[
  {
    "path": ".gitignore",
    "content": "a# Byte-compiled / optimized / DLL files\n__pycache__/\n*.py[cod]\n*$py.class\n\n# C extensions\n*.so\n\ncheckpoints/\ndatasets/\nshared_data/\n\n# Distribution / packaging\n.Python\nbuild/\ndevelop-eggs/\ndist/\ndownloads/\neggs/\n.eggs/\nlib/\nlib64/\nparts/\nsdist/\nvar/\nwheels/\nshare/python-wheels/\n*.egg-info/\n.installed.cfg\n*.egg\nMANIFEST\n\n# PyInstaller\n#  Usually these files are written by a python script from a template\n#  before PyInstaller builds the exe, so as to inject date/other infos into it.\n*.manifest\n*.spec\n\n# Installer logs\npip-log.txt\npip-delete-this-directory.txt\n\n# Unit test / coverage reports\nhtmlcov/\n.tox/\n.nox/\n.coverage\n.coverage.*\n.cache\nnosetests.xml\ncoverage.xml\n*.cover\n*.py,cover\n.hypothesis/\n.pytest_cache/\ncover/\n\n# Translations\n*.mo\n*.pot\n\n# Django stuff:\n*.log\nlocal_settings.py\ndb.sqlite3\ndb.sqlite3-journal\n\n# Flask stuff:\ninstance/\n.webassets-cache\n\n# Scrapy stuff:\n.scrapy\n\n# Sphinx documentation\ndocs/_build/\n\n# PyBuilder\n.pybuilder/\ntarget/\n\n# Jupyter Notebook\n.ipynb_checkpoints\n\n# IPython\nprofile_default/\nipython_config.py\n\n# pyenv\n#   For a library or package, you might want to ignore these files since the code is\n#   intended to run in multiple environments; otherwise, check them in:\n# .python-version\n\n# pipenv\n#   According to pypa/pipenv#598, it is recommended to include Pipfile.lock in version control.\n#   However, in case of collaboration, if having platform-specific dependencies or dependencies\n#   having no cross-platform support, pipenv may install dependencies that don't work, or not\n#   install all needed dependencies.\n#Pipfile.lock\n\n# PEP 582; used by e.g. github.com/David-OConnor/pyflow\n__pypackages__/\n\n# Celery stuff\ncelerybeat-schedule\ncelerybeat.pid\n\n# SageMath parsed files\n*.sage.py\n\n# Environments\n.env\n.venv\nenv/\nvenv/\nENV/\nenv.bak/\nvenv.bak/\n\n# Spyder project settings\n.spyderproject\n.spyproject\n\n# Rope project settings\n.ropeproject\n\n# mkdocs documentation\n/site\n\n# mypy\n.mypy_cache/\n.dmypy.json\ndmypy.json\n\n# Pyre type checker\n.pyre/\n\n# pytype static type analyzer\n.pytype/\n\n# Cython debug symbols\ncython_debug/\n\n\n\n__pycache__\nbuild\ndist\n*.egg-info\n*.vscode/\n*.pth\ntests\ncheckpoints\ndatasets\nruns\ncache\n*.out\n*.o\ndata\nfigures/*.pdf\ntest_codes/\ntensorboard.sh\n\nvisualize/results/\nvisualize/traj_results\n\n\n"
  },
  {
    "path": "README.md",
    "content": "# PVO: Panoptic Visual Odometry\n### [Project Page](https://zju3dv.github.io/pvo/) | [Paper](https://arxiv.org/abs/2207.01610)\n<br/>\n\n> PVO: Panoptic Visual Odometry  \n\n> [[Weicai Ye](https://ywcmaike.github.io/), [Xinyue Lan](https://github.com/siyisan)]<sup>Co-Authors</sup>, [Shuo Chen](https://github.com/Eric3778), [Yuhang Ming](https://github.com/YuhangMing), [Xinyuan Yu](https://github.com/RickyYXY), [Hujun Bao](http://www.cad.zju.edu.cn/home/bao/), [Zhaopeng Cui](https://zhpcui.github.io/), [Guofeng Zhang](http://www.cad.zju.edu.cn/home/gfzhang)\n\n> CVPR 2023\n\n![demo_vid](assets/pvo_teaser.gif)\n\n## Test on vkitti 15-deg-left datasets.\n0) prepare.\nfollow [prepare.md](prepare.md)\n```\nconda activate droidenv\n```\n\n1) generate inital panoptic segmentation.\n```\nsh tools/initial_segmentation.sh  \n```\n\n2) vps->vo，vo Module generate pose, flow and depth.\n```\nsh tools/test_vo_scene.sh  \n```\n\n3) vo->vps, vps Module use flow and depth from vo Module and generate final video panoptic segmentation results and vpq.\n```\nsh tools/test_vps.sh  \n```\n\n## Metrics on Virtual_KITTI2\n|Scene|RMSE|vpq_all/vpq_thing/vpq_stuff|\n|-----|----|---------------------------|\n|Scene01|0.371|40.39/26.43/44.57|\n|Scene02|0.058|68.84/88.83/62.18|\n|Scene06|0.113|66.38/79.99/62.97|\n|Scene18|0.951|68.35/83.86/63.92|\n|Scene20|3.503|35.11/16.83/40.59|\n\nYou can get the results in the paper by iterating multiple times.\n\n## Train on vkitti 15-deg-left datasets.\n1)  To train VPS_Module, you can refer to [Detectron2](https://detectron2.readthedocs.io/en/latest/tutorials/getting_started.html) for more training details.\nHere for example, you can train  vkitti 15-deg-left on 4 GPUs, and training results are saved on `output/vps_training/`. You can modify the config-file according to the hardware conditions.\n```\npython3 -W ignore VPS_Module/tools/train_net.py \\\n--config-file VPS_Module/configs/COCO-PanopticSegmentation/panoptic_fpn_R_50_3x_vkitti_511.yaml --num-gpu 4 \\\nMODEL.WEIGHTS checkpoints/panFPN.pth \\\nOUTPUT_DIR output/vps_training/\n```\n\n2) To train VO_Module, you can refer to [DROID-SLAM](https://github.com/princeton-vl/DROID-SLAM) for more training details.\nHere for example, you can train vkitti on 4 GPUs.\n```\npython VO_Module/train.py --gpus=4 --lr=0.00025\n```\n\n## Visualization\nYou can refer to [DROID-SLAM](https://github.com/princeton-vl/DROID-SLAM) for visualization.\nAll demos can be run on a GPU with 11G of memory. While running, press the \"s\" key to increase the filtering threshold (= more points) and \"a\" to decrease the filtering threshold (= fewer points).\n```\npython VO_Module/evaluation_scripts/test_vo.py --datapath=datasets/Virtual_KITTI2/Scene01 --segm_filter True \n```\n\n## Citation\n\nIf you find this code useful for your research, please use the following BibTeX entry.\n\n```bibtex\n\n@inproceedings{Ye2023PVO,\n  title={{PVO: Panoptic visual odometry}},\n  author={Ye, Weicai and Lan, Xinyue and Chen, Shuo and Ming, Yuhang and Yu, Xingyuan and Bao, Hujun and Cui, Zhaopeng and Zhang, Guofeng},\n  booktitle={Proceedings of the IEEE/CVF Conference on Computer Vision and Pattern Recognition},\n  pages={9579--9589},\n  year={2023}\n}\n\n```\n\n## Acknowledgement\n\nSome code snippets are borrowed from [DROID-SLAM](https://github.com/princeton-vl/DROID-SLAM) and [Detectron2](https://github.com/facebookresearch/detectron2). Thanks for these great projects.\n"
  },
  {
    "path": "VO_Module/README.md",
    "content": "\n## Requirements\n\nTo run the code you will need ...\n* **Inference:** Running the demos will require a GPU with at least 11G of memory. \n\n* **Training:** Training requires a GPU with at least 24G of memory. We train on 4 x RTX-3090 GPUs.\n\n## Getting Started\n1. Creating a new anaconda environment using the provided .yaml file. Use `environment_novis.yaml` to if you do not want to use the visualization\n```Bash\nconda env create -f environment.yml\npip install evo --upgrade --no-binary evo\npip install gdown\n```\n\n2. Compile the extensions (takes about 10 minutes)\n```Bash\npython setup.py install\n```\n\n## Acknowledgements\nWe additionally use evaluation tools from [evo](https://github.com/MichaelGrupp/evo) and [tartanair_tools](https://github.com/castacks/tartanair_tools). Our code is based on the code provided by [DROID-SLAM](https://github.com/princeton-vl/DROID-SLAM).\n\n<center><img src=\"misc/DROID.png\" width=\"640\" style=\"center\"></center>\n\n[DROID-SLAM: Deep Visual SLAM for Monocular, Stereo, and RGB-D Cameras](https://arxiv.org/abs/2108.10869)  \nZachary Teed and Jia Deng\n\n```\n@article{teed2021droid,\n  title={{DROID-SLAM: Deep Visual SLAM for Monocular, Stereo, and RGB-D Cameras}},\n  author={Teed, Zachary and Deng, Jia},\n  journal={arXiv preprint arXiv:2108.10869},\n  year={2021}\n}\n```\n"
  },
  {
    "path": "VO_Module/calib/barn.txt",
    "content": "1161.545689 1161.545689 960.000000 540.000000 -0.025158 0.0 0.0 0.0"
  },
  {
    "path": "VO_Module/calib/eth.txt",
    "content": "726.21081542969 726.21081542969 359.2048034668 202.47247314453"
  },
  {
    "path": "VO_Module/calib/euroc.txt",
    "content": "458.654 457.296 367.215 248.375 -0.28340811 0.07395907 0.00019359 1.76187114e-05"
  },
  {
    "path": "VO_Module/calib/kitti.txt",
    "content": "7.070912000000e+02 7.070912000000e+02 6.018873000000e+02 1.831104000000e+02"
  },
  {
    "path": "VO_Module/calib/replica.txt",
    "content": "600.0 600.0 599.5 339.5"
  },
  {
    "path": "VO_Module/calib/tartan.txt",
    "content": "320.0 320.0 320.0 240.0"
  },
  {
    "path": "VO_Module/calib/tum3.txt",
    "content": "535.4 539.2 320.1 247.6"
  },
  {
    "path": "VO_Module/demo.py",
    "content": "import sys\nsys.path.append('droid_slam')\n\nfrom tqdm import tqdm\nimport numpy as np\nimport torch\nimport lietorch\nimport cv2\nimport os\nimport glob \nimport time\nimport argparse\n\nfrom torch.multiprocessing import Process\nfrom droid import Droid\n\nimport torch.nn.functional as F\n\n\ndef show_image(image):\n    image = image.permute(1, 2, 0).cpu().numpy()\n    cv2.imshow('image', image / 255.0)\n    cv2.waitKey(1)\n\ndef image_stream(imagedir, calib, stride):\n    \"\"\" image generator \"\"\"\n\n    calib = np.loadtxt(calib, delimiter=\" \")\n    fx, fy, cx, cy = calib[:4]\n\n    K = np.eye(3)\n    K[0,0] = fx\n    K[0,2] = cx\n    K[1,1] = fy\n    K[1,2] = cy\n\n    image_list = sorted(os.listdir(imagedir))[::stride]\n\n    for t, imfile in enumerate(image_list):\n        image = cv2.imread(os.path.join(imagedir, imfile))\n        if len(calib) > 4:\n            image = cv2.undistort(image, K, calib[4:])\n\n        h0, w0, _ = image.shape\n        h1 = int(h0 * np.sqrt((384 * 512) / (h0 * w0)))\n        w1 = int(w0 * np.sqrt((384 * 512) / (h0 * w0)))\n\n        image = cv2.resize(image, (w1, h1))\n        image = image[:h1-h1%8, :w1-w1%8]\n        image = torch.as_tensor(image).permute(2, 0, 1)\n\n        intrinsics = torch.as_tensor([fx, fy, cx, cy])\n        intrinsics[0:2] *= (w1 / w0)\n        intrinsics[2:4] *= (h1 / h0)\n\n        yield t, image, intrinsics\n\n\nif __name__ == '__main__':\n    parser = argparse.ArgumentParser()\n    parser.add_argument(\"--imagedir\", type=str, help=\"path to image directory\")\n    parser.add_argument(\"--calib\", type=str, help=\"path to calibration file\")\n    parser.add_argument(\"--t0\", default=0, type=int, help=\"starting frame\")\n    parser.add_argument(\"--stride\", default=3, type=int, help=\"frame stride\")\n\n    parser.add_argument(\"--weights\", default=\"droid.pth\")\n    parser.add_argument(\"--buffer\", type=int, default=512)\n    parser.add_argument(\"--image_size\", default=[240, 320])\n    parser.add_argument(\"--disable_vis\", action=\"store_true\")\n\n    parser.add_argument(\"--beta\", type=float, default=0.3, help=\"weight for translation / rotation components of flow\")\n    parser.add_argument(\"--filter_thresh\", type=float, default=2.4, help=\"how much motion before considering new keyframe\")\n    parser.add_argument(\"--warmup\", type=int, default=8, help=\"number of warmup frames\")\n    parser.add_argument(\"--keyframe_thresh\", type=float, default=4.0, help=\"threshold to create a new keyframe\")\n    parser.add_argument(\"--frontend_thresh\", type=float, default=16.0, help=\"add edges between frames whithin this distance\")\n    parser.add_argument(\"--frontend_window\", type=int, default=25, help=\"frontend optimization window\")\n    parser.add_argument(\"--frontend_radius\", type=int, default=2, help=\"force edges between frames within radius\")\n    parser.add_argument(\"--frontend_nms\", type=int, default=1, help=\"non-maximal supression of edges\")\n\n    parser.add_argument(\"--backend_thresh\", type=float, default=22.0)\n    parser.add_argument(\"--backend_radius\", type=int, default=2)\n    parser.add_argument(\"--backend_nms\", type=int, default=3)\n    args = parser.parse_args()\n\n    torch.multiprocessing.set_start_method('spawn')\n\n    droid = None\n\n    tstamps = []\n    for (t, image, intrinsics) in tqdm(image_stream(args.imagedir, args.calib, args.stride)):\n        if t < args.t0:\n            continue\n\n        if not args.disable_vis:\n            show_image(image)\n\n        if droid is None:\n            args.image_size = [image.shape[1], image.shape[2]]\n            droid = Droid(args)\n        \n        droid.track(t, image, intrinsics=intrinsics)\n\n    traj_est = droid.terminate(image_stream(args.imagedir, args.calib, args.stride))\n"
  },
  {
    "path": "VO_Module/droid_slam/data_readers/__init__.py",
    "content": "\n"
  },
  {
    "path": "VO_Module/droid_slam/data_readers/augmentation.py",
    "content": "import torch\nimport torchvision.transforms as transforms\nimport numpy as np\nimport torch.nn.functional as F\n\n\nclass RGBDAugmentor:\n    \"\"\" perform augmentation on RGB-D video \"\"\"\n\n    def __init__(self, crop_size):\n        self.crop_size = crop_size\n        self.augcolor = transforms.Compose([\n            transforms.ToPILImage(),\n            transforms.ColorJitter(\n                brightness=0.25, contrast=0.25, saturation=0.25, hue=0.4/3.14),\n            transforms.RandomGrayscale(p=0.1),\n            transforms.ToTensor()])\n\n        self.max_scale = 0.25\n\n    def resize_sparse_flow_map(self, flow, valid, fx=1.0, fy=1.0):\n        \"\"\"from RAFT\"\"\"\n        N, ht, wd = flow.shape[:3]\n        coords = np.meshgrid(np.arange(wd), np.arange(ht))\n        coords = np.stack(coords, axis=-1)\n        coords = torch.from_numpy(coords).expand_as(flow)\n\n        coords = coords.reshape(N, -1, 2).float()\n        flow = flow.reshape(N, -1, 2).float()\n        valid = valid.reshape(N, -1).float()\n\n        coords0 = coords[valid >= 1]\n        flow0 = flow[valid >= 1]\n\n        ht1 = int(round(ht * fy))\n        wd1 = int(round(wd * fx))\n\n        coords1 = coords0 * torch.tensor([fx, fy])\n        flow1 = flow0 * torch.tensor([fx, fy])\n\n        xx = torch.round(coords1[..., 0]).long()\n        yy = torch.round(coords1[..., 1]).long()\n\n        v = (xx > 0) & (xx < wd1) & (yy > 0) & (yy < ht1)\n        xx = xx[v]\n        yy = yy[v]\n        flow1 = flow1[v]\n\n        flow_img = torch.zeros([N, ht1, wd1, 2], dtype=torch.float)\n        valid_img = torch.zeros([N, ht1, wd1], dtype=torch.int)\n\n        flow_img[:, yy, xx] = flow1\n        valid_img[:, yy, xx] = 1\n\n        return flow_img, valid_img\n\n    def spatial_transform(self, images, depths, poses, intrinsics,\n                          fo_flows=None, fo_vals=None, ba_flows=None, ba_vals=None,\n                          fo_masks=None, ba_masks=None, gt_masks=None, gt_vals=None,\n                          segments=None):\n        \"\"\" cropping and resizing \"\"\"\n        ht, wd = images.shape[2:]\n\n        max_scale = self.max_scale\n        min_scale = np.log2(np.maximum(\n            (self.crop_size[0] + 1) / float(ht),\n            (self.crop_size[1] + 1) / float(wd)))\n\n        scale = 2 ** np.random.uniform(min_scale, max_scale)\n        intrinsics = scale * intrinsics\n        depths = depths.unsqueeze(dim=1)\n\n        images = F.interpolate(images, scale_factor=scale, mode='bilinear',\n                               align_corners=False, recompute_scale_factor=True)\n\n        depths = F.interpolate(depths, scale_factor=scale,\n                               recompute_scale_factor=True)\n\n        if fo_flows != None:\n            fo_flows, fo_vals = self.resize_sparse_flow_map(\n                fo_flows, fo_vals, fx=scale, fy=scale)\n            fo_flows = torch.cat([fo_flows, fo_vals.unsqueeze(-1)], dim=-1)\n            ba_flows, ba_vals = self.resize_sparse_flow_map(\n                ba_flows, ba_vals, fx=scale, fy=scale)\n            ba_flows = torch.cat([ba_flows, ba_vals.unsqueeze(-1)], dim=-1)\n\n            fo_masks = fo_masks.unsqueeze(1)\n            ba_masks = ba_masks.unsqueeze(1)\n            fo_masks = F.interpolate(fo_masks, scale_factor=scale,\n                                     recompute_scale_factor=True)\n            ba_masks = F.interpolate(ba_masks, scale_factor=scale,\n                                     recompute_scale_factor=True)\n        else:\n            gt_masks = gt_masks.unsqueeze(1)\n            gt_vals = gt_vals.unsqueeze(1)\n            segments = segments.unsqueeze(1)\n            gt_masks = F.interpolate(gt_masks, scale_factor=scale,\n                                     recompute_scale_factor=True)\n            gt_vals = F.interpolate(gt_vals, scale_factor=scale,\n                                    recompute_scale_factor=True)\n            segments = F.interpolate(segments, scale_factor=scale,\n                                    recompute_scale_factor=True)\n\n        # always perform center crop (TODO: try non-center crops)\n        y0 = (images.shape[2] - self.crop_size[0]) // 2\n        x0 = (images.shape[3] - self.crop_size[1]) // 2\n\n        intrinsics = intrinsics - torch.tensor([0.0, 0.0, x0, y0])\n        images = images[:, :, y0:y0+self.crop_size[0], x0:x0+self.crop_size[1]]\n        depths = depths[:, :, y0:y0+self.crop_size[0], x0:x0+self.crop_size[1]]\n        if fo_flows != None:\n            fo_flows = fo_flows[:, y0:y0 +\n                                self.crop_size[0], x0:x0+self.crop_size[1], :]\n            ba_flows = ba_flows[:, y0:y0 +\n                                self.crop_size[0], x0:x0+self.crop_size[1], :]\n            fo_masks = fo_masks[:, :, y0:y0 +\n                                self.crop_size[0], x0:x0+self.crop_size[1]]\n            ba_masks = ba_masks[:, :, y0:y0 +\n                                self.crop_size[0], x0:x0+self.crop_size[1]]\n        else:\n            gt_masks = gt_masks[:, :, y0:y0 +\n                                self.crop_size[0], x0:x0+self.crop_size[1]]\n            gt_vals = gt_vals[:, :, y0:y0 +\n                              self.crop_size[0], x0:x0+self.crop_size[1]]\n            segments = segments[:, :, y0:y0 +\n                              self.crop_size[0], x0:x0+self.crop_size[1]]\n\n        depths = depths.squeeze(dim=1)\n        if fo_flows != None:\n            fo_masks = fo_masks.squeeze(1)\n            ba_masks = ba_masks.squeeze(1)\n            return images, poses, depths, intrinsics, fo_flows, ba_flows, fo_masks, ba_masks\n        else:\n            gt_masks = gt_masks.squeeze(1)\n            gt_vals = gt_vals.squeeze(1)\n            segments = F.interpolate(segments, scale_factor=1/8,\n                                    recompute_scale_factor=True)\n            segments = segments.squeeze(1).int()\n            return images, poses, depths, intrinsics, gt_masks, gt_vals, segments\n\n    def spatial_transform_only_pose(self, images, poses, intrinsics):\n        \"\"\" cropping and resizing \"\"\"\n        ht, wd = images.shape[2:]\n\n        max_scale = self.max_scale\n        min_scale = np.log2(np.maximum(\n            (self.crop_size[0] + 1) / float(ht),\n            (self.crop_size[1] + 1) / float(wd)))\n\n        scale = 2 ** np.random.uniform(min_scale, max_scale)\n        intrinsics = scale * intrinsics\n\n        images = F.interpolate(images, scale_factor=scale, mode='bilinear',\n                               align_corners=False, recompute_scale_factor=True)\n\n        # always perform center crop (TODO: try non-center crops)\n        y0 = (images.shape[2] - self.crop_size[0]) // 2\n        x0 = (images.shape[3] - self.crop_size[1]) // 2\n\n        intrinsics = intrinsics - torch.tensor([0.0, 0.0, x0, y0])\n        images = images[:, :, y0:y0+self.crop_size[0], x0:x0+self.crop_size[1]]\n\n        return images, poses, intrinsics\n\n    def color_transform(self, images):\n        \"\"\" color jittering \"\"\"\n        num, ch, ht, wd = images.shape\n        images = images.permute(1, 2, 3, 0).reshape(ch, ht, wd*num)\n        images = 255 * self.augcolor(images[[2, 1, 0]] / 255.0)\n        return images[[2, 1, 0]].reshape(ch, ht, wd, num).permute(3, 0, 1, 2).contiguous()\n\n    def __call__(self, images, poses, depths, intrinsics,\n                 fo_flows=None, fo_vals=None, ba_flows=None, ba_vals=None,\n                 fo_masks=None, ba_masks=None, gt_masks=None, gt_vals=None,\n                 segments=None):\n        if depths == None:\n            images = self.color_transform(images)\n            return self.spatial_transform_only_pose(images, poses, intrinsics)\n        else:\n            images = self.color_transform(images)\n            return self.spatial_transform(images, depths, poses, intrinsics,\n                                      fo_flows, fo_vals, ba_flows, ba_vals,\n                                      fo_masks, ba_masks, gt_masks, gt_vals,\n                                      segments)\n"
  },
  {
    "path": "VO_Module/droid_slam/data_readers/base.py",
    "content": "\nimport numpy as np\nimport torch\nimport torch.utils.data as data\nimport torch.nn.functional as F\n\nimport sys\nimport csv\nimport os\nimport cv2\nimport math\nimport random\nimport json\nimport pickle\nimport os.path as osp\nfrom collections import OrderedDict\nfrom lietorch import SE3\n\nfrom .augmentation import RGBDAugmentor\nfrom .rgbd_utils import *\n\nfrom geom.projective_ops import projective_transform, coords_grid\nfrom geom.graph_utils import graph_to_edge_list\n\n\nclass RGBDDataset(data.Dataset):\n    def __init__(self, name, datapath, n_frames=4, crop_size=[384, 512],\n                 fmin=8.0, fmax=75.0, do_aug=True, flow_label=False, aug_graph=False,\n                 need_inv=True, build_mask=False, mode='sup', rebuild=False):\n        \"\"\" Base class for RGBD dataset \"\"\"\n        self.aug = None\n        self.root = datapath\n        self.name = name\n        self.mode = mode\n\n        self.n_frames = n_frames\n        self.fmin = fmin  # exclude very easy examples\n        self.fmax = fmax  # exclude very hard examples\n        self.flow_label = flow_label\n        self.aug_graph = aug_graph\n        self.need_inv = need_inv\n        self.build_mask = build_mask\n        self.only_pose = False\n        if do_aug:\n            self.aug = RGBDAugmentor(crop_size=crop_size)\n\n        # building dataset is expensive, cache so only needs to be performed once\n        cur_path = osp.dirname(osp.abspath(__file__))\n        if not os.path.isdir(osp.join(cur_path, 'cache')):\n            os.mkdir(osp.join(cur_path, 'cache'))\n\n        cache_path = osp.join(cur_path, 'cache', '{}.pickle'.format(self.name))\n\n        print(\"cache_path: \",cache_path)\n        if osp.isfile(cache_path) and rebuild==False:\n            scene_info = pickle.load(open(cache_path, 'rb'))[0]\n        else:\n            scene_info = self._build_dataset()\n            with open(cache_path, 'wb') as cachefile:\n                pickle.dump((scene_info,), cachefile)\n\n        self.scene_info = scene_info\n        self._build_dataset_index()\n\n        self.has_segm = False\n\n    def _build_dataset_index(self):\n        self.dataset_index = []\n        for scene in self.scene_info:\n            # if not self.__class__.is_test_scene(scene):\n            if not self.is_test_scene(scene):\n                if self.aug_graph:\n                    graph = self.scene_info[scene]['graph']\n                    for i in graph:\n                        if len(graph[i][0]) > self.n_frames:\n                            self.dataset_index.append((scene, i))\n                else:\n                    for i in range(len(self.scene_info[scene]['images'])-self.n_frames+1):\n                        self.dataset_index.append((scene, i))\n            else:\n                print(\"Reserving {} for validation\".format(scene))\n\n    @staticmethod\n    def image_read(image_file):\n        return cv2.imread(image_file)\n\n    @staticmethod\n    def depth_read(depth_file):\n        return np.load(depth_file)\n\n    def build_frame_graph(self, poses, depths, intrinsics, f=16, max_flow=256):\n        \"\"\" compute optical flow distance between all pairs of frames \"\"\"\n        def read_disp(fn):\n            depth = self.__class__.depth_read(fn)[f//2::f, f//2::f]\n            depth[depth < 0.01] = np.mean(depth)\n            return 1.0 / depth\n\n        poses = np.array(poses)\n        intrinsics = np.array(intrinsics) / f\n\n        disps = np.stack(list(map(read_disp, depths)), 0)\n        # need_inv = False for vkitti2\n        d = f * \\\n            compute_distance_matrix_flow(\n                poses, disps, intrinsics, need_inv=self.need_inv)\n\n        graph = {}\n        for i in range(d.shape[0]):\n            j, = np.where(d[i] < max_flow)\n            graph[i] = (j, d[i, j])\n\n        return graph\n\n    def __getitem__(self, index):\n        \"\"\" return training video \"\"\"\n\n        index = index % len(self.dataset_index)\n        scene_id, ix = self.dataset_index[index]\n\n        if self.aug_graph:\n            frame_graph = self.scene_info[scene_id]['graph']\n        if self.flow_label:\n            fo_flow_list = self.scene_info[scene_id]['fo_flows']\n            ba_flow_list = self.scene_info[scene_id]['ba_flows']\n            if 'segments' in self.scene_info[scene_id]:\n                self.has_segm = True\n                segments_list = self.scene_info[scene_id]['segments']\n        else:\n            if not self.only_pose:\n                dymask_list = self.scene_info[scene_id]['dymasks']\n                segments_list = self.scene_info[scene_id]['segments']\n                self.has_segm = True\n\n        images_list = self.scene_info[scene_id]['images']\n        if not self.only_pose:\n            depths_list = self.scene_info[scene_id]['depths']\n        poses_list = self.scene_info[scene_id]['poses']\n        intrinsics_list = self.scene_info[scene_id]['intrinsics']\n\n        if self.aug_graph:\n            inds = [ix]\n            while len(inds) < self.n_frames:\n                # get other frames within flow threshold\n                k = (frame_graph[ix][1] > self.fmin) & (\n                    frame_graph[ix][1] < self.fmax)\n                frames = frame_graph[ix][0][k]\n\n                # prefer frames forward in time\n                if np.count_nonzero(frames[frames > ix]):\n                    ix = np.random.choice(frames[frames > ix])\n\n                elif np.count_nonzero(frames):\n                    ix = np.random.choice(frames)\n\n                inds += [ix]\n        else:\n            inds = []\n            for i in range(self.n_frames):\n                inds.append(ix + i)\n\n        images, depths, poses, intrinsics = [], [], [], []\n        fo_flows, ba_flows = [], []\n        fo_vals, ba_vals = [], []\n        gt_masks, gt_vals = [], []\n        segments = []\n        filename_list = []\n\n        for num, i in enumerate(inds):\n            images.append(self.__class__.image_read(images_list[i]))\n            if not self.only_pose:\n                depths.append(self.__class__.depth_read(depths_list[i]))\n            poses.append(poses_list[i])\n            intrinsics.append(intrinsics_list[i])\n            filename_list.append(images_list[i].rsplit('/')[-1])\n\n            if self.flow_label and num < len(inds)-1:\n                # 每组flow比图片少一项\n                f, v = self.__class__.flow_read(fo_flow_list[i])\n                fo_flows.append(f)\n                fo_vals.append(v)\n                f, v = self.__class__.flow_read(ba_flow_list[i])\n                ba_flows.append(f)\n                ba_vals.append(v)\n                if self.has_segm:\n                    seg = self.__class__.segment_read(segments_list[i])\n                    segments.append(seg)\n            if not self.flow_label :\n                if not self.only_pose:\n                    mask, v = self.__class__.dymask_read(dymask_list[i])\n                    gt_masks.append(mask)\n                    gt_vals.append(v)\n                    seg = self.__class__.segment_read(segments_list[i])\n                    segments.append(seg)\n\n        images = np.stack(images).astype(np.float32)\n        if not self.only_pose:\n            depths = np.stack(depths).astype(np.float32)\n        poses = np.stack(poses).astype(np.float32)\n        intrinsics = np.stack(intrinsics).astype(np.float32)\n\n        if self.flow_label:\n            fo_flows = np.stack(fo_flows).astype(np.float32)\n            ba_flows = np.stack(ba_flows).astype(np.float32)\n            fo_flows = torch.from_numpy(fo_flows)\n            ba_flows = torch.from_numpy(ba_flows)\n            fo_vals = np.stack(fo_vals).astype(np.float32)\n            ba_vals = np.stack(ba_vals).astype(np.float32)\n            fo_vals = torch.from_numpy(fo_vals)\n            ba_vals = torch.from_numpy(ba_vals)\n            if self.has_segm:\n                segments = np.stack(segments).astype(np.float32)\n                segments = torch.from_numpy(segments)\n        else:\n            if not self.only_pose:\n                gt_masks = np.stack(gt_masks).astype(np.float32)\n                gt_masks = torch.from_numpy(gt_masks)\n                gt_vals = np.stack(gt_vals).astype(np.float32)\n                gt_vals = torch.from_numpy(gt_vals)\n                segments = np.stack(segments).astype(np.float32)\n                segments = torch.from_numpy(segments)\n\n        images = torch.from_numpy(images).float()\n        images = images.permute(0, 3, 1, 2)\n\n        if not self.only_pose:\n            disps = torch.from_numpy(1.0 / depths)\n        poses = torch.from_numpy(poses)\n        intrinsics = torch.from_numpy(intrinsics)\n\n        if self.only_pose:\n            return filename_list, images, poses, intrinsics\n\n        if self.aug is not None:\n            if self.flow_label:\n                fo_masks, ba_masks = self.build_motion_masks(poses, disps, intrinsics,\n                                                             fo_flows, ba_flows)\n                # Only use when build dymasks' labels\n                if self.build_mask:\n                    return fo_masks.unsqueeze(-1), ba_masks.unsqueeze(-1), \\\n                        fo_vals.unsqueeze(-1), ba_vals.unsqueeze(-1)\n\n                images, poses, disps, intrinsics, \\\n                    fo_flows, ba_flows, fo_masks, ba_masks = self.aug(images, poses, disps, intrinsics,\n                                                                      fo_flows, fo_vals, ba_flows, ba_vals,\n                                                                      fo_masks, ba_masks)\n            else:\n                images, poses, disps, intrinsics, \\\n                    gt_masks, gt_vals, segments = self.aug(images, poses, disps, intrinsics,\n                                                 gt_masks=gt_masks, gt_vals=gt_vals, \n                                                 segments=segments)\n        if len(disps[disps > 0.01]) > 0:\n            s = disps[disps > 0.01].mean()\n            disps = disps / s\n            poses[..., :3] *= s\n        \n        if self.flow_label:\n            if self.has_segm:\n                return images, poses, disps, intrinsics, fo_flows, ba_flows, segments\n            else:\n                return images, poses, disps, intrinsics, fo_flows, ba_flows\n        else:\n            gt_masks, gt_vals = gt_masks.unsqueeze(-1), gt_vals.unsqueeze(-1)\n            if self.mode == 'sup':\n                return images, poses, disps, intrinsics, gt_masks, gt_vals\n            elif self.mode == 'semisup':\n                return filename_list, images, poses, disps, intrinsics, gt_masks, gt_vals, segments\n            elif self.mode == 'unsup':\n                return images, poses, disps, intrinsics\n            else:\n                raise Exception('ERROR: Unknown mode!')\n\n    def __len__(self):\n        return len(self.dataset_index)\n\n    def __imul__(self, x):\n        self.dataset_index *= x\n        return self\n\n    def build_motion_masks(self, poses, disps, intrinsics, fo_flows, ba_flows, thresh=0.5):\n        N, ht, wd = poses.shape[0], fo_flows.shape[1], fo_flows.shape[2]\n        graph = OrderedDict()\n        for i in range(N):\n            graph[i] = [j for j in range(N) if abs(i-j) == 1]\n        ii, jj, _ = graph_to_edge_list(graph)\n\n        poses, disps = poses.unsqueeze(0), disps.unsqueeze(0)\n        intrinsics = intrinsics.unsqueeze(0)\n        fo_flows, ba_flows = fo_flows.unsqueeze(0), ba_flows.unsqueeze(0)\n\n        # use w2c for vkitti2\n        poses = SE3(poses)\n\n        coords_cam, _ = projective_transform(poses, disps, intrinsics, ii, jj)\n        cam_flows = coords_cam - coords_grid(ht, wd, device=poses.device)\n\n        fo_masks = ((cam_flows[:, 0::2, ...] -\n                    fo_flows[..., 0:2]).norm(dim=-1) <= thresh).float()\n        ba_masks = ((cam_flows[:, 1::2, ...] -\n                    ba_flows[..., 0:2]).norm(dim=-1) <= thresh).float()\n\n        return fo_masks.squeeze(0), ba_masks.squeeze(0)\n"
  },
  {
    "path": "VO_Module/droid_slam/data_readers/factory.py",
    "content": "\nimport pickle\nimport os\nimport os.path as osp\n\n# RGBD-Dataset\nfrom .tartan import TartanAir\nfrom .replica import Replica\nfrom .vkitti2 import VKitti2\n\nfrom .stream import ImageStream\nfrom .stream import StereoStream\nfrom .stream import RGBDStream\n\n# streaming datasets for inference\nfrom .tartan import TartanAirStream\nfrom .tartan import TartanAirTestStream\n\ndef dataset_factory(dataset_list, **kwargs):\n    \"\"\" create a combined dataset \"\"\"\n\n    from torch.utils.data import ConcatDataset\n\n    dataset_map = {'tartan': (TartanAir, ),\n                   'replica': (Replica, ), \n                   'vkitti2': (VKitti2, ),  }\n    db_list = []\n    for key in dataset_list:\n        # cache datasets for faster future loading\n        db = dataset_map[key][0](**kwargs)\n\n        print(\"Dataset {} has {} images\".format(key, len(db)))\n        db_list.append(db)\n\n    return ConcatDataset(db_list)\n\n\ndef create_datastream(dataset_path, **kwargs):\n    \"\"\" create data_loader to stream images 1 by 1 \"\"\"\n\n    from torch.utils.data import DataLoader\n\n    if osp.isfile(osp.join(dataset_path, 'calibration.txt')):\n        db = ETH3DStream(dataset_path, **kwargs)\n\n    elif osp.isdir(osp.join(dataset_path, 'image_left')):\n        db = TartanAirStream(dataset_path, **kwargs)\n\n    elif osp.isfile(osp.join(dataset_path, 'rgb.txt')):\n        db = TUMStream(dataset_path, **kwargs)\n\n    elif osp.isdir(osp.join(dataset_path, 'mav0')):\n        db = EurocStream(dataset_path, **kwargs)\n\n    elif osp.isfile(osp.join(dataset_path, 'calib.txt')):\n        db = KITTIStream(dataset_path, **kwargs)\n\n    else:\n        # db = TartanAirStream(dataset_path, **kwargs)\n        db = TartanAirTestStream(dataset_path, **kwargs)\n\n    stream = DataLoader(db, shuffle=False, batch_size=1, num_workers=4)\n    return stream\n\n\ndef create_imagestream(dataset_path, **kwargs):\n    \"\"\" create data_loader to stream images 1 by 1 \"\"\"\n    from torch.utils.data import DataLoader\n\n    db = ImageStream(dataset_path, **kwargs)\n    return DataLoader(db, shuffle=False, batch_size=1, num_workers=4)\n\n\ndef create_stereostream(dataset_path, **kwargs):\n    \"\"\" create data_loader to stream images 1 by 1 \"\"\"\n    from torch.utils.data import DataLoader\n\n    db = StereoStream(dataset_path, **kwargs)\n    return DataLoader(db, shuffle=False, batch_size=1, num_workers=4)\n\n\ndef create_rgbdstream(dataset_path, **kwargs):\n    \"\"\" create data_loader to stream images 1 by 1 \"\"\"\n    from torch.utils.data import DataLoader\n\n    db = RGBDStream(dataset_path, **kwargs)\n    return DataLoader(db, shuffle=False, batch_size=1, num_workers=4)\n"
  },
  {
    "path": "VO_Module/droid_slam/data_readers/replica.py",
    "content": "\nimport numpy as np\nimport torch\nimport glob\nimport cv2\nimport os\nimport os.path as osp\n\nfrom lietorch import SE3\nfrom .base import RGBDDataset\nfrom .stream import RGBDStream\n\ncur_path = osp.dirname(osp.abspath(__file__))\ntest_split = osp.join(cur_path, 'replica_test.txt')\ntest_split = open(test_split).read().split()\n\n\nclass Replica(RGBDDataset):\n\n    # scale depths to balance rot & trans\n    # Replica: 1.0 or even smaller?\n    DEPTH_SCALE = 1.0\n\n    def __init__(self, mode='training', **kwargs):\n        self.mode = mode\n        self.n_frames = 2\n        super(Replica, self).__init__(name='Replica', **kwargs)\n\n    @staticmethod \n    def is_test_scene(scene):\n        # print(scene, any(x in scene for x in test_split))\n        return any(x in scene for x in test_split)\n\n    def _build_dataset(self):\n        from tqdm import tqdm\n        print(\"Building Replica dataset\")\n\n        scene_info = {}\n        scenes = glob.glob(osp.join(self.root, '*'))\n        for scene in tqdm(sorted(scenes)):\n            images = sorted(glob.glob(osp.join(scene, 'image_left/*.jpg')))\n            depths = sorted(glob.glob(osp.join(scene, 'depth_left/*.npy')))\n            \n            poses = np.loadtxt(osp.join(scene, 'pose_left.txt'), delimiter=' ')\n            # tx,ty,tz,qx,qy,qz,qw\n            # poses = poses[:, [1, 2, 0, 4, 5, 3, 6]] # 交换是因为NED frame, 修改坐标轴\n            poses[:,:3] /= Replica.DEPTH_SCALE\n            intrinsics = [Replica.calib_read()] * len(images)\n\n            # graph of co-visible frames based on flow\n            graph = self.build_frame_graph(poses, depths, intrinsics)\n\n            scene = '/'.join(scene.split('/'))\n            scene_info[scene] = {'images': images, 'depths': depths, \n                'poses': poses, 'intrinsics': intrinsics, 'graph': graph}\n\n        return scene_info\n\n    @staticmethod\n    def calib_read():\n        return np.array([600.0, 600.0, 599.5, 339.5])\n\n    @staticmethod\n    def image_read(image_file):\n        return cv2.imread(image_file)\n\n    @staticmethod\n    def depth_read(depth_file):\n        depth = np.load(depth_file) / Replica.DEPTH_SCALE\n        depth[depth==np.nan] = 1.0\n        depth[depth==np.inf] = 1.0\n        return depth\n\n\nclass ReplicaStream(RGBDStream):\n    def __init__(self, datapath, **kwargs):\n        super(ReplicaStream, self).__init__(datapath=datapath, **kwargs)\n\n    def _build_dataset_index(self):\n        \"\"\" build list of images, poses, depths, and intrinsics \"\"\"\n        self.root = 'datasets/Replica'\n\n        scene = osp.join(self.root, self.datapath)\n        image_glob = osp.join(scene, 'image_left/*.jpg')\n        images = sorted(glob.glob(image_glob))\n\n        poses = np.loadtxt(osp.join(scene, 'pose_left.txt'), delimiter=' ')\n        poses = poses[:, [1, 2, 0, 4, 5, 3, 6]]\n\n        poses = SE3(torch.as_tensor(poses))\n        poses = poses[[0]].inv() * poses\n        poses = poses.data.cpu().numpy()\n\n        intrinsic = self.calib_read(self.datapath)\n        intrinsics = np.tile(intrinsic[None], (len(images), 1))\n\n        self.images = images[::int(self.frame_rate)]\n        self.poses = poses[::int(self.frame_rate)]\n        self.intrinsics = intrinsics[::int(self.frame_rate)]\n\n    @staticmethod\n    def calib_read(datapath):\n        return np.array([600.0, 600.0, 599.5, 339.5])\n\n    @staticmethod\n    def image_read(image_file):\n        return cv2.imread(image_file)\n\n\nclass ReplicaTestStream(RGBDStream):\n    def __init__(self, datapath, **kwargs):\n        super(ReplicaStream, self).__init__(datapath=datapath, **kwargs)\n\n    def _build_dataset_index(self):\n        \"\"\" build list of images, poses, depths, and intrinsics \"\"\"\n        self.root = 'datasets/mono'\n        image_glob = osp.join(self.root, self.datapath, '*.jpg')\n        images = sorted(glob.glob(image_glob))\n\n        poses = np.loadtxt(osp.join(self.root, 'mono_gt', self.datapath + '.txt'), delimiter=' ')\n        poses = poses[:, [1, 2, 0, 4, 5, 3, 6]]\n\n        poses = SE3(torch.as_tensor(poses))\n        poses = poses[[0]].inv() * poses\n        poses = poses.data.cpu().numpy()\n\n        intrinsic = self.calib_read(self.datapath)\n        intrinsics = np.tile(intrinsic[None], (len(images), 1))\n\n        self.images = images[::int(self.frame_rate)]\n        self.poses = poses[::int(self.frame_rate)]\n        self.intrinsics = intrinsics[::int(self.frame_rate)]\n\n    @staticmethod\n    def calib_read(datapath):\n        return np.array([600.0, 600.0, 599.5, 339.5])\n\n    @staticmethod\n    def image_read(image_file):\n        return cv2.imread(image_file)"
  },
  {
    "path": "VO_Module/droid_slam/data_readers/replica_test.txt",
    "content": "room1\noffice1\nroom2\noffice2\noffice3\noffice4"
  },
  {
    "path": "VO_Module/droid_slam/data_readers/replica_utils.py",
    "content": "from scipy.spatial.transform import Rotation as R\nimport numpy as np\nimport glob\nimport imageio\nimport os.path as osp\n\n\ndef get_replica_cam_list(cam_list_dir, base_dir):\n    \"\"\"\n    direactly get cam matrix\n    \"\"\"\n    cam_list = []\n    with open(osp.join(base_dir, cam_list_dir), 'r') as f:\n        for line in f.readlines():\n            if line[0] == '#':\n                continue\n            data = line.strip('\\n').split(' ')\n            cam_mat = np.array([float(x) for x in data[:-4]]).reshape(3, 4)\n            cam_list.append(cam_mat)\n    return cam_list\n\n\ndef quat_to_rmat(quat):\n    \"\"\"\n    input:\n        quat 四元数\n        list/numpy\n    output:\n        rot matrix 旋转矩阵\n        numpy mat\n    using numpy\n    \"\"\"\n    r = R.from_quat(quat)\n    mat = r.as_matrix()\n    return mat\n\n\ndef rmat_to_quad(mat):\n    r = R.from_matrix(mat)\n    quat = r.as_quat()\n    return quat\n\n\ndef get_trajectories_quad(cam_list, norm_val=1):\n    trajectories = []\n    for cam in cam_list:\n        if not isinstance(cam, np.ndarray):\n            np_cam = cam.detach().cpu().numpy()\n        else:\n            np_cam = cam\n        np_cam[:3] /= norm_val\n        trajectories.append(np_cam)\n    return trajectories\n\n\ndef get_trajectories_mat(cam_list, norm_val=1):\n    trajectories = []\n    for cam in cam_list:\n        if not isinstance(cam, np.ndarray):\n            np_cam = cam.detach().cpu().numpy()\n        else:\n            np_cam = cam\n        rot_mat = np_cam[:, 0:3]\n        t_vec = np_cam[:, 3]/norm_val\n        quad = rmat_to_quad(rot_mat)\n        trajectories.append(np.append(t_vec, quad))\n    return trajectories\n\n\ndef build_track_pred_file(gt_time_dir, pred_dir, trajectories, keyframe_freq=1):\n    time_stamp = []\n    with open(gt_time_dir, 'r') as f:\n        for line in f.readlines():\n            if line[0] == '#':\n                continue\n            time_stamp.append(line.strip('\\n').split(' ')[0])\n    # time_stamp = time_stamp[::keyframe_freq]\n    trajectories = trajectories[::keyframe_freq]\n    cnt = min(len(trajectories), len(time_stamp))\n    with open(pred_dir, 'w') as f:\n        for i in range(cnt):\n            data = ''\n            for j in range(7):\n                data += (' '+str(trajectories[i][j]))\n            data = time_stamp[i]+data+'\\n'\n            f.write(data)\n\n\ndef build_track_pred_file_notime(pred_dir, trajectories, keyframe_freq=1):\n    trajectories = trajectories[::keyframe_freq]\n    cnt = len(trajectories)\n    with open(pred_dir, 'w') as f:\n        for i in range(cnt):\n            s = []\n            for j in range(7):\n                s.append(str(trajectories[i][j]))\n            data = ' '.join(s)\n            data = data+'\\n'\n            f.write(data)\n\n\ndef build_timestamps(file_dir, time_num, interval=0.05):\n    cur_time = 0.\n    with open(file_dir, 'w') as f:\n        for _ in range(time_num):\n            s = str(cur_time)+'\\n'\n            cur_time += interval\n            f.write(s)\n\n\ndef build_depth_npy(root_dir, scene_dir, dep_scale):\n    depths = glob.glob(osp.join(root_dir, scene_dir, 'depth_left/*.png'))\n    for dep in depths:\n        dep_np = imageio.imread(dep)\n        dep_np = dep_np.astype(np.float32)\n        dep_np /= dep_scale\n        dep_np[dep_np == 0] = 1\n        npy_dir = dep.split('.')[0]+'.npy'\n        np.save(npy_dir, dep_np)\n\n\nif __name__ == '__main__':\n    root_dir = 'datasets/Replica'\n    scene_dir = 'office4'\n\n    # cam_list = get_replica_cam_list('traj.txt', osp.join(root_dir, scene_dir))\n    # gt_traj = get_trajectories_mat(cam_list)\n    # build_track_pred_file_notime(osp.join(root_dir, scene_dir, 'pose_left.txt'),\n    #                              gt_traj, 1)\n\n    # timestamps_dir = osp.join(root_dir, scene_dir, 'timestamp.txt')\n    # build_timestamps(timestamps_dir, 2000, 0.025)\n    # build_track_pred_file(timestamps_dir, osp.join(root_dir, scene_dir, 'pose_left_tum.txt'),\n    #                       gt_traj, 1)\n\n    # dep_scale = 6553.5\n    # build_depth_npy(root_dir, scene_dir, dep_scale)\n\n    mat = np.array([-3.205696220032456800e-01, 4.480551946958012954e-01, -8.345547674986967257e-01, 3.452987416406734678e+00,\n                    9.472249560947475500e-01, 1.516354520391845484e-01, -\n                    2.824386167580063001e-01, 4.546110134135947223e-01,\n                    1.078977932490423164e-16, -8.810523436158487209e-01, -\n                    4.730187816662466682e-01, 5.936285447159415085e-01,\n                    0.000000000000000000e+00, 0.000000000000000000e+00, 0.000000000000000000e+00, 1.000000000000000000e+00,\n                    ]).reshape(4, 4)\n    mat2 = mat.copy()\n    mats = np.stack([mat, mat2], axis=0)\n    quads = rmat_to_quad(mats[:, 0:3, 0:3])\n    print(quads.shape)\n"
  },
  {
    "path": "VO_Module/droid_slam/data_readers/rgbd_utils.py",
    "content": "import numpy as np\nimport os.path as osp\n\nimport torch\nfrom lietorch import SE3\n\nimport geom.projective_ops as pops\nfrom scipy.spatial.transform import Rotation\n\n\ndef parse_list(filepath, skiprows=0):\n    \"\"\" read list data \"\"\"\n    data = np.loadtxt(filepath, delimiter=' ',\n                      dtype=np.unicode_, skiprows=skiprows)\n    return data\n\n\ndef associate_frames(tstamp_image, tstamp_depth, tstamp_pose, max_dt=1.0):\n    \"\"\" pair images, depths, and poses \"\"\"\n    associations = []\n    for i, t in enumerate(tstamp_image):\n        if tstamp_pose is None:\n            j = np.argmin(np.abs(tstamp_depth - t))\n            if (np.abs(tstamp_depth[j] - t) < max_dt):\n                associations.append((i, j))\n\n        else:\n            j = np.argmin(np.abs(tstamp_depth - t))\n            k = np.argmin(np.abs(tstamp_pose - t))\n\n            if (np.abs(tstamp_depth[j] - t) < max_dt) and \\\n                    (np.abs(tstamp_pose[k] - t) < max_dt):\n                associations.append((i, j, k))\n\n    return associations\n\n\ndef loadtum(datapath, frame_rate=-1):\n    \"\"\" read video data in tum-rgbd format \"\"\"\n    if osp.isfile(osp.join(datapath, 'groundtruth.txt')):\n        pose_list = osp.join(datapath, 'groundtruth.txt')\n\n    elif osp.isfile(osp.join(datapath, 'pose.txt')):\n        pose_list = osp.join(datapath, 'pose.txt')\n\n    else:\n        return None, None, None, None\n\n    image_list = osp.join(datapath, 'rgb.txt')\n    depth_list = osp.join(datapath, 'depth.txt')\n\n    calib_path = osp.join(datapath, 'calibration.txt')\n    intrinsic = None\n    if osp.isfile(calib_path):\n        intrinsic = np.loadtxt(calib_path, delimiter=' ')\n        intrinsic = intrinsic.astype(np.float64)\n\n    image_data = parse_list(image_list)\n    depth_data = parse_list(depth_list)\n    pose_data = parse_list(pose_list, skiprows=1)\n    pose_vecs = pose_data[:, 1:].astype(np.float64)\n\n    tstamp_image = image_data[:, 0].astype(np.float64)\n    tstamp_depth = depth_data[:, 0].astype(np.float64)\n    tstamp_pose = pose_data[:, 0].astype(np.float64)\n    associations = associate_frames(tstamp_image, tstamp_depth, tstamp_pose)\n\n    # print(len(tstamp_image))\n    # print(len(associations))\n\n    indicies = range(len(associations))[::5]\n\n    # indicies = [ 0 ]\n    # for i in range(1, len(associations)):\n    #     t0 = tstamp_image[associations[indicies[-1]][0]]\n    #     t1 = tstamp_image[associations[i][0]]\n    #     if t1 - t0 > 1.0 / frame_rate:\n    #         indicies += [ i ]\n\n    images, poses, depths, intrinsics, tstamps = [], [], [], [], []\n    for ix in indicies:\n        (i, j, k) = associations[ix]\n        images += [osp.join(datapath, image_data[i, 1])]\n        depths += [osp.join(datapath, depth_data[j, 1])]\n        poses += [pose_vecs[k]]\n        tstamps += [tstamp_image[i]]\n\n        if intrinsic is not None:\n            intrinsics += [intrinsic]\n\n    return images, depths, poses, intrinsics, tstamps\n\n\ndef all_pairs_distance_matrix(poses, beta=2.5):\n    \"\"\" compute distance matrix between all pairs of poses \"\"\"\n    poses = np.array(poses, dtype=np.float32)\n    poses[:, :3] *= beta  # scale to balence rot + trans\n    poses = SE3(torch.from_numpy(poses))\n\n    r = (poses[:, None].inv() * poses[None, :]).log()\n    return r.norm(dim=-1).cpu().numpy()\n\n\ndef pose_matrix_to_quaternion(pose):\n    \"\"\" convert 4x4 pose matrix to (t, q) \"\"\"\n    q = Rotation.from_matrix(pose[:3, :3]).as_quat()\n    return np.concatenate([pose[:3, 3], q], axis=0)\n\n\ndef compute_distance_matrix_flow(poses, disps, intrinsics, need_inv=True):\n    \"\"\" compute flow magnitude between all pairs of frames \"\"\"\n    if not isinstance(poses, SE3):\n        poses = torch.from_numpy(poses).float().cuda()[None]\n        if need_inv:\n            poses = SE3(poses).inv()\n        else:\n            poses = SE3(poses)\n\n        disps = torch.from_numpy(disps).float().cuda()[None]\n        intrinsics = torch.from_numpy(intrinsics).float().cuda()[None]\n\n    N = poses.shape[1]\n\n    ii, jj = torch.meshgrid(torch.arange(N), torch.arange(N))\n    ii = ii.reshape(-1).cuda()\n    jj = jj.reshape(-1).cuda()\n\n    MAX_FLOW = 100.0\n    matrix = np.zeros((N, N), dtype=np.float32)\n\n    s = 2048\n    for i in range(0, ii.shape[0], s):\n        flow1, val1 = pops.induced_flow(\n            poses, disps, intrinsics, ii[i:i+s], jj[i:i+s])\n        flow2, val2 = pops.induced_flow(\n            poses, disps, intrinsics, jj[i:i+s], ii[i:i+s])\n\n        flow = torch.stack([flow1, flow2], dim=2)\n        val = torch.stack([val1, val2], dim=2)\n\n        mag = flow.norm(dim=-1).clamp(max=MAX_FLOW)\n        mag = mag.view(mag.shape[1], -1)\n        val = val.view(val.shape[1], -1)\n\n        mag = (mag * val).mean(-1) / val.mean(-1)\n        mag[val.mean(-1) < 0.7] = np.inf\n\n        i1 = ii[i:i+s].cpu().numpy()\n        j1 = jj[i:i+s].cpu().numpy()\n        matrix[i1, j1] = mag.cpu().numpy()\n\n    return matrix\n\n\ndef compute_distance_matrix_flow2(poses, disps, intrinsics, beta=0.4):\n    \"\"\" compute flow magnitude between all pairs of frames \"\"\"\n    # if not isinstance(poses, SE3):\n    #     poses = torch.from_numpy(poses).float().cuda()[None]\n    #     poses = SE3(poses).inv()\n\n    #     disps = torch.from_numpy(disps).float().cuda()[None]\n    #     intrinsics = torch.from_numpy(intrinsics).float().cuda()[None]\n\n    N = poses.shape[1]\n\n    ii, jj = torch.meshgrid(torch.arange(N), torch.arange(N))\n    ii = ii.reshape(-1)\n    jj = jj.reshape(-1)\n\n    MAX_FLOW = 128.0\n    matrix = np.zeros((N, N), dtype=np.float32)\n\n    s = 2048\n    for i in range(0, ii.shape[0], s):\n        flow1a, val1a = pops.induced_flow(\n            poses, disps, intrinsics, ii[i:i+s], jj[i:i+s], tonly=True)\n        flow1b, val1b = pops.induced_flow(\n            poses, disps, intrinsics, ii[i:i+s], jj[i:i+s])\n        flow2a, val2a = pops.induced_flow(\n            poses, disps, intrinsics, jj[i:i+s], ii[i:i+s], tonly=True)\n        flow2b, val2b = pops.induced_flow(\n            poses, disps, intrinsics, ii[i:i+s], jj[i:i+s])\n\n        flow1 = flow1a + beta * flow1b\n        val1 = val1a * val2b\n\n        flow2 = flow2a + beta * flow2b\n        val2 = val2a * val2b\n\n        flow = torch.stack([flow1, flow2], dim=2)\n        val = torch.stack([val1, val2], dim=2)\n\n        mag = flow.norm(dim=-1).clamp(max=MAX_FLOW)\n        mag = mag.view(mag.shape[1], -1)\n        val = val.view(val.shape[1], -1)\n\n        mag = (mag * val).mean(-1) / val.mean(-1)\n        mag[val.mean(-1) < 0.8] = np.inf\n\n        i1 = ii[i:i+s].cpu().numpy()\n        j1 = jj[i:i+s].cpu().numpy()\n        matrix[i1, j1] = mag.cpu().numpy()\n\n    return matrix\n"
  },
  {
    "path": "VO_Module/droid_slam/data_readers/stream.py",
    "content": "\nimport numpy as np\nimport torch\nimport torch.utils.data as data\nimport torch.nn.functional as F\n\nimport csv\nimport os\nimport cv2\nimport math\nimport random\nimport json\nimport pickle\nimport os.path as osp\n\nfrom .rgbd_utils import *\n\nclass RGBDStream(data.Dataset):\n    def __init__(self, datapath, frame_rate=-1, image_size=[384,512], crop_size=[0,0]):\n        self.datapath = datapath\n        self.frame_rate = frame_rate\n        self.image_size = image_size\n        self.crop_size = crop_size\n        self._build_dataset_index()\n    \n    @staticmethod\n    def image_read(image_file):\n        return cv2.imread(image_file)\n\n    @staticmethod\n    def depth_read(depth_file):\n        return np.load(depth_file)\n\n    def __len__(self):\n        return len(self.images)\n\n    def __getitem__(self, index):\n        \"\"\" return training video \"\"\"\n        image = self.__class__.image_read(self.images[index])\n        image = torch.from_numpy(image).float()\n        image = image.permute(2, 0, 1)\n\n        try:\n            tstamp = self.tstamps[index]\n        except:\n            tstamp = index\n\n        pose = torch.from_numpy(self.poses[index]).float()\n        intrinsic = torch.from_numpy(self.intrinsics[index]).float()\n\n        # resize image\n        sx = self.image_size[1] / image.shape[2]\n        sy = self.image_size[0] / image.shape[1]\n\n        image = F.interpolate(image[None], self.image_size, mode='bilinear', align_corners=False)[0]\n\n        fx, fy, cx, cy = intrinsic.unbind(dim=0)\n        fx, cx = sx * fx, sx * cx\n        fy, cy = sy * fy, sy * cy\n        \n        # crop image\n        if self.crop_size[0] > 0:\n            cy = cy - self.crop_size[0]\n            image = image[:,self.crop_size[0]:-self.crop_size[0],:]\n\n        if self.crop_size[1] > 0:\n            cx = cx - self.crop_size[1]\n            image = image[:,:,self.crop_size[1]:-self.crop_size[1]]\n\n        intrinsic = torch.stack([fx, fy, cx, cy])\n\n        return tstamp, image, pose, intrinsic\n\n\nclass ImageStream(data.Dataset):\n    def __init__(self, datapath, intrinsics, rate=1, image_size=[384,512]):\n        rgb_list = osp.join(datapath, 'rgb.txt')\n        if os.path.isfile(rgb_list):\n            rgb_list = np.loadtxt(rgb_list, delimiter=' ', dtype=np.unicode_)\n            self.timestamps = rgb_list[:,0].astype(np.float)\n            self.images = [os.path.join(datapath, x) for x in rgb_list[:,1]]\n            self.images = self.images[::rate]\n            self.timestamps = self.timestamps[::rate]\n\n        else:\n            import glob\n            self.images = sorted(glob.glob(osp.join(datapath, '*.jpg'))) +  sorted(glob.glob(osp.join(datapath, '*.png')))\n            self.images = self.images[::rate]\n\n        self.intrinsics = intrinsics\n        self.image_size = image_size\n\n    def __len__(self):\n        return len(self.images)\n\n    @staticmethod\n    def image_read(imfile):\n        return cv2.imread(imfile)\n\n    def __getitem__(self, index):\n        \"\"\" return training video \"\"\"\n        image = self.__class__.image_read(self.images[index])\n\n        try:\n            tstamp = self.timestamps[index]\n        except:\n            tstamp = index\n\n        ht0, wd0 = image.shape[:2]\n        ht1, wd1 = self.image_size\n\n        intrinsics = torch.as_tensor(self.intrinsics)\n        intrinsics[0] *= wd1 / wd0\n        intrinsics[1] *= ht1 / ht0\n        intrinsics[2] *= wd1 / wd0\n        intrinsics[3] *= ht1 / ht0\n\n        # resize image\n        ikwargs = {'mode': 'bilinear', 'align_corners': True}\n        image = torch.from_numpy(image).float().permute(2, 0, 1)\n        image = F.interpolate(image[None], self.image_size, **ikwargs)[0]\n\n        return tstamp, image, intrinsics\n\n\n\nclass StereoStream(data.Dataset):\n    def __init__(self, datapath, intrinsics, rate=1, image_size=[384,512], \n            map_left=None, map_right=None, left_root='image_left', right_root='image_right'):\n        import glob\n        self.intrinsics = intrinsics\n        self.image_size = image_size\n        \n        imgs = sorted(glob.glob(osp.join(datapath, left_root, '*.png')))[::rate]\n        self.images_l = []\n        self.images_r = []\n        self.tstamps = []\n\n        for img_l in imgs:\n            img_r = img_l.replace(left_root, right_root)\n            if os.path.isfile(img_r):\n                t = np.float(img_l.split('/')[-1].replace('.png', ''))\n                self.tstamps.append(t)\n                self.images_l += [ img_l ]\n                self.images_r += [ img_r ]\n\n        self.map_left = map_left\n        self.map_right = map_right\n\n    def __len__(self):\n        return len(self.images_l)\n\n    @staticmethod\n    def image_read(imfile, imap=None):\n        image = cv2.imread(imfile)\n        if imap is not None:\n            image = cv2.remap(image, imap[0], imap[1], interpolation=cv2.INTER_LINEAR)\n        return image\n\n    def __getitem__(self, index):\n        \"\"\" return training video \"\"\"\n        tstamp = self.tstamps[index]\n        image_l = self.__class__.image_read(self.images_l[index], self.map_left)\n        image_r = self.__class__.image_read(self.images_r[index], self.map_right)\n\n        ht0, wd0 = image_l.shape[:2]\n        ht1, wd1 = self.image_size\n\n        intrinsics = torch.as_tensor(self.intrinsics)\n        intrinsics[0] *= wd1 / wd0\n        intrinsics[1] *= ht1 / ht0\n        intrinsics[2] *= wd1 / wd0\n        intrinsics[3] *= ht1 / ht0\n\n        image_l = torch.from_numpy(image_l).float().permute(2, 0, 1)\n        image_r = torch.from_numpy(image_r).float().permute(2, 0, 1)\n\n        # resize image\n        ikwargs = {'mode': 'bilinear', 'align_corners': True}\n        image_l = F.interpolate(image_l[None], self.image_size, **ikwargs)[0]\n        image_r = F.interpolate(image_r[None], self.image_size, **ikwargs)[0]\n\n        return tstamp, image_l, image_r, intrinsics\n\n\n\n# class RGBDStream(data.Dataset):\n#     def __init__(self, datapath, intrinsics=None, rate=1, image_size=[384,512]):\n#         assoc_file = osp.join(datapath, 'associated.txt')\n#         assoc_list = np.loadtxt(assoc_file, delimiter=' ', dtype=np.unicode_)\n        \n#         self.intrinsics = intrinsics\n#         self.image_size = image_size\n        \n#         self.timestamps = assoc_list[:,0].astype(np.float)[::rate]\n#         self.images = [os.path.join(datapath, x) for x in assoc_list[:,1]][::rate]\n#         self.depths = [os.path.join(datapath, x) for x in assoc_list[:,3]][::rate]\n\n#     def __len__(self):\n#         return len(self.images)\n\n#     @staticmethod\n#     def image_read(imfile):\n#         return cv2.imread(imfile)\n\n#     @staticmethod\n#     def depth_read(depth_file):\n#         depth = cv2.imread(depth_file, cv2.IMREAD_ANYDEPTH)\n#         return depth.astype(np.float32) / 5000.0\n\n#     def __getitem__(self, index):\n#         \"\"\" return training video \"\"\"\n#         tstamp = self.timestamps[index]\n#         image = self.__class__.image_read(self.images[index])\n#         depth = self.__class__.depth_read(self.depths[index])\n\n#         ht0, wd0 = image.shape[:2]\n#         ht1, wd1 = self.image_size\n\n#         intrinsics = torch.as_tensor(self.intrinsics)\n#         intrinsics[0] *= wd1 / wd0\n#         intrinsics[1] *= ht1 / ht0\n#         intrinsics[2] *= wd1 / wd0\n#         intrinsics[3] *= ht1 / ht0\n\n#         # resize image\n#         ikwargs = {'mode': 'bilinear', 'align_corners': True}\n#         image = torch.from_numpy(image).float().permute(2, 0, 1)\n#         image = F.interpolate(image[None], self.image_size, **ikwargs)[0]\n\n#         depth = torch.from_numpy(depth).float()[None,None]\n#         depth = F.interpolate(depth, self.image_size, mode='nearest').squeeze()\n\n#         return tstamp, image, depth, intrinsics\n"
  },
  {
    "path": "VO_Module/droid_slam/data_readers/tartan.py",
    "content": "\nimport numpy as np\nimport torch\nimport glob\nimport cv2\nimport os\nimport os.path as osp\n\nfrom lietorch import SE3\nfrom .base import RGBDDataset\nfrom .stream import RGBDStream\n\ncur_path = osp.dirname(osp.abspath(__file__))\ntest_split = osp.join(cur_path, 'tartan_test.txt')\ntest_split = open(test_split).read().split()\n\n\nclass TartanAir(RGBDDataset):\n\n    # scale depths to balance rot & trans\n    DEPTH_SCALE = 5.0\n\n    def __init__(self, mode='training', **kwargs):\n        self.mode = mode\n        self.n_frames = 2\n        super(TartanAir, self).__init__(name='TartanAir', **kwargs)\n\n    @staticmethod\n    def is_test_scene(scene):\n        # print(scene, any(x in scene for x in test_split))\n        return any(x in scene for x in test_split)\n\n    def _build_dataset(self):\n        from tqdm import tqdm\n        print(\"Building TartanAir dataset\")\n\n        scene_info = {}\n        scenes = glob.glob(osp.join(self.root, '*/*/*/*'))\n        for scene in tqdm(sorted(scenes)):\n            # [:-1]为了与mask对齐\n            images = sorted(\n                glob.glob(osp.join(scene, 'image_left/*.png')))[:-1]\n            depths = sorted(\n                glob.glob(osp.join(scene, 'depth_left/*.npy')))[:-1]\n\n            poses = np.loadtxt(\n                osp.join(scene, 'pose_left.txt'), delimiter=' ')\n            poses = poses[:-1, [1, 2, 0, 4, 5, 3, 6]]\n            poses[:, :3] /= TartanAir.DEPTH_SCALE\n            intrinsics = [TartanAir.calib_read()] * len(images)\n\n            # graph of co-visible frames based on flow\n            graph = self.build_frame_graph(poses, depths, intrinsics)\n\n            masks = sorted(glob.glob(osp.join(scene, 'flow/*mask.npy')))\n\n            scene = '/'.join(scene.split('/'))\n            scene_info[scene] = {'images': images, 'depths': depths, 'dymasks': masks,\n                                 'poses': poses, 'intrinsics': intrinsics, 'graph': graph}\n\n        return scene_info\n\n    @staticmethod\n    def calib_read():\n        return np.array([320.0, 320.0, 320.0, 240.0])\n\n    @staticmethod\n    def image_read(image_file):\n        return cv2.imread(image_file)\n\n    @staticmethod\n    def depth_read(depth_file):\n        depth = np.load(depth_file) / TartanAir.DEPTH_SCALE\n        depth[depth == np.nan] = 1.0\n        depth[depth == np.inf] = 1.0\n        return depth\n\n    @staticmethod\n    def dymask_read(mask_file):\n        content1 = (np.load(mask_file) <= 0).astype(np.float32)\n        content2 = np.ones_like(content1)\n        return content1, content2\n\n\nclass TartanAirStream(RGBDStream):\n    def __init__(self, datapath, **kwargs):\n        super(TartanAirStream, self).__init__(datapath=datapath, **kwargs)\n\n    def _build_dataset_index(self):\n        \"\"\" build list of images, poses, depths, and intrinsics \"\"\"\n        self.root = 'datasets/TartanAir'\n\n        scene = osp.join(self.root, self.datapath)\n        image_glob = osp.join(scene, 'image_left/*.png')\n        images = sorted(glob.glob(image_glob))\n\n        poses = np.loadtxt(osp.join(scene, 'pose_left.txt'), delimiter=' ')\n        poses = poses[:, [1, 2, 0, 4, 5, 3, 6]]\n\n        poses = SE3(torch.as_tensor(poses))\n        poses = poses[[0]].inv() * poses\n        poses = poses.data.cpu().numpy()\n\n        intrinsic = self.calib_read(self.datapath)\n        intrinsics = np.tile(intrinsic[None], (len(images), 1))\n\n        self.images = images[::int(self.frame_rate)]\n        self.poses = poses[::int(self.frame_rate)]\n        self.intrinsics = intrinsics[::int(self.frame_rate)]\n\n    @staticmethod\n    def calib_read(datapath):\n        return np.array([320.0, 320.0, 320.0, 240.0])\n\n    @staticmethod\n    def image_read(image_file):\n        return cv2.imread(image_file)\n\n\nclass TartanAirTestStream(RGBDStream):\n    def __init__(self, datapath, **kwargs):\n        super(TartanAirTestStream, self).__init__(datapath=datapath, **kwargs)\n\n    def _build_dataset_index(self):\n        \"\"\" build list of images, poses, depths, and intrinsics \"\"\"\n        self.root = 'datasets/mono'\n        image_glob = osp.join(self.root, self.datapath, '*.png')\n        images = sorted(glob.glob(image_glob))\n\n        poses = np.loadtxt(osp.join(self.root, 'mono_gt',\n                           self.datapath + '.txt'), delimiter=' ')\n        poses = poses[:, [1, 2, 0, 4, 5, 3, 6]]\n\n        poses = SE3(torch.as_tensor(poses))\n        poses = poses[[0]].inv() * poses\n        poses = poses.data.cpu().numpy()\n\n        intrinsic = self.calib_read(self.datapath)\n        intrinsics = np.tile(intrinsic[None], (len(images), 1))\n\n        self.images = images[::int(self.frame_rate)]\n        self.poses = poses[::int(self.frame_rate)]\n        self.intrinsics = intrinsics[::int(self.frame_rate)]\n\n    @staticmethod\n    def calib_read(datapath):\n        return np.array([320.0, 320.0, 320.0, 240.0])\n\n    @staticmethod\n    def image_read(image_file):\n        return cv2.imread(image_file)\n"
  },
  {
    "path": "VO_Module/droid_slam/data_readers/tartan_test.txt",
    "content": "abandonedfactory/abandonedfactory/Easy/P011\nabandonedfactory/abandonedfactory/Hard/P011\nabandonedfactory_night/abandonedfactory_night/Easy/P013\nabandonedfactory_night/abandonedfactory_night/Hard/P014\namusement/amusement/Easy/P008\namusement/amusement/Hard/P007\ncarwelding/carwelding/Easy/P007\nendofworld/endofworld/Easy/P009\ngascola/gascola/Easy/P008\ngascola/gascola/Hard/P009\nhospital/hospital/Easy/P036\nhospital/hospital/Hard/P049\njapanesealley/japanesealley/Easy/P007\njapanesealley/japanesealley/Hard/P005\nneighborhood/neighborhood/Easy/P021\nneighborhood/neighborhood/Hard/P017\nocean/ocean/Easy/P013\nocean/ocean/Hard/P009\noffice2/office2/Easy/P011\noffice2/office2/Hard/P010\noffice/office/Hard/P007\noldtown/oldtown/Easy/P007\noldtown/oldtown/Hard/P008\nseasidetown/seasidetown/Easy/P009\nseasonsforest/seasonsforest/Easy/P011\nseasonsforest/seasonsforest/Hard/P006\nseasonsforest_winter/seasonsforest_winter/Easy/P009\nseasonsforest_winter/seasonsforest_winter/Hard/P018\nsoulcity/soulcity/Easy/P012\nsoulcity/soulcity/Hard/P009\nwesterndesert/westerndesert/Easy/P013\nwesterndesert/westerndesert/Hard/P007\n"
  },
  {
    "path": "VO_Module/droid_slam/data_readers/vkitti2.py",
    "content": "\nimport numpy as np\nimport torch\nimport glob\nimport cv2\nimport os\nimport os.path as osp\n\nfrom scipy.spatial.transform import Rotation as R\nfrom lietorch import SE3\nfrom torch.functional import split\nfrom .base import RGBDDataset\nfrom .stream import RGBDStream\n\nfrom panopticapi.utils import  rgb2id\nimport PIL.Image as Image\n\ndef rmat_to_quad(mat):\n    r = R.from_matrix(mat)\n    quat = r.as_quat()\n    return quat\n\nclass VKitti2(RGBDDataset):\n\n    # scale depths to balance rot & trans\n    DEPTH_SCALE = 5.0\n    split = {\n        'train': 'clone',\n        'val': '15-deg-left',\n        'test': '30-deg-right'\n    }\n    scenes = ['Scene18', 'Scene20' , 'Scene06', 'Scene02', 'Scene01']\n    print(scenes)\n    def __init__(self, split_mode='train', foo=False, scene_id='Scene01',  **kwargs):\n        self.split_mode = split_mode\n        self.n_frames = 2\n        self.foo = foo\n        self.test_split = [x for x in VKitti2.scenes if x != scene_id]\n        super(VKitti2, self).__init__(name='VKitti2', **kwargs)\n\n    # @staticmethod\n    def is_test_scene(self, scene):\n        return any(x in scene for x in self.test_split)\n\n    def _build_dataset(self):\n        from tqdm import tqdm\n        print(\"Building VKitti2 dataset\")\n        scenes = VKitti2.scenes\n        scene_info = {}\n        for scene in tqdm(sorted(scenes)):\n            scene = osp.join(self.root, scene)\n            images = sorted(\n                glob.glob(osp.join(scene, VKitti2.split[self.split_mode], 'frames/rgb/Camera_0/*.jpg')))\n            depths = sorted(\n                glob.glob(osp.join( scene, VKitti2.split[self.split_mode], 'frames/depth/Camera_0/*.png')))\n\n            poses = np.loadtxt(\n                osp.join(scene, VKitti2.split[self.split_mode], 'extrinsic.txt'), delimiter=' ', skiprows=1)[::2, 2:]\n            \n            if self.foo:\n                images = np.array(images)\n                depths = np.array(depths)\n                val_num = images.shape[0] // 7\n                train_num = images.shape[0] - val_num - val_num\n                print(val_num,'\\n',images[train_num], \"\\n\", images[train_num+val_num-1])\n                images = images[train_num:train_num + val_num]\n                depths = depths[train_num:train_num + val_num]\n                poses = poses[train_num:train_num + val_num]\n                print(poses.shape)\n                images.tolist()\n                depths.tolist()\n\n            poses = poses.reshape(-1, 4, 4)  \n            r = rmat_to_quad(poses[:, 0:3, 0:3])\n            t = poses[:, :3, 3] / VKitti2.DEPTH_SCALE\n            poses = np.concatenate((t, r), axis=1)\n\n            intrinsics = [VKitti2.calib_read()] * len(images)\n            scene = '/'.join(scene.split('/'))\n\n            # graph of co-visible frames based on flow\n            graph = None\n            if self.aug_graph:\n                graph = self.build_frame_graph(poses, depths, intrinsics)\n\n            if self.flow_label:\n                fo_flows = sorted(\n                    glob.glob(osp.join(scene, VKitti2.split[self.split_mode], 'frames/forwardFlow/Camera_0/*.png')))\n                ba_flows = sorted(\n                    glob.glob(osp.join(scene, VKitti2.split[self.split_mode], 'frames/backwardFlow/Camera_0/*.png')))\n                segments = sorted(\n                    glob.glob(osp.join(scene,  VKitti2.split[self.split_mode], 'panoptic_gt_id/*.png')))\n                scene_info[scene] = {'images': images, 'depths': depths, 'fo_flows': fo_flows,\n                                     'ba_flows': ba_flows, 'poses': poses, 'intrinsics': intrinsics, 'segments' : segments}\n            else: \n                masks = sorted(\n                    glob.glob(osp.join(scene, VKitti2.split[self.split_mode], 'frames/dynamicMask/Camera_0/*.npy')))\n                segments = sorted(\n                    glob.glob(osp.join(scene,  VKitti2.split[self.split_mode], 'panFPN_segm/*.png')))\n\n                scene_info[scene] = {'images': images, 'depths': depths, 'dymasks': masks,\n                                     'poses': poses, 'intrinsics': intrinsics, 'graph': graph, 'segments': segments, }\n            print('segments' in scene_info[scene])\n        return scene_info\n\n    @staticmethod\n    def calib_read():\n        return np.array([725.0087, 725.0087, 620.5, 187])\n\n    @staticmethod\n    def image_read(image_file):\n        return cv2.imread(image_file)\n\n    @staticmethod\n    def depth_read(depth_file):\n        depth = cv2.imread(depth_file, cv2.IMREAD_ANYCOLOR |\n                           cv2.IMREAD_ANYDEPTH) / (VKitti2.DEPTH_SCALE*100)\n        depth[depth == np.nan] = 1.0\n        depth[depth == np.inf] = 1.0\n        depth[depth == 0] = 1.0\n        return depth\n\n    @staticmethod\n    def flow_read(flow_file):\n        bgr = cv2.imread(flow_file, cv2.IMREAD_ANYCOLOR | cv2.IMREAD_ANYDEPTH)\n        h, w, _c = bgr.shape\n        out_flow = 2.0 / (2**16 - 1.0) * bgr[..., 2:0:-1].astype('f4') - 1\n        out_flow[..., 0] *= w - 1\n        out_flow[..., 1] *= h - 1\n        val = (bgr[..., 0] > 0).astype(np.float32)\n        return out_flow, val\n\n    @staticmethod\n    def dymask_read(mask_file):\n        content = np.load(mask_file)\n        return content[..., 0], content[..., 1]\n\n    @staticmethod\n    def segment_read(segment_file):\n        segment = rgb2id(np.array(Image.open(segment_file)))\n        return segment \n\n\nclass VKitti2Stream(RGBDStream):\n    def __init__(self, datapath, **kwargs):\n        super(VKitti2Stream, self).__init__(datapath=datapath, **kwargs)\n\n    def _build_dataset_index(self):\n        \"\"\" build list of images, poses, depths, and intrinsics \"\"\"\n        self.root = 'datasets/VKitti2'\n\n        scene = osp.join(self.root, self.datapath)\n        image_glob = osp.join(scene, 'image_left/*.png')\n        images = sorted(glob.glob(image_glob))\n\n        poses = np.loadtxt(osp.join(scene, 'pose_left.txt'), delimiter=' ')\n        poses = poses[:, [1, 2, 0, 4, 5, 3, 6]]\n\n        poses = SE3(torch.as_tensor(poses))\n        poses = poses[[0]].inv() * poses\n        poses = poses.data.cpu().numpy()\n\n        intrinsic = self.calib_read(self.datapath)\n        intrinsics = np.tile(intrinsic[None], (len(images), 1))\n\n        self.images = images[::int(self.frame_rate)]\n        self.poses = poses[::int(self.frame_rate)]\n        self.intrinsics = intrinsics[::int(self.frame_rate)]\n\n    @staticmethod\n    def calib_read(datapath):\n        return np.array([320.0, 320.0, 320.0, 240.0])\n\n    @staticmethod\n    def image_read(image_file):\n        return cv2.imread(image_file)\n\n\nclass VKitti2TestStream(RGBDStream):\n    def __init__(self, datapath, **kwargs):\n        super(VKitti2TestStream, self).__init__(datapath=datapath, **kwargs)\n\n    def _build_dataset_index(self):\n        \"\"\" build list of images, poses, depths, and intrinsics \"\"\"\n        self.root = 'datasets/mono'\n        image_glob = osp.join(self.root, self.datapath, '*.png')\n        images = sorted(glob.glob(image_glob))\n\n        poses = np.loadtxt(osp.join(self.root, 'mono_gt',\n                           self.datapath + '.txt'), delimiter=' ')\n        poses = poses[:, [1, 2, 0, 4, 5, 3, 6]]\n\n        poses = SE3(torch.as_tensor(poses))\n        poses = poses[[0]].inv() * poses\n        poses = poses.data.cpu().numpy()\n\n        intrinsic = self.calib_read(self.datapath)\n        intrinsics = np.tile(intrinsic[None], (len(images), 1))\n\n        self.images = images[::int(self.frame_rate)]\n        self.poses = poses[::int(self.frame_rate)]\n        self.intrinsics = intrinsics[::int(self.frame_rate)]\n\n    @staticmethod\n    def calib_read(datapath):\n        return np.array([320.0, 320.0, 320.0, 240.0])\n\n    @staticmethod\n    def image_read(image_file):\n        return cv2.imread(image_file)\n"
  },
  {
    "path": "VO_Module/droid_slam/depth_video.py",
    "content": "import numpy as np\nimport torch\nimport lietorch\nimport droid_backends\n\nfrom torch.multiprocessing import Process, Queue, Lock, Value\nfrom collections import OrderedDict\n\nfrom droid_net import cvx_upsample\nimport geom.projective_ops as pops\nfrom geom.ba import BA\nfrom lietorch import SO3, SE3, Sim3\nclass DepthVideo:\n    def __init__(self, image_size=[480, 640], buffer=1024, device=\"cuda:0\", segm_filter=False, thresh=0.8):\n\n        # current keyframe count\n        self.counter = Value('i', 0)\n        self.ready = Value('i', 0)\n        self.ht = ht = image_size[0]\n        self.wd = wd = image_size[1]\n        self.device = device\n\n        ### state attributes ###\n        self.tstamp = torch.zeros(\n            buffer, device=device, dtype=torch.float).share_memory_()\n        self.images = torch.zeros(\n            buffer, 3, ht, wd, device=device, dtype=torch.uint8)\n        self.dirty = torch.zeros(\n            buffer, device=device, dtype=torch.bool).share_memory_()\n        self.red = torch.zeros(buffer, device=device,\n                               dtype=torch.bool).share_memory_()\n        self.poses = torch.zeros(\n            buffer, 7, device=device, dtype=torch.float).share_memory_()\n        self.disps = torch.ones(\n            buffer, ht//8, wd//8, device=device, dtype=torch.float).share_memory_()\n        self.disps_up = torch.zeros(\n            buffer, ht, wd, device=device, dtype=torch.float).share_memory_()\n        self.intrinsics = torch.zeros(\n            buffer, 4, device=device, dtype=torch.float).share_memory_()\n\n        ### feature attributes ###\n        self.fmaps = torch.zeros(\n            buffer, 128, ht//8, wd//8, dtype=torch.half, device=device).share_memory_()\n        self.nets = torch.zeros(\n            buffer, 128, ht//8, wd//8, dtype=torch.half, device=device).share_memory_()\n        self.inps = torch.zeros(\n            buffer, 128, ht//8, wd//8,dtype=torch.half, device=device).share_memory_()\n\n        # initialize poses to identity transformation\n        self.poses[:] = torch.as_tensor(\n            [0, 0, 0, 0, 0, 0, 1], dtype=torch.float, device=device)\n        \n        # new adding\n        self.segms = torch.zeros(\n            buffer, 1, ht//8, wd//8,dtype=torch.int, device=device).share_memory_()\n        self.full_flow = torch.ones(\n            buffer, ht//8, wd//8, 2,device=device, dtype=torch.float).share_memory_()\n        self.segm_filter = segm_filter\n        self.thresh = thresh\n        \n    def get_lock(self):\n        return self.counter.get_lock()\n\n    def __item_setter(self, index, item):\n        if isinstance(index, int) and index >= self.counter.value:\n            self.counter.value = index + 1\n\n        elif isinstance(index, torch.Tensor) and index.max().item() > self.counter.value:\n            self.counter.value = index.max().item() + 1\n\n        # self.dirty[index] = True\n        self.tstamp[index] = item[0]\n        self.images[index] = item[1]\n\n        if item[2] is not None:\n            self.poses[index] = item[2]\n\n        if item[3] is not None:\n            self.disps[index] = item[3]\n\n        if item[4] is not None:\n            self.intrinsics[index] = item[4]\n\n        if len(item) > 5:\n            self.fmaps[index] = item[5]\n\n        if len(item) > 6:\n            self.nets[index] = item[6]\n\n        if len(item) > 7:\n            self.inps[index] = item[7]\n        \n        if self.segm_filter and len(item) > 8:\n            self.segms[index] = item[8]\n\n    def __setitem__(self, index, item):\n        with self.get_lock():\n            self.__item_setter(index, item)\n\n    def __getitem__(self, index):\n        \"\"\" index the depth video \"\"\"\n\n        with self.get_lock():\n            # support negative indexing\n            if isinstance(index, int) and index < 0:\n                index = self.counter.value + index\n\n            item = (\n                self.poses[index],\n                self.disps[index],\n                self.intrinsics[index],\n                self.fmaps[index],\n                self.nets[index],\n                self.inps[index])\n\n        return item\n\n    def append(self, *item):\n        with self.get_lock():\n            self.__item_setter(self.counter.value, item)\n\n    ### geometric operations ###\n\n    @staticmethod\n    def format_indicies(ii, jj, device):\n        \"\"\" to device, long, {-1} \"\"\"\n\n        if not isinstance(ii, torch.Tensor):\n            ii = torch.as_tensor(ii)\n\n        if not isinstance(jj, torch.Tensor):\n            jj = torch.as_tensor(jj)\n\n        ii = ii.to(device=device, dtype=torch.long).reshape(-1)\n        jj = jj.to(device=device, dtype=torch.long).reshape(-1)\n\n        return ii, jj\n\n    def upsample(self, ix, mask):\n        \"\"\" upsample disparity \"\"\"\n\n        disps_up = cvx_upsample(self.disps[ix].unsqueeze(-1), mask)\n        self.disps_up[ix] = disps_up.squeeze()\n\n    def normalize(self):\n        \"\"\" normalize depth and poses \"\"\"\n\n        with self.get_lock():\n            s = self.disps[:self.counter.value].mean()\n            self.disps[:self.counter.value] /= s\n            self.poses[:self.counter.value, :3] *= s\n            self.dirty[:self.counter.value] = True\n\n    def reproject(self, ii, jj):\n        \"\"\" project points from ii -> jj \"\"\"\n        ii, jj = DepthVideo.format_indicies(ii, jj, self.device)\n        Gs = lietorch.SE3(self.poses[None])\n\n        coords, valid_mask = \\\n            pops.projective_transform(\n                Gs, self.disps[None], self.intrinsics[None], ii, jj)\n\n        return coords, valid_mask\n\n    def distance(self, ii=None, jj=None, beta=0.3, bidirectional=True):\n        \"\"\" frame distance metric \"\"\"\n\n        return_matrix = False\n        if ii is None:\n            return_matrix = True\n            N = self.counter.value\n            ii, jj = torch.meshgrid(torch.arange(N), torch.arange(N))\n\n        ii, jj = DepthVideo.format_indicies(ii, jj, self.device)\n\n        if bidirectional:\n\n            poses = self.poses[:self.counter.value].clone()\n\n            d1 = droid_backends.frame_distance(\n                poses, self.disps, self.intrinsics[0], ii, jj, beta)\n\n            d2 = droid_backends.frame_distance(\n                poses, self.disps, self.intrinsics[0], jj, ii, beta)\n\n            d = .5 * (d1 + d2)\n\n        else:\n            d = droid_backends.frame_distance(\n                self.poses, self.disps, self.intrinsics[0], ii, jj, beta)\n\n        if return_matrix:\n            return d.reshape(N, N)\n\n        return d\n\n    def ba(self, target, weight, eta, ii, jj, t0=1, t1=None, itrs=2, lm=1e-4, ep=0.1, motion_only=False):\n        \"\"\" dense bundle adjustment (DBA) \"\"\"\n\n        with self.get_lock():\n\n            # [t0, t1] window of bundle adjustment optimization\n            if t1 is None:\n                t1 = max(ii.max().item(), jj.max().item()) + 1\n\n            if eta is None:\n                k = torch.unique(torch.cat([ii, jj], 0)).shape[0]\n                eta = 1e-7 * \\\n                    torch.ones([k, self.ht//8, self.wd//8], device=self.device)\n\n            droid_backends.ba(self.poses, self.disps, self.intrinsics[0],\n                              target, weight, eta, ii, jj, t0, t1, itrs, lm, ep, motion_only)\n\n            self.disps.clamp_(min=0.001)\n    "
  },
  {
    "path": "VO_Module/droid_slam/droid.py",
    "content": "import torch\nimport torch.nn.functional as F\nimport lietorch\nimport numpy as np\n\nfrom droid_net import DroidNet\nfrom depth_video import DepthVideo\nfrom motion_filter import MotionFilter\nfrom droid_frontend import DroidFrontend\nfrom droid_backend import DroidBackend\nfrom trajectory_filler import PoseTrajectoryFiller\n\nfrom collections import OrderedDict\nfrom torch.multiprocessing import Process\n\nimport lietorch\n\nfrom lietorch import SE3\n\nclass Droid:\n    def __init__(self, args):\n        super(Droid, self).__init__()\n        self.args = args\n        self.load_weights(args.weights, args.use_aff_bri)\n        self.disable_vis = args.disable_vis\n\n        # store images, depth, poses, intrinsics (shared between processes)\n        print( \"use segment filter:\",args.segm_filter)\n        self.video = DepthVideo(args.image_size, args.buffer, args.device, args.segm_filter, args.thresh)\n\n        # filter incoming frames so that there is enough motion\n        self.filterx = MotionFilter(\n            self.net, self.video, thresh=args.filter_thresh, device=args.device)\n\n        # frontend process\n        self.frontend = DroidFrontend(self.net, self.video, self.args)\n\n        # backend process\n        self.backend = DroidBackend(self.net, self.video, self.args)\n\n        # visualizer\n        if not self.disable_vis:\n            from visualization import droid_visualization\n            self.visualizer = Process(\n                target=droid_visualization, args=(self.video, args.device))\n            self.visualizer.start()\n\n        # post processor - fill in poses for non-keyframes\n        self.traj_filler = PoseTrajectoryFiller(\n            self.net, self.video, args.device)\n\n    def load_weights(self, weights, use_aff_bri=False):\n        \"\"\" load trained model weights \"\"\"\n        self.net = DroidNet(use_aff_bri)\n        state_dict = OrderedDict([\n            (k.replace(\"module.\", \"\"), v) for (k, v) in torch.load(weights, self.args.device).items()])\n\n        self.net.load_state_dict(state_dict)\n        self.net.to(self.args.device).eval()\n\n    def track(self, tstamp, image, depth=None, intrinsics=None, segments=None):\n        \"\"\" main thread - update map \"\"\"\n\n        with torch.no_grad():\n            # check there is enough motion\n            self.filterx.track(tstamp, image, depth, intrinsics, segments)\n\n            # local bundle adjustment\n            self.frontend()\n\n            # global bundle adjustment\n            # self.backend()\n    \n    def terminate(self, stream=None, need_inv=True):\n        \"\"\" terminate the visualization process, return poses [t, q] \"\"\"\n\n        del self.frontend\n\n        torch.cuda.empty_cache()\n        print(\"#\" * 32)\n        self.backend(7)\n\n        torch.cuda.empty_cache()\n        print(\"#\" * 32)\n        self.backend(12)\n\n        camera_trajectory = self.traj_filler(stream)\n        if need_inv:\n            return camera_trajectory.inv().data.cpu().numpy()\n        else:\n            # for vkitti2(already w2c)\n            return camera_trajectory.data.cpu().numpy()\n\n    def get_traj(self):\n        Gs = SE3(self.video.poses[:self.video.counter.value])\n        return lietorch.cat([Gs], 0).data.cpu().numpy()\n    \n    def get_depth(self):\n        depth = upsample_inter(self.video.disps[:self.video.counter.value].unsqueeze(0).unsqueeze(4)).squeeze(4).squeeze(0)\n        return depth\n\n    def get_flow(self):\n        flow =  upsample_inter(self.video.full_flow[:self.video.counter.value].unsqueeze(0)*8)\n        return flow\n\ndef upsample_inter(mask):\n    batch, num, ht, wd, dim = mask.shape\n    mask = mask.permute(0, 1, 4, 2, 3).contiguous()\n    mask = mask.view(batch*num, dim, ht, wd)\n    mask = F.interpolate(mask, scale_factor=8, mode='bilinear',\n                         align_corners=True, recompute_scale_factor=True)\n    mask = mask.permute(0, 2, 3, 1).contiguous()\n    return mask.view(batch, num, 8*ht, 8*wd, dim)\n"
  },
  {
    "path": "VO_Module/droid_slam/droid_backend.py",
    "content": "import torch\nimport lietorch\nimport numpy as np\n\nfrom lietorch import SE3\nfrom factor_graph import FactorGraph\n\n\nclass DroidBackend:\n    def __init__(self, net, video, args):\n        self.video = video\n        self.update_op = net.update\n        self.device = args.device\n\n        # global optimization window\n        self.t0 = 0\n        self.t1 = 0\n\n        self.beta = args.beta\n        self.backend_thresh = args.backend_thresh\n        self.backend_radius = args.backend_radius\n        self.backend_nms = args.backend_nms\n\n    @torch.no_grad()\n    def __call__(self, steps=12):\n        \"\"\" main update \"\"\"\n\n        t = self.video.counter.value\n        self.video.normalize()\n\n        graph = FactorGraph(self.video, self.update_op,\n                            self.device, corr_impl=\"alt\", max_factors=100000)\n\n        graph.add_proximity_factors(rad=self.backend_radius,\n                                    nms=self.backend_nms,\n                                    thresh=self.backend_thresh,\n                                    beta=self.beta)\n\n        graph.update_lowmem(steps=steps)\n        graph.clear_edges()\n        self.video.dirty[:t] = True\n"
  },
  {
    "path": "VO_Module/droid_slam/droid_frontend.py",
    "content": "import torch\nimport lietorch\nimport numpy as np\n\nfrom lietorch import SE3\nfrom factor_graph import FactorGraph\n\n\nclass DroidFrontend:\n    def __init__(self, net, video, args):\n        self.video = video\n        self.update_op = net.update\n        self.graph = FactorGraph(\n            video, net.update, args.device, max_factors=48)\n\n        # local optimization window\n        self.t0 = 0\n        self.t1 = 0\n\n        # frontent variables\n        self.is_initialized = False\n        self.count = 0\n\n        self.max_age = 25\n        self.iters1 = 4\n        self.iters2 = 2\n\n        self.warmup = args.warmup\n        self.beta = args.beta\n        self.frontend_nms = args.frontend_nms\n        self.keyframe_thresh = args.keyframe_thresh\n        self.frontend_window = args.frontend_window\n        self.frontend_thresh = args.frontend_thresh\n        self.frontend_radius = args.frontend_radius\n\n    def __update(self):\n        \"\"\" add edges, perform update \"\"\"\n\n        self.count += 1\n        self.t1 += 1\n\n        if self.graph.corr is not None:\n            self.graph.rm_factors(self.graph.age > self.max_age, store=True)\n\n        self.graph.add_proximity_factors(self.t1-5, max(self.t1-self.frontend_window, 0),\n                                         rad=self.frontend_radius, nms=self.frontend_nms, thresh=self.frontend_thresh, beta=self.beta, remove=True)\n\n        for itr in range(self.iters1):\n            self.graph.update(None, None, use_inactive=True)\n\n        # set initial pose for next frame ------------ 删除 帧 -----------------\n        poses = SE3(self.video.poses)\n        d = self.video.distance(\n            [self.t1-3], [self.t1-2], beta=self.beta, bidirectional=True)\n        if d.item() < self.keyframe_thresh:\n            self.graph.rm_keyframe(self.t1 - 2)\n            with self.video.get_lock():\n                self.video.counter.value -= 1\n                self.t1 -= 1\n        else:\n            for itr in range(self.iters2):\n                self.graph.update(None, None, use_inactive=True)\n\n        # set pose for next itration\n        self.video.poses[self.t1] = self.video.poses[self.t1-1]\n        self.video.disps[self.t1] = self.video.disps[self.t1-1].mean()\n        # self.video.full_flow[self.graph.ii] = self.graph.full_flow\n\n        # update visualization\n        self.video.dirty[self.graph.ii.min():self.t1] = True\n\n    def __initialize(self):\n        \"\"\" initialize the SLAM system \"\"\"\n\n        self.t0 = 0\n        self.t1 = self.video.counter.value\n\n        self.graph.add_neighborhood_factors(self.t0, self.t1, r=3)\n\n        for itr in range(8):\n            self.graph.update(1, use_inactive=True)\n\n        self.graph.add_proximity_factors(\n            0, 0, rad=2, nms=2, thresh=self.frontend_thresh)\n\n        for itr in range(12):\n            self.graph.update(1, use_inactive=True)\n\n        # self.video.normalize()\n        self.video.poses[self.t1] = self.video.poses[self.t1-1].clone()\n        self.video.disps[self.t1] = self.video.disps[self.t1-4:self.t1].mean()\n\n        # initialization complete\n        self.is_initialized = True\n        self.last_pose = self.video.poses[self.t1-1].clone()\n        self.last_disp = self.video.disps[self.t1-1].clone()\n        self.last_time = self.video.tstamp[self.t1-1].clone()\n\n        with self.video.get_lock():\n            self.video.ready.value = 1\n            self.video.dirty[:self.t1] = True\n\n    def __call__(self):\n        \"\"\" main update \"\"\"\n\n        # do initialization\n        if not self.is_initialized and self.video.counter.value == self.warmup:\n            self.__initialize()\n\n        # do update\n        elif self.is_initialized and self.t1 < self.video.counter.value:\n            self.__update()\n"
  },
  {
    "path": "VO_Module/droid_slam/droid_net.py",
    "content": "import numpy as np\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom collections import OrderedDict\n\nfrom torch.nn.modules.activation import Sigmoid\n\nfrom modules.extractor import BasicEncoder\nfrom modules.corr import CorrBlock\nfrom modules.gru import ConvGRU\nfrom modules.clipping import GradientClip\n\nfrom lietorch import SE3\nfrom geom.ba import BA\n\nimport geom.projective_ops as pops\nfrom geom.graph_utils import graph_to_edge_list, keyframe_indicies\n\nfrom torch_scatter import scatter_mean\n\n\ndef cvx_upsample(data, mask):\n    \"\"\" upsample pixel-wise transformation field \"\"\"\n    batch, ht, wd, dim = data.shape\n    data = data.permute(0, 3, 1, 2)\n    mask = mask.view(batch, 1, 9, 8, 8, ht, wd)\n    mask = torch.softmax(mask, dim=2)\n\n    up_data = F.unfold(data, [3, 3], padding=1)\n    up_data = up_data.view(batch, dim, 9, 1, 1, ht, wd)\n\n    up_data = torch.sum(mask * up_data, dim=2)\n    up_data = up_data.permute(0, 4, 2, 5, 3, 1)\n    up_data = up_data.reshape(batch, 8*ht, 8*wd, dim)\n\n    return up_data\n\n\ndef upsample_dim_1(disp, mask):\n    batch, num, ht, wd = disp.shape\n    disp = disp.view(batch*num, ht, wd, 1)\n    mask = mask.view(batch*num, -1, ht, wd)\n    return cvx_upsample(disp, mask).view(batch, num, 8*ht, 8*wd)\n\n\ndef upsample_dim_x(flow, mask):\n    batch, num, ht, wd, dim = flow.shape\n    flow = flow.view(batch*num, ht, wd, dim)\n    mask = mask.view(batch*num, -1, ht, wd)\n    return cvx_upsample(flow, mask).view(batch, num, 8*ht, 8*wd, dim)\n\n\ndef upsample_inter(mask):\n    batch, num, ht, wd, dim = mask.shape\n    mask = mask.permute(0, 1, 4, 2, 3).contiguous()\n    mask = mask.view(batch*num, dim, ht, wd)\n    mask = F.interpolate(mask, scale_factor=8, mode='bilinear',\n                         align_corners=True, recompute_scale_factor=True)\n    mask = mask.permute(0, 2, 3, 1).contiguous()\n    return mask.view(batch, num, 8*ht, 8*wd, dim)\n\n\nclass GraphAgg(nn.Module):\n    def __init__(self):\n        super(GraphAgg, self).__init__()\n        self.conv1 = nn.Conv2d(128, 128, 3, padding=1)\n        self.conv2 = nn.Conv2d(128, 128, 3, padding=1)\n        self.relu = nn.ReLU(inplace=True)\n\n        self.eta = nn.Sequential(\n            nn.Conv2d(128, 1, 3, padding=1),\n            GradientClip(),\n            nn.Softplus())\n\n        self.upmask_disp = nn.Sequential(\n            nn.Conv2d(128, 8*8*9, 1, padding=0))\n\n    def forward(self, net, ii):\n        batch, num, ch, ht, wd = net.shape\n        net = net.view(batch*num, ch, ht, wd)\n\n        _, ix = torch.unique(ii, return_inverse=True)\n        net = self.relu(self.conv1(net))\n\n        net = net.view(batch, num, 128, ht, wd)\n        net_less = scatter_mean(net, ix, dim=1)\n        net_less = net_less.view(-1, 128, ht, wd)\n\n        net_less = self.relu(self.conv2(net_less))\n\n        eta = self.eta(net_less).view(batch, -1, ht, wd)\n        upmask_disp = self.upmask_disp(net_less).view(batch, -1, 8*8*9, ht, wd)\n\n        return .01 * eta, upmask_disp, None, None\n\n\nclass UpdateModule(nn.Module):\n    def __init__(self):\n        super(UpdateModule, self).__init__()\n        cor_planes = 4 * (2*3 + 1)**2\n\n        self.corr_encoder = nn.Sequential(\n            nn.Conv2d(cor_planes, 128, 1, padding=0),\n            nn.ReLU(inplace=True),\n            nn.Conv2d(128, 128, 3, padding=1),\n            nn.ReLU(inplace=True))\n\n        self.flow_encoder = nn.Sequential(\n            nn.Conv2d(4, 128, 7, padding=3),\n            nn.ReLU(inplace=True),\n            nn.Conv2d(128, 64, 3, padding=1),\n            nn.ReLU(inplace=True))\n\n        self.weight = nn.Sequential(\n            nn.Conv2d(128, 128, 3, padding=1),\n            nn.ReLU(inplace=True),\n            nn.Conv2d(128, 2, 3, padding=1),\n            GradientClip(),\n            nn.Sigmoid())\n\n        self.delta = nn.Sequential(\n            nn.Conv2d(128, 128, 3, padding=1),\n            nn.ReLU(inplace=True),\n            nn.Conv2d(128, 2, 3, padding=1),\n            GradientClip())\n\n        self.gru = ConvGRU(128, 128+128+64)\n        self.agg = GraphAgg()\n\n    def forward(self, net, inp, corr, flow=None, ii=None, jj=None):\n        \"\"\" RaftSLAM update operator \"\"\"\n\n        batch, num, ch, ht, wd = net.shape\n\n        if flow is None:\n            flow = torch.zeros(batch, num, 4, ht, wd, device=net.device)\n\n        output_dim = (batch, num, -1, ht, wd)\n        net = net.view(batch*num, -1, ht, wd)\n        inp = inp.view(batch*num, -1, ht, wd)\n        corr = corr.view(batch*num, -1, ht, wd)\n        flow = flow.view(batch*num, -1, ht, wd)\n\n        corr = self.corr_encoder(corr)\n        flow = self.flow_encoder(flow)\n        net = self.gru(net, inp, corr, flow)\n\n        ### update variables ###\n        delta = self.delta(net).view(*output_dim)\n        weight = self.weight(net).view(*output_dim)\n\n        delta = delta.permute(0, 1, 3, 4, 2)[..., :2].contiguous()\n        weight = weight.permute(0, 1, 3, 4, 2)[..., :2].contiguous()\n\n        net = net.view(*output_dim)\n\n        if ii is not None:\n            eta, upmask = self.agg(net, ii.to(net.device))\n            return net, delta, weight, eta, upmask\n\n        else:\n            return net, delta, weight\n\n\nclass DynamicUpdateModule(nn.Module):\n    def __init__(self, use_aff_bri=False):\n        super(DynamicUpdateModule, self).__init__()\n        cor_planes = 4 * (2*3 + 1)**2\n        self.mask_num = 2\n\n        self.corr_encoder = nn.Sequential(\n            nn.Conv2d(cor_planes, 128, 1, padding=0),\n            nn.ReLU(inplace=True),\n            nn.Conv2d(128, 128, 3, padding=1),\n            nn.ReLU(inplace=True))\n\n        self.flow_encoder = nn.Sequential(\n            nn.Conv2d(4+self.mask_num+2, 128, 7, padding=3),\n            nn.ReLU(inplace=True),\n            nn.Conv2d(128, 64, 3, padding=1),\n            nn.ReLU(inplace=True))\n\n        self.weight = nn.Sequential(\n            nn.Conv2d(128, 128, 3, padding=1),\n            nn.ReLU(inplace=True),\n            nn.Conv2d(128, 2, 3, padding=1),\n            GradientClip(),\n        )\n\n        self.delta = nn.Sequential(\n            nn.Conv2d(128, 128, 3, padding=1),\n            nn.ReLU(inplace=True),\n            nn.Conv2d(128, 2, 3, padding=1),\n            GradientClip())\n\n        self.delta_dy = nn.Sequential(\n            nn.Conv2d(128, 128, 3, padding=1),\n            nn.ReLU(inplace=True),\n            nn.Conv2d(128, 2, 3, padding=1),\n            GradientClip())\n\n        # 动静mask: 1->static, 0->dynamic\n        # this is a delta mask\n        self.delta_mask = nn.Sequential(\n            nn.Conv2d(128, 128, 3, padding=1),\n            nn.ReLU(inplace=True),\n            nn.Conv2d(128, self.mask_num, 3, padding=1),\n            GradientClip(),\n        )\n\n        if use_aff_bri:\n            self.global_avg_pool = nn.Sequential(\n                nn.Conv2d(128, 128, 3, padding=1),\n                nn.ReLU(inplace=True),\n                nn.AdaptiveAvgPool2d((1, 1)),\n                GradientClip(),\n            )\n            self.param_linear = nn.Sequential(\n                nn.Linear(128, 2),\n                nn.Sigmoid()\n            )\n\n        self.gru = ConvGRU(128, 128+128+64)\n        self.agg = GraphAgg()\n\n    def do_filter(self, lay, weight, delta_dy, delta_m, segments):\n        \n        segments = lay * 1e4 + segments\n        encode = segments * 1e4 + ((delta_dy[...,0]  + delta_dy[...,1]) > 0.5).int()\n        ky, cnt = torch.unique(encode, return_counts=True)\n        cat = ky // 1e4\n        sig = ky % 1e4\n        cat0 = cat[sig==0].detach().cpu().numpy.tolist()\n        cat1 = cat[sig==1].detach().cpu().numpy.tolist()\n        cnt0 = cnt[sig==0]\n        cnt1 = cnt[sig==1]\n        ori_cls = torch.unique(cat) \n        for i in ori_cls:\n            if i not in cat0:\n                prob = 0\n            elif i not in cat1: \n                prob = 1\n            else:\n                n0 = cnt0[cat0.index(i)]\n                n1 = cnt1[cat1.index(i)]\n                prob = n0 / (n0 + n1)\n            if prob > 0.5:     \n                fil = segments[0, i//1e4,...] == i\n                lay[0, i//1e4 ,...] = lay[0, i//1e4 ,...] * (1-fil*1) \n        weight[...,0] = weight[...,0] * lay\n        weight[...,1] = weight[...,1] * lay\n\n        return weight\n    \n    def forward(self, net, inp, corr, flow=None,\n                ii=None, jj=None, use_aff_bri=False, raw_mask=None, segments=None):\n        \"\"\" RaftSLAM update operator \"\"\"\n\n        batch, num, ch, ht, wd = net.shape\n\n        if flow is None:\n            # add mask channel\n            flow = torch.zeros(batch, num, 4+self.mask_num+2,\n                               ht, wd, device=net.device)\n        if raw_mask is None:\n            raw_mask = torch.zeros(\n                batch, num, self.mask_num, ht, wd, device=net.device)\n\n        output_dim = (batch, num, -1, ht, wd) \n        net = net.view(batch*num, -1, ht, wd)               \n        inp = inp.view(batch*num, -1, ht, wd)\n        corr = corr.view(batch*num, -1, ht, wd)\n        flow = flow.view(batch*num, -1, ht, wd)\n        \n        corr = self.corr_encoder(corr)\n        flow = self.flow_encoder(flow)\n        net = self.gru(net, inp, corr, flow)\n\n        ### update variables ###\n        delta = self.delta(net).view(*output_dim)          \n        delta_dy = self.delta_dy(net).view(*output_dim)     \n        weight = self.weight(net).view(*output_dim)         \n        delta_m = self.delta_mask(net).view(*output_dim)    \n\n        if use_aff_bri:\n            tmp = self.global_avg_pool(net).view(batch*num, -1)\n            aff_params = self.param_linear(tmp).view(batch, num, -1)\n\n        delta = delta.permute(0, 1, 3, 4, 2).contiguous() \n        delta_dy = delta_dy.permute(0, 1, 3, 4, 2).contiguous() \n        weight = weight.permute(0, 1, 3, 4, 2).contiguous()\n        delta_m = delta_m.permute(0, 1, 3, 4, 2).contiguous()\n\n        lay = torch.as_tensor(np.range(1, num+1).repeat(ht*wd).reshape(num,ht,wd)).unsqueeze(0) \n        # weight = self.do_filter(lay, weight, delta_dy, delta_m, segments)\n        \n        net = net.view(*output_dim)\n        delta = torch.cat([delta, delta_dy], dim=-1)            \n\n        if ii is not None:\n            eta, upmask_disp, \\\n                upmask_flow, upmask_dymask = self.agg(net, ii.to(net.device))\n            upmask = {\n                'disp': upmask_disp,\n                'flow': upmask_flow,\n                'dy_mask': upmask_dymask,\n            }\n            if use_aff_bri:\n                return net, delta, weight, eta, upmask, delta_m, aff_params\n            else:\n                return net, delta, weight, eta, upmask, delta_m\n        else:\n            return net, delta, weight, delta_m\n\n\nclass DroidNet(nn.Module):\n    def __init__(self, use_aff_bri=False):\n        super(DroidNet, self).__init__()\n        self.fnet = BasicEncoder(output_dim=128, norm_fn='instance')\n        self.cnet = BasicEncoder(output_dim=256, norm_fn='none')\n        self.update = DynamicUpdateModule(use_aff_bri)\n        self.use_aff_bri = use_aff_bri\n\n    def extract_features(self, images):\n        \"\"\" run feeature extraction networks \"\"\"\n\n        # normalize images\n        images = images[:, :, [2, 1, 0]] / 255.0\n        mean = torch.as_tensor([0.485, 0.456, 0.406], device=images.device)\n        std = torch.as_tensor([0.229, 0.224, 0.225], device=images.device)\n        images = images.sub_(mean[:, None, None]).div_(std[:, None, None])\n\n        fmaps = self.fnet(images)\n        net = self.cnet(images)\n\n        net, inp = net.split([128, 128], dim=2)\n        net = torch.tanh(net)\n        inp = torch.relu(inp)\n        return fmaps, net, inp\n\n    def forward(self, Gs, images, disps, intrinsics, graph=None, num_steps=12,\n                fixedp=2, ret_flow=False, downsample=False, segments=None): \n        \"\"\" Estimates SE3 or Sim3 between pair of frames \"\"\"\n\n        u = keyframe_indicies(graph)\n        ii, jj, kk = graph_to_edge_list(graph)\n\n        ii = ii.to(device=images.device, dtype=torch.long)\n        jj = jj.to(device=images.device, dtype=torch.long)\n        dy_thresh = 0.5\n        mask_num = 2\n\n        fmaps, net, inp = self.extract_features(images) \n        segm_all = None\n        if segments != None:\n            segm_all = segments[:,ii]\n        net, inp = net[:, ii], inp[:, ii] \n      \n        corr_fn = CorrBlock(fmaps[:, ii], fmaps[:, jj], num_levels=4, radius=3)\n\n        ht, wd = images.shape[-2:] \n        coords0 = pops.coords_grid(ht//8, wd//8, device=images.device)\n\n        coords1, _ = pops.projective_transform(Gs, disps, intrinsics, ii, jj)\n        target_cam = coords1.clone()\n        delta_dy = torch.zeros_like(coords1)\n        raw_mask = torch.zeros_like(coords1)[..., 0:mask_num]\n\n        Gs_list, disp_list, residual_list = [], [], []\n        full_flow_list, mask_list = [], []\n        if self.use_aff_bri:\n            aff_params_list = []\n\n        for step in range(num_steps):\n            Gs = Gs.detach()\n            disps = disps.detach()\n            coords1 = coords1.detach()\n            target_cam = target_cam.detach()\n            delta_dy = delta_dy.detach()\n            raw_mask = raw_mask.detach()\n\n            corr = corr_fn(coords1)\n            resd = (target_cam - coords1)\n            cam_flow = coords1 - coords0\n            flow = cam_flow + delta_dy\n\n            motion = torch.cat([cam_flow, flow, resd, raw_mask], dim=-1)\n            motion = motion.permute(0, 1, 4, 2, 3).clamp(-64.0, 64.0)\n\n            if self.use_aff_bri:\n                net, delta, weight, eta, upmask, \\\n                    delta_m, aff_params = \\\n                    self.update(net, inp, corr, motion,\n                                ii, jj, self.use_aff_bri)\n            else:\n                net, delta, weight, eta, upmask, delta_m = \\\n                    self.update(net, inp, corr, motion, ii, jj)  \n\n            # (1:static 0:dynamic)\n            raw_mask = raw_mask + delta_m\n            mask = torch.sigmoid(raw_mask)\n            bin_mask = (mask >= dy_thresh).float() \n\n            target_cam = coords1 + delta[..., 0:2]\n            weight = torch.sigmoid(weight + (1-bin_mask)*10) \n\n            for i in range(2):\n                Gs, disps = BA(target_cam, weight, eta, Gs, disps,\n                               intrinsics, ii, jj, fixedp=2)\n           \n            coords1, valid_mask = pops.projective_transform(\n                Gs, disps, intrinsics, ii, jj)\n            residual = (target_cam - coords1) * valid_mask\n\n            delta_dy = delta[..., 2:4] * (1-bin_mask)\n            target_all = coords1 + delta_dy\n\n            Gs_list.append(Gs)\n            disp_list.append(upsample_dim_1(disps, upmask['disp']))\n            residual_list.append(residual)\n            mask_list.append(upsample_inter(mask))\n\n            if ret_flow: \n                if downsample: \n                    full_flow_list.append(target_all - coords0)\n                else:\n                    full_flow_list.append(\n                        upsample_inter((target_all - coords0)*8))\n\n            if self.use_aff_bri: \n                aff_params_list.append(aff_params)\n\n        if ret_flow: \n            if self.use_aff_bri: \n                return Gs_list, disp_list, residual_list, full_flow_list, mask_list, aff_params_list\n            else: \n                return Gs_list, disp_list, residual_list, full_flow_list, mask_list\n        else:\n            return Gs_list, disp_list, residual_list, mask_list\n"
  },
  {
    "path": "VO_Module/droid_slam/factor_graph.py",
    "content": "import torch\nimport lietorch\nimport numpy as np\n\nimport matplotlib.pyplot as plt\nimport torch.nn.functional as F\nfrom lietorch import SE3\nfrom modules.corr import CorrBlock, AltCorrBlock\nimport geom.projective_ops as pops\n\n\nclass FactorGraph:\n    def __init__(self, video, update_op, device=\"cuda:0\", corr_impl=\"volume\", max_factors=-1):\n        self.video = video\n        self.update_op = update_op\n        self.device = device\n        self.max_factors = max_factors\n        self.corr_impl = corr_impl\n\n        # operator at 1/8 resolution\n        self.ht = ht = video.ht // 8\n        self.wd = wd = video.wd // 8\n\n        self.dy_thresh = 0.5\n        self.mask_num = 2\n\n        self.coords0 = pops.coords_grid(ht, wd, device=device)\n        self.ii = torch.as_tensor([], dtype=torch.long, device=device)\n        self.jj = torch.as_tensor([], dtype=torch.long, device=device)\n        self.age = torch.as_tensor([], dtype=torch.long, device=device)\n\n        self.corr, self.net, self.inp = None, None, None\n        self.segm = None\n        self.damping = 1e-6 * torch.ones_like(self.video.disps)\n\n        self.target_cam = torch.zeros(\n            [1, 0, ht, wd, 2], device=device, dtype=torch.float)\n        self.weight = torch.zeros(\n            [1, 0, ht, wd, 2], device=device, dtype=torch.float)\n        self.raw_mask = torch.zeros(\n            [1, 0, ht, wd, self.mask_num], device=device, dtype=torch.float)\n        self.delta_dy = torch.zeros(\n            [1, 0, ht, wd, 2], device=device, dtype=torch.float)\n        self.full_flow = torch.zeros(\n            [1, 0, ht, wd, 2], device=device, dtype=torch.float)\n\n        # inactive factors\n        self.ii_inac = torch.as_tensor([], dtype=torch.long, device=device)\n        self.jj_inac = torch.as_tensor([], dtype=torch.long, device=device)\n        self.ii_bad = torch.as_tensor([], dtype=torch.long, device=device)\n        self.jj_bad = torch.as_tensor([], dtype=torch.long, device=device)\n\n        self.target_cam_inac = torch.zeros(\n            [1, 0, ht, wd, 2], device=device, dtype=torch.float)\n        self.weight_inac = torch.zeros(\n            [1, 0, ht, wd, 2], device=device, dtype=torch.float)\n        self.raw_mask_inac = torch.zeros(\n            [1, 0, ht, wd, self.mask_num], device=device, dtype=torch.float)\n        self.delta_dy_inac = torch.zeros(\n            [1, 0, ht, wd, 2], device=device, dtype=torch.float)\n        self.full_flow_inac = torch.zeros(\n            [1, 0, ht, wd, 2], device=device, dtype=torch.float)\n        \n\n    def __filter_repeated_edges(self, ii, jj):\n        \"\"\" remove duplicate edges \"\"\"\n\n        keep = torch.zeros(ii.shape[0], dtype=torch.bool, device=ii.device)\n        eset = set(\n            [(i.item(), j.item()) for i, j in zip(self.ii, self.jj)] +\n            [(i.item(), j.item()) for i, j in zip(self.ii_inac, self.jj_inac)])\n\n        for k, (i, j) in enumerate(zip(ii, jj)):\n            keep[k] = (i.item(), j.item()) not in eset\n\n        return ii[keep], jj[keep]\n\n    def print_edges(self):\n        ii = self.ii.cpu().numpy()\n        jj = self.jj.cpu().numpy()\n\n        ix = np.argsort(ii)\n        ii = ii[ix]\n        jj = jj[ix]\n\n        w = torch.mean(self.weight, dim=[0, 2, 3, 4]).cpu().numpy()\n        w = w[ix]\n        for e in zip(ii, jj, w):\n            print(e)\n        print()\n\n    def filter_edges(self):\n        \"\"\" remove bad edges \"\"\"\n        conf = torch.mean(self.weight, dim=[0, 2, 3, 4])\n        mask = (torch.abs(self.ii-self.jj) > 2) & (conf < 0.001)\n\n        self.ii_bad = torch.cat([self.ii_bad, self.ii[mask]])\n        self.jj_bad = torch.cat([self.jj_bad, self.jj[mask]])\n        self.rm_factors(mask, store=False)\n\n    def clear_edges(self):\n        self.rm_factors(self.ii >= 0)\n        self.net = None\n        self.inp = None\n\n    @torch.cuda.amp.autocast(enabled=True)\n    def add_factors(self, ii, jj, remove=False):\n        \"\"\" add edges to factor graph \"\"\"\n\n        if not isinstance(ii, torch.Tensor):\n            ii = torch.as_tensor(ii, dtype=torch.long, device=self.device)\n\n        if not isinstance(jj, torch.Tensor):\n            jj = torch.as_tensor(jj, dtype=torch.long, device=self.device)\n\n        # remove duplicate edges\n        ii, jj = self.__filter_repeated_edges(ii, jj)\n\n        if ii.shape[0] == 0:\n            return\n\n        # place limit on number of factors\n        if self.max_factors > 0 and self.ii.shape[0] + ii.shape[0] > self.max_factors \\\n                and self.corr is not None and remove:\n\n            ix = torch.arange(len(self.age))[torch.argsort(self.age).cpu()]\n            self.rm_factors(ix >= self.max_factors - ii.shape[0], store=True)\n\n        net = self.video.nets[ii].to(self.device).unsqueeze(0)\n\n        # correlation volume for new edges\n        if self.corr_impl == \"volume\":\n            fmap1 = self.video.fmaps[ii].to(self.device).unsqueeze(0)\n            fmap2 = self.video.fmaps[jj].to(self.device).unsqueeze(0)\n            corr = CorrBlock(fmap1, fmap2)\n            self.corr = corr if self.corr is None else self.corr.cat(corr)\n\n            inp = self.video.inps[ii].to(self.device).unsqueeze(0)\n            self.inp = inp if self.inp is None else torch.cat([self.inp, inp], 1)\n\n        with torch.cuda.amp.autocast(enabled=False):\n            target, _ = self.video.reproject(ii, jj)\n            weight = torch.zeros_like(target)\n            raw_mask = torch.zeros_like(target)[..., 0:self.mask_num]\n            delta_dy = torch.zeros_like(target)\n\n        self.ii = torch.cat([self.ii, ii], 0)\n        self.jj = torch.cat([self.jj, jj], 0)\n        self.age = torch.cat([self.age, torch.zeros_like(ii)], 0)\n\n        # reprojection factors\n        self.net = net if self.net is None else torch.cat([self.net, net], 1)\n\n        self.target_cam = torch.cat([self.target_cam, target], 1)\n        self.weight = torch.cat([self.weight, weight], 1)\n        self.raw_mask = torch.cat([self.raw_mask, raw_mask], 1)\n        self.delta_dy = torch.cat([self.delta_dy, delta_dy], 1)\n\n        # segmentations\n        segm = self.video.segms[ii].to(self.device).unsqueeze(0)\n        self.segm = segm if self.segm is None else torch.cat([self.segm, segm], 1)\n\n    @torch.cuda.amp.autocast(enabled=True)\n    def rm_factors(self, mask, store=False):\n        \"\"\" drop edges from factor graph \"\"\"\n\n        # store estimated factors\n        if store:\n            self.ii_inac = torch.cat([self.ii_inac, self.ii[mask]], 0)\n            self.jj_inac = torch.cat([self.jj_inac, self.jj[mask]], 0)\n            self.target_cam_inac = torch.cat(\n                [self.target_cam_inac, self.target_cam[:, mask]], 1)\n            self.weight_inac = torch.cat(\n                [self.weight_inac, self.weight[:, mask]], 1)\n            self.raw_mask_inac = torch.cat(\n                [self.raw_mask_inac, self.raw_mask[:, mask]], 1)\n            self.delta_dy_inac = torch.cat(\n                [self.delta_dy_inac, self.delta_dy[:, mask]], 1)\n\n        self.ii = self.ii[~mask]\n        self.jj = self.jj[~mask]\n        self.age = self.age[~mask]\n\n        if self.corr_impl == \"volume\":\n            self.corr = self.corr[~mask]\n\n        if self.net is not None:\n            self.net = self.net[:, ~mask]\n\n        if self.inp is not None:\n            self.inp = self.inp[:, ~mask]\n        \n        if self.segm is not None:\n            self.segm = self.segm[:, ~mask]\n\n        self.target_cam = self.target_cam[:, ~mask]\n        self.weight = self.weight[:, ~mask]\n        self.raw_mask = self.raw_mask[:, ~mask]\n        self.delta_dy = self.delta_dy[:, ~mask]\n\n    @torch.cuda.amp.autocast(enabled=True)\n    def rm_keyframe(self, ix):\n        \"\"\" drop edges from factor graph \"\"\"\n\n        with self.video.get_lock():\n            self.video.poses[ix] = self.video.poses[ix+1]\n            self.video.disps[ix] = self.video.disps[ix+1]\n            self.video.intrinsics[ix] = self.video.intrinsics[ix+1]\n\n            self.video.nets[ix] = self.video.nets[ix+1]\n            self.video.inps[ix] = self.video.inps[ix+1]\n            self.video.fmaps[ix] = self.video.fmaps[ix+1]\n            if self.video.segm_filter:\n                self.video.segms[ix] = self.video.segms[ix+1]\n            \n\n        m = (self.ii == ix) | (self.jj == ix)\n\n        self.ii[self.ii >= ix] -= 1\n        self.jj[self.jj >= ix] -= 1\n\n        self.ii_inac[self.ii_inac >= ix] -= 1\n        self.jj_inac[self.jj_inac >= ix] -= 1\n\n        self.rm_factors(m, store=False)\n\n    @torch.cuda.amp.autocast(enabled=True)\n    def update(self, t0=None, t1=None, itrs=2, use_inactive=False, EP=1e-7, motion_only=False):\n        \"\"\" run update operator on factor graph \"\"\"\n\n        # motion features\n        with torch.cuda.amp.autocast(enabled=False):\n            coords1, mask = self.video.reproject(self.ii, self.jj)\n            motn = torch.cat(\n                [self.target_cam - self.coords0, self.target_cam - self.coords0 + self.delta_dy,\n                 self.target_cam - coords1, self.raw_mask*torch.ones_like(coords1)[..., 0:self.mask_num]], dim=-1)\n            motn = motn.permute(0, 1, 4, 2, 3).clamp(-64.0, 64.0)\n\n        # correlation features\n        corr = self.corr(coords1)\n\n        self.net, delta, weight, damping, upmask, delta_m = \\\n            self.update_op(self.net, self.inp, corr,\n                           motn, self.ii, self.jj, False)\n\n        if t0 is None:\n            t0 = max(1, self.ii.min().item()+1)\n\n        with torch.cuda.amp.autocast(enabled=False):\n            self.target_cam = coords1 + delta[..., 0:2].to(dtype=torch.float)\n            self.weight = weight.to(dtype=torch.float) \n            self.raw_mask = self.raw_mask + delta_m\n            bin_mask = ( torch.sigmoid(self.raw_mask) >= self.dy_thresh) \n            \n            # filter with segm\n            if self.video.segm_filter:\n                ht = weight.shape[2] \n                wd = weight.shape[3]\n                lay = np.arange(1, weight.shape[1]+1).repeat(ht*wd).reshape(1,-1,ht,wd) \n                segments = (lay * 1e6 + self.segm.squeeze(2).detach().cpu().numpy()).astype(np.int32) \n                dynamic_m = ( (bin_mask[...,0] == 0).__or__(bin_mask[...,1] == 0) ).detach().cpu().numpy() \n                ori_ky, ori_cnt = np.unique(segments, return_counts=True)\n                ori_dic = dict(zip(ori_ky, ori_cnt))\n\n                dy_fields = segments * dynamic_m\n                dy_ky, dy_cnt = np.unique(dy_fields, return_counts=True)\n                for (label, dy_n) in zip(dy_ky, dy_cnt):\n                    if label % 1e6 == 0:\n                        continue\n                    if (dy_n / ori_dic[label]) > self.video.thresh: # 0.8\n                        dim = int(label // 1e6) -1\n                        fil = segments[0,dim,...] == label\n                        lay[0,dim,...] =  lay[0,dim,...] * (1-fil*1)\n                lay = torch.as_tensor(lay).to(self.device)\n                bin_mask[...,0] = bin_mask[...,0] * (lay > 0)\n                bin_mask[...,1] = bin_mask[...,1] * (lay > 0)\n            \n            bin_mask = bin_mask.float()\n            self.delta_dy = delta[..., 2:4] * (1-bin_mask)\n            self.weight = torch.sigmoid(self.weight + (1-bin_mask)*10)\n\n            ht, wd = self.coords0.shape[0:2]\n            self.damping[torch.unique(self.ii)] = damping\n\n            if use_inactive:\n                m = (self.ii_inac >= t0 - 3) & (self.jj_inac >= t0 - 3)\n                ii = torch.cat([self.ii_inac[m], self.ii], 0)\n                jj = torch.cat([self.jj_inac[m], self.jj], 0)\n                target_cam = torch.cat(\n                    [self.target_cam_inac[:, m], self.target_cam], 1)\n                weight = torch.cat([self.weight_inac[:, m], self.weight], 1)\n            else:\n                ii, jj, target_cam, weight = self.ii, self.jj, self.target_cam, self.weight\n\n            damping = .2 * self.damping[torch.unique(ii)].contiguous() + EP\n\n            target_cam = target_cam.view(-1, ht, wd, 2).permute(0,\n                                                                3, 1, 2).contiguous()\n            weight = weight.view(-1, ht, wd, 2).permute(0,\n                                                        3, 1, 2).contiguous()\n            # dense bundle adjustment\n            self.video.ba(target_cam, weight, damping, ii, jj, t0, t1,\n                          itrs=itrs, lm=1e-4, ep=0.1, motion_only=motion_only)\n            target_all = coords1 + self.delta_dy  \n            self.full_flow = target_all - self.coords0\n\n        self.age += 1\n\n    @torch.cuda.amp.autocast(enabled=False)\n    def update_lowmem(self, t0=None, t1=None, itrs=2, use_inactive=False, EP=1e-7, steps=8):\n        \"\"\" run update operator on factor graph - reduced memory implementation \"\"\"\n\n        # alternate corr implementation\n        t = self.video.counter.value\n        corr_op = AltCorrBlock(self.video.fmaps[None, :t])\n\n        for step in range(steps):\n            print(\"Global BA Iteration #{}\".format(step+1))\n            with torch.cuda.amp.autocast(enabled=False):\n                coords1, mask = self.video.reproject(self.ii, self.jj)\n                motn = torch.cat(\n                    [self.target_cam - self.coords0, self.target_cam - self.coords0 + self.delta_dy,\n                     self.target_cam - coords1, self.raw_mask*torch.ones_like(coords1)[..., 0:self.mask_num]], dim=-1)\n                motn = motn.permute(0, 1, 4, 2, 3).clamp(-64.0, 64.0)\n\n            s = 8\n            for i in range(0, self.jj.max()+1, s):\n                v = (self.ii >= i) & (self.ii < i + s)\n                iis = self.ii[v]\n                jjs = self.jj[v]\n\n                ht, wd = self.coords0.shape[0:2]\n                corr1 = corr_op(coords1[:, v], iis, jjs)\n\n                with torch.cuda.amp.autocast(enabled=True):\n                    net, delta, weight, damping, _, delta_m = self.update_op(\n                        self.net[:, v], self.video.inps[None, iis], corr1, motn[:, v], iis, jjs, False)\n\n                self.net[:, v] = net\n                self.target_cam[:, v] = coords1[:, v] + delta[..., 0:2].float()\n                self.weight[:, v] = weight.float()\n                self.damping[torch.unique(iis)] = damping\n                self.raw_mask[:, v] = self.raw_mask[:, v] + delta_m.float()\n                bin_mask = (torch.sigmoid(\n                    self.raw_mask[:, v]) >= self.dy_thresh).float()\n\n                self.delta_dy[:, v] = delta[..., 2:4] * (1-bin_mask)\n                self.weight[:, v] = torch.sigmoid(\n                    self.weight[:, v] + (1-bin_mask)*10)\n\n            damping = self.damping[torch.unique(self.ii)].contiguous() + EP\n            target_cam = self.target_cam.view(-1, ht, wd,\n                                              2).permute(0, 3, 1, 2).contiguous()\n            weight = self.weight.view(-1, ht, wd,\n                                      2).permute(0, 3, 1, 2).contiguous()\n            # dense bundle adjustment\n            self.video.ba(target_cam, weight, damping, self.ii, self.jj, 1, t,\n                          itrs=itrs, lm=1e-5, ep=1e-2, motion_only=False)\n\n            self.video.dirty[:t] = True\n\n    def add_neighborhood_factors(self, t0, t1, r=3):\n        \"\"\" add edges between neighboring frames within radius r \"\"\"\n\n        ii, jj = torch.meshgrid(torch.arange(t0, t1), torch.arange(t0, t1))\n        ii = ii.reshape(-1).to(dtype=torch.long, device=self.device)\n        jj = jj.reshape(-1).to(dtype=torch.long, device=self.device)\n\n        keep = ((ii - jj).abs() > 0) & ((ii - jj).abs() <= r)\n        self.add_factors(ii[keep], jj[keep])\n\n    def add_proximity_factors(self, t0=0, t1=0, rad=2, nms=2, beta=0.25, thresh=16.0, remove=False):\n        \"\"\" add edges to the factor graph based on distance \"\"\"\n\n        t = self.video.counter.value\n        ix = torch.arange(t0, t)\n        jx = torch.arange(t1, t)\n\n        ii, jj = torch.meshgrid(ix, jx)\n        ii = ii.reshape(-1)\n        jj = jj.reshape(-1)\n\n        d = self.video.distance(ii, jj, beta=beta)\n        d[ii - rad < jj] = np.inf\n        d[d > 100] = np.inf\n\n        ii1 = torch.cat([self.ii, self.ii_bad, self.ii_inac], 0)\n        jj1 = torch.cat([self.jj, self.jj_bad, self.jj_inac], 0)\n        for i, j in zip(ii1.cpu().numpy(), jj1.cpu().numpy()):\n            if abs(i - j) <= 2:\n                continue\n            for di in range(-nms, nms+1):\n                for dj in range(-nms, nms+1):\n                    if abs(di) + abs(dj) <= max(min(abs(i-j)-2, nms), 0):\n                        i1 = i + di\n                        j1 = j + dj\n\n                        if (t0 <= i1 < t) and (t1 <= j1 < t):\n                            d[(i1-t0)*(t-t1) + (j1-t1)] = np.inf\n\n        es = []\n        for i in range(t0, t):\n            for j in range(i+1, min(i+rad+1, t)):\n                es.append((i, j))\n                es.append((j, i))\n\n        ix = torch.argsort(d)\n        for k in ix:\n            if d[k].item() > thresh:\n                continue\n\n            i = ii[k]\n            j = jj[k]\n\n            # bidirectional\n            es.append((i, j))\n            es.append((j, i))\n\n            for di in range(-nms, nms+1):\n                for dj in range(-nms, nms+1):\n                    if abs(di) + abs(dj) <= max(min(abs(i-j)-2, nms), 0):\n                        i1 = i + di\n                        j1 = j + dj\n\n                        if (t0 <= i1 < t) and (t1 <= j1 < t):\n                            d[(i1-t0)*(t-t1) + (j1-t1)] = np.inf\n\n        ii, jj = torch.as_tensor(es, device=self.device).unbind(dim=-1)\n        self.add_factors(ii, jj, remove)\n\ndef upsample_inter(mask):\n    batch, num, ht, wd, dim = mask.shape\n    mask = mask.permute(0, 1, 4, 2, 3).contiguous()\n    mask = mask.view(batch*num, dim, ht, wd)\n    mask = F.interpolate(mask, scale_factor=8, mode='bilinear',\n                         align_corners=True, recompute_scale_factor=True)\n    mask = mask.permute(0, 2, 3, 1).contiguous()\n    return mask.view(batch, num, 8*ht, 8*wd, dim)\n"
  },
  {
    "path": "VO_Module/droid_slam/geom/__init__.py",
    "content": ""
  },
  {
    "path": "VO_Module/droid_slam/geom/ba.py",
    "content": "import lietorch\nimport torch\nimport torch.nn.functional as F\n\nfrom .chol import block_solve, schur_solve\nimport geom.projective_ops as pops\n\nfrom torch_scatter import scatter_sum\n\n\n# utility functions for scattering ops\ndef safe_scatter_add_mat(A, ii, jj, n, m):\n    v = (ii >= 0) & (jj >= 0) & (ii < n) & (jj < m)\n    return scatter_sum(A[:,v], ii[v]*m + jj[v], dim=1, dim_size=n*m)\n\ndef safe_scatter_add_vec(b, ii, n):\n    v = (ii >= 0) & (ii < n)\n    return scatter_sum(b[:,v], ii[v], dim=1, dim_size=n)\n\n# apply retraction operator to inv-depth maps\ndef disp_retr(disps, dz, ii):\n    ii = ii.to(device=dz.device)\n    return disps + scatter_sum(dz, ii, dim=1, dim_size=disps.shape[1])\n\n# apply retraction operator to poses\ndef pose_retr(poses, dx, ii):\n    ii = ii.to(device=dx.device)\n    return poses.retr(scatter_sum(dx, ii, dim=1, dim_size=poses.shape[1]))\n\n\ndef BA(target, weight, eta, poses, disps, intrinsics, ii, jj, fixedp=1, rig=1):\n    \"\"\" Full Bundle Adjustment \"\"\"\n\n    B, P, ht, wd = disps.shape\n    N = ii.shape[0]\n    D = poses.manifold_dim\n\n    ### 1: commpute jacobians and residuals ###\n    coords, valid, (Ji, Jj, Jz) = pops.projective_transform(\n        poses, disps, intrinsics, ii, jj, jacobian=True)\n\n    r = (target - coords).view(B, N, -1, 1)\n    w = .001 * (valid * weight).view(B, N, -1, 1)\n\n    ### 2: construct linear system ###\n    Ji = Ji.reshape(B, N, -1, D)\n    Jj = Jj.reshape(B, N, -1, D)\n    wJiT = (w * Ji).transpose(2,3)\n    wJjT = (w * Jj).transpose(2,3)\n\n    Jz = Jz.reshape(B, N, ht*wd, -1)\n\n    Hii = torch.matmul(wJiT, Ji)\n    Hij = torch.matmul(wJiT, Jj)\n    Hji = torch.matmul(wJjT, Ji)\n    Hjj = torch.matmul(wJjT, Jj)\n\n    vi = torch.matmul(wJiT, r).squeeze(-1)\n    vj = torch.matmul(wJjT, r).squeeze(-1)\n\n    Ei = (wJiT.view(B,N,D,ht*wd,-1) * Jz[:,:,None]).sum(dim=-1)\n    Ej = (wJjT.view(B,N,D,ht*wd,-1) * Jz[:,:,None]).sum(dim=-1)\n\n    w = w.view(B, N, ht*wd, -1)\n    r = r.view(B, N, ht*wd, -1)\n    wk = torch.sum(w*r*Jz, dim=-1)\n    Ck = torch.sum(w*Jz*Jz, dim=-1)\n\n    kx, kk = torch.unique(ii, return_inverse=True)\n    M = kx.shape[0]\n\n    # only optimize keyframe poses\n    P = P // rig - fixedp\n    ii = ii // rig - fixedp\n    jj = jj // rig - fixedp\n\n    H = safe_scatter_add_mat(Hii, ii, ii, P, P) + \\\n        safe_scatter_add_mat(Hij, ii, jj, P, P) + \\\n        safe_scatter_add_mat(Hji, jj, ii, P, P) + \\\n        safe_scatter_add_mat(Hjj, jj, jj, P, P)\n\n    E = safe_scatter_add_mat(Ei, ii, kk, P, M) + \\\n        safe_scatter_add_mat(Ej, jj, kk, P, M)\n\n    v = safe_scatter_add_vec(vi, ii, P) + \\\n        safe_scatter_add_vec(vj, jj, P)\n\n    C = safe_scatter_add_vec(Ck, kk, M)\n    w = safe_scatter_add_vec(wk, kk, M)\n\n    C = C + eta.view(*C.shape) + 1e-7\n\n    H = H.view(B, P, P, D, D)\n    E = E.view(B, P, M, D, ht*wd)\n\n    ### 3: solve the system ###\n    dx, dz = schur_solve(H, E, C, v, w)\n    \n    ### 4: apply retraction ###\n    poses = pose_retr(poses, dx, torch.arange(P) + fixedp)\n    disps = disp_retr(disps, dz.view(B,-1,ht,wd), kx)\n\n    disps = torch.where(disps > 10, torch.zeros_like(disps), disps)\n    disps = disps.clamp(min=0.0)\n\n    return poses, disps\n\n\ndef MoBA(target, weight, eta, poses, disps, intrinsics, ii, jj, fixedp=1, rig=1):\n    \"\"\" Motion only bundle adjustment \"\"\"\n\n    B, P, ht, wd = disps.shape\n    N = ii.shape[0]\n    D = poses.manifold_dim\n\n    ### 1: commpute jacobians and residuals ###\n    coords, valid, (Ji, Jj, Jz) = pops.projective_transform(\n        poses, disps, intrinsics, ii, jj, jacobian=True)\n\n    r = (target - coords).view(B, N, -1, 1)\n    w = .001 * (valid * weight).view(B, N, -1, 1)\n\n    ### 2: construct linear system ###\n    Ji = Ji.reshape(B, N, -1, D)\n    Jj = Jj.reshape(B, N, -1, D)\n    wJiT = (w * Ji).transpose(2,3)\n    wJjT = (w * Jj).transpose(2,3)\n\n    Hii = torch.matmul(wJiT, Ji)\n    Hij = torch.matmul(wJiT, Jj)\n    Hji = torch.matmul(wJjT, Ji)\n    Hjj = torch.matmul(wJjT, Jj)\n\n    vi = torch.matmul(wJiT, r).squeeze(-1)\n    vj = torch.matmul(wJjT, r).squeeze(-1)\n\n    # only optimize keyframe poses\n    P = P // rig - fixedp\n    ii = ii // rig - fixedp\n    jj = jj // rig - fixedp\n\n    H = safe_scatter_add_mat(Hii, ii, ii, P, P) + \\\n        safe_scatter_add_mat(Hij, ii, jj, P, P) + \\\n        safe_scatter_add_mat(Hji, jj, ii, P, P) + \\\n        safe_scatter_add_mat(Hjj, jj, jj, P, P)\n\n    v = safe_scatter_add_vec(vi, ii, P) + \\\n        safe_scatter_add_vec(vj, jj, P)\n    \n    H = H.view(B, P, P, D, D)\n\n    ### 3: solve the system ###\n    dx = block_solve(H, v)\n\n    ### 4: apply retraction ###\n    poses = pose_retr(poses, dx, torch.arange(P) + fixedp)\n    return poses\n\n"
  },
  {
    "path": "VO_Module/droid_slam/geom/chol.py",
    "content": "import torch\nimport torch.nn.functional as F\nimport geom.projective_ops as pops\n\nclass CholeskySolver(torch.autograd.Function):\n    @staticmethod\n    def forward(ctx, H, b):\n        # don't crash training if cholesky decomp fails\n        try:\n            U = torch.linalg.cholesky(H)\n            xs = torch.cholesky_solve(b, U)\n            ctx.save_for_backward(U, xs)\n            ctx.failed = False\n        except Exception as e:\n            print(e)\n            ctx.failed = True\n            xs = torch.zeros_like(b)\n\n        return xs\n\n    @staticmethod\n    def backward(ctx, grad_x):\n        if ctx.failed:\n            return None, None\n\n        U, xs = ctx.saved_tensors\n        dz = torch.cholesky_solve(grad_x, U)\n        dH = -torch.matmul(xs, dz.transpose(-1,-2))\n\n        return dH, dz\n\ndef block_solve(H, b, ep=0.1, lm=0.0001):\n    \"\"\" solve normal equations \"\"\"\n    B, N, _, D, _ = H.shape\n    I = torch.eye(D).to(H.device)\n    H = H + (ep + lm*H) * I\n\n    H = H.permute(0,1,3,2,4)\n    H = H.reshape(B, N*D, N*D)\n    b = b.reshape(B, N*D, 1)\n\n    x = CholeskySolver.apply(H,b)\n    return x.reshape(B, N, D)\n\n\ndef schur_solve(H, E, C, v, w, ep=0.1, lm=0.0001, sless=False):\n    \"\"\" solve using shur complement \"\"\"\n    \n    B, P, M, D, HW = E.shape\n    H = H.permute(0,1,3,2,4).reshape(B, P*D, P*D)\n    E = E.permute(0,1,3,2,4).reshape(B, P*D, M*HW)\n    Q = (1.0 / C).view(B, M*HW, 1)\n\n    # damping\n    I = torch.eye(P*D).to(H.device)\n    H = H + (ep + lm*H) * I\n    \n    v = v.reshape(B, P*D, 1)\n    w = w.reshape(B, M*HW, 1)\n\n    Et = E.transpose(1,2)\n    S = H - torch.matmul(E, Q*Et)\n    v = v - torch.matmul(E, Q*w)\n\n    dx = CholeskySolver.apply(S, v)\n    if sless:\n        return dx.reshape(B, P, D)\n\n    dz = Q * (w - Et @ dx)    \n    dx = dx.reshape(B, P, D)\n    dz = dz.reshape(B, M, HW)\n\n    return dx, dz"
  },
  {
    "path": "VO_Module/droid_slam/geom/graph_utils.py",
    "content": "\nimport torch\nimport numpy as np\nfrom collections import OrderedDict\n\nimport lietorch\nfrom data_readers.rgbd_utils import compute_distance_matrix_flow, compute_distance_matrix_flow2\n\n\ndef graph_to_edge_list(graph):\n    ii, jj, kk = [], [], []\n    for s, u in enumerate(graph):\n        for v in graph[u]:\n            ii.append(u)\n            jj.append(v)\n            kk.append(s)\n\n    ii = torch.as_tensor(ii)\n    jj = torch.as_tensor(jj)\n    kk = torch.as_tensor(kk)\n    return ii, jj, kk\n\ndef keyframe_indicies(graph):\n    return torch.as_tensor([u for u in graph])\n\ndef meshgrid(m, n, device='cuda'):\n    ii, jj = torch.meshgrid(torch.arange(m), torch.arange(n))\n    return ii.reshape(-1).to(device), jj.reshape(-1).to(device)\n\ndef neighbourhood_graph(n, r):\n    ii, jj = meshgrid(n, n)\n    d = (ii - jj).abs()\n    keep = (d >= 1) & (d <= r)\n    return ii[keep], jj[keep]\n\n\ndef build_frame_graph(poses, disps, intrinsics, num=16, thresh=24.0, r=2, need_inv=True):\n    \"\"\" construct a frame graph between co-visible frames \"\"\"\n    N = poses.shape[1]\n    poses = poses[0].cpu().numpy()\n    disps = disps[0][:,3::8,3::8].cpu().numpy()\n    intrinsics = intrinsics[0].cpu().numpy() / 8.0\n    d = compute_distance_matrix_flow(poses, disps, intrinsics, need_inv)\n\n    count = 0\n    graph = OrderedDict()\n    \n    for i in range(N):\n        graph[i] = []\n        d[i,i] = np.inf\n        for j in range(i-r, i+r+1):\n            if 0 <= j < N and i != j:\n                graph[i].append(j)\n                d[i,j] = np.inf\n                count += 1\n\n    while count < num:\n        ix = np.argmin(d)\n        i, j = ix // N, ix % N\n\n        if d[i,j] < thresh:\n            graph[i].append(j)\n            d[i,j] = np.inf\n            count += 1\n        else:\n            break\n    \n    return graph\n\n\n\ndef build_frame_graph_v2(poses, disps, intrinsics, num=16, thresh=24.0, r=2):\n    \"\"\" construct a frame graph between co-visible frames \"\"\"\n    N = poses.shape[1]\n    # poses = poses[0].cpu().numpy()\n    # disps = disps[0].cpu().numpy()\n    # intrinsics = intrinsics[0].cpu().numpy()\n    d = compute_distance_matrix_flow2(poses, disps, intrinsics)\n\n    # import matplotlib.pyplot as plt\n    # plt.imshow(d)\n    # plt.show()\n\n    count = 0\n    graph = OrderedDict()\n    \n    for i in range(N):\n        graph[i] = []\n        d[i,i] = np.inf\n        for j in range(i-r, i+r+1):\n            if 0 <= j < N and i != j:\n                graph[i].append(j)\n                d[i,j] = np.inf\n                count += 1\n\n    while 1:\n        ix = np.argmin(d)\n        i, j = ix // N, ix % N\n\n        if d[i,j] < thresh:\n            graph[i].append(j)\n\n            for i1 in range(i-1, i+2):\n                for j1 in range(j-1, j+2):\n                    if 0 <= i1 < N and 0 <= j1 < N:\n                        d[i1, j1] = np.inf\n\n            count += 1\n        else:\n            break\n    \n    return graph\n\n"
  },
  {
    "path": "VO_Module/droid_slam/geom/losses.py",
    "content": "from collections import OrderedDict\nimport numpy as np\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom lietorch import SO3, SE3, Sim3\nfrom .graph_utils import graph_to_edge_list\nfrom .projective_ops import projective_transform, coords_valid, coords_grid, projective_transform_unsup\n\n\ndef pose_metrics(dE):\n    \"\"\" Translation/Rotation/Scaling metrics from Sim3 \"\"\"\n    t, q, s = dE.data.split([3, 4, 1], -1)\n    ang = SO3(q).log().norm(dim=-1)\n\n    # convert radians to degrees\n    r_err = (180 / np.pi) * ang\n    t_err = t.norm(dim=-1)\n    s_err = (s - 1.0).abs()\n    return r_err, t_err, s_err\n\n\ndef fit_scale(Ps, Gs):\n    b = Ps.shape[0]\n    t1 = Ps.data[..., :3].detach().reshape(b, -1)\n    t2 = Gs.data[..., :3].detach().reshape(b, -1)\n\n    s = (t1*t2).sum(-1) / ((t2*t2).sum(-1) + 1e-8)\n    return s\n\n\ndef geodesic_loss(Ps, Gs, graph, gamma=0.9, do_scale=True):\n    \"\"\" Loss function for training network \"\"\"\n\n    # relative pose\n    ii, jj, kk = graph_to_edge_list(graph)\n    dP = Ps[:, jj] * Ps[:, ii].inv()\n\n    n = len(Gs)\n    geodesic_loss = 0.0\n\n    for i in range(n):\n        w = gamma ** (n - i - 1)\n        dG = Gs[i][:, jj] * Gs[i][:, ii].inv()\n\n        if do_scale:\n            s = fit_scale(dP, dG)\n            dG = dG.scale(s[:, None])\n\n        # pose error\n        d = (dG * dP.inv()).log()\n\n        if isinstance(dG, SE3):\n            tau, phi = d.split([3, 3], dim=-1)\n            geodesic_loss += w * (\n                tau.norm(dim=-1).mean() +\n                phi.norm(dim=-1).mean())\n\n        elif isinstance(dG, Sim3):\n            tau, phi, sig = d.split([3, 3, 1], dim=-1)\n            geodesic_loss += w * (\n                tau.norm(dim=-1).mean() +\n                phi.norm(dim=-1).mean() +\n                0.05 * sig.norm(dim=-1).mean())\n\n        dE = Sim3(dG * dP.inv()).detach()\n        r_err, t_err, s_err = pose_metrics(dE)\n\n    metrics = {\n        'rot_error': r_err.mean().item(),\n        'tr_error': t_err.mean().item(),\n        'bad_rot': (r_err < .1).float().mean().item(),\n        'bad_tr': (t_err < .01).float().mean().item(),\n    }\n\n    return geodesic_loss, metrics\n\n\ndef residual_loss(residuals, gamma=0.9):\n    \"\"\" loss on system residuals \"\"\"\n    residual_loss = 0.0\n    n = len(residuals)\n\n    for i in range(n):\n        w = gamma ** (n - i - 1)\n        residual_loss += w * residuals[i].abs().mean()\n\n    return residual_loss, {'residual': residual_loss.item()}\n\n\ndef cam_flow_loss(Ps, disps, poses_est, disps_est, intrinsics, graph, gamma=0.9):\n    \"\"\" optical flow loss \"\"\"\n\n    N = Ps.shape[1]\n    graph = OrderedDict()\n    for i in range(N):\n        graph[i] = [j for j in range(N) if abs(i-j) == 1]\n\n    ii, jj, kk = graph_to_edge_list(graph)\n    coords0, val0 = projective_transform(Ps, disps, intrinsics, ii, jj)\n    val0 = val0 * (disps[:, ii] > 0).float().unsqueeze(dim=-1)\n\n    n = len(poses_est)\n    cam_flow_loss = 0.0\n\n    for i in range(n):\n        w = gamma ** (n - i - 1)\n        coords1, val1 = projective_transform(\n            poses_est[i], disps_est[i], intrinsics, ii, jj)\n\n        v = (val0 * val1).squeeze(dim=-1)\n        epe = v * (coords1 - coords0).norm(dim=-1)\n        cam_flow_loss += w * epe.mean()\n\n    epe = epe.reshape(-1)[v.reshape(-1) > 0.5]\n    metrics = {\n        'f_error': epe.mean().item(),\n        '1px': (epe < 1.0).float().mean().item(),\n    }\n\n    return cam_flow_loss, metrics\n\n\ndef flow_loss(fo_flows, ba_flows, full_flows, graph, gamma=0.9):\n    \"\"\"flow loss\"\"\"\n\n    fo_vals = fo_flows[..., 2]\n    ba_vals = ba_flows[..., 2]\n\n    n = len(full_flows)\n    flow_loss = 0\n\n    for i in range(n):\n        w = gamma ** (n - i - 1)\n\n        fo_e = ((full_flows[i][:, 0::2, ...] -\n                fo_flows[..., 0:2]).norm(dim=-1) * fo_vals).mean()\n        ba_e = ((full_flows[i][:, 1::2, ...] -\n                ba_flows[..., 0:2]).norm(dim=-1) * ba_vals).mean()\n\n        f_e = (fo_e + ba_e) / 2\n        flow_loss += w * f_e\n\n    metrics = {\n        'pure_f_error': f_e.item()\n    }\n\n    return flow_loss, metrics\n\n\ndef photo_loss(images, full_flows, vals, graph, mode, gamma=0.9, ssim=None,\n               mean_mask=False, aff_params=None, downsample=False):\n    \"\"\"direct photometric loss\"\"\"\n\n    N, C, L = images.shape[1], images.shape[2], full_flows[0].shape[1]\n    ii, jj, kk = graph_to_edge_list(graph)\n\n    if downsample:\n        images = images[..., 3::8, 3::8]\n    ht, wd = images.shape[-2:]\n\n    if mode != 'unsup':\n        vals = vals[..., 3::8, 3::8, :]\n        # vals = torch.ones_like(images)[:, :, 0, ..., None]\n        vals_all = vals[:, ii].view(-1, ht, wd)\n\n    images0 = images[:, ii].reshape(-1, C, ht, wd) / 255.0\n    images1 = images[:, jj].reshape(-1, C, ht, wd) / 255.0\n    coords0 = coords_grid(ht, wd, device=images.device)\n\n    n = len(full_flows)\n    ph_loss = 0.0\n\n    for i in range(n):\n        w = gamma ** (n - i - 1)\n\n        coords_flow = coords0 + full_flows[i]\n\n        grid_x = coords_flow[..., 0]/(wd-1)\n        grid_y = coords_flow[..., 1]/(ht-1)\n        grid = torch.stack([grid_x, grid_y], dim=-1).view(-1, ht, wd, 2)\n        grid = grid * 2 - 1\n\n        # valid\n        if mode == 'unsup':\n            vals_all = vals[i].cuda().view(-1, ht, wd)\n        val_pix = (grid.abs().max(-1)[0] <= 1).float() * vals_all\n        # val_pix = (grid.abs().max(-1)[0] <= 1).float()\n\n        warped_image0 = F.grid_sample(\n            images1, grid, padding_mode=\"border\", align_corners=True)\n        # warped_image0 = F.grid_sample(\n        #     images1, grid, padding_mode=\"zeros\", align_corners=False)\n        if aff_params is not None:\n            aff_a = aff_params[i][..., 0].view(-1, 1, 1, 1)\n            aff_b = (aff_params[i][..., 1] - 0.5).view(-1, 1, 1, 1)\n            warped_image0 = warped_image0*aff_a + aff_b\n\n        diff = compute_reprojection_loss(images0, warped_image0, ssim)\n        if mean_mask:\n            p_e = mean_on_mask(diff, val_pix)\n        else:\n            p_e = (diff*val_pix).mean()\n        ph_loss += w * p_e\n\n    metrics = {\n        'ph_error': p_e.item(),\n        '0.01color': mean_on_mask((diff < 0.01).float(), val_pix).item(),\n    }\n\n    return ph_loss, metrics\n\n\ndef photo_loss_cam(images, poses_est, disps_est, intrinsics,\n                   graph, mode, masks, gamma=0.9, ssim=None):\n    \"\"\"supervise cam flow in ph_loss\"\"\"\n\n    N, C = images.shape[1], images.shape[2]\n    ht, wd = images.shape[-2:]\n\n    graph = OrderedDict()\n    for i in range(N):\n        graph[i] = [j for j in range(N) if abs(i-j) == 1]\n    ii, jj, kk = graph_to_edge_list(graph)\n\n    images0 = images[:, ii].reshape(-1, C, ht, wd)/255.0\n    images1 = images[:, jj].reshape(-1, C, ht, wd)/255.0\n\n    if mode != \"unsup\":\n        masks_all = masks[:, ii].view(-1, ht, wd)\n\n    n = len(poses_est)\n    ph_loss = 0\n\n    for i in range(n):\n        w = gamma ** (n - i - 1)\n\n        coords_cam, val0 = projective_transform(\n            poses_est[i], disps_est[i], intrinsics, ii, jj)\n\n        grid_x = coords_cam[..., 0]/(wd-1)\n        grid_y = coords_cam[..., 1]/(ht-1)\n        grid = torch.stack([grid_x, grid_y], dim=-1).view(-1, ht, wd, 2)\n        grid = grid * 2 - 1\n\n        val_pix = (grid.abs().max(-1)[0] <= 1).float()\n        val_pix = val_pix * val0.view(-1, ht, wd)\n\n        if mode == 'unsup':\n            masks_all = masks[i].cuda().view(-1, ht, wd)\n        val_pix = val_pix * masks_all\n\n        warped_image0 = F.grid_sample(\n            images1, grid, padding_mode=\"border\", align_corners=True)\n\n        diff = compute_reprojection_loss(images0, warped_image0, ssim)\n        p_e = (diff*val_pix).mean()\n        ph_loss += w * p_e\n\n    metrics = {\n        'ph_cam_error': p_e.item(),\n        '0.01color_cam': mean_on_mask((diff < 0.01).float(), val_pix).item(),\n    }\n\n    return ph_loss, metrics\n\n\ndef unsup_occ_vals(poses_est, disps_est, intrinsics,\n                   downsample, graph, loss, use_one=False):\n    \"\"\"occlusion and dynamic obj valid masks in unsup\"\"\"\n\n    N = disps_est[0].shape[1]\n    n = len(poses_est)\n\n    if graph == None:\n        graph = OrderedDict()\n        for i in range(N):\n            graph[i] = [j for j in range(N) if abs(i-j) == 1]\n    ii, jj, kk = graph_to_edge_list(graph)\n\n    intrinsics = intrinsics.cpu()\n    if downsample:\n        intrinsics /= 8\n\n    val_list = []\n\n    for i in range(n):\n        disp_est = disps_est[i].detach().cpu()\n        pose_est = poses_est[i].detach().cpu()\n\n        if downsample:\n            disp_est = disp_est[:, :, 3::8, 3::8]\n        ht, wd = disp_est.shape[2], disp_est.shape[3]\n\n        if use_one:\n            val = torch.ones_like(disp_est[:, jj].view(-1, 1, ht, wd))\n            val_list.append(val)\n            continue\n\n        coords_cam, disp0, _ = projective_transform_unsup(\n            pose_est, disp_est, intrinsics, ii, jj)\n        disp0 = disp0.view(-1, 1, ht, wd)\n        disp1 = disp_est[:, jj].view(-1, 1, ht, wd)\n\n        grid_x = coords_cam[..., 0]/(wd-1)\n        grid_y = coords_cam[..., 1]/(ht-1)\n        grid = torch.stack([grid_x, grid_y], dim=-1).view(-1, ht, wd, 2)\n        grid = grid * 2 - 1\n\n        warped_disp0 = F.grid_sample(\n            disp1, grid, padding_mode=\"border\", align_corners=True)\n\n        if loss == 'ph_loss':\n            val = ((1/warped_disp0 - 1/disp0) > -0.005).float()\n        else:\n            val = ((1/disp0 - 1/warped_disp0).abs() <= 0.005).float()\n        \n        val_list.append(val)\n\n    return val_list\n\n\ndef unsup_dy_vals(vals, dy_masks, graph):\n    ii, jj, kk = graph_to_edge_list(graph)\n\n    if not isinstance(dy_masks, list):\n        dy_masks = dy_masks.detach().cpu()\n        dy_masks = dy_masks[:, :, 3::8, 3::8]\n        ht, wd = dy_masks.shape[2], dy_masks.shape[3]\n        dy_val = dy_masks[:, ii].view(-1, 1, ht, wd)\n\n    n = len(vals)\n    val_list = []\n\n    for i in range(n):\n        if isinstance(dy_masks, list):\n            dy_val = dy_masks[i]\n            ht, wd = dy_val.shape[2], dy_val.shape[3]\n            dy_val = dy_val.view(-1, 1, ht, wd)\n\n        dy_val = 1 - dy_val\n        val = torch.clamp(vals[i]+dy_val, min=0, max=1)\n        val_list.append(val)\n\n    return val_list\n\n\ndef compute_reprojection_loss(pred, target, ssim):\n    \"\"\"\n    From many-depth\n    Computes reprojection loss between a batch of predicted and target images\n    \"\"\"\n    abs_diff = torch.abs(target - pred)\n    l1_loss = abs_diff.mean(1)\n\n    if ssim is None:\n        reprojection_loss = l1_loss\n    else:\n        ssim_loss = ssim(pred, target).mean(1)\n        reprojection_loss = 0.85 * ssim_loss + 0.15 * l1_loss\n\n    return reprojection_loss\n\n\nclass SSIM(nn.Module):\n    \"\"\"Layer to compute the SSIM loss between a pair of images\n    \"\"\"\n\n    def __init__(self):\n        super(SSIM, self).__init__()\n        self.mu_x_pool = nn.AvgPool2d(3, 1)\n        self.mu_y_pool = nn.AvgPool2d(3, 1)\n        self.sig_x_pool = nn.AvgPool2d(3, 1)\n        self.sig_y_pool = nn.AvgPool2d(3, 1)\n        self.sig_xy_pool = nn.AvgPool2d(3, 1)\n\n        self.refl = nn.ReflectionPad2d(1)\n\n        self.C1 = 0.01 ** 2\n        self.C2 = 0.03 ** 2\n\n    def forward(self, x, y):\n        x = self.refl(x)\n        y = self.refl(y)\n\n        mu_x = self.mu_x_pool(x)\n        mu_y = self.mu_y_pool(y)\n\n        sigma_x = self.sig_x_pool(x ** 2) - mu_x ** 2\n        sigma_y = self.sig_y_pool(y ** 2) - mu_y ** 2\n        sigma_xy = self.sig_xy_pool(x * y) - mu_x * mu_y\n\n        SSIM_n = (2 * mu_x * mu_y + self.C1) * (2 * sigma_xy + self.C2)\n        SSIM_d = (mu_x ** 2 + mu_y ** 2 + self.C1) * \\\n            (sigma_x + sigma_y + self.C2)\n\n        return torch.clamp((1 - SSIM_n / SSIM_d) / 2, 0, 1)\n\n\ndef mean_on_mask(diff, val_pix):\n    mask = val_pix.expand_as(diff)\n    if mask.sum() > 10000:\n        mean_value = (diff * mask).sum() / mask.sum()\n    else:\n        print('warning - most pixels are masked.')\n        mean_value = torch.tensor(0).float().type_as(mask)\n    return mean_value\n\n\ndef ce_reg_loss(preds, gamma=0.9):\n    n = len(preds)\n    entry_loss = 0\n\n    for i in range(n):\n        w = gamma ** (n - i - 1)\n\n        e_e = -preds[i] * torch.log(preds[i] + 1e-10)\n        e_e = e_e.sum(-1).mean()\n\n        entry_loss += w*e_e\n\n    metrics = {\n        'mask_entro_error': e_e.item(),\n    }\n\n    return entry_loss, metrics\n\n\ndef unsup_art_label(poses_est, disps_est, intrinsics, full_flows, graph, thresh=0.5,\n                    downsample=True):\n\n    ht, wd = full_flows[0].shape[2], full_flows[0].shape[3]\n    ii, jj, kk = graph_to_edge_list(graph)\n\n    intrinsics = intrinsics.cpu()\n    if downsample:\n        intrinsics /= 8\n\n    coords0 = coords_grid(ht, wd)\n    n = len(full_flows)\n    art_list = []\n\n    for i in range(n):\n\n        full_flow = full_flows[i].detach().cpu()\n        pose_est = poses_est[i].detach().cpu()\n        disp_est = disps_est[i].detach().cpu()\n        if downsample:\n            disp_est = disp_est[:, :, 3::8, 3::8]\n\n        coords_flow = coords0 + full_flow\n        coords_cam, _ = projective_transform(\n            pose_est, disp_est, intrinsics, ii, jj)\n\n        delta = (coords_flow - coords_cam).norm(dim=-1)\n        art_mask = (delta <= thresh).float().unsqueeze(-1)\n\n        art_list.append(art_mask)\n\n    return art_list\n\n\ndef upsample_inter(mask):\n    batch, num, ht, wd, dim = mask.shape\n    mask = mask.permute(0, 1, 4, 2, 3).contiguous()\n    mask = mask.view(batch*num, dim, ht, wd)\n    mask = F.interpolate(mask, scale_factor=8, mode='bilinear',\n                         align_corners=True, recompute_scale_factor=True)\n    mask = mask.permute(0, 2, 3, 1).contiguous()\n    return mask.view(batch, num, 8*ht, 8*wd, dim)\n\n\ndef art_label_loss(art_masks, masks, gamma=0.9, downsample=True):\n    \"\"\"Artificial Labels Loss\"\"\"\n\n    # ht, wd = masks[0].shape[2], masks[0].shape[3]\n    # ii, jj, kk = graph_to_edge_list(graph)\n    # gt_vals_all = gt_vals[:, ii]\n\n    n = len(masks)\n    al_loss = 0.0\n\n    for i in range(n):\n        w = gamma ** (n - i - 1)\n\n        if downsample:\n            art_mask = upsample_inter(art_masks[i]).cuda()\n        else:\n            art_mask = art_masks[i].cuda()\n\n        diff = ce_func(art_mask, masks[i])\n        # al_e = (diff*gt_vals_all).mean()\n        al_e = diff.mean()\n        al_loss += w * al_e\n\n    metrics = {\n        'art_mask_error': al_e.item(),\n        'static_px_rate': art_mask.mean().item(),\n        'dynamic_px_rate': (1 - art_mask).mean().item()\n    }\n\n    return al_loss, metrics\n\n\ndef gt_label_loss(gt_masks, gt_vals, masks, graph, gamma=0.9, mean_mask=False):\n    \"\"\"gt static/dynamic mask loss\"\"\"\n\n    ii, jj, kk = graph_to_edge_list(graph)\n    gt_masks_all = gt_masks[:, ii]\n    gt_vals_all = gt_vals[:, ii]\n\n    n = len(masks)\n    gt_l_loss = 0.0\n\n    for i in range(n):\n        w = gamma ** (n - i - 1)\n\n        diff = ce_func(gt_masks_all, masks[i])\n        if mean_mask:\n            gt_l_e = mean_on_mask(diff, gt_vals_all)\n        else:\n            gt_l_e = (diff*gt_vals_all).mean()\n\n        gt_l_loss += w * gt_l_e\n\n    metrics = {\n        'gt_mask_error': gt_l_e.item(),\n        'static_px_rate': (gt_masks_all*gt_vals_all).mean().item(),\n        'dynamic_px_rate': ((1-gt_masks_all)*gt_vals_all).mean().item(),\n    }\n\n    return gt_l_loss, metrics\n\n\ndef ce_func(labels, inputs):\n    pos = labels * torch.log(inputs+1e-10)\n    neg = (1-labels) * torch.log(1-inputs+1e-10)\n    return -(pos + neg)\n\n\ndef consistency_loss(masks, n_frames, graph, gamma=0.9):\n    \"\"\"consistency loss to help mask be the same\"\"\"\n\n    ii, jj, kk = graph_to_edge_list(graph)\n    edge_cnt = [0]*(n_frames+1)\n    for i in ii:\n        edge_cnt[i+1] += 1\n    for i in ii:\n        edge_cnt[i+1] += edge_cnt[i]\n\n    n = len(masks)\n    con_loss = 0\n\n    for i in range(n):\n        w = gamma ** (n - i - 1)\n        con_e = 0\n        for j in range(n_frames):\n            tmp_mask = masks[i][:, edge_cnt[j]:edge_cnt[j+1]]\n            tmp_mask_m = tmp_mask.mean(1, keepdim=True)\n            con_e += (tmp_mask-tmp_mask_m).mean()\n        con_e /= n_frames\n        con_loss += con_e*w\n\n    metrics = {\n        'con_error': con_e.item()\n    }\n\n    return con_loss, metrics\n"
  },
  {
    "path": "VO_Module/droid_slam/geom/projective_ops.py",
    "content": "import torch\nimport torch.nn.functional as F\n\nfrom lietorch import SE3, Sim3\n\nMIN_DEPTH = 0.2\n\n\ndef extract_intrinsics(intrinsics):\n    return intrinsics[..., None, None, :].unbind(dim=-1)\n\n\ndef coords_grid(ht, wd, **kwargs):\n    y, x = torch.meshgrid(\n        torch.arange(ht).to(**kwargs).float(),\n        torch.arange(wd).to(**kwargs).float())\n\n    return torch.stack([x, y], dim=-1)\n\n\ndef iproj(disps, intrinsics, jacobian=False):\n    \"\"\" pinhole camera inverse projection \"\"\"\n    ht, wd = disps.shape[2:]\n    fx, fy, cx, cy = extract_intrinsics(intrinsics)\n\n    y, x = torch.meshgrid(\n        torch.arange(ht).to(disps.device).float(),\n        torch.arange(wd).to(disps.device).float())\n\n    i = torch.ones_like(disps)\n    X = (x - cx) / fx\n    Y = (y - cy) / fy\n    pts = torch.stack([X, Y, i, disps], dim=-1)\n\n    if jacobian:\n        J = torch.zeros_like(pts)\n        J[..., -1] = 1.0\n        return pts, J\n\n    return pts, None\n\n\ndef proj(Xs, intrinsics, jacobian=False, return_depth=False):\n    \"\"\" pinhole camera projection \"\"\"\n    fx, fy, cx, cy = extract_intrinsics(intrinsics)\n    X, Y, Z, D = Xs.unbind(dim=-1)\n\n    Z = torch.where(Z < 0.5*MIN_DEPTH, torch.ones_like(Z), Z)\n    d = 1.0 / Z\n\n    x = fx * (X * d) + cx\n    y = fy * (Y * d) + cy\n    if return_depth:\n        coords = torch.stack([x, y, D*d], dim=-1)\n    else:\n        coords = torch.stack([x, y], dim=-1)\n\n    if jacobian:\n        B, N, H, W = d.shape\n        o = torch.zeros_like(d)\n        proj_jac = torch.stack([\n            fx*d,     o, -fx*X*d*d,  o,\n            o,  fy*d, -fy*Y*d*d,  o,\n            # o,     o,    -D*d*d,  d,\n        ], dim=-1).view(B, N, H, W, 2, 4)\n\n        return coords, proj_jac\n\n    return coords, None\n\n\ndef actp(Gij, X0, jacobian=False):\n    \"\"\" action on point cloud \"\"\"\n    X1 = Gij[:, :, None, None] * X0\n\n    if jacobian:\n        X, Y, Z, d = X1.unbind(dim=-1)\n        o = torch.zeros_like(d)\n        B, N, H, W = d.shape\n\n        if isinstance(Gij, SE3):\n            Ja = torch.stack([\n                d,  o,  o,  o,  Z, -Y,\n                o,  d,  o, -Z,  o,  X,\n                o,  o,  d,  Y, -X,  o,\n                o,  o,  o,  o,  o,  o,\n            ], dim=-1).view(B, N, H, W, 4, 6)\n\n        elif isinstance(Gij, Sim3):\n            Ja = torch.stack([\n                d,  o,  o,  o,  Z, -Y,  X,\n                o,  d,  o, -Z,  o,  X,  Y,\n                o,  o,  d,  Y, -X,  o,  Z,\n                o,  o,  o,  o,  o,  o,  o\n            ], dim=-1).view(B, N, H, W, 4, 7)\n\n        return X1, Ja\n\n    return X1, None\n\n\ndef projective_transform(poses, depths, intrinsics, ii, jj, jacobian=False, return_depth=False):\n    \"\"\" map points from ii->jj \"\"\"\n\n    # inverse project (pinhole)\n    X0, Jz = iproj(depths[:, ii], intrinsics[:, ii], jacobian=jacobian)\n\n    # transform: both pose i and j are w2c\n    Gij = poses[:, jj] * poses[:, ii].inv()\n    X1, Ja = actp(Gij, X0, jacobian=jacobian)\n\n    # project (pinhole)\n    x1, Jp = proj(X1, intrinsics[:, jj],\n                  jacobian=jacobian, return_depth=return_depth)\n\n    # exclude points too close to camera\n    valid = ((X1[..., 2] > MIN_DEPTH) & (X0[..., 2] > MIN_DEPTH)).float()\n    valid = valid.unsqueeze(-1)\n\n    if jacobian:\n        # Ji transforms according to dual adjoint\n        Jj = torch.matmul(Jp, Ja)\n        Ji = -Gij[:, :, None, None, None].adjT(Jj)\n\n        Jz = Gij[:, :, None, None] * Jz\n        Jz = torch.matmul(Jp, Jz.unsqueeze(-1))\n\n        return x1, valid, (Ji, Jj, Jz)\n\n    return x1, valid\n\n\ndef projective_transform_unsup(poses, depths, intrinsics, ii, jj, jacobian=False, return_depth=True):\n    \"\"\" map points from ii->jj \"\"\"\n\n    # inverse project (pinhole)\n    X0, Jz = iproj(depths[:, ii], intrinsics[:, ii], jacobian=jacobian)\n\n    # transform: both pose i and j are w2c\n    Gij = poses[:, jj] * poses[:, ii].inv()\n    X1, Ja = actp(Gij, X0, jacobian=jacobian)\n\n    # project (pinhole)\n    # 返回的深度是逆深度\n    coords_disp, Jp = proj(X1, intrinsics[:, jj],\n                           jacobian=jacobian, return_depth=return_depth)\n    x1, disp0 = coords_disp[..., 0:2], coords_disp[..., 2:3]\n\n    # exclude points too close to camera\n    valid = ((X1[..., 2] > MIN_DEPTH) & (X0[..., 2] > MIN_DEPTH)).float()\n    valid = valid.unsqueeze(-1)\n\n    if jacobian:\n        # Ji transforms according to dual adjoint\n        Jj = torch.matmul(Jp, Ja)\n        Ji = -Gij[:, :, None, None, None].adjT(Jj)\n\n        Jz = Gij[:, :, None, None] * Jz\n        Jz = torch.matmul(Jp, Jz.unsqueeze(-1))\n\n        return x1, disp0, valid, (Ji, Jj, Jz)\n\n    return x1, disp0, valid\n\n\ndef induced_flow(poses, disps, intrinsics, ii, jj):\n    \"\"\" optical flow induced by camera motion \"\"\"\n\n    ht, wd = disps.shape[2:]\n    y, x = torch.meshgrid(\n        torch.arange(ht).to(disps.device).float(),\n        torch.arange(wd).to(disps.device).float())\n\n    coords0 = torch.stack([x, y], dim=-1)\n    coords1, valid = projective_transform(\n        poses, disps, intrinsics, ii, jj, False)\n\n    return coords1[..., :2] - coords0, valid\n\n\ndef coords_clamp(coords, h_max, w_max, h_min=0, w_min=0):\n    x_clamp = torch.clamp(coords[..., 0], w_min, w_max)\n    y_clamp = torch.clamp(coords[..., 1], h_min, h_max)\n    return torch.stack([x_clamp, y_clamp], dim=-1)\n\n\ndef coords_valid(coords, h_max, w_max, h_min=0, w_min=0, neg_fac=0.1):\n    val_p = ((coords[..., 0] < w_max) & (coords[..., 0] >= w_min) &\n             (coords[..., 1] < h_max) & (coords[..., 1] >= h_min)).float().unsqueeze(-1)\n    val_n = ((coords[..., 0] >= w_max) | (coords[..., 0] < w_min) |\n             (coords[..., 1] >= h_max) | (coords[..., 1] < h_min)).float().unsqueeze(-1)*neg_fac\n    val = val_p+val_n\n    return val\n"
  },
  {
    "path": "VO_Module/droid_slam/logger.py",
    "content": "\nimport torch\nfrom torch.utils.tensorboard import SummaryWriter\n\n\nSUM_FREQ = 100\n\nclass Logger:\n    def __init__(self, name, scheduler):\n        self.total_steps = 0\n        self.running_loss = {}\n        self.writer = None\n        self.name = name\n        self.scheduler = scheduler\n\n    def _print_training_status(self):\n        if self.writer is None:\n            self.writer = SummaryWriter('runs/%s' % self.name)\n            print([k for k in self.running_loss])\n\n        lr = self.scheduler.get_lr().pop()\n        metrics_data = [self.running_loss[k]/SUM_FREQ for k in self.running_loss.keys()]\n        training_str = \"[{:6d}, {:10.7f}] \".format(self.total_steps+1, lr)\n        metrics_str = (\"{:10.4f}, \"*len(metrics_data)).format(*metrics_data)\n        \n        # print the training status\n        print(training_str + metrics_str)\n\n        for key in self.running_loss:\n            val = self.running_loss[key] / SUM_FREQ\n            self.writer.add_scalar(key, val, self.total_steps)\n            self.running_loss[key] = 0.0\n\n    def push(self, metrics):\n\n        for key in metrics:\n            if key not in self.running_loss:\n                self.running_loss[key] = 0.0\n\n            self.running_loss[key] += metrics[key]\n\n        if self.total_steps % SUM_FREQ == SUM_FREQ-1:\n            self._print_training_status()\n            self.running_loss = {}\n\n        self.total_steps += 1\n\n    def write_dict(self, results):\n        for key in results:\n            self.writer.add_scalar(key, results[key], self.total_steps)\n\n    def close(self):\n        self.writer.close()\n\n"
  },
  {
    "path": "VO_Module/droid_slam/modules/__init__.py",
    "content": ""
  },
  {
    "path": "VO_Module/droid_slam/modules/clipping.py",
    "content": "import torch\nimport torch.nn as nn\nimport torch.nn.functional as F\n\nGRAD_CLIP = .01\n\nclass GradClip(torch.autograd.Function):\n    @staticmethod\n    def forward(ctx, x):\n        return x\n\n    @staticmethod\n    def backward(ctx, grad_x):\n        o = torch.zeros_like(grad_x)\n        grad_x = torch.where(grad_x.abs()>GRAD_CLIP, o, grad_x)\n        grad_x = torch.where(torch.isnan(grad_x), o, grad_x)\n        return grad_x\n\nclass GradientClip(nn.Module):\n    def __init__(self):\n        super(GradientClip, self).__init__()\n\n    def forward(self, x):\n        return GradClip.apply(x)"
  },
  {
    "path": "VO_Module/droid_slam/modules/corr.py",
    "content": "import torch\nimport torch.nn.functional as F\n\nimport droid_backends\n\nclass CorrSampler(torch.autograd.Function):\n\n    @staticmethod\n    def forward(ctx, volume, coords, radius):\n        ctx.save_for_backward(volume,coords)\n        ctx.radius = radius\n        corr, = droid_backends.corr_index_forward(volume, coords, radius)\n        return corr\n\n    @staticmethod\n    def backward(ctx, grad_output):\n        volume, coords = ctx.saved_tensors\n        grad_output = grad_output.contiguous()\n        grad_volume, = droid_backends.corr_index_backward(volume, coords, grad_output, ctx.radius)\n        return grad_volume, None, None\n\n\nclass CorrBlock:\n    def __init__(self, fmap1, fmap2, num_levels=4, radius=3):\n        self.num_levels = num_levels\n        self.radius = radius\n        self.corr_pyramid = []\n\n        # all pairs correlation\n        corr = CorrBlock.corr(fmap1, fmap2)\n\n        batch, num, h1, w1, h2, w2 = corr.shape\n        corr = corr.reshape(batch*num*h1*w1, 1, h2, w2)\n        \n        for i in range(self.num_levels):\n            self.corr_pyramid.append(\n                corr.view(batch*num, h1, w1, h2//2**i, w2//2**i))\n            corr = F.avg_pool2d(corr, 2, stride=2)\n            \n    def __call__(self, coords):\n        out_pyramid = []\n        batch, num, ht, wd, _ = coords.shape\n        coords = coords.permute(0,1,4,2,3)\n        coords = coords.contiguous().view(batch*num, 2, ht, wd)\n        \n        for i in range(self.num_levels):\n            corr = CorrSampler.apply(self.corr_pyramid[i], coords/2**i, self.radius)\n            out_pyramid.append(corr.view(batch, num, -1, ht, wd))\n\n        return torch.cat(out_pyramid, dim=2)\n\n    def cat(self, other):\n        for i in range(self.num_levels):\n            self.corr_pyramid[i] = torch.cat([self.corr_pyramid[i], other.corr_pyramid[i]], 0)\n        return self\n\n    def __getitem__(self, index):\n        for i in range(self.num_levels):\n            self.corr_pyramid[i] = self.corr_pyramid[i][index]\n        return self\n\n\n    @staticmethod\n    def corr(fmap1, fmap2):\n        \"\"\" all-pairs correlation \"\"\"\n        batch, num, dim, ht, wd = fmap1.shape\n        fmap1 = fmap1.reshape(batch*num, dim, ht*wd) / 4.0\n        fmap2 = fmap2.reshape(batch*num, dim, ht*wd) / 4.0\n        \n        corr = torch.matmul(fmap1.transpose(1,2), fmap2)\n        return corr.view(batch, num, ht, wd, ht, wd)\n\n\nclass CorrLayer(torch.autograd.Function):\n    @staticmethod\n    def forward(ctx, fmap1, fmap2, coords, r):\n        ctx.r = r\n        ctx.save_for_backward(fmap1, fmap2, coords)\n        corr, = droid_backends.altcorr_forward(fmap1, fmap2, coords, ctx.r)\n        return corr\n\n    @staticmethod\n    def backward(ctx, grad_corr):\n        fmap1, fmap2, coords = ctx.saved_tensors\n        grad_corr = grad_corr.contiguous()\n        fmap1_grad, fmap2_grad, coords_grad = \\\n            droid_backends.altcorr_backward(fmap1, fmap2, coords, grad_corr, ctx.r)\n        return fmap1_grad, fmap2_grad, coords_grad, None\n\n\nclass AltCorrBlock:\n    def __init__(self, fmaps, num_levels=4, radius=3):\n        self.num_levels = num_levels\n        self.radius = radius\n\n        B, N, C, H, W = fmaps.shape\n        fmaps = fmaps.view(B*N, C, H, W) / 4.0\n        \n        self.pyramid = []\n        for i in range(self.num_levels):\n            sz = (B, N, H//2**i, W//2**i, C)\n            fmap_lvl = fmaps.permute(0, 2, 3, 1).contiguous()\n            self.pyramid.append(fmap_lvl.view(*sz))\n            fmaps = F.avg_pool2d(fmaps, 2, stride=2)\n  \n    def corr_fn(self, coords, ii, jj):\n        B, N, H, W, S, _ = coords.shape\n        coords = coords.permute(0, 1, 4, 2, 3, 5)\n\n        corr_list = []\n        for i in range(self.num_levels):\n            r = self.radius\n            fmap1_i = self.pyramid[0][:, ii]\n            fmap2_i = self.pyramid[i][:, jj]\n\n            coords_i = (coords / 2**i).reshape(B*N, S, H, W, 2).contiguous()\n            fmap1_i = fmap1_i.reshape((B*N,) + fmap1_i.shape[2:])\n            fmap2_i = fmap2_i.reshape((B*N,) + fmap2_i.shape[2:])\n\n            corr = CorrLayer.apply(fmap1_i.float(), fmap2_i.float(), coords_i, self.radius)\n            corr = corr.view(B, N, S, -1, H, W).permute(0, 1, 3, 4, 5, 2)\n            corr_list.append(corr)\n\n        corr = torch.cat(corr_list, dim=2)\n        return corr\n\n\n    def __call__(self, coords, ii, jj):\n        squeeze_output = False\n        if len(coords.shape) == 5:\n            coords = coords.unsqueeze(dim=-2)\n            squeeze_output = True\n\n        corr = self.corr_fn(coords, ii, jj)\n        \n        if squeeze_output:\n            corr = corr.squeeze(dim=-1)\n\n        return corr.contiguous()\n\n"
  },
  {
    "path": "VO_Module/droid_slam/modules/extractor.py",
    "content": "import torch\nimport torch.nn as nn\nimport torch.nn.functional as F\n\n\nclass ResidualBlock(nn.Module):\n    def __init__(self, in_planes, planes, norm_fn='group', stride=1):\n        super(ResidualBlock, self).__init__()\n  \n        self.conv1 = nn.Conv2d(in_planes, planes, kernel_size=3, padding=1, stride=stride)\n        self.conv2 = nn.Conv2d(planes, planes, kernel_size=3, padding=1)\n        self.relu = nn.ReLU(inplace=True)\n\n        num_groups = planes // 8\n\n        if norm_fn == 'group':\n            self.norm1 = nn.GroupNorm(num_groups=num_groups, num_channels=planes)\n            self.norm2 = nn.GroupNorm(num_groups=num_groups, num_channels=planes)\n            if not stride == 1:\n                self.norm3 = nn.GroupNorm(num_groups=num_groups, num_channels=planes)\n        \n        elif norm_fn == 'batch':\n            self.norm1 = nn.BatchNorm2d(planes)\n            self.norm2 = nn.BatchNorm2d(planes)\n            if not stride == 1:\n                self.norm3 = nn.BatchNorm2d(planes)\n        \n        elif norm_fn == 'instance':\n            self.norm1 = nn.InstanceNorm2d(planes)\n            self.norm2 = nn.InstanceNorm2d(planes)\n            if not stride == 1:\n                self.norm3 = nn.InstanceNorm2d(planes)\n\n        elif norm_fn == 'none':\n            self.norm1 = nn.Sequential()\n            self.norm2 = nn.Sequential()\n            if not stride == 1:\n                self.norm3 = nn.Sequential()\n\n        if stride == 1:\n            self.downsample = None\n        \n        else:    \n            self.downsample = nn.Sequential(\n                nn.Conv2d(in_planes, planes, kernel_size=1, stride=stride), self.norm3)\n\n    def forward(self, x):\n        y = x\n        y = self.relu(self.norm1(self.conv1(y)))\n        y = self.relu(self.norm2(self.conv2(y)))\n\n        if self.downsample is not None:\n            x = self.downsample(x)\n\n        return self.relu(x+y)\n\n\nclass BottleneckBlock(nn.Module):\n    def __init__(self, in_planes, planes, norm_fn='group', stride=1):\n        super(BottleneckBlock, self).__init__()\n  \n        self.conv1 = nn.Conv2d(in_planes, planes//4, kernel_size=1, padding=0)\n        self.conv2 = nn.Conv2d(planes//4, planes//4, kernel_size=3, padding=1, stride=stride)\n        self.conv3 = nn.Conv2d(planes//4, planes, kernel_size=1, padding=0)\n        self.relu = nn.ReLU(inplace=True)\n\n        num_groups = planes // 8\n\n        if norm_fn == 'group':\n            self.norm1 = nn.GroupNorm(num_groups=num_groups, num_channels=planes//4)\n            self.norm2 = nn.GroupNorm(num_groups=num_groups, num_channels=planes//4)\n            self.norm3 = nn.GroupNorm(num_groups=num_groups, num_channels=planes)\n            if not stride == 1:\n                self.norm4 = nn.GroupNorm(num_groups=num_groups, num_channels=planes)\n        \n        elif norm_fn == 'batch':\n            self.norm1 = nn.BatchNorm2d(planes//4)\n            self.norm2 = nn.BatchNorm2d(planes//4)\n            self.norm3 = nn.BatchNorm2d(planes)\n            if not stride == 1:\n                self.norm4 = nn.BatchNorm2d(planes)\n        \n        elif norm_fn == 'instance':\n            self.norm1 = nn.InstanceNorm2d(planes//4)\n            self.norm2 = nn.InstanceNorm2d(planes//4)\n            self.norm3 = nn.InstanceNorm2d(planes)\n            if not stride == 1:\n                self.norm4 = nn.InstanceNorm2d(planes)\n\n        elif norm_fn == 'none':\n            self.norm1 = nn.Sequential()\n            self.norm2 = nn.Sequential()\n            self.norm3 = nn.Sequential()\n            if not stride == 1:\n                self.norm4 = nn.Sequential()\n\n        if stride == 1:\n            self.downsample = None\n        \n        else:    \n            self.downsample = nn.Sequential(\n                nn.Conv2d(in_planes, planes, kernel_size=1, stride=stride), self.norm4)\n\n    def forward(self, x):\n        y = x\n        y = self.relu(self.norm1(self.conv1(y)))\n        y = self.relu(self.norm2(self.conv2(y)))\n        y = self.relu(self.norm3(self.conv3(y)))\n\n        if self.downsample is not None:\n            x = self.downsample(x)\n\n        return self.relu(x+y)\n\n\nDIM=32\n\nclass BasicEncoder(nn.Module):\n    def __init__(self, output_dim=128, norm_fn='batch', dropout=0.0, multidim=False):\n        super(BasicEncoder, self).__init__()\n        self.norm_fn = norm_fn\n        self.multidim = multidim\n\n        if self.norm_fn == 'group':\n            self.norm1 = nn.GroupNorm(num_groups=8, num_channels=DIM)\n            \n        elif self.norm_fn == 'batch':\n            self.norm1 = nn.BatchNorm2d(DIM)\n\n        elif self.norm_fn == 'instance':\n            self.norm1 = nn.InstanceNorm2d(DIM)\n\n        elif self.norm_fn == 'none':\n            self.norm1 = nn.Sequential()\n\n        self.conv1 = nn.Conv2d(3, DIM, kernel_size=7, stride=2, padding=3)\n        self.relu1 = nn.ReLU(inplace=True)\n\n        self.in_planes = DIM\n        self.layer1 = self._make_layer(DIM,  stride=1)\n        self.layer2 = self._make_layer(2*DIM, stride=2)\n        self.layer3 = self._make_layer(4*DIM, stride=2)\n\n        # output convolution\n        self.conv2 = nn.Conv2d(4*DIM, output_dim, kernel_size=1)\n\n        if self.multidim:\n            self.layer4 = self._make_layer(256, stride=2)\n            self.layer5 = self._make_layer(512, stride=2)\n\n            self.in_planes = 256\n            self.layer6 = self._make_layer(256, stride=1)\n\n            self.in_planes = 128\n            self.layer7 = self._make_layer(128, stride=1)\n\n            self.up1 = nn.Conv2d(512, 256, 1)\n            self.up2 = nn.Conv2d(256, 128, 1)\n            self.conv3 = nn.Conv2d(128, output_dim, kernel_size=1)\n\n        if dropout > 0:\n            self.dropout = nn.Dropout2d(p=dropout)\n        else:\n            self.dropout = None\n\n        for m in self.modules():\n            if isinstance(m, nn.Conv2d):\n                nn.init.kaiming_normal_(m.weight, mode='fan_out', nonlinearity='relu')\n            elif isinstance(m, (nn.BatchNorm2d, nn.InstanceNorm2d, nn.GroupNorm)):\n                if m.weight is not None:\n                    nn.init.constant_(m.weight, 1)\n                if m.bias is not None:\n                    nn.init.constant_(m.bias, 0)\n\n    def _make_layer(self, dim, stride=1):\n        layer1 = ResidualBlock(self.in_planes, dim, self.norm_fn, stride=stride)\n        layer2 = ResidualBlock(dim, dim, self.norm_fn, stride=1)\n        layers = (layer1, layer2)\n        \n        self.in_planes = dim\n        return nn.Sequential(*layers)\n\n    def forward(self, x):\n        b, n, c1, h1, w1 = x.shape\n        x = x.view(b*n, c1, h1, w1)\n\n        x = self.conv1(x)\n        x = self.norm1(x)\n        x = self.relu1(x)\n\n        x = self.layer1(x)\n        x = self.layer2(x)\n        x = self.layer3(x)\n\n        x = self.conv2(x)\n\n        _, c2, h2, w2 = x.shape\n        return x.view(b, n, c2, h2, w2)\n"
  },
  {
    "path": "VO_Module/droid_slam/modules/gru.py",
    "content": "import torch\nimport torch.nn as nn\n\n\nclass ConvGRU(nn.Module):\n    def __init__(self, h_planes=128, i_planes=128):\n        super(ConvGRU, self).__init__()\n        self.do_checkpoint = False\n        self.convz = nn.Conv2d(h_planes+i_planes, h_planes, 3, padding=1)\n        self.convr = nn.Conv2d(h_planes+i_planes, h_planes, 3, padding=1)\n        self.convq = nn.Conv2d(h_planes+i_planes, h_planes, 3, padding=1)\n\n        self.w = nn.Conv2d(h_planes, h_planes, 1, padding=0)\n\n        self.convz_glo = nn.Conv2d(h_planes, h_planes, 1, padding=0)\n        self.convr_glo = nn.Conv2d(h_planes, h_planes, 1, padding=0)\n        self.convq_glo = nn.Conv2d(h_planes, h_planes, 1, padding=0)\n\n    def forward(self, net, *inputs):\n        inp = torch.cat(inputs, dim=1)\n        net_inp = torch.cat([net, inp], dim=1)\n\n        b, c, h, w = net.shape\n        glo = torch.sigmoid(self.w(net)) * net\n        glo = glo.view(b, c, h*w).mean(-1).view(b, c, 1, 1)\n\n        z = torch.sigmoid(self.convz(net_inp) + self.convz_glo(glo))\n        r = torch.sigmoid(self.convr(net_inp) + self.convr_glo(glo))\n        q = torch.tanh(self.convq(torch.cat([r*net, inp], dim=1)) + self.convq_glo(glo))\n\n        net = (1-z) * net + z * q\n        return net\n\n\n"
  },
  {
    "path": "VO_Module/droid_slam/motion_filter.py",
    "content": "import cv2\nimport torch\nimport lietorch\n\nfrom collections import OrderedDict\nfrom droid_net import DroidNet\n\nimport geom.projective_ops as pops\nfrom modules.corr import CorrBlock\nimport time\n\nclass MotionFilter:\n    \"\"\" This class is used to filter incoming frames and extract features \"\"\"\n\n    def __init__(self, net, video, thresh=2.5, device=\"cuda:0\"):\n\n        # split net modules\n        self.cnet = net.cnet\n        self.fnet = net.fnet\n        self.update = net.update\n\n        self.video = video\n        self.thresh = thresh\n        self.device = device\n\n        self.count = 0\n\n        # mean, std for image normalization\n        self.MEAN = torch.as_tensor([0.485, 0.456, 0.406], device=self.device)[\n            :, None, None]\n        self.STDV = torch.as_tensor([0.229, 0.224, 0.225], device=self.device)[\n            :, None, None]\n\n    @torch.cuda.amp.autocast(enabled=True)\n    def __context_encoder(self, image):\n        \"\"\" context features \"\"\"\n        x = self.cnet(image)\n        net, inp = self.cnet(image).split([128, 128], dim=2)\n        return net.tanh().squeeze(0), inp.relu().squeeze(0)\n\n    @torch.cuda.amp.autocast(enabled=True)\n    def __feature_encoder(self, image):\n        \"\"\" features for correlation volume \"\"\"\n        return self.fnet(image).squeeze(0)\n\n    @torch.cuda.amp.autocast(enabled=True)\n    @torch.no_grad()\n    def track(self, tstamp, image, depth=None, intrinsics=None, segments=None):\n        \"\"\" main update operation - run on every frame in video \"\"\"\n\n        Id = lietorch.SE3.Identity(1,).data.squeeze()\n        ht = image.shape[-2] // 8\n        wd = image.shape[-1] // 8\n\n        # normalize images\n        inputs = image[None, None, [2, 1, 0]].to(self.device) / 255.0\n        inputs = inputs.sub_(self.MEAN).div_(self.STDV)\n\n        # extract features\n        gmap = self.__feature_encoder(inputs)\n\n        ### always add first frame to the depth video ###\n        if self.video.counter.value == 0:\n            net, inp = self.__context_encoder(inputs)\n            self.net, self.inp, self.fmap = net, inp, gmap\n            self.video.append(tstamp, image, Id, 1.0,\n                              intrinsics / 8.0, gmap[0], net[0], inp[0], segments)\n\n        ### only add new frame if there is enough motion ###\n        else:\n            # index correlation volume\n            coords0 = pops.coords_grid(ht, wd, device=self.device)[None, None]\n            corr = CorrBlock(self.fmap[None], gmap[None])(coords0)\n\n            # approximate flow magnitude using 1 update iteration\n            _, delta, weight, _ = self.update(\n                self.net[None], self.inp[None], corr, segments=None)\n\n            # check motion magnitue / add new frame to video\n            if delta[..., 0:2].norm(dim=-1).mean().item() > self.thresh:\n                self.count = 0\n                net, inp = self.__context_encoder(inputs)\n                self.net, self.inp, self.fmap = net, inp, gmap\n                self.video.append(tstamp, image, None, None,\n                                  intrinsics / 8.0, gmap[0], net[0], inp[0], segments)\n            else:\n                self.count += 1\n\n    @torch.cuda.amp.autocast(enabled=True)\n    @torch.no_grad()\n    def track_vo(self, tstamp, image, depth=None, intrinsics=None, segments=None):\n        \"\"\" main update operation - run on every frame in video \"\"\"\n        Id = lietorch.SE3.Identity(1,).data.squeeze()\n        ht = image.shape[-2] // 8\n        wd = image.shape[-1] // 8\n\n        inputs = image[None, None, [2, 1, 0]].to(self.device) / 255.0\n        inputs = inputs.sub_(self.MEAN).div_(self.STDV)\n\n        gmap = self.__feature_encoder(inputs)\n        net, inp = self.__context_encoder(inputs)\n\n        if self.video.counter.value == 0:\n            self.video.append(tstamp, image, Id, 1.0,\n                              intrinsics / 8.0, gmap[0], net[0], inp[0], segments)\n        else:\n            self.video.append(tstamp, image, None, None,\n                                  intrinsics / 8.0, gmap[0], net[0], inp[0], segments)\n            \n   "
  },
  {
    "path": "VO_Module/droid_slam/trajectory_filler.py",
    "content": "import cv2\nimport torch\nimport lietorch\n\nfrom lietorch import SE3\nfrom collections import OrderedDict\nfrom factor_graph import FactorGraph\nfrom droid_net import DroidNet\nimport geom.projective_ops as pops\n\n\nclass PoseTrajectoryFiller:\n    \"\"\" This class is used to fill in non-keyframe poses \"\"\"\n\n    def __init__(self, net, video, device=\"cuda:0\"):\n        \n        # split net modules\n        self.cnet = net.cnet\n        self.fnet = net.fnet\n        self.update = net.update\n\n        self.count = 0\n        self.video = video\n        self.device = device\n\n        # mean, std for image normalization\n        self.MEAN = torch.as_tensor([0.485, 0.456, 0.406], device=self.device)[:, None, None]\n        self.STDV = torch.as_tensor([0.229, 0.224, 0.225], device=self.device)[:, None, None]\n        \n    @torch.cuda.amp.autocast(enabled=True)\n    def __feature_encoder(self, image):\n        \"\"\" features for correlation volume \"\"\"\n        return self.fnet(image).squeeze(0)\n\n    def __fill(self, tstamps, images, intrinsics):\n        \"\"\" fill operator \"\"\"\n\n        tt = torch.as_tensor(tstamps, device=self.device)\n        images = torch.stack(images, 0)\n        intrinsics = torch.stack(intrinsics, 0)\n        inputs = images[None,:,[2,1,0]].to(self.device) / 255.0\n        \n        ### linear pose interpolation ###\n        N = self.video.counter.value\n        M = len(tstamps)\n\n        ts = self.video.tstamp[:N]\n        Ps = SE3(self.video.poses[:N])\n\n        t0 = torch.as_tensor([ts[ts<=t].shape[0] - 1 for t in tstamps])\n        t1 = torch.where(t0<N-1, t0+1, t0)\n\n        dt = ts[t1] - ts[t0] + 1e-3\n        dP = Ps[t1] * Ps[t0].inv()\n\n        v = dP.log() / dt.unsqueeze(-1)\n        w = v * (tt - ts[t0]).unsqueeze(-1)\n        Gs = SE3.exp(w) * Ps[t0]\n\n        # extract features (no need for context features)\n        inputs = inputs.sub_(self.MEAN).div_(self.STDV)\n        fmap = self.__feature_encoder(inputs)\n\n        self.video.counter.value += M\n        self.video[N:N+M] = (tt, images, Gs.data, 1, intrinsics / 8.0, fmap)\n\n        graph = FactorGraph(self.video, self.update)\n        graph.add_factors(t0.to(self.device), torch.arange(N, N+M).to(self.device))\n        graph.add_factors(t1.to(self.device), torch.arange(N, N+M).to(self.device))\n\n        for itr in range(6):\n            graph.update(N, N+M, motion_only=True)\n    \n        Gs = SE3(self.video.poses[N:N+M].clone())\n        self.video.counter.value -= M\n\n        return [ Gs ]\n\n    @torch.no_grad()\n    def __call__(self, image_stream):\n        \"\"\" fill in poses of non-keyframe images \"\"\"\n\n        # store all camera poses\n        pose_list = []\n\n        tstamps = []\n        images = []\n        intrinsics = []\n        \n        for (tstamp, image, intrinsic, segments) in image_stream:\n            tstamps.append(tstamp)\n            images.append(image)\n            intrinsics.append(intrinsic)\n\n            if len(tstamps) == 16:\n                pose_list += self.__fill(tstamps, images, intrinsics)\n                tstamps, images, intrinsics = [], [], []\n\n        if len(tstamps) > 0:\n            pose_list += self.__fill(tstamps, images, intrinsics)\n\n        # stitch pose segments together\n        return lietorch.cat(pose_list, 0)\n\n"
  },
  {
    "path": "VO_Module/droid_slam/visualization.py",
    "content": "import torch\nimport cv2\nimport lietorch\nimport droid_backends\nimport time\nimport argparse\nimport numpy as np\nimport open3d as o3d\n\nfrom lietorch import SE3\nimport geom.projective_ops as pops\n\nCAM_POINTS = np.array([\n        [ 0,   0,   0],\n        [-1,  -1, 1.5],\n        [ 1,  -1, 1.5],\n        [ 1,   1, 1.5],\n        [-1,   1, 1.5],\n        [-0.5, 1, 1.5],\n        [ 0.5, 1, 1.5],\n        [ 0, 1.2, 1.5]])\n\nCAM_LINES = np.array([\n    [1,2], [2,3], [3,4], [4,1], [1,0], [0,2], [3,0], [0,4], [5,7], [7,6]])\n\ndef white_balance(img):\n    # from https://stackoverflow.com/questions/46390779/automatic-white-balancing-with-grayworld-assumption\n    result = cv2.cvtColor(img, cv2.COLOR_BGR2LAB)\n    avg_a = np.average(result[:, :, 1])\n    avg_b = np.average(result[:, :, 2])\n    result[:, :, 1] = result[:, :, 1] - ((avg_a - 128) * (result[:, :, 0] / 255.0) * 1.1)\n    result[:, :, 2] = result[:, :, 2] - ((avg_b - 128) * (result[:, :, 0] / 255.0) * 1.1)\n    result = cv2.cvtColor(result, cv2.COLOR_LAB2BGR)\n    return result\n\ndef create_camera_actor(g, scale=0.05):\n    \"\"\" build open3d camera polydata \"\"\"\n    camera_actor = o3d.geometry.LineSet(\n        points=o3d.utility.Vector3dVector(scale * CAM_POINTS),\n        lines=o3d.utility.Vector2iVector(CAM_LINES))\n\n    color = (g * 1.0, 0.5 * (1-g), 0.9 * (1-g))\n    camera_actor.paint_uniform_color(color)\n    return camera_actor\n\ndef create_point_actor(points, colors):\n    \"\"\" open3d point cloud from numpy array \"\"\"\n    point_cloud = o3d.geometry.PointCloud()\n    point_cloud.points = o3d.utility.Vector3dVector(points)\n    point_cloud.colors = o3d.utility.Vector3dVector(colors)\n    return point_cloud\n\ndef droid_visualization(video, device=\"cuda:0\"):\n    \"\"\" DROID visualization frontend \"\"\"\n\n    torch.cuda.set_device(device)\n    droid_visualization.video = video\n    droid_visualization.cameras = {}\n    droid_visualization.points = {}\n    droid_visualization.warmup = 8\n    droid_visualization.scale = 1.0\n    droid_visualization.ix = 0\n\n    droid_visualization.filter_thresh = 0.005\n\n    def increase_filter(vis):\n        droid_visualization.filter_thresh *= 2\n        with droid_visualization.video.get_lock():\n            droid_visualization.video.dirty[:droid_visualization.video.counter.value] = True\n\n    def decrease_filter(vis):\n        droid_visualization.filter_thresh *= 0.5\n        with droid_visualization.video.get_lock():\n            droid_visualization.video.dirty[:droid_visualization.video.counter.value] = True\n\n    def animation_callback(vis):\n        cam = vis.get_view_control().convert_to_pinhole_camera_parameters()\n\n        with torch.no_grad():\n\n            with video.get_lock():\n                t = video.counter.value \n                dirty_index, = torch.where(video.dirty.clone())\n                dirty_index = dirty_index\n\n            if len(dirty_index) == 0:\n                return\n\n            video.dirty[dirty_index] = False\n\n            # convert poses to 4x4 matrix\n            poses = torch.index_select(video.poses, 0, dirty_index)\n            disps = torch.index_select(video.disps, 0, dirty_index)\n            Ps = SE3(poses).inv().matrix().cpu().numpy()\n\n            images = torch.index_select(video.images, 0, dirty_index)\n            images = images.cpu()[:,[2,1,0],3::8,3::8].permute(0,2,3,1) / 255.0\n            points = droid_backends.iproj(SE3(poses).inv().data, disps, video.intrinsics[0]).cpu()\n\n            thresh = droid_visualization.filter_thresh * torch.ones_like(disps.mean(dim=[1,2]))\n            \n            count = droid_backends.depth_filter(\n                video.poses, video.disps, video.intrinsics[0], dirty_index, thresh)\n\n            count = count.cpu()\n            disps = disps.cpu()\n            masks = ((count >= 2) & (disps > .5*disps.mean(dim=[1,2], keepdim=True)))\n            \n            for i in range(len(dirty_index)):\n                pose = Ps[i]\n                ix = dirty_index[i].item()\n\n                if ix in droid_visualization.cameras:\n                    vis.remove_geometry(droid_visualization.cameras[ix])\n                    del droid_visualization.cameras[ix]\n\n                if ix in droid_visualization.points:\n                    vis.remove_geometry(droid_visualization.points[ix])\n                    del droid_visualization.points[ix]\n\n                ### add camera actor ###\n                cam_actor = create_camera_actor(True)\n                cam_actor.transform(pose)\n                vis.add_geometry(cam_actor)\n                droid_visualization.cameras[ix] = cam_actor\n\n                mask = masks[i].reshape(-1)\n                pts = points[i].reshape(-1, 3)[mask].cpu().numpy()\n                clr = images[i].reshape(-1, 3)[mask].cpu().numpy()\n                \n                ## add point actor ###\n                point_actor = create_point_actor(pts, clr)\n                vis.add_geometry(point_actor)\n                droid_visualization.points[ix] = point_actor\n\n            # hack to allow interacting with vizualization during inference\n            if len(droid_visualization.cameras) >= droid_visualization.warmup:\n                cam = vis.get_view_control().convert_from_pinhole_camera_parameters(cam)\n\n            droid_visualization.ix += 1\n            vis.poll_events()\n            vis.update_renderer()\n\n    ### create Open3D visualization ###\n    vis = o3d.visualization.VisualizerWithKeyCallback()\n    vis.register_animation_callback(animation_callback)\n    vis.register_key_callback(ord(\"S\"), increase_filter)\n    vis.register_key_callback(ord(\"A\"), decrease_filter)\n\n    vis.create_window(height=540, width=960)\n    vis.get_render_option().load_from_json(\"misc/renderoption.json\")\n\n    vis.run()\n    vis.destroy_window()\n"
  },
  {
    "path": "VO_Module/environment.yaml",
    "content": "name: droidenv\nchannels:\n  - rusty1s\n  - pytorch\n  - open3d-admin\n  - nvidia\n  - conda-forge\n  - defaults\ndependencies:\n  - pytorch-scatter\n  - torchaudio\n  - torchvision\n  - open3d\n  - pytorch\n  - cudatoolkit\n  - tensorboard\n  - scipy\n  - opencv\n  - tqdm\n  - suitesparse\n  - matplotlib\n  - pyyaml\n"
  },
  {
    "path": "VO_Module/environment_novis.yaml",
    "content": "name: droidenv\nchannels:\n  - rusty1s\n  - pytorch\n  - nvidia\n  - conda-forge\n  - defaults\ndependencies:\n  - pytorch-scatter\n  - torchaudio\n  - torchvision\n  - pytorch\n  - cudatoolkit=11.1\n  - tensorboard\n  - scipy\n  - opencv\n  - tqdm\n  - suitesparse\n  - matplotlib\n  - pyyaml\n"
  },
  {
    "path": "VO_Module/evaluation_scripts/flow_vis_utils.py",
    "content": "# Flow visualization code used from https://github.com/tomrunia/OpticalFlow_Visualization\n\n\n# MIT License\n#\n# Copyright (c) 2018 Tom Runia\n#\n# Permission is hereby granted, free of charge, to any person obtaining a copy\n# of this software and associated documentation files (the \"Software\"), to deal\n# in the Software without restriction, including without limitation the rights\n# to use, copy, modify, merge, publish, distribute, sublicense, and/or sell\n# copies of the Software, and to permit persons to whom the Software is\n# furnished to do so, subject to conditions.\n#\n# Author: Tom Runia\n# Date Created: 2018-08-03\n\nimport numpy as np\n\ndef make_colorwheel():\n    \"\"\"\n    Generates a color wheel for optical flow visualization as presented in:\n        Baker et al. \"A Database and Evaluation Methodology for Optical Flow\" (ICCV, 2007)\n        URL: http://vision.middlebury.edu/flow/flowEval-iccv07.pdf\n    Code follows the original C++ source code of Daniel Scharstein.\n    Code follows the the Matlab source code of Deqing Sun.\n    Returns:\n        np.ndarray: Color wheel\n    \"\"\"\n\n    RY = 15\n    YG = 6\n    GC = 4\n    CB = 11\n    BM = 13\n    MR = 6\n\n    ncols = RY + YG + GC + CB + BM + MR\n    colorwheel = np.zeros((ncols, 3))\n    col = 0\n\n    # RY\n    colorwheel[0:RY, 0] = 255\n    colorwheel[0:RY, 1] = np.floor(255*np.arange(0,RY)/RY)\n    col = col+RY\n    # YG\n    colorwheel[col:col+YG, 0] = 255 - np.floor(255*np.arange(0,YG)/YG)\n    colorwheel[col:col+YG, 1] = 255\n    col = col+YG\n    # GC\n    colorwheel[col:col+GC, 1] = 255\n    colorwheel[col:col+GC, 2] = np.floor(255*np.arange(0,GC)/GC)\n    col = col+GC\n    # CB\n    colorwheel[col:col+CB, 1] = 255 - np.floor(255*np.arange(CB)/CB)\n    colorwheel[col:col+CB, 2] = 255\n    col = col+CB\n    # BM\n    colorwheel[col:col+BM, 2] = 255\n    colorwheel[col:col+BM, 0] = np.floor(255*np.arange(0,BM)/BM)\n    col = col+BM\n    # MR\n    colorwheel[col:col+MR, 2] = 255 - np.floor(255*np.arange(MR)/MR)\n    colorwheel[col:col+MR, 0] = 255\n    return colorwheel\n\n\ndef flow_uv_to_colors(u, v, convert_to_bgr=False):\n    \"\"\"\n    Applies the flow color wheel to (possibly clipped) flow components u and v.\n    According to the C++ source code of Daniel Scharstein\n    According to the Matlab source code of Deqing Sun\n    Args:\n        u (np.ndarray): Input horizontal flow of shape [H,W]\n        v (np.ndarray): Input vertical flow of shape [H,W]\n        convert_to_bgr (bool, optional): Convert output image to BGR. Defaults to False.\n    Returns:\n        np.ndarray: Flow visualization image of shape [H,W,3]\n    \"\"\"\n    flow_image = np.zeros((u.shape[0], u.shape[1], 3), np.uint8)\n    colorwheel = make_colorwheel()  # shape [55x3]\n    ncols = colorwheel.shape[0]\n    rad = np.sqrt(np.square(u) + np.square(v))\n    a = np.arctan2(-v, -u)/np.pi\n    fk = (a+1) / 2*(ncols-1)\n    k0 = np.floor(fk).astype(np.int32)\n    k1 = k0 + 1\n    k1[k1 == ncols] = 0\n    f = fk - k0\n    for i in range(colorwheel.shape[1]):\n        tmp = colorwheel[:,i]\n        col0 = tmp[k0] / 255.0\n        col1 = tmp[k1] / 255.0\n        col = (1-f)*col0 + f*col1\n        idx = (rad <= 1)\n        col[idx]  = 1 - rad[idx] * (1-col[idx])\n        col[~idx] = col[~idx] * 0.75   # out of range\n        # Note the 2-i => BGR instead of RGB\n        ch_idx = 2-i if convert_to_bgr else i\n        flow_image[:,:,ch_idx] = np.floor(255 * col)\n    return flow_image\n\n\ndef flow_to_image(flow_uv, clip_flow=None, convert_to_bgr=False):\n    \"\"\"\n    Expects a two dimensional flow image of shape.\n    Args:\n        flow_uv (np.ndarray): Flow UV image of shape [H,W,2]\n        clip_flow (float, optional): Clip maximum of flow values. Defaults to None.\n        convert_to_bgr (bool, optional): Convert output image to BGR. Defaults to False.\n    Returns:\n        np.ndarray: Flow visualization image of shape [H,W,3]\n    \"\"\"\n    assert flow_uv.ndim == 3, 'input flow must have three dimensions'\n    assert flow_uv.shape[2] == 2, 'input flow must have shape [H,W,2]'\n    if clip_flow is not None:\n        flow_uv = np.clip(flow_uv, 0, clip_flow)\n    u = flow_uv[:,:,0]\n    v = flow_uv[:,:,1]\n    rad = np.sqrt(np.square(u) + np.square(v))\n    rad_max = np.max(rad)\n    epsilon = 1e-5\n    u = u / (rad_max + epsilon)\n    v = v / (rad_max + epsilon)\n    # print(np.unique(u))\n    return flow_uv_to_colors(u, v, convert_to_bgr)\n\ndef writeFlow(filename,uv,v=None):\n    \"\"\" Write optical flow to file.\n    \n    If v is None, uv is assumed to contain both u and v channels,\n    stacked in depth.\n    Original code by Deqing Sun, adapted from Daniel Scharstein.\n    \"\"\"\n    nBands = 2\n\n    if v is None:\n        assert(uv.ndim == 3)\n        assert(uv.shape[2] == 2)\n        u = uv[:,:,0]\n        v = uv[:,:,1]\n    else:\n        u = uv\n\n    assert(u.shape == v.shape)\n    height,width = u.shape\n    f = open(filename,'wb')\n    # write the header\n    f.write(TAG_CHAR)\n    np.array(width).astype(np.int32).tofile(f)\n    np.array(height).astype(np.int32).tofile(f)\n    # arrange into matrix form\n    tmp = np.zeros((height, width*nBands))\n    tmp[:,np.arange(width)*2] = u\n    tmp[:,np.arange(width)*2 + 1] = v\n    tmp.astype(np.float32).tofile(f)\n    f.close()"
  },
  {
    "path": "VO_Module/evaluation_scripts/test_vo.py",
    "content": "import sys\nsys.path.append('VO_Module/droid_slam')\nfrom droid import Droid\n\nimport glob\nimport torch.nn.functional as F\nimport argparse\nimport time\nimport os\nimport cv2\nimport lietorch\nimport torch\nimport numpy as np\nfrom tqdm import tqdm\n\nfrom panopticapi.utils import  rgb2id, id2rgb\nimport PIL.Image as Image\n\ndef image_stream(datapath, image_size=[240, 808], mode='train', args=None):  # -------------------------------------------\n    \"\"\" image generator \"\"\"\n    fx, fy, cx, cy = 725.0087, 725.0087, 620.5, 187\n\n    split = {\n        'train': 'clone',\n        'val': '15-deg-left',\n        'test': '30-deg-right'\n    }\n    images = np.array(sorted(glob.glob(os.path.join(datapath, split[mode], 'frames/rgb/Camera_0/*.jpg'))))\n    segments_list = sorted(glob.glob(os.path.join(datapath, split[mode], 'panFPN_segm/*.png'))) \n    \n    images_list = images.tolist() \n    print(\"-----test images :\", len(images_list))\n    segm = None\n    for t, imfile in enumerate(images_list):\n        image = cv2.imread(imfile)\n\n        h0, w0, _ = image.shape\n        h1, w1 = image_size[0], image_size[1]\n\n        image = cv2.resize(image, (w1, h1))\n        image = image[:h1-h1 % 8, :w1-w1 % 8]\n        image = torch.as_tensor(image).int().permute(2, 0, 1)\n\n        if args.segm_filter:\n            segm = rgb2id(np.array(Image.open(segments_list[t])))\n            segm = torch.as_tensor(segm).unsqueeze(0).unsqueeze(0).float()\n            segm = F.interpolate(segm, size=(h1,w1))\n            segm = segm[:h1-h1 % 8, :w1-w1 % 8]\n            segm = F.interpolate(segm, scale_factor=1/8,\n                            recompute_scale_factor=True).int()\n\n        intrinsics = torch.as_tensor([fx, fy, cx, cy])\n        intrinsics[0:2] *= (w1 / w0)\n        intrinsics[2:4] *= (h1 / h0)\n        \n        yield t, image, intrinsics , segm\n\ndef init():\n    parser = argparse.ArgumentParser()\n    parser.add_argument('--datapath')\n    parser.add_argument(\"--device\", default=\"cuda:0\")\n    parser.add_argument(\"--weights\", default=\"checkpoints/vkitti2_dy_train_semiv4_080000.pth\")\n    parser.add_argument(\"--buffer\", type=int, default=1024)\n    parser.add_argument(\"--image_size\", default=[240, 808])\n    parser.add_argument(\"--disable_vis\", action=\"store_true\")\n    parser.add_argument(\"--use_aff_bri\", type=bool, default=False)\n\n    parser.add_argument(\"--beta\", type=float, default=0.6)\n    parser.add_argument(\"--filter_thresh\", type=float, default=1.75)\n    parser.add_argument(\"--warmup\", type=int, default=12)\n    parser.add_argument(\"--keyframe_thresh\", type=float, default=2.25)\n    parser.add_argument(\"--frontend_thresh\", type=float, default=12.0)\n    parser.add_argument(\"--frontend_window\", type=int, default=25)\n    # 2\n    parser.add_argument(\"--frontend_radius\", type=int, default=2)\n    parser.add_argument(\"--frontend_nms\", type=int, default=1)\n\n    parser.add_argument(\"--backend_thresh\", type=float, default=15.0)\n    parser.add_argument(\"--backend_radius\", type=int, default=2)\n    parser.add_argument(\"--backend_nms\", type=int, default=3)\n\n    parser.add_argument(\"--segm_filter\", type=bool, default=False, help=\"if filter weight with segmentaion in factory graph\")\n    parser.add_argument(\"--thresh\", type=float, default=0.8)\n\n    args = parser.parse_args()\n    return args\n\nif __name__ == '__main__':\n    args = init()\n    # os.environ[\"CUDA_VISIBLE_DEVICES\"] = args.device.split(':')[-1]\n    torch.multiprocessing.set_start_method('spawn')\n\n    print(\"Running evaluation on {}\".format(args.datapath))\n    print(args)\n\n    if args.datapath[-2:] == \"20\":\n        args.thresh = 0.9\n\n    droid = Droid(args)\n    time.sleep(5)\n\n    print(\"segm_filter: \",args.segm_filter)\n\n    for (t, image, intrinsics, segm) in tqdm(image_stream(args.datapath, mode='val', args=args)):\n        droid.track(t, image, intrinsics=intrinsics, segments=segm)\n\n    print(\"video frames: \", droid.video.counter.value)\n    traj_est = droid.terminate(image_stream(args.datapath, mode='val', args=args), need_inv=True)\n\n    ### run evaluation ###\n    print(\"#\"*20 + \" Results...\")\n\n    import evo\n    from evo.core.trajectory import PoseTrajectory3D\n    from evo.core.trajectory import PosePath3D\n    from evo.tools import file_interface\n    from evo.core import sync\n    import evo.main_ape as main_ape\n    from evo.core.metrics import PoseRelation\n\n    def read_vkitti2_poses_file(file_path, args) -> PosePath3D:\n        \"\"\"\n        parses pose file in Virtual KITTI 2 format (first 3 rows of SE(3) matrix per line)\n        :param file_path: the trajectory file path (or file handle)\n        :return: trajectory.PosePath3D\n        \"\"\"\n        raw_mat = np.loadtxt(file_path, delimiter=' ', skiprows=1)[::2, 2:]\n        error_msg = (\"Virtual KITTI 2 pose files must have 16 entries per row \"\n                     \"and no trailing delimiter at the end of the rows (space)\")\n        if raw_mat is None or (len(raw_mat) > 0 and len(raw_mat[0]) != 16):\n            raise file_interface.FileInterfaceException(error_msg)\n        try:\n            mat = np.array(raw_mat).astype(float)\n        except ValueError:\n            raise file_interface.FileInterfaceException(error_msg)\n        poses = [np.linalg.inv(np.array([[r[0], r[1], r[2], r[3]],\n                                         [r[4], r[5], r[6], r[7]],\n                                         [r[8], r[9], r[10], r[11]],\n                                         [r[12], r[13], r[14], r[15]]])) for r in mat]\n\n        # yapf: enable\n        if not hasattr(file_path, 'read'):  # if not file handle\n            print(\"Loaded {} poses from: {}\".format(len(poses), file_path))\n        return PosePath3D(poses_se3=poses)\n\n    gt_file = os.path.join(args.datapath, '15-deg-left/extrinsic.txt')\n    traj_ref = read_vkitti2_poses_file(gt_file, args)\n\n    traj_est = PosePath3D(\n        positions_xyz=traj_est[:, :3],\n        orientations_quat_wxyz=traj_est[:, 3:])\n    \n    root = 'shared_data/traj/'\n    root = os.path.join(root, args.datapath.rsplit('/')[-1])\n    root = os.path.join(root, '15-deg-left')\n    if not os.path.isdir(root):\n        os.makedirs(root)\n    est_file = os.path.join(root,  'pvo_traj.txt')\n    print(est_file)\n\n    file_interface.write_kitti_poses_file(est_file, traj_est)\n    result = main_ape.ape(traj_ref, traj_est, est_name='traj',\n                          pose_relation=PoseRelation.translation_part, align=True, correct_scale=True)\n    print(result)\n    "
  },
  {
    "path": "VO_Module/evaluation_scripts/test_vo2.py",
    "content": "import sys\nsys.path.append('VO_Module/droid_slam')\n\nimport torch\nfrom torch.utils.data import DataLoader\nimport glob\nimport os\nimport os.path as osp\nimport cv2\nimport numpy as np\nimport torch.nn.functional as F\nfrom scipy.spatial.transform import Rotation as R\nfrom collections import OrderedDict\nfrom lietorch import SE3\nfrom flow_vis_utils import flow_to_image\nfrom geom.projective_ops import projective_transform, coords_grid\nfrom geom.graph_utils import graph_to_edge_list\nfrom droid_net import DroidNet, upsample_inter\nfrom data_readers.factory import dataset_factory\nimport data_readers.vkitti2\nimport argparse\n\ndef resize(mask, size, need_permute):\n    if need_permute:\n        mask = mask.permute(0, 1, 4, 2, 3).contiguous()\n    batch, num, dim, ht, wd = mask.shape\n    mask = mask.view(batch*num, dim, ht, wd)\n    mask = F.interpolate(mask, size=size, mode='bilinear', align_corners=True)\n    if need_permute:\n        mask = mask.permute(0, 2, 3, 1).contiguous()\n        return mask.view(batch, num, size[0], size[1], dim)\n    else:\n        return mask.view(batch, num, dim, size[0], size[1])\n\ndic = { \"Scene01\":\"0001\",\n        \"Scene02\":\"0002\",\n        \"Scene06\":\"0006\",\n        \"Scene18\":\"0018\",\n        \"Scene20\":\"0020\",}\n\ndef init():\n    parser = argparse.ArgumentParser()\n    parser.add_argument(\"--n_frames\", type=int, default=2)\n    parser.add_argument(\"--save_npy\", type=bool, default=True, help=\"save flow and depth\")\n    parser.add_argument(\"--image_size\", default=[376, 1248])\n\n    parser.add_argument(\"--scene\", default=\"Scene02\")\n    parser.add_argument(\"--full_flow_dir\", default=\"shared_data/full_flow\")\n    parser.add_argument(\"--depth_dir\", default=\"shared_data/depth\")\n    parser.add_argument(\"--weights_file\", default=\"checkpoints/vkitti2_dy_train_semiv4_080000.pth\")\n\n    args = parser.parse_args()\n    return args\n\nif __name__ == '__main__':\n    args = init()\n    full_flow_dir = args.full_flow_dir\n    depth_dir = args.depth_dir\n    img_size = args.image_size\n    n_frames = args.n_frames\n    scene_id = args.scene\n    save_npy = args.save_npy\n    if not osp.exists(full_flow_dir):\n        os.makedirs(full_flow_dir)\n    if not osp.exists(depth_dir):\n        os.makedirs(depth_dir)\n\n    db = dataset_factory(['vkitti2'], datapath='datasets/Virtual_KITTI2', do_aug=False,\n                     n_frames=n_frames, flow_label=False, aug_graph=False, split_mode='train', foo=True,\n                     scene_id = scene_id,\n                     need_inv=False, build_mask=False, crop_size=img_size, mode='semisup',\n                     rebuild=True, \n                     )\n    train_loader = DataLoader(db, batch_size=1, num_workers=2)\n\n    device = 'cuda:0'\n    torch.cuda.set_device(int(device.split(':')[-1]))\n\n    graph = OrderedDict()\n    for i in range(n_frames):\n        graph[i] = [j for j in range(n_frames) if abs(i-j) == 1]\n    ii, jj, _ = graph_to_edge_list(graph)\n\n    model = DroidNet()\n    state_dict = OrderedDict([(k.replace(\"module.\", \"\"), v) for (k, v) in torch.load(args.weights_file, device).items()])\n    model.load_state_dict(state_dict)\n    model.to(device).eval()\n    \n    coords0 = coords_grid(img_size[0], img_size[1], device=device)\n\n    Gs = None\n    disps_est = None\n    for i_batch, item in enumerate(train_loader):\n        images, poses, disps, intrinsics, gt_masks, gt_vals, segments = [ x.to('cuda') for x in item if type(x) != list]\n        file1, file2 = item[0]\n        hr, wr = img_size[0]/images.shape[3], img_size[1]/images.shape[4]\n        intrinsics[:, :, 0] *= wr\n        intrinsics[:, :, 2] *= wr\n        intrinsics[:, :, 1] *= hr\n        intrinsics[:, :, 3] *= hr\n        images = resize(images, img_size, False)\n        disps = resize(disps.unsqueeze(2), img_size, False).squeeze(2)\n        gt_masks = resize(gt_masks, img_size, True)\n        gt_vals = resize(gt_vals, img_size, True)\n\n        Gs = SE3(poses)\n        disp0 = torch.ones_like(disps[:, :, 3::8, 3::8]) # 1x2x48x156\n\n        for _ in range(1):\n            poses_est, disps_est, residuals, full_flows, masks = \\\n                model(Gs, images, disp0, intrinsics/8,\n                    graph, num_steps=15, fixedp=2,\n                    ret_flow=True, downsample=True)\n            Gs = poses_est[-1]\n            disp0 = disps_est[-1][:, :, 3::8, 3::8]\n\n        coords1, val0 = projective_transform(\n            poses_est[-1], disps_est[-1], intrinsics, ii, jj)\n\n        cam_flow = (coords1-coords0)[0, 0]\n        full_flow = (upsample_inter(full_flows[-1]*8))[0, 0]\n        resd = full_flow-cam_flow\n        mask = (masks[-1][0, 0].mean(-1, keepdim=True) >= 0.5).float()\n\n        img_id = dic[scene_id] + '_' + file1[0].rsplit('_')[-1][:-4]\n        print(img_id)\n\n        full_flow_np = full_flow.detach().cpu().numpy()\n        full_flow_1 = full_flow_np*gt_vals[0,0].cpu().numpy()\n\n        if save_npy:\n            full_flow_1 = cv2.resize(full_flow_1, (375, 1242))\n            np.save(osp.join(full_flow_dir, img_id +'.npy'), full_flow_1)\n        \n            depth = disps_est[-1][0, 0].detach().cpu().numpy()\n            np.save(osp.join(depth_dir, img_id +'.npy'), depth)\n\n    print('Finished building %d img with flows' % i_batch)\n\ndepth = disps_est[-1][0, 1].detach().cpu().numpy()\nint_id = int(img_id[-2]) * 10 + int(img_id[-1]) + 1\nimg_id = img_id[:-2] + str(int_id)\nnp.save(osp.join(depth_dir, img_id +'.npy'), depth)\nprint(img_id)"
  },
  {
    "path": "VO_Module/setup.py",
    "content": "from setuptools import setup\nfrom torch.utils.cpp_extension import BuildExtension, CUDAExtension\n\nimport os.path as osp\nROOT = osp.dirname(osp.abspath(__file__))\n\nsetup(\n    name='droid_backends',\n    ext_modules=[\n        CUDAExtension('droid_backends',\n            include_dirs=[osp.join(ROOT, 'thirdparty/eigen')],\n            sources=[\n                'src/droid.cpp', \n                'src/droid_kernels.cu',\n                'src/correlation_kernels.cu',\n                'src/altcorr_kernel.cu',\n            ],\n            extra_compile_args={\n                'cxx': ['-O3'],\n                'nvcc': ['-O3',\n                    '-gencode=arch=compute_60,code=sm_60',\n                    '-gencode=arch=compute_61,code=sm_61',\n                    '-gencode=arch=compute_70,code=sm_70',\n                    '-gencode=arch=compute_75,code=sm_75',\n                    # if wrong please comment out following\n                    # This depends on your device's Computing Power\n                    '-gencode=arch=compute_80,code=sm_80',\n                    '-gencode=arch=compute_86,code=sm_86',\n                ]\n            }),\n    ],\n    cmdclass={ 'build_ext' : BuildExtension }\n)\n\nsetup(\n    name='lietorch',\n    version='0.2',\n    description='Lie Groups for PyTorch',\n    packages=['lietorch'],\n    package_dir={'': 'thirdparty/lietorch'},\n    ext_modules=[\n        CUDAExtension('lietorch_backends', \n            include_dirs=[\n                osp.join(ROOT, 'thirdparty/lietorch/lietorch/include'), \n                osp.join(ROOT, 'thirdparty/eigen')],\n            sources=[\n                'thirdparty/lietorch/lietorch/src/lietorch.cpp', \n                'thirdparty/lietorch/lietorch/src/lietorch_gpu.cu',\n                'thirdparty/lietorch/lietorch/src/lietorch_cpu.cpp'],\n            extra_compile_args={\n                'cxx': ['-O2'], \n                'nvcc': ['-O2',\n                    '-gencode=arch=compute_60,code=sm_60', \n                    '-gencode=arch=compute_61,code=sm_61', \n                    '-gencode=arch=compute_70,code=sm_70', \n                    '-gencode=arch=compute_75,code=sm_75',\n                    # if wrong please comment out following\n                    # This depends on your device's Computing Power\n                    '-gencode=arch=compute_80,code=sm_80',\n                    '-gencode=arch=compute_86,code=sm_86',                 \n                ]\n            }),\n    ],\n    cmdclass={ 'build_ext' : BuildExtension }\n)\n"
  },
  {
    "path": "VO_Module/src/altcorr_kernel.cu",
    "content": "#include <torch/extension.h>\n#include <cuda.h>\n#include <cuda_runtime.h>\n#include <vector>\n#include <cuda_fp16.h>\n#include <cuda_runtime.h>\n\n\n#include <ATen/ATen.h>\n#include <ATen/NativeFunctions.h>\n#include <ATen/cuda/CUDAApplyUtils.cuh>\n#include <ATen/native/cuda/KernelUtils.cuh>\n\n\n\n#define BLOCK_H 4\n#define BLOCK_W 8\n#define BLOCK_HW BLOCK_H * BLOCK_W\n#define CHANNEL_STRIDE 32\n\n\n__forceinline__ __device__\nbool within_bounds(int h, int w, int H, int W) {\n  return h >= 0 && h < H && w >= 0 && w < W;\n}\n\ntemplate <typename scalar_t>\n__global__ void altcorr_forward_kernel(\n    const torch::PackedTensorAccessor32<scalar_t,4,torch::RestrictPtrTraits> fmap1,\n    const torch::PackedTensorAccessor32<scalar_t,4,torch::RestrictPtrTraits> fmap2,\n    const torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> coords,\n    torch::PackedTensorAccessor32<scalar_t,5,torch::RestrictPtrTraits> corr,\n    int r)\n{\n  const int b = blockIdx.x;\n  const int h0 = blockIdx.y * blockDim.x;\n  const int w0 = blockIdx.z * blockDim.y;\n  const int tid = threadIdx.x * blockDim.y + threadIdx.y;\n\n  const int H1 = fmap1.size(1);\n  const int W1 = fmap1.size(2);\n  const int H2 = fmap2.size(1);\n  const int W2 = fmap2.size(2);\n  const int N = coords.size(1);\n  const int C = fmap1.size(3);\n\n  __shared__ scalar_t f1[CHANNEL_STRIDE][BLOCK_HW];\n  __shared__ scalar_t f2[CHANNEL_STRIDE][BLOCK_HW];\n  \n  __shared__ float x2s[BLOCK_HW];\n  __shared__ float y2s[BLOCK_HW];\n\n  for (int c=0; c<C; c+=CHANNEL_STRIDE) {\n    for (int k=0; k<BLOCK_HW; k+=BLOCK_HW/CHANNEL_STRIDE) {\n      int k1 = k + tid / CHANNEL_STRIDE;\n      int h1 = h0 + k1 / BLOCK_W;\n      int w1 = w0 + k1 % BLOCK_W;\n      int c1 = tid % CHANNEL_STRIDE;\n\n      if (within_bounds(h1, w1, H1, W1))\n        f1[c1][k1] = fmap1[b][h1][w1][c+c1];\n      \n      else\n        f1[c1][k1] = 0.0;\n    }\n\n    __syncthreads();\n\n    for (int n=0; n<N; n++) {\n      int h1 = h0 + threadIdx.x;\n      int w1 = w0 + threadIdx.y;\n      if (within_bounds(h1, w1, H1, W1)) {\n        x2s[tid] = coords[b][n][h1][w1][0];\n        y2s[tid] = coords[b][n][h1][w1][1];\n      }\n\n      float dx = x2s[tid] - floor(x2s[tid]);\n      float dy = y2s[tid] - floor(y2s[tid]);\n\n      int rd = 2*r + 1;\n      for (int iy=0; iy<rd+1; iy++) {\n        for (int ix=0; ix<rd+1; ix++) {\n          for (int k=0; k<BLOCK_HW; k+=BLOCK_HW/CHANNEL_STRIDE) {\n            int k1 = k + tid / CHANNEL_STRIDE;\n            int h2 = static_cast<int>(floor(y2s[k1])) - r + iy;\n            int w2 = static_cast<int>(floor(x2s[k1])) - r + ix;\n            int c2 = tid % CHANNEL_STRIDE;\n\n            if (within_bounds(h2, w2, H2, W2))\n              f2[c2][k1] = fmap2[b][h2][w2][c+c2];\n            \n            else\n              f2[c2][k1] = static_cast<scalar_t>(0.0);\n          }\n\n          __syncthreads();\n      \n          scalar_t s = 0.0;\n          for (int k=0; k<CHANNEL_STRIDE; k++)\n            s += f1[k][tid] * f2[k][tid];\n\n          int ix_nw = H1*W1*((iy-1) + rd*(ix-1));\n          int ix_ne = H1*W1*((iy-1) + rd*ix);\n          int ix_sw = H1*W1*(iy + rd*(ix-1));\n          int ix_se = H1*W1*(iy + rd*ix);\n\n          // int ix_nw = ((iy-1) + rd*(ix-1));\n          // int ix_ne = ((iy-1) + rd*ix);\n          // int ix_sw = (iy + rd*(ix-1));\n          // int ix_se = (iy + rd*ix);\n\n          scalar_t nw = s * static_cast<scalar_t>((dy) * (dx));\n          scalar_t ne = s * static_cast<scalar_t>((dy) * (1-dx));\n          scalar_t sw = s * static_cast<scalar_t>((1-dy) * (dx));\n          scalar_t se = s * static_cast<scalar_t>((1-dy) * (1-dx));\n\n          // if (iy > 0 && ix > 0 && within_bounds(h1, w1, H1, W1))\n          //   corr[b][n][ix_nw][h1][w1] += nw;\n\n          // if (iy > 0 && ix < rd && within_bounds(h1, w1, H1, W1))\n          //   corr[b][n][ix_ne][h1][w1] += ne;\n\n          // if (iy < rd && ix > 0 && within_bounds(h1, w1, H1, W1))\n          //   corr[b][n][ix_sw][h1][w1] += sw;\n\n          // if (iy < rd && ix < rd && within_bounds(h1, w1, H1, W1))\n          //   corr[b][n][ix_se][h1][w1] += se;\n\n\n          scalar_t* corr_ptr = &corr[b][n][0][h1][w1];\n\n          if (iy > 0 && ix > 0 && within_bounds(h1, w1, H1, W1))\n            *(corr_ptr + ix_nw) += nw;\n\n          if (iy > 0 && ix < rd && within_bounds(h1, w1, H1, W1))\n            *(corr_ptr + ix_ne) += ne;\n\n          if (iy < rd && ix > 0 && within_bounds(h1, w1, H1, W1))\n            *(corr_ptr + ix_sw) += sw;\n\n          if (iy < rd && ix < rd && within_bounds(h1, w1, H1, W1))\n            *(corr_ptr + ix_se) += se;\n\n\n        }\n      } \n    }\n  }\n}\n\n\ntemplate <typename scalar_t>\n__global__ void altcorr_backward_kernel(\n    const torch::PackedTensorAccessor32<scalar_t,4,torch::RestrictPtrTraits> fmap1,\n    const torch::PackedTensorAccessor32<scalar_t,4,torch::RestrictPtrTraits> fmap2,\n    const torch::PackedTensorAccessor32<scalar_t,5,torch::RestrictPtrTraits> coords,\n    const torch::PackedTensorAccessor32<scalar_t,5,torch::RestrictPtrTraits> corr_grad,\n    torch::PackedTensorAccessor32<scalar_t,4,torch::RestrictPtrTraits> fmap1_grad,\n    torch::PackedTensorAccessor32<scalar_t,4,torch::RestrictPtrTraits> fmap2_grad,\n    torch::PackedTensorAccessor32<scalar_t,5,torch::RestrictPtrTraits> coords_grad,\n    int r)\n{\n\n  const int b = blockIdx.x;\n  const int h0 = blockIdx.y * blockDim.x;\n  const int w0 = blockIdx.z * blockDim.y;\n  const int tid = threadIdx.x * blockDim.y + threadIdx.y;\n\n  const int H1 = fmap1.size(1);\n  const int W1 = fmap1.size(2);\n  const int H2 = fmap2.size(1);\n  const int W2 = fmap2.size(2);\n  const int N = coords.size(1);\n  const int C = fmap1.size(3);\n\n  __shared__ scalar_t f1[CHANNEL_STRIDE][BLOCK_HW+1];\n  __shared__ scalar_t f2[CHANNEL_STRIDE][BLOCK_HW+1];\n\n  __shared__ scalar_t f1_grad[CHANNEL_STRIDE][BLOCK_HW+1];\n  __shared__ scalar_t f2_grad[CHANNEL_STRIDE][BLOCK_HW+1];\n\n  __shared__ scalar_t x2s[BLOCK_HW];\n  __shared__ scalar_t y2s[BLOCK_HW];\n\n  for (int c=0; c<C; c+=CHANNEL_STRIDE) {\n\n    for (int k=0; k<BLOCK_HW; k+=BLOCK_HW/CHANNEL_STRIDE) {\n      int k1 = k + tid / CHANNEL_STRIDE;\n      int h1 = h0 + k1 / BLOCK_W;\n      int w1 = w0 + k1 % BLOCK_W;\n      int c1 = tid % CHANNEL_STRIDE;\n\n      auto fptr = fmap1[b][h1][w1];\n      if (within_bounds(h1, w1, H1, W1))\n        f1[c1][k1] = fptr[c+c1];\n      else\n        f1[c1][k1] = 0.0;\n\n      f1_grad[c1][k1] = 0.0;\n    }\n\n    __syncthreads();\n\n    int h1 = h0 + threadIdx.x;\n    int w1 = w0 + threadIdx.y;\n\n    for (int n=0; n<N; n++) {  \n      x2s[tid] = coords[b][n][h1][w1][0];\n      y2s[tid] = coords[b][n][h1][w1][1];\n\n      scalar_t dx = x2s[tid] - floor(x2s[tid]);\n      scalar_t dy = y2s[tid] - floor(y2s[tid]);\n\n      int rd = 2*r + 1;\n      for (int iy=0; iy<rd+1; iy++) {\n        for (int ix=0; ix<rd+1; ix++) {\n          for (int k=0; k<BLOCK_HW; k+=BLOCK_HW/CHANNEL_STRIDE) {\n            int k1 = k + tid / CHANNEL_STRIDE;\n            int h2 = static_cast<int>(floor(y2s[k1]))-r+iy;\n            int w2 = static_cast<int>(floor(x2s[k1]))-r+ix;\n            int c2 = tid % CHANNEL_STRIDE;\n\n            auto fptr = fmap2[b][h2][w2];\n            if (within_bounds(h2, w2, H2, W2))\n              f2[c2][k1] = fptr[c+c2];\n            else\n              f2[c2][k1] = 0.0;\n\n            f2_grad[c2][k1] = 0.0;\n          }\n\n          __syncthreads();\n      \n          const scalar_t* grad_ptr = &corr_grad[b][n][0][h1][w1];\n          scalar_t g = 0.0;\n\n          int ix_nw = H1*W1*((iy-1) + rd*(ix-1));\n          int ix_ne = H1*W1*((iy-1) + rd*ix);\n          int ix_sw = H1*W1*(iy + rd*(ix-1));\n          int ix_se = H1*W1*(iy + rd*ix);\n\n          if (iy > 0 && ix > 0 && within_bounds(h1, w1, H1, W1))\n            g +=  *(grad_ptr + ix_nw) * dy * dx;\n\n          if (iy > 0 && ix < rd && within_bounds(h1, w1, H1, W1))\n            g += *(grad_ptr + ix_ne) * dy * (1-dx);\n\n          if (iy < rd && ix > 0 && within_bounds(h1, w1, H1, W1))\n            g += *(grad_ptr + ix_sw) * (1-dy) * dx;\n\n          if (iy < rd && ix < rd && within_bounds(h1, w1, H1, W1))\n            g += *(grad_ptr + ix_se) * (1-dy) * (1-dx);\n            \n          for (int k=0; k<CHANNEL_STRIDE; k++) {\n            f1_grad[k][tid] += g * f2[k][tid];\n            f2_grad[k][tid] += g * f1[k][tid];\n          }\n\n          for (int k=0; k<BLOCK_HW; k+=BLOCK_HW/CHANNEL_STRIDE) {\n            int k1 = k + tid / CHANNEL_STRIDE;\n            int h2 = static_cast<int>(floor(y2s[k1]))-r+iy;\n            int w2 = static_cast<int>(floor(x2s[k1]))-r+ix;\n            int c2 = tid % CHANNEL_STRIDE;\n\n            scalar_t* fptr = &fmap2_grad[b][h2][w2][0];\n            if (within_bounds(h2, w2, H2, W2))\n              atomicAdd(fptr+c+c2, f2_grad[c2][k1]);\n          }\n        }\n      } \n    }\n    __syncthreads();\n\n\n    for (int k=0; k<BLOCK_HW; k+=BLOCK_HW/CHANNEL_STRIDE) {\n      int k1 = k + tid / CHANNEL_STRIDE;\n      int h1 = h0 + k1 / BLOCK_W;\n      int w1 = w0 + k1 % BLOCK_W;\n      int c1 = tid % CHANNEL_STRIDE;\n\n      scalar_t* fptr = &fmap1_grad[b][h1][w1][0];\n      if (within_bounds(h1, w1, H1, W1))\n        fptr[c+c1] += f1_grad[c1][k1];\n    }\n  }\n}\n\n\n\nstd::vector<torch::Tensor> altcorr_cuda_forward(\n  torch::Tensor fmap1,\n  torch::Tensor fmap2,\n  torch::Tensor coords,\n  int radius)\n{\n  const auto B = coords.size(0);\n  const auto N = coords.size(1);\n  const auto H = coords.size(2);\n  const auto W = coords.size(3);\n\n  const auto rd = 2 * radius + 1;\n  auto opts = fmap1.options();\n  auto corr = torch::zeros({B, N, rd*rd, H, W}, opts);\n  \n  const dim3 blocks(B, (H+BLOCK_H-1)/BLOCK_H, (W+BLOCK_W-1)/BLOCK_W);\n  const dim3 threads(BLOCK_H, BLOCK_W);\n\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(fmap1.type(), \"altcorr_forward_kernel\", ([&] {\n    altcorr_forward_kernel<scalar_t><<<blocks, threads>>>(\n        fmap1.packed_accessor32<scalar_t,4,torch::RestrictPtrTraits>(),\n        fmap2.packed_accessor32<scalar_t,4,torch::RestrictPtrTraits>(),\n        coords.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n        corr.packed_accessor32<scalar_t,5,torch::RestrictPtrTraits>(),\n        radius);\n  }));\n\n  return {corr};\n}\n\nstd::vector<torch::Tensor> altcorr_cuda_backward(\n  torch::Tensor fmap1,\n  torch::Tensor fmap2,\n  torch::Tensor coords,\n  torch::Tensor corr_grad,\n  int radius)\n{\n  const auto B = coords.size(0);\n  const auto N = coords.size(1);\n\n  const auto H1 = fmap1.size(1);\n  const auto W1 = fmap1.size(2);\n  const auto H2 = fmap2.size(1);\n  const auto W2 = fmap2.size(2);\n  const auto C = fmap1.size(3);\n\n  auto opts = fmap1.options();\n  auto fmap1_grad = torch::zeros({B, H1, W1, C}, opts);\n  auto fmap2_grad = torch::zeros({B, H2, W2, C}, opts);\n  auto coords_grad = torch::zeros({B, N, H1, W1, 2}, opts);\n    \n  const dim3 blocks(B, (H1+BLOCK_H-1)/BLOCK_H, (W1+BLOCK_W-1)/BLOCK_W);\n  const dim3 threads(BLOCK_H, BLOCK_W);\n\n  altcorr_backward_kernel<float><<<blocks, threads>>>(\n    fmap1.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    fmap2.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    coords.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    corr_grad.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    fmap1_grad.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    fmap2_grad.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    coords_grad.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    radius);\n\n  return {fmap1_grad, fmap2_grad, coords_grad};\n}"
  },
  {
    "path": "VO_Module/src/correlation_kernels.cu",
    "content": "#include <torch/extension.h>\n#include <cuda.h>\n#include <cuda_runtime.h>\n#include <vector>\n#include <cuda_fp16.h>\n#include <cuda_runtime.h>\n\n\n#include <ATen/ATen.h>\n#include <ATen/NativeFunctions.h>\n#include <ATen/Parallel.h>\n\n#define BLOCK 16\n\n__forceinline__ __device__ bool within_bounds(int h, int w, int H, int W) {\n  return h >= 0 && h < H && w >= 0 && w < W;\n}\n\ntemplate <typename scalar_t>\n__global__ void corr_index_forward_kernel(\n    const torch::PackedTensorAccessor32<scalar_t,5,torch::RestrictPtrTraits> volume,\n    const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> coords,\n    torch::PackedTensorAccessor32<scalar_t,5,torch::RestrictPtrTraits> corr,\n    int r)\n{\n  // batch index\n  const int x = blockIdx.x * blockDim.x + threadIdx.x;\n  const int y = blockIdx.y * blockDim.y + threadIdx.y;\n  const int n = blockIdx.z;\n\n  const int h1 = volume.size(1);\n  const int w1 = volume.size(2);\n  const int h2 = volume.size(3);\n  const int w2 = volume.size(4);\n\n  if (!within_bounds(y, x, h1, w1)) {\n    return;\n  }\n\n  float x0 = coords[n][0][y][x];\n  float y0 = coords[n][1][y][x];\n\n  float dx = x0 - floor(x0);\n  float dy = y0 - floor(y0);\n\n  int rd = 2*r + 1;\n  for (int i=0; i<rd+1; i++) {\n    for (int j=0; j<rd+1; j++) {\n      int x1 = static_cast<int>(floor(x0)) - r + i;\n      int y1 = static_cast<int>(floor(y0)) - r + j;\n\n      if (within_bounds(y1, x1, h2, w2)) {\n        scalar_t s = volume[n][y][x][y1][x1];\n\n        if (i > 0 && j > 0)\n          corr[n][i-1][j-1][y][x] += s * scalar_t(dx * dy);\n\n        if (i > 0 && j < rd)\n          corr[n][i-1][j][y][x] += s * scalar_t(dx * (1.0f-dy));\n\n        if (i < rd && j > 0)\n          corr[n][i][j-1][y][x] += s * scalar_t((1.0f-dx) * dy);\n\n        if (i < rd && j < rd)\n          corr[n][i][j][y][x] += s * scalar_t((1.0f-dx) * (1.0f-dy));\n\n      }\n    }\n  }\n}\n\n\ntemplate <typename scalar_t>\n__global__ void corr_index_backward_kernel(\n    const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> coords,\n    const torch::PackedTensorAccessor32<scalar_t,5,torch::RestrictPtrTraits> corr_grad,\n    torch::PackedTensorAccessor32<scalar_t,5,torch::RestrictPtrTraits> volume_grad,\n    int r)\n{\n  // batch index\n  const int x = blockIdx.x * blockDim.x + threadIdx.x;\n  const int y = blockIdx.y * blockDim.y + threadIdx.y;\n  const int n = blockIdx.z;\n\n  const int h1 = volume_grad.size(1);\n  const int w1 = volume_grad.size(2);\n  const int h2 = volume_grad.size(3);\n  const int w2 = volume_grad.size(4);\n\n  if (!within_bounds(y, x, h1, w1)) {\n    return;\n  }\n\n  float x0 = coords[n][0][y][x];\n  float y0 = coords[n][1][y][x];\n\n  float dx = x0 - floor(x0);\n  float dy = y0 - floor(y0);\n\n  int rd = 2*r + 1;\n  for (int i=0; i<rd+1; i++) {\n    for (int j=0; j<rd+1; j++) {\n      int x1 = static_cast<int>(floor(x0)) - r + i;\n      int y1 = static_cast<int>(floor(y0)) - r + j;\n\n      if (within_bounds(y1, x1, h2, w2)) {\n        scalar_t g = 0.0;\n        if (i > 0 && j > 0)\n          g += corr_grad[n][i-1][j-1][y][x] * scalar_t(dx * dy);\n\n        if (i > 0 && j < rd)\n          g += corr_grad[n][i-1][j][y][x] * scalar_t(dx * (1.0f-dy));\n\n        if (i < rd && j > 0)\n          g += corr_grad[n][i][j-1][y][x] * scalar_t((1.0f-dx) * dy);\n\n        if (i < rd && j < rd)\n          g += corr_grad[n][i][j][y][x] * scalar_t((1.0f-dx) * (1.0f-dy));\n\n        volume_grad[n][y][x][y1][x1] += g;\n      }\n    }\n  }\n}\n\nstd::vector<torch::Tensor> corr_index_cuda_forward(\n    torch::Tensor volume,\n    torch::Tensor coords,\n    int radius)\n{\n  const auto batch_size = volume.size(0);\n  const auto ht = volume.size(1);\n  const auto wd = volume.size(2);\n\n  const dim3 blocks((wd + BLOCK - 1) / BLOCK, \n                    (ht + BLOCK - 1) / BLOCK, \n                    batch_size);\n  \n  const dim3 threads(BLOCK, BLOCK);\n\n  auto opts = volume.options();\n  torch::Tensor corr = torch::zeros(\n    {batch_size, 2*radius+1, 2*radius+1, ht, wd}, opts);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(volume.type(), \"sampler_forward_kernel\", ([&] {\n    corr_index_forward_kernel<scalar_t><<<blocks, threads>>>(\n      volume.packed_accessor32<scalar_t,5,torch::RestrictPtrTraits>(),\n      coords.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n      corr.packed_accessor32<scalar_t,5,torch::RestrictPtrTraits>(),\n      radius);\n   }));\n\n  return {corr};\n\n}\n\nstd::vector<torch::Tensor> corr_index_cuda_backward(\n  torch::Tensor volume,\n  torch::Tensor coords,\n  torch::Tensor corr_grad,\n  int radius)\n{\n  const auto batch_size = volume.size(0);\n  const auto ht = volume.size(1);\n  const auto wd = volume.size(2);\n\n  auto volume_grad = torch::zeros_like(volume);\n\n  const dim3 blocks((wd + BLOCK - 1) / BLOCK, \n                    (ht + BLOCK - 1) / BLOCK, \n                    batch_size);\n\n  const dim3 threads(BLOCK, BLOCK);\n\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(volume.type(), \"sampler_backward_kernel\", ([&] {\n    corr_index_backward_kernel<scalar_t><<<blocks, threads>>>(\n      coords.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n      corr_grad.packed_accessor32<scalar_t,5,torch::RestrictPtrTraits>(),\n      volume_grad.packed_accessor32<scalar_t,5,torch::RestrictPtrTraits>(),\n      radius);\n   }));\n\n  return {volume_grad};\n}"
  },
  {
    "path": "VO_Module/src/droid.cpp",
    "content": "#include <torch/extension.h>\n#include <vector>\n\n// CUDA forward declarations\nstd::vector<torch::Tensor> projective_transform_cuda(\n  torch::Tensor poses,\n  torch::Tensor disps,\n  torch::Tensor intrinsics,\n  torch::Tensor ii,\n  torch::Tensor jj);\n\n\n\ntorch::Tensor depth_filter_cuda(\n    torch::Tensor poses,\n    torch::Tensor disps,\n    torch::Tensor intrinsics,\n    torch::Tensor ix,\n    torch::Tensor thresh);\n\n\ntorch::Tensor frame_distance_cuda(\n  torch::Tensor poses,\n  torch::Tensor disps,\n  torch::Tensor intrinsics,\n  torch::Tensor ii,\n  torch::Tensor jj,\n  const float beta);\n\nstd::vector<torch::Tensor> projmap_cuda(\n  torch::Tensor poses,\n  torch::Tensor disps,\n  torch::Tensor intrinsics,\n  torch::Tensor ii,\n  torch::Tensor jj);\n\ntorch::Tensor iproj_cuda(\n  torch::Tensor poses,\n  torch::Tensor disps,\n  torch::Tensor intrinsics);\n\nstd::vector<torch::Tensor> ba_cuda(\n    torch::Tensor poses,\n    torch::Tensor disps,\n    torch::Tensor intrinsics,\n    torch::Tensor targets,\n    torch::Tensor weights,\n    torch::Tensor eta,\n    torch::Tensor ii,\n    torch::Tensor jj,\n    const int t0,\n    const int t1,\n    const int iterations,\n    const float lm,\n    const float ep,\n    const bool motion_only);\n\nstd::vector<torch::Tensor> corr_index_cuda_forward(\n  torch::Tensor volume,\n  torch::Tensor coords,\n  int radius);\n\nstd::vector<torch::Tensor> corr_index_cuda_backward(\n  torch::Tensor volume,\n  torch::Tensor coords,\n  torch::Tensor corr_grad,\n  int radius);\n\nstd::vector<torch::Tensor> altcorr_cuda_forward(\n  torch::Tensor fmap1,\n  torch::Tensor fmap2,\n  torch::Tensor coords,\n  int radius);\n\nstd::vector<torch::Tensor> altcorr_cuda_backward(\n  torch::Tensor fmap1,\n  torch::Tensor fmap2,\n  torch::Tensor coords,\n  torch::Tensor corr_grad,\n  int radius);\n\n\n#define CHECK_CONTIGUOUS(x) TORCH_CHECK(x.is_contiguous(), #x \" must be contiguous\")\n#define CHECK_INPUT(x) CHECK_CONTIGUOUS(x)\n\n\nstd::vector<torch::Tensor> ba(\n    torch::Tensor poses,\n    torch::Tensor disps,\n    torch::Tensor intrinsics,\n    torch::Tensor targets,\n    torch::Tensor weights,\n    torch::Tensor eta,\n    torch::Tensor ii,\n    torch::Tensor jj,\n    const int t0,\n    const int t1,\n    const int iterations,\n    const float lm,\n    const float ep,\n    const bool motion_only) {\n\n  CHECK_INPUT(targets);\n  CHECK_INPUT(weights);\n  CHECK_INPUT(poses);\n  CHECK_INPUT(disps);\n  CHECK_INPUT(intrinsics);\n  CHECK_INPUT(ii);\n  CHECK_INPUT(jj);\n\n  return ba_cuda(poses, disps, intrinsics, targets, weights,\n                 eta, ii, jj, t0, t1, iterations, lm, ep, motion_only);\n\n}\n\n\ntorch::Tensor frame_distance(\n    torch::Tensor poses,\n    torch::Tensor disps,\n    torch::Tensor intrinsics,\n    torch::Tensor ii,\n    torch::Tensor jj,\n    const float beta) {\n\n  CHECK_INPUT(poses);\n  CHECK_INPUT(disps);\n  CHECK_INPUT(intrinsics);\n  CHECK_INPUT(ii);\n  CHECK_INPUT(jj);\n\n  return frame_distance_cuda(poses, disps, intrinsics, ii, jj, beta);\n\n}\n\n\nstd::vector<torch::Tensor> projmap(\n    torch::Tensor poses,\n    torch::Tensor disps,\n    torch::Tensor intrinsics,\n    torch::Tensor ii,\n    torch::Tensor jj) {\n\n  CHECK_INPUT(poses);\n  CHECK_INPUT(disps);\n  CHECK_INPUT(intrinsics);\n  CHECK_INPUT(ii);\n  CHECK_INPUT(jj);\n\n  return projmap_cuda(poses, disps, intrinsics, ii, jj);\n\n}\n\n\ntorch::Tensor iproj(\n    torch::Tensor poses,\n    torch::Tensor disps,\n    torch::Tensor intrinsics) {\n  CHECK_INPUT(poses);\n  CHECK_INPUT(disps);\n  CHECK_INPUT(intrinsics);\n\n  return iproj_cuda(poses, disps, intrinsics);\n}\n\n\n// c++ python binding\nstd::vector<torch::Tensor> corr_index_forward(\n    torch::Tensor volume,\n    torch::Tensor coords,\n    int radius) {\n  CHECK_INPUT(volume);\n  CHECK_INPUT(coords);\n\n  return corr_index_cuda_forward(volume, coords, radius);\n}\n\nstd::vector<torch::Tensor> corr_index_backward(\n    torch::Tensor volume,\n    torch::Tensor coords,\n    torch::Tensor corr_grad,\n    int radius) {\n  CHECK_INPUT(volume);\n  CHECK_INPUT(coords);\n  CHECK_INPUT(corr_grad);\n\n  auto volume_grad = corr_index_cuda_backward(volume, coords, corr_grad, radius);\n  return {volume_grad};\n}\n\nstd::vector<torch::Tensor> altcorr_forward(\n    torch::Tensor fmap1,\n    torch::Tensor fmap2,\n    torch::Tensor coords,\n    int radius) {\n  CHECK_INPUT(fmap1);\n  CHECK_INPUT(fmap2);\n  CHECK_INPUT(coords);\n\n  return altcorr_cuda_forward(fmap1, fmap2, coords, radius);\n}\n\nstd::vector<torch::Tensor> altcorr_backward(\n    torch::Tensor fmap1,\n    torch::Tensor fmap2,\n    torch::Tensor coords,\n    torch::Tensor corr_grad,\n    int radius) {\n  CHECK_INPUT(fmap1);\n  CHECK_INPUT(fmap2);\n  CHECK_INPUT(coords);\n  CHECK_INPUT(corr_grad);\n\n  return altcorr_cuda_backward(fmap1, fmap2, coords, corr_grad, radius);\n}\n\n\ntorch::Tensor depth_filter(\n    torch::Tensor poses,\n    torch::Tensor disps,\n    torch::Tensor intrinsics,\n    torch::Tensor ix,\n    torch::Tensor thresh) {\n\n    CHECK_INPUT(poses);\n    CHECK_INPUT(disps);\n    CHECK_INPUT(intrinsics);\n    CHECK_INPUT(ix);\n    CHECK_INPUT(thresh);\n\n    return depth_filter_cuda(poses, disps, intrinsics, ix, thresh);\n}\n\n\nPYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {\n  // bundle adjustment kernels\n  m.def(\"ba\", &ba, \"bundle adjustment\");\n  m.def(\"frame_distance\", &frame_distance, \"frame_distance\");\n  m.def(\"projmap\", &projmap, \"projmap\");\n  m.def(\"depth_filter\", &depth_filter, \"depth_filter\");\n  m.def(\"iproj\", &iproj, \"back projection\");\n\n  // correlation volume kernels\n  m.def(\"altcorr_forward\", &altcorr_forward, \"ALTCORR forward\");\n  m.def(\"altcorr_backward\", &altcorr_backward, \"ALTCORR backward\");\n  m.def(\"corr_index_forward\", &corr_index_forward, \"INDEX forward\");\n  m.def(\"corr_index_backward\", &corr_index_backward, \"INDEX backward\");\n}"
  },
  {
    "path": "VO_Module/src/droid_kernels.cu",
    "content": "#include <torch/extension.h>\n#include <cuda.h>\n#include <cuda_runtime.h>\n#include <cuda_runtime.h>\n\n#include <vector>\n#include <iostream>\n\n#include <ATen/ATen.h>\n#include <ATen/NativeFunctions.h>\n#include <ATen/Parallel.h>\n\n// #include \"utils.cuh\"\n\n#include <Eigen/Sparse>\n#include <Eigen/SparseCore>\n#include <Eigen/SparseCholesky>\n\ntypedef Eigen::SparseMatrix<double> SpMat;\ntypedef Eigen::Triplet<double> T;\ntypedef std::vector<std::vector<long>> graph_t;\ntypedef std::vector<torch::Tensor> tensor_list_t;\n\n\n\n#define MIN_DEPTH 0.25\n\n#define THREADS 256\n#define NUM_BLOCKS(batch_size) ((batch_size + THREADS - 1) / THREADS)\n\n\n#define GPU_1D_KERNEL_LOOP(k, n) \\\n  for (size_t k = threadIdx.x; k<n; k += blockDim.x)\n\n\n__device__ void warpReduce(volatile float *sdata, unsigned int tid) {\n  sdata[tid] += sdata[tid + 32];\n  sdata[tid] += sdata[tid + 16];\n  sdata[tid] += sdata[tid +  8];\n  sdata[tid] += sdata[tid +  4];\n  sdata[tid] += sdata[tid +  2];\n  sdata[tid] += sdata[tid +  1];\n}\n\n__device__ void blockReduce(volatile float *sdata) {\n  unsigned int tid = threadIdx.x;\n  __syncthreads();\n\n  // if (threadIdx.x < 256) {sdata[tid] += sdata[tid + 256]; } __syncthreads();\n  if (threadIdx.x < 128) {sdata[tid] += sdata[tid + 128]; } __syncthreads();\n  if (threadIdx.x <  64) {sdata[tid] += sdata[tid +  64]; } __syncthreads();\n\n  if (tid < 32) warpReduce(sdata, tid);\n  __syncthreads();\n}\n\n\n__device__ void\nactSO3(const float *q, const float *X, float *Y) {\n  float uv[3];\n  uv[0] = 2.0 * (q[1]*X[2] - q[2]*X[1]);\n  uv[1] = 2.0 * (q[2]*X[0] - q[0]*X[2]);\n  uv[2] = 2.0 * (q[0]*X[1] - q[1]*X[0]);\n\n  Y[0] = X[0] + q[3]*uv[0] + (q[1]*uv[2] - q[2]*uv[1]);\n  Y[1] = X[1] + q[3]*uv[1] + (q[2]*uv[0] - q[0]*uv[2]);\n  Y[2] = X[2] + q[3]*uv[2] + (q[0]*uv[1] - q[1]*uv[0]);\n}\n\n__device__  void\nactSE3(const float *t, const float *q, const float *X, float *Y) {\n  actSO3(q, X, Y);\n  Y[3] = X[3];\n  Y[0] += X[3] * t[0];\n  Y[1] += X[3] * t[1];\n  Y[2] += X[3] * t[2];\n}\n\n__device__ void\nadjSE3(const float *t, const float *q, const float *X, float *Y) {\n  float qinv[4] = {-q[0], -q[1], -q[2], q[3]};\n  actSO3(qinv, &X[0], &Y[0]);\n  actSO3(qinv, &X[3], &Y[3]);\n\n  float u[3], v[3];\n  u[0] = t[2]*X[1] - t[1]*X[2];\n  u[1] = t[0]*X[2] - t[2]*X[0];\n  u[2] = t[1]*X[0] - t[0]*X[1];\n\n  actSO3(qinv, u, v);\n  Y[3] += v[0];\n  Y[4] += v[1];\n  Y[5] += v[2];\n}\n\n__device__ void \nrelSE3(const float *ti, const float *qi, const float *tj, const float *qj, float *tij, float *qij) {\n  qij[0] = -qj[3] * qi[0] + qj[0] * qi[3] - qj[1] * qi[2] + qj[2] * qi[1],\n  qij[1] = -qj[3] * qi[1] + qj[1] * qi[3] - qj[2] * qi[0] + qj[0] * qi[2],\n  qij[2] = -qj[3] * qi[2] + qj[2] * qi[3] - qj[0] * qi[1] + qj[1] * qi[0],\n  qij[3] =  qj[3] * qi[3] + qj[0] * qi[0] + qj[1] * qi[1] + qj[2] * qi[2],\n\n  actSO3(qij, ti, tij);\n  tij[0] = tj[0] - tij[0];\n  tij[1] = tj[1] - tij[1];\n  tij[2] = tj[2] - tij[2];\n}\n\n  \n__device__ void\nexpSO3(const float *phi, float* q) {\n  // SO3 exponential map\n  float theta_sq = phi[0]*phi[0] + phi[1]*phi[1] + phi[2]*phi[2];\n  float theta_p4 = theta_sq * theta_sq;\n\n  float theta = sqrtf(theta_sq);\n  float imag, real;\n\n  if (theta_sq < 1e-8) {\n    imag = 0.5 - (1.0/48.0)*theta_sq + (1.0/3840.0)*theta_p4;\n    real = 1.0 - (1.0/ 8.0)*theta_sq + (1.0/ 384.0)*theta_p4;\n  } else {\n    imag = sinf(0.5 * theta) / theta;\n    real = cosf(0.5 * theta);\n  }\n\n  q[0] = imag * phi[0];\n  q[1] = imag * phi[1];\n  q[2] = imag * phi[2];\n  q[3] = real;\n\n}\n\n__device__ void\ncrossInplace(const float* a, float *b) {\n  float x[3] = {\n    a[1]*b[2] - a[2]*b[1],\n    a[2]*b[0] - a[0]*b[2],\n    a[0]*b[1] - a[1]*b[0], \n  };\n\n  b[0] = x[0];\n  b[1] = x[1];\n  b[2] = x[2];\n}\n\n__device__ void\nexpSE3(const float *xi, float* t, float* q) {\n  // SE3 exponential map\n\n  expSO3(xi + 3, q);\n\n  float tau[3] = {xi[0], xi[1], xi[2]};\n  float phi[3] = {xi[3], xi[4], xi[45]};\n\n  float theta_sq = phi[0]*phi[0] + phi[1]*phi[1] + phi[2]*phi[2];\n  float theta = sqrtf(theta_sq);\n\n  t[0] = tau[0]; \n  t[1] = tau[1]; \n  t[2] = tau[2];\n\n  if (theta > 1e-4) {\n    float a = (1 - cosf(theta)) / theta_sq;\n    crossInplace(phi, tau);\n    t[0] += a * tau[0];\n    t[1] += a * tau[1];\n    t[2] += a * tau[2];\n\n    float b = (theta - sinf(theta)) / (theta * theta_sq);\n    crossInplace(phi, tau);\n    t[0] += b * tau[0];\n    t[1] += b * tau[1];\n    t[2] += b * tau[2];\n  }\n}\n__global__ void projective_transform_kernel(\n    const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> target,\n    const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> weight,\n    const torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> poses,\n    const torch::PackedTensorAccessor32<float,3,torch::RestrictPtrTraits> disps,\n    const torch::PackedTensorAccessor32<float,1,torch::RestrictPtrTraits> intrinsics,\n    const torch::PackedTensorAccessor32<long,1,torch::RestrictPtrTraits> ii,\n    const torch::PackedTensorAccessor32<long,1,torch::RestrictPtrTraits> jj,\n    torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> Hs,\n    torch::PackedTensorAccessor32<float,3,torch::RestrictPtrTraits> vs,\n    torch::PackedTensorAccessor32<float,3,torch::RestrictPtrTraits> Eii,\n    torch::PackedTensorAccessor32<float,3,torch::RestrictPtrTraits> Eij,\n    torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> Cii,\n    torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> bz)\n{\n  const int block_id = blockIdx.x;\n  const int thread_id = threadIdx.x;\n\n  const int ht = disps.size(1);\n  const int wd = disps.size(2);\n\n  __shared__ int ix;\n  __shared__ int jx;\n\n  __shared__ float fx;\n  __shared__ float fy;\n  __shared__ float cx;\n  __shared__ float cy;\n\n  __shared__ float ti[3], tj[3], tij[3];\n  __shared__ float qi[4], qj[4], qij[4];\n\n  // load intrinsics from global memory\n  if (thread_id == 0) {\n    ix = static_cast<int>(ii[block_id]);\n    jx = static_cast<int>(jj[block_id]);\n    fx = intrinsics[0];\n    fy = intrinsics[1];\n    cx = intrinsics[2];\n    cy = intrinsics[3];\n  }\n\n  __syncthreads();\n\n  // load poses from global memory\n  if (thread_id < 3) {\n    ti[thread_id] = poses[ix][thread_id];\n    tj[thread_id] = poses[jx][thread_id];\n  }\n\n  if (thread_id < 4) {\n    qi[thread_id] = poses[ix][thread_id+3];\n    qj[thread_id] = poses[jx][thread_id+3];\n  }\n\n  __syncthreads();\n\n  if (thread_id == 0) {\n    relSE3(ti, qi, tj, qj, tij, qij);\n  }\n\n  //points \n  float Xi[4];\n  float Xj[4];\n\n  // jacobians\n  float Jx[12];\n  float Jz;\n\n  float* Ji = &Jx[0];\n  float* Jj = &Jx[6];\n\n  // hessians\n  float hij[12*(12+1)/2];\n\n  float vi[6], vj[6];\n\n  int l;\n  for (l=0; l<12*(12+1)/2; l++) {\n    hij[l] = 0;\n  }\n\n  for (int n=0; n<6; n++) {\n    vi[n] = 0;\n    vj[n] = 0;\n  }\n\n  __syncthreads();\n\n  GPU_1D_KERNEL_LOOP(k, ht*wd) {\n\n    const int i = k / wd;\n    const int j = k % wd;\n\n    const float u = static_cast<float>(j);\n    const float v = static_cast<float>(i);\n    \n    // homogenous coordinates\n    Xi[0] = (u - cx) / fx;\n    Xi[1] = (v - cy) / fy;\n    Xi[2] = 1;\n    Xi[3] = disps[ix][i][j];\n\n    // transform homogenous point\n    actSE3(tij, qij, Xi, Xj);\n\n    const float x = Xj[0];\n    const float y = Xj[1];\n    const float h = Xj[3];\n\n    const float d = (Xj[2] < MIN_DEPTH) ? 0.0 : 1.0 / Xj[2];\n    const float d2 = d * d;\n\n    const float wu = (Xj[2] < MIN_DEPTH) ? 0.0 : .001 * weight[block_id][0][i][j];\n    const float wv = (Xj[2] < MIN_DEPTH) ? 0.0 : .001 * weight[block_id][1][i][j];\n\n    const float ru = target[block_id][0][i][j] - (fx * d * x + cx);\n    const float rv = target[block_id][1][i][j] - (fy * d * y + cy);\n\n    // x - coordinate\n\n    Jj[0] = fx * (h*d);\n    Jj[1] = fx * 0;\n    Jj[2] = fx * (-x*h*d2);\n    Jj[3] = fx * (-x*y*d2);\n    Jj[4] = fx * (1 + x*x*d2);\n    Jj[5] = fx * (-y*d);\n\n    Jz = fx * (tij[0] * d - tij[2] * (x * d2));\n    adjSE3(tij, qij, Jj, Ji);\n    for (int n=0; n<6; n++) Ji[n] *= -1;\n\n    l=0;\n    for (int n=0; n<12; n++) {\n      for (int m=0; m<=n; m++) {\n        hij[l] += wu * Jx[n] * Jx[m];\n        l++;\n      }\n    }\n\n    for (int n=0; n<6; n++) {\n      vi[n] += wu * ru * Ji[n];\n      vj[n] += wu * ru * Jj[n];\n\n      Eii[block_id][n][k] = wu * Jz * Ji[n];\n      Eij[block_id][n][k] = wu * Jz * Jj[n];\n    }\n\n    Cii[block_id][k] = wu * Jz * Jz;\n    bz[block_id][k] = wu * ru * Jz;\n\n    Jj[0] = fy * 0;\n    Jj[1] = fy * (h*d);\n    Jj[2] = fy * (-y*h*d2);\n    Jj[3] = fy * (-1 - y*y*d2);\n    Jj[4] = fy * (x*y*d2);\n    Jj[5] = fy * (x*d);\n\n    Jz = fy * (tij[1] * d - tij[2] * (y * d2));\n    adjSE3(tij, qij, Jj, Ji);\n    for (int n=0; n<6; n++) Ji[n] *= -1;\n\n    l=0;\n    for (int n=0; n<12; n++) {\n      for (int m=0; m<=n; m++) {\n        hij[l] += wv * Jx[n] * Jx[m];\n        l++;\n      }\n    }\n\n    for (int n=0; n<6; n++) {\n      vi[n] += wv * rv * Ji[n];\n      vj[n] += wv * rv * Jj[n];\n\n      Eii[block_id][n][k] += wv * Jz * Ji[n];\n      Eij[block_id][n][k] += wv * Jz * Jj[n];\n    }\n\n    Cii[block_id][k] += wv * Jz * Jz;\n    bz[block_id][k] += wv * rv * Jz;\n  }\n\n  __syncthreads();\n\n  __shared__ float sdata[THREADS];\n  for (int n=0; n<6; n++) {\n    sdata[threadIdx.x] = vi[n];\n    blockReduce(sdata);\n    if (threadIdx.x == 0) {\n      vs[0][block_id][n] = sdata[0];\n    }\n\n    __syncthreads();\n\n    sdata[threadIdx.x] = vj[n];\n    blockReduce(sdata);\n    if (threadIdx.x == 0) {\n      vs[1][block_id][n] = sdata[0];\n    }\n\n  }\n\n  l=0;\n  for (int n=0; n<12; n++) {\n    for (int m=0; m<=n; m++) {\n      sdata[threadIdx.x] = hij[l];\n      blockReduce(sdata);\n\n      if (threadIdx.x == 0) {\n        if (n<6 && m<6) {\n          Hs[0][block_id][n][m] = sdata[0];\n          Hs[0][block_id][m][n] = sdata[0];\n        }\n        else if (n >=6 && m<6) {\n          Hs[1][block_id][m][n-6] = sdata[0];\n          Hs[2][block_id][n-6][m] = sdata[0];\n        }\n        else {\n          Hs[3][block_id][n-6][m-6] = sdata[0];\n          Hs[3][block_id][m-6][n-6] = sdata[0];\n        }\n      }\n\n      l++;\n    }\n  }\n}\n\n\n__global__ void projmap_kernel(\n    const torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> poses,\n    const torch::PackedTensorAccessor32<float,3,torch::RestrictPtrTraits> disps,\n    const torch::PackedTensorAccessor32<float,1,torch::RestrictPtrTraits> intrinsics,\n    const torch::PackedTensorAccessor32<long,1,torch::RestrictPtrTraits> ii,\n    const torch::PackedTensorAccessor32<long,1,torch::RestrictPtrTraits> jj,\n    torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> coords,\n    torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> valid)\n{\n\n  const int block_id = blockIdx.x;\n  const int thread_id = threadIdx.x;\n\n  const int ht = disps.size(1);\n  const int wd = disps.size(2);\n\n  __shared__ int ix;\n  __shared__ int jx;\n\n  __shared__ float fx;\n  __shared__ float fy;\n  __shared__ float cx;\n  __shared__ float cy;\n\n  __shared__ float ti[3], tj[3], tij[3];\n  __shared__ float qi[4], qj[4], qij[4];\n\n  // load intrinsics from global memory\n  if (thread_id == 0) {\n    ix = static_cast<int>(ii[block_id]);\n    jx = static_cast<int>(jj[block_id]);\n    fx = intrinsics[0];\n    fy = intrinsics[1];\n    cx = intrinsics[2];\n    cy = intrinsics[3];\n  }\n\n  __syncthreads();\n\n  // load poses from global memory\n  if (thread_id < 3) {\n    ti[thread_id] = poses[ix][thread_id];\n    tj[thread_id] = poses[jx][thread_id];\n  }\n\n  if (thread_id < 4) {\n    qi[thread_id] = poses[ix][thread_id+3];\n    qj[thread_id] = poses[jx][thread_id+3];\n  }\n\n  __syncthreads();\n\n  if (thread_id == 0) {\n    relSE3(ti, qi, tj, qj, tij, qij);\n  }\n\n  //points \n  float Xi[4];\n  float Xj[4];\n\n  __syncthreads();\n\n  GPU_1D_KERNEL_LOOP(k, ht*wd) {\n    const int i = k / wd;\n    const int j = k % wd;\n\n    const float u = static_cast<float>(j);\n    const float v = static_cast<float>(i);\n    \n    // homogenous coordinates\n    Xi[0] = (u - cx) / fx;\n    Xi[1] = (v - cy) / fy;\n    Xi[2] = 1;\n    Xi[3] = disps[ix][i][j];\n\n    // transform homogenous point\n    actSE3(tij, qij, Xi, Xj);\n\n    coords[block_id][i][j][0] = u;\n    coords[block_id][i][j][1] = v;\n\n    if (Xj[2] > 0.01) {\n      coords[block_id][i][j][0] = fx * (Xj[0] / Xj[2]) + cx;\n      coords[block_id][i][j][1] = fy * (Xj[1] / Xj[2]) + cy;\n    }\n\n    valid[block_id][i][j][0] = (Xj[2] > MIN_DEPTH) ? 1.0 : 0.0;\n\n  }\n}\n\n__global__ void frame_distance_kernel(\n    const torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> poses,\n    const torch::PackedTensorAccessor32<float,3,torch::RestrictPtrTraits> disps,\n    const torch::PackedTensorAccessor32<float,1,torch::RestrictPtrTraits> intrinsics,\n    const torch::PackedTensorAccessor32<long,1,torch::RestrictPtrTraits> ii,\n    const torch::PackedTensorAccessor32<long,1,torch::RestrictPtrTraits> jj,\n    torch::PackedTensorAccessor32<float,1,torch::RestrictPtrTraits> dist,\n    const float beta) {\n\n  const int block_id = blockIdx.x;\n  const int thread_id = threadIdx.x;\n\n  const int ht = disps.size(1);\n  const int wd = disps.size(2);\n\n  __shared__ int ix;\n  __shared__ int jx;\n\n  __shared__ float fx;\n  __shared__ float fy;\n  __shared__ float cx;\n  __shared__ float cy;\n\n  __shared__ float ti[3], tj[3], tij[3];\n  __shared__ float qi[4], qj[4], qij[4];\n\n  // load intrinsics from global memory\n  if (thread_id == 0) {\n    ix = static_cast<int>(ii[block_id]);\n    jx = static_cast<int>(jj[block_id]);\n    fx = intrinsics[0];\n    fy = intrinsics[1];\n    cx = intrinsics[2];\n    cy = intrinsics[3];\n  }\n\n  __syncthreads();\n\n\n  //points \n  float Xi[4];\n  float Xj[4];\n\n  __shared__ float accum[THREADS]; accum[thread_id] = 0;\n  __shared__ float valid[THREADS]; valid[thread_id] = 0;\n  __shared__ float total[THREADS]; total[thread_id] = 0;\n\n  __syncthreads();\n\n  for (int n=0; n<1; n++) {\n\n    if (thread_id < 3) {\n      ti[thread_id] = poses[ix][thread_id];\n      tj[thread_id] = poses[jx][thread_id];\n    }\n\n    if (thread_id < 4) {\n      qi[thread_id] = poses[ix][thread_id+3];\n      qj[thread_id] = poses[jx][thread_id+3];\n    }\n\n    __syncthreads();\n\n\n    relSE3(ti, qi, tj, qj, tij, qij);\n\n    float d, du, dv;\n\n    GPU_1D_KERNEL_LOOP(k, ht*wd) {\n      const int i = k / wd;\n      const int j = k % wd;\n\n      const float u = static_cast<float>(j);\n      const float v = static_cast<float>(i);\n\n\n      // if (disps[ix][i][j] < 0.01) {\n      //   continue;\n      // }\n      \n      // homogenous coordinates\n      Xi[0] = (u - cx) / fx;\n      Xi[1] = (v - cy) / fy;\n      Xi[2] = 1;\n      Xi[3] = disps[ix][i][j];\n\n      // transform homogenous point\n      actSE3(tij, qij, Xi, Xj);\n\n      du = fx * (Xj[0] / Xj[2]) + cx - u;\n      dv = fy * (Xj[1] / Xj[2]) + cy - v;\n      d = sqrtf(du*du + dv*dv);\n\n      total[threadIdx.x] += beta;\n      \n      if (Xj[2] > MIN_DEPTH) {\n        accum[threadIdx.x] += beta * d;\n        valid[threadIdx.x] += beta;\n      }\n\n      Xi[0] = (u - cx) / fx;\n      Xi[1] = (v - cy) / fy;\n      Xi[2] = 1;\n      Xi[3] = disps[ix][i][j];\n\n      Xj[0] = Xi[0] + Xi[3] * tij[0];\n      Xj[1] = Xi[1] + Xi[3] * tij[1];\n      Xj[2] = Xi[2] + Xi[3] * tij[2];\n\n      du = fx * (Xj[0] / Xj[2]) + cx - u;\n      dv = fy * (Xj[1] / Xj[2]) + cy - v;\n      d = sqrtf(du*du + dv*dv);\n\n      total[threadIdx.x] += (1 - beta);\n      \n      if (Xj[2] > MIN_DEPTH) {\n        accum[threadIdx.x] += (1 - beta) * d;\n        valid[threadIdx.x] += (1 - beta);\n      }\n    }\n\n    if (threadIdx.x == 0) {\n      int tmp = ix;\n      ix = jx;\n      jx = tmp;\n    }\n\n    __syncthreads();\n\n  }\n  __syncthreads(); blockReduce(accum);\n  __syncthreads(); blockReduce(total);\n  __syncthreads(); blockReduce(valid);\n\n  __syncthreads();\n\n  if (thread_id == 0) {\n    dist[block_id] = (valid[0] / (total[0] + 1e-8) < 0.75) ? 1000.0 : accum[0] / valid[0];\n  }\n}\n\n\n\n__global__ void depth_filter_kernel(\n    const torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> poses,\n    const torch::PackedTensorAccessor32<float,3,torch::RestrictPtrTraits> disps,\n    const torch::PackedTensorAccessor32<float,1,torch::RestrictPtrTraits> intrinsics,\n    const torch::PackedTensorAccessor32<long,1,torch::RestrictPtrTraits> inds,\n    const torch::PackedTensorAccessor32<float,1,torch::RestrictPtrTraits> thresh,\n    torch::PackedTensorAccessor32<float,3,torch::RestrictPtrTraits> counter)\n{\n\n  const int block_id = blockIdx.x;\n  const int neigh_id = blockIdx.y;\n  const int index = blockIdx.z * blockDim.x + threadIdx.x;\n\n  // if (threadIdx.x == 0) {\n  //   printf(\"%d %d %d %d\\n\", blockIdx.x, blockIdx.y, blockDim.x, threadIdx.x);\n  // }\n\n  const int num = disps.size(0);\n  const int ht = disps.size(1);\n  const int wd = disps.size(2);\n\n  __shared__ int ix;\n  __shared__ int jx;\n\n  __shared__ float fx;\n  __shared__ float fy;\n  __shared__ float cx;\n  __shared__ float cy;\n\n  __shared__ float ti[3], tj[3], tij[3];\n  __shared__ float qi[4], qj[4], qij[4];\n\n  if (threadIdx.x == 0) {\n    ix = static_cast<int>(inds[block_id]);\n    jx = (neigh_id < 3) ? ix - neigh_id - 1 : ix + neigh_id;\n    fx = intrinsics[0];\n    fy = intrinsics[1];\n    cx = intrinsics[2];\n    cy = intrinsics[3];\n  }\n\n  __syncthreads();\n\n  if (jx < 0 || jx >= num) {\n    return;\n  }\n\n  const float t = thresh[block_id];\n\n  // load poses from global memory\n  if (threadIdx.x < 3) {\n    ti[threadIdx.x] = poses[ix][threadIdx.x];\n    tj[threadIdx.x] = poses[jx][threadIdx.x];\n  }\n\n  if (threadIdx.x < 4) {\n    qi[threadIdx.x] = poses[ix][threadIdx.x+3];\n    qj[threadIdx.x] = poses[jx][threadIdx.x+3];\n  }\n\n  __syncthreads();\n\n  if (threadIdx.x == 0) {\n    relSE3(ti, qi, tj, qj, tij, qij);\n  }\n\n  //points \n  float Xi[4];\n  float Xj[4];\n\n  __syncthreads();\n\n  if (index < ht*wd) {\n    const int i = index / wd;\n    const int j = index % wd;\n\n    const float ui = static_cast<float>(j);\n    const float vi = static_cast<float>(i);\n    const float di = disps[ix][i][j];\n    \n    // homogenous coordinates\n    Xi[0] = (ui - cx) / fx;\n    Xi[1] = (vi - cy) / fy;\n    Xi[2] = 1;\n    Xi[3] = di;\n\n    // transform homogenous point\n    actSE3(tij, qij, Xi, Xj);\n\n    const float uj = fx * (Xj[0] / Xj[2]) + cx;\n    const float vj = fy * (Xj[1] / Xj[2]) + cy;\n    const float dj = Xj[3] / Xj[2];\n\n    const int u0 = static_cast<int>(floor(uj));\n    const int v0 = static_cast<int>(floor(vj));\n\n    if (u0 >= 0 && v0 >= 0 && u0 < wd-1 && v0 < ht-1) {\n      const float wx = ceil(uj) - uj;\n      const float wy = ceil(vj) - vj;\n\n      const float d00 = disps[jx][v0+0][u0+0];\n      const float d01 = disps[jx][v0+0][u0+1];\n      const float d10 = disps[jx][v0+1][u0+0];\n      const float d11 = disps[jx][v0+1][u0+1];\n\n      const float dj_hat = wy*wx*d00 + wy*(1-wx)*d01 + (1-wy)*wx*d10 + (1-wy)*(1-wx)*d11;\n\n      const float err = abs(1.0/dj - 1.0/dj_hat);\n      if       (abs(1.0/dj - 1.0/d00) < t) atomicAdd(&counter[block_id][i][j], 1.0f);\n      else if  (abs(1.0/dj - 1.0/d01) < t) atomicAdd(&counter[block_id][i][j], 1.0f);\n      else if  (abs(1.0/dj - 1.0/d10) < t) atomicAdd(&counter[block_id][i][j], 1.0f);\n      else if  (abs(1.0/dj - 1.0/d11) < t) atomicAdd(&counter[block_id][i][j], 1.0f);\n    }\n  }\n}\n\n\n\n__global__ void iproj_kernel(\n    const torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> poses,\n    const torch::PackedTensorAccessor32<float,3,torch::RestrictPtrTraits> disps,\n    const torch::PackedTensorAccessor32<float,1,torch::RestrictPtrTraits> intrinsics,\n    torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> points)\n\n{\n\n  const int block_id = blockIdx.x;\n  const int index = blockIdx.y * blockDim.x + threadIdx.x;\n\n\n  const int num = disps.size(0);\n  const int ht = disps.size(1);\n  const int wd = disps.size(2);\n\n  __shared__ float fx;\n  __shared__ float fy;\n  __shared__ float cx;\n  __shared__ float cy;\n\n  __shared__ float t[3];\n  __shared__ float q[4];\n\n  if (threadIdx.x == 0) {\n    fx = intrinsics[0];\n    fy = intrinsics[1];\n    cx = intrinsics[2];\n    cy = intrinsics[3];\n  }\n\n  __syncthreads();\n\n\n  // load poses from global memory\n  if (threadIdx.x < 3) {\n    t[threadIdx.x] = poses[block_id][threadIdx.x];\n  }\n\n  if (threadIdx.x < 4) {\n    q[threadIdx.x] = poses[block_id][threadIdx.x+3];\n  }\n\n  __syncthreads();\n\n  //points \n  float Xi[4];\n  float Xj[4];\n\n  if (index < ht*wd) {\n    const int i = index / wd;\n    const int j = index % wd;\n\n    const float ui = static_cast<float>(j);\n    const float vi = static_cast<float>(i);\n    const float di = disps[block_id][i][j];\n    \n    // homogenous coordinates\n    Xi[0] = (ui - cx) / fx;\n    Xi[1] = (vi - cy) / fy;\n    Xi[2] = 1;\n    Xi[3] = di;\n\n    // transform homogenous point\n    actSE3(t, q, Xi, Xj);\n\n    points[block_id][i][j][0] = Xj[0] / Xj[3];\n    points[block_id][i][j][1] = Xj[1] / Xj[3];\n    points[block_id][i][j][2] = Xj[2] / Xj[3];\n\n  }\n}\n\n\n\n__global__ void accum_kernel(\n    const torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> inps,\n    const torch::PackedTensorAccessor32<long,1,torch::RestrictPtrTraits> ptrs,\n    const torch::PackedTensorAccessor32<long,1,torch::RestrictPtrTraits> idxs,\n    torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> outs)\n{\n  \n  const int block_id = blockIdx.x;\n  const int D = inps.size(2);\n\n  const int start = ptrs[block_id];\n  const int end = ptrs[block_id+1];\n\n  for (int k=threadIdx.x; k<D; k+=blockDim.x) {\n    float x = 0;\n    for (int i=start; i<end; i++) {\n      x += inps[idxs[i]][k];\n    }\n    outs[block_id][k] = x;\n  }  \n}\n\n\n__device__ void\nretrSE3(const float *xi, const float* t, const float* q, float* t1, float* q1) {\n  // retraction on SE3 manifold\n\n  float dt[3] = {0, 0, 0};\n  float dq[4] = {0, 0, 0, 1};\n  \n  expSE3(xi, dt, dq);\n\n  q1[0] = dq[3] * q[0] + dq[0] * q[3] + dq[1] * q[2] - dq[2] * q[1];\n  q1[1] = dq[3] * q[1] + dq[1] * q[3] + dq[2] * q[0] - dq[0] * q[2];\n  q1[2] = dq[3] * q[2] + dq[2] * q[3] + dq[0] * q[1] - dq[1] * q[0];\n  q1[3] = dq[3] * q[3] - dq[0] * q[0] - dq[1] * q[1] - dq[2] * q[2];\n\n  actSO3(dq, t, t1);\n  t1[0] += dt[0];\n  t1[1] += dt[1];\n  t1[2] += dt[2];\n}\n\n\n__global__ void pose_retr_kernel(\n    torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> poses,\n    const torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> dx,\n    const int t0, const int t1) \n{\n\n  for (int k=t0+threadIdx.x; k<t1; k+=blockDim.x) {\n    float xi[6], q[4], q1[4], t[3], t1[3];\n\n    t[0] = poses[k][0];\n    t[1] = poses[k][1];\n    t[2] = poses[k][2];\n\n    q[0] = poses[k][3];\n    q[1] = poses[k][4];\n    q[2] = poses[k][5];\n    q[3] = poses[k][6];\n    \n    for (int n=0; n<6; n++) {\n      xi[n] = dx[k-t0][n];\n    }\n\n    retrSE3(xi, t, q, t1, q1);\n\n    poses[k][0] = t1[0];\n    poses[k][1] = t1[1];\n    poses[k][2] = t1[2];\n\n    poses[k][3] = q1[0];\n    poses[k][4] = q1[1];\n    poses[k][5] = q1[2];\n    poses[k][6] = q1[3];\n  }\n}\n\n__global__ void disp_retr_kernel(\n    torch::PackedTensorAccessor32<float,3,torch::RestrictPtrTraits> disps,\n    const torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> dz,\n    const torch::PackedTensorAccessor32<long,1,torch::RestrictPtrTraits> inds) \n{\n  const int i = inds[blockIdx.x];\n  const int ht = disps.size(1);\n  const int wd = disps.size(2);\n\n  for (int k=threadIdx.x; k<ht*wd; k+=blockDim.x) {\n    float d = disps[i][k/wd][k%wd] + dz[blockIdx.x][k];\n    disps[i][k/wd][k%wd] = d;\n  }\n}\n\ntorch::Tensor accum_cuda(torch::Tensor data, torch::Tensor ix, torch::Tensor jx) {\n  torch::Tensor ix_cpu = ix.to(torch::kCPU);\n  torch::Tensor jx_cpu = jx.to(torch::kCPU);\n  torch::Tensor inds = torch::argsort(ix_cpu);\n\n  long* ix_data = ix_cpu.data_ptr<long>();\n  long* jx_data = jx_cpu.data_ptr<long>();\n  long* kx_data = inds.data_ptr<long>();\n\n  int count = jx.size(0);\n  std::vector<int> cols;\n\n  torch::Tensor ptrs_cpu = torch::zeros({count+1}, \n    torch::TensorOptions().dtype(torch::kInt64));\n  \n  long* ptrs_data = ptrs_cpu.data_ptr<long>();\n  ptrs_data[0] = 0;\n\n  int i = 0;\n  for (int j=0; j<count; j++) {\n    while (i < ix.size(0) && ix_data[kx_data[i]] <= jx_data[j]) {\n      if (ix_data[kx_data[i]] == jx_data[j])\n        cols.push_back(kx_data[i]);\n      i++;\n    }\n    ptrs_data[j+1] = cols.size();\n  }\n\n  torch::Tensor idxs_cpu = torch::zeros({long(cols.size())}, \n    torch::TensorOptions().dtype(torch::kInt64));\n\n  long* idxs_data = idxs_cpu.data_ptr<long>();\n\n  for (int i=0; i<cols.size(); i++) {\n    idxs_data[i] = cols[i];\n  }\n\n  torch::Tensor ptrs = ptrs_cpu.to(torch::kCUDA);\n  torch::Tensor idxs = idxs_cpu.to(torch::kCUDA);\n\n  torch::Tensor out = torch::zeros({jx.size(0), data.size(1)},\n    torch::TensorOptions().dtype(torch::kFloat32).device(torch::kCUDA));\n\n  accum_kernel<<<count, THREADS>>>(\n    data.packed_accessor32<float,2,torch::RestrictPtrTraits>(),\n    ptrs.packed_accessor32<long,1,torch::RestrictPtrTraits>(),\n    idxs.packed_accessor32<long,1,torch::RestrictPtrTraits>(),\n    out.packed_accessor32<float,2,torch::RestrictPtrTraits>());\n\n  return out;\n}\n\n\n__global__ void EEt6x6_kernel(\n    const torch::PackedTensorAccessor32<float,3,torch::RestrictPtrTraits> E,\n    const torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> Q,\n    const torch::PackedTensorAccessor32<long,2,torch::RestrictPtrTraits> idx,\n    torch::PackedTensorAccessor32<float,3,torch::RestrictPtrTraits> S)\n{\n\n  // indicices\n  const int ix = idx[blockIdx.x][0];\n  const int jx = idx[blockIdx.x][1];\n  const int kx = idx[blockIdx.x][2];\n\n  const int D = E.size(2);\n\n  float dS[6][6];\n  float ei[6];\n  float ej[6];\n\n  for (int i=0; i<6; i++) {\n    for (int j=0; j<6; j++) {\n      dS[i][j] = 0;\n    }\n  }\n\n  for (int k=threadIdx.x; k<D; k+=blockDim.x) {\n    const float q = Q[kx][k];\n      \n    // coalesced memory read\n    for (int n=0; n<6; n++) {\n      ei[n] = E[ix][n][k] * q;\n      ej[n] = E[jx][n][k];\n    }\n\n    // block EEt\n    for (int n=0; n<6; n++) {\n      for (int m=0; m<6; m++) {\n        dS[n][m] += ei[n] * ej[m];\n      }\n    }\n  }\n\n  __syncthreads();\n  __shared__ float sdata[THREADS];\n\n  for (int n=0; n<6; n++) {\n    for (int m=0; m<6; m++) {\n      sdata[threadIdx.x] = dS[n][m];\n\n      blockReduce(sdata);\n\n      if (threadIdx.x == 0) {\n        S[blockIdx.x][n][m] = sdata[0];\n      }\n    }\n  }\n}\n\n\n__global__ void Ev6x1_kernel(\n    const torch::PackedTensorAccessor32<float, 3, torch::RestrictPtrTraits> E,\n    const torch::PackedTensorAccessor32<float, 2,torch::RestrictPtrTraits> Q,\n    const torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> w,\n    const torch::PackedTensorAccessor32<long,2,torch::RestrictPtrTraits> idx,\n    torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> v)\n{\n  const int D = E.size(2);\n  const int kx = idx[blockIdx.x][0];\n\n  float b[6];\n  for (int n=0; n<6; n++) {\n    b[n] = 0.0;\n  }\n\n  for (int k=threadIdx.x; k<D; k+=blockDim.x) {\n    const float q_w = Q[kx][k] * w[kx][k];\n\n    for (int n=0; n<6; n++) {\n      b[n] += q_w * E[blockIdx.x][n][k];\n    }\n  }\n\n  __syncthreads();\n  __shared__ float sdata[THREADS];\n\n  for (int n=0; n<6; n++) {\n    sdata[threadIdx.x] = b[n];\n    blockReduce(sdata);\n\n    if (threadIdx.x == 0) {\n      v[blockIdx.x][n] += sdata[0];\n    }\n  }\n}\n\n__global__ void EvT6x1_kernel(\n  const torch::PackedTensorAccessor32<float,3,torch::RestrictPtrTraits> E,\n  const torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> x,\n  const torch::PackedTensorAccessor32<long,1,torch::RestrictPtrTraits> idx,\n  torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> w)\n{\n\n  const int D = E.size(2);\n  const int ix = idx[blockIdx.x];\n\n  if (idx[blockIdx.x] <= 0 || idx[blockIdx.x] >= x.size(0))\n    return;\n\n  for (int k=threadIdx.x; k<D; k+=blockDim.x) {\n    float dw = 0;\n    for (int n=0; n<6; n++) {\n      dw += E[blockIdx.x][n][k] * x[ix][n];\n    }\n    w[blockIdx.x][k] = dw;\n  }\n}\n\nclass SparseBlock {\n  public:\n\n    Eigen::SparseMatrix<double> A;\n    Eigen::VectorX<double> b;\n\n    SparseBlock(int N, int M) : N(N), M(M) {\n      A = Eigen::SparseMatrix<double>(N*M, N*M);\n      b = Eigen::VectorXd::Zero(N*M);\n    }\n\n    SparseBlock(Eigen::SparseMatrix<double> const& A, Eigen::VectorX<double> const& b, \n        int N, int M) : A(A), b(b), N(N), M(M) {}\n\n    void update_lhs(torch::Tensor As, torch::Tensor ii, torch::Tensor jj) {\n\n      auto As_cpu = As.to(torch::kCPU).to(torch::kFloat64);\n      auto ii_cpu = ii.to(torch::kCPU).to(torch::kInt64);\n      auto jj_cpu = jj.to(torch::kCPU).to(torch::kInt64);\n\n      auto As_acc = As_cpu.accessor<double,3>();\n      auto ii_acc = ii_cpu.accessor<long,1>();\n      auto jj_acc = jj_cpu.accessor<long,1>();\n\n      std::vector<T> tripletList;\n      for (int n=0; n<ii.size(0); n++) {\n        const int i = ii_acc[n];\n        const int j = jj_acc[n];\n\n        if (i >= 0 && j >= 0) {\n          for (int k=0; k<M; k++) {\n            for (int l=0; l<M; l++) {\n              double val = As_acc[n][k][l];\n              tripletList.push_back(T(M*i + k, M*j + l, val));\n            }\n          }\n        }\n      }\n      A.setFromTriplets(tripletList.begin(), tripletList.end());\n    }\n\n    void update_rhs(torch::Tensor bs, torch::Tensor ii) {\n      auto bs_cpu = bs.to(torch::kCPU).to(torch::kFloat64);\n      auto ii_cpu = ii.to(torch::kCPU).to(torch::kInt64);\n\n      auto bs_acc = bs_cpu.accessor<double,2>();\n      auto ii_acc = ii_cpu.accessor<long,1>();\n\n      for (int n=0; n<ii.size(0); n++) {\n        const int i = ii_acc[n];\n        if (i >= 0) {\n          for (int j=0; j<M; j++) {\n            b(i*M + j) += bs_acc[n][j];\n          }\n        }\n      }\n    }\n\n    SparseBlock operator-(const SparseBlock& S) {\n      return SparseBlock(A - S.A, b - S.b, N, M);\n    }\n\n    std::tuple<torch::Tensor, torch::Tensor> get_dense() {\n      Eigen::MatrixXd Ad = Eigen::MatrixXd(A);\n\n      torch::Tensor H = torch::from_blob(Ad.data(), {N*M, N*M}, torch::TensorOptions()\n        .dtype(torch::kFloat64)).to(torch::kCUDA).to(torch::kFloat32);\n\n      torch::Tensor v = torch::from_blob(b.data(), {N*M, 1}, torch::TensorOptions()\n        .dtype(torch::kFloat64)).to(torch::kCUDA).to(torch::kFloat32);\n\n      return std::make_tuple(H, v);\n\n    }\n\n    torch::Tensor solve(const float lm=0.0001, const float ep=0.1) {\n\n      torch::Tensor dx;\n\n      Eigen::SparseMatrix<double> L(A);\n      L.diagonal().array() += ep + lm * L.diagonal().array();\n\n      Eigen::SimplicialLLT<Eigen::SparseMatrix<double>> solver;\n      solver.compute(L);\n\n      if (solver.info() == Eigen::Success) {\n        Eigen::VectorXd x = solver.solve(b);\n        dx = torch::from_blob(x.data(), {N, M}, torch::TensorOptions()\n          .dtype(torch::kFloat64)).to(torch::kCUDA).to(torch::kFloat32);\n      }\n      else {\n        dx = torch::zeros({N, M}, torch::TensorOptions()\n          .device(torch::kCUDA).dtype(torch::kFloat32));\n      }\n      \n      return dx;\n    }\n\n  private:\n    const int N;\n    const int M;\n\n};\n\n\nSparseBlock schur_block(torch::Tensor E,\n                        torch::Tensor Q,\n                        torch::Tensor w,\n                        torch::Tensor ii,\n                        torch::Tensor jj,\n                        torch::Tensor kk,\n                        const int t0,\n                        const int t1)\n{\n\n  torch::Tensor ii_cpu = ii.to(torch::kCPU);\n  torch::Tensor jj_cpu = jj.to(torch::kCPU);\n  torch::Tensor kk_cpu = kk.to(torch::kCPU);\n\n  const int P = t1 - t0;\n  const long* ii_data = ii_cpu.data_ptr<long>();\n  const long* jj_data = jj_cpu.data_ptr<long>();\n  const long* kk_data = kk_cpu.data_ptr<long>();\n\n  std::vector<std::vector<long>> graph(P);\n  std::vector<std::vector<long>> index(P);\n\n  for (int n=0; n<ii_cpu.size(0); n++) {\n    const int j = jj_data[n];\n    const int k = kk_data[n];\n\n    if (j >= t0 && j <= t1) {\n      const int t = j - t0;\n      graph[t].push_back(k);\n      index[t].push_back(n);\n    }\n  }\n\n  std::vector<long> ii_list, jj_list, idx, jdx;\n\n  for (int i=0; i<P; i++) {\n    for (int j=0; j<P; j++) {\n      for (int k=0; k < graph[i].size(); k++) {\n        for (int l=0; l < graph[j].size(); l++) {\n          if (graph[i][k] == graph[j][l]) {\n            ii_list.push_back(i);\n            jj_list.push_back(j);\n\n            idx.push_back(index[i][k]);\n            idx.push_back(index[j][l]);\n            idx.push_back(graph[i][k]);\n          }\n        }\n      }\n    }\n  }\n\n  torch::Tensor ix_cuda = torch::from_blob(idx.data(), {long(idx.size())}, \n    torch::TensorOptions().dtype(torch::kInt64)).to(torch::kCUDA).view({-1, 3});\n\n  torch::Tensor jx_cuda = torch::stack({kk_cpu}, -1)\n    .to(torch::kCUDA).to(torch::kInt64);\n\n  torch::Tensor ii2_cpu = torch::from_blob(ii_list.data(), {long(ii_list.size())}, \n    torch::TensorOptions().dtype(torch::kInt64)).view({-1});\n\n  torch::Tensor jj2_cpu = torch::from_blob(jj_list.data(), {long(jj_list.size())}, \n    torch::TensorOptions().dtype(torch::kInt64)).view({-1});\n\n  torch::Tensor S = torch::zeros({ix_cuda.size(0), 6, 6}, \n    torch::TensorOptions().dtype(torch::kFloat32).device(torch::kCUDA));\n\n  torch::Tensor v = torch::zeros({jx_cuda.size(0), 6},\n    torch::TensorOptions().dtype(torch::kFloat32).device(torch::kCUDA));\n\n  EEt6x6_kernel<<<ix_cuda.size(0), THREADS>>>(\n    E.packed_accessor32<float,3,torch::RestrictPtrTraits>(),\n    Q.packed_accessor32<float,2,torch::RestrictPtrTraits>(),\n    ix_cuda.packed_accessor32<long,2,torch::RestrictPtrTraits>(),\n    S.packed_accessor32<float,3,torch::RestrictPtrTraits>());\n\n  Ev6x1_kernel<<<jx_cuda.size(0), THREADS>>>(\n    E.packed_accessor32<float,3,torch::RestrictPtrTraits>(),\n    Q.packed_accessor32<float,2,torch::RestrictPtrTraits>(),\n    w.packed_accessor32<float,2,torch::RestrictPtrTraits>(),\n    jx_cuda.packed_accessor32<long,2,torch::RestrictPtrTraits>(),\n    v.packed_accessor32<float,2,torch::RestrictPtrTraits>());\n\n  // schur block\n  SparseBlock A(P, 6);\n  A.update_lhs(S, ii2_cpu, jj2_cpu);\n  A.update_rhs(v, jj_cpu - t0);\n\n  return A;\n}\n\n\nstd::vector<torch::Tensor> ba_cuda(\n    torch::Tensor poses,\n    torch::Tensor disps,\n    torch::Tensor intrinsics,\n    torch::Tensor targets,\n    torch::Tensor weights,\n    torch::Tensor eta,\n    torch::Tensor ii,\n    torch::Tensor jj,\n    const int t0,\n    const int t1,\n    const int iterations,\n    const float lm,\n    const float ep,\n    const bool motion_only)\n{\n  auto opts = poses.options();\n  const int num = ii.size(0);\n  const int ht = disps.size(1);\n  const int wd = disps.size(2);\n\n  torch::Tensor ts = torch::arange(t0, t1).to(torch::kCUDA);\n  torch::Tensor ii_exp = torch::cat({ts, ii}, 0);\n  torch::Tensor jj_exp = torch::cat({ts, jj}, 0);\n\n  std::tuple<torch::Tensor, torch::Tensor> kuniq = \n    torch::_unique(ii_exp, true, true);\n\n  torch::Tensor kx = std::get<0>(kuniq);\n  torch::Tensor kk_exp = std::get<1>(kuniq);\n    \n  torch::Tensor dx;\n  torch::Tensor dz;\n\n  // initialize buffers\n  torch::Tensor Hs = torch::zeros({4, num, 6, 6}, opts);\n  torch::Tensor vs = torch::zeros({2, num, 6}, opts);\n  torch::Tensor Eii = torch::zeros({num, 6, ht*wd}, opts);\n  torch::Tensor Eij = torch::zeros({num, 6, ht*wd}, opts);\n  torch::Tensor Cii = torch::zeros({num, ht*wd}, opts);\n  torch::Tensor wi = torch::zeros({num, ht*wd}, opts);\n\n  for (int itr=0; itr<iterations; itr++) {\n\n    projective_transform_kernel<<<num, THREADS>>>(\n      targets.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n      weights.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n      poses.packed_accessor32<float,2,torch::RestrictPtrTraits>(),\n      disps.packed_accessor32<float,3,torch::RestrictPtrTraits>(),\n      intrinsics.packed_accessor32<float,1,torch::RestrictPtrTraits>(),\n      ii.packed_accessor32<long,1,torch::RestrictPtrTraits>(),\n      jj.packed_accessor32<long,1,torch::RestrictPtrTraits>(),\n      Hs.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n      vs.packed_accessor32<float,3,torch::RestrictPtrTraits>(),\n      Eii.packed_accessor32<float,3,torch::RestrictPtrTraits>(),\n      Eij.packed_accessor32<float,3,torch::RestrictPtrTraits>(),\n      Cii.packed_accessor32<float,2,torch::RestrictPtrTraits>(),\n      wi.packed_accessor32<float,2,torch::RestrictPtrTraits>());\n\n\n    // pose x pose block\n    SparseBlock A(t1 - t0, 6);\n\n    A.update_lhs(Hs.reshape({-1, 6, 6}), \n        torch::cat({ii, ii, jj, jj}) - t0, \n        torch::cat({ii, jj, ii, jj}) - t0);\n\n    A.update_rhs(vs.reshape({-1, 6}), \n        torch::cat({ii, jj}) - t0);\n\n    if (motion_only) {\n      dx = A.solve(lm, ep);\n\n      // update poses\n      pose_retr_kernel<<<1, THREADS>>>(\n        poses.packed_accessor32<float,2,torch::RestrictPtrTraits>(),\n        dx.packed_accessor32<float,2,torch::RestrictPtrTraits>(), t0, t1);\n    }\n    \n    else {\n\n      torch::Tensor C = accum_cuda(Cii, ii, kx);\n      torch::Tensor w = accum_cuda(wi, ii, kx);\n      torch::Tensor Q = 1.0 / (C + eta.view({-1, ht*wd}));\n\n      torch::Tensor Ei = accum_cuda(Eii.view({num, 6*ht*wd}), ii, ts).view({t1-t0, 6, ht*wd});\n      torch::Tensor E = torch::cat({Ei, Eij}, 0);\n\n      SparseBlock S = schur_block(E, Q, w, ii_exp, jj_exp, kk_exp, t0, t1);\n      dx = (A - S).solve(lm, ep);\n\n      torch::Tensor ix = jj_exp - t0;\n      torch::Tensor dw = torch::zeros({ix.size(0), ht*wd}, opts);\n\n      EvT6x1_kernel<<<ix.size(0), THREADS>>>(\n        E.packed_accessor32<float,3,torch::RestrictPtrTraits>(),\n        dx.packed_accessor32<float,2,torch::RestrictPtrTraits>(),\n        ix.packed_accessor32<long,1,torch::RestrictPtrTraits>(),\n        dw.packed_accessor32<float,2,torch::RestrictPtrTraits>());\n\n      dz = Q * (w - accum_cuda(dw, ii_exp, kx));\n\n      // update poses\n      pose_retr_kernel<<<1, THREADS>>>(\n        poses.packed_accessor32<float,2,torch::RestrictPtrTraits>(),\n        dx.packed_accessor32<float,2,torch::RestrictPtrTraits>(), t0, t1);\n\n      // update disparity maps\n      disp_retr_kernel<<<kx.size(0), THREADS>>>(\n        disps.packed_accessor32<float,3,torch::RestrictPtrTraits>(),\n        dz.packed_accessor32<float,2,torch::RestrictPtrTraits>(),\n        kx.packed_accessor32<long,1,torch::RestrictPtrTraits>());\n    }\n\n  }\n\n  return {dx, dz};\n}\n\n\n\ntorch::Tensor frame_distance_cuda(\n    torch::Tensor poses,\n    torch::Tensor disps,\n    torch::Tensor intrinsics,\n    torch::Tensor ii,\n    torch::Tensor jj,\n    const float beta)\n{\n  auto opts = poses.options();\n  const int num = ii.size(0);\n\n  torch::Tensor dist = torch::zeros({num}, opts);\n\n  frame_distance_kernel<<<num, THREADS>>>(\n    poses.packed_accessor32<float,2,torch::RestrictPtrTraits>(),\n    disps.packed_accessor32<float,3,torch::RestrictPtrTraits>(),\n    intrinsics.packed_accessor32<float,1,torch::RestrictPtrTraits>(),\n    ii.packed_accessor32<long,1,torch::RestrictPtrTraits>(),\n    jj.packed_accessor32<long,1,torch::RestrictPtrTraits>(),\n    dist.packed_accessor32<float,1,torch::RestrictPtrTraits>(), beta);\n\n  return dist;\n}\n\n\nstd::vector<torch::Tensor> projmap_cuda(\n    torch::Tensor poses,\n    torch::Tensor disps,\n    torch::Tensor intrinsics,\n    torch::Tensor ii,\n    torch::Tensor jj)\n{\n  auto opts = poses.options();\n  const int num = ii.size(0);\n  const int ht = disps.size(1);\n  const int wd = disps.size(2);\n\n  torch::Tensor coords = torch::zeros({num, ht, wd, 3}, opts);\n  torch::Tensor valid = torch::zeros({num, ht, wd, 1}, opts);\n\n  projmap_kernel<<<num, THREADS>>>(\n    poses.packed_accessor32<float,2,torch::RestrictPtrTraits>(),\n    disps.packed_accessor32<float,3,torch::RestrictPtrTraits>(),\n    intrinsics.packed_accessor32<float,1,torch::RestrictPtrTraits>(),\n    ii.packed_accessor32<long,1,torch::RestrictPtrTraits>(),\n    jj.packed_accessor32<long,1,torch::RestrictPtrTraits>(),\n    coords.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    valid.packed_accessor32<float,4,torch::RestrictPtrTraits>());\n\n  return {coords, valid};\n}\n\n\ntorch::Tensor depth_filter_cuda(\n    torch::Tensor poses,\n    torch::Tensor disps,\n    torch::Tensor intrinsics,\n    torch::Tensor ix,\n    torch::Tensor thresh)\n{\n  const int num = ix.size(0);\n  const int ht = disps.size(1);\n  const int wd = disps.size(2);\n\n  torch::Tensor counter = torch::zeros({num, ht, wd}, disps.options());\n\n  dim3 blocks(num, 6, NUM_BLOCKS(ht * wd));\n\n  depth_filter_kernel<<<blocks, THREADS>>>(\n    poses.packed_accessor32<float,2,torch::RestrictPtrTraits>(),\n    disps.packed_accessor32<float,3,torch::RestrictPtrTraits>(),\n    intrinsics.packed_accessor32<float,1,torch::RestrictPtrTraits>(),\n    ix.packed_accessor32<long,1,torch::RestrictPtrTraits>(),\n    thresh.packed_accessor32<float,1,torch::RestrictPtrTraits>(),\n    counter.packed_accessor32<float,3,torch::RestrictPtrTraits>());\n\n  return counter;\n}\n\n\ntorch::Tensor iproj_cuda(\n    torch::Tensor poses,\n    torch::Tensor disps,\n    torch::Tensor intrinsics)\n{\n\n  const int nm = disps.size(0);\n  const int ht = disps.size(1);\n  const int wd = disps.size(2);\n\n  auto opts = disps.options();\n  torch::Tensor points = torch::zeros({nm, ht, wd, 3}, opts);\n\n  dim3 blocks(nm, NUM_BLOCKS(ht * wd));\n\n  iproj_kernel<<<blocks, THREADS>>>(\n    poses.packed_accessor32<float,2,torch::RestrictPtrTraits>(),\n    disps.packed_accessor32<float,3,torch::RestrictPtrTraits>(),\n    intrinsics.packed_accessor32<float,1,torch::RestrictPtrTraits>(),\n    points.packed_accessor32<float,4,torch::RestrictPtrTraits>());\n\n  return points;\n\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/.gitignore",
    "content": "qrc_*cxx\n*.orig\n*.pyc\n*.diff\ndiff\n*.save\nsave\n*.old\n*.gmo\n*.qm\ncore\ncore.*\n*.bak\n*~\n*build*\n*.moc.*\n*.moc\nui_*\nCMakeCache.txt\ntags\n.*.swp\nactivity.png\n*.out\n*.php*\n*.log\n*.orig\n*.rej\nlog\npatch\n*.patch\na\na.*\nlapack/testing\nlapack/reference\n.*project\n.settings\nMakefile\n!ci/build.gitlab-ci.yml\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/.gitlab/issue_templates/Bug Report.md",
    "content": "<!--\nPlease read this!\n\nBefore opening a new issue, make sure to search for keywords in the issues\nfiltered by \"bug::confirmed\" or \"bug::unconfirmed\" and \"bugzilla\" label:\n\n- https://gitlab.com/libeigen/eigen/-/issues?scope=all&utf8=%E2%9C%93&state=opened&label_name[]=bug%3A%3Aconfirmed\n- https://gitlab.com/libeigen/eigen/-/issues?scope=all&utf8=%E2%9C%93&state=opened&label_name[]=bug%3A%3Aunconfirmed\n- https://gitlab.com/libeigen/eigen/-/issues?scope=all&utf8=%E2%9C%93&state=opened&label_name[]=bugzilla\n\nand verify the issue you're about to submit isn't a duplicate. -->\n\n### Summary\n<!-- Summarize the bug encountered concisely. -->\n\n### Environment\n<!-- Please provide your development environment here -->\n- **Operating System** : Windows/Linux\n- **Architecture** : x64/Arm64/PowerPC ...\n- **Eigen Version** : 3.3.9\n- **Compiler Version** : Gcc7.0\n- **Compile Flags** : -O3 -march=native\n- **Vector Extension** : SSE/AVX/NEON ...\n\n### Minimal Example\n<!-- If possible, please create a minimal example here that exhibits the problematic behavior.\nYou can also link to [godbolt](https://godbolt.org). But please note that you need to click \nthe \"Share\" button in the top right-hand corner of the godbolt page where you reproduce the sample \ncode to get the share link instead of in your browser address bar. \n\nYou can read [the guidelines on stackoverflow](https://stackoverflow.com/help/minimal-reproducible-example)\non how to create a good minimal example. -->\n\n```cpp\n//show your code here\n```\n\n### Steps to reproduce\n<!-- Describe how one can reproduce the issue - this is very important. Please use an ordered list. -->\n\n1. first step\n2. second step\n3. ... \n\n### What is the current *bug* behavior?\n<!-- Describe what actually happens. -->\n\n### What is the expected *correct* behavior?\n<!-- Describe what you should see instead. -->\n\n### Relevant logs\n<!-- Add relevant code snippets or program output within blocks marked by \" ``` \" -->\n\n<!-- OPTIONAL: remove this section if you are not reporting a compilation warning issue.-->\n### Warning Messages\n<!-- Show us the warning messages you got! -->\n\n<!-- OPTIONAL: remove this section if you are not reporting a performance issue. -->\n### Benchmark scripts and results\n<!-- Please share any benchmark scripts - either standalone, or using [Google Benchmark](https://github.com/google/benchmark). -->\n\n### Anything else that might help\n<!-- It will be better to provide us more information to help narrow down the cause. \nIncluding but not limited to the following: \n- lines of code that might help us diagnose the problem. \n- potential ways to address the issue.\n- last known working/first broken version (release number or commit hash). --> \n\n- [ ] Have a plan to fix this issue.\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/.gitlab/issue_templates/Feature Request.md",
    "content": "### Describe the feature you would like to be implemented.\n\n### Would such a feature be useful for other users? Why?\n\n### Any hints on how to implement the requested feature?\n\n### Additional resources\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/.gitlab/merge_request_templates/Merge Request Template.md",
    "content": "<!-- \nThanks for contributing a merge request! Please name and fully describe your MR as you would for a commit message.\nIf the MR fixes an issue, please include \"Fixes #issue\" in the commit message and the MR description.\n\nIn addition, we recommend that first-time contributors read our [contribution guidelines](https://eigen.tuxfamily.org/index.php?title=Contributing_to_Eigen) and [git page](https://eigen.tuxfamily.org/index.php?title=Git), which will help you submit a more standardized MR.\n\nBefore submitting the MR, you also need to complete the following checks:\n- Make one PR per feature/bugfix (don't mix multiple changes into one PR). Avoid committing unrelated changes.\n- Rebase before committing\n- For code changes, run the test suite (at least the tests that are likely affected by the change).\n  See our [test guidelines](https://eigen.tuxfamily.org/index.php?title=Tests).\n- If possible, add a test (both for bug-fixes as well as new features)\n- Make sure new features are documented\n\nNote that we are a team of volunteers; we appreciate your patience during the review process.\n\nAgain, thanks for contributing! -->\n\n### Reference issue\n<!-- You can link to a specific issue using the gitlab syntax #<issue number>  -->\n\n### What does this implement/fix?\n<!--Please explain your changes.-->\n\n### Additional information\n<!--Any additional information you think is important.-->\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/.gitlab-ci.yml",
    "content": "# This file is part of Eigen, a lightweight C++ template library\n# for linear algebra.\n#\n# Copyright (C) 2020 Arm Ltd. and Contributors\n#\n# This Source Code Form is subject to the terms of the Mozilla\n# Public License v. 2.0. If a copy of the MPL was not distributed\n# with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\nstages:\n  - buildsmoketests\n  - smoketests\n  - build\n  - test\n\nvariables:\n  BUILDDIR: builddir\n  EIGEN_CI_CMAKE_GENEATOR: \"Ninja\"\n\ninclude:\n  - \"/ci/smoketests.gitlab-ci.yml\"\n  - \"/ci/build.gitlab-ci.yml\"\n  - \"/ci/test.gitlab-ci.yml\"\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/.hgeol",
    "content": "[patterns]\n*.sh = LF\n*.MINPACK = CRLF\nscripts/*.in = LF\ndebug/msvc/*.dat = CRLF\ndebug/msvc/*.natvis = CRLF\nunsupported/test/mpreal/*.* = CRLF\n** = native\n\n[repository]\nnative = LF\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/CMakeLists.txt",
    "content": "# cmake_minimum_require must be the first command of the file\ncmake_minimum_required(VERSION 3.5.0)\n\nproject(Eigen3)\n\nset(CMAKE_CXX_STANDARD 11 CACHE STRING \"Default C++ standard\")\nset(CMAKE_CXX_STANDARD_REQUIRED ON CACHE BOOL \"Require C++ standard\")\nset(CMAKE_CXX_EXTENSIONS OFF CACHE BOOL \"Allow C++ extensions\")\n\n# guard against in-source builds\n\nif(${CMAKE_SOURCE_DIR} STREQUAL ${CMAKE_BINARY_DIR})\n  message(FATAL_ERROR \"In-source builds not allowed. Please make a new directory (called a build directory) and run CMake from there. You may need to remove CMakeCache.txt. \")\nendif()\n\n\n# Alias Eigen_*_DIR to Eigen3_*_DIR:\n\nset(Eigen_SOURCE_DIR ${Eigen3_SOURCE_DIR})\nset(Eigen_BINARY_DIR ${Eigen3_BINARY_DIR})\n\n# guard against bad build-type strings\n\nif (NOT CMAKE_BUILD_TYPE)\n  set(CMAKE_BUILD_TYPE \"Release\")\nendif()\n\n\n#############################################################################\n# retrieve version information                                               #\n#############################################################################\n\n# automatically parse the version number\nfile(READ \"${PROJECT_SOURCE_DIR}/Eigen/src/Core/util/Macros.h\" _eigen_version_header)\nstring(REGEX MATCH \"define[ \\t]+EIGEN_WORLD_VERSION[ \\t]+([0-9]+)\" _eigen_world_version_match \"${_eigen_version_header}\")\nset(EIGEN_WORLD_VERSION \"${CMAKE_MATCH_1}\")\nstring(REGEX MATCH \"define[ \\t]+EIGEN_MAJOR_VERSION[ \\t]+([0-9]+)\" _eigen_major_version_match \"${_eigen_version_header}\")\nset(EIGEN_MAJOR_VERSION \"${CMAKE_MATCH_1}\")\nstring(REGEX MATCH \"define[ \\t]+EIGEN_MINOR_VERSION[ \\t]+([0-9]+)\" _eigen_minor_version_match \"${_eigen_version_header}\")\nset(EIGEN_MINOR_VERSION \"${CMAKE_MATCH_1}\")\nset(EIGEN_VERSION_NUMBER ${EIGEN_WORLD_VERSION}.${EIGEN_MAJOR_VERSION}.${EIGEN_MINOR_VERSION})\n\n# if we are not in a git clone\nif(IS_DIRECTORY ${CMAKE_SOURCE_DIR}/.git)\n  # if the git program is absent or this will leave the EIGEN_GIT_REVNUM string empty,\n  # but won't stop CMake.\n  execute_process(COMMAND git ls-remote --refs -q ${CMAKE_SOURCE_DIR} HEAD OUTPUT_VARIABLE EIGEN_GIT_OUTPUT)\nendif()\n\n# extract the git rev number from the git output...\nif(EIGEN_GIT_OUTPUT)\nstring(REGEX MATCH \"^([0-9;a-f]+).*\" EIGEN_GIT_CHANGESET_MATCH \"${EIGEN_GIT_OUTPUT}\")\nset(EIGEN_GIT_REVNUM \"${CMAKE_MATCH_1}\")\nendif()\n#...and show it next to the version number\nif(EIGEN_GIT_REVNUM)\n  set(EIGEN_VERSION \"${EIGEN_VERSION_NUMBER} (git rev ${EIGEN_GIT_REVNUM})\")\nelse()\n  set(EIGEN_VERSION \"${EIGEN_VERSION_NUMBER}\")\nendif()\n\ninclude(CheckCXXCompilerFlag)\ninclude(GNUInstallDirs)\ninclude(CMakeDependentOption)\n\nset(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake)\n\n\noption(EIGEN_TEST_CXX11 \"Enable testing of unsupported CXX11 tests (i.e. those starting with cxx11_).\" OFF)\n\nmacro(ei_add_cxx_compiler_flag FLAG)\n  string(REGEX REPLACE \"-\" \"\" SFLAG1 ${FLAG})\n  string(REGEX REPLACE \"\\\\+\" \"p\" SFLAG ${SFLAG1})\n  check_cxx_compiler_flag(${FLAG} COMPILER_SUPPORT_${SFLAG})\n  if(COMPILER_SUPPORT_${SFLAG})\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} ${FLAG}\")\n  endif()\nendmacro()\n\n# Determine if we should build shared libraries on this platform.\nget_cmake_property(EIGEN_BUILD_SHARED_LIBS TARGET_SUPPORTS_SHARED_LIBS)\n\n#############################################################################\n# find how to link to the standard libraries                                #\n#############################################################################\n\nfind_package(StandardMathLibrary)\n\n\nset(EIGEN_TEST_CUSTOM_LINKER_FLAGS  \"\" CACHE STRING \"Additional linker flags when linking unit tests.\")\nset(EIGEN_TEST_CUSTOM_CXX_FLAGS     \"\" CACHE STRING \"Additional compiler flags when compiling unit tests.\")\n\nset(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO \"\")\n\nif(NOT STANDARD_MATH_LIBRARY_FOUND)\n\n  message(FATAL_ERROR\n    \"Can't link to the standard math library. Please report to the Eigen developers, telling them about your platform.\")\n\nelse()\n\n  if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO)\n    set(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO \"${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO} ${STANDARD_MATH_LIBRARY}\")\n  else()\n    set(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO \"${STANDARD_MATH_LIBRARY}\")\n  endif()\n\nendif()\n\nif(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO)\n  message(STATUS \"Standard libraries to link to explicitly: ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO}\")\nelse()\n  message(STATUS \"Standard libraries to link to explicitly: none\")\nendif()\n\noption(EIGEN_BUILD_BTL \"Build benchmark suite\" OFF)\n\n# Disable pkgconfig only for native Windows builds\nif(NOT WIN32 OR NOT CMAKE_HOST_SYSTEM_NAME MATCHES Windows)\n  option(EIGEN_BUILD_PKGCONFIG \"Build pkg-config .pc file for Eigen\" ON)\nendif()\n\nset(CMAKE_INCLUDE_CURRENT_DIR OFF)\n\noption(EIGEN_SPLIT_LARGE_TESTS \"Split large tests into smaller executables\" ON)\n\noption(EIGEN_DEFAULT_TO_ROW_MAJOR \"Use row-major as default matrix storage order\" OFF)\nif(EIGEN_DEFAULT_TO_ROW_MAJOR)\n  add_definitions(\"-DEIGEN_DEFAULT_TO_ROW_MAJOR\")\nendif()\n\nset(EIGEN_TEST_MAX_SIZE \"320\" CACHE STRING \"Maximal matrix/vector size, default is 320\")\n\nif(NOT MSVC)\n  # We assume that other compilers are partly compatible with GNUCC\n\n  # clang outputs some warnings for unknown flags that are not caught by check_cxx_compiler_flag\n  # adding -Werror turns such warnings into errors\n  check_cxx_compiler_flag(\"-Werror\" COMPILER_SUPPORT_WERROR)\n  if(COMPILER_SUPPORT_WERROR)\n    set(CMAKE_REQUIRED_FLAGS \"-Werror\")\n  endif()\n  ei_add_cxx_compiler_flag(\"-pedantic\")\n  ei_add_cxx_compiler_flag(\"-Wall\")\n  ei_add_cxx_compiler_flag(\"-Wextra\")\n  #ei_add_cxx_compiler_flag(\"-Weverything\")              # clang\n\n  ei_add_cxx_compiler_flag(\"-Wundef\")\n  ei_add_cxx_compiler_flag(\"-Wcast-align\")\n  ei_add_cxx_compiler_flag(\"-Wchar-subscripts\")\n  ei_add_cxx_compiler_flag(\"-Wnon-virtual-dtor\")\n  ei_add_cxx_compiler_flag(\"-Wunused-local-typedefs\")\n  ei_add_cxx_compiler_flag(\"-Wpointer-arith\")\n  ei_add_cxx_compiler_flag(\"-Wwrite-strings\")\n  ei_add_cxx_compiler_flag(\"-Wformat-security\")\n  ei_add_cxx_compiler_flag(\"-Wshorten-64-to-32\")\n  ei_add_cxx_compiler_flag(\"-Wlogical-op\")\n  ei_add_cxx_compiler_flag(\"-Wenum-conversion\")\n  ei_add_cxx_compiler_flag(\"-Wc++11-extensions\")\n  ei_add_cxx_compiler_flag(\"-Wdouble-promotion\")\n#  ei_add_cxx_compiler_flag(\"-Wconversion\")\n\n  ei_add_cxx_compiler_flag(\"-Wshadow\")\n\n  ei_add_cxx_compiler_flag(\"-Wno-psabi\")\n  ei_add_cxx_compiler_flag(\"-Wno-variadic-macros\")\n  ei_add_cxx_compiler_flag(\"-Wno-long-long\")\n\n  ei_add_cxx_compiler_flag(\"-fno-check-new\")\n  ei_add_cxx_compiler_flag(\"-fno-common\")\n  ei_add_cxx_compiler_flag(\"-fstrict-aliasing\")\n  ei_add_cxx_compiler_flag(\"-wd981\")                    # disable ICC's \"operands are evaluated in unspecified order\" remark\n  ei_add_cxx_compiler_flag(\"-wd2304\")                   # disable ICC's \"warning #2304: non-explicit constructor with single argument may cause implicit type conversion\" produced by -Wnon-virtual-dtor\n\n  if(ANDROID_NDK)\n    ei_add_cxx_compiler_flag(\"-pie\")\n    ei_add_cxx_compiler_flag(\"-fPIE\")\n  endif()\n\n  set(CMAKE_REQUIRED_FLAGS \"\")\n\n  option(EIGEN_TEST_SSE2 \"Enable/Disable SSE2 in tests/examples\" OFF)\n  if(EIGEN_TEST_SSE2)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -msse2\")\n    message(STATUS \"Enabling SSE2 in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_SSE3 \"Enable/Disable SSE3 in tests/examples\" OFF)\n  if(EIGEN_TEST_SSE3)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -msse3\")\n    message(STATUS \"Enabling SSE3 in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_SSSE3 \"Enable/Disable SSSE3 in tests/examples\" OFF)\n  if(EIGEN_TEST_SSSE3)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mssse3\")\n    message(STATUS \"Enabling SSSE3 in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_SSE4_1 \"Enable/Disable SSE4.1 in tests/examples\" OFF)\n  if(EIGEN_TEST_SSE4_1)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -msse4.1\")\n    message(STATUS \"Enabling SSE4.1 in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_SSE4_2 \"Enable/Disable SSE4.2 in tests/examples\" OFF)\n  if(EIGEN_TEST_SSE4_2)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -msse4.2\")\n    message(STATUS \"Enabling SSE4.2 in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_AVX \"Enable/Disable AVX in tests/examples\" OFF)\n  if(EIGEN_TEST_AVX)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mavx\")\n    message(STATUS \"Enabling AVX in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_FMA \"Enable/Disable FMA in tests/examples\" OFF)\n  if(EIGEN_TEST_FMA AND NOT EIGEN_TEST_NEON)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mfma\")\n    message(STATUS \"Enabling FMA in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_AVX2 \"Enable/Disable AVX2 in tests/examples\" OFF)\n  if(EIGEN_TEST_AVX2)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mavx2 -mfma\")\n    message(STATUS \"Enabling AVX2 in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_AVX512 \"Enable/Disable AVX512 in tests/examples\" OFF)\n  if(EIGEN_TEST_AVX512)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mavx512f -mfma\")\n    if (NOT \"${CMAKE_CXX_COMPILER_ID}\" STREQUAL \"Clang\")\n      set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -fabi-version=6\")\n    endif()\n    message(STATUS \"Enabling AVX512 in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_AVX512DQ \"Enable/Disable AVX512DQ in tests/examples\" OFF)\n  if(EIGEN_TEST_AVX512DQ)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mavx512dq\")\n    if (NOT \"${CMAKE_CXX_COMPILER_ID}\" STREQUAL \"Clang\")\n      set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -fabi-version=6\")\n    endif()\n    message(STATUS \"Enabling AVX512DQ in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_F16C \"Enable/Disable F16C in tests/examples\" OFF)\n  if(EIGEN_TEST_F16C)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mf16c\")\n    message(STATUS \"Enabling F16C in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_ALTIVEC \"Enable/Disable AltiVec in tests/examples\" OFF)\n  if(EIGEN_TEST_ALTIVEC)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -maltivec -mabi=altivec\")\n    message(STATUS \"Enabling AltiVec in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_VSX \"Enable/Disable VSX in tests/examples\" OFF)\n  if(EIGEN_TEST_VSX)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -m64 -mvsx\")\n    message(STATUS \"Enabling VSX in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_MSA \"Enable/Disable MSA in tests/examples\" OFF)\n  if(EIGEN_TEST_MSA)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mmsa\")\n    message(STATUS \"Enabling MSA in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_NEON \"Enable/Disable Neon in tests/examples\" OFF)\n  if(EIGEN_TEST_NEON)\n    if(EIGEN_TEST_FMA)\n      set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mfpu=neon-vfpv4\")\n    else()\n      set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mfpu=neon\")\n    endif()\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mfloat-abi=hard\")\n    message(STATUS \"Enabling NEON in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_NEON64 \"Enable/Disable Neon in tests/examples\" OFF)\n  if(EIGEN_TEST_NEON64)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS}\")\n    message(STATUS \"Enabling NEON in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_Z13 \"Enable/Disable S390X(zEC13) ZVECTOR in tests/examples\" OFF)\n  if(EIGEN_TEST_Z13)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -march=z13 -mzvector\")\n    message(STATUS \"Enabling S390X(zEC13) ZVECTOR in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_Z14 \"Enable/Disable S390X(zEC14) ZVECTOR in tests/examples\" OFF)\n  if(EIGEN_TEST_Z14)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -march=z14 -mzvector\")\n    message(STATUS \"Enabling S390X(zEC13) ZVECTOR in tests/examples\")\n  endif()\n\n  check_cxx_compiler_flag(\"-fopenmp\" COMPILER_SUPPORT_OPENMP)\n  if(COMPILER_SUPPORT_OPENMP)\n    option(EIGEN_TEST_OPENMP \"Enable/Disable OpenMP in tests/examples\" OFF)\n    if(EIGEN_TEST_OPENMP)\n      set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -fopenmp\")\n      message(STATUS \"Enabling OpenMP in tests/examples\")\n    endif()\n  endif()\n\nelse()\n\n  # C4127 - conditional expression is constant\n  # C4714 - marked as __forceinline not inlined (I failed to deactivate it selectively)\n  #         We can disable this warning in the unit tests since it is clear that it occurs\n  #         because we are oftentimes returning objects that have a destructor or may\n  #         throw exceptions - in particular in the unit tests we are throwing extra many\n  #         exceptions to cover indexing errors.\n  # C4505 - unreferenced local function has been removed (impossible to deactivate selectively)\n  set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} /EHsc /wd4127 /wd4505 /wd4714\")\n\n  # replace all /Wx by /W4\n  string(REGEX REPLACE \"/W[0-9]\" \"/W4\" CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS}\")\n\n  check_cxx_compiler_flag(\"/openmp\" COMPILER_SUPPORT_OPENMP)\n  if(COMPILER_SUPPORT_OPENMP)\n    option(EIGEN_TEST_OPENMP \"Enable/Disable OpenMP in tests/examples\" OFF)\n    if(EIGEN_TEST_OPENMP)\n      set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} /openmp\")\n      message(STATUS \"Enabling OpenMP in tests/examples\")\n    endif()\n  endif()\n\n  option(EIGEN_TEST_SSE2 \"Enable/Disable SSE2 in tests/examples\" OFF)\n  if(EIGEN_TEST_SSE2)\n    if(NOT CMAKE_CL_64)\n      # arch is not supported on 64 bit systems, SSE is enabled automatically.\n      set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} /arch:SSE2\")\n    endif()\n    message(STATUS \"Enabling SSE2 in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_AVX \"Enable/Disable AVX in tests/examples\" OFF)\n  if(EIGEN_TEST_AVX)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} /arch:AVX\")\n    message(STATUS \"Enabling AVX in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_FMA \"Enable/Disable FMA/AVX2 in tests/examples\" OFF)\n  if(EIGEN_TEST_FMA AND NOT EIGEN_TEST_NEON)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} /arch:AVX2\")\n    message(STATUS \"Enabling FMA/AVX2 in tests/examples\")\n  endif()\n\nendif()\n\noption(EIGEN_TEST_NO_EXPLICIT_VECTORIZATION \"Disable explicit vectorization in tests/examples\" OFF)\noption(EIGEN_TEST_X87 \"Force using X87 instructions. Implies no vectorization.\" OFF)\noption(EIGEN_TEST_32BIT \"Force generating 32bit code.\" OFF)\n\nif(EIGEN_TEST_X87)\n  set(EIGEN_TEST_NO_EXPLICIT_VECTORIZATION ON)\n  if(CMAKE_COMPILER_IS_GNUCXX)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mfpmath=387\")\n    message(STATUS \"Forcing use of x87 instructions in tests/examples\")\n  else()\n    message(STATUS \"EIGEN_TEST_X87 ignored on your compiler\")\n  endif()\nendif()\n\nif(EIGEN_TEST_32BIT)\n  if(CMAKE_COMPILER_IS_GNUCXX)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -m32\")\n    message(STATUS \"Forcing generation of 32-bit code in tests/examples\")\n  else()\n    message(STATUS \"EIGEN_TEST_32BIT ignored on your compiler\")\n  endif()\nendif()\n\nif(EIGEN_TEST_NO_EXPLICIT_VECTORIZATION)\n  add_definitions(-DEIGEN_DONT_VECTORIZE=1)\n  message(STATUS \"Disabling vectorization in tests/examples\")\nendif()\n\noption(EIGEN_TEST_NO_EXPLICIT_ALIGNMENT \"Disable explicit alignment (hence vectorization) in tests/examples\" OFF)\nif(EIGEN_TEST_NO_EXPLICIT_ALIGNMENT)\n  add_definitions(-DEIGEN_DONT_ALIGN=1)\n  message(STATUS \"Disabling alignment in tests/examples\")\nendif()\n\noption(EIGEN_TEST_NO_EXCEPTIONS \"Disables C++ exceptions\" OFF)\nif(EIGEN_TEST_NO_EXCEPTIONS)\n  ei_add_cxx_compiler_flag(\"-fno-exceptions\")\n  message(STATUS \"Disabling exceptions in tests/examples\")\nendif()\n\nset(EIGEN_CUDA_COMPUTE_ARCH 30 CACHE STRING \"The CUDA compute architecture level to target when compiling CUDA code\")\n\ninclude_directories(${CMAKE_CURRENT_SOURCE_DIR})\n\n# Backward compatibility support for EIGEN_INCLUDE_INSTALL_DIR\nif(EIGEN_INCLUDE_INSTALL_DIR)\n  message(WARNING \"EIGEN_INCLUDE_INSTALL_DIR is deprecated. Use INCLUDE_INSTALL_DIR instead.\")\nendif()\n\nif(EIGEN_INCLUDE_INSTALL_DIR AND NOT INCLUDE_INSTALL_DIR)\n  set(INCLUDE_INSTALL_DIR ${EIGEN_INCLUDE_INSTALL_DIR}\n      CACHE PATH \"The directory relative to CMAKE_INSTALL_PREFIX where Eigen header files are installed\")\nelse()\n  set(INCLUDE_INSTALL_DIR\n      \"${CMAKE_INSTALL_INCLUDEDIR}/eigen3\"\n      CACHE PATH \"The directory relative to CMAKE_INSTALL_PREFIX where Eigen header files are installed\"\n      )\nendif()\nset(CMAKEPACKAGE_INSTALL_DIR\n    \"${CMAKE_INSTALL_DATADIR}/eigen3/cmake\"\n    CACHE PATH \"The directory relative to CMAKE_INSTALL_PREFIX where Eigen3Config.cmake is installed\"\n    )\nset(PKGCONFIG_INSTALL_DIR\n    \"${CMAKE_INSTALL_DATADIR}/pkgconfig\"\n    CACHE PATH \"The directory relative to CMAKE_INSTALL_PREFIX where eigen3.pc is installed\"\n    )\n\nforeach(var INCLUDE_INSTALL_DIR CMAKEPACKAGE_INSTALL_DIR PKGCONFIG_INSTALL_DIR)\n  # If an absolute path is specified, make it relative to \"{CMAKE_INSTALL_PREFIX}\".\n  if(IS_ABSOLUTE \"${${var}}\")\n    file(RELATIVE_PATH \"${var}\" \"${CMAKE_INSTALL_PREFIX}\" \"${${var}}\")\n  endif()\nendforeach()\n\n# similar to set_target_properties but append the property instead of overwriting it\nmacro(ei_add_target_property target prop value)\n\n  get_target_property(previous ${target} ${prop})\n  # if the property wasn't previously set, ${previous} is now \"previous-NOTFOUND\" which cmake allows catching with plain if()\n  if(NOT previous)\n    set(previous \"\")\n  endif()\n  set_target_properties(${target} PROPERTIES ${prop} \"${previous} ${value}\")\nendmacro()\n\ninstall(FILES\n  signature_of_eigen3_matrix_library\n  DESTINATION ${INCLUDE_INSTALL_DIR} COMPONENT Devel\n  )\n\nif(EIGEN_BUILD_PKGCONFIG)\n    configure_file(eigen3.pc.in eigen3.pc @ONLY)\n    install(FILES ${CMAKE_CURRENT_BINARY_DIR}/eigen3.pc\n        DESTINATION ${PKGCONFIG_INSTALL_DIR}\n        )\nendif()\n\ninstall(DIRECTORY Eigen DESTINATION ${INCLUDE_INSTALL_DIR} COMPONENT Devel)\n\n\noption(EIGEN_BUILD_DOC \"Enable creation of Eigen documentation\" ON)\nif(EIGEN_BUILD_DOC)\n  add_subdirectory(doc EXCLUDE_FROM_ALL)\nendif()\n\n\noption(BUILD_TESTING \"Enable creation of Eigen tests.\" ON)\nif(BUILD_TESTING)\n  include(EigenConfigureTesting)\n\n  if(EIGEN_LEAVE_TEST_IN_ALL_TARGET)\n    add_subdirectory(test) # can't do EXCLUDE_FROM_ALL here, breaks CTest\n  else()\n    add_subdirectory(test EXCLUDE_FROM_ALL)\n  endif()\n\n  add_subdirectory(failtest)\nendif()\n\nif(EIGEN_LEAVE_TEST_IN_ALL_TARGET)\n  add_subdirectory(blas)\n  add_subdirectory(lapack)\nelse()\n  add_subdirectory(blas EXCLUDE_FROM_ALL)\n  add_subdirectory(lapack EXCLUDE_FROM_ALL)\nendif()\n\n# add SYCL\noption(EIGEN_TEST_SYCL \"Add Sycl support.\" OFF)\noption(EIGEN_SYCL_TRISYCL \"Use the triSYCL Sycl implementation (ComputeCPP by default).\" OFF)\nif(EIGEN_TEST_SYCL)\n  set (CMAKE_MODULE_PATH \"${CMAKE_ROOT}/Modules\" \"cmake/Modules/\" \"${CMAKE_MODULE_PATH}\")\n  find_package(Threads REQUIRED)\n  if(EIGEN_SYCL_TRISYCL)\n    message(STATUS \"Using triSYCL\")\n    include(FindTriSYCL)\n  else()\n    message(STATUS \"Using ComputeCPP SYCL\")\n    include(FindComputeCpp)\n    set(COMPUTECPP_DRIVER_DEFAULT_VALUE OFF)\n    if (NOT MSVC)\n      set(COMPUTECPP_DRIVER_DEFAULT_VALUE ON)\n    endif()\n    option(COMPUTECPP_USE_COMPILER_DRIVER\n      \"Use ComputeCpp driver instead of a 2 steps compilation\"\n      ${COMPUTECPP_DRIVER_DEFAULT_VALUE}\n    )\n  endif(EIGEN_SYCL_TRISYCL)\n  option(EIGEN_DONT_VECTORIZE_SYCL \"Don't use vectorisation in the SYCL tests.\" OFF)\n  if(EIGEN_DONT_VECTORIZE_SYCL)\n    message(STATUS \"Disabling SYCL vectorization in tests/examples\")\n    # When disabling SYCL vectorization, also disable Eigen default vectorization\n    add_definitions(-DEIGEN_DONT_VECTORIZE=1)\n    add_definitions(-DEIGEN_DONT_VECTORIZE_SYCL=1)\n  endif()\nendif()\n\nadd_subdirectory(unsupported)\n\nadd_subdirectory(demos EXCLUDE_FROM_ALL)\n\n# must be after test and unsupported, for configuring buildtests.in\nadd_subdirectory(scripts EXCLUDE_FROM_ALL)\n\n# TODO: consider also replacing EIGEN_BUILD_BTL by a custom target \"make btl\"?\nif(EIGEN_BUILD_BTL)\n  add_subdirectory(bench/btl EXCLUDE_FROM_ALL)\nendif()\n\nif(NOT WIN32)\n  add_subdirectory(bench/spbench EXCLUDE_FROM_ALL)\nendif()\n\nconfigure_file(scripts/cdashtesting.cmake.in cdashtesting.cmake @ONLY)\n\nif(BUILD_TESTING)\n  ei_testing_print_summary()\nendif()\n\nmessage(STATUS \"\")\nmessage(STATUS \"Configured Eigen ${EIGEN_VERSION_NUMBER}\")\nmessage(STATUS \"\")\n\nstring(TOLOWER \"${CMAKE_GENERATOR}\" cmake_generator_tolower)\nif(cmake_generator_tolower MATCHES \"makefile\")\n  message(STATUS \"Available targets (use: make TARGET):\")\nelse()\n  message(STATUS \"Available targets (use: cmake --build . --target TARGET):\")\nendif()\nmessage(STATUS \"---------+--------------------------------------------------------------\")\nmessage(STATUS \"Target   |   Description\")\nmessage(STATUS \"---------+--------------------------------------------------------------\")\nmessage(STATUS \"install  | Install Eigen. Headers will be installed to:\")\nmessage(STATUS \"         |     <CMAKE_INSTALL_PREFIX>/<INCLUDE_INSTALL_DIR>\")\nmessage(STATUS \"         |   Using the following values:\")\nmessage(STATUS \"         |     CMAKE_INSTALL_PREFIX: ${CMAKE_INSTALL_PREFIX}\")\nmessage(STATUS \"         |     INCLUDE_INSTALL_DIR:  ${INCLUDE_INSTALL_DIR}\")\nmessage(STATUS \"         |   Change the install location of Eigen headers using:\")\nmessage(STATUS \"         |     cmake . -DCMAKE_INSTALL_PREFIX=yourprefix\")\nmessage(STATUS \"         |   Or:\")\nmessage(STATUS \"         |     cmake . -DINCLUDE_INSTALL_DIR=yourdir\")\nmessage(STATUS \"doc      | Generate the API documentation, requires Doxygen & LaTeX\")\nif(BUILD_TESTING)\n  message(STATUS \"check    | Build and run the unit-tests. Read this page:\")\n  message(STATUS \"         |   http://eigen.tuxfamily.org/index.php?title=Tests\")\nendif()\nmessage(STATUS \"blas     | Build BLAS library (not the same thing as Eigen)\")\nmessage(STATUS \"uninstall| Remove files installed by the install target\")\nmessage(STATUS \"---------+--------------------------------------------------------------\")\nmessage(STATUS \"\")\n\n\nset ( EIGEN_VERSION_STRING ${EIGEN_VERSION_NUMBER} )\nset ( EIGEN_VERSION_MAJOR  ${EIGEN_WORLD_VERSION} )\nset ( EIGEN_VERSION_MINOR  ${EIGEN_MAJOR_VERSION} )\nset ( EIGEN_VERSION_PATCH  ${EIGEN_MINOR_VERSION} )\n\ninclude (CMakePackageConfigHelpers)\n\n# Imported target support\nadd_library (eigen INTERFACE)\nadd_library (Eigen3::Eigen ALIAS eigen)\ntarget_compile_definitions (eigen INTERFACE ${EIGEN_DEFINITIONS})\ntarget_include_directories (eigen INTERFACE\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}>\n  $<INSTALL_INTERFACE:${INCLUDE_INSTALL_DIR}>\n)\n\n# Export as title case Eigen\nset_target_properties (eigen PROPERTIES EXPORT_NAME Eigen)\n\ninstall (TARGETS eigen EXPORT Eigen3Targets)\n\nconfigure_package_config_file (\n  ${CMAKE_CURRENT_SOURCE_DIR}/cmake/Eigen3Config.cmake.in\n  ${CMAKE_CURRENT_BINARY_DIR}/Eigen3Config.cmake\n  INSTALL_DESTINATION ${CMAKEPACKAGE_INSTALL_DIR}\n  NO_SET_AND_CHECK_MACRO # Eigen does not provide legacy style defines\n  NO_CHECK_REQUIRED_COMPONENTS_MACRO # Eigen does not provide components\n)\n# Remove CMAKE_SIZEOF_VOID_P from Eigen3ConfigVersion.cmake since Eigen does\n# not depend on architecture specific settings or libraries. More\n# specifically, an Eigen3Config.cmake generated from a 64 bit target can be\n# used for 32 bit targets as well (and vice versa).\nset (_Eigen3_CMAKE_SIZEOF_VOID_P ${CMAKE_SIZEOF_VOID_P})\nunset (CMAKE_SIZEOF_VOID_P)\nwrite_basic_package_version_file (Eigen3ConfigVersion.cmake\n                                  VERSION ${EIGEN_VERSION_NUMBER}\n                                  COMPATIBILITY SameMajorVersion)\nset (CMAKE_SIZEOF_VOID_P ${_Eigen3_CMAKE_SIZEOF_VOID_P})\n\n# The Eigen target will be located in the Eigen3 namespace. Other CMake\n# targets can refer to it using Eigen3::Eigen.\nexport (TARGETS eigen NAMESPACE Eigen3:: FILE Eigen3Targets.cmake)\n# Export Eigen3 package to CMake registry such that it can be easily found by\n# CMake even if it has not been installed to a standard directory.\nexport (PACKAGE Eigen3)\n\ninstall (EXPORT Eigen3Targets NAMESPACE Eigen3:: DESTINATION ${CMAKEPACKAGE_INSTALL_DIR})\n\ninstall (FILES ${CMAKE_CURRENT_BINARY_DIR}/Eigen3Config.cmake\n               ${CMAKE_CURRENT_BINARY_DIR}/Eigen3ConfigVersion.cmake\n         DESTINATION ${CMAKEPACKAGE_INSTALL_DIR})\n\n# Add uninstall target\nadd_custom_target ( uninstall\n    COMMAND ${CMAKE_COMMAND} -P ${CMAKE_CURRENT_SOURCE_DIR}/cmake/EigenUninstall.cmake)\n\nif (EIGEN_SPLIT_TESTSUITE)\n  ei_split_testsuite(\"${EIGEN_SPLIT_TESTSUITE}\")\nendif()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/COPYING.APACHE",
    "content": "/*\n                                 Apache License\n                           Version 2.0, January 2004\n                        http://www.apache.org/licenses/\n\n   TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION\n\n   1. Definitions.\n\n      \"License\" shall mean the terms and conditions for use, reproduction,\n      and distribution as defined by Sections 1 through 9 of this document.\n\n      \"Licensor\" shall mean the copyright owner or entity authorized by\n      the copyright owner that is granting the License.\n\n      \"Legal Entity\" shall mean the union of the acting entity and all\n      other entities that control, are controlled by, or are under common\n      control with that entity. For the purposes of this definition,\n      \"control\" means (i) the power, direct or indirect, to cause the\n      direction or management of such entity, whether by contract or\n      otherwise, or (ii) ownership of fifty percent (50%) or more of the\n      outstanding shares, or (iii) beneficial ownership of such entity.\n\n      \"You\" (or \"Your\") shall mean an individual or Legal Entity\n      exercising permissions granted by this License.\n\n      \"Source\" form shall mean the preferred form for making modifications,\n      including but not limited to software source code, documentation\n      source, and configuration files.\n\n      \"Object\" form shall mean any form resulting from mechanical\n      transformation or translation of a Source form, including but\n      not limited to compiled object code, generated documentation,\n      and conversions to other media types.\n\n      \"Work\" shall mean the work of authorship, whether in Source or\n      Object form, made available under the License, as indicated by a\n      copyright notice that is included in or attached to the work\n      (an example is provided in the Appendix below).\n\n      \"Derivative Works\" shall mean any work, whether in Source or Object\n      form, that is based on (or derived from) the Work and for which the\n      editorial revisions, annotations, elaborations, or other modifications\n      represent, as a whole, an original work of authorship. For the purposes\n      of this License, Derivative Works shall not include works that remain\n      separable from, or merely link (or bind by name) to the interfaces of,\n      the Work and Derivative Works thereof.\n\n      \"Contribution\" shall mean any work of authorship, including\n      the original version of the Work and any modifications or additions\n      to that Work or Derivative Works thereof, that is intentionally\n      submitted to Licensor for inclusion in the Work by the copyright owner\n      or by an individual or Legal Entity authorized to submit on behalf of\n      the copyright owner. For the purposes of this definition, \"submitted\"\n      means any form of electronic, verbal, or written communication sent\n      to the Licensor or its representatives, including but not limited to\n      communication on electronic mailing lists, source code control systems,\n      and issue tracking systems that are managed by, or on behalf of, the\n      Licensor for the purpose of discussing and improving the Work, but\n      excluding communication that is conspicuously marked or otherwise\n      designated in writing by the copyright owner as \"Not a Contribution.\"\n\n      \"Contributor\" shall mean Licensor and any individual or Legal Entity\n      on behalf of whom a Contribution has been received by Licensor and\n      subsequently incorporated within the Work.\n\n   2. Grant of Copyright License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      copyright license to reproduce, prepare Derivative Works of,\n      publicly display, publicly perform, sublicense, and distribute the\n      Work and such Derivative Works in Source or Object form.\n\n   3. Grant of Patent License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      (except as stated in this section) patent license to make, have made,\n      use, offer to sell, sell, import, and otherwise transfer the Work,\n      where such license applies only to those patent claims licensable\n      by such Contributor that are necessarily infringed by their\n      Contribution(s) alone or by combination of their Contribution(s)\n      with the Work to which such Contribution(s) was submitted. If You\n      institute patent litigation against any entity (including a\n      cross-claim or counterclaim in a lawsuit) alleging that the Work\n      or a Contribution incorporated within the Work constitutes direct\n      or contributory patent infringement, then any patent licenses\n      granted to You under this License for that Work shall terminate\n      as of the date such litigation is filed.\n\n   4. Redistribution. You may reproduce and distribute copies of the\n      Work or Derivative Works thereof in any medium, with or without\n      modifications, and in Source or Object form, provided that You\n      meet the following conditions:\n\n      (a) You must give any other recipients of the Work or\n          Derivative Works a copy of this License; and\n\n      (b) You must cause any modified files to carry prominent notices\n          stating that You changed the files; and\n\n      (c) You must retain, in the Source form of any Derivative Works\n          that You distribute, all copyright, patent, trademark, and\n          attribution notices from the Source form of the Work,\n          excluding those notices that do not pertain to any part of\n          the Derivative Works; and\n\n      (d) If the Work includes a \"NOTICE\" text file as part of its\n          distribution, then any Derivative Works that You distribute must\n          include a readable copy of the attribution notices contained\n          within such NOTICE file, excluding those notices that do not\n          pertain to any part of the Derivative Works, in at least one\n          of the following places: within a NOTICE text file distributed\n          as part of the Derivative Works; within the Source form or\n          documentation, if provided along with the Derivative Works; or,\n          within a display generated by the Derivative Works, if and\n          wherever such third-party notices normally appear. The contents\n          of the NOTICE file are for informational purposes only and\n          do not modify the License. You may add Your own attribution\n          notices within Derivative Works that You distribute, alongside\n          or as an addendum to the NOTICE text from the Work, provided\n          that such additional attribution notices cannot be construed\n          as modifying the License.\n\n      You may add Your own copyright statement to Your modifications and\n      may provide additional or different license terms and conditions\n      for use, reproduction, or distribution of Your modifications, or\n      for any such Derivative Works as a whole, provided Your use,\n      reproduction, and distribution of the Work otherwise complies with\n      the conditions stated in this License.\n\n   5. Submission of Contributions. Unless You explicitly state otherwise,\n      any Contribution intentionally submitted for inclusion in the Work\n      by You to the Licensor shall be under the terms and conditions of\n      this License, without any additional terms or conditions.\n      Notwithstanding the above, nothing herein shall supersede or modify\n      the terms of any separate license agreement you may have executed\n      with Licensor regarding such Contributions.\n\n   6. Trademarks. This License does not grant permission to use the trade\n      names, trademarks, service marks, or product names of the Licensor,\n      except as required for reasonable and customary use in describing the\n      origin of the Work and reproducing the content of the NOTICE file.\n\n   7. Disclaimer of Warranty. Unless required by applicable law or\n      agreed to in writing, Licensor provides the Work (and each\n      Contributor provides its Contributions) on an \"AS IS\" BASIS,\n      WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or\n      implied, including, without limitation, any warranties or conditions\n      of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A\n      PARTICULAR PURPOSE. You are solely responsible for determining the\n      appropriateness of using or redistributing the Work and assume any\n      risks associated with Your exercise of permissions under this License.\n\n   8. Limitation of Liability. In no event and under no legal theory,\n      whether in tort (including negligence), contract, or otherwise,\n      unless required by applicable law (such as deliberate and grossly\n      negligent acts) or agreed to in writing, shall any Contributor be\n      liable to You for damages, including any direct, indirect, special,\n      incidental, or consequential damages of any character arising as a\n      result of this License or out of the use or inability to use the\n      Work (including but not limited to damages for loss of goodwill,\n      work stoppage, computer failure or malfunction, or any and all\n      other commercial damages or losses), even if such Contributor\n      has been advised of the possibility of such damages.\n\n   9. Accepting Warranty or Additional Liability. While redistributing\n      the Work or Derivative Works thereof, You may choose to offer,\n      and charge a fee for, acceptance of support, warranty, indemnity,\n      or other liability obligations and/or rights consistent with this\n      License. However, in accepting such obligations, You may act only\n      on Your own behalf and on Your sole responsibility, not on behalf\n      of any other Contributor, and only if You agree to indemnify,\n      defend, and hold each Contributor harmless for any liability\n      incurred by, or claims asserted against, such Contributor by reason\n      of your accepting any such warranty or additional liability.\n\n   END OF TERMS AND CONDITIONS\n\n   APPENDIX: How to apply the Apache License to your work.\n\n      To apply the Apache License to your work, attach the following\n      boilerplate notice, with the fields enclosed by brackets \"[]\"\n      replaced with your own identifying information. (Don't include\n      the brackets!)  The text should be enclosed in the appropriate\n      comment syntax for the file format. We also recommend that a\n      file or class name and description of purpose be included on the\n      same \"printed page\" as the copyright notice for easier\n      identification within third-party archives.\n\n   Copyright [yyyy] [name of copyright owner]\n\n   Licensed under the Apache License, Version 2.0 (the \"License\");\n   you may not use this file except in compliance with the License.\n   You may obtain a copy of the License at\n\n       http://www.apache.org/licenses/LICENSE-2.0\n\n   Unless required by applicable law or agreed to in writing, software\n   distributed under the License is distributed on an \"AS IS\" BASIS,\n   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n   See the License for the specific language governing permissions and\n   limitations under the License.\n*/"
  },
  {
    "path": "VO_Module/thirdparty/eigen/COPYING.BSD",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n*/\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/COPYING.GPL",
    "content": "                    GNU GENERAL PUBLIC LICENSE\n                       Version 3, 29 June 2007\n\n Copyright (C) 2007 Free Software Foundation, Inc. <http://fsf.org/>\n Everyone is permitted to copy and distribute verbatim copies\n of this license document, but changing it is not allowed.\n\n                            Preamble\n\n  The GNU General Public License is a free, copyleft license for\nsoftware and other kinds of works.\n\n  The licenses for most software and other practical works are designed\nto take away your freedom to share and change the works.  By contrast,\nthe GNU General Public License is intended to guarantee your freedom to\nshare and change all versions of a program--to make sure it remains free\nsoftware for all its users.  We, the Free Software Foundation, use the\nGNU General Public License for most of our software; it applies also to\nany other work released this way by its authors.  You can apply it to\nyour programs, too.\n\n  When we speak of free software, we are referring to freedom, not\nprice.  Our General Public Licenses are designed to make sure that you\nhave the freedom to distribute copies of free software (and charge for\nthem if you wish), that you receive source code or can get it if you\nwant it, that you can change the software or use pieces of it in new\nfree programs, and that you know you can do these things.\n\n  To protect your rights, we need to prevent others from denying you\nthese rights or asking you to surrender the rights.  Therefore, you have\ncertain responsibilities if you distribute copies of the software, or if\nyou modify it: responsibilities to respect the freedom of others.\n\n  For example, if you distribute copies of such a program, whether\ngratis or for a fee, you must pass on to the recipients the same\nfreedoms that you received.  You must make sure that they, too, receive\nor can get the source code.  And you must show them these terms so they\nknow their rights.\n\n  Developers that use the GNU GPL protect your rights with two steps:\n(1) assert copyright on the software, and (2) offer you this License\ngiving you legal permission to copy, distribute and/or modify it.\n\n  For the developers' and authors' protection, the GPL clearly explains\nthat there is no warranty for this free software.  For both users' and\nauthors' sake, the GPL requires that modified versions be marked as\nchanged, so that their problems will not be attributed erroneously to\nauthors of previous versions.\n\n  Some devices are designed to deny users access to install or run\nmodified versions of the software inside them, although the manufacturer\ncan do so.  This is fundamentally incompatible with the aim of\nprotecting users' freedom to change the software.  The systematic\npattern of such abuse occurs in the area of products for individuals to\nuse, which is precisely where it is most unacceptable.  Therefore, we\nhave designed this version of the GPL to prohibit the practice for those\nproducts.  If such problems arise substantially in other domains, we\nstand ready to extend this provision to those domains in future versions\nof the GPL, as needed to protect the freedom of users.\n\n  Finally, every program is threatened constantly by software patents.\nStates should not allow patents to restrict development and use of\nsoftware on general-purpose computers, but in those that do, we wish to\navoid the special danger that patents applied to a free program could\nmake it effectively proprietary.  To prevent this, the GPL assures that\npatents cannot be used to render the program non-free.\n\n  The precise terms and conditions for copying, distribution and\nmodification follow.\n\n                       TERMS AND CONDITIONS\n\n  0. Definitions.\n\n  \"This License\" refers to version 3 of the GNU General Public License.\n\n  \"Copyright\" also means copyright-like laws that apply to other kinds of\nworks, such as semiconductor masks.\n\n  \"The Program\" refers to any copyrightable work licensed under this\nLicense.  Each licensee is addressed as \"you\".  \"Licensees\" and\n\"recipients\" may be individuals or organizations.\n\n  To \"modify\" a work means to copy from or adapt all or part of the work\nin a fashion requiring copyright permission, other than the making of an\nexact copy.  The resulting work is called a \"modified version\" of the\nearlier work or a work \"based on\" the earlier work.\n\n  A \"covered work\" means either the unmodified Program or a work based\non the Program.\n\n  To \"propagate\" a work means to do anything with it that, without\npermission, would make you directly or secondarily liable for\ninfringement under applicable copyright law, except executing it on a\ncomputer or modifying a private copy.  Propagation includes copying,\ndistribution (with or without modification), making available to the\npublic, and in some countries other activities as well.\n\n  To \"convey\" a work means any kind of propagation that enables other\nparties to make or receive copies.  Mere interaction with a user through\na computer network, with no transfer of a copy, is not conveying.\n\n  An interactive user interface displays \"Appropriate Legal Notices\"\nto the extent that it includes a convenient and prominently visible\nfeature that (1) displays an appropriate copyright notice, and (2)\ntells the user that there is no warranty for the work (except to the\nextent that warranties are provided), that licensees may convey the\nwork under this License, and how to view a copy of this License.  If\nthe interface presents a list of user commands or options, such as a\nmenu, a prominent item in the list meets this criterion.\n\n  1. Source Code.\n\n  The \"source code\" for a work means the preferred form of the work\nfor making modifications to it.  \"Object code\" means any non-source\nform of a work.\n\n  A \"Standard Interface\" means an interface that either is an official\nstandard defined by a recognized standards body, or, in the case of\ninterfaces specified for a particular programming language, one that\nis widely used among developers working in that language.\n\n  The \"System Libraries\" of an executable work include anything, other\nthan the work as a whole, that (a) is included in the normal form of\npackaging a Major Component, but which is not part of that Major\nComponent, and (b) serves only to enable use of the work with that\nMajor Component, or to implement a Standard Interface for which an\nimplementation is available to the public in source code form.  A\n\"Major Component\", in this context, means a major essential component\n(kernel, window system, and so on) of the specific operating system\n(if any) on which the executable work runs, or a compiler used to\nproduce the work, or an object code interpreter used to run it.\n\n  The \"Corresponding Source\" for a work in object code form means all\nthe source code needed to generate, install, and (for an executable\nwork) run the object code and to modify the work, including scripts to\ncontrol those activities.  However, it does not include the work's\nSystem Libraries, or general-purpose tools or generally available free\nprograms which are used unmodified in performing those activities but\nwhich are not part of the work.  For example, Corresponding Source\nincludes interface definition files associated with source files for\nthe work, and the source code for shared libraries and dynamically\nlinked subprograms that the work is specifically designed to require,\nsuch as by intimate data communication or control flow between those\nsubprograms and other parts of the work.\n\n  The Corresponding Source need not include anything that users\ncan regenerate automatically from other parts of the Corresponding\nSource.\n\n  The Corresponding Source for a work in source code form is that\nsame work.\n\n  2. Basic Permissions.\n\n  All rights granted under this License are granted for the term of\ncopyright on the Program, and are irrevocable provided the stated\nconditions are met.  This License explicitly affirms your unlimited\npermission to run the unmodified Program.  The output from running a\ncovered work is covered by this License only if the output, given its\ncontent, constitutes a covered work.  This License acknowledges your\nrights of fair use or other equivalent, as provided by copyright law.\n\n  You may make, run and propagate covered works that you do not\nconvey, without conditions so long as your license otherwise remains\nin force.  You may convey covered works to others for the sole purpose\nof having them make modifications exclusively for you, or provide you\nwith facilities for running those works, provided that you comply with\nthe terms of this License in conveying all material for which you do\nnot control copyright.  Those thus making or running the covered works\nfor you must do so exclusively on your behalf, under your direction\nand control, on terms that prohibit them from making any copies of\nyour copyrighted material outside their relationship with you.\n\n  Conveying under any other circumstances is permitted solely under\nthe conditions stated below.  Sublicensing is not allowed; section 10\nmakes it unnecessary.\n\n  3. Protecting Users' Legal Rights From Anti-Circumvention Law.\n\n  No covered work shall be deemed part of an effective technological\nmeasure under any applicable law fulfilling obligations under article\n11 of the WIPO copyright treaty adopted on 20 December 1996, or\nsimilar laws prohibiting or restricting circumvention of such\nmeasures.\n\n  When you convey a covered work, you waive any legal power to forbid\ncircumvention of technological measures to the extent such circumvention\nis effected by exercising rights under this License with respect to\nthe covered work, and you disclaim any intention to limit operation or\nmodification of the work as a means of enforcing, against the work's\nusers, your or third parties' legal rights to forbid circumvention of\ntechnological measures.\n\n  4. Conveying Verbatim Copies.\n\n  You may convey verbatim copies of the Program's source code as you\nreceive it, in any medium, provided that you conspicuously and\nappropriately publish on each copy an appropriate copyright notice;\nkeep intact all notices stating that this License and any\nnon-permissive terms added in accord with section 7 apply to the code;\nkeep intact all notices of the absence of any warranty; and give all\nrecipients a copy of this License along with the Program.\n\n  You may charge any price or no price for each copy that you convey,\nand you may offer support or warranty protection for a fee.\n\n  5. Conveying Modified Source Versions.\n\n  You may convey a work based on the Program, or the modifications to\nproduce it from the Program, in the form of source code under the\nterms of section 4, provided that you also meet all of these conditions:\n\n    a) The work must carry prominent notices stating that you modified\n    it, and giving a relevant date.\n\n    b) The work must carry prominent notices stating that it is\n    released under this License and any conditions added under section\n    7.  This requirement modifies the requirement in section 4 to\n    \"keep intact all notices\".\n\n    c) You must license the entire work, as a whole, under this\n    License to anyone who comes into possession of a copy.  This\n    License will therefore apply, along with any applicable section 7\n    additional terms, to the whole of the work, and all its parts,\n    regardless of how they are packaged.  This License gives no\n    permission to license the work in any other way, but it does not\n    invalidate such permission if you have separately received it.\n\n    d) If the work has interactive user interfaces, each must display\n    Appropriate Legal Notices; however, if the Program has interactive\n    interfaces that do not display Appropriate Legal Notices, your\n    work need not make them do so.\n\n  A compilation of a covered work with other separate and independent\nworks, which are not by their nature extensions of the covered work,\nand which are not combined with it such as to form a larger program,\nin or on a volume of a storage or distribution medium, is called an\n\"aggregate\" if the compilation and its resulting copyright are not\nused to limit the access or legal rights of the compilation's users\nbeyond what the individual works permit.  Inclusion of a covered work\nin an aggregate does not cause this License to apply to the other\nparts of the aggregate.\n\n  6. Conveying Non-Source Forms.\n\n  You may convey a covered work in object code form under the terms\nof sections 4 and 5, provided that you also convey the\nmachine-readable Corresponding Source under the terms of this License,\nin one of these ways:\n\n    a) Convey the object code in, or embodied in, a physical product\n    (including a physical distribution medium), accompanied by the\n    Corresponding Source fixed on a durable physical medium\n    customarily used for software interchange.\n\n    b) Convey the object code in, or embodied in, a physical product\n    (including a physical distribution medium), accompanied by a\n    written offer, valid for at least three years and valid for as\n    long as you offer spare parts or customer support for that product\n    model, to give anyone who possesses the object code either (1) a\n    copy of the Corresponding Source for all the software in the\n    product that is covered by this License, on a durable physical\n    medium customarily used for software interchange, for a price no\n    more than your reasonable cost of physically performing this\n    conveying of source, or (2) access to copy the\n    Corresponding Source from a network server at no charge.\n\n    c) Convey individual copies of the object code with a copy of the\n    written offer to provide the Corresponding Source.  This\n    alternative is allowed only occasionally and noncommercially, and\n    only if you received the object code with such an offer, in accord\n    with subsection 6b.\n\n    d) Convey the object code by offering access from a designated\n    place (gratis or for a charge), and offer equivalent access to the\n    Corresponding Source in the same way through the same place at no\n    further charge.  You need not require recipients to copy the\n    Corresponding Source along with the object code.  If the place to\n    copy the object code is a network server, the Corresponding Source\n    may be on a different server (operated by you or a third party)\n    that supports equivalent copying facilities, provided you maintain\n    clear directions next to the object code saying where to find the\n    Corresponding Source.  Regardless of what server hosts the\n    Corresponding Source, you remain obligated to ensure that it is\n    available for as long as needed to satisfy these requirements.\n\n    e) Convey the object code using peer-to-peer transmission, provided\n    you inform other peers where the object code and Corresponding\n    Source of the work are being offered to the general public at no\n    charge under subsection 6d.\n\n  A separable portion of the object code, whose source code is excluded\nfrom the Corresponding Source as a System Library, need not be\nincluded in conveying the object code work.\n\n  A \"User Product\" is either (1) a \"consumer product\", which means any\ntangible personal property which is normally used for personal, family,\nor household purposes, or (2) anything designed or sold for incorporation\ninto a dwelling.  In determining whether a product is a consumer product,\ndoubtful cases shall be resolved in favor of coverage.  For a particular\nproduct received by a particular user, \"normally used\" refers to a\ntypical or common use of that class of product, regardless of the status\nof the particular user or of the way in which the particular user\nactually uses, or expects or is expected to use, the product.  A product\nis a consumer product regardless of whether the product has substantial\ncommercial, industrial or non-consumer uses, unless such uses represent\nthe only significant mode of use of the product.\n\n  \"Installation Information\" for a User Product means any methods,\nprocedures, authorization keys, or other information required to install\nand execute modified versions of a covered work in that User Product from\na modified version of its Corresponding Source.  The information must\nsuffice to ensure that the continued functioning of the modified object\ncode is in no case prevented or interfered with solely because\nmodification has been made.\n\n  If you convey an object code work under this section in, or with, or\nspecifically for use in, a User Product, and the conveying occurs as\npart of a transaction in which the right of possession and use of the\nUser Product is transferred to the recipient in perpetuity or for a\nfixed term (regardless of how the transaction is characterized), the\nCorresponding Source conveyed under this section must be accompanied\nby the Installation Information.  But this requirement does not apply\nif neither you nor any third party retains the ability to install\nmodified object code on the User Product (for example, the work has\nbeen installed in ROM).\n\n  The requirement to provide Installation Information does not include a\nrequirement to continue to provide support service, warranty, or updates\nfor a work that has been modified or installed by the recipient, or for\nthe User Product in which it has been modified or installed.  Access to a\nnetwork may be denied when the modification itself materially and\nadversely affects the operation of the network or violates the rules and\nprotocols for communication across the network.\n\n  Corresponding Source conveyed, and Installation Information provided,\nin accord with this section must be in a format that is publicly\ndocumented (and with an implementation available to the public in\nsource code form), and must require no special password or key for\nunpacking, reading or copying.\n\n  7. Additional Terms.\n\n  \"Additional permissions\" are terms that supplement the terms of this\nLicense by making exceptions from one or more of its conditions.\nAdditional permissions that are applicable to the entire Program shall\nbe treated as though they were included in this License, to the extent\nthat they are valid under applicable law.  If additional permissions\napply only to part of the Program, that part may be used separately\nunder those permissions, but the entire Program remains governed by\nthis License without regard to the additional permissions.\n\n  When you convey a copy of a covered work, you may at your option\nremove any additional permissions from that copy, or from any part of\nit.  (Additional permissions may be written to require their own\nremoval in certain cases when you modify the work.)  You may place\nadditional permissions on material, added by you to a covered work,\nfor which you have or can give appropriate copyright permission.\n\n  Notwithstanding any other provision of this License, for material you\nadd to a covered work, you may (if authorized by the copyright holders of\nthat material) supplement the terms of this License with terms:\n\n    a) Disclaiming warranty or limiting liability differently from the\n    terms of sections 15 and 16 of this License; or\n\n    b) Requiring preservation of specified reasonable legal notices or\n    author attributions in that material or in the Appropriate Legal\n    Notices displayed by works containing it; or\n\n    c) Prohibiting misrepresentation of the origin of that material, or\n    requiring that modified versions of such material be marked in\n    reasonable ways as different from the original version; or\n\n    d) Limiting the use for publicity purposes of names of licensors or\n    authors of the material; or\n\n    e) Declining to grant rights under trademark law for use of some\n    trade names, trademarks, or service marks; or\n\n    f) Requiring indemnification of licensors and authors of that\n    material by anyone who conveys the material (or modified versions of\n    it) with contractual assumptions of liability to the recipient, for\n    any liability that these contractual assumptions directly impose on\n    those licensors and authors.\n\n  All other non-permissive additional terms are considered \"further\nrestrictions\" within the meaning of section 10.  If the Program as you\nreceived it, or any part of it, contains a notice stating that it is\ngoverned by this License along with a term that is a further\nrestriction, you may remove that term.  If a license document contains\na further restriction but permits relicensing or conveying under this\nLicense, you may add to a covered work material governed by the terms\nof that license document, provided that the further restriction does\nnot survive such relicensing or conveying.\n\n  If you add terms to a covered work in accord with this section, you\nmust place, in the relevant source files, a statement of the\nadditional terms that apply to those files, or a notice indicating\nwhere to find the applicable terms.\n\n  Additional terms, permissive or non-permissive, may be stated in the\nform of a separately written license, or stated as exceptions;\nthe above requirements apply either way.\n\n  8. Termination.\n\n  You may not propagate or modify a covered work except as expressly\nprovided under this License.  Any attempt otherwise to propagate or\nmodify it is void, and will automatically terminate your rights under\nthis License (including any patent licenses granted under the third\nparagraph of section 11).\n\n  However, if you cease all violation of this License, then your\nlicense from a particular copyright holder is reinstated (a)\nprovisionally, unless and until the copyright holder explicitly and\nfinally terminates your license, and (b) permanently, if the copyright\nholder fails to notify you of the violation by some reasonable means\nprior to 60 days after the cessation.\n\n  Moreover, your license from a particular copyright holder is\nreinstated permanently if the copyright holder notifies you of the\nviolation by some reasonable means, this is the first time you have\nreceived notice of violation of this License (for any work) from that\ncopyright holder, and you cure the violation prior to 30 days after\nyour receipt of the notice.\n\n  Termination of your rights under this section does not terminate the\nlicenses of parties who have received copies or rights from you under\nthis License.  If your rights have been terminated and not permanently\nreinstated, you do not qualify to receive new licenses for the same\nmaterial under section 10.\n\n  9. Acceptance Not Required for Having Copies.\n\n  You are not required to accept this License in order to receive or\nrun a copy of the Program.  Ancillary propagation of a covered work\noccurring solely as a consequence of using peer-to-peer transmission\nto receive a copy likewise does not require acceptance.  However,\nnothing other than this License grants you permission to propagate or\nmodify any covered work.  These actions infringe copyright if you do\nnot accept this License.  Therefore, by modifying or propagating a\ncovered work, you indicate your acceptance of this License to do so.\n\n  10. Automatic Licensing of Downstream Recipients.\n\n  Each time you convey a covered work, the recipient automatically\nreceives a license from the original licensors, to run, modify and\npropagate that work, subject to this License.  You are not responsible\nfor enforcing compliance by third parties with this License.\n\n  An \"entity transaction\" is a transaction transferring control of an\norganization, or substantially all assets of one, or subdividing an\norganization, or merging organizations.  If propagation of a covered\nwork results from an entity transaction, each party to that\ntransaction who receives a copy of the work also receives whatever\nlicenses to the work the party's predecessor in interest had or could\ngive under the previous paragraph, plus a right to possession of the\nCorresponding Source of the work from the predecessor in interest, if\nthe predecessor has it or can get it with reasonable efforts.\n\n  You may not impose any further restrictions on the exercise of the\nrights granted or affirmed under this License.  For example, you may\nnot impose a license fee, royalty, or other charge for exercise of\nrights granted under this License, and you may not initiate litigation\n(including a cross-claim or counterclaim in a lawsuit) alleging that\nany patent claim is infringed by making, using, selling, offering for\nsale, or importing the Program or any portion of it.\n\n  11. Patents.\n\n  A \"contributor\" is a copyright holder who authorizes use under this\nLicense of the Program or a work on which the Program is based.  The\nwork thus licensed is called the contributor's \"contributor version\".\n\n  A contributor's \"essential patent claims\" are all patent claims\nowned or controlled by the contributor, whether already acquired or\nhereafter acquired, that would be infringed by some manner, permitted\nby this License, of making, using, or selling its contributor version,\nbut do not include claims that would be infringed only as a\nconsequence of further modification of the contributor version.  For\npurposes of this definition, \"control\" includes the right to grant\npatent sublicenses in a manner consistent with the requirements of\nthis License.\n\n  Each contributor grants you a non-exclusive, worldwide, royalty-free\npatent license under the contributor's essential patent claims, to\nmake, use, sell, offer for sale, import and otherwise run, modify and\npropagate the contents of its contributor version.\n\n  In the following three paragraphs, a \"patent license\" is any express\nagreement or commitment, however denominated, not to enforce a patent\n(such as an express permission to practice a patent or covenant not to\nsue for patent infringement).  To \"grant\" such a patent license to a\nparty means to make such an agreement or commitment not to enforce a\npatent against the party.\n\n  If you convey a covered work, knowingly relying on a patent license,\nand the Corresponding Source of the work is not available for anyone\nto copy, free of charge and under the terms of this License, through a\npublicly available network server or other readily accessible means,\nthen you must either (1) cause the Corresponding Source to be so\navailable, or (2) arrange to deprive yourself of the benefit of the\npatent license for this particular work, or (3) arrange, in a manner\nconsistent with the requirements of this License, to extend the patent\nlicense to downstream recipients.  \"Knowingly relying\" means you have\nactual knowledge that, but for the patent license, your conveying the\ncovered work in a country, or your recipient's use of the covered work\nin a country, would infringe one or more identifiable patents in that\ncountry that you have reason to believe are valid.\n\n  If, pursuant to or in connection with a single transaction or\narrangement, you convey, or propagate by procuring conveyance of, a\ncovered work, and grant a patent license to some of the parties\nreceiving the covered work authorizing them to use, propagate, modify\nor convey a specific copy of the covered work, then the patent license\nyou grant is automatically extended to all recipients of the covered\nwork and works based on it.\n\n  A patent license is \"discriminatory\" if it does not include within\nthe scope of its coverage, prohibits the exercise of, or is\nconditioned on the non-exercise of one or more of the rights that are\nspecifically granted under this License.  You may not convey a covered\nwork if you are a party to an arrangement with a third party that is\nin the business of distributing software, under which you make payment\nto the third party based on the extent of your activity of conveying\nthe work, and under which the third party grants, to any of the\nparties who would receive the covered work from you, a discriminatory\npatent license (a) in connection with copies of the covered work\nconveyed by you (or copies made from those copies), or (b) primarily\nfor and in connection with specific products or compilations that\ncontain the covered work, unless you entered into that arrangement,\nor that patent license was granted, prior to 28 March 2007.\n\n  Nothing in this License shall be construed as excluding or limiting\nany implied license or other defenses to infringement that may\notherwise be available to you under applicable patent law.\n\n  12. No Surrender of Others' Freedom.\n\n  If conditions are imposed on you (whether by court order, agreement or\notherwise) that contradict the conditions of this License, they do not\nexcuse you from the conditions of this License.  If you cannot convey a\ncovered work so as to satisfy simultaneously your obligations under this\nLicense and any other pertinent obligations, then as a consequence you may\nnot convey it at all.  For example, if you agree to terms that obligate you\nto collect a royalty for further conveying from those to whom you convey\nthe Program, the only way you could satisfy both those terms and this\nLicense would be to refrain entirely from conveying the Program.\n\n  13. Use with the GNU Affero General Public License.\n\n  Notwithstanding any other provision of this License, you have\npermission to link or combine any covered work with a work licensed\nunder version 3 of the GNU Affero General Public License into a single\ncombined work, and to convey the resulting work.  The terms of this\nLicense will continue to apply to the part which is the covered work,\nbut the special requirements of the GNU Affero General Public License,\nsection 13, concerning interaction through a network will apply to the\ncombination as such.\n\n  14. Revised Versions of this License.\n\n  The Free Software Foundation may publish revised and/or new versions of\nthe GNU General Public License from time to time.  Such new versions will\nbe similar in spirit to the present version, but may differ in detail to\naddress new problems or concerns.\n\n  Each version is given a distinguishing version number.  If the\nProgram specifies that a certain numbered version of the GNU General\nPublic License \"or any later version\" applies to it, you have the\noption of following the terms and conditions either of that numbered\nversion or of any later version published by the Free Software\nFoundation.  If the Program does not specify a version number of the\nGNU General Public License, you may choose any version ever published\nby the Free Software Foundation.\n\n  If the Program specifies that a proxy can decide which future\nversions of the GNU General Public License can be used, that proxy's\npublic statement of acceptance of a version permanently authorizes you\nto choose that version for the Program.\n\n  Later license versions may give you additional or different\npermissions.  However, no additional obligations are imposed on any\nauthor or copyright holder as a result of your choosing to follow a\nlater version.\n\n  15. Disclaimer of Warranty.\n\n  THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY\nAPPLICABLE LAW.  EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT\nHOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM \"AS IS\" WITHOUT WARRANTY\nOF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO,\nTHE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR\nPURPOSE.  THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM\nIS WITH YOU.  SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF\nALL NECESSARY SERVICING, REPAIR OR CORRECTION.\n\n  16. Limitation of Liability.\n\n  IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING\nWILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS\nTHE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY\nGENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE\nUSE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF\nDATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD\nPARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS),\nEVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF\nSUCH DAMAGES.\n\n  17. Interpretation of Sections 15 and 16.\n\n  If the disclaimer of warranty and limitation of liability provided\nabove cannot be given local legal effect according to their terms,\nreviewing courts shall apply local law that most closely approximates\nan absolute waiver of all civil liability in connection with the\nProgram, unless a warranty or assumption of liability accompanies a\ncopy of the Program in return for a fee.\n\n                     END OF TERMS AND CONDITIONS\n\n            How to Apply These Terms to Your New Programs\n\n  If you develop a new program, and you want it to be of the greatest\npossible use to the public, the best way to achieve this is to make it\nfree software which everyone can redistribute and change under these terms.\n\n  To do so, attach the following notices to the program.  It is safest\nto attach them to the start of each source file to most effectively\nstate the exclusion of warranty; and each file should have at least\nthe \"copyright\" line and a pointer to where the full notice is found.\n\n    <one line to give the program's name and a brief idea of what it does.>\n    Copyright (C) <year>  <name of author>\n\n    This program is free software: you can redistribute it and/or modify\n    it under the terms of the GNU General Public License as published by\n    the Free Software Foundation, either version 3 of the License, or\n    (at your option) any later version.\n\n    This program is distributed in the hope that it will be useful,\n    but WITHOUT ANY WARRANTY; without even the implied warranty of\n    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n    GNU General Public License for more details.\n\n    You should have received a copy of the GNU General Public License\n    along with this program.  If not, see <http://www.gnu.org/licenses/>.\n\nAlso add information on how to contact you by electronic and paper mail.\n\n  If the program does terminal interaction, make it output a short\nnotice like this when it starts in an interactive mode:\n\n    <program>  Copyright (C) <year>  <name of author>\n    This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'.\n    This is free software, and you are welcome to redistribute it\n    under certain conditions; type `show c' for details.\n\nThe hypothetical commands `show w' and `show c' should show the appropriate\nparts of the General Public License.  Of course, your program's commands\nmight be different; for a GUI interface, you would use an \"about box\".\n\n  You should also get your employer (if you work as a programmer) or school,\nif any, to sign a \"copyright disclaimer\" for the program, if necessary.\nFor more information on this, and how to apply and follow the GNU GPL, see\n<http://www.gnu.org/licenses/>.\n\n  The GNU General Public License does not permit incorporating your program\ninto proprietary programs.  If your program is a subroutine library, you\nmay consider it more useful to permit linking proprietary applications with\nthe library.  If this is what you want to do, use the GNU Lesser General\nPublic License instead of this License.  But first, please read\n<http://www.gnu.org/philosophy/why-not-lgpl.html>.\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/COPYING.LGPL",
    "content": "                  GNU LESSER GENERAL PUBLIC LICENSE\n                       Version 2.1, February 1999\n\n Copyright (C) 1991, 1999 Free Software Foundation, Inc.\n 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA\n Everyone is permitted to copy and distribute verbatim copies\n of this license document, but changing it is not allowed.\n\n[This is the first released version of the Lesser GPL.  It also counts\n as the successor of the GNU Library Public License, version 2, hence\n the version number 2.1.]\n\n                            Preamble\n\n  The licenses for most software are designed to take away your\nfreedom to share and change it.  By contrast, the GNU General Public\nLicenses are intended to guarantee your freedom to share and change\nfree software--to make sure the software is free for all its users.\n\n  This license, the Lesser General Public License, applies to some\nspecially designated software packages--typically libraries--of the\nFree Software Foundation and other authors who decide to use it.  You\ncan use it too, but we suggest you first think carefully about whether\nthis license or the ordinary General Public License is the better\nstrategy to use in any particular case, based on the explanations below.\n\n  When we speak of free software, we are referring to freedom of use,\nnot price.  Our General Public Licenses are designed to make sure that\nyou have the freedom to distribute copies of free software (and charge\nfor this service if you wish); that you receive source code or can get\nit if you want it; that you can change the software and use pieces of\nit in new free programs; and that you are informed that you can do\nthese things.\n\n  To protect your rights, we need to make restrictions that forbid\ndistributors to deny you these rights or to ask you to surrender these\nrights.  These restrictions translate to certain responsibilities for\nyou if you distribute copies of the library or if you modify it.\n\n  For example, if you distribute copies of the library, whether gratis\nor for a fee, you must give the recipients all the rights that we gave\nyou.  You must make sure that they, too, receive or can get the source\ncode.  If you link other code with the library, you must provide\ncomplete object files to the recipients, so that they can relink them\nwith the library after making changes to the library and recompiling\nit.  And you must show them these terms so they know their rights.\n\n  We protect your rights with a two-step method: (1) we copyright the\nlibrary, and (2) we offer you this license, which gives you legal\npermission to copy, distribute and/or modify the library.\n\n  To protect each distributor, we want to make it very clear that\nthere is no warranty for the free library.  Also, if the library is\nmodified by someone else and passed on, the recipients should know\nthat what they have is not the original version, so that the original\nauthor's reputation will not be affected by problems that might be\nintroduced by others.\n\f\n  Finally, software patents pose a constant threat to the existence of\nany free program.  We wish to make sure that a company cannot\neffectively restrict the users of a free program by obtaining a\nrestrictive license from a patent holder.  Therefore, we insist that\nany patent license obtained for a version of the library must be\nconsistent with the full freedom of use specified in this license.\n\n  Most GNU software, including some libraries, is covered by the\nordinary GNU General Public License.  This license, the GNU Lesser\nGeneral Public License, applies to certain designated libraries, and\nis quite different from the ordinary General Public License.  We use\nthis license for certain libraries in order to permit linking those\nlibraries into non-free programs.\n\n  When a program is linked with a library, whether statically or using\na shared library, the combination of the two is legally speaking a\ncombined work, a derivative of the original library.  The ordinary\nGeneral Public License therefore permits such linking only if the\nentire combination fits its criteria of freedom.  The Lesser General\nPublic License permits more lax criteria for linking other code with\nthe library.\n\n  We call this license the \"Lesser\" General Public License because it\ndoes Less to protect the user's freedom than the ordinary General\nPublic License.  It also provides other free software developers Less\nof an advantage over competing non-free programs.  These disadvantages\nare the reason we use the ordinary General Public License for many\nlibraries.  However, the Lesser license provides advantages in certain\nspecial circumstances.\n\n  For example, on rare occasions, there may be a special need to\nencourage the widest possible use of a certain library, so that it becomes\na de-facto standard.  To achieve this, non-free programs must be\nallowed to use the library.  A more frequent case is that a free\nlibrary does the same job as widely used non-free libraries.  In this\ncase, there is little to gain by limiting the free library to free\nsoftware only, so we use the Lesser General Public License.\n\n  In other cases, permission to use a particular library in non-free\nprograms enables a greater number of people to use a large body of\nfree software.  For example, permission to use the GNU C Library in\nnon-free programs enables many more people to use the whole GNU\noperating system, as well as its variant, the GNU/Linux operating\nsystem.\n\n  Although the Lesser General Public License is Less protective of the\nusers' freedom, it does ensure that the user of a program that is\nlinked with the Library has the freedom and the wherewithal to run\nthat program using a modified version of the Library.\n\n  The precise terms and conditions for copying, distribution and\nmodification follow.  Pay close attention to the difference between a\n\"work based on the library\" and a \"work that uses the library\".  The\nformer contains code derived from the library, whereas the latter must\nbe combined with the library in order to run.\n\f\n                  GNU LESSER GENERAL PUBLIC LICENSE\n   TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION\n\n  0. This License Agreement applies to any software library or other\nprogram which contains a notice placed by the copyright holder or\nother authorized party saying it may be distributed under the terms of\nthis Lesser General Public License (also called \"this License\").\nEach licensee is addressed as \"you\".\n\n  A \"library\" means a collection of software functions and/or data\nprepared so as to be conveniently linked with application programs\n(which use some of those functions and data) to form executables.\n\n  The \"Library\", below, refers to any such software library or work\nwhich has been distributed under these terms.  A \"work based on the\nLibrary\" means either the Library or any derivative work under\ncopyright law: that is to say, a work containing the Library or a\nportion of it, either verbatim or with modifications and/or translated\nstraightforwardly into another language.  (Hereinafter, translation is\nincluded without limitation in the term \"modification\".)\n\n  \"Source code\" for a work means the preferred form of the work for\nmaking modifications to it.  For a library, complete source code means\nall the source code for all modules it contains, plus any associated\ninterface definition files, plus the scripts used to control compilation\nand installation of the library.\n\n  Activities other than copying, distribution and modification are not\ncovered by this License; they are outside its scope.  The act of\nrunning a program using the Library is not restricted, and output from\nsuch a program is covered only if its contents constitute a work based\non the Library (independent of the use of the Library in a tool for\nwriting it).  Whether that is true depends on what the Library does\nand what the program that uses the Library does.\n\n  1. You may copy and distribute verbatim copies of the Library's\ncomplete source code as you receive it, in any medium, provided that\nyou conspicuously and appropriately publish on each copy an\nappropriate copyright notice and disclaimer of warranty; keep intact\nall the notices that refer to this License and to the absence of any\nwarranty; and distribute a copy of this License along with the\nLibrary.\n\n  You may charge a fee for the physical act of transferring a copy,\nand you may at your option offer warranty protection in exchange for a\nfee.\n\f\n  2. You may modify your copy or copies of the Library or any portion\nof it, thus forming a work based on the Library, and copy and\ndistribute such modifications or work under the terms of Section 1\nabove, provided that you also meet all of these conditions:\n\n    a) The modified work must itself be a software library.\n\n    b) You must cause the files modified to carry prominent notices\n    stating that you changed the files and the date of any change.\n\n    c) You must cause the whole of the work to be licensed at no\n    charge to all third parties under the terms of this License.\n\n    d) If a facility in the modified Library refers to a function or a\n    table of data to be supplied by an application program that uses\n    the facility, other than as an argument passed when the facility\n    is invoked, then you must make a good faith effort to ensure that,\n    in the event an application does not supply such function or\n    table, the facility still operates, and performs whatever part of\n    its purpose remains meaningful.\n\n    (For example, a function in a library to compute square roots has\n    a purpose that is entirely well-defined independent of the\n    application.  Therefore, Subsection 2d requires that any\n    application-supplied function or table used by this function must\n    be optional: if the application does not supply it, the square\n    root function must still compute square roots.)\n\nThese requirements apply to the modified work as a whole.  If\nidentifiable sections of that work are not derived from the Library,\nand can be reasonably considered independent and separate works in\nthemselves, then this License, and its terms, do not apply to those\nsections when you distribute them as separate works.  But when you\ndistribute the same sections as part of a whole which is a work based\non the Library, the distribution of the whole must be on the terms of\nthis License, whose permissions for other licensees extend to the\nentire whole, and thus to each and every part regardless of who wrote\nit.\n\nThus, it is not the intent of this section to claim rights or contest\nyour rights to work written entirely by you; rather, the intent is to\nexercise the right to control the distribution of derivative or\ncollective works based on the Library.\n\nIn addition, mere aggregation of another work not based on the Library\nwith the Library (or with a work based on the Library) on a volume of\na storage or distribution medium does not bring the other work under\nthe scope of this License.\n\n  3. You may opt to apply the terms of the ordinary GNU General Public\nLicense instead of this License to a given copy of the Library.  To do\nthis, you must alter all the notices that refer to this License, so\nthat they refer to the ordinary GNU General Public License, version 2,\ninstead of to this License.  (If a newer version than version 2 of the\nordinary GNU General Public License has appeared, then you can specify\nthat version instead if you wish.)  Do not make any other change in\nthese notices.\n\f\n  Once this change is made in a given copy, it is irreversible for\nthat copy, so the ordinary GNU General Public License applies to all\nsubsequent copies and derivative works made from that copy.\n\n  This option is useful when you wish to copy part of the code of\nthe Library into a program that is not a library.\n\n  4. You may copy and distribute the Library (or a portion or\nderivative of it, under Section 2) in object code or executable form\nunder the terms of Sections 1 and 2 above provided that you accompany\nit with the complete corresponding machine-readable source code, which\nmust be distributed under the terms of Sections 1 and 2 above on a\nmedium customarily used for software interchange.\n\n  If distribution of object code is made by offering access to copy\nfrom a designated place, then offering equivalent access to copy the\nsource code from the same place satisfies the requirement to\ndistribute the source code, even though third parties are not\ncompelled to copy the source along with the object code.\n\n  5. A program that contains no derivative of any portion of the\nLibrary, but is designed to work with the Library by being compiled or\nlinked with it, is called a \"work that uses the Library\".  Such a\nwork, in isolation, is not a derivative work of the Library, and\ntherefore falls outside the scope of this License.\n\n  However, linking a \"work that uses the Library\" with the Library\ncreates an executable that is a derivative of the Library (because it\ncontains portions of the Library), rather than a \"work that uses the\nlibrary\".  The executable is therefore covered by this License.\nSection 6 states terms for distribution of such executables.\n\n  When a \"work that uses the Library\" uses material from a header file\nthat is part of the Library, the object code for the work may be a\nderivative work of the Library even though the source code is not.\nWhether this is true is especially significant if the work can be\nlinked without the Library, or if the work is itself a library.  The\nthreshold for this to be true is not precisely defined by law.\n\n  If such an object file uses only numerical parameters, data\nstructure layouts and accessors, and small macros and small inline\nfunctions (ten lines or less in length), then the use of the object\nfile is unrestricted, regardless of whether it is legally a derivative\nwork.  (Executables containing this object code plus portions of the\nLibrary will still fall under Section 6.)\n\n  Otherwise, if the work is a derivative of the Library, you may\ndistribute the object code for the work under the terms of Section 6.\nAny executables containing that work also fall under Section 6,\nwhether or not they are linked directly with the Library itself.\n\f\n  6. As an exception to the Sections above, you may also combine or\nlink a \"work that uses the Library\" with the Library to produce a\nwork containing portions of the Library, and distribute that work\nunder terms of your choice, provided that the terms permit\nmodification of the work for the customer's own use and reverse\nengineering for debugging such modifications.\n\n  You must give prominent notice with each copy of the work that the\nLibrary is used in it and that the Library and its use are covered by\nthis License.  You must supply a copy of this License.  If the work\nduring execution displays copyright notices, you must include the\ncopyright notice for the Library among them, as well as a reference\ndirecting the user to the copy of this License.  Also, you must do one\nof these things:\n\n    a) Accompany the work with the complete corresponding\n    machine-readable source code for the Library including whatever\n    changes were used in the work (which must be distributed under\n    Sections 1 and 2 above); and, if the work is an executable linked\n    with the Library, with the complete machine-readable \"work that\n    uses the Library\", as object code and/or source code, so that the\n    user can modify the Library and then relink to produce a modified\n    executable containing the modified Library.  (It is understood\n    that the user who changes the contents of definitions files in the\n    Library will not necessarily be able to recompile the application\n    to use the modified definitions.)\n\n    b) Use a suitable shared library mechanism for linking with the\n    Library.  A suitable mechanism is one that (1) uses at run time a\n    copy of the library already present on the user's computer system,\n    rather than copying library functions into the executable, and (2)\n    will operate properly with a modified version of the library, if\n    the user installs one, as long as the modified version is\n    interface-compatible with the version that the work was made with.\n\n    c) Accompany the work with a written offer, valid for at\n    least three years, to give the same user the materials\n    specified in Subsection 6a, above, for a charge no more\n    than the cost of performing this distribution.\n\n    d) If distribution of the work is made by offering access to copy\n    from a designated place, offer equivalent access to copy the above\n    specified materials from the same place.\n\n    e) Verify that the user has already received a copy of these\n    materials or that you have already sent this user a copy.\n\n  For an executable, the required form of the \"work that uses the\nLibrary\" must include any data and utility programs needed for\nreproducing the executable from it.  However, as a special exception,\nthe materials to be distributed need not include anything that is\nnormally distributed (in either source or binary form) with the major\ncomponents (compiler, kernel, and so on) of the operating system on\nwhich the executable runs, unless that component itself accompanies\nthe executable.\n\n  It may happen that this requirement contradicts the license\nrestrictions of other proprietary libraries that do not normally\naccompany the operating system.  Such a contradiction means you cannot\nuse both them and the Library together in an executable that you\ndistribute.\n\f\n  7. You may place library facilities that are a work based on the\nLibrary side-by-side in a single library together with other library\nfacilities not covered by this License, and distribute such a combined\nlibrary, provided that the separate distribution of the work based on\nthe Library and of the other library facilities is otherwise\npermitted, and provided that you do these two things:\n\n    a) Accompany the combined library with a copy of the same work\n    based on the Library, uncombined with any other library\n    facilities.  This must be distributed under the terms of the\n    Sections above.\n\n    b) Give prominent notice with the combined library of the fact\n    that part of it is a work based on the Library, and explaining\n    where to find the accompanying uncombined form of the same work.\n\n  8. You may not copy, modify, sublicense, link with, or distribute\nthe Library except as expressly provided under this License.  Any\nattempt otherwise to copy, modify, sublicense, link with, or\ndistribute the Library is void, and will automatically terminate your\nrights under this License.  However, parties who have received copies,\nor rights, from you under this License will not have their licenses\nterminated so long as such parties remain in full compliance.\n\n  9. You are not required to accept this License, since you have not\nsigned it.  However, nothing else grants you permission to modify or\ndistribute the Library or its derivative works.  These actions are\nprohibited by law if you do not accept this License.  Therefore, by\nmodifying or distributing the Library (or any work based on the\nLibrary), you indicate your acceptance of this License to do so, and\nall its terms and conditions for copying, distributing or modifying\nthe Library or works based on it.\n\n  10. Each time you redistribute the Library (or any work based on the\nLibrary), the recipient automatically receives a license from the\noriginal licensor to copy, distribute, link with or modify the Library\nsubject to these terms and conditions.  You may not impose any further\nrestrictions on the recipients' exercise of the rights granted herein.\nYou are not responsible for enforcing compliance by third parties with\nthis License.\n\f\n  11. If, as a consequence of a court judgment or allegation of patent\ninfringement or for any other reason (not limited to patent issues),\nconditions are imposed on you (whether by court order, agreement or\notherwise) that contradict the conditions of this License, they do not\nexcuse you from the conditions of this License.  If you cannot\ndistribute so as to satisfy simultaneously your obligations under this\nLicense and any other pertinent obligations, then as a consequence you\nmay not distribute the Library at all.  For example, if a patent\nlicense would not permit royalty-free redistribution of the Library by\nall those who receive copies directly or indirectly through you, then\nthe only way you could satisfy both it and this License would be to\nrefrain entirely from distribution of the Library.\n\nIf any portion of this section is held invalid or unenforceable under any\nparticular circumstance, the balance of the section is intended to apply,\nand the section as a whole is intended to apply in other circumstances.\n\nIt is not the purpose of this section to induce you to infringe any\npatents or other property right claims or to contest validity of any\nsuch claims; this section has the sole purpose of protecting the\nintegrity of the free software distribution system which is\nimplemented by public license practices.  Many people have made\ngenerous contributions to the wide range of software distributed\nthrough that system in reliance on consistent application of that\nsystem; it is up to the author/donor to decide if he or she is willing\nto distribute software through any other system and a licensee cannot\nimpose that choice.\n\nThis section is intended to make thoroughly clear what is believed to\nbe a consequence of the rest of this License.\n\n  12. If the distribution and/or use of the Library is restricted in\ncertain countries either by patents or by copyrighted interfaces, the\noriginal copyright holder who places the Library under this License may add\nan explicit geographical distribution limitation excluding those countries,\nso that distribution is permitted only in or among countries not thus\nexcluded.  In such case, this License incorporates the limitation as if\nwritten in the body of this License.\n\n  13. The Free Software Foundation may publish revised and/or new\nversions of the Lesser General Public License from time to time.\nSuch new versions will be similar in spirit to the present version,\nbut may differ in detail to address new problems or concerns.\n\nEach version is given a distinguishing version number.  If the Library\nspecifies a version number of this License which applies to it and\n\"any later version\", you have the option of following the terms and\nconditions either of that version or of any later version published by\nthe Free Software Foundation.  If the Library does not specify a\nlicense version number, you may choose any version ever published by\nthe Free Software Foundation.\n\f\n  14. If you wish to incorporate parts of the Library into other free\nprograms whose distribution conditions are incompatible with these,\nwrite to the author to ask for permission.  For software which is\ncopyrighted by the Free Software Foundation, write to the Free\nSoftware Foundation; we sometimes make exceptions for this.  Our\ndecision will be guided by the two goals of preserving the free status\nof all derivatives of our free software and of promoting the sharing\nand reuse of software generally.\n\n                            NO WARRANTY\n\n  15. BECAUSE THE LIBRARY IS LICENSED FREE OF CHARGE, THERE IS NO\nWARRANTY FOR THE LIBRARY, TO THE EXTENT PERMITTED BY APPLICABLE LAW.\nEXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR\nOTHER PARTIES PROVIDE THE LIBRARY \"AS IS\" WITHOUT WARRANTY OF ANY\nKIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE\nIMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR\nPURPOSE.  THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE\nLIBRARY IS WITH YOU.  SHOULD THE LIBRARY PROVE DEFECTIVE, YOU ASSUME\nTHE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION.\n\n  16. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN\nWRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY\nAND/OR REDISTRIBUTE THE LIBRARY AS PERMITTED ABOVE, BE LIABLE TO YOU\nFOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR\nCONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE\nLIBRARY (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING\nRENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A\nFAILURE OF THE LIBRARY TO OPERATE WITH ANY OTHER SOFTWARE), EVEN IF\nSUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH\nDAMAGES.\n\n                     END OF TERMS AND CONDITIONS\n\f\n           How to Apply These Terms to Your New Libraries\n\n  If you develop a new library, and you want it to be of the greatest\npossible use to the public, we recommend making it free software that\neveryone can redistribute and change.  You can do so by permitting\nredistribution under these terms (or, alternatively, under the terms of the\nordinary General Public License).\n\n  To apply these terms, attach the following notices to the library.  It is\nsafest to attach them to the start of each source file to most effectively\nconvey the exclusion of warranty; and each file should have at least the\n\"copyright\" line and a pointer to where the full notice is found.\n\n    <one line to give the library's name and a brief idea of what it does.>\n    Copyright (C) <year>  <name of author>\n\n    This library is free software; you can redistribute it and/or\n    modify it under the terms of the GNU Lesser General Public\n    License as published by the Free Software Foundation; either\n    version 2.1 of the License, or (at your option) any later version.\n\n    This library is distributed in the hope that it will be useful,\n    but WITHOUT ANY WARRANTY; without even the implied warranty of\n    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU\n    Lesser General Public License for more details.\n\n    You should have received a copy of the GNU Lesser General Public\n    License along with this library; if not, write to the Free Software\n    Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA\n\nAlso add information on how to contact you by electronic and paper mail.\n\nYou should also get your employer (if you work as a programmer) or your\nschool, if any, to sign a \"copyright disclaimer\" for the library, if\nnecessary.  Here is a sample; alter the names:\n\n  Yoyodyne, Inc., hereby disclaims all copyright interest in the\n  library `Frob' (a library for tweaking knobs) written by James Random Hacker.\n\n  <signature of Ty Coon>, 1 April 1990\n  Ty Coon, President of Vice\n\nThat's all there is to it!\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/COPYING.MINPACK",
    "content": "Minpack Copyright Notice (1999) University of Chicago.  All rights reserved\n\nRedistribution and use in source and binary forms, with or\nwithout modification, are permitted provided that the\nfollowing conditions are met:\n\n1. Redistributions of source code must retain the above\ncopyright notice, this list of conditions and the following\ndisclaimer.\n\n2. Redistributions in binary form must reproduce the above\ncopyright notice, this list of conditions and the following\ndisclaimer in the documentation and/or other materials\nprovided with the distribution.\n\n3. The end-user documentation included with the\nredistribution, if any, must include the following\nacknowledgment:\n\n   \"This product includes software developed by the\n   University of Chicago, as Operator of Argonne National\n   Laboratory.\n\nAlternately, this acknowledgment may appear in the software\nitself, if and wherever such third-party acknowledgments\nnormally appear.\n\n4. WARRANTY DISCLAIMER. THE SOFTWARE IS SUPPLIED \"AS IS\"\nWITHOUT WARRANTY OF ANY KIND. THE COPYRIGHT HOLDER, THE\nUNITED STATES, THE UNITED STATES DEPARTMENT OF ENERGY, AND\nTHEIR EMPLOYEES: (1) DISCLAIM ANY WARRANTIES, EXPRESS OR\nIMPLIED, INCLUDING BUT NOT LIMITED TO ANY IMPLIED WARRANTIES\nOF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, TITLE\nOR NON-INFRINGEMENT, (2) DO NOT ASSUME ANY LEGAL LIABILITY\nOR RESPONSIBILITY FOR THE ACCURACY, COMPLETENESS, OR\nUSEFULNESS OF THE SOFTWARE, (3) DO NOT REPRESENT THAT USE OF\nTHE SOFTWARE WOULD NOT INFRINGE PRIVATELY OWNED RIGHTS, (4)\nDO NOT WARRANT THAT THE SOFTWARE WILL FUNCTION\nUNINTERRUPTED, THAT IT IS ERROR-FREE OR THAT ANY ERRORS WILL\nBE CORRECTED.\n\n5. LIMITATION OF LIABILITY. IN NO EVENT WILL THE COPYRIGHT\nHOLDER, THE UNITED STATES, THE UNITED STATES DEPARTMENT OF\nENERGY, OR THEIR EMPLOYEES: BE LIABLE FOR ANY INDIRECT,\nINCIDENTAL, CONSEQUENTIAL, SPECIAL OR PUNITIVE DAMAGES OF\nANY KIND OR NATURE, INCLUDING BUT NOT LIMITED TO LOSS OF\nPROFITS OR LOSS OF DATA, FOR ANY REASON WHATSOEVER, WHETHER\nSUCH LIABILITY IS ASSERTED ON THE BASIS OF CONTRACT, TORT\n(INCLUDING NEGLIGENCE OR STRICT LIABILITY), OR OTHERWISE,\nEVEN IF ANY OF SAID PARTIES HAS BEEN WARNED OF THE\nPOSSIBILITY OF SUCH LOSS OR DAMAGES.\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/COPYING.MPL2",
    "content": "Mozilla Public License Version 2.0\n==================================\n\n1. Definitions\n--------------\n\n1.1. \"Contributor\"\n    means each individual or legal entity that creates, contributes to\n    the creation of, or owns Covered Software.\n\n1.2. \"Contributor Version\"\n    means the combination of the Contributions of others (if any) used\n    by a Contributor and that particular Contributor's Contribution.\n\n1.3. \"Contribution\"\n    means Covered Software of a particular Contributor.\n\n1.4. \"Covered Software\"\n    means Source Code Form to which the initial Contributor has attached\n    the notice in Exhibit A, the Executable Form of such Source Code\n    Form, and Modifications of such Source Code Form, in each case\n    including portions thereof.\n\n1.5. \"Incompatible With Secondary Licenses\"\n    means\n\n    (a) that the initial Contributor has attached the notice described\n        in Exhibit B to the Covered Software; or\n\n    (b) that the Covered Software was made available under the terms of\n        version 1.1 or earlier of the License, but not also under the\n        terms of a Secondary License.\n\n1.6. \"Executable Form\"\n    means any form of the work other than Source Code Form.\n\n1.7. \"Larger Work\"\n    means a work that combines Covered Software with other material, in \n    a separate file or files, that is not Covered Software.\n\n1.8. \"License\"\n    means this document.\n\n1.9. \"Licensable\"\n    means having the right to grant, to the maximum extent possible,\n    whether at the time of the initial grant or subsequently, any and\n    all of the rights conveyed by this License.\n\n1.10. \"Modifications\"\n    means any of the following:\n\n    (a) any file in Source Code Form that results from an addition to,\n        deletion from, or modification of the contents of Covered\n        Software; or\n\n    (b) any new file in Source Code Form that contains any Covered\n        Software.\n\n1.11. \"Patent Claims\" of a Contributor\n    means any patent claim(s), including without limitation, method,\n    process, and apparatus claims, in any patent Licensable by such\n    Contributor that would be infringed, but for the grant of the\n    License, by the making, using, selling, offering for sale, having\n    made, import, or transfer of either its Contributions or its\n    Contributor Version.\n\n1.12. \"Secondary License\"\n    means either the GNU General Public License, Version 2.0, the GNU\n    Lesser General Public License, Version 2.1, the GNU Affero General\n    Public License, Version 3.0, or any later versions of those\n    licenses.\n\n1.13. \"Source Code Form\"\n    means the form of the work preferred for making modifications.\n\n1.14. \"You\" (or \"Your\")\n    means an individual or a legal entity exercising rights under this\n    License. For legal entities, \"You\" includes any entity that\n    controls, is controlled by, or is under common control with You. For\n    purposes of this definition, \"control\" means (a) the power, direct\n    or indirect, to cause the direction or management of such entity,\n    whether by contract or otherwise, or (b) ownership of more than\n    fifty percent (50%) of the outstanding shares or beneficial\n    ownership of such entity.\n\n2. License Grants and Conditions\n--------------------------------\n\n2.1. Grants\n\nEach Contributor hereby grants You a world-wide, royalty-free,\nnon-exclusive license:\n\n(a) under intellectual property rights (other than patent or trademark)\n    Licensable by such Contributor to use, reproduce, make available,\n    modify, display, perform, distribute, and otherwise exploit its\n    Contributions, either on an unmodified basis, with Modifications, or\n    as part of a Larger Work; and\n\n(b) under Patent Claims of such Contributor to make, use, sell, offer\n    for sale, have made, import, and otherwise transfer either its\n    Contributions or its Contributor Version.\n\n2.2. Effective Date\n\nThe licenses granted in Section 2.1 with respect to any Contribution\nbecome effective for each Contribution on the date the Contributor first\ndistributes such Contribution.\n\n2.3. Limitations on Grant Scope\n\nThe licenses granted in this Section 2 are the only rights granted under\nthis License. No additional rights or licenses will be implied from the\ndistribution or licensing of Covered Software under this License.\nNotwithstanding Section 2.1(b) above, no patent license is granted by a\nContributor:\n\n(a) for any code that a Contributor has removed from Covered Software;\n    or\n\n(b) for infringements caused by: (i) Your and any other third party's\n    modifications of Covered Software, or (ii) the combination of its\n    Contributions with other software (except as part of its Contributor\n    Version); or\n\n(c) under Patent Claims infringed by Covered Software in the absence of\n    its Contributions.\n\nThis License does not grant any rights in the trademarks, service marks,\nor logos of any Contributor (except as may be necessary to comply with\nthe notice requirements in Section 3.4).\n\n2.4. Subsequent Licenses\n\nNo Contributor makes additional grants as a result of Your choice to\ndistribute the Covered Software under a subsequent version of this\nLicense (see Section 10.2) or under the terms of a Secondary License (if\npermitted under the terms of Section 3.3).\n\n2.5. Representation\n\nEach Contributor represents that the Contributor believes its\nContributions are its original creation(s) or it has sufficient rights\nto grant the rights to its Contributions conveyed by this License.\n\n2.6. Fair Use\n\nThis License is not intended to limit any rights You have under\napplicable copyright doctrines of fair use, fair dealing, or other\nequivalents.\n\n2.7. Conditions\n\nSections 3.1, 3.2, 3.3, and 3.4 are conditions of the licenses granted\nin Section 2.1.\n\n3. Responsibilities\n-------------------\n\n3.1. Distribution of Source Form\n\nAll distribution of Covered Software in Source Code Form, including any\nModifications that You create or to which You contribute, must be under\nthe terms of this License. You must inform recipients that the Source\nCode Form of the Covered Software is governed by the terms of this\nLicense, and how they can obtain a copy of this License. You may not\nattempt to alter or restrict the recipients' rights in the Source Code\nForm.\n\n3.2. Distribution of Executable Form\n\nIf You distribute Covered Software in Executable Form then:\n\n(a) such Covered Software must also be made available in Source Code\n    Form, as described in Section 3.1, and You must inform recipients of\n    the Executable Form how they can obtain a copy of such Source Code\n    Form by reasonable means in a timely manner, at a charge no more\n    than the cost of distribution to the recipient; and\n\n(b) You may distribute such Executable Form under the terms of this\n    License, or sublicense it under different terms, provided that the\n    license for the Executable Form does not attempt to limit or alter\n    the recipients' rights in the Source Code Form under this License.\n\n3.3. Distribution of a Larger Work\n\nYou may create and distribute a Larger Work under terms of Your choice,\nprovided that You also comply with the requirements of this License for\nthe Covered Software. If the Larger Work is a combination of Covered\nSoftware with a work governed by one or more Secondary Licenses, and the\nCovered Software is not Incompatible With Secondary Licenses, this\nLicense permits You to additionally distribute such Covered Software\nunder the terms of such Secondary License(s), so that the recipient of\nthe Larger Work may, at their option, further distribute the Covered\nSoftware under the terms of either this License or such Secondary\nLicense(s).\n\n3.4. Notices\n\nYou may not remove or alter the substance of any license notices\n(including copyright notices, patent notices, disclaimers of warranty,\nor limitations of liability) contained within the Source Code Form of\nthe Covered Software, except that You may alter any license notices to\nthe extent required to remedy known factual inaccuracies.\n\n3.5. Application of Additional Terms\n\nYou may choose to offer, and to charge a fee for, warranty, support,\nindemnity or liability obligations to one or more recipients of Covered\nSoftware. However, You may do so only on Your own behalf, and not on\nbehalf of any Contributor. You must make it absolutely clear that any\nsuch warranty, support, indemnity, or liability obligation is offered by\nYou alone, and You hereby agree to indemnify every Contributor for any\nliability incurred by such Contributor as a result of warranty, support,\nindemnity or liability terms You offer. You may include additional\ndisclaimers of warranty and limitations of liability specific to any\njurisdiction.\n\n4. Inability to Comply Due to Statute or Regulation\n---------------------------------------------------\n\nIf it is impossible for You to comply with any of the terms of this\nLicense with respect to some or all of the Covered Software due to\nstatute, judicial order, or regulation then You must: (a) comply with\nthe terms of this License to the maximum extent possible; and (b)\ndescribe the limitations and the code they affect. Such description must\nbe placed in a text file included with all distributions of the Covered\nSoftware under this License. Except to the extent prohibited by statute\nor regulation, such description must be sufficiently detailed for a\nrecipient of ordinary skill to be able to understand it.\n\n5. Termination\n--------------\n\n5.1. The rights granted under this License will terminate automatically\nif You fail to comply with any of its terms. However, if You become\ncompliant, then the rights granted under this License from a particular\nContributor are reinstated (a) provisionally, unless and until such\nContributor explicitly and finally terminates Your grants, and (b) on an\nongoing basis, if such Contributor fails to notify You of the\nnon-compliance by some reasonable means prior to 60 days after You have\ncome back into compliance. Moreover, Your grants from a particular\nContributor are reinstated on an ongoing basis if such Contributor\nnotifies You of the non-compliance by some reasonable means, this is the\nfirst time You have received notice of non-compliance with this License\nfrom such Contributor, and You become compliant prior to 30 days after\nYour receipt of the notice.\n\n5.2. If You initiate litigation against any entity by asserting a patent\ninfringement claim (excluding declaratory judgment actions,\ncounter-claims, and cross-claims) alleging that a Contributor Version\ndirectly or indirectly infringes any patent, then the rights granted to\nYou by any and all Contributors for the Covered Software under Section\n2.1 of this License shall terminate.\n\n5.3. In the event of termination under Sections 5.1 or 5.2 above, all\nend user license agreements (excluding distributors and resellers) which\nhave been validly granted by You or Your distributors under this License\nprior to termination shall survive termination.\n\n************************************************************************\n*                                                                      *\n*  6. Disclaimer of Warranty                                           *\n*  -------------------------                                           *\n*                                                                      *\n*  Covered Software is provided under this License on an \"as is\"       *\n*  basis, without warranty of any kind, either expressed, implied, or  *\n*  statutory, including, without limitation, warranties that the       *\n*  Covered Software is free of defects, merchantable, fit for a        *\n*  particular purpose or non-infringing. The entire risk as to the     *\n*  quality and performance of the Covered Software is with You.        *\n*  Should any Covered Software prove defective in any respect, You     *\n*  (not any Contributor) assume the cost of any necessary servicing,   *\n*  repair, or correction. This disclaimer of warranty constitutes an   *\n*  essential part of this License. No use of any Covered Software is   *\n*  authorized under this License except under this disclaimer.         *\n*                                                                      *\n************************************************************************\n\n************************************************************************\n*                                                                      *\n*  7. Limitation of Liability                                          *\n*  --------------------------                                          *\n*                                                                      *\n*  Under no circumstances and under no legal theory, whether tort      *\n*  (including negligence), contract, or otherwise, shall any           *\n*  Contributor, or anyone who distributes Covered Software as          *\n*  permitted above, be liable to You for any direct, indirect,         *\n*  special, incidental, or consequential damages of any character      *\n*  including, without limitation, damages for lost profits, loss of    *\n*  goodwill, work stoppage, computer failure or malfunction, or any    *\n*  and all other commercial damages or losses, even if such party      *\n*  shall have been informed of the possibility of such damages. This   *\n*  limitation of liability shall not apply to liability for death or   *\n*  personal injury resulting from such party's negligence to the       *\n*  extent applicable law prohibits such limitation. Some               *\n*  jurisdictions do not allow the exclusion or limitation of           *\n*  incidental or consequential damages, so this exclusion and          *\n*  limitation may not apply to You.                                    *\n*                                                                      *\n************************************************************************\n\n8. Litigation\n-------------\n\nAny litigation relating to this License may be brought only in the\ncourts of a jurisdiction where the defendant maintains its principal\nplace of business and such litigation shall be governed by laws of that\njurisdiction, without reference to its conflict-of-law provisions.\nNothing in this Section shall prevent a party's ability to bring\ncross-claims or counter-claims.\n\n9. Miscellaneous\n----------------\n\nThis License represents the complete agreement concerning the subject\nmatter hereof. If any provision of this License is held to be\nunenforceable, such provision shall be reformed only to the extent\nnecessary to make it enforceable. Any law or regulation which provides\nthat the language of a contract shall be construed against the drafter\nshall not be used to construe this License against a Contributor.\n\n10. Versions of the License\n---------------------------\n\n10.1. New Versions\n\nMozilla Foundation is the license steward. Except as provided in Section\n10.3, no one other than the license steward has the right to modify or\npublish new versions of this License. Each version will be given a\ndistinguishing version number.\n\n10.2. Effect of New Versions\n\nYou may distribute the Covered Software under the terms of the version\nof the License under which You originally received the Covered Software,\nor under the terms of any subsequent version published by the license\nsteward.\n\n10.3. Modified Versions\n\nIf you create software not governed by this License, and you want to\ncreate a new license for such software, you may create and use a\nmodified version of this License if you rename the license and remove\nany references to the name of the license steward (except to note that\nsuch modified license differs from this License).\n\n10.4. Distributing Source Code Form that is Incompatible With Secondary\nLicenses\n\nIf You choose to distribute Source Code Form that is Incompatible With\nSecondary Licenses under the terms of this version of the License, the\nnotice described in Exhibit B of this License must be attached.\n\nExhibit A - Source Code Form License Notice\n-------------------------------------------\n\n  This Source Code Form is subject to the terms of the Mozilla Public\n  License, v. 2.0. If a copy of the MPL was not distributed with this\n  file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\nIf it is not possible or desirable to put the notice in a particular\nfile, then You may include the notice in a location (such as a LICENSE\nfile in a relevant directory) where a recipient would be likely to look\nfor such a notice.\n\nYou may add additional accurate notices of copyright ownership.\n\nExhibit B - \"Incompatible With Secondary Licenses\" Notice\n---------------------------------------------------------\n\n  This Source Code Form is \"Incompatible With Secondary Licenses\", as\n  defined by the Mozilla Public License, v. 2.0.\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/COPYING.README",
    "content": "Eigen is primarily MPL2 licensed. See COPYING.MPL2 and these links:\n  http://www.mozilla.org/MPL/2.0/\n  http://www.mozilla.org/MPL/2.0/FAQ.html\n\nSome files contain third-party code under BSD or LGPL licenses, whence the other\nCOPYING.* files here.\n\nAll the LGPL code is either LGPL 2.1-only, or LGPL 2.1-or-later.\nFor this reason, the COPYING.LGPL file contains the LGPL 2.1 text.\n\nIf you want to guarantee that the Eigen code that you are #including is licensed\nunder the MPL2 and possibly more permissive licenses (like BSD), #define this\npreprocessor symbol:\n  EIGEN_MPL2_ONLY\nFor example, with most compilers, you could add this to your project CXXFLAGS:\n  -DEIGEN_MPL2_ONLY\nThis will cause a compilation error to be generated if you #include any code that is\nLGPL licensed.\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/CTestConfig.cmake",
    "content": "## This file should be placed in the root directory of your project.\n## Then modify the CMakeLists.txt file in the root directory of your\n## project to incorporate the testing dashboard.\n## # The following are required to uses Dart and the Cdash dashboard\n##   enable_testing()\n##   include(CTest)\nset(CTEST_PROJECT_NAME \"Eigen\")\nset(CTEST_NIGHTLY_START_TIME \"00:00:00 UTC\")\n\nset(CTEST_DROP_METHOD \"http\")\nset(CTEST_DROP_SITE \"my.cdash.org\")\nset(CTEST_DROP_LOCATION \"/submit.php?project=Eigen\")\nset(CTEST_DROP_SITE_CDASH TRUE)\n#set(CTEST_PROJECT_SUBPROJECTS\n#Official\n#Unsupported\n#)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/CTestCustom.cmake.in",
    "content": "\nset(CTEST_CUSTOM_MAXIMUM_NUMBER_OF_WARNINGS \"2000\")\nset(CTEST_CUSTOM_MAXIMUM_NUMBER_OF_ERRORS   \"2000\")\nlist(APPEND CTEST_CUSTOM_ERROR_EXCEPTION    @EIGEN_CTEST_ERROR_EXCEPTION@)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/Cholesky",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CHOLESKY_MODULE_H\n#define EIGEN_CHOLESKY_MODULE_H\n\n#include \"Core\"\n#include \"Jacobi\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \\defgroup Cholesky_Module Cholesky module\n  *\n  *\n  *\n  * This module provides two variants of the Cholesky decomposition for selfadjoint (hermitian) matrices.\n  * Those decompositions are also accessible via the following methods:\n  *  - MatrixBase::llt()\n  *  - MatrixBase::ldlt()\n  *  - SelfAdjointView::llt()\n  *  - SelfAdjointView::ldlt()\n  *\n  * \\code\n  * #include <Eigen/Cholesky>\n  * \\endcode\n  */\n\n#include \"src/Cholesky/LLT.h\"\n#include \"src/Cholesky/LDLT.h\"\n#ifdef EIGEN_USE_LAPACKE\n#ifdef EIGEN_USE_MKL\n#include \"mkl_lapacke.h\"\n#else\n#include \"src/misc/lapacke.h\"\n#endif\n#include \"src/Cholesky/LLT_LAPACKE.h\"\n#endif\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_CHOLESKY_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/CholmodSupport",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CHOLMODSUPPORT_MODULE_H\n#define EIGEN_CHOLMODSUPPORT_MODULE_H\n\n#include \"SparseCore\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\nextern \"C\" {\n  #include <cholmod.h>\n}\n\n/** \\ingroup Support_modules\n  * \\defgroup CholmodSupport_Module CholmodSupport module\n  *\n  * This module provides an interface to the Cholmod library which is part of the <a href=\"http://www.suitesparse.com\">suitesparse</a> package.\n  * It provides the two following main factorization classes:\n  * - class CholmodSupernodalLLT: a supernodal LLT Cholesky factorization.\n  * - class CholmodDecomposiiton: a general L(D)LT Cholesky factorization with automatic or explicit runtime selection of the underlying factorization method (supernodal or simplicial).\n  *\n  * For the sake of completeness, this module also propose the two following classes:\n  * - class CholmodSimplicialLLT\n  * - class CholmodSimplicialLDLT\n  * Note that these classes does not bring any particular advantage compared to the built-in\n  * SimplicialLLT and SimplicialLDLT factorization classes.\n  *\n  * \\code\n  * #include <Eigen/CholmodSupport>\n  * \\endcode\n  *\n  * In order to use this module, the cholmod headers must be accessible from the include paths, and your binary must be linked to the cholmod library and its dependencies.\n  * The dependencies depend on how cholmod has been compiled.\n  * For a cmake based project, you can use our FindCholmod.cmake module to help you in this task.\n  *\n  */\n\n#include \"src/CholmodSupport/CholmodSupport.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_CHOLMODSUPPORT_MODULE_H\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/Dense",
    "content": "#include \"Core\"\n#include \"LU\"\n#include \"Cholesky\"\n#include \"QR\"\n#include \"SVD\"\n#include \"Geometry\"\n#include \"Eigenvalues\"\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/Eigen",
    "content": "#include \"Dense\"\n#include \"Sparse\"\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/Eigenvalues",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_EIGENVALUES_MODULE_H\n#define EIGEN_EIGENVALUES_MODULE_H\n\n#include \"Core\"\n\n#include \"Cholesky\"\n#include \"Jacobi\"\n#include \"Householder\"\n#include \"LU\"\n#include \"Geometry\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \\defgroup Eigenvalues_Module Eigenvalues module\n  *\n  *\n  *\n  * This module mainly provides various eigenvalue solvers.\n  * This module also provides some MatrixBase methods, including:\n  *  - MatrixBase::eigenvalues(),\n  *  - MatrixBase::operatorNorm()\n  *\n  * \\code\n  * #include <Eigen/Eigenvalues>\n  * \\endcode\n  */\n\n#include \"src/misc/RealSvd2x2.h\"\n#include \"src/Eigenvalues/Tridiagonalization.h\"\n#include \"src/Eigenvalues/RealSchur.h\"\n#include \"src/Eigenvalues/EigenSolver.h\"\n#include \"src/Eigenvalues/SelfAdjointEigenSolver.h\"\n#include \"src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h\"\n#include \"src/Eigenvalues/HessenbergDecomposition.h\"\n#include \"src/Eigenvalues/ComplexSchur.h\"\n#include \"src/Eigenvalues/ComplexEigenSolver.h\"\n#include \"src/Eigenvalues/RealQZ.h\"\n#include \"src/Eigenvalues/GeneralizedEigenSolver.h\"\n#include \"src/Eigenvalues/MatrixBaseEigenvalues.h\"\n#ifdef EIGEN_USE_LAPACKE\n#ifdef EIGEN_USE_MKL\n#include \"mkl_lapacke.h\"\n#else\n#include \"src/misc/lapacke.h\"\n#endif\n#include \"src/Eigenvalues/RealSchur_LAPACKE.h\"\n#include \"src/Eigenvalues/ComplexSchur_LAPACKE.h\"\n#include \"src/Eigenvalues/SelfAdjointEigenSolver_LAPACKE.h\"\n#endif\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_EIGENVALUES_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/Geometry",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_GEOMETRY_MODULE_H\n#define EIGEN_GEOMETRY_MODULE_H\n\n#include \"Core\"\n\n#include \"SVD\"\n#include \"LU\"\n#include <limits>\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \\defgroup Geometry_Module Geometry module\n  *\n  * This module provides support for:\n  *  - fixed-size homogeneous transformations\n  *  - translation, scaling, 2D and 3D rotations\n  *  - \\link Quaternion quaternions \\endlink\n  *  - cross products (\\ref MatrixBase::cross, \\ref MatrixBase::cross3)\n  *  - orthognal vector generation (\\ref MatrixBase::unitOrthogonal)\n  *  - some linear components: \\link ParametrizedLine parametrized-lines \\endlink and \\link Hyperplane hyperplanes \\endlink\n  *  - \\link AlignedBox axis aligned bounding boxes \\endlink\n  *  - \\link umeyama least-square transformation fitting \\endlink\n  *\n  * \\code\n  * #include <Eigen/Geometry>\n  * \\endcode\n  */\n\n#include \"src/Geometry/OrthoMethods.h\"\n#include \"src/Geometry/EulerAngles.h\"\n\n#include \"src/Geometry/Homogeneous.h\"\n#include \"src/Geometry/RotationBase.h\"\n#include \"src/Geometry/Rotation2D.h\"\n#include \"src/Geometry/Quaternion.h\"\n#include \"src/Geometry/AngleAxis.h\"\n#include \"src/Geometry/Transform.h\"\n#include \"src/Geometry/Translation.h\"\n#include \"src/Geometry/Scaling.h\"\n#include \"src/Geometry/Hyperplane.h\"\n#include \"src/Geometry/ParametrizedLine.h\"\n#include \"src/Geometry/AlignedBox.h\"\n#include \"src/Geometry/Umeyama.h\"\n\n// Use the SSE optimized version whenever possible.\n#if (defined EIGEN_VECTORIZE_SSE) || (defined EIGEN_VECTORIZE_NEON)\n#include \"src/Geometry/arch/Geometry_SIMD.h\"\n#endif\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_GEOMETRY_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/Householder",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_HOUSEHOLDER_MODULE_H\n#define EIGEN_HOUSEHOLDER_MODULE_H\n\n#include \"Core\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \\defgroup Householder_Module Householder module\n  * This module provides Householder transformations.\n  *\n  * \\code\n  * #include <Eigen/Householder>\n  * \\endcode\n  */\n\n#include \"src/Householder/Householder.h\"\n#include \"src/Householder/HouseholderSequence.h\"\n#include \"src/Householder/BlockHouseholder.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_HOUSEHOLDER_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/IterativeLinearSolvers",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ITERATIVELINEARSOLVERS_MODULE_H\n#define EIGEN_ITERATIVELINEARSOLVERS_MODULE_H\n\n#include \"SparseCore\"\n#include \"OrderingMethods\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \n  * \\defgroup IterativeLinearSolvers_Module IterativeLinearSolvers module\n  *\n  * This module currently provides iterative methods to solve problems of the form \\c A \\c x = \\c b, where \\c A is a squared matrix, usually very large and sparse.\n  * Those solvers are accessible via the following classes:\n  *  - ConjugateGradient for selfadjoint (hermitian) matrices,\n  *  - LeastSquaresConjugateGradient for rectangular least-square problems,\n  *  - BiCGSTAB for general square matrices.\n  *\n  * These iterative solvers are associated with some preconditioners:\n  *  - IdentityPreconditioner - not really useful\n  *  - DiagonalPreconditioner - also called Jacobi preconditioner, work very well on diagonal dominant matrices.\n  *  - IncompleteLUT - incomplete LU factorization with dual thresholding\n  *\n  * Such problems can also be solved using the direct sparse decomposition modules: SparseCholesky, CholmodSupport, UmfPackSupport, SuperLUSupport.\n  *\n    \\code\n    #include <Eigen/IterativeLinearSolvers>\n    \\endcode\n  */\n\n#include \"src/IterativeLinearSolvers/SolveWithGuess.h\"\n#include \"src/IterativeLinearSolvers/IterativeSolverBase.h\"\n#include \"src/IterativeLinearSolvers/BasicPreconditioners.h\"\n#include \"src/IterativeLinearSolvers/ConjugateGradient.h\"\n#include \"src/IterativeLinearSolvers/LeastSquareConjugateGradient.h\"\n#include \"src/IterativeLinearSolvers/BiCGSTAB.h\"\n#include \"src/IterativeLinearSolvers/IncompleteLUT.h\"\n#include \"src/IterativeLinearSolvers/IncompleteCholesky.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_ITERATIVELINEARSOLVERS_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/Jacobi",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_JACOBI_MODULE_H\n#define EIGEN_JACOBI_MODULE_H\n\n#include \"Core\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \\defgroup Jacobi_Module Jacobi module\n  * This module provides Jacobi and Givens rotations.\n  *\n  * \\code\n  * #include <Eigen/Jacobi>\n  * \\endcode\n  *\n  * In addition to listed classes, it defines the two following MatrixBase methods to apply a Jacobi or Givens rotation:\n  *  - MatrixBase::applyOnTheLeft()\n  *  - MatrixBase::applyOnTheRight().\n  */\n\n#include \"src/Jacobi/Jacobi.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_JACOBI_MODULE_H\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/KLUSupport",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_KLUSUPPORT_MODULE_H\n#define EIGEN_KLUSUPPORT_MODULE_H\n\n#include <Eigen/SparseCore>\n\n#include <Eigen/src/Core/util/DisableStupidWarnings.h>\n\nextern \"C\" {\n#include <btf.h>\n#include <klu.h>\n   }\n\n/** \\ingroup Support_modules\n  * \\defgroup KLUSupport_Module KLUSupport module\n  *\n  * This module provides an interface to the KLU library which is part of the <a href=\"http://www.suitesparse.com\">suitesparse</a> package.\n  * It provides the following factorization class:\n  * - class KLU: a sparse LU factorization, well-suited for circuit simulation.\n  *\n  * \\code\n  * #include <Eigen/KLUSupport>\n  * \\endcode\n  *\n  * In order to use this module, the klu and btf headers must be accessible from the include paths, and your binary must be linked to the klu library and its dependencies.\n  * The dependencies depend on how umfpack has been compiled.\n  * For a cmake based project, you can use our FindKLU.cmake module to help you in this task.\n  *\n  */\n\n#include \"src/KLUSupport/KLUSupport.h\"\n\n#include <Eigen/src/Core/util/ReenableStupidWarnings.h>\n\n#endif // EIGEN_KLUSUPPORT_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/LU",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_LU_MODULE_H\n#define EIGEN_LU_MODULE_H\n\n#include \"Core\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \\defgroup LU_Module LU module\n  * This module includes %LU decomposition and related notions such as matrix inversion and determinant.\n  * This module defines the following MatrixBase methods:\n  *  - MatrixBase::inverse()\n  *  - MatrixBase::determinant()\n  *\n  * \\code\n  * #include <Eigen/LU>\n  * \\endcode\n  */\n\n#include \"src/misc/Kernel.h\"\n#include \"src/misc/Image.h\"\n#include \"src/LU/FullPivLU.h\"\n#include \"src/LU/PartialPivLU.h\"\n#ifdef EIGEN_USE_LAPACKE\n#ifdef EIGEN_USE_MKL\n#include \"mkl_lapacke.h\"\n#else\n#include \"src/misc/lapacke.h\"\n#endif\n#include \"src/LU/PartialPivLU_LAPACKE.h\"\n#endif\n#include \"src/LU/Determinant.h\"\n#include \"src/LU/InverseImpl.h\"\n\n#if defined EIGEN_VECTORIZE_SSE || defined EIGEN_VECTORIZE_NEON\n  #include \"src/LU/arch/InverseSize4.h\"\n#endif\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_LU_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/MetisSupport",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_METISSUPPORT_MODULE_H\n#define EIGEN_METISSUPPORT_MODULE_H\n\n#include \"SparseCore\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\nextern \"C\" {\n#include <metis.h>\n}\n\n\n/** \\ingroup Support_modules\n  * \\defgroup MetisSupport_Module MetisSupport module\n  *\n  * \\code\n  * #include <Eigen/MetisSupport>\n  * \\endcode\n  * This module defines an interface to the METIS reordering package (http://glaros.dtc.umn.edu/gkhome/views/metis). \n  * It can be used just as any other built-in method as explained in \\link OrderingMethods_Module here. \\endlink\n  */\n\n\n#include \"src/MetisSupport/MetisSupport.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_METISSUPPORT_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/OrderingMethods",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ORDERINGMETHODS_MODULE_H\n#define EIGEN_ORDERINGMETHODS_MODULE_H\n\n#include \"SparseCore\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \n  * \\defgroup OrderingMethods_Module OrderingMethods module\n  *\n  * This module is currently for internal use only\n  * \n  * It defines various built-in and external ordering methods for sparse matrices. \n  * They are typically used to reduce the number of elements during \n  * the sparse matrix decomposition (LLT, LU, QR).\n  * Precisely, in a preprocessing step, a permutation matrix P is computed using \n  * those ordering methods and applied to the columns of the matrix. \n  * Using for instance the sparse Cholesky decomposition, it is expected that \n  * the nonzeros elements in LLT(A*P) will be much smaller than that in LLT(A).\n  * \n  * \n  * Usage : \n  * \\code\n  * #include <Eigen/OrderingMethods>\n  * \\endcode\n  * \n  * A simple usage is as a template parameter in the sparse decomposition classes : \n  * \n  * \\code \n  * SparseLU<MatrixType, COLAMDOrdering<int> > solver;\n  * \\endcode \n  * \n  * \\code \n  * SparseQR<MatrixType, COLAMDOrdering<int> > solver;\n  * \\endcode\n  * \n  * It is possible as well to call directly a particular ordering method for your own purpose, \n  * \\code \n  * AMDOrdering<int> ordering;\n  * PermutationMatrix<Dynamic, Dynamic, int> perm;\n  * SparseMatrix<double> A; \n  * //Fill the matrix ...\n  * \n  * ordering(A, perm); // Call AMD\n  * \\endcode\n  * \n  * \\note Some of these methods (like AMD or METIS), need the sparsity pattern \n  * of the input matrix to be symmetric. When the matrix is structurally unsymmetric, \n  * Eigen computes internally the pattern of \\f$A^T*A\\f$ before calling the method.\n  * If your matrix is already symmetric (at leat in structure), you can avoid that\n  * by calling the method with a SelfAdjointView type.\n  * \n  * \\code\n  *  // Call the ordering on the pattern of the lower triangular matrix A\n  * ordering(A.selfadjointView<Lower>(), perm);\n  * \\endcode\n  */\n\n#include \"src/OrderingMethods/Amd.h\"\n#include \"src/OrderingMethods/Ordering.h\"\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_ORDERINGMETHODS_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/PaStiXSupport",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_PASTIXSUPPORT_MODULE_H\n#define EIGEN_PASTIXSUPPORT_MODULE_H\n\n#include \"SparseCore\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\nextern \"C\" {\n#include <pastix_nompi.h>\n#include <pastix.h>\n}\n\n#ifdef complex\n#undef complex\n#endif\n\n/** \\ingroup Support_modules\n  * \\defgroup PaStiXSupport_Module PaStiXSupport module\n  * \n  * This module provides an interface to the <a href=\"http://pastix.gforge.inria.fr/\">PaSTiX</a> library.\n  * PaSTiX is a general \\b supernodal, \\b parallel and \\b opensource sparse solver.\n  * It provides the two following main factorization classes:\n  * - class PastixLLT : a supernodal, parallel LLt Cholesky factorization.\n  * - class PastixLDLT: a supernodal, parallel LDLt Cholesky factorization.\n  * - class PastixLU : a supernodal, parallel LU factorization (optimized for a symmetric pattern).\n  * \n  * \\code\n  * #include <Eigen/PaStiXSupport>\n  * \\endcode\n  *\n  * In order to use this module, the PaSTiX headers must be accessible from the include paths, and your binary must be linked to the PaSTiX library and its dependencies.\n  * This wrapper resuires PaStiX version 5.x compiled without MPI support.\n  * The dependencies depend on how PaSTiX has been compiled.\n  * For a cmake based project, you can use our FindPaSTiX.cmake module to help you in this task.\n  *\n  */\n\n#include \"src/PaStiXSupport/PaStiXSupport.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_PASTIXSUPPORT_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/PardisoSupport",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_PARDISOSUPPORT_MODULE_H\n#define EIGEN_PARDISOSUPPORT_MODULE_H\n\n#include \"SparseCore\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n#include <mkl_pardiso.h>\n\n/** \\ingroup Support_modules\n  * \\defgroup PardisoSupport_Module PardisoSupport module\n  *\n  * This module brings support for the Intel(R) MKL PARDISO direct sparse solvers.\n  *\n  * \\code\n  * #include <Eigen/PardisoSupport>\n  * \\endcode\n  *\n  * In order to use this module, the MKL headers must be accessible from the include paths, and your binary must be linked to the MKL library and its dependencies.\n  * See this \\ref TopicUsingIntelMKL \"page\" for more information on MKL-Eigen integration.\n  * \n  */\n\n#include \"src/PardisoSupport/PardisoSupport.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_PARDISOSUPPORT_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/QR",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_QR_MODULE_H\n#define EIGEN_QR_MODULE_H\n\n#include \"Core\"\n\n#include \"Cholesky\"\n#include \"Jacobi\"\n#include \"Householder\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \\defgroup QR_Module QR module\n  *\n  *\n  *\n  * This module provides various QR decompositions\n  * This module also provides some MatrixBase methods, including:\n  *  - MatrixBase::householderQr()\n  *  - MatrixBase::colPivHouseholderQr()\n  *  - MatrixBase::fullPivHouseholderQr()\n  *\n  * \\code\n  * #include <Eigen/QR>\n  * \\endcode\n  */\n\n#include \"src/QR/HouseholderQR.h\"\n#include \"src/QR/FullPivHouseholderQR.h\"\n#include \"src/QR/ColPivHouseholderQR.h\"\n#include \"src/QR/CompleteOrthogonalDecomposition.h\"\n#ifdef EIGEN_USE_LAPACKE\n#ifdef EIGEN_USE_MKL\n#include \"mkl_lapacke.h\"\n#else\n#include \"src/misc/lapacke.h\"\n#endif\n#include \"src/QR/HouseholderQR_LAPACKE.h\"\n#include \"src/QR/ColPivHouseholderQR_LAPACKE.h\"\n#endif\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_QR_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/QtAlignedMalloc",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_QTMALLOC_MODULE_H\n#define EIGEN_QTMALLOC_MODULE_H\n\n#include \"Core\"\n\n#if (!EIGEN_MALLOC_ALREADY_ALIGNED)\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\nvoid *qMalloc(std::size_t size)\n{\n  return Eigen::internal::aligned_malloc(size);\n}\n\nvoid qFree(void *ptr)\n{\n  Eigen::internal::aligned_free(ptr);\n}\n\nvoid *qRealloc(void *ptr, std::size_t size)\n{\n  void* newPtr = Eigen::internal::aligned_malloc(size);\n  std::memcpy(newPtr, ptr, size);\n  Eigen::internal::aligned_free(ptr);\n  return newPtr;\n}\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif\n\n#endif // EIGEN_QTMALLOC_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/SPQRSupport",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPQRSUPPORT_MODULE_H\n#define EIGEN_SPQRSUPPORT_MODULE_H\n\n#include \"SparseCore\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n#include \"SuiteSparseQR.hpp\"\n\n/** \\ingroup Support_modules\n  * \\defgroup SPQRSupport_Module SuiteSparseQR module\n  * \n  * This module provides an interface to the SPQR library, which is part of the <a href=\"http://www.suitesparse.com\">suitesparse</a> package.\n  *\n  * \\code\n  * #include <Eigen/SPQRSupport>\n  * \\endcode\n  *\n  * In order to use this module, the SPQR headers must be accessible from the include paths, and your binary must be linked to the SPQR library and its dependencies (Cholmod, AMD, COLAMD,...).\n  * For a cmake based project, you can use our FindSPQR.cmake and FindCholmod.Cmake modules\n  *\n  */\n\n#include \"src/CholmodSupport/CholmodSupport.h\"\n#include \"src/SPQRSupport/SuiteSparseQRSupport.h\"\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/SVD",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SVD_MODULE_H\n#define EIGEN_SVD_MODULE_H\n\n#include \"QR\"\n#include \"Householder\"\n#include \"Jacobi\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \\defgroup SVD_Module SVD module\n  *\n  *\n  *\n  * This module provides SVD decomposition for matrices (both real and complex).\n  * Two decomposition algorithms are provided:\n  *  - JacobiSVD implementing two-sided Jacobi iterations is numerically very accurate, fast for small matrices, but very slow for larger ones.\n  *  - BDCSVD implementing a recursive divide & conquer strategy on top of an upper-bidiagonalization which remains fast for large problems.\n  * These decompositions are accessible via the respective classes and following MatrixBase methods:\n  *  - MatrixBase::jacobiSvd()\n  *  - MatrixBase::bdcSvd()\n  *\n  * \\code\n  * #include <Eigen/SVD>\n  * \\endcode\n  */\n\n#include \"src/misc/RealSvd2x2.h\"\n#include \"src/SVD/UpperBidiagonalization.h\"\n#include \"src/SVD/SVDBase.h\"\n#include \"src/SVD/JacobiSVD.h\"\n#include \"src/SVD/BDCSVD.h\"\n#if defined(EIGEN_USE_LAPACKE) && !defined(EIGEN_USE_LAPACKE_STRICT)\n#ifdef EIGEN_USE_MKL\n#include \"mkl_lapacke.h\"\n#else\n#include \"src/misc/lapacke.h\"\n#endif\n#include \"src/SVD/JacobiSVD_LAPACKE.h\"\n#endif\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_SVD_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/Sparse",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_MODULE_H\n#define EIGEN_SPARSE_MODULE_H\n\n/** \\defgroup Sparse_Module Sparse meta-module\n  *\n  * Meta-module including all related modules:\n  * - \\ref SparseCore_Module\n  * - \\ref OrderingMethods_Module\n  * - \\ref SparseCholesky_Module\n  * - \\ref SparseLU_Module\n  * - \\ref SparseQR_Module\n  * - \\ref IterativeLinearSolvers_Module\n  *\n    \\code\n    #include <Eigen/Sparse>\n    \\endcode\n  */\n\n#include \"SparseCore\"\n#include \"OrderingMethods\"\n#include \"SparseCholesky\"\n#include \"SparseLU\"\n#include \"SparseQR\"\n#include \"IterativeLinearSolvers\"\n\n#endif // EIGEN_SPARSE_MODULE_H\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/SparseCholesky",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2013 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSECHOLESKY_MODULE_H\n#define EIGEN_SPARSECHOLESKY_MODULE_H\n\n#include \"SparseCore\"\n#include \"OrderingMethods\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \n  * \\defgroup SparseCholesky_Module SparseCholesky module\n  *\n  * This module currently provides two variants of the direct sparse Cholesky decomposition for selfadjoint (hermitian) matrices.\n  * Those decompositions are accessible via the following classes:\n  *  - SimplicialLLt,\n  *  - SimplicialLDLt\n  *\n  * Such problems can also be solved using the ConjugateGradient solver from the IterativeLinearSolvers module.\n  *\n  * \\code\n  * #include <Eigen/SparseCholesky>\n  * \\endcode\n  */\n\n#include \"src/SparseCholesky/SimplicialCholesky.h\"\n#include \"src/SparseCholesky/SimplicialCholesky_impl.h\"\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_SPARSECHOLESKY_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/SparseCore",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSECORE_MODULE_H\n#define EIGEN_SPARSECORE_MODULE_H\n\n#include \"Core\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n#include <vector>\n#include <map>\n#include <cstdlib>\n#include <cstring>\n#include <algorithm>\n\n/** \n  * \\defgroup SparseCore_Module SparseCore module\n  *\n  * This module provides a sparse matrix representation, and basic associated matrix manipulations\n  * and operations.\n  *\n  * See the \\ref TutorialSparse \"Sparse tutorial\"\n  *\n  * \\code\n  * #include <Eigen/SparseCore>\n  * \\endcode\n  *\n  * This module depends on: Core.\n  */\n\n#include \"src/SparseCore/SparseUtil.h\"\n#include \"src/SparseCore/SparseMatrixBase.h\"\n#include \"src/SparseCore/SparseAssign.h\"\n#include \"src/SparseCore/CompressedStorage.h\"\n#include \"src/SparseCore/AmbiVector.h\"\n#include \"src/SparseCore/SparseCompressedBase.h\"\n#include \"src/SparseCore/SparseMatrix.h\"\n#include \"src/SparseCore/SparseMap.h\"\n#include \"src/SparseCore/MappedSparseMatrix.h\"\n#include \"src/SparseCore/SparseVector.h\"\n#include \"src/SparseCore/SparseRef.h\"\n#include \"src/SparseCore/SparseCwiseUnaryOp.h\"\n#include \"src/SparseCore/SparseCwiseBinaryOp.h\"\n#include \"src/SparseCore/SparseTranspose.h\"\n#include \"src/SparseCore/SparseBlock.h\"\n#include \"src/SparseCore/SparseDot.h\"\n#include \"src/SparseCore/SparseRedux.h\"\n#include \"src/SparseCore/SparseView.h\"\n#include \"src/SparseCore/SparseDiagonalProduct.h\"\n#include \"src/SparseCore/ConservativeSparseSparseProduct.h\"\n#include \"src/SparseCore/SparseSparseProductWithPruning.h\"\n#include \"src/SparseCore/SparseProduct.h\"\n#include \"src/SparseCore/SparseDenseProduct.h\"\n#include \"src/SparseCore/SparseSelfAdjointView.h\"\n#include \"src/SparseCore/SparseTriangularView.h\"\n#include \"src/SparseCore/TriangularSolver.h\"\n#include \"src/SparseCore/SparsePermutation.h\"\n#include \"src/SparseCore/SparseFuzzy.h\"\n#include \"src/SparseCore/SparseSolverBase.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_SPARSECORE_MODULE_H\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/SparseLU",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSELU_MODULE_H\n#define EIGEN_SPARSELU_MODULE_H\n\n#include \"SparseCore\"\n\n/** \n  * \\defgroup SparseLU_Module SparseLU module\n  * This module defines a supernodal factorization of general sparse matrices.\n  * The code is fully optimized for supernode-panel updates with specialized kernels.\n  * Please, see the documentation of the SparseLU class for more details.\n  */\n\n// Ordering interface\n#include \"OrderingMethods\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n#include \"src/SparseLU/SparseLU_gemm_kernel.h\"\n\n#include \"src/SparseLU/SparseLU_Structs.h\"\n#include \"src/SparseLU/SparseLU_SupernodalMatrix.h\"\n#include \"src/SparseLU/SparseLUImpl.h\"\n#include \"src/SparseCore/SparseColEtree.h\"\n#include \"src/SparseLU/SparseLU_Memory.h\"\n#include \"src/SparseLU/SparseLU_heap_relax_snode.h\"\n#include \"src/SparseLU/SparseLU_relax_snode.h\"\n#include \"src/SparseLU/SparseLU_pivotL.h\"\n#include \"src/SparseLU/SparseLU_panel_dfs.h\"\n#include \"src/SparseLU/SparseLU_kernel_bmod.h\"\n#include \"src/SparseLU/SparseLU_panel_bmod.h\"\n#include \"src/SparseLU/SparseLU_column_dfs.h\"\n#include \"src/SparseLU/SparseLU_column_bmod.h\"\n#include \"src/SparseLU/SparseLU_copy_to_ucol.h\"\n#include \"src/SparseLU/SparseLU_pruneL.h\"\n#include \"src/SparseLU/SparseLU_Utils.h\"\n#include \"src/SparseLU/SparseLU.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_SPARSELU_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/SparseQR",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEQR_MODULE_H\n#define EIGEN_SPARSEQR_MODULE_H\n\n#include \"SparseCore\"\n#include \"OrderingMethods\"\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \\defgroup SparseQR_Module SparseQR module\n  * \\brief Provides QR decomposition for sparse matrices\n  * \n  * This module provides a simplicial version of the left-looking Sparse QR decomposition. \n  * The columns of the input matrix should be reordered to limit the fill-in during the \n  * decomposition. Built-in methods (COLAMD, AMD) or external  methods (METIS) can be used to this end.\n  * See the \\link OrderingMethods_Module OrderingMethods\\endlink module for the list \n  * of built-in and external ordering methods.\n  * \n  * \\code\n  * #include <Eigen/SparseQR>\n  * \\endcode\n  * \n  * \n  */\n\n#include \"src/SparseCore/SparseColEtree.h\"\n#include \"src/SparseQR/SparseQR.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/StdDeque",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Hauke Heibel <hauke.heibel@googlemail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_STDDEQUE_MODULE_H\n#define EIGEN_STDDEQUE_MODULE_H\n\n#include \"Core\"\n#include <deque>\n\n#if EIGEN_COMP_MSVC && EIGEN_OS_WIN64 && (EIGEN_MAX_STATIC_ALIGN_BYTES<=16) /* MSVC auto aligns up to 16 bytes in 64 bit builds */\n\n#define EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(...)\n\n#else\n\n#include \"src/StlSupport/StdDeque.h\"\n\n#endif\n\n#endif // EIGEN_STDDEQUE_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/StdList",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Hauke Heibel <hauke.heibel@googlemail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_STDLIST_MODULE_H\n#define EIGEN_STDLIST_MODULE_H\n\n#include \"Core\"\n#include <list>\n\n#if EIGEN_COMP_MSVC && EIGEN_OS_WIN64 && (EIGEN_MAX_STATIC_ALIGN_BYTES<=16) /* MSVC auto aligns up to 16 bytes in 64 bit builds */\n\n#define EIGEN_DEFINE_STL_LIST_SPECIALIZATION(...)\n\n#else\n\n#include \"src/StlSupport/StdList.h\"\n\n#endif\n\n#endif // EIGEN_STDLIST_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/StdVector",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Hauke Heibel <hauke.heibel@googlemail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_STDVECTOR_MODULE_H\n#define EIGEN_STDVECTOR_MODULE_H\n\n#include \"Core\"\n#include <vector>\n\n#if EIGEN_COMP_MSVC && EIGEN_OS_WIN64 && (EIGEN_MAX_STATIC_ALIGN_BYTES<=16) /* MSVC auto aligns up to 16 bytes in 64 bit builds */\n\n#define EIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(...)\n\n#else\n\n#include \"src/StlSupport/StdVector.h\"\n\n#endif\n\n#endif // EIGEN_STDVECTOR_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/SuperLUSupport",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SUPERLUSUPPORT_MODULE_H\n#define EIGEN_SUPERLUSUPPORT_MODULE_H\n\n#include \"SparseCore\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n#ifdef EMPTY\n#define EIGEN_EMPTY_WAS_ALREADY_DEFINED\n#endif\n\ntypedef int int_t;\n#include <slu_Cnames.h>\n#include <supermatrix.h>\n#include <slu_util.h>\n\n// slu_util.h defines a preprocessor token named EMPTY which is really polluting,\n// so we remove it in favor of a SUPERLU_EMPTY token.\n// If EMPTY was already defined then we don't undef it.\n\n#if defined(EIGEN_EMPTY_WAS_ALREADY_DEFINED)\n# undef EIGEN_EMPTY_WAS_ALREADY_DEFINED\n#elif defined(EMPTY)\n# undef EMPTY\n#endif\n\n#define SUPERLU_EMPTY (-1)\n\nnamespace Eigen { struct SluMatrix; }\n\n/** \\ingroup Support_modules\n  * \\defgroup SuperLUSupport_Module SuperLUSupport module\n  *\n  * This module provides an interface to the <a href=\"http://crd-legacy.lbl.gov/~xiaoye/SuperLU/\">SuperLU</a> library.\n  * It provides the following factorization class:\n  * - class SuperLU: a supernodal sequential LU factorization.\n  * - class SuperILU: a supernodal sequential incomplete LU factorization (to be used as a preconditioner for iterative methods).\n  *\n  * \\warning This wrapper requires at least versions 4.0 of SuperLU. The 3.x versions are not supported.\n  *\n  * \\warning When including this module, you have to use SUPERLU_EMPTY instead of EMPTY which is no longer defined because it is too polluting.\n  *\n  * \\code\n  * #include <Eigen/SuperLUSupport>\n  * \\endcode\n  *\n  * In order to use this module, the superlu headers must be accessible from the include paths, and your binary must be linked to the superlu library and its dependencies.\n  * The dependencies depend on how superlu has been compiled.\n  * For a cmake based project, you can use our FindSuperLU.cmake module to help you in this task.\n  *\n  */\n\n#include \"src/SuperLUSupport/SuperLUSupport.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_SUPERLUSUPPORT_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/UmfPackSupport",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_UMFPACKSUPPORT_MODULE_H\n#define EIGEN_UMFPACKSUPPORT_MODULE_H\n\n#include \"SparseCore\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\nextern \"C\" {\n#include <umfpack.h>\n}\n\n/** \\ingroup Support_modules\n  * \\defgroup UmfPackSupport_Module UmfPackSupport module\n  *\n  * This module provides an interface to the UmfPack library which is part of the <a href=\"http://www.suitesparse.com\">suitesparse</a> package.\n  * It provides the following factorization class:\n  * - class UmfPackLU: a multifrontal sequential LU factorization.\n  *\n  * \\code\n  * #include <Eigen/UmfPackSupport>\n  * \\endcode\n  *\n  * In order to use this module, the umfpack headers must be accessible from the include paths, and your binary must be linked to the umfpack library and its dependencies.\n  * The dependencies depend on how umfpack has been compiled.\n  * For a cmake based project, you can use our FindUmfPack.cmake module to help you in this task.\n  *\n  */\n\n#include \"src/UmfPackSupport/UmfPackSupport.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_UMFPACKSUPPORT_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Cholesky/LDLT.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Keir Mierle <mierle@gmail.com>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2011 Timothy E. Holy <tim.holy@gmail.com >\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_LDLT_H\n#define EIGEN_LDLT_H\n\nnamespace Eigen {\n\nnamespace internal {\n  template<typename MatrixType_, int UpLo_> struct traits<LDLT<MatrixType_, UpLo_> >\n   : traits<MatrixType_>\n  {\n    typedef MatrixXpr XprKind;\n    typedef SolverStorage StorageKind;\n    typedef int StorageIndex;\n    enum { Flags = 0 };\n  };\n\n  template<typename MatrixType, int UpLo> struct LDLT_Traits;\n\n  // PositiveSemiDef means positive semi-definite and non-zero; same for NegativeSemiDef\n  enum SignMatrix { PositiveSemiDef, NegativeSemiDef, ZeroSign, Indefinite };\n}\n\n/** \\ingroup Cholesky_Module\n  *\n  * \\class LDLT\n  *\n  * \\brief Robust Cholesky decomposition of a matrix with pivoting\n  *\n  * \\tparam MatrixType_ the type of the matrix of which to compute the LDL^T Cholesky decomposition\n  * \\tparam UpLo_ the triangular part that will be used for the decomposition: Lower (default) or Upper.\n  *             The other triangular part won't be read.\n  *\n  * Perform a robust Cholesky decomposition of a positive semidefinite or negative semidefinite\n  * matrix \\f$ A \\f$ such that \\f$ A =  P^TLDL^*P \\f$, where P is a permutation matrix, L\n  * is lower triangular with a unit diagonal and D is a diagonal matrix.\n  *\n  * The decomposition uses pivoting to ensure stability, so that D will have\n  * zeros in the bottom right rank(A) - n submatrix. Avoiding the square root\n  * on D also stabilizes the computation.\n  *\n  * Remember that Cholesky decompositions are not rank-revealing. Also, do not use a Cholesky\n  * decomposition to determine whether a system of equations has a solution.\n  *\n  * This class supports the \\link InplaceDecomposition inplace decomposition \\endlink mechanism.\n  *\n  * \\sa MatrixBase::ldlt(), SelfAdjointView::ldlt(), class LLT\n  */\ntemplate<typename MatrixType_, int UpLo_> class LDLT\n        : public SolverBase<LDLT<MatrixType_, UpLo_> >\n{\n  public:\n    typedef MatrixType_ MatrixType;\n    typedef SolverBase<LDLT> Base;\n    friend class SolverBase<LDLT>;\n\n    EIGEN_GENERIC_PUBLIC_INTERFACE(LDLT)\n    enum {\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime,\n      UpLo = UpLo_\n    };\n    typedef Matrix<Scalar, RowsAtCompileTime, 1, 0, MaxRowsAtCompileTime, 1> TmpMatrixType;\n\n    typedef Transpositions<RowsAtCompileTime, MaxRowsAtCompileTime> TranspositionType;\n    typedef PermutationMatrix<RowsAtCompileTime, MaxRowsAtCompileTime> PermutationType;\n\n    typedef internal::LDLT_Traits<MatrixType,UpLo> Traits;\n\n    /** \\brief Default Constructor.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via LDLT::compute(const MatrixType&).\n      */\n    LDLT()\n      : m_matrix(),\n        m_transpositions(),\n        m_sign(internal::ZeroSign),\n        m_isInitialized(false)\n    {}\n\n    /** \\brief Default Constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem \\a size.\n      * \\sa LDLT()\n      */\n    explicit LDLT(Index size)\n      : m_matrix(size, size),\n        m_transpositions(size),\n        m_temporary(size),\n        m_sign(internal::ZeroSign),\n        m_isInitialized(false)\n    {}\n\n    /** \\brief Constructor with decomposition\n      *\n      * This calculates the decomposition for the input \\a matrix.\n      *\n      * \\sa LDLT(Index size)\n      */\n    template<typename InputType>\n    explicit LDLT(const EigenBase<InputType>& matrix)\n      : m_matrix(matrix.rows(), matrix.cols()),\n        m_transpositions(matrix.rows()),\n        m_temporary(matrix.rows()),\n        m_sign(internal::ZeroSign),\n        m_isInitialized(false)\n    {\n      compute(matrix.derived());\n    }\n\n    /** \\brief Constructs a LDLT factorization from a given matrix\n      *\n      * This overloaded constructor is provided for \\link InplaceDecomposition inplace decomposition \\endlink when \\c MatrixType is a Eigen::Ref.\n      *\n      * \\sa LDLT(const EigenBase&)\n      */\n    template<typename InputType>\n    explicit LDLT(EigenBase<InputType>& matrix)\n      : m_matrix(matrix.derived()),\n        m_transpositions(matrix.rows()),\n        m_temporary(matrix.rows()),\n        m_sign(internal::ZeroSign),\n        m_isInitialized(false)\n    {\n      compute(matrix.derived());\n    }\n\n    /** Clear any existing decomposition\n     * \\sa rankUpdate(w,sigma)\n     */\n    void setZero()\n    {\n      m_isInitialized = false;\n    }\n\n    /** \\returns a view of the upper triangular matrix U */\n    inline typename Traits::MatrixU matrixU() const\n    {\n      eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n      return Traits::getU(m_matrix);\n    }\n\n    /** \\returns a view of the lower triangular matrix L */\n    inline typename Traits::MatrixL matrixL() const\n    {\n      eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n      return Traits::getL(m_matrix);\n    }\n\n    /** \\returns the permutation matrix P as a transposition sequence.\n      */\n    inline const TranspositionType& transpositionsP() const\n    {\n      eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n      return m_transpositions;\n    }\n\n    /** \\returns the coefficients of the diagonal matrix D */\n    inline Diagonal<const MatrixType> vectorD() const\n    {\n      eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n      return m_matrix.diagonal();\n    }\n\n    /** \\returns true if the matrix is positive (semidefinite) */\n    inline bool isPositive() const\n    {\n      eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n      return m_sign == internal::PositiveSemiDef || m_sign == internal::ZeroSign;\n    }\n\n    /** \\returns true if the matrix is negative (semidefinite) */\n    inline bool isNegative(void) const\n    {\n      eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n      return m_sign == internal::NegativeSemiDef || m_sign == internal::ZeroSign;\n    }\n\n    #ifdef EIGEN_PARSED_BY_DOXYGEN\n    /** \\returns a solution x of \\f$ A x = b \\f$ using the current decomposition of A.\n      *\n      * This function also supports in-place solves using the syntax <tt>x = decompositionObject.solve(x)</tt> .\n      *\n      * \\note_about_checking_solutions\n      *\n      * More precisely, this method solves \\f$ A x = b \\f$ using the decomposition \\f$ A = P^T L D L^* P \\f$\n      * by solving the systems \\f$ P^T y_1 = b \\f$, \\f$ L y_2 = y_1 \\f$, \\f$ D y_3 = y_2 \\f$,\n      * \\f$ L^* y_4 = y_3 \\f$ and \\f$ P x = y_4 \\f$ in succession. If the matrix \\f$ A \\f$ is singular, then\n      * \\f$ D \\f$ will also be singular (all the other matrices are invertible). In that case, the\n      * least-square solution of \\f$ D y_3 = y_2 \\f$ is computed. This does not mean that this function\n      * computes the least-square solution of \\f$ A x = b \\f$ if \\f$ A \\f$ is singular.\n      *\n      * \\sa MatrixBase::ldlt(), SelfAdjointView::ldlt()\n      */\n    template<typename Rhs>\n    inline const Solve<LDLT, Rhs>\n    solve(const MatrixBase<Rhs>& b) const;\n    #endif\n\n    template<typename Derived>\n    bool solveInPlace(MatrixBase<Derived> &bAndX) const;\n\n    template<typename InputType>\n    LDLT& compute(const EigenBase<InputType>& matrix);\n\n    /** \\returns an estimate of the reciprocal condition number of the matrix of\n     *  which \\c *this is the LDLT decomposition.\n     */\n    RealScalar rcond() const\n    {\n      eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n      return internal::rcond_estimate_helper(m_l1_norm, *this);\n    }\n\n    template <typename Derived>\n    LDLT& rankUpdate(const MatrixBase<Derived>& w, const RealScalar& alpha=1);\n\n    /** \\returns the internal LDLT decomposition matrix\n      *\n      * TODO: document the storage layout\n      */\n    inline const MatrixType& matrixLDLT() const\n    {\n      eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n      return m_matrix;\n    }\n\n    MatrixType reconstructedMatrix() const;\n\n    /** \\returns the adjoint of \\c *this, that is, a const reference to the decomposition itself as the underlying matrix is self-adjoint.\n      *\n      * This method is provided for compatibility with other matrix decompositions, thus enabling generic code such as:\n      * \\code x = decomposition.adjoint().solve(b) \\endcode\n      */\n    const LDLT& adjoint() const { return *this; };\n\n    EIGEN_DEVICE_FUNC inline EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_matrix.rows(); }\n    EIGEN_DEVICE_FUNC inline EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_matrix.cols(); }\n\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the factorization failed because of a zero pivot.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n      return m_info;\n    }\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<typename RhsType, typename DstType>\n    void _solve_impl(const RhsType &rhs, DstType &dst) const;\n\n    template<bool Conjugate, typename RhsType, typename DstType>\n    void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const;\n    #endif\n\n  protected:\n\n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n    }\n\n    /** \\internal\n      * Used to compute and store the Cholesky decomposition A = L D L^* = U^* D U.\n      * The strict upper part is used during the decomposition, the strict lower\n      * part correspond to the coefficients of L (its diagonal is equal to 1 and\n      * is not stored), and the diagonal entries correspond to D.\n      */\n    MatrixType m_matrix;\n    RealScalar m_l1_norm;\n    TranspositionType m_transpositions;\n    TmpMatrixType m_temporary;\n    internal::SignMatrix m_sign;\n    bool m_isInitialized;\n    ComputationInfo m_info;\n};\n\nnamespace internal {\n\ntemplate<int UpLo> struct ldlt_inplace;\n\ntemplate<> struct ldlt_inplace<Lower>\n{\n  template<typename MatrixType, typename TranspositionType, typename Workspace>\n  static bool unblocked(MatrixType& mat, TranspositionType& transpositions, Workspace& temp, SignMatrix& sign)\n  {\n    using std::abs;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef typename TranspositionType::StorageIndex IndexType;\n    eigen_assert(mat.rows()==mat.cols());\n    const Index size = mat.rows();\n    bool found_zero_pivot = false;\n    bool ret = true;\n\n    if (size <= 1)\n    {\n      transpositions.setIdentity();\n      if(size==0) sign = ZeroSign;\n      else if (numext::real(mat.coeff(0,0)) > static_cast<RealScalar>(0) ) sign = PositiveSemiDef;\n      else if (numext::real(mat.coeff(0,0)) < static_cast<RealScalar>(0)) sign = NegativeSemiDef;\n      else sign = ZeroSign;\n      return true;\n    }\n\n    for (Index k = 0; k < size; ++k)\n    {\n      // Find largest diagonal element\n      Index index_of_biggest_in_corner;\n      mat.diagonal().tail(size-k).cwiseAbs().maxCoeff(&index_of_biggest_in_corner);\n      index_of_biggest_in_corner += k;\n\n      transpositions.coeffRef(k) = IndexType(index_of_biggest_in_corner);\n      if(k != index_of_biggest_in_corner)\n      {\n        // apply the transposition while taking care to consider only\n        // the lower triangular part\n        Index s = size-index_of_biggest_in_corner-1; // trailing size after the biggest element\n        mat.row(k).head(k).swap(mat.row(index_of_biggest_in_corner).head(k));\n        mat.col(k).tail(s).swap(mat.col(index_of_biggest_in_corner).tail(s));\n        std::swap(mat.coeffRef(k,k),mat.coeffRef(index_of_biggest_in_corner,index_of_biggest_in_corner));\n        for(Index i=k+1;i<index_of_biggest_in_corner;++i)\n        {\n          Scalar tmp = mat.coeffRef(i,k);\n          mat.coeffRef(i,k) = numext::conj(mat.coeffRef(index_of_biggest_in_corner,i));\n          mat.coeffRef(index_of_biggest_in_corner,i) = numext::conj(tmp);\n        }\n        if(NumTraits<Scalar>::IsComplex)\n          mat.coeffRef(index_of_biggest_in_corner,k) = numext::conj(mat.coeff(index_of_biggest_in_corner,k));\n      }\n\n      // partition the matrix:\n      //       A00 |  -  |  -\n      // lu  = A10 | A11 |  -\n      //       A20 | A21 | A22\n      Index rs = size - k - 1;\n      Block<MatrixType,Dynamic,1> A21(mat,k+1,k,rs,1);\n      Block<MatrixType,1,Dynamic> A10(mat,k,0,1,k);\n      Block<MatrixType,Dynamic,Dynamic> A20(mat,k+1,0,rs,k);\n\n      if(k>0)\n      {\n        temp.head(k) = mat.diagonal().real().head(k).asDiagonal() * A10.adjoint();\n        mat.coeffRef(k,k) -= (A10 * temp.head(k)).value();\n        if(rs>0)\n          A21.noalias() -= A20 * temp.head(k);\n      }\n\n      // In some previous versions of Eigen (e.g., 3.2.1), the scaling was omitted if the pivot\n      // was smaller than the cutoff value. However, since LDLT is not rank-revealing\n      // we should only make sure that we do not introduce INF or NaN values.\n      // Remark that LAPACK also uses 0 as the cutoff value.\n      RealScalar realAkk = numext::real(mat.coeffRef(k,k));\n      bool pivot_is_valid = (abs(realAkk) > RealScalar(0));\n\n      if(k==0 && !pivot_is_valid)\n      {\n        // The entire diagonal is zero, there is nothing more to do\n        // except filling the transpositions, and checking whether the matrix is zero.\n        sign = ZeroSign;\n        for(Index j = 0; j<size; ++j)\n        {\n          transpositions.coeffRef(j) = IndexType(j);\n          ret = ret && (mat.col(j).tail(size-j-1).array()==Scalar(0)).all();\n        }\n        return ret;\n      }\n\n      if((rs>0) && pivot_is_valid)\n        A21 /= realAkk;\n      else if(rs>0)\n        ret = ret && (A21.array()==Scalar(0)).all();\n\n      if(found_zero_pivot && pivot_is_valid) ret = false; // factorization failed\n      else if(!pivot_is_valid) found_zero_pivot = true;\n\n      if (sign == PositiveSemiDef) {\n        if (realAkk < static_cast<RealScalar>(0)) sign = Indefinite;\n      } else if (sign == NegativeSemiDef) {\n        if (realAkk > static_cast<RealScalar>(0)) sign = Indefinite;\n      } else if (sign == ZeroSign) {\n        if (realAkk > static_cast<RealScalar>(0)) sign = PositiveSemiDef;\n        else if (realAkk < static_cast<RealScalar>(0)) sign = NegativeSemiDef;\n      }\n    }\n\n    return ret;\n  }\n\n  // Reference for the algorithm: Davis and Hager, \"Multiple Rank\n  // Modifications of a Sparse Cholesky Factorization\" (Algorithm 1)\n  // Trivial rearrangements of their computations (Timothy E. Holy)\n  // allow their algorithm to work for rank-1 updates even if the\n  // original matrix is not of full rank.\n  // Here only rank-1 updates are implemented, to reduce the\n  // requirement for intermediate storage and improve accuracy\n  template<typename MatrixType, typename WDerived>\n  static bool updateInPlace(MatrixType& mat, MatrixBase<WDerived>& w, const typename MatrixType::RealScalar& sigma=1)\n  {\n    using numext::isfinite;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n\n    const Index size = mat.rows();\n    eigen_assert(mat.cols() == size && w.size()==size);\n\n    RealScalar alpha = 1;\n\n    // Apply the update\n    for (Index j = 0; j < size; j++)\n    {\n      // Check for termination due to an original decomposition of low-rank\n      if (!(isfinite)(alpha))\n        break;\n\n      // Update the diagonal terms\n      RealScalar dj = numext::real(mat.coeff(j,j));\n      Scalar wj = w.coeff(j);\n      RealScalar swj2 = sigma*numext::abs2(wj);\n      RealScalar gamma = dj*alpha + swj2;\n\n      mat.coeffRef(j,j) += swj2/alpha;\n      alpha += swj2/dj;\n\n\n      // Update the terms of L\n      Index rs = size-j-1;\n      w.tail(rs) -= wj * mat.col(j).tail(rs);\n      if(gamma != 0)\n        mat.col(j).tail(rs) += (sigma*numext::conj(wj)/gamma)*w.tail(rs);\n    }\n    return true;\n  }\n\n  template<typename MatrixType, typename TranspositionType, typename Workspace, typename WType>\n  static bool update(MatrixType& mat, const TranspositionType& transpositions, Workspace& tmp, const WType& w, const typename MatrixType::RealScalar& sigma=1)\n  {\n    // Apply the permutation to the input w\n    tmp = transpositions * w;\n\n    return ldlt_inplace<Lower>::updateInPlace(mat,tmp,sigma);\n  }\n};\n\ntemplate<> struct ldlt_inplace<Upper>\n{\n  template<typename MatrixType, typename TranspositionType, typename Workspace>\n  static EIGEN_STRONG_INLINE bool unblocked(MatrixType& mat, TranspositionType& transpositions, Workspace& temp, SignMatrix& sign)\n  {\n    Transpose<MatrixType> matt(mat);\n    return ldlt_inplace<Lower>::unblocked(matt, transpositions, temp, sign);\n  }\n\n  template<typename MatrixType, typename TranspositionType, typename Workspace, typename WType>\n  static EIGEN_STRONG_INLINE bool update(MatrixType& mat, TranspositionType& transpositions, Workspace& tmp, WType& w, const typename MatrixType::RealScalar& sigma=1)\n  {\n    Transpose<MatrixType> matt(mat);\n    return ldlt_inplace<Lower>::update(matt, transpositions, tmp, w.conjugate(), sigma);\n  }\n};\n\ntemplate<typename MatrixType> struct LDLT_Traits<MatrixType,Lower>\n{\n  typedef const TriangularView<const MatrixType, UnitLower> MatrixL;\n  typedef const TriangularView<const typename MatrixType::AdjointReturnType, UnitUpper> MatrixU;\n  static inline MatrixL getL(const MatrixType& m) { return MatrixL(m); }\n  static inline MatrixU getU(const MatrixType& m) { return MatrixU(m.adjoint()); }\n};\n\ntemplate<typename MatrixType> struct LDLT_Traits<MatrixType,Upper>\n{\n  typedef const TriangularView<const typename MatrixType::AdjointReturnType, UnitLower> MatrixL;\n  typedef const TriangularView<const MatrixType, UnitUpper> MatrixU;\n  static inline MatrixL getL(const MatrixType& m) { return MatrixL(m.adjoint()); }\n  static inline MatrixU getU(const MatrixType& m) { return MatrixU(m); }\n};\n\n} // end namespace internal\n\n/** Compute / recompute the LDLT decomposition A = L D L^* = U^* D U of \\a matrix\n  */\ntemplate<typename MatrixType, int UpLo_>\ntemplate<typename InputType>\nLDLT<MatrixType,UpLo_>& LDLT<MatrixType,UpLo_>::compute(const EigenBase<InputType>& a)\n{\n  check_template_parameters();\n\n  eigen_assert(a.rows()==a.cols());\n  const Index size = a.rows();\n\n  m_matrix = a.derived();\n\n  // Compute matrix L1 norm = max abs column sum.\n  m_l1_norm = RealScalar(0);\n  // TODO move this code to SelfAdjointView\n  for (Index col = 0; col < size; ++col) {\n    RealScalar abs_col_sum;\n    if (UpLo_ == Lower)\n      abs_col_sum = m_matrix.col(col).tail(size - col).template lpNorm<1>() + m_matrix.row(col).head(col).template lpNorm<1>();\n    else\n      abs_col_sum = m_matrix.col(col).head(col).template lpNorm<1>() + m_matrix.row(col).tail(size - col).template lpNorm<1>();\n    if (abs_col_sum > m_l1_norm)\n      m_l1_norm = abs_col_sum;\n  }\n\n  m_transpositions.resize(size);\n  m_isInitialized = false;\n  m_temporary.resize(size);\n  m_sign = internal::ZeroSign;\n\n  m_info = internal::ldlt_inplace<UpLo>::unblocked(m_matrix, m_transpositions, m_temporary, m_sign) ? Success : NumericalIssue;\n\n  m_isInitialized = true;\n  return *this;\n}\n\n/** Update the LDLT decomposition:  given A = L D L^T, efficiently compute the decomposition of A + sigma w w^T.\n * \\param w a vector to be incorporated into the decomposition.\n * \\param sigma a scalar, +1 for updates and -1 for \"downdates,\" which correspond to removing previously-added column vectors. Optional; default value is +1.\n * \\sa setZero()\n  */\ntemplate<typename MatrixType, int UpLo_>\ntemplate<typename Derived>\nLDLT<MatrixType,UpLo_>& LDLT<MatrixType,UpLo_>::rankUpdate(const MatrixBase<Derived>& w, const typename LDLT<MatrixType,UpLo_>::RealScalar& sigma)\n{\n  typedef typename TranspositionType::StorageIndex IndexType;\n  const Index size = w.rows();\n  if (m_isInitialized)\n  {\n    eigen_assert(m_matrix.rows()==size);\n  }\n  else\n  {\n    m_matrix.resize(size,size);\n    m_matrix.setZero();\n    m_transpositions.resize(size);\n    for (Index i = 0; i < size; i++)\n      m_transpositions.coeffRef(i) = IndexType(i);\n    m_temporary.resize(size);\n    m_sign = sigma>=0 ? internal::PositiveSemiDef : internal::NegativeSemiDef;\n    m_isInitialized = true;\n  }\n\n  internal::ldlt_inplace<UpLo>::update(m_matrix, m_transpositions, m_temporary, w, sigma);\n\n  return *this;\n}\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename MatrixType_, int UpLo_>\ntemplate<typename RhsType, typename DstType>\nvoid LDLT<MatrixType_,UpLo_>::_solve_impl(const RhsType &rhs, DstType &dst) const\n{\n  _solve_impl_transposed<true>(rhs, dst);\n}\n\ntemplate<typename MatrixType_,int UpLo_>\ntemplate<bool Conjugate, typename RhsType, typename DstType>\nvoid LDLT<MatrixType_,UpLo_>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const\n{\n  // dst = P b\n  dst = m_transpositions * rhs;\n\n  // dst = L^-1 (P b)\n  // dst = L^-*T (P b)\n  matrixL().template conjugateIf<!Conjugate>().solveInPlace(dst);\n\n  // dst = D^-* (L^-1 P b)\n  // dst = D^-1 (L^-*T P b)\n  // more precisely, use pseudo-inverse of D (see bug 241)\n  using std::abs;\n  const typename Diagonal<const MatrixType>::RealReturnType vecD(vectorD());\n  // In some previous versions, tolerance was set to the max of 1/highest (or rather numeric_limits::min())\n  // and the maximal diagonal entry * epsilon as motivated by LAPACK's xGELSS:\n  // RealScalar tolerance = numext::maxi(vecD.array().abs().maxCoeff() * NumTraits<RealScalar>::epsilon(),RealScalar(1) / NumTraits<RealScalar>::highest());\n  // However, LDLT is not rank revealing, and so adjusting the tolerance wrt to the highest\n  // diagonal element is not well justified and leads to numerical issues in some cases.\n  // Moreover, Lapack's xSYTRS routines use 0 for the tolerance.\n  // Using numeric_limits::min() gives us more robustness to denormals.\n  RealScalar tolerance = (std::numeric_limits<RealScalar>::min)();\n  for (Index i = 0; i < vecD.size(); ++i)\n  {\n    if(abs(vecD(i)) > tolerance)\n      dst.row(i) /= vecD(i);\n    else\n      dst.row(i).setZero();\n  }\n\n  // dst = L^-* (D^-* L^-1 P b)\n  // dst = L^-T (D^-1 L^-*T P b)\n  matrixL().transpose().template conjugateIf<Conjugate>().solveInPlace(dst);\n\n  // dst = P^T (L^-* D^-* L^-1 P b) = A^-1 b\n  // dst = P^-T (L^-T D^-1 L^-*T P b) = A^-1 b\n  dst = m_transpositions.transpose() * dst;\n}\n#endif\n\n/** \\internal use x = ldlt_object.solve(x);\n  *\n  * This is the \\em in-place version of solve().\n  *\n  * \\param bAndX represents both the right-hand side matrix b and result x.\n  *\n  * \\returns true always! If you need to check for existence of solutions, use another decomposition like LU, QR, or SVD.\n  *\n  * This version avoids a copy when the right hand side matrix b is not\n  * needed anymore.\n  *\n  * \\sa LDLT::solve(), MatrixBase::ldlt()\n  */\ntemplate<typename MatrixType,int UpLo_>\ntemplate<typename Derived>\nbool LDLT<MatrixType,UpLo_>::solveInPlace(MatrixBase<Derived> &bAndX) const\n{\n  eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n  eigen_assert(m_matrix.rows() == bAndX.rows());\n\n  bAndX = this->solve(bAndX);\n\n  return true;\n}\n\n/** \\returns the matrix represented by the decomposition,\n * i.e., it returns the product: P^T L D L^* P.\n * This function is provided for debug purpose. */\ntemplate<typename MatrixType, int UpLo_>\nMatrixType LDLT<MatrixType,UpLo_>::reconstructedMatrix() const\n{\n  eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n  const Index size = m_matrix.rows();\n  MatrixType res(size,size);\n\n  // P\n  res.setIdentity();\n  res = transpositionsP() * res;\n  // L^* P\n  res = matrixU() * res;\n  // D(L^*P)\n  res = vectorD().real().asDiagonal() * res;\n  // L(DL^*P)\n  res = matrixL() * res;\n  // P^T (LDL^*P)\n  res = transpositionsP().transpose() * res;\n\n  return res;\n}\n\n/** \\cholesky_module\n  * \\returns the Cholesky decomposition with full pivoting without square root of \\c *this\n  * \\sa MatrixBase::ldlt()\n  */\ntemplate<typename MatrixType, unsigned int UpLo>\ninline const LDLT<typename SelfAdjointView<MatrixType, UpLo>::PlainObject, UpLo>\nSelfAdjointView<MatrixType, UpLo>::ldlt() const\n{\n  return LDLT<PlainObject,UpLo>(m_matrix);\n}\n\n/** \\cholesky_module\n  * \\returns the Cholesky decomposition with full pivoting without square root of \\c *this\n  * \\sa SelfAdjointView::ldlt()\n  */\ntemplate<typename Derived>\ninline const LDLT<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::ldlt() const\n{\n  return LDLT<PlainObject>(derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_LDLT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Cholesky/LLT.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_LLT_H\n#define EIGEN_LLT_H\n\nnamespace Eigen {\n\nnamespace internal{\n\ntemplate<typename MatrixType_, int UpLo_> struct traits<LLT<MatrixType_, UpLo_> >\n : traits<MatrixType_>\n{\n  typedef MatrixXpr XprKind;\n  typedef SolverStorage StorageKind;\n  typedef int StorageIndex;\n  enum { Flags = 0 };\n};\n\ntemplate<typename MatrixType, int UpLo> struct LLT_Traits;\n}\n\n/** \\ingroup Cholesky_Module\n  *\n  * \\class LLT\n  *\n  * \\brief Standard Cholesky decomposition (LL^T) of a matrix and associated features\n  *\n  * \\tparam MatrixType_ the type of the matrix of which we are computing the LL^T Cholesky decomposition\n  * \\tparam UpLo_ the triangular part that will be used for the decomposition: Lower (default) or Upper.\n  *               The other triangular part won't be read.\n  *\n  * This class performs a LL^T Cholesky decomposition of a symmetric, positive definite\n  * matrix A such that A = LL^* = U^*U, where L is lower triangular.\n  *\n  * While the Cholesky decomposition is particularly useful to solve selfadjoint problems like  D^*D x = b,\n  * for that purpose, we recommend the Cholesky decomposition without square root which is more stable\n  * and even faster. Nevertheless, this standard Cholesky decomposition remains useful in many other\n  * situations like generalised eigen problems with hermitian matrices.\n  *\n  * Remember that Cholesky decompositions are not rank-revealing. This LLT decomposition is only stable on positive definite matrices,\n  * use LDLT instead for the semidefinite case. Also, do not use a Cholesky decomposition to determine whether a system of equations\n  * has a solution.\n  *\n  * Example: \\include LLT_example.cpp\n  * Output: \\verbinclude LLT_example.out\n  *\n  * \\b Performance: for best performance, it is recommended to use a column-major storage format\n  * with the Lower triangular part (the default), or, equivalently, a row-major storage format\n  * with the Upper triangular part. Otherwise, you might get a 20% slowdown for the full factorization\n  * step, and rank-updates can be up to 3 times slower.\n  *\n  * This class supports the \\link InplaceDecomposition inplace decomposition \\endlink mechanism.\n  *\n  * Note that during the decomposition, only the lower (or upper, as defined by UpLo_) triangular part of A is considered.\n  * Therefore, the strict lower part does not have to store correct values.\n  *\n  * \\sa MatrixBase::llt(), SelfAdjointView::llt(), class LDLT\n  */\ntemplate<typename MatrixType_, int UpLo_> class LLT\n        : public SolverBase<LLT<MatrixType_, UpLo_> >\n{\n  public:\n    typedef MatrixType_ MatrixType;\n    typedef SolverBase<LLT> Base;\n    friend class SolverBase<LLT>;\n\n    EIGEN_GENERIC_PUBLIC_INTERFACE(LLT)\n    enum {\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n\n    enum {\n      PacketSize = internal::packet_traits<Scalar>::size,\n      AlignmentMask = int(PacketSize)-1,\n      UpLo = UpLo_\n    };\n\n    typedef internal::LLT_Traits<MatrixType,UpLo> Traits;\n\n    /**\n      * \\brief Default Constructor.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via LLT::compute(const MatrixType&).\n      */\n    LLT() : m_matrix(), m_isInitialized(false) {}\n\n    /** \\brief Default Constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem \\a size.\n      * \\sa LLT()\n      */\n    explicit LLT(Index size) : m_matrix(size, size),\n                    m_isInitialized(false) {}\n\n    template<typename InputType>\n    explicit LLT(const EigenBase<InputType>& matrix)\n      : m_matrix(matrix.rows(), matrix.cols()),\n        m_isInitialized(false)\n    {\n      compute(matrix.derived());\n    }\n\n    /** \\brief Constructs a LLT factorization from a given matrix\n      *\n      * This overloaded constructor is provided for \\link InplaceDecomposition inplace decomposition \\endlink when\n      * \\c MatrixType is a Eigen::Ref.\n      *\n      * \\sa LLT(const EigenBase&)\n      */\n    template<typename InputType>\n    explicit LLT(EigenBase<InputType>& matrix)\n      : m_matrix(matrix.derived()),\n        m_isInitialized(false)\n    {\n      compute(matrix.derived());\n    }\n\n    /** \\returns a view of the upper triangular matrix U */\n    inline typename Traits::MatrixU matrixU() const\n    {\n      eigen_assert(m_isInitialized && \"LLT is not initialized.\");\n      return Traits::getU(m_matrix);\n    }\n\n    /** \\returns a view of the lower triangular matrix L */\n    inline typename Traits::MatrixL matrixL() const\n    {\n      eigen_assert(m_isInitialized && \"LLT is not initialized.\");\n      return Traits::getL(m_matrix);\n    }\n\n    #ifdef EIGEN_PARSED_BY_DOXYGEN\n    /** \\returns the solution x of \\f$ A x = b \\f$ using the current decomposition of A.\n      *\n      * Since this LLT class assumes anyway that the matrix A is invertible, the solution\n      * theoretically exists and is unique regardless of b.\n      *\n      * Example: \\include LLT_solve.cpp\n      * Output: \\verbinclude LLT_solve.out\n      *\n      * \\sa solveInPlace(), MatrixBase::llt(), SelfAdjointView::llt()\n      */\n    template<typename Rhs>\n    inline const Solve<LLT, Rhs>\n    solve(const MatrixBase<Rhs>& b) const;\n    #endif\n\n    template<typename Derived>\n    void solveInPlace(const MatrixBase<Derived> &bAndX) const;\n\n    template<typename InputType>\n    LLT& compute(const EigenBase<InputType>& matrix);\n\n    /** \\returns an estimate of the reciprocal condition number of the matrix of\n      *  which \\c *this is the Cholesky decomposition.\n      */\n    RealScalar rcond() const\n    {\n      eigen_assert(m_isInitialized && \"LLT is not initialized.\");\n      eigen_assert(m_info == Success && \"LLT failed because matrix appears to be negative\");\n      return internal::rcond_estimate_helper(m_l1_norm, *this);\n    }\n\n    /** \\returns the LLT decomposition matrix\n      *\n      * TODO: document the storage layout\n      */\n    inline const MatrixType& matrixLLT() const\n    {\n      eigen_assert(m_isInitialized && \"LLT is not initialized.\");\n      return m_matrix;\n    }\n\n    MatrixType reconstructedMatrix() const;\n\n\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the matrix.appears not to be positive definite.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"LLT is not initialized.\");\n      return m_info;\n    }\n\n    /** \\returns the adjoint of \\c *this, that is, a const reference to the decomposition itself as the underlying matrix is self-adjoint.\n      *\n      * This method is provided for compatibility with other matrix decompositions, thus enabling generic code such as:\n      * \\code x = decomposition.adjoint().solve(b) \\endcode\n      */\n    const LLT& adjoint() const EIGEN_NOEXCEPT { return *this; };\n\n    inline EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_matrix.rows(); }\n    inline EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_matrix.cols(); }\n\n    template<typename VectorType>\n    LLT & rankUpdate(const VectorType& vec, const RealScalar& sigma = 1);\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<typename RhsType, typename DstType>\n    void _solve_impl(const RhsType &rhs, DstType &dst) const;\n\n    template<bool Conjugate, typename RhsType, typename DstType>\n    void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const;\n    #endif\n\n  protected:\n\n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n    }\n\n    /** \\internal\n      * Used to compute and store L\n      * The strict upper part is not used and even not initialized.\n      */\n    MatrixType m_matrix;\n    RealScalar m_l1_norm;\n    bool m_isInitialized;\n    ComputationInfo m_info;\n};\n\nnamespace internal {\n\ntemplate<typename Scalar, int UpLo> struct llt_inplace;\n\ntemplate<typename MatrixType, typename VectorType>\nstatic Index llt_rank_update_lower(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma)\n{\n  using std::sqrt;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef typename MatrixType::ColXpr ColXpr;\n  typedef typename internal::remove_all<ColXpr>::type ColXprCleaned;\n  typedef typename ColXprCleaned::SegmentReturnType ColXprSegment;\n  typedef Matrix<Scalar,Dynamic,1> TempVectorType;\n  typedef typename TempVectorType::SegmentReturnType TempVecSegment;\n\n  Index n = mat.cols();\n  eigen_assert(mat.rows()==n && vec.size()==n);\n\n  TempVectorType temp;\n\n  if(sigma>0)\n  {\n    // This version is based on Givens rotations.\n    // It is faster than the other one below, but only works for updates,\n    // i.e., for sigma > 0\n    temp = sqrt(sigma) * vec;\n\n    for(Index i=0; i<n; ++i)\n    {\n      JacobiRotation<Scalar> g;\n      g.makeGivens(mat(i,i), -temp(i), &mat(i,i));\n\n      Index rs = n-i-1;\n      if(rs>0)\n      {\n        ColXprSegment x(mat.col(i).tail(rs));\n        TempVecSegment y(temp.tail(rs));\n        apply_rotation_in_the_plane(x, y, g);\n      }\n    }\n  }\n  else\n  {\n    temp = vec;\n    RealScalar beta = 1;\n    for(Index j=0; j<n; ++j)\n    {\n      RealScalar Ljj = numext::real(mat.coeff(j,j));\n      RealScalar dj = numext::abs2(Ljj);\n      Scalar wj = temp.coeff(j);\n      RealScalar swj2 = sigma*numext::abs2(wj);\n      RealScalar gamma = dj*beta + swj2;\n\n      RealScalar x = dj + swj2/beta;\n      if (x<=RealScalar(0))\n        return j;\n      RealScalar nLjj = sqrt(x);\n      mat.coeffRef(j,j) = nLjj;\n      beta += swj2/dj;\n\n      // Update the terms of L\n      Index rs = n-j-1;\n      if(rs)\n      {\n        temp.tail(rs) -= (wj/Ljj) * mat.col(j).tail(rs);\n        if(gamma != 0)\n          mat.col(j).tail(rs) = (nLjj/Ljj) * mat.col(j).tail(rs) + (nLjj * sigma*numext::conj(wj)/gamma)*temp.tail(rs);\n      }\n    }\n  }\n  return -1;\n}\n\ntemplate<typename Scalar> struct llt_inplace<Scalar, Lower>\n{\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  template<typename MatrixType>\n  static Index unblocked(MatrixType& mat)\n  {\n    using std::sqrt;\n\n    eigen_assert(mat.rows()==mat.cols());\n    const Index size = mat.rows();\n    for(Index k = 0; k < size; ++k)\n    {\n      Index rs = size-k-1; // remaining size\n\n      Block<MatrixType,Dynamic,1> A21(mat,k+1,k,rs,1);\n      Block<MatrixType,1,Dynamic> A10(mat,k,0,1,k);\n      Block<MatrixType,Dynamic,Dynamic> A20(mat,k+1,0,rs,k);\n\n      RealScalar x = numext::real(mat.coeff(k,k));\n      if (k>0) x -= A10.squaredNorm();\n      if (x<=RealScalar(0))\n        return k;\n      mat.coeffRef(k,k) = x = sqrt(x);\n      if (k>0 && rs>0) A21.noalias() -= A20 * A10.adjoint();\n      if (rs>0) A21 /= x;\n    }\n    return -1;\n  }\n\n  template<typename MatrixType>\n  static Index blocked(MatrixType& m)\n  {\n    eigen_assert(m.rows()==m.cols());\n    Index size = m.rows();\n    if(size<32)\n      return unblocked(m);\n\n    Index blockSize = size/8;\n    blockSize = (blockSize/16)*16;\n    blockSize = (std::min)((std::max)(blockSize,Index(8)), Index(128));\n\n    for (Index k=0; k<size; k+=blockSize)\n    {\n      // partition the matrix:\n      //       A00 |  -  |  -\n      // lu  = A10 | A11 |  -\n      //       A20 | A21 | A22\n      Index bs = (std::min)(blockSize, size-k);\n      Index rs = size - k - bs;\n      Block<MatrixType,Dynamic,Dynamic> A11(m,k,   k,   bs,bs);\n      Block<MatrixType,Dynamic,Dynamic> A21(m,k+bs,k,   rs,bs);\n      Block<MatrixType,Dynamic,Dynamic> A22(m,k+bs,k+bs,rs,rs);\n\n      Index ret;\n      if((ret=unblocked(A11))>=0) return k+ret;\n      if(rs>0) A11.adjoint().template triangularView<Upper>().template solveInPlace<OnTheRight>(A21);\n      if(rs>0) A22.template selfadjointView<Lower>().rankUpdate(A21,typename NumTraits<RealScalar>::Literal(-1)); // bottleneck\n    }\n    return -1;\n  }\n\n  template<typename MatrixType, typename VectorType>\n  static Index rankUpdate(MatrixType& mat, const VectorType& vec, const RealScalar& sigma)\n  {\n    return Eigen::internal::llt_rank_update_lower(mat, vec, sigma);\n  }\n};\n\ntemplate<typename Scalar> struct llt_inplace<Scalar, Upper>\n{\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  template<typename MatrixType>\n  static EIGEN_STRONG_INLINE Index unblocked(MatrixType& mat)\n  {\n    Transpose<MatrixType> matt(mat);\n    return llt_inplace<Scalar, Lower>::unblocked(matt);\n  }\n  template<typename MatrixType>\n  static EIGEN_STRONG_INLINE Index blocked(MatrixType& mat)\n  {\n    Transpose<MatrixType> matt(mat);\n    return llt_inplace<Scalar, Lower>::blocked(matt);\n  }\n  template<typename MatrixType, typename VectorType>\n  static Index rankUpdate(MatrixType& mat, const VectorType& vec, const RealScalar& sigma)\n  {\n    Transpose<MatrixType> matt(mat);\n    return llt_inplace<Scalar, Lower>::rankUpdate(matt, vec.conjugate(), sigma);\n  }\n};\n\ntemplate<typename MatrixType> struct LLT_Traits<MatrixType,Lower>\n{\n  typedef const TriangularView<const MatrixType, Lower> MatrixL;\n  typedef const TriangularView<const typename MatrixType::AdjointReturnType, Upper> MatrixU;\n  static inline MatrixL getL(const MatrixType& m) { return MatrixL(m); }\n  static inline MatrixU getU(const MatrixType& m) { return MatrixU(m.adjoint()); }\n  static bool inplace_decomposition(MatrixType& m)\n  { return llt_inplace<typename MatrixType::Scalar, Lower>::blocked(m)==-1; }\n};\n\ntemplate<typename MatrixType> struct LLT_Traits<MatrixType,Upper>\n{\n  typedef const TriangularView<const typename MatrixType::AdjointReturnType, Lower> MatrixL;\n  typedef const TriangularView<const MatrixType, Upper> MatrixU;\n  static inline MatrixL getL(const MatrixType& m) { return MatrixL(m.adjoint()); }\n  static inline MatrixU getU(const MatrixType& m) { return MatrixU(m); }\n  static bool inplace_decomposition(MatrixType& m)\n  { return llt_inplace<typename MatrixType::Scalar, Upper>::blocked(m)==-1; }\n};\n\n} // end namespace internal\n\n/** Computes / recomputes the Cholesky decomposition A = LL^* = U^*U of \\a matrix\n  *\n  * \\returns a reference to *this\n  *\n  * Example: \\include TutorialLinAlgComputeTwice.cpp\n  * Output: \\verbinclude TutorialLinAlgComputeTwice.out\n  */\ntemplate<typename MatrixType, int UpLo_>\ntemplate<typename InputType>\nLLT<MatrixType,UpLo_>& LLT<MatrixType,UpLo_>::compute(const EigenBase<InputType>& a)\n{\n  check_template_parameters();\n\n  eigen_assert(a.rows()==a.cols());\n  const Index size = a.rows();\n  m_matrix.resize(size, size);\n  if (!internal::is_same_dense(m_matrix, a.derived()))\n    m_matrix = a.derived();\n\n  // Compute matrix L1 norm = max abs column sum.\n  m_l1_norm = RealScalar(0);\n  // TODO move this code to SelfAdjointView\n  for (Index col = 0; col < size; ++col) {\n    RealScalar abs_col_sum;\n    if (UpLo_ == Lower)\n      abs_col_sum = m_matrix.col(col).tail(size - col).template lpNorm<1>() + m_matrix.row(col).head(col).template lpNorm<1>();\n    else\n      abs_col_sum = m_matrix.col(col).head(col).template lpNorm<1>() + m_matrix.row(col).tail(size - col).template lpNorm<1>();\n    if (abs_col_sum > m_l1_norm)\n      m_l1_norm = abs_col_sum;\n  }\n\n  m_isInitialized = true;\n  bool ok = Traits::inplace_decomposition(m_matrix);\n  m_info = ok ? Success : NumericalIssue;\n\n  return *this;\n}\n\n/** Performs a rank one update (or dowdate) of the current decomposition.\n  * If A = LL^* before the rank one update,\n  * then after it we have LL^* = A + sigma * v v^* where \\a v must be a vector\n  * of same dimension.\n  */\ntemplate<typename MatrixType_, int UpLo_>\ntemplate<typename VectorType>\nLLT<MatrixType_,UpLo_> & LLT<MatrixType_,UpLo_>::rankUpdate(const VectorType& v, const RealScalar& sigma)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(VectorType);\n  eigen_assert(v.size()==m_matrix.cols());\n  eigen_assert(m_isInitialized);\n  if(internal::llt_inplace<typename MatrixType::Scalar, UpLo>::rankUpdate(m_matrix,v,sigma)>=0)\n    m_info = NumericalIssue;\n  else\n    m_info = Success;\n\n  return *this;\n}\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename MatrixType_,int UpLo_>\ntemplate<typename RhsType, typename DstType>\nvoid LLT<MatrixType_,UpLo_>::_solve_impl(const RhsType &rhs, DstType &dst) const\n{\n  _solve_impl_transposed<true>(rhs, dst);\n}\n\ntemplate<typename MatrixType_,int UpLo_>\ntemplate<bool Conjugate, typename RhsType, typename DstType>\nvoid LLT<MatrixType_,UpLo_>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const\n{\n    dst = rhs;\n\n    matrixL().template conjugateIf<!Conjugate>().solveInPlace(dst);\n    matrixU().template conjugateIf<!Conjugate>().solveInPlace(dst);\n}\n#endif\n\n/** \\internal use x = llt_object.solve(x);\n  *\n  * This is the \\em in-place version of solve().\n  *\n  * \\param bAndX represents both the right-hand side matrix b and result x.\n  *\n  * This version avoids a copy when the right hand side matrix b is not needed anymore.\n  *\n  * \\warning The parameter is only marked 'const' to make the C++ compiler accept a temporary expression here.\n  * This function will const_cast it, so constness isn't honored here.\n  *\n  * \\sa LLT::solve(), MatrixBase::llt()\n  */\ntemplate<typename MatrixType, int UpLo_>\ntemplate<typename Derived>\nvoid LLT<MatrixType,UpLo_>::solveInPlace(const MatrixBase<Derived> &bAndX) const\n{\n  eigen_assert(m_isInitialized && \"LLT is not initialized.\");\n  eigen_assert(m_matrix.rows()==bAndX.rows());\n  matrixL().solveInPlace(bAndX);\n  matrixU().solveInPlace(bAndX);\n}\n\n/** \\returns the matrix represented by the decomposition,\n * i.e., it returns the product: L L^*.\n * This function is provided for debug purpose. */\ntemplate<typename MatrixType, int UpLo_>\nMatrixType LLT<MatrixType,UpLo_>::reconstructedMatrix() const\n{\n  eigen_assert(m_isInitialized && \"LLT is not initialized.\");\n  return matrixL() * matrixL().adjoint().toDenseMatrix();\n}\n\n/** \\cholesky_module\n  * \\returns the LLT decomposition of \\c *this\n  * \\sa SelfAdjointView::llt()\n  */\ntemplate<typename Derived>\ninline const LLT<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::llt() const\n{\n  return LLT<PlainObject>(derived());\n}\n\n/** \\cholesky_module\n  * \\returns the LLT decomposition of \\c *this\n  * \\sa SelfAdjointView::llt()\n  */\ntemplate<typename MatrixType, unsigned int UpLo>\ninline const LLT<typename SelfAdjointView<MatrixType, UpLo>::PlainObject, UpLo>\nSelfAdjointView<MatrixType, UpLo>::llt() const\n{\n  return LLT<PlainObject,UpLo>(m_matrix);\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_LLT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Cholesky/LLT_LAPACKE.h",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Eigen bindings to LAPACKe\n *     LLt decomposition based on LAPACKE_?potrf function.\n ********************************************************************************\n*/\n\n#ifndef EIGEN_LLT_LAPACKE_H\n#define EIGEN_LLT_LAPACKE_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate<typename Scalar> struct lapacke_llt;\n\n#define EIGEN_LAPACKE_LLT(EIGTYPE, BLASTYPE, LAPACKE_PREFIX) \\\ntemplate<> struct lapacke_llt<EIGTYPE> \\\n{ \\\n  template<typename MatrixType> \\\n  static inline Index potrf(MatrixType& m, char uplo) \\\n  { \\\n    lapack_int matrix_order; \\\n    lapack_int size, lda, info, StorageOrder; \\\n    EIGTYPE* a; \\\n    eigen_assert(m.rows()==m.cols()); \\\n    /* Set up parameters for ?potrf */ \\\n    size = convert_index<lapack_int>(m.rows()); \\\n    StorageOrder = MatrixType::Flags&RowMajorBit?RowMajor:ColMajor; \\\n    matrix_order = StorageOrder==RowMajor ? LAPACK_ROW_MAJOR : LAPACK_COL_MAJOR; \\\n    a = &(m.coeffRef(0,0)); \\\n    lda = convert_index<lapack_int>(m.outerStride()); \\\n\\\n    info = LAPACKE_##LAPACKE_PREFIX##potrf( matrix_order, uplo, size, (BLASTYPE*)a, lda ); \\\n    info = (info==0) ? -1 : info>0 ? info-1 : size; \\\n    return info; \\\n  } \\\n}; \\\ntemplate<> struct llt_inplace<EIGTYPE, Lower> \\\n{ \\\n  template<typename MatrixType> \\\n  static Index blocked(MatrixType& m) \\\n  { \\\n    return lapacke_llt<EIGTYPE>::potrf(m, 'L'); \\\n  } \\\n  template<typename MatrixType, typename VectorType> \\\n  static Index rankUpdate(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma) \\\n  { return Eigen::internal::llt_rank_update_lower(mat, vec, sigma); } \\\n}; \\\ntemplate<> struct llt_inplace<EIGTYPE, Upper> \\\n{ \\\n  template<typename MatrixType> \\\n  static Index blocked(MatrixType& m) \\\n  { \\\n    return lapacke_llt<EIGTYPE>::potrf(m, 'U'); \\\n  } \\\n  template<typename MatrixType, typename VectorType> \\\n  static Index rankUpdate(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma) \\\n  { \\\n    Transpose<MatrixType> matt(mat); \\\n    return llt_inplace<EIGTYPE, Lower>::rankUpdate(matt, vec.conjugate(), sigma); \\\n  } \\\n};\n\nEIGEN_LAPACKE_LLT(double, double, d)\nEIGEN_LAPACKE_LLT(float, float, s)\nEIGEN_LAPACKE_LLT(dcomplex, lapack_complex_double, z)\nEIGEN_LAPACKE_LLT(scomplex, lapack_complex_float, c)\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_LLT_LAPACKE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/CholmodSupport/CholmodSupport.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CHOLMODSUPPORT_H\n#define EIGEN_CHOLMODSUPPORT_H\n\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate<typename Scalar> struct cholmod_configure_matrix;\n\ntemplate<> struct cholmod_configure_matrix<double> {\n  template<typename CholmodType>\n  static void run(CholmodType& mat) {\n    mat.xtype = CHOLMOD_REAL;\n    mat.dtype = CHOLMOD_DOUBLE;\n  }\n};\n\ntemplate<> struct cholmod_configure_matrix<std::complex<double> > {\n  template<typename CholmodType>\n  static void run(CholmodType& mat) {\n    mat.xtype = CHOLMOD_COMPLEX;\n    mat.dtype = CHOLMOD_DOUBLE;\n  }\n};\n\n// Other scalar types are not yet supported by Cholmod\n// template<> struct cholmod_configure_matrix<float> {\n//   template<typename CholmodType>\n//   static void run(CholmodType& mat) {\n//     mat.xtype = CHOLMOD_REAL;\n//     mat.dtype = CHOLMOD_SINGLE;\n//   }\n// };\n//\n// template<> struct cholmod_configure_matrix<std::complex<float> > {\n//   template<typename CholmodType>\n//   static void run(CholmodType& mat) {\n//     mat.xtype = CHOLMOD_COMPLEX;\n//     mat.dtype = CHOLMOD_SINGLE;\n//   }\n// };\n\n} // namespace internal\n\n/** Wraps the Eigen sparse matrix \\a mat into a Cholmod sparse matrix object.\n  * Note that the data are shared.\n  */\ntemplate<typename Scalar_, int Options_, typename StorageIndex_>\ncholmod_sparse viewAsCholmod(Ref<SparseMatrix<Scalar_,Options_,StorageIndex_> > mat)\n{\n  cholmod_sparse res;\n  res.nzmax   = mat.nonZeros();\n  res.nrow    = mat.rows();\n  res.ncol    = mat.cols();\n  res.p       = mat.outerIndexPtr();\n  res.i       = mat.innerIndexPtr();\n  res.x       = mat.valuePtr();\n  res.z       = 0;\n  res.sorted  = 1;\n  if(mat.isCompressed())\n  {\n    res.packed  = 1;\n    res.nz = 0;\n  }\n  else\n  {\n    res.packed  = 0;\n    res.nz = mat.innerNonZeroPtr();\n  }\n\n  res.dtype   = 0;\n  res.stype   = -1;\n\n  if (internal::is_same<StorageIndex_,int>::value)\n  {\n    res.itype = CHOLMOD_INT;\n  }\n  else if (internal::is_same<StorageIndex_,SuiteSparse_long>::value)\n  {\n    res.itype = CHOLMOD_LONG;\n  }\n  else\n  {\n    eigen_assert(false && \"Index type not supported yet\");\n  }\n\n  // setup res.xtype\n  internal::cholmod_configure_matrix<Scalar_>::run(res);\n\n  res.stype = 0;\n\n  return res;\n}\n\ntemplate<typename Scalar_, int Options_, typename Index_>\nconst cholmod_sparse viewAsCholmod(const SparseMatrix<Scalar_,Options_,Index_>& mat)\n{\n  cholmod_sparse res = viewAsCholmod(Ref<SparseMatrix<Scalar_,Options_,Index_> >(mat.const_cast_derived()));\n  return res;\n}\n\ntemplate<typename Scalar_, int Options_, typename Index_>\nconst cholmod_sparse viewAsCholmod(const SparseVector<Scalar_,Options_,Index_>& mat)\n{\n  cholmod_sparse res = viewAsCholmod(Ref<SparseMatrix<Scalar_,Options_,Index_> >(mat.const_cast_derived()));\n  return res;\n}\n\n/** Returns a view of the Eigen sparse matrix \\a mat as Cholmod sparse matrix.\n  * The data are not copied but shared. */\ntemplate<typename Scalar_, int Options_, typename Index_, unsigned int UpLo>\ncholmod_sparse viewAsCholmod(const SparseSelfAdjointView<const SparseMatrix<Scalar_,Options_,Index_>, UpLo>& mat)\n{\n  cholmod_sparse res = viewAsCholmod(Ref<SparseMatrix<Scalar_,Options_,Index_> >(mat.matrix().const_cast_derived()));\n\n  if(UpLo==Upper) res.stype =  1;\n  if(UpLo==Lower) res.stype = -1;\n  // swap stype for rowmajor matrices (only works for real matrices)\n  EIGEN_STATIC_ASSERT((Options_ & RowMajorBit) == 0 || NumTraits<Scalar_>::IsComplex == 0, THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES);\n  if(Options_ & RowMajorBit) res.stype *=-1;\n\n  return res;\n}\n\n/** Returns a view of the Eigen \\b dense matrix \\a mat as Cholmod dense matrix.\n  * The data are not copied but shared. */\ntemplate<typename Derived>\ncholmod_dense viewAsCholmod(MatrixBase<Derived>& mat)\n{\n  EIGEN_STATIC_ASSERT((internal::traits<Derived>::Flags&RowMajorBit)==0,THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES);\n  typedef typename Derived::Scalar Scalar;\n\n  cholmod_dense res;\n  res.nrow   = mat.rows();\n  res.ncol   = mat.cols();\n  res.nzmax  = res.nrow * res.ncol;\n  res.d      = Derived::IsVectorAtCompileTime ? mat.derived().size() : mat.derived().outerStride();\n  res.x      = (void*)(mat.derived().data());\n  res.z      = 0;\n\n  internal::cholmod_configure_matrix<Scalar>::run(res);\n\n  return res;\n}\n\n/** Returns a view of the Cholmod sparse matrix \\a cm as an Eigen sparse matrix.\n  * The data are not copied but shared. */\ntemplate<typename Scalar, int Flags, typename StorageIndex>\nMappedSparseMatrix<Scalar,Flags,StorageIndex> viewAsEigen(cholmod_sparse& cm)\n{\n  return MappedSparseMatrix<Scalar,Flags,StorageIndex>\n         (cm.nrow, cm.ncol, static_cast<StorageIndex*>(cm.p)[cm.ncol],\n          static_cast<StorageIndex*>(cm.p), static_cast<StorageIndex*>(cm.i),static_cast<Scalar*>(cm.x) );\n}\n\nnamespace internal {\n\n// template specializations for int and long that call the correct cholmod method\n\n#define EIGEN_CHOLMOD_SPECIALIZE0(ret, name) \\\n    template<typename StorageIndex_> inline ret cm_ ## name       (cholmod_common &Common) { return cholmod_ ## name   (&Common); } \\\n    template<>                       inline ret cm_ ## name<SuiteSparse_long> (cholmod_common &Common) { return cholmod_l_ ## name (&Common); }\n\n#define EIGEN_CHOLMOD_SPECIALIZE1(ret, name, t1, a1) \\\n    template<typename StorageIndex_> inline ret cm_ ## name       (t1& a1, cholmod_common &Common) { return cholmod_ ## name   (&a1, &Common); } \\\n    template<>                       inline ret cm_ ## name<SuiteSparse_long> (t1& a1, cholmod_common &Common) { return cholmod_l_ ## name (&a1, &Common); }\n\nEIGEN_CHOLMOD_SPECIALIZE0(int, start)\nEIGEN_CHOLMOD_SPECIALIZE0(int, finish)\n\nEIGEN_CHOLMOD_SPECIALIZE1(int, free_factor, cholmod_factor*, L)\nEIGEN_CHOLMOD_SPECIALIZE1(int, free_dense,  cholmod_dense*,  X)\nEIGEN_CHOLMOD_SPECIALIZE1(int, free_sparse, cholmod_sparse*, A)\n\nEIGEN_CHOLMOD_SPECIALIZE1(cholmod_factor*, analyze, cholmod_sparse, A)\n\ntemplate<typename StorageIndex_> inline cholmod_dense*  cm_solve         (int sys, cholmod_factor& L, cholmod_dense&  B, cholmod_common &Common) { return cholmod_solve     (sys, &L, &B, &Common); }\ntemplate<>                       inline cholmod_dense*  cm_solve<SuiteSparse_long>   (int sys, cholmod_factor& L, cholmod_dense&  B, cholmod_common &Common) { return cholmod_l_solve   (sys, &L, &B, &Common); }\n\ntemplate<typename StorageIndex_> inline cholmod_sparse* cm_spsolve       (int sys, cholmod_factor& L, cholmod_sparse& B, cholmod_common &Common) { return cholmod_spsolve   (sys, &L, &B, &Common); }\ntemplate<>                       inline cholmod_sparse* cm_spsolve<SuiteSparse_long> (int sys, cholmod_factor& L, cholmod_sparse& B, cholmod_common &Common) { return cholmod_l_spsolve (sys, &L, &B, &Common); }\n\ntemplate<typename StorageIndex_>\ninline int  cm_factorize_p       (cholmod_sparse*  A, double beta[2], StorageIndex_* fset, std::size_t fsize, cholmod_factor* L, cholmod_common &Common) { return cholmod_factorize_p   (A, beta, fset, fsize, L, &Common); }\ntemplate<>\ninline int  cm_factorize_p<SuiteSparse_long> (cholmod_sparse*  A, double beta[2], SuiteSparse_long* fset,          std::size_t fsize, cholmod_factor* L, cholmod_common &Common) { return cholmod_l_factorize_p (A, beta, fset, fsize, L, &Common); }\n\n#undef EIGEN_CHOLMOD_SPECIALIZE0\n#undef EIGEN_CHOLMOD_SPECIALIZE1\n\n}  // namespace internal\n\n\nenum CholmodMode {\n  CholmodAuto, CholmodSimplicialLLt, CholmodSupernodalLLt, CholmodLDLt\n};\n\n\n/** \\ingroup CholmodSupport_Module\n  * \\class CholmodBase\n  * \\brief The base class for the direct Cholesky factorization of Cholmod\n  * \\sa class CholmodSupernodalLLT, class CholmodSimplicialLDLT, class CholmodSimplicialLLT\n  */\ntemplate<typename MatrixType_, int UpLo_, typename Derived>\nclass CholmodBase : public SparseSolverBase<Derived>\n{\n  protected:\n    typedef SparseSolverBase<Derived> Base;\n    using Base::derived;\n    using Base::m_isInitialized;\n  public:\n    typedef MatrixType_ MatrixType;\n    enum { UpLo = UpLo_ };\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef MatrixType CholMatrixType;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    enum {\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n\n  public:\n\n    CholmodBase()\n      : m_cholmodFactor(0), m_info(Success), m_factorizationIsOk(false), m_analysisIsOk(false)\n    {\n      EIGEN_STATIC_ASSERT((internal::is_same<double,RealScalar>::value), CHOLMOD_SUPPORTS_DOUBLE_PRECISION_ONLY);\n      m_shiftOffset[0] = m_shiftOffset[1] = 0.0;\n      internal::cm_start<StorageIndex>(m_cholmod);\n    }\n\n    explicit CholmodBase(const MatrixType& matrix)\n      : m_cholmodFactor(0), m_info(Success), m_factorizationIsOk(false), m_analysisIsOk(false)\n    {\n      EIGEN_STATIC_ASSERT((internal::is_same<double,RealScalar>::value), CHOLMOD_SUPPORTS_DOUBLE_PRECISION_ONLY);\n      m_shiftOffset[0] = m_shiftOffset[1] = 0.0;\n      internal::cm_start<StorageIndex>(m_cholmod);\n      compute(matrix);\n    }\n\n    ~CholmodBase()\n    {\n      if(m_cholmodFactor)\n        internal::cm_free_factor<StorageIndex>(m_cholmodFactor, m_cholmod);\n      internal::cm_finish<StorageIndex>(m_cholmod);\n    }\n\n    inline StorageIndex cols() const { return internal::convert_index<StorageIndex, Index>(m_cholmodFactor->n); }\n    inline StorageIndex rows() const { return internal::convert_index<StorageIndex, Index>(m_cholmodFactor->n); }\n\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the matrix.appears to be negative.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_info;\n    }\n\n    /** Computes the sparse Cholesky decomposition of \\a matrix */\n    Derived& compute(const MatrixType& matrix)\n    {\n      analyzePattern(matrix);\n      factorize(matrix);\n      return derived();\n    }\n\n    /** Performs a symbolic decomposition on the sparsity pattern of \\a matrix.\n      *\n      * This function is particularly useful when solving for several problems having the same structure.\n      *\n      * \\sa factorize()\n      */\n    void analyzePattern(const MatrixType& matrix)\n    {\n      if(m_cholmodFactor)\n      {\n        internal::cm_free_factor<StorageIndex>(m_cholmodFactor, m_cholmod);\n        m_cholmodFactor = 0;\n      }\n      cholmod_sparse A = viewAsCholmod(matrix.template selfadjointView<UpLo>());\n      m_cholmodFactor = internal::cm_analyze<StorageIndex>(A, m_cholmod);\n\n      this->m_isInitialized = true;\n      this->m_info = Success;\n      m_analysisIsOk = true;\n      m_factorizationIsOk = false;\n    }\n\n    /** Performs a numeric decomposition of \\a matrix\n      *\n      * The given matrix must have the same sparsity pattern as the matrix on which the symbolic decomposition has been performed.\n      *\n      * \\sa analyzePattern()\n      */\n    void factorize(const MatrixType& matrix)\n    {\n      eigen_assert(m_analysisIsOk && \"You must first call analyzePattern()\");\n      cholmod_sparse A = viewAsCholmod(matrix.template selfadjointView<UpLo>());\n      internal::cm_factorize_p<StorageIndex>(&A, m_shiftOffset, 0, 0, m_cholmodFactor, m_cholmod);\n\n      // If the factorization failed, minor is the column at which it did. On success minor == n.\n      this->m_info = (m_cholmodFactor->minor == m_cholmodFactor->n ? Success : NumericalIssue);\n      m_factorizationIsOk = true;\n    }\n\n    /** Returns a reference to the Cholmod's configuration structure to get a full control over the performed operations.\n     *  See the Cholmod user guide for details. */\n    cholmod_common& cholmod() { return m_cholmod; }\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    /** \\internal */\n    template<typename Rhs,typename Dest>\n    void _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const\n    {\n      eigen_assert(m_factorizationIsOk && \"The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()\");\n      const Index size = m_cholmodFactor->n;\n      EIGEN_UNUSED_VARIABLE(size);\n      eigen_assert(size==b.rows());\n\n      // Cholmod needs column-major storage without inner-stride, which corresponds to the default behavior of Ref.\n      Ref<const Matrix<typename Rhs::Scalar,Dynamic,Dynamic,ColMajor> > b_ref(b.derived());\n\n      cholmod_dense b_cd = viewAsCholmod(b_ref);\n      cholmod_dense* x_cd = internal::cm_solve<StorageIndex>(CHOLMOD_A, *m_cholmodFactor, b_cd, m_cholmod);\n      if(!x_cd)\n      {\n        this->m_info = NumericalIssue;\n        return;\n      }\n      // TODO optimize this copy by swapping when possible (be careful with alignment, etc.)\n      // NOTE Actually, the copy can be avoided by calling cholmod_solve2 instead of cholmod_solve\n      dest = Matrix<Scalar,Dest::RowsAtCompileTime,Dest::ColsAtCompileTime>::Map(reinterpret_cast<Scalar*>(x_cd->x),b.rows(),b.cols());\n      internal::cm_free_dense<StorageIndex>(x_cd, m_cholmod);\n    }\n\n    /** \\internal */\n    template<typename RhsDerived, typename DestDerived>\n    void _solve_impl(const SparseMatrixBase<RhsDerived> &b, SparseMatrixBase<DestDerived> &dest) const\n    {\n      eigen_assert(m_factorizationIsOk && \"The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()\");\n      const Index size = m_cholmodFactor->n;\n      EIGEN_UNUSED_VARIABLE(size);\n      eigen_assert(size==b.rows());\n\n      // note: cs stands for Cholmod Sparse\n      Ref<SparseMatrix<typename RhsDerived::Scalar,ColMajor,typename RhsDerived::StorageIndex> > b_ref(b.const_cast_derived());\n      cholmod_sparse b_cs = viewAsCholmod(b_ref);\n      cholmod_sparse* x_cs = internal::cm_spsolve<StorageIndex>(CHOLMOD_A, *m_cholmodFactor, b_cs, m_cholmod);\n      if(!x_cs)\n      {\n        this->m_info = NumericalIssue;\n        return;\n      }\n      // TODO optimize this copy by swapping when possible (be careful with alignment, etc.)\n      // NOTE cholmod_spsolve in fact just calls the dense solver for blocks of 4 columns at a time (similar to Eigen's sparse solver)\n      dest.derived() = viewAsEigen<typename DestDerived::Scalar,ColMajor,typename DestDerived::StorageIndex>(*x_cs);\n      internal::cm_free_sparse<StorageIndex>(x_cs, m_cholmod);\n    }\n    #endif // EIGEN_PARSED_BY_DOXYGEN\n\n\n    /** Sets the shift parameter that will be used to adjust the diagonal coefficients during the numerical factorization.\n      *\n      * During the numerical factorization, an offset term is added to the diagonal coefficients:\\n\n      * \\c d_ii = \\a offset + \\c d_ii\n      *\n      * The default is \\a offset=0.\n      *\n      * \\returns a reference to \\c *this.\n      */\n    Derived& setShift(const RealScalar& offset)\n    {\n      m_shiftOffset[0] = double(offset);\n      return derived();\n    }\n\n    /** \\returns the determinant of the underlying matrix from the current factorization */\n    Scalar determinant() const\n    {\n      using std::exp;\n      return exp(logDeterminant());\n    }\n\n    /** \\returns the log determinant of the underlying matrix from the current factorization */\n    Scalar logDeterminant() const\n    {\n      using std::log;\n      using numext::real;\n      eigen_assert(m_factorizationIsOk && \"The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()\");\n\n      RealScalar logDet = 0;\n      Scalar *x = static_cast<Scalar*>(m_cholmodFactor->x);\n      if (m_cholmodFactor->is_super)\n      {\n        // Supernodal factorization stored as a packed list of dense column-major blocs,\n        // as described by the following structure:\n\n        // super[k] == index of the first column of the j-th super node\n        StorageIndex *super = static_cast<StorageIndex*>(m_cholmodFactor->super);\n        // pi[k] == offset to the description of row indices\n        StorageIndex *pi = static_cast<StorageIndex*>(m_cholmodFactor->pi);\n        // px[k] == offset to the respective dense block\n        StorageIndex *px = static_cast<StorageIndex*>(m_cholmodFactor->px);\n\n        Index nb_super_nodes = m_cholmodFactor->nsuper;\n        for (Index k=0; k < nb_super_nodes; ++k)\n        {\n          StorageIndex ncols = super[k + 1] - super[k];\n          StorageIndex nrows = pi[k + 1] - pi[k];\n\n          Map<const Array<Scalar,1,Dynamic>, 0, InnerStride<> > sk(x + px[k], ncols, InnerStride<>(nrows+1));\n          logDet += sk.real().log().sum();\n        }\n      }\n      else\n      {\n        // Simplicial factorization stored as standard CSC matrix.\n        StorageIndex *p = static_cast<StorageIndex*>(m_cholmodFactor->p);\n        Index size = m_cholmodFactor->n;\n        for (Index k=0; k<size; ++k)\n          logDet += log(real( x[p[k]] ));\n      }\n      if (m_cholmodFactor->is_ll)\n        logDet *= 2.0;\n      return logDet;\n    };\n\n    template<typename Stream>\n    void dumpMemory(Stream& /*s*/)\n    {}\n\n  protected:\n    mutable cholmod_common m_cholmod;\n    cholmod_factor* m_cholmodFactor;\n    double m_shiftOffset[2];\n    mutable ComputationInfo m_info;\n    int m_factorizationIsOk;\n    int m_analysisIsOk;\n};\n\n/** \\ingroup CholmodSupport_Module\n  * \\class CholmodSimplicialLLT\n  * \\brief A simplicial direct Cholesky (LLT) factorization and solver based on Cholmod\n  *\n  * This class allows to solve for A.X = B sparse linear problems via a simplicial LL^T Cholesky factorization\n  * using the Cholmod library.\n  * This simplicial variant is equivalent to Eigen's built-in SimplicialLLT class. Therefore, it has little practical interest.\n  * The sparse matrix A must be selfadjoint and positive definite. The vectors or matrices\n  * X and B can be either dense or sparse.\n  *\n  * \\tparam MatrixType_ the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam UpLo_ the triangular part that will be used for the computations. It can be Lower\n  *               or Upper. Default is Lower.\n  *\n  * \\implsparsesolverconcept\n  *\n  * This class supports all kind of SparseMatrix<>: row or column major; upper, lower, or both; compressed or non compressed.\n  *\n  * \\warning Only double precision real and complex scalar types are supported by Cholmod.\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class CholmodSupernodalLLT, class SimplicialLLT\n  */\ntemplate<typename MatrixType_, int UpLo_ = Lower>\nclass CholmodSimplicialLLT : public CholmodBase<MatrixType_, UpLo_, CholmodSimplicialLLT<MatrixType_, UpLo_> >\n{\n    typedef CholmodBase<MatrixType_, UpLo_, CholmodSimplicialLLT> Base;\n    using Base::m_cholmod;\n\n  public:\n\n    typedef MatrixType_ MatrixType;\n\n    CholmodSimplicialLLT() : Base() { init(); }\n\n    CholmodSimplicialLLT(const MatrixType& matrix) : Base()\n    {\n      init();\n      this->compute(matrix);\n    }\n\n    ~CholmodSimplicialLLT() {}\n  protected:\n    void init()\n    {\n      m_cholmod.final_asis = 0;\n      m_cholmod.supernodal = CHOLMOD_SIMPLICIAL;\n      m_cholmod.final_ll = 1;\n    }\n};\n\n\n/** \\ingroup CholmodSupport_Module\n  * \\class CholmodSimplicialLDLT\n  * \\brief A simplicial direct Cholesky (LDLT) factorization and solver based on Cholmod\n  *\n  * This class allows to solve for A.X = B sparse linear problems via a simplicial LDL^T Cholesky factorization\n  * using the Cholmod library.\n  * This simplicial variant is equivalent to Eigen's built-in SimplicialLDLT class. Therefore, it has little practical interest.\n  * The sparse matrix A must be selfadjoint and positive definite. The vectors or matrices\n  * X and B can be either dense or sparse.\n  *\n  * \\tparam MatrixType_ the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam UpLo_ the triangular part that will be used for the computations. It can be Lower\n  *               or Upper. Default is Lower.\n  *\n  * \\implsparsesolverconcept\n  *\n  * This class supports all kind of SparseMatrix<>: row or column major; upper, lower, or both; compressed or non compressed.\n  *\n  * \\warning Only double precision real and complex scalar types are supported by Cholmod.\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class CholmodSupernodalLLT, class SimplicialLDLT\n  */\ntemplate<typename MatrixType_, int UpLo_ = Lower>\nclass CholmodSimplicialLDLT : public CholmodBase<MatrixType_, UpLo_, CholmodSimplicialLDLT<MatrixType_, UpLo_> >\n{\n    typedef CholmodBase<MatrixType_, UpLo_, CholmodSimplicialLDLT> Base;\n    using Base::m_cholmod;\n\n  public:\n\n    typedef MatrixType_ MatrixType;\n\n    CholmodSimplicialLDLT() : Base() { init(); }\n\n    CholmodSimplicialLDLT(const MatrixType& matrix) : Base()\n    {\n      init();\n      this->compute(matrix);\n    }\n\n    ~CholmodSimplicialLDLT() {}\n  protected:\n    void init()\n    {\n      m_cholmod.final_asis = 1;\n      m_cholmod.supernodal = CHOLMOD_SIMPLICIAL;\n    }\n};\n\n/** \\ingroup CholmodSupport_Module\n  * \\class CholmodSupernodalLLT\n  * \\brief A supernodal Cholesky (LLT) factorization and solver based on Cholmod\n  *\n  * This class allows to solve for A.X = B sparse linear problems via a supernodal LL^T Cholesky factorization\n  * using the Cholmod library.\n  * This supernodal variant performs best on dense enough problems, e.g., 3D FEM, or very high order 2D FEM.\n  * The sparse matrix A must be selfadjoint and positive definite. The vectors or matrices\n  * X and B can be either dense or sparse.\n  *\n  * \\tparam MatrixType_ the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam UpLo_ the triangular part that will be used for the computations. It can be Lower\n  *               or Upper. Default is Lower.\n  *\n  * \\implsparsesolverconcept\n  *\n  * This class supports all kind of SparseMatrix<>: row or column major; upper, lower, or both; compressed or non compressed.\n  *\n  * \\warning Only double precision real and complex scalar types are supported by Cholmod.\n  *\n  * \\sa \\ref TutorialSparseSolverConcept\n  */\ntemplate<typename MatrixType_, int UpLo_ = Lower>\nclass CholmodSupernodalLLT : public CholmodBase<MatrixType_, UpLo_, CholmodSupernodalLLT<MatrixType_, UpLo_> >\n{\n    typedef CholmodBase<MatrixType_, UpLo_, CholmodSupernodalLLT> Base;\n    using Base::m_cholmod;\n\n  public:\n\n    typedef MatrixType_ MatrixType;\n\n    CholmodSupernodalLLT() : Base() { init(); }\n\n    CholmodSupernodalLLT(const MatrixType& matrix) : Base()\n    {\n      init();\n      this->compute(matrix);\n    }\n\n    ~CholmodSupernodalLLT() {}\n  protected:\n    void init()\n    {\n      m_cholmod.final_asis = 1;\n      m_cholmod.supernodal = CHOLMOD_SUPERNODAL;\n    }\n};\n\n/** \\ingroup CholmodSupport_Module\n  * \\class CholmodDecomposition\n  * \\brief A general Cholesky factorization and solver based on Cholmod\n  *\n  * This class allows to solve for A.X = B sparse linear problems via a LL^T or LDL^T Cholesky factorization\n  * using the Cholmod library. The sparse matrix A must be selfadjoint and positive definite. The vectors or matrices\n  * X and B can be either dense or sparse.\n  *\n  * This variant permits to change the underlying Cholesky method at runtime.\n  * On the other hand, it does not provide access to the result of the factorization.\n  * The default is to let Cholmod automatically choose between a simplicial and supernodal factorization.\n  *\n  * \\tparam MatrixType_ the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam UpLo_ the triangular part that will be used for the computations. It can be Lower\n  *               or Upper. Default is Lower.\n  *\n  * \\implsparsesolverconcept\n  *\n  * This class supports all kind of SparseMatrix<>: row or column major; upper, lower, or both; compressed or non compressed.\n  *\n  * \\warning Only double precision real and complex scalar types are supported by Cholmod.\n  *\n  * \\sa \\ref TutorialSparseSolverConcept\n  */\ntemplate<typename MatrixType_, int UpLo_ = Lower>\nclass CholmodDecomposition : public CholmodBase<MatrixType_, UpLo_, CholmodDecomposition<MatrixType_, UpLo_> >\n{\n    typedef CholmodBase<MatrixType_, UpLo_, CholmodDecomposition> Base;\n    using Base::m_cholmod;\n\n  public:\n\n    typedef MatrixType_ MatrixType;\n\n    CholmodDecomposition() : Base() { init(); }\n\n    CholmodDecomposition(const MatrixType& matrix) : Base()\n    {\n      init();\n      this->compute(matrix);\n    }\n\n    ~CholmodDecomposition() {}\n\n    void setMode(CholmodMode mode)\n    {\n      switch(mode)\n      {\n        case CholmodAuto:\n          m_cholmod.final_asis = 1;\n          m_cholmod.supernodal = CHOLMOD_AUTO;\n          break;\n        case CholmodSimplicialLLt:\n          m_cholmod.final_asis = 0;\n          m_cholmod.supernodal = CHOLMOD_SIMPLICIAL;\n          m_cholmod.final_ll = 1;\n          break;\n        case CholmodSupernodalLLt:\n          m_cholmod.final_asis = 1;\n          m_cholmod.supernodal = CHOLMOD_SUPERNODAL;\n          break;\n        case CholmodLDLt:\n          m_cholmod.final_asis = 1;\n          m_cholmod.supernodal = CHOLMOD_SIMPLICIAL;\n          break;\n        default:\n          break;\n      }\n    }\n  protected:\n    void init()\n    {\n      m_cholmod.final_asis = 1;\n      m_cholmod.supernodal = CHOLMOD_AUTO;\n    }\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CHOLMODSUPPORT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Eigenvalues/ComplexEigenSolver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Claire Maurice\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010,2012 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_COMPLEX_EIGEN_SOLVER_H\n#define EIGEN_COMPLEX_EIGEN_SOLVER_H\n\n#include \"./ComplexSchur.h\"\n\nnamespace Eigen { \n\n/** \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  *\n  * \\class ComplexEigenSolver\n  *\n  * \\brief Computes eigenvalues and eigenvectors of general complex matrices\n  *\n  * \\tparam MatrixType_ the type of the matrix of which we are\n  * computing the eigendecomposition; this is expected to be an\n  * instantiation of the Matrix class template.\n  *\n  * The eigenvalues and eigenvectors of a matrix \\f$ A \\f$ are scalars\n  * \\f$ \\lambda \\f$ and vectors \\f$ v \\f$ such that \\f$ Av = \\lambda v\n  * \\f$.  If \\f$ D \\f$ is a diagonal matrix with the eigenvalues on\n  * the diagonal, and \\f$ V \\f$ is a matrix with the eigenvectors as\n  * its columns, then \\f$ A V = V D \\f$. The matrix \\f$ V \\f$ is\n  * almost always invertible, in which case we have \\f$ A = V D V^{-1}\n  * \\f$. This is called the eigendecomposition.\n  *\n  * The main function in this class is compute(), which computes the\n  * eigenvalues and eigenvectors of a given function. The\n  * documentation for that function contains an example showing the\n  * main features of the class.\n  *\n  * \\sa class EigenSolver, class SelfAdjointEigenSolver\n  */\ntemplate<typename MatrixType_> class ComplexEigenSolver\n{\n  public:\n\n    /** \\brief Synonym for the template parameter \\p MatrixType_. */\n    typedef MatrixType_ MatrixType;\n\n    enum {\n      RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      Options = MatrixType::Options,\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n\n    /** \\brief Scalar type for matrices of type #MatrixType. */\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n\n    /** \\brief Complex scalar type for #MatrixType.\n      *\n      * This is \\c std::complex<Scalar> if #Scalar is real (e.g.,\n      * \\c float or \\c double) and just \\c Scalar if #Scalar is\n      * complex.\n      */\n    typedef std::complex<RealScalar> ComplexScalar;\n\n    /** \\brief Type for vector of eigenvalues as returned by eigenvalues().\n      *\n      * This is a column vector with entries of type #ComplexScalar.\n      * The length of the vector is the size of #MatrixType.\n      */\n    typedef Matrix<ComplexScalar, ColsAtCompileTime, 1, Options&(~RowMajor), MaxColsAtCompileTime, 1> EigenvalueType;\n\n    /** \\brief Type for matrix of eigenvectors as returned by eigenvectors().\n      *\n      * This is a square matrix with entries of type #ComplexScalar.\n      * The size is the same as the size of #MatrixType.\n      */\n    typedef Matrix<ComplexScalar, RowsAtCompileTime, ColsAtCompileTime, Options, MaxRowsAtCompileTime, MaxColsAtCompileTime> EigenvectorType;\n\n    /** \\brief Default constructor.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via compute().\n      */\n    ComplexEigenSolver()\n            : m_eivec(),\n              m_eivalues(),\n              m_schur(),\n              m_isInitialized(false),\n              m_eigenvectorsOk(false),\n              m_matX()\n    {}\n\n    /** \\brief Default Constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem \\a size.\n      * \\sa ComplexEigenSolver()\n      */\n    explicit ComplexEigenSolver(Index size)\n            : m_eivec(size, size),\n              m_eivalues(size),\n              m_schur(size),\n              m_isInitialized(false),\n              m_eigenvectorsOk(false),\n              m_matX(size, size)\n    {}\n\n    /** \\brief Constructor; computes eigendecomposition of given matrix.\n      *\n      * \\param[in]  matrix  Square matrix whose eigendecomposition is to be computed.\n      * \\param[in]  computeEigenvectors  If true, both the eigenvectors and the\n      *    eigenvalues are computed; if false, only the eigenvalues are\n      *    computed.\n      *\n      * This constructor calls compute() to compute the eigendecomposition.\n      */\n    template<typename InputType>\n    explicit ComplexEigenSolver(const EigenBase<InputType>& matrix, bool computeEigenvectors = true)\n            : m_eivec(matrix.rows(),matrix.cols()),\n              m_eivalues(matrix.cols()),\n              m_schur(matrix.rows()),\n              m_isInitialized(false),\n              m_eigenvectorsOk(false),\n              m_matX(matrix.rows(),matrix.cols())\n    {\n      compute(matrix.derived(), computeEigenvectors);\n    }\n\n    /** \\brief Returns the eigenvectors of given matrix.\n      *\n      * \\returns  A const reference to the matrix whose columns are the eigenvectors.\n      *\n      * \\pre Either the constructor\n      * ComplexEigenSolver(const MatrixType& matrix, bool) or the member\n      * function compute(const MatrixType& matrix, bool) has been called before\n      * to compute the eigendecomposition of a matrix, and\n      * \\p computeEigenvectors was set to true (the default).\n      *\n      * This function returns a matrix whose columns are the eigenvectors. Column\n      * \\f$ k \\f$ is an eigenvector corresponding to eigenvalue number \\f$ k\n      * \\f$ as returned by eigenvalues().  The eigenvectors are normalized to\n      * have (Euclidean) norm equal to one. The matrix returned by this\n      * function is the matrix \\f$ V \\f$ in the eigendecomposition \\f$ A = V D\n      * V^{-1} \\f$, if it exists.\n      *\n      * Example: \\include ComplexEigenSolver_eigenvectors.cpp\n      * Output: \\verbinclude ComplexEigenSolver_eigenvectors.out\n      */\n    const EigenvectorType& eigenvectors() const\n    {\n      eigen_assert(m_isInitialized && \"ComplexEigenSolver is not initialized.\");\n      eigen_assert(m_eigenvectorsOk && \"The eigenvectors have not been computed together with the eigenvalues.\");\n      return m_eivec;\n    }\n\n    /** \\brief Returns the eigenvalues of given matrix.\n      *\n      * \\returns A const reference to the column vector containing the eigenvalues.\n      *\n      * \\pre Either the constructor\n      * ComplexEigenSolver(const MatrixType& matrix, bool) or the member\n      * function compute(const MatrixType& matrix, bool) has been called before\n      * to compute the eigendecomposition of a matrix.\n      *\n      * This function returns a column vector containing the\n      * eigenvalues. Eigenvalues are repeated according to their\n      * algebraic multiplicity, so there are as many eigenvalues as\n      * rows in the matrix. The eigenvalues are not sorted in any particular\n      * order.\n      *\n      * Example: \\include ComplexEigenSolver_eigenvalues.cpp\n      * Output: \\verbinclude ComplexEigenSolver_eigenvalues.out\n      */\n    const EigenvalueType& eigenvalues() const\n    {\n      eigen_assert(m_isInitialized && \"ComplexEigenSolver is not initialized.\");\n      return m_eivalues;\n    }\n\n    /** \\brief Computes eigendecomposition of given matrix.\n      *\n      * \\param[in]  matrix  Square matrix whose eigendecomposition is to be computed.\n      * \\param[in]  computeEigenvectors  If true, both the eigenvectors and the\n      *    eigenvalues are computed; if false, only the eigenvalues are\n      *    computed.\n      * \\returns    Reference to \\c *this\n      *\n      * This function computes the eigenvalues of the complex matrix \\p matrix.\n      * The eigenvalues() function can be used to retrieve them.  If\n      * \\p computeEigenvectors is true, then the eigenvectors are also computed\n      * and can be retrieved by calling eigenvectors().\n      *\n      * The matrix is first reduced to Schur form using the\n      * ComplexSchur class. The Schur decomposition is then used to\n      * compute the eigenvalues and eigenvectors.\n      *\n      * The cost of the computation is dominated by the cost of the\n      * Schur decomposition, which is \\f$ O(n^3) \\f$ where \\f$ n \\f$\n      * is the size of the matrix.\n      *\n      * Example: \\include ComplexEigenSolver_compute.cpp\n      * Output: \\verbinclude ComplexEigenSolver_compute.out\n      */\n    template<typename InputType>\n    ComplexEigenSolver& compute(const EigenBase<InputType>& matrix, bool computeEigenvectors = true);\n\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful, \\c NoConvergence otherwise.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"ComplexEigenSolver is not initialized.\");\n      return m_schur.info();\n    }\n\n    /** \\brief Sets the maximum number of iterations allowed. */\n    ComplexEigenSolver& setMaxIterations(Index maxIters)\n    {\n      m_schur.setMaxIterations(maxIters);\n      return *this;\n    }\n\n    /** \\brief Returns the maximum number of iterations. */\n    Index getMaxIterations()\n    {\n      return m_schur.getMaxIterations();\n    }\n\n  protected:\n    \n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n    }\n    \n    EigenvectorType m_eivec;\n    EigenvalueType m_eivalues;\n    ComplexSchur<MatrixType> m_schur;\n    bool m_isInitialized;\n    bool m_eigenvectorsOk;\n    EigenvectorType m_matX;\n\n  private:\n    void doComputeEigenvectors(RealScalar matrixnorm);\n    void sortEigenvalues(bool computeEigenvectors);\n};\n\n\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nComplexEigenSolver<MatrixType>& \nComplexEigenSolver<MatrixType>::compute(const EigenBase<InputType>& matrix, bool computeEigenvectors)\n{\n  check_template_parameters();\n  \n  // this code is inspired from Jampack\n  eigen_assert(matrix.cols() == matrix.rows());\n\n  // Do a complex Schur decomposition, A = U T U^*\n  // The eigenvalues are on the diagonal of T.\n  m_schur.compute(matrix.derived(), computeEigenvectors);\n\n  if(m_schur.info() == Success)\n  {\n    m_eivalues = m_schur.matrixT().diagonal();\n    if(computeEigenvectors)\n      doComputeEigenvectors(m_schur.matrixT().norm());\n    sortEigenvalues(computeEigenvectors);\n  }\n\n  m_isInitialized = true;\n  m_eigenvectorsOk = computeEigenvectors;\n  return *this;\n}\n\n\ntemplate<typename MatrixType>\nvoid ComplexEigenSolver<MatrixType>::doComputeEigenvectors(RealScalar matrixnorm)\n{\n  const Index n = m_eivalues.size();\n\n  matrixnorm = numext::maxi(matrixnorm,(std::numeric_limits<RealScalar>::min)());\n\n  // Compute X such that T = X D X^(-1), where D is the diagonal of T.\n  // The matrix X is unit triangular.\n  m_matX = EigenvectorType::Zero(n, n);\n  for(Index k=n-1 ; k>=0 ; k--)\n  {\n    m_matX.coeffRef(k,k) = ComplexScalar(1.0,0.0);\n    // Compute X(i,k) using the (i,k) entry of the equation X T = D X\n    for(Index i=k-1 ; i>=0 ; i--)\n    {\n      m_matX.coeffRef(i,k) = -m_schur.matrixT().coeff(i,k);\n      if(k-i-1>0)\n        m_matX.coeffRef(i,k) -= (m_schur.matrixT().row(i).segment(i+1,k-i-1) * m_matX.col(k).segment(i+1,k-i-1)).value();\n      ComplexScalar z = m_schur.matrixT().coeff(i,i) - m_schur.matrixT().coeff(k,k);\n      if(z==ComplexScalar(0))\n      {\n        // If the i-th and k-th eigenvalue are equal, then z equals 0.\n        // Use a small value instead, to prevent division by zero.\n        numext::real_ref(z) = NumTraits<RealScalar>::epsilon() * matrixnorm;\n      }\n      m_matX.coeffRef(i,k) = m_matX.coeff(i,k) / z;\n    }\n  }\n\n  // Compute V as V = U X; now A = U T U^* = U X D X^(-1) U^* = V D V^(-1)\n  m_eivec.noalias() = m_schur.matrixU() * m_matX;\n  // .. and normalize the eigenvectors\n  for(Index k=0 ; k<n ; k++)\n  {\n    m_eivec.col(k).normalize();\n  }\n}\n\n\ntemplate<typename MatrixType>\nvoid ComplexEigenSolver<MatrixType>::sortEigenvalues(bool computeEigenvectors)\n{\n  const Index n =  m_eivalues.size();\n  for (Index i=0; i<n; i++)\n  {\n    Index k;\n    m_eivalues.cwiseAbs().tail(n-i).minCoeff(&k);\n    if (k != 0)\n    {\n      k += i;\n      std::swap(m_eivalues[k],m_eivalues[i]);\n      if(computeEigenvectors)\n\tm_eivec.col(i).swap(m_eivec.col(k));\n    }\n  }\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_COMPLEX_EIGEN_SOLVER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Eigenvalues/ComplexSchur.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Claire Maurice\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010,2012 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_COMPLEX_SCHUR_H\n#define EIGEN_COMPLEX_SCHUR_H\n\n#include \"./HessenbergDecomposition.h\"\n\nnamespace Eigen { \n\nnamespace internal {\ntemplate<typename MatrixType, bool IsComplex> struct complex_schur_reduce_to_hessenberg;\n}\n\n/** \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  *\n  * \\class ComplexSchur\n  *\n  * \\brief Performs a complex Schur decomposition of a real or complex square matrix\n  *\n  * \\tparam MatrixType_ the type of the matrix of which we are\n  * computing the Schur decomposition; this is expected to be an\n  * instantiation of the Matrix class template.\n  *\n  * Given a real or complex square matrix A, this class computes the\n  * Schur decomposition: \\f$ A = U T U^*\\f$ where U is a unitary\n  * complex matrix, and T is a complex upper triangular matrix.  The\n  * diagonal of the matrix T corresponds to the eigenvalues of the\n  * matrix A.\n  *\n  * Call the function compute() to compute the Schur decomposition of\n  * a given matrix. Alternatively, you can use the \n  * ComplexSchur(const MatrixType&, bool) constructor which computes\n  * the Schur decomposition at construction time. Once the\n  * decomposition is computed, you can use the matrixU() and matrixT()\n  * functions to retrieve the matrices U and V in the decomposition.\n  *\n  * \\note This code is inspired from Jampack\n  *\n  * \\sa class RealSchur, class EigenSolver, class ComplexEigenSolver\n  */\ntemplate<typename MatrixType_> class ComplexSchur\n{\n  public:\n    typedef MatrixType_ MatrixType;\n    enum {\n      RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      Options = MatrixType::Options,\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n\n    /** \\brief Scalar type for matrices of type \\p MatrixType_. */\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n\n    /** \\brief Complex scalar type for \\p MatrixType_.\n      *\n      * This is \\c std::complex<Scalar> if #Scalar is real (e.g.,\n      * \\c float or \\c double) and just \\c Scalar if #Scalar is\n      * complex.\n      */\n    typedef std::complex<RealScalar> ComplexScalar;\n\n    /** \\brief Type for the matrices in the Schur decomposition.\n      *\n      * This is a square matrix with entries of type #ComplexScalar. \n      * The size is the same as the size of \\p MatrixType_.\n      */\n    typedef Matrix<ComplexScalar, RowsAtCompileTime, ColsAtCompileTime, Options, MaxRowsAtCompileTime, MaxColsAtCompileTime> ComplexMatrixType;\n\n    /** \\brief Default constructor.\n      *\n      * \\param [in] size  Positive integer, size of the matrix whose Schur decomposition will be computed.\n      *\n      * The default constructor is useful in cases in which the user\n      * intends to perform decompositions via compute().  The \\p size\n      * parameter is only used as a hint. It is not an error to give a\n      * wrong \\p size, but it may impair performance.\n      *\n      * \\sa compute() for an example.\n      */\n    explicit ComplexSchur(Index size = RowsAtCompileTime==Dynamic ? 1 : RowsAtCompileTime)\n      : m_matT(size,size),\n        m_matU(size,size),\n        m_hess(size),\n        m_isInitialized(false),\n        m_matUisUptodate(false),\n        m_maxIters(-1)\n    {}\n\n    /** \\brief Constructor; computes Schur decomposition of given matrix. \n      * \n      * \\param[in]  matrix    Square matrix whose Schur decomposition is to be computed.\n      * \\param[in]  computeU  If true, both T and U are computed; if false, only T is computed.\n      *\n      * This constructor calls compute() to compute the Schur decomposition.\n      *\n      * \\sa matrixT() and matrixU() for examples.\n      */\n    template<typename InputType>\n    explicit ComplexSchur(const EigenBase<InputType>& matrix, bool computeU = true)\n      : m_matT(matrix.rows(),matrix.cols()),\n        m_matU(matrix.rows(),matrix.cols()),\n        m_hess(matrix.rows()),\n        m_isInitialized(false),\n        m_matUisUptodate(false),\n        m_maxIters(-1)\n    {\n      compute(matrix.derived(), computeU);\n    }\n\n    /** \\brief Returns the unitary matrix in the Schur decomposition. \n      *\n      * \\returns A const reference to the matrix U.\n      *\n      * It is assumed that either the constructor\n      * ComplexSchur(const MatrixType& matrix, bool computeU) or the\n      * member function compute(const MatrixType& matrix, bool computeU)\n      * has been called before to compute the Schur decomposition of a\n      * matrix, and that \\p computeU was set to true (the default\n      * value).\n      *\n      * Example: \\include ComplexSchur_matrixU.cpp\n      * Output: \\verbinclude ComplexSchur_matrixU.out\n      */\n    const ComplexMatrixType& matrixU() const\n    {\n      eigen_assert(m_isInitialized && \"ComplexSchur is not initialized.\");\n      eigen_assert(m_matUisUptodate && \"The matrix U has not been computed during the ComplexSchur decomposition.\");\n      return m_matU;\n    }\n\n    /** \\brief Returns the triangular matrix in the Schur decomposition. \n      *\n      * \\returns A const reference to the matrix T.\n      *\n      * It is assumed that either the constructor\n      * ComplexSchur(const MatrixType& matrix, bool computeU) or the\n      * member function compute(const MatrixType& matrix, bool computeU)\n      * has been called before to compute the Schur decomposition of a\n      * matrix.\n      *\n      * Note that this function returns a plain square matrix. If you want to reference\n      * only the upper triangular part, use:\n      * \\code schur.matrixT().triangularView<Upper>() \\endcode \n      *\n      * Example: \\include ComplexSchur_matrixT.cpp\n      * Output: \\verbinclude ComplexSchur_matrixT.out\n      */\n    const ComplexMatrixType& matrixT() const\n    {\n      eigen_assert(m_isInitialized && \"ComplexSchur is not initialized.\");\n      return m_matT;\n    }\n\n    /** \\brief Computes Schur decomposition of given matrix. \n      * \n      * \\param[in]  matrix  Square matrix whose Schur decomposition is to be computed.\n      * \\param[in]  computeU  If true, both T and U are computed; if false, only T is computed.\n\n      * \\returns    Reference to \\c *this\n      *\n      * The Schur decomposition is computed by first reducing the\n      * matrix to Hessenberg form using the class\n      * HessenbergDecomposition. The Hessenberg matrix is then reduced\n      * to triangular form by performing QR iterations with a single\n      * shift. The cost of computing the Schur decomposition depends\n      * on the number of iterations; as a rough guide, it may be taken\n      * on the number of iterations; as a rough guide, it may be taken\n      * to be \\f$25n^3\\f$ complex flops, or \\f$10n^3\\f$ complex flops\n      * if \\a computeU is false.\n      *\n      * Example: \\include ComplexSchur_compute.cpp\n      * Output: \\verbinclude ComplexSchur_compute.out\n      *\n      * \\sa compute(const MatrixType&, bool, Index)\n      */\n    template<typename InputType>\n    ComplexSchur& compute(const EigenBase<InputType>& matrix, bool computeU = true);\n    \n    /** \\brief Compute Schur decomposition from a given Hessenberg matrix\n     *  \\param[in] matrixH Matrix in Hessenberg form H\n     *  \\param[in] matrixQ orthogonal matrix Q that transform a matrix A to H : A = Q H Q^T\n     *  \\param computeU Computes the matriX U of the Schur vectors\n     * \\return Reference to \\c *this\n     * \n     *  This routine assumes that the matrix is already reduced in Hessenberg form matrixH\n     *  using either the class HessenbergDecomposition or another mean. \n     *  It computes the upper quasi-triangular matrix T of the Schur decomposition of H\n     *  When computeU is true, this routine computes the matrix U such that \n     *  A = U T U^T =  (QZ) T (QZ)^T = Q H Q^T where A is the initial matrix\n     * \n     * NOTE Q is referenced if computeU is true; so, if the initial orthogonal matrix\n     * is not available, the user should give an identity matrix (Q.setIdentity())\n     * \n     * \\sa compute(const MatrixType&, bool)\n     */\n    template<typename HessMatrixType, typename OrthMatrixType>\n    ComplexSchur& computeFromHessenberg(const HessMatrixType& matrixH, const OrthMatrixType& matrixQ,  bool computeU=true);\n\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful, \\c NoConvergence otherwise.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"ComplexSchur is not initialized.\");\n      return m_info;\n    }\n\n    /** \\brief Sets the maximum number of iterations allowed. \n      *\n      * If not specified by the user, the maximum number of iterations is m_maxIterationsPerRow times the size\n      * of the matrix.\n      */\n    ComplexSchur& setMaxIterations(Index maxIters)\n    {\n      m_maxIters = maxIters;\n      return *this;\n    }\n\n    /** \\brief Returns the maximum number of iterations. */\n    Index getMaxIterations()\n    {\n      return m_maxIters;\n    }\n\n    /** \\brief Maximum number of iterations per row.\n      *\n      * If not otherwise specified, the maximum number of iterations is this number times the size of the\n      * matrix. It is currently set to 30.\n      */\n    static const int m_maxIterationsPerRow = 30;\n\n  protected:\n    ComplexMatrixType m_matT, m_matU;\n    HessenbergDecomposition<MatrixType> m_hess;\n    ComputationInfo m_info;\n    bool m_isInitialized;\n    bool m_matUisUptodate;\n    Index m_maxIters;\n\n  private:  \n    bool subdiagonalEntryIsNeglegible(Index i);\n    ComplexScalar computeShift(Index iu, Index iter);\n    void reduceToTriangularForm(bool computeU);\n    friend struct internal::complex_schur_reduce_to_hessenberg<MatrixType, NumTraits<Scalar>::IsComplex>;\n};\n\n/** If m_matT(i+1,i) is neglegible in floating point arithmetic\n  * compared to m_matT(i,i) and m_matT(j,j), then set it to zero and\n  * return true, else return false. */\ntemplate<typename MatrixType>\ninline bool ComplexSchur<MatrixType>::subdiagonalEntryIsNeglegible(Index i)\n{\n  RealScalar d = numext::norm1(m_matT.coeff(i,i)) + numext::norm1(m_matT.coeff(i+1,i+1));\n  RealScalar sd = numext::norm1(m_matT.coeff(i+1,i));\n  if (internal::isMuchSmallerThan(sd, d, NumTraits<RealScalar>::epsilon()))\n  {\n    m_matT.coeffRef(i+1,i) = ComplexScalar(0);\n    return true;\n  }\n  return false;\n}\n\n\n/** Compute the shift in the current QR iteration. */\ntemplate<typename MatrixType>\ntypename ComplexSchur<MatrixType>::ComplexScalar ComplexSchur<MatrixType>::computeShift(Index iu, Index iter)\n{\n  using std::abs;\n  if (iter == 10 || iter == 20) \n  {\n    // exceptional shift, taken from http://www.netlib.org/eispack/comqr.f\n    return abs(numext::real(m_matT.coeff(iu,iu-1))) + abs(numext::real(m_matT.coeff(iu-1,iu-2)));\n  }\n\n  // compute the shift as one of the eigenvalues of t, the 2x2\n  // diagonal block on the bottom of the active submatrix\n  Matrix<ComplexScalar,2,2> t = m_matT.template block<2,2>(iu-1,iu-1);\n  RealScalar normt = t.cwiseAbs().sum();\n  t /= normt;     // the normalization by sf is to avoid under/overflow\n\n  ComplexScalar b = t.coeff(0,1) * t.coeff(1,0);\n  ComplexScalar c = t.coeff(0,0) - t.coeff(1,1);\n  ComplexScalar disc = sqrt(c*c + RealScalar(4)*b);\n  ComplexScalar det = t.coeff(0,0) * t.coeff(1,1) - b;\n  ComplexScalar trace = t.coeff(0,0) + t.coeff(1,1);\n  ComplexScalar eival1 = (trace + disc) / RealScalar(2);\n  ComplexScalar eival2 = (trace - disc) / RealScalar(2);\n  RealScalar eival1_norm = numext::norm1(eival1);\n  RealScalar eival2_norm = numext::norm1(eival2);\n  // A division by zero can only occur if eival1==eival2==0.\n  // In this case, det==0, and all we have to do is checking that eival2_norm!=0\n  if(eival1_norm > eival2_norm)\n    eival2 = det / eival1;\n  else if(eival2_norm!=RealScalar(0))\n    eival1 = det / eival2;\n\n  // choose the eigenvalue closest to the bottom entry of the diagonal\n  if(numext::norm1(eival1-t.coeff(1,1)) < numext::norm1(eival2-t.coeff(1,1)))\n    return normt * eival1;\n  else\n    return normt * eival2;\n}\n\n\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nComplexSchur<MatrixType>& ComplexSchur<MatrixType>::compute(const EigenBase<InputType>& matrix, bool computeU)\n{\n  m_matUisUptodate = false;\n  eigen_assert(matrix.cols() == matrix.rows());\n\n  if(matrix.cols() == 1)\n  {\n    m_matT = matrix.derived().template cast<ComplexScalar>();\n    if(computeU)  m_matU = ComplexMatrixType::Identity(1,1);\n    m_info = Success;\n    m_isInitialized = true;\n    m_matUisUptodate = computeU;\n    return *this;\n  }\n\n  internal::complex_schur_reduce_to_hessenberg<MatrixType, NumTraits<Scalar>::IsComplex>::run(*this, matrix.derived(), computeU);\n  computeFromHessenberg(m_matT, m_matU, computeU);\n  return *this;\n}\n\ntemplate<typename MatrixType>\ntemplate<typename HessMatrixType, typename OrthMatrixType>\nComplexSchur<MatrixType>& ComplexSchur<MatrixType>::computeFromHessenberg(const HessMatrixType& matrixH, const OrthMatrixType& matrixQ, bool computeU)\n{\n  m_matT = matrixH;\n  if(computeU)\n    m_matU = matrixQ;\n  reduceToTriangularForm(computeU);\n  return *this;\n}\nnamespace internal {\n\n/* Reduce given matrix to Hessenberg form */\ntemplate<typename MatrixType, bool IsComplex>\nstruct complex_schur_reduce_to_hessenberg\n{\n  // this is the implementation for the case IsComplex = true\n  static void run(ComplexSchur<MatrixType>& _this, const MatrixType& matrix, bool computeU)\n  {\n    _this.m_hess.compute(matrix);\n    _this.m_matT = _this.m_hess.matrixH();\n    if(computeU)  _this.m_matU = _this.m_hess.matrixQ();\n  }\n};\n\ntemplate<typename MatrixType>\nstruct complex_schur_reduce_to_hessenberg<MatrixType, false>\n{\n  static void run(ComplexSchur<MatrixType>& _this, const MatrixType& matrix, bool computeU)\n  {\n    typedef typename ComplexSchur<MatrixType>::ComplexScalar ComplexScalar;\n\n    // Note: m_hess is over RealScalar; m_matT and m_matU is over ComplexScalar\n    _this.m_hess.compute(matrix);\n    _this.m_matT = _this.m_hess.matrixH().template cast<ComplexScalar>();\n    if(computeU)  \n    {\n      // This may cause an allocation which seems to be avoidable\n      MatrixType Q = _this.m_hess.matrixQ(); \n      _this.m_matU = Q.template cast<ComplexScalar>();\n    }\n  }\n};\n\n} // end namespace internal\n\n// Reduce the Hessenberg matrix m_matT to triangular form by QR iteration.\ntemplate<typename MatrixType>\nvoid ComplexSchur<MatrixType>::reduceToTriangularForm(bool computeU)\n{  \n  Index maxIters = m_maxIters;\n  if (maxIters == -1)\n    maxIters = m_maxIterationsPerRow * m_matT.rows();\n\n  // The matrix m_matT is divided in three parts. \n  // Rows 0,...,il-1 are decoupled from the rest because m_matT(il,il-1) is zero. \n  // Rows il,...,iu is the part we are working on (the active submatrix).\n  // Rows iu+1,...,end are already brought in triangular form.\n  Index iu = m_matT.cols() - 1;\n  Index il;\n  Index iter = 0; // number of iterations we are working on the (iu,iu) element\n  Index totalIter = 0; // number of iterations for whole matrix\n\n  while(true)\n  {\n    // find iu, the bottom row of the active submatrix\n    while(iu > 0)\n    {\n      if(!subdiagonalEntryIsNeglegible(iu-1)) break;\n      iter = 0;\n      --iu;\n    }\n\n    // if iu is zero then we are done; the whole matrix is triangularized\n    if(iu==0) break;\n\n    // if we spent too many iterations, we give up\n    iter++;\n    totalIter++;\n    if(totalIter > maxIters) break;\n\n    // find il, the top row of the active submatrix\n    il = iu-1;\n    while(il > 0 && !subdiagonalEntryIsNeglegible(il-1))\n    {\n      --il;\n    }\n\n    /* perform the QR step using Givens rotations. The first rotation\n       creates a bulge; the (il+2,il) element becomes nonzero. This\n       bulge is chased down to the bottom of the active submatrix. */\n\n    ComplexScalar shift = computeShift(iu, iter);\n    JacobiRotation<ComplexScalar> rot;\n    rot.makeGivens(m_matT.coeff(il,il) - shift, m_matT.coeff(il+1,il));\n    m_matT.rightCols(m_matT.cols()-il).applyOnTheLeft(il, il+1, rot.adjoint());\n    m_matT.topRows((std::min)(il+2,iu)+1).applyOnTheRight(il, il+1, rot);\n    if(computeU) m_matU.applyOnTheRight(il, il+1, rot);\n\n    for(Index i=il+1 ; i<iu ; i++)\n    {\n      rot.makeGivens(m_matT.coeffRef(i,i-1), m_matT.coeffRef(i+1,i-1), &m_matT.coeffRef(i,i-1));\n      m_matT.coeffRef(i+1,i-1) = ComplexScalar(0);\n      m_matT.rightCols(m_matT.cols()-i).applyOnTheLeft(i, i+1, rot.adjoint());\n      m_matT.topRows((std::min)(i+2,iu)+1).applyOnTheRight(i, i+1, rot);\n      if(computeU) m_matU.applyOnTheRight(i, i+1, rot);\n    }\n  }\n\n  if(totalIter <= maxIters)\n    m_info = Success;\n  else\n    m_info = NoConvergence;\n\n  m_isInitialized = true;\n  m_matUisUptodate = computeU;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_COMPLEX_SCHUR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Eigenvalues/ComplexSchur_LAPACKE.h",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Eigen bindings to LAPACKe\n *    Complex Schur needed to complex unsymmetrical eigenvalues/eigenvectors.\n ********************************************************************************\n*/\n\n#ifndef EIGEN_COMPLEX_SCHUR_LAPACKE_H\n#define EIGEN_COMPLEX_SCHUR_LAPACKE_H\n\nnamespace Eigen { \n\n/** \\internal Specialization for the data types supported by LAPACKe */\n\n#define EIGEN_LAPACKE_SCHUR_COMPLEX(EIGTYPE, LAPACKE_TYPE, LAPACKE_PREFIX, LAPACKE_PREFIX_U, EIGCOLROW, LAPACKE_COLROW) \\\ntemplate<> template<typename InputType> inline \\\nComplexSchur<Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW> >& \\\nComplexSchur<Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW> >::compute(const EigenBase<InputType>& matrix, bool computeU) \\\n{ \\\n  typedef Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW> MatrixType; \\\n  typedef MatrixType::RealScalar RealScalar; \\\n  typedef std::complex<RealScalar> ComplexScalar; \\\n\\\n  eigen_assert(matrix.cols() == matrix.rows()); \\\n\\\n  m_matUisUptodate = false; \\\n  if(matrix.cols() == 1) \\\n  { \\\n    m_matT = matrix.derived().template cast<ComplexScalar>(); \\\n    if(computeU)  m_matU = ComplexMatrixType::Identity(1,1); \\\n      m_info = Success; \\\n      m_isInitialized = true; \\\n      m_matUisUptodate = computeU; \\\n      return *this; \\\n  } \\\n  lapack_int n = internal::convert_index<lapack_int>(matrix.cols()), sdim, info; \\\n  lapack_int matrix_order = LAPACKE_COLROW; \\\n  char jobvs, sort='N'; \\\n  LAPACK_##LAPACKE_PREFIX_U##_SELECT1 select = 0; \\\n  jobvs = (computeU) ? 'V' : 'N'; \\\n  m_matU.resize(n, n); \\\n  lapack_int ldvs  = internal::convert_index<lapack_int>(m_matU.outerStride()); \\\n  m_matT = matrix; \\\n  lapack_int lda = internal::convert_index<lapack_int>(m_matT.outerStride()); \\\n  Matrix<EIGTYPE, Dynamic, Dynamic> w; \\\n  w.resize(n, 1);\\\n  info = LAPACKE_##LAPACKE_PREFIX##gees( matrix_order, jobvs, sort, select, n, (LAPACKE_TYPE*)m_matT.data(), lda, &sdim, (LAPACKE_TYPE*)w.data(), (LAPACKE_TYPE*)m_matU.data(), ldvs ); \\\n  if(info == 0) \\\n    m_info = Success; \\\n  else \\\n    m_info = NoConvergence; \\\n\\\n  m_isInitialized = true; \\\n  m_matUisUptodate = computeU; \\\n  return *this; \\\n\\\n}\n\nEIGEN_LAPACKE_SCHUR_COMPLEX(dcomplex, lapack_complex_double, z, Z, ColMajor, LAPACK_COL_MAJOR)\nEIGEN_LAPACKE_SCHUR_COMPLEX(scomplex, lapack_complex_float,  c, C, ColMajor, LAPACK_COL_MAJOR)\nEIGEN_LAPACKE_SCHUR_COMPLEX(dcomplex, lapack_complex_double, z, Z, RowMajor, LAPACK_ROW_MAJOR)\nEIGEN_LAPACKE_SCHUR_COMPLEX(scomplex, lapack_complex_float,  c, C, RowMajor, LAPACK_ROW_MAJOR)\n\n} // end namespace Eigen\n\n#endif // EIGEN_COMPLEX_SCHUR_LAPACKE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Eigenvalues/EigenSolver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010,2012 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_EIGENSOLVER_H\n#define EIGEN_EIGENSOLVER_H\n\n#include \"./RealSchur.h\"\n\nnamespace Eigen { \n\n/** \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  *\n  * \\class EigenSolver\n  *\n  * \\brief Computes eigenvalues and eigenvectors of general matrices\n  *\n  * \\tparam MatrixType_ the type of the matrix of which we are computing the\n  * eigendecomposition; this is expected to be an instantiation of the Matrix\n  * class template. Currently, only real matrices are supported.\n  *\n  * The eigenvalues and eigenvectors of a matrix \\f$ A \\f$ are scalars\n  * \\f$ \\lambda \\f$ and vectors \\f$ v \\f$ such that \\f$ Av = \\lambda v \\f$.  If\n  * \\f$ D \\f$ is a diagonal matrix with the eigenvalues on the diagonal, and\n  * \\f$ V \\f$ is a matrix with the eigenvectors as its columns, then \\f$ A V =\n  * V D \\f$. The matrix \\f$ V \\f$ is almost always invertible, in which case we\n  * have \\f$ A = V D V^{-1} \\f$. This is called the eigendecomposition.\n  *\n  * The eigenvalues and eigenvectors of a matrix may be complex, even when the\n  * matrix is real. However, we can choose real matrices \\f$ V \\f$ and \\f$ D\n  * \\f$ satisfying \\f$ A V = V D \\f$, just like the eigendecomposition, if the\n  * matrix \\f$ D \\f$ is not required to be diagonal, but if it is allowed to\n  * have blocks of the form\n  * \\f[ \\begin{bmatrix} u & v \\\\ -v & u \\end{bmatrix} \\f]\n  * (where \\f$ u \\f$ and \\f$ v \\f$ are real numbers) on the diagonal.  These\n  * blocks correspond to complex eigenvalue pairs \\f$ u \\pm iv \\f$. We call\n  * this variant of the eigendecomposition the pseudo-eigendecomposition.\n  *\n  * Call the function compute() to compute the eigenvalues and eigenvectors of\n  * a given matrix. Alternatively, you can use the \n  * EigenSolver(const MatrixType&, bool) constructor which computes the\n  * eigenvalues and eigenvectors at construction time. Once the eigenvalue and\n  * eigenvectors are computed, they can be retrieved with the eigenvalues() and\n  * eigenvectors() functions. The pseudoEigenvalueMatrix() and\n  * pseudoEigenvectors() methods allow the construction of the\n  * pseudo-eigendecomposition.\n  *\n  * The documentation for EigenSolver(const MatrixType&, bool) contains an\n  * example of the typical use of this class.\n  *\n  * \\note The implementation is adapted from\n  * <a href=\"http://math.nist.gov/javanumerics/jama/\">JAMA</a> (public domain).\n  * Their code is based on EISPACK.\n  *\n  * \\sa MatrixBase::eigenvalues(), class ComplexEigenSolver, class SelfAdjointEigenSolver\n  */\ntemplate<typename MatrixType_> class EigenSolver\n{\n  public:\n\n    /** \\brief Synonym for the template parameter \\p MatrixType_. */\n    typedef MatrixType_ MatrixType;\n\n    enum {\n      RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      Options = MatrixType::Options,\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n\n    /** \\brief Scalar type for matrices of type #MatrixType. */\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n\n    /** \\brief Complex scalar type for #MatrixType. \n      *\n      * This is \\c std::complex<Scalar> if #Scalar is real (e.g.,\n      * \\c float or \\c double) and just \\c Scalar if #Scalar is\n      * complex.\n      */\n    typedef std::complex<RealScalar> ComplexScalar;\n\n    /** \\brief Type for vector of eigenvalues as returned by eigenvalues(). \n      *\n      * This is a column vector with entries of type #ComplexScalar.\n      * The length of the vector is the size of #MatrixType.\n      */\n    typedef Matrix<ComplexScalar, ColsAtCompileTime, 1, Options & ~RowMajor, MaxColsAtCompileTime, 1> EigenvalueType;\n\n    /** \\brief Type for matrix of eigenvectors as returned by eigenvectors(). \n      *\n      * This is a square matrix with entries of type #ComplexScalar. \n      * The size is the same as the size of #MatrixType.\n      */\n    typedef Matrix<ComplexScalar, RowsAtCompileTime, ColsAtCompileTime, Options, MaxRowsAtCompileTime, MaxColsAtCompileTime> EigenvectorsType;\n\n    /** \\brief Default constructor.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via EigenSolver::compute(const MatrixType&, bool).\n      *\n      * \\sa compute() for an example.\n      */\n    EigenSolver() : m_eivec(), m_eivalues(), m_isInitialized(false), m_eigenvectorsOk(false), m_realSchur(), m_matT(), m_tmp() {}\n\n    /** \\brief Default constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem \\a size.\n      * \\sa EigenSolver()\n      */\n    explicit EigenSolver(Index size)\n      : m_eivec(size, size),\n        m_eivalues(size),\n        m_isInitialized(false),\n        m_eigenvectorsOk(false),\n        m_realSchur(size),\n        m_matT(size, size), \n        m_tmp(size)\n    {}\n\n    /** \\brief Constructor; computes eigendecomposition of given matrix. \n      * \n      * \\param[in]  matrix  Square matrix whose eigendecomposition is to be computed.\n      * \\param[in]  computeEigenvectors  If true, both the eigenvectors and the\n      *    eigenvalues are computed; if false, only the eigenvalues are\n      *    computed. \n      *\n      * This constructor calls compute() to compute the eigenvalues\n      * and eigenvectors.\n      *\n      * Example: \\include EigenSolver_EigenSolver_MatrixType.cpp\n      * Output: \\verbinclude EigenSolver_EigenSolver_MatrixType.out\n      *\n      * \\sa compute()\n      */\n    template<typename InputType>\n    explicit EigenSolver(const EigenBase<InputType>& matrix, bool computeEigenvectors = true)\n      : m_eivec(matrix.rows(), matrix.cols()),\n        m_eivalues(matrix.cols()),\n        m_isInitialized(false),\n        m_eigenvectorsOk(false),\n        m_realSchur(matrix.cols()),\n        m_matT(matrix.rows(), matrix.cols()), \n        m_tmp(matrix.cols())\n    {\n      compute(matrix.derived(), computeEigenvectors);\n    }\n\n    /** \\brief Returns the eigenvectors of given matrix. \n      *\n      * \\returns  %Matrix whose columns are the (possibly complex) eigenvectors.\n      *\n      * \\pre Either the constructor \n      * EigenSolver(const MatrixType&,bool) or the member function\n      * compute(const MatrixType&, bool) has been called before, and\n      * \\p computeEigenvectors was set to true (the default).\n      *\n      * Column \\f$ k \\f$ of the returned matrix is an eigenvector corresponding\n      * to eigenvalue number \\f$ k \\f$ as returned by eigenvalues().  The\n      * eigenvectors are normalized to have (Euclidean) norm equal to one. The\n      * matrix returned by this function is the matrix \\f$ V \\f$ in the\n      * eigendecomposition \\f$ A = V D V^{-1} \\f$, if it exists.\n      *\n      * Example: \\include EigenSolver_eigenvectors.cpp\n      * Output: \\verbinclude EigenSolver_eigenvectors.out\n      *\n      * \\sa eigenvalues(), pseudoEigenvectors()\n      */\n    EigenvectorsType eigenvectors() const;\n\n    /** \\brief Returns the pseudo-eigenvectors of given matrix. \n      *\n      * \\returns  Const reference to matrix whose columns are the pseudo-eigenvectors.\n      *\n      * \\pre Either the constructor \n      * EigenSolver(const MatrixType&,bool) or the member function\n      * compute(const MatrixType&, bool) has been called before, and\n      * \\p computeEigenvectors was set to true (the default).\n      *\n      * The real matrix \\f$ V \\f$ returned by this function and the\n      * block-diagonal matrix \\f$ D \\f$ returned by pseudoEigenvalueMatrix()\n      * satisfy \\f$ AV = VD \\f$.\n      *\n      * Example: \\include EigenSolver_pseudoEigenvectors.cpp\n      * Output: \\verbinclude EigenSolver_pseudoEigenvectors.out\n      *\n      * \\sa pseudoEigenvalueMatrix(), eigenvectors()\n      */\n    const MatrixType& pseudoEigenvectors() const\n    {\n      eigen_assert(m_isInitialized && \"EigenSolver is not initialized.\");\n      eigen_assert(m_eigenvectorsOk && \"The eigenvectors have not been computed together with the eigenvalues.\");\n      return m_eivec;\n    }\n\n    /** \\brief Returns the block-diagonal matrix in the pseudo-eigendecomposition.\n      *\n      * \\returns  A block-diagonal matrix.\n      *\n      * \\pre Either the constructor \n      * EigenSolver(const MatrixType&,bool) or the member function\n      * compute(const MatrixType&, bool) has been called before.\n      *\n      * The matrix \\f$ D \\f$ returned by this function is real and\n      * block-diagonal. The blocks on the diagonal are either 1-by-1 or 2-by-2\n      * blocks of the form\n      * \\f$ \\begin{bmatrix} u & v \\\\ -v & u \\end{bmatrix} \\f$.\n      * These blocks are not sorted in any particular order.\n      * The matrix \\f$ D \\f$ and the matrix \\f$ V \\f$ returned by\n      * pseudoEigenvectors() satisfy \\f$ AV = VD \\f$.\n      *\n      * \\sa pseudoEigenvectors() for an example, eigenvalues()\n      */\n    MatrixType pseudoEigenvalueMatrix() const;\n\n    /** \\brief Returns the eigenvalues of given matrix. \n      *\n      * \\returns A const reference to the column vector containing the eigenvalues.\n      *\n      * \\pre Either the constructor \n      * EigenSolver(const MatrixType&,bool) or the member function\n      * compute(const MatrixType&, bool) has been called before.\n      *\n      * The eigenvalues are repeated according to their algebraic multiplicity,\n      * so there are as many eigenvalues as rows in the matrix. The eigenvalues \n      * are not sorted in any particular order.\n      *\n      * Example: \\include EigenSolver_eigenvalues.cpp\n      * Output: \\verbinclude EigenSolver_eigenvalues.out\n      *\n      * \\sa eigenvectors(), pseudoEigenvalueMatrix(),\n      *     MatrixBase::eigenvalues()\n      */\n    const EigenvalueType& eigenvalues() const\n    {\n      eigen_assert(m_isInitialized && \"EigenSolver is not initialized.\");\n      return m_eivalues;\n    }\n\n    /** \\brief Computes eigendecomposition of given matrix. \n      * \n      * \\param[in]  matrix  Square matrix whose eigendecomposition is to be computed.\n      * \\param[in]  computeEigenvectors  If true, both the eigenvectors and the\n      *    eigenvalues are computed; if false, only the eigenvalues are\n      *    computed. \n      * \\returns    Reference to \\c *this\n      *\n      * This function computes the eigenvalues of the real matrix \\p matrix.\n      * The eigenvalues() function can be used to retrieve them.  If \n      * \\p computeEigenvectors is true, then the eigenvectors are also computed\n      * and can be retrieved by calling eigenvectors().\n      *\n      * The matrix is first reduced to real Schur form using the RealSchur\n      * class. The Schur decomposition is then used to compute the eigenvalues\n      * and eigenvectors.\n      *\n      * The cost of the computation is dominated by the cost of the\n      * Schur decomposition, which is very approximately \\f$ 25n^3 \\f$\n      * (where \\f$ n \\f$ is the size of the matrix) if \\p computeEigenvectors \n      * is true, and \\f$ 10n^3 \\f$ if \\p computeEigenvectors is false.\n      *\n      * This method reuses of the allocated data in the EigenSolver object.\n      *\n      * Example: \\include EigenSolver_compute.cpp\n      * Output: \\verbinclude EigenSolver_compute.out\n      */\n    template<typename InputType>\n    EigenSolver& compute(const EigenBase<InputType>& matrix, bool computeEigenvectors = true);\n\n    /** \\returns NumericalIssue if the input contains INF or NaN values or overflow occurred. Returns Success otherwise. */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"EigenSolver is not initialized.\");\n      return m_info;\n    }\n\n    /** \\brief Sets the maximum number of iterations allowed. */\n    EigenSolver& setMaxIterations(Index maxIters)\n    {\n      m_realSchur.setMaxIterations(maxIters);\n      return *this;\n    }\n\n    /** \\brief Returns the maximum number of iterations. */\n    Index getMaxIterations()\n    {\n      return m_realSchur.getMaxIterations();\n    }\n\n  private:\n    void doComputeEigenvectors();\n\n  protected:\n    \n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n      EIGEN_STATIC_ASSERT(!NumTraits<Scalar>::IsComplex, NUMERIC_TYPE_MUST_BE_REAL);\n    }\n    \n    MatrixType m_eivec;\n    EigenvalueType m_eivalues;\n    bool m_isInitialized;\n    bool m_eigenvectorsOk;\n    ComputationInfo m_info;\n    RealSchur<MatrixType> m_realSchur;\n    MatrixType m_matT;\n\n    typedef Matrix<Scalar, ColsAtCompileTime, 1, Options & ~RowMajor, MaxColsAtCompileTime, 1> ColumnVectorType;\n    ColumnVectorType m_tmp;\n};\n\ntemplate<typename MatrixType>\nMatrixType EigenSolver<MatrixType>::pseudoEigenvalueMatrix() const\n{\n  eigen_assert(m_isInitialized && \"EigenSolver is not initialized.\");\n  const RealScalar precision = RealScalar(2)*NumTraits<RealScalar>::epsilon();\n  Index n = m_eivalues.rows();\n  MatrixType matD = MatrixType::Zero(n,n);\n  for (Index i=0; i<n; ++i)\n  {\n    if (internal::isMuchSmallerThan(numext::imag(m_eivalues.coeff(i)), numext::real(m_eivalues.coeff(i)), precision))\n      matD.coeffRef(i,i) = numext::real(m_eivalues.coeff(i));\n    else\n    {\n      matD.template block<2,2>(i,i) <<  numext::real(m_eivalues.coeff(i)), numext::imag(m_eivalues.coeff(i)),\n                                       -numext::imag(m_eivalues.coeff(i)), numext::real(m_eivalues.coeff(i));\n      ++i;\n    }\n  }\n  return matD;\n}\n\ntemplate<typename MatrixType>\ntypename EigenSolver<MatrixType>::EigenvectorsType EigenSolver<MatrixType>::eigenvectors() const\n{\n  eigen_assert(m_isInitialized && \"EigenSolver is not initialized.\");\n  eigen_assert(m_eigenvectorsOk && \"The eigenvectors have not been computed together with the eigenvalues.\");\n  const RealScalar precision = RealScalar(2)*NumTraits<RealScalar>::epsilon();\n  Index n = m_eivec.cols();\n  EigenvectorsType matV(n,n);\n  for (Index j=0; j<n; ++j)\n  {\n    if (internal::isMuchSmallerThan(numext::imag(m_eivalues.coeff(j)), numext::real(m_eivalues.coeff(j)), precision) || j+1==n)\n    {\n      // we have a real eigen value\n      matV.col(j) = m_eivec.col(j).template cast<ComplexScalar>();\n      matV.col(j).normalize();\n    }\n    else\n    {\n      // we have a pair of complex eigen values\n      for (Index i=0; i<n; ++i)\n      {\n        matV.coeffRef(i,j)   = ComplexScalar(m_eivec.coeff(i,j),  m_eivec.coeff(i,j+1));\n        matV.coeffRef(i,j+1) = ComplexScalar(m_eivec.coeff(i,j), -m_eivec.coeff(i,j+1));\n      }\n      matV.col(j).normalize();\n      matV.col(j+1).normalize();\n      ++j;\n    }\n  }\n  return matV;\n}\n\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nEigenSolver<MatrixType>& \nEigenSolver<MatrixType>::compute(const EigenBase<InputType>& matrix, bool computeEigenvectors)\n{\n  check_template_parameters();\n  \n  using std::sqrt;\n  using std::abs;\n  using numext::isfinite;\n  eigen_assert(matrix.cols() == matrix.rows());\n\n  // Reduce to real Schur form.\n  m_realSchur.compute(matrix.derived(), computeEigenvectors);\n  \n  m_info = m_realSchur.info();\n\n  if (m_info == Success)\n  {\n    m_matT = m_realSchur.matrixT();\n    if (computeEigenvectors)\n      m_eivec = m_realSchur.matrixU();\n  \n    // Compute eigenvalues from matT\n    m_eivalues.resize(matrix.cols());\n    Index i = 0;\n    while (i < matrix.cols()) \n    {\n      if (i == matrix.cols() - 1 || m_matT.coeff(i+1, i) == Scalar(0)) \n      {\n        m_eivalues.coeffRef(i) = m_matT.coeff(i, i);\n        if(!(isfinite)(m_eivalues.coeffRef(i)))\n        {\n          m_isInitialized = true;\n          m_eigenvectorsOk = false;\n          m_info = NumericalIssue;\n          return *this;\n        }\n        ++i;\n      }\n      else\n      {\n        Scalar p = Scalar(0.5) * (m_matT.coeff(i, i) - m_matT.coeff(i+1, i+1));\n        Scalar z;\n        // Compute z = sqrt(abs(p * p + m_matT.coeff(i+1, i) * m_matT.coeff(i, i+1)));\n        // without overflow\n        {\n          Scalar t0 = m_matT.coeff(i+1, i);\n          Scalar t1 = m_matT.coeff(i, i+1);\n          Scalar maxval = numext::maxi<Scalar>(abs(p),numext::maxi<Scalar>(abs(t0),abs(t1)));\n          t0 /= maxval;\n          t1 /= maxval;\n          Scalar p0 = p/maxval;\n          z = maxval * sqrt(abs(p0 * p0 + t0 * t1));\n        }\n        \n        m_eivalues.coeffRef(i)   = ComplexScalar(m_matT.coeff(i+1, i+1) + p, z);\n        m_eivalues.coeffRef(i+1) = ComplexScalar(m_matT.coeff(i+1, i+1) + p, -z);\n        if(!((isfinite)(m_eivalues.coeffRef(i)) && (isfinite)(m_eivalues.coeffRef(i+1))))\n        {\n          m_isInitialized = true;\n          m_eigenvectorsOk = false;\n          m_info = NumericalIssue;\n          return *this;\n        }\n        i += 2;\n      }\n    }\n    \n    // Compute eigenvectors.\n    if (computeEigenvectors)\n      doComputeEigenvectors();\n  }\n\n  m_isInitialized = true;\n  m_eigenvectorsOk = computeEigenvectors;\n\n  return *this;\n}\n\n\ntemplate<typename MatrixType>\nvoid EigenSolver<MatrixType>::doComputeEigenvectors()\n{\n  using std::abs;\n  const Index size = m_eivec.cols();\n  const Scalar eps = NumTraits<Scalar>::epsilon();\n\n  // inefficient! this is already computed in RealSchur\n  Scalar norm(0);\n  for (Index j = 0; j < size; ++j)\n  {\n    norm += m_matT.row(j).segment((std::max)(j-1,Index(0)), size-(std::max)(j-1,Index(0))).cwiseAbs().sum();\n  }\n  \n  // Backsubstitute to find vectors of upper triangular form\n  if (norm == Scalar(0))\n  {\n    return;\n  }\n\n  for (Index n = size-1; n >= 0; n--)\n  {\n    Scalar p = m_eivalues.coeff(n).real();\n    Scalar q = m_eivalues.coeff(n).imag();\n\n    // Scalar vector\n    if (q == Scalar(0))\n    {\n      Scalar lastr(0), lastw(0);\n      Index l = n;\n\n      m_matT.coeffRef(n,n) = Scalar(1);\n      for (Index i = n-1; i >= 0; i--)\n      {\n        Scalar w = m_matT.coeff(i,i) - p;\n        Scalar r = m_matT.row(i).segment(l,n-l+1).dot(m_matT.col(n).segment(l, n-l+1));\n\n        if (m_eivalues.coeff(i).imag() < Scalar(0))\n        {\n          lastw = w;\n          lastr = r;\n        }\n        else\n        {\n          l = i;\n          if (m_eivalues.coeff(i).imag() == Scalar(0))\n          {\n            if (w != Scalar(0))\n              m_matT.coeffRef(i,n) = -r / w;\n            else\n              m_matT.coeffRef(i,n) = -r / (eps * norm);\n          }\n          else // Solve real equations\n          {\n            Scalar x = m_matT.coeff(i,i+1);\n            Scalar y = m_matT.coeff(i+1,i);\n            Scalar denom = (m_eivalues.coeff(i).real() - p) * (m_eivalues.coeff(i).real() - p) + m_eivalues.coeff(i).imag() * m_eivalues.coeff(i).imag();\n            Scalar t = (x * lastr - lastw * r) / denom;\n            m_matT.coeffRef(i,n) = t;\n            if (abs(x) > abs(lastw))\n              m_matT.coeffRef(i+1,n) = (-r - w * t) / x;\n            else\n              m_matT.coeffRef(i+1,n) = (-lastr - y * t) / lastw;\n          }\n\n          // Overflow control\n          Scalar t = abs(m_matT.coeff(i,n));\n          if ((eps * t) * t > Scalar(1))\n            m_matT.col(n).tail(size-i) /= t;\n        }\n      }\n    }\n    else if (q < Scalar(0) && n > 0) // Complex vector\n    {\n      Scalar lastra(0), lastsa(0), lastw(0);\n      Index l = n-1;\n\n      // Last vector component imaginary so matrix is triangular\n      if (abs(m_matT.coeff(n,n-1)) > abs(m_matT.coeff(n-1,n)))\n      {\n        m_matT.coeffRef(n-1,n-1) = q / m_matT.coeff(n,n-1);\n        m_matT.coeffRef(n-1,n) = -(m_matT.coeff(n,n) - p) / m_matT.coeff(n,n-1);\n      }\n      else\n      {\n        ComplexScalar cc = ComplexScalar(Scalar(0),-m_matT.coeff(n-1,n)) / ComplexScalar(m_matT.coeff(n-1,n-1)-p,q);\n        m_matT.coeffRef(n-1,n-1) = numext::real(cc);\n        m_matT.coeffRef(n-1,n) = numext::imag(cc);\n      }\n      m_matT.coeffRef(n,n-1) = Scalar(0);\n      m_matT.coeffRef(n,n) = Scalar(1);\n      for (Index i = n-2; i >= 0; i--)\n      {\n        Scalar ra = m_matT.row(i).segment(l, n-l+1).dot(m_matT.col(n-1).segment(l, n-l+1));\n        Scalar sa = m_matT.row(i).segment(l, n-l+1).dot(m_matT.col(n).segment(l, n-l+1));\n        Scalar w = m_matT.coeff(i,i) - p;\n\n        if (m_eivalues.coeff(i).imag() < Scalar(0))\n        {\n          lastw = w;\n          lastra = ra;\n          lastsa = sa;\n        }\n        else\n        {\n          l = i;\n          if (m_eivalues.coeff(i).imag() == RealScalar(0))\n          {\n            ComplexScalar cc = ComplexScalar(-ra,-sa) / ComplexScalar(w,q);\n            m_matT.coeffRef(i,n-1) = numext::real(cc);\n            m_matT.coeffRef(i,n) = numext::imag(cc);\n          }\n          else\n          {\n            // Solve complex equations\n            Scalar x = m_matT.coeff(i,i+1);\n            Scalar y = m_matT.coeff(i+1,i);\n            Scalar vr = (m_eivalues.coeff(i).real() - p) * (m_eivalues.coeff(i).real() - p) + m_eivalues.coeff(i).imag() * m_eivalues.coeff(i).imag() - q * q;\n            Scalar vi = (m_eivalues.coeff(i).real() - p) * Scalar(2) * q;\n            if ((vr == Scalar(0)) && (vi == Scalar(0)))\n              vr = eps * norm * (abs(w) + abs(q) + abs(x) + abs(y) + abs(lastw));\n\n            ComplexScalar cc = ComplexScalar(x*lastra-lastw*ra+q*sa,x*lastsa-lastw*sa-q*ra) / ComplexScalar(vr,vi);\n            m_matT.coeffRef(i,n-1) = numext::real(cc);\n            m_matT.coeffRef(i,n) = numext::imag(cc);\n            if (abs(x) > (abs(lastw) + abs(q)))\n            {\n              m_matT.coeffRef(i+1,n-1) = (-ra - w * m_matT.coeff(i,n-1) + q * m_matT.coeff(i,n)) / x;\n              m_matT.coeffRef(i+1,n) = (-sa - w * m_matT.coeff(i,n) - q * m_matT.coeff(i,n-1)) / x;\n            }\n            else\n            {\n              cc = ComplexScalar(-lastra-y*m_matT.coeff(i,n-1),-lastsa-y*m_matT.coeff(i,n)) / ComplexScalar(lastw,q);\n              m_matT.coeffRef(i+1,n-1) = numext::real(cc);\n              m_matT.coeffRef(i+1,n) = numext::imag(cc);\n            }\n          }\n\n          // Overflow control\n          Scalar t = numext::maxi<Scalar>(abs(m_matT.coeff(i,n-1)),abs(m_matT.coeff(i,n)));\n          if ((eps * t) * t > Scalar(1))\n            m_matT.block(i, n-1, size-i, 2) /= t;\n\n        }\n      }\n      \n      // We handled a pair of complex conjugate eigenvalues, so need to skip them both\n      n--;\n    }\n    else\n    {\n      eigen_assert(0 && \"Internal bug in EigenSolver (INF or NaN has not been detected)\"); // this should not happen\n    }\n  }\n\n  // Back transformation to get eigenvectors of original matrix\n  for (Index j = size-1; j >= 0; j--)\n  {\n    m_tmp.noalias() = m_eivec.leftCols(j+1) * m_matT.col(j).segment(0, j+1);\n    m_eivec.col(j) = m_tmp;\n  }\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_EIGENSOLVER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012-2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010,2012 Jitse Niesen <jitse@maths.leeds.ac.uk>\n// Copyright (C) 2016 Tobias Wood <tobias@spinicist.org.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_GENERALIZEDEIGENSOLVER_H\n#define EIGEN_GENERALIZEDEIGENSOLVER_H\n\n#include \"./RealQZ.h\"\n\nnamespace Eigen { \n\n/** \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  *\n  * \\class GeneralizedEigenSolver\n  *\n  * \\brief Computes the generalized eigenvalues and eigenvectors of a pair of general matrices\n  *\n  * \\tparam MatrixType_ the type of the matrices of which we are computing the\n  * eigen-decomposition; this is expected to be an instantiation of the Matrix\n  * class template. Currently, only real matrices are supported.\n  *\n  * The generalized eigenvalues and eigenvectors of a matrix pair \\f$ A \\f$ and \\f$ B \\f$ are scalars\n  * \\f$ \\lambda \\f$ and vectors \\f$ v \\f$ such that \\f$ Av = \\lambda Bv \\f$.  If\n  * \\f$ D \\f$ is a diagonal matrix with the eigenvalues on the diagonal, and\n  * \\f$ V \\f$ is a matrix with the eigenvectors as its columns, then \\f$ A V =\n  * B V D \\f$. The matrix \\f$ V \\f$ is almost always invertible, in which case we\n  * have \\f$ A = B V D V^{-1} \\f$. This is called the generalized eigen-decomposition.\n  *\n  * The generalized eigenvalues and eigenvectors of a matrix pair may be complex, even when the\n  * matrices are real. Moreover, the generalized eigenvalue might be infinite if the matrix B is\n  * singular. To workaround this difficulty, the eigenvalues are provided as a pair of complex \\f$ \\alpha \\f$\n  * and real \\f$ \\beta \\f$ such that: \\f$ \\lambda_i = \\alpha_i / \\beta_i \\f$. If \\f$ \\beta_i \\f$ is (nearly) zero,\n  * then one can consider the well defined left eigenvalue \\f$ \\mu = \\beta_i / \\alpha_i\\f$ such that:\n  * \\f$ \\mu_i A v_i = B v_i \\f$, or even \\f$ \\mu_i u_i^T A  = u_i^T B \\f$ where \\f$ u_i \\f$ is\n  * called the left eigenvector.\n  *\n  * Call the function compute() to compute the generalized eigenvalues and eigenvectors of\n  * a given matrix pair. Alternatively, you can use the\n  * GeneralizedEigenSolver(const MatrixType&, const MatrixType&, bool) constructor which computes the\n  * eigenvalues and eigenvectors at construction time. Once the eigenvalue and\n  * eigenvectors are computed, they can be retrieved with the eigenvalues() and\n  * eigenvectors() functions.\n  *\n  * Here is an usage example of this class:\n  * Example: \\include GeneralizedEigenSolver.cpp\n  * Output: \\verbinclude GeneralizedEigenSolver.out\n  *\n  * \\sa MatrixBase::eigenvalues(), class ComplexEigenSolver, class SelfAdjointEigenSolver\n  */\ntemplate<typename MatrixType_> class GeneralizedEigenSolver\n{\n  public:\n\n    /** \\brief Synonym for the template parameter \\p MatrixType_. */\n    typedef MatrixType_ MatrixType;\n\n    enum {\n      RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      Options = MatrixType::Options,\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n\n    /** \\brief Scalar type for matrices of type #MatrixType. */\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n\n    /** \\brief Complex scalar type for #MatrixType. \n      *\n      * This is \\c std::complex<Scalar> if #Scalar is real (e.g.,\n      * \\c float or \\c double) and just \\c Scalar if #Scalar is\n      * complex.\n      */\n    typedef std::complex<RealScalar> ComplexScalar;\n\n    /** \\brief Type for vector of real scalar values eigenvalues as returned by betas().\n      *\n      * This is a column vector with entries of type #Scalar.\n      * The length of the vector is the size of #MatrixType.\n      */\n    typedef Matrix<Scalar, ColsAtCompileTime, 1, Options & ~RowMajor, MaxColsAtCompileTime, 1> VectorType;\n\n    /** \\brief Type for vector of complex scalar values eigenvalues as returned by alphas().\n      *\n      * This is a column vector with entries of type #ComplexScalar.\n      * The length of the vector is the size of #MatrixType.\n      */\n    typedef Matrix<ComplexScalar, ColsAtCompileTime, 1, Options & ~RowMajor, MaxColsAtCompileTime, 1> ComplexVectorType;\n\n    /** \\brief Expression type for the eigenvalues as returned by eigenvalues().\n      */\n    typedef CwiseBinaryOp<internal::scalar_quotient_op<ComplexScalar,Scalar>,ComplexVectorType,VectorType> EigenvalueType;\n\n    /** \\brief Type for matrix of eigenvectors as returned by eigenvectors(). \n      *\n      * This is a square matrix with entries of type #ComplexScalar. \n      * The size is the same as the size of #MatrixType.\n      */\n    typedef Matrix<ComplexScalar, RowsAtCompileTime, ColsAtCompileTime, Options, MaxRowsAtCompileTime, MaxColsAtCompileTime> EigenvectorsType;\n\n    /** \\brief Default constructor.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via EigenSolver::compute(const MatrixType&, bool).\n      *\n      * \\sa compute() for an example.\n      */\n    GeneralizedEigenSolver()\n      : m_eivec(),\n        m_alphas(),\n        m_betas(),\n        m_valuesOkay(false),\n        m_vectorsOkay(false),\n        m_realQZ()\n    {}\n\n    /** \\brief Default constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem \\a size.\n      * \\sa GeneralizedEigenSolver()\n      */\n    explicit GeneralizedEigenSolver(Index size)\n      : m_eivec(size, size),\n        m_alphas(size),\n        m_betas(size),\n        m_valuesOkay(false),\n        m_vectorsOkay(false),\n        m_realQZ(size),\n        m_tmp(size)\n    {}\n\n    /** \\brief Constructor; computes the generalized eigendecomposition of given matrix pair.\n      * \n      * \\param[in]  A  Square matrix whose eigendecomposition is to be computed.\n      * \\param[in]  B  Square matrix whose eigendecomposition is to be computed.\n      * \\param[in]  computeEigenvectors  If true, both the eigenvectors and the\n      *    eigenvalues are computed; if false, only the eigenvalues are computed.\n      *\n      * This constructor calls compute() to compute the generalized eigenvalues\n      * and eigenvectors.\n      *\n      * \\sa compute()\n      */\n    GeneralizedEigenSolver(const MatrixType& A, const MatrixType& B, bool computeEigenvectors = true)\n      : m_eivec(A.rows(), A.cols()),\n        m_alphas(A.cols()),\n        m_betas(A.cols()),\n        m_valuesOkay(false),\n        m_vectorsOkay(false),\n        m_realQZ(A.cols()),\n        m_tmp(A.cols())\n    {\n      compute(A, B, computeEigenvectors);\n    }\n\n    /* \\brief Returns the computed generalized eigenvectors.\n      *\n      * \\returns  %Matrix whose columns are the (possibly complex) right eigenvectors.\n      * i.e. the eigenvectors that solve (A - l*B)x = 0. The ordering matches the eigenvalues.\n      *\n      * \\pre Either the constructor \n      * GeneralizedEigenSolver(const MatrixType&,const MatrixType&, bool) or the member function\n      * compute(const MatrixType&, const MatrixType& bool) has been called before, and\n      * \\p computeEigenvectors was set to true (the default).\n      *\n      * \\sa eigenvalues()\n      */\n    EigenvectorsType eigenvectors() const {\n      eigen_assert(m_vectorsOkay && \"Eigenvectors for GeneralizedEigenSolver were not calculated.\");\n      return m_eivec;\n    }\n\n    /** \\brief Returns an expression of the computed generalized eigenvalues.\n      *\n      * \\returns An expression of the column vector containing the eigenvalues.\n      *\n      * It is a shortcut for \\code this->alphas().cwiseQuotient(this->betas()); \\endcode\n      * Not that betas might contain zeros. It is therefore not recommended to use this function,\n      * but rather directly deal with the alphas and betas vectors.\n      *\n      * \\pre Either the constructor \n      * GeneralizedEigenSolver(const MatrixType&,const MatrixType&,bool) or the member function\n      * compute(const MatrixType&,const MatrixType&,bool) has been called before.\n      *\n      * The eigenvalues are repeated according to their algebraic multiplicity,\n      * so there are as many eigenvalues as rows in the matrix. The eigenvalues \n      * are not sorted in any particular order.\n      *\n      * \\sa alphas(), betas(), eigenvectors()\n      */\n    EigenvalueType eigenvalues() const\n    {\n      eigen_assert(m_valuesOkay && \"GeneralizedEigenSolver is not initialized.\");\n      return EigenvalueType(m_alphas,m_betas);\n    }\n\n    /** \\returns A const reference to the vectors containing the alpha values\n      *\n      * This vector permits to reconstruct the j-th eigenvalues as alphas(i)/betas(j).\n      *\n      * \\sa betas(), eigenvalues() */\n    ComplexVectorType alphas() const\n    {\n      eigen_assert(m_valuesOkay && \"GeneralizedEigenSolver is not initialized.\");\n      return m_alphas;\n    }\n\n    /** \\returns A const reference to the vectors containing the beta values\n      *\n      * This vector permits to reconstruct the j-th eigenvalues as alphas(i)/betas(j).\n      *\n      * \\sa alphas(), eigenvalues() */\n    VectorType betas() const\n    {\n      eigen_assert(m_valuesOkay && \"GeneralizedEigenSolver is not initialized.\");\n      return m_betas;\n    }\n\n    /** \\brief Computes generalized eigendecomposition of given matrix.\n      * \n      * \\param[in]  A  Square matrix whose eigendecomposition is to be computed.\n      * \\param[in]  B  Square matrix whose eigendecomposition is to be computed.\n      * \\param[in]  computeEigenvectors  If true, both the eigenvectors and the\n      *    eigenvalues are computed; if false, only the eigenvalues are\n      *    computed. \n      * \\returns    Reference to \\c *this\n      *\n      * This function computes the eigenvalues of the real matrix \\p matrix.\n      * The eigenvalues() function can be used to retrieve them.  If \n      * \\p computeEigenvectors is true, then the eigenvectors are also computed\n      * and can be retrieved by calling eigenvectors().\n      *\n      * The matrix is first reduced to real generalized Schur form using the RealQZ\n      * class. The generalized Schur decomposition is then used to compute the eigenvalues\n      * and eigenvectors.\n      *\n      * The cost of the computation is dominated by the cost of the\n      * generalized Schur decomposition.\n      *\n      * This method reuses of the allocated data in the GeneralizedEigenSolver object.\n      */\n    GeneralizedEigenSolver& compute(const MatrixType& A, const MatrixType& B, bool computeEigenvectors = true);\n\n    ComputationInfo info() const\n    {\n      eigen_assert(m_valuesOkay && \"EigenSolver is not initialized.\");\n      return m_realQZ.info();\n    }\n\n    /** Sets the maximal number of iterations allowed.\n    */\n    GeneralizedEigenSolver& setMaxIterations(Index maxIters)\n    {\n      m_realQZ.setMaxIterations(maxIters);\n      return *this;\n    }\n\n  protected:\n    \n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n      EIGEN_STATIC_ASSERT(!NumTraits<Scalar>::IsComplex, NUMERIC_TYPE_MUST_BE_REAL);\n    }\n    \n    EigenvectorsType m_eivec;\n    ComplexVectorType m_alphas;\n    VectorType m_betas;\n    bool m_valuesOkay, m_vectorsOkay;\n    RealQZ<MatrixType> m_realQZ;\n    ComplexVectorType m_tmp;\n};\n\ntemplate<typename MatrixType>\nGeneralizedEigenSolver<MatrixType>&\nGeneralizedEigenSolver<MatrixType>::compute(const MatrixType& A, const MatrixType& B, bool computeEigenvectors)\n{\n  check_template_parameters();\n  \n  using std::sqrt;\n  using std::abs;\n  eigen_assert(A.cols() == A.rows() && B.cols() == A.rows() && B.cols() == B.rows());\n  Index size = A.cols();\n  m_valuesOkay = false;\n  m_vectorsOkay = false;\n  // Reduce to generalized real Schur form:\n  // A = Q S Z and B = Q T Z\n  m_realQZ.compute(A, B, computeEigenvectors);\n  if (m_realQZ.info() == Success)\n  {\n    // Resize storage\n    m_alphas.resize(size);\n    m_betas.resize(size);\n    if (computeEigenvectors)\n    {\n      m_eivec.resize(size,size);\n      m_tmp.resize(size);\n    }\n\n    // Aliases:\n    Map<VectorType> v(reinterpret_cast<Scalar*>(m_tmp.data()), size);\n    ComplexVectorType &cv = m_tmp;\n    const MatrixType &mS = m_realQZ.matrixS();\n    const MatrixType &mT = m_realQZ.matrixT();\n\n    Index i = 0;\n    while (i < size)\n    {\n      if (i == size - 1 || mS.coeff(i+1, i) == Scalar(0))\n      {\n        // Real eigenvalue\n        m_alphas.coeffRef(i) = mS.diagonal().coeff(i);\n        m_betas.coeffRef(i)  = mT.diagonal().coeff(i);\n        if (computeEigenvectors)\n        {\n          v.setConstant(Scalar(0.0));\n          v.coeffRef(i) = Scalar(1.0);\n          // For singular eigenvalues do nothing more\n          if(abs(m_betas.coeffRef(i)) >= (std::numeric_limits<RealScalar>::min)())\n          {\n            // Non-singular eigenvalue\n            const Scalar alpha = real(m_alphas.coeffRef(i));\n            const Scalar beta = m_betas.coeffRef(i);\n            for (Index j = i-1; j >= 0; j--)\n            {\n              const Index st = j+1;\n              const Index sz = i-j;\n              if (j > 0 && mS.coeff(j, j-1) != Scalar(0))\n              {\n                // 2x2 block\n                Matrix<Scalar, 2, 1> rhs = (alpha*mT.template block<2,Dynamic>(j-1,st,2,sz) - beta*mS.template block<2,Dynamic>(j-1,st,2,sz)) .lazyProduct( v.segment(st,sz) );\n                Matrix<Scalar, 2, 2> lhs = beta * mS.template block<2,2>(j-1,j-1) - alpha * mT.template block<2,2>(j-1,j-1);\n                v.template segment<2>(j-1) = lhs.partialPivLu().solve(rhs);\n                j--;\n              }\n              else\n              {\n                v.coeffRef(j) = -v.segment(st,sz).transpose().cwiseProduct(beta*mS.block(j,st,1,sz) - alpha*mT.block(j,st,1,sz)).sum() / (beta*mS.coeffRef(j,j) - alpha*mT.coeffRef(j,j));\n              }\n            }\n          }\n          m_eivec.col(i).real().noalias() = m_realQZ.matrixZ().transpose() * v;\n          m_eivec.col(i).real().normalize();\n          m_eivec.col(i).imag().setConstant(0);\n        }\n        ++i;\n      }\n      else\n      {\n        // We need to extract the generalized eigenvalues of the pair of a general 2x2 block S and a positive diagonal 2x2 block T\n        // Then taking beta=T_00*T_11, we can avoid any division, and alpha is the eigenvalues of A = (U^-1 * S * U) * diag(T_11,T_00):\n\n        // T =  [a 0]\n        //      [0 b]\n        RealScalar a = mT.diagonal().coeff(i),\n                   b = mT.diagonal().coeff(i+1);\n        const RealScalar beta = m_betas.coeffRef(i) = m_betas.coeffRef(i+1) = a*b;\n\n        // ^^ NOTE: using diagonal()(i) instead of coeff(i,i) workarounds a MSVC bug.\n        Matrix<RealScalar,2,2> S2 = mS.template block<2,2>(i,i) * Matrix<Scalar,2,1>(b,a).asDiagonal();\n\n        Scalar p = Scalar(0.5) * (S2.coeff(0,0) - S2.coeff(1,1));\n        Scalar z = sqrt(abs(p * p + S2.coeff(1,0) * S2.coeff(0,1)));\n        const ComplexScalar alpha = ComplexScalar(S2.coeff(1,1) + p, (beta > 0) ? z : -z);\n        m_alphas.coeffRef(i)   = conj(alpha);\n        m_alphas.coeffRef(i+1) = alpha;\n\n        if (computeEigenvectors) {\n          // Compute eigenvector in position (i+1) and then position (i) is just the conjugate\n          cv.setZero();\n          cv.coeffRef(i+1) = Scalar(1.0);\n          // here, the \"static_cast\" workaound expression template issues.\n          cv.coeffRef(i) = -(static_cast<Scalar>(beta*mS.coeffRef(i,i+1)) - alpha*mT.coeffRef(i,i+1))\n                          / (static_cast<Scalar>(beta*mS.coeffRef(i,i))   - alpha*mT.coeffRef(i,i));\n          for (Index j = i-1; j >= 0; j--)\n          {\n            const Index st = j+1;\n            const Index sz = i+1-j;\n            if (j > 0 && mS.coeff(j, j-1) != Scalar(0))\n            {\n              // 2x2 block\n              Matrix<ComplexScalar, 2, 1> rhs = (alpha*mT.template block<2,Dynamic>(j-1,st,2,sz) - beta*mS.template block<2,Dynamic>(j-1,st,2,sz)) .lazyProduct( cv.segment(st,sz) );\n              Matrix<ComplexScalar, 2, 2> lhs = beta * mS.template block<2,2>(j-1,j-1) - alpha * mT.template block<2,2>(j-1,j-1);\n              cv.template segment<2>(j-1) = lhs.partialPivLu().solve(rhs);\n              j--;\n            } else {\n              cv.coeffRef(j) =  cv.segment(st,sz).transpose().cwiseProduct(beta*mS.block(j,st,1,sz) - alpha*mT.block(j,st,1,sz)).sum()\n                              / (alpha*mT.coeffRef(j,j) - static_cast<Scalar>(beta*mS.coeffRef(j,j)));\n            }\n          }\n          m_eivec.col(i+1).noalias() = (m_realQZ.matrixZ().transpose() * cv);\n          m_eivec.col(i+1).normalize();\n          m_eivec.col(i) = m_eivec.col(i+1).conjugate();\n        }\n        i += 2;\n      }\n    }\n\n    m_valuesOkay = true;\n    m_vectorsOkay = computeEigenvectors;\n  }\n  return *this;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_GENERALIZEDEIGENSOLVER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_GENERALIZEDSELFADJOINTEIGENSOLVER_H\n#define EIGEN_GENERALIZEDSELFADJOINTEIGENSOLVER_H\n\n#include \"./Tridiagonalization.h\"\n\nnamespace Eigen { \n\n/** \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  *\n  * \\class GeneralizedSelfAdjointEigenSolver\n  *\n  * \\brief Computes eigenvalues and eigenvectors of the generalized selfadjoint eigen problem\n  *\n  * \\tparam MatrixType_ the type of the matrix of which we are computing the\n  * eigendecomposition; this is expected to be an instantiation of the Matrix\n  * class template.\n  *\n  * This class solves the generalized eigenvalue problem\n  * \\f$ Av = \\lambda Bv \\f$. In this case, the matrix \\f$ A \\f$ should be\n  * selfadjoint and the matrix \\f$ B \\f$ should be positive definite.\n  *\n  * Only the \\b lower \\b triangular \\b part of the input matrix is referenced.\n  *\n  * Call the function compute() to compute the eigenvalues and eigenvectors of\n  * a given matrix. Alternatively, you can use the\n  * GeneralizedSelfAdjointEigenSolver(const MatrixType&, const MatrixType&, int)\n  * constructor which computes the eigenvalues and eigenvectors at construction time.\n  * Once the eigenvalue and eigenvectors are computed, they can be retrieved with the eigenvalues()\n  * and eigenvectors() functions.\n  *\n  * The documentation for GeneralizedSelfAdjointEigenSolver(const MatrixType&, const MatrixType&, int)\n  * contains an example of the typical use of this class.\n  *\n  * \\sa class SelfAdjointEigenSolver, class EigenSolver, class ComplexEigenSolver\n  */\ntemplate<typename MatrixType_>\nclass GeneralizedSelfAdjointEigenSolver : public SelfAdjointEigenSolver<MatrixType_>\n{\n    typedef SelfAdjointEigenSolver<MatrixType_> Base;\n  public:\n\n    typedef MatrixType_ MatrixType;\n\n    /** \\brief Default constructor for fixed-size matrices.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via compute(). This constructor\n      * can only be used if \\p MatrixType_ is a fixed-size matrix; use\n      * GeneralizedSelfAdjointEigenSolver(Index) for dynamic-size matrices.\n      */\n    GeneralizedSelfAdjointEigenSolver() : Base() {}\n\n    /** \\brief Constructor, pre-allocates memory for dynamic-size matrices.\n      *\n      * \\param [in]  size  Positive integer, size of the matrix whose\n      * eigenvalues and eigenvectors will be computed.\n      *\n      * This constructor is useful for dynamic-size matrices, when the user\n      * intends to perform decompositions via compute(). The \\p size\n      * parameter is only used as a hint. It is not an error to give a wrong\n      * \\p size, but it may impair performance.\n      *\n      * \\sa compute() for an example\n      */\n    explicit GeneralizedSelfAdjointEigenSolver(Index size)\n        : Base(size)\n    {}\n\n    /** \\brief Constructor; computes generalized eigendecomposition of given matrix pencil.\n      *\n      * \\param[in]  matA  Selfadjoint matrix in matrix pencil.\n      *                   Only the lower triangular part of the matrix is referenced.\n      * \\param[in]  matB  Positive-definite matrix in matrix pencil.\n      *                   Only the lower triangular part of the matrix is referenced.\n      * \\param[in]  options A or-ed set of flags {#ComputeEigenvectors,#EigenvaluesOnly} | {#Ax_lBx,#ABx_lx,#BAx_lx}.\n      *                     Default is #ComputeEigenvectors|#Ax_lBx.\n      *\n      * This constructor calls compute(const MatrixType&, const MatrixType&, int)\n      * to compute the eigenvalues and (if requested) the eigenvectors of the\n      * generalized eigenproblem \\f$ Ax = \\lambda B x \\f$ with \\a matA the\n      * selfadjoint matrix \\f$ A \\f$ and \\a matB the positive definite matrix\n      * \\f$ B \\f$. Each eigenvector \\f$ x \\f$ satisfies the property\n      * \\f$ x^* B x = 1 \\f$. The eigenvectors are computed if\n      * \\a options contains ComputeEigenvectors.\n      *\n      * In addition, the two following variants can be solved via \\p options:\n      * - \\c ABx_lx: \\f$ ABx = \\lambda x \\f$\n      * - \\c BAx_lx: \\f$ BAx = \\lambda x \\f$\n      *\n      * Example: \\include SelfAdjointEigenSolver_SelfAdjointEigenSolver_MatrixType2.cpp\n      * Output: \\verbinclude SelfAdjointEigenSolver_SelfAdjointEigenSolver_MatrixType2.out\n      *\n      * \\sa compute(const MatrixType&, const MatrixType&, int)\n      */\n    GeneralizedSelfAdjointEigenSolver(const MatrixType& matA, const MatrixType& matB,\n                                      int options = ComputeEigenvectors|Ax_lBx)\n      : Base(matA.cols())\n    {\n      compute(matA, matB, options);\n    }\n\n    /** \\brief Computes generalized eigendecomposition of given matrix pencil.\n      *\n      * \\param[in]  matA  Selfadjoint matrix in matrix pencil.\n      *                   Only the lower triangular part of the matrix is referenced.\n      * \\param[in]  matB  Positive-definite matrix in matrix pencil.\n      *                   Only the lower triangular part of the matrix is referenced.\n      * \\param[in]  options A or-ed set of flags {#ComputeEigenvectors,#EigenvaluesOnly} | {#Ax_lBx,#ABx_lx,#BAx_lx}.\n      *                     Default is #ComputeEigenvectors|#Ax_lBx.\n      *\n      * \\returns    Reference to \\c *this\n      *\n      * According to \\p options, this function computes eigenvalues and (if requested)\n      * the eigenvectors of one of the following three generalized eigenproblems:\n      * - \\c Ax_lBx: \\f$ Ax = \\lambda B x \\f$\n      * - \\c ABx_lx: \\f$ ABx = \\lambda x \\f$\n      * - \\c BAx_lx: \\f$ BAx = \\lambda x \\f$\n      * with \\a matA the selfadjoint matrix \\f$ A \\f$ and \\a matB the positive definite\n      * matrix \\f$ B \\f$.\n      * In addition, each eigenvector \\f$ x \\f$ satisfies the property \\f$ x^* B x = 1 \\f$.\n      *\n      * The eigenvalues() function can be used to retrieve\n      * the eigenvalues. If \\p options contains ComputeEigenvectors, then the\n      * eigenvectors are also computed and can be retrieved by calling\n      * eigenvectors().\n      *\n      * The implementation uses LLT to compute the Cholesky decomposition\n      * \\f$ B = LL^* \\f$ and computes the classical eigendecomposition\n      * of the selfadjoint matrix \\f$ L^{-1} A (L^*)^{-1} \\f$ if \\p options contains Ax_lBx\n      * and of \\f$ L^{*} A L \\f$ otherwise. This solves the\n      * generalized eigenproblem, because any solution of the generalized\n      * eigenproblem \\f$ Ax = \\lambda B x \\f$ corresponds to a solution\n      * \\f$ L^{-1} A (L^*)^{-1} (L^* x) = \\lambda (L^* x) \\f$ of the\n      * eigenproblem for \\f$ L^{-1} A (L^*)^{-1} \\f$. Similar statements\n      * can be made for the two other variants.\n      *\n      * Example: \\include SelfAdjointEigenSolver_compute_MatrixType2.cpp\n      * Output: \\verbinclude SelfAdjointEigenSolver_compute_MatrixType2.out\n      *\n      * \\sa GeneralizedSelfAdjointEigenSolver(const MatrixType&, const MatrixType&, int)\n      */\n    GeneralizedSelfAdjointEigenSolver& compute(const MatrixType& matA, const MatrixType& matB,\n                                               int options = ComputeEigenvectors|Ax_lBx);\n\n  protected:\n\n};\n\n\ntemplate<typename MatrixType>\nGeneralizedSelfAdjointEigenSolver<MatrixType>& GeneralizedSelfAdjointEigenSolver<MatrixType>::\ncompute(const MatrixType& matA, const MatrixType& matB, int options)\n{\n  eigen_assert(matA.cols()==matA.rows() && matB.rows()==matA.rows() && matB.cols()==matB.rows());\n  eigen_assert((options&~(EigVecMask|GenEigMask))==0\n          && (options&EigVecMask)!=EigVecMask\n          && ((options&GenEigMask)==0 || (options&GenEigMask)==Ax_lBx\n           || (options&GenEigMask)==ABx_lx || (options&GenEigMask)==BAx_lx)\n          && \"invalid option parameter\");\n\n  bool computeEigVecs = ((options&EigVecMask)==0) || ((options&EigVecMask)==ComputeEigenvectors);\n\n  // Compute the cholesky decomposition of matB = L L' = U'U\n  LLT<MatrixType> cholB(matB);\n\n  int type = (options&GenEigMask);\n  if(type==0)\n    type = Ax_lBx;\n\n  if(type==Ax_lBx)\n  {\n    // compute C = inv(L) A inv(L')\n    MatrixType matC = matA.template selfadjointView<Lower>();\n    cholB.matrixL().template solveInPlace<OnTheLeft>(matC);\n    cholB.matrixU().template solveInPlace<OnTheRight>(matC);\n\n    Base::compute(matC, computeEigVecs ? ComputeEigenvectors : EigenvaluesOnly );\n\n    // transform back the eigen vectors: evecs = inv(U) * evecs\n    if(computeEigVecs)\n      cholB.matrixU().solveInPlace(Base::m_eivec);\n  }\n  else if(type==ABx_lx)\n  {\n    // compute C = L' A L\n    MatrixType matC = matA.template selfadjointView<Lower>();\n    matC = matC * cholB.matrixL();\n    matC = cholB.matrixU() * matC;\n\n    Base::compute(matC, computeEigVecs ? ComputeEigenvectors : EigenvaluesOnly);\n\n    // transform back the eigen vectors: evecs = inv(U) * evecs\n    if(computeEigVecs)\n      cholB.matrixU().solveInPlace(Base::m_eivec);\n  }\n  else if(type==BAx_lx)\n  {\n    // compute C = L' A L\n    MatrixType matC = matA.template selfadjointView<Lower>();\n    matC = matC * cholB.matrixL();\n    matC = cholB.matrixU() * matC;\n\n    Base::compute(matC, computeEigVecs ? ComputeEigenvectors : EigenvaluesOnly);\n\n    // transform back the eigen vectors: evecs = L * evecs\n    if(computeEigVecs)\n      Base::m_eivec = cholB.matrixL() * Base::m_eivec;\n  }\n\n  return *this;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_GENERALIZEDSELFADJOINTEIGENSOLVER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Eigenvalues/HessenbergDecomposition.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_HESSENBERGDECOMPOSITION_H\n#define EIGEN_HESSENBERGDECOMPOSITION_H\n\nnamespace Eigen { \n\nnamespace internal {\n  \ntemplate<typename MatrixType> struct HessenbergDecompositionMatrixHReturnType;\ntemplate<typename MatrixType>\nstruct traits<HessenbergDecompositionMatrixHReturnType<MatrixType> >\n{\n  typedef MatrixType ReturnType;\n};\n\n}\n\n/** \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  *\n  * \\class HessenbergDecomposition\n  *\n  * \\brief Reduces a square matrix to Hessenberg form by an orthogonal similarity transformation\n  *\n  * \\tparam MatrixType_ the type of the matrix of which we are computing the Hessenberg decomposition\n  *\n  * This class performs an Hessenberg decomposition of a matrix \\f$ A \\f$. In\n  * the real case, the Hessenberg decomposition consists of an orthogonal\n  * matrix \\f$ Q \\f$ and a Hessenberg matrix \\f$ H \\f$ such that \\f$ A = Q H\n  * Q^T \\f$. An orthogonal matrix is a matrix whose inverse equals its\n  * transpose (\\f$ Q^{-1} = Q^T \\f$). A Hessenberg matrix has zeros below the\n  * subdiagonal, so it is almost upper triangular. The Hessenberg decomposition\n  * of a complex matrix is \\f$ A = Q H Q^* \\f$ with \\f$ Q \\f$ unitary (that is,\n  * \\f$ Q^{-1} = Q^* \\f$).\n  *\n  * Call the function compute() to compute the Hessenberg decomposition of a\n  * given matrix. Alternatively, you can use the\n  * HessenbergDecomposition(const MatrixType&) constructor which computes the\n  * Hessenberg decomposition at construction time. Once the decomposition is\n  * computed, you can use the matrixH() and matrixQ() functions to construct\n  * the matrices H and Q in the decomposition.\n  *\n  * The documentation for matrixH() contains an example of the typical use of\n  * this class.\n  *\n  * \\sa class ComplexSchur, class Tridiagonalization, \\ref QR_Module \"QR Module\"\n  */\ntemplate<typename MatrixType_> class HessenbergDecomposition\n{\n  public:\n\n    /** \\brief Synonym for the template parameter \\p MatrixType_. */\n    typedef MatrixType_ MatrixType;\n\n    enum {\n      Size = MatrixType::RowsAtCompileTime,\n      SizeMinusOne = Size == Dynamic ? Dynamic : Size - 1,\n      Options = MatrixType::Options,\n      MaxSize = MatrixType::MaxRowsAtCompileTime,\n      MaxSizeMinusOne = MaxSize == Dynamic ? Dynamic : MaxSize - 1\n    };\n\n    /** \\brief Scalar type for matrices of type #MatrixType. */\n    typedef typename MatrixType::Scalar Scalar;\n    typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n\n    /** \\brief Type for vector of Householder coefficients.\n      *\n      * This is column vector with entries of type #Scalar. The length of the\n      * vector is one less than the size of #MatrixType, if it is a fixed-side\n      * type.\n      */\n    typedef Matrix<Scalar, SizeMinusOne, 1, Options & ~RowMajor, MaxSizeMinusOne, 1> CoeffVectorType;\n\n    /** \\brief Return type of matrixQ() */\n    typedef HouseholderSequence<MatrixType,typename internal::remove_all<typename CoeffVectorType::ConjugateReturnType>::type> HouseholderSequenceType;\n    \n    typedef internal::HessenbergDecompositionMatrixHReturnType<MatrixType> MatrixHReturnType;\n\n    /** \\brief Default constructor; the decomposition will be computed later.\n      *\n      * \\param [in] size  The size of the matrix whose Hessenberg decomposition will be computed.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via compute().  The \\p size parameter is only\n      * used as a hint. It is not an error to give a wrong \\p size, but it may\n      * impair performance.\n      *\n      * \\sa compute() for an example.\n      */\n    explicit HessenbergDecomposition(Index size = Size==Dynamic ? 2 : Size)\n      : m_matrix(size,size),\n        m_temp(size),\n        m_isInitialized(false)\n    {\n      if(size>1)\n        m_hCoeffs.resize(size-1);\n    }\n\n    /** \\brief Constructor; computes Hessenberg decomposition of given matrix.\n      *\n      * \\param[in]  matrix  Square matrix whose Hessenberg decomposition is to be computed.\n      *\n      * This constructor calls compute() to compute the Hessenberg\n      * decomposition.\n      *\n      * \\sa matrixH() for an example.\n      */\n    template<typename InputType>\n    explicit HessenbergDecomposition(const EigenBase<InputType>& matrix)\n      : m_matrix(matrix.derived()),\n        m_temp(matrix.rows()),\n        m_isInitialized(false)\n    {\n      if(matrix.rows()<2)\n      {\n        m_isInitialized = true;\n        return;\n      }\n      m_hCoeffs.resize(matrix.rows()-1,1);\n      _compute(m_matrix, m_hCoeffs, m_temp);\n      m_isInitialized = true;\n    }\n\n    /** \\brief Computes Hessenberg decomposition of given matrix.\n      *\n      * \\param[in]  matrix  Square matrix whose Hessenberg decomposition is to be computed.\n      * \\returns    Reference to \\c *this\n      *\n      * The Hessenberg decomposition is computed by bringing the columns of the\n      * matrix successively in the required form using Householder reflections\n      * (see, e.g., Algorithm 7.4.2 in Golub \\& Van Loan, <i>%Matrix\n      * Computations</i>). The cost is \\f$ 10n^3/3 \\f$ flops, where \\f$ n \\f$\n      * denotes the size of the given matrix.\n      *\n      * This method reuses of the allocated data in the HessenbergDecomposition\n      * object.\n      *\n      * Example: \\include HessenbergDecomposition_compute.cpp\n      * Output: \\verbinclude HessenbergDecomposition_compute.out\n      */\n    template<typename InputType>\n    HessenbergDecomposition& compute(const EigenBase<InputType>& matrix)\n    {\n      m_matrix = matrix.derived();\n      if(matrix.rows()<2)\n      {\n        m_isInitialized = true;\n        return *this;\n      }\n      m_hCoeffs.resize(matrix.rows()-1,1);\n      _compute(m_matrix, m_hCoeffs, m_temp);\n      m_isInitialized = true;\n      return *this;\n    }\n\n    /** \\brief Returns the Householder coefficients.\n      *\n      * \\returns a const reference to the vector of Householder coefficients\n      *\n      * \\pre Either the constructor HessenbergDecomposition(const MatrixType&)\n      * or the member function compute(const MatrixType&) has been called\n      * before to compute the Hessenberg decomposition of a matrix.\n      *\n      * The Householder coefficients allow the reconstruction of the matrix\n      * \\f$ Q \\f$ in the Hessenberg decomposition from the packed data.\n      *\n      * \\sa packedMatrix(), \\ref Householder_Module \"Householder module\"\n      */\n    const CoeffVectorType& householderCoefficients() const\n    {\n      eigen_assert(m_isInitialized && \"HessenbergDecomposition is not initialized.\");\n      return m_hCoeffs;\n    }\n\n    /** \\brief Returns the internal representation of the decomposition\n      *\n      *\t\\returns a const reference to a matrix with the internal representation\n      *\t         of the decomposition.\n      *\n      * \\pre Either the constructor HessenbergDecomposition(const MatrixType&)\n      * or the member function compute(const MatrixType&) has been called\n      * before to compute the Hessenberg decomposition of a matrix.\n      *\n      * The returned matrix contains the following information:\n      *  - the upper part and lower sub-diagonal represent the Hessenberg matrix H\n      *  - the rest of the lower part contains the Householder vectors that, combined with\n      *    Householder coefficients returned by householderCoefficients(),\n      *    allows to reconstruct the matrix Q as\n      *       \\f$ Q = H_{N-1} \\ldots H_1 H_0 \\f$.\n      *    Here, the matrices \\f$ H_i \\f$ are the Householder transformations\n      *       \\f$ H_i = (I - h_i v_i v_i^T) \\f$\n      *    where \\f$ h_i \\f$ is the \\f$ i \\f$th Householder coefficient and\n      *    \\f$ v_i \\f$ is the Householder vector defined by\n      *       \\f$ v_i = [ 0, \\ldots, 0, 1, M(i+2,i), \\ldots, M(N-1,i) ]^T \\f$\n      *    with M the matrix returned by this function.\n      *\n      * See LAPACK for further details on this packed storage.\n      *\n      * Example: \\include HessenbergDecomposition_packedMatrix.cpp\n      * Output: \\verbinclude HessenbergDecomposition_packedMatrix.out\n      *\n      * \\sa householderCoefficients()\n      */\n    const MatrixType& packedMatrix() const\n    {\n      eigen_assert(m_isInitialized && \"HessenbergDecomposition is not initialized.\");\n      return m_matrix;\n    }\n\n    /** \\brief Reconstructs the orthogonal matrix Q in the decomposition\n      *\n      * \\returns object representing the matrix Q\n      *\n      * \\pre Either the constructor HessenbergDecomposition(const MatrixType&)\n      * or the member function compute(const MatrixType&) has been called\n      * before to compute the Hessenberg decomposition of a matrix.\n      *\n      * This function returns a light-weight object of template class\n      * HouseholderSequence. You can either apply it directly to a matrix or\n      * you can convert it to a matrix of type #MatrixType.\n      *\n      * \\sa matrixH() for an example, class HouseholderSequence\n      */\n    HouseholderSequenceType matrixQ() const\n    {\n      eigen_assert(m_isInitialized && \"HessenbergDecomposition is not initialized.\");\n      return HouseholderSequenceType(m_matrix, m_hCoeffs.conjugate())\n             .setLength(m_matrix.rows() - 1)\n             .setShift(1);\n    }\n\n    /** \\brief Constructs the Hessenberg matrix H in the decomposition\n      *\n      * \\returns expression object representing the matrix H\n      *\n      * \\pre Either the constructor HessenbergDecomposition(const MatrixType&)\n      * or the member function compute(const MatrixType&) has been called\n      * before to compute the Hessenberg decomposition of a matrix.\n      *\n      * The object returned by this function constructs the Hessenberg matrix H\n      * when it is assigned to a matrix or otherwise evaluated. The matrix H is\n      * constructed from the packed matrix as returned by packedMatrix(): The\n      * upper part (including the subdiagonal) of the packed matrix contains\n      * the matrix H. It may sometimes be better to directly use the packed\n      * matrix instead of constructing the matrix H.\n      *\n      * Example: \\include HessenbergDecomposition_matrixH.cpp\n      * Output: \\verbinclude HessenbergDecomposition_matrixH.out\n      *\n      * \\sa matrixQ(), packedMatrix()\n      */\n    MatrixHReturnType matrixH() const\n    {\n      eigen_assert(m_isInitialized && \"HessenbergDecomposition is not initialized.\");\n      return MatrixHReturnType(*this);\n    }\n\n  private:\n\n    typedef Matrix<Scalar, 1, Size, int(Options) | int(RowMajor), 1, MaxSize> VectorType;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    static void _compute(MatrixType& matA, CoeffVectorType& hCoeffs, VectorType& temp);\n\n  protected:\n    MatrixType m_matrix;\n    CoeffVectorType m_hCoeffs;\n    VectorType m_temp;\n    bool m_isInitialized;\n};\n\n/** \\internal\n  * Performs a tridiagonal decomposition of \\a matA in place.\n  *\n  * \\param matA the input selfadjoint matrix\n  * \\param hCoeffs returned Householder coefficients\n  *\n  * The result is written in the lower triangular part of \\a matA.\n  *\n  * Implemented from Golub's \"%Matrix Computations\", algorithm 8.3.1.\n  *\n  * \\sa packedMatrix()\n  */\ntemplate<typename MatrixType>\nvoid HessenbergDecomposition<MatrixType>::_compute(MatrixType& matA, CoeffVectorType& hCoeffs, VectorType& temp)\n{\n  eigen_assert(matA.rows()==matA.cols());\n  Index n = matA.rows();\n  temp.resize(n);\n  for (Index i = 0; i<n-1; ++i)\n  {\n    // let's consider the vector v = i-th column starting at position i+1\n    Index remainingSize = n-i-1;\n    RealScalar beta;\n    Scalar h;\n    matA.col(i).tail(remainingSize).makeHouseholderInPlace(h, beta);\n    matA.col(i).coeffRef(i+1) = beta;\n    hCoeffs.coeffRef(i) = h;\n\n    // Apply similarity transformation to remaining columns,\n    // i.e., compute A = H A H'\n\n    // A = H A\n    matA.bottomRightCorner(remainingSize, remainingSize)\n        .applyHouseholderOnTheLeft(matA.col(i).tail(remainingSize-1), h, &temp.coeffRef(0));\n\n    // A = A H'\n    matA.rightCols(remainingSize)\n        .applyHouseholderOnTheRight(matA.col(i).tail(remainingSize-1), numext::conj(h), &temp.coeffRef(0));\n  }\n}\n\nnamespace internal {\n\n/** \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  *\n  * \\brief Expression type for return value of HessenbergDecomposition::matrixH()\n  *\n  * \\tparam MatrixType type of matrix in the Hessenberg decomposition\n  *\n  * Objects of this type represent the Hessenberg matrix in the Hessenberg\n  * decomposition of some matrix. The object holds a reference to the\n  * HessenbergDecomposition class until the it is assigned or evaluated for\n  * some other reason (the reference should remain valid during the life time\n  * of this object). This class is the return type of\n  * HessenbergDecomposition::matrixH(); there is probably no other use for this\n  * class.\n  */\ntemplate<typename MatrixType> struct HessenbergDecompositionMatrixHReturnType\n: public ReturnByValue<HessenbergDecompositionMatrixHReturnType<MatrixType> >\n{\n  public:\n    /** \\brief Constructor.\n      *\n      * \\param[in] hess  Hessenberg decomposition\n      */\n    HessenbergDecompositionMatrixHReturnType(const HessenbergDecomposition<MatrixType>& hess) : m_hess(hess) { }\n\n    /** \\brief Hessenberg matrix in decomposition.\n      *\n      * \\param[out] result  Hessenberg matrix in decomposition \\p hess which\n      *                     was passed to the constructor\n      */\n    template <typename ResultType>\n    inline void evalTo(ResultType& result) const\n    {\n      result = m_hess.packedMatrix();\n      Index n = result.rows();\n      if (n>2)\n        result.bottomLeftCorner(n-2, n-2).template triangularView<Lower>().setZero();\n    }\n\n    Index rows() const { return m_hess.packedMatrix().rows(); }\n    Index cols() const { return m_hess.packedMatrix().cols(); }\n\n  protected:\n    const HessenbergDecomposition<MatrixType>& m_hess;\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_HESSENBERGDECOMPOSITION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MATRIXBASEEIGENVALUES_H\n#define EIGEN_MATRIXBASEEIGENVALUES_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate<typename Derived, bool IsComplex>\nstruct eigenvalues_selector\n{\n  // this is the implementation for the case IsComplex = true\n  static inline typename MatrixBase<Derived>::EigenvaluesReturnType const\n  run(const MatrixBase<Derived>& m)\n  {\n    typedef typename Derived::PlainObject PlainObject;\n    PlainObject m_eval(m);\n    return ComplexEigenSolver<PlainObject>(m_eval, false).eigenvalues();\n  }\n};\n\ntemplate<typename Derived>\nstruct eigenvalues_selector<Derived, false>\n{\n  static inline typename MatrixBase<Derived>::EigenvaluesReturnType const\n  run(const MatrixBase<Derived>& m)\n  {\n    typedef typename Derived::PlainObject PlainObject;\n    PlainObject m_eval(m);\n    return EigenSolver<PlainObject>(m_eval, false).eigenvalues();\n  }\n};\n\n} // end namespace internal\n\n/** \\brief Computes the eigenvalues of a matrix \n  * \\returns Column vector containing the eigenvalues.\n  *\n  * \\eigenvalues_module\n  * This function computes the eigenvalues with the help of the EigenSolver\n  * class (for real matrices) or the ComplexEigenSolver class (for complex\n  * matrices). \n  *\n  * The eigenvalues are repeated according to their algebraic multiplicity,\n  * so there are as many eigenvalues as rows in the matrix.\n  *\n  * The SelfAdjointView class provides a better algorithm for selfadjoint\n  * matrices.\n  *\n  * Example: \\include MatrixBase_eigenvalues.cpp\n  * Output: \\verbinclude MatrixBase_eigenvalues.out\n  *\n  * \\sa EigenSolver::eigenvalues(), ComplexEigenSolver::eigenvalues(),\n  *     SelfAdjointView::eigenvalues()\n  */\ntemplate<typename Derived>\ninline typename MatrixBase<Derived>::EigenvaluesReturnType\nMatrixBase<Derived>::eigenvalues() const\n{\n  return internal::eigenvalues_selector<Derived, NumTraits<Scalar>::IsComplex>::run(derived());\n}\n\n/** \\brief Computes the eigenvalues of a matrix\n  * \\returns Column vector containing the eigenvalues.\n  *\n  * \\eigenvalues_module\n  * This function computes the eigenvalues with the help of the\n  * SelfAdjointEigenSolver class.  The eigenvalues are repeated according to\n  * their algebraic multiplicity, so there are as many eigenvalues as rows in\n  * the matrix.\n  *\n  * Example: \\include SelfAdjointView_eigenvalues.cpp\n  * Output: \\verbinclude SelfAdjointView_eigenvalues.out\n  *\n  * \\sa SelfAdjointEigenSolver::eigenvalues(), MatrixBase::eigenvalues()\n  */\ntemplate<typename MatrixType, unsigned int UpLo> \nEIGEN_DEVICE_FUNC inline typename SelfAdjointView<MatrixType, UpLo>::EigenvaluesReturnType\nSelfAdjointView<MatrixType, UpLo>::eigenvalues() const\n{\n  PlainObject thisAsMatrix(*this);\n  return SelfAdjointEigenSolver<PlainObject>(thisAsMatrix, false).eigenvalues();\n}\n\n\n\n/** \\brief Computes the L2 operator norm\n  * \\returns Operator norm of the matrix.\n  *\n  * \\eigenvalues_module\n  * This function computes the L2 operator norm of a matrix, which is also\n  * known as the spectral norm. The norm of a matrix \\f$ A \\f$ is defined to be\n  * \\f[ \\|A\\|_2 = \\max_x \\frac{\\|Ax\\|_2}{\\|x\\|_2} \\f]\n  * where the maximum is over all vectors and the norm on the right is the\n  * Euclidean vector norm. The norm equals the largest singular value, which is\n  * the square root of the largest eigenvalue of the positive semi-definite\n  * matrix \\f$ A^*A \\f$.\n  *\n  * The current implementation uses the eigenvalues of \\f$ A^*A \\f$, as computed\n  * by SelfAdjointView::eigenvalues(), to compute the operator norm of a\n  * matrix.  The SelfAdjointView class provides a better algorithm for\n  * selfadjoint matrices.\n  *\n  * Example: \\include MatrixBase_operatorNorm.cpp\n  * Output: \\verbinclude MatrixBase_operatorNorm.out\n  *\n  * \\sa SelfAdjointView::eigenvalues(), SelfAdjointView::operatorNorm()\n  */\ntemplate<typename Derived>\ninline typename MatrixBase<Derived>::RealScalar\nMatrixBase<Derived>::operatorNorm() const\n{\n  using std::sqrt;\n  typename Derived::PlainObject m_eval(derived());\n  // FIXME if it is really guaranteed that the eigenvalues are already sorted,\n  // then we don't need to compute a maxCoeff() here, comparing the 1st and last ones is enough.\n  return sqrt((m_eval*m_eval.adjoint())\n                 .eval()\n\t\t .template selfadjointView<Lower>()\n\t\t .eigenvalues()\n\t\t .maxCoeff()\n\t\t );\n}\n\n/** \\brief Computes the L2 operator norm\n  * \\returns Operator norm of the matrix.\n  *\n  * \\eigenvalues_module\n  * This function computes the L2 operator norm of a self-adjoint matrix. For a\n  * self-adjoint matrix, the operator norm is the largest eigenvalue.\n  *\n  * The current implementation uses the eigenvalues of the matrix, as computed\n  * by eigenvalues(), to compute the operator norm of the matrix.\n  *\n  * Example: \\include SelfAdjointView_operatorNorm.cpp\n  * Output: \\verbinclude SelfAdjointView_operatorNorm.out\n  *\n  * \\sa eigenvalues(), MatrixBase::operatorNorm()\n  */\ntemplate<typename MatrixType, unsigned int UpLo>\nEIGEN_DEVICE_FUNC inline typename SelfAdjointView<MatrixType, UpLo>::RealScalar\nSelfAdjointView<MatrixType, UpLo>::operatorNorm() const\n{\n  return eigenvalues().cwiseAbs().maxCoeff();\n}\n\n} // end namespace Eigen\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Eigenvalues/RealQZ.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Alexey Korepanov <kaikaikai@yandex.ru>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_REAL_QZ_H\n#define EIGEN_REAL_QZ_H\n\nnamespace Eigen {\n\n  /** \\eigenvalues_module \\ingroup Eigenvalues_Module\n   *\n   *\n   * \\class RealQZ\n   *\n   * \\brief Performs a real QZ decomposition of a pair of square matrices\n   *\n   * \\tparam MatrixType_ the type of the matrix of which we are computing the\n   * real QZ decomposition; this is expected to be an instantiation of the\n   * Matrix class template.\n   *\n   * Given a real square matrices A and B, this class computes the real QZ\n   * decomposition: \\f$ A = Q S Z \\f$, \\f$ B = Q T Z \\f$ where Q and Z are\n   * real orthogonal matrixes, T is upper-triangular matrix, and S is upper\n   * quasi-triangular matrix. An orthogonal matrix is a matrix whose\n   * inverse is equal to its transpose, \\f$ U^{-1} = U^T \\f$. A quasi-triangular\n   * matrix is a block-triangular matrix whose diagonal consists of 1-by-1\n   * blocks and 2-by-2 blocks where further reduction is impossible due to\n   * complex eigenvalues. \n   *\n   * The eigenvalues of the pencil \\f$ A - z B \\f$ can be obtained from\n   * 1x1 and 2x2 blocks on the diagonals of S and T.\n   *\n   * Call the function compute() to compute the real QZ decomposition of a\n   * given pair of matrices. Alternatively, you can use the \n   * RealQZ(const MatrixType& B, const MatrixType& B, bool computeQZ)\n   * constructor which computes the real QZ decomposition at construction\n   * time. Once the decomposition is computed, you can use the matrixS(),\n   * matrixT(), matrixQ() and matrixZ() functions to retrieve the matrices\n   * S, T, Q and Z in the decomposition. If computeQZ==false, some time\n   * is saved by not computing matrices Q and Z.\n   *\n   * Example: \\include RealQZ_compute.cpp\n   * Output: \\include RealQZ_compute.out\n   *\n   * \\note The implementation is based on the algorithm in \"Matrix Computations\"\n   * by Gene H. Golub and Charles F. Van Loan, and a paper \"An algorithm for\n   * generalized eigenvalue problems\" by C.B.Moler and G.W.Stewart.\n   *\n   * \\sa class RealSchur, class ComplexSchur, class EigenSolver, class ComplexEigenSolver\n   */\n\n  template<typename MatrixType_> class RealQZ\n  {\n    public:\n      typedef MatrixType_ MatrixType;\n      enum {\n        RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n        ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n        Options = MatrixType::Options,\n        MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n        MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n      };\n      typedef typename MatrixType::Scalar Scalar;\n      typedef std::complex<typename NumTraits<Scalar>::Real> ComplexScalar;\n      typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n\n      typedef Matrix<ComplexScalar, ColsAtCompileTime, 1, Options & ~RowMajor, MaxColsAtCompileTime, 1> EigenvalueType;\n      typedef Matrix<Scalar, ColsAtCompileTime, 1, Options & ~RowMajor, MaxColsAtCompileTime, 1> ColumnVectorType;\n\n      /** \\brief Default constructor.\n       *\n       * \\param [in] size  Positive integer, size of the matrix whose QZ decomposition will be computed.\n       *\n       * The default constructor is useful in cases in which the user intends to\n       * perform decompositions via compute().  The \\p size parameter is only\n       * used as a hint. It is not an error to give a wrong \\p size, but it may\n       * impair performance.\n       *\n       * \\sa compute() for an example.\n       */\n      explicit RealQZ(Index size = RowsAtCompileTime==Dynamic ? 1 : RowsAtCompileTime) :\n        m_S(size, size),\n        m_T(size, size),\n        m_Q(size, size),\n        m_Z(size, size),\n        m_workspace(size*2),\n        m_maxIters(400),\n        m_isInitialized(false),\n        m_computeQZ(true)\n      {}\n\n      /** \\brief Constructor; computes real QZ decomposition of given matrices\n       * \n       * \\param[in]  A          Matrix A.\n       * \\param[in]  B          Matrix B.\n       * \\param[in]  computeQZ  If false, A and Z are not computed.\n       *\n       * This constructor calls compute() to compute the QZ decomposition.\n       */\n      RealQZ(const MatrixType& A, const MatrixType& B, bool computeQZ = true) :\n        m_S(A.rows(),A.cols()),\n        m_T(A.rows(),A.cols()),\n        m_Q(A.rows(),A.cols()),\n        m_Z(A.rows(),A.cols()),\n        m_workspace(A.rows()*2),\n        m_maxIters(400),\n        m_isInitialized(false),\n        m_computeQZ(true)\n      {\n        compute(A, B, computeQZ);\n      }\n\n      /** \\brief Returns matrix Q in the QZ decomposition. \n       *\n       * \\returns A const reference to the matrix Q.\n       */\n      const MatrixType& matrixQ() const {\n        eigen_assert(m_isInitialized && \"RealQZ is not initialized.\");\n        eigen_assert(m_computeQZ && \"The matrices Q and Z have not been computed during the QZ decomposition.\");\n        return m_Q;\n      }\n\n      /** \\brief Returns matrix Z in the QZ decomposition. \n       *\n       * \\returns A const reference to the matrix Z.\n       */\n      const MatrixType& matrixZ() const {\n        eigen_assert(m_isInitialized && \"RealQZ is not initialized.\");\n        eigen_assert(m_computeQZ && \"The matrices Q and Z have not been computed during the QZ decomposition.\");\n        return m_Z;\n      }\n\n      /** \\brief Returns matrix S in the QZ decomposition. \n       *\n       * \\returns A const reference to the matrix S.\n       */\n      const MatrixType& matrixS() const {\n        eigen_assert(m_isInitialized && \"RealQZ is not initialized.\");\n        return m_S;\n      }\n\n      /** \\brief Returns matrix S in the QZ decomposition. \n       *\n       * \\returns A const reference to the matrix S.\n       */\n      const MatrixType& matrixT() const {\n        eigen_assert(m_isInitialized && \"RealQZ is not initialized.\");\n        return m_T;\n      }\n\n      /** \\brief Computes QZ decomposition of given matrix. \n       * \n       * \\param[in]  A          Matrix A.\n       * \\param[in]  B          Matrix B.\n       * \\param[in]  computeQZ  If false, A and Z are not computed.\n       * \\returns    Reference to \\c *this\n       */\n      RealQZ& compute(const MatrixType& A, const MatrixType& B, bool computeQZ = true);\n\n      /** \\brief Reports whether previous computation was successful.\n       *\n       * \\returns \\c Success if computation was successful, \\c NoConvergence otherwise.\n       */\n      ComputationInfo info() const\n      {\n        eigen_assert(m_isInitialized && \"RealQZ is not initialized.\");\n        return m_info;\n      }\n\n      /** \\brief Returns number of performed QR-like iterations.\n      */\n      Index iterations() const\n      {\n        eigen_assert(m_isInitialized && \"RealQZ is not initialized.\");\n        return m_global_iter;\n      }\n\n      /** Sets the maximal number of iterations allowed to converge to one eigenvalue\n       * or decouple the problem.\n      */\n      RealQZ& setMaxIterations(Index maxIters)\n      {\n        m_maxIters = maxIters;\n        return *this;\n      }\n\n    private:\n\n      MatrixType m_S, m_T, m_Q, m_Z;\n      Matrix<Scalar,Dynamic,1> m_workspace;\n      ComputationInfo m_info;\n      Index m_maxIters;\n      bool m_isInitialized;\n      bool m_computeQZ;\n      Scalar m_normOfT, m_normOfS;\n      Index m_global_iter;\n\n      typedef Matrix<Scalar,3,1> Vector3s;\n      typedef Matrix<Scalar,2,1> Vector2s;\n      typedef Matrix<Scalar,2,2> Matrix2s;\n      typedef JacobiRotation<Scalar> JRs;\n\n      void hessenbergTriangular();\n      void computeNorms();\n      Index findSmallSubdiagEntry(Index iu);\n      Index findSmallDiagEntry(Index f, Index l);\n      void splitOffTwoRows(Index i);\n      void pushDownZero(Index z, Index f, Index l);\n      void step(Index f, Index l, Index iter);\n\n  }; // RealQZ\n\n  /** \\internal Reduces S and T to upper Hessenberg - triangular form */\n  template<typename MatrixType>\n    void RealQZ<MatrixType>::hessenbergTriangular()\n    {\n\n      const Index dim = m_S.cols();\n\n      // perform QR decomposition of T, overwrite T with R, save Q\n      HouseholderQR<MatrixType> qrT(m_T);\n      m_T = qrT.matrixQR();\n      m_T.template triangularView<StrictlyLower>().setZero();\n      m_Q = qrT.householderQ();\n      // overwrite S with Q* S\n      m_S.applyOnTheLeft(m_Q.adjoint());\n      // init Z as Identity\n      if (m_computeQZ)\n        m_Z = MatrixType::Identity(dim,dim);\n      // reduce S to upper Hessenberg with Givens rotations\n      for (Index j=0; j<=dim-3; j++) {\n        for (Index i=dim-1; i>=j+2; i--) {\n          JRs G;\n          // kill S(i,j)\n          if(m_S.coeff(i,j) != 0)\n          {\n            G.makeGivens(m_S.coeff(i-1,j), m_S.coeff(i,j), &m_S.coeffRef(i-1, j));\n            m_S.coeffRef(i,j) = Scalar(0.0);\n            m_S.rightCols(dim-j-1).applyOnTheLeft(i-1,i,G.adjoint());\n            m_T.rightCols(dim-i+1).applyOnTheLeft(i-1,i,G.adjoint());\n            // update Q\n            if (m_computeQZ)\n              m_Q.applyOnTheRight(i-1,i,G);\n          }\n          // kill T(i,i-1)\n          if(m_T.coeff(i,i-1)!=Scalar(0))\n          {\n            G.makeGivens(m_T.coeff(i,i), m_T.coeff(i,i-1), &m_T.coeffRef(i,i));\n            m_T.coeffRef(i,i-1) = Scalar(0.0);\n            m_S.applyOnTheRight(i,i-1,G);\n            m_T.topRows(i).applyOnTheRight(i,i-1,G);\n            // update Z\n            if (m_computeQZ)\n              m_Z.applyOnTheLeft(i,i-1,G.adjoint());\n          }\n        }\n      }\n    }\n\n  /** \\internal Computes vector L1 norms of S and T when in Hessenberg-Triangular form already */\n  template<typename MatrixType>\n    inline void RealQZ<MatrixType>::computeNorms()\n    {\n      const Index size = m_S.cols();\n      m_normOfS = Scalar(0.0);\n      m_normOfT = Scalar(0.0);\n      for (Index j = 0; j < size; ++j)\n      {\n        m_normOfS += m_S.col(j).segment(0, (std::min)(size,j+2)).cwiseAbs().sum();\n        m_normOfT += m_T.row(j).segment(j, size - j).cwiseAbs().sum();\n      }\n    }\n\n\n  /** \\internal Look for single small sub-diagonal element S(res, res-1) and return res (or 0) */\n  template<typename MatrixType>\n    inline Index RealQZ<MatrixType>::findSmallSubdiagEntry(Index iu)\n    {\n      using std::abs;\n      Index res = iu;\n      while (res > 0)\n      {\n        Scalar s = abs(m_S.coeff(res-1,res-1)) + abs(m_S.coeff(res,res));\n        if (s == Scalar(0.0))\n          s = m_normOfS;\n        if (abs(m_S.coeff(res,res-1)) < NumTraits<Scalar>::epsilon() * s)\n          break;\n        res--;\n      }\n      return res;\n    }\n\n  /** \\internal Look for single small diagonal element T(res, res) for res between f and l, and return res (or f-1)  */\n  template<typename MatrixType>\n    inline Index RealQZ<MatrixType>::findSmallDiagEntry(Index f, Index l)\n    {\n      using std::abs;\n      Index res = l;\n      while (res >= f) {\n        if (abs(m_T.coeff(res,res)) <= NumTraits<Scalar>::epsilon() * m_normOfT)\n          break;\n        res--;\n      }\n      return res;\n    }\n\n  /** \\internal decouple 2x2 diagonal block in rows i, i+1 if eigenvalues are real */\n  template<typename MatrixType>\n    inline void RealQZ<MatrixType>::splitOffTwoRows(Index i)\n    {\n      using std::abs;\n      using std::sqrt;\n      const Index dim=m_S.cols();\n      if (abs(m_S.coeff(i+1,i))==Scalar(0))\n        return;\n      Index j = findSmallDiagEntry(i,i+1);\n      if (j==i-1)\n      {\n        // block of (S T^{-1})\n        Matrix2s STi = m_T.template block<2,2>(i,i).template triangularView<Upper>().\n          template solve<OnTheRight>(m_S.template block<2,2>(i,i));\n        Scalar p = Scalar(0.5)*(STi(0,0)-STi(1,1));\n        Scalar q = p*p + STi(1,0)*STi(0,1);\n        if (q>=0) {\n          Scalar z = sqrt(q);\n          // one QR-like iteration for ABi - lambda I\n          // is enough - when we know exact eigenvalue in advance,\n          // convergence is immediate\n          JRs G;\n          if (p>=0)\n            G.makeGivens(p + z, STi(1,0));\n          else\n            G.makeGivens(p - z, STi(1,0));\n          m_S.rightCols(dim-i).applyOnTheLeft(i,i+1,G.adjoint());\n          m_T.rightCols(dim-i).applyOnTheLeft(i,i+1,G.adjoint());\n          // update Q\n          if (m_computeQZ)\n            m_Q.applyOnTheRight(i,i+1,G);\n\n          G.makeGivens(m_T.coeff(i+1,i+1), m_T.coeff(i+1,i));\n          m_S.topRows(i+2).applyOnTheRight(i+1,i,G);\n          m_T.topRows(i+2).applyOnTheRight(i+1,i,G);\n          // update Z\n          if (m_computeQZ)\n            m_Z.applyOnTheLeft(i+1,i,G.adjoint());\n\n          m_S.coeffRef(i+1,i) = Scalar(0.0);\n          m_T.coeffRef(i+1,i) = Scalar(0.0);\n        }\n      }\n      else\n      {\n        pushDownZero(j,i,i+1);\n      }\n    }\n\n  /** \\internal use zero in T(z,z) to zero S(l,l-1), working in block f..l */\n  template<typename MatrixType>\n    inline void RealQZ<MatrixType>::pushDownZero(Index z, Index f, Index l)\n    {\n      JRs G;\n      const Index dim = m_S.cols();\n      for (Index zz=z; zz<l; zz++)\n      {\n        // push 0 down\n        Index firstColS = zz>f ? (zz-1) : zz;\n        G.makeGivens(m_T.coeff(zz, zz+1), m_T.coeff(zz+1, zz+1));\n        m_S.rightCols(dim-firstColS).applyOnTheLeft(zz,zz+1,G.adjoint());\n        m_T.rightCols(dim-zz).applyOnTheLeft(zz,zz+1,G.adjoint());\n        m_T.coeffRef(zz+1,zz+1) = Scalar(0.0);\n        // update Q\n        if (m_computeQZ)\n          m_Q.applyOnTheRight(zz,zz+1,G);\n        // kill S(zz+1, zz-1)\n        if (zz>f)\n        {\n          G.makeGivens(m_S.coeff(zz+1, zz), m_S.coeff(zz+1,zz-1));\n          m_S.topRows(zz+2).applyOnTheRight(zz, zz-1,G);\n          m_T.topRows(zz+1).applyOnTheRight(zz, zz-1,G);\n          m_S.coeffRef(zz+1,zz-1) = Scalar(0.0);\n          // update Z\n          if (m_computeQZ)\n            m_Z.applyOnTheLeft(zz,zz-1,G.adjoint());\n        }\n      }\n      // finally kill S(l,l-1)\n      G.makeGivens(m_S.coeff(l,l), m_S.coeff(l,l-1));\n      m_S.applyOnTheRight(l,l-1,G);\n      m_T.applyOnTheRight(l,l-1,G);\n      m_S.coeffRef(l,l-1)=Scalar(0.0);\n      // update Z\n      if (m_computeQZ)\n        m_Z.applyOnTheLeft(l,l-1,G.adjoint());\n    }\n\n  /** \\internal QR-like iterative step for block f..l */\n  template<typename MatrixType>\n    inline void RealQZ<MatrixType>::step(Index f, Index l, Index iter)\n    {\n      using std::abs;\n      const Index dim = m_S.cols();\n\n      // x, y, z\n      Scalar x, y, z;\n      if (iter==10)\n      {\n        // Wilkinson ad hoc shift\n        const Scalar\n          a11=m_S.coeff(f+0,f+0), a12=m_S.coeff(f+0,f+1),\n          a21=m_S.coeff(f+1,f+0), a22=m_S.coeff(f+1,f+1), a32=m_S.coeff(f+2,f+1),\n          b12=m_T.coeff(f+0,f+1),\n          b11i=Scalar(1.0)/m_T.coeff(f+0,f+0),\n          b22i=Scalar(1.0)/m_T.coeff(f+1,f+1),\n          a87=m_S.coeff(l-1,l-2),\n          a98=m_S.coeff(l-0,l-1),\n          b77i=Scalar(1.0)/m_T.coeff(l-2,l-2),\n          b88i=Scalar(1.0)/m_T.coeff(l-1,l-1);\n        Scalar ss = abs(a87*b77i) + abs(a98*b88i),\n               lpl = Scalar(1.5)*ss,\n               ll = ss*ss;\n        x = ll + a11*a11*b11i*b11i - lpl*a11*b11i + a12*a21*b11i*b22i\n          - a11*a21*b12*b11i*b11i*b22i;\n        y = a11*a21*b11i*b11i - lpl*a21*b11i + a21*a22*b11i*b22i \n          - a21*a21*b12*b11i*b11i*b22i;\n        z = a21*a32*b11i*b22i;\n      }\n      else if (iter==16)\n      {\n        // another exceptional shift\n        x = m_S.coeff(f,f)/m_T.coeff(f,f)-m_S.coeff(l,l)/m_T.coeff(l,l) + m_S.coeff(l,l-1)*m_T.coeff(l-1,l) /\n          (m_T.coeff(l-1,l-1)*m_T.coeff(l,l));\n        y = m_S.coeff(f+1,f)/m_T.coeff(f,f);\n        z = 0;\n      }\n      else if (iter>23 && !(iter%8))\n      {\n        // extremely exceptional shift\n        x = internal::random<Scalar>(-1.0,1.0);\n        y = internal::random<Scalar>(-1.0,1.0);\n        z = internal::random<Scalar>(-1.0,1.0);\n      }\n      else\n      {\n        // Compute the shifts: (x,y,z,0...) = (AB^-1 - l1 I) (AB^-1 - l2 I) e1\n        // where l1 and l2 are the eigenvalues of the 2x2 matrix C = U V^-1 where\n        // U and V are 2x2 bottom right sub matrices of A and B. Thus:\n        //  = AB^-1AB^-1 + l1 l2 I - (l1+l2)(AB^-1)\n        //  = AB^-1AB^-1 + det(M) - tr(M)(AB^-1)\n        // Since we are only interested in having x, y, z with a correct ratio, we have:\n        const Scalar\n          a11 = m_S.coeff(f,f),     a12 = m_S.coeff(f,f+1),\n          a21 = m_S.coeff(f+1,f),   a22 = m_S.coeff(f+1,f+1),\n                                    a32 = m_S.coeff(f+2,f+1),\n\n          a88 = m_S.coeff(l-1,l-1), a89 = m_S.coeff(l-1,l),\n          a98 = m_S.coeff(l,l-1),   a99 = m_S.coeff(l,l),\n\n          b11 = m_T.coeff(f,f),     b12 = m_T.coeff(f,f+1),\n                                    b22 = m_T.coeff(f+1,f+1),\n\n          b88 = m_T.coeff(l-1,l-1), b89 = m_T.coeff(l-1,l),\n                                    b99 = m_T.coeff(l,l);\n\n        x = ( (a88/b88 - a11/b11)*(a99/b99 - a11/b11) - (a89/b99)*(a98/b88) + (a98/b88)*(b89/b99)*(a11/b11) ) * (b11/a21)\n          + a12/b22 - (a11/b11)*(b12/b22);\n        y = (a22/b22-a11/b11) - (a21/b11)*(b12/b22) - (a88/b88-a11/b11) - (a99/b99-a11/b11) + (a98/b88)*(b89/b99);\n        z = a32/b22;\n      }\n\n      JRs G;\n\n      for (Index k=f; k<=l-2; k++)\n      {\n        // variables for Householder reflections\n        Vector2s essential2;\n        Scalar tau, beta;\n\n        Vector3s hr(x,y,z);\n\n        // Q_k to annihilate S(k+1,k-1) and S(k+2,k-1)\n        hr.makeHouseholderInPlace(tau, beta);\n        essential2 = hr.template bottomRows<2>();\n        Index fc=(std::max)(k-1,Index(0));  // first col to update\n        m_S.template middleRows<3>(k).rightCols(dim-fc).applyHouseholderOnTheLeft(essential2, tau, m_workspace.data());\n        m_T.template middleRows<3>(k).rightCols(dim-fc).applyHouseholderOnTheLeft(essential2, tau, m_workspace.data());\n        if (m_computeQZ)\n          m_Q.template middleCols<3>(k).applyHouseholderOnTheRight(essential2, tau, m_workspace.data());\n        if (k>f)\n          m_S.coeffRef(k+2,k-1) = m_S.coeffRef(k+1,k-1) = Scalar(0.0);\n\n        // Z_{k1} to annihilate T(k+2,k+1) and T(k+2,k)\n        hr << m_T.coeff(k+2,k+2),m_T.coeff(k+2,k),m_T.coeff(k+2,k+1);\n        hr.makeHouseholderInPlace(tau, beta);\n        essential2 = hr.template bottomRows<2>();\n        {\n          Index lr = (std::min)(k+4,dim); // last row to update\n          Map<Matrix<Scalar,Dynamic,1> > tmp(m_workspace.data(),lr);\n          // S\n          tmp = m_S.template middleCols<2>(k).topRows(lr) * essential2;\n          tmp += m_S.col(k+2).head(lr);\n          m_S.col(k+2).head(lr) -= tau*tmp;\n          m_S.template middleCols<2>(k).topRows(lr) -= (tau*tmp) * essential2.adjoint();\n          // T\n          tmp = m_T.template middleCols<2>(k).topRows(lr) * essential2;\n          tmp += m_T.col(k+2).head(lr);\n          m_T.col(k+2).head(lr) -= tau*tmp;\n          m_T.template middleCols<2>(k).topRows(lr) -= (tau*tmp) * essential2.adjoint();\n        }\n        if (m_computeQZ)\n        {\n          // Z\n          Map<Matrix<Scalar,1,Dynamic> > tmp(m_workspace.data(),dim);\n          tmp = essential2.adjoint()*(m_Z.template middleRows<2>(k));\n          tmp += m_Z.row(k+2);\n          m_Z.row(k+2) -= tau*tmp;\n          m_Z.template middleRows<2>(k) -= essential2 * (tau*tmp);\n        }\n        m_T.coeffRef(k+2,k) = m_T.coeffRef(k+2,k+1) = Scalar(0.0);\n\n        // Z_{k2} to annihilate T(k+1,k)\n        G.makeGivens(m_T.coeff(k+1,k+1), m_T.coeff(k+1,k));\n        m_S.applyOnTheRight(k+1,k,G);\n        m_T.applyOnTheRight(k+1,k,G);\n        // update Z\n        if (m_computeQZ)\n          m_Z.applyOnTheLeft(k+1,k,G.adjoint());\n        m_T.coeffRef(k+1,k) = Scalar(0.0);\n\n        // update x,y,z\n        x = m_S.coeff(k+1,k);\n        y = m_S.coeff(k+2,k);\n        if (k < l-2)\n          z = m_S.coeff(k+3,k);\n      } // loop over k\n\n      // Q_{n-1} to annihilate y = S(l,l-2)\n      G.makeGivens(x,y);\n      m_S.applyOnTheLeft(l-1,l,G.adjoint());\n      m_T.applyOnTheLeft(l-1,l,G.adjoint());\n      if (m_computeQZ)\n        m_Q.applyOnTheRight(l-1,l,G);\n      m_S.coeffRef(l,l-2) = Scalar(0.0);\n\n      // Z_{n-1} to annihilate T(l,l-1)\n      G.makeGivens(m_T.coeff(l,l),m_T.coeff(l,l-1));\n      m_S.applyOnTheRight(l,l-1,G);\n      m_T.applyOnTheRight(l,l-1,G);\n      if (m_computeQZ)\n        m_Z.applyOnTheLeft(l,l-1,G.adjoint());\n      m_T.coeffRef(l,l-1) = Scalar(0.0);\n    }\n\n  template<typename MatrixType>\n    RealQZ<MatrixType>& RealQZ<MatrixType>::compute(const MatrixType& A_in, const MatrixType& B_in, bool computeQZ)\n    {\n\n      const Index dim = A_in.cols();\n\n      eigen_assert (A_in.rows()==dim && A_in.cols()==dim \n          && B_in.rows()==dim && B_in.cols()==dim \n          && \"Need square matrices of the same dimension\");\n\n      m_isInitialized = true;\n      m_computeQZ = computeQZ;\n      m_S = A_in; m_T = B_in;\n      m_workspace.resize(dim*2);\n      m_global_iter = 0;\n\n      // entrance point: hessenberg triangular decomposition\n      hessenbergTriangular();\n      // compute L1 vector norms of T, S into m_normOfS, m_normOfT\n      computeNorms();\n\n      Index l = dim-1, \n            f, \n            local_iter = 0;\n\n      while (l>0 && local_iter<m_maxIters)\n      {\n        f = findSmallSubdiagEntry(l);\n        // now rows and columns f..l (including) decouple from the rest of the problem\n        if (f>0) m_S.coeffRef(f,f-1) = Scalar(0.0);\n        if (f == l) // One root found\n        {\n          l--;\n          local_iter = 0;\n        }\n        else if (f == l-1) // Two roots found\n        {\n          splitOffTwoRows(f);\n          l -= 2;\n          local_iter = 0;\n        }\n        else // No convergence yet\n        {\n          // if there's zero on diagonal of T, we can isolate an eigenvalue with Givens rotations\n          Index z = findSmallDiagEntry(f,l);\n          if (z>=f)\n          {\n            // zero found\n            pushDownZero(z,f,l);\n          }\n          else\n          {\n            // We are sure now that S.block(f,f, l-f+1,l-f+1) is underuced upper-Hessenberg \n            // and T.block(f,f, l-f+1,l-f+1) is invertible uper-triangular, which allows to\n            // apply a QR-like iteration to rows and columns f..l.\n            step(f,l, local_iter);\n            local_iter++;\n            m_global_iter++;\n          }\n        }\n      }\n      // check if we converged before reaching iterations limit\n      m_info = (local_iter<m_maxIters) ? Success : NoConvergence;\n\n      // For each non triangular 2x2 diagonal block of S,\n      //    reduce the respective 2x2 diagonal block of T to positive diagonal form using 2x2 SVD.\n      // This step is not mandatory for QZ, but it does help further extraction of eigenvalues/eigenvectors,\n      // and is in par with Lapack/Matlab QZ.\n      if(m_info==Success)\n      {\n        for(Index i=0; i<dim-1; ++i)\n        {\n          if(m_S.coeff(i+1, i) != Scalar(0))\n          {\n            JacobiRotation<Scalar> j_left, j_right;\n            internal::real_2x2_jacobi_svd(m_T, i, i+1, &j_left, &j_right);\n\n            // Apply resulting Jacobi rotations\n            m_S.applyOnTheLeft(i,i+1,j_left);\n            m_S.applyOnTheRight(i,i+1,j_right);\n            m_T.applyOnTheLeft(i,i+1,j_left);\n            m_T.applyOnTheRight(i,i+1,j_right);\n            m_T(i+1,i) = m_T(i,i+1) = Scalar(0);\n\n            if(m_computeQZ) {\n              m_Q.applyOnTheRight(i,i+1,j_left.transpose());\n              m_Z.applyOnTheLeft(i,i+1,j_right.transpose());\n            }\n\n            i++;\n          }\n        }\n      }\n\n      return *this;\n    } // end compute\n\n} // end namespace Eigen\n\n#endif //EIGEN_REAL_QZ\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Eigenvalues/RealSchur.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010,2012 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_REAL_SCHUR_H\n#define EIGEN_REAL_SCHUR_H\n\n#include \"./HessenbergDecomposition.h\"\n\nnamespace Eigen { \n\n/** \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  *\n  * \\class RealSchur\n  *\n  * \\brief Performs a real Schur decomposition of a square matrix\n  *\n  * \\tparam MatrixType_ the type of the matrix of which we are computing the\n  * real Schur decomposition; this is expected to be an instantiation of the\n  * Matrix class template.\n  *\n  * Given a real square matrix A, this class computes the real Schur\n  * decomposition: \\f$ A = U T U^T \\f$ where U is a real orthogonal matrix and\n  * T is a real quasi-triangular matrix. An orthogonal matrix is a matrix whose\n  * inverse is equal to its transpose, \\f$ U^{-1} = U^T \\f$. A quasi-triangular\n  * matrix is a block-triangular matrix whose diagonal consists of 1-by-1\n  * blocks and 2-by-2 blocks with complex eigenvalues. The eigenvalues of the\n  * blocks on the diagonal of T are the same as the eigenvalues of the matrix\n  * A, and thus the real Schur decomposition is used in EigenSolver to compute\n  * the eigendecomposition of a matrix.\n  *\n  * Call the function compute() to compute the real Schur decomposition of a\n  * given matrix. Alternatively, you can use the RealSchur(const MatrixType&, bool)\n  * constructor which computes the real Schur decomposition at construction\n  * time. Once the decomposition is computed, you can use the matrixU() and\n  * matrixT() functions to retrieve the matrices U and T in the decomposition.\n  *\n  * The documentation of RealSchur(const MatrixType&, bool) contains an example\n  * of the typical use of this class.\n  *\n  * \\note The implementation is adapted from\n  * <a href=\"http://math.nist.gov/javanumerics/jama/\">JAMA</a> (public domain).\n  * Their code is based on EISPACK.\n  *\n  * \\sa class ComplexSchur, class EigenSolver, class ComplexEigenSolver\n  */\ntemplate<typename MatrixType_> class RealSchur\n{\n  public:\n    typedef MatrixType_ MatrixType;\n    enum {\n      RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      Options = MatrixType::Options,\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n    typedef typename MatrixType::Scalar Scalar;\n    typedef std::complex<typename NumTraits<Scalar>::Real> ComplexScalar;\n    typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n\n    typedef Matrix<ComplexScalar, ColsAtCompileTime, 1, Options & ~RowMajor, MaxColsAtCompileTime, 1> EigenvalueType;\n    typedef Matrix<Scalar, ColsAtCompileTime, 1, Options & ~RowMajor, MaxColsAtCompileTime, 1> ColumnVectorType;\n\n    /** \\brief Default constructor.\n      *\n      * \\param [in] size  Positive integer, size of the matrix whose Schur decomposition will be computed.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via compute().  The \\p size parameter is only\n      * used as a hint. It is not an error to give a wrong \\p size, but it may\n      * impair performance.\n      *\n      * \\sa compute() for an example.\n      */\n    explicit RealSchur(Index size = RowsAtCompileTime==Dynamic ? 1 : RowsAtCompileTime)\n            : m_matT(size, size),\n              m_matU(size, size),\n              m_workspaceVector(size),\n              m_hess(size),\n              m_isInitialized(false),\n              m_matUisUptodate(false),\n              m_maxIters(-1)\n    { }\n\n    /** \\brief Constructor; computes real Schur decomposition of given matrix. \n      * \n      * \\param[in]  matrix    Square matrix whose Schur decomposition is to be computed.\n      * \\param[in]  computeU  If true, both T and U are computed; if false, only T is computed.\n      *\n      * This constructor calls compute() to compute the Schur decomposition.\n      *\n      * Example: \\include RealSchur_RealSchur_MatrixType.cpp\n      * Output: \\verbinclude RealSchur_RealSchur_MatrixType.out\n      */\n    template<typename InputType>\n    explicit RealSchur(const EigenBase<InputType>& matrix, bool computeU = true)\n            : m_matT(matrix.rows(),matrix.cols()),\n              m_matU(matrix.rows(),matrix.cols()),\n              m_workspaceVector(matrix.rows()),\n              m_hess(matrix.rows()),\n              m_isInitialized(false),\n              m_matUisUptodate(false),\n              m_maxIters(-1)\n    {\n      compute(matrix.derived(), computeU);\n    }\n\n    /** \\brief Returns the orthogonal matrix in the Schur decomposition. \n      *\n      * \\returns A const reference to the matrix U.\n      *\n      * \\pre Either the constructor RealSchur(const MatrixType&, bool) or the\n      * member function compute(const MatrixType&, bool) has been called before\n      * to compute the Schur decomposition of a matrix, and \\p computeU was set\n      * to true (the default value).\n      *\n      * \\sa RealSchur(const MatrixType&, bool) for an example\n      */\n    const MatrixType& matrixU() const\n    {\n      eigen_assert(m_isInitialized && \"RealSchur is not initialized.\");\n      eigen_assert(m_matUisUptodate && \"The matrix U has not been computed during the RealSchur decomposition.\");\n      return m_matU;\n    }\n\n    /** \\brief Returns the quasi-triangular matrix in the Schur decomposition. \n      *\n      * \\returns A const reference to the matrix T.\n      *\n      * \\pre Either the constructor RealSchur(const MatrixType&, bool) or the\n      * member function compute(const MatrixType&, bool) has been called before\n      * to compute the Schur decomposition of a matrix.\n      *\n      * \\sa RealSchur(const MatrixType&, bool) for an example\n      */\n    const MatrixType& matrixT() const\n    {\n      eigen_assert(m_isInitialized && \"RealSchur is not initialized.\");\n      return m_matT;\n    }\n  \n    /** \\brief Computes Schur decomposition of given matrix. \n      * \n      * \\param[in]  matrix    Square matrix whose Schur decomposition is to be computed.\n      * \\param[in]  computeU  If true, both T and U are computed; if false, only T is computed.\n      * \\returns    Reference to \\c *this\n      *\n      * The Schur decomposition is computed by first reducing the matrix to\n      * Hessenberg form using the class HessenbergDecomposition. The Hessenberg\n      * matrix is then reduced to triangular form by performing Francis QR\n      * iterations with implicit double shift. The cost of computing the Schur\n      * decomposition depends on the number of iterations; as a rough guide, it\n      * may be taken to be \\f$25n^3\\f$ flops if \\a computeU is true and\n      * \\f$10n^3\\f$ flops if \\a computeU is false.\n      *\n      * Example: \\include RealSchur_compute.cpp\n      * Output: \\verbinclude RealSchur_compute.out\n      *\n      * \\sa compute(const MatrixType&, bool, Index)\n      */\n    template<typename InputType>\n    RealSchur& compute(const EigenBase<InputType>& matrix, bool computeU = true);\n\n    /** \\brief Computes Schur decomposition of a Hessenberg matrix H = Z T Z^T\n     *  \\param[in] matrixH Matrix in Hessenberg form H\n     *  \\param[in] matrixQ orthogonal matrix Q that transform a matrix A to H : A = Q H Q^T\n     *  \\param computeU Computes the matriX U of the Schur vectors\n     * \\return Reference to \\c *this\n     * \n     *  This routine assumes that the matrix is already reduced in Hessenberg form matrixH\n     *  using either the class HessenbergDecomposition or another mean. \n     *  It computes the upper quasi-triangular matrix T of the Schur decomposition of H\n     *  When computeU is true, this routine computes the matrix U such that \n     *  A = U T U^T =  (QZ) T (QZ)^T = Q H Q^T where A is the initial matrix\n     * \n     * NOTE Q is referenced if computeU is true; so, if the initial orthogonal matrix\n     * is not available, the user should give an identity matrix (Q.setIdentity())\n     * \n     * \\sa compute(const MatrixType&, bool)\n     */\n    template<typename HessMatrixType, typename OrthMatrixType>\n    RealSchur& computeFromHessenberg(const HessMatrixType& matrixH, const OrthMatrixType& matrixQ,  bool computeU);\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful, \\c NoConvergence otherwise.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"RealSchur is not initialized.\");\n      return m_info;\n    }\n\n    /** \\brief Sets the maximum number of iterations allowed. \n      *\n      * If not specified by the user, the maximum number of iterations is m_maxIterationsPerRow times the size\n      * of the matrix.\n      */\n    RealSchur& setMaxIterations(Index maxIters)\n    {\n      m_maxIters = maxIters;\n      return *this;\n    }\n\n    /** \\brief Returns the maximum number of iterations. */\n    Index getMaxIterations()\n    {\n      return m_maxIters;\n    }\n\n    /** \\brief Maximum number of iterations per row.\n      *\n      * If not otherwise specified, the maximum number of iterations is this number times the size of the\n      * matrix. It is currently set to 40.\n      */\n    static const int m_maxIterationsPerRow = 40;\n\n  private:\n    \n    MatrixType m_matT;\n    MatrixType m_matU;\n    ColumnVectorType m_workspaceVector;\n    HessenbergDecomposition<MatrixType> m_hess;\n    ComputationInfo m_info;\n    bool m_isInitialized;\n    bool m_matUisUptodate;\n    Index m_maxIters;\n\n    typedef Matrix<Scalar,3,1> Vector3s;\n\n    Scalar computeNormOfT();\n    Index findSmallSubdiagEntry(Index iu, const Scalar& considerAsZero);\n    void splitOffTwoRows(Index iu, bool computeU, const Scalar& exshift);\n    void computeShift(Index iu, Index iter, Scalar& exshift, Vector3s& shiftInfo);\n    void initFrancisQRStep(Index il, Index iu, const Vector3s& shiftInfo, Index& im, Vector3s& firstHouseholderVector);\n    void performFrancisQRStep(Index il, Index im, Index iu, bool computeU, const Vector3s& firstHouseholderVector, Scalar* workspace);\n};\n\n\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nRealSchur<MatrixType>& RealSchur<MatrixType>::compute(const EigenBase<InputType>& matrix, bool computeU)\n{\n  const Scalar considerAsZero = (std::numeric_limits<Scalar>::min)();\n\n  eigen_assert(matrix.cols() == matrix.rows());\n  Index maxIters = m_maxIters;\n  if (maxIters == -1)\n    maxIters = m_maxIterationsPerRow * matrix.rows();\n\n  Scalar scale = matrix.derived().cwiseAbs().maxCoeff();\n  if(scale<considerAsZero)\n  {\n    m_matT.setZero(matrix.rows(),matrix.cols());\n    if(computeU)\n      m_matU.setIdentity(matrix.rows(),matrix.cols());\n    m_info = Success;\n    m_isInitialized = true;\n    m_matUisUptodate = computeU;\n    return *this;\n  }\n\n  // Step 1. Reduce to Hessenberg form\n  m_hess.compute(matrix.derived()/scale);\n\n  // Step 2. Reduce to real Schur form\n  // Note: we copy m_hess.matrixQ() into m_matU here and not in computeFromHessenberg\n  //       to be able to pass our working-space buffer for the Householder to Dense evaluation.\n  m_workspaceVector.resize(matrix.cols());\n  if(computeU)\n    m_hess.matrixQ().evalTo(m_matU, m_workspaceVector);\n  computeFromHessenberg(m_hess.matrixH(), m_matU, computeU);\n\n  m_matT *= scale;\n  \n  return *this;\n}\ntemplate<typename MatrixType>\ntemplate<typename HessMatrixType, typename OrthMatrixType>\nRealSchur<MatrixType>& RealSchur<MatrixType>::computeFromHessenberg(const HessMatrixType& matrixH, const OrthMatrixType& matrixQ,  bool computeU)\n{\n  using std::abs;\n\n  m_matT = matrixH;\n  m_workspaceVector.resize(m_matT.cols());\n  if(computeU && !internal::is_same_dense(m_matU,matrixQ))\n    m_matU = matrixQ;\n  \n  Index maxIters = m_maxIters;\n  if (maxIters == -1)\n    maxIters = m_maxIterationsPerRow * matrixH.rows();\n  Scalar* workspace = &m_workspaceVector.coeffRef(0);\n\n  // The matrix m_matT is divided in three parts. \n  // Rows 0,...,il-1 are decoupled from the rest because m_matT(il,il-1) is zero. \n  // Rows il,...,iu is the part we are working on (the active window).\n  // Rows iu+1,...,end are already brought in triangular form.\n  Index iu = m_matT.cols() - 1;\n  Index iter = 0;      // iteration count for current eigenvalue\n  Index totalIter = 0; // iteration count for whole matrix\n  Scalar exshift(0);   // sum of exceptional shifts\n  Scalar norm = computeNormOfT();\n  // sub-diagonal entries smaller than considerAsZero will be treated as zero.\n  // We use eps^2 to enable more precision in small eigenvalues.\n  Scalar considerAsZero = numext::maxi<Scalar>( norm * numext::abs2(NumTraits<Scalar>::epsilon()),\n                                                (std::numeric_limits<Scalar>::min)() );\n\n  if(norm!=Scalar(0))\n  {\n    while (iu >= 0)\n    {\n      Index il = findSmallSubdiagEntry(iu,considerAsZero);\n\n      // Check for convergence\n      if (il == iu) // One root found\n      {\n        m_matT.coeffRef(iu,iu) = m_matT.coeff(iu,iu) + exshift;\n        if (iu > 0)\n          m_matT.coeffRef(iu, iu-1) = Scalar(0);\n        iu--;\n        iter = 0;\n      }\n      else if (il == iu-1) // Two roots found\n      {\n        splitOffTwoRows(iu, computeU, exshift);\n        iu -= 2;\n        iter = 0;\n      }\n      else // No convergence yet\n      {\n        // The firstHouseholderVector vector has to be initialized to something to get rid of a silly GCC warning (-O1 -Wall -DNDEBUG )\n        Vector3s firstHouseholderVector = Vector3s::Zero(), shiftInfo;\n        computeShift(iu, iter, exshift, shiftInfo);\n        iter = iter + 1;\n        totalIter = totalIter + 1;\n        if (totalIter > maxIters) break;\n        Index im;\n        initFrancisQRStep(il, iu, shiftInfo, im, firstHouseholderVector);\n        performFrancisQRStep(il, im, iu, computeU, firstHouseholderVector, workspace);\n      }\n    }\n  }\n  if(totalIter <= maxIters)\n    m_info = Success;\n  else\n    m_info = NoConvergence;\n\n  m_isInitialized = true;\n  m_matUisUptodate = computeU;\n  return *this;\n}\n\n/** \\internal Computes and returns vector L1 norm of T */\ntemplate<typename MatrixType>\ninline typename MatrixType::Scalar RealSchur<MatrixType>::computeNormOfT()\n{\n  const Index size = m_matT.cols();\n  // FIXME to be efficient the following would requires a triangular reduxion code\n  // Scalar norm = m_matT.upper().cwiseAbs().sum() \n  //               + m_matT.bottomLeftCorner(size-1,size-1).diagonal().cwiseAbs().sum();\n  Scalar norm(0);\n  for (Index j = 0; j < size; ++j)\n    norm += m_matT.col(j).segment(0, (std::min)(size,j+2)).cwiseAbs().sum();\n  return norm;\n}\n\n/** \\internal Look for single small sub-diagonal element and returns its index */\ntemplate<typename MatrixType>\ninline Index RealSchur<MatrixType>::findSmallSubdiagEntry(Index iu, const Scalar& considerAsZero)\n{\n  using std::abs;\n  Index res = iu;\n  while (res > 0)\n  {\n    Scalar s = abs(m_matT.coeff(res-1,res-1)) + abs(m_matT.coeff(res,res));\n\n    s = numext::maxi<Scalar>(s * NumTraits<Scalar>::epsilon(), considerAsZero);\n    \n    if (abs(m_matT.coeff(res,res-1)) <= s)\n      break;\n    res--;\n  }\n  return res;\n}\n\n/** \\internal Update T given that rows iu-1 and iu decouple from the rest. */\ntemplate<typename MatrixType>\ninline void RealSchur<MatrixType>::splitOffTwoRows(Index iu, bool computeU, const Scalar& exshift)\n{\n  using std::sqrt;\n  using std::abs;\n  const Index size = m_matT.cols();\n\n  // The eigenvalues of the 2x2 matrix [a b; c d] are \n  // trace +/- sqrt(discr/4) where discr = tr^2 - 4*det, tr = a + d, det = ad - bc\n  Scalar p = Scalar(0.5) * (m_matT.coeff(iu-1,iu-1) - m_matT.coeff(iu,iu));\n  Scalar q = p * p + m_matT.coeff(iu,iu-1) * m_matT.coeff(iu-1,iu);   // q = tr^2 / 4 - det = discr/4\n  m_matT.coeffRef(iu,iu) += exshift;\n  m_matT.coeffRef(iu-1,iu-1) += exshift;\n\n  if (q >= Scalar(0)) // Two real eigenvalues\n  {\n    Scalar z = sqrt(abs(q));\n    JacobiRotation<Scalar> rot;\n    if (p >= Scalar(0))\n      rot.makeGivens(p + z, m_matT.coeff(iu, iu-1));\n    else\n      rot.makeGivens(p - z, m_matT.coeff(iu, iu-1));\n\n    m_matT.rightCols(size-iu+1).applyOnTheLeft(iu-1, iu, rot.adjoint());\n    m_matT.topRows(iu+1).applyOnTheRight(iu-1, iu, rot);\n    m_matT.coeffRef(iu, iu-1) = Scalar(0); \n    if (computeU)\n      m_matU.applyOnTheRight(iu-1, iu, rot);\n  }\n\n  if (iu > 1) \n    m_matT.coeffRef(iu-1, iu-2) = Scalar(0);\n}\n\n/** \\internal Form shift in shiftInfo, and update exshift if an exceptional shift is performed. */\ntemplate<typename MatrixType>\ninline void RealSchur<MatrixType>::computeShift(Index iu, Index iter, Scalar& exshift, Vector3s& shiftInfo)\n{\n  using std::sqrt;\n  using std::abs;\n  shiftInfo.coeffRef(0) = m_matT.coeff(iu,iu);\n  shiftInfo.coeffRef(1) = m_matT.coeff(iu-1,iu-1);\n  shiftInfo.coeffRef(2) = m_matT.coeff(iu,iu-1) * m_matT.coeff(iu-1,iu);\n\n  // Wilkinson's original ad hoc shift\n  if (iter == 10)\n  {\n    exshift += shiftInfo.coeff(0);\n    for (Index i = 0; i <= iu; ++i)\n      m_matT.coeffRef(i,i) -= shiftInfo.coeff(0);\n    Scalar s = abs(m_matT.coeff(iu,iu-1)) + abs(m_matT.coeff(iu-1,iu-2));\n    shiftInfo.coeffRef(0) = Scalar(0.75) * s;\n    shiftInfo.coeffRef(1) = Scalar(0.75) * s;\n    shiftInfo.coeffRef(2) = Scalar(-0.4375) * s * s;\n  }\n\n  // MATLAB's new ad hoc shift\n  if (iter == 30)\n  {\n    Scalar s = (shiftInfo.coeff(1) - shiftInfo.coeff(0)) / Scalar(2.0);\n    s = s * s + shiftInfo.coeff(2);\n    if (s > Scalar(0))\n    {\n      s = sqrt(s);\n      if (shiftInfo.coeff(1) < shiftInfo.coeff(0))\n        s = -s;\n      s = s + (shiftInfo.coeff(1) - shiftInfo.coeff(0)) / Scalar(2.0);\n      s = shiftInfo.coeff(0) - shiftInfo.coeff(2) / s;\n      exshift += s;\n      for (Index i = 0; i <= iu; ++i)\n        m_matT.coeffRef(i,i) -= s;\n      shiftInfo.setConstant(Scalar(0.964));\n    }\n  }\n}\n\n/** \\internal Compute index im at which Francis QR step starts and the first Householder vector. */\ntemplate<typename MatrixType>\ninline void RealSchur<MatrixType>::initFrancisQRStep(Index il, Index iu, const Vector3s& shiftInfo, Index& im, Vector3s& firstHouseholderVector)\n{\n  using std::abs;\n  Vector3s& v = firstHouseholderVector; // alias to save typing\n\n  for (im = iu-2; im >= il; --im)\n  {\n    const Scalar Tmm = m_matT.coeff(im,im);\n    const Scalar r = shiftInfo.coeff(0) - Tmm;\n    const Scalar s = shiftInfo.coeff(1) - Tmm;\n    v.coeffRef(0) = (r * s - shiftInfo.coeff(2)) / m_matT.coeff(im+1,im) + m_matT.coeff(im,im+1);\n    v.coeffRef(1) = m_matT.coeff(im+1,im+1) - Tmm - r - s;\n    v.coeffRef(2) = m_matT.coeff(im+2,im+1);\n    if (im == il) {\n      break;\n    }\n    const Scalar lhs = m_matT.coeff(im,im-1) * (abs(v.coeff(1)) + abs(v.coeff(2)));\n    const Scalar rhs = v.coeff(0) * (abs(m_matT.coeff(im-1,im-1)) + abs(Tmm) + abs(m_matT.coeff(im+1,im+1)));\n    if (abs(lhs) < NumTraits<Scalar>::epsilon() * rhs)\n      break;\n  }\n}\n\n/** \\internal Perform a Francis QR step involving rows il:iu and columns im:iu. */\ntemplate<typename MatrixType>\ninline void RealSchur<MatrixType>::performFrancisQRStep(Index il, Index im, Index iu, bool computeU, const Vector3s& firstHouseholderVector, Scalar* workspace)\n{\n  eigen_assert(im >= il);\n  eigen_assert(im <= iu-2);\n\n  const Index size = m_matT.cols();\n\n  for (Index k = im; k <= iu-2; ++k)\n  {\n    bool firstIteration = (k == im);\n\n    Vector3s v;\n    if (firstIteration)\n      v = firstHouseholderVector;\n    else\n      v = m_matT.template block<3,1>(k,k-1);\n\n    Scalar tau, beta;\n    Matrix<Scalar, 2, 1> ess;\n    v.makeHouseholder(ess, tau, beta);\n    \n    if (beta != Scalar(0)) // if v is not zero\n    {\n      if (firstIteration && k > il)\n        m_matT.coeffRef(k,k-1) = -m_matT.coeff(k,k-1);\n      else if (!firstIteration)\n        m_matT.coeffRef(k,k-1) = beta;\n\n      // These Householder transformations form the O(n^3) part of the algorithm\n      m_matT.block(k, k, 3, size-k).applyHouseholderOnTheLeft(ess, tau, workspace);\n      m_matT.block(0, k, (std::min)(iu,k+3) + 1, 3).applyHouseholderOnTheRight(ess, tau, workspace);\n      if (computeU)\n        m_matU.block(0, k, size, 3).applyHouseholderOnTheRight(ess, tau, workspace);\n    }\n  }\n\n  Matrix<Scalar, 2, 1> v = m_matT.template block<2,1>(iu-1, iu-2);\n  Scalar tau, beta;\n  Matrix<Scalar, 1, 1> ess;\n  v.makeHouseholder(ess, tau, beta);\n\n  if (beta != Scalar(0)) // if v is not zero\n  {\n    m_matT.coeffRef(iu-1, iu-2) = beta;\n    m_matT.block(iu-1, iu-1, 2, size-iu+1).applyHouseholderOnTheLeft(ess, tau, workspace);\n    m_matT.block(0, iu-1, iu+1, 2).applyHouseholderOnTheRight(ess, tau, workspace);\n    if (computeU)\n      m_matU.block(0, iu-1, size, 2).applyHouseholderOnTheRight(ess, tau, workspace);\n  }\n\n  // clean up pollution due to round-off errors\n  for (Index i = im+2; i <= iu; ++i)\n  {\n    m_matT.coeffRef(i,i-2) = Scalar(0);\n    if (i > im+2)\n      m_matT.coeffRef(i,i-3) = Scalar(0);\n  }\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_REAL_SCHUR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Eigenvalues/RealSchur_LAPACKE.h",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Eigen bindings to LAPACKe\n *    Real Schur needed to real unsymmetrical eigenvalues/eigenvectors.\n ********************************************************************************\n*/\n\n#ifndef EIGEN_REAL_SCHUR_LAPACKE_H\n#define EIGEN_REAL_SCHUR_LAPACKE_H\n\nnamespace Eigen { \n\n/** \\internal Specialization for the data types supported by LAPACKe */\n\n#define EIGEN_LAPACKE_SCHUR_REAL(EIGTYPE, LAPACKE_TYPE, LAPACKE_PREFIX, LAPACKE_PREFIX_U, EIGCOLROW, LAPACKE_COLROW) \\\ntemplate<> template<typename InputType> inline \\\nRealSchur<Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW> >& \\\nRealSchur<Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW> >::compute(const EigenBase<InputType>& matrix, bool computeU) \\\n{ \\\n  eigen_assert(matrix.cols() == matrix.rows()); \\\n\\\n  lapack_int n = internal::convert_index<lapack_int>(matrix.cols()), sdim, info; \\\n  lapack_int matrix_order = LAPACKE_COLROW; \\\n  char jobvs, sort='N'; \\\n  LAPACK_##LAPACKE_PREFIX_U##_SELECT2 select = 0; \\\n  jobvs = (computeU) ? 'V' : 'N'; \\\n  m_matU.resize(n, n); \\\n  lapack_int ldvs  = internal::convert_index<lapack_int>(m_matU.outerStride()); \\\n  m_matT = matrix; \\\n  lapack_int lda = internal::convert_index<lapack_int>(m_matT.outerStride()); \\\n  Matrix<EIGTYPE, Dynamic, Dynamic> wr, wi; \\\n  wr.resize(n, 1); wi.resize(n, 1); \\\n  info = LAPACKE_##LAPACKE_PREFIX##gees( matrix_order, jobvs, sort, select, n, (LAPACKE_TYPE*)m_matT.data(), lda, &sdim, (LAPACKE_TYPE*)wr.data(), (LAPACKE_TYPE*)wi.data(), (LAPACKE_TYPE*)m_matU.data(), ldvs ); \\\n  if(info == 0) \\\n    m_info = Success; \\\n  else \\\n    m_info = NoConvergence; \\\n\\\n  m_isInitialized = true; \\\n  m_matUisUptodate = computeU; \\\n  return *this; \\\n\\\n}\n\nEIGEN_LAPACKE_SCHUR_REAL(double,   double, d, D, ColMajor, LAPACK_COL_MAJOR)\nEIGEN_LAPACKE_SCHUR_REAL(float,    float,  s, S, ColMajor, LAPACK_COL_MAJOR)\nEIGEN_LAPACKE_SCHUR_REAL(double,   double, d, D, RowMajor, LAPACK_ROW_MAJOR)\nEIGEN_LAPACKE_SCHUR_REAL(float,    float,  s, S, RowMajor, LAPACK_ROW_MAJOR)\n\n} // end namespace Eigen\n\n#endif // EIGEN_REAL_SCHUR_LAPACKE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SELFADJOINTEIGENSOLVER_H\n#define EIGEN_SELFADJOINTEIGENSOLVER_H\n\n#include \"./Tridiagonalization.h\"\n\nnamespace Eigen { \n\ntemplate<typename MatrixType_>\nclass GeneralizedSelfAdjointEigenSolver;\n\nnamespace internal {\ntemplate<typename SolverType,int Size,bool IsComplex> struct direct_selfadjoint_eigenvalues;\n\ntemplate<typename MatrixType, typename DiagType, typename SubDiagType>\nEIGEN_DEVICE_FUNC\nComputationInfo computeFromTridiagonal_impl(DiagType& diag, SubDiagType& subdiag, const Index maxIterations, bool computeEigenvectors, MatrixType& eivec);\n}\n\n/** \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  *\n  * \\class SelfAdjointEigenSolver\n  *\n  * \\brief Computes eigenvalues and eigenvectors of selfadjoint matrices\n  *\n  * \\tparam MatrixType_ the type of the matrix of which we are computing the\n  * eigendecomposition; this is expected to be an instantiation of the Matrix\n  * class template.\n  *\n  * A matrix \\f$ A \\f$ is selfadjoint if it equals its adjoint. For real\n  * matrices, this means that the matrix is symmetric: it equals its\n  * transpose. This class computes the eigenvalues and eigenvectors of a\n  * selfadjoint matrix. These are the scalars \\f$ \\lambda \\f$ and vectors\n  * \\f$ v \\f$ such that \\f$ Av = \\lambda v \\f$.  The eigenvalues of a\n  * selfadjoint matrix are always real. If \\f$ D \\f$ is a diagonal matrix with\n  * the eigenvalues on the diagonal, and \\f$ V \\f$ is a matrix with the\n  * eigenvectors as its columns, then \\f$ A = V D V^{-1} \\f$. This is called the\n  * eigendecomposition.\n  *\n  * For a selfadjoint matrix, \\f$ V \\f$ is unitary, meaning its inverse is equal\n  * to its adjoint, \\f$ V^{-1} = V^{\\dagger} \\f$. If \\f$ A \\f$ is real, then\n  * \\f$ V \\f$ is also real and therefore orthogonal, meaning its inverse is\n  * equal to its transpose, \\f$ V^{-1} = V^T \\f$.\n  *\n  * The algorithm exploits the fact that the matrix is selfadjoint, making it\n  * faster and more accurate than the general purpose eigenvalue algorithms\n  * implemented in EigenSolver and ComplexEigenSolver.\n  *\n  * Only the \\b lower \\b triangular \\b part of the input matrix is referenced.\n  *\n  * Call the function compute() to compute the eigenvalues and eigenvectors of\n  * a given matrix. Alternatively, you can use the\n  * SelfAdjointEigenSolver(const MatrixType&, int) constructor which computes\n  * the eigenvalues and eigenvectors at construction time. Once the eigenvalue\n  * and eigenvectors are computed, they can be retrieved with the eigenvalues()\n  * and eigenvectors() functions.\n  *\n  * The documentation for SelfAdjointEigenSolver(const MatrixType&, int)\n  * contains an example of the typical use of this class.\n  *\n  * To solve the \\em generalized eigenvalue problem \\f$ Av = \\lambda Bv \\f$ and\n  * the likes, see the class GeneralizedSelfAdjointEigenSolver.\n  *\n  * \\sa MatrixBase::eigenvalues(), class EigenSolver, class ComplexEigenSolver\n  */\ntemplate<typename MatrixType_> class SelfAdjointEigenSolver\n{\n  public:\n\n    typedef MatrixType_ MatrixType;\n    enum {\n      Size = MatrixType::RowsAtCompileTime,\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      Options = MatrixType::Options,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n    \n    /** \\brief Scalar type for matrices of type \\p MatrixType_. */\n    typedef typename MatrixType::Scalar Scalar;\n    typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n    \n    typedef Matrix<Scalar,Size,Size,ColMajor,MaxColsAtCompileTime,MaxColsAtCompileTime> EigenvectorsType;\n\n    /** \\brief Real scalar type for \\p MatrixType_.\n      *\n      * This is just \\c Scalar if #Scalar is real (e.g., \\c float or\n      * \\c double), and the type of the real part of \\c Scalar if #Scalar is\n      * complex.\n      */\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    \n    friend struct internal::direct_selfadjoint_eigenvalues<SelfAdjointEigenSolver,Size,NumTraits<Scalar>::IsComplex>;\n\n    /** \\brief Type for vector of eigenvalues as returned by eigenvalues().\n      *\n      * This is a column vector with entries of type #RealScalar.\n      * The length of the vector is the size of \\p MatrixType_.\n      */\n    typedef typename internal::plain_col_type<MatrixType, RealScalar>::type RealVectorType;\n    typedef Tridiagonalization<MatrixType> TridiagonalizationType;\n    typedef typename TridiagonalizationType::SubDiagonalType SubDiagonalType;\n\n    /** \\brief Default constructor for fixed-size matrices.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via compute(). This constructor\n      * can only be used if \\p MatrixType_ is a fixed-size matrix; use\n      * SelfAdjointEigenSolver(Index) for dynamic-size matrices.\n      *\n      * Example: \\include SelfAdjointEigenSolver_SelfAdjointEigenSolver.cpp\n      * Output: \\verbinclude SelfAdjointEigenSolver_SelfAdjointEigenSolver.out\n      */\n    EIGEN_DEVICE_FUNC\n    SelfAdjointEigenSolver()\n        : m_eivec(),\n          m_eivalues(),\n          m_subdiag(),\n          m_hcoeffs(),\n          m_info(InvalidInput),\n          m_isInitialized(false),\n          m_eigenvectorsOk(false)\n    { }\n\n    /** \\brief Constructor, pre-allocates memory for dynamic-size matrices.\n      *\n      * \\param [in]  size  Positive integer, size of the matrix whose\n      * eigenvalues and eigenvectors will be computed.\n      *\n      * This constructor is useful for dynamic-size matrices, when the user\n      * intends to perform decompositions via compute(). The \\p size\n      * parameter is only used as a hint. It is not an error to give a wrong\n      * \\p size, but it may impair performance.\n      *\n      * \\sa compute() for an example\n      */\n    EIGEN_DEVICE_FUNC\n    explicit SelfAdjointEigenSolver(Index size)\n        : m_eivec(size, size),\n          m_eivalues(size),\n          m_subdiag(size > 1 ? size - 1 : 1),\n          m_hcoeffs(size > 1 ? size - 1 : 1),\n          m_isInitialized(false),\n          m_eigenvectorsOk(false)\n    {}\n\n    /** \\brief Constructor; computes eigendecomposition of given matrix.\n      *\n      * \\param[in]  matrix  Selfadjoint matrix whose eigendecomposition is to\n      *    be computed. Only the lower triangular part of the matrix is referenced.\n      * \\param[in]  options Can be #ComputeEigenvectors (default) or #EigenvaluesOnly.\n      *\n      * This constructor calls compute(const MatrixType&, int) to compute the\n      * eigenvalues of the matrix \\p matrix. The eigenvectors are computed if\n      * \\p options equals #ComputeEigenvectors.\n      *\n      * Example: \\include SelfAdjointEigenSolver_SelfAdjointEigenSolver_MatrixType.cpp\n      * Output: \\verbinclude SelfAdjointEigenSolver_SelfAdjointEigenSolver_MatrixType.out\n      *\n      * \\sa compute(const MatrixType&, int)\n      */\n    template<typename InputType>\n    EIGEN_DEVICE_FUNC\n    explicit SelfAdjointEigenSolver(const EigenBase<InputType>& matrix, int options = ComputeEigenvectors)\n      : m_eivec(matrix.rows(), matrix.cols()),\n        m_eivalues(matrix.cols()),\n        m_subdiag(matrix.rows() > 1 ? matrix.rows() - 1 : 1),\n        m_hcoeffs(matrix.cols() > 1 ? matrix.cols() - 1 : 1),\n        m_isInitialized(false),\n        m_eigenvectorsOk(false)\n    {\n      compute(matrix.derived(), options);\n    }\n\n    /** \\brief Computes eigendecomposition of given matrix.\n      *\n      * \\param[in]  matrix  Selfadjoint matrix whose eigendecomposition is to\n      *    be computed. Only the lower triangular part of the matrix is referenced.\n      * \\param[in]  options Can be #ComputeEigenvectors (default) or #EigenvaluesOnly.\n      * \\returns    Reference to \\c *this\n      *\n      * This function computes the eigenvalues of \\p matrix.  The eigenvalues()\n      * function can be used to retrieve them.  If \\p options equals #ComputeEigenvectors,\n      * then the eigenvectors are also computed and can be retrieved by\n      * calling eigenvectors().\n      *\n      * This implementation uses a symmetric QR algorithm. The matrix is first\n      * reduced to tridiagonal form using the Tridiagonalization class. The\n      * tridiagonal matrix is then brought to diagonal form with implicit\n      * symmetric QR steps with Wilkinson shift. Details can be found in\n      * Section 8.3 of Golub \\& Van Loan, <i>%Matrix Computations</i>.\n      *\n      * The cost of the computation is about \\f$ 9n^3 \\f$ if the eigenvectors\n      * are required and \\f$ 4n^3/3 \\f$ if they are not required.\n      *\n      * This method reuses the memory in the SelfAdjointEigenSolver object that\n      * was allocated when the object was constructed, if the size of the\n      * matrix does not change.\n      *\n      * Example: \\include SelfAdjointEigenSolver_compute_MatrixType.cpp\n      * Output: \\verbinclude SelfAdjointEigenSolver_compute_MatrixType.out\n      *\n      * \\sa SelfAdjointEigenSolver(const MatrixType&, int)\n      */\n    template<typename InputType>\n    EIGEN_DEVICE_FUNC\n    SelfAdjointEigenSolver& compute(const EigenBase<InputType>& matrix, int options = ComputeEigenvectors);\n    \n    /** \\brief Computes eigendecomposition of given matrix using a closed-form algorithm\n      *\n      * This is a variant of compute(const MatrixType&, int options) which\n      * directly solves the underlying polynomial equation.\n      * \n      * Currently only 2x2 and 3x3 matrices for which the sizes are known at compile time are supported (e.g., Matrix3d).\n      * \n      * This method is usually significantly faster than the QR iterative algorithm\n      * but it might also be less accurate. It is also worth noting that\n      * for 3x3 matrices it involves trigonometric operations which are\n      * not necessarily available for all scalar types.\n      * \n      * For the 3x3 case, we observed the following worst case relative error regarding the eigenvalues:\n      *   - double: 1e-8\n      *   - float:  1e-3\n      *\n      * \\sa compute(const MatrixType&, int options)\n      */\n    EIGEN_DEVICE_FUNC\n    SelfAdjointEigenSolver& computeDirect(const MatrixType& matrix, int options = ComputeEigenvectors);\n\n    /**\n      *\\brief Computes the eigen decomposition from a tridiagonal symmetric matrix\n      *\n      * \\param[in] diag The vector containing the diagonal of the matrix.\n      * \\param[in] subdiag The subdiagonal of the matrix.\n      * \\param[in] options Can be #ComputeEigenvectors (default) or #EigenvaluesOnly.\n      * \\returns Reference to \\c *this\n      *\n      * This function assumes that the matrix has been reduced to tridiagonal form.\n      *\n      * \\sa compute(const MatrixType&, int) for more information\n      */\n    SelfAdjointEigenSolver& computeFromTridiagonal(const RealVectorType& diag, const SubDiagonalType& subdiag , int options=ComputeEigenvectors);\n\n    /** \\brief Returns the eigenvectors of given matrix.\n      *\n      * \\returns  A const reference to the matrix whose columns are the eigenvectors.\n      *\n      * \\pre The eigenvectors have been computed before.\n      *\n      * Column \\f$ k \\f$ of the returned matrix is an eigenvector corresponding\n      * to eigenvalue number \\f$ k \\f$ as returned by eigenvalues().  The\n      * eigenvectors are normalized to have (Euclidean) norm equal to one. If\n      * this object was used to solve the eigenproblem for the selfadjoint\n      * matrix \\f$ A \\f$, then the matrix returned by this function is the\n      * matrix \\f$ V \\f$ in the eigendecomposition \\f$ A = V D V^{-1} \\f$.\n      *\n      * For a selfadjoint matrix, \\f$ V \\f$ is unitary, meaning its inverse is equal\n      * to its adjoint, \\f$ V^{-1} = V^{\\dagger} \\f$. If \\f$ A \\f$ is real, then\n      * \\f$ V \\f$ is also real and therefore orthogonal, meaning its inverse is\n      * equal to its transpose, \\f$ V^{-1} = V^T \\f$.\n      *\n      * Example: \\include SelfAdjointEigenSolver_eigenvectors.cpp\n      * Output: \\verbinclude SelfAdjointEigenSolver_eigenvectors.out\n      *\n      * \\sa eigenvalues()\n      */\n    EIGEN_DEVICE_FUNC\n    const EigenvectorsType& eigenvectors() const\n    {\n      eigen_assert(m_isInitialized && \"SelfAdjointEigenSolver is not initialized.\");\n      eigen_assert(m_eigenvectorsOk && \"The eigenvectors have not been computed together with the eigenvalues.\");\n      return m_eivec;\n    }\n\n    /** \\brief Returns the eigenvalues of given matrix.\n      *\n      * \\returns A const reference to the column vector containing the eigenvalues.\n      *\n      * \\pre The eigenvalues have been computed before.\n      *\n      * The eigenvalues are repeated according to their algebraic multiplicity,\n      * so there are as many eigenvalues as rows in the matrix. The eigenvalues\n      * are sorted in increasing order.\n      *\n      * Example: \\include SelfAdjointEigenSolver_eigenvalues.cpp\n      * Output: \\verbinclude SelfAdjointEigenSolver_eigenvalues.out\n      *\n      * \\sa eigenvectors(), MatrixBase::eigenvalues()\n      */\n    EIGEN_DEVICE_FUNC\n    const RealVectorType& eigenvalues() const\n    {\n      eigen_assert(m_isInitialized && \"SelfAdjointEigenSolver is not initialized.\");\n      return m_eivalues;\n    }\n\n    /** \\brief Computes the positive-definite square root of the matrix.\n      *\n      * \\returns the positive-definite square root of the matrix\n      *\n      * \\pre The eigenvalues and eigenvectors of a positive-definite matrix\n      * have been computed before.\n      *\n      * The square root of a positive-definite matrix \\f$ A \\f$ is the\n      * positive-definite matrix whose square equals \\f$ A \\f$. This function\n      * uses the eigendecomposition \\f$ A = V D V^{-1} \\f$ to compute the\n      * square root as \\f$ A^{1/2} = V D^{1/2} V^{-1} \\f$.\n      *\n      * Example: \\include SelfAdjointEigenSolver_operatorSqrt.cpp\n      * Output: \\verbinclude SelfAdjointEigenSolver_operatorSqrt.out\n      *\n      * \\sa operatorInverseSqrt(), <a href=\"unsupported/group__MatrixFunctions__Module.html\">MatrixFunctions Module</a>\n      */\n    EIGEN_DEVICE_FUNC\n    MatrixType operatorSqrt() const\n    {\n      eigen_assert(m_isInitialized && \"SelfAdjointEigenSolver is not initialized.\");\n      eigen_assert(m_eigenvectorsOk && \"The eigenvectors have not been computed together with the eigenvalues.\");\n      return m_eivec * m_eivalues.cwiseSqrt().asDiagonal() * m_eivec.adjoint();\n    }\n\n    /** \\brief Computes the inverse square root of the matrix.\n      *\n      * \\returns the inverse positive-definite square root of the matrix\n      *\n      * \\pre The eigenvalues and eigenvectors of a positive-definite matrix\n      * have been computed before.\n      *\n      * This function uses the eigendecomposition \\f$ A = V D V^{-1} \\f$ to\n      * compute the inverse square root as \\f$ V D^{-1/2} V^{-1} \\f$. This is\n      * cheaper than first computing the square root with operatorSqrt() and\n      * then its inverse with MatrixBase::inverse().\n      *\n      * Example: \\include SelfAdjointEigenSolver_operatorInverseSqrt.cpp\n      * Output: \\verbinclude SelfAdjointEigenSolver_operatorInverseSqrt.out\n      *\n      * \\sa operatorSqrt(), MatrixBase::inverse(), <a href=\"unsupported/group__MatrixFunctions__Module.html\">MatrixFunctions Module</a>\n      */\n    EIGEN_DEVICE_FUNC\n    MatrixType operatorInverseSqrt() const\n    {\n      eigen_assert(m_isInitialized && \"SelfAdjointEigenSolver is not initialized.\");\n      eigen_assert(m_eigenvectorsOk && \"The eigenvectors have not been computed together with the eigenvalues.\");\n      return m_eivec * m_eivalues.cwiseInverse().cwiseSqrt().asDiagonal() * m_eivec.adjoint();\n    }\n\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful, \\c NoConvergence otherwise.\n      */\n    EIGEN_DEVICE_FUNC\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"SelfAdjointEigenSolver is not initialized.\");\n      return m_info;\n    }\n\n    /** \\brief Maximum number of iterations.\n      *\n      * The algorithm terminates if it does not converge within m_maxIterations * n iterations, where n\n      * denotes the size of the matrix. This value is currently set to 30 (copied from LAPACK).\n      */\n    static const int m_maxIterations = 30;\n\n  protected:\n    static EIGEN_DEVICE_FUNC\n    void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n    }\n    \n    EigenvectorsType m_eivec;\n    RealVectorType m_eivalues;\n    typename TridiagonalizationType::SubDiagonalType m_subdiag;\n    typename TridiagonalizationType::CoeffVectorType m_hcoeffs;\n    ComputationInfo m_info;\n    bool m_isInitialized;\n    bool m_eigenvectorsOk;\n};\n\nnamespace internal {\n/** \\internal\n  *\n  * \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  * Performs a QR step on a tridiagonal symmetric matrix represented as a\n  * pair of two vectors \\a diag and \\a subdiag.\n  *\n  * \\param diag the diagonal part of the input selfadjoint tridiagonal matrix\n  * \\param subdiag the sub-diagonal part of the input selfadjoint tridiagonal matrix\n  * \\param start starting index of the submatrix to work on\n  * \\param end last+1 index of the submatrix to work on\n  * \\param matrixQ pointer to the column-major matrix holding the eigenvectors, can be 0\n  * \\param n size of the input matrix\n  *\n  * For compilation efficiency reasons, this procedure does not use eigen expression\n  * for its arguments.\n  *\n  * Implemented from Golub's \"Matrix Computations\", algorithm 8.3.2:\n  * \"implicit symmetric QR step with Wilkinson shift\"\n  */\ntemplate<int StorageOrder,typename RealScalar, typename Scalar, typename Index>\nEIGEN_DEVICE_FUNC\nstatic void tridiagonal_qr_step(RealScalar* diag, RealScalar* subdiag, Index start, Index end, Scalar* matrixQ, Index n);\n}\n\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nEIGEN_DEVICE_FUNC\nSelfAdjointEigenSolver<MatrixType>& SelfAdjointEigenSolver<MatrixType>\n::compute(const EigenBase<InputType>& a_matrix, int options)\n{\n  check_template_parameters();\n  \n  const InputType &matrix(a_matrix.derived());\n  \n  EIGEN_USING_STD(abs);\n  eigen_assert(matrix.cols() == matrix.rows());\n  eigen_assert((options&~(EigVecMask|GenEigMask))==0\n          && (options&EigVecMask)!=EigVecMask\n          && \"invalid option parameter\");\n  bool computeEigenvectors = (options&ComputeEigenvectors)==ComputeEigenvectors;\n  Index n = matrix.cols();\n  m_eivalues.resize(n,1);\n\n  if(n==1)\n  {\n    m_eivec = matrix;\n    m_eivalues.coeffRef(0,0) = numext::real(m_eivec.coeff(0,0));\n    if(computeEigenvectors)\n      m_eivec.setOnes(n,n);\n    m_info = Success;\n    m_isInitialized = true;\n    m_eigenvectorsOk = computeEigenvectors;\n    return *this;\n  }\n\n  // declare some aliases\n  RealVectorType& diag = m_eivalues;\n  EigenvectorsType& mat = m_eivec;\n\n  // map the matrix coefficients to [-1:1] to avoid over- and underflow.\n  mat = matrix.template triangularView<Lower>();\n  RealScalar scale = mat.cwiseAbs().maxCoeff();\n  if(scale==RealScalar(0)) scale = RealScalar(1);\n  mat.template triangularView<Lower>() /= scale;\n  m_subdiag.resize(n-1);\n  m_hcoeffs.resize(n-1);\n  internal::tridiagonalization_inplace(mat, diag, m_subdiag, m_hcoeffs, computeEigenvectors);\n\n  m_info = internal::computeFromTridiagonal_impl(diag, m_subdiag, m_maxIterations, computeEigenvectors, m_eivec);\n  \n  // scale back the eigen values\n  m_eivalues *= scale;\n\n  m_isInitialized = true;\n  m_eigenvectorsOk = computeEigenvectors;\n  return *this;\n}\n\ntemplate<typename MatrixType>\nSelfAdjointEigenSolver<MatrixType>& SelfAdjointEigenSolver<MatrixType>\n::computeFromTridiagonal(const RealVectorType& diag, const SubDiagonalType& subdiag , int options)\n{\n  //TODO : Add an option to scale the values beforehand\n  bool computeEigenvectors = (options&ComputeEigenvectors)==ComputeEigenvectors;\n\n  m_eivalues = diag;\n  m_subdiag = subdiag;\n  if (computeEigenvectors)\n  {\n    m_eivec.setIdentity(diag.size(), diag.size());\n  }\n  m_info = internal::computeFromTridiagonal_impl(m_eivalues, m_subdiag, m_maxIterations, computeEigenvectors, m_eivec);\n\n  m_isInitialized = true;\n  m_eigenvectorsOk = computeEigenvectors;\n  return *this;\n}\n\nnamespace internal {\n/**\n  * \\internal\n  * \\brief Compute the eigendecomposition from a tridiagonal matrix\n  *\n  * \\param[in,out] diag : On input, the diagonal of the matrix, on output the eigenvalues\n  * \\param[in,out] subdiag : The subdiagonal part of the matrix (entries are modified during the decomposition)\n  * \\param[in] maxIterations : the maximum number of iterations\n  * \\param[in] computeEigenvectors : whether the eigenvectors have to be computed or not\n  * \\param[out] eivec : The matrix to store the eigenvectors if computeEigenvectors==true. Must be allocated on input.\n  * \\returns \\c Success or \\c NoConvergence\n  */\ntemplate<typename MatrixType, typename DiagType, typename SubDiagType>\nEIGEN_DEVICE_FUNC\nComputationInfo computeFromTridiagonal_impl(DiagType& diag, SubDiagType& subdiag, const Index maxIterations, bool computeEigenvectors, MatrixType& eivec)\n{\n  ComputationInfo info;\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index n = diag.size();\n  Index end = n-1;\n  Index start = 0;\n  Index iter = 0; // total number of iterations\n  \n  typedef typename DiagType::RealScalar RealScalar;\n  const RealScalar considerAsZero = (std::numeric_limits<RealScalar>::min)();\n  const RealScalar precision_inv = RealScalar(1)/NumTraits<RealScalar>::epsilon();\n  while (end>0)\n  {\n    for (Index i = start; i<end; ++i) {\n      if (numext::abs(subdiag[i]) < considerAsZero) {\n        subdiag[i] = RealScalar(0);\n      } else {\n        // abs(subdiag[i]) <= epsilon * sqrt(abs(diag[i]) + abs(diag[i+1]))\n        // Scaled to prevent underflows.\n        const RealScalar scaled_subdiag = precision_inv * subdiag[i];\n        if (scaled_subdiag * scaled_subdiag <= (numext::abs(diag[i])+numext::abs(diag[i+1]))) {\n          subdiag[i] = RealScalar(0);\n        }\n      }\n    }\n\n    // find the largest unreduced block at the end of the matrix.\n    while (end>0 && subdiag[end-1]==RealScalar(0))\n    {\n      end--;\n    }\n    if (end<=0)\n      break;\n\n    // if we spent too many iterations, we give up\n    iter++;\n    if(iter > maxIterations * n) break;\n\n    start = end - 1;\n    while (start>0 && subdiag[start-1]!=0)\n      start--;\n\n    internal::tridiagonal_qr_step<MatrixType::Flags&RowMajorBit ? RowMajor : ColMajor>(diag.data(), subdiag.data(), start, end, computeEigenvectors ? eivec.data() : (Scalar*)0, n);\n  }\n  if (iter <= maxIterations * n)\n    info = Success;\n  else\n    info = NoConvergence;\n\n  // Sort eigenvalues and corresponding vectors.\n  // TODO make the sort optional ?\n  // TODO use a better sort algorithm !!\n  if (info == Success)\n  {\n    for (Index i = 0; i < n-1; ++i)\n    {\n      Index k;\n      diag.segment(i,n-i).minCoeff(&k);\n      if (k > 0)\n      {\n        numext::swap(diag[i], diag[k+i]);\n        if(computeEigenvectors)\n          eivec.col(i).swap(eivec.col(k+i));\n      }\n    }\n  }\n  return info;\n}\n  \ntemplate<typename SolverType,int Size,bool IsComplex> struct direct_selfadjoint_eigenvalues\n{\n  EIGEN_DEVICE_FUNC\n  static inline void run(SolverType& eig, const typename SolverType::MatrixType& A, int options)\n  { eig.compute(A,options); }\n};\n\ntemplate<typename SolverType> struct direct_selfadjoint_eigenvalues<SolverType,3,false>\n{\n  typedef typename SolverType::MatrixType MatrixType;\n  typedef typename SolverType::RealVectorType VectorType;\n  typedef typename SolverType::Scalar Scalar;\n  typedef typename SolverType::EigenvectorsType EigenvectorsType;\n  \n\n  /** \\internal\n   * Computes the roots of the characteristic polynomial of \\a m.\n   * For numerical stability m.trace() should be near zero and to avoid over- or underflow m should be normalized.\n   */\n  EIGEN_DEVICE_FUNC\n  static inline void computeRoots(const MatrixType& m, VectorType& roots)\n  {\n    EIGEN_USING_STD(sqrt)\n    EIGEN_USING_STD(atan2)\n    EIGEN_USING_STD(cos)\n    EIGEN_USING_STD(sin)\n    const Scalar s_inv3 = Scalar(1)/Scalar(3);\n    const Scalar s_sqrt3 = sqrt(Scalar(3));\n\n    // The characteristic equation is x^3 - c2*x^2 + c1*x - c0 = 0.  The\n    // eigenvalues are the roots to this equation, all guaranteed to be\n    // real-valued, because the matrix is symmetric.\n    Scalar c0 = m(0,0)*m(1,1)*m(2,2) + Scalar(2)*m(1,0)*m(2,0)*m(2,1) - m(0,0)*m(2,1)*m(2,1) - m(1,1)*m(2,0)*m(2,0) - m(2,2)*m(1,0)*m(1,0);\n    Scalar c1 = m(0,0)*m(1,1) - m(1,0)*m(1,0) + m(0,0)*m(2,2) - m(2,0)*m(2,0) + m(1,1)*m(2,2) - m(2,1)*m(2,1);\n    Scalar c2 = m(0,0) + m(1,1) + m(2,2);\n\n    // Construct the parameters used in classifying the roots of the equation\n    // and in solving the equation for the roots in closed form.\n    Scalar c2_over_3 = c2*s_inv3;\n    Scalar a_over_3 = (c2*c2_over_3 - c1)*s_inv3;\n    a_over_3 = numext::maxi(a_over_3, Scalar(0));\n\n    Scalar half_b = Scalar(0.5)*(c0 + c2_over_3*(Scalar(2)*c2_over_3*c2_over_3 - c1));\n\n    Scalar q = a_over_3*a_over_3*a_over_3 - half_b*half_b;\n    q = numext::maxi(q, Scalar(0));\n\n    // Compute the eigenvalues by solving for the roots of the polynomial.\n    Scalar rho = sqrt(a_over_3);\n    Scalar theta = atan2(sqrt(q),half_b)*s_inv3;  // since sqrt(q) > 0, atan2 is in [0, pi] and theta is in [0, pi/3]\n    Scalar cos_theta = cos(theta);\n    Scalar sin_theta = sin(theta);\n    // roots are already sorted, since cos is monotonically decreasing on [0, pi]\n    roots(0) = c2_over_3 - rho*(cos_theta + s_sqrt3*sin_theta); // == 2*rho*cos(theta+2pi/3)\n    roots(1) = c2_over_3 - rho*(cos_theta - s_sqrt3*sin_theta); // == 2*rho*cos(theta+ pi/3)\n    roots(2) = c2_over_3 + Scalar(2)*rho*cos_theta;\n  }\n\n  EIGEN_DEVICE_FUNC\n  static inline bool extract_kernel(MatrixType& mat, Ref<VectorType> res, Ref<VectorType> representative)\n  {\n    EIGEN_USING_STD(abs);\n    EIGEN_USING_STD(sqrt);\n    Index i0;\n    // Find non-zero column i0 (by construction, there must exist a non zero coefficient on the diagonal):\n    mat.diagonal().cwiseAbs().maxCoeff(&i0);\n    // mat.col(i0) is a good candidate for an orthogonal vector to the current eigenvector,\n    // so let's save it:\n    representative = mat.col(i0);\n    Scalar n0, n1;\n    VectorType c0, c1;\n    n0 = (c0 = representative.cross(mat.col((i0+1)%3))).squaredNorm();\n    n1 = (c1 = representative.cross(mat.col((i0+2)%3))).squaredNorm();\n    if(n0>n1) res = c0/sqrt(n0);\n    else      res = c1/sqrt(n1);\n\n    return true;\n  }\n\n  EIGEN_DEVICE_FUNC\n  static inline void run(SolverType& solver, const MatrixType& mat, int options)\n  {\n    eigen_assert(mat.cols() == 3 && mat.cols() == mat.rows());\n    eigen_assert((options&~(EigVecMask|GenEigMask))==0\n            && (options&EigVecMask)!=EigVecMask\n            && \"invalid option parameter\");\n    bool computeEigenvectors = (options&ComputeEigenvectors)==ComputeEigenvectors;\n    \n    EigenvectorsType& eivecs = solver.m_eivec;\n    VectorType& eivals = solver.m_eivalues;\n  \n    // Shift the matrix to the mean eigenvalue and map the matrix coefficients to [-1:1] to avoid over- and underflow.\n    Scalar shift = mat.trace() / Scalar(3);\n    // TODO Avoid this copy. Currently it is necessary to suppress bogus values when determining maxCoeff and for computing the eigenvectors later\n    MatrixType scaledMat = mat.template selfadjointView<Lower>();\n    scaledMat.diagonal().array() -= shift;\n    Scalar scale = scaledMat.cwiseAbs().maxCoeff();\n    if(scale > 0) scaledMat /= scale;   // TODO for scale==0 we could save the remaining operations\n\n    // compute the eigenvalues\n    computeRoots(scaledMat,eivals);\n\n    // compute the eigenvectors\n    if(computeEigenvectors)\n    {\n      if((eivals(2)-eivals(0))<=Eigen::NumTraits<Scalar>::epsilon())\n      {\n        // All three eigenvalues are numerically the same\n        eivecs.setIdentity();\n      }\n      else\n      {\n        MatrixType tmp;\n        tmp = scaledMat;\n\n        // Compute the eigenvector of the most distinct eigenvalue\n        Scalar d0 = eivals(2) - eivals(1);\n        Scalar d1 = eivals(1) - eivals(0);\n        Index k(0), l(2);\n        if(d0 > d1)\n        {\n          numext::swap(k,l);\n          d0 = d1;\n        }\n\n        // Compute the eigenvector of index k\n        {\n          tmp.diagonal().array () -= eivals(k);\n          // By construction, 'tmp' is of rank 2, and its kernel corresponds to the respective eigenvector.\n          extract_kernel(tmp, eivecs.col(k), eivecs.col(l));\n        }\n\n        // Compute eigenvector of index l\n        if(d0<=2*Eigen::NumTraits<Scalar>::epsilon()*d1)\n        {\n          // If d0 is too small, then the two other eigenvalues are numerically the same,\n          // and thus we only have to ortho-normalize the near orthogonal vector we saved above.\n          eivecs.col(l) -= eivecs.col(k).dot(eivecs.col(l))*eivecs.col(l);\n          eivecs.col(l).normalize();\n        }\n        else\n        {\n          tmp = scaledMat;\n          tmp.diagonal().array () -= eivals(l);\n\n          VectorType dummy;\n          extract_kernel(tmp, eivecs.col(l), dummy);\n        }\n\n        // Compute last eigenvector from the other two\n        eivecs.col(1) = eivecs.col(2).cross(eivecs.col(0)).normalized();\n      }\n    }\n\n    // Rescale back to the original size.\n    eivals *= scale;\n    eivals.array() += shift;\n    \n    solver.m_info = Success;\n    solver.m_isInitialized = true;\n    solver.m_eigenvectorsOk = computeEigenvectors;\n  }\n};\n\n// 2x2 direct eigenvalues decomposition, code from Hauke Heibel\ntemplate<typename SolverType> \nstruct direct_selfadjoint_eigenvalues<SolverType,2,false>\n{\n  typedef typename SolverType::MatrixType MatrixType;\n  typedef typename SolverType::RealVectorType VectorType;\n  typedef typename SolverType::Scalar Scalar;\n  typedef typename SolverType::EigenvectorsType EigenvectorsType;\n  \n  EIGEN_DEVICE_FUNC\n  static inline void computeRoots(const MatrixType& m, VectorType& roots)\n  {\n    EIGEN_USING_STD(sqrt);\n    const Scalar t0 = Scalar(0.5) * sqrt( numext::abs2(m(0,0)-m(1,1)) + Scalar(4)*numext::abs2(m(1,0)));\n    const Scalar t1 = Scalar(0.5) * (m(0,0) + m(1,1));\n    roots(0) = t1 - t0;\n    roots(1) = t1 + t0;\n  }\n  \n  EIGEN_DEVICE_FUNC\n  static inline void run(SolverType& solver, const MatrixType& mat, int options)\n  {\n    EIGEN_USING_STD(sqrt);\n    EIGEN_USING_STD(abs);\n    \n    eigen_assert(mat.cols() == 2 && mat.cols() == mat.rows());\n    eigen_assert((options&~(EigVecMask|GenEigMask))==0\n            && (options&EigVecMask)!=EigVecMask\n            && \"invalid option parameter\");\n    bool computeEigenvectors = (options&ComputeEigenvectors)==ComputeEigenvectors;\n    \n    EigenvectorsType& eivecs = solver.m_eivec;\n    VectorType& eivals = solver.m_eivalues;\n  \n    // Shift the matrix to the mean eigenvalue and map the matrix coefficients to [-1:1] to avoid over- and underflow.\n    Scalar shift = mat.trace() / Scalar(2);\n    MatrixType scaledMat = mat;\n    scaledMat.coeffRef(0,1) = mat.coeff(1,0);\n    scaledMat.diagonal().array() -= shift;\n    Scalar scale = scaledMat.cwiseAbs().maxCoeff();\n    if(scale > Scalar(0))\n      scaledMat /= scale;\n\n    // Compute the eigenvalues\n    computeRoots(scaledMat,eivals);\n\n    // compute the eigen vectors\n    if(computeEigenvectors)\n    {\n      if((eivals(1)-eivals(0))<=abs(eivals(1))*Eigen::NumTraits<Scalar>::epsilon())\n      {\n        eivecs.setIdentity();\n      }\n      else\n      {\n        scaledMat.diagonal().array () -= eivals(1);\n        Scalar a2 = numext::abs2(scaledMat(0,0));\n        Scalar c2 = numext::abs2(scaledMat(1,1));\n        Scalar b2 = numext::abs2(scaledMat(1,0));\n        if(a2>c2)\n        {\n          eivecs.col(1) << -scaledMat(1,0), scaledMat(0,0);\n          eivecs.col(1) /= sqrt(a2+b2);\n        }\n        else\n        {\n          eivecs.col(1) << -scaledMat(1,1), scaledMat(1,0);\n          eivecs.col(1) /= sqrt(c2+b2);\n        }\n\n        eivecs.col(0) << eivecs.col(1).unitOrthogonal();\n      }\n    }\n\n    // Rescale back to the original size.\n    eivals *= scale;\n    eivals.array() += shift;\n\n    solver.m_info = Success;\n    solver.m_isInitialized = true;\n    solver.m_eigenvectorsOk = computeEigenvectors;\n  }\n};\n\n}\n\ntemplate<typename MatrixType>\nEIGEN_DEVICE_FUNC\nSelfAdjointEigenSolver<MatrixType>& SelfAdjointEigenSolver<MatrixType>\n::computeDirect(const MatrixType& matrix, int options)\n{\n  internal::direct_selfadjoint_eigenvalues<SelfAdjointEigenSolver,Size,NumTraits<Scalar>::IsComplex>::run(*this,matrix,options);\n  return *this;\n}\n\nnamespace internal {\n\n// Francis implicit QR step.\ntemplate<int StorageOrder,typename RealScalar, typename Scalar, typename Index>\nEIGEN_DEVICE_FUNC\nstatic void tridiagonal_qr_step(RealScalar* diag, RealScalar* subdiag, Index start, Index end, Scalar* matrixQ, Index n)\n{\n  // Wilkinson Shift.\n  RealScalar td = (diag[end-1] - diag[end])*RealScalar(0.5);\n  RealScalar e = subdiag[end-1];\n  // Note that thanks to scaling, e^2 or td^2 cannot overflow, however they can still\n  // underflow thus leading to inf/NaN values when using the following commented code:\n  //   RealScalar e2 = numext::abs2(subdiag[end-1]);\n  //   RealScalar mu = diag[end] - e2 / (td + (td>0 ? 1 : -1) * sqrt(td*td + e2));\n  // This explain the following, somewhat more complicated, version:\n  RealScalar mu = diag[end];\n  if(td==RealScalar(0)) {\n    mu -= numext::abs(e);\n  } else if (e != RealScalar(0)) {\n    const RealScalar e2 = numext::abs2(e);\n    const RealScalar h = numext::hypot(td,e);\n    if(e2 == RealScalar(0)) {\n      mu -= e / ((td + (td>RealScalar(0) ? h : -h)) / e);\n    } else {\n      mu -= e2 / (td + (td>RealScalar(0) ? h : -h)); \n    }\n  }\n\n  RealScalar x = diag[start] - mu;\n  RealScalar z = subdiag[start];\n  // If z ever becomes zero, the Givens rotation will be the identity and\n  // z will stay zero for all future iterations.\n  for (Index k = start; k < end && z != RealScalar(0); ++k)\n  {\n    JacobiRotation<RealScalar> rot;\n    rot.makeGivens(x, z);\n\n    // do T = G' T G\n    RealScalar sdk = rot.s() * diag[k] + rot.c() * subdiag[k];\n    RealScalar dkp1 = rot.s() * subdiag[k] + rot.c() * diag[k+1];\n\n    diag[k] = rot.c() * (rot.c() * diag[k] - rot.s() * subdiag[k]) - rot.s() * (rot.c() * subdiag[k] - rot.s() * diag[k+1]);\n    diag[k+1] = rot.s() * sdk + rot.c() * dkp1;\n    subdiag[k] = rot.c() * sdk - rot.s() * dkp1;\n    \n    if (k > start)\n      subdiag[k - 1] = rot.c() * subdiag[k-1] - rot.s() * z;\n\n    // \"Chasing the bulge\" to return to triangular form.\n    x = subdiag[k];\n    if (k < end - 1)\n    {\n      z = -rot.s() * subdiag[k+1];\n      subdiag[k + 1] = rot.c() * subdiag[k+1];\n    }\n    \n    // apply the givens rotation to the unit matrix Q = Q * G\n    if (matrixQ)\n    {\n      // FIXME if StorageOrder == RowMajor this operation is not very efficient\n      Map<Matrix<Scalar,Dynamic,Dynamic,StorageOrder> > q(matrixQ,n,n);\n      q.applyOnTheRight(k,k+1,rot);\n    }\n  }\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SELFADJOINTEIGENSOLVER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_LAPACKE.h",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Eigen bindings to LAPACKe\n *    Self-adjoint eigenvalues/eigenvectors.\n ********************************************************************************\n*/\n\n#ifndef EIGEN_SAEIGENSOLVER_LAPACKE_H\n#define EIGEN_SAEIGENSOLVER_LAPACKE_H\n\nnamespace Eigen { \n\n/** \\internal Specialization for the data types supported by LAPACKe */\n\n#define EIGEN_LAPACKE_EIG_SELFADJ_2(EIGTYPE, LAPACKE_TYPE, LAPACKE_RTYPE, LAPACKE_NAME, EIGCOLROW ) \\\ntemplate<> template<typename InputType> inline \\\nSelfAdjointEigenSolver<Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW> >& \\\nSelfAdjointEigenSolver<Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW> >::compute(const EigenBase<InputType>& matrix, int options) \\\n{ \\\n  eigen_assert(matrix.cols() == matrix.rows()); \\\n  eigen_assert((options&~(EigVecMask|GenEigMask))==0 \\\n          && (options&EigVecMask)!=EigVecMask \\\n          && \"invalid option parameter\"); \\\n  bool computeEigenvectors = (options&ComputeEigenvectors)==ComputeEigenvectors; \\\n  lapack_int n = internal::convert_index<lapack_int>(matrix.cols()), lda, info; \\\n  m_eivalues.resize(n,1); \\\n  m_subdiag.resize(n-1); \\\n  m_eivec = matrix; \\\n\\\n  if(n==1) \\\n  { \\\n    m_eivalues.coeffRef(0,0) = numext::real(m_eivec.coeff(0,0)); \\\n    if(computeEigenvectors) m_eivec.setOnes(n,n); \\\n    m_info = Success; \\\n    m_isInitialized = true; \\\n    m_eigenvectorsOk = computeEigenvectors; \\\n    return *this; \\\n  } \\\n\\\n  lda = internal::convert_index<lapack_int>(m_eivec.outerStride()); \\\n  char jobz, uplo='L'/*, range='A'*/; \\\n  jobz = computeEigenvectors ? 'V' : 'N'; \\\n\\\n  info = LAPACKE_##LAPACKE_NAME( LAPACK_COL_MAJOR, jobz, uplo, n, (LAPACKE_TYPE*)m_eivec.data(), lda, (LAPACKE_RTYPE*)m_eivalues.data() ); \\\n  m_info = (info==0) ? Success : NoConvergence; \\\n  m_isInitialized = true; \\\n  m_eigenvectorsOk = computeEigenvectors; \\\n  return *this; \\\n}\n\n#define EIGEN_LAPACKE_EIG_SELFADJ(EIGTYPE, LAPACKE_TYPE, LAPACKE_RTYPE, LAPACKE_NAME )              \\\n        EIGEN_LAPACKE_EIG_SELFADJ_2(EIGTYPE, LAPACKE_TYPE, LAPACKE_RTYPE, LAPACKE_NAME, ColMajor )  \\\n        EIGEN_LAPACKE_EIG_SELFADJ_2(EIGTYPE, LAPACKE_TYPE, LAPACKE_RTYPE, LAPACKE_NAME, RowMajor ) \n\nEIGEN_LAPACKE_EIG_SELFADJ(double,   double,                double, dsyev)\nEIGEN_LAPACKE_EIG_SELFADJ(float,    float,                 float,  ssyev)\nEIGEN_LAPACKE_EIG_SELFADJ(dcomplex, lapack_complex_double, double, zheev)\nEIGEN_LAPACKE_EIG_SELFADJ(scomplex, lapack_complex_float,  float,  cheev)\n\n} // end namespace Eigen\n\n#endif // EIGEN_SAEIGENSOLVER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Eigenvalues/Tridiagonalization.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_TRIDIAGONALIZATION_H\n#define EIGEN_TRIDIAGONALIZATION_H\n\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate<typename MatrixType> struct TridiagonalizationMatrixTReturnType;\ntemplate<typename MatrixType>\nstruct traits<TridiagonalizationMatrixTReturnType<MatrixType> >\n  : public traits<typename MatrixType::PlainObject>\n{\n  typedef typename MatrixType::PlainObject ReturnType; // FIXME shall it be a BandMatrix?\n  enum { Flags = 0 };\n};\n\ntemplate<typename MatrixType, typename CoeffVectorType>\nEIGEN_DEVICE_FUNC\nvoid tridiagonalization_inplace(MatrixType& matA, CoeffVectorType& hCoeffs);\n}\n\n/** \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  *\n  * \\class Tridiagonalization\n  *\n  * \\brief Tridiagonal decomposition of a selfadjoint matrix\n  *\n  * \\tparam MatrixType_ the type of the matrix of which we are computing the\n  * tridiagonal decomposition; this is expected to be an instantiation of the\n  * Matrix class template.\n  *\n  * This class performs a tridiagonal decomposition of a selfadjoint matrix \\f$ A \\f$ such that:\n  * \\f$ A = Q T Q^* \\f$ where \\f$ Q \\f$ is unitary and \\f$ T \\f$ a real symmetric tridiagonal matrix.\n  *\n  * A tridiagonal matrix is a matrix which has nonzero elements only on the\n  * main diagonal and the first diagonal below and above it. The Hessenberg\n  * decomposition of a selfadjoint matrix is in fact a tridiagonal\n  * decomposition. This class is used in SelfAdjointEigenSolver to compute the\n  * eigenvalues and eigenvectors of a selfadjoint matrix.\n  *\n  * Call the function compute() to compute the tridiagonal decomposition of a\n  * given matrix. Alternatively, you can use the Tridiagonalization(const MatrixType&)\n  * constructor which computes the tridiagonal Schur decomposition at\n  * construction time. Once the decomposition is computed, you can use the\n  * matrixQ() and matrixT() functions to retrieve the matrices Q and T in the\n  * decomposition.\n  *\n  * The documentation of Tridiagonalization(const MatrixType&) contains an\n  * example of the typical use of this class.\n  *\n  * \\sa class HessenbergDecomposition, class SelfAdjointEigenSolver\n  */\ntemplate<typename MatrixType_> class Tridiagonalization\n{\n  public:\n\n    /** \\brief Synonym for the template parameter \\p MatrixType_. */\n    typedef MatrixType_ MatrixType;\n\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n\n    enum {\n      Size = MatrixType::RowsAtCompileTime,\n      SizeMinusOne = Size == Dynamic ? Dynamic : (Size > 1 ? Size - 1 : 1),\n      Options = MatrixType::Options,\n      MaxSize = MatrixType::MaxRowsAtCompileTime,\n      MaxSizeMinusOne = MaxSize == Dynamic ? Dynamic : (MaxSize > 1 ? MaxSize - 1 : 1)\n    };\n\n    typedef Matrix<Scalar, SizeMinusOne, 1, Options & ~RowMajor, MaxSizeMinusOne, 1> CoeffVectorType;\n    typedef typename internal::plain_col_type<MatrixType, RealScalar>::type DiagonalType;\n    typedef Matrix<RealScalar, SizeMinusOne, 1, Options & ~RowMajor, MaxSizeMinusOne, 1> SubDiagonalType;\n    typedef typename internal::remove_all<typename MatrixType::RealReturnType>::type MatrixTypeRealView;\n    typedef internal::TridiagonalizationMatrixTReturnType<MatrixTypeRealView> MatrixTReturnType;\n\n    typedef typename internal::conditional<NumTraits<Scalar>::IsComplex,\n              typename internal::add_const_on_value_type<typename Diagonal<const MatrixType>::RealReturnType>::type,\n              const Diagonal<const MatrixType>\n            >::type DiagonalReturnType;\n\n    typedef typename internal::conditional<NumTraits<Scalar>::IsComplex,\n              typename internal::add_const_on_value_type<typename Diagonal<const MatrixType, -1>::RealReturnType>::type,\n              const Diagonal<const MatrixType, -1>\n            >::type SubDiagonalReturnType;\n\n    /** \\brief Return type of matrixQ() */\n    typedef HouseholderSequence<MatrixType,typename internal::remove_all<typename CoeffVectorType::ConjugateReturnType>::type> HouseholderSequenceType;\n\n    /** \\brief Default constructor.\n      *\n      * \\param [in]  size  Positive integer, size of the matrix whose tridiagonal\n      * decomposition will be computed.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via compute().  The \\p size parameter is only\n      * used as a hint. It is not an error to give a wrong \\p size, but it may\n      * impair performance.\n      *\n      * \\sa compute() for an example.\n      */\n    explicit Tridiagonalization(Index size = Size==Dynamic ? 2 : Size)\n      : m_matrix(size,size),\n        m_hCoeffs(size > 1 ? size-1 : 1),\n        m_isInitialized(false)\n    {}\n\n    /** \\brief Constructor; computes tridiagonal decomposition of given matrix.\n      *\n      * \\param[in]  matrix  Selfadjoint matrix whose tridiagonal decomposition\n      * is to be computed.\n      *\n      * This constructor calls compute() to compute the tridiagonal decomposition.\n      *\n      * Example: \\include Tridiagonalization_Tridiagonalization_MatrixType.cpp\n      * Output: \\verbinclude Tridiagonalization_Tridiagonalization_MatrixType.out\n      */\n    template<typename InputType>\n    explicit Tridiagonalization(const EigenBase<InputType>& matrix)\n      : m_matrix(matrix.derived()),\n        m_hCoeffs(matrix.cols() > 1 ? matrix.cols()-1 : 1),\n        m_isInitialized(false)\n    {\n      internal::tridiagonalization_inplace(m_matrix, m_hCoeffs);\n      m_isInitialized = true;\n    }\n\n    /** \\brief Computes tridiagonal decomposition of given matrix.\n      *\n      * \\param[in]  matrix  Selfadjoint matrix whose tridiagonal decomposition\n      * is to be computed.\n      * \\returns    Reference to \\c *this\n      *\n      * The tridiagonal decomposition is computed by bringing the columns of\n      * the matrix successively in the required form using Householder\n      * reflections. The cost is \\f$ 4n^3/3 \\f$ flops, where \\f$ n \\f$ denotes\n      * the size of the given matrix.\n      *\n      * This method reuses of the allocated data in the Tridiagonalization\n      * object, if the size of the matrix does not change.\n      *\n      * Example: \\include Tridiagonalization_compute.cpp\n      * Output: \\verbinclude Tridiagonalization_compute.out\n      */\n    template<typename InputType>\n    Tridiagonalization& compute(const EigenBase<InputType>& matrix)\n    {\n      m_matrix = matrix.derived();\n      m_hCoeffs.resize(matrix.rows()-1, 1);\n      internal::tridiagonalization_inplace(m_matrix, m_hCoeffs);\n      m_isInitialized = true;\n      return *this;\n    }\n\n    /** \\brief Returns the Householder coefficients.\n      *\n      * \\returns a const reference to the vector of Householder coefficients\n      *\n      * \\pre Either the constructor Tridiagonalization(const MatrixType&) or\n      * the member function compute(const MatrixType&) has been called before\n      * to compute the tridiagonal decomposition of a matrix.\n      *\n      * The Householder coefficients allow the reconstruction of the matrix\n      * \\f$ Q \\f$ in the tridiagonal decomposition from the packed data.\n      *\n      * Example: \\include Tridiagonalization_householderCoefficients.cpp\n      * Output: \\verbinclude Tridiagonalization_householderCoefficients.out\n      *\n      * \\sa packedMatrix(), \\ref Householder_Module \"Householder module\"\n      */\n    inline CoeffVectorType householderCoefficients() const\n    {\n      eigen_assert(m_isInitialized && \"Tridiagonalization is not initialized.\");\n      return m_hCoeffs;\n    }\n\n    /** \\brief Returns the internal representation of the decomposition\n      *\n      *\t\\returns a const reference to a matrix with the internal representation\n      *\t         of the decomposition.\n      *\n      * \\pre Either the constructor Tridiagonalization(const MatrixType&) or\n      * the member function compute(const MatrixType&) has been called before\n      * to compute the tridiagonal decomposition of a matrix.\n      *\n      * The returned matrix contains the following information:\n      *  - the strict upper triangular part is equal to the input matrix A.\n      *  - the diagonal and lower sub-diagonal represent the real tridiagonal\n      *    symmetric matrix T.\n      *  - the rest of the lower part contains the Householder vectors that,\n      *    combined with Householder coefficients returned by\n      *    householderCoefficients(), allows to reconstruct the matrix Q as\n      *       \\f$ Q = H_{N-1} \\ldots H_1 H_0 \\f$.\n      *    Here, the matrices \\f$ H_i \\f$ are the Householder transformations\n      *       \\f$ H_i = (I - h_i v_i v_i^T) \\f$\n      *    where \\f$ h_i \\f$ is the \\f$ i \\f$th Householder coefficient and\n      *    \\f$ v_i \\f$ is the Householder vector defined by\n      *       \\f$ v_i = [ 0, \\ldots, 0, 1, M(i+2,i), \\ldots, M(N-1,i) ]^T \\f$\n      *    with M the matrix returned by this function.\n      *\n      * See LAPACK for further details on this packed storage.\n      *\n      * Example: \\include Tridiagonalization_packedMatrix.cpp\n      * Output: \\verbinclude Tridiagonalization_packedMatrix.out\n      *\n      * \\sa householderCoefficients()\n      */\n    inline const MatrixType& packedMatrix() const\n    {\n      eigen_assert(m_isInitialized && \"Tridiagonalization is not initialized.\");\n      return m_matrix;\n    }\n\n    /** \\brief Returns the unitary matrix Q in the decomposition\n      *\n      * \\returns object representing the matrix Q\n      *\n      * \\pre Either the constructor Tridiagonalization(const MatrixType&) or\n      * the member function compute(const MatrixType&) has been called before\n      * to compute the tridiagonal decomposition of a matrix.\n      *\n      * This function returns a light-weight object of template class\n      * HouseholderSequence. You can either apply it directly to a matrix or\n      * you can convert it to a matrix of type #MatrixType.\n      *\n      * \\sa Tridiagonalization(const MatrixType&) for an example,\n      *     matrixT(), class HouseholderSequence\n      */\n    HouseholderSequenceType matrixQ() const\n    {\n      eigen_assert(m_isInitialized && \"Tridiagonalization is not initialized.\");\n      return HouseholderSequenceType(m_matrix, m_hCoeffs.conjugate())\n             .setLength(m_matrix.rows() - 1)\n             .setShift(1);\n    }\n\n    /** \\brief Returns an expression of the tridiagonal matrix T in the decomposition\n      *\n      * \\returns expression object representing the matrix T\n      *\n      * \\pre Either the constructor Tridiagonalization(const MatrixType&) or\n      * the member function compute(const MatrixType&) has been called before\n      * to compute the tridiagonal decomposition of a matrix.\n      *\n      * Currently, this function can be used to extract the matrix T from internal\n      * data and copy it to a dense matrix object. In most cases, it may be\n      * sufficient to directly use the packed matrix or the vector expressions\n      * returned by diagonal() and subDiagonal() instead of creating a new\n      * dense copy matrix with this function.\n      *\n      * \\sa Tridiagonalization(const MatrixType&) for an example,\n      * matrixQ(), packedMatrix(), diagonal(), subDiagonal()\n      */\n    MatrixTReturnType matrixT() const\n    {\n      eigen_assert(m_isInitialized && \"Tridiagonalization is not initialized.\");\n      return MatrixTReturnType(m_matrix.real());\n    }\n\n    /** \\brief Returns the diagonal of the tridiagonal matrix T in the decomposition.\n      *\n      * \\returns expression representing the diagonal of T\n      *\n      * \\pre Either the constructor Tridiagonalization(const MatrixType&) or\n      * the member function compute(const MatrixType&) has been called before\n      * to compute the tridiagonal decomposition of a matrix.\n      *\n      * Example: \\include Tridiagonalization_diagonal.cpp\n      * Output: \\verbinclude Tridiagonalization_diagonal.out\n      *\n      * \\sa matrixT(), subDiagonal()\n      */\n    DiagonalReturnType diagonal() const;\n\n    /** \\brief Returns the subdiagonal of the tridiagonal matrix T in the decomposition.\n      *\n      * \\returns expression representing the subdiagonal of T\n      *\n      * \\pre Either the constructor Tridiagonalization(const MatrixType&) or\n      * the member function compute(const MatrixType&) has been called before\n      * to compute the tridiagonal decomposition of a matrix.\n      *\n      * \\sa diagonal() for an example, matrixT()\n      */\n    SubDiagonalReturnType subDiagonal() const;\n\n  protected:\n\n    MatrixType m_matrix;\n    CoeffVectorType m_hCoeffs;\n    bool m_isInitialized;\n};\n\ntemplate<typename MatrixType>\ntypename Tridiagonalization<MatrixType>::DiagonalReturnType\nTridiagonalization<MatrixType>::diagonal() const\n{\n  eigen_assert(m_isInitialized && \"Tridiagonalization is not initialized.\");\n  return m_matrix.diagonal().real();\n}\n\ntemplate<typename MatrixType>\ntypename Tridiagonalization<MatrixType>::SubDiagonalReturnType\nTridiagonalization<MatrixType>::subDiagonal() const\n{\n  eigen_assert(m_isInitialized && \"Tridiagonalization is not initialized.\");\n  return m_matrix.template diagonal<-1>().real();\n}\n\nnamespace internal {\n\n/** \\internal\n  * Performs a tridiagonal decomposition of the selfadjoint matrix \\a matA in-place.\n  *\n  * \\param[in,out] matA On input the selfadjoint matrix. Only the \\b lower triangular part is referenced.\n  *                     On output, the strict upper part is left unchanged, and the lower triangular part\n  *                     represents the T and Q matrices in packed format has detailed below.\n  * \\param[out]    hCoeffs returned Householder coefficients (see below)\n  *\n  * On output, the tridiagonal selfadjoint matrix T is stored in the diagonal\n  * and lower sub-diagonal of the matrix \\a matA.\n  * The unitary matrix Q is represented in a compact way as a product of\n  * Householder reflectors \\f$ H_i \\f$ such that:\n  *       \\f$ Q = H_{N-1} \\ldots H_1 H_0 \\f$.\n  * The Householder reflectors are defined as\n  *       \\f$ H_i = (I - h_i v_i v_i^T) \\f$\n  * where \\f$ h_i = hCoeffs[i]\\f$ is the \\f$ i \\f$th Householder coefficient and\n  * \\f$ v_i \\f$ is the Householder vector defined by\n  *       \\f$ v_i = [ 0, \\ldots, 0, 1, matA(i+2,i), \\ldots, matA(N-1,i) ]^T \\f$.\n  *\n  * Implemented from Golub's \"Matrix Computations\", algorithm 8.3.1.\n  *\n  * \\sa Tridiagonalization::packedMatrix()\n  */\ntemplate<typename MatrixType, typename CoeffVectorType>\nEIGEN_DEVICE_FUNC\nvoid tridiagonalization_inplace(MatrixType& matA, CoeffVectorType& hCoeffs)\n{\n  using numext::conj;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  Index n = matA.rows();\n  eigen_assert(n==matA.cols());\n  eigen_assert(n==hCoeffs.size()+1 || n==1);\n\n  for (Index i = 0; i<n-1; ++i)\n  {\n    Index remainingSize = n-i-1;\n    RealScalar beta;\n    Scalar h;\n    matA.col(i).tail(remainingSize).makeHouseholderInPlace(h, beta);\n\n    // Apply similarity transformation to remaining columns,\n    // i.e., A = H A H' where H = I - h v v' and v = matA.col(i).tail(n-i-1)\n    matA.col(i).coeffRef(i+1) = 1;\n\n    hCoeffs.tail(n-i-1).noalias() = (matA.bottomRightCorner(remainingSize,remainingSize).template selfadjointView<Lower>()\n                                  * (conj(h) * matA.col(i).tail(remainingSize)));\n\n    hCoeffs.tail(n-i-1) += (conj(h)*RealScalar(-0.5)*(hCoeffs.tail(remainingSize).dot(matA.col(i).tail(remainingSize)))) * matA.col(i).tail(n-i-1);\n\n    matA.bottomRightCorner(remainingSize, remainingSize).template selfadjointView<Lower>()\n      .rankUpdate(matA.col(i).tail(remainingSize), hCoeffs.tail(remainingSize), Scalar(-1));\n\n    matA.col(i).coeffRef(i+1) = beta;\n    hCoeffs.coeffRef(i) = h;\n  }\n}\n\n// forward declaration, implementation at the end of this file\ntemplate<typename MatrixType,\n         int Size=MatrixType::ColsAtCompileTime,\n         bool IsComplex=NumTraits<typename MatrixType::Scalar>::IsComplex>\nstruct tridiagonalization_inplace_selector;\n\n/** \\brief Performs a full tridiagonalization in place\n  *\n  * \\param[in,out]  mat  On input, the selfadjoint matrix whose tridiagonal\n  *    decomposition is to be computed. Only the lower triangular part referenced.\n  *    The rest is left unchanged. On output, the orthogonal matrix Q\n  *    in the decomposition if \\p extractQ is true.\n  * \\param[out]  diag  The diagonal of the tridiagonal matrix T in the\n  *    decomposition.\n  * \\param[out]  subdiag  The subdiagonal of the tridiagonal matrix T in\n  *    the decomposition.\n  * \\param[in]  extractQ  If true, the orthogonal matrix Q in the\n  *    decomposition is computed and stored in \\p mat.\n  *\n  * Computes the tridiagonal decomposition of the selfadjoint matrix \\p mat in place\n  * such that \\f$ mat = Q T Q^* \\f$ where \\f$ Q \\f$ is unitary and \\f$ T \\f$ a real\n  * symmetric tridiagonal matrix.\n  *\n  * The tridiagonal matrix T is passed to the output parameters \\p diag and \\p subdiag. If\n  * \\p extractQ is true, then the orthogonal matrix Q is passed to \\p mat. Otherwise the lower\n  * part of the matrix \\p mat is destroyed.\n  *\n  * The vectors \\p diag and \\p subdiag are not resized. The function\n  * assumes that they are already of the correct size. The length of the\n  * vector \\p diag should equal the number of rows in \\p mat, and the\n  * length of the vector \\p subdiag should be one left.\n  *\n  * This implementation contains an optimized path for 3-by-3 matrices\n  * which is especially useful for plane fitting.\n  *\n  * \\note Currently, it requires two temporary vectors to hold the intermediate\n  * Householder coefficients, and to reconstruct the matrix Q from the Householder\n  * reflectors.\n  *\n  * Example (this uses the same matrix as the example in\n  *    Tridiagonalization::Tridiagonalization(const MatrixType&)):\n  *    \\include Tridiagonalization_decomposeInPlace.cpp\n  * Output: \\verbinclude Tridiagonalization_decomposeInPlace.out\n  *\n  * \\sa class Tridiagonalization\n  */\ntemplate<typename MatrixType, typename DiagonalType, typename SubDiagonalType, typename CoeffVectorType>\nEIGEN_DEVICE_FUNC\nvoid tridiagonalization_inplace(MatrixType& mat, DiagonalType& diag, SubDiagonalType& subdiag,\n                                CoeffVectorType& hcoeffs, bool extractQ)\n{\n  eigen_assert(mat.cols()==mat.rows() && diag.size()==mat.rows() && subdiag.size()==mat.rows()-1);\n  tridiagonalization_inplace_selector<MatrixType>::run(mat, diag, subdiag, hcoeffs, extractQ);\n}\n\n/** \\internal\n  * General full tridiagonalization\n  */\ntemplate<typename MatrixType, int Size, bool IsComplex>\nstruct tridiagonalization_inplace_selector\n{\n  typedef typename Tridiagonalization<MatrixType>::CoeffVectorType CoeffVectorType;\n  typedef typename Tridiagonalization<MatrixType>::HouseholderSequenceType HouseholderSequenceType;\n  template<typename DiagonalType, typename SubDiagonalType>\n  static EIGEN_DEVICE_FUNC\n      void run(MatrixType& mat, DiagonalType& diag, SubDiagonalType& subdiag, CoeffVectorType& hCoeffs, bool extractQ)\n  {\n    tridiagonalization_inplace(mat, hCoeffs);\n    diag = mat.diagonal().real();\n    subdiag = mat.template diagonal<-1>().real();\n    if(extractQ)\n      mat = HouseholderSequenceType(mat, hCoeffs.conjugate())\n            .setLength(mat.rows() - 1)\n            .setShift(1);\n  }\n};\n\n/** \\internal\n  * Specialization for 3x3 real matrices.\n  * Especially useful for plane fitting.\n  */\ntemplate<typename MatrixType>\nstruct tridiagonalization_inplace_selector<MatrixType,3,false>\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n\n  template<typename DiagonalType, typename SubDiagonalType, typename CoeffVectorType>\n  static void run(MatrixType& mat, DiagonalType& diag, SubDiagonalType& subdiag, CoeffVectorType&, bool extractQ)\n  {\n    using std::sqrt;\n    const RealScalar tol = (std::numeric_limits<RealScalar>::min)();\n    diag[0] = mat(0,0);\n    RealScalar v1norm2 = numext::abs2(mat(2,0));\n    if(v1norm2 <= tol)\n    {\n      diag[1] = mat(1,1);\n      diag[2] = mat(2,2);\n      subdiag[0] = mat(1,0);\n      subdiag[1] = mat(2,1);\n      if (extractQ)\n        mat.setIdentity();\n    }\n    else\n    {\n      RealScalar beta = sqrt(numext::abs2(mat(1,0)) + v1norm2);\n      RealScalar invBeta = RealScalar(1)/beta;\n      Scalar m01 = mat(1,0) * invBeta;\n      Scalar m02 = mat(2,0) * invBeta;\n      Scalar q = RealScalar(2)*m01*mat(2,1) + m02*(mat(2,2) - mat(1,1));\n      diag[1] = mat(1,1) + m02*q;\n      diag[2] = mat(2,2) - m02*q;\n      subdiag[0] = beta;\n      subdiag[1] = mat(2,1) - m01 * q;\n      if (extractQ)\n      {\n        mat << 1,   0,    0,\n               0, m01,  m02,\n               0, m02, -m01;\n      }\n    }\n  }\n};\n\n/** \\internal\n  * Trivial specialization for 1x1 matrices\n  */\ntemplate<typename MatrixType, bool IsComplex>\nstruct tridiagonalization_inplace_selector<MatrixType,1,IsComplex>\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  template<typename DiagonalType, typename SubDiagonalType, typename CoeffVectorType>\n  static EIGEN_DEVICE_FUNC\n  void run(MatrixType& mat, DiagonalType& diag, SubDiagonalType&, CoeffVectorType&, bool extractQ)\n  {\n    diag(0,0) = numext::real(mat(0,0));\n    if(extractQ)\n      mat(0,0) = Scalar(1);\n  }\n};\n\n/** \\internal\n  * \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  * \\brief Expression type for return value of Tridiagonalization::matrixT()\n  *\n  * \\tparam MatrixType type of underlying dense matrix\n  */\ntemplate<typename MatrixType> struct TridiagonalizationMatrixTReturnType\n: public ReturnByValue<TridiagonalizationMatrixTReturnType<MatrixType> >\n{\n  public:\n    /** \\brief Constructor.\n      *\n      * \\param[in] mat The underlying dense matrix\n      */\n    TridiagonalizationMatrixTReturnType(const MatrixType& mat) : m_matrix(mat) { }\n\n    template <typename ResultType>\n    inline void evalTo(ResultType& result) const\n    {\n      result.setZero();\n      result.template diagonal<1>() = m_matrix.template diagonal<-1>().conjugate();\n      result.diagonal() = m_matrix.diagonal();\n      result.template diagonal<-1>() = m_matrix.template diagonal<-1>();\n    }\n\n    EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_matrix.rows(); }\n    EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_matrix.cols(); }\n\n  protected:\n    typename MatrixType::Nested m_matrix;\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_TRIDIAGONALIZATION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Geometry/AlignedBox.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// Function void Eigen::AlignedBox::transform(const Transform& transform)\n// is provided under the following license agreement:\n//\n// Software License Agreement (BSD License)\n//\n// Copyright (c) 2011-2014, Willow Garage, Inc.\n// Copyright (c) 2014-2015, Open Source Robotics Foundation\n// All rights reserved.\n//\n// Redistribution and use in source and binary forms, with or without\n// modification, are permitted provided that the following conditions\n// are met:\n//\n//  * Redistributions of source code must retain the above copyright\n//    notice, this list of conditions and the following disclaimer.\n//  * Redistributions in binary form must reproduce the above\n//    copyright notice, this list of conditions and the following\n//    disclaimer in the documentation and/or other materials provided\n//    with the distribution.\n//  * Neither the name of Open Source Robotics Foundation nor the names of its\n//    contributors may be used to endorse or promote products derived\n//    from this software without specific prior written permission.\n//\n// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n// \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n// POSSIBILITY OF SUCH DAMAGE.\n\n#ifndef EIGEN_ALIGNEDBOX_H\n#define EIGEN_ALIGNEDBOX_H\n\nnamespace Eigen {\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  *\n  * \\class AlignedBox\n  *\n  * \\brief An axis aligned box\n  *\n  * \\tparam Scalar_ the type of the scalar coefficients\n  * \\tparam _AmbientDim the dimension of the ambient space, can be a compile time value or Dynamic.\n  *\n  * This class represents an axis aligned box as a pair of the minimal and maximal corners.\n  * \\warning The result of most methods is undefined when applied to an empty box. You can check for empty boxes using isEmpty().\n  * \\sa alignedboxtypedefs\n  */\ntemplate <typename Scalar_, int _AmbientDim>\nclass AlignedBox\n{\npublic:\nEIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(Scalar_,_AmbientDim)\n  enum { AmbientDimAtCompileTime = _AmbientDim };\n  typedef Scalar_                                   Scalar;\n  typedef NumTraits<Scalar>                         ScalarTraits;\n  typedef Eigen::Index                              Index; ///< \\deprecated since Eigen 3.3\n  typedef typename ScalarTraits::Real               RealScalar;\n  typedef typename ScalarTraits::NonInteger         NonInteger;\n  typedef Matrix<Scalar,AmbientDimAtCompileTime,1>  VectorType;\n  typedef CwiseBinaryOp<internal::scalar_sum_op<Scalar>, const VectorType, const VectorType> VectorTypeSum;\n\n  /** Define constants to name the corners of a 1D, 2D or 3D axis aligned bounding box */\n  enum CornerType\n  {\n    /** 1D names @{ */\n    Min=0, Max=1,\n    /** @} */\n\n    /** Identifier for 2D corner @{ */\n    BottomLeft=0, BottomRight=1,\n    TopLeft=2, TopRight=3,\n    /** @} */\n\n    /** Identifier for 3D corner  @{ */\n    BottomLeftFloor=0, BottomRightFloor=1,\n    TopLeftFloor=2, TopRightFloor=3,\n    BottomLeftCeil=4, BottomRightCeil=5,\n    TopLeftCeil=6, TopRightCeil=7\n    /** @} */\n  };\n\n\n  /** Default constructor initializing a null box. */\n  EIGEN_DEVICE_FUNC inline AlignedBox()\n  { if (EIGEN_CONST_CONDITIONAL(AmbientDimAtCompileTime!=Dynamic)) setEmpty(); }\n\n  /** Constructs a null box with \\a _dim the dimension of the ambient space. */\n  EIGEN_DEVICE_FUNC inline explicit AlignedBox(Index _dim) : m_min(_dim), m_max(_dim)\n  { setEmpty(); }\n\n  /** Constructs a box with extremities \\a _min and \\a _max.\n   * \\warning If either component of \\a _min is larger than the same component of \\a _max, the constructed box is empty. */\n  template<typename OtherVectorType1, typename OtherVectorType2>\n  EIGEN_DEVICE_FUNC inline AlignedBox(const OtherVectorType1& _min, const OtherVectorType2& _max) : m_min(_min), m_max(_max) {}\n\n  /** Constructs a box containing a single point \\a p. */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline explicit AlignedBox(const MatrixBase<Derived>& p) : m_min(p), m_max(m_min)\n  { }\n\n  EIGEN_DEVICE_FUNC ~AlignedBox() {}\n\n  /** \\returns the dimension in which the box holds */\n  EIGEN_DEVICE_FUNC inline Index dim() const { return AmbientDimAtCompileTime==Dynamic ? m_min.size() : Index(AmbientDimAtCompileTime); }\n\n  /** \\deprecated use isEmpty() */\n  EIGEN_DEVICE_FUNC inline bool isNull() const { return isEmpty(); }\n\n  /** \\deprecated use setEmpty() */\n  EIGEN_DEVICE_FUNC inline void setNull() { setEmpty(); }\n\n  /** \\returns true if the box is empty.\n   * \\sa setEmpty */\n  EIGEN_DEVICE_FUNC inline bool isEmpty() const { return (m_min.array() > m_max.array()).any(); }\n\n  /** Makes \\c *this an empty box.\n   * \\sa isEmpty */\n  EIGEN_DEVICE_FUNC inline void setEmpty()\n  {\n    m_min.setConstant( ScalarTraits::highest() );\n    m_max.setConstant( ScalarTraits::lowest() );\n  }\n\n  /** \\returns the minimal corner */\n  EIGEN_DEVICE_FUNC inline const VectorType& (min)() const { return m_min; }\n  /** \\returns a non const reference to the minimal corner */\n  EIGEN_DEVICE_FUNC inline VectorType& (min)() { return m_min; }\n  /** \\returns the maximal corner */\n  EIGEN_DEVICE_FUNC inline const VectorType& (max)() const { return m_max; }\n  /** \\returns a non const reference to the maximal corner */\n  EIGEN_DEVICE_FUNC inline VectorType& (max)() { return m_max; }\n\n  /** \\returns the center of the box */\n  EIGEN_DEVICE_FUNC inline const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(VectorTypeSum, RealScalar, quotient)\n  center() const\n  { return (m_min+m_max)/RealScalar(2); }\n\n  /** \\returns the lengths of the sides of the bounding box.\n    * Note that this function does not get the same\n    * result for integral or floating scalar types: see\n    */\n  EIGEN_DEVICE_FUNC inline const CwiseBinaryOp< internal::scalar_difference_op<Scalar,Scalar>, const VectorType, const VectorType> sizes() const\n  { return m_max - m_min; }\n\n  /** \\returns the volume of the bounding box */\n  EIGEN_DEVICE_FUNC inline Scalar volume() const\n  { return sizes().prod(); }\n\n  /** \\returns an expression for the bounding box diagonal vector\n    * if the length of the diagonal is needed: diagonal().norm()\n    * will provide it.\n    */\n  EIGEN_DEVICE_FUNC inline CwiseBinaryOp< internal::scalar_difference_op<Scalar,Scalar>, const VectorType, const VectorType> diagonal() const\n  { return sizes(); }\n\n  /** \\returns the vertex of the bounding box at the corner defined by\n    * the corner-id corner. It works only for a 1D, 2D or 3D bounding box.\n    * For 1D bounding boxes corners are named by 2 enum constants:\n    * BottomLeft and BottomRight.\n    * For 2D bounding boxes, corners are named by 4 enum constants:\n    * BottomLeft, BottomRight, TopLeft, TopRight.\n    * For 3D bounding boxes, the following names are added:\n    * BottomLeftCeil, BottomRightCeil, TopLeftCeil, TopRightCeil.\n    */\n  EIGEN_DEVICE_FUNC inline VectorType corner(CornerType corner) const\n  {\n    EIGEN_STATIC_ASSERT(_AmbientDim <= 3, THIS_METHOD_IS_ONLY_FOR_VECTORS_OF_A_SPECIFIC_SIZE);\n\n    VectorType res;\n\n    Index mult = 1;\n    for(Index d=0; d<dim(); ++d)\n    {\n      if( mult & corner ) res[d] = m_max[d];\n      else                res[d] = m_min[d];\n      mult *= 2;\n    }\n    return res;\n  }\n\n  /** \\returns a random point inside the bounding box sampled with\n   * a uniform distribution */\n  EIGEN_DEVICE_FUNC inline VectorType sample() const\n  {\n    VectorType r(dim());\n    for(Index d=0; d<dim(); ++d)\n    {\n      if(!ScalarTraits::IsInteger)\n      {\n        r[d] = m_min[d] + (m_max[d]-m_min[d])\n             * internal::random<Scalar>(Scalar(0), Scalar(1));\n      }\n      else\n        r[d] = internal::random(m_min[d], m_max[d]);\n    }\n    return r;\n  }\n\n  /** \\returns true if the point \\a p is inside the box \\c *this. */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline bool contains(const MatrixBase<Derived>& p) const\n  {\n    typename internal::nested_eval<Derived,2>::type p_n(p.derived());\n    return (m_min.array()<=p_n.array()).all() && (p_n.array()<=m_max.array()).all();\n  }\n\n  /** \\returns true if the box \\a b is entirely inside the box \\c *this. */\n  EIGEN_DEVICE_FUNC inline bool contains(const AlignedBox& b) const\n  { return (m_min.array()<=(b.min)().array()).all() && ((b.max)().array()<=m_max.array()).all(); }\n\n  /** \\returns true if the box \\a b is intersecting the box \\c *this.\n   * \\sa intersection, clamp */\n  EIGEN_DEVICE_FUNC inline bool intersects(const AlignedBox& b) const\n  { return (m_min.array()<=(b.max)().array()).all() && ((b.min)().array()<=m_max.array()).all(); }\n\n  /** Extends \\c *this such that it contains the point \\a p and returns a reference to \\c *this.\n   * \\sa extend(const AlignedBox&) */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline AlignedBox& extend(const MatrixBase<Derived>& p)\n  {\n    typename internal::nested_eval<Derived,2>::type p_n(p.derived());\n    m_min = m_min.cwiseMin(p_n);\n    m_max = m_max.cwiseMax(p_n);\n    return *this;\n  }\n\n  /** Extends \\c *this such that it contains the box \\a b and returns a reference to \\c *this.\n   * \\sa merged, extend(const MatrixBase&) */\n  EIGEN_DEVICE_FUNC inline AlignedBox& extend(const AlignedBox& b)\n  {\n    m_min = m_min.cwiseMin(b.m_min);\n    m_max = m_max.cwiseMax(b.m_max);\n    return *this;\n  }\n\n  /** Clamps \\c *this by the box \\a b and returns a reference to \\c *this.\n   * \\note If the boxes don't intersect, the resulting box is empty.\n   * \\sa intersection(), intersects() */\n  EIGEN_DEVICE_FUNC inline AlignedBox& clamp(const AlignedBox& b)\n  {\n    m_min = m_min.cwiseMax(b.m_min);\n    m_max = m_max.cwiseMin(b.m_max);\n    return *this;\n  }\n\n  /** Returns an AlignedBox that is the intersection of \\a b and \\c *this\n   * \\note If the boxes don't intersect, the resulting box is empty.\n   * \\sa intersects(), clamp, contains()  */\n  EIGEN_DEVICE_FUNC inline AlignedBox intersection(const AlignedBox& b) const\n  {return AlignedBox(m_min.cwiseMax(b.m_min), m_max.cwiseMin(b.m_max)); }\n\n  /** Returns an AlignedBox that is the union of \\a b and \\c *this.\n   * \\note Merging with an empty box may result in a box bigger than \\c *this.\n   * \\sa extend(const AlignedBox&) */\n  EIGEN_DEVICE_FUNC inline AlignedBox merged(const AlignedBox& b) const\n  { return AlignedBox(m_min.cwiseMin(b.m_min), m_max.cwiseMax(b.m_max)); }\n\n  /** Translate \\c *this by the vector \\a t and returns a reference to \\c *this. */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline AlignedBox& translate(const MatrixBase<Derived>& a_t)\n  {\n    const typename internal::nested_eval<Derived,2>::type t(a_t.derived());\n    m_min += t;\n    m_max += t;\n    return *this;\n  }\n\n  /** \\returns a copy of \\c *this translated by the vector \\a t. */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline AlignedBox translated(const MatrixBase<Derived>& a_t) const\n  {\n    AlignedBox result(m_min, m_max);\n    result.translate(a_t);\n    return result;\n  }\n\n  /** \\returns the squared distance between the point \\a p and the box \\c *this,\n    * and zero if \\a p is inside the box.\n    * \\sa exteriorDistance(const MatrixBase&), squaredExteriorDistance(const AlignedBox&)\n    */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline Scalar squaredExteriorDistance(const MatrixBase<Derived>& p) const;\n\n  /** \\returns the squared distance between the boxes \\a b and \\c *this,\n    * and zero if the boxes intersect.\n    * \\sa exteriorDistance(const AlignedBox&), squaredExteriorDistance(const MatrixBase&)\n    */\n  EIGEN_DEVICE_FUNC inline Scalar squaredExteriorDistance(const AlignedBox& b) const;\n\n  /** \\returns the distance between the point \\a p and the box \\c *this,\n    * and zero if \\a p is inside the box.\n    * \\sa squaredExteriorDistance(const MatrixBase&), exteriorDistance(const AlignedBox&)\n    */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline NonInteger exteriorDistance(const MatrixBase<Derived>& p) const\n  { EIGEN_USING_STD(sqrt) return sqrt(NonInteger(squaredExteriorDistance(p))); }\n\n  /** \\returns the distance between the boxes \\a b and \\c *this,\n    * and zero if the boxes intersect.\n    * \\sa squaredExteriorDistance(const AlignedBox&), exteriorDistance(const MatrixBase&)\n    */\n  EIGEN_DEVICE_FUNC inline NonInteger exteriorDistance(const AlignedBox& b) const\n  { EIGEN_USING_STD(sqrt) return sqrt(NonInteger(squaredExteriorDistance(b))); }\n\n  /**\n   * Specialization of transform for pure translation.\n   */\n  template<int Mode, int Options>\n  EIGEN_DEVICE_FUNC inline void transform(\n      const typename Transform<Scalar, AmbientDimAtCompileTime, Mode, Options>::TranslationType& translation)\n  {\n    this->translate(translation);\n  }\n\n  /**\n   * Transforms this box by \\a transform and recomputes it to\n   * still be an axis-aligned box.\n   *\n   * \\note This method is provided under BSD license (see the top of this file).\n   */\n  template<int Mode, int Options>\n  EIGEN_DEVICE_FUNC inline void transform(const Transform<Scalar, AmbientDimAtCompileTime, Mode, Options>& transform)\n  {\n    // Only Affine and Isometry transforms are currently supported.\n    EIGEN_STATIC_ASSERT(Mode == Affine || Mode == AffineCompact || Mode == Isometry, THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS);\n\n    // Method adapted from FCL src/shape/geometric_shapes_utility.cpp#computeBV<AABB, Box>(...)\n    // https://github.com/flexible-collision-library/fcl/blob/fcl-0.4/src/shape/geometric_shapes_utility.cpp#L292\n    //\n    // Here's a nice explanation why it works: https://zeuxcg.org/2010/10/17/aabb-from-obb-with-component-wise-abs/\n\n    // two times rotated extent\n    const VectorType rotated_extent_2 = transform.linear().cwiseAbs() * sizes();\n    // two times new center\n    const VectorType rotated_center_2 = transform.linear() * (this->m_max + this->m_min) +\n        Scalar(2) * transform.translation();\n\n    this->m_max = (rotated_center_2 + rotated_extent_2) / Scalar(2);\n    this->m_min = (rotated_center_2 - rotated_extent_2) / Scalar(2);\n  }\n\n  /**\n   * \\returns a copy of \\c *this transformed by \\a transform and recomputed to\n   * still be an axis-aligned box.\n   */\n  template<int Mode, int Options>\n  EIGEN_DEVICE_FUNC AlignedBox transformed(const Transform<Scalar, AmbientDimAtCompileTime, Mode, Options>& transform) const\n  {\n    AlignedBox result(m_min, m_max);\n    result.transform(transform);\n    return result;\n  }\n\n  /** \\returns \\c *this with scalar type casted to \\a NewScalarType\n    *\n    * Note that if \\a NewScalarType is equal to the current scalar type of \\c *this\n    * then this function smartly returns a const reference to \\c *this.\n    */\n  template<typename NewScalarType>\n  EIGEN_DEVICE_FUNC inline typename internal::cast_return_type<AlignedBox,\n           AlignedBox<NewScalarType,AmbientDimAtCompileTime> >::type cast() const\n  {\n    return typename internal::cast_return_type<AlignedBox,\n                    AlignedBox<NewScalarType,AmbientDimAtCompileTime> >::type(*this);\n  }\n\n  /** Copy constructor with scalar type conversion */\n  template<typename OtherScalarType>\n  EIGEN_DEVICE_FUNC inline explicit AlignedBox(const AlignedBox<OtherScalarType,AmbientDimAtCompileTime>& other)\n  {\n    m_min = (other.min)().template cast<Scalar>();\n    m_max = (other.max)().template cast<Scalar>();\n  }\n\n  /** \\returns \\c true if \\c *this is approximately equal to \\a other, within the precision\n    * determined by \\a prec.\n    *\n    * \\sa MatrixBase::isApprox() */\n  EIGEN_DEVICE_FUNC bool isApprox(const AlignedBox& other, const RealScalar& prec = ScalarTraits::dummy_precision()) const\n  { return m_min.isApprox(other.m_min, prec) && m_max.isApprox(other.m_max, prec); }\n\nprotected:\n\n  VectorType m_min, m_max;\n};\n\n\n\ntemplate<typename Scalar,int AmbientDim>\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC inline Scalar AlignedBox<Scalar,AmbientDim>::squaredExteriorDistance(const MatrixBase<Derived>& a_p) const\n{\n  typename internal::nested_eval<Derived,2*AmbientDim>::type p(a_p.derived());\n  Scalar dist2(0);\n  Scalar aux;\n  for (Index k=0; k<dim(); ++k)\n  {\n    if( m_min[k] > p[k] )\n    {\n      aux = m_min[k] - p[k];\n      dist2 += aux*aux;\n    }\n    else if( p[k] > m_max[k] )\n    {\n      aux = p[k] - m_max[k];\n      dist2 += aux*aux;\n    }\n  }\n  return dist2;\n}\n\ntemplate<typename Scalar,int AmbientDim>\nEIGEN_DEVICE_FUNC inline Scalar AlignedBox<Scalar,AmbientDim>::squaredExteriorDistance(const AlignedBox& b) const\n{\n  Scalar dist2(0);\n  Scalar aux;\n  for (Index k=0; k<dim(); ++k)\n  {\n    if( m_min[k] > b.m_max[k] )\n    {\n      aux = m_min[k] - b.m_max[k];\n      dist2 += aux*aux;\n    }\n    else if( b.m_min[k] > m_max[k] )\n    {\n      aux = b.m_min[k] - m_max[k];\n      dist2 += aux*aux;\n    }\n  }\n  return dist2;\n}\n\n/** \\defgroup alignedboxtypedefs Global aligned box typedefs\n  *\n  * \\ingroup Geometry_Module\n  *\n  * Eigen defines several typedef shortcuts for most common aligned box types.\n  *\n  * The general patterns are the following:\n  *\n  * \\c AlignedBoxSizeType where \\c Size can be \\c 1, \\c 2,\\c 3,\\c 4 for fixed size boxes or \\c X for dynamic size,\n  * and where \\c Type can be \\c i for integer, \\c f for float, \\c d for double.\n  *\n  * For example, \\c AlignedBox3d is a fixed-size 3x3 aligned box type of doubles, and \\c AlignedBoxXf is a dynamic-size aligned box of floats.\n  *\n  * \\sa class AlignedBox\n  */\n\n#define EIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, Size, SizeSuffix)    \\\n/** \\ingroup alignedboxtypedefs */                                 \\\ntypedef AlignedBox<Type, Size>   AlignedBox##SizeSuffix##TypeSuffix;\n\n#define EIGEN_MAKE_TYPEDEFS_ALL_SIZES(Type, TypeSuffix) \\\nEIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, 1, 1) \\\nEIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, 2, 2) \\\nEIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, 3, 3) \\\nEIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, 4, 4) \\\nEIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, Dynamic, X)\n\nEIGEN_MAKE_TYPEDEFS_ALL_SIZES(int,                  i)\nEIGEN_MAKE_TYPEDEFS_ALL_SIZES(float,                f)\nEIGEN_MAKE_TYPEDEFS_ALL_SIZES(double,               d)\n\n#undef EIGEN_MAKE_TYPEDEFS_ALL_SIZES\n#undef EIGEN_MAKE_TYPEDEFS\n\n} // end namespace Eigen\n\n#endif // EIGEN_ALIGNEDBOX_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Geometry/AngleAxis.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ANGLEAXIS_H\n#define EIGEN_ANGLEAXIS_H\n\nnamespace Eigen { \n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\class AngleAxis\n  *\n  * \\brief Represents a 3D rotation as a rotation angle around an arbitrary 3D axis\n  *\n  * \\param Scalar_ the scalar type, i.e., the type of the coefficients.\n  *\n  * \\warning When setting up an AngleAxis object, the axis vector \\b must \\b be \\b normalized.\n  *\n  * The following two typedefs are provided for convenience:\n  * \\li \\c AngleAxisf for \\c float\n  * \\li \\c AngleAxisd for \\c double\n  *\n  * Combined with MatrixBase::Unit{X,Y,Z}, AngleAxis can be used to easily\n  * mimic Euler-angles. Here is an example:\n  * \\include AngleAxis_mimic_euler.cpp\n  * Output: \\verbinclude AngleAxis_mimic_euler.out\n  *\n  * \\note This class is not aimed to be used to store a rotation transformation,\n  * but rather to make easier the creation of other rotation (Quaternion, rotation Matrix)\n  * and transformation objects.\n  *\n  * \\sa class Quaternion, class Transform, MatrixBase::UnitX()\n  */\n\nnamespace internal {\ntemplate<typename Scalar_> struct traits<AngleAxis<Scalar_> >\n{\n  typedef Scalar_ Scalar;\n};\n}\n\ntemplate<typename Scalar_>\nclass AngleAxis : public RotationBase<AngleAxis<Scalar_>,3>\n{\n  typedef RotationBase<AngleAxis<Scalar_>,3> Base;\n\npublic:\n\n  using Base::operator*;\n\n  enum { Dim = 3 };\n  /** the scalar type of the coefficients */\n  typedef Scalar_ Scalar;\n  typedef Matrix<Scalar,3,3> Matrix3;\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef Quaternion<Scalar> QuaternionType;\n\nprotected:\n\n  Vector3 m_axis;\n  Scalar m_angle;\n\npublic:\n\n  /** Default constructor without initialization. */\n  EIGEN_DEVICE_FUNC AngleAxis() {}\n  /** Constructs and initialize the angle-axis rotation from an \\a angle in radian\n    * and an \\a axis which \\b must \\b be \\b normalized.\n    *\n    * \\warning If the \\a axis vector is not normalized, then the angle-axis object\n    *          represents an invalid rotation. */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC \n  inline AngleAxis(const Scalar& angle, const MatrixBase<Derived>& axis) : m_axis(axis), m_angle(angle) {}\n  /** Constructs and initialize the angle-axis rotation from a quaternion \\a q.\n    * This function implicitly normalizes the quaternion \\a q.\n    */\n  template<typename QuatDerived> \n  EIGEN_DEVICE_FUNC inline explicit AngleAxis(const QuaternionBase<QuatDerived>& q) { *this = q; }\n  /** Constructs and initialize the angle-axis rotation from a 3x3 rotation matrix. */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline explicit AngleAxis(const MatrixBase<Derived>& m) { *this = m; }\n\n  /** \\returns the value of the rotation angle in radian */\n  EIGEN_DEVICE_FUNC Scalar angle() const { return m_angle; }\n  /** \\returns a read-write reference to the stored angle in radian */\n  EIGEN_DEVICE_FUNC Scalar& angle() { return m_angle; }\n\n  /** \\returns the rotation axis */\n  EIGEN_DEVICE_FUNC const Vector3& axis() const { return m_axis; }\n  /** \\returns a read-write reference to the stored rotation axis.\n    *\n    * \\warning The rotation axis must remain a \\b unit vector.\n    */\n  EIGEN_DEVICE_FUNC Vector3& axis() { return m_axis; }\n\n  /** Concatenates two rotations */\n  EIGEN_DEVICE_FUNC inline QuaternionType operator* (const AngleAxis& other) const\n  { return QuaternionType(*this) * QuaternionType(other); }\n\n  /** Concatenates two rotations */\n  EIGEN_DEVICE_FUNC inline QuaternionType operator* (const QuaternionType& other) const\n  { return QuaternionType(*this) * other; }\n\n  /** Concatenates two rotations */\n  friend EIGEN_DEVICE_FUNC inline QuaternionType operator* (const QuaternionType& a, const AngleAxis& b)\n  { return a * QuaternionType(b); }\n\n  /** \\returns the inverse rotation, i.e., an angle-axis with opposite rotation angle */\n  EIGEN_DEVICE_FUNC AngleAxis inverse() const\n  { return AngleAxis(-m_angle, m_axis); }\n\n  template<class QuatDerived>\n  EIGEN_DEVICE_FUNC AngleAxis& operator=(const QuaternionBase<QuatDerived>& q);\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC AngleAxis& operator=(const MatrixBase<Derived>& m);\n\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC AngleAxis& fromRotationMatrix(const MatrixBase<Derived>& m);\n  EIGEN_DEVICE_FUNC Matrix3 toRotationMatrix(void) const;\n\n  /** \\returns \\c *this with scalar type casted to \\a NewScalarType\n    *\n    * Note that if \\a NewScalarType is equal to the current scalar type of \\c *this\n    * then this function smartly returns a const reference to \\c *this.\n    */\n  template<typename NewScalarType>\n  EIGEN_DEVICE_FUNC inline typename internal::cast_return_type<AngleAxis,AngleAxis<NewScalarType> >::type cast() const\n  { return typename internal::cast_return_type<AngleAxis,AngleAxis<NewScalarType> >::type(*this); }\n\n  /** Copy constructor with scalar type conversion */\n  template<typename OtherScalarType>\n  EIGEN_DEVICE_FUNC inline explicit AngleAxis(const AngleAxis<OtherScalarType>& other)\n  {\n    m_axis = other.axis().template cast<Scalar>();\n    m_angle = Scalar(other.angle());\n  }\n\n  EIGEN_DEVICE_FUNC static inline const AngleAxis Identity() { return AngleAxis(Scalar(0), Vector3::UnitX()); }\n\n  /** \\returns \\c true if \\c *this is approximately equal to \\a other, within the precision\n    * determined by \\a prec.\n    *\n    * \\sa MatrixBase::isApprox() */\n  EIGEN_DEVICE_FUNC bool isApprox(const AngleAxis& other, const typename NumTraits<Scalar>::Real& prec = NumTraits<Scalar>::dummy_precision()) const\n  { return m_axis.isApprox(other.m_axis, prec) && internal::isApprox(m_angle,other.m_angle, prec); }\n};\n\n/** \\ingroup Geometry_Module\n  * single precision angle-axis type */\ntypedef AngleAxis<float> AngleAxisf;\n/** \\ingroup Geometry_Module\n  * double precision angle-axis type */\ntypedef AngleAxis<double> AngleAxisd;\n\n/** Set \\c *this from a \\b unit quaternion.\n  *\n  * The resulting axis is normalized, and the computed angle is in the [0,pi] range.\n  * \n  * This function implicitly normalizes the quaternion \\a q.\n  */\ntemplate<typename Scalar>\ntemplate<typename QuatDerived>\nEIGEN_DEVICE_FUNC AngleAxis<Scalar>& AngleAxis<Scalar>::operator=(const QuaternionBase<QuatDerived>& q)\n{\n  EIGEN_USING_STD(atan2)\n  EIGEN_USING_STD(abs)\n  Scalar n = q.vec().norm();\n  if(n<NumTraits<Scalar>::epsilon())\n    n = q.vec().stableNorm();\n\n  if (n != Scalar(0))\n  {\n    m_angle = Scalar(2)*atan2(n, abs(q.w()));\n    if(q.w() < Scalar(0))\n      n = -n;\n    m_axis  = q.vec() / n;\n  }\n  else\n  {\n    m_angle = Scalar(0);\n    m_axis << Scalar(1), Scalar(0), Scalar(0);\n  }\n  return *this;\n}\n\n/** Set \\c *this from a 3x3 rotation matrix \\a mat.\n  */\ntemplate<typename Scalar>\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC AngleAxis<Scalar>& AngleAxis<Scalar>::operator=(const MatrixBase<Derived>& mat)\n{\n  // Since a direct conversion would not be really faster,\n  // let's use the robust Quaternion implementation:\n  return *this = QuaternionType(mat);\n}\n\n/**\n* \\brief Sets \\c *this from a 3x3 rotation matrix.\n**/\ntemplate<typename Scalar>\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC AngleAxis<Scalar>& AngleAxis<Scalar>::fromRotationMatrix(const MatrixBase<Derived>& mat)\n{\n  return *this = QuaternionType(mat);\n}\n\n/** Constructs and \\returns an equivalent 3x3 rotation matrix.\n  */\ntemplate<typename Scalar>\ntypename AngleAxis<Scalar>::Matrix3\nEIGEN_DEVICE_FUNC AngleAxis<Scalar>::toRotationMatrix(void) const\n{\n  EIGEN_USING_STD(sin)\n  EIGEN_USING_STD(cos)\n  Matrix3 res;\n  Vector3 sin_axis  = sin(m_angle) * m_axis;\n  Scalar c = cos(m_angle);\n  Vector3 cos1_axis = (Scalar(1)-c) * m_axis;\n\n  Scalar tmp;\n  tmp = cos1_axis.x() * m_axis.y();\n  res.coeffRef(0,1) = tmp - sin_axis.z();\n  res.coeffRef(1,0) = tmp + sin_axis.z();\n\n  tmp = cos1_axis.x() * m_axis.z();\n  res.coeffRef(0,2) = tmp + sin_axis.y();\n  res.coeffRef(2,0) = tmp - sin_axis.y();\n\n  tmp = cos1_axis.y() * m_axis.z();\n  res.coeffRef(1,2) = tmp - sin_axis.x();\n  res.coeffRef(2,1) = tmp + sin_axis.x();\n\n  res.diagonal() = (cos1_axis.cwiseProduct(m_axis)).array() + c;\n\n  return res;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_ANGLEAXIS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Geometry/EulerAngles.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_EULERANGLES_H\n#define EIGEN_EULERANGLES_H\n\nnamespace Eigen { \n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  *\n  * \\returns the Euler-angles of the rotation matrix \\c *this using the convention defined by the triplet (\\a a0,\\a a1,\\a a2)\n  *\n  * Each of the three parameters \\a a0,\\a a1,\\a a2 represents the respective rotation axis as an integer in {0,1,2}.\n  * For instance, in:\n  * \\code Vector3f ea = mat.eulerAngles(2, 0, 2); \\endcode\n  * \"2\" represents the z axis and \"0\" the x axis, etc. The returned angles are such that\n  * we have the following equality:\n  * \\code\n  * mat == AngleAxisf(ea[0], Vector3f::UnitZ())\n  *      * AngleAxisf(ea[1], Vector3f::UnitX())\n  *      * AngleAxisf(ea[2], Vector3f::UnitZ()); \\endcode\n  * This corresponds to the right-multiply conventions (with right hand side frames).\n  * \n  * The returned angles are in the ranges [0:pi]x[-pi:pi]x[-pi:pi].\n  * \n  * \\sa class AngleAxis\n  */\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC inline Matrix<typename MatrixBase<Derived>::Scalar,3,1>\nMatrixBase<Derived>::eulerAngles(Index a0, Index a1, Index a2) const\n{\n  EIGEN_USING_STD(atan2)\n  EIGEN_USING_STD(sin)\n  EIGEN_USING_STD(cos)\n  /* Implemented from Graphics Gems IV */\n  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Derived,3,3)\n\n  Matrix<Scalar,3,1> res;\n  typedef Matrix<typename Derived::Scalar,2,1> Vector2;\n\n  const Index odd = ((a0+1)%3 == a1) ? 0 : 1;\n  const Index i = a0;\n  const Index j = (a0 + 1 + odd)%3;\n  const Index k = (a0 + 2 - odd)%3;\n  \n  if (a0==a2)\n  {\n    res[0] = atan2(coeff(j,i), coeff(k,i));\n    if((odd && res[0]<Scalar(0)) || ((!odd) && res[0]>Scalar(0)))\n    {\n      if(res[0] > Scalar(0)) {\n        res[0] -= Scalar(EIGEN_PI);\n      }\n      else {\n        res[0] += Scalar(EIGEN_PI);\n      }\n      Scalar s2 = Vector2(coeff(j,i), coeff(k,i)).norm();\n      res[1] = -atan2(s2, coeff(i,i));\n    }\n    else\n    {\n      Scalar s2 = Vector2(coeff(j,i), coeff(k,i)).norm();\n      res[1] = atan2(s2, coeff(i,i));\n    }\n    \n    // With a=(0,1,0), we have i=0; j=1; k=2, and after computing the first two angles,\n    // we can compute their respective rotation, and apply its inverse to M. Since the result must\n    // be a rotation around x, we have:\n    //\n    //  c2  s1.s2 c1.s2                   1  0   0 \n    //  0   c1    -s1       *    M    =   0  c3  s3\n    //  -s2 s1.c2 c1.c2                   0 -s3  c3\n    //\n    //  Thus:  m11.c1 - m21.s1 = c3  &   m12.c1 - m22.s1 = s3\n    \n    Scalar s1 = sin(res[0]);\n    Scalar c1 = cos(res[0]);\n    res[2] = atan2(c1*coeff(j,k)-s1*coeff(k,k), c1*coeff(j,j) - s1 * coeff(k,j));\n  } \n  else\n  {\n    res[0] = atan2(coeff(j,k), coeff(k,k));\n    Scalar c2 = Vector2(coeff(i,i), coeff(i,j)).norm();\n    if((odd && res[0]<Scalar(0)) || ((!odd) && res[0]>Scalar(0))) {\n      if(res[0] > Scalar(0)) {\n        res[0] -= Scalar(EIGEN_PI);\n      }\n      else {\n        res[0] += Scalar(EIGEN_PI);\n      }\n      res[1] = atan2(-coeff(i,k), -c2);\n    }\n    else\n      res[1] = atan2(-coeff(i,k), c2);\n    Scalar s1 = sin(res[0]);\n    Scalar c1 = cos(res[0]);\n    res[2] = atan2(s1*coeff(k,i)-c1*coeff(j,i), c1*coeff(j,j) - s1 * coeff(k,j));\n  }\n  if (!odd)\n    res = -res;\n  \n  return res;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_EULERANGLES_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Geometry/Homogeneous.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_HOMOGENEOUS_H\n#define EIGEN_HOMOGENEOUS_H\n\nnamespace Eigen {\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\class Homogeneous\n  *\n  * \\brief Expression of one (or a set of) homogeneous vector(s)\n  *\n  * \\param MatrixType the type of the object in which we are making homogeneous\n  *\n  * This class represents an expression of one (or a set of) homogeneous vector(s).\n  * It is the return type of MatrixBase::homogeneous() and most of the time\n  * this is the only way it is used.\n  *\n  * \\sa MatrixBase::homogeneous()\n  */\n\nnamespace internal {\n\ntemplate<typename MatrixType,int Direction>\nstruct traits<Homogeneous<MatrixType,Direction> >\n : traits<MatrixType>\n{\n  typedef typename traits<MatrixType>::StorageKind StorageKind;\n  typedef typename ref_selector<MatrixType>::type MatrixTypeNested;\n  typedef typename remove_reference<MatrixTypeNested>::type _MatrixTypeNested;\n  enum {\n    RowsPlusOne = (MatrixType::RowsAtCompileTime != Dynamic) ?\n                  int(MatrixType::RowsAtCompileTime) + 1 : Dynamic,\n    ColsPlusOne = (MatrixType::ColsAtCompileTime != Dynamic) ?\n                  int(MatrixType::ColsAtCompileTime) + 1 : Dynamic,\n    RowsAtCompileTime = Direction==Vertical  ?  RowsPlusOne : MatrixType::RowsAtCompileTime,\n    ColsAtCompileTime = Direction==Horizontal ? ColsPlusOne : MatrixType::ColsAtCompileTime,\n    MaxRowsAtCompileTime = RowsAtCompileTime,\n    MaxColsAtCompileTime = ColsAtCompileTime,\n    TmpFlags = _MatrixTypeNested::Flags & HereditaryBits,\n    Flags = ColsAtCompileTime==1 ? (TmpFlags & ~RowMajorBit)\n          : RowsAtCompileTime==1 ? (TmpFlags | RowMajorBit)\n          : TmpFlags\n  };\n};\n\ntemplate<typename MatrixType,typename Lhs> struct homogeneous_left_product_impl;\ntemplate<typename MatrixType,typename Rhs> struct homogeneous_right_product_impl;\n\n} // end namespace internal\n\ntemplate<typename MatrixType,int Direction_> class Homogeneous\n  : public MatrixBase<Homogeneous<MatrixType,Direction_> >, internal::no_assignment_operator\n{\n  public:\n\n    typedef MatrixType NestedExpression;\n    enum { Direction = Direction_ };\n\n    typedef MatrixBase<Homogeneous> Base;\n    EIGEN_DENSE_PUBLIC_INTERFACE(Homogeneous)\n\n    EIGEN_DEVICE_FUNC explicit inline Homogeneous(const MatrixType& matrix)\n      : m_matrix(matrix)\n    {}\n\n    EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR\n    inline Index rows() const EIGEN_NOEXCEPT { return m_matrix.rows() + (int(Direction)==Vertical   ? 1 : 0); }\n    EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR\n    inline Index cols() const EIGEN_NOEXCEPT { return m_matrix.cols() + (int(Direction)==Horizontal ? 1 : 0); }\n\n    EIGEN_DEVICE_FUNC const NestedExpression& nestedExpression() const { return m_matrix; }\n\n    template<typename Rhs>\n    EIGEN_DEVICE_FUNC inline const Product<Homogeneous,Rhs>\n    operator* (const MatrixBase<Rhs>& rhs) const\n    {\n      eigen_assert(int(Direction)==Horizontal);\n      return Product<Homogeneous,Rhs>(*this,rhs.derived());\n    }\n\n    template<typename Lhs> friend\n    EIGEN_DEVICE_FUNC inline const Product<Lhs,Homogeneous>\n    operator* (const MatrixBase<Lhs>& lhs, const Homogeneous& rhs)\n    {\n      eigen_assert(int(Direction)==Vertical);\n      return Product<Lhs,Homogeneous>(lhs.derived(),rhs);\n    }\n\n    template<typename Scalar, int Dim, int Mode, int Options> friend\n    EIGEN_DEVICE_FUNC inline const Product<Transform<Scalar,Dim,Mode,Options>, Homogeneous >\n    operator* (const Transform<Scalar,Dim,Mode,Options>& lhs, const Homogeneous& rhs)\n    {\n      eigen_assert(int(Direction)==Vertical);\n      return Product<Transform<Scalar,Dim,Mode,Options>, Homogeneous>(lhs,rhs);\n    }\n\n    template<typename Func>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename internal::result_of<Func(Scalar,Scalar)>::type\n    redux(const Func& func) const\n    {\n      return func(m_matrix.redux(func), Scalar(1));\n    }\n\n  protected:\n    typename MatrixType::Nested m_matrix;\n};\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\returns a vector expression that is one longer than the vector argument, with the value 1 symbolically appended as the last coefficient.\n  *\n  * This can be used to convert affine coordinates to homogeneous coordinates.\n  *\n  * \\only_for_vectors\n  *\n  * Example: \\include MatrixBase_homogeneous.cpp\n  * Output: \\verbinclude MatrixBase_homogeneous.out\n  *\n  * \\sa VectorwiseOp::homogeneous(), class Homogeneous\n  */\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC inline typename MatrixBase<Derived>::HomogeneousReturnType\nMatrixBase<Derived>::homogeneous() const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived);\n  return HomogeneousReturnType(derived());\n}\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\returns an expression where the value 1 is symbolically appended as the final coefficient to each column (or row) of the matrix.\n  *\n  * This can be used to convert affine coordinates to homogeneous coordinates.\n  *\n  * Example: \\include VectorwiseOp_homogeneous.cpp\n  * Output: \\verbinclude VectorwiseOp_homogeneous.out\n  *\n  * \\sa MatrixBase::homogeneous(), class Homogeneous */\ntemplate<typename ExpressionType, int Direction>\nEIGEN_DEVICE_FUNC inline Homogeneous<ExpressionType,Direction>\nVectorwiseOp<ExpressionType,Direction>::homogeneous() const\n{\n  return HomogeneousReturnType(_expression());\n}\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\brief homogeneous normalization\n  *\n  * \\returns a vector expression of the N-1 first coefficients of \\c *this divided by that last coefficient.\n  *\n  * This can be used to convert homogeneous coordinates to affine coordinates.\n  *\n  * It is essentially a shortcut for:\n  * \\code\n    this->head(this->size()-1)/this->coeff(this->size()-1);\n    \\endcode\n  *\n  * Example: \\include MatrixBase_hnormalized.cpp\n  * Output: \\verbinclude MatrixBase_hnormalized.out\n  *\n  * \\sa VectorwiseOp::hnormalized() */\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC inline const typename MatrixBase<Derived>::HNormalizedReturnType\nMatrixBase<Derived>::hnormalized() const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived);\n  return ConstStartMinusOne(derived(),0,0,\n    ColsAtCompileTime==1?size()-1:1,\n    ColsAtCompileTime==1?1:size()-1) / coeff(size()-1);\n}\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\brief column or row-wise homogeneous normalization\n  *\n  * \\returns an expression of the first N-1 coefficients of each column (or row) of \\c *this divided by the last coefficient of each column (or row).\n  *\n  * This can be used to convert homogeneous coordinates to affine coordinates.\n  *\n  * It is conceptually equivalent to calling MatrixBase::hnormalized() to each column (or row) of \\c *this.\n  *\n  * Example: \\include DirectionWise_hnormalized.cpp\n  * Output: \\verbinclude DirectionWise_hnormalized.out\n  *\n  * \\sa MatrixBase::hnormalized() */\ntemplate<typename ExpressionType, int Direction>\nEIGEN_DEVICE_FUNC inline const typename VectorwiseOp<ExpressionType,Direction>::HNormalizedReturnType\nVectorwiseOp<ExpressionType,Direction>::hnormalized() const\n{\n  return HNormalized_Block(_expression(),0,0,\n      Direction==Vertical   ? _expression().rows()-1 : _expression().rows(),\n      Direction==Horizontal ? _expression().cols()-1 : _expression().cols()).cwiseQuotient(\n      Replicate<HNormalized_Factors,\n                Direction==Vertical   ? HNormalized_SizeMinusOne : 1,\n                Direction==Horizontal ? HNormalized_SizeMinusOne : 1>\n        (HNormalized_Factors(_expression(),\n          Direction==Vertical    ? _expression().rows()-1:0,\n          Direction==Horizontal  ? _expression().cols()-1:0,\n          Direction==Vertical    ? 1 : _expression().rows(),\n          Direction==Horizontal  ? 1 : _expression().cols()),\n         Direction==Vertical   ? _expression().rows()-1 : 1,\n         Direction==Horizontal ? _expression().cols()-1 : 1));\n}\n\nnamespace internal {\n\ntemplate<typename MatrixOrTransformType>\nstruct take_matrix_for_product\n{\n  typedef MatrixOrTransformType type;\n  EIGEN_DEVICE_FUNC static const type& run(const type &x) { return x; }\n};\n\ntemplate<typename Scalar, int Dim, int Mode,int Options>\nstruct take_matrix_for_product<Transform<Scalar, Dim, Mode, Options> >\n{\n  typedef Transform<Scalar, Dim, Mode, Options> TransformType;\n  typedef typename internal::add_const<typename TransformType::ConstAffinePart>::type type;\n  EIGEN_DEVICE_FUNC static type run (const TransformType& x) { return x.affine(); }\n};\n\ntemplate<typename Scalar, int Dim, int Options>\nstruct take_matrix_for_product<Transform<Scalar, Dim, Projective, Options> >\n{\n  typedef Transform<Scalar, Dim, Projective, Options> TransformType;\n  typedef typename TransformType::MatrixType type;\n  EIGEN_DEVICE_FUNC static const type& run (const TransformType& x) { return x.matrix(); }\n};\n\ntemplate<typename MatrixType,typename Lhs>\nstruct traits<homogeneous_left_product_impl<Homogeneous<MatrixType,Vertical>,Lhs> >\n{\n  typedef typename take_matrix_for_product<Lhs>::type LhsMatrixType;\n  typedef typename remove_all<MatrixType>::type MatrixTypeCleaned;\n  typedef typename remove_all<LhsMatrixType>::type LhsMatrixTypeCleaned;\n  typedef typename make_proper_matrix_type<\n                 typename traits<MatrixTypeCleaned>::Scalar,\n                 LhsMatrixTypeCleaned::RowsAtCompileTime,\n                 MatrixTypeCleaned::ColsAtCompileTime,\n                 MatrixTypeCleaned::PlainObject::Options,\n                 LhsMatrixTypeCleaned::MaxRowsAtCompileTime,\n                 MatrixTypeCleaned::MaxColsAtCompileTime>::type ReturnType;\n};\n\ntemplate<typename MatrixType,typename Lhs>\nstruct homogeneous_left_product_impl<Homogeneous<MatrixType,Vertical>,Lhs>\n  : public ReturnByValue<homogeneous_left_product_impl<Homogeneous<MatrixType,Vertical>,Lhs> >\n{\n  typedef typename traits<homogeneous_left_product_impl>::LhsMatrixType LhsMatrixType;\n  typedef typename remove_all<LhsMatrixType>::type LhsMatrixTypeCleaned;\n  typedef typename remove_all<typename LhsMatrixTypeCleaned::Nested>::type LhsMatrixTypeNested;\n  EIGEN_DEVICE_FUNC homogeneous_left_product_impl(const Lhs& lhs, const MatrixType& rhs)\n    : m_lhs(take_matrix_for_product<Lhs>::run(lhs)),\n      m_rhs(rhs)\n  {}\n\n  EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR\n  inline Index rows() const EIGEN_NOEXCEPT { return m_lhs.rows(); }\n  EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR\n  inline Index cols() const EIGEN_NOEXCEPT { return m_rhs.cols(); }\n\n  template<typename Dest> EIGEN_DEVICE_FUNC void evalTo(Dest& dst) const\n  {\n    // FIXME investigate how to allow lazy evaluation of this product when possible\n    dst = Block<const LhsMatrixTypeNested,\n              LhsMatrixTypeNested::RowsAtCompileTime,\n              LhsMatrixTypeNested::ColsAtCompileTime==Dynamic?Dynamic:LhsMatrixTypeNested::ColsAtCompileTime-1>\n            (m_lhs,0,0,m_lhs.rows(),m_lhs.cols()-1) * m_rhs;\n    dst += m_lhs.col(m_lhs.cols()-1).rowwise()\n            .template replicate<MatrixType::ColsAtCompileTime>(m_rhs.cols());\n  }\n\n  typename LhsMatrixTypeCleaned::Nested m_lhs;\n  typename MatrixType::Nested m_rhs;\n};\n\ntemplate<typename MatrixType,typename Rhs>\nstruct traits<homogeneous_right_product_impl<Homogeneous<MatrixType,Horizontal>,Rhs> >\n{\n  typedef typename make_proper_matrix_type<typename traits<MatrixType>::Scalar,\n                 MatrixType::RowsAtCompileTime,\n                 Rhs::ColsAtCompileTime,\n                 MatrixType::PlainObject::Options,\n                 MatrixType::MaxRowsAtCompileTime,\n                 Rhs::MaxColsAtCompileTime>::type ReturnType;\n};\n\ntemplate<typename MatrixType,typename Rhs>\nstruct homogeneous_right_product_impl<Homogeneous<MatrixType,Horizontal>,Rhs>\n  : public ReturnByValue<homogeneous_right_product_impl<Homogeneous<MatrixType,Horizontal>,Rhs> >\n{\n  typedef typename remove_all<typename Rhs::Nested>::type RhsNested;\n  EIGEN_DEVICE_FUNC homogeneous_right_product_impl(const MatrixType& lhs, const Rhs& rhs)\n    : m_lhs(lhs), m_rhs(rhs)\n  {}\n\n  EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline Index rows() const EIGEN_NOEXCEPT { return m_lhs.rows(); }\n  EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR inline Index cols() const EIGEN_NOEXCEPT { return m_rhs.cols(); }\n\n  template<typename Dest> EIGEN_DEVICE_FUNC void evalTo(Dest& dst) const\n  {\n    // FIXME investigate how to allow lazy evaluation of this product when possible\n    dst = m_lhs * Block<const RhsNested,\n                        RhsNested::RowsAtCompileTime==Dynamic?Dynamic:RhsNested::RowsAtCompileTime-1,\n                        RhsNested::ColsAtCompileTime>\n            (m_rhs,0,0,m_rhs.rows()-1,m_rhs.cols());\n    dst += m_rhs.row(m_rhs.rows()-1).colwise()\n            .template replicate<MatrixType::RowsAtCompileTime>(m_lhs.rows());\n  }\n\n  typename MatrixType::Nested m_lhs;\n  typename Rhs::Nested m_rhs;\n};\n\ntemplate<typename ArgType,int Direction>\nstruct evaluator_traits<Homogeneous<ArgType,Direction> >\n{\n  typedef typename storage_kind_to_evaluator_kind<typename ArgType::StorageKind>::Kind Kind;\n  typedef HomogeneousShape Shape;\n};\n\ntemplate<> struct AssignmentKind<DenseShape,HomogeneousShape> { typedef Dense2Dense Kind; };\n\n\ntemplate<typename ArgType,int Direction>\nstruct unary_evaluator<Homogeneous<ArgType,Direction>, IndexBased>\n  : evaluator<typename Homogeneous<ArgType,Direction>::PlainObject >\n{\n  typedef Homogeneous<ArgType,Direction> XprType;\n  typedef typename XprType::PlainObject PlainObject;\n  typedef evaluator<PlainObject> Base;\n\n  EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& op)\n    : Base(), m_temp(op)\n  {\n    ::new (static_cast<Base*>(this)) Base(m_temp);\n  }\n\nprotected:\n  PlainObject m_temp;\n};\n\n// dense = homogeneous\ntemplate< typename DstXprType, typename ArgType, typename Scalar>\nstruct Assignment<DstXprType, Homogeneous<ArgType,Vertical>, internal::assign_op<Scalar,typename ArgType::Scalar>, Dense2Dense>\n{\n  typedef Homogeneous<ArgType,Vertical> SrcXprType;\n  EIGEN_DEVICE_FUNC static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<Scalar,typename ArgType::Scalar> &)\n  {\n    Index dstRows = src.rows();\n    Index dstCols = src.cols();\n    if((dst.rows()!=dstRows) || (dst.cols()!=dstCols))\n      dst.resize(dstRows, dstCols);\n\n    dst.template topRows<ArgType::RowsAtCompileTime>(src.nestedExpression().rows()) = src.nestedExpression();\n    dst.row(dst.rows()-1).setOnes();\n  }\n};\n\n// dense = homogeneous\ntemplate< typename DstXprType, typename ArgType, typename Scalar>\nstruct Assignment<DstXprType, Homogeneous<ArgType,Horizontal>, internal::assign_op<Scalar,typename ArgType::Scalar>, Dense2Dense>\n{\n  typedef Homogeneous<ArgType,Horizontal> SrcXprType;\n  EIGEN_DEVICE_FUNC static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<Scalar,typename ArgType::Scalar> &)\n  {\n    Index dstRows = src.rows();\n    Index dstCols = src.cols();\n    if((dst.rows()!=dstRows) || (dst.cols()!=dstCols))\n      dst.resize(dstRows, dstCols);\n\n    dst.template leftCols<ArgType::ColsAtCompileTime>(src.nestedExpression().cols()) = src.nestedExpression();\n    dst.col(dst.cols()-1).setOnes();\n  }\n};\n\ntemplate<typename LhsArg, typename Rhs, int ProductTag>\nstruct generic_product_impl<Homogeneous<LhsArg,Horizontal>, Rhs, HomogeneousShape, DenseShape, ProductTag>\n{\n  template<typename Dest>\n  EIGEN_DEVICE_FUNC static void evalTo(Dest& dst, const Homogeneous<LhsArg,Horizontal>& lhs, const Rhs& rhs)\n  {\n    homogeneous_right_product_impl<Homogeneous<LhsArg,Horizontal>, Rhs>(lhs.nestedExpression(), rhs).evalTo(dst);\n  }\n};\n\ntemplate<typename Lhs,typename Rhs>\nstruct homogeneous_right_product_refactoring_helper\n{\n  enum {\n    Dim  = Lhs::ColsAtCompileTime,\n    Rows = Lhs::RowsAtCompileTime\n  };\n  typedef typename Rhs::template ConstNRowsBlockXpr<Dim>::Type          LinearBlockConst;\n  typedef typename remove_const<LinearBlockConst>::type                 LinearBlock;\n  typedef typename Rhs::ConstRowXpr                                     ConstantColumn;\n  typedef Replicate<const ConstantColumn,Rows,1>                        ConstantBlock;\n  typedef Product<Lhs,LinearBlock,LazyProduct>                          LinearProduct;\n  typedef CwiseBinaryOp<internal::scalar_sum_op<typename Lhs::Scalar,typename Rhs::Scalar>, const LinearProduct, const ConstantBlock> Xpr;\n};\n\ntemplate<typename Lhs, typename Rhs, int ProductTag>\nstruct product_evaluator<Product<Lhs, Rhs, LazyProduct>, ProductTag, HomogeneousShape, DenseShape>\n : public evaluator<typename homogeneous_right_product_refactoring_helper<typename Lhs::NestedExpression,Rhs>::Xpr>\n{\n  typedef Product<Lhs, Rhs, LazyProduct> XprType;\n  typedef homogeneous_right_product_refactoring_helper<typename Lhs::NestedExpression,Rhs> helper;\n  typedef typename helper::ConstantBlock ConstantBlock;\n  typedef typename helper::Xpr RefactoredXpr;\n  typedef evaluator<RefactoredXpr> Base;\n\n  EIGEN_DEVICE_FUNC explicit product_evaluator(const XprType& xpr)\n    : Base(  xpr.lhs().nestedExpression() .lazyProduct(  xpr.rhs().template topRows<helper::Dim>(xpr.lhs().nestedExpression().cols()) )\n            + ConstantBlock(xpr.rhs().row(xpr.rhs().rows()-1),xpr.lhs().rows(), 1) )\n  {}\n};\n\ntemplate<typename Lhs, typename RhsArg, int ProductTag>\nstruct generic_product_impl<Lhs, Homogeneous<RhsArg,Vertical>, DenseShape, HomogeneousShape, ProductTag>\n{\n  template<typename Dest>\n  EIGEN_DEVICE_FUNC static void evalTo(Dest& dst, const Lhs& lhs, const Homogeneous<RhsArg,Vertical>& rhs)\n  {\n    homogeneous_left_product_impl<Homogeneous<RhsArg,Vertical>, Lhs>(lhs, rhs.nestedExpression()).evalTo(dst);\n  }\n};\n\n// TODO: the following specialization is to address a regression from 3.2 to 3.3\n// In the future, this path should be optimized.\ntemplate<typename Lhs, typename RhsArg, int ProductTag>\nstruct generic_product_impl<Lhs, Homogeneous<RhsArg,Vertical>, TriangularShape, HomogeneousShape, ProductTag>\n{\n  template<typename Dest>\n  static void evalTo(Dest& dst, const Lhs& lhs, const Homogeneous<RhsArg,Vertical>& rhs)\n  {\n    dst.noalias() = lhs * rhs.eval();\n  }\n};\n\ntemplate<typename Lhs,typename Rhs>\nstruct homogeneous_left_product_refactoring_helper\n{\n  enum {\n    Dim = Rhs::RowsAtCompileTime,\n    Cols = Rhs::ColsAtCompileTime\n  };\n  typedef typename Lhs::template ConstNColsBlockXpr<Dim>::Type          LinearBlockConst;\n  typedef typename remove_const<LinearBlockConst>::type                 LinearBlock;\n  typedef typename Lhs::ConstColXpr                                     ConstantColumn;\n  typedef Replicate<const ConstantColumn,1,Cols>                        ConstantBlock;\n  typedef Product<LinearBlock,Rhs,LazyProduct>                          LinearProduct;\n  typedef CwiseBinaryOp<internal::scalar_sum_op<typename Lhs::Scalar,typename Rhs::Scalar>, const LinearProduct, const ConstantBlock> Xpr;\n};\n\ntemplate<typename Lhs, typename Rhs, int ProductTag>\nstruct product_evaluator<Product<Lhs, Rhs, LazyProduct>, ProductTag, DenseShape, HomogeneousShape>\n : public evaluator<typename homogeneous_left_product_refactoring_helper<Lhs,typename Rhs::NestedExpression>::Xpr>\n{\n  typedef Product<Lhs, Rhs, LazyProduct> XprType;\n  typedef homogeneous_left_product_refactoring_helper<Lhs,typename Rhs::NestedExpression> helper;\n  typedef typename helper::ConstantBlock ConstantBlock;\n  typedef typename helper::Xpr RefactoredXpr;\n  typedef evaluator<RefactoredXpr> Base;\n\n  EIGEN_DEVICE_FUNC explicit product_evaluator(const XprType& xpr)\n    : Base(   xpr.lhs().template leftCols<helper::Dim>(xpr.rhs().nestedExpression().rows()) .lazyProduct( xpr.rhs().nestedExpression() )\n            + ConstantBlock(xpr.lhs().col(xpr.lhs().cols()-1),1,xpr.rhs().cols()) )\n  {}\n};\n\ntemplate<typename Scalar, int Dim, int Mode,int Options, typename RhsArg, int ProductTag>\nstruct generic_product_impl<Transform<Scalar,Dim,Mode,Options>, Homogeneous<RhsArg,Vertical>, DenseShape, HomogeneousShape, ProductTag>\n{\n  typedef Transform<Scalar,Dim,Mode,Options> TransformType;\n  template<typename Dest>\n  EIGEN_DEVICE_FUNC static void evalTo(Dest& dst, const TransformType& lhs, const Homogeneous<RhsArg,Vertical>& rhs)\n  {\n    homogeneous_left_product_impl<Homogeneous<RhsArg,Vertical>, TransformType>(lhs, rhs.nestedExpression()).evalTo(dst);\n  }\n};\n\ntemplate<typename ExpressionType, int Side, bool Transposed>\nstruct permutation_matrix_product<ExpressionType, Side, Transposed, HomogeneousShape>\n  : public permutation_matrix_product<ExpressionType, Side, Transposed, DenseShape>\n{};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_HOMOGENEOUS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Geometry/Hyperplane.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_HYPERPLANE_H\n#define EIGEN_HYPERPLANE_H\n\nnamespace Eigen { \n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\class Hyperplane\n  *\n  * \\brief A hyperplane\n  *\n  * A hyperplane is an affine subspace of dimension n-1 in a space of dimension n.\n  * For example, a hyperplane in a plane is a line; a hyperplane in 3-space is a plane.\n  *\n  * \\tparam Scalar_ the scalar type, i.e., the type of the coefficients\n  * \\tparam _AmbientDim the dimension of the ambient space, can be a compile time value or Dynamic.\n  *             Notice that the dimension of the hyperplane is _AmbientDim-1.\n  *\n  * This class represents an hyperplane as the zero set of the implicit equation\n  * \\f$ n \\cdot x + d = 0 \\f$ where \\f$ n \\f$ is a unit normal vector of the plane (linear part)\n  * and \\f$ d \\f$ is the distance (offset) to the origin.\n  */\ntemplate <typename Scalar_, int _AmbientDim, int Options_>\nclass Hyperplane\n{\npublic:\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(Scalar_,_AmbientDim==Dynamic ? Dynamic : _AmbientDim+1)\n  enum {\n    AmbientDimAtCompileTime = _AmbientDim,\n    Options = Options_\n  };\n  typedef Scalar_ Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n  typedef Matrix<Scalar,AmbientDimAtCompileTime,1> VectorType;\n  typedef Matrix<Scalar,Index(AmbientDimAtCompileTime)==Dynamic\n                        ? Dynamic\n                        : Index(AmbientDimAtCompileTime)+1,1,Options> Coefficients;\n  typedef Block<Coefficients,AmbientDimAtCompileTime,1> NormalReturnType;\n  typedef const Block<const Coefficients,AmbientDimAtCompileTime,1> ConstNormalReturnType;\n\n  /** Default constructor without initialization */\n  EIGEN_DEVICE_FUNC inline Hyperplane() {}\n  \n  template<int OtherOptions>\n  EIGEN_DEVICE_FUNC Hyperplane(const Hyperplane<Scalar,AmbientDimAtCompileTime,OtherOptions>& other)\n   : m_coeffs(other.coeffs())\n  {}\n\n  /** Constructs a dynamic-size hyperplane with \\a _dim the dimension\n    * of the ambient space */\n  EIGEN_DEVICE_FUNC inline explicit Hyperplane(Index _dim) : m_coeffs(_dim+1) {}\n\n  /** Construct a plane from its normal \\a n and a point \\a e onto the plane.\n    * \\warning the vector normal is assumed to be normalized.\n    */\n  EIGEN_DEVICE_FUNC inline Hyperplane(const VectorType& n, const VectorType& e)\n    : m_coeffs(n.size()+1)\n  {\n    normal() = n;\n    offset() = -n.dot(e);\n  }\n\n  /** Constructs a plane from its normal \\a n and distance to the origin \\a d\n    * such that the algebraic equation of the plane is \\f$ n \\cdot x + d = 0 \\f$.\n    * \\warning the vector normal is assumed to be normalized.\n    */\n  EIGEN_DEVICE_FUNC inline Hyperplane(const VectorType& n, const Scalar& d)\n    : m_coeffs(n.size()+1)\n  {\n    normal() = n;\n    offset() = d;\n  }\n\n  /** Constructs a hyperplane passing through the two points. If the dimension of the ambient space\n    * is greater than 2, then there isn't uniqueness, so an arbitrary choice is made.\n    */\n  EIGEN_DEVICE_FUNC static inline Hyperplane Through(const VectorType& p0, const VectorType& p1)\n  {\n    Hyperplane result(p0.size());\n    result.normal() = (p1 - p0).unitOrthogonal();\n    result.offset() = -p0.dot(result.normal());\n    return result;\n  }\n\n  /** Constructs a hyperplane passing through the three points. The dimension of the ambient space\n    * is required to be exactly 3.\n    */\n  EIGEN_DEVICE_FUNC static inline Hyperplane Through(const VectorType& p0, const VectorType& p1, const VectorType& p2)\n  {\n    EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(VectorType, 3)\n    Hyperplane result(p0.size());\n    VectorType v0(p2 - p0), v1(p1 - p0);\n    result.normal() = v0.cross(v1);\n    RealScalar norm = result.normal().norm();\n    if(norm <= v0.norm() * v1.norm() * NumTraits<RealScalar>::epsilon())\n    {\n      Matrix<Scalar,2,3> m; m << v0.transpose(), v1.transpose();\n      JacobiSVD<Matrix<Scalar,2,3> > svd(m, ComputeFullV);\n      result.normal() = svd.matrixV().col(2);\n    }\n    else\n      result.normal() /= norm;\n    result.offset() = -p0.dot(result.normal());\n    return result;\n  }\n\n  /** Constructs a hyperplane passing through the parametrized line \\a parametrized.\n    * If the dimension of the ambient space is greater than 2, then there isn't uniqueness,\n    * so an arbitrary choice is made.\n    */\n  // FIXME to be consistent with the rest this could be implemented as a static Through function ??\n  EIGEN_DEVICE_FUNC explicit Hyperplane(const ParametrizedLine<Scalar, AmbientDimAtCompileTime>& parametrized)\n  {\n    normal() = parametrized.direction().unitOrthogonal();\n    offset() = -parametrized.origin().dot(normal());\n  }\n\n  EIGEN_DEVICE_FUNC ~Hyperplane() {}\n\n  /** \\returns the dimension in which the plane holds */\n  EIGEN_DEVICE_FUNC inline Index dim() const { return AmbientDimAtCompileTime==Dynamic ? m_coeffs.size()-1 : Index(AmbientDimAtCompileTime); }\n\n  /** normalizes \\c *this */\n  EIGEN_DEVICE_FUNC void normalize(void)\n  {\n    m_coeffs /= normal().norm();\n  }\n\n  /** \\returns the signed distance between the plane \\c *this and a point \\a p.\n    * \\sa absDistance()\n    */\n  EIGEN_DEVICE_FUNC inline Scalar signedDistance(const VectorType& p) const { return normal().dot(p) + offset(); }\n\n  /** \\returns the absolute distance between the plane \\c *this and a point \\a p.\n    * \\sa signedDistance()\n    */\n  EIGEN_DEVICE_FUNC inline Scalar absDistance(const VectorType& p) const { return numext::abs(signedDistance(p)); }\n\n  /** \\returns the projection of a point \\a p onto the plane \\c *this.\n    */\n  EIGEN_DEVICE_FUNC inline VectorType projection(const VectorType& p) const { return p - signedDistance(p) * normal(); }\n\n  /** \\returns a constant reference to the unit normal vector of the plane, which corresponds\n    * to the linear part of the implicit equation.\n    */\n  EIGEN_DEVICE_FUNC inline ConstNormalReturnType normal() const { return ConstNormalReturnType(m_coeffs,0,0,dim(),1); }\n\n  /** \\returns a non-constant reference to the unit normal vector of the plane, which corresponds\n    * to the linear part of the implicit equation.\n    */\n  EIGEN_DEVICE_FUNC inline NormalReturnType normal() { return NormalReturnType(m_coeffs,0,0,dim(),1); }\n\n  /** \\returns the distance to the origin, which is also the \"constant term\" of the implicit equation\n    * \\warning the vector normal is assumed to be normalized.\n    */\n  EIGEN_DEVICE_FUNC inline const Scalar& offset() const { return m_coeffs.coeff(dim()); }\n\n  /** \\returns a non-constant reference to the distance to the origin, which is also the constant part\n    * of the implicit equation */\n  EIGEN_DEVICE_FUNC inline Scalar& offset() { return m_coeffs(dim()); }\n\n  /** \\returns a constant reference to the coefficients c_i of the plane equation:\n    * \\f$ c_0*x_0 + ... + c_{d-1}*x_{d-1} + c_d = 0 \\f$\n    */\n  EIGEN_DEVICE_FUNC inline const Coefficients& coeffs() const { return m_coeffs; }\n\n  /** \\returns a non-constant reference to the coefficients c_i of the plane equation:\n    * \\f$ c_0*x_0 + ... + c_{d-1}*x_{d-1} + c_d = 0 \\f$\n    */\n  EIGEN_DEVICE_FUNC inline Coefficients& coeffs() { return m_coeffs; }\n\n  /** \\returns the intersection of *this with \\a other.\n    *\n    * \\warning The ambient space must be a plane, i.e. have dimension 2, so that \\c *this and \\a other are lines.\n    *\n    * \\note If \\a other is approximately parallel to *this, this method will return any point on *this.\n    */\n  EIGEN_DEVICE_FUNC VectorType intersection(const Hyperplane& other) const\n  {\n    EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(VectorType, 2)\n    Scalar det = coeffs().coeff(0) * other.coeffs().coeff(1) - coeffs().coeff(1) * other.coeffs().coeff(0);\n    // since the line equations ax+by=c are normalized with a^2+b^2=1, the following tests\n    // whether the two lines are approximately parallel.\n    if(internal::isMuchSmallerThan(det, Scalar(1)))\n    {   // special case where the two lines are approximately parallel. Pick any point on the first line.\n        if(numext::abs(coeffs().coeff(1))>numext::abs(coeffs().coeff(0)))\n            return VectorType(coeffs().coeff(1), -coeffs().coeff(2)/coeffs().coeff(1)-coeffs().coeff(0));\n        else\n            return VectorType(-coeffs().coeff(2)/coeffs().coeff(0)-coeffs().coeff(1), coeffs().coeff(0));\n    }\n    else\n    {   // general case\n        Scalar invdet = Scalar(1) / det;\n        return VectorType(invdet*(coeffs().coeff(1)*other.coeffs().coeff(2)-other.coeffs().coeff(1)*coeffs().coeff(2)),\n                          invdet*(other.coeffs().coeff(0)*coeffs().coeff(2)-coeffs().coeff(0)*other.coeffs().coeff(2)));\n    }\n  }\n\n  /** Applies the transformation matrix \\a mat to \\c *this and returns a reference to \\c *this.\n    *\n    * \\param mat the Dim x Dim transformation matrix\n    * \\param traits specifies whether the matrix \\a mat represents an #Isometry\n    *               or a more generic #Affine transformation. The default is #Affine.\n    */\n  template<typename XprType>\n  EIGEN_DEVICE_FUNC inline Hyperplane& transform(const MatrixBase<XprType>& mat, TransformTraits traits = Affine)\n  {\n    if (traits==Affine)\n    {\n      normal() = mat.inverse().transpose() * normal();\n      m_coeffs /= normal().norm();\n    }\n    else if (traits==Isometry)\n      normal() = mat * normal();\n    else\n    {\n      eigen_assert(0 && \"invalid traits value in Hyperplane::transform()\");\n    }\n    return *this;\n  }\n\n  /** Applies the transformation \\a t to \\c *this and returns a reference to \\c *this.\n    *\n    * \\param t the transformation of dimension Dim\n    * \\param traits specifies whether the transformation \\a t represents an #Isometry\n    *               or a more generic #Affine transformation. The default is #Affine.\n    *               Other kind of transformations are not supported.\n    */\n  template<int TrOptions>\n  EIGEN_DEVICE_FUNC inline Hyperplane& transform(const Transform<Scalar,AmbientDimAtCompileTime,Affine,TrOptions>& t,\n                                TransformTraits traits = Affine)\n  {\n    transform(t.linear(), traits);\n    offset() -= normal().dot(t.translation());\n    return *this;\n  }\n\n  /** \\returns \\c *this with scalar type casted to \\a NewScalarType\n    *\n    * Note that if \\a NewScalarType is equal to the current scalar type of \\c *this\n    * then this function smartly returns a const reference to \\c *this.\n    */\n  template<typename NewScalarType>\n  EIGEN_DEVICE_FUNC inline typename internal::cast_return_type<Hyperplane,\n           Hyperplane<NewScalarType,AmbientDimAtCompileTime,Options> >::type cast() const\n  {\n    return typename internal::cast_return_type<Hyperplane,\n                    Hyperplane<NewScalarType,AmbientDimAtCompileTime,Options> >::type(*this);\n  }\n\n  /** Copy constructor with scalar type conversion */\n  template<typename OtherScalarType,int OtherOptions>\n  EIGEN_DEVICE_FUNC inline explicit Hyperplane(const Hyperplane<OtherScalarType,AmbientDimAtCompileTime,OtherOptions>& other)\n  { m_coeffs = other.coeffs().template cast<Scalar>(); }\n\n  /** \\returns \\c true if \\c *this is approximately equal to \\a other, within the precision\n    * determined by \\a prec.\n    *\n    * \\sa MatrixBase::isApprox() */\n  template<int OtherOptions>\n  EIGEN_DEVICE_FUNC bool isApprox(const Hyperplane<Scalar,AmbientDimAtCompileTime,OtherOptions>& other, const typename NumTraits<Scalar>::Real& prec = NumTraits<Scalar>::dummy_precision()) const\n  { return m_coeffs.isApprox(other.m_coeffs, prec); }\n\nprotected:\n\n  Coefficients m_coeffs;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_HYPERPLANE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Geometry/OrthoMethods.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ORTHOMETHODS_H\n#define EIGEN_ORTHOMETHODS_H\n\nnamespace Eigen { \n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\returns the cross product of \\c *this and \\a other\n  *\n  * Here is a very good explanation of cross-product: http://xkcd.com/199/\n  * \n  * With complex numbers, the cross product is implemented as\n  * \\f$ (\\mathbf{a}+i\\mathbf{b}) \\times (\\mathbf{c}+i\\mathbf{d}) = (\\mathbf{a} \\times \\mathbf{c} - \\mathbf{b} \\times \\mathbf{d}) - i(\\mathbf{a} \\times \\mathbf{d} - \\mathbf{b} \\times \\mathbf{c})\\f$\n  * \n  * \\sa MatrixBase::cross3()\n  */\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename MatrixBase<Derived>::template cross_product_return_type<OtherDerived>::type\n#else\ntypename MatrixBase<Derived>::PlainObject\n#endif\nMatrixBase<Derived>::cross(const MatrixBase<OtherDerived>& other) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Derived,3)\n  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(OtherDerived,3)\n\n  // Note that there is no need for an expression here since the compiler\n  // optimize such a small temporary very well (even within a complex expression)\n  typename internal::nested_eval<Derived,2>::type lhs(derived());\n  typename internal::nested_eval<OtherDerived,2>::type rhs(other.derived());\n  return typename cross_product_return_type<OtherDerived>::type(\n    numext::conj(lhs.coeff(1) * rhs.coeff(2) - lhs.coeff(2) * rhs.coeff(1)),\n    numext::conj(lhs.coeff(2) * rhs.coeff(0) - lhs.coeff(0) * rhs.coeff(2)),\n    numext::conj(lhs.coeff(0) * rhs.coeff(1) - lhs.coeff(1) * rhs.coeff(0))\n  );\n}\n\nnamespace internal {\n\ntemplate< int Arch,typename VectorLhs,typename VectorRhs,\n          typename Scalar = typename VectorLhs::Scalar,\n          bool Vectorizable = bool((VectorLhs::Flags&VectorRhs::Flags)&PacketAccessBit)>\nstruct cross3_impl {\n  EIGEN_DEVICE_FUNC static inline typename internal::plain_matrix_type<VectorLhs>::type\n  run(const VectorLhs& lhs, const VectorRhs& rhs)\n  {\n    return typename internal::plain_matrix_type<VectorLhs>::type(\n      numext::conj(lhs.coeff(1) * rhs.coeff(2) - lhs.coeff(2) * rhs.coeff(1)),\n      numext::conj(lhs.coeff(2) * rhs.coeff(0) - lhs.coeff(0) * rhs.coeff(2)),\n      numext::conj(lhs.coeff(0) * rhs.coeff(1) - lhs.coeff(1) * rhs.coeff(0)),\n      0\n    );\n  }\n};\n\n}\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\returns the cross product of \\c *this and \\a other using only the x, y, and z coefficients\n  *\n  * The size of \\c *this and \\a other must be four. This function is especially useful\n  * when using 4D vectors instead of 3D ones to get advantage of SSE/AltiVec vectorization.\n  *\n  * \\sa MatrixBase::cross()\n  */\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC inline typename MatrixBase<Derived>::PlainObject\nMatrixBase<Derived>::cross3(const MatrixBase<OtherDerived>& other) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Derived,4)\n  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(OtherDerived,4)\n\n  typedef typename internal::nested_eval<Derived,2>::type DerivedNested;\n  typedef typename internal::nested_eval<OtherDerived,2>::type OtherDerivedNested;\n  DerivedNested lhs(derived());\n  OtherDerivedNested rhs(other.derived());\n\n  return internal::cross3_impl<Architecture::Target,\n                        typename internal::remove_all<DerivedNested>::type,\n                        typename internal::remove_all<OtherDerivedNested>::type>::run(lhs,rhs);\n}\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\returns a matrix expression of the cross product of each column or row\n  * of the referenced expression with the \\a other vector.\n  *\n  * The referenced matrix must have one dimension equal to 3.\n  * The result matrix has the same dimensions than the referenced one.\n  *\n  * \\sa MatrixBase::cross() */\ntemplate<typename ExpressionType, int Direction>\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC \nconst typename VectorwiseOp<ExpressionType,Direction>::CrossReturnType\nVectorwiseOp<ExpressionType,Direction>::cross(const MatrixBase<OtherDerived>& other) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(OtherDerived,3)\n  EIGEN_STATIC_ASSERT((internal::is_same<Scalar, typename OtherDerived::Scalar>::value),\n    YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n  \n  typename internal::nested_eval<ExpressionType,2>::type mat(_expression());\n  typename internal::nested_eval<OtherDerived,2>::type vec(other.derived());\n\n  CrossReturnType res(_expression().rows(),_expression().cols());\n  if(Direction==Vertical)\n  {\n    eigen_assert(CrossReturnType::RowsAtCompileTime==3 && \"the matrix must have exactly 3 rows\");\n    res.row(0) = (mat.row(1) * vec.coeff(2) - mat.row(2) * vec.coeff(1)).conjugate();\n    res.row(1) = (mat.row(2) * vec.coeff(0) - mat.row(0) * vec.coeff(2)).conjugate();\n    res.row(2) = (mat.row(0) * vec.coeff(1) - mat.row(1) * vec.coeff(0)).conjugate();\n  }\n  else\n  {\n    eigen_assert(CrossReturnType::ColsAtCompileTime==3 && \"the matrix must have exactly 3 columns\");\n    res.col(0) = (mat.col(1) * vec.coeff(2) - mat.col(2) * vec.coeff(1)).conjugate();\n    res.col(1) = (mat.col(2) * vec.coeff(0) - mat.col(0) * vec.coeff(2)).conjugate();\n    res.col(2) = (mat.col(0) * vec.coeff(1) - mat.col(1) * vec.coeff(0)).conjugate();\n  }\n  return res;\n}\n\nnamespace internal {\n\ntemplate<typename Derived, int Size = Derived::SizeAtCompileTime>\nstruct unitOrthogonal_selector\n{\n  typedef typename plain_matrix_type<Derived>::type VectorType;\n  typedef typename traits<Derived>::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar,2,1> Vector2;\n  EIGEN_DEVICE_FUNC\n  static inline VectorType run(const Derived& src)\n  {\n    VectorType perp = VectorType::Zero(src.size());\n    Index maxi = 0;\n    Index sndi = 0;\n    src.cwiseAbs().maxCoeff(&maxi);\n    if (maxi==0)\n      sndi = 1;\n    RealScalar invnm = RealScalar(1)/(Vector2() << src.coeff(sndi),src.coeff(maxi)).finished().norm();\n    perp.coeffRef(maxi) = -numext::conj(src.coeff(sndi)) * invnm;\n    perp.coeffRef(sndi) =  numext::conj(src.coeff(maxi)) * invnm;\n\n    return perp;\n   }\n};\n\ntemplate<typename Derived>\nstruct unitOrthogonal_selector<Derived,3>\n{\n  typedef typename plain_matrix_type<Derived>::type VectorType;\n  typedef typename traits<Derived>::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  EIGEN_DEVICE_FUNC\n  static inline VectorType run(const Derived& src)\n  {\n    VectorType perp;\n    /* Let us compute the crossed product of *this with a vector\n     * that is not too close to being colinear to *this.\n     */\n\n    /* unless the x and y coords are both close to zero, we can\n     * simply take ( -y, x, 0 ) and normalize it.\n     */\n    if((!isMuchSmallerThan(src.x(), src.z()))\n    || (!isMuchSmallerThan(src.y(), src.z())))\n    {\n      RealScalar invnm = RealScalar(1)/src.template head<2>().norm();\n      perp.coeffRef(0) = -numext::conj(src.y())*invnm;\n      perp.coeffRef(1) = numext::conj(src.x())*invnm;\n      perp.coeffRef(2) = 0;\n    }\n    /* if both x and y are close to zero, then the vector is close\n     * to the z-axis, so it's far from colinear to the x-axis for instance.\n     * So we take the crossed product with (1,0,0) and normalize it.\n     */\n    else\n    {\n      RealScalar invnm = RealScalar(1)/src.template tail<2>().norm();\n      perp.coeffRef(0) = 0;\n      perp.coeffRef(1) = -numext::conj(src.z())*invnm;\n      perp.coeffRef(2) = numext::conj(src.y())*invnm;\n    }\n\n    return perp;\n   }\n};\n\ntemplate<typename Derived>\nstruct unitOrthogonal_selector<Derived,2>\n{\n  typedef typename plain_matrix_type<Derived>::type VectorType;\n  EIGEN_DEVICE_FUNC\n  static inline VectorType run(const Derived& src)\n  { return VectorType(-numext::conj(src.y()), numext::conj(src.x())).normalized(); }\n};\n\n} // end namespace internal\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\returns a unit vector which is orthogonal to \\c *this\n  *\n  * The size of \\c *this must be at least 2. If the size is exactly 2,\n  * then the returned vector is a counter clock wise rotation of \\c *this, i.e., (-y,x).normalized().\n  *\n  * \\sa cross()\n  */\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC typename MatrixBase<Derived>::PlainObject\nMatrixBase<Derived>::unitOrthogonal() const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return internal::unitOrthogonal_selector<Derived>::run(derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_ORTHOMETHODS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Geometry/ParametrizedLine.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_PARAMETRIZEDLINE_H\n#define EIGEN_PARAMETRIZEDLINE_H\n\nnamespace Eigen { \n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\class ParametrizedLine\n  *\n  * \\brief A parametrized line\n  *\n  * A parametrized line is defined by an origin point \\f$ \\mathbf{o} \\f$ and a unit\n  * direction vector \\f$ \\mathbf{d} \\f$ such that the line corresponds to\n  * the set \\f$ l(t) = \\mathbf{o} + t \\mathbf{d} \\f$, \\f$ t \\in \\mathbf{R} \\f$.\n  *\n  * \\tparam Scalar_ the scalar type, i.e., the type of the coefficients\n  * \\tparam _AmbientDim the dimension of the ambient space, can be a compile time value or Dynamic.\n  */\ntemplate <typename Scalar_, int _AmbientDim, int Options_>\nclass ParametrizedLine\n{\npublic:\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(Scalar_,_AmbientDim)\n  enum {\n    AmbientDimAtCompileTime = _AmbientDim,\n    Options = Options_\n  };\n  typedef Scalar_ Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n  typedef Matrix<Scalar,AmbientDimAtCompileTime,1,Options> VectorType;\n\n  /** Default constructor without initialization */\n  EIGEN_DEVICE_FUNC inline ParametrizedLine() {}\n  \n  template<int OtherOptions>\n  EIGEN_DEVICE_FUNC ParametrizedLine(const ParametrizedLine<Scalar,AmbientDimAtCompileTime,OtherOptions>& other)\n   : m_origin(other.origin()), m_direction(other.direction())\n  {}\n\n  /** Constructs a dynamic-size line with \\a _dim the dimension\n    * of the ambient space */\n  EIGEN_DEVICE_FUNC inline explicit ParametrizedLine(Index _dim) : m_origin(_dim), m_direction(_dim) {}\n\n  /** Initializes a parametrized line of direction \\a direction and origin \\a origin.\n    * \\warning the vector direction is assumed to be normalized.\n    */\n  EIGEN_DEVICE_FUNC ParametrizedLine(const VectorType& origin, const VectorType& direction)\n    : m_origin(origin), m_direction(direction) {}\n\n  template <int OtherOptions>\n  EIGEN_DEVICE_FUNC explicit ParametrizedLine(const Hyperplane<Scalar_, _AmbientDim, OtherOptions>& hyperplane);\n\n  /** Constructs a parametrized line going from \\a p0 to \\a p1. */\n  EIGEN_DEVICE_FUNC static inline ParametrizedLine Through(const VectorType& p0, const VectorType& p1)\n  { return ParametrizedLine(p0, (p1-p0).normalized()); }\n\n  EIGEN_DEVICE_FUNC ~ParametrizedLine() {}\n\n  /** \\returns the dimension in which the line holds */\n  EIGEN_DEVICE_FUNC inline Index dim() const { return m_direction.size(); }\n\n  EIGEN_DEVICE_FUNC const VectorType& origin() const { return m_origin; }\n  EIGEN_DEVICE_FUNC VectorType& origin() { return m_origin; }\n\n  EIGEN_DEVICE_FUNC const VectorType& direction() const { return m_direction; }\n  EIGEN_DEVICE_FUNC VectorType& direction() { return m_direction; }\n\n  /** \\returns the squared distance of a point \\a p to its projection onto the line \\c *this.\n    * \\sa distance()\n    */\n  EIGEN_DEVICE_FUNC RealScalar squaredDistance(const VectorType& p) const\n  {\n    VectorType diff = p - origin();\n    return (diff - direction().dot(diff) * direction()).squaredNorm();\n  }\n  /** \\returns the distance of a point \\a p to its projection onto the line \\c *this.\n    * \\sa squaredDistance()\n    */\n  EIGEN_DEVICE_FUNC RealScalar distance(const VectorType& p) const { EIGEN_USING_STD(sqrt) return sqrt(squaredDistance(p)); }\n\n  /** \\returns the projection of a point \\a p onto the line \\c *this. */\n  EIGEN_DEVICE_FUNC VectorType projection(const VectorType& p) const\n  { return origin() + direction().dot(p-origin()) * direction(); }\n\n  EIGEN_DEVICE_FUNC VectorType pointAt(const Scalar& t) const;\n  \n  template <int OtherOptions>\n  EIGEN_DEVICE_FUNC Scalar intersectionParameter(const Hyperplane<Scalar_, _AmbientDim, OtherOptions>& hyperplane) const;\n \n  template <int OtherOptions>\n  EIGEN_DEVICE_FUNC Scalar intersection(const Hyperplane<Scalar_, _AmbientDim, OtherOptions>& hyperplane) const;\n  \n  template <int OtherOptions>\n  EIGEN_DEVICE_FUNC VectorType intersectionPoint(const Hyperplane<Scalar_, _AmbientDim, OtherOptions>& hyperplane) const;\n\n  /** Applies the transformation matrix \\a mat to \\c *this and returns a reference to \\c *this.\n    *\n    * \\param mat the Dim x Dim transformation matrix\n    * \\param traits specifies whether the matrix \\a mat represents an #Isometry\n    *               or a more generic #Affine transformation. The default is #Affine.\n    */\n  template<typename XprType>\n  EIGEN_DEVICE_FUNC inline ParametrizedLine& transform(const MatrixBase<XprType>& mat, TransformTraits traits = Affine)\n  {\n    if (traits==Affine)\n      direction() = (mat * direction()).normalized();\n    else if (traits==Isometry)\n      direction() = mat * direction();\n    else\n    {\n      eigen_assert(0 && \"invalid traits value in ParametrizedLine::transform()\");\n    }\n    origin() = mat * origin();\n    return *this;\n  }\n\n  /** Applies the transformation \\a t to \\c *this and returns a reference to \\c *this.\n    *\n    * \\param t the transformation of dimension Dim\n    * \\param traits specifies whether the transformation \\a t represents an #Isometry\n    *               or a more generic #Affine transformation. The default is #Affine.\n    *               Other kind of transformations are not supported.\n    */\n  template<int TrOptions>\n  EIGEN_DEVICE_FUNC inline ParametrizedLine& transform(const Transform<Scalar,AmbientDimAtCompileTime,Affine,TrOptions>& t,\n                                                       TransformTraits traits = Affine)\n  {\n    transform(t.linear(), traits);\n    origin() += t.translation();\n    return *this;\n  }\n\n/** \\returns \\c *this with scalar type casted to \\a NewScalarType\n    *\n    * Note that if \\a NewScalarType is equal to the current scalar type of \\c *this\n    * then this function smartly returns a const reference to \\c *this.\n    */\n  template<typename NewScalarType>\n  EIGEN_DEVICE_FUNC inline typename internal::cast_return_type<ParametrizedLine,\n           ParametrizedLine<NewScalarType,AmbientDimAtCompileTime,Options> >::type cast() const\n  {\n    return typename internal::cast_return_type<ParametrizedLine,\n                    ParametrizedLine<NewScalarType,AmbientDimAtCompileTime,Options> >::type(*this);\n  }\n\n  /** Copy constructor with scalar type conversion */\n  template<typename OtherScalarType,int OtherOptions>\n  EIGEN_DEVICE_FUNC inline explicit ParametrizedLine(const ParametrizedLine<OtherScalarType,AmbientDimAtCompileTime,OtherOptions>& other)\n  {\n    m_origin = other.origin().template cast<Scalar>();\n    m_direction = other.direction().template cast<Scalar>();\n  }\n\n  /** \\returns \\c true if \\c *this is approximately equal to \\a other, within the precision\n    * determined by \\a prec.\n    *\n    * \\sa MatrixBase::isApprox() */\n  EIGEN_DEVICE_FUNC bool isApprox(const ParametrizedLine& other, const typename NumTraits<Scalar>::Real& prec = NumTraits<Scalar>::dummy_precision()) const\n  { return m_origin.isApprox(other.m_origin, prec) && m_direction.isApprox(other.m_direction, prec); }\n\nprotected:\n\n  VectorType m_origin, m_direction;\n};\n\n/** Constructs a parametrized line from a 2D hyperplane\n  *\n  * \\warning the ambient space must have dimension 2 such that the hyperplane actually describes a line\n  */\ntemplate <typename Scalar_, int _AmbientDim, int Options_>\ntemplate <int OtherOptions>\nEIGEN_DEVICE_FUNC inline ParametrizedLine<Scalar_, _AmbientDim,Options_>::ParametrizedLine(const Hyperplane<Scalar_, _AmbientDim,OtherOptions>& hyperplane)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(VectorType, 2)\n  direction() = hyperplane.normal().unitOrthogonal();\n  origin() = -hyperplane.normal()*hyperplane.offset();\n}\n\n/** \\returns the point at \\a t along this line\n  */\ntemplate <typename Scalar_, int _AmbientDim, int Options_>\nEIGEN_DEVICE_FUNC inline typename ParametrizedLine<Scalar_, _AmbientDim,Options_>::VectorType\nParametrizedLine<Scalar_, _AmbientDim,Options_>::pointAt(const Scalar_& t) const\n{\n  return origin() + (direction()*t); \n}\n\n/** \\returns the parameter value of the intersection between \\c *this and the given \\a hyperplane\n  */\ntemplate <typename Scalar_, int _AmbientDim, int Options_>\ntemplate <int OtherOptions>\nEIGEN_DEVICE_FUNC inline Scalar_ ParametrizedLine<Scalar_, _AmbientDim,Options_>::intersectionParameter(const Hyperplane<Scalar_, _AmbientDim, OtherOptions>& hyperplane) const\n{\n  return -(hyperplane.offset()+hyperplane.normal().dot(origin()))\n          / hyperplane.normal().dot(direction());\n}\n\n\n/** \\deprecated use intersectionParameter()\n  * \\returns the parameter value of the intersection between \\c *this and the given \\a hyperplane\n  */\ntemplate <typename Scalar_, int _AmbientDim, int Options_>\ntemplate <int OtherOptions>\nEIGEN_DEVICE_FUNC inline Scalar_ ParametrizedLine<Scalar_, _AmbientDim,Options_>::intersection(const Hyperplane<Scalar_, _AmbientDim, OtherOptions>& hyperplane) const\n{\n  return intersectionParameter(hyperplane);\n}\n\n/** \\returns the point of the intersection between \\c *this and the given hyperplane\n  */\ntemplate <typename Scalar_, int _AmbientDim, int Options_>\ntemplate <int OtherOptions>\nEIGEN_DEVICE_FUNC inline typename ParametrizedLine<Scalar_, _AmbientDim,Options_>::VectorType\nParametrizedLine<Scalar_, _AmbientDim,Options_>::intersectionPoint(const Hyperplane<Scalar_, _AmbientDim, OtherOptions>& hyperplane) const\n{\n  return pointAt(intersectionParameter(hyperplane));\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_PARAMETRIZEDLINE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Geometry/Quaternion.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Mathieu Gautier <mathieu.gautier@cea.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_QUATERNION_H\n#define EIGEN_QUATERNION_H\nnamespace Eigen { \n\n\n/***************************************************************************\n* Definition of QuaternionBase<Derived>\n* The implementation is at the end of the file\n***************************************************************************/\n\nnamespace internal {\ntemplate<typename Other,\n         int OtherRows=Other::RowsAtCompileTime,\n         int OtherCols=Other::ColsAtCompileTime>\nstruct quaternionbase_assign_impl;\n}\n\n/** \\geometry_module \\ingroup Geometry_Module\n  * \\class QuaternionBase\n  * \\brief Base class for quaternion expressions\n  * \\tparam Derived derived type (CRTP)\n  * \\sa class Quaternion\n  */\ntemplate<class Derived>\nclass QuaternionBase : public RotationBase<Derived, 3>\n{\n public:\n  typedef RotationBase<Derived, 3> Base;\n\n  using Base::operator*;\n  using Base::derived;\n\n  typedef typename internal::traits<Derived>::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef typename internal::traits<Derived>::Coefficients Coefficients;\n  typedef typename Coefficients::CoeffReturnType CoeffReturnType;\n  typedef typename internal::conditional<bool(internal::traits<Derived>::Flags&LvalueBit),\n                                        Scalar&, CoeffReturnType>::type NonConstCoeffReturnType;\n\n\n  enum {\n    Flags = Eigen::internal::traits<Derived>::Flags\n  };\n\n // typedef typename Matrix<Scalar,4,1> Coefficients;\n  /** the type of a 3D vector */\n  typedef Matrix<Scalar,3,1> Vector3;\n  /** the equivalent rotation matrix type */\n  typedef Matrix<Scalar,3,3> Matrix3;\n  /** the equivalent angle-axis type */\n  typedef AngleAxis<Scalar> AngleAxisType;\n\n\n\n  /** \\returns the \\c x coefficient */\n  EIGEN_DEVICE_FUNC inline CoeffReturnType x() const { return this->derived().coeffs().coeff(0); }\n  /** \\returns the \\c y coefficient */\n  EIGEN_DEVICE_FUNC inline CoeffReturnType y() const { return this->derived().coeffs().coeff(1); }\n  /** \\returns the \\c z coefficient */\n  EIGEN_DEVICE_FUNC inline CoeffReturnType z() const { return this->derived().coeffs().coeff(2); }\n  /** \\returns the \\c w coefficient */\n  EIGEN_DEVICE_FUNC inline CoeffReturnType w() const { return this->derived().coeffs().coeff(3); }\n\n  /** \\returns a reference to the \\c x coefficient (if Derived is a non-const lvalue) */\n  EIGEN_DEVICE_FUNC inline NonConstCoeffReturnType x() { return this->derived().coeffs().x(); }\n  /** \\returns a reference to the \\c y coefficient (if Derived is a non-const lvalue) */\n  EIGEN_DEVICE_FUNC inline NonConstCoeffReturnType y() { return this->derived().coeffs().y(); }\n  /** \\returns a reference to the \\c z coefficient (if Derived is a non-const lvalue) */\n  EIGEN_DEVICE_FUNC inline NonConstCoeffReturnType z() { return this->derived().coeffs().z(); }\n  /** \\returns a reference to the \\c w coefficient (if Derived is a non-const lvalue) */\n  EIGEN_DEVICE_FUNC inline NonConstCoeffReturnType w() { return this->derived().coeffs().w(); }\n\n  /** \\returns a read-only vector expression of the imaginary part (x,y,z) */\n  EIGEN_DEVICE_FUNC inline const VectorBlock<const Coefficients,3> vec() const { return coeffs().template head<3>(); }\n\n  /** \\returns a vector expression of the imaginary part (x,y,z) */\n  EIGEN_DEVICE_FUNC inline VectorBlock<Coefficients,3> vec() { return coeffs().template head<3>(); }\n\n  /** \\returns a read-only vector expression of the coefficients (x,y,z,w) */\n  EIGEN_DEVICE_FUNC inline const typename internal::traits<Derived>::Coefficients& coeffs() const { return derived().coeffs(); }\n\n  /** \\returns a vector expression of the coefficients (x,y,z,w) */\n  EIGEN_DEVICE_FUNC inline typename internal::traits<Derived>::Coefficients& coeffs() { return derived().coeffs(); }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE QuaternionBase<Derived>& operator=(const QuaternionBase<Derived>& other);\n  template<class OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const QuaternionBase<OtherDerived>& other);\n\n// disabled this copy operator as it is giving very strange compilation errors when compiling\n// test_stdvector with GCC 4.4.2. This looks like a GCC bug though, so feel free to re-enable it if it's\n// useful; however notice that we already have the templated operator= above and e.g. in MatrixBase\n// we didn't have to add, in addition to templated operator=, such a non-templated copy operator.\n//  Derived& operator=(const QuaternionBase& other)\n//  { return operator=<Derived>(other); }\n\n  EIGEN_DEVICE_FUNC Derived& operator=(const AngleAxisType& aa);\n  template<class OtherDerived> EIGEN_DEVICE_FUNC Derived& operator=(const MatrixBase<OtherDerived>& m);\n\n  /** \\returns a quaternion representing an identity rotation\n    * \\sa MatrixBase::Identity()\n    */\n  EIGEN_DEVICE_FUNC static inline Quaternion<Scalar> Identity() { return Quaternion<Scalar>(Scalar(1), Scalar(0), Scalar(0), Scalar(0)); }\n\n  /** \\sa QuaternionBase::Identity(), MatrixBase::setIdentity()\n    */\n  EIGEN_DEVICE_FUNC inline QuaternionBase& setIdentity() { coeffs() << Scalar(0), Scalar(0), Scalar(0), Scalar(1); return *this; }\n\n  /** \\returns the squared norm of the quaternion's coefficients\n    * \\sa QuaternionBase::norm(), MatrixBase::squaredNorm()\n    */\n  EIGEN_DEVICE_FUNC inline Scalar squaredNorm() const { return coeffs().squaredNorm(); }\n\n  /** \\returns the norm of the quaternion's coefficients\n    * \\sa QuaternionBase::squaredNorm(), MatrixBase::norm()\n    */\n  EIGEN_DEVICE_FUNC inline Scalar norm() const { return coeffs().norm(); }\n\n  /** Normalizes the quaternion \\c *this\n    * \\sa normalized(), MatrixBase::normalize() */\n  EIGEN_DEVICE_FUNC inline void normalize() { coeffs().normalize(); }\n  /** \\returns a normalized copy of \\c *this\n    * \\sa normalize(), MatrixBase::normalized() */\n  EIGEN_DEVICE_FUNC inline Quaternion<Scalar> normalized() const { return Quaternion<Scalar>(coeffs().normalized()); }\n\n    /** \\returns the dot product of \\c *this and \\a other\n    * Geometrically speaking, the dot product of two unit quaternions\n    * corresponds to the cosine of half the angle between the two rotations.\n    * \\sa angularDistance()\n    */\n  template<class OtherDerived> EIGEN_DEVICE_FUNC inline Scalar dot(const QuaternionBase<OtherDerived>& other) const { return coeffs().dot(other.coeffs()); }\n\n  template<class OtherDerived> EIGEN_DEVICE_FUNC Scalar angularDistance(const QuaternionBase<OtherDerived>& other) const;\n\n  /** \\returns an equivalent 3x3 rotation matrix */\n  EIGEN_DEVICE_FUNC inline Matrix3 toRotationMatrix() const;\n\n  /** \\returns the quaternion which transform \\a a into \\a b through a rotation */\n  template<typename Derived1, typename Derived2>\n  EIGEN_DEVICE_FUNC Derived& setFromTwoVectors(const MatrixBase<Derived1>& a, const MatrixBase<Derived2>& b);\n\n  template<class OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Quaternion<Scalar> operator* (const QuaternionBase<OtherDerived>& q) const;\n  template<class OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator*= (const QuaternionBase<OtherDerived>& q);\n\n  /** \\returns the quaternion describing the inverse rotation */\n  EIGEN_DEVICE_FUNC Quaternion<Scalar> inverse() const;\n\n  /** \\returns the conjugated quaternion */\n  EIGEN_DEVICE_FUNC Quaternion<Scalar> conjugate() const;\n\n  template<class OtherDerived> EIGEN_DEVICE_FUNC Quaternion<Scalar> slerp(const Scalar& t, const QuaternionBase<OtherDerived>& other) const;\n\n  /** \\returns true if each coefficients of \\c *this and \\a other are all exactly equal.\n    * \\warning When using floating point scalar values you probably should rather use a\n    *          fuzzy comparison such as isApprox()\n    * \\sa isApprox(), operator!= */\n  template<class OtherDerived>\n  EIGEN_DEVICE_FUNC inline bool operator==(const QuaternionBase<OtherDerived>& other) const\n  { return coeffs() == other.coeffs(); }\n\n  /** \\returns true if at least one pair of coefficients of \\c *this and \\a other are not exactly equal to each other.\n    * \\warning When using floating point scalar values you probably should rather use a\n    *          fuzzy comparison such as isApprox()\n    * \\sa isApprox(), operator== */\n  template<class OtherDerived>\n  EIGEN_DEVICE_FUNC inline bool operator!=(const QuaternionBase<OtherDerived>& other) const\n  { return coeffs() != other.coeffs(); }\n\n  /** \\returns \\c true if \\c *this is approximately equal to \\a other, within the precision\n    * determined by \\a prec.\n    *\n    * \\sa MatrixBase::isApprox() */\n  template<class OtherDerived>\n  EIGEN_DEVICE_FUNC bool isApprox(const QuaternionBase<OtherDerived>& other, const RealScalar& prec = NumTraits<Scalar>::dummy_precision()) const\n  { return coeffs().isApprox(other.coeffs(), prec); }\n\n  /** return the result vector of \\a v through the rotation*/\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Vector3 _transformVector(const Vector3& v) const;\n\n  #ifdef EIGEN_PARSED_BY_DOXYGEN\n  /** \\returns \\c *this with scalar type casted to \\a NewScalarType\n    *\n    * Note that if \\a NewScalarType is equal to the current scalar type of \\c *this\n    * then this function smartly returns a const reference to \\c *this.\n    */\n  template<typename NewScalarType>\n  EIGEN_DEVICE_FUNC inline typename internal::cast_return_type<Derived,Quaternion<NewScalarType> >::type cast() const;\n\n  #else\n\n  template<typename NewScalarType>\n  EIGEN_DEVICE_FUNC inline\n  typename internal::enable_if<internal::is_same<Scalar,NewScalarType>::value,const Derived&>::type cast() const\n  {\n    return derived();\n  }\n\n  template<typename NewScalarType>\n  EIGEN_DEVICE_FUNC inline\n  typename internal::enable_if<!internal::is_same<Scalar,NewScalarType>::value,Quaternion<NewScalarType> >::type cast() const\n  {\n    return Quaternion<NewScalarType>(coeffs().template cast<NewScalarType>());\n  }\n  #endif\n\n#ifndef EIGEN_NO_IO\n  friend std::ostream& operator<<(std::ostream& s, const QuaternionBase<Derived>& q) {\n    s << q.x() << \"i + \" << q.y() << \"j + \" << q.z() << \"k\" << \" + \" << q.w();\n    return s;\n  }\n#endif\n\n#ifdef EIGEN_QUATERNIONBASE_PLUGIN\n# include EIGEN_QUATERNIONBASE_PLUGIN\n#endif\nprotected:\n  EIGEN_DEFAULT_COPY_CONSTRUCTOR(QuaternionBase)\n  EIGEN_DEFAULT_EMPTY_CONSTRUCTOR_AND_DESTRUCTOR(QuaternionBase)\n};\n\n/***************************************************************************\n* Definition/implementation of Quaternion<Scalar>\n***************************************************************************/\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\class Quaternion\n  *\n  * \\brief The quaternion class used to represent 3D orientations and rotations\n  *\n  * \\tparam Scalar_ the scalar type, i.e., the type of the coefficients\n  * \\tparam Options_ controls the memory alignment of the coefficients. Can be \\# AutoAlign or \\# DontAlign. Default is AutoAlign.\n  *\n  * This class represents a quaternion \\f$ w+xi+yj+zk \\f$ that is a convenient representation of\n  * orientations and rotations of objects in three dimensions. Compared to other representations\n  * like Euler angles or 3x3 matrices, quaternions offer the following advantages:\n  * \\li \\b compact storage (4 scalars)\n  * \\li \\b efficient to compose (28 flops),\n  * \\li \\b stable spherical interpolation\n  *\n  * The following two typedefs are provided for convenience:\n  * \\li \\c Quaternionf for \\c float\n  * \\li \\c Quaterniond for \\c double\n  *\n  * \\warning Operations interpreting the quaternion as rotation have undefined behavior if the quaternion is not normalized.\n  *\n  * \\sa  class AngleAxis, class Transform\n  */\n\nnamespace internal {\ntemplate<typename Scalar_,int Options_>\nstruct traits<Quaternion<Scalar_,Options_> >\n{\n  typedef Quaternion<Scalar_,Options_> PlainObject;\n  typedef Scalar_ Scalar;\n  typedef Matrix<Scalar_,4,1,Options_> Coefficients;\n  enum{\n    Alignment = internal::traits<Coefficients>::Alignment,\n    Flags = LvalueBit\n  };\n};\n}\n\ntemplate<typename Scalar_, int Options_>\nclass Quaternion : public QuaternionBase<Quaternion<Scalar_,Options_> >\n{\npublic:\n  typedef QuaternionBase<Quaternion<Scalar_,Options_> > Base;\n  enum { NeedsAlignment = internal::traits<Quaternion>::Alignment>0 };\n\n  typedef Scalar_ Scalar;\n\n  EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Quaternion)\n  using Base::operator*=;\n\n  typedef typename internal::traits<Quaternion>::Coefficients Coefficients;\n  typedef typename Base::AngleAxisType AngleAxisType;\n\n  /** Default constructor leaving the quaternion uninitialized. */\n  EIGEN_DEVICE_FUNC inline Quaternion() {}\n\n  /** Constructs and initializes the quaternion \\f$ w+xi+yj+zk \\f$ from\n    * its four coefficients \\a w, \\a x, \\a y and \\a z.\n    *\n    * \\warning Note the order of the arguments: the real \\a w coefficient first,\n    * while internally the coefficients are stored in the following order:\n    * [\\c x, \\c y, \\c z, \\c w]\n    */\n  EIGEN_DEVICE_FUNC inline Quaternion(const Scalar& w, const Scalar& x, const Scalar& y, const Scalar& z) : m_coeffs(x, y, z, w){}\n\n  /** Constructs and initialize a quaternion from the array data */\n  EIGEN_DEVICE_FUNC explicit inline Quaternion(const Scalar* data) : m_coeffs(data) {}\n\n  /** Copy constructor */\n  template<class Derived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Quaternion(const QuaternionBase<Derived>& other) { this->Base::operator=(other); }\n\n  /** Constructs and initializes a quaternion from the angle-axis \\a aa */\n  EIGEN_DEVICE_FUNC explicit inline Quaternion(const AngleAxisType& aa) { *this = aa; }\n\n  /** Constructs and initializes a quaternion from either:\n    *  - a rotation matrix expression,\n    *  - a 4D vector expression representing quaternion coefficients.\n    */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC explicit inline Quaternion(const MatrixBase<Derived>& other) { *this = other; }\n\n  /** Explicit copy constructor with scalar conversion */\n  template<typename OtherScalar, int OtherOptions>\n  EIGEN_DEVICE_FUNC explicit inline Quaternion(const Quaternion<OtherScalar, OtherOptions>& other)\n  { m_coeffs = other.coeffs().template cast<Scalar>(); }\n\n#if EIGEN_HAS_RVALUE_REFERENCES\n  // We define a copy constructor, which means we don't get an implicit move constructor or assignment operator.\n  /** Default move constructor */\n  EIGEN_DEVICE_FUNC inline Quaternion(Quaternion&& other) EIGEN_NOEXCEPT_IF(std::is_nothrow_move_constructible<Scalar>::value)\n    : m_coeffs(std::move(other.coeffs()))\n  {}\n\n  /** Default move assignment operator */\n  EIGEN_DEVICE_FUNC Quaternion& operator=(Quaternion&& other) EIGEN_NOEXCEPT_IF(std::is_nothrow_move_assignable<Scalar>::value)\n  {\n    m_coeffs = std::move(other.coeffs());\n    return *this;\n  }\n#endif\n\n  EIGEN_DEVICE_FUNC static Quaternion UnitRandom();\n\n  template<typename Derived1, typename Derived2>\n  EIGEN_DEVICE_FUNC static Quaternion FromTwoVectors(const MatrixBase<Derived1>& a, const MatrixBase<Derived2>& b);\n\n  EIGEN_DEVICE_FUNC inline Coefficients& coeffs() { return m_coeffs;}\n  EIGEN_DEVICE_FUNC inline const Coefficients& coeffs() const { return m_coeffs;}\n\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(bool(NeedsAlignment))\n  \n#ifdef EIGEN_QUATERNION_PLUGIN\n# include EIGEN_QUATERNION_PLUGIN\n#endif\n\nprotected:\n  Coefficients m_coeffs;\n  \n#ifndef EIGEN_PARSED_BY_DOXYGEN\n    static EIGEN_STRONG_INLINE void _check_template_params()\n    {\n      EIGEN_STATIC_ASSERT( (Options_ & DontAlign) == Options_,\n        INVALID_MATRIX_TEMPLATE_PARAMETERS)\n    }\n#endif\n};\n\n/** \\ingroup Geometry_Module\n  * single precision quaternion type */\ntypedef Quaternion<float> Quaternionf;\n/** \\ingroup Geometry_Module\n  * double precision quaternion type */\ntypedef Quaternion<double> Quaterniond;\n\n/***************************************************************************\n* Specialization of Map<Quaternion<Scalar>>\n***************************************************************************/\n\nnamespace internal {\n  template<typename Scalar_, int Options_>\n  struct traits<Map<Quaternion<Scalar_>, Options_> > : traits<Quaternion<Scalar_, (int(Options_)&Aligned)==Aligned ? AutoAlign : DontAlign> >\n  {\n    typedef Map<Matrix<Scalar_,4,1>, Options_> Coefficients;\n  };\n}\n\nnamespace internal {\n  template<typename Scalar_, int Options_>\n  struct traits<Map<const Quaternion<Scalar_>, Options_> > : traits<Quaternion<Scalar_, (int(Options_)&Aligned)==Aligned ? AutoAlign : DontAlign> >\n  {\n    typedef Map<const Matrix<Scalar_,4,1>, Options_> Coefficients;\n    typedef traits<Quaternion<Scalar_, (int(Options_)&Aligned)==Aligned ? AutoAlign : DontAlign> > TraitsBase;\n    enum {\n      Flags = TraitsBase::Flags & ~LvalueBit\n    };\n  };\n}\n\n/** \\ingroup Geometry_Module\n  * \\brief Quaternion expression mapping a constant memory buffer\n  *\n  * \\tparam Scalar_ the type of the Quaternion coefficients\n  * \\tparam Options_ see class Map\n  *\n  * This is a specialization of class Map for Quaternion. This class allows to view\n  * a 4 scalar memory buffer as an Eigen's Quaternion object.\n  *\n  * \\sa class Map, class Quaternion, class QuaternionBase\n  */\ntemplate<typename Scalar_, int Options_>\nclass Map<const Quaternion<Scalar_>, Options_ >\n  : public QuaternionBase<Map<const Quaternion<Scalar_>, Options_> >\n{\n  public:\n    typedef QuaternionBase<Map<const Quaternion<Scalar_>, Options_> > Base;\n\n    typedef Scalar_ Scalar;\n    typedef typename internal::traits<Map>::Coefficients Coefficients;\n    EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Map)\n    using Base::operator*=;\n\n    /** Constructs a Mapped Quaternion object from the pointer \\a coeffs\n      *\n      * The pointer \\a coeffs must reference the four coefficients of Quaternion in the following order:\n      * \\code *coeffs == {x, y, z, w} \\endcode\n      *\n      * If the template parameter Options_ is set to #Aligned, then the pointer coeffs must be aligned. */\n    EIGEN_DEVICE_FUNC explicit EIGEN_STRONG_INLINE Map(const Scalar* coeffs) : m_coeffs(coeffs) {}\n\n    EIGEN_DEVICE_FUNC inline const Coefficients& coeffs() const { return m_coeffs;}\n\n  protected:\n    const Coefficients m_coeffs;\n};\n\n/** \\ingroup Geometry_Module\n  * \\brief Expression of a quaternion from a memory buffer\n  *\n  * \\tparam Scalar_ the type of the Quaternion coefficients\n  * \\tparam Options_ see class Map\n  *\n  * This is a specialization of class Map for Quaternion. This class allows to view\n  * a 4 scalar memory buffer as an Eigen's  Quaternion object.\n  *\n  * \\sa class Map, class Quaternion, class QuaternionBase\n  */\ntemplate<typename Scalar_, int Options_>\nclass Map<Quaternion<Scalar_>, Options_ >\n  : public QuaternionBase<Map<Quaternion<Scalar_>, Options_> >\n{\n  public:\n    typedef QuaternionBase<Map<Quaternion<Scalar_>, Options_> > Base;\n\n    typedef Scalar_ Scalar;\n    typedef typename internal::traits<Map>::Coefficients Coefficients;\n    EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Map)\n    using Base::operator*=;\n\n    /** Constructs a Mapped Quaternion object from the pointer \\a coeffs\n      *\n      * The pointer \\a coeffs must reference the four coefficients of Quaternion in the following order:\n      * \\code *coeffs == {x, y, z, w} \\endcode\n      *\n      * If the template parameter Options_ is set to #Aligned, then the pointer coeffs must be aligned. */\n    EIGEN_DEVICE_FUNC explicit EIGEN_STRONG_INLINE Map(Scalar* coeffs) : m_coeffs(coeffs) {}\n\n    EIGEN_DEVICE_FUNC inline Coefficients& coeffs() { return m_coeffs; }\n    EIGEN_DEVICE_FUNC inline const Coefficients& coeffs() const { return m_coeffs; }\n\n  protected:\n    Coefficients m_coeffs;\n};\n\n/** \\ingroup Geometry_Module\n  * Map an unaligned array of single precision scalars as a quaternion */\ntypedef Map<Quaternion<float>, 0>         QuaternionMapf;\n/** \\ingroup Geometry_Module\n  * Map an unaligned array of double precision scalars as a quaternion */\ntypedef Map<Quaternion<double>, 0>        QuaternionMapd;\n/** \\ingroup Geometry_Module\n  * Map a 16-byte aligned array of single precision scalars as a quaternion */\ntypedef Map<Quaternion<float>, Aligned>   QuaternionMapAlignedf;\n/** \\ingroup Geometry_Module\n  * Map a 16-byte aligned array of double precision scalars as a quaternion */\ntypedef Map<Quaternion<double>, Aligned>  QuaternionMapAlignedd;\n\n/***************************************************************************\n* Implementation of QuaternionBase methods\n***************************************************************************/\n\n// Generic Quaternion * Quaternion product\n// This product can be specialized for a given architecture via the Arch template argument.\nnamespace internal {\ntemplate<int Arch, class Derived1, class Derived2, typename Scalar> struct quat_product\n{\n  EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Quaternion<Scalar> run(const QuaternionBase<Derived1>& a, const QuaternionBase<Derived2>& b){\n    return Quaternion<Scalar>\n    (\n      a.w() * b.w() - a.x() * b.x() - a.y() * b.y() - a.z() * b.z(),\n      a.w() * b.x() + a.x() * b.w() + a.y() * b.z() - a.z() * b.y(),\n      a.w() * b.y() + a.y() * b.w() + a.z() * b.x() - a.x() * b.z(),\n      a.w() * b.z() + a.z() * b.w() + a.x() * b.y() - a.y() * b.x()\n    );\n  }\n};\n}\n\n/** \\returns the concatenation of two rotations as a quaternion-quaternion product */\ntemplate <class Derived>\ntemplate <class OtherDerived>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Quaternion<typename internal::traits<Derived>::Scalar>\nQuaternionBase<Derived>::operator* (const QuaternionBase<OtherDerived>& other) const\n{\n  EIGEN_STATIC_ASSERT((internal::is_same<typename Derived::Scalar, typename OtherDerived::Scalar>::value),\n   YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n  return internal::quat_product<Architecture::Target, Derived, OtherDerived,\n                         typename internal::traits<Derived>::Scalar>::run(*this, other);\n}\n\n/** \\sa operator*(Quaternion) */\ntemplate <class Derived>\ntemplate <class OtherDerived>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& QuaternionBase<Derived>::operator*= (const QuaternionBase<OtherDerived>& other)\n{\n  derived() = derived() * other.derived();\n  return derived();\n}\n\n/** Rotation of a vector by a quaternion.\n  * \\remarks If the quaternion is used to rotate several points (>1)\n  * then it is much more efficient to first convert it to a 3x3 Matrix.\n  * Comparison of the operation cost for n transformations:\n  *   - Quaternion2:    30n\n  *   - Via a Matrix3: 24 + 15n\n  */\ntemplate <class Derived>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename QuaternionBase<Derived>::Vector3\nQuaternionBase<Derived>::_transformVector(const Vector3& v) const\n{\n    // Note that this algorithm comes from the optimization by hand\n    // of the conversion to a Matrix followed by a Matrix/Vector product.\n    // It appears to be much faster than the common algorithm found\n    // in the literature (30 versus 39 flops). It also requires two\n    // Vector3 as temporaries.\n    Vector3 uv = this->vec().cross(v);\n    uv += uv;\n    return v + this->w() * uv + this->vec().cross(uv);\n}\n\ntemplate<class Derived>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE QuaternionBase<Derived>& QuaternionBase<Derived>::operator=(const QuaternionBase<Derived>& other)\n{\n  coeffs() = other.coeffs();\n  return derived();\n}\n\ntemplate<class Derived>\ntemplate<class OtherDerived>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& QuaternionBase<Derived>::operator=(const QuaternionBase<OtherDerived>& other)\n{\n  coeffs() = other.coeffs();\n  return derived();\n}\n\n/** Set \\c *this from an angle-axis \\a aa and returns a reference to \\c *this\n  */\ntemplate<class Derived>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& QuaternionBase<Derived>::operator=(const AngleAxisType& aa)\n{\n  EIGEN_USING_STD(cos)\n  EIGEN_USING_STD(sin)\n  Scalar ha = Scalar(0.5)*aa.angle(); // Scalar(0.5) to suppress precision loss warnings\n  this->w() = cos(ha);\n  this->vec() = sin(ha) * aa.axis();\n  return derived();\n}\n\n/** Set \\c *this from the expression \\a xpr:\n  *   - if \\a xpr is a 4x1 vector, then \\a xpr is assumed to be a quaternion\n  *   - if \\a xpr is a 3x3 matrix, then \\a xpr is assumed to be rotation matrix\n  *     and \\a xpr is converted to a quaternion\n  */\n\ntemplate<class Derived>\ntemplate<class MatrixDerived>\nEIGEN_DEVICE_FUNC inline Derived& QuaternionBase<Derived>::operator=(const MatrixBase<MatrixDerived>& xpr)\n{\n  EIGEN_STATIC_ASSERT((internal::is_same<typename Derived::Scalar, typename MatrixDerived::Scalar>::value),\n   YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n  internal::quaternionbase_assign_impl<MatrixDerived>::run(*this, xpr.derived());\n  return derived();\n}\n\n/** Convert the quaternion to a 3x3 rotation matrix. The quaternion is required to\n  * be normalized, otherwise the result is undefined.\n  */\ntemplate<class Derived>\nEIGEN_DEVICE_FUNC inline typename QuaternionBase<Derived>::Matrix3\nQuaternionBase<Derived>::toRotationMatrix(void) const\n{\n  // NOTE if inlined, then gcc 4.2 and 4.4 get rid of the temporary (not gcc 4.3 !!)\n  // if not inlined then the cost of the return by value is huge ~ +35%,\n  // however, not inlining this function is an order of magnitude slower, so\n  // it has to be inlined, and so the return by value is not an issue\n  Matrix3 res;\n\n  const Scalar tx  = Scalar(2)*this->x();\n  const Scalar ty  = Scalar(2)*this->y();\n  const Scalar tz  = Scalar(2)*this->z();\n  const Scalar twx = tx*this->w();\n  const Scalar twy = ty*this->w();\n  const Scalar twz = tz*this->w();\n  const Scalar txx = tx*this->x();\n  const Scalar txy = ty*this->x();\n  const Scalar txz = tz*this->x();\n  const Scalar tyy = ty*this->y();\n  const Scalar tyz = tz*this->y();\n  const Scalar tzz = tz*this->z();\n\n  res.coeffRef(0,0) = Scalar(1)-(tyy+tzz);\n  res.coeffRef(0,1) = txy-twz;\n  res.coeffRef(0,2) = txz+twy;\n  res.coeffRef(1,0) = txy+twz;\n  res.coeffRef(1,1) = Scalar(1)-(txx+tzz);\n  res.coeffRef(1,2) = tyz-twx;\n  res.coeffRef(2,0) = txz-twy;\n  res.coeffRef(2,1) = tyz+twx;\n  res.coeffRef(2,2) = Scalar(1)-(txx+tyy);\n\n  return res;\n}\n\n/** Sets \\c *this to be a quaternion representing a rotation between\n  * the two arbitrary vectors \\a a and \\a b. In other words, the built\n  * rotation represent a rotation sending the line of direction \\a a\n  * to the line of direction \\a b, both lines passing through the origin.\n  *\n  * \\returns a reference to \\c *this.\n  *\n  * Note that the two input vectors do \\b not have to be normalized, and\n  * do not need to have the same norm.\n  */\ntemplate<class Derived>\ntemplate<typename Derived1, typename Derived2>\nEIGEN_DEVICE_FUNC inline Derived& QuaternionBase<Derived>::setFromTwoVectors(const MatrixBase<Derived1>& a, const MatrixBase<Derived2>& b)\n{\n  EIGEN_USING_STD(sqrt)\n  Vector3 v0 = a.normalized();\n  Vector3 v1 = b.normalized();\n  Scalar c = v1.dot(v0);\n\n  // if dot == -1, vectors are nearly opposites\n  // => accurately compute the rotation axis by computing the\n  //    intersection of the two planes. This is done by solving:\n  //       x^T v0 = 0\n  //       x^T v1 = 0\n  //    under the constraint:\n  //       ||x|| = 1\n  //    which yields a singular value problem\n  if (c < Scalar(-1)+NumTraits<Scalar>::dummy_precision())\n  {\n    c = numext::maxi(c,Scalar(-1));\n    Matrix<Scalar,2,3> m; m << v0.transpose(), v1.transpose();\n    JacobiSVD<Matrix<Scalar,2,3> > svd(m, ComputeFullV);\n    Vector3 axis = svd.matrixV().col(2);\n\n    Scalar w2 = (Scalar(1)+c)*Scalar(0.5);\n    this->w() = sqrt(w2);\n    this->vec() = axis * sqrt(Scalar(1) - w2);\n    return derived();\n  }\n  Vector3 axis = v0.cross(v1);\n  Scalar s = sqrt((Scalar(1)+c)*Scalar(2));\n  Scalar invs = Scalar(1)/s;\n  this->vec() = axis * invs;\n  this->w() = s * Scalar(0.5);\n\n  return derived();\n}\n\n/** \\returns a random unit quaternion following a uniform distribution law on SO(3)\n  *\n  * \\note The implementation is based on http://planning.cs.uiuc.edu/node198.html\n  */\ntemplate<typename Scalar, int Options>\nEIGEN_DEVICE_FUNC Quaternion<Scalar,Options> Quaternion<Scalar,Options>::UnitRandom()\n{\n  EIGEN_USING_STD(sqrt)\n  EIGEN_USING_STD(sin)\n  EIGEN_USING_STD(cos)\n  const Scalar u1 = internal::random<Scalar>(0, 1),\n               u2 = internal::random<Scalar>(0, 2*EIGEN_PI),\n               u3 = internal::random<Scalar>(0, 2*EIGEN_PI);\n  const Scalar a = sqrt(Scalar(1) - u1),\n               b = sqrt(u1);\n  return Quaternion (a * sin(u2), a * cos(u2), b * sin(u3), b * cos(u3));\n}\n\n\n/** Returns a quaternion representing a rotation between\n  * the two arbitrary vectors \\a a and \\a b. In other words, the built\n  * rotation represent a rotation sending the line of direction \\a a\n  * to the line of direction \\a b, both lines passing through the origin.\n  *\n  * \\returns resulting quaternion\n  *\n  * Note that the two input vectors do \\b not have to be normalized, and\n  * do not need to have the same norm.\n  */\ntemplate<typename Scalar, int Options>\ntemplate<typename Derived1, typename Derived2>\nEIGEN_DEVICE_FUNC Quaternion<Scalar,Options> Quaternion<Scalar,Options>::FromTwoVectors(const MatrixBase<Derived1>& a, const MatrixBase<Derived2>& b)\n{\n    Quaternion quat;\n    quat.setFromTwoVectors(a, b);\n    return quat;\n}\n\n\n/** \\returns the multiplicative inverse of \\c *this\n  * Note that in most cases, i.e., if you simply want the opposite rotation,\n  * and/or the quaternion is normalized, then it is enough to use the conjugate.\n  *\n  * \\sa QuaternionBase::conjugate()\n  */\ntemplate <class Derived>\nEIGEN_DEVICE_FUNC inline Quaternion<typename internal::traits<Derived>::Scalar> QuaternionBase<Derived>::inverse() const\n{\n  // FIXME should this function be called multiplicativeInverse and conjugate() be called inverse() or opposite()  ??\n  Scalar n2 = this->squaredNorm();\n  if (n2 > Scalar(0))\n    return Quaternion<Scalar>(conjugate().coeffs() / n2);\n  else\n  {\n    // return an invalid result to flag the error\n    return Quaternion<Scalar>(Coefficients::Zero());\n  }\n}\n\n// Generic conjugate of a Quaternion\nnamespace internal {\ntemplate<int Arch, class Derived, typename Scalar> struct quat_conj\n{\n  EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Quaternion<Scalar> run(const QuaternionBase<Derived>& q){\n    return Quaternion<Scalar>(q.w(),-q.x(),-q.y(),-q.z());\n  }\n};\n}\n                         \n/** \\returns the conjugate of the \\c *this which is equal to the multiplicative inverse\n  * if the quaternion is normalized.\n  * The conjugate of a quaternion represents the opposite rotation.\n  *\n  * \\sa Quaternion2::inverse()\n  */\ntemplate <class Derived>\nEIGEN_DEVICE_FUNC inline Quaternion<typename internal::traits<Derived>::Scalar>\nQuaternionBase<Derived>::conjugate() const\n{\n  return internal::quat_conj<Architecture::Target, Derived,\n                         typename internal::traits<Derived>::Scalar>::run(*this);\n                         \n}\n\n/** \\returns the angle (in radian) between two rotations\n  * \\sa dot()\n  */\ntemplate <class Derived>\ntemplate <class OtherDerived>\nEIGEN_DEVICE_FUNC inline typename internal::traits<Derived>::Scalar\nQuaternionBase<Derived>::angularDistance(const QuaternionBase<OtherDerived>& other) const\n{\n  EIGEN_USING_STD(atan2)\n  Quaternion<Scalar> d = (*this) * other.conjugate();\n  return Scalar(2) * atan2( d.vec().norm(), numext::abs(d.w()) );\n}\n\n \n    \n/** \\returns the spherical linear interpolation between the two quaternions\n  * \\c *this and \\a other at the parameter \\a t in [0;1].\n  * \n  * This represents an interpolation for a constant motion between \\c *this and \\a other,\n  * see also http://en.wikipedia.org/wiki/Slerp.\n  */\ntemplate <class Derived>\ntemplate <class OtherDerived>\nEIGEN_DEVICE_FUNC Quaternion<typename internal::traits<Derived>::Scalar>\nQuaternionBase<Derived>::slerp(const Scalar& t, const QuaternionBase<OtherDerived>& other) const\n{\n  EIGEN_USING_STD(acos)\n  EIGEN_USING_STD(sin)\n  const Scalar one = Scalar(1) - NumTraits<Scalar>::epsilon();\n  Scalar d = this->dot(other);\n  Scalar absD = numext::abs(d);\n\n  Scalar scale0;\n  Scalar scale1;\n\n  if(absD>=one)\n  {\n    scale0 = Scalar(1) - t;\n    scale1 = t;\n  }\n  else\n  {\n    // theta is the angle between the 2 quaternions\n    Scalar theta = acos(absD);\n    Scalar sinTheta = sin(theta);\n\n    scale0 = sin( ( Scalar(1) - t ) * theta) / sinTheta;\n    scale1 = sin( ( t * theta) ) / sinTheta;\n  }\n  if(d<Scalar(0)) scale1 = -scale1;\n\n  return Quaternion<Scalar>(scale0 * coeffs() + scale1 * other.coeffs());\n}\n\nnamespace internal {\n\n// set from a rotation matrix\ntemplate<typename Other>\nstruct quaternionbase_assign_impl<Other,3,3>\n{\n  typedef typename Other::Scalar Scalar;\n  template<class Derived> EIGEN_DEVICE_FUNC static inline void run(QuaternionBase<Derived>& q, const Other& a_mat)\n  {\n    const typename internal::nested_eval<Other,2>::type mat(a_mat);\n    EIGEN_USING_STD(sqrt)\n    // This algorithm comes from  \"Quaternion Calculus and Fast Animation\",\n    // Ken Shoemake, 1987 SIGGRAPH course notes\n    Scalar t = mat.trace();\n    if (t > Scalar(0))\n    {\n      t = sqrt(t + Scalar(1.0));\n      q.w() = Scalar(0.5)*t;\n      t = Scalar(0.5)/t;\n      q.x() = (mat.coeff(2,1) - mat.coeff(1,2)) * t;\n      q.y() = (mat.coeff(0,2) - mat.coeff(2,0)) * t;\n      q.z() = (mat.coeff(1,0) - mat.coeff(0,1)) * t;\n    }\n    else\n    {\n      Index i = 0;\n      if (mat.coeff(1,1) > mat.coeff(0,0))\n        i = 1;\n      if (mat.coeff(2,2) > mat.coeff(i,i))\n        i = 2;\n      Index j = (i+1)%3;\n      Index k = (j+1)%3;\n\n      t = sqrt(mat.coeff(i,i)-mat.coeff(j,j)-mat.coeff(k,k) + Scalar(1.0));\n      q.coeffs().coeffRef(i) = Scalar(0.5) * t;\n      t = Scalar(0.5)/t;\n      q.w() = (mat.coeff(k,j)-mat.coeff(j,k))*t;\n      q.coeffs().coeffRef(j) = (mat.coeff(j,i)+mat.coeff(i,j))*t;\n      q.coeffs().coeffRef(k) = (mat.coeff(k,i)+mat.coeff(i,k))*t;\n    }\n  }\n};\n\n// set from a vector of coefficients assumed to be a quaternion\ntemplate<typename Other>\nstruct quaternionbase_assign_impl<Other,4,1>\n{\n  typedef typename Other::Scalar Scalar;\n  template<class Derived> EIGEN_DEVICE_FUNC static inline void run(QuaternionBase<Derived>& q, const Other& vec)\n  {\n    q.coeffs() = vec;\n  }\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_QUATERNION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Geometry/Rotation2D.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ROTATION2D_H\n#define EIGEN_ROTATION2D_H\n\nnamespace Eigen { \n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\class Rotation2D\n  *\n  * \\brief Represents a rotation/orientation in a 2 dimensional space.\n  *\n  * \\tparam Scalar_ the scalar type, i.e., the type of the coefficients\n  *\n  * This class is equivalent to a single scalar representing a counter clock wise rotation\n  * as a single angle in radian. It provides some additional features such as the automatic\n  * conversion from/to a 2x2 rotation matrix. Moreover this class aims to provide a similar\n  * interface to Quaternion in order to facilitate the writing of generic algorithms\n  * dealing with rotations.\n  *\n  * \\sa class Quaternion, class Transform\n  */\n\nnamespace internal {\n\ntemplate<typename Scalar_> struct traits<Rotation2D<Scalar_> >\n{\n  typedef Scalar_ Scalar;\n};\n} // end namespace internal\n\ntemplate<typename Scalar_>\nclass Rotation2D : public RotationBase<Rotation2D<Scalar_>,2>\n{\n  typedef RotationBase<Rotation2D<Scalar_>,2> Base;\n\npublic:\n\n  using Base::operator*;\n\n  enum { Dim = 2 };\n  /** the scalar type of the coefficients */\n  typedef Scalar_ Scalar;\n  typedef Matrix<Scalar,2,1> Vector2;\n  typedef Matrix<Scalar,2,2> Matrix2;\n\nprotected:\n\n  Scalar m_angle;\n\npublic:\n\n  /** Construct a 2D counter clock wise rotation from the angle \\a a in radian. */\n  EIGEN_DEVICE_FUNC explicit inline Rotation2D(const Scalar& a) : m_angle(a) {}\n  \n  /** Default constructor wihtout initialization. The represented rotation is undefined. */\n  EIGEN_DEVICE_FUNC Rotation2D() {}\n\n  /** Construct a 2D rotation from a 2x2 rotation matrix \\a mat.\n    *\n    * \\sa fromRotationMatrix()\n    */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC explicit Rotation2D(const MatrixBase<Derived>& m)\n  {\n    fromRotationMatrix(m.derived());\n  }\n\n  /** \\returns the rotation angle */\n  EIGEN_DEVICE_FUNC inline Scalar angle() const { return m_angle; }\n\n  /** \\returns a read-write reference to the rotation angle */\n  EIGEN_DEVICE_FUNC inline Scalar& angle() { return m_angle; }\n  \n  /** \\returns the rotation angle in [0,2pi] */\n  EIGEN_DEVICE_FUNC inline Scalar smallestPositiveAngle() const {\n    Scalar tmp = numext::fmod(m_angle,Scalar(2*EIGEN_PI));\n    return tmp<Scalar(0) ? tmp + Scalar(2*EIGEN_PI) : tmp;\n  }\n  \n  /** \\returns the rotation angle in [-pi,pi] */\n  EIGEN_DEVICE_FUNC inline Scalar smallestAngle() const {\n    Scalar tmp = numext::fmod(m_angle,Scalar(2*EIGEN_PI));\n    if(tmp>Scalar(EIGEN_PI))       tmp -= Scalar(2*EIGEN_PI);\n    else if(tmp<-Scalar(EIGEN_PI)) tmp += Scalar(2*EIGEN_PI);\n    return tmp;\n  }\n\n  /** \\returns the inverse rotation */\n  EIGEN_DEVICE_FUNC inline Rotation2D inverse() const { return Rotation2D(-m_angle); }\n\n  /** Concatenates two rotations */\n  EIGEN_DEVICE_FUNC inline Rotation2D operator*(const Rotation2D& other) const\n  { return Rotation2D(m_angle + other.m_angle); }\n\n  /** Concatenates two rotations */\n  EIGEN_DEVICE_FUNC inline Rotation2D& operator*=(const Rotation2D& other)\n  { m_angle += other.m_angle; return *this; }\n\n  /** Applies the rotation to a 2D vector */\n  EIGEN_DEVICE_FUNC Vector2 operator* (const Vector2& vec) const\n  { return toRotationMatrix() * vec; }\n  \n  template<typename Derived>\n  EIGEN_DEVICE_FUNC Rotation2D& fromRotationMatrix(const MatrixBase<Derived>& m);\n  EIGEN_DEVICE_FUNC Matrix2 toRotationMatrix() const;\n\n  /** Set \\c *this from a 2x2 rotation matrix \\a mat.\n    * In other words, this function extract the rotation angle from the rotation matrix.\n    *\n    * This method is an alias for fromRotationMatrix()\n    *\n    * \\sa fromRotationMatrix()\n    */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC Rotation2D& operator=(const  MatrixBase<Derived>& m)\n  { return fromRotationMatrix(m.derived()); }\n\n  /** \\returns the spherical interpolation between \\c *this and \\a other using\n    * parameter \\a t. It is in fact equivalent to a linear interpolation.\n    */\n  EIGEN_DEVICE_FUNC inline Rotation2D slerp(const Scalar& t, const Rotation2D& other) const\n  {\n    Scalar dist = Rotation2D(other.m_angle-m_angle).smallestAngle();\n    return Rotation2D(m_angle + dist*t);\n  }\n\n  /** \\returns \\c *this with scalar type casted to \\a NewScalarType\n    *\n    * Note that if \\a NewScalarType is equal to the current scalar type of \\c *this\n    * then this function smartly returns a const reference to \\c *this.\n    */\n  template<typename NewScalarType>\n  EIGEN_DEVICE_FUNC inline typename internal::cast_return_type<Rotation2D,Rotation2D<NewScalarType> >::type cast() const\n  { return typename internal::cast_return_type<Rotation2D,Rotation2D<NewScalarType> >::type(*this); }\n\n  /** Copy constructor with scalar type conversion */\n  template<typename OtherScalarType>\n  EIGEN_DEVICE_FUNC inline explicit Rotation2D(const Rotation2D<OtherScalarType>& other)\n  {\n    m_angle = Scalar(other.angle());\n  }\n\n  EIGEN_DEVICE_FUNC static inline Rotation2D Identity() { return Rotation2D(0); }\n\n  /** \\returns \\c true if \\c *this is approximately equal to \\a other, within the precision\n    * determined by \\a prec.\n    *\n    * \\sa MatrixBase::isApprox() */\n  EIGEN_DEVICE_FUNC bool isApprox(const Rotation2D& other, const typename NumTraits<Scalar>::Real& prec = NumTraits<Scalar>::dummy_precision()) const\n  { return internal::isApprox(m_angle,other.m_angle, prec); }\n  \n};\n\n/** \\ingroup Geometry_Module\n  * single precision 2D rotation type */\ntypedef Rotation2D<float> Rotation2Df;\n/** \\ingroup Geometry_Module\n  * double precision 2D rotation type */\ntypedef Rotation2D<double> Rotation2Dd;\n\n/** Set \\c *this from a 2x2 rotation matrix \\a mat.\n  * In other words, this function extract the rotation angle\n  * from the rotation matrix.\n  */\ntemplate<typename Scalar>\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC Rotation2D<Scalar>& Rotation2D<Scalar>::fromRotationMatrix(const MatrixBase<Derived>& mat)\n{\n  EIGEN_USING_STD(atan2)\n  EIGEN_STATIC_ASSERT(Derived::RowsAtCompileTime==2 && Derived::ColsAtCompileTime==2,YOU_MADE_A_PROGRAMMING_MISTAKE)\n  m_angle = atan2(mat.coeff(1,0), mat.coeff(0,0));\n  return *this;\n}\n\n/** Constructs and \\returns an equivalent 2x2 rotation matrix.\n  */\ntemplate<typename Scalar>\ntypename Rotation2D<Scalar>::Matrix2\nEIGEN_DEVICE_FUNC Rotation2D<Scalar>::toRotationMatrix(void) const\n{\n  EIGEN_USING_STD(sin)\n  EIGEN_USING_STD(cos)\n  Scalar sinA = sin(m_angle);\n  Scalar cosA = cos(m_angle);\n  return (Matrix2() << cosA, -sinA, sinA, cosA).finished();\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_ROTATION2D_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Geometry/RotationBase.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ROTATIONBASE_H\n#define EIGEN_ROTATIONBASE_H\n\nnamespace Eigen { \n\n// forward declaration\nnamespace internal {\ntemplate<typename RotationDerived, typename MatrixType, bool IsVector=MatrixType::IsVectorAtCompileTime>\nstruct rotation_base_generic_product_selector;\n}\n\n/** \\class RotationBase\n  *\n  * \\brief Common base class for compact rotation representations\n  *\n  * \\tparam Derived is the derived type, i.e., a rotation type\n  * \\tparam Dim_ the dimension of the space\n  */\ntemplate<typename Derived, int Dim_>\nclass RotationBase\n{\n  public:\n    enum { Dim = Dim_ };\n    /** the scalar type of the coefficients */\n    typedef typename internal::traits<Derived>::Scalar Scalar;\n\n    /** corresponding linear transformation matrix type */\n    typedef Matrix<Scalar,Dim,Dim> RotationMatrixType;\n    typedef Matrix<Scalar,Dim,1> VectorType;\n\n  public:\n    EIGEN_DEVICE_FUNC inline const Derived& derived() const { return *static_cast<const Derived*>(this); }\n    EIGEN_DEVICE_FUNC inline Derived& derived() { return *static_cast<Derived*>(this); }\n\n    /** \\returns an equivalent rotation matrix */\n    EIGEN_DEVICE_FUNC inline RotationMatrixType toRotationMatrix() const { return derived().toRotationMatrix(); }\n\n    /** \\returns an equivalent rotation matrix \n      * This function is added to be conform with the Transform class' naming scheme.\n      */\n    EIGEN_DEVICE_FUNC inline RotationMatrixType matrix() const { return derived().toRotationMatrix(); }\n\n    /** \\returns the inverse rotation */\n    EIGEN_DEVICE_FUNC inline Derived inverse() const { return derived().inverse(); }\n\n    /** \\returns the concatenation of the rotation \\c *this with a translation \\a t */\n    EIGEN_DEVICE_FUNC inline Transform<Scalar,Dim,Isometry> operator*(const Translation<Scalar,Dim>& t) const\n    { return Transform<Scalar,Dim,Isometry>(*this) * t; }\n\n    /** \\returns the concatenation of the rotation \\c *this with a uniform scaling \\a s */\n    EIGEN_DEVICE_FUNC inline RotationMatrixType operator*(const UniformScaling<Scalar>& s) const\n    { return toRotationMatrix() * s.factor(); }\n\n    /** \\returns the concatenation of the rotation \\c *this with a generic expression \\a e\n      * \\a e can be:\n      *  - a DimxDim linear transformation matrix\n      *  - a DimxDim diagonal matrix (axis aligned scaling)\n      *  - a vector of size Dim\n      */\n    template<typename OtherDerived>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename internal::rotation_base_generic_product_selector<Derived,OtherDerived,OtherDerived::IsVectorAtCompileTime>::ReturnType\n    operator*(const EigenBase<OtherDerived>& e) const\n    { return internal::rotation_base_generic_product_selector<Derived,OtherDerived>::run(derived(), e.derived()); }\n\n    /** \\returns the concatenation of a linear transformation \\a l with the rotation \\a r */\n    template<typename OtherDerived> friend\n    EIGEN_DEVICE_FUNC inline RotationMatrixType operator*(const EigenBase<OtherDerived>& l, const Derived& r)\n    { return l.derived() * r.toRotationMatrix(); }\n\n    /** \\returns the concatenation of a scaling \\a l with the rotation \\a r */\n    EIGEN_DEVICE_FUNC friend inline Transform<Scalar,Dim,Affine> operator*(const DiagonalMatrix<Scalar,Dim>& l, const Derived& r)\n    { \n      Transform<Scalar,Dim,Affine> res(r);\n      res.linear().applyOnTheLeft(l);\n      return res;\n    }\n\n    /** \\returns the concatenation of the rotation \\c *this with a transformation \\a t */\n    template<int Mode, int Options>\n    EIGEN_DEVICE_FUNC inline Transform<Scalar,Dim,Mode> operator*(const Transform<Scalar,Dim,Mode,Options>& t) const\n    { return toRotationMatrix() * t; }\n\n    template<typename OtherVectorType>\n    EIGEN_DEVICE_FUNC inline VectorType _transformVector(const OtherVectorType& v) const\n    { return toRotationMatrix() * v; }\n};\n\nnamespace internal {\n\n// implementation of the generic product rotation * matrix\ntemplate<typename RotationDerived, typename MatrixType>\nstruct rotation_base_generic_product_selector<RotationDerived,MatrixType,false>\n{\n  enum { Dim = RotationDerived::Dim };\n  typedef Matrix<typename RotationDerived::Scalar,Dim,Dim> ReturnType;\n  EIGEN_DEVICE_FUNC static inline ReturnType run(const RotationDerived& r, const MatrixType& m)\n  { return r.toRotationMatrix() * m; }\n};\n\ntemplate<typename RotationDerived, typename Scalar, int Dim, int MaxDim>\nstruct rotation_base_generic_product_selector< RotationDerived, DiagonalMatrix<Scalar,Dim,MaxDim>, false >\n{\n  typedef Transform<Scalar,Dim,Affine> ReturnType;\n  EIGEN_DEVICE_FUNC static inline ReturnType run(const RotationDerived& r, const DiagonalMatrix<Scalar,Dim,MaxDim>& m)\n  {\n    ReturnType res(r);\n    res.linear() *= m;\n    return res;\n  }\n};\n\ntemplate<typename RotationDerived,typename OtherVectorType>\nstruct rotation_base_generic_product_selector<RotationDerived,OtherVectorType,true>\n{\n  enum { Dim = RotationDerived::Dim };\n  typedef Matrix<typename RotationDerived::Scalar,Dim,1> ReturnType;\n  EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE ReturnType run(const RotationDerived& r, const OtherVectorType& v)\n  {\n    return r._transformVector(v);\n  }\n};\n\n} // end namespace internal\n\n/** \\geometry_module\n  *\n  * \\brief Constructs a Dim x Dim rotation matrix from the rotation \\a r\n  */\ntemplate<typename Scalar_, int Rows_, int Cols_, int _Storage, int MaxRows_, int MaxCols_>\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC Matrix<Scalar_, Rows_, Cols_, _Storage, MaxRows_, MaxCols_>\n::Matrix(const RotationBase<OtherDerived,ColsAtCompileTime>& r)\n{\n  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix,int(OtherDerived::Dim),int(OtherDerived::Dim))\n  *this = r.toRotationMatrix();\n}\n\n/** \\geometry_module\n  *\n  * \\brief Set a Dim x Dim rotation matrix from the rotation \\a r\n  */\ntemplate<typename Scalar_, int Rows_, int Cols_, int _Storage, int MaxRows_, int MaxCols_>\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC Matrix<Scalar_, Rows_, Cols_, _Storage, MaxRows_, MaxCols_>&\nMatrix<Scalar_, Rows_, Cols_, _Storage, MaxRows_, MaxCols_>\n::operator=(const RotationBase<OtherDerived,ColsAtCompileTime>& r)\n{\n  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix,int(OtherDerived::Dim),int(OtherDerived::Dim))\n  return *this = r.toRotationMatrix();\n}\n\nnamespace internal {\n\n/** \\internal\n  *\n  * Helper function to return an arbitrary rotation object to a rotation matrix.\n  *\n  * \\tparam Scalar the numeric type of the matrix coefficients\n  * \\tparam Dim the dimension of the current space\n  *\n  * It returns a Dim x Dim fixed size matrix.\n  *\n  * Default specializations are provided for:\n  *   - any scalar type (2D),\n  *   - any matrix expression,\n  *   - any type based on RotationBase (e.g., Quaternion, AngleAxis, Rotation2D)\n  *\n  * Currently toRotationMatrix is only used by Transform.\n  *\n  * \\sa class Transform, class Rotation2D, class Quaternion, class AngleAxis\n  */\ntemplate<typename Scalar, int Dim>\nEIGEN_DEVICE_FUNC static inline Matrix<Scalar,2,2> toRotationMatrix(const Scalar& s)\n{\n  EIGEN_STATIC_ASSERT(Dim==2,YOU_MADE_A_PROGRAMMING_MISTAKE)\n  return Rotation2D<Scalar>(s).toRotationMatrix();\n}\n\ntemplate<typename Scalar, int Dim, typename OtherDerived>\nEIGEN_DEVICE_FUNC static inline Matrix<Scalar,Dim,Dim> toRotationMatrix(const RotationBase<OtherDerived,Dim>& r)\n{\n  return r.toRotationMatrix();\n}\n\ntemplate<typename Scalar, int Dim, typename OtherDerived>\nEIGEN_DEVICE_FUNC static inline const MatrixBase<OtherDerived>& toRotationMatrix(const MatrixBase<OtherDerived>& mat)\n{\n  EIGEN_STATIC_ASSERT(OtherDerived::RowsAtCompileTime==Dim && OtherDerived::ColsAtCompileTime==Dim,\n    YOU_MADE_A_PROGRAMMING_MISTAKE)\n  return mat;\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_ROTATIONBASE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Geometry/Scaling.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SCALING_H\n#define EIGEN_SCALING_H\n\nnamespace Eigen { \n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\class UniformScaling\n  *\n  * \\brief Represents a generic uniform scaling transformation\n  *\n  * \\tparam Scalar_ the scalar type, i.e., the type of the coefficients.\n  *\n  * This class represent a uniform scaling transformation. It is the return\n  * type of Scaling(Scalar), and most of the time this is the only way it\n  * is used. In particular, this class is not aimed to be used to store a scaling transformation,\n  * but rather to make easier the constructions and updates of Transform objects.\n  *\n  * To represent an axis aligned scaling, use the DiagonalMatrix class.\n  *\n  * \\sa Scaling(), class DiagonalMatrix, MatrixBase::asDiagonal(), class Translation, class Transform\n  */\n\nnamespace internal\n{\n  // This helper helps nvcc+MSVC to properly parse this file.\n  // See bug 1412.\n  template <typename Scalar, int Dim, int Mode>\n  struct uniformscaling_times_affine_returntype\n  {\n    enum\n    {\n      NewMode = int(Mode) == int(Isometry) ? Affine : Mode\n    };\n    typedef Transform <Scalar, Dim, NewMode> type;\n  };\n}\n\ntemplate<typename Scalar_>\nclass UniformScaling\n{\npublic:\n  /** the scalar type of the coefficients */\n  typedef Scalar_ Scalar;\n\nprotected:\n\n  Scalar m_factor;\n\npublic:\n\n  /** Default constructor without initialization. */\n  UniformScaling() {}\n  /** Constructs and initialize a uniform scaling transformation */\n  explicit inline UniformScaling(const Scalar& s) : m_factor(s) {}\n\n  inline const Scalar& factor() const { return m_factor; }\n  inline Scalar& factor() { return m_factor; }\n\n  /** Concatenates two uniform scaling */\n  inline UniformScaling operator* (const UniformScaling& other) const\n  { return UniformScaling(m_factor * other.factor()); }\n\n  /** Concatenates a uniform scaling and a translation */\n  template<int Dim>\n  inline Transform<Scalar,Dim,Affine> operator* (const Translation<Scalar,Dim>& t) const;\n\n  /** Concatenates a uniform scaling and an affine transformation */\n  template<int Dim, int Mode, int Options>\n  inline typename\n\tinternal::uniformscaling_times_affine_returntype<Scalar,Dim,Mode>::type\n\toperator* (const Transform<Scalar, Dim, Mode, Options>& t) const\n  {\n    typename internal::uniformscaling_times_affine_returntype<Scalar,Dim,Mode>::type res = t;\n    res.prescale(factor());\n    return res;\n  }\n\n  /** Concatenates a uniform scaling and a linear transformation matrix */\n  // TODO returns an expression\n  template<typename Derived>\n  inline typename Eigen::internal::plain_matrix_type<Derived>::type operator* (const MatrixBase<Derived>& other) const\n  { return other * m_factor; }\n\n  template<typename Derived,int Dim>\n  inline Matrix<Scalar,Dim,Dim> operator*(const RotationBase<Derived,Dim>& r) const\n  { return r.toRotationMatrix() * m_factor; }\n\n  /** \\returns the inverse scaling */\n  inline UniformScaling inverse() const\n  { return UniformScaling(Scalar(1)/m_factor); }\n\n  /** \\returns \\c *this with scalar type casted to \\a NewScalarType\n    *\n    * Note that if \\a NewScalarType is equal to the current scalar type of \\c *this\n    * then this function smartly returns a const reference to \\c *this.\n    */\n  template<typename NewScalarType>\n  inline UniformScaling<NewScalarType> cast() const\n  { return UniformScaling<NewScalarType>(NewScalarType(m_factor)); }\n\n  /** Copy constructor with scalar type conversion */\n  template<typename OtherScalarType>\n  inline explicit UniformScaling(const UniformScaling<OtherScalarType>& other)\n  { m_factor = Scalar(other.factor()); }\n\n  /** \\returns \\c true if \\c *this is approximately equal to \\a other, within the precision\n    * determined by \\a prec.\n    *\n    * \\sa MatrixBase::isApprox() */\n  bool isApprox(const UniformScaling& other, const typename NumTraits<Scalar>::Real& prec = NumTraits<Scalar>::dummy_precision()) const\n  { return internal::isApprox(m_factor, other.factor(), prec); }\n\n};\n\n/** \\addtogroup Geometry_Module */\n//@{\n\n/** Concatenates a linear transformation matrix and a uniform scaling\n  * \\relates UniformScaling\n  */\n// NOTE this operator is defined in MatrixBase and not as a friend function\n// of UniformScaling to fix an internal crash of Intel's ICC\ntemplate<typename Derived,typename Scalar>\nEIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(Derived,Scalar,product)\noperator*(const MatrixBase<Derived>& matrix, const UniformScaling<Scalar>& s)\n{ return matrix.derived() * s.factor(); }\n\n/** Constructs a uniform scaling from scale factor \\a s */\ninline UniformScaling<float> Scaling(float s) { return UniformScaling<float>(s); }\n/** Constructs a uniform scaling from scale factor \\a s */\ninline UniformScaling<double> Scaling(double s) { return UniformScaling<double>(s); }\n/** Constructs a uniform scaling from scale factor \\a s */\ntemplate<typename RealScalar>\ninline UniformScaling<std::complex<RealScalar> > Scaling(const std::complex<RealScalar>& s)\n{ return UniformScaling<std::complex<RealScalar> >(s); }\n\n/** Constructs a 2D axis aligned scaling */\ntemplate<typename Scalar>\ninline DiagonalMatrix<Scalar,2> Scaling(const Scalar& sx, const Scalar& sy)\n{ return DiagonalMatrix<Scalar,2>(sx, sy); }\n/** Constructs a 3D axis aligned scaling */\ntemplate<typename Scalar>\ninline DiagonalMatrix<Scalar,3> Scaling(const Scalar& sx, const Scalar& sy, const Scalar& sz)\n{ return DiagonalMatrix<Scalar,3>(sx, sy, sz); }\n\n/** Constructs an axis aligned scaling expression from vector expression \\a coeffs\n  * This is an alias for coeffs.asDiagonal()\n  */\ntemplate<typename Derived>\ninline const DiagonalWrapper<const Derived> Scaling(const MatrixBase<Derived>& coeffs)\n{ return coeffs.asDiagonal(); }\n\n/** \\deprecated */\ntypedef DiagonalMatrix<float, 2> AlignedScaling2f;\n/** \\deprecated */\ntypedef DiagonalMatrix<double,2> AlignedScaling2d;\n/** \\deprecated */\ntypedef DiagonalMatrix<float, 3> AlignedScaling3f;\n/** \\deprecated */\ntypedef DiagonalMatrix<double,3> AlignedScaling3d;\n//@}\n\ntemplate<typename Scalar>\ntemplate<int Dim>\ninline Transform<Scalar,Dim,Affine>\nUniformScaling<Scalar>::operator* (const Translation<Scalar,Dim>& t) const\n{\n  Transform<Scalar,Dim,Affine> res;\n  res.matrix().setZero();\n  res.linear().diagonal().fill(factor());\n  res.translation() = factor() * t.vector();\n  res(Dim,Dim) = Scalar(1);\n  return res;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SCALING_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Geometry/Transform.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2010 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_TRANSFORM_H\n#define EIGEN_TRANSFORM_H\n\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate<typename Transform>\nstruct transform_traits\n{\n  enum\n  {\n    Dim = Transform::Dim,\n    HDim = Transform::HDim,\n    Mode = Transform::Mode,\n    IsProjective = (int(Mode)==int(Projective))\n  };\n};\n\ntemplate< typename TransformType,\n          typename MatrixType,\n          int Case = transform_traits<TransformType>::IsProjective ? 0\n                   : int(MatrixType::RowsAtCompileTime) == int(transform_traits<TransformType>::HDim) ? 1\n                   : 2,\n          int RhsCols = MatrixType::ColsAtCompileTime>\nstruct transform_right_product_impl;\n\ntemplate< typename Other,\n          int Mode,\n          int Options,\n          int Dim,\n          int HDim,\n          int OtherRows=Other::RowsAtCompileTime,\n          int OtherCols=Other::ColsAtCompileTime>\nstruct transform_left_product_impl;\n\ntemplate< typename Lhs,\n          typename Rhs,\n          bool AnyProjective =\n            transform_traits<Lhs>::IsProjective ||\n            transform_traits<Rhs>::IsProjective>\nstruct transform_transform_product_impl;\n\ntemplate< typename Other,\n          int Mode,\n          int Options,\n          int Dim,\n          int HDim,\n          int OtherRows=Other::RowsAtCompileTime,\n          int OtherCols=Other::ColsAtCompileTime>\nstruct transform_construct_from_matrix;\n\ntemplate<typename TransformType> struct transform_take_affine_part;\n\ntemplate<typename Scalar_, int Dim_, int _Mode, int Options_>\nstruct traits<Transform<Scalar_,Dim_,_Mode,Options_> >\n{\n  typedef Scalar_ Scalar;\n  typedef Eigen::Index StorageIndex;\n  typedef Dense StorageKind;\n  enum {\n    Dim1 = Dim_==Dynamic ? Dim_ : Dim_ + 1,\n    RowsAtCompileTime = _Mode==Projective ? Dim1 : Dim_,\n    ColsAtCompileTime = Dim1,\n    MaxRowsAtCompileTime = RowsAtCompileTime,\n    MaxColsAtCompileTime = ColsAtCompileTime,\n    Flags = 0\n  };\n};\n\ntemplate<int Mode> struct transform_make_affine;\n\n} // end namespace internal\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\class Transform\n  *\n  * \\brief Represents an homogeneous transformation in a N dimensional space\n  *\n  * \\tparam Scalar_ the scalar type, i.e., the type of the coefficients\n  * \\tparam Dim_ the dimension of the space\n  * \\tparam _Mode the type of the transformation. Can be:\n  *              - #Affine: the transformation is stored as a (Dim+1)^2 matrix,\n  *                         where the last row is assumed to be [0 ... 0 1].\n  *              - #AffineCompact: the transformation is stored as a (Dim)x(Dim+1) matrix.\n  *              - #Projective: the transformation is stored as a (Dim+1)^2 matrix\n  *                             without any assumption.\n  *              - #Isometry: same as #Affine with the additional assumption that\n  *                           the linear part represents a rotation. This assumption is exploited\n  *                           to speed up some functions such as inverse() and rotation().\n  * \\tparam Options_ has the same meaning as in class Matrix. It allows to specify DontAlign and/or RowMajor.\n  *                  These Options are passed directly to the underlying matrix type.\n  *\n  * The homography is internally represented and stored by a matrix which\n  * is available through the matrix() method. To understand the behavior of\n  * this class you have to think a Transform object as its internal\n  * matrix representation. The chosen convention is right multiply:\n  *\n  * \\code v' = T * v \\endcode\n  *\n  * Therefore, an affine transformation matrix M is shaped like this:\n  *\n  * \\f$ \\left( \\begin{array}{cc}\n  * linear & translation\\\\\n  * 0 ... 0 & 1\n  * \\end{array} \\right) \\f$\n  *\n  * Note that for a projective transformation the last row can be anything,\n  * and then the interpretation of different parts might be slightly different.\n  *\n  * However, unlike a plain matrix, the Transform class provides many features\n  * simplifying both its assembly and usage. In particular, it can be composed\n  * with any other transformations (Transform,Translation,RotationBase,DiagonalMatrix)\n  * and can be directly used to transform implicit homogeneous vectors. All these\n  * operations are handled via the operator*. For the composition of transformations,\n  * its principle consists to first convert the right/left hand sides of the product\n  * to a compatible (Dim+1)^2 matrix and then perform a pure matrix product.\n  * Of course, internally, operator* tries to perform the minimal number of operations\n  * according to the nature of each terms. Likewise, when applying the transform\n  * to points, the latters are automatically promoted to homogeneous vectors\n  * before doing the matrix product. The conventions to homogeneous representations\n  * are performed as follow:\n  *\n  * \\b Translation t (Dim)x(1):\n  * \\f$ \\left( \\begin{array}{cc}\n  * I & t \\\\\n  * 0\\,...\\,0 & 1\n  * \\end{array} \\right) \\f$\n  *\n  * \\b Rotation R (Dim)x(Dim):\n  * \\f$ \\left( \\begin{array}{cc}\n  * R & 0\\\\\n  * 0\\,...\\,0 & 1\n  * \\end{array} \\right) \\f$\n  *<!--\n  * \\b Linear \\b Matrix L (Dim)x(Dim):\n  * \\f$ \\left( \\begin{array}{cc}\n  * L & 0\\\\\n  * 0\\,...\\,0 & 1\n  * \\end{array} \\right) \\f$\n  *\n  * \\b Affine \\b Matrix A (Dim)x(Dim+1):\n  * \\f$ \\left( \\begin{array}{c}\n  * A\\\\\n  * 0\\,...\\,0\\,1\n  * \\end{array} \\right) \\f$\n  *-->\n  * \\b Scaling \\b DiagonalMatrix S (Dim)x(Dim):\n  * \\f$ \\left( \\begin{array}{cc}\n  * S & 0\\\\\n  * 0\\,...\\,0 & 1\n  * \\end{array} \\right) \\f$\n  *\n  * \\b Column \\b point v (Dim)x(1):\n  * \\f$ \\left( \\begin{array}{c}\n  * v\\\\\n  * 1\n  * \\end{array} \\right) \\f$\n  *\n  * \\b Set \\b of \\b column \\b points V1...Vn (Dim)x(n):\n  * \\f$ \\left( \\begin{array}{ccc}\n  * v_1 & ... & v_n\\\\\n  * 1 & ... & 1\n  * \\end{array} \\right) \\f$\n  *\n  * The concatenation of a Transform object with any kind of other transformation\n  * always returns a Transform object.\n  *\n  * A little exception to the \"as pure matrix product\" rule is the case of the\n  * transformation of non homogeneous vectors by an affine transformation. In\n  * that case the last matrix row can be ignored, and the product returns non\n  * homogeneous vectors.\n  *\n  * Since, for instance, a Dim x Dim matrix is interpreted as a linear transformation,\n  * it is not possible to directly transform Dim vectors stored in a Dim x Dim matrix.\n  * The solution is either to use a Dim x Dynamic matrix or explicitly request a\n  * vector transformation by making the vector homogeneous:\n  * \\code\n  * m' = T * m.colwise().homogeneous();\n  * \\endcode\n  * Note that there is zero overhead.\n  *\n  * Conversion methods from/to Qt's QMatrix and QTransform are available if the\n  * preprocessor token EIGEN_QT_SUPPORT is defined.\n  *\n  * This class can be extended with the help of the plugin mechanism described on the page\n  * \\ref TopicCustomizing_Plugins by defining the preprocessor symbol \\c EIGEN_TRANSFORM_PLUGIN.\n  *\n  * \\sa class Matrix, class Quaternion\n  */\ntemplate<typename Scalar_, int Dim_, int _Mode, int Options_>\nclass Transform\n{\npublic:\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(Scalar_,Dim_==Dynamic ? Dynamic : (Dim_+1)*(Dim_+1))\n  enum {\n    Mode = _Mode,\n    Options = Options_,\n    Dim = Dim_,     ///< space dimension in which the transformation holds\n    HDim = Dim_+1,  ///< size of a respective homogeneous vector\n    Rows = int(Mode)==(AffineCompact) ? Dim : HDim\n  };\n  /** the scalar type of the coefficients */\n  typedef Scalar_ Scalar;\n  typedef Eigen::Index StorageIndex;\n  typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n  /** type of the matrix used to represent the transformation */\n  typedef typename internal::make_proper_matrix_type<Scalar,Rows,HDim,Options>::type MatrixType;\n  /** constified MatrixType */\n  typedef const MatrixType ConstMatrixType;\n  /** type of the matrix used to represent the linear part of the transformation */\n  typedef Matrix<Scalar,Dim,Dim,Options> LinearMatrixType;\n  /** type of read/write reference to the linear part of the transformation */\n  typedef Block<MatrixType,Dim,Dim,int(Mode)==(AffineCompact) && (int(Options)&RowMajor)==0> LinearPart;\n  /** type of read reference to the linear part of the transformation */\n  typedef const Block<ConstMatrixType,Dim,Dim,int(Mode)==(AffineCompact) && (int(Options)&RowMajor)==0> ConstLinearPart;\n  /** type of read/write reference to the affine part of the transformation */\n  typedef typename internal::conditional<int(Mode)==int(AffineCompact),\n                              MatrixType&,\n                              Block<MatrixType,Dim,HDim> >::type AffinePart;\n  /** type of read reference to the affine part of the transformation */\n  typedef typename internal::conditional<int(Mode)==int(AffineCompact),\n                              const MatrixType&,\n                              const Block<const MatrixType,Dim,HDim> >::type ConstAffinePart;\n  /** type of a vector */\n  typedef Matrix<Scalar,Dim,1> VectorType;\n  /** type of a read/write reference to the translation part of the rotation */\n  typedef Block<MatrixType,Dim,1,!(internal::traits<MatrixType>::Flags & RowMajorBit)> TranslationPart;\n  /** type of a read reference to the translation part of the rotation */\n  typedef const Block<ConstMatrixType,Dim,1,!(internal::traits<MatrixType>::Flags & RowMajorBit)> ConstTranslationPart;\n  /** corresponding translation type */\n  typedef Translation<Scalar,Dim> TranslationType;\n\n  // this intermediate enum is needed to avoid an ICE with gcc 3.4 and 4.0\n  enum { TransformTimeDiagonalMode = ((Mode==int(Isometry))?Affine:int(Mode)) };\n  /** The return type of the product between a diagonal matrix and a transform */\n  typedef Transform<Scalar,Dim,TransformTimeDiagonalMode> TransformTimeDiagonalReturnType;\n\nprotected:\n\n  MatrixType m_matrix;\n\npublic:\n\n  /** Default constructor without initialization of the meaningful coefficients.\n    * If Mode==Affine or Mode==Isometry, then the last row is set to [0 ... 0 1] */\n  EIGEN_DEVICE_FUNC inline Transform()\n  {\n    check_template_params();\n    internal::transform_make_affine<(int(Mode)==Affine || int(Mode)==Isometry) ? Affine : AffineCompact>::run(m_matrix);\n  }\n\n  EIGEN_DEVICE_FUNC inline explicit Transform(const TranslationType& t)\n  {\n    check_template_params();\n    *this = t;\n  }\n  EIGEN_DEVICE_FUNC inline explicit Transform(const UniformScaling<Scalar>& s)\n  {\n    check_template_params();\n    *this = s;\n  }\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline explicit Transform(const RotationBase<Derived, Dim>& r)\n  {\n    check_template_params();\n    *this = r;\n  }\n\n  typedef internal::transform_take_affine_part<Transform> take_affine_part;\n\n  /** Constructs and initializes a transformation from a Dim^2 or a (Dim+1)^2 matrix. */\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC inline explicit Transform(const EigenBase<OtherDerived>& other)\n  {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar,typename OtherDerived::Scalar>::value),\n      YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY);\n\n    check_template_params();\n    internal::transform_construct_from_matrix<OtherDerived,Mode,Options,Dim,HDim>::run(this, other.derived());\n  }\n\n  /** Set \\c *this from a Dim^2 or (Dim+1)^2 matrix. */\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC inline Transform& operator=(const EigenBase<OtherDerived>& other)\n  {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar,typename OtherDerived::Scalar>::value),\n      YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY);\n\n    internal::transform_construct_from_matrix<OtherDerived,Mode,Options,Dim,HDim>::run(this, other.derived());\n    return *this;\n  }\n\n  template<int OtherOptions>\n  EIGEN_DEVICE_FUNC inline Transform(const Transform<Scalar,Dim,Mode,OtherOptions>& other)\n  {\n    check_template_params();\n    // only the options change, we can directly copy the matrices\n    m_matrix = other.matrix();\n  }\n\n  template<int OtherMode,int OtherOptions>\n  EIGEN_DEVICE_FUNC inline Transform(const Transform<Scalar,Dim,OtherMode,OtherOptions>& other)\n  {\n    check_template_params();\n    // prevent conversions as:\n    // Affine | AffineCompact | Isometry = Projective\n    EIGEN_STATIC_ASSERT(EIGEN_IMPLIES(OtherMode==int(Projective), Mode==int(Projective)),\n                        YOU_PERFORMED_AN_INVALID_TRANSFORMATION_CONVERSION)\n\n    // prevent conversions as:\n    // Isometry = Affine | AffineCompact\n    EIGEN_STATIC_ASSERT(EIGEN_IMPLIES(OtherMode==int(Affine)||OtherMode==int(AffineCompact), Mode!=int(Isometry)),\n                        YOU_PERFORMED_AN_INVALID_TRANSFORMATION_CONVERSION)\n\n    enum { ModeIsAffineCompact = Mode == int(AffineCompact),\n           OtherModeIsAffineCompact = OtherMode == int(AffineCompact)\n    };\n\n    if(EIGEN_CONST_CONDITIONAL(ModeIsAffineCompact == OtherModeIsAffineCompact))\n    {\n      // We need the block expression because the code is compiled for all\n      // combinations of transformations and will trigger a compile time error\n      // if one tries to assign the matrices directly\n      m_matrix.template block<Dim,Dim+1>(0,0) = other.matrix().template block<Dim,Dim+1>(0,0);\n      makeAffine();\n    }\n    else if(EIGEN_CONST_CONDITIONAL(OtherModeIsAffineCompact))\n    {\n      typedef typename Transform<Scalar,Dim,OtherMode,OtherOptions>::MatrixType OtherMatrixType;\n      internal::transform_construct_from_matrix<OtherMatrixType,Mode,Options,Dim,HDim>::run(this, other.matrix());\n    }\n    else\n    {\n      // here we know that Mode == AffineCompact and OtherMode != AffineCompact.\n      // if OtherMode were Projective, the static assert above would already have caught it.\n      // So the only possibility is that OtherMode == Affine\n      linear() = other.linear();\n      translation() = other.translation();\n    }\n  }\n\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC Transform(const ReturnByValue<OtherDerived>& other)\n  {\n    check_template_params();\n    other.evalTo(*this);\n  }\n\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC Transform& operator=(const ReturnByValue<OtherDerived>& other)\n  {\n    other.evalTo(*this);\n    return *this;\n  }\n\n  #ifdef EIGEN_QT_SUPPORT\n  inline Transform(const QMatrix& other);\n  inline Transform& operator=(const QMatrix& other);\n  inline QMatrix toQMatrix(void) const;\n  inline Transform(const QTransform& other);\n  inline Transform& operator=(const QTransform& other);\n  inline QTransform toQTransform(void) const;\n  #endif\n\n  EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return int(Mode)==int(Projective) ? m_matrix.cols() : (m_matrix.cols()-1); }\n  EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_matrix.cols(); }\n\n  /** shortcut for m_matrix(row,col);\n    * \\sa MatrixBase::operator(Index,Index) const */\n  EIGEN_DEVICE_FUNC inline Scalar operator() (Index row, Index col) const { return m_matrix(row,col); }\n  /** shortcut for m_matrix(row,col);\n    * \\sa MatrixBase::operator(Index,Index) */\n  EIGEN_DEVICE_FUNC inline Scalar& operator() (Index row, Index col) { return m_matrix(row,col); }\n\n  /** \\returns a read-only expression of the transformation matrix */\n  EIGEN_DEVICE_FUNC inline const MatrixType& matrix() const { return m_matrix; }\n  /** \\returns a writable expression of the transformation matrix */\n  EIGEN_DEVICE_FUNC inline MatrixType& matrix() { return m_matrix; }\n\n  /** \\returns a read-only expression of the linear part of the transformation */\n  EIGEN_DEVICE_FUNC inline ConstLinearPart linear() const { return ConstLinearPart(m_matrix,0,0); }\n  /** \\returns a writable expression of the linear part of the transformation */\n  EIGEN_DEVICE_FUNC inline LinearPart linear() { return LinearPart(m_matrix,0,0); }\n\n  /** \\returns a read-only expression of the Dim x HDim affine part of the transformation */\n  EIGEN_DEVICE_FUNC inline ConstAffinePart affine() const { return take_affine_part::run(m_matrix); }\n  /** \\returns a writable expression of the Dim x HDim affine part of the transformation */\n  EIGEN_DEVICE_FUNC inline AffinePart affine() { return take_affine_part::run(m_matrix); }\n\n  /** \\returns a read-only expression of the translation vector of the transformation */\n  EIGEN_DEVICE_FUNC inline ConstTranslationPart translation() const { return ConstTranslationPart(m_matrix,0,Dim); }\n  /** \\returns a writable expression of the translation vector of the transformation */\n  EIGEN_DEVICE_FUNC inline TranslationPart translation() { return TranslationPart(m_matrix,0,Dim); }\n\n  /** \\returns an expression of the product between the transform \\c *this and a matrix expression \\a other.\n    *\n    * The right-hand-side \\a other can be either:\n    * \\li an homogeneous vector of size Dim+1,\n    * \\li a set of homogeneous vectors of size Dim+1 x N,\n    * \\li a transformation matrix of size Dim+1 x Dim+1.\n    *\n    * Moreover, if \\c *this represents an affine transformation (i.e., Mode!=Projective), then \\a other can also be:\n    * \\li a point of size Dim (computes: \\code this->linear() * other + this->translation()\\endcode),\n    * \\li a set of N points as a Dim x N matrix (computes: \\code (this->linear() * other).colwise() + this->translation()\\endcode),\n    *\n    * In all cases, the return type is a matrix or vector of same sizes as the right-hand-side \\a other.\n    *\n    * If you want to interpret \\a other as a linear or affine transformation, then first convert it to a Transform<> type,\n    * or do your own cooking.\n    *\n    * Finally, if you want to apply Affine transformations to vectors, then explicitly apply the linear part only:\n    * \\code\n    * Affine3f A;\n    * Vector3f v1, v2;\n    * v2 = A.linear() * v1;\n    * \\endcode\n    *\n    */\n  // note: this function is defined here because some compilers cannot find the respective declaration\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename internal::transform_right_product_impl<Transform, OtherDerived>::ResultType\n  operator * (const EigenBase<OtherDerived> &other) const\n  { return internal::transform_right_product_impl<Transform, OtherDerived>::run(*this,other.derived()); }\n\n  /** \\returns the product expression of a transformation matrix \\a a times a transform \\a b\n    *\n    * The left hand side \\a other can be either:\n    * \\li a linear transformation matrix of size Dim x Dim,\n    * \\li an affine transformation matrix of size Dim x Dim+1,\n    * \\li a general transformation matrix of size Dim+1 x Dim+1.\n    */\n  template<typename OtherDerived> friend\n  EIGEN_DEVICE_FUNC inline const typename internal::transform_left_product_impl<OtherDerived,Mode,Options,Dim_,Dim_+1>::ResultType\n    operator * (const EigenBase<OtherDerived> &a, const Transform &b)\n  { return internal::transform_left_product_impl<OtherDerived,Mode,Options,Dim,HDim>::run(a.derived(),b); }\n\n  /** \\returns The product expression of a transform \\a a times a diagonal matrix \\a b\n    *\n    * The rhs diagonal matrix is interpreted as an affine scaling transformation. The\n    * product results in a Transform of the same type (mode) as the lhs only if the lhs\n    * mode is no isometry. In that case, the returned transform is an affinity.\n    */\n  template<typename DiagonalDerived>\n  EIGEN_DEVICE_FUNC inline const TransformTimeDiagonalReturnType\n    operator * (const DiagonalBase<DiagonalDerived> &b) const\n  {\n    TransformTimeDiagonalReturnType res(*this);\n    res.linearExt() *= b;\n    return res;\n  }\n\n  /** \\returns The product expression of a diagonal matrix \\a a times a transform \\a b\n    *\n    * The lhs diagonal matrix is interpreted as an affine scaling transformation. The\n    * product results in a Transform of the same type (mode) as the lhs only if the lhs\n    * mode is no isometry. In that case, the returned transform is an affinity.\n    */\n  template<typename DiagonalDerived>\n  EIGEN_DEVICE_FUNC friend inline TransformTimeDiagonalReturnType\n    operator * (const DiagonalBase<DiagonalDerived> &a, const Transform &b)\n  {\n    TransformTimeDiagonalReturnType res;\n    res.linear().noalias() = a*b.linear();\n    res.translation().noalias() = a*b.translation();\n    if (EIGEN_CONST_CONDITIONAL(Mode!=int(AffineCompact)))\n      res.matrix().row(Dim) = b.matrix().row(Dim);\n    return res;\n  }\n\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC inline Transform& operator*=(const EigenBase<OtherDerived>& other) { return *this = *this * other; }\n\n  /** Concatenates two transformations */\n  EIGEN_DEVICE_FUNC inline const Transform operator * (const Transform& other) const\n  {\n    return internal::transform_transform_product_impl<Transform,Transform>::run(*this,other);\n  }\n\n  #if EIGEN_COMP_ICC\nprivate:\n  // this intermediate structure permits to workaround a bug in ICC 11:\n  //   error: template instantiation resulted in unexpected function type of \"Eigen::Transform<double, 3, 32, 0>\n  //             (const Eigen::Transform<double, 3, 2, 0> &) const\"\n  //  (the meaning of a name may have changed since the template declaration -- the type of the template is:\n  // \"Eigen::internal::transform_transform_product_impl<Eigen::Transform<double, 3, 32, 0>,\n  //     Eigen::Transform<double, 3, Mode, Options>, <expression>>::ResultType (const Eigen::Transform<double, 3, Mode, Options> &) const\")\n  //\n  template<int OtherMode,int OtherOptions> struct icc_11_workaround\n  {\n    typedef internal::transform_transform_product_impl<Transform,Transform<Scalar,Dim,OtherMode,OtherOptions> > ProductType;\n    typedef typename ProductType::ResultType ResultType;\n  };\n\npublic:\n  /** Concatenates two different transformations */\n  template<int OtherMode,int OtherOptions>\n  inline typename icc_11_workaround<OtherMode,OtherOptions>::ResultType\n    operator * (const Transform<Scalar,Dim,OtherMode,OtherOptions>& other) const\n  {\n    typedef typename icc_11_workaround<OtherMode,OtherOptions>::ProductType ProductType;\n    return ProductType::run(*this,other);\n  }\n  #else\n  /** Concatenates two different transformations */\n  template<int OtherMode,int OtherOptions>\n  EIGEN_DEVICE_FUNC inline typename internal::transform_transform_product_impl<Transform,Transform<Scalar,Dim,OtherMode,OtherOptions> >::ResultType\n    operator * (const Transform<Scalar,Dim,OtherMode,OtherOptions>& other) const\n  {\n    return internal::transform_transform_product_impl<Transform,Transform<Scalar,Dim,OtherMode,OtherOptions> >::run(*this,other);\n  }\n  #endif\n\n  /** \\sa MatrixBase::setIdentity() */\n  EIGEN_DEVICE_FUNC void setIdentity() { m_matrix.setIdentity(); }\n\n  /**\n   * \\brief Returns an identity transformation.\n   * \\todo In the future this function should be returning a Transform expression.\n   */\n  EIGEN_DEVICE_FUNC static const Transform Identity()\n  {\n    return Transform(MatrixType::Identity());\n  }\n\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC\n  inline Transform& scale(const MatrixBase<OtherDerived> &other);\n\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC\n  inline Transform& prescale(const MatrixBase<OtherDerived> &other);\n\n  EIGEN_DEVICE_FUNC inline Transform& scale(const Scalar& s);\n  EIGEN_DEVICE_FUNC inline Transform& prescale(const Scalar& s);\n\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC\n  inline Transform& translate(const MatrixBase<OtherDerived> &other);\n\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC\n  inline Transform& pretranslate(const MatrixBase<OtherDerived> &other);\n\n  template<typename RotationType>\n  EIGEN_DEVICE_FUNC\n  inline Transform& rotate(const RotationType& rotation);\n\n  template<typename RotationType>\n  EIGEN_DEVICE_FUNC\n  inline Transform& prerotate(const RotationType& rotation);\n\n  EIGEN_DEVICE_FUNC Transform& shear(const Scalar& sx, const Scalar& sy);\n  EIGEN_DEVICE_FUNC Transform& preshear(const Scalar& sx, const Scalar& sy);\n\n  EIGEN_DEVICE_FUNC inline Transform& operator=(const TranslationType& t);\n\n  EIGEN_DEVICE_FUNC\n  inline Transform& operator*=(const TranslationType& t) { return translate(t.vector()); }\n\n  EIGEN_DEVICE_FUNC inline Transform operator*(const TranslationType& t) const;\n\n  EIGEN_DEVICE_FUNC\n  inline Transform& operator=(const UniformScaling<Scalar>& t);\n\n  EIGEN_DEVICE_FUNC\n  inline Transform& operator*=(const UniformScaling<Scalar>& s) { return scale(s.factor()); }\n\n  EIGEN_DEVICE_FUNC\n  inline TransformTimeDiagonalReturnType operator*(const UniformScaling<Scalar>& s) const\n  {\n    TransformTimeDiagonalReturnType res = *this;\n    res.scale(s.factor());\n    return res;\n  }\n\n  EIGEN_DEVICE_FUNC\n  inline Transform& operator*=(const DiagonalMatrix<Scalar,Dim>& s) { linearExt() *= s; return *this; }\n\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline Transform& operator=(const RotationBase<Derived,Dim>& r);\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline Transform& operator*=(const RotationBase<Derived,Dim>& r) { return rotate(r.toRotationMatrix()); }\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline Transform operator*(const RotationBase<Derived,Dim>& r) const;\n\n  typedef typename internal::conditional<int(Mode)==Isometry,ConstLinearPart,const LinearMatrixType>::type RotationReturnType;\n  EIGEN_DEVICE_FUNC RotationReturnType rotation() const;\n\n  template<typename RotationMatrixType, typename ScalingMatrixType>\n  EIGEN_DEVICE_FUNC\n  void computeRotationScaling(RotationMatrixType *rotation, ScalingMatrixType *scaling) const;\n  template<typename ScalingMatrixType, typename RotationMatrixType>\n  EIGEN_DEVICE_FUNC\n  void computeScalingRotation(ScalingMatrixType *scaling, RotationMatrixType *rotation) const;\n\n  template<typename PositionDerived, typename OrientationType, typename ScaleDerived>\n  EIGEN_DEVICE_FUNC\n  Transform& fromPositionOrientationScale(const MatrixBase<PositionDerived> &position,\n    const OrientationType& orientation, const MatrixBase<ScaleDerived> &scale);\n\n  EIGEN_DEVICE_FUNC\n  inline Transform inverse(TransformTraits traits = (TransformTraits)Mode) const;\n\n  /** \\returns a const pointer to the column major internal matrix */\n  EIGEN_DEVICE_FUNC const Scalar* data() const { return m_matrix.data(); }\n  /** \\returns a non-const pointer to the column major internal matrix */\n  EIGEN_DEVICE_FUNC Scalar* data() { return m_matrix.data(); }\n\n  /** \\returns \\c *this with scalar type casted to \\a NewScalarType\n    *\n    * Note that if \\a NewScalarType is equal to the current scalar type of \\c *this\n    * then this function smartly returns a const reference to \\c *this.\n    */\n  template<typename NewScalarType>\n  EIGEN_DEVICE_FUNC inline typename internal::cast_return_type<Transform,Transform<NewScalarType,Dim,Mode,Options> >::type cast() const\n  { return typename internal::cast_return_type<Transform,Transform<NewScalarType,Dim,Mode,Options> >::type(*this); }\n\n  /** Copy constructor with scalar type conversion */\n  template<typename OtherScalarType>\n  EIGEN_DEVICE_FUNC inline explicit Transform(const Transform<OtherScalarType,Dim,Mode,Options>& other)\n  {\n    check_template_params();\n    m_matrix = other.matrix().template cast<Scalar>();\n  }\n\n  /** \\returns \\c true if \\c *this is approximately equal to \\a other, within the precision\n    * determined by \\a prec.\n    *\n    * \\sa MatrixBase::isApprox() */\n  EIGEN_DEVICE_FUNC bool isApprox(const Transform& other, const typename NumTraits<Scalar>::Real& prec = NumTraits<Scalar>::dummy_precision()) const\n  { return m_matrix.isApprox(other.m_matrix, prec); }\n\n  /** Sets the last row to [0 ... 0 1]\n    */\n  EIGEN_DEVICE_FUNC void makeAffine()\n  {\n    internal::transform_make_affine<int(Mode)>::run(m_matrix);\n  }\n\n  /** \\internal\n    * \\returns the Dim x Dim linear part if the transformation is affine,\n    *          and the HDim x Dim part for projective transformations.\n    */\n  EIGEN_DEVICE_FUNC inline Block<MatrixType,int(Mode)==int(Projective)?HDim:Dim,Dim> linearExt()\n  { return m_matrix.template block<int(Mode)==int(Projective)?HDim:Dim,Dim>(0,0); }\n  /** \\internal\n    * \\returns the Dim x Dim linear part if the transformation is affine,\n    *          and the HDim x Dim part for projective transformations.\n    */\n  EIGEN_DEVICE_FUNC inline const Block<MatrixType,int(Mode)==int(Projective)?HDim:Dim,Dim> linearExt() const\n  { return m_matrix.template block<int(Mode)==int(Projective)?HDim:Dim,Dim>(0,0); }\n\n  /** \\internal\n    * \\returns the translation part if the transformation is affine,\n    *          and the last column for projective transformations.\n    */\n  EIGEN_DEVICE_FUNC inline Block<MatrixType,int(Mode)==int(Projective)?HDim:Dim,1> translationExt()\n  { return m_matrix.template block<int(Mode)==int(Projective)?HDim:Dim,1>(0,Dim); }\n  /** \\internal\n    * \\returns the translation part if the transformation is affine,\n    *          and the last column for projective transformations.\n    */\n  EIGEN_DEVICE_FUNC inline const Block<MatrixType,int(Mode)==int(Projective)?HDim:Dim,1> translationExt() const\n  { return m_matrix.template block<int(Mode)==int(Projective)?HDim:Dim,1>(0,Dim); }\n\n\n  #ifdef EIGEN_TRANSFORM_PLUGIN\n  #include EIGEN_TRANSFORM_PLUGIN\n  #endif\n\nprotected:\n  #ifndef EIGEN_PARSED_BY_DOXYGEN\n    EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void check_template_params()\n    {\n      EIGEN_STATIC_ASSERT((Options & (DontAlign|RowMajor)) == Options, INVALID_MATRIX_TEMPLATE_PARAMETERS)\n    }\n  #endif\n\n};\n\n/** \\ingroup Geometry_Module */\ntypedef Transform<float,2,Isometry> Isometry2f;\n/** \\ingroup Geometry_Module */\ntypedef Transform<float,3,Isometry> Isometry3f;\n/** \\ingroup Geometry_Module */\ntypedef Transform<double,2,Isometry> Isometry2d;\n/** \\ingroup Geometry_Module */\ntypedef Transform<double,3,Isometry> Isometry3d;\n\n/** \\ingroup Geometry_Module */\ntypedef Transform<float,2,Affine> Affine2f;\n/** \\ingroup Geometry_Module */\ntypedef Transform<float,3,Affine> Affine3f;\n/** \\ingroup Geometry_Module */\ntypedef Transform<double,2,Affine> Affine2d;\n/** \\ingroup Geometry_Module */\ntypedef Transform<double,3,Affine> Affine3d;\n\n/** \\ingroup Geometry_Module */\ntypedef Transform<float,2,AffineCompact> AffineCompact2f;\n/** \\ingroup Geometry_Module */\ntypedef Transform<float,3,AffineCompact> AffineCompact3f;\n/** \\ingroup Geometry_Module */\ntypedef Transform<double,2,AffineCompact> AffineCompact2d;\n/** \\ingroup Geometry_Module */\ntypedef Transform<double,3,AffineCompact> AffineCompact3d;\n\n/** \\ingroup Geometry_Module */\ntypedef Transform<float,2,Projective> Projective2f;\n/** \\ingroup Geometry_Module */\ntypedef Transform<float,3,Projective> Projective3f;\n/** \\ingroup Geometry_Module */\ntypedef Transform<double,2,Projective> Projective2d;\n/** \\ingroup Geometry_Module */\ntypedef Transform<double,3,Projective> Projective3d;\n\n/**************************\n*** Optional QT support ***\n**************************/\n\n#ifdef EIGEN_QT_SUPPORT\n/** Initializes \\c *this from a QMatrix assuming the dimension is 2.\n  *\n  * This function is available only if the token EIGEN_QT_SUPPORT is defined.\n  */\ntemplate<typename Scalar, int Dim, int Mode,int Options>\nTransform<Scalar,Dim,Mode,Options>::Transform(const QMatrix& other)\n{\n  check_template_params();\n  *this = other;\n}\n\n/** Set \\c *this from a QMatrix assuming the dimension is 2.\n  *\n  * This function is available only if the token EIGEN_QT_SUPPORT is defined.\n  */\ntemplate<typename Scalar, int Dim, int Mode,int Options>\nTransform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::operator=(const QMatrix& other)\n{\n  EIGEN_STATIC_ASSERT(Dim==2, YOU_MADE_A_PROGRAMMING_MISTAKE)\n  if (EIGEN_CONST_CONDITIONAL(Mode == int(AffineCompact)))\n    m_matrix << other.m11(), other.m21(), other.dx(),\n                other.m12(), other.m22(), other.dy();\n  else\n    m_matrix << other.m11(), other.m21(), other.dx(),\n                other.m12(), other.m22(), other.dy(),\n                0, 0, 1;\n  return *this;\n}\n\n/** \\returns a QMatrix from \\c *this assuming the dimension is 2.\n  *\n  * \\warning this conversion might loss data if \\c *this is not affine\n  *\n  * This function is available only if the token EIGEN_QT_SUPPORT is defined.\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nQMatrix Transform<Scalar,Dim,Mode,Options>::toQMatrix(void) const\n{\n  check_template_params();\n  EIGEN_STATIC_ASSERT(Dim==2, YOU_MADE_A_PROGRAMMING_MISTAKE)\n  return QMatrix(m_matrix.coeff(0,0), m_matrix.coeff(1,0),\n                 m_matrix.coeff(0,1), m_matrix.coeff(1,1),\n                 m_matrix.coeff(0,2), m_matrix.coeff(1,2));\n}\n\n/** Initializes \\c *this from a QTransform assuming the dimension is 2.\n  *\n  * This function is available only if the token EIGEN_QT_SUPPORT is defined.\n  */\ntemplate<typename Scalar, int Dim, int Mode,int Options>\nTransform<Scalar,Dim,Mode,Options>::Transform(const QTransform& other)\n{\n  check_template_params();\n  *this = other;\n}\n\n/** Set \\c *this from a QTransform assuming the dimension is 2.\n  *\n  * This function is available only if the token EIGEN_QT_SUPPORT is defined.\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nTransform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::operator=(const QTransform& other)\n{\n  check_template_params();\n  EIGEN_STATIC_ASSERT(Dim==2, YOU_MADE_A_PROGRAMMING_MISTAKE)\n  if (EIGEN_CONST_CONDITIONAL(Mode == int(AffineCompact)))\n    m_matrix << other.m11(), other.m21(), other.dx(),\n                other.m12(), other.m22(), other.dy();\n  else\n    m_matrix << other.m11(), other.m21(), other.dx(),\n                other.m12(), other.m22(), other.dy(),\n                other.m13(), other.m23(), other.m33();\n  return *this;\n}\n\n/** \\returns a QTransform from \\c *this assuming the dimension is 2.\n  *\n  * This function is available only if the token EIGEN_QT_SUPPORT is defined.\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nQTransform Transform<Scalar,Dim,Mode,Options>::toQTransform(void) const\n{\n  EIGEN_STATIC_ASSERT(Dim==2, YOU_MADE_A_PROGRAMMING_MISTAKE)\n  if (EIGEN_CONST_CONDITIONAL(Mode == int(AffineCompact)))\n    return QTransform(m_matrix.coeff(0,0), m_matrix.coeff(1,0),\n                      m_matrix.coeff(0,1), m_matrix.coeff(1,1),\n                      m_matrix.coeff(0,2), m_matrix.coeff(1,2));\n  else\n    return QTransform(m_matrix.coeff(0,0), m_matrix.coeff(1,0), m_matrix.coeff(2,0),\n                      m_matrix.coeff(0,1), m_matrix.coeff(1,1), m_matrix.coeff(2,1),\n                      m_matrix.coeff(0,2), m_matrix.coeff(1,2), m_matrix.coeff(2,2));\n}\n#endif\n\n/*********************\n*** Procedural API ***\n*********************/\n\n/** Applies on the right the non uniform scale transformation represented\n  * by the vector \\a other to \\c *this and returns a reference to \\c *this.\n  * \\sa prescale()\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode,Options>&\nTransform<Scalar,Dim,Mode,Options>::scale(const MatrixBase<OtherDerived> &other)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(OtherDerived,int(Dim))\n  EIGEN_STATIC_ASSERT(Mode!=int(Isometry), THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS)\n  linearExt().noalias() = (linearExt() * other.asDiagonal());\n  return *this;\n}\n\n/** Applies on the right a uniform scale of a factor \\a c to \\c *this\n  * and returns a reference to \\c *this.\n  * \\sa prescale(Scalar)\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nEIGEN_DEVICE_FUNC inline Transform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::scale(const Scalar& s)\n{\n  EIGEN_STATIC_ASSERT(Mode!=int(Isometry), THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS)\n  linearExt() *= s;\n  return *this;\n}\n\n/** Applies on the left the non uniform scale transformation represented\n  * by the vector \\a other to \\c *this and returns a reference to \\c *this.\n  * \\sa scale()\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode,Options>&\nTransform<Scalar,Dim,Mode,Options>::prescale(const MatrixBase<OtherDerived> &other)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(OtherDerived,int(Dim))\n  EIGEN_STATIC_ASSERT(Mode!=int(Isometry), THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS)\n  affine().noalias() = (other.asDiagonal() * affine());\n  return *this;\n}\n\n/** Applies on the left a uniform scale of a factor \\a c to \\c *this\n  * and returns a reference to \\c *this.\n  * \\sa scale(Scalar)\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nEIGEN_DEVICE_FUNC inline Transform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::prescale(const Scalar& s)\n{\n  EIGEN_STATIC_ASSERT(Mode!=int(Isometry), THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS)\n  m_matrix.template topRows<Dim>() *= s;\n  return *this;\n}\n\n/** Applies on the right the translation matrix represented by the vector \\a other\n  * to \\c *this and returns a reference to \\c *this.\n  * \\sa pretranslate()\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode,Options>&\nTransform<Scalar,Dim,Mode,Options>::translate(const MatrixBase<OtherDerived> &other)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(OtherDerived,int(Dim))\n  translationExt() += linearExt() * other;\n  return *this;\n}\n\n/** Applies on the left the translation matrix represented by the vector \\a other\n  * to \\c *this and returns a reference to \\c *this.\n  * \\sa translate()\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode,Options>&\nTransform<Scalar,Dim,Mode,Options>::pretranslate(const MatrixBase<OtherDerived> &other)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(OtherDerived,int(Dim))\n  if(EIGEN_CONST_CONDITIONAL(int(Mode)==int(Projective)))\n    affine() += other * m_matrix.row(Dim);\n  else\n    translation() += other;\n  return *this;\n}\n\n/** Applies on the right the rotation represented by the rotation \\a rotation\n  * to \\c *this and returns a reference to \\c *this.\n  *\n  * The template parameter \\a RotationType is the type of the rotation which\n  * must be known by internal::toRotationMatrix<>.\n  *\n  * Natively supported types includes:\n  *   - any scalar (2D),\n  *   - a Dim x Dim matrix expression,\n  *   - a Quaternion (3D),\n  *   - a AngleAxis (3D)\n  *\n  * This mechanism is easily extendable to support user types such as Euler angles,\n  * or a pair of Quaternion for 4D rotations.\n  *\n  * \\sa rotate(Scalar), class Quaternion, class AngleAxis, prerotate(RotationType)\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename RotationType>\nEIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode,Options>&\nTransform<Scalar,Dim,Mode,Options>::rotate(const RotationType& rotation)\n{\n  linearExt() *= internal::toRotationMatrix<Scalar,Dim>(rotation);\n  return *this;\n}\n\n/** Applies on the left the rotation represented by the rotation \\a rotation\n  * to \\c *this and returns a reference to \\c *this.\n  *\n  * See rotate() for further details.\n  *\n  * \\sa rotate()\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename RotationType>\nEIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode,Options>&\nTransform<Scalar,Dim,Mode,Options>::prerotate(const RotationType& rotation)\n{\n  m_matrix.template block<Dim,HDim>(0,0) = internal::toRotationMatrix<Scalar,Dim>(rotation)\n                                         * m_matrix.template block<Dim,HDim>(0,0);\n  return *this;\n}\n\n/** Applies on the right the shear transformation represented\n  * by the vector \\a other to \\c *this and returns a reference to \\c *this.\n  * \\warning 2D only.\n  * \\sa preshear()\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nEIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode,Options>&\nTransform<Scalar,Dim,Mode,Options>::shear(const Scalar& sx, const Scalar& sy)\n{\n  EIGEN_STATIC_ASSERT(int(Dim)==2, YOU_MADE_A_PROGRAMMING_MISTAKE)\n  EIGEN_STATIC_ASSERT(Mode!=int(Isometry), THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS)\n  VectorType tmp = linear().col(0)*sy + linear().col(1);\n  linear() << linear().col(0) + linear().col(1)*sx, tmp;\n  return *this;\n}\n\n/** Applies on the left the shear transformation represented\n  * by the vector \\a other to \\c *this and returns a reference to \\c *this.\n  * \\warning 2D only.\n  * \\sa shear()\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nEIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode,Options>&\nTransform<Scalar,Dim,Mode,Options>::preshear(const Scalar& sx, const Scalar& sy)\n{\n  EIGEN_STATIC_ASSERT(int(Dim)==2, YOU_MADE_A_PROGRAMMING_MISTAKE)\n  EIGEN_STATIC_ASSERT(Mode!=int(Isometry), THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS)\n  m_matrix.template block<Dim,HDim>(0,0) = LinearMatrixType(1, sx, sy, 1) * m_matrix.template block<Dim,HDim>(0,0);\n  return *this;\n}\n\n/******************************************************\n*** Scaling, Translation and Rotation compatibility ***\n******************************************************/\n\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nEIGEN_DEVICE_FUNC inline Transform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::operator=(const TranslationType& t)\n{\n  linear().setIdentity();\n  translation() = t.vector();\n  makeAffine();\n  return *this;\n}\n\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nEIGEN_DEVICE_FUNC inline Transform<Scalar,Dim,Mode,Options> Transform<Scalar,Dim,Mode,Options>::operator*(const TranslationType& t) const\n{\n  Transform res = *this;\n  res.translate(t.vector());\n  return res;\n}\n\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nEIGEN_DEVICE_FUNC inline Transform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::operator=(const UniformScaling<Scalar>& s)\n{\n  m_matrix.setZero();\n  linear().diagonal().fill(s.factor());\n  makeAffine();\n  return *this;\n}\n\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC inline Transform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::operator=(const RotationBase<Derived,Dim>& r)\n{\n  linear() = internal::toRotationMatrix<Scalar,Dim>(r);\n  translation().setZero();\n  makeAffine();\n  return *this;\n}\n\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC inline Transform<Scalar,Dim,Mode,Options> Transform<Scalar,Dim,Mode,Options>::operator*(const RotationBase<Derived,Dim>& r) const\n{\n  Transform res = *this;\n  res.rotate(r.derived());\n  return res;\n}\n\n/************************\n*** Special functions ***\n************************/\n\nnamespace internal {\ntemplate<int Mode> struct transform_rotation_impl {\n  template<typename TransformType>\n  EIGEN_DEVICE_FUNC static inline\n  const typename TransformType::LinearMatrixType run(const TransformType& t)\n  {\n    typedef typename TransformType::LinearMatrixType LinearMatrixType;\n    LinearMatrixType result;\n    t.computeRotationScaling(&result, (LinearMatrixType*)0);\n    return result;\n  }\n};\ntemplate<> struct transform_rotation_impl<Isometry> {\n  template<typename TransformType>\n  EIGEN_DEVICE_FUNC static inline\n  typename TransformType::ConstLinearPart run(const TransformType& t)\n  {\n    return t.linear();\n  }\n};\n}\n/** \\returns the rotation part of the transformation\n  *\n  * If Mode==Isometry, then this method is an alias for linear(),\n  * otherwise it calls computeRotationScaling() to extract the rotation\n  * through a SVD decomposition.\n  *\n  * \\svd_module\n  *\n  * \\sa computeRotationScaling(), computeScalingRotation(), class SVD\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nEIGEN_DEVICE_FUNC\ntypename Transform<Scalar,Dim,Mode,Options>::RotationReturnType\nTransform<Scalar,Dim,Mode,Options>::rotation() const\n{\n  return internal::transform_rotation_impl<Mode>::run(*this);\n}\n\n\n/** decomposes the linear part of the transformation as a product rotation x scaling, the scaling being\n  * not necessarily positive.\n  *\n  * If either pointer is zero, the corresponding computation is skipped.\n  *\n  *\n  *\n  * \\svd_module\n  *\n  * \\sa computeScalingRotation(), rotation(), class SVD\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename RotationMatrixType, typename ScalingMatrixType>\nEIGEN_DEVICE_FUNC void Transform<Scalar,Dim,Mode,Options>::computeRotationScaling(RotationMatrixType *rotation, ScalingMatrixType *scaling) const\n{\n  // Note that JacobiSVD is faster than BDCSVD for small matrices.\n  JacobiSVD<LinearMatrixType> svd(linear(), ComputeFullU | ComputeFullV);\n\n  Scalar x = (svd.matrixU() * svd.matrixV().adjoint()).determinant() < Scalar(0) ? Scalar(-1) : Scalar(1); // so x has absolute value 1\n  VectorType sv(svd.singularValues());\n  sv.coeffRef(Dim-1) *= x;\n  if(scaling) *scaling = svd.matrixV() * sv.asDiagonal() * svd.matrixV().adjoint();\n  if(rotation)\n  {\n    LinearMatrixType m(svd.matrixU());\n    m.col(Dim-1) *= x;\n    *rotation = m * svd.matrixV().adjoint();\n  }\n}\n\n/** decomposes the linear part of the transformation as a product scaling x rotation, the scaling being\n  * not necessarily positive.\n  *\n  * If either pointer is zero, the corresponding computation is skipped.\n  *\n  *\n  *\n  * \\svd_module\n  *\n  * \\sa computeRotationScaling(), rotation(), class SVD\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename ScalingMatrixType, typename RotationMatrixType>\nEIGEN_DEVICE_FUNC void Transform<Scalar,Dim,Mode,Options>::computeScalingRotation(ScalingMatrixType *scaling, RotationMatrixType *rotation) const\n{\n  // Note that JacobiSVD is faster than BDCSVD for small matrices.\n  JacobiSVD<LinearMatrixType> svd(linear(), ComputeFullU | ComputeFullV);\n\n  Scalar x = (svd.matrixU() * svd.matrixV().adjoint()).determinant() < Scalar(0) ? Scalar(-1) : Scalar(1); // so x has absolute value 1\n  VectorType sv(svd.singularValues());\n  sv.coeffRef(Dim-1) *= x;\n  if(scaling) *scaling = svd.matrixU() * sv.asDiagonal() * svd.matrixU().adjoint();\n  if(rotation)\n  {\n    LinearMatrixType m(svd.matrixU());\n    m.col(Dim-1) *= x;\n    *rotation = m * svd.matrixV().adjoint();\n  }\n}\n\n/** Convenient method to set \\c *this from a position, orientation and scale\n  * of a 3D object.\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename PositionDerived, typename OrientationType, typename ScaleDerived>\nEIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode,Options>&\nTransform<Scalar,Dim,Mode,Options>::fromPositionOrientationScale(const MatrixBase<PositionDerived> &position,\n  const OrientationType& orientation, const MatrixBase<ScaleDerived> &scale)\n{\n  linear() = internal::toRotationMatrix<Scalar,Dim>(orientation);\n  linear() *= scale.asDiagonal();\n  translation() = position;\n  makeAffine();\n  return *this;\n}\n\nnamespace internal {\n\ntemplate<int Mode>\nstruct transform_make_affine\n{\n  template<typename MatrixType>\n  EIGEN_DEVICE_FUNC static void run(MatrixType &mat)\n  {\n    static const int Dim = MatrixType::ColsAtCompileTime-1;\n    mat.template block<1,Dim>(Dim,0).setZero();\n    mat.coeffRef(Dim,Dim) = typename MatrixType::Scalar(1);\n  }\n};\n\ntemplate<>\nstruct transform_make_affine<AffineCompact>\n{\n  template<typename MatrixType> EIGEN_DEVICE_FUNC static void run(MatrixType &) { }\n};\n\n// selector needed to avoid taking the inverse of a 3x4 matrix\ntemplate<typename TransformType, int Mode=TransformType::Mode>\nstruct projective_transform_inverse\n{\n  EIGEN_DEVICE_FUNC static inline void run(const TransformType&, TransformType&)\n  {}\n};\n\ntemplate<typename TransformType>\nstruct projective_transform_inverse<TransformType, Projective>\n{\n  EIGEN_DEVICE_FUNC static inline void run(const TransformType& m, TransformType& res)\n  {\n    res.matrix() = m.matrix().inverse();\n  }\n};\n\n} // end namespace internal\n\n\n/**\n  *\n  * \\returns the inverse transformation according to some given knowledge\n  * on \\c *this.\n  *\n  * \\param hint allows to optimize the inversion process when the transformation\n  * is known to be not a general transformation (optional). The possible values are:\n  *  - #Projective if the transformation is not necessarily affine, i.e., if the\n  *    last row is not guaranteed to be [0 ... 0 1]\n  *  - #Affine if the last row can be assumed to be [0 ... 0 1]\n  *  - #Isometry if the transformation is only a concatenations of translations\n  *    and rotations.\n  *  The default is the template class parameter \\c Mode.\n  *\n  * \\warning unless \\a traits is always set to NoShear or NoScaling, this function\n  * requires the generic inverse method of MatrixBase defined in the LU module. If\n  * you forget to include this module, then you will get hard to debug linking errors.\n  *\n  * \\sa MatrixBase::inverse()\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nEIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode,Options>\nTransform<Scalar,Dim,Mode,Options>::inverse(TransformTraits hint) const\n{\n  Transform res;\n  if (hint == Projective)\n  {\n    internal::projective_transform_inverse<Transform>::run(*this, res);\n  }\n  else\n  {\n    if (hint == Isometry)\n    {\n      res.matrix().template topLeftCorner<Dim,Dim>() = linear().transpose();\n    }\n    else if(hint&Affine)\n    {\n      res.matrix().template topLeftCorner<Dim,Dim>() = linear().inverse();\n    }\n    else\n    {\n      eigen_assert(false && \"Invalid transform traits in Transform::Inverse\");\n    }\n    // translation and remaining parts\n    res.matrix().template topRightCorner<Dim,1>()\n      = - res.matrix().template topLeftCorner<Dim,Dim>() * translation();\n    res.makeAffine(); // we do need this, because in the beginning res is uninitialized\n  }\n  return res;\n}\n\nnamespace internal {\n\n/*****************************************************\n*** Specializations of take affine part            ***\n*****************************************************/\n\ntemplate<typename TransformType> struct transform_take_affine_part {\n  typedef typename TransformType::MatrixType MatrixType;\n  typedef typename TransformType::AffinePart AffinePart;\n  typedef typename TransformType::ConstAffinePart ConstAffinePart;\n  static inline AffinePart run(MatrixType& m)\n  { return m.template block<TransformType::Dim,TransformType::HDim>(0,0); }\n  static inline ConstAffinePart run(const MatrixType& m)\n  { return m.template block<TransformType::Dim,TransformType::HDim>(0,0); }\n};\n\ntemplate<typename Scalar, int Dim, int Options>\nstruct transform_take_affine_part<Transform<Scalar,Dim,AffineCompact, Options> > {\n  typedef typename Transform<Scalar,Dim,AffineCompact,Options>::MatrixType MatrixType;\n  static inline MatrixType& run(MatrixType& m) { return m; }\n  static inline const MatrixType& run(const MatrixType& m) { return m; }\n};\n\n/*****************************************************\n*** Specializations of construct from matrix       ***\n*****************************************************/\n\ntemplate<typename Other, int Mode, int Options, int Dim, int HDim>\nstruct transform_construct_from_matrix<Other, Mode,Options,Dim,HDim, Dim,Dim>\n{\n  static inline void run(Transform<typename Other::Scalar,Dim,Mode,Options> *transform, const Other& other)\n  {\n    transform->linear() = other;\n    transform->translation().setZero();\n    transform->makeAffine();\n  }\n};\n\ntemplate<typename Other, int Mode, int Options, int Dim, int HDim>\nstruct transform_construct_from_matrix<Other, Mode,Options,Dim,HDim, Dim,HDim>\n{\n  static inline void run(Transform<typename Other::Scalar,Dim,Mode,Options> *transform, const Other& other)\n  {\n    transform->affine() = other;\n    transform->makeAffine();\n  }\n};\n\ntemplate<typename Other, int Mode, int Options, int Dim, int HDim>\nstruct transform_construct_from_matrix<Other, Mode,Options,Dim,HDim, HDim,HDim>\n{\n  static inline void run(Transform<typename Other::Scalar,Dim,Mode,Options> *transform, const Other& other)\n  { transform->matrix() = other; }\n};\n\ntemplate<typename Other, int Options, int Dim, int HDim>\nstruct transform_construct_from_matrix<Other, AffineCompact,Options,Dim,HDim, HDim,HDim>\n{\n  static inline void run(Transform<typename Other::Scalar,Dim,AffineCompact,Options> *transform, const Other& other)\n  { transform->matrix() = other.template block<Dim,HDim>(0,0); }\n};\n\n/**********************************************************\n***   Specializations of operator* with rhs EigenBase   ***\n**********************************************************/\n\ntemplate<int LhsMode,int RhsMode>\nstruct transform_product_result\n{\n  enum\n  {\n    Mode =\n      (LhsMode == (int)Projective    || RhsMode == (int)Projective    ) ? Projective :\n      (LhsMode == (int)Affine        || RhsMode == (int)Affine        ) ? Affine :\n      (LhsMode == (int)AffineCompact || RhsMode == (int)AffineCompact ) ? AffineCompact :\n      (LhsMode == (int)Isometry      || RhsMode == (int)Isometry      ) ? Isometry : Projective\n  };\n};\n\ntemplate< typename TransformType, typename MatrixType, int RhsCols>\nstruct transform_right_product_impl< TransformType, MatrixType, 0, RhsCols>\n{\n  typedef typename MatrixType::PlainObject ResultType;\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other)\n  {\n    return T.matrix() * other;\n  }\n};\n\ntemplate< typename TransformType, typename MatrixType, int RhsCols>\nstruct transform_right_product_impl< TransformType, MatrixType, 1, RhsCols>\n{\n  enum {\n    Dim = TransformType::Dim,\n    HDim = TransformType::HDim,\n    OtherRows = MatrixType::RowsAtCompileTime,\n    OtherCols = MatrixType::ColsAtCompileTime\n  };\n\n  typedef typename MatrixType::PlainObject ResultType;\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other)\n  {\n    EIGEN_STATIC_ASSERT(OtherRows==HDim, YOU_MIXED_MATRICES_OF_DIFFERENT_SIZES);\n\n    typedef Block<ResultType, Dim, OtherCols, int(MatrixType::RowsAtCompileTime)==Dim> TopLeftLhs;\n\n    ResultType res(other.rows(),other.cols());\n    TopLeftLhs(res, 0, 0, Dim, other.cols()).noalias() = T.affine() * other;\n    res.row(OtherRows-1) = other.row(OtherRows-1);\n\n    return res;\n  }\n};\n\ntemplate< typename TransformType, typename MatrixType, int RhsCols>\nstruct transform_right_product_impl< TransformType, MatrixType, 2, RhsCols>\n{\n  enum {\n    Dim = TransformType::Dim,\n    HDim = TransformType::HDim,\n    OtherRows = MatrixType::RowsAtCompileTime,\n    OtherCols = MatrixType::ColsAtCompileTime\n  };\n\n  typedef typename MatrixType::PlainObject ResultType;\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other)\n  {\n    EIGEN_STATIC_ASSERT(OtherRows==Dim, YOU_MIXED_MATRICES_OF_DIFFERENT_SIZES);\n\n    typedef Block<ResultType, Dim, OtherCols, true> TopLeftLhs;\n    ResultType res(Replicate<typename TransformType::ConstTranslationPart, 1, OtherCols>(T.translation(),1,other.cols()));\n    TopLeftLhs(res, 0, 0, Dim, other.cols()).noalias() += T.linear() * other;\n\n    return res;\n  }\n};\n\ntemplate< typename TransformType, typename MatrixType >\nstruct transform_right_product_impl< TransformType, MatrixType, 2, 1> // rhs is a vector of size Dim\n{\n  typedef typename TransformType::MatrixType TransformMatrix;\n  enum {\n    Dim = TransformType::Dim,\n    HDim = TransformType::HDim,\n    OtherRows = MatrixType::RowsAtCompileTime,\n    WorkingRows = EIGEN_PLAIN_ENUM_MIN(TransformMatrix::RowsAtCompileTime,HDim)\n  };\n\n  typedef typename MatrixType::PlainObject ResultType;\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other)\n  {\n    EIGEN_STATIC_ASSERT(OtherRows==Dim, YOU_MIXED_MATRICES_OF_DIFFERENT_SIZES);\n\n    Matrix<typename ResultType::Scalar, Dim+1, 1> rhs;\n    rhs.template head<Dim>() = other; rhs[Dim] = typename ResultType::Scalar(1);\n    Matrix<typename ResultType::Scalar, WorkingRows, 1> res(T.matrix() * rhs);\n    return res.template head<Dim>();\n  }\n};\n\n/**********************************************************\n***   Specializations of operator* with lhs EigenBase   ***\n**********************************************************/\n\n// generic HDim x HDim matrix * T => Projective\ntemplate<typename Other,int Mode, int Options, int Dim, int HDim>\nstruct transform_left_product_impl<Other,Mode,Options,Dim,HDim, HDim,HDim>\n{\n  typedef Transform<typename Other::Scalar,Dim,Mode,Options> TransformType;\n  typedef typename TransformType::MatrixType MatrixType;\n  typedef Transform<typename Other::Scalar,Dim,Projective,Options> ResultType;\n  static ResultType run(const Other& other,const TransformType& tr)\n  { return ResultType(other * tr.matrix()); }\n};\n\n// generic HDim x HDim matrix * AffineCompact => Projective\ntemplate<typename Other, int Options, int Dim, int HDim>\nstruct transform_left_product_impl<Other,AffineCompact,Options,Dim,HDim, HDim,HDim>\n{\n  typedef Transform<typename Other::Scalar,Dim,AffineCompact,Options> TransformType;\n  typedef typename TransformType::MatrixType MatrixType;\n  typedef Transform<typename Other::Scalar,Dim,Projective,Options> ResultType;\n  static ResultType run(const Other& other,const TransformType& tr)\n  {\n    ResultType res;\n    res.matrix().noalias() = other.template block<HDim,Dim>(0,0) * tr.matrix();\n    res.matrix().col(Dim) += other.col(Dim);\n    return res;\n  }\n};\n\n// affine matrix * T\ntemplate<typename Other,int Mode, int Options, int Dim, int HDim>\nstruct transform_left_product_impl<Other,Mode,Options,Dim,HDim, Dim,HDim>\n{\n  typedef Transform<typename Other::Scalar,Dim,Mode,Options> TransformType;\n  typedef typename TransformType::MatrixType MatrixType;\n  typedef TransformType ResultType;\n  static ResultType run(const Other& other,const TransformType& tr)\n  {\n    ResultType res;\n    res.affine().noalias() = other * tr.matrix();\n    res.matrix().row(Dim) = tr.matrix().row(Dim);\n    return res;\n  }\n};\n\n// affine matrix * AffineCompact\ntemplate<typename Other, int Options, int Dim, int HDim>\nstruct transform_left_product_impl<Other,AffineCompact,Options,Dim,HDim, Dim,HDim>\n{\n  typedef Transform<typename Other::Scalar,Dim,AffineCompact,Options> TransformType;\n  typedef typename TransformType::MatrixType MatrixType;\n  typedef TransformType ResultType;\n  static ResultType run(const Other& other,const TransformType& tr)\n  {\n    ResultType res;\n    res.matrix().noalias() = other.template block<Dim,Dim>(0,0) * tr.matrix();\n    res.translation() += other.col(Dim);\n    return res;\n  }\n};\n\n// linear matrix * T\ntemplate<typename Other,int Mode, int Options, int Dim, int HDim>\nstruct transform_left_product_impl<Other,Mode,Options,Dim,HDim, Dim,Dim>\n{\n  typedef Transform<typename Other::Scalar,Dim,Mode,Options> TransformType;\n  typedef typename TransformType::MatrixType MatrixType;\n  typedef TransformType ResultType;\n  static ResultType run(const Other& other, const TransformType& tr)\n  {\n    TransformType res;\n    if(Mode!=int(AffineCompact))\n      res.matrix().row(Dim) = tr.matrix().row(Dim);\n    res.matrix().template topRows<Dim>().noalias()\n      = other * tr.matrix().template topRows<Dim>();\n    return res;\n  }\n};\n\n/**********************************************************\n*** Specializations of operator* with another Transform ***\n**********************************************************/\n\ntemplate<typename Scalar, int Dim, int LhsMode, int LhsOptions, int RhsMode, int RhsOptions>\nstruct transform_transform_product_impl<Transform<Scalar,Dim,LhsMode,LhsOptions>,Transform<Scalar,Dim,RhsMode,RhsOptions>,false >\n{\n  enum { ResultMode = transform_product_result<LhsMode,RhsMode>::Mode };\n  typedef Transform<Scalar,Dim,LhsMode,LhsOptions> Lhs;\n  typedef Transform<Scalar,Dim,RhsMode,RhsOptions> Rhs;\n  typedef Transform<Scalar,Dim,ResultMode,LhsOptions> ResultType;\n  static ResultType run(const Lhs& lhs, const Rhs& rhs)\n  {\n    ResultType res;\n    res.linear() = lhs.linear() * rhs.linear();\n    res.translation() = lhs.linear() * rhs.translation() + lhs.translation();\n    res.makeAffine();\n    return res;\n  }\n};\n\ntemplate<typename Scalar, int Dim, int LhsMode, int LhsOptions, int RhsMode, int RhsOptions>\nstruct transform_transform_product_impl<Transform<Scalar,Dim,LhsMode,LhsOptions>,Transform<Scalar,Dim,RhsMode,RhsOptions>,true >\n{\n  typedef Transform<Scalar,Dim,LhsMode,LhsOptions> Lhs;\n  typedef Transform<Scalar,Dim,RhsMode,RhsOptions> Rhs;\n  typedef Transform<Scalar,Dim,Projective> ResultType;\n  static ResultType run(const Lhs& lhs, const Rhs& rhs)\n  {\n    return ResultType( lhs.matrix() * rhs.matrix() );\n  }\n};\n\ntemplate<typename Scalar, int Dim, int LhsOptions, int RhsOptions>\nstruct transform_transform_product_impl<Transform<Scalar,Dim,AffineCompact,LhsOptions>,Transform<Scalar,Dim,Projective,RhsOptions>,true >\n{\n  typedef Transform<Scalar,Dim,AffineCompact,LhsOptions> Lhs;\n  typedef Transform<Scalar,Dim,Projective,RhsOptions> Rhs;\n  typedef Transform<Scalar,Dim,Projective> ResultType;\n  static ResultType run(const Lhs& lhs, const Rhs& rhs)\n  {\n    ResultType res;\n    res.matrix().template topRows<Dim>() = lhs.matrix() * rhs.matrix();\n    res.matrix().row(Dim) = rhs.matrix().row(Dim);\n    return res;\n  }\n};\n\ntemplate<typename Scalar, int Dim, int LhsOptions, int RhsOptions>\nstruct transform_transform_product_impl<Transform<Scalar,Dim,Projective,LhsOptions>,Transform<Scalar,Dim,AffineCompact,RhsOptions>,true >\n{\n  typedef Transform<Scalar,Dim,Projective,LhsOptions> Lhs;\n  typedef Transform<Scalar,Dim,AffineCompact,RhsOptions> Rhs;\n  typedef Transform<Scalar,Dim,Projective> ResultType;\n  static ResultType run(const Lhs& lhs, const Rhs& rhs)\n  {\n    ResultType res(lhs.matrix().template leftCols<Dim>() * rhs.matrix());\n    res.matrix().col(Dim) += lhs.matrix().col(Dim);\n    return res;\n  }\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_TRANSFORM_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Geometry/Translation.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_TRANSLATION_H\n#define EIGEN_TRANSLATION_H\n\nnamespace Eigen { \n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\class Translation\n  *\n  * \\brief Represents a translation transformation\n  *\n  * \\tparam Scalar_ the scalar type, i.e., the type of the coefficients.\n  * \\tparam Dim_ the  dimension of the space, can be a compile time value or Dynamic\n  *\n  * \\note This class is not aimed to be used to store a translation transformation,\n  * but rather to make easier the constructions and updates of Transform objects.\n  *\n  * \\sa class Scaling, class Transform\n  */\ntemplate<typename Scalar_, int Dim_>\nclass Translation\n{\npublic:\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(Scalar_,Dim_)\n  /** dimension of the space */\n  enum { Dim = Dim_ };\n  /** the scalar type of the coefficients */\n  typedef Scalar_ Scalar;\n  /** corresponding vector type */\n  typedef Matrix<Scalar,Dim,1> VectorType;\n  /** corresponding linear transformation matrix type */\n  typedef Matrix<Scalar,Dim,Dim> LinearMatrixType;\n  /** corresponding affine transformation type */\n  typedef Transform<Scalar,Dim,Affine> AffineTransformType;\n  /** corresponding isometric transformation type */\n  typedef Transform<Scalar,Dim,Isometry> IsometryTransformType;\n\nprotected:\n\n  VectorType m_coeffs;\n\npublic:\n\n  /** Default constructor without initialization. */\n  EIGEN_DEVICE_FUNC Translation() {}\n  /**  */\n  EIGEN_DEVICE_FUNC inline Translation(const Scalar& sx, const Scalar& sy)\n  {\n    eigen_assert(Dim==2);\n    m_coeffs.x() = sx;\n    m_coeffs.y() = sy;\n  }\n  /**  */\n  EIGEN_DEVICE_FUNC inline Translation(const Scalar& sx, const Scalar& sy, const Scalar& sz)\n  {\n    eigen_assert(Dim==3);\n    m_coeffs.x() = sx;\n    m_coeffs.y() = sy;\n    m_coeffs.z() = sz;\n  }\n  /** Constructs and initialize the translation transformation from a vector of translation coefficients */\n  EIGEN_DEVICE_FUNC explicit inline Translation(const VectorType& vector) : m_coeffs(vector) {}\n\n  /** \\brief Returns the x-translation by value. **/\n  EIGEN_DEVICE_FUNC inline Scalar x() const { return m_coeffs.x(); }\n  /** \\brief Returns the y-translation by value. **/\n  EIGEN_DEVICE_FUNC inline Scalar y() const { return m_coeffs.y(); }\n  /** \\brief Returns the z-translation by value. **/\n  EIGEN_DEVICE_FUNC inline Scalar z() const { return m_coeffs.z(); }\n\n  /** \\brief Returns the x-translation as a reference. **/\n  EIGEN_DEVICE_FUNC inline Scalar& x() { return m_coeffs.x(); }\n  /** \\brief Returns the y-translation as a reference. **/\n  EIGEN_DEVICE_FUNC inline Scalar& y() { return m_coeffs.y(); }\n  /** \\brief Returns the z-translation as a reference. **/\n  EIGEN_DEVICE_FUNC inline Scalar& z() { return m_coeffs.z(); }\n\n  EIGEN_DEVICE_FUNC const VectorType& vector() const { return m_coeffs; }\n  EIGEN_DEVICE_FUNC VectorType& vector() { return m_coeffs; }\n\n  EIGEN_DEVICE_FUNC const VectorType& translation() const { return m_coeffs; }\n  EIGEN_DEVICE_FUNC VectorType& translation() { return m_coeffs; }\n\n  /** Concatenates two translation */\n  EIGEN_DEVICE_FUNC inline Translation operator* (const Translation& other) const\n  { return Translation(m_coeffs + other.m_coeffs); }\n\n  /** Concatenates a translation and a uniform scaling */\n  EIGEN_DEVICE_FUNC inline AffineTransformType operator* (const UniformScaling<Scalar>& other) const;\n\n  /** Concatenates a translation and a linear transformation */\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC inline AffineTransformType operator* (const EigenBase<OtherDerived>& linear) const;\n\n  /** Concatenates a translation and a rotation */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline IsometryTransformType operator*(const RotationBase<Derived,Dim>& r) const\n  { return *this * IsometryTransformType(r); }\n\n  /** \\returns the concatenation of a linear transformation \\a l with the translation \\a t */\n  // its a nightmare to define a templated friend function outside its declaration\n  template<typename OtherDerived> friend\n  EIGEN_DEVICE_FUNC inline AffineTransformType operator*(const EigenBase<OtherDerived>& linear, const Translation& t)\n  {\n    AffineTransformType res;\n    res.matrix().setZero();\n    res.linear() = linear.derived();\n    res.translation() = linear.derived() * t.m_coeffs;\n    res.matrix().row(Dim).setZero();\n    res(Dim,Dim) = Scalar(1);\n    return res;\n  }\n\n  /** Concatenates a translation and a transformation */\n  template<int Mode, int Options>\n  EIGEN_DEVICE_FUNC inline Transform<Scalar,Dim,Mode> operator* (const Transform<Scalar,Dim,Mode,Options>& t) const\n  {\n    Transform<Scalar,Dim,Mode> res = t;\n    res.pretranslate(m_coeffs);\n    return res;\n  }\n\n  /** Applies translation to vector */\n  template<typename Derived>\n  inline typename internal::enable_if<Derived::IsVectorAtCompileTime,VectorType>::type\n  operator* (const MatrixBase<Derived>& vec) const\n  { return m_coeffs + vec.derived(); }\n\n  /** \\returns the inverse translation (opposite) */\n  Translation inverse() const { return Translation(-m_coeffs); }\n\n  static const Translation Identity() { return Translation(VectorType::Zero()); }\n\n  /** \\returns \\c *this with scalar type casted to \\a NewScalarType\n    *\n    * Note that if \\a NewScalarType is equal to the current scalar type of \\c *this\n    * then this function smartly returns a const reference to \\c *this.\n    */\n  template<typename NewScalarType>\n  EIGEN_DEVICE_FUNC inline typename internal::cast_return_type<Translation,Translation<NewScalarType,Dim> >::type cast() const\n  { return typename internal::cast_return_type<Translation,Translation<NewScalarType,Dim> >::type(*this); }\n\n  /** Copy constructor with scalar type conversion */\n  template<typename OtherScalarType>\n  EIGEN_DEVICE_FUNC inline explicit Translation(const Translation<OtherScalarType,Dim>& other)\n  { m_coeffs = other.vector().template cast<Scalar>(); }\n\n  /** \\returns \\c true if \\c *this is approximately equal to \\a other, within the precision\n    * determined by \\a prec.\n    *\n    * \\sa MatrixBase::isApprox() */\n  EIGEN_DEVICE_FUNC bool isApprox(const Translation& other, const typename NumTraits<Scalar>::Real& prec = NumTraits<Scalar>::dummy_precision()) const\n  { return m_coeffs.isApprox(other.m_coeffs, prec); }\n\n};\n\n/** \\addtogroup Geometry_Module */\n//@{\ntypedef Translation<float, 2> Translation2f;\ntypedef Translation<double,2> Translation2d;\ntypedef Translation<float, 3> Translation3f;\ntypedef Translation<double,3> Translation3d;\n//@}\n\ntemplate<typename Scalar, int Dim>\nEIGEN_DEVICE_FUNC inline typename Translation<Scalar,Dim>::AffineTransformType\nTranslation<Scalar,Dim>::operator* (const UniformScaling<Scalar>& other) const\n{\n  AffineTransformType res;\n  res.matrix().setZero();\n  res.linear().diagonal().fill(other.factor());\n  res.translation() = m_coeffs;\n  res(Dim,Dim) = Scalar(1);\n  return res;\n}\n\ntemplate<typename Scalar, int Dim>\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC inline typename Translation<Scalar,Dim>::AffineTransformType\nTranslation<Scalar,Dim>::operator* (const EigenBase<OtherDerived>& linear) const\n{\n  AffineTransformType res;\n  res.matrix().setZero();\n  res.linear() = linear.derived();\n  res.translation() = m_coeffs;\n  res.matrix().row(Dim).setZero();\n  res(Dim,Dim) = Scalar(1);\n  return res;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_TRANSLATION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Geometry/Umeyama.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_UMEYAMA_H\n#define EIGEN_UMEYAMA_H\n\n// This file requires the user to include \n// * Eigen/Core\n// * Eigen/LU \n// * Eigen/SVD\n// * Eigen/Array\n\nnamespace Eigen { \n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n\n// These helpers are required since it allows to use mixed types as parameters\n// for the Umeyama. The problem with mixed parameters is that the return type\n// cannot trivially be deduced when float and double types are mixed.\nnamespace internal {\n\n// Compile time return type deduction for different MatrixBase types.\n// Different means here different alignment and parameters but the same underlying\n// real scalar type.\ntemplate<typename MatrixType, typename OtherMatrixType>\nstruct umeyama_transform_matrix_type\n{\n  enum {\n    MinRowsAtCompileTime = EIGEN_SIZE_MIN_PREFER_DYNAMIC(MatrixType::RowsAtCompileTime, OtherMatrixType::RowsAtCompileTime),\n\n    // When possible we want to choose some small fixed size value since the result\n    // is likely to fit on the stack. So here, EIGEN_SIZE_MIN_PREFER_DYNAMIC is not what we want.\n    HomogeneousDimension = int(MinRowsAtCompileTime) == Dynamic ? Dynamic : int(MinRowsAtCompileTime)+1\n  };\n\n  typedef Matrix<typename traits<MatrixType>::Scalar,\n    HomogeneousDimension,\n    HomogeneousDimension,\n    AutoAlign | (traits<MatrixType>::Flags & RowMajorBit ? RowMajor : ColMajor),\n    HomogeneousDimension,\n    HomogeneousDimension\n  > type;\n};\n\n}\n\n#endif\n\n/**\n* \\geometry_module \\ingroup Geometry_Module\n*\n* \\brief Returns the transformation between two point sets.\n*\n* The algorithm is based on:\n* \"Least-squares estimation of transformation parameters between two point patterns\",\n* Shinji Umeyama, PAMI 1991, DOI: 10.1109/34.88573\n*\n* It estimates parameters \\f$ c, \\mathbf{R}, \\f$ and \\f$ \\mathbf{t} \\f$ such that\n* \\f{align*}\n*   \\frac{1}{n} \\sum_{i=1}^n \\vert\\vert y_i - (c\\mathbf{R}x_i + \\mathbf{t}) \\vert\\vert_2^2\n* \\f}\n* is minimized.\n*\n* The algorithm is based on the analysis of the covariance matrix\n* \\f$ \\Sigma_{\\mathbf{x}\\mathbf{y}} \\in \\mathbb{R}^{d \\times d} \\f$\n* of the input point sets \\f$ \\mathbf{x} \\f$ and \\f$ \\mathbf{y} \\f$ where \n* \\f$d\\f$ is corresponding to the dimension (which is typically small).\n* The analysis is involving the SVD having a complexity of \\f$O(d^3)\\f$\n* though the actual computational effort lies in the covariance\n* matrix computation which has an asymptotic lower bound of \\f$O(dm)\\f$ when \n* the input point sets have dimension \\f$d \\times m\\f$.\n*\n* Currently the method is working only for floating point matrices.\n*\n* \\todo Should the return type of umeyama() become a Transform?\n*\n* \\param src Source points \\f$ \\mathbf{x} = \\left( x_1, \\hdots, x_n \\right) \\f$.\n* \\param dst Destination points \\f$ \\mathbf{y} = \\left( y_1, \\hdots, y_n \\right) \\f$.\n* \\param with_scaling Sets \\f$ c=1 \\f$ when <code>false</code> is passed.\n* \\return The homogeneous transformation \n* \\f{align*}\n*   T = \\begin{bmatrix} c\\mathbf{R} & \\mathbf{t} \\\\ \\mathbf{0} & 1 \\end{bmatrix}\n* \\f}\n* minimizing the residual above. This transformation is always returned as an \n* Eigen::Matrix.\n*/\ntemplate <typename Derived, typename OtherDerived>\ntypename internal::umeyama_transform_matrix_type<Derived, OtherDerived>::type\numeyama(const MatrixBase<Derived>& src, const MatrixBase<OtherDerived>& dst, bool with_scaling = true)\n{\n  typedef typename internal::umeyama_transform_matrix_type<Derived, OtherDerived>::type TransformationMatrixType;\n  typedef typename internal::traits<TransformationMatrixType>::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  EIGEN_STATIC_ASSERT(!NumTraits<Scalar>::IsComplex, NUMERIC_TYPE_MUST_BE_REAL)\n  EIGEN_STATIC_ASSERT((internal::is_same<Scalar, typename internal::traits<OtherDerived>::Scalar>::value),\n    YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n\n  enum { Dimension = EIGEN_SIZE_MIN_PREFER_DYNAMIC(Derived::RowsAtCompileTime, OtherDerived::RowsAtCompileTime) };\n\n  typedef Matrix<Scalar, Dimension, 1> VectorType;\n  typedef Matrix<Scalar, Dimension, Dimension> MatrixType;\n  typedef typename internal::plain_matrix_type_row_major<Derived>::type RowMajorMatrixType;\n\n  const Index m = src.rows(); // dimension\n  const Index n = src.cols(); // number of measurements\n\n  // required for demeaning ...\n  const RealScalar one_over_n = RealScalar(1) / static_cast<RealScalar>(n);\n\n  // computation of mean\n  const VectorType src_mean = src.rowwise().sum() * one_over_n;\n  const VectorType dst_mean = dst.rowwise().sum() * one_over_n;\n\n  // demeaning of src and dst points\n  const RowMajorMatrixType src_demean = src.colwise() - src_mean;\n  const RowMajorMatrixType dst_demean = dst.colwise() - dst_mean;\n\n  // Eq. (36)-(37)\n  const Scalar src_var = src_demean.rowwise().squaredNorm().sum() * one_over_n;\n\n  // Eq. (38)\n  const MatrixType sigma = one_over_n * dst_demean * src_demean.transpose();\n\n  JacobiSVD<MatrixType> svd(sigma, ComputeFullU | ComputeFullV);\n\n  // Initialize the resulting transformation with an identity matrix...\n  TransformationMatrixType Rt = TransformationMatrixType::Identity(m+1,m+1);\n\n  // Eq. (39)\n  VectorType S = VectorType::Ones(m);\n\n  if  ( svd.matrixU().determinant() * svd.matrixV().determinant() < 0 )\n    S(m-1) = -1;\n\n  // Eq. (40) and (43)\n  Rt.block(0,0,m,m).noalias() = svd.matrixU() * S.asDiagonal() * svd.matrixV().transpose();\n\n  if (with_scaling)\n  {\n    // Eq. (42)\n    const Scalar c = Scalar(1)/src_var * svd.singularValues().dot(S);\n\n    // Eq. (41)\n    Rt.col(m).head(m) = dst_mean;\n    Rt.col(m).head(m).noalias() -= c*Rt.topLeftCorner(m,m)*src_mean;\n    Rt.block(0,0,m,m) *= c;\n  }\n  else\n  {\n    Rt.col(m).head(m) = dst_mean;\n    Rt.col(m).head(m).noalias() -= Rt.topLeftCorner(m,m)*src_mean;\n  }\n\n  return Rt;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_UMEYAMA_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Geometry/arch/Geometry_SIMD.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Rohit Garg <rpg.314@gmail.com>\n// Copyright (C) 2009-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_GEOMETRY_SIMD_H\n#define EIGEN_GEOMETRY_SIMD_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate<class Derived, class OtherDerived>\nstruct quat_product<Architecture::Target, Derived, OtherDerived, float>\n{\n  enum {\n    AAlignment = traits<Derived>::Alignment,\n    BAlignment = traits<OtherDerived>::Alignment,\n    ResAlignment = traits<Quaternion<float> >::Alignment\n  };\n  static inline Quaternion<float> run(const QuaternionBase<Derived>& _a, const QuaternionBase<OtherDerived>& _b)\n  {\n    evaluator<typename Derived::Coefficients> ae(_a.coeffs());\n    evaluator<typename OtherDerived::Coefficients> be(_b.coeffs());\n    Quaternion<float> res;\n    const float neg_zero = numext::bit_cast<float>(0x80000000u);\n    const float arr[4] = {0.f, 0.f, 0.f, neg_zero};\n    const Packet4f mask = ploadu<Packet4f>(arr);\n    Packet4f a = ae.template packet<AAlignment,Packet4f>(0);\n    Packet4f b = be.template packet<BAlignment,Packet4f>(0);\n    Packet4f s1 = pmul(vec4f_swizzle1(a,1,2,0,2),vec4f_swizzle1(b,2,0,1,2));\n    Packet4f s2 = pmul(vec4f_swizzle1(a,3,3,3,1),vec4f_swizzle1(b,0,1,2,1));\n    pstoret<float,Packet4f,ResAlignment>(\n              &res.x(),\n              padd(psub(pmul(a,vec4f_swizzle1(b,3,3,3,3)),\n                                    pmul(vec4f_swizzle1(a,2,0,1,0),\n                                               vec4f_swizzle1(b,1,2,0,0))),\n                         pxor(mask,padd(s1,s2))));\n    \n    return res;\n  }\n};\n\ntemplate<class Derived>\nstruct quat_conj<Architecture::Target, Derived, float>\n{\n  enum {\n    ResAlignment = traits<Quaternion<float> >::Alignment\n  };\n  static inline Quaternion<float> run(const QuaternionBase<Derived>& q)\n  {\n    evaluator<typename Derived::Coefficients> qe(q.coeffs());\n    Quaternion<float> res;\n    const float neg_zero = numext::bit_cast<float>(0x80000000u);\n    const float arr[4] = {neg_zero, neg_zero, neg_zero,0.f};\n    const Packet4f mask = ploadu<Packet4f>(arr);\n    pstoret<float,Packet4f,ResAlignment>(&res.x(), pxor(mask, qe.template packet<traits<Derived>::Alignment,Packet4f>(0)));\n    return res;\n  }\n};\n\n\ntemplate<typename VectorLhs,typename VectorRhs>\nstruct cross3_impl<Architecture::Target,VectorLhs,VectorRhs,float,true>\n{\n  enum {\n    ResAlignment = traits<typename plain_matrix_type<VectorLhs>::type>::Alignment\n  };\n  static inline typename plain_matrix_type<VectorLhs>::type\n  run(const VectorLhs& lhs, const VectorRhs& rhs)\n  {\n    evaluator<VectorLhs> lhs_eval(lhs);\n    evaluator<VectorRhs> rhs_eval(rhs);\n    Packet4f a = lhs_eval.template packet<traits<VectorLhs>::Alignment,Packet4f>(0);\n    Packet4f b = rhs_eval.template packet<traits<VectorRhs>::Alignment,Packet4f>(0);\n    Packet4f mul1 = pmul(vec4f_swizzle1(a,1,2,0,3),vec4f_swizzle1(b,2,0,1,3));\n    Packet4f mul2 = pmul(vec4f_swizzle1(a,2,0,1,3),vec4f_swizzle1(b,1,2,0,3));\n    typename plain_matrix_type<VectorLhs>::type res;\n    pstoret<float,Packet4f,ResAlignment>(&res.x(),psub(mul1,mul2));\n    return res;\n  }\n};\n\n\n\n#if (defined EIGEN_VECTORIZE_SSE) || (EIGEN_ARCH_ARM64)\n\ntemplate<class Derived, class OtherDerived>\nstruct quat_product<Architecture::Target, Derived, OtherDerived, double>\n{\n  enum {\n    BAlignment = traits<OtherDerived>::Alignment,\n    ResAlignment = traits<Quaternion<double> >::Alignment\n  };\n\n  static inline Quaternion<double> run(const QuaternionBase<Derived>& _a, const QuaternionBase<OtherDerived>& _b)\n  {\n  Quaternion<double> res;\n\n  evaluator<typename Derived::Coefficients> ae(_a.coeffs());\n  evaluator<typename OtherDerived::Coefficients> be(_b.coeffs());\n\n  const double* a = _a.coeffs().data();\n  Packet2d b_xy = be.template packet<BAlignment,Packet2d>(0);\n  Packet2d b_zw = be.template packet<BAlignment,Packet2d>(2);\n  Packet2d a_xx = pset1<Packet2d>(a[0]);\n  Packet2d a_yy = pset1<Packet2d>(a[1]);\n  Packet2d a_zz = pset1<Packet2d>(a[2]);\n  Packet2d a_ww = pset1<Packet2d>(a[3]);\n\n  // two temporaries:\n  Packet2d t1, t2;\n\n  /*\n   * t1 = ww*xy + yy*zw\n   * t2 = zz*xy - xx*zw\n   * res.xy = t1 +/- swap(t2)\n   */\n  t1 = padd(pmul(a_ww, b_xy), pmul(a_yy, b_zw));\n  t2 = psub(pmul(a_zz, b_xy), pmul(a_xx, b_zw));\n  pstoret<double,Packet2d,ResAlignment>(&res.x(), paddsub(t1, preverse(t2)));\n  \n  /*\n   * t1 = ww*zw - yy*xy\n   * t2 = zz*zw + xx*xy\n   * res.zw = t1 -/+ swap(t2) = swap( swap(t1) +/- t2)\n   */\n  t1 = psub(pmul(a_ww, b_zw), pmul(a_yy, b_xy));\n  t2 = padd(pmul(a_zz, b_zw), pmul(a_xx, b_xy));\n  pstoret<double,Packet2d,ResAlignment>(&res.z(), preverse(paddsub(preverse(t1), t2)));\n\n  return res;\n}\n};\n\ntemplate<class Derived>\nstruct quat_conj<Architecture::Target, Derived, double>\n{\n  enum {\n    ResAlignment = traits<Quaternion<double> >::Alignment\n  };\n  static inline Quaternion<double> run(const QuaternionBase<Derived>& q)\n  {\n    evaluator<typename Derived::Coefficients> qe(q.coeffs());\n    Quaternion<double> res;\n    const double neg_zero = numext::bit_cast<double>(0x8000000000000000ull);\n    const double arr1[2] = {neg_zero, neg_zero};\n    const double arr2[2] = {neg_zero,  0.0};\n    const Packet2d mask0 = ploadu<Packet2d>(arr1);\n    const Packet2d mask2 = ploadu<Packet2d>(arr2);\n    pstoret<double,Packet2d,ResAlignment>(&res.x(), pxor(mask0, qe.template packet<traits<Derived>::Alignment,Packet2d>(0)));\n    pstoret<double,Packet2d,ResAlignment>(&res.z(), pxor(mask2, qe.template packet<traits<Derived>::Alignment,Packet2d>(2)));\n    return res;\n  }\n};\n\n#endif // end EIGEN_VECTORIZE_SSE_OR_EIGEN_ARCH_ARM64\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_GEOMETRY_SIMD_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Householder/BlockHouseholder.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Vincent Lejeune\n// Copyright (C) 2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BLOCK_HOUSEHOLDER_H\n#define EIGEN_BLOCK_HOUSEHOLDER_H\n\n// This file contains some helper function to deal with block householder reflectors\n\nnamespace Eigen { \n\nnamespace internal {\n  \n/** \\internal */\n// template<typename TriangularFactorType,typename VectorsType,typename CoeffsType>\n// void make_block_householder_triangular_factor(TriangularFactorType& triFactor, const VectorsType& vectors, const CoeffsType& hCoeffs)\n// {\n//   typedef typename VectorsType::Scalar Scalar;\n//   const Index nbVecs = vectors.cols();\n//   eigen_assert(triFactor.rows() == nbVecs && triFactor.cols() == nbVecs && vectors.rows()>=nbVecs);\n// \n//   for(Index i = 0; i < nbVecs; i++)\n//   {\n//     Index rs = vectors.rows() - i;\n//     // Warning, note that hCoeffs may alias with vectors.\n//     // It is then necessary to copy it before modifying vectors(i,i). \n//     typename CoeffsType::Scalar h = hCoeffs(i);\n//     // This hack permits to pass trough nested Block<> and Transpose<> expressions.\n//     Scalar *Vii_ptr = const_cast<Scalar*>(vectors.data() + vectors.outerStride()*i + vectors.innerStride()*i);\n//     Scalar Vii = *Vii_ptr;\n//     *Vii_ptr = Scalar(1);\n//     triFactor.col(i).head(i).noalias() = -h * vectors.block(i, 0, rs, i).adjoint()\n//                                        * vectors.col(i).tail(rs);\n//     *Vii_ptr = Vii;\n//     // FIXME add .noalias() once the triangular product can work inplace\n//     triFactor.col(i).head(i) = triFactor.block(0,0,i,i).template triangularView<Upper>()\n//                              * triFactor.col(i).head(i);\n//     triFactor(i,i) = hCoeffs(i);\n//   }\n// }\n\n/** \\internal */\n// This variant avoid modifications in vectors\ntemplate<typename TriangularFactorType,typename VectorsType,typename CoeffsType>\nvoid make_block_householder_triangular_factor(TriangularFactorType& triFactor, const VectorsType& vectors, const CoeffsType& hCoeffs)\n{\n  const Index nbVecs = vectors.cols();\n  eigen_assert(triFactor.rows() == nbVecs && triFactor.cols() == nbVecs && vectors.rows()>=nbVecs);\n\n  for(Index i = nbVecs-1; i >=0 ; --i)\n  {\n    Index rs = vectors.rows() - i - 1;\n    Index rt = nbVecs-i-1;\n\n    if(rt>0)\n    {\n      triFactor.row(i).tail(rt).noalias() = -hCoeffs(i) * vectors.col(i).tail(rs).adjoint()\n                                                        * vectors.bottomRightCorner(rs, rt).template triangularView<UnitLower>();\n            \n      // FIXME use the following line with .noalias() once the triangular product can work inplace\n      // triFactor.row(i).tail(rt) = triFactor.row(i).tail(rt) * triFactor.bottomRightCorner(rt,rt).template triangularView<Upper>();\n      for(Index j=nbVecs-1; j>i; --j)\n      {\n        typename TriangularFactorType::Scalar z = triFactor(i,j);\n        triFactor(i,j) = z * triFactor(j,j);\n        if(nbVecs-j-1>0)\n          triFactor.row(i).tail(nbVecs-j-1) += z * triFactor.row(j).tail(nbVecs-j-1);\n      }\n      \n    }\n    triFactor(i,i) = hCoeffs(i);\n  }\n}\n\n/** \\internal\n  * if forward then perform   mat = H0 * H1 * H2 * mat\n  * otherwise perform         mat = H2 * H1 * H0 * mat\n  */\ntemplate<typename MatrixType,typename VectorsType,typename CoeffsType>\nvoid apply_block_householder_on_the_left(MatrixType& mat, const VectorsType& vectors, const CoeffsType& hCoeffs, bool forward)\n{\n  enum { TFactorSize = MatrixType::ColsAtCompileTime };\n  Index nbVecs = vectors.cols();\n  Matrix<typename MatrixType::Scalar, TFactorSize, TFactorSize, RowMajor> T(nbVecs,nbVecs);\n  \n  if(forward) make_block_householder_triangular_factor(T, vectors, hCoeffs);\n  else        make_block_householder_triangular_factor(T, vectors, hCoeffs.conjugate());  \n  const TriangularView<const VectorsType, UnitLower> V(vectors);\n\n  // A -= V T V^* A\n  Matrix<typename MatrixType::Scalar,VectorsType::ColsAtCompileTime,MatrixType::ColsAtCompileTime,\n         (VectorsType::MaxColsAtCompileTime==1 && MatrixType::MaxColsAtCompileTime!=1)?RowMajor:ColMajor,\n         VectorsType::MaxColsAtCompileTime,MatrixType::MaxColsAtCompileTime> tmp = V.adjoint() * mat;\n  // FIXME add .noalias() once the triangular product can work inplace\n  if(forward) tmp = T.template triangularView<Upper>()           * tmp;\n  else        tmp = T.template triangularView<Upper>().adjoint() * tmp;\n  mat.noalias() -= V * tmp;\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_BLOCK_HOUSEHOLDER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Householder/Householder.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_HOUSEHOLDER_H\n#define EIGEN_HOUSEHOLDER_H\n\nnamespace Eigen { \n\nnamespace internal {\ntemplate<int n> struct decrement_size\n{\n  enum {\n    ret = n==Dynamic ? n : n-1\n  };\n};\n}\n\n/** Computes the elementary reflector H such that:\n  * \\f$ H *this = [ beta 0 ... 0]^T \\f$\n  * where the transformation H is:\n  * \\f$ H = I - tau v v^*\\f$\n  * and the vector v is:\n  * \\f$ v^T = [1 essential^T] \\f$\n  *\n  * The essential part of the vector \\c v is stored in *this.\n  * \n  * On output:\n  * \\param tau the scaling factor of the Householder transformation\n  * \\param beta the result of H * \\c *this\n  *\n  * \\sa MatrixBase::makeHouseholder(), MatrixBase::applyHouseholderOnTheLeft(),\n  *     MatrixBase::applyHouseholderOnTheRight()\n  */\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC\nvoid MatrixBase<Derived>::makeHouseholderInPlace(Scalar& tau, RealScalar& beta)\n{\n  VectorBlock<Derived, internal::decrement_size<Base::SizeAtCompileTime>::ret> essentialPart(derived(), 1, size()-1);\n  makeHouseholder(essentialPart, tau, beta);\n}\n\n/** Computes the elementary reflector H such that:\n  * \\f$ H *this = [ beta 0 ... 0]^T \\f$\n  * where the transformation H is:\n  * \\f$ H = I - tau v v^*\\f$\n  * and the vector v is:\n  * \\f$ v^T = [1 essential^T] \\f$\n  *\n  * On output:\n  * \\param essential the essential part of the vector \\c v\n  * \\param tau the scaling factor of the Householder transformation\n  * \\param beta the result of H * \\c *this\n  *\n  * \\sa MatrixBase::makeHouseholderInPlace(), MatrixBase::applyHouseholderOnTheLeft(),\n  *     MatrixBase::applyHouseholderOnTheRight()\n  */\ntemplate<typename Derived>\ntemplate<typename EssentialPart>\nEIGEN_DEVICE_FUNC\nvoid MatrixBase<Derived>::makeHouseholder(\n  EssentialPart& essential,\n  Scalar& tau,\n  RealScalar& beta) const\n{\n  using std::sqrt;\n  using numext::conj;\n  \n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(EssentialPart)\n  VectorBlock<const Derived, EssentialPart::SizeAtCompileTime> tail(derived(), 1, size()-1);\n  \n  RealScalar tailSqNorm = size()==1 ? RealScalar(0) : tail.squaredNorm();\n  Scalar c0 = coeff(0);\n  const RealScalar tol = (std::numeric_limits<RealScalar>::min)();\n\n  if(tailSqNorm <= tol && numext::abs2(numext::imag(c0))<=tol)\n  {\n    tau = RealScalar(0);\n    beta = numext::real(c0);\n    essential.setZero();\n  }\n  else\n  {\n    beta = sqrt(numext::abs2(c0) + tailSqNorm);\n    if (numext::real(c0)>=RealScalar(0))\n      beta = -beta;\n    essential = tail / (c0 - beta);\n    tau = conj((beta - c0) / beta);\n  }\n}\n\n/** Apply the elementary reflector H given by\n  * \\f$ H = I - tau v v^*\\f$\n  * with\n  * \\f$ v^T = [1 essential^T] \\f$\n  * from the left to a vector or matrix.\n  *\n  * On input:\n  * \\param essential the essential part of the vector \\c v\n  * \\param tau the scaling factor of the Householder transformation\n  * \\param workspace a pointer to working space with at least\n  *                  this->cols() entries\n  *\n  * \\sa MatrixBase::makeHouseholder(), MatrixBase::makeHouseholderInPlace(), \n  *     MatrixBase::applyHouseholderOnTheRight()\n  */\ntemplate<typename Derived>\ntemplate<typename EssentialPart>\nEIGEN_DEVICE_FUNC\nvoid MatrixBase<Derived>::applyHouseholderOnTheLeft(\n  const EssentialPart& essential,\n  const Scalar& tau,\n  Scalar* workspace)\n{\n  if(rows() == 1)\n  {\n    *this *= Scalar(1)-tau;\n  }\n  else if(tau!=Scalar(0))\n  {\n    Map<typename internal::plain_row_type<PlainObject>::type> tmp(workspace,cols());\n    Block<Derived, EssentialPart::SizeAtCompileTime, Derived::ColsAtCompileTime> bottom(derived(), 1, 0, rows()-1, cols());\n    tmp.noalias() = essential.adjoint() * bottom;\n    tmp += this->row(0);\n    this->row(0) -= tau * tmp;\n    bottom.noalias() -= tau * essential * tmp;\n  }\n}\n\n/** Apply the elementary reflector H given by\n  * \\f$ H = I - tau v v^*\\f$\n  * with\n  * \\f$ v^T = [1 essential^T] \\f$\n  * from the right to a vector or matrix.\n  *\n  * On input:\n  * \\param essential the essential part of the vector \\c v\n  * \\param tau the scaling factor of the Householder transformation\n  * \\param workspace a pointer to working space with at least\n  *                  this->rows() entries\n  *\n  * \\sa MatrixBase::makeHouseholder(), MatrixBase::makeHouseholderInPlace(), \n  *     MatrixBase::applyHouseholderOnTheLeft()\n  */\ntemplate<typename Derived>\ntemplate<typename EssentialPart>\nEIGEN_DEVICE_FUNC\nvoid MatrixBase<Derived>::applyHouseholderOnTheRight(\n  const EssentialPart& essential,\n  const Scalar& tau,\n  Scalar* workspace)\n{\n  if(cols() == 1)\n  {\n    *this *= Scalar(1)-tau;\n  }\n  else if(tau!=Scalar(0))\n  {\n    Map<typename internal::plain_col_type<PlainObject>::type> tmp(workspace,rows());\n    Block<Derived, Derived::RowsAtCompileTime, EssentialPart::SizeAtCompileTime> right(derived(), 0, 1, rows(), cols()-1);\n    tmp.noalias() = right * essential;\n    tmp += this->col(0);\n    this->col(0) -= tau * tmp;\n    right.noalias() -= tau * tmp * essential.adjoint();\n  }\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_HOUSEHOLDER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Householder/HouseholderSequence.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_HOUSEHOLDER_SEQUENCE_H\n#define EIGEN_HOUSEHOLDER_SEQUENCE_H\n\nnamespace Eigen {\n\n/** \\ingroup Householder_Module\n  * \\householder_module\n  * \\class HouseholderSequence\n  * \\brief Sequence of Householder reflections acting on subspaces with decreasing size\n  * \\tparam VectorsType type of matrix containing the Householder vectors\n  * \\tparam CoeffsType  type of vector containing the Householder coefficients\n  * \\tparam Side        either OnTheLeft (the default) or OnTheRight\n  *\n  * This class represents a product sequence of Householder reflections where the first Householder reflection\n  * acts on the whole space, the second Householder reflection leaves the one-dimensional subspace spanned by\n  * the first unit vector invariant, the third Householder reflection leaves the two-dimensional subspace\n  * spanned by the first two unit vectors invariant, and so on up to the last reflection which leaves all but\n  * one dimensions invariant and acts only on the last dimension. Such sequences of Householder reflections\n  * are used in several algorithms to zero out certain parts of a matrix. Indeed, the methods\n  * HessenbergDecomposition::matrixQ(), Tridiagonalization::matrixQ(), HouseholderQR::householderQ(),\n  * and ColPivHouseholderQR::householderQ() all return a %HouseholderSequence.\n  *\n  * More precisely, the class %HouseholderSequence represents an \\f$ n \\times n \\f$ matrix \\f$ H \\f$ of the\n  * form \\f$ H = \\prod_{i=0}^{n-1} H_i \\f$ where the i-th Householder reflection is \\f$ H_i = I - h_i v_i\n  * v_i^* \\f$. The i-th Householder coefficient \\f$ h_i \\f$ is a scalar and the i-th Householder vector \\f$\n  * v_i \\f$ is a vector of the form\n  * \\f[\n  * v_i = [\\underbrace{0, \\ldots, 0}_{i-1\\mbox{ zeros}}, 1, \\underbrace{*, \\ldots,*}_{n-i\\mbox{ arbitrary entries}} ].\n  * \\f]\n  * The last \\f$ n-i \\f$ entries of \\f$ v_i \\f$ are called the essential part of the Householder vector.\n  *\n  * Typical usages are listed below, where H is a HouseholderSequence:\n  * \\code\n  * A.applyOnTheRight(H);             // A = A * H\n  * A.applyOnTheLeft(H);              // A = H * A\n  * A.applyOnTheRight(H.adjoint());   // A = A * H^*\n  * A.applyOnTheLeft(H.adjoint());    // A = H^* * A\n  * MatrixXd Q = H;                   // conversion to a dense matrix\n  * \\endcode\n  * In addition to the adjoint, you can also apply the inverse (=adjoint), the transpose, and the conjugate operators.\n  *\n  * See the documentation for HouseholderSequence(const VectorsType&, const CoeffsType&) for an example.\n  *\n  * \\sa MatrixBase::applyOnTheLeft(), MatrixBase::applyOnTheRight()\n  */\n\nnamespace internal {\n\ntemplate<typename VectorsType, typename CoeffsType, int Side>\nstruct traits<HouseholderSequence<VectorsType,CoeffsType,Side> >\n{\n  typedef typename VectorsType::Scalar Scalar;\n  typedef typename VectorsType::StorageIndex StorageIndex;\n  typedef typename VectorsType::StorageKind StorageKind;\n  enum {\n    RowsAtCompileTime = Side==OnTheLeft ? traits<VectorsType>::RowsAtCompileTime\n                                        : traits<VectorsType>::ColsAtCompileTime,\n    ColsAtCompileTime = RowsAtCompileTime,\n    MaxRowsAtCompileTime = Side==OnTheLeft ? traits<VectorsType>::MaxRowsAtCompileTime\n                                           : traits<VectorsType>::MaxColsAtCompileTime,\n    MaxColsAtCompileTime = MaxRowsAtCompileTime,\n    Flags = 0\n  };\n};\n\nstruct HouseholderSequenceShape {};\n\ntemplate<typename VectorsType, typename CoeffsType, int Side>\nstruct evaluator_traits<HouseholderSequence<VectorsType,CoeffsType,Side> >\n  : public evaluator_traits_base<HouseholderSequence<VectorsType,CoeffsType,Side> >\n{\n  typedef HouseholderSequenceShape Shape;\n};\n\ntemplate<typename VectorsType, typename CoeffsType, int Side>\nstruct hseq_side_dependent_impl\n{\n  typedef Block<const VectorsType, Dynamic, 1> EssentialVectorType;\n  typedef HouseholderSequence<VectorsType, CoeffsType, OnTheLeft> HouseholderSequenceType;\n  static EIGEN_DEVICE_FUNC inline const EssentialVectorType essentialVector(const HouseholderSequenceType& h, Index k)\n  {\n    Index start = k+1+h.m_shift;\n    return Block<const VectorsType,Dynamic,1>(h.m_vectors, start, k, h.rows()-start, 1);\n  }\n};\n\ntemplate<typename VectorsType, typename CoeffsType>\nstruct hseq_side_dependent_impl<VectorsType, CoeffsType, OnTheRight>\n{\n  typedef Transpose<Block<const VectorsType, 1, Dynamic> > EssentialVectorType;\n  typedef HouseholderSequence<VectorsType, CoeffsType, OnTheRight> HouseholderSequenceType;\n  static inline const EssentialVectorType essentialVector(const HouseholderSequenceType& h, Index k)\n  {\n    Index start = k+1+h.m_shift;\n    return Block<const VectorsType,1,Dynamic>(h.m_vectors, k, start, 1, h.rows()-start).transpose();\n  }\n};\n\ntemplate<typename OtherScalarType, typename MatrixType> struct matrix_type_times_scalar_type\n{\n  typedef typename ScalarBinaryOpTraits<OtherScalarType, typename MatrixType::Scalar>::ReturnType\n    ResultScalar;\n  typedef Matrix<ResultScalar, MatrixType::RowsAtCompileTime, MatrixType::ColsAtCompileTime,\n                 0, MatrixType::MaxRowsAtCompileTime, MatrixType::MaxColsAtCompileTime> Type;\n};\n\n} // end namespace internal\n\ntemplate<typename VectorsType, typename CoeffsType, int Side> class HouseholderSequence\n  : public EigenBase<HouseholderSequence<VectorsType,CoeffsType,Side> >\n{\n    typedef typename internal::hseq_side_dependent_impl<VectorsType,CoeffsType,Side>::EssentialVectorType EssentialVectorType;\n\n  public:\n    enum {\n      RowsAtCompileTime = internal::traits<HouseholderSequence>::RowsAtCompileTime,\n      ColsAtCompileTime = internal::traits<HouseholderSequence>::ColsAtCompileTime,\n      MaxRowsAtCompileTime = internal::traits<HouseholderSequence>::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = internal::traits<HouseholderSequence>::MaxColsAtCompileTime\n    };\n    typedef typename internal::traits<HouseholderSequence>::Scalar Scalar;\n\n    typedef HouseholderSequence<\n      typename internal::conditional<NumTraits<Scalar>::IsComplex,\n        typename internal::remove_all<typename VectorsType::ConjugateReturnType>::type,\n        VectorsType>::type,\n      typename internal::conditional<NumTraits<Scalar>::IsComplex,\n        typename internal::remove_all<typename CoeffsType::ConjugateReturnType>::type,\n        CoeffsType>::type,\n      Side\n    > ConjugateReturnType;\n\n    typedef HouseholderSequence<\n      VectorsType,\n      typename internal::conditional<NumTraits<Scalar>::IsComplex,\n        typename internal::remove_all<typename CoeffsType::ConjugateReturnType>::type,\n        CoeffsType>::type,\n      Side\n    > AdjointReturnType;\n\n    typedef HouseholderSequence<\n      typename internal::conditional<NumTraits<Scalar>::IsComplex,\n        typename internal::remove_all<typename VectorsType::ConjugateReturnType>::type,\n        VectorsType>::type,\n      CoeffsType,\n      Side\n    > TransposeReturnType;\n\n    typedef HouseholderSequence<\n      typename internal::add_const<VectorsType>::type,\n      typename internal::add_const<CoeffsType>::type,\n      Side\n    > ConstHouseholderSequence;\n\n    /** \\brief Constructor.\n      * \\param[in]  v      %Matrix containing the essential parts of the Householder vectors\n      * \\param[in]  h      Vector containing the Householder coefficients\n      *\n      * Constructs the Householder sequence with coefficients given by \\p h and vectors given by \\p v. The\n      * i-th Householder coefficient \\f$ h_i \\f$ is given by \\p h(i) and the essential part of the i-th\n      * Householder vector \\f$ v_i \\f$ is given by \\p v(k,i) with \\p k > \\p i (the subdiagonal part of the\n      * i-th column). If \\p v has fewer columns than rows, then the Householder sequence contains as many\n      * Householder reflections as there are columns.\n      *\n      * \\note The %HouseholderSequence object stores \\p v and \\p h by reference.\n      *\n      * Example: \\include HouseholderSequence_HouseholderSequence.cpp\n      * Output: \\verbinclude HouseholderSequence_HouseholderSequence.out\n      *\n      * \\sa setLength(), setShift()\n      */\n    EIGEN_DEVICE_FUNC\n    HouseholderSequence(const VectorsType& v, const CoeffsType& h)\n      : m_vectors(v), m_coeffs(h), m_reverse(false), m_length(v.diagonalSize()),\n        m_shift(0)\n    {\n    }\n\n    /** \\brief Copy constructor. */\n    EIGEN_DEVICE_FUNC\n    HouseholderSequence(const HouseholderSequence& other)\n      : m_vectors(other.m_vectors),\n        m_coeffs(other.m_coeffs),\n        m_reverse(other.m_reverse),\n        m_length(other.m_length),\n        m_shift(other.m_shift)\n    {\n    }\n\n    /** \\brief Number of rows of transformation viewed as a matrix.\n      * \\returns Number of rows\n      * \\details This equals the dimension of the space that the transformation acts on.\n      */\n    EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR\n    Index rows() const EIGEN_NOEXCEPT { return Side==OnTheLeft ? m_vectors.rows() : m_vectors.cols(); }\n\n    /** \\brief Number of columns of transformation viewed as a matrix.\n      * \\returns Number of columns\n      * \\details This equals the dimension of the space that the transformation acts on.\n      */\n    EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR\n    Index cols() const EIGEN_NOEXCEPT { return rows(); }\n\n    /** \\brief Essential part of a Householder vector.\n      * \\param[in]  k  Index of Householder reflection\n      * \\returns    Vector containing non-trivial entries of k-th Householder vector\n      *\n      * This function returns the essential part of the Householder vector \\f$ v_i \\f$. This is a vector of\n      * length \\f$ n-i \\f$ containing the last \\f$ n-i \\f$ entries of the vector\n      * \\f[\n      * v_i = [\\underbrace{0, \\ldots, 0}_{i-1\\mbox{ zeros}}, 1, \\underbrace{*, \\ldots,*}_{n-i\\mbox{ arbitrary entries}} ].\n      * \\f]\n      * The index \\f$ i \\f$ equals \\p k + shift(), corresponding to the k-th column of the matrix \\p v\n      * passed to the constructor.\n      *\n      * \\sa setShift(), shift()\n      */\n    EIGEN_DEVICE_FUNC\n    const EssentialVectorType essentialVector(Index k) const\n    {\n      eigen_assert(k >= 0 && k < m_length);\n      return internal::hseq_side_dependent_impl<VectorsType,CoeffsType,Side>::essentialVector(*this, k);\n    }\n\n    /** \\brief %Transpose of the Householder sequence. */\n    TransposeReturnType transpose() const\n    {\n      return TransposeReturnType(m_vectors.conjugate(), m_coeffs)\n              .setReverseFlag(!m_reverse)\n              .setLength(m_length)\n              .setShift(m_shift);\n    }\n\n    /** \\brief Complex conjugate of the Householder sequence. */\n    ConjugateReturnType conjugate() const\n    {\n      return ConjugateReturnType(m_vectors.conjugate(), m_coeffs.conjugate())\n             .setReverseFlag(m_reverse)\n             .setLength(m_length)\n             .setShift(m_shift);\n    }\n\n    /** \\returns an expression of the complex conjugate of \\c *this if Cond==true,\n     *           returns \\c *this otherwise.\n     */\n    template<bool Cond>\n    EIGEN_DEVICE_FUNC\n    inline typename internal::conditional<Cond,ConjugateReturnType,ConstHouseholderSequence>::type\n    conjugateIf() const\n    {\n      typedef typename internal::conditional<Cond,ConjugateReturnType,ConstHouseholderSequence>::type ReturnType;\n      return ReturnType(m_vectors.template conjugateIf<Cond>(), m_coeffs.template conjugateIf<Cond>());\n    }\n\n    /** \\brief Adjoint (conjugate transpose) of the Householder sequence. */\n    AdjointReturnType adjoint() const\n    {\n      return AdjointReturnType(m_vectors, m_coeffs.conjugate())\n              .setReverseFlag(!m_reverse)\n              .setLength(m_length)\n              .setShift(m_shift);\n    }\n\n    /** \\brief Inverse of the Householder sequence (equals the adjoint). */\n    AdjointReturnType inverse() const { return adjoint(); }\n\n    /** \\internal */\n    template<typename DestType>\n    inline EIGEN_DEVICE_FUNC\n    void evalTo(DestType& dst) const\n    {\n      Matrix<Scalar, DestType::RowsAtCompileTime, 1,\n             AutoAlign|ColMajor, DestType::MaxRowsAtCompileTime, 1> workspace(rows());\n      evalTo(dst, workspace);\n    }\n\n    /** \\internal */\n    template<typename Dest, typename Workspace>\n    EIGEN_DEVICE_FUNC\n    void evalTo(Dest& dst, Workspace& workspace) const\n    {\n      workspace.resize(rows());\n      Index vecs = m_length;\n      if(internal::is_same_dense(dst,m_vectors))\n      {\n        // in-place\n        dst.diagonal().setOnes();\n        dst.template triangularView<StrictlyUpper>().setZero();\n        for(Index k = vecs-1; k >= 0; --k)\n        {\n          Index cornerSize = rows() - k - m_shift;\n          if(m_reverse)\n            dst.bottomRightCorner(cornerSize, cornerSize)\n               .applyHouseholderOnTheRight(essentialVector(k), m_coeffs.coeff(k), workspace.data());\n          else\n            dst.bottomRightCorner(cornerSize, cornerSize)\n               .applyHouseholderOnTheLeft(essentialVector(k), m_coeffs.coeff(k), workspace.data());\n\n          // clear the off diagonal vector\n          dst.col(k).tail(rows()-k-1).setZero();\n        }\n        // clear the remaining columns if needed\n        for(Index k = 0; k<cols()-vecs ; ++k)\n          dst.col(k).tail(rows()-k-1).setZero();\n      }\n      else if(m_length>BlockSize)\n      {\n        dst.setIdentity(rows(), rows());\n        if(m_reverse)\n          applyThisOnTheLeft(dst,workspace,true);\n        else\n          applyThisOnTheLeft(dst,workspace,true);\n      }\n      else\n      {\n        dst.setIdentity(rows(), rows());\n        for(Index k = vecs-1; k >= 0; --k)\n        {\n          Index cornerSize = rows() - k - m_shift;\n          if(m_reverse)\n            dst.bottomRightCorner(cornerSize, cornerSize)\n               .applyHouseholderOnTheRight(essentialVector(k), m_coeffs.coeff(k), workspace.data());\n          else\n            dst.bottomRightCorner(cornerSize, cornerSize)\n               .applyHouseholderOnTheLeft(essentialVector(k), m_coeffs.coeff(k), workspace.data());\n        }\n      }\n    }\n\n    /** \\internal */\n    template<typename Dest> inline void applyThisOnTheRight(Dest& dst) const\n    {\n      Matrix<Scalar,1,Dest::RowsAtCompileTime,RowMajor,1,Dest::MaxRowsAtCompileTime> workspace(dst.rows());\n      applyThisOnTheRight(dst, workspace);\n    }\n\n    /** \\internal */\n    template<typename Dest, typename Workspace>\n    inline void applyThisOnTheRight(Dest& dst, Workspace& workspace) const\n    {\n      workspace.resize(dst.rows());\n      for(Index k = 0; k < m_length; ++k)\n      {\n        Index actual_k = m_reverse ? m_length-k-1 : k;\n        dst.rightCols(rows()-m_shift-actual_k)\n           .applyHouseholderOnTheRight(essentialVector(actual_k), m_coeffs.coeff(actual_k), workspace.data());\n      }\n    }\n\n    /** \\internal */\n    template<typename Dest> inline void applyThisOnTheLeft(Dest& dst, bool inputIsIdentity = false) const\n    {\n      Matrix<Scalar,1,Dest::ColsAtCompileTime,RowMajor,1,Dest::MaxColsAtCompileTime> workspace;\n      applyThisOnTheLeft(dst, workspace, inputIsIdentity);\n    }\n\n    /** \\internal */\n    template<typename Dest, typename Workspace>\n    inline void applyThisOnTheLeft(Dest& dst, Workspace& workspace, bool inputIsIdentity = false) const\n    {\n      if(inputIsIdentity && m_reverse)\n        inputIsIdentity = false;\n      // if the entries are large enough, then apply the reflectors by block\n      if(m_length>=BlockSize && dst.cols()>1)\n      {\n        // Make sure we have at least 2 useful blocks, otherwise it is point-less:\n        Index blockSize = m_length<Index(2*BlockSize) ? (m_length+1)/2 : Index(BlockSize);\n        for(Index i = 0; i < m_length; i+=blockSize)\n        {\n          Index end = m_reverse ? (std::min)(m_length,i+blockSize) : m_length-i;\n          Index k = m_reverse ? i : (std::max)(Index(0),end-blockSize);\n          Index bs = end-k;\n          Index start = k + m_shift;\n\n          typedef Block<typename internal::remove_all<VectorsType>::type,Dynamic,Dynamic> SubVectorsType;\n          SubVectorsType sub_vecs1(m_vectors.const_cast_derived(), Side==OnTheRight ? k : start,\n                                                                   Side==OnTheRight ? start : k,\n                                                                   Side==OnTheRight ? bs : m_vectors.rows()-start,\n                                                                   Side==OnTheRight ? m_vectors.cols()-start : bs);\n          typename internal::conditional<Side==OnTheRight, Transpose<SubVectorsType>, SubVectorsType&>::type sub_vecs(sub_vecs1);\n\n          Index dstStart = dst.rows()-rows()+m_shift+k;\n          Index dstRows  = rows()-m_shift-k;\n          Block<Dest,Dynamic,Dynamic> sub_dst(dst,\n                                              dstStart,\n                                              inputIsIdentity ? dstStart : 0,\n                                              dstRows,\n                                              inputIsIdentity ? dstRows : dst.cols());\n          apply_block_householder_on_the_left(sub_dst, sub_vecs, m_coeffs.segment(k, bs), !m_reverse);\n        }\n      }\n      else\n      {\n        workspace.resize(dst.cols());\n        for(Index k = 0; k < m_length; ++k)\n        {\n          Index actual_k = m_reverse ? k : m_length-k-1;\n          Index dstStart = rows()-m_shift-actual_k;\n          dst.bottomRightCorner(dstStart, inputIsIdentity ? dstStart : dst.cols())\n            .applyHouseholderOnTheLeft(essentialVector(actual_k), m_coeffs.coeff(actual_k), workspace.data());\n        }\n      }\n    }\n\n    /** \\brief Computes the product of a Householder sequence with a matrix.\n      * \\param[in]  other  %Matrix being multiplied.\n      * \\returns    Expression object representing the product.\n      *\n      * This function computes \\f$ HM \\f$ where \\f$ H \\f$ is the Householder sequence represented by \\p *this\n      * and \\f$ M \\f$ is the matrix \\p other.\n      */\n    template<typename OtherDerived>\n    typename internal::matrix_type_times_scalar_type<Scalar, OtherDerived>::Type operator*(const MatrixBase<OtherDerived>& other) const\n    {\n      typename internal::matrix_type_times_scalar_type<Scalar, OtherDerived>::Type\n        res(other.template cast<typename internal::matrix_type_times_scalar_type<Scalar,OtherDerived>::ResultScalar>());\n      applyThisOnTheLeft(res, internal::is_identity<OtherDerived>::value && res.rows()==res.cols());\n      return res;\n    }\n\n    template<typename VectorsType_, typename CoeffsType_, int Side_> friend struct internal::hseq_side_dependent_impl;\n\n    /** \\brief Sets the length of the Householder sequence.\n      * \\param [in]  length  New value for the length.\n      *\n      * By default, the length \\f$ n \\f$ of the Householder sequence \\f$ H = H_0 H_1 \\ldots H_{n-1} \\f$ is set\n      * to the number of columns of the matrix \\p v passed to the constructor, or the number of rows if that\n      * is smaller. After this function is called, the length equals \\p length.\n      *\n      * \\sa length()\n      */\n    EIGEN_DEVICE_FUNC\n    HouseholderSequence& setLength(Index length)\n    {\n      m_length = length;\n      return *this;\n    }\n\n    /** \\brief Sets the shift of the Householder sequence.\n      * \\param [in]  shift  New value for the shift.\n      *\n      * By default, a %HouseholderSequence object represents \\f$ H = H_0 H_1 \\ldots H_{n-1} \\f$ and the i-th\n      * column of the matrix \\p v passed to the constructor corresponds to the i-th Householder\n      * reflection. After this function is called, the object represents \\f$ H = H_{\\mathrm{shift}}\n      * H_{\\mathrm{shift}+1} \\ldots H_{n-1} \\f$ and the i-th column of \\p v corresponds to the (shift+i)-th\n      * Householder reflection.\n      *\n      * \\sa shift()\n      */\n    EIGEN_DEVICE_FUNC\n    HouseholderSequence& setShift(Index shift)\n    {\n      m_shift = shift;\n      return *this;\n    }\n\n    EIGEN_DEVICE_FUNC\n    Index length() const { return m_length; }  /**< \\brief Returns the length of the Householder sequence. */\n\n    EIGEN_DEVICE_FUNC\n    Index shift() const { return m_shift; }    /**< \\brief Returns the shift of the Householder sequence. */\n\n    /* Necessary for .adjoint() and .conjugate() */\n    template <typename VectorsType2, typename CoeffsType2, int Side2> friend class HouseholderSequence;\n\n  protected:\n\n    /** \\internal\n      * \\brief Sets the reverse flag.\n      * \\param [in]  reverse  New value of the reverse flag.\n      *\n      * By default, the reverse flag is not set. If the reverse flag is set, then this object represents\n      * \\f$ H^r = H_{n-1} \\ldots H_1 H_0 \\f$ instead of \\f$ H = H_0 H_1 \\ldots H_{n-1} \\f$.\n      * \\note For real valued HouseholderSequence this is equivalent to transposing \\f$ H \\f$.\n      *\n      * \\sa reverseFlag(), transpose(), adjoint()\n      */\n    HouseholderSequence& setReverseFlag(bool reverse)\n    {\n      m_reverse = reverse;\n      return *this;\n    }\n\n    bool reverseFlag() const { return m_reverse; }     /**< \\internal \\brief Returns the reverse flag. */\n\n    typename VectorsType::Nested m_vectors;\n    typename CoeffsType::Nested m_coeffs;\n    bool m_reverse;\n    Index m_length;\n    Index m_shift;\n    enum { BlockSize = 48 };\n};\n\n/** \\brief Computes the product of a matrix with a Householder sequence.\n  * \\param[in]  other  %Matrix being multiplied.\n  * \\param[in]  h      %HouseholderSequence being multiplied.\n  * \\returns    Expression object representing the product.\n  *\n  * This function computes \\f$ MH \\f$ where \\f$ M \\f$ is the matrix \\p other and \\f$ H \\f$ is the\n  * Householder sequence represented by \\p h.\n  */\ntemplate<typename OtherDerived, typename VectorsType, typename CoeffsType, int Side>\ntypename internal::matrix_type_times_scalar_type<typename VectorsType::Scalar,OtherDerived>::Type operator*(const MatrixBase<OtherDerived>& other, const HouseholderSequence<VectorsType,CoeffsType,Side>& h)\n{\n  typename internal::matrix_type_times_scalar_type<typename VectorsType::Scalar,OtherDerived>::Type\n    res(other.template cast<typename internal::matrix_type_times_scalar_type<typename VectorsType::Scalar,OtherDerived>::ResultScalar>());\n  h.applyThisOnTheRight(res);\n  return res;\n}\n\n/** \\ingroup Householder_Module \\householder_module\n  * \\brief Convenience function for constructing a Householder sequence.\n  * \\returns A HouseholderSequence constructed from the specified arguments.\n  */\ntemplate<typename VectorsType, typename CoeffsType>\nHouseholderSequence<VectorsType,CoeffsType> householderSequence(const VectorsType& v, const CoeffsType& h)\n{\n  return HouseholderSequence<VectorsType,CoeffsType,OnTheLeft>(v, h);\n}\n\n/** \\ingroup Householder_Module \\householder_module\n  * \\brief Convenience function for constructing a Householder sequence.\n  * \\returns A HouseholderSequence constructed from the specified arguments.\n  * \\details This function differs from householderSequence() in that the template argument \\p OnTheSide of\n  * the constructed HouseholderSequence is set to OnTheRight, instead of the default OnTheLeft.\n  */\ntemplate<typename VectorsType, typename CoeffsType>\nHouseholderSequence<VectorsType,CoeffsType,OnTheRight> rightHouseholderSequence(const VectorsType& v, const CoeffsType& h)\n{\n  return HouseholderSequence<VectorsType,CoeffsType,OnTheRight>(v, h);\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_HOUSEHOLDER_SEQUENCE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BASIC_PRECONDITIONERS_H\n#define EIGEN_BASIC_PRECONDITIONERS_H\n\nnamespace Eigen {\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\brief A preconditioner based on the digonal entries\n  *\n  * This class allows to approximately solve for A.x = b problems assuming A is a diagonal matrix.\n  * In other words, this preconditioner neglects all off diagonal entries and, in Eigen's language, solves for:\n    \\code\n    A.diagonal().asDiagonal() . x = b\n    \\endcode\n  *\n  * \\tparam Scalar_ the type of the scalar.\n  *\n  * \\implsparsesolverconcept\n  *\n  * This preconditioner is suitable for both selfadjoint and general problems.\n  * The diagonal entries are pre-inverted and stored into a dense vector.\n  *\n  * \\note A variant that has yet to be implemented would attempt to preserve the norm of each column.\n  *\n  * \\sa class LeastSquareDiagonalPreconditioner, class ConjugateGradient\n  */\ntemplate <typename Scalar_>\nclass DiagonalPreconditioner\n{\n    typedef Scalar_ Scalar;\n    typedef Matrix<Scalar,Dynamic,1> Vector;\n  public:\n    typedef typename Vector::StorageIndex StorageIndex;\n    enum {\n      ColsAtCompileTime = Dynamic,\n      MaxColsAtCompileTime = Dynamic\n    };\n\n    DiagonalPreconditioner() : m_isInitialized(false) {}\n\n    template<typename MatType>\n    explicit DiagonalPreconditioner(const MatType& mat) : m_invdiag(mat.cols())\n    {\n      compute(mat);\n    }\n\n    EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_invdiag.size(); }\n    EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_invdiag.size(); }\n\n    template<typename MatType>\n    DiagonalPreconditioner& analyzePattern(const MatType& )\n    {\n      return *this;\n    }\n\n    template<typename MatType>\n    DiagonalPreconditioner& factorize(const MatType& mat)\n    {\n      m_invdiag.resize(mat.cols());\n      for(int j=0; j<mat.outerSize(); ++j)\n      {\n        typename MatType::InnerIterator it(mat,j);\n        while(it && it.index()!=j) ++it;\n        if(it && it.index()==j && it.value()!=Scalar(0))\n          m_invdiag(j) = Scalar(1)/it.value();\n        else\n          m_invdiag(j) = Scalar(1);\n      }\n      m_isInitialized = true;\n      return *this;\n    }\n\n    template<typename MatType>\n    DiagonalPreconditioner& compute(const MatType& mat)\n    {\n      return factorize(mat);\n    }\n\n    /** \\internal */\n    template<typename Rhs, typename Dest>\n    void _solve_impl(const Rhs& b, Dest& x) const\n    {\n      x = m_invdiag.array() * b.array() ;\n    }\n\n    template<typename Rhs> inline const Solve<DiagonalPreconditioner, Rhs>\n    solve(const MatrixBase<Rhs>& b) const\n    {\n      eigen_assert(m_isInitialized && \"DiagonalPreconditioner is not initialized.\");\n      eigen_assert(m_invdiag.size()==b.rows()\n                && \"DiagonalPreconditioner::solve(): invalid number of rows of the right hand side matrix b\");\n      return Solve<DiagonalPreconditioner, Rhs>(*this, b.derived());\n    }\n\n    ComputationInfo info() { return Success; }\n\n  protected:\n    Vector m_invdiag;\n    bool m_isInitialized;\n};\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\brief Jacobi preconditioner for LeastSquaresConjugateGradient\n  *\n  * This class allows to approximately solve for A' A x  = A' b problems assuming A' A is a diagonal matrix.\n  * In other words, this preconditioner neglects all off diagonal entries and, in Eigen's language, solves for:\n    \\code\n    (A.adjoint() * A).diagonal().asDiagonal() * x = b\n    \\endcode\n  *\n  * \\tparam Scalar_ the type of the scalar.\n  *\n  * \\implsparsesolverconcept\n  *\n  * The diagonal entries are pre-inverted and stored into a dense vector.\n  *\n  * \\sa class LeastSquaresConjugateGradient, class DiagonalPreconditioner\n  */\ntemplate <typename Scalar_>\nclass LeastSquareDiagonalPreconditioner : public DiagonalPreconditioner<Scalar_>\n{\n    typedef Scalar_ Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef DiagonalPreconditioner<Scalar_> Base;\n    using Base::m_invdiag;\n  public:\n\n    LeastSquareDiagonalPreconditioner() : Base() {}\n\n    template<typename MatType>\n    explicit LeastSquareDiagonalPreconditioner(const MatType& mat) : Base()\n    {\n      compute(mat);\n    }\n\n    template<typename MatType>\n    LeastSquareDiagonalPreconditioner& analyzePattern(const MatType& )\n    {\n      return *this;\n    }\n\n    template<typename MatType>\n    LeastSquareDiagonalPreconditioner& factorize(const MatType& mat)\n    {\n      // Compute the inverse squared-norm of each column of mat\n      m_invdiag.resize(mat.cols());\n      if(MatType::IsRowMajor)\n      {\n        m_invdiag.setZero();\n        for(Index j=0; j<mat.outerSize(); ++j)\n        {\n          for(typename MatType::InnerIterator it(mat,j); it; ++it)\n            m_invdiag(it.index()) += numext::abs2(it.value());\n        }\n        for(Index j=0; j<mat.cols(); ++j)\n          if(numext::real(m_invdiag(j))>RealScalar(0))\n            m_invdiag(j) = RealScalar(1)/numext::real(m_invdiag(j));\n      }\n      else\n      {\n        for(Index j=0; j<mat.outerSize(); ++j)\n        {\n          RealScalar sum = mat.col(j).squaredNorm();\n          if(sum>RealScalar(0))\n            m_invdiag(j) = RealScalar(1)/sum;\n          else\n            m_invdiag(j) = RealScalar(1);\n        }\n      }\n      Base::m_isInitialized = true;\n      return *this;\n    }\n\n    template<typename MatType>\n    LeastSquareDiagonalPreconditioner& compute(const MatType& mat)\n    {\n      return factorize(mat);\n    }\n\n    ComputationInfo info() { return Success; }\n\n  protected:\n};\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\brief A naive preconditioner which approximates any matrix as the identity matrix\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa class DiagonalPreconditioner\n  */\nclass IdentityPreconditioner\n{\n  public:\n\n    IdentityPreconditioner() {}\n\n    template<typename MatrixType>\n    explicit IdentityPreconditioner(const MatrixType& ) {}\n\n    template<typename MatrixType>\n    IdentityPreconditioner& analyzePattern(const MatrixType& ) { return *this; }\n\n    template<typename MatrixType>\n    IdentityPreconditioner& factorize(const MatrixType& ) { return *this; }\n\n    template<typename MatrixType>\n    IdentityPreconditioner& compute(const MatrixType& ) { return *this; }\n\n    template<typename Rhs>\n    inline const Rhs& solve(const Rhs& b) const { return b; }\n\n    ComputationInfo info() { return Success; }\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_BASIC_PRECONDITIONERS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BICGSTAB_H\n#define EIGEN_BICGSTAB_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\internal Low-level bi conjugate gradient stabilized algorithm\n  * \\param mat The matrix A\n  * \\param rhs The right hand side vector b\n  * \\param x On input and initial solution, on output the computed solution.\n  * \\param precond A preconditioner being able to efficiently solve for an\n  *                approximation of Ax=b (regardless of b)\n  * \\param iters On input the max number of iteration, on output the number of performed iterations.\n  * \\param tol_error On input the tolerance error, on output an estimation of the relative error.\n  * \\return false in the case of numerical issue, for example a break down of BiCGSTAB. \n  */\ntemplate<typename MatrixType, typename Rhs, typename Dest, typename Preconditioner>\nbool bicgstab(const MatrixType& mat, const Rhs& rhs, Dest& x,\n              const Preconditioner& precond, Index& iters,\n              typename Dest::RealScalar& tol_error)\n{\n  using std::sqrt;\n  using std::abs;\n  typedef typename Dest::RealScalar RealScalar;\n  typedef typename Dest::Scalar Scalar;\n  typedef Matrix<Scalar,Dynamic,1> VectorType;\n  RealScalar tol = tol_error;\n  Index maxIters = iters;\n\n  Index n = mat.cols();\n  VectorType r  = rhs - mat * x;\n  VectorType r0 = r;\n  \n  RealScalar r0_sqnorm = r0.squaredNorm();\n  RealScalar rhs_sqnorm = rhs.squaredNorm();\n  if(rhs_sqnorm == 0)\n  {\n    x.setZero();\n    return true;\n  }\n  Scalar rho    = 1;\n  Scalar alpha  = 1;\n  Scalar w      = 1;\n  \n  VectorType v = VectorType::Zero(n), p = VectorType::Zero(n);\n  VectorType y(n),  z(n);\n  VectorType kt(n), ks(n);\n\n  VectorType s(n), t(n);\n\n  RealScalar tol2 = tol*tol*rhs_sqnorm;\n  RealScalar eps2 = NumTraits<Scalar>::epsilon()*NumTraits<Scalar>::epsilon();\n  Index i = 0;\n  Index restarts = 0;\n\n  while ( r.squaredNorm() > tol2 && i<maxIters )\n  {\n    Scalar rho_old = rho;\n\n    rho = r0.dot(r);\n    if (abs(rho) < eps2*r0_sqnorm)\n    {\n      // The new residual vector became too orthogonal to the arbitrarily chosen direction r0\n      // Let's restart with a new r0:\n      r  = rhs - mat * x;\n      r0 = r;\n      rho = r0_sqnorm = r.squaredNorm();\n      if(restarts++ == 0)\n        i = 0;\n    }\n    Scalar beta = (rho/rho_old) * (alpha / w);\n    p = r + beta * (p - w * v);\n    \n    y = precond.solve(p);\n    \n    v.noalias() = mat * y;\n\n    alpha = rho / r0.dot(v);\n    s = r - alpha * v;\n\n    z = precond.solve(s);\n    t.noalias() = mat * z;\n\n    RealScalar tmp = t.squaredNorm();\n    if(tmp>RealScalar(0))\n      w = t.dot(s) / tmp;\n    else\n      w = Scalar(0);\n    x += alpha * y + w * z;\n    r = s - w * t;\n    ++i;\n  }\n  tol_error = sqrt(r.squaredNorm()/rhs_sqnorm);\n  iters = i;\n  return true; \n}\n\n}\n\ntemplate< typename MatrixType_,\n          typename Preconditioner_ = DiagonalPreconditioner<typename MatrixType_::Scalar> >\nclass BiCGSTAB;\n\nnamespace internal {\n\ntemplate< typename MatrixType_, typename Preconditioner_>\nstruct traits<BiCGSTAB<MatrixType_,Preconditioner_> >\n{\n  typedef MatrixType_ MatrixType;\n  typedef Preconditioner_ Preconditioner;\n};\n\n}\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\brief A bi conjugate gradient stabilized solver for sparse square problems\n  *\n  * This class allows to solve for A.x = b sparse linear problems using a bi conjugate gradient\n  * stabilized algorithm. The vectors x and b can be either dense or sparse.\n  *\n  * \\tparam MatrixType_ the type of the sparse matrix A, can be a dense or a sparse matrix.\n  * \\tparam Preconditioner_ the type of the preconditioner. Default is DiagonalPreconditioner\n  *\n  * \\implsparsesolverconcept\n  *\n  * The maximal number of iterations and tolerance value can be controlled via the setMaxIterations()\n  * and setTolerance() methods. The defaults are the size of the problem for the maximal number of iterations\n  * and NumTraits<Scalar>::epsilon() for the tolerance.\n  * \n  * The tolerance corresponds to the relative residual error: |Ax-b|/|b|\n  * \n  * \\b Performance: when using sparse matrices, best performance is achied for a row-major sparse matrix format.\n  * Moreover, in this case multi-threading can be exploited if the user code is compiled with OpenMP enabled.\n  * See \\ref TopicMultiThreading for details.\n  * \n  * This class can be used as the direct solver classes. Here is a typical usage example:\n  * \\include BiCGSTAB_simple.cpp\n  * \n  * By default the iterations start with x=0 as an initial guess of the solution.\n  * One can control the start using the solveWithGuess() method.\n  * \n  * BiCGSTAB can also be used in a matrix-free context, see the following \\link MatrixfreeSolverExample example \\endlink.\n  *\n  * \\sa class SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner\n  */\ntemplate< typename MatrixType_, typename Preconditioner_>\nclass BiCGSTAB : public IterativeSolverBase<BiCGSTAB<MatrixType_,Preconditioner_> >\n{\n  typedef IterativeSolverBase<BiCGSTAB> Base;\n  using Base::matrix;\n  using Base::m_error;\n  using Base::m_iterations;\n  using Base::m_info;\n  using Base::m_isInitialized;\npublic:\n  typedef MatrixType_ MatrixType;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef Preconditioner_ Preconditioner;\n\npublic:\n\n  /** Default constructor. */\n  BiCGSTAB() : Base() {}\n\n  /** Initialize the solver with matrix \\a A for further \\c Ax=b solving.\n    * \n    * This constructor is a shortcut for the default constructor followed\n    * by a call to compute().\n    * \n    * \\warning this class stores a reference to the matrix A as well as some\n    * precomputed values that depend on it. Therefore, if \\a A is changed\n    * this class becomes invalid. Call compute() to update it with the new\n    * matrix A, or modify a copy of A.\n    */\n  template<typename MatrixDerived>\n  explicit BiCGSTAB(const EigenBase<MatrixDerived>& A) : Base(A.derived()) {}\n\n  ~BiCGSTAB() {}\n\n  /** \\internal */\n  template<typename Rhs,typename Dest>\n  void _solve_vector_with_guess_impl(const Rhs& b, Dest& x) const\n  {    \n    m_iterations = Base::maxIterations();\n    m_error = Base::m_tolerance;\n    \n    bool ret = internal::bicgstab(matrix(), b, x, Base::m_preconditioner, m_iterations, m_error);\n\n    m_info = (!ret) ? NumericalIssue\n           : m_error <= Base::m_tolerance ? Success\n           : NoConvergence;\n  }\n\nprotected:\n\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_BICGSTAB_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CONJUGATE_GRADIENT_H\n#define EIGEN_CONJUGATE_GRADIENT_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\internal Low-level conjugate gradient algorithm\n  * \\param mat The matrix A\n  * \\param rhs The right hand side vector b\n  * \\param x On input and initial solution, on output the computed solution.\n  * \\param precond A preconditioner being able to efficiently solve for an\n  *                approximation of Ax=b (regardless of b)\n  * \\param iters On input the max number of iteration, on output the number of performed iterations.\n  * \\param tol_error On input the tolerance error, on output an estimation of the relative error.\n  */\ntemplate<typename MatrixType, typename Rhs, typename Dest, typename Preconditioner>\nEIGEN_DONT_INLINE\nvoid conjugate_gradient(const MatrixType& mat, const Rhs& rhs, Dest& x,\n                        const Preconditioner& precond, Index& iters,\n                        typename Dest::RealScalar& tol_error)\n{\n  using std::sqrt;\n  using std::abs;\n  typedef typename Dest::RealScalar RealScalar;\n  typedef typename Dest::Scalar Scalar;\n  typedef Matrix<Scalar,Dynamic,1> VectorType;\n  \n  RealScalar tol = tol_error;\n  Index maxIters = iters;\n  \n  Index n = mat.cols();\n\n  VectorType residual = rhs - mat * x; //initial residual\n\n  RealScalar rhsNorm2 = rhs.squaredNorm();\n  if(rhsNorm2 == 0) \n  {\n    x.setZero();\n    iters = 0;\n    tol_error = 0;\n    return;\n  }\n  const RealScalar considerAsZero = (std::numeric_limits<RealScalar>::min)();\n  RealScalar threshold = numext::maxi(RealScalar(tol*tol*rhsNorm2),considerAsZero);\n  RealScalar residualNorm2 = residual.squaredNorm();\n  if (residualNorm2 < threshold)\n  {\n    iters = 0;\n    tol_error = sqrt(residualNorm2 / rhsNorm2);\n    return;\n  }\n\n  VectorType p(n);\n  p = precond.solve(residual);      // initial search direction\n\n  VectorType z(n), tmp(n);\n  RealScalar absNew = numext::real(residual.dot(p));  // the square of the absolute value of r scaled by invM\n  Index i = 0;\n  while(i < maxIters)\n  {\n    tmp.noalias() = mat * p;                    // the bottleneck of the algorithm\n\n    Scalar alpha = absNew / p.dot(tmp);         // the amount we travel on dir\n    x += alpha * p;                             // update solution\n    residual -= alpha * tmp;                    // update residual\n    \n    residualNorm2 = residual.squaredNorm();\n    if(residualNorm2 < threshold)\n      break;\n    \n    z = precond.solve(residual);                // approximately solve for \"A z = residual\"\n\n    RealScalar absOld = absNew;\n    absNew = numext::real(residual.dot(z));     // update the absolute value of r\n    RealScalar beta = absNew / absOld;          // calculate the Gram-Schmidt value used to create the new search direction\n    p = z + beta * p;                           // update search direction\n    i++;\n  }\n  tol_error = sqrt(residualNorm2 / rhsNorm2);\n  iters = i;\n}\n\n}\n\ntemplate< typename MatrixType_, int UpLo_=Lower,\n          typename Preconditioner_ = DiagonalPreconditioner<typename MatrixType_::Scalar> >\nclass ConjugateGradient;\n\nnamespace internal {\n\ntemplate< typename MatrixType_, int UpLo_, typename Preconditioner_>\nstruct traits<ConjugateGradient<MatrixType_,UpLo_,Preconditioner_> >\n{\n  typedef MatrixType_ MatrixType;\n  typedef Preconditioner_ Preconditioner;\n};\n\n}\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\brief A conjugate gradient solver for sparse (or dense) self-adjoint problems\n  *\n  * This class allows to solve for A.x = b linear problems using an iterative conjugate gradient algorithm.\n  * The matrix A must be selfadjoint. The matrix A and the vectors x and b can be either dense or sparse.\n  *\n  * \\tparam MatrixType_ the type of the matrix A, can be a dense or a sparse matrix.\n  * \\tparam UpLo_ the triangular part that will be used for the computations. It can be Lower,\n  *               \\c Upper, or \\c Lower|Upper in which the full matrix entries will be considered.\n  *               Default is \\c Lower, best performance is \\c Lower|Upper.\n  * \\tparam Preconditioner_ the type of the preconditioner. Default is DiagonalPreconditioner\n  *\n  * \\implsparsesolverconcept\n  *\n  * The maximal number of iterations and tolerance value can be controlled via the setMaxIterations()\n  * and setTolerance() methods. The defaults are the size of the problem for the maximal number of iterations\n  * and NumTraits<Scalar>::epsilon() for the tolerance.\n  * \n  * The tolerance corresponds to the relative residual error: |Ax-b|/|b|\n  * \n  * \\b Performance: Even though the default value of \\c UpLo_ is \\c Lower, significantly higher performance is\n  * achieved when using a complete matrix and \\b Lower|Upper as the \\a UpLo_ template parameter. Moreover, in this\n  * case multi-threading can be exploited if the user code is compiled with OpenMP enabled.\n  * See \\ref TopicMultiThreading for details.\n  * \n  * This class can be used as the direct solver classes. Here is a typical usage example:\n    \\code\n    int n = 10000;\n    VectorXd x(n), b(n);\n    SparseMatrix<double> A(n,n);\n    // fill A and b\n    ConjugateGradient<SparseMatrix<double>, Lower|Upper> cg;\n    cg.compute(A);\n    x = cg.solve(b);\n    std::cout << \"#iterations:     \" << cg.iterations() << std::endl;\n    std::cout << \"estimated error: \" << cg.error()      << std::endl;\n    // update b, and solve again\n    x = cg.solve(b);\n    \\endcode\n  * \n  * By default the iterations start with x=0 as an initial guess of the solution.\n  * One can control the start using the solveWithGuess() method.\n  * \n  * ConjugateGradient can also be used in a matrix-free context, see the following \\link MatrixfreeSolverExample example \\endlink.\n  *\n  * \\sa class LeastSquaresConjugateGradient, class SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner\n  */\ntemplate< typename MatrixType_, int UpLo_, typename Preconditioner_>\nclass ConjugateGradient : public IterativeSolverBase<ConjugateGradient<MatrixType_,UpLo_,Preconditioner_> >\n{\n  typedef IterativeSolverBase<ConjugateGradient> Base;\n  using Base::matrix;\n  using Base::m_error;\n  using Base::m_iterations;\n  using Base::m_info;\n  using Base::m_isInitialized;\npublic:\n  typedef MatrixType_ MatrixType;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef Preconditioner_ Preconditioner;\n\n  enum {\n    UpLo = UpLo_\n  };\n\npublic:\n\n  /** Default constructor. */\n  ConjugateGradient() : Base() {}\n\n  /** Initialize the solver with matrix \\a A for further \\c Ax=b solving.\n    * \n    * This constructor is a shortcut for the default constructor followed\n    * by a call to compute().\n    * \n    * \\warning this class stores a reference to the matrix A as well as some\n    * precomputed values that depend on it. Therefore, if \\a A is changed\n    * this class becomes invalid. Call compute() to update it with the new\n    * matrix A, or modify a copy of A.\n    */\n  template<typename MatrixDerived>\n  explicit ConjugateGradient(const EigenBase<MatrixDerived>& A) : Base(A.derived()) {}\n\n  ~ConjugateGradient() {}\n\n  /** \\internal */\n  template<typename Rhs,typename Dest>\n  void _solve_vector_with_guess_impl(const Rhs& b, Dest& x) const\n  {\n    typedef typename Base::MatrixWrapper MatrixWrapper;\n    typedef typename Base::ActualMatrixType ActualMatrixType;\n    enum {\n      TransposeInput  =   (!MatrixWrapper::MatrixFree)\n                      &&  (UpLo==(Lower|Upper))\n                      &&  (!MatrixType::IsRowMajor)\n                      &&  (!NumTraits<Scalar>::IsComplex)\n    };\n    typedef typename internal::conditional<TransposeInput,Transpose<const ActualMatrixType>, ActualMatrixType const&>::type RowMajorWrapper;\n    EIGEN_STATIC_ASSERT(EIGEN_IMPLIES(MatrixWrapper::MatrixFree,UpLo==(Lower|Upper)),MATRIX_FREE_CONJUGATE_GRADIENT_IS_COMPATIBLE_WITH_UPPER_UNION_LOWER_MODE_ONLY);\n    typedef typename internal::conditional<UpLo==(Lower|Upper),\n                                           RowMajorWrapper,\n                                           typename MatrixWrapper::template ConstSelfAdjointViewReturnType<UpLo>::Type\n                                          >::type SelfAdjointWrapper;\n\n    m_iterations = Base::maxIterations();\n    m_error = Base::m_tolerance;\n\n    RowMajorWrapper row_mat(matrix());\n    internal::conjugate_gradient(SelfAdjointWrapper(row_mat), b, x, Base::m_preconditioner, m_iterations, m_error);\n    m_info = m_error <= Base::m_tolerance ? Success : NoConvergence;\n  }\n\nprotected:\n\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CONJUGATE_GRADIENT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/IterativeLinearSolvers/IncompleteCholesky.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_INCOMPLETE_CHOlESKY_H\n#define EIGEN_INCOMPLETE_CHOlESKY_H\n\n#include <vector>\n#include <list>\n\nnamespace Eigen {\n/**\n  * \\brief Modified Incomplete Cholesky with dual threshold\n  *\n  * References : C-J. Lin and J. J. Moré, Incomplete Cholesky Factorizations with\n  *              Limited memory, SIAM J. Sci. Comput.  21(1), pp. 24-45, 1999\n  *\n  * \\tparam Scalar the scalar type of the input matrices\n  * \\tparam UpLo_ The triangular part that will be used for the computations. It can be Lower\n    *               or Upper. Default is Lower.\n  * \\tparam OrderingType_ The ordering method to use, either AMDOrdering<> or NaturalOrdering<>. Default is AMDOrdering<int>,\n  *                       unless EIGEN_MPL2_ONLY is defined, in which case the default is NaturalOrdering<int>.\n  *\n  * \\implsparsesolverconcept\n  *\n  * It performs the following incomplete factorization: \\f$ S P A P' S \\approx L L' \\f$\n  * where L is a lower triangular factor, S is a diagonal scaling matrix, and P is a\n  * fill-in reducing permutation as computed by the ordering method.\n  *\n  * \\b Shifting \\b strategy: Let \\f$ B = S P A P' S \\f$  be the scaled matrix on which the factorization is carried out,\n  * and \\f$ \\beta \\f$ be the minimum value of the diagonal. If \\f$ \\beta > 0 \\f$ then, the factorization is directly performed\n  * on the matrix B. Otherwise, the factorization is performed on the shifted matrix \\f$ B + (\\sigma+|\\beta| I \\f$ where\n  * \\f$ \\sigma \\f$ is the initial shift value as returned and set by setInitialShift() method. The default value is \\f$ \\sigma = 10^{-3} \\f$.\n  * If the factorization fails, then the shift in doubled until it succeed or a maximum of ten attempts. If it still fails, as returned by\n  * the info() method, then you can either increase the initial shift, or better use another preconditioning technique.\n  *\n  */\ntemplate <typename Scalar, int UpLo_ = Lower, typename OrderingType_ = AMDOrdering<int> >\nclass IncompleteCholesky : public SparseSolverBase<IncompleteCholesky<Scalar,UpLo_,OrderingType_> >\n{\n  protected:\n    typedef SparseSolverBase<IncompleteCholesky<Scalar,UpLo_,OrderingType_> > Base;\n    using Base::m_isInitialized;\n  public:\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef OrderingType_ OrderingType;\n    typedef typename OrderingType::PermutationType PermutationType;\n    typedef typename PermutationType::StorageIndex StorageIndex;\n    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> FactorType;\n    typedef Matrix<Scalar,Dynamic,1> VectorSx;\n    typedef Matrix<RealScalar,Dynamic,1> VectorRx;\n    typedef Matrix<StorageIndex,Dynamic, 1> VectorIx;\n    typedef std::vector<std::list<StorageIndex> > VectorList;\n    enum { UpLo = UpLo_ };\n    enum {\n      ColsAtCompileTime = Dynamic,\n      MaxColsAtCompileTime = Dynamic\n    };\n  public:\n\n    /** Default constructor leaving the object in a partly non-initialized stage.\n      *\n      * You must call compute() or the pair analyzePattern()/factorize() to make it valid.\n      *\n      * \\sa IncompleteCholesky(const MatrixType&)\n      */\n    IncompleteCholesky() : m_initialShift(1e-3),m_analysisIsOk(false),m_factorizationIsOk(false) {}\n\n    /** Constructor computing the incomplete factorization for the given matrix \\a matrix.\n      */\n    template<typename MatrixType>\n    IncompleteCholesky(const MatrixType& matrix) : m_initialShift(1e-3),m_analysisIsOk(false),m_factorizationIsOk(false)\n    {\n      compute(matrix);\n    }\n\n    /** \\returns number of rows of the factored matrix */\n    EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_L.rows(); }\n\n    /** \\returns number of columns of the factored matrix */\n    EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_L.cols(); }\n\n\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * It triggers an assertion if \\c *this has not been initialized through the respective constructor,\n      * or a call to compute() or analyzePattern().\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the matrix appears to be negative.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"IncompleteCholesky is not initialized.\");\n      return m_info;\n    }\n\n    /** \\brief Set the initial shift parameter \\f$ \\sigma \\f$.\n      */\n    void setInitialShift(RealScalar shift) { m_initialShift = shift; }\n\n    /** \\brief Computes the fill reducing permutation vector using the sparsity pattern of \\a mat\n      */\n    template<typename MatrixType>\n    void analyzePattern(const MatrixType& mat)\n    {\n      OrderingType ord;\n      PermutationType pinv;\n      ord(mat.template selfadjointView<UpLo>(), pinv);\n      if(pinv.size()>0) m_perm = pinv.inverse();\n      else              m_perm.resize(0);\n      m_L.resize(mat.rows(), mat.cols());\n      m_analysisIsOk = true;\n      m_isInitialized = true;\n      m_info = Success;\n    }\n\n    /** \\brief Performs the numerical factorization of the input matrix \\a mat\n      *\n      * The method analyzePattern() or compute() must have been called beforehand\n      * with a matrix having the same pattern.\n      *\n      * \\sa compute(), analyzePattern()\n      */\n    template<typename MatrixType>\n    void factorize(const MatrixType& mat);\n\n    /** Computes or re-computes the incomplete Cholesky factorization of the input matrix \\a mat\n      *\n      * It is a shortcut for a sequential call to the analyzePattern() and factorize() methods.\n      *\n      * \\sa analyzePattern(), factorize()\n      */\n    template<typename MatrixType>\n    void compute(const MatrixType& mat)\n    {\n      analyzePattern(mat);\n      factorize(mat);\n    }\n\n    // internal\n    template<typename Rhs, typename Dest>\n    void _solve_impl(const Rhs& b, Dest& x) const\n    {\n      eigen_assert(m_factorizationIsOk && \"factorize() should be called first\");\n      if (m_perm.rows() == b.rows())  x = m_perm * b;\n      else                            x = b;\n      x = m_scale.asDiagonal() * x;\n      x = m_L.template triangularView<Lower>().solve(x);\n      x = m_L.adjoint().template triangularView<Upper>().solve(x);\n      x = m_scale.asDiagonal() * x;\n      if (m_perm.rows() == b.rows())\n        x = m_perm.inverse() * x;\n    }\n\n    /** \\returns the sparse lower triangular factor L */\n    const FactorType& matrixL() const { eigen_assert(\"m_factorizationIsOk\"); return m_L; }\n\n    /** \\returns a vector representing the scaling factor S */\n    const VectorRx& scalingS() const { eigen_assert(\"m_factorizationIsOk\"); return m_scale; }\n\n    /** \\returns the fill-in reducing permutation P (can be empty for a natural ordering) */\n    const PermutationType& permutationP() const { eigen_assert(\"m_analysisIsOk\"); return m_perm; }\n\n  protected:\n    FactorType m_L;              // The lower part stored in CSC\n    VectorRx m_scale;            // The vector for scaling the matrix\n    RealScalar m_initialShift;   // The initial shift parameter\n    bool m_analysisIsOk;\n    bool m_factorizationIsOk;\n    ComputationInfo m_info;\n    PermutationType m_perm;\n\n  private:\n    inline void updateList(Ref<const VectorIx> colPtr, Ref<VectorIx> rowIdx, Ref<VectorSx> vals, const Index& col, const Index& jk, VectorIx& firstElt, VectorList& listCol);\n};\n\n// Based on the following paper:\n//   C-J. Lin and J. J. Moré, Incomplete Cholesky Factorizations with\n//   Limited memory, SIAM J. Sci. Comput.  21(1), pp. 24-45, 1999\n//   http://ftp.mcs.anl.gov/pub/tech_reports/reports/P682.pdf\ntemplate<typename Scalar, int UpLo_, typename OrderingType>\ntemplate<typename MatrixType_>\nvoid IncompleteCholesky<Scalar,UpLo_, OrderingType>::factorize(const MatrixType_& mat)\n{\n  using std::sqrt;\n  eigen_assert(m_analysisIsOk && \"analyzePattern() should be called first\");\n\n  // Dropping strategy : Keep only the p largest elements per column, where p is the number of elements in the column of the original matrix. Other strategies will be added\n\n  // Apply the fill-reducing permutation computed in analyzePattern()\n  if (m_perm.rows() == mat.rows() ) // To detect the null permutation\n  {\n    // The temporary is needed to make sure that the diagonal entry is properly sorted\n    FactorType tmp(mat.rows(), mat.cols());\n    tmp = mat.template selfadjointView<UpLo_>().twistedBy(m_perm);\n    m_L.template selfadjointView<Lower>() = tmp.template selfadjointView<Lower>();\n  }\n  else\n  {\n    m_L.template selfadjointView<Lower>() = mat.template selfadjointView<UpLo_>();\n  }\n\n  Index n = m_L.cols();\n  Index nnz = m_L.nonZeros();\n  Map<VectorSx> vals(m_L.valuePtr(), nnz);         //values\n  Map<VectorIx> rowIdx(m_L.innerIndexPtr(), nnz);  //Row indices\n  Map<VectorIx> colPtr( m_L.outerIndexPtr(), n+1); // Pointer to the beginning of each row\n  VectorIx firstElt(n-1); // for each j, points to the next entry in vals that will be used in the factorization\n  VectorList listCol(n);  // listCol(j) is a linked list of columns to update column j\n  VectorSx col_vals(n);   // Store a  nonzero values in each column\n  VectorIx col_irow(n);   // Row indices of nonzero elements in each column\n  VectorIx col_pattern(n);\n  col_pattern.fill(-1);\n  StorageIndex col_nnz;\n\n\n  // Computes the scaling factors\n  m_scale.resize(n);\n  m_scale.setZero();\n  for (Index j = 0; j < n; j++)\n    for (Index k = colPtr[j]; k < colPtr[j+1]; k++)\n    {\n      m_scale(j) += numext::abs2(vals(k));\n      if(rowIdx[k]!=j)\n        m_scale(rowIdx[k]) += numext::abs2(vals(k));\n    }\n\n  m_scale = m_scale.cwiseSqrt().cwiseSqrt();\n\n  for (Index j = 0; j < n; ++j)\n    if(m_scale(j)>(std::numeric_limits<RealScalar>::min)())\n      m_scale(j) = RealScalar(1)/m_scale(j);\n    else\n      m_scale(j) = 1;\n\n  // TODO disable scaling if not needed, i.e., if it is roughly uniform? (this will make solve() faster)\n\n  // Scale and compute the shift for the matrix\n  RealScalar mindiag = NumTraits<RealScalar>::highest();\n  for (Index j = 0; j < n; j++)\n  {\n    for (Index k = colPtr[j]; k < colPtr[j+1]; k++)\n      vals[k] *= (m_scale(j)*m_scale(rowIdx[k]));\n    eigen_internal_assert(rowIdx[colPtr[j]]==j && \"IncompleteCholesky: only the lower triangular part must be stored\");\n    mindiag = numext::mini(numext::real(vals[colPtr[j]]), mindiag);\n  }\n\n  FactorType L_save = m_L;\n\n  RealScalar shift = 0;\n  if(mindiag <= RealScalar(0.))\n    shift = m_initialShift - mindiag;\n\n  m_info = NumericalIssue;\n\n  // Try to perform the incomplete factorization using the current shift\n  int iter = 0;\n  do\n  {\n    // Apply the shift to the diagonal elements of the matrix\n    for (Index j = 0; j < n; j++)\n      vals[colPtr[j]] += shift;\n\n    // jki version of the Cholesky factorization\n    Index j=0;\n    for (; j < n; ++j)\n    {\n      // Left-looking factorization of the j-th column\n      // First, load the j-th column into col_vals\n      Scalar diag = vals[colPtr[j]];  // It is assumed that only the lower part is stored\n      col_nnz = 0;\n      for (Index i = colPtr[j] + 1; i < colPtr[j+1]; i++)\n      {\n        StorageIndex l = rowIdx[i];\n        col_vals(col_nnz) = vals[i];\n        col_irow(col_nnz) = l;\n        col_pattern(l) = col_nnz;\n        col_nnz++;\n      }\n      {\n        typename std::list<StorageIndex>::iterator k;\n        // Browse all previous columns that will update column j\n        for(k = listCol[j].begin(); k != listCol[j].end(); k++)\n        {\n          Index jk = firstElt(*k); // First element to use in the column\n          eigen_internal_assert(rowIdx[jk]==j);\n          Scalar v_j_jk = numext::conj(vals[jk]);\n\n          jk += 1;\n          for (Index i = jk; i < colPtr[*k+1]; i++)\n          {\n            StorageIndex l = rowIdx[i];\n            if(col_pattern[l]<0)\n            {\n              col_vals(col_nnz) = vals[i] * v_j_jk;\n              col_irow[col_nnz] = l;\n              col_pattern(l) = col_nnz;\n              col_nnz++;\n            }\n            else\n              col_vals(col_pattern[l]) -= vals[i] * v_j_jk;\n          }\n          updateList(colPtr,rowIdx,vals, *k, jk, firstElt, listCol);\n        }\n      }\n\n      // Scale the current column\n      if(numext::real(diag) <= 0)\n      {\n        if(++iter>=10)\n          return;\n\n        // increase shift\n        shift = numext::maxi(m_initialShift,RealScalar(2)*shift);\n        // restore m_L, col_pattern, and listCol\n        vals = Map<const VectorSx>(L_save.valuePtr(), nnz);\n        rowIdx = Map<const VectorIx>(L_save.innerIndexPtr(), nnz);\n        colPtr = Map<const VectorIx>(L_save.outerIndexPtr(), n+1);\n        col_pattern.fill(-1);\n        for(Index i=0; i<n; ++i)\n          listCol[i].clear();\n\n        break;\n      }\n\n      RealScalar rdiag = sqrt(numext::real(diag));\n      vals[colPtr[j]] = rdiag;\n      for (Index k = 0; k<col_nnz; ++k)\n      {\n        Index i = col_irow[k];\n        //Scale\n        col_vals(k) /= rdiag;\n        //Update the remaining diagonals with col_vals\n        vals[colPtr[i]] -= numext::abs2(col_vals(k));\n      }\n      // Select the largest p elements\n      // p is the original number of elements in the column (without the diagonal)\n      Index p = colPtr[j+1] - colPtr[j] - 1 ;\n      Ref<VectorSx> cvals = col_vals.head(col_nnz);\n      Ref<VectorIx> cirow = col_irow.head(col_nnz);\n      internal::QuickSplit(cvals,cirow, p);\n      // Insert the largest p elements in the matrix\n      Index cpt = 0;\n      for (Index i = colPtr[j]+1; i < colPtr[j+1]; i++)\n      {\n        vals[i] = col_vals(cpt);\n        rowIdx[i] = col_irow(cpt);\n        // restore col_pattern:\n        col_pattern(col_irow(cpt)) = -1;\n        cpt++;\n      }\n      // Get the first smallest row index and put it after the diagonal element\n      Index jk = colPtr(j)+1;\n      updateList(colPtr,rowIdx,vals,j,jk,firstElt,listCol);\n    }\n\n    if(j==n)\n    {\n      m_factorizationIsOk = true;\n      m_info = Success;\n    }\n  } while(m_info!=Success);\n}\n\ntemplate<typename Scalar, int UpLo_, typename OrderingType>\ninline void IncompleteCholesky<Scalar,UpLo_, OrderingType>::updateList(Ref<const VectorIx> colPtr, Ref<VectorIx> rowIdx, Ref<VectorSx> vals, const Index& col, const Index& jk, VectorIx& firstElt, VectorList& listCol)\n{\n  if (jk < colPtr(col+1) )\n  {\n    Index p = colPtr(col+1) - jk;\n    Index minpos;\n    rowIdx.segment(jk,p).minCoeff(&minpos);\n    minpos += jk;\n    if (rowIdx(minpos) != rowIdx(jk))\n    {\n      //Swap\n      std::swap(rowIdx(jk),rowIdx(minpos));\n      std::swap(vals(jk),vals(minpos));\n    }\n    firstElt(col) = internal::convert_index<StorageIndex,Index>(jk);\n    listCol[rowIdx(jk)].push_back(internal::convert_index<StorageIndex,Index>(col));\n  }\n}\n\n} // end namespace Eigen\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/IterativeLinearSolvers/IncompleteLUT.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_INCOMPLETE_LUT_H\n#define EIGEN_INCOMPLETE_LUT_H\n\n\nnamespace Eigen {\n\nnamespace internal {\n\n/** \\internal\n  * Compute a quick-sort split of a vector\n  * On output, the vector row is permuted such that its elements satisfy\n  * abs(row(i)) >= abs(row(ncut)) if i<ncut\n  * abs(row(i)) <= abs(row(ncut)) if i>ncut\n  * \\param row The vector of values\n  * \\param ind The array of index for the elements in @p row\n  * \\param ncut  The number of largest elements to keep\n  **/\ntemplate <typename VectorV, typename VectorI>\nIndex QuickSplit(VectorV &row, VectorI &ind, Index ncut)\n{\n  typedef typename VectorV::RealScalar RealScalar;\n  using std::swap;\n  using std::abs;\n  Index mid;\n  Index n = row.size(); /* length of the vector */\n  Index first, last ;\n\n  ncut--; /* to fit the zero-based indices */\n  first = 0;\n  last = n-1;\n  if (ncut < first || ncut > last ) return 0;\n\n  do {\n    mid = first;\n    RealScalar abskey = abs(row(mid));\n    for (Index j = first + 1; j <= last; j++) {\n      if ( abs(row(j)) > abskey) {\n        ++mid;\n        swap(row(mid), row(j));\n        swap(ind(mid), ind(j));\n      }\n    }\n    /* Interchange for the pivot element */\n    swap(row(mid), row(first));\n    swap(ind(mid), ind(first));\n\n    if (mid > ncut) last = mid - 1;\n    else if (mid < ncut ) first = mid + 1;\n  } while (mid != ncut );\n\n  return 0; /* mid is equal to ncut */\n}\n\n}// end namespace internal\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\class IncompleteLUT\n  * \\brief Incomplete LU factorization with dual-threshold strategy\n  *\n  * \\implsparsesolverconcept\n  *\n  * During the numerical factorization, two dropping rules are used :\n  *  1) any element whose magnitude is less than some tolerance is dropped.\n  *    This tolerance is obtained by multiplying the input tolerance @p droptol\n  *    by the average magnitude of all the original elements in the current row.\n  *  2) After the elimination of the row, only the @p fill largest elements in\n  *    the L part and the @p fill largest elements in the U part are kept\n  *    (in addition to the diagonal element ). Note that @p fill is computed from\n  *    the input parameter @p fillfactor which is used the ratio to control the fill_in\n  *    relatively to the initial number of nonzero elements.\n  *\n  * The two extreme cases are when @p droptol=0 (to keep all the @p fill*2 largest elements)\n  * and when @p fill=n/2 with @p droptol being different to zero.\n  *\n  * References : Yousef Saad, ILUT: A dual threshold incomplete LU factorization,\n  *              Numerical Linear Algebra with Applications, 1(4), pp 387-402, 1994.\n  *\n  * NOTE : The following implementation is derived from the ILUT implementation\n  * in the SPARSKIT package, Copyright (C) 2005, the Regents of the University of Minnesota\n  *  released under the terms of the GNU LGPL:\n  *    http://www-users.cs.umn.edu/~saad/software/SPARSKIT/README\n  * However, Yousef Saad gave us permission to relicense his ILUT code to MPL2.\n  * See the Eigen mailing list archive, thread: ILUT, date: July 8, 2012:\n  *   http://listengine.tuxfamily.org/lists.tuxfamily.org/eigen/2012/07/msg00064.html\n  * alternatively, on GMANE:\n  *   http://comments.gmane.org/gmane.comp.lib.eigen/3302\n  */\ntemplate <typename Scalar_, typename StorageIndex_ = int>\nclass IncompleteLUT : public SparseSolverBase<IncompleteLUT<Scalar_, StorageIndex_> >\n{\n  protected:\n    typedef SparseSolverBase<IncompleteLUT> Base;\n    using Base::m_isInitialized;\n  public:\n    typedef Scalar_ Scalar;\n    typedef StorageIndex_ StorageIndex;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef Matrix<Scalar,Dynamic,1> Vector;\n    typedef Matrix<StorageIndex,Dynamic,1> VectorI;\n    typedef SparseMatrix<Scalar,RowMajor,StorageIndex> FactorType;\n\n    enum {\n      ColsAtCompileTime = Dynamic,\n      MaxColsAtCompileTime = Dynamic\n    };\n\n  public:\n\n    IncompleteLUT()\n      : m_droptol(NumTraits<Scalar>::dummy_precision()), m_fillfactor(10),\n        m_analysisIsOk(false), m_factorizationIsOk(false)\n    {}\n\n    template<typename MatrixType>\n    explicit IncompleteLUT(const MatrixType& mat, const RealScalar& droptol=NumTraits<Scalar>::dummy_precision(), int fillfactor = 10)\n      : m_droptol(droptol),m_fillfactor(fillfactor),\n        m_analysisIsOk(false),m_factorizationIsOk(false)\n    {\n      eigen_assert(fillfactor != 0);\n      compute(mat);\n    }\n\n    EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return m_lu.rows(); }\n\n    EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return m_lu.cols(); }\n\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the matrix.appears to be negative.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"IncompleteLUT is not initialized.\");\n      return m_info;\n    }\n\n    template<typename MatrixType>\n    void analyzePattern(const MatrixType& amat);\n\n    template<typename MatrixType>\n    void factorize(const MatrixType& amat);\n\n    /**\n      * Compute an incomplete LU factorization with dual threshold on the matrix mat\n      * No pivoting is done in this version\n      *\n      **/\n    template<typename MatrixType>\n    IncompleteLUT& compute(const MatrixType& amat)\n    {\n      analyzePattern(amat);\n      factorize(amat);\n      return *this;\n    }\n\n    void setDroptol(const RealScalar& droptol);\n    void setFillfactor(int fillfactor);\n\n    template<typename Rhs, typename Dest>\n    void _solve_impl(const Rhs& b, Dest& x) const\n    {\n      x = m_Pinv * b;\n      x = m_lu.template triangularView<UnitLower>().solve(x);\n      x = m_lu.template triangularView<Upper>().solve(x);\n      x = m_P * x;\n    }\n\nprotected:\n\n    /** keeps off-diagonal entries; drops diagonal entries */\n    struct keep_diag {\n      inline bool operator() (const Index& row, const Index& col, const Scalar&) const\n      {\n        return row!=col;\n      }\n    };\n\nprotected:\n\n    FactorType m_lu;\n    RealScalar m_droptol;\n    int m_fillfactor;\n    bool m_analysisIsOk;\n    bool m_factorizationIsOk;\n    ComputationInfo m_info;\n    PermutationMatrix<Dynamic,Dynamic,StorageIndex> m_P;     // Fill-reducing permutation\n    PermutationMatrix<Dynamic,Dynamic,StorageIndex> m_Pinv;  // Inverse permutation\n};\n\n/**\n * Set control parameter droptol\n *  \\param droptol   Drop any element whose magnitude is less than this tolerance\n **/\ntemplate<typename Scalar, typename StorageIndex>\nvoid IncompleteLUT<Scalar,StorageIndex>::setDroptol(const RealScalar& droptol)\n{\n  this->m_droptol = droptol;\n}\n\n/**\n * Set control parameter fillfactor\n * \\param fillfactor  This is used to compute the  number @p fill_in of largest elements to keep on each row.\n **/\ntemplate<typename Scalar, typename StorageIndex>\nvoid IncompleteLUT<Scalar,StorageIndex>::setFillfactor(int fillfactor)\n{\n  this->m_fillfactor = fillfactor;\n}\n\ntemplate <typename Scalar, typename StorageIndex>\ntemplate<typename MatrixType_>\nvoid IncompleteLUT<Scalar,StorageIndex>::analyzePattern(const MatrixType_& amat)\n{\n  // Compute the Fill-reducing permutation\n  // Since ILUT does not perform any numerical pivoting,\n  // it is highly preferable to keep the diagonal through symmetric permutations.\n  // To this end, let's symmetrize the pattern and perform AMD on it.\n  SparseMatrix<Scalar,ColMajor, StorageIndex> mat1 = amat;\n  SparseMatrix<Scalar,ColMajor, StorageIndex> mat2 = amat.transpose();\n  // FIXME for a matrix with nearly symmetric pattern, mat2+mat1 is the appropriate choice.\n  //       on the other hand for a really non-symmetric pattern, mat2*mat1 should be preferred...\n  SparseMatrix<Scalar,ColMajor, StorageIndex> AtA = mat2 + mat1;\n  AMDOrdering<StorageIndex> ordering;\n  ordering(AtA,m_P);\n  m_Pinv  = m_P.inverse(); // cache the inverse permutation\n  m_analysisIsOk = true;\n  m_factorizationIsOk = false;\n  m_isInitialized = true;\n}\n\ntemplate <typename Scalar, typename StorageIndex>\ntemplate<typename MatrixType_>\nvoid IncompleteLUT<Scalar,StorageIndex>::factorize(const MatrixType_& amat)\n{\n  using std::sqrt;\n  using std::swap;\n  using std::abs;\n  using internal::convert_index;\n\n  eigen_assert((amat.rows() == amat.cols()) && \"The factorization should be done on a square matrix\");\n  Index n = amat.cols();  // Size of the matrix\n  m_lu.resize(n,n);\n  // Declare Working vectors and variables\n  Vector u(n) ;     // real values of the row -- maximum size is n --\n  VectorI ju(n);   // column position of the values in u -- maximum size  is n\n  VectorI jr(n);   // Indicate the position of the nonzero elements in the vector u -- A zero location is indicated by -1\n\n  // Apply the fill-reducing permutation\n  eigen_assert(m_analysisIsOk && \"You must first call analyzePattern()\");\n  SparseMatrix<Scalar,RowMajor, StorageIndex> mat;\n  mat = amat.twistedBy(m_Pinv);\n\n  // Initialization\n  jr.fill(-1);\n  ju.fill(0);\n  u.fill(0);\n\n  // number of largest elements to keep in each row:\n  Index fill_in = (amat.nonZeros()*m_fillfactor)/n + 1;\n  if (fill_in > n) fill_in = n;\n\n  // number of largest nonzero elements to keep in the L and the U part of the current row:\n  Index nnzL = fill_in/2;\n  Index nnzU = nnzL;\n  m_lu.reserve(n * (nnzL + nnzU + 1));\n\n  // global loop over the rows of the sparse matrix\n  for (Index ii = 0; ii < n; ii++)\n  {\n    // 1 - copy the lower and the upper part of the row i of mat in the working vector u\n\n    Index sizeu = 1; // number of nonzero elements in the upper part of the current row\n    Index sizel = 0; // number of nonzero elements in the lower part of the current row\n    ju(ii)    = convert_index<StorageIndex>(ii);\n    u(ii)     = 0;\n    jr(ii)    = convert_index<StorageIndex>(ii);\n    RealScalar rownorm = 0;\n\n    typename FactorType::InnerIterator j_it(mat, ii); // Iterate through the current row ii\n    for (; j_it; ++j_it)\n    {\n      Index k = j_it.index();\n      if (k < ii)\n      {\n        // copy the lower part\n        ju(sizel) = convert_index<StorageIndex>(k);\n        u(sizel) = j_it.value();\n        jr(k) = convert_index<StorageIndex>(sizel);\n        ++sizel;\n      }\n      else if (k == ii)\n      {\n        u(ii) = j_it.value();\n      }\n      else\n      {\n        // copy the upper part\n        Index jpos = ii + sizeu;\n        ju(jpos) = convert_index<StorageIndex>(k);\n        u(jpos) = j_it.value();\n        jr(k) = convert_index<StorageIndex>(jpos);\n        ++sizeu;\n      }\n      rownorm += numext::abs2(j_it.value());\n    }\n\n    // 2 - detect possible zero row\n    if(rownorm==0)\n    {\n      m_info = NumericalIssue;\n      return;\n    }\n    // Take the 2-norm of the current row as a relative tolerance\n    rownorm = sqrt(rownorm);\n\n    // 3 - eliminate the previous nonzero rows\n    Index jj = 0;\n    Index len = 0;\n    while (jj < sizel)\n    {\n      // In order to eliminate in the correct order,\n      // we must select first the smallest column index among  ju(jj:sizel)\n      Index k;\n      Index minrow = ju.segment(jj,sizel-jj).minCoeff(&k); // k is relative to the segment\n      k += jj;\n      if (minrow != ju(jj))\n      {\n        // swap the two locations\n        Index j = ju(jj);\n        swap(ju(jj), ju(k));\n        jr(minrow) = convert_index<StorageIndex>(jj);\n        jr(j) = convert_index<StorageIndex>(k);\n        swap(u(jj), u(k));\n      }\n      // Reset this location\n      jr(minrow) = -1;\n\n      // Start elimination\n      typename FactorType::InnerIterator ki_it(m_lu, minrow);\n      while (ki_it && ki_it.index() < minrow) ++ki_it;\n      eigen_internal_assert(ki_it && ki_it.col()==minrow);\n      Scalar fact = u(jj) / ki_it.value();\n\n      // drop too small elements\n      if(abs(fact) <= m_droptol)\n      {\n        jj++;\n        continue;\n      }\n\n      // linear combination of the current row ii and the row minrow\n      ++ki_it;\n      for (; ki_it; ++ki_it)\n      {\n        Scalar prod = fact * ki_it.value();\n        Index j     = ki_it.index();\n        Index jpos  = jr(j);\n        if (jpos == -1) // fill-in element\n        {\n          Index newpos;\n          if (j >= ii) // dealing with the upper part\n          {\n            newpos = ii + sizeu;\n            sizeu++;\n            eigen_internal_assert(sizeu<=n);\n          }\n          else // dealing with the lower part\n          {\n            newpos = sizel;\n            sizel++;\n            eigen_internal_assert(sizel<=ii);\n          }\n          ju(newpos) = convert_index<StorageIndex>(j);\n          u(newpos) = -prod;\n          jr(j) = convert_index<StorageIndex>(newpos);\n        }\n        else\n          u(jpos) -= prod;\n      }\n      // store the pivot element\n      u(len)  = fact;\n      ju(len) = convert_index<StorageIndex>(minrow);\n      ++len;\n\n      jj++;\n    } // end of the elimination on the row ii\n\n    // reset the upper part of the pointer jr to zero\n    for(Index k = 0; k <sizeu; k++) jr(ju(ii+k)) = -1;\n\n    // 4 - partially sort and insert the elements in the m_lu matrix\n\n    // sort the L-part of the row\n    sizel = len;\n    len = (std::min)(sizel, nnzL);\n    typename Vector::SegmentReturnType ul(u.segment(0, sizel));\n    typename VectorI::SegmentReturnType jul(ju.segment(0, sizel));\n    internal::QuickSplit(ul, jul, len);\n\n    // store the largest m_fill elements of the L part\n    m_lu.startVec(ii);\n    for(Index k = 0; k < len; k++)\n      m_lu.insertBackByOuterInnerUnordered(ii,ju(k)) = u(k);\n\n    // store the diagonal element\n    // apply a shifting rule to avoid zero pivots (we are doing an incomplete factorization)\n    if (u(ii) == Scalar(0))\n      u(ii) = sqrt(m_droptol) * rownorm;\n    m_lu.insertBackByOuterInnerUnordered(ii, ii) = u(ii);\n\n    // sort the U-part of the row\n    // apply the dropping rule first\n    len = 0;\n    for(Index k = 1; k < sizeu; k++)\n    {\n      if(abs(u(ii+k)) > m_droptol * rownorm )\n      {\n        ++len;\n        u(ii + len)  = u(ii + k);\n        ju(ii + len) = ju(ii + k);\n      }\n    }\n    sizeu = len + 1; // +1 to take into account the diagonal element\n    len = (std::min)(sizeu, nnzU);\n    typename Vector::SegmentReturnType uu(u.segment(ii+1, sizeu-1));\n    typename VectorI::SegmentReturnType juu(ju.segment(ii+1, sizeu-1));\n    internal::QuickSplit(uu, juu, len);\n\n    // store the largest elements of the U part\n    for(Index k = ii + 1; k < ii + len; k++)\n      m_lu.insertBackByOuterInnerUnordered(ii,ju(k)) = u(k);\n  }\n  m_lu.finalize();\n  m_lu.makeCompressed();\n\n  m_factorizationIsOk = true;\n  m_info = Success;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_INCOMPLETE_LUT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ITERATIVE_SOLVER_BASE_H\n#define EIGEN_ITERATIVE_SOLVER_BASE_H\n\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate<typename MatrixType>\nstruct is_ref_compatible_impl\n{\nprivate:\n  template <typename T0>\n  struct any_conversion\n  {\n    template <typename T> any_conversion(const volatile T&);\n    template <typename T> any_conversion(T&);\n  };\n  struct yes {int a[1];};\n  struct no  {int a[2];};\n\n  template<typename T>\n  static yes test(const Ref<const T>&, int);\n  template<typename T>\n  static no  test(any_conversion<T>, ...);\n\npublic:\n  static MatrixType ms_from;\n  enum { value = sizeof(test<MatrixType>(ms_from, 0))==sizeof(yes) };\n};\n\ntemplate<typename MatrixType>\nstruct is_ref_compatible\n{\n  enum { value = is_ref_compatible_impl<typename remove_all<MatrixType>::type>::value };\n};\n\ntemplate<typename MatrixType, bool MatrixFree = !internal::is_ref_compatible<MatrixType>::value>\nclass generic_matrix_wrapper;\n\n// We have an explicit matrix at hand, compatible with Ref<>\ntemplate<typename MatrixType>\nclass generic_matrix_wrapper<MatrixType,false>\n{\npublic:\n  typedef Ref<const MatrixType> ActualMatrixType;\n  template<int UpLo> struct ConstSelfAdjointViewReturnType {\n    typedef typename ActualMatrixType::template ConstSelfAdjointViewReturnType<UpLo>::Type Type;\n  };\n\n  enum {\n    MatrixFree = false\n  };\n\n  generic_matrix_wrapper()\n    : m_dummy(0,0), m_matrix(m_dummy)\n  {}\n\n  template<typename InputType>\n  generic_matrix_wrapper(const InputType &mat)\n    : m_matrix(mat)\n  {}\n\n  const ActualMatrixType& matrix() const\n  {\n    return m_matrix;\n  }\n\n  template<typename MatrixDerived>\n  void grab(const EigenBase<MatrixDerived> &mat)\n  {\n    m_matrix.~Ref<const MatrixType>();\n    ::new (&m_matrix) Ref<const MatrixType>(mat.derived());\n  }\n\n  void grab(const Ref<const MatrixType> &mat)\n  {\n    if(&(mat.derived()) != &m_matrix)\n    {\n      m_matrix.~Ref<const MatrixType>();\n      ::new (&m_matrix) Ref<const MatrixType>(mat);\n    }\n  }\n\nprotected:\n  MatrixType m_dummy; // used to default initialize the Ref<> object\n  ActualMatrixType m_matrix;\n};\n\n// MatrixType is not compatible with Ref<> -> matrix-free wrapper\ntemplate<typename MatrixType>\nclass generic_matrix_wrapper<MatrixType,true>\n{\npublic:\n  typedef MatrixType ActualMatrixType;\n  template<int UpLo> struct ConstSelfAdjointViewReturnType\n  {\n    typedef ActualMatrixType Type;\n  };\n\n  enum {\n    MatrixFree = true\n  };\n\n  generic_matrix_wrapper()\n    : mp_matrix(0)\n  {}\n\n  generic_matrix_wrapper(const MatrixType &mat)\n    : mp_matrix(&mat)\n  {}\n\n  const ActualMatrixType& matrix() const\n  {\n    return *mp_matrix;\n  }\n\n  void grab(const MatrixType &mat)\n  {\n    mp_matrix = &mat;\n  }\n\nprotected:\n  const ActualMatrixType *mp_matrix;\n};\n\n}\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\brief Base class for linear iterative solvers\n  *\n  * \\sa class SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner\n  */\ntemplate< typename Derived>\nclass IterativeSolverBase : public SparseSolverBase<Derived>\n{\nprotected:\n  typedef SparseSolverBase<Derived> Base;\n  using Base::m_isInitialized;\n\npublic:\n  typedef typename internal::traits<Derived>::MatrixType MatrixType;\n  typedef typename internal::traits<Derived>::Preconditioner Preconditioner;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::StorageIndex StorageIndex;\n  typedef typename MatrixType::RealScalar RealScalar;\n\n  enum {\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n    MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n  };\n\npublic:\n\n  using Base::derived;\n\n  /** Default constructor. */\n  IterativeSolverBase()\n  {\n    init();\n  }\n\n  /** Initialize the solver with matrix \\a A for further \\c Ax=b solving.\n    *\n    * This constructor is a shortcut for the default constructor followed\n    * by a call to compute().\n    *\n    * \\warning this class stores a reference to the matrix A as well as some\n    * precomputed values that depend on it. Therefore, if \\a A is changed\n    * this class becomes invalid. Call compute() to update it with the new\n    * matrix A, or modify a copy of A.\n    */\n  template<typename MatrixDerived>\n  explicit IterativeSolverBase(const EigenBase<MatrixDerived>& A)\n    : m_matrixWrapper(A.derived())\n  {\n    init();\n    compute(matrix());\n  }\n\n  ~IterativeSolverBase() {}\n\n  /** Initializes the iterative solver for the sparsity pattern of the matrix \\a A for further solving \\c Ax=b problems.\n    *\n    * Currently, this function mostly calls analyzePattern on the preconditioner. In the future\n    * we might, for instance, implement column reordering for faster matrix vector products.\n    */\n  template<typename MatrixDerived>\n  Derived& analyzePattern(const EigenBase<MatrixDerived>& A)\n  {\n    grab(A.derived());\n    m_preconditioner.analyzePattern(matrix());\n    m_isInitialized = true;\n    m_analysisIsOk = true;\n    m_info = m_preconditioner.info();\n    return derived();\n  }\n\n  /** Initializes the iterative solver with the numerical values of the matrix \\a A for further solving \\c Ax=b problems.\n    *\n    * Currently, this function mostly calls factorize on the preconditioner.\n    *\n    * \\warning this class stores a reference to the matrix A as well as some\n    * precomputed values that depend on it. Therefore, if \\a A is changed\n    * this class becomes invalid. Call compute() to update it with the new\n    * matrix A, or modify a copy of A.\n    */\n  template<typename MatrixDerived>\n  Derived& factorize(const EigenBase<MatrixDerived>& A)\n  {\n    eigen_assert(m_analysisIsOk && \"You must first call analyzePattern()\");\n    grab(A.derived());\n    m_preconditioner.factorize(matrix());\n    m_factorizationIsOk = true;\n    m_info = m_preconditioner.info();\n    return derived();\n  }\n\n  /** Initializes the iterative solver with the matrix \\a A for further solving \\c Ax=b problems.\n    *\n    * Currently, this function mostly initializes/computes the preconditioner. In the future\n    * we might, for instance, implement column reordering for faster matrix vector products.\n    *\n    * \\warning this class stores a reference to the matrix A as well as some\n    * precomputed values that depend on it. Therefore, if \\a A is changed\n    * this class becomes invalid. Call compute() to update it with the new\n    * matrix A, or modify a copy of A.\n    */\n  template<typename MatrixDerived>\n  Derived& compute(const EigenBase<MatrixDerived>& A)\n  {\n    grab(A.derived());\n    m_preconditioner.compute(matrix());\n    m_isInitialized = true;\n    m_analysisIsOk = true;\n    m_factorizationIsOk = true;\n    m_info = m_preconditioner.info();\n    return derived();\n  }\n\n  /** \\internal */\n  EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT { return matrix().rows(); }\n\n  /** \\internal */\n  EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT { return matrix().cols(); }\n\n  /** \\returns the tolerance threshold used by the stopping criteria.\n    * \\sa setTolerance()\n    */\n  RealScalar tolerance() const { return m_tolerance; }\n\n  /** Sets the tolerance threshold used by the stopping criteria.\n    *\n    * This value is used as an upper bound to the relative residual error: |Ax-b|/|b|.\n    * The default value is the machine precision given by NumTraits<Scalar>::epsilon()\n    */\n  Derived& setTolerance(const RealScalar& tolerance)\n  {\n    m_tolerance = tolerance;\n    return derived();\n  }\n\n  /** \\returns a read-write reference to the preconditioner for custom configuration. */\n  Preconditioner& preconditioner() { return m_preconditioner; }\n\n  /** \\returns a read-only reference to the preconditioner. */\n  const Preconditioner& preconditioner() const { return m_preconditioner; }\n\n  /** \\returns the max number of iterations.\n    * It is either the value set by setMaxIterations or, by default,\n    * twice the number of columns of the matrix.\n    */\n  Index maxIterations() const\n  {\n    return (m_maxIterations<0) ? 2*matrix().cols() : m_maxIterations;\n  }\n\n  /** Sets the max number of iterations.\n    * Default is twice the number of columns of the matrix.\n    */\n  Derived& setMaxIterations(Index maxIters)\n  {\n    m_maxIterations = maxIters;\n    return derived();\n  }\n\n  /** \\returns the number of iterations performed during the last solve */\n  Index iterations() const\n  {\n    eigen_assert(m_isInitialized && \"ConjugateGradient is not initialized.\");\n    return m_iterations;\n  }\n\n  /** \\returns the tolerance error reached during the last solve.\n    * It is a close approximation of the true relative residual error |Ax-b|/|b|.\n    */\n  RealScalar error() const\n  {\n    eigen_assert(m_isInitialized && \"ConjugateGradient is not initialized.\");\n    return m_error;\n  }\n\n  /** \\returns the solution x of \\f$ A x = b \\f$ using the current decomposition of A\n    * and \\a x0 as an initial solution.\n    *\n    * \\sa solve(), compute()\n    */\n  template<typename Rhs,typename Guess>\n  inline const SolveWithGuess<Derived, Rhs, Guess>\n  solveWithGuess(const MatrixBase<Rhs>& b, const Guess& x0) const\n  {\n    eigen_assert(m_isInitialized && \"Solver is not initialized.\");\n    eigen_assert(derived().rows()==b.rows() && \"solve(): invalid number of rows of the right hand side matrix b\");\n    return SolveWithGuess<Derived, Rhs, Guess>(derived(), b.derived(), x0);\n  }\n\n  /** \\returns Success if the iterations converged, and NoConvergence otherwise. */\n  ComputationInfo info() const\n  {\n    eigen_assert(m_isInitialized && \"IterativeSolverBase is not initialized.\");\n    return m_info;\n  }\n\n  /** \\internal */\n  template<typename Rhs, typename DestDerived>\n  void _solve_with_guess_impl(const Rhs& b, SparseMatrixBase<DestDerived> &aDest) const\n  {\n    eigen_assert(rows()==b.rows());\n\n    Index rhsCols = b.cols();\n    Index size = b.rows();\n    DestDerived& dest(aDest.derived());\n    typedef typename DestDerived::Scalar DestScalar;\n    Eigen::Matrix<DestScalar,Dynamic,1> tb(size);\n    Eigen::Matrix<DestScalar,Dynamic,1> tx(cols());\n    // We do not directly fill dest because sparse expressions have to be free of aliasing issue.\n    // For non square least-square problems, b and dest might not have the same size whereas they might alias each-other.\n    typename DestDerived::PlainObject tmp(cols(),rhsCols);\n    ComputationInfo global_info = Success;\n    for(Index k=0; k<rhsCols; ++k)\n    {\n      tb = b.col(k);\n      tx = dest.col(k);\n      derived()._solve_vector_with_guess_impl(tb,tx);\n      tmp.col(k) = tx.sparseView(0);\n\n      // The call to _solve_vector_with_guess_impl updates m_info, so if it failed for a previous column\n      // we need to restore it to the worst value.\n      if(m_info==NumericalIssue)\n        global_info = NumericalIssue;\n      else if(m_info==NoConvergence)\n        global_info = NoConvergence;\n    }\n    m_info = global_info;\n    dest.swap(tmp);\n  }\n\n  template<typename Rhs, typename DestDerived>\n  typename internal::enable_if<Rhs::ColsAtCompileTime!=1 && DestDerived::ColsAtCompileTime!=1>::type\n  _solve_with_guess_impl(const Rhs& b, MatrixBase<DestDerived> &aDest) const\n  {\n    eigen_assert(rows()==b.rows());\n\n    Index rhsCols = b.cols();\n    DestDerived& dest(aDest.derived());\n    ComputationInfo global_info = Success;\n    for(Index k=0; k<rhsCols; ++k)\n    {\n      typename DestDerived::ColXpr xk(dest,k);\n      typename Rhs::ConstColXpr bk(b,k);\n      derived()._solve_vector_with_guess_impl(bk,xk);\n\n      // The call to _solve_vector_with_guess updates m_info, so if it failed for a previous column\n      // we need to restore it to the worst value.\n      if(m_info==NumericalIssue)\n        global_info = NumericalIssue;\n      else if(m_info==NoConvergence)\n        global_info = NoConvergence;\n    }\n    m_info = global_info;\n  }\n\n  template<typename Rhs, typename DestDerived>\n  typename internal::enable_if<Rhs::ColsAtCompileTime==1 || DestDerived::ColsAtCompileTime==1>::type\n  _solve_with_guess_impl(const Rhs& b, MatrixBase<DestDerived> &dest) const\n  {\n    derived()._solve_vector_with_guess_impl(b,dest.derived());\n  }\n\n  /** \\internal default initial guess = 0 */\n  template<typename Rhs,typename Dest>\n  void _solve_impl(const Rhs& b, Dest& x) const\n  {\n    x.setZero();\n    derived()._solve_with_guess_impl(b,x);\n  }\n\nprotected:\n  void init()\n  {\n    m_isInitialized = false;\n    m_analysisIsOk = false;\n    m_factorizationIsOk = false;\n    m_maxIterations = -1;\n    m_tolerance = NumTraits<Scalar>::epsilon();\n  }\n\n  typedef internal::generic_matrix_wrapper<MatrixType> MatrixWrapper;\n  typedef typename MatrixWrapper::ActualMatrixType ActualMatrixType;\n\n  const ActualMatrixType& matrix() const\n  {\n    return m_matrixWrapper.matrix();\n  }\n\n  template<typename InputType>\n  void grab(const InputType &A)\n  {\n    m_matrixWrapper.grab(A);\n  }\n\n  MatrixWrapper m_matrixWrapper;\n  Preconditioner m_preconditioner;\n\n  Index m_maxIterations;\n  RealScalar m_tolerance;\n\n  mutable RealScalar m_error;\n  mutable Index m_iterations;\n  mutable ComputationInfo m_info;\n  mutable bool m_analysisIsOk, m_factorizationIsOk;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_ITERATIVE_SOLVER_BASE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/IterativeLinearSolvers/LeastSquareConjugateGradient.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_LEAST_SQUARE_CONJUGATE_GRADIENT_H\n#define EIGEN_LEAST_SQUARE_CONJUGATE_GRADIENT_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\internal Low-level conjugate gradient algorithm for least-square problems\n  * \\param mat The matrix A\n  * \\param rhs The right hand side vector b\n  * \\param x On input and initial solution, on output the computed solution.\n  * \\param precond A preconditioner being able to efficiently solve for an\n  *                approximation of A'Ax=b (regardless of b)\n  * \\param iters On input the max number of iteration, on output the number of performed iterations.\n  * \\param tol_error On input the tolerance error, on output an estimation of the relative error.\n  */\ntemplate<typename MatrixType, typename Rhs, typename Dest, typename Preconditioner>\nEIGEN_DONT_INLINE\nvoid least_square_conjugate_gradient(const MatrixType& mat, const Rhs& rhs, Dest& x,\n                                     const Preconditioner& precond, Index& iters,\n                                     typename Dest::RealScalar& tol_error)\n{\n  using std::sqrt;\n  using std::abs;\n  typedef typename Dest::RealScalar RealScalar;\n  typedef typename Dest::Scalar Scalar;\n  typedef Matrix<Scalar,Dynamic,1> VectorType;\n  \n  RealScalar tol = tol_error;\n  Index maxIters = iters;\n  \n  Index m = mat.rows(), n = mat.cols();\n\n  VectorType residual        = rhs - mat * x;\n  VectorType normal_residual = mat.adjoint() * residual;\n\n  RealScalar rhsNorm2 = (mat.adjoint()*rhs).squaredNorm();\n  if(rhsNorm2 == 0) \n  {\n    x.setZero();\n    iters = 0;\n    tol_error = 0;\n    return;\n  }\n  RealScalar threshold = tol*tol*rhsNorm2;\n  RealScalar residualNorm2 = normal_residual.squaredNorm();\n  if (residualNorm2 < threshold)\n  {\n    iters = 0;\n    tol_error = sqrt(residualNorm2 / rhsNorm2);\n    return;\n  }\n  \n  VectorType p(n);\n  p = precond.solve(normal_residual);                         // initial search direction\n\n  VectorType z(n), tmp(m);\n  RealScalar absNew = numext::real(normal_residual.dot(p));  // the square of the absolute value of r scaled by invM\n  Index i = 0;\n  while(i < maxIters)\n  {\n    tmp.noalias() = mat * p;\n\n    Scalar alpha = absNew / tmp.squaredNorm();      // the amount we travel on dir\n    x += alpha * p;                                 // update solution\n    residual -= alpha * tmp;                        // update residual\n    normal_residual = mat.adjoint() * residual;     // update residual of the normal equation\n    \n    residualNorm2 = normal_residual.squaredNorm();\n    if(residualNorm2 < threshold)\n      break;\n    \n    z = precond.solve(normal_residual);             // approximately solve for \"A'A z = normal_residual\"\n\n    RealScalar absOld = absNew;\n    absNew = numext::real(normal_residual.dot(z));  // update the absolute value of r\n    RealScalar beta = absNew / absOld;              // calculate the Gram-Schmidt value used to create the new search direction\n    p = z + beta * p;                               // update search direction\n    i++;\n  }\n  tol_error = sqrt(residualNorm2 / rhsNorm2);\n  iters = i;\n}\n\n}\n\ntemplate< typename MatrixType_,\n          typename Preconditioner_ = LeastSquareDiagonalPreconditioner<typename MatrixType_::Scalar> >\nclass LeastSquaresConjugateGradient;\n\nnamespace internal {\n\ntemplate< typename MatrixType_, typename Preconditioner_>\nstruct traits<LeastSquaresConjugateGradient<MatrixType_,Preconditioner_> >\n{\n  typedef MatrixType_ MatrixType;\n  typedef Preconditioner_ Preconditioner;\n};\n\n}\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\brief A conjugate gradient solver for sparse (or dense) least-square problems\n  *\n  * This class allows to solve for A x = b linear problems using an iterative conjugate gradient algorithm.\n  * The matrix A can be non symmetric and rectangular, but the matrix A' A should be positive-definite to guaranty stability.\n  * Otherwise, the SparseLU or SparseQR classes might be preferable.\n  * The matrix A and the vectors x and b can be either dense or sparse.\n  *\n  * \\tparam MatrixType_ the type of the matrix A, can be a dense or a sparse matrix.\n  * \\tparam Preconditioner_ the type of the preconditioner. Default is LeastSquareDiagonalPreconditioner\n  *\n  * \\implsparsesolverconcept\n  * \n  * The maximal number of iterations and tolerance value can be controlled via the setMaxIterations()\n  * and setTolerance() methods. The defaults are the size of the problem for the maximal number of iterations\n  * and NumTraits<Scalar>::epsilon() for the tolerance.\n  * \n  * This class can be used as the direct solver classes. Here is a typical usage example:\n    \\code\n    int m=1000000, n = 10000;\n    VectorXd x(n), b(m);\n    SparseMatrix<double> A(m,n);\n    // fill A and b\n    LeastSquaresConjugateGradient<SparseMatrix<double> > lscg;\n    lscg.compute(A);\n    x = lscg.solve(b);\n    std::cout << \"#iterations:     \" << lscg.iterations() << std::endl;\n    std::cout << \"estimated error: \" << lscg.error()      << std::endl;\n    // update b, and solve again\n    x = lscg.solve(b);\n    \\endcode\n  * \n  * By default the iterations start with x=0 as an initial guess of the solution.\n  * One can control the start using the solveWithGuess() method.\n  * \n  * \\sa class ConjugateGradient, SparseLU, SparseQR\n  */\ntemplate< typename MatrixType_, typename Preconditioner_>\nclass LeastSquaresConjugateGradient : public IterativeSolverBase<LeastSquaresConjugateGradient<MatrixType_,Preconditioner_> >\n{\n  typedef IterativeSolverBase<LeastSquaresConjugateGradient> Base;\n  using Base::matrix;\n  using Base::m_error;\n  using Base::m_iterations;\n  using Base::m_info;\n  using Base::m_isInitialized;\npublic:\n  typedef MatrixType_ MatrixType;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef Preconditioner_ Preconditioner;\n\npublic:\n\n  /** Default constructor. */\n  LeastSquaresConjugateGradient() : Base() {}\n\n  /** Initialize the solver with matrix \\a A for further \\c Ax=b solving.\n    * \n    * This constructor is a shortcut for the default constructor followed\n    * by a call to compute().\n    * \n    * \\warning this class stores a reference to the matrix A as well as some\n    * precomputed values that depend on it. Therefore, if \\a A is changed\n    * this class becomes invalid. Call compute() to update it with the new\n    * matrix A, or modify a copy of A.\n    */\n  template<typename MatrixDerived>\n  explicit LeastSquaresConjugateGradient(const EigenBase<MatrixDerived>& A) : Base(A.derived()) {}\n\n  ~LeastSquaresConjugateGradient() {}\n\n  /** \\internal */\n  template<typename Rhs,typename Dest>\n  void _solve_vector_with_guess_impl(const Rhs& b, Dest& x) const\n  {\n    m_iterations = Base::maxIterations();\n    m_error = Base::m_tolerance;\n\n    internal::least_square_conjugate_gradient(matrix(), b, x, Base::m_preconditioner, m_iterations, m_error);\n    m_info = m_error <= Base::m_tolerance ? Success : NoConvergence;\n  }\n\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_LEAST_SQUARE_CONJUGATE_GRADIENT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/IterativeLinearSolvers/SolveWithGuess.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SOLVEWITHGUESS_H\n#define EIGEN_SOLVEWITHGUESS_H\n\nnamespace Eigen {\n\ntemplate<typename Decomposition, typename RhsType, typename GuessType> class SolveWithGuess;\n\n/** \\class SolveWithGuess\n  * \\ingroup IterativeLinearSolvers_Module\n  *\n  * \\brief Pseudo expression representing a solving operation\n  *\n  * \\tparam Decomposition the type of the matrix or decomposion object\n  * \\tparam Rhstype the type of the right-hand side\n  *\n  * This class represents an expression of A.solve(B)\n  * and most of the time this is the only way it is used.\n  *\n  */\nnamespace internal {\n\n\ntemplate<typename Decomposition, typename RhsType, typename GuessType>\nstruct traits<SolveWithGuess<Decomposition, RhsType, GuessType> >\n  : traits<Solve<Decomposition,RhsType> >\n{};\n\n}\n\n\ntemplate<typename Decomposition, typename RhsType, typename GuessType>\nclass SolveWithGuess : public internal::generic_xpr_base<SolveWithGuess<Decomposition,RhsType,GuessType>, MatrixXpr, typename internal::traits<RhsType>::StorageKind>::type\n{\npublic:\n  typedef typename internal::traits<SolveWithGuess>::Scalar Scalar;\n  typedef typename internal::traits<SolveWithGuess>::PlainObject PlainObject;\n  typedef typename internal::generic_xpr_base<SolveWithGuess<Decomposition,RhsType,GuessType>, MatrixXpr, typename internal::traits<RhsType>::StorageKind>::type Base;\n  typedef typename internal::ref_selector<SolveWithGuess>::type Nested;\n\n  SolveWithGuess(const Decomposition &dec, const RhsType &rhs, const GuessType &guess)\n    : m_dec(dec), m_rhs(rhs), m_guess(guess)\n  {}\n\n  EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR\n  Index rows() const EIGEN_NOEXCEPT { return m_dec.cols(); }\n  EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR\n  Index cols() const EIGEN_NOEXCEPT { return m_rhs.cols(); }\n\n  EIGEN_DEVICE_FUNC const Decomposition& dec()   const { return m_dec; }\n  EIGEN_DEVICE_FUNC const RhsType&       rhs()   const { return m_rhs; }\n  EIGEN_DEVICE_FUNC const GuessType&     guess() const { return m_guess; }\n\nprotected:\n  const Decomposition &m_dec;\n  const RhsType       &m_rhs;\n  const GuessType     &m_guess;\n\nprivate:\n  Scalar coeff(Index row, Index col) const;\n  Scalar coeff(Index i) const;\n};\n\nnamespace internal {\n\n// Evaluator of SolveWithGuess -> eval into a temporary\ntemplate<typename Decomposition, typename RhsType, typename GuessType>\nstruct evaluator<SolveWithGuess<Decomposition,RhsType, GuessType> >\n  : public evaluator<typename SolveWithGuess<Decomposition,RhsType,GuessType>::PlainObject>\n{\n  typedef SolveWithGuess<Decomposition,RhsType,GuessType> SolveType;\n  typedef typename SolveType::PlainObject PlainObject;\n  typedef evaluator<PlainObject> Base;\n\n  evaluator(const SolveType& solve)\n    : m_result(solve.rows(), solve.cols())\n  {\n    ::new (static_cast<Base*>(this)) Base(m_result);\n    m_result = solve.guess();\n    solve.dec()._solve_with_guess_impl(solve.rhs(), m_result);\n  }\n\nprotected:\n  PlainObject m_result;\n};\n\n// Specialization for \"dst = dec.solveWithGuess(rhs)\"\n// NOTE we need to specialize it for Dense2Dense to avoid ambiguous specialization error and a Sparse2Sparse specialization must exist somewhere\ntemplate<typename DstXprType, typename DecType, typename RhsType, typename GuessType, typename Scalar>\nstruct Assignment<DstXprType, SolveWithGuess<DecType,RhsType,GuessType>, internal::assign_op<Scalar,Scalar>, Dense2Dense>\n{\n  typedef SolveWithGuess<DecType,RhsType,GuessType> SrcXprType;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<Scalar,Scalar> &)\n  {\n    Index dstRows = src.rows();\n    Index dstCols = src.cols();\n    if((dst.rows()!=dstRows) || (dst.cols()!=dstCols))\n      dst.resize(dstRows, dstCols);\n\n    dst = src.guess();\n    src.dec()._solve_with_guess_impl(src.rhs(), dst/*, src.guess()*/);\n  }\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SOLVEWITHGUESS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/Jacobi/Jacobi.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_JACOBI_H\n#define EIGEN_JACOBI_H\n\nnamespace Eigen {\n\n/** \\ingroup Jacobi_Module\n  * \\jacobi_module\n  * \\class JacobiRotation\n  * \\brief Rotation given by a cosine-sine pair.\n  *\n  * This class represents a Jacobi or Givens rotation.\n  * This is a 2D rotation in the plane \\c J of angle \\f$ \\theta \\f$ defined by\n  * its cosine \\c c and sine \\c s as follow:\n  * \\f$ J = \\left ( \\begin{array}{cc} c & \\overline s \\\\ -s  & \\overline c \\end{array} \\right ) \\f$\n  *\n  * You can apply the respective counter-clockwise rotation to a column vector \\c v by\n  * applying its adjoint on the left: \\f$ v = J^* v \\f$ that translates to the following Eigen code:\n  * \\code\n  * v.applyOnTheLeft(J.adjoint());\n  * \\endcode\n  *\n  * \\sa MatrixBase::applyOnTheLeft(), MatrixBase::applyOnTheRight()\n  */\ntemplate<typename Scalar> class JacobiRotation\n{\n  public:\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n\n    /** Default constructor without any initialization. */\n    EIGEN_DEVICE_FUNC\n    JacobiRotation() {}\n\n    /** Construct a planar rotation from a cosine-sine pair (\\a c, \\c s). */\n    EIGEN_DEVICE_FUNC\n    JacobiRotation(const Scalar& c, const Scalar& s) : m_c(c), m_s(s) {}\n\n    EIGEN_DEVICE_FUNC Scalar& c() { return m_c; }\n    EIGEN_DEVICE_FUNC Scalar c() const { return m_c; }\n    EIGEN_DEVICE_FUNC Scalar& s() { return m_s; }\n    EIGEN_DEVICE_FUNC Scalar s() const { return m_s; }\n\n    /** Concatenates two planar rotation */\n    EIGEN_DEVICE_FUNC\n    JacobiRotation operator*(const JacobiRotation& other)\n    {\n      using numext::conj;\n      return JacobiRotation(m_c * other.m_c - conj(m_s) * other.m_s,\n                            conj(m_c * conj(other.m_s) + conj(m_s) * conj(other.m_c)));\n    }\n\n    /** Returns the transposed transformation */\n    EIGEN_DEVICE_FUNC\n    JacobiRotation transpose() const { using numext::conj; return JacobiRotation(m_c, -conj(m_s)); }\n\n    /** Returns the adjoint transformation */\n    EIGEN_DEVICE_FUNC\n    JacobiRotation adjoint() const { using numext::conj; return JacobiRotation(conj(m_c), -m_s); }\n\n    template<typename Derived>\n    EIGEN_DEVICE_FUNC\n    bool makeJacobi(const MatrixBase<Derived>&, Index p, Index q);\n    EIGEN_DEVICE_FUNC\n    bool makeJacobi(const RealScalar& x, const Scalar& y, const RealScalar& z);\n\n    EIGEN_DEVICE_FUNC\n    void makeGivens(const Scalar& p, const Scalar& q, Scalar* r=0);\n\n  protected:\n    EIGEN_DEVICE_FUNC\n    void makeGivens(const Scalar& p, const Scalar& q, Scalar* r, internal::true_type);\n    EIGEN_DEVICE_FUNC\n    void makeGivens(const Scalar& p, const Scalar& q, Scalar* r, internal::false_type);\n\n    Scalar m_c, m_s;\n};\n\n/** Makes \\c *this as a Jacobi rotation \\a J such that applying \\a J on both the right and left sides of the selfadjoint 2x2 matrix\n  * \\f$ B = \\left ( \\begin{array}{cc} x & y \\\\ \\overline y & z \\end{array} \\right )\\f$ yields a diagonal matrix \\f$ A = J^* B J \\f$\n  *\n  * \\sa MatrixBase::makeJacobi(const MatrixBase<Derived>&, Index, Index), MatrixBase::applyOnTheLeft(), MatrixBase::applyOnTheRight()\n  */\ntemplate<typename Scalar>\nEIGEN_DEVICE_FUNC\nbool JacobiRotation<Scalar>::makeJacobi(const RealScalar& x, const Scalar& y, const RealScalar& z)\n{\n  using std::sqrt;\n  using std::abs;\n\n  RealScalar deno = RealScalar(2)*abs(y);\n  if(deno < (std::numeric_limits<RealScalar>::min)())\n  {\n    m_c = Scalar(1);\n    m_s = Scalar(0);\n    return false;\n  }\n  else\n  {\n    RealScalar tau = (x-z)/deno;\n    RealScalar w = sqrt(numext::abs2(tau) + RealScalar(1));\n    RealScalar t;\n    if(tau>RealScalar(0))\n    {\n      t = RealScalar(1) / (tau + w);\n    }\n    else\n    {\n      t = RealScalar(1) / (tau - w);\n    }\n    RealScalar sign_t = t > RealScalar(0) ? RealScalar(1) : RealScalar(-1);\n    RealScalar n = RealScalar(1) / sqrt(numext::abs2(t)+RealScalar(1));\n    m_s = - sign_t * (numext::conj(y) / abs(y)) * abs(t) * n;\n    m_c = n;\n    return true;\n  }\n}\n\n/** Makes \\c *this as a Jacobi rotation \\c J such that applying \\a J on both the right and left sides of the 2x2 selfadjoint matrix\n  * \\f$ B = \\left ( \\begin{array}{cc} \\text{this}_{pp} & \\text{this}_{pq} \\\\ (\\text{this}_{pq})^* & \\text{this}_{qq} \\end{array} \\right )\\f$ yields\n  * a diagonal matrix \\f$ A = J^* B J \\f$\n  *\n  * Example: \\include Jacobi_makeJacobi.cpp\n  * Output: \\verbinclude Jacobi_makeJacobi.out\n  *\n  * \\sa JacobiRotation::makeJacobi(RealScalar, Scalar, RealScalar), MatrixBase::applyOnTheLeft(), MatrixBase::applyOnTheRight()\n  */\ntemplate<typename Scalar>\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC\ninline bool JacobiRotation<Scalar>::makeJacobi(const MatrixBase<Derived>& m, Index p, Index q)\n{\n  return makeJacobi(numext::real(m.coeff(p,p)), m.coeff(p,q), numext::real(m.coeff(q,q)));\n}\n\n/** Makes \\c *this as a Givens rotation \\c G such that applying \\f$ G^* \\f$ to the left of the vector\n  * \\f$ V = \\left ( \\begin{array}{c} p \\\\ q \\end{array} \\right )\\f$ yields:\n  * \\f$ G^* V = \\left ( \\begin{array}{c} r \\\\ 0 \\end{array} \\right )\\f$.\n  *\n  * The value of \\a r is returned if \\a r is not null (the default is null).\n  * Also note that G is built such that the cosine is always real.\n  *\n  * Example: \\include Jacobi_makeGivens.cpp\n  * Output: \\verbinclude Jacobi_makeGivens.out\n  *\n  * This function implements the continuous Givens rotation generation algorithm\n  * found in Anderson (2000), Discontinuous Plane Rotations and the Symmetric Eigenvalue Problem.\n  * LAPACK Working Note 150, University of Tennessee, UT-CS-00-454, December 4, 2000.\n  *\n  * \\sa MatrixBase::applyOnTheLeft(), MatrixBase::applyOnTheRight()\n  */\ntemplate<typename Scalar>\nEIGEN_DEVICE_FUNC\nvoid JacobiRotation<Scalar>::makeGivens(const Scalar& p, const Scalar& q, Scalar* r)\n{\n  makeGivens(p, q, r, typename internal::conditional<NumTraits<Scalar>::IsComplex, internal::true_type, internal::false_type>::type());\n}\n\n\n// specialization for complexes\ntemplate<typename Scalar>\nEIGEN_DEVICE_FUNC\nvoid JacobiRotation<Scalar>::makeGivens(const Scalar& p, const Scalar& q, Scalar* r, internal::true_type)\n{\n  using std::sqrt;\n  using std::abs;\n  using numext::conj;\n\n  if(q==Scalar(0))\n  {\n    m_c = numext::real(p)<0 ? Scalar(-1) : Scalar(1);\n    m_s = 0;\n    if(r) *r = m_c * p;\n  }\n  else if(p==Scalar(0))\n  {\n    m_c = 0;\n    m_s = -q/abs(q);\n    if(r) *r = abs(q);\n  }\n  else\n  {\n    RealScalar p1 = numext::norm1(p);\n    RealScalar q1 = numext::norm1(q);\n    if(p1>=q1)\n    {\n      Scalar ps = p / p1;\n      RealScalar p2 = numext::abs2(ps);\n      Scalar qs = q / p1;\n      RealScalar q2 = numext::abs2(qs);\n\n      RealScalar u = sqrt(RealScalar(1) + q2/p2);\n      if(numext::real(p)<RealScalar(0))\n        u = -u;\n\n      m_c = Scalar(1)/u;\n      m_s = -qs*conj(ps)*(m_c/p2);\n      if(r) *r = p * u;\n    }\n    else\n    {\n      Scalar ps = p / q1;\n      RealScalar p2 = numext::abs2(ps);\n      Scalar qs = q / q1;\n      RealScalar q2 = numext::abs2(qs);\n\n      RealScalar u = q1 * sqrt(p2 + q2);\n      if(numext::real(p)<RealScalar(0))\n        u = -u;\n\n      p1 = abs(p);\n      ps = p/p1;\n      m_c = p1/u;\n      m_s = -conj(ps) * (q/u);\n      if(r) *r = ps * u;\n    }\n  }\n}\n\n// specialization for reals\ntemplate<typename Scalar>\nEIGEN_DEVICE_FUNC\nvoid JacobiRotation<Scalar>::makeGivens(const Scalar& p, const Scalar& q, Scalar* r, internal::false_type)\n{\n  using std::sqrt;\n  using std::abs;\n  if(q==Scalar(0))\n  {\n    m_c = p<Scalar(0) ? Scalar(-1) : Scalar(1);\n    m_s = Scalar(0);\n    if(r) *r = abs(p);\n  }\n  else if(p==Scalar(0))\n  {\n    m_c = Scalar(0);\n    m_s = q<Scalar(0) ? Scalar(1) : Scalar(-1);\n    if(r) *r = abs(q);\n  }\n  else if(abs(p) > abs(q))\n  {\n    Scalar t = q/p;\n    Scalar u = sqrt(Scalar(1) + numext::abs2(t));\n    if(p<Scalar(0))\n      u = -u;\n    m_c = Scalar(1)/u;\n    m_s = -t * m_c;\n    if(r) *r = p * u;\n  }\n  else\n  {\n    Scalar t = p/q;\n    Scalar u = sqrt(Scalar(1) + numext::abs2(t));\n    if(q<Scalar(0))\n      u = -u;\n    m_s = -Scalar(1)/u;\n    m_c = -t * m_s;\n    if(r) *r = q * u;\n  }\n\n}\n\n/****************************************************************************************\n*   Implementation of MatrixBase methods\n****************************************************************************************/\n\nnamespace internal {\n/** \\jacobi_module\n  * Applies the clock wise 2D rotation \\a j to the set of 2D vectors of coordinates \\a x and \\a y:\n  * \\f$ \\left ( \\begin{array}{cc} x \\\\ y \\end{array} \\right )  =  J \\left ( \\begin{array}{cc} x \\\\ y \\end{array} \\right ) \\f$\n  *\n  * \\sa MatrixBase::applyOnTheLeft(), MatrixBase::applyOnTheRight()\n  */\ntemplate<typename VectorX, typename VectorY, typename OtherScalar>\nEIGEN_DEVICE_FUNC\nvoid apply_rotation_in_the_plane(DenseBase<VectorX>& xpr_x, DenseBase<VectorY>& xpr_y, const JacobiRotation<OtherScalar>& j);\n}\n\n/** \\jacobi_module\n  * Applies the rotation in the plane \\a j to the rows \\a p and \\a q of \\c *this, i.e., it computes B = J * B,\n  * with \\f$ B = \\left ( \\begin{array}{cc} \\text{*this.row}(p) \\\\ \\text{*this.row}(q) \\end{array} \\right ) \\f$.\n  *\n  * \\sa class JacobiRotation, MatrixBase::applyOnTheRight(), internal::apply_rotation_in_the_plane()\n  */\ntemplate<typename Derived>\ntemplate<typename OtherScalar>\nEIGEN_DEVICE_FUNC\ninline void MatrixBase<Derived>::applyOnTheLeft(Index p, Index q, const JacobiRotation<OtherScalar>& j)\n{\n  RowXpr x(this->row(p));\n  RowXpr y(this->row(q));\n  internal::apply_rotation_in_the_plane(x, y, j);\n}\n\n/** \\ingroup Jacobi_Module\n  * Applies the rotation in the plane \\a j to the columns \\a p and \\a q of \\c *this, i.e., it computes B = B * J\n  * with \\f$ B = \\left ( \\begin{array}{cc} \\text{*this.col}(p) & \\text{*this.col}(q) \\end{array} \\right ) \\f$.\n  *\n  * \\sa class JacobiRotation, MatrixBase::applyOnTheLeft(), internal::apply_rotation_in_the_plane()\n  */\ntemplate<typename Derived>\ntemplate<typename OtherScalar>\nEIGEN_DEVICE_FUNC\ninline void MatrixBase<Derived>::applyOnTheRight(Index p, Index q, const JacobiRotation<OtherScalar>& j)\n{\n  ColXpr x(this->col(p));\n  ColXpr y(this->col(q));\n  internal::apply_rotation_in_the_plane(x, y, j.transpose());\n}\n\nnamespace internal {\n\ntemplate<typename Scalar, typename OtherScalar,\n         int SizeAtCompileTime, int MinAlignment, bool Vectorizable>\nstruct apply_rotation_in_the_plane_selector\n{\n  static EIGEN_DEVICE_FUNC\n  inline void run(Scalar *x, Index incrx, Scalar *y, Index incry, Index size, OtherScalar c, OtherScalar s)\n  {\n    for(Index i=0; i<size; ++i)\n    {\n      Scalar xi = *x;\n      Scalar yi = *y;\n      *x =  c * xi + numext::conj(s) * yi;\n      *y = -s * xi + numext::conj(c) * yi;\n      x += incrx;\n      y += incry;\n    }\n  }\n};\n\ntemplate<typename Scalar, typename OtherScalar,\n         int SizeAtCompileTime, int MinAlignment>\nstruct apply_rotation_in_the_plane_selector<Scalar,OtherScalar,SizeAtCompileTime,MinAlignment,true /* vectorizable */>\n{\n  static inline void run(Scalar *x, Index incrx, Scalar *y, Index incry, Index size, OtherScalar c, OtherScalar s)\n  {\n    enum {\n      PacketSize = packet_traits<Scalar>::size,\n      OtherPacketSize = packet_traits<OtherScalar>::size\n    };\n    typedef typename packet_traits<Scalar>::type Packet;\n    typedef typename packet_traits<OtherScalar>::type OtherPacket;\n\n    /*** dynamic-size vectorized paths ***/\n    if(SizeAtCompileTime == Dynamic && ((incrx==1 && incry==1) || PacketSize == 1))\n    {\n      // both vectors are sequentially stored in memory => vectorization\n      enum { Peeling = 2 };\n\n      Index alignedStart = internal::first_default_aligned(y, size);\n      Index alignedEnd = alignedStart + ((size-alignedStart)/PacketSize)*PacketSize;\n\n      const OtherPacket pc = pset1<OtherPacket>(c);\n      const OtherPacket ps = pset1<OtherPacket>(s);\n      conj_helper<OtherPacket,Packet,NumTraits<OtherScalar>::IsComplex,false> pcj;\n      conj_helper<OtherPacket,Packet,false,false> pm;\n\n      for(Index i=0; i<alignedStart; ++i)\n      {\n        Scalar xi = x[i];\n        Scalar yi = y[i];\n        x[i] =  c * xi + numext::conj(s) * yi;\n        y[i] = -s * xi + numext::conj(c) * yi;\n      }\n\n      Scalar* EIGEN_RESTRICT px = x + alignedStart;\n      Scalar* EIGEN_RESTRICT py = y + alignedStart;\n\n      if(internal::first_default_aligned(x, size)==alignedStart)\n      {\n        for(Index i=alignedStart; i<alignedEnd; i+=PacketSize)\n        {\n          Packet xi = pload<Packet>(px);\n          Packet yi = pload<Packet>(py);\n          pstore(px, padd(pm.pmul(pc,xi),pcj.pmul(ps,yi)));\n          pstore(py, psub(pcj.pmul(pc,yi),pm.pmul(ps,xi)));\n          px += PacketSize;\n          py += PacketSize;\n        }\n      }\n      else\n      {\n        Index peelingEnd = alignedStart + ((size-alignedStart)/(Peeling*PacketSize))*(Peeling*PacketSize);\n        for(Index i=alignedStart; i<peelingEnd; i+=Peeling*PacketSize)\n        {\n          Packet xi   = ploadu<Packet>(px);\n          Packet xi1  = ploadu<Packet>(px+PacketSize);\n          Packet yi   = pload <Packet>(py);\n          Packet yi1  = pload <Packet>(py+PacketSize);\n          pstoreu(px, padd(pm.pmul(pc,xi),pcj.pmul(ps,yi)));\n          pstoreu(px+PacketSize, padd(pm.pmul(pc,xi1),pcj.pmul(ps,yi1)));\n          pstore (py, psub(pcj.pmul(pc,yi),pm.pmul(ps,xi)));\n          pstore (py+PacketSize, psub(pcj.pmul(pc,yi1),pm.pmul(ps,xi1)));\n          px += Peeling*PacketSize;\n          py += Peeling*PacketSize;\n        }\n        if(alignedEnd!=peelingEnd)\n        {\n          Packet xi = ploadu<Packet>(x+peelingEnd);\n          Packet yi = pload <Packet>(y+peelingEnd);\n          pstoreu(x+peelingEnd, padd(pm.pmul(pc,xi),pcj.pmul(ps,yi)));\n          pstore (y+peelingEnd, psub(pcj.pmul(pc,yi),pm.pmul(ps,xi)));\n        }\n      }\n\n      for(Index i=alignedEnd; i<size; ++i)\n      {\n        Scalar xi = x[i];\n        Scalar yi = y[i];\n        x[i] =  c * xi + numext::conj(s) * yi;\n        y[i] = -s * xi + numext::conj(c) * yi;\n      }\n    }\n\n    /*** fixed-size vectorized path ***/\n    else if(SizeAtCompileTime != Dynamic && MinAlignment>0) // FIXME should be compared to the required alignment\n    {\n      const OtherPacket pc = pset1<OtherPacket>(c);\n      const OtherPacket ps = pset1<OtherPacket>(s);\n      conj_helper<OtherPacket,Packet,NumTraits<OtherPacket>::IsComplex,false> pcj;\n      conj_helper<OtherPacket,Packet,false,false> pm;\n      Scalar* EIGEN_RESTRICT px = x;\n      Scalar* EIGEN_RESTRICT py = y;\n      for(Index i=0; i<size; i+=PacketSize)\n      {\n        Packet xi = pload<Packet>(px);\n        Packet yi = pload<Packet>(py);\n        pstore(px, padd(pm.pmul(pc,xi),pcj.pmul(ps,yi)));\n        pstore(py, psub(pcj.pmul(pc,yi),pm.pmul(ps,xi)));\n        px += PacketSize;\n        py += PacketSize;\n      }\n    }\n\n    /*** non-vectorized path ***/\n    else\n    {\n      apply_rotation_in_the_plane_selector<Scalar,OtherScalar,SizeAtCompileTime,MinAlignment,false>::run(x,incrx,y,incry,size,c,s);\n    }\n  }\n};\n\ntemplate<typename VectorX, typename VectorY, typename OtherScalar>\nEIGEN_DEVICE_FUNC\nvoid /*EIGEN_DONT_INLINE*/ apply_rotation_in_the_plane(DenseBase<VectorX>& xpr_x, DenseBase<VectorY>& xpr_y, const JacobiRotation<OtherScalar>& j)\n{\n  typedef typename VectorX::Scalar Scalar;\n  const bool Vectorizable =    (int(VectorX::Flags) & int(VectorY::Flags) & PacketAccessBit)\n                            && (int(packet_traits<Scalar>::size) == int(packet_traits<OtherScalar>::size));\n\n  eigen_assert(xpr_x.size() == xpr_y.size());\n  Index size = xpr_x.size();\n  Index incrx = xpr_x.derived().innerStride();\n  Index incry = xpr_y.derived().innerStride();\n\n  Scalar* EIGEN_RESTRICT x = &xpr_x.derived().coeffRef(0);\n  Scalar* EIGEN_RESTRICT y = &xpr_y.derived().coeffRef(0);\n\n  OtherScalar c = j.c();\n  OtherScalar s = j.s();\n  if (c==OtherScalar(1) && s==OtherScalar(0))\n    return;\n\n  apply_rotation_in_the_plane_selector<\n    Scalar,OtherScalar,\n    VectorX::SizeAtCompileTime,\n    EIGEN_PLAIN_ENUM_MIN(evaluator<VectorX>::Alignment, evaluator<VectorY>::Alignment),\n    Vectorizable>::run(x,incrx,y,incry,size,c,s);\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_JACOBI_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/KLUSupport/KLUSupport.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2017 Kyle Macfarlan <kyle.macfarlan@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_KLUSUPPORT_H\n#define EIGEN_KLUSUPPORT_H\n\nnamespace Eigen {\n\n/* TODO extract L, extract U, compute det, etc... */\n\n/** \\ingroup KLUSupport_Module\n  * \\brief A sparse LU factorization and solver based on KLU\n  *\n  * This class allows to solve for A.X = B sparse linear problems via a LU factorization\n  * using the KLU library. The sparse matrix A must be squared and full rank.\n  * The vectors or matrices X and B can be either dense or sparse.\n  *\n  * \\warning The input matrix A should be in a \\b compressed and \\b column-major form.\n  * Otherwise an expensive copy will be made. You can call the inexpensive makeCompressed() to get a compressed matrix.\n  * \\tparam MatrixType_ the type of the sparse matrix A, it must be a SparseMatrix<>\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class UmfPackLU, class SparseLU\n  */\n\n\ninline int klu_solve(klu_symbolic *Symbolic, klu_numeric *Numeric, Index ldim, Index nrhs, double B [ ], klu_common *Common, double) {\n   return klu_solve(Symbolic, Numeric, internal::convert_index<int>(ldim), internal::convert_index<int>(nrhs), B, Common);\n}\n\ninline int klu_solve(klu_symbolic *Symbolic, klu_numeric *Numeric, Index ldim, Index nrhs, std::complex<double>B[], klu_common *Common, std::complex<double>) {\n   return klu_z_solve(Symbolic, Numeric, internal::convert_index<int>(ldim), internal::convert_index<int>(nrhs), &numext::real_ref(B[0]), Common);\n}\n\ninline int klu_tsolve(klu_symbolic *Symbolic, klu_numeric *Numeric, Index ldim, Index nrhs, double B[], klu_common *Common, double) {\n   return klu_tsolve(Symbolic, Numeric, internal::convert_index<int>(ldim), internal::convert_index<int>(nrhs), B, Common);\n}\n\ninline int klu_tsolve(klu_symbolic *Symbolic, klu_numeric *Numeric, Index ldim, Index nrhs, std::complex<double>B[], klu_common *Common, std::complex<double>) {\n   return klu_z_tsolve(Symbolic, Numeric, internal::convert_index<int>(ldim), internal::convert_index<int>(nrhs), &numext::real_ref(B[0]), 0, Common);\n}\n\ninline klu_numeric* klu_factor(int Ap [ ], int Ai [ ], double Ax [ ], klu_symbolic *Symbolic, klu_common *Common, double) {\n   return klu_factor(Ap, Ai, Ax, Symbolic, Common);\n}\n\ninline klu_numeric* klu_factor(int Ap[], int Ai[], std::complex<double> Ax[], klu_symbolic *Symbolic, klu_common *Common, std::complex<double>) {\n   return klu_z_factor(Ap, Ai, &numext::real_ref(Ax[0]), Symbolic, Common);\n}\n\n\ntemplate<typename MatrixType_>\nclass KLU : public SparseSolverBase<KLU<MatrixType_> >\n{\n  protected:\n    typedef SparseSolverBase<KLU<MatrixType_> > Base;\n    using Base::m_isInitialized;\n  public:\n    using Base::_solve_impl;\n    typedef MatrixType_ MatrixType;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef Matrix<Scalar,Dynamic,1> Vector;\n    typedef Matrix<int, 1, MatrixType::ColsAtCompileTime> IntRowVectorType;\n    typedef Matrix<int, MatrixType::RowsAtCompileTime, 1> IntColVectorType;\n    typedef SparseMatrix<Scalar> LUMatrixType;\n    typedef SparseMatrix<Scalar,ColMajor,int> KLUMatrixType;\n    typedef Ref<const KLUMatrixType, StandardCompressedFormat> KLUMatrixRef;\n    enum {\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n\n  public:\n\n    KLU()\n      : m_dummy(0,0), mp_matrix(m_dummy)\n    {\n      init();\n    }\n\n    template<typename InputMatrixType>\n    explicit KLU(const InputMatrixType& matrix)\n      : mp_matrix(matrix)\n    {\n      init();\n      compute(matrix);\n    }\n\n    ~KLU()\n    {\n      if(m_symbolic) klu_free_symbolic(&m_symbolic,&m_common);\n      if(m_numeric)  klu_free_numeric(&m_numeric,&m_common);\n    }\n\n    EIGEN_CONSTEXPR inline Index rows() const EIGEN_NOEXCEPT { return mp_matrix.rows(); }\n    EIGEN_CONSTEXPR inline Index cols() const EIGEN_NOEXCEPT { return mp_matrix.cols(); }\n\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the matrix.appears to be negative.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_info;\n    }\n#if 0 // not implemented yet\n    inline const LUMatrixType& matrixL() const\n    {\n      if (m_extractedDataAreDirty) extractData();\n      return m_l;\n    }\n\n    inline const LUMatrixType& matrixU() const\n    {\n      if (m_extractedDataAreDirty) extractData();\n      return m_u;\n    }\n\n    inline const IntColVectorType& permutationP() const\n    {\n      if (m_extractedDataAreDirty) extractData();\n      return m_p;\n    }\n\n    inline const IntRowVectorType& permutationQ() const\n    {\n      if (m_extractedDataAreDirty) extractData();\n      return m_q;\n    }\n#endif\n    /** Computes the sparse Cholesky decomposition of \\a matrix\n     *  Note that the matrix should be column-major, and in compressed format for best performance.\n     *  \\sa SparseMatrix::makeCompressed().\n     */\n    template<typename InputMatrixType>\n    void compute(const InputMatrixType& matrix)\n    {\n      if(m_symbolic) klu_free_symbolic(&m_symbolic, &m_common);\n      if(m_numeric)  klu_free_numeric(&m_numeric, &m_common);\n      grab(matrix.derived());\n      analyzePattern_impl();\n      factorize_impl();\n    }\n\n    /** Performs a symbolic decomposition on the sparcity of \\a matrix.\n      *\n      * This function is particularly useful when solving for several problems having the same structure.\n      *\n      * \\sa factorize(), compute()\n      */\n    template<typename InputMatrixType>\n    void analyzePattern(const InputMatrixType& matrix)\n    {\n      if(m_symbolic) klu_free_symbolic(&m_symbolic, &m_common);\n      if(m_numeric)  klu_free_numeric(&m_numeric, &m_common);\n\n      grab(matrix.derived());\n\n      analyzePattern_impl();\n    }\n\n\n    /** Provides access to the control settings array used by KLU.\n      *\n      * See KLU documentation for details.\n      */\n    inline const klu_common& kluCommon() const\n    {\n      return m_common;\n    }\n\n    /** Provides access to the control settings array used by UmfPack.\n      *\n      * If this array contains NaN's, the default values are used.\n      *\n      * See KLU documentation for details.\n      */\n    inline klu_common& kluCommon()\n    {\n      return m_common;\n    }\n\n    /** Performs a numeric decomposition of \\a matrix\n      *\n      * The given matrix must has the same sparcity than the matrix on which the pattern anylysis has been performed.\n      *\n      * \\sa analyzePattern(), compute()\n      */\n    template<typename InputMatrixType>\n    void factorize(const InputMatrixType& matrix)\n    {\n      eigen_assert(m_analysisIsOk && \"KLU: you must first call analyzePattern()\");\n      if(m_numeric)\n        klu_free_numeric(&m_numeric,&m_common);\n\n      grab(matrix.derived());\n\n      factorize_impl();\n    }\n\n    /** \\internal */\n    template<typename BDerived,typename XDerived>\n    bool _solve_impl(const MatrixBase<BDerived> &b, MatrixBase<XDerived> &x) const;\n\n#if 0 // not implemented yet\n    Scalar determinant() const;\n\n    void extractData() const;\n#endif\n\n  protected:\n\n    void init()\n    {\n      m_info                  = InvalidInput;\n      m_isInitialized         = false;\n      m_numeric               = 0;\n      m_symbolic              = 0;\n      m_extractedDataAreDirty = true;\n\n      klu_defaults(&m_common);\n    }\n\n    void analyzePattern_impl()\n    {\n      m_info = InvalidInput;\n      m_analysisIsOk = false;\n      m_factorizationIsOk = false;\n      m_symbolic = klu_analyze(internal::convert_index<int>(mp_matrix.rows()),\n                                     const_cast<StorageIndex*>(mp_matrix.outerIndexPtr()), const_cast<StorageIndex*>(mp_matrix.innerIndexPtr()),\n                                     &m_common);\n      if (m_symbolic) {\n         m_isInitialized = true;\n         m_info = Success;\n         m_analysisIsOk = true;\n         m_extractedDataAreDirty = true;\n      }\n    }\n\n    void factorize_impl()\n    {\n\n      m_numeric = klu_factor(const_cast<StorageIndex*>(mp_matrix.outerIndexPtr()), const_cast<StorageIndex*>(mp_matrix.innerIndexPtr()), const_cast<Scalar*>(mp_matrix.valuePtr()),\n                                    m_symbolic, &m_common, Scalar());\n\n\n      m_info = m_numeric ? Success : NumericalIssue;\n      m_factorizationIsOk = m_numeric ? 1 : 0;\n      m_extractedDataAreDirty = true;\n    }\n\n    template<typename MatrixDerived>\n    void grab(const EigenBase<MatrixDerived> &A)\n    {\n      mp_matrix.~KLUMatrixRef();\n      ::new (&mp_matrix) KLUMatrixRef(A.derived());\n    }\n\n    void grab(const KLUMatrixRef &A)\n    {\n      if(&(A.derived()) != &mp_matrix)\n      {\n        mp_matrix.~KLUMatrixRef();\n        ::new (&mp_matrix) KLUMatrixRef(A);\n      }\n    }\n\n    // cached data to reduce reallocation, etc.\n#if 0 // not implemented yet\n    mutable LUMatrixType m_l;\n    mutable LUMatrixType m_u;\n    mutable IntColVectorType m_p;\n    mutable IntRowVectorType m_q;\n#endif\n\n    KLUMatrixType m_dummy;\n    KLUMatrixRef mp_matrix;\n\n    klu_numeric* m_numeric;\n    klu_symbolic* m_symbolic;\n    klu_common m_common;\n    mutable ComputationInfo m_info;\n    int m_factorizationIsOk;\n    int m_analysisIsOk;\n    mutable bool m_extractedDataAreDirty;\n\n  private:\n    KLU(const KLU& ) { }\n};\n\n#if 0 // not implemented yet\ntemplate<typename MatrixType>\nvoid KLU<MatrixType>::extractData() const\n{\n  if (m_extractedDataAreDirty)\n  {\n     eigen_assert(false && \"KLU: extractData Not Yet Implemented\");\n\n    // get size of the data\n    int lnz, unz, rows, cols, nz_udiag;\n    umfpack_get_lunz(&lnz, &unz, &rows, &cols, &nz_udiag, m_numeric, Scalar());\n\n    // allocate data\n    m_l.resize(rows,(std::min)(rows,cols));\n    m_l.resizeNonZeros(lnz);\n\n    m_u.resize((std::min)(rows,cols),cols);\n    m_u.resizeNonZeros(unz);\n\n    m_p.resize(rows);\n    m_q.resize(cols);\n\n    // extract\n    umfpack_get_numeric(m_l.outerIndexPtr(), m_l.innerIndexPtr(), m_l.valuePtr(),\n                        m_u.outerIndexPtr(), m_u.innerIndexPtr(), m_u.valuePtr(),\n                        m_p.data(), m_q.data(), 0, 0, 0, m_numeric);\n\n    m_extractedDataAreDirty = false;\n  }\n}\n\ntemplate<typename MatrixType>\ntypename KLU<MatrixType>::Scalar KLU<MatrixType>::determinant() const\n{\n  eigen_assert(false && \"KLU: extractData Not Yet Implemented\");\n  return Scalar();\n}\n#endif\n\ntemplate<typename MatrixType>\ntemplate<typename BDerived,typename XDerived>\nbool KLU<MatrixType>::_solve_impl(const MatrixBase<BDerived> &b, MatrixBase<XDerived> &x) const\n{\n  Index rhsCols = b.cols();\n  EIGEN_STATIC_ASSERT((XDerived::Flags&RowMajorBit)==0, THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES);\n  eigen_assert(m_factorizationIsOk && \"The decomposition is not in a valid state for solving, you must first call either compute() or analyzePattern()/factorize()\");\n\n  x = b;\n  int info = klu_solve(m_symbolic, m_numeric, b.rows(), rhsCols, x.const_cast_derived().data(), const_cast<klu_common*>(&m_common), Scalar());\n\n  m_info = info!=0 ? Success : NumericalIssue;\n  return true;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_KLUSUPPORT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/LU/Determinant.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_DETERMINANT_H\n#define EIGEN_DETERMINANT_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC\ninline const typename Derived::Scalar bruteforce_det3_helper\n(const MatrixBase<Derived>& matrix, int a, int b, int c)\n{\n  return matrix.coeff(0,a)\n         * (matrix.coeff(1,b) * matrix.coeff(2,c) - matrix.coeff(1,c) * matrix.coeff(2,b));\n}\n\ntemplate<typename Derived,\n         int DeterminantType = Derived::RowsAtCompileTime\n> struct determinant_impl\n{\n  static inline typename traits<Derived>::Scalar run(const Derived& m)\n  {\n    if(Derived::ColsAtCompileTime==Dynamic && m.rows()==0)\n      return typename traits<Derived>::Scalar(1);\n    return m.partialPivLu().determinant();\n  }\n};\n\ntemplate<typename Derived> struct determinant_impl<Derived, 1>\n{\n  static inline EIGEN_DEVICE_FUNC\n  typename traits<Derived>::Scalar run(const Derived& m)\n  {\n    return m.coeff(0,0);\n  }\n};\n\ntemplate<typename Derived> struct determinant_impl<Derived, 2>\n{\n  static inline EIGEN_DEVICE_FUNC\n  typename traits<Derived>::Scalar run(const Derived& m)\n  {\n    return m.coeff(0,0) * m.coeff(1,1) - m.coeff(1,0) * m.coeff(0,1);\n  }\n};\n\ntemplate<typename Derived> struct determinant_impl<Derived, 3>\n{\n  static inline EIGEN_DEVICE_FUNC\n  typename traits<Derived>::Scalar run(const Derived& m)\n  {\n    return bruteforce_det3_helper(m,0,1,2)\n          - bruteforce_det3_helper(m,1,0,2)\n          + bruteforce_det3_helper(m,2,0,1);\n  }\n};\n\ntemplate<typename Derived> struct determinant_impl<Derived, 4>\n{\n  typedef typename traits<Derived>::Scalar Scalar;\n  static EIGEN_DEVICE_FUNC\n  Scalar run(const Derived& m)\n  {\n    Scalar d2_01 = det2(m, 0, 1);\n    Scalar d2_02 = det2(m, 0, 2);\n    Scalar d2_03 = det2(m, 0, 3);\n    Scalar d2_12 = det2(m, 1, 2);\n    Scalar d2_13 = det2(m, 1, 3);\n    Scalar d2_23 = det2(m, 2, 3);\n    Scalar d3_0 = det3(m, 1,d2_23, 2,d2_13, 3,d2_12);\n    Scalar d3_1 = det3(m, 0,d2_23, 2,d2_03, 3,d2_02);\n    Scalar d3_2 = det3(m, 0,d2_13, 1,d2_03, 3,d2_01);\n    Scalar d3_3 = det3(m, 0,d2_12, 1,d2_02, 2,d2_01);\n    return internal::pmadd(-m(0,3),d3_0, m(1,3)*d3_1) +\n           internal::pmadd(-m(2,3),d3_2, m(3,3)*d3_3);\n  }\nprotected:\n  static EIGEN_DEVICE_FUNC\n  Scalar det2(const Derived& m, Index i0, Index i1)\n  {\n    return m(i0,0) * m(i1,1) - m(i1,0) * m(i0,1);\n  }\n\n  static EIGEN_DEVICE_FUNC\n  Scalar det3(const Derived& m, Index i0, const Scalar& d0, Index i1, const Scalar& d1, Index i2, const Scalar& d2)\n  {\n    return internal::pmadd(m(i0,2), d0, internal::pmadd(-m(i1,2), d1, m(i2,2)*d2));\n  }\n};\n\n} // end namespace internal\n\n/** \\lu_module\n  *\n  * \\returns the determinant of this matrix\n  */\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC\ninline typename internal::traits<Derived>::Scalar MatrixBase<Derived>::determinant() const\n{\n  eigen_assert(rows() == cols());\n  typedef typename internal::nested_eval<Derived,Base::RowsAtCompileTime>::type Nested;\n  return internal::determinant_impl<typename internal::remove_all<Nested>::type>::run(derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_DETERMINANT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/LU/FullPivLU.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_LU_H\n#define EIGEN_LU_H\n\nnamespace Eigen {\n\nnamespace internal {\ntemplate<typename MatrixType_> struct traits<FullPivLU<MatrixType_> >\n : traits<MatrixType_>\n{\n  typedef MatrixXpr XprKind;\n  typedef SolverStorage StorageKind;\n  typedef int StorageIndex;\n  enum { Flags = 0 };\n};\n\n} // end namespace internal\n\n/** \\ingroup LU_Module\n  *\n  * \\class FullPivLU\n  *\n  * \\brief LU decomposition of a matrix with complete pivoting, and related features\n  *\n  * \\tparam MatrixType_ the type of the matrix of which we are computing the LU decomposition\n  *\n  * This class represents a LU decomposition of any matrix, with complete pivoting: the matrix A is\n  * decomposed as \\f$ A = P^{-1} L U Q^{-1} \\f$ where L is unit-lower-triangular, U is\n  * upper-triangular, and P and Q are permutation matrices. This is a rank-revealing LU\n  * decomposition. The eigenvalues (diagonal coefficients) of U are sorted in such a way that any\n  * zeros are at the end.\n  *\n  * This decomposition provides the generic approach to solving systems of linear equations, computing\n  * the rank, invertibility, inverse, kernel, and determinant.\n  *\n  * This LU decomposition is very stable and well tested with large matrices. However there are use cases where the SVD\n  * decomposition is inherently more stable and/or flexible. For example, when computing the kernel of a matrix,\n  * working with the SVD allows to select the smallest singular values of the matrix, something that\n  * the LU decomposition doesn't see.\n  *\n  * The data of the LU decomposition can be directly accessed through the methods matrixLU(),\n  * permutationP(), permutationQ().\n  *\n  * As an example, here is how the original matrix can be retrieved:\n  * \\include class_FullPivLU.cpp\n  * Output: \\verbinclude class_FullPivLU.out\n  *\n  * This class supports the \\link InplaceDecomposition inplace decomposition \\endlink mechanism.\n  *\n  * \\sa MatrixBase::fullPivLu(), MatrixBase::determinant(), MatrixBase::inverse()\n  */\ntemplate<typename MatrixType_> class FullPivLU\n  : public SolverBase<FullPivLU<MatrixType_> >\n{\n  public:\n    typedef MatrixType_ MatrixType;\n    typedef SolverBase<FullPivLU> Base;\n    friend class SolverBase<FullPivLU>;\n\n    EIGEN_GENERIC_PUBLIC_INTERFACE(FullPivLU)\n    enum {\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n    typedef typename internal::plain_row_type<MatrixType, StorageIndex>::type IntRowVectorType;\n    typedef typename internal::plain_col_type<MatrixType, StorageIndex>::type IntColVectorType;\n    typedef PermutationMatrix<ColsAtCompileTime, MaxColsAtCompileTime> PermutationQType;\n    typedef PermutationMatrix<RowsAtCompileTime, MaxRowsAtCompileTime> PermutationPType;\n    typedef typename MatrixType::PlainObject PlainObject;\n\n    /**\n      * \\brief Default Constructor.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via LU::compute(const MatrixType&).\n      */\n    FullPivLU();\n\n    /** \\brief Default Constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem \\a size.\n      * \\sa FullPivLU()\n      */\n    FullPivLU(Index rows, Index cols);\n\n    /** Constructor.\n      *\n      * \\param matrix the matrix of which to compute the LU decomposition.\n      *               It is required to be nonzero.\n      */\n    template<typename InputType>\n    explicit FullPivLU(const EigenBase<InputType>& matrix);\n\n    /** \\brief Constructs a LU factorization from a given matrix\n      *\n      * This overloaded constructor is provided for \\link InplaceDecomposition inplace decomposition \\endlink when \\c MatrixType is a Eigen::Ref.\n      *\n      * \\sa FullPivLU(const EigenBase&)\n      */\n    template<typename InputType>\n    explicit FullPivLU(EigenBase<InputType>& matrix);\n\n    /** Computes the LU decomposition of the given matrix.\n      *\n      * \\param matrix the matrix of which to compute the LU decomposition.\n      *               It is required to be nonzero.\n      *\n      * \\returns a reference to *this\n      */\n    template<typename InputType>\n    FullPivLU& compute(const EigenBase<InputType>& matrix) {\n      m_lu = matrix.derived();\n      computeInPlace();\n      return *this;\n    }\n\n    /** \\returns the LU decomposition matrix: the upper-triangular part is U, the\n      * unit-lower-triangular part is L (at least for square matrices; in the non-square\n      * case, special care is needed, see the documentation of class FullPivLU).\n      *\n      * \\sa matrixL(), matrixU()\n      */\n    inline const MatrixType& matrixLU() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return m_lu;\n    }\n\n    /** \\returns the number of nonzero pivots in the LU decomposition.\n      * Here nonzero is meant in the exact sense, not in a fuzzy sense.\n      * So that notion isn't really intrinsically interesting, but it is\n      * still useful when implementing algorithms.\n      *\n      * \\sa rank()\n      */\n    inline Index nonzeroPivots() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return m_nonzero_pivots;\n    }\n\n    /** \\returns the absolute value of the biggest pivot, i.e. the biggest\n      *          diagonal coefficient of U.\n      */\n    RealScalar maxPivot() const { return m_maxpivot; }\n\n    /** \\returns the permutation matrix P\n      *\n      * \\sa permutationQ()\n      */\n    EIGEN_DEVICE_FUNC inline const PermutationPType& permutationP() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return m_p;\n    }\n\n    /** \\returns the permutation matrix Q\n      *\n      * \\sa permutationP()\n      */\n    inline const PermutationQType& permutationQ() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return m_q;\n    }\n\n    /** \\returns the kernel of the matrix, also called its null-space. The columns of the returned matrix\n      * will form a basis of the kernel.\n      *\n      * \\note If the kernel has dimension zero, then the returned matrix is a column-vector filled with zeros.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      *\n      * Example: \\include FullPivLU_kernel.cpp\n      * Output: \\verbinclude FullPivLU_kernel.out\n      *\n      * \\sa image()\n      */\n    inline const internal::kernel_retval<FullPivLU> kernel() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return internal::kernel_retval<FullPivLU>(*this);\n    }\n\n    /** \\returns the image of the matrix, also called its column-space. The columns of the returned matrix\n      * will form a basis of the image (column-space).\n      *\n      * \\param originalMatrix the original matrix, of which *this is the LU decomposition.\n      *                       The reason why it is needed to pass it here, is that this allows\n      *                       a large optimization, as otherwise this method would need to reconstruct it\n      *                       from the LU decomposition.\n      *\n      * \\note If the image has dimension zero, then the returned matrix is a column-vector filled with zeros.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      *\n      * Example: \\include FullPivLU_image.cpp\n      * Output: \\verbinclude FullPivLU_image.out\n      *\n      * \\sa kernel()\n      */\n    inline const internal::image_retval<FullPivLU>\n      image(const MatrixType& originalMatrix) const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return internal::image_retval<FullPivLU>(*this, originalMatrix);\n    }\n\n    #ifdef EIGEN_PARSED_BY_DOXYGEN\n    /** \\return a solution x to the equation Ax=b, where A is the matrix of which\n      * *this is the LU decomposition.\n      *\n      * \\param b the right-hand-side of the equation to solve. Can be a vector or a matrix,\n      *          the only requirement in order for the equation to make sense is that\n      *          b.rows()==A.rows(), where A is the matrix of which *this is the LU decomposition.\n      *\n      * \\returns a solution.\n      *\n      * \\note_about_checking_solutions\n      *\n      * \\note_about_arbitrary_choice_of_solution\n      * \\note_about_using_kernel_to_study_multiple_solutions\n      *\n      * Example: \\include FullPivLU_solve.cpp\n      * Output: \\verbinclude FullPivLU_solve.out\n      *\n      * \\sa TriangularView::solve(), kernel(), inverse()\n      */\n    template<typename Rhs>\n    inline const Solve<FullPivLU, Rhs>\n    solve(const MatrixBase<Rhs>& b) const;\n    #endif\n\n    /** \\returns an estimate of the reciprocal condition number of the matrix of which \\c *this is\n        the LU decomposition.\n      */\n    inline RealScalar rcond() const\n    {\n      eigen_assert(m_isInitialized && \"PartialPivLU is not initialized.\");\n      return internal::rcond_estimate_helper(m_l1_norm, *this);\n    }\n\n    /** \\returns the determinant of the matrix of which\n      * *this is the LU decomposition. It has only linear complexity\n      * (that is, O(n) where n is the dimension of the square matrix)\n      * as the LU decomposition has already been computed.\n      *\n      * \\note This is only for square matrices.\n      *\n      * \\note For fixed-size matrices of size up to 4, MatrixBase::determinant() offers\n      *       optimized paths.\n      *\n      * \\warning a determinant can be very big or small, so for matrices\n      * of large enough dimension, there is a risk of overflow/underflow.\n      *\n      * \\sa MatrixBase::determinant()\n      */\n    typename internal::traits<MatrixType>::Scalar determinant() const;\n\n    /** Allows to prescribe a threshold to be used by certain methods, such as rank(),\n      * who need to determine when pivots are to be considered nonzero. This is not used for the\n      * LU decomposition itself.\n      *\n      * When it needs to get the threshold value, Eigen calls threshold(). By default, this\n      * uses a formula to automatically determine a reasonable threshold.\n      * Once you have called the present method setThreshold(const RealScalar&),\n      * your value is used instead.\n      *\n      * \\param threshold The new value to use as the threshold.\n      *\n      * A pivot will be considered nonzero if its absolute value is strictly greater than\n      *  \\f$ \\vert pivot \\vert \\leqslant threshold \\times \\vert maxpivot \\vert \\f$\n      * where maxpivot is the biggest pivot.\n      *\n      * If you want to come back to the default behavior, call setThreshold(Default_t)\n      */\n    FullPivLU& setThreshold(const RealScalar& threshold)\n    {\n      m_usePrescribedThreshold = true;\n      m_prescribedThreshold = threshold;\n      return *this;\n    }\n\n    /** Allows to come back to the default behavior, letting Eigen use its default formula for\n      * determining the threshold.\n      *\n      * You should pass the special object Eigen::Default as parameter here.\n      * \\code lu.setThreshold(Eigen::Default); \\endcode\n      *\n      * See the documentation of setThreshold(const RealScalar&).\n      */\n    FullPivLU& setThreshold(Default_t)\n    {\n      m_usePrescribedThreshold = false;\n      return *this;\n    }\n\n    /** Returns the threshold that will be used by certain methods such as rank().\n      *\n      * See the documentation of setThreshold(const RealScalar&).\n      */\n    RealScalar threshold() const\n    {\n      eigen_assert(m_isInitialized || m_usePrescribedThreshold);\n      return m_usePrescribedThreshold ? m_prescribedThreshold\n      // this formula comes from experimenting (see \"LU precision tuning\" thread on the list)\n      // and turns out to be identical to Higham's formula used already in LDLt.\n          : NumTraits<Scalar>::epsilon() * RealScalar(m_lu.diagonalSize());\n    }\n\n    /** \\returns the rank of the matrix of which *this is the LU decomposition.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline Index rank() const\n    {\n      using std::abs;\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      RealScalar premultiplied_threshold = abs(m_maxpivot) * threshold();\n      Index result = 0;\n      for(Index i = 0; i < m_nonzero_pivots; ++i)\n        result += (abs(m_lu.coeff(i,i)) > premultiplied_threshold);\n      return result;\n    }\n\n    /** \\returns the dimension of the kernel of the matrix of which *this is the LU decomposition.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline Index dimensionOfKernel() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return cols() - rank();\n    }\n\n    /** \\returns true if the matrix of which *this is the LU decomposition represents an injective\n      *          linear map, i.e. has trivial kernel; false otherwise.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline bool isInjective() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return rank() == cols();\n    }\n\n    /** \\returns true if the matrix of which *this is the LU decomposition represents a surjective\n      *          linear map; false otherwise.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline bool isSurjective() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return rank() == rows();\n    }\n\n    /** \\returns true if the matrix of which *this is the LU decomposition is invertible.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline bool isInvertible() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return isInjective() && (m_lu.rows() == m_lu.cols());\n    }\n\n    /** \\returns the inverse of the matrix of which *this is the LU decomposition.\n      *\n      * \\note If this matrix is not invertible, the returned matrix has undefined coefficients.\n      *       Use isInvertible() to first determine whether this matrix is invertible.\n      *\n      * \\sa MatrixBase::inverse()\n      */\n    inline const Inverse<FullPivLU> inverse() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      eigen_assert(m_lu.rows() == m_lu.cols() && \"You can't take the inverse of a non-square matrix!\");\n      return Inverse<FullPivLU>(*this);\n    }\n\n    MatrixType reconstructedMatrix() const;\n\n    EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR\n    inline Index rows() const EIGEN_NOEXCEPT { return m_lu.rows(); }\n    EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR\n    inline Index cols() const EIGEN_NOEXCEPT { return m_lu.cols(); }\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<typename RhsType, typename DstType>\n    void _solve_impl(const RhsType &rhs, DstType &dst) const;\n\n    template<bool Conjugate, typename RhsType, typename DstType>\n    void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const;\n    #endif\n\n  protected:\n\n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n    }\n\n    void computeInPlace();\n\n    MatrixType m_lu;\n    PermutationPType m_p;\n    PermutationQType m_q;\n    IntColVectorType m_rowsTranspositions;\n    IntRowVectorType m_colsTranspositions;\n    Index m_nonzero_pivots;\n    RealScalar m_l1_norm;\n    RealScalar m_maxpivot, m_prescribedThreshold;\n    signed char m_det_pq;\n    bool m_isInitialized, m_usePrescribedThreshold;\n};\n\ntemplate<typename MatrixType>\nFullPivLU<MatrixType>::FullPivLU()\n  : m_isInitialized(false), m_usePrescribedThreshold(false)\n{\n}\n\ntemplate<typename MatrixType>\nFullPivLU<MatrixType>::FullPivLU(Index rows, Index cols)\n  : m_lu(rows, cols),\n    m_p(rows),\n    m_q(cols),\n    m_rowsTranspositions(rows),\n    m_colsTranspositions(cols),\n    m_isInitialized(false),\n    m_usePrescribedThreshold(false)\n{\n}\n\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nFullPivLU<MatrixType>::FullPivLU(const EigenBase<InputType>& matrix)\n  : m_lu(matrix.rows(), matrix.cols()),\n    m_p(matrix.rows()),\n    m_q(matrix.cols()),\n    m_rowsTranspositions(matrix.rows()),\n    m_colsTranspositions(matrix.cols()),\n    m_isInitialized(false),\n    m_usePrescribedThreshold(false)\n{\n  compute(matrix.derived());\n}\n\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nFullPivLU<MatrixType>::FullPivLU(EigenBase<InputType>& matrix)\n  : m_lu(matrix.derived()),\n    m_p(matrix.rows()),\n    m_q(matrix.cols()),\n    m_rowsTranspositions(matrix.rows()),\n    m_colsTranspositions(matrix.cols()),\n    m_isInitialized(false),\n    m_usePrescribedThreshold(false)\n{\n  computeInPlace();\n}\n\ntemplate<typename MatrixType>\nvoid FullPivLU<MatrixType>::computeInPlace()\n{\n  check_template_parameters();\n\n  // the permutations are stored as int indices, so just to be sure:\n  eigen_assert(m_lu.rows()<=NumTraits<int>::highest() && m_lu.cols()<=NumTraits<int>::highest());\n\n  m_l1_norm = m_lu.cwiseAbs().colwise().sum().maxCoeff();\n\n  const Index size = m_lu.diagonalSize();\n  const Index rows = m_lu.rows();\n  const Index cols = m_lu.cols();\n\n  // will store the transpositions, before we accumulate them at the end.\n  // can't accumulate on-the-fly because that will be done in reverse order for the rows.\n  m_rowsTranspositions.resize(m_lu.rows());\n  m_colsTranspositions.resize(m_lu.cols());\n  Index number_of_transpositions = 0; // number of NONTRIVIAL transpositions, i.e. m_rowsTranspositions[i]!=i\n\n  m_nonzero_pivots = size; // the generic case is that in which all pivots are nonzero (invertible case)\n  m_maxpivot = RealScalar(0);\n\n  for(Index k = 0; k < size; ++k)\n  {\n    // First, we need to find the pivot.\n\n    // biggest coefficient in the remaining bottom-right corner (starting at row k, col k)\n    Index row_of_biggest_in_corner, col_of_biggest_in_corner;\n    typedef internal::scalar_score_coeff_op<Scalar> Scoring;\n    typedef typename Scoring::result_type Score;\n    Score biggest_in_corner;\n    biggest_in_corner = m_lu.bottomRightCorner(rows-k, cols-k)\n                        .unaryExpr(Scoring())\n                        .maxCoeff(&row_of_biggest_in_corner, &col_of_biggest_in_corner);\n    row_of_biggest_in_corner += k; // correct the values! since they were computed in the corner,\n    col_of_biggest_in_corner += k; // need to add k to them.\n\n    if(biggest_in_corner==Score(0))\n    {\n      // before exiting, make sure to initialize the still uninitialized transpositions\n      // in a sane state without destroying what we already have.\n      m_nonzero_pivots = k;\n      for(Index i = k; i < size; ++i)\n      {\n        m_rowsTranspositions.coeffRef(i) = internal::convert_index<StorageIndex>(i);\n        m_colsTranspositions.coeffRef(i) = internal::convert_index<StorageIndex>(i);\n      }\n      break;\n    }\n\n    RealScalar abs_pivot = internal::abs_knowing_score<Scalar>()(m_lu(row_of_biggest_in_corner, col_of_biggest_in_corner), biggest_in_corner);\n    if(abs_pivot > m_maxpivot) m_maxpivot = abs_pivot;\n\n    // Now that we've found the pivot, we need to apply the row/col swaps to\n    // bring it to the location (k,k).\n\n    m_rowsTranspositions.coeffRef(k) = internal::convert_index<StorageIndex>(row_of_biggest_in_corner);\n    m_colsTranspositions.coeffRef(k) = internal::convert_index<StorageIndex>(col_of_biggest_in_corner);\n    if(k != row_of_biggest_in_corner) {\n      m_lu.row(k).swap(m_lu.row(row_of_biggest_in_corner));\n      ++number_of_transpositions;\n    }\n    if(k != col_of_biggest_in_corner) {\n      m_lu.col(k).swap(m_lu.col(col_of_biggest_in_corner));\n      ++number_of_transpositions;\n    }\n\n    // Now that the pivot is at the right location, we update the remaining\n    // bottom-right corner by Gaussian elimination.\n\n    if(k<rows-1)\n      m_lu.col(k).tail(rows-k-1) /= m_lu.coeff(k,k);\n    if(k<size-1)\n      m_lu.block(k+1,k+1,rows-k-1,cols-k-1).noalias() -= m_lu.col(k).tail(rows-k-1) * m_lu.row(k).tail(cols-k-1);\n  }\n\n  // the main loop is over, we still have to accumulate the transpositions to find the\n  // permutations P and Q\n\n  m_p.setIdentity(rows);\n  for(Index k = size-1; k >= 0; --k)\n    m_p.applyTranspositionOnTheRight(k, m_rowsTranspositions.coeff(k));\n\n  m_q.setIdentity(cols);\n  for(Index k = 0; k < size; ++k)\n    m_q.applyTranspositionOnTheRight(k, m_colsTranspositions.coeff(k));\n\n  m_det_pq = (number_of_transpositions%2) ? -1 : 1;\n\n  m_isInitialized = true;\n}\n\ntemplate<typename MatrixType>\ntypename internal::traits<MatrixType>::Scalar FullPivLU<MatrixType>::determinant() const\n{\n  eigen_assert(m_isInitialized && \"LU is not initialized.\");\n  eigen_assert(m_lu.rows() == m_lu.cols() && \"You can't take the determinant of a non-square matrix!\");\n  return Scalar(m_det_pq) * Scalar(m_lu.diagonal().prod());\n}\n\n/** \\returns the matrix represented by the decomposition,\n * i.e., it returns the product: \\f$ P^{-1} L U Q^{-1} \\f$.\n * This function is provided for debug purposes. */\ntemplate<typename MatrixType>\nMatrixType FullPivLU<MatrixType>::reconstructedMatrix() const\n{\n  eigen_assert(m_isInitialized && \"LU is not initialized.\");\n  const Index smalldim = (std::min)(m_lu.rows(), m_lu.cols());\n  // LU\n  MatrixType res(m_lu.rows(),m_lu.cols());\n  // FIXME the .toDenseMatrix() should not be needed...\n  res = m_lu.leftCols(smalldim)\n            .template triangularView<UnitLower>().toDenseMatrix()\n      * m_lu.topRows(smalldim)\n            .template triangularView<Upper>().toDenseMatrix();\n\n  // P^{-1}(LU)\n  res = m_p.inverse() * res;\n\n  // (P^{-1}LU)Q^{-1}\n  res = res * m_q.inverse();\n\n  return res;\n}\n\n/********* Implementation of kernel() **************************************************/\n\nnamespace internal {\ntemplate<typename MatrixType_>\nstruct kernel_retval<FullPivLU<MatrixType_> >\n  : kernel_retval_base<FullPivLU<MatrixType_> >\n{\n  EIGEN_MAKE_KERNEL_HELPERS(FullPivLU<MatrixType_>)\n\n  enum { MaxSmallDimAtCompileTime = EIGEN_SIZE_MIN_PREFER_FIXED(\n            MatrixType::MaxColsAtCompileTime,\n            MatrixType::MaxRowsAtCompileTime)\n  };\n\n  template<typename Dest> void evalTo(Dest& dst) const\n  {\n    using std::abs;\n    const Index cols = dec().matrixLU().cols(), dimker = cols - rank();\n    if(dimker == 0)\n    {\n      // The Kernel is just {0}, so it doesn't have a basis properly speaking, but let's\n      // avoid crashing/asserting as that depends on floating point calculations. Let's\n      // just return a single column vector filled with zeros.\n      dst.setZero();\n      return;\n    }\n\n    /* Let us use the following lemma:\n      *\n      * Lemma: If the matrix A has the LU decomposition PAQ = LU,\n      * then Ker A = Q(Ker U).\n      *\n      * Proof: trivial: just keep in mind that P, Q, L are invertible.\n      */\n\n    /* Thus, all we need to do is to compute Ker U, and then apply Q.\n      *\n      * U is upper triangular, with eigenvalues sorted so that any zeros appear at the end.\n      * Thus, the diagonal of U ends with exactly\n      * dimKer zero's. Let us use that to construct dimKer linearly\n      * independent vectors in Ker U.\n      */\n\n    Matrix<Index, Dynamic, 1, 0, MaxSmallDimAtCompileTime, 1> pivots(rank());\n    RealScalar premultiplied_threshold = dec().maxPivot() * dec().threshold();\n    Index p = 0;\n    for(Index i = 0; i < dec().nonzeroPivots(); ++i)\n      if(abs(dec().matrixLU().coeff(i,i)) > premultiplied_threshold)\n        pivots.coeffRef(p++) = i;\n    eigen_internal_assert(p == rank());\n\n    // we construct a temporaty trapezoid matrix m, by taking the U matrix and\n    // permuting the rows and cols to bring the nonnegligible pivots to the top of\n    // the main diagonal. We need that to be able to apply our triangular solvers.\n    // FIXME when we get triangularView-for-rectangular-matrices, this can be simplified\n    Matrix<typename MatrixType::Scalar, Dynamic, Dynamic, MatrixType::Options,\n           MaxSmallDimAtCompileTime, MatrixType::MaxColsAtCompileTime>\n      m(dec().matrixLU().block(0, 0, rank(), cols));\n    for(Index i = 0; i < rank(); ++i)\n    {\n      if(i) m.row(i).head(i).setZero();\n      m.row(i).tail(cols-i) = dec().matrixLU().row(pivots.coeff(i)).tail(cols-i);\n    }\n    m.block(0, 0, rank(), rank());\n    m.block(0, 0, rank(), rank()).template triangularView<StrictlyLower>().setZero();\n    for(Index i = 0; i < rank(); ++i)\n      m.col(i).swap(m.col(pivots.coeff(i)));\n\n    // ok, we have our trapezoid matrix, we can apply the triangular solver.\n    // notice that the math behind this suggests that we should apply this to the\n    // negative of the RHS, but for performance we just put the negative sign elsewhere, see below.\n    m.topLeftCorner(rank(), rank())\n     .template triangularView<Upper>().solveInPlace(\n        m.topRightCorner(rank(), dimker)\n      );\n\n    // now we must undo the column permutation that we had applied!\n    for(Index i = rank()-1; i >= 0; --i)\n      m.col(i).swap(m.col(pivots.coeff(i)));\n\n    // see the negative sign in the next line, that's what we were talking about above.\n    for(Index i = 0; i < rank(); ++i) dst.row(dec().permutationQ().indices().coeff(i)) = -m.row(i).tail(dimker);\n    for(Index i = rank(); i < cols; ++i) dst.row(dec().permutationQ().indices().coeff(i)).setZero();\n    for(Index k = 0; k < dimker; ++k) dst.coeffRef(dec().permutationQ().indices().coeff(rank()+k), k) = Scalar(1);\n  }\n};\n\n/***** Implementation of image() *****************************************************/\n\ntemplate<typename MatrixType_>\nstruct image_retval<FullPivLU<MatrixType_> >\n  : image_retval_base<FullPivLU<MatrixType_> >\n{\n  EIGEN_MAKE_IMAGE_HELPERS(FullPivLU<MatrixType_>)\n\n  enum { MaxSmallDimAtCompileTime = EIGEN_SIZE_MIN_PREFER_FIXED(\n            MatrixType::MaxColsAtCompileTime,\n            MatrixType::MaxRowsAtCompileTime)\n  };\n\n  template<typename Dest> void evalTo(Dest& dst) const\n  {\n    using std::abs;\n    if(rank() == 0)\n    {\n      // The Image is just {0}, so it doesn't have a basis properly speaking, but let's\n      // avoid crashing/asserting as that depends on floating point calculations. Let's\n      // just return a single column vector filled with zeros.\n      dst.setZero();\n      return;\n    }\n\n    Matrix<Index, Dynamic, 1, 0, MaxSmallDimAtCompileTime, 1> pivots(rank());\n    RealScalar premultiplied_threshold = dec().maxPivot() * dec().threshold();\n    Index p = 0;\n    for(Index i = 0; i < dec().nonzeroPivots(); ++i)\n      if(abs(dec().matrixLU().coeff(i,i)) > premultiplied_threshold)\n        pivots.coeffRef(p++) = i;\n    eigen_internal_assert(p == rank());\n\n    for(Index i = 0; i < rank(); ++i)\n      dst.col(i) = originalMatrix().col(dec().permutationQ().indices().coeff(pivots.coeff(i)));\n  }\n};\n\n/***** Implementation of solve() *****************************************************/\n\n} // end namespace internal\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename MatrixType_>\ntemplate<typename RhsType, typename DstType>\nvoid FullPivLU<MatrixType_>::_solve_impl(const RhsType &rhs, DstType &dst) const\n{\n  /* The decomposition PAQ = LU can be rewritten as A = P^{-1} L U Q^{-1}.\n  * So we proceed as follows:\n  * Step 1: compute c = P * rhs.\n  * Step 2: replace c by the solution x to Lx = c. Exists because L is invertible.\n  * Step 3: replace c by the solution x to Ux = c. May or may not exist.\n  * Step 4: result = Q * c;\n  */\n\n  const Index rows = this->rows(),\n              cols = this->cols(),\n              nonzero_pivots = this->rank();\n  const Index smalldim = (std::min)(rows, cols);\n\n  if(nonzero_pivots == 0)\n  {\n    dst.setZero();\n    return;\n  }\n\n  typename RhsType::PlainObject c(rhs.rows(), rhs.cols());\n\n  // Step 1\n  c = permutationP() * rhs;\n\n  // Step 2\n  m_lu.topLeftCorner(smalldim,smalldim)\n      .template triangularView<UnitLower>()\n      .solveInPlace(c.topRows(smalldim));\n  if(rows>cols)\n    c.bottomRows(rows-cols) -= m_lu.bottomRows(rows-cols) * c.topRows(cols);\n\n  // Step 3\n  m_lu.topLeftCorner(nonzero_pivots, nonzero_pivots)\n      .template triangularView<Upper>()\n      .solveInPlace(c.topRows(nonzero_pivots));\n\n  // Step 4\n  for(Index i = 0; i < nonzero_pivots; ++i)\n    dst.row(permutationQ().indices().coeff(i)) = c.row(i);\n  for(Index i = nonzero_pivots; i < m_lu.cols(); ++i)\n    dst.row(permutationQ().indices().coeff(i)).setZero();\n}\n\ntemplate<typename MatrixType_>\ntemplate<bool Conjugate, typename RhsType, typename DstType>\nvoid FullPivLU<MatrixType_>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const\n{\n  /* The decomposition PAQ = LU can be rewritten as A = P^{-1} L U Q^{-1},\n   * and since permutations are real and unitary, we can write this\n   * as   A^T = Q U^T L^T P,\n   * So we proceed as follows:\n   * Step 1: compute c = Q^T rhs.\n   * Step 2: replace c by the solution x to U^T x = c. May or may not exist.\n   * Step 3: replace c by the solution x to L^T x = c.\n   * Step 4: result = P^T c.\n   * If Conjugate is true, replace \"^T\" by \"^*\" above.\n   */\n\n  const Index rows = this->rows(), cols = this->cols(),\n    nonzero_pivots = this->rank();\n  const Index smalldim = (std::min)(rows, cols);\n\n  if(nonzero_pivots == 0)\n  {\n    dst.setZero();\n    return;\n  }\n\n  typename RhsType::PlainObject c(rhs.rows(), rhs.cols());\n\n  // Step 1\n  c = permutationQ().inverse() * rhs;\n\n  // Step 2\n  m_lu.topLeftCorner(nonzero_pivots, nonzero_pivots)\n      .template triangularView<Upper>()\n      .transpose()\n      .template conjugateIf<Conjugate>()\n      .solveInPlace(c.topRows(nonzero_pivots));\n\n  // Step 3\n  m_lu.topLeftCorner(smalldim, smalldim)\n      .template triangularView<UnitLower>()\n      .transpose()\n      .template conjugateIf<Conjugate>()\n      .solveInPlace(c.topRows(smalldim));\n\n  // Step 4\n  PermutationPType invp = permutationP().inverse().eval();\n  for(Index i = 0; i < smalldim; ++i)\n    dst.row(invp.indices().coeff(i)) = c.row(i);\n  for(Index i = smalldim; i < rows; ++i)\n    dst.row(invp.indices().coeff(i)).setZero();\n}\n\n#endif\n\nnamespace internal {\n\n\n/***** Implementation of inverse() *****************************************************/\ntemplate<typename DstXprType, typename MatrixType>\nstruct Assignment<DstXprType, Inverse<FullPivLU<MatrixType> >, internal::assign_op<typename DstXprType::Scalar,typename FullPivLU<MatrixType>::Scalar>, Dense2Dense>\n{\n  typedef FullPivLU<MatrixType> LuType;\n  typedef Inverse<LuType> SrcXprType;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename MatrixType::Scalar> &)\n  {\n    dst = src.nestedExpression().solve(MatrixType::Identity(src.rows(), src.cols()));\n  }\n};\n} // end namespace internal\n\n/******* MatrixBase methods *****************************************************************/\n\n/** \\lu_module\n  *\n  * \\return the full-pivoting LU decomposition of \\c *this.\n  *\n  * \\sa class FullPivLU\n  */\ntemplate<typename Derived>\ninline const FullPivLU<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::fullPivLu() const\n{\n  return FullPivLU<PlainObject>(eval());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_LU_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/LU/InverseImpl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_INVERSE_IMPL_H\n#define EIGEN_INVERSE_IMPL_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/**********************************\n*** General case implementation ***\n**********************************/\n\ntemplate<typename MatrixType, typename ResultType, int Size = MatrixType::RowsAtCompileTime>\nstruct compute_inverse\n{\n  EIGEN_DEVICE_FUNC\n  static inline void run(const MatrixType& matrix, ResultType& result)\n  {\n    result = matrix.partialPivLu().inverse();\n  }\n};\n\ntemplate<typename MatrixType, typename ResultType, int Size = MatrixType::RowsAtCompileTime>\nstruct compute_inverse_and_det_with_check { /* nothing! general case not supported. */ };\n\n/****************************\n*** Size 1 implementation ***\n****************************/\n\ntemplate<typename MatrixType, typename ResultType>\nstruct compute_inverse<MatrixType, ResultType, 1>\n{\n  EIGEN_DEVICE_FUNC\n  static inline void run(const MatrixType& matrix, ResultType& result)\n  {\n    typedef typename MatrixType::Scalar Scalar;\n    internal::evaluator<MatrixType> matrixEval(matrix);\n    result.coeffRef(0,0) = Scalar(1) / matrixEval.coeff(0,0);\n  }\n};\n\ntemplate<typename MatrixType, typename ResultType>\nstruct compute_inverse_and_det_with_check<MatrixType, ResultType, 1>\n{\n  EIGEN_DEVICE_FUNC\n  static inline void run(\n    const MatrixType& matrix,\n    const typename MatrixType::RealScalar& absDeterminantThreshold,\n    ResultType& result,\n    typename ResultType::Scalar& determinant,\n    bool& invertible\n  )\n  {\n    using std::abs;\n    determinant = matrix.coeff(0,0);\n    invertible = abs(determinant) > absDeterminantThreshold;\n    if(invertible) result.coeffRef(0,0) = typename ResultType::Scalar(1) / determinant;\n  }\n};\n\n/****************************\n*** Size 2 implementation ***\n****************************/\n\ntemplate<typename MatrixType, typename ResultType>\nEIGEN_DEVICE_FUNC \ninline void compute_inverse_size2_helper(\n    const MatrixType& matrix, const typename ResultType::Scalar& invdet,\n    ResultType& result)\n{\n  typename ResultType::Scalar temp = matrix.coeff(0,0);\n  result.coeffRef(0,0) =  matrix.coeff(1,1) * invdet;\n  result.coeffRef(1,0) = -matrix.coeff(1,0) * invdet;\n  result.coeffRef(0,1) = -matrix.coeff(0,1) * invdet;\n  result.coeffRef(1,1) =  temp * invdet;\n}\n\ntemplate<typename MatrixType, typename ResultType>\nstruct compute_inverse<MatrixType, ResultType, 2>\n{\n  EIGEN_DEVICE_FUNC\n  static inline void run(const MatrixType& matrix, ResultType& result)\n  {\n    typedef typename ResultType::Scalar Scalar;\n    const Scalar invdet = typename MatrixType::Scalar(1) / matrix.determinant();\n    compute_inverse_size2_helper(matrix, invdet, result);\n  }\n};\n\ntemplate<typename MatrixType, typename ResultType>\nstruct compute_inverse_and_det_with_check<MatrixType, ResultType, 2>\n{\n  EIGEN_DEVICE_FUNC\n  static inline void run(\n    const MatrixType& matrix,\n    const typename MatrixType::RealScalar& absDeterminantThreshold,\n    ResultType& inverse,\n    typename ResultType::Scalar& determinant,\n    bool& invertible\n  )\n  {\n    using std::abs;\n    typedef typename ResultType::Scalar Scalar;\n    determinant = matrix.determinant();\n    invertible = abs(determinant) > absDeterminantThreshold;\n    if(!invertible) return;\n    const Scalar invdet = Scalar(1) / determinant;\n    compute_inverse_size2_helper(matrix, invdet, inverse);\n  }\n};\n\n/****************************\n*** Size 3 implementation ***\n****************************/\n\ntemplate<typename MatrixType, int i, int j>\nEIGEN_DEVICE_FUNC \ninline typename MatrixType::Scalar cofactor_3x3(const MatrixType& m)\n{\n  enum {\n    i1 = (i+1) % 3,\n    i2 = (i+2) % 3,\n    j1 = (j+1) % 3,\n    j2 = (j+2) % 3\n  };\n  return m.coeff(i1, j1) * m.coeff(i2, j2)\n       - m.coeff(i1, j2) * m.coeff(i2, j1);\n}\n\ntemplate<typename MatrixType, typename ResultType>\nEIGEN_DEVICE_FUNC\ninline void compute_inverse_size3_helper(\n    const MatrixType& matrix,\n    const typename ResultType::Scalar& invdet,\n    const Matrix<typename ResultType::Scalar,3,1>& cofactors_col0,\n    ResultType& result)\n{\n  // Compute cofactors in a way that avoids aliasing issues.\n  typedef typename ResultType::Scalar Scalar;\n  const Scalar c01 = cofactor_3x3<MatrixType,0,1>(matrix) * invdet;\n  const Scalar c11 = cofactor_3x3<MatrixType,1,1>(matrix) * invdet;\n  const Scalar c02 = cofactor_3x3<MatrixType,0,2>(matrix) * invdet;\n  result.coeffRef(1,2) =  cofactor_3x3<MatrixType,2,1>(matrix) * invdet;\n  result.coeffRef(2,1) =  cofactor_3x3<MatrixType,1,2>(matrix) * invdet;\n  result.coeffRef(2,2) =  cofactor_3x3<MatrixType,2,2>(matrix) * invdet;\n  result.coeffRef(1,0) =  c01;\n  result.coeffRef(1,1) =  c11;\n  result.coeffRef(2,0) =  c02;  \n  result.row(0) = cofactors_col0 * invdet;\n}\n\ntemplate<typename MatrixType, typename ResultType>\nstruct compute_inverse<MatrixType, ResultType, 3>\n{\n  EIGEN_DEVICE_FUNC\n  static inline void run(const MatrixType& matrix, ResultType& result)\n  {\n    typedef typename ResultType::Scalar Scalar;\n    Matrix<typename MatrixType::Scalar,3,1> cofactors_col0;\n    cofactors_col0.coeffRef(0) =  cofactor_3x3<MatrixType,0,0>(matrix);\n    cofactors_col0.coeffRef(1) =  cofactor_3x3<MatrixType,1,0>(matrix);\n    cofactors_col0.coeffRef(2) =  cofactor_3x3<MatrixType,2,0>(matrix);\n    const Scalar det = (cofactors_col0.cwiseProduct(matrix.col(0))).sum();\n    const Scalar invdet = Scalar(1) / det;\n    compute_inverse_size3_helper(matrix, invdet, cofactors_col0, result);\n  }\n};\n\ntemplate<typename MatrixType, typename ResultType>\nstruct compute_inverse_and_det_with_check<MatrixType, ResultType, 3>\n{\n  EIGEN_DEVICE_FUNC\n  static inline void run(\n    const MatrixType& matrix,\n    const typename MatrixType::RealScalar& absDeterminantThreshold,\n    ResultType& inverse,\n    typename ResultType::Scalar& determinant,\n    bool& invertible\n  )\n  {\n    typedef typename ResultType::Scalar Scalar;\n    Matrix<Scalar,3,1> cofactors_col0;\n    cofactors_col0.coeffRef(0) =  cofactor_3x3<MatrixType,0,0>(matrix);\n    cofactors_col0.coeffRef(1) =  cofactor_3x3<MatrixType,1,0>(matrix);\n    cofactors_col0.coeffRef(2) =  cofactor_3x3<MatrixType,2,0>(matrix);\n    determinant = (cofactors_col0.cwiseProduct(matrix.col(0))).sum();\n    invertible = Eigen::numext::abs(determinant) > absDeterminantThreshold;\n    if(!invertible) return;\n    const Scalar invdet = Scalar(1) / determinant;\n    compute_inverse_size3_helper(matrix, invdet, cofactors_col0, inverse);\n  }\n};\n\n/****************************\n*** Size 4 implementation ***\n****************************/\n\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC \ninline const typename Derived::Scalar general_det3_helper\n(const MatrixBase<Derived>& matrix, int i1, int i2, int i3, int j1, int j2, int j3)\n{\n  return matrix.coeff(i1,j1)\n         * (matrix.coeff(i2,j2) * matrix.coeff(i3,j3) - matrix.coeff(i2,j3) * matrix.coeff(i3,j2));\n}\n\ntemplate<typename MatrixType, int i, int j>\nEIGEN_DEVICE_FUNC \ninline typename MatrixType::Scalar cofactor_4x4(const MatrixType& matrix)\n{\n  enum {\n    i1 = (i+1) % 4,\n    i2 = (i+2) % 4,\n    i3 = (i+3) % 4,\n    j1 = (j+1) % 4,\n    j2 = (j+2) % 4,\n    j3 = (j+3) % 4\n  };\n  return general_det3_helper(matrix, i1, i2, i3, j1, j2, j3)\n       + general_det3_helper(matrix, i2, i3, i1, j1, j2, j3)\n       + general_det3_helper(matrix, i3, i1, i2, j1, j2, j3);\n}\n\ntemplate<int Arch, typename Scalar, typename MatrixType, typename ResultType>\nstruct compute_inverse_size4\n{\n  EIGEN_DEVICE_FUNC\n  static void run(const MatrixType& matrix, ResultType& result)\n  {\n    result.coeffRef(0,0) =  cofactor_4x4<MatrixType,0,0>(matrix);\n    result.coeffRef(1,0) = -cofactor_4x4<MatrixType,0,1>(matrix);\n    result.coeffRef(2,0) =  cofactor_4x4<MatrixType,0,2>(matrix);\n    result.coeffRef(3,0) = -cofactor_4x4<MatrixType,0,3>(matrix);\n    result.coeffRef(0,2) =  cofactor_4x4<MatrixType,2,0>(matrix);\n    result.coeffRef(1,2) = -cofactor_4x4<MatrixType,2,1>(matrix);\n    result.coeffRef(2,2) =  cofactor_4x4<MatrixType,2,2>(matrix);\n    result.coeffRef(3,2) = -cofactor_4x4<MatrixType,2,3>(matrix);\n    result.coeffRef(0,1) = -cofactor_4x4<MatrixType,1,0>(matrix);\n    result.coeffRef(1,1) =  cofactor_4x4<MatrixType,1,1>(matrix);\n    result.coeffRef(2,1) = -cofactor_4x4<MatrixType,1,2>(matrix);\n    result.coeffRef(3,1) =  cofactor_4x4<MatrixType,1,3>(matrix);\n    result.coeffRef(0,3) = -cofactor_4x4<MatrixType,3,0>(matrix);\n    result.coeffRef(1,3) =  cofactor_4x4<MatrixType,3,1>(matrix);\n    result.coeffRef(2,3) = -cofactor_4x4<MatrixType,3,2>(matrix);\n    result.coeffRef(3,3) =  cofactor_4x4<MatrixType,3,3>(matrix);\n    result /= (matrix.col(0).cwiseProduct(result.row(0).transpose())).sum();\n  }\n};\n\ntemplate<typename MatrixType, typename ResultType>\nstruct compute_inverse<MatrixType, ResultType, 4>\n : compute_inverse_size4<Architecture::Target, typename MatrixType::Scalar,\n                            MatrixType, ResultType>\n{\n};\n\ntemplate<typename MatrixType, typename ResultType>\nstruct compute_inverse_and_det_with_check<MatrixType, ResultType, 4>\n{\n  EIGEN_DEVICE_FUNC\n  static inline void run(\n    const MatrixType& matrix,\n    const typename MatrixType::RealScalar& absDeterminantThreshold,\n    ResultType& inverse,\n    typename ResultType::Scalar& determinant,\n    bool& invertible\n  )\n  {\n    using std::abs;\n    determinant = matrix.determinant();\n    invertible = abs(determinant) > absDeterminantThreshold;\n    if(invertible && extract_data(matrix) != extract_data(inverse)) {\n      compute_inverse<MatrixType, ResultType>::run(matrix, inverse);\n    }\n    else if(invertible) {\n      MatrixType matrix_t = matrix;\n      compute_inverse<MatrixType, ResultType>::run(matrix_t, inverse);\n    }\n  }\n};\n\n/*************************\n*** MatrixBase methods ***\n*************************/\n\n} // end namespace internal\n\nnamespace internal {\n\n// Specialization for \"dense = dense_xpr.inverse()\"\ntemplate<typename DstXprType, typename XprType>\nstruct Assignment<DstXprType, Inverse<XprType>, internal::assign_op<typename DstXprType::Scalar,typename XprType::Scalar>, Dense2Dense>\n{\n  typedef Inverse<XprType> SrcXprType;\n  EIGEN_DEVICE_FUNC\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename XprType::Scalar> &)\n  {\n    Index dstRows = src.rows();\n    Index dstCols = src.cols();\n    if((dst.rows()!=dstRows) || (dst.cols()!=dstCols))\n      dst.resize(dstRows, dstCols);\n    \n    const int Size = EIGEN_PLAIN_ENUM_MIN(XprType::ColsAtCompileTime,DstXprType::ColsAtCompileTime);\n    EIGEN_ONLY_USED_FOR_DEBUG(Size);\n    eigen_assert(( (Size<=1) || (Size>4) || (extract_data(src.nestedExpression())!=extract_data(dst)))\n              && \"Aliasing problem detected in inverse(), you need to do inverse().eval() here.\");\n\n    typedef typename internal::nested_eval<XprType,XprType::ColsAtCompileTime>::type  ActualXprType;\n    typedef typename internal::remove_all<ActualXprType>::type                        ActualXprTypeCleanded;\n    \n    ActualXprType actual_xpr(src.nestedExpression());\n    \n    compute_inverse<ActualXprTypeCleanded, DstXprType>::run(actual_xpr, dst);\n  }\n};\n\n  \n} // end namespace internal\n\n/** \\lu_module\n  *\n  * \\returns the matrix inverse of this matrix.\n  *\n  * For small fixed sizes up to 4x4, this method uses cofactors.\n  * In the general case, this method uses class PartialPivLU.\n  *\n  * \\note This matrix must be invertible, otherwise the result is undefined. If you need an\n  * invertibility check, do the following:\n  * \\li for fixed sizes up to 4x4, use computeInverseAndDetWithCheck().\n  * \\li for the general case, use class FullPivLU.\n  *\n  * Example: \\include MatrixBase_inverse.cpp\n  * Output: \\verbinclude MatrixBase_inverse.out\n  *\n  * \\sa computeInverseAndDetWithCheck()\n  */\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC\ninline const Inverse<Derived> MatrixBase<Derived>::inverse() const\n{\n  EIGEN_STATIC_ASSERT(!NumTraits<Scalar>::IsInteger,THIS_FUNCTION_IS_NOT_FOR_INTEGER_NUMERIC_TYPES)\n  eigen_assert(rows() == cols());\n  return Inverse<Derived>(derived());\n}\n\n/** \\lu_module\n  *\n  * Computation of matrix inverse and determinant, with invertibility check.\n  *\n  * This is only for fixed-size square matrices of size up to 4x4.\n  *\n  * Notice that it will trigger a copy of input matrix when trying to do the inverse in place.\n  *\n  * \\param inverse Reference to the matrix in which to store the inverse.\n  * \\param determinant Reference to the variable in which to store the determinant.\n  * \\param invertible Reference to the bool variable in which to store whether the matrix is invertible.\n  * \\param absDeterminantThreshold Optional parameter controlling the invertibility check.\n  *                                The matrix will be declared invertible if the absolute value of its\n  *                                determinant is greater than this threshold.\n  *\n  * Example: \\include MatrixBase_computeInverseAndDetWithCheck.cpp\n  * Output: \\verbinclude MatrixBase_computeInverseAndDetWithCheck.out\n  *\n  * \\sa inverse(), computeInverseWithCheck()\n  */\ntemplate<typename Derived>\ntemplate<typename ResultType>\ninline void MatrixBase<Derived>::computeInverseAndDetWithCheck(\n    ResultType& inverse,\n    typename ResultType::Scalar& determinant,\n    bool& invertible,\n    const RealScalar& absDeterminantThreshold\n  ) const\n{\n  // i'd love to put some static assertions there, but SFINAE means that they have no effect...\n  eigen_assert(rows() == cols());\n  // for 2x2, it's worth giving a chance to avoid evaluating.\n  // for larger sizes, evaluating has negligible cost and limits code size.\n  typedef typename internal::conditional<\n    RowsAtCompileTime == 2,\n    typename internal::remove_all<typename internal::nested_eval<Derived, 2>::type>::type,\n    PlainObject\n  >::type MatrixType;\n  internal::compute_inverse_and_det_with_check<MatrixType, ResultType>::run\n    (derived(), absDeterminantThreshold, inverse, determinant, invertible);\n}\n\n/** \\lu_module\n  *\n  * Computation of matrix inverse, with invertibility check.\n  *\n  * This is only for fixed-size square matrices of size up to 4x4.\n  *\n  * Notice that it will trigger a copy of input matrix when trying to do the inverse in place.\n  *\n  * \\param inverse Reference to the matrix in which to store the inverse.\n  * \\param invertible Reference to the bool variable in which to store whether the matrix is invertible.\n  * \\param absDeterminantThreshold Optional parameter controlling the invertibility check.\n  *                                The matrix will be declared invertible if the absolute value of its\n  *                                determinant is greater than this threshold.\n  *\n  * Example: \\include MatrixBase_computeInverseWithCheck.cpp\n  * Output: \\verbinclude MatrixBase_computeInverseWithCheck.out\n  *\n  * \\sa inverse(), computeInverseAndDetWithCheck()\n  */\ntemplate<typename Derived>\ntemplate<typename ResultType>\ninline void MatrixBase<Derived>::computeInverseWithCheck(\n    ResultType& inverse,\n    bool& invertible,\n    const RealScalar& absDeterminantThreshold\n  ) const\n{\n  Scalar determinant;\n  // i'd love to put some static assertions there, but SFINAE means that they have no effect...\n  eigen_assert(rows() == cols());\n  computeInverseAndDetWithCheck(inverse,determinant,invertible,absDeterminantThreshold);\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_INVERSE_IMPL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/LU/PartialPivLU.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_PARTIALLU_H\n#define EIGEN_PARTIALLU_H\n\nnamespace Eigen {\n\nnamespace internal {\ntemplate<typename MatrixType_> struct traits<PartialPivLU<MatrixType_> >\n : traits<MatrixType_>\n{\n  typedef MatrixXpr XprKind;\n  typedef SolverStorage StorageKind;\n  typedef int StorageIndex;\n  typedef traits<MatrixType_> BaseTraits;\n  enum {\n    Flags = BaseTraits::Flags & RowMajorBit,\n    CoeffReadCost = Dynamic\n  };\n};\n\ntemplate<typename T,typename Derived>\nstruct enable_if_ref;\n// {\n//   typedef Derived type;\n// };\n\ntemplate<typename T,typename Derived>\nstruct enable_if_ref<Ref<T>,Derived> {\n  typedef Derived type;\n};\n\n} // end namespace internal\n\n/** \\ingroup LU_Module\n  *\n  * \\class PartialPivLU\n  *\n  * \\brief LU decomposition of a matrix with partial pivoting, and related features\n  *\n  * \\tparam MatrixType_ the type of the matrix of which we are computing the LU decomposition\n  *\n  * This class represents a LU decomposition of a \\b square \\b invertible matrix, with partial pivoting: the matrix A\n  * is decomposed as A = PLU where L is unit-lower-triangular, U is upper-triangular, and P\n  * is a permutation matrix.\n  *\n  * Typically, partial pivoting LU decomposition is only considered numerically stable for square invertible\n  * matrices. Thus LAPACK's dgesv and dgesvx require the matrix to be square and invertible. The present class\n  * does the same. It will assert that the matrix is square, but it won't (actually it can't) check that the\n  * matrix is invertible: it is your task to check that you only use this decomposition on invertible matrices.\n  *\n  * The guaranteed safe alternative, working for all matrices, is the full pivoting LU decomposition, provided\n  * by class FullPivLU.\n  *\n  * This is \\b not a rank-revealing LU decomposition. Many features are intentionally absent from this class,\n  * such as rank computation. If you need these features, use class FullPivLU.\n  *\n  * This LU decomposition is suitable to invert invertible matrices. It is what MatrixBase::inverse() uses\n  * in the general case.\n  * On the other hand, it is \\b not suitable to determine whether a given matrix is invertible.\n  *\n  * The data of the LU decomposition can be directly accessed through the methods matrixLU(), permutationP().\n  *\n  * This class supports the \\link InplaceDecomposition inplace decomposition \\endlink mechanism.\n  *\n  * \\sa MatrixBase::partialPivLu(), MatrixBase::determinant(), MatrixBase::inverse(), MatrixBase::computeInverse(), class FullPivLU\n  */\ntemplate<typename MatrixType_> class PartialPivLU\n  : public SolverBase<PartialPivLU<MatrixType_> >\n{\n  public:\n\n    typedef MatrixType_ MatrixType;\n    typedef SolverBase<PartialPivLU> Base;\n    friend class SolverBase<PartialPivLU>;\n\n    EIGEN_GENERIC_PUBLIC_INTERFACE(PartialPivLU)\n    enum {\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n    typedef PermutationMatrix<RowsAtCompileTime, MaxRowsAtCompileTime> PermutationType;\n    typedef Transpositions<RowsAtCompileTime, MaxRowsAtCompileTime> TranspositionType;\n    typedef typename MatrixType::PlainObject PlainObject;\n\n    /**\n      * \\brief Default Constructor.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via PartialPivLU::compute(const MatrixType&).\n      */\n    PartialPivLU();\n\n    /** \\brief Default Constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem \\a size.\n      * \\sa PartialPivLU()\n      */\n    explicit PartialPivLU(Index size);\n\n    /** Constructor.\n      *\n      * \\param matrix the matrix of which to compute the LU decomposition.\n      *\n      * \\warning The matrix should have full rank (e.g. if it's square, it should be invertible).\n      * If you need to deal with non-full rank, use class FullPivLU instead.\n      */\n    template<typename InputType>\n    explicit PartialPivLU(const EigenBase<InputType>& matrix);\n\n    /** Constructor for \\link InplaceDecomposition inplace decomposition \\endlink\n      *\n      * \\param matrix the matrix of which to compute the LU decomposition.\n      *\n      * \\warning The matrix should have full rank (e.g. if it's square, it should be invertible).\n      * If you need to deal with non-full rank, use class FullPivLU instead.\n      */\n    template<typename InputType>\n    explicit PartialPivLU(EigenBase<InputType>& matrix);\n\n    template<typename InputType>\n    PartialPivLU& compute(const EigenBase<InputType>& matrix) {\n      m_lu = matrix.derived();\n      compute();\n      return *this;\n    }\n\n    /** \\returns the LU decomposition matrix: the upper-triangular part is U, the\n      * unit-lower-triangular part is L (at least for square matrices; in the non-square\n      * case, special care is needed, see the documentation of class FullPivLU).\n      *\n      * \\sa matrixL(), matrixU()\n      */\n    inline const MatrixType& matrixLU() const\n    {\n      eigen_assert(m_isInitialized && \"PartialPivLU is not initialized.\");\n      return m_lu;\n    }\n\n    /** \\returns the permutation matrix P.\n      */\n    inline const PermutationType& permutationP() const\n    {\n      eigen_assert(m_isInitialized && \"PartialPivLU is not initialized.\");\n      return m_p;\n    }\n\n    #ifdef EIGEN_PARSED_BY_DOXYGEN\n    /** This method returns the solution x to the equation Ax=b, where A is the matrix of which\n      * *this is the LU decomposition.\n      *\n      * \\param b the right-hand-side of the equation to solve. Can be a vector or a matrix,\n      *          the only requirement in order for the equation to make sense is that\n      *          b.rows()==A.rows(), where A is the matrix of which *this is the LU decomposition.\n      *\n      * \\returns the solution.\n      *\n      * Example: \\include PartialPivLU_solve.cpp\n      * Output: \\verbinclude PartialPivLU_solve.out\n      *\n      * Since this PartialPivLU class assumes anyway that the matrix A is invertible, the solution\n      * theoretically exists and is unique regardless of b.\n      *\n      * \\sa TriangularView::solve(), inverse(), computeInverse()\n      */\n    template<typename Rhs>\n    inline const Solve<PartialPivLU, Rhs>\n    solve(const MatrixBase<Rhs>& b) const;\n    #endif\n\n    /** \\returns an estimate of the reciprocal condition number of the matrix of which \\c *this is\n        the LU decomposition.\n      */\n    inline RealScalar rcond() const\n    {\n      eigen_assert(m_isInitialized && \"PartialPivLU is not initialized.\");\n      return internal::rcond_estimate_helper(m_l1_norm, *this);\n    }\n\n    /** \\returns the inverse of the matrix of which *this is the LU decomposition.\n      *\n      * \\warning The matrix being decomposed here is assumed to be invertible. If you need to check for\n      *          invertibility, use class FullPivLU instead.\n      *\n      * \\sa MatrixBase::inverse(), LU::inverse()\n      */\n    inline const Inverse<PartialPivLU> inverse() const\n    {\n      eigen_assert(m_isInitialized && \"PartialPivLU is not initialized.\");\n      return Inverse<PartialPivLU>(*this);\n    }\n\n    /** \\returns the determinant of the matrix of which\n      * *this is the LU decomposition. It has only linear complexity\n      * (that is, O(n) where n is the dimension of the square matrix)\n      * as the LU decomposition has already been computed.\n      *\n      * \\note For fixed-size matrices of size up to 4, MatrixBase::determinant() offers\n      *       optimized paths.\n      *\n      * \\warning a determinant can be very big or small, so for matrices\n      * of large enough dimension, there is a risk of overflow/underflow.\n      *\n      * \\sa MatrixBase::determinant()\n      */\n    Scalar determinant() const;\n\n    MatrixType reconstructedMatrix() const;\n\n    EIGEN_CONSTEXPR inline Index rows() const EIGEN_NOEXCEPT { return m_lu.rows(); }\n    EIGEN_CONSTEXPR inline Index cols() const EIGEN_NOEXCEPT { return m_lu.cols(); }\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<typename RhsType, typename DstType>\n    EIGEN_DEVICE_FUNC\n    void _solve_impl(const RhsType &rhs, DstType &dst) const {\n     /* The decomposition PA = LU can be rewritten as A = P^{-1} L U.\n      * So we proceed as follows:\n      * Step 1: compute c = Pb.\n      * Step 2: replace c by the solution x to Lx = c.\n      * Step 3: replace c by the solution x to Ux = c.\n      */\n\n      // Step 1\n      dst = permutationP() * rhs;\n\n      // Step 2\n      m_lu.template triangularView<UnitLower>().solveInPlace(dst);\n\n      // Step 3\n      m_lu.template triangularView<Upper>().solveInPlace(dst);\n    }\n\n    template<bool Conjugate, typename RhsType, typename DstType>\n    EIGEN_DEVICE_FUNC\n    void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const {\n     /* The decomposition PA = LU can be rewritten as A^T = U^T L^T P.\n      * So we proceed as follows:\n      * Step 1: compute c as the solution to L^T c = b\n      * Step 2: replace c by the solution x to U^T x = c.\n      * Step 3: update  c = P^-1 c.\n      */\n\n      eigen_assert(rhs.rows() == m_lu.cols());\n\n      // Step 1\n      dst = m_lu.template triangularView<Upper>().transpose()\n                .template conjugateIf<Conjugate>().solve(rhs);\n      // Step 2\n      m_lu.template triangularView<UnitLower>().transpose()\n          .template conjugateIf<Conjugate>().solveInPlace(dst);\n      // Step 3\n      dst = permutationP().transpose() * dst;\n    }\n    #endif\n\n  protected:\n\n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n    }\n\n    void compute();\n\n    MatrixType m_lu;\n    PermutationType m_p;\n    TranspositionType m_rowsTranspositions;\n    RealScalar m_l1_norm;\n    signed char m_det_p;\n    bool m_isInitialized;\n};\n\ntemplate<typename MatrixType>\nPartialPivLU<MatrixType>::PartialPivLU()\n  : m_lu(),\n    m_p(),\n    m_rowsTranspositions(),\n    m_l1_norm(0),\n    m_det_p(0),\n    m_isInitialized(false)\n{\n}\n\ntemplate<typename MatrixType>\nPartialPivLU<MatrixType>::PartialPivLU(Index size)\n  : m_lu(size, size),\n    m_p(size),\n    m_rowsTranspositions(size),\n    m_l1_norm(0),\n    m_det_p(0),\n    m_isInitialized(false)\n{\n}\n\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nPartialPivLU<MatrixType>::PartialPivLU(const EigenBase<InputType>& matrix)\n  : m_lu(matrix.rows(),matrix.cols()),\n    m_p(matrix.rows()),\n    m_rowsTranspositions(matrix.rows()),\n    m_l1_norm(0),\n    m_det_p(0),\n    m_isInitialized(false)\n{\n  compute(matrix.derived());\n}\n\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nPartialPivLU<MatrixType>::PartialPivLU(EigenBase<InputType>& matrix)\n  : m_lu(matrix.derived()),\n    m_p(matrix.rows()),\n    m_rowsTranspositions(matrix.rows()),\n    m_l1_norm(0),\n    m_det_p(0),\n    m_isInitialized(false)\n{\n  compute();\n}\n\nnamespace internal {\n\n/** \\internal This is the blocked version of fullpivlu_unblocked() */\ntemplate<typename Scalar, int StorageOrder, typename PivIndex, int SizeAtCompileTime=Dynamic>\nstruct partial_lu_impl\n{\n  static const int UnBlockedBound = 16;\n  static const bool UnBlockedAtCompileTime = SizeAtCompileTime!=Dynamic && SizeAtCompileTime<=UnBlockedBound;\n  static const int ActualSizeAtCompileTime = UnBlockedAtCompileTime ? SizeAtCompileTime : Dynamic;\n  // Remaining rows and columns at compile-time:\n  static const int RRows = SizeAtCompileTime==2 ? 1 : Dynamic;\n  static const int RCols = SizeAtCompileTime==2 ? 1 : Dynamic;\n  typedef Matrix<Scalar, ActualSizeAtCompileTime, ActualSizeAtCompileTime, StorageOrder> MatrixType;\n  typedef Ref<MatrixType> MatrixTypeRef;\n  typedef Ref<Matrix<Scalar, Dynamic, Dynamic, StorageOrder> > BlockType;\n  typedef typename MatrixType::RealScalar RealScalar;\n\n  /** \\internal performs the LU decomposition in-place of the matrix \\a lu\n    * using an unblocked algorithm.\n    *\n    * In addition, this function returns the row transpositions in the\n    * vector \\a row_transpositions which must have a size equal to the number\n    * of columns of the matrix \\a lu, and an integer \\a nb_transpositions\n    * which returns the actual number of transpositions.\n    *\n    * \\returns The index of the first pivot which is exactly zero if any, or a negative number otherwise.\n    */\n  static Index unblocked_lu(MatrixTypeRef& lu, PivIndex* row_transpositions, PivIndex& nb_transpositions)\n  {\n    typedef scalar_score_coeff_op<Scalar> Scoring;\n    typedef typename Scoring::result_type Score;\n    const Index rows = lu.rows();\n    const Index cols = lu.cols();\n    const Index size = (std::min)(rows,cols);\n    // For small compile-time matrices it is worth processing the last row separately:\n    //  speedup: +100% for 2x2, +10% for others.\n    const Index endk = UnBlockedAtCompileTime ? size-1 : size;\n    nb_transpositions = 0;\n    Index first_zero_pivot = -1;\n    for(Index k = 0; k < endk; ++k)\n    {\n      int rrows = internal::convert_index<int>(rows-k-1);\n      int rcols = internal::convert_index<int>(cols-k-1);\n\n      Index row_of_biggest_in_col;\n      Score biggest_in_corner\n        = lu.col(k).tail(rows-k).unaryExpr(Scoring()).maxCoeff(&row_of_biggest_in_col);\n      row_of_biggest_in_col += k;\n\n      row_transpositions[k] = PivIndex(row_of_biggest_in_col);\n\n      if(biggest_in_corner != Score(0))\n      {\n        if(k != row_of_biggest_in_col)\n        {\n          lu.row(k).swap(lu.row(row_of_biggest_in_col));\n          ++nb_transpositions;\n        }\n\n        lu.col(k).tail(fix<RRows>(rrows)) /= lu.coeff(k,k);\n      }\n      else if(first_zero_pivot==-1)\n      {\n        // the pivot is exactly zero, we record the index of the first pivot which is exactly 0,\n        // and continue the factorization such we still have A = PLU\n        first_zero_pivot = k;\n      }\n\n      if(k<rows-1)\n        lu.bottomRightCorner(fix<RRows>(rrows),fix<RCols>(rcols)).noalias() -= lu.col(k).tail(fix<RRows>(rrows)) * lu.row(k).tail(fix<RCols>(rcols));\n    }\n\n    // special handling of the last entry\n    if(UnBlockedAtCompileTime)\n    {\n      Index k = endk;\n      row_transpositions[k] = PivIndex(k);\n      if (Scoring()(lu(k, k)) == Score(0) && first_zero_pivot == -1)\n        first_zero_pivot = k;\n    }\n\n    return first_zero_pivot;\n  }\n\n  /** \\internal performs the LU decomposition in-place of the matrix represented\n    * by the variables \\a rows, \\a cols, \\a lu_data, and \\a lu_stride using a\n    * recursive, blocked algorithm.\n    *\n    * In addition, this function returns the row transpositions in the\n    * vector \\a row_transpositions which must have a size equal to the number\n    * of columns of the matrix \\a lu, and an integer \\a nb_transpositions\n    * which returns the actual number of transpositions.\n    *\n    * \\returns The index of the first pivot which is exactly zero if any, or a negative number otherwise.\n    *\n    * \\note This very low level interface using pointers, etc. is to:\n    *   1 - reduce the number of instantiations to the strict minimum\n    *   2 - avoid infinite recursion of the instantiations with Block<Block<Block<...> > >\n    */\n  static Index blocked_lu(Index rows, Index cols, Scalar* lu_data, Index luStride, PivIndex* row_transpositions, PivIndex& nb_transpositions, Index maxBlockSize=256)\n  {\n    MatrixTypeRef lu = MatrixType::Map(lu_data,rows, cols, OuterStride<>(luStride));\n\n    const Index size = (std::min)(rows,cols);\n\n    // if the matrix is too small, no blocking:\n    if(UnBlockedAtCompileTime || size<=UnBlockedBound)\n    {\n      return unblocked_lu(lu, row_transpositions, nb_transpositions);\n    }\n\n    // automatically adjust the number of subdivisions to the size\n    // of the matrix so that there is enough sub blocks:\n    Index blockSize;\n    {\n      blockSize = size/8;\n      blockSize = (blockSize/16)*16;\n      blockSize = (std::min)((std::max)(blockSize,Index(8)), maxBlockSize);\n    }\n\n    nb_transpositions = 0;\n    Index first_zero_pivot = -1;\n    for(Index k = 0; k < size; k+=blockSize)\n    {\n      Index bs = (std::min)(size-k,blockSize); // actual size of the block\n      Index trows = rows - k - bs; // trailing rows\n      Index tsize = size - k - bs; // trailing size\n\n      // partition the matrix:\n      //                          A00 | A01 | A02\n      // lu  = A_0 | A_1 | A_2 =  A10 | A11 | A12\n      //                          A20 | A21 | A22\n      BlockType A_0 = lu.block(0,0,rows,k);\n      BlockType A_2 = lu.block(0,k+bs,rows,tsize);\n      BlockType A11 = lu.block(k,k,bs,bs);\n      BlockType A12 = lu.block(k,k+bs,bs,tsize);\n      BlockType A21 = lu.block(k+bs,k,trows,bs);\n      BlockType A22 = lu.block(k+bs,k+bs,trows,tsize);\n\n      PivIndex nb_transpositions_in_panel;\n      // recursively call the blocked LU algorithm on [A11^T A21^T]^T\n      // with a very small blocking size:\n      Index ret = blocked_lu(trows+bs, bs, &lu.coeffRef(k,k), luStride,\n                   row_transpositions+k, nb_transpositions_in_panel, 16);\n      if(ret>=0 && first_zero_pivot==-1)\n        first_zero_pivot = k+ret;\n\n      nb_transpositions += nb_transpositions_in_panel;\n      // update permutations and apply them to A_0\n      for(Index i=k; i<k+bs; ++i)\n      {\n        Index piv = (row_transpositions[i] += internal::convert_index<PivIndex>(k));\n        A_0.row(i).swap(A_0.row(piv));\n      }\n\n      if(trows)\n      {\n        // apply permutations to A_2\n        for(Index i=k;i<k+bs; ++i)\n          A_2.row(i).swap(A_2.row(row_transpositions[i]));\n\n        // A12 = A11^-1 A12\n        A11.template triangularView<UnitLower>().solveInPlace(A12);\n\n        A22.noalias() -= A21 * A12;\n      }\n    }\n    return first_zero_pivot;\n  }\n};\n\n/** \\internal performs the LU decomposition with partial pivoting in-place.\n  */\ntemplate<typename MatrixType, typename TranspositionType>\nvoid partial_lu_inplace(MatrixType& lu, TranspositionType& row_transpositions, typename TranspositionType::StorageIndex& nb_transpositions)\n{\n  // Special-case of zero matrix.\n  if (lu.rows() == 0 || lu.cols() == 0) {\n    nb_transpositions = 0;\n    return;\n  }\n  eigen_assert(lu.cols() == row_transpositions.size());\n  eigen_assert(row_transpositions.size() < 2 || (&row_transpositions.coeffRef(1)-&row_transpositions.coeffRef(0)) == 1);\n\n  partial_lu_impl\n    < typename MatrixType::Scalar, MatrixType::Flags&RowMajorBit?RowMajor:ColMajor,\n      typename TranspositionType::StorageIndex,\n      EIGEN_SIZE_MIN_PREFER_FIXED(MatrixType::RowsAtCompileTime,MatrixType::ColsAtCompileTime)>\n    ::blocked_lu(lu.rows(), lu.cols(), &lu.coeffRef(0,0), lu.outerStride(), &row_transpositions.coeffRef(0), nb_transpositions);\n}\n\n} // end namespace internal\n\ntemplate<typename MatrixType>\nvoid PartialPivLU<MatrixType>::compute()\n{\n  check_template_parameters();\n\n  // the row permutation is stored as int indices, so just to be sure:\n  eigen_assert(m_lu.rows()<NumTraits<int>::highest());\n\n  if(m_lu.cols()>0)\n    m_l1_norm = m_lu.cwiseAbs().colwise().sum().maxCoeff();\n  else\n    m_l1_norm = RealScalar(0);\n\n  eigen_assert(m_lu.rows() == m_lu.cols() && \"PartialPivLU is only for square (and moreover invertible) matrices\");\n  const Index size = m_lu.rows();\n\n  m_rowsTranspositions.resize(size);\n\n  typename TranspositionType::StorageIndex nb_transpositions;\n  internal::partial_lu_inplace(m_lu, m_rowsTranspositions, nb_transpositions);\n  m_det_p = (nb_transpositions%2) ? -1 : 1;\n\n  m_p = m_rowsTranspositions;\n\n  m_isInitialized = true;\n}\n\ntemplate<typename MatrixType>\ntypename PartialPivLU<MatrixType>::Scalar PartialPivLU<MatrixType>::determinant() const\n{\n  eigen_assert(m_isInitialized && \"PartialPivLU is not initialized.\");\n  return Scalar(m_det_p) * m_lu.diagonal().prod();\n}\n\n/** \\returns the matrix represented by the decomposition,\n * i.e., it returns the product: P^{-1} L U.\n * This function is provided for debug purpose. */\ntemplate<typename MatrixType>\nMatrixType PartialPivLU<MatrixType>::reconstructedMatrix() const\n{\n  eigen_assert(m_isInitialized && \"LU is not initialized.\");\n  // LU\n  MatrixType res = m_lu.template triangularView<UnitLower>().toDenseMatrix()\n                 * m_lu.template triangularView<Upper>();\n\n  // P^{-1}(LU)\n  res = m_p.inverse() * res;\n\n  return res;\n}\n\n/***** Implementation details *****************************************************/\n\nnamespace internal {\n\n/***** Implementation of inverse() *****************************************************/\ntemplate<typename DstXprType, typename MatrixType>\nstruct Assignment<DstXprType, Inverse<PartialPivLU<MatrixType> >, internal::assign_op<typename DstXprType::Scalar,typename PartialPivLU<MatrixType>::Scalar>, Dense2Dense>\n{\n  typedef PartialPivLU<MatrixType> LuType;\n  typedef Inverse<LuType> SrcXprType;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename LuType::Scalar> &)\n  {\n    dst = src.nestedExpression().solve(MatrixType::Identity(src.rows(), src.cols()));\n  }\n};\n} // end namespace internal\n\n/******** MatrixBase methods *******/\n\n/** \\lu_module\n  *\n  * \\return the partial-pivoting LU decomposition of \\c *this.\n  *\n  * \\sa class PartialPivLU\n  */\ntemplate<typename Derived>\ninline const PartialPivLU<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::partialPivLu() const\n{\n  return PartialPivLU<PlainObject>(eval());\n}\n\n/** \\lu_module\n  *\n  * Synonym of partialPivLu().\n  *\n  * \\return the partial-pivoting LU decomposition of \\c *this.\n  *\n  * \\sa class PartialPivLU\n  */\ntemplate<typename Derived>\ninline const PartialPivLU<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::lu() const\n{\n  return PartialPivLU<PlainObject>(eval());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_PARTIALLU_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/LU/PartialPivLU_LAPACKE.h",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Eigen bindings to LAPACKe\n *     LU decomposition with partial pivoting based on LAPACKE_?getrf function.\n ********************************************************************************\n*/\n\n#ifndef EIGEN_PARTIALLU_LAPACK_H\n#define EIGEN_PARTIALLU_LAPACK_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\internal Specialization for the data types supported by LAPACKe */\n\n#define EIGEN_LAPACKE_LU_PARTPIV(EIGTYPE, LAPACKE_TYPE, LAPACKE_PREFIX) \\\ntemplate<int StorageOrder> \\\nstruct partial_lu_impl<EIGTYPE, StorageOrder, lapack_int> \\\n{ \\\n  /* \\internal performs the LU decomposition in-place of the matrix represented */ \\\n  static lapack_int blocked_lu(Index rows, Index cols, EIGTYPE* lu_data, Index luStride, lapack_int* row_transpositions, lapack_int& nb_transpositions, lapack_int maxBlockSize=256) \\\n  { \\\n    EIGEN_UNUSED_VARIABLE(maxBlockSize);\\\n    lapack_int matrix_order, first_zero_pivot; \\\n    lapack_int m, n, lda, *ipiv, info; \\\n    EIGTYPE* a; \\\n/* Set up parameters for ?getrf */ \\\n    matrix_order = StorageOrder==RowMajor ? LAPACK_ROW_MAJOR : LAPACK_COL_MAJOR; \\\n    lda = convert_index<lapack_int>(luStride); \\\n    a = lu_data; \\\n    ipiv = row_transpositions; \\\n    m = convert_index<lapack_int>(rows); \\\n    n = convert_index<lapack_int>(cols); \\\n    nb_transpositions = 0; \\\n\\\n    info = LAPACKE_##LAPACKE_PREFIX##getrf( matrix_order, m, n, (LAPACKE_TYPE*)a, lda, ipiv ); \\\n\\\n    for(int i=0;i<m;i++) { ipiv[i]--; if (ipiv[i]!=i) nb_transpositions++; } \\\n\\\n    eigen_assert(info >= 0); \\\n/* something should be done with nb_transpositions */ \\\n\\\n    first_zero_pivot = info; \\\n    return first_zero_pivot; \\\n  } \\\n};\n\nEIGEN_LAPACKE_LU_PARTPIV(double, double, d)\nEIGEN_LAPACKE_LU_PARTPIV(float, float, s)\nEIGEN_LAPACKE_LU_PARTPIV(dcomplex, lapack_complex_double, z)\nEIGEN_LAPACKE_LU_PARTPIV(scomplex, lapack_complex_float,  c)\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_PARTIALLU_LAPACK_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/LU/arch/InverseSize4.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2001 Intel Corporation\n// Copyright (C) 2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n//\n// The algorithm below is a reimplementation of former \\src\\LU\\Inverse_SSE.h using PacketMath.\n// inv(M) = M#/|M|, where inv(M), M# and |M| denote the inverse of M,\n// adjugate of M and determinant of M respectively. M# is computed block-wise\n// using specific formulae. For proof, see:\n// https://lxjk.github.io/2017/09/03/Fast-4x4-Matrix-Inverse-with-SSE-SIMD-Explained.html\n// Variable names are adopted from \\src\\LU\\Inverse_SSE.h.\n//\n// The SSE code for the 4x4 float and double matrix inverse in former (deprecated) \\src\\LU\\Inverse_SSE.h\n// comes from the following Intel's library:\n// http://software.intel.com/en-us/articles/optimized-matrix-library-for-use-with-the-intel-pentiumr-4-processors-sse2-instructions/\n//\n// Here is the respective copyright and license statement:\n//\n//   Copyright (c) 2001 Intel Corporation.\n//\n// Permition is granted to use, copy, distribute and prepare derivative works\n// of this library for any purpose and without fee, provided, that the above\n// copyright notice and this statement appear in all copies.\n// Intel makes no representations about the suitability of this software for\n// any purpose, and specifically disclaims all warranties.\n// See LEGAL.TXT for all the legal information.\n//\n// TODO: Unify implementations of different data types (i.e. float and double).\n#ifndef EIGEN_INVERSE_SIZE_4_H\n#define EIGEN_INVERSE_SIZE_4_H\n\nnamespace Eigen\n{\nnamespace internal\n{\ntemplate <typename MatrixType, typename ResultType>\nstruct compute_inverse_size4<Architecture::Target, float, MatrixType, ResultType>\n{\n  enum\n  {\n    MatrixAlignment = traits<MatrixType>::Alignment,\n    ResultAlignment = traits<ResultType>::Alignment,\n    StorageOrdersMatch = (MatrixType::Flags & RowMajorBit) == (ResultType::Flags & RowMajorBit)\n  };\n  typedef typename conditional<(MatrixType::Flags & LinearAccessBit), MatrixType const &, typename MatrixType::PlainObject>::type ActualMatrixType;\n\n  static void run(const MatrixType &mat, ResultType &result)\n  {\n    ActualMatrixType matrix(mat);\n\n    const float* data = matrix.data();\n    const Index stride = matrix.innerStride();\n    Packet4f _L1 = ploadt<Packet4f,MatrixAlignment>(data);\n    Packet4f _L2 = ploadt<Packet4f,MatrixAlignment>(data + stride*4);\n    Packet4f _L3 = ploadt<Packet4f,MatrixAlignment>(data + stride*8);\n    Packet4f _L4 = ploadt<Packet4f,MatrixAlignment>(data + stride*12);\n\n    // Four 2x2 sub-matrices of the input matrix\n    // input = [[A, B],\n    //          [C, D]]\n    Packet4f A, B, C, D;\n\n    if (!StorageOrdersMatch)\n    {\n      A = vec4f_unpacklo(_L1, _L2);\n      B = vec4f_unpacklo(_L3, _L4);\n      C = vec4f_unpackhi(_L1, _L2);\n      D = vec4f_unpackhi(_L3, _L4);\n    }\n    else\n    {\n      A = vec4f_movelh(_L1, _L2);\n      B = vec4f_movehl(_L2, _L1);\n      C = vec4f_movelh(_L3, _L4);\n      D = vec4f_movehl(_L4, _L3);\n    }\n\n    Packet4f AB, DC;\n\n    // AB = A# * B, where A# denotes the adjugate of A, and * denotes matrix product.\n    AB = pmul(vec4f_swizzle2(A, A, 3, 3, 0, 0), B);\n    AB = psub(AB, pmul(vec4f_swizzle2(A, A, 1, 1, 2, 2), vec4f_swizzle2(B, B, 2, 3, 0, 1)));\n\n    // DC = D#*C\n    DC = pmul(vec4f_swizzle2(D, D, 3, 3, 0, 0), C);\n    DC = psub(DC, pmul(vec4f_swizzle2(D, D, 1, 1, 2, 2), vec4f_swizzle2(C, C, 2, 3, 0, 1)));\n\n    // determinants of the sub-matrices\n    Packet4f dA, dB, dC, dD;\n\n    dA = pmul(vec4f_swizzle2(A, A, 3, 3, 1, 1), A);\n    dA = psub(dA, vec4f_movehl(dA, dA));\n\n    dB = pmul(vec4f_swizzle2(B, B, 3, 3, 1, 1), B);\n    dB = psub(dB, vec4f_movehl(dB, dB));\n\n    dC = pmul(vec4f_swizzle2(C, C, 3, 3, 1, 1), C);\n    dC = psub(dC, vec4f_movehl(dC, dC));\n\n    dD = pmul(vec4f_swizzle2(D, D, 3, 3, 1, 1), D);\n    dD = psub(dD, vec4f_movehl(dD, dD));\n\n    Packet4f d, d1, d2;\n\n    d = pmul(vec4f_swizzle2(DC, DC, 0, 2, 1, 3), AB);\n    d = padd(d, vec4f_movehl(d, d));\n    d = padd(d, vec4f_swizzle2(d, d, 1, 0, 0, 0));\n    d1 = pmul(dA, dD);\n    d2 = pmul(dB, dC);\n\n    // determinant of the input matrix, det = |A||D| + |B||C| - trace(A#*B*D#*C)\n    Packet4f det = vec4f_duplane(psub(padd(d1, d2), d), 0);\n\n    // reciprocal of the determinant of the input matrix, rd = 1/det\n    Packet4f rd = pdiv(pset1<Packet4f>(1.0f), det);\n\n    // Four sub-matrices of the inverse\n    Packet4f iA, iB, iC, iD;\n\n    // iD = D*|A| - C*A#*B\n    iD = pmul(vec4f_swizzle2(C, C, 0, 0, 2, 2), vec4f_movelh(AB, AB));\n    iD = padd(iD, pmul(vec4f_swizzle2(C, C, 1, 1, 3, 3), vec4f_movehl(AB, AB)));\n    iD = psub(pmul(D, vec4f_duplane(dA, 0)), iD);\n\n    // iA = A*|D| - B*D#*C\n    iA = pmul(vec4f_swizzle2(B, B, 0, 0, 2, 2), vec4f_movelh(DC, DC));\n    iA = padd(iA, pmul(vec4f_swizzle2(B, B, 1, 1, 3, 3), vec4f_movehl(DC, DC)));\n    iA = psub(pmul(A, vec4f_duplane(dD, 0)), iA);\n\n    // iB = C*|B| - D * (A#B)# = C*|B| - D*B#*A\n    iB = pmul(D, vec4f_swizzle2(AB, AB, 3, 0, 3, 0));\n    iB = psub(iB, pmul(vec4f_swizzle2(D, D, 1, 0, 3, 2), vec4f_swizzle2(AB, AB, 2, 1, 2, 1)));\n    iB = psub(pmul(C, vec4f_duplane(dB, 0)), iB);\n\n    // iC = B*|C| - A * (D#C)# = B*|C| - A*C#*D\n    iC = pmul(A, vec4f_swizzle2(DC, DC, 3, 0, 3, 0));\n    iC = psub(iC, pmul(vec4f_swizzle2(A, A, 1, 0, 3, 2), vec4f_swizzle2(DC, DC, 2, 1, 2, 1)));\n    iC = psub(pmul(B, vec4f_duplane(dC, 0)), iC);\n\n    const float sign_mask[4] = {0.0f, numext::bit_cast<float>(0x80000000u), numext::bit_cast<float>(0x80000000u), 0.0f};\n    const Packet4f p4f_sign_PNNP = ploadu<Packet4f>(sign_mask);\n    rd = pxor(rd, p4f_sign_PNNP);\n    iA = pmul(iA, rd);\n    iB = pmul(iB, rd);\n    iC = pmul(iC, rd);\n    iD = pmul(iD, rd);\n\n    Index res_stride = result.outerStride();\n    float *res = result.data();\n\n    pstoret<float, Packet4f, ResultAlignment>(res + 0, vec4f_swizzle2(iA, iB, 3, 1, 3, 1));\n    pstoret<float, Packet4f, ResultAlignment>(res + res_stride, vec4f_swizzle2(iA, iB, 2, 0, 2, 0));\n    pstoret<float, Packet4f, ResultAlignment>(res + 2 * res_stride, vec4f_swizzle2(iC, iD, 3, 1, 3, 1));\n    pstoret<float, Packet4f, ResultAlignment>(res + 3 * res_stride, vec4f_swizzle2(iC, iD, 2, 0, 2, 0));\n  }\n};\n\n#if !(defined EIGEN_VECTORIZE_NEON && !(EIGEN_ARCH_ARM64 && !EIGEN_APPLE_DOUBLE_NEON_BUG))\n// same algorithm as above, except that each operand is split into\n// halves for two registers to hold.\ntemplate <typename MatrixType, typename ResultType>\nstruct compute_inverse_size4<Architecture::Target, double, MatrixType, ResultType>\n{\n  enum\n  {\n    MatrixAlignment = traits<MatrixType>::Alignment,\n    ResultAlignment = traits<ResultType>::Alignment,\n    StorageOrdersMatch = (MatrixType::Flags & RowMajorBit) == (ResultType::Flags & RowMajorBit)\n  };\n  typedef typename conditional<(MatrixType::Flags & LinearAccessBit),\n                               MatrixType const &,\n                               typename MatrixType::PlainObject>::type\n      ActualMatrixType;\n\n  static void run(const MatrixType &mat, ResultType &result)\n  {\n    ActualMatrixType matrix(mat);\n\n    // Four 2x2 sub-matrices of the input matrix, each is further divided into upper and lower\n    // row e.g. A1, upper row of A, A2, lower row of A\n    // input = [[A, B],  =  [[[A1, [B1,\n    //          [C, D]]        A2], B2]],\n    //                       [[C1, [D1,\n    //                         C2], D2]]]\n\n    Packet2d A1, A2, B1, B2, C1, C2, D1, D2;\n\n    const double* data = matrix.data();\n    const Index stride = matrix.innerStride();\n    if (StorageOrdersMatch)\n    {\n      A1 = ploadt<Packet2d,MatrixAlignment>(data + stride*0);\n      B1 = ploadt<Packet2d,MatrixAlignment>(data + stride*2);\n      A2 = ploadt<Packet2d,MatrixAlignment>(data + stride*4);\n      B2 = ploadt<Packet2d,MatrixAlignment>(data + stride*6);\n      C1 = ploadt<Packet2d,MatrixAlignment>(data + stride*8);\n      D1 = ploadt<Packet2d,MatrixAlignment>(data + stride*10);\n      C2 = ploadt<Packet2d,MatrixAlignment>(data + stride*12);\n      D2 = ploadt<Packet2d,MatrixAlignment>(data + stride*14);\n    }\n    else\n    {\n      Packet2d temp;\n      A1 = ploadt<Packet2d,MatrixAlignment>(data + stride*0);\n      C1 = ploadt<Packet2d,MatrixAlignment>(data + stride*2);\n      A2 = ploadt<Packet2d,MatrixAlignment>(data + stride*4);\n      C2 = ploadt<Packet2d,MatrixAlignment>(data + stride*6);\n      temp = A1;\n      A1 = vec2d_unpacklo(A1, A2);\n      A2 = vec2d_unpackhi(temp, A2);\n\n      temp = C1;\n      C1 = vec2d_unpacklo(C1, C2);\n      C2 = vec2d_unpackhi(temp, C2);\n\n      B1 = ploadt<Packet2d,MatrixAlignment>(data + stride*8);\n      D1 = ploadt<Packet2d,MatrixAlignment>(data + stride*10);\n      B2 = ploadt<Packet2d,MatrixAlignment>(data + stride*12);\n      D2 = ploadt<Packet2d,MatrixAlignment>(data + stride*14);\n\n      temp = B1;\n      B1 = vec2d_unpacklo(B1, B2);\n      B2 = vec2d_unpackhi(temp, B2);\n\n      temp = D1;\n      D1 = vec2d_unpacklo(D1, D2);\n      D2 = vec2d_unpackhi(temp, D2);\n    }\n\n    // determinants of the sub-matrices\n    Packet2d dA, dB, dC, dD;\n\n    dA = vec2d_swizzle2(A2, A2, 1);\n    dA = pmul(A1, dA);\n    dA = psub(dA, vec2d_duplane(dA, 1));\n\n    dB = vec2d_swizzle2(B2, B2, 1);\n    dB = pmul(B1, dB);\n    dB = psub(dB, vec2d_duplane(dB, 1));\n\n    dC = vec2d_swizzle2(C2, C2, 1);\n    dC = pmul(C1, dC);\n    dC = psub(dC, vec2d_duplane(dC, 1));\n\n    dD = vec2d_swizzle2(D2, D2, 1);\n    dD = pmul(D1, dD);\n    dD = psub(dD, vec2d_duplane(dD, 1));\n\n    Packet2d DC1, DC2, AB1, AB2;\n\n    // AB = A# * B, where A# denotes the adjugate of A, and * denotes matrix product.\n    AB1 = pmul(B1, vec2d_duplane(A2, 1));\n    AB2 = pmul(B2, vec2d_duplane(A1, 0));\n    AB1 = psub(AB1, pmul(B2, vec2d_duplane(A1, 1)));\n    AB2 = psub(AB2, pmul(B1, vec2d_duplane(A2, 0)));\n\n    // DC = D#*C\n    DC1 = pmul(C1, vec2d_duplane(D2, 1));\n    DC2 = pmul(C2, vec2d_duplane(D1, 0));\n    DC1 = psub(DC1, pmul(C2, vec2d_duplane(D1, 1)));\n    DC2 = psub(DC2, pmul(C1, vec2d_duplane(D2, 0)));\n\n    Packet2d d1, d2;\n\n    // determinant of the input matrix, det = |A||D| + |B||C| - trace(A#*B*D#*C)\n    Packet2d det;\n\n    // reciprocal of the determinant of the input matrix, rd = 1/det\n    Packet2d rd;\n\n    d1 = pmul(AB1, vec2d_swizzle2(DC1, DC2, 0));\n    d2 = pmul(AB2, vec2d_swizzle2(DC1, DC2, 3));\n    rd = padd(d1, d2);\n    rd = padd(rd, vec2d_duplane(rd, 1));\n\n    d1 = pmul(dA, dD);\n    d2 = pmul(dB, dC);\n\n    det = padd(d1, d2);\n    det = psub(det, rd);\n    det = vec2d_duplane(det, 0);\n    rd = pdiv(pset1<Packet2d>(1.0), det);\n\n    // rows of four sub-matrices of the inverse\n    Packet2d iA1, iA2, iB1, iB2, iC1, iC2, iD1, iD2;\n\n    // iD = D*|A| - C*A#*B\n    iD1 = pmul(AB1, vec2d_duplane(C1, 0));\n    iD2 = pmul(AB1, vec2d_duplane(C2, 0));\n    iD1 = padd(iD1, pmul(AB2, vec2d_duplane(C1, 1)));\n    iD2 = padd(iD2, pmul(AB2, vec2d_duplane(C2, 1)));\n    dA = vec2d_duplane(dA, 0);\n    iD1 = psub(pmul(D1, dA), iD1);\n    iD2 = psub(pmul(D2, dA), iD2);\n\n    // iA = A*|D| - B*D#*C\n    iA1 = pmul(DC1, vec2d_duplane(B1, 0));\n    iA2 = pmul(DC1, vec2d_duplane(B2, 0));\n    iA1 = padd(iA1, pmul(DC2, vec2d_duplane(B1, 1)));\n    iA2 = padd(iA2, pmul(DC2, vec2d_duplane(B2, 1)));\n    dD = vec2d_duplane(dD, 0);\n    iA1 = psub(pmul(A1, dD), iA1);\n    iA2 = psub(pmul(A2, dD), iA2);\n\n    // iB = C*|B| - D * (A#B)# = C*|B| - D*B#*A\n    iB1 = pmul(D1, vec2d_swizzle2(AB2, AB1, 1));\n    iB2 = pmul(D2, vec2d_swizzle2(AB2, AB1, 1));\n    iB1 = psub(iB1, pmul(vec2d_swizzle2(D1, D1, 1), vec2d_swizzle2(AB2, AB1, 2)));\n    iB2 = psub(iB2, pmul(vec2d_swizzle2(D2, D2, 1), vec2d_swizzle2(AB2, AB1, 2)));\n    dB = vec2d_duplane(dB, 0);\n    iB1 = psub(pmul(C1, dB), iB1);\n    iB2 = psub(pmul(C2, dB), iB2);\n\n    // iC = B*|C| - A * (D#C)# = B*|C| - A*C#*D\n    iC1 = pmul(A1, vec2d_swizzle2(DC2, DC1, 1));\n    iC2 = pmul(A2, vec2d_swizzle2(DC2, DC1, 1));\n    iC1 = psub(iC1, pmul(vec2d_swizzle2(A1, A1, 1), vec2d_swizzle2(DC2, DC1, 2)));\n    iC2 = psub(iC2, pmul(vec2d_swizzle2(A2, A2, 1), vec2d_swizzle2(DC2, DC1, 2)));\n    dC = vec2d_duplane(dC, 0);\n    iC1 = psub(pmul(B1, dC), iC1);\n    iC2 = psub(pmul(B2, dC), iC2);\n\n    const double sign_mask1[2] = {0.0, numext::bit_cast<double>(0x8000000000000000ull)};\n    const double sign_mask2[2] = {numext::bit_cast<double>(0x8000000000000000ull), 0.0};\n    const Packet2d sign_PN = ploadu<Packet2d>(sign_mask1);\n    const Packet2d sign_NP = ploadu<Packet2d>(sign_mask2);\n    d1 = pxor(rd, sign_PN);\n    d2 = pxor(rd, sign_NP);\n\n    Index res_stride = result.outerStride();\n    double *res = result.data();\n    pstoret<double, Packet2d, ResultAlignment>(res + 0, pmul(vec2d_swizzle2(iA2, iA1, 3), d1));\n    pstoret<double, Packet2d, ResultAlignment>(res + res_stride, pmul(vec2d_swizzle2(iA2, iA1, 0), d2));\n    pstoret<double, Packet2d, ResultAlignment>(res + 2, pmul(vec2d_swizzle2(iB2, iB1, 3), d1));\n    pstoret<double, Packet2d, ResultAlignment>(res + res_stride + 2, pmul(vec2d_swizzle2(iB2, iB1, 0), d2));\n    pstoret<double, Packet2d, ResultAlignment>(res + 2 * res_stride, pmul(vec2d_swizzle2(iC2, iC1, 3), d1));\n    pstoret<double, Packet2d, ResultAlignment>(res + 3 * res_stride, pmul(vec2d_swizzle2(iC2, iC1, 0), d2));\n    pstoret<double, Packet2d, ResultAlignment>(res + 2 * res_stride + 2, pmul(vec2d_swizzle2(iD2, iD1, 3), d1));\n    pstoret<double, Packet2d, ResultAlignment>(res + 3 * res_stride + 2, pmul(vec2d_swizzle2(iD2, iD1, 0), d2));\n  }\n};\n#endif\n} // namespace internal\n} // namespace Eigen\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/MetisSupport/MetisSupport.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n#ifndef METIS_SUPPORT_H\n#define METIS_SUPPORT_H\n\nnamespace Eigen {\n/**\n * Get the fill-reducing ordering from the METIS package\n * \n * If A is the original matrix and Ap is the permuted matrix, \n * the fill-reducing permutation is defined as follows :\n * Row (column) i of A is the matperm(i) row (column) of Ap. \n * WARNING: As computed by METIS, this corresponds to the vector iperm (instead of perm)\n */\ntemplate <typename StorageIndex>\nclass MetisOrdering\n{\npublic:\n  typedef PermutationMatrix<Dynamic,Dynamic,StorageIndex> PermutationType;\n  typedef Matrix<StorageIndex,Dynamic,1> IndexVector; \n  \n  template <typename MatrixType>\n  void get_symmetrized_graph(const MatrixType& A)\n  {\n    Index m = A.cols(); \n    eigen_assert((A.rows() == A.cols()) && \"ONLY FOR SQUARED MATRICES\");\n    // Get the transpose of the input matrix \n    MatrixType At = A.transpose(); \n    // Get the number of nonzeros elements in each row/col of At+A\n    Index TotNz = 0; \n    IndexVector visited(m); \n    visited.setConstant(-1); \n    for (StorageIndex j = 0; j < m; j++)\n    {\n      // Compute the union structure of of A(j,:) and At(j,:)\n      visited(j) = j; // Do not include the diagonal element\n      // Get the nonzeros in row/column j of A\n      for (typename MatrixType::InnerIterator it(A, j); it; ++it)\n      {\n        Index idx = it.index(); // Get the row index (for column major) or column index (for row major)\n        if (visited(idx) != j ) \n        {\n          visited(idx) = j; \n          ++TotNz; \n        }\n      }\n      //Get the nonzeros in row/column j of At\n      for (typename MatrixType::InnerIterator it(At, j); it; ++it)\n      {\n        Index idx = it.index(); \n        if(visited(idx) != j)\n        {\n          visited(idx) = j; \n          ++TotNz; \n        }\n      }\n    }\n    // Reserve place for A + At\n    m_indexPtr.resize(m+1);\n    m_innerIndices.resize(TotNz); \n\n    // Now compute the real adjacency list of each column/row \n    visited.setConstant(-1); \n    StorageIndex CurNz = 0; \n    for (StorageIndex j = 0; j < m; j++)\n    {\n      m_indexPtr(j) = CurNz; \n      \n      visited(j) = j; // Do not include the diagonal element\n      // Add the pattern of row/column j of A to A+At\n      for (typename MatrixType::InnerIterator it(A,j); it; ++it)\n      {\n        StorageIndex idx = it.index(); // Get the row index (for column major) or column index (for row major)\n        if (visited(idx) != j ) \n        {\n          visited(idx) = j; \n          m_innerIndices(CurNz) = idx; \n          CurNz++; \n        }\n      }\n      //Add the pattern of row/column j of At to A+At\n      for (typename MatrixType::InnerIterator it(At, j); it; ++it)\n      {\n        StorageIndex idx = it.index(); \n        if(visited(idx) != j)\n        {\n          visited(idx) = j; \n          m_innerIndices(CurNz) = idx; \n          ++CurNz; \n        }\n      }\n    }\n    m_indexPtr(m) = CurNz;    \n  }\n  \n  template <typename MatrixType>\n  void operator() (const MatrixType& A, PermutationType& matperm)\n  {\n     StorageIndex m = internal::convert_index<StorageIndex>(A.cols()); // must be StorageIndex, because it is passed by address to METIS\n     IndexVector perm(m),iperm(m); \n    // First, symmetrize the matrix graph. \n     get_symmetrized_graph(A); \n     int output_error;\n     \n     // Call the fill-reducing routine from METIS \n     output_error = METIS_NodeND(&m, m_indexPtr.data(), m_innerIndices.data(), NULL, NULL, perm.data(), iperm.data());\n     \n    if(output_error != METIS_OK) \n    {\n      //FIXME The ordering interface should define a class of possible errors \n     std::cerr << \"ERROR WHILE CALLING THE METIS PACKAGE \\n\"; \n     return; \n    }\n    \n    // Get the fill-reducing permutation \n    //NOTE:  If Ap is the permuted matrix then perm and iperm vectors are defined as follows \n    // Row (column) i of Ap is the perm(i) row(column) of A, and row (column) i of A is the iperm(i) row(column) of Ap\n    \n     matperm.resize(m);\n     for (int j = 0; j < m; j++)\n       matperm.indices()(iperm(j)) = j;\n   \n  }\n  \n  protected:\n    IndexVector m_indexPtr; // Pointer to the adjacenccy list of each row/column\n    IndexVector m_innerIndices; // Adjacency list \n};\n\n}// end namespace eigen \n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/OrderingMethods/Amd.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/*\nNOTE: this routine has been adapted from the CSparse library:\n\nCopyright (c) 2006, Timothy A. Davis.\nhttp://www.suitesparse.com\n\nThe author of CSparse, Timothy A. Davis., has executed a license with Google LLC\nto permit distribution of this code and derivative works as part of Eigen under\nthe Mozilla Public License v. 2.0, as stated at the top of this file.\n*/\n\n#ifndef EIGEN_SPARSE_AMD_H\n#define EIGEN_SPARSE_AMD_H\n\nnamespace Eigen { \n\nnamespace internal {\n  \ntemplate<typename T> inline T amd_flip(const T& i) { return -i-2; }\ntemplate<typename T> inline T amd_unflip(const T& i) { return i<0 ? amd_flip(i) : i; }\ntemplate<typename T0, typename T1> inline bool amd_marked(const T0* w, const T1& j) { return w[j]<0; }\ntemplate<typename T0, typename T1> inline void amd_mark(const T0* w, const T1& j) { return w[j] = amd_flip(w[j]); }\n\n/* clear w */\ntemplate<typename StorageIndex>\nstatic StorageIndex cs_wclear (StorageIndex mark, StorageIndex lemax, StorageIndex *w, StorageIndex n)\n{\n  StorageIndex k;\n  if(mark < 2 || (mark + lemax < 0))\n  {\n    for(k = 0; k < n; k++)\n      if(w[k] != 0)\n        w[k] = 1;\n    mark = 2;\n  }\n  return (mark);     /* at this point, w[0..n-1] < mark holds */\n}\n\n/* depth-first search and postorder of a tree rooted at node j */\ntemplate<typename StorageIndex>\nStorageIndex cs_tdfs(StorageIndex j, StorageIndex k, StorageIndex *head, const StorageIndex *next, StorageIndex *post, StorageIndex *stack)\n{\n  StorageIndex i, p, top = 0;\n  if(!head || !next || !post || !stack) return (-1);    /* check inputs */\n  stack[0] = j;                 /* place j on the stack */\n  while (top >= 0)                /* while (stack is not empty) */\n  {\n    p = stack[top];           /* p = top of stack */\n    i = head[p];              /* i = youngest child of p */\n    if(i == -1)\n    {\n      top--;                 /* p has no unordered children left */\n      post[k++] = p;        /* node p is the kth postordered node */\n    }\n    else\n    {\n      head[p] = next[i];   /* remove i from children of p */\n      stack[++top] = i;     /* start dfs on child node i */\n    }\n  }\n  return k;\n}\n\n\n/** \\internal\n  * \\ingroup OrderingMethods_Module \n  * Approximate minimum degree ordering algorithm.\n  *\n  * \\param[in] C the input selfadjoint matrix stored in compressed column major format.\n  * \\param[out] perm the permutation P reducing the fill-in of the input matrix \\a C\n  *\n  * Note that the input matrix \\a C must be complete, that is both the upper and lower parts have to be stored, as well as the diagonal entries.\n  * On exit the values of C are destroyed */\ntemplate<typename Scalar, typename StorageIndex>\nvoid minimum_degree_ordering(SparseMatrix<Scalar,ColMajor,StorageIndex>& C, PermutationMatrix<Dynamic,Dynamic,StorageIndex>& perm)\n{\n  using std::sqrt;\n  \n  StorageIndex d, dk, dext, lemax = 0, e, elenk, eln, i, j, k, k1,\n                k2, k3, jlast, ln, dense, nzmax, mindeg = 0, nvi, nvj, nvk, mark, wnvi,\n                ok, nel = 0, p, p1, p2, p3, p4, pj, pk, pk1, pk2, pn, q, t, h;\n  \n  StorageIndex n = StorageIndex(C.cols());\n  dense = std::max<StorageIndex> (16, StorageIndex(10 * sqrt(double(n))));   /* find dense threshold */\n  dense = (std::min)(n-2, dense);\n  \n  StorageIndex cnz = StorageIndex(C.nonZeros());\n  perm.resize(n+1);\n  t = cnz + cnz/5 + 2*n;                 /* add elbow room to C */\n  C.resizeNonZeros(t);\n  \n  // get workspace\n  ei_declare_aligned_stack_constructed_variable(StorageIndex,W,8*(n+1),0);\n  StorageIndex* len     = W;\n  StorageIndex* nv      = W +   (n+1);\n  StorageIndex* next    = W + 2*(n+1);\n  StorageIndex* head    = W + 3*(n+1);\n  StorageIndex* elen    = W + 4*(n+1);\n  StorageIndex* degree  = W + 5*(n+1);\n  StorageIndex* w       = W + 6*(n+1);\n  StorageIndex* hhead   = W + 7*(n+1);\n  StorageIndex* last    = perm.indices().data();                              /* use P as workspace for last */\n  \n  /* --- Initialize quotient graph ---------------------------------------- */\n  StorageIndex* Cp = C.outerIndexPtr();\n  StorageIndex* Ci = C.innerIndexPtr();\n  for(k = 0; k < n; k++)\n    len[k] = Cp[k+1] - Cp[k];\n  len[n] = 0;\n  nzmax = t;\n  \n  for(i = 0; i <= n; i++)\n  {\n    head[i]   = -1;                     // degree list i is empty\n    last[i]   = -1;\n    next[i]   = -1;\n    hhead[i]  = -1;                     // hash list i is empty \n    nv[i]     = 1;                      // node i is just one node\n    w[i]      = 1;                      // node i is alive\n    elen[i]   = 0;                      // Ek of node i is empty\n    degree[i] = len[i];                 // degree of node i\n  }\n  mark = internal::cs_wclear<StorageIndex>(0, 0, w, n);         /* clear w */\n  \n  /* --- Initialize degree lists ------------------------------------------ */\n  for(i = 0; i < n; i++)\n  {\n    bool has_diag = false;\n    for(p = Cp[i]; p<Cp[i+1]; ++p)\n      if(Ci[p]==i)\n      {\n        has_diag = true;\n        break;\n      }\n   \n    d = degree[i];\n    if(d == 1 && has_diag)           /* node i is empty */\n    {\n      elen[i] = -2;                 /* element i is dead */\n      nel++;\n      Cp[i] = -1;                   /* i is a root of assembly tree */\n      w[i] = 0;\n    }\n    else if(d > dense || !has_diag)  /* node i is dense or has no structural diagonal element */\n    {\n      nv[i] = 0;                    /* absorb i into element n */\n      elen[i] = -1;                 /* node i is dead */\n      nel++;\n      Cp[i] = amd_flip (n);\n      nv[n]++;\n    }\n    else\n    {\n      if(head[d] != -1) last[head[d]] = i;\n      next[i] = head[d];           /* put node i in degree list d */\n      head[d] = i;\n    }\n  }\n  \n  elen[n] = -2;                         /* n is a dead element */\n  Cp[n] = -1;                           /* n is a root of assembly tree */\n  w[n] = 0;                             /* n is a dead element */\n  \n  while (nel < n)                         /* while (selecting pivots) do */\n  {\n    /* --- Select node of minimum approximate degree -------------------- */\n    for(k = -1; mindeg < n && (k = head[mindeg]) == -1; mindeg++) {}\n    if(next[k] != -1) last[next[k]] = -1;\n    head[mindeg] = next[k];          /* remove k from degree list */\n    elenk = elen[k];                  /* elenk = |Ek| */\n    nvk = nv[k];                      /* # of nodes k represents */\n    nel += nvk;                        /* nv[k] nodes of A eliminated */\n    \n    /* --- Garbage collection ------------------------------------------- */\n    if(elenk > 0 && cnz + mindeg >= nzmax)\n    {\n      for(j = 0; j < n; j++)\n      {\n        if((p = Cp[j]) >= 0)      /* j is a live node or element */\n        {\n          Cp[j] = Ci[p];          /* save first entry of object */\n          Ci[p] = amd_flip (j);    /* first entry is now amd_flip(j) */\n        }\n      }\n      for(q = 0, p = 0; p < cnz; ) /* scan all of memory */\n      {\n        if((j = amd_flip (Ci[p++])) >= 0)  /* found object j */\n        {\n          Ci[q] = Cp[j];       /* restore first entry of object */\n          Cp[j] = q++;          /* new pointer to object j */\n          for(k3 = 0; k3 < len[j]-1; k3++) Ci[q++] = Ci[p++];\n        }\n      }\n      cnz = q;                       /* Ci[cnz...nzmax-1] now free */\n    }\n    \n    /* --- Construct new element ---------------------------------------- */\n    dk = 0;\n    nv[k] = -nvk;                     /* flag k as in Lk */\n    p = Cp[k];\n    pk1 = (elenk == 0) ? p : cnz;      /* do in place if elen[k] == 0 */\n    pk2 = pk1;\n    for(k1 = 1; k1 <= elenk + 1; k1++)\n    {\n      if(k1 > elenk)\n      {\n        e = k;                     /* search the nodes in k */\n        pj = p;                    /* list of nodes starts at Ci[pj]*/\n        ln = len[k] - elenk;      /* length of list of nodes in k */\n      }\n      else\n      {\n        e = Ci[p++];              /* search the nodes in e */\n        pj = Cp[e];\n        ln = len[e];              /* length of list of nodes in e */\n      }\n      for(k2 = 1; k2 <= ln; k2++)\n      {\n        i = Ci[pj++];\n        if((nvi = nv[i]) <= 0) continue; /* node i dead, or seen */\n        dk += nvi;                 /* degree[Lk] += size of node i */\n        nv[i] = -nvi;             /* negate nv[i] to denote i in Lk*/\n        Ci[pk2++] = i;            /* place i in Lk */\n        if(next[i] != -1) last[next[i]] = last[i];\n        if(last[i] != -1)         /* remove i from degree list */\n        {\n          next[last[i]] = next[i];\n        }\n        else\n        {\n          head[degree[i]] = next[i];\n        }\n      }\n      if(e != k)\n      {\n        Cp[e] = amd_flip (k);      /* absorb e into k */\n        w[e] = 0;                 /* e is now a dead element */\n      }\n    }\n    if(elenk != 0) cnz = pk2;         /* Ci[cnz...nzmax] is free */\n    degree[k] = dk;                   /* external degree of k - |Lk\\i| */\n    Cp[k] = pk1;                      /* element k is in Ci[pk1..pk2-1] */\n    len[k] = pk2 - pk1;\n    elen[k] = -2;                     /* k is now an element */\n    \n    /* --- Find set differences ----------------------------------------- */\n    mark = internal::cs_wclear<StorageIndex>(mark, lemax, w, n);  /* clear w if necessary */\n    for(pk = pk1; pk < pk2; pk++)    /* scan 1: find |Le\\Lk| */\n    {\n      i = Ci[pk];\n      if((eln = elen[i]) <= 0) continue;/* skip if elen[i] empty */\n      nvi = -nv[i];                      /* nv[i] was negated */\n      wnvi = mark - nvi;\n      for(p = Cp[i]; p <= Cp[i] + eln - 1; p++)  /* scan Ei */\n      {\n        e = Ci[p];\n        if(w[e] >= mark)\n        {\n          w[e] -= nvi;          /* decrement |Le\\Lk| */\n        }\n        else if(w[e] != 0)        /* ensure e is a live element */\n        {\n          w[e] = degree[e] + wnvi; /* 1st time e seen in scan 1 */\n        }\n      }\n    }\n    \n    /* --- Degree update ------------------------------------------------ */\n    for(pk = pk1; pk < pk2; pk++)    /* scan2: degree update */\n    {\n      i = Ci[pk];                   /* consider node i in Lk */\n      p1 = Cp[i];\n      p2 = p1 + elen[i] - 1;\n      pn = p1;\n      for(h = 0, d = 0, p = p1; p <= p2; p++)    /* scan Ei */\n      {\n        e = Ci[p];\n        if(w[e] != 0)             /* e is an unabsorbed element */\n        {\n          dext = w[e] - mark;   /* dext = |Le\\Lk| */\n          if(dext > 0)\n          {\n            d += dext;         /* sum up the set differences */\n            Ci[pn++] = e;     /* keep e in Ei */\n            h += e;            /* compute the hash of node i */\n          }\n          else\n          {\n            Cp[e] = amd_flip (k);  /* aggressive absorb. e->k */\n            w[e] = 0;             /* e is a dead element */\n          }\n        }\n      }\n      elen[i] = pn - p1 + 1;        /* elen[i] = |Ei| */\n      p3 = pn;\n      p4 = p1 + len[i];\n      for(p = p2 + 1; p < p4; p++) /* prune edges in Ai */\n      {\n        j = Ci[p];\n        if((nvj = nv[j]) <= 0) continue; /* node j dead or in Lk */\n        d += nvj;                  /* degree(i) += |j| */\n        Ci[pn++] = j;             /* place j in node list of i */\n        h += j;                    /* compute hash for node i */\n      }\n      if(d == 0)                     /* check for mass elimination */\n      {\n        Cp[i] = amd_flip (k);      /* absorb i into k */\n        nvi = -nv[i];\n        dk -= nvi;                 /* |Lk| -= |i| */\n        nvk += nvi;                /* |k| += nv[i] */\n        nel += nvi;\n        nv[i] = 0;\n        elen[i] = -1;             /* node i is dead */\n      }\n      else\n      {\n        degree[i] = std::min<StorageIndex> (degree[i], d);   /* update degree(i) */\n        Ci[pn] = Ci[p3];         /* move first node to end */\n        Ci[p3] = Ci[p1];         /* move 1st el. to end of Ei */\n        Ci[p1] = k;               /* add k as 1st element in of Ei */\n        len[i] = pn - p1 + 1;     /* new len of adj. list of node i */\n        h %= n;                    /* finalize hash of i */\n        next[i] = hhead[h];      /* place i in hash bucket */\n        hhead[h] = i;\n        last[i] = h;      /* save hash of i in last[i] */\n      }\n    }                                   /* scan2 is done */\n    degree[k] = dk;                   /* finalize |Lk| */\n    lemax = std::max<StorageIndex>(lemax, dk);\n    mark = internal::cs_wclear<StorageIndex>(mark+lemax, lemax, w, n);    /* clear w */\n    \n    /* --- Supernode detection ------------------------------------------ */\n    for(pk = pk1; pk < pk2; pk++)\n    {\n      i = Ci[pk];\n      if(nv[i] >= 0) continue;         /* skip if i is dead */\n      h = last[i];                      /* scan hash bucket of node i */\n      i = hhead[h];\n      hhead[h] = -1;                    /* hash bucket will be empty */\n      for(; i != -1 && next[i] != -1; i = next[i], mark++)\n      {\n        ln = len[i];\n        eln = elen[i];\n        for(p = Cp[i]+1; p <= Cp[i] + ln-1; p++) w[Ci[p]] = mark;\n        jlast = i;\n        for(j = next[i]; j != -1; ) /* compare i with all j */\n        {\n          ok = (len[j] == ln) && (elen[j] == eln);\n          for(p = Cp[j] + 1; ok && p <= Cp[j] + ln - 1; p++)\n          {\n            if(w[Ci[p]] != mark) ok = 0;    /* compare i and j*/\n          }\n          if(ok)                     /* i and j are identical */\n          {\n            Cp[j] = amd_flip (i);  /* absorb j into i */\n            nv[i] += nv[j];\n            nv[j] = 0;\n            elen[j] = -1;         /* node j is dead */\n            j = next[j];          /* delete j from hash bucket */\n            next[jlast] = j;\n          }\n          else\n          {\n            jlast = j;             /* j and i are different */\n            j = next[j];\n          }\n        }\n      }\n    }\n    \n    /* --- Finalize new element------------------------------------------ */\n    for(p = pk1, pk = pk1; pk < pk2; pk++)   /* finalize Lk */\n    {\n      i = Ci[pk];\n      if((nvi = -nv[i]) <= 0) continue;/* skip if i is dead */\n      nv[i] = nvi;                      /* restore nv[i] */\n      d = degree[i] + dk - nvi;         /* compute external degree(i) */\n      d = std::min<StorageIndex> (d, n - nel - nvi);\n      if(head[d] != -1) last[head[d]] = i;\n      next[i] = head[d];               /* put i back in degree list */\n      last[i] = -1;\n      head[d] = i;\n      mindeg = std::min<StorageIndex> (mindeg, d);       /* find new minimum degree */\n      degree[i] = d;\n      Ci[p++] = i;                      /* place i in Lk */\n    }\n    nv[k] = nvk;                      /* # nodes absorbed into k */\n    if((len[k] = p-pk1) == 0)         /* length of adj list of element k*/\n    {\n      Cp[k] = -1;                   /* k is a root of the tree */\n      w[k] = 0;                     /* k is now a dead element */\n    }\n    if(elenk != 0) cnz = p;           /* free unused space in Lk */\n  }\n  \n  /* --- Postordering ----------------------------------------------------- */\n  for(i = 0; i < n; i++) Cp[i] = amd_flip (Cp[i]);/* fix assembly tree */\n  for(j = 0; j <= n; j++) head[j] = -1;\n  for(j = n; j >= 0; j--)              /* place unordered nodes in lists */\n  {\n    if(nv[j] > 0) continue;          /* skip if j is an element */\n    next[j] = head[Cp[j]];          /* place j in list of its parent */\n    head[Cp[j]] = j;\n  }\n  for(e = n; e >= 0; e--)              /* place elements in lists */\n  {\n    if(nv[e] <= 0) continue;         /* skip unless e is an element */\n    if(Cp[e] != -1)\n    {\n      next[e] = head[Cp[e]];      /* place e in list of its parent */\n      head[Cp[e]] = e;\n    }\n  }\n  for(k = 0, i = 0; i <= n; i++)       /* postorder the assembly tree */\n  {\n    if(Cp[i] == -1) k = internal::cs_tdfs<StorageIndex>(i, k, head, next, perm.indices().data(), w);\n  }\n  \n  perm.indices().conservativeResize(n);\n}\n\n} // namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_AMD_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/OrderingMethods/Eigen_Colamd.h",
    "content": "// // This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Desire Nuentsa Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// This file is modified from the colamd/symamd library. The copyright is below\n\n//   The authors of the code itself are Stefan I. Larimore and Timothy A.\n//   Davis (davis@cise.ufl.edu), University of Florida.  The algorithm was\n//   developed in collaboration with John Gilbert, Xerox PARC, and Esmond\n//   Ng, Oak Ridge National Laboratory.\n//\n//     Date:\n//\n//   September 8, 2003.  Version 2.3.\n//\n//     Acknowledgements:\n//\n//   This work was supported by the National Science Foundation, under\n//   grants DMS-9504974 and DMS-9803599.\n//\n//     Notice:\n//\n//   Copyright (c) 1998-2003 by the University of Florida.\n//   All Rights Reserved.\n//\n//   THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n//   EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n//\n//   Permission is hereby granted to use, copy, modify, and/or distribute\n//   this program, provided that the Copyright, this License, and the\n//   Availability of the original version is retained on all copies and made\n//   accessible to the end-user of any code or package that includes COLAMD\n//   or any modified version of COLAMD.\n//\n//     Availability:\n//\n//   The colamd/symamd library is available at\n//\n//       http://www.suitesparse.com\n\n\n#ifndef EIGEN_COLAMD_H\n#define EIGEN_COLAMD_H\n\nnamespace internal {\n\nnamespace Colamd {\n\n/* Ensure that debugging is turned off: */\n#ifndef COLAMD_NDEBUG\n#define COLAMD_NDEBUG\n#endif /* NDEBUG */\n\n\n/* ========================================================================== */\n/* === Knob and statistics definitions ====================================== */\n/* ========================================================================== */\n\n/* size of the knobs [ ] array.  Only knobs [0..1] are currently used. */\nconst int NKnobs = 20;\n\n/* number of output statistics.  Only stats [0..6] are currently used. */\nconst int NStats = 20;\n\n/* Indices into knobs and stats array. */\nenum KnobsStatsIndex {\n  /* knobs [0] and stats [0]: dense row knob and output statistic. */\n  DenseRow = 0,\n\n  /* knobs [1] and stats [1]: dense column knob and output statistic. */\n  DenseCol = 1,\n\n  /* stats [2]: memory defragmentation count output statistic */\n  DefragCount = 2,\n\n  /* stats [3]: colamd status:  zero OK, > 0 warning or notice, < 0 error */\n  Status = 3,\n\n  /* stats [4..6]: error info, or info on jumbled columns */\n  Info1 = 4,\n  Info2 = 5,\n  Info3 = 6\n};\n\n/* error codes returned in stats [3]: */\nenum Status {\n  Ok = 0,\n  OkButJumbled = 1,\n  ErrorANotPresent = -1,\n  ErrorPNotPresent = -2,\n  ErrorNrowNegative = -3,\n  ErrorNcolNegative = -4,\n  ErrorNnzNegative = -5,\n  ErrorP0Nonzero = -6,\n  ErrorATooSmall = -7,\n  ErrorColLengthNegative = -8,\n  ErrorRowIndexOutOfBounds = -9,\n  ErrorOutOfMemory = -10,\n  ErrorInternalError = -999\n};\n/* ========================================================================== */\n/* === Definitions ========================================================== */\n/* ========================================================================== */\n\ntemplate <typename IndexType>\nIndexType ones_complement(const IndexType r) {\n  return (-(r)-1);\n}\n\n/* -------------------------------------------------------------------------- */\nconst int Empty = -1;\n\n/* Row and column status */\nenum RowColumnStatus {\n  Alive = 0,\n  Dead = -1\n};\n\n/* Column status */\nenum ColumnStatus {\n  DeadPrincipal = -1,\n  DeadNonPrincipal = -2\n};\n\n/* ========================================================================== */\n/* === Colamd reporting mechanism =========================================== */\n/* ========================================================================== */\n\n// == Row and Column structures ==\ntemplate <typename IndexType>\nstruct ColStructure\n{\n  IndexType start ;   /* index for A of first row in this column, or Dead */\n  /* if column is dead */\n  IndexType length ;  /* number of rows in this column */\n  union\n  {\n    IndexType thickness ; /* number of original columns represented by this */\n    /* col, if the column is alive */\n    IndexType parent ;  /* parent in parent tree super-column structure, if */\n    /* the column is dead */\n  } shared1 ;\n  union\n  {\n    IndexType score ; /* the score used to maintain heap, if col is alive */\n    IndexType order ; /* pivot ordering of this column, if col is dead */\n  } shared2 ;\n  union\n  {\n    IndexType headhash ;  /* head of a hash bucket, if col is at the head of */\n    /* a degree list */\n    IndexType hash ;  /* hash value, if col is not in a degree list */\n    IndexType prev ;  /* previous column in degree list, if col is in a */\n    /* degree list (but not at the head of a degree list) */\n  } shared3 ;\n  union\n  {\n    IndexType degree_next ; /* next column, if col is in a degree list */\n    IndexType hash_next ;   /* next column, if col is in a hash list */\n  } shared4 ;\n\n  inline bool is_dead() const { return start < Alive; }\n\n  inline bool is_alive() const { return start >= Alive; }\n\n  inline bool is_dead_principal() const { return start == DeadPrincipal; }\n\n  inline void kill_principal() { start = DeadPrincipal; }\n\n  inline void kill_non_principal() { start = DeadNonPrincipal; }\n\n};\n\ntemplate <typename IndexType>\nstruct RowStructure\n{\n  IndexType start ;   /* index for A of first col in this row */\n  IndexType length ;  /* number of principal columns in this row */\n  union\n  {\n    IndexType degree ;  /* number of principal & non-principal columns in row */\n    IndexType p ;   /* used as a row pointer in init_rows_cols () */\n  } shared1 ;\n  union\n  {\n    IndexType mark ;  /* for computing set differences and marking dead rows*/\n    IndexType first_column ;/* first column in row (used in garbage collection) */\n  } shared2 ;\n\n  inline bool is_dead() const { return shared2.mark < Alive; }\n\n  inline bool is_alive() const { return shared2.mark >= Alive; }\n\n  inline void kill() { shared2.mark = Dead; }\n\n};\n\n/* ========================================================================== */\n/* === Colamd recommended memory size ======================================= */\n/* ========================================================================== */\n\n/*\n  The recommended length Alen of the array A passed to colamd is given by\n  the COLAMD_RECOMMENDED (nnz, n_row, n_col) macro.  It returns -1 if any\n  argument is negative.  2*nnz space is required for the row and column\n  indices of the matrix. colamd_c (n_col) + colamd_r (n_row) space is\n  required for the Col and Row arrays, respectively, which are internal to\n  colamd.  An additional n_col space is the minimal amount of \"elbow room\",\n  and nnz/5 more space is recommended for run time efficiency.\n\n  This macro is not needed when using symamd.\n\n  Explicit typecast to IndexType added Sept. 23, 2002, COLAMD version 2.2, to avoid\n  gcc -pedantic warning messages.\n*/\ntemplate <typename IndexType>\ninline IndexType colamd_c(IndexType n_col)\n{ return IndexType( ((n_col) + 1) * sizeof (ColStructure<IndexType>) / sizeof (IndexType) ) ; }\n\ntemplate <typename IndexType>\ninline IndexType  colamd_r(IndexType n_row)\n{ return IndexType(((n_row) + 1) * sizeof (RowStructure<IndexType>) / sizeof (IndexType)); }\n\n// Prototypes of non-user callable routines\ntemplate <typename IndexType>\nstatic IndexType init_rows_cols (IndexType n_row, IndexType n_col, RowStructure<IndexType> Row [], ColStructure<IndexType> col [], IndexType A [], IndexType p [], IndexType stats[NStats] );\n\ntemplate <typename IndexType>\nstatic void init_scoring (IndexType n_row, IndexType n_col, RowStructure<IndexType> Row [], ColStructure<IndexType> Col [], IndexType A [], IndexType head [], double knobs[NKnobs], IndexType *p_n_row2, IndexType *p_n_col2, IndexType *p_max_deg);\n\ntemplate <typename IndexType>\nstatic IndexType find_ordering (IndexType n_row, IndexType n_col, IndexType Alen, RowStructure<IndexType> Row [], ColStructure<IndexType> Col [], IndexType A [], IndexType head [], IndexType n_col2, IndexType max_deg, IndexType pfree);\n\ntemplate <typename IndexType>\nstatic void order_children (IndexType n_col, ColStructure<IndexType> Col [], IndexType p []);\n\ntemplate <typename IndexType>\nstatic void detect_super_cols (ColStructure<IndexType> Col [], IndexType A [], IndexType head [], IndexType row_start, IndexType row_length ) ;\n\ntemplate <typename IndexType>\nstatic IndexType garbage_collection (IndexType n_row, IndexType n_col, RowStructure<IndexType> Row [], ColStructure<IndexType> Col [], IndexType A [], IndexType *pfree) ;\n\ntemplate <typename IndexType>\nstatic inline  IndexType clear_mark (IndexType n_row, RowStructure<IndexType> Row [] ) ;\n\n/* === No debugging ========================================================= */\n\n#define COLAMD_DEBUG0(params) ;\n#define COLAMD_DEBUG1(params) ;\n#define COLAMD_DEBUG2(params) ;\n#define COLAMD_DEBUG3(params) ;\n#define COLAMD_DEBUG4(params) ;\n\n#define COLAMD_ASSERT(expression) ((void) 0)\n\n\n/**\n * \\brief Returns the recommended value of Alen\n *\n * Returns recommended value of Alen for use by colamd.\n * Returns -1 if any input argument is negative.\n * The use of this routine or macro is optional.\n * Note that the macro uses its arguments   more than once,\n * so be careful for side effects, if you pass expressions as arguments to COLAMD_RECOMMENDED.\n *\n * \\param nnz nonzeros in A\n * \\param n_row number of rows in A\n * \\param n_col number of columns in A\n * \\return recommended value of Alen for use by colamd\n */\ntemplate <typename IndexType>\ninline IndexType recommended ( IndexType nnz, IndexType n_row, IndexType n_col)\n{\n  if ((nnz) < 0 || (n_row) < 0 || (n_col) < 0)\n    return (-1);\n  else\n    return (2 * (nnz) + colamd_c (n_col) + colamd_r (n_row) + (n_col) + ((nnz) / 5));\n}\n\n/**\n * \\brief set default parameters  The use of this routine is optional.\n *\n * Colamd: rows with more than (knobs [DenseRow] * n_col)\n * entries are removed prior to ordering.  Columns with more than\n * (knobs [DenseCol] * n_row) entries are removed prior to\n * ordering, and placed last in the output column ordering.\n *\n * DenseRow and DenseCol are defined as 0 and 1,\n * respectively, in colamd.h.  Default values of these two knobs\n * are both 0.5.  Currently, only knobs [0] and knobs [1] are\n * used, but future versions may use more knobs.  If so, they will\n * be properly set to their defaults by the future version of\n * colamd_set_defaults, so that the code that calls colamd will\n * not need to change, assuming that you either use\n * colamd_set_defaults, or pass a (double *) NULL pointer as the\n * knobs array to colamd or symamd.\n *\n * \\param knobs parameter settings for colamd\n */\n\nstatic inline void set_defaults(double knobs[NKnobs])\n{\n  /* === Local variables ================================================== */\n\n  int i ;\n\n  if (!knobs)\n  {\n    return ;      /* no knobs to initialize */\n  }\n  for (i = 0 ; i < NKnobs ; i++)\n  {\n    knobs [i] = 0 ;\n  }\n  knobs [Colamd::DenseRow] = 0.5 ;  /* ignore rows over 50% dense */\n  knobs [Colamd::DenseCol] = 0.5 ;  /* ignore columns over 50% dense */\n}\n\n/**\n * \\brief  Computes a column ordering using the column approximate minimum degree ordering\n *\n * Computes a column ordering (Q) of A such that P(AQ)=LU or\n * (AQ)'AQ=LL' have less fill-in and require fewer floating point\n * operations than factorizing the unpermuted matrix A or A'A,\n * respectively.\n *\n *\n * \\param n_row number of rows in A\n * \\param n_col number of columns in A\n * \\param Alen, size of the array A\n * \\param A row indices of the matrix, of size ALen\n * \\param p column pointers of A, of size n_col+1\n * \\param knobs parameter settings for colamd\n * \\param stats colamd output statistics and error codes\n */\ntemplate <typename IndexType>\nstatic bool compute_ordering(IndexType n_row, IndexType n_col, IndexType Alen, IndexType *A, IndexType *p, double knobs[NKnobs], IndexType stats[NStats])\n{\n  /* === Local variables ================================================== */\n\n  IndexType i ;     /* loop index */\n  IndexType nnz ;     /* nonzeros in A */\n  IndexType Row_size ;    /* size of Row [], in integers */\n  IndexType Col_size ;    /* size of Col [], in integers */\n  IndexType need ;      /* minimum required length of A */\n  Colamd::RowStructure<IndexType> *Row ;   /* pointer into A of Row [0..n_row] array */\n  Colamd::ColStructure<IndexType> *Col ;   /* pointer into A of Col [0..n_col] array */\n  IndexType n_col2 ;    /* number of non-dense, non-empty columns */\n  IndexType n_row2 ;    /* number of non-dense, non-empty rows */\n  IndexType ngarbage ;    /* number of garbage collections performed */\n  IndexType max_deg ;   /* maximum row degree */\n  double default_knobs [NKnobs] ; /* default knobs array */\n\n\n  /* === Check the input arguments ======================================== */\n\n  if (!stats)\n  {\n    COLAMD_DEBUG0 ((\"colamd: stats not present\\n\")) ;\n    return (false) ;\n  }\n  for (i = 0 ; i < NStats ; i++)\n  {\n    stats [i] = 0 ;\n  }\n  stats [Colamd::Status] = Colamd::Ok ;\n  stats [Colamd::Info1] = -1 ;\n  stats [Colamd::Info2] = -1 ;\n\n  if (!A)   /* A is not present */\n  {\n    stats [Colamd::Status] = Colamd::ErrorANotPresent ;\n    COLAMD_DEBUG0 ((\"colamd: A not present\\n\")) ;\n    return (false) ;\n  }\n\n  if (!p)   /* p is not present */\n  {\n    stats [Colamd::Status] = Colamd::ErrorPNotPresent ;\n    COLAMD_DEBUG0 ((\"colamd: p not present\\n\")) ;\n    return (false) ;\n  }\n\n  if (n_row < 0)  /* n_row must be >= 0 */\n  {\n    stats [Colamd::Status] = Colamd::ErrorNrowNegative ;\n    stats [Colamd::Info1] = n_row ;\n    COLAMD_DEBUG0 ((\"colamd: nrow negative %d\\n\", n_row)) ;\n    return (false) ;\n  }\n\n  if (n_col < 0)  /* n_col must be >= 0 */\n  {\n    stats [Colamd::Status] = Colamd::ErrorNcolNegative ;\n    stats [Colamd::Info1] = n_col ;\n    COLAMD_DEBUG0 ((\"colamd: ncol negative %d\\n\", n_col)) ;\n    return (false) ;\n  }\n\n  nnz = p [n_col] ;\n  if (nnz < 0)  /* nnz must be >= 0 */\n  {\n    stats [Colamd::Status] = Colamd::ErrorNnzNegative ;\n    stats [Colamd::Info1] = nnz ;\n    COLAMD_DEBUG0 ((\"colamd: number of entries negative %d\\n\", nnz)) ;\n    return (false) ;\n  }\n\n  if (p [0] != 0)\n  {\n    stats [Colamd::Status] = Colamd::ErrorP0Nonzero ;\n    stats [Colamd::Info1] = p [0] ;\n    COLAMD_DEBUG0 ((\"colamd: p[0] not zero %d\\n\", p [0])) ;\n    return (false) ;\n  }\n\n  /* === If no knobs, set default knobs =================================== */\n\n  if (!knobs)\n  {\n    set_defaults (default_knobs) ;\n    knobs = default_knobs ;\n  }\n\n  /* === Allocate the Row and Col arrays from array A ===================== */\n\n  Col_size = colamd_c (n_col) ;\n  Row_size = colamd_r (n_row) ;\n  need = 2*nnz + n_col + Col_size + Row_size ;\n\n  if (need > Alen)\n  {\n    /* not enough space in array A to perform the ordering */\n    stats [Colamd::Status] = Colamd::ErrorATooSmall ;\n    stats [Colamd::Info1] = need ;\n    stats [Colamd::Info2] = Alen ;\n    COLAMD_DEBUG0 ((\"colamd: Need Alen >= %d, given only Alen = %d\\n\", need,Alen));\n    return (false) ;\n  }\n\n  Alen -= Col_size + Row_size ;\n  Col = (ColStructure<IndexType> *) &A [Alen] ;\n  Row = (RowStructure<IndexType> *) &A [Alen + Col_size] ;\n\n  /* === Construct the row and column data structures ===================== */\n\n  if (!Colamd::init_rows_cols (n_row, n_col, Row, Col, A, p, stats))\n  {\n    /* input matrix is invalid */\n    COLAMD_DEBUG0 ((\"colamd: Matrix invalid\\n\")) ;\n    return (false) ;\n  }\n\n  /* === Initialize scores, kill dense rows/columns ======================= */\n\n  Colamd::init_scoring (n_row, n_col, Row, Col, A, p, knobs,\n\t\t&n_row2, &n_col2, &max_deg) ;\n\n  /* === Order the supercolumns =========================================== */\n\n  ngarbage = Colamd::find_ordering (n_row, n_col, Alen, Row, Col, A, p,\n\t\t\t    n_col2, max_deg, 2*nnz) ;\n\n  /* === Order the non-principal columns ================================== */\n\n  Colamd::order_children (n_col, Col, p) ;\n\n  /* === Return statistics in stats ======================================= */\n\n  stats [Colamd::DenseRow] = n_row - n_row2 ;\n  stats [Colamd::DenseCol] = n_col - n_col2 ;\n  stats [Colamd::DefragCount] = ngarbage ;\n  COLAMD_DEBUG0 ((\"colamd: done.\\n\")) ;\n  return (true) ;\n}\n\n/* ========================================================================== */\n/* === NON-USER-CALLABLE ROUTINES: ========================================== */\n/* ========================================================================== */\n\n/* There are no user-callable routines beyond this point in the file */\n\n/* ========================================================================== */\n/* === init_rows_cols ======================================================= */\n/* ========================================================================== */\n\n/*\n  Takes the column form of the matrix in A and creates the row form of the\n  matrix.  Also, row and column attributes are stored in the Col and Row\n  structs.  If the columns are un-sorted or contain duplicate row indices,\n  this routine will also sort and remove duplicate row indices from the\n  column form of the matrix.  Returns false if the matrix is invalid,\n  true otherwise.  Not user-callable.\n*/\ntemplate <typename IndexType>\nstatic IndexType init_rows_cols  /* returns true if OK, or false otherwise */\n  (\n    /* === Parameters ======================================================= */\n\n    IndexType n_row,      /* number of rows of A */\n    IndexType n_col,      /* number of columns of A */\n    RowStructure<IndexType> Row [],    /* of size n_row+1 */\n    ColStructure<IndexType> Col [],    /* of size n_col+1 */\n    IndexType A [],     /* row indices of A, of size Alen */\n    IndexType p [],     /* pointers to columns in A, of size n_col+1 */\n    IndexType stats [NStats]  /* colamd statistics */\n    )\n{\n  /* === Local variables ================================================== */\n\n  IndexType col ;     /* a column index */\n  IndexType row ;     /* a row index */\n  IndexType *cp ;     /* a column pointer */\n  IndexType *cp_end ;   /* a pointer to the end of a column */\n  IndexType *rp ;     /* a row pointer */\n  IndexType *rp_end ;   /* a pointer to the end of a row */\n  IndexType last_row ;    /* previous row */\n\n  /* === Initialize columns, and check column pointers ==================== */\n\n  for (col = 0 ; col < n_col ; col++)\n  {\n    Col [col].start = p [col] ;\n    Col [col].length = p [col+1] - p [col] ;\n\n    if ((Col [col].length) < 0) // extra parentheses to work-around gcc bug 10200\n    {\n      /* column pointers must be non-decreasing */\n      stats [Colamd::Status] = Colamd::ErrorColLengthNegative ;\n      stats [Colamd::Info1] = col ;\n      stats [Colamd::Info2] = Col [col].length ;\n      COLAMD_DEBUG0 ((\"colamd: col %d length %d < 0\\n\", col, Col [col].length)) ;\n      return (false) ;\n    }\n\n    Col [col].shared1.thickness = 1 ;\n    Col [col].shared2.score = 0 ;\n    Col [col].shared3.prev = Empty ;\n    Col [col].shared4.degree_next = Empty ;\n  }\n\n  /* p [0..n_col] no longer needed, used as \"head\" in subsequent routines */\n\n  /* === Scan columns, compute row degrees, and check row indices ========= */\n\n  stats [Info3] = 0 ;  /* number of duplicate or unsorted row indices*/\n\n  for (row = 0 ; row < n_row ; row++)\n  {\n    Row [row].length = 0 ;\n    Row [row].shared2.mark = -1 ;\n  }\n\n  for (col = 0 ; col < n_col ; col++)\n  {\n    last_row = -1 ;\n\n    cp = &A [p [col]] ;\n    cp_end = &A [p [col+1]] ;\n\n    while (cp < cp_end)\n    {\n      row = *cp++ ;\n\n      /* make sure row indices within range */\n      if (row < 0 || row >= n_row)\n      {\n\tstats [Colamd::Status] = Colamd::ErrorRowIndexOutOfBounds ;\n\tstats [Colamd::Info1] = col ;\n\tstats [Colamd::Info2] = row ;\n\tstats [Colamd::Info3] = n_row ;\n\tCOLAMD_DEBUG0 ((\"colamd: row %d col %d out of bounds\\n\", row, col)) ;\n\treturn (false) ;\n      }\n\n      if (row <= last_row || Row [row].shared2.mark == col)\n      {\n\t/* row index are unsorted or repeated (or both), thus col */\n\t/* is jumbled.  This is a notice, not an error condition. */\n\tstats [Colamd::Status] = Colamd::OkButJumbled ;\n\tstats [Colamd::Info1] = col ;\n\tstats [Colamd::Info2] = row ;\n\t(stats [Colamd::Info3]) ++ ;\n\tCOLAMD_DEBUG1 ((\"colamd: row %d col %d unsorted/duplicate\\n\",row,col));\n      }\n\n      if (Row [row].shared2.mark != col)\n      {\n\tRow [row].length++ ;\n      }\n      else\n      {\n\t/* this is a repeated entry in the column, */\n\t/* it will be removed */\n\tCol [col].length-- ;\n      }\n\n      /* mark the row as having been seen in this column */\n      Row [row].shared2.mark = col ;\n\n      last_row = row ;\n    }\n  }\n\n  /* === Compute row pointers ============================================= */\n\n  /* row form of the matrix starts directly after the column */\n  /* form of matrix in A */\n  Row [0].start = p [n_col] ;\n  Row [0].shared1.p = Row [0].start ;\n  Row [0].shared2.mark = -1 ;\n  for (row = 1 ; row < n_row ; row++)\n  {\n    Row [row].start = Row [row-1].start + Row [row-1].length ;\n    Row [row].shared1.p = Row [row].start ;\n    Row [row].shared2.mark = -1 ;\n  }\n\n  /* === Create row form ================================================== */\n\n  if (stats [Status] == OkButJumbled)\n  {\n    /* if cols jumbled, watch for repeated row indices */\n    for (col = 0 ; col < n_col ; col++)\n    {\n      cp = &A [p [col]] ;\n      cp_end = &A [p [col+1]] ;\n      while (cp < cp_end)\n      {\n\trow = *cp++ ;\n\tif (Row [row].shared2.mark != col)\n\t{\n\t  A [(Row [row].shared1.p)++] = col ;\n\t  Row [row].shared2.mark = col ;\n\t}\n      }\n    }\n  }\n  else\n  {\n    /* if cols not jumbled, we don't need the mark (this is faster) */\n    for (col = 0 ; col < n_col ; col++)\n    {\n      cp = &A [p [col]] ;\n      cp_end = &A [p [col+1]] ;\n      while (cp < cp_end)\n      {\n\tA [(Row [*cp++].shared1.p)++] = col ;\n      }\n    }\n  }\n\n  /* === Clear the row marks and set row degrees ========================== */\n\n  for (row = 0 ; row < n_row ; row++)\n  {\n    Row [row].shared2.mark = 0 ;\n    Row [row].shared1.degree = Row [row].length ;\n  }\n\n  /* === See if we need to re-create columns ============================== */\n\n  if (stats [Status] == OkButJumbled)\n  {\n    COLAMD_DEBUG0 ((\"colamd: reconstructing column form, matrix jumbled\\n\")) ;\n\n\n    /* === Compute col pointers ========================================= */\n\n    /* col form of the matrix starts at A [0]. */\n    /* Note, we may have a gap between the col form and the row */\n    /* form if there were duplicate entries, if so, it will be */\n    /* removed upon the first garbage collection */\n    Col [0].start = 0 ;\n    p [0] = Col [0].start ;\n    for (col = 1 ; col < n_col ; col++)\n    {\n      /* note that the lengths here are for pruned columns, i.e. */\n      /* no duplicate row indices will exist for these columns */\n      Col [col].start = Col [col-1].start + Col [col-1].length ;\n      p [col] = Col [col].start ;\n    }\n\n    /* === Re-create col form =========================================== */\n\n    for (row = 0 ; row < n_row ; row++)\n    {\n      rp = &A [Row [row].start] ;\n      rp_end = rp + Row [row].length ;\n      while (rp < rp_end)\n      {\n\tA [(p [*rp++])++] = row ;\n      }\n    }\n  }\n\n  /* === Done.  Matrix is not (or no longer) jumbled ====================== */\n\n  return (true) ;\n}\n\n\n/* ========================================================================== */\n/* === init_scoring ========================================================= */\n/* ========================================================================== */\n\n/*\n  Kills dense or empty columns and rows, calculates an initial score for\n  each column, and places all columns in the degree lists.  Not user-callable.\n*/\ntemplate <typename IndexType>\nstatic void init_scoring\n  (\n    /* === Parameters ======================================================= */\n\n    IndexType n_row,      /* number of rows of A */\n    IndexType n_col,      /* number of columns of A */\n    RowStructure<IndexType> Row [],    /* of size n_row+1 */\n    ColStructure<IndexType> Col [],    /* of size n_col+1 */\n    IndexType A [],     /* column form and row form of A */\n    IndexType head [],    /* of size n_col+1 */\n    double knobs [NKnobs],/* parameters */\n    IndexType *p_n_row2,    /* number of non-dense, non-empty rows */\n    IndexType *p_n_col2,    /* number of non-dense, non-empty columns */\n    IndexType *p_max_deg    /* maximum row degree */\n    )\n{\n  /* === Local variables ================================================== */\n\n  IndexType c ;     /* a column index */\n  IndexType r, row ;    /* a row index */\n  IndexType *cp ;     /* a column pointer */\n  IndexType deg ;     /* degree of a row or column */\n  IndexType *cp_end ;   /* a pointer to the end of a column */\n  IndexType *new_cp ;   /* new column pointer */\n  IndexType col_length ;    /* length of pruned column */\n  IndexType score ;     /* current column score */\n  IndexType n_col2 ;    /* number of non-dense, non-empty columns */\n  IndexType n_row2 ;    /* number of non-dense, non-empty rows */\n  IndexType dense_row_count ; /* remove rows with more entries than this */\n  IndexType dense_col_count ; /* remove cols with more entries than this */\n  IndexType min_score ;   /* smallest column score */\n  IndexType max_deg ;   /* maximum row degree */\n  IndexType next_col ;    /* Used to add to degree list.*/\n\n\n  /* === Extract knobs ==================================================== */\n\n  dense_row_count = numext::maxi(IndexType(0), numext::mini(IndexType(knobs [Colamd::DenseRow] * n_col), n_col)) ;\n  dense_col_count = numext::maxi(IndexType(0), numext::mini(IndexType(knobs [Colamd::DenseCol] * n_row), n_row)) ;\n  COLAMD_DEBUG1 ((\"colamd: densecount: %d %d\\n\", dense_row_count, dense_col_count)) ;\n  max_deg = 0 ;\n  n_col2 = n_col ;\n  n_row2 = n_row ;\n\n  /* === Kill empty columns =============================================== */\n\n  /* Put the empty columns at the end in their natural order, so that LU */\n  /* factorization can proceed as far as possible. */\n  for (c = n_col-1 ; c >= 0 ; c--)\n  {\n    deg = Col [c].length ;\n    if (deg == 0)\n    {\n      /* this is a empty column, kill and order it last */\n      Col [c].shared2.order = --n_col2 ;\n      Col[c].kill_principal() ;\n    }\n  }\n  COLAMD_DEBUG1 ((\"colamd: null columns killed: %d\\n\", n_col - n_col2)) ;\n\n  /* === Kill dense columns =============================================== */\n\n  /* Put the dense columns at the end, in their natural order */\n  for (c = n_col-1 ; c >= 0 ; c--)\n  {\n    /* skip any dead columns */\n    if (Col[c].is_dead())\n    {\n      continue ;\n    }\n    deg = Col [c].length ;\n    if (deg > dense_col_count)\n    {\n      /* this is a dense column, kill and order it last */\n      Col [c].shared2.order = --n_col2 ;\n      /* decrement the row degrees */\n      cp = &A [Col [c].start] ;\n      cp_end = cp + Col [c].length ;\n      while (cp < cp_end)\n      {\n\tRow [*cp++].shared1.degree-- ;\n      }\n      Col[c].kill_principal() ;\n    }\n  }\n  COLAMD_DEBUG1 ((\"colamd: Dense and null columns killed: %d\\n\", n_col - n_col2)) ;\n\n  /* === Kill dense and empty rows ======================================== */\n\n  for (r = 0 ; r < n_row ; r++)\n  {\n    deg = Row [r].shared1.degree ;\n    COLAMD_ASSERT (deg >= 0 && deg <= n_col) ;\n    if (deg > dense_row_count || deg == 0)\n    {\n      /* kill a dense or empty row */\n      Row[r].kill() ;\n      --n_row2 ;\n    }\n    else\n    {\n      /* keep track of max degree of remaining rows */\n      max_deg = numext::maxi(max_deg, deg) ;\n    }\n  }\n  COLAMD_DEBUG1 ((\"colamd: Dense and null rows killed: %d\\n\", n_row - n_row2)) ;\n\n  /* === Compute initial column scores ==================================== */\n\n  /* At this point the row degrees are accurate.  They reflect the number */\n  /* of \"live\" (non-dense) columns in each row.  No empty rows exist. */\n  /* Some \"live\" columns may contain only dead rows, however.  These are */\n  /* pruned in the code below. */\n\n  /* now find the initial matlab score for each column */\n  for (c = n_col-1 ; c >= 0 ; c--)\n  {\n    /* skip dead column */\n    if (Col[c].is_dead())\n    {\n      continue ;\n    }\n    score = 0 ;\n    cp = &A [Col [c].start] ;\n    new_cp = cp ;\n    cp_end = cp + Col [c].length ;\n    while (cp < cp_end)\n    {\n      /* get a row */\n      row = *cp++ ;\n      /* skip if dead */\n      if (Row[row].is_dead())\n      {\n\tcontinue ;\n      }\n      /* compact the column */\n      *new_cp++ = row ;\n      /* add row's external degree */\n      score += Row [row].shared1.degree - 1 ;\n      /* guard against integer overflow */\n      score = numext::mini(score, n_col) ;\n    }\n    /* determine pruned column length */\n    col_length = (IndexType) (new_cp - &A [Col [c].start]) ;\n    if (col_length == 0)\n    {\n      /* a newly-made null column (all rows in this col are \"dense\" */\n      /* and have already been killed) */\n      COLAMD_DEBUG2 ((\"Newly null killed: %d\\n\", c)) ;\n      Col [c].shared2.order = --n_col2 ;\n      Col[c].kill_principal() ;\n    }\n    else\n    {\n      /* set column length and set score */\n      COLAMD_ASSERT (score >= 0) ;\n      COLAMD_ASSERT (score <= n_col) ;\n      Col [c].length = col_length ;\n      Col [c].shared2.score = score ;\n    }\n  }\n  COLAMD_DEBUG1 ((\"colamd: Dense, null, and newly-null columns killed: %d\\n\",\n\t\t  n_col-n_col2)) ;\n\n  /* At this point, all empty rows and columns are dead.  All live columns */\n  /* are \"clean\" (containing no dead rows) and simplicial (no supercolumns */\n  /* yet).  Rows may contain dead columns, but all live rows contain at */\n  /* least one live column. */\n\n  /* === Initialize degree lists ========================================== */\n\n\n  /* clear the hash buckets */\n  for (c = 0 ; c <= n_col ; c++)\n  {\n    head [c] = Empty ;\n  }\n  min_score = n_col ;\n  /* place in reverse order, so low column indices are at the front */\n  /* of the lists.  This is to encourage natural tie-breaking */\n  for (c = n_col-1 ; c >= 0 ; c--)\n  {\n    /* only add principal columns to degree lists */\n    if (Col[c].is_alive())\n    {\n      COLAMD_DEBUG4 ((\"place %d score %d minscore %d ncol %d\\n\",\n\t\t      c, Col [c].shared2.score, min_score, n_col)) ;\n\n      /* === Add columns score to DList =============================== */\n\n      score = Col [c].shared2.score ;\n\n      COLAMD_ASSERT (min_score >= 0) ;\n      COLAMD_ASSERT (min_score <= n_col) ;\n      COLAMD_ASSERT (score >= 0) ;\n      COLAMD_ASSERT (score <= n_col) ;\n      COLAMD_ASSERT (head [score] >= Empty) ;\n\n      /* now add this column to dList at proper score location */\n      next_col = head [score] ;\n      Col [c].shared3.prev = Empty ;\n      Col [c].shared4.degree_next = next_col ;\n\n      /* if there already was a column with the same score, set its */\n      /* previous pointer to this new column */\n      if (next_col != Empty)\n      {\n\tCol [next_col].shared3.prev = c ;\n      }\n      head [score] = c ;\n\n      /* see if this score is less than current min */\n      min_score = numext::mini(min_score, score) ;\n\n\n    }\n  }\n\n\n  /* === Return number of remaining columns, and max row degree =========== */\n\n  *p_n_col2 = n_col2 ;\n  *p_n_row2 = n_row2 ;\n  *p_max_deg = max_deg ;\n}\n\n\n/* ========================================================================== */\n/* === find_ordering ======================================================== */\n/* ========================================================================== */\n\n/*\n  Order the principal columns of the supercolumn form of the matrix\n  (no supercolumns on input).  Uses a minimum approximate column minimum\n  degree ordering method.  Not user-callable.\n*/\ntemplate <typename IndexType>\nstatic IndexType find_ordering /* return the number of garbage collections */\n  (\n    /* === Parameters ======================================================= */\n\n    IndexType n_row,      /* number of rows of A */\n    IndexType n_col,      /* number of columns of A */\n    IndexType Alen,     /* size of A, 2*nnz + n_col or larger */\n    RowStructure<IndexType> Row [],    /* of size n_row+1 */\n    ColStructure<IndexType> Col [],    /* of size n_col+1 */\n    IndexType A [],     /* column form and row form of A */\n    IndexType head [],    /* of size n_col+1 */\n    IndexType n_col2,     /* Remaining columns to order */\n    IndexType max_deg,    /* Maximum row degree */\n    IndexType pfree     /* index of first free slot (2*nnz on entry) */\n    )\n{\n  /* === Local variables ================================================== */\n\n  IndexType k ;     /* current pivot ordering step */\n  IndexType pivot_col ;   /* current pivot column */\n  IndexType *cp ;     /* a column pointer */\n  IndexType *rp ;     /* a row pointer */\n  IndexType pivot_row ;   /* current pivot row */\n  IndexType *new_cp ;   /* modified column pointer */\n  IndexType *new_rp ;   /* modified row pointer */\n  IndexType pivot_row_start ; /* pointer to start of pivot row */\n  IndexType pivot_row_degree ;  /* number of columns in pivot row */\n  IndexType pivot_row_length ;  /* number of supercolumns in pivot row */\n  IndexType pivot_col_score ; /* score of pivot column */\n  IndexType needed_memory ;   /* free space needed for pivot row */\n  IndexType *cp_end ;   /* pointer to the end of a column */\n  IndexType *rp_end ;   /* pointer to the end of a row */\n  IndexType row ;     /* a row index */\n  IndexType col ;     /* a column index */\n  IndexType max_score ;   /* maximum possible score */\n  IndexType cur_score ;   /* score of current column */\n  unsigned int hash ;   /* hash value for supernode detection */\n  IndexType head_column ;   /* head of hash bucket */\n  IndexType first_col ;   /* first column in hash bucket */\n  IndexType tag_mark ;    /* marker value for mark array */\n  IndexType row_mark ;    /* Row [row].shared2.mark */\n  IndexType set_difference ;  /* set difference size of row with pivot row */\n  IndexType min_score ;   /* smallest column score */\n  IndexType col_thickness ;   /* \"thickness\" (no. of columns in a supercol) */\n  IndexType max_mark ;    /* maximum value of tag_mark */\n  IndexType pivot_col_thickness ; /* number of columns represented by pivot col */\n  IndexType prev_col ;    /* Used by Dlist operations. */\n  IndexType next_col ;    /* Used by Dlist operations. */\n  IndexType ngarbage ;    /* number of garbage collections performed */\n\n\n  /* === Initialization and clear mark ==================================== */\n\n  max_mark = INT_MAX - n_col ;  /* INT_MAX defined in <limits.h> */\n  tag_mark = Colamd::clear_mark (n_row, Row) ;\n  min_score = 0 ;\n  ngarbage = 0 ;\n  COLAMD_DEBUG1 ((\"colamd: Ordering, n_col2=%d\\n\", n_col2)) ;\n\n  /* === Order the columns ================================================ */\n\n  for (k = 0 ; k < n_col2 ; /* 'k' is incremented below */)\n  {\n\n    /* === Select pivot column, and order it ============================ */\n\n    /* make sure degree list isn't empty */\n    COLAMD_ASSERT (min_score >= 0) ;\n    COLAMD_ASSERT (min_score <= n_col) ;\n    COLAMD_ASSERT (head [min_score] >= Empty) ;\n\n    /* get pivot column from head of minimum degree list */\n    while (min_score < n_col && head [min_score] == Empty)\n    {\n      min_score++ ;\n    }\n    pivot_col = head [min_score] ;\n    COLAMD_ASSERT (pivot_col >= 0 && pivot_col <= n_col) ;\n    next_col = Col [pivot_col].shared4.degree_next ;\n    head [min_score] = next_col ;\n    if (next_col != Empty)\n    {\n      Col [next_col].shared3.prev = Empty ;\n    }\n\n    COLAMD_ASSERT (Col[pivot_col].is_alive()) ;\n    COLAMD_DEBUG3 ((\"Pivot col: %d\\n\", pivot_col)) ;\n\n    /* remember score for defrag check */\n    pivot_col_score = Col [pivot_col].shared2.score ;\n\n    /* the pivot column is the kth column in the pivot order */\n    Col [pivot_col].shared2.order = k ;\n\n    /* increment order count by column thickness */\n    pivot_col_thickness = Col [pivot_col].shared1.thickness ;\n    k += pivot_col_thickness ;\n    COLAMD_ASSERT (pivot_col_thickness > 0) ;\n\n    /* === Garbage_collection, if necessary ============================= */\n\n    needed_memory = numext::mini(pivot_col_score, n_col - k) ;\n    if (pfree + needed_memory >= Alen)\n    {\n      pfree = Colamd::garbage_collection (n_row, n_col, Row, Col, A, &A [pfree]) ;\n      ngarbage++ ;\n      /* after garbage collection we will have enough */\n      COLAMD_ASSERT (pfree + needed_memory < Alen) ;\n      /* garbage collection has wiped out the Row[].shared2.mark array */\n      tag_mark = Colamd::clear_mark (n_row, Row) ;\n\n    }\n\n    /* === Compute pivot row pattern ==================================== */\n\n    /* get starting location for this new merged row */\n    pivot_row_start = pfree ;\n\n    /* initialize new row counts to zero */\n    pivot_row_degree = 0 ;\n\n    /* tag pivot column as having been visited so it isn't included */\n    /* in merged pivot row */\n    Col [pivot_col].shared1.thickness = -pivot_col_thickness ;\n\n    /* pivot row is the union of all rows in the pivot column pattern */\n    cp = &A [Col [pivot_col].start] ;\n    cp_end = cp + Col [pivot_col].length ;\n    while (cp < cp_end)\n    {\n      /* get a row */\n      row = *cp++ ;\n      COLAMD_DEBUG4 ((\"Pivot col pattern %d %d\\n\", Row[row].is_alive(), row)) ;\n      /* skip if row is dead */\n      if (Row[row].is_dead())\n      {\n\tcontinue ;\n      }\n      rp = &A [Row [row].start] ;\n      rp_end = rp + Row [row].length ;\n      while (rp < rp_end)\n      {\n\t/* get a column */\n\tcol = *rp++ ;\n\t/* add the column, if alive and untagged */\n\tcol_thickness = Col [col].shared1.thickness ;\n\tif (col_thickness > 0 && Col[col].is_alive())\n\t{\n\t  /* tag column in pivot row */\n\t  Col [col].shared1.thickness = -col_thickness ;\n\t  COLAMD_ASSERT (pfree < Alen) ;\n\t  /* place column in pivot row */\n\t  A [pfree++] = col ;\n\t  pivot_row_degree += col_thickness ;\n\t}\n      }\n    }\n\n    /* clear tag on pivot column */\n    Col [pivot_col].shared1.thickness = pivot_col_thickness ;\n    max_deg = numext::maxi(max_deg, pivot_row_degree) ;\n\n\n    /* === Kill all rows used to construct pivot row ==================== */\n\n    /* also kill pivot row, temporarily */\n    cp = &A [Col [pivot_col].start] ;\n    cp_end = cp + Col [pivot_col].length ;\n    while (cp < cp_end)\n    {\n      /* may be killing an already dead row */\n      row = *cp++ ;\n      COLAMD_DEBUG3 ((\"Kill row in pivot col: %d\\n\", row)) ;\n      Row[row].kill() ;\n    }\n\n    /* === Select a row index to use as the new pivot row =============== */\n\n    pivot_row_length = pfree - pivot_row_start ;\n    if (pivot_row_length > 0)\n    {\n      /* pick the \"pivot\" row arbitrarily (first row in col) */\n      pivot_row = A [Col [pivot_col].start] ;\n      COLAMD_DEBUG3 ((\"Pivotal row is %d\\n\", pivot_row)) ;\n    }\n    else\n    {\n      /* there is no pivot row, since it is of zero length */\n      pivot_row = Empty ;\n      COLAMD_ASSERT (pivot_row_length == 0) ;\n    }\n    COLAMD_ASSERT (Col [pivot_col].length > 0 || pivot_row_length == 0) ;\n\n    /* === Approximate degree computation =============================== */\n\n    /* Here begins the computation of the approximate degree.  The column */\n    /* score is the sum of the pivot row \"length\", plus the size of the */\n    /* set differences of each row in the column minus the pattern of the */\n    /* pivot row itself.  The column (\"thickness\") itself is also */\n    /* excluded from the column score (we thus use an approximate */\n    /* external degree). */\n\n    /* The time taken by the following code (compute set differences, and */\n    /* add them up) is proportional to the size of the data structure */\n    /* being scanned - that is, the sum of the sizes of each column in */\n    /* the pivot row.  Thus, the amortized time to compute a column score */\n    /* is proportional to the size of that column (where size, in this */\n    /* context, is the column \"length\", or the number of row indices */\n    /* in that column).  The number of row indices in a column is */\n    /* monotonically non-decreasing, from the length of the original */\n    /* column on input to colamd. */\n\n    /* === Compute set differences ====================================== */\n\n    COLAMD_DEBUG3 ((\"** Computing set differences phase. **\\n\")) ;\n\n    /* pivot row is currently dead - it will be revived later. */\n\n    COLAMD_DEBUG3 ((\"Pivot row: \")) ;\n    /* for each column in pivot row */\n    rp = &A [pivot_row_start] ;\n    rp_end = rp + pivot_row_length ;\n    while (rp < rp_end)\n    {\n      col = *rp++ ;\n      COLAMD_ASSERT (Col[col].is_alive() && col != pivot_col) ;\n      COLAMD_DEBUG3 ((\"Col: %d\\n\", col)) ;\n\n      /* clear tags used to construct pivot row pattern */\n      col_thickness = -Col [col].shared1.thickness ;\n      COLAMD_ASSERT (col_thickness > 0) ;\n      Col [col].shared1.thickness = col_thickness ;\n\n      /* === Remove column from degree list =========================== */\n\n      cur_score = Col [col].shared2.score ;\n      prev_col = Col [col].shared3.prev ;\n      next_col = Col [col].shared4.degree_next ;\n      COLAMD_ASSERT (cur_score >= 0) ;\n      COLAMD_ASSERT (cur_score <= n_col) ;\n      COLAMD_ASSERT (cur_score >= Empty) ;\n      if (prev_col == Empty)\n      {\n\thead [cur_score] = next_col ;\n      }\n      else\n      {\n\tCol [prev_col].shared4.degree_next = next_col ;\n      }\n      if (next_col != Empty)\n      {\n\tCol [next_col].shared3.prev = prev_col ;\n      }\n\n      /* === Scan the column ========================================== */\n\n      cp = &A [Col [col].start] ;\n      cp_end = cp + Col [col].length ;\n      while (cp < cp_end)\n      {\n\t/* get a row */\n\trow = *cp++ ;\n\t/* skip if dead */\n\tif (Row[row].is_dead())\n\t{\n\t  continue ;\n\t}\n  row_mark = Row [row].shared2.mark ;\n\tCOLAMD_ASSERT (row != pivot_row) ;\n\tset_difference = row_mark - tag_mark ;\n\t/* check if the row has been seen yet */\n\tif (set_difference < 0)\n\t{\n\t  COLAMD_ASSERT (Row [row].shared1.degree <= max_deg) ;\n\t  set_difference = Row [row].shared1.degree ;\n\t}\n\t/* subtract column thickness from this row's set difference */\n\tset_difference -= col_thickness ;\n\tCOLAMD_ASSERT (set_difference >= 0) ;\n\t/* absorb this row if the set difference becomes zero */\n\tif (set_difference == 0)\n\t{\n\t  COLAMD_DEBUG3 ((\"aggressive absorption. Row: %d\\n\", row)) ;\n\t  Row[row].kill() ;\n\t}\n\telse\n\t{\n\t  /* save the new mark */\n\t  Row [row].shared2.mark = set_difference + tag_mark ;\n\t}\n      }\n    }\n\n\n    /* === Add up set differences for each column ======================= */\n\n    COLAMD_DEBUG3 ((\"** Adding set differences phase. **\\n\")) ;\n\n    /* for each column in pivot row */\n    rp = &A [pivot_row_start] ;\n    rp_end = rp + pivot_row_length ;\n    while (rp < rp_end)\n    {\n      /* get a column */\n      col = *rp++ ;\n      COLAMD_ASSERT (Col[col].is_alive() && col != pivot_col) ;\n      hash = 0 ;\n      cur_score = 0 ;\n      cp = &A [Col [col].start] ;\n      /* compact the column */\n      new_cp = cp ;\n      cp_end = cp + Col [col].length ;\n\n      COLAMD_DEBUG4 ((\"Adding set diffs for Col: %d.\\n\", col)) ;\n\n      while (cp < cp_end)\n      {\n\t/* get a row */\n\trow = *cp++ ;\n\tCOLAMD_ASSERT(row >= 0 && row < n_row) ;\n\t/* skip if dead */\n\tif (Row [row].is_dead())\n\t{\n\t  continue ;\n\t}\n  row_mark = Row [row].shared2.mark ;\n\tCOLAMD_ASSERT (row_mark > tag_mark) ;\n\t/* compact the column */\n\t*new_cp++ = row ;\n\t/* compute hash function */\n\thash += row ;\n\t/* add set difference */\n\tcur_score += row_mark - tag_mark ;\n\t/* integer overflow... */\n\tcur_score = numext::mini(cur_score, n_col) ;\n      }\n\n      /* recompute the column's length */\n      Col [col].length = (IndexType) (new_cp - &A [Col [col].start]) ;\n\n      /* === Further mass elimination ================================= */\n\n      if (Col [col].length == 0)\n      {\n\tCOLAMD_DEBUG4 ((\"further mass elimination. Col: %d\\n\", col)) ;\n\t/* nothing left but the pivot row in this column */\n\tCol[col].kill_principal() ;\n\tpivot_row_degree -= Col [col].shared1.thickness ;\n\tCOLAMD_ASSERT (pivot_row_degree >= 0) ;\n\t/* order it */\n\tCol [col].shared2.order = k ;\n\t/* increment order count by column thickness */\n\tk += Col [col].shared1.thickness ;\n      }\n      else\n      {\n\t/* === Prepare for supercolumn detection ==================== */\n\n\tCOLAMD_DEBUG4 ((\"Preparing supercol detection for Col: %d.\\n\", col)) ;\n\n\t/* save score so far */\n\tCol [col].shared2.score = cur_score ;\n\n\t/* add column to hash table, for supercolumn detection */\n\thash %= n_col + 1 ;\n\n\tCOLAMD_DEBUG4 ((\" Hash = %d, n_col = %d.\\n\", hash, n_col)) ;\n\tCOLAMD_ASSERT (hash <= n_col) ;\n\n\thead_column = head [hash] ;\n\tif (head_column > Empty)\n\t{\n\t  /* degree list \"hash\" is non-empty, use prev (shared3) of */\n\t  /* first column in degree list as head of hash bucket */\n\t  first_col = Col [head_column].shared3.headhash ;\n\t  Col [head_column].shared3.headhash = col ;\n\t}\n\telse\n\t{\n\t  /* degree list \"hash\" is empty, use head as hash bucket */\n\t  first_col = - (head_column + 2) ;\n\t  head [hash] = - (col + 2) ;\n\t}\n\tCol [col].shared4.hash_next = first_col ;\n\n\t/* save hash function in Col [col].shared3.hash */\n\tCol [col].shared3.hash = (IndexType) hash ;\n\tCOLAMD_ASSERT (Col[col].is_alive()) ;\n      }\n    }\n\n    /* The approximate external column degree is now computed.  */\n\n    /* === Supercolumn detection ======================================== */\n\n    COLAMD_DEBUG3 ((\"** Supercolumn detection phase. **\\n\")) ;\n\n    Colamd::detect_super_cols (Col, A, head, pivot_row_start, pivot_row_length) ;\n\n    /* === Kill the pivotal column ====================================== */\n\n    Col[pivot_col].kill_principal() ;\n\n    /* === Clear mark =================================================== */\n\n    tag_mark += (max_deg + 1) ;\n    if (tag_mark >= max_mark)\n    {\n      COLAMD_DEBUG2 ((\"clearing tag_mark\\n\")) ;\n      tag_mark = Colamd::clear_mark (n_row, Row) ;\n    }\n\n    /* === Finalize the new pivot row, and column scores ================ */\n\n    COLAMD_DEBUG3 ((\"** Finalize scores phase. **\\n\")) ;\n\n    /* for each column in pivot row */\n    rp = &A [pivot_row_start] ;\n    /* compact the pivot row */\n    new_rp = rp ;\n    rp_end = rp + pivot_row_length ;\n    while (rp < rp_end)\n    {\n      col = *rp++ ;\n      /* skip dead columns */\n      if (Col[col].is_dead())\n      {\n\tcontinue ;\n      }\n      *new_rp++ = col ;\n      /* add new pivot row to column */\n      A [Col [col].start + (Col [col].length++)] = pivot_row ;\n\n      /* retrieve score so far and add on pivot row's degree. */\n      /* (we wait until here for this in case the pivot */\n      /* row's degree was reduced due to mass elimination). */\n      cur_score = Col [col].shared2.score + pivot_row_degree ;\n\n      /* calculate the max possible score as the number of */\n      /* external columns minus the 'k' value minus the */\n      /* columns thickness */\n      max_score = n_col - k - Col [col].shared1.thickness ;\n\n      /* make the score the external degree of the union-of-rows */\n      cur_score -= Col [col].shared1.thickness ;\n\n      /* make sure score is less or equal than the max score */\n      cur_score = numext::mini(cur_score, max_score) ;\n      COLAMD_ASSERT (cur_score >= 0) ;\n\n      /* store updated score */\n      Col [col].shared2.score = cur_score ;\n\n      /* === Place column back in degree list ========================= */\n\n      COLAMD_ASSERT (min_score >= 0) ;\n      COLAMD_ASSERT (min_score <= n_col) ;\n      COLAMD_ASSERT (cur_score >= 0) ;\n      COLAMD_ASSERT (cur_score <= n_col) ;\n      COLAMD_ASSERT (head [cur_score] >= Empty) ;\n      next_col = head [cur_score] ;\n      Col [col].shared4.degree_next = next_col ;\n      Col [col].shared3.prev = Empty ;\n      if (next_col != Empty)\n      {\n\tCol [next_col].shared3.prev = col ;\n      }\n      head [cur_score] = col ;\n\n      /* see if this score is less than current min */\n      min_score = numext::mini(min_score, cur_score) ;\n\n    }\n\n    /* === Resurrect the new pivot row ================================== */\n\n    if (pivot_row_degree > 0)\n    {\n      /* update pivot row length to reflect any cols that were killed */\n      /* during super-col detection and mass elimination */\n      Row [pivot_row].start  = pivot_row_start ;\n      Row [pivot_row].length = (IndexType) (new_rp - &A[pivot_row_start]) ;\n      Row [pivot_row].shared1.degree = pivot_row_degree ;\n      Row [pivot_row].shared2.mark = 0 ;\n      /* pivot row is no longer dead */\n    }\n  }\n\n  /* === All principal columns have now been ordered ====================== */\n\n  return (ngarbage) ;\n}\n\n\n/* ========================================================================== */\n/* === order_children ======================================================= */\n/* ========================================================================== */\n\n/*\n  The find_ordering routine has ordered all of the principal columns (the\n  representatives of the supercolumns).  The non-principal columns have not\n  yet been ordered.  This routine orders those columns by walking up the\n  parent tree (a column is a child of the column which absorbed it).  The\n  final permutation vector is then placed in p [0 ... n_col-1], with p [0]\n  being the first column, and p [n_col-1] being the last.  It doesn't look\n  like it at first glance, but be assured that this routine takes time linear\n  in the number of columns.  Although not immediately obvious, the time\n  taken by this routine is O (n_col), that is, linear in the number of\n  columns.  Not user-callable.\n*/\ntemplate <typename IndexType>\nstatic inline  void order_children\n(\n  /* === Parameters ======================================================= */\n\n  IndexType n_col,      /* number of columns of A */\n  ColStructure<IndexType> Col [],    /* of size n_col+1 */\n  IndexType p []      /* p [0 ... n_col-1] is the column permutation*/\n  )\n{\n  /* === Local variables ================================================== */\n\n  IndexType i ;     /* loop counter for all columns */\n  IndexType c ;     /* column index */\n  IndexType parent ;    /* index of column's parent */\n  IndexType order ;     /* column's order */\n\n  /* === Order each non-principal column ================================== */\n\n  for (i = 0 ; i < n_col ; i++)\n  {\n    /* find an un-ordered non-principal column */\n    COLAMD_ASSERT (col_is_dead(Col, i)) ;\n    if (!Col[i].is_dead_principal() && Col [i].shared2.order == Empty)\n    {\n      parent = i ;\n      /* once found, find its principal parent */\n      do\n      {\n\tparent = Col [parent].shared1.parent ;\n      } while (!Col[parent].is_dead_principal()) ;\n\n      /* now, order all un-ordered non-principal columns along path */\n      /* to this parent.  collapse tree at the same time */\n      c = i ;\n      /* get order of parent */\n      order = Col [parent].shared2.order ;\n\n      do\n      {\n\tCOLAMD_ASSERT (Col [c].shared2.order == Empty) ;\n\n\t/* order this column */\n\tCol [c].shared2.order = order++ ;\n\t/* collaps tree */\n\tCol [c].shared1.parent = parent ;\n\n\t/* get immediate parent of this column */\n\tc = Col [c].shared1.parent ;\n\n\t/* continue until we hit an ordered column.  There are */\n\t/* guaranteed not to be anymore unordered columns */\n\t/* above an ordered column */\n      } while (Col [c].shared2.order == Empty) ;\n\n      /* re-order the super_col parent to largest order for this group */\n      Col [parent].shared2.order = order ;\n    }\n  }\n\n  /* === Generate the permutation ========================================= */\n\n  for (c = 0 ; c < n_col ; c++)\n  {\n    p [Col [c].shared2.order] = c ;\n  }\n}\n\n\n/* ========================================================================== */\n/* === detect_super_cols ==================================================== */\n/* ========================================================================== */\n\n/*\n  Detects supercolumns by finding matches between columns in the hash buckets.\n  Check amongst columns in the set A [row_start ... row_start + row_length-1].\n  The columns under consideration are currently *not* in the degree lists,\n  and have already been placed in the hash buckets.\n\n  The hash bucket for columns whose hash function is equal to h is stored\n  as follows:\n\n  if head [h] is >= 0, then head [h] contains a degree list, so:\n\n  head [h] is the first column in degree bucket h.\n  Col [head [h]].headhash gives the first column in hash bucket h.\n\n  otherwise, the degree list is empty, and:\n\n  -(head [h] + 2) is the first column in hash bucket h.\n\n  For a column c in a hash bucket, Col [c].shared3.prev is NOT a \"previous\n  column\" pointer.  Col [c].shared3.hash is used instead as the hash number\n  for that column.  The value of Col [c].shared4.hash_next is the next column\n  in the same hash bucket.\n\n  Assuming no, or \"few\" hash collisions, the time taken by this routine is\n  linear in the sum of the sizes (lengths) of each column whose score has\n  just been computed in the approximate degree computation.\n  Not user-callable.\n*/\ntemplate <typename IndexType>\nstatic void detect_super_cols\n(\n  /* === Parameters ======================================================= */\n\n  ColStructure<IndexType> Col [],    /* of size n_col+1 */\n  IndexType A [],     /* row indices of A */\n  IndexType head [],    /* head of degree lists and hash buckets */\n  IndexType row_start,    /* pointer to set of columns to check */\n  IndexType row_length    /* number of columns to check */\n)\n{\n  /* === Local variables ================================================== */\n\n  IndexType hash ;      /* hash value for a column */\n  IndexType *rp ;     /* pointer to a row */\n  IndexType c ;     /* a column index */\n  IndexType super_c ;   /* column index of the column to absorb into */\n  IndexType *cp1 ;      /* column pointer for column super_c */\n  IndexType *cp2 ;      /* column pointer for column c */\n  IndexType length ;    /* length of column super_c */\n  IndexType prev_c ;    /* column preceding c in hash bucket */\n  IndexType i ;     /* loop counter */\n  IndexType *rp_end ;   /* pointer to the end of the row */\n  IndexType col ;     /* a column index in the row to check */\n  IndexType head_column ;   /* first column in hash bucket or degree list */\n  IndexType first_col ;   /* first column in hash bucket */\n\n  /* === Consider each column in the row ================================== */\n\n  rp = &A [row_start] ;\n  rp_end = rp + row_length ;\n  while (rp < rp_end)\n  {\n    col = *rp++ ;\n    if (Col[col].is_dead())\n    {\n      continue ;\n    }\n\n    /* get hash number for this column */\n    hash = Col [col].shared3.hash ;\n    COLAMD_ASSERT (hash <= n_col) ;\n\n    /* === Get the first column in this hash bucket ===================== */\n\n    head_column = head [hash] ;\n    if (head_column > Empty)\n    {\n      first_col = Col [head_column].shared3.headhash ;\n    }\n    else\n    {\n      first_col = - (head_column + 2) ;\n    }\n\n    /* === Consider each column in the hash bucket ====================== */\n\n    for (super_c = first_col ; super_c != Empty ;\n\t super_c = Col [super_c].shared4.hash_next)\n    {\n      COLAMD_ASSERT (Col [super_c].is_alive()) ;\n      COLAMD_ASSERT (Col [super_c].shared3.hash == hash) ;\n      length = Col [super_c].length ;\n\n      /* prev_c is the column preceding column c in the hash bucket */\n      prev_c = super_c ;\n\n      /* === Compare super_c with all columns after it ================ */\n\n      for (c = Col [super_c].shared4.hash_next ;\n\t   c != Empty ; c = Col [c].shared4.hash_next)\n      {\n\tCOLAMD_ASSERT (c != super_c) ;\n\tCOLAMD_ASSERT (Col[c].is_alive()) ;\n\tCOLAMD_ASSERT (Col [c].shared3.hash == hash) ;\n\n\t/* not identical if lengths or scores are different */\n\tif (Col [c].length != length ||\n\t    Col [c].shared2.score != Col [super_c].shared2.score)\n\t{\n\t  prev_c = c ;\n\t  continue ;\n\t}\n\n\t/* compare the two columns */\n\tcp1 = &A [Col [super_c].start] ;\n\tcp2 = &A [Col [c].start] ;\n\n\tfor (i = 0 ; i < length ; i++)\n\t{\n\t  /* the columns are \"clean\" (no dead rows) */\n\t  COLAMD_ASSERT ( cp1->is_alive() );\n\t  COLAMD_ASSERT ( cp2->is_alive() );\n\t  /* row indices will same order for both supercols, */\n\t  /* no gather scatter necessary */\n\t  if (*cp1++ != *cp2++)\n\t  {\n\t    break ;\n\t  }\n\t}\n\n\t/* the two columns are different if the for-loop \"broke\" */\n\tif (i != length)\n\t{\n\t  prev_c = c ;\n\t  continue ;\n\t}\n\n\t/* === Got it!  two columns are identical =================== */\n\n\tCOLAMD_ASSERT (Col [c].shared2.score == Col [super_c].shared2.score) ;\n\n\tCol [super_c].shared1.thickness += Col [c].shared1.thickness ;\n\tCol [c].shared1.parent = super_c ;\n\tCol[c].kill_non_principal() ;\n\t/* order c later, in order_children() */\n\tCol [c].shared2.order = Empty ;\n\t/* remove c from hash bucket */\n\tCol [prev_c].shared4.hash_next = Col [c].shared4.hash_next ;\n      }\n    }\n\n    /* === Empty this hash bucket ======================================= */\n\n    if (head_column > Empty)\n    {\n      /* corresponding degree list \"hash\" is not empty */\n      Col [head_column].shared3.headhash = Empty ;\n    }\n    else\n    {\n      /* corresponding degree list \"hash\" is empty */\n      head [hash] = Empty ;\n    }\n  }\n}\n\n\n/* ========================================================================== */\n/* === garbage_collection =================================================== */\n/* ========================================================================== */\n\n/*\n  Defragments and compacts columns and rows in the workspace A.  Used when\n  all available memory has been used while performing row merging.  Returns\n  the index of the first free position in A, after garbage collection.  The\n  time taken by this routine is linear is the size of the array A, which is\n  itself linear in the number of nonzeros in the input matrix.\n  Not user-callable.\n*/\ntemplate <typename IndexType>\nstatic IndexType garbage_collection  /* returns the new value of pfree */\n  (\n    /* === Parameters ======================================================= */\n\n    IndexType n_row,      /* number of rows */\n    IndexType n_col,      /* number of columns */\n    RowStructure<IndexType> Row [],    /* row info */\n    ColStructure<IndexType> Col [],    /* column info */\n    IndexType A [],     /* A [0 ... Alen-1] holds the matrix */\n    IndexType *pfree      /* &A [0] ... pfree is in use */\n    )\n{\n  /* === Local variables ================================================== */\n\n  IndexType *psrc ;     /* source pointer */\n  IndexType *pdest ;    /* destination pointer */\n  IndexType j ;     /* counter */\n  IndexType r ;     /* a row index */\n  IndexType c ;     /* a column index */\n  IndexType length ;    /* length of a row or column */\n\n  /* === Defragment the columns =========================================== */\n\n  pdest = &A[0] ;\n  for (c = 0 ; c < n_col ; c++)\n  {\n    if (Col[c].is_alive())\n    {\n      psrc = &A [Col [c].start] ;\n\n      /* move and compact the column */\n      COLAMD_ASSERT (pdest <= psrc) ;\n      Col [c].start = (IndexType) (pdest - &A [0]) ;\n      length = Col [c].length ;\n      for (j = 0 ; j < length ; j++)\n      {\n\tr = *psrc++ ;\n\tif (Row[r].is_alive())\n\t{\n\t  *pdest++ = r ;\n\t}\n      }\n      Col [c].length = (IndexType) (pdest - &A [Col [c].start]) ;\n    }\n  }\n\n  /* === Prepare to defragment the rows =================================== */\n\n  for (r = 0 ; r < n_row ; r++)\n  {\n    if (Row[r].is_alive())\n    {\n      if (Row [r].length == 0)\n      {\n        /* this row is of zero length.  cannot compact it, so kill it */\n        COLAMD_DEBUG3 ((\"Defrag row kill\\n\")) ;\n        Row[r].kill() ;\n      }\n      else\n      {\n        /* save first column index in Row [r].shared2.first_column */\n        psrc = &A [Row [r].start] ;\n        Row [r].shared2.first_column = *psrc ;\n        COLAMD_ASSERT (Row[r].is_alive()) ;\n        /* flag the start of the row with the one's complement of row */\n        *psrc = ones_complement(r) ;\n\n      }\n    }\n  }\n\n  /* === Defragment the rows ============================================== */\n\n  psrc = pdest ;\n  while (psrc < pfree)\n  {\n    /* find a negative number ... the start of a row */\n    if (*psrc++ < 0)\n    {\n      psrc-- ;\n      /* get the row index */\n      r = ones_complement(*psrc) ;\n      COLAMD_ASSERT (r >= 0 && r < n_row) ;\n      /* restore first column index */\n      *psrc = Row [r].shared2.first_column ;\n      COLAMD_ASSERT (Row[r].is_alive()) ;\n\n      /* move and compact the row */\n      COLAMD_ASSERT (pdest <= psrc) ;\n      Row [r].start = (IndexType) (pdest - &A [0]) ;\n      length = Row [r].length ;\n      for (j = 0 ; j < length ; j++)\n      {\n\tc = *psrc++ ;\n\tif (Col[c].is_alive())\n\t{\n\t  *pdest++ = c ;\n\t}\n      }\n      Row [r].length = (IndexType) (pdest - &A [Row [r].start]) ;\n\n    }\n  }\n  /* ensure we found all the rows */\n  COLAMD_ASSERT (debug_rows == 0) ;\n\n  /* === Return the new value of pfree ==================================== */\n\n  return ((IndexType) (pdest - &A [0])) ;\n}\n\n\n/* ========================================================================== */\n/* === clear_mark =========================================================== */\n/* ========================================================================== */\n\n/*\n  Clears the Row [].shared2.mark array, and returns the new tag_mark.\n  Return value is the new tag_mark.  Not user-callable.\n*/\ntemplate <typename IndexType>\nstatic inline  IndexType clear_mark  /* return the new value for tag_mark */\n  (\n      /* === Parameters ======================================================= */\n\n    IndexType n_row,    /* number of rows in A */\n    RowStructure<IndexType> Row [] /* Row [0 ... n_row-1].shared2.mark is set to zero */\n    )\n{\n  /* === Local variables ================================================== */\n\n  IndexType r ;\n\n  for (r = 0 ; r < n_row ; r++)\n  {\n    if (Row[r].is_alive())\n    {\n      Row [r].shared2.mark = 0 ;\n    }\n  }\n  return (1) ;\n}\n\n} // namespace Colamd\n\n} // namespace internal\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/OrderingMethods/Ordering.h",
    "content": " \n// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012  Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ORDERING_H\n#define EIGEN_ORDERING_H\n\nnamespace Eigen {\n  \n#include \"Eigen_Colamd.h\"\n\nnamespace internal {\n    \n/** \\internal\n  * \\ingroup OrderingMethods_Module\n  * \\param[in] A the input non-symmetric matrix\n  * \\param[out] symmat the symmetric pattern A^T+A from the input matrix \\a A.\n  * FIXME: The values should not be considered here\n  */\ntemplate<typename MatrixType> \nvoid ordering_helper_at_plus_a(const MatrixType& A, MatrixType& symmat)\n{\n  MatrixType C;\n  C = A.transpose(); // NOTE: Could be  costly\n  for (int i = 0; i < C.rows(); i++) \n  {\n      for (typename MatrixType::InnerIterator it(C, i); it; ++it)\n        it.valueRef() = typename MatrixType::Scalar(0);\n  }\n  symmat = C + A;\n}\n    \n}\n\n/** \\ingroup OrderingMethods_Module\n  * \\class AMDOrdering\n  *\n  * Functor computing the \\em approximate \\em minimum \\em degree ordering\n  * If the matrix is not structurally symmetric, an ordering of A^T+A is computed\n  * \\tparam  StorageIndex The type of indices of the matrix \n  * \\sa COLAMDOrdering\n  */\ntemplate <typename StorageIndex>\nclass AMDOrdering\n{\n  public:\n    typedef PermutationMatrix<Dynamic, Dynamic, StorageIndex> PermutationType;\n    \n    /** Compute the permutation vector from a sparse matrix\n     * This routine is much faster if the input matrix is column-major     \n     */\n    template <typename MatrixType>\n    void operator()(const MatrixType& mat, PermutationType& perm)\n    {\n      // Compute the symmetric pattern\n      SparseMatrix<typename MatrixType::Scalar, ColMajor, StorageIndex> symm;\n      internal::ordering_helper_at_plus_a(mat,symm); \n    \n      // Call the AMD routine \n      //m_mat.prune(keep_diag());\n      internal::minimum_degree_ordering(symm, perm);\n    }\n    \n    /** Compute the permutation with a selfadjoint matrix */\n    template <typename SrcType, unsigned int SrcUpLo> \n    void operator()(const SparseSelfAdjointView<SrcType, SrcUpLo>& mat, PermutationType& perm)\n    { \n      SparseMatrix<typename SrcType::Scalar, ColMajor, StorageIndex> C; C = mat;\n      \n      // Call the AMD routine \n      // m_mat.prune(keep_diag()); //Remove the diagonal elements \n      internal::minimum_degree_ordering(C, perm);\n    }\n};\n\n/** \\ingroup OrderingMethods_Module\n  * \\class NaturalOrdering\n  *\n  * Functor computing the natural ordering (identity)\n  * \n  * \\note Returns an empty permutation matrix\n  * \\tparam  StorageIndex The type of indices of the matrix \n  */\ntemplate <typename StorageIndex>\nclass NaturalOrdering\n{\n  public:\n    typedef PermutationMatrix<Dynamic, Dynamic, StorageIndex> PermutationType;\n    \n    /** Compute the permutation vector from a column-major sparse matrix */\n    template <typename MatrixType>\n    void operator()(const MatrixType& /*mat*/, PermutationType& perm)\n    {\n      perm.resize(0); \n    }\n    \n};\n\n/** \\ingroup OrderingMethods_Module\n  * \\class COLAMDOrdering\n  *\n  * \\tparam  StorageIndex The type of indices of the matrix \n  * \n  * Functor computing the \\em column \\em approximate \\em minimum \\em degree ordering \n  * The matrix should be in column-major and \\b compressed format (see SparseMatrix::makeCompressed()).\n  */\ntemplate<typename StorageIndex>\nclass COLAMDOrdering\n{\n  public:\n    typedef PermutationMatrix<Dynamic, Dynamic, StorageIndex> PermutationType; \n    typedef Matrix<StorageIndex, Dynamic, 1> IndexVector;\n    \n    /** Compute the permutation vector \\a perm form the sparse matrix \\a mat\n      * \\warning The input sparse matrix \\a mat must be in compressed mode (see SparseMatrix::makeCompressed()).\n      */\n    template <typename MatrixType>\n    void operator() (const MatrixType& mat, PermutationType& perm)\n    {\n      eigen_assert(mat.isCompressed() && \"COLAMDOrdering requires a sparse matrix in compressed mode. Call .makeCompressed() before passing it to COLAMDOrdering\");\n      \n      StorageIndex m = StorageIndex(mat.rows());\n      StorageIndex n = StorageIndex(mat.cols());\n      StorageIndex nnz = StorageIndex(mat.nonZeros());\n      // Get the recommended value of Alen to be used by colamd\n      StorageIndex Alen = internal::Colamd::recommended(nnz, m, n); \n      // Set the default parameters\n      double knobs [internal::Colamd::NKnobs]; \n      StorageIndex stats [internal::Colamd::NStats];\n      internal::Colamd::set_defaults(knobs);\n      \n      IndexVector p(n+1), A(Alen); \n      for(StorageIndex i=0; i <= n; i++)   p(i) = mat.outerIndexPtr()[i];\n      for(StorageIndex i=0; i < nnz; i++)  A(i) = mat.innerIndexPtr()[i];\n      // Call Colamd routine to compute the ordering \n      StorageIndex info = internal::Colamd::compute_ordering(m, n, Alen, A.data(), p.data(), knobs, stats); \n      EIGEN_UNUSED_VARIABLE(info);\n      eigen_assert( info && \"COLAMD failed \" );\n      \n      perm.resize(n);\n      for (StorageIndex i = 0; i < n; i++) perm.indices()(p(i)) = i;\n    }\n};\n\n} // end namespace Eigen\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/PaStiXSupport/PaStiXSupport.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_PASTIXSUPPORT_H\n#define EIGEN_PASTIXSUPPORT_H\n\nnamespace Eigen { \n\n#if defined(DCOMPLEX)\n  #define PASTIX_COMPLEX  COMPLEX\n  #define PASTIX_DCOMPLEX DCOMPLEX\n#else\n  #define PASTIX_COMPLEX  std::complex<float>\n  #define PASTIX_DCOMPLEX std::complex<double>\n#endif\n\n/** \\ingroup PaStiXSupport_Module\n  * \\brief Interface to the PaStix solver\n  * \n  * This class is used to solve the linear systems A.X = B via the PaStix library. \n  * The matrix can be either real or complex, symmetric or not.\n  *\n  * \\sa TutorialSparseDirectSolvers\n  */\ntemplate<typename MatrixType_, bool IsStrSym = false> class PastixLU;\ntemplate<typename MatrixType_, int Options> class PastixLLT;\ntemplate<typename MatrixType_, int Options> class PastixLDLT;\n\nnamespace internal\n{\n    \n  template<class Pastix> struct pastix_traits;\n\n  template<typename MatrixType_>\n  struct pastix_traits< PastixLU<MatrixType_> >\n  {\n    typedef MatrixType_ MatrixType;\n    typedef typename MatrixType_::Scalar Scalar;\n    typedef typename MatrixType_::RealScalar RealScalar;\n    typedef typename MatrixType_::StorageIndex StorageIndex;\n  };\n\n  template<typename MatrixType_, int Options>\n  struct pastix_traits< PastixLLT<MatrixType_,Options> >\n  {\n    typedef MatrixType_ MatrixType;\n    typedef typename MatrixType_::Scalar Scalar;\n    typedef typename MatrixType_::RealScalar RealScalar;\n    typedef typename MatrixType_::StorageIndex StorageIndex;\n  };\n\n  template<typename MatrixType_, int Options>\n  struct pastix_traits< PastixLDLT<MatrixType_,Options> >\n  {\n    typedef MatrixType_ MatrixType;\n    typedef typename MatrixType_::Scalar Scalar;\n    typedef typename MatrixType_::RealScalar RealScalar;\n    typedef typename MatrixType_::StorageIndex StorageIndex;\n  };\n  \n  inline void eigen_pastix(pastix_data_t **pastix_data, int pastix_comm, int n, int *ptr, int *idx, float *vals, int *perm, int * invp, float *x, int nbrhs, int *iparm, double *dparm)\n  {\n    if (n == 0) { ptr = NULL; idx = NULL; vals = NULL; }\n    if (nbrhs == 0) {x = NULL; nbrhs=1;}\n    s_pastix(pastix_data, pastix_comm, n, ptr, idx, vals, perm, invp, x, nbrhs, iparm, dparm); \n  }\n  \n  inline void eigen_pastix(pastix_data_t **pastix_data, int pastix_comm, int n, int *ptr, int *idx, double *vals, int *perm, int * invp, double *x, int nbrhs, int *iparm, double *dparm)\n  {\n    if (n == 0) { ptr = NULL; idx = NULL; vals = NULL; }\n    if (nbrhs == 0) {x = NULL; nbrhs=1;}\n    d_pastix(pastix_data, pastix_comm, n, ptr, idx, vals, perm, invp, x, nbrhs, iparm, dparm); \n  }\n  \n  inline void eigen_pastix(pastix_data_t **pastix_data, int pastix_comm, int n, int *ptr, int *idx, std::complex<float> *vals, int *perm, int * invp, std::complex<float> *x, int nbrhs, int *iparm, double *dparm)\n  {\n    if (n == 0) { ptr = NULL; idx = NULL; vals = NULL; }\n    if (nbrhs == 0) {x = NULL; nbrhs=1;}\n    c_pastix(pastix_data, pastix_comm, n, ptr, idx, reinterpret_cast<PASTIX_COMPLEX*>(vals), perm, invp, reinterpret_cast<PASTIX_COMPLEX*>(x), nbrhs, iparm, dparm); \n  }\n  \n  inline void eigen_pastix(pastix_data_t **pastix_data, int pastix_comm, int n, int *ptr, int *idx, std::complex<double> *vals, int *perm, int * invp, std::complex<double> *x, int nbrhs, int *iparm, double *dparm)\n  {\n    if (n == 0) { ptr = NULL; idx = NULL; vals = NULL; }\n    if (nbrhs == 0) {x = NULL; nbrhs=1;}\n    z_pastix(pastix_data, pastix_comm, n, ptr, idx, reinterpret_cast<PASTIX_DCOMPLEX*>(vals), perm, invp, reinterpret_cast<PASTIX_DCOMPLEX*>(x), nbrhs, iparm, dparm); \n  }\n\n  // Convert the matrix  to Fortran-style Numbering\n  template <typename MatrixType>\n  void c_to_fortran_numbering (MatrixType& mat)\n  {\n    if ( !(mat.outerIndexPtr()[0]) ) \n    { \n      int i;\n      for(i = 0; i <= mat.rows(); ++i)\n        ++mat.outerIndexPtr()[i];\n      for(i = 0; i < mat.nonZeros(); ++i)\n        ++mat.innerIndexPtr()[i];\n    }\n  }\n  \n  // Convert to C-style Numbering\n  template <typename MatrixType>\n  void fortran_to_c_numbering (MatrixType& mat)\n  {\n    // Check the Numbering\n    if ( mat.outerIndexPtr()[0] == 1 ) \n    { // Convert to C-style numbering\n      int i;\n      for(i = 0; i <= mat.rows(); ++i)\n        --mat.outerIndexPtr()[i];\n      for(i = 0; i < mat.nonZeros(); ++i)\n        --mat.innerIndexPtr()[i];\n    }\n  }\n}\n\n// This is the base class to interface with PaStiX functions. \n// Users should not used this class directly. \ntemplate <class Derived>\nclass PastixBase : public SparseSolverBase<Derived>\n{\n  protected:\n    typedef SparseSolverBase<Derived> Base;\n    using Base::derived;\n    using Base::m_isInitialized;\n  public:\n    using Base::_solve_impl;\n    \n    typedef typename internal::pastix_traits<Derived>::MatrixType MatrixType_;\n    typedef MatrixType_ MatrixType;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef Matrix<Scalar,Dynamic,1> Vector;\n    typedef SparseMatrix<Scalar, ColMajor> ColSpMatrix;\n    enum {\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n    \n  public:\n    \n    PastixBase() : m_initisOk(false), m_analysisIsOk(false), m_factorizationIsOk(false), m_pastixdata(0), m_size(0)\n    {\n      init();\n    }\n    \n    ~PastixBase() \n    {\n      clean();\n    }\n    \n    template<typename Rhs,typename Dest>\n    bool _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &x) const;\n    \n    /** Returns a reference to the integer vector IPARM of PaStiX parameters\n      * to modify the default parameters. \n      * The statistics related to the different phases of factorization and solve are saved here as well\n      * \\sa analyzePattern() factorize()\n      */\n    Array<StorageIndex,IPARM_SIZE,1>& iparm()\n    {\n      return m_iparm; \n    }\n    \n    /** Return a reference to a particular index parameter of the IPARM vector \n     * \\sa iparm()\n     */\n    \n    int& iparm(int idxparam)\n    {\n      return m_iparm(idxparam);\n    }\n    \n     /** Returns a reference to the double vector DPARM of PaStiX parameters \n      * The statistics related to the different phases of factorization and solve are saved here as well\n      * \\sa analyzePattern() factorize()\n      */\n    Array<double,DPARM_SIZE,1>& dparm()\n    {\n      return m_dparm; \n    }\n    \n    \n    /** Return a reference to a particular index parameter of the DPARM vector \n     * \\sa dparm()\n     */\n    double& dparm(int idxparam)\n    {\n      return m_dparm(idxparam);\n    }\n    \n    inline Index cols() const { return m_size; }\n    inline Index rows() const { return m_size; }\n    \n     /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the PaStiX reports a problem\n      *          \\c InvalidInput if the input matrix is invalid\n      *\n      * \\sa iparm()          \n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_info;\n    }\n    \n  protected:\n\n    // Initialize the Pastix data structure, check the matrix\n    void init(); \n    \n    // Compute the ordering and the symbolic factorization\n    void analyzePattern(ColSpMatrix& mat);\n    \n    // Compute the numerical factorization\n    void factorize(ColSpMatrix& mat);\n    \n    // Free all the data allocated by Pastix\n    void clean()\n    {\n      eigen_assert(m_initisOk && \"The Pastix structure should be allocated first\"); \n      m_iparm(IPARM_START_TASK) = API_TASK_CLEAN;\n      m_iparm(IPARM_END_TASK) = API_TASK_CLEAN;\n      internal::eigen_pastix(&m_pastixdata, MPI_COMM_WORLD, 0, 0, 0, (Scalar*)0,\n                             m_perm.data(), m_invp.data(), 0, 0, m_iparm.data(), m_dparm.data());\n    }\n    \n    void compute(ColSpMatrix& mat);\n    \n    int m_initisOk; \n    int m_analysisIsOk;\n    int m_factorizationIsOk;\n    mutable ComputationInfo m_info; \n    mutable pastix_data_t *m_pastixdata; // Data structure for pastix\n    mutable int m_comm; // The MPI communicator identifier\n    mutable Array<int,IPARM_SIZE,1> m_iparm; // integer vector for the input parameters\n    mutable Array<double,DPARM_SIZE,1> m_dparm; // Scalar vector for the input parameters\n    mutable Matrix<StorageIndex,Dynamic,1> m_perm;  // Permutation vector\n    mutable Matrix<StorageIndex,Dynamic,1> m_invp;  // Inverse permutation vector\n    mutable int m_size; // Size of the matrix \n}; \n\n /** Initialize the PaStiX data structure. \n   *A first call to this function fills iparm and dparm with the default PaStiX parameters\n   * \\sa iparm() dparm()\n   */\ntemplate <class Derived>\nvoid PastixBase<Derived>::init()\n{\n  m_size = 0; \n  m_iparm.setZero(IPARM_SIZE);\n  m_dparm.setZero(DPARM_SIZE);\n  \n  m_iparm(IPARM_MODIFY_PARAMETER) = API_NO;\n  pastix(&m_pastixdata, MPI_COMM_WORLD,\n         0, 0, 0, 0,\n         0, 0, 0, 1, m_iparm.data(), m_dparm.data());\n  \n  m_iparm[IPARM_MATRIX_VERIFICATION] = API_NO;\n  m_iparm[IPARM_VERBOSE]             = API_VERBOSE_NOT;\n  m_iparm[IPARM_ORDERING]            = API_ORDER_SCOTCH;\n  m_iparm[IPARM_INCOMPLETE]          = API_NO;\n  m_iparm[IPARM_OOC_LIMIT]           = 2000;\n  m_iparm[IPARM_RHS_MAKING]          = API_RHS_B;\n  m_iparm(IPARM_MATRIX_VERIFICATION) = API_NO;\n  \n  m_iparm(IPARM_START_TASK) = API_TASK_INIT;\n  m_iparm(IPARM_END_TASK) = API_TASK_INIT;\n  internal::eigen_pastix(&m_pastixdata, MPI_COMM_WORLD, 0, 0, 0, (Scalar*)0,\n                         0, 0, 0, 0, m_iparm.data(), m_dparm.data());\n  \n  // Check the returned error\n  if(m_iparm(IPARM_ERROR_NUMBER)) {\n    m_info = InvalidInput;\n    m_initisOk = false;\n  }\n  else { \n    m_info = Success;\n    m_initisOk = true;\n  }\n}\n\ntemplate <class Derived>\nvoid PastixBase<Derived>::compute(ColSpMatrix& mat)\n{\n  eigen_assert(mat.rows() == mat.cols() && \"The input matrix should be squared\");\n  \n  analyzePattern(mat);  \n  factorize(mat);\n  \n  m_iparm(IPARM_MATRIX_VERIFICATION) = API_NO;\n}\n\n\ntemplate <class Derived>\nvoid PastixBase<Derived>::analyzePattern(ColSpMatrix& mat)\n{                         \n  eigen_assert(m_initisOk && \"The initialization of PaSTiX failed\");\n  \n  // clean previous calls\n  if(m_size>0)\n    clean();\n  \n  m_size = internal::convert_index<int>(mat.rows());\n  m_perm.resize(m_size);\n  m_invp.resize(m_size);\n  \n  m_iparm(IPARM_START_TASK) = API_TASK_ORDERING;\n  m_iparm(IPARM_END_TASK) = API_TASK_ANALYSE;\n  internal::eigen_pastix(&m_pastixdata, MPI_COMM_WORLD, m_size, mat.outerIndexPtr(), mat.innerIndexPtr(),\n               mat.valuePtr(), m_perm.data(), m_invp.data(), 0, 0, m_iparm.data(), m_dparm.data());\n  \n  // Check the returned error\n  if(m_iparm(IPARM_ERROR_NUMBER))\n  {\n    m_info = NumericalIssue;\n    m_analysisIsOk = false;\n  }\n  else\n  { \n    m_info = Success;\n    m_analysisIsOk = true;\n  }\n}\n\ntemplate <class Derived>\nvoid PastixBase<Derived>::factorize(ColSpMatrix& mat)\n{\n//   if(&m_cpyMat != &mat) m_cpyMat = mat;\n  eigen_assert(m_analysisIsOk && \"The analysis phase should be called before the factorization phase\");\n  m_iparm(IPARM_START_TASK) = API_TASK_NUMFACT;\n  m_iparm(IPARM_END_TASK) = API_TASK_NUMFACT;\n  m_size = internal::convert_index<int>(mat.rows());\n  \n  internal::eigen_pastix(&m_pastixdata, MPI_COMM_WORLD, m_size, mat.outerIndexPtr(), mat.innerIndexPtr(),\n               mat.valuePtr(), m_perm.data(), m_invp.data(), 0, 0, m_iparm.data(), m_dparm.data());\n  \n  // Check the returned error\n  if(m_iparm(IPARM_ERROR_NUMBER))\n  {\n    m_info = NumericalIssue;\n    m_factorizationIsOk = false;\n    m_isInitialized = false;\n  }\n  else\n  {\n    m_info = Success;\n    m_factorizationIsOk = true;\n    m_isInitialized = true;\n  }\n}\n\n/* Solve the system */\ntemplate<typename Base>\ntemplate<typename Rhs,typename Dest>\nbool PastixBase<Base>::_solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &x) const\n{\n  eigen_assert(m_isInitialized && \"The matrix should be factorized first\");\n  EIGEN_STATIC_ASSERT((Dest::Flags&RowMajorBit)==0,\n                     THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES);\n  int rhs = 1;\n  \n  x = b; /* on return, x is overwritten by the computed solution */\n  \n  for (int i = 0; i < b.cols(); i++){\n    m_iparm[IPARM_START_TASK]          = API_TASK_SOLVE;\n    m_iparm[IPARM_END_TASK]            = API_TASK_REFINE;\n  \n    internal::eigen_pastix(&m_pastixdata, MPI_COMM_WORLD, internal::convert_index<int>(x.rows()), 0, 0, 0,\n                           m_perm.data(), m_invp.data(), &x(0, i), rhs, m_iparm.data(), m_dparm.data());\n  }\n  \n  // Check the returned error\n  m_info = m_iparm(IPARM_ERROR_NUMBER)==0 ? Success : NumericalIssue;\n  \n  return m_iparm(IPARM_ERROR_NUMBER)==0;\n}\n\n/** \\ingroup PaStiXSupport_Module\n  * \\class PastixLU\n  * \\brief Sparse direct LU solver based on PaStiX library\n  * \n  * This class is used to solve the linear systems A.X = B with a supernodal LU \n  * factorization in the PaStiX library. The matrix A should be squared and nonsingular\n  * PaStiX requires that the matrix A has a symmetric structural pattern. \n  * This interface can symmetrize the input matrix otherwise. \n  * The vectors or matrices X and B can be either dense or sparse.\n  * \n  * \\tparam MatrixType_ the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam IsStrSym Indicates if the input matrix has a symmetric pattern, default is false\n  * NOTE : Note that if the analysis and factorization phase are called separately, \n  * the input matrix will be symmetrized at each call, hence it is advised to \n  * symmetrize the matrix in a end-user program and set \\p IsStrSym to true\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class SparseLU\n  * \n  */\ntemplate<typename MatrixType_, bool IsStrSym>\nclass PastixLU : public PastixBase< PastixLU<MatrixType_> >\n{\n  public:\n    typedef MatrixType_ MatrixType;\n    typedef PastixBase<PastixLU<MatrixType> > Base;\n    typedef typename Base::ColSpMatrix ColSpMatrix;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    \n  public:\n    PastixLU() : Base()\n    {\n      init();\n    }\n    \n    explicit PastixLU(const MatrixType& matrix):Base()\n    {\n      init();\n      compute(matrix);\n    }\n    /** Compute the LU supernodal factorization of \\p matrix. \n      * iparm and dparm can be used to tune the PaStiX parameters. \n      * see the PaStiX user's manual\n      * \\sa analyzePattern() factorize()\n      */\n    void compute (const MatrixType& matrix)\n    {\n      m_structureIsUptodate = false;\n      ColSpMatrix temp;\n      grabMatrix(matrix, temp);\n      Base::compute(temp);\n    }\n    /** Compute the LU symbolic factorization of \\p matrix using its sparsity pattern. \n      * Several ordering methods can be used at this step. See the PaStiX user's manual. \n      * The result of this operation can be used with successive matrices having the same pattern as \\p matrix\n      * \\sa factorize()\n      */\n    void analyzePattern(const MatrixType& matrix)\n    {\n      m_structureIsUptodate = false;\n      ColSpMatrix temp;\n      grabMatrix(matrix, temp);\n      Base::analyzePattern(temp);\n    }\n\n    /** Compute the LU supernodal factorization of \\p matrix\n      * WARNING The matrix \\p matrix should have the same structural pattern \n      * as the same used in the analysis phase.\n      * \\sa analyzePattern()\n      */ \n    void factorize(const MatrixType& matrix)\n    {\n      ColSpMatrix temp;\n      grabMatrix(matrix, temp);\n      Base::factorize(temp);\n    }\n  protected:\n    \n    void init()\n    {\n      m_structureIsUptodate = false;\n      m_iparm(IPARM_SYM) = API_SYM_NO;\n      m_iparm(IPARM_FACTORIZATION) = API_FACT_LU;\n    }\n    \n    void grabMatrix(const MatrixType& matrix, ColSpMatrix& out)\n    {\n      if(IsStrSym)\n        out = matrix;\n      else\n      {\n        if(!m_structureIsUptodate)\n        {\n          // update the transposed structure\n          m_transposedStructure = matrix.transpose();\n          \n          // Set the elements of the matrix to zero \n          for (Index j=0; j<m_transposedStructure.outerSize(); ++j) \n            for(typename ColSpMatrix::InnerIterator it(m_transposedStructure, j); it; ++it)\n              it.valueRef() = 0.0;\n\n          m_structureIsUptodate = true;\n        }\n        \n        out = m_transposedStructure + matrix;\n      }\n      internal::c_to_fortran_numbering(out);\n    }\n    \n    using Base::m_iparm;\n    using Base::m_dparm;\n    \n    ColSpMatrix m_transposedStructure;\n    bool m_structureIsUptodate;\n};\n\n/** \\ingroup PaStiXSupport_Module\n  * \\class PastixLLT\n  * \\brief A sparse direct supernodal Cholesky (LLT) factorization and solver based on the PaStiX library\n  * \n  * This class is used to solve the linear systems A.X = B via a LL^T supernodal Cholesky factorization\n  * available in the PaStiX library. The matrix A should be symmetric and positive definite\n  * WARNING Selfadjoint complex matrices are not supported in the current version of PaStiX\n  * The vectors or matrices X and B can be either dense or sparse\n  * \n  * \\tparam MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam UpLo The part of the matrix to use : Lower or Upper. The default is Lower as required by PaStiX\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class SimplicialLLT\n  */\ntemplate<typename MatrixType_, int UpLo_>\nclass PastixLLT : public PastixBase< PastixLLT<MatrixType_, UpLo_> >\n{\n  public:\n    typedef MatrixType_ MatrixType;\n    typedef PastixBase<PastixLLT<MatrixType, UpLo_> > Base;\n    typedef typename Base::ColSpMatrix ColSpMatrix;\n    \n  public:\n    enum { UpLo = UpLo_ };\n    PastixLLT() : Base()\n    {\n      init();\n    }\n    \n    explicit PastixLLT(const MatrixType& matrix):Base()\n    {\n      init();\n      compute(matrix);\n    }\n\n    /** Compute the L factor of the LL^T supernodal factorization of \\p matrix \n      * \\sa analyzePattern() factorize()\n      */\n    void compute (const MatrixType& matrix)\n    {\n      ColSpMatrix temp;\n      grabMatrix(matrix, temp);\n      Base::compute(temp);\n    }\n\n     /** Compute the LL^T symbolic factorization of \\p matrix using its sparsity pattern\n      * The result of this operation can be used with successive matrices having the same pattern as \\p matrix\n      * \\sa factorize()\n      */\n    void analyzePattern(const MatrixType& matrix)\n    {\n      ColSpMatrix temp;\n      grabMatrix(matrix, temp);\n      Base::analyzePattern(temp);\n    }\n      /** Compute the LL^T supernodal numerical factorization of \\p matrix \n        * \\sa analyzePattern()\n        */\n    void factorize(const MatrixType& matrix)\n    {\n      ColSpMatrix temp;\n      grabMatrix(matrix, temp);\n      Base::factorize(temp);\n    }\n  protected:\n    using Base::m_iparm;\n    \n    void init()\n    {\n      m_iparm(IPARM_SYM) = API_SYM_YES;\n      m_iparm(IPARM_FACTORIZATION) = API_FACT_LLT;\n    }\n    \n    void grabMatrix(const MatrixType& matrix, ColSpMatrix& out)\n    {\n      out.resize(matrix.rows(), matrix.cols());\n      // Pastix supports only lower, column-major matrices \n      out.template selfadjointView<Lower>() = matrix.template selfadjointView<UpLo>();\n      internal::c_to_fortran_numbering(out);\n    }\n};\n\n/** \\ingroup PaStiXSupport_Module\n  * \\class PastixLDLT\n  * \\brief A sparse direct supernodal Cholesky (LLT) factorization and solver based on the PaStiX library\n  * \n  * This class is used to solve the linear systems A.X = B via a LDL^T supernodal Cholesky factorization\n  * available in the PaStiX library. The matrix A should be symmetric and positive definite\n  * WARNING Selfadjoint complex matrices are not supported in the current version of PaStiX\n  * The vectors or matrices X and B can be either dense or sparse\n  * \n  * \\tparam MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam UpLo The part of the matrix to use : Lower or Upper. The default is Lower as required by PaStiX\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class SimplicialLDLT\n  */\ntemplate<typename MatrixType_, int UpLo_>\nclass PastixLDLT : public PastixBase< PastixLDLT<MatrixType_, UpLo_> >\n{\n  public:\n    typedef MatrixType_ MatrixType;\n    typedef PastixBase<PastixLDLT<MatrixType, UpLo_> > Base;\n    typedef typename Base::ColSpMatrix ColSpMatrix;\n    \n  public:\n    enum { UpLo = UpLo_ };\n    PastixLDLT():Base()\n    {\n      init();\n    }\n    \n    explicit PastixLDLT(const MatrixType& matrix):Base()\n    {\n      init();\n      compute(matrix);\n    }\n\n    /** Compute the L and D factors of the LDL^T factorization of \\p matrix \n      * \\sa analyzePattern() factorize()\n      */\n    void compute (const MatrixType& matrix)\n    {\n      ColSpMatrix temp;\n      grabMatrix(matrix, temp);\n      Base::compute(temp);\n    }\n\n    /** Compute the LDL^T symbolic factorization of \\p matrix using its sparsity pattern\n      * The result of this operation can be used with successive matrices having the same pattern as \\p matrix\n      * \\sa factorize()\n      */\n    void analyzePattern(const MatrixType& matrix)\n    { \n      ColSpMatrix temp;\n      grabMatrix(matrix, temp);\n      Base::analyzePattern(temp);\n    }\n    /** Compute the LDL^T supernodal numerical factorization of \\p matrix \n      * \n      */\n    void factorize(const MatrixType& matrix)\n    {\n      ColSpMatrix temp;\n      grabMatrix(matrix, temp);\n      Base::factorize(temp);\n    }\n\n  protected:\n    using Base::m_iparm;\n    \n    void init()\n    {\n      m_iparm(IPARM_SYM) = API_SYM_YES;\n      m_iparm(IPARM_FACTORIZATION) = API_FACT_LDLT;\n    }\n    \n    void grabMatrix(const MatrixType& matrix, ColSpMatrix& out)\n    {\n      // Pastix supports only lower, column-major matrices \n      out.resize(matrix.rows(), matrix.cols());\n      out.template selfadjointView<Lower>() = matrix.template selfadjointView<UpLo>();\n      internal::c_to_fortran_numbering(out);\n    }\n};\n\n} // end namespace Eigen\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/PardisoSupport/PardisoSupport.h",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Eigen bindings to Intel(R) MKL PARDISO\n ********************************************************************************\n*/\n\n#ifndef EIGEN_PARDISOSUPPORT_H\n#define EIGEN_PARDISOSUPPORT_H\n\nnamespace Eigen { \n\ntemplate<typename MatrixType_> class PardisoLU;\ntemplate<typename MatrixType_, int Options=Upper> class PardisoLLT;\ntemplate<typename MatrixType_, int Options=Upper> class PardisoLDLT;\n\nnamespace internal\n{\n  template<typename IndexType>\n  struct pardiso_run_selector\n  {\n    static IndexType run( _MKL_DSS_HANDLE_t pt, IndexType maxfct, IndexType mnum, IndexType type, IndexType phase, IndexType n, void *a,\n                      IndexType *ia, IndexType *ja, IndexType *perm, IndexType nrhs, IndexType *iparm, IndexType msglvl, void *b, void *x)\n    {\n      IndexType error = 0;\n      ::pardiso(pt, &maxfct, &mnum, &type, &phase, &n, a, ia, ja, perm, &nrhs, iparm, &msglvl, b, x, &error);\n      return error;\n    }\n  };\n  template<>\n  struct pardiso_run_selector<long long int>\n  {\n    typedef long long int IndexType;\n    static IndexType run( _MKL_DSS_HANDLE_t pt, IndexType maxfct, IndexType mnum, IndexType type, IndexType phase, IndexType n, void *a,\n                      IndexType *ia, IndexType *ja, IndexType *perm, IndexType nrhs, IndexType *iparm, IndexType msglvl, void *b, void *x)\n    {\n      IndexType error = 0;\n      ::pardiso_64(pt, &maxfct, &mnum, &type, &phase, &n, a, ia, ja, perm, &nrhs, iparm, &msglvl, b, x, &error);\n      return error;\n    }\n  };\n\n  template<class Pardiso> struct pardiso_traits;\n\n  template<typename MatrixType_>\n  struct pardiso_traits< PardisoLU<MatrixType_> >\n  {\n    typedef MatrixType_ MatrixType;\n    typedef typename MatrixType_::Scalar Scalar;\n    typedef typename MatrixType_::RealScalar RealScalar;\n    typedef typename MatrixType_::StorageIndex StorageIndex;\n  };\n\n  template<typename MatrixType_, int Options>\n  struct pardiso_traits< PardisoLLT<MatrixType_, Options> >\n  {\n    typedef MatrixType_ MatrixType;\n    typedef typename MatrixType_::Scalar Scalar;\n    typedef typename MatrixType_::RealScalar RealScalar;\n    typedef typename MatrixType_::StorageIndex StorageIndex;\n  };\n\n  template<typename MatrixType_, int Options>\n  struct pardiso_traits< PardisoLDLT<MatrixType_, Options> >\n  {\n    typedef MatrixType_ MatrixType;\n    typedef typename MatrixType_::Scalar Scalar;\n    typedef typename MatrixType_::RealScalar RealScalar;\n    typedef typename MatrixType_::StorageIndex StorageIndex;\n  };\n\n} // end namespace internal\n\ntemplate<class Derived>\nclass PardisoImpl : public SparseSolverBase<Derived>\n{\n  protected:\n    typedef SparseSolverBase<Derived> Base;\n    using Base::derived;\n    using Base::m_isInitialized;\n    \n    typedef internal::pardiso_traits<Derived> Traits;\n  public:\n    using Base::_solve_impl;\n    \n    typedef typename Traits::MatrixType MatrixType;\n    typedef typename Traits::Scalar Scalar;\n    typedef typename Traits::RealScalar RealScalar;\n    typedef typename Traits::StorageIndex StorageIndex;\n    typedef SparseMatrix<Scalar,RowMajor,StorageIndex> SparseMatrixType;\n    typedef Matrix<Scalar,Dynamic,1> VectorType;\n    typedef Matrix<StorageIndex, 1, MatrixType::ColsAtCompileTime> IntRowVectorType;\n    typedef Matrix<StorageIndex, MatrixType::RowsAtCompileTime, 1> IntColVectorType;\n    typedef Array<StorageIndex,64,1,DontAlign> ParameterType;\n    enum {\n      ScalarIsComplex = NumTraits<Scalar>::IsComplex,\n      ColsAtCompileTime = Dynamic,\n      MaxColsAtCompileTime = Dynamic\n    };\n\n    PardisoImpl()\n      : m_analysisIsOk(false), m_factorizationIsOk(false)\n    {\n      eigen_assert((sizeof(StorageIndex) >= sizeof(_INTEGER_t) && sizeof(StorageIndex) <= 8) && \"Non-supported index type\");\n      m_iparm.setZero();\n      m_msglvl = 0; // No output\n      m_isInitialized = false;\n    }\n\n    ~PardisoImpl()\n    {\n      pardisoRelease();\n    }\n\n    inline Index cols() const { return m_size; }\n    inline Index rows() const { return m_size; }\n  \n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the matrix appears to be negative.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_info;\n    }\n\n    /** \\warning for advanced usage only.\n      * \\returns a reference to the parameter array controlling PARDISO.\n      * See the PARDISO manual to know how to use it. */\n    ParameterType& pardisoParameterArray()\n    {\n      return m_iparm;\n    }\n    \n    /** Performs a symbolic decomposition on the sparcity of \\a matrix.\n      *\n      * This function is particularly useful when solving for several problems having the same structure.\n      * \n      * \\sa factorize()\n      */\n    Derived& analyzePattern(const MatrixType& matrix);\n    \n    /** Performs a numeric decomposition of \\a matrix\n      *\n      * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed.\n      *\n      * \\sa analyzePattern()\n      */\n    Derived& factorize(const MatrixType& matrix);\n\n    Derived& compute(const MatrixType& matrix);\n\n    template<typename Rhs,typename Dest>\n    void _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const;\n\n  protected:\n    void pardisoRelease()\n    {\n      if(m_isInitialized) // Factorization ran at least once\n      {\n        internal::pardiso_run_selector<StorageIndex>::run(m_pt, 1, 1, m_type, -1, internal::convert_index<StorageIndex>(m_size),0, 0, 0, m_perm.data(), 0,\n                                                          m_iparm.data(), m_msglvl, NULL, NULL);\n        m_isInitialized = false;\n      }\n    }\n\n    void pardisoInit(int type)\n    {\n      m_type = type;\n      bool symmetric = std::abs(m_type) < 10;\n      m_iparm[0] = 1;   // No solver default\n      m_iparm[1] = 2;   // use Metis for the ordering\n      m_iparm[2] = 0;   // Reserved. Set to zero. (??Numbers of processors, value of OMP_NUM_THREADS??)\n      m_iparm[3] = 0;   // No iterative-direct algorithm\n      m_iparm[4] = 0;   // No user fill-in reducing permutation\n      m_iparm[5] = 0;   // Write solution into x, b is left unchanged\n      m_iparm[6] = 0;   // Not in use\n      m_iparm[7] = 2;   // Max numbers of iterative refinement steps\n      m_iparm[8] = 0;   // Not in use\n      m_iparm[9] = 13;  // Perturb the pivot elements with 1E-13\n      m_iparm[10] = symmetric ? 0 : 1; // Use nonsymmetric permutation and scaling MPS\n      m_iparm[11] = 0;  // Not in use\n      m_iparm[12] = symmetric ? 0 : 1;  // Maximum weighted matching algorithm is switched-off (default for symmetric).\n                                        // Try m_iparm[12] = 1 in case of inappropriate accuracy\n      m_iparm[13] = 0;  // Output: Number of perturbed pivots\n      m_iparm[14] = 0;  // Not in use\n      m_iparm[15] = 0;  // Not in use\n      m_iparm[16] = 0;  // Not in use\n      m_iparm[17] = -1; // Output: Number of nonzeros in the factor LU\n      m_iparm[18] = -1; // Output: Mflops for LU factorization\n      m_iparm[19] = 0;  // Output: Numbers of CG Iterations\n      \n      m_iparm[20] = 0;  // 1x1 pivoting\n      m_iparm[26] = 0;  // No matrix checker\n      m_iparm[27] = (sizeof(RealScalar) == 4) ? 1 : 0;\n      m_iparm[34] = 1;  // C indexing\n      m_iparm[36] = 0;  // CSR\n      m_iparm[59] = 0;  // 0 - In-Core ; 1 - Automatic switch between In-Core and Out-of-Core modes ; 2 - Out-of-Core\n      \n      memset(m_pt, 0, sizeof(m_pt));\n    }\n\n  protected:\n    // cached data to reduce reallocation, etc.\n    \n    void manageErrorCode(Index error) const\n    {\n      switch(error)\n      {\n        case 0:\n          m_info = Success;\n          break;\n        case -4:\n        case -7:\n          m_info = NumericalIssue;\n          break;\n        default:\n          m_info = InvalidInput;\n      }\n    }\n\n    mutable SparseMatrixType m_matrix;\n    mutable ComputationInfo m_info;\n    bool m_analysisIsOk, m_factorizationIsOk;\n    StorageIndex m_type, m_msglvl;\n    mutable void *m_pt[64];\n    mutable ParameterType m_iparm;\n    mutable IntColVectorType m_perm;\n    Index m_size;\n    \n};\n\ntemplate<class Derived>\nDerived& PardisoImpl<Derived>::compute(const MatrixType& a)\n{\n  m_size = a.rows();\n  eigen_assert(a.rows() == a.cols());\n\n  pardisoRelease();\n  m_perm.setZero(m_size);\n  derived().getMatrix(a);\n  \n  Index error;\n  error = internal::pardiso_run_selector<StorageIndex>::run(m_pt, 1, 1, m_type, 12, internal::convert_index<StorageIndex>(m_size),\n                                                            m_matrix.valuePtr(), m_matrix.outerIndexPtr(), m_matrix.innerIndexPtr(),\n                                                            m_perm.data(), 0, m_iparm.data(), m_msglvl, NULL, NULL);\n  manageErrorCode(error);\n  m_analysisIsOk = true;\n  m_factorizationIsOk = true;\n  m_isInitialized = true;\n  return derived();\n}\n\ntemplate<class Derived>\nDerived& PardisoImpl<Derived>::analyzePattern(const MatrixType& a)\n{\n  m_size = a.rows();\n  eigen_assert(m_size == a.cols());\n\n  pardisoRelease();\n  m_perm.setZero(m_size);\n  derived().getMatrix(a);\n  \n  Index error;\n  error = internal::pardiso_run_selector<StorageIndex>::run(m_pt, 1, 1, m_type, 11, internal::convert_index<StorageIndex>(m_size),\n                                                            m_matrix.valuePtr(), m_matrix.outerIndexPtr(), m_matrix.innerIndexPtr(),\n                                                            m_perm.data(), 0, m_iparm.data(), m_msglvl, NULL, NULL);\n  \n  manageErrorCode(error);\n  m_analysisIsOk = true;\n  m_factorizationIsOk = false;\n  m_isInitialized = true;\n  return derived();\n}\n\ntemplate<class Derived>\nDerived& PardisoImpl<Derived>::factorize(const MatrixType& a)\n{\n  eigen_assert(m_analysisIsOk && \"You must first call analyzePattern()\");\n  eigen_assert(m_size == a.rows() && m_size == a.cols());\n  \n  derived().getMatrix(a);\n\n  Index error;\n  error = internal::pardiso_run_selector<StorageIndex>::run(m_pt, 1, 1, m_type, 22, internal::convert_index<StorageIndex>(m_size),\n                                                            m_matrix.valuePtr(), m_matrix.outerIndexPtr(), m_matrix.innerIndexPtr(),\n                                                            m_perm.data(), 0, m_iparm.data(), m_msglvl, NULL, NULL);\n  \n  manageErrorCode(error);\n  m_factorizationIsOk = true;\n  return derived();\n}\n\ntemplate<class Derived>\ntemplate<typename BDerived,typename XDerived>\nvoid PardisoImpl<Derived>::_solve_impl(const MatrixBase<BDerived> &b, MatrixBase<XDerived>& x) const\n{\n  if(m_iparm[0] == 0) // Factorization was not computed\n  {\n    m_info = InvalidInput;\n    return;\n  }\n\n  //Index n = m_matrix.rows();\n  Index nrhs = Index(b.cols());\n  eigen_assert(m_size==b.rows());\n  eigen_assert(((MatrixBase<BDerived>::Flags & RowMajorBit) == 0 || nrhs == 1) && \"Row-major right hand sides are not supported\");\n  eigen_assert(((MatrixBase<XDerived>::Flags & RowMajorBit) == 0 || nrhs == 1) && \"Row-major matrices of unknowns are not supported\");\n  eigen_assert(((nrhs == 1) || b.outerStride() == b.rows()));\n\n\n//  switch (transposed) {\n//    case SvNoTrans    : m_iparm[11] = 0 ; break;\n//    case SvTranspose  : m_iparm[11] = 2 ; break;\n//    case SvAdjoint    : m_iparm[11] = 1 ; break;\n//    default:\n//      //std::cerr << \"Eigen: transposition  option \\\"\" << transposed << \"\\\" not supported by the PARDISO backend\\n\";\n//      m_iparm[11] = 0;\n//  }\n\n  Scalar* rhs_ptr = const_cast<Scalar*>(b.derived().data());\n  Matrix<Scalar,Dynamic,Dynamic,ColMajor> tmp;\n  \n  // Pardiso cannot solve in-place\n  if(rhs_ptr == x.derived().data())\n  {\n    tmp = b;\n    rhs_ptr = tmp.data();\n  }\n  \n  Index error;\n  error = internal::pardiso_run_selector<StorageIndex>::run(m_pt, 1, 1, m_type, 33, internal::convert_index<StorageIndex>(m_size),\n                                                            m_matrix.valuePtr(), m_matrix.outerIndexPtr(), m_matrix.innerIndexPtr(),\n                                                            m_perm.data(), internal::convert_index<StorageIndex>(nrhs), m_iparm.data(), m_msglvl,\n                                                            rhs_ptr, x.derived().data());\n\n  manageErrorCode(error);\n}\n\n\n/** \\ingroup PardisoSupport_Module\n  * \\class PardisoLU\n  * \\brief A sparse direct LU factorization and solver based on the PARDISO library\n  *\n  * This class allows to solve for A.X = B sparse linear problems via a direct LU factorization\n  * using the Intel MKL PARDISO library. The sparse matrix A must be squared and invertible.\n  * The vectors or matrices X and B can be either dense or sparse.\n  *\n  * By default, it runs in in-core mode. To enable PARDISO's out-of-core feature, set:\n  * \\code solver.pardisoParameterArray()[59] = 1; \\endcode\n  *\n  * \\tparam MatrixType_ the type of the sparse matrix A, it must be a SparseMatrix<>\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class SparseLU\n  */\ntemplate<typename MatrixType>\nclass PardisoLU : public PardisoImpl< PardisoLU<MatrixType> >\n{\n  protected:\n    typedef PardisoImpl<PardisoLU> Base;\n    using Base::pardisoInit;\n    using Base::m_matrix;\n    friend class PardisoImpl< PardisoLU<MatrixType> >;\n\n  public:\n\n    typedef typename Base::Scalar Scalar;\n    typedef typename Base::RealScalar RealScalar;\n\n    using Base::compute;\n    using Base::solve;\n\n    PardisoLU()\n      : Base()\n    {\n      pardisoInit(Base::ScalarIsComplex ? 13 : 11);\n    }\n\n    explicit PardisoLU(const MatrixType& matrix)\n      : Base()\n    {\n      pardisoInit(Base::ScalarIsComplex ? 13 : 11);\n      compute(matrix);\n    }\n  protected:\n    void getMatrix(const MatrixType& matrix)\n    {\n      m_matrix = matrix;\n      m_matrix.makeCompressed();\n    }\n};\n\n/** \\ingroup PardisoSupport_Module\n  * \\class PardisoLLT\n  * \\brief A sparse direct Cholesky (LLT) factorization and solver based on the PARDISO library\n  *\n  * This class allows to solve for A.X = B sparse linear problems via a LL^T Cholesky factorization\n  * using the Intel MKL PARDISO library. The sparse matrix A must be selfajoint and positive definite.\n  * The vectors or matrices X and B can be either dense or sparse.\n  *\n  * By default, it runs in in-core mode. To enable PARDISO's out-of-core feature, set:\n  * \\code solver.pardisoParameterArray()[59] = 1; \\endcode\n  *\n  * \\tparam MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam UpLo can be any bitwise combination of Upper, Lower. The default is Upper, meaning only the upper triangular part has to be used.\n  *         Upper|Lower can be used to tell both triangular parts can be used as input.\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class SimplicialLLT\n  */\ntemplate<typename MatrixType, int UpLo_>\nclass PardisoLLT : public PardisoImpl< PardisoLLT<MatrixType,UpLo_> >\n{\n  protected:\n    typedef PardisoImpl< PardisoLLT<MatrixType,UpLo_> > Base;\n    using Base::pardisoInit;\n    using Base::m_matrix;\n    friend class PardisoImpl< PardisoLLT<MatrixType,UpLo_> >;\n\n  public:\n\n    typedef typename Base::Scalar Scalar;\n    typedef typename Base::RealScalar RealScalar;\n    typedef typename Base::StorageIndex StorageIndex;\n    enum { UpLo = UpLo_ };\n    using Base::compute;\n\n    PardisoLLT()\n      : Base()\n    {\n      pardisoInit(Base::ScalarIsComplex ? 4 : 2);\n    }\n\n    explicit PardisoLLT(const MatrixType& matrix)\n      : Base()\n    {\n      pardisoInit(Base::ScalarIsComplex ? 4 : 2);\n      compute(matrix);\n    }\n    \n  protected:\n    \n    void getMatrix(const MatrixType& matrix)\n    {\n      // PARDISO supports only upper, row-major matrices\n      PermutationMatrix<Dynamic,Dynamic,StorageIndex> p_null;\n      m_matrix.resize(matrix.rows(), matrix.cols());\n      m_matrix.template selfadjointView<Upper>() = matrix.template selfadjointView<UpLo>().twistedBy(p_null);\n      m_matrix.makeCompressed();\n    }\n};\n\n/** \\ingroup PardisoSupport_Module\n  * \\class PardisoLDLT\n  * \\brief A sparse direct Cholesky (LDLT) factorization and solver based on the PARDISO library\n  *\n  * This class allows to solve for A.X = B sparse linear problems via a LDL^T Cholesky factorization\n  * using the Intel MKL PARDISO library. The sparse matrix A is assumed to be selfajoint and positive definite.\n  * For complex matrices, A can also be symmetric only, see the \\a Options template parameter.\n  * The vectors or matrices X and B can be either dense or sparse.\n  *\n  * By default, it runs in in-core mode. To enable PARDISO's out-of-core feature, set:\n  * \\code solver.pardisoParameterArray()[59] = 1; \\endcode\n  *\n  * \\tparam MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam Options can be any bitwise combination of Upper, Lower, and Symmetric. The default is Upper, meaning only the upper triangular part has to be used.\n  *         Symmetric can be used for symmetric, non-selfadjoint complex matrices, the default being to assume a selfadjoint matrix.\n  *         Upper|Lower can be used to tell both triangular parts can be used as input.\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class SimplicialLDLT\n  */\ntemplate<typename MatrixType, int Options>\nclass PardisoLDLT : public PardisoImpl< PardisoLDLT<MatrixType,Options> >\n{\n  protected:\n    typedef PardisoImpl< PardisoLDLT<MatrixType,Options> > Base;\n    using Base::pardisoInit;\n    using Base::m_matrix;\n    friend class PardisoImpl< PardisoLDLT<MatrixType,Options> >;\n\n  public:\n\n    typedef typename Base::Scalar Scalar;\n    typedef typename Base::RealScalar RealScalar;\n    typedef typename Base::StorageIndex StorageIndex;\n    using Base::compute;\n    enum { UpLo = Options&(Upper|Lower) };\n\n    PardisoLDLT()\n      : Base()\n    {\n      pardisoInit(Base::ScalarIsComplex ? ( bool(Options&Symmetric) ? 6 : -4 ) : -2);\n    }\n\n    explicit PardisoLDLT(const MatrixType& matrix)\n      : Base()\n    {\n      pardisoInit(Base::ScalarIsComplex ? ( bool(Options&Symmetric) ? 6 : -4 ) : -2);\n      compute(matrix);\n    }\n    \n    void getMatrix(const MatrixType& matrix)\n    {\n      // PARDISO supports only upper, row-major matrices\n      PermutationMatrix<Dynamic,Dynamic,StorageIndex> p_null;\n      m_matrix.resize(matrix.rows(), matrix.cols());\n      m_matrix.template selfadjointView<Upper>() = matrix.template selfadjointView<UpLo>().twistedBy(p_null);\n      m_matrix.makeCompressed();\n    }\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_PARDISOSUPPORT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/QR/ColPivHouseholderQR.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_COLPIVOTINGHOUSEHOLDERQR_H\n#define EIGEN_COLPIVOTINGHOUSEHOLDERQR_H\n\nnamespace Eigen {\n\nnamespace internal {\ntemplate<typename MatrixType_> struct traits<ColPivHouseholderQR<MatrixType_> >\n : traits<MatrixType_>\n{\n  typedef MatrixXpr XprKind;\n  typedef SolverStorage StorageKind;\n  typedef int StorageIndex;\n  enum { Flags = 0 };\n};\n\n} // end namespace internal\n\n/** \\ingroup QR_Module\n  *\n  * \\class ColPivHouseholderQR\n  *\n  * \\brief Householder rank-revealing QR decomposition of a matrix with column-pivoting\n  *\n  * \\tparam MatrixType_ the type of the matrix of which we are computing the QR decomposition\n  *\n  * This class performs a rank-revealing QR decomposition of a matrix \\b A into matrices \\b P, \\b Q and \\b R\n  * such that\n  * \\f[\n  *  \\mathbf{A} \\, \\mathbf{P} = \\mathbf{Q} \\, \\mathbf{R}\n  * \\f]\n  * by using Householder transformations. Here, \\b P is a permutation matrix, \\b Q a unitary matrix and \\b R an\n  * upper triangular matrix.\n  *\n  * This decomposition performs column pivoting in order to be rank-revealing and improve\n  * numerical stability. It is slower than HouseholderQR, and faster than FullPivHouseholderQR.\n  *\n  * This class supports the \\link InplaceDecomposition inplace decomposition \\endlink mechanism.\n  * \n  * \\sa MatrixBase::colPivHouseholderQr()\n  */\ntemplate<typename MatrixType_> class ColPivHouseholderQR\n        : public SolverBase<ColPivHouseholderQR<MatrixType_> >\n{\n  public:\n\n    typedef MatrixType_ MatrixType;\n    typedef SolverBase<ColPivHouseholderQR> Base;\n    friend class SolverBase<ColPivHouseholderQR>;\n\n    EIGEN_GENERIC_PUBLIC_INTERFACE(ColPivHouseholderQR)\n    enum {\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n    typedef typename internal::plain_diag_type<MatrixType>::type HCoeffsType;\n    typedef PermutationMatrix<ColsAtCompileTime, MaxColsAtCompileTime> PermutationType;\n    typedef typename internal::plain_row_type<MatrixType, Index>::type IntRowVectorType;\n    typedef typename internal::plain_row_type<MatrixType>::type RowVectorType;\n    typedef typename internal::plain_row_type<MatrixType, RealScalar>::type RealRowVectorType;\n    typedef HouseholderSequence<MatrixType,typename internal::remove_all<typename HCoeffsType::ConjugateReturnType>::type> HouseholderSequenceType;\n    typedef typename MatrixType::PlainObject PlainObject;\n\n  private:\n\n    typedef typename PermutationType::StorageIndex PermIndexType;\n\n  public:\n\n    /**\n    * \\brief Default Constructor.\n    *\n    * The default constructor is useful in cases in which the user intends to\n    * perform decompositions via ColPivHouseholderQR::compute(const MatrixType&).\n    */\n    ColPivHouseholderQR()\n      : m_qr(),\n        m_hCoeffs(),\n        m_colsPermutation(),\n        m_colsTranspositions(),\n        m_temp(),\n        m_colNormsUpdated(),\n        m_colNormsDirect(),\n        m_isInitialized(false),\n        m_usePrescribedThreshold(false) {}\n\n    /** \\brief Default Constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem \\a size.\n      * \\sa ColPivHouseholderQR()\n      */\n    ColPivHouseholderQR(Index rows, Index cols)\n      : m_qr(rows, cols),\n        m_hCoeffs((std::min)(rows,cols)),\n        m_colsPermutation(PermIndexType(cols)),\n        m_colsTranspositions(cols),\n        m_temp(cols),\n        m_colNormsUpdated(cols),\n        m_colNormsDirect(cols),\n        m_isInitialized(false),\n        m_usePrescribedThreshold(false) {}\n\n    /** \\brief Constructs a QR factorization from a given matrix\n      *\n      * This constructor computes the QR factorization of the matrix \\a matrix by calling\n      * the method compute(). It is a short cut for:\n      *\n      * \\code\n      * ColPivHouseholderQR<MatrixType> qr(matrix.rows(), matrix.cols());\n      * qr.compute(matrix);\n      * \\endcode\n      *\n      * \\sa compute()\n      */\n    template<typename InputType>\n    explicit ColPivHouseholderQR(const EigenBase<InputType>& matrix)\n      : m_qr(matrix.rows(), matrix.cols()),\n        m_hCoeffs((std::min)(matrix.rows(),matrix.cols())),\n        m_colsPermutation(PermIndexType(matrix.cols())),\n        m_colsTranspositions(matrix.cols()),\n        m_temp(matrix.cols()),\n        m_colNormsUpdated(matrix.cols()),\n        m_colNormsDirect(matrix.cols()),\n        m_isInitialized(false),\n        m_usePrescribedThreshold(false)\n    {\n      compute(matrix.derived());\n    }\n\n    /** \\brief Constructs a QR factorization from a given matrix\n      *\n      * This overloaded constructor is provided for \\link InplaceDecomposition inplace decomposition \\endlink when \\c MatrixType is a Eigen::Ref.\n      *\n      * \\sa ColPivHouseholderQR(const EigenBase&)\n      */\n    template<typename InputType>\n    explicit ColPivHouseholderQR(EigenBase<InputType>& matrix)\n      : m_qr(matrix.derived()),\n        m_hCoeffs((std::min)(matrix.rows(),matrix.cols())),\n        m_colsPermutation(PermIndexType(matrix.cols())),\n        m_colsTranspositions(matrix.cols()),\n        m_temp(matrix.cols()),\n        m_colNormsUpdated(matrix.cols()),\n        m_colNormsDirect(matrix.cols()),\n        m_isInitialized(false),\n        m_usePrescribedThreshold(false)\n    {\n      computeInPlace();\n    }\n\n    #ifdef EIGEN_PARSED_BY_DOXYGEN\n    /** This method finds a solution x to the equation Ax=b, where A is the matrix of which\n      * *this is the QR decomposition, if any exists.\n      *\n      * \\param b the right-hand-side of the equation to solve.\n      *\n      * \\returns a solution.\n      *\n      * \\note_about_checking_solutions\n      *\n      * \\note_about_arbitrary_choice_of_solution\n      *\n      * Example: \\include ColPivHouseholderQR_solve.cpp\n      * Output: \\verbinclude ColPivHouseholderQR_solve.out\n      */\n    template<typename Rhs>\n    inline const Solve<ColPivHouseholderQR, Rhs>\n    solve(const MatrixBase<Rhs>& b) const;\n    #endif\n\n    HouseholderSequenceType householderQ() const;\n    HouseholderSequenceType matrixQ() const\n    {\n      return householderQ();\n    }\n\n    /** \\returns a reference to the matrix where the Householder QR decomposition is stored\n      */\n    const MatrixType& matrixQR() const\n    {\n      eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n      return m_qr;\n    }\n\n    /** \\returns a reference to the matrix where the result Householder QR is stored\n     * \\warning The strict lower part of this matrix contains internal values.\n     * Only the upper triangular part should be referenced. To get it, use\n     * \\code matrixR().template triangularView<Upper>() \\endcode\n     * For rank-deficient matrices, use\n     * \\code\n     * matrixR().topLeftCorner(rank(), rank()).template triangularView<Upper>()\n     * \\endcode\n     */\n    const MatrixType& matrixR() const\n    {\n      eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n      return m_qr;\n    }\n\n    template<typename InputType>\n    ColPivHouseholderQR& compute(const EigenBase<InputType>& matrix);\n\n    /** \\returns a const reference to the column permutation matrix */\n    const PermutationType& colsPermutation() const\n    {\n      eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n      return m_colsPermutation;\n    }\n\n    /** \\returns the absolute value of the determinant of the matrix of which\n      * *this is the QR decomposition. It has only linear complexity\n      * (that is, O(n) where n is the dimension of the square matrix)\n      * as the QR decomposition has already been computed.\n      *\n      * \\note This is only for square matrices.\n      *\n      * \\warning a determinant can be very big or small, so for matrices\n      * of large enough dimension, there is a risk of overflow/underflow.\n      * One way to work around that is to use logAbsDeterminant() instead.\n      *\n      * \\sa logAbsDeterminant(), MatrixBase::determinant()\n      */\n    typename MatrixType::RealScalar absDeterminant() const;\n\n    /** \\returns the natural log of the absolute value of the determinant of the matrix of which\n      * *this is the QR decomposition. It has only linear complexity\n      * (that is, O(n) where n is the dimension of the square matrix)\n      * as the QR decomposition has already been computed.\n      *\n      * \\note This is only for square matrices.\n      *\n      * \\note This method is useful to work around the risk of overflow/underflow that's inherent\n      * to determinant computation.\n      *\n      * \\sa absDeterminant(), MatrixBase::determinant()\n      */\n    typename MatrixType::RealScalar logAbsDeterminant() const;\n\n    /** \\returns the rank of the matrix of which *this is the QR decomposition.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline Index rank() const\n    {\n      using std::abs;\n      eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n      RealScalar premultiplied_threshold = abs(m_maxpivot) * threshold();\n      Index result = 0;\n      for(Index i = 0; i < m_nonzero_pivots; ++i)\n        result += (abs(m_qr.coeff(i,i)) > premultiplied_threshold);\n      return result;\n    }\n\n    /** \\returns the dimension of the kernel of the matrix of which *this is the QR decomposition.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline Index dimensionOfKernel() const\n    {\n      eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n      return cols() - rank();\n    }\n\n    /** \\returns true if the matrix of which *this is the QR decomposition represents an injective\n      *          linear map, i.e. has trivial kernel; false otherwise.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline bool isInjective() const\n    {\n      eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n      return rank() == cols();\n    }\n\n    /** \\returns true if the matrix of which *this is the QR decomposition represents a surjective\n      *          linear map; false otherwise.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline bool isSurjective() const\n    {\n      eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n      return rank() == rows();\n    }\n\n    /** \\returns true if the matrix of which *this is the QR decomposition is invertible.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline bool isInvertible() const\n    {\n      eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n      return isInjective() && isSurjective();\n    }\n\n    /** \\returns the inverse of the matrix of which *this is the QR decomposition.\n      *\n      * \\note If this matrix is not invertible, the returned matrix has undefined coefficients.\n      *       Use isInvertible() to first determine whether this matrix is invertible.\n      */\n    inline const Inverse<ColPivHouseholderQR> inverse() const\n    {\n      eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n      return Inverse<ColPivHouseholderQR>(*this);\n    }\n\n    inline Index rows() const { return m_qr.rows(); }\n    inline Index cols() const { return m_qr.cols(); }\n\n    /** \\returns a const reference to the vector of Householder coefficients used to represent the factor \\c Q.\n      *\n      * For advanced uses only.\n      */\n    const HCoeffsType& hCoeffs() const { return m_hCoeffs; }\n\n    /** Allows to prescribe a threshold to be used by certain methods, such as rank(),\n      * who need to determine when pivots are to be considered nonzero. This is not used for the\n      * QR decomposition itself.\n      *\n      * When it needs to get the threshold value, Eigen calls threshold(). By default, this\n      * uses a formula to automatically determine a reasonable threshold.\n      * Once you have called the present method setThreshold(const RealScalar&),\n      * your value is used instead.\n      *\n      * \\param threshold The new value to use as the threshold.\n      *\n      * A pivot will be considered nonzero if its absolute value is strictly greater than\n      *  \\f$ \\vert pivot \\vert \\leqslant threshold \\times \\vert maxpivot \\vert \\f$\n      * where maxpivot is the biggest pivot.\n      *\n      * If you want to come back to the default behavior, call setThreshold(Default_t)\n      */\n    ColPivHouseholderQR& setThreshold(const RealScalar& threshold)\n    {\n      m_usePrescribedThreshold = true;\n      m_prescribedThreshold = threshold;\n      return *this;\n    }\n\n    /** Allows to come back to the default behavior, letting Eigen use its default formula for\n      * determining the threshold.\n      *\n      * You should pass the special object Eigen::Default as parameter here.\n      * \\code qr.setThreshold(Eigen::Default); \\endcode\n      *\n      * See the documentation of setThreshold(const RealScalar&).\n      */\n    ColPivHouseholderQR& setThreshold(Default_t)\n    {\n      m_usePrescribedThreshold = false;\n      return *this;\n    }\n\n    /** Returns the threshold that will be used by certain methods such as rank().\n      *\n      * See the documentation of setThreshold(const RealScalar&).\n      */\n    RealScalar threshold() const\n    {\n      eigen_assert(m_isInitialized || m_usePrescribedThreshold);\n      return m_usePrescribedThreshold ? m_prescribedThreshold\n      // this formula comes from experimenting (see \"LU precision tuning\" thread on the list)\n      // and turns out to be identical to Higham's formula used already in LDLt.\n                                      : NumTraits<Scalar>::epsilon() * RealScalar(m_qr.diagonalSize());\n    }\n\n    /** \\returns the number of nonzero pivots in the QR decomposition.\n      * Here nonzero is meant in the exact sense, not in a fuzzy sense.\n      * So that notion isn't really intrinsically interesting, but it is\n      * still useful when implementing algorithms.\n      *\n      * \\sa rank()\n      */\n    inline Index nonzeroPivots() const\n    {\n      eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n      return m_nonzero_pivots;\n    }\n\n    /** \\returns the absolute value of the biggest pivot, i.e. the biggest\n      *          diagonal coefficient of R.\n      */\n    RealScalar maxPivot() const { return m_maxpivot; }\n\n    /** \\brief Reports whether the QR factorization was successful.\n      *\n      * \\note This function always returns \\c Success. It is provided for compatibility\n      * with other factorization routines.\n      * \\returns \\c Success\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return Success;\n    }\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<typename RhsType, typename DstType>\n    void _solve_impl(const RhsType &rhs, DstType &dst) const;\n\n    template<bool Conjugate, typename RhsType, typename DstType>\n    void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const;\n    #endif\n\n  protected:\n\n    friend class CompleteOrthogonalDecomposition<MatrixType>;\n\n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n    }\n\n    void computeInPlace();\n\n    MatrixType m_qr;\n    HCoeffsType m_hCoeffs;\n    PermutationType m_colsPermutation;\n    IntRowVectorType m_colsTranspositions;\n    RowVectorType m_temp;\n    RealRowVectorType m_colNormsUpdated;\n    RealRowVectorType m_colNormsDirect;\n    bool m_isInitialized, m_usePrescribedThreshold;\n    RealScalar m_prescribedThreshold, m_maxpivot;\n    Index m_nonzero_pivots;\n    Index m_det_pq;\n};\n\ntemplate<typename MatrixType>\ntypename MatrixType::RealScalar ColPivHouseholderQR<MatrixType>::absDeterminant() const\n{\n  using std::abs;\n  eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n  eigen_assert(m_qr.rows() == m_qr.cols() && \"You can't take the determinant of a non-square matrix!\");\n  return abs(m_qr.diagonal().prod());\n}\n\ntemplate<typename MatrixType>\ntypename MatrixType::RealScalar ColPivHouseholderQR<MatrixType>::logAbsDeterminant() const\n{\n  eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n  eigen_assert(m_qr.rows() == m_qr.cols() && \"You can't take the determinant of a non-square matrix!\");\n  return m_qr.diagonal().cwiseAbs().array().log().sum();\n}\n\n/** Performs the QR factorization of the given matrix \\a matrix. The result of\n  * the factorization is stored into \\c *this, and a reference to \\c *this\n  * is returned.\n  *\n  * \\sa class ColPivHouseholderQR, ColPivHouseholderQR(const MatrixType&)\n  */\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nColPivHouseholderQR<MatrixType>& ColPivHouseholderQR<MatrixType>::compute(const EigenBase<InputType>& matrix)\n{\n  m_qr = matrix.derived();\n  computeInPlace();\n  return *this;\n}\n\ntemplate<typename MatrixType>\nvoid ColPivHouseholderQR<MatrixType>::computeInPlace()\n{\n  check_template_parameters();\n\n  // the column permutation is stored as int indices, so just to be sure:\n  eigen_assert(m_qr.cols()<=NumTraits<int>::highest());\n\n  using std::abs;\n\n  Index rows = m_qr.rows();\n  Index cols = m_qr.cols();\n  Index size = m_qr.diagonalSize();\n\n  m_hCoeffs.resize(size);\n\n  m_temp.resize(cols);\n\n  m_colsTranspositions.resize(m_qr.cols());\n  Index number_of_transpositions = 0;\n\n  m_colNormsUpdated.resize(cols);\n  m_colNormsDirect.resize(cols);\n  for (Index k = 0; k < cols; ++k) {\n    // colNormsDirect(k) caches the most recent directly computed norm of\n    // column k.\n    m_colNormsDirect.coeffRef(k) = m_qr.col(k).norm();\n    m_colNormsUpdated.coeffRef(k) = m_colNormsDirect.coeffRef(k);\n  }\n\n  RealScalar threshold_helper =  numext::abs2<RealScalar>(m_colNormsUpdated.maxCoeff() * NumTraits<RealScalar>::epsilon()) / RealScalar(rows);\n  RealScalar norm_downdate_threshold = numext::sqrt(NumTraits<RealScalar>::epsilon());\n\n  m_nonzero_pivots = size; // the generic case is that in which all pivots are nonzero (invertible case)\n  m_maxpivot = RealScalar(0);\n\n  for(Index k = 0; k < size; ++k)\n  {\n    // first, we look up in our table m_colNormsUpdated which column has the biggest norm\n    Index biggest_col_index;\n    RealScalar biggest_col_sq_norm = numext::abs2(m_colNormsUpdated.tail(cols-k).maxCoeff(&biggest_col_index));\n    biggest_col_index += k;\n\n    // Track the number of meaningful pivots but do not stop the decomposition to make\n    // sure that the initial matrix is properly reproduced. See bug 941.\n    if(m_nonzero_pivots==size && biggest_col_sq_norm < threshold_helper * RealScalar(rows-k))\n      m_nonzero_pivots = k;\n\n    // apply the transposition to the columns\n    m_colsTranspositions.coeffRef(k) = biggest_col_index;\n    if(k != biggest_col_index) {\n      m_qr.col(k).swap(m_qr.col(biggest_col_index));\n      std::swap(m_colNormsUpdated.coeffRef(k), m_colNormsUpdated.coeffRef(biggest_col_index));\n      std::swap(m_colNormsDirect.coeffRef(k), m_colNormsDirect.coeffRef(biggest_col_index));\n      ++number_of_transpositions;\n    }\n\n    // generate the householder vector, store it below the diagonal\n    RealScalar beta;\n    m_qr.col(k).tail(rows-k).makeHouseholderInPlace(m_hCoeffs.coeffRef(k), beta);\n\n    // apply the householder transformation to the diagonal coefficient\n    m_qr.coeffRef(k,k) = beta;\n\n    // remember the maximum absolute value of diagonal coefficients\n    if(abs(beta) > m_maxpivot) m_maxpivot = abs(beta);\n\n    // apply the householder transformation\n    m_qr.bottomRightCorner(rows-k, cols-k-1)\n        .applyHouseholderOnTheLeft(m_qr.col(k).tail(rows-k-1), m_hCoeffs.coeffRef(k), &m_temp.coeffRef(k+1));\n\n    // update our table of norms of the columns\n    for (Index j = k + 1; j < cols; ++j) {\n      // The following implements the stable norm downgrade step discussed in\n      // http://www.netlib.org/lapack/lawnspdf/lawn176.pdf\n      // and used in LAPACK routines xGEQPF and xGEQP3.\n      // See lines 278-297 in http://www.netlib.org/lapack/explore-html/dc/df4/sgeqpf_8f_source.html\n      if (m_colNormsUpdated.coeffRef(j) != RealScalar(0)) {\n        RealScalar temp = abs(m_qr.coeffRef(k, j)) / m_colNormsUpdated.coeffRef(j);\n        temp = (RealScalar(1) + temp) * (RealScalar(1) - temp);\n        temp = temp <  RealScalar(0) ? RealScalar(0) : temp;\n        RealScalar temp2 = temp * numext::abs2<RealScalar>(m_colNormsUpdated.coeffRef(j) /\n                                                           m_colNormsDirect.coeffRef(j));\n        if (temp2 <= norm_downdate_threshold) {\n          // The updated norm has become too inaccurate so re-compute the column\n          // norm directly.\n          m_colNormsDirect.coeffRef(j) = m_qr.col(j).tail(rows - k - 1).norm();\n          m_colNormsUpdated.coeffRef(j) = m_colNormsDirect.coeffRef(j);\n        } else {\n          m_colNormsUpdated.coeffRef(j) *= numext::sqrt(temp);\n        }\n      }\n    }\n  }\n\n  m_colsPermutation.setIdentity(PermIndexType(cols));\n  for(PermIndexType k = 0; k < size/*m_nonzero_pivots*/; ++k)\n    m_colsPermutation.applyTranspositionOnTheRight(k, PermIndexType(m_colsTranspositions.coeff(k)));\n\n  m_det_pq = (number_of_transpositions%2) ? -1 : 1;\n  m_isInitialized = true;\n}\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename MatrixType_>\ntemplate<typename RhsType, typename DstType>\nvoid ColPivHouseholderQR<MatrixType_>::_solve_impl(const RhsType &rhs, DstType &dst) const\n{\n  const Index nonzero_pivots = nonzeroPivots();\n\n  if(nonzero_pivots == 0)\n  {\n    dst.setZero();\n    return;\n  }\n\n  typename RhsType::PlainObject c(rhs);\n\n  c.applyOnTheLeft(householderQ().setLength(nonzero_pivots).adjoint() );\n\n  m_qr.topLeftCorner(nonzero_pivots, nonzero_pivots)\n      .template triangularView<Upper>()\n      .solveInPlace(c.topRows(nonzero_pivots));\n\n  for(Index i = 0; i < nonzero_pivots; ++i) dst.row(m_colsPermutation.indices().coeff(i)) = c.row(i);\n  for(Index i = nonzero_pivots; i < cols(); ++i) dst.row(m_colsPermutation.indices().coeff(i)).setZero();\n}\n\ntemplate<typename MatrixType_>\ntemplate<bool Conjugate, typename RhsType, typename DstType>\nvoid ColPivHouseholderQR<MatrixType_>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const\n{\n  const Index nonzero_pivots = nonzeroPivots();\n\n  if(nonzero_pivots == 0)\n  {\n    dst.setZero();\n    return;\n  }\n\n  typename RhsType::PlainObject c(m_colsPermutation.transpose()*rhs);\n\n  m_qr.topLeftCorner(nonzero_pivots, nonzero_pivots)\n        .template triangularView<Upper>()\n        .transpose().template conjugateIf<Conjugate>()\n        .solveInPlace(c.topRows(nonzero_pivots));\n\n  dst.topRows(nonzero_pivots) = c.topRows(nonzero_pivots);\n  dst.bottomRows(rows()-nonzero_pivots).setZero();\n\n  dst.applyOnTheLeft(householderQ().setLength(nonzero_pivots).template conjugateIf<!Conjugate>() );\n}\n#endif\n\nnamespace internal {\n\ntemplate<typename DstXprType, typename MatrixType>\nstruct Assignment<DstXprType, Inverse<ColPivHouseholderQR<MatrixType> >, internal::assign_op<typename DstXprType::Scalar,typename ColPivHouseholderQR<MatrixType>::Scalar>, Dense2Dense>\n{\n  typedef ColPivHouseholderQR<MatrixType> QrType;\n  typedef Inverse<QrType> SrcXprType;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename QrType::Scalar> &)\n  {\n    dst = src.nestedExpression().solve(MatrixType::Identity(src.rows(), src.cols()));\n  }\n};\n\n} // end namespace internal\n\n/** \\returns the matrix Q as a sequence of householder transformations.\n  * You can extract the meaningful part only by using:\n  * \\code qr.householderQ().setLength(qr.nonzeroPivots()) \\endcode*/\ntemplate<typename MatrixType>\ntypename ColPivHouseholderQR<MatrixType>::HouseholderSequenceType ColPivHouseholderQR<MatrixType>\n  ::householderQ() const\n{\n  eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n  return HouseholderSequenceType(m_qr, m_hCoeffs.conjugate());\n}\n\n/** \\return the column-pivoting Householder QR decomposition of \\c *this.\n  *\n  * \\sa class ColPivHouseholderQR\n  */\ntemplate<typename Derived>\nconst ColPivHouseholderQR<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::colPivHouseholderQr() const\n{\n  return ColPivHouseholderQR<PlainObject>(eval());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_COLPIVOTINGHOUSEHOLDERQR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/QR/ColPivHouseholderQR_LAPACKE.h",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Eigen bindings to LAPACKe\n *    Householder QR decomposition of a matrix with column pivoting based on\n *    LAPACKE_?geqp3 function.\n ********************************************************************************\n*/\n\n#ifndef EIGEN_COLPIVOTINGHOUSEHOLDERQR_LAPACKE_H\n#define EIGEN_COLPIVOTINGHOUSEHOLDERQR_LAPACKE_H\n\nnamespace Eigen { \n\n/** \\internal Specialization for the data types supported by LAPACKe */\n\n#define EIGEN_LAPACKE_QR_COLPIV(EIGTYPE, LAPACKE_TYPE, LAPACKE_PREFIX, EIGCOLROW, LAPACKE_COLROW) \\\ntemplate<> template<typename InputType> inline \\\nColPivHouseholderQR<Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW, Dynamic, Dynamic> >& \\\nColPivHouseholderQR<Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW, Dynamic, Dynamic> >::compute( \\\n              const EigenBase<InputType>& matrix) \\\n\\\n{ \\\n  using std::abs; \\\n  typedef Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW, Dynamic, Dynamic> MatrixType; \\\n  typedef MatrixType::RealScalar RealScalar; \\\n  Index rows = matrix.rows();\\\n  Index cols = matrix.cols();\\\n\\\n  m_qr = matrix;\\\n  Index size = m_qr.diagonalSize();\\\n  m_hCoeffs.resize(size);\\\n\\\n  m_colsTranspositions.resize(cols);\\\n  /*Index number_of_transpositions = 0;*/ \\\n\\\n  m_nonzero_pivots = 0; \\\n  m_maxpivot = RealScalar(0);\\\n  m_colsPermutation.resize(cols); \\\n  m_colsPermutation.indices().setZero(); \\\n\\\n  lapack_int lda = internal::convert_index<lapack_int,Index>(m_qr.outerStride()); \\\n  lapack_int matrix_order = LAPACKE_COLROW; \\\n  LAPACKE_##LAPACKE_PREFIX##geqp3( matrix_order, internal::convert_index<lapack_int,Index>(rows), internal::convert_index<lapack_int,Index>(cols), \\\n                              (LAPACKE_TYPE*)m_qr.data(), lda, (lapack_int*)m_colsPermutation.indices().data(), (LAPACKE_TYPE*)m_hCoeffs.data()); \\\n  m_isInitialized = true; \\\n  m_maxpivot=m_qr.diagonal().cwiseAbs().maxCoeff(); \\\n  m_hCoeffs.adjointInPlace(); \\\n  RealScalar premultiplied_threshold = abs(m_maxpivot) * threshold(); \\\n  lapack_int *perm = m_colsPermutation.indices().data(); \\\n  for(Index i=0;i<size;i++) { \\\n    m_nonzero_pivots += (abs(m_qr.coeff(i,i)) > premultiplied_threshold);\\\n  } \\\n  for(Index i=0;i<cols;i++) perm[i]--;\\\n\\\n  /*m_det_pq = (number_of_transpositions%2) ? -1 : 1;  // TODO: It's not needed now; fix upon availability in Eigen */ \\\n\\\n  return *this; \\\n}\n\nEIGEN_LAPACKE_QR_COLPIV(double,   double,        d, ColMajor, LAPACK_COL_MAJOR)\nEIGEN_LAPACKE_QR_COLPIV(float,    float,         s, ColMajor, LAPACK_COL_MAJOR)\nEIGEN_LAPACKE_QR_COLPIV(dcomplex, lapack_complex_double, z, ColMajor, LAPACK_COL_MAJOR)\nEIGEN_LAPACKE_QR_COLPIV(scomplex, lapack_complex_float,  c, ColMajor, LAPACK_COL_MAJOR)\n\nEIGEN_LAPACKE_QR_COLPIV(double,   double,        d, RowMajor, LAPACK_ROW_MAJOR)\nEIGEN_LAPACKE_QR_COLPIV(float,    float,         s, RowMajor, LAPACK_ROW_MAJOR)\nEIGEN_LAPACKE_QR_COLPIV(dcomplex, lapack_complex_double, z, RowMajor, LAPACK_ROW_MAJOR)\nEIGEN_LAPACKE_QR_COLPIV(scomplex, lapack_complex_float,  c, RowMajor, LAPACK_ROW_MAJOR)\n\n} // end namespace Eigen\n\n#endif // EIGEN_COLPIVOTINGHOUSEHOLDERQR_LAPACKE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/QR/CompleteOrthogonalDecomposition.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Rasmus Munk Larsen <rmlarsen@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_COMPLETEORTHOGONALDECOMPOSITION_H\n#define EIGEN_COMPLETEORTHOGONALDECOMPOSITION_H\n\nnamespace Eigen {\n\nnamespace internal {\ntemplate <typename MatrixType_>\nstruct traits<CompleteOrthogonalDecomposition<MatrixType_> >\n    : traits<MatrixType_> {\n  typedef MatrixXpr XprKind;\n  typedef SolverStorage StorageKind;\n  typedef int StorageIndex;\n  enum { Flags = 0 };\n};\n\n}  // end namespace internal\n\n/** \\ingroup QR_Module\n  *\n  * \\class CompleteOrthogonalDecomposition\n  *\n  * \\brief Complete orthogonal decomposition (COD) of a matrix.\n  *\n  * \\param MatrixType the type of the matrix of which we are computing the COD.\n  *\n  * This class performs a rank-revealing complete orthogonal decomposition of a\n  * matrix  \\b A into matrices \\b P, \\b Q, \\b T, and \\b Z such that\n  * \\f[\n  *  \\mathbf{A} \\, \\mathbf{P} = \\mathbf{Q} \\,\n  *                     \\begin{bmatrix} \\mathbf{T} &  \\mathbf{0} \\\\\n  *                                     \\mathbf{0} & \\mathbf{0} \\end{bmatrix} \\, \\mathbf{Z}\n  * \\f]\n  * by using Householder transformations. Here, \\b P is a permutation matrix,\n  * \\b Q and \\b Z are unitary matrices and \\b T an upper triangular matrix of\n  * size rank-by-rank. \\b A may be rank deficient.\n  *\n  * This class supports the \\link InplaceDecomposition inplace decomposition \\endlink mechanism.\n  * \n  * \\sa MatrixBase::completeOrthogonalDecomposition()\n  */\ntemplate <typename MatrixType_> class CompleteOrthogonalDecomposition\n          : public SolverBase<CompleteOrthogonalDecomposition<MatrixType_> >\n{\n public:\n  typedef MatrixType_ MatrixType;\n  typedef SolverBase<CompleteOrthogonalDecomposition> Base;\n\n  template<typename Derived>\n  friend struct internal::solve_assertion;\n\n  EIGEN_GENERIC_PUBLIC_INTERFACE(CompleteOrthogonalDecomposition)\n  enum {\n    MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n    MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n  };\n  typedef typename internal::plain_diag_type<MatrixType>::type HCoeffsType;\n  typedef PermutationMatrix<ColsAtCompileTime, MaxColsAtCompileTime>\n      PermutationType;\n  typedef typename internal::plain_row_type<MatrixType, Index>::type\n      IntRowVectorType;\n  typedef typename internal::plain_row_type<MatrixType>::type RowVectorType;\n  typedef typename internal::plain_row_type<MatrixType, RealScalar>::type\n      RealRowVectorType;\n  typedef HouseholderSequence<\n      MatrixType, typename internal::remove_all<\n                      typename HCoeffsType::ConjugateReturnType>::type>\n      HouseholderSequenceType;\n  typedef typename MatrixType::PlainObject PlainObject;\n\n private:\n  typedef typename PermutationType::Index PermIndexType;\n\n public:\n  /**\n   * \\brief Default Constructor.\n   *\n   * The default constructor is useful in cases in which the user intends to\n   * perform decompositions via\n   * \\c CompleteOrthogonalDecomposition::compute(const* MatrixType&).\n   */\n  CompleteOrthogonalDecomposition() : m_cpqr(), m_zCoeffs(), m_temp() {}\n\n  /** \\brief Default Constructor with memory preallocation\n   *\n   * Like the default constructor but with preallocation of the internal data\n   * according to the specified problem \\a size.\n   * \\sa CompleteOrthogonalDecomposition()\n   */\n  CompleteOrthogonalDecomposition(Index rows, Index cols)\n      : m_cpqr(rows, cols), m_zCoeffs((std::min)(rows, cols)), m_temp(cols) {}\n\n  /** \\brief Constructs a complete orthogonal decomposition from a given\n   * matrix.\n   *\n   * This constructor computes the complete orthogonal decomposition of the\n   * matrix \\a matrix by calling the method compute(). The default\n   * threshold for rank determination will be used. It is a short cut for:\n   *\n   * \\code\n   * CompleteOrthogonalDecomposition<MatrixType> cod(matrix.rows(),\n   *                                                 matrix.cols());\n   * cod.setThreshold(Default);\n   * cod.compute(matrix);\n   * \\endcode\n   *\n   * \\sa compute()\n   */\n  template <typename InputType>\n  explicit CompleteOrthogonalDecomposition(const EigenBase<InputType>& matrix)\n      : m_cpqr(matrix.rows(), matrix.cols()),\n        m_zCoeffs((std::min)(matrix.rows(), matrix.cols())),\n        m_temp(matrix.cols())\n  {\n    compute(matrix.derived());\n  }\n\n  /** \\brief Constructs a complete orthogonal decomposition from a given matrix\n    *\n    * This overloaded constructor is provided for \\link InplaceDecomposition inplace decomposition \\endlink when \\c MatrixType is a Eigen::Ref.\n    *\n    * \\sa CompleteOrthogonalDecomposition(const EigenBase&)\n    */\n  template<typename InputType>\n  explicit CompleteOrthogonalDecomposition(EigenBase<InputType>& matrix)\n    : m_cpqr(matrix.derived()),\n      m_zCoeffs((std::min)(matrix.rows(), matrix.cols())),\n      m_temp(matrix.cols())\n  {\n    computeInPlace();\n  } \n\n  #ifdef EIGEN_PARSED_BY_DOXYGEN\n  /** This method computes the minimum-norm solution X to a least squares\n   * problem \\f[\\mathrm{minimize} \\|A X - B\\|, \\f] where \\b A is the matrix of\n   * which \\c *this is the complete orthogonal decomposition.\n   *\n   * \\param b the right-hand sides of the problem to solve.\n   *\n   * \\returns a solution.\n   *\n   */\n  template <typename Rhs>\n  inline const Solve<CompleteOrthogonalDecomposition, Rhs> solve(\n      const MatrixBase<Rhs>& b) const;\n  #endif\n\n  HouseholderSequenceType householderQ(void) const;\n  HouseholderSequenceType matrixQ(void) const { return m_cpqr.householderQ(); }\n\n  /** \\returns the matrix \\b Z.\n   */\n  MatrixType matrixZ() const {\n    MatrixType Z = MatrixType::Identity(m_cpqr.cols(), m_cpqr.cols());\n    applyZOnTheLeftInPlace<false>(Z);\n    return Z;\n  }\n\n  /** \\returns a reference to the matrix where the complete orthogonal\n   * decomposition is stored\n   */\n  const MatrixType& matrixQTZ() const { return m_cpqr.matrixQR(); }\n\n  /** \\returns a reference to the matrix where the complete orthogonal\n   * decomposition is stored.\n   * \\warning The strict lower part and \\code cols() - rank() \\endcode right\n   * columns of this matrix contains internal values.\n   * Only the upper triangular part should be referenced. To get it, use\n   * \\code matrixT().template triangularView<Upper>() \\endcode\n   * For rank-deficient matrices, use\n   * \\code\n   * matrixR().topLeftCorner(rank(), rank()).template triangularView<Upper>()\n   * \\endcode\n   */\n  const MatrixType& matrixT() const { return m_cpqr.matrixQR(); }\n\n  template <typename InputType>\n  CompleteOrthogonalDecomposition& compute(const EigenBase<InputType>& matrix) {\n    // Compute the column pivoted QR factorization A P = Q R.\n    m_cpqr.compute(matrix);\n    computeInPlace();\n    return *this;\n  }\n\n  /** \\returns a const reference to the column permutation matrix */\n  const PermutationType& colsPermutation() const {\n    return m_cpqr.colsPermutation();\n  }\n\n  /** \\returns the absolute value of the determinant of the matrix of which\n   * *this is the complete orthogonal decomposition. It has only linear\n   * complexity (that is, O(n) where n is the dimension of the square matrix)\n   * as the complete orthogonal decomposition has already been computed.\n   *\n   * \\note This is only for square matrices.\n   *\n   * \\warning a determinant can be very big or small, so for matrices\n   * of large enough dimension, there is a risk of overflow/underflow.\n   * One way to work around that is to use logAbsDeterminant() instead.\n   *\n   * \\sa logAbsDeterminant(), MatrixBase::determinant()\n   */\n  typename MatrixType::RealScalar absDeterminant() const;\n\n  /** \\returns the natural log of the absolute value of the determinant of the\n   * matrix of which *this is the complete orthogonal decomposition. It has\n   * only linear complexity (that is, O(n) where n is the dimension of the\n   * square matrix) as the complete orthogonal decomposition has already been\n   * computed.\n   *\n   * \\note This is only for square matrices.\n   *\n   * \\note This method is useful to work around the risk of overflow/underflow\n   * that's inherent to determinant computation.\n   *\n   * \\sa absDeterminant(), MatrixBase::determinant()\n   */\n  typename MatrixType::RealScalar logAbsDeterminant() const;\n\n  /** \\returns the rank of the matrix of which *this is the complete orthogonal\n   * decomposition.\n   *\n   * \\note This method has to determine which pivots should be considered\n   * nonzero. For that, it uses the threshold value that you can control by\n   * calling setThreshold(const RealScalar&).\n   */\n  inline Index rank() const { return m_cpqr.rank(); }\n\n  /** \\returns the dimension of the kernel of the matrix of which *this is the\n   * complete orthogonal decomposition.\n   *\n   * \\note This method has to determine which pivots should be considered\n   * nonzero. For that, it uses the threshold value that you can control by\n   * calling setThreshold(const RealScalar&).\n   */\n  inline Index dimensionOfKernel() const { return m_cpqr.dimensionOfKernel(); }\n\n  /** \\returns true if the matrix of which *this is the decomposition represents\n   * an injective linear map, i.e. has trivial kernel; false otherwise.\n   *\n   * \\note This method has to determine which pivots should be considered\n   * nonzero. For that, it uses the threshold value that you can control by\n   * calling setThreshold(const RealScalar&).\n   */\n  inline bool isInjective() const { return m_cpqr.isInjective(); }\n\n  /** \\returns true if the matrix of which *this is the decomposition represents\n   * a surjective linear map; false otherwise.\n   *\n   * \\note This method has to determine which pivots should be considered\n   * nonzero. For that, it uses the threshold value that you can control by\n   * calling setThreshold(const RealScalar&).\n   */\n  inline bool isSurjective() const { return m_cpqr.isSurjective(); }\n\n  /** \\returns true if the matrix of which *this is the complete orthogonal\n   * decomposition is invertible.\n   *\n   * \\note This method has to determine which pivots should be considered\n   * nonzero. For that, it uses the threshold value that you can control by\n   * calling setThreshold(const RealScalar&).\n   */\n  inline bool isInvertible() const { return m_cpqr.isInvertible(); }\n\n  /** \\returns the pseudo-inverse of the matrix of which *this is the complete\n   * orthogonal decomposition.\n   * \\warning: Do not compute \\c this->pseudoInverse()*rhs to solve a linear systems.\n   * It is more efficient and numerically stable to call \\c this->solve(rhs).\n   */\n  inline const Inverse<CompleteOrthogonalDecomposition> pseudoInverse() const\n  {\n    eigen_assert(m_cpqr.m_isInitialized && \"CompleteOrthogonalDecomposition is not initialized.\");\n    return Inverse<CompleteOrthogonalDecomposition>(*this);\n  }\n\n  inline Index rows() const { return m_cpqr.rows(); }\n  inline Index cols() const { return m_cpqr.cols(); }\n\n  /** \\returns a const reference to the vector of Householder coefficients used\n   * to represent the factor \\c Q.\n   *\n   * For advanced uses only.\n   */\n  inline const HCoeffsType& hCoeffs() const { return m_cpqr.hCoeffs(); }\n\n  /** \\returns a const reference to the vector of Householder coefficients\n   * used to represent the factor \\c Z.\n   *\n   * For advanced uses only.\n   */\n  const HCoeffsType& zCoeffs() const { return m_zCoeffs; }\n\n  /** Allows to prescribe a threshold to be used by certain methods, such as\n   * rank(), who need to determine when pivots are to be considered nonzero.\n   * Most be called before calling compute().\n   *\n   * When it needs to get the threshold value, Eigen calls threshold(). By\n   * default, this uses a formula to automatically determine a reasonable\n   * threshold. Once you have called the present method\n   * setThreshold(const RealScalar&), your value is used instead.\n   *\n   * \\param threshold The new value to use as the threshold.\n   *\n   * A pivot will be considered nonzero if its absolute value is strictly\n   * greater than\n   *  \\f$ \\vert pivot \\vert \\leqslant threshold \\times \\vert maxpivot \\vert \\f$\n   * where maxpivot is the biggest pivot.\n   *\n   * If you want to come back to the default behavior, call\n   * setThreshold(Default_t)\n   */\n  CompleteOrthogonalDecomposition& setThreshold(const RealScalar& threshold) {\n    m_cpqr.setThreshold(threshold);\n    return *this;\n  }\n\n  /** Allows to come back to the default behavior, letting Eigen use its default\n   * formula for determining the threshold.\n   *\n   * You should pass the special object Eigen::Default as parameter here.\n   * \\code qr.setThreshold(Eigen::Default); \\endcode\n   *\n   * See the documentation of setThreshold(const RealScalar&).\n   */\n  CompleteOrthogonalDecomposition& setThreshold(Default_t) {\n    m_cpqr.setThreshold(Default);\n    return *this;\n  }\n\n  /** Returns the threshold that will be used by certain methods such as rank().\n   *\n   * See the documentation of setThreshold(const RealScalar&).\n   */\n  RealScalar threshold() const { return m_cpqr.threshold(); }\n\n  /** \\returns the number of nonzero pivots in the complete orthogonal\n   * decomposition. Here nonzero is meant in the exact sense, not in a\n   * fuzzy sense. So that notion isn't really intrinsically interesting,\n   * but it is still useful when implementing algorithms.\n   *\n   * \\sa rank()\n   */\n  inline Index nonzeroPivots() const { return m_cpqr.nonzeroPivots(); }\n\n  /** \\returns the absolute value of the biggest pivot, i.e. the biggest\n   *          diagonal coefficient of R.\n   */\n  inline RealScalar maxPivot() const { return m_cpqr.maxPivot(); }\n\n  /** \\brief Reports whether the complete orthogonal decomposition was\n   * successful.\n   *\n   * \\note This function always returns \\c Success. It is provided for\n   * compatibility\n   * with other factorization routines.\n   * \\returns \\c Success\n   */\n  ComputationInfo info() const {\n    eigen_assert(m_cpqr.m_isInitialized && \"Decomposition is not initialized.\");\n    return Success;\n  }\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n  template <typename RhsType, typename DstType>\n  void _solve_impl(const RhsType& rhs, DstType& dst) const;\n\n  template<bool Conjugate, typename RhsType, typename DstType>\n  void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const;\n#endif\n\n protected:\n  static void check_template_parameters() {\n    EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n  }\n\n  template<bool Transpose_, typename Rhs>\n  void _check_solve_assertion(const Rhs& b) const {\n      EIGEN_ONLY_USED_FOR_DEBUG(b);\n      eigen_assert(m_cpqr.m_isInitialized && \"CompleteOrthogonalDecomposition is not initialized.\");\n      eigen_assert((Transpose_?derived().cols():derived().rows())==b.rows() && \"CompleteOrthogonalDecomposition::solve(): invalid number of rows of the right hand side matrix b\");\n  }\n\n  void computeInPlace();\n\n  /** Overwrites \\b rhs with \\f$ \\mathbf{Z} * \\mathbf{rhs} \\f$ or\n   *  \\f$ \\mathbf{\\overline Z} * \\mathbf{rhs} \\f$ if \\c Conjugate \n   *  is set to \\c true.\n   */\n  template <bool Conjugate, typename Rhs>\n  void applyZOnTheLeftInPlace(Rhs& rhs) const;\n\n  /** Overwrites \\b rhs with \\f$ \\mathbf{Z}^* * \\mathbf{rhs} \\f$.\n   */\n  template <typename Rhs>\n  void applyZAdjointOnTheLeftInPlace(Rhs& rhs) const;\n\n  ColPivHouseholderQR<MatrixType> m_cpqr;\n  HCoeffsType m_zCoeffs;\n  RowVectorType m_temp;\n};\n\ntemplate <typename MatrixType>\ntypename MatrixType::RealScalar\nCompleteOrthogonalDecomposition<MatrixType>::absDeterminant() const {\n  return m_cpqr.absDeterminant();\n}\n\ntemplate <typename MatrixType>\ntypename MatrixType::RealScalar\nCompleteOrthogonalDecomposition<MatrixType>::logAbsDeterminant() const {\n  return m_cpqr.logAbsDeterminant();\n}\n\n/** Performs the complete orthogonal decomposition of the given matrix \\a\n * matrix. The result of the factorization is stored into \\c *this, and a\n * reference to \\c *this is returned.\n *\n * \\sa class CompleteOrthogonalDecomposition,\n * CompleteOrthogonalDecomposition(const MatrixType&)\n */\ntemplate <typename MatrixType>\nvoid CompleteOrthogonalDecomposition<MatrixType>::computeInPlace()\n{\n  check_template_parameters();\n\n  // the column permutation is stored as int indices, so just to be sure:\n  eigen_assert(m_cpqr.cols() <= NumTraits<int>::highest());\n\n  const Index rank = m_cpqr.rank();\n  const Index cols = m_cpqr.cols();\n  const Index rows = m_cpqr.rows();\n  m_zCoeffs.resize((std::min)(rows, cols));\n  m_temp.resize(cols);\n\n  if (rank < cols) {\n    // We have reduced the (permuted) matrix to the form\n    //   [R11 R12]\n    //   [ 0  R22]\n    // where R11 is r-by-r (r = rank) upper triangular, R12 is\n    // r-by-(n-r), and R22 is empty or the norm of R22 is negligible.\n    // We now compute the complete orthogonal decomposition by applying\n    // Householder transformations from the right to the upper trapezoidal\n    // matrix X = [R11 R12] to zero out R12 and obtain the factorization\n    // [R11 R12] = [T11 0] * Z, where T11 is r-by-r upper triangular and\n    // Z = Z(0) * Z(1) ... Z(r-1) is an n-by-n orthogonal matrix.\n    // We store the data representing Z in R12 and m_zCoeffs.\n    for (Index k = rank - 1; k >= 0; --k) {\n      if (k != rank - 1) {\n        // Given the API for Householder reflectors, it is more convenient if\n        // we swap the leading parts of columns k and r-1 (zero-based) to form\n        // the matrix X_k = [X(0:k, k), X(0:k, r:n)]\n        m_cpqr.m_qr.col(k).head(k + 1).swap(\n            m_cpqr.m_qr.col(rank - 1).head(k + 1));\n      }\n      // Construct Householder reflector Z(k) to zero out the last row of X_k,\n      // i.e. choose Z(k) such that\n      // [X(k, k), X(k, r:n)] * Z(k) = [beta, 0, .., 0].\n      RealScalar beta;\n      m_cpqr.m_qr.row(k)\n          .tail(cols - rank + 1)\n          .makeHouseholderInPlace(m_zCoeffs(k), beta);\n      m_cpqr.m_qr(k, rank - 1) = beta;\n      if (k > 0) {\n        // Apply Z(k) to the first k rows of X_k\n        m_cpqr.m_qr.topRightCorner(k, cols - rank + 1)\n            .applyHouseholderOnTheRight(\n                m_cpqr.m_qr.row(k).tail(cols - rank).adjoint(), m_zCoeffs(k),\n                &m_temp(0));\n      }\n      if (k != rank - 1) {\n        // Swap X(0:k,k) back to its proper location.\n        m_cpqr.m_qr.col(k).head(k + 1).swap(\n            m_cpqr.m_qr.col(rank - 1).head(k + 1));\n      }\n    }\n  }\n}\n\ntemplate <typename MatrixType>\ntemplate <bool Conjugate, typename Rhs>\nvoid CompleteOrthogonalDecomposition<MatrixType>::applyZOnTheLeftInPlace(\n    Rhs& rhs) const {\n  const Index cols = this->cols();\n  const Index nrhs = rhs.cols();\n  const Index rank = this->rank();\n  Matrix<typename Rhs::Scalar, Dynamic, 1> temp((std::max)(cols, nrhs));\n  for (Index k = rank-1; k >= 0; --k) {\n    if (k != rank - 1) {\n      rhs.row(k).swap(rhs.row(rank - 1));\n    }\n    rhs.middleRows(rank - 1, cols - rank + 1)\n        .applyHouseholderOnTheLeft(\n            matrixQTZ().row(k).tail(cols - rank).transpose().template conjugateIf<!Conjugate>(), zCoeffs().template conjugateIf<Conjugate>()(k),\n            &temp(0));\n    if (k != rank - 1) {\n      rhs.row(k).swap(rhs.row(rank - 1));\n    }\n  }\n}\n\ntemplate <typename MatrixType>\ntemplate <typename Rhs>\nvoid CompleteOrthogonalDecomposition<MatrixType>::applyZAdjointOnTheLeftInPlace(\n    Rhs& rhs) const {\n  const Index cols = this->cols();\n  const Index nrhs = rhs.cols();\n  const Index rank = this->rank();\n  Matrix<typename Rhs::Scalar, Dynamic, 1> temp((std::max)(cols, nrhs));\n  for (Index k = 0; k < rank; ++k) {\n    if (k != rank - 1) {\n      rhs.row(k).swap(rhs.row(rank - 1));\n    }\n    rhs.middleRows(rank - 1, cols - rank + 1)\n        .applyHouseholderOnTheLeft(\n            matrixQTZ().row(k).tail(cols - rank).adjoint(), zCoeffs()(k),\n            &temp(0));\n    if (k != rank - 1) {\n      rhs.row(k).swap(rhs.row(rank - 1));\n    }\n  }\n}\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate <typename MatrixType_>\ntemplate <typename RhsType, typename DstType>\nvoid CompleteOrthogonalDecomposition<MatrixType_>::_solve_impl(\n    const RhsType& rhs, DstType& dst) const {\n  const Index rank = this->rank();\n  if (rank == 0) {\n    dst.setZero();\n    return;\n  }\n\n  // Compute c = Q^* * rhs\n  typename RhsType::PlainObject c(rhs);\n  c.applyOnTheLeft(matrixQ().setLength(rank).adjoint());\n\n  // Solve T z = c(1:rank, :)\n  dst.topRows(rank) = matrixT()\n                          .topLeftCorner(rank, rank)\n                          .template triangularView<Upper>()\n                          .solve(c.topRows(rank));\n\n  const Index cols = this->cols();\n  if (rank < cols) {\n    // Compute y = Z^* * [ z ]\n    //                   [ 0 ]\n    dst.bottomRows(cols - rank).setZero();\n    applyZAdjointOnTheLeftInPlace(dst);\n  }\n\n  // Undo permutation to get x = P^{-1} * y.\n  dst = colsPermutation() * dst;\n}\n\ntemplate<typename MatrixType_>\ntemplate<bool Conjugate, typename RhsType, typename DstType>\nvoid CompleteOrthogonalDecomposition<MatrixType_>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const\n{\n  const Index rank = this->rank();\n\n  if (rank == 0) {\n    dst.setZero();\n    return;\n  }\n\n  typename RhsType::PlainObject c(colsPermutation().transpose()*rhs);\n\n  if (rank < cols()) {\n    applyZOnTheLeftInPlace<!Conjugate>(c);\n  }\n\n  matrixT().topLeftCorner(rank, rank)\n           .template triangularView<Upper>()\n           .transpose().template conjugateIf<Conjugate>()\n           .solveInPlace(c.topRows(rank));\n\n  dst.topRows(rank) = c.topRows(rank);\n  dst.bottomRows(rows()-rank).setZero();\n\n  dst.applyOnTheLeft(householderQ().setLength(rank).template conjugateIf<!Conjugate>() );\n}\n#endif\n\nnamespace internal {\n\ntemplate<typename MatrixType>\nstruct traits<Inverse<CompleteOrthogonalDecomposition<MatrixType> > >\n  : traits<typename Transpose<typename MatrixType::PlainObject>::PlainObject>\n{\n  enum { Flags = 0 };\n};\n\ntemplate<typename DstXprType, typename MatrixType>\nstruct Assignment<DstXprType, Inverse<CompleteOrthogonalDecomposition<MatrixType> >, internal::assign_op<typename DstXprType::Scalar,typename CompleteOrthogonalDecomposition<MatrixType>::Scalar>, Dense2Dense>\n{\n  typedef CompleteOrthogonalDecomposition<MatrixType> CodType;\n  typedef Inverse<CodType> SrcXprType;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename CodType::Scalar> &)\n  {\n    typedef Matrix<typename CodType::Scalar, CodType::RowsAtCompileTime, CodType::RowsAtCompileTime, 0, CodType::MaxRowsAtCompileTime, CodType::MaxRowsAtCompileTime> IdentityMatrixType;\n    dst = src.nestedExpression().solve(IdentityMatrixType::Identity(src.cols(), src.cols()));\n  }\n};\n\n} // end namespace internal\n\n/** \\returns the matrix Q as a sequence of householder transformations */\ntemplate <typename MatrixType>\ntypename CompleteOrthogonalDecomposition<MatrixType>::HouseholderSequenceType\nCompleteOrthogonalDecomposition<MatrixType>::householderQ() const {\n  return m_cpqr.householderQ();\n}\n\n/** \\return the complete orthogonal decomposition of \\c *this.\n  *\n  * \\sa class CompleteOrthogonalDecomposition\n  */\ntemplate <typename Derived>\nconst CompleteOrthogonalDecomposition<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::completeOrthogonalDecomposition() const {\n  return CompleteOrthogonalDecomposition<PlainObject>(eval());\n}\n\n}  // end namespace Eigen\n\n#endif  // EIGEN_COMPLETEORTHOGONALDECOMPOSITION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/QR/FullPivHouseholderQR.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_FULLPIVOTINGHOUSEHOLDERQR_H\n#define EIGEN_FULLPIVOTINGHOUSEHOLDERQR_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate<typename MatrixType_> struct traits<FullPivHouseholderQR<MatrixType_> >\n : traits<MatrixType_>\n{\n  typedef MatrixXpr XprKind;\n  typedef SolverStorage StorageKind;\n  typedef int StorageIndex;\n  enum { Flags = 0 };\n};\n\ntemplate<typename MatrixType> struct FullPivHouseholderQRMatrixQReturnType;\n\ntemplate<typename MatrixType>\nstruct traits<FullPivHouseholderQRMatrixQReturnType<MatrixType> >\n{\n  typedef typename MatrixType::PlainObject ReturnType;\n};\n\n} // end namespace internal\n\n/** \\ingroup QR_Module\n  *\n  * \\class FullPivHouseholderQR\n  *\n  * \\brief Householder rank-revealing QR decomposition of a matrix with full pivoting\n  *\n  * \\tparam MatrixType_ the type of the matrix of which we are computing the QR decomposition\n  *\n  * This class performs a rank-revealing QR decomposition of a matrix \\b A into matrices \\b P, \\b P', \\b Q and \\b R\n  * such that \n  * \\f[\n  *  \\mathbf{P} \\, \\mathbf{A} \\, \\mathbf{P}' = \\mathbf{Q} \\, \\mathbf{R}\n  * \\f]\n  * by using Householder transformations. Here, \\b P and \\b P' are permutation matrices, \\b Q a unitary matrix \n  * and \\b R an upper triangular matrix.\n  *\n  * This decomposition performs a very prudent full pivoting in order to be rank-revealing and achieve optimal\n  * numerical stability. The trade-off is that it is slower than HouseholderQR and ColPivHouseholderQR.\n  *\n  * This class supports the \\link InplaceDecomposition inplace decomposition \\endlink mechanism.\n  * \n  * \\sa MatrixBase::fullPivHouseholderQr()\n  */\ntemplate<typename MatrixType_> class FullPivHouseholderQR\n        : public SolverBase<FullPivHouseholderQR<MatrixType_> >\n{\n  public:\n\n    typedef MatrixType_ MatrixType;\n    typedef SolverBase<FullPivHouseholderQR> Base;\n    friend class SolverBase<FullPivHouseholderQR>;\n\n    EIGEN_GENERIC_PUBLIC_INTERFACE(FullPivHouseholderQR)\n    enum {\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n    typedef internal::FullPivHouseholderQRMatrixQReturnType<MatrixType> MatrixQReturnType;\n    typedef typename internal::plain_diag_type<MatrixType>::type HCoeffsType;\n    typedef Matrix<StorageIndex, 1,\n                   EIGEN_SIZE_MIN_PREFER_DYNAMIC(ColsAtCompileTime,RowsAtCompileTime), RowMajor, 1,\n                   EIGEN_SIZE_MIN_PREFER_FIXED(MaxColsAtCompileTime,MaxRowsAtCompileTime)> IntDiagSizeVectorType;\n    typedef PermutationMatrix<ColsAtCompileTime, MaxColsAtCompileTime> PermutationType;\n    typedef typename internal::plain_row_type<MatrixType>::type RowVectorType;\n    typedef typename internal::plain_col_type<MatrixType>::type ColVectorType;\n    typedef typename MatrixType::PlainObject PlainObject;\n\n    /** \\brief Default Constructor.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via FullPivHouseholderQR::compute(const MatrixType&).\n      */\n    FullPivHouseholderQR()\n      : m_qr(),\n        m_hCoeffs(),\n        m_rows_transpositions(),\n        m_cols_transpositions(),\n        m_cols_permutation(),\n        m_temp(),\n        m_isInitialized(false),\n        m_usePrescribedThreshold(false) {}\n\n    /** \\brief Default Constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem \\a size.\n      * \\sa FullPivHouseholderQR()\n      */\n    FullPivHouseholderQR(Index rows, Index cols)\n      : m_qr(rows, cols),\n        m_hCoeffs((std::min)(rows,cols)),\n        m_rows_transpositions((std::min)(rows,cols)),\n        m_cols_transpositions((std::min)(rows,cols)),\n        m_cols_permutation(cols),\n        m_temp(cols),\n        m_isInitialized(false),\n        m_usePrescribedThreshold(false) {}\n\n    /** \\brief Constructs a QR factorization from a given matrix\n      *\n      * This constructor computes the QR factorization of the matrix \\a matrix by calling\n      * the method compute(). It is a short cut for:\n      * \n      * \\code\n      * FullPivHouseholderQR<MatrixType> qr(matrix.rows(), matrix.cols());\n      * qr.compute(matrix);\n      * \\endcode\n      * \n      * \\sa compute()\n      */\n    template<typename InputType>\n    explicit FullPivHouseholderQR(const EigenBase<InputType>& matrix)\n      : m_qr(matrix.rows(), matrix.cols()),\n        m_hCoeffs((std::min)(matrix.rows(), matrix.cols())),\n        m_rows_transpositions((std::min)(matrix.rows(), matrix.cols())),\n        m_cols_transpositions((std::min)(matrix.rows(), matrix.cols())),\n        m_cols_permutation(matrix.cols()),\n        m_temp(matrix.cols()),\n        m_isInitialized(false),\n        m_usePrescribedThreshold(false)\n    {\n      compute(matrix.derived());\n    }\n\n    /** \\brief Constructs a QR factorization from a given matrix\n      *\n      * This overloaded constructor is provided for \\link InplaceDecomposition inplace decomposition \\endlink when \\c MatrixType is a Eigen::Ref.\n      *\n      * \\sa FullPivHouseholderQR(const EigenBase&)\n      */\n    template<typename InputType>\n    explicit FullPivHouseholderQR(EigenBase<InputType>& matrix)\n      : m_qr(matrix.derived()),\n        m_hCoeffs((std::min)(matrix.rows(), matrix.cols())),\n        m_rows_transpositions((std::min)(matrix.rows(), matrix.cols())),\n        m_cols_transpositions((std::min)(matrix.rows(), matrix.cols())),\n        m_cols_permutation(matrix.cols()),\n        m_temp(matrix.cols()),\n        m_isInitialized(false),\n        m_usePrescribedThreshold(false)\n    {\n      computeInPlace();\n    }\n\n    #ifdef EIGEN_PARSED_BY_DOXYGEN\n    /** This method finds a solution x to the equation Ax=b, where A is the matrix of which\n      * \\c *this is the QR decomposition.\n      *\n      * \\param b the right-hand-side of the equation to solve.\n      *\n      * \\returns the exact or least-square solution if the rank is greater or equal to the number of columns of A,\n      * and an arbitrary solution otherwise.\n      *\n      * \\note_about_checking_solutions\n      *\n      * \\note_about_arbitrary_choice_of_solution\n      *\n      * Example: \\include FullPivHouseholderQR_solve.cpp\n      * Output: \\verbinclude FullPivHouseholderQR_solve.out\n      */\n    template<typename Rhs>\n    inline const Solve<FullPivHouseholderQR, Rhs>\n    solve(const MatrixBase<Rhs>& b) const;\n    #endif\n\n    /** \\returns Expression object representing the matrix Q\n      */\n    MatrixQReturnType matrixQ(void) const;\n\n    /** \\returns a reference to the matrix where the Householder QR decomposition is stored\n      */\n    const MatrixType& matrixQR() const\n    {\n      eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n      return m_qr;\n    }\n\n    template<typename InputType>\n    FullPivHouseholderQR& compute(const EigenBase<InputType>& matrix);\n\n    /** \\returns a const reference to the column permutation matrix */\n    const PermutationType& colsPermutation() const\n    {\n      eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n      return m_cols_permutation;\n    }\n\n    /** \\returns a const reference to the vector of indices representing the rows transpositions */\n    const IntDiagSizeVectorType& rowsTranspositions() const\n    {\n      eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n      return m_rows_transpositions;\n    }\n\n    /** \\returns the absolute value of the determinant of the matrix of which\n      * *this is the QR decomposition. It has only linear complexity\n      * (that is, O(n) where n is the dimension of the square matrix)\n      * as the QR decomposition has already been computed.\n      *\n      * \\note This is only for square matrices.\n      *\n      * \\warning a determinant can be very big or small, so for matrices\n      * of large enough dimension, there is a risk of overflow/underflow.\n      * One way to work around that is to use logAbsDeterminant() instead.\n      *\n      * \\sa logAbsDeterminant(), MatrixBase::determinant()\n      */\n    typename MatrixType::RealScalar absDeterminant() const;\n\n    /** \\returns the natural log of the absolute value of the determinant of the matrix of which\n      * *this is the QR decomposition. It has only linear complexity\n      * (that is, O(n) where n is the dimension of the square matrix)\n      * as the QR decomposition has already been computed.\n      *\n      * \\note This is only for square matrices.\n      *\n      * \\note This method is useful to work around the risk of overflow/underflow that's inherent\n      * to determinant computation.\n      *\n      * \\sa absDeterminant(), MatrixBase::determinant()\n      */\n    typename MatrixType::RealScalar logAbsDeterminant() const;\n\n    /** \\returns the rank of the matrix of which *this is the QR decomposition.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline Index rank() const\n    {\n      using std::abs;\n      eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n      RealScalar premultiplied_threshold = abs(m_maxpivot) * threshold();\n      Index result = 0;\n      for(Index i = 0; i < m_nonzero_pivots; ++i)\n        result += (abs(m_qr.coeff(i,i)) > premultiplied_threshold);\n      return result;\n    }\n\n    /** \\returns the dimension of the kernel of the matrix of which *this is the QR decomposition.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline Index dimensionOfKernel() const\n    {\n      eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n      return cols() - rank();\n    }\n\n    /** \\returns true if the matrix of which *this is the QR decomposition represents an injective\n      *          linear map, i.e. has trivial kernel; false otherwise.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline bool isInjective() const\n    {\n      eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n      return rank() == cols();\n    }\n\n    /** \\returns true if the matrix of which *this is the QR decomposition represents a surjective\n      *          linear map; false otherwise.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline bool isSurjective() const\n    {\n      eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n      return rank() == rows();\n    }\n\n    /** \\returns true if the matrix of which *this is the QR decomposition is invertible.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline bool isInvertible() const\n    {\n      eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n      return isInjective() && isSurjective();\n    }\n\n    /** \\returns the inverse of the matrix of which *this is the QR decomposition.\n      *\n      * \\note If this matrix is not invertible, the returned matrix has undefined coefficients.\n      *       Use isInvertible() to first determine whether this matrix is invertible.\n      */\n    inline const Inverse<FullPivHouseholderQR> inverse() const\n    {\n      eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n      return Inverse<FullPivHouseholderQR>(*this);\n    }\n\n    inline Index rows() const { return m_qr.rows(); }\n    inline Index cols() const { return m_qr.cols(); }\n    \n    /** \\returns a const reference to the vector of Householder coefficients used to represent the factor \\c Q.\n      * \n      * For advanced uses only.\n      */\n    const HCoeffsType& hCoeffs() const { return m_hCoeffs; }\n\n    /** Allows to prescribe a threshold to be used by certain methods, such as rank(),\n      * who need to determine when pivots are to be considered nonzero. This is not used for the\n      * QR decomposition itself.\n      *\n      * When it needs to get the threshold value, Eigen calls threshold(). By default, this\n      * uses a formula to automatically determine a reasonable threshold.\n      * Once you have called the present method setThreshold(const RealScalar&),\n      * your value is used instead.\n      *\n      * \\param threshold The new value to use as the threshold.\n      *\n      * A pivot will be considered nonzero if its absolute value is strictly greater than\n      *  \\f$ \\vert pivot \\vert \\leqslant threshold \\times \\vert maxpivot \\vert \\f$\n      * where maxpivot is the biggest pivot.\n      *\n      * If you want to come back to the default behavior, call setThreshold(Default_t)\n      */\n    FullPivHouseholderQR& setThreshold(const RealScalar& threshold)\n    {\n      m_usePrescribedThreshold = true;\n      m_prescribedThreshold = threshold;\n      return *this;\n    }\n\n    /** Allows to come back to the default behavior, letting Eigen use its default formula for\n      * determining the threshold.\n      *\n      * You should pass the special object Eigen::Default as parameter here.\n      * \\code qr.setThreshold(Eigen::Default); \\endcode\n      *\n      * See the documentation of setThreshold(const RealScalar&).\n      */\n    FullPivHouseholderQR& setThreshold(Default_t)\n    {\n      m_usePrescribedThreshold = false;\n      return *this;\n    }\n\n    /** Returns the threshold that will be used by certain methods such as rank().\n      *\n      * See the documentation of setThreshold(const RealScalar&).\n      */\n    RealScalar threshold() const\n    {\n      eigen_assert(m_isInitialized || m_usePrescribedThreshold);\n      return m_usePrescribedThreshold ? m_prescribedThreshold\n      // this formula comes from experimenting (see \"LU precision tuning\" thread on the list)\n      // and turns out to be identical to Higham's formula used already in LDLt.\n                                      : NumTraits<Scalar>::epsilon() * RealScalar(m_qr.diagonalSize());\n    }\n\n    /** \\returns the number of nonzero pivots in the QR decomposition.\n      * Here nonzero is meant in the exact sense, not in a fuzzy sense.\n      * So that notion isn't really intrinsically interesting, but it is\n      * still useful when implementing algorithms.\n      *\n      * \\sa rank()\n      */\n    inline Index nonzeroPivots() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return m_nonzero_pivots;\n    }\n\n    /** \\returns the absolute value of the biggest pivot, i.e. the biggest\n      *          diagonal coefficient of U.\n      */\n    RealScalar maxPivot() const { return m_maxpivot; }\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<typename RhsType, typename DstType>\n    void _solve_impl(const RhsType &rhs, DstType &dst) const;\n\n    template<bool Conjugate, typename RhsType, typename DstType>\n    void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const;\n    #endif\n\n  protected:\n\n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n    }\n\n    void computeInPlace();\n\n    MatrixType m_qr;\n    HCoeffsType m_hCoeffs;\n    IntDiagSizeVectorType m_rows_transpositions;\n    IntDiagSizeVectorType m_cols_transpositions;\n    PermutationType m_cols_permutation;\n    RowVectorType m_temp;\n    bool m_isInitialized, m_usePrescribedThreshold;\n    RealScalar m_prescribedThreshold, m_maxpivot;\n    Index m_nonzero_pivots;\n    RealScalar m_precision;\n    Index m_det_pq;\n};\n\ntemplate<typename MatrixType>\ntypename MatrixType::RealScalar FullPivHouseholderQR<MatrixType>::absDeterminant() const\n{\n  using std::abs;\n  eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n  eigen_assert(m_qr.rows() == m_qr.cols() && \"You can't take the determinant of a non-square matrix!\");\n  return abs(m_qr.diagonal().prod());\n}\n\ntemplate<typename MatrixType>\ntypename MatrixType::RealScalar FullPivHouseholderQR<MatrixType>::logAbsDeterminant() const\n{\n  eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n  eigen_assert(m_qr.rows() == m_qr.cols() && \"You can't take the determinant of a non-square matrix!\");\n  return m_qr.diagonal().cwiseAbs().array().log().sum();\n}\n\n/** Performs the QR factorization of the given matrix \\a matrix. The result of\n  * the factorization is stored into \\c *this, and a reference to \\c *this\n  * is returned.\n  *\n  * \\sa class FullPivHouseholderQR, FullPivHouseholderQR(const MatrixType&)\n  */\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nFullPivHouseholderQR<MatrixType>& FullPivHouseholderQR<MatrixType>::compute(const EigenBase<InputType>& matrix)\n{\n  m_qr = matrix.derived();\n  computeInPlace();\n  return *this;\n}\n\ntemplate<typename MatrixType>\nvoid FullPivHouseholderQR<MatrixType>::computeInPlace()\n{\n  check_template_parameters();\n\n  using std::abs;\n  Index rows = m_qr.rows();\n  Index cols = m_qr.cols();\n  Index size = (std::min)(rows,cols);\n\n  \n  m_hCoeffs.resize(size);\n\n  m_temp.resize(cols);\n\n  m_precision = NumTraits<Scalar>::epsilon() * RealScalar(size);\n\n  m_rows_transpositions.resize(size);\n  m_cols_transpositions.resize(size);\n  Index number_of_transpositions = 0;\n\n  RealScalar biggest(0);\n\n  m_nonzero_pivots = size; // the generic case is that in which all pivots are nonzero (invertible case)\n  m_maxpivot = RealScalar(0);\n\n  for (Index k = 0; k < size; ++k)\n  {\n    Index row_of_biggest_in_corner, col_of_biggest_in_corner;\n    typedef internal::scalar_score_coeff_op<Scalar> Scoring;\n    typedef typename Scoring::result_type Score;\n\n    Score score = m_qr.bottomRightCorner(rows-k, cols-k)\n                      .unaryExpr(Scoring())\n                      .maxCoeff(&row_of_biggest_in_corner, &col_of_biggest_in_corner);\n    row_of_biggest_in_corner += k;\n    col_of_biggest_in_corner += k;\n    RealScalar biggest_in_corner = internal::abs_knowing_score<Scalar>()(m_qr(row_of_biggest_in_corner, col_of_biggest_in_corner), score);\n    if(k==0) biggest = biggest_in_corner;\n\n    // if the corner is negligible, then we have less than full rank, and we can finish early\n    if(internal::isMuchSmallerThan(biggest_in_corner, biggest, m_precision))\n    {\n      m_nonzero_pivots = k;\n      for(Index i = k; i < size; i++)\n      {\n        m_rows_transpositions.coeffRef(i) = internal::convert_index<StorageIndex>(i);\n        m_cols_transpositions.coeffRef(i) = internal::convert_index<StorageIndex>(i);\n        m_hCoeffs.coeffRef(i) = Scalar(0);\n      }\n      break;\n    }\n\n    m_rows_transpositions.coeffRef(k) = internal::convert_index<StorageIndex>(row_of_biggest_in_corner);\n    m_cols_transpositions.coeffRef(k) = internal::convert_index<StorageIndex>(col_of_biggest_in_corner);\n    if(k != row_of_biggest_in_corner) {\n      m_qr.row(k).tail(cols-k).swap(m_qr.row(row_of_biggest_in_corner).tail(cols-k));\n      ++number_of_transpositions;\n    }\n    if(k != col_of_biggest_in_corner) {\n      m_qr.col(k).swap(m_qr.col(col_of_biggest_in_corner));\n      ++number_of_transpositions;\n    }\n\n    RealScalar beta;\n    m_qr.col(k).tail(rows-k).makeHouseholderInPlace(m_hCoeffs.coeffRef(k), beta);\n    m_qr.coeffRef(k,k) = beta;\n\n    // remember the maximum absolute value of diagonal coefficients\n    if(abs(beta) > m_maxpivot) m_maxpivot = abs(beta);\n\n    m_qr.bottomRightCorner(rows-k, cols-k-1)\n        .applyHouseholderOnTheLeft(m_qr.col(k).tail(rows-k-1), m_hCoeffs.coeffRef(k), &m_temp.coeffRef(k+1));\n  }\n\n  m_cols_permutation.setIdentity(cols);\n  for(Index k = 0; k < size; ++k)\n    m_cols_permutation.applyTranspositionOnTheRight(k, m_cols_transpositions.coeff(k));\n\n  m_det_pq = (number_of_transpositions%2) ? -1 : 1;\n  m_isInitialized = true;\n}\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename MatrixType_>\ntemplate<typename RhsType, typename DstType>\nvoid FullPivHouseholderQR<MatrixType_>::_solve_impl(const RhsType &rhs, DstType &dst) const\n{\n  const Index l_rank = rank();\n\n  // FIXME introduce nonzeroPivots() and use it here. and more generally,\n  // make the same improvements in this dec as in FullPivLU.\n  if(l_rank==0)\n  {\n    dst.setZero();\n    return;\n  }\n\n  typename RhsType::PlainObject c(rhs);\n\n  Matrix<typename RhsType::Scalar,1,RhsType::ColsAtCompileTime> temp(rhs.cols());\n  for (Index k = 0; k < l_rank; ++k)\n  {\n    Index remainingSize = rows()-k;\n    c.row(k).swap(c.row(m_rows_transpositions.coeff(k)));\n    c.bottomRightCorner(remainingSize, rhs.cols())\n      .applyHouseholderOnTheLeft(m_qr.col(k).tail(remainingSize-1),\n                               m_hCoeffs.coeff(k), &temp.coeffRef(0));\n  }\n\n  m_qr.topLeftCorner(l_rank, l_rank)\n      .template triangularView<Upper>()\n      .solveInPlace(c.topRows(l_rank));\n\n  for(Index i = 0; i < l_rank; ++i) dst.row(m_cols_permutation.indices().coeff(i)) = c.row(i);\n  for(Index i = l_rank; i < cols(); ++i) dst.row(m_cols_permutation.indices().coeff(i)).setZero();\n}\n\ntemplate<typename MatrixType_>\ntemplate<bool Conjugate, typename RhsType, typename DstType>\nvoid FullPivHouseholderQR<MatrixType_>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const\n{\n  const Index l_rank = rank();\n\n  if(l_rank == 0)\n  {\n    dst.setZero();\n    return;\n  }\n\n  typename RhsType::PlainObject c(m_cols_permutation.transpose()*rhs);\n\n  m_qr.topLeftCorner(l_rank, l_rank)\n         .template triangularView<Upper>()\n         .transpose().template conjugateIf<Conjugate>()\n         .solveInPlace(c.topRows(l_rank));\n\n  dst.topRows(l_rank) = c.topRows(l_rank);\n  dst.bottomRows(rows()-l_rank).setZero();\n\n  Matrix<Scalar, 1, DstType::ColsAtCompileTime> temp(dst.cols());\n  const Index size = (std::min)(rows(), cols());\n  for (Index k = size-1; k >= 0; --k)\n  {\n    Index remainingSize = rows()-k;\n\n    dst.bottomRightCorner(remainingSize, dst.cols())\n       .applyHouseholderOnTheLeft(m_qr.col(k).tail(remainingSize-1).template conjugateIf<!Conjugate>(),\n                                  m_hCoeffs.template conjugateIf<Conjugate>().coeff(k), &temp.coeffRef(0));\n\n    dst.row(k).swap(dst.row(m_rows_transpositions.coeff(k)));\n  }\n}\n#endif\n\nnamespace internal {\n  \ntemplate<typename DstXprType, typename MatrixType>\nstruct Assignment<DstXprType, Inverse<FullPivHouseholderQR<MatrixType> >, internal::assign_op<typename DstXprType::Scalar,typename FullPivHouseholderQR<MatrixType>::Scalar>, Dense2Dense>\n{\n  typedef FullPivHouseholderQR<MatrixType> QrType;\n  typedef Inverse<QrType> SrcXprType;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename QrType::Scalar> &)\n  {    \n    dst = src.nestedExpression().solve(MatrixType::Identity(src.rows(), src.cols()));\n  }\n};\n\n/** \\ingroup QR_Module\n  *\n  * \\brief Expression type for return value of FullPivHouseholderQR::matrixQ()\n  *\n  * \\tparam MatrixType type of underlying dense matrix\n  */\ntemplate<typename MatrixType> struct FullPivHouseholderQRMatrixQReturnType\n  : public ReturnByValue<FullPivHouseholderQRMatrixQReturnType<MatrixType> >\n{\npublic:\n  typedef typename FullPivHouseholderQR<MatrixType>::IntDiagSizeVectorType IntDiagSizeVectorType;\n  typedef typename internal::plain_diag_type<MatrixType>::type HCoeffsType;\n  typedef Matrix<typename MatrixType::Scalar, 1, MatrixType::RowsAtCompileTime, RowMajor, 1,\n                 MatrixType::MaxRowsAtCompileTime> WorkVectorType;\n\n  FullPivHouseholderQRMatrixQReturnType(const MatrixType&       qr,\n                                        const HCoeffsType&      hCoeffs,\n                                        const IntDiagSizeVectorType& rowsTranspositions)\n    : m_qr(qr),\n      m_hCoeffs(hCoeffs),\n      m_rowsTranspositions(rowsTranspositions)\n  {}\n\n  template <typename ResultType>\n  void evalTo(ResultType& result) const\n  {\n    const Index rows = m_qr.rows();\n    WorkVectorType workspace(rows);\n    evalTo(result, workspace);\n  }\n\n  template <typename ResultType>\n  void evalTo(ResultType& result, WorkVectorType& workspace) const\n  {\n    using numext::conj;\n    // compute the product H'_0 H'_1 ... H'_n-1,\n    // where H_k is the k-th Householder transformation I - h_k v_k v_k'\n    // and v_k is the k-th Householder vector [1,m_qr(k+1,k), m_qr(k+2,k), ...]\n    const Index rows = m_qr.rows();\n    const Index cols = m_qr.cols();\n    const Index size = (std::min)(rows, cols);\n    workspace.resize(rows);\n    result.setIdentity(rows, rows);\n    for (Index k = size-1; k >= 0; k--)\n    {\n      result.block(k, k, rows-k, rows-k)\n            .applyHouseholderOnTheLeft(m_qr.col(k).tail(rows-k-1), conj(m_hCoeffs.coeff(k)), &workspace.coeffRef(k));\n      result.row(k).swap(result.row(m_rowsTranspositions.coeff(k)));\n    }\n  }\n\n  Index rows() const { return m_qr.rows(); }\n  Index cols() const { return m_qr.rows(); }\n\nprotected:\n  typename MatrixType::Nested m_qr;\n  typename HCoeffsType::Nested m_hCoeffs;\n  typename IntDiagSizeVectorType::Nested m_rowsTranspositions;\n};\n\n// template<typename MatrixType>\n// struct evaluator<FullPivHouseholderQRMatrixQReturnType<MatrixType> >\n//  : public evaluator<ReturnByValue<FullPivHouseholderQRMatrixQReturnType<MatrixType> > >\n// {};\n\n} // end namespace internal\n\ntemplate<typename MatrixType>\ninline typename FullPivHouseholderQR<MatrixType>::MatrixQReturnType FullPivHouseholderQR<MatrixType>::matrixQ() const\n{\n  eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n  return MatrixQReturnType(m_qr, m_hCoeffs, m_rows_transpositions);\n}\n\n/** \\return the full-pivoting Householder QR decomposition of \\c *this.\n  *\n  * \\sa class FullPivHouseholderQR\n  */\ntemplate<typename Derived>\nconst FullPivHouseholderQR<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::fullPivHouseholderQr() const\n{\n  return FullPivHouseholderQR<PlainObject>(eval());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_FULLPIVOTINGHOUSEHOLDERQR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/QR/HouseholderQR.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2010 Vincent Lejeune\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_QR_H\n#define EIGEN_QR_H\n\nnamespace Eigen { \n\nnamespace internal {\ntemplate<typename MatrixType_> struct traits<HouseholderQR<MatrixType_> >\n : traits<MatrixType_>\n{\n  typedef MatrixXpr XprKind;\n  typedef SolverStorage StorageKind;\n  typedef int StorageIndex;\n  enum { Flags = 0 };\n};\n\n} // end namespace internal\n\n/** \\ingroup QR_Module\n  *\n  *\n  * \\class HouseholderQR\n  *\n  * \\brief Householder QR decomposition of a matrix\n  *\n  * \\tparam MatrixType_ the type of the matrix of which we are computing the QR decomposition\n  *\n  * This class performs a QR decomposition of a matrix \\b A into matrices \\b Q and \\b R\n  * such that \n  * \\f[\n  *  \\mathbf{A} = \\mathbf{Q} \\, \\mathbf{R}\n  * \\f]\n  * by using Householder transformations. Here, \\b Q a unitary matrix and \\b R an upper triangular matrix.\n  * The result is stored in a compact way compatible with LAPACK.\n  *\n  * Note that no pivoting is performed. This is \\b not a rank-revealing decomposition.\n  * If you want that feature, use FullPivHouseholderQR or ColPivHouseholderQR instead.\n  *\n  * This Householder QR decomposition is faster, but less numerically stable and less feature-full than\n  * FullPivHouseholderQR or ColPivHouseholderQR.\n  *\n  * This class supports the \\link InplaceDecomposition inplace decomposition \\endlink mechanism.\n  *\n  * \\sa MatrixBase::householderQr()\n  */\ntemplate<typename MatrixType_> class HouseholderQR\n        : public SolverBase<HouseholderQR<MatrixType_> >\n{\n  public:\n\n    typedef MatrixType_ MatrixType;\n    typedef SolverBase<HouseholderQR> Base;\n    friend class SolverBase<HouseholderQR>;\n\n    EIGEN_GENERIC_PUBLIC_INTERFACE(HouseholderQR)\n    enum {\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n    typedef Matrix<Scalar, RowsAtCompileTime, RowsAtCompileTime, (MatrixType::Flags&RowMajorBit) ? RowMajor : ColMajor, MaxRowsAtCompileTime, MaxRowsAtCompileTime> MatrixQType;\n    typedef typename internal::plain_diag_type<MatrixType>::type HCoeffsType;\n    typedef typename internal::plain_row_type<MatrixType>::type RowVectorType;\n    typedef HouseholderSequence<MatrixType,typename internal::remove_all<typename HCoeffsType::ConjugateReturnType>::type> HouseholderSequenceType;\n\n    /**\n      * \\brief Default Constructor.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via HouseholderQR::compute(const MatrixType&).\n      */\n    HouseholderQR() : m_qr(), m_hCoeffs(), m_temp(), m_isInitialized(false) {}\n\n    /** \\brief Default Constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem \\a size.\n      * \\sa HouseholderQR()\n      */\n    HouseholderQR(Index rows, Index cols)\n      : m_qr(rows, cols),\n        m_hCoeffs((std::min)(rows,cols)),\n        m_temp(cols),\n        m_isInitialized(false) {}\n\n    /** \\brief Constructs a QR factorization from a given matrix\n      *\n      * This constructor computes the QR factorization of the matrix \\a matrix by calling\n      * the method compute(). It is a short cut for:\n      * \n      * \\code\n      * HouseholderQR<MatrixType> qr(matrix.rows(), matrix.cols());\n      * qr.compute(matrix);\n      * \\endcode\n      * \n      * \\sa compute()\n      */\n    template<typename InputType>\n    explicit HouseholderQR(const EigenBase<InputType>& matrix)\n      : m_qr(matrix.rows(), matrix.cols()),\n        m_hCoeffs((std::min)(matrix.rows(),matrix.cols())),\n        m_temp(matrix.cols()),\n        m_isInitialized(false)\n    {\n      compute(matrix.derived());\n    }\n\n\n    /** \\brief Constructs a QR factorization from a given matrix\n      *\n      * This overloaded constructor is provided for \\link InplaceDecomposition inplace decomposition \\endlink when\n      * \\c MatrixType is a Eigen::Ref.\n      *\n      * \\sa HouseholderQR(const EigenBase&)\n      */\n    template<typename InputType>\n    explicit HouseholderQR(EigenBase<InputType>& matrix)\n      : m_qr(matrix.derived()),\n        m_hCoeffs((std::min)(matrix.rows(),matrix.cols())),\n        m_temp(matrix.cols()),\n        m_isInitialized(false)\n    {\n      computeInPlace();\n    }\n\n    #ifdef EIGEN_PARSED_BY_DOXYGEN\n    /** This method finds a solution x to the equation Ax=b, where A is the matrix of which\n      * *this is the QR decomposition, if any exists.\n      *\n      * \\param b the right-hand-side of the equation to solve.\n      *\n      * \\returns a solution.\n      *\n      * \\note_about_checking_solutions\n      *\n      * \\note_about_arbitrary_choice_of_solution\n      *\n      * Example: \\include HouseholderQR_solve.cpp\n      * Output: \\verbinclude HouseholderQR_solve.out\n      */\n    template<typename Rhs>\n    inline const Solve<HouseholderQR, Rhs>\n    solve(const MatrixBase<Rhs>& b) const;\n    #endif\n\n    /** This method returns an expression of the unitary matrix Q as a sequence of Householder transformations.\n      *\n      * The returned expression can directly be used to perform matrix products. It can also be assigned to a dense Matrix object.\n      * Here is an example showing how to recover the full or thin matrix Q, as well as how to perform matrix products using operator*:\n      *\n      * Example: \\include HouseholderQR_householderQ.cpp\n      * Output: \\verbinclude HouseholderQR_householderQ.out\n      */\n    HouseholderSequenceType householderQ() const\n    {\n      eigen_assert(m_isInitialized && \"HouseholderQR is not initialized.\");\n      return HouseholderSequenceType(m_qr, m_hCoeffs.conjugate());\n    }\n\n    /** \\returns a reference to the matrix where the Householder QR decomposition is stored\n      * in a LAPACK-compatible way.\n      */\n    const MatrixType& matrixQR() const\n    {\n        eigen_assert(m_isInitialized && \"HouseholderQR is not initialized.\");\n        return m_qr;\n    }\n\n    template<typename InputType>\n    HouseholderQR& compute(const EigenBase<InputType>& matrix) {\n      m_qr = matrix.derived();\n      computeInPlace();\n      return *this;\n    }\n\n    /** \\returns the absolute value of the determinant of the matrix of which\n      * *this is the QR decomposition. It has only linear complexity\n      * (that is, O(n) where n is the dimension of the square matrix)\n      * as the QR decomposition has already been computed.\n      *\n      * \\note This is only for square matrices.\n      *\n      * \\warning a determinant can be very big or small, so for matrices\n      * of large enough dimension, there is a risk of overflow/underflow.\n      * One way to work around that is to use logAbsDeterminant() instead.\n      *\n      * \\sa logAbsDeterminant(), MatrixBase::determinant()\n      */\n    typename MatrixType::RealScalar absDeterminant() const;\n\n    /** \\returns the natural log of the absolute value of the determinant of the matrix of which\n      * *this is the QR decomposition. It has only linear complexity\n      * (that is, O(n) where n is the dimension of the square matrix)\n      * as the QR decomposition has already been computed.\n      *\n      * \\note This is only for square matrices.\n      *\n      * \\note This method is useful to work around the risk of overflow/underflow that's inherent\n      * to determinant computation.\n      *\n      * \\sa absDeterminant(), MatrixBase::determinant()\n      */\n    typename MatrixType::RealScalar logAbsDeterminant() const;\n\n    inline Index rows() const { return m_qr.rows(); }\n    inline Index cols() const { return m_qr.cols(); }\n\n    /** \\returns a const reference to the vector of Householder coefficients used to represent the factor \\c Q.\n      * \n      * For advanced uses only.\n      */\n    const HCoeffsType& hCoeffs() const { return m_hCoeffs; }\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<typename RhsType, typename DstType>\n    void _solve_impl(const RhsType &rhs, DstType &dst) const;\n\n    template<bool Conjugate, typename RhsType, typename DstType>\n    void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const;\n    #endif\n\n  protected:\n\n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n    }\n\n    void computeInPlace();\n\n    MatrixType m_qr;\n    HCoeffsType m_hCoeffs;\n    RowVectorType m_temp;\n    bool m_isInitialized;\n};\n\ntemplate<typename MatrixType>\ntypename MatrixType::RealScalar HouseholderQR<MatrixType>::absDeterminant() const\n{\n  using std::abs;\n  eigen_assert(m_isInitialized && \"HouseholderQR is not initialized.\");\n  eigen_assert(m_qr.rows() == m_qr.cols() && \"You can't take the determinant of a non-square matrix!\");\n  return abs(m_qr.diagonal().prod());\n}\n\ntemplate<typename MatrixType>\ntypename MatrixType::RealScalar HouseholderQR<MatrixType>::logAbsDeterminant() const\n{\n  eigen_assert(m_isInitialized && \"HouseholderQR is not initialized.\");\n  eigen_assert(m_qr.rows() == m_qr.cols() && \"You can't take the determinant of a non-square matrix!\");\n  return m_qr.diagonal().cwiseAbs().array().log().sum();\n}\n\nnamespace internal {\n\n/** \\internal */\ntemplate<typename MatrixQR, typename HCoeffs>\nvoid householder_qr_inplace_unblocked(MatrixQR& mat, HCoeffs& hCoeffs, typename MatrixQR::Scalar* tempData = 0)\n{\n  typedef typename MatrixQR::Scalar Scalar;\n  typedef typename MatrixQR::RealScalar RealScalar;\n  Index rows = mat.rows();\n  Index cols = mat.cols();\n  Index size = (std::min)(rows,cols);\n\n  eigen_assert(hCoeffs.size() == size);\n\n  typedef Matrix<Scalar,MatrixQR::ColsAtCompileTime,1> TempType;\n  TempType tempVector;\n  if(tempData==0)\n  {\n    tempVector.resize(cols);\n    tempData = tempVector.data();\n  }\n\n  for(Index k = 0; k < size; ++k)\n  {\n    Index remainingRows = rows - k;\n    Index remainingCols = cols - k - 1;\n\n    RealScalar beta;\n    mat.col(k).tail(remainingRows).makeHouseholderInPlace(hCoeffs.coeffRef(k), beta);\n    mat.coeffRef(k,k) = beta;\n\n    // apply H to remaining part of m_qr from the left\n    mat.bottomRightCorner(remainingRows, remainingCols)\n        .applyHouseholderOnTheLeft(mat.col(k).tail(remainingRows-1), hCoeffs.coeffRef(k), tempData+k+1);\n  }\n}\n\n/** \\internal */\ntemplate<typename MatrixQR, typename HCoeffs,\n  typename MatrixQRScalar = typename MatrixQR::Scalar,\n  bool InnerStrideIsOne = (MatrixQR::InnerStrideAtCompileTime == 1 && HCoeffs::InnerStrideAtCompileTime == 1)>\nstruct householder_qr_inplace_blocked\n{\n  // This is specialized for LAPACK-supported Scalar types in HouseholderQR_LAPACKE.h\n  static void run(MatrixQR& mat, HCoeffs& hCoeffs, Index maxBlockSize=32,\n      typename MatrixQR::Scalar* tempData = 0)\n  {\n    typedef typename MatrixQR::Scalar Scalar;\n    typedef Block<MatrixQR,Dynamic,Dynamic> BlockType;\n\n    Index rows = mat.rows();\n    Index cols = mat.cols();\n    Index size = (std::min)(rows, cols);\n\n    typedef Matrix<Scalar,Dynamic,1,ColMajor,MatrixQR::MaxColsAtCompileTime,1> TempType;\n    TempType tempVector;\n    if(tempData==0)\n    {\n      tempVector.resize(cols);\n      tempData = tempVector.data();\n    }\n\n    Index blockSize = (std::min)(maxBlockSize,size);\n\n    Index k = 0;\n    for (k = 0; k < size; k += blockSize)\n    {\n      Index bs = (std::min)(size-k,blockSize);  // actual size of the block\n      Index tcols = cols - k - bs;              // trailing columns\n      Index brows = rows-k;                     // rows of the block\n\n      // partition the matrix:\n      //        A00 | A01 | A02\n      // mat  = A10 | A11 | A12\n      //        A20 | A21 | A22\n      // and performs the qr dec of [A11^T A12^T]^T\n      // and update [A21^T A22^T]^T using level 3 operations.\n      // Finally, the algorithm continue on A22\n\n      BlockType A11_21 = mat.block(k,k,brows,bs);\n      Block<HCoeffs,Dynamic,1> hCoeffsSegment = hCoeffs.segment(k,bs);\n\n      householder_qr_inplace_unblocked(A11_21, hCoeffsSegment, tempData);\n\n      if(tcols)\n      {\n        BlockType A21_22 = mat.block(k,k+bs,brows,tcols);\n        apply_block_householder_on_the_left(A21_22,A11_21,hCoeffsSegment, false); // false == backward\n      }\n    }\n  }\n};\n\n} // end namespace internal\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename MatrixType_>\ntemplate<typename RhsType, typename DstType>\nvoid HouseholderQR<MatrixType_>::_solve_impl(const RhsType &rhs, DstType &dst) const\n{\n  const Index rank = (std::min)(rows(), cols());\n\n  typename RhsType::PlainObject c(rhs);\n\n  c.applyOnTheLeft(householderQ().setLength(rank).adjoint() );\n\n  m_qr.topLeftCorner(rank, rank)\n      .template triangularView<Upper>()\n      .solveInPlace(c.topRows(rank));\n\n  dst.topRows(rank) = c.topRows(rank);\n  dst.bottomRows(cols()-rank).setZero();\n}\n\ntemplate<typename MatrixType_>\ntemplate<bool Conjugate, typename RhsType, typename DstType>\nvoid HouseholderQR<MatrixType_>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const\n{\n  const Index rank = (std::min)(rows(), cols());\n\n  typename RhsType::PlainObject c(rhs);\n\n  m_qr.topLeftCorner(rank, rank)\n      .template triangularView<Upper>()\n      .transpose().template conjugateIf<Conjugate>()\n      .solveInPlace(c.topRows(rank));\n\n  dst.topRows(rank) = c.topRows(rank);\n  dst.bottomRows(rows()-rank).setZero();\n\n  dst.applyOnTheLeft(householderQ().setLength(rank).template conjugateIf<!Conjugate>() );\n}\n#endif\n\n/** Performs the QR factorization of the given matrix \\a matrix. The result of\n  * the factorization is stored into \\c *this, and a reference to \\c *this\n  * is returned.\n  *\n  * \\sa class HouseholderQR, HouseholderQR(const MatrixType&)\n  */\ntemplate<typename MatrixType>\nvoid HouseholderQR<MatrixType>::computeInPlace()\n{\n  check_template_parameters();\n  \n  Index rows = m_qr.rows();\n  Index cols = m_qr.cols();\n  Index size = (std::min)(rows,cols);\n\n  m_hCoeffs.resize(size);\n\n  m_temp.resize(cols);\n\n  internal::householder_qr_inplace_blocked<MatrixType, HCoeffsType>::run(m_qr, m_hCoeffs, 48, m_temp.data());\n\n  m_isInitialized = true;\n}\n\n/** \\return the Householder QR decomposition of \\c *this.\n  *\n  * \\sa class HouseholderQR\n  */\ntemplate<typename Derived>\nconst HouseholderQR<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::householderQr() const\n{\n  return HouseholderQR<PlainObject>(eval());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_QR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/QR/HouseholderQR_LAPACKE.h",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Eigen bindings to LAPACKe\n *    Householder QR decomposition of a matrix w/o pivoting based on\n *    LAPACKE_?geqrf function.\n ********************************************************************************\n*/\n\n#ifndef EIGEN_QR_LAPACKE_H\n#define EIGEN_QR_LAPACKE_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\internal Specialization for the data types supported by LAPACKe */\n\n#define EIGEN_LAPACKE_QR_NOPIV(EIGTYPE, LAPACKE_TYPE, LAPACKE_PREFIX) \\\ntemplate<typename MatrixQR, typename HCoeffs> \\\nstruct householder_qr_inplace_blocked<MatrixQR, HCoeffs, EIGTYPE, true> \\\n{ \\\n  static void run(MatrixQR& mat, HCoeffs& hCoeffs, Index = 32, \\\n      typename MatrixQR::Scalar* = 0) \\\n  { \\\n    lapack_int m = (lapack_int) mat.rows(); \\\n    lapack_int n = (lapack_int) mat.cols(); \\\n    lapack_int lda = (lapack_int) mat.outerStride(); \\\n    lapack_int matrix_order = (MatrixQR::IsRowMajor) ? LAPACK_ROW_MAJOR : LAPACK_COL_MAJOR; \\\n    LAPACKE_##LAPACKE_PREFIX##geqrf( matrix_order, m, n, (LAPACKE_TYPE*)mat.data(), lda, (LAPACKE_TYPE*)hCoeffs.data()); \\\n    hCoeffs.adjointInPlace(); \\\n  } \\\n};\n\nEIGEN_LAPACKE_QR_NOPIV(double, double, d)\nEIGEN_LAPACKE_QR_NOPIV(float, float, s)\nEIGEN_LAPACKE_QR_NOPIV(dcomplex, lapack_complex_double, z)\nEIGEN_LAPACKE_QR_NOPIV(scomplex, lapack_complex_float, c)\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_QR_LAPACKE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SPQRSupport/SuiteSparseQRSupport.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Desire Nuentsa <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SUITESPARSEQRSUPPORT_H\n#define EIGEN_SUITESPARSEQRSUPPORT_H\n\nnamespace Eigen {\n  \n  template<typename MatrixType> class SPQR; \n  template<typename SPQRType> struct SPQRMatrixQReturnType; \n  template<typename SPQRType> struct SPQRMatrixQTransposeReturnType; \n  template <typename SPQRType, typename Derived> struct SPQR_QProduct;\n  namespace internal {\n    template <typename SPQRType> struct traits<SPQRMatrixQReturnType<SPQRType> >\n    {\n      typedef typename SPQRType::MatrixType ReturnType;\n    };\n    template <typename SPQRType> struct traits<SPQRMatrixQTransposeReturnType<SPQRType> >\n    {\n      typedef typename SPQRType::MatrixType ReturnType;\n    };\n    template <typename SPQRType, typename Derived> struct traits<SPQR_QProduct<SPQRType, Derived> >\n    {\n      typedef typename Derived::PlainObject ReturnType;\n    };\n  } // End namespace internal\n  \n/**\n  * \\ingroup SPQRSupport_Module\n  * \\class SPQR\n  * \\brief Sparse QR factorization based on SuiteSparseQR library\n  *\n  * This class is used to perform a multithreaded and multifrontal rank-revealing QR decomposition\n  * of sparse matrices. The result is then used to solve linear leasts_square systems.\n  * Clearly, a QR factorization is returned such that A*P = Q*R where :\n  *\n  * P is the column permutation. Use colsPermutation() to get it.\n  *\n  * Q is the orthogonal matrix represented as Householder reflectors.\n  * Use matrixQ() to get an expression and matrixQ().transpose() to get the transpose.\n  * You can then apply it to a vector.\n  *\n  * R is the sparse triangular factor. Use matrixQR() to get it as SparseMatrix.\n  * NOTE : The Index type of R is always SuiteSparse_long. You can get it with SPQR::Index\n  *\n  * \\tparam MatrixType_ The type of the sparse matrix A, must be a column-major SparseMatrix<>\n  *\n  * \\implsparsesolverconcept\n  *\n  *\n  */\ntemplate<typename MatrixType_>\nclass SPQR : public SparseSolverBase<SPQR<MatrixType_> >\n{\n  protected:\n    typedef SparseSolverBase<SPQR<MatrixType_> > Base;\n    using Base::m_isInitialized;\n  public:\n    typedef typename MatrixType_::Scalar Scalar;\n    typedef typename MatrixType_::RealScalar RealScalar;\n    typedef SuiteSparse_long StorageIndex ;\n    typedef SparseMatrix<Scalar, ColMajor, StorageIndex> MatrixType;\n    typedef Map<PermutationMatrix<Dynamic, Dynamic, StorageIndex> > PermutationType;\n    enum {\n      ColsAtCompileTime = Dynamic,\n      MaxColsAtCompileTime = Dynamic\n    };\n  public:\n    SPQR() \n      : m_analysisIsOk(false),\n        m_factorizationIsOk(false),\n        m_isRUpToDate(false),\n        m_ordering(SPQR_ORDERING_DEFAULT),\n        m_allow_tol(SPQR_DEFAULT_TOL),\n        m_tolerance (NumTraits<Scalar>::epsilon()),\n        m_cR(0),\n        m_E(0),\n        m_H(0),\n        m_HPinv(0),\n        m_HTau(0),\n        m_useDefaultThreshold(true)\n    { \n      cholmod_l_start(&m_cc);\n    }\n    \n    explicit SPQR(const MatrixType_& matrix)\n      : m_analysisIsOk(false),\n        m_factorizationIsOk(false),\n        m_isRUpToDate(false),\n        m_ordering(SPQR_ORDERING_DEFAULT),\n        m_allow_tol(SPQR_DEFAULT_TOL),\n        m_tolerance (NumTraits<Scalar>::epsilon()),\n        m_cR(0),\n        m_E(0),\n        m_H(0),\n        m_HPinv(0),\n        m_HTau(0),\n        m_useDefaultThreshold(true)\n    {\n      cholmod_l_start(&m_cc);\n      compute(matrix);\n    }\n    \n    ~SPQR()\n    {\n      SPQR_free();\n      cholmod_l_finish(&m_cc);\n    }\n    void SPQR_free()\n    {\n      cholmod_l_free_sparse(&m_H, &m_cc);\n      cholmod_l_free_sparse(&m_cR, &m_cc);\n      cholmod_l_free_dense(&m_HTau, &m_cc);\n      std::free(m_E);\n      std::free(m_HPinv);\n    }\n\n    void compute(const MatrixType_& matrix)\n    {\n      if(m_isInitialized) SPQR_free();\n\n      MatrixType mat(matrix);\n      \n      /* Compute the default threshold as in MatLab, see:\n       * Tim Davis, \"Algorithm 915, SuiteSparseQR: Multifrontal Multithreaded Rank-Revealing\n       * Sparse QR Factorization, ACM Trans. on Math. Soft. 38(1), 2011, Page 8:3 \n       */\n      RealScalar pivotThreshold = m_tolerance;\n      if(m_useDefaultThreshold) \n      {\n        RealScalar max2Norm = 0.0;\n        for (int j = 0; j < mat.cols(); j++) max2Norm = numext::maxi(max2Norm, mat.col(j).norm());\n        if(max2Norm==RealScalar(0))\n          max2Norm = RealScalar(1);\n        pivotThreshold = 20 * (mat.rows() + mat.cols()) * max2Norm * NumTraits<RealScalar>::epsilon();\n      }\n      cholmod_sparse A; \n      A = viewAsCholmod(mat);\n      m_rows = matrix.rows();\n      Index col = matrix.cols();\n      m_rank = SuiteSparseQR<Scalar>(m_ordering, pivotThreshold, col, &A, \n                             &m_cR, &m_E, &m_H, &m_HPinv, &m_HTau, &m_cc);\n\n      if (!m_cR)\n      {\n        m_info = NumericalIssue;\n        m_isInitialized = false;\n        return;\n      }\n      m_info = Success;\n      m_isInitialized = true;\n      m_isRUpToDate = false;\n    }\n    /** \n     * Get the number of rows of the input matrix and the Q matrix\n     */\n    inline Index rows() const {return m_rows; }\n    \n    /** \n     * Get the number of columns of the input matrix. \n     */\n    inline Index cols() const { return m_cR->ncol; }\n    \n    template<typename Rhs, typename Dest>\n    void _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const\n    {\n      eigen_assert(m_isInitialized && \" The QR factorization should be computed first, call compute()\");\n      eigen_assert(b.cols()==1 && \"This method is for vectors only\");\n\n      //Compute Q^T * b\n      typename Dest::PlainObject y, y2;\n      y = matrixQ().transpose() * b;\n      \n      // Solves with the triangular matrix R\n      Index rk = this->rank();\n      y2 = y;\n      y.resize((std::max)(cols(),Index(y.rows())),y.cols());\n      y.topRows(rk) = this->matrixR().topLeftCorner(rk, rk).template triangularView<Upper>().solve(y2.topRows(rk));\n\n      // Apply the column permutation \n      // colsPermutation() performs a copy of the permutation,\n      // so let's apply it manually:\n      for(Index i = 0; i < rk; ++i) dest.row(m_E[i]) = y.row(i);\n      for(Index i = rk; i < cols(); ++i) dest.row(m_E[i]).setZero();\n      \n//       y.bottomRows(y.rows()-rk).setZero();\n//       dest = colsPermutation() * y.topRows(cols());\n      \n      m_info = Success;\n    }\n    \n    /** \\returns the sparse triangular factor R. It is a sparse matrix\n     */\n    const MatrixType matrixR() const\n    {\n      eigen_assert(m_isInitialized && \" The QR factorization should be computed first, call compute()\");\n      if(!m_isRUpToDate) {\n        m_R = viewAsEigen<Scalar,ColMajor, typename MatrixType::StorageIndex>(*m_cR);\n        m_isRUpToDate = true;\n      }\n      return m_R;\n    }\n    /// Get an expression of the matrix Q\n    SPQRMatrixQReturnType<SPQR> matrixQ() const\n    {\n      return SPQRMatrixQReturnType<SPQR>(*this);\n    }\n    /// Get the permutation that was applied to columns of A\n    PermutationType colsPermutation() const\n    { \n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return PermutationType(m_E, m_cR->ncol);\n    }\n    /**\n     * Gets the rank of the matrix. \n     * It should be equal to matrixQR().cols if the matrix is full-rank\n     */\n    Index rank() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_cc.SPQR_istat[4];\n    }\n    /// Set the fill-reducing ordering method to be used\n    void setSPQROrdering(int ord) { m_ordering = ord;}\n    /// Set the tolerance tol to treat columns with 2-norm < =tol as zero\n    void setPivotThreshold(const RealScalar& tol)\n    {\n      m_useDefaultThreshold = false;\n      m_tolerance = tol;\n    }\n    \n    /** \\returns a pointer to the SPQR workspace */\n    cholmod_common *cholmodCommon() const { return &m_cc; }\n    \n    \n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the sparse QR can not be computed\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_info;\n    }\n  protected:\n    bool m_analysisIsOk;\n    bool m_factorizationIsOk;\n    mutable bool m_isRUpToDate;\n    mutable ComputationInfo m_info;\n    int m_ordering; // Ordering method to use, see SPQR's manual\n    int m_allow_tol; // Allow to use some tolerance during numerical factorization.\n    RealScalar m_tolerance; // treat columns with 2-norm below this tolerance as zero\n    mutable cholmod_sparse *m_cR; // The sparse R factor in cholmod format\n    mutable MatrixType m_R; // The sparse matrix R in Eigen format\n    mutable StorageIndex *m_E; // The permutation applied to columns\n    mutable cholmod_sparse *m_H;  //The householder vectors\n    mutable StorageIndex *m_HPinv; // The row permutation of H\n    mutable cholmod_dense *m_HTau; // The Householder coefficients\n    mutable Index m_rank; // The rank of the matrix\n    mutable cholmod_common m_cc; // Workspace and parameters\n    bool m_useDefaultThreshold;     // Use default threshold\n    Index m_rows;\n    template<typename ,typename > friend struct SPQR_QProduct;\n};\n\ntemplate <typename SPQRType, typename Derived>\nstruct SPQR_QProduct : ReturnByValue<SPQR_QProduct<SPQRType,Derived> >\n{\n  typedef typename SPQRType::Scalar Scalar;\n  typedef typename SPQRType::StorageIndex StorageIndex;\n  //Define the constructor to get reference to argument types\n  SPQR_QProduct(const SPQRType& spqr, const Derived& other, bool transpose) : m_spqr(spqr),m_other(other),m_transpose(transpose) {}\n  \n  inline Index rows() const { return m_transpose ? m_spqr.rows() : m_spqr.cols(); }\n  inline Index cols() const { return m_other.cols(); }\n  // Assign to a vector\n  template<typename ResType>\n  void evalTo(ResType& res) const\n  {\n    cholmod_dense y_cd;\n    cholmod_dense *x_cd; \n    int method = m_transpose ? SPQR_QTX : SPQR_QX; \n    cholmod_common *cc = m_spqr.cholmodCommon();\n    y_cd = viewAsCholmod(m_other.const_cast_derived());\n    x_cd = SuiteSparseQR_qmult<Scalar>(method, m_spqr.m_H, m_spqr.m_HTau, m_spqr.m_HPinv, &y_cd, cc);\n    res = Matrix<Scalar,ResType::RowsAtCompileTime,ResType::ColsAtCompileTime>::Map(reinterpret_cast<Scalar*>(x_cd->x), x_cd->nrow, x_cd->ncol);\n    cholmod_l_free_dense(&x_cd, cc);\n  }\n  const SPQRType& m_spqr; \n  const Derived& m_other; \n  bool m_transpose; \n  \n};\ntemplate<typename SPQRType>\nstruct SPQRMatrixQReturnType{\n  \n  SPQRMatrixQReturnType(const SPQRType& spqr) : m_spqr(spqr) {}\n  template<typename Derived>\n  SPQR_QProduct<SPQRType, Derived> operator*(const MatrixBase<Derived>& other)\n  {\n    return SPQR_QProduct<SPQRType,Derived>(m_spqr,other.derived(),false);\n  }\n  SPQRMatrixQTransposeReturnType<SPQRType> adjoint() const\n  {\n    return SPQRMatrixQTransposeReturnType<SPQRType>(m_spqr);\n  }\n  // To use for operations with the transpose of Q\n  SPQRMatrixQTransposeReturnType<SPQRType> transpose() const\n  {\n    return SPQRMatrixQTransposeReturnType<SPQRType>(m_spqr);\n  }\n  const SPQRType& m_spqr;\n};\n\ntemplate<typename SPQRType>\nstruct SPQRMatrixQTransposeReturnType{\n  SPQRMatrixQTransposeReturnType(const SPQRType& spqr) : m_spqr(spqr) {}\n  template<typename Derived>\n  SPQR_QProduct<SPQRType,Derived> operator*(const MatrixBase<Derived>& other)\n  {\n    return SPQR_QProduct<SPQRType,Derived>(m_spqr,other.derived(), true);\n  }\n  const SPQRType& m_spqr;\n};\n\n}// End namespace Eigen\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SVD/BDCSVD.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n// \n// We used the \"A Divide-And-Conquer Algorithm for the Bidiagonal SVD\"\n// research report written by Ming Gu and Stanley C.Eisenstat\n// The code variable names correspond to the names they used in their \n// report\n//\n// Copyright (C) 2013 Gauthier Brun <brun.gauthier@gmail.com>\n// Copyright (C) 2013 Nicolas Carre <nicolas.carre@ensimag.fr>\n// Copyright (C) 2013 Jean Ceccato <jean.ceccato@ensimag.fr>\n// Copyright (C) 2013 Pierre Zoppitelli <pierre.zoppitelli@ensimag.fr>\n// Copyright (C) 2013 Jitse Niesen <jitse@maths.leeds.ac.uk>\n// Copyright (C) 2014-2017 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BDCSVD_H\n#define EIGEN_BDCSVD_H\n// #define EIGEN_BDCSVD_DEBUG_VERBOSE\n// #define EIGEN_BDCSVD_SANITY_CHECKS\n\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n#undef eigen_internal_assert\n#define eigen_internal_assert(X) assert(X);\n#endif\n\nnamespace Eigen {\n\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\nIOFormat bdcsvdfmt(8, 0, \", \", \"\\n\", \"  [\", \"]\");\n#endif\n  \ntemplate<typename MatrixType_> class BDCSVD;\n\nnamespace internal {\n\ntemplate<typename MatrixType_>\nstruct traits<BDCSVD<MatrixType_> >\n        : traits<MatrixType_>\n{\n  typedef MatrixType_ MatrixType;\n};  \n\n} // end namespace internal\n  \n  \n/** \\ingroup SVD_Module\n *\n *\n * \\class BDCSVD\n *\n * \\brief class Bidiagonal Divide and Conquer SVD\n *\n * \\tparam MatrixType_ the type of the matrix of which we are computing the SVD decomposition\n *\n * This class first reduces the input matrix to bi-diagonal form using class UpperBidiagonalization,\n * and then performs a divide-and-conquer diagonalization. Small blocks are diagonalized using class JacobiSVD.\n * You can control the switching size with the setSwitchSize() method, default is 16.\n * For small matrice (<16), it is thus preferable to directly use JacobiSVD. For larger ones, BDCSVD is highly\n * recommended and can several order of magnitude faster.\n *\n * \\warning this algorithm is unlikely to provide accurate result when compiled with unsafe math optimizations.\n * For instance, this concerns Intel's compiler (ICC), which performs such optimization by default unless\n * you compile with the \\c -fp-model \\c precise option. Likewise, the \\c -ffast-math option of GCC or clang will\n * significantly degrade the accuracy.\n *\n * \\sa class JacobiSVD\n */\ntemplate<typename MatrixType_>\nclass BDCSVD : public SVDBase<BDCSVD<MatrixType_> >\n{\n  typedef SVDBase<BDCSVD> Base;\n    \npublic:\n  using Base::rows;\n  using Base::cols;\n  using Base::computeU;\n  using Base::computeV;\n  \n  typedef MatrixType_ MatrixType;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<typename MatrixType::Scalar>::Real RealScalar;\n  typedef typename NumTraits<RealScalar>::Literal Literal;\n  enum {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime, \n    ColsAtCompileTime = MatrixType::ColsAtCompileTime, \n    DiagSizeAtCompileTime = EIGEN_SIZE_MIN_PREFER_DYNAMIC(RowsAtCompileTime, ColsAtCompileTime), \n    MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime, \n    MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime, \n    MaxDiagSizeAtCompileTime = EIGEN_SIZE_MIN_PREFER_FIXED(MaxRowsAtCompileTime, MaxColsAtCompileTime), \n    MatrixOptions = MatrixType::Options\n  };\n\n  typedef typename Base::MatrixUType MatrixUType;\n  typedef typename Base::MatrixVType MatrixVType;\n  typedef typename Base::SingularValuesType SingularValuesType;\n  \n  typedef Matrix<Scalar, Dynamic, Dynamic, ColMajor> MatrixX;\n  typedef Matrix<RealScalar, Dynamic, Dynamic, ColMajor> MatrixXr;\n  typedef Matrix<RealScalar, Dynamic, 1> VectorType;\n  typedef Array<RealScalar, Dynamic, 1> ArrayXr;\n  typedef Array<Index,1,Dynamic> ArrayXi;\n  typedef Ref<ArrayXr> ArrayRef;\n  typedef Ref<ArrayXi> IndicesRef;\n\n  /** \\brief Default Constructor.\n   *\n   * The default constructor is useful in cases in which the user intends to\n   * perform decompositions via BDCSVD::compute(const MatrixType&).\n   */\n  BDCSVD() : m_algoswap(16), m_isTranspose(false), m_compU(false), m_compV(false), m_numIters(0)\n  {}\n\n\n  /** \\brief Default Constructor with memory preallocation\n   *\n   * Like the default constructor but with preallocation of the internal data\n   * according to the specified problem size.\n   * \\sa BDCSVD()\n   */\n  BDCSVD(Index rows, Index cols, unsigned int computationOptions = 0)\n    : m_algoswap(16), m_numIters(0)\n  {\n    allocate(rows, cols, computationOptions);\n  }\n\n  /** \\brief Constructor performing the decomposition of given matrix.\n   *\n   * \\param matrix the matrix to decompose\n   * \\param computationOptions optional parameter allowing to specify if you want full or thin U or V unitaries to be computed.\n   *                           By default, none is computed. This is a bit - field, the possible bits are #ComputeFullU, #ComputeThinU, \n   *                           #ComputeFullV, #ComputeThinV.\n   *\n   * Thin unitaries are only available if your matrix type has a Dynamic number of columns (for example MatrixXf). They also are not\n   * available with the (non - default) FullPivHouseholderQR preconditioner.\n   */\n  BDCSVD(const MatrixType& matrix, unsigned int computationOptions = 0)\n    : m_algoswap(16), m_numIters(0)\n  {\n    compute(matrix, computationOptions);\n  }\n\n  ~BDCSVD() \n  {\n  }\n  \n  /** \\brief Method performing the decomposition of given matrix using custom options.\n   *\n   * \\param matrix the matrix to decompose\n   * \\param computationOptions optional parameter allowing to specify if you want full or thin U or V unitaries to be computed.\n   *                           By default, none is computed. This is a bit - field, the possible bits are #ComputeFullU, #ComputeThinU, \n   *                           #ComputeFullV, #ComputeThinV.\n   *\n   * Thin unitaries are only available if your matrix type has a Dynamic number of columns (for example MatrixXf). They also are not\n   * available with the (non - default) FullPivHouseholderQR preconditioner.\n   */\n  BDCSVD& compute(const MatrixType& matrix, unsigned int computationOptions);\n\n  /** \\brief Method performing the decomposition of given matrix using current options.\n   *\n   * \\param matrix the matrix to decompose\n   *\n   * This method uses the current \\a computationOptions, as already passed to the constructor or to compute(const MatrixType&, unsigned int).\n   */\n  BDCSVD& compute(const MatrixType& matrix)\n  {\n    return compute(matrix, this->m_computationOptions);\n  }\n\n  void setSwitchSize(int s) \n  {\n    eigen_assert(s>3 && \"BDCSVD the size of the algo switch has to be greater than 3\");\n    m_algoswap = s;\n  }\n \nprivate:\n  void allocate(Index rows, Index cols, unsigned int computationOptions);\n  void divide(Index firstCol, Index lastCol, Index firstRowW, Index firstColW, Index shift);\n  void computeSVDofM(Index firstCol, Index n, MatrixXr& U, VectorType& singVals, MatrixXr& V);\n  void computeSingVals(const ArrayRef& col0, const ArrayRef& diag, const IndicesRef& perm, VectorType& singVals, ArrayRef shifts, ArrayRef mus);\n  void perturbCol0(const ArrayRef& col0, const ArrayRef& diag, const IndicesRef& perm, const VectorType& singVals, const ArrayRef& shifts, const ArrayRef& mus, ArrayRef zhat);\n  void computeSingVecs(const ArrayRef& zhat, const ArrayRef& diag, const IndicesRef& perm, const VectorType& singVals, const ArrayRef& shifts, const ArrayRef& mus, MatrixXr& U, MatrixXr& V);\n  void deflation43(Index firstCol, Index shift, Index i, Index size);\n  void deflation44(Index firstColu , Index firstColm, Index firstRowW, Index firstColW, Index i, Index j, Index size);\n  void deflation(Index firstCol, Index lastCol, Index k, Index firstRowW, Index firstColW, Index shift);\n  template<typename HouseholderU, typename HouseholderV, typename NaiveU, typename NaiveV>\n  void copyUV(const HouseholderU &householderU, const HouseholderV &householderV, const NaiveU &naiveU, const NaiveV &naivev);\n  void structured_update(Block<MatrixXr,Dynamic,Dynamic> A, const MatrixXr &B, Index n1);\n  static RealScalar secularEq(RealScalar x, const ArrayRef& col0, const ArrayRef& diag, const IndicesRef &perm, const ArrayRef& diagShifted, RealScalar shift);\n\nprotected:\n  MatrixXr m_naiveU, m_naiveV;\n  MatrixXr m_computed;\n  Index m_nRec;\n  ArrayXr m_workspace;\n  ArrayXi m_workspaceI;\n  int m_algoswap;\n  bool m_isTranspose, m_compU, m_compV;\n  \n  using Base::m_singularValues;\n  using Base::m_diagSize;\n  using Base::m_computeFullU;\n  using Base::m_computeFullV;\n  using Base::m_computeThinU;\n  using Base::m_computeThinV;\n  using Base::m_matrixU;\n  using Base::m_matrixV;\n  using Base::m_info;\n  using Base::m_isInitialized;\n  using Base::m_nonzeroSingularValues;\n\npublic:  \n  int m_numIters;\n}; //end class BDCSVD\n\n\n// Method to allocate and initialize matrix and attributes\ntemplate<typename MatrixType>\nvoid BDCSVD<MatrixType>::allocate(Eigen::Index rows, Eigen::Index cols, unsigned int computationOptions)\n{\n  m_isTranspose = (cols > rows);\n\n  if (Base::allocate(rows, cols, computationOptions))\n    return;\n  \n  m_computed = MatrixXr::Zero(m_diagSize + 1, m_diagSize );\n  m_compU = computeV();\n  m_compV = computeU();\n  if (m_isTranspose)\n    std::swap(m_compU, m_compV);\n  \n  if (m_compU) m_naiveU = MatrixXr::Zero(m_diagSize + 1, m_diagSize + 1 );\n  else         m_naiveU = MatrixXr::Zero(2, m_diagSize + 1 );\n  \n  if (m_compV) m_naiveV = MatrixXr::Zero(m_diagSize, m_diagSize);\n  \n  m_workspace.resize((m_diagSize+1)*(m_diagSize+1)*3);\n  m_workspaceI.resize(3*m_diagSize);\n}// end allocate\n\ntemplate<typename MatrixType>\nBDCSVD<MatrixType>& BDCSVD<MatrixType>::compute(const MatrixType& matrix, unsigned int computationOptions) \n{\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n  std::cout << \"\\n\\n\\n======================================================================================================================\\n\\n\\n\";\n#endif\n  allocate(matrix.rows(), matrix.cols(), computationOptions);\n  using std::abs;\n\n  const RealScalar considerZero = (std::numeric_limits<RealScalar>::min)();\n  \n  //**** step -1 - If the problem is too small, directly falls back to JacobiSVD and return\n  if(matrix.cols() < m_algoswap)\n  {\n    // FIXME this line involves temporaries\n    JacobiSVD<MatrixType> jsvd(matrix,computationOptions);\n    m_isInitialized = true;\n    m_info = jsvd.info();\n    if (m_info == Success || m_info == NoConvergence) {\n      if(computeU()) m_matrixU = jsvd.matrixU();\n      if(computeV()) m_matrixV = jsvd.matrixV();\n      m_singularValues = jsvd.singularValues();\n      m_nonzeroSingularValues = jsvd.nonzeroSingularValues();\n    }\n    return *this;\n  }\n  \n  //**** step 0 - Copy the input matrix and apply scaling to reduce over/under-flows\n  RealScalar scale = matrix.cwiseAbs().template maxCoeff<PropagateNaN>();\n  if (!(numext::isfinite)(scale)) {\n    m_isInitialized = true;\n    m_info = InvalidInput;\n    return *this;\n  }\n\n  if(scale==Literal(0)) scale = Literal(1);\n  MatrixX copy;\n  if (m_isTranspose) copy = matrix.adjoint()/scale;\n  else               copy = matrix/scale;\n  \n  //**** step 1 - Bidiagonalization\n  // FIXME this line involves temporaries\n  internal::UpperBidiagonalization<MatrixX> bid(copy);\n\n  //**** step 2 - Divide & Conquer\n  m_naiveU.setZero();\n  m_naiveV.setZero();\n  // FIXME this line involves a temporary matrix\n  m_computed.topRows(m_diagSize) = bid.bidiagonal().toDenseMatrix().transpose();\n  m_computed.template bottomRows<1>().setZero();\n  divide(0, m_diagSize - 1, 0, 0, 0);\n  if (m_info != Success && m_info != NoConvergence) {\n    m_isInitialized = true;\n    return *this;\n  }\n    \n  //**** step 3 - Copy singular values and vectors\n  for (int i=0; i<m_diagSize; i++)\n  {\n    RealScalar a = abs(m_computed.coeff(i, i));\n    m_singularValues.coeffRef(i) = a * scale;\n    if (a<considerZero)\n    {\n      m_nonzeroSingularValues = i;\n      m_singularValues.tail(m_diagSize - i - 1).setZero();\n      break;\n    }\n    else if (i == m_diagSize - 1)\n    {\n      m_nonzeroSingularValues = i + 1;\n      break;\n    }\n  }\n\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n//   std::cout << \"m_naiveU\\n\" << m_naiveU << \"\\n\\n\";\n//   std::cout << \"m_naiveV\\n\" << m_naiveV << \"\\n\\n\";\n#endif\n  if(m_isTranspose) copyUV(bid.householderV(), bid.householderU(), m_naiveV, m_naiveU);\n  else              copyUV(bid.householderU(), bid.householderV(), m_naiveU, m_naiveV);\n\n  m_isInitialized = true;\n  return *this;\n}// end compute\n\n\ntemplate<typename MatrixType>\ntemplate<typename HouseholderU, typename HouseholderV, typename NaiveU, typename NaiveV>\nvoid BDCSVD<MatrixType>::copyUV(const HouseholderU &householderU, const HouseholderV &householderV, const NaiveU &naiveU, const NaiveV &naiveV)\n{\n  // Note exchange of U and V: m_matrixU is set from m_naiveV and vice versa\n  if (computeU())\n  {\n    Index Ucols = m_computeThinU ? m_diagSize : householderU.cols();\n    m_matrixU = MatrixX::Identity(householderU.cols(), Ucols);\n    m_matrixU.topLeftCorner(m_diagSize, m_diagSize) = naiveV.template cast<Scalar>().topLeftCorner(m_diagSize, m_diagSize);\n    householderU.applyThisOnTheLeft(m_matrixU); // FIXME this line involves a temporary buffer\n  }\n  if (computeV())\n  {\n    Index Vcols = m_computeThinV ? m_diagSize : householderV.cols();\n    m_matrixV = MatrixX::Identity(householderV.cols(), Vcols);\n    m_matrixV.topLeftCorner(m_diagSize, m_diagSize) = naiveU.template cast<Scalar>().topLeftCorner(m_diagSize, m_diagSize);\n    householderV.applyThisOnTheLeft(m_matrixV); // FIXME this line involves a temporary buffer\n  }\n}\n\n/** \\internal\n  * Performs A = A * B exploiting the special structure of the matrix A. Splitting A as:\n  *  A = [A1]\n  *      [A2]\n  * such that A1.rows()==n1, then we assume that at least half of the columns of A1 and A2 are zeros.\n  * We can thus pack them prior to the the matrix product. However, this is only worth the effort if the matrix is large\n  * enough.\n  */\ntemplate<typename MatrixType>\nvoid BDCSVD<MatrixType>::structured_update(Block<MatrixXr,Dynamic,Dynamic> A, const MatrixXr &B, Index n1)\n{\n  Index n = A.rows();\n  if(n>100)\n  {\n    // If the matrices are large enough, let's exploit the sparse structure of A by\n    // splitting it in half (wrt n1), and packing the non-zero columns.\n    Index n2 = n - n1;\n    Map<MatrixXr> A1(m_workspace.data()      , n1, n);\n    Map<MatrixXr> A2(m_workspace.data()+ n1*n, n2, n);\n    Map<MatrixXr> B1(m_workspace.data()+  n*n, n,  n);\n    Map<MatrixXr> B2(m_workspace.data()+2*n*n, n,  n);\n    Index k1=0, k2=0;\n    for(Index j=0; j<n; ++j)\n    {\n      if( (A.col(j).head(n1).array()!=Literal(0)).any() )\n      {\n        A1.col(k1) = A.col(j).head(n1);\n        B1.row(k1) = B.row(j);\n        ++k1;\n      }\n      if( (A.col(j).tail(n2).array()!=Literal(0)).any() )\n      {\n        A2.col(k2) = A.col(j).tail(n2);\n        B2.row(k2) = B.row(j);\n        ++k2;\n      }\n    }\n  \n    A.topRows(n1).noalias()    = A1.leftCols(k1) * B1.topRows(k1);\n    A.bottomRows(n2).noalias() = A2.leftCols(k2) * B2.topRows(k2);\n  }\n  else\n  {\n    Map<MatrixXr,Aligned> tmp(m_workspace.data(),n,n);\n    tmp.noalias() = A*B;\n    A = tmp;\n  }\n}\n\n// The divide algorithm is done \"in place\", we are always working on subsets of the same matrix. The divide methods takes as argument the \n// place of the submatrix we are currently working on.\n\n//@param firstCol : The Index of the first column of the submatrix of m_computed and for m_naiveU;\n//@param lastCol : The Index of the last column of the submatrix of m_computed and for m_naiveU; \n// lastCol + 1 - firstCol is the size of the submatrix.\n//@param firstRowW : The Index of the first row of the matrix W that we are to change. (see the reference paper section 1 for more information on W)\n//@param firstRowW : Same as firstRowW with the column.\n//@param shift : Each time one takes the left submatrix, one must add 1 to the shift. Why? Because! We actually want the last column of the U submatrix \n// to become the first column (*coeff) and to shift all the other columns to the right. There are more details on the reference paper.\ntemplate<typename MatrixType>\nvoid BDCSVD<MatrixType>::divide(Eigen::Index firstCol, Eigen::Index lastCol, Eigen::Index firstRowW, Eigen::Index firstColW, Eigen::Index shift)\n{\n  // requires rows = cols + 1;\n  using std::pow;\n  using std::sqrt;\n  using std::abs;\n  const Index n = lastCol - firstCol + 1;\n  const Index k = n/2;\n  const RealScalar considerZero = (std::numeric_limits<RealScalar>::min)();\n  RealScalar alphaK;\n  RealScalar betaK; \n  RealScalar r0; \n  RealScalar lambda, phi, c0, s0;\n  VectorType l, f;\n  // We use the other algorithm which is more efficient for small \n  // matrices.\n  if (n < m_algoswap)\n  {\n    // FIXME this line involves temporaries\n    JacobiSVD<MatrixXr> b(m_computed.block(firstCol, firstCol, n + 1, n), ComputeFullU | (m_compV ? ComputeFullV : 0));\n    m_info = b.info();\n    if (m_info != Success && m_info != NoConvergence) return;\n    if (m_compU)\n      m_naiveU.block(firstCol, firstCol, n + 1, n + 1).real() = b.matrixU();\n    else \n    {\n      m_naiveU.row(0).segment(firstCol, n + 1).real() = b.matrixU().row(0);\n      m_naiveU.row(1).segment(firstCol, n + 1).real() = b.matrixU().row(n);\n    }\n    if (m_compV) m_naiveV.block(firstRowW, firstColW, n, n).real() = b.matrixV();\n    m_computed.block(firstCol + shift, firstCol + shift, n + 1, n).setZero();\n    m_computed.diagonal().segment(firstCol + shift, n) = b.singularValues().head(n);\n    return;\n  }\n  // We use the divide and conquer algorithm\n  alphaK =  m_computed(firstCol + k, firstCol + k);\n  betaK = m_computed(firstCol + k + 1, firstCol + k);\n  // The divide must be done in that order in order to have good results. Divide change the data inside the submatrices\n  // and the divide of the right submatrice reads one column of the left submatrice. That's why we need to treat the \n  // right submatrix before the left one. \n  divide(k + 1 + firstCol, lastCol, k + 1 + firstRowW, k + 1 + firstColW, shift);\n  if (m_info != Success && m_info != NoConvergence) return;\n  divide(firstCol, k - 1 + firstCol, firstRowW, firstColW + 1, shift + 1);\n  if (m_info != Success && m_info != NoConvergence) return;\n\n  if (m_compU)\n  {\n    lambda = m_naiveU(firstCol + k, firstCol + k);\n    phi = m_naiveU(firstCol + k + 1, lastCol + 1);\n  } \n  else \n  {\n    lambda = m_naiveU(1, firstCol + k);\n    phi = m_naiveU(0, lastCol + 1);\n  }\n  r0 = sqrt((abs(alphaK * lambda) * abs(alphaK * lambda)) + abs(betaK * phi) * abs(betaK * phi));\n  if (m_compU)\n  {\n    l = m_naiveU.row(firstCol + k).segment(firstCol, k);\n    f = m_naiveU.row(firstCol + k + 1).segment(firstCol + k + 1, n - k - 1);\n  } \n  else \n  {\n    l = m_naiveU.row(1).segment(firstCol, k);\n    f = m_naiveU.row(0).segment(firstCol + k + 1, n - k - 1);\n  }\n  if (m_compV) m_naiveV(firstRowW+k, firstColW) = Literal(1);\n  if (r0<considerZero)\n  {\n    c0 = Literal(1);\n    s0 = Literal(0);\n  }\n  else\n  {\n    c0 = alphaK * lambda / r0;\n    s0 = betaK * phi / r0;\n  }\n  \n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  assert(m_naiveU.allFinite());\n  assert(m_naiveV.allFinite());\n  assert(m_computed.allFinite());\n#endif\n  \n  if (m_compU)\n  {\n    MatrixXr q1 (m_naiveU.col(firstCol + k).segment(firstCol, k + 1));     \n    // we shiftW Q1 to the right\n    for (Index i = firstCol + k - 1; i >= firstCol; i--) \n      m_naiveU.col(i + 1).segment(firstCol, k + 1) = m_naiveU.col(i).segment(firstCol, k + 1);\n    // we shift q1 at the left with a factor c0\n    m_naiveU.col(firstCol).segment( firstCol, k + 1) = (q1 * c0);\n    // last column = q1 * - s0\n    m_naiveU.col(lastCol + 1).segment(firstCol, k + 1) = (q1 * ( - s0));\n    // first column = q2 * s0\n    m_naiveU.col(firstCol).segment(firstCol + k + 1, n - k) = m_naiveU.col(lastCol + 1).segment(firstCol + k + 1, n - k) * s0; \n    // q2 *= c0\n    m_naiveU.col(lastCol + 1).segment(firstCol + k + 1, n - k) *= c0;\n  } \n  else \n  {\n    RealScalar q1 = m_naiveU(0, firstCol + k);\n    // we shift Q1 to the right\n    for (Index i = firstCol + k - 1; i >= firstCol; i--) \n      m_naiveU(0, i + 1) = m_naiveU(0, i);\n    // we shift q1 at the left with a factor c0\n    m_naiveU(0, firstCol) = (q1 * c0);\n    // last column = q1 * - s0\n    m_naiveU(0, lastCol + 1) = (q1 * ( - s0));\n    // first column = q2 * s0\n    m_naiveU(1, firstCol) = m_naiveU(1, lastCol + 1) *s0; \n    // q2 *= c0\n    m_naiveU(1, lastCol + 1) *= c0;\n    m_naiveU.row(1).segment(firstCol + 1, k).setZero();\n    m_naiveU.row(0).segment(firstCol + k + 1, n - k - 1).setZero();\n  }\n  \n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  assert(m_naiveU.allFinite());\n  assert(m_naiveV.allFinite());\n  assert(m_computed.allFinite());\n#endif\n  \n  m_computed(firstCol + shift, firstCol + shift) = r0;\n  m_computed.col(firstCol + shift).segment(firstCol + shift + 1, k) = alphaK * l.transpose().real();\n  m_computed.col(firstCol + shift).segment(firstCol + shift + k + 1, n - k - 1) = betaK * f.transpose().real();\n\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n  ArrayXr tmp1 = (m_computed.block(firstCol+shift, firstCol+shift, n, n)).jacobiSvd().singularValues();\n#endif\n  // Second part: try to deflate singular values in combined matrix\n  deflation(firstCol, lastCol, k, firstRowW, firstColW, shift);\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n  ArrayXr tmp2 = (m_computed.block(firstCol+shift, firstCol+shift, n, n)).jacobiSvd().singularValues();\n  std::cout << \"\\n\\nj1 = \" << tmp1.transpose().format(bdcsvdfmt) << \"\\n\";\n  std::cout << \"j2 = \" << tmp2.transpose().format(bdcsvdfmt) << \"\\n\\n\";\n  std::cout << \"err:      \" << ((tmp1-tmp2).abs()>1e-12*tmp2.abs()).transpose() << \"\\n\";\n  static int count = 0;\n  std::cout << \"# \" << ++count << \"\\n\\n\";\n  assert((tmp1-tmp2).matrix().norm() < 1e-14*tmp2.matrix().norm());\n//   assert(count<681);\n//   assert(((tmp1-tmp2).abs()<1e-13*tmp2.abs()).all());\n#endif\n  \n  // Third part: compute SVD of combined matrix\n  MatrixXr UofSVD, VofSVD;\n  VectorType singVals;\n  computeSVDofM(firstCol + shift, n, UofSVD, singVals, VofSVD);\n  \n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  assert(UofSVD.allFinite());\n  assert(VofSVD.allFinite());\n#endif\n  \n  if (m_compU)\n    structured_update(m_naiveU.block(firstCol, firstCol, n + 1, n + 1), UofSVD, (n+2)/2);\n  else\n  {\n    Map<Matrix<RealScalar,2,Dynamic>,Aligned> tmp(m_workspace.data(),2,n+1);\n    tmp.noalias() = m_naiveU.middleCols(firstCol, n+1) * UofSVD;\n    m_naiveU.middleCols(firstCol, n + 1) = tmp;\n  }\n  \n  if (m_compV)  structured_update(m_naiveV.block(firstRowW, firstColW, n, n), VofSVD, (n+1)/2);\n  \n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  assert(m_naiveU.allFinite());\n  assert(m_naiveV.allFinite());\n  assert(m_computed.allFinite());\n#endif\n  \n  m_computed.block(firstCol + shift, firstCol + shift, n, n).setZero();\n  m_computed.block(firstCol + shift, firstCol + shift, n, n).diagonal() = singVals;\n}// end divide\n\n// Compute SVD of m_computed.block(firstCol, firstCol, n + 1, n); this block only has non-zeros in\n// the first column and on the diagonal and has undergone deflation, so diagonal is in increasing\n// order except for possibly the (0,0) entry. The computed SVD is stored U, singVals and V, except\n// that if m_compV is false, then V is not computed. Singular values are sorted in decreasing order.\n//\n// TODO Opportunities for optimization: better root finding algo, better stopping criterion, better\n// handling of round-off errors, be consistent in ordering\n// For instance, to solve the secular equation using FMM, see http://www.stat.uchicago.edu/~lekheng/courses/302/classics/greengard-rokhlin.pdf\ntemplate <typename MatrixType>\nvoid BDCSVD<MatrixType>::computeSVDofM(Eigen::Index firstCol, Eigen::Index n, MatrixXr& U, VectorType& singVals, MatrixXr& V)\n{\n  const RealScalar considerZero = (std::numeric_limits<RealScalar>::min)();\n  using std::abs;\n  ArrayRef col0 = m_computed.col(firstCol).segment(firstCol, n);\n  m_workspace.head(n) =  m_computed.block(firstCol, firstCol, n, n).diagonal();\n  ArrayRef diag = m_workspace.head(n);\n  diag(0) = Literal(0);\n\n  // Allocate space for singular values and vectors\n  singVals.resize(n);\n  U.resize(n+1, n+1);\n  if (m_compV) V.resize(n, n);\n\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n  if (col0.hasNaN() || diag.hasNaN())\n    std::cout << \"\\n\\nHAS NAN\\n\\n\";\n#endif\n  \n  // Many singular values might have been deflated, the zero ones have been moved to the end,\n  // but others are interleaved and we must ignore them at this stage.\n  // To this end, let's compute a permutation skipping them:\n  Index actual_n = n;\n  while(actual_n>1 && diag(actual_n-1)==Literal(0)) {--actual_n; eigen_internal_assert(col0(actual_n)==Literal(0)); }\n  Index m = 0; // size of the deflated problem\n  for(Index k=0;k<actual_n;++k)\n    if(abs(col0(k))>considerZero)\n      m_workspaceI(m++) = k;\n  Map<ArrayXi> perm(m_workspaceI.data(),m);\n  \n  Map<ArrayXr> shifts(m_workspace.data()+1*n, n);\n  Map<ArrayXr> mus(m_workspace.data()+2*n, n);\n  Map<ArrayXr> zhat(m_workspace.data()+3*n, n);\n\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n  std::cout << \"computeSVDofM using:\\n\";\n  std::cout << \"  z: \" << col0.transpose() << \"\\n\";\n  std::cout << \"  d: \" << diag.transpose() << \"\\n\";\n#endif\n  \n  // Compute singVals, shifts, and mus\n  computeSingVals(col0, diag, perm, singVals, shifts, mus);\n  \n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n  std::cout << \"  j:        \" << (m_computed.block(firstCol, firstCol, n, n)).jacobiSvd().singularValues().transpose().reverse() << \"\\n\\n\";\n  std::cout << \"  sing-val: \" << singVals.transpose() << \"\\n\";\n  std::cout << \"  mu:       \" << mus.transpose() << \"\\n\";\n  std::cout << \"  shift:    \" << shifts.transpose() << \"\\n\";\n  \n  {\n    std::cout << \"\\n\\n    mus:    \" << mus.head(actual_n).transpose() << \"\\n\\n\";\n    std::cout << \"    check1 (expect0) : \" << ((singVals.array()-(shifts+mus)) / singVals.array()).head(actual_n).transpose() << \"\\n\\n\";\n    assert((((singVals.array()-(shifts+mus)) / singVals.array()).head(actual_n) >= 0).all());\n    std::cout << \"    check2 (>0)      : \" << ((singVals.array()-diag) / singVals.array()).head(actual_n).transpose() << \"\\n\\n\";\n    assert((((singVals.array()-diag) / singVals.array()).head(actual_n) >= 0).all());\n  }\n#endif\n  \n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  assert(singVals.allFinite());\n  assert(mus.allFinite());\n  assert(shifts.allFinite());\n#endif\n  \n  // Compute zhat\n  perturbCol0(col0, diag, perm, singVals, shifts, mus, zhat);\n#ifdef  EIGEN_BDCSVD_DEBUG_VERBOSE\n  std::cout << \"  zhat: \" << zhat.transpose() << \"\\n\";\n#endif\n  \n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  assert(zhat.allFinite());\n#endif\n  \n  computeSingVecs(zhat, diag, perm, singVals, shifts, mus, U, V);\n  \n#ifdef  EIGEN_BDCSVD_DEBUG_VERBOSE\n  std::cout << \"U^T U: \" << (U.transpose() * U - MatrixXr(MatrixXr::Identity(U.cols(),U.cols()))).norm() << \"\\n\";\n  std::cout << \"V^T V: \" << (V.transpose() * V - MatrixXr(MatrixXr::Identity(V.cols(),V.cols()))).norm() << \"\\n\";\n#endif\n  \n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  assert(m_naiveU.allFinite());\n  assert(m_naiveV.allFinite());\n  assert(m_computed.allFinite());\n  assert(U.allFinite());\n  assert(V.allFinite());\n//   assert((U.transpose() * U - MatrixXr(MatrixXr::Identity(U.cols(),U.cols()))).norm() < 100*NumTraits<RealScalar>::epsilon() * n);\n//   assert((V.transpose() * V - MatrixXr(MatrixXr::Identity(V.cols(),V.cols()))).norm() < 100*NumTraits<RealScalar>::epsilon() * n);\n#endif\n  \n  // Because of deflation, the singular values might not be completely sorted.\n  // Fortunately, reordering them is a O(n) problem\n  for(Index i=0; i<actual_n-1; ++i)\n  {\n    if(singVals(i)>singVals(i+1))\n    {\n      using std::swap;\n      swap(singVals(i),singVals(i+1));\n      U.col(i).swap(U.col(i+1));\n      if(m_compV) V.col(i).swap(V.col(i+1));\n    }\n  }\n\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  {\n    bool singular_values_sorted = (((singVals.segment(1,actual_n-1)-singVals.head(actual_n-1))).array() >= 0).all();\n    if(!singular_values_sorted)\n      std::cout << \"Singular values are not sorted: \" << singVals.segment(1,actual_n).transpose() << \"\\n\";\n    assert(singular_values_sorted);\n  }\n#endif\n  \n  // Reverse order so that singular values in increased order\n  // Because of deflation, the zeros singular-values are already at the end\n  singVals.head(actual_n).reverseInPlace();\n  U.leftCols(actual_n).rowwise().reverseInPlace();\n  if (m_compV) V.leftCols(actual_n).rowwise().reverseInPlace();\n  \n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n  JacobiSVD<MatrixXr> jsvd(m_computed.block(firstCol, firstCol, n, n) );\n  std::cout << \"  * j:        \" << jsvd.singularValues().transpose() << \"\\n\\n\";\n  std::cout << \"  * sing-val: \" << singVals.transpose() << \"\\n\";\n//   std::cout << \"  * err:      \" << ((jsvd.singularValues()-singVals)>1e-13*singVals.norm()).transpose() << \"\\n\";\n#endif\n}\n\ntemplate <typename MatrixType>\ntypename BDCSVD<MatrixType>::RealScalar BDCSVD<MatrixType>::secularEq(RealScalar mu, const ArrayRef& col0, const ArrayRef& diag, const IndicesRef &perm, const ArrayRef& diagShifted, RealScalar shift)\n{\n  Index m = perm.size();\n  RealScalar res = Literal(1);\n  for(Index i=0; i<m; ++i)\n  {\n    Index j = perm(i);\n    // The following expression could be rewritten to involve only a single division,\n    // but this would make the expression more sensitive to overflow.\n    res += (col0(j) / (diagShifted(j) - mu)) * (col0(j) / (diag(j) + shift + mu));\n  }\n  return res;\n\n}\n\ntemplate <typename MatrixType>\nvoid BDCSVD<MatrixType>::computeSingVals(const ArrayRef& col0, const ArrayRef& diag, const IndicesRef &perm,\n                                         VectorType& singVals, ArrayRef shifts, ArrayRef mus)\n{\n  using std::abs;\n  using std::swap;\n  using std::sqrt;\n\n  Index n = col0.size();\n  Index actual_n = n;\n  // Note that here actual_n is computed based on col0(i)==0 instead of diag(i)==0 as above\n  // because 1) we have diag(i)==0 => col0(i)==0 and 2) if col0(i)==0, then diag(i) is already a singular value.\n  while(actual_n>1 && col0(actual_n-1)==Literal(0)) --actual_n;\n\n  for (Index k = 0; k < n; ++k)\n  {\n    if (col0(k) == Literal(0) || actual_n==1)\n    {\n      // if col0(k) == 0, then entry is deflated, so singular value is on diagonal\n      // if actual_n==1, then the deflated problem is already diagonalized\n      singVals(k) = k==0 ? col0(0) : diag(k);\n      mus(k) = Literal(0);\n      shifts(k) = k==0 ? col0(0) : diag(k);\n      continue;\n    } \n\n    // otherwise, use secular equation to find singular value\n    RealScalar left = diag(k);\n    RealScalar right; // was: = (k != actual_n-1) ? diag(k+1) : (diag(actual_n-1) + col0.matrix().norm());\n    if(k==actual_n-1)\n      right = (diag(actual_n-1) + col0.matrix().norm());\n    else\n    {\n      // Skip deflated singular values,\n      // recall that at this stage we assume that z[j]!=0 and all entries for which z[j]==0 have been put aside.\n      // This should be equivalent to using perm[]\n      Index l = k+1;\n      while(col0(l)==Literal(0)) { ++l; eigen_internal_assert(l<actual_n); }\n      right = diag(l);\n    }\n\n    // first decide whether it's closer to the left end or the right end\n    RealScalar mid = left + (right-left) / Literal(2);\n    RealScalar fMid = secularEq(mid, col0, diag, perm, diag, Literal(0));\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n    std::cout << \"right-left = \" << right-left << \"\\n\";\n//     std::cout << \"fMid = \" << fMid << \" \" << secularEq(mid-left, col0, diag, perm, ArrayXr(diag-left), left)\n//                            << \" \" << secularEq(mid-right, col0, diag, perm, ArrayXr(diag-right), right)   << \"\\n\";\n    std::cout << \"     = \" << secularEq(left+RealScalar(0.000001)*(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.1)     *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.2)     *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.3)     *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.4)     *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.49)    *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.5)     *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.51)    *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.6)     *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.7)     *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.8)     *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.9)     *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.999999)*(right-left), col0, diag, perm, diag, 0) << \"\\n\";\n#endif\n    RealScalar shift = (k == actual_n-1 || fMid > Literal(0)) ? left : right;\n    \n    // measure everything relative to shift\n    Map<ArrayXr> diagShifted(m_workspace.data()+4*n, n);\n    diagShifted = diag - shift;\n\n    if(k!=actual_n-1)\n    {\n      // check that after the shift, f(mid) is still negative:\n      RealScalar midShifted = (right - left) / RealScalar(2);\n      if(shift==right)\n        midShifted = -midShifted;\n      RealScalar fMidShifted = secularEq(midShifted, col0, diag, perm, diagShifted, shift);\n      if(fMidShifted>0)\n      {\n        // fMid was erroneous, fix it:\n        shift =  fMidShifted > Literal(0) ? left : right;\n        diagShifted = diag - shift;\n      }\n    }\n    \n    // initial guess\n    RealScalar muPrev, muCur;\n    if (shift == left)\n    {\n      muPrev = (right - left) * RealScalar(0.1);\n      if (k == actual_n-1) muCur = right - left;\n      else                 muCur = (right - left) * RealScalar(0.5);\n    }\n    else\n    {\n      muPrev = -(right - left) * RealScalar(0.1);\n      muCur = -(right - left) * RealScalar(0.5);\n    }\n\n    RealScalar fPrev = secularEq(muPrev, col0, diag, perm, diagShifted, shift);\n    RealScalar fCur = secularEq(muCur, col0, diag, perm, diagShifted, shift);\n    if (abs(fPrev) < abs(fCur))\n    {\n      swap(fPrev, fCur);\n      swap(muPrev, muCur);\n    }\n\n    // rational interpolation: fit a function of the form a / mu + b through the two previous\n    // iterates and use its zero to compute the next iterate\n    bool useBisection = fPrev*fCur>Literal(0);\n    while (fCur!=Literal(0) && abs(muCur - muPrev) > Literal(8) * NumTraits<RealScalar>::epsilon() * numext::maxi<RealScalar>(abs(muCur), abs(muPrev)) && abs(fCur - fPrev)>NumTraits<RealScalar>::epsilon() && !useBisection)\n    {\n      ++m_numIters;\n\n      // Find a and b such that the function f(mu) = a / mu + b matches the current and previous samples.\n      RealScalar a = (fCur - fPrev) / (Literal(1)/muCur - Literal(1)/muPrev);\n      RealScalar b = fCur - a / muCur;\n      // And find mu such that f(mu)==0:\n      RealScalar muZero = -a/b;\n      RealScalar fZero = secularEq(muZero, col0, diag, perm, diagShifted, shift);\n\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n      assert((numext::isfinite)(fZero));\n#endif\n      \n      muPrev = muCur;\n      fPrev = fCur;\n      muCur = muZero;\n      fCur = fZero;\n      \n      if (shift == left  && (muCur < Literal(0) || muCur > right - left)) useBisection = true;\n      if (shift == right && (muCur < -(right - left) || muCur > Literal(0))) useBisection = true;\n      if (abs(fCur)>abs(fPrev)) useBisection = true;\n    }\n\n    // fall back on bisection method if rational interpolation did not work\n    if (useBisection)\n    {\n#ifdef  EIGEN_BDCSVD_DEBUG_VERBOSE\n      std::cout << \"useBisection for k = \" << k << \", actual_n = \" << actual_n << \"\\n\";\n#endif\n      RealScalar leftShifted, rightShifted;\n      if (shift == left)\n      {\n        // to avoid overflow, we must have mu > max(real_min, |z(k)|/sqrt(real_max)),\n        // the factor 2 is to be more conservative\n        leftShifted = numext::maxi<RealScalar>( (std::numeric_limits<RealScalar>::min)(), Literal(2) * abs(col0(k)) / sqrt((std::numeric_limits<RealScalar>::max)()) );\n\n        // check that we did it right:\n        eigen_internal_assert( (numext::isfinite)( (col0(k)/leftShifted)*(col0(k)/(diag(k)+shift+leftShifted)) ) );\n        // I don't understand why the case k==0 would be special there:\n        // if (k == 0) rightShifted = right - left; else\n        rightShifted = (k==actual_n-1) ? right : ((right - left) * RealScalar(0.51)); // theoretically we can take 0.5, but let's be safe\n      }\n      else\n      {\n        leftShifted = -(right - left) * RealScalar(0.51);\n        if(k+1<n)\n          rightShifted = -numext::maxi<RealScalar>( (std::numeric_limits<RealScalar>::min)(), abs(col0(k+1)) / sqrt((std::numeric_limits<RealScalar>::max)()) );\n        else\n          rightShifted = -(std::numeric_limits<RealScalar>::min)();\n      }\n\n      RealScalar fLeft = secularEq(leftShifted, col0, diag, perm, diagShifted, shift);\n      eigen_internal_assert(fLeft<Literal(0));\n\n#if defined EIGEN_INTERNAL_DEBUGGING || defined EIGEN_BDCSVD_SANITY_CHECKS\n      RealScalar fRight = secularEq(rightShifted, col0, diag, perm, diagShifted, shift);\n#endif\n\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n      if(!(numext::isfinite)(fLeft))\n        std::cout << \"f(\" << leftShifted << \") =\" << fLeft << \" ; \" << left << \" \" << shift << \" \" << right << \"\\n\";\n      assert((numext::isfinite)(fLeft));\n\n      if(!(numext::isfinite)(fRight))\n        std::cout << \"f(\" << rightShifted << \") =\" << fRight << \" ; \" << left << \" \" << shift << \" \" << right << \"\\n\";\n      // assert((numext::isfinite)(fRight));\n#endif\n    \n#ifdef  EIGEN_BDCSVD_DEBUG_VERBOSE\n      if(!(fLeft * fRight<0))\n      {\n        std::cout << \"f(leftShifted) using  leftShifted=\" << leftShifted << \" ;  diagShifted(1:10):\" << diagShifted.head(10).transpose()  << \"\\n ; \"\n                  << \"left==shift=\" << bool(left==shift) << \" ; left-shift = \" << (left-shift) << \"\\n\";\n        std::cout << \"k=\" << k << \", \" <<  fLeft << \" * \" << fRight << \" == \" << fLeft * fRight << \"  ;  \"\n                  << \"[\" << left << \" .. \" << right << \"] -> [\" << leftShifted << \" \" << rightShifted << \"], shift=\" << shift\n                  << \" ,  f(right)=\" << secularEq(0,     col0, diag, perm, diagShifted, shift)\n                           << \" == \" << secularEq(right, col0, diag, perm, diag, 0) << \" == \" << fRight << \"\\n\";\n      }\n#endif\n      eigen_internal_assert(fLeft * fRight < Literal(0));\n\n      if(fLeft<Literal(0))\n      {\n        while (rightShifted - leftShifted > Literal(2) * NumTraits<RealScalar>::epsilon() * numext::maxi<RealScalar>(abs(leftShifted), abs(rightShifted)))\n        {\n          RealScalar midShifted = (leftShifted + rightShifted) / Literal(2);\n          fMid = secularEq(midShifted, col0, diag, perm, diagShifted, shift);\n          eigen_internal_assert((numext::isfinite)(fMid));\n\n          if (fLeft * fMid < Literal(0))\n          {\n            rightShifted = midShifted;\n          }\n          else\n          {\n            leftShifted = midShifted;\n            fLeft = fMid;\n          }\n        }\n        muCur = (leftShifted + rightShifted) / Literal(2);\n      }\n      else \n      {\n        // We have a problem as shifting on the left or right give either a positive or negative value\n        // at the middle of [left,right]...\n        // Instead fo abbording or entering an infinite loop,\n        // let's just use the middle as the estimated zero-crossing:\n        muCur = (right - left) * RealScalar(0.5);\n        if(shift == right)\n          muCur = -muCur;\n      }\n    }\n      \n    singVals[k] = shift + muCur;\n    shifts[k] = shift;\n    mus[k] = muCur;\n\n#ifdef  EIGEN_BDCSVD_DEBUG_VERBOSE\n    if(k+1<n)\n      std::cout << \"found \" << singVals[k] << \" == \" << shift << \" + \" << muCur << \" from \" << diag(k) << \" .. \"  << diag(k+1) << \"\\n\";\n#endif\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n    assert(k==0 || singVals[k]>=singVals[k-1]);\n    assert(singVals[k]>=diag(k));\n#endif\n\n    // perturb singular value slightly if it equals diagonal entry to avoid division by zero later\n    // (deflation is supposed to avoid this from happening)\n    // - this does no seem to be necessary anymore -\n//     if (singVals[k] == left) singVals[k] *= 1 + NumTraits<RealScalar>::epsilon();\n//     if (singVals[k] == right) singVals[k] *= 1 - NumTraits<RealScalar>::epsilon();\n  }\n}\n\n\n// zhat is perturbation of col0 for which singular vectors can be computed stably (see Section 3.1)\ntemplate <typename MatrixType>\nvoid BDCSVD<MatrixType>::perturbCol0\n   (const ArrayRef& col0, const ArrayRef& diag, const IndicesRef &perm, const VectorType& singVals,\n    const ArrayRef& shifts, const ArrayRef& mus, ArrayRef zhat)\n{\n  using std::sqrt;\n  Index n = col0.size();\n  Index m = perm.size();\n  if(m==0)\n  {\n    zhat.setZero();\n    return;\n  }\n  Index lastIdx = perm(m-1);\n  // The offset permits to skip deflated entries while computing zhat\n  for (Index k = 0; k < n; ++k)\n  {\n    if (col0(k) == Literal(0)) // deflated\n      zhat(k) = Literal(0);\n    else\n    {\n      // see equation (3.6)\n      RealScalar dk = diag(k);\n      RealScalar prod = (singVals(lastIdx) + dk) * (mus(lastIdx) + (shifts(lastIdx) - dk));\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n      if(prod<0) {\n        std::cout << \"k = \" << k << \" ;  z(k)=\" << col0(k) << \", diag(k)=\" << dk << \"\\n\";\n        std::cout << \"prod = \" << \"(\" << singVals(lastIdx) << \" + \" << dk << \") * (\" << mus(lastIdx) << \" + (\" << shifts(lastIdx) << \" - \" << dk << \"))\" << \"\\n\";\n        std::cout << \"     = \" << singVals(lastIdx) + dk << \" * \" << mus(lastIdx) + (shifts(lastIdx) - dk) <<  \"\\n\";\n      }\n      assert(prod>=0);\n#endif\n\n      for(Index l = 0; l<m; ++l)\n      {\n        Index i = perm(l);\n        if(i!=k)\n        {\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n          if(i>=k && (l==0 || l-1>=m))\n          {\n            std::cout << \"Error in perturbCol0\\n\";\n            std::cout << \"  \" << k << \"/\" << n << \" \"  << l << \"/\" << m << \" \" << i << \"/\" << n << \" ; \" << col0(k) << \" \" << diag(k) << \" \"  <<  \"\\n\";\n            std::cout << \"  \" <<diag(i) << \"\\n\";\n            Index j = (i<k /*|| l==0*/) ? i : perm(l-1);\n            std::cout << \"  \" << \"j=\" << j << \"\\n\";\n          }\n#endif\n          Index j = i<k ? i : perm(l-1);\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n          if(!(dk!=Literal(0) || diag(i)!=Literal(0)))\n          {\n            std::cout << \"k=\" << k << \", i=\" << i << \", l=\" << l << \", perm.size()=\" << perm.size() << \"\\n\";\n          }\n          assert(dk!=Literal(0) || diag(i)!=Literal(0));\n#endif\n          prod *= ((singVals(j)+dk) / ((diag(i)+dk))) * ((mus(j)+(shifts(j)-dk)) / ((diag(i)-dk)));\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n          assert(prod>=0);\n#endif\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n          if(i!=k && numext::abs(((singVals(j)+dk)*(mus(j)+(shifts(j)-dk)))/((diag(i)+dk)*(diag(i)-dk)) - 1) > 0.9 )\n            std::cout << \"     \" << ((singVals(j)+dk)*(mus(j)+(shifts(j)-dk)))/((diag(i)+dk)*(diag(i)-dk)) << \" == (\" << (singVals(j)+dk) << \" * \" << (mus(j)+(shifts(j)-dk))\n                       << \") / (\" << (diag(i)+dk) << \" * \" << (diag(i)-dk) << \")\\n\";\n#endif\n        }\n      }\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n      std::cout << \"zhat(\" << k << \") =  sqrt( \" << prod << \")  ;  \" << (singVals(lastIdx) + dk) << \" * \" << mus(lastIdx) + shifts(lastIdx) << \" - \" << dk << \"\\n\";\n#endif\n      RealScalar tmp = sqrt(prod);\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n      assert((numext::isfinite)(tmp));\n#endif\n      zhat(k) = col0(k) > Literal(0) ? RealScalar(tmp) : RealScalar(-tmp);\n    }\n  }\n}\n\n// compute singular vectors\ntemplate <typename MatrixType>\nvoid BDCSVD<MatrixType>::computeSingVecs\n   (const ArrayRef& zhat, const ArrayRef& diag, const IndicesRef &perm, const VectorType& singVals,\n    const ArrayRef& shifts, const ArrayRef& mus, MatrixXr& U, MatrixXr& V)\n{\n  Index n = zhat.size();\n  Index m = perm.size();\n  \n  for (Index k = 0; k < n; ++k)\n  {\n    if (zhat(k) == Literal(0))\n    {\n      U.col(k) = VectorType::Unit(n+1, k);\n      if (m_compV) V.col(k) = VectorType::Unit(n, k);\n    }\n    else\n    {\n      U.col(k).setZero();\n      for(Index l=0;l<m;++l)\n      {\n        Index i = perm(l);\n        U(i,k) = zhat(i)/(((diag(i) - shifts(k)) - mus(k)) )/( (diag(i) + singVals[k]));\n      }\n      U(n,k) = Literal(0);\n      U.col(k).normalize();\n    \n      if (m_compV)\n      {\n        V.col(k).setZero();\n        for(Index l=1;l<m;++l)\n        {\n          Index i = perm(l);\n          V(i,k) = diag(i) * zhat(i) / (((diag(i) - shifts(k)) - mus(k)) )/( (diag(i) + singVals[k]));\n        }\n        V(0,k) = Literal(-1);\n        V.col(k).normalize();\n      }\n    }\n  }\n  U.col(n) = VectorType::Unit(n+1, n);\n}\n\n\n// page 12_13\n// i >= 1, di almost null and zi non null.\n// We use a rotation to zero out zi applied to the left of M\ntemplate <typename MatrixType>\nvoid BDCSVD<MatrixType>::deflation43(Eigen::Index firstCol, Eigen::Index shift, Eigen::Index i, Eigen::Index size)\n{\n  using std::abs;\n  using std::sqrt;\n  using std::pow;\n  Index start = firstCol + shift;\n  RealScalar c = m_computed(start, start);\n  RealScalar s = m_computed(start+i, start);\n  RealScalar r = numext::hypot(c,s);\n  if (r == Literal(0))\n  {\n    m_computed(start+i, start+i) = Literal(0);\n    return;\n  }\n  m_computed(start,start) = r;  \n  m_computed(start+i, start) = Literal(0);\n  m_computed(start+i, start+i) = Literal(0);\n  \n  JacobiRotation<RealScalar> J(c/r,-s/r);\n  if (m_compU)  m_naiveU.middleRows(firstCol, size+1).applyOnTheRight(firstCol, firstCol+i, J);\n  else          m_naiveU.applyOnTheRight(firstCol, firstCol+i, J);\n}// end deflation 43\n\n\n// page 13\n// i,j >= 1, i!=j and |di - dj| < epsilon * norm2(M)\n// We apply two rotations to have zj = 0;\n// TODO deflation44 is still broken and not properly tested\ntemplate <typename MatrixType>\nvoid BDCSVD<MatrixType>::deflation44(Eigen::Index firstColu , Eigen::Index firstColm, Eigen::Index firstRowW, Eigen::Index firstColW, Eigen::Index i, Eigen::Index j, Eigen::Index size)\n{\n  using std::abs;\n  using std::sqrt;\n  using std::conj;\n  using std::pow;\n  RealScalar c = m_computed(firstColm+i, firstColm);\n  RealScalar s = m_computed(firstColm+j, firstColm);\n  RealScalar r = sqrt(numext::abs2(c) + numext::abs2(s));\n#ifdef  EIGEN_BDCSVD_DEBUG_VERBOSE\n  std::cout << \"deflation 4.4: \" << i << \",\" << j << \" -> \" << c << \" \" << s << \" \" << r << \" ; \"\n    << m_computed(firstColm + i-1, firstColm)  << \" \"\n    << m_computed(firstColm + i, firstColm)  << \" \"\n    << m_computed(firstColm + i+1, firstColm) << \" \"\n    << m_computed(firstColm + i+2, firstColm) << \"\\n\";\n  std::cout << m_computed(firstColm + i-1, firstColm + i-1)  << \" \"\n    << m_computed(firstColm + i, firstColm+i)  << \" \"\n    << m_computed(firstColm + i+1, firstColm+i+1) << \" \"\n    << m_computed(firstColm + i+2, firstColm+i+2) << \"\\n\";\n#endif\n  if (r==Literal(0))\n  {\n    m_computed(firstColm + i, firstColm + i) = m_computed(firstColm + j, firstColm + j);\n    return;\n  }\n  c/=r;\n  s/=r;\n  m_computed(firstColm + i, firstColm) = r;\n  m_computed(firstColm + j, firstColm + j) = m_computed(firstColm + i, firstColm + i);\n  m_computed(firstColm + j, firstColm) = Literal(0);\n\n  JacobiRotation<RealScalar> J(c,-s);\n  if (m_compU)  m_naiveU.middleRows(firstColu, size+1).applyOnTheRight(firstColu + i, firstColu + j, J);\n  else          m_naiveU.applyOnTheRight(firstColu+i, firstColu+j, J);\n  if (m_compV)  m_naiveV.middleRows(firstRowW, size).applyOnTheRight(firstColW + i, firstColW + j, J);\n}// end deflation 44\n\n\n// acts on block from (firstCol+shift, firstCol+shift) to (lastCol+shift, lastCol+shift) [inclusive]\ntemplate <typename MatrixType>\nvoid BDCSVD<MatrixType>::deflation(Eigen::Index firstCol, Eigen::Index lastCol, Eigen::Index k, Eigen::Index firstRowW, Eigen::Index firstColW, Eigen::Index shift)\n{\n  using std::sqrt;\n  using std::abs;\n  const Index length = lastCol + 1 - firstCol;\n  \n  Block<MatrixXr,Dynamic,1> col0(m_computed, firstCol+shift, firstCol+shift, length, 1);\n  Diagonal<MatrixXr> fulldiag(m_computed);\n  VectorBlock<Diagonal<MatrixXr>,Dynamic> diag(fulldiag, firstCol+shift, length);\n  \n  const RealScalar considerZero = (std::numeric_limits<RealScalar>::min)();\n  RealScalar maxDiag = diag.tail((std::max)(Index(1),length-1)).cwiseAbs().maxCoeff();\n  RealScalar epsilon_strict = numext::maxi<RealScalar>(considerZero,NumTraits<RealScalar>::epsilon() * maxDiag);\n  RealScalar epsilon_coarse = Literal(8) * NumTraits<RealScalar>::epsilon() * numext::maxi<RealScalar>(col0.cwiseAbs().maxCoeff(), maxDiag);\n  \n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  assert(m_naiveU.allFinite());\n  assert(m_naiveV.allFinite());\n  assert(m_computed.allFinite());\n#endif\n\n#ifdef  EIGEN_BDCSVD_DEBUG_VERBOSE  \n  std::cout << \"\\ndeflate:\" << diag.head(k+1).transpose() << \"  |  \" << diag.segment(k+1,length-k-1).transpose() << \"\\n\";\n#endif\n  \n  //condition 4.1\n  if (diag(0) < epsilon_coarse)\n  { \n#ifdef  EIGEN_BDCSVD_DEBUG_VERBOSE\n    std::cout << \"deflation 4.1, because \" << diag(0) << \" < \" << epsilon_coarse << \"\\n\";\n#endif\n    diag(0) = epsilon_coarse;\n  }\n\n  //condition 4.2\n  for (Index i=1;i<length;++i)\n    if (abs(col0(i)) < epsilon_strict)\n    {\n#ifdef  EIGEN_BDCSVD_DEBUG_VERBOSE\n      std::cout << \"deflation 4.2, set z(\" << i << \") to zero because \" << abs(col0(i)) << \" < \" << epsilon_strict << \"  (diag(\" << i << \")=\" << diag(i) << \")\\n\";\n#endif\n      col0(i) = Literal(0);\n    }\n\n  //condition 4.3\n  for (Index i=1;i<length; i++)\n    if (diag(i) < epsilon_coarse)\n    {\n#ifdef  EIGEN_BDCSVD_DEBUG_VERBOSE\n      std::cout << \"deflation 4.3, cancel z(\" << i << \")=\" << col0(i) << \" because diag(\" << i << \")=\" << diag(i) << \" < \" << epsilon_coarse << \"\\n\";\n#endif\n      deflation43(firstCol, shift, i, length);\n    }\n\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  assert(m_naiveU.allFinite());\n  assert(m_naiveV.allFinite());\n  assert(m_computed.allFinite());\n#endif\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n  std::cout << \"to be sorted: \" << diag.transpose() << \"\\n\\n\";\n  std::cout << \"            : \" << col0.transpose() << \"\\n\\n\";\n#endif\n  {\n    // Check for total deflation\n    // If we have a total deflation, then we have to consider col0(0)==diag(0) as a singular value during sorting\n    bool total_deflation = (col0.tail(length-1).array()<considerZero).all();\n    \n    // Sort the diagonal entries, since diag(1:k-1) and diag(k:length) are already sorted, let's do a sorted merge.\n    // First, compute the respective permutation.\n    Index *permutation = m_workspaceI.data();\n    {\n      permutation[0] = 0;\n      Index p = 1;\n      \n      // Move deflated diagonal entries at the end.\n      for(Index i=1; i<length; ++i)\n        if(abs(diag(i))<considerZero)\n          permutation[p++] = i;\n        \n      Index i=1, j=k+1;\n      for( ; p < length; ++p)\n      {\n             if (i > k)             permutation[p] = j++;\n        else if (j >= length)       permutation[p] = i++;\n        else if (diag(i) < diag(j)) permutation[p] = j++;\n        else                        permutation[p] = i++;\n      }\n    }\n    \n    // If we have a total deflation, then we have to insert diag(0) at the right place\n    if(total_deflation)\n    {\n      for(Index i=1; i<length; ++i)\n      {\n        Index pi = permutation[i];\n        if(abs(diag(pi))<considerZero || diag(0)<diag(pi))\n          permutation[i-1] = permutation[i];\n        else\n        {\n          permutation[i-1] = 0;\n          break;\n        }\n      }\n    }\n    \n    // Current index of each col, and current column of each index\n    Index *realInd = m_workspaceI.data()+length;\n    Index *realCol = m_workspaceI.data()+2*length;\n    \n    for(int pos = 0; pos< length; pos++)\n    {\n      realCol[pos] = pos;\n      realInd[pos] = pos;\n    }\n    \n    for(Index i = total_deflation?0:1; i < length; i++)\n    {\n      const Index pi = permutation[length - (total_deflation ? i+1 : i)];\n      const Index J = realCol[pi];\n      \n      using std::swap;\n      // swap diagonal and first column entries:\n      swap(diag(i), diag(J));\n      if(i!=0 && J!=0) swap(col0(i), col0(J));\n\n      // change columns\n      if (m_compU) m_naiveU.col(firstCol+i).segment(firstCol, length + 1).swap(m_naiveU.col(firstCol+J).segment(firstCol, length + 1));\n      else         m_naiveU.col(firstCol+i).segment(0, 2)                .swap(m_naiveU.col(firstCol+J).segment(0, 2));\n      if (m_compV) m_naiveV.col(firstColW + i).segment(firstRowW, length).swap(m_naiveV.col(firstColW + J).segment(firstRowW, length));\n\n      //update real pos\n      const Index realI = realInd[i];\n      realCol[realI] = J;\n      realCol[pi] = i;\n      realInd[J] = realI;\n      realInd[i] = pi;\n    }\n  }\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n  std::cout << \"sorted: \" << diag.transpose().format(bdcsvdfmt) << \"\\n\";\n  std::cout << \"      : \" << col0.transpose() << \"\\n\\n\";\n#endif\n    \n  //condition 4.4\n  {\n    Index i = length-1;\n    while(i>0 && (abs(diag(i))<considerZero || abs(col0(i))<considerZero)) --i;\n    for(; i>1;--i)\n       if( (diag(i) - diag(i-1)) < NumTraits<RealScalar>::epsilon()*maxDiag )\n      {\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n        std::cout << \"deflation 4.4 with i = \" << i << \" because \" << diag(i) << \" - \" << diag(i-1) << \" == \" << (diag(i) - diag(i-1)) << \" < \" << NumTraits<RealScalar>::epsilon()*/*diag(i)*/maxDiag << \"\\n\";\n#endif\n        eigen_internal_assert(abs(diag(i) - diag(i-1))<epsilon_coarse && \" diagonal entries are not properly sorted\");\n        deflation44(firstCol, firstCol + shift, firstRowW, firstColW, i-1, i, length);\n      }\n  }\n  \n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  for(Index j=2;j<length;++j)\n    assert(diag(j-1)<=diag(j) || abs(diag(j))<considerZero);\n#endif\n  \n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  assert(m_naiveU.allFinite());\n  assert(m_naiveV.allFinite());\n  assert(m_computed.allFinite());\n#endif\n}//end deflation\n\n/** \\svd_module\n  *\n  * \\return the singular value decomposition of \\c *this computed by Divide & Conquer algorithm\n  *\n  * \\sa class BDCSVD\n  */\ntemplate<typename Derived>\nBDCSVD<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::bdcSvd(unsigned int computationOptions) const\n{\n  return BDCSVD<PlainObject>(*this, computationOptions);\n}\n\n} // end namespace Eigen\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SVD/JacobiSVD.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2013-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_JACOBISVD_H\n#define EIGEN_JACOBISVD_H\n\nnamespace Eigen { \n\nnamespace internal {\n// forward declaration (needed by ICC)\n// the empty body is required by MSVC\ntemplate<typename MatrixType, int QRPreconditioner,\n         bool IsComplex = NumTraits<typename MatrixType::Scalar>::IsComplex>\nstruct svd_precondition_2x2_block_to_be_real {};\n\n/*** QR preconditioners (R-SVD)\n ***\n *** Their role is to reduce the problem of computing the SVD to the case of a square matrix.\n *** This approach, known as R-SVD, is an optimization for rectangular-enough matrices, and is a requirement for\n *** JacobiSVD which by itself is only able to work on square matrices.\n ***/\n\nenum { PreconditionIfMoreColsThanRows, PreconditionIfMoreRowsThanCols };\n\ntemplate<typename MatrixType, int QRPreconditioner, int Case>\nstruct qr_preconditioner_should_do_anything\n{\n  enum { a = MatrixType::RowsAtCompileTime != Dynamic &&\n             MatrixType::ColsAtCompileTime != Dynamic &&\n             MatrixType::ColsAtCompileTime <= MatrixType::RowsAtCompileTime,\n         b = MatrixType::RowsAtCompileTime != Dynamic &&\n             MatrixType::ColsAtCompileTime != Dynamic &&\n             MatrixType::RowsAtCompileTime <= MatrixType::ColsAtCompileTime,\n         ret = !( (QRPreconditioner == NoQRPreconditioner) ||\n                  (Case == PreconditionIfMoreColsThanRows && bool(a)) ||\n                  (Case == PreconditionIfMoreRowsThanCols && bool(b)) )\n  };\n};\n\ntemplate<typename MatrixType, int QRPreconditioner, int Case,\n         bool DoAnything = qr_preconditioner_should_do_anything<MatrixType, QRPreconditioner, Case>::ret\n> struct qr_preconditioner_impl {};\n\ntemplate<typename MatrixType, int QRPreconditioner, int Case>\nclass qr_preconditioner_impl<MatrixType, QRPreconditioner, Case, false>\n{\npublic:\n  void allocate(const JacobiSVD<MatrixType, QRPreconditioner>&) {}\n  bool run(JacobiSVD<MatrixType, QRPreconditioner>&, const MatrixType&)\n  {\n    return false;\n  }\n};\n\n/*** preconditioner using FullPivHouseholderQR ***/\n\ntemplate<typename MatrixType>\nclass qr_preconditioner_impl<MatrixType, FullPivHouseholderQRPreconditioner, PreconditionIfMoreRowsThanCols, true>\n{\npublic:\n  typedef typename MatrixType::Scalar Scalar;\n  enum\n  {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n    MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime\n  };\n  typedef Matrix<Scalar, 1, RowsAtCompileTime, RowMajor, 1, MaxRowsAtCompileTime> WorkspaceType;\n\n  void allocate(const JacobiSVD<MatrixType, FullPivHouseholderQRPreconditioner>& svd)\n  {\n    if (svd.rows() != m_qr.rows() || svd.cols() != m_qr.cols())\n    {\n      m_qr.~QRType();\n      ::new (&m_qr) QRType(svd.rows(), svd.cols());\n    }\n    if (svd.m_computeFullU) m_workspace.resize(svd.rows());\n  }\n\n  bool run(JacobiSVD<MatrixType, FullPivHouseholderQRPreconditioner>& svd, const MatrixType& matrix)\n  {\n    if(matrix.rows() > matrix.cols())\n    {\n      m_qr.compute(matrix);\n      svd.m_workMatrix = m_qr.matrixQR().block(0,0,matrix.cols(),matrix.cols()).template triangularView<Upper>();\n      if(svd.m_computeFullU) m_qr.matrixQ().evalTo(svd.m_matrixU, m_workspace);\n      if(svd.computeV()) svd.m_matrixV = m_qr.colsPermutation();\n      return true;\n    }\n    return false;\n  }\nprivate:\n  typedef FullPivHouseholderQR<MatrixType> QRType;\n  QRType m_qr;\n  WorkspaceType m_workspace;\n};\n\ntemplate<typename MatrixType>\nclass qr_preconditioner_impl<MatrixType, FullPivHouseholderQRPreconditioner, PreconditionIfMoreColsThanRows, true>\n{\npublic:\n  typedef typename MatrixType::Scalar Scalar;\n  enum\n  {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n    MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n    MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime,\n    Options = MatrixType::Options\n  };\n\n  typedef typename internal::make_proper_matrix_type<\n    Scalar, ColsAtCompileTime, RowsAtCompileTime, Options, MaxColsAtCompileTime, MaxRowsAtCompileTime\n  >::type TransposeTypeWithSameStorageOrder;\n\n  void allocate(const JacobiSVD<MatrixType, FullPivHouseholderQRPreconditioner>& svd)\n  {\n    if (svd.cols() != m_qr.rows() || svd.rows() != m_qr.cols())\n    {\n      m_qr.~QRType();\n      ::new (&m_qr) QRType(svd.cols(), svd.rows());\n    }\n    m_adjoint.resize(svd.cols(), svd.rows());\n    if (svd.m_computeFullV) m_workspace.resize(svd.cols());\n  }\n\n  bool run(JacobiSVD<MatrixType, FullPivHouseholderQRPreconditioner>& svd, const MatrixType& matrix)\n  {\n    if(matrix.cols() > matrix.rows())\n    {\n      m_adjoint = matrix.adjoint();\n      m_qr.compute(m_adjoint);\n      svd.m_workMatrix = m_qr.matrixQR().block(0,0,matrix.rows(),matrix.rows()).template triangularView<Upper>().adjoint();\n      if(svd.m_computeFullV) m_qr.matrixQ().evalTo(svd.m_matrixV, m_workspace);\n      if(svd.computeU()) svd.m_matrixU = m_qr.colsPermutation();\n      return true;\n    }\n    else return false;\n  }\nprivate:\n  typedef FullPivHouseholderQR<TransposeTypeWithSameStorageOrder> QRType;\n  QRType m_qr;\n  TransposeTypeWithSameStorageOrder m_adjoint;\n  typename internal::plain_row_type<MatrixType>::type m_workspace;\n};\n\n/*** preconditioner using ColPivHouseholderQR ***/\n\ntemplate<typename MatrixType>\nclass qr_preconditioner_impl<MatrixType, ColPivHouseholderQRPreconditioner, PreconditionIfMoreRowsThanCols, true>\n{\npublic:\n  void allocate(const JacobiSVD<MatrixType, ColPivHouseholderQRPreconditioner>& svd)\n  {\n    if (svd.rows() != m_qr.rows() || svd.cols() != m_qr.cols())\n    {\n      m_qr.~QRType();\n      ::new (&m_qr) QRType(svd.rows(), svd.cols());\n    }\n    if (svd.m_computeFullU) m_workspace.resize(svd.rows());\n    else if (svd.m_computeThinU) m_workspace.resize(svd.cols());\n  }\n\n  bool run(JacobiSVD<MatrixType, ColPivHouseholderQRPreconditioner>& svd, const MatrixType& matrix)\n  {\n    if(matrix.rows() > matrix.cols())\n    {\n      m_qr.compute(matrix);\n      svd.m_workMatrix = m_qr.matrixQR().block(0,0,matrix.cols(),matrix.cols()).template triangularView<Upper>();\n      if(svd.m_computeFullU) m_qr.householderQ().evalTo(svd.m_matrixU, m_workspace);\n      else if(svd.m_computeThinU)\n      {\n        svd.m_matrixU.setIdentity(matrix.rows(), matrix.cols());\n        m_qr.householderQ().applyThisOnTheLeft(svd.m_matrixU, m_workspace);\n      }\n      if(svd.computeV()) svd.m_matrixV = m_qr.colsPermutation();\n      return true;\n    }\n    return false;\n  }\n\nprivate:\n  typedef ColPivHouseholderQR<MatrixType> QRType;\n  QRType m_qr;\n  typename internal::plain_col_type<MatrixType>::type m_workspace;\n};\n\ntemplate<typename MatrixType>\nclass qr_preconditioner_impl<MatrixType, ColPivHouseholderQRPreconditioner, PreconditionIfMoreColsThanRows, true>\n{\npublic:\n  typedef typename MatrixType::Scalar Scalar;\n  enum\n  {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n    MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n    MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime,\n    Options = MatrixType::Options\n  };\n\n  typedef typename internal::make_proper_matrix_type<\n    Scalar, ColsAtCompileTime, RowsAtCompileTime, Options, MaxColsAtCompileTime, MaxRowsAtCompileTime\n  >::type TransposeTypeWithSameStorageOrder;\n\n  void allocate(const JacobiSVD<MatrixType, ColPivHouseholderQRPreconditioner>& svd)\n  {\n    if (svd.cols() != m_qr.rows() || svd.rows() != m_qr.cols())\n    {\n      m_qr.~QRType();\n      ::new (&m_qr) QRType(svd.cols(), svd.rows());\n    }\n    if (svd.m_computeFullV) m_workspace.resize(svd.cols());\n    else if (svd.m_computeThinV) m_workspace.resize(svd.rows());\n    m_adjoint.resize(svd.cols(), svd.rows());\n  }\n\n  bool run(JacobiSVD<MatrixType, ColPivHouseholderQRPreconditioner>& svd, const MatrixType& matrix)\n  {\n    if(matrix.cols() > matrix.rows())\n    {\n      m_adjoint = matrix.adjoint();\n      m_qr.compute(m_adjoint);\n\n      svd.m_workMatrix = m_qr.matrixQR().block(0,0,matrix.rows(),matrix.rows()).template triangularView<Upper>().adjoint();\n      if(svd.m_computeFullV) m_qr.householderQ().evalTo(svd.m_matrixV, m_workspace);\n      else if(svd.m_computeThinV)\n      {\n        svd.m_matrixV.setIdentity(matrix.cols(), matrix.rows());\n        m_qr.householderQ().applyThisOnTheLeft(svd.m_matrixV, m_workspace);\n      }\n      if(svd.computeU()) svd.m_matrixU = m_qr.colsPermutation();\n      return true;\n    }\n    else return false;\n  }\n\nprivate:\n  typedef ColPivHouseholderQR<TransposeTypeWithSameStorageOrder> QRType;\n  QRType m_qr;\n  TransposeTypeWithSameStorageOrder m_adjoint;\n  typename internal::plain_row_type<MatrixType>::type m_workspace;\n};\n\n/*** preconditioner using HouseholderQR ***/\n\ntemplate<typename MatrixType>\nclass qr_preconditioner_impl<MatrixType, HouseholderQRPreconditioner, PreconditionIfMoreRowsThanCols, true>\n{\npublic:\n  void allocate(const JacobiSVD<MatrixType, HouseholderQRPreconditioner>& svd)\n  {\n    if (svd.rows() != m_qr.rows() || svd.cols() != m_qr.cols())\n    {\n      m_qr.~QRType();\n      ::new (&m_qr) QRType(svd.rows(), svd.cols());\n    }\n    if (svd.m_computeFullU) m_workspace.resize(svd.rows());\n    else if (svd.m_computeThinU) m_workspace.resize(svd.cols());\n  }\n\n  bool run(JacobiSVD<MatrixType, HouseholderQRPreconditioner>& svd, const MatrixType& matrix)\n  {\n    if(matrix.rows() > matrix.cols())\n    {\n      m_qr.compute(matrix);\n      svd.m_workMatrix = m_qr.matrixQR().block(0,0,matrix.cols(),matrix.cols()).template triangularView<Upper>();\n      if(svd.m_computeFullU) m_qr.householderQ().evalTo(svd.m_matrixU, m_workspace);\n      else if(svd.m_computeThinU)\n      {\n        svd.m_matrixU.setIdentity(matrix.rows(), matrix.cols());\n        m_qr.householderQ().applyThisOnTheLeft(svd.m_matrixU, m_workspace);\n      }\n      if(svd.computeV()) svd.m_matrixV.setIdentity(matrix.cols(), matrix.cols());\n      return true;\n    }\n    return false;\n  }\nprivate:\n  typedef HouseholderQR<MatrixType> QRType;\n  QRType m_qr;\n  typename internal::plain_col_type<MatrixType>::type m_workspace;\n};\n\ntemplate<typename MatrixType>\nclass qr_preconditioner_impl<MatrixType, HouseholderQRPreconditioner, PreconditionIfMoreColsThanRows, true>\n{\npublic:\n  typedef typename MatrixType::Scalar Scalar;\n  enum\n  {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n    MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n    MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime,\n    Options = MatrixType::Options\n  };\n\n  typedef typename internal::make_proper_matrix_type<\n    Scalar, ColsAtCompileTime, RowsAtCompileTime, Options, MaxColsAtCompileTime, MaxRowsAtCompileTime\n  >::type TransposeTypeWithSameStorageOrder;\n\n  void allocate(const JacobiSVD<MatrixType, HouseholderQRPreconditioner>& svd)\n  {\n    if (svd.cols() != m_qr.rows() || svd.rows() != m_qr.cols())\n    {\n      m_qr.~QRType();\n      ::new (&m_qr) QRType(svd.cols(), svd.rows());\n    }\n    if (svd.m_computeFullV) m_workspace.resize(svd.cols());\n    else if (svd.m_computeThinV) m_workspace.resize(svd.rows());\n    m_adjoint.resize(svd.cols(), svd.rows());\n  }\n\n  bool run(JacobiSVD<MatrixType, HouseholderQRPreconditioner>& svd, const MatrixType& matrix)\n  {\n    if(matrix.cols() > matrix.rows())\n    {\n      m_adjoint = matrix.adjoint();\n      m_qr.compute(m_adjoint);\n\n      svd.m_workMatrix = m_qr.matrixQR().block(0,0,matrix.rows(),matrix.rows()).template triangularView<Upper>().adjoint();\n      if(svd.m_computeFullV) m_qr.householderQ().evalTo(svd.m_matrixV, m_workspace);\n      else if(svd.m_computeThinV)\n      {\n        svd.m_matrixV.setIdentity(matrix.cols(), matrix.rows());\n        m_qr.householderQ().applyThisOnTheLeft(svd.m_matrixV, m_workspace);\n      }\n      if(svd.computeU()) svd.m_matrixU.setIdentity(matrix.rows(), matrix.rows());\n      return true;\n    }\n    else return false;\n  }\n\nprivate:\n  typedef HouseholderQR<TransposeTypeWithSameStorageOrder> QRType;\n  QRType m_qr;\n  TransposeTypeWithSameStorageOrder m_adjoint;\n  typename internal::plain_row_type<MatrixType>::type m_workspace;\n};\n\n/*** 2x2 SVD implementation\n ***\n *** JacobiSVD consists in performing a series of 2x2 SVD subproblems\n ***/\n\ntemplate<typename MatrixType, int QRPreconditioner>\nstruct svd_precondition_2x2_block_to_be_real<MatrixType, QRPreconditioner, false>\n{\n  typedef JacobiSVD<MatrixType, QRPreconditioner> SVD;\n  typedef typename MatrixType::RealScalar RealScalar;\n  static bool run(typename SVD::WorkMatrixType&, SVD&, Index, Index, RealScalar&) { return true; }\n};\n\ntemplate<typename MatrixType, int QRPreconditioner>\nstruct svd_precondition_2x2_block_to_be_real<MatrixType, QRPreconditioner, true>\n{\n  typedef JacobiSVD<MatrixType, QRPreconditioner> SVD;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  static bool run(typename SVD::WorkMatrixType& work_matrix, SVD& svd, Index p, Index q, RealScalar& maxDiagEntry)\n  {\n    using std::sqrt;\n    using std::abs;\n    Scalar z;\n    JacobiRotation<Scalar> rot;\n    RealScalar n = sqrt(numext::abs2(work_matrix.coeff(p,p)) + numext::abs2(work_matrix.coeff(q,p)));\n\n    const RealScalar considerAsZero = (std::numeric_limits<RealScalar>::min)();\n    const RealScalar precision = NumTraits<Scalar>::epsilon();\n\n    if(n==0)\n    {\n      // make sure first column is zero\n      work_matrix.coeffRef(p,p) = work_matrix.coeffRef(q,p) = Scalar(0);\n\n      if(abs(numext::imag(work_matrix.coeff(p,q)))>considerAsZero)\n      {\n        // work_matrix.coeff(p,q) can be zero if work_matrix.coeff(q,p) is not zero but small enough to underflow when computing n\n        z = abs(work_matrix.coeff(p,q)) / work_matrix.coeff(p,q);\n        work_matrix.row(p) *= z;\n        if(svd.computeU()) svd.m_matrixU.col(p) *= conj(z);\n      }\n      if(abs(numext::imag(work_matrix.coeff(q,q)))>considerAsZero)\n      {\n        z = abs(work_matrix.coeff(q,q)) / work_matrix.coeff(q,q);\n        work_matrix.row(q) *= z;\n        if(svd.computeU()) svd.m_matrixU.col(q) *= conj(z);\n      }\n      // otherwise the second row is already zero, so we have nothing to do.\n    }\n    else\n    {\n      rot.c() = conj(work_matrix.coeff(p,p)) / n;\n      rot.s() = work_matrix.coeff(q,p) / n;\n      work_matrix.applyOnTheLeft(p,q,rot);\n      if(svd.computeU()) svd.m_matrixU.applyOnTheRight(p,q,rot.adjoint());\n      if(abs(numext::imag(work_matrix.coeff(p,q)))>considerAsZero)\n      {\n        z = abs(work_matrix.coeff(p,q)) / work_matrix.coeff(p,q);\n        work_matrix.col(q) *= z;\n        if(svd.computeV()) svd.m_matrixV.col(q) *= z;\n      }\n      if(abs(numext::imag(work_matrix.coeff(q,q)))>considerAsZero)\n      {\n        z = abs(work_matrix.coeff(q,q)) / work_matrix.coeff(q,q);\n        work_matrix.row(q) *= z;\n        if(svd.computeU()) svd.m_matrixU.col(q) *= conj(z);\n      }\n    }\n\n    // update largest diagonal entry\n    maxDiagEntry = numext::maxi<RealScalar>(maxDiagEntry,numext::maxi<RealScalar>(abs(work_matrix.coeff(p,p)), abs(work_matrix.coeff(q,q))));\n    // and check whether the 2x2 block is already diagonal\n    RealScalar threshold = numext::maxi<RealScalar>(considerAsZero, precision * maxDiagEntry);\n    return abs(work_matrix.coeff(p,q))>threshold || abs(work_matrix.coeff(q,p)) > threshold;\n  }\n};\n\ntemplate<typename MatrixType_, int QRPreconditioner>\nstruct traits<JacobiSVD<MatrixType_,QRPreconditioner> >\n        : traits<MatrixType_>\n{\n  typedef MatrixType_ MatrixType;\n};\n\n} // end namespace internal\n\n/** \\ingroup SVD_Module\n  *\n  *\n  * \\class JacobiSVD\n  *\n  * \\brief Two-sided Jacobi SVD decomposition of a rectangular matrix\n  *\n  * \\tparam MatrixType_ the type of the matrix of which we are computing the SVD decomposition\n  * \\tparam QRPreconditioner this optional parameter allows to specify the type of QR decomposition that will be used internally\n  *                        for the R-SVD step for non-square matrices. See discussion of possible values below.\n  *\n  * SVD decomposition consists in decomposing any n-by-p matrix \\a A as a product\n  *   \\f[ A = U S V^* \\f]\n  * where \\a U is a n-by-n unitary, \\a V is a p-by-p unitary, and \\a S is a n-by-p real positive matrix which is zero outside of its main diagonal;\n  * the diagonal entries of S are known as the \\em singular \\em values of \\a A and the columns of \\a U and \\a V are known as the left\n  * and right \\em singular \\em vectors of \\a A respectively.\n  *\n  * Singular values are always sorted in decreasing order.\n  *\n  * This JacobiSVD decomposition computes only the singular values by default. If you want \\a U or \\a V, you need to ask for them explicitly.\n  *\n  * You can ask for only \\em thin \\a U or \\a V to be computed, meaning the following. In case of a rectangular n-by-p matrix, letting \\a m be the\n  * smaller value among \\a n and \\a p, there are only \\a m singular vectors; the remaining columns of \\a U and \\a V do not correspond to actual\n  * singular vectors. Asking for \\em thin \\a U or \\a V means asking for only their \\a m first columns to be formed. So \\a U is then a n-by-m matrix,\n  * and \\a V is then a p-by-m matrix. Notice that thin \\a U and \\a V are all you need for (least squares) solving.\n  *\n  * Here's an example demonstrating basic usage:\n  * \\include JacobiSVD_basic.cpp\n  * Output: \\verbinclude JacobiSVD_basic.out\n  *\n  * This JacobiSVD class is a two-sided Jacobi R-SVD decomposition, ensuring optimal reliability and accuracy. The downside is that it's slower than\n  * bidiagonalizing SVD algorithms for large square matrices; however its complexity is still \\f$ O(n^2p) \\f$ where \\a n is the smaller dimension and\n  * \\a p is the greater dimension, meaning that it is still of the same order of complexity as the faster bidiagonalizing R-SVD algorithms.\n  * In particular, like any R-SVD, it takes advantage of non-squareness in that its complexity is only linear in the greater dimension.\n  *\n  * If the input matrix has inf or nan coefficients, the result of the computation is undefined, but the computation is guaranteed to\n  * terminate in finite (and reasonable) time.\n  *\n  * The possible values for QRPreconditioner are:\n  * \\li ColPivHouseholderQRPreconditioner is the default. In practice it's very safe. It uses column-pivoting QR.\n  * \\li FullPivHouseholderQRPreconditioner, is the safest and slowest. It uses full-pivoting QR.\n  *     Contrary to other QRs, it doesn't allow computing thin unitaries.\n  * \\li HouseholderQRPreconditioner is the fastest, and less safe and accurate than the pivoting variants. It uses non-pivoting QR.\n  *     This is very similar in safety and accuracy to the bidiagonalization process used by bidiagonalizing SVD algorithms (since bidiagonalization\n  *     is inherently non-pivoting). However the resulting SVD is still more reliable than bidiagonalizing SVDs because the Jacobi-based iterarive\n  *     process is more reliable than the optimized bidiagonal SVD iterations.\n  * \\li NoQRPreconditioner allows not to use a QR preconditioner at all. This is useful if you know that you will only be computing\n  *     JacobiSVD decompositions of square matrices. Non-square matrices require a QR preconditioner. Using this option will result in\n  *     faster compilation and smaller executable code. It won't significantly speed up computation, since JacobiSVD is always checking\n  *     if QR preconditioning is needed before applying it anyway.\n  *\n  * \\sa MatrixBase::jacobiSvd()\n  */\ntemplate<typename MatrixType_, int QRPreconditioner> class JacobiSVD\n : public SVDBase<JacobiSVD<MatrixType_,QRPreconditioner> >\n{\n    typedef SVDBase<JacobiSVD> Base;\n  public:\n\n    typedef MatrixType_ MatrixType;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename NumTraits<typename MatrixType::Scalar>::Real RealScalar;\n    enum {\n      RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      DiagSizeAtCompileTime = EIGEN_SIZE_MIN_PREFER_DYNAMIC(RowsAtCompileTime,ColsAtCompileTime),\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime,\n      MaxDiagSizeAtCompileTime = EIGEN_SIZE_MIN_PREFER_FIXED(MaxRowsAtCompileTime,MaxColsAtCompileTime),\n      MatrixOptions = MatrixType::Options\n    };\n\n    typedef typename Base::MatrixUType MatrixUType;\n    typedef typename Base::MatrixVType MatrixVType;\n    typedef typename Base::SingularValuesType SingularValuesType;\n    \n    typedef typename internal::plain_row_type<MatrixType>::type RowType;\n    typedef typename internal::plain_col_type<MatrixType>::type ColType;\n    typedef Matrix<Scalar, DiagSizeAtCompileTime, DiagSizeAtCompileTime,\n                   MatrixOptions, MaxDiagSizeAtCompileTime, MaxDiagSizeAtCompileTime>\n            WorkMatrixType;\n\n    /** \\brief Default Constructor.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via JacobiSVD::compute(const MatrixType&).\n      */\n    JacobiSVD()\n    {}\n\n\n    /** \\brief Default Constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem size.\n      * \\sa JacobiSVD()\n      */\n    JacobiSVD(Index rows, Index cols, unsigned int computationOptions = 0)\n    {\n      allocate(rows, cols, computationOptions);\n    }\n\n    /** \\brief Constructor performing the decomposition of given matrix.\n     *\n     * \\param matrix the matrix to decompose\n     * \\param computationOptions optional parameter allowing to specify if you want full or thin U or V unitaries to be computed.\n     *                           By default, none is computed. This is a bit-field, the possible bits are #ComputeFullU, #ComputeThinU,\n     *                           #ComputeFullV, #ComputeThinV.\n     *\n     * Thin unitaries are only available if your matrix type has a Dynamic number of columns (for example MatrixXf). They also are not\n     * available with the (non-default) FullPivHouseholderQR preconditioner.\n     */\n    explicit JacobiSVD(const MatrixType& matrix, unsigned int computationOptions = 0)\n    {\n      compute(matrix, computationOptions);\n    }\n\n    /** \\brief Method performing the decomposition of given matrix using custom options.\n     *\n     * \\param matrix the matrix to decompose\n     * \\param computationOptions optional parameter allowing to specify if you want full or thin U or V unitaries to be computed.\n     *                           By default, none is computed. This is a bit-field, the possible bits are #ComputeFullU, #ComputeThinU,\n     *                           #ComputeFullV, #ComputeThinV.\n     *\n     * Thin unitaries are only available if your matrix type has a Dynamic number of columns (for example MatrixXf). They also are not\n     * available with the (non-default) FullPivHouseholderQR preconditioner.\n     */\n    JacobiSVD& compute(const MatrixType& matrix, unsigned int computationOptions);\n\n    /** \\brief Method performing the decomposition of given matrix using current options.\n     *\n     * \\param matrix the matrix to decompose\n     *\n     * This method uses the current \\a computationOptions, as already passed to the constructor or to compute(const MatrixType&, unsigned int).\n     */\n    JacobiSVD& compute(const MatrixType& matrix)\n    {\n      return compute(matrix, m_computationOptions);\n    }\n\n    using Base::computeU;\n    using Base::computeV;\n    using Base::rows;\n    using Base::cols;\n    using Base::rank;\n\n  private:\n    void allocate(Index rows, Index cols, unsigned int computationOptions);\n\n  protected:\n    using Base::m_matrixU;\n    using Base::m_matrixV;\n    using Base::m_singularValues;\n    using Base::m_info;\n    using Base::m_isInitialized;\n    using Base::m_isAllocated;\n    using Base::m_usePrescribedThreshold;\n    using Base::m_computeFullU;\n    using Base::m_computeThinU;\n    using Base::m_computeFullV;\n    using Base::m_computeThinV;\n    using Base::m_computationOptions;\n    using Base::m_nonzeroSingularValues;\n    using Base::m_rows;\n    using Base::m_cols;\n    using Base::m_diagSize;\n    using Base::m_prescribedThreshold;\n    WorkMatrixType m_workMatrix;\n\n    template<typename MatrixType__, int QRPreconditioner_, bool IsComplex_>\n    friend struct internal::svd_precondition_2x2_block_to_be_real;\n    template<typename MatrixType__, int QRPreconditioner_, int Case_, bool DoAnything_>\n    friend struct internal::qr_preconditioner_impl;\n\n    internal::qr_preconditioner_impl<MatrixType, QRPreconditioner, internal::PreconditionIfMoreColsThanRows> m_qr_precond_morecols;\n    internal::qr_preconditioner_impl<MatrixType, QRPreconditioner, internal::PreconditionIfMoreRowsThanCols> m_qr_precond_morerows;\n    MatrixType m_scaledMatrix;\n};\n\ntemplate<typename MatrixType, int QRPreconditioner>\nvoid JacobiSVD<MatrixType, QRPreconditioner>::allocate(Eigen::Index rows, Eigen::Index cols, unsigned int computationOptions)\n{\n  eigen_assert(rows >= 0 && cols >= 0);\n\n  if (m_isAllocated &&\n      rows == m_rows &&\n      cols == m_cols &&\n      computationOptions == m_computationOptions)\n  {\n    return;\n  }\n\n  m_rows = rows;\n  m_cols = cols;\n  m_info = Success;\n  m_isInitialized = false;\n  m_isAllocated = true;\n  m_computationOptions = computationOptions;\n  m_computeFullU = (computationOptions & ComputeFullU) != 0;\n  m_computeThinU = (computationOptions & ComputeThinU) != 0;\n  m_computeFullV = (computationOptions & ComputeFullV) != 0;\n  m_computeThinV = (computationOptions & ComputeThinV) != 0;\n  eigen_assert(!(m_computeFullU && m_computeThinU) && \"JacobiSVD: you can't ask for both full and thin U\");\n  eigen_assert(!(m_computeFullV && m_computeThinV) && \"JacobiSVD: you can't ask for both full and thin V\");\n  eigen_assert(EIGEN_IMPLIES(m_computeThinU || m_computeThinV, MatrixType::ColsAtCompileTime==Dynamic) &&\n              \"JacobiSVD: thin U and V are only available when your matrix has a dynamic number of columns.\");\n  if (QRPreconditioner == FullPivHouseholderQRPreconditioner)\n  {\n      eigen_assert(!(m_computeThinU || m_computeThinV) &&\n              \"JacobiSVD: can't compute thin U or thin V with the FullPivHouseholderQR preconditioner. \"\n              \"Use the ColPivHouseholderQR preconditioner instead.\");\n  }\n  m_diagSize = (std::min)(m_rows, m_cols);\n  m_singularValues.resize(m_diagSize);\n  if(RowsAtCompileTime==Dynamic)\n    m_matrixU.resize(m_rows, m_computeFullU ? m_rows\n                            : m_computeThinU ? m_diagSize\n                            : 0);\n  if(ColsAtCompileTime==Dynamic)\n    m_matrixV.resize(m_cols, m_computeFullV ? m_cols\n                            : m_computeThinV ? m_diagSize\n                            : 0);\n  m_workMatrix.resize(m_diagSize, m_diagSize);\n  \n  if(m_cols>m_rows)   m_qr_precond_morecols.allocate(*this);\n  if(m_rows>m_cols)   m_qr_precond_morerows.allocate(*this);\n  if(m_rows!=m_cols)  m_scaledMatrix.resize(rows,cols);\n}\n\ntemplate<typename MatrixType, int QRPreconditioner>\nJacobiSVD<MatrixType, QRPreconditioner>&\nJacobiSVD<MatrixType, QRPreconditioner>::compute(const MatrixType& matrix, unsigned int computationOptions)\n{\n  using std::abs;\n  allocate(matrix.rows(), matrix.cols(), computationOptions);\n\n  // currently we stop when we reach precision 2*epsilon as the last bit of precision can require an unreasonable number of iterations,\n  // only worsening the precision of U and V as we accumulate more rotations\n  const RealScalar precision = RealScalar(2) * NumTraits<Scalar>::epsilon();\n\n  // limit for denormal numbers to be considered zero in order to avoid infinite loops (see bug 286)\n  const RealScalar considerAsZero = (std::numeric_limits<RealScalar>::min)();\n\n  // Scaling factor to reduce over/under-flows\n  RealScalar scale = matrix.cwiseAbs().template maxCoeff<PropagateNaN>();\n  if (!(numext::isfinite)(scale)) {\n    m_isInitialized = true;\n    m_info = InvalidInput;\n    return *this;\n  }\n  if(scale==RealScalar(0)) scale = RealScalar(1);\n  \n  /*** step 1. The R-SVD step: we use a QR decomposition to reduce to the case of a square matrix */\n\n  if(m_rows!=m_cols)\n  {\n    m_scaledMatrix = matrix / scale;\n    m_qr_precond_morecols.run(*this, m_scaledMatrix);\n    m_qr_precond_morerows.run(*this, m_scaledMatrix);\n  }\n  else\n  {\n    m_workMatrix = matrix.block(0,0,m_diagSize,m_diagSize) / scale;\n    if(m_computeFullU) m_matrixU.setIdentity(m_rows,m_rows);\n    if(m_computeThinU) m_matrixU.setIdentity(m_rows,m_diagSize);\n    if(m_computeFullV) m_matrixV.setIdentity(m_cols,m_cols);\n    if(m_computeThinV) m_matrixV.setIdentity(m_cols, m_diagSize);\n  }\n\n  /*** step 2. The main Jacobi SVD iteration. ***/\n  RealScalar maxDiagEntry = m_workMatrix.cwiseAbs().diagonal().maxCoeff();\n\n  bool finished = false;\n  while(!finished)\n  {\n    finished = true;\n\n    // do a sweep: for all index pairs (p,q), perform SVD of the corresponding 2x2 sub-matrix\n\n    for(Index p = 1; p < m_diagSize; ++p)\n    {\n      for(Index q = 0; q < p; ++q)\n      {\n        // if this 2x2 sub-matrix is not diagonal already...\n        // notice that this comparison will evaluate to false if any NaN is involved, ensuring that NaN's don't\n        // keep us iterating forever. Similarly, small denormal numbers are considered zero.\n        RealScalar threshold = numext::maxi<RealScalar>(considerAsZero, precision * maxDiagEntry);\n        if(abs(m_workMatrix.coeff(p,q))>threshold || abs(m_workMatrix.coeff(q,p)) > threshold)\n        {\n          finished = false;\n          // perform SVD decomposition of 2x2 sub-matrix corresponding to indices p,q to make it diagonal\n          // the complex to real operation returns true if the updated 2x2 block is not already diagonal\n          if(internal::svd_precondition_2x2_block_to_be_real<MatrixType, QRPreconditioner>::run(m_workMatrix, *this, p, q, maxDiagEntry))\n          {\n            JacobiRotation<RealScalar> j_left, j_right;\n            internal::real_2x2_jacobi_svd(m_workMatrix, p, q, &j_left, &j_right);\n\n            // accumulate resulting Jacobi rotations\n            m_workMatrix.applyOnTheLeft(p,q,j_left);\n            if(computeU()) m_matrixU.applyOnTheRight(p,q,j_left.transpose());\n\n            m_workMatrix.applyOnTheRight(p,q,j_right);\n            if(computeV()) m_matrixV.applyOnTheRight(p,q,j_right);\n\n            // keep track of the largest diagonal coefficient\n            maxDiagEntry = numext::maxi<RealScalar>(maxDiagEntry,numext::maxi<RealScalar>(abs(m_workMatrix.coeff(p,p)), abs(m_workMatrix.coeff(q,q))));\n          }\n        }\n      }\n    }\n  }\n\n  /*** step 3. The work matrix is now diagonal, so ensure it's positive so its diagonal entries are the singular values ***/\n\n  for(Index i = 0; i < m_diagSize; ++i)\n  {\n    // For a complex matrix, some diagonal coefficients might note have been\n    // treated by svd_precondition_2x2_block_to_be_real, and the imaginary part\n    // of some diagonal entry might not be null.\n    if(NumTraits<Scalar>::IsComplex && abs(numext::imag(m_workMatrix.coeff(i,i)))>considerAsZero)\n    {\n      RealScalar a = abs(m_workMatrix.coeff(i,i));\n      m_singularValues.coeffRef(i) = abs(a);\n      if(computeU()) m_matrixU.col(i) *= m_workMatrix.coeff(i,i)/a;\n    }\n    else\n    {\n      // m_workMatrix.coeff(i,i) is already real, no difficulty:\n      RealScalar a = numext::real(m_workMatrix.coeff(i,i));\n      m_singularValues.coeffRef(i) = abs(a);\n      if(computeU() && (a<RealScalar(0))) m_matrixU.col(i) = -m_matrixU.col(i);\n    }\n  }\n  \n  m_singularValues *= scale;\n\n  /*** step 4. Sort singular values in descending order and compute the number of nonzero singular values ***/\n\n  m_nonzeroSingularValues = m_diagSize;\n  for(Index i = 0; i < m_diagSize; i++)\n  {\n    Index pos;\n    RealScalar maxRemainingSingularValue = m_singularValues.tail(m_diagSize-i).maxCoeff(&pos);\n    if(maxRemainingSingularValue == RealScalar(0))\n    {\n      m_nonzeroSingularValues = i;\n      break;\n    }\n    if(pos)\n    {\n      pos += i;\n      std::swap(m_singularValues.coeffRef(i), m_singularValues.coeffRef(pos));\n      if(computeU()) m_matrixU.col(pos).swap(m_matrixU.col(i));\n      if(computeV()) m_matrixV.col(pos).swap(m_matrixV.col(i));\n    }\n  }\n\n  m_isInitialized = true;\n  return *this;\n}\n\n/** \\svd_module\n  *\n  * \\return the singular value decomposition of \\c *this computed by two-sided\n  * Jacobi transformations.\n  *\n  * \\sa class JacobiSVD\n  */\ntemplate<typename Derived>\nJacobiSVD<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::jacobiSvd(unsigned int computationOptions) const\n{\n  return JacobiSVD<PlainObject>(*this, computationOptions);\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_JACOBISVD_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SVD/JacobiSVD_LAPACKE.h",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Eigen bindings to LAPACKe\n *    Singular Value Decomposition - SVD.\n ********************************************************************************\n*/\n\n#ifndef EIGEN_JACOBISVD_LAPACKE_H\n#define EIGEN_JACOBISVD_LAPACKE_H\n\nnamespace Eigen { \n\n/** \\internal Specialization for the data types supported by LAPACKe */\n\n#define EIGEN_LAPACKE_SVD(EIGTYPE, LAPACKE_TYPE, LAPACKE_RTYPE, LAPACKE_PREFIX, EIGCOLROW, LAPACKE_COLROW) \\\ntemplate<> inline \\\nJacobiSVD<Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW, Dynamic, Dynamic>, ColPivHouseholderQRPreconditioner>& \\\nJacobiSVD<Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW, Dynamic, Dynamic>, ColPivHouseholderQRPreconditioner>::compute(const Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW, Dynamic, Dynamic>& matrix, unsigned int computationOptions) \\\n{ \\\n  typedef Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW, Dynamic, Dynamic> MatrixType; \\\n  /*typedef MatrixType::Scalar Scalar;*/ \\\n  /*typedef MatrixType::RealScalar RealScalar;*/ \\\n  allocate(matrix.rows(), matrix.cols(), computationOptions); \\\n\\\n  /*const RealScalar precision = RealScalar(2) * NumTraits<Scalar>::epsilon();*/ \\\n  m_nonzeroSingularValues = m_diagSize; \\\n\\\n  lapack_int lda = internal::convert_index<lapack_int>(matrix.outerStride()), ldu, ldvt; \\\n  lapack_int matrix_order = LAPACKE_COLROW; \\\n  char jobu, jobvt; \\\n  LAPACKE_TYPE *u, *vt, dummy; \\\n  jobu  = (m_computeFullU) ? 'A' : (m_computeThinU) ? 'S' : 'N'; \\\n  jobvt = (m_computeFullV) ? 'A' : (m_computeThinV) ? 'S' : 'N'; \\\n  if (computeU()) { \\\n    ldu  = internal::convert_index<lapack_int>(m_matrixU.outerStride()); \\\n    u    = (LAPACKE_TYPE*)m_matrixU.data(); \\\n  } else { ldu=1; u=&dummy; }\\\n  MatrixType localV; \\\n  lapack_int vt_rows = (m_computeFullV) ? internal::convert_index<lapack_int>(m_cols) : (m_computeThinV) ? internal::convert_index<lapack_int>(m_diagSize) : 1; \\\n  if (computeV()) { \\\n    localV.resize(vt_rows, m_cols); \\\n    ldvt  = internal::convert_index<lapack_int>(localV.outerStride()); \\\n    vt   = (LAPACKE_TYPE*)localV.data(); \\\n  } else { ldvt=1; vt=&dummy; }\\\n  Matrix<LAPACKE_RTYPE, Dynamic, Dynamic> superb; superb.resize(m_diagSize, 1); \\\n  MatrixType m_temp; m_temp = matrix; \\\n  LAPACKE_##LAPACKE_PREFIX##gesvd( matrix_order, jobu, jobvt, internal::convert_index<lapack_int>(m_rows), internal::convert_index<lapack_int>(m_cols), (LAPACKE_TYPE*)m_temp.data(), lda, (LAPACKE_RTYPE*)m_singularValues.data(), u, ldu, vt, ldvt, superb.data()); \\\n  if (computeV()) m_matrixV = localV.adjoint(); \\\n /* for(int i=0;i<m_diagSize;i++) if (m_singularValues.coeffRef(i) < precision) { m_nonzeroSingularValues--; m_singularValues.coeffRef(i)=RealScalar(0);}*/ \\\n  m_isInitialized = true; \\\n  return *this; \\\n}\n\nEIGEN_LAPACKE_SVD(double,   double,                double, d, ColMajor, LAPACK_COL_MAJOR)\nEIGEN_LAPACKE_SVD(float,    float,                 float , s, ColMajor, LAPACK_COL_MAJOR)\nEIGEN_LAPACKE_SVD(dcomplex, lapack_complex_double, double, z, ColMajor, LAPACK_COL_MAJOR)\nEIGEN_LAPACKE_SVD(scomplex, lapack_complex_float,  float , c, ColMajor, LAPACK_COL_MAJOR)\n\nEIGEN_LAPACKE_SVD(double,   double,                double, d, RowMajor, LAPACK_ROW_MAJOR)\nEIGEN_LAPACKE_SVD(float,    float,                 float , s, RowMajor, LAPACK_ROW_MAJOR)\nEIGEN_LAPACKE_SVD(dcomplex, lapack_complex_double, double, z, RowMajor, LAPACK_ROW_MAJOR)\nEIGEN_LAPACKE_SVD(scomplex, lapack_complex_float,  float , c, RowMajor, LAPACK_ROW_MAJOR)\n\n} // end namespace Eigen\n\n#endif // EIGEN_JACOBISVD_LAPACKE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SVD/SVDBase.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// Copyright (C) 2013 Gauthier Brun <brun.gauthier@gmail.com>\n// Copyright (C) 2013 Nicolas Carre <nicolas.carre@ensimag.fr>\n// Copyright (C) 2013 Jean Ceccato <jean.ceccato@ensimag.fr>\n// Copyright (C) 2013 Pierre Zoppitelli <pierre.zoppitelli@ensimag.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SVDBASE_H\n#define EIGEN_SVDBASE_H\n\nnamespace Eigen {\n\nnamespace internal {\ntemplate<typename Derived> struct traits<SVDBase<Derived> >\n : traits<Derived>\n{\n  typedef MatrixXpr XprKind;\n  typedef SolverStorage StorageKind;\n  typedef int StorageIndex;\n  enum { Flags = 0 };\n};\n}\n\n/** \\ingroup SVD_Module\n *\n *\n * \\class SVDBase\n *\n * \\brief Base class of SVD algorithms\n *\n * \\tparam Derived the type of the actual SVD decomposition\n *\n * SVD decomposition consists in decomposing any n-by-p matrix \\a A as a product\n *   \\f[ A = U S V^* \\f]\n * where \\a U is a n-by-n unitary, \\a V is a p-by-p unitary, and \\a S is a n-by-p real positive matrix which is zero outside of its main diagonal;\n * the diagonal entries of S are known as the \\em singular \\em values of \\a A and the columns of \\a U and \\a V are known as the left\n * and right \\em singular \\em vectors of \\a A respectively.\n *\n * Singular values are always sorted in decreasing order.\n *\n * \n * You can ask for only \\em thin \\a U or \\a V to be computed, meaning the following. In case of a rectangular n-by-p matrix, letting \\a m be the\n * smaller value among \\a n and \\a p, there are only \\a m singular vectors; the remaining columns of \\a U and \\a V do not correspond to actual\n * singular vectors. Asking for \\em thin \\a U or \\a V means asking for only their \\a m first columns to be formed. So \\a U is then a n-by-m matrix,\n * and \\a V is then a p-by-m matrix. Notice that thin \\a U and \\a V are all you need for (least squares) solving.\n * \n * The status of the computation can be retrived using the \\a info() method. Unless \\a info() returns \\a Success, the results should be not\n * considered well defined.\n *  \n * If the input matrix has inf or nan coefficients, the result of the computation is undefined, and \\a info() will return \\a InvalidInput, but the computation is guaranteed to\n * terminate in finite (and reasonable) time.\n * \\sa class BDCSVD, class JacobiSVD\n */\ntemplate<typename Derived> class SVDBase\n : public SolverBase<SVDBase<Derived> >\n{\npublic: \n   \n  template<typename Derived_>\n  friend struct internal::solve_assertion;\n\n  typedef typename internal::traits<Derived>::MatrixType MatrixType;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<typename MatrixType::Scalar>::Real RealScalar;\n  typedef typename Eigen::internal::traits<SVDBase>::StorageIndex StorageIndex;\n  typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n  enum {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n    DiagSizeAtCompileTime = EIGEN_SIZE_MIN_PREFER_DYNAMIC(RowsAtCompileTime,ColsAtCompileTime),\n    MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n    MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime,\n    MaxDiagSizeAtCompileTime = EIGEN_SIZE_MIN_PREFER_FIXED(MaxRowsAtCompileTime,MaxColsAtCompileTime),\n    MatrixOptions = MatrixType::Options\n  };\n\n  typedef Matrix<Scalar, RowsAtCompileTime, RowsAtCompileTime, MatrixOptions, MaxRowsAtCompileTime, MaxRowsAtCompileTime> MatrixUType;\n  typedef Matrix<Scalar, ColsAtCompileTime, ColsAtCompileTime, MatrixOptions, MaxColsAtCompileTime, MaxColsAtCompileTime> MatrixVType;\n  typedef typename internal::plain_diag_type<MatrixType, RealScalar>::type SingularValuesType;\n  \n  Derived& derived() { return *static_cast<Derived*>(this); }\n  const Derived& derived() const { return *static_cast<const Derived*>(this); }\n\n  /** \\returns the \\a U matrix.\n   *\n   * For the SVD decomposition of a n-by-p matrix, letting \\a m be the minimum of \\a n and \\a p,\n   * the U matrix is n-by-n if you asked for \\link Eigen::ComputeFullU ComputeFullU \\endlink, and is n-by-m if you asked for \\link Eigen::ComputeThinU ComputeThinU \\endlink.\n   *\n   * The \\a m first columns of \\a U are the left singular vectors of the matrix being decomposed.\n   *\n   * This method asserts that you asked for \\a U to be computed.\n   */\n  const MatrixUType& matrixU() const\n  {\n    _check_compute_assertions();\n    eigen_assert(computeU() && \"This SVD decomposition didn't compute U. Did you ask for it?\");\n    return m_matrixU;\n  }\n\n  /** \\returns the \\a V matrix.\n   *\n   * For the SVD decomposition of a n-by-p matrix, letting \\a m be the minimum of \\a n and \\a p,\n   * the V matrix is p-by-p if you asked for \\link Eigen::ComputeFullV ComputeFullV \\endlink, and is p-by-m if you asked for \\link Eigen::ComputeThinV ComputeThinV \\endlink.\n   *\n   * The \\a m first columns of \\a V are the right singular vectors of the matrix being decomposed.\n   *\n   * This method asserts that you asked for \\a V to be computed.\n   */\n  const MatrixVType& matrixV() const\n  {\n    _check_compute_assertions();\n    eigen_assert(computeV() && \"This SVD decomposition didn't compute V. Did you ask for it?\");\n    return m_matrixV;\n  }\n\n  /** \\returns the vector of singular values.\n   *\n   * For the SVD decomposition of a n-by-p matrix, letting \\a m be the minimum of \\a n and \\a p, the\n   * returned vector has size \\a m.  Singular values are always sorted in decreasing order.\n   */\n  const SingularValuesType& singularValues() const\n  {\n    _check_compute_assertions();\n    return m_singularValues;\n  }\n\n  /** \\returns the number of singular values that are not exactly 0 */\n  Index nonzeroSingularValues() const\n  {\n    _check_compute_assertions();\n    return m_nonzeroSingularValues;\n  }\n  \n  /** \\returns the rank of the matrix of which \\c *this is the SVD.\n    *\n    * \\note This method has to determine which singular values should be considered nonzero.\n    *       For that, it uses the threshold value that you can control by calling\n    *       setThreshold(const RealScalar&).\n    */\n  inline Index rank() const\n  {\n    using std::abs;\n    _check_compute_assertions();\n    if(m_singularValues.size()==0) return 0;\n    RealScalar premultiplied_threshold = numext::maxi<RealScalar>(m_singularValues.coeff(0) * threshold(), (std::numeric_limits<RealScalar>::min)());\n    Index i = m_nonzeroSingularValues-1;\n    while(i>=0 && m_singularValues.coeff(i) < premultiplied_threshold) --i;\n    return i+1;\n  }\n  \n  /** Allows to prescribe a threshold to be used by certain methods, such as rank() and solve(),\n    * which need to determine when singular values are to be considered nonzero.\n    * This is not used for the SVD decomposition itself.\n    *\n    * When it needs to get the threshold value, Eigen calls threshold().\n    * The default is \\c NumTraits<Scalar>::epsilon()\n    *\n    * \\param threshold The new value to use as the threshold.\n    *\n    * A singular value will be considered nonzero if its value is strictly greater than\n    *  \\f$ \\vert singular value \\vert \\leqslant threshold \\times \\vert max singular value \\vert \\f$.\n    *\n    * If you want to come back to the default behavior, call setThreshold(Default_t)\n    */\n  Derived& setThreshold(const RealScalar& threshold)\n  {\n    m_usePrescribedThreshold = true;\n    m_prescribedThreshold = threshold;\n    return derived();\n  }\n\n  /** Allows to come back to the default behavior, letting Eigen use its default formula for\n    * determining the threshold.\n    *\n    * You should pass the special object Eigen::Default as parameter here.\n    * \\code svd.setThreshold(Eigen::Default); \\endcode\n    *\n    * See the documentation of setThreshold(const RealScalar&).\n    */\n  Derived& setThreshold(Default_t)\n  {\n    m_usePrescribedThreshold = false;\n    return derived();\n  }\n\n  /** Returns the threshold that will be used by certain methods such as rank().\n    *\n    * See the documentation of setThreshold(const RealScalar&).\n    */\n  RealScalar threshold() const\n  {\n    eigen_assert(m_isInitialized || m_usePrescribedThreshold);\n    // this temporary is needed to workaround a MSVC issue\n    Index diagSize = (std::max<Index>)(1,m_diagSize);\n    return m_usePrescribedThreshold ? m_prescribedThreshold\n                                    : RealScalar(diagSize)*NumTraits<Scalar>::epsilon();\n  }\n\n  /** \\returns true if \\a U (full or thin) is asked for in this SVD decomposition */\n  inline bool computeU() const { return m_computeFullU || m_computeThinU; }\n  /** \\returns true if \\a V (full or thin) is asked for in this SVD decomposition */\n  inline bool computeV() const { return m_computeFullV || m_computeThinV; }\n\n  inline Index rows() const { return m_rows; }\n  inline Index cols() const { return m_cols; }\n  \n  #ifdef EIGEN_PARSED_BY_DOXYGEN\n  /** \\returns a (least squares) solution of \\f$ A x = b \\f$ using the current SVD decomposition of A.\n    *\n    * \\param b the right-hand-side of the equation to solve.\n    *\n    * \\note Solving requires both U and V to be computed. Thin U and V are enough, there is no need for full U or V.\n    *\n    * \\note SVD solving is implicitly least-squares. Thus, this method serves both purposes of exact solving and least-squares solving.\n    * In other words, the returned solution is guaranteed to minimize the Euclidean norm \\f$ \\Vert A x - b \\Vert \\f$.\n    */\n  template<typename Rhs>\n  inline const Solve<Derived, Rhs>\n  solve(const MatrixBase<Rhs>& b) const;\n  #endif\n\n\n  /** \\brief Reports whether previous computation was successful.\n   *\n   * \\returns \\c Success if computation was successful.\n   */\n  EIGEN_DEVICE_FUNC\n  ComputationInfo info() const\n  {\n    eigen_assert(m_isInitialized && \"SVD is not initialized.\");\n    return m_info;\n  }\n\n  #ifndef EIGEN_PARSED_BY_DOXYGEN\n  template<typename RhsType, typename DstType>\n  void _solve_impl(const RhsType &rhs, DstType &dst) const;\n\n  template<bool Conjugate, typename RhsType, typename DstType>\n  void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const;\n  #endif\n\nprotected:\n\n  static void check_template_parameters()\n  {\n    EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n  }\n\n  void _check_compute_assertions() const {\n    eigen_assert(m_isInitialized && \"SVD is not initialized.\");\n  }\n\n  template<bool Transpose_, typename Rhs>\n  void _check_solve_assertion(const Rhs& b) const {\n      EIGEN_ONLY_USED_FOR_DEBUG(b);\n      _check_compute_assertions();\n      eigen_assert(computeU() && computeV() && \"SVDBase::solve(): Both unitaries U and V are required to be computed (thin unitaries suffice).\");\n      eigen_assert((Transpose_?cols():rows())==b.rows() && \"SVDBase::solve(): invalid number of rows of the right hand side matrix b\");\n  }\n\n  // return true if already allocated\n  bool allocate(Index rows, Index cols, unsigned int computationOptions) ;\n\n  MatrixUType m_matrixU;\n  MatrixVType m_matrixV;\n  SingularValuesType m_singularValues;\n  ComputationInfo m_info;\n  bool m_isInitialized, m_isAllocated, m_usePrescribedThreshold;\n  bool m_computeFullU, m_computeThinU;\n  bool m_computeFullV, m_computeThinV;\n  unsigned int m_computationOptions;\n  Index m_nonzeroSingularValues, m_rows, m_cols, m_diagSize;\n  RealScalar m_prescribedThreshold;\n\n  /** \\brief Default Constructor.\n   *\n   * Default constructor of SVDBase\n   */\n  SVDBase()\n    : m_info(Success),\n      m_isInitialized(false),\n      m_isAllocated(false),\n      m_usePrescribedThreshold(false),\n      m_computeFullU(false),\n      m_computeThinU(false),\n      m_computeFullV(false),\n      m_computeThinV(false),\n      m_computationOptions(0),\n      m_rows(-1), m_cols(-1), m_diagSize(0)\n  {\n    check_template_parameters();\n  }\n\n\n};\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename Derived>\ntemplate<typename RhsType, typename DstType>\nvoid SVDBase<Derived>::_solve_impl(const RhsType &rhs, DstType &dst) const\n{\n  // A = U S V^*\n  // So A^{-1} = V S^{-1} U^*\n\n  Matrix<typename RhsType::Scalar, Dynamic, RhsType::ColsAtCompileTime, 0, MatrixType::MaxRowsAtCompileTime, RhsType::MaxColsAtCompileTime> tmp;\n  Index l_rank = rank();\n  tmp.noalias() =  m_matrixU.leftCols(l_rank).adjoint() * rhs;\n  tmp = m_singularValues.head(l_rank).asDiagonal().inverse() * tmp;\n  dst = m_matrixV.leftCols(l_rank) * tmp;\n}\n\ntemplate<typename Derived>\ntemplate<bool Conjugate, typename RhsType, typename DstType>\nvoid SVDBase<Derived>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const\n{\n  // A = U S V^*\n  // So  A^{-*} = U S^{-1} V^*\n  // And A^{-T} = U_conj S^{-1} V^T\n  Matrix<typename RhsType::Scalar, Dynamic, RhsType::ColsAtCompileTime, 0, MatrixType::MaxRowsAtCompileTime, RhsType::MaxColsAtCompileTime> tmp;\n  Index l_rank = rank();\n\n  tmp.noalias() =  m_matrixV.leftCols(l_rank).transpose().template conjugateIf<Conjugate>() * rhs;\n  tmp = m_singularValues.head(l_rank).asDiagonal().inverse() * tmp;\n  dst = m_matrixU.template conjugateIf<!Conjugate>().leftCols(l_rank) * tmp;\n}\n#endif\n\ntemplate<typename MatrixType>\nbool SVDBase<MatrixType>::allocate(Index rows, Index cols, unsigned int computationOptions)\n{\n  eigen_assert(rows >= 0 && cols >= 0);\n\n  if (m_isAllocated &&\n      rows == m_rows &&\n      cols == m_cols &&\n      computationOptions == m_computationOptions)\n  {\n    return true;\n  }\n\n  m_rows = rows;\n  m_cols = cols;\n  m_info = Success;\n  m_isInitialized = false;\n  m_isAllocated = true;\n  m_computationOptions = computationOptions;\n  m_computeFullU = (computationOptions & ComputeFullU) != 0;\n  m_computeThinU = (computationOptions & ComputeThinU) != 0;\n  m_computeFullV = (computationOptions & ComputeFullV) != 0;\n  m_computeThinV = (computationOptions & ComputeThinV) != 0;\n  eigen_assert(!(m_computeFullU && m_computeThinU) && \"SVDBase: you can't ask for both full and thin U\");\n  eigen_assert(!(m_computeFullV && m_computeThinV) && \"SVDBase: you can't ask for both full and thin V\");\n  eigen_assert(EIGEN_IMPLIES(m_computeThinU || m_computeThinV, MatrixType::ColsAtCompileTime==Dynamic) &&\n\t       \"SVDBase: thin U and V are only available when your matrix has a dynamic number of columns.\");\n\n  m_diagSize = (std::min)(m_rows, m_cols);\n  m_singularValues.resize(m_diagSize);\n  if(RowsAtCompileTime==Dynamic)\n    m_matrixU.resize(m_rows, m_computeFullU ? m_rows : m_computeThinU ? m_diagSize : 0);\n  if(ColsAtCompileTime==Dynamic)\n    m_matrixV.resize(m_cols, m_computeFullV ? m_cols : m_computeThinV ? m_diagSize : 0);\n\n  return false;\n}\n\n}// end namespace\n\n#endif // EIGEN_SVDBASE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SVD/UpperBidiagonalization.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2013-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BIDIAGONALIZATION_H\n#define EIGEN_BIDIAGONALIZATION_H\n\nnamespace Eigen { \n\nnamespace internal {\n// UpperBidiagonalization will probably be replaced by a Bidiagonalization class, don't want to make it stable API.\n// At the same time, it's useful to keep for now as it's about the only thing that is testing the BandMatrix class.\n\ntemplate<typename MatrixType_> class UpperBidiagonalization\n{\n  public:\n\n    typedef MatrixType_ MatrixType;\n    enum {\n      RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      ColsAtCompileTimeMinusOne = internal::decrement_size<ColsAtCompileTime>::ret\n    };\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n    typedef Matrix<Scalar, 1, ColsAtCompileTime> RowVectorType;\n    typedef Matrix<Scalar, RowsAtCompileTime, 1> ColVectorType;\n    typedef BandMatrix<RealScalar, ColsAtCompileTime, ColsAtCompileTime, 1, 0, RowMajor> BidiagonalType;\n    typedef Matrix<Scalar, ColsAtCompileTime, 1> DiagVectorType;\n    typedef Matrix<Scalar, ColsAtCompileTimeMinusOne, 1> SuperDiagVectorType;\n    typedef HouseholderSequence<\n              const MatrixType,\n              const typename internal::remove_all<typename Diagonal<const MatrixType,0>::ConjugateReturnType>::type\n            > HouseholderUSequenceType;\n    typedef HouseholderSequence<\n              const typename internal::remove_all<typename MatrixType::ConjugateReturnType>::type,\n              Diagonal<const MatrixType,1>,\n              OnTheRight\n            > HouseholderVSequenceType;\n    \n    /**\n    * \\brief Default Constructor.\n    *\n    * The default constructor is useful in cases in which the user intends to\n    * perform decompositions via Bidiagonalization::compute(const MatrixType&).\n    */\n    UpperBidiagonalization() : m_householder(), m_bidiagonal(), m_isInitialized(false) {}\n\n    explicit UpperBidiagonalization(const MatrixType& matrix)\n      : m_householder(matrix.rows(), matrix.cols()),\n        m_bidiagonal(matrix.cols(), matrix.cols()),\n        m_isInitialized(false)\n    {\n      compute(matrix);\n    }\n    \n    UpperBidiagonalization& compute(const MatrixType& matrix);\n    UpperBidiagonalization& computeUnblocked(const MatrixType& matrix);\n    \n    const MatrixType& householder() const { return m_householder; }\n    const BidiagonalType& bidiagonal() const { return m_bidiagonal; }\n    \n    const HouseholderUSequenceType householderU() const\n    {\n      eigen_assert(m_isInitialized && \"UpperBidiagonalization is not initialized.\");\n      return HouseholderUSequenceType(m_householder, m_householder.diagonal().conjugate());\n    }\n\n    const HouseholderVSequenceType householderV() // const here gives nasty errors and i'm lazy\n    {\n      eigen_assert(m_isInitialized && \"UpperBidiagonalization is not initialized.\");\n      return HouseholderVSequenceType(m_householder.conjugate(), m_householder.const_derived().template diagonal<1>())\n             .setLength(m_householder.cols()-1)\n             .setShift(1);\n    }\n    \n  protected:\n    MatrixType m_householder;\n    BidiagonalType m_bidiagonal;\n    bool m_isInitialized;\n};\n\n// Standard upper bidiagonalization without fancy optimizations\n// This version should be faster for small matrix size\ntemplate<typename MatrixType>\nvoid upperbidiagonalization_inplace_unblocked(MatrixType& mat,\n                                              typename MatrixType::RealScalar *diagonal,\n                                              typename MatrixType::RealScalar *upper_diagonal,\n                                              typename MatrixType::Scalar* tempData = 0)\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index rows = mat.rows();\n  Index cols = mat.cols();\n\n  typedef Matrix<Scalar,Dynamic,1,ColMajor,MatrixType::MaxRowsAtCompileTime,1> TempType;\n  TempType tempVector;\n  if(tempData==0)\n  {\n    tempVector.resize(rows);\n    tempData = tempVector.data();\n  }\n\n  for (Index k = 0; /* breaks at k==cols-1 below */ ; ++k)\n  {\n    Index remainingRows = rows - k;\n    Index remainingCols = cols - k - 1;\n\n    // construct left householder transform in-place in A\n    mat.col(k).tail(remainingRows)\n       .makeHouseholderInPlace(mat.coeffRef(k,k), diagonal[k]);\n    // apply householder transform to remaining part of A on the left\n    mat.bottomRightCorner(remainingRows, remainingCols)\n       .applyHouseholderOnTheLeft(mat.col(k).tail(remainingRows-1), mat.coeff(k,k), tempData);\n\n    if(k == cols-1) break;\n\n    // construct right householder transform in-place in mat\n    mat.row(k).tail(remainingCols)\n       .makeHouseholderInPlace(mat.coeffRef(k,k+1), upper_diagonal[k]);\n    // apply householder transform to remaining part of mat on the left\n    mat.bottomRightCorner(remainingRows-1, remainingCols)\n       .applyHouseholderOnTheRight(mat.row(k).tail(remainingCols-1).adjoint(), mat.coeff(k,k+1), tempData);\n  }\n}\n\n/** \\internal\n  * Helper routine for the block reduction to upper bidiagonal form.\n  *\n  * Let's partition the matrix A:\n  * \n  *      | A00 A01 |\n  *  A = |         |\n  *      | A10 A11 |\n  *\n  * This function reduces to bidiagonal form the left \\c rows x \\a blockSize vertical panel [A00/A10]\n  * and the \\a blockSize x \\c cols horizontal panel [A00 A01] of the matrix \\a A. The bottom-right block A11\n  * is updated using matrix-matrix products:\n  *   A22 -= V * Y^T - X * U^T\n  * where V and U contains the left and right Householder vectors. U and V are stored in A10, and A01\n  * respectively, and the update matrices X and Y are computed during the reduction.\n  * \n  */\ntemplate<typename MatrixType>\nvoid upperbidiagonalization_blocked_helper(MatrixType& A,\n                                           typename MatrixType::RealScalar *diagonal,\n                                           typename MatrixType::RealScalar *upper_diagonal,\n                                           Index bs,\n                                           Ref<Matrix<typename MatrixType::Scalar, Dynamic, Dynamic,\n                                                      traits<MatrixType>::Flags & RowMajorBit> > X,\n                                           Ref<Matrix<typename MatrixType::Scalar, Dynamic, Dynamic,\n                                                      traits<MatrixType>::Flags & RowMajorBit> > Y)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef typename NumTraits<RealScalar>::Literal Literal;\n  enum { StorageOrder = traits<MatrixType>::Flags & RowMajorBit };\n  typedef InnerStride<int(StorageOrder) == int(ColMajor) ? 1 : Dynamic> ColInnerStride;\n  typedef InnerStride<int(StorageOrder) == int(ColMajor) ? Dynamic : 1> RowInnerStride;\n  typedef Ref<Matrix<Scalar, Dynamic, 1>, 0, ColInnerStride>    SubColumnType;\n  typedef Ref<Matrix<Scalar, 1, Dynamic>, 0, RowInnerStride>    SubRowType;\n  typedef Ref<Matrix<Scalar, Dynamic, Dynamic, StorageOrder > > SubMatType;\n  \n  Index brows = A.rows();\n  Index bcols = A.cols();\n\n  Scalar tau_u, tau_u_prev(0), tau_v;\n\n  for(Index k = 0; k < bs; ++k)\n  {\n    Index remainingRows = brows - k;\n    Index remainingCols = bcols - k - 1;\n\n    SubMatType X_k1( X.block(k,0, remainingRows,k) );\n    SubMatType V_k1( A.block(k,0, remainingRows,k) );\n\n    // 1 - update the k-th column of A\n    SubColumnType v_k = A.col(k).tail(remainingRows);\n          v_k -= V_k1 * Y.row(k).head(k).adjoint();\n    if(k) v_k -= X_k1 * A.col(k).head(k);\n    \n    // 2 - construct left Householder transform in-place\n    v_k.makeHouseholderInPlace(tau_v, diagonal[k]);\n       \n    if(k+1<bcols)\n    {\n      SubMatType Y_k  ( Y.block(k+1,0, remainingCols, k+1) );\n      SubMatType U_k1 ( A.block(0,k+1, k,remainingCols) );\n      \n      // this eases the application of Householder transforAions\n      // A(k,k) will store tau_v later\n      A(k,k) = Scalar(1);\n\n      // 3 - Compute y_k^T = tau_v * ( A^T*v_k - Y_k-1*V_k-1^T*v_k - U_k-1*X_k-1^T*v_k )\n      {\n        SubColumnType y_k( Y.col(k).tail(remainingCols) );\n        \n        // let's use the beginning of column k of Y as a temporary vector\n        SubColumnType tmp( Y.col(k).head(k) );\n        y_k.noalias()  = A.block(k,k+1, remainingRows,remainingCols).adjoint() * v_k; // bottleneck\n        tmp.noalias()  = V_k1.adjoint()  * v_k;\n        y_k.noalias() -= Y_k.leftCols(k) * tmp;\n        tmp.noalias()  = X_k1.adjoint()  * v_k;\n        y_k.noalias() -= U_k1.adjoint()  * tmp;\n        y_k *= numext::conj(tau_v);\n      }\n\n      // 4 - update k-th row of A (it will become u_k)\n      SubRowType u_k( A.row(k).tail(remainingCols) );\n      u_k = u_k.conjugate();\n      {\n        u_k -= Y_k * A.row(k).head(k+1).adjoint();\n        if(k) u_k -= U_k1.adjoint() * X.row(k).head(k).adjoint();\n      }\n\n      // 5 - construct right Householder transform in-place\n      u_k.makeHouseholderInPlace(tau_u, upper_diagonal[k]);\n\n      // this eases the application of Householder transformations\n      // A(k,k+1) will store tau_u later\n      A(k,k+1) = Scalar(1);\n\n      // 6 - Compute x_k = tau_u * ( A*u_k - X_k-1*U_k-1^T*u_k - V_k*Y_k^T*u_k )\n      {\n        SubColumnType x_k ( X.col(k).tail(remainingRows-1) );\n        \n        // let's use the beginning of column k of X as a temporary vectors\n        // note that tmp0 and tmp1 overlaps\n        SubColumnType tmp0 ( X.col(k).head(k) ),\n                      tmp1 ( X.col(k).head(k+1) );\n                    \n        x_k.noalias()   = A.block(k+1,k+1, remainingRows-1,remainingCols) * u_k.transpose(); // bottleneck\n        tmp0.noalias()  = U_k1 * u_k.transpose();\n        x_k.noalias()  -= X_k1.bottomRows(remainingRows-1) * tmp0;\n        tmp1.noalias()  = Y_k.adjoint() * u_k.transpose();\n        x_k.noalias()  -= A.block(k+1,0, remainingRows-1,k+1) * tmp1;\n        x_k *= numext::conj(tau_u);\n        tau_u = numext::conj(tau_u);\n        u_k = u_k.conjugate();\n      }\n\n      if(k>0) A.coeffRef(k-1,k) = tau_u_prev;\n      tau_u_prev = tau_u;\n    }\n    else\n      A.coeffRef(k-1,k) = tau_u_prev;\n\n    A.coeffRef(k,k) = tau_v;\n  }\n  \n  if(bs<bcols)\n    A.coeffRef(bs-1,bs) = tau_u_prev;\n\n  // update A22\n  if(bcols>bs && brows>bs)\n  {\n    SubMatType A11( A.bottomRightCorner(brows-bs,bcols-bs) );\n    SubMatType A10( A.block(bs,0, brows-bs,bs) );\n    SubMatType A01( A.block(0,bs, bs,bcols-bs) );\n    Scalar tmp = A01(bs-1,0);\n    A01(bs-1,0) = Literal(1);\n    A11.noalias() -= A10 * Y.topLeftCorner(bcols,bs).bottomRows(bcols-bs).adjoint();\n    A11.noalias() -= X.topLeftCorner(brows,bs).bottomRows(brows-bs) * A01;\n    A01(bs-1,0) = tmp;\n  }\n}\n\n/** \\internal\n  *\n  * Implementation of a block-bidiagonal reduction.\n  * It is based on the following paper:\n  *   The Design of a Parallel Dense Linear Algebra Software Library: Reduction to Hessenberg, Tridiagonal, and Bidiagonal Form.\n  *   by Jaeyoung Choi, Jack J. Dongarra, David W. Walker. (1995)\n  *   section 3.3\n  */\ntemplate<typename MatrixType, typename BidiagType>\nvoid upperbidiagonalization_inplace_blocked(MatrixType& A, BidiagType& bidiagonal,\n                                            Index maxBlockSize=32,\n                                            typename MatrixType::Scalar* /*tempData*/ = 0)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Block<MatrixType,Dynamic,Dynamic> BlockType;\n\n  Index rows = A.rows();\n  Index cols = A.cols();\n  Index size = (std::min)(rows, cols);\n\n  // X and Y are work space\n  enum { StorageOrder = traits<MatrixType>::Flags & RowMajorBit };\n  Matrix<Scalar,\n         MatrixType::RowsAtCompileTime,\n         Dynamic,\n         StorageOrder,\n         MatrixType::MaxRowsAtCompileTime> X(rows,maxBlockSize);\n  Matrix<Scalar,\n         MatrixType::ColsAtCompileTime,\n         Dynamic,\n         StorageOrder,\n         MatrixType::MaxColsAtCompileTime> Y(cols,maxBlockSize);\n  Index blockSize = (std::min)(maxBlockSize,size);\n\n  Index k = 0;\n  for(k = 0; k < size; k += blockSize)\n  {\n    Index bs = (std::min)(size-k,blockSize);  // actual size of the block\n    Index brows = rows - k;                   // rows of the block\n    Index bcols = cols - k;                   // columns of the block\n\n    // partition the matrix A:\n    // \n    //      | A00 A01 A02 |\n    //      |             |\n    // A  = | A10 A11 A12 |\n    //      |             |\n    //      | A20 A21 A22 |\n    //\n    // where A11 is a bs x bs diagonal block,\n    // and let:\n    //      | A11 A12 |\n    //  B = |         |\n    //      | A21 A22 |\n\n    BlockType B = A.block(k,k,brows,bcols);\n    \n    // This stage performs the bidiagonalization of A11, A21, A12, and updating of A22.\n    // Finally, the algorithm continue on the updated A22.\n    //\n    // However, if B is too small, or A22 empty, then let's use an unblocked strategy\n    if(k+bs==cols || bcols<48) // somewhat arbitrary threshold\n    {\n      upperbidiagonalization_inplace_unblocked(B,\n                                               &(bidiagonal.template diagonal<0>().coeffRef(k)),\n                                               &(bidiagonal.template diagonal<1>().coeffRef(k)),\n                                               X.data()\n                                              );\n      break; // We're done\n    }\n    else\n    {\n      upperbidiagonalization_blocked_helper<BlockType>( B,\n                                                        &(bidiagonal.template diagonal<0>().coeffRef(k)),\n                                                        &(bidiagonal.template diagonal<1>().coeffRef(k)),\n                                                        bs,\n                                                        X.topLeftCorner(brows,bs),\n                                                        Y.topLeftCorner(bcols,bs)\n                                                      );\n    }\n  }\n}\n\ntemplate<typename MatrixType_>\nUpperBidiagonalization<MatrixType_>& UpperBidiagonalization<MatrixType_>::computeUnblocked(const MatrixType_& matrix)\n{\n  Index rows = matrix.rows();\n  Index cols = matrix.cols();\n  EIGEN_ONLY_USED_FOR_DEBUG(cols);\n\n  eigen_assert(rows >= cols && \"UpperBidiagonalization is only for Arices satisfying rows>=cols.\");\n\n  m_householder = matrix;\n\n  ColVectorType temp(rows);\n\n  upperbidiagonalization_inplace_unblocked(m_householder,\n                                           &(m_bidiagonal.template diagonal<0>().coeffRef(0)),\n                                           &(m_bidiagonal.template diagonal<1>().coeffRef(0)),\n                                           temp.data());\n\n  m_isInitialized = true;\n  return *this;\n}\n\ntemplate<typename MatrixType_>\nUpperBidiagonalization<MatrixType_>& UpperBidiagonalization<MatrixType_>::compute(const MatrixType_& matrix)\n{\n  Index rows = matrix.rows();\n  Index cols = matrix.cols();\n  EIGEN_ONLY_USED_FOR_DEBUG(rows);\n  EIGEN_ONLY_USED_FOR_DEBUG(cols);\n\n  eigen_assert(rows >= cols && \"UpperBidiagonalization is only for Arices satisfying rows>=cols.\");\n\n  m_householder = matrix;\n  upperbidiagonalization_inplace_blocked(m_householder, m_bidiagonal);\n            \n  m_isInitialized = true;\n  return *this;\n}\n\n#if 0\n/** \\return the Householder QR decomposition of \\c *this.\n  *\n  * \\sa class Bidiagonalization\n  */\ntemplate<typename Derived>\nconst UpperBidiagonalization<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::bidiagonalization() const\n{\n  return UpperBidiagonalization<PlainObject>(eval());\n}\n#endif\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_BIDIAGONALIZATION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCholesky/SimplicialCholesky.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SIMPLICIAL_CHOLESKY_H\n#define EIGEN_SIMPLICIAL_CHOLESKY_H\n\nnamespace Eigen { \n\nenum SimplicialCholeskyMode {\n  SimplicialCholeskyLLT,\n  SimplicialCholeskyLDLT\n};\n\nnamespace internal {\n  template<typename CholMatrixType, typename InputMatrixType>\n  struct simplicial_cholesky_grab_input {\n    typedef CholMatrixType const * ConstCholMatrixPtr;\n    static void run(const InputMatrixType& input, ConstCholMatrixPtr &pmat, CholMatrixType &tmp)\n    {\n      tmp = input;\n      pmat = &tmp;\n    }\n  };\n  \n  template<typename MatrixType>\n  struct simplicial_cholesky_grab_input<MatrixType,MatrixType> {\n    typedef MatrixType const * ConstMatrixPtr;\n    static void run(const MatrixType& input, ConstMatrixPtr &pmat, MatrixType &/*tmp*/)\n    {\n      pmat = &input;\n    }\n  };\n} // end namespace internal\n\n/** \\ingroup SparseCholesky_Module\n  * \\brief A base class for direct sparse Cholesky factorizations\n  *\n  * This is a base class for LL^T and LDL^T Cholesky factorizations of sparse matrices that are\n  * selfadjoint and positive definite. These factorizations allow for solving A.X = B where\n  * X and B can be either dense or sparse.\n  * \n  * In order to reduce the fill-in, a symmetric permutation P is applied prior to the factorization\n  * such that the factorized matrix is P A P^-1.\n  *\n  * \\tparam Derived the type of the derived class, that is the actual factorization type.\n  *\n  */\ntemplate<typename Derived>\nclass SimplicialCholeskyBase : public SparseSolverBase<Derived>\n{\n    typedef SparseSolverBase<Derived> Base;\n    using Base::m_isInitialized;\n    \n  public:\n    typedef typename internal::traits<Derived>::MatrixType MatrixType;\n    typedef typename internal::traits<Derived>::OrderingType OrderingType;\n    enum { UpLo = internal::traits<Derived>::UpLo };\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> CholMatrixType;\n    typedef CholMatrixType const * ConstCholMatrixPtr;\n    typedef Matrix<Scalar,Dynamic,1> VectorType;\n    typedef Matrix<StorageIndex,Dynamic,1> VectorI;\n\n    enum {\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n\n  public:\n    \n    using Base::derived;\n\n    /** Default constructor */\n    SimplicialCholeskyBase()\n      : m_info(Success),\n        m_factorizationIsOk(false),\n        m_analysisIsOk(false),\n        m_shiftOffset(0),\n        m_shiftScale(1)\n    {}\n\n    explicit SimplicialCholeskyBase(const MatrixType& matrix)\n      : m_info(Success),\n        m_factorizationIsOk(false),\n        m_analysisIsOk(false),\n        m_shiftOffset(0),\n        m_shiftScale(1)\n    {\n      derived().compute(matrix);\n    }\n\n    ~SimplicialCholeskyBase()\n    {\n    }\n\n    Derived& derived() { return *static_cast<Derived*>(this); }\n    const Derived& derived() const { return *static_cast<const Derived*>(this); }\n    \n    inline Index cols() const { return m_matrix.cols(); }\n    inline Index rows() const { return m_matrix.rows(); }\n    \n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the matrix.appears to be negative.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_info;\n    }\n    \n    /** \\returns the permutation P\n      * \\sa permutationPinv() */\n    const PermutationMatrix<Dynamic,Dynamic,StorageIndex>& permutationP() const\n    { return m_P; }\n    \n    /** \\returns the inverse P^-1 of the permutation P\n      * \\sa permutationP() */\n    const PermutationMatrix<Dynamic,Dynamic,StorageIndex>& permutationPinv() const\n    { return m_Pinv; }\n\n    /** Sets the shift parameters that will be used to adjust the diagonal coefficients during the numerical factorization.\n      *\n      * During the numerical factorization, the diagonal coefficients are transformed by the following linear model:\\n\n      * \\c d_ii = \\a offset + \\a scale * \\c d_ii\n      *\n      * The default is the identity transformation with \\a offset=0, and \\a scale=1.\n      *\n      * \\returns a reference to \\c *this.\n      */\n    Derived& setShift(const RealScalar& offset, const RealScalar& scale = 1)\n    {\n      m_shiftOffset = offset;\n      m_shiftScale = scale;\n      return derived();\n    }\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n    /** \\internal */\n    template<typename Stream>\n    void dumpMemory(Stream& s)\n    {\n      int total = 0;\n      s << \"  L:        \" << ((total+=(m_matrix.cols()+1) * sizeof(int) + m_matrix.nonZeros()*(sizeof(int)+sizeof(Scalar))) >> 20) << \"Mb\" << \"\\n\";\n      s << \"  diag:     \" << ((total+=m_diag.size() * sizeof(Scalar)) >> 20) << \"Mb\" << \"\\n\";\n      s << \"  tree:     \" << ((total+=m_parent.size() * sizeof(int)) >> 20) << \"Mb\" << \"\\n\";\n      s << \"  nonzeros: \" << ((total+=m_nonZerosPerCol.size() * sizeof(int)) >> 20) << \"Mb\" << \"\\n\";\n      s << \"  perm:     \" << ((total+=m_P.size() * sizeof(int)) >> 20) << \"Mb\" << \"\\n\";\n      s << \"  perm^-1:  \" << ((total+=m_Pinv.size() * sizeof(int)) >> 20) << \"Mb\" << \"\\n\";\n      s << \"  TOTAL:    \" << (total>> 20) << \"Mb\" << \"\\n\";\n    }\n\n    /** \\internal */\n    template<typename Rhs,typename Dest>\n    void _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const\n    {\n      eigen_assert(m_factorizationIsOk && \"The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()\");\n      eigen_assert(m_matrix.rows()==b.rows());\n\n      if(m_info!=Success)\n        return;\n\n      if(m_P.size()>0)\n        dest = m_P * b;\n      else\n        dest = b;\n\n      if(m_matrix.nonZeros()>0) // otherwise L==I\n        derived().matrixL().solveInPlace(dest);\n\n      if(m_diag.size()>0)\n        dest = m_diag.asDiagonal().inverse() * dest;\n\n      if (m_matrix.nonZeros()>0) // otherwise U==I\n        derived().matrixU().solveInPlace(dest);\n\n      if(m_P.size()>0)\n        dest = m_Pinv * dest;\n    }\n    \n    template<typename Rhs,typename Dest>\n    void _solve_impl(const SparseMatrixBase<Rhs> &b, SparseMatrixBase<Dest> &dest) const\n    {\n      internal::solve_sparse_through_dense_panels(derived(), b, dest);\n    }\n\n#endif // EIGEN_PARSED_BY_DOXYGEN\n\n  protected:\n    \n    /** Computes the sparse Cholesky decomposition of \\a matrix */\n    template<bool DoLDLT>\n    void compute(const MatrixType& matrix)\n    {\n      eigen_assert(matrix.rows()==matrix.cols());\n      Index size = matrix.cols();\n      CholMatrixType tmp(size,size);\n      ConstCholMatrixPtr pmat;\n      ordering(matrix, pmat, tmp);\n      analyzePattern_preordered(*pmat, DoLDLT);\n      factorize_preordered<DoLDLT>(*pmat);\n    }\n    \n    template<bool DoLDLT>\n    void factorize(const MatrixType& a)\n    {\n      eigen_assert(a.rows()==a.cols());\n      Index size = a.cols();\n      CholMatrixType tmp(size,size);\n      ConstCholMatrixPtr pmat;\n      \n      if(m_P.size() == 0 && (int(UpLo) & int(Upper)) == Upper)\n      {\n        // If there is no ordering, try to directly use the input matrix without any copy\n        internal::simplicial_cholesky_grab_input<CholMatrixType,MatrixType>::run(a, pmat, tmp);\n      }\n      else\n      {\n        tmp.template selfadjointView<Upper>() = a.template selfadjointView<UpLo>().twistedBy(m_P);\n        pmat = &tmp;\n      }\n      \n      factorize_preordered<DoLDLT>(*pmat);\n    }\n\n    template<bool DoLDLT>\n    void factorize_preordered(const CholMatrixType& a);\n\n    void analyzePattern(const MatrixType& a, bool doLDLT)\n    {\n      eigen_assert(a.rows()==a.cols());\n      Index size = a.cols();\n      CholMatrixType tmp(size,size);\n      ConstCholMatrixPtr pmat;\n      ordering(a, pmat, tmp);\n      analyzePattern_preordered(*pmat,doLDLT);\n    }\n    void analyzePattern_preordered(const CholMatrixType& a, bool doLDLT);\n    \n    void ordering(const MatrixType& a, ConstCholMatrixPtr &pmat, CholMatrixType& ap);\n\n    /** keeps off-diagonal entries; drops diagonal entries */\n    struct keep_diag {\n      inline bool operator() (const Index& row, const Index& col, const Scalar&) const\n      {\n        return row!=col;\n      }\n    };\n\n    mutable ComputationInfo m_info;\n    bool m_factorizationIsOk;\n    bool m_analysisIsOk;\n    \n    CholMatrixType m_matrix;\n    VectorType m_diag;                                // the diagonal coefficients (LDLT mode)\n    VectorI m_parent;                                 // elimination tree\n    VectorI m_nonZerosPerCol;\n    PermutationMatrix<Dynamic,Dynamic,StorageIndex> m_P;     // the permutation\n    PermutationMatrix<Dynamic,Dynamic,StorageIndex> m_Pinv;  // the inverse permutation\n\n    RealScalar m_shiftOffset;\n    RealScalar m_shiftScale;\n};\n\ntemplate<typename MatrixType_, int UpLo_ = Lower, typename Ordering_ = AMDOrdering<typename MatrixType_::StorageIndex> > class SimplicialLLT;\ntemplate<typename MatrixType_, int UpLo_ = Lower, typename Ordering_ = AMDOrdering<typename MatrixType_::StorageIndex> > class SimplicialLDLT;\ntemplate<typename MatrixType_, int UpLo_ = Lower, typename Ordering_ = AMDOrdering<typename MatrixType_::StorageIndex> > class SimplicialCholesky;\n\nnamespace internal {\n\ntemplate<typename MatrixType_, int UpLo_, typename Ordering_> struct traits<SimplicialLLT<MatrixType_,UpLo_,Ordering_> >\n{\n  typedef MatrixType_ MatrixType;\n  typedef Ordering_ OrderingType;\n  enum { UpLo = UpLo_ };\n  typedef typename MatrixType::Scalar                         Scalar;\n  typedef typename MatrixType::StorageIndex                   StorageIndex;\n  typedef SparseMatrix<Scalar, ColMajor, StorageIndex>        CholMatrixType;\n  typedef TriangularView<const CholMatrixType, Eigen::Lower>  MatrixL;\n  typedef TriangularView<const typename CholMatrixType::AdjointReturnType, Eigen::Upper>   MatrixU;\n  static inline MatrixL getL(const CholMatrixType& m) { return MatrixL(m); }\n  static inline MatrixU getU(const CholMatrixType& m) { return MatrixU(m.adjoint()); }\n};\n\ntemplate<typename MatrixType_,int UpLo_, typename Ordering_> struct traits<SimplicialLDLT<MatrixType_,UpLo_,Ordering_> >\n{\n  typedef MatrixType_ MatrixType;\n  typedef Ordering_ OrderingType;\n  enum { UpLo = UpLo_ };\n  typedef typename MatrixType::Scalar                             Scalar;\n  typedef typename MatrixType::StorageIndex                       StorageIndex;\n  typedef SparseMatrix<Scalar, ColMajor, StorageIndex>            CholMatrixType;\n  typedef TriangularView<const CholMatrixType, Eigen::UnitLower>  MatrixL;\n  typedef TriangularView<const typename CholMatrixType::AdjointReturnType, Eigen::UnitUpper> MatrixU;\n  static inline MatrixL getL(const CholMatrixType& m) { return MatrixL(m); }\n  static inline MatrixU getU(const CholMatrixType& m) { return MatrixU(m.adjoint()); }\n};\n\ntemplate<typename MatrixType_, int UpLo_, typename Ordering_> struct traits<SimplicialCholesky<MatrixType_,UpLo_,Ordering_> >\n{\n  typedef MatrixType_ MatrixType;\n  typedef Ordering_ OrderingType;\n  enum { UpLo = UpLo_ };\n};\n\n}\n\n/** \\ingroup SparseCholesky_Module\n  * \\class SimplicialLLT\n  * \\brief A direct sparse LLT Cholesky factorizations\n  *\n  * This class provides a LL^T Cholesky factorizations of sparse matrices that are\n  * selfadjoint and positive definite. The factorization allows for solving A.X = B where\n  * X and B can be either dense or sparse.\n  * \n  * In order to reduce the fill-in, a symmetric permutation P is applied prior to the factorization\n  * such that the factorized matrix is P A P^-1.\n  *\n  * \\tparam MatrixType_ the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam UpLo_ the triangular part that will be used for the computations. It can be Lower\n  *               or Upper. Default is Lower.\n  * \\tparam Ordering_ The ordering method to use, either AMDOrdering<> or NaturalOrdering<>. Default is AMDOrdering<>\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa class SimplicialLDLT, class AMDOrdering, class NaturalOrdering\n  */\ntemplate<typename MatrixType_, int UpLo_, typename Ordering_>\n    class SimplicialLLT : public SimplicialCholeskyBase<SimplicialLLT<MatrixType_,UpLo_,Ordering_> >\n{\npublic:\n    typedef MatrixType_ MatrixType;\n    enum { UpLo = UpLo_ };\n    typedef SimplicialCholeskyBase<SimplicialLLT> Base;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef SparseMatrix<Scalar,ColMajor,Index> CholMatrixType;\n    typedef Matrix<Scalar,Dynamic,1> VectorType;\n    typedef internal::traits<SimplicialLLT> Traits;\n    typedef typename Traits::MatrixL  MatrixL;\n    typedef typename Traits::MatrixU  MatrixU;\npublic:\n    /** Default constructor */\n    SimplicialLLT() : Base() {}\n    /** Constructs and performs the LLT factorization of \\a matrix */\n    explicit SimplicialLLT(const MatrixType& matrix)\n        : Base(matrix) {}\n\n    /** \\returns an expression of the factor L */\n    inline const MatrixL matrixL() const {\n        eigen_assert(Base::m_factorizationIsOk && \"Simplicial LLT not factorized\");\n        return Traits::getL(Base::m_matrix);\n    }\n\n    /** \\returns an expression of the factor U (= L^*) */\n    inline const MatrixU matrixU() const {\n        eigen_assert(Base::m_factorizationIsOk && \"Simplicial LLT not factorized\");\n        return Traits::getU(Base::m_matrix);\n    }\n    \n    /** Computes the sparse Cholesky decomposition of \\a matrix */\n    SimplicialLLT& compute(const MatrixType& matrix)\n    {\n      Base::template compute<false>(matrix);\n      return *this;\n    }\n\n    /** Performs a symbolic decomposition on the sparcity of \\a matrix.\n      *\n      * This function is particularly useful when solving for several problems having the same structure.\n      *\n      * \\sa factorize()\n      */\n    void analyzePattern(const MatrixType& a)\n    {\n      Base::analyzePattern(a, false);\n    }\n\n    /** Performs a numeric decomposition of \\a matrix\n      *\n      * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed.\n      *\n      * \\sa analyzePattern()\n      */\n    void factorize(const MatrixType& a)\n    {\n      Base::template factorize<false>(a);\n    }\n\n    /** \\returns the determinant of the underlying matrix from the current factorization */\n    Scalar determinant() const\n    {\n      Scalar detL = Base::m_matrix.diagonal().prod();\n      return numext::abs2(detL);\n    }\n};\n\n/** \\ingroup SparseCholesky_Module\n  * \\class SimplicialLDLT\n  * \\brief A direct sparse LDLT Cholesky factorizations without square root.\n  *\n  * This class provides a LDL^T Cholesky factorizations without square root of sparse matrices that are\n  * selfadjoint and positive definite. The factorization allows for solving A.X = B where\n  * X and B can be either dense or sparse.\n  * \n  * In order to reduce the fill-in, a symmetric permutation P is applied prior to the factorization\n  * such that the factorized matrix is P A P^-1.\n  *\n  * \\tparam MatrixType_ the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam UpLo_ the triangular part that will be used for the computations. It can be Lower\n  *               or Upper. Default is Lower.\n  * \\tparam Ordering_ The ordering method to use, either AMDOrdering<> or NaturalOrdering<>. Default is AMDOrdering<>\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa class SimplicialLLT, class AMDOrdering, class NaturalOrdering\n  */\ntemplate<typename MatrixType_, int UpLo_, typename Ordering_>\n    class SimplicialLDLT : public SimplicialCholeskyBase<SimplicialLDLT<MatrixType_,UpLo_,Ordering_> >\n{\npublic:\n    typedef MatrixType_ MatrixType;\n    enum { UpLo = UpLo_ };\n    typedef SimplicialCholeskyBase<SimplicialLDLT> Base;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> CholMatrixType;\n    typedef Matrix<Scalar,Dynamic,1> VectorType;\n    typedef internal::traits<SimplicialLDLT> Traits;\n    typedef typename Traits::MatrixL  MatrixL;\n    typedef typename Traits::MatrixU  MatrixU;\npublic:\n    /** Default constructor */\n    SimplicialLDLT() : Base() {}\n\n    /** Constructs and performs the LLT factorization of \\a matrix */\n    explicit SimplicialLDLT(const MatrixType& matrix)\n        : Base(matrix) {}\n\n    /** \\returns a vector expression of the diagonal D */\n    inline const VectorType vectorD() const {\n        eigen_assert(Base::m_factorizationIsOk && \"Simplicial LDLT not factorized\");\n        return Base::m_diag;\n    }\n    /** \\returns an expression of the factor L */\n    inline const MatrixL matrixL() const {\n        eigen_assert(Base::m_factorizationIsOk && \"Simplicial LDLT not factorized\");\n        return Traits::getL(Base::m_matrix);\n    }\n\n    /** \\returns an expression of the factor U (= L^*) */\n    inline const MatrixU matrixU() const {\n        eigen_assert(Base::m_factorizationIsOk && \"Simplicial LDLT not factorized\");\n        return Traits::getU(Base::m_matrix);\n    }\n\n    /** Computes the sparse Cholesky decomposition of \\a matrix */\n    SimplicialLDLT& compute(const MatrixType& matrix)\n    {\n      Base::template compute<true>(matrix);\n      return *this;\n    }\n    \n    /** Performs a symbolic decomposition on the sparcity of \\a matrix.\n      *\n      * This function is particularly useful when solving for several problems having the same structure.\n      *\n      * \\sa factorize()\n      */\n    void analyzePattern(const MatrixType& a)\n    {\n      Base::analyzePattern(a, true);\n    }\n\n    /** Performs a numeric decomposition of \\a matrix\n      *\n      * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed.\n      *\n      * \\sa analyzePattern()\n      */\n    void factorize(const MatrixType& a)\n    {\n      Base::template factorize<true>(a);\n    }\n\n    /** \\returns the determinant of the underlying matrix from the current factorization */\n    Scalar determinant() const\n    {\n      return Base::m_diag.prod();\n    }\n};\n\n/** \\deprecated use SimplicialLDLT or class SimplicialLLT\n  * \\ingroup SparseCholesky_Module\n  * \\class SimplicialCholesky\n  *\n  * \\sa class SimplicialLDLT, class SimplicialLLT\n  */\ntemplate<typename MatrixType_, int UpLo_, typename Ordering_>\n    class SimplicialCholesky : public SimplicialCholeskyBase<SimplicialCholesky<MatrixType_,UpLo_,Ordering_> >\n{\npublic:\n    typedef MatrixType_ MatrixType;\n    enum { UpLo = UpLo_ };\n    typedef SimplicialCholeskyBase<SimplicialCholesky> Base;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> CholMatrixType;\n    typedef Matrix<Scalar,Dynamic,1> VectorType;\n    typedef internal::traits<SimplicialCholesky> Traits;\n    typedef internal::traits<SimplicialLDLT<MatrixType,UpLo> > LDLTTraits;\n    typedef internal::traits<SimplicialLLT<MatrixType,UpLo>  > LLTTraits;\n  public:\n    SimplicialCholesky() : Base(), m_LDLT(true) {}\n\n    explicit SimplicialCholesky(const MatrixType& matrix)\n      : Base(), m_LDLT(true)\n    {\n      compute(matrix);\n    }\n\n    SimplicialCholesky& setMode(SimplicialCholeskyMode mode)\n    {\n      switch(mode)\n      {\n      case SimplicialCholeskyLLT:\n        m_LDLT = false;\n        break;\n      case SimplicialCholeskyLDLT:\n        m_LDLT = true;\n        break;\n      default:\n        break;\n      }\n\n      return *this;\n    }\n\n    inline const VectorType vectorD() const {\n        eigen_assert(Base::m_factorizationIsOk && \"Simplicial Cholesky not factorized\");\n        return Base::m_diag;\n    }\n    inline const CholMatrixType rawMatrix() const {\n        eigen_assert(Base::m_factorizationIsOk && \"Simplicial Cholesky not factorized\");\n        return Base::m_matrix;\n    }\n    \n    /** Computes the sparse Cholesky decomposition of \\a matrix */\n    SimplicialCholesky& compute(const MatrixType& matrix)\n    {\n      if(m_LDLT)\n        Base::template compute<true>(matrix);\n      else\n        Base::template compute<false>(matrix);\n      return *this;\n    }\n\n    /** Performs a symbolic decomposition on the sparcity of \\a matrix.\n      *\n      * This function is particularly useful when solving for several problems having the same structure.\n      *\n      * \\sa factorize()\n      */\n    void analyzePattern(const MatrixType& a)\n    {\n      Base::analyzePattern(a, m_LDLT);\n    }\n\n    /** Performs a numeric decomposition of \\a matrix\n      *\n      * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed.\n      *\n      * \\sa analyzePattern()\n      */\n    void factorize(const MatrixType& a)\n    {\n      if(m_LDLT)\n        Base::template factorize<true>(a);\n      else\n        Base::template factorize<false>(a);\n    }\n\n    /** \\internal */\n    template<typename Rhs,typename Dest>\n    void _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const\n    {\n      eigen_assert(Base::m_factorizationIsOk && \"The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()\");\n      eigen_assert(Base::m_matrix.rows()==b.rows());\n\n      if(Base::m_info!=Success)\n        return;\n\n      if(Base::m_P.size()>0)\n        dest = Base::m_P * b;\n      else\n        dest = b;\n\n      if(Base::m_matrix.nonZeros()>0) // otherwise L==I\n      {\n        if(m_LDLT)\n          LDLTTraits::getL(Base::m_matrix).solveInPlace(dest);\n        else\n          LLTTraits::getL(Base::m_matrix).solveInPlace(dest);\n      }\n\n      if(Base::m_diag.size()>0)\n        dest = Base::m_diag.real().asDiagonal().inverse() * dest;\n\n      if (Base::m_matrix.nonZeros()>0) // otherwise I==I\n      {\n        if(m_LDLT)\n          LDLTTraits::getU(Base::m_matrix).solveInPlace(dest);\n        else\n          LLTTraits::getU(Base::m_matrix).solveInPlace(dest);\n      }\n\n      if(Base::m_P.size()>0)\n        dest = Base::m_Pinv * dest;\n    }\n    \n    /** \\internal */\n    template<typename Rhs,typename Dest>\n    void _solve_impl(const SparseMatrixBase<Rhs> &b, SparseMatrixBase<Dest> &dest) const\n    {\n      internal::solve_sparse_through_dense_panels(*this, b, dest);\n    }\n    \n    Scalar determinant() const\n    {\n      if(m_LDLT)\n      {\n        return Base::m_diag.prod();\n      }\n      else\n      {\n        Scalar detL = Diagonal<const CholMatrixType>(Base::m_matrix).prod();\n        return numext::abs2(detL);\n      }\n    }\n    \n  protected:\n    bool m_LDLT;\n};\n\ntemplate<typename Derived>\nvoid SimplicialCholeskyBase<Derived>::ordering(const MatrixType& a, ConstCholMatrixPtr &pmat, CholMatrixType& ap)\n{\n  eigen_assert(a.rows()==a.cols());\n  const Index size = a.rows();\n  pmat = &ap;\n  // Note that ordering methods compute the inverse permutation\n  if(!internal::is_same<OrderingType,NaturalOrdering<Index> >::value)\n  {\n    {\n      CholMatrixType C;\n      C = a.template selfadjointView<UpLo>();\n      \n      OrderingType ordering;\n      ordering(C,m_Pinv);\n    }\n\n    if(m_Pinv.size()>0) m_P = m_Pinv.inverse();\n    else                m_P.resize(0);\n    \n    ap.resize(size,size);\n    ap.template selfadjointView<Upper>() = a.template selfadjointView<UpLo>().twistedBy(m_P);\n  }\n  else\n  {\n    m_Pinv.resize(0);\n    m_P.resize(0);\n    if(int(UpLo)==int(Lower) || MatrixType::IsRowMajor)\n    {\n      // we have to transpose the lower part to to the upper one\n      ap.resize(size,size);\n      ap.template selfadjointView<Upper>() = a.template selfadjointView<UpLo>();\n    }\n    else\n      internal::simplicial_cholesky_grab_input<CholMatrixType,MatrixType>::run(a, pmat, ap);\n  }  \n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SIMPLICIAL_CHOLESKY_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCholesky/SimplicialCholesky_impl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/*\nNOTE: these functions have been adapted from the LDL library:\n\nLDL Copyright (c) 2005 by Timothy A. Davis.  All Rights Reserved.\n\nThe author of LDL, Timothy A. Davis., has executed a license with Google LLC\nto permit distribution of this code and derivative works as part of Eigen under\nthe Mozilla Public License v. 2.0, as stated at the top of this file.\n */\n\n#ifndef EIGEN_SIMPLICIAL_CHOLESKY_IMPL_H\n#define EIGEN_SIMPLICIAL_CHOLESKY_IMPL_H\n\nnamespace Eigen {\n\ntemplate<typename Derived>\nvoid SimplicialCholeskyBase<Derived>::analyzePattern_preordered(const CholMatrixType& ap, bool doLDLT)\n{\n  const StorageIndex size = StorageIndex(ap.rows());\n  m_matrix.resize(size, size);\n  m_parent.resize(size);\n  m_nonZerosPerCol.resize(size);\n\n  ei_declare_aligned_stack_constructed_variable(StorageIndex, tags, size, 0);\n\n  for(StorageIndex k = 0; k < size; ++k)\n  {\n    /* L(k,:) pattern: all nodes reachable in etree from nz in A(0:k-1,k) */\n    m_parent[k] = -1;             /* parent of k is not yet known */\n    tags[k] = k;                  /* mark node k as visited */\n    m_nonZerosPerCol[k] = 0;      /* count of nonzeros in column k of L */\n    for(typename CholMatrixType::InnerIterator it(ap,k); it; ++it)\n    {\n      StorageIndex i = it.index();\n      if(i < k)\n      {\n        /* follow path from i to root of etree, stop at flagged node */\n        for(; tags[i] != k; i = m_parent[i])\n        {\n          /* find parent of i if not yet determined */\n          if (m_parent[i] == -1)\n            m_parent[i] = k;\n          m_nonZerosPerCol[i]++;        /* L (k,i) is nonzero */\n          tags[i] = k;                  /* mark i as visited */\n        }\n      }\n    }\n  }\n\n  /* construct Lp index array from m_nonZerosPerCol column counts */\n  StorageIndex* Lp = m_matrix.outerIndexPtr();\n  Lp[0] = 0;\n  for(StorageIndex k = 0; k < size; ++k)\n    Lp[k+1] = Lp[k] + m_nonZerosPerCol[k] + (doLDLT ? 0 : 1);\n\n  m_matrix.resizeNonZeros(Lp[size]);\n\n  m_isInitialized     = true;\n  m_info              = Success;\n  m_analysisIsOk      = true;\n  m_factorizationIsOk = false;\n}\n\n\ntemplate<typename Derived>\ntemplate<bool DoLDLT>\nvoid SimplicialCholeskyBase<Derived>::factorize_preordered(const CholMatrixType& ap)\n{\n  using std::sqrt;\n\n  eigen_assert(m_analysisIsOk && \"You must first call analyzePattern()\");\n  eigen_assert(ap.rows()==ap.cols());\n  eigen_assert(m_parent.size()==ap.rows());\n  eigen_assert(m_nonZerosPerCol.size()==ap.rows());\n\n  const StorageIndex size = StorageIndex(ap.rows());\n  const StorageIndex* Lp = m_matrix.outerIndexPtr();\n  StorageIndex* Li = m_matrix.innerIndexPtr();\n  Scalar* Lx = m_matrix.valuePtr();\n\n  ei_declare_aligned_stack_constructed_variable(Scalar, y, size, 0);\n  ei_declare_aligned_stack_constructed_variable(StorageIndex,  pattern, size, 0);\n  ei_declare_aligned_stack_constructed_variable(StorageIndex,  tags, size, 0);\n\n  bool ok = true;\n  m_diag.resize(DoLDLT ? size : 0);\n\n  for(StorageIndex k = 0; k < size; ++k)\n  {\n    // compute nonzero pattern of kth row of L, in topological order\n    y[k] = Scalar(0);                     // Y(0:k) is now all zero\n    StorageIndex top = size;               // stack for pattern is empty\n    tags[k] = k;                    // mark node k as visited\n    m_nonZerosPerCol[k] = 0;        // count of nonzeros in column k of L\n    for(typename CholMatrixType::InnerIterator it(ap,k); it; ++it)\n    {\n      StorageIndex i = it.index();\n      if(i <= k)\n      {\n        y[i] += numext::conj(it.value());            /* scatter A(i,k) into Y (sum duplicates) */\n        Index len;\n        for(len = 0; tags[i] != k; i = m_parent[i])\n        {\n          pattern[len++] = i;     /* L(k,i) is nonzero */\n          tags[i] = k;            /* mark i as visited */\n        }\n        while(len > 0)\n          pattern[--top] = pattern[--len];\n      }\n    }\n\n    /* compute numerical values kth row of L (a sparse triangular solve) */\n\n    RealScalar d = numext::real(y[k]) * m_shiftScale + m_shiftOffset;    // get D(k,k), apply the shift function, and clear Y(k)\n    y[k] = Scalar(0);\n    for(; top < size; ++top)\n    {\n      Index i = pattern[top];       /* pattern[top:n-1] is pattern of L(:,k) */\n      Scalar yi = y[i];             /* get and clear Y(i) */\n      y[i] = Scalar(0);\n\n      /* the nonzero entry L(k,i) */\n      Scalar l_ki;\n      if(DoLDLT)\n        l_ki = yi / numext::real(m_diag[i]);\n      else\n        yi = l_ki = yi / Lx[Lp[i]];\n\n      Index p2 = Lp[i] + m_nonZerosPerCol[i];\n      Index p;\n      for(p = Lp[i] + (DoLDLT ? 0 : 1); p < p2; ++p)\n        y[Li[p]] -= numext::conj(Lx[p]) * yi;\n      d -= numext::real(l_ki * numext::conj(yi));\n      Li[p] = k;                          /* store L(k,i) in column form of L */\n      Lx[p] = l_ki;\n      ++m_nonZerosPerCol[i];              /* increment count of nonzeros in col i */\n    }\n    if(DoLDLT)\n    {\n      m_diag[k] = d;\n      if(d == RealScalar(0))\n      {\n        ok = false;                         /* failure, D(k,k) is zero */\n        break;\n      }\n    }\n    else\n    {\n      Index p = Lp[k] + m_nonZerosPerCol[k]++;\n      Li[p] = k ;                /* store L(k,k) = sqrt (d) in column k */\n      if(d <= RealScalar(0)) {\n        ok = false;              /* failure, matrix is not positive definite */\n        break;\n      }\n      Lx[p] = sqrt(d) ;\n    }\n  }\n\n  m_info = ok ? Success : NumericalIssue;\n  m_factorizationIsOk = true;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SIMPLICIAL_CHOLESKY_IMPL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/AmbiVector.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_AMBIVECTOR_H\n#define EIGEN_AMBIVECTOR_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\internal\n  * Hybrid sparse/dense vector class designed for intensive read-write operations.\n  *\n  * See BasicSparseLLT and SparseProduct for usage examples.\n  */\ntemplate<typename Scalar_, typename StorageIndex_>\nclass AmbiVector\n{\n  public:\n    typedef Scalar_ Scalar;\n    typedef StorageIndex_ StorageIndex;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n\n    explicit AmbiVector(Index size)\n      : m_buffer(0), m_zero(0), m_size(0), m_end(0), m_allocatedSize(0), m_allocatedElements(0), m_mode(-1)\n    {\n      resize(size);\n    }\n\n    void init(double estimatedDensity);\n    void init(int mode);\n\n    Index nonZeros() const;\n\n    /** Specifies a sub-vector to work on */\n    void setBounds(Index start, Index end) { m_start = convert_index(start); m_end = convert_index(end); }\n\n    void setZero();\n\n    void restart();\n    Scalar& coeffRef(Index i);\n    Scalar& coeff(Index i);\n\n    class Iterator;\n\n    ~AmbiVector() { delete[] m_buffer; }\n\n    void resize(Index size)\n    {\n      if (m_allocatedSize < size)\n        reallocate(size);\n      m_size = convert_index(size);\n    }\n\n    StorageIndex size() const { return m_size; }\n\n  protected:\n    StorageIndex convert_index(Index idx)\n    {\n      return internal::convert_index<StorageIndex>(idx);\n    }\n\n    void reallocate(Index size)\n    {\n      // if the size of the matrix is not too large, let's allocate a bit more than needed such\n      // that we can handle dense vector even in sparse mode.\n      delete[] m_buffer;\n      if (size<1000)\n      {\n        Index allocSize = (size * sizeof(ListEl) + sizeof(Scalar) - 1)/sizeof(Scalar);\n        m_allocatedElements = convert_index((allocSize*sizeof(Scalar))/sizeof(ListEl));\n        m_buffer = new Scalar[allocSize];\n      }\n      else\n      {\n        m_allocatedElements = convert_index((size*sizeof(Scalar))/sizeof(ListEl));\n        m_buffer = new Scalar[size];\n      }\n      m_size = convert_index(size);\n      m_start = 0;\n      m_end = m_size;\n    }\n\n    void reallocateSparse()\n    {\n      Index copyElements = m_allocatedElements;\n      m_allocatedElements = (std::min)(StorageIndex(m_allocatedElements*1.5),m_size);\n      Index allocSize = m_allocatedElements * sizeof(ListEl);\n      allocSize = (allocSize + sizeof(Scalar) - 1)/sizeof(Scalar);\n      Scalar* newBuffer = new Scalar[allocSize];\n      std::memcpy(newBuffer,  m_buffer,  copyElements * sizeof(ListEl));\n      delete[] m_buffer;\n      m_buffer = newBuffer;\n    }\n\n  protected:\n    // element type of the linked list\n    struct ListEl\n    {\n      StorageIndex next;\n      StorageIndex index;\n      Scalar value;\n    };\n\n    // used to store data in both mode\n    Scalar* m_buffer;\n    Scalar m_zero;\n    StorageIndex m_size;\n    StorageIndex m_start;\n    StorageIndex m_end;\n    StorageIndex m_allocatedSize;\n    StorageIndex m_allocatedElements;\n    StorageIndex m_mode;\n\n    // linked list mode\n    StorageIndex m_llStart;\n    StorageIndex m_llCurrent;\n    StorageIndex m_llSize;\n};\n\n/** \\returns the number of non zeros in the current sub vector */\ntemplate<typename Scalar_,typename StorageIndex_>\nIndex AmbiVector<Scalar_,StorageIndex_>::nonZeros() const\n{\n  if (m_mode==IsSparse)\n    return m_llSize;\n  else\n    return m_end - m_start;\n}\n\ntemplate<typename Scalar_,typename StorageIndex_>\nvoid AmbiVector<Scalar_,StorageIndex_>::init(double estimatedDensity)\n{\n  if (estimatedDensity>0.1)\n    init(IsDense);\n  else\n    init(IsSparse);\n}\n\ntemplate<typename Scalar_,typename StorageIndex_>\nvoid AmbiVector<Scalar_,StorageIndex_>::init(int mode)\n{\n  m_mode = mode;\n  // This is only necessary in sparse mode, but we set these unconditionally to avoid some maybe-uninitialized warnings\n  // if (m_mode==IsSparse)\n  {\n    m_llSize = 0;\n    m_llStart = -1;\n  }\n}\n\n/** Must be called whenever we might perform a write access\n  * with an index smaller than the previous one.\n  *\n  * Don't worry, this function is extremely cheap.\n  */\ntemplate<typename Scalar_,typename StorageIndex_>\nvoid AmbiVector<Scalar_,StorageIndex_>::restart()\n{\n  m_llCurrent = m_llStart;\n}\n\n/** Set all coefficients of current subvector to zero */\ntemplate<typename Scalar_,typename StorageIndex_>\nvoid AmbiVector<Scalar_,StorageIndex_>::setZero()\n{\n  if (m_mode==IsDense)\n  {\n    for (Index i=m_start; i<m_end; ++i)\n      m_buffer[i] = Scalar(0);\n  }\n  else\n  {\n    eigen_assert(m_mode==IsSparse);\n    m_llSize = 0;\n    m_llStart = -1;\n  }\n}\n\ntemplate<typename Scalar_,typename StorageIndex_>\nScalar_& AmbiVector<Scalar_,StorageIndex_>::coeffRef(Index i)\n{\n  if (m_mode==IsDense)\n    return m_buffer[i];\n  else\n  {\n    ListEl* EIGEN_RESTRICT llElements = reinterpret_cast<ListEl*>(m_buffer);\n    // TODO factorize the following code to reduce code generation\n    eigen_assert(m_mode==IsSparse);\n    if (m_llSize==0)\n    {\n      // this is the first element\n      m_llStart = 0;\n      m_llCurrent = 0;\n      ++m_llSize;\n      llElements[0].value = Scalar(0);\n      llElements[0].index = convert_index(i);\n      llElements[0].next = -1;\n      return llElements[0].value;\n    }\n    else if (i<llElements[m_llStart].index)\n    {\n      // this is going to be the new first element of the list\n      ListEl& el = llElements[m_llSize];\n      el.value = Scalar(0);\n      el.index = convert_index(i);\n      el.next = m_llStart;\n      m_llStart = m_llSize;\n      ++m_llSize;\n      m_llCurrent = m_llStart;\n      return el.value;\n    }\n    else\n    {\n      StorageIndex nextel = llElements[m_llCurrent].next;\n      eigen_assert(i>=llElements[m_llCurrent].index && \"you must call restart() before inserting an element with lower or equal index\");\n      while (nextel >= 0 && llElements[nextel].index<=i)\n      {\n        m_llCurrent = nextel;\n        nextel = llElements[nextel].next;\n      }\n\n      if (llElements[m_llCurrent].index==i)\n      {\n        // the coefficient already exists and we found it !\n        return llElements[m_llCurrent].value;\n      }\n      else\n      {\n        if (m_llSize>=m_allocatedElements)\n        {\n          reallocateSparse();\n          llElements = reinterpret_cast<ListEl*>(m_buffer);\n        }\n        eigen_internal_assert(m_llSize<m_allocatedElements && \"internal error: overflow in sparse mode\");\n        // let's insert a new coefficient\n        ListEl& el = llElements[m_llSize];\n        el.value = Scalar(0);\n        el.index = convert_index(i);\n        el.next = llElements[m_llCurrent].next;\n        llElements[m_llCurrent].next = m_llSize;\n        ++m_llSize;\n        return el.value;\n      }\n    }\n  }\n}\n\ntemplate<typename Scalar_,typename StorageIndex_>\nScalar_& AmbiVector<Scalar_,StorageIndex_>::coeff(Index i)\n{\n  if (m_mode==IsDense)\n    return m_buffer[i];\n  else\n  {\n    ListEl* EIGEN_RESTRICT llElements = reinterpret_cast<ListEl*>(m_buffer);\n    eigen_assert(m_mode==IsSparse);\n    if ((m_llSize==0) || (i<llElements[m_llStart].index))\n    {\n      return m_zero;\n    }\n    else\n    {\n      Index elid = m_llStart;\n      while (elid >= 0 && llElements[elid].index<i)\n        elid = llElements[elid].next;\n\n      if (llElements[elid].index==i)\n        return llElements[m_llCurrent].value;\n      else\n        return m_zero;\n    }\n  }\n}\n\n/** Iterator over the nonzero coefficients */\ntemplate<typename Scalar_,typename StorageIndex_>\nclass AmbiVector<Scalar_,StorageIndex_>::Iterator\n{\n  public:\n    typedef Scalar_ Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n\n    /** Default constructor\n      * \\param vec the vector on which we iterate\n      * \\param epsilon the minimal value used to prune zero coefficients.\n      * In practice, all coefficients having a magnitude smaller than \\a epsilon\n      * are skipped.\n      */\n    explicit Iterator(const AmbiVector& vec, const RealScalar& epsilon = 0)\n      : m_vector(vec)\n    {\n      using std::abs;\n      m_epsilon = epsilon;\n      m_isDense = m_vector.m_mode==IsDense;\n      if (m_isDense)\n      {\n        m_currentEl = 0;   // this is to avoid a compilation warning\n        m_cachedValue = 0; // this is to avoid a compilation warning\n        m_cachedIndex = m_vector.m_start-1;\n        ++(*this);\n      }\n      else\n      {\n        ListEl* EIGEN_RESTRICT llElements = reinterpret_cast<ListEl*>(m_vector.m_buffer);\n        m_currentEl = m_vector.m_llStart;\n        while (m_currentEl>=0 && abs(llElements[m_currentEl].value)<=m_epsilon)\n          m_currentEl = llElements[m_currentEl].next;\n        if (m_currentEl<0)\n        {\n          m_cachedValue = 0; // this is to avoid a compilation warning\n          m_cachedIndex = -1;\n        }\n        else\n        {\n          m_cachedIndex = llElements[m_currentEl].index;\n          m_cachedValue = llElements[m_currentEl].value;\n        }\n      }\n    }\n\n    StorageIndex index() const { return m_cachedIndex; }\n    Scalar value() const { return m_cachedValue; }\n\n    operator bool() const { return m_cachedIndex>=0; }\n\n    Iterator& operator++()\n    {\n      using std::abs;\n      if (m_isDense)\n      {\n        do {\n          ++m_cachedIndex;\n        } while (m_cachedIndex<m_vector.m_end && abs(m_vector.m_buffer[m_cachedIndex])<=m_epsilon);\n        if (m_cachedIndex<m_vector.m_end)\n          m_cachedValue = m_vector.m_buffer[m_cachedIndex];\n        else\n          m_cachedIndex=-1;\n      }\n      else\n      {\n        ListEl* EIGEN_RESTRICT llElements = reinterpret_cast<ListEl*>(m_vector.m_buffer);\n        do {\n          m_currentEl = llElements[m_currentEl].next;\n        } while (m_currentEl>=0 && abs(llElements[m_currentEl].value)<=m_epsilon);\n        if (m_currentEl<0)\n        {\n          m_cachedIndex = -1;\n        }\n        else\n        {\n          m_cachedIndex = llElements[m_currentEl].index;\n          m_cachedValue = llElements[m_currentEl].value;\n        }\n      }\n      return *this;\n    }\n\n  protected:\n    const AmbiVector& m_vector; // the target vector\n    StorageIndex m_currentEl;   // the current element in sparse/linked-list mode\n    RealScalar m_epsilon;       // epsilon used to prune zero coefficients\n    StorageIndex m_cachedIndex; // current coordinate\n    Scalar m_cachedValue;       // current value\n    bool m_isDense;             // mode of the vector\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_AMBIVECTOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/CompressedStorage.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_COMPRESSED_STORAGE_H\n#define EIGEN_COMPRESSED_STORAGE_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\internal\n  * Stores a sparse set of values as a list of values and a list of indices.\n  *\n  */\ntemplate<typename Scalar_,typename StorageIndex_>\nclass CompressedStorage\n{\n  public:\n\n    typedef Scalar_ Scalar;\n    typedef StorageIndex_ StorageIndex;\n\n  protected:\n\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  public:\n\n    CompressedStorage()\n      : m_values(0), m_indices(0), m_size(0), m_allocatedSize(0)\n    {}\n\n    explicit CompressedStorage(Index size)\n      : m_values(0), m_indices(0), m_size(0), m_allocatedSize(0)\n    {\n      resize(size);\n    }\n\n    CompressedStorage(const CompressedStorage& other)\n      : m_values(0), m_indices(0), m_size(0), m_allocatedSize(0)\n    {\n      *this = other;\n    }\n\n    CompressedStorage& operator=(const CompressedStorage& other)\n    {\n      resize(other.size());\n      if(other.size()>0)\n      {\n        internal::smart_copy(other.m_values,  other.m_values  + m_size, m_values);\n        internal::smart_copy(other.m_indices, other.m_indices + m_size, m_indices);\n      }\n      return *this;\n    }\n\n    void swap(CompressedStorage& other)\n    {\n      std::swap(m_values, other.m_values);\n      std::swap(m_indices, other.m_indices);\n      std::swap(m_size, other.m_size);\n      std::swap(m_allocatedSize, other.m_allocatedSize);\n    }\n\n    ~CompressedStorage()\n    {\n      delete[] m_values;\n      delete[] m_indices;\n    }\n\n    void reserve(Index size)\n    {\n      Index newAllocatedSize = m_size + size;\n      if (newAllocatedSize > m_allocatedSize)\n        reallocate(newAllocatedSize);\n    }\n\n    void squeeze()\n    {\n      if (m_allocatedSize>m_size)\n        reallocate(m_size);\n    }\n\n    void resize(Index size, double reserveSizeFactor = 0)\n    {\n      if (m_allocatedSize<size)\n      {\n        Index realloc_size = (std::min<Index>)(NumTraits<StorageIndex>::highest(),  size + Index(reserveSizeFactor*double(size)));\n        if(realloc_size<size)\n          internal::throw_std_bad_alloc();\n        reallocate(realloc_size);\n      }\n      m_size = size;\n    }\n\n    void append(const Scalar& v, Index i)\n    {\n      Index id = m_size;\n      resize(m_size+1, 1);\n      m_values[id] = v;\n      m_indices[id] = internal::convert_index<StorageIndex>(i);\n    }\n\n    inline Index size() const { return m_size; }\n    inline Index allocatedSize() const { return m_allocatedSize; }\n    inline void clear() { m_size = 0; }\n\n    const Scalar* valuePtr() const { return m_values; }\n    Scalar* valuePtr() { return m_values; }\n    const StorageIndex* indexPtr() const { return m_indices; }\n    StorageIndex* indexPtr() { return m_indices; }\n\n    inline Scalar& value(Index i) { eigen_internal_assert(m_values!=0); return m_values[i]; }\n    inline const Scalar& value(Index i) const { eigen_internal_assert(m_values!=0); return m_values[i]; }\n\n    inline StorageIndex& index(Index i) { eigen_internal_assert(m_indices!=0); return m_indices[i]; }\n    inline const StorageIndex& index(Index i) const { eigen_internal_assert(m_indices!=0); return m_indices[i]; }\n\n    /** \\returns the largest \\c k such that for all \\c j in [0,k) index[\\c j]\\<\\a key */\n    inline Index searchLowerIndex(Index key) const\n    {\n      return searchLowerIndex(0, m_size, key);\n    }\n\n    /** \\returns the largest \\c k in [start,end) such that for all \\c j in [start,k) index[\\c j]\\<\\a key */\n    inline Index searchLowerIndex(Index start, Index end, Index key) const\n    {\n      while(end>start)\n      {\n        Index mid = (end+start)>>1;\n        if (m_indices[mid]<key)\n          start = mid+1;\n        else\n          end = mid;\n      }\n      return start;\n    }\n\n    /** \\returns the stored value at index \\a key\n      * If the value does not exist, then the value \\a defaultValue is returned without any insertion. */\n    inline Scalar at(Index key, const Scalar& defaultValue = Scalar(0)) const\n    {\n      if (m_size==0)\n        return defaultValue;\n      else if (key==m_indices[m_size-1])\n        return m_values[m_size-1];\n      // ^^  optimization: let's first check if it is the last coefficient\n      // (very common in high level algorithms)\n      const Index id = searchLowerIndex(0,m_size-1,key);\n      return ((id<m_size) && (m_indices[id]==key)) ? m_values[id] : defaultValue;\n    }\n\n    /** Like at(), but the search is performed in the range [start,end) */\n    inline Scalar atInRange(Index start, Index end, Index key, const Scalar &defaultValue = Scalar(0)) const\n    {\n      if (start>=end)\n        return defaultValue;\n      else if (end>start && key==m_indices[end-1])\n        return m_values[end-1];\n      // ^^  optimization: let's first check if it is the last coefficient\n      // (very common in high level algorithms)\n      const Index id = searchLowerIndex(start,end-1,key);\n      return ((id<end) && (m_indices[id]==key)) ? m_values[id] : defaultValue;\n    }\n\n    /** \\returns a reference to the value at index \\a key\n      * If the value does not exist, then the value \\a defaultValue is inserted\n      * such that the keys are sorted. */\n    inline Scalar& atWithInsertion(Index key, const Scalar& defaultValue = Scalar(0))\n    {\n      Index id = searchLowerIndex(0,m_size,key);\n      if (id>=m_size || m_indices[id]!=key)\n      {\n        if (m_allocatedSize<m_size+1)\n        {\n          m_allocatedSize = 2*(m_size+1);\n          internal::scoped_array<Scalar> newValues(m_allocatedSize);\n          internal::scoped_array<StorageIndex> newIndices(m_allocatedSize);\n\n          // copy first chunk\n          internal::smart_copy(m_values,  m_values +id, newValues.ptr());\n          internal::smart_copy(m_indices, m_indices+id, newIndices.ptr());\n\n          // copy the rest\n          if(m_size>id)\n          {\n            internal::smart_copy(m_values +id,  m_values +m_size, newValues.ptr() +id+1);\n            internal::smart_copy(m_indices+id,  m_indices+m_size, newIndices.ptr()+id+1);\n          }\n          std::swap(m_values,newValues.ptr());\n          std::swap(m_indices,newIndices.ptr());\n        }\n        else if(m_size>id)\n        {\n          internal::smart_memmove(m_values +id, m_values +m_size, m_values +id+1);\n          internal::smart_memmove(m_indices+id, m_indices+m_size, m_indices+id+1);\n        }\n        m_size++;\n        m_indices[id] = internal::convert_index<StorageIndex>(key);\n        m_values[id] = defaultValue;\n      }\n      return m_values[id];\n    }\n\n    void moveChunk(Index from, Index to, Index chunkSize)\n    {\n      eigen_internal_assert(to+chunkSize <= m_size);\n      if(to>from && from+chunkSize>to)\n      {\n        // move backward\n        internal::smart_memmove(m_values+from,  m_values+from+chunkSize,  m_values+to);\n        internal::smart_memmove(m_indices+from, m_indices+from+chunkSize, m_indices+to);\n      }\n      else\n      {\n        internal::smart_copy(m_values+from,  m_values+from+chunkSize,  m_values+to);\n        internal::smart_copy(m_indices+from, m_indices+from+chunkSize, m_indices+to);\n      }\n    }\n\n    void prune(const Scalar& reference, const RealScalar& epsilon = NumTraits<RealScalar>::dummy_precision())\n    {\n      Index k = 0;\n      Index n = size();\n      for (Index i=0; i<n; ++i)\n      {\n        if (!internal::isMuchSmallerThan(value(i), reference, epsilon))\n        {\n          value(k) = value(i);\n          index(k) = index(i);\n          ++k;\n        }\n      }\n      resize(k,0);\n    }\n\n  protected:\n\n    inline void reallocate(Index size)\n    {\n      #ifdef EIGEN_SPARSE_COMPRESSED_STORAGE_REALLOCATE_PLUGIN\n        EIGEN_SPARSE_COMPRESSED_STORAGE_REALLOCATE_PLUGIN\n      #endif\n      eigen_internal_assert(size!=m_allocatedSize);\n      internal::scoped_array<Scalar> newValues(size);\n      internal::scoped_array<StorageIndex> newIndices(size);\n      Index copySize = (std::min)(size, m_size);\n      if (copySize>0) {\n        internal::smart_copy(m_values, m_values+copySize, newValues.ptr());\n        internal::smart_copy(m_indices, m_indices+copySize, newIndices.ptr());\n      }\n      std::swap(m_values,newValues.ptr());\n      std::swap(m_indices,newIndices.ptr());\n      m_allocatedSize = size;\n    }\n\n  protected:\n    Scalar* m_values;\n    StorageIndex* m_indices;\n    Index m_size;\n    Index m_allocatedSize;\n\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_COMPRESSED_STORAGE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/ConservativeSparseSparseProduct.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CONSERVATIVESPARSESPARSEPRODUCT_H\n#define EIGEN_CONSERVATIVESPARSESPARSEPRODUCT_H\n\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstatic void conservative_sparse_sparse_product_impl(const Lhs& lhs, const Rhs& rhs, ResultType& res, bool sortedInsertion = false)\n{\n  typedef typename remove_all<Lhs>::type::Scalar LhsScalar;\n  typedef typename remove_all<Rhs>::type::Scalar RhsScalar;\n  typedef typename remove_all<ResultType>::type::Scalar ResScalar;\n\n  // make sure to call innerSize/outerSize since we fake the storage order.\n  Index rows = lhs.innerSize();\n  Index cols = rhs.outerSize();\n  eigen_assert(lhs.outerSize() == rhs.innerSize());\n\n  ei_declare_aligned_stack_constructed_variable(bool,   mask,     rows, 0);\n  ei_declare_aligned_stack_constructed_variable(ResScalar, values,   rows, 0);\n  ei_declare_aligned_stack_constructed_variable(Index,  indices,  rows, 0);\n\n  std::memset(mask,0,sizeof(bool)*rows);\n\n  evaluator<Lhs> lhsEval(lhs);\n  evaluator<Rhs> rhsEval(rhs);\n\n  // estimate the number of non zero entries\n  // given a rhs column containing Y non zeros, we assume that the respective Y columns\n  // of the lhs differs in average of one non zeros, thus the number of non zeros for\n  // the product of a rhs column with the lhs is X+Y where X is the average number of non zero\n  // per column of the lhs.\n  // Therefore, we have nnz(lhs*rhs) = nnz(lhs) + nnz(rhs)\n  Index estimated_nnz_prod = lhsEval.nonZerosEstimate() + rhsEval.nonZerosEstimate();\n\n  res.setZero();\n  res.reserve(Index(estimated_nnz_prod));\n  // we compute each column of the result, one after the other\n  for (Index j=0; j<cols; ++j)\n  {\n\n    res.startVec(j);\n    Index nnz = 0;\n    for (typename evaluator<Rhs>::InnerIterator rhsIt(rhsEval, j); rhsIt; ++rhsIt)\n    {\n      RhsScalar y = rhsIt.value();\n      Index k = rhsIt.index();\n      for (typename evaluator<Lhs>::InnerIterator lhsIt(lhsEval, k); lhsIt; ++lhsIt)\n      {\n        Index i = lhsIt.index();\n        LhsScalar x = lhsIt.value();\n        if(!mask[i])\n        {\n          mask[i] = true;\n          values[i] = x * y;\n          indices[nnz] = i;\n          ++nnz;\n        }\n        else\n          values[i] += x * y;\n      }\n    }\n    if(!sortedInsertion)\n    {\n      // unordered insertion\n      for(Index k=0; k<nnz; ++k)\n      {\n        Index i = indices[k];\n        res.insertBackByOuterInnerUnordered(j,i) = values[i];\n        mask[i] = false;\n      }\n    }\n    else\n    {\n      // alternative ordered insertion code:\n      const Index t200 = rows/11; // 11 == (log2(200)*1.39)\n      const Index t = (rows*100)/139;\n\n      // FIXME reserve nnz non zeros\n      // FIXME implement faster sorting algorithms for very small nnz\n      // if the result is sparse enough => use a quick sort\n      // otherwise => loop through the entire vector\n      // In order to avoid to perform an expensive log2 when the\n      // result is clearly very sparse we use a linear bound up to 200.\n      if((nnz<200 && nnz<t200) || nnz * numext::log2(int(nnz)) < t)\n      {\n        if(nnz>1) std::sort(indices,indices+nnz);\n        for(Index k=0; k<nnz; ++k)\n        {\n          Index i = indices[k];\n          res.insertBackByOuterInner(j,i) = values[i];\n          mask[i] = false;\n        }\n      }\n      else\n      {\n        // dense path\n        for(Index i=0; i<rows; ++i)\n        {\n          if(mask[i])\n          {\n            mask[i] = false;\n            res.insertBackByOuterInner(j,i) = values[i];\n          }\n        }\n      }\n    }\n  }\n  res.finalize();\n}\n\n\n} // end namespace internal\n\nnamespace internal {\n\ntemplate<typename Lhs, typename Rhs, typename ResultType,\n  int LhsStorageOrder = (traits<Lhs>::Flags&RowMajorBit) ? RowMajor : ColMajor,\n  int RhsStorageOrder = (traits<Rhs>::Flags&RowMajorBit) ? RowMajor : ColMajor,\n  int ResStorageOrder = (traits<ResultType>::Flags&RowMajorBit) ? RowMajor : ColMajor>\nstruct conservative_sparse_sparse_product_selector;\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,ColMajor,ColMajor,ColMajor>\n{\n  typedef typename remove_all<Lhs>::type LhsCleaned;\n  typedef typename LhsCleaned::Scalar Scalar;\n\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    typedef SparseMatrix<typename ResultType::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorMatrix;\n    typedef SparseMatrix<typename ResultType::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorMatrixAux;\n    typedef typename sparse_eval<ColMajorMatrixAux,ResultType::RowsAtCompileTime,ResultType::ColsAtCompileTime,ColMajorMatrixAux::Flags>::type ColMajorMatrix;\n\n    // If the result is tall and thin (in the extreme case a column vector)\n    // then it is faster to sort the coefficients inplace instead of transposing twice.\n    // FIXME, the following heuristic is probably not very good.\n    if(lhs.rows()>rhs.cols())\n    {\n      ColMajorMatrix resCol(lhs.rows(),rhs.cols());\n      // perform sorted insertion\n      internal::conservative_sparse_sparse_product_impl<Lhs,Rhs,ColMajorMatrix>(lhs, rhs, resCol, true);\n      res = resCol.markAsRValue();\n    }\n    else\n    {\n      ColMajorMatrixAux resCol(lhs.rows(),rhs.cols());\n      // resort to transpose to sort the entries\n      internal::conservative_sparse_sparse_product_impl<Lhs,Rhs,ColMajorMatrixAux>(lhs, rhs, resCol, false);\n      RowMajorMatrix resRow(resCol);\n      res = resRow.markAsRValue();\n    }\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,RowMajor,ColMajor,ColMajor>\n{\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    typedef SparseMatrix<typename Rhs::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorRhs;\n    typedef SparseMatrix<typename ResultType::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorRes;\n    RowMajorRhs rhsRow = rhs;\n    RowMajorRes resRow(lhs.rows(), rhs.cols());\n    internal::conservative_sparse_sparse_product_impl<RowMajorRhs,Lhs,RowMajorRes>(rhsRow, lhs, resRow);\n    res = resRow;\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,ColMajor,RowMajor,ColMajor>\n{\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    typedef SparseMatrix<typename Lhs::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorLhs;\n    typedef SparseMatrix<typename ResultType::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorRes;\n    RowMajorLhs lhsRow = lhs;\n    RowMajorRes resRow(lhs.rows(), rhs.cols());\n    internal::conservative_sparse_sparse_product_impl<Rhs,RowMajorLhs,RowMajorRes>(rhs, lhsRow, resRow);\n    res = resRow;\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,RowMajor,RowMajor,ColMajor>\n{\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    typedef SparseMatrix<typename ResultType::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorMatrix;\n    RowMajorMatrix resRow(lhs.rows(), rhs.cols());\n    internal::conservative_sparse_sparse_product_impl<Rhs,Lhs,RowMajorMatrix>(rhs, lhs, resRow);\n    res = resRow;\n  }\n};\n\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,ColMajor,ColMajor,RowMajor>\n{\n  typedef typename traits<typename remove_all<Lhs>::type>::Scalar Scalar;\n\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    typedef SparseMatrix<typename ResultType::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorMatrix;\n    ColMajorMatrix resCol(lhs.rows(), rhs.cols());\n    internal::conservative_sparse_sparse_product_impl<Lhs,Rhs,ColMajorMatrix>(lhs, rhs, resCol);\n    res = resCol;\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,RowMajor,ColMajor,RowMajor>\n{\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    typedef SparseMatrix<typename Lhs::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorLhs;\n    typedef SparseMatrix<typename ResultType::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorRes;\n    ColMajorLhs lhsCol = lhs;\n    ColMajorRes resCol(lhs.rows(), rhs.cols());\n    internal::conservative_sparse_sparse_product_impl<ColMajorLhs,Rhs,ColMajorRes>(lhsCol, rhs, resCol);\n    res = resCol;\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,ColMajor,RowMajor,RowMajor>\n{\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    typedef SparseMatrix<typename Rhs::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorRhs;\n    typedef SparseMatrix<typename ResultType::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorRes;\n    ColMajorRhs rhsCol = rhs;\n    ColMajorRes resCol(lhs.rows(), rhs.cols());\n    internal::conservative_sparse_sparse_product_impl<Lhs,ColMajorRhs,ColMajorRes>(lhs, rhsCol, resCol);\n    res = resCol;\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,RowMajor,RowMajor,RowMajor>\n{\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    typedef SparseMatrix<typename ResultType::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorMatrix;\n    typedef SparseMatrix<typename ResultType::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorMatrix;\n    RowMajorMatrix resRow(lhs.rows(),rhs.cols());\n    internal::conservative_sparse_sparse_product_impl<Rhs,Lhs,RowMajorMatrix>(rhs, lhs, resRow);\n    // sort the non zeros:\n    ColMajorMatrix resCol(resRow);\n    res = resCol;\n  }\n};\n\n} // end namespace internal\n\n\nnamespace internal {\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstatic void sparse_sparse_to_dense_product_impl(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n{\n  typedef typename remove_all<Lhs>::type::Scalar LhsScalar;\n  typedef typename remove_all<Rhs>::type::Scalar RhsScalar;\n  Index cols = rhs.outerSize();\n  eigen_assert(lhs.outerSize() == rhs.innerSize());\n\n  evaluator<Lhs> lhsEval(lhs);\n  evaluator<Rhs> rhsEval(rhs);\n\n  for (Index j=0; j<cols; ++j)\n  {\n    for (typename evaluator<Rhs>::InnerIterator rhsIt(rhsEval, j); rhsIt; ++rhsIt)\n    {\n      RhsScalar y = rhsIt.value();\n      Index k = rhsIt.index();\n      for (typename evaluator<Lhs>::InnerIterator lhsIt(lhsEval, k); lhsIt; ++lhsIt)\n      {\n        Index i = lhsIt.index();\n        LhsScalar x = lhsIt.value();\n        res.coeffRef(i,j) += x * y;\n      }\n    }\n  }\n}\n\n\n} // end namespace internal\n\nnamespace internal {\n\ntemplate<typename Lhs, typename Rhs, typename ResultType,\n  int LhsStorageOrder = (traits<Lhs>::Flags&RowMajorBit) ? RowMajor : ColMajor,\n  int RhsStorageOrder = (traits<Rhs>::Flags&RowMajorBit) ? RowMajor : ColMajor>\nstruct sparse_sparse_to_dense_product_selector;\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_to_dense_product_selector<Lhs,Rhs,ResultType,ColMajor,ColMajor>\n{\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    internal::sparse_sparse_to_dense_product_impl<Lhs,Rhs,ResultType>(lhs, rhs, res);\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_to_dense_product_selector<Lhs,Rhs,ResultType,RowMajor,ColMajor>\n{\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    typedef SparseMatrix<typename Lhs::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorLhs;\n    ColMajorLhs lhsCol(lhs);\n    internal::sparse_sparse_to_dense_product_impl<ColMajorLhs,Rhs,ResultType>(lhsCol, rhs, res);\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_to_dense_product_selector<Lhs,Rhs,ResultType,ColMajor,RowMajor>\n{\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    typedef SparseMatrix<typename Rhs::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorRhs;\n    ColMajorRhs rhsCol(rhs);\n    internal::sparse_sparse_to_dense_product_impl<Lhs,ColMajorRhs,ResultType>(lhs, rhsCol, res);\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_to_dense_product_selector<Lhs,Rhs,ResultType,RowMajor,RowMajor>\n{\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    Transpose<ResultType> trRes(res);\n    internal::sparse_sparse_to_dense_product_impl<Rhs,Lhs,Transpose<ResultType> >(rhs, lhs, trRes);\n  }\n};\n\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_CONSERVATIVESPARSESPARSEPRODUCT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/MappedSparseMatrix.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MAPPED_SPARSEMATRIX_H\n#define EIGEN_MAPPED_SPARSEMATRIX_H\n\nnamespace Eigen {\n\n/** \\deprecated Use Map<SparseMatrix<> >\n  * \\class MappedSparseMatrix\n  *\n  * \\brief Sparse matrix\n  *\n  * \\param Scalar_ the scalar type, i.e. the type of the coefficients\n  *\n  * See http://www.netlib.org/linalg/html_templates/node91.html for details on the storage scheme.\n  *\n  */\nnamespace internal {\ntemplate<typename Scalar_, int _Flags, typename StorageIndex_>\nstruct traits<MappedSparseMatrix<Scalar_, _Flags, StorageIndex_> > : traits<SparseMatrix<Scalar_, _Flags, StorageIndex_> >\n{};\n} // end namespace internal\n\ntemplate<typename Scalar_, int _Flags, typename StorageIndex_>\nclass MappedSparseMatrix\n  : public Map<SparseMatrix<Scalar_, _Flags, StorageIndex_> >\n{\n    typedef Map<SparseMatrix<Scalar_, _Flags, StorageIndex_> > Base;\n\n  public:\n    \n    typedef typename Base::StorageIndex StorageIndex;\n    typedef typename Base::Scalar Scalar;\n\n    inline MappedSparseMatrix(Index rows, Index cols, Index nnz, StorageIndex* outerIndexPtr, StorageIndex* innerIndexPtr, Scalar* valuePtr, StorageIndex* innerNonZeroPtr = 0)\n      : Base(rows, cols, nnz, outerIndexPtr, innerIndexPtr, valuePtr, innerNonZeroPtr)\n    {}\n\n    /** Empty destructor */\n    inline ~MappedSparseMatrix() {}\n};\n\nnamespace internal {\n\ntemplate<typename Scalar_, int Options_, typename StorageIndex_>\nstruct evaluator<MappedSparseMatrix<Scalar_,Options_,StorageIndex_> >\n  : evaluator<SparseCompressedBase<MappedSparseMatrix<Scalar_,Options_,StorageIndex_> > >\n{\n  typedef MappedSparseMatrix<Scalar_,Options_,StorageIndex_> XprType;\n  typedef evaluator<SparseCompressedBase<XprType> > Base;\n  \n  evaluator() : Base() {}\n  explicit evaluator(const XprType &mat) : Base(mat) {}\n};\n\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_MAPPED_SPARSEMATRIX_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseAssign.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEASSIGN_H\n#define EIGEN_SPARSEASSIGN_H\n\nnamespace Eigen { \n\ntemplate<typename Derived>    \ntemplate<typename OtherDerived>\nDerived& SparseMatrixBase<Derived>::operator=(const EigenBase<OtherDerived> &other)\n{\n  internal::call_assignment_no_alias(derived(), other.derived());\n  return derived();\n}\n\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\nDerived& SparseMatrixBase<Derived>::operator=(const ReturnByValue<OtherDerived>& other)\n{\n  // TODO use the evaluator mechanism\n  other.evalTo(derived());\n  return derived();\n}\n\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\ninline Derived& SparseMatrixBase<Derived>::operator=(const SparseMatrixBase<OtherDerived>& other)\n{\n  // by default sparse evaluation do not alias, so we can safely bypass the generic call_assignment routine\n  internal::Assignment<Derived,OtherDerived,internal::assign_op<Scalar,typename OtherDerived::Scalar> >\n          ::run(derived(), other.derived(), internal::assign_op<Scalar,typename OtherDerived::Scalar>());\n  return derived();\n}\n\ntemplate<typename Derived>\ninline Derived& SparseMatrixBase<Derived>::operator=(const Derived& other)\n{\n  internal::call_assignment_no_alias(derived(), other.derived());\n  return derived();\n}\n\nnamespace internal {\n\ntemplate<>\nstruct storage_kind_to_evaluator_kind<Sparse> {\n  typedef IteratorBased Kind;\n};\n\ntemplate<>\nstruct storage_kind_to_shape<Sparse> {\n  typedef SparseShape Shape;\n};\n\nstruct Sparse2Sparse {};\nstruct Sparse2Dense  {};\n\ntemplate<> struct AssignmentKind<SparseShape, SparseShape>           { typedef Sparse2Sparse Kind; };\ntemplate<> struct AssignmentKind<SparseShape, SparseTriangularShape> { typedef Sparse2Sparse Kind; };\ntemplate<> struct AssignmentKind<DenseShape,  SparseShape>           { typedef Sparse2Dense  Kind; };\ntemplate<> struct AssignmentKind<DenseShape,  SparseTriangularShape> { typedef Sparse2Dense  Kind; };\n\n\ntemplate<typename DstXprType, typename SrcXprType>\nvoid assign_sparse_to_sparse(DstXprType &dst, const SrcXprType &src)\n{\n  typedef typename DstXprType::Scalar Scalar;\n  typedef internal::evaluator<DstXprType> DstEvaluatorType;\n  typedef internal::evaluator<SrcXprType> SrcEvaluatorType;\n\n  SrcEvaluatorType srcEvaluator(src);\n\n  const bool transpose = (DstEvaluatorType::Flags & RowMajorBit) != (SrcEvaluatorType::Flags & RowMajorBit);\n  const Index outerEvaluationSize = (SrcEvaluatorType::Flags&RowMajorBit) ? src.rows() : src.cols();\n  if ((!transpose) && src.isRValue())\n  {\n    // eval without temporary\n    dst.resize(src.rows(), src.cols());\n    dst.setZero();\n    dst.reserve((std::min)(src.rows()*src.cols(), (std::max)(src.rows(),src.cols())*2));\n    for (Index j=0; j<outerEvaluationSize; ++j)\n    {\n      dst.startVec(j);\n      for (typename SrcEvaluatorType::InnerIterator it(srcEvaluator, j); it; ++it)\n      {\n        Scalar v = it.value();\n        dst.insertBackByOuterInner(j,it.index()) = v;\n      }\n    }\n    dst.finalize();\n  }\n  else\n  {\n    // eval through a temporary\n    eigen_assert(( ((internal::traits<DstXprType>::SupportedAccessPatterns & OuterRandomAccessPattern)==OuterRandomAccessPattern) ||\n              (!((DstEvaluatorType::Flags & RowMajorBit) != (SrcEvaluatorType::Flags & RowMajorBit)))) &&\n              \"the transpose operation is supposed to be handled in SparseMatrix::operator=\");\n\n    enum { Flip = (DstEvaluatorType::Flags & RowMajorBit) != (SrcEvaluatorType::Flags & RowMajorBit) };\n\n    \n    DstXprType temp(src.rows(), src.cols());\n\n    temp.reserve((std::min)(src.rows()*src.cols(), (std::max)(src.rows(),src.cols())*2));\n    for (Index j=0; j<outerEvaluationSize; ++j)\n    {\n      temp.startVec(j);\n      for (typename SrcEvaluatorType::InnerIterator it(srcEvaluator, j); it; ++it)\n      {\n        Scalar v = it.value();\n        temp.insertBackByOuterInner(Flip?it.index():j,Flip?j:it.index()) = v;\n      }\n    }\n    temp.finalize();\n\n    dst = temp.markAsRValue();\n  }\n}\n\n// Generic Sparse to Sparse assignment\ntemplate< typename DstXprType, typename SrcXprType, typename Functor>\nstruct Assignment<DstXprType, SrcXprType, Functor, Sparse2Sparse>\n{\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &/*func*/)\n  {\n    assign_sparse_to_sparse(dst.derived(), src.derived());\n  }\n};\n\n// Generic Sparse to Dense assignment\ntemplate< typename DstXprType, typename SrcXprType, typename Functor, typename Weak>\nstruct Assignment<DstXprType, SrcXprType, Functor, Sparse2Dense, Weak>\n{\n  static void run(DstXprType &dst, const SrcXprType &src, const Functor &func)\n  {\n    if(internal::is_same<Functor,internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> >::value)\n      dst.setZero();\n    \n    internal::evaluator<SrcXprType> srcEval(src);\n    resize_if_allowed(dst, src, func);\n    internal::evaluator<DstXprType> dstEval(dst);\n    \n    const Index outerEvaluationSize = (internal::evaluator<SrcXprType>::Flags&RowMajorBit) ? src.rows() : src.cols();\n    for (Index j=0; j<outerEvaluationSize; ++j)\n      for (typename internal::evaluator<SrcXprType>::InnerIterator i(srcEval,j); i; ++i)\n        func.assignCoeff(dstEval.coeffRef(i.row(),i.col()), i.value());\n  }\n};\n\n// Specialization for dense ?= dense +/- sparse and dense ?= sparse +/- dense\ntemplate<typename DstXprType, typename Func1, typename Func2>\nstruct assignment_from_dense_op_sparse\n{\n  template<typename SrcXprType, typename InitialFunc>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void run(DstXprType &dst, const SrcXprType &src, const InitialFunc& /*func*/)\n  {\n    #ifdef EIGEN_SPARSE_ASSIGNMENT_FROM_DENSE_OP_SPARSE_PLUGIN\n    EIGEN_SPARSE_ASSIGNMENT_FROM_DENSE_OP_SPARSE_PLUGIN\n    #endif\n\n    call_assignment_no_alias(dst, src.lhs(), Func1());\n    call_assignment_no_alias(dst, src.rhs(), Func2());\n  }\n\n  // Specialization for dense1 = sparse + dense2; -> dense1 = dense2; dense1 += sparse;\n  template<typename Lhs, typename Rhs, typename Scalar>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  typename internal::enable_if<internal::is_same<typename internal::evaluator_traits<Rhs>::Shape,DenseShape>::value>::type\n  run(DstXprType &dst, const CwiseBinaryOp<internal::scalar_sum_op<Scalar,Scalar>, const Lhs, const Rhs> &src,\n      const internal::assign_op<typename DstXprType::Scalar,Scalar>& /*func*/)\n  {\n    #ifdef EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_ADD_DENSE_PLUGIN\n    EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_ADD_DENSE_PLUGIN\n    #endif\n\n    // Apply the dense matrix first, then the sparse one.\n    call_assignment_no_alias(dst, src.rhs(), Func1());\n    call_assignment_no_alias(dst, src.lhs(), Func2());\n  }\n\n  // Specialization for dense1 = sparse - dense2; -> dense1 = -dense2; dense1 += sparse;\n  template<typename Lhs, typename Rhs, typename Scalar>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  typename internal::enable_if<internal::is_same<typename internal::evaluator_traits<Rhs>::Shape,DenseShape>::value>::type\n  run(DstXprType &dst, const CwiseBinaryOp<internal::scalar_difference_op<Scalar,Scalar>, const Lhs, const Rhs> &src,\n      const internal::assign_op<typename DstXprType::Scalar,Scalar>& /*func*/)\n  {\n    #ifdef EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_SUB_DENSE_PLUGIN\n    EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_SUB_DENSE_PLUGIN\n    #endif\n\n    // Apply the dense matrix first, then the sparse one.\n    call_assignment_no_alias(dst, -src.rhs(), Func1());\n    call_assignment_no_alias(dst,  src.lhs(), add_assign_op<typename DstXprType::Scalar,typename Lhs::Scalar>());\n  }\n};\n\n#define EIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(ASSIGN_OP,BINOP,ASSIGN_OP2) \\\n  template< typename DstXprType, typename Lhs, typename Rhs, typename Scalar> \\\n  struct Assignment<DstXprType, CwiseBinaryOp<internal::BINOP<Scalar,Scalar>, const Lhs, const Rhs>, internal::ASSIGN_OP<typename DstXprType::Scalar,Scalar>, \\\n                    Sparse2Dense, \\\n                    typename internal::enable_if<   internal::is_same<typename internal::evaluator_traits<Lhs>::Shape,DenseShape>::value \\\n                                                 || internal::is_same<typename internal::evaluator_traits<Rhs>::Shape,DenseShape>::value>::type> \\\n    : assignment_from_dense_op_sparse<DstXprType, internal::ASSIGN_OP<typename DstXprType::Scalar,typename Lhs::Scalar>, internal::ASSIGN_OP2<typename DstXprType::Scalar,typename Rhs::Scalar> > \\\n  {}\n\nEIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(assign_op,    scalar_sum_op,add_assign_op);\nEIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(add_assign_op,scalar_sum_op,add_assign_op);\nEIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(sub_assign_op,scalar_sum_op,sub_assign_op);\n\nEIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(assign_op,    scalar_difference_op,sub_assign_op);\nEIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(add_assign_op,scalar_difference_op,sub_assign_op);\nEIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(sub_assign_op,scalar_difference_op,add_assign_op);\n\n\n// Specialization for \"dst = dec.solve(rhs)\"\n// NOTE we need to specialize it for Sparse2Sparse to avoid ambiguous specialization error\ntemplate<typename DstXprType, typename DecType, typename RhsType, typename Scalar>\nstruct Assignment<DstXprType, Solve<DecType,RhsType>, internal::assign_op<Scalar,Scalar>, Sparse2Sparse>\n{\n  typedef Solve<DecType,RhsType> SrcXprType;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<Scalar,Scalar> &)\n  {\n    Index dstRows = src.rows();\n    Index dstCols = src.cols();\n    if((dst.rows()!=dstRows) || (dst.cols()!=dstCols))\n      dst.resize(dstRows, dstCols);\n\n    src.dec()._solve_impl(src.rhs(), dst);\n  }\n};\n\nstruct Diagonal2Sparse {};\n\ntemplate<> struct AssignmentKind<SparseShape,DiagonalShape> { typedef Diagonal2Sparse Kind; };\n\ntemplate< typename DstXprType, typename SrcXprType, typename Functor>\nstruct Assignment<DstXprType, SrcXprType, Functor, Diagonal2Sparse>\n{\n  typedef typename DstXprType::StorageIndex StorageIndex;\n  typedef typename DstXprType::Scalar Scalar;\n\n  template<int Options, typename AssignFunc>\n  static void run(SparseMatrix<Scalar,Options,StorageIndex> &dst, const SrcXprType &src, const AssignFunc &func)\n  { dst.assignDiagonal(src.diagonal(), func); }\n  \n  template<typename DstDerived>\n  static void run(SparseMatrixBase<DstDerived> &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &/*func*/)\n  { dst.derived().diagonal() = src.diagonal(); }\n  \n  template<typename DstDerived>\n  static void run(SparseMatrixBase<DstDerived> &dst, const SrcXprType &src, const internal::add_assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &/*func*/)\n  { dst.derived().diagonal() += src.diagonal(); }\n  \n  template<typename DstDerived>\n  static void run(SparseMatrixBase<DstDerived> &dst, const SrcXprType &src, const internal::sub_assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &/*func*/)\n  { dst.derived().diagonal() -= src.diagonal(); }\n};\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSEASSIGN_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseBlock.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_BLOCK_H\n#define EIGEN_SPARSE_BLOCK_H\n\nnamespace Eigen {\n\n// Subset of columns or rows\ntemplate<typename XprType, int BlockRows, int BlockCols>\nclass BlockImpl<XprType,BlockRows,BlockCols,true,Sparse>\n  : public SparseMatrixBase<Block<XprType,BlockRows,BlockCols,true> >\n{\n    typedef typename internal::remove_all<typename XprType::Nested>::type _MatrixTypeNested;\n    typedef Block<XprType, BlockRows, BlockCols, true> BlockType;\npublic:\n    enum { IsRowMajor = internal::traits<BlockType>::IsRowMajor };\nprotected:\n    enum { OuterSize = IsRowMajor ? BlockRows : BlockCols };\n    typedef SparseMatrixBase<BlockType> Base;\n    using Base::convert_index;\npublic:\n    EIGEN_SPARSE_PUBLIC_INTERFACE(BlockType)\n\n    inline BlockImpl(XprType& xpr, Index i)\n      : m_matrix(xpr), m_outerStart(convert_index(i)), m_outerSize(OuterSize)\n    {}\n\n    inline BlockImpl(XprType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols)\n      : m_matrix(xpr), m_outerStart(convert_index(IsRowMajor ? startRow : startCol)), m_outerSize(convert_index(IsRowMajor ? blockRows : blockCols))\n    {}\n\n    EIGEN_STRONG_INLINE Index rows() const { return IsRowMajor ? m_outerSize.value() : m_matrix.rows(); }\n    EIGEN_STRONG_INLINE Index cols() const { return IsRowMajor ? m_matrix.cols() : m_outerSize.value(); }\n\n    Index nonZeros() const\n    {\n      typedef internal::evaluator<XprType> EvaluatorType;\n      EvaluatorType matEval(m_matrix);\n      Index nnz = 0;\n      Index end = m_outerStart + m_outerSize.value();\n      for(Index j=m_outerStart; j<end; ++j)\n        for(typename EvaluatorType::InnerIterator it(matEval, j); it; ++it)\n          ++nnz;\n      return nnz;\n    }\n\n    inline const Scalar coeff(Index row, Index col) const\n    {\n      return m_matrix.coeff(row + (IsRowMajor ? m_outerStart : 0), col + (IsRowMajor ? 0 :  m_outerStart));\n    }\n\n    inline const Scalar coeff(Index index) const\n    {\n      return m_matrix.coeff(IsRowMajor ? m_outerStart : index, IsRowMajor ? index :  m_outerStart);\n    }\n\n    inline const XprType& nestedExpression() const { return m_matrix; }\n    inline XprType& nestedExpression() { return m_matrix; }\n    Index startRow() const { return IsRowMajor ? m_outerStart : 0; }\n    Index startCol() const { return IsRowMajor ? 0 : m_outerStart; }\n    Index blockRows() const { return IsRowMajor ? m_outerSize.value() : m_matrix.rows(); }\n    Index blockCols() const { return IsRowMajor ? m_matrix.cols() : m_outerSize.value(); }\n\n  protected:\n\n    typename internal::ref_selector<XprType>::non_const_type m_matrix;\n    Index m_outerStart;\n    const internal::variable_if_dynamic<Index, OuterSize> m_outerSize;\n\n  protected:\n    // Disable assignment with clear error message.\n    // Note that simply removing operator= yields compilation errors with ICC+MSVC\n    template<typename T>\n    BlockImpl& operator=(const T&)\n    {\n      EIGEN_STATIC_ASSERT(sizeof(T)==0, THIS_SPARSE_BLOCK_SUBEXPRESSION_IS_READ_ONLY);\n      return *this;\n    }\n};\n\n\n/***************************************************************************\n* specialization for SparseMatrix\n***************************************************************************/\n\nnamespace internal {\n\ntemplate<typename SparseMatrixType, int BlockRows, int BlockCols>\nclass sparse_matrix_block_impl\n  : public SparseCompressedBase<Block<SparseMatrixType,BlockRows,BlockCols,true> >\n{\n    typedef typename internal::remove_all<typename SparseMatrixType::Nested>::type _MatrixTypeNested;\n    typedef Block<SparseMatrixType, BlockRows, BlockCols, true> BlockType;\n    typedef SparseCompressedBase<Block<SparseMatrixType,BlockRows,BlockCols,true> > Base;\n    using Base::convert_index;\npublic:\n    enum { IsRowMajor = internal::traits<BlockType>::IsRowMajor };\n    EIGEN_SPARSE_PUBLIC_INTERFACE(BlockType)\nprotected:\n    typedef typename Base::IndexVector IndexVector;\n    enum { OuterSize = IsRowMajor ? BlockRows : BlockCols };\npublic:\n\n    inline sparse_matrix_block_impl(SparseMatrixType& xpr, Index i)\n      : m_matrix(xpr), m_outerStart(convert_index(i)), m_outerSize(OuterSize)\n    {}\n\n    inline sparse_matrix_block_impl(SparseMatrixType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols)\n      : m_matrix(xpr), m_outerStart(convert_index(IsRowMajor ? startRow : startCol)), m_outerSize(convert_index(IsRowMajor ? blockRows : blockCols))\n    {}\n\n    template<typename OtherDerived>\n    inline BlockType& operator=(const SparseMatrixBase<OtherDerived>& other)\n    {\n      typedef typename internal::remove_all<typename SparseMatrixType::Nested>::type _NestedMatrixType;\n      _NestedMatrixType& matrix = m_matrix;\n      // This assignment is slow if this vector set is not empty\n      // and/or it is not at the end of the nonzeros of the underlying matrix.\n\n      // 1 - eval to a temporary to avoid transposition and/or aliasing issues\n      Ref<const SparseMatrix<Scalar, IsRowMajor ? RowMajor : ColMajor, StorageIndex> > tmp(other.derived());\n      eigen_internal_assert(tmp.outerSize()==m_outerSize.value());\n\n      // 2 - let's check whether there is enough allocated memory\n      Index nnz           = tmp.nonZeros();\n      Index start         = m_outerStart==0 ? 0 : m_matrix.outerIndexPtr()[m_outerStart]; // starting position of the current block\n      Index end           = m_matrix.outerIndexPtr()[m_outerStart+m_outerSize.value()]; // ending position of the current block\n      Index block_size    = end - start;                                                // available room in the current block\n      Index tail_size     = m_matrix.outerIndexPtr()[m_matrix.outerSize()] - end;\n\n      Index free_size     = m_matrix.isCompressed()\n                          ? Index(matrix.data().allocatedSize()) + block_size\n                          : block_size;\n\n      Index tmp_start = tmp.outerIndexPtr()[0];\n\n      bool update_trailing_pointers = false;\n      if(nnz>free_size)\n      {\n        // realloc manually to reduce copies\n        typename SparseMatrixType::Storage newdata(m_matrix.data().allocatedSize() - block_size + nnz);\n\n        internal::smart_copy(m_matrix.valuePtr(),       m_matrix.valuePtr() + start,      newdata.valuePtr());\n        internal::smart_copy(m_matrix.innerIndexPtr(),  m_matrix.innerIndexPtr() + start, newdata.indexPtr());\n\n        internal::smart_copy(tmp.valuePtr() + tmp_start,      tmp.valuePtr() + tmp_start + nnz,       newdata.valuePtr() + start);\n        internal::smart_copy(tmp.innerIndexPtr() + tmp_start, tmp.innerIndexPtr() + tmp_start + nnz,  newdata.indexPtr() + start);\n\n        internal::smart_copy(matrix.valuePtr()+end,       matrix.valuePtr()+end + tail_size,      newdata.valuePtr()+start+nnz);\n        internal::smart_copy(matrix.innerIndexPtr()+end,  matrix.innerIndexPtr()+end + tail_size, newdata.indexPtr()+start+nnz);\n\n        newdata.resize(m_matrix.outerIndexPtr()[m_matrix.outerSize()] - block_size + nnz);\n\n        matrix.data().swap(newdata);\n\n        update_trailing_pointers = true;\n      }\n      else\n      {\n        if(m_matrix.isCompressed() && nnz!=block_size)\n        {\n          // no need to realloc, simply copy the tail at its respective position and insert tmp\n          matrix.data().resize(start + nnz + tail_size);\n\n          internal::smart_memmove(matrix.valuePtr()+end,      matrix.valuePtr() + end+tail_size,      matrix.valuePtr() + start+nnz);\n          internal::smart_memmove(matrix.innerIndexPtr()+end, matrix.innerIndexPtr() + end+tail_size, matrix.innerIndexPtr() + start+nnz);\n\n          update_trailing_pointers = true;\n        }\n\n        internal::smart_copy(tmp.valuePtr() + tmp_start,      tmp.valuePtr() + tmp_start + nnz,       matrix.valuePtr() + start);\n        internal::smart_copy(tmp.innerIndexPtr() + tmp_start, tmp.innerIndexPtr() + tmp_start + nnz,  matrix.innerIndexPtr() + start);\n      }\n\n      // update outer index pointers and innerNonZeros\n      if(IsVectorAtCompileTime)\n      {\n        if(!m_matrix.isCompressed())\n          matrix.innerNonZeroPtr()[m_outerStart] = StorageIndex(nnz);\n        matrix.outerIndexPtr()[m_outerStart] = StorageIndex(start);\n      }\n      else\n      {\n        StorageIndex p = StorageIndex(start);\n        for(Index k=0; k<m_outerSize.value(); ++k)\n        {\n          StorageIndex nnz_k = internal::convert_index<StorageIndex>(tmp.innerVector(k).nonZeros());\n          if(!m_matrix.isCompressed())\n            matrix.innerNonZeroPtr()[m_outerStart+k] = nnz_k;\n          matrix.outerIndexPtr()[m_outerStart+k] = p;\n          p += nnz_k;\n        }\n      }\n\n      if(update_trailing_pointers)\n      {\n        StorageIndex offset = internal::convert_index<StorageIndex>(nnz - block_size);\n        for(Index k = m_outerStart + m_outerSize.value(); k<=matrix.outerSize(); ++k)\n        {\n          matrix.outerIndexPtr()[k] += offset;\n        }\n      }\n\n      return derived();\n    }\n\n    inline BlockType& operator=(const BlockType& other)\n    {\n      return operator=<BlockType>(other);\n    }\n\n    inline const Scalar* valuePtr() const\n    { return m_matrix.valuePtr(); }\n    inline Scalar* valuePtr()\n    { return m_matrix.valuePtr(); }\n\n    inline const StorageIndex* innerIndexPtr() const\n    { return m_matrix.innerIndexPtr(); }\n    inline StorageIndex* innerIndexPtr()\n    { return m_matrix.innerIndexPtr(); }\n\n    inline const StorageIndex* outerIndexPtr() const\n    { return m_matrix.outerIndexPtr() + m_outerStart; }\n    inline StorageIndex* outerIndexPtr()\n    { return m_matrix.outerIndexPtr() + m_outerStart; }\n\n    inline const StorageIndex* innerNonZeroPtr() const\n    { return isCompressed() ? 0 : (m_matrix.innerNonZeroPtr()+m_outerStart); }\n    inline StorageIndex* innerNonZeroPtr()\n    { return isCompressed() ? 0 : (m_matrix.innerNonZeroPtr()+m_outerStart); }\n\n    bool isCompressed() const { return m_matrix.innerNonZeroPtr()==0; }\n\n    inline Scalar& coeffRef(Index row, Index col)\n    {\n      return m_matrix.coeffRef(row + (IsRowMajor ? m_outerStart : 0), col + (IsRowMajor ? 0 :  m_outerStart));\n    }\n\n    inline const Scalar coeff(Index row, Index col) const\n    {\n      return m_matrix.coeff(row + (IsRowMajor ? m_outerStart : 0), col + (IsRowMajor ? 0 :  m_outerStart));\n    }\n\n    inline const Scalar coeff(Index index) const\n    {\n      return m_matrix.coeff(IsRowMajor ? m_outerStart : index, IsRowMajor ? index :  m_outerStart);\n    }\n\n    const Scalar& lastCoeff() const\n    {\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(sparse_matrix_block_impl);\n      eigen_assert(Base::nonZeros()>0);\n      if(m_matrix.isCompressed())\n        return m_matrix.valuePtr()[m_matrix.outerIndexPtr()[m_outerStart+1]-1];\n      else\n        return m_matrix.valuePtr()[m_matrix.outerIndexPtr()[m_outerStart]+m_matrix.innerNonZeroPtr()[m_outerStart]-1];\n    }\n\n    EIGEN_STRONG_INLINE Index rows() const { return IsRowMajor ? m_outerSize.value() : m_matrix.rows(); }\n    EIGEN_STRONG_INLINE Index cols() const { return IsRowMajor ? m_matrix.cols() : m_outerSize.value(); }\n\n    inline const SparseMatrixType& nestedExpression() const { return m_matrix; }\n    inline SparseMatrixType& nestedExpression() { return m_matrix; }\n    Index startRow() const { return IsRowMajor ? m_outerStart : 0; }\n    Index startCol() const { return IsRowMajor ? 0 : m_outerStart; }\n    Index blockRows() const { return IsRowMajor ? m_outerSize.value() : m_matrix.rows(); }\n    Index blockCols() const { return IsRowMajor ? m_matrix.cols() : m_outerSize.value(); }\n\n  protected:\n\n    typename internal::ref_selector<SparseMatrixType>::non_const_type m_matrix;\n    Index m_outerStart;\n    const internal::variable_if_dynamic<Index, OuterSize> m_outerSize;\n\n};\n\n} // namespace internal\n\ntemplate<typename Scalar_, int Options_, typename StorageIndex_, int BlockRows, int BlockCols>\nclass BlockImpl<SparseMatrix<Scalar_, Options_, StorageIndex_>,BlockRows,BlockCols,true,Sparse>\n  : public internal::sparse_matrix_block_impl<SparseMatrix<Scalar_, Options_, StorageIndex_>,BlockRows,BlockCols>\n{\npublic:\n  typedef StorageIndex_ StorageIndex;\n  typedef SparseMatrix<Scalar_, Options_, StorageIndex_> SparseMatrixType;\n  typedef internal::sparse_matrix_block_impl<SparseMatrixType,BlockRows,BlockCols> Base;\n  inline BlockImpl(SparseMatrixType& xpr, Index i)\n    : Base(xpr, i)\n  {}\n\n  inline BlockImpl(SparseMatrixType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols)\n    : Base(xpr, startRow, startCol, blockRows, blockCols)\n  {}\n\n  using Base::operator=;\n};\n\ntemplate<typename Scalar_, int Options_, typename StorageIndex_, int BlockRows, int BlockCols>\nclass BlockImpl<const SparseMatrix<Scalar_, Options_, StorageIndex_>,BlockRows,BlockCols,true,Sparse>\n  : public internal::sparse_matrix_block_impl<const SparseMatrix<Scalar_, Options_, StorageIndex_>,BlockRows,BlockCols>\n{\npublic:\n  typedef StorageIndex_ StorageIndex;\n  typedef const SparseMatrix<Scalar_, Options_, StorageIndex_> SparseMatrixType;\n  typedef internal::sparse_matrix_block_impl<SparseMatrixType,BlockRows,BlockCols> Base;\n  inline BlockImpl(SparseMatrixType& xpr, Index i)\n    : Base(xpr, i)\n  {}\n\n  inline BlockImpl(SparseMatrixType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols)\n    : Base(xpr, startRow, startCol, blockRows, blockCols)\n  {}\n\n  using Base::operator=;\nprivate:\n  template<typename Derived> BlockImpl(const SparseMatrixBase<Derived>& xpr, Index i);\n  template<typename Derived> BlockImpl(const SparseMatrixBase<Derived>& xpr);\n};\n\n//----------\n\n/** Generic implementation of sparse Block expression.\n  * Real-only.\n  */\ntemplate<typename XprType, int BlockRows, int BlockCols, bool InnerPanel>\nclass BlockImpl<XprType,BlockRows,BlockCols,InnerPanel,Sparse>\n  : public SparseMatrixBase<Block<XprType,BlockRows,BlockCols,InnerPanel> >, internal::no_assignment_operator\n{\n    typedef Block<XprType, BlockRows, BlockCols, InnerPanel> BlockType;\n    typedef SparseMatrixBase<BlockType> Base;\n    using Base::convert_index;\npublic:\n    enum { IsRowMajor = internal::traits<BlockType>::IsRowMajor };\n    EIGEN_SPARSE_PUBLIC_INTERFACE(BlockType)\n\n    typedef typename internal::remove_all<typename XprType::Nested>::type _MatrixTypeNested;\n\n    /** Column or Row constructor\n      */\n    inline BlockImpl(XprType& xpr, Index i)\n      : m_matrix(xpr),\n        m_startRow( (BlockRows==1) && (BlockCols==XprType::ColsAtCompileTime) ? convert_index(i) : 0),\n        m_startCol( (BlockRows==XprType::RowsAtCompileTime) && (BlockCols==1) ? convert_index(i) : 0),\n        m_blockRows(BlockRows==1 ? 1 : xpr.rows()),\n        m_blockCols(BlockCols==1 ? 1 : xpr.cols())\n    {}\n\n    /** Dynamic-size constructor\n      */\n    inline BlockImpl(XprType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols)\n      : m_matrix(xpr), m_startRow(convert_index(startRow)), m_startCol(convert_index(startCol)), m_blockRows(convert_index(blockRows)), m_blockCols(convert_index(blockCols))\n    {}\n\n    inline Index rows() const { return m_blockRows.value(); }\n    inline Index cols() const { return m_blockCols.value(); }\n\n    inline Scalar& coeffRef(Index row, Index col)\n    {\n      return m_matrix.coeffRef(row + m_startRow.value(), col + m_startCol.value());\n    }\n\n    inline const Scalar coeff(Index row, Index col) const\n    {\n      return m_matrix.coeff(row + m_startRow.value(), col + m_startCol.value());\n    }\n\n    inline Scalar& coeffRef(Index index)\n    {\n      return m_matrix.coeffRef(m_startRow.value() + (RowsAtCompileTime == 1 ? 0 : index),\n                               m_startCol.value() + (RowsAtCompileTime == 1 ? index : 0));\n    }\n\n    inline const Scalar coeff(Index index) const\n    {\n      return m_matrix.coeff(m_startRow.value() + (RowsAtCompileTime == 1 ? 0 : index),\n                            m_startCol.value() + (RowsAtCompileTime == 1 ? index : 0));\n    }\n\n    inline const XprType& nestedExpression() const { return m_matrix; }\n    inline XprType& nestedExpression() { return m_matrix; }\n    Index startRow() const { return m_startRow.value(); }\n    Index startCol() const { return m_startCol.value(); }\n    Index blockRows() const { return m_blockRows.value(); }\n    Index blockCols() const { return m_blockCols.value(); }\n\n  protected:\n//     friend class internal::GenericSparseBlockInnerIteratorImpl<XprType,BlockRows,BlockCols,InnerPanel>;\n    friend struct internal::unary_evaluator<Block<XprType,BlockRows,BlockCols,InnerPanel>, internal::IteratorBased, Scalar >;\n\n    Index nonZeros() const { return Dynamic; }\n\n    typename internal::ref_selector<XprType>::non_const_type m_matrix;\n    const internal::variable_if_dynamic<Index, XprType::RowsAtCompileTime == 1 ? 0 : Dynamic> m_startRow;\n    const internal::variable_if_dynamic<Index, XprType::ColsAtCompileTime == 1 ? 0 : Dynamic> m_startCol;\n    const internal::variable_if_dynamic<Index, RowsAtCompileTime> m_blockRows;\n    const internal::variable_if_dynamic<Index, ColsAtCompileTime> m_blockCols;\n\n  protected:\n    // Disable assignment with clear error message.\n    // Note that simply removing operator= yields compilation errors with ICC+MSVC\n    template<typename T>\n    BlockImpl& operator=(const T&)\n    {\n      EIGEN_STATIC_ASSERT(sizeof(T)==0, THIS_SPARSE_BLOCK_SUBEXPRESSION_IS_READ_ONLY);\n      return *this;\n    }\n\n};\n\nnamespace internal {\n\ntemplate<typename ArgType, int BlockRows, int BlockCols, bool InnerPanel>\nstruct unary_evaluator<Block<ArgType,BlockRows,BlockCols,InnerPanel>, IteratorBased >\n : public evaluator_base<Block<ArgType,BlockRows,BlockCols,InnerPanel> >\n{\n    class InnerVectorInnerIterator;\n    class OuterVectorInnerIterator;\n  public:\n    typedef Block<ArgType,BlockRows,BlockCols,InnerPanel> XprType;\n    typedef typename XprType::StorageIndex StorageIndex;\n    typedef typename XprType::Scalar Scalar;\n\n    enum {\n      IsRowMajor = XprType::IsRowMajor,\n\n      OuterVector =  (BlockCols==1 && ArgType::IsRowMajor)\n                    | // FIXME | instead of || to please GCC 4.4.0 stupid warning \"suggest parentheses around &&\".\n                      // revert to || as soon as not needed anymore.\n                     (BlockRows==1 && !ArgType::IsRowMajor),\n\n      CoeffReadCost = evaluator<ArgType>::CoeffReadCost,\n      Flags = XprType::Flags\n    };\n\n    typedef typename internal::conditional<OuterVector,OuterVectorInnerIterator,InnerVectorInnerIterator>::type InnerIterator;\n\n    explicit unary_evaluator(const XprType& op)\n      : m_argImpl(op.nestedExpression()), m_block(op)\n    {}\n\n    inline Index nonZerosEstimate() const {\n      const Index nnz = m_block.nonZeros();\n      if(nnz < 0) {\n        // Scale the non-zero estimate for the underlying expression linearly with block size.\n        // Return zero if the underlying block is empty.\n        const Index nested_sz = m_block.nestedExpression().size();        \n        return nested_sz == 0 ? 0 : m_argImpl.nonZerosEstimate() * m_block.size() / nested_sz;\n      }\n      return nnz;\n    }\n\n  protected:\n    typedef typename evaluator<ArgType>::InnerIterator EvalIterator;\n\n    evaluator<ArgType> m_argImpl;\n    const XprType &m_block;\n};\n\ntemplate<typename ArgType, int BlockRows, int BlockCols, bool InnerPanel>\nclass unary_evaluator<Block<ArgType,BlockRows,BlockCols,InnerPanel>, IteratorBased>::InnerVectorInnerIterator\n : public EvalIterator\n{\n  // NOTE MSVC fails to compile if we don't explicitely \"import\" IsRowMajor from unary_evaluator\n  //      because the base class EvalIterator has a private IsRowMajor enum too. (bug #1786)\n  // NOTE We cannot call it IsRowMajor because it would shadow unary_evaluator::IsRowMajor\n  enum { XprIsRowMajor = unary_evaluator::IsRowMajor };\n  const XprType& m_block;\n  Index m_end;\npublic:\n\n  EIGEN_STRONG_INLINE InnerVectorInnerIterator(const unary_evaluator& aEval, Index outer)\n    : EvalIterator(aEval.m_argImpl, outer + (XprIsRowMajor ? aEval.m_block.startRow() : aEval.m_block.startCol())),\n      m_block(aEval.m_block),\n      m_end(XprIsRowMajor ? aEval.m_block.startCol()+aEval.m_block.blockCols() : aEval.m_block.startRow()+aEval.m_block.blockRows())\n  {\n    while( (EvalIterator::operator bool()) && (EvalIterator::index() < (XprIsRowMajor ? m_block.startCol() : m_block.startRow())) )\n      EvalIterator::operator++();\n  }\n\n  inline StorageIndex index() const { return EvalIterator::index() - convert_index<StorageIndex>(XprIsRowMajor ? m_block.startCol() : m_block.startRow()); }\n  inline Index outer()  const { return EvalIterator::outer() - (XprIsRowMajor ? m_block.startRow() : m_block.startCol()); }\n  inline Index row()    const { return EvalIterator::row()   - m_block.startRow(); }\n  inline Index col()    const { return EvalIterator::col()   - m_block.startCol(); }\n\n  inline operator bool() const { return EvalIterator::operator bool() && EvalIterator::index() < m_end; }\n};\n\ntemplate<typename ArgType, int BlockRows, int BlockCols, bool InnerPanel>\nclass unary_evaluator<Block<ArgType,BlockRows,BlockCols,InnerPanel>, IteratorBased>::OuterVectorInnerIterator\n{\n  // NOTE see above\n  enum { XprIsRowMajor = unary_evaluator::IsRowMajor };\n  const unary_evaluator& m_eval;\n  Index m_outerPos;\n  const Index m_innerIndex;\n  Index m_end;\n  EvalIterator m_it;\npublic:\n\n  EIGEN_STRONG_INLINE OuterVectorInnerIterator(const unary_evaluator& aEval, Index outer)\n    : m_eval(aEval),\n      m_outerPos( (XprIsRowMajor ? aEval.m_block.startCol() : aEval.m_block.startRow()) ),\n      m_innerIndex(XprIsRowMajor ? aEval.m_block.startRow() : aEval.m_block.startCol()),\n      m_end(XprIsRowMajor ? aEval.m_block.startCol()+aEval.m_block.blockCols() : aEval.m_block.startRow()+aEval.m_block.blockRows()),\n      m_it(m_eval.m_argImpl, m_outerPos)\n  {\n    EIGEN_UNUSED_VARIABLE(outer);\n    eigen_assert(outer==0);\n\n    while(m_it && m_it.index() < m_innerIndex) ++m_it;\n    if((!m_it) || (m_it.index()!=m_innerIndex))\n      ++(*this);\n  }\n\n  inline StorageIndex index() const { return convert_index<StorageIndex>(m_outerPos - (XprIsRowMajor ? m_eval.m_block.startCol() : m_eval.m_block.startRow())); }\n  inline Index outer()  const { return 0; }\n  inline Index row()    const { return XprIsRowMajor ? 0 : index(); }\n  inline Index col()    const { return XprIsRowMajor ? index() : 0; }\n\n  inline Scalar value() const { return m_it.value(); }\n  inline Scalar& valueRef() { return m_it.valueRef(); }\n\n  inline OuterVectorInnerIterator& operator++()\n  {\n    // search next non-zero entry\n    while(++m_outerPos<m_end)\n    {\n      // Restart iterator at the next inner-vector:\n      m_it.~EvalIterator();\n      ::new (&m_it) EvalIterator(m_eval.m_argImpl, m_outerPos);\n      // search for the key m_innerIndex in the current outer-vector\n      while(m_it && m_it.index() < m_innerIndex) ++m_it;\n      if(m_it && m_it.index()==m_innerIndex) break;\n    }\n    return *this;\n  }\n\n  inline operator bool() const { return m_outerPos < m_end; }\n};\n\ntemplate<typename Scalar_, int Options_, typename StorageIndex_, int BlockRows, int BlockCols>\nstruct unary_evaluator<Block<SparseMatrix<Scalar_, Options_, StorageIndex_>,BlockRows,BlockCols,true>, IteratorBased>\n  : evaluator<SparseCompressedBase<Block<SparseMatrix<Scalar_, Options_, StorageIndex_>,BlockRows,BlockCols,true> > >\n{\n  typedef Block<SparseMatrix<Scalar_, Options_, StorageIndex_>,BlockRows,BlockCols,true> XprType;\n  typedef evaluator<SparseCompressedBase<XprType> > Base;\n  explicit unary_evaluator(const XprType &xpr) : Base(xpr) {}\n};\n\ntemplate<typename Scalar_, int Options_, typename StorageIndex_, int BlockRows, int BlockCols>\nstruct unary_evaluator<Block<const SparseMatrix<Scalar_, Options_, StorageIndex_>,BlockRows,BlockCols,true>, IteratorBased>\n  : evaluator<SparseCompressedBase<Block<const SparseMatrix<Scalar_, Options_, StorageIndex_>,BlockRows,BlockCols,true> > >\n{\n  typedef Block<const SparseMatrix<Scalar_, Options_, StorageIndex_>,BlockRows,BlockCols,true> XprType;\n  typedef evaluator<SparseCompressedBase<XprType> > Base;\n  explicit unary_evaluator(const XprType &xpr) : Base(xpr) {}\n};\n\n} // end namespace internal\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_BLOCK_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseColEtree.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n/* \n \n * NOTE: This file is the modified version of sp_coletree.c file in SuperLU \n \n * -- SuperLU routine (version 3.1) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * August 1, 2008\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n#ifndef SPARSE_COLETREE_H\n#define SPARSE_COLETREE_H\n\nnamespace Eigen {\n\nnamespace internal {\n\n/** Find the root of the tree/set containing the vertex i : Use Path halving */ \ntemplate<typename Index, typename IndexVector>\nIndex etree_find (Index i, IndexVector& pp)\n{\n  Index p = pp(i); // Parent \n  Index gp = pp(p); // Grand parent \n  while (gp != p) \n  {\n    pp(i) = gp; // Parent pointer on find path is changed to former grand parent\n    i = gp; \n    p = pp(i);\n    gp = pp(p);\n  }\n  return p; \n}\n\n/** Compute the column elimination tree of a sparse matrix\n  * \\param mat The matrix in column-major format. \n  * \\param parent The elimination tree\n  * \\param firstRowElt The column index of the first element in each row\n  * \\param perm The permutation to apply to the column of \\b mat\n  */\ntemplate <typename MatrixType, typename IndexVector>\nint coletree(const MatrixType& mat, IndexVector& parent, IndexVector& firstRowElt, typename MatrixType::StorageIndex *perm=0)\n{\n  typedef typename MatrixType::StorageIndex StorageIndex;\n  StorageIndex nc = convert_index<StorageIndex>(mat.cols()); // Number of columns\n  StorageIndex m = convert_index<StorageIndex>(mat.rows());\n  StorageIndex diagSize = (std::min)(nc,m);\n  IndexVector root(nc); // root of subtree of etree \n  root.setZero();\n  IndexVector pp(nc); // disjoint sets \n  pp.setZero(); // Initialize disjoint sets \n  parent.resize(mat.cols());\n  //Compute first nonzero column in each row \n  firstRowElt.resize(m);\n  firstRowElt.setConstant(nc);\n  firstRowElt.segment(0, diagSize).setLinSpaced(diagSize, 0, diagSize-1);\n  bool found_diag;\n  for (StorageIndex col = 0; col < nc; col++)\n  {\n    StorageIndex pcol = col;\n    if(perm) pcol  = perm[col];\n    for (typename MatrixType::InnerIterator it(mat, pcol); it; ++it)\n    { \n      Index row = it.row();\n      firstRowElt(row) = (std::min)(firstRowElt(row), col);\n    }\n  }\n  /* Compute etree by Liu's algorithm for symmetric matrices,\n          except use (firstRowElt[r],c) in place of an edge (r,c) of A.\n    Thus each row clique in A'*A is replaced by a star\n    centered at its first vertex, which has the same fill. */\n  StorageIndex rset, cset, rroot;\n  for (StorageIndex col = 0; col < nc; col++) \n  {\n    found_diag = col>=m;\n    pp(col) = col; \n    cset = col; \n    root(cset) = col; \n    parent(col) = nc; \n    /* The diagonal element is treated here even if it does not exist in the matrix\n     * hence the loop is executed once more */ \n    StorageIndex pcol = col;\n    if(perm) pcol  = perm[col];\n    for (typename MatrixType::InnerIterator it(mat, pcol); it||!found_diag; ++it)\n    { //  A sequence of interleaved find and union is performed \n      Index i = col;\n      if(it) i = it.index();\n      if (i == col) found_diag = true;\n      \n      StorageIndex row = firstRowElt(i);\n      if (row >= col) continue; \n      rset = internal::etree_find(row, pp); // Find the name of the set containing row\n      rroot = root(rset);\n      if (rroot != col) \n      {\n        parent(rroot) = col; \n        pp(cset) = rset; \n        cset = rset; \n        root(cset) = col; \n      }\n    }\n  }\n  return 0;  \n}\n\n/** \n  * Depth-first search from vertex n.  No recursion.\n  * This routine was contributed by Cédric Doucet, CEDRAT Group, Meylan, France.\n*/\ntemplate <typename IndexVector>\nvoid nr_etdfs (typename IndexVector::Scalar n, IndexVector& parent, IndexVector& first_kid, IndexVector& next_kid, IndexVector& post, typename IndexVector::Scalar postnum)\n{\n  typedef typename IndexVector::Scalar StorageIndex;\n  StorageIndex current = n, first, next;\n  while (postnum != n) \n  {\n    // No kid for the current node\n    first = first_kid(current);\n    \n    // no kid for the current node\n    if (first == -1) \n    {\n      // Numbering this node because it has no kid \n      post(current) = postnum++;\n      \n      // looking for the next kid \n      next = next_kid(current); \n      while (next == -1) \n      {\n        // No more kids : back to the parent node\n        current = parent(current); \n        // numbering the parent node \n        post(current) = postnum++;\n        \n        // Get the next kid \n        next = next_kid(current); \n      }\n      // stopping criterion \n      if (postnum == n+1) return; \n      \n      // Updating current node \n      current = next; \n    }\n    else \n    {\n      current = first; \n    }\n  }\n}\n\n\n/**\n  * \\brief Post order a tree \n  * \\param n the number of nodes\n  * \\param parent Input tree\n  * \\param post postordered tree\n  */\ntemplate <typename IndexVector>\nvoid treePostorder(typename IndexVector::Scalar n, IndexVector& parent, IndexVector& post)\n{\n  typedef typename IndexVector::Scalar StorageIndex;\n  IndexVector first_kid, next_kid; // Linked list of children \n  StorageIndex postnum; \n  // Allocate storage for working arrays and results \n  first_kid.resize(n+1); \n  next_kid.setZero(n+1);\n  post.setZero(n+1);\n  \n  // Set up structure describing children\n  first_kid.setConstant(-1); \n  for (StorageIndex v = n-1; v >= 0; v--) \n  {\n    StorageIndex dad = parent(v);\n    next_kid(v) = first_kid(dad); \n    first_kid(dad) = v; \n  }\n  \n  // Depth-first search from dummy root vertex #n\n  postnum = 0; \n  internal::nr_etdfs(n, parent, first_kid, next_kid, post, postnum);\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // SPARSE_COLETREE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseCompressedBase.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_COMPRESSED_BASE_H\n#define EIGEN_SPARSE_COMPRESSED_BASE_H\n\nnamespace Eigen { \n\ntemplate<typename Derived> class SparseCompressedBase;\n  \nnamespace internal {\n\ntemplate<typename Derived>\nstruct traits<SparseCompressedBase<Derived> > : traits<Derived>\n{};\n\n} // end namespace internal\n\n/** \\ingroup SparseCore_Module\n  * \\class SparseCompressedBase\n  * \\brief Common base class for sparse [compressed]-{row|column}-storage format.\n  *\n  * This class defines the common interface for all derived classes implementing the compressed sparse storage format, such as:\n  *  - SparseMatrix\n  *  - Ref<SparseMatrixType,Options>\n  *  - Map<SparseMatrixType>\n  *\n  */\ntemplate<typename Derived>\nclass SparseCompressedBase\n  : public SparseMatrixBase<Derived>\n{\n  public:\n    typedef SparseMatrixBase<Derived> Base;\n    EIGEN_SPARSE_PUBLIC_INTERFACE(SparseCompressedBase)\n    using Base::operator=;\n    using Base::IsRowMajor;\n    \n    class InnerIterator;\n    class ReverseInnerIterator;\n    \n  protected:\n    typedef typename Base::IndexVector IndexVector;\n    Eigen::Map<IndexVector> innerNonZeros() { return Eigen::Map<IndexVector>(innerNonZeroPtr(), isCompressed()?0:derived().outerSize()); }\n    const  Eigen::Map<const IndexVector> innerNonZeros() const { return Eigen::Map<const IndexVector>(innerNonZeroPtr(), isCompressed()?0:derived().outerSize()); }\n        \n  public:\n    \n    /** \\returns the number of non zero coefficients */\n    inline Index nonZeros() const\n    {\n      if(Derived::IsVectorAtCompileTime && outerIndexPtr()==0)\n        return derived().nonZeros();\n      else if(isCompressed())\n        return outerIndexPtr()[derived().outerSize()]-outerIndexPtr()[0];\n      else if(derived().outerSize()==0)\n        return 0;\n      else\n        return innerNonZeros().sum();\n    }\n    \n    /** \\returns a const pointer to the array of values.\n      * This function is aimed at interoperability with other libraries.\n      * \\sa innerIndexPtr(), outerIndexPtr() */\n    inline const Scalar* valuePtr() const { return derived().valuePtr(); }\n    /** \\returns a non-const pointer to the array of values.\n      * This function is aimed at interoperability with other libraries.\n      * \\sa innerIndexPtr(), outerIndexPtr() */\n    inline Scalar* valuePtr() { return derived().valuePtr(); }\n\n    /** \\returns a const pointer to the array of inner indices.\n      * This function is aimed at interoperability with other libraries.\n      * \\sa valuePtr(), outerIndexPtr() */\n    inline const StorageIndex* innerIndexPtr() const { return derived().innerIndexPtr(); }\n    /** \\returns a non-const pointer to the array of inner indices.\n      * This function is aimed at interoperability with other libraries.\n      * \\sa valuePtr(), outerIndexPtr() */\n    inline StorageIndex* innerIndexPtr() { return derived().innerIndexPtr(); }\n\n    /** \\returns a const pointer to the array of the starting positions of the inner vectors.\n      * This function is aimed at interoperability with other libraries.\n      * \\warning it returns the null pointer 0 for SparseVector\n      * \\sa valuePtr(), innerIndexPtr() */\n    inline const StorageIndex* outerIndexPtr() const { return derived().outerIndexPtr(); }\n    /** \\returns a non-const pointer to the array of the starting positions of the inner vectors.\n      * This function is aimed at interoperability with other libraries.\n      * \\warning it returns the null pointer 0 for SparseVector\n      * \\sa valuePtr(), innerIndexPtr() */\n    inline StorageIndex* outerIndexPtr() { return derived().outerIndexPtr(); }\n\n    /** \\returns a const pointer to the array of the number of non zeros of the inner vectors.\n      * This function is aimed at interoperability with other libraries.\n      * \\warning it returns the null pointer 0 in compressed mode */\n    inline const StorageIndex* innerNonZeroPtr() const { return derived().innerNonZeroPtr(); }\n    /** \\returns a non-const pointer to the array of the number of non zeros of the inner vectors.\n      * This function is aimed at interoperability with other libraries.\n      * \\warning it returns the null pointer 0 in compressed mode */\n    inline StorageIndex* innerNonZeroPtr() { return derived().innerNonZeroPtr(); }\n    \n    /** \\returns whether \\c *this is in compressed form. */\n    inline bool isCompressed() const { return innerNonZeroPtr()==0; }\n\n    /** \\returns a read-only view of the stored coefficients as a 1D array expression.\n      *\n      * \\warning this method is for \\b compressed \\b storage \\b only, and it will trigger an assertion otherwise.\n      *\n      * \\sa valuePtr(), isCompressed() */\n    const Map<const Array<Scalar,Dynamic,1> > coeffs() const { eigen_assert(isCompressed()); return Array<Scalar,Dynamic,1>::Map(valuePtr(),nonZeros()); }\n\n    /** \\returns a read-write view of the stored coefficients as a 1D array expression\n      *\n      * \\warning this method is for \\b compressed \\b storage \\b only, and it will trigger an assertion otherwise.\n      *\n      * Here is an example:\n      * \\include SparseMatrix_coeffs.cpp\n      * and the output is:\n      * \\include SparseMatrix_coeffs.out\n      *\n      * \\sa valuePtr(), isCompressed() */\n    Map<Array<Scalar,Dynamic,1> > coeffs() { eigen_assert(isCompressed()); return Array<Scalar,Dynamic,1>::Map(valuePtr(),nonZeros()); }\n\n  protected:\n    /** Default constructor. Do nothing. */\n    SparseCompressedBase() {}\n\n    /** \\internal return the index of the coeff at (row,col) or just before if it does not exist.\n      * This is an analogue of std::lower_bound.\n      */\n    internal::LowerBoundIndex lower_bound(Index row, Index col) const\n    {\n      eigen_internal_assert(row>=0 && row<this->rows() && col>=0 && col<this->cols());\n\n      const Index outer = Derived::IsRowMajor ? row : col;\n      const Index inner = Derived::IsRowMajor ? col : row;\n\n      Index start = this->outerIndexPtr()[outer];\n      Index end = this->isCompressed() ? this->outerIndexPtr()[outer+1] : this->outerIndexPtr()[outer] + this->innerNonZeroPtr()[outer];\n      eigen_assert(end>=start && \"you are using a non finalized sparse matrix or written coefficient does not exist\");\n      internal::LowerBoundIndex p;\n      p.value = std::lower_bound(this->innerIndexPtr()+start, this->innerIndexPtr()+end,inner) - this->innerIndexPtr();\n      p.found = (p.value<end) && (this->innerIndexPtr()[p.value]==inner);\n      return p;\n    }\n\n    friend struct internal::evaluator<SparseCompressedBase<Derived> >;\n\n  private:\n    template<typename OtherDerived> explicit SparseCompressedBase(const SparseCompressedBase<OtherDerived>&);\n};\n\ntemplate<typename Derived>\nclass SparseCompressedBase<Derived>::InnerIterator\n{\n  public:\n    InnerIterator()\n      : m_values(0), m_indices(0), m_outer(0), m_id(0), m_end(0)\n    {}\n\n    InnerIterator(const InnerIterator& other)\n      : m_values(other.m_values), m_indices(other.m_indices), m_outer(other.m_outer), m_id(other.m_id), m_end(other.m_end)\n    {}\n\n    InnerIterator& operator=(const InnerIterator& other)\n    {\n      m_values = other.m_values;\n      m_indices = other.m_indices;\n      const_cast<OuterType&>(m_outer).setValue(other.m_outer.value());\n      m_id = other.m_id;\n      m_end = other.m_end;\n      return *this;\n    }\n\n    InnerIterator(const SparseCompressedBase& mat, Index outer)\n      : m_values(mat.valuePtr()), m_indices(mat.innerIndexPtr()), m_outer(outer)\n    {\n      if(Derived::IsVectorAtCompileTime && mat.outerIndexPtr()==0)\n      {\n        m_id = 0;\n        m_end = mat.nonZeros();\n      }\n      else\n      {\n        m_id = mat.outerIndexPtr()[outer];\n        if(mat.isCompressed())\n          m_end = mat.outerIndexPtr()[outer+1];\n        else\n          m_end = m_id + mat.innerNonZeroPtr()[outer];\n      }\n    }\n\n    explicit InnerIterator(const SparseCompressedBase& mat)\n      : m_values(mat.valuePtr()), m_indices(mat.innerIndexPtr()), m_outer(0), m_id(0), m_end(mat.nonZeros())\n    {\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived);\n    }\n\n    explicit InnerIterator(const internal::CompressedStorage<Scalar,StorageIndex>& data)\n      : m_values(data.valuePtr()), m_indices(data.indexPtr()), m_outer(0), m_id(0), m_end(data.size())\n    {\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived);\n    }\n\n    inline InnerIterator& operator++() { m_id++; return *this; }\n    inline InnerIterator& operator+=(Index i) { m_id += i ; return *this; }\n\n    inline InnerIterator operator+(Index i) \n    { \n        InnerIterator result = *this;\n        result += i;\n        return result;\n    }\n\n    inline const Scalar& value() const { return m_values[m_id]; }\n    inline Scalar& valueRef() { return const_cast<Scalar&>(m_values[m_id]); }\n\n    inline StorageIndex index() const { return m_indices[m_id]; }\n    inline Index outer() const { return m_outer.value(); }\n    inline Index row() const { return IsRowMajor ? m_outer.value() : index(); }\n    inline Index col() const { return IsRowMajor ? index() : m_outer.value(); }\n\n    inline operator bool() const { return (m_id < m_end); }\n\n  protected:\n    const Scalar* m_values;\n    const StorageIndex* m_indices;\n    typedef internal::variable_if_dynamic<Index,Derived::IsVectorAtCompileTime?0:Dynamic> OuterType;\n    const OuterType m_outer;\n    Index m_id;\n    Index m_end;\n  private:\n    // If you get here, then you're not using the right InnerIterator type, e.g.:\n    //   SparseMatrix<double,RowMajor> A;\n    //   SparseMatrix<double>::InnerIterator it(A,0);\n    template<typename T> InnerIterator(const SparseMatrixBase<T>&, Index outer);\n};\n\ntemplate<typename Derived>\nclass SparseCompressedBase<Derived>::ReverseInnerIterator\n{\n  public:\n    ReverseInnerIterator(const SparseCompressedBase& mat, Index outer)\n      : m_values(mat.valuePtr()), m_indices(mat.innerIndexPtr()), m_outer(outer)\n    {\n      if(Derived::IsVectorAtCompileTime && mat.outerIndexPtr()==0)\n      {\n        m_start = 0;\n        m_id = mat.nonZeros();\n      }\n      else\n      {\n        m_start = mat.outerIndexPtr()[outer];\n        if(mat.isCompressed())\n          m_id = mat.outerIndexPtr()[outer+1];\n        else\n          m_id = m_start + mat.innerNonZeroPtr()[outer];\n      }\n    }\n\n    explicit ReverseInnerIterator(const SparseCompressedBase& mat)\n      : m_values(mat.valuePtr()), m_indices(mat.innerIndexPtr()), m_outer(0), m_start(0), m_id(mat.nonZeros())\n    {\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived);\n    }\n\n    explicit ReverseInnerIterator(const internal::CompressedStorage<Scalar,StorageIndex>& data)\n      : m_values(data.valuePtr()), m_indices(data.indexPtr()), m_outer(0), m_start(0), m_id(data.size())\n    {\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived);\n    }\n\n    inline ReverseInnerIterator& operator--() { --m_id; return *this; }\n    inline ReverseInnerIterator& operator-=(Index i) { m_id -= i; return *this; }\n\n    inline ReverseInnerIterator operator-(Index i) \n    {\n        ReverseInnerIterator result = *this;\n        result -= i;\n        return result;\n    }\n\n    inline const Scalar& value() const { return m_values[m_id-1]; }\n    inline Scalar& valueRef() { return const_cast<Scalar&>(m_values[m_id-1]); }\n\n    inline StorageIndex index() const { return m_indices[m_id-1]; }\n    inline Index outer() const { return m_outer.value(); }\n    inline Index row() const { return IsRowMajor ? m_outer.value() : index(); }\n    inline Index col() const { return IsRowMajor ? index() : m_outer.value(); }\n\n    inline operator bool() const { return (m_id > m_start); }\n\n  protected:\n    const Scalar* m_values;\n    const StorageIndex* m_indices;\n    typedef internal::variable_if_dynamic<Index,Derived::IsVectorAtCompileTime?0:Dynamic> OuterType;\n    const OuterType m_outer;\n    Index m_start;\n    Index m_id;\n};\n\nnamespace internal {\n\ntemplate<typename Derived>\nstruct evaluator<SparseCompressedBase<Derived> >\n  : evaluator_base<Derived>\n{\n  typedef typename Derived::Scalar Scalar;\n  typedef typename Derived::InnerIterator InnerIterator;\n  \n  enum {\n    CoeffReadCost = NumTraits<Scalar>::ReadCost,\n    Flags = Derived::Flags\n  };\n  \n  evaluator() : m_matrix(0), m_zero(0)\n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n  explicit evaluator(const Derived &mat) : m_matrix(&mat), m_zero(0)\n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n  \n  inline Index nonZerosEstimate() const {\n    return m_matrix->nonZeros();\n  }\n  \n  operator Derived&() { return m_matrix->const_cast_derived(); }\n  operator const Derived&() const { return *m_matrix; }\n  \n  typedef typename DenseCoeffsBase<Derived,ReadOnlyAccessors>::CoeffReturnType CoeffReturnType;\n  const Scalar& coeff(Index row, Index col) const\n  {\n    Index p = find(row,col);\n\n    if(p==Dynamic)\n      return m_zero;\n    else\n      return m_matrix->const_cast_derived().valuePtr()[p];\n  }\n\n  Scalar& coeffRef(Index row, Index col)\n  {\n    Index p = find(row,col);\n    eigen_assert(p!=Dynamic && \"written coefficient does not exist\");\n    return m_matrix->const_cast_derived().valuePtr()[p];\n  }\n\nprotected:\n\n  Index find(Index row, Index col) const\n  {\n    internal::LowerBoundIndex p = m_matrix->lower_bound(row,col);\n    return p.found ? p.value : Dynamic;\n  }\n\n  const Derived *m_matrix;\n  const Scalar m_zero;\n};\n\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_COMPRESSED_BASE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseCwiseBinaryOp.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_CWISE_BINARY_OP_H\n#define EIGEN_SPARSE_CWISE_BINARY_OP_H\n\nnamespace Eigen { \n\n// Here we have to handle 3 cases:\n//  1 - sparse op dense\n//  2 - dense op sparse\n//  3 - sparse op sparse\n// We also need to implement a 4th iterator for:\n//  4 - dense op dense\n// Finally, we also need to distinguish between the product and other operations :\n//                configuration      returned mode\n//  1 - sparse op dense    product      sparse\n//                         generic      dense\n//  2 - dense op sparse    product      sparse\n//                         generic      dense\n//  3 - sparse op sparse   product      sparse\n//                         generic      sparse\n//  4 - dense op dense     product      dense\n//                         generic      dense\n//\n// TODO to ease compiler job, we could specialize product/quotient with a scalar\n//      and fallback to cwise-unary evaluator using bind1st_op and bind2nd_op.\n\ntemplate<typename BinaryOp, typename Lhs, typename Rhs>\nclass CwiseBinaryOpImpl<BinaryOp, Lhs, Rhs, Sparse>\n  : public SparseMatrixBase<CwiseBinaryOp<BinaryOp, Lhs, Rhs> >\n{\n  public:\n    typedef CwiseBinaryOp<BinaryOp, Lhs, Rhs> Derived;\n    typedef SparseMatrixBase<Derived> Base;\n    EIGEN_SPARSE_PUBLIC_INTERFACE(Derived)\n    CwiseBinaryOpImpl()\n    {\n      EIGEN_STATIC_ASSERT((\n                (!internal::is_same<typename internal::traits<Lhs>::StorageKind,\n                                    typename internal::traits<Rhs>::StorageKind>::value)\n            ||  ((internal::evaluator<Lhs>::Flags&RowMajorBit) == (internal::evaluator<Rhs>::Flags&RowMajorBit))),\n            THE_STORAGE_ORDER_OF_BOTH_SIDES_MUST_MATCH);\n    }\n};\n\nnamespace internal {\n\n  \n// Generic \"sparse OP sparse\"\ntemplate<typename XprType> struct binary_sparse_evaluator;\n\ntemplate<typename BinaryOp, typename Lhs, typename Rhs>\nstruct binary_evaluator<CwiseBinaryOp<BinaryOp, Lhs, Rhs>, IteratorBased, IteratorBased>\n  : evaluator_base<CwiseBinaryOp<BinaryOp, Lhs, Rhs> >\n{\nprotected:\n  typedef typename evaluator<Lhs>::InnerIterator  LhsIterator;\n  typedef typename evaluator<Rhs>::InnerIterator  RhsIterator;\n  typedef CwiseBinaryOp<BinaryOp, Lhs, Rhs> XprType;\n  typedef typename traits<XprType>::Scalar Scalar;\n  typedef typename XprType::StorageIndex StorageIndex;\npublic:\n\n  class InnerIterator\n  {\n  public:\n    \n    EIGEN_STRONG_INLINE InnerIterator(const binary_evaluator& aEval, Index outer)\n      : m_lhsIter(aEval.m_lhsImpl,outer), m_rhsIter(aEval.m_rhsImpl,outer), m_functor(aEval.m_functor)\n    {\n      this->operator++();\n    }\n\n    EIGEN_STRONG_INLINE InnerIterator& operator++()\n    {\n      if (m_lhsIter && m_rhsIter && (m_lhsIter.index() == m_rhsIter.index()))\n      {\n        m_id = m_lhsIter.index();\n        m_value = m_functor(m_lhsIter.value(), m_rhsIter.value());\n        ++m_lhsIter;\n        ++m_rhsIter;\n      }\n      else if (m_lhsIter && (!m_rhsIter || (m_lhsIter.index() < m_rhsIter.index())))\n      {\n        m_id = m_lhsIter.index();\n        m_value = m_functor(m_lhsIter.value(), Scalar(0));\n        ++m_lhsIter;\n      }\n      else if (m_rhsIter && (!m_lhsIter || (m_lhsIter.index() > m_rhsIter.index())))\n      {\n        m_id = m_rhsIter.index();\n        m_value = m_functor(Scalar(0), m_rhsIter.value());\n        ++m_rhsIter;\n      }\n      else\n      {\n        m_value = Scalar(0); // this is to avoid a compilation warning\n        m_id = -1;\n      }\n      return *this;\n    }\n\n    EIGEN_STRONG_INLINE Scalar value() const { return m_value; }\n\n    EIGEN_STRONG_INLINE StorageIndex index() const { return m_id; }\n    EIGEN_STRONG_INLINE Index outer() const { return m_lhsIter.outer(); }\n    EIGEN_STRONG_INLINE Index row() const { return Lhs::IsRowMajor ? m_lhsIter.row() : index(); }\n    EIGEN_STRONG_INLINE Index col() const { return Lhs::IsRowMajor ? index() : m_lhsIter.col(); }\n\n    EIGEN_STRONG_INLINE operator bool() const { return m_id>=0; }\n\n  protected:\n    LhsIterator m_lhsIter;\n    RhsIterator m_rhsIter;\n    const BinaryOp& m_functor;\n    Scalar m_value;\n    StorageIndex m_id;\n  };\n  \n  \n  enum {\n    CoeffReadCost = int(evaluator<Lhs>::CoeffReadCost) + int(evaluator<Rhs>::CoeffReadCost) + int(functor_traits<BinaryOp>::Cost),\n    Flags = XprType::Flags\n  };\n  \n  explicit binary_evaluator(const XprType& xpr)\n    : m_functor(xpr.functor()),\n      m_lhsImpl(xpr.lhs()), \n      m_rhsImpl(xpr.rhs())  \n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<BinaryOp>::Cost);\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n  \n  inline Index nonZerosEstimate() const {\n    return m_lhsImpl.nonZerosEstimate() + m_rhsImpl.nonZerosEstimate();\n  }\n\nprotected:\n  const BinaryOp m_functor;\n  evaluator<Lhs> m_lhsImpl;\n  evaluator<Rhs> m_rhsImpl;\n};\n\n// dense op sparse\ntemplate<typename BinaryOp, typename Lhs, typename Rhs>\nstruct binary_evaluator<CwiseBinaryOp<BinaryOp, Lhs, Rhs>, IndexBased, IteratorBased>\n  : evaluator_base<CwiseBinaryOp<BinaryOp, Lhs, Rhs> >\n{\nprotected:\n  typedef typename evaluator<Rhs>::InnerIterator  RhsIterator;\n  typedef CwiseBinaryOp<BinaryOp, Lhs, Rhs> XprType;\n  typedef typename traits<XprType>::Scalar Scalar;\n  typedef typename XprType::StorageIndex StorageIndex;\npublic:\n\n  class InnerIterator\n  {\n    enum { IsRowMajor = (int(Rhs::Flags)&RowMajorBit)==RowMajorBit };\n  public:\n\n    EIGEN_STRONG_INLINE InnerIterator(const binary_evaluator& aEval, Index outer)\n      : m_lhsEval(aEval.m_lhsImpl), m_rhsIter(aEval.m_rhsImpl,outer), m_functor(aEval.m_functor), m_value(0), m_id(-1), m_innerSize(aEval.m_expr.rhs().innerSize())\n    {\n      this->operator++();\n    }\n\n    EIGEN_STRONG_INLINE InnerIterator& operator++()\n    {\n      ++m_id;\n      if(m_id<m_innerSize)\n      {\n        Scalar lhsVal = m_lhsEval.coeff(IsRowMajor?m_rhsIter.outer():m_id,\n                                        IsRowMajor?m_id:m_rhsIter.outer());\n        if(m_rhsIter && m_rhsIter.index()==m_id)\n        {\n          m_value = m_functor(lhsVal, m_rhsIter.value());\n          ++m_rhsIter;\n        }\n        else\n          m_value = m_functor(lhsVal, Scalar(0));\n      }\n\n      return *this;\n    }\n\n    EIGEN_STRONG_INLINE Scalar value() const { eigen_internal_assert(m_id<m_innerSize); return m_value; }\n\n    EIGEN_STRONG_INLINE StorageIndex index() const { return m_id; }\n    EIGEN_STRONG_INLINE Index outer() const { return m_rhsIter.outer(); }\n    EIGEN_STRONG_INLINE Index row() const { return IsRowMajor ? m_rhsIter.outer() : m_id; }\n    EIGEN_STRONG_INLINE Index col() const { return IsRowMajor ? m_id : m_rhsIter.outer(); }\n\n    EIGEN_STRONG_INLINE operator bool() const { return m_id<m_innerSize; }\n\n  protected:\n    const evaluator<Lhs> &m_lhsEval;\n    RhsIterator m_rhsIter;\n    const BinaryOp& m_functor;\n    Scalar m_value;\n    StorageIndex m_id;\n    StorageIndex m_innerSize;\n  };\n\n\n  enum {\n    CoeffReadCost = int(evaluator<Lhs>::CoeffReadCost) + int(evaluator<Rhs>::CoeffReadCost) + int(functor_traits<BinaryOp>::Cost),\n    Flags = XprType::Flags\n  };\n\n  explicit binary_evaluator(const XprType& xpr)\n    : m_functor(xpr.functor()),\n      m_lhsImpl(xpr.lhs()),\n      m_rhsImpl(xpr.rhs()),\n      m_expr(xpr)\n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<BinaryOp>::Cost);\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n\n  inline Index nonZerosEstimate() const {\n    return m_expr.size();\n  }\n\nprotected:\n  const BinaryOp m_functor;\n  evaluator<Lhs> m_lhsImpl;\n  evaluator<Rhs> m_rhsImpl;\n  const XprType &m_expr;\n};\n\n// sparse op dense\ntemplate<typename BinaryOp, typename Lhs, typename Rhs>\nstruct binary_evaluator<CwiseBinaryOp<BinaryOp, Lhs, Rhs>, IteratorBased, IndexBased>\n  : evaluator_base<CwiseBinaryOp<BinaryOp, Lhs, Rhs> >\n{\nprotected:\n  typedef typename evaluator<Lhs>::InnerIterator  LhsIterator;\n  typedef CwiseBinaryOp<BinaryOp, Lhs, Rhs> XprType;\n  typedef typename traits<XprType>::Scalar Scalar;\n  typedef typename XprType::StorageIndex StorageIndex;\npublic:\n\n  class InnerIterator\n  {\n    enum { IsRowMajor = (int(Lhs::Flags)&RowMajorBit)==RowMajorBit };\n  public:\n\n    EIGEN_STRONG_INLINE InnerIterator(const binary_evaluator& aEval, Index outer)\n      : m_lhsIter(aEval.m_lhsImpl,outer), m_rhsEval(aEval.m_rhsImpl), m_functor(aEval.m_functor), m_value(0), m_id(-1), m_innerSize(aEval.m_expr.lhs().innerSize())\n    {\n      this->operator++();\n    }\n\n    EIGEN_STRONG_INLINE InnerIterator& operator++()\n    {\n      ++m_id;\n      if(m_id<m_innerSize)\n      {\n        Scalar rhsVal = m_rhsEval.coeff(IsRowMajor?m_lhsIter.outer():m_id,\n                                        IsRowMajor?m_id:m_lhsIter.outer());\n        if(m_lhsIter && m_lhsIter.index()==m_id)\n        {\n          m_value = m_functor(m_lhsIter.value(), rhsVal);\n          ++m_lhsIter;\n        }\n        else\n          m_value = m_functor(Scalar(0),rhsVal);\n      }\n\n      return *this;\n    }\n\n    EIGEN_STRONG_INLINE Scalar value() const { eigen_internal_assert(m_id<m_innerSize); return m_value; }\n\n    EIGEN_STRONG_INLINE StorageIndex index() const { return m_id; }\n    EIGEN_STRONG_INLINE Index outer() const { return m_lhsIter.outer(); }\n    EIGEN_STRONG_INLINE Index row() const { return IsRowMajor ? m_lhsIter.outer() : m_id; }\n    EIGEN_STRONG_INLINE Index col() const { return IsRowMajor ? m_id : m_lhsIter.outer(); }\n\n    EIGEN_STRONG_INLINE operator bool() const { return m_id<m_innerSize; }\n\n  protected:\n    LhsIterator m_lhsIter;\n    const evaluator<Rhs> &m_rhsEval;\n    const BinaryOp& m_functor;\n    Scalar m_value;\n    StorageIndex m_id;\n    StorageIndex m_innerSize;\n  };\n\n\n  enum {\n    CoeffReadCost = int(evaluator<Lhs>::CoeffReadCost) + int(evaluator<Rhs>::CoeffReadCost) + int(functor_traits<BinaryOp>::Cost),\n    Flags = XprType::Flags\n  };\n\n  explicit binary_evaluator(const XprType& xpr)\n    : m_functor(xpr.functor()),\n      m_lhsImpl(xpr.lhs()),\n      m_rhsImpl(xpr.rhs()),\n      m_expr(xpr)\n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<BinaryOp>::Cost);\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n\n  inline Index nonZerosEstimate() const {\n    return m_expr.size();\n  }\n\nprotected:\n  const BinaryOp m_functor;\n  evaluator<Lhs> m_lhsImpl;\n  evaluator<Rhs> m_rhsImpl;\n  const XprType &m_expr;\n};\n\ntemplate<typename T,\n         typename LhsKind   = typename evaluator_traits<typename T::Lhs>::Kind,\n         typename RhsKind   = typename evaluator_traits<typename T::Rhs>::Kind,\n         typename LhsScalar = typename traits<typename T::Lhs>::Scalar,\n         typename RhsScalar = typename traits<typename T::Rhs>::Scalar> struct sparse_conjunction_evaluator;\n\n// \"sparse .* sparse\"\ntemplate<typename T1, typename T2, typename Lhs, typename Rhs>\nstruct binary_evaluator<CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs>, IteratorBased, IteratorBased>\n  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs> >\n{\n  typedef CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs> XprType;\n  typedef sparse_conjunction_evaluator<XprType> Base;\n  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}\n};\n// \"dense .* sparse\"\ntemplate<typename T1, typename T2, typename Lhs, typename Rhs>\nstruct binary_evaluator<CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs>, IndexBased, IteratorBased>\n  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs> >\n{\n  typedef CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs> XprType;\n  typedef sparse_conjunction_evaluator<XprType> Base;\n  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}\n};\n// \"sparse .* dense\"\ntemplate<typename T1, typename T2, typename Lhs, typename Rhs>\nstruct binary_evaluator<CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs>, IteratorBased, IndexBased>\n  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs> >\n{\n  typedef CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs> XprType;\n  typedef sparse_conjunction_evaluator<XprType> Base;\n  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}\n};\n\n// \"sparse ./ dense\"\ntemplate<typename T1, typename T2, typename Lhs, typename Rhs>\nstruct binary_evaluator<CwiseBinaryOp<scalar_quotient_op<T1,T2>, Lhs, Rhs>, IteratorBased, IndexBased>\n  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_quotient_op<T1,T2>, Lhs, Rhs> >\n{\n  typedef CwiseBinaryOp<scalar_quotient_op<T1,T2>, Lhs, Rhs> XprType;\n  typedef sparse_conjunction_evaluator<XprType> Base;\n  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}\n};\n\n// \"sparse && sparse\"\ntemplate<typename Lhs, typename Rhs>\nstruct binary_evaluator<CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs>, IteratorBased, IteratorBased>\n  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs> >\n{\n  typedef CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs> XprType;\n  typedef sparse_conjunction_evaluator<XprType> Base;\n  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}\n};\n// \"dense && sparse\"\ntemplate<typename Lhs, typename Rhs>\nstruct binary_evaluator<CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs>, IndexBased, IteratorBased>\n  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs> >\n{\n  typedef CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs> XprType;\n  typedef sparse_conjunction_evaluator<XprType> Base;\n  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}\n};\n// \"sparse && dense\"\ntemplate<typename Lhs, typename Rhs>\nstruct binary_evaluator<CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs>, IteratorBased, IndexBased>\n  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs> >\n{\n  typedef CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs> XprType;\n  typedef sparse_conjunction_evaluator<XprType> Base;\n  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}\n};\n\n// \"sparse ^ sparse\"\ntemplate<typename XprType>\nstruct sparse_conjunction_evaluator<XprType, IteratorBased, IteratorBased>\n  : evaluator_base<XprType>\n{\nprotected:\n  typedef typename XprType::Functor BinaryOp;\n  typedef typename XprType::Lhs LhsArg;\n  typedef typename XprType::Rhs RhsArg;\n  typedef typename evaluator<LhsArg>::InnerIterator  LhsIterator;\n  typedef typename evaluator<RhsArg>::InnerIterator  RhsIterator;\n  typedef typename XprType::StorageIndex StorageIndex;\n  typedef typename traits<XprType>::Scalar Scalar;\npublic:\n\n  class InnerIterator\n  {\n  public:\n    \n    EIGEN_STRONG_INLINE InnerIterator(const sparse_conjunction_evaluator& aEval, Index outer)\n      : m_lhsIter(aEval.m_lhsImpl,outer), m_rhsIter(aEval.m_rhsImpl,outer), m_functor(aEval.m_functor)\n    {\n      while (m_lhsIter && m_rhsIter && (m_lhsIter.index() != m_rhsIter.index()))\n      {\n        if (m_lhsIter.index() < m_rhsIter.index())\n          ++m_lhsIter;\n        else\n          ++m_rhsIter;\n      }\n    }\n\n    EIGEN_STRONG_INLINE InnerIterator& operator++()\n    {\n      ++m_lhsIter;\n      ++m_rhsIter;\n      while (m_lhsIter && m_rhsIter && (m_lhsIter.index() != m_rhsIter.index()))\n      {\n        if (m_lhsIter.index() < m_rhsIter.index())\n          ++m_lhsIter;\n        else\n          ++m_rhsIter;\n      }\n      return *this;\n    }\n    \n    EIGEN_STRONG_INLINE Scalar value() const { return m_functor(m_lhsIter.value(), m_rhsIter.value()); }\n\n    EIGEN_STRONG_INLINE StorageIndex index() const { return m_lhsIter.index(); }\n    EIGEN_STRONG_INLINE Index outer() const { return m_lhsIter.outer(); }\n    EIGEN_STRONG_INLINE Index row() const { return m_lhsIter.row(); }\n    EIGEN_STRONG_INLINE Index col() const { return m_lhsIter.col(); }\n\n    EIGEN_STRONG_INLINE operator bool() const { return (m_lhsIter && m_rhsIter); }\n\n  protected:\n    LhsIterator m_lhsIter;\n    RhsIterator m_rhsIter;\n    const BinaryOp& m_functor;\n  };\n  \n  \n  enum {\n    CoeffReadCost = int(evaluator<LhsArg>::CoeffReadCost) + int(evaluator<RhsArg>::CoeffReadCost) + int(functor_traits<BinaryOp>::Cost),\n    Flags = XprType::Flags\n  };\n  \n  explicit sparse_conjunction_evaluator(const XprType& xpr)\n    : m_functor(xpr.functor()),\n      m_lhsImpl(xpr.lhs()), \n      m_rhsImpl(xpr.rhs())  \n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<BinaryOp>::Cost);\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n  \n  inline Index nonZerosEstimate() const {\n    return (std::min)(m_lhsImpl.nonZerosEstimate(), m_rhsImpl.nonZerosEstimate());\n  }\n\nprotected:\n  const BinaryOp m_functor;\n  evaluator<LhsArg> m_lhsImpl;\n  evaluator<RhsArg> m_rhsImpl;\n};\n\n// \"dense ^ sparse\"\ntemplate<typename XprType>\nstruct sparse_conjunction_evaluator<XprType, IndexBased, IteratorBased>\n  : evaluator_base<XprType>\n{\nprotected:\n  typedef typename XprType::Functor BinaryOp;\n  typedef typename XprType::Lhs LhsArg;\n  typedef typename XprType::Rhs RhsArg;\n  typedef evaluator<LhsArg> LhsEvaluator;\n  typedef typename evaluator<RhsArg>::InnerIterator  RhsIterator;\n  typedef typename XprType::StorageIndex StorageIndex;\n  typedef typename traits<XprType>::Scalar Scalar;\npublic:\n\n  class InnerIterator\n  {\n    enum { IsRowMajor = (int(RhsArg::Flags)&RowMajorBit)==RowMajorBit };\n\n  public:\n    \n    EIGEN_STRONG_INLINE InnerIterator(const sparse_conjunction_evaluator& aEval, Index outer)\n      : m_lhsEval(aEval.m_lhsImpl), m_rhsIter(aEval.m_rhsImpl,outer), m_functor(aEval.m_functor), m_outer(outer)\n    {}\n\n    EIGEN_STRONG_INLINE InnerIterator& operator++()\n    {\n      ++m_rhsIter;\n      return *this;\n    }\n\n    EIGEN_STRONG_INLINE Scalar value() const\n    { return m_functor(m_lhsEval.coeff(IsRowMajor?m_outer:m_rhsIter.index(),IsRowMajor?m_rhsIter.index():m_outer), m_rhsIter.value()); }\n\n    EIGEN_STRONG_INLINE StorageIndex index() const { return m_rhsIter.index(); }\n    EIGEN_STRONG_INLINE Index outer() const { return m_rhsIter.outer(); }\n    EIGEN_STRONG_INLINE Index row() const { return m_rhsIter.row(); }\n    EIGEN_STRONG_INLINE Index col() const { return m_rhsIter.col(); }\n\n    EIGEN_STRONG_INLINE operator bool() const { return m_rhsIter; }\n    \n  protected:\n    const LhsEvaluator &m_lhsEval;\n    RhsIterator m_rhsIter;\n    const BinaryOp& m_functor;\n    const Index m_outer;\n  };\n  \n  \n  enum {\n    CoeffReadCost = int(evaluator<LhsArg>::CoeffReadCost) + int(evaluator<RhsArg>::CoeffReadCost) + int(functor_traits<BinaryOp>::Cost),\n    Flags = XprType::Flags\n  };\n  \n  explicit sparse_conjunction_evaluator(const XprType& xpr)\n    : m_functor(xpr.functor()),\n      m_lhsImpl(xpr.lhs()), \n      m_rhsImpl(xpr.rhs())  \n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<BinaryOp>::Cost);\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n  \n  inline Index nonZerosEstimate() const {\n    return m_rhsImpl.nonZerosEstimate();\n  }\n\nprotected:\n  const BinaryOp m_functor;\n  evaluator<LhsArg> m_lhsImpl;\n  evaluator<RhsArg> m_rhsImpl;\n};\n\n// \"sparse ^ dense\"\ntemplate<typename XprType>\nstruct sparse_conjunction_evaluator<XprType, IteratorBased, IndexBased>\n  : evaluator_base<XprType>\n{\nprotected:\n  typedef typename XprType::Functor BinaryOp;\n  typedef typename XprType::Lhs LhsArg;\n  typedef typename XprType::Rhs RhsArg;\n  typedef typename evaluator<LhsArg>::InnerIterator LhsIterator;\n  typedef evaluator<RhsArg> RhsEvaluator;\n  typedef typename XprType::StorageIndex StorageIndex;\n  typedef typename traits<XprType>::Scalar Scalar;\npublic:\n\n  class InnerIterator\n  {\n    enum { IsRowMajor = (int(LhsArg::Flags)&RowMajorBit)==RowMajorBit };\n\n  public:\n    \n    EIGEN_STRONG_INLINE InnerIterator(const sparse_conjunction_evaluator& aEval, Index outer)\n      : m_lhsIter(aEval.m_lhsImpl,outer), m_rhsEval(aEval.m_rhsImpl), m_functor(aEval.m_functor), m_outer(outer)\n    {}\n\n    EIGEN_STRONG_INLINE InnerIterator& operator++()\n    {\n      ++m_lhsIter;\n      return *this;\n    }\n\n    EIGEN_STRONG_INLINE Scalar value() const\n    { return m_functor(m_lhsIter.value(),\n                       m_rhsEval.coeff(IsRowMajor?m_outer:m_lhsIter.index(),IsRowMajor?m_lhsIter.index():m_outer)); }\n\n    EIGEN_STRONG_INLINE StorageIndex index() const { return m_lhsIter.index(); }\n    EIGEN_STRONG_INLINE Index outer() const { return m_lhsIter.outer(); }\n    EIGEN_STRONG_INLINE Index row() const { return m_lhsIter.row(); }\n    EIGEN_STRONG_INLINE Index col() const { return m_lhsIter.col(); }\n\n    EIGEN_STRONG_INLINE operator bool() const { return m_lhsIter; }\n    \n  protected:\n    LhsIterator m_lhsIter;\n    const evaluator<RhsArg> &m_rhsEval;\n    const BinaryOp& m_functor;\n    const Index m_outer;\n  };\n  \n  \n  enum {\n    CoeffReadCost = int(evaluator<LhsArg>::CoeffReadCost) + int(evaluator<RhsArg>::CoeffReadCost) + int(functor_traits<BinaryOp>::Cost),\n    Flags = XprType::Flags\n  };\n  \n  explicit sparse_conjunction_evaluator(const XprType& xpr)\n    : m_functor(xpr.functor()),\n      m_lhsImpl(xpr.lhs()), \n      m_rhsImpl(xpr.rhs())  \n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<BinaryOp>::Cost);\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n  \n  inline Index nonZerosEstimate() const {\n    return m_lhsImpl.nonZerosEstimate();\n  }\n\nprotected:\n  const BinaryOp m_functor;\n  evaluator<LhsArg> m_lhsImpl;\n  evaluator<RhsArg> m_rhsImpl;\n};\n\n}\n\n/***************************************************************************\n* Implementation of SparseMatrixBase and SparseCwise functions/operators\n***************************************************************************/\n\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\nDerived& SparseMatrixBase<Derived>::operator+=(const EigenBase<OtherDerived> &other)\n{\n  call_assignment(derived(), other.derived(), internal::add_assign_op<Scalar,typename OtherDerived::Scalar>());\n  return derived();\n}\n\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\nDerived& SparseMatrixBase<Derived>::operator-=(const EigenBase<OtherDerived> &other)\n{\n  call_assignment(derived(), other.derived(), internal::assign_op<Scalar,typename OtherDerived::Scalar>());\n  return derived();\n}\n\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\nEIGEN_STRONG_INLINE Derived &\nSparseMatrixBase<Derived>::operator-=(const SparseMatrixBase<OtherDerived> &other)\n{\n  return derived() = derived() - other.derived();\n}\n\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\nEIGEN_STRONG_INLINE Derived &\nSparseMatrixBase<Derived>::operator+=(const SparseMatrixBase<OtherDerived>& other)\n{\n  return derived() = derived() + other.derived();\n}\n\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\nDerived& SparseMatrixBase<Derived>::operator+=(const DiagonalBase<OtherDerived>& other)\n{\n  call_assignment_no_alias(derived(), other.derived(), internal::add_assign_op<Scalar,typename OtherDerived::Scalar>());\n  return derived();\n}\n\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\nDerived& SparseMatrixBase<Derived>::operator-=(const DiagonalBase<OtherDerived>& other)\n{\n  call_assignment_no_alias(derived(), other.derived(), internal::sub_assign_op<Scalar,typename OtherDerived::Scalar>());\n  return derived();\n}\n    \ntemplate<typename Derived>\ntemplate<typename OtherDerived>\nEIGEN_STRONG_INLINE const typename SparseMatrixBase<Derived>::template CwiseProductDenseReturnType<OtherDerived>::Type\nSparseMatrixBase<Derived>::cwiseProduct(const MatrixBase<OtherDerived> &other) const\n{\n  return typename CwiseProductDenseReturnType<OtherDerived>::Type(derived(), other.derived());\n}\n\ntemplate<typename DenseDerived, typename SparseDerived>\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_sum_op<typename DenseDerived::Scalar,typename SparseDerived::Scalar>, const DenseDerived, const SparseDerived>\noperator+(const MatrixBase<DenseDerived> &a, const SparseMatrixBase<SparseDerived> &b)\n{\n  return CwiseBinaryOp<internal::scalar_sum_op<typename DenseDerived::Scalar,typename SparseDerived::Scalar>, const DenseDerived, const SparseDerived>(a.derived(), b.derived());\n}\n\ntemplate<typename SparseDerived, typename DenseDerived>\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_sum_op<typename SparseDerived::Scalar,typename DenseDerived::Scalar>, const SparseDerived, const DenseDerived>\noperator+(const SparseMatrixBase<SparseDerived> &a, const MatrixBase<DenseDerived> &b)\n{\n  return CwiseBinaryOp<internal::scalar_sum_op<typename SparseDerived::Scalar,typename DenseDerived::Scalar>, const SparseDerived, const DenseDerived>(a.derived(), b.derived());\n}\n\ntemplate<typename DenseDerived, typename SparseDerived>\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_difference_op<typename DenseDerived::Scalar,typename SparseDerived::Scalar>, const DenseDerived, const SparseDerived>\noperator-(const MatrixBase<DenseDerived> &a, const SparseMatrixBase<SparseDerived> &b)\n{\n  return CwiseBinaryOp<internal::scalar_difference_op<typename DenseDerived::Scalar,typename SparseDerived::Scalar>, const DenseDerived, const SparseDerived>(a.derived(), b.derived());\n}\n\ntemplate<typename SparseDerived, typename DenseDerived>\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_difference_op<typename SparseDerived::Scalar,typename DenseDerived::Scalar>, const SparseDerived, const DenseDerived>\noperator-(const SparseMatrixBase<SparseDerived> &a, const MatrixBase<DenseDerived> &b)\n{\n  return CwiseBinaryOp<internal::scalar_difference_op<typename SparseDerived::Scalar,typename DenseDerived::Scalar>, const SparseDerived, const DenseDerived>(a.derived(), b.derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_CWISE_BINARY_OP_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseCwiseUnaryOp.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_CWISE_UNARY_OP_H\n#define EIGEN_SPARSE_CWISE_UNARY_OP_H\n\nnamespace Eigen { \n\nnamespace internal {\n  \ntemplate<typename UnaryOp, typename ArgType>\nstruct unary_evaluator<CwiseUnaryOp<UnaryOp,ArgType>, IteratorBased>\n  : public evaluator_base<CwiseUnaryOp<UnaryOp,ArgType> >\n{\n  public:\n    typedef CwiseUnaryOp<UnaryOp, ArgType> XprType;\n\n    class InnerIterator;\n    \n    enum {\n      CoeffReadCost = int(evaluator<ArgType>::CoeffReadCost) + int(functor_traits<UnaryOp>::Cost),\n      Flags = XprType::Flags\n    };\n    \n    explicit unary_evaluator(const XprType& op) : m_functor(op.functor()), m_argImpl(op.nestedExpression())\n    {\n      EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<UnaryOp>::Cost);\n      EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n    }\n    \n    inline Index nonZerosEstimate() const {\n      return m_argImpl.nonZerosEstimate();\n    }\n\n  protected:\n    typedef typename evaluator<ArgType>::InnerIterator        EvalIterator;\n    \n    const UnaryOp m_functor;\n    evaluator<ArgType> m_argImpl;\n};\n\ntemplate<typename UnaryOp, typename ArgType>\nclass unary_evaluator<CwiseUnaryOp<UnaryOp,ArgType>, IteratorBased>::InnerIterator\n    : public unary_evaluator<CwiseUnaryOp<UnaryOp,ArgType>, IteratorBased>::EvalIterator\n{\n  protected:\n    typedef typename XprType::Scalar Scalar;\n    typedef typename unary_evaluator<CwiseUnaryOp<UnaryOp,ArgType>, IteratorBased>::EvalIterator Base;\n  public:\n\n    EIGEN_STRONG_INLINE InnerIterator(const unary_evaluator& unaryOp, Index outer)\n      : Base(unaryOp.m_argImpl,outer), m_functor(unaryOp.m_functor)\n    {}\n\n    EIGEN_STRONG_INLINE InnerIterator& operator++()\n    { Base::operator++(); return *this; }\n\n    EIGEN_STRONG_INLINE Scalar value() const { return m_functor(Base::value()); }\n\n  protected:\n    const UnaryOp m_functor;\n  private:\n    Scalar& valueRef();\n};\n\ntemplate<typename ViewOp, typename ArgType>\nstruct unary_evaluator<CwiseUnaryView<ViewOp,ArgType>, IteratorBased>\n  : public evaluator_base<CwiseUnaryView<ViewOp,ArgType> >\n{\n  public:\n    typedef CwiseUnaryView<ViewOp, ArgType> XprType;\n\n    class InnerIterator;\n    \n    enum {\n      CoeffReadCost = int(evaluator<ArgType>::CoeffReadCost) + int(functor_traits<ViewOp>::Cost),\n      Flags = XprType::Flags\n    };\n    \n    explicit unary_evaluator(const XprType& op) : m_functor(op.functor()), m_argImpl(op.nestedExpression())\n    {\n      EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<ViewOp>::Cost);\n      EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n    }\n\n  protected:\n    typedef typename evaluator<ArgType>::InnerIterator        EvalIterator;\n    \n    const ViewOp m_functor;\n    evaluator<ArgType> m_argImpl;\n};\n\ntemplate<typename ViewOp, typename ArgType>\nclass unary_evaluator<CwiseUnaryView<ViewOp,ArgType>, IteratorBased>::InnerIterator\n    : public unary_evaluator<CwiseUnaryView<ViewOp,ArgType>, IteratorBased>::EvalIterator\n{\n  protected:\n    typedef typename XprType::Scalar Scalar;\n    typedef typename unary_evaluator<CwiseUnaryView<ViewOp,ArgType>, IteratorBased>::EvalIterator Base;\n  public:\n\n    EIGEN_STRONG_INLINE InnerIterator(const unary_evaluator& unaryOp, Index outer)\n      : Base(unaryOp.m_argImpl,outer), m_functor(unaryOp.m_functor)\n    {}\n\n    EIGEN_STRONG_INLINE InnerIterator& operator++()\n    { Base::operator++(); return *this; }\n\n    EIGEN_STRONG_INLINE Scalar value() const { return m_functor(Base::value()); }\n    EIGEN_STRONG_INLINE Scalar& valueRef() { return m_functor(Base::valueRef()); }\n\n  protected:\n    const ViewOp m_functor;\n};\n\n} // end namespace internal\n\ntemplate<typename Derived>\nEIGEN_STRONG_INLINE Derived&\nSparseMatrixBase<Derived>::operator*=(const Scalar& other)\n{\n  typedef typename internal::evaluator<Derived>::InnerIterator EvalIterator;\n  internal::evaluator<Derived> thisEval(derived());\n  for (Index j=0; j<outerSize(); ++j)\n    for (EvalIterator i(thisEval,j); i; ++i)\n      i.valueRef() *= other;\n  return derived();\n}\n\ntemplate<typename Derived>\nEIGEN_STRONG_INLINE Derived&\nSparseMatrixBase<Derived>::operator/=(const Scalar& other)\n{\n  typedef typename internal::evaluator<Derived>::InnerIterator EvalIterator;\n  internal::evaluator<Derived> thisEval(derived());\n  for (Index j=0; j<outerSize(); ++j)\n    for (EvalIterator i(thisEval,j); i; ++i)\n      i.valueRef() /= other;\n  return derived();\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_CWISE_UNARY_OP_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseDenseProduct.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEDENSEPRODUCT_H\n#define EIGEN_SPARSEDENSEPRODUCT_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate <> struct product_promote_storage_type<Sparse,Dense, OuterProduct> { typedef Sparse ret; };\ntemplate <> struct product_promote_storage_type<Dense,Sparse, OuterProduct> { typedef Sparse ret; };\n\ntemplate<typename SparseLhsType, typename DenseRhsType, typename DenseResType,\n         typename AlphaType,\n         int LhsStorageOrder = ((SparseLhsType::Flags&RowMajorBit)==RowMajorBit) ? RowMajor : ColMajor,\n         bool ColPerCol = ((DenseRhsType::Flags&RowMajorBit)==0) || DenseRhsType::ColsAtCompileTime==1>\nstruct sparse_time_dense_product_impl;\n\ntemplate<typename SparseLhsType, typename DenseRhsType, typename DenseResType>\nstruct sparse_time_dense_product_impl<SparseLhsType,DenseRhsType,DenseResType, typename DenseResType::Scalar, RowMajor, true>\n{\n  typedef typename internal::remove_all<SparseLhsType>::type Lhs;\n  typedef typename internal::remove_all<DenseRhsType>::type Rhs;\n  typedef typename internal::remove_all<DenseResType>::type Res;\n  typedef typename evaluator<Lhs>::InnerIterator LhsInnerIterator;\n  typedef evaluator<Lhs> LhsEval;\n  static void run(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const typename Res::Scalar& alpha)\n  {\n    LhsEval lhsEval(lhs);\n    \n    Index n = lhs.outerSize();\n#ifdef EIGEN_HAS_OPENMP\n    Eigen::initParallel();\n    Index threads = Eigen::nbThreads();\n#endif\n    \n    for(Index c=0; c<rhs.cols(); ++c)\n    {\n#ifdef EIGEN_HAS_OPENMP\n      // This 20000 threshold has been found experimentally on 2D and 3D Poisson problems.\n      // It basically represents the minimal amount of work to be done to be worth it.\n      if(threads>1 && lhsEval.nonZerosEstimate() > 20000)\n      {\n        #pragma omp parallel for schedule(dynamic,(n+threads*4-1)/(threads*4)) num_threads(threads)\n        for(Index i=0; i<n; ++i)\n          processRow(lhsEval,rhs,res,alpha,i,c);\n      }\n      else\n#endif\n      {\n        for(Index i=0; i<n; ++i)\n          processRow(lhsEval,rhs,res,alpha,i,c);\n      }\n    }\n  }\n  \n  static void processRow(const LhsEval& lhsEval, const DenseRhsType& rhs, DenseResType& res, const typename Res::Scalar& alpha, Index i, Index col)\n  {\n    typename Res::Scalar tmp(0);\n    for(LhsInnerIterator it(lhsEval,i); it ;++it)\n      tmp += it.value() * rhs.coeff(it.index(),col);\n    res.coeffRef(i,col) += alpha * tmp;\n  }\n  \n};\n\n// FIXME: what is the purpose of the following specialization? Is it for the BlockedSparse format?\n// -> let's disable it for now as it is conflicting with generic scalar*matrix and matrix*scalar operators\n// template<typename T1, typename T2/*, int Options_, typename _StrideType*/>\n// struct ScalarBinaryOpTraits<T1, Ref<T2/*, Options_, _StrideType*/> >\n// {\n//   enum {\n//     Defined = 1\n//   };\n//   typedef typename CwiseUnaryOp<scalar_multiple2_op<T1, typename T2::Scalar>, T2>::PlainObject ReturnType;\n// };\n\ntemplate<typename SparseLhsType, typename DenseRhsType, typename DenseResType, typename AlphaType>\nstruct sparse_time_dense_product_impl<SparseLhsType,DenseRhsType,DenseResType, AlphaType, ColMajor, true>\n{\n  typedef typename internal::remove_all<SparseLhsType>::type Lhs;\n  typedef typename internal::remove_all<DenseRhsType>::type Rhs;\n  typedef typename internal::remove_all<DenseResType>::type Res;\n  typedef evaluator<Lhs> LhsEval;\n  typedef typename LhsEval::InnerIterator LhsInnerIterator;\n  static void run(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const AlphaType& alpha)\n  {\n    LhsEval lhsEval(lhs);\n    for(Index c=0; c<rhs.cols(); ++c)\n    {\n      for(Index j=0; j<lhs.outerSize(); ++j)\n      {\n//        typename Res::Scalar rhs_j = alpha * rhs.coeff(j,c);\n        typename ScalarBinaryOpTraits<AlphaType, typename Rhs::Scalar>::ReturnType rhs_j(alpha * rhs.coeff(j,c));\n        for(LhsInnerIterator it(lhsEval,j); it ;++it)\n          res.coeffRef(it.index(),c) += it.value() * rhs_j;\n      }\n    }\n  }\n};\n\ntemplate<typename SparseLhsType, typename DenseRhsType, typename DenseResType>\nstruct sparse_time_dense_product_impl<SparseLhsType,DenseRhsType,DenseResType, typename DenseResType::Scalar, RowMajor, false>\n{\n  typedef typename internal::remove_all<SparseLhsType>::type Lhs;\n  typedef typename internal::remove_all<DenseRhsType>::type Rhs;\n  typedef typename internal::remove_all<DenseResType>::type Res;\n  typedef evaluator<Lhs> LhsEval;\n  typedef typename LhsEval::InnerIterator LhsInnerIterator;\n  static void run(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const typename Res::Scalar& alpha)\n  {\n    Index n = lhs.rows();\n    LhsEval lhsEval(lhs);\n\n#ifdef EIGEN_HAS_OPENMP\n    Eigen::initParallel();\n    Index threads = Eigen::nbThreads();\n    // This 20000 threshold has been found experimentally on 2D and 3D Poisson problems.\n    // It basically represents the minimal amount of work to be done to be worth it.\n    if(threads>1 && lhsEval.nonZerosEstimate()*rhs.cols() > 20000)\n    {\n      #pragma omp parallel for schedule(dynamic,(n+threads*4-1)/(threads*4)) num_threads(threads)\n      for(Index i=0; i<n; ++i)\n        processRow(lhsEval,rhs,res,alpha,i);\n    }\n    else\n#endif\n    {\n      for(Index i=0; i<n; ++i)\n        processRow(lhsEval, rhs, res, alpha, i);\n    }\n  }\n\n  static void processRow(const LhsEval& lhsEval, const DenseRhsType& rhs, Res& res, const typename Res::Scalar& alpha, Index i)\n  {\n    typename Res::RowXpr res_i(res.row(i));\n    for(LhsInnerIterator it(lhsEval,i); it ;++it)\n      res_i += (alpha*it.value()) * rhs.row(it.index());\n  }\n};\n\ntemplate<typename SparseLhsType, typename DenseRhsType, typename DenseResType>\nstruct sparse_time_dense_product_impl<SparseLhsType,DenseRhsType,DenseResType, typename DenseResType::Scalar, ColMajor, false>\n{\n  typedef typename internal::remove_all<SparseLhsType>::type Lhs;\n  typedef typename internal::remove_all<DenseRhsType>::type Rhs;\n  typedef typename internal::remove_all<DenseResType>::type Res;\n  typedef typename evaluator<Lhs>::InnerIterator LhsInnerIterator;\n  static void run(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const typename Res::Scalar& alpha)\n  {\n    evaluator<Lhs> lhsEval(lhs);\n    for(Index j=0; j<lhs.outerSize(); ++j)\n    {\n      typename Rhs::ConstRowXpr rhs_j(rhs.row(j));\n      for(LhsInnerIterator it(lhsEval,j); it ;++it)\n        res.row(it.index()) += (alpha*it.value()) * rhs_j;\n    }\n  }\n};\n\ntemplate<typename SparseLhsType, typename DenseRhsType, typename DenseResType,typename AlphaType>\ninline void sparse_time_dense_product(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const AlphaType& alpha)\n{\n  sparse_time_dense_product_impl<SparseLhsType,DenseRhsType,DenseResType, AlphaType>::run(lhs, rhs, res, alpha);\n}\n\n} // end namespace internal\n\nnamespace internal {\n\ntemplate<typename Lhs, typename Rhs, int ProductType>\nstruct generic_product_impl<Lhs, Rhs, SparseShape, DenseShape, ProductType>\n : generic_product_impl_base<Lhs,Rhs,generic_product_impl<Lhs,Rhs,SparseShape,DenseShape,ProductType> >\n{\n  typedef typename Product<Lhs,Rhs>::Scalar Scalar;\n  \n  template<typename Dest>\n  static void scaleAndAddTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha)\n  {\n    typedef typename nested_eval<Lhs,((Rhs::Flags&RowMajorBit)==0) ? 1 : Rhs::ColsAtCompileTime>::type LhsNested;\n    typedef typename nested_eval<Rhs,((Lhs::Flags&RowMajorBit)==0) ? 1 : Dynamic>::type RhsNested;\n    LhsNested lhsNested(lhs);\n    RhsNested rhsNested(rhs);\n    internal::sparse_time_dense_product(lhsNested, rhsNested, dst, alpha);\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, int ProductType>\nstruct generic_product_impl<Lhs, Rhs, SparseTriangularShape, DenseShape, ProductType>\n  : generic_product_impl<Lhs, Rhs, SparseShape, DenseShape, ProductType>\n{};\n\ntemplate<typename Lhs, typename Rhs, int ProductType>\nstruct generic_product_impl<Lhs, Rhs, DenseShape, SparseShape, ProductType>\n  : generic_product_impl_base<Lhs,Rhs,generic_product_impl<Lhs,Rhs,DenseShape,SparseShape,ProductType> >\n{\n  typedef typename Product<Lhs,Rhs>::Scalar Scalar;\n  \n  template<typename Dst>\n  static void scaleAndAddTo(Dst& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha)\n  {\n    typedef typename nested_eval<Lhs,((Rhs::Flags&RowMajorBit)==0) ? Dynamic : 1>::type LhsNested;\n    typedef typename nested_eval<Rhs,((Lhs::Flags&RowMajorBit)==RowMajorBit) ? 1 : Lhs::RowsAtCompileTime>::type RhsNested;\n    LhsNested lhsNested(lhs);\n    RhsNested rhsNested(rhs);\n    \n    // transpose everything\n    Transpose<Dst> dstT(dst);\n    internal::sparse_time_dense_product(rhsNested.transpose(), lhsNested.transpose(), dstT, alpha);\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, int ProductType>\nstruct generic_product_impl<Lhs, Rhs, DenseShape, SparseTriangularShape, ProductType>\n  : generic_product_impl<Lhs, Rhs, DenseShape, SparseShape, ProductType>\n{};\n\ntemplate<typename LhsT, typename RhsT, bool NeedToTranspose>\nstruct sparse_dense_outer_product_evaluator\n{\nprotected:\n  typedef typename conditional<NeedToTranspose,RhsT,LhsT>::type Lhs1;\n  typedef typename conditional<NeedToTranspose,LhsT,RhsT>::type ActualRhs;\n  typedef Product<LhsT,RhsT,DefaultProduct> ProdXprType;\n  \n  // if the actual left-hand side is a dense vector,\n  // then build a sparse-view so that we can seamlessly iterate over it.\n  typedef typename conditional<is_same<typename internal::traits<Lhs1>::StorageKind,Sparse>::value,\n            Lhs1, SparseView<Lhs1> >::type ActualLhs;\n  typedef typename conditional<is_same<typename internal::traits<Lhs1>::StorageKind,Sparse>::value,\n            Lhs1 const&, SparseView<Lhs1> >::type LhsArg;\n            \n  typedef evaluator<ActualLhs> LhsEval;\n  typedef evaluator<ActualRhs> RhsEval;\n  typedef typename evaluator<ActualLhs>::InnerIterator LhsIterator;\n  typedef typename ProdXprType::Scalar Scalar;\n  \npublic:\n  enum {\n    Flags = NeedToTranspose ? RowMajorBit : 0,\n    CoeffReadCost = HugeCost\n  };\n  \n  class InnerIterator : public LhsIterator\n  {\n  public:\n    InnerIterator(const sparse_dense_outer_product_evaluator &xprEval, Index outer)\n      : LhsIterator(xprEval.m_lhsXprImpl, 0),\n        m_outer(outer),\n        m_empty(false),\n        m_factor(get(xprEval.m_rhsXprImpl, outer, typename internal::traits<ActualRhs>::StorageKind() ))\n    {}\n    \n    EIGEN_STRONG_INLINE Index outer() const { return m_outer; }\n    EIGEN_STRONG_INLINE Index row()   const { return NeedToTranspose ? m_outer : LhsIterator::index(); }\n    EIGEN_STRONG_INLINE Index col()   const { return NeedToTranspose ? LhsIterator::index() : m_outer; }\n\n    EIGEN_STRONG_INLINE Scalar value() const { return LhsIterator::value() * m_factor; }\n    EIGEN_STRONG_INLINE operator bool() const { return LhsIterator::operator bool() && (!m_empty); }\n    \n  protected:\n    Scalar get(const RhsEval &rhs, Index outer, Dense = Dense()) const\n    {\n      return rhs.coeff(outer);\n    }\n    \n    Scalar get(const RhsEval &rhs, Index outer, Sparse = Sparse())\n    {\n      typename RhsEval::InnerIterator it(rhs, outer);\n      if (it && it.index()==0 && it.value()!=Scalar(0))\n        return it.value();\n      m_empty = true;\n      return Scalar(0);\n    }\n    \n    Index m_outer;\n    bool m_empty;\n    Scalar m_factor;\n  };\n  \n  sparse_dense_outer_product_evaluator(const Lhs1 &lhs, const ActualRhs &rhs)\n     : m_lhs(lhs), m_lhsXprImpl(m_lhs), m_rhsXprImpl(rhs)\n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n  \n  // transpose case\n  sparse_dense_outer_product_evaluator(const ActualRhs &rhs, const Lhs1 &lhs)\n     : m_lhs(lhs), m_lhsXprImpl(m_lhs), m_rhsXprImpl(rhs)\n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n    \nprotected:\n  const LhsArg m_lhs;\n  evaluator<ActualLhs> m_lhsXprImpl;\n  evaluator<ActualRhs> m_rhsXprImpl;\n};\n\n// sparse * dense outer product\ntemplate<typename Lhs, typename Rhs>\nstruct product_evaluator<Product<Lhs, Rhs, DefaultProduct>, OuterProduct, SparseShape, DenseShape>\n  : sparse_dense_outer_product_evaluator<Lhs,Rhs, Lhs::IsRowMajor>\n{\n  typedef sparse_dense_outer_product_evaluator<Lhs,Rhs, Lhs::IsRowMajor> Base;\n  \n  typedef Product<Lhs, Rhs> XprType;\n  typedef typename XprType::PlainObject PlainObject;\n\n  explicit product_evaluator(const XprType& xpr)\n    : Base(xpr.lhs(), xpr.rhs())\n  {}\n  \n};\n\ntemplate<typename Lhs, typename Rhs>\nstruct product_evaluator<Product<Lhs, Rhs, DefaultProduct>, OuterProduct, DenseShape, SparseShape>\n  : sparse_dense_outer_product_evaluator<Lhs,Rhs, Rhs::IsRowMajor>\n{\n  typedef sparse_dense_outer_product_evaluator<Lhs,Rhs, Rhs::IsRowMajor> Base;\n  \n  typedef Product<Lhs, Rhs> XprType;\n  typedef typename XprType::PlainObject PlainObject;\n\n  explicit product_evaluator(const XprType& xpr)\n    : Base(xpr.lhs(), xpr.rhs())\n  {}\n  \n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSEDENSEPRODUCT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseDiagonalProduct.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_DIAGONAL_PRODUCT_H\n#define EIGEN_SPARSE_DIAGONAL_PRODUCT_H\n\nnamespace Eigen { \n\n// The product of a diagonal matrix with a sparse matrix can be easily\n// implemented using expression template.\n// We have two consider very different cases:\n// 1 - diag * row-major sparse\n//     => each inner vector <=> scalar * sparse vector product\n//     => so we can reuse CwiseUnaryOp::InnerIterator\n// 2 - diag * col-major sparse\n//     => each inner vector <=> densevector * sparse vector cwise product\n//     => again, we can reuse specialization of CwiseBinaryOp::InnerIterator\n//        for that particular case\n// The two other cases are symmetric.\n\nnamespace internal {\n\nenum {\n  SDP_AsScalarProduct,\n  SDP_AsCwiseProduct\n};\n  \ntemplate<typename SparseXprType, typename DiagonalCoeffType, int SDP_Tag>\nstruct sparse_diagonal_product_evaluator;\n\ntemplate<typename Lhs, typename Rhs, int ProductTag>\nstruct product_evaluator<Product<Lhs, Rhs, DefaultProduct>, ProductTag, DiagonalShape, SparseShape>\n  : public sparse_diagonal_product_evaluator<Rhs, typename Lhs::DiagonalVectorType, Rhs::Flags&RowMajorBit?SDP_AsScalarProduct:SDP_AsCwiseProduct>\n{\n  typedef Product<Lhs, Rhs, DefaultProduct> XprType;\n  enum { CoeffReadCost = HugeCost, Flags = Rhs::Flags&RowMajorBit, Alignment = 0 }; // FIXME CoeffReadCost & Flags\n  \n  typedef sparse_diagonal_product_evaluator<Rhs, typename Lhs::DiagonalVectorType, Rhs::Flags&RowMajorBit?SDP_AsScalarProduct:SDP_AsCwiseProduct> Base;\n  explicit product_evaluator(const XprType& xpr) : Base(xpr.rhs(), xpr.lhs().diagonal()) {}\n};\n\ntemplate<typename Lhs, typename Rhs, int ProductTag>\nstruct product_evaluator<Product<Lhs, Rhs, DefaultProduct>, ProductTag, SparseShape, DiagonalShape>\n  : public sparse_diagonal_product_evaluator<Lhs, Transpose<const typename Rhs::DiagonalVectorType>, Lhs::Flags&RowMajorBit?SDP_AsCwiseProduct:SDP_AsScalarProduct>\n{\n  typedef Product<Lhs, Rhs, DefaultProduct> XprType;\n  enum { CoeffReadCost = HugeCost, Flags = Lhs::Flags&RowMajorBit, Alignment = 0 }; // FIXME CoeffReadCost & Flags\n  \n  typedef sparse_diagonal_product_evaluator<Lhs, Transpose<const typename Rhs::DiagonalVectorType>, Lhs::Flags&RowMajorBit?SDP_AsCwiseProduct:SDP_AsScalarProduct> Base;\n  explicit product_evaluator(const XprType& xpr) : Base(xpr.lhs(), xpr.rhs().diagonal().transpose()) {}\n};\n\ntemplate<typename SparseXprType, typename DiagonalCoeffType>\nstruct sparse_diagonal_product_evaluator<SparseXprType, DiagonalCoeffType, SDP_AsScalarProduct>\n{\nprotected:\n  typedef typename evaluator<SparseXprType>::InnerIterator SparseXprInnerIterator;\n  typedef typename SparseXprType::Scalar Scalar;\n  \npublic:\n  class InnerIterator : public SparseXprInnerIterator\n  {\n  public:\n    InnerIterator(const sparse_diagonal_product_evaluator &xprEval, Index outer)\n      : SparseXprInnerIterator(xprEval.m_sparseXprImpl, outer),\n        m_coeff(xprEval.m_diagCoeffImpl.coeff(outer))\n    {}\n    \n    EIGEN_STRONG_INLINE Scalar value() const { return m_coeff * SparseXprInnerIterator::value(); }\n  protected:\n    typename DiagonalCoeffType::Scalar m_coeff;\n  };\n  \n  sparse_diagonal_product_evaluator(const SparseXprType &sparseXpr, const DiagonalCoeffType &diagCoeff)\n    : m_sparseXprImpl(sparseXpr), m_diagCoeffImpl(diagCoeff)\n  {}\n\n  Index nonZerosEstimate() const { return m_sparseXprImpl.nonZerosEstimate(); }\n    \nprotected:\n  evaluator<SparseXprType> m_sparseXprImpl;\n  evaluator<DiagonalCoeffType> m_diagCoeffImpl;\n};\n\n\ntemplate<typename SparseXprType, typename DiagCoeffType>\nstruct sparse_diagonal_product_evaluator<SparseXprType, DiagCoeffType, SDP_AsCwiseProduct>\n{\n  typedef typename SparseXprType::Scalar Scalar;\n  typedef typename SparseXprType::StorageIndex StorageIndex;\n  \n  typedef typename nested_eval<DiagCoeffType,SparseXprType::IsRowMajor ? SparseXprType::RowsAtCompileTime\n                                                                       : SparseXprType::ColsAtCompileTime>::type DiagCoeffNested;\n  \n  class InnerIterator\n  {\n    typedef typename evaluator<SparseXprType>::InnerIterator SparseXprIter;\n  public:\n    InnerIterator(const sparse_diagonal_product_evaluator &xprEval, Index outer)\n      : m_sparseIter(xprEval.m_sparseXprEval, outer), m_diagCoeffNested(xprEval.m_diagCoeffNested)\n    {}\n    \n    inline Scalar value() const { return m_sparseIter.value() * m_diagCoeffNested.coeff(index()); }\n    inline StorageIndex index() const  { return m_sparseIter.index(); }\n    inline Index outer() const  { return m_sparseIter.outer(); }\n    inline Index col() const    { return SparseXprType::IsRowMajor ? m_sparseIter.index() : m_sparseIter.outer(); }\n    inline Index row() const    { return SparseXprType::IsRowMajor ? m_sparseIter.outer() : m_sparseIter.index(); }\n    \n    EIGEN_STRONG_INLINE InnerIterator& operator++() { ++m_sparseIter; return *this; }\n    inline operator bool() const  { return m_sparseIter; }\n    \n  protected:\n    SparseXprIter m_sparseIter;\n    DiagCoeffNested m_diagCoeffNested;\n  };\n  \n  sparse_diagonal_product_evaluator(const SparseXprType &sparseXpr, const DiagCoeffType &diagCoeff)\n    : m_sparseXprEval(sparseXpr), m_diagCoeffNested(diagCoeff)\n  {}\n\n  Index nonZerosEstimate() const { return m_sparseXprEval.nonZerosEstimate(); }\n    \nprotected:\n  evaluator<SparseXprType> m_sparseXprEval;\n  DiagCoeffNested m_diagCoeffNested;\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_DIAGONAL_PRODUCT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseDot.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_DOT_H\n#define EIGEN_SPARSE_DOT_H\n\nnamespace Eigen { \n\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\ntypename internal::traits<Derived>::Scalar\nSparseMatrixBase<Derived>::dot(const MatrixBase<OtherDerived>& other) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived)\n  EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Derived,OtherDerived)\n  EIGEN_STATIC_ASSERT((internal::is_same<Scalar, typename OtherDerived::Scalar>::value),\n    YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n\n  eigen_assert(size() == other.size());\n  eigen_assert(other.size()>0 && \"you are using a non initialized vector\");\n\n  internal::evaluator<Derived> thisEval(derived());\n  typename internal::evaluator<Derived>::InnerIterator i(thisEval, 0);\n  Scalar res(0);\n  while (i)\n  {\n    res += numext::conj(i.value()) * other.coeff(i.index());\n    ++i;\n  }\n  return res;\n}\n\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\ntypename internal::traits<Derived>::Scalar\nSparseMatrixBase<Derived>::dot(const SparseMatrixBase<OtherDerived>& other) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived)\n  EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Derived,OtherDerived)\n  EIGEN_STATIC_ASSERT((internal::is_same<Scalar, typename OtherDerived::Scalar>::value),\n    YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n\n  eigen_assert(size() == other.size());\n\n  internal::evaluator<Derived> thisEval(derived());\n  typename internal::evaluator<Derived>::InnerIterator i(thisEval, 0);\n  \n  internal::evaluator<OtherDerived>  otherEval(other.derived());\n  typename internal::evaluator<OtherDerived>::InnerIterator j(otherEval, 0);\n\n  Scalar res(0);\n  while (i && j)\n  {\n    if (i.index()==j.index())\n    {\n      res += numext::conj(i.value()) * j.value();\n      ++i; ++j;\n    }\n    else if (i.index()<j.index())\n      ++i;\n    else\n      ++j;\n  }\n  return res;\n}\n\ntemplate<typename Derived>\ninline typename NumTraits<typename internal::traits<Derived>::Scalar>::Real\nSparseMatrixBase<Derived>::squaredNorm() const\n{\n  return numext::real((*this).cwiseAbs2().sum());\n}\n\ntemplate<typename Derived>\ninline typename NumTraits<typename internal::traits<Derived>::Scalar>::Real\nSparseMatrixBase<Derived>::norm() const\n{\n  using std::sqrt;\n  return sqrt(squaredNorm());\n}\n\ntemplate<typename Derived>\ninline typename NumTraits<typename internal::traits<Derived>::Scalar>::Real\nSparseMatrixBase<Derived>::blueNorm() const\n{\n  return internal::blueNorm_impl(*this);\n}\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_DOT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseFuzzy.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_FUZZY_H\n#define EIGEN_SPARSE_FUZZY_H\n\nnamespace Eigen {\n  \ntemplate<typename Derived>\ntemplate<typename OtherDerived>\nbool SparseMatrixBase<Derived>::isApprox(const SparseMatrixBase<OtherDerived>& other, const RealScalar &prec) const\n{\n  const typename internal::nested_eval<Derived,2,PlainObject>::type actualA(derived());\n  typename internal::conditional<bool(IsRowMajor)==bool(OtherDerived::IsRowMajor),\n    const typename internal::nested_eval<OtherDerived,2,PlainObject>::type,\n    const PlainObject>::type actualB(other.derived());\n\n  return (actualA - actualB).squaredNorm() <= prec * prec * numext::mini(actualA.squaredNorm(), actualB.squaredNorm());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_FUZZY_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseMap.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_MAP_H\n#define EIGEN_SPARSE_MAP_H\n\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nstruct traits<Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n  : public traits<SparseMatrix<MatScalar,MatOptions,MatIndex> >\n{\n  typedef SparseMatrix<MatScalar,MatOptions,MatIndex> PlainObjectType;\n  typedef traits<PlainObjectType> TraitsBase;\n  enum {\n    Flags = TraitsBase::Flags & (~NestByRefBit)\n  };\n};\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nstruct traits<Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n  : public traits<SparseMatrix<MatScalar,MatOptions,MatIndex> >\n{\n  typedef SparseMatrix<MatScalar,MatOptions,MatIndex> PlainObjectType;\n  typedef traits<PlainObjectType> TraitsBase;\n  enum {\n    Flags = TraitsBase::Flags & (~ (NestByRefBit | LvalueBit))\n  };\n};\n\n} // end namespace internal\n\ntemplate<typename Derived,\n         int Level = internal::accessors_level<Derived>::has_write_access ? WriteAccessors : ReadOnlyAccessors\n> class SparseMapBase;\n\n/** \\ingroup SparseCore_Module\n  * class SparseMapBase\n  * \\brief Common base class for Map and Ref instance of sparse matrix and vector.\n  */\ntemplate<typename Derived>\nclass SparseMapBase<Derived,ReadOnlyAccessors>\n  : public SparseCompressedBase<Derived>\n{\n  public:\n    typedef SparseCompressedBase<Derived> Base;\n    typedef typename Base::Scalar Scalar;\n    typedef typename Base::StorageIndex StorageIndex;\n    enum { IsRowMajor = Base::IsRowMajor };\n    using Base::operator=;\n  protected:\n    \n    typedef typename internal::conditional<\n                         bool(internal::is_lvalue<Derived>::value),\n                         Scalar *, const Scalar *>::type ScalarPointer;\n    typedef typename internal::conditional<\n                         bool(internal::is_lvalue<Derived>::value),\n                         StorageIndex *, const StorageIndex *>::type IndexPointer;\n\n    Index   m_outerSize;\n    Index   m_innerSize;\n    Array<StorageIndex,2,1>  m_zero_nnz;\n    IndexPointer  m_outerIndex;\n    IndexPointer  m_innerIndices;\n    ScalarPointer m_values;\n    IndexPointer  m_innerNonZeros;\n\n  public:\n\n    /** \\copydoc SparseMatrixBase::rows() */\n    inline Index rows() const { return IsRowMajor ? m_outerSize : m_innerSize; }\n    /** \\copydoc SparseMatrixBase::cols() */\n    inline Index cols() const { return IsRowMajor ? m_innerSize : m_outerSize; }\n    /** \\copydoc SparseMatrixBase::innerSize() */\n    inline Index innerSize() const { return m_innerSize; }\n    /** \\copydoc SparseMatrixBase::outerSize() */\n    inline Index outerSize() const { return m_outerSize; }\n    /** \\copydoc SparseCompressedBase::nonZeros */\n    inline Index nonZeros() const { return m_zero_nnz[1]; }\n    \n    /** \\copydoc SparseCompressedBase::isCompressed */\n    bool isCompressed() const { return m_innerNonZeros==0; }\n\n    //----------------------------------------\n    // direct access interface\n    /** \\copydoc SparseMatrix::valuePtr */\n    inline const Scalar* valuePtr() const { return m_values; }\n    /** \\copydoc SparseMatrix::innerIndexPtr */\n    inline const StorageIndex* innerIndexPtr() const { return m_innerIndices; }\n    /** \\copydoc SparseMatrix::outerIndexPtr */\n    inline const StorageIndex* outerIndexPtr() const { return m_outerIndex; }\n    /** \\copydoc SparseMatrix::innerNonZeroPtr */\n    inline const StorageIndex* innerNonZeroPtr() const { return m_innerNonZeros; }\n    //----------------------------------------\n\n    /** \\copydoc SparseMatrix::coeff */\n    inline Scalar coeff(Index row, Index col) const\n    {\n      const Index outer = IsRowMajor ? row : col;\n      const Index inner = IsRowMajor ? col : row;\n\n      Index start = m_outerIndex[outer];\n      Index end = isCompressed() ? m_outerIndex[outer+1] : start + m_innerNonZeros[outer];\n      if (start==end)\n        return Scalar(0);\n      else if (end>0 && inner==m_innerIndices[end-1])\n        return m_values[end-1];\n      // ^^  optimization: let's first check if it is the last coefficient\n      // (very common in high level algorithms)\n\n      const StorageIndex* r = std::lower_bound(&m_innerIndices[start],&m_innerIndices[end-1],inner);\n      const Index id = r-&m_innerIndices[0];\n      return ((*r==inner) && (id<end)) ? m_values[id] : Scalar(0);\n    }\n\n    inline SparseMapBase(Index rows, Index cols, Index nnz, IndexPointer outerIndexPtr, IndexPointer innerIndexPtr,\n                              ScalarPointer valuePtr, IndexPointer innerNonZerosPtr = 0)\n      : m_outerSize(IsRowMajor?rows:cols), m_innerSize(IsRowMajor?cols:rows), m_zero_nnz(0,internal::convert_index<StorageIndex>(nnz)), m_outerIndex(outerIndexPtr),\n        m_innerIndices(innerIndexPtr), m_values(valuePtr), m_innerNonZeros(innerNonZerosPtr)\n    {}\n\n    // for vectors\n    inline SparseMapBase(Index size, Index nnz, IndexPointer innerIndexPtr, ScalarPointer valuePtr)\n      : m_outerSize(1), m_innerSize(size), m_zero_nnz(0,internal::convert_index<StorageIndex>(nnz)), m_outerIndex(m_zero_nnz.data()),\n        m_innerIndices(innerIndexPtr), m_values(valuePtr), m_innerNonZeros(0)\n    {}\n\n    /** Empty destructor */\n    inline ~SparseMapBase() {}\n\n  protected:\n    inline SparseMapBase() {}\n};\n\n/** \\ingroup SparseCore_Module\n  * class SparseMapBase\n  * \\brief Common base class for writable Map and Ref instance of sparse matrix and vector.\n  */\ntemplate<typename Derived>\nclass SparseMapBase<Derived,WriteAccessors>\n  : public SparseMapBase<Derived,ReadOnlyAccessors>\n{\n    typedef MapBase<Derived, ReadOnlyAccessors> ReadOnlyMapBase;\n    \n  public:\n    typedef SparseMapBase<Derived, ReadOnlyAccessors> Base;\n    typedef typename Base::Scalar Scalar;\n    typedef typename Base::StorageIndex StorageIndex;\n    enum { IsRowMajor = Base::IsRowMajor };\n    \n    using Base::operator=;\n\n  public:\n    \n    //----------------------------------------\n    // direct access interface\n    using Base::valuePtr;\n    using Base::innerIndexPtr;\n    using Base::outerIndexPtr;\n    using Base::innerNonZeroPtr;\n    /** \\copydoc SparseMatrix::valuePtr */\n    inline Scalar* valuePtr()              { return Base::m_values; }\n    /** \\copydoc SparseMatrix::innerIndexPtr */\n    inline StorageIndex* innerIndexPtr()   { return Base::m_innerIndices; }\n    /** \\copydoc SparseMatrix::outerIndexPtr */\n    inline StorageIndex* outerIndexPtr()   { return Base::m_outerIndex; }\n    /** \\copydoc SparseMatrix::innerNonZeroPtr */\n    inline StorageIndex* innerNonZeroPtr() { return Base::m_innerNonZeros; }\n    //----------------------------------------\n\n    /** \\copydoc SparseMatrix::coeffRef */\n    inline Scalar& coeffRef(Index row, Index col)\n    {\n      const Index outer = IsRowMajor ? row : col;\n      const Index inner = IsRowMajor ? col : row;\n\n      Index start = Base::m_outerIndex[outer];\n      Index end = Base::isCompressed() ? Base::m_outerIndex[outer+1] : start + Base::m_innerNonZeros[outer];\n      eigen_assert(end>=start && \"you probably called coeffRef on a non finalized matrix\");\n      eigen_assert(end>start && \"coeffRef cannot be called on a zero coefficient\");\n      StorageIndex* r = std::lower_bound(&Base::m_innerIndices[start],&Base::m_innerIndices[end],inner);\n      const Index id = r - &Base::m_innerIndices[0];\n      eigen_assert((*r==inner) && (id<end) && \"coeffRef cannot be called on a zero coefficient\");\n      return const_cast<Scalar*>(Base::m_values)[id];\n    }\n    \n    inline SparseMapBase(Index rows, Index cols, Index nnz, StorageIndex* outerIndexPtr, StorageIndex* innerIndexPtr,\n                         Scalar* valuePtr, StorageIndex* innerNonZerosPtr = 0)\n      : Base(rows, cols, nnz, outerIndexPtr, innerIndexPtr, valuePtr, innerNonZerosPtr)\n    {}\n\n    // for vectors\n    inline SparseMapBase(Index size, Index nnz, StorageIndex* innerIndexPtr, Scalar* valuePtr)\n      : Base(size, nnz, innerIndexPtr, valuePtr)\n    {}\n\n    /** Empty destructor */\n    inline ~SparseMapBase() {}\n\n  protected:\n    inline SparseMapBase() {}\n};\n\n/** \\ingroup SparseCore_Module\n  *\n  * \\brief Specialization of class Map for SparseMatrix-like storage.\n  *\n  * \\tparam SparseMatrixType the equivalent sparse matrix type of the referenced data, it must be a template instance of class SparseMatrix.\n  *\n  * \\sa class Map, class SparseMatrix, class Ref<SparseMatrixType,Options>\n  */\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nclass Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType>\n  : public SparseMapBase<Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n#else\ntemplate<typename SparseMatrixType>\nclass Map<SparseMatrixType>\n  : public SparseMapBase<Derived,WriteAccessors>\n#endif\n{\n  public:\n    typedef SparseMapBase<Map> Base;\n    EIGEN_SPARSE_PUBLIC_INTERFACE(Map)\n    enum { IsRowMajor = Base::IsRowMajor };\n\n  public:\n\n    /** Constructs a read-write Map to a sparse matrix of size \\a rows x \\a cols, containing \\a nnz non-zero coefficients,\n      * stored as a sparse format as defined by the pointers \\a outerIndexPtr, \\a innerIndexPtr, and \\a valuePtr.\n      * If the optional parameter \\a innerNonZerosPtr is the null pointer, then a standard compressed format is assumed.\n      *\n      * This constructor is available only if \\c SparseMatrixType is non-const.\n      *\n      * More details on the expected storage schemes are given in the \\ref TutorialSparse \"manual pages\".\n      */\n    inline Map(Index rows, Index cols, Index nnz, StorageIndex* outerIndexPtr,\n               StorageIndex* innerIndexPtr, Scalar* valuePtr, StorageIndex* innerNonZerosPtr = 0)\n      : Base(rows, cols, nnz, outerIndexPtr, innerIndexPtr, valuePtr, innerNonZerosPtr)\n    {}\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n    /** Empty destructor */\n    inline ~Map() {}\n};\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nclass Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType>\n  : public SparseMapBase<Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n{\n  public:\n    typedef SparseMapBase<Map> Base;\n    EIGEN_SPARSE_PUBLIC_INTERFACE(Map)\n    enum { IsRowMajor = Base::IsRowMajor };\n\n  public:\n#endif\n    /** This is the const version of the above constructor.\n      *\n      * This constructor is available only if \\c SparseMatrixType is const, e.g.:\n      * \\code Map<const SparseMatrix<double> >  \\endcode\n      */\n    inline Map(Index rows, Index cols, Index nnz, const StorageIndex* outerIndexPtr,\n               const StorageIndex* innerIndexPtr, const Scalar* valuePtr, const StorageIndex* innerNonZerosPtr = 0)\n      : Base(rows, cols, nnz, outerIndexPtr, innerIndexPtr, valuePtr, innerNonZerosPtr)\n    {}\n\n    /** Empty destructor */\n    inline ~Map() {}\n};\n\nnamespace internal {\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nstruct evaluator<Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n  : evaluator<SparseCompressedBase<Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > >\n{\n  typedef evaluator<SparseCompressedBase<Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > > Base;\n  typedef Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> XprType;  \n  evaluator() : Base() {}\n  explicit evaluator(const XprType &mat) : Base(mat) {}\n};\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nstruct evaluator<Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n  : evaluator<SparseCompressedBase<Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > >\n{\n  typedef evaluator<SparseCompressedBase<Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > > Base;\n  typedef Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> XprType;  \n  evaluator() : Base() {}\n  explicit evaluator(const XprType &mat) : Base(mat) {}\n};\n\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_MAP_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseMatrix.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEMATRIX_H\n#define EIGEN_SPARSEMATRIX_H\n\nnamespace Eigen { \n\n/** \\ingroup SparseCore_Module\n  *\n  * \\class SparseMatrix\n  *\n  * \\brief A versatible sparse matrix representation\n  *\n  * This class implements a more versatile variants of the common \\em compressed row/column storage format.\n  * Each colmun's (resp. row) non zeros are stored as a pair of value with associated row (resp. colmiun) index.\n  * All the non zeros are stored in a single large buffer. Unlike the \\em compressed format, there might be extra\n  * space in between the nonzeros of two successive colmuns (resp. rows) such that insertion of new non-zero\n  * can be done with limited memory reallocation and copies.\n  *\n  * A call to the function makeCompressed() turns the matrix into the standard \\em compressed format\n  * compatible with many library.\n  *\n  * More details on this storage sceheme are given in the \\ref TutorialSparse \"manual pages\".\n  *\n  * \\tparam Scalar_ the scalar type, i.e. the type of the coefficients\n  * \\tparam Options_ Union of bit flags controlling the storage scheme. Currently the only possibility\n  *                 is ColMajor or RowMajor. The default is 0 which means column-major.\n  * \\tparam StorageIndex_ the type of the indices. It has to be a \\b signed type (e.g., short, int, std::ptrdiff_t). Default is \\c int.\n  *\n  * \\warning In %Eigen 3.2, the undocumented type \\c SparseMatrix::Index was improperly defined as the storage index type (e.g., int),\n  *          whereas it is now (starting from %Eigen 3.3) deprecated and always defined as Eigen::Index.\n  *          Codes making use of \\c SparseMatrix::Index, might thus likely have to be changed to use \\c SparseMatrix::StorageIndex instead.\n  *\n  * This class can be extended with the help of the plugin mechanism described on the page\n  * \\ref TopicCustomizing_Plugins by defining the preprocessor symbol \\c EIGEN_SPARSEMATRIX_PLUGIN.\n  */\n\nnamespace internal {\ntemplate<typename Scalar_, int Options_, typename StorageIndex_>\nstruct traits<SparseMatrix<Scalar_, Options_, StorageIndex_> >\n{\n  typedef Scalar_ Scalar;\n  typedef StorageIndex_ StorageIndex;\n  typedef Sparse StorageKind;\n  typedef MatrixXpr XprKind;\n  enum {\n    RowsAtCompileTime = Dynamic,\n    ColsAtCompileTime = Dynamic,\n    MaxRowsAtCompileTime = Dynamic,\n    MaxColsAtCompileTime = Dynamic,\n    Flags = Options_ | NestByRefBit | LvalueBit | CompressedAccessBit,\n    SupportedAccessPatterns = InnerRandomAccessPattern\n  };\n};\n\ntemplate<typename Scalar_, int Options_, typename StorageIndex_, int DiagIndex>\nstruct traits<Diagonal<SparseMatrix<Scalar_, Options_, StorageIndex_>, DiagIndex> >\n{\n  typedef SparseMatrix<Scalar_, Options_, StorageIndex_> MatrixType;\n  typedef typename ref_selector<MatrixType>::type MatrixTypeNested;\n  typedef typename remove_reference<MatrixTypeNested>::type _MatrixTypeNested;\n\n  typedef Scalar_ Scalar;\n  typedef Dense StorageKind;\n  typedef StorageIndex_ StorageIndex;\n  typedef MatrixXpr XprKind;\n\n  enum {\n    RowsAtCompileTime = Dynamic,\n    ColsAtCompileTime = 1,\n    MaxRowsAtCompileTime = Dynamic,\n    MaxColsAtCompileTime = 1,\n    Flags = LvalueBit\n  };\n};\n\ntemplate<typename Scalar_, int Options_, typename StorageIndex_, int DiagIndex>\nstruct traits<Diagonal<const SparseMatrix<Scalar_, Options_, StorageIndex_>, DiagIndex> >\n : public traits<Diagonal<SparseMatrix<Scalar_, Options_, StorageIndex_>, DiagIndex> >\n{\n  enum {\n    Flags = 0\n  };\n};\n\n} // end namespace internal\n\ntemplate<typename Scalar_, int Options_, typename StorageIndex_>\nclass SparseMatrix\n  : public SparseCompressedBase<SparseMatrix<Scalar_, Options_, StorageIndex_> >\n{\n    typedef SparseCompressedBase<SparseMatrix> Base;\n    using Base::convert_index;\n    friend class SparseVector<Scalar_,0,StorageIndex_>;\n    template<typename, typename, typename, typename, typename>\n    friend struct internal::Assignment;\n  public:\n    using Base::isCompressed;\n    using Base::nonZeros;\n    EIGEN_SPARSE_PUBLIC_INTERFACE(SparseMatrix)\n    using Base::operator+=;\n    using Base::operator-=;\n\n    typedef MappedSparseMatrix<Scalar,Flags> Map;\n    typedef Diagonal<SparseMatrix> DiagonalReturnType;\n    typedef Diagonal<const SparseMatrix> ConstDiagonalReturnType;\n    typedef typename Base::InnerIterator InnerIterator;\n    typedef typename Base::ReverseInnerIterator ReverseInnerIterator;\n    \n\n    using Base::IsRowMajor;\n    typedef internal::CompressedStorage<Scalar,StorageIndex> Storage;\n    enum {\n      Options = Options_\n    };\n\n    typedef typename Base::IndexVector IndexVector;\n    typedef typename Base::ScalarVector ScalarVector;\n  protected:\n    typedef SparseMatrix<Scalar,(Flags&~RowMajorBit)|(IsRowMajor?RowMajorBit:0)> TransposedSparseMatrix;\n\n    Index m_outerSize;\n    Index m_innerSize;\n    StorageIndex* m_outerIndex;\n    StorageIndex* m_innerNonZeros;     // optional, if null then the data is compressed\n    Storage m_data;\n\n  public:\n    \n    /** \\returns the number of rows of the matrix */\n    inline Index rows() const { return IsRowMajor ? m_outerSize : m_innerSize; }\n    /** \\returns the number of columns of the matrix */\n    inline Index cols() const { return IsRowMajor ? m_innerSize : m_outerSize; }\n\n    /** \\returns the number of rows (resp. columns) of the matrix if the storage order column major (resp. row major) */\n    inline Index innerSize() const { return m_innerSize; }\n    /** \\returns the number of columns (resp. rows) of the matrix if the storage order column major (resp. row major) */\n    inline Index outerSize() const { return m_outerSize; }\n    \n    /** \\returns a const pointer to the array of values.\n      * This function is aimed at interoperability with other libraries.\n      * \\sa innerIndexPtr(), outerIndexPtr() */\n    inline const Scalar* valuePtr() const { return m_data.valuePtr(); }\n    /** \\returns a non-const pointer to the array of values.\n      * This function is aimed at interoperability with other libraries.\n      * \\sa innerIndexPtr(), outerIndexPtr() */\n    inline Scalar* valuePtr() { return m_data.valuePtr(); }\n\n    /** \\returns a const pointer to the array of inner indices.\n      * This function is aimed at interoperability with other libraries.\n      * \\sa valuePtr(), outerIndexPtr() */\n    inline const StorageIndex* innerIndexPtr() const { return m_data.indexPtr(); }\n    /** \\returns a non-const pointer to the array of inner indices.\n      * This function is aimed at interoperability with other libraries.\n      * \\sa valuePtr(), outerIndexPtr() */\n    inline StorageIndex* innerIndexPtr() { return m_data.indexPtr(); }\n\n    /** \\returns a const pointer to the array of the starting positions of the inner vectors.\n      * This function is aimed at interoperability with other libraries.\n      * \\sa valuePtr(), innerIndexPtr() */\n    inline const StorageIndex* outerIndexPtr() const { return m_outerIndex; }\n    /** \\returns a non-const pointer to the array of the starting positions of the inner vectors.\n      * This function is aimed at interoperability with other libraries.\n      * \\sa valuePtr(), innerIndexPtr() */\n    inline StorageIndex* outerIndexPtr() { return m_outerIndex; }\n\n    /** \\returns a const pointer to the array of the number of non zeros of the inner vectors.\n      * This function is aimed at interoperability with other libraries.\n      * \\warning it returns the null pointer 0 in compressed mode */\n    inline const StorageIndex* innerNonZeroPtr() const { return m_innerNonZeros; }\n    /** \\returns a non-const pointer to the array of the number of non zeros of the inner vectors.\n      * This function is aimed at interoperability with other libraries.\n      * \\warning it returns the null pointer 0 in compressed mode */\n    inline StorageIndex* innerNonZeroPtr() { return m_innerNonZeros; }\n\n    /** \\internal */\n    inline Storage& data() { return m_data; }\n    /** \\internal */\n    inline const Storage& data() const { return m_data; }\n\n    /** \\returns the value of the matrix at position \\a i, \\a j\n      * This function returns Scalar(0) if the element is an explicit \\em zero */\n    inline Scalar coeff(Index row, Index col) const\n    {\n      eigen_assert(row>=0 && row<rows() && col>=0 && col<cols());\n      \n      const Index outer = IsRowMajor ? row : col;\n      const Index inner = IsRowMajor ? col : row;\n      Index end = m_innerNonZeros ? m_outerIndex[outer] + m_innerNonZeros[outer] : m_outerIndex[outer+1];\n      return m_data.atInRange(m_outerIndex[outer], end, StorageIndex(inner));\n    }\n\n    /** \\returns a non-const reference to the value of the matrix at position \\a i, \\a j\n      *\n      * If the element does not exist then it is inserted via the insert(Index,Index) function\n      * which itself turns the matrix into a non compressed form if that was not the case.\n      *\n      * This is a O(log(nnz_j)) operation (binary search) plus the cost of insert(Index,Index)\n      * function if the element does not already exist.\n      */\n    inline Scalar& coeffRef(Index row, Index col)\n    {\n      eigen_assert(row>=0 && row<rows() && col>=0 && col<cols());\n      \n      const Index outer = IsRowMajor ? row : col;\n      const Index inner = IsRowMajor ? col : row;\n\n      Index start = m_outerIndex[outer];\n      Index end = m_innerNonZeros ? m_outerIndex[outer] + m_innerNonZeros[outer] : m_outerIndex[outer+1];\n      eigen_assert(end>=start && \"you probably called coeffRef on a non finalized matrix\");\n      if(end<=start)\n        return insert(row,col);\n      const Index p = m_data.searchLowerIndex(start,end-1,StorageIndex(inner));\n      if((p<end) && (m_data.index(p)==inner))\n        return m_data.value(p);\n      else\n        return insert(row,col);\n    }\n\n    /** \\returns a reference to a novel non zero coefficient with coordinates \\a row x \\a col.\n      * The non zero coefficient must \\b not already exist.\n      *\n      * If the matrix \\c *this is in compressed mode, then \\c *this is turned into uncompressed\n      * mode while reserving room for 2 x this->innerSize() non zeros if reserve(Index) has not been called earlier.\n      * In this case, the insertion procedure is optimized for a \\e sequential insertion mode where elements are assumed to be\n      * inserted by increasing outer-indices.\n      * \n      * If that's not the case, then it is strongly recommended to either use a triplet-list to assemble the matrix, or to first\n      * call reserve(const SizesType &) to reserve the appropriate number of non-zero elements per inner vector.\n      *\n      * Assuming memory has been appropriately reserved, this function performs a sorted insertion in O(1)\n      * if the elements of each inner vector are inserted in increasing inner index order, and in O(nnz_j) for a random insertion.\n      *\n      */\n    Scalar& insert(Index row, Index col);\n\n  public:\n\n    /** Removes all non zeros but keep allocated memory\n      *\n      * This function does not free the currently allocated memory. To release as much as memory as possible,\n      * call \\code mat.data().squeeze(); \\endcode after resizing it.\n      * \n      * \\sa resize(Index,Index), data()\n      */\n    inline void setZero()\n    {\n      m_data.clear();\n      std::fill_n(m_outerIndex, m_outerSize + 1, StorageIndex(0));\n      if(m_innerNonZeros) {\n        std::fill_n(m_innerNonZeros, m_outerSize, StorageIndex(0));\n      }\n    }\n\n    /** Preallocates \\a reserveSize non zeros.\n      *\n      * Precondition: the matrix must be in compressed mode. */\n    inline void reserve(Index reserveSize)\n    {\n      eigen_assert(isCompressed() && \"This function does not make sense in non compressed mode.\");\n      m_data.reserve(reserveSize);\n    }\n    \n    #ifdef EIGEN_PARSED_BY_DOXYGEN\n    /** Preallocates \\a reserveSize[\\c j] non zeros for each column (resp. row) \\c j.\n      *\n      * This function turns the matrix in non-compressed mode.\n      * \n      * The type \\c SizesType must expose the following interface:\n        \\code\n        typedef value_type;\n        const value_type& operator[](i) const;\n        \\endcode\n      * for \\c i in the [0,this->outerSize()[ range.\n      * Typical choices include std::vector<int>, Eigen::VectorXi, Eigen::VectorXi::Constant, etc.\n      */\n    template<class SizesType>\n    inline void reserve(const SizesType& reserveSizes);\n    #else\n    template<class SizesType>\n    inline void reserve(const SizesType& reserveSizes, const typename SizesType::value_type& enableif =\n    #if (!EIGEN_COMP_MSVC) || (EIGEN_COMP_MSVC>=1500) // MSVC 2005 fails to compile with this typename\n        typename\n    #endif\n        SizesType::value_type())\n    {\n      EIGEN_UNUSED_VARIABLE(enableif);\n      reserveInnerVectors(reserveSizes);\n    }\n    #endif // EIGEN_PARSED_BY_DOXYGEN\n  protected:\n    template<class SizesType>\n    inline void reserveInnerVectors(const SizesType& reserveSizes)\n    {\n      if(isCompressed())\n      {\n        Index totalReserveSize = 0;\n        // turn the matrix into non-compressed mode\n        m_innerNonZeros = static_cast<StorageIndex*>(std::malloc(m_outerSize * sizeof(StorageIndex)));\n        if (!m_innerNonZeros) internal::throw_std_bad_alloc();\n        \n        // temporarily use m_innerSizes to hold the new starting points.\n        StorageIndex* newOuterIndex = m_innerNonZeros;\n        \n        StorageIndex count = 0;\n        for(Index j=0; j<m_outerSize; ++j)\n        {\n          newOuterIndex[j] = count;\n          count += reserveSizes[j] + (m_outerIndex[j+1]-m_outerIndex[j]);\n          totalReserveSize += reserveSizes[j];\n        }\n        m_data.reserve(totalReserveSize);\n        StorageIndex previousOuterIndex = m_outerIndex[m_outerSize];\n        for(Index j=m_outerSize-1; j>=0; --j)\n        {\n          StorageIndex innerNNZ = previousOuterIndex - m_outerIndex[j];\n          for(Index i=innerNNZ-1; i>=0; --i)\n          {\n            m_data.index(newOuterIndex[j]+i) = m_data.index(m_outerIndex[j]+i);\n            m_data.value(newOuterIndex[j]+i) = m_data.value(m_outerIndex[j]+i);\n          }\n          previousOuterIndex = m_outerIndex[j];\n          m_outerIndex[j] = newOuterIndex[j];\n          m_innerNonZeros[j] = innerNNZ;\n        }\n        if(m_outerSize>0)\n          m_outerIndex[m_outerSize] = m_outerIndex[m_outerSize-1] + m_innerNonZeros[m_outerSize-1] + reserveSizes[m_outerSize-1];\n        \n        m_data.resize(m_outerIndex[m_outerSize]);\n      }\n      else\n      {\n        StorageIndex* newOuterIndex = static_cast<StorageIndex*>(std::malloc((m_outerSize+1)*sizeof(StorageIndex)));\n        if (!newOuterIndex) internal::throw_std_bad_alloc();\n        \n        StorageIndex count = 0;\n        for(Index j=0; j<m_outerSize; ++j)\n        {\n          newOuterIndex[j] = count;\n          StorageIndex alreadyReserved = (m_outerIndex[j+1]-m_outerIndex[j]) - m_innerNonZeros[j];\n          StorageIndex toReserve = std::max<StorageIndex>(reserveSizes[j], alreadyReserved);\n          count += toReserve + m_innerNonZeros[j];\n        }\n        newOuterIndex[m_outerSize] = count;\n        \n        m_data.resize(count);\n        for(Index j=m_outerSize-1; j>=0; --j)\n        {\n          Index offset = newOuterIndex[j] - m_outerIndex[j];\n          if(offset>0)\n          {\n            StorageIndex innerNNZ = m_innerNonZeros[j];\n            for(Index i=innerNNZ-1; i>=0; --i)\n            {\n              m_data.index(newOuterIndex[j]+i) = m_data.index(m_outerIndex[j]+i);\n              m_data.value(newOuterIndex[j]+i) = m_data.value(m_outerIndex[j]+i);\n            }\n          }\n        }\n        \n        std::swap(m_outerIndex, newOuterIndex);\n        std::free(newOuterIndex);\n      }\n      \n    }\n  public:\n\n    //--- low level purely coherent filling ---\n\n    /** \\internal\n      * \\returns a reference to the non zero coefficient at position \\a row, \\a col assuming that:\n      * - the nonzero does not already exist\n      * - the new coefficient is the last one according to the storage order\n      *\n      * Before filling a given inner vector you must call the statVec(Index) function.\n      *\n      * After an insertion session, you should call the finalize() function.\n      *\n      * \\sa insert, insertBackByOuterInner, startVec */\n    inline Scalar& insertBack(Index row, Index col)\n    {\n      return insertBackByOuterInner(IsRowMajor?row:col, IsRowMajor?col:row);\n    }\n\n    /** \\internal\n      * \\sa insertBack, startVec */\n    inline Scalar& insertBackByOuterInner(Index outer, Index inner)\n    {\n      eigen_assert(Index(m_outerIndex[outer+1]) == m_data.size() && \"Invalid ordered insertion (invalid outer index)\");\n      eigen_assert( (m_outerIndex[outer+1]-m_outerIndex[outer]==0 || m_data.index(m_data.size()-1)<inner) && \"Invalid ordered insertion (invalid inner index)\");\n      Index p = m_outerIndex[outer+1];\n      ++m_outerIndex[outer+1];\n      m_data.append(Scalar(0), inner);\n      return m_data.value(p);\n    }\n\n    /** \\internal\n      * \\warning use it only if you know what you are doing */\n    inline Scalar& insertBackByOuterInnerUnordered(Index outer, Index inner)\n    {\n      Index p = m_outerIndex[outer+1];\n      ++m_outerIndex[outer+1];\n      m_data.append(Scalar(0), inner);\n      return m_data.value(p);\n    }\n\n    /** \\internal\n      * \\sa insertBack, insertBackByOuterInner */\n    inline void startVec(Index outer)\n    {\n      eigen_assert(m_outerIndex[outer]==Index(m_data.size()) && \"You must call startVec for each inner vector sequentially\");\n      eigen_assert(m_outerIndex[outer+1]==0 && \"You must call startVec for each inner vector sequentially\");\n      m_outerIndex[outer+1] = m_outerIndex[outer];\n    }\n\n    /** \\internal\n      * Must be called after inserting a set of non zero entries using the low level compressed API.\n      */\n    inline void finalize()\n    {\n      if(isCompressed())\n      {\n        StorageIndex size = internal::convert_index<StorageIndex>(m_data.size());\n        Index i = m_outerSize;\n        // find the last filled column\n        while (i>=0 && m_outerIndex[i]==0)\n          --i;\n        ++i;\n        while (i<=m_outerSize)\n        {\n          m_outerIndex[i] = size;\n          ++i;\n        }\n      }\n    }\n\n    //---\n\n    template<typename InputIterators>\n    void setFromTriplets(const InputIterators& begin, const InputIterators& end);\n\n    template<typename InputIterators,typename DupFunctor>\n    void setFromTriplets(const InputIterators& begin, const InputIterators& end, DupFunctor dup_func);\n\n    void sumupDuplicates() { collapseDuplicates(internal::scalar_sum_op<Scalar,Scalar>()); }\n\n    template<typename DupFunctor>\n    void collapseDuplicates(DupFunctor dup_func = DupFunctor());\n\n    //---\n    \n    /** \\internal\n      * same as insert(Index,Index) except that the indices are given relative to the storage order */\n    Scalar& insertByOuterInner(Index j, Index i)\n    {\n      return insert(IsRowMajor ? j : i, IsRowMajor ? i : j);\n    }\n\n    /** Turns the matrix into the \\em compressed format.\n      */\n    void makeCompressed()\n    {\n      if(isCompressed())\n        return;\n      \n      eigen_internal_assert(m_outerIndex!=0 && m_outerSize>0);\n      \n      Index oldStart = m_outerIndex[1];\n      m_outerIndex[1] = m_innerNonZeros[0];\n      for(Index j=1; j<m_outerSize; ++j)\n      {\n        Index nextOldStart = m_outerIndex[j+1];\n        Index offset = oldStart - m_outerIndex[j];\n        if(offset>0)\n        {\n          for(Index k=0; k<m_innerNonZeros[j]; ++k)\n          {\n            m_data.index(m_outerIndex[j]+k) = m_data.index(oldStart+k);\n            m_data.value(m_outerIndex[j]+k) = m_data.value(oldStart+k);\n          }\n        }\n        m_outerIndex[j+1] = m_outerIndex[j] + m_innerNonZeros[j];\n        oldStart = nextOldStart;\n      }\n      std::free(m_innerNonZeros);\n      m_innerNonZeros = 0;\n      m_data.resize(m_outerIndex[m_outerSize]);\n      m_data.squeeze();\n    }\n\n    /** Turns the matrix into the uncompressed mode */\n    void uncompress()\n    {\n      if(m_innerNonZeros != 0)\n        return; \n      m_innerNonZeros = static_cast<StorageIndex*>(std::malloc(m_outerSize * sizeof(StorageIndex)));\n      for (Index i = 0; i < m_outerSize; i++)\n      {\n        m_innerNonZeros[i] = m_outerIndex[i+1] - m_outerIndex[i]; \n      }\n    }\n\n    /** Suppresses all nonzeros which are \\b much \\b smaller \\b than \\a reference under the tolerance \\a epsilon */\n    void prune(const Scalar& reference, const RealScalar& epsilon = NumTraits<RealScalar>::dummy_precision())\n    {\n      prune(default_prunning_func(reference,epsilon));\n    }\n    \n    /** Turns the matrix into compressed format, and suppresses all nonzeros which do not satisfy the predicate \\a keep.\n      * The functor type \\a KeepFunc must implement the following function:\n      * \\code\n      * bool operator() (const Index& row, const Index& col, const Scalar& value) const;\n      * \\endcode\n      * \\sa prune(Scalar,RealScalar)\n      */\n    template<typename KeepFunc>\n    void prune(const KeepFunc& keep = KeepFunc())\n    {\n      // TODO optimize the uncompressed mode to avoid moving and allocating the data twice\n      makeCompressed();\n\n      StorageIndex k = 0;\n      for(Index j=0; j<m_outerSize; ++j)\n      {\n        Index previousStart = m_outerIndex[j];\n        m_outerIndex[j] = k;\n        Index end = m_outerIndex[j+1];\n        for(Index i=previousStart; i<end; ++i)\n        {\n          if(keep(IsRowMajor?j:m_data.index(i), IsRowMajor?m_data.index(i):j, m_data.value(i)))\n          {\n            m_data.value(k) = m_data.value(i);\n            m_data.index(k) = m_data.index(i);\n            ++k;\n          }\n        }\n      }\n      m_outerIndex[m_outerSize] = k;\n      m_data.resize(k,0);\n    }\n\n    /** Resizes the matrix to a \\a rows x \\a cols matrix leaving old values untouched.\n      *\n      * If the sizes of the matrix are decreased, then the matrix is turned to \\b uncompressed-mode\n      * and the storage of the out of bounds coefficients is kept and reserved.\n      * Call makeCompressed() to pack the entries and squeeze extra memory.\n      *\n      * \\sa reserve(), setZero(), makeCompressed()\n      */\n    void conservativeResize(Index rows, Index cols) \n    {\n      // No change\n      if (this->rows() == rows && this->cols() == cols) return;\n      \n      // If one dimension is null, then there is nothing to be preserved\n      if(rows==0 || cols==0) return resize(rows,cols);\n\n      Index innerChange = IsRowMajor ? cols - this->cols() : rows - this->rows();\n      Index outerChange = IsRowMajor ? rows - this->rows() : cols - this->cols();\n      StorageIndex newInnerSize = convert_index(IsRowMajor ? cols : rows);\n\n      // Deals with inner non zeros\n      if (m_innerNonZeros)\n      {\n        // Resize m_innerNonZeros\n        StorageIndex *newInnerNonZeros = static_cast<StorageIndex*>(std::realloc(m_innerNonZeros, (m_outerSize + outerChange) * sizeof(StorageIndex)));\n        if (!newInnerNonZeros) internal::throw_std_bad_alloc();\n        m_innerNonZeros = newInnerNonZeros;\n        \n        for(Index i=m_outerSize; i<m_outerSize+outerChange; i++)          \n          m_innerNonZeros[i] = 0;\n      } \n      else if (innerChange < 0) \n      {\n        // Inner size decreased: allocate a new m_innerNonZeros\n        m_innerNonZeros = static_cast<StorageIndex*>(std::malloc((m_outerSize + outerChange) * sizeof(StorageIndex)));\n        if (!m_innerNonZeros) internal::throw_std_bad_alloc();\n        for(Index i = 0; i < m_outerSize + (std::min)(outerChange, Index(0)); i++)\n          m_innerNonZeros[i] = m_outerIndex[i+1] - m_outerIndex[i];\n        for(Index i = m_outerSize; i < m_outerSize + outerChange; i++)\n          m_innerNonZeros[i] = 0;\n      }\n      \n      // Change the m_innerNonZeros in case of a decrease of inner size\n      if (m_innerNonZeros && innerChange < 0)\n      {\n        for(Index i = 0; i < m_outerSize + (std::min)(outerChange, Index(0)); i++)\n        {\n          StorageIndex &n = m_innerNonZeros[i];\n          StorageIndex start = m_outerIndex[i];\n          while (n > 0 && m_data.index(start+n-1) >= newInnerSize) --n; \n        }\n      }\n      \n      m_innerSize = newInnerSize;\n\n      // Re-allocate outer index structure if necessary\n      if (outerChange == 0)\n        return;\n          \n      StorageIndex *newOuterIndex = static_cast<StorageIndex*>(std::realloc(m_outerIndex, (m_outerSize + outerChange + 1) * sizeof(StorageIndex)));\n      if (!newOuterIndex) internal::throw_std_bad_alloc();\n      m_outerIndex = newOuterIndex;\n      if (outerChange > 0)\n      {\n        StorageIndex lastIdx = m_outerSize == 0 ? 0 : m_outerIndex[m_outerSize];\n        for(Index i=m_outerSize; i<m_outerSize+outerChange+1; i++)          \n          m_outerIndex[i] = lastIdx; \n      }\n      m_outerSize += outerChange;\n    }\n    \n    /** Resizes the matrix to a \\a rows x \\a cols matrix and initializes it to zero.\n      * \n      * This function does not free the currently allocated memory. To release as much as memory as possible,\n      * call \\code mat.data().squeeze(); \\endcode after resizing it.\n      * \n      * \\sa reserve(), setZero()\n      */\n    void resize(Index rows, Index cols)\n    {\n      const Index outerSize = IsRowMajor ? rows : cols;\n      m_innerSize = IsRowMajor ? cols : rows;\n      m_data.clear();\n      if (m_outerSize != outerSize || m_outerSize==0)\n      {\n        std::free(m_outerIndex);\n        m_outerIndex = static_cast<StorageIndex*>(std::malloc((outerSize + 1) * sizeof(StorageIndex)));\n        if (!m_outerIndex) internal::throw_std_bad_alloc();\n        \n        m_outerSize = outerSize;\n      }\n      if(m_innerNonZeros)\n      {\n        std::free(m_innerNonZeros);\n        m_innerNonZeros = 0;\n      }\n      std::fill_n(m_outerIndex, m_outerSize + 1, StorageIndex(0));\n    }\n\n    /** \\internal\n      * Resize the nonzero vector to \\a size */\n    void resizeNonZeros(Index size)\n    {\n      m_data.resize(size);\n    }\n\n    /** \\returns a const expression of the diagonal coefficients. */\n    const ConstDiagonalReturnType diagonal() const { return ConstDiagonalReturnType(*this); }\n    \n    /** \\returns a read-write expression of the diagonal coefficients.\n      * \\warning If the diagonal entries are written, then all diagonal\n      * entries \\b must already exist, otherwise an assertion will be raised.\n      */\n    DiagonalReturnType diagonal() { return DiagonalReturnType(*this); }\n\n    /** Default constructor yielding an empty \\c 0 \\c x \\c 0 matrix */\n    inline SparseMatrix()\n      : m_outerSize(-1), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)\n    {\n      check_template_parameters();\n      resize(0, 0);\n    }\n\n    /** Constructs a \\a rows \\c x \\a cols empty matrix */\n    inline SparseMatrix(Index rows, Index cols)\n      : m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)\n    {\n      check_template_parameters();\n      resize(rows, cols);\n    }\n\n    /** Constructs a sparse matrix from the sparse expression \\a other */\n    template<typename OtherDerived>\n    inline SparseMatrix(const SparseMatrixBase<OtherDerived>& other)\n      : m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)\n    {\n      EIGEN_STATIC_ASSERT((internal::is_same<Scalar, typename OtherDerived::Scalar>::value),\n        YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n      check_template_parameters();\n      const bool needToTranspose = (Flags & RowMajorBit) != (internal::evaluator<OtherDerived>::Flags & RowMajorBit);\n      if (needToTranspose)\n        *this = other.derived();\n      else\n      {\n        #ifdef EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n          EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n        #endif\n        internal::call_assignment_no_alias(*this, other.derived());\n      }\n    }\n    \n    /** Constructs a sparse matrix from the sparse selfadjoint view \\a other */\n    template<typename OtherDerived, unsigned int UpLo>\n    inline SparseMatrix(const SparseSelfAdjointView<OtherDerived, UpLo>& other)\n      : m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)\n    {\n      check_template_parameters();\n      Base::operator=(other);\n    }\n\n    /** Copy constructor (it performs a deep copy) */\n    inline SparseMatrix(const SparseMatrix& other)\n      : Base(), m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)\n    {\n      check_template_parameters();\n      *this = other.derived();\n    }\n\n    /** \\brief Copy constructor with in-place evaluation */\n    template<typename OtherDerived>\n    SparseMatrix(const ReturnByValue<OtherDerived>& other)\n      : Base(), m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)\n    {\n      check_template_parameters();\n      initAssignment(other);\n      other.evalTo(*this);\n    }\n    \n    /** \\brief Copy constructor with in-place evaluation */\n    template<typename OtherDerived>\n    explicit SparseMatrix(const DiagonalBase<OtherDerived>& other)\n      : Base(), m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)\n    {\n      check_template_parameters();\n      *this = other.derived();\n    }\n\n    /** Swaps the content of two sparse matrices of the same type.\n      * This is a fast operation that simply swaps the underlying pointers and parameters. */\n    inline void swap(SparseMatrix& other)\n    {\n      //EIGEN_DBG_SPARSE(std::cout << \"SparseMatrix:: swap\\n\");\n      std::swap(m_outerIndex, other.m_outerIndex);\n      std::swap(m_innerSize, other.m_innerSize);\n      std::swap(m_outerSize, other.m_outerSize);\n      std::swap(m_innerNonZeros, other.m_innerNonZeros);\n      m_data.swap(other.m_data);\n    }\n\n    /** Sets *this to the identity matrix.\n      * This function also turns the matrix into compressed mode, and drop any reserved memory. */\n    inline void setIdentity()\n    {\n      eigen_assert(rows() == cols() && \"ONLY FOR SQUARED MATRICES\");\n      this->m_data.resize(rows());\n      Eigen::Map<IndexVector>(this->m_data.indexPtr(), rows()).setLinSpaced(0, StorageIndex(rows()-1));\n      Eigen::Map<ScalarVector>(this->m_data.valuePtr(), rows()).setOnes();\n      Eigen::Map<IndexVector>(this->m_outerIndex, rows()+1).setLinSpaced(0, StorageIndex(rows()));\n      std::free(m_innerNonZeros);\n      m_innerNonZeros = 0;\n    }\n    inline SparseMatrix& operator=(const SparseMatrix& other)\n    {\n      if (other.isRValue())\n      {\n        swap(other.const_cast_derived());\n      }\n      else if(this!=&other)\n      {\n        #ifdef EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n          EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n        #endif\n        initAssignment(other);\n        if(other.isCompressed())\n        {\n          internal::smart_copy(other.m_outerIndex, other.m_outerIndex + m_outerSize + 1, m_outerIndex);\n          m_data = other.m_data;\n        }\n        else\n        {\n          Base::operator=(other);\n        }\n      }\n      return *this;\n    }\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<typename OtherDerived>\n    inline SparseMatrix& operator=(const EigenBase<OtherDerived>& other)\n    { return Base::operator=(other.derived()); }\n\n    template<typename Lhs, typename Rhs>\n    inline SparseMatrix& operator=(const Product<Lhs,Rhs,AliasFreeProduct>& other);\n#endif // EIGEN_PARSED_BY_DOXYGEN\n\n    template<typename OtherDerived>\n    EIGEN_DONT_INLINE SparseMatrix& operator=(const SparseMatrixBase<OtherDerived>& other);\n\n    friend std::ostream & operator << (std::ostream & s, const SparseMatrix& m)\n    {\n      EIGEN_DBG_SPARSE(\n        s << \"Nonzero entries:\\n\";\n        if(m.isCompressed())\n        {\n          for (Index i=0; i<m.nonZeros(); ++i)\n            s << \"(\" << m.m_data.value(i) << \",\" << m.m_data.index(i) << \") \";\n        }\n        else\n        {\n          for (Index i=0; i<m.outerSize(); ++i)\n          {\n            Index p = m.m_outerIndex[i];\n            Index pe = m.m_outerIndex[i]+m.m_innerNonZeros[i];\n            Index k=p;\n            for (; k<pe; ++k) {\n              s << \"(\" << m.m_data.value(k) << \",\" << m.m_data.index(k) << \") \";\n            }\n            for (; k<m.m_outerIndex[i+1]; ++k) {\n              s << \"(_,_) \";\n            }\n          }\n        }\n        s << std::endl;\n        s << std::endl;\n        s << \"Outer pointers:\\n\";\n        for (Index i=0; i<m.outerSize(); ++i) {\n          s << m.m_outerIndex[i] << \" \";\n        }\n        s << \" $\" << std::endl;\n        if(!m.isCompressed())\n        {\n          s << \"Inner non zeros:\\n\";\n          for (Index i=0; i<m.outerSize(); ++i) {\n            s << m.m_innerNonZeros[i] << \" \";\n          }\n          s << \" $\" << std::endl;\n        }\n        s << std::endl;\n      );\n      s << static_cast<const SparseMatrixBase<SparseMatrix>&>(m);\n      return s;\n    }\n\n    /** Destructor */\n    inline ~SparseMatrix()\n    {\n      std::free(m_outerIndex);\n      std::free(m_innerNonZeros);\n    }\n\n    /** Overloaded for performance */\n    Scalar sum() const;\n    \n#   ifdef EIGEN_SPARSEMATRIX_PLUGIN\n#     include EIGEN_SPARSEMATRIX_PLUGIN\n#   endif\n\nprotected:\n\n    template<typename Other>\n    void initAssignment(const Other& other)\n    {\n      resize(other.rows(), other.cols());\n      if(m_innerNonZeros)\n      {\n        std::free(m_innerNonZeros);\n        m_innerNonZeros = 0;\n      }\n    }\n\n    /** \\internal\n      * \\sa insert(Index,Index) */\n    EIGEN_DONT_INLINE Scalar& insertCompressed(Index row, Index col);\n\n    /** \\internal\n      * A vector object that is equal to 0 everywhere but v at the position i */\n    class SingletonVector\n    {\n        StorageIndex m_index;\n        StorageIndex m_value;\n      public:\n        typedef StorageIndex value_type;\n        SingletonVector(Index i, Index v)\n          : m_index(convert_index(i)), m_value(convert_index(v))\n        {}\n\n        StorageIndex operator[](Index i) const { return i==m_index ? m_value : 0; }\n    };\n\n    /** \\internal\n      * \\sa insert(Index,Index) */\n    EIGEN_DONT_INLINE Scalar& insertUncompressed(Index row, Index col);\n\npublic:\n    /** \\internal\n      * \\sa insert(Index,Index) */\n    EIGEN_STRONG_INLINE Scalar& insertBackUncompressed(Index row, Index col)\n    {\n      const Index outer = IsRowMajor ? row : col;\n      const Index inner = IsRowMajor ? col : row;\n\n      eigen_assert(!isCompressed());\n      eigen_assert(m_innerNonZeros[outer]<=(m_outerIndex[outer+1] - m_outerIndex[outer]));\n\n      Index p = m_outerIndex[outer] + m_innerNonZeros[outer]++;\n      m_data.index(p) = convert_index(inner);\n      return (m_data.value(p) = Scalar(0));\n    }\nprotected:\n    struct IndexPosPair {\n      IndexPosPair(Index a_i, Index a_p) : i(a_i), p(a_p) {}\n      Index i;\n      Index p;\n    };\n\n    /** \\internal assign \\a diagXpr to the diagonal of \\c *this\n      * There are different strategies:\n      *   1 - if *this is overwritten (Func==assign_op) or *this is empty, then we can work treat *this as a dense vector expression.\n      *   2 - otherwise, for each diagonal coeff,\n      *     2.a - if it already exists, then we update it,\n      *     2.b - otherwise, if *this is uncompressed and that the current inner-vector has empty room for at least 1 element, then we perform an in-place insertion.\n      *     2.c - otherwise, we'll have to reallocate and copy everything, so instead of doing so for each new element, it is recorded in a std::vector.\n      *   3 - at the end, if some entries failed to be inserted in-place, then we alloc a new buffer, copy each chunk at the right position, and insert the new elements.\n      * \n      * TODO: some piece of code could be isolated and reused for a general in-place update strategy.\n      * TODO: if we start to defer the insertion of some elements (i.e., case 2.c executed once),\n      *       then it *might* be better to disable case 2.b since they will have to be copied anyway.\n      */\n    template<typename DiagXpr, typename Func>\n    void assignDiagonal(const DiagXpr diagXpr, const Func& assignFunc)\n    {\n      Index n = diagXpr.size();\n\n      const bool overwrite = internal::is_same<Func, internal::assign_op<Scalar,Scalar> >::value;\n      if(overwrite)\n      {\n        if((this->rows()!=n) || (this->cols()!=n))\n          this->resize(n, n);\n      }\n\n      if(m_data.size()==0 || overwrite)\n      {\n        typedef Array<StorageIndex,Dynamic,1> ArrayXI;  \n        this->makeCompressed();\n        this->resizeNonZeros(n);\n        Eigen::Map<ArrayXI>(this->innerIndexPtr(), n).setLinSpaced(0,StorageIndex(n)-1);\n        Eigen::Map<ArrayXI>(this->outerIndexPtr(), n+1).setLinSpaced(0,StorageIndex(n));\n        Eigen::Map<Array<Scalar,Dynamic,1> > values = this->coeffs();\n        values.setZero();\n        internal::call_assignment_no_alias(values, diagXpr, assignFunc);\n      }\n      else\n      {\n        bool isComp = isCompressed();\n        internal::evaluator<DiagXpr> diaEval(diagXpr);\n        std::vector<IndexPosPair> newEntries;\n\n        // 1 - try in-place update and record insertion failures\n        for(Index i = 0; i<n; ++i)\n        {\n          internal::LowerBoundIndex lb = this->lower_bound(i,i);\n          Index p = lb.value;\n          if(lb.found)\n          {\n            // the coeff already exists\n            assignFunc.assignCoeff(m_data.value(p), diaEval.coeff(i));\n          }\n          else if((!isComp) && m_innerNonZeros[i] < (m_outerIndex[i+1]-m_outerIndex[i]))\n          {\n            // non compressed mode with local room for inserting one element\n            m_data.moveChunk(p, p+1, m_outerIndex[i]+m_innerNonZeros[i]-p);\n            m_innerNonZeros[i]++;\n            m_data.value(p) = Scalar(0);\n            m_data.index(p) = StorageIndex(i);\n            assignFunc.assignCoeff(m_data.value(p), diaEval.coeff(i));\n          }\n          else\n          {\n            // defer insertion\n            newEntries.push_back(IndexPosPair(i,p));\n          }\n        }\n        // 2 - insert deferred entries\n        Index n_entries = Index(newEntries.size());\n        if(n_entries>0)\n        {\n          Storage newData(m_data.size()+n_entries);\n          Index prev_p = 0;\n          Index prev_i = 0;\n          for(Index k=0; k<n_entries;++k)\n          {\n            Index i = newEntries[k].i;\n            Index p = newEntries[k].p;\n            internal::smart_copy(m_data.valuePtr()+prev_p, m_data.valuePtr()+p, newData.valuePtr()+prev_p+k);\n            internal::smart_copy(m_data.indexPtr()+prev_p, m_data.indexPtr()+p, newData.indexPtr()+prev_p+k);\n            for(Index j=prev_i;j<i;++j)\n              m_outerIndex[j+1] += k;\n            if(!isComp)\n              m_innerNonZeros[i]++;\n            prev_p = p;\n            prev_i = i;\n            newData.value(p+k) = Scalar(0);\n            newData.index(p+k) = StorageIndex(i);\n            assignFunc.assignCoeff(newData.value(p+k), diaEval.coeff(i));\n          }\n          {\n            internal::smart_copy(m_data.valuePtr()+prev_p, m_data.valuePtr()+m_data.size(), newData.valuePtr()+prev_p+n_entries);\n            internal::smart_copy(m_data.indexPtr()+prev_p, m_data.indexPtr()+m_data.size(), newData.indexPtr()+prev_p+n_entries);\n            for(Index j=prev_i+1;j<=m_outerSize;++j)\n              m_outerIndex[j] += n_entries;\n          }\n          m_data.swap(newData);\n        }\n      }\n    }\n\nprivate:\n  static void check_template_parameters()\n  {\n    EIGEN_STATIC_ASSERT(NumTraits<StorageIndex>::IsSigned,THE_INDEX_TYPE_MUST_BE_A_SIGNED_TYPE);\n    EIGEN_STATIC_ASSERT((Options&(ColMajor|RowMajor))==Options,INVALID_MATRIX_TEMPLATE_PARAMETERS);\n  }\n\n  struct default_prunning_func {\n    default_prunning_func(const Scalar& ref, const RealScalar& eps) : reference(ref), epsilon(eps) {}\n    inline bool operator() (const Index&, const Index&, const Scalar& value) const\n    {\n      return !internal::isMuchSmallerThan(value, reference, epsilon);\n    }\n    Scalar reference;\n    RealScalar epsilon;\n  };\n};\n\nnamespace internal {\n\ntemplate<typename InputIterator, typename SparseMatrixType, typename DupFunctor>\nvoid set_from_triplets(const InputIterator& begin, const InputIterator& end, SparseMatrixType& mat, DupFunctor dup_func)\n{\n  enum { IsRowMajor = SparseMatrixType::IsRowMajor };\n  typedef typename SparseMatrixType::Scalar Scalar;\n  typedef typename SparseMatrixType::StorageIndex StorageIndex;\n  SparseMatrix<Scalar,IsRowMajor?ColMajor:RowMajor,StorageIndex> trMat(mat.rows(),mat.cols());\n\n  if(begin!=end)\n  {\n    // pass 1: count the nnz per inner-vector\n    typename SparseMatrixType::IndexVector wi(trMat.outerSize());\n    wi.setZero();\n    for(InputIterator it(begin); it!=end; ++it)\n    {\n      eigen_assert(it->row()>=0 && it->row()<mat.rows() && it->col()>=0 && it->col()<mat.cols());\n      wi(IsRowMajor ? it->col() : it->row())++;\n    }\n\n    // pass 2: insert all the elements into trMat\n    trMat.reserve(wi);\n    for(InputIterator it(begin); it!=end; ++it)\n      trMat.insertBackUncompressed(it->row(),it->col()) = it->value();\n\n    // pass 3:\n    trMat.collapseDuplicates(dup_func);\n  }\n\n  // pass 4: transposed copy -> implicit sorting\n  mat = trMat;\n}\n\n}\n\n\n/** Fill the matrix \\c *this with the list of \\em triplets defined by the iterator range \\a begin - \\a end.\n  *\n  * A \\em triplet is a tuple (i,j,value) defining a non-zero element.\n  * The input list of triplets does not have to be sorted, and can contains duplicated elements.\n  * In any case, the result is a \\b sorted and \\b compressed sparse matrix where the duplicates have been summed up.\n  * This is a \\em O(n) operation, with \\em n the number of triplet elements.\n  * The initial contents of \\c *this is destroyed.\n  * The matrix \\c *this must be properly resized beforehand using the SparseMatrix(Index,Index) constructor,\n  * or the resize(Index,Index) method. The sizes are not extracted from the triplet list.\n  *\n  * The \\a InputIterators value_type must provide the following interface:\n  * \\code\n  * Scalar value() const; // the value\n  * Scalar row() const;   // the row index i\n  * Scalar col() const;   // the column index j\n  * \\endcode\n  * See for instance the Eigen::Triplet template class.\n  *\n  * Here is a typical usage example:\n  * \\code\n    typedef Triplet<double> T;\n    std::vector<T> tripletList;\n    tripletList.reserve(estimation_of_entries);\n    for(...)\n    {\n      // ...\n      tripletList.push_back(T(i,j,v_ij));\n    }\n    SparseMatrixType m(rows,cols);\n    m.setFromTriplets(tripletList.begin(), tripletList.end());\n    // m is ready to go!\n  * \\endcode\n  *\n  * \\warning The list of triplets is read multiple times (at least twice). Therefore, it is not recommended to define\n  * an abstract iterator over a complex data-structure that would be expensive to evaluate. The triplets should rather\n  * be explicitly stored into a std::vector for instance.\n  */\ntemplate<typename Scalar, int Options_, typename StorageIndex_>\ntemplate<typename InputIterators>\nvoid SparseMatrix<Scalar,Options_,StorageIndex_>::setFromTriplets(const InputIterators& begin, const InputIterators& end)\n{\n  internal::set_from_triplets<InputIterators, SparseMatrix<Scalar,Options_,StorageIndex_> >(begin, end, *this, internal::scalar_sum_op<Scalar,Scalar>());\n}\n\n/** The same as setFromTriplets but when duplicates are met the functor \\a dup_func is applied:\n  * \\code\n  * value = dup_func(OldValue, NewValue)\n  * \\endcode \n  * Here is a C++11 example keeping the latest entry only:\n  * \\code\n  * mat.setFromTriplets(triplets.begin(), triplets.end(), [] (const Scalar&,const Scalar &b) { return b; });\n  * \\endcode\n  */\ntemplate<typename Scalar, int Options_, typename StorageIndex_>\ntemplate<typename InputIterators,typename DupFunctor>\nvoid SparseMatrix<Scalar,Options_,StorageIndex_>::setFromTriplets(const InputIterators& begin, const InputIterators& end, DupFunctor dup_func)\n{\n  internal::set_from_triplets<InputIterators, SparseMatrix<Scalar,Options_,StorageIndex_>, DupFunctor>(begin, end, *this, dup_func);\n}\n\n/** \\internal */\ntemplate<typename Scalar, int Options_, typename StorageIndex_>\ntemplate<typename DupFunctor>\nvoid SparseMatrix<Scalar,Options_,StorageIndex_>::collapseDuplicates(DupFunctor dup_func)\n{\n  eigen_assert(!isCompressed());\n  // TODO, in practice we should be able to use m_innerNonZeros for that task\n  IndexVector wi(innerSize());\n  wi.fill(-1);\n  StorageIndex count = 0;\n  // for each inner-vector, wi[inner_index] will hold the position of first element into the index/value buffers\n  for(Index j=0; j<outerSize(); ++j)\n  {\n    StorageIndex start   = count;\n    Index oldEnd  = m_outerIndex[j]+m_innerNonZeros[j];\n    for(Index k=m_outerIndex[j]; k<oldEnd; ++k)\n    {\n      Index i = m_data.index(k);\n      if(wi(i)>=start)\n      {\n        // we already meet this entry => accumulate it\n        m_data.value(wi(i)) = dup_func(m_data.value(wi(i)), m_data.value(k));\n      }\n      else\n      {\n        m_data.value(count) = m_data.value(k);\n        m_data.index(count) = m_data.index(k);\n        wi(i) = count;\n        ++count;\n      }\n    }\n    m_outerIndex[j] = start;\n  }\n  m_outerIndex[m_outerSize] = count;\n\n  // turn the matrix into compressed form\n  std::free(m_innerNonZeros);\n  m_innerNonZeros = 0;\n  m_data.resize(m_outerIndex[m_outerSize]);\n}\n\ntemplate<typename Scalar, int Options_, typename StorageIndex_>\ntemplate<typename OtherDerived>\nEIGEN_DONT_INLINE SparseMatrix<Scalar,Options_,StorageIndex_>& SparseMatrix<Scalar,Options_,StorageIndex_>::operator=(const SparseMatrixBase<OtherDerived>& other)\n{\n  EIGEN_STATIC_ASSERT((internal::is_same<Scalar, typename OtherDerived::Scalar>::value),\n        YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n\n  #ifdef EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n    EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n  #endif\n      \n  const bool needToTranspose = (Flags & RowMajorBit) != (internal::evaluator<OtherDerived>::Flags & RowMajorBit);\n  if (needToTranspose)\n  {\n    #ifdef EIGEN_SPARSE_TRANSPOSED_COPY_PLUGIN\n      EIGEN_SPARSE_TRANSPOSED_COPY_PLUGIN\n    #endif\n    // two passes algorithm:\n    //  1 - compute the number of coeffs per dest inner vector\n    //  2 - do the actual copy/eval\n    // Since each coeff of the rhs has to be evaluated twice, let's evaluate it if needed\n    typedef typename internal::nested_eval<OtherDerived,2,typename internal::plain_matrix_type<OtherDerived>::type >::type OtherCopy;\n    typedef typename internal::remove_all<OtherCopy>::type _OtherCopy;\n    typedef internal::evaluator<_OtherCopy> OtherCopyEval;\n    OtherCopy otherCopy(other.derived());\n    OtherCopyEval otherCopyEval(otherCopy);\n\n    SparseMatrix dest(other.rows(),other.cols());\n    Eigen::Map<IndexVector> (dest.m_outerIndex,dest.outerSize()).setZero();\n\n    // pass 1\n    // FIXME the above copy could be merged with that pass\n    for (Index j=0; j<otherCopy.outerSize(); ++j)\n      for (typename OtherCopyEval::InnerIterator it(otherCopyEval, j); it; ++it)\n        ++dest.m_outerIndex[it.index()];\n\n    // prefix sum\n    StorageIndex count = 0;\n    IndexVector positions(dest.outerSize());\n    for (Index j=0; j<dest.outerSize(); ++j)\n    {\n      StorageIndex tmp = dest.m_outerIndex[j];\n      dest.m_outerIndex[j] = count;\n      positions[j] = count;\n      count += tmp;\n    }\n    dest.m_outerIndex[dest.outerSize()] = count;\n    // alloc\n    dest.m_data.resize(count);\n    // pass 2\n    for (StorageIndex j=0; j<otherCopy.outerSize(); ++j)\n    {\n      for (typename OtherCopyEval::InnerIterator it(otherCopyEval, j); it; ++it)\n      {\n        Index pos = positions[it.index()]++;\n        dest.m_data.index(pos) = j;\n        dest.m_data.value(pos) = it.value();\n      }\n    }\n    this->swap(dest);\n    return *this;\n  }\n  else\n  {\n    if(other.isRValue())\n    {\n      initAssignment(other.derived());\n    }\n    // there is no special optimization\n    return Base::operator=(other.derived());\n  }\n}\n\ntemplate<typename Scalar_, int Options_, typename StorageIndex_>\ntypename SparseMatrix<Scalar_,Options_,StorageIndex_>::Scalar& SparseMatrix<Scalar_,Options_,StorageIndex_>::insert(Index row, Index col)\n{\n  eigen_assert(row>=0 && row<rows() && col>=0 && col<cols());\n  \n  const Index outer = IsRowMajor ? row : col;\n  const Index inner = IsRowMajor ? col : row;\n  \n  if(isCompressed())\n  {\n    if(nonZeros()==0)\n    {\n      // reserve space if not already done\n      if(m_data.allocatedSize()==0)\n        m_data.reserve(2*m_innerSize);\n      \n      // turn the matrix into non-compressed mode\n      m_innerNonZeros = static_cast<StorageIndex*>(std::malloc(m_outerSize * sizeof(StorageIndex)));\n      if(!m_innerNonZeros) internal::throw_std_bad_alloc();\n      \n      std::fill(m_innerNonZeros, m_innerNonZeros + m_outerSize, StorageIndex(0));\n      \n      // pack all inner-vectors to the end of the pre-allocated space\n      // and allocate the entire free-space to the first inner-vector\n      StorageIndex end = convert_index(m_data.allocatedSize());\n      for(Index j=1; j<=m_outerSize; ++j)\n        m_outerIndex[j] = end;\n    }\n    else\n    {\n      // turn the matrix into non-compressed mode\n      m_innerNonZeros = static_cast<StorageIndex*>(std::malloc(m_outerSize * sizeof(StorageIndex)));\n      if(!m_innerNonZeros) internal::throw_std_bad_alloc();\n      for(Index j=0; j<m_outerSize; ++j)\n        m_innerNonZeros[j] = m_outerIndex[j+1]-m_outerIndex[j];\n    }\n  }\n  \n  // check whether we can do a fast \"push back\" insertion\n  Index data_end = m_data.allocatedSize();\n  \n  // First case: we are filling a new inner vector which is packed at the end.\n  // We assume that all remaining inner-vectors are also empty and packed to the end.\n  if(m_outerIndex[outer]==data_end)\n  {\n    eigen_internal_assert(m_innerNonZeros[outer]==0);\n    \n    // pack previous empty inner-vectors to end of the used-space\n    // and allocate the entire free-space to the current inner-vector.\n    StorageIndex p = convert_index(m_data.size());\n    Index j = outer;\n    while(j>=0 && m_innerNonZeros[j]==0)\n      m_outerIndex[j--] = p;\n    \n    // push back the new element\n    ++m_innerNonZeros[outer];\n    m_data.append(Scalar(0), inner);\n    \n    // check for reallocation\n    if(data_end != m_data.allocatedSize())\n    {\n      // m_data has been reallocated\n      //  -> move remaining inner-vectors back to the end of the free-space\n      //     so that the entire free-space is allocated to the current inner-vector.\n      eigen_internal_assert(data_end < m_data.allocatedSize());\n      StorageIndex new_end = convert_index(m_data.allocatedSize());\n      for(Index k=outer+1; k<=m_outerSize; ++k)\n        if(m_outerIndex[k]==data_end)\n          m_outerIndex[k] = new_end;\n    }\n    return m_data.value(p);\n  }\n  \n  // Second case: the next inner-vector is packed to the end\n  // and the current inner-vector end match the used-space.\n  if(m_outerIndex[outer+1]==data_end && m_outerIndex[outer]+m_innerNonZeros[outer]==m_data.size())\n  {\n    eigen_internal_assert(outer+1==m_outerSize || m_innerNonZeros[outer+1]==0);\n    \n    // add space for the new element\n    ++m_innerNonZeros[outer];\n    m_data.resize(m_data.size()+1);\n    \n    // check for reallocation\n    if(data_end != m_data.allocatedSize())\n    {\n      // m_data has been reallocated\n      //  -> move remaining inner-vectors back to the end of the free-space\n      //     so that the entire free-space is allocated to the current inner-vector.\n      eigen_internal_assert(data_end < m_data.allocatedSize());\n      StorageIndex new_end = convert_index(m_data.allocatedSize());\n      for(Index k=outer+1; k<=m_outerSize; ++k)\n        if(m_outerIndex[k]==data_end)\n          m_outerIndex[k] = new_end;\n    }\n    \n    // and insert it at the right position (sorted insertion)\n    Index startId = m_outerIndex[outer];\n    Index p = m_outerIndex[outer]+m_innerNonZeros[outer]-1;\n    while ( (p > startId) && (m_data.index(p-1) > inner) )\n    {\n      m_data.index(p) = m_data.index(p-1);\n      m_data.value(p) = m_data.value(p-1);\n      --p;\n    }\n    \n    m_data.index(p) = convert_index(inner);\n    return (m_data.value(p) = Scalar(0));\n  }\n  \n  if(m_data.size() != m_data.allocatedSize())\n  {\n    // make sure the matrix is compatible to random un-compressed insertion:\n    m_data.resize(m_data.allocatedSize());\n    this->reserveInnerVectors(Array<StorageIndex,Dynamic,1>::Constant(m_outerSize, 2));\n  }\n  \n  return insertUncompressed(row,col);\n}\n    \ntemplate<typename Scalar_, int Options_, typename StorageIndex_>\nEIGEN_DONT_INLINE typename SparseMatrix<Scalar_,Options_,StorageIndex_>::Scalar& SparseMatrix<Scalar_,Options_,StorageIndex_>::insertUncompressed(Index row, Index col)\n{\n  eigen_assert(!isCompressed());\n\n  const Index outer = IsRowMajor ? row : col;\n  const StorageIndex inner = convert_index(IsRowMajor ? col : row);\n\n  Index room = m_outerIndex[outer+1] - m_outerIndex[outer];\n  StorageIndex innerNNZ = m_innerNonZeros[outer];\n  if(innerNNZ>=room)\n  {\n    // this inner vector is full, we need to reallocate the whole buffer :(\n    reserve(SingletonVector(outer,std::max<StorageIndex>(2,innerNNZ)));\n  }\n\n  Index startId = m_outerIndex[outer];\n  Index p = startId + m_innerNonZeros[outer];\n  while ( (p > startId) && (m_data.index(p-1) > inner) )\n  {\n    m_data.index(p) = m_data.index(p-1);\n    m_data.value(p) = m_data.value(p-1);\n    --p;\n  }\n  eigen_assert((p<=startId || m_data.index(p-1)!=inner) && \"you cannot insert an element that already exists, you must call coeffRef to this end\");\n\n  m_innerNonZeros[outer]++;\n\n  m_data.index(p) = inner;\n  return (m_data.value(p) = Scalar(0));\n}\n\ntemplate<typename Scalar_, int Options_, typename StorageIndex_>\nEIGEN_DONT_INLINE typename SparseMatrix<Scalar_,Options_,StorageIndex_>::Scalar& SparseMatrix<Scalar_,Options_,StorageIndex_>::insertCompressed(Index row, Index col)\n{\n  eigen_assert(isCompressed());\n\n  const Index outer = IsRowMajor ? row : col;\n  const Index inner = IsRowMajor ? col : row;\n\n  Index previousOuter = outer;\n  if (m_outerIndex[outer+1]==0)\n  {\n    // we start a new inner vector\n    while (previousOuter>=0 && m_outerIndex[previousOuter]==0)\n    {\n      m_outerIndex[previousOuter] = convert_index(m_data.size());\n      --previousOuter;\n    }\n    m_outerIndex[outer+1] = m_outerIndex[outer];\n  }\n\n  // here we have to handle the tricky case where the outerIndex array\n  // starts with: [ 0 0 0 0 0 1 ...] and we are inserted in, e.g.,\n  // the 2nd inner vector...\n  bool isLastVec = (!(previousOuter==-1 && m_data.size()!=0))\n                && (std::size_t(m_outerIndex[outer+1]) == m_data.size());\n\n  std::size_t startId = m_outerIndex[outer];\n  // FIXME let's make sure sizeof(long int) == sizeof(std::size_t)\n  std::size_t p = m_outerIndex[outer+1];\n  ++m_outerIndex[outer+1];\n\n  double reallocRatio = 1;\n  if (m_data.allocatedSize()<=m_data.size())\n  {\n    // if there is no preallocated memory, let's reserve a minimum of 32 elements\n    if (m_data.size()==0)\n    {\n      m_data.reserve(32);\n    }\n    else\n    {\n      // we need to reallocate the data, to reduce multiple reallocations\n      // we use a smart resize algorithm based on the current filling ratio\n      // in addition, we use double to avoid integers overflows\n      double nnzEstimate = double(m_outerIndex[outer])*double(m_outerSize)/double(outer+1);\n      reallocRatio = (nnzEstimate-double(m_data.size()))/double(m_data.size());\n      // furthermore we bound the realloc ratio to:\n      //   1) reduce multiple minor realloc when the matrix is almost filled\n      //   2) avoid to allocate too much memory when the matrix is almost empty\n      reallocRatio = (std::min)((std::max)(reallocRatio,1.5),8.);\n    }\n  }\n  m_data.resize(m_data.size()+1,reallocRatio);\n\n  if (!isLastVec)\n  {\n    if (previousOuter==-1)\n    {\n      // oops wrong guess.\n      // let's correct the outer offsets\n      for (Index k=0; k<=(outer+1); ++k)\n        m_outerIndex[k] = 0;\n      Index k=outer+1;\n      while(m_outerIndex[k]==0)\n        m_outerIndex[k++] = 1;\n      while (k<=m_outerSize && m_outerIndex[k]!=0)\n        m_outerIndex[k++]++;\n      p = 0;\n      --k;\n      k = m_outerIndex[k]-1;\n      while (k>0)\n      {\n        m_data.index(k) = m_data.index(k-1);\n        m_data.value(k) = m_data.value(k-1);\n        k--;\n      }\n    }\n    else\n    {\n      // we are not inserting into the last inner vec\n      // update outer indices:\n      Index j = outer+2;\n      while (j<=m_outerSize && m_outerIndex[j]!=0)\n        m_outerIndex[j++]++;\n      --j;\n      // shift data of last vecs:\n      Index k = m_outerIndex[j]-1;\n      while (k>=Index(p))\n      {\n        m_data.index(k) = m_data.index(k-1);\n        m_data.value(k) = m_data.value(k-1);\n        k--;\n      }\n    }\n  }\n\n  while ( (p > startId) && (m_data.index(p-1) > inner) )\n  {\n    m_data.index(p) = m_data.index(p-1);\n    m_data.value(p) = m_data.value(p-1);\n    --p;\n  }\n\n  m_data.index(p) = inner;\n  return (m_data.value(p) = Scalar(0));\n}\n\nnamespace internal {\n\ntemplate<typename Scalar_, int Options_, typename StorageIndex_>\nstruct evaluator<SparseMatrix<Scalar_,Options_,StorageIndex_> >\n  : evaluator<SparseCompressedBase<SparseMatrix<Scalar_,Options_,StorageIndex_> > >\n{\n  typedef evaluator<SparseCompressedBase<SparseMatrix<Scalar_,Options_,StorageIndex_> > > Base;\n  typedef SparseMatrix<Scalar_,Options_,StorageIndex_> SparseMatrixType;\n  evaluator() : Base() {}\n  explicit evaluator(const SparseMatrixType &mat) : Base(mat) {}\n};\n\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSEMATRIX_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseMatrixBase.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEMATRIXBASE_H\n#define EIGEN_SPARSEMATRIXBASE_H\n\nnamespace Eigen { \n\n/** \\ingroup SparseCore_Module\n  *\n  * \\class SparseMatrixBase\n  *\n  * \\brief Base class of any sparse matrices or sparse expressions\n  *\n  * \\tparam Derived is the derived type, e.g. a sparse matrix type, or an expression, etc.\n  *\n  * This class can be extended with the help of the plugin mechanism described on the page\n  * \\ref TopicCustomizing_Plugins by defining the preprocessor symbol \\c EIGEN_SPARSEMATRIXBASE_PLUGIN.\n  */\ntemplate<typename Derived> class SparseMatrixBase\n  : public EigenBase<Derived>\n{\n  public:\n\n    typedef typename internal::traits<Derived>::Scalar Scalar;\n    \n    /** The numeric type of the expression' coefficients, e.g. float, double, int or std::complex<float>, etc.\n      *\n      * It is an alias for the Scalar type */\n    typedef Scalar value_type;\n    \n    typedef typename internal::packet_traits<Scalar>::type PacketScalar;\n    typedef typename internal::traits<Derived>::StorageKind StorageKind;\n\n    /** The integer type used to \\b store indices within a SparseMatrix.\n      * For a \\c SparseMatrix<Scalar,Options,IndexType> it an alias of the third template parameter \\c IndexType. */\n    typedef typename internal::traits<Derived>::StorageIndex StorageIndex;\n\n    typedef typename internal::add_const_on_value_type_if_arithmetic<\n                         typename internal::packet_traits<Scalar>::type\n                     >::type PacketReturnType;\n\n    typedef SparseMatrixBase StorageBaseType;\n\n    typedef Matrix<StorageIndex,Dynamic,1> IndexVector;\n    typedef Matrix<Scalar,Dynamic,1> ScalarVector;\n    \n    template<typename OtherDerived>\n    Derived& operator=(const EigenBase<OtherDerived> &other);\n\n    enum {\n\n      RowsAtCompileTime = internal::traits<Derived>::RowsAtCompileTime,\n        /**< The number of rows at compile-time. This is just a copy of the value provided\n          * by the \\a Derived type. If a value is not known at compile-time,\n          * it is set to the \\a Dynamic constant.\n          * \\sa MatrixBase::rows(), MatrixBase::cols(), ColsAtCompileTime, SizeAtCompileTime */\n\n      ColsAtCompileTime = internal::traits<Derived>::ColsAtCompileTime,\n        /**< The number of columns at compile-time. This is just a copy of the value provided\n          * by the \\a Derived type. If a value is not known at compile-time,\n          * it is set to the \\a Dynamic constant.\n          * \\sa MatrixBase::rows(), MatrixBase::cols(), RowsAtCompileTime, SizeAtCompileTime */\n\n\n      SizeAtCompileTime = (internal::size_at_compile_time<internal::traits<Derived>::RowsAtCompileTime,\n                                                   internal::traits<Derived>::ColsAtCompileTime>::ret),\n        /**< This is equal to the number of coefficients, i.e. the number of\n          * rows times the number of columns, or to \\a Dynamic if this is not\n          * known at compile-time. \\sa RowsAtCompileTime, ColsAtCompileTime */\n\n      MaxRowsAtCompileTime = RowsAtCompileTime,\n      MaxColsAtCompileTime = ColsAtCompileTime,\n\n      MaxSizeAtCompileTime = (internal::size_at_compile_time<MaxRowsAtCompileTime,\n                                                      MaxColsAtCompileTime>::ret),\n\n      IsVectorAtCompileTime = RowsAtCompileTime == 1 || ColsAtCompileTime == 1,\n        /**< This is set to true if either the number of rows or the number of\n          * columns is known at compile-time to be equal to 1. Indeed, in that case,\n          * we are dealing with a column-vector (if there is only one column) or with\n          * a row-vector (if there is only one row). */\n\n      NumDimensions = int(MaxSizeAtCompileTime) == 1 ? 0 : bool(IsVectorAtCompileTime) ? 1 : 2,\n        /**< This value is equal to Tensor::NumDimensions, i.e. 0 for scalars, 1 for vectors,\n         * and 2 for matrices.\n         */\n\n      Flags = internal::traits<Derived>::Flags,\n        /**< This stores expression \\ref flags flags which may or may not be inherited by new expressions\n          * constructed from this one. See the \\ref flags \"list of flags\".\n          */\n\n      IsRowMajor = Flags&RowMajorBit ? 1 : 0,\n      \n      InnerSizeAtCompileTime = int(IsVectorAtCompileTime) ? int(SizeAtCompileTime)\n                             : int(IsRowMajor) ? int(ColsAtCompileTime) : int(RowsAtCompileTime),\n\n      #ifndef EIGEN_PARSED_BY_DOXYGEN\n      _HasDirectAccess = (int(Flags)&DirectAccessBit) ? 1 : 0 // workaround sunCC\n      #endif\n    };\n\n    /** \\internal the return type of MatrixBase::adjoint() */\n    typedef typename internal::conditional<NumTraits<Scalar>::IsComplex,\n                        CwiseUnaryOp<internal::scalar_conjugate_op<Scalar>, Eigen::Transpose<const Derived> >,\n                        Transpose<const Derived>\n                     >::type AdjointReturnType;\n    typedef Transpose<Derived> TransposeReturnType;\n    typedef typename internal::add_const<Transpose<const Derived> >::type ConstTransposeReturnType;\n\n    // FIXME storage order do not match evaluator storage order\n    typedef SparseMatrix<Scalar, Flags&RowMajorBit ? RowMajor : ColMajor, StorageIndex> PlainObject;\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n    /** This is the \"real scalar\" type; if the \\a Scalar type is already real numbers\n      * (e.g. int, float or double) then \\a RealScalar is just the same as \\a Scalar. If\n      * \\a Scalar is \\a std::complex<T> then RealScalar is \\a T.\n      *\n      * \\sa class NumTraits\n      */\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n\n    /** \\internal the return type of coeff()\n      */\n    typedef typename internal::conditional<_HasDirectAccess, const Scalar&, Scalar>::type CoeffReturnType;\n\n    /** \\internal Represents a matrix with all coefficients equal to one another*/\n    typedef CwiseNullaryOp<internal::scalar_constant_op<Scalar>,Matrix<Scalar,Dynamic,Dynamic> > ConstantReturnType;\n\n    /** type of the equivalent dense matrix */\n    typedef Matrix<Scalar,RowsAtCompileTime,ColsAtCompileTime> DenseMatrixType;\n    /** type of the equivalent square matrix */\n    typedef Matrix<Scalar,EIGEN_SIZE_MAX(RowsAtCompileTime,ColsAtCompileTime),\n                          EIGEN_SIZE_MAX(RowsAtCompileTime,ColsAtCompileTime)> SquareMatrixType;\n\n    inline const Derived& derived() const { return *static_cast<const Derived*>(this); }\n    inline Derived& derived() { return *static_cast<Derived*>(this); }\n    inline Derived& const_cast_derived() const\n    { return *static_cast<Derived*>(const_cast<SparseMatrixBase*>(this)); }\n\n    typedef EigenBase<Derived> Base;\n\n#endif // not EIGEN_PARSED_BY_DOXYGEN\n\n#define EIGEN_CURRENT_STORAGE_BASE_CLASS Eigen::SparseMatrixBase\n#ifdef EIGEN_PARSED_BY_DOXYGEN\n#define EIGEN_DOC_UNARY_ADDONS(METHOD,OP)           /** <p>This method does not change the sparsity of \\c *this: the OP is applied to explicitly stored coefficients only. \\sa SparseCompressedBase::coeffs() </p> */\n#define EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL      /** <p> \\warning This method returns a read-only expression for any sparse matrices. \\sa \\ref TutorialSparse_SubMatrices \"Sparse block operations\" </p> */\n#define EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(COND) /** <p> \\warning This method returns a read-write expression for COND sparse matrices only. Otherwise, the returned expression is read-only. \\sa \\ref TutorialSparse_SubMatrices \"Sparse block operations\" </p> */\n#else\n#define EIGEN_DOC_UNARY_ADDONS(X,Y)\n#define EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n#define EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(COND)\n#endif\n#   include \"../plugins/CommonCwiseUnaryOps.h\"\n#   include \"../plugins/CommonCwiseBinaryOps.h\"\n#   include \"../plugins/MatrixCwiseUnaryOps.h\"\n#   include \"../plugins/MatrixCwiseBinaryOps.h\"\n#   include \"../plugins/BlockMethods.h\"\n#   ifdef EIGEN_SPARSEMATRIXBASE_PLUGIN\n#     include EIGEN_SPARSEMATRIXBASE_PLUGIN\n#   endif\n#undef EIGEN_CURRENT_STORAGE_BASE_CLASS\n#undef EIGEN_DOC_UNARY_ADDONS\n#undef EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n#undef EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF\n\n    /** \\returns the number of rows. \\sa cols() */\n    inline Index rows() const { return derived().rows(); }\n    /** \\returns the number of columns. \\sa rows() */\n    inline Index cols() const { return derived().cols(); }\n    /** \\returns the number of coefficients, which is \\a rows()*cols().\n      * \\sa rows(), cols(). */\n    inline Index size() const { return rows() * cols(); }\n    /** \\returns true if either the number of rows or the number of columns is equal to 1.\n      * In other words, this function returns\n      * \\code rows()==1 || cols()==1 \\endcode\n      * \\sa rows(), cols(), IsVectorAtCompileTime. */\n    inline bool isVector() const { return rows()==1 || cols()==1; }\n    /** \\returns the size of the storage major dimension,\n      * i.e., the number of columns for a columns major matrix, and the number of rows otherwise */\n    Index outerSize() const { return (int(Flags)&RowMajorBit) ? this->rows() : this->cols(); }\n    /** \\returns the size of the inner dimension according to the storage order,\n      * i.e., the number of rows for a columns major matrix, and the number of cols otherwise */\n    Index innerSize() const { return (int(Flags)&RowMajorBit) ? this->cols() : this->rows(); }\n\n    bool isRValue() const { return m_isRValue; }\n    Derived& markAsRValue() { m_isRValue = true; return derived(); }\n\n    SparseMatrixBase() : m_isRValue(false) { /* TODO check flags */ }\n\n    \n    template<typename OtherDerived>\n    Derived& operator=(const ReturnByValue<OtherDerived>& other);\n\n    template<typename OtherDerived>\n    inline Derived& operator=(const SparseMatrixBase<OtherDerived>& other);\n\n    inline Derived& operator=(const Derived& other);\n\n  protected:\n\n    template<typename OtherDerived>\n    inline Derived& assign(const OtherDerived& other);\n\n    template<typename OtherDerived>\n    inline void assignGeneric(const OtherDerived& other);\n\n  public:\n\n    friend std::ostream & operator << (std::ostream & s, const SparseMatrixBase& m)\n    {\n      typedef typename Derived::Nested Nested;\n      typedef typename internal::remove_all<Nested>::type NestedCleaned;\n\n      if (Flags&RowMajorBit)\n      {\n        Nested nm(m.derived());\n        internal::evaluator<NestedCleaned> thisEval(nm);\n        for (Index row=0; row<nm.outerSize(); ++row)\n        {\n          Index col = 0;\n          for (typename internal::evaluator<NestedCleaned>::InnerIterator it(thisEval, row); it; ++it)\n          {\n            for ( ; col<it.index(); ++col)\n              s << \"0 \";\n            s << it.value() << \" \";\n            ++col;\n          }\n          for ( ; col<m.cols(); ++col)\n            s << \"0 \";\n          s << std::endl;\n        }\n      }\n      else\n      {\n        Nested nm(m.derived());\n        internal::evaluator<NestedCleaned> thisEval(nm);\n        if (m.cols() == 1) {\n          Index row = 0;\n          for (typename internal::evaluator<NestedCleaned>::InnerIterator it(thisEval, 0); it; ++it)\n          {\n            for ( ; row<it.index(); ++row)\n              s << \"0\" << std::endl;\n            s << it.value() << std::endl;\n            ++row;\n          }\n          for ( ; row<m.rows(); ++row)\n            s << \"0\" << std::endl;\n        }\n        else\n        {\n          SparseMatrix<Scalar, RowMajorBit, StorageIndex> trans = m;\n          s << static_cast<const SparseMatrixBase<SparseMatrix<Scalar, RowMajorBit, StorageIndex> >&>(trans);\n        }\n      }\n      return s;\n    }\n\n    template<typename OtherDerived>\n    Derived& operator+=(const SparseMatrixBase<OtherDerived>& other);\n    template<typename OtherDerived>\n    Derived& operator-=(const SparseMatrixBase<OtherDerived>& other);\n    \n    template<typename OtherDerived>\n    Derived& operator+=(const DiagonalBase<OtherDerived>& other);\n    template<typename OtherDerived>\n    Derived& operator-=(const DiagonalBase<OtherDerived>& other);\n\n    template<typename OtherDerived>\n    Derived& operator+=(const EigenBase<OtherDerived> &other);\n    template<typename OtherDerived>\n    Derived& operator-=(const EigenBase<OtherDerived> &other);\n\n    Derived& operator*=(const Scalar& other);\n    Derived& operator/=(const Scalar& other);\n\n    template<typename OtherDerived> struct CwiseProductDenseReturnType {\n      typedef CwiseBinaryOp<internal::scalar_product_op<typename ScalarBinaryOpTraits<\n                                                          typename internal::traits<Derived>::Scalar,\n                                                          typename internal::traits<OtherDerived>::Scalar\n                                                        >::ReturnType>,\n                            const Derived,\n                            const OtherDerived\n                          > Type;\n    };\n\n    template<typename OtherDerived>\n    EIGEN_STRONG_INLINE const typename CwiseProductDenseReturnType<OtherDerived>::Type\n    cwiseProduct(const MatrixBase<OtherDerived> &other) const;\n\n    // sparse * diagonal\n    template<typename OtherDerived>\n    const Product<Derived,OtherDerived>\n    operator*(const DiagonalBase<OtherDerived> &other) const\n    { return Product<Derived,OtherDerived>(derived(), other.derived()); }\n\n    // diagonal * sparse\n    template<typename OtherDerived> friend\n    const Product<OtherDerived,Derived>\n    operator*(const DiagonalBase<OtherDerived> &lhs, const SparseMatrixBase& rhs)\n    { return Product<OtherDerived,Derived>(lhs.derived(), rhs.derived()); }\n    \n    // sparse * sparse\n    template<typename OtherDerived>\n    const Product<Derived,OtherDerived,AliasFreeProduct>\n    operator*(const SparseMatrixBase<OtherDerived> &other) const;\n    \n    // sparse * dense\n    template<typename OtherDerived>\n    const Product<Derived,OtherDerived>\n    operator*(const MatrixBase<OtherDerived> &other) const\n    { return Product<Derived,OtherDerived>(derived(), other.derived()); }\n    \n    // dense * sparse\n    template<typename OtherDerived> friend\n    const Product<OtherDerived,Derived>\n    operator*(const MatrixBase<OtherDerived> &lhs, const SparseMatrixBase& rhs)\n    { return Product<OtherDerived,Derived>(lhs.derived(), rhs.derived()); }\n    \n     /** \\returns an expression of P H P^-1 where H is the matrix represented by \\c *this */\n    SparseSymmetricPermutationProduct<Derived,Upper|Lower> twistedBy(const PermutationMatrix<Dynamic,Dynamic,StorageIndex>& perm) const\n    {\n      return SparseSymmetricPermutationProduct<Derived,Upper|Lower>(derived(), perm);\n    }\n\n    template<typename OtherDerived>\n    Derived& operator*=(const SparseMatrixBase<OtherDerived>& other);\n\n    template<int Mode>\n    inline const TriangularView<const Derived, Mode> triangularView() const;\n    \n    template<unsigned int UpLo> struct SelfAdjointViewReturnType { typedef SparseSelfAdjointView<Derived, UpLo> Type; };\n    template<unsigned int UpLo> struct ConstSelfAdjointViewReturnType { typedef const SparseSelfAdjointView<const Derived, UpLo> Type; };\n\n    template<unsigned int UpLo> inline \n    typename ConstSelfAdjointViewReturnType<UpLo>::Type selfadjointView() const;\n    template<unsigned int UpLo> inline\n    typename SelfAdjointViewReturnType<UpLo>::Type selfadjointView();\n\n    template<typename OtherDerived> Scalar dot(const MatrixBase<OtherDerived>& other) const;\n    template<typename OtherDerived> Scalar dot(const SparseMatrixBase<OtherDerived>& other) const;\n    RealScalar squaredNorm() const;\n    RealScalar norm()  const;\n    RealScalar blueNorm() const;\n\n    TransposeReturnType transpose() { return TransposeReturnType(derived()); }\n    const ConstTransposeReturnType transpose() const { return ConstTransposeReturnType(derived()); }\n    const AdjointReturnType adjoint() const { return AdjointReturnType(transpose()); }\n\n    DenseMatrixType toDense() const\n    {\n      return DenseMatrixType(derived());\n    }\n\n    template<typename OtherDerived>\n    bool isApprox(const SparseMatrixBase<OtherDerived>& other,\n                  const RealScalar& prec = NumTraits<Scalar>::dummy_precision()) const;\n\n    template<typename OtherDerived>\n    bool isApprox(const MatrixBase<OtherDerived>& other,\n                  const RealScalar& prec = NumTraits<Scalar>::dummy_precision()) const\n    { return toDense().isApprox(other,prec); }\n\n    /** \\returns the matrix or vector obtained by evaluating this expression.\n      *\n      * Notice that in the case of a plain matrix or vector (not an expression) this function just returns\n      * a const reference, in order to avoid a useless copy.\n      */\n    inline const typename internal::eval<Derived>::type eval() const\n    { return typename internal::eval<Derived>::type(derived()); }\n\n    Scalar sum() const;\n    \n    inline const SparseView<Derived>\n    pruned(const Scalar& reference = Scalar(0), const RealScalar& epsilon = NumTraits<Scalar>::dummy_precision()) const;\n\n  protected:\n\n    bool m_isRValue;\n\n    static inline StorageIndex convert_index(const Index idx) {\n      return internal::convert_index<StorageIndex>(idx);\n    }\n  private:\n    template<typename Dest> void evalTo(Dest &) const;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSEMATRIXBASE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparsePermutation.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_PERMUTATION_H\n#define EIGEN_SPARSE_PERMUTATION_H\n\n// This file implements sparse * permutation products\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate<typename ExpressionType, int Side, bool Transposed>\nstruct permutation_matrix_product<ExpressionType, Side, Transposed, SparseShape>\n{\n    typedef typename nested_eval<ExpressionType, 1>::type MatrixType;\n    typedef typename remove_all<MatrixType>::type MatrixTypeCleaned;\n\n    typedef typename MatrixTypeCleaned::Scalar Scalar;\n    typedef typename MatrixTypeCleaned::StorageIndex StorageIndex;\n\n    enum {\n      SrcStorageOrder = MatrixTypeCleaned::Flags&RowMajorBit ? RowMajor : ColMajor,\n      MoveOuter = SrcStorageOrder==RowMajor ? Side==OnTheLeft : Side==OnTheRight\n    };\n    \n    typedef typename internal::conditional<MoveOuter,\n        SparseMatrix<Scalar,SrcStorageOrder,StorageIndex>,\n        SparseMatrix<Scalar,int(SrcStorageOrder)==RowMajor?ColMajor:RowMajor,StorageIndex> >::type ReturnType;\n\n    template<typename Dest,typename PermutationType>\n    static inline void run(Dest& dst, const PermutationType& perm, const ExpressionType& xpr)\n    {\n      MatrixType mat(xpr);\n      if(MoveOuter)\n      {\n        SparseMatrix<Scalar,SrcStorageOrder,StorageIndex> tmp(mat.rows(), mat.cols());\n        Matrix<StorageIndex,Dynamic,1> sizes(mat.outerSize());\n        for(Index j=0; j<mat.outerSize(); ++j)\n        {\n          Index jp = perm.indices().coeff(j);\n          sizes[((Side==OnTheLeft) ^ Transposed) ? jp : j] = StorageIndex(mat.innerVector(((Side==OnTheRight) ^ Transposed) ? jp : j).nonZeros());\n        }\n        tmp.reserve(sizes);\n        for(Index j=0; j<mat.outerSize(); ++j)\n        {\n          Index jp = perm.indices().coeff(j);\n          Index jsrc = ((Side==OnTheRight) ^ Transposed) ? jp : j;\n          Index jdst = ((Side==OnTheLeft) ^ Transposed) ? jp : j;\n          for(typename MatrixTypeCleaned::InnerIterator it(mat,jsrc); it; ++it)\n            tmp.insertByOuterInner(jdst,it.index()) = it.value();\n        }\n        dst = tmp;\n      }\n      else\n      {\n        SparseMatrix<Scalar,int(SrcStorageOrder)==RowMajor?ColMajor:RowMajor,StorageIndex> tmp(mat.rows(), mat.cols());\n        Matrix<StorageIndex,Dynamic,1> sizes(tmp.outerSize());\n        sizes.setZero();\n        PermutationMatrix<Dynamic,Dynamic,StorageIndex> perm_cpy;\n        if((Side==OnTheLeft) ^ Transposed)\n          perm_cpy = perm;\n        else\n          perm_cpy = perm.transpose();\n\n        for(Index j=0; j<mat.outerSize(); ++j)\n          for(typename MatrixTypeCleaned::InnerIterator it(mat,j); it; ++it)\n            sizes[perm_cpy.indices().coeff(it.index())]++;\n        tmp.reserve(sizes);\n        for(Index j=0; j<mat.outerSize(); ++j)\n          for(typename MatrixTypeCleaned::InnerIterator it(mat,j); it; ++it)\n            tmp.insertByOuterInner(perm_cpy.indices().coeff(it.index()),j) = it.value();\n        dst = tmp;\n      }\n    }\n};\n\n}\n\nnamespace internal {\n\ntemplate <int ProductTag> struct product_promote_storage_type<Sparse,             PermutationStorage, ProductTag> { typedef Sparse ret; };\ntemplate <int ProductTag> struct product_promote_storage_type<PermutationStorage, Sparse,             ProductTag> { typedef Sparse ret; };\n\n// TODO, the following two overloads are only needed to define the right temporary type through \n// typename traits<permutation_sparse_matrix_product<Rhs,Lhs,OnTheRight,false> >::ReturnType\n// whereas it should be correctly handled by traits<Product<> >::PlainObject\n\ntemplate<typename Lhs, typename Rhs, int ProductTag>\nstruct product_evaluator<Product<Lhs, Rhs, AliasFreeProduct>, ProductTag, PermutationShape, SparseShape>\n  : public evaluator<typename permutation_matrix_product<Rhs,OnTheLeft,false,SparseShape>::ReturnType>\n{\n  typedef Product<Lhs, Rhs, AliasFreeProduct> XprType;\n  typedef typename permutation_matrix_product<Rhs,OnTheLeft,false,SparseShape>::ReturnType PlainObject;\n  typedef evaluator<PlainObject> Base;\n\n  enum {\n    Flags = Base::Flags | EvalBeforeNestingBit\n  };\n\n  explicit product_evaluator(const XprType& xpr)\n    : m_result(xpr.rows(), xpr.cols())\n  {\n    ::new (static_cast<Base*>(this)) Base(m_result);\n    generic_product_impl<Lhs, Rhs, PermutationShape, SparseShape, ProductTag>::evalTo(m_result, xpr.lhs(), xpr.rhs());\n  }\n\nprotected:\n  PlainObject m_result;\n};\n\ntemplate<typename Lhs, typename Rhs, int ProductTag>\nstruct product_evaluator<Product<Lhs, Rhs, AliasFreeProduct>, ProductTag, SparseShape, PermutationShape >\n  : public evaluator<typename permutation_matrix_product<Lhs,OnTheRight,false,SparseShape>::ReturnType>\n{\n  typedef Product<Lhs, Rhs, AliasFreeProduct> XprType;\n  typedef typename permutation_matrix_product<Lhs,OnTheRight,false,SparseShape>::ReturnType PlainObject;\n  typedef evaluator<PlainObject> Base;\n\n  enum {\n    Flags = Base::Flags | EvalBeforeNestingBit\n  };\n\n  explicit product_evaluator(const XprType& xpr)\n    : m_result(xpr.rows(), xpr.cols())\n  {\n    ::new (static_cast<Base*>(this)) Base(m_result);\n    generic_product_impl<Lhs, Rhs, SparseShape, PermutationShape, ProductTag>::evalTo(m_result, xpr.lhs(), xpr.rhs());\n  }\n\nprotected:\n  PlainObject m_result;\n};\n\n} // end namespace internal\n\n/** \\returns the matrix with the permutation applied to the columns\n  */\ntemplate<typename SparseDerived, typename PermDerived>\ninline const Product<SparseDerived, PermDerived, AliasFreeProduct>\noperator*(const SparseMatrixBase<SparseDerived>& matrix, const PermutationBase<PermDerived>& perm)\n{ return Product<SparseDerived, PermDerived, AliasFreeProduct>(matrix.derived(), perm.derived()); }\n\n/** \\returns the matrix with the permutation applied to the rows\n  */\ntemplate<typename SparseDerived, typename PermDerived>\ninline const Product<PermDerived, SparseDerived, AliasFreeProduct>\noperator*( const PermutationBase<PermDerived>& perm, const SparseMatrixBase<SparseDerived>& matrix)\n{ return  Product<PermDerived, SparseDerived, AliasFreeProduct>(perm.derived(), matrix.derived()); }\n\n\n/** \\returns the matrix with the inverse permutation applied to the columns.\n  */\ntemplate<typename SparseDerived, typename PermutationType>\ninline const Product<SparseDerived, Inverse<PermutationType>, AliasFreeProduct>\noperator*(const SparseMatrixBase<SparseDerived>& matrix, const InverseImpl<PermutationType, PermutationStorage>& tperm)\n{\n  return Product<SparseDerived, Inverse<PermutationType>, AliasFreeProduct>(matrix.derived(), tperm.derived());\n}\n\n/** \\returns the matrix with the inverse permutation applied to the rows.\n  */\ntemplate<typename SparseDerived, typename PermutationType>\ninline const Product<Inverse<PermutationType>, SparseDerived, AliasFreeProduct>\noperator*(const InverseImpl<PermutationType,PermutationStorage>& tperm, const SparseMatrixBase<SparseDerived>& matrix)\n{\n  return Product<Inverse<PermutationType>, SparseDerived, AliasFreeProduct>(tperm.derived(), matrix.derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_SELFADJOINTVIEW_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseProduct.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEPRODUCT_H\n#define EIGEN_SPARSEPRODUCT_H\n\nnamespace Eigen { \n\n/** \\returns an expression of the product of two sparse matrices.\n  * By default a conservative product preserving the symbolic non zeros is performed.\n  * The automatic pruning of the small values can be achieved by calling the pruned() function\n  * in which case a totally different product algorithm is employed:\n  * \\code\n  * C = (A*B).pruned();             // suppress numerical zeros (exact)\n  * C = (A*B).pruned(ref);\n  * C = (A*B).pruned(ref,epsilon);\n  * \\endcode\n  * where \\c ref is a meaningful non zero reference value.\n  * */\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\ninline const Product<Derived,OtherDerived,AliasFreeProduct>\nSparseMatrixBase<Derived>::operator*(const SparseMatrixBase<OtherDerived> &other) const\n{\n  return Product<Derived,OtherDerived,AliasFreeProduct>(derived(), other.derived());\n}\n\nnamespace internal {\n\n// sparse * sparse\ntemplate<typename Lhs, typename Rhs, int ProductType>\nstruct generic_product_impl<Lhs, Rhs, SparseShape, SparseShape, ProductType>\n{\n  template<typename Dest>\n  static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs)\n  {\n    evalTo(dst, lhs, rhs, typename evaluator_traits<Dest>::Shape());\n  }\n\n  // dense += sparse * sparse\n  template<typename Dest,typename ActualLhs>\n  static void addTo(Dest& dst, const ActualLhs& lhs, const Rhs& rhs, typename enable_if<is_same<typename evaluator_traits<Dest>::Shape,DenseShape>::value,int*>::type* = 0)\n  {\n    typedef typename nested_eval<ActualLhs,Dynamic>::type LhsNested;\n    typedef typename nested_eval<Rhs,Dynamic>::type RhsNested;\n    LhsNested lhsNested(lhs);\n    RhsNested rhsNested(rhs);\n    internal::sparse_sparse_to_dense_product_selector<typename remove_all<LhsNested>::type,\n                                                      typename remove_all<RhsNested>::type, Dest>::run(lhsNested,rhsNested,dst);\n  }\n\n  // dense -= sparse * sparse\n  template<typename Dest>\n  static void subTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, typename enable_if<is_same<typename evaluator_traits<Dest>::Shape,DenseShape>::value,int*>::type* = 0)\n  {\n    addTo(dst, -lhs, rhs);\n  }\n\nprotected:\n\n  // sparse = sparse * sparse\n  template<typename Dest>\n  static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, SparseShape)\n  {\n    typedef typename nested_eval<Lhs,Dynamic>::type LhsNested;\n    typedef typename nested_eval<Rhs,Dynamic>::type RhsNested;\n    LhsNested lhsNested(lhs);\n    RhsNested rhsNested(rhs);\n    internal::conservative_sparse_sparse_product_selector<typename remove_all<LhsNested>::type,\n                                                          typename remove_all<RhsNested>::type, Dest>::run(lhsNested,rhsNested,dst);\n  }\n\n  // dense = sparse * sparse\n  template<typename Dest>\n  static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, DenseShape)\n  {\n    dst.setZero();\n    addTo(dst, lhs, rhs);\n  }\n};\n\n// sparse * sparse-triangular\ntemplate<typename Lhs, typename Rhs, int ProductType>\nstruct generic_product_impl<Lhs, Rhs, SparseShape, SparseTriangularShape, ProductType>\n : public generic_product_impl<Lhs, Rhs, SparseShape, SparseShape, ProductType>\n{};\n\n// sparse-triangular * sparse\ntemplate<typename Lhs, typename Rhs, int ProductType>\nstruct generic_product_impl<Lhs, Rhs, SparseTriangularShape, SparseShape, ProductType>\n : public generic_product_impl<Lhs, Rhs, SparseShape, SparseShape, ProductType>\n{};\n\n// dense = sparse-product (can be sparse*sparse, sparse*perm, etc.)\ntemplate< typename DstXprType, typename Lhs, typename Rhs>\nstruct Assignment<DstXprType, Product<Lhs,Rhs,AliasFreeProduct>, internal::assign_op<typename DstXprType::Scalar,typename Product<Lhs,Rhs,AliasFreeProduct>::Scalar>, Sparse2Dense>\n{\n  typedef Product<Lhs,Rhs,AliasFreeProduct> SrcXprType;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &)\n  {\n    Index dstRows = src.rows();\n    Index dstCols = src.cols();\n    if((dst.rows()!=dstRows) || (dst.cols()!=dstCols))\n      dst.resize(dstRows, dstCols);\n    \n    generic_product_impl<Lhs, Rhs>::evalTo(dst,src.lhs(),src.rhs());\n  }\n};\n\n// dense += sparse-product (can be sparse*sparse, sparse*perm, etc.)\ntemplate< typename DstXprType, typename Lhs, typename Rhs>\nstruct Assignment<DstXprType, Product<Lhs,Rhs,AliasFreeProduct>, internal::add_assign_op<typename DstXprType::Scalar,typename Product<Lhs,Rhs,AliasFreeProduct>::Scalar>, Sparse2Dense>\n{\n  typedef Product<Lhs,Rhs,AliasFreeProduct> SrcXprType;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::add_assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &)\n  {\n    generic_product_impl<Lhs, Rhs>::addTo(dst,src.lhs(),src.rhs());\n  }\n};\n\n// dense -= sparse-product (can be sparse*sparse, sparse*perm, etc.)\ntemplate< typename DstXprType, typename Lhs, typename Rhs>\nstruct Assignment<DstXprType, Product<Lhs,Rhs,AliasFreeProduct>, internal::sub_assign_op<typename DstXprType::Scalar,typename Product<Lhs,Rhs,AliasFreeProduct>::Scalar>, Sparse2Dense>\n{\n  typedef Product<Lhs,Rhs,AliasFreeProduct> SrcXprType;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::sub_assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &)\n  {\n    generic_product_impl<Lhs, Rhs>::subTo(dst,src.lhs(),src.rhs());\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, int Options>\nstruct unary_evaluator<SparseView<Product<Lhs, Rhs, Options> >, IteratorBased>\n : public evaluator<typename Product<Lhs, Rhs, DefaultProduct>::PlainObject>\n{\n  typedef SparseView<Product<Lhs, Rhs, Options> > XprType;\n  typedef typename XprType::PlainObject PlainObject;\n  typedef evaluator<PlainObject> Base;\n\n  explicit unary_evaluator(const XprType& xpr)\n    : m_result(xpr.rows(), xpr.cols())\n  {\n    using std::abs;\n    ::new (static_cast<Base*>(this)) Base(m_result);\n    typedef typename nested_eval<Lhs,Dynamic>::type LhsNested;\n    typedef typename nested_eval<Rhs,Dynamic>::type RhsNested;\n    LhsNested lhsNested(xpr.nestedExpression().lhs());\n    RhsNested rhsNested(xpr.nestedExpression().rhs());\n\n    internal::sparse_sparse_product_with_pruning_selector<typename remove_all<LhsNested>::type,\n                                                          typename remove_all<RhsNested>::type, PlainObject>::run(lhsNested,rhsNested,m_result,\n                                                                                                                  abs(xpr.reference())*xpr.epsilon());\n  }\n\nprotected:\n  PlainObject m_result;\n};\n\n} // end namespace internal\n\n// sparse matrix = sparse-product (can be sparse*sparse, sparse*perm, etc.)\ntemplate<typename Scalar, int Options_, typename StorageIndex_>\ntemplate<typename Lhs, typename Rhs>\nSparseMatrix<Scalar,Options_,StorageIndex_>& SparseMatrix<Scalar,Options_,StorageIndex_>::operator=(const Product<Lhs,Rhs,AliasFreeProduct>& src)\n{\n  // std::cout << \"in Assignment : \" << DstOptions << \"\\n\";\n  SparseMatrix dst(src.rows(),src.cols());\n  internal::generic_product_impl<Lhs, Rhs>::evalTo(dst,src.lhs(),src.rhs());\n  this->swap(dst);\n  return *this;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSEPRODUCT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseRedux.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEREDUX_H\n#define EIGEN_SPARSEREDUX_H\n\nnamespace Eigen { \n\ntemplate<typename Derived>\ntypename internal::traits<Derived>::Scalar\nSparseMatrixBase<Derived>::sum() const\n{\n  eigen_assert(rows()>0 && cols()>0 && \"you are using a non initialized matrix\");\n  Scalar res(0);\n  internal::evaluator<Derived> thisEval(derived());\n  for (Index j=0; j<outerSize(); ++j)\n    for (typename internal::evaluator<Derived>::InnerIterator iter(thisEval,j); iter; ++iter)\n      res += iter.value();\n  return res;\n}\n\ntemplate<typename Scalar_, int Options_, typename Index_>\ntypename internal::traits<SparseMatrix<Scalar_,Options_,Index_> >::Scalar\nSparseMatrix<Scalar_,Options_,Index_>::sum() const\n{\n  eigen_assert(rows()>0 && cols()>0 && \"you are using a non initialized matrix\");\n  if(this->isCompressed())\n    return Matrix<Scalar,1,Dynamic>::Map(m_data.valuePtr(), m_data.size()).sum();\n  else\n    return Base::sum();\n}\n\ntemplate<typename Scalar_, int Options_, typename Index_>\ntypename internal::traits<SparseVector<Scalar_,Options_, Index_> >::Scalar\nSparseVector<Scalar_,Options_,Index_>::sum() const\n{\n  eigen_assert(rows()>0 && cols()>0 && \"you are using a non initialized matrix\");\n  return Matrix<Scalar,1,Dynamic>::Map(m_data.valuePtr(), m_data.size()).sum();\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSEREDUX_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseRef.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_REF_H\n#define EIGEN_SPARSE_REF_H\n\nnamespace Eigen {\n\nenum {\n  StandardCompressedFormat = 2 /**< used by Ref<SparseMatrix> to specify whether the input storage must be in standard compressed form */\n};\n  \nnamespace internal {\n\ntemplate<typename Derived> class SparseRefBase;\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options_, typename _StrideType>\nstruct traits<Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options_, _StrideType> >\n  : public traits<SparseMatrix<MatScalar,MatOptions,MatIndex> >\n{\n  typedef SparseMatrix<MatScalar,MatOptions,MatIndex> PlainObjectType;\n  enum {\n    Options = Options_,\n    Flags = traits<PlainObjectType>::Flags | CompressedAccessBit | NestByRefBit\n  };\n\n  template<typename Derived> struct match {\n    enum {\n      StorageOrderMatch = PlainObjectType::IsVectorAtCompileTime || Derived::IsVectorAtCompileTime || ((PlainObjectType::Flags&RowMajorBit)==(Derived::Flags&RowMajorBit)),\n      MatchAtCompileTime = (Derived::Flags&CompressedAccessBit) && StorageOrderMatch\n    };\n    typedef typename internal::conditional<MatchAtCompileTime,internal::true_type,internal::false_type>::type type;\n  };\n  \n};\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options_, typename _StrideType>\nstruct traits<Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options_, _StrideType> >\n  : public traits<Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options_, _StrideType> >\n{\n  enum {\n    Flags = (traits<SparseMatrix<MatScalar,MatOptions,MatIndex> >::Flags | CompressedAccessBit | NestByRefBit) & ~LvalueBit\n  };\n};\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options_, typename _StrideType>\nstruct traits<Ref<SparseVector<MatScalar,MatOptions,MatIndex>, Options_, _StrideType> >\n  : public traits<SparseVector<MatScalar,MatOptions,MatIndex> >\n{\n  typedef SparseVector<MatScalar,MatOptions,MatIndex> PlainObjectType;\n  enum {\n    Options = Options_,\n    Flags = traits<PlainObjectType>::Flags | CompressedAccessBit | NestByRefBit\n  };\n\n  template<typename Derived> struct match {\n    enum {\n      MatchAtCompileTime = (Derived::Flags&CompressedAccessBit) && Derived::IsVectorAtCompileTime\n    };\n    typedef typename internal::conditional<MatchAtCompileTime,internal::true_type,internal::false_type>::type type;\n  };\n\n};\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options_, typename _StrideType>\nstruct traits<Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, Options_, _StrideType> >\n  : public traits<Ref<SparseVector<MatScalar,MatOptions,MatIndex>, Options_, _StrideType> >\n{\n  enum {\n    Flags = (traits<SparseVector<MatScalar,MatOptions,MatIndex> >::Flags | CompressedAccessBit | NestByRefBit) & ~LvalueBit\n  };\n};\n\ntemplate<typename Derived>\nstruct traits<SparseRefBase<Derived> > : public traits<Derived> {};\n\ntemplate<typename Derived> class SparseRefBase\n  : public SparseMapBase<Derived>\n{\npublic:\n\n  typedef SparseMapBase<Derived> Base;\n  EIGEN_SPARSE_PUBLIC_INTERFACE(SparseRefBase)\n\n  SparseRefBase()\n    : Base(RowsAtCompileTime==Dynamic?0:RowsAtCompileTime,ColsAtCompileTime==Dynamic?0:ColsAtCompileTime, 0, 0, 0, 0, 0)\n  {}\n  \nprotected:\n\n  template<typename Expression>\n  void construct(Expression& expr)\n  {\n    if(expr.outerIndexPtr()==0)\n      ::new (static_cast<Base*>(this)) Base(expr.size(), expr.nonZeros(), expr.innerIndexPtr(), expr.valuePtr());\n    else\n      ::new (static_cast<Base*>(this)) Base(expr.rows(), expr.cols(), expr.nonZeros(), expr.outerIndexPtr(), expr.innerIndexPtr(), expr.valuePtr(), expr.innerNonZeroPtr());\n  }\n};\n\n} // namespace internal\n\n\n/** \n  * \\ingroup SparseCore_Module\n  *\n  * \\brief A sparse matrix expression referencing an existing sparse expression\n  *\n  * \\tparam SparseMatrixType the equivalent sparse matrix type of the referenced data, it must be a template instance of class SparseMatrix.\n  * \\tparam Options specifies whether the a standard compressed format is required \\c Options is  \\c #StandardCompressedFormat, or \\c 0.\n  *                The default is \\c 0.\n  *\n  * \\sa class Ref\n  */\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nclass Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType >\n  : public internal::SparseRefBase<Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType > >\n#else\ntemplate<typename SparseMatrixType, int Options>\nclass Ref<SparseMatrixType, Options>\n  : public SparseMapBase<Derived,WriteAccessors> // yes, that's weird to use Derived here, but that works!\n#endif\n{\n    typedef SparseMatrix<MatScalar,MatOptions,MatIndex> PlainObjectType;\n    typedef internal::traits<Ref> Traits;\n    template<int OtherOptions>\n    inline Ref(const SparseMatrix<MatScalar,OtherOptions,MatIndex>& expr);\n    template<int OtherOptions>\n    inline Ref(const MappedSparseMatrix<MatScalar,OtherOptions,MatIndex>& expr);\n  public:\n\n    typedef internal::SparseRefBase<Ref> Base;\n    EIGEN_SPARSE_PUBLIC_INTERFACE(Ref)\n\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<int OtherOptions>\n    inline Ref(SparseMatrix<MatScalar,OtherOptions,MatIndex>& expr)\n    {\n      EIGEN_STATIC_ASSERT(bool(Traits::template match<SparseMatrix<MatScalar,OtherOptions,MatIndex> >::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH);\n      eigen_assert( ((Options & int(StandardCompressedFormat))==0) || (expr.isCompressed()) );\n      Base::construct(expr.derived());\n    }\n    \n    template<int OtherOptions>\n    inline Ref(MappedSparseMatrix<MatScalar,OtherOptions,MatIndex>& expr)\n    {\n      EIGEN_STATIC_ASSERT(bool(Traits::template match<SparseMatrix<MatScalar,OtherOptions,MatIndex> >::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH);\n      eigen_assert( ((Options & int(StandardCompressedFormat))==0) || (expr.isCompressed()) );\n      Base::construct(expr.derived());\n    }\n    \n    template<typename Derived>\n    inline Ref(const SparseCompressedBase<Derived>& expr)\n    #else\n    /** Implicit constructor from any sparse expression (2D matrix or 1D vector) */\n    template<typename Derived>\n    inline Ref(SparseCompressedBase<Derived>& expr)\n    #endif\n    {\n      EIGEN_STATIC_ASSERT(bool(internal::is_lvalue<Derived>::value), THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY);\n      EIGEN_STATIC_ASSERT(bool(Traits::template match<Derived>::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH);\n      eigen_assert( ((Options & int(StandardCompressedFormat))==0) || (expr.isCompressed()) );\n      Base::construct(expr.const_cast_derived());\n    }\n};\n\n// this is the const ref version\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nclass Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType>\n  : public internal::SparseRefBase<Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n{\n    typedef SparseMatrix<MatScalar,MatOptions,MatIndex> TPlainObjectType;\n    typedef internal::traits<Ref> Traits;\n  public:\n\n    typedef internal::SparseRefBase<Ref> Base;\n    EIGEN_SPARSE_PUBLIC_INTERFACE(Ref)\n\n    template<typename Derived>\n    inline Ref(const SparseMatrixBase<Derived>& expr) : m_hasCopy(false)\n    {\n      construct(expr.derived(), typename Traits::template match<Derived>::type());\n    }\n\n    inline Ref(const Ref& other) : Base(other), m_hasCopy(false) {\n      // copy constructor shall not copy the m_object, to avoid unnecessary malloc and copy\n    }\n\n    template<typename OtherRef>\n    inline Ref(const RefBase<OtherRef>& other) : m_hasCopy(false) {\n      construct(other.derived(), typename Traits::template match<OtherRef>::type());\n    }\n\n    ~Ref() {\n      if(m_hasCopy) {\n        TPlainObjectType* obj = reinterpret_cast<TPlainObjectType*>(&m_storage);\n        obj->~TPlainObjectType();\n      }\n    }\n\n  protected:\n\n    template<typename Expression>\n    void construct(const Expression& expr,internal::true_type)\n    {\n      if((Options & int(StandardCompressedFormat)) && (!expr.isCompressed()))\n      {\n        TPlainObjectType* obj = reinterpret_cast<TPlainObjectType*>(&m_storage);\n        ::new (obj) TPlainObjectType(expr);\n        m_hasCopy = true;\n        Base::construct(*obj);\n      }\n      else\n      {\n        Base::construct(expr);\n      }\n    }\n\n    template<typename Expression>\n    void construct(const Expression& expr, internal::false_type)\n    {\n      TPlainObjectType* obj = reinterpret_cast<TPlainObjectType*>(&m_storage);\n      ::new (obj) TPlainObjectType(expr);\n      m_hasCopy = true;\n      Base::construct(*obj);\n    }\n\n  protected:\n    typename internal::aligned_storage<sizeof(TPlainObjectType), EIGEN_ALIGNOF(TPlainObjectType)>::type m_storage;\n    bool m_hasCopy;\n};\n\n\n\n/**\n  * \\ingroup SparseCore_Module\n  *\n  * \\brief A sparse vector expression referencing an existing sparse vector expression\n  *\n  * \\tparam SparseVectorType the equivalent sparse vector type of the referenced data, it must be a template instance of class SparseVector.\n  *\n  * \\sa class Ref\n  */\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nclass Ref<SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType >\n  : public internal::SparseRefBase<Ref<SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType > >\n#else\ntemplate<typename SparseVectorType>\nclass Ref<SparseVectorType>\n  : public SparseMapBase<Derived,WriteAccessors>\n#endif\n{\n    typedef SparseVector<MatScalar,MatOptions,MatIndex> PlainObjectType;\n    typedef internal::traits<Ref> Traits;\n    template<int OtherOptions>\n    inline Ref(const SparseVector<MatScalar,OtherOptions,MatIndex>& expr);\n  public:\n\n    typedef internal::SparseRefBase<Ref> Base;\n    EIGEN_SPARSE_PUBLIC_INTERFACE(Ref)\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<int OtherOptions>\n    inline Ref(SparseVector<MatScalar,OtherOptions,MatIndex>& expr)\n    {\n      EIGEN_STATIC_ASSERT(bool(Traits::template match<SparseVector<MatScalar,OtherOptions,MatIndex> >::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH);\n      Base::construct(expr.derived());\n    }\n\n    template<typename Derived>\n    inline Ref(const SparseCompressedBase<Derived>& expr)\n    #else\n    /** Implicit constructor from any 1D sparse vector expression */\n    template<typename Derived>\n    inline Ref(SparseCompressedBase<Derived>& expr)\n    #endif\n    {\n      EIGEN_STATIC_ASSERT(bool(internal::is_lvalue<Derived>::value), THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY);\n      EIGEN_STATIC_ASSERT(bool(Traits::template match<Derived>::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH);\n      Base::construct(expr.const_cast_derived());\n    }\n};\n\n// this is the const ref version\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nclass Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType>\n  : public internal::SparseRefBase<Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n{\n    typedef SparseVector<MatScalar,MatOptions,MatIndex> TPlainObjectType;\n    typedef internal::traits<Ref> Traits;\n  public:\n\n    typedef internal::SparseRefBase<Ref> Base;\n    EIGEN_SPARSE_PUBLIC_INTERFACE(Ref)\n\n    template<typename Derived>\n    inline Ref(const SparseMatrixBase<Derived>& expr) : m_hasCopy(false)\n    {\n      construct(expr.derived(), typename Traits::template match<Derived>::type());\n    }\n\n    inline Ref(const Ref& other) : Base(other), m_hasCopy(false) {\n      // copy constructor shall not copy the m_object, to avoid unnecessary malloc and copy\n    }\n\n    template<typename OtherRef>\n    inline Ref(const RefBase<OtherRef>& other) : m_hasCopy(false) {\n      construct(other.derived(), typename Traits::template match<OtherRef>::type());\n    }\n\n    ~Ref() {\n      if(m_hasCopy) {\n        TPlainObjectType* obj = reinterpret_cast<TPlainObjectType*>(&m_storage);\n        obj->~TPlainObjectType();\n      }\n    }\n\n  protected:\n\n    template<typename Expression>\n    void construct(const Expression& expr,internal::true_type)\n    {\n      Base::construct(expr);\n    }\n\n    template<typename Expression>\n    void construct(const Expression& expr, internal::false_type)\n    {\n      TPlainObjectType* obj = reinterpret_cast<TPlainObjectType*>(&m_storage);\n      ::new (obj) TPlainObjectType(expr);\n      m_hasCopy = true;\n      Base::construct(*obj);\n    }\n\n  protected:\n    typename internal::aligned_storage<sizeof(TPlainObjectType), EIGEN_ALIGNOF(TPlainObjectType)>::type m_storage;\n    bool m_hasCopy;\n};\n\nnamespace internal {\n\n// FIXME shall we introduce a general evaluatior_ref that we can specialize for any sparse object once, and thus remove this copy-pasta thing...\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nstruct evaluator<Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n  : evaluator<SparseCompressedBase<Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > >\n{\n  typedef evaluator<SparseCompressedBase<Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > > Base;\n  typedef Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> XprType;  \n  evaluator() : Base() {}\n  explicit evaluator(const XprType &mat) : Base(mat) {}\n};\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nstruct evaluator<Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n  : evaluator<SparseCompressedBase<Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > >\n{\n  typedef evaluator<SparseCompressedBase<Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > > Base;\n  typedef Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> XprType;  \n  evaluator() : Base() {}\n  explicit evaluator(const XprType &mat) : Base(mat) {}\n};\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nstruct evaluator<Ref<SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n  : evaluator<SparseCompressedBase<Ref<SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> > >\n{\n  typedef evaluator<SparseCompressedBase<Ref<SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> > > Base;\n  typedef Ref<SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> XprType;\n  evaluator() : Base() {}\n  explicit evaluator(const XprType &mat) : Base(mat) {}\n};\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nstruct evaluator<Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n  : evaluator<SparseCompressedBase<Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> > >\n{\n  typedef evaluator<SparseCompressedBase<Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> > > Base;\n  typedef Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> XprType;\n  evaluator() : Base() {}\n  explicit evaluator(const XprType &mat) : Base(mat) {}\n};\n\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_REF_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseSelfAdjointView.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_SELFADJOINTVIEW_H\n#define EIGEN_SPARSE_SELFADJOINTVIEW_H\n\nnamespace Eigen { \n  \n/** \\ingroup SparseCore_Module\n  * \\class SparseSelfAdjointView\n  *\n  * \\brief Pseudo expression to manipulate a triangular sparse matrix as a selfadjoint matrix.\n  *\n  * \\param MatrixType the type of the dense matrix storing the coefficients\n  * \\param Mode can be either \\c #Lower or \\c #Upper\n  *\n  * This class is an expression of a sefladjoint matrix from a triangular part of a matrix\n  * with given dense storage of the coefficients. It is the return type of MatrixBase::selfadjointView()\n  * and most of the time this is the only way that it is used.\n  *\n  * \\sa SparseMatrixBase::selfadjointView()\n  */\nnamespace internal {\n  \ntemplate<typename MatrixType, unsigned int Mode>\nstruct traits<SparseSelfAdjointView<MatrixType,Mode> > : traits<MatrixType> {\n};\n\ntemplate<int SrcMode,int DstMode,typename MatrixType,int DestOrder>\nvoid permute_symm_to_symm(const MatrixType& mat, SparseMatrix<typename MatrixType::Scalar,DestOrder,typename MatrixType::StorageIndex>& _dest, const typename MatrixType::StorageIndex* perm = 0);\n\ntemplate<int Mode,typename MatrixType,int DestOrder>\nvoid permute_symm_to_fullsymm(const MatrixType& mat, SparseMatrix<typename MatrixType::Scalar,DestOrder,typename MatrixType::StorageIndex>& _dest, const typename MatrixType::StorageIndex* perm = 0);\n\n}\n\ntemplate<typename MatrixType, unsigned int Mode_> class SparseSelfAdjointView\n  : public EigenBase<SparseSelfAdjointView<MatrixType,Mode_> >\n{\n  public:\n    \n    enum {\n      Mode = Mode_,\n      TransposeMode = ((Mode & Upper) ? Lower : 0) | ((Mode & Lower) ? Upper : 0),\n      RowsAtCompileTime = internal::traits<SparseSelfAdjointView>::RowsAtCompileTime,\n      ColsAtCompileTime = internal::traits<SparseSelfAdjointView>::ColsAtCompileTime\n    };\n\n    typedef EigenBase<SparseSelfAdjointView> Base;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef Matrix<StorageIndex,Dynamic,1> VectorI;\n    typedef typename internal::ref_selector<MatrixType>::non_const_type MatrixTypeNested;\n    typedef typename internal::remove_all<MatrixTypeNested>::type _MatrixTypeNested;\n    \n    explicit inline SparseSelfAdjointView(MatrixType& matrix) : m_matrix(matrix)\n    {\n      eigen_assert(rows()==cols() && \"SelfAdjointView is only for squared matrices\");\n    }\n\n    inline Index rows() const { return m_matrix.rows(); }\n    inline Index cols() const { return m_matrix.cols(); }\n\n    /** \\internal \\returns a reference to the nested matrix */\n    const _MatrixTypeNested& matrix() const { return m_matrix; }\n    typename internal::remove_reference<MatrixTypeNested>::type& matrix() { return m_matrix; }\n\n    /** \\returns an expression of the matrix product between a sparse self-adjoint matrix \\c *this and a sparse matrix \\a rhs.\n      *\n      * Note that there is no algorithmic advantage of performing such a product compared to a general sparse-sparse matrix product.\n      * Indeed, the SparseSelfadjointView operand is first copied into a temporary SparseMatrix before computing the product.\n      */\n    template<typename OtherDerived>\n    Product<SparseSelfAdjointView, OtherDerived>\n    operator*(const SparseMatrixBase<OtherDerived>& rhs) const\n    {\n      return Product<SparseSelfAdjointView, OtherDerived>(*this, rhs.derived());\n    }\n\n    /** \\returns an expression of the matrix product between a sparse matrix \\a lhs and a sparse self-adjoint matrix \\a rhs.\n      *\n      * Note that there is no algorithmic advantage of performing such a product compared to a general sparse-sparse matrix product.\n      * Indeed, the SparseSelfadjointView operand is first copied into a temporary SparseMatrix before computing the product.\n      */\n    template<typename OtherDerived> friend\n    Product<OtherDerived, SparseSelfAdjointView>\n    operator*(const SparseMatrixBase<OtherDerived>& lhs, const SparseSelfAdjointView& rhs)\n    {\n      return Product<OtherDerived, SparseSelfAdjointView>(lhs.derived(), rhs);\n    }\n    \n    /** Efficient sparse self-adjoint matrix times dense vector/matrix product */\n    template<typename OtherDerived>\n    Product<SparseSelfAdjointView,OtherDerived>\n    operator*(const MatrixBase<OtherDerived>& rhs) const\n    {\n      return Product<SparseSelfAdjointView,OtherDerived>(*this, rhs.derived());\n    }\n\n    /** Efficient dense vector/matrix times sparse self-adjoint matrix product */\n    template<typename OtherDerived> friend\n    Product<OtherDerived,SparseSelfAdjointView>\n    operator*(const MatrixBase<OtherDerived>& lhs, const SparseSelfAdjointView& rhs)\n    {\n      return Product<OtherDerived,SparseSelfAdjointView>(lhs.derived(), rhs);\n    }\n\n    /** Perform a symmetric rank K update of the selfadjoint matrix \\c *this:\n      * \\f$ this = this + \\alpha ( u u^* ) \\f$ where \\a u is a vector or matrix.\n      *\n      * \\returns a reference to \\c *this\n      *\n      * To perform \\f$ this = this + \\alpha ( u^* u ) \\f$ you can simply\n      * call this function with u.adjoint().\n      */\n    template<typename DerivedU>\n    SparseSelfAdjointView& rankUpdate(const SparseMatrixBase<DerivedU>& u, const Scalar& alpha = Scalar(1));\n    \n    /** \\returns an expression of P H P^-1 */\n    // TODO implement twists in a more evaluator friendly fashion\n    SparseSymmetricPermutationProduct<_MatrixTypeNested,Mode> twistedBy(const PermutationMatrix<Dynamic,Dynamic,StorageIndex>& perm) const\n    {\n      return SparseSymmetricPermutationProduct<_MatrixTypeNested,Mode>(m_matrix, perm);\n    }\n\n    template<typename SrcMatrixType,int SrcMode>\n    SparseSelfAdjointView& operator=(const SparseSymmetricPermutationProduct<SrcMatrixType,SrcMode>& permutedMatrix)\n    {\n      internal::call_assignment_no_alias_no_transpose(*this, permutedMatrix);\n      return *this;\n    }\n\n    SparseSelfAdjointView& operator=(const SparseSelfAdjointView& src)\n    {\n      PermutationMatrix<Dynamic,Dynamic,StorageIndex> pnull;\n      return *this = src.twistedBy(pnull);\n    }\n\n    // Since we override the copy-assignment operator, we need to explicitly re-declare the copy-constructor\n    EIGEN_DEFAULT_COPY_CONSTRUCTOR(SparseSelfAdjointView)\n\n    template<typename SrcMatrixType,unsigned int SrcMode>\n    SparseSelfAdjointView& operator=(const SparseSelfAdjointView<SrcMatrixType,SrcMode>& src)\n    {\n      PermutationMatrix<Dynamic,Dynamic,StorageIndex> pnull;\n      return *this = src.twistedBy(pnull);\n    }\n    \n    void resize(Index rows, Index cols)\n    {\n      EIGEN_ONLY_USED_FOR_DEBUG(rows);\n      EIGEN_ONLY_USED_FOR_DEBUG(cols);\n      eigen_assert(rows == this->rows() && cols == this->cols()\n                && \"SparseSelfadjointView::resize() does not actually allow to resize.\");\n    }\n    \n  protected:\n\n    MatrixTypeNested m_matrix;\n    //mutable VectorI m_countPerRow;\n    //mutable VectorI m_countPerCol;\n  private:\n    template<typename Dest> void evalTo(Dest &) const;\n};\n\n/***************************************************************************\n* Implementation of SparseMatrixBase methods\n***************************************************************************/\n\ntemplate<typename Derived>\ntemplate<unsigned int UpLo>\ntypename SparseMatrixBase<Derived>::template ConstSelfAdjointViewReturnType<UpLo>::Type SparseMatrixBase<Derived>::selfadjointView() const\n{\n  return SparseSelfAdjointView<const Derived, UpLo>(derived());\n}\n\ntemplate<typename Derived>\ntemplate<unsigned int UpLo>\ntypename SparseMatrixBase<Derived>::template SelfAdjointViewReturnType<UpLo>::Type SparseMatrixBase<Derived>::selfadjointView()\n{\n  return SparseSelfAdjointView<Derived, UpLo>(derived());\n}\n\n/***************************************************************************\n* Implementation of SparseSelfAdjointView methods\n***************************************************************************/\n\ntemplate<typename MatrixType, unsigned int Mode>\ntemplate<typename DerivedU>\nSparseSelfAdjointView<MatrixType,Mode>&\nSparseSelfAdjointView<MatrixType,Mode>::rankUpdate(const SparseMatrixBase<DerivedU>& u, const Scalar& alpha)\n{\n  SparseMatrix<Scalar,(MatrixType::Flags&RowMajorBit)?RowMajor:ColMajor> tmp = u * u.adjoint();\n  if(alpha==Scalar(0))\n    m_matrix = tmp.template triangularView<Mode>();\n  else\n    m_matrix += alpha * tmp.template triangularView<Mode>();\n\n  return *this;\n}\n\nnamespace internal {\n  \n// TODO currently a selfadjoint expression has the form SelfAdjointView<.,.>\n//      in the future selfadjoint-ness should be defined by the expression traits\n//      such that Transpose<SelfAdjointView<.,.> > is valid. (currently TriangularBase::transpose() is overloaded to make it work)\ntemplate<typename MatrixType, unsigned int Mode>\nstruct evaluator_traits<SparseSelfAdjointView<MatrixType,Mode> >\n{\n  typedef typename storage_kind_to_evaluator_kind<typename MatrixType::StorageKind>::Kind Kind;\n  typedef SparseSelfAdjointShape Shape;\n};\n\nstruct SparseSelfAdjoint2Sparse {};\n\ntemplate<> struct AssignmentKind<SparseShape,SparseSelfAdjointShape> { typedef SparseSelfAdjoint2Sparse Kind; };\ntemplate<> struct AssignmentKind<SparseSelfAdjointShape,SparseShape> { typedef Sparse2Sparse Kind; };\n\ntemplate< typename DstXprType, typename SrcXprType, typename Functor>\nstruct Assignment<DstXprType, SrcXprType, Functor, SparseSelfAdjoint2Sparse>\n{\n  typedef typename DstXprType::StorageIndex StorageIndex;\n  typedef internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> AssignOpType;\n\n  template<typename DestScalar,int StorageOrder>\n  static void run(SparseMatrix<DestScalar,StorageOrder,StorageIndex> &dst, const SrcXprType &src, const AssignOpType&/*func*/)\n  {\n    internal::permute_symm_to_fullsymm<SrcXprType::Mode>(src.matrix(), dst);\n  }\n\n  // FIXME: the handling of += and -= in sparse matrices should be cleanup so that next two overloads could be reduced to:\n  template<typename DestScalar,int StorageOrder,typename AssignFunc>\n  static void run(SparseMatrix<DestScalar,StorageOrder,StorageIndex> &dst, const SrcXprType &src, const AssignFunc& func)\n  {\n    SparseMatrix<DestScalar,StorageOrder,StorageIndex> tmp(src.rows(),src.cols());\n    run(tmp, src, AssignOpType());\n    call_assignment_no_alias_no_transpose(dst, tmp, func);\n  }\n\n  template<typename DestScalar,int StorageOrder>\n  static void run(SparseMatrix<DestScalar,StorageOrder,StorageIndex> &dst, const SrcXprType &src,\n                  const internal::add_assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar>& /* func */)\n  {\n    SparseMatrix<DestScalar,StorageOrder,StorageIndex> tmp(src.rows(),src.cols());\n    run(tmp, src, AssignOpType());\n    dst += tmp;\n  }\n\n  template<typename DestScalar,int StorageOrder>\n  static void run(SparseMatrix<DestScalar,StorageOrder,StorageIndex> &dst, const SrcXprType &src,\n                  const internal::sub_assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar>& /* func */)\n  {\n    SparseMatrix<DestScalar,StorageOrder,StorageIndex> tmp(src.rows(),src.cols());\n    run(tmp, src, AssignOpType());\n    dst -= tmp;\n  }\n  \n  template<typename DestScalar>\n  static void run(DynamicSparseMatrix<DestScalar,ColMajor,StorageIndex>& dst, const SrcXprType &src, const AssignOpType&/*func*/)\n  {\n    // TODO directly evaluate into dst;\n    SparseMatrix<DestScalar,ColMajor,StorageIndex> tmp(dst.rows(),dst.cols());\n    internal::permute_symm_to_fullsymm<SrcXprType::Mode>(src.matrix(), tmp);\n    dst = tmp;\n  }\n};\n\n} // end namespace internal\n\n/***************************************************************************\n* Implementation of sparse self-adjoint time dense matrix\n***************************************************************************/\n\nnamespace internal {\n\ntemplate<int Mode, typename SparseLhsType, typename DenseRhsType, typename DenseResType, typename AlphaType>\ninline void sparse_selfadjoint_time_dense_product(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const AlphaType& alpha)\n{\n  EIGEN_ONLY_USED_FOR_DEBUG(alpha);\n  \n  typedef typename internal::nested_eval<SparseLhsType,DenseRhsType::MaxColsAtCompileTime>::type SparseLhsTypeNested;\n  typedef typename internal::remove_all<SparseLhsTypeNested>::type SparseLhsTypeNestedCleaned;\n  typedef evaluator<SparseLhsTypeNestedCleaned> LhsEval;\n  typedef typename LhsEval::InnerIterator LhsIterator;\n  typedef typename SparseLhsType::Scalar LhsScalar;\n  \n  enum {\n    LhsIsRowMajor = (LhsEval::Flags&RowMajorBit)==RowMajorBit,\n    ProcessFirstHalf =\n              ((Mode&(Upper|Lower))==(Upper|Lower))\n          || ( (Mode&Upper) && !LhsIsRowMajor)\n          || ( (Mode&Lower) && LhsIsRowMajor),\n    ProcessSecondHalf = !ProcessFirstHalf\n  };\n  \n  SparseLhsTypeNested lhs_nested(lhs);\n  LhsEval lhsEval(lhs_nested);\n\n  // work on one column at once\n  for (Index k=0; k<rhs.cols(); ++k)\n  {\n    for (Index j=0; j<lhs.outerSize(); ++j)\n    {\n      LhsIterator i(lhsEval,j);\n      // handle diagonal coeff\n      if (ProcessSecondHalf)\n      {\n        while (i && i.index()<j) ++i;\n        if(i && i.index()==j)\n        {\n          res.coeffRef(j,k) += alpha * i.value() * rhs.coeff(j,k);\n          ++i;\n        }\n      }\n\n      // premultiplied rhs for scatters\n      typename ScalarBinaryOpTraits<AlphaType, typename DenseRhsType::Scalar>::ReturnType rhs_j(alpha*rhs(j,k));\n      // accumulator for partial scalar product\n      typename DenseResType::Scalar res_j(0);\n      for(; (ProcessFirstHalf ? i && i.index() < j : i) ; ++i)\n      {\n        LhsScalar lhs_ij = i.value();\n        if(!LhsIsRowMajor) lhs_ij = numext::conj(lhs_ij);\n        res_j += lhs_ij * rhs.coeff(i.index(),k);\n        res(i.index(),k) += numext::conj(lhs_ij) * rhs_j;\n      }\n      res.coeffRef(j,k) += alpha * res_j;\n\n      // handle diagonal coeff\n      if (ProcessFirstHalf && i && (i.index()==j))\n        res.coeffRef(j,k) += alpha * i.value() * rhs.coeff(j,k);\n    }\n  }\n}\n\n\ntemplate<typename LhsView, typename Rhs, int ProductType>\nstruct generic_product_impl<LhsView, Rhs, SparseSelfAdjointShape, DenseShape, ProductType>\n: generic_product_impl_base<LhsView, Rhs, generic_product_impl<LhsView, Rhs, SparseSelfAdjointShape, DenseShape, ProductType> >\n{\n  template<typename Dest>\n  static void scaleAndAddTo(Dest& dst, const LhsView& lhsView, const Rhs& rhs, const typename Dest::Scalar& alpha)\n  {\n    typedef typename LhsView::_MatrixTypeNested Lhs;\n    typedef typename nested_eval<Lhs,Dynamic>::type LhsNested;\n    typedef typename nested_eval<Rhs,Dynamic>::type RhsNested;\n    LhsNested lhsNested(lhsView.matrix());\n    RhsNested rhsNested(rhs);\n    \n    internal::sparse_selfadjoint_time_dense_product<LhsView::Mode>(lhsNested, rhsNested, dst, alpha);\n  }\n};\n\ntemplate<typename Lhs, typename RhsView, int ProductType>\nstruct generic_product_impl<Lhs, RhsView, DenseShape, SparseSelfAdjointShape, ProductType>\n: generic_product_impl_base<Lhs, RhsView, generic_product_impl<Lhs, RhsView, DenseShape, SparseSelfAdjointShape, ProductType> >\n{\n  template<typename Dest>\n  static void scaleAndAddTo(Dest& dst, const Lhs& lhs, const RhsView& rhsView, const typename Dest::Scalar& alpha)\n  {\n    typedef typename RhsView::_MatrixTypeNested Rhs;\n    typedef typename nested_eval<Lhs,Dynamic>::type LhsNested;\n    typedef typename nested_eval<Rhs,Dynamic>::type RhsNested;\n    LhsNested lhsNested(lhs);\n    RhsNested rhsNested(rhsView.matrix());\n    \n    // transpose everything\n    Transpose<Dest> dstT(dst);\n    internal::sparse_selfadjoint_time_dense_product<RhsView::TransposeMode>(rhsNested.transpose(), lhsNested.transpose(), dstT, alpha);\n  }\n};\n\n// NOTE: these two overloads are needed to evaluate the sparse selfadjoint view into a full sparse matrix\n// TODO: maybe the copy could be handled by generic_product_impl so that these overloads would not be needed anymore\n\ntemplate<typename LhsView, typename Rhs, int ProductTag>\nstruct product_evaluator<Product<LhsView, Rhs, DefaultProduct>, ProductTag, SparseSelfAdjointShape, SparseShape>\n  : public evaluator<typename Product<typename Rhs::PlainObject, Rhs, DefaultProduct>::PlainObject>\n{\n  typedef Product<LhsView, Rhs, DefaultProduct> XprType;\n  typedef typename XprType::PlainObject PlainObject;\n  typedef evaluator<PlainObject> Base;\n\n  product_evaluator(const XprType& xpr)\n    : m_lhs(xpr.lhs()), m_result(xpr.rows(), xpr.cols())\n  {\n    ::new (static_cast<Base*>(this)) Base(m_result);\n    generic_product_impl<typename Rhs::PlainObject, Rhs, SparseShape, SparseShape, ProductTag>::evalTo(m_result, m_lhs, xpr.rhs());\n  }\n  \nprotected:\n  typename Rhs::PlainObject m_lhs;\n  PlainObject m_result;\n};\n\ntemplate<typename Lhs, typename RhsView, int ProductTag>\nstruct product_evaluator<Product<Lhs, RhsView, DefaultProduct>, ProductTag, SparseShape, SparseSelfAdjointShape>\n  : public evaluator<typename Product<Lhs, typename Lhs::PlainObject, DefaultProduct>::PlainObject>\n{\n  typedef Product<Lhs, RhsView, DefaultProduct> XprType;\n  typedef typename XprType::PlainObject PlainObject;\n  typedef evaluator<PlainObject> Base;\n\n  product_evaluator(const XprType& xpr)\n    : m_rhs(xpr.rhs()), m_result(xpr.rows(), xpr.cols())\n  {\n    ::new (static_cast<Base*>(this)) Base(m_result);\n    generic_product_impl<Lhs, typename Lhs::PlainObject, SparseShape, SparseShape, ProductTag>::evalTo(m_result, xpr.lhs(), m_rhs);\n  }\n  \nprotected:\n  typename Lhs::PlainObject m_rhs;\n  PlainObject m_result;\n};\n\n} // namespace internal\n\n/***************************************************************************\n* Implementation of symmetric copies and permutations\n***************************************************************************/\nnamespace internal {\n\ntemplate<int Mode,typename MatrixType,int DestOrder>\nvoid permute_symm_to_fullsymm(const MatrixType& mat, SparseMatrix<typename MatrixType::Scalar,DestOrder,typename MatrixType::StorageIndex>& _dest, const typename MatrixType::StorageIndex* perm)\n{\n  typedef typename MatrixType::StorageIndex StorageIndex;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef SparseMatrix<Scalar,DestOrder,StorageIndex> Dest;\n  typedef Matrix<StorageIndex,Dynamic,1> VectorI;\n  typedef evaluator<MatrixType> MatEval;\n  typedef typename evaluator<MatrixType>::InnerIterator MatIterator;\n  \n  MatEval matEval(mat);\n  Dest& dest(_dest.derived());\n  enum {\n    StorageOrderMatch = int(Dest::IsRowMajor) == int(MatrixType::IsRowMajor)\n  };\n  \n  Index size = mat.rows();\n  VectorI count;\n  count.resize(size);\n  count.setZero();\n  dest.resize(size,size);\n  for(Index j = 0; j<size; ++j)\n  {\n    Index jp = perm ? perm[j] : j;\n    for(MatIterator it(matEval,j); it; ++it)\n    {\n      Index i = it.index();\n      Index r = it.row();\n      Index c = it.col();\n      Index ip = perm ? perm[i] : i;\n      if(Mode==int(Upper|Lower))\n        count[StorageOrderMatch ? jp : ip]++;\n      else if(r==c)\n        count[ip]++;\n      else if(( Mode==Lower && r>c) || ( Mode==Upper && r<c))\n      {\n        count[ip]++;\n        count[jp]++;\n      }\n    }\n  }\n  Index nnz = count.sum();\n  \n  // reserve space\n  dest.resizeNonZeros(nnz);\n  dest.outerIndexPtr()[0] = 0;\n  for(Index j=0; j<size; ++j)\n    dest.outerIndexPtr()[j+1] = dest.outerIndexPtr()[j] + count[j];\n  for(Index j=0; j<size; ++j)\n    count[j] = dest.outerIndexPtr()[j];\n  \n  // copy data\n  for(StorageIndex j = 0; j<size; ++j)\n  {\n    for(MatIterator it(matEval,j); it; ++it)\n    {\n      StorageIndex i = internal::convert_index<StorageIndex>(it.index());\n      Index r = it.row();\n      Index c = it.col();\n      \n      StorageIndex jp = perm ? perm[j] : j;\n      StorageIndex ip = perm ? perm[i] : i;\n      \n      if(Mode==int(Upper|Lower))\n      {\n        Index k = count[StorageOrderMatch ? jp : ip]++;\n        dest.innerIndexPtr()[k] = StorageOrderMatch ? ip : jp;\n        dest.valuePtr()[k] = it.value();\n      }\n      else if(r==c)\n      {\n        Index k = count[ip]++;\n        dest.innerIndexPtr()[k] = ip;\n        dest.valuePtr()[k] = it.value();\n      }\n      else if(( (Mode&Lower)==Lower && r>c) || ( (Mode&Upper)==Upper && r<c))\n      {\n        if(!StorageOrderMatch)\n          std::swap(ip,jp);\n        Index k = count[jp]++;\n        dest.innerIndexPtr()[k] = ip;\n        dest.valuePtr()[k] = it.value();\n        k = count[ip]++;\n        dest.innerIndexPtr()[k] = jp;\n        dest.valuePtr()[k] = numext::conj(it.value());\n      }\n    }\n  }\n}\n\ntemplate<int SrcMode_,int DstMode_,typename MatrixType,int DstOrder>\nvoid permute_symm_to_symm(const MatrixType& mat, SparseMatrix<typename MatrixType::Scalar,DstOrder,typename MatrixType::StorageIndex>& _dest, const typename MatrixType::StorageIndex* perm)\n{\n  typedef typename MatrixType::StorageIndex StorageIndex;\n  typedef typename MatrixType::Scalar Scalar;\n  SparseMatrix<Scalar,DstOrder,StorageIndex>& dest(_dest.derived());\n  typedef Matrix<StorageIndex,Dynamic,1> VectorI;\n  typedef evaluator<MatrixType> MatEval;\n  typedef typename evaluator<MatrixType>::InnerIterator MatIterator;\n\n  enum {\n    SrcOrder = MatrixType::IsRowMajor ? RowMajor : ColMajor,\n    StorageOrderMatch = int(SrcOrder) == int(DstOrder),\n    DstMode = DstOrder==RowMajor ? (DstMode_==Upper ? Lower : Upper) : DstMode_,\n    SrcMode = SrcOrder==RowMajor ? (SrcMode_==Upper ? Lower : Upper) : SrcMode_\n  };\n\n  MatEval matEval(mat);\n  \n  Index size = mat.rows();\n  VectorI count(size);\n  count.setZero();\n  dest.resize(size,size);\n  for(StorageIndex j = 0; j<size; ++j)\n  {\n    StorageIndex jp = perm ? perm[j] : j;\n    for(MatIterator it(matEval,j); it; ++it)\n    {\n      StorageIndex i = it.index();\n      if((int(SrcMode)==int(Lower) && i<j) || (int(SrcMode)==int(Upper) && i>j))\n        continue;\n                  \n      StorageIndex ip = perm ? perm[i] : i;\n      count[int(DstMode)==int(Lower) ? (std::min)(ip,jp) : (std::max)(ip,jp)]++;\n    }\n  }\n  dest.outerIndexPtr()[0] = 0;\n  for(Index j=0; j<size; ++j)\n    dest.outerIndexPtr()[j+1] = dest.outerIndexPtr()[j] + count[j];\n  dest.resizeNonZeros(dest.outerIndexPtr()[size]);\n  for(Index j=0; j<size; ++j)\n    count[j] = dest.outerIndexPtr()[j];\n  \n  for(StorageIndex j = 0; j<size; ++j)\n  {\n    \n    for(MatIterator it(matEval,j); it; ++it)\n    {\n      StorageIndex i = it.index();\n      if((int(SrcMode)==int(Lower) && i<j) || (int(SrcMode)==int(Upper) && i>j))\n        continue;\n                  \n      StorageIndex jp = perm ? perm[j] : j;\n      StorageIndex ip = perm? perm[i] : i;\n      \n      Index k = count[int(DstMode)==int(Lower) ? (std::min)(ip,jp) : (std::max)(ip,jp)]++;\n      dest.innerIndexPtr()[k] = int(DstMode)==int(Lower) ? (std::max)(ip,jp) : (std::min)(ip,jp);\n      \n      if(!StorageOrderMatch) std::swap(ip,jp);\n      if( ((int(DstMode)==int(Lower) && ip<jp) || (int(DstMode)==int(Upper) && ip>jp)))\n        dest.valuePtr()[k] = numext::conj(it.value());\n      else\n        dest.valuePtr()[k] = it.value();\n    }\n  }\n}\n\n}\n\n// TODO implement twists in a more evaluator friendly fashion\n\nnamespace internal {\n\ntemplate<typename MatrixType, int Mode>\nstruct traits<SparseSymmetricPermutationProduct<MatrixType,Mode> > : traits<MatrixType> {\n};\n\n}\n\ntemplate<typename MatrixType,int Mode>\nclass SparseSymmetricPermutationProduct\n  : public EigenBase<SparseSymmetricPermutationProduct<MatrixType,Mode> >\n{\n  public:\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    enum {\n      RowsAtCompileTime = internal::traits<SparseSymmetricPermutationProduct>::RowsAtCompileTime,\n      ColsAtCompileTime = internal::traits<SparseSymmetricPermutationProduct>::ColsAtCompileTime\n    };\n  protected:\n    typedef PermutationMatrix<Dynamic,Dynamic,StorageIndex> Perm;\n  public:\n    typedef Matrix<StorageIndex,Dynamic,1> VectorI;\n    typedef typename MatrixType::Nested MatrixTypeNested;\n    typedef typename internal::remove_all<MatrixTypeNested>::type NestedExpression;\n    \n    SparseSymmetricPermutationProduct(const MatrixType& mat, const Perm& perm)\n      : m_matrix(mat), m_perm(perm)\n    {}\n    \n    inline Index rows() const { return m_matrix.rows(); }\n    inline Index cols() const { return m_matrix.cols(); }\n        \n    const NestedExpression& matrix() const { return m_matrix; }\n    const Perm& perm() const { return m_perm; }\n    \n  protected:\n    MatrixTypeNested m_matrix;\n    const Perm& m_perm;\n\n};\n\nnamespace internal {\n  \ntemplate<typename DstXprType, typename MatrixType, int Mode, typename Scalar>\nstruct Assignment<DstXprType, SparseSymmetricPermutationProduct<MatrixType,Mode>, internal::assign_op<Scalar,typename MatrixType::Scalar>, Sparse2Sparse>\n{\n  typedef SparseSymmetricPermutationProduct<MatrixType,Mode> SrcXprType;\n  typedef typename DstXprType::StorageIndex DstIndex;\n  template<int Options>\n  static void run(SparseMatrix<Scalar,Options,DstIndex> &dst, const SrcXprType &src, const internal::assign_op<Scalar,typename MatrixType::Scalar> &)\n  {\n    // internal::permute_symm_to_fullsymm<Mode>(m_matrix,_dest,m_perm.indices().data());\n    SparseMatrix<Scalar,(Options&RowMajor)==RowMajor ? ColMajor : RowMajor, DstIndex> tmp;\n    internal::permute_symm_to_fullsymm<Mode>(src.matrix(),tmp,src.perm().indices().data());\n    dst = tmp;\n  }\n  \n  template<typename DestType,unsigned int DestMode>\n  static void run(SparseSelfAdjointView<DestType,DestMode>& dst, const SrcXprType &src, const internal::assign_op<Scalar,typename MatrixType::Scalar> &)\n  {\n    internal::permute_symm_to_symm<Mode,DestMode>(src.matrix(),dst.matrix(),src.perm().indices().data());\n  }\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_SELFADJOINTVIEW_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseSolverBase.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSESOLVERBASE_H\n#define EIGEN_SPARSESOLVERBASE_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n  /** \\internal\n  * Helper functions to solve with a sparse right-hand-side and result.\n  * The rhs is decomposed into small vertical panels which are solved through dense temporaries.\n  */\ntemplate<typename Decomposition, typename Rhs, typename Dest>\ntypename enable_if<Rhs::ColsAtCompileTime!=1 && Dest::ColsAtCompileTime!=1>::type\nsolve_sparse_through_dense_panels(const Decomposition &dec, const Rhs& rhs, Dest &dest)\n{\n  EIGEN_STATIC_ASSERT((Dest::Flags&RowMajorBit)==0,THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES);\n  typedef typename Dest::Scalar DestScalar;\n  // we process the sparse rhs per block of NbColsAtOnce columns temporarily stored into a dense matrix.\n  static const Index NbColsAtOnce = 4;\n  Index rhsCols = rhs.cols();\n  Index size = rhs.rows();\n  // the temporary matrices do not need more columns than NbColsAtOnce:\n  Index tmpCols = (std::min)(rhsCols, NbColsAtOnce); \n  Eigen::Matrix<DestScalar,Dynamic,Dynamic> tmp(size,tmpCols);\n  Eigen::Matrix<DestScalar,Dynamic,Dynamic> tmpX(size,tmpCols);\n  for(Index k=0; k<rhsCols; k+=NbColsAtOnce)\n  {\n    Index actualCols = std::min<Index>(rhsCols-k, NbColsAtOnce);\n    tmp.leftCols(actualCols) = rhs.middleCols(k,actualCols);\n    tmpX.leftCols(actualCols) = dec.solve(tmp.leftCols(actualCols));\n    dest.middleCols(k,actualCols) = tmpX.leftCols(actualCols).sparseView();\n  }\n}\n\n// Overload for vector as rhs\ntemplate<typename Decomposition, typename Rhs, typename Dest>\ntypename enable_if<Rhs::ColsAtCompileTime==1 || Dest::ColsAtCompileTime==1>::type\nsolve_sparse_through_dense_panels(const Decomposition &dec, const Rhs& rhs, Dest &dest)\n{\n  typedef typename Dest::Scalar DestScalar;\n  Index size = rhs.rows();\n  Eigen::Matrix<DestScalar,Dynamic,1> rhs_dense(rhs);\n  Eigen::Matrix<DestScalar,Dynamic,1> dest_dense(size);\n  dest_dense = dec.solve(rhs_dense);\n  dest = dest_dense.sparseView();\n}\n\n} // end namespace internal\n\n/** \\class SparseSolverBase\n  * \\ingroup SparseCore_Module\n  * \\brief A base class for sparse solvers\n  *\n  * \\tparam Derived the actual type of the solver.\n  *\n  */\ntemplate<typename Derived>\nclass SparseSolverBase : internal::noncopyable\n{\n  public:\n\n    /** Default constructor */\n    SparseSolverBase()\n      : m_isInitialized(false)\n    {}\n\n    ~SparseSolverBase()\n    {}\n\n    Derived& derived() { return *static_cast<Derived*>(this); }\n    const Derived& derived() const { return *static_cast<const Derived*>(this); }\n    \n    /** \\returns an expression of the solution x of \\f$ A x = b \\f$ using the current decomposition of A.\n      *\n      * \\sa compute()\n      */\n    template<typename Rhs>\n    inline const Solve<Derived, Rhs>\n    solve(const MatrixBase<Rhs>& b) const\n    {\n      eigen_assert(m_isInitialized && \"Solver is not initialized.\");\n      eigen_assert(derived().rows()==b.rows() && \"solve(): invalid number of rows of the right hand side matrix b\");\n      return Solve<Derived, Rhs>(derived(), b.derived());\n    }\n    \n    /** \\returns an expression of the solution x of \\f$ A x = b \\f$ using the current decomposition of A.\n      *\n      * \\sa compute()\n      */\n    template<typename Rhs>\n    inline const Solve<Derived, Rhs>\n    solve(const SparseMatrixBase<Rhs>& b) const\n    {\n      eigen_assert(m_isInitialized && \"Solver is not initialized.\");\n      eigen_assert(derived().rows()==b.rows() && \"solve(): invalid number of rows of the right hand side matrix b\");\n      return Solve<Derived, Rhs>(derived(), b.derived());\n    }\n    \n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    /** \\internal default implementation of solving with a sparse rhs */\n    template<typename Rhs,typename Dest>\n    void _solve_impl(const SparseMatrixBase<Rhs> &b, SparseMatrixBase<Dest> &dest) const\n    {\n      internal::solve_sparse_through_dense_panels(derived(), b.derived(), dest.derived());\n    }\n    #endif // EIGEN_PARSED_BY_DOXYGEN\n\n  protected:\n    \n    mutable bool m_isInitialized;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSESOLVERBASE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseSparseProductWithPruning.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSESPARSEPRODUCTWITHPRUNING_H\n#define EIGEN_SPARSESPARSEPRODUCTWITHPRUNING_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n\n// perform a pseudo in-place sparse * sparse product assuming all matrices are col major\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstatic void sparse_sparse_product_with_pruning_impl(const Lhs& lhs, const Rhs& rhs, ResultType& res, const typename ResultType::RealScalar& tolerance)\n{\n  // return sparse_sparse_product_with_pruning_impl2(lhs,rhs,res);\n\n  typedef typename remove_all<Rhs>::type::Scalar RhsScalar;\n  typedef typename remove_all<ResultType>::type::Scalar ResScalar;\n  typedef typename remove_all<Lhs>::type::StorageIndex StorageIndex;\n\n  // make sure to call innerSize/outerSize since we fake the storage order.\n  Index rows = lhs.innerSize();\n  Index cols = rhs.outerSize();\n  //Index size = lhs.outerSize();\n  eigen_assert(lhs.outerSize() == rhs.innerSize());\n\n  // allocate a temporary buffer\n  AmbiVector<ResScalar,StorageIndex> tempVector(rows);\n\n  // mimics a resizeByInnerOuter:\n  if(ResultType::IsRowMajor)\n    res.resize(cols, rows);\n  else\n    res.resize(rows, cols);\n  \n  evaluator<Lhs> lhsEval(lhs);\n  evaluator<Rhs> rhsEval(rhs);\n  \n  // estimate the number of non zero entries\n  // given a rhs column containing Y non zeros, we assume that the respective Y columns\n  // of the lhs differs in average of one non zeros, thus the number of non zeros for\n  // the product of a rhs column with the lhs is X+Y where X is the average number of non zero\n  // per column of the lhs.\n  // Therefore, we have nnz(lhs*rhs) = nnz(lhs) + nnz(rhs)\n  Index estimated_nnz_prod = lhsEval.nonZerosEstimate() + rhsEval.nonZerosEstimate();\n\n  res.reserve(estimated_nnz_prod);\n  double ratioColRes = double(estimated_nnz_prod)/(double(lhs.rows())*double(rhs.cols()));\n  for (Index j=0; j<cols; ++j)\n  {\n    // FIXME:\n    //double ratioColRes = (double(rhs.innerVector(j).nonZeros()) + double(lhs.nonZeros())/double(lhs.cols()))/double(lhs.rows());\n    // let's do a more accurate determination of the nnz ratio for the current column j of res\n    tempVector.init(ratioColRes);\n    tempVector.setZero();\n    for (typename evaluator<Rhs>::InnerIterator rhsIt(rhsEval, j); rhsIt; ++rhsIt)\n    {\n      // FIXME should be written like this: tmp += rhsIt.value() * lhs.col(rhsIt.index())\n      tempVector.restart();\n      RhsScalar x = rhsIt.value();\n      for (typename evaluator<Lhs>::InnerIterator lhsIt(lhsEval, rhsIt.index()); lhsIt; ++lhsIt)\n      {\n        tempVector.coeffRef(lhsIt.index()) += lhsIt.value() * x;\n      }\n    }\n    res.startVec(j);\n    for (typename AmbiVector<ResScalar,StorageIndex>::Iterator it(tempVector,tolerance); it; ++it)\n      res.insertBackByOuterInner(j,it.index()) = it.value();\n  }\n  res.finalize();\n}\n\ntemplate<typename Lhs, typename Rhs, typename ResultType,\n  int LhsStorageOrder = traits<Lhs>::Flags&RowMajorBit,\n  int RhsStorageOrder = traits<Rhs>::Flags&RowMajorBit,\n  int ResStorageOrder = traits<ResultType>::Flags&RowMajorBit>\nstruct sparse_sparse_product_with_pruning_selector;\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,ColMajor,ColMajor,ColMajor>\n{\n  typedef typename ResultType::RealScalar RealScalar;\n\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)\n  {\n    typename remove_all<ResultType>::type _res(res.rows(), res.cols());\n    internal::sparse_sparse_product_with_pruning_impl<Lhs,Rhs,ResultType>(lhs, rhs, _res, tolerance);\n    res.swap(_res);\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,ColMajor,ColMajor,RowMajor>\n{\n  typedef typename ResultType::RealScalar RealScalar;\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)\n  {\n    // we need a col-major matrix to hold the result\n    typedef SparseMatrix<typename ResultType::Scalar,ColMajor,typename ResultType::StorageIndex> SparseTemporaryType;\n    SparseTemporaryType _res(res.rows(), res.cols());\n    internal::sparse_sparse_product_with_pruning_impl<Lhs,Rhs,SparseTemporaryType>(lhs, rhs, _res, tolerance);\n    res = _res;\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,RowMajor,RowMajor,RowMajor>\n{\n  typedef typename ResultType::RealScalar RealScalar;\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)\n  {\n    // let's transpose the product to get a column x column product\n    typename remove_all<ResultType>::type _res(res.rows(), res.cols());\n    internal::sparse_sparse_product_with_pruning_impl<Rhs,Lhs,ResultType>(rhs, lhs, _res, tolerance);\n    res.swap(_res);\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,RowMajor,RowMajor,ColMajor>\n{\n  typedef typename ResultType::RealScalar RealScalar;\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)\n  {\n    typedef SparseMatrix<typename Lhs::Scalar,ColMajor,typename Lhs::StorageIndex> ColMajorMatrixLhs;\n    typedef SparseMatrix<typename Rhs::Scalar,ColMajor,typename Lhs::StorageIndex> ColMajorMatrixRhs;\n    ColMajorMatrixLhs colLhs(lhs);\n    ColMajorMatrixRhs colRhs(rhs);\n    internal::sparse_sparse_product_with_pruning_impl<ColMajorMatrixLhs,ColMajorMatrixRhs,ResultType>(colLhs, colRhs, res, tolerance);\n\n    // let's transpose the product to get a column x column product\n//     typedef SparseMatrix<typename ResultType::Scalar> SparseTemporaryType;\n//     SparseTemporaryType _res(res.cols(), res.rows());\n//     sparse_sparse_product_with_pruning_impl<Rhs,Lhs,SparseTemporaryType>(rhs, lhs, _res);\n//     res = _res.transpose();\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,ColMajor,RowMajor,RowMajor>\n{\n  typedef typename ResultType::RealScalar RealScalar;\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)\n  {\n    typedef SparseMatrix<typename Lhs::Scalar,RowMajor,typename Lhs::StorageIndex> RowMajorMatrixLhs;\n    RowMajorMatrixLhs rowLhs(lhs);\n    sparse_sparse_product_with_pruning_selector<RowMajorMatrixLhs,Rhs,ResultType,RowMajor,RowMajor>(rowLhs,rhs,res,tolerance);\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,RowMajor,ColMajor,RowMajor>\n{\n  typedef typename ResultType::RealScalar RealScalar;\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)\n  {\n    typedef SparseMatrix<typename Rhs::Scalar,RowMajor,typename Lhs::StorageIndex> RowMajorMatrixRhs;\n    RowMajorMatrixRhs rowRhs(rhs);\n    sparse_sparse_product_with_pruning_selector<Lhs,RowMajorMatrixRhs,ResultType,RowMajor,RowMajor,RowMajor>(lhs,rowRhs,res,tolerance);\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,ColMajor,RowMajor,ColMajor>\n{\n  typedef typename ResultType::RealScalar RealScalar;\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)\n  {\n    typedef SparseMatrix<typename Rhs::Scalar,ColMajor,typename Lhs::StorageIndex> ColMajorMatrixRhs;\n    ColMajorMatrixRhs colRhs(rhs);\n    internal::sparse_sparse_product_with_pruning_impl<Lhs,ColMajorMatrixRhs,ResultType>(lhs, colRhs, res, tolerance);\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,RowMajor,ColMajor,ColMajor>\n{\n  typedef typename ResultType::RealScalar RealScalar;\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)\n  {\n    typedef SparseMatrix<typename Lhs::Scalar,ColMajor,typename Lhs::StorageIndex> ColMajorMatrixLhs;\n    ColMajorMatrixLhs colLhs(lhs);\n    internal::sparse_sparse_product_with_pruning_impl<ColMajorMatrixLhs,Rhs,ResultType>(colLhs, rhs, res, tolerance);\n  }\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSESPARSEPRODUCTWITHPRUNING_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseTranspose.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSETRANSPOSE_H\n#define EIGEN_SPARSETRANSPOSE_H\n\nnamespace Eigen { \n\nnamespace internal {\n  template<typename MatrixType,int CompressedAccess=int(MatrixType::Flags&CompressedAccessBit)>\n  class SparseTransposeImpl\n    : public SparseMatrixBase<Transpose<MatrixType> >\n  {};\n  \n  template<typename MatrixType>\n  class SparseTransposeImpl<MatrixType,CompressedAccessBit>\n    : public SparseCompressedBase<Transpose<MatrixType> >\n  {\n    typedef SparseCompressedBase<Transpose<MatrixType> > Base;\n  public:\n    using Base::derived;\n    typedef typename Base::Scalar Scalar;\n    typedef typename Base::StorageIndex StorageIndex;\n\n    inline Index nonZeros() const { return derived().nestedExpression().nonZeros(); }\n    \n    inline const Scalar* valuePtr() const { return derived().nestedExpression().valuePtr(); }\n    inline const StorageIndex* innerIndexPtr() const { return derived().nestedExpression().innerIndexPtr(); }\n    inline const StorageIndex* outerIndexPtr() const { return derived().nestedExpression().outerIndexPtr(); }\n    inline const StorageIndex* innerNonZeroPtr() const { return derived().nestedExpression().innerNonZeroPtr(); }\n\n    inline Scalar* valuePtr() { return derived().nestedExpression().valuePtr(); }\n    inline StorageIndex* innerIndexPtr() { return derived().nestedExpression().innerIndexPtr(); }\n    inline StorageIndex* outerIndexPtr() { return derived().nestedExpression().outerIndexPtr(); }\n    inline StorageIndex* innerNonZeroPtr() { return derived().nestedExpression().innerNonZeroPtr(); }\n  };\n}\n  \ntemplate<typename MatrixType> class TransposeImpl<MatrixType,Sparse>\n  : public internal::SparseTransposeImpl<MatrixType>\n{\n  protected:\n    typedef internal::SparseTransposeImpl<MatrixType> Base;\n};\n\nnamespace internal {\n  \ntemplate<typename ArgType>\nstruct unary_evaluator<Transpose<ArgType>, IteratorBased>\n  : public evaluator_base<Transpose<ArgType> >\n{\n    typedef typename evaluator<ArgType>::InnerIterator        EvalIterator;\n  public:\n    typedef Transpose<ArgType> XprType;\n    \n    inline Index nonZerosEstimate() const {\n      return m_argImpl.nonZerosEstimate();\n    }\n\n    class InnerIterator : public EvalIterator\n    {\n    public:\n      EIGEN_STRONG_INLINE InnerIterator(const unary_evaluator& unaryOp, Index outer)\n        : EvalIterator(unaryOp.m_argImpl,outer)\n      {}\n      \n      Index row() const { return EvalIterator::col(); }\n      Index col() const { return EvalIterator::row(); }\n    };\n    \n    enum {\n      CoeffReadCost = evaluator<ArgType>::CoeffReadCost,\n      Flags = XprType::Flags\n    };\n    \n    explicit unary_evaluator(const XprType& op) :m_argImpl(op.nestedExpression()) {}\n\n  protected:\n    evaluator<ArgType> m_argImpl;\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSETRANSPOSE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseTriangularView.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_TRIANGULARVIEW_H\n#define EIGEN_SPARSE_TRIANGULARVIEW_H\n\nnamespace Eigen {\n\n/** \\ingroup SparseCore_Module\n  *\n  * \\brief Base class for a triangular part in a \\b sparse matrix\n  *\n  * This class is an abstract base class of class TriangularView, and objects of type TriangularViewImpl cannot be instantiated.\n  * It extends class TriangularView with additional methods which are available for sparse expressions only.\n  *\n  * \\sa class TriangularView, SparseMatrixBase::triangularView()\n  */\ntemplate<typename MatrixType, unsigned int Mode> class TriangularViewImpl<MatrixType,Mode,Sparse>\n  : public SparseMatrixBase<TriangularView<MatrixType,Mode> >\n{\n    enum { SkipFirst = ((Mode&Lower) && !(MatrixType::Flags&RowMajorBit))\n                    || ((Mode&Upper) &&  (MatrixType::Flags&RowMajorBit)),\n           SkipLast = !SkipFirst,\n           SkipDiag = (Mode&ZeroDiag) ? 1 : 0,\n           HasUnitDiag = (Mode&UnitDiag) ? 1 : 0\n    };\n    \n    typedef TriangularView<MatrixType,Mode> TriangularViewType;\n    \n  protected:\n    // dummy solve function to make TriangularView happy.\n    void solve() const;\n\n    typedef SparseMatrixBase<TriangularViewType> Base;\n  public:\n    \n    EIGEN_SPARSE_PUBLIC_INTERFACE(TriangularViewType)\n    \n    typedef typename MatrixType::Nested MatrixTypeNested;\n    typedef typename internal::remove_reference<MatrixTypeNested>::type MatrixTypeNestedNonRef;\n    typedef typename internal::remove_all<MatrixTypeNested>::type MatrixTypeNestedCleaned;\n\n    template<typename RhsType, typename DstType>\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE void _solve_impl(const RhsType &rhs, DstType &dst) const {\n      if(!(internal::is_same<RhsType,DstType>::value && internal::extract_data(dst) == internal::extract_data(rhs)))\n        dst = rhs;\n      this->solveInPlace(dst);\n    }\n\n    /** Applies the inverse of \\c *this to the dense vector or matrix \\a other, \"in-place\" */\n    template<typename OtherDerived> void solveInPlace(MatrixBase<OtherDerived>& other) const;\n\n    /** Applies the inverse of \\c *this to the sparse vector or matrix \\a other, \"in-place\" */\n    template<typename OtherDerived> void solveInPlace(SparseMatrixBase<OtherDerived>& other) const;\n  \n};\n\nnamespace internal {\n\ntemplate<typename ArgType, unsigned int Mode>\nstruct unary_evaluator<TriangularView<ArgType,Mode>, IteratorBased>\n : evaluator_base<TriangularView<ArgType,Mode> >\n{\n  typedef TriangularView<ArgType,Mode> XprType;\n  \nprotected:\n  \n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::StorageIndex StorageIndex;\n  typedef typename evaluator<ArgType>::InnerIterator EvalIterator;\n  \n  enum { SkipFirst = ((Mode&Lower) && !(ArgType::Flags&RowMajorBit))\n                    || ((Mode&Upper) &&  (ArgType::Flags&RowMajorBit)),\n         SkipLast = !SkipFirst,\n         SkipDiag = (Mode&ZeroDiag) ? 1 : 0,\n         HasUnitDiag = (Mode&UnitDiag) ? 1 : 0\n  };\n  \npublic:\n  \n  enum {\n    CoeffReadCost = evaluator<ArgType>::CoeffReadCost,\n    Flags = XprType::Flags\n  };\n    \n  explicit unary_evaluator(const XprType &xpr) : m_argImpl(xpr.nestedExpression()), m_arg(xpr.nestedExpression()) {}\n  \n  inline Index nonZerosEstimate() const {\n    return m_argImpl.nonZerosEstimate();\n  }\n  \n  class InnerIterator : public EvalIterator\n  {\n      typedef EvalIterator Base;\n    public:\n\n      EIGEN_STRONG_INLINE InnerIterator(const unary_evaluator& xprEval, Index outer)\n        : Base(xprEval.m_argImpl,outer), m_returnOne(false), m_containsDiag(Base::outer()<xprEval.m_arg.innerSize())\n      {\n        if(SkipFirst)\n        {\n          while((*this) && ((HasUnitDiag||SkipDiag)  ? this->index()<=outer : this->index()<outer))\n            Base::operator++();\n          if(HasUnitDiag)\n            m_returnOne = m_containsDiag;\n        }\n        else if(HasUnitDiag && ((!Base::operator bool()) || Base::index()>=Base::outer()))\n        {\n          if((!SkipFirst) && Base::operator bool())\n            Base::operator++();\n          m_returnOne = m_containsDiag;\n        }\n      }\n\n      EIGEN_STRONG_INLINE InnerIterator& operator++()\n      {\n        if(HasUnitDiag && m_returnOne)\n          m_returnOne = false;\n        else\n        {\n          Base::operator++();\n          if(HasUnitDiag && (!SkipFirst) && ((!Base::operator bool()) || Base::index()>=Base::outer()))\n          {\n            if((!SkipFirst) && Base::operator bool())\n              Base::operator++();\n            m_returnOne = m_containsDiag;\n          }\n        }\n        return *this;\n      }\n      \n      EIGEN_STRONG_INLINE operator bool() const\n      {\n        if(HasUnitDiag && m_returnOne)\n          return true;\n        if(SkipFirst) return  Base::operator bool();\n        else\n        {\n          if (SkipDiag) return (Base::operator bool() && this->index() < this->outer());\n          else return (Base::operator bool() && this->index() <= this->outer());\n        }\n      }\n\n//       inline Index row() const { return (ArgType::Flags&RowMajorBit ? Base::outer() : this->index()); }\n//       inline Index col() const { return (ArgType::Flags&RowMajorBit ? this->index() : Base::outer()); }\n      inline StorageIndex index() const\n      {\n        if(HasUnitDiag && m_returnOne)  return internal::convert_index<StorageIndex>(Base::outer());\n        else                            return Base::index();\n      }\n      inline Scalar value() const\n      {\n        if(HasUnitDiag && m_returnOne)  return Scalar(1);\n        else                            return Base::value();\n      }\n\n    protected:\n      bool m_returnOne;\n      bool m_containsDiag;\n    private:\n      Scalar& valueRef();\n  };\n  \nprotected:\n  evaluator<ArgType> m_argImpl;\n  const ArgType& m_arg;\n};\n\n} // end namespace internal\n\ntemplate<typename Derived>\ntemplate<int Mode>\ninline const TriangularView<const Derived, Mode>\nSparseMatrixBase<Derived>::triangularView() const\n{\n  return TriangularView<const Derived, Mode>(derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_TRIANGULARVIEW_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseUtil.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEUTIL_H\n#define EIGEN_SPARSEUTIL_H\n\nnamespace Eigen { \n\n#ifdef NDEBUG\n#define EIGEN_DBG_SPARSE(X)\n#else\n#define EIGEN_DBG_SPARSE(X) X\n#endif\n\n#define EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(Derived, Op) \\\ntemplate<typename OtherDerived> \\\nEIGEN_STRONG_INLINE Derived& operator Op(const Eigen::SparseMatrixBase<OtherDerived>& other) \\\n{ \\\n  return Base::operator Op(other.derived()); \\\n} \\\nEIGEN_STRONG_INLINE Derived& operator Op(const Derived& other) \\\n{ \\\n  return Base::operator Op(other); \\\n}\n\n#define EIGEN_SPARSE_INHERIT_SCALAR_ASSIGNMENT_OPERATOR(Derived, Op) \\\ntemplate<typename Other> \\\nEIGEN_STRONG_INLINE Derived& operator Op(const Other& scalar) \\\n{ \\\n  return Base::operator Op(scalar); \\\n}\n\n#define EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATORS(Derived) \\\nEIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(Derived, =)\n\n\n#define EIGEN_SPARSE_PUBLIC_INTERFACE(Derived) \\\n  EIGEN_GENERIC_PUBLIC_INTERFACE(Derived)\n\n  \nconst int CoherentAccessPattern     = 0x1;\nconst int InnerRandomAccessPattern  = 0x2 | CoherentAccessPattern;\nconst int OuterRandomAccessPattern  = 0x4 | CoherentAccessPattern;\nconst int RandomAccessPattern       = 0x8 | OuterRandomAccessPattern | InnerRandomAccessPattern;\n\ntemplate<typename Scalar_, int _Flags = 0, typename StorageIndex_ = int>  class SparseMatrix;\ntemplate<typename Scalar_, int _Flags = 0, typename StorageIndex_ = int>  class DynamicSparseMatrix;\ntemplate<typename Scalar_, int _Flags = 0, typename StorageIndex_ = int>  class SparseVector;\ntemplate<typename Scalar_, int _Flags = 0, typename StorageIndex_ = int>  class MappedSparseMatrix;\n\ntemplate<typename MatrixType, unsigned int UpLo>  class SparseSelfAdjointView;\ntemplate<typename Lhs, typename Rhs>              class SparseDiagonalProduct;\ntemplate<typename MatrixType> class SparseView;\n\ntemplate<typename Lhs, typename Rhs>        class SparseSparseProduct;\ntemplate<typename Lhs, typename Rhs>        class SparseTimeDenseProduct;\ntemplate<typename Lhs, typename Rhs>        class DenseTimeSparseProduct;\ntemplate<typename Lhs, typename Rhs, bool Transpose> class SparseDenseOuterProduct;\n\ntemplate<typename Lhs, typename Rhs> struct SparseSparseProductReturnType;\ntemplate<typename Lhs, typename Rhs,\n         int InnerSize = EIGEN_SIZE_MIN_PREFER_FIXED(internal::traits<Lhs>::ColsAtCompileTime,internal::traits<Rhs>::RowsAtCompileTime)> struct DenseSparseProductReturnType;\n         \ntemplate<typename Lhs, typename Rhs,\n         int InnerSize = EIGEN_SIZE_MIN_PREFER_FIXED(internal::traits<Lhs>::ColsAtCompileTime,internal::traits<Rhs>::RowsAtCompileTime)> struct SparseDenseProductReturnType;\ntemplate<typename MatrixType,int UpLo> class SparseSymmetricPermutationProduct;\n\nnamespace internal {\n\ntemplate<typename T,int Rows,int Cols,int Flags> struct sparse_eval;\n\ntemplate<typename T> struct eval<T,Sparse>\n  : sparse_eval<T, traits<T>::RowsAtCompileTime,traits<T>::ColsAtCompileTime,traits<T>::Flags>\n{};\n\ntemplate<typename T,int Cols,int Flags> struct sparse_eval<T,1,Cols,Flags> {\n    typedef typename traits<T>::Scalar Scalar_;\n    typedef typename traits<T>::StorageIndex StorageIndex_;\n  public:\n    typedef SparseVector<Scalar_, RowMajor, StorageIndex_> type;\n};\n\ntemplate<typename T,int Rows,int Flags> struct sparse_eval<T,Rows,1,Flags> {\n    typedef typename traits<T>::Scalar Scalar_;\n    typedef typename traits<T>::StorageIndex StorageIndex_;\n  public:\n    typedef SparseVector<Scalar_, ColMajor, StorageIndex_> type;\n};\n\n// TODO this seems almost identical to plain_matrix_type<T, Sparse>\ntemplate<typename T,int Rows,int Cols,int Flags> struct sparse_eval {\n    typedef typename traits<T>::Scalar Scalar_;\n    typedef typename traits<T>::StorageIndex StorageIndex_;\n    enum { Options_ = ((Flags&RowMajorBit)==RowMajorBit) ? RowMajor : ColMajor };\n  public:\n    typedef SparseMatrix<Scalar_, Options_, StorageIndex_> type;\n};\n\ntemplate<typename T,int Flags> struct sparse_eval<T,1,1,Flags> {\n    typedef typename traits<T>::Scalar Scalar_;\n  public:\n    typedef Matrix<Scalar_, 1, 1> type;\n};\n\ntemplate<typename T> struct plain_matrix_type<T,Sparse>\n{\n  typedef typename traits<T>::Scalar Scalar_;\n  typedef typename traits<T>::StorageIndex StorageIndex_;\n  enum { Options_ = ((evaluator<T>::Flags&RowMajorBit)==RowMajorBit) ? RowMajor : ColMajor };\n  public:\n    typedef SparseMatrix<Scalar_, Options_, StorageIndex_> type;\n};\n\ntemplate<typename T>\nstruct plain_object_eval<T,Sparse>\n  : sparse_eval<T, traits<T>::RowsAtCompileTime,traits<T>::ColsAtCompileTime, evaluator<T>::Flags>\n{};\n\ntemplate<typename Decomposition, typename RhsType>\nstruct solve_traits<Decomposition,RhsType,Sparse>\n{\n  typedef typename sparse_eval<RhsType, RhsType::RowsAtCompileTime, RhsType::ColsAtCompileTime,traits<RhsType>::Flags>::type PlainObject;\n};\n\ntemplate<typename Derived>\nstruct generic_xpr_base<Derived, MatrixXpr, Sparse>\n{\n  typedef SparseMatrixBase<Derived> type;\n};\n\nstruct SparseTriangularShape  { static std::string debugName() { return \"SparseTriangularShape\"; } };\nstruct SparseSelfAdjointShape { static std::string debugName() { return \"SparseSelfAdjointShape\"; } };\n\ntemplate<> struct glue_shapes<SparseShape,SelfAdjointShape> { typedef SparseSelfAdjointShape type;  };\ntemplate<> struct glue_shapes<SparseShape,TriangularShape > { typedef SparseTriangularShape  type;  };\n\n// return type of SparseCompressedBase::lower_bound;\nstruct LowerBoundIndex {\n  LowerBoundIndex() : value(-1), found(false) {}\n  LowerBoundIndex(Index val, bool ok) : value(val), found(ok) {}\n  Index value;\n  bool found;\n};\n\n} // end namespace internal\n\n/** \\ingroup SparseCore_Module\n  *\n  * \\class Triplet\n  *\n  * \\brief A small structure to hold a non zero as a triplet (i,j,value).\n  *\n  * \\sa SparseMatrix::setFromTriplets()\n  */\ntemplate<typename Scalar, typename StorageIndex=typename SparseMatrix<Scalar>::StorageIndex >\nclass Triplet\n{\npublic:\n  Triplet() : m_row(0), m_col(0), m_value(0) {}\n\n  Triplet(const StorageIndex& i, const StorageIndex& j, const Scalar& v = Scalar(0))\n    : m_row(i), m_col(j), m_value(v)\n  {}\n\n  /** \\returns the row index of the element */\n  const StorageIndex& row() const { return m_row; }\n\n  /** \\returns the column index of the element */\n  const StorageIndex& col() const { return m_col; }\n\n  /** \\returns the value of the element */\n  const Scalar& value() const { return m_value; }\nprotected:\n  StorageIndex m_row, m_col;\n  Scalar m_value;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSEUTIL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseVector.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEVECTOR_H\n#define EIGEN_SPARSEVECTOR_H\n\nnamespace Eigen { \n\n/** \\ingroup SparseCore_Module\n  * \\class SparseVector\n  *\n  * \\brief a sparse vector class\n  *\n  * \\tparam Scalar_ the scalar type, i.e. the type of the coefficients\n  *\n  * See http://www.netlib.org/linalg/html_templates/node91.html for details on the storage scheme.\n  *\n  * This class can be extended with the help of the plugin mechanism described on the page\n  * \\ref TopicCustomizing_Plugins by defining the preprocessor symbol \\c EIGEN_SPARSEVECTOR_PLUGIN.\n  */\n\nnamespace internal {\ntemplate<typename Scalar_, int Options_, typename StorageIndex_>\nstruct traits<SparseVector<Scalar_, Options_, StorageIndex_> >\n{\n  typedef Scalar_ Scalar;\n  typedef StorageIndex_ StorageIndex;\n  typedef Sparse StorageKind;\n  typedef MatrixXpr XprKind;\n  enum {\n    IsColVector = (Options_ & RowMajorBit) ? 0 : 1,\n\n    RowsAtCompileTime = IsColVector ? Dynamic : 1,\n    ColsAtCompileTime = IsColVector ? 1 : Dynamic,\n    MaxRowsAtCompileTime = RowsAtCompileTime,\n    MaxColsAtCompileTime = ColsAtCompileTime,\n    Flags = Options_ | NestByRefBit | LvalueBit | (IsColVector ? 0 : RowMajorBit) | CompressedAccessBit,\n    SupportedAccessPatterns = InnerRandomAccessPattern\n  };\n};\n\n// Sparse-Vector-Assignment kinds:\nenum {\n  SVA_RuntimeSwitch,\n  SVA_Inner,\n  SVA_Outer\n};\n\ntemplate< typename Dest, typename Src,\n          int AssignmentKind = !bool(Src::IsVectorAtCompileTime) ? SVA_RuntimeSwitch\n                             : Src::InnerSizeAtCompileTime==1 ? SVA_Outer\n                             : SVA_Inner>\nstruct sparse_vector_assign_selector;\n\n}\n\ntemplate<typename Scalar_, int Options_, typename StorageIndex_>\nclass SparseVector\n  : public SparseCompressedBase<SparseVector<Scalar_, Options_, StorageIndex_> >\n{\n    typedef SparseCompressedBase<SparseVector> Base;\n    using Base::convert_index;\n  public:\n    EIGEN_SPARSE_PUBLIC_INTERFACE(SparseVector)\n    EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(SparseVector, +=)\n    EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(SparseVector, -=)\n    \n    typedef internal::CompressedStorage<Scalar,StorageIndex> Storage;\n    enum { IsColVector = internal::traits<SparseVector>::IsColVector };\n    \n    enum {\n      Options = Options_\n    };\n    \n    EIGEN_STRONG_INLINE Index rows() const { return IsColVector ? m_size : 1; }\n    EIGEN_STRONG_INLINE Index cols() const { return IsColVector ? 1 : m_size; }\n    EIGEN_STRONG_INLINE Index innerSize() const { return m_size; }\n    EIGEN_STRONG_INLINE Index outerSize() const { return 1; }\n\n    EIGEN_STRONG_INLINE const Scalar* valuePtr() const { return m_data.valuePtr(); }\n    EIGEN_STRONG_INLINE Scalar* valuePtr() { return m_data.valuePtr(); }\n\n    EIGEN_STRONG_INLINE const StorageIndex* innerIndexPtr() const { return m_data.indexPtr(); }\n    EIGEN_STRONG_INLINE StorageIndex* innerIndexPtr() { return m_data.indexPtr(); }\n\n    inline const StorageIndex* outerIndexPtr() const { return 0; }\n    inline StorageIndex* outerIndexPtr() { return 0; }\n    inline const StorageIndex* innerNonZeroPtr() const { return 0; }\n    inline StorageIndex* innerNonZeroPtr() { return 0; }\n    \n    /** \\internal */\n    inline Storage& data() { return m_data; }\n    /** \\internal */\n    inline const Storage& data() const { return m_data; }\n\n    inline Scalar coeff(Index row, Index col) const\n    {\n      eigen_assert(IsColVector ? (col==0 && row>=0 && row<m_size) : (row==0 && col>=0 && col<m_size));\n      return coeff(IsColVector ? row : col);\n    }\n    inline Scalar coeff(Index i) const\n    {\n      eigen_assert(i>=0 && i<m_size);\n      return m_data.at(StorageIndex(i));\n    }\n\n    inline Scalar& coeffRef(Index row, Index col)\n    {\n      eigen_assert(IsColVector ? (col==0 && row>=0 && row<m_size) : (row==0 && col>=0 && col<m_size));\n      return coeffRef(IsColVector ? row : col);\n    }\n\n    /** \\returns a reference to the coefficient value at given index \\a i\n      * This operation involes a log(rho*size) binary search. If the coefficient does not\n      * exist yet, then a sorted insertion into a sequential buffer is performed.\n      *\n      * This insertion might be very costly if the number of nonzeros above \\a i is large.\n      */\n    inline Scalar& coeffRef(Index i)\n    {\n      eigen_assert(i>=0 && i<m_size);\n\n      return m_data.atWithInsertion(StorageIndex(i));\n    }\n\n  public:\n\n    typedef typename Base::InnerIterator InnerIterator;\n    typedef typename Base::ReverseInnerIterator ReverseInnerIterator;\n\n    inline void setZero() { m_data.clear(); }\n\n    /** \\returns the number of non zero coefficients */\n    inline Index nonZeros() const  { return m_data.size(); }\n\n    inline void startVec(Index outer)\n    {\n      EIGEN_UNUSED_VARIABLE(outer);\n      eigen_assert(outer==0);\n    }\n\n    inline Scalar& insertBackByOuterInner(Index outer, Index inner)\n    {\n      EIGEN_UNUSED_VARIABLE(outer);\n      eigen_assert(outer==0);\n      return insertBack(inner);\n    }\n    inline Scalar& insertBack(Index i)\n    {\n      m_data.append(0, i);\n      return m_data.value(m_data.size()-1);\n    }\n    \n    Scalar& insertBackByOuterInnerUnordered(Index outer, Index inner)\n    {\n      EIGEN_UNUSED_VARIABLE(outer);\n      eigen_assert(outer==0);\n      return insertBackUnordered(inner);\n    }\n    inline Scalar& insertBackUnordered(Index i)\n    {\n      m_data.append(0, i);\n      return m_data.value(m_data.size()-1);\n    }\n\n    inline Scalar& insert(Index row, Index col)\n    {\n      eigen_assert(IsColVector ? (col==0 && row>=0 && row<m_size) : (row==0 && col>=0 && col<m_size));\n      \n      Index inner = IsColVector ? row : col;\n      Index outer = IsColVector ? col : row;\n      EIGEN_ONLY_USED_FOR_DEBUG(outer);\n      eigen_assert(outer==0);\n      return insert(inner);\n    }\n    Scalar& insert(Index i)\n    {\n      eigen_assert(i>=0 && i<m_size);\n      \n      Index startId = 0;\n      Index p = Index(m_data.size()) - 1;\n      // TODO smart realloc\n      m_data.resize(p+2,1);\n\n      while ( (p >= startId) && (m_data.index(p) > i) )\n      {\n        m_data.index(p+1) = m_data.index(p);\n        m_data.value(p+1) = m_data.value(p);\n        --p;\n      }\n      m_data.index(p+1) = convert_index(i);\n      m_data.value(p+1) = 0;\n      return m_data.value(p+1);\n    }\n\n    /**\n      */\n    inline void reserve(Index reserveSize) { m_data.reserve(reserveSize); }\n\n\n    inline void finalize() {}\n\n    /** \\copydoc SparseMatrix::prune(const Scalar&,const RealScalar&) */\n    void prune(const Scalar& reference, const RealScalar& epsilon = NumTraits<RealScalar>::dummy_precision())\n    {\n      m_data.prune(reference,epsilon);\n    }\n\n    /** Resizes the sparse vector to \\a rows x \\a cols\n      *\n      * This method is provided for compatibility with matrices.\n      * For a column vector, \\a cols must be equal to 1.\n      * For a row vector, \\a rows must be equal to 1.\n      *\n      * \\sa resize(Index)\n      */\n    void resize(Index rows, Index cols)\n    {\n      eigen_assert((IsColVector ? cols : rows)==1 && \"Outer dimension must equal 1\");\n      resize(IsColVector ? rows : cols);\n    }\n\n    /** Resizes the sparse vector to \\a newSize\n      * This method deletes all entries, thus leaving an empty sparse vector\n      *\n      * \\sa  conservativeResize(), setZero() */\n    void resize(Index newSize)\n    {\n      m_size = newSize;\n      m_data.clear();\n    }\n\n    /** Resizes the sparse vector to \\a newSize, while leaving old values untouched.\n      *\n      * If the size of the vector is decreased, then the storage of the out-of bounds coefficients is kept and reserved.\n      * Call .data().squeeze() to free extra memory.\n      *\n      * \\sa reserve(), setZero()\n      */\n    void conservativeResize(Index newSize)\n    {\n      if (newSize < m_size)\n      {\n        Index i = 0;\n        while (i<m_data.size() && m_data.index(i)<newSize) ++i;\n        m_data.resize(i);\n      }\n      m_size = newSize;\n    }\n\n    void resizeNonZeros(Index size) { m_data.resize(size); }\n\n    inline SparseVector() : m_size(0) { check_template_parameters(); resize(0); }\n\n    explicit inline SparseVector(Index size) : m_size(0) { check_template_parameters(); resize(size); }\n\n    inline SparseVector(Index rows, Index cols) : m_size(0) { check_template_parameters(); resize(rows,cols); }\n\n    template<typename OtherDerived>\n    inline SparseVector(const SparseMatrixBase<OtherDerived>& other)\n      : m_size(0)\n    {\n      #ifdef EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n        EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n      #endif\n      check_template_parameters();\n      *this = other.derived();\n    }\n\n    inline SparseVector(const SparseVector& other)\n      : Base(other), m_size(0)\n    {\n      check_template_parameters();\n      *this = other.derived();\n    }\n\n    /** Swaps the values of \\c *this and \\a other.\n      * Overloaded for performance: this version performs a \\em shallow swap by swapping pointers and attributes only.\n      * \\sa SparseMatrixBase::swap()\n      */\n    inline void swap(SparseVector& other)\n    {\n      std::swap(m_size, other.m_size);\n      m_data.swap(other.m_data);\n    }\n\n    template<int OtherOptions>\n    inline void swap(SparseMatrix<Scalar,OtherOptions,StorageIndex>& other)\n    {\n      eigen_assert(other.outerSize()==1);\n      std::swap(m_size, other.m_innerSize);\n      m_data.swap(other.m_data);\n    }\n\n    inline SparseVector& operator=(const SparseVector& other)\n    {\n      if (other.isRValue())\n      {\n        swap(other.const_cast_derived());\n      }\n      else\n      {\n        resize(other.size());\n        m_data = other.m_data;\n      }\n      return *this;\n    }\n\n    template<typename OtherDerived>\n    inline SparseVector& operator=(const SparseMatrixBase<OtherDerived>& other)\n    {\n      SparseVector tmp(other.size());\n      internal::sparse_vector_assign_selector<SparseVector,OtherDerived>::run(tmp,other.derived());\n      this->swap(tmp);\n      return *this;\n    }\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<typename Lhs, typename Rhs>\n    inline SparseVector& operator=(const SparseSparseProduct<Lhs,Rhs>& product)\n    {\n      return Base::operator=(product);\n    }\n    #endif\n\n    friend std::ostream & operator << (std::ostream & s, const SparseVector& m)\n    {\n      for (Index i=0; i<m.nonZeros(); ++i)\n        s << \"(\" << m.m_data.value(i) << \",\" << m.m_data.index(i) << \") \";\n      s << std::endl;\n      return s;\n    }\n\n    /** Destructor */\n    inline ~SparseVector() {}\n\n    /** Overloaded for performance */\n    Scalar sum() const;\n\n  public:\n\n    /** \\internal \\deprecated use setZero() and reserve() */\n    EIGEN_DEPRECATED void startFill(Index reserve)\n    {\n      setZero();\n      m_data.reserve(reserve);\n    }\n\n    /** \\internal \\deprecated use insertBack(Index,Index) */\n    EIGEN_DEPRECATED Scalar& fill(Index r, Index c)\n    {\n      eigen_assert(r==0 || c==0);\n      return fill(IsColVector ? r : c);\n    }\n\n    /** \\internal \\deprecated use insertBack(Index) */\n    EIGEN_DEPRECATED Scalar& fill(Index i)\n    {\n      m_data.append(0, i);\n      return m_data.value(m_data.size()-1);\n    }\n\n    /** \\internal \\deprecated use insert(Index,Index) */\n    EIGEN_DEPRECATED Scalar& fillrand(Index r, Index c)\n    {\n      eigen_assert(r==0 || c==0);\n      return fillrand(IsColVector ? r : c);\n    }\n\n    /** \\internal \\deprecated use insert(Index) */\n    EIGEN_DEPRECATED Scalar& fillrand(Index i)\n    {\n      return insert(i);\n    }\n\n    /** \\internal \\deprecated use finalize() */\n    EIGEN_DEPRECATED void endFill() {}\n    \n    // These two functions were here in the 3.1 release, so let's keep them in case some code rely on them.\n    /** \\internal \\deprecated use data() */\n    EIGEN_DEPRECATED Storage& _data() { return m_data; }\n    /** \\internal \\deprecated use data() */\n    EIGEN_DEPRECATED const Storage& _data() const { return m_data; }\n    \n#   ifdef EIGEN_SPARSEVECTOR_PLUGIN\n#     include EIGEN_SPARSEVECTOR_PLUGIN\n#   endif\n\nprotected:\n  \n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT(NumTraits<StorageIndex>::IsSigned,THE_INDEX_TYPE_MUST_BE_A_SIGNED_TYPE);\n      EIGEN_STATIC_ASSERT((Options_&(ColMajor|RowMajor))==Options,INVALID_MATRIX_TEMPLATE_PARAMETERS);\n    }\n    \n    Storage m_data;\n    Index m_size;\n};\n\nnamespace internal {\n\ntemplate<typename Scalar_, int Options_, typename Index_>\nstruct evaluator<SparseVector<Scalar_,Options_,Index_> >\n  : evaluator_base<SparseVector<Scalar_,Options_,Index_> >\n{\n  typedef SparseVector<Scalar_,Options_,Index_> SparseVectorType;\n  typedef evaluator_base<SparseVectorType> Base;\n  typedef typename SparseVectorType::InnerIterator InnerIterator;\n  typedef typename SparseVectorType::ReverseInnerIterator ReverseInnerIterator;\n  \n  enum {\n    CoeffReadCost = NumTraits<Scalar_>::ReadCost,\n    Flags = SparseVectorType::Flags\n  };\n\n  evaluator() : Base() {}\n  \n  explicit evaluator(const SparseVectorType &mat) : m_matrix(&mat)\n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n  \n  inline Index nonZerosEstimate() const {\n    return m_matrix->nonZeros();\n  }\n  \n  operator SparseVectorType&() { return m_matrix->const_cast_derived(); }\n  operator const SparseVectorType&() const { return *m_matrix; }\n  \n  const SparseVectorType *m_matrix;\n};\n\ntemplate< typename Dest, typename Src>\nstruct sparse_vector_assign_selector<Dest,Src,SVA_Inner> {\n  static void run(Dest& dst, const Src& src) {\n    eigen_internal_assert(src.innerSize()==src.size());\n    typedef internal::evaluator<Src> SrcEvaluatorType;\n    SrcEvaluatorType srcEval(src);\n    for(typename SrcEvaluatorType::InnerIterator it(srcEval, 0); it; ++it)\n      dst.insert(it.index()) = it.value();\n  }\n};\n\ntemplate< typename Dest, typename Src>\nstruct sparse_vector_assign_selector<Dest,Src,SVA_Outer> {\n  static void run(Dest& dst, const Src& src) {\n    eigen_internal_assert(src.outerSize()==src.size());\n    typedef internal::evaluator<Src> SrcEvaluatorType;\n    SrcEvaluatorType srcEval(src);\n    for(Index i=0; i<src.size(); ++i)\n    {\n      typename SrcEvaluatorType::InnerIterator it(srcEval, i);\n      if(it)\n        dst.insert(i) = it.value();\n    }\n  }\n};\n\ntemplate< typename Dest, typename Src>\nstruct sparse_vector_assign_selector<Dest,Src,SVA_RuntimeSwitch> {\n  static void run(Dest& dst, const Src& src) {\n    if(src.outerSize()==1)  sparse_vector_assign_selector<Dest,Src,SVA_Inner>::run(dst, src);\n    else                    sparse_vector_assign_selector<Dest,Src,SVA_Outer>::run(dst, src);\n  }\n};\n\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSEVECTOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/SparseView.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010 Daniel Lowengrub <lowdanie@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEVIEW_H\n#define EIGEN_SPARSEVIEW_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate<typename MatrixType>\nstruct traits<SparseView<MatrixType> > : traits<MatrixType>\n{\n  typedef typename MatrixType::StorageIndex StorageIndex;\n  typedef Sparse StorageKind;\n  enum {\n    Flags = int(traits<MatrixType>::Flags) & (RowMajorBit)\n  };\n};\n\n} // end namespace internal\n\n/** \\ingroup SparseCore_Module\n  * \\class SparseView\n  *\n  * \\brief Expression of a dense or sparse matrix with zero or too small values removed\n  *\n  * \\tparam MatrixType the type of the object of which we are removing the small entries\n  *\n  * This class represents an expression of a given dense or sparse matrix with\n  * entries smaller than \\c reference * \\c epsilon are removed.\n  * It is the return type of MatrixBase::sparseView() and SparseMatrixBase::pruned()\n  * and most of the time this is the only way it is used.\n  *\n  * \\sa MatrixBase::sparseView(), SparseMatrixBase::pruned()\n  */\ntemplate<typename MatrixType>\nclass SparseView : public SparseMatrixBase<SparseView<MatrixType> >\n{\n  typedef typename MatrixType::Nested MatrixTypeNested;\n  typedef typename internal::remove_all<MatrixTypeNested>::type _MatrixTypeNested;\n  typedef SparseMatrixBase<SparseView > Base;\npublic:\n  EIGEN_SPARSE_PUBLIC_INTERFACE(SparseView)\n  typedef typename internal::remove_all<MatrixType>::type NestedExpression;\n\n  explicit SparseView(const MatrixType& mat, const Scalar& reference = Scalar(0),\n                      const RealScalar &epsilon = NumTraits<Scalar>::dummy_precision())\n    : m_matrix(mat), m_reference(reference), m_epsilon(epsilon) {}\n\n  inline Index rows() const { return m_matrix.rows(); }\n  inline Index cols() const { return m_matrix.cols(); }\n\n  inline Index innerSize() const { return m_matrix.innerSize(); }\n  inline Index outerSize() const { return m_matrix.outerSize(); }\n  \n  /** \\returns the nested expression */\n  const typename internal::remove_all<MatrixTypeNested>::type&\n  nestedExpression() const { return m_matrix; }\n  \n  Scalar reference() const { return m_reference; }\n  RealScalar epsilon() const { return m_epsilon; }\n  \nprotected:\n  MatrixTypeNested m_matrix;\n  Scalar m_reference;\n  RealScalar m_epsilon;\n};\n\nnamespace internal {\n\n// TODO find a way to unify the two following variants\n// This is tricky because implementing an inner iterator on top of an IndexBased evaluator is\n// not easy because the evaluators do not expose the sizes of the underlying expression.\n  \ntemplate<typename ArgType>\nstruct unary_evaluator<SparseView<ArgType>, IteratorBased>\n  : public evaluator_base<SparseView<ArgType> >\n{\n    typedef typename evaluator<ArgType>::InnerIterator EvalIterator;\n  public:\n    typedef SparseView<ArgType> XprType;\n    \n    class InnerIterator : public EvalIterator\n    {\n      protected:\n        typedef typename XprType::Scalar Scalar;\n      public:\n\n        EIGEN_STRONG_INLINE InnerIterator(const unary_evaluator& sve, Index outer)\n          : EvalIterator(sve.m_argImpl,outer), m_view(sve.m_view)\n        {\n          incrementToNonZero();\n        }\n\n        EIGEN_STRONG_INLINE InnerIterator& operator++()\n        {\n          EvalIterator::operator++();\n          incrementToNonZero();\n          return *this;\n        }\n\n        using EvalIterator::value;\n\n      protected:\n        const XprType &m_view;\n\n      private:\n        void incrementToNonZero()\n        {\n          while((bool(*this)) && internal::isMuchSmallerThan(value(), m_view.reference(), m_view.epsilon()))\n          {\n            EvalIterator::operator++();\n          }\n        }\n    };\n    \n    enum {\n      CoeffReadCost = evaluator<ArgType>::CoeffReadCost,\n      Flags = XprType::Flags\n    };\n    \n    explicit unary_evaluator(const XprType& xpr) : m_argImpl(xpr.nestedExpression()), m_view(xpr) {}\n\n  protected:\n    evaluator<ArgType> m_argImpl;\n    const XprType &m_view;\n};\n\ntemplate<typename ArgType>\nstruct unary_evaluator<SparseView<ArgType>, IndexBased>\n  : public evaluator_base<SparseView<ArgType> >\n{\n  public:\n    typedef SparseView<ArgType> XprType;\n  protected:\n    enum { IsRowMajor = (XprType::Flags&RowMajorBit)==RowMajorBit };\n    typedef typename XprType::Scalar Scalar;\n    typedef typename XprType::StorageIndex StorageIndex;\n  public:\n    \n    class InnerIterator\n    {\n      public:\n\n        EIGEN_STRONG_INLINE InnerIterator(const unary_evaluator& sve, Index outer)\n          : m_sve(sve), m_inner(0), m_outer(outer), m_end(sve.m_view.innerSize())\n        {\n          incrementToNonZero();\n        }\n\n        EIGEN_STRONG_INLINE InnerIterator& operator++()\n        {\n          m_inner++;\n          incrementToNonZero();\n          return *this;\n        }\n\n        EIGEN_STRONG_INLINE Scalar value() const\n        {\n          return (IsRowMajor) ? m_sve.m_argImpl.coeff(m_outer, m_inner)\n                              : m_sve.m_argImpl.coeff(m_inner, m_outer);\n        }\n\n        EIGEN_STRONG_INLINE StorageIndex index() const { return m_inner; }\n        inline Index row() const { return IsRowMajor ? m_outer : index(); }\n        inline Index col() const { return IsRowMajor ? index() : m_outer; }\n\n        EIGEN_STRONG_INLINE operator bool() const { return m_inner < m_end && m_inner>=0; }\n\n      protected:\n        const unary_evaluator &m_sve;\n        Index m_inner;\n        const Index m_outer;\n        const Index m_end;\n\n      private:\n        void incrementToNonZero()\n        {\n          while((bool(*this)) && internal::isMuchSmallerThan(value(), m_sve.m_view.reference(), m_sve.m_view.epsilon()))\n          {\n            m_inner++;\n          }\n        }\n    };\n    \n    enum {\n      CoeffReadCost = evaluator<ArgType>::CoeffReadCost,\n      Flags = XprType::Flags\n    };\n    \n    explicit unary_evaluator(const XprType& xpr) : m_argImpl(xpr.nestedExpression()), m_view(xpr) {}\n\n  protected:\n    evaluator<ArgType> m_argImpl;\n    const XprType &m_view;\n};\n\n} // end namespace internal\n\n/** \\ingroup SparseCore_Module\n  *\n  * \\returns a sparse expression of the dense expression \\c *this with values smaller than\n  * \\a reference * \\a epsilon removed.\n  *\n  * This method is typically used when prototyping to convert a quickly assembled dense Matrix \\c D to a SparseMatrix \\c S:\n  * \\code\n  * MatrixXd D(n,m);\n  * SparseMatrix<double> S;\n  * S = D.sparseView();             // suppress numerical zeros (exact)\n  * S = D.sparseView(reference);\n  * S = D.sparseView(reference,epsilon);\n  * \\endcode\n  * where \\a reference is a meaningful non zero reference value,\n  * and \\a epsilon is a tolerance factor defaulting to NumTraits<Scalar>::dummy_precision().\n  *\n  * \\sa SparseMatrixBase::pruned(), class SparseView */\ntemplate<typename Derived>\nconst SparseView<Derived> MatrixBase<Derived>::sparseView(const Scalar& reference,\n                                                          const typename NumTraits<Scalar>::Real& epsilon) const\n{\n  return SparseView<Derived>(derived(), reference, epsilon);\n}\n\n/** \\returns an expression of \\c *this with values smaller than\n  * \\a reference * \\a epsilon removed.\n  *\n  * This method is typically used in conjunction with the product of two sparse matrices\n  * to automatically prune the smallest values as follows:\n  * \\code\n  * C = (A*B).pruned();             // suppress numerical zeros (exact)\n  * C = (A*B).pruned(ref);\n  * C = (A*B).pruned(ref,epsilon);\n  * \\endcode\n  * where \\c ref is a meaningful non zero reference value.\n  * */\ntemplate<typename Derived>\nconst SparseView<Derived>\nSparseMatrixBase<Derived>::pruned(const Scalar& reference,\n                                  const RealScalar& epsilon) const\n{\n  return SparseView<Derived>(derived(), reference, epsilon);\n}\n\n} // end namespace Eigen\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseCore/TriangularSolver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSETRIANGULARSOLVER_H\n#define EIGEN_SPARSETRIANGULARSOLVER_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate<typename Lhs, typename Rhs, int Mode,\n  int UpLo = (Mode & Lower)\n           ? Lower\n           : (Mode & Upper)\n           ? Upper\n           : -1,\n  int StorageOrder = int(traits<Lhs>::Flags) & RowMajorBit>\nstruct sparse_solve_triangular_selector;\n\n// forward substitution, row-major\ntemplate<typename Lhs, typename Rhs, int Mode>\nstruct sparse_solve_triangular_selector<Lhs,Rhs,Mode,Lower,RowMajor>\n{\n  typedef typename Rhs::Scalar Scalar;\n  typedef evaluator<Lhs> LhsEval;\n  typedef typename evaluator<Lhs>::InnerIterator LhsIterator;\n  static void run(const Lhs& lhs, Rhs& other)\n  {\n    LhsEval lhsEval(lhs);\n    for(Index col=0 ; col<other.cols() ; ++col)\n    {\n      for(Index i=0; i<lhs.rows(); ++i)\n      {\n        Scalar tmp = other.coeff(i,col);\n        Scalar lastVal(0);\n        Index lastIndex = 0;\n        for(LhsIterator it(lhsEval, i); it; ++it)\n        {\n          lastVal = it.value();\n          lastIndex = it.index();\n          if(lastIndex==i)\n            break;\n          tmp -= lastVal * other.coeff(lastIndex,col);\n        }\n        if (Mode & UnitDiag)\n          other.coeffRef(i,col) = tmp;\n        else\n        {\n          eigen_assert(lastIndex==i);\n          other.coeffRef(i,col) = tmp/lastVal;\n        }\n      }\n    }\n  }\n};\n\n// backward substitution, row-major\ntemplate<typename Lhs, typename Rhs, int Mode>\nstruct sparse_solve_triangular_selector<Lhs,Rhs,Mode,Upper,RowMajor>\n{\n  typedef typename Rhs::Scalar Scalar;\n  typedef evaluator<Lhs> LhsEval;\n  typedef typename evaluator<Lhs>::InnerIterator LhsIterator;\n  static void run(const Lhs& lhs, Rhs& other)\n  {\n    LhsEval lhsEval(lhs);\n    for(Index col=0 ; col<other.cols() ; ++col)\n    {\n      for(Index i=lhs.rows()-1 ; i>=0 ; --i)\n      {\n        Scalar tmp = other.coeff(i,col);\n        Scalar l_ii(0);\n        LhsIterator it(lhsEval, i);\n        while(it && it.index()<i)\n          ++it;\n        if(!(Mode & UnitDiag))\n        {\n          eigen_assert(it && it.index()==i);\n          l_ii = it.value();\n          ++it;\n        }\n        else if (it && it.index() == i)\n          ++it;\n        for(; it; ++it)\n        {\n          tmp -= it.value() * other.coeff(it.index(),col);\n        }\n\n        if (Mode & UnitDiag)  other.coeffRef(i,col) = tmp;\n        else                  other.coeffRef(i,col) = tmp/l_ii;\n      }\n    }\n  }\n};\n\n// forward substitution, col-major\ntemplate<typename Lhs, typename Rhs, int Mode>\nstruct sparse_solve_triangular_selector<Lhs,Rhs,Mode,Lower,ColMajor>\n{\n  typedef typename Rhs::Scalar Scalar;\n  typedef evaluator<Lhs> LhsEval;\n  typedef typename evaluator<Lhs>::InnerIterator LhsIterator;\n  static void run(const Lhs& lhs, Rhs& other)\n  {\n    LhsEval lhsEval(lhs);\n    for(Index col=0 ; col<other.cols() ; ++col)\n    {\n      for(Index i=0; i<lhs.cols(); ++i)\n      {\n        Scalar& tmp = other.coeffRef(i,col);\n        if (tmp!=Scalar(0)) // optimization when other is actually sparse\n        {\n          LhsIterator it(lhsEval, i);\n          while(it && it.index()<i)\n            ++it;\n          if(!(Mode & UnitDiag))\n          {\n            eigen_assert(it && it.index()==i);\n            tmp /= it.value();\n          }\n          if (it && it.index()==i)\n            ++it;\n          for(; it; ++it)\n            other.coeffRef(it.index(), col) -= tmp * it.value();\n        }\n      }\n    }\n  }\n};\n\n// backward substitution, col-major\ntemplate<typename Lhs, typename Rhs, int Mode>\nstruct sparse_solve_triangular_selector<Lhs,Rhs,Mode,Upper,ColMajor>\n{\n  typedef typename Rhs::Scalar Scalar;\n  typedef evaluator<Lhs> LhsEval;\n  typedef typename evaluator<Lhs>::InnerIterator LhsIterator;\n  static void run(const Lhs& lhs, Rhs& other)\n  {\n    LhsEval lhsEval(lhs);\n    for(Index col=0 ; col<other.cols() ; ++col)\n    {\n      for(Index i=lhs.cols()-1; i>=0; --i)\n      {\n        Scalar& tmp = other.coeffRef(i,col);\n        if (tmp!=Scalar(0)) // optimization when other is actually sparse\n        {\n          if(!(Mode & UnitDiag))\n          {\n            // TODO replace this by a binary search. make sure the binary search is safe for partially sorted elements\n            LhsIterator it(lhsEval, i);\n            while(it && it.index()!=i)\n              ++it;\n            eigen_assert(it && it.index()==i);\n            other.coeffRef(i,col) /= it.value();\n          }\n          LhsIterator it(lhsEval, i);\n          for(; it && it.index()<i; ++it)\n            other.coeffRef(it.index(), col) -= tmp * it.value();\n        }\n      }\n    }\n  }\n};\n\n} // end namespace internal\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n\ntemplate<typename ExpressionType,unsigned int Mode>\ntemplate<typename OtherDerived>\nvoid TriangularViewImpl<ExpressionType,Mode,Sparse>::solveInPlace(MatrixBase<OtherDerived>& other) const\n{\n  eigen_assert(derived().cols() == derived().rows() && derived().cols() == other.rows());\n  eigen_assert((!(Mode & ZeroDiag)) && bool(Mode & (Upper|Lower)));\n\n  enum { copy = internal::traits<OtherDerived>::Flags & RowMajorBit };\n\n  typedef typename internal::conditional<copy,\n    typename internal::plain_matrix_type_column_major<OtherDerived>::type, OtherDerived&>::type OtherCopy;\n  OtherCopy otherCopy(other.derived());\n\n  internal::sparse_solve_triangular_selector<ExpressionType, typename internal::remove_reference<OtherCopy>::type, Mode>::run(derived().nestedExpression(), otherCopy);\n\n  if (copy)\n    other = otherCopy;\n}\n#endif\n\n// pure sparse path\n\nnamespace internal {\n\ntemplate<typename Lhs, typename Rhs, int Mode,\n  int UpLo = (Mode & Lower)\n           ? Lower\n           : (Mode & Upper)\n           ? Upper\n           : -1,\n  int StorageOrder = int(Lhs::Flags) & (RowMajorBit)>\nstruct sparse_solve_triangular_sparse_selector;\n\n// forward substitution, col-major\ntemplate<typename Lhs, typename Rhs, int Mode, int UpLo>\nstruct sparse_solve_triangular_sparse_selector<Lhs,Rhs,Mode,UpLo,ColMajor>\n{\n  typedef typename Rhs::Scalar Scalar;\n  typedef typename promote_index_type<typename traits<Lhs>::StorageIndex,\n                                      typename traits<Rhs>::StorageIndex>::type StorageIndex;\n  static void run(const Lhs& lhs, Rhs& other)\n  {\n    const bool IsLower = (UpLo==Lower);\n    AmbiVector<Scalar,StorageIndex> tempVector(other.rows()*2);\n    tempVector.setBounds(0,other.rows());\n\n    Rhs res(other.rows(), other.cols());\n    res.reserve(other.nonZeros());\n\n    for(Index col=0 ; col<other.cols() ; ++col)\n    {\n      // FIXME estimate number of non zeros\n      tempVector.init(.99/*float(other.col(col).nonZeros())/float(other.rows())*/);\n      tempVector.setZero();\n      tempVector.restart();\n      for (typename Rhs::InnerIterator rhsIt(other, col); rhsIt; ++rhsIt)\n      {\n        tempVector.coeffRef(rhsIt.index()) = rhsIt.value();\n      }\n\n      for(Index i=IsLower?0:lhs.cols()-1;\n          IsLower?i<lhs.cols():i>=0;\n          i+=IsLower?1:-1)\n      {\n        tempVector.restart();\n        Scalar& ci = tempVector.coeffRef(i);\n        if (ci!=Scalar(0))\n        {\n          // find\n          typename Lhs::InnerIterator it(lhs, i);\n          if(!(Mode & UnitDiag))\n          {\n            if (IsLower)\n            {\n              eigen_assert(it.index()==i);\n              ci /= it.value();\n            }\n            else\n              ci /= lhs.coeff(i,i);\n          }\n          tempVector.restart();\n          if (IsLower)\n          {\n            if (it.index()==i)\n              ++it;\n            for(; it; ++it)\n              tempVector.coeffRef(it.index()) -= ci * it.value();\n          }\n          else\n          {\n            for(; it && it.index()<i; ++it)\n              tempVector.coeffRef(it.index()) -= ci * it.value();\n          }\n        }\n      }\n\n\n      Index count = 0;\n      // FIXME compute a reference value to filter zeros\n      for (typename AmbiVector<Scalar,StorageIndex>::Iterator it(tempVector/*,1e-12*/); it; ++it)\n      {\n        ++ count;\n//         std::cerr << \"fill \" << it.index() << \", \" << col << \"\\n\";\n//         std::cout << it.value() << \"  \";\n        // FIXME use insertBack\n        res.insert(it.index(), col) = it.value();\n      }\n//       std::cout << \"tempVector.nonZeros() == \" << int(count) << \" / \" << (other.rows()) << \"\\n\";\n    }\n    res.finalize();\n    other = res.markAsRValue();\n  }\n};\n\n} // end namespace internal\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename ExpressionType,unsigned int Mode>\ntemplate<typename OtherDerived>\nvoid TriangularViewImpl<ExpressionType,Mode,Sparse>::solveInPlace(SparseMatrixBase<OtherDerived>& other) const\n{\n  eigen_assert(derived().cols() == derived().rows() && derived().cols() == other.rows());\n  eigen_assert( (!(Mode & ZeroDiag)) && bool(Mode & (Upper|Lower)));\n\n//   enum { copy = internal::traits<OtherDerived>::Flags & RowMajorBit };\n\n//   typedef typename internal::conditional<copy,\n//     typename internal::plain_matrix_type_column_major<OtherDerived>::type, OtherDerived&>::type OtherCopy;\n//   OtherCopy otherCopy(other.derived());\n\n  internal::sparse_solve_triangular_sparse_selector<ExpressionType, OtherDerived, Mode>::run(derived().nestedExpression(), other.derived());\n\n//   if (copy)\n//     other = otherCopy;\n}\n#endif\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSETRIANGULARSOLVER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseLU/SparseLU.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2012-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#ifndef EIGEN_SPARSE_LU_H\n#define EIGEN_SPARSE_LU_H\n\nnamespace Eigen {\n\ntemplate <typename MatrixType_, typename OrderingType_ = COLAMDOrdering<typename MatrixType_::StorageIndex> > class SparseLU;\ntemplate <typename MappedSparseMatrixType> struct SparseLUMatrixLReturnType;\ntemplate <typename MatrixLType, typename MatrixUType> struct SparseLUMatrixUReturnType;\n\ntemplate <bool Conjugate,class SparseLUType>\nclass SparseLUTransposeView : public SparseSolverBase<SparseLUTransposeView<Conjugate,SparseLUType> >\n{\nprotected:\n  typedef SparseSolverBase<SparseLUTransposeView<Conjugate,SparseLUType> > APIBase;\n  using APIBase::m_isInitialized;\npublic:\n  typedef typename SparseLUType::Scalar Scalar;\n  typedef typename SparseLUType::StorageIndex StorageIndex;\n  typedef typename SparseLUType::MatrixType MatrixType;\n  typedef typename SparseLUType::OrderingType OrderingType;\n\n  enum {\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n    MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n  };\n\n  SparseLUTransposeView() : m_sparseLU(NULL) {}\n  SparseLUTransposeView(const SparseLUTransposeView& view) {\n    this->m_sparseLU = view.m_sparseLU;\n  }\n  void setIsInitialized(const bool isInitialized) {this->m_isInitialized = isInitialized;}\n  void setSparseLU(SparseLUType* sparseLU) {m_sparseLU = sparseLU;}\n  using APIBase::_solve_impl;\n  template<typename Rhs, typename Dest>\n  bool _solve_impl(const MatrixBase<Rhs> &B, MatrixBase<Dest> &X_base) const\n  {\n    Dest& X(X_base.derived());\n    eigen_assert(m_sparseLU->info() == Success && \"The matrix should be factorized first\");\n    EIGEN_STATIC_ASSERT((Dest::Flags&RowMajorBit)==0,\n                        THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES);\n\n\n    // this ugly const_cast_derived() helps to detect aliasing when applying the permutations\n    for(Index j = 0; j < B.cols(); ++j){\n      X.col(j) = m_sparseLU->colsPermutation() * B.const_cast_derived().col(j);\n    }\n    //Forward substitution with transposed or adjoint of U\n    m_sparseLU->matrixU().template solveTransposedInPlace<Conjugate>(X);\n\n    //Backward substitution with transposed or adjoint of L\n    m_sparseLU->matrixL().template solveTransposedInPlace<Conjugate>(X);\n\n    // Permute back the solution\n    for (Index j = 0; j < B.cols(); ++j)\n      X.col(j) = m_sparseLU->rowsPermutation().transpose() * X.col(j);\n    return true;\n  }\n  inline Index rows() const { return m_sparseLU->rows(); }\n  inline Index cols() const { return m_sparseLU->cols(); }\n\nprivate:\n  SparseLUType *m_sparseLU;\n  SparseLUTransposeView& operator=(const SparseLUTransposeView&);\n};\n\n\n/** \\ingroup SparseLU_Module\n  * \\class SparseLU\n  * \n  * \\brief Sparse supernodal LU factorization for general matrices\n  * \n  * This class implements the supernodal LU factorization for general matrices.\n  * It uses the main techniques from the sequential SuperLU package \n  * (http://crd-legacy.lbl.gov/~xiaoye/SuperLU/). It handles transparently real \n  * and complex arithmetic with single and double precision, depending on the \n  * scalar type of your input matrix. \n  * The code has been optimized to provide BLAS-3 operations during supernode-panel updates. \n  * It benefits directly from the built-in high-performant Eigen BLAS routines. \n  * Moreover, when the size of a supernode is very small, the BLAS calls are avoided to \n  * enable a better optimization from the compiler. For best performance, \n  * you should compile it with NDEBUG flag to avoid the numerous bounds checking on vectors. \n  * \n  * An important parameter of this class is the ordering method. It is used to reorder the columns \n  * (and eventually the rows) of the matrix to reduce the number of new elements that are created during \n  * numerical factorization. The cheapest method available is COLAMD. \n  * See  \\link OrderingMethods_Module the OrderingMethods module \\endlink for the list of \n  * built-in and external ordering methods. \n  *\n  * Simple example with key steps \n  * \\code\n  * VectorXd x(n), b(n);\n  * SparseMatrix<double> A;\n  * SparseLU<SparseMatrix<double>, COLAMDOrdering<int> >   solver;\n  * // fill A and b;\n  * // Compute the ordering permutation vector from the structural pattern of A\n  * solver.analyzePattern(A); \n  * // Compute the numerical factorization \n  * solver.factorize(A); \n  * //Use the factors to solve the linear system \n  * x = solver.solve(b); \n  * \\endcode\n  * \n  * \\warning The input matrix A should be in a \\b compressed and \\b column-major form.\n  * Otherwise an expensive copy will be made. You can call the inexpensive makeCompressed() to get a compressed matrix.\n  * \n  * \\note Unlike the initial SuperLU implementation, there is no step to equilibrate the matrix. \n  * For badly scaled matrices, this step can be useful to reduce the pivoting during factorization. \n  * If this is the case for your matrices, you can try the basic scaling method at\n  *  \"unsupported/Eigen/src/IterativeSolvers/Scaling.h\"\n  * \n  * \\tparam MatrixType_ The type of the sparse matrix. It must be a column-major SparseMatrix<>\n  * \\tparam OrderingType_ The ordering method to use, either AMD, COLAMD or METIS. Default is COLMAD\n  *\n  * \\implsparsesolverconcept\n  * \n  * \\sa \\ref TutorialSparseSolverConcept\n  * \\sa \\ref OrderingMethods_Module\n  */\ntemplate <typename MatrixType_, typename OrderingType_>\nclass SparseLU : public SparseSolverBase<SparseLU<MatrixType_,OrderingType_> >, public internal::SparseLUImpl<typename MatrixType_::Scalar, typename MatrixType_::StorageIndex>\n{\n  protected:\n    typedef SparseSolverBase<SparseLU<MatrixType_,OrderingType_> > APIBase;\n    using APIBase::m_isInitialized;\n  public:\n    using APIBase::_solve_impl;\n    \n    typedef MatrixType_ MatrixType;\n    typedef OrderingType_ OrderingType;\n    typedef typename MatrixType::Scalar Scalar; \n    typedef typename MatrixType::RealScalar RealScalar; \n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> NCMatrix;\n    typedef internal::MappedSuperNodalMatrix<Scalar, StorageIndex> SCMatrix;\n    typedef Matrix<Scalar,Dynamic,1> ScalarVector;\n    typedef Matrix<StorageIndex,Dynamic,1> IndexVector;\n    typedef PermutationMatrix<Dynamic, Dynamic, StorageIndex> PermutationType;\n    typedef internal::SparseLUImpl<Scalar, StorageIndex> Base;\n\n    enum {\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n    \n  public:\n\n    SparseLU():m_lastError(\"\"),m_Ustore(0,0,0,0,0,0),m_symmetricmode(false),m_diagpivotthresh(1.0),m_detPermR(1)\n    {\n      initperfvalues(); \n    }\n    explicit SparseLU(const MatrixType& matrix)\n      : m_lastError(\"\"),m_Ustore(0,0,0,0,0,0),m_symmetricmode(false),m_diagpivotthresh(1.0),m_detPermR(1)\n    {\n      initperfvalues(); \n      compute(matrix);\n    }\n    \n    ~SparseLU()\n    {\n      // Free all explicit dynamic pointers \n    }\n    \n    void analyzePattern (const MatrixType& matrix);\n    void factorize (const MatrixType& matrix);\n    void simplicialfactorize(const MatrixType& matrix);\n    \n    /**\n      * Compute the symbolic and numeric factorization of the input sparse matrix.\n      * The input matrix should be in column-major storage. \n      */\n    void compute (const MatrixType& matrix)\n    {\n      // Analyze \n      analyzePattern(matrix); \n      //Factorize\n      factorize(matrix);\n    } \n\n    /** \\returns an expression of the transposed of the factored matrix.\n      *\n      * A typical usage is to solve for the transposed problem A^T x = b:\n      * \\code\n      * solver.compute(A);\n      * x = solver.transpose().solve(b);\n      * \\endcode\n      *\n      * \\sa adjoint(), solve()\n      */\n    const SparseLUTransposeView<false,SparseLU<MatrixType_,OrderingType_> > transpose()\n    {\n      SparseLUTransposeView<false,  SparseLU<MatrixType_,OrderingType_> > transposeView;\n      transposeView.setSparseLU(this);\n      transposeView.setIsInitialized(this->m_isInitialized);\n      return transposeView;\n    }\n\n\n    /** \\returns an expression of the adjoint of the factored matrix\n      *\n      * A typical usage is to solve for the adjoint problem A' x = b:\n      * \\code\n      * solver.compute(A);\n      * x = solver.adjoint().solve(b);\n      * \\endcode\n      *\n      * For real scalar types, this function is equivalent to transpose().\n      *\n      * \\sa transpose(), solve()\n      */\n    const SparseLUTransposeView<true, SparseLU<MatrixType_,OrderingType_> > adjoint()\n    {\n      SparseLUTransposeView<true,  SparseLU<MatrixType_,OrderingType_> > adjointView;\n      adjointView.setSparseLU(this);\n      adjointView.setIsInitialized(this->m_isInitialized);\n      return adjointView;\n    }\n    \n    inline Index rows() const { return m_mat.rows(); }\n    inline Index cols() const { return m_mat.cols(); }\n    /** Indicate that the pattern of the input matrix is symmetric */\n    void isSymmetric(bool sym)\n    {\n      m_symmetricmode = sym;\n    }\n    \n    /** \\returns an expression of the matrix L, internally stored as supernodes\n      * The only operation available with this expression is the triangular solve\n      * \\code\n      * y = b; matrixL().solveInPlace(y);\n      * \\endcode\n      */\n    SparseLUMatrixLReturnType<SCMatrix> matrixL() const\n    {\n      return SparseLUMatrixLReturnType<SCMatrix>(m_Lstore);\n    }\n    /** \\returns an expression of the matrix U,\n      * The only operation available with this expression is the triangular solve\n      * \\code\n      * y = b; matrixU().solveInPlace(y);\n      * \\endcode\n      */\n    SparseLUMatrixUReturnType<SCMatrix,MappedSparseMatrix<Scalar,ColMajor,StorageIndex> > matrixU() const\n    {\n      return SparseLUMatrixUReturnType<SCMatrix, MappedSparseMatrix<Scalar,ColMajor,StorageIndex> >(m_Lstore, m_Ustore);\n    }\n\n    /**\n      * \\returns a reference to the row matrix permutation \\f$ P_r \\f$ such that \\f$P_r A P_c^T = L U\\f$\n      * \\sa colsPermutation()\n      */\n    inline const PermutationType& rowsPermutation() const\n    {\n      return m_perm_r;\n    }\n    /**\n      * \\returns a reference to the column matrix permutation\\f$ P_c^T \\f$ such that \\f$P_r A P_c^T = L U\\f$\n      * \\sa rowsPermutation()\n      */\n    inline const PermutationType& colsPermutation() const\n    {\n      return m_perm_c;\n    }\n    /** Set the threshold used for a diagonal entry to be an acceptable pivot. */\n    void setPivotThreshold(const RealScalar& thresh)\n    {\n      m_diagpivotthresh = thresh; \n    }\n\n#ifdef EIGEN_PARSED_BY_DOXYGEN\n    /** \\returns the solution X of \\f$ A X = B \\f$ using the current decomposition of A.\n      *\n      * \\warning the destination matrix X in X = this->solve(B) must be colmun-major.\n      *\n      * \\sa compute()\n      */\n    template<typename Rhs>\n    inline const Solve<SparseLU, Rhs> solve(const MatrixBase<Rhs>& B) const;\n#endif // EIGEN_PARSED_BY_DOXYGEN\n    \n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the LU factorization reports a problem, zero diagonal for instance\n      *          \\c InvalidInput if the input matrix is invalid\n      *\n      * \\sa iparm()          \n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_info;\n    }\n    \n    /**\n      * \\returns A string describing the type of error\n      */\n    std::string lastErrorMessage() const\n    {\n      return m_lastError; \n    }\n\n    template<typename Rhs, typename Dest>\n    bool _solve_impl(const MatrixBase<Rhs> &B, MatrixBase<Dest> &X_base) const\n    {\n      Dest& X(X_base.derived());\n      eigen_assert(m_factorizationIsOk && \"The matrix should be factorized first\");\n      EIGEN_STATIC_ASSERT((Dest::Flags&RowMajorBit)==0,\n                        THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES);\n      \n      // Permute the right hand side to form X = Pr*B\n      // on return, X is overwritten by the computed solution\n      X.resize(B.rows(),B.cols());\n\n      // this ugly const_cast_derived() helps to detect aliasing when applying the permutations\n      for(Index j = 0; j < B.cols(); ++j)\n        X.col(j) = rowsPermutation() * B.const_cast_derived().col(j);\n      \n      //Forward substitution with L\n      this->matrixL().solveInPlace(X);\n      this->matrixU().solveInPlace(X);\n      \n      // Permute back the solution \n      for (Index j = 0; j < B.cols(); ++j)\n        X.col(j) = colsPermutation().inverse() * X.col(j);\n      \n      return true; \n    }\n    \n    /**\n      * \\returns the absolute value of the determinant of the matrix of which\n      * *this is the QR decomposition.\n      *\n      * \\warning a determinant can be very big or small, so for matrices\n      * of large enough dimension, there is a risk of overflow/underflow.\n      * One way to work around that is to use logAbsDeterminant() instead.\n      *\n      * \\sa logAbsDeterminant(), signDeterminant()\n      */\n    Scalar absDeterminant()\n    {\n      using std::abs;\n      eigen_assert(m_factorizationIsOk && \"The matrix should be factorized first.\");\n      // Initialize with the determinant of the row matrix\n      Scalar det = Scalar(1.);\n      // Note that the diagonal blocks of U are stored in supernodes,\n      // which are available in the  L part :)\n      for (Index j = 0; j < this->cols(); ++j)\n      {\n        for (typename SCMatrix::InnerIterator it(m_Lstore, j); it; ++it)\n        {\n          if(it.index() == j)\n          {\n            det *= abs(it.value());\n            break;\n          }\n        }\n      }\n      return det;\n    }\n\n    /** \\returns the natural log of the absolute value of the determinant of the matrix\n      * of which **this is the QR decomposition\n      *\n      * \\note This method is useful to work around the risk of overflow/underflow that's\n      * inherent to the determinant computation.\n      *\n      * \\sa absDeterminant(), signDeterminant()\n      */\n    Scalar logAbsDeterminant() const\n    {\n      using std::log;\n      using std::abs;\n\n      eigen_assert(m_factorizationIsOk && \"The matrix should be factorized first.\");\n      Scalar det = Scalar(0.);\n      for (Index j = 0; j < this->cols(); ++j)\n      {\n        for (typename SCMatrix::InnerIterator it(m_Lstore, j); it; ++it)\n        {\n          if(it.row() < j) continue;\n          if(it.row() == j)\n          {\n            det += log(abs(it.value()));\n            break;\n          }\n        }\n      }\n      return det;\n    }\n\n    /** \\returns A number representing the sign of the determinant\n      *\n      * \\sa absDeterminant(), logAbsDeterminant()\n      */\n    Scalar signDeterminant()\n    {\n      eigen_assert(m_factorizationIsOk && \"The matrix should be factorized first.\");\n      // Initialize with the determinant of the row matrix\n      Index det = 1;\n      // Note that the diagonal blocks of U are stored in supernodes,\n      // which are available in the  L part :)\n      for (Index j = 0; j < this->cols(); ++j)\n      {\n        for (typename SCMatrix::InnerIterator it(m_Lstore, j); it; ++it)\n        {\n          if(it.index() == j)\n          {\n            if(it.value()<0)\n              det = -det;\n            else if(it.value()==0)\n              return 0;\n            break;\n          }\n        }\n      }\n      return det * m_detPermR * m_detPermC;\n    }\n    \n    /** \\returns The determinant of the matrix.\n      *\n      * \\sa absDeterminant(), logAbsDeterminant()\n      */\n    Scalar determinant()\n    {\n      eigen_assert(m_factorizationIsOk && \"The matrix should be factorized first.\");\n      // Initialize with the determinant of the row matrix\n      Scalar det = Scalar(1.);\n      // Note that the diagonal blocks of U are stored in supernodes,\n      // which are available in the  L part :)\n      for (Index j = 0; j < this->cols(); ++j)\n      {\n        for (typename SCMatrix::InnerIterator it(m_Lstore, j); it; ++it)\n        {\n          if(it.index() == j)\n          {\n            det *= it.value();\n            break;\n          }\n        }\n      }\n      return (m_detPermR * m_detPermC) > 0 ? det : -det;\n    }\n\n    Index nnzL() const { return m_nnzL; };\n    Index nnzU() const { return m_nnzU; };\n\n  protected:\n    // Functions \n    void initperfvalues()\n    {\n      m_perfv.panel_size = 16;\n      m_perfv.relax = 1; \n      m_perfv.maxsuper = 128; \n      m_perfv.rowblk = 16; \n      m_perfv.colblk = 8; \n      m_perfv.fillfactor = 20;  \n    }\n      \n    // Variables \n    mutable ComputationInfo m_info;\n    bool m_factorizationIsOk;\n    bool m_analysisIsOk;\n    std::string m_lastError;\n    NCMatrix m_mat; // The input (permuted ) matrix \n    SCMatrix m_Lstore; // The lower triangular matrix (supernodal)\n    MappedSparseMatrix<Scalar,ColMajor,StorageIndex> m_Ustore; // The upper triangular matrix\n    PermutationType m_perm_c; // Column permutation \n    PermutationType m_perm_r ; // Row permutation\n    IndexVector m_etree; // Column elimination tree \n    \n    typename Base::GlobalLU_t m_glu; \n                               \n    // SparseLU options \n    bool m_symmetricmode;\n    // values for performance \n    internal::perfvalues m_perfv;\n    RealScalar m_diagpivotthresh; // Specifies the threshold used for a diagonal entry to be an acceptable pivot\n    Index m_nnzL, m_nnzU; // Nonzeros in L and U factors\n    Index m_detPermR, m_detPermC; // Determinants of the permutation matrices\n  private:\n    // Disable copy constructor \n    SparseLU (const SparseLU& );\n}; // End class SparseLU\n\n\n\n// Functions needed by the anaysis phase\n/** \n  * Compute the column permutation to minimize the fill-in\n  * \n  *  - Apply this permutation to the input matrix - \n  * \n  *  - Compute the column elimination tree on the permuted matrix \n  * \n  *  - Postorder the elimination tree and the column permutation\n  * \n  */\ntemplate <typename MatrixType, typename OrderingType>\nvoid SparseLU<MatrixType, OrderingType>::analyzePattern(const MatrixType& mat)\n{\n  \n  //TODO  It is possible as in SuperLU to compute row and columns scaling vectors to equilibrate the matrix mat.\n  \n  // Firstly, copy the whole input matrix. \n  m_mat = mat;\n  \n  // Compute fill-in ordering\n  OrderingType ord; \n  ord(m_mat,m_perm_c);\n  \n  // Apply the permutation to the column of the input  matrix\n  if (m_perm_c.size())\n  {\n    m_mat.uncompress(); //NOTE: The effect of this command is only to create the InnerNonzeros pointers. FIXME : This vector is filled but not subsequently used.  \n    // Then, permute only the column pointers\n    ei_declare_aligned_stack_constructed_variable(StorageIndex,outerIndexPtr,mat.cols()+1,mat.isCompressed()?const_cast<StorageIndex*>(mat.outerIndexPtr()):0);\n    \n    // If the input matrix 'mat' is uncompressed, then the outer-indices do not match the ones of m_mat, and a copy is thus needed.\n    if(!mat.isCompressed()) \n      IndexVector::Map(outerIndexPtr, mat.cols()+1) = IndexVector::Map(m_mat.outerIndexPtr(),mat.cols()+1);\n    \n    // Apply the permutation and compute the nnz per column.\n    for (Index i = 0; i < mat.cols(); i++)\n    {\n      m_mat.outerIndexPtr()[m_perm_c.indices()(i)] = outerIndexPtr[i];\n      m_mat.innerNonZeroPtr()[m_perm_c.indices()(i)] = outerIndexPtr[i+1] - outerIndexPtr[i];\n    }\n  }\n  \n  // Compute the column elimination tree of the permuted matrix \n  IndexVector firstRowElt;\n  internal::coletree(m_mat, m_etree,firstRowElt); \n     \n  // In symmetric mode, do not do postorder here\n  if (!m_symmetricmode) {\n    IndexVector post, iwork; \n    // Post order etree\n    internal::treePostorder(StorageIndex(m_mat.cols()), m_etree, post); \n      \n   \n    // Renumber etree in postorder \n    Index m = m_mat.cols(); \n    iwork.resize(m+1);\n    for (Index i = 0; i < m; ++i) iwork(post(i)) = post(m_etree(i));\n    m_etree = iwork;\n    \n    // Postmultiply A*Pc by post, i.e reorder the matrix according to the postorder of the etree\n    PermutationType post_perm(m); \n    for (Index i = 0; i < m; i++) \n      post_perm.indices()(i) = post(i); \n        \n    // Combine the two permutations : postorder the permutation for future use\n    if(m_perm_c.size()) {\n      m_perm_c = post_perm * m_perm_c;\n    }\n    \n  } // end postordering \n  \n  m_analysisIsOk = true; \n}\n\n// Functions needed by the numerical factorization phase\n\n\n/** \n  *  - Numerical factorization \n  *  - Interleaved with the symbolic factorization \n  * On exit,  info is \n  * \n  *    = 0: successful factorization\n  * \n  *    > 0: if info = i, and i is\n  * \n  *       <= A->ncol: U(i,i) is exactly zero. The factorization has\n  *          been completed, but the factor U is exactly singular,\n  *          and division by zero will occur if it is used to solve a\n  *          system of equations.\n  * \n  *       > A->ncol: number of bytes allocated when memory allocation\n  *         failure occurred, plus A->ncol. If lwork = -1, it is\n  *         the estimated amount of space needed, plus A->ncol.  \n  */\ntemplate <typename MatrixType, typename OrderingType>\nvoid SparseLU<MatrixType, OrderingType>::factorize(const MatrixType& matrix)\n{\n  using internal::emptyIdxLU;\n  eigen_assert(m_analysisIsOk && \"analyzePattern() should be called first\"); \n  eigen_assert((matrix.rows() == matrix.cols()) && \"Only for squared matrices\");\n  \n  m_isInitialized = true;\n  \n  // Apply the column permutation computed in analyzepattern()\n  //   m_mat = matrix * m_perm_c.inverse(); \n  m_mat = matrix;\n  if (m_perm_c.size()) \n  {\n    m_mat.uncompress(); //NOTE: The effect of this command is only to create the InnerNonzeros pointers.\n    //Then, permute only the column pointers\n    const StorageIndex * outerIndexPtr;\n    if (matrix.isCompressed()) outerIndexPtr = matrix.outerIndexPtr();\n    else\n    {\n      StorageIndex* outerIndexPtr_t = new StorageIndex[matrix.cols()+1];\n      for(Index i = 0; i <= matrix.cols(); i++) outerIndexPtr_t[i] = m_mat.outerIndexPtr()[i];\n      outerIndexPtr = outerIndexPtr_t;\n    }\n    for (Index i = 0; i < matrix.cols(); i++)\n    {\n      m_mat.outerIndexPtr()[m_perm_c.indices()(i)] = outerIndexPtr[i];\n      m_mat.innerNonZeroPtr()[m_perm_c.indices()(i)] = outerIndexPtr[i+1] - outerIndexPtr[i];\n    }\n    if(!matrix.isCompressed()) delete[] outerIndexPtr;\n  } \n  else \n  { //FIXME This should not be needed if the empty permutation is handled transparently\n    m_perm_c.resize(matrix.cols());\n    for(StorageIndex i = 0; i < matrix.cols(); ++i) m_perm_c.indices()(i) = i;\n  }\n  \n  Index m = m_mat.rows();\n  Index n = m_mat.cols();\n  Index nnz = m_mat.nonZeros();\n  Index maxpanel = m_perfv.panel_size * m;\n  // Allocate working storage common to the factor routines\n  Index lwork = 0;\n  Index info = Base::memInit(m, n, nnz, lwork, m_perfv.fillfactor, m_perfv.panel_size, m_glu); \n  if (info) \n  {\n    m_lastError = \"UNABLE TO ALLOCATE WORKING MEMORY\\n\\n\" ;\n    m_factorizationIsOk = false;\n    return ; \n  }\n  \n  // Set up pointers for integer working arrays \n  IndexVector segrep(m); segrep.setZero();\n  IndexVector parent(m); parent.setZero();\n  IndexVector xplore(m); xplore.setZero();\n  IndexVector repfnz(maxpanel);\n  IndexVector panel_lsub(maxpanel);\n  IndexVector xprune(n); xprune.setZero();\n  IndexVector marker(m*internal::LUNoMarker); marker.setZero();\n  \n  repfnz.setConstant(-1); \n  panel_lsub.setConstant(-1);\n  \n  // Set up pointers for scalar working arrays \n  ScalarVector dense; \n  dense.setZero(maxpanel);\n  ScalarVector tempv; \n  tempv.setZero(internal::LUnumTempV(m, m_perfv.panel_size, m_perfv.maxsuper, /*m_perfv.rowblk*/m) );\n  \n  // Compute the inverse of perm_c\n  PermutationType iperm_c(m_perm_c.inverse()); \n  \n  // Identify initial relaxed snodes\n  IndexVector relax_end(n);\n  if ( m_symmetricmode == true ) \n    Base::heap_relax_snode(n, m_etree, m_perfv.relax, marker, relax_end);\n  else\n    Base::relax_snode(n, m_etree, m_perfv.relax, marker, relax_end);\n  \n  \n  m_perm_r.resize(m); \n  m_perm_r.indices().setConstant(-1);\n  marker.setConstant(-1);\n  m_detPermR = 1; // Record the determinant of the row permutation\n  \n  m_glu.supno(0) = emptyIdxLU; m_glu.xsup.setConstant(0);\n  m_glu.xsup(0) = m_glu.xlsub(0) = m_glu.xusub(0) = m_glu.xlusup(0) = Index(0);\n  \n  // Work on one 'panel' at a time. A panel is one of the following :\n  //  (a) a relaxed supernode at the bottom of the etree, or\n  //  (b) panel_size contiguous columns, <panel_size> defined by the user\n  Index jcol; \n  Index pivrow; // Pivotal row number in the original row matrix\n  Index nseg1; // Number of segments in U-column above panel row jcol\n  Index nseg; // Number of segments in each U-column \n  Index irep; \n  Index i, k, jj; \n  for (jcol = 0; jcol < n; )\n  {\n    // Adjust panel size so that a panel won't overlap with the next relaxed snode. \n    Index panel_size = m_perfv.panel_size; // upper bound on panel width\n    for (k = jcol + 1; k < (std::min)(jcol+panel_size, n); k++)\n    {\n      if (relax_end(k) != emptyIdxLU) \n      {\n        panel_size = k - jcol; \n        break; \n      }\n    }\n    if (k == n) \n      panel_size = n - jcol; \n      \n    // Symbolic outer factorization on a panel of columns \n    Base::panel_dfs(m, panel_size, jcol, m_mat, m_perm_r.indices(), nseg1, dense, panel_lsub, segrep, repfnz, xprune, marker, parent, xplore, m_glu); \n    \n    // Numeric sup-panel updates in topological order \n    Base::panel_bmod(m, panel_size, jcol, nseg1, dense, tempv, segrep, repfnz, m_glu); \n    \n    // Sparse LU within the panel, and below the panel diagonal \n    for ( jj = jcol; jj< jcol + panel_size; jj++) \n    {\n      k = (jj - jcol) * m; // Column index for w-wide arrays \n      \n      nseg = nseg1; // begin after all the panel segments\n      //Depth-first-search for the current column\n      VectorBlock<IndexVector> panel_lsubk(panel_lsub, k, m);\n      VectorBlock<IndexVector> repfnz_k(repfnz, k, m); \n      info = Base::column_dfs(m, jj, m_perm_r.indices(), m_perfv.maxsuper, nseg, panel_lsubk, segrep, repfnz_k, xprune, marker, parent, xplore, m_glu); \n      if ( info ) \n      {\n        m_lastError =  \"UNABLE TO EXPAND MEMORY IN COLUMN_DFS() \";\n        m_info = NumericalIssue; \n        m_factorizationIsOk = false; \n        return; \n      }\n      // Numeric updates to this column \n      VectorBlock<ScalarVector> dense_k(dense, k, m); \n      VectorBlock<IndexVector> segrep_k(segrep, nseg1, m-nseg1); \n      info = Base::column_bmod(jj, (nseg - nseg1), dense_k, tempv, segrep_k, repfnz_k, jcol, m_glu); \n      if ( info ) \n      {\n        m_lastError = \"UNABLE TO EXPAND MEMORY IN COLUMN_BMOD() \";\n        m_info = NumericalIssue; \n        m_factorizationIsOk = false; \n        return; \n      }\n      \n      // Copy the U-segments to ucol(*)\n      info = Base::copy_to_ucol(jj, nseg, segrep, repfnz_k ,m_perm_r.indices(), dense_k, m_glu); \n      if ( info ) \n      {\n        m_lastError = \"UNABLE TO EXPAND MEMORY IN COPY_TO_UCOL() \";\n        m_info = NumericalIssue; \n        m_factorizationIsOk = false; \n        return; \n      }\n      \n      // Form the L-segment \n      info = Base::pivotL(jj, m_diagpivotthresh, m_perm_r.indices(), iperm_c.indices(), pivrow, m_glu);\n      if ( info ) \n      {\n        m_lastError = \"THE MATRIX IS STRUCTURALLY SINGULAR ... ZERO COLUMN AT \";\n        std::ostringstream returnInfo;\n        returnInfo << info; \n        m_lastError += returnInfo.str();\n        m_info = NumericalIssue; \n        m_factorizationIsOk = false; \n        return; \n      }\n      \n      // Update the determinant of the row permutation matrix\n      // FIXME: the following test is not correct, we should probably take iperm_c into account and pivrow is not directly the row pivot.\n      if (pivrow != jj) m_detPermR = -m_detPermR;\n\n      // Prune columns (0:jj-1) using column jj\n      Base::pruneL(jj, m_perm_r.indices(), pivrow, nseg, segrep, repfnz_k, xprune, m_glu); \n      \n      // Reset repfnz for this column \n      for (i = 0; i < nseg; i++)\n      {\n        irep = segrep(i); \n        repfnz_k(irep) = emptyIdxLU; \n      }\n    } // end SparseLU within the panel  \n    jcol += panel_size;  // Move to the next panel\n  } // end for -- end elimination \n  \n  m_detPermR = m_perm_r.determinant();\n  m_detPermC = m_perm_c.determinant();\n  \n  // Count the number of nonzeros in factors \n  Base::countnz(n, m_nnzL, m_nnzU, m_glu); \n  // Apply permutation  to the L subscripts \n  Base::fixupL(n, m_perm_r.indices(), m_glu);\n  \n  // Create supernode matrix L \n  m_Lstore.setInfos(m, n, m_glu.lusup, m_glu.xlusup, m_glu.lsub, m_glu.xlsub, m_glu.supno, m_glu.xsup); \n  // Create the column major upper sparse matrix  U; \n  new (&m_Ustore) MappedSparseMatrix<Scalar, ColMajor, StorageIndex> ( m, n, m_nnzU, m_glu.xusub.data(), m_glu.usub.data(), m_glu.ucol.data() );\n  \n  m_info = Success;\n  m_factorizationIsOk = true;\n}\n\ntemplate<typename MappedSupernodalType>\nstruct SparseLUMatrixLReturnType : internal::no_assignment_operator\n{\n  typedef typename MappedSupernodalType::Scalar Scalar;\n  explicit SparseLUMatrixLReturnType(const MappedSupernodalType& mapL) : m_mapL(mapL)\n  { }\n  Index rows() const { return m_mapL.rows(); }\n  Index cols() const { return m_mapL.cols(); }\n  template<typename Dest>\n  void solveInPlace( MatrixBase<Dest> &X) const\n  {\n    m_mapL.solveInPlace(X);\n  }\n  template<bool Conjugate, typename Dest>\n  void solveTransposedInPlace( MatrixBase<Dest> &X) const\n  {\n    m_mapL.template solveTransposedInPlace<Conjugate>(X);\n  }\n\n  const MappedSupernodalType& m_mapL;\n};\n\ntemplate<typename MatrixLType, typename MatrixUType>\nstruct SparseLUMatrixUReturnType : internal::no_assignment_operator\n{\n  typedef typename MatrixLType::Scalar Scalar;\n  SparseLUMatrixUReturnType(const MatrixLType& mapL, const MatrixUType& mapU)\n  : m_mapL(mapL),m_mapU(mapU)\n  { }\n  Index rows() const { return m_mapL.rows(); }\n  Index cols() const { return m_mapL.cols(); }\n\n  template<typename Dest>   void solveInPlace(MatrixBase<Dest> &X) const\n  {\n    Index nrhs = X.cols();\n    Index n    = X.rows();\n    // Backward solve with U\n    for (Index k = m_mapL.nsuper(); k >= 0; k--)\n    {\n      Index fsupc = m_mapL.supToCol()[k];\n      Index lda = m_mapL.colIndexPtr()[fsupc+1] - m_mapL.colIndexPtr()[fsupc]; // leading dimension\n      Index nsupc = m_mapL.supToCol()[k+1] - fsupc;\n      Index luptr = m_mapL.colIndexPtr()[fsupc];\n\n      if (nsupc == 1)\n      {\n        for (Index j = 0; j < nrhs; j++)\n        {\n          X(fsupc, j) /= m_mapL.valuePtr()[luptr];\n        }\n      }\n      else\n      {\n        // FIXME: the following lines should use Block expressions and not Map!\n        Map<const Matrix<Scalar,Dynamic,Dynamic, ColMajor>, 0, OuterStride<> > A( &(m_mapL.valuePtr()[luptr]), nsupc, nsupc, OuterStride<>(lda) );\n        Map< Matrix<Scalar,Dynamic,Dest::ColsAtCompileTime, ColMajor>, 0, OuterStride<> > U (&(X.coeffRef(fsupc,0)), nsupc, nrhs, OuterStride<>(n) );\n        U = A.template triangularView<Upper>().solve(U);\n      }\n\n      for (Index j = 0; j < nrhs; ++j)\n      {\n        for (Index jcol = fsupc; jcol < fsupc + nsupc; jcol++)\n        {\n          typename MatrixUType::InnerIterator it(m_mapU, jcol);\n          for ( ; it; ++it)\n          {\n            Index irow = it.index();\n            X(irow, j) -= X(jcol, j) * it.value();\n          }\n        }\n      }\n    } // End For U-solve\n  }\n\n  template<bool Conjugate, typename Dest>   void solveTransposedInPlace(MatrixBase<Dest> &X) const\n  {\n    using numext::conj;\n    Index nrhs = X.cols();\n    Index n    = X.rows();\n    // Forward solve with U\n    for (Index k = 0; k <=  m_mapL.nsuper(); k++)\n    {\n      Index fsupc = m_mapL.supToCol()[k];\n      Index lda = m_mapL.colIndexPtr()[fsupc+1] - m_mapL.colIndexPtr()[fsupc]; // leading dimension\n      Index nsupc = m_mapL.supToCol()[k+1] - fsupc;\n      Index luptr = m_mapL.colIndexPtr()[fsupc];\n\n      for (Index j = 0; j < nrhs; ++j)\n      {\n        for (Index jcol = fsupc; jcol < fsupc + nsupc; jcol++)\n        {\n          typename MatrixUType::InnerIterator it(m_mapU, jcol);\n          for ( ; it; ++it)\n          {\n            Index irow = it.index();\n            X(jcol, j) -= X(irow, j) * (Conjugate? conj(it.value()): it.value());\n          }\n        }\n      }\n      if (nsupc == 1)\n      {\n        for (Index j = 0; j < nrhs; j++)\n        {\n          X(fsupc, j) /= (Conjugate? conj(m_mapL.valuePtr()[luptr]) : m_mapL.valuePtr()[luptr]);\n        }\n      }\n      else\n      {\n        Map<const Matrix<Scalar,Dynamic,Dynamic, ColMajor>, 0, OuterStride<> > A( &(m_mapL.valuePtr()[luptr]), nsupc, nsupc, OuterStride<>(lda) );\n        Map< Matrix<Scalar,Dynamic,Dest::ColsAtCompileTime, ColMajor>, 0, OuterStride<> > U (&(X(fsupc,0)), nsupc, nrhs, OuterStride<>(n) );\n        if(Conjugate)\n          U = A.adjoint().template triangularView<Lower>().solve(U);\n        else\n          U = A.transpose().template triangularView<Lower>().solve(U);\n      }\n    }// End For U-solve\n  }\n\n\n  const MatrixLType& m_mapL;\n  const MatrixUType& m_mapU;\n};\n\n} // End namespace Eigen \n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseLU/SparseLUImpl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n#ifndef SPARSELU_IMPL_H\n#define SPARSELU_IMPL_H\n\nnamespace Eigen {\nnamespace internal {\n  \n/** \\ingroup SparseLU_Module\n  * \\class SparseLUImpl\n  * Base class for sparseLU\n  */\ntemplate <typename Scalar, typename StorageIndex>\nclass SparseLUImpl\n{\n  public:\n    typedef Matrix<Scalar,Dynamic,1> ScalarVector;\n    typedef Matrix<StorageIndex,Dynamic,1> IndexVector; \n    typedef Matrix<Scalar,Dynamic,Dynamic,ColMajor> ScalarMatrix;\n    typedef Map<ScalarMatrix, 0,  OuterStride<> > MappedMatrixBlock;\n    typedef typename ScalarVector::RealScalar RealScalar; \n    typedef Ref<Matrix<Scalar,Dynamic,1> > BlockScalarVector;\n    typedef Ref<Matrix<StorageIndex,Dynamic,1> > BlockIndexVector;\n    typedef LU_GlobalLU_t<IndexVector, ScalarVector> GlobalLU_t; \n    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> MatrixType; \n    \n  protected:\n     template <typename VectorType>\n     Index expand(VectorType& vec, Index& length, Index nbElts, Index keep_prev, Index& num_expansions);\n     Index memInit(Index m, Index n, Index annz, Index lwork, Index fillratio, Index panel_size,  GlobalLU_t& glu); \n     template <typename VectorType>\n     Index memXpand(VectorType& vec, Index& maxlen, Index nbElts, MemType memtype, Index& num_expansions);\n     void heap_relax_snode (const Index n, IndexVector& et, const Index relax_columns, IndexVector& descendants, IndexVector& relax_end); \n     void relax_snode (const Index n, IndexVector& et, const Index relax_columns, IndexVector& descendants, IndexVector& relax_end); \n     Index snode_dfs(const Index jcol, const Index kcol,const MatrixType& mat,  IndexVector& xprune, IndexVector& marker, GlobalLU_t& glu); \n     Index snode_bmod (const Index jcol, const Index fsupc, ScalarVector& dense, GlobalLU_t& glu);\n     Index pivotL(const Index jcol, const RealScalar& diagpivotthresh, IndexVector& perm_r, IndexVector& iperm_c, Index& pivrow, GlobalLU_t& glu);\n     template <typename Traits>\n     void dfs_kernel(const StorageIndex jj, IndexVector& perm_r,\n                    Index& nseg, IndexVector& panel_lsub, IndexVector& segrep,\n                    Ref<IndexVector> repfnz_col, IndexVector& xprune, Ref<IndexVector> marker, IndexVector& parent,\n                    IndexVector& xplore, GlobalLU_t& glu, Index& nextl_col, Index krow, Traits& traits);\n     void panel_dfs(const Index m, const Index w, const Index jcol, MatrixType& A, IndexVector& perm_r, Index& nseg, ScalarVector& dense, IndexVector& panel_lsub, IndexVector& segrep, IndexVector& repfnz, IndexVector& xprune, IndexVector& marker, IndexVector& parent, IndexVector& xplore, GlobalLU_t& glu);\n    \n     void panel_bmod(const Index m, const Index w, const Index jcol, const Index nseg, ScalarVector& dense, ScalarVector& tempv, IndexVector& segrep, IndexVector& repfnz, GlobalLU_t& glu);\n     Index column_dfs(const Index m, const Index jcol, IndexVector& perm_r, Index maxsuper, Index& nseg,  BlockIndexVector lsub_col, IndexVector& segrep, BlockIndexVector repfnz, IndexVector& xprune, IndexVector& marker, IndexVector& parent, IndexVector& xplore, GlobalLU_t& glu);\n     Index column_bmod(const Index jcol, const Index nseg, BlockScalarVector dense, ScalarVector& tempv, BlockIndexVector segrep, BlockIndexVector repfnz, Index fpanelc, GlobalLU_t& glu); \n     Index copy_to_ucol(const Index jcol, const Index nseg, IndexVector& segrep, BlockIndexVector repfnz ,IndexVector& perm_r, BlockScalarVector dense, GlobalLU_t& glu); \n     void pruneL(const Index jcol, const IndexVector& perm_r, const Index pivrow, const Index nseg, const IndexVector& segrep, BlockIndexVector repfnz, IndexVector& xprune, GlobalLU_t& glu);\n     void countnz(const Index n, Index& nnzL, Index& nnzU, GlobalLU_t& glu); \n     void fixupL(const Index n, const IndexVector& perm_r, GlobalLU_t& glu); \n     \n     template<typename , typename >\n     friend struct column_dfs_traits;\n}; \n\n} // end namespace internal\n} // namespace Eigen\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseLU/SparseLU_Memory.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/* \n \n * NOTE: This file is the modified version of [s,d,c,z]memory.c files in SuperLU \n \n * -- SuperLU routine (version 3.1) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * August 1, 2008\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n\n#ifndef EIGEN_SPARSELU_MEMORY\n#define EIGEN_SPARSELU_MEMORY\n\nnamespace Eigen {\nnamespace internal {\n  \nenum { LUNoMarker = 3 };\nenum {emptyIdxLU = -1};\ninline Index LUnumTempV(Index& m, Index& w, Index& t, Index& b)\n{\n  return (std::max)(m, (t+b)*w);\n}\n\ntemplate< typename Scalar>\ninline Index LUTempSpace(Index&m, Index& w)\n{\n  return (2*w + 4 + LUNoMarker) * m * sizeof(Index) + (w + 1) * m * sizeof(Scalar);\n}\n\n\n\n\n/** \n  * Expand the existing storage to accommodate more fill-ins\n  * \\param vec Valid pointer to the vector to allocate or expand\n  * \\param[in,out] length  At input, contain the current length of the vector that is to be increased. At output, length of the newly allocated vector\n  * \\param[in] nbElts Current number of elements in the factors\n  * \\param keep_prev  1: use length  and do not expand the vector; 0: compute new_len and expand\n  * \\param[in,out] num_expansions Number of times the memory has been expanded\n  */\ntemplate <typename Scalar, typename StorageIndex>\ntemplate <typename VectorType>\nIndex  SparseLUImpl<Scalar,StorageIndex>::expand(VectorType& vec, Index& length, Index nbElts, Index keep_prev, Index& num_expansions) \n{\n  \n  float alpha = 1.5; // Ratio of the memory increase \n  Index new_len; // New size of the allocated memory\n  \n  if(num_expansions == 0 || keep_prev) \n    new_len = length ; // First time allocate requested\n  else \n    new_len = (std::max)(length+1,Index(alpha * length));\n  \n  VectorType old_vec; // Temporary vector to hold the previous values   \n  if (nbElts > 0 )\n    old_vec = vec.segment(0,nbElts); \n  \n  //Allocate or expand the current vector\n#ifdef EIGEN_EXCEPTIONS\n  try\n#endif\n  {\n    vec.resize(new_len); \n  }\n#ifdef EIGEN_EXCEPTIONS\n  catch(std::bad_alloc& )\n#else\n  if(!vec.size())\n#endif\n  {\n    if (!num_expansions)\n    {\n      // First time to allocate from LUMemInit()\n      // Let LUMemInit() deals with it.\n      return -1;\n    }\n    if (keep_prev)\n    {\n      // In this case, the memory length should not not be reduced\n      return new_len;\n    }\n    else \n    {\n      // Reduce the size and increase again \n      Index tries = 0; // Number of attempts\n      do \n      {\n        alpha = (alpha + 1)/2;\n        new_len = (std::max)(length+1,Index(alpha * length));\n#ifdef EIGEN_EXCEPTIONS\n        try\n#endif\n        {\n          vec.resize(new_len); \n        }\n#ifdef EIGEN_EXCEPTIONS\n        catch(std::bad_alloc& )\n#else\n        if (!vec.size())\n#endif\n        {\n          tries += 1; \n          if ( tries > 10) return new_len; \n        }\n      } while (!vec.size());\n    }\n  }\n  //Copy the previous values to the newly allocated space \n  if (nbElts > 0)\n    vec.segment(0, nbElts) = old_vec;   \n   \n  \n  length  = new_len;\n  if(num_expansions) ++num_expansions;\n  return 0; \n}\n\n/**\n * \\brief  Allocate various working space for the numerical factorization phase.\n * \\param m number of rows of the input matrix \n * \\param n number of columns \n * \\param annz number of initial nonzeros in the matrix \n * \\param lwork  if lwork=-1, this routine returns an estimated size of the required memory\n * \\param glu persistent data to facilitate multiple factors : will be deleted later ??\n * \\param fillratio estimated ratio of fill in the factors\n * \\param panel_size Size of a panel\n * \\return an estimated size of the required memory if lwork = -1; otherwise, return the size of actually allocated memory when allocation failed, and 0 on success\n * \\note Unlike SuperLU, this routine does not support successive factorization with the same pattern and the same row permutation\n */\ntemplate <typename Scalar, typename StorageIndex>\nIndex SparseLUImpl<Scalar,StorageIndex>::memInit(Index m, Index n, Index annz, Index lwork, Index fillratio, Index panel_size,  GlobalLU_t& glu)\n{\n  Index& num_expansions = glu.num_expansions; //No memory expansions so far\n  num_expansions = 0;\n  glu.nzumax = glu.nzlumax = (std::min)(fillratio * (annz+1) / n, m) * n; // estimated number of nonzeros in U \n  glu.nzlmax = (std::max)(Index(4), fillratio) * (annz+1) / 4; // estimated  nnz in L factor\n  // Return the estimated size to the user if necessary\n  Index tempSpace;\n  tempSpace = (2*panel_size + 4 + LUNoMarker) * m * sizeof(Index) + (panel_size + 1) * m * sizeof(Scalar);\n  if (lwork == emptyIdxLU) \n  {\n    Index estimated_size;\n    estimated_size = (5 * n + 5) * sizeof(Index)  + tempSpace\n                    + (glu.nzlmax + glu.nzumax) * sizeof(Index) + (glu.nzlumax+glu.nzumax) *  sizeof(Scalar) + n; \n    return estimated_size;\n  }\n  \n  // Setup the required space \n  \n  // First allocate Integer pointers for L\\U factors\n  glu.xsup.resize(n+1);\n  glu.supno.resize(n+1);\n  glu.xlsub.resize(n+1);\n  glu.xlusup.resize(n+1);\n  glu.xusub.resize(n+1);\n\n  // Reserve memory for L/U factors\n  do \n  {\n    if(     (expand<ScalarVector>(glu.lusup, glu.nzlumax, 0, 0, num_expansions)<0)\n        ||  (expand<ScalarVector>(glu.ucol,  glu.nzumax,  0, 0, num_expansions)<0)\n        ||  (expand<IndexVector> (glu.lsub,  glu.nzlmax,  0, 0, num_expansions)<0)\n        ||  (expand<IndexVector> (glu.usub,  glu.nzumax,  0, 1, num_expansions)<0) )\n    {\n      //Reduce the estimated size and retry\n      glu.nzlumax /= 2;\n      glu.nzumax /= 2;\n      glu.nzlmax /= 2;\n      if (glu.nzlumax < annz ) return glu.nzlumax; \n    }\n  } while (!glu.lusup.size() || !glu.ucol.size() || !glu.lsub.size() || !glu.usub.size());\n  \n  ++num_expansions;\n  return 0;\n  \n} // end LuMemInit\n\n/** \n * \\brief Expand the existing storage \n * \\param vec vector to expand \n * \\param[in,out] maxlen On input, previous size of vec (Number of elements to copy ). on output, new size\n * \\param nbElts current number of elements in the vector.\n * \\param memtype Type of the element to expand\n * \\param num_expansions Number of expansions \n * \\return 0 on success, > 0 size of the memory allocated so far\n */\ntemplate <typename Scalar, typename StorageIndex>\ntemplate <typename VectorType>\nIndex SparseLUImpl<Scalar,StorageIndex>::memXpand(VectorType& vec, Index& maxlen, Index nbElts, MemType memtype, Index& num_expansions)\n{\n  Index failed_size; \n  if (memtype == USUB)\n     failed_size = this->expand<VectorType>(vec, maxlen, nbElts, 1, num_expansions);\n  else\n    failed_size = this->expand<VectorType>(vec, maxlen, nbElts, 0, num_expansions);\n\n  if (failed_size)\n    return failed_size; \n  \n  return 0 ;  \n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n#endif // EIGEN_SPARSELU_MEMORY\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseLU/SparseLU_Structs.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/* \n * NOTE: This file comes from a partly modified version of files slu_[s,d,c,z]defs.h\n * -- SuperLU routine (version 4.1) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * November, 2010\n * \n * Global data structures used in LU factorization -\n * \n *   nsuper: #supernodes = nsuper + 1, numbered [0, nsuper].\n *   (xsup,supno): supno[i] is the supernode no to which i belongs;\n *  xsup(s) points to the beginning of the s-th supernode.\n *  e.g.   supno 0 1 2 2 3 3 3 4 4 4 4 4   (n=12)\n *          xsup 0 1 2 4 7 12\n *  Note: dfs will be performed on supernode rep. relative to the new \n *        row pivoting ordering\n *\n *   (xlsub,lsub): lsub[*] contains the compressed subscript of\n *  rectangular supernodes; xlsub[j] points to the starting\n *  location of the j-th column in lsub[*]. Note that xlsub \n *  is indexed by column.\n *  Storage: original row subscripts\n *\n *      During the course of sparse LU factorization, we also use\n *  (xlsub,lsub) for the purpose of symmetric pruning. For each\n *  supernode {s,s+1,...,t=s+r} with first column s and last\n *  column t, the subscript set\n *    lsub[j], j=xlsub[s], .., xlsub[s+1]-1\n *  is the structure of column s (i.e. structure of this supernode).\n *  It is used for the storage of numerical values.\n *  Furthermore,\n *    lsub[j], j=xlsub[t], .., xlsub[t+1]-1\n *  is the structure of the last column t of this supernode.\n *  It is for the purpose of symmetric pruning. Therefore, the\n *  structural subscripts can be rearranged without making physical\n *  interchanges among the numerical values.\n *\n *  However, if the supernode has only one column, then we\n *  only keep one set of subscripts. For any subscript interchange\n *  performed, similar interchange must be done on the numerical\n *  values.\n *\n *  The last column structures (for pruning) will be removed\n *  after the numercial LU factorization phase.\n *\n *   (xlusup,lusup): lusup[*] contains the numerical values of the\n *  rectangular supernodes; xlusup[j] points to the starting\n *  location of the j-th column in storage vector lusup[*]\n *  Note: xlusup is indexed by column.\n *  Each rectangular supernode is stored by column-major\n *  scheme, consistent with Fortran 2-dim array storage.\n *\n *   (xusub,ucol,usub): ucol[*] stores the numerical values of\n *  U-columns outside the rectangular supernodes. The row\n *  subscript of nonzero ucol[k] is stored in usub[k].\n *  xusub[i] points to the starting location of column i in ucol.\n *  Storage: new row subscripts; that is subscripts of PA.\n */\n\n#ifndef EIGEN_LU_STRUCTS\n#define EIGEN_LU_STRUCTS\nnamespace Eigen {\nnamespace internal {\n  \ntypedef enum {LUSUP, UCOL, LSUB, USUB, LLVL, ULVL} MemType; \n\ntemplate <typename IndexVector, typename ScalarVector>\nstruct LU_GlobalLU_t {\n  typedef typename IndexVector::Scalar StorageIndex; \n  IndexVector xsup; //First supernode column ... xsup(s) points to the beginning of the s-th supernode\n  IndexVector supno; // Supernode number corresponding to this column (column to supernode mapping)\n  ScalarVector  lusup; // nonzero values of L ordered by columns \n  IndexVector lsub; // Compressed row indices of L rectangular supernodes. \n  IndexVector xlusup; // pointers to the beginning of each column in lusup\n  IndexVector xlsub; // pointers to the beginning of each column in lsub\n  Index   nzlmax; // Current max size of lsub\n  Index   nzlumax; // Current max size of lusup\n  ScalarVector  ucol; // nonzero values of U ordered by columns \n  IndexVector usub; // row indices of U columns in ucol\n  IndexVector xusub; // Pointers to the beginning of each column of U in ucol \n  Index   nzumax; // Current max size of ucol\n  Index   n; // Number of columns in the matrix  \n  Index   num_expansions; \n};\n\n// Values to set for performance\nstruct perfvalues {\n  Index panel_size; // a panel consists of at most <panel_size> consecutive columns\n  Index relax; // To control degree of relaxing supernodes. If the number of nodes (columns) \n                // in a subtree of the elimination tree is less than relax, this subtree is considered \n                // as one supernode regardless of the row structures of those columns\n  Index maxsuper; // The maximum size for a supernode in complete LU\n  Index rowblk; // The minimum row dimension for 2-D blocking to be used;\n  Index colblk; // The minimum column dimension for 2-D blocking to be used;\n  Index fillfactor; // The estimated fills factors for L and U, compared with A\n}; \n\n} // end namespace internal\n\n} // end namespace Eigen\n#endif // EIGEN_LU_STRUCTS\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSELU_SUPERNODAL_MATRIX_H\n#define EIGEN_SPARSELU_SUPERNODAL_MATRIX_H\n\nnamespace Eigen {\nnamespace internal {\n\n/** \\ingroup SparseLU_Module\n * \\brief a class to manipulate the L supernodal factor from the SparseLU factorization\n * \n * This class  contain the data to easily store \n * and manipulate the supernodes during the factorization and solution phase of Sparse LU. \n * Only the lower triangular matrix has supernodes.\n * \n * NOTE : This class corresponds to the SCformat structure in SuperLU\n * \n */\n/* TODO\n * InnerIterator as for sparsematrix \n * SuperInnerIterator to iterate through all supernodes \n * Function for triangular solve\n */\ntemplate <typename Scalar_, typename StorageIndex_>\nclass MappedSuperNodalMatrix\n{\n  public:\n    typedef Scalar_ Scalar;\n    typedef StorageIndex_ StorageIndex;\n    typedef Matrix<StorageIndex,Dynamic,1> IndexVector;\n    typedef Matrix<Scalar,Dynamic,1> ScalarVector;\n  public:\n    MappedSuperNodalMatrix()\n    {\n      \n    }\n    MappedSuperNodalMatrix(Index m, Index n,  ScalarVector& nzval, IndexVector& nzval_colptr, IndexVector& rowind,\n             IndexVector& rowind_colptr, IndexVector& col_to_sup, IndexVector& sup_to_col )\n    {\n      setInfos(m, n, nzval, nzval_colptr, rowind, rowind_colptr, col_to_sup, sup_to_col);\n    }\n    \n    ~MappedSuperNodalMatrix()\n    {\n      \n    }\n    /**\n     * Set appropriate pointers for the lower triangular supernodal matrix\n     * These infos are available at the end of the numerical factorization\n     * FIXME This class will be modified such that it can be use in the course \n     * of the factorization.\n     */\n    void setInfos(Index m, Index n, ScalarVector& nzval, IndexVector& nzval_colptr, IndexVector& rowind,\n             IndexVector& rowind_colptr, IndexVector& col_to_sup, IndexVector& sup_to_col )\n    {\n      m_row = m;\n      m_col = n; \n      m_nzval = nzval.data(); \n      m_nzval_colptr = nzval_colptr.data(); \n      m_rowind = rowind.data(); \n      m_rowind_colptr = rowind_colptr.data(); \n      m_nsuper = col_to_sup(n); \n      m_col_to_sup = col_to_sup.data(); \n      m_sup_to_col = sup_to_col.data(); \n    }\n    \n    /**\n     * Number of rows\n     */\n    Index rows() const { return m_row; }\n    \n    /**\n     * Number of columns\n     */\n    Index cols() const { return m_col; }\n    \n    /**\n     * Return the array of nonzero values packed by column\n     * \n     * The size is nnz\n     */\n    Scalar* valuePtr() {  return m_nzval; }\n    \n    const Scalar* valuePtr() const \n    {\n      return m_nzval; \n    }\n    /**\n     * Return the pointers to the beginning of each column in \\ref valuePtr()\n     */\n    StorageIndex* colIndexPtr()\n    {\n      return m_nzval_colptr; \n    }\n    \n    const StorageIndex* colIndexPtr() const\n    {\n      return m_nzval_colptr; \n    }\n    \n    /**\n     * Return the array of compressed row indices of all supernodes\n     */\n    StorageIndex* rowIndex()  { return m_rowind; }\n    \n    const StorageIndex* rowIndex() const\n    {\n      return m_rowind; \n    }\n    \n    /**\n     * Return the location in \\em rowvaluePtr() which starts each column\n     */\n    StorageIndex* rowIndexPtr() { return m_rowind_colptr; }\n    \n    const StorageIndex* rowIndexPtr() const\n    {\n      return m_rowind_colptr; \n    }\n    \n    /** \n     * Return the array of column-to-supernode mapping \n     */\n    StorageIndex* colToSup()  { return m_col_to_sup; }\n    \n    const StorageIndex* colToSup() const\n    {\n      return m_col_to_sup;       \n    }\n    /**\n     * Return the array of supernode-to-column mapping\n     */\n    StorageIndex* supToCol() { return m_sup_to_col; }\n    \n    const StorageIndex* supToCol() const\n    {\n      return m_sup_to_col;\n    }\n    \n    /**\n     * Return the number of supernodes\n     */\n    Index nsuper() const\n    {\n      return m_nsuper; \n    }\n    \n    class InnerIterator; \n    template<typename Dest>\n    void solveInPlace( MatrixBase<Dest>&X) const;\n    template<bool Conjugate, typename Dest>\n    void solveTransposedInPlace( MatrixBase<Dest>&X) const;\n\n    \n      \n      \n    \n  protected:\n    Index m_row; // Number of rows\n    Index m_col; // Number of columns\n    Index m_nsuper; // Number of supernodes\n    Scalar* m_nzval; //array of nonzero values packed by column\n    StorageIndex* m_nzval_colptr; //nzval_colptr[j] Stores the location in nzval[] which starts column j\n    StorageIndex* m_rowind; // Array of compressed row indices of rectangular supernodes\n    StorageIndex* m_rowind_colptr; //rowind_colptr[j] stores the location in rowind[] which starts column j\n    StorageIndex* m_col_to_sup; // col_to_sup[j] is the supernode number to which column j belongs\n    StorageIndex* m_sup_to_col; //sup_to_col[s] points to the starting column of the s-th supernode\n    \n  private :\n};\n\n/**\n  * \\brief InnerIterator class to iterate over nonzero values of the current column in the supernodal matrix L\n  * \n  */\ntemplate<typename Scalar, typename StorageIndex>\nclass MappedSuperNodalMatrix<Scalar,StorageIndex>::InnerIterator\n{\n  public:\n     InnerIterator(const MappedSuperNodalMatrix& mat, Index outer)\n      : m_matrix(mat),\n        m_outer(outer),\n        m_supno(mat.colToSup()[outer]),\n        m_idval(mat.colIndexPtr()[outer]),\n        m_startidval(m_idval),\n        m_endidval(mat.colIndexPtr()[outer+1]),\n        m_idrow(mat.rowIndexPtr()[mat.supToCol()[mat.colToSup()[outer]]]),\n        m_endidrow(mat.rowIndexPtr()[mat.supToCol()[mat.colToSup()[outer]]+1])\n    {}\n    inline InnerIterator& operator++()\n    { \n      m_idval++; \n      m_idrow++;\n      return *this;\n    }\n    inline Scalar value() const { return m_matrix.valuePtr()[m_idval]; }\n    \n    inline Scalar& valueRef() { return const_cast<Scalar&>(m_matrix.valuePtr()[m_idval]); }\n    \n    inline Index index() const { return m_matrix.rowIndex()[m_idrow]; }\n    inline Index row() const { return index(); }\n    inline Index col() const { return m_outer; }\n    \n    inline Index supIndex() const { return m_supno; }\n    \n    inline operator bool() const \n    { \n      return ( (m_idval < m_endidval) && (m_idval >= m_startidval)\n                && (m_idrow < m_endidrow) );\n    }\n    \n  protected:\n    const MappedSuperNodalMatrix& m_matrix; // Supernodal lower triangular matrix \n    const Index m_outer;                    // Current column \n    const Index m_supno;                    // Current SuperNode number\n    Index m_idval;                          // Index to browse the values in the current column\n    const Index m_startidval;               // Start of the column value\n    const Index m_endidval;                 // End of the column value\n    Index m_idrow;                          // Index to browse the row indices \n    Index m_endidrow;                       // End index of row indices of the current column\n};\n\n/**\n * \\brief Solve with the supernode triangular matrix\n * \n */\ntemplate<typename Scalar, typename Index_>\ntemplate<typename Dest>\nvoid MappedSuperNodalMatrix<Scalar,Index_>::solveInPlace( MatrixBase<Dest>&X) const\n{\n    /* Explicit type conversion as the Index type of MatrixBase<Dest> may be wider than Index */\n//    eigen_assert(X.rows() <= NumTraits<Index>::highest());\n//    eigen_assert(X.cols() <= NumTraits<Index>::highest());\n    Index n    = int(X.rows());\n    Index nrhs = Index(X.cols());\n    const Scalar * Lval = valuePtr();                 // Nonzero values \n    Matrix<Scalar,Dynamic,Dest::ColsAtCompileTime, ColMajor> work(n, nrhs);     // working vector\n    work.setZero();\n    for (Index k = 0; k <= nsuper(); k ++)\n    {\n      Index fsupc = supToCol()[k];                    // First column of the current supernode \n      Index istart = rowIndexPtr()[fsupc];            // Pointer index to the subscript of the current column\n      Index nsupr = rowIndexPtr()[fsupc+1] - istart;  // Number of rows in the current supernode\n      Index nsupc = supToCol()[k+1] - fsupc;          // Number of columns in the current supernode\n      Index nrow = nsupr - nsupc;                     // Number of rows in the non-diagonal part of the supernode\n      Index irow;                                     //Current index row\n      \n      if (nsupc == 1 )\n      {\n        for (Index j = 0; j < nrhs; j++)\n        {\n          InnerIterator it(*this, fsupc);\n          ++it; // Skip the diagonal element\n          for (; it; ++it)\n          {\n            irow = it.row();\n            X(irow, j) -= X(fsupc, j) * it.value();\n          }\n        }\n      }\n      else\n      {\n        // The supernode has more than one column \n        Index luptr = colIndexPtr()[fsupc]; \n        Index lda = colIndexPtr()[fsupc+1] - luptr;\n        \n        // Triangular solve \n        Map<const Matrix<Scalar,Dynamic,Dynamic, ColMajor>, 0, OuterStride<> > A( &(Lval[luptr]), nsupc, nsupc, OuterStride<>(lda) );\n        Map< Matrix<Scalar,Dynamic,Dest::ColsAtCompileTime, ColMajor>, 0, OuterStride<> > U (&(X(fsupc,0)), nsupc, nrhs, OuterStride<>(n) );\n        U = A.template triangularView<UnitLower>().solve(U); \n        \n        // Matrix-vector product \n        new (&A) Map<const Matrix<Scalar,Dynamic,Dynamic, ColMajor>, 0, OuterStride<> > ( &(Lval[luptr+nsupc]), nrow, nsupc, OuterStride<>(lda) );\n        work.topRows(nrow).noalias() = A * U;\n        \n        //Begin Scatter \n        for (Index j = 0; j < nrhs; j++)\n        {\n          Index iptr = istart + nsupc; \n          for (Index i = 0; i < nrow; i++)\n          {\n            irow = rowIndex()[iptr]; \n            X(irow, j) -= work(i, j); // Scatter operation\n            work(i, j) = Scalar(0); \n            iptr++;\n          }\n        }\n      }\n    } \n}\n\ntemplate<typename Scalar, typename Index_>\ntemplate<bool Conjugate, typename Dest>\nvoid MappedSuperNodalMatrix<Scalar,Index_>::solveTransposedInPlace( MatrixBase<Dest>&X) const\n{\n    using numext::conj;\n  Index n    = int(X.rows());\n  Index nrhs = Index(X.cols());\n  const Scalar * Lval = valuePtr();                 // Nonzero values\n  Matrix<Scalar,Dynamic,Dest::ColsAtCompileTime, ColMajor> work(n, nrhs);     // working vector\n  work.setZero();\n  for (Index k = nsuper(); k >= 0; k--)\n  {\n    Index fsupc = supToCol()[k];                    // First column of the current supernode\n    Index istart = rowIndexPtr()[fsupc];            // Pointer index to the subscript of the current column\n    Index nsupr = rowIndexPtr()[fsupc+1] - istart;  // Number of rows in the current supernode\n    Index nsupc = supToCol()[k+1] - fsupc;          // Number of columns in the current supernode\n    Index nrow = nsupr - nsupc;                     // Number of rows in the non-diagonal part of the supernode\n    Index irow;                                     //Current index row\n\n    if (nsupc == 1 )\n    {\n      for (Index j = 0; j < nrhs; j++)\n      {\n        InnerIterator it(*this, fsupc);\n        ++it; // Skip the diagonal element\n        for (; it; ++it)\n        {\n          irow = it.row();\n          X(fsupc,j) -= X(irow, j) * (Conjugate?conj(it.value()):it.value());\n        }\n      }\n    }\n    else\n    {\n      // The supernode has more than one column\n      Index luptr = colIndexPtr()[fsupc];\n      Index lda = colIndexPtr()[fsupc+1] - luptr;\n\n      //Begin Gather\n      for (Index j = 0; j < nrhs; j++)\n      {\n        Index iptr = istart + nsupc;\n        for (Index i = 0; i < nrow; i++)\n        {\n          irow = rowIndex()[iptr];\n          work.topRows(nrow)(i,j)= X(irow,j); // Gather operation\n          iptr++;\n        }\n      }\n\n      // Matrix-vector product with transposed submatrix\n      Map<const Matrix<Scalar,Dynamic,Dynamic, ColMajor>, 0, OuterStride<> > A( &(Lval[luptr+nsupc]), nrow, nsupc, OuterStride<>(lda) );\n      Map< Matrix<Scalar,Dynamic,Dest::ColsAtCompileTime, ColMajor>, 0, OuterStride<> > U (&(X(fsupc,0)), nsupc, nrhs, OuterStride<>(n) );\n      if(Conjugate)\n        U = U - A.adjoint() * work.topRows(nrow);\n      else\n        U = U - A.transpose() * work.topRows(nrow);\n\n      // Triangular solve (of transposed diagonal block)\n      new (&A) Map<const Matrix<Scalar,Dynamic,Dynamic, ColMajor>, 0, OuterStride<> > ( &(Lval[luptr]), nsupc, nsupc, OuterStride<>(lda) );\n      if(Conjugate)\n        U = A.adjoint().template triangularView<UnitUpper>().solve(U);\n      else\n        U = A.transpose().template triangularView<UnitUpper>().solve(U);\n\n    }\n\n  }\n}\n\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSELU_MATRIX_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseLU/SparseLU_Utils.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#ifndef EIGEN_SPARSELU_UTILS_H\n#define EIGEN_SPARSELU_UTILS_H\n\nnamespace Eigen {\nnamespace internal {\n\n/**\n * \\brief Count Nonzero elements in the factors\n */\ntemplate <typename Scalar, typename StorageIndex>\nvoid SparseLUImpl<Scalar,StorageIndex>::countnz(const Index n, Index& nnzL, Index& nnzU, GlobalLU_t& glu)\n{\n nnzL = 0; \n nnzU = (glu.xusub)(n); \n Index nsuper = (glu.supno)(n); \n Index jlen; \n Index i, j, fsupc;\n if (n <= 0 ) return; \n // For each supernode\n for (i = 0; i <= nsuper; i++)\n {\n   fsupc = glu.xsup(i); \n   jlen = glu.xlsub(fsupc+1) - glu.xlsub(fsupc); \n   \n   for (j = fsupc; j < glu.xsup(i+1); j++)\n   {\n     nnzL += jlen; \n     nnzU += j - fsupc + 1; \n     jlen--; \n   }\n }\n}\n\n/**\n * \\brief Fix up the data storage lsub for L-subscripts. \n * \n * It removes the subscripts sets for structural pruning, \n * and applies permutation to the remaining subscripts\n * \n */\ntemplate <typename Scalar, typename StorageIndex>\nvoid SparseLUImpl<Scalar,StorageIndex>::fixupL(const Index n, const IndexVector& perm_r, GlobalLU_t& glu)\n{\n  Index fsupc, i, j, k, jstart; \n  \n  StorageIndex nextl = 0; \n  Index nsuper = (glu.supno)(n); \n  \n  // For each supernode \n  for (i = 0; i <= nsuper; i++)\n  {\n    fsupc = glu.xsup(i); \n    jstart = glu.xlsub(fsupc); \n    glu.xlsub(fsupc) = nextl; \n    for (j = jstart; j < glu.xlsub(fsupc + 1); j++)\n    {\n      glu.lsub(nextl) = perm_r(glu.lsub(j)); // Now indexed into P*A\n      nextl++;\n    }\n    for (k = fsupc+1; k < glu.xsup(i+1); k++)\n      glu.xlsub(k) = nextl; // other columns in supernode i\n  }\n  \n  glu.xlsub(n) = nextl; \n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n#endif // EIGEN_SPARSELU_UTILS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseLU/SparseLU_column_bmod.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/* \n \n * NOTE: This file is the modified version of xcolumn_bmod.c file in SuperLU \n \n * -- SuperLU routine (version 3.0) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * October 15, 2003\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n#ifndef SPARSELU_COLUMN_BMOD_H\n#define SPARSELU_COLUMN_BMOD_H\n\nnamespace Eigen {\n\nnamespace internal {\n/**\n * \\brief Performs numeric block updates (sup-col) in topological order\n * \n * \\param jcol current column to update\n * \\param nseg Number of segments in the U part\n * \\param dense Store the full representation of the column\n * \\param tempv working array \n * \\param segrep segment representative ...\n * \\param repfnz ??? First nonzero column in each row ???  ...\n * \\param fpanelc First column in the current panel\n * \\param glu Global LU data. \n * \\return 0 - successful return \n *         > 0 - number of bytes allocated when run out of space\n * \n */\ntemplate <typename Scalar, typename StorageIndex>\nIndex SparseLUImpl<Scalar,StorageIndex>::column_bmod(const Index jcol, const Index nseg, BlockScalarVector dense, ScalarVector& tempv,\n                                                     BlockIndexVector segrep, BlockIndexVector repfnz, Index fpanelc, GlobalLU_t& glu)\n{\n  Index  jsupno, k, ksub, krep, ksupno; \n  Index lptr, nrow, isub, irow, nextlu, new_next, ufirst; \n  Index fsupc, nsupc, nsupr, luptr, kfnz, no_zeros; \n  /* krep = representative of current k-th supernode\n    * fsupc =  first supernodal column\n    * nsupc = number of columns in a supernode\n    * nsupr = number of rows in a supernode\n    * luptr = location of supernodal LU-block in storage\n    * kfnz = first nonz in the k-th supernodal segment\n    * no_zeros = no lf leading zeros in a supernodal U-segment\n    */\n  \n  jsupno = glu.supno(jcol);\n  // For each nonzero supernode segment of U[*,j] in topological order \n  k = nseg - 1; \n  Index d_fsupc; // distance between the first column of the current panel and the \n               // first column of the current snode\n  Index fst_col; // First column within small LU update\n  Index segsize; \n  for (ksub = 0; ksub < nseg; ksub++)\n  {\n    krep = segrep(k); k--; \n    ksupno = glu.supno(krep); \n    if (jsupno != ksupno )\n    {\n      // outside the rectangular supernode \n      fsupc = glu.xsup(ksupno); \n      fst_col = (std::max)(fsupc, fpanelc); \n      \n      // Distance from the current supernode to the current panel; \n      // d_fsupc = 0 if fsupc > fpanelc\n      d_fsupc = fst_col - fsupc; \n      \n      luptr = glu.xlusup(fst_col) + d_fsupc; \n      lptr = glu.xlsub(fsupc) + d_fsupc; \n      \n      kfnz = repfnz(krep); \n      kfnz = (std::max)(kfnz, fpanelc); \n      \n      segsize = krep - kfnz + 1; \n      nsupc = krep - fst_col + 1; \n      nsupr = glu.xlsub(fsupc+1) - glu.xlsub(fsupc); \n      nrow = nsupr - d_fsupc - nsupc;\n      Index lda = glu.xlusup(fst_col+1) - glu.xlusup(fst_col);\n      \n      \n      // Perform a triangular solver and block update, \n      // then scatter the result of sup-col update to dense\n      no_zeros = kfnz - fst_col; \n      if(segsize==1)\n        LU_kernel_bmod<1>::run(segsize, dense, tempv, glu.lusup, luptr, lda, nrow, glu.lsub, lptr, no_zeros);\n      else\n        LU_kernel_bmod<Dynamic>::run(segsize, dense, tempv, glu.lusup, luptr, lda, nrow, glu.lsub, lptr, no_zeros);\n    } // end if jsupno \n  } // end for each segment\n  \n  // Process the supernodal portion of  L\\U[*,j]\n  nextlu = glu.xlusup(jcol); \n  fsupc = glu.xsup(jsupno);\n  \n  // copy the SPA dense into L\\U[*,j]\n  Index mem; \n  new_next = nextlu + glu.xlsub(fsupc + 1) - glu.xlsub(fsupc); \n  Index offset = internal::first_multiple<Index>(new_next, internal::packet_traits<Scalar>::size) - new_next;\n  if(offset)\n    new_next += offset;\n  while (new_next > glu.nzlumax )\n  {\n    mem = memXpand<ScalarVector>(glu.lusup, glu.nzlumax, nextlu, LUSUP, glu.num_expansions);  \n    if (mem) return mem; \n  }\n  \n  for (isub = glu.xlsub(fsupc); isub < glu.xlsub(fsupc+1); isub++)\n  {\n    irow = glu.lsub(isub);\n    glu.lusup(nextlu) = dense(irow);\n    dense(irow) = Scalar(0.0); \n    ++nextlu; \n  }\n  \n  if(offset)\n  {\n    glu.lusup.segment(nextlu,offset).setZero();\n    nextlu += offset;\n  }\n  glu.xlusup(jcol + 1) = StorageIndex(nextlu);  // close L\\U(*,jcol); \n  \n  /* For more updates within the panel (also within the current supernode),\n   * should start from the first column of the panel, or the first column\n   * of the supernode, whichever is bigger. There are two cases:\n   *  1) fsupc < fpanelc, then fst_col <-- fpanelc\n   *  2) fsupc >= fpanelc, then fst_col <-- fsupc\n   */\n  fst_col = (std::max)(fsupc, fpanelc); \n  \n  if (fst_col  < jcol)\n  {\n    // Distance between the current supernode and the current panel\n    // d_fsupc = 0 if fsupc >= fpanelc\n    d_fsupc = fst_col - fsupc; \n    \n    lptr = glu.xlsub(fsupc) + d_fsupc; \n    luptr = glu.xlusup(fst_col) + d_fsupc; \n    nsupr = glu.xlsub(fsupc+1) - glu.xlsub(fsupc); // leading dimension\n    nsupc = jcol - fst_col; // excluding jcol \n    nrow = nsupr - d_fsupc - nsupc; \n    \n    // points to the beginning of jcol in snode L\\U(jsupno) \n    ufirst = glu.xlusup(jcol) + d_fsupc; \n    Index lda = glu.xlusup(jcol+1) - glu.xlusup(jcol);\n    MappedMatrixBlock A( &(glu.lusup.data()[luptr]), nsupc, nsupc, OuterStride<>(lda) );\n    VectorBlock<ScalarVector> u(glu.lusup, ufirst, nsupc); \n    u = A.template triangularView<UnitLower>().solve(u); \n    \n    new (&A) MappedMatrixBlock ( &(glu.lusup.data()[luptr+nsupc]), nrow, nsupc, OuterStride<>(lda) );\n    VectorBlock<ScalarVector> l(glu.lusup, ufirst+nsupc, nrow); \n    l.noalias() -= A * u;\n    \n  } // End if fst_col\n  return 0; \n}\n\n} // end namespace internal\n} // end namespace Eigen\n\n#endif // SPARSELU_COLUMN_BMOD_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseLU/SparseLU_column_dfs.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/* \n \n * NOTE: This file is the modified version of [s,d,c,z]column_dfs.c file in SuperLU \n \n * -- SuperLU routine (version 2.0) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * November 15, 1997\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n#ifndef SPARSELU_COLUMN_DFS_H\n#define SPARSELU_COLUMN_DFS_H\n\ntemplate <typename Scalar, typename StorageIndex> class SparseLUImpl;\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate<typename IndexVector, typename ScalarVector>\nstruct column_dfs_traits : no_assignment_operator\n{\n  typedef typename ScalarVector::Scalar Scalar;\n  typedef typename IndexVector::Scalar StorageIndex;\n  column_dfs_traits(Index jcol, Index& jsuper, typename SparseLUImpl<Scalar, StorageIndex>::GlobalLU_t& glu, SparseLUImpl<Scalar, StorageIndex>& luImpl)\n   : m_jcol(jcol), m_jsuper_ref(jsuper), m_glu(glu), m_luImpl(luImpl)\n {}\n  bool update_segrep(Index /*krep*/, Index /*jj*/)\n  {\n    return true;\n  }\n  void mem_expand(IndexVector& lsub, Index& nextl, Index chmark)\n  {\n    if (nextl >= m_glu.nzlmax)\n      m_luImpl.memXpand(lsub, m_glu.nzlmax, nextl, LSUB, m_glu.num_expansions); \n    if (chmark != (m_jcol-1)) m_jsuper_ref = emptyIdxLU;\n  }\n  enum { ExpandMem = true };\n  \n  Index m_jcol;\n  Index& m_jsuper_ref;\n  typename SparseLUImpl<Scalar, StorageIndex>::GlobalLU_t& m_glu;\n  SparseLUImpl<Scalar, StorageIndex>& m_luImpl;\n};\n\n\n/**\n * \\brief Performs a symbolic factorization on column jcol and decide the supernode boundary\n * \n * A supernode representative is the last column of a supernode.\n * The nonzeros in U[*,j] are segments that end at supernodes representatives. \n * The routine returns a list of the supernodal representatives \n * in topological order of the dfs that generates them. \n * The location of the first nonzero in each supernodal segment \n * (supernodal entry location) is also returned. \n * \n * \\param m number of rows in the matrix\n * \\param jcol Current column \n * \\param perm_r Row permutation\n * \\param maxsuper  Maximum number of column allowed in a supernode\n * \\param [in,out] nseg Number of segments in current U[*,j] - new segments appended\n * \\param lsub_col defines the rhs vector to start the dfs\n * \\param [in,out] segrep Segment representatives - new segments appended \n * \\param repfnz  First nonzero location in each row\n * \\param xprune \n * \\param marker  marker[i] == jj, if i was visited during dfs of current column jj;\n * \\param parent\n * \\param xplore working array\n * \\param glu global LU data \n * \\return 0 success\n *         > 0 number of bytes allocated when run out of space\n * \n */\ntemplate <typename Scalar, typename StorageIndex>\nIndex SparseLUImpl<Scalar,StorageIndex>::column_dfs(const Index m, const Index jcol, IndexVector& perm_r, Index maxsuper, Index& nseg,\n                                                    BlockIndexVector lsub_col, IndexVector& segrep, BlockIndexVector repfnz, IndexVector& xprune,\n                                                    IndexVector& marker, IndexVector& parent, IndexVector& xplore, GlobalLU_t& glu)\n{\n  \n  Index jsuper = glu.supno(jcol); \n  Index nextl = glu.xlsub(jcol); \n  VectorBlock<IndexVector> marker2(marker, 2*m, m); \n  \n  \n  column_dfs_traits<IndexVector, ScalarVector> traits(jcol, jsuper, glu, *this);\n  \n  // For each nonzero in A(*,jcol) do dfs \n  for (Index k = 0; ((k < m) ? lsub_col[k] != emptyIdxLU : false) ; k++)\n  {\n    Index krow = lsub_col(k); \n    lsub_col(k) = emptyIdxLU; \n    Index kmark = marker2(krow); \n    \n    // krow was visited before, go to the next nonz; \n    if (kmark == jcol) continue;\n    \n    dfs_kernel(StorageIndex(jcol), perm_r, nseg, glu.lsub, segrep, repfnz, xprune, marker2, parent,\n                   xplore, glu, nextl, krow, traits);\n  } // for each nonzero ... \n  \n  Index fsupc;\n  StorageIndex nsuper = glu.supno(jcol);\n  StorageIndex jcolp1 = StorageIndex(jcol) + 1;\n  Index jcolm1 = jcol - 1;\n  \n  // check to see if j belongs in the same supernode as j-1\n  if ( jcol == 0 )\n  { // Do nothing for column 0 \n    nsuper = glu.supno(0) = 0 ;\n  }\n  else \n  {\n    fsupc = glu.xsup(nsuper); \n    StorageIndex jptr = glu.xlsub(jcol); // Not yet compressed\n    StorageIndex jm1ptr = glu.xlsub(jcolm1); \n    \n    // Use supernodes of type T2 : see SuperLU paper\n    if ( (nextl-jptr != jptr-jm1ptr-1) ) jsuper = emptyIdxLU;\n    \n    // Make sure the number of columns in a supernode doesn't\n    // exceed threshold\n    if ( (jcol - fsupc) >= maxsuper) jsuper = emptyIdxLU; \n    \n    /* If jcol starts a new supernode, reclaim storage space in\n     * glu.lsub from previous supernode. Note we only store \n     * the subscript set of the first and last columns of \n     * a supernode. (first for num values, last for pruning)\n     */\n    if (jsuper == emptyIdxLU)\n    { // starts a new supernode \n      if ( (fsupc < jcolm1-1) ) \n      { // >= 3 columns in nsuper\n        StorageIndex ito = glu.xlsub(fsupc+1);\n        glu.xlsub(jcolm1) = ito; \n        StorageIndex istop = ito + jptr - jm1ptr; \n        xprune(jcolm1) = istop; // initialize xprune(jcol-1)\n        glu.xlsub(jcol) = istop; \n        \n        for (StorageIndex ifrom = jm1ptr; ifrom < nextl; ++ifrom, ++ito)\n          glu.lsub(ito) = glu.lsub(ifrom); \n        nextl = ito;  // = istop + length(jcol)\n      }\n      nsuper++; \n      glu.supno(jcol) = nsuper; \n    } // if a new supernode \n  } // end else:  jcol > 0\n  \n  // Tidy up the pointers before exit\n  glu.xsup(nsuper+1) = jcolp1; \n  glu.supno(jcolp1) = nsuper; \n  xprune(jcol) = StorageIndex(nextl);  // Initialize upper bound for pruning\n  glu.xlsub(jcolp1) = StorageIndex(nextl); \n  \n  return 0; \n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseLU/SparseLU_copy_to_ucol.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n/* \n \n * NOTE: This file is the modified version of [s,d,c,z]copy_to_ucol.c file in SuperLU \n \n * -- SuperLU routine (version 2.0) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * November 15, 1997\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n#ifndef SPARSELU_COPY_TO_UCOL_H\n#define SPARSELU_COPY_TO_UCOL_H\n\nnamespace Eigen {\nnamespace internal {\n\n/**\n * \\brief Performs numeric block updates (sup-col) in topological order\n * \n * \\param jcol current column to update\n * \\param nseg Number of segments in the U part\n * \\param segrep segment representative ...\n * \\param repfnz First nonzero column in each row  ...\n * \\param perm_r Row permutation \n * \\param dense Store the full representation of the column\n * \\param glu Global LU data. \n * \\return 0 - successful return \n *         > 0 - number of bytes allocated when run out of space\n * \n */\ntemplate <typename Scalar, typename StorageIndex>\nIndex SparseLUImpl<Scalar,StorageIndex>::copy_to_ucol(const Index jcol, const Index nseg, IndexVector& segrep,\n                                                      BlockIndexVector repfnz ,IndexVector& perm_r, BlockScalarVector dense, GlobalLU_t& glu)\n{  \n  Index ksub, krep, ksupno; \n    \n  Index jsupno = glu.supno(jcol);\n  \n  // For each nonzero supernode segment of U[*,j] in topological order \n  Index k = nseg - 1, i; \n  StorageIndex nextu = glu.xusub(jcol); \n  Index kfnz, isub, segsize; \n  Index new_next,irow; \n  Index fsupc, mem; \n  for (ksub = 0; ksub < nseg; ksub++)\n  {\n    krep = segrep(k); k--; \n    ksupno = glu.supno(krep); \n    if (jsupno != ksupno ) // should go into ucol(); \n    {\n      kfnz = repfnz(krep); \n      if (kfnz != emptyIdxLU)\n      { // Nonzero U-segment \n        fsupc = glu.xsup(ksupno); \n        isub = glu.xlsub(fsupc) + kfnz - fsupc; \n        segsize = krep - kfnz + 1; \n        new_next = nextu + segsize; \n        while (new_next > glu.nzumax) \n        {\n          mem = memXpand<ScalarVector>(glu.ucol, glu.nzumax, nextu, UCOL, glu.num_expansions); \n          if (mem) return mem; \n          mem = memXpand<IndexVector>(glu.usub, glu.nzumax, nextu, USUB, glu.num_expansions); \n          if (mem) return mem; \n          \n        }\n        \n        for (i = 0; i < segsize; i++)\n        {\n          irow = glu.lsub(isub); \n          glu.usub(nextu) = perm_r(irow); // Unlike the L part, the U part is stored in its final order\n          glu.ucol(nextu) = dense(irow); \n          dense(irow) = Scalar(0.0); \n          nextu++;\n          isub++;\n        }\n        \n      } // end nonzero U-segment \n      \n    } // end if jsupno \n    \n  } // end for each segment\n  glu.xusub(jcol + 1) = nextu; // close U(*,jcol)\n  return 0; \n}\n\n} // namespace internal\n} // end namespace Eigen\n\n#endif // SPARSELU_COPY_TO_UCOL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseLU/SparseLU_gemm_kernel.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSELU_GEMM_KERNEL_H\n#define EIGEN_SPARSELU_GEMM_KERNEL_H\n\nnamespace Eigen {\n\nnamespace internal {\n\n\n/** \\internal\n  * A general matrix-matrix product kernel optimized for the SparseLU factorization.\n  *  - A, B, and C must be column major\n  *  - lda and ldc must be multiples of the respective packet size\n  *  - C must have the same alignment as A\n  */\ntemplate<typename Scalar>\nEIGEN_DONT_INLINE\nvoid sparselu_gemm(Index m, Index n, Index d, const Scalar* A, Index lda, const Scalar* B, Index ldb, Scalar* C, Index ldc)\n{\n  using namespace Eigen::internal;\n  \n  typedef typename packet_traits<Scalar>::type Packet;\n  enum {\n    NumberOfRegisters = EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS,\n    PacketSize = packet_traits<Scalar>::size,\n    PM = 8,                             // peeling in M\n    RN = 2,                             // register blocking\n    RK = NumberOfRegisters>=16 ? 4 : 2, // register blocking\n    BM = 4096/sizeof(Scalar),           // number of rows of A-C per chunk\n    SM = PM*PacketSize                  // step along M\n  };\n  Index d_end = (d/RK)*RK;    // number of columns of A (rows of B) suitable for full register blocking\n  Index n_end = (n/RN)*RN;    // number of columns of B-C suitable for processing RN columns at once\n  Index i0 = internal::first_default_aligned(A,m);\n  \n  eigen_internal_assert(((lda%PacketSize)==0) && ((ldc%PacketSize)==0) && (i0==internal::first_default_aligned(C,m)));\n  \n  // handle the non aligned rows of A and C without any optimization:\n  for(Index i=0; i<i0; ++i)\n  {\n    for(Index j=0; j<n; ++j)\n    {\n      Scalar c = C[i+j*ldc];\n      for(Index k=0; k<d; ++k)\n        c += B[k+j*ldb] * A[i+k*lda];\n      C[i+j*ldc] = c;\n    }\n  }\n  // process the remaining rows per chunk of BM rows\n  for(Index ib=i0; ib<m; ib+=BM)\n  {\n    Index actual_b = std::min<Index>(BM, m-ib);                 // actual number of rows\n    Index actual_b_end1 = (actual_b/SM)*SM;                   // actual number of rows suitable for peeling\n    Index actual_b_end2 = (actual_b/PacketSize)*PacketSize;   // actual number of rows suitable for vectorization\n    \n    // Let's process two columns of B-C at once\n    for(Index j=0; j<n_end; j+=RN)\n    {\n      const Scalar* Bc0 = B+(j+0)*ldb;\n      const Scalar* Bc1 = B+(j+1)*ldb;\n      \n      for(Index k=0; k<d_end; k+=RK)\n      {\n        \n        // load and expand a RN x RK block of B\n        Packet b00, b10, b20, b30, b01, b11, b21, b31;\n                  { b00 = pset1<Packet>(Bc0[0]); }\n                  { b10 = pset1<Packet>(Bc0[1]); }\n        if(RK==4) { b20 = pset1<Packet>(Bc0[2]); }\n        if(RK==4) { b30 = pset1<Packet>(Bc0[3]); }\n                  { b01 = pset1<Packet>(Bc1[0]); }\n                  { b11 = pset1<Packet>(Bc1[1]); }\n        if(RK==4) { b21 = pset1<Packet>(Bc1[2]); }\n        if(RK==4) { b31 = pset1<Packet>(Bc1[3]); }\n        \n        Packet a0, a1, a2, a3, c0, c1, t0, t1;\n        \n        const Scalar* A0 = A+ib+(k+0)*lda;\n        const Scalar* A1 = A+ib+(k+1)*lda;\n        const Scalar* A2 = A+ib+(k+2)*lda;\n        const Scalar* A3 = A+ib+(k+3)*lda;\n        \n        Scalar* C0 = C+ib+(j+0)*ldc;\n        Scalar* C1 = C+ib+(j+1)*ldc;\n        \n                  a0 = pload<Packet>(A0);\n                  a1 = pload<Packet>(A1);\n        if(RK==4)\n        {\n          a2 = pload<Packet>(A2);\n          a3 = pload<Packet>(A3);\n        }\n        else\n        {\n          // workaround \"may be used uninitialized in this function\" warning\n          a2 = a3 = a0;\n        }\n        \n#define KMADD(c, a, b, tmp) {tmp = b; tmp = pmul(a,tmp); c = padd(c,tmp);}\n#define WORK(I)  \\\n                     c0 = pload<Packet>(C0+i+(I)*PacketSize);    \\\n                     c1 = pload<Packet>(C1+i+(I)*PacketSize);    \\\n                     KMADD(c0, a0, b00, t0)                      \\\n                     KMADD(c1, a0, b01, t1)                      \\\n                     a0 = pload<Packet>(A0+i+(I+1)*PacketSize);  \\\n                     KMADD(c0, a1, b10, t0)                      \\\n                     KMADD(c1, a1, b11, t1)                      \\\n                     a1 = pload<Packet>(A1+i+(I+1)*PacketSize);  \\\n          if(RK==4){ KMADD(c0, a2, b20, t0)                     }\\\n          if(RK==4){ KMADD(c1, a2, b21, t1)                     }\\\n          if(RK==4){ a2 = pload<Packet>(A2+i+(I+1)*PacketSize); }\\\n          if(RK==4){ KMADD(c0, a3, b30, t0)                     }\\\n          if(RK==4){ KMADD(c1, a3, b31, t1)                     }\\\n          if(RK==4){ a3 = pload<Packet>(A3+i+(I+1)*PacketSize); }\\\n                     pstore(C0+i+(I)*PacketSize, c0);            \\\n                     pstore(C1+i+(I)*PacketSize, c1)\n        \n        // process rows of A' - C' with aggressive vectorization and peeling \n        for(Index i=0; i<actual_b_end1; i+=PacketSize*8)\n        {\n          EIGEN_ASM_COMMENT(\"SPARSELU_GEMML_KERNEL1\");\n                    prefetch((A0+i+(5)*PacketSize));\n                    prefetch((A1+i+(5)*PacketSize));\n          if(RK==4) prefetch((A2+i+(5)*PacketSize));\n          if(RK==4) prefetch((A3+i+(5)*PacketSize));\n\n          WORK(0);\n          WORK(1);\n          WORK(2);\n          WORK(3);\n          WORK(4);\n          WORK(5);\n          WORK(6);\n          WORK(7);\n        }\n        // process the remaining rows with vectorization only\n        for(Index i=actual_b_end1; i<actual_b_end2; i+=PacketSize)\n        {\n          WORK(0);\n        }\n#undef WORK\n        // process the remaining rows without vectorization\n        for(Index i=actual_b_end2; i<actual_b; ++i)\n        {\n          if(RK==4)\n          {\n            C0[i] += A0[i]*Bc0[0]+A1[i]*Bc0[1]+A2[i]*Bc0[2]+A3[i]*Bc0[3];\n            C1[i] += A0[i]*Bc1[0]+A1[i]*Bc1[1]+A2[i]*Bc1[2]+A3[i]*Bc1[3];\n          }\n          else\n          {\n            C0[i] += A0[i]*Bc0[0]+A1[i]*Bc0[1];\n            C1[i] += A0[i]*Bc1[0]+A1[i]*Bc1[1];\n          }\n        }\n        \n        Bc0 += RK;\n        Bc1 += RK;\n      } // peeled loop on k\n    } // peeled loop on the columns j\n    // process the last column (we now perform a matrix-vector product)\n    if((n-n_end)>0)\n    {\n      const Scalar* Bc0 = B+(n-1)*ldb;\n      \n      for(Index k=0; k<d_end; k+=RK)\n      {\n        \n        // load and expand a 1 x RK block of B\n        Packet b00, b10, b20, b30;\n                  b00 = pset1<Packet>(Bc0[0]);\n                  b10 = pset1<Packet>(Bc0[1]);\n        if(RK==4) b20 = pset1<Packet>(Bc0[2]);\n        if(RK==4) b30 = pset1<Packet>(Bc0[3]);\n        \n        Packet a0, a1, a2, a3, c0, t0/*, t1*/;\n        \n        const Scalar* A0 = A+ib+(k+0)*lda;\n        const Scalar* A1 = A+ib+(k+1)*lda;\n        const Scalar* A2 = A+ib+(k+2)*lda;\n        const Scalar* A3 = A+ib+(k+3)*lda;\n        \n        Scalar* C0 = C+ib+(n_end)*ldc;\n        \n                  a0 = pload<Packet>(A0);\n                  a1 = pload<Packet>(A1);\n        if(RK==4)\n        {\n          a2 = pload<Packet>(A2);\n          a3 = pload<Packet>(A3);\n        }\n        else\n        {\n          // workaround \"may be used uninitialized in this function\" warning\n          a2 = a3 = a0;\n        }\n        \n#define WORK(I) \\\n                   c0 = pload<Packet>(C0+i+(I)*PacketSize);     \\\n                   KMADD(c0, a0, b00, t0)                       \\\n                   a0 = pload<Packet>(A0+i+(I+1)*PacketSize);   \\\n                   KMADD(c0, a1, b10, t0)                       \\\n                   a1 = pload<Packet>(A1+i+(I+1)*PacketSize);   \\\n        if(RK==4){ KMADD(c0, a2, b20, t0)                      }\\\n        if(RK==4){ a2 = pload<Packet>(A2+i+(I+1)*PacketSize);  }\\\n        if(RK==4){ KMADD(c0, a3, b30, t0)                      }\\\n        if(RK==4){ a3 = pload<Packet>(A3+i+(I+1)*PacketSize);  }\\\n                   pstore(C0+i+(I)*PacketSize, c0);\n        \n        // aggressive vectorization and peeling\n        for(Index i=0; i<actual_b_end1; i+=PacketSize*8)\n        {\n          EIGEN_ASM_COMMENT(\"SPARSELU_GEMML_KERNEL2\");\n          WORK(0);\n          WORK(1);\n          WORK(2);\n          WORK(3);\n          WORK(4);\n          WORK(5);\n          WORK(6);\n          WORK(7);\n        }\n        // vectorization only\n        for(Index i=actual_b_end1; i<actual_b_end2; i+=PacketSize)\n        {\n          WORK(0);\n        }\n        // remaining scalars\n        for(Index i=actual_b_end2; i<actual_b; ++i)\n        {\n          if(RK==4) \n            C0[i] += A0[i]*Bc0[0]+A1[i]*Bc0[1]+A2[i]*Bc0[2]+A3[i]*Bc0[3];\n          else\n            C0[i] += A0[i]*Bc0[0]+A1[i]*Bc0[1];\n        }\n        \n        Bc0 += RK;\n#undef WORK\n      }\n    }\n    \n    // process the last columns of A, corresponding to the last rows of B\n    Index rd = d-d_end;\n    if(rd>0)\n    {\n      for(Index j=0; j<n; ++j)\n      {\n        enum {\n          Alignment = PacketSize>1 ? Aligned : 0\n        };\n        typedef Map<Matrix<Scalar,Dynamic,1>, Alignment > MapVector;\n        typedef Map<const Matrix<Scalar,Dynamic,1>, Alignment > ConstMapVector;\n        if(rd==1)       MapVector(C+j*ldc+ib,actual_b) += B[0+d_end+j*ldb] * ConstMapVector(A+(d_end+0)*lda+ib, actual_b);\n        \n        else if(rd==2)  MapVector(C+j*ldc+ib,actual_b) += B[0+d_end+j*ldb] * ConstMapVector(A+(d_end+0)*lda+ib, actual_b)\n                                                        + B[1+d_end+j*ldb] * ConstMapVector(A+(d_end+1)*lda+ib, actual_b);\n        \n        else            MapVector(C+j*ldc+ib,actual_b) += B[0+d_end+j*ldb] * ConstMapVector(A+(d_end+0)*lda+ib, actual_b)\n                                                        + B[1+d_end+j*ldb] * ConstMapVector(A+(d_end+1)*lda+ib, actual_b)\n                                                        + B[2+d_end+j*ldb] * ConstMapVector(A+(d_end+2)*lda+ib, actual_b);\n      }\n    }\n  \n  } // blocking on the rows of A and C\n}\n#undef KMADD\n\n} // namespace internal\n\n} // namespace Eigen\n\n#endif // EIGEN_SPARSELU_GEMM_KERNEL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseLU/SparseLU_heap_relax_snode.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/* This file is a modified version of heap_relax_snode.c file in SuperLU\n * -- SuperLU routine (version 3.0) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * October 15, 2003\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n\n#ifndef SPARSELU_HEAP_RELAX_SNODE_H\n#define SPARSELU_HEAP_RELAX_SNODE_H\n\nnamespace Eigen {\nnamespace internal {\n\n/** \n * \\brief Identify the initial relaxed supernodes\n * \n * This routine applied to a symmetric elimination tree. \n * It assumes that the matrix has been reordered according to the postorder of the etree\n * \\param n The number of columns\n * \\param et elimination tree \n * \\param relax_columns Maximum number of columns allowed in a relaxed snode \n * \\param descendants Number of descendants of each node in the etree\n * \\param relax_end last column in a supernode\n */\ntemplate <typename Scalar, typename StorageIndex>\nvoid SparseLUImpl<Scalar,StorageIndex>::heap_relax_snode (const Index n, IndexVector& et, const Index relax_columns, IndexVector& descendants, IndexVector& relax_end)\n{\n  \n  // The etree may not be postordered, but its heap ordered  \n  IndexVector post;\n  internal::treePostorder(StorageIndex(n), et, post); // Post order etree\n  IndexVector inv_post(n+1); \n  for (StorageIndex i = 0; i < n+1; ++i) inv_post(post(i)) = i; // inv_post = post.inverse()???\n  \n  // Renumber etree in postorder \n  IndexVector iwork(n);\n  IndexVector et_save(n+1);\n  for (Index i = 0; i < n; ++i)\n  {\n    iwork(post(i)) = post(et(i));\n  }\n  et_save = et; // Save the original etree\n  et = iwork; \n  \n  // compute the number of descendants of each node in the etree\n  relax_end.setConstant(emptyIdxLU);\n  Index j, parent; \n  descendants.setZero();\n  for (j = 0; j < n; j++) \n  {\n    parent = et(j);\n    if (parent != n) // not the dummy root\n      descendants(parent) += descendants(j) + 1;\n  }\n  // Identify the relaxed supernodes by postorder traversal of the etree\n  Index snode_start; // beginning of a snode \n  StorageIndex k;\n  Index nsuper_et_post = 0; // Number of relaxed snodes in postordered etree \n  Index nsuper_et = 0; // Number of relaxed snodes in the original etree \n  StorageIndex l; \n  for (j = 0; j < n; )\n  {\n    parent = et(j);\n    snode_start = j; \n    while ( parent != n && descendants(parent) < relax_columns ) \n    {\n      j = parent; \n      parent = et(j);\n    }\n    // Found a supernode in postordered etree, j is the last column \n    ++nsuper_et_post;\n    k = StorageIndex(n);\n    for (Index i = snode_start; i <= j; ++i)\n      k = (std::min)(k, inv_post(i));\n    l = inv_post(j);\n    if ( (l - k) == (j - snode_start) )  // Same number of columns in the snode\n    {\n      // This is also a supernode in the original etree\n      relax_end(k) = l; // Record last column \n      ++nsuper_et; \n    }\n    else \n    {\n      for (Index i = snode_start; i <= j; ++i) \n      {\n        l = inv_post(i);\n        if (descendants(i) == 0) \n        {\n          relax_end(l) = l;\n          ++nsuper_et;\n        }\n      }\n    }\n    j++;\n    // Search for a new leaf\n    while (descendants(j) != 0 && j < n) j++;\n  } // End postorder traversal of the etree\n  \n  // Recover the original etree\n  et = et_save; \n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n#endif // SPARSELU_HEAP_RELAX_SNODE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseLU/SparseLU_kernel_bmod.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef SPARSELU_KERNEL_BMOD_H\n#define SPARSELU_KERNEL_BMOD_H\n\nnamespace Eigen {\nnamespace internal {\n  \ntemplate <int SegSizeAtCompileTime> struct LU_kernel_bmod\n{\n  /** \\internal\n    * \\brief Performs numeric block updates from a given supernode to a single column\n    *\n    * \\param segsize Size of the segment (and blocks ) to use for updates\n    * \\param[in,out] dense Packed values of the original matrix\n    * \\param tempv temporary vector to use for updates\n    * \\param lusup array containing the supernodes\n    * \\param lda Leading dimension in the supernode\n    * \\param nrow Number of rows in the rectangular part of the supernode\n    * \\param lsub compressed row subscripts of supernodes\n    * \\param lptr pointer to the first column of the current supernode in lsub\n    * \\param no_zeros Number of nonzeros elements before the diagonal part of the supernode\n    */\n  template <typename BlockScalarVector, typename ScalarVector, typename IndexVector>\n  static EIGEN_DONT_INLINE void run(const Index segsize, BlockScalarVector& dense, ScalarVector& tempv, ScalarVector& lusup, Index& luptr, const Index lda,\n                                    const Index nrow, IndexVector& lsub, const Index lptr, const Index no_zeros);\n};\n\ntemplate <int SegSizeAtCompileTime>\ntemplate <typename BlockScalarVector, typename ScalarVector, typename IndexVector>\nEIGEN_DONT_INLINE void LU_kernel_bmod<SegSizeAtCompileTime>::run(const Index segsize, BlockScalarVector& dense, ScalarVector& tempv, ScalarVector& lusup, Index& luptr, const Index lda,\n                                                                  const Index nrow, IndexVector& lsub, const Index lptr, const Index no_zeros)\n{\n  typedef typename ScalarVector::Scalar Scalar;\n  // First, copy U[*,j] segment from dense(*) to tempv(*)\n  // The result of triangular solve is in tempv[*]; \n    // The result of matric-vector update is in dense[*]\n  Index isub = lptr + no_zeros; \n  Index i;\n  Index irow;\n  for (i = 0; i < ((SegSizeAtCompileTime==Dynamic)?segsize:SegSizeAtCompileTime); i++)\n  {\n    irow = lsub(isub); \n    tempv(i) = dense(irow); \n    ++isub; \n  }\n  // Dense triangular solve -- start effective triangle\n  luptr += lda * no_zeros + no_zeros; \n  // Form Eigen matrix and vector \n  Map<Matrix<Scalar,SegSizeAtCompileTime,SegSizeAtCompileTime, ColMajor>, 0, OuterStride<> > A( &(lusup.data()[luptr]), segsize, segsize, OuterStride<>(lda) );\n  Map<Matrix<Scalar,SegSizeAtCompileTime,1> > u(tempv.data(), segsize);\n  \n  u = A.template triangularView<UnitLower>().solve(u); \n  \n  // Dense matrix-vector product y <-- B*x \n  luptr += segsize;\n  const Index PacketSize = internal::packet_traits<Scalar>::size;\n  Index ldl = internal::first_multiple(nrow, PacketSize);\n  Map<Matrix<Scalar,Dynamic,SegSizeAtCompileTime, ColMajor>, 0, OuterStride<> > B( &(lusup.data()[luptr]), nrow, segsize, OuterStride<>(lda) );\n  Index aligned_offset = internal::first_default_aligned(tempv.data()+segsize, PacketSize);\n  Index aligned_with_B_offset = (PacketSize-internal::first_default_aligned(B.data(), PacketSize))%PacketSize;\n  Map<Matrix<Scalar,Dynamic,1>, 0, OuterStride<> > l(tempv.data()+segsize+aligned_offset+aligned_with_B_offset, nrow, OuterStride<>(ldl) );\n  \n  l.setZero();\n  internal::sparselu_gemm<Scalar>(l.rows(), l.cols(), B.cols(), B.data(), B.outerStride(), u.data(), u.outerStride(), l.data(), l.outerStride());\n  \n  // Scatter tempv[] into SPA dense[] as a temporary storage \n  isub = lptr + no_zeros;\n  for (i = 0; i < ((SegSizeAtCompileTime==Dynamic)?segsize:SegSizeAtCompileTime); i++)\n  {\n    irow = lsub(isub++); \n    dense(irow) = tempv(i);\n  }\n  \n  // Scatter l into SPA dense[]\n  for (i = 0; i < nrow; i++)\n  {\n    irow = lsub(isub++); \n    dense(irow) -= l(i);\n  } \n}\n\ntemplate <> struct LU_kernel_bmod<1>\n{\n  template <typename BlockScalarVector, typename ScalarVector, typename IndexVector>\n  static EIGEN_DONT_INLINE void run(const Index /*segsize*/, BlockScalarVector& dense, ScalarVector& /*tempv*/, ScalarVector& lusup, Index& luptr,\n                                    const Index lda, const Index nrow, IndexVector& lsub, const Index lptr, const Index no_zeros);\n};\n\n\ntemplate <typename BlockScalarVector, typename ScalarVector, typename IndexVector>\nEIGEN_DONT_INLINE void LU_kernel_bmod<1>::run(const Index /*segsize*/, BlockScalarVector& dense, ScalarVector& /*tempv*/, ScalarVector& lusup, Index& luptr,\n                                              const Index lda, const Index nrow, IndexVector& lsub, const Index lptr, const Index no_zeros)\n{\n  typedef typename ScalarVector::Scalar Scalar;\n  typedef typename IndexVector::Scalar StorageIndex;\n  Scalar f = dense(lsub(lptr + no_zeros));\n  luptr += lda * no_zeros + no_zeros + 1;\n  const Scalar* a(lusup.data() + luptr);\n  const StorageIndex*  irow(lsub.data()+lptr + no_zeros + 1);\n  Index i = 0;\n  for (; i+1 < nrow; i+=2)\n  {\n    Index i0 = *(irow++);\n    Index i1 = *(irow++);\n    Scalar a0 = *(a++);\n    Scalar a1 = *(a++);\n    Scalar d0 = dense.coeff(i0);\n    Scalar d1 = dense.coeff(i1);\n    d0 -= f*a0;\n    d1 -= f*a1;\n    dense.coeffRef(i0) = d0;\n    dense.coeffRef(i1) = d1;\n  }\n  if(i<nrow)\n    dense.coeffRef(*(irow++)) -= f * *(a++);\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n#endif // SPARSELU_KERNEL_BMOD_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseLU/SparseLU_panel_bmod.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/* \n \n * NOTE: This file is the modified version of [s,d,c,z]panel_bmod.c file in SuperLU \n \n * -- SuperLU routine (version 3.0) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * October 15, 2003\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n#ifndef SPARSELU_PANEL_BMOD_H\n#define SPARSELU_PANEL_BMOD_H\n\nnamespace Eigen {\nnamespace internal {\n\n/**\n * \\brief Performs numeric block updates (sup-panel) in topological order.\n * \n * Before entering this routine, the original nonzeros in the panel\n * were already copied into the spa[m,w]\n * \n * \\param m number of rows in the matrix\n * \\param w Panel size\n * \\param jcol Starting  column of the panel\n * \\param nseg Number of segments in the U part\n * \\param dense Store the full representation of the panel \n * \\param tempv working array \n * \\param segrep segment representative... first row in the segment\n * \\param repfnz First nonzero rows\n * \\param glu Global LU data. \n * \n * \n */\ntemplate <typename Scalar, typename StorageIndex>\nvoid SparseLUImpl<Scalar,StorageIndex>::panel_bmod(const Index m, const Index w, const Index jcol, \n                                            const Index nseg, ScalarVector& dense, ScalarVector& tempv,\n                                            IndexVector& segrep, IndexVector& repfnz, GlobalLU_t& glu)\n{\n  \n  Index ksub,jj,nextl_col; \n  Index fsupc, nsupc, nsupr, nrow; \n  Index krep, kfnz; \n  Index lptr; // points to the row subscripts of a supernode \n  Index luptr; // ...\n  Index segsize,no_zeros ; \n  // For each nonz supernode segment of U[*,j] in topological order\n  Index k = nseg - 1; \n  const Index PacketSize = internal::packet_traits<Scalar>::size;\n  \n  for (ksub = 0; ksub < nseg; ksub++)\n  { // For each updating supernode\n    /* krep = representative of current k-th supernode\n     * fsupc =  first supernodal column\n     * nsupc = number of columns in a supernode\n     * nsupr = number of rows in a supernode\n     */\n    krep = segrep(k); k--; \n    fsupc = glu.xsup(glu.supno(krep)); \n    nsupc = krep - fsupc + 1; \n    nsupr = glu.xlsub(fsupc+1) - glu.xlsub(fsupc); \n    nrow = nsupr - nsupc; \n    lptr = glu.xlsub(fsupc); \n    \n    // loop over the panel columns to detect the actual number of columns and rows\n    Index u_rows = 0;\n    Index u_cols = 0;\n    for (jj = jcol; jj < jcol + w; jj++)\n    {\n      nextl_col = (jj-jcol) * m; \n      VectorBlock<IndexVector> repfnz_col(repfnz, nextl_col, m); // First nonzero column index for each row\n      \n      kfnz = repfnz_col(krep); \n      if ( kfnz == emptyIdxLU ) \n        continue; // skip any zero segment\n      \n      segsize = krep - kfnz + 1;\n      u_cols++;\n      u_rows = (std::max)(segsize,u_rows);\n    }\n    \n    if(nsupc >= 2)\n    { \n      Index ldu = internal::first_multiple<Index>(u_rows, PacketSize);\n      Map<ScalarMatrix, Aligned,  OuterStride<> > U(tempv.data(), u_rows, u_cols, OuterStride<>(ldu));\n      \n      // gather U\n      Index u_col = 0;\n      for (jj = jcol; jj < jcol + w; jj++)\n      {\n        nextl_col = (jj-jcol) * m; \n        VectorBlock<IndexVector> repfnz_col(repfnz, nextl_col, m); // First nonzero column index for each row\n        VectorBlock<ScalarVector> dense_col(dense, nextl_col, m); // Scatter/gather entire matrix column from/to here\n        \n        kfnz = repfnz_col(krep); \n        if ( kfnz == emptyIdxLU ) \n          continue; // skip any zero segment\n        \n        segsize = krep - kfnz + 1;\n        luptr = glu.xlusup(fsupc);    \n        no_zeros = kfnz - fsupc; \n        \n        Index isub = lptr + no_zeros;\n        Index off = u_rows-segsize;\n        for (Index i = 0; i < off; i++) U(i,u_col) = 0;\n        for (Index i = 0; i < segsize; i++)\n        {\n          Index irow = glu.lsub(isub); \n          U(i+off,u_col) = dense_col(irow); \n          ++isub; \n        }\n        u_col++;\n      }\n      // solve U = A^-1 U\n      luptr = glu.xlusup(fsupc);\n      Index lda = glu.xlusup(fsupc+1) - glu.xlusup(fsupc);\n      no_zeros = (krep - u_rows + 1) - fsupc;\n      luptr += lda * no_zeros + no_zeros;\n      MappedMatrixBlock A(glu.lusup.data()+luptr, u_rows, u_rows, OuterStride<>(lda) );\n      U = A.template triangularView<UnitLower>().solve(U);\n      \n      // update\n      luptr += u_rows;\n      MappedMatrixBlock B(glu.lusup.data()+luptr, nrow, u_rows, OuterStride<>(lda) );\n      eigen_assert(tempv.size()>w*ldu + nrow*w + 1);\n      \n      Index ldl = internal::first_multiple<Index>(nrow, PacketSize);\n      Index offset = (PacketSize-internal::first_default_aligned(B.data(), PacketSize)) % PacketSize;\n      MappedMatrixBlock L(tempv.data()+w*ldu+offset, nrow, u_cols, OuterStride<>(ldl));\n      \n      L.setZero();\n      internal::sparselu_gemm<Scalar>(L.rows(), L.cols(), B.cols(), B.data(), B.outerStride(), U.data(), U.outerStride(), L.data(), L.outerStride());\n      \n      // scatter U and L\n      u_col = 0;\n      for (jj = jcol; jj < jcol + w; jj++)\n      {\n        nextl_col = (jj-jcol) * m; \n        VectorBlock<IndexVector> repfnz_col(repfnz, nextl_col, m); // First nonzero column index for each row\n        VectorBlock<ScalarVector> dense_col(dense, nextl_col, m); // Scatter/gather entire matrix column from/to here\n        \n        kfnz = repfnz_col(krep); \n        if ( kfnz == emptyIdxLU ) \n          continue; // skip any zero segment\n        \n        segsize = krep - kfnz + 1;\n        no_zeros = kfnz - fsupc; \n        Index isub = lptr + no_zeros;\n        \n        Index off = u_rows-segsize;\n        for (Index i = 0; i < segsize; i++)\n        {\n          Index irow = glu.lsub(isub++); \n          dense_col(irow) = U.coeff(i+off,u_col);\n          U.coeffRef(i+off,u_col) = 0;\n        }\n        \n        // Scatter l into SPA dense[]\n        for (Index i = 0; i < nrow; i++)\n        {\n          Index irow = glu.lsub(isub++); \n          dense_col(irow) -= L.coeff(i,u_col);\n          L.coeffRef(i,u_col) = 0;\n        }\n        u_col++;\n      }\n    }\n    else // level 2 only\n    {\n      // Sequence through each column in the panel\n      for (jj = jcol; jj < jcol + w; jj++)\n      {\n        nextl_col = (jj-jcol) * m; \n        VectorBlock<IndexVector> repfnz_col(repfnz, nextl_col, m); // First nonzero column index for each row\n        VectorBlock<ScalarVector> dense_col(dense, nextl_col, m); // Scatter/gather entire matrix column from/to here\n        \n        kfnz = repfnz_col(krep); \n        if ( kfnz == emptyIdxLU ) \n          continue; // skip any zero segment\n        \n        segsize = krep - kfnz + 1;\n        luptr = glu.xlusup(fsupc);\n        \n        Index lda = glu.xlusup(fsupc+1)-glu.xlusup(fsupc);// nsupr\n        \n        // Perform a trianglar solve and block update, \n        // then scatter the result of sup-col update to dense[]\n        no_zeros = kfnz - fsupc; \n              if(segsize==1)  LU_kernel_bmod<1>::run(segsize, dense_col, tempv, glu.lusup, luptr, lda, nrow, glu.lsub, lptr, no_zeros);\n        else  if(segsize==2)  LU_kernel_bmod<2>::run(segsize, dense_col, tempv, glu.lusup, luptr, lda, nrow, glu.lsub, lptr, no_zeros);\n        else  if(segsize==3)  LU_kernel_bmod<3>::run(segsize, dense_col, tempv, glu.lusup, luptr, lda, nrow, glu.lsub, lptr, no_zeros);\n        else                  LU_kernel_bmod<Dynamic>::run(segsize, dense_col, tempv, glu.lusup, luptr, lda, nrow, glu.lsub, lptr, no_zeros); \n      } // End for each column in the panel \n    }\n    \n  } // End for each updating supernode\n} // end panel bmod\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // SPARSELU_PANEL_BMOD_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseLU/SparseLU_panel_dfs.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/* \n \n * NOTE: This file is the modified version of [s,d,c,z]panel_dfs.c file in SuperLU \n \n * -- SuperLU routine (version 2.0) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * November 15, 1997\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n#ifndef SPARSELU_PANEL_DFS_H\n#define SPARSELU_PANEL_DFS_H\n\nnamespace Eigen {\n\nnamespace internal {\n  \ntemplate<typename IndexVector>\nstruct panel_dfs_traits\n{\n  typedef typename IndexVector::Scalar StorageIndex;\n  panel_dfs_traits(Index jcol, StorageIndex* marker)\n    : m_jcol(jcol), m_marker(marker)\n  {}\n  bool update_segrep(Index krep, StorageIndex jj)\n  {\n    if(m_marker[krep]<m_jcol)\n    {\n      m_marker[krep] = jj; \n      return true;\n    }\n    return false;\n  }\n  void mem_expand(IndexVector& /*glu.lsub*/, Index /*nextl*/, Index /*chmark*/) {}\n  enum { ExpandMem = false };\n  Index m_jcol;\n  StorageIndex* m_marker;\n};\n\n\ntemplate <typename Scalar, typename StorageIndex>\ntemplate <typename Traits>\nvoid SparseLUImpl<Scalar,StorageIndex>::dfs_kernel(const StorageIndex jj, IndexVector& perm_r,\n                   Index& nseg, IndexVector& panel_lsub, IndexVector& segrep,\n                   Ref<IndexVector> repfnz_col, IndexVector& xprune, Ref<IndexVector> marker, IndexVector& parent,\n                   IndexVector& xplore, GlobalLU_t& glu,\n                   Index& nextl_col, Index krow, Traits& traits\n                  )\n{\n  \n  StorageIndex kmark = marker(krow);\n      \n  // For each unmarked krow of jj\n  marker(krow) = jj; \n  StorageIndex kperm = perm_r(krow); \n  if (kperm == emptyIdxLU ) {\n    // krow is in L : place it in structure of L(*, jj)\n    panel_lsub(nextl_col++) = StorageIndex(krow);  // krow is indexed into A\n    \n    traits.mem_expand(panel_lsub, nextl_col, kmark);\n  }\n  else \n  {\n    // krow is in U : if its supernode-representative krep\n    // has been explored, update repfnz(*)\n    // krep = supernode representative of the current row\n    StorageIndex krep = glu.xsup(glu.supno(kperm)+1) - 1; \n    // First nonzero element in the current column:\n    StorageIndex myfnz = repfnz_col(krep); \n    \n    if (myfnz != emptyIdxLU )\n    {\n      // Representative visited before\n      if (myfnz > kperm ) repfnz_col(krep) = kperm; \n      \n    }\n    else \n    {\n      // Otherwise, perform dfs starting at krep\n      StorageIndex oldrep = emptyIdxLU; \n      parent(krep) = oldrep; \n      repfnz_col(krep) = kperm; \n      StorageIndex xdfs =  glu.xlsub(krep); \n      Index maxdfs = xprune(krep); \n      \n      StorageIndex kpar;\n      do \n      {\n        // For each unmarked kchild of krep\n        while (xdfs < maxdfs) \n        {\n          StorageIndex kchild = glu.lsub(xdfs); \n          xdfs++; \n          StorageIndex chmark = marker(kchild); \n          \n          if (chmark != jj ) \n          {\n            marker(kchild) = jj; \n            StorageIndex chperm = perm_r(kchild); \n            \n            if (chperm == emptyIdxLU) \n            {\n              // case kchild is in L: place it in L(*, j)\n              panel_lsub(nextl_col++) = kchild;\n              traits.mem_expand(panel_lsub, nextl_col, chmark);\n            }\n            else\n            {\n              // case kchild is in U :\n              // chrep = its supernode-rep. If its rep has been explored, \n              // update its repfnz(*)\n              StorageIndex chrep = glu.xsup(glu.supno(chperm)+1) - 1; \n              myfnz = repfnz_col(chrep); \n              \n              if (myfnz != emptyIdxLU) \n              { // Visited before \n                if (myfnz > chperm) \n                  repfnz_col(chrep) = chperm; \n              }\n              else \n              { // Cont. dfs at snode-rep of kchild\n                xplore(krep) = xdfs; \n                oldrep = krep; \n                krep = chrep; // Go deeper down G(L)\n                parent(krep) = oldrep; \n                repfnz_col(krep) = chperm; \n                xdfs = glu.xlsub(krep); \n                maxdfs = xprune(krep); \n                \n              } // end if myfnz != -1\n            } // end if chperm == -1 \n                \n          } // end if chmark !=jj\n        } // end while xdfs < maxdfs\n        \n        // krow has no more unexplored nbrs :\n        //    Place snode-rep krep in postorder DFS, if this \n        //    segment is seen for the first time. (Note that \n        //    \"repfnz(krep)\" may change later.)\n        //    Baktrack dfs to its parent\n        if(traits.update_segrep(krep,jj))\n        //if (marker1(krep) < jcol )\n        {\n          segrep(nseg) = krep; \n          ++nseg; \n          //marker1(krep) = jj; \n        }\n        \n        kpar = parent(krep); // Pop recursion, mimic recursion \n        if (kpar == emptyIdxLU) \n          break; // dfs done \n        krep = kpar; \n        xdfs = xplore(krep); \n        maxdfs = xprune(krep); \n\n      } while (kpar != emptyIdxLU); // Do until empty stack \n      \n    } // end if (myfnz = -1)\n\n  } // end if (kperm == -1)   \n}\n\n/**\n * \\brief Performs a symbolic factorization on a panel of columns [jcol, jcol+w)\n * \n * A supernode representative is the last column of a supernode.\n * The nonzeros in U[*,j] are segments that end at supernodes representatives\n * \n * The routine returns a list of the supernodal representatives \n * in topological order of the dfs that generates them. This list is \n * a superset of the topological order of each individual column within \n * the panel.\n * The location of the first nonzero in each supernodal segment \n * (supernodal entry location) is also returned. Each column has \n * a separate list for this purpose. \n * \n * Two markers arrays are used for dfs :\n *    marker[i] == jj, if i was visited during dfs of current column jj;\n *    marker1[i] >= jcol, if i was visited by earlier columns in this panel; \n * \n * \\param[in] m number of rows in the matrix\n * \\param[in] w Panel size\n * \\param[in] jcol Starting  column of the panel\n * \\param[in] A Input matrix in column-major storage\n * \\param[in] perm_r Row permutation\n * \\param[out] nseg Number of U segments\n * \\param[out] dense Accumulate the column vectors of the panel\n * \\param[out] panel_lsub Subscripts of the row in the panel \n * \\param[out] segrep Segment representative i.e first nonzero row of each segment\n * \\param[out] repfnz First nonzero location in each row\n * \\param[out] xprune The pruned elimination tree\n * \\param[out] marker work vector\n * \\param  parent The elimination tree\n * \\param xplore work vector\n * \\param glu The global data structure\n * \n */\n\ntemplate <typename Scalar, typename StorageIndex>\nvoid SparseLUImpl<Scalar,StorageIndex>::panel_dfs(const Index m, const Index w, const Index jcol, MatrixType& A, IndexVector& perm_r, Index& nseg, ScalarVector& dense, IndexVector& panel_lsub, IndexVector& segrep, IndexVector& repfnz, IndexVector& xprune, IndexVector& marker, IndexVector& parent, IndexVector& xplore, GlobalLU_t& glu)\n{\n  Index nextl_col; // Next available position in panel_lsub[*,jj] \n  \n  // Initialize pointers \n  VectorBlock<IndexVector> marker1(marker, m, m); \n  nseg = 0; \n  \n  panel_dfs_traits<IndexVector> traits(jcol, marker1.data());\n  \n  // For each column in the panel \n  for (StorageIndex jj = StorageIndex(jcol); jj < jcol + w; jj++) \n  {\n    nextl_col = (jj - jcol) * m; \n    \n    VectorBlock<IndexVector> repfnz_col(repfnz, nextl_col, m); // First nonzero location in each row\n    VectorBlock<ScalarVector> dense_col(dense,nextl_col, m); // Accumulate a column vector here\n    \n    \n    // For each nnz in A[*, jj] do depth first search\n    for (typename MatrixType::InnerIterator it(A, jj); it; ++it)\n    {\n      Index krow = it.row(); \n      dense_col(krow) = it.value();\n      \n      StorageIndex kmark = marker(krow); \n      if (kmark == jj) \n        continue; // krow visited before, go to the next nonzero\n      \n      dfs_kernel(jj, perm_r, nseg, panel_lsub, segrep, repfnz_col, xprune, marker, parent,\n                   xplore, glu, nextl_col, krow, traits);\n    }// end for nonzeros in column jj\n    \n  } // end for column jj\n}\n\n} // end namespace internal\n} // end namespace Eigen\n\n#endif // SPARSELU_PANEL_DFS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseLU/SparseLU_pivotL.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/* \n \n * NOTE: This file is the modified version of xpivotL.c file in SuperLU \n \n * -- SuperLU routine (version 3.0) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * October 15, 2003\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n#ifndef SPARSELU_PIVOTL_H\n#define SPARSELU_PIVOTL_H\n\nnamespace Eigen {\nnamespace internal {\n  \n/**\n * \\brief Performs the numerical pivotin on the current column of L, and the CDIV operation.\n * \n * Pivot policy :\n * (1) Compute thresh = u * max_(i>=j) abs(A_ij);\n * (2) IF user specifies pivot row k and abs(A_kj) >= thresh THEN\n *           pivot row = k;\n *       ELSE IF abs(A_jj) >= thresh THEN\n *           pivot row = j;\n *       ELSE\n *           pivot row = m;\n * \n *   Note: If you absolutely want to use a given pivot order, then set u=0.0.\n * \n * \\param jcol The current column of L\n * \\param diagpivotthresh diagonal pivoting threshold\n * \\param[in,out] perm_r Row permutation (threshold pivoting)\n * \\param[in] iperm_c column permutation - used to finf diagonal of Pc*A*Pc'\n * \\param[out] pivrow  The pivot row\n * \\param glu Global LU data\n * \\return 0 if success, i > 0 if U(i,i) is exactly zero \n * \n */\ntemplate <typename Scalar, typename StorageIndex>\nIndex SparseLUImpl<Scalar,StorageIndex>::pivotL(const Index jcol, const RealScalar& diagpivotthresh, IndexVector& perm_r, IndexVector& iperm_c, Index& pivrow, GlobalLU_t& glu)\n{\n  \n  Index fsupc = (glu.xsup)((glu.supno)(jcol)); // First column in the supernode containing the column jcol\n  Index nsupc = jcol - fsupc; // Number of columns in the supernode portion, excluding jcol; nsupc >=0\n  Index lptr = glu.xlsub(fsupc); // pointer to the starting location of the row subscripts for this supernode portion\n  Index nsupr = glu.xlsub(fsupc+1) - lptr; // Number of rows in the supernode\n  Index lda = glu.xlusup(fsupc+1) - glu.xlusup(fsupc); // leading dimension\n  Scalar* lu_sup_ptr = &(glu.lusup.data()[glu.xlusup(fsupc)]); // Start of the current supernode\n  Scalar* lu_col_ptr = &(glu.lusup.data()[glu.xlusup(jcol)]); // Start of jcol in the supernode\n  StorageIndex* lsub_ptr = &(glu.lsub.data()[lptr]); // Start of row indices of the supernode\n  \n  // Determine the largest abs numerical value for partial pivoting \n  Index diagind = iperm_c(jcol); // diagonal index \n  RealScalar pivmax(-1.0);\n  Index pivptr = nsupc; \n  Index diag = emptyIdxLU; \n  RealScalar rtemp;\n  Index isub, icol, itemp, k; \n  for (isub = nsupc; isub < nsupr; ++isub) {\n    using std::abs;\n    rtemp = abs(lu_col_ptr[isub]);\n    if (rtemp > pivmax) {\n      pivmax = rtemp; \n      pivptr = isub;\n    } \n    if (lsub_ptr[isub] == diagind) diag = isub;\n  }\n  \n  // Test for singularity\n  if ( pivmax <= RealScalar(0.0) ) {\n    // if pivmax == -1, the column is structurally empty, otherwise it is only numerically zero\n    pivrow = pivmax < RealScalar(0.0) ? diagind : lsub_ptr[pivptr];\n    perm_r(pivrow) = StorageIndex(jcol);\n    return (jcol+1);\n  }\n  \n  RealScalar thresh = diagpivotthresh * pivmax; \n  \n  // Choose appropriate pivotal element \n  \n  {\n    // Test if the diagonal element can be used as a pivot (given the threshold value)\n    if (diag >= 0 ) \n    {\n      // Diagonal element exists\n      using std::abs;\n      rtemp = abs(lu_col_ptr[diag]);\n      if (rtemp != RealScalar(0.0) && rtemp >= thresh) pivptr = diag;\n    }\n    pivrow = lsub_ptr[pivptr];\n  }\n  \n  // Record pivot row\n  perm_r(pivrow) = StorageIndex(jcol);\n  // Interchange row subscripts\n  if (pivptr != nsupc )\n  {\n    std::swap( lsub_ptr[pivptr], lsub_ptr[nsupc] );\n    // Interchange numerical values as well, for the two rows in the whole snode\n    // such that L is indexed the same way as A\n    for (icol = 0; icol <= nsupc; icol++)\n    {\n      itemp = pivptr + icol * lda; \n      std::swap(lu_sup_ptr[itemp], lu_sup_ptr[nsupc + icol * lda]);\n    }\n  }\n  // cdiv operations\n  Scalar temp = Scalar(1.0) / lu_col_ptr[nsupc];\n  for (k = nsupc+1; k < nsupr; k++)\n    lu_col_ptr[k] *= temp; \n  return 0;\n}\n\n} // end namespace internal\n} // end namespace Eigen\n\n#endif // SPARSELU_PIVOTL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseLU/SparseLU_pruneL.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/* \n \n * NOTE: This file is the modified version of [s,d,c,z]pruneL.c file in SuperLU \n \n * -- SuperLU routine (version 2.0) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * November 15, 1997\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n#ifndef SPARSELU_PRUNEL_H\n#define SPARSELU_PRUNEL_H\n\nnamespace Eigen {\nnamespace internal {\n\n/**\n * \\brief Prunes the L-structure.\n *\n * It prunes the L-structure  of supernodes whose L-structure contains the current pivot row \"pivrow\"\n * \n * \n * \\param jcol The current column of L\n * \\param[in] perm_r Row permutation\n * \\param[out] pivrow  The pivot row\n * \\param nseg Number of segments\n * \\param segrep \n * \\param repfnz\n * \\param[out] xprune \n * \\param glu Global LU data\n * \n */\ntemplate <typename Scalar, typename StorageIndex>\nvoid SparseLUImpl<Scalar,StorageIndex>::pruneL(const Index jcol, const IndexVector& perm_r, const Index pivrow, const Index nseg,\n                                               const IndexVector& segrep, BlockIndexVector repfnz, IndexVector& xprune, GlobalLU_t& glu)\n{\n  // For each supernode-rep irep in U(*,j]\n  Index jsupno = glu.supno(jcol); \n  Index i,irep,irep1; \n  bool movnum, do_prune = false; \n  Index kmin = 0, kmax = 0, minloc, maxloc,krow; \n  for (i = 0; i < nseg; i++)\n  {\n    irep = segrep(i); \n    irep1 = irep + 1; \n    do_prune = false; \n    \n    // Don't prune with a zero U-segment \n    if (repfnz(irep) == emptyIdxLU) continue; \n    \n    // If a snode overlaps with the next panel, then the U-segment\n    // is fragmented into two parts -- irep and irep1. We should let \n    // pruning occur at the rep-column in irep1s snode. \n    if (glu.supno(irep) == glu.supno(irep1) ) continue; // don't prune \n    \n    // If it has not been pruned & it has a nonz in row L(pivrow,i)\n    if (glu.supno(irep) != jsupno )\n    {\n      if ( xprune (irep) >= glu.xlsub(irep1) )\n      {\n        kmin = glu.xlsub(irep);\n        kmax = glu.xlsub(irep1) - 1; \n        for (krow = kmin; krow <= kmax; krow++)\n        {\n          if (glu.lsub(krow) == pivrow) \n          {\n            do_prune = true; \n            break; \n          }\n        }\n      }\n      \n      if (do_prune) \n      {\n        // do a quicksort-type partition\n        // movnum=true means that the num values have to be exchanged\n        movnum = false; \n        if (irep == glu.xsup(glu.supno(irep)) ) // Snode of size 1 \n          movnum = true; \n        \n        while (kmin <= kmax)\n        {\n          if (perm_r(glu.lsub(kmax)) == emptyIdxLU)\n            kmax--; \n          else if ( perm_r(glu.lsub(kmin)) != emptyIdxLU)\n            kmin++;\n          else \n          {\n            // kmin below pivrow (not yet pivoted), and kmax\n            // above pivrow: interchange the two suscripts\n            std::swap(glu.lsub(kmin), glu.lsub(kmax)); \n            \n            // If the supernode has only one column, then we \n            // only keep one set of subscripts. For any subscript\n            // intercnahge performed, similar interchange must be \n            // done on the numerical values. \n            if (movnum) \n            {\n              minloc = glu.xlusup(irep) + ( kmin - glu.xlsub(irep) ); \n              maxloc = glu.xlusup(irep) + ( kmax - glu.xlsub(irep) ); \n              std::swap(glu.lusup(minloc), glu.lusup(maxloc)); \n            }\n            kmin++;\n            kmax--;\n          }\n        } // end while \n        \n        xprune(irep) = StorageIndex(kmin);  //Pruning \n      } // end if do_prune \n    } // end pruning \n  } // End for each U-segment\n}\n\n} // end namespace internal\n} // end namespace Eigen\n\n#endif // SPARSELU_PRUNEL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseLU/SparseLU_relax_snode.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/* This file is a modified version of heap_relax_snode.c file in SuperLU\n * -- SuperLU routine (version 3.0) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * October 15, 2003\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n\n#ifndef SPARSELU_RELAX_SNODE_H\n#define SPARSELU_RELAX_SNODE_H\n\nnamespace Eigen {\n\nnamespace internal {\n \n/** \n * \\brief Identify the initial relaxed supernodes\n * \n * This routine is applied to a column elimination tree. \n * It assumes that the matrix has been reordered according to the postorder of the etree\n * \\param n  the number of columns\n * \\param et elimination tree \n * \\param relax_columns Maximum number of columns allowed in a relaxed snode \n * \\param descendants Number of descendants of each node in the etree\n * \\param relax_end last column in a supernode\n */\ntemplate <typename Scalar, typename StorageIndex>\nvoid SparseLUImpl<Scalar,StorageIndex>::relax_snode (const Index n, IndexVector& et, const Index relax_columns, IndexVector& descendants, IndexVector& relax_end)\n{\n  \n  // compute the number of descendants of each node in the etree\n  Index parent; \n  relax_end.setConstant(emptyIdxLU);\n  descendants.setZero();\n  for (Index j = 0; j < n; j++) \n  {\n    parent = et(j);\n    if (parent != n) // not the dummy root\n      descendants(parent) += descendants(j) + 1;\n  }\n  // Identify the relaxed supernodes by postorder traversal of the etree\n  Index snode_start; // beginning of a snode \n  for (Index j = 0; j < n; )\n  {\n    parent = et(j);\n    snode_start = j; \n    while ( parent != n && descendants(parent) < relax_columns ) \n    {\n      j = parent; \n      parent = et(j);\n    }\n    // Found a supernode in postordered etree, j is the last column \n    relax_end(snode_start) = StorageIndex(j); // Record last column\n    j++;\n    // Search for a new leaf\n    while (descendants(j) != 0 && j < n) j++;\n  } // End postorder traversal of the etree\n  \n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SparseQR/SparseQR.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012-2013 Desire Nuentsa <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2012-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_QR_H\n#define EIGEN_SPARSE_QR_H\n\nnamespace Eigen {\n\ntemplate<typename MatrixType, typename OrderingType> class SparseQR;\ntemplate<typename SparseQRType> struct SparseQRMatrixQReturnType;\ntemplate<typename SparseQRType> struct SparseQRMatrixQTransposeReturnType;\ntemplate<typename SparseQRType, typename Derived> struct SparseQR_QProduct;\nnamespace internal {\n  template <typename SparseQRType> struct traits<SparseQRMatrixQReturnType<SparseQRType> >\n  {\n    typedef typename SparseQRType::MatrixType ReturnType;\n    typedef typename ReturnType::StorageIndex StorageIndex;\n    typedef typename ReturnType::StorageKind StorageKind;\n    enum {\n      RowsAtCompileTime = Dynamic,\n      ColsAtCompileTime = Dynamic\n    };\n  };\n  template <typename SparseQRType> struct traits<SparseQRMatrixQTransposeReturnType<SparseQRType> >\n  {\n    typedef typename SparseQRType::MatrixType ReturnType;\n  };\n  template <typename SparseQRType, typename Derived> struct traits<SparseQR_QProduct<SparseQRType, Derived> >\n  {\n    typedef typename Derived::PlainObject ReturnType;\n  };\n} // End namespace internal\n\n/**\n  * \\ingroup SparseQR_Module\n  * \\class SparseQR\n  * \\brief Sparse left-looking QR factorization with numerical column pivoting\n  * \n  * This class implements a left-looking QR decomposition of sparse matrices\n  * with numerical column pivoting.\n  * When a column has a norm less than a given tolerance\n  * it is implicitly permuted to the end. The QR factorization thus obtained is \n  * given by A*P = Q*R where R is upper triangular or trapezoidal. \n  * \n  * P is the column permutation which is the product of the fill-reducing and the\n  * numerical permutations. Use colsPermutation() to get it.\n  * \n  * Q is the orthogonal matrix represented as products of Householder reflectors. \n  * Use matrixQ() to get an expression and matrixQ().adjoint() to get the adjoint.\n  * You can then apply it to a vector.\n  * \n  * R is the sparse triangular or trapezoidal matrix. The later occurs when A is rank-deficient.\n  * matrixR().topLeftCorner(rank(), rank()) always returns a triangular factor of full rank.\n  * \n  * \\tparam MatrixType_ The type of the sparse matrix A, must be a column-major SparseMatrix<>\n  * \\tparam OrderingType_ The fill-reducing ordering method. See the \\link OrderingMethods_Module\n  *  OrderingMethods \\endlink module for the list of built-in and external ordering methods.\n  * \n  * \\implsparsesolverconcept\n  *\n  * The numerical pivoting strategy and default threshold are the same as in SuiteSparse QR, and\n  * detailed in the following paper:\n  * <i>\n  * Tim Davis, \"Algorithm 915, SuiteSparseQR: Multifrontal Multithreaded Rank-Revealing\n  * Sparse QR Factorization, ACM Trans. on Math. Soft. 38(1), 2011.\n  * </i>\n  * Even though it is qualified as \"rank-revealing\", this strategy might fail for some \n  * rank deficient problems. When this class is used to solve linear or least-square problems\n  * it is thus strongly recommended to check the accuracy of the computed solution. If it\n  * failed, it usually helps to increase the threshold with setPivotThreshold.\n  * \n  * \\warning The input sparse matrix A must be in compressed mode (see SparseMatrix::makeCompressed()).\n  * \\warning For complex matrices matrixQ().transpose() will actually return the adjoint matrix.\n  * \n  */\ntemplate<typename MatrixType_, typename OrderingType_>\nclass SparseQR : public SparseSolverBase<SparseQR<MatrixType_,OrderingType_> >\n{\n  protected:\n    typedef SparseSolverBase<SparseQR<MatrixType_,OrderingType_> > Base;\n    using Base::m_isInitialized;\n  public:\n    using Base::_solve_impl;\n    typedef MatrixType_ MatrixType;\n    typedef OrderingType_ OrderingType;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> QRMatrixType;\n    typedef Matrix<StorageIndex, Dynamic, 1> IndexVector;\n    typedef Matrix<Scalar, Dynamic, 1> ScalarVector;\n    typedef PermutationMatrix<Dynamic, Dynamic, StorageIndex> PermutationType;\n\n    enum {\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n    \n  public:\n    SparseQR () :  m_analysisIsok(false), m_lastError(\"\"), m_useDefaultThreshold(true),m_isQSorted(false),m_isEtreeOk(false)\n    { }\n    \n    /** Construct a QR factorization of the matrix \\a mat.\n      * \n      * \\warning The matrix \\a mat must be in compressed mode (see SparseMatrix::makeCompressed()).\n      * \n      * \\sa compute()\n      */\n    explicit SparseQR(const MatrixType& mat) : m_analysisIsok(false), m_lastError(\"\"), m_useDefaultThreshold(true),m_isQSorted(false),m_isEtreeOk(false)\n    {\n      compute(mat);\n    }\n    \n    /** Computes the QR factorization of the sparse matrix \\a mat.\n      * \n      * \\warning The matrix \\a mat must be in compressed mode (see SparseMatrix::makeCompressed()).\n      * \n      * \\sa analyzePattern(), factorize()\n      */\n    void compute(const MatrixType& mat)\n    {\n      analyzePattern(mat);\n      factorize(mat);\n    }\n    void analyzePattern(const MatrixType& mat);\n    void factorize(const MatrixType& mat);\n    \n    /** \\returns the number of rows of the represented matrix. \n      */\n    inline Index rows() const { return m_pmat.rows(); }\n    \n    /** \\returns the number of columns of the represented matrix. \n      */\n    inline Index cols() const { return m_pmat.cols();}\n    \n    /** \\returns a const reference to the \\b sparse upper triangular matrix R of the QR factorization.\n      * \\warning The entries of the returned matrix are not sorted. This means that using it in algorithms\n      *          expecting sorted entries will fail. This include random coefficient accesses (SpaseMatrix::coeff()),\n      *          and coefficient-wise operations. Matrix products and triangular solves are fine though.\n      *\n      * To sort the entries, you can assign it to a row-major matrix, and if a column-major matrix\n      * is required, you can copy it again:\n      * \\code\n      * SparseMatrix<double>          R  = qr.matrixR();  // column-major, not sorted!\n      * SparseMatrix<double,RowMajor> Rr = qr.matrixR();  // row-major, sorted\n      * SparseMatrix<double>          Rc = Rr;            // column-major, sorted\n      * \\endcode\n      */\n    const QRMatrixType& matrixR() const { return m_R; }\n    \n    /** \\returns the number of non linearly dependent columns as determined by the pivoting threshold.\n      *\n      * \\sa setPivotThreshold()\n      */\n    Index rank() const\n    {\n      eigen_assert(m_isInitialized && \"The factorization should be called first, use compute()\");\n      return m_nonzeropivots; \n    }\n    \n    /** \\returns an expression of the matrix Q as products of sparse Householder reflectors.\n    * The common usage of this function is to apply it to a dense matrix or vector\n    * \\code\n    * VectorXd B1, B2;\n    * // Initialize B1\n    * B2 = matrixQ() * B1;\n    * \\endcode\n    *\n    * To get a plain SparseMatrix representation of Q:\n    * \\code\n    * SparseMatrix<double> Q;\n    * Q = SparseQR<SparseMatrix<double> >(A).matrixQ();\n    * \\endcode\n    * Internally, this call simply performs a sparse product between the matrix Q\n    * and a sparse identity matrix. However, due to the fact that the sparse\n    * reflectors are stored unsorted, two transpositions are needed to sort\n    * them before performing the product.\n    */\n    SparseQRMatrixQReturnType<SparseQR> matrixQ() const \n    { return SparseQRMatrixQReturnType<SparseQR>(*this); }\n    \n    /** \\returns a const reference to the column permutation P that was applied to A such that A*P = Q*R\n      * It is the combination of the fill-in reducing permutation and numerical column pivoting.\n      */\n    const PermutationType& colsPermutation() const\n    { \n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_outputPerm_c;\n    }\n    \n    /** \\returns A string describing the type of error.\n      * This method is provided to ease debugging, not to handle errors.\n      */\n    std::string lastErrorMessage() const { return m_lastError; }\n    \n    /** \\internal */\n    template<typename Rhs, typename Dest>\n    bool _solve_impl(const MatrixBase<Rhs> &B, MatrixBase<Dest> &dest) const\n    {\n      eigen_assert(m_isInitialized && \"The factorization should be called first, use compute()\");\n      eigen_assert(this->rows() == B.rows() && \"SparseQR::solve() : invalid number of rows in the right hand side matrix\");\n\n      Index rank = this->rank();\n      \n      // Compute Q^* * b;\n      typename Dest::PlainObject y, b;\n      y = this->matrixQ().adjoint() * B;\n      b = y;\n      \n      // Solve with the triangular matrix R\n      y.resize((std::max<Index>)(cols(),y.rows()),y.cols());\n      y.topRows(rank) = this->matrixR().topLeftCorner(rank, rank).template triangularView<Upper>().solve(b.topRows(rank));\n      y.bottomRows(y.rows()-rank).setZero();\n      \n      // Apply the column permutation\n      if (m_perm_c.size())  dest = colsPermutation() * y.topRows(cols());\n      else                  dest = y.topRows(cols());\n      \n      m_info = Success;\n      return true;\n    }\n\n    /** Sets the threshold that is used to determine linearly dependent columns during the factorization.\n      *\n      * In practice, if during the factorization the norm of the column that has to be eliminated is below\n      * this threshold, then the entire column is treated as zero, and it is moved at the end.\n      */\n    void setPivotThreshold(const RealScalar& threshold)\n    {\n      m_useDefaultThreshold = false;\n      m_threshold = threshold;\n    }\n    \n    /** \\returns the solution X of \\f$ A X = B \\f$ using the current decomposition of A.\n      *\n      * \\sa compute()\n      */\n    template<typename Rhs>\n    inline const Solve<SparseQR, Rhs> solve(const MatrixBase<Rhs>& B) const \n    {\n      eigen_assert(m_isInitialized && \"The factorization should be called first, use compute()\");\n      eigen_assert(this->rows() == B.rows() && \"SparseQR::solve() : invalid number of rows in the right hand side matrix\");\n      return Solve<SparseQR, Rhs>(*this, B.derived());\n    }\n    template<typename Rhs>\n    inline const Solve<SparseQR, Rhs> solve(const SparseMatrixBase<Rhs>& B) const\n    {\n          eigen_assert(m_isInitialized && \"The factorization should be called first, use compute()\");\n          eigen_assert(this->rows() == B.rows() && \"SparseQR::solve() : invalid number of rows in the right hand side matrix\");\n          return Solve<SparseQR, Rhs>(*this, B.derived());\n    }\n    \n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the QR factorization reports a numerical problem\n      *          \\c InvalidInput if the input matrix is invalid\n      *\n      * \\sa iparm()          \n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_info;\n    }\n\n\n    /** \\internal */\n    inline void _sort_matrix_Q()\n    {\n      if(this->m_isQSorted) return;\n      // The matrix Q is sorted during the transposition\n      SparseMatrix<Scalar, RowMajor, Index> mQrm(this->m_Q);\n      this->m_Q = mQrm;\n      this->m_isQSorted = true;\n    }\n\n    \n  protected:\n    bool m_analysisIsok;\n    bool m_factorizationIsok;\n    mutable ComputationInfo m_info;\n    std::string m_lastError;\n    QRMatrixType m_pmat;            // Temporary matrix\n    QRMatrixType m_R;               // The triangular factor matrix\n    QRMatrixType m_Q;               // The orthogonal reflectors\n    ScalarVector m_hcoeffs;         // The Householder coefficients\n    PermutationType m_perm_c;       // Fill-reducing  Column  permutation\n    PermutationType m_pivotperm;    // The permutation for rank revealing\n    PermutationType m_outputPerm_c; // The final column permutation\n    RealScalar m_threshold;         // Threshold to determine null Householder reflections\n    bool m_useDefaultThreshold;     // Use default threshold\n    Index m_nonzeropivots;          // Number of non zero pivots found\n    IndexVector m_etree;            // Column elimination tree\n    IndexVector m_firstRowElt;      // First element in each row\n    bool m_isQSorted;               // whether Q is sorted or not\n    bool m_isEtreeOk;               // whether the elimination tree match the initial input matrix\n    \n    template <typename, typename > friend struct SparseQR_QProduct;\n    \n};\n\n/** \\brief Preprocessing step of a QR factorization \n  * \n  * \\warning The matrix \\a mat must be in compressed mode (see SparseMatrix::makeCompressed()).\n  * \n  * In this step, the fill-reducing permutation is computed and applied to the columns of A\n  * and the column elimination tree is computed as well. Only the sparsity pattern of \\a mat is exploited.\n  * \n  * \\note In this step it is assumed that there is no empty row in the matrix \\a mat.\n  */\ntemplate <typename MatrixType, typename OrderingType>\nvoid SparseQR<MatrixType,OrderingType>::analyzePattern(const MatrixType& mat)\n{\n  eigen_assert(mat.isCompressed() && \"SparseQR requires a sparse matrix in compressed mode. Call .makeCompressed() before passing it to SparseQR\");\n  // Copy to a column major matrix if the input is rowmajor\n  typename internal::conditional<MatrixType::IsRowMajor,QRMatrixType,const MatrixType&>::type matCpy(mat);\n  // Compute the column fill reducing ordering\n  OrderingType ord; \n  ord(matCpy, m_perm_c); \n  Index n = mat.cols();\n  Index m = mat.rows();\n  Index diagSize = (std::min)(m,n);\n  \n  if (!m_perm_c.size())\n  {\n    m_perm_c.resize(n);\n    m_perm_c.indices().setLinSpaced(n, 0,StorageIndex(n-1));\n  }\n  \n  // Compute the column elimination tree of the permuted matrix\n  m_outputPerm_c = m_perm_c.inverse();\n  internal::coletree(matCpy, m_etree, m_firstRowElt, m_outputPerm_c.indices().data());\n  m_isEtreeOk = true;\n  \n  m_R.resize(m, n);\n  m_Q.resize(m, diagSize);\n  \n  // Allocate space for nonzero elements: rough estimation\n  m_R.reserve(2*mat.nonZeros()); //FIXME Get a more accurate estimation through symbolic factorization with the etree\n  m_Q.reserve(2*mat.nonZeros());\n  m_hcoeffs.resize(diagSize);\n  m_analysisIsok = true;\n}\n\n/** \\brief Performs the numerical QR factorization of the input matrix\n  * \n  * The function SparseQR::analyzePattern(const MatrixType&) must have been called beforehand with\n  * a matrix having the same sparsity pattern than \\a mat.\n  * \n  * \\param mat The sparse column-major matrix\n  */\ntemplate <typename MatrixType, typename OrderingType>\nvoid SparseQR<MatrixType,OrderingType>::factorize(const MatrixType& mat)\n{\n  using std::abs;\n  \n  eigen_assert(m_analysisIsok && \"analyzePattern() should be called before this step\");\n  StorageIndex m = StorageIndex(mat.rows());\n  StorageIndex n = StorageIndex(mat.cols());\n  StorageIndex diagSize = (std::min)(m,n);\n  IndexVector mark((std::max)(m,n)); mark.setConstant(-1);  // Record the visited nodes\n  IndexVector Ridx(n), Qidx(m);                             // Store temporarily the row indexes for the current column of R and Q\n  Index nzcolR, nzcolQ;                                     // Number of nonzero for the current column of R and Q\n  ScalarVector tval(m);                                     // The dense vector used to compute the current column\n  RealScalar pivotThreshold = m_threshold;\n  \n  m_R.setZero();\n  m_Q.setZero();\n  m_pmat = mat;\n  if(!m_isEtreeOk)\n  {\n    m_outputPerm_c = m_perm_c.inverse();\n    internal::coletree(m_pmat, m_etree, m_firstRowElt, m_outputPerm_c.indices().data());\n    m_isEtreeOk = true;\n  }\n\n  m_pmat.uncompress(); // To have the innerNonZeroPtr allocated\n  \n  // Apply the fill-in reducing permutation lazily:\n  {\n    // If the input is row major, copy the original column indices,\n    // otherwise directly use the input matrix\n    // \n    IndexVector originalOuterIndicesCpy;\n    const StorageIndex *originalOuterIndices = mat.outerIndexPtr();\n    if(MatrixType::IsRowMajor)\n    {\n      originalOuterIndicesCpy = IndexVector::Map(m_pmat.outerIndexPtr(),n+1);\n      originalOuterIndices = originalOuterIndicesCpy.data();\n    }\n    \n    for (int i = 0; i < n; i++)\n    {\n      Index p = m_perm_c.size() ? m_perm_c.indices()(i) : i;\n      m_pmat.outerIndexPtr()[p] = originalOuterIndices[i]; \n      m_pmat.innerNonZeroPtr()[p] = originalOuterIndices[i+1] - originalOuterIndices[i]; \n    }\n  }\n  \n  /* Compute the default threshold as in MatLab, see:\n   * Tim Davis, \"Algorithm 915, SuiteSparseQR: Multifrontal Multithreaded Rank-Revealing\n   * Sparse QR Factorization, ACM Trans. on Math. Soft. 38(1), 2011, Page 8:3 \n   */\n  if(m_useDefaultThreshold) \n  {\n    RealScalar max2Norm = 0.0;\n    for (int j = 0; j < n; j++) max2Norm = numext::maxi(max2Norm, m_pmat.col(j).norm());\n    if(max2Norm==RealScalar(0))\n      max2Norm = RealScalar(1);\n    pivotThreshold = 20 * (m + n) * max2Norm * NumTraits<RealScalar>::epsilon();\n  }\n  \n  // Initialize the numerical permutation\n  m_pivotperm.setIdentity(n);\n  \n  StorageIndex nonzeroCol = 0; // Record the number of valid pivots\n  m_Q.startVec(0);\n\n  // Left looking rank-revealing QR factorization: compute a column of R and Q at a time\n  for (StorageIndex col = 0; col < n; ++col)\n  {\n    mark.setConstant(-1);\n    m_R.startVec(col);\n    mark(nonzeroCol) = col;\n    Qidx(0) = nonzeroCol;\n    nzcolR = 0; nzcolQ = 1;\n    bool found_diag = nonzeroCol>=m;\n    tval.setZero(); \n    \n    // Symbolic factorization: find the nonzero locations of the column k of the factors R and Q, i.e.,\n    // all the nodes (with indexes lower than rank) reachable through the column elimination tree (etree) rooted at node k.\n    // Note: if the diagonal entry does not exist, then its contribution must be explicitly added,\n    // thus the trick with found_diag that permits to do one more iteration on the diagonal element if this one has not been found.\n    for (typename QRMatrixType::InnerIterator itp(m_pmat, col); itp || !found_diag; ++itp)\n    {\n      StorageIndex curIdx = nonzeroCol;\n      if(itp) curIdx = StorageIndex(itp.row());\n      if(curIdx == nonzeroCol) found_diag = true;\n      \n      // Get the nonzeros indexes of the current column of R\n      StorageIndex st = m_firstRowElt(curIdx); // The traversal of the etree starts here\n      if (st < 0 )\n      {\n        m_lastError = \"Empty row found during numerical factorization\";\n        m_info = InvalidInput;\n        return;\n      }\n\n      // Traverse the etree \n      Index bi = nzcolR;\n      for (; mark(st) != col; st = m_etree(st))\n      {\n        Ridx(nzcolR) = st;  // Add this row to the list,\n        mark(st) = col;     // and mark this row as visited\n        nzcolR++;\n      }\n\n      // Reverse the list to get the topological ordering\n      Index nt = nzcolR-bi;\n      for(Index i = 0; i < nt/2; i++) std::swap(Ridx(bi+i), Ridx(nzcolR-i-1));\n       \n      // Copy the current (curIdx,pcol) value of the input matrix\n      if(itp) tval(curIdx) = itp.value();\n      else    tval(curIdx) = Scalar(0);\n      \n      // Compute the pattern of Q(:,k)\n      if(curIdx > nonzeroCol && mark(curIdx) != col ) \n      {\n        Qidx(nzcolQ) = curIdx;  // Add this row to the pattern of Q,\n        mark(curIdx) = col;     // and mark it as visited\n        nzcolQ++;\n      }\n    }\n\n    // Browse all the indexes of R(:,col) in reverse order\n    for (Index i = nzcolR-1; i >= 0; i--)\n    {\n      Index curIdx = Ridx(i);\n      \n      // Apply the curIdx-th householder vector to the current column (temporarily stored into tval)\n      Scalar tdot(0);\n      \n      // First compute q' * tval\n      tdot = m_Q.col(curIdx).dot(tval);\n\n      tdot *= m_hcoeffs(curIdx);\n      \n      // Then update tval = tval - q * tau\n      // FIXME: tval -= tdot * m_Q.col(curIdx) should amount to the same (need to check/add support for efficient \"dense ?= sparse\")\n      for (typename QRMatrixType::InnerIterator itq(m_Q, curIdx); itq; ++itq)\n        tval(itq.row()) -= itq.value() * tdot;\n\n      // Detect fill-in for the current column of Q\n      if(m_etree(Ridx(i)) == nonzeroCol)\n      {\n        for (typename QRMatrixType::InnerIterator itq(m_Q, curIdx); itq; ++itq)\n        {\n          StorageIndex iQ = StorageIndex(itq.row());\n          if (mark(iQ) != col)\n          {\n            Qidx(nzcolQ++) = iQ;  // Add this row to the pattern of Q,\n            mark(iQ) = col;       // and mark it as visited\n          }\n        }\n      }\n    } // End update current column\n    \n    Scalar tau = RealScalar(0);\n    RealScalar beta = 0;\n    \n    if(nonzeroCol < diagSize)\n    {\n      // Compute the Householder reflection that eliminate the current column\n      // FIXME this step should call the Householder module.\n      Scalar c0 = nzcolQ ? tval(Qidx(0)) : Scalar(0);\n      \n      // First, the squared norm of Q((col+1):m, col)\n      RealScalar sqrNorm = 0.;\n      for (Index itq = 1; itq < nzcolQ; ++itq) sqrNorm += numext::abs2(tval(Qidx(itq)));\n      if(sqrNorm == RealScalar(0) && numext::imag(c0) == RealScalar(0))\n      {\n        beta = numext::real(c0);\n        tval(Qidx(0)) = 1;\n      }\n      else\n      {\n        using std::sqrt;\n        beta = sqrt(numext::abs2(c0) + sqrNorm);\n        if(numext::real(c0) >= RealScalar(0))\n          beta = -beta;\n        tval(Qidx(0)) = 1;\n        for (Index itq = 1; itq < nzcolQ; ++itq)\n          tval(Qidx(itq)) /= (c0 - beta);\n        tau = numext::conj((beta-c0) / beta);\n          \n      }\n    }\n\n    // Insert values in R\n    for (Index  i = nzcolR-1; i >= 0; i--)\n    {\n      Index curIdx = Ridx(i);\n      if(curIdx < nonzeroCol) \n      {\n        m_R.insertBackByOuterInnerUnordered(col, curIdx) = tval(curIdx);\n        tval(curIdx) = Scalar(0.);\n      }\n    }\n\n    if(nonzeroCol < diagSize && abs(beta) >= pivotThreshold)\n    {\n      m_R.insertBackByOuterInner(col, nonzeroCol) = beta;\n      // The householder coefficient\n      m_hcoeffs(nonzeroCol) = tau;\n      // Record the householder reflections\n      for (Index itq = 0; itq < nzcolQ; ++itq)\n      {\n        Index iQ = Qidx(itq);\n        m_Q.insertBackByOuterInnerUnordered(nonzeroCol,iQ) = tval(iQ);\n        tval(iQ) = Scalar(0.);\n      }\n      nonzeroCol++;\n      if(nonzeroCol<diagSize)\n        m_Q.startVec(nonzeroCol);\n    }\n    else\n    {\n      // Zero pivot found: move implicitly this column to the end\n      for (Index j = nonzeroCol; j < n-1; j++) \n        std::swap(m_pivotperm.indices()(j), m_pivotperm.indices()[j+1]);\n      \n      // Recompute the column elimination tree\n      internal::coletree(m_pmat, m_etree, m_firstRowElt, m_pivotperm.indices().data());\n      m_isEtreeOk = false;\n    }\n  }\n  \n  m_hcoeffs.tail(diagSize-nonzeroCol).setZero();\n  \n  // Finalize the column pointers of the sparse matrices R and Q\n  m_Q.finalize();\n  m_Q.makeCompressed();\n  m_R.finalize();\n  m_R.makeCompressed();\n  m_isQSorted = false;\n\n  m_nonzeropivots = nonzeroCol;\n  \n  if(nonzeroCol<n)\n  {\n    // Permute the triangular factor to put the 'dead' columns to the end\n    QRMatrixType tempR(m_R);\n    m_R = tempR * m_pivotperm;\n    \n    // Update the column permutation\n    m_outputPerm_c = m_outputPerm_c * m_pivotperm;\n  }\n  \n  m_isInitialized = true; \n  m_factorizationIsok = true;\n  m_info = Success;\n}\n\ntemplate <typename SparseQRType, typename Derived>\nstruct SparseQR_QProduct : ReturnByValue<SparseQR_QProduct<SparseQRType, Derived> >\n{\n  typedef typename SparseQRType::QRMatrixType MatrixType;\n  typedef typename SparseQRType::Scalar Scalar;\n  // Get the references \n  SparseQR_QProduct(const SparseQRType& qr, const Derived& other, bool transpose) : \n  m_qr(qr),m_other(other),m_transpose(transpose) {}\n  inline Index rows() const { return m_qr.matrixQ().rows(); }\n  inline Index cols() const { return m_other.cols(); }\n  \n  // Assign to a vector\n  template<typename DesType>\n  void evalTo(DesType& res) const\n  {\n    Index m = m_qr.rows();\n    Index n = m_qr.cols();\n    Index diagSize = (std::min)(m,n);\n    res = m_other;\n    if (m_transpose)\n    {\n      eigen_assert(m_qr.m_Q.rows() == m_other.rows() && \"Non conforming object sizes\");\n      //Compute res = Q' * other column by column\n      for(Index j = 0; j < res.cols(); j++){\n        for (Index k = 0; k < diagSize; k++)\n        {\n          Scalar tau = Scalar(0);\n          tau = m_qr.m_Q.col(k).dot(res.col(j));\n          if(tau==Scalar(0)) continue;\n          tau = tau * m_qr.m_hcoeffs(k);\n          res.col(j) -= tau * m_qr.m_Q.col(k);\n        }\n      }\n    }\n    else\n    {\n      eigen_assert(m_qr.matrixQ().cols() == m_other.rows() && \"Non conforming object sizes\");\n\n      res.conservativeResize(rows(), cols());\n\n      // Compute res = Q * other column by column\n      for(Index j = 0; j < res.cols(); j++)\n      {\n        Index start_k = internal::is_identity<Derived>::value ? numext::mini(j,diagSize-1) : diagSize-1;\n        for (Index k = start_k; k >=0; k--)\n        {\n          Scalar tau = Scalar(0);\n          tau = m_qr.m_Q.col(k).dot(res.col(j));\n          if(tau==Scalar(0)) continue;\n          tau = tau * numext::conj(m_qr.m_hcoeffs(k));\n          res.col(j) -= tau * m_qr.m_Q.col(k);\n        }\n      }\n    }\n  }\n  \n  const SparseQRType& m_qr;\n  const Derived& m_other;\n  bool m_transpose; // TODO this actually means adjoint\n};\n\ntemplate<typename SparseQRType>\nstruct SparseQRMatrixQReturnType : public EigenBase<SparseQRMatrixQReturnType<SparseQRType> >\n{  \n  typedef typename SparseQRType::Scalar Scalar;\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  enum {\n    RowsAtCompileTime = Dynamic,\n    ColsAtCompileTime = Dynamic\n  };\n  explicit SparseQRMatrixQReturnType(const SparseQRType& qr) : m_qr(qr) {}\n  template<typename Derived>\n  SparseQR_QProduct<SparseQRType, Derived> operator*(const MatrixBase<Derived>& other)\n  {\n    return SparseQR_QProduct<SparseQRType,Derived>(m_qr,other.derived(),false);\n  }\n  // To use for operations with the adjoint of Q\n  SparseQRMatrixQTransposeReturnType<SparseQRType> adjoint() const\n  {\n    return SparseQRMatrixQTransposeReturnType<SparseQRType>(m_qr);\n  }\n  inline Index rows() const { return m_qr.rows(); }\n  inline Index cols() const { return m_qr.rows(); }\n  // To use for operations with the transpose of Q FIXME this is the same as adjoint at the moment\n  SparseQRMatrixQTransposeReturnType<SparseQRType> transpose() const\n  {\n    return SparseQRMatrixQTransposeReturnType<SparseQRType>(m_qr);\n  }\n  const SparseQRType& m_qr;\n};\n\n// TODO this actually represents the adjoint of Q\ntemplate<typename SparseQRType>\nstruct SparseQRMatrixQTransposeReturnType\n{\n  explicit SparseQRMatrixQTransposeReturnType(const SparseQRType& qr) : m_qr(qr) {}\n  template<typename Derived>\n  SparseQR_QProduct<SparseQRType,Derived> operator*(const MatrixBase<Derived>& other)\n  {\n    return SparseQR_QProduct<SparseQRType,Derived>(m_qr,other.derived(), true);\n  }\n  const SparseQRType& m_qr;\n};\n\nnamespace internal {\n  \ntemplate<typename SparseQRType>\nstruct evaluator_traits<SparseQRMatrixQReturnType<SparseQRType> >\n{\n  typedef typename SparseQRType::MatrixType MatrixType;\n  typedef typename storage_kind_to_evaluator_kind<typename MatrixType::StorageKind>::Kind Kind;\n  typedef SparseShape Shape;\n};\n\ntemplate< typename DstXprType, typename SparseQRType>\nstruct Assignment<DstXprType, SparseQRMatrixQReturnType<SparseQRType>, internal::assign_op<typename DstXprType::Scalar,typename DstXprType::Scalar>, Sparse2Sparse>\n{\n  typedef SparseQRMatrixQReturnType<SparseQRType> SrcXprType;\n  typedef typename DstXprType::Scalar Scalar;\n  typedef typename DstXprType::StorageIndex StorageIndex;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<Scalar,Scalar> &/*func*/)\n  {\n    typename DstXprType::PlainObject idMat(src.rows(), src.cols());\n    idMat.setIdentity();\n    // Sort the sparse householder reflectors if needed\n    const_cast<SparseQRType *>(&src.m_qr)->_sort_matrix_Q();\n    dst = SparseQR_QProduct<SparseQRType, DstXprType>(src.m_qr, idMat, false);\n  }\n};\n\ntemplate< typename DstXprType, typename SparseQRType>\nstruct Assignment<DstXprType, SparseQRMatrixQReturnType<SparseQRType>, internal::assign_op<typename DstXprType::Scalar,typename DstXprType::Scalar>, Sparse2Dense>\n{\n  typedef SparseQRMatrixQReturnType<SparseQRType> SrcXprType;\n  typedef typename DstXprType::Scalar Scalar;\n  typedef typename DstXprType::StorageIndex StorageIndex;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<Scalar,Scalar> &/*func*/)\n  {\n    dst = src.m_qr.matrixQ() * DstXprType::Identity(src.m_qr.rows(), src.m_qr.rows());\n  }\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/StlSupport/StdDeque.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Hauke Heibel <hauke.heibel@googlemail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_STDDEQUE_H\n#define EIGEN_STDDEQUE_H\n\n#include \"details.h\"\n\n/**\n * This section contains a convenience MACRO which allows an easy specialization of\n * std::deque such that for data types with alignment issues the correct allocator\n * is used automatically.\n */\n#define EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(...) \\\nnamespace std \\\n{ \\\n  template<> \\\n  class deque<__VA_ARGS__, std::allocator<__VA_ARGS__> >           \\\n    : public deque<__VA_ARGS__, EIGEN_ALIGNED_ALLOCATOR<__VA_ARGS__> > \\\n  { \\\n    typedef deque<__VA_ARGS__, EIGEN_ALIGNED_ALLOCATOR<__VA_ARGS__> > deque_base; \\\n  public: \\\n    typedef __VA_ARGS__ value_type; \\\n    typedef deque_base::allocator_type allocator_type; \\\n    typedef deque_base::size_type size_type;  \\\n    typedef deque_base::iterator iterator;  \\\n    explicit deque(const allocator_type& a = allocator_type()) : deque_base(a) {}  \\\n    template<typename InputIterator> \\\n    deque(InputIterator first, InputIterator last, const allocator_type& a = allocator_type()) : deque_base(first, last, a) {} \\\n    deque(const deque& c) : deque_base(c) {}  \\\n    explicit deque(size_type num, const value_type& val = value_type()) : deque_base(num, val) {} \\\n    deque(iterator start_, iterator end_) : deque_base(start_, end_) {}  \\\n    deque& operator=(const deque& x) {  \\\n      deque_base::operator=(x);  \\\n      return *this;  \\\n    } \\\n  }; \\\n}\n\n// check whether we really need the std::deque specialization\n#if !EIGEN_HAS_CXX11_CONTAINERS && !(defined(_GLIBCXX_DEQUE) && (!EIGEN_GNUC_AT_LEAST(4,1))) /* Note that before gcc-4.1 we already have: std::deque::resize(size_type,const T&). */\n\nnamespace std {\n\n#define EIGEN_STD_DEQUE_SPECIALIZATION_BODY \\\n  public:  \\\n    typedef T value_type; \\\n    typedef typename deque_base::allocator_type allocator_type; \\\n    typedef typename deque_base::size_type size_type;  \\\n    typedef typename deque_base::iterator iterator;  \\\n    typedef typename deque_base::const_iterator const_iterator;  \\\n    explicit deque(const allocator_type& a = allocator_type()) : deque_base(a) {}  \\\n    template<typename InputIterator> \\\n    deque(InputIterator first, InputIterator last, const allocator_type& a = allocator_type()) \\\n    : deque_base(first, last, a) {} \\\n    deque(const deque& c) : deque_base(c) {}  \\\n    explicit deque(size_type num, const value_type& val = value_type()) : deque_base(num, val) {} \\\n    deque(iterator start_, iterator end_) : deque_base(start_, end_) {}  \\\n    deque& operator=(const deque& x) {  \\\n      deque_base::operator=(x);  \\\n      return *this;  \\\n    }\n\n  template<typename T>\n  class deque<T,EIGEN_ALIGNED_ALLOCATOR<T> >\n    : public deque<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T),\n                   Eigen::aligned_allocator_indirection<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T)> >\n{\n  typedef deque<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T),\n                Eigen::aligned_allocator_indirection<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T)> > deque_base;\n  EIGEN_STD_DEQUE_SPECIALIZATION_BODY\n\n  void resize(size_type new_size)\n  { resize(new_size, T()); }\n\n#if defined(_DEQUE_)\n  // workaround MSVC std::deque implementation\n  void resize(size_type new_size, const value_type& x)\n  {\n    if (deque_base::size() < new_size)\n      deque_base::_Insert_n(deque_base::end(), new_size - deque_base::size(), x);\n    else if (new_size < deque_base::size())\n      deque_base::erase(deque_base::begin() + new_size, deque_base::end());\n  }\n  void push_back(const value_type& x)\n  { deque_base::push_back(x); } \n  void push_front(const value_type& x)\n  { deque_base::push_front(x); }\n  using deque_base::insert;  \n  iterator insert(const_iterator position, const value_type& x)\n  { return deque_base::insert(position,x); }\n  void insert(const_iterator position, size_type new_size, const value_type& x)\n  { deque_base::insert(position, new_size, x); }\n#else\n  // default implementation which should always work.\n  void resize(size_type new_size, const value_type& x)\n  {\n    if (new_size < deque_base::size())\n      deque_base::erase(deque_base::begin() + new_size, deque_base::end());\n    else if (new_size > deque_base::size())\n      deque_base::insert(deque_base::end(), new_size - deque_base::size(), x);\n  }\n#endif\n  };\n}\n\n#endif // check whether specialization is actually required\n\n#endif // EIGEN_STDDEQUE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/StlSupport/StdList.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Hauke Heibel <hauke.heibel@googlemail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_STDLIST_H\n#define EIGEN_STDLIST_H\n\n#include \"details.h\"\n\n/**\n * This section contains a convenience MACRO which allows an easy specialization of\n * std::list such that for data types with alignment issues the correct allocator\n * is used automatically.\n */\n#define EIGEN_DEFINE_STL_LIST_SPECIALIZATION(...) \\\nnamespace std \\\n{ \\\n  template<> \\\n  class list<__VA_ARGS__, std::allocator<__VA_ARGS__> >           \\\n    : public list<__VA_ARGS__, EIGEN_ALIGNED_ALLOCATOR<__VA_ARGS__> > \\\n  { \\\n    typedef list<__VA_ARGS__, EIGEN_ALIGNED_ALLOCATOR<__VA_ARGS__> > list_base; \\\n  public: \\\n    typedef __VA_ARGS__ value_type; \\\n    typedef list_base::allocator_type allocator_type; \\\n    typedef list_base::size_type size_type;  \\\n    typedef list_base::iterator iterator;  \\\n    explicit list(const allocator_type& a = allocator_type()) : list_base(a) {}  \\\n    template<typename InputIterator> \\\n    list(InputIterator first, InputIterator last, const allocator_type& a = allocator_type()) : list_base(first, last, a) {} \\\n    list(const list& c) : list_base(c) {}  \\\n    explicit list(size_type num, const value_type& val = value_type()) : list_base(num, val) {} \\\n    list(iterator start_, iterator end_) : list_base(start_, end_) {}  \\\n    list& operator=(const list& x) {  \\\n      list_base::operator=(x);  \\\n      return *this;  \\\n    } \\\n  }; \\\n}\n\n// check whether we really need the std::list specialization\n#if !EIGEN_HAS_CXX11_CONTAINERS && !(defined(_GLIBCXX_LIST) && (!EIGEN_GNUC_AT_LEAST(4,1))) /* Note that before gcc-4.1 we already have: std::list::resize(size_type,const T&). */\n\nnamespace std\n{\n\n#define EIGEN_STD_LIST_SPECIALIZATION_BODY \\\n  public:  \\\n    typedef T value_type; \\\n    typedef typename list_base::allocator_type allocator_type; \\\n    typedef typename list_base::size_type size_type;  \\\n    typedef typename list_base::iterator iterator;  \\\n    typedef typename list_base::const_iterator const_iterator;  \\\n    explicit list(const allocator_type& a = allocator_type()) : list_base(a) {}  \\\n    template<typename InputIterator> \\\n    list(InputIterator first, InputIterator last, const allocator_type& a = allocator_type()) \\\n    : list_base(first, last, a) {} \\\n    list(const list& c) : list_base(c) {}  \\\n    explicit list(size_type num, const value_type& val = value_type()) : list_base(num, val) {} \\\n    list(iterator start_, iterator end_) : list_base(start_, end_) {}  \\\n    list& operator=(const list& x) {  \\\n    list_base::operator=(x);  \\\n    return *this; \\\n  }\n\n  template<typename T>\n  class list<T,EIGEN_ALIGNED_ALLOCATOR<T> >\n    : public list<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T),\n                  Eigen::aligned_allocator_indirection<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T)> >\n  {\n    typedef list<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T),\n                 Eigen::aligned_allocator_indirection<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T)> > list_base;\n    EIGEN_STD_LIST_SPECIALIZATION_BODY\n\n    void resize(size_type new_size)\n    { resize(new_size, T()); }\n\n    void resize(size_type new_size, const value_type& x)\n    {\n      if (list_base::size() < new_size)\n        list_base::insert(list_base::end(), new_size - list_base::size(), x);\n      else\n        while (new_size < list_base::size()) list_base::pop_back();\n    }\n\n#if defined(_LIST_)\n    // workaround MSVC std::list implementation\n    void push_back(const value_type& x)\n    { list_base::push_back(x); } \n    using list_base::insert;  \n    iterator insert(const_iterator position, const value_type& x)\n    { return list_base::insert(position,x); }\n    void insert(const_iterator position, size_type new_size, const value_type& x)\n    { list_base::insert(position, new_size, x); }\n#endif\n  };\n}\n\n#endif // check whether specialization is actually required\n\n#endif // EIGEN_STDLIST_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/StlSupport/StdVector.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Hauke Heibel <hauke.heibel@googlemail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_STDVECTOR_H\n#define EIGEN_STDVECTOR_H\n\n#include \"details.h\"\n\n/**\n * This section contains a convenience MACRO which allows an easy specialization of\n * std::vector such that for data types with alignment issues the correct allocator\n * is used automatically.\n */\n#define EIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(...) \\\nnamespace std \\\n{ \\\n  template<> \\\n  class vector<__VA_ARGS__, std::allocator<__VA_ARGS__> >  \\\n    : public vector<__VA_ARGS__, EIGEN_ALIGNED_ALLOCATOR<__VA_ARGS__> > \\\n  { \\\n    typedef vector<__VA_ARGS__, EIGEN_ALIGNED_ALLOCATOR<__VA_ARGS__> > vector_base; \\\n  public: \\\n    typedef __VA_ARGS__ value_type; \\\n    typedef vector_base::allocator_type allocator_type; \\\n    typedef vector_base::size_type size_type;  \\\n    typedef vector_base::iterator iterator;  \\\n    explicit vector(const allocator_type& a = allocator_type()) : vector_base(a) {}  \\\n    template<typename InputIterator> \\\n    vector(InputIterator first, InputIterator last, const allocator_type& a = allocator_type()) : vector_base(first, last, a) {} \\\n    vector(const vector& c) : vector_base(c) {}  \\\n    explicit vector(size_type num, const value_type& val = value_type()) : vector_base(num, val) {} \\\n    vector(iterator start_, iterator end_) : vector_base(start_, end_) {}  \\\n    vector& operator=(const vector& x) {  \\\n      vector_base::operator=(x);  \\\n      return *this;  \\\n    } \\\n  }; \\\n}\n\n// Don't specialize if containers are implemented according to C++11\n#if !EIGEN_HAS_CXX11_CONTAINERS\n\nnamespace std {\n\n#define EIGEN_STD_VECTOR_SPECIALIZATION_BODY \\\n  public:  \\\n    typedef T value_type; \\\n    typedef typename vector_base::allocator_type allocator_type; \\\n    typedef typename vector_base::size_type size_type;  \\\n    typedef typename vector_base::iterator iterator;  \\\n    typedef typename vector_base::const_iterator const_iterator;  \\\n    explicit vector(const allocator_type& a = allocator_type()) : vector_base(a) {}  \\\n    template<typename InputIterator> \\\n    vector(InputIterator first, InputIterator last, const allocator_type& a = allocator_type()) \\\n    : vector_base(first, last, a) {} \\\n    vector(const vector& c) : vector_base(c) {}  \\\n    explicit vector(size_type num, const value_type& val = value_type()) : vector_base(num, val) {} \\\n    vector(iterator start_, iterator end_) : vector_base(start_, end_) {}  \\\n    vector& operator=(const vector& x) {  \\\n      vector_base::operator=(x);  \\\n      return *this;  \\\n    }\n\n  template<typename T>\n  class vector<T,EIGEN_ALIGNED_ALLOCATOR<T> >\n    : public vector<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T),\n                    Eigen::aligned_allocator_indirection<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T)> >\n{\n  typedef vector<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T),\n                 Eigen::aligned_allocator_indirection<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T)> > vector_base;\n  EIGEN_STD_VECTOR_SPECIALIZATION_BODY\n\n  void resize(size_type new_size)\n  { resize(new_size, T()); }\n\n#if defined(_VECTOR_)\n  // workaround MSVC std::vector implementation\n  void resize(size_type new_size, const value_type& x)\n  {\n    if (vector_base::size() < new_size)\n      vector_base::_Insert_n(vector_base::end(), new_size - vector_base::size(), x);\n    else if (new_size < vector_base::size())\n      vector_base::erase(vector_base::begin() + new_size, vector_base::end());\n  }\n  void push_back(const value_type& x)\n  { vector_base::push_back(x); } \n  using vector_base::insert;  \n  iterator insert(const_iterator position, const value_type& x)\n  { return vector_base::insert(position,x); }\n  void insert(const_iterator position, size_type new_size, const value_type& x)\n  { vector_base::insert(position, new_size, x); }\n#elif defined(_GLIBCXX_VECTOR) && (!(EIGEN_GNUC_AT_LEAST(4,1)))\n  /* Note that before gcc-4.1 we already have: std::vector::resize(size_type,const T&).\n   * However, this specialization is still needed to make the above EIGEN_DEFINE_STL_VECTOR_SPECIALIZATION trick to work. */\n  void resize(size_type new_size, const value_type& x)\n  {\n    vector_base::resize(new_size,x);\n  }\n#elif defined(_GLIBCXX_VECTOR) && EIGEN_GNUC_AT_LEAST(4,2)\n  // workaround GCC std::vector implementation\n  void resize(size_type new_size, const value_type& x)\n  {\n    if (new_size < vector_base::size())\n      vector_base::_M_erase_at_end(this->_M_impl._M_start + new_size);\n    else\n      vector_base::insert(vector_base::end(), new_size - vector_base::size(), x);\n  }\n#else\n  // either GCC 4.1 or non-GCC\n  // default implementation which should always work.\n  void resize(size_type new_size, const value_type& x)\n  {\n    if (new_size < vector_base::size())\n      vector_base::erase(vector_base::begin() + new_size, vector_base::end());\n    else if (new_size > vector_base::size())\n      vector_base::insert(vector_base::end(), new_size - vector_base::size(), x);\n  }\n#endif\n  };\n}\n#endif // !EIGEN_HAS_CXX11_CONTAINERS\n\n\n#endif // EIGEN_STDVECTOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/StlSupport/details.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Hauke Heibel <hauke.heibel@googlemail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_STL_DETAILS_H\n#define EIGEN_STL_DETAILS_H\n\n#ifndef EIGEN_ALIGNED_ALLOCATOR\n  #define EIGEN_ALIGNED_ALLOCATOR Eigen::aligned_allocator\n#endif\n\nnamespace Eigen {\n\n  // This one is needed to prevent reimplementing the whole std::vector.\n  template <class T>\n  class aligned_allocator_indirection : public EIGEN_ALIGNED_ALLOCATOR<T>\n  {\n  public:\n    typedef std::size_t     size_type;\n    typedef std::ptrdiff_t  difference_type;\n    typedef T*              pointer;\n    typedef const T*        const_pointer;\n    typedef T&              reference;\n    typedef const T&        const_reference;\n    typedef T               value_type;\n\n    template<class U>\n    struct rebind\n    {\n      typedef aligned_allocator_indirection<U> other;\n    };\n\n    aligned_allocator_indirection() {}\n    aligned_allocator_indirection(const aligned_allocator_indirection& ) : EIGEN_ALIGNED_ALLOCATOR<T>() {}\n    aligned_allocator_indirection(const EIGEN_ALIGNED_ALLOCATOR<T>& ) {}\n    template<class U>\n    aligned_allocator_indirection(const aligned_allocator_indirection<U>& ) {}\n    template<class U>\n    aligned_allocator_indirection(const EIGEN_ALIGNED_ALLOCATOR<U>& ) {}\n    ~aligned_allocator_indirection() {}\n  };\n\n#if EIGEN_COMP_MSVC\n\n  // sometimes, MSVC detects, at compile time, that the argument x\n  // in std::vector::resize(size_t s,T x) won't be aligned and generate an error\n  // even if this function is never called. Whence this little wrapper.\n#define EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T) \\\n  typename Eigen::internal::conditional< \\\n    Eigen::internal::is_arithmetic<T>::value, \\\n    T, \\\n    Eigen::internal::workaround_msvc_stl_support<T> \\\n  >::type\n\n  namespace internal {\n  template<typename T> struct workaround_msvc_stl_support : public T\n  {\n    inline workaround_msvc_stl_support() : T() {}\n    inline workaround_msvc_stl_support(const T& other) : T(other) {}\n    inline operator T& () { return *static_cast<T*>(this); }\n    inline operator const T& () const { return *static_cast<const T*>(this); }\n    template<typename OtherT>\n    inline T& operator=(const OtherT& other)\n    { T::operator=(other); return *this; }\n    inline workaround_msvc_stl_support& operator=(const workaround_msvc_stl_support& other)\n    { T::operator=(other); return *this; }\n  };\n  }\n\n#else\n\n#define EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T) T\n\n#endif\n\n}\n\n#endif // EIGEN_STL_DETAILS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/SuperLUSupport/SuperLUSupport.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SUPERLUSUPPORT_H\n#define EIGEN_SUPERLUSUPPORT_H\n\nnamespace Eigen {\n\n#if defined(SUPERLU_MAJOR_VERSION) && (SUPERLU_MAJOR_VERSION >= 5)\n#define DECL_GSSVX(PREFIX,FLOATTYPE,KEYTYPE)\t\t\\\n    extern \"C\" {                                                                                          \\\n      extern void PREFIX##gssvx(superlu_options_t *, SuperMatrix *, int *, int *, int *,                  \\\n                                char *, FLOATTYPE *, FLOATTYPE *, SuperMatrix *, SuperMatrix *,           \\\n                                void *, int, SuperMatrix *, SuperMatrix *,                                \\\n                                FLOATTYPE *, FLOATTYPE *, FLOATTYPE *, FLOATTYPE *,                       \\\n                                GlobalLU_t *, mem_usage_t *, SuperLUStat_t *, int *);                     \\\n    }                                                                                                     \\\n    inline float SuperLU_gssvx(superlu_options_t *options, SuperMatrix *A,                                \\\n         int *perm_c, int *perm_r, int *etree, char *equed,                                               \\\n         FLOATTYPE *R, FLOATTYPE *C, SuperMatrix *L,                                                      \\\n         SuperMatrix *U, void *work, int lwork,                                                           \\\n         SuperMatrix *B, SuperMatrix *X,                                                                  \\\n         FLOATTYPE *recip_pivot_growth,                                                                   \\\n         FLOATTYPE *rcond, FLOATTYPE *ferr, FLOATTYPE *berr,                                              \\\n         SuperLUStat_t *stats, int *info, KEYTYPE) {                                                      \\\n    mem_usage_t mem_usage;                                                                                \\\n    GlobalLU_t gLU;                                                                                       \\\n    PREFIX##gssvx(options, A, perm_c, perm_r, etree, equed, R, C, L,                                      \\\n         U, work, lwork, B, X, recip_pivot_growth, rcond,                                                 \\\n         ferr, berr, &gLU, &mem_usage, stats, info);                                                      \\\n    return mem_usage.for_lu; /* bytes used by the factor storage */                                       \\\n  }\n#else // version < 5.0\n#define DECL_GSSVX(PREFIX,FLOATTYPE,KEYTYPE)\t\t\\\n    extern \"C\" {                                                                                          \\\n      extern void PREFIX##gssvx(superlu_options_t *, SuperMatrix *, int *, int *, int *,                  \\\n                                char *, FLOATTYPE *, FLOATTYPE *, SuperMatrix *, SuperMatrix *,           \\\n                                void *, int, SuperMatrix *, SuperMatrix *,                                \\\n                                FLOATTYPE *, FLOATTYPE *, FLOATTYPE *, FLOATTYPE *,                       \\\n                                mem_usage_t *, SuperLUStat_t *, int *);                                   \\\n    }                                                                                                     \\\n    inline float SuperLU_gssvx(superlu_options_t *options, SuperMatrix *A,                                \\\n         int *perm_c, int *perm_r, int *etree, char *equed,                                               \\\n         FLOATTYPE *R, FLOATTYPE *C, SuperMatrix *L,                                                      \\\n         SuperMatrix *U, void *work, int lwork,                                                           \\\n         SuperMatrix *B, SuperMatrix *X,                                                                  \\\n         FLOATTYPE *recip_pivot_growth,                                                                   \\\n         FLOATTYPE *rcond, FLOATTYPE *ferr, FLOATTYPE *berr,                                              \\\n         SuperLUStat_t *stats, int *info, KEYTYPE) {                                                      \\\n    mem_usage_t mem_usage;                                                                                \\\n    PREFIX##gssvx(options, A, perm_c, perm_r, etree, equed, R, C, L,                                      \\\n         U, work, lwork, B, X, recip_pivot_growth, rcond,                                                 \\\n         ferr, berr, &mem_usage, stats, info);                                                            \\\n    return mem_usage.for_lu; /* bytes used by the factor storage */                                       \\\n  }\n#endif\n\nDECL_GSSVX(s,float,float)\nDECL_GSSVX(c,float,std::complex<float>)\nDECL_GSSVX(d,double,double)\nDECL_GSSVX(z,double,std::complex<double>)\n\n#ifdef MILU_ALPHA\n#define EIGEN_SUPERLU_HAS_ILU\n#endif\n\n#ifdef EIGEN_SUPERLU_HAS_ILU\n\n// similarly for the incomplete factorization using gsisx\n#define DECL_GSISX(PREFIX,FLOATTYPE,KEYTYPE)                                                    \\\n    extern \"C\" {                                                                                \\\n      extern void PREFIX##gsisx(superlu_options_t *, SuperMatrix *, int *, int *, int *,        \\\n                         char *, FLOATTYPE *, FLOATTYPE *, SuperMatrix *, SuperMatrix *,        \\\n                         void *, int, SuperMatrix *, SuperMatrix *, FLOATTYPE *, FLOATTYPE *,   \\\n                         mem_usage_t *, SuperLUStat_t *, int *);                        \\\n    }                                                                                           \\\n    inline float SuperLU_gsisx(superlu_options_t *options, SuperMatrix *A,                      \\\n         int *perm_c, int *perm_r, int *etree, char *equed,                                     \\\n         FLOATTYPE *R, FLOATTYPE *C, SuperMatrix *L,                                            \\\n         SuperMatrix *U, void *work, int lwork,                                                 \\\n         SuperMatrix *B, SuperMatrix *X,                                                        \\\n         FLOATTYPE *recip_pivot_growth,                                                         \\\n         FLOATTYPE *rcond,                                                                      \\\n         SuperLUStat_t *stats, int *info, KEYTYPE) {                                            \\\n    mem_usage_t mem_usage;                                                              \\\n    PREFIX##gsisx(options, A, perm_c, perm_r, etree, equed, R, C, L,                            \\\n         U, work, lwork, B, X, recip_pivot_growth, rcond,                                       \\\n         &mem_usage, stats, info);                                                              \\\n    return mem_usage.for_lu; /* bytes used by the factor storage */                             \\\n  }\n\nDECL_GSISX(s,float,float)\nDECL_GSISX(c,float,std::complex<float>)\nDECL_GSISX(d,double,double)\nDECL_GSISX(z,double,std::complex<double>)\n\n#endif\n\ntemplate<typename MatrixType>\nstruct SluMatrixMapHelper;\n\n/** \\internal\n  *\n  * A wrapper class for SuperLU matrices. It supports only compressed sparse matrices\n  * and dense matrices. Supernodal and other fancy format are not supported by this wrapper.\n  *\n  * This wrapper class mainly aims to avoids the need of dynamic allocation of the storage structure.\n  */\nstruct SluMatrix : SuperMatrix\n{\n  SluMatrix()\n  {\n    Store = &storage;\n  }\n\n  SluMatrix(const SluMatrix& other)\n    : SuperMatrix(other)\n  {\n    Store = &storage;\n    storage = other.storage;\n  }\n\n  SluMatrix& operator=(const SluMatrix& other)\n  {\n    SuperMatrix::operator=(static_cast<const SuperMatrix&>(other));\n    Store = &storage;\n    storage = other.storage;\n    return *this;\n  }\n\n  struct\n  {\n    union {int nnz;int lda;};\n    void *values;\n    int *innerInd;\n    int *outerInd;\n  } storage;\n\n  void setStorageType(Stype_t t)\n  {\n    Stype = t;\n    if (t==SLU_NC || t==SLU_NR || t==SLU_DN)\n      Store = &storage;\n    else\n    {\n      eigen_assert(false && \"storage type not supported\");\n      Store = 0;\n    }\n  }\n\n  template<typename Scalar>\n  void setScalarType()\n  {\n    if (internal::is_same<Scalar,float>::value)\n      Dtype = SLU_S;\n    else if (internal::is_same<Scalar,double>::value)\n      Dtype = SLU_D;\n    else if (internal::is_same<Scalar,std::complex<float> >::value)\n      Dtype = SLU_C;\n    else if (internal::is_same<Scalar,std::complex<double> >::value)\n      Dtype = SLU_Z;\n    else\n    {\n      eigen_assert(false && \"Scalar type not supported by SuperLU\");\n    }\n  }\n\n  template<typename MatrixType>\n  static SluMatrix Map(MatrixBase<MatrixType>& _mat)\n  {\n    MatrixType& mat(_mat.derived());\n    eigen_assert( ((MatrixType::Flags&RowMajorBit)!=RowMajorBit) && \"row-major dense matrices are not supported by SuperLU\");\n    SluMatrix res;\n    res.setStorageType(SLU_DN);\n    res.setScalarType<typename MatrixType::Scalar>();\n    res.Mtype     = SLU_GE;\n\n    res.nrow      = internal::convert_index<int>(mat.rows());\n    res.ncol      = internal::convert_index<int>(mat.cols());\n\n    res.storage.lda       = internal::convert_index<int>(MatrixType::IsVectorAtCompileTime ? mat.size() : mat.outerStride());\n    res.storage.values    = (void*)(mat.data());\n    return res;\n  }\n\n  template<typename MatrixType>\n  static SluMatrix Map(SparseMatrixBase<MatrixType>& a_mat)\n  {\n    MatrixType &mat(a_mat.derived());\n    SluMatrix res;\n    if ((MatrixType::Flags&RowMajorBit)==RowMajorBit)\n    {\n      res.setStorageType(SLU_NR);\n      res.nrow      = internal::convert_index<int>(mat.cols());\n      res.ncol      = internal::convert_index<int>(mat.rows());\n    }\n    else\n    {\n      res.setStorageType(SLU_NC);\n      res.nrow      = internal::convert_index<int>(mat.rows());\n      res.ncol      = internal::convert_index<int>(mat.cols());\n    }\n\n    res.Mtype       = SLU_GE;\n\n    res.storage.nnz       = internal::convert_index<int>(mat.nonZeros());\n    res.storage.values    = mat.valuePtr();\n    res.storage.innerInd  = mat.innerIndexPtr();\n    res.storage.outerInd  = mat.outerIndexPtr();\n\n    res.setScalarType<typename MatrixType::Scalar>();\n\n    // FIXME the following is not very accurate\n    if (int(MatrixType::Flags) & int(Upper))\n      res.Mtype = SLU_TRU;\n    if (int(MatrixType::Flags) & int(Lower))\n      res.Mtype = SLU_TRL;\n\n    eigen_assert(((int(MatrixType::Flags) & int(SelfAdjoint))==0) && \"SelfAdjoint matrix shape not supported by SuperLU\");\n\n    return res;\n  }\n};\n\ntemplate<typename Scalar, int Rows, int Cols, int Options, int MRows, int MCols>\nstruct SluMatrixMapHelper<Matrix<Scalar,Rows,Cols,Options,MRows,MCols> >\n{\n  typedef Matrix<Scalar,Rows,Cols,Options,MRows,MCols> MatrixType;\n  static void run(MatrixType& mat, SluMatrix& res)\n  {\n    eigen_assert( ((Options&RowMajor)!=RowMajor) && \"row-major dense matrices is not supported by SuperLU\");\n    res.setStorageType(SLU_DN);\n    res.setScalarType<Scalar>();\n    res.Mtype     = SLU_GE;\n\n    res.nrow      = mat.rows();\n    res.ncol      = mat.cols();\n\n    res.storage.lda       = mat.outerStride();\n    res.storage.values    = mat.data();\n  }\n};\n\ntemplate<typename Derived>\nstruct SluMatrixMapHelper<SparseMatrixBase<Derived> >\n{\n  typedef Derived MatrixType;\n  static void run(MatrixType& mat, SluMatrix& res)\n  {\n    if ((MatrixType::Flags&RowMajorBit)==RowMajorBit)\n    {\n      res.setStorageType(SLU_NR);\n      res.nrow      = mat.cols();\n      res.ncol      = mat.rows();\n    }\n    else\n    {\n      res.setStorageType(SLU_NC);\n      res.nrow      = mat.rows();\n      res.ncol      = mat.cols();\n    }\n\n    res.Mtype       = SLU_GE;\n\n    res.storage.nnz       = mat.nonZeros();\n    res.storage.values    = mat.valuePtr();\n    res.storage.innerInd  = mat.innerIndexPtr();\n    res.storage.outerInd  = mat.outerIndexPtr();\n\n    res.setScalarType<typename MatrixType::Scalar>();\n\n    // FIXME the following is not very accurate\n    if (MatrixType::Flags & Upper)\n      res.Mtype = SLU_TRU;\n    if (MatrixType::Flags & Lower)\n      res.Mtype = SLU_TRL;\n\n    eigen_assert(((MatrixType::Flags & SelfAdjoint)==0) && \"SelfAdjoint matrix shape not supported by SuperLU\");\n  }\n};\n\nnamespace internal {\n\ntemplate<typename MatrixType>\nSluMatrix asSluMatrix(MatrixType& mat)\n{\n  return SluMatrix::Map(mat);\n}\n\n/** View a Super LU matrix as an Eigen expression */\ntemplate<typename Scalar, int Flags, typename Index>\nMappedSparseMatrix<Scalar,Flags,Index> map_superlu(SluMatrix& sluMat)\n{\n  eigen_assert(((Flags&RowMajor)==RowMajor && sluMat.Stype == SLU_NR)\n         || ((Flags&ColMajor)==ColMajor && sluMat.Stype == SLU_NC));\n\n  Index outerSize = (Flags&RowMajor)==RowMajor ? sluMat.ncol : sluMat.nrow;\n\n  return MappedSparseMatrix<Scalar,Flags,Index>(\n    sluMat.nrow, sluMat.ncol, sluMat.storage.outerInd[outerSize],\n    sluMat.storage.outerInd, sluMat.storage.innerInd, reinterpret_cast<Scalar*>(sluMat.storage.values) );\n}\n\n} // end namespace internal\n\n/** \\ingroup SuperLUSupport_Module\n  * \\class SuperLUBase\n  * \\brief The base class for the direct and incomplete LU factorization of SuperLU\n  */\ntemplate<typename MatrixType_, typename Derived>\nclass SuperLUBase : public SparseSolverBase<Derived>\n{\n  protected:\n    typedef SparseSolverBase<Derived> Base;\n    using Base::derived;\n    using Base::m_isInitialized;\n  public:\n    typedef MatrixType_ MatrixType;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef Matrix<Scalar,Dynamic,1> Vector;\n    typedef Matrix<int, 1, MatrixType::ColsAtCompileTime> IntRowVectorType;\n    typedef Matrix<int, MatrixType::RowsAtCompileTime, 1> IntColVectorType;    \n    typedef Map<PermutationMatrix<Dynamic,Dynamic,int> > PermutationMap;\n    typedef SparseMatrix<Scalar> LUMatrixType;\n    enum {\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n\n  public:\n\n    SuperLUBase() {}\n\n    ~SuperLUBase()\n    {\n      clearFactors();\n    }\n    \n    inline Index rows() const { return m_matrix.rows(); }\n    inline Index cols() const { return m_matrix.cols(); }\n    \n    /** \\returns a reference to the Super LU option object to configure the  Super LU algorithms. */\n    inline superlu_options_t& options() { return m_sluOptions; }\n    \n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the matrix.appears to be negative.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_info;\n    }\n\n    /** Computes the sparse Cholesky decomposition of \\a matrix */\n    void compute(const MatrixType& matrix)\n    {\n      derived().analyzePattern(matrix);\n      derived().factorize(matrix);\n    }\n\n    /** Performs a symbolic decomposition on the sparcity of \\a matrix.\n      *\n      * This function is particularly useful when solving for several problems having the same structure.\n      * \n      * \\sa factorize()\n      */\n    void analyzePattern(const MatrixType& /*matrix*/)\n    {\n      m_isInitialized = true;\n      m_info = Success;\n      m_analysisIsOk = true;\n      m_factorizationIsOk = false;\n    }\n    \n    template<typename Stream>\n    void dumpMemory(Stream& /*s*/)\n    {}\n    \n  protected:\n    \n    void initFactorization(const MatrixType& a)\n    {\n      set_default_options(&this->m_sluOptions);\n      \n      const Index size = a.rows();\n      m_matrix = a;\n\n      m_sluA = internal::asSluMatrix(m_matrix);\n      clearFactors();\n\n      m_p.resize(size);\n      m_q.resize(size);\n      m_sluRscale.resize(size);\n      m_sluCscale.resize(size);\n      m_sluEtree.resize(size);\n\n      // set empty B and X\n      m_sluB.setStorageType(SLU_DN);\n      m_sluB.setScalarType<Scalar>();\n      m_sluB.Mtype          = SLU_GE;\n      m_sluB.storage.values = 0;\n      m_sluB.nrow           = 0;\n      m_sluB.ncol           = 0;\n      m_sluB.storage.lda    = internal::convert_index<int>(size);\n      m_sluX                = m_sluB;\n      \n      m_extractedDataAreDirty = true;\n    }\n    \n    void init()\n    {\n      m_info = InvalidInput;\n      m_isInitialized = false;\n      m_sluL.Store = 0;\n      m_sluU.Store = 0;\n    }\n    \n    void extractData() const;\n\n    void clearFactors()\n    {\n      if(m_sluL.Store)\n        Destroy_SuperNode_Matrix(&m_sluL);\n      if(m_sluU.Store)\n        Destroy_CompCol_Matrix(&m_sluU);\n\n      m_sluL.Store = 0;\n      m_sluU.Store = 0;\n\n      memset(&m_sluL,0,sizeof m_sluL);\n      memset(&m_sluU,0,sizeof m_sluU);\n    }\n\n    // cached data to reduce reallocation, etc.\n    mutable LUMatrixType m_l;\n    mutable LUMatrixType m_u;\n    mutable IntColVectorType m_p;\n    mutable IntRowVectorType m_q;\n\n    mutable LUMatrixType m_matrix;  // copy of the factorized matrix\n    mutable SluMatrix m_sluA;\n    mutable SuperMatrix m_sluL, m_sluU;\n    mutable SluMatrix m_sluB, m_sluX;\n    mutable SuperLUStat_t m_sluStat;\n    mutable superlu_options_t m_sluOptions;\n    mutable std::vector<int> m_sluEtree;\n    mutable Matrix<RealScalar,Dynamic,1> m_sluRscale, m_sluCscale;\n    mutable Matrix<RealScalar,Dynamic,1> m_sluFerr, m_sluBerr;\n    mutable char m_sluEqued;\n\n    mutable ComputationInfo m_info;\n    int m_factorizationIsOk;\n    int m_analysisIsOk;\n    mutable bool m_extractedDataAreDirty;\n    \n  private:\n    SuperLUBase(SuperLUBase& ) { }\n};\n\n\n/** \\ingroup SuperLUSupport_Module\n  * \\class SuperLU\n  * \\brief A sparse direct LU factorization and solver based on the SuperLU library\n  *\n  * This class allows to solve for A.X = B sparse linear problems via a direct LU factorization\n  * using the SuperLU library. The sparse matrix A must be squared and invertible. The vectors or matrices\n  * X and B can be either dense or sparse.\n  *\n  * \\tparam MatrixType_ the type of the sparse matrix A, it must be a SparseMatrix<>\n  *\n  * \\warning This class is only for the 4.x versions of SuperLU. The 3.x and 5.x versions are not supported.\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class SparseLU\n  */\ntemplate<typename MatrixType_>\nclass SuperLU : public SuperLUBase<MatrixType_,SuperLU<MatrixType_> >\n{\n  public:\n    typedef SuperLUBase<MatrixType_,SuperLU> Base;\n    typedef MatrixType_ MatrixType;\n    typedef typename Base::Scalar Scalar;\n    typedef typename Base::RealScalar RealScalar;\n    typedef typename Base::StorageIndex StorageIndex;\n    typedef typename Base::IntRowVectorType IntRowVectorType;\n    typedef typename Base::IntColVectorType IntColVectorType;   \n    typedef typename Base::PermutationMap PermutationMap;\n    typedef typename Base::LUMatrixType LUMatrixType;\n    typedef TriangularView<LUMatrixType, Lower|UnitDiag>  LMatrixType;\n    typedef TriangularView<LUMatrixType,  Upper>          UMatrixType;\n\n  public:\n    using Base::_solve_impl;\n\n    SuperLU() : Base() { init(); }\n\n    explicit SuperLU(const MatrixType& matrix) : Base()\n    {\n      init();\n      Base::compute(matrix);\n    }\n\n    ~SuperLU()\n    {\n    }\n    \n    /** Performs a symbolic decomposition on the sparcity of \\a matrix.\n      *\n      * This function is particularly useful when solving for several problems having the same structure.\n      * \n      * \\sa factorize()\n      */\n    void analyzePattern(const MatrixType& matrix)\n    {\n      m_info = InvalidInput;\n      m_isInitialized = false;\n      Base::analyzePattern(matrix);\n    }\n    \n    /** Performs a numeric decomposition of \\a matrix\n      *\n      * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed.\n      *\n      * \\sa analyzePattern()\n      */\n    void factorize(const MatrixType& matrix);\n    \n    /** \\internal */\n    template<typename Rhs,typename Dest>\n    void _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const;\n    \n    inline const LMatrixType& matrixL() const\n    {\n      if (m_extractedDataAreDirty) this->extractData();\n      return m_l;\n    }\n\n    inline const UMatrixType& matrixU() const\n    {\n      if (m_extractedDataAreDirty) this->extractData();\n      return m_u;\n    }\n\n    inline const IntColVectorType& permutationP() const\n    {\n      if (m_extractedDataAreDirty) this->extractData();\n      return m_p;\n    }\n\n    inline const IntRowVectorType& permutationQ() const\n    {\n      if (m_extractedDataAreDirty) this->extractData();\n      return m_q;\n    }\n    \n    Scalar determinant() const;\n    \n  protected:\n    \n    using Base::m_matrix;\n    using Base::m_sluOptions;\n    using Base::m_sluA;\n    using Base::m_sluB;\n    using Base::m_sluX;\n    using Base::m_p;\n    using Base::m_q;\n    using Base::m_sluEtree;\n    using Base::m_sluEqued;\n    using Base::m_sluRscale;\n    using Base::m_sluCscale;\n    using Base::m_sluL;\n    using Base::m_sluU;\n    using Base::m_sluStat;\n    using Base::m_sluFerr;\n    using Base::m_sluBerr;\n    using Base::m_l;\n    using Base::m_u;\n    \n    using Base::m_analysisIsOk;\n    using Base::m_factorizationIsOk;\n    using Base::m_extractedDataAreDirty;\n    using Base::m_isInitialized;\n    using Base::m_info;\n    \n    void init()\n    {\n      Base::init();\n      \n      set_default_options(&this->m_sluOptions);\n      m_sluOptions.PrintStat        = NO;\n      m_sluOptions.ConditionNumber  = NO;\n      m_sluOptions.Trans            = NOTRANS;\n      m_sluOptions.ColPerm          = COLAMD;\n    }\n    \n    \n  private:\n    SuperLU(SuperLU& ) { }\n};\n\ntemplate<typename MatrixType>\nvoid SuperLU<MatrixType>::factorize(const MatrixType& a)\n{\n  eigen_assert(m_analysisIsOk && \"You must first call analyzePattern()\");\n  if(!m_analysisIsOk)\n  {\n    m_info = InvalidInput;\n    return;\n  }\n  \n  this->initFactorization(a);\n  \n  m_sluOptions.ColPerm = COLAMD;\n  int info = 0;\n  RealScalar recip_pivot_growth, rcond;\n  RealScalar ferr, berr;\n\n  StatInit(&m_sluStat);\n  SuperLU_gssvx(&m_sluOptions, &m_sluA, m_q.data(), m_p.data(), &m_sluEtree[0],\n                &m_sluEqued, &m_sluRscale[0], &m_sluCscale[0],\n                &m_sluL, &m_sluU,\n                NULL, 0,\n                &m_sluB, &m_sluX,\n                &recip_pivot_growth, &rcond,\n                &ferr, &berr,\n                &m_sluStat, &info, Scalar());\n  StatFree(&m_sluStat);\n\n  m_extractedDataAreDirty = true;\n\n  // FIXME how to better check for errors ???\n  m_info = info == 0 ? Success : NumericalIssue;\n  m_factorizationIsOk = true;\n}\n\ntemplate<typename MatrixType>\ntemplate<typename Rhs,typename Dest>\nvoid SuperLU<MatrixType>::_solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest>& x) const\n{\n  eigen_assert(m_factorizationIsOk && \"The decomposition is not in a valid state for solving, you must first call either compute() or analyzePattern()/factorize()\");\n\n  const Index rhsCols = b.cols();\n  eigen_assert(m_matrix.rows()==b.rows());\n\n  m_sluOptions.Trans = NOTRANS;\n  m_sluOptions.Fact = FACTORED;\n  m_sluOptions.IterRefine = NOREFINE;\n  \n\n  m_sluFerr.resize(rhsCols);\n  m_sluBerr.resize(rhsCols);\n  \n  Ref<const Matrix<typename Rhs::Scalar,Dynamic,Dynamic,ColMajor> > b_ref(b);\n  Ref<const Matrix<typename Dest::Scalar,Dynamic,Dynamic,ColMajor> > x_ref(x);\n  \n  m_sluB = SluMatrix::Map(b_ref.const_cast_derived());\n  m_sluX = SluMatrix::Map(x_ref.const_cast_derived());\n  \n  typename Rhs::PlainObject b_cpy;\n  if(m_sluEqued!='N')\n  {\n    b_cpy = b;\n    m_sluB = SluMatrix::Map(b_cpy.const_cast_derived());  \n  }\n\n  StatInit(&m_sluStat);\n  int info = 0;\n  RealScalar recip_pivot_growth, rcond;\n  SuperLU_gssvx(&m_sluOptions, &m_sluA,\n                m_q.data(), m_p.data(),\n                &m_sluEtree[0], &m_sluEqued,\n                &m_sluRscale[0], &m_sluCscale[0],\n                &m_sluL, &m_sluU,\n                NULL, 0,\n                &m_sluB, &m_sluX,\n                &recip_pivot_growth, &rcond,\n                &m_sluFerr[0], &m_sluBerr[0],\n                &m_sluStat, &info, Scalar());\n  StatFree(&m_sluStat);\n  \n  if(x.derived().data() != x_ref.data())\n    x = x_ref;\n  \n  m_info = info==0 ? Success : NumericalIssue;\n}\n\n// the code of this extractData() function has been adapted from the SuperLU's Matlab support code,\n//\n//  Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n//\n//  THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n//  EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n//\ntemplate<typename MatrixType, typename Derived>\nvoid SuperLUBase<MatrixType,Derived>::extractData() const\n{\n  eigen_assert(m_factorizationIsOk && \"The decomposition is not in a valid state for extracting factors, you must first call either compute() or analyzePattern()/factorize()\");\n  if (m_extractedDataAreDirty)\n  {\n    int         upper;\n    int         fsupc, istart, nsupr;\n    int         lastl = 0, lastu = 0;\n    SCformat    *Lstore = static_cast<SCformat*>(m_sluL.Store);\n    NCformat    *Ustore = static_cast<NCformat*>(m_sluU.Store);\n    Scalar      *SNptr;\n\n    const Index size = m_matrix.rows();\n    m_l.resize(size,size);\n    m_l.resizeNonZeros(Lstore->nnz);\n    m_u.resize(size,size);\n    m_u.resizeNonZeros(Ustore->nnz);\n\n    int* Lcol = m_l.outerIndexPtr();\n    int* Lrow = m_l.innerIndexPtr();\n    Scalar* Lval = m_l.valuePtr();\n\n    int* Ucol = m_u.outerIndexPtr();\n    int* Urow = m_u.innerIndexPtr();\n    Scalar* Uval = m_u.valuePtr();\n\n    Ucol[0] = 0;\n    Ucol[0] = 0;\n\n    /* for each supernode */\n    for (int k = 0; k <= Lstore->nsuper; ++k)\n    {\n      fsupc   = L_FST_SUPC(k);\n      istart  = L_SUB_START(fsupc);\n      nsupr   = L_SUB_START(fsupc+1) - istart;\n      upper   = 1;\n\n      /* for each column in the supernode */\n      for (int j = fsupc; j < L_FST_SUPC(k+1); ++j)\n      {\n        SNptr = &((Scalar*)Lstore->nzval)[L_NZ_START(j)];\n\n        /* Extract U */\n        for (int i = U_NZ_START(j); i < U_NZ_START(j+1); ++i)\n        {\n          Uval[lastu] = ((Scalar*)Ustore->nzval)[i];\n          /* Matlab doesn't like explicit zero. */\n          if (Uval[lastu] != 0.0)\n            Urow[lastu++] = U_SUB(i);\n        }\n        for (int i = 0; i < upper; ++i)\n        {\n          /* upper triangle in the supernode */\n          Uval[lastu] = SNptr[i];\n          /* Matlab doesn't like explicit zero. */\n          if (Uval[lastu] != 0.0)\n            Urow[lastu++] = L_SUB(istart+i);\n        }\n        Ucol[j+1] = lastu;\n\n        /* Extract L */\n        Lval[lastl] = 1.0; /* unit diagonal */\n        Lrow[lastl++] = L_SUB(istart + upper - 1);\n        for (int i = upper; i < nsupr; ++i)\n        {\n          Lval[lastl] = SNptr[i];\n          /* Matlab doesn't like explicit zero. */\n          if (Lval[lastl] != 0.0)\n            Lrow[lastl++] = L_SUB(istart+i);\n        }\n        Lcol[j+1] = lastl;\n\n        ++upper;\n      } /* for j ... */\n\n    } /* for k ... */\n\n    // squeeze the matrices :\n    m_l.resizeNonZeros(lastl);\n    m_u.resizeNonZeros(lastu);\n\n    m_extractedDataAreDirty = false;\n  }\n}\n\ntemplate<typename MatrixType>\ntypename SuperLU<MatrixType>::Scalar SuperLU<MatrixType>::determinant() const\n{\n  eigen_assert(m_factorizationIsOk && \"The decomposition is not in a valid state for computing the determinant, you must first call either compute() or analyzePattern()/factorize()\");\n  \n  if (m_extractedDataAreDirty)\n    this->extractData();\n\n  Scalar det = Scalar(1);\n  for (int j=0; j<m_u.cols(); ++j)\n  {\n    if (m_u.outerIndexPtr()[j+1]-m_u.outerIndexPtr()[j] > 0)\n    {\n      int lastId = m_u.outerIndexPtr()[j+1]-1;\n      eigen_assert(m_u.innerIndexPtr()[lastId]<=j);\n      if (m_u.innerIndexPtr()[lastId]==j)\n        det *= m_u.valuePtr()[lastId];\n    }\n  }\n  if(PermutationMap(m_p.data(),m_p.size()).determinant()*PermutationMap(m_q.data(),m_q.size()).determinant()<0)\n    det = -det;\n  if(m_sluEqued!='N')\n    return det/m_sluRscale.prod()/m_sluCscale.prod();\n  else\n    return det;\n}\n\n#ifdef EIGEN_PARSED_BY_DOXYGEN\n#define EIGEN_SUPERLU_HAS_ILU\n#endif\n\n#ifdef EIGEN_SUPERLU_HAS_ILU\n\n/** \\ingroup SuperLUSupport_Module\n  * \\class SuperILU\n  * \\brief A sparse direct \\b incomplete LU factorization and solver based on the SuperLU library\n  *\n  * This class allows to solve for an approximate solution of A.X = B sparse linear problems via an incomplete LU factorization\n  * using the SuperLU library. This class is aimed to be used as a preconditioner of the iterative linear solvers.\n  *\n  * \\warning This class is only for the 4.x versions of SuperLU. The 3.x and 5.x versions are not supported.\n  *\n  * \\tparam MatrixType_ the type of the sparse matrix A, it must be a SparseMatrix<>\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class IncompleteLUT, class ConjugateGradient, class BiCGSTAB\n  */\n\ntemplate<typename MatrixType_>\nclass SuperILU : public SuperLUBase<MatrixType_,SuperILU<MatrixType_> >\n{\n  public:\n    typedef SuperLUBase<MatrixType_,SuperILU> Base;\n    typedef MatrixType_ MatrixType;\n    typedef typename Base::Scalar Scalar;\n    typedef typename Base::RealScalar RealScalar;\n\n  public:\n    using Base::_solve_impl;\n\n    SuperILU() : Base() { init(); }\n\n    SuperILU(const MatrixType& matrix) : Base()\n    {\n      init();\n      Base::compute(matrix);\n    }\n\n    ~SuperILU()\n    {\n    }\n    \n    /** Performs a symbolic decomposition on the sparcity of \\a matrix.\n      *\n      * This function is particularly useful when solving for several problems having the same structure.\n      * \n      * \\sa factorize()\n      */\n    void analyzePattern(const MatrixType& matrix)\n    {\n      Base::analyzePattern(matrix);\n    }\n    \n    /** Performs a numeric decomposition of \\a matrix\n      *\n      * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed.\n      *\n      * \\sa analyzePattern()\n      */\n    void factorize(const MatrixType& matrix);\n    \n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    /** \\internal */\n    template<typename Rhs,typename Dest>\n    void _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const;\n    #endif // EIGEN_PARSED_BY_DOXYGEN\n    \n  protected:\n    \n    using Base::m_matrix;\n    using Base::m_sluOptions;\n    using Base::m_sluA;\n    using Base::m_sluB;\n    using Base::m_sluX;\n    using Base::m_p;\n    using Base::m_q;\n    using Base::m_sluEtree;\n    using Base::m_sluEqued;\n    using Base::m_sluRscale;\n    using Base::m_sluCscale;\n    using Base::m_sluL;\n    using Base::m_sluU;\n    using Base::m_sluStat;\n    using Base::m_sluFerr;\n    using Base::m_sluBerr;\n    using Base::m_l;\n    using Base::m_u;\n    \n    using Base::m_analysisIsOk;\n    using Base::m_factorizationIsOk;\n    using Base::m_extractedDataAreDirty;\n    using Base::m_isInitialized;\n    using Base::m_info;\n\n    void init()\n    {\n      Base::init();\n      \n      ilu_set_default_options(&m_sluOptions);\n      m_sluOptions.PrintStat        = NO;\n      m_sluOptions.ConditionNumber  = NO;\n      m_sluOptions.Trans            = NOTRANS;\n      m_sluOptions.ColPerm          = MMD_AT_PLUS_A;\n      \n      // no attempt to preserve column sum\n      m_sluOptions.ILU_MILU = SILU;\n      // only basic ILU(k) support -- no direct control over memory consumption\n      // better to use ILU_DropRule = DROP_BASIC | DROP_AREA\n      // and set ILU_FillFactor to max memory growth\n      m_sluOptions.ILU_DropRule = DROP_BASIC;\n      m_sluOptions.ILU_DropTol = NumTraits<Scalar>::dummy_precision()*10;\n    }\n    \n  private:\n    SuperILU(SuperILU& ) { }\n};\n\ntemplate<typename MatrixType>\nvoid SuperILU<MatrixType>::factorize(const MatrixType& a)\n{\n  eigen_assert(m_analysisIsOk && \"You must first call analyzePattern()\");\n  if(!m_analysisIsOk)\n  {\n    m_info = InvalidInput;\n    return;\n  }\n  \n  this->initFactorization(a);\n\n  int info = 0;\n  RealScalar recip_pivot_growth, rcond;\n\n  StatInit(&m_sluStat);\n  SuperLU_gsisx(&m_sluOptions, &m_sluA, m_q.data(), m_p.data(), &m_sluEtree[0],\n                &m_sluEqued, &m_sluRscale[0], &m_sluCscale[0],\n                &m_sluL, &m_sluU,\n                NULL, 0,\n                &m_sluB, &m_sluX,\n                &recip_pivot_growth, &rcond,\n                &m_sluStat, &info, Scalar());\n  StatFree(&m_sluStat);\n\n  // FIXME how to better check for errors ???\n  m_info = info == 0 ? Success : NumericalIssue;\n  m_factorizationIsOk = true;\n}\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename MatrixType>\ntemplate<typename Rhs,typename Dest>\nvoid SuperILU<MatrixType>::_solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest>& x) const\n{\n  eigen_assert(m_factorizationIsOk && \"The decomposition is not in a valid state for solving, you must first call either compute() or analyzePattern()/factorize()\");\n\n  const int rhsCols = b.cols();\n  eigen_assert(m_matrix.rows()==b.rows());\n\n  m_sluOptions.Trans = NOTRANS;\n  m_sluOptions.Fact = FACTORED;\n  m_sluOptions.IterRefine = NOREFINE;\n\n  m_sluFerr.resize(rhsCols);\n  m_sluBerr.resize(rhsCols);\n  \n  Ref<const Matrix<typename Rhs::Scalar,Dynamic,Dynamic,ColMajor> > b_ref(b);\n  Ref<const Matrix<typename Dest::Scalar,Dynamic,Dynamic,ColMajor> > x_ref(x);\n  \n  m_sluB = SluMatrix::Map(b_ref.const_cast_derived());\n  m_sluX = SluMatrix::Map(x_ref.const_cast_derived());\n\n  typename Rhs::PlainObject b_cpy;\n  if(m_sluEqued!='N')\n  {\n    b_cpy = b;\n    m_sluB = SluMatrix::Map(b_cpy.const_cast_derived());  \n  }\n  \n  int info = 0;\n  RealScalar recip_pivot_growth, rcond;\n\n  StatInit(&m_sluStat);\n  SuperLU_gsisx(&m_sluOptions, &m_sluA,\n                m_q.data(), m_p.data(),\n                &m_sluEtree[0], &m_sluEqued,\n                &m_sluRscale[0], &m_sluCscale[0],\n                &m_sluL, &m_sluU,\n                NULL, 0,\n                &m_sluB, &m_sluX,\n                &recip_pivot_growth, &rcond,\n                &m_sluStat, &info, Scalar());\n  StatFree(&m_sluStat);\n  \n  if(x.derived().data() != x_ref.data())\n    x = x_ref;\n\n  m_info = info==0 ? Success : NumericalIssue;\n}\n#endif\n\n#endif\n\n} // end namespace Eigen\n\n#endif // EIGEN_SUPERLUSUPPORT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/UmfPackSupport/UmfPackSupport.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_UMFPACKSUPPORT_H\n#define EIGEN_UMFPACKSUPPORT_H\n\n// for compatibility with super old version of umfpack,\n// not sure this is really needed, but this is harmless.\n#ifndef SuiteSparse_long\n#ifdef UF_long\n#define SuiteSparse_long UF_long\n#else\n#error neither SuiteSparse_long nor UF_long are defined\n#endif\n#endif\n\nnamespace Eigen {\n\n/* TODO extract L, extract U, compute det, etc... */\n\n// generic double/complex<double> wrapper functions:\n\n\n // Defaults\ninline void umfpack_defaults(double control[UMFPACK_CONTROL], double, int)\n{ umfpack_di_defaults(control); }\n\ninline void umfpack_defaults(double control[UMFPACK_CONTROL], std::complex<double>, int)\n{ umfpack_zi_defaults(control); }\n\ninline void umfpack_defaults(double control[UMFPACK_CONTROL], double, SuiteSparse_long)\n{ umfpack_dl_defaults(control); }\n\ninline void umfpack_defaults(double control[UMFPACK_CONTROL], std::complex<double>, SuiteSparse_long)\n{ umfpack_zl_defaults(control); }\n\n// Report info\ninline void umfpack_report_info(double control[UMFPACK_CONTROL], double info[UMFPACK_INFO], double, int)\n{ umfpack_di_report_info(control, info);}\n\ninline void umfpack_report_info(double control[UMFPACK_CONTROL], double info[UMFPACK_INFO], std::complex<double>, int)\n{ umfpack_zi_report_info(control, info);}\n\ninline void umfpack_report_info(double control[UMFPACK_CONTROL], double info[UMFPACK_INFO], double, SuiteSparse_long)\n{ umfpack_dl_report_info(control, info);}\n\ninline void umfpack_report_info(double control[UMFPACK_CONTROL], double info[UMFPACK_INFO], std::complex<double>, SuiteSparse_long)\n{ umfpack_zl_report_info(control, info);}\n\n// Report status\ninline void umfpack_report_status(double control[UMFPACK_CONTROL], int status, double, int)\n{ umfpack_di_report_status(control, status);}\n\ninline void umfpack_report_status(double control[UMFPACK_CONTROL], int status, std::complex<double>, int)\n{ umfpack_zi_report_status(control, status);}\n\ninline void umfpack_report_status(double control[UMFPACK_CONTROL], int status, double, SuiteSparse_long)\n{ umfpack_dl_report_status(control, status);}\n\ninline void umfpack_report_status(double control[UMFPACK_CONTROL], int status, std::complex<double>, SuiteSparse_long)\n{ umfpack_zl_report_status(control, status);}\n\n// report control\ninline void umfpack_report_control(double control[UMFPACK_CONTROL], double, int)\n{ umfpack_di_report_control(control);}\n\ninline void umfpack_report_control(double control[UMFPACK_CONTROL], std::complex<double>, int)\n{ umfpack_zi_report_control(control);}\n\ninline void umfpack_report_control(double control[UMFPACK_CONTROL], double, SuiteSparse_long)\n{ umfpack_dl_report_control(control);}\n\ninline void umfpack_report_control(double control[UMFPACK_CONTROL], std::complex<double>, SuiteSparse_long)\n{ umfpack_zl_report_control(control);}\n\n// Free numeric\ninline void umfpack_free_numeric(void **Numeric, double, int)\n{ umfpack_di_free_numeric(Numeric); *Numeric = 0; }\n\ninline void umfpack_free_numeric(void **Numeric, std::complex<double>, int)\n{ umfpack_zi_free_numeric(Numeric); *Numeric = 0; }\n\ninline void umfpack_free_numeric(void **Numeric, double, SuiteSparse_long)\n{ umfpack_dl_free_numeric(Numeric); *Numeric = 0; }\n\ninline void umfpack_free_numeric(void **Numeric, std::complex<double>, SuiteSparse_long)\n{ umfpack_zl_free_numeric(Numeric); *Numeric = 0; }\n\n// Free symbolic\ninline void umfpack_free_symbolic(void **Symbolic, double, int)\n{ umfpack_di_free_symbolic(Symbolic); *Symbolic = 0; }\n\ninline void umfpack_free_symbolic(void **Symbolic, std::complex<double>, int)\n{ umfpack_zi_free_symbolic(Symbolic); *Symbolic = 0; }\n\ninline void umfpack_free_symbolic(void **Symbolic, double, SuiteSparse_long)\n{ umfpack_dl_free_symbolic(Symbolic); *Symbolic = 0; }\n\ninline void umfpack_free_symbolic(void **Symbolic, std::complex<double>, SuiteSparse_long)\n{ umfpack_zl_free_symbolic(Symbolic); *Symbolic = 0; }\n\n// Symbolic\ninline int umfpack_symbolic(int n_row,int n_col,\n                            const int Ap[], const int Ai[], const double Ax[], void **Symbolic,\n                            const double Control [UMFPACK_CONTROL], double Info [UMFPACK_INFO])\n{\n  return umfpack_di_symbolic(n_row,n_col,Ap,Ai,Ax,Symbolic,Control,Info);\n}\n\ninline int umfpack_symbolic(int n_row,int n_col,\n                            const int Ap[], const int Ai[], const std::complex<double> Ax[], void **Symbolic,\n                            const double Control [UMFPACK_CONTROL], double Info [UMFPACK_INFO])\n{\n  return umfpack_zi_symbolic(n_row,n_col,Ap,Ai,&numext::real_ref(Ax[0]),0,Symbolic,Control,Info);\n}\ninline SuiteSparse_long umfpack_symbolic( SuiteSparse_long n_row,SuiteSparse_long n_col,\n                                          const SuiteSparse_long Ap[], const SuiteSparse_long Ai[], const double Ax[], void **Symbolic,\n                                          const double Control [UMFPACK_CONTROL], double Info [UMFPACK_INFO])\n{\n  return umfpack_dl_symbolic(n_row,n_col,Ap,Ai,Ax,Symbolic,Control,Info);\n}\n\ninline SuiteSparse_long umfpack_symbolic( SuiteSparse_long n_row,SuiteSparse_long n_col,\n                                          const SuiteSparse_long Ap[], const SuiteSparse_long Ai[], const std::complex<double> Ax[], void **Symbolic,\n                                          const double Control [UMFPACK_CONTROL], double Info [UMFPACK_INFO])\n{\n  return umfpack_zl_symbolic(n_row,n_col,Ap,Ai,&numext::real_ref(Ax[0]),0,Symbolic,Control,Info);\n}\n\n// Numeric\ninline int umfpack_numeric( const int Ap[], const int Ai[], const double Ax[],\n                            void *Symbolic, void **Numeric,\n                            const double Control[UMFPACK_CONTROL],double Info [UMFPACK_INFO])\n{\n  return umfpack_di_numeric(Ap,Ai,Ax,Symbolic,Numeric,Control,Info);\n}\n\ninline int umfpack_numeric( const int Ap[], const int Ai[], const std::complex<double> Ax[],\n                            void *Symbolic, void **Numeric,\n                            const double Control[UMFPACK_CONTROL],double Info [UMFPACK_INFO])\n{\n  return umfpack_zi_numeric(Ap,Ai,&numext::real_ref(Ax[0]),0,Symbolic,Numeric,Control,Info);\n}\ninline SuiteSparse_long umfpack_numeric(const SuiteSparse_long Ap[], const SuiteSparse_long Ai[], const double Ax[],\n                                        void *Symbolic, void **Numeric,\n                                        const double Control[UMFPACK_CONTROL],double Info [UMFPACK_INFO])\n{\n  return umfpack_dl_numeric(Ap,Ai,Ax,Symbolic,Numeric,Control,Info);\n}\n\ninline SuiteSparse_long umfpack_numeric(const SuiteSparse_long Ap[], const SuiteSparse_long Ai[], const std::complex<double> Ax[],\n                                        void *Symbolic, void **Numeric,\n                                        const double Control[UMFPACK_CONTROL],double Info [UMFPACK_INFO])\n{\n  return umfpack_zl_numeric(Ap,Ai,&numext::real_ref(Ax[0]),0,Symbolic,Numeric,Control,Info);\n}\n\n// solve\ninline int umfpack_solve( int sys, const int Ap[], const int Ai[], const double Ax[],\n                          double X[], const double B[], void *Numeric,\n                          const double Control[UMFPACK_CONTROL], double Info[UMFPACK_INFO])\n{\n  return umfpack_di_solve(sys,Ap,Ai,Ax,X,B,Numeric,Control,Info);\n}\n\ninline int umfpack_solve( int sys, const int Ap[], const int Ai[], const std::complex<double> Ax[],\n                          std::complex<double> X[], const std::complex<double> B[], void *Numeric,\n                          const double Control[UMFPACK_CONTROL], double Info[UMFPACK_INFO])\n{\n  return umfpack_zi_solve(sys,Ap,Ai,&numext::real_ref(Ax[0]),0,&numext::real_ref(X[0]),0,&numext::real_ref(B[0]),0,Numeric,Control,Info);\n}\n\ninline SuiteSparse_long umfpack_solve(int sys, const SuiteSparse_long Ap[], const SuiteSparse_long Ai[], const double Ax[],\n                                      double X[], const double B[], void *Numeric,\n                                      const double Control[UMFPACK_CONTROL], double Info[UMFPACK_INFO])\n{\n  return umfpack_dl_solve(sys,Ap,Ai,Ax,X,B,Numeric,Control,Info);\n}\n\ninline SuiteSparse_long umfpack_solve(int sys, const SuiteSparse_long Ap[], const SuiteSparse_long Ai[], const std::complex<double> Ax[],\n                                      std::complex<double> X[], const std::complex<double> B[], void *Numeric,\n                                      const double Control[UMFPACK_CONTROL], double Info[UMFPACK_INFO])\n{\n  return umfpack_zl_solve(sys,Ap,Ai,&numext::real_ref(Ax[0]),0,&numext::real_ref(X[0]),0,&numext::real_ref(B[0]),0,Numeric,Control,Info);\n}\n\n// Get Lunz\ninline int umfpack_get_lunz(int *lnz, int *unz, int *n_row, int *n_col, int *nz_udiag, void *Numeric, double)\n{\n  return umfpack_di_get_lunz(lnz,unz,n_row,n_col,nz_udiag,Numeric);\n}\n\ninline int umfpack_get_lunz(int *lnz, int *unz, int *n_row, int *n_col, int *nz_udiag, void *Numeric, std::complex<double>)\n{\n  return umfpack_zi_get_lunz(lnz,unz,n_row,n_col,nz_udiag,Numeric);\n}\n\ninline SuiteSparse_long umfpack_get_lunz( SuiteSparse_long *lnz, SuiteSparse_long *unz, SuiteSparse_long *n_row, SuiteSparse_long *n_col,\n                                          SuiteSparse_long *nz_udiag, void *Numeric, double)\n{\n  return umfpack_dl_get_lunz(lnz,unz,n_row,n_col,nz_udiag,Numeric);\n}\n\ninline SuiteSparse_long umfpack_get_lunz( SuiteSparse_long *lnz, SuiteSparse_long *unz, SuiteSparse_long *n_row, SuiteSparse_long *n_col,\n                                          SuiteSparse_long *nz_udiag, void *Numeric, std::complex<double>)\n{\n  return umfpack_zl_get_lunz(lnz,unz,n_row,n_col,nz_udiag,Numeric);\n}\n\n// Get Numeric\ninline int umfpack_get_numeric(int Lp[], int Lj[], double Lx[], int Up[], int Ui[], double Ux[],\n                               int P[], int Q[], double Dx[], int *do_recip, double Rs[], void *Numeric)\n{\n  return umfpack_di_get_numeric(Lp,Lj,Lx,Up,Ui,Ux,P,Q,Dx,do_recip,Rs,Numeric);\n}\n\ninline int umfpack_get_numeric(int Lp[], int Lj[], std::complex<double> Lx[], int Up[], int Ui[], std::complex<double> Ux[],\n                               int P[], int Q[], std::complex<double> Dx[], int *do_recip, double Rs[], void *Numeric)\n{\n  double& lx0_real = numext::real_ref(Lx[0]);\n  double& ux0_real = numext::real_ref(Ux[0]);\n  double& dx0_real = numext::real_ref(Dx[0]);\n  return umfpack_zi_get_numeric(Lp,Lj,Lx?&lx0_real:0,0,Up,Ui,Ux?&ux0_real:0,0,P,Q,\n                                Dx?&dx0_real:0,0,do_recip,Rs,Numeric);\n}\ninline SuiteSparse_long umfpack_get_numeric(SuiteSparse_long Lp[], SuiteSparse_long Lj[], double Lx[], SuiteSparse_long Up[], SuiteSparse_long Ui[], double Ux[],\n                                            SuiteSparse_long P[], SuiteSparse_long Q[], double Dx[], SuiteSparse_long *do_recip, double Rs[], void *Numeric)\n{\n  return umfpack_dl_get_numeric(Lp,Lj,Lx,Up,Ui,Ux,P,Q,Dx,do_recip,Rs,Numeric);\n}\n\ninline SuiteSparse_long umfpack_get_numeric(SuiteSparse_long Lp[], SuiteSparse_long Lj[], std::complex<double> Lx[], SuiteSparse_long Up[], SuiteSparse_long Ui[], std::complex<double> Ux[],\n                                            SuiteSparse_long P[], SuiteSparse_long Q[], std::complex<double> Dx[], SuiteSparse_long *do_recip, double Rs[], void *Numeric)\n{\n  double& lx0_real = numext::real_ref(Lx[0]);\n  double& ux0_real = numext::real_ref(Ux[0]);\n  double& dx0_real = numext::real_ref(Dx[0]);\n  return umfpack_zl_get_numeric(Lp,Lj,Lx?&lx0_real:0,0,Up,Ui,Ux?&ux0_real:0,0,P,Q,\n                                Dx?&dx0_real:0,0,do_recip,Rs,Numeric);\n}\n\n// Get Determinant\ninline int umfpack_get_determinant(double *Mx, double *Ex, void *NumericHandle, double User_Info [UMFPACK_INFO], int)\n{\n  return umfpack_di_get_determinant(Mx,Ex,NumericHandle,User_Info);\n}\n\ninline int umfpack_get_determinant(std::complex<double> *Mx, double *Ex, void *NumericHandle, double User_Info [UMFPACK_INFO], int)\n{\n  double& mx_real = numext::real_ref(*Mx);\n  return umfpack_zi_get_determinant(&mx_real,0,Ex,NumericHandle,User_Info);\n}\n\ninline SuiteSparse_long umfpack_get_determinant(double *Mx, double *Ex, void *NumericHandle, double User_Info [UMFPACK_INFO], SuiteSparse_long)\n{\n  return umfpack_dl_get_determinant(Mx,Ex,NumericHandle,User_Info);\n}\n\ninline SuiteSparse_long umfpack_get_determinant(std::complex<double> *Mx, double *Ex, void *NumericHandle, double User_Info [UMFPACK_INFO], SuiteSparse_long)\n{\n  double& mx_real = numext::real_ref(*Mx);\n  return umfpack_zl_get_determinant(&mx_real,0,Ex,NumericHandle,User_Info);\n}\n\n\n/** \\ingroup UmfPackSupport_Module\n  * \\brief A sparse LU factorization and solver based on UmfPack\n  *\n  * This class allows to solve for A.X = B sparse linear problems via a LU factorization\n  * using the UmfPack library. The sparse matrix A must be squared and full rank.\n  * The vectors or matrices X and B can be either dense or sparse.\n  *\n  * \\warning The input matrix A should be in a \\b compressed and \\b column-major form.\n  * Otherwise an expensive copy will be made. You can call the inexpensive makeCompressed() to get a compressed matrix.\n  * \\tparam MatrixType_ the type of the sparse matrix A, it must be a SparseMatrix<>\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class SparseLU\n  */\ntemplate<typename MatrixType_>\nclass UmfPackLU : public SparseSolverBase<UmfPackLU<MatrixType_> >\n{\n  protected:\n    typedef SparseSolverBase<UmfPackLU<MatrixType_> > Base;\n    using Base::m_isInitialized;\n  public:\n    using Base::_solve_impl;\n    typedef MatrixType_ MatrixType;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef Matrix<Scalar,Dynamic,1> Vector;\n    typedef Matrix<int, 1, MatrixType::ColsAtCompileTime> IntRowVectorType;\n    typedef Matrix<int, MatrixType::RowsAtCompileTime, 1> IntColVectorType;\n    typedef SparseMatrix<Scalar> LUMatrixType;\n    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> UmfpackMatrixType;\n    typedef Ref<const UmfpackMatrixType, StandardCompressedFormat> UmfpackMatrixRef;\n    enum {\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n\n  public:\n\n    typedef Array<double, UMFPACK_CONTROL, 1> UmfpackControl;\n    typedef Array<double, UMFPACK_INFO, 1> UmfpackInfo;\n\n    UmfPackLU()\n      : m_dummy(0,0), mp_matrix(m_dummy)\n    {\n      init();\n    }\n\n    template<typename InputMatrixType>\n    explicit UmfPackLU(const InputMatrixType& matrix)\n      : mp_matrix(matrix)\n    {\n      init();\n      compute(matrix);\n    }\n\n    ~UmfPackLU()\n    {\n      if(m_symbolic) umfpack_free_symbolic(&m_symbolic,Scalar(), StorageIndex());\n      if(m_numeric)  umfpack_free_numeric(&m_numeric,Scalar(), StorageIndex());\n    }\n\n    inline Index rows() const { return mp_matrix.rows(); }\n    inline Index cols() const { return mp_matrix.cols(); }\n\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the matrix.appears to be negative.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_info;\n    }\n\n    inline const LUMatrixType& matrixL() const\n    {\n      if (m_extractedDataAreDirty) extractData();\n      return m_l;\n    }\n\n    inline const LUMatrixType& matrixU() const\n    {\n      if (m_extractedDataAreDirty) extractData();\n      return m_u;\n    }\n\n    inline const IntColVectorType& permutationP() const\n    {\n      if (m_extractedDataAreDirty) extractData();\n      return m_p;\n    }\n\n    inline const IntRowVectorType& permutationQ() const\n    {\n      if (m_extractedDataAreDirty) extractData();\n      return m_q;\n    }\n\n    /** Computes the sparse Cholesky decomposition of \\a matrix\n     *  Note that the matrix should be column-major, and in compressed format for best performance.\n     *  \\sa SparseMatrix::makeCompressed().\n     */\n    template<typename InputMatrixType>\n    void compute(const InputMatrixType& matrix)\n    {\n      if(m_symbolic) umfpack_free_symbolic(&m_symbolic,Scalar(),StorageIndex());\n      if(m_numeric)  umfpack_free_numeric(&m_numeric,Scalar(),StorageIndex());\n      grab(matrix.derived());\n      analyzePattern_impl();\n      factorize_impl();\n    }\n\n    /** Performs a symbolic decomposition on the sparcity of \\a matrix.\n      *\n      * This function is particularly useful when solving for several problems having the same structure.\n      *\n      * \\sa factorize(), compute()\n      */\n    template<typename InputMatrixType>\n    void analyzePattern(const InputMatrixType& matrix)\n    {\n      if(m_symbolic) umfpack_free_symbolic(&m_symbolic,Scalar(),StorageIndex());\n      if(m_numeric)  umfpack_free_numeric(&m_numeric,Scalar(),StorageIndex());\n\n      grab(matrix.derived());\n\n      analyzePattern_impl();\n    }\n\n    /** Provides the return status code returned by UmfPack during the numeric\n      * factorization.\n      *\n      * \\sa factorize(), compute()\n      */\n    inline int umfpackFactorizeReturncode() const\n    {\n      eigen_assert(m_numeric && \"UmfPackLU: you must first call factorize()\");\n      return m_fact_errorCode;\n    }\n\n    /** Provides access to the control settings array used by UmfPack.\n      *\n      * If this array contains NaN's, the default values are used.\n      *\n      * See UMFPACK documentation for details.\n      */\n    inline const UmfpackControl& umfpackControl() const\n    {\n      return m_control;\n    }\n\n    /** Provides access to the control settings array used by UmfPack.\n      *\n      * If this array contains NaN's, the default values are used.\n      *\n      * See UMFPACK documentation for details.\n      */\n    inline UmfpackControl& umfpackControl()\n    {\n      return m_control;\n    }\n\n    /** Performs a numeric decomposition of \\a matrix\n      *\n      * The given matrix must has the same sparcity than the matrix on which the pattern anylysis has been performed.\n      *\n      * \\sa analyzePattern(), compute()\n      */\n    template<typename InputMatrixType>\n    void factorize(const InputMatrixType& matrix)\n    {\n      eigen_assert(m_analysisIsOk && \"UmfPackLU: you must first call analyzePattern()\");\n      if(m_numeric)\n        umfpack_free_numeric(&m_numeric,Scalar(),StorageIndex());\n\n      grab(matrix.derived());\n\n      factorize_impl();\n    }\n\n    /** Prints the current UmfPack control settings.\n      *\n      * \\sa umfpackControl()\n      */\n    void printUmfpackControl()\n    {\n      umfpack_report_control(m_control.data(), Scalar(),StorageIndex());\n    }\n\n    /** Prints statistics collected by UmfPack.\n      *\n      * \\sa analyzePattern(), compute()\n      */\n    void printUmfpackInfo()\n    {\n      eigen_assert(m_analysisIsOk && \"UmfPackLU: you must first call analyzePattern()\");\n      umfpack_report_info(m_control.data(), m_umfpackInfo.data(), Scalar(),StorageIndex());\n    }\n\n    /** Prints the status of the previous factorization operation performed by UmfPack (symbolic or numerical factorization).\n      *\n      * \\sa analyzePattern(), compute()\n      */\n    void printUmfpackStatus() {\n      eigen_assert(m_analysisIsOk && \"UmfPackLU: you must first call analyzePattern()\");\n      umfpack_report_status(m_control.data(), m_fact_errorCode, Scalar(),StorageIndex());\n    }\n\n    /** \\internal */\n    template<typename BDerived,typename XDerived>\n    bool _solve_impl(const MatrixBase<BDerived> &b, MatrixBase<XDerived> &x) const;\n\n    Scalar determinant() const;\n\n    void extractData() const;\n\n  protected:\n\n    void init()\n    {\n      m_info                  = InvalidInput;\n      m_isInitialized         = false;\n      m_numeric               = 0;\n      m_symbolic              = 0;\n      m_extractedDataAreDirty = true;\n\n      umfpack_defaults(m_control.data(), Scalar(),StorageIndex());\n    }\n\n    void analyzePattern_impl()\n    {\n      m_fact_errorCode = umfpack_symbolic(internal::convert_index<StorageIndex>(mp_matrix.rows()),\n                                          internal::convert_index<StorageIndex>(mp_matrix.cols()),\n                                          mp_matrix.outerIndexPtr(), mp_matrix.innerIndexPtr(), mp_matrix.valuePtr(),\n                                          &m_symbolic, m_control.data(), m_umfpackInfo.data());\n\n      m_isInitialized = true;\n      m_info = m_fact_errorCode ? InvalidInput : Success;\n      m_analysisIsOk = true;\n      m_factorizationIsOk = false;\n      m_extractedDataAreDirty = true;\n    }\n\n    void factorize_impl()\n    {\n\n      m_fact_errorCode = umfpack_numeric(mp_matrix.outerIndexPtr(), mp_matrix.innerIndexPtr(), mp_matrix.valuePtr(),\n                                         m_symbolic, &m_numeric, m_control.data(), m_umfpackInfo.data());\n\n      m_info = m_fact_errorCode == UMFPACK_OK ? Success : NumericalIssue;\n      m_factorizationIsOk = true;\n      m_extractedDataAreDirty = true;\n    }\n\n    template<typename MatrixDerived>\n    void grab(const EigenBase<MatrixDerived> &A)\n    {\n      mp_matrix.~UmfpackMatrixRef();\n      ::new (&mp_matrix) UmfpackMatrixRef(A.derived());\n    }\n\n    void grab(const UmfpackMatrixRef &A)\n    {\n      if(&(A.derived()) != &mp_matrix)\n      {\n        mp_matrix.~UmfpackMatrixRef();\n        ::new (&mp_matrix) UmfpackMatrixRef(A);\n      }\n    }\n\n    // cached data to reduce reallocation, etc.\n    mutable LUMatrixType m_l;\n    StorageIndex m_fact_errorCode;\n    UmfpackControl m_control;\n    mutable UmfpackInfo m_umfpackInfo;\n\n    mutable LUMatrixType m_u;\n    mutable IntColVectorType m_p;\n    mutable IntRowVectorType m_q;\n\n    UmfpackMatrixType m_dummy;\n    UmfpackMatrixRef mp_matrix;\n\n    void* m_numeric;\n    void* m_symbolic;\n\n    mutable ComputationInfo m_info;\n    int m_factorizationIsOk;\n    int m_analysisIsOk;\n    mutable bool m_extractedDataAreDirty;\n\n  private:\n    UmfPackLU(const UmfPackLU& ) { }\n};\n\n\ntemplate<typename MatrixType>\nvoid UmfPackLU<MatrixType>::extractData() const\n{\n  if (m_extractedDataAreDirty)\n  {\n    // get size of the data\n    StorageIndex lnz, unz, rows, cols, nz_udiag;\n    umfpack_get_lunz(&lnz, &unz, &rows, &cols, &nz_udiag, m_numeric, Scalar());\n\n    // allocate data\n    m_l.resize(rows,(std::min)(rows,cols));\n    m_l.resizeNonZeros(lnz);\n\n    m_u.resize((std::min)(rows,cols),cols);\n    m_u.resizeNonZeros(unz);\n\n    m_p.resize(rows);\n    m_q.resize(cols);\n\n    // extract\n    umfpack_get_numeric(m_l.outerIndexPtr(), m_l.innerIndexPtr(), m_l.valuePtr(),\n                        m_u.outerIndexPtr(), m_u.innerIndexPtr(), m_u.valuePtr(),\n                        m_p.data(), m_q.data(), 0, 0, 0, m_numeric);\n\n    m_extractedDataAreDirty = false;\n  }\n}\n\ntemplate<typename MatrixType>\ntypename UmfPackLU<MatrixType>::Scalar UmfPackLU<MatrixType>::determinant() const\n{\n  Scalar det;\n  umfpack_get_determinant(&det, 0, m_numeric, 0, StorageIndex());\n  return det;\n}\n\ntemplate<typename MatrixType>\ntemplate<typename BDerived,typename XDerived>\nbool UmfPackLU<MatrixType>::_solve_impl(const MatrixBase<BDerived> &b, MatrixBase<XDerived> &x) const\n{\n  Index rhsCols = b.cols();\n  eigen_assert((BDerived::Flags&RowMajorBit)==0 && \"UmfPackLU backend does not support non col-major rhs yet\");\n  eigen_assert((XDerived::Flags&RowMajorBit)==0 && \"UmfPackLU backend does not support non col-major result yet\");\n  eigen_assert(b.derived().data() != x.derived().data() && \" Umfpack does not support inplace solve\");\n\n  Scalar* x_ptr = 0;\n  Matrix<Scalar,Dynamic,1> x_tmp;\n  if(x.innerStride()!=1)\n  {\n    x_tmp.resize(x.rows());\n    x_ptr = x_tmp.data();\n  }\n  for (int j=0; j<rhsCols; ++j)\n  {\n    if(x.innerStride()==1)\n      x_ptr = &x.col(j).coeffRef(0);\n    StorageIndex errorCode = umfpack_solve(UMFPACK_A,\n                                mp_matrix.outerIndexPtr(), mp_matrix.innerIndexPtr(), mp_matrix.valuePtr(),\n                                x_ptr, &b.const_cast_derived().col(j).coeffRef(0),\n                                m_numeric, m_control.data(), m_umfpackInfo.data());\n    if(x.innerStride()!=1)\n      x.col(j) = x_tmp;\n    if (errorCode!=0)\n      return false;\n  }\n\n  return true;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_UMFPACKSUPPORT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/misc/Image.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MISC_IMAGE_H\n#define EIGEN_MISC_IMAGE_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\class image_retval_base\n  *\n  */\ntemplate<typename DecompositionType>\nstruct traits<image_retval_base<DecompositionType> >\n{\n  typedef typename DecompositionType::MatrixType MatrixType;\n  typedef Matrix<\n    typename MatrixType::Scalar,\n    MatrixType::RowsAtCompileTime, // the image is a subspace of the destination space, whose\n                                   // dimension is the number of rows of the original matrix\n    Dynamic,                       // we don't know at compile time the dimension of the image (the rank)\n    MatrixType::Options,\n    MatrixType::MaxRowsAtCompileTime, // the image matrix will consist of columns from the original matrix,\n    MatrixType::MaxColsAtCompileTime  // so it has the same number of rows and at most as many columns.\n  > ReturnType;\n};\n\ntemplate<typename DecompositionType_> struct image_retval_base\n : public ReturnByValue<image_retval_base<DecompositionType_> >\n{\n  typedef DecompositionType_ DecompositionType;\n  typedef typename DecompositionType::MatrixType MatrixType;\n  typedef ReturnByValue<image_retval_base> Base;\n\n  image_retval_base(const DecompositionType& dec, const MatrixType& originalMatrix)\n    : m_dec(dec), m_rank(dec.rank()),\n      m_cols(m_rank == 0 ? 1 : m_rank),\n      m_originalMatrix(originalMatrix)\n  {}\n\n  inline Index rows() const { return m_dec.rows(); }\n  inline Index cols() const { return m_cols; }\n  inline Index rank() const { return m_rank; }\n  inline const DecompositionType& dec() const { return m_dec; }\n  inline const MatrixType& originalMatrix() const { return m_originalMatrix; }\n\n  template<typename Dest> inline void evalTo(Dest& dst) const\n  {\n    static_cast<const image_retval<DecompositionType>*>(this)->evalTo(dst);\n  }\n\n  protected:\n    const DecompositionType& m_dec;\n    Index m_rank, m_cols;\n    const MatrixType& m_originalMatrix;\n};\n\n} // end namespace internal\n\n#define EIGEN_MAKE_IMAGE_HELPERS(DecompositionType) \\\n  typedef typename DecompositionType::MatrixType MatrixType; \\\n  typedef typename MatrixType::Scalar Scalar; \\\n  typedef typename MatrixType::RealScalar RealScalar; \\\n  typedef Eigen::internal::image_retval_base<DecompositionType> Base; \\\n  using Base::dec; \\\n  using Base::originalMatrix; \\\n  using Base::rank; \\\n  using Base::rows; \\\n  using Base::cols; \\\n  image_retval(const DecompositionType& dec, const MatrixType& originalMatrix) \\\n    : Base(dec, originalMatrix) {}\n\n} // end namespace Eigen\n\n#endif // EIGEN_MISC_IMAGE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/misc/Kernel.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MISC_KERNEL_H\n#define EIGEN_MISC_KERNEL_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\class kernel_retval_base\n  *\n  */\ntemplate<typename DecompositionType>\nstruct traits<kernel_retval_base<DecompositionType> >\n{\n  typedef typename DecompositionType::MatrixType MatrixType;\n  typedef Matrix<\n    typename MatrixType::Scalar,\n    MatrixType::ColsAtCompileTime, // the number of rows in the \"kernel matrix\"\n                                   // is the number of cols of the original matrix\n                                   // so that the product \"matrix * kernel = zero\" makes sense\n    Dynamic,                       // we don't know at compile-time the dimension of the kernel\n    MatrixType::Options,\n    MatrixType::MaxColsAtCompileTime, // see explanation for 2nd template parameter\n    MatrixType::MaxColsAtCompileTime // the kernel is a subspace of the domain space,\n                                     // whose dimension is the number of columns of the original matrix\n  > ReturnType;\n};\n\ntemplate<typename DecompositionType_> struct kernel_retval_base\n : public ReturnByValue<kernel_retval_base<DecompositionType_> >\n{\n  typedef DecompositionType_ DecompositionType;\n  typedef ReturnByValue<kernel_retval_base> Base;\n\n  explicit kernel_retval_base(const DecompositionType& dec)\n    : m_dec(dec),\n      m_rank(dec.rank()),\n      m_cols(m_rank==dec.cols() ? 1 : dec.cols() - m_rank)\n  {}\n\n  inline Index rows() const { return m_dec.cols(); }\n  inline Index cols() const { return m_cols; }\n  inline Index rank() const { return m_rank; }\n  inline const DecompositionType& dec() const { return m_dec; }\n\n  template<typename Dest> inline void evalTo(Dest& dst) const\n  {\n    static_cast<const kernel_retval<DecompositionType>*>(this)->evalTo(dst);\n  }\n\n  protected:\n    const DecompositionType& m_dec;\n    Index m_rank, m_cols;\n};\n\n} // end namespace internal\n\n#define EIGEN_MAKE_KERNEL_HELPERS(DecompositionType) \\\n  typedef typename DecompositionType::MatrixType MatrixType; \\\n  typedef typename MatrixType::Scalar Scalar; \\\n  typedef typename MatrixType::RealScalar RealScalar; \\\n  typedef Eigen::internal::kernel_retval_base<DecompositionType> Base; \\\n  using Base::dec; \\\n  using Base::rank; \\\n  using Base::rows; \\\n  using Base::cols; \\\n  kernel_retval(const DecompositionType& dec) : Base(dec) {}\n\n} // end namespace Eigen\n\n#endif // EIGEN_MISC_KERNEL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/misc/RealSvd2x2.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2013-2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_REALSVD2X2_H\n#define EIGEN_REALSVD2X2_H\n\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate<typename MatrixType, typename RealScalar, typename Index>\nvoid real_2x2_jacobi_svd(const MatrixType& matrix, Index p, Index q,\n                         JacobiRotation<RealScalar> *j_left,\n                         JacobiRotation<RealScalar> *j_right)\n{\n  using std::sqrt;\n  using std::abs;\n  Matrix<RealScalar,2,2> m;\n  m << numext::real(matrix.coeff(p,p)), numext::real(matrix.coeff(p,q)),\n       numext::real(matrix.coeff(q,p)), numext::real(matrix.coeff(q,q));\n  JacobiRotation<RealScalar> rot1;\n  RealScalar t = m.coeff(0,0) + m.coeff(1,1);\n  RealScalar d = m.coeff(1,0) - m.coeff(0,1);\n\n  if(abs(d) < (std::numeric_limits<RealScalar>::min)())\n  {\n    rot1.s() = RealScalar(0);\n    rot1.c() = RealScalar(1);\n  }\n  else\n  {\n    // If d!=0, then t/d cannot overflow because the magnitude of the\n    // entries forming d are not too small compared to the ones forming t.\n    RealScalar u = t / d;\n    RealScalar tmp = sqrt(RealScalar(1) + numext::abs2(u));\n    rot1.s() = RealScalar(1) / tmp;\n    rot1.c() = u / tmp;\n  }\n  m.applyOnTheLeft(0,1,rot1);\n  j_right->makeJacobi(m,0,1);\n  *j_left = rot1 * j_right->transpose();\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_REALSVD2X2_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/misc/blas.h",
    "content": "#ifndef BLAS_H\n#define BLAS_H\n\n#ifdef __cplusplus\nextern \"C\"\n{\n#endif\n\n#define BLASFUNC(FUNC) FUNC##_\n\n#ifdef __WIN64__\ntypedef long long BLASLONG;\ntypedef unsigned long long BLASULONG;\n#else\ntypedef long BLASLONG;\ntypedef unsigned long BLASULONG;\n#endif\n\nint    BLASFUNC(xerbla)(const char *, int *info, int);\n\nfloat  BLASFUNC(sdot)  (int *, float  *, int *, float  *, int *);\nfloat  BLASFUNC(sdsdot)(int *, float  *,        float  *, int *, float  *, int *);\n\ndouble BLASFUNC(dsdot) (int *, float  *, int *, float  *, int *);\ndouble BLASFUNC(ddot)  (int *, double *, int *, double *, int *);\ndouble BLASFUNC(qdot)  (int *, double *, int *, double *, int *);\n\nint  BLASFUNC(cdotuw)  (int *, float  *, int *, float  *, int *, float*);\nint  BLASFUNC(cdotcw)  (int *, float  *, int *, float  *, int *, float*);\nint  BLASFUNC(zdotuw)  (int *, double  *, int *, double  *, int *, double*);\nint  BLASFUNC(zdotcw)  (int *, double  *, int *, double  *, int *, double*);\n\nint    BLASFUNC(saxpy) (const int *, const float  *, const float  *, const int *, float  *, const int *);\nint    BLASFUNC(daxpy) (const int *, const double *, const double *, const int *, double *, const int *);\nint    BLASFUNC(qaxpy) (const int *, const double *, const double *, const int *, double *, const int *);\nint    BLASFUNC(caxpy) (const int *, const float  *, const float  *, const int *, float  *, const int *);\nint    BLASFUNC(zaxpy) (const int *, const double *, const double *, const int *, double *, const int *);\nint    BLASFUNC(xaxpy) (const int *, const double *, const double *, const int *, double *, const int *);\nint    BLASFUNC(caxpyc)(const int *, const float  *, const float  *, const int *, float  *, const int *);\nint    BLASFUNC(zaxpyc)(const int *, const double *, const double *, const int *, double *, const int *);\nint    BLASFUNC(xaxpyc)(const int *, const double *, const double *, const int *, double *, const int *);\n\nint    BLASFUNC(scopy) (int *, float  *, int *, float  *, int *);\nint    BLASFUNC(dcopy) (int *, double *, int *, double *, int *);\nint    BLASFUNC(qcopy) (int *, double *, int *, double *, int *);\nint    BLASFUNC(ccopy) (int *, float  *, int *, float  *, int *);\nint    BLASFUNC(zcopy) (int *, double *, int *, double *, int *);\nint    BLASFUNC(xcopy) (int *, double *, int *, double *, int *);\n\nint    BLASFUNC(sswap) (int *, float  *, int *, float  *, int *);\nint    BLASFUNC(dswap) (int *, double *, int *, double *, int *);\nint    BLASFUNC(qswap) (int *, double *, int *, double *, int *);\nint    BLASFUNC(cswap) (int *, float  *, int *, float  *, int *);\nint    BLASFUNC(zswap) (int *, double *, int *, double *, int *);\nint    BLASFUNC(xswap) (int *, double *, int *, double *, int *);\n\nfloat  BLASFUNC(sasum) (int *, float  *, int *);\nfloat  BLASFUNC(scasum)(int *, float  *, int *);\ndouble BLASFUNC(dasum) (int *, double *, int *);\ndouble BLASFUNC(qasum) (int *, double *, int *);\ndouble BLASFUNC(dzasum)(int *, double *, int *);\ndouble BLASFUNC(qxasum)(int *, double *, int *);\n\nint    BLASFUNC(isamax)(int *, float  *, int *);\nint    BLASFUNC(idamax)(int *, double *, int *);\nint    BLASFUNC(iqamax)(int *, double *, int *);\nint    BLASFUNC(icamax)(int *, float  *, int *);\nint    BLASFUNC(izamax)(int *, double *, int *);\nint    BLASFUNC(ixamax)(int *, double *, int *);\n\nint    BLASFUNC(ismax) (int *, float  *, int *);\nint    BLASFUNC(idmax) (int *, double *, int *);\nint    BLASFUNC(iqmax) (int *, double *, int *);\nint    BLASFUNC(icmax) (int *, float  *, int *);\nint    BLASFUNC(izmax) (int *, double *, int *);\nint    BLASFUNC(ixmax) (int *, double *, int *);\n\nint    BLASFUNC(isamin)(int *, float  *, int *);\nint    BLASFUNC(idamin)(int *, double *, int *);\nint    BLASFUNC(iqamin)(int *, double *, int *);\nint    BLASFUNC(icamin)(int *, float  *, int *);\nint    BLASFUNC(izamin)(int *, double *, int *);\nint    BLASFUNC(ixamin)(int *, double *, int *);\n\nint    BLASFUNC(ismin)(int *, float  *, int *);\nint    BLASFUNC(idmin)(int *, double *, int *);\nint    BLASFUNC(iqmin)(int *, double *, int *);\nint    BLASFUNC(icmin)(int *, float  *, int *);\nint    BLASFUNC(izmin)(int *, double *, int *);\nint    BLASFUNC(ixmin)(int *, double *, int *);\n\nfloat  BLASFUNC(samax) (int *, float  *, int *);\ndouble BLASFUNC(damax) (int *, double *, int *);\ndouble BLASFUNC(qamax) (int *, double *, int *);\nfloat  BLASFUNC(scamax)(int *, float  *, int *);\ndouble BLASFUNC(dzamax)(int *, double *, int *);\ndouble BLASFUNC(qxamax)(int *, double *, int *);\n\nfloat  BLASFUNC(samin) (int *, float  *, int *);\ndouble BLASFUNC(damin) (int *, double *, int *);\ndouble BLASFUNC(qamin) (int *, double *, int *);\nfloat  BLASFUNC(scamin)(int *, float  *, int *);\ndouble BLASFUNC(dzamin)(int *, double *, int *);\ndouble BLASFUNC(qxamin)(int *, double *, int *);\n\nfloat  BLASFUNC(smax)  (int *, float  *, int *);\ndouble BLASFUNC(dmax)  (int *, double *, int *);\ndouble BLASFUNC(qmax)  (int *, double *, int *);\nfloat  BLASFUNC(scmax) (int *, float  *, int *);\ndouble BLASFUNC(dzmax) (int *, double *, int *);\ndouble BLASFUNC(qxmax) (int *, double *, int *);\n\nfloat  BLASFUNC(smin)  (int *, float  *, int *);\ndouble BLASFUNC(dmin)  (int *, double *, int *);\ndouble BLASFUNC(qmin)  (int *, double *, int *);\nfloat  BLASFUNC(scmin) (int *, float  *, int *);\ndouble BLASFUNC(dzmin) (int *, double *, int *);\ndouble BLASFUNC(qxmin) (int *, double *, int *);\n\nint    BLASFUNC(sscal) (int *,  float  *, float  *, int *);\nint    BLASFUNC(dscal) (int *,  double *, double *, int *);\nint    BLASFUNC(qscal) (int *,  double *, double *, int *);\nint    BLASFUNC(cscal) (int *,  float  *, float  *, int *);\nint    BLASFUNC(zscal) (int *,  double *, double *, int *);\nint    BLASFUNC(xscal) (int *,  double *, double *, int *);\nint    BLASFUNC(csscal)(int *,  float  *, float  *, int *);\nint    BLASFUNC(zdscal)(int *,  double *, double *, int *);\nint    BLASFUNC(xqscal)(int *,  double *, double *, int *);\n\nfloat  BLASFUNC(snrm2) (int *, float  *, int *);\nfloat  BLASFUNC(scnrm2)(int *, float  *, int *);\n\ndouble BLASFUNC(dnrm2) (int *, double *, int *);\ndouble BLASFUNC(qnrm2) (int *, double *, int *);\ndouble BLASFUNC(dznrm2)(int *, double *, int *);\ndouble BLASFUNC(qxnrm2)(int *, double *, int *);\n\nint    BLASFUNC(srot)  (int *, float  *, int *, float  *, int *, float  *, float  *);\nint    BLASFUNC(drot)  (int *, double *, int *, double *, int *, double *, double *);\nint    BLASFUNC(qrot)  (int *, double *, int *, double *, int *, double *, double *);\nint    BLASFUNC(csrot) (int *, float  *, int *, float  *, int *, float  *, float  *);\nint    BLASFUNC(zdrot) (int *, double *, int *, double *, int *, double *, double *);\nint    BLASFUNC(xqrot) (int *, double *, int *, double *, int *, double *, double *);\n\nint    BLASFUNC(srotg) (float  *, float  *, float  *, float  *);\nint    BLASFUNC(drotg) (double *, double *, double *, double *);\nint    BLASFUNC(qrotg) (double *, double *, double *, double *);\nint    BLASFUNC(crotg) (float  *, float  *, float  *, float  *);\nint    BLASFUNC(zrotg) (double *, double *, double *, double *);\nint    BLASFUNC(xrotg) (double *, double *, double *, double *);\n\nint    BLASFUNC(srotmg)(float  *, float  *, float  *, float  *, float  *);\nint    BLASFUNC(drotmg)(double *, double *, double *, double *, double *);\n\nint    BLASFUNC(srotm) (int *, float  *, int *, float  *, int *, float  *);\nint    BLASFUNC(drotm) (int *, double *, int *, double *, int *, double *);\nint    BLASFUNC(qrotm) (int *, double *, int *, double *, int *, double *);\n\n/* Level 2 routines */\n\nint BLASFUNC(sger)(int *,    int *, float *,  float *, int *,\n\t\t   float *,  int *, float *,  int *);\nint BLASFUNC(dger)(int *,    int *, double *, double *, int *,\n\t\t   double *, int *, double *, int *);\nint BLASFUNC(qger)(int *,    int *, double *, double *, int *,\n\t\t   double *, int *, double *, int *);\nint BLASFUNC(cgeru)(int *,    int *, float *,  float *, int *,\n\t\t    float *,  int *, float *,  int *);\nint BLASFUNC(cgerc)(int *,    int *, float *,  float *, int *,\n\t\t    float *,  int *, float *,  int *);\nint BLASFUNC(zgeru)(int *,    int *, double *, double *, int *,\n\t\t    double *, int *, double *, int *);\nint BLASFUNC(zgerc)(int *,    int *, double *, double *, int *,\n\t\t    double *, int *, double *, int *);\nint BLASFUNC(xgeru)(int *,    int *, double *, double *, int *,\n\t\t    double *, int *, double *, int *);\nint BLASFUNC(xgerc)(int *,    int *, double *, double *, int *,\n\t\t    double *, int *, double *, int *);\n\nint BLASFUNC(sgemv)(const char *, const int *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(dgemv)(const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(qgemv)(const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(cgemv)(const char *, const int *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zgemv)(const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(xgemv)(const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\n\nint BLASFUNC(strsv) (const char *, const char *, const char *, const int *, const float  *, const int *, float  *, const int *);\nint BLASFUNC(dtrsv) (const char *, const char *, const char *, const int *, const double *, const int *, double *, const int *);\nint BLASFUNC(qtrsv) (const char *, const char *, const char *, const int *, const double *, const int *, double *, const int *);\nint BLASFUNC(ctrsv) (const char *, const char *, const char *, const int *, const float  *, const int *, float  *, const int *);\nint BLASFUNC(ztrsv) (const char *, const char *, const char *, const int *, const double *, const int *, double *, const int *);\nint BLASFUNC(xtrsv) (const char *, const char *, const char *, const int *, const double *, const int *, double *, const int *);\n\nint BLASFUNC(stpsv) (char *, char *, char *, int *, float  *, float  *, int *);\nint BLASFUNC(dtpsv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(qtpsv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(ctpsv) (char *, char *, char *, int *, float  *, float  *, int *);\nint BLASFUNC(ztpsv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(xtpsv) (char *, char *, char *, int *, double *, double *, int *);\n\nint BLASFUNC(strmv) (const char *, const char *, const char *, const int *, const float  *, const int *, float  *, const int *);\nint BLASFUNC(dtrmv) (const char *, const char *, const char *, const int *, const double *, const int *, double *, const int *);\nint BLASFUNC(qtrmv) (const char *, const char *, const char *, const int *, const double *, const int *, double *, const int *);\nint BLASFUNC(ctrmv) (const char *, const char *, const char *, const int *, const float  *, const int *, float  *, const int *);\nint BLASFUNC(ztrmv) (const char *, const char *, const char *, const int *, const double *, const int *, double *, const int *);\nint BLASFUNC(xtrmv) (const char *, const char *, const char *, const int *, const double *, const int *, double *, const int *);\n\nint BLASFUNC(stpmv) (char *, char *, char *, int *, float  *, float  *, int *);\nint BLASFUNC(dtpmv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(qtpmv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(ctpmv) (char *, char *, char *, int *, float  *, float  *, int *);\nint BLASFUNC(ztpmv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(xtpmv) (char *, char *, char *, int *, double *, double *, int *);\n\nint BLASFUNC(stbmv) (char *, char *, char *, int *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(dtbmv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(qtbmv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(ctbmv) (char *, char *, char *, int *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(ztbmv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(xtbmv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\n\nint BLASFUNC(stbsv) (char *, char *, char *, int *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(dtbsv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(qtbsv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(ctbsv) (char *, char *, char *, int *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(ztbsv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(xtbsv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\n\nint BLASFUNC(ssymv) (const char *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(dsymv) (const char *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(qsymv) (const char *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\n\nint BLASFUNC(sspmv) (char *, int *, float  *, float *,\n\t\t     float  *, int *, float *, float *, int *);\nint BLASFUNC(dspmv) (char *, int *, double  *, double *,\n\t\t     double  *, int *, double *, double *, int *);\nint BLASFUNC(qspmv) (char *, int *, double  *, double *,\n\t\t     double  *, int *, double *, double *, int *);\n\nint BLASFUNC(ssyr) (const char *, const int *, const float   *, const float  *, const int *, float  *, const int *);\nint BLASFUNC(dsyr) (const char *, const int *, const double  *, const double *, const int *, double *, const int *);\nint BLASFUNC(qsyr) (const char *, const int *, const double  *, const double *, const int *, double *, const int *);\n\nint BLASFUNC(ssyr2) (const char *, const int *, const float   *, const float  *, const int *, const float  *, const int *, float  *, const int *);\nint BLASFUNC(dsyr2) (const char *, const int *, const double  *, const double *, const int *, const double *, const int *, double *, const int *);\nint BLASFUNC(qsyr2) (const char *, const int *, const double  *, const double *, const int *, const double *, const int *, double *, const int *);\nint BLASFUNC(csyr2) (const char *, const int *, const float   *, const float  *, const int *, const float  *, const int *, float  *, const int *);\nint BLASFUNC(zsyr2) (const char *, const int *, const double  *, const double *, const int *, const double *, const int *, double *, const int *);\nint BLASFUNC(xsyr2) (const char *, const int *, const double  *, const double *, const int *, const double *, const int *, double *, const int *);\n\nint BLASFUNC(sspr) (char *, int *, float   *, float  *, int *,\n\t\t    float  *);\nint BLASFUNC(dspr) (char *, int *, double  *, double *, int *,\n\t\t    double *);\nint BLASFUNC(qspr) (char *, int *, double  *, double *, int *,\n\t\t    double *);\n\nint BLASFUNC(sspr2) (char *, int *, float   *,\n\t\t     float  *, int *, float  *, int *, float  *);\nint BLASFUNC(dspr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\nint BLASFUNC(qspr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\nint BLASFUNC(cspr2) (char *, int *, float   *,\n\t\t     float  *, int *, float  *, int *, float  *);\nint BLASFUNC(zspr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\nint BLASFUNC(xspr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\n\nint BLASFUNC(cher) (char *, int *, float   *, float  *, int *,\n\t\t    float  *, int *);\nint BLASFUNC(zher) (char *, int *, double  *, double *, int *,\n\t\t    double *, int *);\nint BLASFUNC(xher) (char *, int *, double  *, double *, int *,\n\t\t    double *, int *);\n\nint BLASFUNC(chpr) (char *, int *, float   *, float  *, int *, float  *);\nint BLASFUNC(zhpr) (char *, int *, double  *, double *, int *, double *);\nint BLASFUNC(xhpr) (char *, int *, double  *, double *, int *, double *);\n\nint BLASFUNC(cher2) (char *, int *, float   *,\n\t\t     float  *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(zher2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *, int *);\nint BLASFUNC(xher2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *, int *);\n\nint BLASFUNC(chpr2) (char *, int *, float   *,\n\t\t     float  *, int *, float  *, int *, float  *);\nint BLASFUNC(zhpr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\nint BLASFUNC(xhpr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\n\nint BLASFUNC(chemv) (const char *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zhemv) (const char *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(xhemv) (const char *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\n\nint BLASFUNC(chpmv) (char *, int *, float  *, float *,\n\t\t     float  *, int *, float *, float *, int *);\nint BLASFUNC(zhpmv) (char *, int *, double  *, double *,\n\t\t     double  *, int *, double *, double *, int *);\nint BLASFUNC(xhpmv) (char *, int *, double  *, double *,\n\t\t     double  *, int *, double *, double *, int *);\n\nint BLASFUNC(snorm)(char *, int *, int *, float  *, int *);\nint BLASFUNC(dnorm)(char *, int *, int *, double *, int *);\nint BLASFUNC(cnorm)(char *, int *, int *, float  *, int *);\nint BLASFUNC(znorm)(char *, int *, int *, double *, int *);\n\nint BLASFUNC(sgbmv)(char *, int *, int *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(dgbmv)(char *, int *, int *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(qgbmv)(char *, int *, int *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(cgbmv)(char *, int *, int *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zgbmv)(char *, int *, int *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(xgbmv)(char *, int *, int *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\n\nint BLASFUNC(ssbmv)(char *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(dsbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(qsbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(csbmv)(char *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zsbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(xsbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\n\nint BLASFUNC(chbmv)(char *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zhbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(xhbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\n\n/* Level 3 routines */\n\nint BLASFUNC(sgemm)(const char *, const char *, const int *, const int *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(dgemm)(const char *, const char *, const int *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(qgemm)(const char *, const char *, const int *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(cgemm)(const char *, const char *, const int *, const int *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zgemm)(const char *, const char *, const int *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(xgemm)(const char *, const char *, const int *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\n\nint BLASFUNC(cgemm3m)(char *, char *, int *, int *, int *, float *,\n\t   float  *, int *, float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zgemm3m)(char *, char *, int *, int *, int *, double *,\n\t   double *, int *, double *, int *, double *, double *, int *);\nint BLASFUNC(xgemm3m)(char *, char *, int *, int *, int *, double *,\n\t   double *, int *, double *, int *, double *, double *, int *);\n\nint BLASFUNC(sge2mm)(char *, char *, char *, int *, int *,\n\t\t     float *, float  *, int *, float  *, int *,\n\t\t     float *, float  *, int *);\nint BLASFUNC(dge2mm)(char *, char *, char *, int *, int *,\n\t\t     double *, double  *, int *, double  *, int *,\n\t\t     double *, double  *, int *);\nint BLASFUNC(cge2mm)(char *, char *, char *, int *, int *,\n\t\t     float *, float  *, int *, float  *, int *,\n\t\t     float *, float  *, int *);\nint BLASFUNC(zge2mm)(char *, char *, char *, int *, int *,\n\t\t     double *, double  *, int *, double  *, int *,\n\t\t     double *, double  *, int *);\n\nint BLASFUNC(strsm)(const char *, const char *, const char *, const char *, const int *, const int *, const float *,  const float *,  const int *, float *,  const int *);\nint BLASFUNC(dtrsm)(const char *, const char *, const char *, const char *, const int *, const int *, const double *, const double *, const int *, double *, const int *);\nint BLASFUNC(qtrsm)(const char *, const char *, const char *, const char *, const int *, const int *, const double *, const double *, const int *, double *, const int *);\nint BLASFUNC(ctrsm)(const char *, const char *, const char *, const char *, const int *, const int *, const float *,  const float *,  const int *, float *,  const int *);\nint BLASFUNC(ztrsm)(const char *, const char *, const char *, const char *, const int *, const int *, const double *, const double *, const int *, double *, const int *);\nint BLASFUNC(xtrsm)(const char *, const char *, const char *, const char *, const int *, const int *, const double *, const double *, const int *, double *, const int *);\n\nint BLASFUNC(strmm)(const char *, const char *, const char *, const char *, const int *, const int *, const float *,  const float *,  const int *, float *,  const int *);\nint BLASFUNC(dtrmm)(const char *, const char *, const char *, const char *, const int *, const int *, const double *, const double *, const int *, double *, const int *);\nint BLASFUNC(qtrmm)(const char *, const char *, const char *, const char *, const int *, const int *, const double *, const double *, const int *, double *, const int *);\nint BLASFUNC(ctrmm)(const char *, const char *, const char *, const char *, const int *, const int *, const float *,  const float *,  const int *, float *,  const int *);\nint BLASFUNC(ztrmm)(const char *, const char *, const char *, const char *, const int *, const int *, const double *, const double *, const int *, double *, const int *);\nint BLASFUNC(xtrmm)(const char *, const char *, const char *, const char *, const int *, const int *, const double *, const double *, const int *, double *, const int *);\n\nint BLASFUNC(ssymm)(const char *, const char *, const int *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(dsymm)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(qsymm)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(csymm)(const char *, const char *, const int *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zsymm)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(xsymm)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\n\nint BLASFUNC(csymm3m)(char *, char *, int *, int *, float  *, float  *, int *, float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zsymm3m)(char *, char *, int *, int *, double *, double *, int *, double *, int *, double *, double *, int *);\nint BLASFUNC(xsymm3m)(char *, char *, int *, int *, double *, double *, int *, double *, int *, double *, double *, int *);\n\nint BLASFUNC(ssyrk)(const char *, const char *, const int *, const int *, const float  *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(dsyrk)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(qsyrk)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(csyrk)(const char *, const char *, const int *, const int *, const float  *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zsyrk)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(xsyrk)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, double *, const int *);\n\nint BLASFUNC(ssyr2k)(const char *, const char *, const int *, const int *, const float  *, const float  *, const int *, const float *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(dsyr2k)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double*, const int *, const double *, double *, const int *);\nint BLASFUNC(qsyr2k)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double*, const int *, const double *, double *, const int *);\nint BLASFUNC(csyr2k)(const char *, const char *, const int *, const int *, const float  *, const float  *, const int *, const float *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zsyr2k)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double*, const int *, const double *, double *, const int *);\nint BLASFUNC(xsyr2k)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double*, const int *, const double *, double *, const int *);\n\nint BLASFUNC(chemm)(const char *, const char *, const int *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zhemm)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(xhemm)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\n\nint BLASFUNC(chemm3m)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zhemm3m)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\nint BLASFUNC(xhemm3m)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\n\nint BLASFUNC(cherk)(const char *, const char *, const int *, const int *, const float  *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zherk)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(xherk)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, double *, const int *);\n\nint BLASFUNC(cher2k)(const char *, const char *, const int *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zher2k)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(xher2k)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(cher2m)(const char *, const char *, const char *, const int *, const int *, const float  *, const float  *, const int *, const float *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zher2m)(const char *, const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double*, const int *, const double *, double *, const int *);\nint BLASFUNC(xher2m)(const char *, const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double*, const int *, const double *, double *, const int *);\n\n\n#ifdef __cplusplus\n}\n#endif\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/misc/lapack.h",
    "content": "#ifndef LAPACK_H\n#define LAPACK_H\n\n#include \"blas.h\"\n\n#ifdef __cplusplus\nextern \"C\"\n{\n#endif\n\nint BLASFUNC(csymv) (const char *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zsymv) (const char *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(xsymv) (const char *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\n\n\nint BLASFUNC(cspmv) (char *, int *, float  *, float *,\n         float  *, int *, float *, float *, int *);\nint BLASFUNC(zspmv) (char *, int *, double  *, double *,\n         double  *, int *, double *, double *, int *);\nint BLASFUNC(xspmv) (char *, int *, double  *, double *,\n         double  *, int *, double *, double *, int *);\n\nint BLASFUNC(csyr) (char *, int *, float   *, float  *, int *,\n        float  *, int *);\nint BLASFUNC(zsyr) (char *, int *, double  *, double *, int *,\n        double *, int *);\nint BLASFUNC(xsyr) (char *, int *, double  *, double *, int *,\n        double *, int *);\n\nint BLASFUNC(cspr) (char *, int *, float   *, float  *, int *,\n        float  *);\nint BLASFUNC(zspr) (char *, int *, double  *, double *, int *,\n        double *);\nint BLASFUNC(xspr) (char *, int *, double  *, double *, int *,\n        double *);\n\nint BLASFUNC(sgemt)(char *, int *, int *, float  *, float  *, int *,\n        float  *, int *);\nint BLASFUNC(dgemt)(char *, int *, int *, double *, double *, int *,\n        double *, int *);\nint BLASFUNC(cgemt)(char *, int *, int *, float  *, float  *, int *,\n        float  *, int *);\nint BLASFUNC(zgemt)(char *, int *, int *, double *, double *, int *,\n        double *, int *);\n\nint BLASFUNC(sgema)(char *, char *, int *, int *, float  *,\n        float  *, int *, float *, float  *, int *, float *, int *);\nint BLASFUNC(dgema)(char *, char *, int *, int *, double *,\n        double *, int *, double*, double *, int *, double*, int *);\nint BLASFUNC(cgema)(char *, char *, int *, int *, float  *,\n        float  *, int *, float *, float  *, int *, float *, int *);\nint BLASFUNC(zgema)(char *, char *, int *, int *, double *,\n        double *, int *, double*, double *, int *, double*, int *);\n\nint BLASFUNC(sgems)(char *, char *, int *, int *, float  *,\n        float  *, int *, float *, float  *, int *, float *, int *);\nint BLASFUNC(dgems)(char *, char *, int *, int *, double *,\n        double *, int *, double*, double *, int *, double*, int *);\nint BLASFUNC(cgems)(char *, char *, int *, int *, float  *,\n        float  *, int *, float *, float  *, int *, float *, int *);\nint BLASFUNC(zgems)(char *, char *, int *, int *, double *,\n        double *, int *, double*, double *, int *, double*, int *);\n\nint BLASFUNC(sgetf2)(int *, int *, float  *, int *, int *, int *);\nint BLASFUNC(dgetf2)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(qgetf2)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(cgetf2)(int *, int *, float  *, int *, int *, int *);\nint BLASFUNC(zgetf2)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(xgetf2)(int *, int *, double *, int *, int *, int *);\n\nint BLASFUNC(sgetrf)(int *, int *, float  *, int *, int *, int *);\nint BLASFUNC(dgetrf)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(qgetrf)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(cgetrf)(int *, int *, float  *, int *, int *, int *);\nint BLASFUNC(zgetrf)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(xgetrf)(int *, int *, double *, int *, int *, int *);\n\nint BLASFUNC(slaswp)(int *, float  *, int *, int *, int *, int *, int *);\nint BLASFUNC(dlaswp)(int *, double *, int *, int *, int *, int *, int *);\nint BLASFUNC(qlaswp)(int *, double *, int *, int *, int *, int *, int *);\nint BLASFUNC(claswp)(int *, float  *, int *, int *, int *, int *, int *);\nint BLASFUNC(zlaswp)(int *, double *, int *, int *, int *, int *, int *);\nint BLASFUNC(xlaswp)(int *, double *, int *, int *, int *, int *, int *);\n\nint BLASFUNC(sgetrs)(char *, int *, int *, float  *, int *, int *, float  *, int *, int *);\nint BLASFUNC(dgetrs)(char *, int *, int *, double *, int *, int *, double *, int *, int *);\nint BLASFUNC(qgetrs)(char *, int *, int *, double *, int *, int *, double *, int *, int *);\nint BLASFUNC(cgetrs)(char *, int *, int *, float  *, int *, int *, float  *, int *, int *);\nint BLASFUNC(zgetrs)(char *, int *, int *, double *, int *, int *, double *, int *, int *);\nint BLASFUNC(xgetrs)(char *, int *, int *, double *, int *, int *, double *, int *, int *);\n\nint BLASFUNC(sgesv)(int *, int *, float  *, int *, int *, float *, int *, int *);\nint BLASFUNC(dgesv)(int *, int *, double *, int *, int *, double*, int *, int *);\nint BLASFUNC(qgesv)(int *, int *, double *, int *, int *, double*, int *, int *);\nint BLASFUNC(cgesv)(int *, int *, float  *, int *, int *, float *, int *, int *);\nint BLASFUNC(zgesv)(int *, int *, double *, int *, int *, double*, int *, int *);\nint BLASFUNC(xgesv)(int *, int *, double *, int *, int *, double*, int *, int *);\n\nint BLASFUNC(spotf2)(char *, int *, float  *, int *, int *);\nint BLASFUNC(dpotf2)(char *, int *, double *, int *, int *);\nint BLASFUNC(qpotf2)(char *, int *, double *, int *, int *);\nint BLASFUNC(cpotf2)(char *, int *, float  *, int *, int *);\nint BLASFUNC(zpotf2)(char *, int *, double *, int *, int *);\nint BLASFUNC(xpotf2)(char *, int *, double *, int *, int *);\n\nint BLASFUNC(spotrf)(char *, int *, float  *, int *, int *);\nint BLASFUNC(dpotrf)(char *, int *, double *, int *, int *);\nint BLASFUNC(qpotrf)(char *, int *, double *, int *, int *);\nint BLASFUNC(cpotrf)(char *, int *, float  *, int *, int *);\nint BLASFUNC(zpotrf)(char *, int *, double *, int *, int *);\nint BLASFUNC(xpotrf)(char *, int *, double *, int *, int *);\n\nint BLASFUNC(slauu2)(char *, int *, float  *, int *, int *);\nint BLASFUNC(dlauu2)(char *, int *, double *, int *, int *);\nint BLASFUNC(qlauu2)(char *, int *, double *, int *, int *);\nint BLASFUNC(clauu2)(char *, int *, float  *, int *, int *);\nint BLASFUNC(zlauu2)(char *, int *, double *, int *, int *);\nint BLASFUNC(xlauu2)(char *, int *, double *, int *, int *);\n\nint BLASFUNC(slauum)(char *, int *, float  *, int *, int *);\nint BLASFUNC(dlauum)(char *, int *, double *, int *, int *);\nint BLASFUNC(qlauum)(char *, int *, double *, int *, int *);\nint BLASFUNC(clauum)(char *, int *, float  *, int *, int *);\nint BLASFUNC(zlauum)(char *, int *, double *, int *, int *);\nint BLASFUNC(xlauum)(char *, int *, double *, int *, int *);\n\nint BLASFUNC(strti2)(char *, char *, int *, float  *, int *, int *);\nint BLASFUNC(dtrti2)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(qtrti2)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(ctrti2)(char *, char *, int *, float  *, int *, int *);\nint BLASFUNC(ztrti2)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(xtrti2)(char *, char *, int *, double *, int *, int *);\n\nint BLASFUNC(strtri)(char *, char *, int *, float  *, int *, int *);\nint BLASFUNC(dtrtri)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(qtrtri)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(ctrtri)(char *, char *, int *, float  *, int *, int *);\nint BLASFUNC(ztrtri)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(xtrtri)(char *, char *, int *, double *, int *, int *);\n\nint BLASFUNC(spotri)(char *, int *, float  *, int *, int *);\nint BLASFUNC(dpotri)(char *, int *, double *, int *, int *);\nint BLASFUNC(qpotri)(char *, int *, double *, int *, int *);\nint BLASFUNC(cpotri)(char *, int *, float  *, int *, int *);\nint BLASFUNC(zpotri)(char *, int *, double *, int *, int *);\nint BLASFUNC(xpotri)(char *, int *, double *, int *, int *);\n\n#ifdef __cplusplus\n}\n#endif\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/misc/lapacke.h",
    "content": "/*****************************************************************************\n  Copyright (c) 2010, Intel Corp.\n  All rights reserved.\n\n  Redistribution and use in source and binary forms, with or without\n  modification, are permitted provided that the following conditions are met:\n\n    * Redistributions of source code must retain the above copyright notice,\n      this list of conditions and the following disclaimer.\n    * Redistributions in binary form must reproduce the above copyright\n      notice, this list of conditions and the following disclaimer in the\n      documentation and/or other materials provided with the distribution.\n    * Neither the name of Intel Corporation nor the names of its contributors\n      may be used to endorse or promote products derived from this software\n      without specific prior written permission.\n\n  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\"\n  AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\n  IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE\n  ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE\n  LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR\n  CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF\n  SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS\n  INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN\n  CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)\n  ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF\n  THE POSSIBILITY OF SUCH DAMAGE.\n******************************************************************************\n* Contents: Native C interface to LAPACK\n* Author: Intel Corporation\n* Generated November, 2011\n*****************************************************************************/\n\n#ifndef _MKL_LAPACKE_H_\n\n#ifndef _LAPACKE_H_\n#define _LAPACKE_H_\n\n/*\n*  Turn on HAVE_LAPACK_CONFIG_H to redefine C-LAPACK datatypes\n*/\n#ifdef HAVE_LAPACK_CONFIG_H\n#include \"lapacke_config.h\"\n#endif\n\n#include <stdlib.h>\n\n#ifndef lapack_int\n#define lapack_int     int\n#endif\n\n#ifndef lapack_logical\n#define lapack_logical lapack_int\n#endif\n\n/* Complex types are structures equivalent to the\n* Fortran complex types COMPLEX(4) and COMPLEX(8).\n*\n* One can also redefine the types with his own types\n* for example by including in the code definitions like\n*\n* #define lapack_complex_float std::complex<float>\n* #define lapack_complex_double std::complex<double>\n*\n* or define these types in the command line:\n*\n* -Dlapack_complex_float=\"std::complex<float>\"\n* -Dlapack_complex_double=\"std::complex<double>\"\n*/\n\n#ifndef LAPACK_COMPLEX_CUSTOM\n\n/* Complex type (single precision) */\n#ifndef lapack_complex_float\n#include <complex.h>\n#define lapack_complex_float    float _Complex\n#endif\n\n#ifndef lapack_complex_float_real\n#define lapack_complex_float_real(z)       (creal(z))\n#endif\n\n#ifndef lapack_complex_float_imag\n#define lapack_complex_float_imag(z)       (cimag(z))\n#endif\n\nlapack_complex_float lapack_make_complex_float( float re, float im );\n\n/* Complex type (double precision) */\n#ifndef lapack_complex_double\n#include <complex.h>\n#define lapack_complex_double   double _Complex\n#endif\n\n#ifndef lapack_complex_double_real\n#define lapack_complex_double_real(z)      (creal(z))\n#endif\n\n#ifndef lapack_complex_double_imag\n#define lapack_complex_double_imag(z)       (cimag(z))\n#endif\n\nlapack_complex_double lapack_make_complex_double( double re, double im );\n\n#endif\n\n\n#ifdef __cplusplus\nextern \"C\" {\n#endif /* __cplusplus */\n\n#ifndef LAPACKE_malloc\n#define LAPACKE_malloc( size ) malloc( size )\n#endif\n#ifndef LAPACKE_free\n#define LAPACKE_free( p )      free( p )\n#endif\n\n#define LAPACK_C2INT( x ) (lapack_int)(*((float*)&x ))\n#define LAPACK_Z2INT( x ) (lapack_int)(*((double*)&x ))\n\n#define LAPACK_ROW_MAJOR               101\n#define LAPACK_COL_MAJOR               102\n\n#define LAPACK_WORK_MEMORY_ERROR       -1010\n#define LAPACK_TRANSPOSE_MEMORY_ERROR  -1011\n\n/* Callback logical functions of one, two, or three arguments are used\n*  to select eigenvalues to sort to the top left of the Schur form.\n*  The value is selected if function returns TRUE (non-zero). */\n\ntypedef lapack_logical (*LAPACK_S_SELECT2) ( const float*, const float* );\ntypedef lapack_logical (*LAPACK_S_SELECT3)\n    ( const float*, const float*, const float* );\ntypedef lapack_logical (*LAPACK_D_SELECT2) ( const double*, const double* );\ntypedef lapack_logical (*LAPACK_D_SELECT3)\n    ( const double*, const double*, const double* );\n\ntypedef lapack_logical (*LAPACK_C_SELECT1) ( const lapack_complex_float* );\ntypedef lapack_logical (*LAPACK_C_SELECT2)\n    ( const lapack_complex_float*, const lapack_complex_float* );\ntypedef lapack_logical (*LAPACK_Z_SELECT1) ( const lapack_complex_double* );\ntypedef lapack_logical (*LAPACK_Z_SELECT2)\n    ( const lapack_complex_double*, const lapack_complex_double* );\n\n#include \"lapacke_mangling.h\"\n\n#define LAPACK_lsame LAPACK_GLOBAL(lsame,LSAME)\nlapack_logical LAPACK_lsame( char* ca,  char* cb,\n                              lapack_int lca, lapack_int lcb );\n\n/* C-LAPACK function prototypes */\n\nlapack_int LAPACKE_sbdsdc( int matrix_order, char uplo, char compq,\n                           lapack_int n, float* d, float* e, float* u,\n                           lapack_int ldu, float* vt, lapack_int ldvt, float* q,\n                           lapack_int* iq );\nlapack_int LAPACKE_dbdsdc( int matrix_order, char uplo, char compq,\n                           lapack_int n, double* d, double* e, double* u,\n                           lapack_int ldu, double* vt, lapack_int ldvt,\n                           double* q, lapack_int* iq );\n\nlapack_int LAPACKE_sbdsqr( int matrix_order, char uplo, lapack_int n,\n                           lapack_int ncvt, lapack_int nru, lapack_int ncc,\n                           float* d, float* e, float* vt, lapack_int ldvt,\n                           float* u, lapack_int ldu, float* c, lapack_int ldc );\nlapack_int LAPACKE_dbdsqr( int matrix_order, char uplo, lapack_int n,\n                           lapack_int ncvt, lapack_int nru, lapack_int ncc,\n                           double* d, double* e, double* vt, lapack_int ldvt,\n                           double* u, lapack_int ldu, double* c,\n                           lapack_int ldc );\nlapack_int LAPACKE_cbdsqr( int matrix_order, char uplo, lapack_int n,\n                           lapack_int ncvt, lapack_int nru, lapack_int ncc,\n                           float* d, float* e, lapack_complex_float* vt,\n                           lapack_int ldvt, lapack_complex_float* u,\n                           lapack_int ldu, lapack_complex_float* c,\n                           lapack_int ldc );\nlapack_int LAPACKE_zbdsqr( int matrix_order, char uplo, lapack_int n,\n                           lapack_int ncvt, lapack_int nru, lapack_int ncc,\n                           double* d, double* e, lapack_complex_double* vt,\n                           lapack_int ldvt, lapack_complex_double* u,\n                           lapack_int ldu, lapack_complex_double* c,\n                           lapack_int ldc );\n\nlapack_int LAPACKE_sdisna( char job, lapack_int m, lapack_int n, const float* d,\n                           float* sep );\nlapack_int LAPACKE_ddisna( char job, lapack_int m, lapack_int n,\n                           const double* d, double* sep );\n\nlapack_int LAPACKE_sgbbrd( int matrix_order, char vect, lapack_int m,\n                           lapack_int n, lapack_int ncc, lapack_int kl,\n                           lapack_int ku, float* ab, lapack_int ldab, float* d,\n                           float* e, float* q, lapack_int ldq, float* pt,\n                           lapack_int ldpt, float* c, lapack_int ldc );\nlapack_int LAPACKE_dgbbrd( int matrix_order, char vect, lapack_int m,\n                           lapack_int n, lapack_int ncc, lapack_int kl,\n                           lapack_int ku, double* ab, lapack_int ldab,\n                           double* d, double* e, double* q, lapack_int ldq,\n                           double* pt, lapack_int ldpt, double* c,\n                           lapack_int ldc );\nlapack_int LAPACKE_cgbbrd( int matrix_order, char vect, lapack_int m,\n                           lapack_int n, lapack_int ncc, lapack_int kl,\n                           lapack_int ku, lapack_complex_float* ab,\n                           lapack_int ldab, float* d, float* e,\n                           lapack_complex_float* q, lapack_int ldq,\n                           lapack_complex_float* pt, lapack_int ldpt,\n                           lapack_complex_float* c, lapack_int ldc );\nlapack_int LAPACKE_zgbbrd( int matrix_order, char vect, lapack_int m,\n                           lapack_int n, lapack_int ncc, lapack_int kl,\n                           lapack_int ku, lapack_complex_double* ab,\n                           lapack_int ldab, double* d, double* e,\n                           lapack_complex_double* q, lapack_int ldq,\n                           lapack_complex_double* pt, lapack_int ldpt,\n                           lapack_complex_double* c, lapack_int ldc );\n\nlapack_int LAPACKE_sgbcon( int matrix_order, char norm, lapack_int n,\n                           lapack_int kl, lapack_int ku, const float* ab,\n                           lapack_int ldab, const lapack_int* ipiv, float anorm,\n                           float* rcond );\nlapack_int LAPACKE_dgbcon( int matrix_order, char norm, lapack_int n,\n                           lapack_int kl, lapack_int ku, const double* ab,\n                           lapack_int ldab, const lapack_int* ipiv,\n                           double anorm, double* rcond );\nlapack_int LAPACKE_cgbcon( int matrix_order, char norm, lapack_int n,\n                           lapack_int kl, lapack_int ku,\n                           const lapack_complex_float* ab, lapack_int ldab,\n                           const lapack_int* ipiv, float anorm, float* rcond );\nlapack_int LAPACKE_zgbcon( int matrix_order, char norm, lapack_int n,\n                           lapack_int kl, lapack_int ku,\n                           const lapack_complex_double* ab, lapack_int ldab,\n                           const lapack_int* ipiv, double anorm,\n                           double* rcond );\n\nlapack_int LAPACKE_sgbequ( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku, const float* ab,\n                           lapack_int ldab, float* r, float* c, float* rowcnd,\n                           float* colcnd, float* amax );\nlapack_int LAPACKE_dgbequ( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku, const double* ab,\n                           lapack_int ldab, double* r, double* c,\n                           double* rowcnd, double* colcnd, double* amax );\nlapack_int LAPACKE_cgbequ( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku,\n                           const lapack_complex_float* ab, lapack_int ldab,\n                           float* r, float* c, float* rowcnd, float* colcnd,\n                           float* amax );\nlapack_int LAPACKE_zgbequ( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku,\n                           const lapack_complex_double* ab, lapack_int ldab,\n                           double* r, double* c, double* rowcnd, double* colcnd,\n                           double* amax );\n\nlapack_int LAPACKE_sgbequb( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_int kl, lapack_int ku, const float* ab,\n                            lapack_int ldab, float* r, float* c, float* rowcnd,\n                            float* colcnd, float* amax );\nlapack_int LAPACKE_dgbequb( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_int kl, lapack_int ku, const double* ab,\n                            lapack_int ldab, double* r, double* c,\n                            double* rowcnd, double* colcnd, double* amax );\nlapack_int LAPACKE_cgbequb( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_int kl, lapack_int ku,\n                            const lapack_complex_float* ab, lapack_int ldab,\n                            float* r, float* c, float* rowcnd, float* colcnd,\n                            float* amax );\nlapack_int LAPACKE_zgbequb( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_int kl, lapack_int ku,\n                            const lapack_complex_double* ab, lapack_int ldab,\n                            double* r, double* c, double* rowcnd,\n                            double* colcnd, double* amax );\n\nlapack_int LAPACKE_sgbrfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int kl, lapack_int ku, lapack_int nrhs,\n                           const float* ab, lapack_int ldab, const float* afb,\n                           lapack_int ldafb, const lapack_int* ipiv,\n                           const float* b, lapack_int ldb, float* x,\n                           lapack_int ldx, float* ferr, float* berr );\nlapack_int LAPACKE_dgbrfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int kl, lapack_int ku, lapack_int nrhs,\n                           const double* ab, lapack_int ldab, const double* afb,\n                           lapack_int ldafb, const lapack_int* ipiv,\n                           const double* b, lapack_int ldb, double* x,\n                           lapack_int ldx, double* ferr, double* berr );\nlapack_int LAPACKE_cgbrfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int kl, lapack_int ku, lapack_int nrhs,\n                           const lapack_complex_float* ab, lapack_int ldab,\n                           const lapack_complex_float* afb, lapack_int ldafb,\n                           const lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zgbrfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int kl, lapack_int ku, lapack_int nrhs,\n                           const lapack_complex_double* ab, lapack_int ldab,\n                           const lapack_complex_double* afb, lapack_int ldafb,\n                           const lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_sgbrfsx( int matrix_order, char trans, char equed,\n                            lapack_int n, lapack_int kl, lapack_int ku,\n                            lapack_int nrhs, const float* ab, lapack_int ldab,\n                            const float* afb, lapack_int ldafb,\n                            const lapack_int* ipiv, const float* r,\n                            const float* c, const float* b, lapack_int ldb,\n                            float* x, lapack_int ldx, float* rcond, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_dgbrfsx( int matrix_order, char trans, char equed,\n                            lapack_int n, lapack_int kl, lapack_int ku,\n                            lapack_int nrhs, const double* ab, lapack_int ldab,\n                            const double* afb, lapack_int ldafb,\n                            const lapack_int* ipiv, const double* r,\n                            const double* c, const double* b, lapack_int ldb,\n                            double* x, lapack_int ldx, double* rcond,\n                            double* berr, lapack_int n_err_bnds,\n                            double* err_bnds_norm, double* err_bnds_comp,\n                            lapack_int nparams, double* params );\nlapack_int LAPACKE_cgbrfsx( int matrix_order, char trans, char equed,\n                            lapack_int n, lapack_int kl, lapack_int ku,\n                            lapack_int nrhs, const lapack_complex_float* ab,\n                            lapack_int ldab, const lapack_complex_float* afb,\n                            lapack_int ldafb, const lapack_int* ipiv,\n                            const float* r, const float* c,\n                            const lapack_complex_float* b, lapack_int ldb,\n                            lapack_complex_float* x, lapack_int ldx,\n                            float* rcond, float* berr, lapack_int n_err_bnds,\n                            float* err_bnds_norm, float* err_bnds_comp,\n                            lapack_int nparams, float* params );\nlapack_int LAPACKE_zgbrfsx( int matrix_order, char trans, char equed,\n                            lapack_int n, lapack_int kl, lapack_int ku,\n                            lapack_int nrhs, const lapack_complex_double* ab,\n                            lapack_int ldab, const lapack_complex_double* afb,\n                            lapack_int ldafb, const lapack_int* ipiv,\n                            const double* r, const double* c,\n                            const lapack_complex_double* b, lapack_int ldb,\n                            lapack_complex_double* x, lapack_int ldx,\n                            double* rcond, double* berr, lapack_int n_err_bnds,\n                            double* err_bnds_norm, double* err_bnds_comp,\n                            lapack_int nparams, double* params );\n\nlapack_int LAPACKE_sgbsv( int matrix_order, lapack_int n, lapack_int kl,\n                          lapack_int ku, lapack_int nrhs, float* ab,\n                          lapack_int ldab, lapack_int* ipiv, float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_dgbsv( int matrix_order, lapack_int n, lapack_int kl,\n                          lapack_int ku, lapack_int nrhs, double* ab,\n                          lapack_int ldab, lapack_int* ipiv, double* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_cgbsv( int matrix_order, lapack_int n, lapack_int kl,\n                          lapack_int ku, lapack_int nrhs,\n                          lapack_complex_float* ab, lapack_int ldab,\n                          lapack_int* ipiv, lapack_complex_float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_zgbsv( int matrix_order, lapack_int n, lapack_int kl,\n                          lapack_int ku, lapack_int nrhs,\n                          lapack_complex_double* ab, lapack_int ldab,\n                          lapack_int* ipiv, lapack_complex_double* b,\n                          lapack_int ldb );\n\nlapack_int LAPACKE_sgbsvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int kl, lapack_int ku,\n                           lapack_int nrhs, float* ab, lapack_int ldab,\n                           float* afb, lapack_int ldafb, lapack_int* ipiv,\n                           char* equed, float* r, float* c, float* b,\n                           lapack_int ldb, float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr,\n                           float* rpivot );\nlapack_int LAPACKE_dgbsvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int kl, lapack_int ku,\n                           lapack_int nrhs, double* ab, lapack_int ldab,\n                           double* afb, lapack_int ldafb, lapack_int* ipiv,\n                           char* equed, double* r, double* c, double* b,\n                           lapack_int ldb, double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr,\n                           double* rpivot );\nlapack_int LAPACKE_cgbsvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int kl, lapack_int ku,\n                           lapack_int nrhs, lapack_complex_float* ab,\n                           lapack_int ldab, lapack_complex_float* afb,\n                           lapack_int ldafb, lapack_int* ipiv, char* equed,\n                           float* r, float* c, lapack_complex_float* b,\n                           lapack_int ldb, lapack_complex_float* x,\n                           lapack_int ldx, float* rcond, float* ferr,\n                           float* berr, float* rpivot );\nlapack_int LAPACKE_zgbsvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int kl, lapack_int ku,\n                           lapack_int nrhs, lapack_complex_double* ab,\n                           lapack_int ldab, lapack_complex_double* afb,\n                           lapack_int ldafb, lapack_int* ipiv, char* equed,\n                           double* r, double* c, lapack_complex_double* b,\n                           lapack_int ldb, lapack_complex_double* x,\n                           lapack_int ldx, double* rcond, double* ferr,\n                           double* berr, double* rpivot );\n\nlapack_int LAPACKE_sgbsvxx( int matrix_order, char fact, char trans,\n                            lapack_int n, lapack_int kl, lapack_int ku,\n                            lapack_int nrhs, float* ab, lapack_int ldab,\n                            float* afb, lapack_int ldafb, lapack_int* ipiv,\n                            char* equed, float* r, float* c, float* b,\n                            lapack_int ldb, float* x, lapack_int ldx,\n                            float* rcond, float* rpvgrw, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_dgbsvxx( int matrix_order, char fact, char trans,\n                            lapack_int n, lapack_int kl, lapack_int ku,\n                            lapack_int nrhs, double* ab, lapack_int ldab,\n                            double* afb, lapack_int ldafb, lapack_int* ipiv,\n                            char* equed, double* r, double* c, double* b,\n                            lapack_int ldb, double* x, lapack_int ldx,\n                            double* rcond, double* rpvgrw, double* berr,\n                            lapack_int n_err_bnds, double* err_bnds_norm,\n                            double* err_bnds_comp, lapack_int nparams,\n                            double* params );\nlapack_int LAPACKE_cgbsvxx( int matrix_order, char fact, char trans,\n                            lapack_int n, lapack_int kl, lapack_int ku,\n                            lapack_int nrhs, lapack_complex_float* ab,\n                            lapack_int ldab, lapack_complex_float* afb,\n                            lapack_int ldafb, lapack_int* ipiv, char* equed,\n                            float* r, float* c, lapack_complex_float* b,\n                            lapack_int ldb, lapack_complex_float* x,\n                            lapack_int ldx, float* rcond, float* rpvgrw,\n                            float* berr, lapack_int n_err_bnds,\n                            float* err_bnds_norm, float* err_bnds_comp,\n                            lapack_int nparams, float* params );\nlapack_int LAPACKE_zgbsvxx( int matrix_order, char fact, char trans,\n                            lapack_int n, lapack_int kl, lapack_int ku,\n                            lapack_int nrhs, lapack_complex_double* ab,\n                            lapack_int ldab, lapack_complex_double* afb,\n                            lapack_int ldafb, lapack_int* ipiv, char* equed,\n                            double* r, double* c, lapack_complex_double* b,\n                            lapack_int ldb, lapack_complex_double* x,\n                            lapack_int ldx, double* rcond, double* rpvgrw,\n                            double* berr, lapack_int n_err_bnds,\n                            double* err_bnds_norm, double* err_bnds_comp,\n                            lapack_int nparams, double* params );\n\nlapack_int LAPACKE_sgbtrf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku, float* ab,\n                           lapack_int ldab, lapack_int* ipiv );\nlapack_int LAPACKE_dgbtrf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku, double* ab,\n                           lapack_int ldab, lapack_int* ipiv );\nlapack_int LAPACKE_cgbtrf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku,\n                           lapack_complex_float* ab, lapack_int ldab,\n                           lapack_int* ipiv );\nlapack_int LAPACKE_zgbtrf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku,\n                           lapack_complex_double* ab, lapack_int ldab,\n                           lapack_int* ipiv );\n\nlapack_int LAPACKE_sgbtrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int kl, lapack_int ku, lapack_int nrhs,\n                           const float* ab, lapack_int ldab,\n                           const lapack_int* ipiv, float* b, lapack_int ldb );\nlapack_int LAPACKE_dgbtrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int kl, lapack_int ku, lapack_int nrhs,\n                           const double* ab, lapack_int ldab,\n                           const lapack_int* ipiv, double* b, lapack_int ldb );\nlapack_int LAPACKE_cgbtrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int kl, lapack_int ku, lapack_int nrhs,\n                           const lapack_complex_float* ab, lapack_int ldab,\n                           const lapack_int* ipiv, lapack_complex_float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_zgbtrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int kl, lapack_int ku, lapack_int nrhs,\n                           const lapack_complex_double* ab, lapack_int ldab,\n                           const lapack_int* ipiv, lapack_complex_double* b,\n                           lapack_int ldb );\n\nlapack_int LAPACKE_sgebak( int matrix_order, char job, char side, lapack_int n,\n                           lapack_int ilo, lapack_int ihi, const float* scale,\n                           lapack_int m, float* v, lapack_int ldv );\nlapack_int LAPACKE_dgebak( int matrix_order, char job, char side, lapack_int n,\n                           lapack_int ilo, lapack_int ihi, const double* scale,\n                           lapack_int m, double* v, lapack_int ldv );\nlapack_int LAPACKE_cgebak( int matrix_order, char job, char side, lapack_int n,\n                           lapack_int ilo, lapack_int ihi, const float* scale,\n                           lapack_int m, lapack_complex_float* v,\n                           lapack_int ldv );\nlapack_int LAPACKE_zgebak( int matrix_order, char job, char side, lapack_int n,\n                           lapack_int ilo, lapack_int ihi, const double* scale,\n                           lapack_int m, lapack_complex_double* v,\n                           lapack_int ldv );\n\nlapack_int LAPACKE_sgebal( int matrix_order, char job, lapack_int n, float* a,\n                           lapack_int lda, lapack_int* ilo, lapack_int* ihi,\n                           float* scale );\nlapack_int LAPACKE_dgebal( int matrix_order, char job, lapack_int n, double* a,\n                           lapack_int lda, lapack_int* ilo, lapack_int* ihi,\n                           double* scale );\nlapack_int LAPACKE_cgebal( int matrix_order, char job, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int* ilo, lapack_int* ihi, float* scale );\nlapack_int LAPACKE_zgebal( int matrix_order, char job, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* ilo, lapack_int* ihi, double* scale );\n\nlapack_int LAPACKE_sgebrd( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, float* d, float* e,\n                           float* tauq, float* taup );\nlapack_int LAPACKE_dgebrd( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, double* d, double* e,\n                           double* tauq, double* taup );\nlapack_int LAPACKE_cgebrd( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda, float* d,\n                           float* e, lapack_complex_float* tauq,\n                           lapack_complex_float* taup );\nlapack_int LAPACKE_zgebrd( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda, double* d,\n                           double* e, lapack_complex_double* tauq,\n                           lapack_complex_double* taup );\n\nlapack_int LAPACKE_sgecon( int matrix_order, char norm, lapack_int n,\n                           const float* a, lapack_int lda, float anorm,\n                           float* rcond );\nlapack_int LAPACKE_dgecon( int matrix_order, char norm, lapack_int n,\n                           const double* a, lapack_int lda, double anorm,\n                           double* rcond );\nlapack_int LAPACKE_cgecon( int matrix_order, char norm, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           float anorm, float* rcond );\nlapack_int LAPACKE_zgecon( int matrix_order, char norm, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           double anorm, double* rcond );\n\nlapack_int LAPACKE_sgeequ( int matrix_order, lapack_int m, lapack_int n,\n                           const float* a, lapack_int lda, float* r, float* c,\n                           float* rowcnd, float* colcnd, float* amax );\nlapack_int LAPACKE_dgeequ( int matrix_order, lapack_int m, lapack_int n,\n                           const double* a, lapack_int lda, double* r,\n                           double* c, double* rowcnd, double* colcnd,\n                           double* amax );\nlapack_int LAPACKE_cgeequ( int matrix_order, lapack_int m, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           float* r, float* c, float* rowcnd, float* colcnd,\n                           float* amax );\nlapack_int LAPACKE_zgeequ( int matrix_order, lapack_int m, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           double* r, double* c, double* rowcnd, double* colcnd,\n                           double* amax );\n\nlapack_int LAPACKE_sgeequb( int matrix_order, lapack_int m, lapack_int n,\n                            const float* a, lapack_int lda, float* r, float* c,\n                            float* rowcnd, float* colcnd, float* amax );\nlapack_int LAPACKE_dgeequb( int matrix_order, lapack_int m, lapack_int n,\n                            const double* a, lapack_int lda, double* r,\n                            double* c, double* rowcnd, double* colcnd,\n                            double* amax );\nlapack_int LAPACKE_cgeequb( int matrix_order, lapack_int m, lapack_int n,\n                            const lapack_complex_float* a, lapack_int lda,\n                            float* r, float* c, float* rowcnd, float* colcnd,\n                            float* amax );\nlapack_int LAPACKE_zgeequb( int matrix_order, lapack_int m, lapack_int n,\n                            const lapack_complex_double* a, lapack_int lda,\n                            double* r, double* c, double* rowcnd,\n                            double* colcnd, double* amax );\n\nlapack_int LAPACKE_sgees( int matrix_order, char jobvs, char sort,\n                          LAPACK_S_SELECT2 select, lapack_int n, float* a,\n                          lapack_int lda, lapack_int* sdim, float* wr,\n                          float* wi, float* vs, lapack_int ldvs );\nlapack_int LAPACKE_dgees( int matrix_order, char jobvs, char sort,\n                          LAPACK_D_SELECT2 select, lapack_int n, double* a,\n                          lapack_int lda, lapack_int* sdim, double* wr,\n                          double* wi, double* vs, lapack_int ldvs );\nlapack_int LAPACKE_cgees( int matrix_order, char jobvs, char sort,\n                          LAPACK_C_SELECT1 select, lapack_int n,\n                          lapack_complex_float* a, lapack_int lda,\n                          lapack_int* sdim, lapack_complex_float* w,\n                          lapack_complex_float* vs, lapack_int ldvs );\nlapack_int LAPACKE_zgees( int matrix_order, char jobvs, char sort,\n                          LAPACK_Z_SELECT1 select, lapack_int n,\n                          lapack_complex_double* a, lapack_int lda,\n                          lapack_int* sdim, lapack_complex_double* w,\n                          lapack_complex_double* vs, lapack_int ldvs );\n\nlapack_int LAPACKE_sgeesx( int matrix_order, char jobvs, char sort,\n                           LAPACK_S_SELECT2 select, char sense, lapack_int n,\n                           float* a, lapack_int lda, lapack_int* sdim,\n                           float* wr, float* wi, float* vs, lapack_int ldvs,\n                           float* rconde, float* rcondv );\nlapack_int LAPACKE_dgeesx( int matrix_order, char jobvs, char sort,\n                           LAPACK_D_SELECT2 select, char sense, lapack_int n,\n                           double* a, lapack_int lda, lapack_int* sdim,\n                           double* wr, double* wi, double* vs, lapack_int ldvs,\n                           double* rconde, double* rcondv );\nlapack_int LAPACKE_cgeesx( int matrix_order, char jobvs, char sort,\n                           LAPACK_C_SELECT1 select, char sense, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int* sdim, lapack_complex_float* w,\n                           lapack_complex_float* vs, lapack_int ldvs,\n                           float* rconde, float* rcondv );\nlapack_int LAPACKE_zgeesx( int matrix_order, char jobvs, char sort,\n                           LAPACK_Z_SELECT1 select, char sense, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* sdim, lapack_complex_double* w,\n                           lapack_complex_double* vs, lapack_int ldvs,\n                           double* rconde, double* rcondv );\n\nlapack_int LAPACKE_sgeev( int matrix_order, char jobvl, char jobvr,\n                          lapack_int n, float* a, lapack_int lda, float* wr,\n                          float* wi, float* vl, lapack_int ldvl, float* vr,\n                          lapack_int ldvr );\nlapack_int LAPACKE_dgeev( int matrix_order, char jobvl, char jobvr,\n                          lapack_int n, double* a, lapack_int lda, double* wr,\n                          double* wi, double* vl, lapack_int ldvl, double* vr,\n                          lapack_int ldvr );\nlapack_int LAPACKE_cgeev( int matrix_order, char jobvl, char jobvr,\n                          lapack_int n, lapack_complex_float* a, lapack_int lda,\n                          lapack_complex_float* w, lapack_complex_float* vl,\n                          lapack_int ldvl, lapack_complex_float* vr,\n                          lapack_int ldvr );\nlapack_int LAPACKE_zgeev( int matrix_order, char jobvl, char jobvr,\n                          lapack_int n, lapack_complex_double* a,\n                          lapack_int lda, lapack_complex_double* w,\n                          lapack_complex_double* vl, lapack_int ldvl,\n                          lapack_complex_double* vr, lapack_int ldvr );\n\nlapack_int LAPACKE_sgeevx( int matrix_order, char balanc, char jobvl,\n                           char jobvr, char sense, lapack_int n, float* a,\n                           lapack_int lda, float* wr, float* wi, float* vl,\n                           lapack_int ldvl, float* vr, lapack_int ldvr,\n                           lapack_int* ilo, lapack_int* ihi, float* scale,\n                           float* abnrm, float* rconde, float* rcondv );\nlapack_int LAPACKE_dgeevx( int matrix_order, char balanc, char jobvl,\n                           char jobvr, char sense, lapack_int n, double* a,\n                           lapack_int lda, double* wr, double* wi, double* vl,\n                           lapack_int ldvl, double* vr, lapack_int ldvr,\n                           lapack_int* ilo, lapack_int* ihi, double* scale,\n                           double* abnrm, double* rconde, double* rcondv );\nlapack_int LAPACKE_cgeevx( int matrix_order, char balanc, char jobvl,\n                           char jobvr, char sense, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* w, lapack_complex_float* vl,\n                           lapack_int ldvl, lapack_complex_float* vr,\n                           lapack_int ldvr, lapack_int* ilo, lapack_int* ihi,\n                           float* scale, float* abnrm, float* rconde,\n                           float* rcondv );\nlapack_int LAPACKE_zgeevx( int matrix_order, char balanc, char jobvl,\n                           char jobvr, char sense, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* w, lapack_complex_double* vl,\n                           lapack_int ldvl, lapack_complex_double* vr,\n                           lapack_int ldvr, lapack_int* ilo, lapack_int* ihi,\n                           double* scale, double* abnrm, double* rconde,\n                           double* rcondv );\n\nlapack_int LAPACKE_sgehrd( int matrix_order, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, float* a, lapack_int lda,\n                           float* tau );\nlapack_int LAPACKE_dgehrd( int matrix_order, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, double* a, lapack_int lda,\n                           double* tau );\nlapack_int LAPACKE_cgehrd( int matrix_order, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* tau );\nlapack_int LAPACKE_zgehrd( int matrix_order, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* tau );\n\nlapack_int LAPACKE_sgejsv( int matrix_order, char joba, char jobu, char jobv,\n                           char jobr, char jobt, char jobp, lapack_int m,\n                           lapack_int n, float* a, lapack_int lda, float* sva,\n                           float* u, lapack_int ldu, float* v, lapack_int ldv,\n                           float* stat, lapack_int* istat );\nlapack_int LAPACKE_dgejsv( int matrix_order, char joba, char jobu, char jobv,\n                           char jobr, char jobt, char jobp, lapack_int m,\n                           lapack_int n, double* a, lapack_int lda, double* sva,\n                           double* u, lapack_int ldu, double* v, lapack_int ldv,\n                           double* stat, lapack_int* istat );\n\nlapack_int LAPACKE_sgelq2( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, float* tau );\nlapack_int LAPACKE_dgelq2( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, double* tau );\nlapack_int LAPACKE_cgelq2( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* tau );\nlapack_int LAPACKE_zgelq2( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* tau );\n\nlapack_int LAPACKE_sgelqf( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, float* tau );\nlapack_int LAPACKE_dgelqf( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, double* tau );\nlapack_int LAPACKE_cgelqf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* tau );\nlapack_int LAPACKE_zgelqf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* tau );\n\nlapack_int LAPACKE_sgels( int matrix_order, char trans, lapack_int m,\n                          lapack_int n, lapack_int nrhs, float* a,\n                          lapack_int lda, float* b, lapack_int ldb );\nlapack_int LAPACKE_dgels( int matrix_order, char trans, lapack_int m,\n                          lapack_int n, lapack_int nrhs, double* a,\n                          lapack_int lda, double* b, lapack_int ldb );\nlapack_int LAPACKE_cgels( int matrix_order, char trans, lapack_int m,\n                          lapack_int n, lapack_int nrhs,\n                          lapack_complex_float* a, lapack_int lda,\n                          lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zgels( int matrix_order, char trans, lapack_int m,\n                          lapack_int n, lapack_int nrhs,\n                          lapack_complex_double* a, lapack_int lda,\n                          lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_sgelsd( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, float* a, lapack_int lda, float* b,\n                           lapack_int ldb, float* s, float rcond,\n                           lapack_int* rank );\nlapack_int LAPACKE_dgelsd( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, double* a, lapack_int lda,\n                           double* b, lapack_int ldb, double* s, double rcond,\n                           lapack_int* rank );\nlapack_int LAPACKE_cgelsd( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* b,\n                           lapack_int ldb, float* s, float rcond,\n                           lapack_int* rank );\nlapack_int LAPACKE_zgelsd( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb, double* s, double rcond,\n                           lapack_int* rank );\n\nlapack_int LAPACKE_sgelss( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, float* a, lapack_int lda, float* b,\n                           lapack_int ldb, float* s, float rcond,\n                           lapack_int* rank );\nlapack_int LAPACKE_dgelss( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, double* a, lapack_int lda,\n                           double* b, lapack_int ldb, double* s, double rcond,\n                           lapack_int* rank );\nlapack_int LAPACKE_cgelss( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* b,\n                           lapack_int ldb, float* s, float rcond,\n                           lapack_int* rank );\nlapack_int LAPACKE_zgelss( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb, double* s, double rcond,\n                           lapack_int* rank );\n\nlapack_int LAPACKE_sgelsy( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, float* a, lapack_int lda, float* b,\n                           lapack_int ldb, lapack_int* jpvt, float rcond,\n                           lapack_int* rank );\nlapack_int LAPACKE_dgelsy( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, double* a, lapack_int lda,\n                           double* b, lapack_int ldb, lapack_int* jpvt,\n                           double rcond, lapack_int* rank );\nlapack_int LAPACKE_cgelsy( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* b,\n                           lapack_int ldb, lapack_int* jpvt, float rcond,\n                           lapack_int* rank );\nlapack_int LAPACKE_zgelsy( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb, lapack_int* jpvt, double rcond,\n                           lapack_int* rank );\n\nlapack_int LAPACKE_sgeqlf( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, float* tau );\nlapack_int LAPACKE_dgeqlf( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, double* tau );\nlapack_int LAPACKE_cgeqlf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* tau );\nlapack_int LAPACKE_zgeqlf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* tau );\n\nlapack_int LAPACKE_sgeqp3( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, lapack_int* jpvt,\n                           float* tau );\nlapack_int LAPACKE_dgeqp3( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, lapack_int* jpvt,\n                           double* tau );\nlapack_int LAPACKE_cgeqp3( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int* jpvt, lapack_complex_float* tau );\nlapack_int LAPACKE_zgeqp3( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* jpvt, lapack_complex_double* tau );\n\nlapack_int LAPACKE_sgeqpf( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, lapack_int* jpvt,\n                           float* tau );\nlapack_int LAPACKE_dgeqpf( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, lapack_int* jpvt,\n                           double* tau );\nlapack_int LAPACKE_cgeqpf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int* jpvt, lapack_complex_float* tau );\nlapack_int LAPACKE_zgeqpf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* jpvt, lapack_complex_double* tau );\n\nlapack_int LAPACKE_sgeqr2( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, float* tau );\nlapack_int LAPACKE_dgeqr2( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, double* tau );\nlapack_int LAPACKE_cgeqr2( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* tau );\nlapack_int LAPACKE_zgeqr2( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* tau );\n\nlapack_int LAPACKE_sgeqrf( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, float* tau );\nlapack_int LAPACKE_dgeqrf( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, double* tau );\nlapack_int LAPACKE_cgeqrf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* tau );\nlapack_int LAPACKE_zgeqrf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* tau );\n\nlapack_int LAPACKE_sgeqrfp( int matrix_order, lapack_int m, lapack_int n,\n                            float* a, lapack_int lda, float* tau );\nlapack_int LAPACKE_dgeqrfp( int matrix_order, lapack_int m, lapack_int n,\n                            double* a, lapack_int lda, double* tau );\nlapack_int LAPACKE_cgeqrfp( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_complex_float* a, lapack_int lda,\n                            lapack_complex_float* tau );\nlapack_int LAPACKE_zgeqrfp( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_complex_double* a, lapack_int lda,\n                            lapack_complex_double* tau );\n\nlapack_int LAPACKE_sgerfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const float* a, lapack_int lda,\n                           const float* af, lapack_int ldaf,\n                           const lapack_int* ipiv, const float* b,\n                           lapack_int ldb, float* x, lapack_int ldx,\n                           float* ferr, float* berr );\nlapack_int LAPACKE_dgerfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const double* a, lapack_int lda,\n                           const double* af, lapack_int ldaf,\n                           const lapack_int* ipiv, const double* b,\n                           lapack_int ldb, double* x, lapack_int ldx,\n                           double* ferr, double* berr );\nlapack_int LAPACKE_cgerfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* af,\n                           lapack_int ldaf, const lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zgerfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* af,\n                           lapack_int ldaf, const lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_sgerfsx( int matrix_order, char trans, char equed,\n                            lapack_int n, lapack_int nrhs, const float* a,\n                            lapack_int lda, const float* af, lapack_int ldaf,\n                            const lapack_int* ipiv, const float* r,\n                            const float* c, const float* b, lapack_int ldb,\n                            float* x, lapack_int ldx, float* rcond, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_dgerfsx( int matrix_order, char trans, char equed,\n                            lapack_int n, lapack_int nrhs, const double* a,\n                            lapack_int lda, const double* af, lapack_int ldaf,\n                            const lapack_int* ipiv, const double* r,\n                            const double* c, const double* b, lapack_int ldb,\n                            double* x, lapack_int ldx, double* rcond,\n                            double* berr, lapack_int n_err_bnds,\n                            double* err_bnds_norm, double* err_bnds_comp,\n                            lapack_int nparams, double* params );\nlapack_int LAPACKE_cgerfsx( int matrix_order, char trans, char equed,\n                            lapack_int n, lapack_int nrhs,\n                            const lapack_complex_float* a, lapack_int lda,\n                            const lapack_complex_float* af, lapack_int ldaf,\n                            const lapack_int* ipiv, const float* r,\n                            const float* c, const lapack_complex_float* b,\n                            lapack_int ldb, lapack_complex_float* x,\n                            lapack_int ldx, float* rcond, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_zgerfsx( int matrix_order, char trans, char equed,\n                            lapack_int n, lapack_int nrhs,\n                            const lapack_complex_double* a, lapack_int lda,\n                            const lapack_complex_double* af, lapack_int ldaf,\n                            const lapack_int* ipiv, const double* r,\n                            const double* c, const lapack_complex_double* b,\n                            lapack_int ldb, lapack_complex_double* x,\n                            lapack_int ldx, double* rcond, double* berr,\n                            lapack_int n_err_bnds, double* err_bnds_norm,\n                            double* err_bnds_comp, lapack_int nparams,\n                            double* params );\n\nlapack_int LAPACKE_sgerqf( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, float* tau );\nlapack_int LAPACKE_dgerqf( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, double* tau );\nlapack_int LAPACKE_cgerqf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* tau );\nlapack_int LAPACKE_zgerqf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* tau );\n\nlapack_int LAPACKE_sgesdd( int matrix_order, char jobz, lapack_int m,\n                           lapack_int n, float* a, lapack_int lda, float* s,\n                           float* u, lapack_int ldu, float* vt,\n                           lapack_int ldvt );\nlapack_int LAPACKE_dgesdd( int matrix_order, char jobz, lapack_int m,\n                           lapack_int n, double* a, lapack_int lda, double* s,\n                           double* u, lapack_int ldu, double* vt,\n                           lapack_int ldvt );\nlapack_int LAPACKE_cgesdd( int matrix_order, char jobz, lapack_int m,\n                           lapack_int n, lapack_complex_float* a,\n                           lapack_int lda, float* s, lapack_complex_float* u,\n                           lapack_int ldu, lapack_complex_float* vt,\n                           lapack_int ldvt );\nlapack_int LAPACKE_zgesdd( int matrix_order, char jobz, lapack_int m,\n                           lapack_int n, lapack_complex_double* a,\n                           lapack_int lda, double* s, lapack_complex_double* u,\n                           lapack_int ldu, lapack_complex_double* vt,\n                           lapack_int ldvt );\n\nlapack_int LAPACKE_sgesv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          float* a, lapack_int lda, lapack_int* ipiv, float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_dgesv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          double* a, lapack_int lda, lapack_int* ipiv,\n                          double* b, lapack_int ldb );\nlapack_int LAPACKE_cgesv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          lapack_complex_float* a, lapack_int lda,\n                          lapack_int* ipiv, lapack_complex_float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_zgesv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          lapack_complex_double* a, lapack_int lda,\n                          lapack_int* ipiv, lapack_complex_double* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_dsgesv( int matrix_order, lapack_int n, lapack_int nrhs,\n                           double* a, lapack_int lda, lapack_int* ipiv,\n                           double* b, lapack_int ldb, double* x, lapack_int ldx,\n                           lapack_int* iter );\nlapack_int LAPACKE_zcgesv( int matrix_order, lapack_int n, lapack_int nrhs,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* ipiv, lapack_complex_double* b,\n                           lapack_int ldb, lapack_complex_double* x,\n                           lapack_int ldx, lapack_int* iter );\n\nlapack_int LAPACKE_sgesvd( int matrix_order, char jobu, char jobvt,\n                           lapack_int m, lapack_int n, float* a, lapack_int lda,\n                           float* s, float* u, lapack_int ldu, float* vt,\n                           lapack_int ldvt, float* superb );\nlapack_int LAPACKE_dgesvd( int matrix_order, char jobu, char jobvt,\n                           lapack_int m, lapack_int n, double* a,\n                           lapack_int lda, double* s, double* u, lapack_int ldu,\n                           double* vt, lapack_int ldvt, double* superb );\nlapack_int LAPACKE_cgesvd( int matrix_order, char jobu, char jobvt,\n                           lapack_int m, lapack_int n, lapack_complex_float* a,\n                           lapack_int lda, float* s, lapack_complex_float* u,\n                           lapack_int ldu, lapack_complex_float* vt,\n                           lapack_int ldvt, float* superb );\nlapack_int LAPACKE_zgesvd( int matrix_order, char jobu, char jobvt,\n                           lapack_int m, lapack_int n, lapack_complex_double* a,\n                           lapack_int lda, double* s, lapack_complex_double* u,\n                           lapack_int ldu, lapack_complex_double* vt,\n                           lapack_int ldvt, double* superb );\n\nlapack_int LAPACKE_sgesvj( int matrix_order, char joba, char jobu, char jobv,\n                           lapack_int m, lapack_int n, float* a, lapack_int lda,\n                           float* sva, lapack_int mv, float* v, lapack_int ldv,\n                           float* stat );\nlapack_int LAPACKE_dgesvj( int matrix_order, char joba, char jobu, char jobv,\n                           lapack_int m, lapack_int n, double* a,\n                           lapack_int lda, double* sva, lapack_int mv,\n                           double* v, lapack_int ldv, double* stat );\n\nlapack_int LAPACKE_sgesvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int nrhs, float* a,\n                           lapack_int lda, float* af, lapack_int ldaf,\n                           lapack_int* ipiv, char* equed, float* r, float* c,\n                           float* b, lapack_int ldb, float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr,\n                           float* rpivot );\nlapack_int LAPACKE_dgesvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int nrhs, double* a,\n                           lapack_int lda, double* af, lapack_int ldaf,\n                           lapack_int* ipiv, char* equed, double* r, double* c,\n                           double* b, lapack_int ldb, double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr,\n                           double* rpivot );\nlapack_int LAPACKE_cgesvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int nrhs,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* af, lapack_int ldaf,\n                           lapack_int* ipiv, char* equed, float* r, float* c,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr,\n                           float* rpivot );\nlapack_int LAPACKE_zgesvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int nrhs,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* af, lapack_int ldaf,\n                           lapack_int* ipiv, char* equed, double* r, double* c,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr,\n                           double* rpivot );\n\nlapack_int LAPACKE_sgesvxx( int matrix_order, char fact, char trans,\n                            lapack_int n, lapack_int nrhs, float* a,\n                            lapack_int lda, float* af, lapack_int ldaf,\n                            lapack_int* ipiv, char* equed, float* r, float* c,\n                            float* b, lapack_int ldb, float* x, lapack_int ldx,\n                            float* rcond, float* rpvgrw, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_dgesvxx( int matrix_order, char fact, char trans,\n                            lapack_int n, lapack_int nrhs, double* a,\n                            lapack_int lda, double* af, lapack_int ldaf,\n                            lapack_int* ipiv, char* equed, double* r, double* c,\n                            double* b, lapack_int ldb, double* x,\n                            lapack_int ldx, double* rcond, double* rpvgrw,\n                            double* berr, lapack_int n_err_bnds,\n                            double* err_bnds_norm, double* err_bnds_comp,\n                            lapack_int nparams, double* params );\nlapack_int LAPACKE_cgesvxx( int matrix_order, char fact, char trans,\n                            lapack_int n, lapack_int nrhs,\n                            lapack_complex_float* a, lapack_int lda,\n                            lapack_complex_float* af, lapack_int ldaf,\n                            lapack_int* ipiv, char* equed, float* r, float* c,\n                            lapack_complex_float* b, lapack_int ldb,\n                            lapack_complex_float* x, lapack_int ldx,\n                            float* rcond, float* rpvgrw, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_zgesvxx( int matrix_order, char fact, char trans,\n                            lapack_int n, lapack_int nrhs,\n                            lapack_complex_double* a, lapack_int lda,\n                            lapack_complex_double* af, lapack_int ldaf,\n                            lapack_int* ipiv, char* equed, double* r, double* c,\n                            lapack_complex_double* b, lapack_int ldb,\n                            lapack_complex_double* x, lapack_int ldx,\n                            double* rcond, double* rpvgrw, double* berr,\n                            lapack_int n_err_bnds, double* err_bnds_norm,\n                            double* err_bnds_comp, lapack_int nparams,\n                            double* params );\n\nlapack_int LAPACKE_sgetf2( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, lapack_int* ipiv );\nlapack_int LAPACKE_dgetf2( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, lapack_int* ipiv );\nlapack_int LAPACKE_cgetf2( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int* ipiv );\nlapack_int LAPACKE_zgetf2( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* ipiv );\n\nlapack_int LAPACKE_sgetrf( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, lapack_int* ipiv );\nlapack_int LAPACKE_dgetrf( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, lapack_int* ipiv );\nlapack_int LAPACKE_cgetrf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int* ipiv );\nlapack_int LAPACKE_zgetrf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* ipiv );\n\nlapack_int LAPACKE_sgetri( int matrix_order, lapack_int n, float* a,\n                           lapack_int lda, const lapack_int* ipiv );\nlapack_int LAPACKE_dgetri( int matrix_order, lapack_int n, double* a,\n                           lapack_int lda, const lapack_int* ipiv );\nlapack_int LAPACKE_cgetri( int matrix_order, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           const lapack_int* ipiv );\nlapack_int LAPACKE_zgetri( int matrix_order, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           const lapack_int* ipiv );\n\nlapack_int LAPACKE_sgetrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const float* a, lapack_int lda,\n                           const lapack_int* ipiv, float* b, lapack_int ldb );\nlapack_int LAPACKE_dgetrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const double* a, lapack_int lda,\n                           const lapack_int* ipiv, double* b, lapack_int ldb );\nlapack_int LAPACKE_cgetrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* a,\n                           lapack_int lda, const lapack_int* ipiv,\n                           lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zgetrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* a,\n                           lapack_int lda, const lapack_int* ipiv,\n                           lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_sggbak( int matrix_order, char job, char side, lapack_int n,\n                           lapack_int ilo, lapack_int ihi, const float* lscale,\n                           const float* rscale, lapack_int m, float* v,\n                           lapack_int ldv );\nlapack_int LAPACKE_dggbak( int matrix_order, char job, char side, lapack_int n,\n                           lapack_int ilo, lapack_int ihi, const double* lscale,\n                           const double* rscale, lapack_int m, double* v,\n                           lapack_int ldv );\nlapack_int LAPACKE_cggbak( int matrix_order, char job, char side, lapack_int n,\n                           lapack_int ilo, lapack_int ihi, const float* lscale,\n                           const float* rscale, lapack_int m,\n                           lapack_complex_float* v, lapack_int ldv );\nlapack_int LAPACKE_zggbak( int matrix_order, char job, char side, lapack_int n,\n                           lapack_int ilo, lapack_int ihi, const double* lscale,\n                           const double* rscale, lapack_int m,\n                           lapack_complex_double* v, lapack_int ldv );\n\nlapack_int LAPACKE_sggbal( int matrix_order, char job, lapack_int n, float* a,\n                           lapack_int lda, float* b, lapack_int ldb,\n                           lapack_int* ilo, lapack_int* ihi, float* lscale,\n                           float* rscale );\nlapack_int LAPACKE_dggbal( int matrix_order, char job, lapack_int n, double* a,\n                           lapack_int lda, double* b, lapack_int ldb,\n                           lapack_int* ilo, lapack_int* ihi, double* lscale,\n                           double* rscale );\nlapack_int LAPACKE_cggbal( int matrix_order, char job, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_int* ilo, lapack_int* ihi, float* lscale,\n                           float* rscale );\nlapack_int LAPACKE_zggbal( int matrix_order, char job, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_int* ilo, lapack_int* ihi, double* lscale,\n                           double* rscale );\n\nlapack_int LAPACKE_sgges( int matrix_order, char jobvsl, char jobvsr, char sort,\n                          LAPACK_S_SELECT3 selctg, lapack_int n, float* a,\n                          lapack_int lda, float* b, lapack_int ldb,\n                          lapack_int* sdim, float* alphar, float* alphai,\n                          float* beta, float* vsl, lapack_int ldvsl, float* vsr,\n                          lapack_int ldvsr );\nlapack_int LAPACKE_dgges( int matrix_order, char jobvsl, char jobvsr, char sort,\n                          LAPACK_D_SELECT3 selctg, lapack_int n, double* a,\n                          lapack_int lda, double* b, lapack_int ldb,\n                          lapack_int* sdim, double* alphar, double* alphai,\n                          double* beta, double* vsl, lapack_int ldvsl,\n                          double* vsr, lapack_int ldvsr );\nlapack_int LAPACKE_cgges( int matrix_order, char jobvsl, char jobvsr, char sort,\n                          LAPACK_C_SELECT2 selctg, lapack_int n,\n                          lapack_complex_float* a, lapack_int lda,\n                          lapack_complex_float* b, lapack_int ldb,\n                          lapack_int* sdim, lapack_complex_float* alpha,\n                          lapack_complex_float* beta, lapack_complex_float* vsl,\n                          lapack_int ldvsl, lapack_complex_float* vsr,\n                          lapack_int ldvsr );\nlapack_int LAPACKE_zgges( int matrix_order, char jobvsl, char jobvsr, char sort,\n                          LAPACK_Z_SELECT2 selctg, lapack_int n,\n                          lapack_complex_double* a, lapack_int lda,\n                          lapack_complex_double* b, lapack_int ldb,\n                          lapack_int* sdim, lapack_complex_double* alpha,\n                          lapack_complex_double* beta,\n                          lapack_complex_double* vsl, lapack_int ldvsl,\n                          lapack_complex_double* vsr, lapack_int ldvsr );\n\nlapack_int LAPACKE_sggesx( int matrix_order, char jobvsl, char jobvsr,\n                           char sort, LAPACK_S_SELECT3 selctg, char sense,\n                           lapack_int n, float* a, lapack_int lda, float* b,\n                           lapack_int ldb, lapack_int* sdim, float* alphar,\n                           float* alphai, float* beta, float* vsl,\n                           lapack_int ldvsl, float* vsr, lapack_int ldvsr,\n                           float* rconde, float* rcondv );\nlapack_int LAPACKE_dggesx( int matrix_order, char jobvsl, char jobvsr,\n                           char sort, LAPACK_D_SELECT3 selctg, char sense,\n                           lapack_int n, double* a, lapack_int lda, double* b,\n                           lapack_int ldb, lapack_int* sdim, double* alphar,\n                           double* alphai, double* beta, double* vsl,\n                           lapack_int ldvsl, double* vsr, lapack_int ldvsr,\n                           double* rconde, double* rcondv );\nlapack_int LAPACKE_cggesx( int matrix_order, char jobvsl, char jobvsr,\n                           char sort, LAPACK_C_SELECT2 selctg, char sense,\n                           lapack_int n, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* b,\n                           lapack_int ldb, lapack_int* sdim,\n                           lapack_complex_float* alpha,\n                           lapack_complex_float* beta,\n                           lapack_complex_float* vsl, lapack_int ldvsl,\n                           lapack_complex_float* vsr, lapack_int ldvsr,\n                           float* rconde, float* rcondv );\nlapack_int LAPACKE_zggesx( int matrix_order, char jobvsl, char jobvsr,\n                           char sort, LAPACK_Z_SELECT2 selctg, char sense,\n                           lapack_int n, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb, lapack_int* sdim,\n                           lapack_complex_double* alpha,\n                           lapack_complex_double* beta,\n                           lapack_complex_double* vsl, lapack_int ldvsl,\n                           lapack_complex_double* vsr, lapack_int ldvsr,\n                           double* rconde, double* rcondv );\n\nlapack_int LAPACKE_sggev( int matrix_order, char jobvl, char jobvr,\n                          lapack_int n, float* a, lapack_int lda, float* b,\n                          lapack_int ldb, float* alphar, float* alphai,\n                          float* beta, float* vl, lapack_int ldvl, float* vr,\n                          lapack_int ldvr );\nlapack_int LAPACKE_dggev( int matrix_order, char jobvl, char jobvr,\n                          lapack_int n, double* a, lapack_int lda, double* b,\n                          lapack_int ldb, double* alphar, double* alphai,\n                          double* beta, double* vl, lapack_int ldvl, double* vr,\n                          lapack_int ldvr );\nlapack_int LAPACKE_cggev( int matrix_order, char jobvl, char jobvr,\n                          lapack_int n, lapack_complex_float* a, lapack_int lda,\n                          lapack_complex_float* b, lapack_int ldb,\n                          lapack_complex_float* alpha,\n                          lapack_complex_float* beta, lapack_complex_float* vl,\n                          lapack_int ldvl, lapack_complex_float* vr,\n                          lapack_int ldvr );\nlapack_int LAPACKE_zggev( int matrix_order, char jobvl, char jobvr,\n                          lapack_int n, lapack_complex_double* a,\n                          lapack_int lda, lapack_complex_double* b,\n                          lapack_int ldb, lapack_complex_double* alpha,\n                          lapack_complex_double* beta,\n                          lapack_complex_double* vl, lapack_int ldvl,\n                          lapack_complex_double* vr, lapack_int ldvr );\n\nlapack_int LAPACKE_sggevx( int matrix_order, char balanc, char jobvl,\n                           char jobvr, char sense, lapack_int n, float* a,\n                           lapack_int lda, float* b, lapack_int ldb,\n                           float* alphar, float* alphai, float* beta, float* vl,\n                           lapack_int ldvl, float* vr, lapack_int ldvr,\n                           lapack_int* ilo, lapack_int* ihi, float* lscale,\n                           float* rscale, float* abnrm, float* bbnrm,\n                           float* rconde, float* rcondv );\nlapack_int LAPACKE_dggevx( int matrix_order, char balanc, char jobvl,\n                           char jobvr, char sense, lapack_int n, double* a,\n                           lapack_int lda, double* b, lapack_int ldb,\n                           double* alphar, double* alphai, double* beta,\n                           double* vl, lapack_int ldvl, double* vr,\n                           lapack_int ldvr, lapack_int* ilo, lapack_int* ihi,\n                           double* lscale, double* rscale, double* abnrm,\n                           double* bbnrm, double* rconde, double* rcondv );\nlapack_int LAPACKE_cggevx( int matrix_order, char balanc, char jobvl,\n                           char jobvr, char sense, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* alpha,\n                           lapack_complex_float* beta, lapack_complex_float* vl,\n                           lapack_int ldvl, lapack_complex_float* vr,\n                           lapack_int ldvr, lapack_int* ilo, lapack_int* ihi,\n                           float* lscale, float* rscale, float* abnrm,\n                           float* bbnrm, float* rconde, float* rcondv );\nlapack_int LAPACKE_zggevx( int matrix_order, char balanc, char jobvl,\n                           char jobvr, char sense, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* alpha,\n                           lapack_complex_double* beta,\n                           lapack_complex_double* vl, lapack_int ldvl,\n                           lapack_complex_double* vr, lapack_int ldvr,\n                           lapack_int* ilo, lapack_int* ihi, double* lscale,\n                           double* rscale, double* abnrm, double* bbnrm,\n                           double* rconde, double* rcondv );\n\nlapack_int LAPACKE_sggglm( int matrix_order, lapack_int n, lapack_int m,\n                           lapack_int p, float* a, lapack_int lda, float* b,\n                           lapack_int ldb, float* d, float* x, float* y );\nlapack_int LAPACKE_dggglm( int matrix_order, lapack_int n, lapack_int m,\n                           lapack_int p, double* a, lapack_int lda, double* b,\n                           lapack_int ldb, double* d, double* x, double* y );\nlapack_int LAPACKE_cggglm( int matrix_order, lapack_int n, lapack_int m,\n                           lapack_int p, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* b,\n                           lapack_int ldb, lapack_complex_float* d,\n                           lapack_complex_float* x, lapack_complex_float* y );\nlapack_int LAPACKE_zggglm( int matrix_order, lapack_int n, lapack_int m,\n                           lapack_int p, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb, lapack_complex_double* d,\n                           lapack_complex_double* x, lapack_complex_double* y );\n\nlapack_int LAPACKE_sgghrd( int matrix_order, char compq, char compz,\n                           lapack_int n, lapack_int ilo, lapack_int ihi,\n                           float* a, lapack_int lda, float* b, lapack_int ldb,\n                           float* q, lapack_int ldq, float* z, lapack_int ldz );\nlapack_int LAPACKE_dgghrd( int matrix_order, char compq, char compz,\n                           lapack_int n, lapack_int ilo, lapack_int ihi,\n                           double* a, lapack_int lda, double* b, lapack_int ldb,\n                           double* q, lapack_int ldq, double* z,\n                           lapack_int ldz );\nlapack_int LAPACKE_cgghrd( int matrix_order, char compq, char compz,\n                           lapack_int n, lapack_int ilo, lapack_int ihi,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* q, lapack_int ldq,\n                           lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zgghrd( int matrix_order, char compq, char compz,\n                           lapack_int n, lapack_int ilo, lapack_int ihi,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* q, lapack_int ldq,\n                           lapack_complex_double* z, lapack_int ldz );\n\nlapack_int LAPACKE_sgglse( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int p, float* a, lapack_int lda, float* b,\n                           lapack_int ldb, float* c, float* d, float* x );\nlapack_int LAPACKE_dgglse( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int p, double* a, lapack_int lda, double* b,\n                           lapack_int ldb, double* c, double* d, double* x );\nlapack_int LAPACKE_cgglse( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int p, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* b,\n                           lapack_int ldb, lapack_complex_float* c,\n                           lapack_complex_float* d, lapack_complex_float* x );\nlapack_int LAPACKE_zgglse( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int p, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb, lapack_complex_double* c,\n                           lapack_complex_double* d, lapack_complex_double* x );\n\nlapack_int LAPACKE_sggqrf( int matrix_order, lapack_int n, lapack_int m,\n                           lapack_int p, float* a, lapack_int lda, float* taua,\n                           float* b, lapack_int ldb, float* taub );\nlapack_int LAPACKE_dggqrf( int matrix_order, lapack_int n, lapack_int m,\n                           lapack_int p, double* a, lapack_int lda,\n                           double* taua, double* b, lapack_int ldb,\n                           double* taub );\nlapack_int LAPACKE_cggqrf( int matrix_order, lapack_int n, lapack_int m,\n                           lapack_int p, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* taua,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* taub );\nlapack_int LAPACKE_zggqrf( int matrix_order, lapack_int n, lapack_int m,\n                           lapack_int p, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* taua,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* taub );\n\nlapack_int LAPACKE_sggrqf( int matrix_order, lapack_int m, lapack_int p,\n                           lapack_int n, float* a, lapack_int lda, float* taua,\n                           float* b, lapack_int ldb, float* taub );\nlapack_int LAPACKE_dggrqf( int matrix_order, lapack_int m, lapack_int p,\n                           lapack_int n, double* a, lapack_int lda,\n                           double* taua, double* b, lapack_int ldb,\n                           double* taub );\nlapack_int LAPACKE_cggrqf( int matrix_order, lapack_int m, lapack_int p,\n                           lapack_int n, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* taua,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* taub );\nlapack_int LAPACKE_zggrqf( int matrix_order, lapack_int m, lapack_int p,\n                           lapack_int n, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* taua,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* taub );\n\nlapack_int LAPACKE_sggsvd( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int n, lapack_int p,\n                           lapack_int* k, lapack_int* l, float* a,\n                           lapack_int lda, float* b, lapack_int ldb,\n                           float* alpha, float* beta, float* u, lapack_int ldu,\n                           float* v, lapack_int ldv, float* q, lapack_int ldq,\n                           lapack_int* iwork );\nlapack_int LAPACKE_dggsvd( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int n, lapack_int p,\n                           lapack_int* k, lapack_int* l, double* a,\n                           lapack_int lda, double* b, lapack_int ldb,\n                           double* alpha, double* beta, double* u,\n                           lapack_int ldu, double* v, lapack_int ldv, double* q,\n                           lapack_int ldq, lapack_int* iwork );\nlapack_int LAPACKE_cggsvd( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int n, lapack_int p,\n                           lapack_int* k, lapack_int* l,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* b, lapack_int ldb,\n                           float* alpha, float* beta, lapack_complex_float* u,\n                           lapack_int ldu, lapack_complex_float* v,\n                           lapack_int ldv, lapack_complex_float* q,\n                           lapack_int ldq, lapack_int* iwork );\nlapack_int LAPACKE_zggsvd( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int n, lapack_int p,\n                           lapack_int* k, lapack_int* l,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb,\n                           double* alpha, double* beta,\n                           lapack_complex_double* u, lapack_int ldu,\n                           lapack_complex_double* v, lapack_int ldv,\n                           lapack_complex_double* q, lapack_int ldq,\n                           lapack_int* iwork );\n\nlapack_int LAPACKE_sggsvp( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int p, lapack_int n, float* a,\n                           lapack_int lda, float* b, lapack_int ldb, float tola,\n                           float tolb, lapack_int* k, lapack_int* l, float* u,\n                           lapack_int ldu, float* v, lapack_int ldv, float* q,\n                           lapack_int ldq );\nlapack_int LAPACKE_dggsvp( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int p, lapack_int n, double* a,\n                           lapack_int lda, double* b, lapack_int ldb,\n                           double tola, double tolb, lapack_int* k,\n                           lapack_int* l, double* u, lapack_int ldu, double* v,\n                           lapack_int ldv, double* q, lapack_int ldq );\nlapack_int LAPACKE_cggsvp( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int p, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* b, lapack_int ldb, float tola,\n                           float tolb, lapack_int* k, lapack_int* l,\n                           lapack_complex_float* u, lapack_int ldu,\n                           lapack_complex_float* v, lapack_int ldv,\n                           lapack_complex_float* q, lapack_int ldq );\nlapack_int LAPACKE_zggsvp( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int p, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb,\n                           double tola, double tolb, lapack_int* k,\n                           lapack_int* l, lapack_complex_double* u,\n                           lapack_int ldu, lapack_complex_double* v,\n                           lapack_int ldv, lapack_complex_double* q,\n                           lapack_int ldq );\n\nlapack_int LAPACKE_sgtcon( char norm, lapack_int n, const float* dl,\n                           const float* d, const float* du, const float* du2,\n                           const lapack_int* ipiv, float anorm, float* rcond );\nlapack_int LAPACKE_dgtcon( char norm, lapack_int n, const double* dl,\n                           const double* d, const double* du, const double* du2,\n                           const lapack_int* ipiv, double anorm,\n                           double* rcond );\nlapack_int LAPACKE_cgtcon( char norm, lapack_int n,\n                           const lapack_complex_float* dl,\n                           const lapack_complex_float* d,\n                           const lapack_complex_float* du,\n                           const lapack_complex_float* du2,\n                           const lapack_int* ipiv, float anorm, float* rcond );\nlapack_int LAPACKE_zgtcon( char norm, lapack_int n,\n                           const lapack_complex_double* dl,\n                           const lapack_complex_double* d,\n                           const lapack_complex_double* du,\n                           const lapack_complex_double* du2,\n                           const lapack_int* ipiv, double anorm,\n                           double* rcond );\n\nlapack_int LAPACKE_sgtrfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const float* dl, const float* d,\n                           const float* du, const float* dlf, const float* df,\n                           const float* duf, const float* du2,\n                           const lapack_int* ipiv, const float* b,\n                           lapack_int ldb, float* x, lapack_int ldx,\n                           float* ferr, float* berr );\nlapack_int LAPACKE_dgtrfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const double* dl, const double* d,\n                           const double* du, const double* dlf,\n                           const double* df, const double* duf,\n                           const double* du2, const lapack_int* ipiv,\n                           const double* b, lapack_int ldb, double* x,\n                           lapack_int ldx, double* ferr, double* berr );\nlapack_int LAPACKE_cgtrfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* dl,\n                           const lapack_complex_float* d,\n                           const lapack_complex_float* du,\n                           const lapack_complex_float* dlf,\n                           const lapack_complex_float* df,\n                           const lapack_complex_float* duf,\n                           const lapack_complex_float* du2,\n                           const lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zgtrfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* dl,\n                           const lapack_complex_double* d,\n                           const lapack_complex_double* du,\n                           const lapack_complex_double* dlf,\n                           const lapack_complex_double* df,\n                           const lapack_complex_double* duf,\n                           const lapack_complex_double* du2,\n                           const lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_sgtsv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          float* dl, float* d, float* du, float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_dgtsv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          double* dl, double* d, double* du, double* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_cgtsv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          lapack_complex_float* dl, lapack_complex_float* d,\n                          lapack_complex_float* du, lapack_complex_float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_zgtsv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          lapack_complex_double* dl, lapack_complex_double* d,\n                          lapack_complex_double* du, lapack_complex_double* b,\n                          lapack_int ldb );\n\nlapack_int LAPACKE_sgtsvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int nrhs, const float* dl,\n                           const float* d, const float* du, float* dlf,\n                           float* df, float* duf, float* du2, lapack_int* ipiv,\n                           const float* b, lapack_int ldb, float* x,\n                           lapack_int ldx, float* rcond, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_dgtsvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int nrhs, const double* dl,\n                           const double* d, const double* du, double* dlf,\n                           double* df, double* duf, double* du2,\n                           lapack_int* ipiv, const double* b, lapack_int ldb,\n                           double* x, lapack_int ldx, double* rcond,\n                           double* ferr, double* berr );\nlapack_int LAPACKE_cgtsvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_float* dl,\n                           const lapack_complex_float* d,\n                           const lapack_complex_float* du,\n                           lapack_complex_float* dlf, lapack_complex_float* df,\n                           lapack_complex_float* duf, lapack_complex_float* du2,\n                           lapack_int* ipiv, const lapack_complex_float* b,\n                           lapack_int ldb, lapack_complex_float* x,\n                           lapack_int ldx, float* rcond, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zgtsvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_double* dl,\n                           const lapack_complex_double* d,\n                           const lapack_complex_double* du,\n                           lapack_complex_double* dlf,\n                           lapack_complex_double* df,\n                           lapack_complex_double* duf,\n                           lapack_complex_double* du2, lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr );\n\nlapack_int LAPACKE_sgttrf( lapack_int n, float* dl, float* d, float* du,\n                           float* du2, lapack_int* ipiv );\nlapack_int LAPACKE_dgttrf( lapack_int n, double* dl, double* d, double* du,\n                           double* du2, lapack_int* ipiv );\nlapack_int LAPACKE_cgttrf( lapack_int n, lapack_complex_float* dl,\n                           lapack_complex_float* d, lapack_complex_float* du,\n                           lapack_complex_float* du2, lapack_int* ipiv );\nlapack_int LAPACKE_zgttrf( lapack_int n, lapack_complex_double* dl,\n                           lapack_complex_double* d, lapack_complex_double* du,\n                           lapack_complex_double* du2, lapack_int* ipiv );\n\nlapack_int LAPACKE_sgttrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const float* dl, const float* d,\n                           const float* du, const float* du2,\n                           const lapack_int* ipiv, float* b, lapack_int ldb );\nlapack_int LAPACKE_dgttrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const double* dl, const double* d,\n                           const double* du, const double* du2,\n                           const lapack_int* ipiv, double* b, lapack_int ldb );\nlapack_int LAPACKE_cgttrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* dl,\n                           const lapack_complex_float* d,\n                           const lapack_complex_float* du,\n                           const lapack_complex_float* du2,\n                           const lapack_int* ipiv, lapack_complex_float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_zgttrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* dl,\n                           const lapack_complex_double* d,\n                           const lapack_complex_double* du,\n                           const lapack_complex_double* du2,\n                           const lapack_int* ipiv, lapack_complex_double* b,\n                           lapack_int ldb );\n\nlapack_int LAPACKE_chbev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_int kd, lapack_complex_float* ab,\n                          lapack_int ldab, float* w, lapack_complex_float* z,\n                          lapack_int ldz );\nlapack_int LAPACKE_zhbev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_int kd, lapack_complex_double* ab,\n                          lapack_int ldab, double* w, lapack_complex_double* z,\n                          lapack_int ldz );\n\nlapack_int LAPACKE_chbevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_int kd, lapack_complex_float* ab,\n                           lapack_int ldab, float* w, lapack_complex_float* z,\n                           lapack_int ldz );\nlapack_int LAPACKE_zhbevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_int kd, lapack_complex_double* ab,\n                           lapack_int ldab, double* w, lapack_complex_double* z,\n                           lapack_int ldz );\n\nlapack_int LAPACKE_chbevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_int kd,\n                           lapack_complex_float* ab, lapack_int ldab,\n                           lapack_complex_float* q, lapack_int ldq, float vl,\n                           float vu, lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, lapack_complex_float* z,\n                           lapack_int ldz, lapack_int* ifail );\nlapack_int LAPACKE_zhbevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_int kd,\n                           lapack_complex_double* ab, lapack_int ldab,\n                           lapack_complex_double* q, lapack_int ldq, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w,\n                           lapack_complex_double* z, lapack_int ldz,\n                           lapack_int* ifail );\n\nlapack_int LAPACKE_chbgst( int matrix_order, char vect, char uplo, lapack_int n,\n                           lapack_int ka, lapack_int kb,\n                           lapack_complex_float* ab, lapack_int ldab,\n                           const lapack_complex_float* bb, lapack_int ldbb,\n                           lapack_complex_float* x, lapack_int ldx );\nlapack_int LAPACKE_zhbgst( int matrix_order, char vect, char uplo, lapack_int n,\n                           lapack_int ka, lapack_int kb,\n                           lapack_complex_double* ab, lapack_int ldab,\n                           const lapack_complex_double* bb, lapack_int ldbb,\n                           lapack_complex_double* x, lapack_int ldx );\n\nlapack_int LAPACKE_chbgv( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_int ka, lapack_int kb,\n                          lapack_complex_float* ab, lapack_int ldab,\n                          lapack_complex_float* bb, lapack_int ldbb, float* w,\n                          lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zhbgv( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_int ka, lapack_int kb,\n                          lapack_complex_double* ab, lapack_int ldab,\n                          lapack_complex_double* bb, lapack_int ldbb, double* w,\n                          lapack_complex_double* z, lapack_int ldz );\n\nlapack_int LAPACKE_chbgvd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_int ka, lapack_int kb,\n                           lapack_complex_float* ab, lapack_int ldab,\n                           lapack_complex_float* bb, lapack_int ldbb, float* w,\n                           lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zhbgvd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_int ka, lapack_int kb,\n                           lapack_complex_double* ab, lapack_int ldab,\n                           lapack_complex_double* bb, lapack_int ldbb,\n                           double* w, lapack_complex_double* z,\n                           lapack_int ldz );\n\nlapack_int LAPACKE_chbgvx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_int ka, lapack_int kb,\n                           lapack_complex_float* ab, lapack_int ldab,\n                           lapack_complex_float* bb, lapack_int ldbb,\n                           lapack_complex_float* q, lapack_int ldq, float vl,\n                           float vu, lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, lapack_complex_float* z,\n                           lapack_int ldz, lapack_int* ifail );\nlapack_int LAPACKE_zhbgvx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_int ka, lapack_int kb,\n                           lapack_complex_double* ab, lapack_int ldab,\n                           lapack_complex_double* bb, lapack_int ldbb,\n                           lapack_complex_double* q, lapack_int ldq, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w,\n                           lapack_complex_double* z, lapack_int ldz,\n                           lapack_int* ifail );\n\nlapack_int LAPACKE_chbtrd( int matrix_order, char vect, char uplo, lapack_int n,\n                           lapack_int kd, lapack_complex_float* ab,\n                           lapack_int ldab, float* d, float* e,\n                           lapack_complex_float* q, lapack_int ldq );\nlapack_int LAPACKE_zhbtrd( int matrix_order, char vect, char uplo, lapack_int n,\n                           lapack_int kd, lapack_complex_double* ab,\n                           lapack_int ldab, double* d, double* e,\n                           lapack_complex_double* q, lapack_int ldq );\n\nlapack_int LAPACKE_checon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_int* ipiv, float anorm, float* rcond );\nlapack_int LAPACKE_zhecon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_int* ipiv, double anorm,\n                           double* rcond );\n\nlapack_int LAPACKE_cheequb( int matrix_order, char uplo, lapack_int n,\n                            const lapack_complex_float* a, lapack_int lda,\n                            float* s, float* scond, float* amax );\nlapack_int LAPACKE_zheequb( int matrix_order, char uplo, lapack_int n,\n                            const lapack_complex_double* a, lapack_int lda,\n                            double* s, double* scond, double* amax );\n\nlapack_int LAPACKE_cheev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_complex_float* a, lapack_int lda, float* w );\nlapack_int LAPACKE_zheev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_complex_double* a, lapack_int lda, double* w );\n\nlapack_int LAPACKE_cheevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda, float* w );\nlapack_int LAPACKE_zheevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           double* w );\n\nlapack_int LAPACKE_cheevr( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_complex_float* a,\n                           lapack_int lda, float vl, float vu, lapack_int il,\n                           lapack_int iu, float abstol, lapack_int* m, float* w,\n                           lapack_complex_float* z, lapack_int ldz,\n                           lapack_int* isuppz );\nlapack_int LAPACKE_zheevr( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_complex_double* a,\n                           lapack_int lda, double vl, double vu, lapack_int il,\n                           lapack_int iu, double abstol, lapack_int* m,\n                           double* w, lapack_complex_double* z, lapack_int ldz,\n                           lapack_int* isuppz );\n\nlapack_int LAPACKE_cheevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_complex_float* a,\n                           lapack_int lda, float vl, float vu, lapack_int il,\n                           lapack_int iu, float abstol, lapack_int* m, float* w,\n                           lapack_complex_float* z, lapack_int ldz,\n                           lapack_int* ifail );\nlapack_int LAPACKE_zheevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_complex_double* a,\n                           lapack_int lda, double vl, double vu, lapack_int il,\n                           lapack_int iu, double abstol, lapack_int* m,\n                           double* w, lapack_complex_double* z, lapack_int ldz,\n                           lapack_int* ifail );\n\nlapack_int LAPACKE_chegst( int matrix_order, lapack_int itype, char uplo,\n                           lapack_int n, lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_zhegst( int matrix_order, lapack_int itype, char uplo,\n                           lapack_int n, lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* b,\n                           lapack_int ldb );\n\nlapack_int LAPACKE_chegv( int matrix_order, lapack_int itype, char jobz,\n                          char uplo, lapack_int n, lapack_complex_float* a,\n                          lapack_int lda, lapack_complex_float* b,\n                          lapack_int ldb, float* w );\nlapack_int LAPACKE_zhegv( int matrix_order, lapack_int itype, char jobz,\n                          char uplo, lapack_int n, lapack_complex_double* a,\n                          lapack_int lda, lapack_complex_double* b,\n                          lapack_int ldb, double* w );\n\nlapack_int LAPACKE_chegvd( int matrix_order, lapack_int itype, char jobz,\n                           char uplo, lapack_int n, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* b,\n                           lapack_int ldb, float* w );\nlapack_int LAPACKE_zhegvd( int matrix_order, lapack_int itype, char jobz,\n                           char uplo, lapack_int n, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb, double* w );\n\nlapack_int LAPACKE_chegvx( int matrix_order, lapack_int itype, char jobz,\n                           char range, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* b, lapack_int ldb, float vl,\n                           float vu, lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, lapack_complex_float* z,\n                           lapack_int ldz, lapack_int* ifail );\nlapack_int LAPACKE_zhegvx( int matrix_order, lapack_int itype, char jobz,\n                           char range, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w,\n                           lapack_complex_double* z, lapack_int ldz,\n                           lapack_int* ifail );\n\nlapack_int LAPACKE_cherfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* af,\n                           lapack_int ldaf, const lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zherfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* af,\n                           lapack_int ldaf, const lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_cherfsx( int matrix_order, char uplo, char equed,\n                            lapack_int n, lapack_int nrhs,\n                            const lapack_complex_float* a, lapack_int lda,\n                            const lapack_complex_float* af, lapack_int ldaf,\n                            const lapack_int* ipiv, const float* s,\n                            const lapack_complex_float* b, lapack_int ldb,\n                            lapack_complex_float* x, lapack_int ldx,\n                            float* rcond, float* berr, lapack_int n_err_bnds,\n                            float* err_bnds_norm, float* err_bnds_comp,\n                            lapack_int nparams, float* params );\nlapack_int LAPACKE_zherfsx( int matrix_order, char uplo, char equed,\n                            lapack_int n, lapack_int nrhs,\n                            const lapack_complex_double* a, lapack_int lda,\n                            const lapack_complex_double* af, lapack_int ldaf,\n                            const lapack_int* ipiv, const double* s,\n                            const lapack_complex_double* b, lapack_int ldb,\n                            lapack_complex_double* x, lapack_int ldx,\n                            double* rcond, double* berr, lapack_int n_err_bnds,\n                            double* err_bnds_norm, double* err_bnds_comp,\n                            lapack_int nparams, double* params );\n\nlapack_int LAPACKE_chesv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_float* a,\n                          lapack_int lda, lapack_int* ipiv,\n                          lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zhesv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_double* a,\n                          lapack_int lda, lapack_int* ipiv,\n                          lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_chesvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* af,\n                           lapack_int ldaf, lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr );\nlapack_int LAPACKE_zhesvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* af,\n                           lapack_int ldaf, lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr );\n\nlapack_int LAPACKE_chesvxx( int matrix_order, char fact, char uplo,\n                            lapack_int n, lapack_int nrhs,\n                            lapack_complex_float* a, lapack_int lda,\n                            lapack_complex_float* af, lapack_int ldaf,\n                            lapack_int* ipiv, char* equed, float* s,\n                            lapack_complex_float* b, lapack_int ldb,\n                            lapack_complex_float* x, lapack_int ldx,\n                            float* rcond, float* rpvgrw, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_zhesvxx( int matrix_order, char fact, char uplo,\n                            lapack_int n, lapack_int nrhs,\n                            lapack_complex_double* a, lapack_int lda,\n                            lapack_complex_double* af, lapack_int ldaf,\n                            lapack_int* ipiv, char* equed, double* s,\n                            lapack_complex_double* b, lapack_int ldb,\n                            lapack_complex_double* x, lapack_int ldx,\n                            double* rcond, double* rpvgrw, double* berr,\n                            lapack_int n_err_bnds, double* err_bnds_norm,\n                            double* err_bnds_comp, lapack_int nparams,\n                            double* params );\n\nlapack_int LAPACKE_chetrd( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda, float* d,\n                           float* e, lapack_complex_float* tau );\nlapack_int LAPACKE_zhetrd( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda, double* d,\n                           double* e, lapack_complex_double* tau );\n\nlapack_int LAPACKE_chetrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int* ipiv );\nlapack_int LAPACKE_zhetrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* ipiv );\n\nlapack_int LAPACKE_chetri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           const lapack_int* ipiv );\nlapack_int LAPACKE_zhetri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           const lapack_int* ipiv );\n\nlapack_int LAPACKE_chetrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* a,\n                           lapack_int lda, const lapack_int* ipiv,\n                           lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zhetrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* a,\n                           lapack_int lda, const lapack_int* ipiv,\n                           lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_chfrk( int matrix_order, char transr, char uplo, char trans,\n                          lapack_int n, lapack_int k, float alpha,\n                          const lapack_complex_float* a, lapack_int lda,\n                          float beta, lapack_complex_float* c );\nlapack_int LAPACKE_zhfrk( int matrix_order, char transr, char uplo, char trans,\n                          lapack_int n, lapack_int k, double alpha,\n                          const lapack_complex_double* a, lapack_int lda,\n                          double beta, lapack_complex_double* c );\n\nlapack_int LAPACKE_shgeqz( int matrix_order, char job, char compq, char compz,\n                           lapack_int n, lapack_int ilo, lapack_int ihi,\n                           float* h, lapack_int ldh, float* t, lapack_int ldt,\n                           float* alphar, float* alphai, float* beta, float* q,\n                           lapack_int ldq, float* z, lapack_int ldz );\nlapack_int LAPACKE_dhgeqz( int matrix_order, char job, char compq, char compz,\n                           lapack_int n, lapack_int ilo, lapack_int ihi,\n                           double* h, lapack_int ldh, double* t, lapack_int ldt,\n                           double* alphar, double* alphai, double* beta,\n                           double* q, lapack_int ldq, double* z,\n                           lapack_int ldz );\nlapack_int LAPACKE_chgeqz( int matrix_order, char job, char compq, char compz,\n                           lapack_int n, lapack_int ilo, lapack_int ihi,\n                           lapack_complex_float* h, lapack_int ldh,\n                           lapack_complex_float* t, lapack_int ldt,\n                           lapack_complex_float* alpha,\n                           lapack_complex_float* beta, lapack_complex_float* q,\n                           lapack_int ldq, lapack_complex_float* z,\n                           lapack_int ldz );\nlapack_int LAPACKE_zhgeqz( int matrix_order, char job, char compq, char compz,\n                           lapack_int n, lapack_int ilo, lapack_int ihi,\n                           lapack_complex_double* h, lapack_int ldh,\n                           lapack_complex_double* t, lapack_int ldt,\n                           lapack_complex_double* alpha,\n                           lapack_complex_double* beta,\n                           lapack_complex_double* q, lapack_int ldq,\n                           lapack_complex_double* z, lapack_int ldz );\n\nlapack_int LAPACKE_chpcon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_float* ap,\n                           const lapack_int* ipiv, float anorm, float* rcond );\nlapack_int LAPACKE_zhpcon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_double* ap,\n                           const lapack_int* ipiv, double anorm,\n                           double* rcond );\n\nlapack_int LAPACKE_chpev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_complex_float* ap, float* w,\n                          lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zhpev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_complex_double* ap, double* w,\n                          lapack_complex_double* z, lapack_int ldz );\n\nlapack_int LAPACKE_chpevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_complex_float* ap, float* w,\n                           lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zhpevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_complex_double* ap, double* w,\n                           lapack_complex_double* z, lapack_int ldz );\n\nlapack_int LAPACKE_chpevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_complex_float* ap, float vl,\n                           float vu, lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, lapack_complex_float* z,\n                           lapack_int ldz, lapack_int* ifail );\nlapack_int LAPACKE_zhpevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_complex_double* ap, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w,\n                           lapack_complex_double* z, lapack_int ldz,\n                           lapack_int* ifail );\n\nlapack_int LAPACKE_chpgst( int matrix_order, lapack_int itype, char uplo,\n                           lapack_int n, lapack_complex_float* ap,\n                           const lapack_complex_float* bp );\nlapack_int LAPACKE_zhpgst( int matrix_order, lapack_int itype, char uplo,\n                           lapack_int n, lapack_complex_double* ap,\n                           const lapack_complex_double* bp );\n\nlapack_int LAPACKE_chpgv( int matrix_order, lapack_int itype, char jobz,\n                          char uplo, lapack_int n, lapack_complex_float* ap,\n                          lapack_complex_float* bp, float* w,\n                          lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zhpgv( int matrix_order, lapack_int itype, char jobz,\n                          char uplo, lapack_int n, lapack_complex_double* ap,\n                          lapack_complex_double* bp, double* w,\n                          lapack_complex_double* z, lapack_int ldz );\n\nlapack_int LAPACKE_chpgvd( int matrix_order, lapack_int itype, char jobz,\n                           char uplo, lapack_int n, lapack_complex_float* ap,\n                           lapack_complex_float* bp, float* w,\n                           lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zhpgvd( int matrix_order, lapack_int itype, char jobz,\n                           char uplo, lapack_int n, lapack_complex_double* ap,\n                           lapack_complex_double* bp, double* w,\n                           lapack_complex_double* z, lapack_int ldz );\n\nlapack_int LAPACKE_chpgvx( int matrix_order, lapack_int itype, char jobz,\n                           char range, char uplo, lapack_int n,\n                           lapack_complex_float* ap, lapack_complex_float* bp,\n                           float vl, float vu, lapack_int il, lapack_int iu,\n                           float abstol, lapack_int* m, float* w,\n                           lapack_complex_float* z, lapack_int ldz,\n                           lapack_int* ifail );\nlapack_int LAPACKE_zhpgvx( int matrix_order, lapack_int itype, char jobz,\n                           char range, char uplo, lapack_int n,\n                           lapack_complex_double* ap, lapack_complex_double* bp,\n                           double vl, double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w,\n                           lapack_complex_double* z, lapack_int ldz,\n                           lapack_int* ifail );\n\nlapack_int LAPACKE_chprfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* ap,\n                           const lapack_complex_float* afp,\n                           const lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zhprfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* ap,\n                           const lapack_complex_double* afp,\n                           const lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_chpsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_float* ap,\n                          lapack_int* ipiv, lapack_complex_float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_zhpsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_double* ap,\n                          lapack_int* ipiv, lapack_complex_double* b,\n                          lapack_int ldb );\n\nlapack_int LAPACKE_chpsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* ap,\n                           lapack_complex_float* afp, lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr );\nlapack_int LAPACKE_zhpsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* ap,\n                           lapack_complex_double* afp, lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr );\n\nlapack_int LAPACKE_chptrd( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* ap, float* d, float* e,\n                           lapack_complex_float* tau );\nlapack_int LAPACKE_zhptrd( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* ap, double* d, double* e,\n                           lapack_complex_double* tau );\n\nlapack_int LAPACKE_chptrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* ap, lapack_int* ipiv );\nlapack_int LAPACKE_zhptrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* ap, lapack_int* ipiv );\n\nlapack_int LAPACKE_chptri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* ap, const lapack_int* ipiv );\nlapack_int LAPACKE_zhptri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* ap, const lapack_int* ipiv );\n\nlapack_int LAPACKE_chptrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* ap,\n                           const lapack_int* ipiv, lapack_complex_float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_zhptrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* ap,\n                           const lapack_int* ipiv, lapack_complex_double* b,\n                           lapack_int ldb );\n\nlapack_int LAPACKE_shsein( int matrix_order, char job, char eigsrc, char initv,\n                           lapack_logical* select, lapack_int n, const float* h,\n                           lapack_int ldh, float* wr, const float* wi,\n                           float* vl, lapack_int ldvl, float* vr,\n                           lapack_int ldvr, lapack_int mm, lapack_int* m,\n                           lapack_int* ifaill, lapack_int* ifailr );\nlapack_int LAPACKE_dhsein( int matrix_order, char job, char eigsrc, char initv,\n                           lapack_logical* select, lapack_int n,\n                           const double* h, lapack_int ldh, double* wr,\n                           const double* wi, double* vl, lapack_int ldvl,\n                           double* vr, lapack_int ldvr, lapack_int mm,\n                           lapack_int* m, lapack_int* ifaill,\n                           lapack_int* ifailr );\nlapack_int LAPACKE_chsein( int matrix_order, char job, char eigsrc, char initv,\n                           const lapack_logical* select, lapack_int n,\n                           const lapack_complex_float* h, lapack_int ldh,\n                           lapack_complex_float* w, lapack_complex_float* vl,\n                           lapack_int ldvl, lapack_complex_float* vr,\n                           lapack_int ldvr, lapack_int mm, lapack_int* m,\n                           lapack_int* ifaill, lapack_int* ifailr );\nlapack_int LAPACKE_zhsein( int matrix_order, char job, char eigsrc, char initv,\n                           const lapack_logical* select, lapack_int n,\n                           const lapack_complex_double* h, lapack_int ldh,\n                           lapack_complex_double* w, lapack_complex_double* vl,\n                           lapack_int ldvl, lapack_complex_double* vr,\n                           lapack_int ldvr, lapack_int mm, lapack_int* m,\n                           lapack_int* ifaill, lapack_int* ifailr );\n\nlapack_int LAPACKE_shseqr( int matrix_order, char job, char compz, lapack_int n,\n                           lapack_int ilo, lapack_int ihi, float* h,\n                           lapack_int ldh, float* wr, float* wi, float* z,\n                           lapack_int ldz );\nlapack_int LAPACKE_dhseqr( int matrix_order, char job, char compz, lapack_int n,\n                           lapack_int ilo, lapack_int ihi, double* h,\n                           lapack_int ldh, double* wr, double* wi, double* z,\n                           lapack_int ldz );\nlapack_int LAPACKE_chseqr( int matrix_order, char job, char compz, lapack_int n,\n                           lapack_int ilo, lapack_int ihi,\n                           lapack_complex_float* h, lapack_int ldh,\n                           lapack_complex_float* w, lapack_complex_float* z,\n                           lapack_int ldz );\nlapack_int LAPACKE_zhseqr( int matrix_order, char job, char compz, lapack_int n,\n                           lapack_int ilo, lapack_int ihi,\n                           lapack_complex_double* h, lapack_int ldh,\n                           lapack_complex_double* w, lapack_complex_double* z,\n                           lapack_int ldz );\n\nlapack_int LAPACKE_clacgv( lapack_int n, lapack_complex_float* x,\n                           lapack_int incx );\nlapack_int LAPACKE_zlacgv( lapack_int n, lapack_complex_double* x,\n                           lapack_int incx );\n\nlapack_int LAPACKE_slacpy( int matrix_order, char uplo, lapack_int m,\n                           lapack_int n, const float* a, lapack_int lda, float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_dlacpy( int matrix_order, char uplo, lapack_int m,\n                           lapack_int n, const double* a, lapack_int lda, double* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_clacpy( int matrix_order, char uplo, lapack_int m,\n                           lapack_int n, const lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_zlacpy( int matrix_order, char uplo, lapack_int m,\n                           lapack_int n, const lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb );\n\nlapack_int LAPACKE_zlag2c( int matrix_order, lapack_int m, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_float* sa, lapack_int ldsa );\n\nlapack_int LAPACKE_slag2d( int matrix_order, lapack_int m, lapack_int n,\n                           const float* sa, lapack_int ldsa, double* a,\n                           lapack_int lda );\n\nlapack_int LAPACKE_dlag2s( int matrix_order, lapack_int m, lapack_int n,\n                           const double* a, lapack_int lda, float* sa,\n                           lapack_int ldsa );\n\nlapack_int LAPACKE_clag2z( int matrix_order, lapack_int m, lapack_int n,\n                           const lapack_complex_float* sa, lapack_int ldsa,\n                           lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_slagge( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku, const float* d,\n                           float* a, lapack_int lda, lapack_int* iseed );\nlapack_int LAPACKE_dlagge( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku, const double* d,\n                           double* a, lapack_int lda, lapack_int* iseed );\nlapack_int LAPACKE_clagge( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku, const float* d,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int* iseed );\nlapack_int LAPACKE_zlagge( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku, const double* d,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* iseed );\n\nfloat LAPACKE_slamch( char cmach );\ndouble LAPACKE_dlamch( char cmach );\n\nfloat LAPACKE_slange( int matrix_order, char norm, lapack_int m,\n                           lapack_int n, const float* a, lapack_int lda );\ndouble LAPACKE_dlange( int matrix_order, char norm, lapack_int m,\n                           lapack_int n, const double* a, lapack_int lda );\nfloat LAPACKE_clange( int matrix_order, char norm, lapack_int m,\n                           lapack_int n, const lapack_complex_float* a,\n                           lapack_int lda );\ndouble LAPACKE_zlange( int matrix_order, char norm, lapack_int m,\n                           lapack_int n, const lapack_complex_double* a,\n                           lapack_int lda );\n\nfloat LAPACKE_clanhe( int matrix_order, char norm, char uplo, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda );\ndouble LAPACKE_zlanhe( int matrix_order, char norm, char uplo, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda );\n\nfloat LAPACKE_slansy( int matrix_order, char norm, char uplo, lapack_int n,\n                           const float* a, lapack_int lda );\ndouble LAPACKE_dlansy( int matrix_order, char norm, char uplo, lapack_int n,\n                           const double* a, lapack_int lda );\nfloat LAPACKE_clansy( int matrix_order, char norm, char uplo, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda );\ndouble LAPACKE_zlansy( int matrix_order, char norm, char uplo, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda );\n\nfloat LAPACKE_slantr( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int m, lapack_int n, const float* a,\n                           lapack_int lda );\ndouble LAPACKE_dlantr( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int m, lapack_int n, const double* a,\n                           lapack_int lda );\nfloat LAPACKE_clantr( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int m, lapack_int n, const lapack_complex_float* a,\n                           lapack_int lda );\ndouble LAPACKE_zlantr( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int m, lapack_int n, const lapack_complex_double* a,\n                           lapack_int lda );\n\n\nlapack_int LAPACKE_slarfb( int matrix_order, char side, char trans, char direct,\n                           char storev, lapack_int m, lapack_int n,\n                           lapack_int k, const float* v, lapack_int ldv,\n                           const float* t, lapack_int ldt, float* c,\n                           lapack_int ldc );\nlapack_int LAPACKE_dlarfb( int matrix_order, char side, char trans, char direct,\n                           char storev, lapack_int m, lapack_int n,\n                           lapack_int k, const double* v, lapack_int ldv,\n                           const double* t, lapack_int ldt, double* c,\n                           lapack_int ldc );\nlapack_int LAPACKE_clarfb( int matrix_order, char side, char trans, char direct,\n                           char storev, lapack_int m, lapack_int n,\n                           lapack_int k, const lapack_complex_float* v,\n                           lapack_int ldv, const lapack_complex_float* t,\n                           lapack_int ldt, lapack_complex_float* c,\n                           lapack_int ldc );\nlapack_int LAPACKE_zlarfb( int matrix_order, char side, char trans, char direct,\n                           char storev, lapack_int m, lapack_int n,\n                           lapack_int k, const lapack_complex_double* v,\n                           lapack_int ldv, const lapack_complex_double* t,\n                           lapack_int ldt, lapack_complex_double* c,\n                           lapack_int ldc );\n\nlapack_int LAPACKE_slarfg( lapack_int n, float* alpha, float* x,\n                           lapack_int incx, float* tau );\nlapack_int LAPACKE_dlarfg( lapack_int n, double* alpha, double* x,\n                           lapack_int incx, double* tau );\nlapack_int LAPACKE_clarfg( lapack_int n, lapack_complex_float* alpha,\n                           lapack_complex_float* x, lapack_int incx,\n                           lapack_complex_float* tau );\nlapack_int LAPACKE_zlarfg( lapack_int n, lapack_complex_double* alpha,\n                           lapack_complex_double* x, lapack_int incx,\n                           lapack_complex_double* tau );\n\nlapack_int LAPACKE_slarft( int matrix_order, char direct, char storev,\n                           lapack_int n, lapack_int k, const float* v,\n                           lapack_int ldv, const float* tau, float* t,\n                           lapack_int ldt );\nlapack_int LAPACKE_dlarft( int matrix_order, char direct, char storev,\n                           lapack_int n, lapack_int k, const double* v,\n                           lapack_int ldv, const double* tau, double* t,\n                           lapack_int ldt );\nlapack_int LAPACKE_clarft( int matrix_order, char direct, char storev,\n                           lapack_int n, lapack_int k,\n                           const lapack_complex_float* v, lapack_int ldv,\n                           const lapack_complex_float* tau,\n                           lapack_complex_float* t, lapack_int ldt );\nlapack_int LAPACKE_zlarft( int matrix_order, char direct, char storev,\n                           lapack_int n, lapack_int k,\n                           const lapack_complex_double* v, lapack_int ldv,\n                           const lapack_complex_double* tau,\n                           lapack_complex_double* t, lapack_int ldt );\n\nlapack_int LAPACKE_slarfx( int matrix_order, char side, lapack_int m,\n                           lapack_int n, const float* v, float tau, float* c,\n                           lapack_int ldc, float* work );\nlapack_int LAPACKE_dlarfx( int matrix_order, char side, lapack_int m,\n                           lapack_int n, const double* v, double tau, double* c,\n                           lapack_int ldc, double* work );\nlapack_int LAPACKE_clarfx( int matrix_order, char side, lapack_int m,\n                           lapack_int n, const lapack_complex_float* v,\n                           lapack_complex_float tau, lapack_complex_float* c,\n                           lapack_int ldc, lapack_complex_float* work );\nlapack_int LAPACKE_zlarfx( int matrix_order, char side, lapack_int m,\n                           lapack_int n, const lapack_complex_double* v,\n                           lapack_complex_double tau, lapack_complex_double* c,\n                           lapack_int ldc, lapack_complex_double* work );\n\nlapack_int LAPACKE_slarnv( lapack_int idist, lapack_int* iseed, lapack_int n,\n                           float* x );\nlapack_int LAPACKE_dlarnv( lapack_int idist, lapack_int* iseed, lapack_int n,\n                           double* x );\nlapack_int LAPACKE_clarnv( lapack_int idist, lapack_int* iseed, lapack_int n,\n                           lapack_complex_float* x );\nlapack_int LAPACKE_zlarnv( lapack_int idist, lapack_int* iseed, lapack_int n,\n                           lapack_complex_double* x );\n\nlapack_int LAPACKE_slaset( int matrix_order, char uplo, lapack_int m,\n                           lapack_int n, float alpha, float beta, float* a,\n                           lapack_int lda );\nlapack_int LAPACKE_dlaset( int matrix_order, char uplo, lapack_int m,\n                           lapack_int n, double alpha, double beta, double* a,\n                           lapack_int lda );\nlapack_int LAPACKE_claset( int matrix_order, char uplo, lapack_int m,\n                           lapack_int n, lapack_complex_float alpha,\n                           lapack_complex_float beta, lapack_complex_float* a,\n                           lapack_int lda );\nlapack_int LAPACKE_zlaset( int matrix_order, char uplo, lapack_int m,\n                           lapack_int n, lapack_complex_double alpha,\n                           lapack_complex_double beta, lapack_complex_double* a,\n                           lapack_int lda );\n\nlapack_int LAPACKE_slasrt( char id, lapack_int n, float* d );\nlapack_int LAPACKE_dlasrt( char id, lapack_int n, double* d );\n\nlapack_int LAPACKE_slaswp( int matrix_order, lapack_int n, float* a,\n                           lapack_int lda, lapack_int k1, lapack_int k2,\n                           const lapack_int* ipiv, lapack_int incx );\nlapack_int LAPACKE_dlaswp( int matrix_order, lapack_int n, double* a,\n                           lapack_int lda, lapack_int k1, lapack_int k2,\n                           const lapack_int* ipiv, lapack_int incx );\nlapack_int LAPACKE_claswp( int matrix_order, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int k1, lapack_int k2, const lapack_int* ipiv,\n                           lapack_int incx );\nlapack_int LAPACKE_zlaswp( int matrix_order, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int k1, lapack_int k2, const lapack_int* ipiv,\n                           lapack_int incx );\n\nlapack_int LAPACKE_slatms( int matrix_order, lapack_int m, lapack_int n,\n                           char dist, lapack_int* iseed, char sym, float* d,\n                           lapack_int mode, float cond, float dmax,\n                           lapack_int kl, lapack_int ku, char pack, float* a,\n                           lapack_int lda );\nlapack_int LAPACKE_dlatms( int matrix_order, lapack_int m, lapack_int n,\n                           char dist, lapack_int* iseed, char sym, double* d,\n                           lapack_int mode, double cond, double dmax,\n                           lapack_int kl, lapack_int ku, char pack, double* a,\n                           lapack_int lda );\nlapack_int LAPACKE_clatms( int matrix_order, lapack_int m, lapack_int n,\n                           char dist, lapack_int* iseed, char sym, float* d,\n                           lapack_int mode, float cond, float dmax,\n                           lapack_int kl, lapack_int ku, char pack,\n                           lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_zlatms( int matrix_order, lapack_int m, lapack_int n,\n                           char dist, lapack_int* iseed, char sym, double* d,\n                           lapack_int mode, double cond, double dmax,\n                           lapack_int kl, lapack_int ku, char pack,\n                           lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_slauum( int matrix_order, char uplo, lapack_int n, float* a,\n                           lapack_int lda );\nlapack_int LAPACKE_dlauum( int matrix_order, char uplo, lapack_int n, double* a,\n                           lapack_int lda );\nlapack_int LAPACKE_clauum( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_zlauum( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_sopgtr( int matrix_order, char uplo, lapack_int n,\n                           const float* ap, const float* tau, float* q,\n                           lapack_int ldq );\nlapack_int LAPACKE_dopgtr( int matrix_order, char uplo, lapack_int n,\n                           const double* ap, const double* tau, double* q,\n                           lapack_int ldq );\n\nlapack_int LAPACKE_sopmtr( int matrix_order, char side, char uplo, char trans,\n                           lapack_int m, lapack_int n, const float* ap,\n                           const float* tau, float* c, lapack_int ldc );\nlapack_int LAPACKE_dopmtr( int matrix_order, char side, char uplo, char trans,\n                           lapack_int m, lapack_int n, const double* ap,\n                           const double* tau, double* c, lapack_int ldc );\n\nlapack_int LAPACKE_sorgbr( int matrix_order, char vect, lapack_int m,\n                           lapack_int n, lapack_int k, float* a, lapack_int lda,\n                           const float* tau );\nlapack_int LAPACKE_dorgbr( int matrix_order, char vect, lapack_int m,\n                           lapack_int n, lapack_int k, double* a,\n                           lapack_int lda, const double* tau );\n\nlapack_int LAPACKE_sorghr( int matrix_order, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, float* a, lapack_int lda,\n                           const float* tau );\nlapack_int LAPACKE_dorghr( int matrix_order, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, double* a, lapack_int lda,\n                           const double* tau );\n\nlapack_int LAPACKE_sorglq( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, float* a, lapack_int lda,\n                           const float* tau );\nlapack_int LAPACKE_dorglq( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, double* a, lapack_int lda,\n                           const double* tau );\n\nlapack_int LAPACKE_sorgql( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, float* a, lapack_int lda,\n                           const float* tau );\nlapack_int LAPACKE_dorgql( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, double* a, lapack_int lda,\n                           const double* tau );\n\nlapack_int LAPACKE_sorgqr( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, float* a, lapack_int lda,\n                           const float* tau );\nlapack_int LAPACKE_dorgqr( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, double* a, lapack_int lda,\n                           const double* tau );\n\nlapack_int LAPACKE_sorgrq( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, float* a, lapack_int lda,\n                           const float* tau );\nlapack_int LAPACKE_dorgrq( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, double* a, lapack_int lda,\n                           const double* tau );\n\nlapack_int LAPACKE_sorgtr( int matrix_order, char uplo, lapack_int n, float* a,\n                           lapack_int lda, const float* tau );\nlapack_int LAPACKE_dorgtr( int matrix_order, char uplo, lapack_int n, double* a,\n                           lapack_int lda, const double* tau );\n\nlapack_int LAPACKE_sormbr( int matrix_order, char vect, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const float* a, lapack_int lda, const float* tau,\n                           float* c, lapack_int ldc );\nlapack_int LAPACKE_dormbr( int matrix_order, char vect, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const double* a, lapack_int lda, const double* tau,\n                           double* c, lapack_int ldc );\n\nlapack_int LAPACKE_sormhr( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, const float* a, lapack_int lda,\n                           const float* tau, float* c, lapack_int ldc );\nlapack_int LAPACKE_dormhr( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, const double* a, lapack_int lda,\n                           const double* tau, double* c, lapack_int ldc );\n\nlapack_int LAPACKE_sormlq( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const float* a, lapack_int lda, const float* tau,\n                           float* c, lapack_int ldc );\nlapack_int LAPACKE_dormlq( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const double* a, lapack_int lda, const double* tau,\n                           double* c, lapack_int ldc );\n\nlapack_int LAPACKE_sormql( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const float* a, lapack_int lda, const float* tau,\n                           float* c, lapack_int ldc );\nlapack_int LAPACKE_dormql( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const double* a, lapack_int lda, const double* tau,\n                           double* c, lapack_int ldc );\n\nlapack_int LAPACKE_sormqr( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const float* a, lapack_int lda, const float* tau,\n                           float* c, lapack_int ldc );\nlapack_int LAPACKE_dormqr( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const double* a, lapack_int lda, const double* tau,\n                           double* c, lapack_int ldc );\n\nlapack_int LAPACKE_sormrq( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const float* a, lapack_int lda, const float* tau,\n                           float* c, lapack_int ldc );\nlapack_int LAPACKE_dormrq( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const double* a, lapack_int lda, const double* tau,\n                           double* c, lapack_int ldc );\n\nlapack_int LAPACKE_sormrz( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           lapack_int l, const float* a, lapack_int lda,\n                           const float* tau, float* c, lapack_int ldc );\nlapack_int LAPACKE_dormrz( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           lapack_int l, const double* a, lapack_int lda,\n                           const double* tau, double* c, lapack_int ldc );\n\nlapack_int LAPACKE_sormtr( int matrix_order, char side, char uplo, char trans,\n                           lapack_int m, lapack_int n, const float* a,\n                           lapack_int lda, const float* tau, float* c,\n                           lapack_int ldc );\nlapack_int LAPACKE_dormtr( int matrix_order, char side, char uplo, char trans,\n                           lapack_int m, lapack_int n, const double* a,\n                           lapack_int lda, const double* tau, double* c,\n                           lapack_int ldc );\n\nlapack_int LAPACKE_spbcon( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, const float* ab, lapack_int ldab,\n                           float anorm, float* rcond );\nlapack_int LAPACKE_dpbcon( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, const double* ab, lapack_int ldab,\n                           double anorm, double* rcond );\nlapack_int LAPACKE_cpbcon( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, const lapack_complex_float* ab,\n                           lapack_int ldab, float anorm, float* rcond );\nlapack_int LAPACKE_zpbcon( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, const lapack_complex_double* ab,\n                           lapack_int ldab, double anorm, double* rcond );\n\nlapack_int LAPACKE_spbequ( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, const float* ab, lapack_int ldab,\n                           float* s, float* scond, float* amax );\nlapack_int LAPACKE_dpbequ( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, const double* ab, lapack_int ldab,\n                           double* s, double* scond, double* amax );\nlapack_int LAPACKE_cpbequ( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, const lapack_complex_float* ab,\n                           lapack_int ldab, float* s, float* scond,\n                           float* amax );\nlapack_int LAPACKE_zpbequ( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, const lapack_complex_double* ab,\n                           lapack_int ldab, double* s, double* scond,\n                           double* amax );\n\nlapack_int LAPACKE_spbrfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs, const float* ab,\n                           lapack_int ldab, const float* afb, lapack_int ldafb,\n                           const float* b, lapack_int ldb, float* x,\n                           lapack_int ldx, float* ferr, float* berr );\nlapack_int LAPACKE_dpbrfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs, const double* ab,\n                           lapack_int ldab, const double* afb, lapack_int ldafb,\n                           const double* b, lapack_int ldb, double* x,\n                           lapack_int ldx, double* ferr, double* berr );\nlapack_int LAPACKE_cpbrfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs,\n                           const lapack_complex_float* ab, lapack_int ldab,\n                           const lapack_complex_float* afb, lapack_int ldafb,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zpbrfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs,\n                           const lapack_complex_double* ab, lapack_int ldab,\n                           const lapack_complex_double* afb, lapack_int ldafb,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_spbstf( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kb, float* bb, lapack_int ldbb );\nlapack_int LAPACKE_dpbstf( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kb, double* bb, lapack_int ldbb );\nlapack_int LAPACKE_cpbstf( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kb, lapack_complex_float* bb,\n                           lapack_int ldbb );\nlapack_int LAPACKE_zpbstf( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kb, lapack_complex_double* bb,\n                           lapack_int ldbb );\n\nlapack_int LAPACKE_spbsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int kd, lapack_int nrhs, float* ab,\n                          lapack_int ldab, float* b, lapack_int ldb );\nlapack_int LAPACKE_dpbsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int kd, lapack_int nrhs, double* ab,\n                          lapack_int ldab, double* b, lapack_int ldb );\nlapack_int LAPACKE_cpbsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int kd, lapack_int nrhs,\n                          lapack_complex_float* ab, lapack_int ldab,\n                          lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zpbsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int kd, lapack_int nrhs,\n                          lapack_complex_double* ab, lapack_int ldab,\n                          lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_spbsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs, float* ab,\n                           lapack_int ldab, float* afb, lapack_int ldafb,\n                           char* equed, float* s, float* b, lapack_int ldb,\n                           float* x, lapack_int ldx, float* rcond, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_dpbsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs, double* ab,\n                           lapack_int ldab, double* afb, lapack_int ldafb,\n                           char* equed, double* s, double* b, lapack_int ldb,\n                           double* x, lapack_int ldx, double* rcond,\n                           double* ferr, double* berr );\nlapack_int LAPACKE_cpbsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs,\n                           lapack_complex_float* ab, lapack_int ldab,\n                           lapack_complex_float* afb, lapack_int ldafb,\n                           char* equed, float* s, lapack_complex_float* b,\n                           lapack_int ldb, lapack_complex_float* x,\n                           lapack_int ldx, float* rcond, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zpbsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs,\n                           lapack_complex_double* ab, lapack_int ldab,\n                           lapack_complex_double* afb, lapack_int ldafb,\n                           char* equed, double* s, lapack_complex_double* b,\n                           lapack_int ldb, lapack_complex_double* x,\n                           lapack_int ldx, double* rcond, double* ferr,\n                           double* berr );\n\nlapack_int LAPACKE_spbtrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, float* ab, lapack_int ldab );\nlapack_int LAPACKE_dpbtrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, double* ab, lapack_int ldab );\nlapack_int LAPACKE_cpbtrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, lapack_complex_float* ab,\n                           lapack_int ldab );\nlapack_int LAPACKE_zpbtrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, lapack_complex_double* ab,\n                           lapack_int ldab );\n\nlapack_int LAPACKE_spbtrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs, const float* ab,\n                           lapack_int ldab, float* b, lapack_int ldb );\nlapack_int LAPACKE_dpbtrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs, const double* ab,\n                           lapack_int ldab, double* b, lapack_int ldb );\nlapack_int LAPACKE_cpbtrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs,\n                           const lapack_complex_float* ab, lapack_int ldab,\n                           lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zpbtrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs,\n                           const lapack_complex_double* ab, lapack_int ldab,\n                           lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_spftrf( int matrix_order, char transr, char uplo,\n                           lapack_int n, float* a );\nlapack_int LAPACKE_dpftrf( int matrix_order, char transr, char uplo,\n                           lapack_int n, double* a );\nlapack_int LAPACKE_cpftrf( int matrix_order, char transr, char uplo,\n                           lapack_int n, lapack_complex_float* a );\nlapack_int LAPACKE_zpftrf( int matrix_order, char transr, char uplo,\n                           lapack_int n, lapack_complex_double* a );\n\nlapack_int LAPACKE_spftri( int matrix_order, char transr, char uplo,\n                           lapack_int n, float* a );\nlapack_int LAPACKE_dpftri( int matrix_order, char transr, char uplo,\n                           lapack_int n, double* a );\nlapack_int LAPACKE_cpftri( int matrix_order, char transr, char uplo,\n                           lapack_int n, lapack_complex_float* a );\nlapack_int LAPACKE_zpftri( int matrix_order, char transr, char uplo,\n                           lapack_int n, lapack_complex_double* a );\n\nlapack_int LAPACKE_spftrs( int matrix_order, char transr, char uplo,\n                           lapack_int n, lapack_int nrhs, const float* a,\n                           float* b, lapack_int ldb );\nlapack_int LAPACKE_dpftrs( int matrix_order, char transr, char uplo,\n                           lapack_int n, lapack_int nrhs, const double* a,\n                           double* b, lapack_int ldb );\nlapack_int LAPACKE_cpftrs( int matrix_order, char transr, char uplo,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_float* a,\n                           lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zpftrs( int matrix_order, char transr, char uplo,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_double* a,\n                           lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_spocon( int matrix_order, char uplo, lapack_int n,\n                           const float* a, lapack_int lda, float anorm,\n                           float* rcond );\nlapack_int LAPACKE_dpocon( int matrix_order, char uplo, lapack_int n,\n                           const double* a, lapack_int lda, double anorm,\n                           double* rcond );\nlapack_int LAPACKE_cpocon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           float anorm, float* rcond );\nlapack_int LAPACKE_zpocon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           double anorm, double* rcond );\n\nlapack_int LAPACKE_spoequ( int matrix_order, lapack_int n, const float* a,\n                           lapack_int lda, float* s, float* scond,\n                           float* amax );\nlapack_int LAPACKE_dpoequ( int matrix_order, lapack_int n, const double* a,\n                           lapack_int lda, double* s, double* scond,\n                           double* amax );\nlapack_int LAPACKE_cpoequ( int matrix_order, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           float* s, float* scond, float* amax );\nlapack_int LAPACKE_zpoequ( int matrix_order, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           double* s, double* scond, double* amax );\n\nlapack_int LAPACKE_spoequb( int matrix_order, lapack_int n, const float* a,\n                            lapack_int lda, float* s, float* scond,\n                            float* amax );\nlapack_int LAPACKE_dpoequb( int matrix_order, lapack_int n, const double* a,\n                            lapack_int lda, double* s, double* scond,\n                            double* amax );\nlapack_int LAPACKE_cpoequb( int matrix_order, lapack_int n,\n                            const lapack_complex_float* a, lapack_int lda,\n                            float* s, float* scond, float* amax );\nlapack_int LAPACKE_zpoequb( int matrix_order, lapack_int n,\n                            const lapack_complex_double* a, lapack_int lda,\n                            double* s, double* scond, double* amax );\n\nlapack_int LAPACKE_sporfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* a, lapack_int lda,\n                           const float* af, lapack_int ldaf, const float* b,\n                           lapack_int ldb, float* x, lapack_int ldx,\n                           float* ferr, float* berr );\nlapack_int LAPACKE_dporfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* a, lapack_int lda,\n                           const double* af, lapack_int ldaf, const double* b,\n                           lapack_int ldb, double* x, lapack_int ldx,\n                           double* ferr, double* berr );\nlapack_int LAPACKE_cporfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* af,\n                           lapack_int ldaf, const lapack_complex_float* b,\n                           lapack_int ldb, lapack_complex_float* x,\n                           lapack_int ldx, float* ferr, float* berr );\nlapack_int LAPACKE_zporfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* af,\n                           lapack_int ldaf, const lapack_complex_double* b,\n                           lapack_int ldb, lapack_complex_double* x,\n                           lapack_int ldx, double* ferr, double* berr );\n\nlapack_int LAPACKE_sporfsx( int matrix_order, char uplo, char equed,\n                            lapack_int n, lapack_int nrhs, const float* a,\n                            lapack_int lda, const float* af, lapack_int ldaf,\n                            const float* s, const float* b, lapack_int ldb,\n                            float* x, lapack_int ldx, float* rcond, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_dporfsx( int matrix_order, char uplo, char equed,\n                            lapack_int n, lapack_int nrhs, const double* a,\n                            lapack_int lda, const double* af, lapack_int ldaf,\n                            const double* s, const double* b, lapack_int ldb,\n                            double* x, lapack_int ldx, double* rcond,\n                            double* berr, lapack_int n_err_bnds,\n                            double* err_bnds_norm, double* err_bnds_comp,\n                            lapack_int nparams, double* params );\nlapack_int LAPACKE_cporfsx( int matrix_order, char uplo, char equed,\n                            lapack_int n, lapack_int nrhs,\n                            const lapack_complex_float* a, lapack_int lda,\n                            const lapack_complex_float* af, lapack_int ldaf,\n                            const float* s, const lapack_complex_float* b,\n                            lapack_int ldb, lapack_complex_float* x,\n                            lapack_int ldx, float* rcond, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_zporfsx( int matrix_order, char uplo, char equed,\n                            lapack_int n, lapack_int nrhs,\n                            const lapack_complex_double* a, lapack_int lda,\n                            const lapack_complex_double* af, lapack_int ldaf,\n                            const double* s, const lapack_complex_double* b,\n                            lapack_int ldb, lapack_complex_double* x,\n                            lapack_int ldx, double* rcond, double* berr,\n                            lapack_int n_err_bnds, double* err_bnds_norm,\n                            double* err_bnds_comp, lapack_int nparams,\n                            double* params );\n\nlapack_int LAPACKE_sposv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, float* a, lapack_int lda, float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_dposv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, double* a, lapack_int lda, double* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_cposv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_float* a,\n                          lapack_int lda, lapack_complex_float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_zposv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_double* a,\n                          lapack_int lda, lapack_complex_double* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_dsposv( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, double* a, lapack_int lda,\n                           double* b, lapack_int ldb, double* x, lapack_int ldx,\n                           lapack_int* iter );\nlapack_int LAPACKE_zcposv( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb, lapack_complex_double* x,\n                           lapack_int ldx, lapack_int* iter );\n\nlapack_int LAPACKE_sposvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, float* a, lapack_int lda, float* af,\n                           lapack_int ldaf, char* equed, float* s, float* b,\n                           lapack_int ldb, float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr );\nlapack_int LAPACKE_dposvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, double* a, lapack_int lda,\n                           double* af, lapack_int ldaf, char* equed, double* s,\n                           double* b, lapack_int ldb, double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr );\nlapack_int LAPACKE_cposvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* af,\n                           lapack_int ldaf, char* equed, float* s,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr );\nlapack_int LAPACKE_zposvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* af,\n                           lapack_int ldaf, char* equed, double* s,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr );\n\nlapack_int LAPACKE_sposvxx( int matrix_order, char fact, char uplo,\n                            lapack_int n, lapack_int nrhs, float* a,\n                            lapack_int lda, float* af, lapack_int ldaf,\n                            char* equed, float* s, float* b, lapack_int ldb,\n                            float* x, lapack_int ldx, float* rcond,\n                            float* rpvgrw, float* berr, lapack_int n_err_bnds,\n                            float* err_bnds_norm, float* err_bnds_comp,\n                            lapack_int nparams, float* params );\nlapack_int LAPACKE_dposvxx( int matrix_order, char fact, char uplo,\n                            lapack_int n, lapack_int nrhs, double* a,\n                            lapack_int lda, double* af, lapack_int ldaf,\n                            char* equed, double* s, double* b, lapack_int ldb,\n                            double* x, lapack_int ldx, double* rcond,\n                            double* rpvgrw, double* berr, lapack_int n_err_bnds,\n                            double* err_bnds_norm, double* err_bnds_comp,\n                            lapack_int nparams, double* params );\nlapack_int LAPACKE_cposvxx( int matrix_order, char fact, char uplo,\n                            lapack_int n, lapack_int nrhs,\n                            lapack_complex_float* a, lapack_int lda,\n                            lapack_complex_float* af, lapack_int ldaf,\n                            char* equed, float* s, lapack_complex_float* b,\n                            lapack_int ldb, lapack_complex_float* x,\n                            lapack_int ldx, float* rcond, float* rpvgrw,\n                            float* berr, lapack_int n_err_bnds,\n                            float* err_bnds_norm, float* err_bnds_comp,\n                            lapack_int nparams, float* params );\nlapack_int LAPACKE_zposvxx( int matrix_order, char fact, char uplo,\n                            lapack_int n, lapack_int nrhs,\n                            lapack_complex_double* a, lapack_int lda,\n                            lapack_complex_double* af, lapack_int ldaf,\n                            char* equed, double* s, lapack_complex_double* b,\n                            lapack_int ldb, lapack_complex_double* x,\n                            lapack_int ldx, double* rcond, double* rpvgrw,\n                            double* berr, lapack_int n_err_bnds,\n                            double* err_bnds_norm, double* err_bnds_comp,\n                            lapack_int nparams, double* params );\n\nlapack_int LAPACKE_spotrf( int matrix_order, char uplo, lapack_int n, float* a,\n                           lapack_int lda );\nlapack_int LAPACKE_dpotrf( int matrix_order, char uplo, lapack_int n, double* a,\n                           lapack_int lda );\nlapack_int LAPACKE_cpotrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_zpotrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_spotri( int matrix_order, char uplo, lapack_int n, float* a,\n                           lapack_int lda );\nlapack_int LAPACKE_dpotri( int matrix_order, char uplo, lapack_int n, double* a,\n                           lapack_int lda );\nlapack_int LAPACKE_cpotri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_zpotri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_spotrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* a, lapack_int lda,\n                           float* b, lapack_int ldb );\nlapack_int LAPACKE_dpotrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* a, lapack_int lda,\n                           double* b, lapack_int ldb );\nlapack_int LAPACKE_cpotrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_zpotrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb );\n\nlapack_int LAPACKE_sppcon( int matrix_order, char uplo, lapack_int n,\n                           const float* ap, float anorm, float* rcond );\nlapack_int LAPACKE_dppcon( int matrix_order, char uplo, lapack_int n,\n                           const double* ap, double anorm, double* rcond );\nlapack_int LAPACKE_cppcon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_float* ap, float anorm,\n                           float* rcond );\nlapack_int LAPACKE_zppcon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_double* ap, double anorm,\n                           double* rcond );\n\nlapack_int LAPACKE_sppequ( int matrix_order, char uplo, lapack_int n,\n                           const float* ap, float* s, float* scond,\n                           float* amax );\nlapack_int LAPACKE_dppequ( int matrix_order, char uplo, lapack_int n,\n                           const double* ap, double* s, double* scond,\n                           double* amax );\nlapack_int LAPACKE_cppequ( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_float* ap, float* s,\n                           float* scond, float* amax );\nlapack_int LAPACKE_zppequ( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_double* ap, double* s,\n                           double* scond, double* amax );\n\nlapack_int LAPACKE_spprfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* ap, const float* afp,\n                           const float* b, lapack_int ldb, float* x,\n                           lapack_int ldx, float* ferr, float* berr );\nlapack_int LAPACKE_dpprfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* ap, const double* afp,\n                           const double* b, lapack_int ldb, double* x,\n                           lapack_int ldx, double* ferr, double* berr );\nlapack_int LAPACKE_cpprfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* ap,\n                           const lapack_complex_float* afp,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zpprfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* ap,\n                           const lapack_complex_double* afp,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_sppsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, float* ap, float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_dppsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, double* ap, double* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_cppsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_float* ap,\n                          lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zppsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_double* ap,\n                          lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_sppsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, float* ap, float* afp, char* equed,\n                           float* s, float* b, lapack_int ldb, float* x,\n                           lapack_int ldx, float* rcond, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_dppsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, double* ap, double* afp,\n                           char* equed, double* s, double* b, lapack_int ldb,\n                           double* x, lapack_int ldx, double* rcond,\n                           double* ferr, double* berr );\nlapack_int LAPACKE_cppsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, lapack_complex_float* ap,\n                           lapack_complex_float* afp, char* equed, float* s,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr );\nlapack_int LAPACKE_zppsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, lapack_complex_double* ap,\n                           lapack_complex_double* afp, char* equed, double* s,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr );\n\nlapack_int LAPACKE_spptrf( int matrix_order, char uplo, lapack_int n,\n                           float* ap );\nlapack_int LAPACKE_dpptrf( int matrix_order, char uplo, lapack_int n,\n                           double* ap );\nlapack_int LAPACKE_cpptrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* ap );\nlapack_int LAPACKE_zpptrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* ap );\n\nlapack_int LAPACKE_spptri( int matrix_order, char uplo, lapack_int n,\n                           float* ap );\nlapack_int LAPACKE_dpptri( int matrix_order, char uplo, lapack_int n,\n                           double* ap );\nlapack_int LAPACKE_cpptri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* ap );\nlapack_int LAPACKE_zpptri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* ap );\n\nlapack_int LAPACKE_spptrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* ap, float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_dpptrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* ap, double* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_cpptrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* ap,\n                           lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zpptrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* ap,\n                           lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_spstrf( int matrix_order, char uplo, lapack_int n, float* a,\n                           lapack_int lda, lapack_int* piv, lapack_int* rank,\n                           float tol );\nlapack_int LAPACKE_dpstrf( int matrix_order, char uplo, lapack_int n, double* a,\n                           lapack_int lda, lapack_int* piv, lapack_int* rank,\n                           double tol );\nlapack_int LAPACKE_cpstrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int* piv, lapack_int* rank, float tol );\nlapack_int LAPACKE_zpstrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* piv, lapack_int* rank, double tol );\n\nlapack_int LAPACKE_sptcon( lapack_int n, const float* d, const float* e,\n                           float anorm, float* rcond );\nlapack_int LAPACKE_dptcon( lapack_int n, const double* d, const double* e,\n                           double anorm, double* rcond );\nlapack_int LAPACKE_cptcon( lapack_int n, const float* d,\n                           const lapack_complex_float* e, float anorm,\n                           float* rcond );\nlapack_int LAPACKE_zptcon( lapack_int n, const double* d,\n                           const lapack_complex_double* e, double anorm,\n                           double* rcond );\n\nlapack_int LAPACKE_spteqr( int matrix_order, char compz, lapack_int n, float* d,\n                           float* e, float* z, lapack_int ldz );\nlapack_int LAPACKE_dpteqr( int matrix_order, char compz, lapack_int n,\n                           double* d, double* e, double* z, lapack_int ldz );\nlapack_int LAPACKE_cpteqr( int matrix_order, char compz, lapack_int n, float* d,\n                           float* e, lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zpteqr( int matrix_order, char compz, lapack_int n,\n                           double* d, double* e, lapack_complex_double* z,\n                           lapack_int ldz );\n\nlapack_int LAPACKE_sptrfs( int matrix_order, lapack_int n, lapack_int nrhs,\n                           const float* d, const float* e, const float* df,\n                           const float* ef, const float* b, lapack_int ldb,\n                           float* x, lapack_int ldx, float* ferr, float* berr );\nlapack_int LAPACKE_dptrfs( int matrix_order, lapack_int n, lapack_int nrhs,\n                           const double* d, const double* e, const double* df,\n                           const double* ef, const double* b, lapack_int ldb,\n                           double* x, lapack_int ldx, double* ferr,\n                           double* berr );\nlapack_int LAPACKE_cptrfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* d,\n                           const lapack_complex_float* e, const float* df,\n                           const lapack_complex_float* ef,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zptrfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* d,\n                           const lapack_complex_double* e, const double* df,\n                           const lapack_complex_double* ef,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_sptsv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          float* d, float* e, float* b, lapack_int ldb );\nlapack_int LAPACKE_dptsv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          double* d, double* e, double* b, lapack_int ldb );\nlapack_int LAPACKE_cptsv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          float* d, lapack_complex_float* e,\n                          lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zptsv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          double* d, lapack_complex_double* e,\n                          lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_sptsvx( int matrix_order, char fact, lapack_int n,\n                           lapack_int nrhs, const float* d, const float* e,\n                           float* df, float* ef, const float* b, lapack_int ldb,\n                           float* x, lapack_int ldx, float* rcond, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_dptsvx( int matrix_order, char fact, lapack_int n,\n                           lapack_int nrhs, const double* d, const double* e,\n                           double* df, double* ef, const double* b,\n                           lapack_int ldb, double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr );\nlapack_int LAPACKE_cptsvx( int matrix_order, char fact, lapack_int n,\n                           lapack_int nrhs, const float* d,\n                           const lapack_complex_float* e, float* df,\n                           lapack_complex_float* ef,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr );\nlapack_int LAPACKE_zptsvx( int matrix_order, char fact, lapack_int n,\n                           lapack_int nrhs, const double* d,\n                           const lapack_complex_double* e, double* df,\n                           lapack_complex_double* ef,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr );\n\nlapack_int LAPACKE_spttrf( lapack_int n, float* d, float* e );\nlapack_int LAPACKE_dpttrf( lapack_int n, double* d, double* e );\nlapack_int LAPACKE_cpttrf( lapack_int n, float* d, lapack_complex_float* e );\nlapack_int LAPACKE_zpttrf( lapack_int n, double* d, lapack_complex_double* e );\n\nlapack_int LAPACKE_spttrs( int matrix_order, lapack_int n, lapack_int nrhs,\n                           const float* d, const float* e, float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_dpttrs( int matrix_order, lapack_int n, lapack_int nrhs,\n                           const double* d, const double* e, double* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_cpttrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* d,\n                           const lapack_complex_float* e,\n                           lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zpttrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* d,\n                           const lapack_complex_double* e,\n                           lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_ssbev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_int kd, float* ab, lapack_int ldab, float* w,\n                          float* z, lapack_int ldz );\nlapack_int LAPACKE_dsbev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_int kd, double* ab, lapack_int ldab, double* w,\n                          double* z, lapack_int ldz );\n\nlapack_int LAPACKE_ssbevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_int kd, float* ab, lapack_int ldab, float* w,\n                           float* z, lapack_int ldz );\nlapack_int LAPACKE_dsbevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_int kd, double* ab, lapack_int ldab,\n                           double* w, double* z, lapack_int ldz );\n\nlapack_int LAPACKE_ssbevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_int kd, float* ab,\n                           lapack_int ldab, float* q, lapack_int ldq, float vl,\n                           float vu, lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, float* z, lapack_int ldz,\n                           lapack_int* ifail );\nlapack_int LAPACKE_dsbevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_int kd, double* ab,\n                           lapack_int ldab, double* q, lapack_int ldq,\n                           double vl, double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w, double* z,\n                           lapack_int ldz, lapack_int* ifail );\n\nlapack_int LAPACKE_ssbgst( int matrix_order, char vect, char uplo, lapack_int n,\n                           lapack_int ka, lapack_int kb, float* ab,\n                           lapack_int ldab, const float* bb, lapack_int ldbb,\n                           float* x, lapack_int ldx );\nlapack_int LAPACKE_dsbgst( int matrix_order, char vect, char uplo, lapack_int n,\n                           lapack_int ka, lapack_int kb, double* ab,\n                           lapack_int ldab, const double* bb, lapack_int ldbb,\n                           double* x, lapack_int ldx );\n\nlapack_int LAPACKE_ssbgv( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_int ka, lapack_int kb, float* ab,\n                          lapack_int ldab, float* bb, lapack_int ldbb, float* w,\n                          float* z, lapack_int ldz );\nlapack_int LAPACKE_dsbgv( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_int ka, lapack_int kb, double* ab,\n                          lapack_int ldab, double* bb, lapack_int ldbb,\n                          double* w, double* z, lapack_int ldz );\n\nlapack_int LAPACKE_ssbgvd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_int ka, lapack_int kb, float* ab,\n                           lapack_int ldab, float* bb, lapack_int ldbb,\n                           float* w, float* z, lapack_int ldz );\nlapack_int LAPACKE_dsbgvd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_int ka, lapack_int kb, double* ab,\n                           lapack_int ldab, double* bb, lapack_int ldbb,\n                           double* w, double* z, lapack_int ldz );\n\nlapack_int LAPACKE_ssbgvx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_int ka, lapack_int kb,\n                           float* ab, lapack_int ldab, float* bb,\n                           lapack_int ldbb, float* q, lapack_int ldq, float vl,\n                           float vu, lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, float* z, lapack_int ldz,\n                           lapack_int* ifail );\nlapack_int LAPACKE_dsbgvx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_int ka, lapack_int kb,\n                           double* ab, lapack_int ldab, double* bb,\n                           lapack_int ldbb, double* q, lapack_int ldq,\n                           double vl, double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w, double* z,\n                           lapack_int ldz, lapack_int* ifail );\n\nlapack_int LAPACKE_ssbtrd( int matrix_order, char vect, char uplo, lapack_int n,\n                           lapack_int kd, float* ab, lapack_int ldab, float* d,\n                           float* e, float* q, lapack_int ldq );\nlapack_int LAPACKE_dsbtrd( int matrix_order, char vect, char uplo, lapack_int n,\n                           lapack_int kd, double* ab, lapack_int ldab,\n                           double* d, double* e, double* q, lapack_int ldq );\n\nlapack_int LAPACKE_ssfrk( int matrix_order, char transr, char uplo, char trans,\n                          lapack_int n, lapack_int k, float alpha,\n                          const float* a, lapack_int lda, float beta,\n                          float* c );\nlapack_int LAPACKE_dsfrk( int matrix_order, char transr, char uplo, char trans,\n                          lapack_int n, lapack_int k, double alpha,\n                          const double* a, lapack_int lda, double beta,\n                          double* c );\n\nlapack_int LAPACKE_sspcon( int matrix_order, char uplo, lapack_int n,\n                           const float* ap, const lapack_int* ipiv, float anorm,\n                           float* rcond );\nlapack_int LAPACKE_dspcon( int matrix_order, char uplo, lapack_int n,\n                           const double* ap, const lapack_int* ipiv,\n                           double anorm, double* rcond );\nlapack_int LAPACKE_cspcon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_float* ap,\n                           const lapack_int* ipiv, float anorm, float* rcond );\nlapack_int LAPACKE_zspcon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_double* ap,\n                           const lapack_int* ipiv, double anorm,\n                           double* rcond );\n\nlapack_int LAPACKE_sspev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          float* ap, float* w, float* z, lapack_int ldz );\nlapack_int LAPACKE_dspev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          double* ap, double* w, double* z, lapack_int ldz );\n\nlapack_int LAPACKE_sspevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           float* ap, float* w, float* z, lapack_int ldz );\nlapack_int LAPACKE_dspevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           double* ap, double* w, double* z, lapack_int ldz );\n\nlapack_int LAPACKE_sspevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, float* ap, float vl, float vu,\n                           lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, float* z, lapack_int ldz,\n                           lapack_int* ifail );\nlapack_int LAPACKE_dspevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, double* ap, double vl, double vu,\n                           lapack_int il, lapack_int iu, double abstol,\n                           lapack_int* m, double* w, double* z, lapack_int ldz,\n                           lapack_int* ifail );\n\nlapack_int LAPACKE_sspgst( int matrix_order, lapack_int itype, char uplo,\n                           lapack_int n, float* ap, const float* bp );\nlapack_int LAPACKE_dspgst( int matrix_order, lapack_int itype, char uplo,\n                           lapack_int n, double* ap, const double* bp );\n\nlapack_int LAPACKE_sspgv( int matrix_order, lapack_int itype, char jobz,\n                          char uplo, lapack_int n, float* ap, float* bp,\n                          float* w, float* z, lapack_int ldz );\nlapack_int LAPACKE_dspgv( int matrix_order, lapack_int itype, char jobz,\n                          char uplo, lapack_int n, double* ap, double* bp,\n                          double* w, double* z, lapack_int ldz );\n\nlapack_int LAPACKE_sspgvd( int matrix_order, lapack_int itype, char jobz,\n                           char uplo, lapack_int n, float* ap, float* bp,\n                           float* w, float* z, lapack_int ldz );\nlapack_int LAPACKE_dspgvd( int matrix_order, lapack_int itype, char jobz,\n                           char uplo, lapack_int n, double* ap, double* bp,\n                           double* w, double* z, lapack_int ldz );\n\nlapack_int LAPACKE_sspgvx( int matrix_order, lapack_int itype, char jobz,\n                           char range, char uplo, lapack_int n, float* ap,\n                           float* bp, float vl, float vu, lapack_int il,\n                           lapack_int iu, float abstol, lapack_int* m, float* w,\n                           float* z, lapack_int ldz, lapack_int* ifail );\nlapack_int LAPACKE_dspgvx( int matrix_order, lapack_int itype, char jobz,\n                           char range, char uplo, lapack_int n, double* ap,\n                           double* bp, double vl, double vu, lapack_int il,\n                           lapack_int iu, double abstol, lapack_int* m,\n                           double* w, double* z, lapack_int ldz,\n                           lapack_int* ifail );\n\nlapack_int LAPACKE_ssprfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* ap, const float* afp,\n                           const lapack_int* ipiv, const float* b,\n                           lapack_int ldb, float* x, lapack_int ldx,\n                           float* ferr, float* berr );\nlapack_int LAPACKE_dsprfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* ap, const double* afp,\n                           const lapack_int* ipiv, const double* b,\n                           lapack_int ldb, double* x, lapack_int ldx,\n                           double* ferr, double* berr );\nlapack_int LAPACKE_csprfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* ap,\n                           const lapack_complex_float* afp,\n                           const lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zsprfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* ap,\n                           const lapack_complex_double* afp,\n                           const lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_sspsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, float* ap, lapack_int* ipiv,\n                          float* b, lapack_int ldb );\nlapack_int LAPACKE_dspsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, double* ap, lapack_int* ipiv,\n                          double* b, lapack_int ldb );\nlapack_int LAPACKE_cspsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_float* ap,\n                          lapack_int* ipiv, lapack_complex_float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_zspsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_double* ap,\n                          lapack_int* ipiv, lapack_complex_double* b,\n                          lapack_int ldb );\n\nlapack_int LAPACKE_sspsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* ap, float* afp,\n                           lapack_int* ipiv, const float* b, lapack_int ldb,\n                           float* x, lapack_int ldx, float* rcond, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_dspsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* ap, double* afp,\n                           lapack_int* ipiv, const double* b, lapack_int ldb,\n                           double* x, lapack_int ldx, double* rcond,\n                           double* ferr, double* berr );\nlapack_int LAPACKE_cspsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* ap,\n                           lapack_complex_float* afp, lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr );\nlapack_int LAPACKE_zspsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* ap,\n                           lapack_complex_double* afp, lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr );\n\nlapack_int LAPACKE_ssptrd( int matrix_order, char uplo, lapack_int n, float* ap,\n                           float* d, float* e, float* tau );\nlapack_int LAPACKE_dsptrd( int matrix_order, char uplo, lapack_int n,\n                           double* ap, double* d, double* e, double* tau );\n\nlapack_int LAPACKE_ssptrf( int matrix_order, char uplo, lapack_int n, float* ap,\n                           lapack_int* ipiv );\nlapack_int LAPACKE_dsptrf( int matrix_order, char uplo, lapack_int n,\n                           double* ap, lapack_int* ipiv );\nlapack_int LAPACKE_csptrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* ap, lapack_int* ipiv );\nlapack_int LAPACKE_zsptrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* ap, lapack_int* ipiv );\n\nlapack_int LAPACKE_ssptri( int matrix_order, char uplo, lapack_int n, float* ap,\n                           const lapack_int* ipiv );\nlapack_int LAPACKE_dsptri( int matrix_order, char uplo, lapack_int n,\n                           double* ap, const lapack_int* ipiv );\nlapack_int LAPACKE_csptri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* ap, const lapack_int* ipiv );\nlapack_int LAPACKE_zsptri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* ap, const lapack_int* ipiv );\n\nlapack_int LAPACKE_ssptrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* ap,\n                           const lapack_int* ipiv, float* b, lapack_int ldb );\nlapack_int LAPACKE_dsptrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* ap,\n                           const lapack_int* ipiv, double* b, lapack_int ldb );\nlapack_int LAPACKE_csptrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* ap,\n                           const lapack_int* ipiv, lapack_complex_float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_zsptrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* ap,\n                           const lapack_int* ipiv, lapack_complex_double* b,\n                           lapack_int ldb );\n\nlapack_int LAPACKE_sstebz( char range, char order, lapack_int n, float vl,\n                           float vu, lapack_int il, lapack_int iu, float abstol,\n                           const float* d, const float* e, lapack_int* m,\n                           lapack_int* nsplit, float* w, lapack_int* iblock,\n                           lapack_int* isplit );\nlapack_int LAPACKE_dstebz( char range, char order, lapack_int n, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, const double* d, const double* e,\n                           lapack_int* m, lapack_int* nsplit, double* w,\n                           lapack_int* iblock, lapack_int* isplit );\n\nlapack_int LAPACKE_sstedc( int matrix_order, char compz, lapack_int n, float* d,\n                           float* e, float* z, lapack_int ldz );\nlapack_int LAPACKE_dstedc( int matrix_order, char compz, lapack_int n,\n                           double* d, double* e, double* z, lapack_int ldz );\nlapack_int LAPACKE_cstedc( int matrix_order, char compz, lapack_int n, float* d,\n                           float* e, lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zstedc( int matrix_order, char compz, lapack_int n,\n                           double* d, double* e, lapack_complex_double* z,\n                           lapack_int ldz );\n\nlapack_int LAPACKE_sstegr( int matrix_order, char jobz, char range,\n                           lapack_int n, float* d, float* e, float vl, float vu,\n                           lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, float* z, lapack_int ldz,\n                           lapack_int* isuppz );\nlapack_int LAPACKE_dstegr( int matrix_order, char jobz, char range,\n                           lapack_int n, double* d, double* e, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w, double* z,\n                           lapack_int ldz, lapack_int* isuppz );\nlapack_int LAPACKE_cstegr( int matrix_order, char jobz, char range,\n                           lapack_int n, float* d, float* e, float vl, float vu,\n                           lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, lapack_complex_float* z,\n                           lapack_int ldz, lapack_int* isuppz );\nlapack_int LAPACKE_zstegr( int matrix_order, char jobz, char range,\n                           lapack_int n, double* d, double* e, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w,\n                           lapack_complex_double* z, lapack_int ldz,\n                           lapack_int* isuppz );\n\nlapack_int LAPACKE_sstein( int matrix_order, lapack_int n, const float* d,\n                           const float* e, lapack_int m, const float* w,\n                           const lapack_int* iblock, const lapack_int* isplit,\n                           float* z, lapack_int ldz, lapack_int* ifailv );\nlapack_int LAPACKE_dstein( int matrix_order, lapack_int n, const double* d,\n                           const double* e, lapack_int m, const double* w,\n                           const lapack_int* iblock, const lapack_int* isplit,\n                           double* z, lapack_int ldz, lapack_int* ifailv );\nlapack_int LAPACKE_cstein( int matrix_order, lapack_int n, const float* d,\n                           const float* e, lapack_int m, const float* w,\n                           const lapack_int* iblock, const lapack_int* isplit,\n                           lapack_complex_float* z, lapack_int ldz,\n                           lapack_int* ifailv );\nlapack_int LAPACKE_zstein( int matrix_order, lapack_int n, const double* d,\n                           const double* e, lapack_int m, const double* w,\n                           const lapack_int* iblock, const lapack_int* isplit,\n                           lapack_complex_double* z, lapack_int ldz,\n                           lapack_int* ifailv );\n\nlapack_int LAPACKE_sstemr( int matrix_order, char jobz, char range,\n                           lapack_int n, float* d, float* e, float vl, float vu,\n                           lapack_int il, lapack_int iu, lapack_int* m,\n                           float* w, float* z, lapack_int ldz, lapack_int nzc,\n                           lapack_int* isuppz, lapack_logical* tryrac );\nlapack_int LAPACKE_dstemr( int matrix_order, char jobz, char range,\n                           lapack_int n, double* d, double* e, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           lapack_int* m, double* w, double* z, lapack_int ldz,\n                           lapack_int nzc, lapack_int* isuppz,\n                           lapack_logical* tryrac );\nlapack_int LAPACKE_cstemr( int matrix_order, char jobz, char range,\n                           lapack_int n, float* d, float* e, float vl, float vu,\n                           lapack_int il, lapack_int iu, lapack_int* m,\n                           float* w, lapack_complex_float* z, lapack_int ldz,\n                           lapack_int nzc, lapack_int* isuppz,\n                           lapack_logical* tryrac );\nlapack_int LAPACKE_zstemr( int matrix_order, char jobz, char range,\n                           lapack_int n, double* d, double* e, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           lapack_int* m, double* w, lapack_complex_double* z,\n                           lapack_int ldz, lapack_int nzc, lapack_int* isuppz,\n                           lapack_logical* tryrac );\n\nlapack_int LAPACKE_ssteqr( int matrix_order, char compz, lapack_int n, float* d,\n                           float* e, float* z, lapack_int ldz );\nlapack_int LAPACKE_dsteqr( int matrix_order, char compz, lapack_int n,\n                           double* d, double* e, double* z, lapack_int ldz );\nlapack_int LAPACKE_csteqr( int matrix_order, char compz, lapack_int n, float* d,\n                           float* e, lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zsteqr( int matrix_order, char compz, lapack_int n,\n                           double* d, double* e, lapack_complex_double* z,\n                           lapack_int ldz );\n\nlapack_int LAPACKE_ssterf( lapack_int n, float* d, float* e );\nlapack_int LAPACKE_dsterf( lapack_int n, double* d, double* e );\n\nlapack_int LAPACKE_sstev( int matrix_order, char jobz, lapack_int n, float* d,\n                          float* e, float* z, lapack_int ldz );\nlapack_int LAPACKE_dstev( int matrix_order, char jobz, lapack_int n, double* d,\n                          double* e, double* z, lapack_int ldz );\n\nlapack_int LAPACKE_sstevd( int matrix_order, char jobz, lapack_int n, float* d,\n                           float* e, float* z, lapack_int ldz );\nlapack_int LAPACKE_dstevd( int matrix_order, char jobz, lapack_int n, double* d,\n                           double* e, double* z, lapack_int ldz );\n\nlapack_int LAPACKE_sstevr( int matrix_order, char jobz, char range,\n                           lapack_int n, float* d, float* e, float vl, float vu,\n                           lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, float* z, lapack_int ldz,\n                           lapack_int* isuppz );\nlapack_int LAPACKE_dstevr( int matrix_order, char jobz, char range,\n                           lapack_int n, double* d, double* e, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w, double* z,\n                           lapack_int ldz, lapack_int* isuppz );\n\nlapack_int LAPACKE_sstevx( int matrix_order, char jobz, char range,\n                           lapack_int n, float* d, float* e, float vl, float vu,\n                           lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, float* z, lapack_int ldz,\n                           lapack_int* ifail );\nlapack_int LAPACKE_dstevx( int matrix_order, char jobz, char range,\n                           lapack_int n, double* d, double* e, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w, double* z,\n                           lapack_int ldz, lapack_int* ifail );\n\nlapack_int LAPACKE_ssycon( int matrix_order, char uplo, lapack_int n,\n                           const float* a, lapack_int lda,\n                           const lapack_int* ipiv, float anorm, float* rcond );\nlapack_int LAPACKE_dsycon( int matrix_order, char uplo, lapack_int n,\n                           const double* a, lapack_int lda,\n                           const lapack_int* ipiv, double anorm,\n                           double* rcond );\nlapack_int LAPACKE_csycon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_int* ipiv, float anorm, float* rcond );\nlapack_int LAPACKE_zsycon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_int* ipiv, double anorm,\n                           double* rcond );\n\nlapack_int LAPACKE_ssyequb( int matrix_order, char uplo, lapack_int n,\n                            const float* a, lapack_int lda, float* s,\n                            float* scond, float* amax );\nlapack_int LAPACKE_dsyequb( int matrix_order, char uplo, lapack_int n,\n                            const double* a, lapack_int lda, double* s,\n                            double* scond, double* amax );\nlapack_int LAPACKE_csyequb( int matrix_order, char uplo, lapack_int n,\n                            const lapack_complex_float* a, lapack_int lda,\n                            float* s, float* scond, float* amax );\nlapack_int LAPACKE_zsyequb( int matrix_order, char uplo, lapack_int n,\n                            const lapack_complex_double* a, lapack_int lda,\n                            double* s, double* scond, double* amax );\n\nlapack_int LAPACKE_ssyev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          float* a, lapack_int lda, float* w );\nlapack_int LAPACKE_dsyev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          double* a, lapack_int lda, double* w );\n\nlapack_int LAPACKE_ssyevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           float* a, lapack_int lda, float* w );\nlapack_int LAPACKE_dsyevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           double* a, lapack_int lda, double* w );\n\nlapack_int LAPACKE_ssyevr( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, float* a, lapack_int lda, float vl,\n                           float vu, lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, float* z, lapack_int ldz,\n                           lapack_int* isuppz );\nlapack_int LAPACKE_dsyevr( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, double* a, lapack_int lda, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w, double* z,\n                           lapack_int ldz, lapack_int* isuppz );\n\nlapack_int LAPACKE_ssyevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, float* a, lapack_int lda, float vl,\n                           float vu, lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, float* z, lapack_int ldz,\n                           lapack_int* ifail );\nlapack_int LAPACKE_dsyevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, double* a, lapack_int lda, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w, double* z,\n                           lapack_int ldz, lapack_int* ifail );\n\nlapack_int LAPACKE_ssygst( int matrix_order, lapack_int itype, char uplo,\n                           lapack_int n, float* a, lapack_int lda,\n                           const float* b, lapack_int ldb );\nlapack_int LAPACKE_dsygst( int matrix_order, lapack_int itype, char uplo,\n                           lapack_int n, double* a, lapack_int lda,\n                           const double* b, lapack_int ldb );\n\nlapack_int LAPACKE_ssygv( int matrix_order, lapack_int itype, char jobz,\n                          char uplo, lapack_int n, float* a, lapack_int lda,\n                          float* b, lapack_int ldb, float* w );\nlapack_int LAPACKE_dsygv( int matrix_order, lapack_int itype, char jobz,\n                          char uplo, lapack_int n, double* a, lapack_int lda,\n                          double* b, lapack_int ldb, double* w );\n\nlapack_int LAPACKE_ssygvd( int matrix_order, lapack_int itype, char jobz,\n                           char uplo, lapack_int n, float* a, lapack_int lda,\n                           float* b, lapack_int ldb, float* w );\nlapack_int LAPACKE_dsygvd( int matrix_order, lapack_int itype, char jobz,\n                           char uplo, lapack_int n, double* a, lapack_int lda,\n                           double* b, lapack_int ldb, double* w );\n\nlapack_int LAPACKE_ssygvx( int matrix_order, lapack_int itype, char jobz,\n                           char range, char uplo, lapack_int n, float* a,\n                           lapack_int lda, float* b, lapack_int ldb, float vl,\n                           float vu, lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, float* z, lapack_int ldz,\n                           lapack_int* ifail );\nlapack_int LAPACKE_dsygvx( int matrix_order, lapack_int itype, char jobz,\n                           char range, char uplo, lapack_int n, double* a,\n                           lapack_int lda, double* b, lapack_int ldb, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w, double* z,\n                           lapack_int ldz, lapack_int* ifail );\n\nlapack_int LAPACKE_ssyrfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* a, lapack_int lda,\n                           const float* af, lapack_int ldaf,\n                           const lapack_int* ipiv, const float* b,\n                           lapack_int ldb, float* x, lapack_int ldx,\n                           float* ferr, float* berr );\nlapack_int LAPACKE_dsyrfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* a, lapack_int lda,\n                           const double* af, lapack_int ldaf,\n                           const lapack_int* ipiv, const double* b,\n                           lapack_int ldb, double* x, lapack_int ldx,\n                           double* ferr, double* berr );\nlapack_int LAPACKE_csyrfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* af,\n                           lapack_int ldaf, const lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zsyrfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* af,\n                           lapack_int ldaf, const lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_ssyrfsx( int matrix_order, char uplo, char equed,\n                            lapack_int n, lapack_int nrhs, const float* a,\n                            lapack_int lda, const float* af, lapack_int ldaf,\n                            const lapack_int* ipiv, const float* s,\n                            const float* b, lapack_int ldb, float* x,\n                            lapack_int ldx, float* rcond, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_dsyrfsx( int matrix_order, char uplo, char equed,\n                            lapack_int n, lapack_int nrhs, const double* a,\n                            lapack_int lda, const double* af, lapack_int ldaf,\n                            const lapack_int* ipiv, const double* s,\n                            const double* b, lapack_int ldb, double* x,\n                            lapack_int ldx, double* rcond, double* berr,\n                            lapack_int n_err_bnds, double* err_bnds_norm,\n                            double* err_bnds_comp, lapack_int nparams,\n                            double* params );\nlapack_int LAPACKE_csyrfsx( int matrix_order, char uplo, char equed,\n                            lapack_int n, lapack_int nrhs,\n                            const lapack_complex_float* a, lapack_int lda,\n                            const lapack_complex_float* af, lapack_int ldaf,\n                            const lapack_int* ipiv, const float* s,\n                            const lapack_complex_float* b, lapack_int ldb,\n                            lapack_complex_float* x, lapack_int ldx,\n                            float* rcond, float* berr, lapack_int n_err_bnds,\n                            float* err_bnds_norm, float* err_bnds_comp,\n                            lapack_int nparams, float* params );\nlapack_int LAPACKE_zsyrfsx( int matrix_order, char uplo, char equed,\n                            lapack_int n, lapack_int nrhs,\n                            const lapack_complex_double* a, lapack_int lda,\n                            const lapack_complex_double* af, lapack_int ldaf,\n                            const lapack_int* ipiv, const double* s,\n                            const lapack_complex_double* b, lapack_int ldb,\n                            lapack_complex_double* x, lapack_int ldx,\n                            double* rcond, double* berr, lapack_int n_err_bnds,\n                            double* err_bnds_norm, double* err_bnds_comp,\n                            lapack_int nparams, double* params );\n\nlapack_int LAPACKE_ssysv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, float* a, lapack_int lda,\n                          lapack_int* ipiv, float* b, lapack_int ldb );\nlapack_int LAPACKE_dsysv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, double* a, lapack_int lda,\n                          lapack_int* ipiv, double* b, lapack_int ldb );\nlapack_int LAPACKE_csysv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_float* a,\n                          lapack_int lda, lapack_int* ipiv,\n                          lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zsysv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_double* a,\n                          lapack_int lda, lapack_int* ipiv,\n                          lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_ssysvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* a, lapack_int lda,\n                           float* af, lapack_int ldaf, lapack_int* ipiv,\n                           const float* b, lapack_int ldb, float* x,\n                           lapack_int ldx, float* rcond, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_dsysvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* a, lapack_int lda,\n                           double* af, lapack_int ldaf, lapack_int* ipiv,\n                           const double* b, lapack_int ldb, double* x,\n                           lapack_int ldx, double* rcond, double* ferr,\n                           double* berr );\nlapack_int LAPACKE_csysvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* af,\n                           lapack_int ldaf, lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr );\nlapack_int LAPACKE_zsysvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* af,\n                           lapack_int ldaf, lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr );\n\nlapack_int LAPACKE_ssysvxx( int matrix_order, char fact, char uplo,\n                            lapack_int n, lapack_int nrhs, float* a,\n                            lapack_int lda, float* af, lapack_int ldaf,\n                            lapack_int* ipiv, char* equed, float* s, float* b,\n                            lapack_int ldb, float* x, lapack_int ldx,\n                            float* rcond, float* rpvgrw, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_dsysvxx( int matrix_order, char fact, char uplo,\n                            lapack_int n, lapack_int nrhs, double* a,\n                            lapack_int lda, double* af, lapack_int ldaf,\n                            lapack_int* ipiv, char* equed, double* s, double* b,\n                            lapack_int ldb, double* x, lapack_int ldx,\n                            double* rcond, double* rpvgrw, double* berr,\n                            lapack_int n_err_bnds, double* err_bnds_norm,\n                            double* err_bnds_comp, lapack_int nparams,\n                            double* params );\nlapack_int LAPACKE_csysvxx( int matrix_order, char fact, char uplo,\n                            lapack_int n, lapack_int nrhs,\n                            lapack_complex_float* a, lapack_int lda,\n                            lapack_complex_float* af, lapack_int ldaf,\n                            lapack_int* ipiv, char* equed, float* s,\n                            lapack_complex_float* b, lapack_int ldb,\n                            lapack_complex_float* x, lapack_int ldx,\n                            float* rcond, float* rpvgrw, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_zsysvxx( int matrix_order, char fact, char uplo,\n                            lapack_int n, lapack_int nrhs,\n                            lapack_complex_double* a, lapack_int lda,\n                            lapack_complex_double* af, lapack_int ldaf,\n                            lapack_int* ipiv, char* equed, double* s,\n                            lapack_complex_double* b, lapack_int ldb,\n                            lapack_complex_double* x, lapack_int ldx,\n                            double* rcond, double* rpvgrw, double* berr,\n                            lapack_int n_err_bnds, double* err_bnds_norm,\n                            double* err_bnds_comp, lapack_int nparams,\n                            double* params );\n\nlapack_int LAPACKE_ssytrd( int matrix_order, char uplo, lapack_int n, float* a,\n                           lapack_int lda, float* d, float* e, float* tau );\nlapack_int LAPACKE_dsytrd( int matrix_order, char uplo, lapack_int n, double* a,\n                           lapack_int lda, double* d, double* e, double* tau );\n\nlapack_int LAPACKE_ssytrf( int matrix_order, char uplo, lapack_int n, float* a,\n                           lapack_int lda, lapack_int* ipiv );\nlapack_int LAPACKE_dsytrf( int matrix_order, char uplo, lapack_int n, double* a,\n                           lapack_int lda, lapack_int* ipiv );\nlapack_int LAPACKE_csytrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int* ipiv );\nlapack_int LAPACKE_zsytrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* ipiv );\n\nlapack_int LAPACKE_ssytri( int matrix_order, char uplo, lapack_int n, float* a,\n                           lapack_int lda, const lapack_int* ipiv );\nlapack_int LAPACKE_dsytri( int matrix_order, char uplo, lapack_int n, double* a,\n                           lapack_int lda, const lapack_int* ipiv );\nlapack_int LAPACKE_csytri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           const lapack_int* ipiv );\nlapack_int LAPACKE_zsytri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           const lapack_int* ipiv );\n\nlapack_int LAPACKE_ssytrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* a, lapack_int lda,\n                           const lapack_int* ipiv, float* b, lapack_int ldb );\nlapack_int LAPACKE_dsytrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* a, lapack_int lda,\n                           const lapack_int* ipiv, double* b, lapack_int ldb );\nlapack_int LAPACKE_csytrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* a,\n                           lapack_int lda, const lapack_int* ipiv,\n                           lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zsytrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* a,\n                           lapack_int lda, const lapack_int* ipiv,\n                           lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_stbcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, lapack_int kd, const float* ab,\n                           lapack_int ldab, float* rcond );\nlapack_int LAPACKE_dtbcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, lapack_int kd, const double* ab,\n                           lapack_int ldab, double* rcond );\nlapack_int LAPACKE_ctbcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, lapack_int kd,\n                           const lapack_complex_float* ab, lapack_int ldab,\n                           float* rcond );\nlapack_int LAPACKE_ztbcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, lapack_int kd,\n                           const lapack_complex_double* ab, lapack_int ldab,\n                           double* rcond );\n\nlapack_int LAPACKE_stbrfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int kd, lapack_int nrhs,\n                           const float* ab, lapack_int ldab, const float* b,\n                           lapack_int ldb, const float* x, lapack_int ldx,\n                           float* ferr, float* berr );\nlapack_int LAPACKE_dtbrfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int kd, lapack_int nrhs,\n                           const double* ab, lapack_int ldab, const double* b,\n                           lapack_int ldb, const double* x, lapack_int ldx,\n                           double* ferr, double* berr );\nlapack_int LAPACKE_ctbrfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int kd, lapack_int nrhs,\n                           const lapack_complex_float* ab, lapack_int ldab,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           const lapack_complex_float* x, lapack_int ldx,\n                           float* ferr, float* berr );\nlapack_int LAPACKE_ztbrfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int kd, lapack_int nrhs,\n                           const lapack_complex_double* ab, lapack_int ldab,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           const lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_stbtrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int kd, lapack_int nrhs,\n                           const float* ab, lapack_int ldab, float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_dtbtrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int kd, lapack_int nrhs,\n                           const double* ab, lapack_int ldab, double* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_ctbtrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int kd, lapack_int nrhs,\n                           const lapack_complex_float* ab, lapack_int ldab,\n                           lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_ztbtrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int kd, lapack_int nrhs,\n                           const lapack_complex_double* ab, lapack_int ldab,\n                           lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_stfsm( int matrix_order, char transr, char side, char uplo,\n                          char trans, char diag, lapack_int m, lapack_int n,\n                          float alpha, const float* a, float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_dtfsm( int matrix_order, char transr, char side, char uplo,\n                          char trans, char diag, lapack_int m, lapack_int n,\n                          double alpha, const double* a, double* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_ctfsm( int matrix_order, char transr, char side, char uplo,\n                          char trans, char diag, lapack_int m, lapack_int n,\n                          lapack_complex_float alpha,\n                          const lapack_complex_float* a,\n                          lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_ztfsm( int matrix_order, char transr, char side, char uplo,\n                          char trans, char diag, lapack_int m, lapack_int n,\n                          lapack_complex_double alpha,\n                          const lapack_complex_double* a,\n                          lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_stftri( int matrix_order, char transr, char uplo, char diag,\n                           lapack_int n, float* a );\nlapack_int LAPACKE_dtftri( int matrix_order, char transr, char uplo, char diag,\n                           lapack_int n, double* a );\nlapack_int LAPACKE_ctftri( int matrix_order, char transr, char uplo, char diag,\n                           lapack_int n, lapack_complex_float* a );\nlapack_int LAPACKE_ztftri( int matrix_order, char transr, char uplo, char diag,\n                           lapack_int n, lapack_complex_double* a );\n\nlapack_int LAPACKE_stfttp( int matrix_order, char transr, char uplo,\n                           lapack_int n, const float* arf, float* ap );\nlapack_int LAPACKE_dtfttp( int matrix_order, char transr, char uplo,\n                           lapack_int n, const double* arf, double* ap );\nlapack_int LAPACKE_ctfttp( int matrix_order, char transr, char uplo,\n                           lapack_int n, const lapack_complex_float* arf,\n                           lapack_complex_float* ap );\nlapack_int LAPACKE_ztfttp( int matrix_order, char transr, char uplo,\n                           lapack_int n, const lapack_complex_double* arf,\n                           lapack_complex_double* ap );\n\nlapack_int LAPACKE_stfttr( int matrix_order, char transr, char uplo,\n                           lapack_int n, const float* arf, float* a,\n                           lapack_int lda );\nlapack_int LAPACKE_dtfttr( int matrix_order, char transr, char uplo,\n                           lapack_int n, const double* arf, double* a,\n                           lapack_int lda );\nlapack_int LAPACKE_ctfttr( int matrix_order, char transr, char uplo,\n                           lapack_int n, const lapack_complex_float* arf,\n                           lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_ztfttr( int matrix_order, char transr, char uplo,\n                           lapack_int n, const lapack_complex_double* arf,\n                           lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_stgevc( int matrix_order, char side, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const float* s, lapack_int lds, const float* p,\n                           lapack_int ldp, float* vl, lapack_int ldvl,\n                           float* vr, lapack_int ldvr, lapack_int mm,\n                           lapack_int* m );\nlapack_int LAPACKE_dtgevc( int matrix_order, char side, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const double* s, lapack_int lds, const double* p,\n                           lapack_int ldp, double* vl, lapack_int ldvl,\n                           double* vr, lapack_int ldvr, lapack_int mm,\n                           lapack_int* m );\nlapack_int LAPACKE_ctgevc( int matrix_order, char side, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const lapack_complex_float* s, lapack_int lds,\n                           const lapack_complex_float* p, lapack_int ldp,\n                           lapack_complex_float* vl, lapack_int ldvl,\n                           lapack_complex_float* vr, lapack_int ldvr,\n                           lapack_int mm, lapack_int* m );\nlapack_int LAPACKE_ztgevc( int matrix_order, char side, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const lapack_complex_double* s, lapack_int lds,\n                           const lapack_complex_double* p, lapack_int ldp,\n                           lapack_complex_double* vl, lapack_int ldvl,\n                           lapack_complex_double* vr, lapack_int ldvr,\n                           lapack_int mm, lapack_int* m );\n\nlapack_int LAPACKE_stgexc( int matrix_order, lapack_logical wantq,\n                           lapack_logical wantz, lapack_int n, float* a,\n                           lapack_int lda, float* b, lapack_int ldb, float* q,\n                           lapack_int ldq, float* z, lapack_int ldz,\n                           lapack_int* ifst, lapack_int* ilst );\nlapack_int LAPACKE_dtgexc( int matrix_order, lapack_logical wantq,\n                           lapack_logical wantz, lapack_int n, double* a,\n                           lapack_int lda, double* b, lapack_int ldb, double* q,\n                           lapack_int ldq, double* z, lapack_int ldz,\n                           lapack_int* ifst, lapack_int* ilst );\nlapack_int LAPACKE_ctgexc( int matrix_order, lapack_logical wantq,\n                           lapack_logical wantz, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* q, lapack_int ldq,\n                           lapack_complex_float* z, lapack_int ldz,\n                           lapack_int ifst, lapack_int ilst );\nlapack_int LAPACKE_ztgexc( int matrix_order, lapack_logical wantq,\n                           lapack_logical wantz, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* q, lapack_int ldq,\n                           lapack_complex_double* z, lapack_int ldz,\n                           lapack_int ifst, lapack_int ilst );\n\nlapack_int LAPACKE_stgsen( int matrix_order, lapack_int ijob,\n                           lapack_logical wantq, lapack_logical wantz,\n                           const lapack_logical* select, lapack_int n, float* a,\n                           lapack_int lda, float* b, lapack_int ldb,\n                           float* alphar, float* alphai, float* beta, float* q,\n                           lapack_int ldq, float* z, lapack_int ldz,\n                           lapack_int* m, float* pl, float* pr, float* dif );\nlapack_int LAPACKE_dtgsen( int matrix_order, lapack_int ijob,\n                           lapack_logical wantq, lapack_logical wantz,\n                           const lapack_logical* select, lapack_int n,\n                           double* a, lapack_int lda, double* b, lapack_int ldb,\n                           double* alphar, double* alphai, double* beta,\n                           double* q, lapack_int ldq, double* z, lapack_int ldz,\n                           lapack_int* m, double* pl, double* pr, double* dif );\nlapack_int LAPACKE_ctgsen( int matrix_order, lapack_int ijob,\n                           lapack_logical wantq, lapack_logical wantz,\n                           const lapack_logical* select, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* alpha,\n                           lapack_complex_float* beta, lapack_complex_float* q,\n                           lapack_int ldq, lapack_complex_float* z,\n                           lapack_int ldz, lapack_int* m, float* pl, float* pr,\n                           float* dif );\nlapack_int LAPACKE_ztgsen( int matrix_order, lapack_int ijob,\n                           lapack_logical wantq, lapack_logical wantz,\n                           const lapack_logical* select, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* alpha,\n                           lapack_complex_double* beta,\n                           lapack_complex_double* q, lapack_int ldq,\n                           lapack_complex_double* z, lapack_int ldz,\n                           lapack_int* m, double* pl, double* pr, double* dif );\n\nlapack_int LAPACKE_stgsja( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int p, lapack_int n,\n                           lapack_int k, lapack_int l, float* a, lapack_int lda,\n                           float* b, lapack_int ldb, float tola, float tolb,\n                           float* alpha, float* beta, float* u, lapack_int ldu,\n                           float* v, lapack_int ldv, float* q, lapack_int ldq,\n                           lapack_int* ncycle );\nlapack_int LAPACKE_dtgsja( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int p, lapack_int n,\n                           lapack_int k, lapack_int l, double* a,\n                           lapack_int lda, double* b, lapack_int ldb,\n                           double tola, double tolb, double* alpha,\n                           double* beta, double* u, lapack_int ldu, double* v,\n                           lapack_int ldv, double* q, lapack_int ldq,\n                           lapack_int* ncycle );\nlapack_int LAPACKE_ctgsja( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int p, lapack_int n,\n                           lapack_int k, lapack_int l, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* b,\n                           lapack_int ldb, float tola, float tolb, float* alpha,\n                           float* beta, lapack_complex_float* u, lapack_int ldu,\n                           lapack_complex_float* v, lapack_int ldv,\n                           lapack_complex_float* q, lapack_int ldq,\n                           lapack_int* ncycle );\nlapack_int LAPACKE_ztgsja( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int p, lapack_int n,\n                           lapack_int k, lapack_int l, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb, double tola, double tolb,\n                           double* alpha, double* beta,\n                           lapack_complex_double* u, lapack_int ldu,\n                           lapack_complex_double* v, lapack_int ldv,\n                           lapack_complex_double* q, lapack_int ldq,\n                           lapack_int* ncycle );\n\nlapack_int LAPACKE_stgsna( int matrix_order, char job, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const float* a, lapack_int lda, const float* b,\n                           lapack_int ldb, const float* vl, lapack_int ldvl,\n                           const float* vr, lapack_int ldvr, float* s,\n                           float* dif, lapack_int mm, lapack_int* m );\nlapack_int LAPACKE_dtgsna( int matrix_order, char job, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const double* a, lapack_int lda, const double* b,\n                           lapack_int ldb, const double* vl, lapack_int ldvl,\n                           const double* vr, lapack_int ldvr, double* s,\n                           double* dif, lapack_int mm, lapack_int* m );\nlapack_int LAPACKE_ctgsna( int matrix_order, char job, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           const lapack_complex_float* vl, lapack_int ldvl,\n                           const lapack_complex_float* vr, lapack_int ldvr,\n                           float* s, float* dif, lapack_int mm, lapack_int* m );\nlapack_int LAPACKE_ztgsna( int matrix_order, char job, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           const lapack_complex_double* vl, lapack_int ldvl,\n                           const lapack_complex_double* vr, lapack_int ldvr,\n                           double* s, double* dif, lapack_int mm,\n                           lapack_int* m );\n\nlapack_int LAPACKE_stgsyl( int matrix_order, char trans, lapack_int ijob,\n                           lapack_int m, lapack_int n, const float* a,\n                           lapack_int lda, const float* b, lapack_int ldb,\n                           float* c, lapack_int ldc, const float* d,\n                           lapack_int ldd, const float* e, lapack_int lde,\n                           float* f, lapack_int ldf, float* scale, float* dif );\nlapack_int LAPACKE_dtgsyl( int matrix_order, char trans, lapack_int ijob,\n                           lapack_int m, lapack_int n, const double* a,\n                           lapack_int lda, const double* b, lapack_int ldb,\n                           double* c, lapack_int ldc, const double* d,\n                           lapack_int ldd, const double* e, lapack_int lde,\n                           double* f, lapack_int ldf, double* scale,\n                           double* dif );\nlapack_int LAPACKE_ctgsyl( int matrix_order, char trans, lapack_int ijob,\n                           lapack_int m, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* c, lapack_int ldc,\n                           const lapack_complex_float* d, lapack_int ldd,\n                           const lapack_complex_float* e, lapack_int lde,\n                           lapack_complex_float* f, lapack_int ldf,\n                           float* scale, float* dif );\nlapack_int LAPACKE_ztgsyl( int matrix_order, char trans, lapack_int ijob,\n                           lapack_int m, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* c, lapack_int ldc,\n                           const lapack_complex_double* d, lapack_int ldd,\n                           const lapack_complex_double* e, lapack_int lde,\n                           lapack_complex_double* f, lapack_int ldf,\n                           double* scale, double* dif );\n\nlapack_int LAPACKE_stpcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, const float* ap, float* rcond );\nlapack_int LAPACKE_dtpcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, const double* ap, double* rcond );\nlapack_int LAPACKE_ctpcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, const lapack_complex_float* ap,\n                           float* rcond );\nlapack_int LAPACKE_ztpcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, const lapack_complex_double* ap,\n                           double* rcond );\n\nlapack_int LAPACKE_stprfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs, const float* ap,\n                           const float* b, lapack_int ldb, const float* x,\n                           lapack_int ldx, float* ferr, float* berr );\nlapack_int LAPACKE_dtprfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs, const double* ap,\n                           const double* b, lapack_int ldb, const double* x,\n                           lapack_int ldx, double* ferr, double* berr );\nlapack_int LAPACKE_ctprfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_float* ap,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           const lapack_complex_float* x, lapack_int ldx,\n                           float* ferr, float* berr );\nlapack_int LAPACKE_ztprfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_double* ap,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           const lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_stptri( int matrix_order, char uplo, char diag, lapack_int n,\n                           float* ap );\nlapack_int LAPACKE_dtptri( int matrix_order, char uplo, char diag, lapack_int n,\n                           double* ap );\nlapack_int LAPACKE_ctptri( int matrix_order, char uplo, char diag, lapack_int n,\n                           lapack_complex_float* ap );\nlapack_int LAPACKE_ztptri( int matrix_order, char uplo, char diag, lapack_int n,\n                           lapack_complex_double* ap );\n\nlapack_int LAPACKE_stptrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs, const float* ap,\n                           float* b, lapack_int ldb );\nlapack_int LAPACKE_dtptrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs, const double* ap,\n                           double* b, lapack_int ldb );\nlapack_int LAPACKE_ctptrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_float* ap,\n                           lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_ztptrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_double* ap,\n                           lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_stpttf( int matrix_order, char transr, char uplo,\n                           lapack_int n, const float* ap, float* arf );\nlapack_int LAPACKE_dtpttf( int matrix_order, char transr, char uplo,\n                           lapack_int n, const double* ap, double* arf );\nlapack_int LAPACKE_ctpttf( int matrix_order, char transr, char uplo,\n                           lapack_int n, const lapack_complex_float* ap,\n                           lapack_complex_float* arf );\nlapack_int LAPACKE_ztpttf( int matrix_order, char transr, char uplo,\n                           lapack_int n, const lapack_complex_double* ap,\n                           lapack_complex_double* arf );\n\nlapack_int LAPACKE_stpttr( int matrix_order, char uplo, lapack_int n,\n                           const float* ap, float* a, lapack_int lda );\nlapack_int LAPACKE_dtpttr( int matrix_order, char uplo, lapack_int n,\n                           const double* ap, double* a, lapack_int lda );\nlapack_int LAPACKE_ctpttr( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_float* ap,\n                           lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_ztpttr( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_double* ap,\n                           lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_strcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, const float* a, lapack_int lda,\n                           float* rcond );\nlapack_int LAPACKE_dtrcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, const double* a, lapack_int lda,\n                           double* rcond );\nlapack_int LAPACKE_ctrcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, const lapack_complex_float* a,\n                           lapack_int lda, float* rcond );\nlapack_int LAPACKE_ztrcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, const lapack_complex_double* a,\n                           lapack_int lda, double* rcond );\n\nlapack_int LAPACKE_strevc( int matrix_order, char side, char howmny,\n                           lapack_logical* select, lapack_int n, const float* t,\n                           lapack_int ldt, float* vl, lapack_int ldvl,\n                           float* vr, lapack_int ldvr, lapack_int mm,\n                           lapack_int* m );\nlapack_int LAPACKE_dtrevc( int matrix_order, char side, char howmny,\n                           lapack_logical* select, lapack_int n,\n                           const double* t, lapack_int ldt, double* vl,\n                           lapack_int ldvl, double* vr, lapack_int ldvr,\n                           lapack_int mm, lapack_int* m );\nlapack_int LAPACKE_ctrevc( int matrix_order, char side, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           lapack_complex_float* t, lapack_int ldt,\n                           lapack_complex_float* vl, lapack_int ldvl,\n                           lapack_complex_float* vr, lapack_int ldvr,\n                           lapack_int mm, lapack_int* m );\nlapack_int LAPACKE_ztrevc( int matrix_order, char side, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           lapack_complex_double* t, lapack_int ldt,\n                           lapack_complex_double* vl, lapack_int ldvl,\n                           lapack_complex_double* vr, lapack_int ldvr,\n                           lapack_int mm, lapack_int* m );\n\nlapack_int LAPACKE_strexc( int matrix_order, char compq, lapack_int n, float* t,\n                           lapack_int ldt, float* q, lapack_int ldq,\n                           lapack_int* ifst, lapack_int* ilst );\nlapack_int LAPACKE_dtrexc( int matrix_order, char compq, lapack_int n,\n                           double* t, lapack_int ldt, double* q, lapack_int ldq,\n                           lapack_int* ifst, lapack_int* ilst );\nlapack_int LAPACKE_ctrexc( int matrix_order, char compq, lapack_int n,\n                           lapack_complex_float* t, lapack_int ldt,\n                           lapack_complex_float* q, lapack_int ldq,\n                           lapack_int ifst, lapack_int ilst );\nlapack_int LAPACKE_ztrexc( int matrix_order, char compq, lapack_int n,\n                           lapack_complex_double* t, lapack_int ldt,\n                           lapack_complex_double* q, lapack_int ldq,\n                           lapack_int ifst, lapack_int ilst );\n\nlapack_int LAPACKE_strrfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs, const float* a,\n                           lapack_int lda, const float* b, lapack_int ldb,\n                           const float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_dtrrfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs, const double* a,\n                           lapack_int lda, const double* b, lapack_int ldb,\n                           const double* x, lapack_int ldx, double* ferr,\n                           double* berr );\nlapack_int LAPACKE_ctrrfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           const lapack_complex_float* x, lapack_int ldx,\n                           float* ferr, float* berr );\nlapack_int LAPACKE_ztrrfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           const lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_strsen( int matrix_order, char job, char compq,\n                           const lapack_logical* select, lapack_int n, float* t,\n                           lapack_int ldt, float* q, lapack_int ldq, float* wr,\n                           float* wi, lapack_int* m, float* s, float* sep );\nlapack_int LAPACKE_dtrsen( int matrix_order, char job, char compq,\n                           const lapack_logical* select, lapack_int n,\n                           double* t, lapack_int ldt, double* q, lapack_int ldq,\n                           double* wr, double* wi, lapack_int* m, double* s,\n                           double* sep );\nlapack_int LAPACKE_ctrsen( int matrix_order, char job, char compq,\n                           const lapack_logical* select, lapack_int n,\n                           lapack_complex_float* t, lapack_int ldt,\n                           lapack_complex_float* q, lapack_int ldq,\n                           lapack_complex_float* w, lapack_int* m, float* s,\n                           float* sep );\nlapack_int LAPACKE_ztrsen( int matrix_order, char job, char compq,\n                           const lapack_logical* select, lapack_int n,\n                           lapack_complex_double* t, lapack_int ldt,\n                           lapack_complex_double* q, lapack_int ldq,\n                           lapack_complex_double* w, lapack_int* m, double* s,\n                           double* sep );\n\nlapack_int LAPACKE_strsna( int matrix_order, char job, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const float* t, lapack_int ldt, const float* vl,\n                           lapack_int ldvl, const float* vr, lapack_int ldvr,\n                           float* s, float* sep, lapack_int mm, lapack_int* m );\nlapack_int LAPACKE_dtrsna( int matrix_order, char job, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const double* t, lapack_int ldt, const double* vl,\n                           lapack_int ldvl, const double* vr, lapack_int ldvr,\n                           double* s, double* sep, lapack_int mm,\n                           lapack_int* m );\nlapack_int LAPACKE_ctrsna( int matrix_order, char job, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const lapack_complex_float* t, lapack_int ldt,\n                           const lapack_complex_float* vl, lapack_int ldvl,\n                           const lapack_complex_float* vr, lapack_int ldvr,\n                           float* s, float* sep, lapack_int mm, lapack_int* m );\nlapack_int LAPACKE_ztrsna( int matrix_order, char job, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const lapack_complex_double* t, lapack_int ldt,\n                           const lapack_complex_double* vl, lapack_int ldvl,\n                           const lapack_complex_double* vr, lapack_int ldvr,\n                           double* s, double* sep, lapack_int mm,\n                           lapack_int* m );\n\nlapack_int LAPACKE_strsyl( int matrix_order, char trana, char tranb,\n                           lapack_int isgn, lapack_int m, lapack_int n,\n                           const float* a, lapack_int lda, const float* b,\n                           lapack_int ldb, float* c, lapack_int ldc,\n                           float* scale );\nlapack_int LAPACKE_dtrsyl( int matrix_order, char trana, char tranb,\n                           lapack_int isgn, lapack_int m, lapack_int n,\n                           const double* a, lapack_int lda, const double* b,\n                           lapack_int ldb, double* c, lapack_int ldc,\n                           double* scale );\nlapack_int LAPACKE_ctrsyl( int matrix_order, char trana, char tranb,\n                           lapack_int isgn, lapack_int m, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* c, lapack_int ldc,\n                           float* scale );\nlapack_int LAPACKE_ztrsyl( int matrix_order, char trana, char tranb,\n                           lapack_int isgn, lapack_int m, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* c, lapack_int ldc,\n                           double* scale );\n\nlapack_int LAPACKE_strtri( int matrix_order, char uplo, char diag, lapack_int n,\n                           float* a, lapack_int lda );\nlapack_int LAPACKE_dtrtri( int matrix_order, char uplo, char diag, lapack_int n,\n                           double* a, lapack_int lda );\nlapack_int LAPACKE_ctrtri( int matrix_order, char uplo, char diag, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_ztrtri( int matrix_order, char uplo, char diag, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_strtrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs, const float* a,\n                           lapack_int lda, float* b, lapack_int ldb );\nlapack_int LAPACKE_dtrtrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs, const double* a,\n                           lapack_int lda, double* b, lapack_int ldb );\nlapack_int LAPACKE_ctrtrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_ztrtrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_strttf( int matrix_order, char transr, char uplo,\n                           lapack_int n, const float* a, lapack_int lda,\n                           float* arf );\nlapack_int LAPACKE_dtrttf( int matrix_order, char transr, char uplo,\n                           lapack_int n, const double* a, lapack_int lda,\n                           double* arf );\nlapack_int LAPACKE_ctrttf( int matrix_order, char transr, char uplo,\n                           lapack_int n, const lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* arf );\nlapack_int LAPACKE_ztrttf( int matrix_order, char transr, char uplo,\n                           lapack_int n, const lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* arf );\n\nlapack_int LAPACKE_strttp( int matrix_order, char uplo, lapack_int n,\n                           const float* a, lapack_int lda, float* ap );\nlapack_int LAPACKE_dtrttp( int matrix_order, char uplo, lapack_int n,\n                           const double* a, lapack_int lda, double* ap );\nlapack_int LAPACKE_ctrttp( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* ap );\nlapack_int LAPACKE_ztrttp( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* ap );\n\nlapack_int LAPACKE_stzrzf( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, float* tau );\nlapack_int LAPACKE_dtzrzf( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, double* tau );\nlapack_int LAPACKE_ctzrzf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* tau );\nlapack_int LAPACKE_ztzrzf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* tau );\n\nlapack_int LAPACKE_cungbr( int matrix_order, char vect, lapack_int m,\n                           lapack_int n, lapack_int k, lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* tau );\nlapack_int LAPACKE_zungbr( int matrix_order, char vect, lapack_int m,\n                           lapack_int n, lapack_int k, lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* tau );\n\nlapack_int LAPACKE_cunghr( int matrix_order, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* tau );\nlapack_int LAPACKE_zunghr( int matrix_order, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* tau );\n\nlapack_int LAPACKE_cunglq( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* tau );\nlapack_int LAPACKE_zunglq( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* tau );\n\nlapack_int LAPACKE_cungql( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* tau );\nlapack_int LAPACKE_zungql( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* tau );\n\nlapack_int LAPACKE_cungqr( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* tau );\nlapack_int LAPACKE_zungqr( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* tau );\n\nlapack_int LAPACKE_cungrq( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* tau );\nlapack_int LAPACKE_zungrq( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* tau );\n\nlapack_int LAPACKE_cungtr( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* tau );\nlapack_int LAPACKE_zungtr( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* tau );\n\nlapack_int LAPACKE_cunmbr( int matrix_order, char vect, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* tau,\n                           lapack_complex_float* c, lapack_int ldc );\nlapack_int LAPACKE_zunmbr( int matrix_order, char vect, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* tau,\n                           lapack_complex_double* c, lapack_int ldc );\n\nlapack_int LAPACKE_cunmhr( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, const lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* tau,\n                           lapack_complex_float* c, lapack_int ldc );\nlapack_int LAPACKE_zunmhr( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, const lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* tau,\n                           lapack_complex_double* c, lapack_int ldc );\n\nlapack_int LAPACKE_cunmlq( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* tau,\n                           lapack_complex_float* c, lapack_int ldc );\nlapack_int LAPACKE_zunmlq( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* tau,\n                           lapack_complex_double* c, lapack_int ldc );\n\nlapack_int LAPACKE_cunmql( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* tau,\n                           lapack_complex_float* c, lapack_int ldc );\nlapack_int LAPACKE_zunmql( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* tau,\n                           lapack_complex_double* c, lapack_int ldc );\n\nlapack_int LAPACKE_cunmqr( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* tau,\n                           lapack_complex_float* c, lapack_int ldc );\nlapack_int LAPACKE_zunmqr( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* tau,\n                           lapack_complex_double* c, lapack_int ldc );\n\nlapack_int LAPACKE_cunmrq( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* tau,\n                           lapack_complex_float* c, lapack_int ldc );\nlapack_int LAPACKE_zunmrq( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* tau,\n                           lapack_complex_double* c, lapack_int ldc );\n\nlapack_int LAPACKE_cunmrz( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           lapack_int l, const lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* tau,\n                           lapack_complex_float* c, lapack_int ldc );\nlapack_int LAPACKE_zunmrz( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           lapack_int l, const lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* tau,\n                           lapack_complex_double* c, lapack_int ldc );\n\nlapack_int LAPACKE_cunmtr( int matrix_order, char side, char uplo, char trans,\n                           lapack_int m, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* tau,\n                           lapack_complex_float* c, lapack_int ldc );\nlapack_int LAPACKE_zunmtr( int matrix_order, char side, char uplo, char trans,\n                           lapack_int m, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* tau,\n                           lapack_complex_double* c, lapack_int ldc );\n\nlapack_int LAPACKE_cupgtr( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_float* ap,\n                           const lapack_complex_float* tau,\n                           lapack_complex_float* q, lapack_int ldq );\nlapack_int LAPACKE_zupgtr( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_double* ap,\n                           const lapack_complex_double* tau,\n                           lapack_complex_double* q, lapack_int ldq );\n\nlapack_int LAPACKE_cupmtr( int matrix_order, char side, char uplo, char trans,\n                           lapack_int m, lapack_int n,\n                           const lapack_complex_float* ap,\n                           const lapack_complex_float* tau,\n                           lapack_complex_float* c, lapack_int ldc );\nlapack_int LAPACKE_zupmtr( int matrix_order, char side, char uplo, char trans,\n                           lapack_int m, lapack_int n,\n                           const lapack_complex_double* ap,\n                           const lapack_complex_double* tau,\n                           lapack_complex_double* c, lapack_int ldc );\n\nlapack_int LAPACKE_sbdsdc_work( int matrix_order, char uplo, char compq,\n                                lapack_int n, float* d, float* e, float* u,\n                                lapack_int ldu, float* vt, lapack_int ldvt,\n                                float* q, lapack_int* iq, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dbdsdc_work( int matrix_order, char uplo, char compq,\n                                lapack_int n, double* d, double* e, double* u,\n                                lapack_int ldu, double* vt, lapack_int ldvt,\n                                double* q, lapack_int* iq, double* work,\n                                lapack_int* iwork );\n\nlapack_int LAPACKE_sbdsqr_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int ncvt, lapack_int nru, lapack_int ncc,\n                                float* d, float* e, float* vt, lapack_int ldvt,\n                                float* u, lapack_int ldu, float* c,\n                                lapack_int ldc, float* work );\nlapack_int LAPACKE_dbdsqr_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int ncvt, lapack_int nru, lapack_int ncc,\n                                double* d, double* e, double* vt,\n                                lapack_int ldvt, double* u, lapack_int ldu,\n                                double* c, lapack_int ldc, double* work );\nlapack_int LAPACKE_cbdsqr_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int ncvt, lapack_int nru, lapack_int ncc,\n                                float* d, float* e, lapack_complex_float* vt,\n                                lapack_int ldvt, lapack_complex_float* u,\n                                lapack_int ldu, lapack_complex_float* c,\n                                lapack_int ldc, float* work );\nlapack_int LAPACKE_zbdsqr_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int ncvt, lapack_int nru, lapack_int ncc,\n                                double* d, double* e, lapack_complex_double* vt,\n                                lapack_int ldvt, lapack_complex_double* u,\n                                lapack_int ldu, lapack_complex_double* c,\n                                lapack_int ldc, double* work );\n\nlapack_int LAPACKE_sdisna_work( char job, lapack_int m, lapack_int n,\n                                const float* d, float* sep );\nlapack_int LAPACKE_ddisna_work( char job, lapack_int m, lapack_int n,\n                                const double* d, double* sep );\n\nlapack_int LAPACKE_sgbbrd_work( int matrix_order, char vect, lapack_int m,\n                                lapack_int n, lapack_int ncc, lapack_int kl,\n                                lapack_int ku, float* ab, lapack_int ldab,\n                                float* d, float* e, float* q, lapack_int ldq,\n                                float* pt, lapack_int ldpt, float* c,\n                                lapack_int ldc, float* work );\nlapack_int LAPACKE_dgbbrd_work( int matrix_order, char vect, lapack_int m,\n                                lapack_int n, lapack_int ncc, lapack_int kl,\n                                lapack_int ku, double* ab, lapack_int ldab,\n                                double* d, double* e, double* q, lapack_int ldq,\n                                double* pt, lapack_int ldpt, double* c,\n                                lapack_int ldc, double* work );\nlapack_int LAPACKE_cgbbrd_work( int matrix_order, char vect, lapack_int m,\n                                lapack_int n, lapack_int ncc, lapack_int kl,\n                                lapack_int ku, lapack_complex_float* ab,\n                                lapack_int ldab, float* d, float* e,\n                                lapack_complex_float* q, lapack_int ldq,\n                                lapack_complex_float* pt, lapack_int ldpt,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zgbbrd_work( int matrix_order, char vect, lapack_int m,\n                                lapack_int n, lapack_int ncc, lapack_int kl,\n                                lapack_int ku, lapack_complex_double* ab,\n                                lapack_int ldab, double* d, double* e,\n                                lapack_complex_double* q, lapack_int ldq,\n                                lapack_complex_double* pt, lapack_int ldpt,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sgbcon_work( int matrix_order, char norm, lapack_int n,\n                                lapack_int kl, lapack_int ku, const float* ab,\n                                lapack_int ldab, const lapack_int* ipiv,\n                                float anorm, float* rcond, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dgbcon_work( int matrix_order, char norm, lapack_int n,\n                                lapack_int kl, lapack_int ku, const double* ab,\n                                lapack_int ldab, const lapack_int* ipiv,\n                                double anorm, double* rcond, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_cgbcon_work( int matrix_order, char norm, lapack_int n,\n                                lapack_int kl, lapack_int ku,\n                                const lapack_complex_float* ab, lapack_int ldab,\n                                const lapack_int* ipiv, float anorm,\n                                float* rcond, lapack_complex_float* work,\n                                float* rwork );\nlapack_int LAPACKE_zgbcon_work( int matrix_order, char norm, lapack_int n,\n                                lapack_int kl, lapack_int ku,\n                                const lapack_complex_double* ab,\n                                lapack_int ldab, const lapack_int* ipiv,\n                                double anorm, double* rcond,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sgbequ_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku, const float* ab,\n                                lapack_int ldab, float* r, float* c,\n                                float* rowcnd, float* colcnd, float* amax );\nlapack_int LAPACKE_dgbequ_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku, const double* ab,\n                                lapack_int ldab, double* r, double* c,\n                                double* rowcnd, double* colcnd, double* amax );\nlapack_int LAPACKE_cgbequ_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku,\n                                const lapack_complex_float* ab, lapack_int ldab,\n                                float* r, float* c, float* rowcnd,\n                                float* colcnd, float* amax );\nlapack_int LAPACKE_zgbequ_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku,\n                                const lapack_complex_double* ab,\n                                lapack_int ldab, double* r, double* c,\n                                double* rowcnd, double* colcnd, double* amax );\n\nlapack_int LAPACKE_sgbequb_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_int kl, lapack_int ku, const float* ab,\n                                 lapack_int ldab, float* r, float* c,\n                                 float* rowcnd, float* colcnd, float* amax );\nlapack_int LAPACKE_dgbequb_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_int kl, lapack_int ku, const double* ab,\n                                 lapack_int ldab, double* r, double* c,\n                                 double* rowcnd, double* colcnd, double* amax );\nlapack_int LAPACKE_cgbequb_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_int kl, lapack_int ku,\n                                 const lapack_complex_float* ab,\n                                 lapack_int ldab, float* r, float* c,\n                                 float* rowcnd, float* colcnd, float* amax );\nlapack_int LAPACKE_zgbequb_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_int kl, lapack_int ku,\n                                 const lapack_complex_double* ab,\n                                 lapack_int ldab, double* r, double* c,\n                                 double* rowcnd, double* colcnd, double* amax );\n\nlapack_int LAPACKE_sgbrfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int kl, lapack_int ku, lapack_int nrhs,\n                                const float* ab, lapack_int ldab,\n                                const float* afb, lapack_int ldafb,\n                                const lapack_int* ipiv, const float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* ferr, float* berr, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dgbrfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int kl, lapack_int ku, lapack_int nrhs,\n                                const double* ab, lapack_int ldab,\n                                const double* afb, lapack_int ldafb,\n                                const lapack_int* ipiv, const double* b,\n                                lapack_int ldb, double* x, lapack_int ldx,\n                                double* ferr, double* berr, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_cgbrfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int kl, lapack_int ku, lapack_int nrhs,\n                                const lapack_complex_float* ab, lapack_int ldab,\n                                const lapack_complex_float* afb,\n                                lapack_int ldafb, const lapack_int* ipiv,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zgbrfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int kl, lapack_int ku, lapack_int nrhs,\n                                const lapack_complex_double* ab,\n                                lapack_int ldab,\n                                const lapack_complex_double* afb,\n                                lapack_int ldafb, const lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sgbrfsx_work( int matrix_order, char trans, char equed,\n                                 lapack_int n, lapack_int kl, lapack_int ku,\n                                 lapack_int nrhs, const float* ab,\n                                 lapack_int ldab, const float* afb,\n                                 lapack_int ldafb, const lapack_int* ipiv,\n                                 const float* r, const float* c, const float* b,\n                                 lapack_int ldb, float* x, lapack_int ldx,\n                                 float* rcond, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, float* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_dgbrfsx_work( int matrix_order, char trans, char equed,\n                                 lapack_int n, lapack_int kl, lapack_int ku,\n                                 lapack_int nrhs, const double* ab,\n                                 lapack_int ldab, const double* afb,\n                                 lapack_int ldafb, const lapack_int* ipiv,\n                                 const double* r, const double* c,\n                                 const double* b, lapack_int ldb, double* x,\n                                 lapack_int ldx, double* rcond, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, double* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_cgbrfsx_work( int matrix_order, char trans, char equed,\n                                 lapack_int n, lapack_int kl, lapack_int ku,\n                                 lapack_int nrhs,\n                                 const lapack_complex_float* ab,\n                                 lapack_int ldab,\n                                 const lapack_complex_float* afb,\n                                 lapack_int ldafb, const lapack_int* ipiv,\n                                 const float* r, const float* c,\n                                 const lapack_complex_float* b, lapack_int ldb,\n                                 lapack_complex_float* x, lapack_int ldx,\n                                 float* rcond, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, lapack_complex_float* work,\n                                 float* rwork );\nlapack_int LAPACKE_zgbrfsx_work( int matrix_order, char trans, char equed,\n                                 lapack_int n, lapack_int kl, lapack_int ku,\n                                 lapack_int nrhs,\n                                 const lapack_complex_double* ab,\n                                 lapack_int ldab,\n                                 const lapack_complex_double* afb,\n                                 lapack_int ldafb, const lapack_int* ipiv,\n                                 const double* r, const double* c,\n                                 const lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* x, lapack_int ldx,\n                                 double* rcond, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, lapack_complex_double* work,\n                                 double* rwork );\n\nlapack_int LAPACKE_sgbsv_work( int matrix_order, lapack_int n, lapack_int kl,\n                               lapack_int ku, lapack_int nrhs, float* ab,\n                               lapack_int ldab, lapack_int* ipiv, float* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_dgbsv_work( int matrix_order, lapack_int n, lapack_int kl,\n                               lapack_int ku, lapack_int nrhs, double* ab,\n                               lapack_int ldab, lapack_int* ipiv, double* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_cgbsv_work( int matrix_order, lapack_int n, lapack_int kl,\n                               lapack_int ku, lapack_int nrhs,\n                               lapack_complex_float* ab, lapack_int ldab,\n                               lapack_int* ipiv, lapack_complex_float* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_zgbsv_work( int matrix_order, lapack_int n, lapack_int kl,\n                               lapack_int ku, lapack_int nrhs,\n                               lapack_complex_double* ab, lapack_int ldab,\n                               lapack_int* ipiv, lapack_complex_double* b,\n                               lapack_int ldb );\n\nlapack_int LAPACKE_sgbsvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int kl, lapack_int ku,\n                                lapack_int nrhs, float* ab, lapack_int ldab,\n                                float* afb, lapack_int ldafb, lapack_int* ipiv,\n                                char* equed, float* r, float* c, float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* rcond, float* ferr, float* berr,\n                                float* work, lapack_int* iwork );\nlapack_int LAPACKE_dgbsvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int kl, lapack_int ku,\n                                lapack_int nrhs, double* ab, lapack_int ldab,\n                                double* afb, lapack_int ldafb, lapack_int* ipiv,\n                                char* equed, double* r, double* c, double* b,\n                                lapack_int ldb, double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_cgbsvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int kl, lapack_int ku,\n                                lapack_int nrhs, lapack_complex_float* ab,\n                                lapack_int ldab, lapack_complex_float* afb,\n                                lapack_int ldafb, lapack_int* ipiv, char* equed,\n                                float* r, float* c, lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* x,\n                                lapack_int ldx, float* rcond, float* ferr,\n                                float* berr, lapack_complex_float* work,\n                                float* rwork );\nlapack_int LAPACKE_zgbsvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int kl, lapack_int ku,\n                                lapack_int nrhs, lapack_complex_double* ab,\n                                lapack_int ldab, lapack_complex_double* afb,\n                                lapack_int ldafb, lapack_int* ipiv, char* equed,\n                                double* r, double* c, lapack_complex_double* b,\n                                lapack_int ldb, lapack_complex_double* x,\n                                lapack_int ldx, double* rcond, double* ferr,\n                                double* berr, lapack_complex_double* work,\n                                double* rwork );\n\nlapack_int LAPACKE_sgbsvxx_work( int matrix_order, char fact, char trans,\n                                 lapack_int n, lapack_int kl, lapack_int ku,\n                                 lapack_int nrhs, float* ab, lapack_int ldab,\n                                 float* afb, lapack_int ldafb, lapack_int* ipiv,\n                                 char* equed, float* r, float* c, float* b,\n                                 lapack_int ldb, float* x, lapack_int ldx,\n                                 float* rcond, float* rpvgrw, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, float* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_dgbsvxx_work( int matrix_order, char fact, char trans,\n                                 lapack_int n, lapack_int kl, lapack_int ku,\n                                 lapack_int nrhs, double* ab, lapack_int ldab,\n                                 double* afb, lapack_int ldafb,\n                                 lapack_int* ipiv, char* equed, double* r,\n                                 double* c, double* b, lapack_int ldb,\n                                 double* x, lapack_int ldx, double* rcond,\n                                 double* rpvgrw, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, double* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_cgbsvxx_work( int matrix_order, char fact, char trans,\n                                 lapack_int n, lapack_int kl, lapack_int ku,\n                                 lapack_int nrhs, lapack_complex_float* ab,\n                                 lapack_int ldab, lapack_complex_float* afb,\n                                 lapack_int ldafb, lapack_int* ipiv,\n                                 char* equed, float* r, float* c,\n                                 lapack_complex_float* b, lapack_int ldb,\n                                 lapack_complex_float* x, lapack_int ldx,\n                                 float* rcond, float* rpvgrw, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, lapack_complex_float* work,\n                                 float* rwork );\nlapack_int LAPACKE_zgbsvxx_work( int matrix_order, char fact, char trans,\n                                 lapack_int n, lapack_int kl, lapack_int ku,\n                                 lapack_int nrhs, lapack_complex_double* ab,\n                                 lapack_int ldab, lapack_complex_double* afb,\n                                 lapack_int ldafb, lapack_int* ipiv,\n                                 char* equed, double* r, double* c,\n                                 lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* x, lapack_int ldx,\n                                 double* rcond, double* rpvgrw, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, lapack_complex_double* work,\n                                 double* rwork );\n\nlapack_int LAPACKE_sgbtrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku, float* ab,\n                                lapack_int ldab, lapack_int* ipiv );\nlapack_int LAPACKE_dgbtrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku, double* ab,\n                                lapack_int ldab, lapack_int* ipiv );\nlapack_int LAPACKE_cgbtrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku,\n                                lapack_complex_float* ab, lapack_int ldab,\n                                lapack_int* ipiv );\nlapack_int LAPACKE_zgbtrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku,\n                                lapack_complex_double* ab, lapack_int ldab,\n                                lapack_int* ipiv );\n\nlapack_int LAPACKE_sgbtrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int kl, lapack_int ku, lapack_int nrhs,\n                                const float* ab, lapack_int ldab,\n                                const lapack_int* ipiv, float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_dgbtrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int kl, lapack_int ku, lapack_int nrhs,\n                                const double* ab, lapack_int ldab,\n                                const lapack_int* ipiv, double* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_cgbtrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int kl, lapack_int ku, lapack_int nrhs,\n                                const lapack_complex_float* ab, lapack_int ldab,\n                                const lapack_int* ipiv, lapack_complex_float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_zgbtrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int kl, lapack_int ku, lapack_int nrhs,\n                                const lapack_complex_double* ab,\n                                lapack_int ldab, const lapack_int* ipiv,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_sgebak_work( int matrix_order, char job, char side,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                const float* scale, lapack_int m, float* v,\n                                lapack_int ldv );\nlapack_int LAPACKE_dgebak_work( int matrix_order, char job, char side,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                const double* scale, lapack_int m, double* v,\n                                lapack_int ldv );\nlapack_int LAPACKE_cgebak_work( int matrix_order, char job, char side,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                const float* scale, lapack_int m,\n                                lapack_complex_float* v, lapack_int ldv );\nlapack_int LAPACKE_zgebak_work( int matrix_order, char job, char side,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                const double* scale, lapack_int m,\n                                lapack_complex_double* v, lapack_int ldv );\n\nlapack_int LAPACKE_sgebal_work( int matrix_order, char job, lapack_int n,\n                                float* a, lapack_int lda, lapack_int* ilo,\n                                lapack_int* ihi, float* scale );\nlapack_int LAPACKE_dgebal_work( int matrix_order, char job, lapack_int n,\n                                double* a, lapack_int lda, lapack_int* ilo,\n                                lapack_int* ihi, double* scale );\nlapack_int LAPACKE_cgebal_work( int matrix_order, char job, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_int* ilo, lapack_int* ihi,\n                                float* scale );\nlapack_int LAPACKE_zgebal_work( int matrix_order, char job, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int* ilo, lapack_int* ihi,\n                                double* scale );\n\nlapack_int LAPACKE_sgebrd_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, float* d, float* e,\n                                float* tauq, float* taup, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dgebrd_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, double* d, double* e,\n                                double* tauq, double* taup, double* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_cgebrd_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                float* d, float* e, lapack_complex_float* tauq,\n                                lapack_complex_float* taup,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zgebrd_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                double* d, double* e,\n                                lapack_complex_double* tauq,\n                                lapack_complex_double* taup,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sgecon_work( int matrix_order, char norm, lapack_int n,\n                                const float* a, lapack_int lda, float anorm,\n                                float* rcond, float* work, lapack_int* iwork );\nlapack_int LAPACKE_dgecon_work( int matrix_order, char norm, lapack_int n,\n                                const double* a, lapack_int lda, double anorm,\n                                double* rcond, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_cgecon_work( int matrix_order, char norm, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                float anorm, float* rcond,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zgecon_work( int matrix_order, char norm, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                double anorm, double* rcond,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sgeequ_work( int matrix_order, lapack_int m, lapack_int n,\n                                const float* a, lapack_int lda, float* r,\n                                float* c, float* rowcnd, float* colcnd,\n                                float* amax );\nlapack_int LAPACKE_dgeequ_work( int matrix_order, lapack_int m, lapack_int n,\n                                const double* a, lapack_int lda, double* r,\n                                double* c, double* rowcnd, double* colcnd,\n                                double* amax );\nlapack_int LAPACKE_cgeequ_work( int matrix_order, lapack_int m, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                float* r, float* c, float* rowcnd,\n                                float* colcnd, float* amax );\nlapack_int LAPACKE_zgeequ_work( int matrix_order, lapack_int m, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                double* r, double* c, double* rowcnd,\n                                double* colcnd, double* amax );\n\nlapack_int LAPACKE_sgeequb_work( int matrix_order, lapack_int m, lapack_int n,\n                                 const float* a, lapack_int lda, float* r,\n                                 float* c, float* rowcnd, float* colcnd,\n                                 float* amax );\nlapack_int LAPACKE_dgeequb_work( int matrix_order, lapack_int m, lapack_int n,\n                                 const double* a, lapack_int lda, double* r,\n                                 double* c, double* rowcnd, double* colcnd,\n                                 double* amax );\nlapack_int LAPACKE_cgeequb_work( int matrix_order, lapack_int m, lapack_int n,\n                                 const lapack_complex_float* a, lapack_int lda,\n                                 float* r, float* c, float* rowcnd,\n                                 float* colcnd, float* amax );\nlapack_int LAPACKE_zgeequb_work( int matrix_order, lapack_int m, lapack_int n,\n                                 const lapack_complex_double* a, lapack_int lda,\n                                 double* r, double* c, double* rowcnd,\n                                 double* colcnd, double* amax );\n\nlapack_int LAPACKE_sgees_work( int matrix_order, char jobvs, char sort,\n                               LAPACK_S_SELECT2 select, lapack_int n, float* a,\n                               lapack_int lda, lapack_int* sdim, float* wr,\n                               float* wi, float* vs, lapack_int ldvs,\n                               float* work, lapack_int lwork,\n                               lapack_logical* bwork );\nlapack_int LAPACKE_dgees_work( int matrix_order, char jobvs, char sort,\n                               LAPACK_D_SELECT2 select, lapack_int n, double* a,\n                               lapack_int lda, lapack_int* sdim, double* wr,\n                               double* wi, double* vs, lapack_int ldvs,\n                               double* work, lapack_int lwork,\n                               lapack_logical* bwork );\nlapack_int LAPACKE_cgees_work( int matrix_order, char jobvs, char sort,\n                               LAPACK_C_SELECT1 select, lapack_int n,\n                               lapack_complex_float* a, lapack_int lda,\n                               lapack_int* sdim, lapack_complex_float* w,\n                               lapack_complex_float* vs, lapack_int ldvs,\n                               lapack_complex_float* work, lapack_int lwork,\n                               float* rwork, lapack_logical* bwork );\nlapack_int LAPACKE_zgees_work( int matrix_order, char jobvs, char sort,\n                               LAPACK_Z_SELECT1 select, lapack_int n,\n                               lapack_complex_double* a, lapack_int lda,\n                               lapack_int* sdim, lapack_complex_double* w,\n                               lapack_complex_double* vs, lapack_int ldvs,\n                               lapack_complex_double* work, lapack_int lwork,\n                               double* rwork, lapack_logical* bwork );\n\nlapack_int LAPACKE_sgeesx_work( int matrix_order, char jobvs, char sort,\n                                LAPACK_S_SELECT2 select, char sense,\n                                lapack_int n, float* a, lapack_int lda,\n                                lapack_int* sdim, float* wr, float* wi,\n                                float* vs, lapack_int ldvs, float* rconde,\n                                float* rcondv, float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork,\n                                lapack_logical* bwork );\nlapack_int LAPACKE_dgeesx_work( int matrix_order, char jobvs, char sort,\n                                LAPACK_D_SELECT2 select, char sense,\n                                lapack_int n, double* a, lapack_int lda,\n                                lapack_int* sdim, double* wr, double* wi,\n                                double* vs, lapack_int ldvs, double* rconde,\n                                double* rcondv, double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork,\n                                lapack_logical* bwork );\nlapack_int LAPACKE_cgeesx_work( int matrix_order, char jobvs, char sort,\n                                LAPACK_C_SELECT1 select, char sense,\n                                lapack_int n, lapack_complex_float* a,\n                                lapack_int lda, lapack_int* sdim,\n                                lapack_complex_float* w,\n                                lapack_complex_float* vs, lapack_int ldvs,\n                                float* rconde, float* rcondv,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork, lapack_logical* bwork );\nlapack_int LAPACKE_zgeesx_work( int matrix_order, char jobvs, char sort,\n                                LAPACK_Z_SELECT1 select, char sense,\n                                lapack_int n, lapack_complex_double* a,\n                                lapack_int lda, lapack_int* sdim,\n                                lapack_complex_double* w,\n                                lapack_complex_double* vs, lapack_int ldvs,\n                                double* rconde, double* rcondv,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork, lapack_logical* bwork );\n\nlapack_int LAPACKE_sgeev_work( int matrix_order, char jobvl, char jobvr,\n                               lapack_int n, float* a, lapack_int lda,\n                               float* wr, float* wi, float* vl, lapack_int ldvl,\n                               float* vr, lapack_int ldvr, float* work,\n                               lapack_int lwork );\nlapack_int LAPACKE_dgeev_work( int matrix_order, char jobvl, char jobvr,\n                               lapack_int n, double* a, lapack_int lda,\n                               double* wr, double* wi, double* vl,\n                               lapack_int ldvl, double* vr, lapack_int ldvr,\n                               double* work, lapack_int lwork );\nlapack_int LAPACKE_cgeev_work( int matrix_order, char jobvl, char jobvr,\n                               lapack_int n, lapack_complex_float* a,\n                               lapack_int lda, lapack_complex_float* w,\n                               lapack_complex_float* vl, lapack_int ldvl,\n                               lapack_complex_float* vr, lapack_int ldvr,\n                               lapack_complex_float* work, lapack_int lwork,\n                               float* rwork );\nlapack_int LAPACKE_zgeev_work( int matrix_order, char jobvl, char jobvr,\n                               lapack_int n, lapack_complex_double* a,\n                               lapack_int lda, lapack_complex_double* w,\n                               lapack_complex_double* vl, lapack_int ldvl,\n                               lapack_complex_double* vr, lapack_int ldvr,\n                               lapack_complex_double* work, lapack_int lwork,\n                               double* rwork );\n\nlapack_int LAPACKE_sgeevx_work( int matrix_order, char balanc, char jobvl,\n                                char jobvr, char sense, lapack_int n, float* a,\n                                lapack_int lda, float* wr, float* wi, float* vl,\n                                lapack_int ldvl, float* vr, lapack_int ldvr,\n                                lapack_int* ilo, lapack_int* ihi, float* scale,\n                                float* abnrm, float* rconde, float* rcondv,\n                                float* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dgeevx_work( int matrix_order, char balanc, char jobvl,\n                                char jobvr, char sense, lapack_int n, double* a,\n                                lapack_int lda, double* wr, double* wi,\n                                double* vl, lapack_int ldvl, double* vr,\n                                lapack_int ldvr, lapack_int* ilo,\n                                lapack_int* ihi, double* scale, double* abnrm,\n                                double* rconde, double* rcondv, double* work,\n                                lapack_int lwork, lapack_int* iwork );\nlapack_int LAPACKE_cgeevx_work( int matrix_order, char balanc, char jobvl,\n                                char jobvr, char sense, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* w,\n                                lapack_complex_float* vl, lapack_int ldvl,\n                                lapack_complex_float* vr, lapack_int ldvr,\n                                lapack_int* ilo, lapack_int* ihi, float* scale,\n                                float* abnrm, float* rconde, float* rcondv,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork );\nlapack_int LAPACKE_zgeevx_work( int matrix_order, char balanc, char jobvl,\n                                char jobvr, char sense, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* w,\n                                lapack_complex_double* vl, lapack_int ldvl,\n                                lapack_complex_double* vr, lapack_int ldvr,\n                                lapack_int* ilo, lapack_int* ihi, double* scale,\n                                double* abnrm, double* rconde, double* rcondv,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork );\n\nlapack_int LAPACKE_sgehrd_work( int matrix_order, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, float* a, lapack_int lda,\n                                float* tau, float* work, lapack_int lwork );\nlapack_int LAPACKE_dgehrd_work( int matrix_order, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, double* a, lapack_int lda,\n                                double* tau, double* work, lapack_int lwork );\nlapack_int LAPACKE_cgehrd_work( int matrix_order, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zgehrd_work( int matrix_order, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sgejsv_work( int matrix_order, char joba, char jobu,\n                                char jobv, char jobr, char jobt, char jobp,\n                                lapack_int m, lapack_int n, float* a,\n                                lapack_int lda, float* sva, float* u,\n                                lapack_int ldu, float* v, lapack_int ldv,\n                                float* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dgejsv_work( int matrix_order, char joba, char jobu,\n                                char jobv, char jobr, char jobt, char jobp,\n                                lapack_int m, lapack_int n, double* a,\n                                lapack_int lda, double* sva, double* u,\n                                lapack_int ldu, double* v, lapack_int ldv,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork );\n\nlapack_int LAPACKE_sgelq2_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, float* tau,\n                                float* work );\nlapack_int LAPACKE_dgelq2_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, double* tau,\n                                double* work );\nlapack_int LAPACKE_cgelq2_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* tau,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zgelq2_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* tau,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_sgelqf_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, float* tau,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dgelqf_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, double* tau,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_cgelqf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zgelqf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sgels_work( int matrix_order, char trans, lapack_int m,\n                               lapack_int n, lapack_int nrhs, float* a,\n                               lapack_int lda, float* b, lapack_int ldb,\n                               float* work, lapack_int lwork );\nlapack_int LAPACKE_dgels_work( int matrix_order, char trans, lapack_int m,\n                               lapack_int n, lapack_int nrhs, double* a,\n                               lapack_int lda, double* b, lapack_int ldb,\n                               double* work, lapack_int lwork );\nlapack_int LAPACKE_cgels_work( int matrix_order, char trans, lapack_int m,\n                               lapack_int n, lapack_int nrhs,\n                               lapack_complex_float* a, lapack_int lda,\n                               lapack_complex_float* b, lapack_int ldb,\n                               lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zgels_work( int matrix_order, char trans, lapack_int m,\n                               lapack_int n, lapack_int nrhs,\n                               lapack_complex_double* a, lapack_int lda,\n                               lapack_complex_double* b, lapack_int ldb,\n                               lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sgelsd_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, float* a, lapack_int lda,\n                                float* b, lapack_int ldb, float* s, float rcond,\n                                lapack_int* rank, float* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dgelsd_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, double* a, lapack_int lda,\n                                double* b, lapack_int ldb, double* s,\n                                double rcond, lapack_int* rank, double* work,\n                                lapack_int lwork, lapack_int* iwork );\nlapack_int LAPACKE_cgelsd_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* b,\n                                lapack_int ldb, float* s, float rcond,\n                                lapack_int* rank, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_zgelsd_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* b,\n                                lapack_int ldb, double* s, double rcond,\n                                lapack_int* rank, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork,\n                                lapack_int* iwork );\n\nlapack_int LAPACKE_sgelss_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, float* a, lapack_int lda,\n                                float* b, lapack_int ldb, float* s, float rcond,\n                                lapack_int* rank, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dgelss_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, double* a, lapack_int lda,\n                                double* b, lapack_int ldb, double* s,\n                                double rcond, lapack_int* rank, double* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_cgelss_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* b,\n                                lapack_int ldb, float* s, float rcond,\n                                lapack_int* rank, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork );\nlapack_int LAPACKE_zgelss_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* b,\n                                lapack_int ldb, double* s, double rcond,\n                                lapack_int* rank, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork );\n\nlapack_int LAPACKE_sgelsy_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, float* a, lapack_int lda,\n                                float* b, lapack_int ldb, lapack_int* jpvt,\n                                float rcond, lapack_int* rank, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dgelsy_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, double* a, lapack_int lda,\n                                double* b, lapack_int ldb, lapack_int* jpvt,\n                                double rcond, lapack_int* rank, double* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_cgelsy_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* b,\n                                lapack_int ldb, lapack_int* jpvt, float rcond,\n                                lapack_int* rank, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork );\nlapack_int LAPACKE_zgelsy_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* b,\n                                lapack_int ldb, lapack_int* jpvt, double rcond,\n                                lapack_int* rank, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork );\n\nlapack_int LAPACKE_sgeqlf_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, float* tau,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dgeqlf_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, double* tau,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_cgeqlf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zgeqlf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sgeqp3_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, lapack_int* jpvt,\n                                float* tau, float* work, lapack_int lwork );\nlapack_int LAPACKE_dgeqp3_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, lapack_int* jpvt,\n                                double* tau, double* work, lapack_int lwork );\nlapack_int LAPACKE_cgeqp3_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_int* jpvt, lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork );\nlapack_int LAPACKE_zgeqp3_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int* jpvt, lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork );\n\nlapack_int LAPACKE_sgeqpf_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, lapack_int* jpvt,\n                                float* tau, float* work );\nlapack_int LAPACKE_dgeqpf_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, lapack_int* jpvt,\n                                double* tau, double* work );\nlapack_int LAPACKE_cgeqpf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_int* jpvt, lapack_complex_float* tau,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zgeqpf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int* jpvt, lapack_complex_double* tau,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sgeqr2_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, float* tau,\n                                float* work );\nlapack_int LAPACKE_dgeqr2_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, double* tau,\n                                double* work );\nlapack_int LAPACKE_cgeqr2_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* tau,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zgeqr2_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* tau,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_sgeqrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, float* tau,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dgeqrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, double* tau,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_cgeqrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zgeqrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sgeqrfp_work( int matrix_order, lapack_int m, lapack_int n,\n                                 float* a, lapack_int lda, float* tau,\n                                 float* work, lapack_int lwork );\nlapack_int LAPACKE_dgeqrfp_work( int matrix_order, lapack_int m, lapack_int n,\n                                 double* a, lapack_int lda, double* tau,\n                                 double* work, lapack_int lwork );\nlapack_int LAPACKE_cgeqrfp_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 lapack_complex_float* tau,\n                                 lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zgeqrfp_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 lapack_complex_double* tau,\n                                 lapack_complex_double* work,\n                                 lapack_int lwork );\n\nlapack_int LAPACKE_sgerfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const float* a, lapack_int lda,\n                                const float* af, lapack_int ldaf,\n                                const lapack_int* ipiv, const float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* ferr, float* berr, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dgerfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const double* a,\n                                lapack_int lda, const double* af,\n                                lapack_int ldaf, const lapack_int* ipiv,\n                                const double* b, lapack_int ldb, double* x,\n                                lapack_int ldx, double* ferr, double* berr,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_cgerfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* af,\n                                lapack_int ldaf, const lapack_int* ipiv,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zgerfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_double* a,\n                                lapack_int lda, const lapack_complex_double* af,\n                                lapack_int ldaf, const lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sgerfsx_work( int matrix_order, char trans, char equed,\n                                 lapack_int n, lapack_int nrhs, const float* a,\n                                 lapack_int lda, const float* af,\n                                 lapack_int ldaf, const lapack_int* ipiv,\n                                 const float* r, const float* c, const float* b,\n                                 lapack_int ldb, float* x, lapack_int ldx,\n                                 float* rcond, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, float* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_dgerfsx_work( int matrix_order, char trans, char equed,\n                                 lapack_int n, lapack_int nrhs, const double* a,\n                                 lapack_int lda, const double* af,\n                                 lapack_int ldaf, const lapack_int* ipiv,\n                                 const double* r, const double* c,\n                                 const double* b, lapack_int ldb, double* x,\n                                 lapack_int ldx, double* rcond, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, double* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_cgerfsx_work( int matrix_order, char trans, char equed,\n                                 lapack_int n, lapack_int nrhs,\n                                 const lapack_complex_float* a, lapack_int lda,\n                                 const lapack_complex_float* af,\n                                 lapack_int ldaf, const lapack_int* ipiv,\n                                 const float* r, const float* c,\n                                 const lapack_complex_float* b, lapack_int ldb,\n                                 lapack_complex_float* x, lapack_int ldx,\n                                 float* rcond, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, lapack_complex_float* work,\n                                 float* rwork );\nlapack_int LAPACKE_zgerfsx_work( int matrix_order, char trans, char equed,\n                                 lapack_int n, lapack_int nrhs,\n                                 const lapack_complex_double* a, lapack_int lda,\n                                 const lapack_complex_double* af,\n                                 lapack_int ldaf, const lapack_int* ipiv,\n                                 const double* r, const double* c,\n                                 const lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* x, lapack_int ldx,\n                                 double* rcond, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, lapack_complex_double* work,\n                                 double* rwork );\n\nlapack_int LAPACKE_sgerqf_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, float* tau,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dgerqf_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, double* tau,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_cgerqf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zgerqf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sgesdd_work( int matrix_order, char jobz, lapack_int m,\n                                lapack_int n, float* a, lapack_int lda,\n                                float* s, float* u, lapack_int ldu, float* vt,\n                                lapack_int ldvt, float* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dgesdd_work( int matrix_order, char jobz, lapack_int m,\n                                lapack_int n, double* a, lapack_int lda,\n                                double* s, double* u, lapack_int ldu,\n                                double* vt, lapack_int ldvt, double* work,\n                                lapack_int lwork, lapack_int* iwork );\nlapack_int LAPACKE_cgesdd_work( int matrix_order, char jobz, lapack_int m,\n                                lapack_int n, lapack_complex_float* a,\n                                lapack_int lda, float* s,\n                                lapack_complex_float* u, lapack_int ldu,\n                                lapack_complex_float* vt, lapack_int ldvt,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork, lapack_int* iwork );\nlapack_int LAPACKE_zgesdd_work( int matrix_order, char jobz, lapack_int m,\n                                lapack_int n, lapack_complex_double* a,\n                                lapack_int lda, double* s,\n                                lapack_complex_double* u, lapack_int ldu,\n                                lapack_complex_double* vt, lapack_int ldvt,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork, lapack_int* iwork );\n\nlapack_int LAPACKE_sgesv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               float* a, lapack_int lda, lapack_int* ipiv,\n                               float* b, lapack_int ldb );\nlapack_int LAPACKE_dgesv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               double* a, lapack_int lda, lapack_int* ipiv,\n                               double* b, lapack_int ldb );\nlapack_int LAPACKE_cgesv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               lapack_complex_float* a, lapack_int lda,\n                               lapack_int* ipiv, lapack_complex_float* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_zgesv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               lapack_complex_double* a, lapack_int lda,\n                               lapack_int* ipiv, lapack_complex_double* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_dsgesv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                                double* a, lapack_int lda, lapack_int* ipiv,\n                                double* b, lapack_int ldb, double* x,\n                                lapack_int ldx, double* work, float* swork,\n                                lapack_int* iter );\nlapack_int LAPACKE_zcgesv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int* ipiv, lapack_complex_double* b,\n                                lapack_int ldb, lapack_complex_double* x,\n                                lapack_int ldx, lapack_complex_double* work,\n                                lapack_complex_float* swork, double* rwork,\n                                lapack_int* iter );\n\nlapack_int LAPACKE_sgesvd_work( int matrix_order, char jobu, char jobvt,\n                                lapack_int m, lapack_int n, float* a,\n                                lapack_int lda, float* s, float* u,\n                                lapack_int ldu, float* vt, lapack_int ldvt,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dgesvd_work( int matrix_order, char jobu, char jobvt,\n                                lapack_int m, lapack_int n, double* a,\n                                lapack_int lda, double* s, double* u,\n                                lapack_int ldu, double* vt, lapack_int ldvt,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_cgesvd_work( int matrix_order, char jobu, char jobvt,\n                                lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                float* s, lapack_complex_float* u,\n                                lapack_int ldu, lapack_complex_float* vt,\n                                lapack_int ldvt, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork );\nlapack_int LAPACKE_zgesvd_work( int matrix_order, char jobu, char jobvt,\n                                lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                double* s, lapack_complex_double* u,\n                                lapack_int ldu, lapack_complex_double* vt,\n                                lapack_int ldvt, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork );\n\nlapack_int LAPACKE_sgesvj_work( int matrix_order, char joba, char jobu,\n                                char jobv, lapack_int m, lapack_int n, float* a,\n                                lapack_int lda, float* sva, lapack_int mv,\n                                float* v, lapack_int ldv, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dgesvj_work( int matrix_order, char joba, char jobu,\n                                char jobv, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, double* sva,\n                                lapack_int mv, double* v, lapack_int ldv,\n                                double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sgesvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int nrhs, float* a,\n                                lapack_int lda, float* af, lapack_int ldaf,\n                                lapack_int* ipiv, char* equed, float* r,\n                                float* c, float* b, lapack_int ldb, float* x,\n                                lapack_int ldx, float* rcond, float* ferr,\n                                float* berr, float* work, lapack_int* iwork );\nlapack_int LAPACKE_dgesvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int nrhs, double* a,\n                                lapack_int lda, double* af, lapack_int ldaf,\n                                lapack_int* ipiv, char* equed, double* r,\n                                double* c, double* b, lapack_int ldb, double* x,\n                                lapack_int ldx, double* rcond, double* ferr,\n                                double* berr, double* work, lapack_int* iwork );\nlapack_int LAPACKE_cgesvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int nrhs,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* af, lapack_int ldaf,\n                                lapack_int* ipiv, char* equed, float* r,\n                                float* c, lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* x,\n                                lapack_int ldx, float* rcond, float* ferr,\n                                float* berr, lapack_complex_float* work,\n                                float* rwork );\nlapack_int LAPACKE_zgesvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int nrhs,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* af, lapack_int ldaf,\n                                lapack_int* ipiv, char* equed, double* r,\n                                double* c, lapack_complex_double* b,\n                                lapack_int ldb, lapack_complex_double* x,\n                                lapack_int ldx, double* rcond, double* ferr,\n                                double* berr, lapack_complex_double* work,\n                                double* rwork );\n\nlapack_int LAPACKE_sgesvxx_work( int matrix_order, char fact, char trans,\n                                 lapack_int n, lapack_int nrhs, float* a,\n                                 lapack_int lda, float* af, lapack_int ldaf,\n                                 lapack_int* ipiv, char* equed, float* r,\n                                 float* c, float* b, lapack_int ldb, float* x,\n                                 lapack_int ldx, float* rcond, float* rpvgrw,\n                                 float* berr, lapack_int n_err_bnds,\n                                 float* err_bnds_norm, float* err_bnds_comp,\n                                 lapack_int nparams, float* params, float* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_dgesvxx_work( int matrix_order, char fact, char trans,\n                                 lapack_int n, lapack_int nrhs, double* a,\n                                 lapack_int lda, double* af, lapack_int ldaf,\n                                 lapack_int* ipiv, char* equed, double* r,\n                                 double* c, double* b, lapack_int ldb,\n                                 double* x, lapack_int ldx, double* rcond,\n                                 double* rpvgrw, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, double* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_cgesvxx_work( int matrix_order, char fact, char trans,\n                                 lapack_int n, lapack_int nrhs,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 lapack_complex_float* af, lapack_int ldaf,\n                                 lapack_int* ipiv, char* equed, float* r,\n                                 float* c, lapack_complex_float* b,\n                                 lapack_int ldb, lapack_complex_float* x,\n                                 lapack_int ldx, float* rcond, float* rpvgrw,\n                                 float* berr, lapack_int n_err_bnds,\n                                 float* err_bnds_norm, float* err_bnds_comp,\n                                 lapack_int nparams, float* params,\n                                 lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zgesvxx_work( int matrix_order, char fact, char trans,\n                                 lapack_int n, lapack_int nrhs,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 lapack_complex_double* af, lapack_int ldaf,\n                                 lapack_int* ipiv, char* equed, double* r,\n                                 double* c, lapack_complex_double* b,\n                                 lapack_int ldb, lapack_complex_double* x,\n                                 lapack_int ldx, double* rcond, double* rpvgrw,\n                                 double* berr, lapack_int n_err_bnds,\n                                 double* err_bnds_norm, double* err_bnds_comp,\n                                 lapack_int nparams, double* params,\n                                 lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sgetf2_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, lapack_int* ipiv );\nlapack_int LAPACKE_dgetf2_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, lapack_int* ipiv );\nlapack_int LAPACKE_cgetf2_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_int* ipiv );\nlapack_int LAPACKE_zgetf2_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int* ipiv );\n\nlapack_int LAPACKE_sgetrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, lapack_int* ipiv );\nlapack_int LAPACKE_dgetrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, lapack_int* ipiv );\nlapack_int LAPACKE_cgetrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_int* ipiv );\nlapack_int LAPACKE_zgetrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int* ipiv );\n\nlapack_int LAPACKE_sgetri_work( int matrix_order, lapack_int n, float* a,\n                                lapack_int lda, const lapack_int* ipiv,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dgetri_work( int matrix_order, lapack_int n, double* a,\n                                lapack_int lda, const lapack_int* ipiv,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_cgetri_work( int matrix_order, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                const lapack_int* ipiv,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zgetri_work( int matrix_order, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                const lapack_int* ipiv,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sgetrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const float* a, lapack_int lda,\n                                const lapack_int* ipiv, float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_dgetrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const double* a,\n                                lapack_int lda, const lapack_int* ipiv,\n                                double* b, lapack_int ldb );\nlapack_int LAPACKE_cgetrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* a,\n                                lapack_int lda, const lapack_int* ipiv,\n                                lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zgetrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_double* a,\n                                lapack_int lda, const lapack_int* ipiv,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_sggbak_work( int matrix_order, char job, char side,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                const float* lscale, const float* rscale,\n                                lapack_int m, float* v, lapack_int ldv );\nlapack_int LAPACKE_dggbak_work( int matrix_order, char job, char side,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                const double* lscale, const double* rscale,\n                                lapack_int m, double* v, lapack_int ldv );\nlapack_int LAPACKE_cggbak_work( int matrix_order, char job, char side,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                const float* lscale, const float* rscale,\n                                lapack_int m, lapack_complex_float* v,\n                                lapack_int ldv );\nlapack_int LAPACKE_zggbak_work( int matrix_order, char job, char side,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                const double* lscale, const double* rscale,\n                                lapack_int m, lapack_complex_double* v,\n                                lapack_int ldv );\n\nlapack_int LAPACKE_sggbal_work( int matrix_order, char job, lapack_int n,\n                                float* a, lapack_int lda, float* b,\n                                lapack_int ldb, lapack_int* ilo,\n                                lapack_int* ihi, float* lscale, float* rscale,\n                                float* work );\nlapack_int LAPACKE_dggbal_work( int matrix_order, char job, lapack_int n,\n                                double* a, lapack_int lda, double* b,\n                                lapack_int ldb, lapack_int* ilo,\n                                lapack_int* ihi, double* lscale, double* rscale,\n                                double* work );\nlapack_int LAPACKE_cggbal_work( int matrix_order, char job, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb,\n                                lapack_int* ilo, lapack_int* ihi, float* lscale,\n                                float* rscale, float* work );\nlapack_int LAPACKE_zggbal_work( int matrix_order, char job, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                lapack_int* ilo, lapack_int* ihi,\n                                double* lscale, double* rscale, double* work );\n\nlapack_int LAPACKE_sgges_work( int matrix_order, char jobvsl, char jobvsr,\n                               char sort, LAPACK_S_SELECT3 selctg, lapack_int n,\n                               float* a, lapack_int lda, float* b,\n                               lapack_int ldb, lapack_int* sdim, float* alphar,\n                               float* alphai, float* beta, float* vsl,\n                               lapack_int ldvsl, float* vsr, lapack_int ldvsr,\n                               float* work, lapack_int lwork,\n                               lapack_logical* bwork );\nlapack_int LAPACKE_dgges_work( int matrix_order, char jobvsl, char jobvsr,\n                               char sort, LAPACK_D_SELECT3 selctg, lapack_int n,\n                               double* a, lapack_int lda, double* b,\n                               lapack_int ldb, lapack_int* sdim, double* alphar,\n                               double* alphai, double* beta, double* vsl,\n                               lapack_int ldvsl, double* vsr, lapack_int ldvsr,\n                               double* work, lapack_int lwork,\n                               lapack_logical* bwork );\nlapack_int LAPACKE_cgges_work( int matrix_order, char jobvsl, char jobvsr,\n                               char sort, LAPACK_C_SELECT2 selctg, lapack_int n,\n                               lapack_complex_float* a, lapack_int lda,\n                               lapack_complex_float* b, lapack_int ldb,\n                               lapack_int* sdim, lapack_complex_float* alpha,\n                               lapack_complex_float* beta,\n                               lapack_complex_float* vsl, lapack_int ldvsl,\n                               lapack_complex_float* vsr, lapack_int ldvsr,\n                               lapack_complex_float* work, lapack_int lwork,\n                               float* rwork, lapack_logical* bwork );\nlapack_int LAPACKE_zgges_work( int matrix_order, char jobvsl, char jobvsr,\n                               char sort, LAPACK_Z_SELECT2 selctg, lapack_int n,\n                               lapack_complex_double* a, lapack_int lda,\n                               lapack_complex_double* b, lapack_int ldb,\n                               lapack_int* sdim, lapack_complex_double* alpha,\n                               lapack_complex_double* beta,\n                               lapack_complex_double* vsl, lapack_int ldvsl,\n                               lapack_complex_double* vsr, lapack_int ldvsr,\n                               lapack_complex_double* work, lapack_int lwork,\n                               double* rwork, lapack_logical* bwork );\n\nlapack_int LAPACKE_sggesx_work( int matrix_order, char jobvsl, char jobvsr,\n                                char sort, LAPACK_S_SELECT3 selctg, char sense,\n                                lapack_int n, float* a, lapack_int lda,\n                                float* b, lapack_int ldb, lapack_int* sdim,\n                                float* alphar, float* alphai, float* beta,\n                                float* vsl, lapack_int ldvsl, float* vsr,\n                                lapack_int ldvsr, float* rconde, float* rcondv,\n                                float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork,\n                                lapack_logical* bwork );\nlapack_int LAPACKE_dggesx_work( int matrix_order, char jobvsl, char jobvsr,\n                                char sort, LAPACK_D_SELECT3 selctg, char sense,\n                                lapack_int n, double* a, lapack_int lda,\n                                double* b, lapack_int ldb, lapack_int* sdim,\n                                double* alphar, double* alphai, double* beta,\n                                double* vsl, lapack_int ldvsl, double* vsr,\n                                lapack_int ldvsr, double* rconde,\n                                double* rcondv, double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork,\n                                lapack_logical* bwork );\nlapack_int LAPACKE_cggesx_work( int matrix_order, char jobvsl, char jobvsr,\n                                char sort, LAPACK_C_SELECT2 selctg, char sense,\n                                lapack_int n, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* b,\n                                lapack_int ldb, lapack_int* sdim,\n                                lapack_complex_float* alpha,\n                                lapack_complex_float* beta,\n                                lapack_complex_float* vsl, lapack_int ldvsl,\n                                lapack_complex_float* vsr, lapack_int ldvsr,\n                                float* rconde, float* rcondv,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork, lapack_int* iwork,\n                                lapack_int liwork, lapack_logical* bwork );\nlapack_int LAPACKE_zggesx_work( int matrix_order, char jobvsl, char jobvsr,\n                                char sort, LAPACK_Z_SELECT2 selctg, char sense,\n                                lapack_int n, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* b,\n                                lapack_int ldb, lapack_int* sdim,\n                                lapack_complex_double* alpha,\n                                lapack_complex_double* beta,\n                                lapack_complex_double* vsl, lapack_int ldvsl,\n                                lapack_complex_double* vsr, lapack_int ldvsr,\n                                double* rconde, double* rcondv,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork, lapack_int* iwork,\n                                lapack_int liwork, lapack_logical* bwork );\n\nlapack_int LAPACKE_sggev_work( int matrix_order, char jobvl, char jobvr,\n                               lapack_int n, float* a, lapack_int lda, float* b,\n                               lapack_int ldb, float* alphar, float* alphai,\n                               float* beta, float* vl, lapack_int ldvl,\n                               float* vr, lapack_int ldvr, float* work,\n                               lapack_int lwork );\nlapack_int LAPACKE_dggev_work( int matrix_order, char jobvl, char jobvr,\n                               lapack_int n, double* a, lapack_int lda,\n                               double* b, lapack_int ldb, double* alphar,\n                               double* alphai, double* beta, double* vl,\n                               lapack_int ldvl, double* vr, lapack_int ldvr,\n                               double* work, lapack_int lwork );\nlapack_int LAPACKE_cggev_work( int matrix_order, char jobvl, char jobvr,\n                               lapack_int n, lapack_complex_float* a,\n                               lapack_int lda, lapack_complex_float* b,\n                               lapack_int ldb, lapack_complex_float* alpha,\n                               lapack_complex_float* beta,\n                               lapack_complex_float* vl, lapack_int ldvl,\n                               lapack_complex_float* vr, lapack_int ldvr,\n                               lapack_complex_float* work, lapack_int lwork,\n                               float* rwork );\nlapack_int LAPACKE_zggev_work( int matrix_order, char jobvl, char jobvr,\n                               lapack_int n, lapack_complex_double* a,\n                               lapack_int lda, lapack_complex_double* b,\n                               lapack_int ldb, lapack_complex_double* alpha,\n                               lapack_complex_double* beta,\n                               lapack_complex_double* vl, lapack_int ldvl,\n                               lapack_complex_double* vr, lapack_int ldvr,\n                               lapack_complex_double* work, lapack_int lwork,\n                               double* rwork );\n\nlapack_int LAPACKE_sggevx_work( int matrix_order, char balanc, char jobvl,\n                                char jobvr, char sense, lapack_int n, float* a,\n                                lapack_int lda, float* b, lapack_int ldb,\n                                float* alphar, float* alphai, float* beta,\n                                float* vl, lapack_int ldvl, float* vr,\n                                lapack_int ldvr, lapack_int* ilo,\n                                lapack_int* ihi, float* lscale, float* rscale,\n                                float* abnrm, float* bbnrm, float* rconde,\n                                float* rcondv, float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_logical* bwork );\nlapack_int LAPACKE_dggevx_work( int matrix_order, char balanc, char jobvl,\n                                char jobvr, char sense, lapack_int n, double* a,\n                                lapack_int lda, double* b, lapack_int ldb,\n                                double* alphar, double* alphai, double* beta,\n                                double* vl, lapack_int ldvl, double* vr,\n                                lapack_int ldvr, lapack_int* ilo,\n                                lapack_int* ihi, double* lscale, double* rscale,\n                                double* abnrm, double* bbnrm, double* rconde,\n                                double* rcondv, double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_logical* bwork );\nlapack_int LAPACKE_cggevx_work( int matrix_order, char balanc, char jobvl,\n                                char jobvr, char sense, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* alpha,\n                                lapack_complex_float* beta,\n                                lapack_complex_float* vl, lapack_int ldvl,\n                                lapack_complex_float* vr, lapack_int ldvr,\n                                lapack_int* ilo, lapack_int* ihi, float* lscale,\n                                float* rscale, float* abnrm, float* bbnrm,\n                                float* rconde, float* rcondv,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork, lapack_int* iwork,\n                                lapack_logical* bwork );\nlapack_int LAPACKE_zggevx_work( int matrix_order, char balanc, char jobvl,\n                                char jobvr, char sense, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* alpha,\n                                lapack_complex_double* beta,\n                                lapack_complex_double* vl, lapack_int ldvl,\n                                lapack_complex_double* vr, lapack_int ldvr,\n                                lapack_int* ilo, lapack_int* ihi,\n                                double* lscale, double* rscale, double* abnrm,\n                                double* bbnrm, double* rconde, double* rcondv,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork, lapack_int* iwork,\n                                lapack_logical* bwork );\n\nlapack_int LAPACKE_sggglm_work( int matrix_order, lapack_int n, lapack_int m,\n                                lapack_int p, float* a, lapack_int lda,\n                                float* b, lapack_int ldb, float* d, float* x,\n                                float* y, float* work, lapack_int lwork );\nlapack_int LAPACKE_dggglm_work( int matrix_order, lapack_int n, lapack_int m,\n                                lapack_int p, double* a, lapack_int lda,\n                                double* b, lapack_int ldb, double* d, double* x,\n                                double* y, double* work, lapack_int lwork );\nlapack_int LAPACKE_cggglm_work( int matrix_order, lapack_int n, lapack_int m,\n                                lapack_int p, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* d,\n                                lapack_complex_float* x,\n                                lapack_complex_float* y,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zggglm_work( int matrix_order, lapack_int n, lapack_int m,\n                                lapack_int p, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* b,\n                                lapack_int ldb, lapack_complex_double* d,\n                                lapack_complex_double* x,\n                                lapack_complex_double* y,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sgghrd_work( int matrix_order, char compq, char compz,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                float* a, lapack_int lda, float* b,\n                                lapack_int ldb, float* q, lapack_int ldq,\n                                float* z, lapack_int ldz );\nlapack_int LAPACKE_dgghrd_work( int matrix_order, char compq, char compz,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                double* a, lapack_int lda, double* b,\n                                lapack_int ldb, double* q, lapack_int ldq,\n                                double* z, lapack_int ldz );\nlapack_int LAPACKE_cgghrd_work( int matrix_order, char compq, char compz,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* q, lapack_int ldq,\n                                lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zgghrd_work( int matrix_order, char compq, char compz,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* q, lapack_int ldq,\n                                lapack_complex_double* z, lapack_int ldz );\n\nlapack_int LAPACKE_sgglse_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int p, float* a, lapack_int lda,\n                                float* b, lapack_int ldb, float* c, float* d,\n                                float* x, float* work, lapack_int lwork );\nlapack_int LAPACKE_dgglse_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int p, double* a, lapack_int lda,\n                                double* b, lapack_int ldb, double* c, double* d,\n                                double* x, double* work, lapack_int lwork );\nlapack_int LAPACKE_cgglse_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int p, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* c,\n                                lapack_complex_float* d,\n                                lapack_complex_float* x,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zgglse_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int p, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* b,\n                                lapack_int ldb, lapack_complex_double* c,\n                                lapack_complex_double* d,\n                                lapack_complex_double* x,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sggqrf_work( int matrix_order, lapack_int n, lapack_int m,\n                                lapack_int p, float* a, lapack_int lda,\n                                float* taua, float* b, lapack_int ldb,\n                                float* taub, float* work, lapack_int lwork );\nlapack_int LAPACKE_dggqrf_work( int matrix_order, lapack_int n, lapack_int m,\n                                lapack_int p, double* a, lapack_int lda,\n                                double* taua, double* b, lapack_int ldb,\n                                double* taub, double* work, lapack_int lwork );\nlapack_int LAPACKE_cggqrf_work( int matrix_order, lapack_int n, lapack_int m,\n                                lapack_int p, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* taua,\n                                lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* taub,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zggqrf_work( int matrix_order, lapack_int n, lapack_int m,\n                                lapack_int p, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* taua,\n                                lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* taub,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sggrqf_work( int matrix_order, lapack_int m, lapack_int p,\n                                lapack_int n, float* a, lapack_int lda,\n                                float* taua, float* b, lapack_int ldb,\n                                float* taub, float* work, lapack_int lwork );\nlapack_int LAPACKE_dggrqf_work( int matrix_order, lapack_int m, lapack_int p,\n                                lapack_int n, double* a, lapack_int lda,\n                                double* taua, double* b, lapack_int ldb,\n                                double* taub, double* work, lapack_int lwork );\nlapack_int LAPACKE_cggrqf_work( int matrix_order, lapack_int m, lapack_int p,\n                                lapack_int n, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* taua,\n                                lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* taub,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zggrqf_work( int matrix_order, lapack_int m, lapack_int p,\n                                lapack_int n, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* taua,\n                                lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* taub,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sggsvd_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int n,\n                                lapack_int p, lapack_int* k, lapack_int* l,\n                                float* a, lapack_int lda, float* b,\n                                lapack_int ldb, float* alpha, float* beta,\n                                float* u, lapack_int ldu, float* v,\n                                lapack_int ldv, float* q, lapack_int ldq,\n                                float* work, lapack_int* iwork );\nlapack_int LAPACKE_dggsvd_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int n,\n                                lapack_int p, lapack_int* k, lapack_int* l,\n                                double* a, lapack_int lda, double* b,\n                                lapack_int ldb, double* alpha, double* beta,\n                                double* u, lapack_int ldu, double* v,\n                                lapack_int ldv, double* q, lapack_int ldq,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_cggsvd_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int n,\n                                lapack_int p, lapack_int* k, lapack_int* l,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb,\n                                float* alpha, float* beta,\n                                lapack_complex_float* u, lapack_int ldu,\n                                lapack_complex_float* v, lapack_int ldv,\n                                lapack_complex_float* q, lapack_int ldq,\n                                lapack_complex_float* work, float* rwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_zggsvd_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int n,\n                                lapack_int p, lapack_int* k, lapack_int* l,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                double* alpha, double* beta,\n                                lapack_complex_double* u, lapack_int ldu,\n                                lapack_complex_double* v, lapack_int ldv,\n                                lapack_complex_double* q, lapack_int ldq,\n                                lapack_complex_double* work, double* rwork,\n                                lapack_int* iwork );\n\nlapack_int LAPACKE_sggsvp_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int p,\n                                lapack_int n, float* a, lapack_int lda,\n                                float* b, lapack_int ldb, float tola,\n                                float tolb, lapack_int* k, lapack_int* l,\n                                float* u, lapack_int ldu, float* v,\n                                lapack_int ldv, float* q, lapack_int ldq,\n                                lapack_int* iwork, float* tau, float* work );\nlapack_int LAPACKE_dggsvp_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int p,\n                                lapack_int n, double* a, lapack_int lda,\n                                double* b, lapack_int ldb, double tola,\n                                double tolb, lapack_int* k, lapack_int* l,\n                                double* u, lapack_int ldu, double* v,\n                                lapack_int ldv, double* q, lapack_int ldq,\n                                lapack_int* iwork, double* tau, double* work );\nlapack_int LAPACKE_cggsvp_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int p,\n                                lapack_int n, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* b,\n                                lapack_int ldb, float tola, float tolb,\n                                lapack_int* k, lapack_int* l,\n                                lapack_complex_float* u, lapack_int ldu,\n                                lapack_complex_float* v, lapack_int ldv,\n                                lapack_complex_float* q, lapack_int ldq,\n                                lapack_int* iwork, float* rwork,\n                                lapack_complex_float* tau,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zggsvp_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int p,\n                                lapack_int n, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* b,\n                                lapack_int ldb, double tola, double tolb,\n                                lapack_int* k, lapack_int* l,\n                                lapack_complex_double* u, lapack_int ldu,\n                                lapack_complex_double* v, lapack_int ldv,\n                                lapack_complex_double* q, lapack_int ldq,\n                                lapack_int* iwork, double* rwork,\n                                lapack_complex_double* tau,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_sgtcon_work( char norm, lapack_int n, const float* dl,\n                                const float* d, const float* du,\n                                const float* du2, const lapack_int* ipiv,\n                                float anorm, float* rcond, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dgtcon_work( char norm, lapack_int n, const double* dl,\n                                const double* d, const double* du,\n                                const double* du2, const lapack_int* ipiv,\n                                double anorm, double* rcond, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_cgtcon_work( char norm, lapack_int n,\n                                const lapack_complex_float* dl,\n                                const lapack_complex_float* d,\n                                const lapack_complex_float* du,\n                                const lapack_complex_float* du2,\n                                const lapack_int* ipiv, float anorm,\n                                float* rcond, lapack_complex_float* work );\nlapack_int LAPACKE_zgtcon_work( char norm, lapack_int n,\n                                const lapack_complex_double* dl,\n                                const lapack_complex_double* d,\n                                const lapack_complex_double* du,\n                                const lapack_complex_double* du2,\n                                const lapack_int* ipiv, double anorm,\n                                double* rcond, lapack_complex_double* work );\n\nlapack_int LAPACKE_sgtrfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const float* dl,\n                                const float* d, const float* du,\n                                const float* dlf, const float* df,\n                                const float* duf, const float* du2,\n                                const lapack_int* ipiv, const float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* ferr, float* berr, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dgtrfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const double* dl,\n                                const double* d, const double* du,\n                                const double* dlf, const double* df,\n                                const double* duf, const double* du2,\n                                const lapack_int* ipiv, const double* b,\n                                lapack_int ldb, double* x, lapack_int ldx,\n                                double* ferr, double* berr, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_cgtrfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* dl,\n                                const lapack_complex_float* d,\n                                const lapack_complex_float* du,\n                                const lapack_complex_float* dlf,\n                                const lapack_complex_float* df,\n                                const lapack_complex_float* duf,\n                                const lapack_complex_float* du2,\n                                const lapack_int* ipiv,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zgtrfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs,\n                                const lapack_complex_double* dl,\n                                const lapack_complex_double* d,\n                                const lapack_complex_double* du,\n                                const lapack_complex_double* dlf,\n                                const lapack_complex_double* df,\n                                const lapack_complex_double* duf,\n                                const lapack_complex_double* du2,\n                                const lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sgtsv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               float* dl, float* d, float* du, float* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_dgtsv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               double* dl, double* d, double* du, double* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_cgtsv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               lapack_complex_float* dl,\n                               lapack_complex_float* d,\n                               lapack_complex_float* du,\n                               lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zgtsv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               lapack_complex_double* dl,\n                               lapack_complex_double* d,\n                               lapack_complex_double* du,\n                               lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_sgtsvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int nrhs, const float* dl,\n                                const float* d, const float* du, float* dlf,\n                                float* df, float* duf, float* du2,\n                                lapack_int* ipiv, const float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* rcond, float* ferr, float* berr,\n                                float* work, lapack_int* iwork );\nlapack_int LAPACKE_dgtsvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int nrhs, const double* dl,\n                                const double* d, const double* du, double* dlf,\n                                double* df, double* duf, double* du2,\n                                lapack_int* ipiv, const double* b,\n                                lapack_int ldb, double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_cgtsvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_float* dl,\n                                const lapack_complex_float* d,\n                                const lapack_complex_float* du,\n                                lapack_complex_float* dlf,\n                                lapack_complex_float* df,\n                                lapack_complex_float* duf,\n                                lapack_complex_float* du2, lapack_int* ipiv,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* rcond, float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zgtsvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_double* dl,\n                                const lapack_complex_double* d,\n                                const lapack_complex_double* du,\n                                lapack_complex_double* dlf,\n                                lapack_complex_double* df,\n                                lapack_complex_double* duf,\n                                lapack_complex_double* du2, lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sgttrf_work( lapack_int n, float* dl, float* d, float* du,\n                                float* du2, lapack_int* ipiv );\nlapack_int LAPACKE_dgttrf_work( lapack_int n, double* dl, double* d, double* du,\n                                double* du2, lapack_int* ipiv );\nlapack_int LAPACKE_cgttrf_work( lapack_int n, lapack_complex_float* dl,\n                                lapack_complex_float* d,\n                                lapack_complex_float* du,\n                                lapack_complex_float* du2, lapack_int* ipiv );\nlapack_int LAPACKE_zgttrf_work( lapack_int n, lapack_complex_double* dl,\n                                lapack_complex_double* d,\n                                lapack_complex_double* du,\n                                lapack_complex_double* du2, lapack_int* ipiv );\n\nlapack_int LAPACKE_sgttrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const float* dl,\n                                const float* d, const float* du,\n                                const float* du2, const lapack_int* ipiv,\n                                float* b, lapack_int ldb );\nlapack_int LAPACKE_dgttrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const double* dl,\n                                const double* d, const double* du,\n                                const double* du2, const lapack_int* ipiv,\n                                double* b, lapack_int ldb );\nlapack_int LAPACKE_cgttrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* dl,\n                                const lapack_complex_float* d,\n                                const lapack_complex_float* du,\n                                const lapack_complex_float* du2,\n                                const lapack_int* ipiv, lapack_complex_float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_zgttrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs,\n                                const lapack_complex_double* dl,\n                                const lapack_complex_double* d,\n                                const lapack_complex_double* du,\n                                const lapack_complex_double* du2,\n                                const lapack_int* ipiv,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_chbev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_int kd,\n                               lapack_complex_float* ab, lapack_int ldab,\n                               float* w, lapack_complex_float* z,\n                               lapack_int ldz, lapack_complex_float* work,\n                               float* rwork );\nlapack_int LAPACKE_zhbev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_int kd,\n                               lapack_complex_double* ab, lapack_int ldab,\n                               double* w, lapack_complex_double* z,\n                               lapack_int ldz, lapack_complex_double* work,\n                               double* rwork );\n\nlapack_int LAPACKE_chbevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_int kd,\n                                lapack_complex_float* ab, lapack_int ldab,\n                                float* w, lapack_complex_float* z,\n                                lapack_int ldz, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork,\n                                lapack_int lrwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_zhbevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_int kd,\n                                lapack_complex_double* ab, lapack_int ldab,\n                                double* w, lapack_complex_double* z,\n                                lapack_int ldz, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork,\n                                lapack_int lrwork, lapack_int* iwork,\n                                lapack_int liwork );\n\nlapack_int LAPACKE_chbevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, lapack_int kd,\n                                lapack_complex_float* ab, lapack_int ldab,\n                                lapack_complex_float* q, lapack_int ldq,\n                                float vl, float vu, lapack_int il,\n                                lapack_int iu, float abstol, lapack_int* m,\n                                float* w, lapack_complex_float* z,\n                                lapack_int ldz, lapack_complex_float* work,\n                                float* rwork, lapack_int* iwork,\n                                lapack_int* ifail );\nlapack_int LAPACKE_zhbevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, lapack_int kd,\n                                lapack_complex_double* ab, lapack_int ldab,\n                                lapack_complex_double* q, lapack_int ldq,\n                                double vl, double vu, lapack_int il,\n                                lapack_int iu, double abstol, lapack_int* m,\n                                double* w, lapack_complex_double* z,\n                                lapack_int ldz, lapack_complex_double* work,\n                                double* rwork, lapack_int* iwork,\n                                lapack_int* ifail );\n\nlapack_int LAPACKE_chbgst_work( int matrix_order, char vect, char uplo,\n                                lapack_int n, lapack_int ka, lapack_int kb,\n                                lapack_complex_float* ab, lapack_int ldab,\n                                const lapack_complex_float* bb, lapack_int ldbb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zhbgst_work( int matrix_order, char vect, char uplo,\n                                lapack_int n, lapack_int ka, lapack_int kb,\n                                lapack_complex_double* ab, lapack_int ldab,\n                                const lapack_complex_double* bb,\n                                lapack_int ldbb, lapack_complex_double* x,\n                                lapack_int ldx, lapack_complex_double* work,\n                                double* rwork );\n\nlapack_int LAPACKE_chbgv_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_int ka, lapack_int kb,\n                               lapack_complex_float* ab, lapack_int ldab,\n                               lapack_complex_float* bb, lapack_int ldbb,\n                               float* w, lapack_complex_float* z,\n                               lapack_int ldz, lapack_complex_float* work,\n                               float* rwork );\nlapack_int LAPACKE_zhbgv_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_int ka, lapack_int kb,\n                               lapack_complex_double* ab, lapack_int ldab,\n                               lapack_complex_double* bb, lapack_int ldbb,\n                               double* w, lapack_complex_double* z,\n                               lapack_int ldz, lapack_complex_double* work,\n                               double* rwork );\n\nlapack_int LAPACKE_chbgvd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_int ka, lapack_int kb,\n                                lapack_complex_float* ab, lapack_int ldab,\n                                lapack_complex_float* bb, lapack_int ldbb,\n                                float* w, lapack_complex_float* z,\n                                lapack_int ldz, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork,\n                                lapack_int lrwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_zhbgvd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_int ka, lapack_int kb,\n                                lapack_complex_double* ab, lapack_int ldab,\n                                lapack_complex_double* bb, lapack_int ldbb,\n                                double* w, lapack_complex_double* z,\n                                lapack_int ldz, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork,\n                                lapack_int lrwork, lapack_int* iwork,\n                                lapack_int liwork );\n\nlapack_int LAPACKE_chbgvx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, lapack_int ka,\n                                lapack_int kb, lapack_complex_float* ab,\n                                lapack_int ldab, lapack_complex_float* bb,\n                                lapack_int ldbb, lapack_complex_float* q,\n                                lapack_int ldq, float vl, float vu,\n                                lapack_int il, lapack_int iu, float abstol,\n                                lapack_int* m, float* w,\n                                lapack_complex_float* z, lapack_int ldz,\n                                lapack_complex_float* work, float* rwork,\n                                lapack_int* iwork, lapack_int* ifail );\nlapack_int LAPACKE_zhbgvx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, lapack_int ka,\n                                lapack_int kb, lapack_complex_double* ab,\n                                lapack_int ldab, lapack_complex_double* bb,\n                                lapack_int ldbb, lapack_complex_double* q,\n                                lapack_int ldq, double vl, double vu,\n                                lapack_int il, lapack_int iu, double abstol,\n                                lapack_int* m, double* w,\n                                lapack_complex_double* z, lapack_int ldz,\n                                lapack_complex_double* work, double* rwork,\n                                lapack_int* iwork, lapack_int* ifail );\n\nlapack_int LAPACKE_chbtrd_work( int matrix_order, char vect, char uplo,\n                                lapack_int n, lapack_int kd,\n                                lapack_complex_float* ab, lapack_int ldab,\n                                float* d, float* e, lapack_complex_float* q,\n                                lapack_int ldq, lapack_complex_float* work );\nlapack_int LAPACKE_zhbtrd_work( int matrix_order, char vect, char uplo,\n                                lapack_int n, lapack_int kd,\n                                lapack_complex_double* ab, lapack_int ldab,\n                                double* d, double* e, lapack_complex_double* q,\n                                lapack_int ldq, lapack_complex_double* work );\n\nlapack_int LAPACKE_checon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_int* ipiv, float anorm,\n                                float* rcond, lapack_complex_float* work );\nlapack_int LAPACKE_zhecon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_int* ipiv, double anorm,\n                                double* rcond, lapack_complex_double* work );\n\nlapack_int LAPACKE_cheequb_work( int matrix_order, char uplo, lapack_int n,\n                                 const lapack_complex_float* a, lapack_int lda,\n                                 float* s, float* scond, float* amax,\n                                 lapack_complex_float* work );\nlapack_int LAPACKE_zheequb_work( int matrix_order, char uplo, lapack_int n,\n                                 const lapack_complex_double* a, lapack_int lda,\n                                 double* s, double* scond, double* amax,\n                                 lapack_complex_double* work );\n\nlapack_int LAPACKE_cheev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_complex_float* a,\n                               lapack_int lda, float* w,\n                               lapack_complex_float* work, lapack_int lwork,\n                               float* rwork );\nlapack_int LAPACKE_zheev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_complex_double* a,\n                               lapack_int lda, double* w,\n                               lapack_complex_double* work, lapack_int lwork,\n                               double* rwork );\n\nlapack_int LAPACKE_cheevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_complex_float* a,\n                                lapack_int lda, float* w,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork, lapack_int lrwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_zheevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_complex_double* a,\n                                lapack_int lda, double* w,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork, lapack_int lrwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_cheevr_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                float vl, float vu, lapack_int il,\n                                lapack_int iu, float abstol, lapack_int* m,\n                                float* w, lapack_complex_float* z,\n                                lapack_int ldz, lapack_int* isuppz,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork, lapack_int lrwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_zheevr_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                double vl, double vu, lapack_int il,\n                                lapack_int iu, double abstol, lapack_int* m,\n                                double* w, lapack_complex_double* z,\n                                lapack_int ldz, lapack_int* isuppz,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork, lapack_int lrwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_cheevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                float vl, float vu, lapack_int il,\n                                lapack_int iu, float abstol, lapack_int* m,\n                                float* w, lapack_complex_float* z,\n                                lapack_int ldz, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork,\n                                lapack_int* iwork, lapack_int* ifail );\nlapack_int LAPACKE_zheevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                double vl, double vu, lapack_int il,\n                                lapack_int iu, double abstol, lapack_int* m,\n                                double* w, lapack_complex_double* z,\n                                lapack_int ldz, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork,\n                                lapack_int* iwork, lapack_int* ifail );\n\nlapack_int LAPACKE_chegst_work( int matrix_order, lapack_int itype, char uplo,\n                                lapack_int n, lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_zhegst_work( int matrix_order, lapack_int itype, char uplo,\n                                lapack_int n, lapack_complex_double* a,\n                                lapack_int lda, const lapack_complex_double* b,\n                                lapack_int ldb );\n\nlapack_int LAPACKE_chegv_work( int matrix_order, lapack_int itype, char jobz,\n                               char uplo, lapack_int n, lapack_complex_float* a,\n                               lapack_int lda, lapack_complex_float* b,\n                               lapack_int ldb, float* w,\n                               lapack_complex_float* work, lapack_int lwork,\n                               float* rwork );\nlapack_int LAPACKE_zhegv_work( int matrix_order, lapack_int itype, char jobz,\n                               char uplo, lapack_int n,\n                               lapack_complex_double* a, lapack_int lda,\n                               lapack_complex_double* b, lapack_int ldb,\n                               double* w, lapack_complex_double* work,\n                               lapack_int lwork, double* rwork );\n\nlapack_int LAPACKE_chegvd_work( int matrix_order, lapack_int itype, char jobz,\n                                char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb,\n                                float* w, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork,\n                                lapack_int lrwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_zhegvd_work( int matrix_order, lapack_int itype, char jobz,\n                                char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                double* w, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork,\n                                lapack_int lrwork, lapack_int* iwork,\n                                lapack_int liwork );\n\nlapack_int LAPACKE_chegvx_work( int matrix_order, lapack_int itype, char jobz,\n                                char range, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb,\n                                float vl, float vu, lapack_int il,\n                                lapack_int iu, float abstol, lapack_int* m,\n                                float* w, lapack_complex_float* z,\n                                lapack_int ldz, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork,\n                                lapack_int* iwork, lapack_int* ifail );\nlapack_int LAPACKE_zhegvx_work( int matrix_order, lapack_int itype, char jobz,\n                                char range, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                double vl, double vu, lapack_int il,\n                                lapack_int iu, double abstol, lapack_int* m,\n                                double* w, lapack_complex_double* z,\n                                lapack_int ldz, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork,\n                                lapack_int* iwork, lapack_int* ifail );\n\nlapack_int LAPACKE_cherfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* af,\n                                lapack_int ldaf, const lapack_int* ipiv,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zherfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_double* a,\n                                lapack_int lda, const lapack_complex_double* af,\n                                lapack_int ldaf, const lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_cherfsx_work( int matrix_order, char uplo, char equed,\n                                 lapack_int n, lapack_int nrhs,\n                                 const lapack_complex_float* a, lapack_int lda,\n                                 const lapack_complex_float* af,\n                                 lapack_int ldaf, const lapack_int* ipiv,\n                                 const float* s, const lapack_complex_float* b,\n                                 lapack_int ldb, lapack_complex_float* x,\n                                 lapack_int ldx, float* rcond, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, lapack_complex_float* work,\n                                 float* rwork );\nlapack_int LAPACKE_zherfsx_work( int matrix_order, char uplo, char equed,\n                                 lapack_int n, lapack_int nrhs,\n                                 const lapack_complex_double* a, lapack_int lda,\n                                 const lapack_complex_double* af,\n                                 lapack_int ldaf, const lapack_int* ipiv,\n                                 const double* s,\n                                 const lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* x, lapack_int ldx,\n                                 double* rcond, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, lapack_complex_double* work,\n                                 double* rwork );\n\nlapack_int LAPACKE_chesv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_float* a,\n                               lapack_int lda, lapack_int* ipiv,\n                               lapack_complex_float* b, lapack_int ldb,\n                               lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zhesv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_double* a,\n                               lapack_int lda, lapack_int* ipiv,\n                               lapack_complex_double* b, lapack_int ldb,\n                               lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_chesvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* af, lapack_int ldaf,\n                                lapack_int* ipiv, const lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* x,\n                                lapack_int ldx, float* rcond, float* ferr,\n                                float* berr, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork );\nlapack_int LAPACKE_zhesvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* af, lapack_int ldaf,\n                                lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork );\n\nlapack_int LAPACKE_chesvxx_work( int matrix_order, char fact, char uplo,\n                                 lapack_int n, lapack_int nrhs,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 lapack_complex_float* af, lapack_int ldaf,\n                                 lapack_int* ipiv, char* equed, float* s,\n                                 lapack_complex_float* b, lapack_int ldb,\n                                 lapack_complex_float* x, lapack_int ldx,\n                                 float* rcond, float* rpvgrw, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, lapack_complex_float* work,\n                                 float* rwork );\nlapack_int LAPACKE_zhesvxx_work( int matrix_order, char fact, char uplo,\n                                 lapack_int n, lapack_int nrhs,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 lapack_complex_double* af, lapack_int ldaf,\n                                 lapack_int* ipiv, char* equed, double* s,\n                                 lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* x, lapack_int ldx,\n                                 double* rcond, double* rpvgrw, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, lapack_complex_double* work,\n                                 double* rwork );\n\nlapack_int LAPACKE_chetrd_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                float* d, float* e, lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zhetrd_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                double* d, double* e,\n                                lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_chetrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_int* ipiv, lapack_complex_float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_zhetrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int* ipiv, lapack_complex_double* work,\n                                lapack_int lwork );\n\nlapack_int LAPACKE_chetri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                const lapack_int* ipiv,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zhetri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                const lapack_int* ipiv,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_chetrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* a,\n                                lapack_int lda, const lapack_int* ipiv,\n                                lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zhetrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_double* a,\n                                lapack_int lda, const lapack_int* ipiv,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_chfrk_work( int matrix_order, char transr, char uplo,\n                               char trans, lapack_int n, lapack_int k,\n                               float alpha, const lapack_complex_float* a,\n                               lapack_int lda, float beta,\n                               lapack_complex_float* c );\nlapack_int LAPACKE_zhfrk_work( int matrix_order, char transr, char uplo,\n                               char trans, lapack_int n, lapack_int k,\n                               double alpha, const lapack_complex_double* a,\n                               lapack_int lda, double beta,\n                               lapack_complex_double* c );\n\nlapack_int LAPACKE_shgeqz_work( int matrix_order, char job, char compq,\n                                char compz, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, float* h, lapack_int ldh,\n                                float* t, lapack_int ldt, float* alphar,\n                                float* alphai, float* beta, float* q,\n                                lapack_int ldq, float* z, lapack_int ldz,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dhgeqz_work( int matrix_order, char job, char compq,\n                                char compz, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, double* h, lapack_int ldh,\n                                double* t, lapack_int ldt, double* alphar,\n                                double* alphai, double* beta, double* q,\n                                lapack_int ldq, double* z, lapack_int ldz,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_chgeqz_work( int matrix_order, char job, char compq,\n                                char compz, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, lapack_complex_float* h,\n                                lapack_int ldh, lapack_complex_float* t,\n                                lapack_int ldt, lapack_complex_float* alpha,\n                                lapack_complex_float* beta,\n                                lapack_complex_float* q, lapack_int ldq,\n                                lapack_complex_float* z, lapack_int ldz,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork );\nlapack_int LAPACKE_zhgeqz_work( int matrix_order, char job, char compq,\n                                char compz, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, lapack_complex_double* h,\n                                lapack_int ldh, lapack_complex_double* t,\n                                lapack_int ldt, lapack_complex_double* alpha,\n                                lapack_complex_double* beta,\n                                lapack_complex_double* q, lapack_int ldq,\n                                lapack_complex_double* z, lapack_int ldz,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork );\n\nlapack_int LAPACKE_chpcon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_float* ap,\n                                const lapack_int* ipiv, float anorm,\n                                float* rcond, lapack_complex_float* work );\nlapack_int LAPACKE_zhpcon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_double* ap,\n                                const lapack_int* ipiv, double anorm,\n                                double* rcond, lapack_complex_double* work );\n\nlapack_int LAPACKE_chpev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_complex_float* ap, float* w,\n                               lapack_complex_float* z, lapack_int ldz,\n                               lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zhpev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_complex_double* ap,\n                               double* w, lapack_complex_double* z,\n                               lapack_int ldz, lapack_complex_double* work,\n                               double* rwork );\n\nlapack_int LAPACKE_chpevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_complex_float* ap,\n                                float* w, lapack_complex_float* z,\n                                lapack_int ldz, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork,\n                                lapack_int lrwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_zhpevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_complex_double* ap,\n                                double* w, lapack_complex_double* z,\n                                lapack_int ldz, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork,\n                                lapack_int lrwork, lapack_int* iwork,\n                                lapack_int liwork );\n\nlapack_int LAPACKE_chpevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n,\n                                lapack_complex_float* ap, float vl, float vu,\n                                lapack_int il, lapack_int iu, float abstol,\n                                lapack_int* m, float* w,\n                                lapack_complex_float* z, lapack_int ldz,\n                                lapack_complex_float* work, float* rwork,\n                                lapack_int* iwork, lapack_int* ifail );\nlapack_int LAPACKE_zhpevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n,\n                                lapack_complex_double* ap, double vl, double vu,\n                                lapack_int il, lapack_int iu, double abstol,\n                                lapack_int* m, double* w,\n                                lapack_complex_double* z, lapack_int ldz,\n                                lapack_complex_double* work, double* rwork,\n                                lapack_int* iwork, lapack_int* ifail );\n\nlapack_int LAPACKE_chpgst_work( int matrix_order, lapack_int itype, char uplo,\n                                lapack_int n, lapack_complex_float* ap,\n                                const lapack_complex_float* bp );\nlapack_int LAPACKE_zhpgst_work( int matrix_order, lapack_int itype, char uplo,\n                                lapack_int n, lapack_complex_double* ap,\n                                const lapack_complex_double* bp );\n\nlapack_int LAPACKE_chpgv_work( int matrix_order, lapack_int itype, char jobz,\n                               char uplo, lapack_int n,\n                               lapack_complex_float* ap,\n                               lapack_complex_float* bp, float* w,\n                               lapack_complex_float* z, lapack_int ldz,\n                               lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zhpgv_work( int matrix_order, lapack_int itype, char jobz,\n                               char uplo, lapack_int n,\n                               lapack_complex_double* ap,\n                               lapack_complex_double* bp, double* w,\n                               lapack_complex_double* z, lapack_int ldz,\n                               lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_chpgvd_work( int matrix_order, lapack_int itype, char jobz,\n                                char uplo, lapack_int n,\n                                lapack_complex_float* ap,\n                                lapack_complex_float* bp, float* w,\n                                lapack_complex_float* z, lapack_int ldz,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork, lapack_int lrwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_zhpgvd_work( int matrix_order, lapack_int itype, char jobz,\n                                char uplo, lapack_int n,\n                                lapack_complex_double* ap,\n                                lapack_complex_double* bp, double* w,\n                                lapack_complex_double* z, lapack_int ldz,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork, lapack_int lrwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_chpgvx_work( int matrix_order, lapack_int itype, char jobz,\n                                char range, char uplo, lapack_int n,\n                                lapack_complex_float* ap,\n                                lapack_complex_float* bp, float vl, float vu,\n                                lapack_int il, lapack_int iu, float abstol,\n                                lapack_int* m, float* w,\n                                lapack_complex_float* z, lapack_int ldz,\n                                lapack_complex_float* work, float* rwork,\n                                lapack_int* iwork, lapack_int* ifail );\nlapack_int LAPACKE_zhpgvx_work( int matrix_order, lapack_int itype, char jobz,\n                                char range, char uplo, lapack_int n,\n                                lapack_complex_double* ap,\n                                lapack_complex_double* bp, double vl, double vu,\n                                lapack_int il, lapack_int iu, double abstol,\n                                lapack_int* m, double* w,\n                                lapack_complex_double* z, lapack_int ldz,\n                                lapack_complex_double* work, double* rwork,\n                                lapack_int* iwork, lapack_int* ifail );\n\nlapack_int LAPACKE_chprfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* ap,\n                                const lapack_complex_float* afp,\n                                const lapack_int* ipiv,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zhprfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs,\n                                const lapack_complex_double* ap,\n                                const lapack_complex_double* afp,\n                                const lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_chpsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_float* ap,\n                               lapack_int* ipiv, lapack_complex_float* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_zhpsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_double* ap,\n                               lapack_int* ipiv, lapack_complex_double* b,\n                               lapack_int ldb );\n\nlapack_int LAPACKE_chpsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_float* ap,\n                                lapack_complex_float* afp, lapack_int* ipiv,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* rcond, float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zhpsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_double* ap,\n                                lapack_complex_double* afp, lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_chptrd_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* ap, float* d, float* e,\n                                lapack_complex_float* tau );\nlapack_int LAPACKE_zhptrd_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* ap, double* d, double* e,\n                                lapack_complex_double* tau );\n\nlapack_int LAPACKE_chptrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* ap, lapack_int* ipiv );\nlapack_int LAPACKE_zhptrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* ap, lapack_int* ipiv );\n\nlapack_int LAPACKE_chptri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* ap,\n                                const lapack_int* ipiv,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zhptri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* ap,\n                                const lapack_int* ipiv,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_chptrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* ap,\n                                const lapack_int* ipiv, lapack_complex_float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_zhptrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs,\n                                const lapack_complex_double* ap,\n                                const lapack_int* ipiv,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_shsein_work( int matrix_order, char job, char eigsrc,\n                                char initv, lapack_logical* select,\n                                lapack_int n, const float* h, lapack_int ldh,\n                                float* wr, const float* wi, float* vl,\n                                lapack_int ldvl, float* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m, float* work,\n                                lapack_int* ifaill, lapack_int* ifailr );\nlapack_int LAPACKE_dhsein_work( int matrix_order, char job, char eigsrc,\n                                char initv, lapack_logical* select,\n                                lapack_int n, const double* h, lapack_int ldh,\n                                double* wr, const double* wi, double* vl,\n                                lapack_int ldvl, double* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m, double* work,\n                                lapack_int* ifaill, lapack_int* ifailr );\nlapack_int LAPACKE_chsein_work( int matrix_order, char job, char eigsrc,\n                                char initv, const lapack_logical* select,\n                                lapack_int n, const lapack_complex_float* h,\n                                lapack_int ldh, lapack_complex_float* w,\n                                lapack_complex_float* vl, lapack_int ldvl,\n                                lapack_complex_float* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m,\n                                lapack_complex_float* work, float* rwork,\n                                lapack_int* ifaill, lapack_int* ifailr );\nlapack_int LAPACKE_zhsein_work( int matrix_order, char job, char eigsrc,\n                                char initv, const lapack_logical* select,\n                                lapack_int n, const lapack_complex_double* h,\n                                lapack_int ldh, lapack_complex_double* w,\n                                lapack_complex_double* vl, lapack_int ldvl,\n                                lapack_complex_double* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m,\n                                lapack_complex_double* work, double* rwork,\n                                lapack_int* ifaill, lapack_int* ifailr );\n\nlapack_int LAPACKE_shseqr_work( int matrix_order, char job, char compz,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                float* h, lapack_int ldh, float* wr, float* wi,\n                                float* z, lapack_int ldz, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dhseqr_work( int matrix_order, char job, char compz,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                double* h, lapack_int ldh, double* wr,\n                                double* wi, double* z, lapack_int ldz,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_chseqr_work( int matrix_order, char job, char compz,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                lapack_complex_float* h, lapack_int ldh,\n                                lapack_complex_float* w,\n                                lapack_complex_float* z, lapack_int ldz,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zhseqr_work( int matrix_order, char job, char compz,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                lapack_complex_double* h, lapack_int ldh,\n                                lapack_complex_double* w,\n                                lapack_complex_double* z, lapack_int ldz,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_clacgv_work( lapack_int n, lapack_complex_float* x,\n                                lapack_int incx );\nlapack_int LAPACKE_zlacgv_work( lapack_int n, lapack_complex_double* x,\n                                lapack_int incx );\n\nlapack_int LAPACKE_slacpy_work( int matrix_order, char uplo, lapack_int m,\n                                lapack_int n, const float* a, lapack_int lda,\n                                float* b, lapack_int ldb );\nlapack_int LAPACKE_dlacpy_work( int matrix_order, char uplo, lapack_int m,\n                                lapack_int n, const double* a, lapack_int lda,\n                                double* b, lapack_int ldb );\nlapack_int LAPACKE_clacpy_work( int matrix_order, char uplo, lapack_int m,\n                                lapack_int n, const lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_zlacpy_work( int matrix_order, char uplo, lapack_int m,\n                                lapack_int n, const lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* b,\n                                lapack_int ldb );\n\nlapack_int LAPACKE_zlag2c_work( int matrix_order, lapack_int m, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_float* sa, lapack_int ldsa );\n\nlapack_int LAPACKE_slag2d_work( int matrix_order, lapack_int m, lapack_int n,\n                                const float* sa, lapack_int ldsa, double* a,\n                                lapack_int lda );\n\nlapack_int LAPACKE_dlag2s_work( int matrix_order, lapack_int m, lapack_int n,\n                                const double* a, lapack_int lda, float* sa,\n                                lapack_int ldsa );\n\nlapack_int LAPACKE_clag2z_work( int matrix_order, lapack_int m, lapack_int n,\n                                const lapack_complex_float* sa, lapack_int ldsa,\n                                lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_slagge_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku, const float* d,\n                                float* a, lapack_int lda, lapack_int* iseed,\n                                float* work );\nlapack_int LAPACKE_dlagge_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku, const double* d,\n                                double* a, lapack_int lda, lapack_int* iseed,\n                                double* work );\nlapack_int LAPACKE_clagge_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku, const float* d,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_int* iseed, lapack_complex_float* work );\nlapack_int LAPACKE_zlagge_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku, const double* d,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int* iseed,\n                                lapack_complex_double* work );\n                                \nlapack_int LAPACKE_claghe_work( int matrix_order, lapack_int n, lapack_int k,\n                                const float* d, lapack_complex_float* a,\n                                lapack_int lda, lapack_int* iseed,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zlaghe_work( int matrix_order, lapack_int n, lapack_int k,\n                                const double* d, lapack_complex_double* a,\n                                lapack_int lda, lapack_int* iseed,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_slagsy_work( int matrix_order, lapack_int n, lapack_int k,\n                                const float* d, float* a, lapack_int lda,\n                                lapack_int* iseed, float* work );\nlapack_int LAPACKE_dlagsy_work( int matrix_order, lapack_int n, lapack_int k,\n                                const double* d, double* a, lapack_int lda,\n                                lapack_int* iseed, double* work );\nlapack_int LAPACKE_clagsy_work( int matrix_order, lapack_int n, lapack_int k,\n                                const float* d, lapack_complex_float* a,\n                                lapack_int lda, lapack_int* iseed,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zlagsy_work( int matrix_order, lapack_int n, lapack_int k,\n                                const double* d, lapack_complex_double* a,\n                                lapack_int lda, lapack_int* iseed,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_slapmr_work( int matrix_order, lapack_logical forwrd,\n                                lapack_int m, lapack_int n, float* x,\n                                lapack_int ldx, lapack_int* k );\nlapack_int LAPACKE_dlapmr_work( int matrix_order, lapack_logical forwrd,\n                                lapack_int m, lapack_int n, double* x,\n                                lapack_int ldx, lapack_int* k );\nlapack_int LAPACKE_clapmr_work( int matrix_order, lapack_logical forwrd,\n                                lapack_int m, lapack_int n,\n                                lapack_complex_float* x, lapack_int ldx,\n                                lapack_int* k );\nlapack_int LAPACKE_zlapmr_work( int matrix_order, lapack_logical forwrd,\n                                lapack_int m, lapack_int n,\n                                lapack_complex_double* x, lapack_int ldx,\n                                lapack_int* k );\n\nlapack_int LAPACKE_slartgp_work( float f, float g, float* cs, float* sn,\n                                 float* r );\nlapack_int LAPACKE_dlartgp_work( double f, double g, double* cs, double* sn,\n                                 double* r );\n\nlapack_int LAPACKE_slartgs_work( float x, float y, float sigma, float* cs,\n                                 float* sn );\nlapack_int LAPACKE_dlartgs_work( double x, double y, double sigma, double* cs,\n                                 double* sn );\n                                \nfloat LAPACKE_slapy2_work( float x, float y );\ndouble LAPACKE_dlapy2_work( double x, double y );\n\nfloat LAPACKE_slapy3_work( float x, float y, float z );\ndouble LAPACKE_dlapy3_work( double x, double y, double z );\n\nfloat LAPACKE_slamch_work( char cmach );\ndouble LAPACKE_dlamch_work( char cmach );\n\nfloat LAPACKE_slange_work( int matrix_order, char norm, lapack_int m,\n                                lapack_int n, const float* a, lapack_int lda,\n                                float* work );\ndouble LAPACKE_dlange_work( int matrix_order, char norm, lapack_int m,\n                                lapack_int n, const double* a, lapack_int lda,\n                                double* work );\nfloat LAPACKE_clange_work( int matrix_order, char norm, lapack_int m,\n                                lapack_int n, const lapack_complex_float* a,\n                                lapack_int lda, float* work );\ndouble LAPACKE_zlange_work( int matrix_order, char norm, lapack_int m,\n                                lapack_int n, const lapack_complex_double* a,\n                                lapack_int lda, double* work );\n\nfloat LAPACKE_clanhe_work( int matrix_order, char norm, char uplo,\n                                lapack_int n, const lapack_complex_float* a,\n                                lapack_int lda, float* work );\ndouble LAPACKE_zlanhe_work( int matrix_order, char norm, char uplo,\n                                lapack_int n, const lapack_complex_double* a,\n                                lapack_int lda, double* work );\n\nfloat LAPACKE_slansy_work( int matrix_order, char norm, char uplo,\n                                lapack_int n, const float* a, lapack_int lda,\n                                float* work );\ndouble LAPACKE_dlansy_work( int matrix_order, char norm, char uplo,\n                                lapack_int n, const double* a, lapack_int lda,\n                                double* work );\nfloat LAPACKE_clansy_work( int matrix_order, char norm, char uplo,\n                                lapack_int n, const lapack_complex_float* a,\n                                lapack_int lda, float* work );\ndouble LAPACKE_zlansy_work( int matrix_order, char norm, char uplo,\n                                lapack_int n, const lapack_complex_double* a,\n                                lapack_int lda, double* work );\n\nfloat LAPACKE_slantr_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int m, lapack_int n, const float* a,\n                                lapack_int lda, float* work );\ndouble LAPACKE_dlantr_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int m, lapack_int n,\n                                const double* a, lapack_int lda, double* work );\nfloat LAPACKE_clantr_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int m, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                float* work );\ndouble LAPACKE_zlantr_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int m, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                double* work );\n\nlapack_int LAPACKE_slarfb_work( int matrix_order, char side, char trans,\n                                char direct, char storev, lapack_int m,\n                                lapack_int n, lapack_int k, const float* v,\n                                lapack_int ldv, const float* t, lapack_int ldt,\n                                float* c, lapack_int ldc, float* work,\n                                lapack_int ldwork );\nlapack_int LAPACKE_dlarfb_work( int matrix_order, char side, char trans,\n                                char direct, char storev, lapack_int m,\n                                lapack_int n, lapack_int k, const double* v,\n                                lapack_int ldv, const double* t, lapack_int ldt,\n                                double* c, lapack_int ldc, double* work,\n                                lapack_int ldwork );\nlapack_int LAPACKE_clarfb_work( int matrix_order, char side, char trans,\n                                char direct, char storev, lapack_int m,\n                                lapack_int n, lapack_int k,\n                                const lapack_complex_float* v, lapack_int ldv,\n                                const lapack_complex_float* t, lapack_int ldt,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work, lapack_int ldwork );\nlapack_int LAPACKE_zlarfb_work( int matrix_order, char side, char trans,\n                                char direct, char storev, lapack_int m,\n                                lapack_int n, lapack_int k,\n                                const lapack_complex_double* v, lapack_int ldv,\n                                const lapack_complex_double* t, lapack_int ldt,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work,\n                                lapack_int ldwork );\n\nlapack_int LAPACKE_slarfg_work( lapack_int n, float* alpha, float* x,\n                                lapack_int incx, float* tau );\nlapack_int LAPACKE_dlarfg_work( lapack_int n, double* alpha, double* x,\n                                lapack_int incx, double* tau );\nlapack_int LAPACKE_clarfg_work( lapack_int n, lapack_complex_float* alpha,\n                                lapack_complex_float* x, lapack_int incx,\n                                lapack_complex_float* tau );\nlapack_int LAPACKE_zlarfg_work( lapack_int n, lapack_complex_double* alpha,\n                                lapack_complex_double* x, lapack_int incx,\n                                lapack_complex_double* tau );\n\nlapack_int LAPACKE_slarft_work( int matrix_order, char direct, char storev,\n                                lapack_int n, lapack_int k, const float* v,\n                                lapack_int ldv, const float* tau, float* t,\n                                lapack_int ldt );\nlapack_int LAPACKE_dlarft_work( int matrix_order, char direct, char storev,\n                                lapack_int n, lapack_int k, const double* v,\n                                lapack_int ldv, const double* tau, double* t,\n                                lapack_int ldt );\nlapack_int LAPACKE_clarft_work( int matrix_order, char direct, char storev,\n                                lapack_int n, lapack_int k,\n                                const lapack_complex_float* v, lapack_int ldv,\n                                const lapack_complex_float* tau,\n                                lapack_complex_float* t, lapack_int ldt );\nlapack_int LAPACKE_zlarft_work( int matrix_order, char direct, char storev,\n                                lapack_int n, lapack_int k,\n                                const lapack_complex_double* v, lapack_int ldv,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* t, lapack_int ldt );\n\nlapack_int LAPACKE_slarfx_work( int matrix_order, char side, lapack_int m,\n                                lapack_int n, const float* v, float tau,\n                                float* c, lapack_int ldc, float* work );\nlapack_int LAPACKE_dlarfx_work( int matrix_order, char side, lapack_int m,\n                                lapack_int n, const double* v, double tau,\n                                double* c, lapack_int ldc, double* work );\nlapack_int LAPACKE_clarfx_work( int matrix_order, char side, lapack_int m,\n                                lapack_int n, const lapack_complex_float* v,\n                                lapack_complex_float tau,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zlarfx_work( int matrix_order, char side, lapack_int m,\n                                lapack_int n, const lapack_complex_double* v,\n                                lapack_complex_double tau,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_slarnv_work( lapack_int idist, lapack_int* iseed,\n                                lapack_int n, float* x );\nlapack_int LAPACKE_dlarnv_work( lapack_int idist, lapack_int* iseed,\n                                lapack_int n, double* x );\nlapack_int LAPACKE_clarnv_work( lapack_int idist, lapack_int* iseed,\n                                lapack_int n, lapack_complex_float* x );\nlapack_int LAPACKE_zlarnv_work( lapack_int idist, lapack_int* iseed,\n                                lapack_int n, lapack_complex_double* x );\n\nlapack_int LAPACKE_slaset_work( int matrix_order, char uplo, lapack_int m,\n                                lapack_int n, float alpha, float beta, float* a,\n                                lapack_int lda );\nlapack_int LAPACKE_dlaset_work( int matrix_order, char uplo, lapack_int m,\n                                lapack_int n, double alpha, double beta,\n                                double* a, lapack_int lda );\nlapack_int LAPACKE_claset_work( int matrix_order, char uplo, lapack_int m,\n                                lapack_int n, lapack_complex_float alpha,\n                                lapack_complex_float beta,\n                                lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_zlaset_work( int matrix_order, char uplo, lapack_int m,\n                                lapack_int n, lapack_complex_double alpha,\n                                lapack_complex_double beta,\n                                lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_slasrt_work( char id, lapack_int n, float* d );\nlapack_int LAPACKE_dlasrt_work( char id, lapack_int n, double* d );\n\nlapack_int LAPACKE_slaswp_work( int matrix_order, lapack_int n, float* a,\n                                lapack_int lda, lapack_int k1, lapack_int k2,\n                                const lapack_int* ipiv, lapack_int incx );\nlapack_int LAPACKE_dlaswp_work( int matrix_order, lapack_int n, double* a,\n                                lapack_int lda, lapack_int k1, lapack_int k2,\n                                const lapack_int* ipiv, lapack_int incx );\nlapack_int LAPACKE_claswp_work( int matrix_order, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_int k1, lapack_int k2,\n                                const lapack_int* ipiv, lapack_int incx );\nlapack_int LAPACKE_zlaswp_work( int matrix_order, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int k1, lapack_int k2,\n                                const lapack_int* ipiv, lapack_int incx );\n\nlapack_int LAPACKE_slatms_work( int matrix_order, lapack_int m, lapack_int n,\n                                char dist, lapack_int* iseed, char sym,\n                                float* d, lapack_int mode, float cond,\n                                float dmax, lapack_int kl, lapack_int ku,\n                                char pack, float* a, lapack_int lda,\n                                float* work );\nlapack_int LAPACKE_dlatms_work( int matrix_order, lapack_int m, lapack_int n,\n                                char dist, lapack_int* iseed, char sym,\n                                double* d, lapack_int mode, double cond,\n                                double dmax, lapack_int kl, lapack_int ku,\n                                char pack, double* a, lapack_int lda,\n                                double* work );\nlapack_int LAPACKE_clatms_work( int matrix_order, lapack_int m, lapack_int n,\n                                char dist, lapack_int* iseed, char sym,\n                                float* d, lapack_int mode, float cond,\n                                float dmax, lapack_int kl, lapack_int ku,\n                                char pack, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* work );\nlapack_int LAPACKE_zlatms_work( int matrix_order, lapack_int m, lapack_int n,\n                                char dist, lapack_int* iseed, char sym,\n                                double* d, lapack_int mode, double cond,\n                                double dmax, lapack_int kl, lapack_int ku,\n                                char pack, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* work );\n\nlapack_int LAPACKE_slauum_work( int matrix_order, char uplo, lapack_int n,\n                                float* a, lapack_int lda );\nlapack_int LAPACKE_dlauum_work( int matrix_order, char uplo, lapack_int n,\n                                double* a, lapack_int lda );\nlapack_int LAPACKE_clauum_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_zlauum_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_sopgtr_work( int matrix_order, char uplo, lapack_int n,\n                                const float* ap, const float* tau, float* q,\n                                lapack_int ldq, float* work );\nlapack_int LAPACKE_dopgtr_work( int matrix_order, char uplo, lapack_int n,\n                                const double* ap, const double* tau, double* q,\n                                lapack_int ldq, double* work );\n\nlapack_int LAPACKE_sopmtr_work( int matrix_order, char side, char uplo,\n                                char trans, lapack_int m, lapack_int n,\n                                const float* ap, const float* tau, float* c,\n                                lapack_int ldc, float* work );\nlapack_int LAPACKE_dopmtr_work( int matrix_order, char side, char uplo,\n                                char trans, lapack_int m, lapack_int n,\n                                const double* ap, const double* tau, double* c,\n                                lapack_int ldc, double* work );\n\nlapack_int LAPACKE_sorgbr_work( int matrix_order, char vect, lapack_int m,\n                                lapack_int n, lapack_int k, float* a,\n                                lapack_int lda, const float* tau, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dorgbr_work( int matrix_order, char vect, lapack_int m,\n                                lapack_int n, lapack_int k, double* a,\n                                lapack_int lda, const double* tau, double* work,\n                                lapack_int lwork );\n\nlapack_int LAPACKE_sorghr_work( int matrix_order, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, float* a, lapack_int lda,\n                                const float* tau, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dorghr_work( int matrix_order, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, double* a, lapack_int lda,\n                                const double* tau, double* work,\n                                lapack_int lwork );\n\nlapack_int LAPACKE_sorglq_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, float* a, lapack_int lda,\n                                const float* tau, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dorglq_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, double* a, lapack_int lda,\n                                const double* tau, double* work,\n                                lapack_int lwork );\n\nlapack_int LAPACKE_sorgql_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, float* a, lapack_int lda,\n                                const float* tau, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dorgql_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, double* a, lapack_int lda,\n                                const double* tau, double* work,\n                                lapack_int lwork );\n\nlapack_int LAPACKE_sorgqr_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, float* a, lapack_int lda,\n                                const float* tau, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dorgqr_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, double* a, lapack_int lda,\n                                const double* tau, double* work,\n                                lapack_int lwork );\n\nlapack_int LAPACKE_sorgrq_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, float* a, lapack_int lda,\n                                const float* tau, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dorgrq_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, double* a, lapack_int lda,\n                                const double* tau, double* work,\n                                lapack_int lwork );\n\nlapack_int LAPACKE_sorgtr_work( int matrix_order, char uplo, lapack_int n,\n                                float* a, lapack_int lda, const float* tau,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dorgtr_work( int matrix_order, char uplo, lapack_int n,\n                                double* a, lapack_int lda, const double* tau,\n                                double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sormbr_work( int matrix_order, char vect, char side,\n                                char trans, lapack_int m, lapack_int n,\n                                lapack_int k, const float* a, lapack_int lda,\n                                const float* tau, float* c, lapack_int ldc,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dormbr_work( int matrix_order, char vect, char side,\n                                char trans, lapack_int m, lapack_int n,\n                                lapack_int k, const double* a, lapack_int lda,\n                                const double* tau, double* c, lapack_int ldc,\n                                double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sormhr_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, const float* a, lapack_int lda,\n                                const float* tau, float* c, lapack_int ldc,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dormhr_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, const double* a, lapack_int lda,\n                                const double* tau, double* c, lapack_int ldc,\n                                double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sormlq_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const float* a, lapack_int lda,\n                                const float* tau, float* c, lapack_int ldc,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dormlq_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const double* a, lapack_int lda,\n                                const double* tau, double* c, lapack_int ldc,\n                                double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sormql_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const float* a, lapack_int lda,\n                                const float* tau, float* c, lapack_int ldc,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dormql_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const double* a, lapack_int lda,\n                                const double* tau, double* c, lapack_int ldc,\n                                double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sormqr_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const float* a, lapack_int lda,\n                                const float* tau, float* c, lapack_int ldc,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dormqr_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const double* a, lapack_int lda,\n                                const double* tau, double* c, lapack_int ldc,\n                                double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sormrq_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const float* a, lapack_int lda,\n                                const float* tau, float* c, lapack_int ldc,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dormrq_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const double* a, lapack_int lda,\n                                const double* tau, double* c, lapack_int ldc,\n                                double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sormrz_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                lapack_int l, const float* a, lapack_int lda,\n                                const float* tau, float* c, lapack_int ldc,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dormrz_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                lapack_int l, const double* a, lapack_int lda,\n                                const double* tau, double* c, lapack_int ldc,\n                                double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sormtr_work( int matrix_order, char side, char uplo,\n                                char trans, lapack_int m, lapack_int n,\n                                const float* a, lapack_int lda,\n                                const float* tau, float* c, lapack_int ldc,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dormtr_work( int matrix_order, char side, char uplo,\n                                char trans, lapack_int m, lapack_int n,\n                                const double* a, lapack_int lda,\n                                const double* tau, double* c, lapack_int ldc,\n                                double* work, lapack_int lwork );\n\nlapack_int LAPACKE_spbcon_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, const float* ab, lapack_int ldab,\n                                float anorm, float* rcond, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dpbcon_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, const double* ab,\n                                lapack_int ldab, double anorm, double* rcond,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_cpbcon_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, const lapack_complex_float* ab,\n                                lapack_int ldab, float anorm, float* rcond,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zpbcon_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, const lapack_complex_double* ab,\n                                lapack_int ldab, double anorm, double* rcond,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_spbequ_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, const float* ab, lapack_int ldab,\n                                float* s, float* scond, float* amax );\nlapack_int LAPACKE_dpbequ_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, const double* ab,\n                                lapack_int ldab, double* s, double* scond,\n                                double* amax );\nlapack_int LAPACKE_cpbequ_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, const lapack_complex_float* ab,\n                                lapack_int ldab, float* s, float* scond,\n                                float* amax );\nlapack_int LAPACKE_zpbequ_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, const lapack_complex_double* ab,\n                                lapack_int ldab, double* s, double* scond,\n                                double* amax );\n\nlapack_int LAPACKE_spbrfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, lapack_int nrhs, const float* ab,\n                                lapack_int ldab, const float* afb,\n                                lapack_int ldafb, const float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* ferr, float* berr, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dpbrfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, lapack_int nrhs,\n                                const double* ab, lapack_int ldab,\n                                const double* afb, lapack_int ldafb,\n                                const double* b, lapack_int ldb, double* x,\n                                lapack_int ldx, double* ferr, double* berr,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_cpbrfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, lapack_int nrhs,\n                                const lapack_complex_float* ab, lapack_int ldab,\n                                const lapack_complex_float* afb,\n                                lapack_int ldafb, const lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* x,\n                                lapack_int ldx, float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zpbrfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, lapack_int nrhs,\n                                const lapack_complex_double* ab,\n                                lapack_int ldab,\n                                const lapack_complex_double* afb,\n                                lapack_int ldafb,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_spbstf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kb, float* bb, lapack_int ldbb );\nlapack_int LAPACKE_dpbstf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kb, double* bb, lapack_int ldbb );\nlapack_int LAPACKE_cpbstf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kb, lapack_complex_float* bb,\n                                lapack_int ldbb );\nlapack_int LAPACKE_zpbstf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kb, lapack_complex_double* bb,\n                                lapack_int ldbb );\n\nlapack_int LAPACKE_spbsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int kd, lapack_int nrhs, float* ab,\n                               lapack_int ldab, float* b, lapack_int ldb );\nlapack_int LAPACKE_dpbsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int kd, lapack_int nrhs, double* ab,\n                               lapack_int ldab, double* b, lapack_int ldb );\nlapack_int LAPACKE_cpbsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int kd, lapack_int nrhs,\n                               lapack_complex_float* ab, lapack_int ldab,\n                               lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zpbsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int kd, lapack_int nrhs,\n                               lapack_complex_double* ab, lapack_int ldab,\n                               lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_spbsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int kd, lapack_int nrhs,\n                                float* ab, lapack_int ldab, float* afb,\n                                lapack_int ldafb, char* equed, float* s,\n                                float* b, lapack_int ldb, float* x,\n                                lapack_int ldx, float* rcond, float* ferr,\n                                float* berr, float* work, lapack_int* iwork );\nlapack_int LAPACKE_dpbsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int kd, lapack_int nrhs,\n                                double* ab, lapack_int ldab, double* afb,\n                                lapack_int ldafb, char* equed, double* s,\n                                double* b, lapack_int ldb, double* x,\n                                lapack_int ldx, double* rcond, double* ferr,\n                                double* berr, double* work, lapack_int* iwork );\nlapack_int LAPACKE_cpbsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int kd, lapack_int nrhs,\n                                lapack_complex_float* ab, lapack_int ldab,\n                                lapack_complex_float* afb, lapack_int ldafb,\n                                char* equed, float* s, lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* x,\n                                lapack_int ldx, float* rcond, float* ferr,\n                                float* berr, lapack_complex_float* work,\n                                float* rwork );\nlapack_int LAPACKE_zpbsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int kd, lapack_int nrhs,\n                                lapack_complex_double* ab, lapack_int ldab,\n                                lapack_complex_double* afb, lapack_int ldafb,\n                                char* equed, double* s,\n                                lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_spbtrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, float* ab, lapack_int ldab );\nlapack_int LAPACKE_dpbtrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, double* ab, lapack_int ldab );\nlapack_int LAPACKE_cpbtrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, lapack_complex_float* ab,\n                                lapack_int ldab );\nlapack_int LAPACKE_zpbtrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, lapack_complex_double* ab,\n                                lapack_int ldab );\n\nlapack_int LAPACKE_spbtrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, lapack_int nrhs, const float* ab,\n                                lapack_int ldab, float* b, lapack_int ldb );\nlapack_int LAPACKE_dpbtrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, lapack_int nrhs,\n                                const double* ab, lapack_int ldab, double* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_cpbtrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, lapack_int nrhs,\n                                const lapack_complex_float* ab, lapack_int ldab,\n                                lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zpbtrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, lapack_int nrhs,\n                                const lapack_complex_double* ab,\n                                lapack_int ldab, lapack_complex_double* b,\n                                lapack_int ldb );\n\nlapack_int LAPACKE_spftrf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, float* a );\nlapack_int LAPACKE_dpftrf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, double* a );\nlapack_int LAPACKE_cpftrf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, lapack_complex_float* a );\nlapack_int LAPACKE_zpftrf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, lapack_complex_double* a );\n\nlapack_int LAPACKE_spftri_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, float* a );\nlapack_int LAPACKE_dpftri_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, double* a );\nlapack_int LAPACKE_cpftri_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, lapack_complex_float* a );\nlapack_int LAPACKE_zpftri_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, lapack_complex_double* a );\n\nlapack_int LAPACKE_spftrs_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, lapack_int nrhs, const float* a,\n                                float* b, lapack_int ldb );\nlapack_int LAPACKE_dpftrs_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, lapack_int nrhs, const double* a,\n                                double* b, lapack_int ldb );\nlapack_int LAPACKE_cpftrs_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_float* a,\n                                lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zpftrs_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_double* a,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_spocon_work( int matrix_order, char uplo, lapack_int n,\n                                const float* a, lapack_int lda, float anorm,\n                                float* rcond, float* work, lapack_int* iwork );\nlapack_int LAPACKE_dpocon_work( int matrix_order, char uplo, lapack_int n,\n                                const double* a, lapack_int lda, double anorm,\n                                double* rcond, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_cpocon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                float anorm, float* rcond,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zpocon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                double anorm, double* rcond,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_spoequ_work( int matrix_order, lapack_int n, const float* a,\n                                lapack_int lda, float* s, float* scond,\n                                float* amax );\nlapack_int LAPACKE_dpoequ_work( int matrix_order, lapack_int n, const double* a,\n                                lapack_int lda, double* s, double* scond,\n                                double* amax );\nlapack_int LAPACKE_cpoequ_work( int matrix_order, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                float* s, float* scond, float* amax );\nlapack_int LAPACKE_zpoequ_work( int matrix_order, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                double* s, double* scond, double* amax );\n\nlapack_int LAPACKE_spoequb_work( int matrix_order, lapack_int n, const float* a,\n                                 lapack_int lda, float* s, float* scond,\n                                 float* amax );\nlapack_int LAPACKE_dpoequb_work( int matrix_order, lapack_int n,\n                                 const double* a, lapack_int lda, double* s,\n                                 double* scond, double* amax );\nlapack_int LAPACKE_cpoequb_work( int matrix_order, lapack_int n,\n                                 const lapack_complex_float* a, lapack_int lda,\n                                 float* s, float* scond, float* amax );\nlapack_int LAPACKE_zpoequb_work( int matrix_order, lapack_int n,\n                                 const lapack_complex_double* a, lapack_int lda,\n                                 double* s, double* scond, double* amax );\n\nlapack_int LAPACKE_sporfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const float* a, lapack_int lda,\n                                const float* af, lapack_int ldaf,\n                                const float* b, lapack_int ldb, float* x,\n                                lapack_int ldx, float* ferr, float* berr,\n                                float* work, lapack_int* iwork );\nlapack_int LAPACKE_dporfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const double* a,\n                                lapack_int lda, const double* af,\n                                lapack_int ldaf, const double* b,\n                                lapack_int ldb, double* x, lapack_int ldx,\n                                double* ferr, double* berr, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_cporfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* af,\n                                lapack_int ldaf, const lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* x,\n                                lapack_int ldx, float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zporfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_double* a,\n                                lapack_int lda, const lapack_complex_double* af,\n                                lapack_int ldaf, const lapack_complex_double* b,\n                                lapack_int ldb, lapack_complex_double* x,\n                                lapack_int ldx, double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sporfsx_work( int matrix_order, char uplo, char equed,\n                                 lapack_int n, lapack_int nrhs, const float* a,\n                                 lapack_int lda, const float* af,\n                                 lapack_int ldaf, const float* s,\n                                 const float* b, lapack_int ldb, float* x,\n                                 lapack_int ldx, float* rcond, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, float* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_dporfsx_work( int matrix_order, char uplo, char equed,\n                                 lapack_int n, lapack_int nrhs, const double* a,\n                                 lapack_int lda, const double* af,\n                                 lapack_int ldaf, const double* s,\n                                 const double* b, lapack_int ldb, double* x,\n                                 lapack_int ldx, double* rcond, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, double* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_cporfsx_work( int matrix_order, char uplo, char equed,\n                                 lapack_int n, lapack_int nrhs,\n                                 const lapack_complex_float* a, lapack_int lda,\n                                 const lapack_complex_float* af,\n                                 lapack_int ldaf, const float* s,\n                                 const lapack_complex_float* b, lapack_int ldb,\n                                 lapack_complex_float* x, lapack_int ldx,\n                                 float* rcond, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, lapack_complex_float* work,\n                                 float* rwork );\nlapack_int LAPACKE_zporfsx_work( int matrix_order, char uplo, char equed,\n                                 lapack_int n, lapack_int nrhs,\n                                 const lapack_complex_double* a, lapack_int lda,\n                                 const lapack_complex_double* af,\n                                 lapack_int ldaf, const double* s,\n                                 const lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* x, lapack_int ldx,\n                                 double* rcond, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, lapack_complex_double* work,\n                                 double* rwork );\n\nlapack_int LAPACKE_sposv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, float* a, lapack_int lda,\n                               float* b, lapack_int ldb );\nlapack_int LAPACKE_dposv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, double* a, lapack_int lda,\n                               double* b, lapack_int ldb );\nlapack_int LAPACKE_cposv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_float* a,\n                               lapack_int lda, lapack_complex_float* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_zposv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_double* a,\n                               lapack_int lda, lapack_complex_double* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_dsposv_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, double* a, lapack_int lda,\n                                double* b, lapack_int ldb, double* x,\n                                lapack_int ldx, double* work, float* swork,\n                                lapack_int* iter );\nlapack_int LAPACKE_zcposv_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* b,\n                                lapack_int ldb, lapack_complex_double* x,\n                                lapack_int ldx, lapack_complex_double* work,\n                                lapack_complex_float* swork, double* rwork,\n                                lapack_int* iter );\n\nlapack_int LAPACKE_sposvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs, float* a,\n                                lapack_int lda, float* af, lapack_int ldaf,\n                                char* equed, float* s, float* b, lapack_int ldb,\n                                float* x, lapack_int ldx, float* rcond,\n                                float* ferr, float* berr, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dposvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs, double* a,\n                                lapack_int lda, double* af, lapack_int ldaf,\n                                char* equed, double* s, double* b,\n                                lapack_int ldb, double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_cposvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* af, lapack_int ldaf,\n                                char* equed, float* s, lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* x,\n                                lapack_int ldx, float* rcond, float* ferr,\n                                float* berr, lapack_complex_float* work,\n                                float* rwork );\nlapack_int LAPACKE_zposvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* af, lapack_int ldaf,\n                                char* equed, double* s,\n                                lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sposvxx_work( int matrix_order, char fact, char uplo,\n                                 lapack_int n, lapack_int nrhs, float* a,\n                                 lapack_int lda, float* af, lapack_int ldaf,\n                                 char* equed, float* s, float* b,\n                                 lapack_int ldb, float* x, lapack_int ldx,\n                                 float* rcond, float* rpvgrw, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, float* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_dposvxx_work( int matrix_order, char fact, char uplo,\n                                 lapack_int n, lapack_int nrhs, double* a,\n                                 lapack_int lda, double* af, lapack_int ldaf,\n                                 char* equed, double* s, double* b,\n                                 lapack_int ldb, double* x, lapack_int ldx,\n                                 double* rcond, double* rpvgrw, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, double* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_cposvxx_work( int matrix_order, char fact, char uplo,\n                                 lapack_int n, lapack_int nrhs,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 lapack_complex_float* af, lapack_int ldaf,\n                                 char* equed, float* s, lapack_complex_float* b,\n                                 lapack_int ldb, lapack_complex_float* x,\n                                 lapack_int ldx, float* rcond, float* rpvgrw,\n                                 float* berr, lapack_int n_err_bnds,\n                                 float* err_bnds_norm, float* err_bnds_comp,\n                                 lapack_int nparams, float* params,\n                                 lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zposvxx_work( int matrix_order, char fact, char uplo,\n                                 lapack_int n, lapack_int nrhs,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 lapack_complex_double* af, lapack_int ldaf,\n                                 char* equed, double* s,\n                                 lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* x, lapack_int ldx,\n                                 double* rcond, double* rpvgrw, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, lapack_complex_double* work,\n                                 double* rwork );\n\nlapack_int LAPACKE_spotrf_work( int matrix_order, char uplo, lapack_int n,\n                                float* a, lapack_int lda );\nlapack_int LAPACKE_dpotrf_work( int matrix_order, char uplo, lapack_int n,\n                                double* a, lapack_int lda );\nlapack_int LAPACKE_cpotrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_zpotrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_spotri_work( int matrix_order, char uplo, lapack_int n,\n                                float* a, lapack_int lda );\nlapack_int LAPACKE_dpotri_work( int matrix_order, char uplo, lapack_int n,\n                                double* a, lapack_int lda );\nlapack_int LAPACKE_cpotri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_zpotri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_spotrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const float* a, lapack_int lda,\n                                float* b, lapack_int ldb );\nlapack_int LAPACKE_dpotrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const double* a,\n                                lapack_int lda, double* b, lapack_int ldb );\nlapack_int LAPACKE_cpotrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_zpotrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* b,\n                                lapack_int ldb );\n\nlapack_int LAPACKE_sppcon_work( int matrix_order, char uplo, lapack_int n,\n                                const float* ap, float anorm, float* rcond,\n                                float* work, lapack_int* iwork );\nlapack_int LAPACKE_dppcon_work( int matrix_order, char uplo, lapack_int n,\n                                const double* ap, double anorm, double* rcond,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_cppcon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_float* ap, float anorm,\n                                float* rcond, lapack_complex_float* work,\n                                float* rwork );\nlapack_int LAPACKE_zppcon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_double* ap, double anorm,\n                                double* rcond, lapack_complex_double* work,\n                                double* rwork );\n\nlapack_int LAPACKE_sppequ_work( int matrix_order, char uplo, lapack_int n,\n                                const float* ap, float* s, float* scond,\n                                float* amax );\nlapack_int LAPACKE_dppequ_work( int matrix_order, char uplo, lapack_int n,\n                                const double* ap, double* s, double* scond,\n                                double* amax );\nlapack_int LAPACKE_cppequ_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_float* ap, float* s,\n                                float* scond, float* amax );\nlapack_int LAPACKE_zppequ_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_double* ap, double* s,\n                                double* scond, double* amax );\n\nlapack_int LAPACKE_spprfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const float* ap,\n                                const float* afp, const float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* ferr, float* berr, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dpprfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const double* ap,\n                                const double* afp, const double* b,\n                                lapack_int ldb, double* x, lapack_int ldx,\n                                double* ferr, double* berr, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_cpprfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* ap,\n                                const lapack_complex_float* afp,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zpprfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs,\n                                const lapack_complex_double* ap,\n                                const lapack_complex_double* afp,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sppsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, float* ap, float* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_dppsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, double* ap, double* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_cppsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_float* ap,\n                               lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zppsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_double* ap,\n                               lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_sppsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs, float* ap,\n                                float* afp, char* equed, float* s, float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* rcond, float* ferr, float* berr,\n                                float* work, lapack_int* iwork );\nlapack_int LAPACKE_dppsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs, double* ap,\n                                double* afp, char* equed, double* s, double* b,\n                                lapack_int ldb, double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_cppsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                lapack_complex_float* ap,\n                                lapack_complex_float* afp, char* equed,\n                                float* s, lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* x,\n                                lapack_int ldx, float* rcond, float* ferr,\n                                float* berr, lapack_complex_float* work,\n                                float* rwork );\nlapack_int LAPACKE_zppsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                lapack_complex_double* ap,\n                                lapack_complex_double* afp, char* equed,\n                                double* s, lapack_complex_double* b,\n                                lapack_int ldb, lapack_complex_double* x,\n                                lapack_int ldx, double* rcond, double* ferr,\n                                double* berr, lapack_complex_double* work,\n                                double* rwork );\n\nlapack_int LAPACKE_spptrf_work( int matrix_order, char uplo, lapack_int n,\n                                float* ap );\nlapack_int LAPACKE_dpptrf_work( int matrix_order, char uplo, lapack_int n,\n                                double* ap );\nlapack_int LAPACKE_cpptrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* ap );\nlapack_int LAPACKE_zpptrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* ap );\n\nlapack_int LAPACKE_spptri_work( int matrix_order, char uplo, lapack_int n,\n                                float* ap );\nlapack_int LAPACKE_dpptri_work( int matrix_order, char uplo, lapack_int n,\n                                double* ap );\nlapack_int LAPACKE_cpptri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* ap );\nlapack_int LAPACKE_zpptri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* ap );\n\nlapack_int LAPACKE_spptrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const float* ap, float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_dpptrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const double* ap, double* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_cpptrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* ap,\n                                lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zpptrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs,\n                                const lapack_complex_double* ap,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_spstrf_work( int matrix_order, char uplo, lapack_int n,\n                                float* a, lapack_int lda, lapack_int* piv,\n                                lapack_int* rank, float tol, float* work );\nlapack_int LAPACKE_dpstrf_work( int matrix_order, char uplo, lapack_int n,\n                                double* a, lapack_int lda, lapack_int* piv,\n                                lapack_int* rank, double tol, double* work );\nlapack_int LAPACKE_cpstrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_int* piv, lapack_int* rank, float tol,\n                                float* work );\nlapack_int LAPACKE_zpstrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int* piv, lapack_int* rank, double tol,\n                                double* work );\n\nlapack_int LAPACKE_sptcon_work( lapack_int n, const float* d, const float* e,\n                                float anorm, float* rcond, float* work );\nlapack_int LAPACKE_dptcon_work( lapack_int n, const double* d, const double* e,\n                                double anorm, double* rcond, double* work );\nlapack_int LAPACKE_cptcon_work( lapack_int n, const float* d,\n                                const lapack_complex_float* e, float anorm,\n                                float* rcond, float* work );\nlapack_int LAPACKE_zptcon_work( lapack_int n, const double* d,\n                                const lapack_complex_double* e, double anorm,\n                                double* rcond, double* work );\n\nlapack_int LAPACKE_spteqr_work( int matrix_order, char compz, lapack_int n,\n                                float* d, float* e, float* z, lapack_int ldz,\n                                float* work );\nlapack_int LAPACKE_dpteqr_work( int matrix_order, char compz, lapack_int n,\n                                double* d, double* e, double* z, lapack_int ldz,\n                                double* work );\nlapack_int LAPACKE_cpteqr_work( int matrix_order, char compz, lapack_int n,\n                                float* d, float* e, lapack_complex_float* z,\n                                lapack_int ldz, float* work );\nlapack_int LAPACKE_zpteqr_work( int matrix_order, char compz, lapack_int n,\n                                double* d, double* e, lapack_complex_double* z,\n                                lapack_int ldz, double* work );\n\nlapack_int LAPACKE_sptrfs_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                                const float* d, const float* e, const float* df,\n                                const float* ef, const float* b, lapack_int ldb,\n                                float* x, lapack_int ldx, float* ferr,\n                                float* berr, float* work );\nlapack_int LAPACKE_dptrfs_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                                const double* d, const double* e,\n                                const double* df, const double* ef,\n                                const double* b, lapack_int ldb, double* x,\n                                lapack_int ldx, double* ferr, double* berr,\n                                double* work );\nlapack_int LAPACKE_cptrfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const float* d,\n                                const lapack_complex_float* e, const float* df,\n                                const lapack_complex_float* ef,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zptrfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const double* d,\n                                const lapack_complex_double* e,\n                                const double* df,\n                                const lapack_complex_double* ef,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sptsv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               float* d, float* e, float* b, lapack_int ldb );\nlapack_int LAPACKE_dptsv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               double* d, double* e, double* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_cptsv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               float* d, lapack_complex_float* e,\n                               lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zptsv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               double* d, lapack_complex_double* e,\n                               lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_sptsvx_work( int matrix_order, char fact, lapack_int n,\n                                lapack_int nrhs, const float* d, const float* e,\n                                float* df, float* ef, const float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* rcond, float* ferr, float* berr,\n                                float* work );\nlapack_int LAPACKE_dptsvx_work( int matrix_order, char fact, lapack_int n,\n                                lapack_int nrhs, const double* d,\n                                const double* e, double* df, double* ef,\n                                const double* b, lapack_int ldb, double* x,\n                                lapack_int ldx, double* rcond, double* ferr,\n                                double* berr, double* work );\nlapack_int LAPACKE_cptsvx_work( int matrix_order, char fact, lapack_int n,\n                                lapack_int nrhs, const float* d,\n                                const lapack_complex_float* e, float* df,\n                                lapack_complex_float* ef,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* rcond, float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zptsvx_work( int matrix_order, char fact, lapack_int n,\n                                lapack_int nrhs, const double* d,\n                                const lapack_complex_double* e, double* df,\n                                lapack_complex_double* ef,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_spttrf_work( lapack_int n, float* d, float* e );\nlapack_int LAPACKE_dpttrf_work( lapack_int n, double* d, double* e );\nlapack_int LAPACKE_cpttrf_work( lapack_int n, float* d,\n                                lapack_complex_float* e );\nlapack_int LAPACKE_zpttrf_work( lapack_int n, double* d,\n                                lapack_complex_double* e );\n\nlapack_int LAPACKE_spttrs_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                                const float* d, const float* e, float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_dpttrs_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                                const double* d, const double* e, double* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_cpttrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const float* d,\n                                const lapack_complex_float* e,\n                                lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zpttrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const double* d,\n                                const lapack_complex_double* e,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_ssbev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_int kd, float* ab,\n                               lapack_int ldab, float* w, float* z,\n                               lapack_int ldz, float* work );\nlapack_int LAPACKE_dsbev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_int kd, double* ab,\n                               lapack_int ldab, double* w, double* z,\n                               lapack_int ldz, double* work );\n\nlapack_int LAPACKE_ssbevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_int kd, float* ab,\n                                lapack_int ldab, float* w, float* z,\n                                lapack_int ldz, float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_dsbevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_int kd, double* ab,\n                                lapack_int ldab, double* w, double* z,\n                                lapack_int ldz, double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_ssbevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, lapack_int kd,\n                                float* ab, lapack_int ldab, float* q,\n                                lapack_int ldq, float vl, float vu,\n                                lapack_int il, lapack_int iu, float abstol,\n                                lapack_int* m, float* w, float* z,\n                                lapack_int ldz, float* work, lapack_int* iwork,\n                                lapack_int* ifail );\nlapack_int LAPACKE_dsbevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, lapack_int kd,\n                                double* ab, lapack_int ldab, double* q,\n                                lapack_int ldq, double vl, double vu,\n                                lapack_int il, lapack_int iu, double abstol,\n                                lapack_int* m, double* w, double* z,\n                                lapack_int ldz, double* work, lapack_int* iwork,\n                                lapack_int* ifail );\n\nlapack_int LAPACKE_ssbgst_work( int matrix_order, char vect, char uplo,\n                                lapack_int n, lapack_int ka, lapack_int kb,\n                                float* ab, lapack_int ldab, const float* bb,\n                                lapack_int ldbb, float* x, lapack_int ldx,\n                                float* work );\nlapack_int LAPACKE_dsbgst_work( int matrix_order, char vect, char uplo,\n                                lapack_int n, lapack_int ka, lapack_int kb,\n                                double* ab, lapack_int ldab, const double* bb,\n                                lapack_int ldbb, double* x, lapack_int ldx,\n                                double* work );\n\nlapack_int LAPACKE_ssbgv_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_int ka, lapack_int kb,\n                               float* ab, lapack_int ldab, float* bb,\n                               lapack_int ldbb, float* w, float* z,\n                               lapack_int ldz, float* work );\nlapack_int LAPACKE_dsbgv_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_int ka, lapack_int kb,\n                               double* ab, lapack_int ldab, double* bb,\n                               lapack_int ldbb, double* w, double* z,\n                               lapack_int ldz, double* work );\n\nlapack_int LAPACKE_ssbgvd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_int ka, lapack_int kb,\n                                float* ab, lapack_int ldab, float* bb,\n                                lapack_int ldbb, float* w, float* z,\n                                lapack_int ldz, float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_dsbgvd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_int ka, lapack_int kb,\n                                double* ab, lapack_int ldab, double* bb,\n                                lapack_int ldbb, double* w, double* z,\n                                lapack_int ldz, double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_ssbgvx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, lapack_int ka,\n                                lapack_int kb, float* ab, lapack_int ldab,\n                                float* bb, lapack_int ldbb, float* q,\n                                lapack_int ldq, float vl, float vu,\n                                lapack_int il, lapack_int iu, float abstol,\n                                lapack_int* m, float* w, float* z,\n                                lapack_int ldz, float* work, lapack_int* iwork,\n                                lapack_int* ifail );\nlapack_int LAPACKE_dsbgvx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, lapack_int ka,\n                                lapack_int kb, double* ab, lapack_int ldab,\n                                double* bb, lapack_int ldbb, double* q,\n                                lapack_int ldq, double vl, double vu,\n                                lapack_int il, lapack_int iu, double abstol,\n                                lapack_int* m, double* w, double* z,\n                                lapack_int ldz, double* work, lapack_int* iwork,\n                                lapack_int* ifail );\n\nlapack_int LAPACKE_ssbtrd_work( int matrix_order, char vect, char uplo,\n                                lapack_int n, lapack_int kd, float* ab,\n                                lapack_int ldab, float* d, float* e, float* q,\n                                lapack_int ldq, float* work );\nlapack_int LAPACKE_dsbtrd_work( int matrix_order, char vect, char uplo,\n                                lapack_int n, lapack_int kd, double* ab,\n                                lapack_int ldab, double* d, double* e,\n                                double* q, lapack_int ldq, double* work );\n\nlapack_int LAPACKE_ssfrk_work( int matrix_order, char transr, char uplo,\n                               char trans, lapack_int n, lapack_int k,\n                               float alpha, const float* a, lapack_int lda,\n                               float beta, float* c );\nlapack_int LAPACKE_dsfrk_work( int matrix_order, char transr, char uplo,\n                               char trans, lapack_int n, lapack_int k,\n                               double alpha, const double* a, lapack_int lda,\n                               double beta, double* c );\n\nlapack_int LAPACKE_sspcon_work( int matrix_order, char uplo, lapack_int n,\n                                const float* ap, const lapack_int* ipiv,\n                                float anorm, float* rcond, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dspcon_work( int matrix_order, char uplo, lapack_int n,\n                                const double* ap, const lapack_int* ipiv,\n                                double anorm, double* rcond, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_cspcon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_float* ap,\n                                const lapack_int* ipiv, float anorm,\n                                float* rcond, lapack_complex_float* work );\nlapack_int LAPACKE_zspcon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_double* ap,\n                                const lapack_int* ipiv, double anorm,\n                                double* rcond, lapack_complex_double* work );\n\nlapack_int LAPACKE_sspev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, float* ap, float* w, float* z,\n                               lapack_int ldz, float* work );\nlapack_int LAPACKE_dspev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, double* ap, double* w, double* z,\n                               lapack_int ldz, double* work );\n\nlapack_int LAPACKE_sspevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, float* ap, float* w, float* z,\n                                lapack_int ldz, float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_dspevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, double* ap, double* w, double* z,\n                                lapack_int ldz, double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_sspevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, float* ap, float vl,\n                                float vu, lapack_int il, lapack_int iu,\n                                float abstol, lapack_int* m, float* w, float* z,\n                                lapack_int ldz, float* work, lapack_int* iwork,\n                                lapack_int* ifail );\nlapack_int LAPACKE_dspevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, double* ap, double vl,\n                                double vu, lapack_int il, lapack_int iu,\n                                double abstol, lapack_int* m, double* w,\n                                double* z, lapack_int ldz, double* work,\n                                lapack_int* iwork, lapack_int* ifail );\n\nlapack_int LAPACKE_sspgst_work( int matrix_order, lapack_int itype, char uplo,\n                                lapack_int n, float* ap, const float* bp );\nlapack_int LAPACKE_dspgst_work( int matrix_order, lapack_int itype, char uplo,\n                                lapack_int n, double* ap, const double* bp );\n\nlapack_int LAPACKE_sspgv_work( int matrix_order, lapack_int itype, char jobz,\n                               char uplo, lapack_int n, float* ap, float* bp,\n                               float* w, float* z, lapack_int ldz,\n                               float* work );\nlapack_int LAPACKE_dspgv_work( int matrix_order, lapack_int itype, char jobz,\n                               char uplo, lapack_int n, double* ap, double* bp,\n                               double* w, double* z, lapack_int ldz,\n                               double* work );\n\nlapack_int LAPACKE_sspgvd_work( int matrix_order, lapack_int itype, char jobz,\n                                char uplo, lapack_int n, float* ap, float* bp,\n                                float* w, float* z, lapack_int ldz, float* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_dspgvd_work( int matrix_order, lapack_int itype, char jobz,\n                                char uplo, lapack_int n, double* ap, double* bp,\n                                double* w, double* z, lapack_int ldz,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_sspgvx_work( int matrix_order, lapack_int itype, char jobz,\n                                char range, char uplo, lapack_int n, float* ap,\n                                float* bp, float vl, float vu, lapack_int il,\n                                lapack_int iu, float abstol, lapack_int* m,\n                                float* w, float* z, lapack_int ldz, float* work,\n                                lapack_int* iwork, lapack_int* ifail );\nlapack_int LAPACKE_dspgvx_work( int matrix_order, lapack_int itype, char jobz,\n                                char range, char uplo, lapack_int n, double* ap,\n                                double* bp, double vl, double vu, lapack_int il,\n                                lapack_int iu, double abstol, lapack_int* m,\n                                double* w, double* z, lapack_int ldz,\n                                double* work, lapack_int* iwork,\n                                lapack_int* ifail );\n\nlapack_int LAPACKE_ssprfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const float* ap,\n                                const float* afp, const lapack_int* ipiv,\n                                const float* b, lapack_int ldb, float* x,\n                                lapack_int ldx, float* ferr, float* berr,\n                                float* work, lapack_int* iwork );\nlapack_int LAPACKE_dsprfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const double* ap,\n                                const double* afp, const lapack_int* ipiv,\n                                const double* b, lapack_int ldb, double* x,\n                                lapack_int ldx, double* ferr, double* berr,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_csprfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* ap,\n                                const lapack_complex_float* afp,\n                                const lapack_int* ipiv,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zsprfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs,\n                                const lapack_complex_double* ap,\n                                const lapack_complex_double* afp,\n                                const lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sspsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, float* ap, lapack_int* ipiv,\n                               float* b, lapack_int ldb );\nlapack_int LAPACKE_dspsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, double* ap, lapack_int* ipiv,\n                               double* b, lapack_int ldb );\nlapack_int LAPACKE_cspsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_float* ap,\n                               lapack_int* ipiv, lapack_complex_float* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_zspsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_double* ap,\n                               lapack_int* ipiv, lapack_complex_double* b,\n                               lapack_int ldb );\n\nlapack_int LAPACKE_sspsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs, const float* ap,\n                                float* afp, lapack_int* ipiv, const float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* rcond, float* ferr, float* berr,\n                                float* work, lapack_int* iwork );\nlapack_int LAPACKE_dspsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs, const double* ap,\n                                double* afp, lapack_int* ipiv, const double* b,\n                                lapack_int ldb, double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_cspsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_float* ap,\n                                lapack_complex_float* afp, lapack_int* ipiv,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* rcond, float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zspsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_double* ap,\n                                lapack_complex_double* afp, lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_ssptrd_work( int matrix_order, char uplo, lapack_int n,\n                                float* ap, float* d, float* e, float* tau );\nlapack_int LAPACKE_dsptrd_work( int matrix_order, char uplo, lapack_int n,\n                                double* ap, double* d, double* e, double* tau );\n\nlapack_int LAPACKE_ssptrf_work( int matrix_order, char uplo, lapack_int n,\n                                float* ap, lapack_int* ipiv );\nlapack_int LAPACKE_dsptrf_work( int matrix_order, char uplo, lapack_int n,\n                                double* ap, lapack_int* ipiv );\nlapack_int LAPACKE_csptrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* ap, lapack_int* ipiv );\nlapack_int LAPACKE_zsptrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* ap, lapack_int* ipiv );\n\nlapack_int LAPACKE_ssptri_work( int matrix_order, char uplo, lapack_int n,\n                                float* ap, const lapack_int* ipiv,\n                                float* work );\nlapack_int LAPACKE_dsptri_work( int matrix_order, char uplo, lapack_int n,\n                                double* ap, const lapack_int* ipiv,\n                                double* work );\nlapack_int LAPACKE_csptri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* ap,\n                                const lapack_int* ipiv,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zsptri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* ap,\n                                const lapack_int* ipiv,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_ssptrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const float* ap,\n                                const lapack_int* ipiv, float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_dsptrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const double* ap,\n                                const lapack_int* ipiv, double* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_csptrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* ap,\n                                const lapack_int* ipiv, lapack_complex_float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_zsptrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs,\n                                const lapack_complex_double* ap,\n                                const lapack_int* ipiv,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_sstebz_work( char range, char order, lapack_int n, float vl,\n                                float vu, lapack_int il, lapack_int iu,\n                                float abstol, const float* d, const float* e,\n                                lapack_int* m, lapack_int* nsplit, float* w,\n                                lapack_int* iblock, lapack_int* isplit,\n                                float* work, lapack_int* iwork );\nlapack_int LAPACKE_dstebz_work( char range, char order, lapack_int n, double vl,\n                                double vu, lapack_int il, lapack_int iu,\n                                double abstol, const double* d, const double* e,\n                                lapack_int* m, lapack_int* nsplit, double* w,\n                                lapack_int* iblock, lapack_int* isplit,\n                                double* work, lapack_int* iwork );\n\nlapack_int LAPACKE_sstedc_work( int matrix_order, char compz, lapack_int n,\n                                float* d, float* e, float* z, lapack_int ldz,\n                                float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_dstedc_work( int matrix_order, char compz, lapack_int n,\n                                double* d, double* e, double* z, lapack_int ldz,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_cstedc_work( int matrix_order, char compz, lapack_int n,\n                                float* d, float* e, lapack_complex_float* z,\n                                lapack_int ldz, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork,\n                                lapack_int lrwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_zstedc_work( int matrix_order, char compz, lapack_int n,\n                                double* d, double* e, lapack_complex_double* z,\n                                lapack_int ldz, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork,\n                                lapack_int lrwork, lapack_int* iwork,\n                                lapack_int liwork );\n\nlapack_int LAPACKE_sstegr_work( int matrix_order, char jobz, char range,\n                                lapack_int n, float* d, float* e, float vl,\n                                float vu, lapack_int il, lapack_int iu,\n                                float abstol, lapack_int* m, float* w, float* z,\n                                lapack_int ldz, lapack_int* isuppz, float* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_dstegr_work( int matrix_order, char jobz, char range,\n                                lapack_int n, double* d, double* e, double vl,\n                                double vu, lapack_int il, lapack_int iu,\n                                double abstol, lapack_int* m, double* w,\n                                double* z, lapack_int ldz, lapack_int* isuppz,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_cstegr_work( int matrix_order, char jobz, char range,\n                                lapack_int n, float* d, float* e, float vl,\n                                float vu, lapack_int il, lapack_int iu,\n                                float abstol, lapack_int* m, float* w,\n                                lapack_complex_float* z, lapack_int ldz,\n                                lapack_int* isuppz, float* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_zstegr_work( int matrix_order, char jobz, char range,\n                                lapack_int n, double* d, double* e, double vl,\n                                double vu, lapack_int il, lapack_int iu,\n                                double abstol, lapack_int* m, double* w,\n                                lapack_complex_double* z, lapack_int ldz,\n                                lapack_int* isuppz, double* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int liwork );\n\nlapack_int LAPACKE_sstein_work( int matrix_order, lapack_int n, const float* d,\n                                const float* e, lapack_int m, const float* w,\n                                const lapack_int* iblock,\n                                const lapack_int* isplit, float* z,\n                                lapack_int ldz, float* work, lapack_int* iwork,\n                                lapack_int* ifailv );\nlapack_int LAPACKE_dstein_work( int matrix_order, lapack_int n, const double* d,\n                                const double* e, lapack_int m, const double* w,\n                                const lapack_int* iblock,\n                                const lapack_int* isplit, double* z,\n                                lapack_int ldz, double* work, lapack_int* iwork,\n                                lapack_int* ifailv );\nlapack_int LAPACKE_cstein_work( int matrix_order, lapack_int n, const float* d,\n                                const float* e, lapack_int m, const float* w,\n                                const lapack_int* iblock,\n                                const lapack_int* isplit,\n                                lapack_complex_float* z, lapack_int ldz,\n                                float* work, lapack_int* iwork,\n                                lapack_int* ifailv );\nlapack_int LAPACKE_zstein_work( int matrix_order, lapack_int n, const double* d,\n                                const double* e, lapack_int m, const double* w,\n                                const lapack_int* iblock,\n                                const lapack_int* isplit,\n                                lapack_complex_double* z, lapack_int ldz,\n                                double* work, lapack_int* iwork,\n                                lapack_int* ifailv );\n\nlapack_int LAPACKE_sstemr_work( int matrix_order, char jobz, char range,\n                                lapack_int n, float* d, float* e, float vl,\n                                float vu, lapack_int il, lapack_int iu,\n                                lapack_int* m, float* w, float* z,\n                                lapack_int ldz, lapack_int nzc,\n                                lapack_int* isuppz, lapack_logical* tryrac,\n                                float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_dstemr_work( int matrix_order, char jobz, char range,\n                                lapack_int n, double* d, double* e, double vl,\n                                double vu, lapack_int il, lapack_int iu,\n                                lapack_int* m, double* w, double* z,\n                                lapack_int ldz, lapack_int nzc,\n                                lapack_int* isuppz, lapack_logical* tryrac,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_cstemr_work( int matrix_order, char jobz, char range,\n                                lapack_int n, float* d, float* e, float vl,\n                                float vu, lapack_int il, lapack_int iu,\n                                lapack_int* m, float* w,\n                                lapack_complex_float* z, lapack_int ldz,\n                                lapack_int nzc, lapack_int* isuppz,\n                                lapack_logical* tryrac, float* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_zstemr_work( int matrix_order, char jobz, char range,\n                                lapack_int n, double* d, double* e, double vl,\n                                double vu, lapack_int il, lapack_int iu,\n                                lapack_int* m, double* w,\n                                lapack_complex_double* z, lapack_int ldz,\n                                lapack_int nzc, lapack_int* isuppz,\n                                lapack_logical* tryrac, double* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int liwork );\n\nlapack_int LAPACKE_ssteqr_work( int matrix_order, char compz, lapack_int n,\n                                float* d, float* e, float* z, lapack_int ldz,\n                                float* work );\nlapack_int LAPACKE_dsteqr_work( int matrix_order, char compz, lapack_int n,\n                                double* d, double* e, double* z, lapack_int ldz,\n                                double* work );\nlapack_int LAPACKE_csteqr_work( int matrix_order, char compz, lapack_int n,\n                                float* d, float* e, lapack_complex_float* z,\n                                lapack_int ldz, float* work );\nlapack_int LAPACKE_zsteqr_work( int matrix_order, char compz, lapack_int n,\n                                double* d, double* e, lapack_complex_double* z,\n                                lapack_int ldz, double* work );\n\nlapack_int LAPACKE_ssterf_work( lapack_int n, float* d, float* e );\nlapack_int LAPACKE_dsterf_work( lapack_int n, double* d, double* e );\n\nlapack_int LAPACKE_sstev_work( int matrix_order, char jobz, lapack_int n,\n                               float* d, float* e, float* z, lapack_int ldz,\n                               float* work );\nlapack_int LAPACKE_dstev_work( int matrix_order, char jobz, lapack_int n,\n                               double* d, double* e, double* z, lapack_int ldz,\n                               double* work );\n\nlapack_int LAPACKE_sstevd_work( int matrix_order, char jobz, lapack_int n,\n                                float* d, float* e, float* z, lapack_int ldz,\n                                float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_dstevd_work( int matrix_order, char jobz, lapack_int n,\n                                double* d, double* e, double* z, lapack_int ldz,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_sstevr_work( int matrix_order, char jobz, char range,\n                                lapack_int n, float* d, float* e, float vl,\n                                float vu, lapack_int il, lapack_int iu,\n                                float abstol, lapack_int* m, float* w, float* z,\n                                lapack_int ldz, lapack_int* isuppz, float* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_dstevr_work( int matrix_order, char jobz, char range,\n                                lapack_int n, double* d, double* e, double vl,\n                                double vu, lapack_int il, lapack_int iu,\n                                double abstol, lapack_int* m, double* w,\n                                double* z, lapack_int ldz, lapack_int* isuppz,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_sstevx_work( int matrix_order, char jobz, char range,\n                                lapack_int n, float* d, float* e, float vl,\n                                float vu, lapack_int il, lapack_int iu,\n                                float abstol, lapack_int* m, float* w, float* z,\n                                lapack_int ldz, float* work, lapack_int* iwork,\n                                lapack_int* ifail );\nlapack_int LAPACKE_dstevx_work( int matrix_order, char jobz, char range,\n                                lapack_int n, double* d, double* e, double vl,\n                                double vu, lapack_int il, lapack_int iu,\n                                double abstol, lapack_int* m, double* w,\n                                double* z, lapack_int ldz, double* work,\n                                lapack_int* iwork, lapack_int* ifail );\n\nlapack_int LAPACKE_ssycon_work( int matrix_order, char uplo, lapack_int n,\n                                const float* a, lapack_int lda,\n                                const lapack_int* ipiv, float anorm,\n                                float* rcond, float* work, lapack_int* iwork );\nlapack_int LAPACKE_dsycon_work( int matrix_order, char uplo, lapack_int n,\n                                const double* a, lapack_int lda,\n                                const lapack_int* ipiv, double anorm,\n                                double* rcond, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_csycon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_int* ipiv, float anorm,\n                                float* rcond, lapack_complex_float* work );\nlapack_int LAPACKE_zsycon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_int* ipiv, double anorm,\n                                double* rcond, lapack_complex_double* work );\n\nlapack_int LAPACKE_ssyequb_work( int matrix_order, char uplo, lapack_int n,\n                                 const float* a, lapack_int lda, float* s,\n                                 float* scond, float* amax, float* work );\nlapack_int LAPACKE_dsyequb_work( int matrix_order, char uplo, lapack_int n,\n                                 const double* a, lapack_int lda, double* s,\n                                 double* scond, double* amax, double* work );\nlapack_int LAPACKE_csyequb_work( int matrix_order, char uplo, lapack_int n,\n                                 const lapack_complex_float* a, lapack_int lda,\n                                 float* s, float* scond, float* amax,\n                                 lapack_complex_float* work );\nlapack_int LAPACKE_zsyequb_work( int matrix_order, char uplo, lapack_int n,\n                                 const lapack_complex_double* a, lapack_int lda,\n                                 double* s, double* scond, double* amax,\n                                 lapack_complex_double* work );\n\nlapack_int LAPACKE_ssyev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, float* a, lapack_int lda, float* w,\n                               float* work, lapack_int lwork );\nlapack_int LAPACKE_dsyev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, double* a, lapack_int lda,\n                               double* w, double* work, lapack_int lwork );\n\nlapack_int LAPACKE_ssyevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, float* a, lapack_int lda,\n                                float* w, float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_dsyevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, double* a, lapack_int lda,\n                                double* w, double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_ssyevr_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, float* a,\n                                lapack_int lda, float vl, float vu,\n                                lapack_int il, lapack_int iu, float abstol,\n                                lapack_int* m, float* w, float* z,\n                                lapack_int ldz, lapack_int* isuppz, float* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_dsyevr_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, double* a,\n                                lapack_int lda, double vl, double vu,\n                                lapack_int il, lapack_int iu, double abstol,\n                                lapack_int* m, double* w, double* z,\n                                lapack_int ldz, lapack_int* isuppz,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_ssyevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, float* a,\n                                lapack_int lda, float vl, float vu,\n                                lapack_int il, lapack_int iu, float abstol,\n                                lapack_int* m, float* w, float* z,\n                                lapack_int ldz, float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int* ifail );\nlapack_int LAPACKE_dsyevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, double* a,\n                                lapack_int lda, double vl, double vu,\n                                lapack_int il, lapack_int iu, double abstol,\n                                lapack_int* m, double* w, double* z,\n                                lapack_int ldz, double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int* ifail );\n\nlapack_int LAPACKE_ssygst_work( int matrix_order, lapack_int itype, char uplo,\n                                lapack_int n, float* a, lapack_int lda,\n                                const float* b, lapack_int ldb );\nlapack_int LAPACKE_dsygst_work( int matrix_order, lapack_int itype, char uplo,\n                                lapack_int n, double* a, lapack_int lda,\n                                const double* b, lapack_int ldb );\n\nlapack_int LAPACKE_ssygv_work( int matrix_order, lapack_int itype, char jobz,\n                               char uplo, lapack_int n, float* a,\n                               lapack_int lda, float* b, lapack_int ldb,\n                               float* w, float* work, lapack_int lwork );\nlapack_int LAPACKE_dsygv_work( int matrix_order, lapack_int itype, char jobz,\n                               char uplo, lapack_int n, double* a,\n                               lapack_int lda, double* b, lapack_int ldb,\n                               double* w, double* work, lapack_int lwork );\n\nlapack_int LAPACKE_ssygvd_work( int matrix_order, lapack_int itype, char jobz,\n                                char uplo, lapack_int n, float* a,\n                                lapack_int lda, float* b, lapack_int ldb,\n                                float* w, float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_dsygvd_work( int matrix_order, lapack_int itype, char jobz,\n                                char uplo, lapack_int n, double* a,\n                                lapack_int lda, double* b, lapack_int ldb,\n                                double* w, double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_ssygvx_work( int matrix_order, lapack_int itype, char jobz,\n                                char range, char uplo, lapack_int n, float* a,\n                                lapack_int lda, float* b, lapack_int ldb,\n                                float vl, float vu, lapack_int il,\n                                lapack_int iu, float abstol, lapack_int* m,\n                                float* w, float* z, lapack_int ldz, float* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int* ifail );\nlapack_int LAPACKE_dsygvx_work( int matrix_order, lapack_int itype, char jobz,\n                                char range, char uplo, lapack_int n, double* a,\n                                lapack_int lda, double* b, lapack_int ldb,\n                                double vl, double vu, lapack_int il,\n                                lapack_int iu, double abstol, lapack_int* m,\n                                double* w, double* z, lapack_int ldz,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int* ifail );\n\nlapack_int LAPACKE_ssyrfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const float* a, lapack_int lda,\n                                const float* af, lapack_int ldaf,\n                                const lapack_int* ipiv, const float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* ferr, float* berr, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dsyrfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const double* a,\n                                lapack_int lda, const double* af,\n                                lapack_int ldaf, const lapack_int* ipiv,\n                                const double* b, lapack_int ldb, double* x,\n                                lapack_int ldx, double* ferr, double* berr,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_csyrfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* af,\n                                lapack_int ldaf, const lapack_int* ipiv,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zsyrfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_double* a,\n                                lapack_int lda, const lapack_complex_double* af,\n                                lapack_int ldaf, const lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_ssyrfsx_work( int matrix_order, char uplo, char equed,\n                                 lapack_int n, lapack_int nrhs, const float* a,\n                                 lapack_int lda, const float* af,\n                                 lapack_int ldaf, const lapack_int* ipiv,\n                                 const float* s, const float* b, lapack_int ldb,\n                                 float* x, lapack_int ldx, float* rcond,\n                                 float* berr, lapack_int n_err_bnds,\n                                 float* err_bnds_norm, float* err_bnds_comp,\n                                 lapack_int nparams, float* params, float* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_dsyrfsx_work( int matrix_order, char uplo, char equed,\n                                 lapack_int n, lapack_int nrhs, const double* a,\n                                 lapack_int lda, const double* af,\n                                 lapack_int ldaf, const lapack_int* ipiv,\n                                 const double* s, const double* b,\n                                 lapack_int ldb, double* x, lapack_int ldx,\n                                 double* rcond, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, double* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_csyrfsx_work( int matrix_order, char uplo, char equed,\n                                 lapack_int n, lapack_int nrhs,\n                                 const lapack_complex_float* a, lapack_int lda,\n                                 const lapack_complex_float* af,\n                                 lapack_int ldaf, const lapack_int* ipiv,\n                                 const float* s, const lapack_complex_float* b,\n                                 lapack_int ldb, lapack_complex_float* x,\n                                 lapack_int ldx, float* rcond, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, lapack_complex_float* work,\n                                 float* rwork );\nlapack_int LAPACKE_zsyrfsx_work( int matrix_order, char uplo, char equed,\n                                 lapack_int n, lapack_int nrhs,\n                                 const lapack_complex_double* a, lapack_int lda,\n                                 const lapack_complex_double* af,\n                                 lapack_int ldaf, const lapack_int* ipiv,\n                                 const double* s,\n                                 const lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* x, lapack_int ldx,\n                                 double* rcond, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, lapack_complex_double* work,\n                                 double* rwork );\n\nlapack_int LAPACKE_ssysv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, float* a, lapack_int lda,\n                               lapack_int* ipiv, float* b, lapack_int ldb,\n                               float* work, lapack_int lwork );\nlapack_int LAPACKE_dsysv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, double* a, lapack_int lda,\n                               lapack_int* ipiv, double* b, lapack_int ldb,\n                               double* work, lapack_int lwork );\nlapack_int LAPACKE_csysv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_float* a,\n                               lapack_int lda, lapack_int* ipiv,\n                               lapack_complex_float* b, lapack_int ldb,\n                               lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zsysv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_double* a,\n                               lapack_int lda, lapack_int* ipiv,\n                               lapack_complex_double* b, lapack_int ldb,\n                               lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_ssysvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs, const float* a,\n                                lapack_int lda, float* af, lapack_int ldaf,\n                                lapack_int* ipiv, const float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* rcond, float* ferr, float* berr,\n                                float* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dsysvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs, const double* a,\n                                lapack_int lda, double* af, lapack_int ldaf,\n                                lapack_int* ipiv, const double* b,\n                                lapack_int ldb, double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_csysvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* af, lapack_int ldaf,\n                                lapack_int* ipiv, const lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* x,\n                                lapack_int ldx, float* rcond, float* ferr,\n                                float* berr, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork );\nlapack_int LAPACKE_zsysvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* af, lapack_int ldaf,\n                                lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork );\n\nlapack_int LAPACKE_ssysvxx_work( int matrix_order, char fact, char uplo,\n                                 lapack_int n, lapack_int nrhs, float* a,\n                                 lapack_int lda, float* af, lapack_int ldaf,\n                                 lapack_int* ipiv, char* equed, float* s,\n                                 float* b, lapack_int ldb, float* x,\n                                 lapack_int ldx, float* rcond, float* rpvgrw,\n                                 float* berr, lapack_int n_err_bnds,\n                                 float* err_bnds_norm, float* err_bnds_comp,\n                                 lapack_int nparams, float* params, float* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_dsysvxx_work( int matrix_order, char fact, char uplo,\n                                 lapack_int n, lapack_int nrhs, double* a,\n                                 lapack_int lda, double* af, lapack_int ldaf,\n                                 lapack_int* ipiv, char* equed, double* s,\n                                 double* b, lapack_int ldb, double* x,\n                                 lapack_int ldx, double* rcond, double* rpvgrw,\n                                 double* berr, lapack_int n_err_bnds,\n                                 double* err_bnds_norm, double* err_bnds_comp,\n                                 lapack_int nparams, double* params,\n                                 double* work, lapack_int* iwork );\nlapack_int LAPACKE_csysvxx_work( int matrix_order, char fact, char uplo,\n                                 lapack_int n, lapack_int nrhs,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 lapack_complex_float* af, lapack_int ldaf,\n                                 lapack_int* ipiv, char* equed, float* s,\n                                 lapack_complex_float* b, lapack_int ldb,\n                                 lapack_complex_float* x, lapack_int ldx,\n                                 float* rcond, float* rpvgrw, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, lapack_complex_float* work,\n                                 float* rwork );\nlapack_int LAPACKE_zsysvxx_work( int matrix_order, char fact, char uplo,\n                                 lapack_int n, lapack_int nrhs,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 lapack_complex_double* af, lapack_int ldaf,\n                                 lapack_int* ipiv, char* equed, double* s,\n                                 lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* x, lapack_int ldx,\n                                 double* rcond, double* rpvgrw, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, lapack_complex_double* work,\n                                 double* rwork );\n\nlapack_int LAPACKE_ssytrd_work( int matrix_order, char uplo, lapack_int n,\n                                float* a, lapack_int lda, float* d, float* e,\n                                float* tau, float* work, lapack_int lwork );\nlapack_int LAPACKE_dsytrd_work( int matrix_order, char uplo, lapack_int n,\n                                double* a, lapack_int lda, double* d, double* e,\n                                double* tau, double* work, lapack_int lwork );\n\nlapack_int LAPACKE_ssytrf_work( int matrix_order, char uplo, lapack_int n,\n                                float* a, lapack_int lda, lapack_int* ipiv,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dsytrf_work( int matrix_order, char uplo, lapack_int n,\n                                double* a, lapack_int lda, lapack_int* ipiv,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_csytrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_int* ipiv, lapack_complex_float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_zsytrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int* ipiv, lapack_complex_double* work,\n                                lapack_int lwork );\n\nlapack_int LAPACKE_ssytri_work( int matrix_order, char uplo, lapack_int n,\n                                float* a, lapack_int lda,\n                                const lapack_int* ipiv, float* work );\nlapack_int LAPACKE_dsytri_work( int matrix_order, char uplo, lapack_int n,\n                                double* a, lapack_int lda,\n                                const lapack_int* ipiv, double* work );\nlapack_int LAPACKE_csytri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                const lapack_int* ipiv,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zsytri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                const lapack_int* ipiv,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_ssytrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const float* a, lapack_int lda,\n                                const lapack_int* ipiv, float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_dsytrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const double* a,\n                                lapack_int lda, const lapack_int* ipiv,\n                                double* b, lapack_int ldb );\nlapack_int LAPACKE_csytrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* a,\n                                lapack_int lda, const lapack_int* ipiv,\n                                lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zsytrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_double* a,\n                                lapack_int lda, const lapack_int* ipiv,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_stbcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n, lapack_int kd,\n                                const float* ab, lapack_int ldab, float* rcond,\n                                float* work, lapack_int* iwork );\nlapack_int LAPACKE_dtbcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n, lapack_int kd,\n                                const double* ab, lapack_int ldab,\n                                double* rcond, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_ctbcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n, lapack_int kd,\n                                const lapack_complex_float* ab, lapack_int ldab,\n                                float* rcond, lapack_complex_float* work,\n                                float* rwork );\nlapack_int LAPACKE_ztbcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n, lapack_int kd,\n                                const lapack_complex_double* ab,\n                                lapack_int ldab, double* rcond,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_stbrfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int kd,\n                                lapack_int nrhs, const float* ab,\n                                lapack_int ldab, const float* b, lapack_int ldb,\n                                const float* x, lapack_int ldx, float* ferr,\n                                float* berr, float* work, lapack_int* iwork );\nlapack_int LAPACKE_dtbrfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int kd,\n                                lapack_int nrhs, const double* ab,\n                                lapack_int ldab, const double* b,\n                                lapack_int ldb, const double* x, lapack_int ldx,\n                                double* ferr, double* berr, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_ctbrfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int kd,\n                                lapack_int nrhs, const lapack_complex_float* ab,\n                                lapack_int ldab, const lapack_complex_float* b,\n                                lapack_int ldb, const lapack_complex_float* x,\n                                lapack_int ldx, float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_ztbrfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int kd,\n                                lapack_int nrhs,\n                                const lapack_complex_double* ab,\n                                lapack_int ldab, const lapack_complex_double* b,\n                                lapack_int ldb, const lapack_complex_double* x,\n                                lapack_int ldx, double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_stbtrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int kd,\n                                lapack_int nrhs, const float* ab,\n                                lapack_int ldab, float* b, lapack_int ldb );\nlapack_int LAPACKE_dtbtrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int kd,\n                                lapack_int nrhs, const double* ab,\n                                lapack_int ldab, double* b, lapack_int ldb );\nlapack_int LAPACKE_ctbtrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int kd,\n                                lapack_int nrhs, const lapack_complex_float* ab,\n                                lapack_int ldab, lapack_complex_float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_ztbtrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int kd,\n                                lapack_int nrhs,\n                                const lapack_complex_double* ab,\n                                lapack_int ldab, lapack_complex_double* b,\n                                lapack_int ldb );\n\nlapack_int LAPACKE_stfsm_work( int matrix_order, char transr, char side,\n                               char uplo, char trans, char diag, lapack_int m,\n                               lapack_int n, float alpha, const float* a,\n                               float* b, lapack_int ldb );\nlapack_int LAPACKE_dtfsm_work( int matrix_order, char transr, char side,\n                               char uplo, char trans, char diag, lapack_int m,\n                               lapack_int n, double alpha, const double* a,\n                               double* b, lapack_int ldb );\nlapack_int LAPACKE_ctfsm_work( int matrix_order, char transr, char side,\n                               char uplo, char trans, char diag, lapack_int m,\n                               lapack_int n, lapack_complex_float alpha,\n                               const lapack_complex_float* a,\n                               lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_ztfsm_work( int matrix_order, char transr, char side,\n                               char uplo, char trans, char diag, lapack_int m,\n                               lapack_int n, lapack_complex_double alpha,\n                               const lapack_complex_double* a,\n                               lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_stftri_work( int matrix_order, char transr, char uplo,\n                                char diag, lapack_int n, float* a );\nlapack_int LAPACKE_dtftri_work( int matrix_order, char transr, char uplo,\n                                char diag, lapack_int n, double* a );\nlapack_int LAPACKE_ctftri_work( int matrix_order, char transr, char uplo,\n                                char diag, lapack_int n,\n                                lapack_complex_float* a );\nlapack_int LAPACKE_ztftri_work( int matrix_order, char transr, char uplo,\n                                char diag, lapack_int n,\n                                lapack_complex_double* a );\n\nlapack_int LAPACKE_stfttp_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const float* arf, float* ap );\nlapack_int LAPACKE_dtfttp_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const double* arf, double* ap );\nlapack_int LAPACKE_ctfttp_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const lapack_complex_float* arf,\n                                lapack_complex_float* ap );\nlapack_int LAPACKE_ztfttp_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const lapack_complex_double* arf,\n                                lapack_complex_double* ap );\n\nlapack_int LAPACKE_stfttr_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const float* arf, float* a,\n                                lapack_int lda );\nlapack_int LAPACKE_dtfttr_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const double* arf, double* a,\n                                lapack_int lda );\nlapack_int LAPACKE_ctfttr_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const lapack_complex_float* arf,\n                                lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_ztfttr_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const lapack_complex_double* arf,\n                                lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_stgevc_work( int matrix_order, char side, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const float* s, lapack_int lds, const float* p,\n                                lapack_int ldp, float* vl, lapack_int ldvl,\n                                float* vr, lapack_int ldvr, lapack_int mm,\n                                lapack_int* m, float* work );\nlapack_int LAPACKE_dtgevc_work( int matrix_order, char side, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const double* s, lapack_int lds,\n                                const double* p, lapack_int ldp, double* vl,\n                                lapack_int ldvl, double* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m, double* work );\nlapack_int LAPACKE_ctgevc_work( int matrix_order, char side, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const lapack_complex_float* s, lapack_int lds,\n                                const lapack_complex_float* p, lapack_int ldp,\n                                lapack_complex_float* vl, lapack_int ldvl,\n                                lapack_complex_float* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_ztgevc_work( int matrix_order, char side, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const lapack_complex_double* s, lapack_int lds,\n                                const lapack_complex_double* p, lapack_int ldp,\n                                lapack_complex_double* vl, lapack_int ldvl,\n                                lapack_complex_double* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_stgexc_work( int matrix_order, lapack_logical wantq,\n                                lapack_logical wantz, lapack_int n, float* a,\n                                lapack_int lda, float* b, lapack_int ldb,\n                                float* q, lapack_int ldq, float* z,\n                                lapack_int ldz, lapack_int* ifst,\n                                lapack_int* ilst, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dtgexc_work( int matrix_order, lapack_logical wantq,\n                                lapack_logical wantz, lapack_int n, double* a,\n                                lapack_int lda, double* b, lapack_int ldb,\n                                double* q, lapack_int ldq, double* z,\n                                lapack_int ldz, lapack_int* ifst,\n                                lapack_int* ilst, double* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_ctgexc_work( int matrix_order, lapack_logical wantq,\n                                lapack_logical wantz, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* q, lapack_int ldq,\n                                lapack_complex_float* z, lapack_int ldz,\n                                lapack_int ifst, lapack_int ilst );\nlapack_int LAPACKE_ztgexc_work( int matrix_order, lapack_logical wantq,\n                                lapack_logical wantz, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* q, lapack_int ldq,\n                                lapack_complex_double* z, lapack_int ldz,\n                                lapack_int ifst, lapack_int ilst );\n\nlapack_int LAPACKE_stgsen_work( int matrix_order, lapack_int ijob,\n                                lapack_logical wantq, lapack_logical wantz,\n                                const lapack_logical* select, lapack_int n,\n                                float* a, lapack_int lda, float* b,\n                                lapack_int ldb, float* alphar, float* alphai,\n                                float* beta, float* q, lapack_int ldq, float* z,\n                                lapack_int ldz, lapack_int* m, float* pl,\n                                float* pr, float* dif, float* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_dtgsen_work( int matrix_order, lapack_int ijob,\n                                lapack_logical wantq, lapack_logical wantz,\n                                const lapack_logical* select, lapack_int n,\n                                double* a, lapack_int lda, double* b,\n                                lapack_int ldb, double* alphar, double* alphai,\n                                double* beta, double* q, lapack_int ldq,\n                                double* z, lapack_int ldz, lapack_int* m,\n                                double* pl, double* pr, double* dif,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_ctgsen_work( int matrix_order, lapack_int ijob,\n                                lapack_logical wantq, lapack_logical wantz,\n                                const lapack_logical* select, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* alpha,\n                                lapack_complex_float* beta,\n                                lapack_complex_float* q, lapack_int ldq,\n                                lapack_complex_float* z, lapack_int ldz,\n                                lapack_int* m, float* pl, float* pr, float* dif,\n                                lapack_complex_float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_ztgsen_work( int matrix_order, lapack_int ijob,\n                                lapack_logical wantq, lapack_logical wantz,\n                                const lapack_logical* select, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* alpha,\n                                lapack_complex_double* beta,\n                                lapack_complex_double* q, lapack_int ldq,\n                                lapack_complex_double* z, lapack_int ldz,\n                                lapack_int* m, double* pl, double* pr,\n                                double* dif, lapack_complex_double* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int liwork );\n\nlapack_int LAPACKE_stgsja_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int p,\n                                lapack_int n, lapack_int k, lapack_int l,\n                                float* a, lapack_int lda, float* b,\n                                lapack_int ldb, float tola, float tolb,\n                                float* alpha, float* beta, float* u,\n                                lapack_int ldu, float* v, lapack_int ldv,\n                                float* q, lapack_int ldq, float* work,\n                                lapack_int* ncycle );\nlapack_int LAPACKE_dtgsja_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int p,\n                                lapack_int n, lapack_int k, lapack_int l,\n                                double* a, lapack_int lda, double* b,\n                                lapack_int ldb, double tola, double tolb,\n                                double* alpha, double* beta, double* u,\n                                lapack_int ldu, double* v, lapack_int ldv,\n                                double* q, lapack_int ldq, double* work,\n                                lapack_int* ncycle );\nlapack_int LAPACKE_ctgsja_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int p,\n                                lapack_int n, lapack_int k, lapack_int l,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb,\n                                float tola, float tolb, float* alpha,\n                                float* beta, lapack_complex_float* u,\n                                lapack_int ldu, lapack_complex_float* v,\n                                lapack_int ldv, lapack_complex_float* q,\n                                lapack_int ldq, lapack_complex_float* work,\n                                lapack_int* ncycle );\nlapack_int LAPACKE_ztgsja_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int p,\n                                lapack_int n, lapack_int k, lapack_int l,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                double tola, double tolb, double* alpha,\n                                double* beta, lapack_complex_double* u,\n                                lapack_int ldu, lapack_complex_double* v,\n                                lapack_int ldv, lapack_complex_double* q,\n                                lapack_int ldq, lapack_complex_double* work,\n                                lapack_int* ncycle );\n\nlapack_int LAPACKE_stgsna_work( int matrix_order, char job, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const float* a, lapack_int lda, const float* b,\n                                lapack_int ldb, const float* vl,\n                                lapack_int ldvl, const float* vr,\n                                lapack_int ldvr, float* s, float* dif,\n                                lapack_int mm, lapack_int* m, float* work,\n                                lapack_int lwork, lapack_int* iwork );\nlapack_int LAPACKE_dtgsna_work( int matrix_order, char job, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const double* a, lapack_int lda,\n                                const double* b, lapack_int ldb,\n                                const double* vl, lapack_int ldvl,\n                                const double* vr, lapack_int ldvr, double* s,\n                                double* dif, lapack_int mm, lapack_int* m,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_ctgsna_work( int matrix_order, char job, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                const lapack_complex_float* vl, lapack_int ldvl,\n                                const lapack_complex_float* vr, lapack_int ldvr,\n                                float* s, float* dif, lapack_int mm,\n                                lapack_int* m, lapack_complex_float* work,\n                                lapack_int lwork, lapack_int* iwork );\nlapack_int LAPACKE_ztgsna_work( int matrix_order, char job, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                const lapack_complex_double* vl,\n                                lapack_int ldvl,\n                                const lapack_complex_double* vr,\n                                lapack_int ldvr, double* s, double* dif,\n                                lapack_int mm, lapack_int* m,\n                                lapack_complex_double* work, lapack_int lwork,\n                                lapack_int* iwork );\n\nlapack_int LAPACKE_stgsyl_work( int matrix_order, char trans, lapack_int ijob,\n                                lapack_int m, lapack_int n, const float* a,\n                                lapack_int lda, const float* b, lapack_int ldb,\n                                float* c, lapack_int ldc, const float* d,\n                                lapack_int ldd, const float* e, lapack_int lde,\n                                float* f, lapack_int ldf, float* scale,\n                                float* dif, float* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dtgsyl_work( int matrix_order, char trans, lapack_int ijob,\n                                lapack_int m, lapack_int n, const double* a,\n                                lapack_int lda, const double* b, lapack_int ldb,\n                                double* c, lapack_int ldc, const double* d,\n                                lapack_int ldd, const double* e, lapack_int lde,\n                                double* f, lapack_int ldf, double* scale,\n                                double* dif, double* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_ctgsyl_work( int matrix_order, char trans, lapack_int ijob,\n                                lapack_int m, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* c, lapack_int ldc,\n                                const lapack_complex_float* d, lapack_int ldd,\n                                const lapack_complex_float* e, lapack_int lde,\n                                lapack_complex_float* f, lapack_int ldf,\n                                float* scale, float* dif,\n                                lapack_complex_float* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_ztgsyl_work( int matrix_order, char trans, lapack_int ijob,\n                                lapack_int m, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* c, lapack_int ldc,\n                                const lapack_complex_double* d, lapack_int ldd,\n                                const lapack_complex_double* e, lapack_int lde,\n                                lapack_complex_double* f, lapack_int ldf,\n                                double* scale, double* dif,\n                                lapack_complex_double* work, lapack_int lwork,\n                                lapack_int* iwork );\n\nlapack_int LAPACKE_stpcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n, const float* ap,\n                                float* rcond, float* work, lapack_int* iwork );\nlapack_int LAPACKE_dtpcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n, const double* ap,\n                                double* rcond, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_ctpcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n,\n                                const lapack_complex_float* ap, float* rcond,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_ztpcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n,\n                                const lapack_complex_double* ap, double* rcond,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_stprfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const float* ap, const float* b, lapack_int ldb,\n                                const float* x, lapack_int ldx, float* ferr,\n                                float* berr, float* work, lapack_int* iwork );\nlapack_int LAPACKE_dtprfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const double* ap, const double* b,\n                                lapack_int ldb, const double* x, lapack_int ldx,\n                                double* ferr, double* berr, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_ctprfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const lapack_complex_float* ap,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                const lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_ztprfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const lapack_complex_double* ap,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                const lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_stptri_work( int matrix_order, char uplo, char diag,\n                                lapack_int n, float* ap );\nlapack_int LAPACKE_dtptri_work( int matrix_order, char uplo, char diag,\n                                lapack_int n, double* ap );\nlapack_int LAPACKE_ctptri_work( int matrix_order, char uplo, char diag,\n                                lapack_int n, lapack_complex_float* ap );\nlapack_int LAPACKE_ztptri_work( int matrix_order, char uplo, char diag,\n                                lapack_int n, lapack_complex_double* ap );\n\nlapack_int LAPACKE_stptrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const float* ap, float* b, lapack_int ldb );\nlapack_int LAPACKE_dtptrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const double* ap, double* b, lapack_int ldb );\nlapack_int LAPACKE_ctptrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const lapack_complex_float* ap,\n                                lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_ztptrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const lapack_complex_double* ap,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_stpttf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const float* ap, float* arf );\nlapack_int LAPACKE_dtpttf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const double* ap, double* arf );\nlapack_int LAPACKE_ctpttf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const lapack_complex_float* ap,\n                                lapack_complex_float* arf );\nlapack_int LAPACKE_ztpttf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const lapack_complex_double* ap,\n                                lapack_complex_double* arf );\n\nlapack_int LAPACKE_stpttr_work( int matrix_order, char uplo, lapack_int n,\n                                const float* ap, float* a, lapack_int lda );\nlapack_int LAPACKE_dtpttr_work( int matrix_order, char uplo, lapack_int n,\n                                const double* ap, double* a, lapack_int lda );\nlapack_int LAPACKE_ctpttr_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_float* ap,\n                                lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_ztpttr_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_double* ap,\n                                lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_strcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n, const float* a,\n                                lapack_int lda, float* rcond, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dtrcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n, const double* a,\n                                lapack_int lda, double* rcond, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_ctrcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                float* rcond, lapack_complex_float* work,\n                                float* rwork );\nlapack_int LAPACKE_ztrcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                double* rcond, lapack_complex_double* work,\n                                double* rwork );\n\nlapack_int LAPACKE_strevc_work( int matrix_order, char side, char howmny,\n                                lapack_logical* select, lapack_int n,\n                                const float* t, lapack_int ldt, float* vl,\n                                lapack_int ldvl, float* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m, float* work );\nlapack_int LAPACKE_dtrevc_work( int matrix_order, char side, char howmny,\n                                lapack_logical* select, lapack_int n,\n                                const double* t, lapack_int ldt, double* vl,\n                                lapack_int ldvl, double* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m, double* work );\nlapack_int LAPACKE_ctrevc_work( int matrix_order, char side, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                lapack_complex_float* t, lapack_int ldt,\n                                lapack_complex_float* vl, lapack_int ldvl,\n                                lapack_complex_float* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_ztrevc_work( int matrix_order, char side, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                lapack_complex_double* t, lapack_int ldt,\n                                lapack_complex_double* vl, lapack_int ldvl,\n                                lapack_complex_double* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_strexc_work( int matrix_order, char compq, lapack_int n,\n                                float* t, lapack_int ldt, float* q,\n                                lapack_int ldq, lapack_int* ifst,\n                                lapack_int* ilst, float* work );\nlapack_int LAPACKE_dtrexc_work( int matrix_order, char compq, lapack_int n,\n                                double* t, lapack_int ldt, double* q,\n                                lapack_int ldq, lapack_int* ifst,\n                                lapack_int* ilst, double* work );\nlapack_int LAPACKE_ctrexc_work( int matrix_order, char compq, lapack_int n,\n                                lapack_complex_float* t, lapack_int ldt,\n                                lapack_complex_float* q, lapack_int ldq,\n                                lapack_int ifst, lapack_int ilst );\nlapack_int LAPACKE_ztrexc_work( int matrix_order, char compq, lapack_int n,\n                                lapack_complex_double* t, lapack_int ldt,\n                                lapack_complex_double* q, lapack_int ldq,\n                                lapack_int ifst, lapack_int ilst );\n\nlapack_int LAPACKE_strrfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const float* a, lapack_int lda, const float* b,\n                                lapack_int ldb, const float* x, lapack_int ldx,\n                                float* ferr, float* berr, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dtrrfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const double* a, lapack_int lda,\n                                const double* b, lapack_int ldb,\n                                const double* x, lapack_int ldx, double* ferr,\n                                double* berr, double* work, lapack_int* iwork );\nlapack_int LAPACKE_ctrrfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                const lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_ztrrfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                const lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_strsen_work( int matrix_order, char job, char compq,\n                                const lapack_logical* select, lapack_int n,\n                                float* t, lapack_int ldt, float* q,\n                                lapack_int ldq, float* wr, float* wi,\n                                lapack_int* m, float* s, float* sep,\n                                float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_dtrsen_work( int matrix_order, char job, char compq,\n                                const lapack_logical* select, lapack_int n,\n                                double* t, lapack_int ldt, double* q,\n                                lapack_int ldq, double* wr, double* wi,\n                                lapack_int* m, double* s, double* sep,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_ctrsen_work( int matrix_order, char job, char compq,\n                                const lapack_logical* select, lapack_int n,\n                                lapack_complex_float* t, lapack_int ldt,\n                                lapack_complex_float* q, lapack_int ldq,\n                                lapack_complex_float* w, lapack_int* m,\n                                float* s, float* sep,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_ztrsen_work( int matrix_order, char job, char compq,\n                                const lapack_logical* select, lapack_int n,\n                                lapack_complex_double* t, lapack_int ldt,\n                                lapack_complex_double* q, lapack_int ldq,\n                                lapack_complex_double* w, lapack_int* m,\n                                double* s, double* sep,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_strsna_work( int matrix_order, char job, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const float* t, lapack_int ldt, const float* vl,\n                                lapack_int ldvl, const float* vr,\n                                lapack_int ldvr, float* s, float* sep,\n                                lapack_int mm, lapack_int* m, float* work,\n                                lapack_int ldwork, lapack_int* iwork );\nlapack_int LAPACKE_dtrsna_work( int matrix_order, char job, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const double* t, lapack_int ldt,\n                                const double* vl, lapack_int ldvl,\n                                const double* vr, lapack_int ldvr, double* s,\n                                double* sep, lapack_int mm, lapack_int* m,\n                                double* work, lapack_int ldwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_ctrsna_work( int matrix_order, char job, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const lapack_complex_float* t, lapack_int ldt,\n                                const lapack_complex_float* vl, lapack_int ldvl,\n                                const lapack_complex_float* vr, lapack_int ldvr,\n                                float* s, float* sep, lapack_int mm,\n                                lapack_int* m, lapack_complex_float* work,\n                                lapack_int ldwork, float* rwork );\nlapack_int LAPACKE_ztrsna_work( int matrix_order, char job, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const lapack_complex_double* t, lapack_int ldt,\n                                const lapack_complex_double* vl,\n                                lapack_int ldvl,\n                                const lapack_complex_double* vr,\n                                lapack_int ldvr, double* s, double* sep,\n                                lapack_int mm, lapack_int* m,\n                                lapack_complex_double* work, lapack_int ldwork,\n                                double* rwork );\n\nlapack_int LAPACKE_strsyl_work( int matrix_order, char trana, char tranb,\n                                lapack_int isgn, lapack_int m, lapack_int n,\n                                const float* a, lapack_int lda, const float* b,\n                                lapack_int ldb, float* c, lapack_int ldc,\n                                float* scale );\nlapack_int LAPACKE_dtrsyl_work( int matrix_order, char trana, char tranb,\n                                lapack_int isgn, lapack_int m, lapack_int n,\n                                const double* a, lapack_int lda,\n                                const double* b, lapack_int ldb, double* c,\n                                lapack_int ldc, double* scale );\nlapack_int LAPACKE_ctrsyl_work( int matrix_order, char trana, char tranb,\n                                lapack_int isgn, lapack_int m, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* c, lapack_int ldc,\n                                float* scale );\nlapack_int LAPACKE_ztrsyl_work( int matrix_order, char trana, char tranb,\n                                lapack_int isgn, lapack_int m, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* c, lapack_int ldc,\n                                double* scale );\n\nlapack_int LAPACKE_strtri_work( int matrix_order, char uplo, char diag,\n                                lapack_int n, float* a, lapack_int lda );\nlapack_int LAPACKE_dtrtri_work( int matrix_order, char uplo, char diag,\n                                lapack_int n, double* a, lapack_int lda );\nlapack_int LAPACKE_ctrtri_work( int matrix_order, char uplo, char diag,\n                                lapack_int n, lapack_complex_float* a,\n                                lapack_int lda );\nlapack_int LAPACKE_ztrtri_work( int matrix_order, char uplo, char diag,\n                                lapack_int n, lapack_complex_double* a,\n                                lapack_int lda );\n\nlapack_int LAPACKE_strtrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const float* a, lapack_int lda, float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_dtrtrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const double* a, lapack_int lda, double* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_ctrtrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_ztrtrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_strttf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const float* a, lapack_int lda,\n                                float* arf );\nlapack_int LAPACKE_dtrttf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const double* a, lapack_int lda,\n                                double* arf );\nlapack_int LAPACKE_ctrttf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* arf );\nlapack_int LAPACKE_ztrttf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* arf );\n\nlapack_int LAPACKE_strttp_work( int matrix_order, char uplo, lapack_int n,\n                                const float* a, lapack_int lda, float* ap );\nlapack_int LAPACKE_dtrttp_work( int matrix_order, char uplo, lapack_int n,\n                                const double* a, lapack_int lda, double* ap );\nlapack_int LAPACKE_ctrttp_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* ap );\nlapack_int LAPACKE_ztrttp_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* ap );\n\nlapack_int LAPACKE_stzrzf_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, float* tau,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dtzrzf_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, double* tau,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_ctzrzf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_ztzrzf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cungbr_work( int matrix_order, char vect, lapack_int m,\n                                lapack_int n, lapack_int k,\n                                lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zungbr_work( int matrix_order, char vect, lapack_int m,\n                                lapack_int n, lapack_int k,\n                                lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cunghr_work( int matrix_order, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zunghr_work( int matrix_order, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, lapack_complex_double* a,\n                                lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cunglq_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zunglq_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, lapack_complex_double* a,\n                                lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cungql_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zungql_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, lapack_complex_double* a,\n                                lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cungqr_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zungqr_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, lapack_complex_double* a,\n                                lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cungrq_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zungrq_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, lapack_complex_double* a,\n                                lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cungtr_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zungtr_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cunmbr_work( int matrix_order, char vect, char side,\n                                char trans, lapack_int m, lapack_int n,\n                                lapack_int k, const lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* tau,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zunmbr_work( int matrix_order, char vect, char side,\n                                char trans, lapack_int m, lapack_int n,\n                                lapack_int k, const lapack_complex_double* a,\n                                lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cunmhr_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, const lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* tau,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zunmhr_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, const lapack_complex_double* a,\n                                lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cunmlq_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* tau,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zunmlq_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cunmql_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* tau,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zunmql_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cunmqr_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* tau,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zunmqr_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cunmrq_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* tau,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zunmrq_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cunmrz_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                lapack_int l, const lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* tau,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zunmrz_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                lapack_int l, const lapack_complex_double* a,\n                                lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cunmtr_work( int matrix_order, char side, char uplo,\n                                char trans, lapack_int m, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* tau,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zunmtr_work( int matrix_order, char side, char uplo,\n                                char trans, lapack_int m, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cupgtr_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_float* ap,\n                                const lapack_complex_float* tau,\n                                lapack_complex_float* q, lapack_int ldq,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zupgtr_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_double* ap,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* q, lapack_int ldq,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_cupmtr_work( int matrix_order, char side, char uplo,\n                                char trans, lapack_int m, lapack_int n,\n                                const lapack_complex_float* ap,\n                                const lapack_complex_float* tau,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zupmtr_work( int matrix_order, char side, char uplo,\n                                char trans, lapack_int m, lapack_int n,\n                                const lapack_complex_double* ap,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_claghe( int matrix_order, lapack_int n, lapack_int k,\n                           const float* d, lapack_complex_float* a,\n                           lapack_int lda, lapack_int* iseed );\nlapack_int LAPACKE_zlaghe( int matrix_order, lapack_int n, lapack_int k,\n                           const double* d, lapack_complex_double* a,\n                           lapack_int lda, lapack_int* iseed );\n\nlapack_int LAPACKE_slagsy( int matrix_order, lapack_int n, lapack_int k,\n                           const float* d, float* a, lapack_int lda,\n                           lapack_int* iseed );\nlapack_int LAPACKE_dlagsy( int matrix_order, lapack_int n, lapack_int k,\n                           const double* d, double* a, lapack_int lda,\n                           lapack_int* iseed );\nlapack_int LAPACKE_clagsy( int matrix_order, lapack_int n, lapack_int k,\n                           const float* d, lapack_complex_float* a,\n                           lapack_int lda, lapack_int* iseed );\nlapack_int LAPACKE_zlagsy( int matrix_order, lapack_int n, lapack_int k,\n                           const double* d, lapack_complex_double* a,\n                           lapack_int lda, lapack_int* iseed );\n\nlapack_int LAPACKE_slapmr( int matrix_order, lapack_logical forwrd,\n                           lapack_int m, lapack_int n, float* x, lapack_int ldx,\n                           lapack_int* k );\nlapack_int LAPACKE_dlapmr( int matrix_order, lapack_logical forwrd,\n                           lapack_int m, lapack_int n, double* x,\n                           lapack_int ldx, lapack_int* k );\nlapack_int LAPACKE_clapmr( int matrix_order, lapack_logical forwrd,\n                           lapack_int m, lapack_int n, lapack_complex_float* x,\n                           lapack_int ldx, lapack_int* k );\nlapack_int LAPACKE_zlapmr( int matrix_order, lapack_logical forwrd,\n                           lapack_int m, lapack_int n, lapack_complex_double* x,\n                           lapack_int ldx, lapack_int* k );\n\n\nfloat LAPACKE_slapy2( float x, float y );\ndouble LAPACKE_dlapy2( double x, double y );\n\nfloat LAPACKE_slapy3( float x, float y, float z );\ndouble LAPACKE_dlapy3( double x, double y, double z );\n\nlapack_int LAPACKE_slartgp( float f, float g, float* cs, float* sn, float* r );\nlapack_int LAPACKE_dlartgp( double f, double g, double* cs, double* sn,\n                            double* r );\n\nlapack_int LAPACKE_slartgs( float x, float y, float sigma, float* cs,\n                            float* sn );\nlapack_int LAPACKE_dlartgs( double x, double y, double sigma, double* cs,\n                            double* sn );\n\n\n//LAPACK 3.3.0\nlapack_int LAPACKE_cbbcsd( int matrix_order, char jobu1, char jobu2,\n                           char jobv1t, char jobv2t, char trans, lapack_int m,\n                           lapack_int p, lapack_int q, float* theta, float* phi,\n                           lapack_complex_float* u1, lapack_int ldu1,\n                           lapack_complex_float* u2, lapack_int ldu2,\n                           lapack_complex_float* v1t, lapack_int ldv1t,\n                           lapack_complex_float* v2t, lapack_int ldv2t,\n                           float* b11d, float* b11e, float* b12d, float* b12e,\n                           float* b21d, float* b21e, float* b22d, float* b22e );\nlapack_int LAPACKE_cbbcsd_work( int matrix_order, char jobu1, char jobu2,\n                                char jobv1t, char jobv2t, char trans,\n                                lapack_int m, lapack_int p, lapack_int q,\n                                float* theta, float* phi,\n                                lapack_complex_float* u1, lapack_int ldu1,\n                                lapack_complex_float* u2, lapack_int ldu2,\n                                lapack_complex_float* v1t, lapack_int ldv1t,\n                                lapack_complex_float* v2t, lapack_int ldv2t,\n                                float* b11d, float* b11e, float* b12d,\n                                float* b12e, float* b21d, float* b21e,\n                                float* b22d, float* b22e, float* rwork,\n                                lapack_int lrwork );\nlapack_int LAPACKE_cheswapr( int matrix_order, char uplo, lapack_int n,\n                             lapack_complex_float* a, lapack_int i1,\n                             lapack_int i2 );\nlapack_int LAPACKE_cheswapr_work( int matrix_order, char uplo, lapack_int n,\n                                  lapack_complex_float* a, lapack_int i1,\n                                  lapack_int i2 );\nlapack_int LAPACKE_chetri2( int matrix_order, char uplo, lapack_int n,\n                            lapack_complex_float* a, lapack_int lda,\n                            const lapack_int* ipiv );\nlapack_int LAPACKE_chetri2_work( int matrix_order, char uplo, lapack_int n,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 const lapack_int* ipiv,\n                                 lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_chetri2x( int matrix_order, char uplo, lapack_int n,\n                             lapack_complex_float* a, lapack_int lda,\n                             const lapack_int* ipiv, lapack_int nb );\nlapack_int LAPACKE_chetri2x_work( int matrix_order, char uplo, lapack_int n,\n                                  lapack_complex_float* a, lapack_int lda,\n                                  const lapack_int* ipiv,\n                                  lapack_complex_float* work, lapack_int nb );\nlapack_int LAPACKE_chetrs2( int matrix_order, char uplo, lapack_int n,\n                            lapack_int nrhs, const lapack_complex_float* a,\n                            lapack_int lda, const lapack_int* ipiv,\n                            lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_chetrs2_work( int matrix_order, char uplo, lapack_int n,\n                                 lapack_int nrhs, const lapack_complex_float* a,\n                                 lapack_int lda, const lapack_int* ipiv,\n                                 lapack_complex_float* b, lapack_int ldb,\n                                 lapack_complex_float* work );\nlapack_int LAPACKE_csyconv( int matrix_order, char uplo, char way, lapack_int n,\n                            lapack_complex_float* a, lapack_int lda,\n                            const lapack_int* ipiv );\nlapack_int LAPACKE_csyconv_work( int matrix_order, char uplo, char way,\n                                 lapack_int n, lapack_complex_float* a,\n                                 lapack_int lda, const lapack_int* ipiv,\n                                 lapack_complex_float* work );\nlapack_int LAPACKE_csyswapr( int matrix_order, char uplo, lapack_int n,\n                             lapack_complex_float* a, lapack_int i1,\n                             lapack_int i2 );\nlapack_int LAPACKE_csyswapr_work( int matrix_order, char uplo, lapack_int n,\n                                  lapack_complex_float* a, lapack_int i1,\n                                  lapack_int i2 );\nlapack_int LAPACKE_csytri2( int matrix_order, char uplo, lapack_int n,\n                            lapack_complex_float* a, lapack_int lda,\n                            const lapack_int* ipiv );\nlapack_int LAPACKE_csytri2_work( int matrix_order, char uplo, lapack_int n,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 const lapack_int* ipiv,\n                                 lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_csytri2x( int matrix_order, char uplo, lapack_int n,\n                             lapack_complex_float* a, lapack_int lda,\n                             const lapack_int* ipiv, lapack_int nb );\nlapack_int LAPACKE_csytri2x_work( int matrix_order, char uplo, lapack_int n,\n                                  lapack_complex_float* a, lapack_int lda,\n                                  const lapack_int* ipiv,\n                                  lapack_complex_float* work, lapack_int nb );\nlapack_int LAPACKE_csytrs2( int matrix_order, char uplo, lapack_int n,\n                            lapack_int nrhs, const lapack_complex_float* a,\n                            lapack_int lda, const lapack_int* ipiv,\n                            lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_csytrs2_work( int matrix_order, char uplo, lapack_int n,\n                                 lapack_int nrhs, const lapack_complex_float* a,\n                                 lapack_int lda, const lapack_int* ipiv,\n                                 lapack_complex_float* b, lapack_int ldb,\n                                 lapack_complex_float* work );\nlapack_int LAPACKE_cunbdb( int matrix_order, char trans, char signs,\n                           lapack_int m, lapack_int p, lapack_int q,\n                           lapack_complex_float* x11, lapack_int ldx11,\n                           lapack_complex_float* x12, lapack_int ldx12,\n                           lapack_complex_float* x21, lapack_int ldx21,\n                           lapack_complex_float* x22, lapack_int ldx22,\n                           float* theta, float* phi,\n                           lapack_complex_float* taup1,\n                           lapack_complex_float* taup2,\n                           lapack_complex_float* tauq1,\n                           lapack_complex_float* tauq2 );\nlapack_int LAPACKE_cunbdb_work( int matrix_order, char trans, char signs,\n                                lapack_int m, lapack_int p, lapack_int q,\n                                lapack_complex_float* x11, lapack_int ldx11,\n                                lapack_complex_float* x12, lapack_int ldx12,\n                                lapack_complex_float* x21, lapack_int ldx21,\n                                lapack_complex_float* x22, lapack_int ldx22,\n                                float* theta, float* phi,\n                                lapack_complex_float* taup1,\n                                lapack_complex_float* taup2,\n                                lapack_complex_float* tauq1,\n                                lapack_complex_float* tauq2,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_cuncsd( int matrix_order, char jobu1, char jobu2,\n                           char jobv1t, char jobv2t, char trans, char signs,\n                           lapack_int m, lapack_int p, lapack_int q,\n                           lapack_complex_float* x11, lapack_int ldx11,\n                           lapack_complex_float* x12, lapack_int ldx12,\n                           lapack_complex_float* x21, lapack_int ldx21,\n                           lapack_complex_float* x22, lapack_int ldx22,\n                           float* theta, lapack_complex_float* u1,\n                           lapack_int ldu1, lapack_complex_float* u2,\n                           lapack_int ldu2, lapack_complex_float* v1t,\n                           lapack_int ldv1t, lapack_complex_float* v2t,\n                           lapack_int ldv2t );\nlapack_int LAPACKE_cuncsd_work( int matrix_order, char jobu1, char jobu2,\n                                char jobv1t, char jobv2t, char trans,\n                                char signs, lapack_int m, lapack_int p,\n                                lapack_int q, lapack_complex_float* x11,\n                                lapack_int ldx11, lapack_complex_float* x12,\n                                lapack_int ldx12, lapack_complex_float* x21,\n                                lapack_int ldx21, lapack_complex_float* x22,\n                                lapack_int ldx22, float* theta,\n                                lapack_complex_float* u1, lapack_int ldu1,\n                                lapack_complex_float* u2, lapack_int ldu2,\n                                lapack_complex_float* v1t, lapack_int ldv1t,\n                                lapack_complex_float* v2t, lapack_int ldv2t,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork, lapack_int lrwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dbbcsd( int matrix_order, char jobu1, char jobu2,\n                           char jobv1t, char jobv2t, char trans, lapack_int m,\n                           lapack_int p, lapack_int q, double* theta,\n                           double* phi, double* u1, lapack_int ldu1, double* u2,\n                           lapack_int ldu2, double* v1t, lapack_int ldv1t,\n                           double* v2t, lapack_int ldv2t, double* b11d,\n                           double* b11e, double* b12d, double* b12e,\n                           double* b21d, double* b21e, double* b22d,\n                           double* b22e );\nlapack_int LAPACKE_dbbcsd_work( int matrix_order, char jobu1, char jobu2,\n                                char jobv1t, char jobv2t, char trans,\n                                lapack_int m, lapack_int p, lapack_int q,\n                                double* theta, double* phi, double* u1,\n                                lapack_int ldu1, double* u2, lapack_int ldu2,\n                                double* v1t, lapack_int ldv1t, double* v2t,\n                                lapack_int ldv2t, double* b11d, double* b11e,\n                                double* b12d, double* b12e, double* b21d,\n                                double* b21e, double* b22d, double* b22e,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_dorbdb( int matrix_order, char trans, char signs,\n                           lapack_int m, lapack_int p, lapack_int q,\n                           double* x11, lapack_int ldx11, double* x12,\n                           lapack_int ldx12, double* x21, lapack_int ldx21,\n                           double* x22, lapack_int ldx22, double* theta,\n                           double* phi, double* taup1, double* taup2,\n                           double* tauq1, double* tauq2 );\nlapack_int LAPACKE_dorbdb_work( int matrix_order, char trans, char signs,\n                                lapack_int m, lapack_int p, lapack_int q,\n                                double* x11, lapack_int ldx11, double* x12,\n                                lapack_int ldx12, double* x21, lapack_int ldx21,\n                                double* x22, lapack_int ldx22, double* theta,\n                                double* phi, double* taup1, double* taup2,\n                                double* tauq1, double* tauq2, double* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dorcsd( int matrix_order, char jobu1, char jobu2,\n                           char jobv1t, char jobv2t, char trans, char signs,\n                           lapack_int m, lapack_int p, lapack_int q,\n                           double* x11, lapack_int ldx11, double* x12,\n                           lapack_int ldx12, double* x21, lapack_int ldx21,\n                           double* x22, lapack_int ldx22, double* theta,\n                           double* u1, lapack_int ldu1, double* u2,\n                           lapack_int ldu2, double* v1t, lapack_int ldv1t,\n                           double* v2t, lapack_int ldv2t );\nlapack_int LAPACKE_dorcsd_work( int matrix_order, char jobu1, char jobu2,\n                                char jobv1t, char jobv2t, char trans,\n                                char signs, lapack_int m, lapack_int p,\n                                lapack_int q, double* x11, lapack_int ldx11,\n                                double* x12, lapack_int ldx12, double* x21,\n                                lapack_int ldx21, double* x22, lapack_int ldx22,\n                                double* theta, double* u1, lapack_int ldu1,\n                                double* u2, lapack_int ldu2, double* v1t,\n                                lapack_int ldv1t, double* v2t, lapack_int ldv2t,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dsyconv( int matrix_order, char uplo, char way, lapack_int n,\n                            double* a, lapack_int lda, const lapack_int* ipiv );\nlapack_int LAPACKE_dsyconv_work( int matrix_order, char uplo, char way,\n                                 lapack_int n, double* a, lapack_int lda,\n                                 const lapack_int* ipiv, double* work );\nlapack_int LAPACKE_dsyswapr( int matrix_order, char uplo, lapack_int n,\n                             double* a, lapack_int i1, lapack_int i2 );\nlapack_int LAPACKE_dsyswapr_work( int matrix_order, char uplo, lapack_int n,\n                                  double* a, lapack_int i1, lapack_int i2 );\nlapack_int LAPACKE_dsytri2( int matrix_order, char uplo, lapack_int n,\n                            double* a, lapack_int lda, const lapack_int* ipiv );\nlapack_int LAPACKE_dsytri2_work( int matrix_order, char uplo, lapack_int n,\n                                 double* a, lapack_int lda,\n                                 const lapack_int* ipiv,\n                                 lapack_complex_double* work, lapack_int lwork );\nlapack_int LAPACKE_dsytri2x( int matrix_order, char uplo, lapack_int n,\n                             double* a, lapack_int lda, const lapack_int* ipiv,\n                             lapack_int nb );\nlapack_int LAPACKE_dsytri2x_work( int matrix_order, char uplo, lapack_int n,\n                                  double* a, lapack_int lda,\n                                  const lapack_int* ipiv, double* work,\n                                  lapack_int nb );\nlapack_int LAPACKE_dsytrs2( int matrix_order, char uplo, lapack_int n,\n                            lapack_int nrhs, const double* a, lapack_int lda,\n                            const lapack_int* ipiv, double* b, lapack_int ldb );\nlapack_int LAPACKE_dsytrs2_work( int matrix_order, char uplo, lapack_int n,\n                                 lapack_int nrhs, const double* a,\n                                 lapack_int lda, const lapack_int* ipiv,\n                                 double* b, lapack_int ldb, double* work );\nlapack_int LAPACKE_sbbcsd( int matrix_order, char jobu1, char jobu2,\n                           char jobv1t, char jobv2t, char trans, lapack_int m,\n                           lapack_int p, lapack_int q, float* theta, float* phi,\n                           float* u1, lapack_int ldu1, float* u2,\n                           lapack_int ldu2, float* v1t, lapack_int ldv1t,\n                           float* v2t, lapack_int ldv2t, float* b11d,\n                           float* b11e, float* b12d, float* b12e, float* b21d,\n                           float* b21e, float* b22d, float* b22e );\nlapack_int LAPACKE_sbbcsd_work( int matrix_order, char jobu1, char jobu2,\n                                char jobv1t, char jobv2t, char trans,\n                                lapack_int m, lapack_int p, lapack_int q,\n                                float* theta, float* phi, float* u1,\n                                lapack_int ldu1, float* u2, lapack_int ldu2,\n                                float* v1t, lapack_int ldv1t, float* v2t,\n                                lapack_int ldv2t, float* b11d, float* b11e,\n                                float* b12d, float* b12e, float* b21d,\n                                float* b21e, float* b22d, float* b22e,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_sorbdb( int matrix_order, char trans, char signs,\n                           lapack_int m, lapack_int p, lapack_int q, float* x11,\n                           lapack_int ldx11, float* x12, lapack_int ldx12,\n                           float* x21, lapack_int ldx21, float* x22,\n                           lapack_int ldx22, float* theta, float* phi,\n                           float* taup1, float* taup2, float* tauq1,\n                           float* tauq2 );\nlapack_int LAPACKE_sorbdb_work( int matrix_order, char trans, char signs,\n                                lapack_int m, lapack_int p, lapack_int q,\n                                float* x11, lapack_int ldx11, float* x12,\n                                lapack_int ldx12, float* x21, lapack_int ldx21,\n                                float* x22, lapack_int ldx22, float* theta,\n                                float* phi, float* taup1, float* taup2,\n                                float* tauq1, float* tauq2, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_sorcsd( int matrix_order, char jobu1, char jobu2,\n                           char jobv1t, char jobv2t, char trans, char signs,\n                           lapack_int m, lapack_int p, lapack_int q, float* x11,\n                           lapack_int ldx11, float* x12, lapack_int ldx12,\n                           float* x21, lapack_int ldx21, float* x22,\n                           lapack_int ldx22, float* theta, float* u1,\n                           lapack_int ldu1, float* u2, lapack_int ldu2,\n                           float* v1t, lapack_int ldv1t, float* v2t,\n                           lapack_int ldv2t );\nlapack_int LAPACKE_sorcsd_work( int matrix_order, char jobu1, char jobu2,\n                                char jobv1t, char jobv2t, char trans,\n                                char signs, lapack_int m, lapack_int p,\n                                lapack_int q, float* x11, lapack_int ldx11,\n                                float* x12, lapack_int ldx12, float* x21,\n                                lapack_int ldx21, float* x22, lapack_int ldx22,\n                                float* theta, float* u1, lapack_int ldu1,\n                                float* u2, lapack_int ldu2, float* v1t,\n                                lapack_int ldv1t, float* v2t, lapack_int ldv2t,\n                                float* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_ssyconv( int matrix_order, char uplo, char way, lapack_int n,\n                            float* a, lapack_int lda, const lapack_int* ipiv );\nlapack_int LAPACKE_ssyconv_work( int matrix_order, char uplo, char way,\n                                 lapack_int n, float* a, lapack_int lda,\n                                 const lapack_int* ipiv, float* work );\nlapack_int LAPACKE_ssyswapr( int matrix_order, char uplo, lapack_int n,\n                             float* a, lapack_int i1, lapack_int i2 );\nlapack_int LAPACKE_ssyswapr_work( int matrix_order, char uplo, lapack_int n,\n                                  float* a, lapack_int i1, lapack_int i2 );\nlapack_int LAPACKE_ssytri2( int matrix_order, char uplo, lapack_int n, float* a,\n                            lapack_int lda, const lapack_int* ipiv );\nlapack_int LAPACKE_ssytri2_work( int matrix_order, char uplo, lapack_int n,\n                                 float* a, lapack_int lda,\n                                 const lapack_int* ipiv,\n                                 lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_ssytri2x( int matrix_order, char uplo, lapack_int n,\n                             float* a, lapack_int lda, const lapack_int* ipiv,\n                             lapack_int nb );\nlapack_int LAPACKE_ssytri2x_work( int matrix_order, char uplo, lapack_int n,\n                                  float* a, lapack_int lda,\n                                  const lapack_int* ipiv, float* work,\n                                  lapack_int nb );\nlapack_int LAPACKE_ssytrs2( int matrix_order, char uplo, lapack_int n,\n                            lapack_int nrhs, const float* a, lapack_int lda,\n                            const lapack_int* ipiv, float* b, lapack_int ldb );\nlapack_int LAPACKE_ssytrs2_work( int matrix_order, char uplo, lapack_int n,\n                                 lapack_int nrhs, const float* a,\n                                 lapack_int lda, const lapack_int* ipiv,\n                                 float* b, lapack_int ldb, float* work );\nlapack_int LAPACKE_zbbcsd( int matrix_order, char jobu1, char jobu2,\n                           char jobv1t, char jobv2t, char trans, lapack_int m,\n                           lapack_int p, lapack_int q, double* theta,\n                           double* phi, lapack_complex_double* u1,\n                           lapack_int ldu1, lapack_complex_double* u2,\n                           lapack_int ldu2, lapack_complex_double* v1t,\n                           lapack_int ldv1t, lapack_complex_double* v2t,\n                           lapack_int ldv2t, double* b11d, double* b11e,\n                           double* b12d, double* b12e, double* b21d,\n                           double* b21e, double* b22d, double* b22e );\nlapack_int LAPACKE_zbbcsd_work( int matrix_order, char jobu1, char jobu2,\n                                char jobv1t, char jobv2t, char trans,\n                                lapack_int m, lapack_int p, lapack_int q,\n                                double* theta, double* phi,\n                                lapack_complex_double* u1, lapack_int ldu1,\n                                lapack_complex_double* u2, lapack_int ldu2,\n                                lapack_complex_double* v1t, lapack_int ldv1t,\n                                lapack_complex_double* v2t, lapack_int ldv2t,\n                                double* b11d, double* b11e, double* b12d,\n                                double* b12e, double* b21d, double* b21e,\n                                double* b22d, double* b22e, double* rwork,\n                                lapack_int lrwork );\nlapack_int LAPACKE_zheswapr( int matrix_order, char uplo, lapack_int n,\n                             lapack_complex_double* a, lapack_int i1,\n                             lapack_int i2 );\nlapack_int LAPACKE_zheswapr_work( int matrix_order, char uplo, lapack_int n,\n                                  lapack_complex_double* a, lapack_int i1,\n                                  lapack_int i2 );\nlapack_int LAPACKE_zhetri2( int matrix_order, char uplo, lapack_int n,\n                            lapack_complex_double* a, lapack_int lda,\n                            const lapack_int* ipiv );\nlapack_int LAPACKE_zhetri2_work( int matrix_order, char uplo, lapack_int n,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 const lapack_int* ipiv,\n                                 lapack_complex_double* work, lapack_int lwork );\nlapack_int LAPACKE_zhetri2x( int matrix_order, char uplo, lapack_int n,\n                             lapack_complex_double* a, lapack_int lda,\n                             const lapack_int* ipiv, lapack_int nb );\nlapack_int LAPACKE_zhetri2x_work( int matrix_order, char uplo, lapack_int n,\n                                  lapack_complex_double* a, lapack_int lda,\n                                  const lapack_int* ipiv,\n                                  lapack_complex_double* work, lapack_int nb );\nlapack_int LAPACKE_zhetrs2( int matrix_order, char uplo, lapack_int n,\n                            lapack_int nrhs, const lapack_complex_double* a,\n                            lapack_int lda, const lapack_int* ipiv,\n                            lapack_complex_double* b, lapack_int ldb );\nlapack_int LAPACKE_zhetrs2_work( int matrix_order, char uplo, lapack_int n,\n                                 lapack_int nrhs, const lapack_complex_double* a,\n                                 lapack_int lda, const lapack_int* ipiv,\n                                 lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* work );\nlapack_int LAPACKE_zsyconv( int matrix_order, char uplo, char way, lapack_int n,\n                            lapack_complex_double* a, lapack_int lda,\n                            const lapack_int* ipiv );\nlapack_int LAPACKE_zsyconv_work( int matrix_order, char uplo, char way,\n                                 lapack_int n, lapack_complex_double* a,\n                                 lapack_int lda, const lapack_int* ipiv,\n                                 lapack_complex_double* work );\nlapack_int LAPACKE_zsyswapr( int matrix_order, char uplo, lapack_int n,\n                             lapack_complex_double* a, lapack_int i1,\n                             lapack_int i2 );\nlapack_int LAPACKE_zsyswapr_work( int matrix_order, char uplo, lapack_int n,\n                                  lapack_complex_double* a, lapack_int i1,\n                                  lapack_int i2 );\nlapack_int LAPACKE_zsytri2( int matrix_order, char uplo, lapack_int n,\n                            lapack_complex_double* a, lapack_int lda,\n                            const lapack_int* ipiv );\nlapack_int LAPACKE_zsytri2_work( int matrix_order, char uplo, lapack_int n,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 const lapack_int* ipiv,\n                                 lapack_complex_double* work, lapack_int lwork );\nlapack_int LAPACKE_zsytri2x( int matrix_order, char uplo, lapack_int n,\n                             lapack_complex_double* a, lapack_int lda,\n                             const lapack_int* ipiv, lapack_int nb );\nlapack_int LAPACKE_zsytri2x_work( int matrix_order, char uplo, lapack_int n,\n                                  lapack_complex_double* a, lapack_int lda,\n                                  const lapack_int* ipiv,\n                                  lapack_complex_double* work, lapack_int nb );\nlapack_int LAPACKE_zsytrs2( int matrix_order, char uplo, lapack_int n,\n                            lapack_int nrhs, const lapack_complex_double* a,\n                            lapack_int lda, const lapack_int* ipiv,\n                            lapack_complex_double* b, lapack_int ldb );\nlapack_int LAPACKE_zsytrs2_work( int matrix_order, char uplo, lapack_int n,\n                                 lapack_int nrhs, const lapack_complex_double* a,\n                                 lapack_int lda, const lapack_int* ipiv,\n                                 lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* work );\nlapack_int LAPACKE_zunbdb( int matrix_order, char trans, char signs,\n                           lapack_int m, lapack_int p, lapack_int q,\n                           lapack_complex_double* x11, lapack_int ldx11,\n                           lapack_complex_double* x12, lapack_int ldx12,\n                           lapack_complex_double* x21, lapack_int ldx21,\n                           lapack_complex_double* x22, lapack_int ldx22,\n                           double* theta, double* phi,\n                           lapack_complex_double* taup1,\n                           lapack_complex_double* taup2,\n                           lapack_complex_double* tauq1,\n                           lapack_complex_double* tauq2 );\nlapack_int LAPACKE_zunbdb_work( int matrix_order, char trans, char signs,\n                                lapack_int m, lapack_int p, lapack_int q,\n                                lapack_complex_double* x11, lapack_int ldx11,\n                                lapack_complex_double* x12, lapack_int ldx12,\n                                lapack_complex_double* x21, lapack_int ldx21,\n                                lapack_complex_double* x22, lapack_int ldx22,\n                                double* theta, double* phi,\n                                lapack_complex_double* taup1,\n                                lapack_complex_double* taup2,\n                                lapack_complex_double* tauq1,\n                                lapack_complex_double* tauq2,\n                                lapack_complex_double* work, lapack_int lwork );\nlapack_int LAPACKE_zuncsd( int matrix_order, char jobu1, char jobu2,\n                           char jobv1t, char jobv2t, char trans, char signs,\n                           lapack_int m, lapack_int p, lapack_int q,\n                           lapack_complex_double* x11, lapack_int ldx11,\n                           lapack_complex_double* x12, lapack_int ldx12,\n                           lapack_complex_double* x21, lapack_int ldx21,\n                           lapack_complex_double* x22, lapack_int ldx22,\n                           double* theta, lapack_complex_double* u1,\n                           lapack_int ldu1, lapack_complex_double* u2,\n                           lapack_int ldu2, lapack_complex_double* v1t,\n                           lapack_int ldv1t, lapack_complex_double* v2t,\n                           lapack_int ldv2t );\nlapack_int LAPACKE_zuncsd_work( int matrix_order, char jobu1, char jobu2,\n                                char jobv1t, char jobv2t, char trans,\n                                char signs, lapack_int m, lapack_int p,\n                                lapack_int q, lapack_complex_double* x11,\n                                lapack_int ldx11, lapack_complex_double* x12,\n                                lapack_int ldx12, lapack_complex_double* x21,\n                                lapack_int ldx21, lapack_complex_double* x22,\n                                lapack_int ldx22, double* theta,\n                                lapack_complex_double* u1, lapack_int ldu1,\n                                lapack_complex_double* u2, lapack_int ldu2,\n                                lapack_complex_double* v1t, lapack_int ldv1t,\n                                lapack_complex_double* v2t, lapack_int ldv2t,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork, lapack_int lrwork,\n                                lapack_int* iwork );\n//LAPACK 3.4.0\nlapack_int LAPACKE_sgemqrt( int matrix_order, char side, char trans,\n                            lapack_int m, lapack_int n, lapack_int k,\n                            lapack_int nb, const float* v, lapack_int ldv,\n                            const float* t, lapack_int ldt, float* c,\n                            lapack_int ldc );\nlapack_int LAPACKE_dgemqrt( int matrix_order, char side, char trans,\n                            lapack_int m, lapack_int n, lapack_int k,\n                            lapack_int nb, const double* v, lapack_int ldv,\n                            const double* t, lapack_int ldt, double* c,\n                            lapack_int ldc );\nlapack_int LAPACKE_cgemqrt( int matrix_order, char side, char trans,\n                            lapack_int m, lapack_int n, lapack_int k,\n                            lapack_int nb, const lapack_complex_float* v,\n                            lapack_int ldv, const lapack_complex_float* t,\n                            lapack_int ldt, lapack_complex_float* c,\n                            lapack_int ldc );\nlapack_int LAPACKE_zgemqrt( int matrix_order, char side, char trans,\n                            lapack_int m, lapack_int n, lapack_int k,\n                            lapack_int nb, const lapack_complex_double* v,\n                            lapack_int ldv, const lapack_complex_double* t,\n                            lapack_int ldt, lapack_complex_double* c,\n                            lapack_int ldc );\n\nlapack_int LAPACKE_sgeqrt( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nb, float* a, lapack_int lda, float* t,\n                           lapack_int ldt );\nlapack_int LAPACKE_dgeqrt( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nb, double* a, lapack_int lda, double* t,\n                           lapack_int ldt );\nlapack_int LAPACKE_cgeqrt( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nb, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* t,\n                           lapack_int ldt );\nlapack_int LAPACKE_zgeqrt( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nb, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* t,\n                           lapack_int ldt );\n\nlapack_int LAPACKE_sgeqrt2( int matrix_order, lapack_int m, lapack_int n,\n                            float* a, lapack_int lda, float* t,\n                            lapack_int ldt );\nlapack_int LAPACKE_dgeqrt2( int matrix_order, lapack_int m, lapack_int n,\n                            double* a, lapack_int lda, double* t,\n                            lapack_int ldt );\nlapack_int LAPACKE_cgeqrt2( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_complex_float* a, lapack_int lda,\n                            lapack_complex_float* t, lapack_int ldt );\nlapack_int LAPACKE_zgeqrt2( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_complex_double* a, lapack_int lda,\n                            lapack_complex_double* t, lapack_int ldt );\n\nlapack_int LAPACKE_sgeqrt3( int matrix_order, lapack_int m, lapack_int n,\n                            float* a, lapack_int lda, float* t,\n                            lapack_int ldt );\nlapack_int LAPACKE_dgeqrt3( int matrix_order, lapack_int m, lapack_int n,\n                            double* a, lapack_int lda, double* t,\n                            lapack_int ldt );\nlapack_int LAPACKE_cgeqrt3( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_complex_float* a, lapack_int lda,\n                            lapack_complex_float* t, lapack_int ldt );\nlapack_int LAPACKE_zgeqrt3( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_complex_double* a, lapack_int lda,\n                            lapack_complex_double* t, lapack_int ldt );\n\nlapack_int LAPACKE_stpmqrt( int matrix_order, char side, char trans,\n                            lapack_int m, lapack_int n, lapack_int k,\n                            lapack_int l, lapack_int nb, const float* v,\n                            lapack_int ldv, const float* t, lapack_int ldt,\n                            float* a, lapack_int lda, float* b,\n                            lapack_int ldb );\nlapack_int LAPACKE_dtpmqrt( int matrix_order, char side, char trans,\n                            lapack_int m, lapack_int n, lapack_int k,\n                            lapack_int l, lapack_int nb, const double* v,\n                            lapack_int ldv, const double* t, lapack_int ldt,\n                            double* a, lapack_int lda, double* b,\n                            lapack_int ldb );\nlapack_int LAPACKE_ctpmqrt( int matrix_order, char side, char trans,\n                            lapack_int m, lapack_int n, lapack_int k,\n                            lapack_int l, lapack_int nb,\n                            const lapack_complex_float* v, lapack_int ldv,\n                            const lapack_complex_float* t, lapack_int ldt,\n                            lapack_complex_float* a, lapack_int lda,\n                            lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_ztpmqrt( int matrix_order, char side, char trans,\n                            lapack_int m, lapack_int n, lapack_int k,\n                            lapack_int l, lapack_int nb,\n                            const lapack_complex_double* v, lapack_int ldv,\n                            const lapack_complex_double* t, lapack_int ldt,\n                            lapack_complex_double* a, lapack_int lda,\n                            lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_dtpqrt( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int l, lapack_int nb, double* a,\n                           lapack_int lda, double* b, lapack_int ldb, double* t,\n                           lapack_int ldt );\nlapack_int LAPACKE_ctpqrt( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int l, lapack_int nb, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* t,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_int ldt );\nlapack_int LAPACKE_ztpqrt( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int l, lapack_int nb,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* t, lapack_int ldt );\n\nlapack_int LAPACKE_stpqrt2( int matrix_order, lapack_int m, lapack_int n,\n                            float* a, lapack_int lda, float* b, lapack_int ldb,\n                            float* t, lapack_int ldt );\nlapack_int LAPACKE_dtpqrt2( int matrix_order, lapack_int m, lapack_int n,\n                            double* a, lapack_int lda, double* b,\n                            lapack_int ldb, double* t, lapack_int ldt );\nlapack_int LAPACKE_ctpqrt2( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_complex_float* a, lapack_int lda,\n                            lapack_complex_float* b, lapack_int ldb,\n                            lapack_complex_float* t, lapack_int ldt );\nlapack_int LAPACKE_ztpqrt2( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_complex_double* a, lapack_int lda,\n                            lapack_complex_double* b, lapack_int ldb,\n                            lapack_complex_double* t, lapack_int ldt );\n\nlapack_int LAPACKE_stprfb( int matrix_order, char side, char trans, char direct,\n                           char storev, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_int l, const float* v,\n                           lapack_int ldv, const float* t, lapack_int ldt,\n                           float* a, lapack_int lda, float* b, lapack_int ldb,\n                           lapack_int myldwork );\nlapack_int LAPACKE_dtprfb( int matrix_order, char side, char trans, char direct,\n                           char storev, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_int l, const double* v,\n                           lapack_int ldv, const double* t, lapack_int ldt,\n                           double* a, lapack_int lda, double* b, lapack_int ldb,\n                           lapack_int myldwork );\nlapack_int LAPACKE_ctprfb( int matrix_order, char side, char trans, char direct,\n                           char storev, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_int l,\n                           const lapack_complex_float* v, lapack_int ldv,\n                           const lapack_complex_float* t, lapack_int ldt,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_int myldwork );\nlapack_int LAPACKE_ztprfb( int matrix_order, char side, char trans, char direct,\n                           char storev, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_int l,\n                           const lapack_complex_double* v, lapack_int ldv,\n                           const lapack_complex_double* t, lapack_int ldt,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_int myldwork );\n\nlapack_int LAPACKE_sgemqrt_work( int matrix_order, char side, char trans,\n                                 lapack_int m, lapack_int n, lapack_int k,\n                                 lapack_int nb, const float* v, lapack_int ldv,\n                                 const float* t, lapack_int ldt, float* c,\n                                 lapack_int ldc, float* work );\nlapack_int LAPACKE_dgemqrt_work( int matrix_order, char side, char trans,\n                                 lapack_int m, lapack_int n, lapack_int k,\n                                 lapack_int nb, const double* v, lapack_int ldv,\n                                 const double* t, lapack_int ldt, double* c,\n                                 lapack_int ldc, double* work );\nlapack_int LAPACKE_cgemqrt_work( int matrix_order, char side, char trans,\n                                 lapack_int m, lapack_int n, lapack_int k,\n                                 lapack_int nb, const lapack_complex_float* v,\n                                 lapack_int ldv, const lapack_complex_float* t,\n                                 lapack_int ldt, lapack_complex_float* c,\n                                 lapack_int ldc, lapack_complex_float* work );\nlapack_int LAPACKE_zgemqrt_work( int matrix_order, char side, char trans,\n                                 lapack_int m, lapack_int n, lapack_int k,\n                                 lapack_int nb, const lapack_complex_double* v,\n                                 lapack_int ldv, const lapack_complex_double* t,\n                                 lapack_int ldt, lapack_complex_double* c,\n                                 lapack_int ldc, lapack_complex_double* work );\n\nlapack_int LAPACKE_sgeqrt_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nb, float* a, lapack_int lda,\n                                float* t, lapack_int ldt, float* work );\nlapack_int LAPACKE_dgeqrt_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nb, double* a, lapack_int lda,\n                                double* t, lapack_int ldt, double* work );\nlapack_int LAPACKE_cgeqrt_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nb, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* t,\n                                lapack_int ldt, lapack_complex_float* work );\nlapack_int LAPACKE_zgeqrt_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nb, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* t,\n                                lapack_int ldt, lapack_complex_double* work );\n\nlapack_int LAPACKE_sgeqrt2_work( int matrix_order, lapack_int m, lapack_int n,\n                                 float* a, lapack_int lda, float* t,\n                                 lapack_int ldt );\nlapack_int LAPACKE_dgeqrt2_work( int matrix_order, lapack_int m, lapack_int n,\n                                 double* a, lapack_int lda, double* t,\n                                 lapack_int ldt );\nlapack_int LAPACKE_cgeqrt2_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 lapack_complex_float* t, lapack_int ldt );\nlapack_int LAPACKE_zgeqrt2_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 lapack_complex_double* t, lapack_int ldt );\n\nlapack_int LAPACKE_sgeqrt3_work( int matrix_order, lapack_int m, lapack_int n,\n                                 float* a, lapack_int lda, float* t,\n                                 lapack_int ldt );\nlapack_int LAPACKE_dgeqrt3_work( int matrix_order, lapack_int m, lapack_int n,\n                                 double* a, lapack_int lda, double* t,\n                                 lapack_int ldt );\nlapack_int LAPACKE_cgeqrt3_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 lapack_complex_float* t, lapack_int ldt );\nlapack_int LAPACKE_zgeqrt3_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 lapack_complex_double* t, lapack_int ldt );\n\nlapack_int LAPACKE_stpmqrt_work( int matrix_order, char side, char trans,\n                                 lapack_int m, lapack_int n, lapack_int k,\n                                 lapack_int l, lapack_int nb, const float* v,\n                                 lapack_int ldv, const float* t, lapack_int ldt,\n                                 float* a, lapack_int lda, float* b,\n                                 lapack_int ldb, float* work );\nlapack_int LAPACKE_dtpmqrt_work( int matrix_order, char side, char trans,\n                                 lapack_int m, lapack_int n, lapack_int k,\n                                 lapack_int l, lapack_int nb, const double* v,\n                                 lapack_int ldv, const double* t,\n                                 lapack_int ldt, double* a, lapack_int lda,\n                                 double* b, lapack_int ldb, double* work );\nlapack_int LAPACKE_ctpmqrt_work( int matrix_order, char side, char trans,\n                                 lapack_int m, lapack_int n, lapack_int k,\n                                 lapack_int l, lapack_int nb,\n                                 const lapack_complex_float* v, lapack_int ldv,\n                                 const lapack_complex_float* t, lapack_int ldt,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 lapack_complex_float* b, lapack_int ldb,\n                                 lapack_complex_float* work );\nlapack_int LAPACKE_ztpmqrt_work( int matrix_order, char side, char trans,\n                                 lapack_int m, lapack_int n, lapack_int k,\n                                 lapack_int l, lapack_int nb,\n                                 const lapack_complex_double* v, lapack_int ldv,\n                                 const lapack_complex_double* t, lapack_int ldt,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* work );\n\nlapack_int LAPACKE_dtpqrt_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int l, lapack_int nb, double* a,\n                                lapack_int lda, double* b, lapack_int ldb,\n                                double* t, lapack_int ldt, double* work );\nlapack_int LAPACKE_ctpqrt_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int l, lapack_int nb,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* t,\n                                lapack_complex_float* b, lapack_int ldb,\n                                lapack_int ldt, lapack_complex_float* work );\nlapack_int LAPACKE_ztpqrt_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int l, lapack_int nb,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* t, lapack_int ldt,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_stpqrt2_work( int matrix_order, lapack_int m, lapack_int n,\n                                 float* a, lapack_int lda, float* b,\n                                 lapack_int ldb, float* t, lapack_int ldt );\nlapack_int LAPACKE_dtpqrt2_work( int matrix_order, lapack_int m, lapack_int n,\n                                 double* a, lapack_int lda, double* b,\n                                 lapack_int ldb, double* t, lapack_int ldt );\nlapack_int LAPACKE_ctpqrt2_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 lapack_complex_float* b, lapack_int ldb,\n                                 lapack_complex_float* t, lapack_int ldt );\nlapack_int LAPACKE_ztpqrt2_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* t, lapack_int ldt );\n\nlapack_int LAPACKE_stprfb_work( int matrix_order, char side, char trans,\n                                char direct, char storev, lapack_int m,\n                                lapack_int n, lapack_int k, lapack_int l,\n                                const float* v, lapack_int ldv, const float* t,\n                                lapack_int ldt, float* a, lapack_int lda,\n                                float* b, lapack_int ldb, const float* mywork,\n                                lapack_int myldwork );\nlapack_int LAPACKE_dtprfb_work( int matrix_order, char side, char trans,\n                                char direct, char storev, lapack_int m,\n                                lapack_int n, lapack_int k, lapack_int l,\n                                const double* v, lapack_int ldv,\n                                const double* t, lapack_int ldt, double* a,\n                                lapack_int lda, double* b, lapack_int ldb,\n                                const double* mywork, lapack_int myldwork );\nlapack_int LAPACKE_ctprfb_work( int matrix_order, char side, char trans,\n                                char direct, char storev, lapack_int m,\n                                lapack_int n, lapack_int k, lapack_int l,\n                                const lapack_complex_float* v, lapack_int ldv,\n                                const lapack_complex_float* t, lapack_int ldt,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb,\n                                const float* mywork, lapack_int myldwork );\nlapack_int LAPACKE_ztprfb_work( int matrix_order, char side, char trans,\n                                char direct, char storev, lapack_int m,\n                                lapack_int n, lapack_int k, lapack_int l,\n                                const lapack_complex_double* v, lapack_int ldv,\n                                const lapack_complex_double* t, lapack_int ldt,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                const double* mywork, lapack_int myldwork );\n//LAPACK 3.X.X\nlapack_int LAPACKE_csyr( int matrix_order, char uplo, lapack_int n,\n                             lapack_complex_float alpha,\n                             const lapack_complex_float* x, lapack_int incx,\n                             lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_zsyr( int matrix_order, char uplo, lapack_int n,\n                             lapack_complex_double alpha,\n                             const lapack_complex_double* x, lapack_int incx,\n                             lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_csyr_work( int matrix_order, char uplo, lapack_int n,\n                                  lapack_complex_float alpha,\n                                  const lapack_complex_float* x,\n                                  lapack_int incx, lapack_complex_float* a,\n                                  lapack_int lda );\nlapack_int LAPACKE_zsyr_work( int matrix_order, char uplo, lapack_int n,\n                                  lapack_complex_double alpha,\n                                  const lapack_complex_double* x,\n                                  lapack_int incx, lapack_complex_double* a,\n                                  lapack_int lda );\n\n\n\n#define LAPACK_sgetrf LAPACK_GLOBAL(sgetrf,SGETRF)\n#define LAPACK_dgetrf LAPACK_GLOBAL(dgetrf,DGETRF)\n#define LAPACK_cgetrf LAPACK_GLOBAL(cgetrf,CGETRF)\n#define LAPACK_zgetrf LAPACK_GLOBAL(zgetrf,ZGETRF)\n#define LAPACK_sgbtrf LAPACK_GLOBAL(sgbtrf,SGBTRF)\n#define LAPACK_dgbtrf LAPACK_GLOBAL(dgbtrf,DGBTRF)\n#define LAPACK_cgbtrf LAPACK_GLOBAL(cgbtrf,CGBTRF)\n#define LAPACK_zgbtrf LAPACK_GLOBAL(zgbtrf,ZGBTRF)\n#define LAPACK_sgttrf LAPACK_GLOBAL(sgttrf,SGTTRF)\n#define LAPACK_dgttrf LAPACK_GLOBAL(dgttrf,DGTTRF)\n#define LAPACK_cgttrf LAPACK_GLOBAL(cgttrf,CGTTRF)\n#define LAPACK_zgttrf LAPACK_GLOBAL(zgttrf,ZGTTRF)\n#define LAPACK_spotrf LAPACK_GLOBAL(spotrf,SPOTRF)\n#define LAPACK_dpotrf LAPACK_GLOBAL(dpotrf,DPOTRF)\n#define LAPACK_cpotrf LAPACK_GLOBAL(cpotrf,CPOTRF)\n#define LAPACK_zpotrf LAPACK_GLOBAL(zpotrf,ZPOTRF)\n#define LAPACK_dpstrf LAPACK_GLOBAL(dpstrf,DPSTRF)\n#define LAPACK_spstrf LAPACK_GLOBAL(spstrf,SPSTRF)\n#define LAPACK_zpstrf LAPACK_GLOBAL(zpstrf,ZPSTRF)\n#define LAPACK_cpstrf LAPACK_GLOBAL(cpstrf,CPSTRF)\n#define LAPACK_dpftrf LAPACK_GLOBAL(dpftrf,DPFTRF)\n#define LAPACK_spftrf LAPACK_GLOBAL(spftrf,SPFTRF)\n#define LAPACK_zpftrf LAPACK_GLOBAL(zpftrf,ZPFTRF)\n#define LAPACK_cpftrf LAPACK_GLOBAL(cpftrf,CPFTRF)\n#define LAPACK_spptrf LAPACK_GLOBAL(spptrf,SPPTRF)\n#define LAPACK_dpptrf LAPACK_GLOBAL(dpptrf,DPPTRF)\n#define LAPACK_cpptrf LAPACK_GLOBAL(cpptrf,CPPTRF)\n#define LAPACK_zpptrf LAPACK_GLOBAL(zpptrf,ZPPTRF)\n#define LAPACK_spbtrf LAPACK_GLOBAL(spbtrf,SPBTRF)\n#define LAPACK_dpbtrf LAPACK_GLOBAL(dpbtrf,DPBTRF)\n#define LAPACK_cpbtrf LAPACK_GLOBAL(cpbtrf,CPBTRF)\n#define LAPACK_zpbtrf LAPACK_GLOBAL(zpbtrf,ZPBTRF)\n#define LAPACK_spttrf LAPACK_GLOBAL(spttrf,SPTTRF)\n#define LAPACK_dpttrf LAPACK_GLOBAL(dpttrf,DPTTRF)\n#define LAPACK_cpttrf LAPACK_GLOBAL(cpttrf,CPTTRF)\n#define LAPACK_zpttrf LAPACK_GLOBAL(zpttrf,ZPTTRF)\n#define LAPACK_ssytrf LAPACK_GLOBAL(ssytrf,SSYTRF)\n#define LAPACK_dsytrf LAPACK_GLOBAL(dsytrf,DSYTRF)\n#define LAPACK_csytrf LAPACK_GLOBAL(csytrf,CSYTRF)\n#define LAPACK_zsytrf LAPACK_GLOBAL(zsytrf,ZSYTRF)\n#define LAPACK_chetrf LAPACK_GLOBAL(chetrf,CHETRF)\n#define LAPACK_zhetrf LAPACK_GLOBAL(zhetrf,ZHETRF)\n#define LAPACK_ssptrf LAPACK_GLOBAL(ssptrf,SSPTRF)\n#define LAPACK_dsptrf LAPACK_GLOBAL(dsptrf,DSPTRF)\n#define LAPACK_csptrf LAPACK_GLOBAL(csptrf,CSPTRF)\n#define LAPACK_zsptrf LAPACK_GLOBAL(zsptrf,ZSPTRF)\n#define LAPACK_chptrf LAPACK_GLOBAL(chptrf,CHPTRF)\n#define LAPACK_zhptrf LAPACK_GLOBAL(zhptrf,ZHPTRF)\n#define LAPACK_sgetrs LAPACK_GLOBAL(sgetrs,SGETRS)\n#define LAPACK_dgetrs LAPACK_GLOBAL(dgetrs,DGETRS)\n#define LAPACK_cgetrs LAPACK_GLOBAL(cgetrs,CGETRS)\n#define LAPACK_zgetrs LAPACK_GLOBAL(zgetrs,ZGETRS)\n#define LAPACK_sgbtrs LAPACK_GLOBAL(sgbtrs,SGBTRS)\n#define LAPACK_dgbtrs LAPACK_GLOBAL(dgbtrs,DGBTRS)\n#define LAPACK_cgbtrs LAPACK_GLOBAL(cgbtrs,CGBTRS)\n#define LAPACK_zgbtrs LAPACK_GLOBAL(zgbtrs,ZGBTRS)\n#define LAPACK_sgttrs LAPACK_GLOBAL(sgttrs,SGTTRS)\n#define LAPACK_dgttrs LAPACK_GLOBAL(dgttrs,DGTTRS)\n#define LAPACK_cgttrs LAPACK_GLOBAL(cgttrs,CGTTRS)\n#define LAPACK_zgttrs LAPACK_GLOBAL(zgttrs,ZGTTRS)\n#define LAPACK_spotrs LAPACK_GLOBAL(spotrs,SPOTRS)\n#define LAPACK_dpotrs LAPACK_GLOBAL(dpotrs,DPOTRS)\n#define LAPACK_cpotrs LAPACK_GLOBAL(cpotrs,CPOTRS)\n#define LAPACK_zpotrs LAPACK_GLOBAL(zpotrs,ZPOTRS)\n#define LAPACK_dpftrs LAPACK_GLOBAL(dpftrs,DPFTRS)\n#define LAPACK_spftrs LAPACK_GLOBAL(spftrs,SPFTRS)\n#define LAPACK_zpftrs LAPACK_GLOBAL(zpftrs,ZPFTRS)\n#define LAPACK_cpftrs LAPACK_GLOBAL(cpftrs,CPFTRS)\n#define LAPACK_spptrs LAPACK_GLOBAL(spptrs,SPPTRS)\n#define LAPACK_dpptrs LAPACK_GLOBAL(dpptrs,DPPTRS)\n#define LAPACK_cpptrs LAPACK_GLOBAL(cpptrs,CPPTRS)\n#define LAPACK_zpptrs LAPACK_GLOBAL(zpptrs,ZPPTRS)\n#define LAPACK_spbtrs LAPACK_GLOBAL(spbtrs,SPBTRS)\n#define LAPACK_dpbtrs LAPACK_GLOBAL(dpbtrs,DPBTRS)\n#define LAPACK_cpbtrs LAPACK_GLOBAL(cpbtrs,CPBTRS)\n#define LAPACK_zpbtrs LAPACK_GLOBAL(zpbtrs,ZPBTRS)\n#define LAPACK_spttrs LAPACK_GLOBAL(spttrs,SPTTRS)\n#define LAPACK_dpttrs LAPACK_GLOBAL(dpttrs,DPTTRS)\n#define LAPACK_cpttrs LAPACK_GLOBAL(cpttrs,CPTTRS)\n#define LAPACK_zpttrs LAPACK_GLOBAL(zpttrs,ZPTTRS)\n#define LAPACK_ssytrs LAPACK_GLOBAL(ssytrs,SSYTRS)\n#define LAPACK_dsytrs LAPACK_GLOBAL(dsytrs,DSYTRS)\n#define LAPACK_csytrs LAPACK_GLOBAL(csytrs,CSYTRS)\n#define LAPACK_zsytrs LAPACK_GLOBAL(zsytrs,ZSYTRS)\n#define LAPACK_chetrs LAPACK_GLOBAL(chetrs,CHETRS)\n#define LAPACK_zhetrs LAPACK_GLOBAL(zhetrs,ZHETRS)\n#define LAPACK_ssptrs LAPACK_GLOBAL(ssptrs,SSPTRS)\n#define LAPACK_dsptrs LAPACK_GLOBAL(dsptrs,DSPTRS)\n#define LAPACK_csptrs LAPACK_GLOBAL(csptrs,CSPTRS)\n#define LAPACK_zsptrs LAPACK_GLOBAL(zsptrs,ZSPTRS)\n#define LAPACK_chptrs LAPACK_GLOBAL(chptrs,CHPTRS)\n#define LAPACK_zhptrs LAPACK_GLOBAL(zhptrs,ZHPTRS)\n#define LAPACK_strtrs LAPACK_GLOBAL(strtrs,STRTRS)\n#define LAPACK_dtrtrs LAPACK_GLOBAL(dtrtrs,DTRTRS)\n#define LAPACK_ctrtrs LAPACK_GLOBAL(ctrtrs,CTRTRS)\n#define LAPACK_ztrtrs LAPACK_GLOBAL(ztrtrs,ZTRTRS)\n#define LAPACK_stptrs LAPACK_GLOBAL(stptrs,STPTRS)\n#define LAPACK_dtptrs LAPACK_GLOBAL(dtptrs,DTPTRS)\n#define LAPACK_ctptrs LAPACK_GLOBAL(ctptrs,CTPTRS)\n#define LAPACK_ztptrs LAPACK_GLOBAL(ztptrs,ZTPTRS)\n#define LAPACK_stbtrs LAPACK_GLOBAL(stbtrs,STBTRS)\n#define LAPACK_dtbtrs LAPACK_GLOBAL(dtbtrs,DTBTRS)\n#define LAPACK_ctbtrs LAPACK_GLOBAL(ctbtrs,CTBTRS)\n#define LAPACK_ztbtrs LAPACK_GLOBAL(ztbtrs,ZTBTRS)\n#define LAPACK_sgecon LAPACK_GLOBAL(sgecon,SGECON)\n#define LAPACK_dgecon LAPACK_GLOBAL(dgecon,DGECON)\n#define LAPACK_cgecon LAPACK_GLOBAL(cgecon,CGECON)\n#define LAPACK_zgecon LAPACK_GLOBAL(zgecon,ZGECON)\n#define LAPACK_sgbcon LAPACK_GLOBAL(sgbcon,SGBCON)\n#define LAPACK_dgbcon LAPACK_GLOBAL(dgbcon,DGBCON)\n#define LAPACK_cgbcon LAPACK_GLOBAL(cgbcon,CGBCON)\n#define LAPACK_zgbcon LAPACK_GLOBAL(zgbcon,ZGBCON)\n#define LAPACK_sgtcon LAPACK_GLOBAL(sgtcon,SGTCON)\n#define LAPACK_dgtcon LAPACK_GLOBAL(dgtcon,DGTCON)\n#define LAPACK_cgtcon LAPACK_GLOBAL(cgtcon,CGTCON)\n#define LAPACK_zgtcon LAPACK_GLOBAL(zgtcon,ZGTCON)\n#define LAPACK_spocon LAPACK_GLOBAL(spocon,SPOCON)\n#define LAPACK_dpocon LAPACK_GLOBAL(dpocon,DPOCON)\n#define LAPACK_cpocon LAPACK_GLOBAL(cpocon,CPOCON)\n#define LAPACK_zpocon LAPACK_GLOBAL(zpocon,ZPOCON)\n#define LAPACK_sppcon LAPACK_GLOBAL(sppcon,SPPCON)\n#define LAPACK_dppcon LAPACK_GLOBAL(dppcon,DPPCON)\n#define LAPACK_cppcon LAPACK_GLOBAL(cppcon,CPPCON)\n#define LAPACK_zppcon LAPACK_GLOBAL(zppcon,ZPPCON)\n#define LAPACK_spbcon LAPACK_GLOBAL(spbcon,SPBCON)\n#define LAPACK_dpbcon LAPACK_GLOBAL(dpbcon,DPBCON)\n#define LAPACK_cpbcon LAPACK_GLOBAL(cpbcon,CPBCON)\n#define LAPACK_zpbcon LAPACK_GLOBAL(zpbcon,ZPBCON)\n#define LAPACK_sptcon LAPACK_GLOBAL(sptcon,SPTCON)\n#define LAPACK_dptcon LAPACK_GLOBAL(dptcon,DPTCON)\n#define LAPACK_cptcon LAPACK_GLOBAL(cptcon,CPTCON)\n#define LAPACK_zptcon LAPACK_GLOBAL(zptcon,ZPTCON)\n#define LAPACK_ssycon LAPACK_GLOBAL(ssycon,SSYCON)\n#define LAPACK_dsycon LAPACK_GLOBAL(dsycon,DSYCON)\n#define LAPACK_csycon LAPACK_GLOBAL(csycon,CSYCON)\n#define LAPACK_zsycon LAPACK_GLOBAL(zsycon,ZSYCON)\n#define LAPACK_checon LAPACK_GLOBAL(checon,CHECON)\n#define LAPACK_zhecon LAPACK_GLOBAL(zhecon,ZHECON)\n#define LAPACK_sspcon LAPACK_GLOBAL(sspcon,SSPCON)\n#define LAPACK_dspcon LAPACK_GLOBAL(dspcon,DSPCON)\n#define LAPACK_cspcon LAPACK_GLOBAL(cspcon,CSPCON)\n#define LAPACK_zspcon LAPACK_GLOBAL(zspcon,ZSPCON)\n#define LAPACK_chpcon LAPACK_GLOBAL(chpcon,CHPCON)\n#define LAPACK_zhpcon LAPACK_GLOBAL(zhpcon,ZHPCON)\n#define LAPACK_strcon LAPACK_GLOBAL(strcon,STRCON)\n#define LAPACK_dtrcon LAPACK_GLOBAL(dtrcon,DTRCON)\n#define LAPACK_ctrcon LAPACK_GLOBAL(ctrcon,CTRCON)\n#define LAPACK_ztrcon LAPACK_GLOBAL(ztrcon,ZTRCON)\n#define LAPACK_stpcon LAPACK_GLOBAL(stpcon,STPCON)\n#define LAPACK_dtpcon LAPACK_GLOBAL(dtpcon,DTPCON)\n#define LAPACK_ctpcon LAPACK_GLOBAL(ctpcon,CTPCON)\n#define LAPACK_ztpcon LAPACK_GLOBAL(ztpcon,ZTPCON)\n#define LAPACK_stbcon LAPACK_GLOBAL(stbcon,STBCON)\n#define LAPACK_dtbcon LAPACK_GLOBAL(dtbcon,DTBCON)\n#define LAPACK_ctbcon LAPACK_GLOBAL(ctbcon,CTBCON)\n#define LAPACK_ztbcon LAPACK_GLOBAL(ztbcon,ZTBCON)\n#define LAPACK_sgerfs LAPACK_GLOBAL(sgerfs,SGERFS)\n#define LAPACK_dgerfs LAPACK_GLOBAL(dgerfs,DGERFS)\n#define LAPACK_cgerfs LAPACK_GLOBAL(cgerfs,CGERFS)\n#define LAPACK_zgerfs LAPACK_GLOBAL(zgerfs,ZGERFS)\n#define LAPACK_dgerfsx LAPACK_GLOBAL(dgerfsx,DGERFSX)\n#define LAPACK_sgerfsx LAPACK_GLOBAL(sgerfsx,SGERFSX)\n#define LAPACK_zgerfsx LAPACK_GLOBAL(zgerfsx,ZGERFSX)\n#define LAPACK_cgerfsx LAPACK_GLOBAL(cgerfsx,CGERFSX)\n#define LAPACK_sgbrfs LAPACK_GLOBAL(sgbrfs,SGBRFS)\n#define LAPACK_dgbrfs LAPACK_GLOBAL(dgbrfs,DGBRFS)\n#define LAPACK_cgbrfs LAPACK_GLOBAL(cgbrfs,CGBRFS)\n#define LAPACK_zgbrfs LAPACK_GLOBAL(zgbrfs,ZGBRFS)\n#define LAPACK_dgbrfsx LAPACK_GLOBAL(dgbrfsx,DGBRFSX)\n#define LAPACK_sgbrfsx LAPACK_GLOBAL(sgbrfsx,SGBRFSX)\n#define LAPACK_zgbrfsx LAPACK_GLOBAL(zgbrfsx,ZGBRFSX)\n#define LAPACK_cgbrfsx LAPACK_GLOBAL(cgbrfsx,CGBRFSX)\n#define LAPACK_sgtrfs LAPACK_GLOBAL(sgtrfs,SGTRFS)\n#define LAPACK_dgtrfs LAPACK_GLOBAL(dgtrfs,DGTRFS)\n#define LAPACK_cgtrfs LAPACK_GLOBAL(cgtrfs,CGTRFS)\n#define LAPACK_zgtrfs LAPACK_GLOBAL(zgtrfs,ZGTRFS)\n#define LAPACK_sporfs LAPACK_GLOBAL(sporfs,SPORFS)\n#define LAPACK_dporfs LAPACK_GLOBAL(dporfs,DPORFS)\n#define LAPACK_cporfs LAPACK_GLOBAL(cporfs,CPORFS)\n#define LAPACK_zporfs LAPACK_GLOBAL(zporfs,ZPORFS)\n#define LAPACK_dporfsx LAPACK_GLOBAL(dporfsx,DPORFSX)\n#define LAPACK_sporfsx LAPACK_GLOBAL(sporfsx,SPORFSX)\n#define LAPACK_zporfsx LAPACK_GLOBAL(zporfsx,ZPORFSX)\n#define LAPACK_cporfsx LAPACK_GLOBAL(cporfsx,CPORFSX)\n#define LAPACK_spprfs LAPACK_GLOBAL(spprfs,SPPRFS)\n#define LAPACK_dpprfs LAPACK_GLOBAL(dpprfs,DPPRFS)\n#define LAPACK_cpprfs LAPACK_GLOBAL(cpprfs,CPPRFS)\n#define LAPACK_zpprfs LAPACK_GLOBAL(zpprfs,ZPPRFS)\n#define LAPACK_spbrfs LAPACK_GLOBAL(spbrfs,SPBRFS)\n#define LAPACK_dpbrfs LAPACK_GLOBAL(dpbrfs,DPBRFS)\n#define LAPACK_cpbrfs LAPACK_GLOBAL(cpbrfs,CPBRFS)\n#define LAPACK_zpbrfs LAPACK_GLOBAL(zpbrfs,ZPBRFS)\n#define LAPACK_sptrfs LAPACK_GLOBAL(sptrfs,SPTRFS)\n#define LAPACK_dptrfs LAPACK_GLOBAL(dptrfs,DPTRFS)\n#define LAPACK_cptrfs LAPACK_GLOBAL(cptrfs,CPTRFS)\n#define LAPACK_zptrfs LAPACK_GLOBAL(zptrfs,ZPTRFS)\n#define LAPACK_ssyrfs LAPACK_GLOBAL(ssyrfs,SSYRFS)\n#define LAPACK_dsyrfs LAPACK_GLOBAL(dsyrfs,DSYRFS)\n#define LAPACK_csyrfs LAPACK_GLOBAL(csyrfs,CSYRFS)\n#define LAPACK_zsyrfs LAPACK_GLOBAL(zsyrfs,ZSYRFS)\n#define LAPACK_dsyrfsx LAPACK_GLOBAL(dsyrfsx,DSYRFSX)\n#define LAPACK_ssyrfsx LAPACK_GLOBAL(ssyrfsx,SSYRFSX)\n#define LAPACK_zsyrfsx LAPACK_GLOBAL(zsyrfsx,ZSYRFSX)\n#define LAPACK_csyrfsx LAPACK_GLOBAL(csyrfsx,CSYRFSX)\n#define LAPACK_cherfs LAPACK_GLOBAL(cherfs,CHERFS)\n#define LAPACK_zherfs LAPACK_GLOBAL(zherfs,ZHERFS)\n#define LAPACK_zherfsx LAPACK_GLOBAL(zherfsx,ZHERFSX)\n#define LAPACK_cherfsx LAPACK_GLOBAL(cherfsx,CHERFSX)\n#define LAPACK_ssprfs LAPACK_GLOBAL(ssprfs,SSPRFS)\n#define LAPACK_dsprfs LAPACK_GLOBAL(dsprfs,DSPRFS)\n#define LAPACK_csprfs LAPACK_GLOBAL(csprfs,CSPRFS)\n#define LAPACK_zsprfs LAPACK_GLOBAL(zsprfs,ZSPRFS)\n#define LAPACK_chprfs LAPACK_GLOBAL(chprfs,CHPRFS)\n#define LAPACK_zhprfs LAPACK_GLOBAL(zhprfs,ZHPRFS)\n#define LAPACK_strrfs LAPACK_GLOBAL(strrfs,STRRFS)\n#define LAPACK_dtrrfs LAPACK_GLOBAL(dtrrfs,DTRRFS)\n#define LAPACK_ctrrfs LAPACK_GLOBAL(ctrrfs,CTRRFS)\n#define LAPACK_ztrrfs LAPACK_GLOBAL(ztrrfs,ZTRRFS)\n#define LAPACK_stprfs LAPACK_GLOBAL(stprfs,STPRFS)\n#define LAPACK_dtprfs LAPACK_GLOBAL(dtprfs,DTPRFS)\n#define LAPACK_ctprfs LAPACK_GLOBAL(ctprfs,CTPRFS)\n#define LAPACK_ztprfs LAPACK_GLOBAL(ztprfs,ZTPRFS)\n#define LAPACK_stbrfs LAPACK_GLOBAL(stbrfs,STBRFS)\n#define LAPACK_dtbrfs LAPACK_GLOBAL(dtbrfs,DTBRFS)\n#define LAPACK_ctbrfs LAPACK_GLOBAL(ctbrfs,CTBRFS)\n#define LAPACK_ztbrfs LAPACK_GLOBAL(ztbrfs,ZTBRFS)\n#define LAPACK_sgetri LAPACK_GLOBAL(sgetri,SGETRI)\n#define LAPACK_dgetri LAPACK_GLOBAL(dgetri,DGETRI)\n#define LAPACK_cgetri LAPACK_GLOBAL(cgetri,CGETRI)\n#define LAPACK_zgetri LAPACK_GLOBAL(zgetri,ZGETRI)\n#define LAPACK_spotri LAPACK_GLOBAL(spotri,SPOTRI)\n#define LAPACK_dpotri LAPACK_GLOBAL(dpotri,DPOTRI)\n#define LAPACK_cpotri LAPACK_GLOBAL(cpotri,CPOTRI)\n#define LAPACK_zpotri LAPACK_GLOBAL(zpotri,ZPOTRI)\n#define LAPACK_dpftri LAPACK_GLOBAL(dpftri,DPFTRI)\n#define LAPACK_spftri LAPACK_GLOBAL(spftri,SPFTRI)\n#define LAPACK_zpftri LAPACK_GLOBAL(zpftri,ZPFTRI)\n#define LAPACK_cpftri LAPACK_GLOBAL(cpftri,CPFTRI)\n#define LAPACK_spptri LAPACK_GLOBAL(spptri,SPPTRI)\n#define LAPACK_dpptri LAPACK_GLOBAL(dpptri,DPPTRI)\n#define LAPACK_cpptri LAPACK_GLOBAL(cpptri,CPPTRI)\n#define LAPACK_zpptri LAPACK_GLOBAL(zpptri,ZPPTRI)\n#define LAPACK_ssytri LAPACK_GLOBAL(ssytri,SSYTRI)\n#define LAPACK_dsytri LAPACK_GLOBAL(dsytri,DSYTRI)\n#define LAPACK_csytri LAPACK_GLOBAL(csytri,CSYTRI)\n#define LAPACK_zsytri LAPACK_GLOBAL(zsytri,ZSYTRI)\n#define LAPACK_chetri LAPACK_GLOBAL(chetri,CHETRI)\n#define LAPACK_zhetri LAPACK_GLOBAL(zhetri,ZHETRI)\n#define LAPACK_ssptri LAPACK_GLOBAL(ssptri,SSPTRI)\n#define LAPACK_dsptri LAPACK_GLOBAL(dsptri,DSPTRI)\n#define LAPACK_csptri LAPACK_GLOBAL(csptri,CSPTRI)\n#define LAPACK_zsptri LAPACK_GLOBAL(zsptri,ZSPTRI)\n#define LAPACK_chptri LAPACK_GLOBAL(chptri,CHPTRI)\n#define LAPACK_zhptri LAPACK_GLOBAL(zhptri,ZHPTRI)\n#define LAPACK_strtri LAPACK_GLOBAL(strtri,STRTRI)\n#define LAPACK_dtrtri LAPACK_GLOBAL(dtrtri,DTRTRI)\n#define LAPACK_ctrtri LAPACK_GLOBAL(ctrtri,CTRTRI)\n#define LAPACK_ztrtri LAPACK_GLOBAL(ztrtri,ZTRTRI)\n#define LAPACK_dtftri LAPACK_GLOBAL(dtftri,DTFTRI)\n#define LAPACK_stftri LAPACK_GLOBAL(stftri,STFTRI)\n#define LAPACK_ztftri LAPACK_GLOBAL(ztftri,ZTFTRI)\n#define LAPACK_ctftri LAPACK_GLOBAL(ctftri,CTFTRI)\n#define LAPACK_stptri LAPACK_GLOBAL(stptri,STPTRI)\n#define LAPACK_dtptri LAPACK_GLOBAL(dtptri,DTPTRI)\n#define LAPACK_ctptri LAPACK_GLOBAL(ctptri,CTPTRI)\n#define LAPACK_ztptri LAPACK_GLOBAL(ztptri,ZTPTRI)\n#define LAPACK_sgeequ LAPACK_GLOBAL(sgeequ,SGEEQU)\n#define LAPACK_dgeequ LAPACK_GLOBAL(dgeequ,DGEEQU)\n#define LAPACK_cgeequ LAPACK_GLOBAL(cgeequ,CGEEQU)\n#define LAPACK_zgeequ LAPACK_GLOBAL(zgeequ,ZGEEQU)\n#define LAPACK_dgeequb LAPACK_GLOBAL(dgeequb,DGEEQUB)\n#define LAPACK_sgeequb LAPACK_GLOBAL(sgeequb,SGEEQUB)\n#define LAPACK_zgeequb LAPACK_GLOBAL(zgeequb,ZGEEQUB)\n#define LAPACK_cgeequb LAPACK_GLOBAL(cgeequb,CGEEQUB)\n#define LAPACK_sgbequ LAPACK_GLOBAL(sgbequ,SGBEQU)\n#define LAPACK_dgbequ LAPACK_GLOBAL(dgbequ,DGBEQU)\n#define LAPACK_cgbequ LAPACK_GLOBAL(cgbequ,CGBEQU)\n#define LAPACK_zgbequ LAPACK_GLOBAL(zgbequ,ZGBEQU)\n#define LAPACK_dgbequb LAPACK_GLOBAL(dgbequb,DGBEQUB)\n#define LAPACK_sgbequb LAPACK_GLOBAL(sgbequb,SGBEQUB)\n#define LAPACK_zgbequb LAPACK_GLOBAL(zgbequb,ZGBEQUB)\n#define LAPACK_cgbequb LAPACK_GLOBAL(cgbequb,CGBEQUB)\n#define LAPACK_spoequ LAPACK_GLOBAL(spoequ,SPOEQU)\n#define LAPACK_dpoequ LAPACK_GLOBAL(dpoequ,DPOEQU)\n#define LAPACK_cpoequ LAPACK_GLOBAL(cpoequ,CPOEQU)\n#define LAPACK_zpoequ LAPACK_GLOBAL(zpoequ,ZPOEQU)\n#define LAPACK_dpoequb LAPACK_GLOBAL(dpoequb,DPOEQUB)\n#define LAPACK_spoequb LAPACK_GLOBAL(spoequb,SPOEQUB)\n#define LAPACK_zpoequb LAPACK_GLOBAL(zpoequb,ZPOEQUB)\n#define LAPACK_cpoequb LAPACK_GLOBAL(cpoequb,CPOEQUB)\n#define LAPACK_sppequ LAPACK_GLOBAL(sppequ,SPPEQU)\n#define LAPACK_dppequ LAPACK_GLOBAL(dppequ,DPPEQU)\n#define LAPACK_cppequ LAPACK_GLOBAL(cppequ,CPPEQU)\n#define LAPACK_zppequ LAPACK_GLOBAL(zppequ,ZPPEQU)\n#define LAPACK_spbequ LAPACK_GLOBAL(spbequ,SPBEQU)\n#define LAPACK_dpbequ LAPACK_GLOBAL(dpbequ,DPBEQU)\n#define LAPACK_cpbequ LAPACK_GLOBAL(cpbequ,CPBEQU)\n#define LAPACK_zpbequ LAPACK_GLOBAL(zpbequ,ZPBEQU)\n#define LAPACK_dsyequb LAPACK_GLOBAL(dsyequb,DSYEQUB)\n#define LAPACK_ssyequb LAPACK_GLOBAL(ssyequb,SSYEQUB)\n#define LAPACK_zsyequb LAPACK_GLOBAL(zsyequb,ZSYEQUB)\n#define LAPACK_csyequb LAPACK_GLOBAL(csyequb,CSYEQUB)\n#define LAPACK_zheequb LAPACK_GLOBAL(zheequb,ZHEEQUB)\n#define LAPACK_cheequb LAPACK_GLOBAL(cheequb,CHEEQUB)\n#define LAPACK_sgesv LAPACK_GLOBAL(sgesv,SGESV)\n#define LAPACK_dgesv LAPACK_GLOBAL(dgesv,DGESV)\n#define LAPACK_cgesv LAPACK_GLOBAL(cgesv,CGESV)\n#define LAPACK_zgesv LAPACK_GLOBAL(zgesv,ZGESV)\n#define LAPACK_dsgesv LAPACK_GLOBAL(dsgesv,DSGESV)\n#define LAPACK_zcgesv LAPACK_GLOBAL(zcgesv,ZCGESV)\n#define LAPACK_sgesvx LAPACK_GLOBAL(sgesvx,SGESVX)\n#define LAPACK_dgesvx LAPACK_GLOBAL(dgesvx,DGESVX)\n#define LAPACK_cgesvx LAPACK_GLOBAL(cgesvx,CGESVX)\n#define LAPACK_zgesvx LAPACK_GLOBAL(zgesvx,ZGESVX)\n#define LAPACK_dgesvxx LAPACK_GLOBAL(dgesvxx,DGESVXX)\n#define LAPACK_sgesvxx LAPACK_GLOBAL(sgesvxx,SGESVXX)\n#define LAPACK_zgesvxx LAPACK_GLOBAL(zgesvxx,ZGESVXX)\n#define LAPACK_cgesvxx LAPACK_GLOBAL(cgesvxx,CGESVXX)\n#define LAPACK_sgbsv LAPACK_GLOBAL(sgbsv,SGBSV)\n#define LAPACK_dgbsv LAPACK_GLOBAL(dgbsv,DGBSV)\n#define LAPACK_cgbsv LAPACK_GLOBAL(cgbsv,CGBSV)\n#define LAPACK_zgbsv LAPACK_GLOBAL(zgbsv,ZGBSV)\n#define LAPACK_sgbsvx LAPACK_GLOBAL(sgbsvx,SGBSVX)\n#define LAPACK_dgbsvx LAPACK_GLOBAL(dgbsvx,DGBSVX)\n#define LAPACK_cgbsvx LAPACK_GLOBAL(cgbsvx,CGBSVX)\n#define LAPACK_zgbsvx LAPACK_GLOBAL(zgbsvx,ZGBSVX)\n#define LAPACK_dgbsvxx LAPACK_GLOBAL(dgbsvxx,DGBSVXX)\n#define LAPACK_sgbsvxx LAPACK_GLOBAL(sgbsvxx,SGBSVXX)\n#define LAPACK_zgbsvxx LAPACK_GLOBAL(zgbsvxx,ZGBSVXX)\n#define LAPACK_cgbsvxx LAPACK_GLOBAL(cgbsvxx,CGBSVXX)\n#define LAPACK_sgtsv LAPACK_GLOBAL(sgtsv,SGTSV)\n#define LAPACK_dgtsv LAPACK_GLOBAL(dgtsv,DGTSV)\n#define LAPACK_cgtsv LAPACK_GLOBAL(cgtsv,CGTSV)\n#define LAPACK_zgtsv LAPACK_GLOBAL(zgtsv,ZGTSV)\n#define LAPACK_sgtsvx LAPACK_GLOBAL(sgtsvx,SGTSVX)\n#define LAPACK_dgtsvx LAPACK_GLOBAL(dgtsvx,DGTSVX)\n#define LAPACK_cgtsvx LAPACK_GLOBAL(cgtsvx,CGTSVX)\n#define LAPACK_zgtsvx LAPACK_GLOBAL(zgtsvx,ZGTSVX)\n#define LAPACK_sposv LAPACK_GLOBAL(sposv,SPOSV)\n#define LAPACK_dposv LAPACK_GLOBAL(dposv,DPOSV)\n#define LAPACK_cposv LAPACK_GLOBAL(cposv,CPOSV)\n#define LAPACK_zposv LAPACK_GLOBAL(zposv,ZPOSV)\n#define LAPACK_dsposv LAPACK_GLOBAL(dsposv,DSPOSV)\n#define LAPACK_zcposv LAPACK_GLOBAL(zcposv,ZCPOSV)\n#define LAPACK_sposvx LAPACK_GLOBAL(sposvx,SPOSVX)\n#define LAPACK_dposvx LAPACK_GLOBAL(dposvx,DPOSVX)\n#define LAPACK_cposvx LAPACK_GLOBAL(cposvx,CPOSVX)\n#define LAPACK_zposvx LAPACK_GLOBAL(zposvx,ZPOSVX)\n#define LAPACK_dposvxx LAPACK_GLOBAL(dposvxx,DPOSVXX)\n#define LAPACK_sposvxx LAPACK_GLOBAL(sposvxx,SPOSVXX)\n#define LAPACK_zposvxx LAPACK_GLOBAL(zposvxx,ZPOSVXX)\n#define LAPACK_cposvxx LAPACK_GLOBAL(cposvxx,CPOSVXX)\n#define LAPACK_sppsv LAPACK_GLOBAL(sppsv,SPPSV)\n#define LAPACK_dppsv LAPACK_GLOBAL(dppsv,DPPSV)\n#define LAPACK_cppsv LAPACK_GLOBAL(cppsv,CPPSV)\n#define LAPACK_zppsv LAPACK_GLOBAL(zppsv,ZPPSV)\n#define LAPACK_sppsvx LAPACK_GLOBAL(sppsvx,SPPSVX)\n#define LAPACK_dppsvx LAPACK_GLOBAL(dppsvx,DPPSVX)\n#define LAPACK_cppsvx LAPACK_GLOBAL(cppsvx,CPPSVX)\n#define LAPACK_zppsvx LAPACK_GLOBAL(zppsvx,ZPPSVX)\n#define LAPACK_spbsv LAPACK_GLOBAL(spbsv,SPBSV)\n#define LAPACK_dpbsv LAPACK_GLOBAL(dpbsv,DPBSV)\n#define LAPACK_cpbsv LAPACK_GLOBAL(cpbsv,CPBSV)\n#define LAPACK_zpbsv LAPACK_GLOBAL(zpbsv,ZPBSV)\n#define LAPACK_spbsvx LAPACK_GLOBAL(spbsvx,SPBSVX)\n#define LAPACK_dpbsvx LAPACK_GLOBAL(dpbsvx,DPBSVX)\n#define LAPACK_cpbsvx LAPACK_GLOBAL(cpbsvx,CPBSVX)\n#define LAPACK_zpbsvx LAPACK_GLOBAL(zpbsvx,ZPBSVX)\n#define LAPACK_sptsv LAPACK_GLOBAL(sptsv,SPTSV)\n#define LAPACK_dptsv LAPACK_GLOBAL(dptsv,DPTSV)\n#define LAPACK_cptsv LAPACK_GLOBAL(cptsv,CPTSV)\n#define LAPACK_zptsv LAPACK_GLOBAL(zptsv,ZPTSV)\n#define LAPACK_sptsvx LAPACK_GLOBAL(sptsvx,SPTSVX)\n#define LAPACK_dptsvx LAPACK_GLOBAL(dptsvx,DPTSVX)\n#define LAPACK_cptsvx LAPACK_GLOBAL(cptsvx,CPTSVX)\n#define LAPACK_zptsvx LAPACK_GLOBAL(zptsvx,ZPTSVX)\n#define LAPACK_ssysv LAPACK_GLOBAL(ssysv,SSYSV)\n#define LAPACK_dsysv LAPACK_GLOBAL(dsysv,DSYSV)\n#define LAPACK_csysv LAPACK_GLOBAL(csysv,CSYSV)\n#define LAPACK_zsysv LAPACK_GLOBAL(zsysv,ZSYSV)\n#define LAPACK_ssysvx LAPACK_GLOBAL(ssysvx,SSYSVX)\n#define LAPACK_dsysvx LAPACK_GLOBAL(dsysvx,DSYSVX)\n#define LAPACK_csysvx LAPACK_GLOBAL(csysvx,CSYSVX)\n#define LAPACK_zsysvx LAPACK_GLOBAL(zsysvx,ZSYSVX)\n#define LAPACK_dsysvxx LAPACK_GLOBAL(dsysvxx,DSYSVXX)\n#define LAPACK_ssysvxx LAPACK_GLOBAL(ssysvxx,SSYSVXX)\n#define LAPACK_zsysvxx LAPACK_GLOBAL(zsysvxx,ZSYSVXX)\n#define LAPACK_csysvxx LAPACK_GLOBAL(csysvxx,CSYSVXX)\n#define LAPACK_chesv LAPACK_GLOBAL(chesv,CHESV)\n#define LAPACK_zhesv LAPACK_GLOBAL(zhesv,ZHESV)\n#define LAPACK_chesvx LAPACK_GLOBAL(chesvx,CHESVX)\n#define LAPACK_zhesvx LAPACK_GLOBAL(zhesvx,ZHESVX)\n#define LAPACK_zhesvxx LAPACK_GLOBAL(zhesvxx,ZHESVXX)\n#define LAPACK_chesvxx LAPACK_GLOBAL(chesvxx,CHESVXX)\n#define LAPACK_sspsv LAPACK_GLOBAL(sspsv,SSPSV)\n#define LAPACK_dspsv LAPACK_GLOBAL(dspsv,DSPSV)\n#define LAPACK_cspsv LAPACK_GLOBAL(cspsv,CSPSV)\n#define LAPACK_zspsv LAPACK_GLOBAL(zspsv,ZSPSV)\n#define LAPACK_sspsvx LAPACK_GLOBAL(sspsvx,SSPSVX)\n#define LAPACK_dspsvx LAPACK_GLOBAL(dspsvx,DSPSVX)\n#define LAPACK_cspsvx LAPACK_GLOBAL(cspsvx,CSPSVX)\n#define LAPACK_zspsvx LAPACK_GLOBAL(zspsvx,ZSPSVX)\n#define LAPACK_chpsv LAPACK_GLOBAL(chpsv,CHPSV)\n#define LAPACK_zhpsv LAPACK_GLOBAL(zhpsv,ZHPSV)\n#define LAPACK_chpsvx LAPACK_GLOBAL(chpsvx,CHPSVX)\n#define LAPACK_zhpsvx LAPACK_GLOBAL(zhpsvx,ZHPSVX)\n#define LAPACK_sgeqrf LAPACK_GLOBAL(sgeqrf,SGEQRF)\n#define LAPACK_dgeqrf LAPACK_GLOBAL(dgeqrf,DGEQRF)\n#define LAPACK_cgeqrf LAPACK_GLOBAL(cgeqrf,CGEQRF)\n#define LAPACK_zgeqrf LAPACK_GLOBAL(zgeqrf,ZGEQRF)\n#define LAPACK_sgeqpf LAPACK_GLOBAL(sgeqpf,SGEQPF)\n#define LAPACK_dgeqpf LAPACK_GLOBAL(dgeqpf,DGEQPF)\n#define LAPACK_cgeqpf LAPACK_GLOBAL(cgeqpf,CGEQPF)\n#define LAPACK_zgeqpf LAPACK_GLOBAL(zgeqpf,ZGEQPF)\n#define LAPACK_sgeqp3 LAPACK_GLOBAL(sgeqp3,SGEQP3)\n#define LAPACK_dgeqp3 LAPACK_GLOBAL(dgeqp3,DGEQP3)\n#define LAPACK_cgeqp3 LAPACK_GLOBAL(cgeqp3,CGEQP3)\n#define LAPACK_zgeqp3 LAPACK_GLOBAL(zgeqp3,ZGEQP3)\n#define LAPACK_sorgqr LAPACK_GLOBAL(sorgqr,SORGQR)\n#define LAPACK_dorgqr LAPACK_GLOBAL(dorgqr,DORGQR)\n#define LAPACK_sormqr LAPACK_GLOBAL(sormqr,SORMQR)\n#define LAPACK_dormqr LAPACK_GLOBAL(dormqr,DORMQR)\n#define LAPACK_cungqr LAPACK_GLOBAL(cungqr,CUNGQR)\n#define LAPACK_zungqr LAPACK_GLOBAL(zungqr,ZUNGQR)\n#define LAPACK_cunmqr LAPACK_GLOBAL(cunmqr,CUNMQR)\n#define LAPACK_zunmqr LAPACK_GLOBAL(zunmqr,ZUNMQR)\n#define LAPACK_sgelqf LAPACK_GLOBAL(sgelqf,SGELQF)\n#define LAPACK_dgelqf LAPACK_GLOBAL(dgelqf,DGELQF)\n#define LAPACK_cgelqf LAPACK_GLOBAL(cgelqf,CGELQF)\n#define LAPACK_zgelqf LAPACK_GLOBAL(zgelqf,ZGELQF)\n#define LAPACK_sorglq LAPACK_GLOBAL(sorglq,SORGLQ)\n#define LAPACK_dorglq LAPACK_GLOBAL(dorglq,DORGLQ)\n#define LAPACK_sormlq LAPACK_GLOBAL(sormlq,SORMLQ)\n#define LAPACK_dormlq LAPACK_GLOBAL(dormlq,DORMLQ)\n#define LAPACK_cunglq LAPACK_GLOBAL(cunglq,CUNGLQ)\n#define LAPACK_zunglq LAPACK_GLOBAL(zunglq,ZUNGLQ)\n#define LAPACK_cunmlq LAPACK_GLOBAL(cunmlq,CUNMLQ)\n#define LAPACK_zunmlq LAPACK_GLOBAL(zunmlq,ZUNMLQ)\n#define LAPACK_sgeqlf LAPACK_GLOBAL(sgeqlf,SGEQLF)\n#define LAPACK_dgeqlf LAPACK_GLOBAL(dgeqlf,DGEQLF)\n#define LAPACK_cgeqlf LAPACK_GLOBAL(cgeqlf,CGEQLF)\n#define LAPACK_zgeqlf LAPACK_GLOBAL(zgeqlf,ZGEQLF)\n#define LAPACK_sorgql LAPACK_GLOBAL(sorgql,SORGQL)\n#define LAPACK_dorgql LAPACK_GLOBAL(dorgql,DORGQL)\n#define LAPACK_cungql LAPACK_GLOBAL(cungql,CUNGQL)\n#define LAPACK_zungql LAPACK_GLOBAL(zungql,ZUNGQL)\n#define LAPACK_sormql LAPACK_GLOBAL(sormql,SORMQL)\n#define LAPACK_dormql LAPACK_GLOBAL(dormql,DORMQL)\n#define LAPACK_cunmql LAPACK_GLOBAL(cunmql,CUNMQL)\n#define LAPACK_zunmql LAPACK_GLOBAL(zunmql,ZUNMQL)\n#define LAPACK_sgerqf LAPACK_GLOBAL(sgerqf,SGERQF)\n#define LAPACK_dgerqf LAPACK_GLOBAL(dgerqf,DGERQF)\n#define LAPACK_cgerqf LAPACK_GLOBAL(cgerqf,CGERQF)\n#define LAPACK_zgerqf LAPACK_GLOBAL(zgerqf,ZGERQF)\n#define LAPACK_sorgrq LAPACK_GLOBAL(sorgrq,SORGRQ)\n#define LAPACK_dorgrq LAPACK_GLOBAL(dorgrq,DORGRQ)\n#define LAPACK_cungrq LAPACK_GLOBAL(cungrq,CUNGRQ)\n#define LAPACK_zungrq LAPACK_GLOBAL(zungrq,ZUNGRQ)\n#define LAPACK_sormrq LAPACK_GLOBAL(sormrq,SORMRQ)\n#define LAPACK_dormrq LAPACK_GLOBAL(dormrq,DORMRQ)\n#define LAPACK_cunmrq LAPACK_GLOBAL(cunmrq,CUNMRQ)\n#define LAPACK_zunmrq LAPACK_GLOBAL(zunmrq,ZUNMRQ)\n#define LAPACK_stzrzf LAPACK_GLOBAL(stzrzf,STZRZF)\n#define LAPACK_dtzrzf LAPACK_GLOBAL(dtzrzf,DTZRZF)\n#define LAPACK_ctzrzf LAPACK_GLOBAL(ctzrzf,CTZRZF)\n#define LAPACK_ztzrzf LAPACK_GLOBAL(ztzrzf,ZTZRZF)\n#define LAPACK_sormrz LAPACK_GLOBAL(sormrz,SORMRZ)\n#define LAPACK_dormrz LAPACK_GLOBAL(dormrz,DORMRZ)\n#define LAPACK_cunmrz LAPACK_GLOBAL(cunmrz,CUNMRZ)\n#define LAPACK_zunmrz LAPACK_GLOBAL(zunmrz,ZUNMRZ)\n#define LAPACK_sggqrf LAPACK_GLOBAL(sggqrf,SGGQRF)\n#define LAPACK_dggqrf LAPACK_GLOBAL(dggqrf,DGGQRF)\n#define LAPACK_cggqrf LAPACK_GLOBAL(cggqrf,CGGQRF)\n#define LAPACK_zggqrf LAPACK_GLOBAL(zggqrf,ZGGQRF)\n#define LAPACK_sggrqf LAPACK_GLOBAL(sggrqf,SGGRQF)\n#define LAPACK_dggrqf LAPACK_GLOBAL(dggrqf,DGGRQF)\n#define LAPACK_cggrqf LAPACK_GLOBAL(cggrqf,CGGRQF)\n#define LAPACK_zggrqf LAPACK_GLOBAL(zggrqf,ZGGRQF)\n#define LAPACK_sgebrd LAPACK_GLOBAL(sgebrd,SGEBRD)\n#define LAPACK_dgebrd LAPACK_GLOBAL(dgebrd,DGEBRD)\n#define LAPACK_cgebrd LAPACK_GLOBAL(cgebrd,CGEBRD)\n#define LAPACK_zgebrd LAPACK_GLOBAL(zgebrd,ZGEBRD)\n#define LAPACK_sgbbrd LAPACK_GLOBAL(sgbbrd,SGBBRD)\n#define LAPACK_dgbbrd LAPACK_GLOBAL(dgbbrd,DGBBRD)\n#define LAPACK_cgbbrd LAPACK_GLOBAL(cgbbrd,CGBBRD)\n#define LAPACK_zgbbrd LAPACK_GLOBAL(zgbbrd,ZGBBRD)\n#define LAPACK_sorgbr LAPACK_GLOBAL(sorgbr,SORGBR)\n#define LAPACK_dorgbr LAPACK_GLOBAL(dorgbr,DORGBR)\n#define LAPACK_sormbr LAPACK_GLOBAL(sormbr,SORMBR)\n#define LAPACK_dormbr LAPACK_GLOBAL(dormbr,DORMBR)\n#define LAPACK_cungbr LAPACK_GLOBAL(cungbr,CUNGBR)\n#define LAPACK_zungbr LAPACK_GLOBAL(zungbr,ZUNGBR)\n#define LAPACK_cunmbr LAPACK_GLOBAL(cunmbr,CUNMBR)\n#define LAPACK_zunmbr LAPACK_GLOBAL(zunmbr,ZUNMBR)\n#define LAPACK_sbdsqr LAPACK_GLOBAL(sbdsqr,SBDSQR)\n#define LAPACK_dbdsqr LAPACK_GLOBAL(dbdsqr,DBDSQR)\n#define LAPACK_cbdsqr LAPACK_GLOBAL(cbdsqr,CBDSQR)\n#define LAPACK_zbdsqr LAPACK_GLOBAL(zbdsqr,ZBDSQR)\n#define LAPACK_sbdsdc LAPACK_GLOBAL(sbdsdc,SBDSDC)\n#define LAPACK_dbdsdc LAPACK_GLOBAL(dbdsdc,DBDSDC)\n#define LAPACK_ssytrd LAPACK_GLOBAL(ssytrd,SSYTRD)\n#define LAPACK_dsytrd LAPACK_GLOBAL(dsytrd,DSYTRD)\n#define LAPACK_sorgtr LAPACK_GLOBAL(sorgtr,SORGTR)\n#define LAPACK_dorgtr LAPACK_GLOBAL(dorgtr,DORGTR)\n#define LAPACK_sormtr LAPACK_GLOBAL(sormtr,SORMTR)\n#define LAPACK_dormtr LAPACK_GLOBAL(dormtr,DORMTR)\n#define LAPACK_chetrd LAPACK_GLOBAL(chetrd,CHETRD)\n#define LAPACK_zhetrd LAPACK_GLOBAL(zhetrd,ZHETRD)\n#define LAPACK_cungtr LAPACK_GLOBAL(cungtr,CUNGTR)\n#define LAPACK_zungtr LAPACK_GLOBAL(zungtr,ZUNGTR)\n#define LAPACK_cunmtr LAPACK_GLOBAL(cunmtr,CUNMTR)\n#define LAPACK_zunmtr LAPACK_GLOBAL(zunmtr,ZUNMTR)\n#define LAPACK_ssptrd LAPACK_GLOBAL(ssptrd,SSPTRD)\n#define LAPACK_dsptrd LAPACK_GLOBAL(dsptrd,DSPTRD)\n#define LAPACK_sopgtr LAPACK_GLOBAL(sopgtr,SOPGTR)\n#define LAPACK_dopgtr LAPACK_GLOBAL(dopgtr,DOPGTR)\n#define LAPACK_sopmtr LAPACK_GLOBAL(sopmtr,SOPMTR)\n#define LAPACK_dopmtr LAPACK_GLOBAL(dopmtr,DOPMTR)\n#define LAPACK_chptrd LAPACK_GLOBAL(chptrd,CHPTRD)\n#define LAPACK_zhptrd LAPACK_GLOBAL(zhptrd,ZHPTRD)\n#define LAPACK_cupgtr LAPACK_GLOBAL(cupgtr,CUPGTR)\n#define LAPACK_zupgtr LAPACK_GLOBAL(zupgtr,ZUPGTR)\n#define LAPACK_cupmtr LAPACK_GLOBAL(cupmtr,CUPMTR)\n#define LAPACK_zupmtr LAPACK_GLOBAL(zupmtr,ZUPMTR)\n#define LAPACK_ssbtrd LAPACK_GLOBAL(ssbtrd,SSBTRD)\n#define LAPACK_dsbtrd LAPACK_GLOBAL(dsbtrd,DSBTRD)\n#define LAPACK_chbtrd LAPACK_GLOBAL(chbtrd,CHBTRD)\n#define LAPACK_zhbtrd LAPACK_GLOBAL(zhbtrd,ZHBTRD)\n#define LAPACK_ssterf LAPACK_GLOBAL(ssterf,SSTERF)\n#define LAPACK_dsterf LAPACK_GLOBAL(dsterf,DSTERF)\n#define LAPACK_ssteqr LAPACK_GLOBAL(ssteqr,SSTEQR)\n#define LAPACK_dsteqr LAPACK_GLOBAL(dsteqr,DSTEQR)\n#define LAPACK_csteqr LAPACK_GLOBAL(csteqr,CSTEQR)\n#define LAPACK_zsteqr LAPACK_GLOBAL(zsteqr,ZSTEQR)\n#define LAPACK_sstemr LAPACK_GLOBAL(sstemr,SSTEMR)\n#define LAPACK_dstemr LAPACK_GLOBAL(dstemr,DSTEMR)\n#define LAPACK_cstemr LAPACK_GLOBAL(cstemr,CSTEMR)\n#define LAPACK_zstemr LAPACK_GLOBAL(zstemr,ZSTEMR)\n#define LAPACK_sstedc LAPACK_GLOBAL(sstedc,SSTEDC)\n#define LAPACK_dstedc LAPACK_GLOBAL(dstedc,DSTEDC)\n#define LAPACK_cstedc LAPACK_GLOBAL(cstedc,CSTEDC)\n#define LAPACK_zstedc LAPACK_GLOBAL(zstedc,ZSTEDC)\n#define LAPACK_sstegr LAPACK_GLOBAL(sstegr,SSTEGR)\n#define LAPACK_dstegr LAPACK_GLOBAL(dstegr,DSTEGR)\n#define LAPACK_cstegr LAPACK_GLOBAL(cstegr,CSTEGR)\n#define LAPACK_zstegr LAPACK_GLOBAL(zstegr,ZSTEGR)\n#define LAPACK_spteqr LAPACK_GLOBAL(spteqr,SPTEQR)\n#define LAPACK_dpteqr LAPACK_GLOBAL(dpteqr,DPTEQR)\n#define LAPACK_cpteqr LAPACK_GLOBAL(cpteqr,CPTEQR)\n#define LAPACK_zpteqr LAPACK_GLOBAL(zpteqr,ZPTEQR)\n#define LAPACK_sstebz LAPACK_GLOBAL(sstebz,SSTEBZ)\n#define LAPACK_dstebz LAPACK_GLOBAL(dstebz,DSTEBZ)\n#define LAPACK_sstein LAPACK_GLOBAL(sstein,SSTEIN)\n#define LAPACK_dstein LAPACK_GLOBAL(dstein,DSTEIN)\n#define LAPACK_cstein LAPACK_GLOBAL(cstein,CSTEIN)\n#define LAPACK_zstein LAPACK_GLOBAL(zstein,ZSTEIN)\n#define LAPACK_sdisna LAPACK_GLOBAL(sdisna,SDISNA)\n#define LAPACK_ddisna LAPACK_GLOBAL(ddisna,DDISNA)\n#define LAPACK_ssygst LAPACK_GLOBAL(ssygst,SSYGST)\n#define LAPACK_dsygst LAPACK_GLOBAL(dsygst,DSYGST)\n#define LAPACK_chegst LAPACK_GLOBAL(chegst,CHEGST)\n#define LAPACK_zhegst LAPACK_GLOBAL(zhegst,ZHEGST)\n#define LAPACK_sspgst LAPACK_GLOBAL(sspgst,SSPGST)\n#define LAPACK_dspgst LAPACK_GLOBAL(dspgst,DSPGST)\n#define LAPACK_chpgst LAPACK_GLOBAL(chpgst,CHPGST)\n#define LAPACK_zhpgst LAPACK_GLOBAL(zhpgst,ZHPGST)\n#define LAPACK_ssbgst LAPACK_GLOBAL(ssbgst,SSBGST)\n#define LAPACK_dsbgst LAPACK_GLOBAL(dsbgst,DSBGST)\n#define LAPACK_chbgst LAPACK_GLOBAL(chbgst,CHBGST)\n#define LAPACK_zhbgst LAPACK_GLOBAL(zhbgst,ZHBGST)\n#define LAPACK_spbstf LAPACK_GLOBAL(spbstf,SPBSTF)\n#define LAPACK_dpbstf LAPACK_GLOBAL(dpbstf,DPBSTF)\n#define LAPACK_cpbstf LAPACK_GLOBAL(cpbstf,CPBSTF)\n#define LAPACK_zpbstf LAPACK_GLOBAL(zpbstf,ZPBSTF)\n#define LAPACK_sgehrd LAPACK_GLOBAL(sgehrd,SGEHRD)\n#define LAPACK_dgehrd LAPACK_GLOBAL(dgehrd,DGEHRD)\n#define LAPACK_cgehrd LAPACK_GLOBAL(cgehrd,CGEHRD)\n#define LAPACK_zgehrd LAPACK_GLOBAL(zgehrd,ZGEHRD)\n#define LAPACK_sorghr LAPACK_GLOBAL(sorghr,SORGHR)\n#define LAPACK_dorghr LAPACK_GLOBAL(dorghr,DORGHR)\n#define LAPACK_sormhr LAPACK_GLOBAL(sormhr,SORMHR)\n#define LAPACK_dormhr LAPACK_GLOBAL(dormhr,DORMHR)\n#define LAPACK_cunghr LAPACK_GLOBAL(cunghr,CUNGHR)\n#define LAPACK_zunghr LAPACK_GLOBAL(zunghr,ZUNGHR)\n#define LAPACK_cunmhr LAPACK_GLOBAL(cunmhr,CUNMHR)\n#define LAPACK_zunmhr LAPACK_GLOBAL(zunmhr,ZUNMHR)\n#define LAPACK_sgebal LAPACK_GLOBAL(sgebal,SGEBAL)\n#define LAPACK_dgebal LAPACK_GLOBAL(dgebal,DGEBAL)\n#define LAPACK_cgebal LAPACK_GLOBAL(cgebal,CGEBAL)\n#define LAPACK_zgebal LAPACK_GLOBAL(zgebal,ZGEBAL)\n#define LAPACK_sgebak LAPACK_GLOBAL(sgebak,SGEBAK)\n#define LAPACK_dgebak LAPACK_GLOBAL(dgebak,DGEBAK)\n#define LAPACK_cgebak LAPACK_GLOBAL(cgebak,CGEBAK)\n#define LAPACK_zgebak LAPACK_GLOBAL(zgebak,ZGEBAK)\n#define LAPACK_shseqr LAPACK_GLOBAL(shseqr,SHSEQR)\n#define LAPACK_dhseqr LAPACK_GLOBAL(dhseqr,DHSEQR)\n#define LAPACK_chseqr LAPACK_GLOBAL(chseqr,CHSEQR)\n#define LAPACK_zhseqr LAPACK_GLOBAL(zhseqr,ZHSEQR)\n#define LAPACK_shsein LAPACK_GLOBAL(shsein,SHSEIN)\n#define LAPACK_dhsein LAPACK_GLOBAL(dhsein,DHSEIN)\n#define LAPACK_chsein LAPACK_GLOBAL(chsein,CHSEIN)\n#define LAPACK_zhsein LAPACK_GLOBAL(zhsein,ZHSEIN)\n#define LAPACK_strevc LAPACK_GLOBAL(strevc,STREVC)\n#define LAPACK_dtrevc LAPACK_GLOBAL(dtrevc,DTREVC)\n#define LAPACK_ctrevc LAPACK_GLOBAL(ctrevc,CTREVC)\n#define LAPACK_ztrevc LAPACK_GLOBAL(ztrevc,ZTREVC)\n#define LAPACK_strsna LAPACK_GLOBAL(strsna,STRSNA)\n#define LAPACK_dtrsna LAPACK_GLOBAL(dtrsna,DTRSNA)\n#define LAPACK_ctrsna LAPACK_GLOBAL(ctrsna,CTRSNA)\n#define LAPACK_ztrsna LAPACK_GLOBAL(ztrsna,ZTRSNA)\n#define LAPACK_strexc LAPACK_GLOBAL(strexc,STREXC)\n#define LAPACK_dtrexc LAPACK_GLOBAL(dtrexc,DTREXC)\n#define LAPACK_ctrexc LAPACK_GLOBAL(ctrexc,CTREXC)\n#define LAPACK_ztrexc LAPACK_GLOBAL(ztrexc,ZTREXC)\n#define LAPACK_strsen LAPACK_GLOBAL(strsen,STRSEN)\n#define LAPACK_dtrsen LAPACK_GLOBAL(dtrsen,DTRSEN)\n#define LAPACK_ctrsen LAPACK_GLOBAL(ctrsen,CTRSEN)\n#define LAPACK_ztrsen LAPACK_GLOBAL(ztrsen,ZTRSEN)\n#define LAPACK_strsyl LAPACK_GLOBAL(strsyl,STRSYL)\n#define LAPACK_dtrsyl LAPACK_GLOBAL(dtrsyl,DTRSYL)\n#define LAPACK_ctrsyl LAPACK_GLOBAL(ctrsyl,CTRSYL)\n#define LAPACK_ztrsyl LAPACK_GLOBAL(ztrsyl,ZTRSYL)\n#define LAPACK_sgghrd LAPACK_GLOBAL(sgghrd,SGGHRD)\n#define LAPACK_dgghrd LAPACK_GLOBAL(dgghrd,DGGHRD)\n#define LAPACK_cgghrd LAPACK_GLOBAL(cgghrd,CGGHRD)\n#define LAPACK_zgghrd LAPACK_GLOBAL(zgghrd,ZGGHRD)\n#define LAPACK_sggbal LAPACK_GLOBAL(sggbal,SGGBAL)\n#define LAPACK_dggbal LAPACK_GLOBAL(dggbal,DGGBAL)\n#define LAPACK_cggbal LAPACK_GLOBAL(cggbal,CGGBAL)\n#define LAPACK_zggbal LAPACK_GLOBAL(zggbal,ZGGBAL)\n#define LAPACK_sggbak LAPACK_GLOBAL(sggbak,SGGBAK)\n#define LAPACK_dggbak LAPACK_GLOBAL(dggbak,DGGBAK)\n#define LAPACK_cggbak LAPACK_GLOBAL(cggbak,CGGBAK)\n#define LAPACK_zggbak LAPACK_GLOBAL(zggbak,ZGGBAK)\n#define LAPACK_shgeqz LAPACK_GLOBAL(shgeqz,SHGEQZ)\n#define LAPACK_dhgeqz LAPACK_GLOBAL(dhgeqz,DHGEQZ)\n#define LAPACK_chgeqz LAPACK_GLOBAL(chgeqz,CHGEQZ)\n#define LAPACK_zhgeqz LAPACK_GLOBAL(zhgeqz,ZHGEQZ)\n#define LAPACK_stgevc LAPACK_GLOBAL(stgevc,STGEVC)\n#define LAPACK_dtgevc LAPACK_GLOBAL(dtgevc,DTGEVC)\n#define LAPACK_ctgevc LAPACK_GLOBAL(ctgevc,CTGEVC)\n#define LAPACK_ztgevc LAPACK_GLOBAL(ztgevc,ZTGEVC)\n#define LAPACK_stgexc LAPACK_GLOBAL(stgexc,STGEXC)\n#define LAPACK_dtgexc LAPACK_GLOBAL(dtgexc,DTGEXC)\n#define LAPACK_ctgexc LAPACK_GLOBAL(ctgexc,CTGEXC)\n#define LAPACK_ztgexc LAPACK_GLOBAL(ztgexc,ZTGEXC)\n#define LAPACK_stgsen LAPACK_GLOBAL(stgsen,STGSEN)\n#define LAPACK_dtgsen LAPACK_GLOBAL(dtgsen,DTGSEN)\n#define LAPACK_ctgsen LAPACK_GLOBAL(ctgsen,CTGSEN)\n#define LAPACK_ztgsen LAPACK_GLOBAL(ztgsen,ZTGSEN)\n#define LAPACK_stgsyl LAPACK_GLOBAL(stgsyl,STGSYL)\n#define LAPACK_dtgsyl LAPACK_GLOBAL(dtgsyl,DTGSYL)\n#define LAPACK_ctgsyl LAPACK_GLOBAL(ctgsyl,CTGSYL)\n#define LAPACK_ztgsyl LAPACK_GLOBAL(ztgsyl,ZTGSYL)\n#define LAPACK_stgsna LAPACK_GLOBAL(stgsna,STGSNA)\n#define LAPACK_dtgsna LAPACK_GLOBAL(dtgsna,DTGSNA)\n#define LAPACK_ctgsna LAPACK_GLOBAL(ctgsna,CTGSNA)\n#define LAPACK_ztgsna LAPACK_GLOBAL(ztgsna,ZTGSNA)\n#define LAPACK_sggsvp LAPACK_GLOBAL(sggsvp,SGGSVP)\n#define LAPACK_dggsvp LAPACK_GLOBAL(dggsvp,DGGSVP)\n#define LAPACK_cggsvp LAPACK_GLOBAL(cggsvp,CGGSVP)\n#define LAPACK_zggsvp LAPACK_GLOBAL(zggsvp,ZGGSVP)\n#define LAPACK_stgsja LAPACK_GLOBAL(stgsja,STGSJA)\n#define LAPACK_dtgsja LAPACK_GLOBAL(dtgsja,DTGSJA)\n#define LAPACK_ctgsja LAPACK_GLOBAL(ctgsja,CTGSJA)\n#define LAPACK_ztgsja LAPACK_GLOBAL(ztgsja,ZTGSJA)\n#define LAPACK_sgels LAPACK_GLOBAL(sgels,SGELS)\n#define LAPACK_dgels LAPACK_GLOBAL(dgels,DGELS)\n#define LAPACK_cgels LAPACK_GLOBAL(cgels,CGELS)\n#define LAPACK_zgels LAPACK_GLOBAL(zgels,ZGELS)\n#define LAPACK_sgelsy LAPACK_GLOBAL(sgelsy,SGELSY)\n#define LAPACK_dgelsy LAPACK_GLOBAL(dgelsy,DGELSY)\n#define LAPACK_cgelsy LAPACK_GLOBAL(cgelsy,CGELSY)\n#define LAPACK_zgelsy LAPACK_GLOBAL(zgelsy,ZGELSY)\n#define LAPACK_sgelss LAPACK_GLOBAL(sgelss,SGELSS)\n#define LAPACK_dgelss LAPACK_GLOBAL(dgelss,DGELSS)\n#define LAPACK_cgelss LAPACK_GLOBAL(cgelss,CGELSS)\n#define LAPACK_zgelss LAPACK_GLOBAL(zgelss,ZGELSS)\n#define LAPACK_sgelsd LAPACK_GLOBAL(sgelsd,SGELSD)\n#define LAPACK_dgelsd LAPACK_GLOBAL(dgelsd,DGELSD)\n#define LAPACK_cgelsd LAPACK_GLOBAL(cgelsd,CGELSD)\n#define LAPACK_zgelsd LAPACK_GLOBAL(zgelsd,ZGELSD)\n#define LAPACK_sgglse LAPACK_GLOBAL(sgglse,SGGLSE)\n#define LAPACK_dgglse LAPACK_GLOBAL(dgglse,DGGLSE)\n#define LAPACK_cgglse LAPACK_GLOBAL(cgglse,CGGLSE)\n#define LAPACK_zgglse LAPACK_GLOBAL(zgglse,ZGGLSE)\n#define LAPACK_sggglm LAPACK_GLOBAL(sggglm,SGGGLM)\n#define LAPACK_dggglm LAPACK_GLOBAL(dggglm,DGGGLM)\n#define LAPACK_cggglm LAPACK_GLOBAL(cggglm,CGGGLM)\n#define LAPACK_zggglm LAPACK_GLOBAL(zggglm,ZGGGLM)\n#define LAPACK_ssyev LAPACK_GLOBAL(ssyev,SSYEV)\n#define LAPACK_dsyev LAPACK_GLOBAL(dsyev,DSYEV)\n#define LAPACK_cheev LAPACK_GLOBAL(cheev,CHEEV)\n#define LAPACK_zheev LAPACK_GLOBAL(zheev,ZHEEV)\n#define LAPACK_ssyevd LAPACK_GLOBAL(ssyevd,SSYEVD)\n#define LAPACK_dsyevd LAPACK_GLOBAL(dsyevd,DSYEVD)\n#define LAPACK_cheevd LAPACK_GLOBAL(cheevd,CHEEVD)\n#define LAPACK_zheevd LAPACK_GLOBAL(zheevd,ZHEEVD)\n#define LAPACK_ssyevx LAPACK_GLOBAL(ssyevx,SSYEVX)\n#define LAPACK_dsyevx LAPACK_GLOBAL(dsyevx,DSYEVX)\n#define LAPACK_cheevx LAPACK_GLOBAL(cheevx,CHEEVX)\n#define LAPACK_zheevx LAPACK_GLOBAL(zheevx,ZHEEVX)\n#define LAPACK_ssyevr LAPACK_GLOBAL(ssyevr,SSYEVR)\n#define LAPACK_dsyevr LAPACK_GLOBAL(dsyevr,DSYEVR)\n#define LAPACK_cheevr LAPACK_GLOBAL(cheevr,CHEEVR)\n#define LAPACK_zheevr LAPACK_GLOBAL(zheevr,ZHEEVR)\n#define LAPACK_sspev LAPACK_GLOBAL(sspev,SSPEV)\n#define LAPACK_dspev LAPACK_GLOBAL(dspev,DSPEV)\n#define LAPACK_chpev LAPACK_GLOBAL(chpev,CHPEV)\n#define LAPACK_zhpev LAPACK_GLOBAL(zhpev,ZHPEV)\n#define LAPACK_sspevd LAPACK_GLOBAL(sspevd,SSPEVD)\n#define LAPACK_dspevd LAPACK_GLOBAL(dspevd,DSPEVD)\n#define LAPACK_chpevd LAPACK_GLOBAL(chpevd,CHPEVD)\n#define LAPACK_zhpevd LAPACK_GLOBAL(zhpevd,ZHPEVD)\n#define LAPACK_sspevx LAPACK_GLOBAL(sspevx,SSPEVX)\n#define LAPACK_dspevx LAPACK_GLOBAL(dspevx,DSPEVX)\n#define LAPACK_chpevx LAPACK_GLOBAL(chpevx,CHPEVX)\n#define LAPACK_zhpevx LAPACK_GLOBAL(zhpevx,ZHPEVX)\n#define LAPACK_ssbev LAPACK_GLOBAL(ssbev,SSBEV)\n#define LAPACK_dsbev LAPACK_GLOBAL(dsbev,DSBEV)\n#define LAPACK_chbev LAPACK_GLOBAL(chbev,CHBEV)\n#define LAPACK_zhbev LAPACK_GLOBAL(zhbev,ZHBEV)\n#define LAPACK_ssbevd LAPACK_GLOBAL(ssbevd,SSBEVD)\n#define LAPACK_dsbevd LAPACK_GLOBAL(dsbevd,DSBEVD)\n#define LAPACK_chbevd LAPACK_GLOBAL(chbevd,CHBEVD)\n#define LAPACK_zhbevd LAPACK_GLOBAL(zhbevd,ZHBEVD)\n#define LAPACK_ssbevx LAPACK_GLOBAL(ssbevx,SSBEVX)\n#define LAPACK_dsbevx LAPACK_GLOBAL(dsbevx,DSBEVX)\n#define LAPACK_chbevx LAPACK_GLOBAL(chbevx,CHBEVX)\n#define LAPACK_zhbevx LAPACK_GLOBAL(zhbevx,ZHBEVX)\n#define LAPACK_sstev LAPACK_GLOBAL(sstev,SSTEV)\n#define LAPACK_dstev LAPACK_GLOBAL(dstev,DSTEV)\n#define LAPACK_sstevd LAPACK_GLOBAL(sstevd,SSTEVD)\n#define LAPACK_dstevd LAPACK_GLOBAL(dstevd,DSTEVD)\n#define LAPACK_sstevx LAPACK_GLOBAL(sstevx,SSTEVX)\n#define LAPACK_dstevx LAPACK_GLOBAL(dstevx,DSTEVX)\n#define LAPACK_sstevr LAPACK_GLOBAL(sstevr,SSTEVR)\n#define LAPACK_dstevr LAPACK_GLOBAL(dstevr,DSTEVR)\n#define LAPACK_sgees LAPACK_GLOBAL(sgees,SGEES)\n#define LAPACK_dgees LAPACK_GLOBAL(dgees,DGEES)\n#define LAPACK_cgees LAPACK_GLOBAL(cgees,CGEES)\n#define LAPACK_zgees LAPACK_GLOBAL(zgees,ZGEES)\n#define LAPACK_sgeesx LAPACK_GLOBAL(sgeesx,SGEESX)\n#define LAPACK_dgeesx LAPACK_GLOBAL(dgeesx,DGEESX)\n#define LAPACK_cgeesx LAPACK_GLOBAL(cgeesx,CGEESX)\n#define LAPACK_zgeesx LAPACK_GLOBAL(zgeesx,ZGEESX)\n#define LAPACK_sgeev LAPACK_GLOBAL(sgeev,SGEEV)\n#define LAPACK_dgeev LAPACK_GLOBAL(dgeev,DGEEV)\n#define LAPACK_cgeev LAPACK_GLOBAL(cgeev,CGEEV)\n#define LAPACK_zgeev LAPACK_GLOBAL(zgeev,ZGEEV)\n#define LAPACK_sgeevx LAPACK_GLOBAL(sgeevx,SGEEVX)\n#define LAPACK_dgeevx LAPACK_GLOBAL(dgeevx,DGEEVX)\n#define LAPACK_cgeevx LAPACK_GLOBAL(cgeevx,CGEEVX)\n#define LAPACK_zgeevx LAPACK_GLOBAL(zgeevx,ZGEEVX)\n#define LAPACK_sgesvd LAPACK_GLOBAL(sgesvd,SGESVD)\n#define LAPACK_dgesvd LAPACK_GLOBAL(dgesvd,DGESVD)\n#define LAPACK_cgesvd LAPACK_GLOBAL(cgesvd,CGESVD)\n#define LAPACK_zgesvd LAPACK_GLOBAL(zgesvd,ZGESVD)\n#define LAPACK_sgesdd LAPACK_GLOBAL(sgesdd,SGESDD)\n#define LAPACK_dgesdd LAPACK_GLOBAL(dgesdd,DGESDD)\n#define LAPACK_cgesdd LAPACK_GLOBAL(cgesdd,CGESDD)\n#define LAPACK_zgesdd LAPACK_GLOBAL(zgesdd,ZGESDD)\n#define LAPACK_dgejsv LAPACK_GLOBAL(dgejsv,DGEJSV)\n#define LAPACK_sgejsv LAPACK_GLOBAL(sgejsv,SGEJSV)\n#define LAPACK_dgesvj LAPACK_GLOBAL(dgesvj,DGESVJ)\n#define LAPACK_sgesvj LAPACK_GLOBAL(sgesvj,SGESVJ)\n#define LAPACK_sggsvd LAPACK_GLOBAL(sggsvd,SGGSVD)\n#define LAPACK_dggsvd LAPACK_GLOBAL(dggsvd,DGGSVD)\n#define LAPACK_cggsvd LAPACK_GLOBAL(cggsvd,CGGSVD)\n#define LAPACK_zggsvd LAPACK_GLOBAL(zggsvd,ZGGSVD)\n#define LAPACK_ssygv LAPACK_GLOBAL(ssygv,SSYGV)\n#define LAPACK_dsygv LAPACK_GLOBAL(dsygv,DSYGV)\n#define LAPACK_chegv LAPACK_GLOBAL(chegv,CHEGV)\n#define LAPACK_zhegv LAPACK_GLOBAL(zhegv,ZHEGV)\n#define LAPACK_ssygvd LAPACK_GLOBAL(ssygvd,SSYGVD)\n#define LAPACK_dsygvd LAPACK_GLOBAL(dsygvd,DSYGVD)\n#define LAPACK_chegvd LAPACK_GLOBAL(chegvd,CHEGVD)\n#define LAPACK_zhegvd LAPACK_GLOBAL(zhegvd,ZHEGVD)\n#define LAPACK_ssygvx LAPACK_GLOBAL(ssygvx,SSYGVX)\n#define LAPACK_dsygvx LAPACK_GLOBAL(dsygvx,DSYGVX)\n#define LAPACK_chegvx LAPACK_GLOBAL(chegvx,CHEGVX)\n#define LAPACK_zhegvx LAPACK_GLOBAL(zhegvx,ZHEGVX)\n#define LAPACK_sspgv LAPACK_GLOBAL(sspgv,SSPGV)\n#define LAPACK_dspgv LAPACK_GLOBAL(dspgv,DSPGV)\n#define LAPACK_chpgv LAPACK_GLOBAL(chpgv,CHPGV)\n#define LAPACK_zhpgv LAPACK_GLOBAL(zhpgv,ZHPGV)\n#define LAPACK_sspgvd LAPACK_GLOBAL(sspgvd,SSPGVD)\n#define LAPACK_dspgvd LAPACK_GLOBAL(dspgvd,DSPGVD)\n#define LAPACK_chpgvd LAPACK_GLOBAL(chpgvd,CHPGVD)\n#define LAPACK_zhpgvd LAPACK_GLOBAL(zhpgvd,ZHPGVD)\n#define LAPACK_sspgvx LAPACK_GLOBAL(sspgvx,SSPGVX)\n#define LAPACK_dspgvx LAPACK_GLOBAL(dspgvx,DSPGVX)\n#define LAPACK_chpgvx LAPACK_GLOBAL(chpgvx,CHPGVX)\n#define LAPACK_zhpgvx LAPACK_GLOBAL(zhpgvx,ZHPGVX)\n#define LAPACK_ssbgv LAPACK_GLOBAL(ssbgv,SSBGV)\n#define LAPACK_dsbgv LAPACK_GLOBAL(dsbgv,DSBGV)\n#define LAPACK_chbgv LAPACK_GLOBAL(chbgv,CHBGV)\n#define LAPACK_zhbgv LAPACK_GLOBAL(zhbgv,ZHBGV)\n#define LAPACK_ssbgvd LAPACK_GLOBAL(ssbgvd,SSBGVD)\n#define LAPACK_dsbgvd LAPACK_GLOBAL(dsbgvd,DSBGVD)\n#define LAPACK_chbgvd LAPACK_GLOBAL(chbgvd,CHBGVD)\n#define LAPACK_zhbgvd LAPACK_GLOBAL(zhbgvd,ZHBGVD)\n#define LAPACK_ssbgvx LAPACK_GLOBAL(ssbgvx,SSBGVX)\n#define LAPACK_dsbgvx LAPACK_GLOBAL(dsbgvx,DSBGVX)\n#define LAPACK_chbgvx LAPACK_GLOBAL(chbgvx,CHBGVX)\n#define LAPACK_zhbgvx LAPACK_GLOBAL(zhbgvx,ZHBGVX)\n#define LAPACK_sgges LAPACK_GLOBAL(sgges,SGGES)\n#define LAPACK_dgges LAPACK_GLOBAL(dgges,DGGES)\n#define LAPACK_cgges LAPACK_GLOBAL(cgges,CGGES)\n#define LAPACK_zgges LAPACK_GLOBAL(zgges,ZGGES)\n#define LAPACK_sggesx LAPACK_GLOBAL(sggesx,SGGESX)\n#define LAPACK_dggesx LAPACK_GLOBAL(dggesx,DGGESX)\n#define LAPACK_cggesx LAPACK_GLOBAL(cggesx,CGGESX)\n#define LAPACK_zggesx LAPACK_GLOBAL(zggesx,ZGGESX)\n#define LAPACK_sggev LAPACK_GLOBAL(sggev,SGGEV)\n#define LAPACK_dggev LAPACK_GLOBAL(dggev,DGGEV)\n#define LAPACK_cggev LAPACK_GLOBAL(cggev,CGGEV)\n#define LAPACK_zggev LAPACK_GLOBAL(zggev,ZGGEV)\n#define LAPACK_sggevx LAPACK_GLOBAL(sggevx,SGGEVX)\n#define LAPACK_dggevx LAPACK_GLOBAL(dggevx,DGGEVX)\n#define LAPACK_cggevx LAPACK_GLOBAL(cggevx,CGGEVX)\n#define LAPACK_zggevx LAPACK_GLOBAL(zggevx,ZGGEVX)\n#define LAPACK_dsfrk LAPACK_GLOBAL(dsfrk,DSFRK)\n#define LAPACK_ssfrk LAPACK_GLOBAL(ssfrk,SSFRK)\n#define LAPACK_zhfrk LAPACK_GLOBAL(zhfrk,ZHFRK)\n#define LAPACK_chfrk LAPACK_GLOBAL(chfrk,CHFRK)\n#define LAPACK_dtfsm LAPACK_GLOBAL(dtfsm,DTFSM)\n#define LAPACK_stfsm LAPACK_GLOBAL(stfsm,STFSM)\n#define LAPACK_ztfsm LAPACK_GLOBAL(ztfsm,ZTFSM)\n#define LAPACK_ctfsm LAPACK_GLOBAL(ctfsm,CTFSM)\n#define LAPACK_dtfttp LAPACK_GLOBAL(dtfttp,DTFTTP)\n#define LAPACK_stfttp LAPACK_GLOBAL(stfttp,STFTTP)\n#define LAPACK_ztfttp LAPACK_GLOBAL(ztfttp,ZTFTTP)\n#define LAPACK_ctfttp LAPACK_GLOBAL(ctfttp,CTFTTP)\n#define LAPACK_dtfttr LAPACK_GLOBAL(dtfttr,DTFTTR)\n#define LAPACK_stfttr LAPACK_GLOBAL(stfttr,STFTTR)\n#define LAPACK_ztfttr LAPACK_GLOBAL(ztfttr,ZTFTTR)\n#define LAPACK_ctfttr LAPACK_GLOBAL(ctfttr,CTFTTR)\n#define LAPACK_dtpttf LAPACK_GLOBAL(dtpttf,DTPTTF)\n#define LAPACK_stpttf LAPACK_GLOBAL(stpttf,STPTTF)\n#define LAPACK_ztpttf LAPACK_GLOBAL(ztpttf,ZTPTTF)\n#define LAPACK_ctpttf LAPACK_GLOBAL(ctpttf,CTPTTF)\n#define LAPACK_dtpttr LAPACK_GLOBAL(dtpttr,DTPTTR)\n#define LAPACK_stpttr LAPACK_GLOBAL(stpttr,STPTTR)\n#define LAPACK_ztpttr LAPACK_GLOBAL(ztpttr,ZTPTTR)\n#define LAPACK_ctpttr LAPACK_GLOBAL(ctpttr,CTPTTR)\n#define LAPACK_dtrttf LAPACK_GLOBAL(dtrttf,DTRTTF)\n#define LAPACK_strttf LAPACK_GLOBAL(strttf,STRTTF)\n#define LAPACK_ztrttf LAPACK_GLOBAL(ztrttf,ZTRTTF)\n#define LAPACK_ctrttf LAPACK_GLOBAL(ctrttf,CTRTTF)\n#define LAPACK_dtrttp LAPACK_GLOBAL(dtrttp,DTRTTP)\n#define LAPACK_strttp LAPACK_GLOBAL(strttp,STRTTP)\n#define LAPACK_ztrttp LAPACK_GLOBAL(ztrttp,ZTRTTP)\n#define LAPACK_ctrttp LAPACK_GLOBAL(ctrttp,CTRTTP)\n#define LAPACK_sgeqrfp LAPACK_GLOBAL(sgeqrfp,SGEQRFP)\n#define LAPACK_dgeqrfp LAPACK_GLOBAL(dgeqrfp,DGEQRFP)\n#define LAPACK_cgeqrfp LAPACK_GLOBAL(cgeqrfp,CGEQRFP)\n#define LAPACK_zgeqrfp LAPACK_GLOBAL(zgeqrfp,ZGEQRFP)\n#define LAPACK_clacgv LAPACK_GLOBAL(clacgv,CLACGV)\n#define LAPACK_zlacgv LAPACK_GLOBAL(zlacgv,ZLACGV)\n#define LAPACK_slarnv LAPACK_GLOBAL(slarnv,SLARNV)\n#define LAPACK_dlarnv LAPACK_GLOBAL(dlarnv,DLARNV)\n#define LAPACK_clarnv LAPACK_GLOBAL(clarnv,CLARNV)\n#define LAPACK_zlarnv LAPACK_GLOBAL(zlarnv,ZLARNV)\n#define LAPACK_sgeqr2 LAPACK_GLOBAL(sgeqr2,SGEQR2)\n#define LAPACK_dgeqr2 LAPACK_GLOBAL(dgeqr2,DGEQR2)\n#define LAPACK_cgeqr2 LAPACK_GLOBAL(cgeqr2,CGEQR2)\n#define LAPACK_zgeqr2 LAPACK_GLOBAL(zgeqr2,ZGEQR2)\n#define LAPACK_slacpy LAPACK_GLOBAL(slacpy,SLACPY)\n#define LAPACK_dlacpy LAPACK_GLOBAL(dlacpy,DLACPY)\n#define LAPACK_clacpy LAPACK_GLOBAL(clacpy,CLACPY)\n#define LAPACK_zlacpy LAPACK_GLOBAL(zlacpy,ZLACPY)\n#define LAPACK_sgetf2 LAPACK_GLOBAL(sgetf2,SGETF2)\n#define LAPACK_dgetf2 LAPACK_GLOBAL(dgetf2,DGETF2)\n#define LAPACK_cgetf2 LAPACK_GLOBAL(cgetf2,CGETF2)\n#define LAPACK_zgetf2 LAPACK_GLOBAL(zgetf2,ZGETF2)\n#define LAPACK_slaswp LAPACK_GLOBAL(slaswp,SLASWP)\n#define LAPACK_dlaswp LAPACK_GLOBAL(dlaswp,DLASWP)\n#define LAPACK_claswp LAPACK_GLOBAL(claswp,CLASWP)\n#define LAPACK_zlaswp LAPACK_GLOBAL(zlaswp,ZLASWP)\n#define LAPACK_slange LAPACK_GLOBAL(slange,SLANGE)\n#define LAPACK_dlange LAPACK_GLOBAL(dlange,DLANGE)\n#define LAPACK_clange LAPACK_GLOBAL(clange,CLANGE)\n#define LAPACK_zlange LAPACK_GLOBAL(zlange,ZLANGE)\n#define LAPACK_clanhe LAPACK_GLOBAL(clanhe,CLANHE)\n#define LAPACK_zlanhe LAPACK_GLOBAL(zlanhe,ZLANHE)\n#define LAPACK_slansy LAPACK_GLOBAL(slansy,SLANSY)\n#define LAPACK_dlansy LAPACK_GLOBAL(dlansy,DLANSY)\n#define LAPACK_clansy LAPACK_GLOBAL(clansy,CLANSY)\n#define LAPACK_zlansy LAPACK_GLOBAL(zlansy,ZLANSY)\n#define LAPACK_slantr LAPACK_GLOBAL(slantr,SLANTR)\n#define LAPACK_dlantr LAPACK_GLOBAL(dlantr,DLANTR)\n#define LAPACK_clantr LAPACK_GLOBAL(clantr,CLANTR)\n#define LAPACK_zlantr LAPACK_GLOBAL(zlantr,ZLANTR)\n#define LAPACK_slamch LAPACK_GLOBAL(slamch,SLAMCH)\n#define LAPACK_dlamch LAPACK_GLOBAL(dlamch,DLAMCH)\n#define LAPACK_sgelq2 LAPACK_GLOBAL(sgelq2,SGELQ2)\n#define LAPACK_dgelq2 LAPACK_GLOBAL(dgelq2,DGELQ2)\n#define LAPACK_cgelq2 LAPACK_GLOBAL(cgelq2,CGELQ2)\n#define LAPACK_zgelq2 LAPACK_GLOBAL(zgelq2,ZGELQ2)\n#define LAPACK_slarfb LAPACK_GLOBAL(slarfb,SLARFB)\n#define LAPACK_dlarfb LAPACK_GLOBAL(dlarfb,DLARFB)\n#define LAPACK_clarfb LAPACK_GLOBAL(clarfb,CLARFB)\n#define LAPACK_zlarfb LAPACK_GLOBAL(zlarfb,ZLARFB)\n#define LAPACK_slarfg LAPACK_GLOBAL(slarfg,SLARFG)\n#define LAPACK_dlarfg LAPACK_GLOBAL(dlarfg,DLARFG)\n#define LAPACK_clarfg LAPACK_GLOBAL(clarfg,CLARFG)\n#define LAPACK_zlarfg LAPACK_GLOBAL(zlarfg,ZLARFG)\n#define LAPACK_slarft LAPACK_GLOBAL(slarft,SLARFT)\n#define LAPACK_dlarft LAPACK_GLOBAL(dlarft,DLARFT)\n#define LAPACK_clarft LAPACK_GLOBAL(clarft,CLARFT)\n#define LAPACK_zlarft LAPACK_GLOBAL(zlarft,ZLARFT)\n#define LAPACK_slarfx LAPACK_GLOBAL(slarfx,SLARFX)\n#define LAPACK_dlarfx LAPACK_GLOBAL(dlarfx,DLARFX)\n#define LAPACK_clarfx LAPACK_GLOBAL(clarfx,CLARFX)\n#define LAPACK_zlarfx LAPACK_GLOBAL(zlarfx,ZLARFX)\n#define LAPACK_slatms LAPACK_GLOBAL(slatms,SLATMS)\n#define LAPACK_dlatms LAPACK_GLOBAL(dlatms,DLATMS)\n#define LAPACK_clatms LAPACK_GLOBAL(clatms,CLATMS)\n#define LAPACK_zlatms LAPACK_GLOBAL(zlatms,ZLATMS)\n#define LAPACK_slag2d LAPACK_GLOBAL(slag2d,SLAG2D)\n#define LAPACK_dlag2s LAPACK_GLOBAL(dlag2s,DLAG2S)\n#define LAPACK_clag2z LAPACK_GLOBAL(clag2z,CLAG2Z)\n#define LAPACK_zlag2c LAPACK_GLOBAL(zlag2c,ZLAG2C)\n#define LAPACK_slauum LAPACK_GLOBAL(slauum,SLAUUM)\n#define LAPACK_dlauum LAPACK_GLOBAL(dlauum,DLAUUM)\n#define LAPACK_clauum LAPACK_GLOBAL(clauum,CLAUUM)\n#define LAPACK_zlauum LAPACK_GLOBAL(zlauum,ZLAUUM)\n#define LAPACK_slagge LAPACK_GLOBAL(slagge,SLAGGE)\n#define LAPACK_dlagge LAPACK_GLOBAL(dlagge,DLAGGE)\n#define LAPACK_clagge LAPACK_GLOBAL(clagge,CLAGGE)\n#define LAPACK_zlagge LAPACK_GLOBAL(zlagge,ZLAGGE)\n#define LAPACK_slaset LAPACK_GLOBAL(slaset,SLASET)\n#define LAPACK_dlaset LAPACK_GLOBAL(dlaset,DLASET)\n#define LAPACK_claset LAPACK_GLOBAL(claset,CLASET)\n#define LAPACK_zlaset LAPACK_GLOBAL(zlaset,ZLASET)\n#define LAPACK_slasrt LAPACK_GLOBAL(slasrt,SLASRT)\n#define LAPACK_dlasrt LAPACK_GLOBAL(dlasrt,DLASRT)\n#define LAPACK_slagsy LAPACK_GLOBAL(slagsy,SLAGSY)\n#define LAPACK_dlagsy LAPACK_GLOBAL(dlagsy,DLAGSY)\n#define LAPACK_clagsy LAPACK_GLOBAL(clagsy,CLAGSY)\n#define LAPACK_zlagsy LAPACK_GLOBAL(zlagsy,ZLAGSY)\n#define LAPACK_claghe LAPACK_GLOBAL(claghe,CLAGHE)\n#define LAPACK_zlaghe LAPACK_GLOBAL(zlaghe,ZLAGHE)\n#define LAPACK_slapmr LAPACK_GLOBAL(slapmr,SLAPMR)\n#define LAPACK_dlapmr LAPACK_GLOBAL(dlapmr,DLAPMR)\n#define LAPACK_clapmr LAPACK_GLOBAL(clapmr,CLAPMR)\n#define LAPACK_zlapmr LAPACK_GLOBAL(zlapmr,ZLAPMR)\n#define LAPACK_slapy2 LAPACK_GLOBAL(slapy2,SLAPY2)\n#define LAPACK_dlapy2 LAPACK_GLOBAL(dlapy2,DLAPY2)\n#define LAPACK_slapy3 LAPACK_GLOBAL(slapy3,SLAPY3)\n#define LAPACK_dlapy3 LAPACK_GLOBAL(dlapy3,DLAPY3)\n#define LAPACK_slartgp LAPACK_GLOBAL(slartgp,SLARTGP)\n#define LAPACK_dlartgp LAPACK_GLOBAL(dlartgp,DLARTGP)\n#define LAPACK_slartgs LAPACK_GLOBAL(slartgs,SLARTGS)\n#define LAPACK_dlartgs LAPACK_GLOBAL(dlartgs,DLARTGS)\n// LAPACK 3.3.0\n#define LAPACK_cbbcsd LAPACK_GLOBAL(cbbcsd,CBBCSD)\n#define LAPACK_cheswapr LAPACK_GLOBAL(cheswapr,CHESWAPR)\n#define LAPACK_chetri2 LAPACK_GLOBAL(chetri2,CHETRI2)\n#define LAPACK_chetri2x LAPACK_GLOBAL(chetri2x,CHETRI2X)\n#define LAPACK_chetrs2 LAPACK_GLOBAL(chetrs2,CHETRS2)\n#define LAPACK_csyconv LAPACK_GLOBAL(csyconv,CSYCONV)\n#define LAPACK_csyswapr LAPACK_GLOBAL(csyswapr,CSYSWAPR)\n#define LAPACK_csytri2 LAPACK_GLOBAL(csytri2,CSYTRI2)\n#define LAPACK_csytri2x LAPACK_GLOBAL(csytri2x,CSYTRI2X)\n#define LAPACK_csytrs2 LAPACK_GLOBAL(csytrs2,CSYTRS2)\n#define LAPACK_cunbdb LAPACK_GLOBAL(cunbdb,CUNBDB)\n#define LAPACK_cuncsd LAPACK_GLOBAL(cuncsd,CUNCSD)\n#define LAPACK_dbbcsd LAPACK_GLOBAL(dbbcsd,DBBCSD)\n#define LAPACK_dorbdb LAPACK_GLOBAL(dorbdb,DORBDB)\n#define LAPACK_dorcsd LAPACK_GLOBAL(dorcsd,DORCSD)\n#define LAPACK_dsyconv LAPACK_GLOBAL(dsyconv,DSYCONV)\n#define LAPACK_dsyswapr LAPACK_GLOBAL(dsyswapr,DSYSWAPR)\n#define LAPACK_dsytri2 LAPACK_GLOBAL(dsytri2,DSYTRI2)\n#define LAPACK_dsytri2x LAPACK_GLOBAL(dsytri2x,DSYTRI2X)\n#define LAPACK_dsytrs2 LAPACK_GLOBAL(dsytrs2,DSYTRS2)\n#define LAPACK_sbbcsd LAPACK_GLOBAL(sbbcsd,SBBCSD)\n#define LAPACK_sorbdb LAPACK_GLOBAL(sorbdb,SORBDB)\n#define LAPACK_sorcsd LAPACK_GLOBAL(sorcsd,SORCSD)\n#define LAPACK_ssyconv LAPACK_GLOBAL(ssyconv,SSYCONV)\n#define LAPACK_ssyswapr LAPACK_GLOBAL(ssyswapr,SSYSWAPR)\n#define LAPACK_ssytri2 LAPACK_GLOBAL(ssytri2,SSYTRI2)\n#define LAPACK_ssytri2x LAPACK_GLOBAL(ssytri2x,SSYTRI2X)\n#define LAPACK_ssytrs2 LAPACK_GLOBAL(ssytrs2,SSYTRS2)\n#define LAPACK_zbbcsd LAPACK_GLOBAL(zbbcsd,ZBBCSD)\n#define LAPACK_zheswapr LAPACK_GLOBAL(zheswapr,ZHESWAPR)\n#define LAPACK_zhetri2 LAPACK_GLOBAL(zhetri2,ZHETRI2)\n#define LAPACK_zhetri2x LAPACK_GLOBAL(zhetri2x,ZHETRI2X)\n#define LAPACK_zhetrs2 LAPACK_GLOBAL(zhetrs2,ZHETRS2)\n#define LAPACK_zsyconv LAPACK_GLOBAL(zsyconv,ZSYCONV)\n#define LAPACK_zsyswapr LAPACK_GLOBAL(zsyswapr,ZSYSWAPR)\n#define LAPACK_zsytri2 LAPACK_GLOBAL(zsytri2,ZSYTRI2)\n#define LAPACK_zsytri2x LAPACK_GLOBAL(zsytri2x,ZSYTRI2X)\n#define LAPACK_zsytrs2 LAPACK_GLOBAL(zsytrs2,ZSYTRS2)\n#define LAPACK_zunbdb LAPACK_GLOBAL(zunbdb,ZUNBDB)\n#define LAPACK_zuncsd LAPACK_GLOBAL(zuncsd,ZUNCSD)\n// LAPACK 3.4.0\n#define LAPACK_sgemqrt LAPACK_GLOBAL(sgemqrt,SGEMQRT)\n#define LAPACK_dgemqrt LAPACK_GLOBAL(dgemqrt,DGEMQRT)\n#define LAPACK_cgemqrt LAPACK_GLOBAL(cgemqrt,CGEMQRT)\n#define LAPACK_zgemqrt LAPACK_GLOBAL(zgemqrt,ZGEMQRT)\n#define LAPACK_sgeqrt LAPACK_GLOBAL(sgeqrt,SGEQRT)\n#define LAPACK_dgeqrt LAPACK_GLOBAL(dgeqrt,DGEQRT)\n#define LAPACK_cgeqrt LAPACK_GLOBAL(cgeqrt,CGEQRT)\n#define LAPACK_zgeqrt LAPACK_GLOBAL(zgeqrt,ZGEQRT)\n#define LAPACK_sgeqrt2 LAPACK_GLOBAL(sgeqrt2,SGEQRT2)\n#define LAPACK_dgeqrt2 LAPACK_GLOBAL(dgeqrt2,DGEQRT2)\n#define LAPACK_cgeqrt2 LAPACK_GLOBAL(cgeqrt2,CGEQRT2)\n#define LAPACK_zgeqrt2 LAPACK_GLOBAL(zgeqrt2,ZGEQRT2)\n#define LAPACK_sgeqrt3 LAPACK_GLOBAL(sgeqrt3,SGEQRT3)\n#define LAPACK_dgeqrt3 LAPACK_GLOBAL(dgeqrt3,DGEQRT3)\n#define LAPACK_cgeqrt3 LAPACK_GLOBAL(cgeqrt3,CGEQRT3)\n#define LAPACK_zgeqrt3 LAPACK_GLOBAL(zgeqrt3,ZGEQRT3)\n#define LAPACK_stpmqrt LAPACK_GLOBAL(stpmqrt,STPMQRT)\n#define LAPACK_dtpmqrt LAPACK_GLOBAL(dtpmqrt,DTPMQRT)\n#define LAPACK_ctpmqrt LAPACK_GLOBAL(ctpmqrt,CTPMQRT)\n#define LAPACK_ztpmqrt LAPACK_GLOBAL(ztpmqrt,ZTPMQRT)\n#define LAPACK_dtpqrt LAPACK_GLOBAL(dtpqrt,DTPQRT)\n#define LAPACK_ctpqrt LAPACK_GLOBAL(ctpqrt,CTPQRT)\n#define LAPACK_ztpqrt LAPACK_GLOBAL(ztpqrt,ZTPQRT)\n#define LAPACK_stpqrt2 LAPACK_GLOBAL(stpqrt2,STPQRT2)\n#define LAPACK_dtpqrt2 LAPACK_GLOBAL(dtpqrt2,DTPQRT2)\n#define LAPACK_ctpqrt2 LAPACK_GLOBAL(ctpqrt2,CTPQRT2)\n#define LAPACK_ztpqrt2 LAPACK_GLOBAL(ztpqrt2,ZTPQRT2)\n#define LAPACK_stprfb LAPACK_GLOBAL(stprfb,STPRFB)\n#define LAPACK_dtprfb LAPACK_GLOBAL(dtprfb,DTPRFB)\n#define LAPACK_ctprfb LAPACK_GLOBAL(ctprfb,CTPRFB)\n#define LAPACK_ztprfb LAPACK_GLOBAL(ztprfb,ZTPRFB)\n// LAPACK 3.X.X\n#define LAPACK_csyr LAPACK_GLOBAL(csyr,CSYR)\n#define LAPACK_zsyr LAPACK_GLOBAL(zsyr,ZSYR)\n\n\nvoid LAPACK_sgetrf( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_dgetrf( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_cgetrf( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_zgetrf( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_sgbtrf( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, float* ab, lapack_int* ldab,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_dgbtrf( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, double* ab, lapack_int* ldab,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_cgbtrf( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, lapack_complex_float* ab, lapack_int* ldab,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_zgbtrf( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, lapack_complex_double* ab, lapack_int* ldab,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_sgttrf( lapack_int* n, float* dl, float* d, float* du, float* du2,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_dgttrf( lapack_int* n, double* dl, double* d, double* du,\n                    double* du2, lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_cgttrf( lapack_int* n, lapack_complex_float* dl,\n                    lapack_complex_float* d, lapack_complex_float* du,\n                    lapack_complex_float* du2, lapack_int* ipiv,\n                    lapack_int *info );\nvoid LAPACK_zgttrf( lapack_int* n, lapack_complex_double* dl,\n                    lapack_complex_double* d, lapack_complex_double* du,\n                    lapack_complex_double* du2, lapack_int* ipiv,\n                    lapack_int *info );\nvoid LAPACK_spotrf( char* uplo, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_dpotrf( char* uplo, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_cpotrf( char* uplo, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_zpotrf( char* uplo, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_dpstrf( char* uplo, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int* piv, lapack_int* rank, double* tol,\n                    double* work, lapack_int *info );\nvoid LAPACK_spstrf( char* uplo, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int* piv, lapack_int* rank, float* tol, float* work,\n                    lapack_int *info );\nvoid LAPACK_zpstrf( char* uplo, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* piv, lapack_int* rank,\n                    double* tol, double* work, lapack_int *info );\nvoid LAPACK_cpstrf( char* uplo, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int* piv, lapack_int* rank,\n                    float* tol, float* work, lapack_int *info );\nvoid LAPACK_dpftrf( char* transr, char* uplo, lapack_int* n, double* a,\n                    lapack_int *info );\nvoid LAPACK_spftrf( char* transr, char* uplo, lapack_int* n, float* a,\n                    lapack_int *info );\nvoid LAPACK_zpftrf( char* transr, char* uplo, lapack_int* n,\n                    lapack_complex_double* a, lapack_int *info );\nvoid LAPACK_cpftrf( char* transr, char* uplo, lapack_int* n,\n                    lapack_complex_float* a, lapack_int *info );\nvoid LAPACK_spptrf( char* uplo, lapack_int* n, float* ap, lapack_int *info );\nvoid LAPACK_dpptrf( char* uplo, lapack_int* n, double* ap, lapack_int *info );\nvoid LAPACK_cpptrf( char* uplo, lapack_int* n, lapack_complex_float* ap,\n                    lapack_int *info );\nvoid LAPACK_zpptrf( char* uplo, lapack_int* n, lapack_complex_double* ap,\n                    lapack_int *info );\nvoid LAPACK_spbtrf( char* uplo, lapack_int* n, lapack_int* kd, float* ab,\n                    lapack_int* ldab, lapack_int *info );\nvoid LAPACK_dpbtrf( char* uplo, lapack_int* n, lapack_int* kd, double* ab,\n                    lapack_int* ldab, lapack_int *info );\nvoid LAPACK_cpbtrf( char* uplo, lapack_int* n, lapack_int* kd,\n                    lapack_complex_float* ab, lapack_int* ldab,\n                    lapack_int *info );\nvoid LAPACK_zpbtrf( char* uplo, lapack_int* n, lapack_int* kd,\n                    lapack_complex_double* ab, lapack_int* ldab,\n                    lapack_int *info );\nvoid LAPACK_spttrf( lapack_int* n, float* d, float* e, lapack_int *info );\nvoid LAPACK_dpttrf( lapack_int* n, double* d, double* e, lapack_int *info );\nvoid LAPACK_cpttrf( lapack_int* n, float* d, lapack_complex_float* e,\n                    lapack_int *info );\nvoid LAPACK_zpttrf( lapack_int* n, double* d, lapack_complex_double* e,\n                    lapack_int *info );\nvoid LAPACK_ssytrf( char* uplo, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int* ipiv, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dsytrf( char* uplo, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int* ipiv, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_csytrf( char* uplo, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int* ipiv,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zsytrf( char* uplo, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* ipiv,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_chetrf( char* uplo, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int* ipiv,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zhetrf( char* uplo, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* ipiv,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_ssptrf( char* uplo, lapack_int* n, float* ap, lapack_int* ipiv,\n                    lapack_int *info );\nvoid LAPACK_dsptrf( char* uplo, lapack_int* n, double* ap, lapack_int* ipiv,\n                    lapack_int *info );\nvoid LAPACK_csptrf( char* uplo, lapack_int* n, lapack_complex_float* ap,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_zsptrf( char* uplo, lapack_int* n, lapack_complex_double* ap,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_chptrf( char* uplo, lapack_int* n, lapack_complex_float* ap,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_zhptrf( char* uplo, lapack_int* n, lapack_complex_double* ap,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_sgetrs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const float* a, lapack_int* lda, const lapack_int* ipiv,\n                    float* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dgetrs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const double* a, lapack_int* lda, const lapack_int* ipiv,\n                    double* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_cgetrs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    const lapack_int* ipiv, lapack_complex_float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zgetrs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_int* ipiv, lapack_complex_double* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_sgbtrs( char* trans, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    lapack_int* nrhs, const float* ab, lapack_int* ldab,\n                    const lapack_int* ipiv, float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_dgbtrs( char* trans, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    lapack_int* nrhs, const double* ab, lapack_int* ldab,\n                    const lapack_int* ipiv, double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_cgbtrs( char* trans, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    lapack_int* nrhs, const lapack_complex_float* ab,\n                    lapack_int* ldab, const lapack_int* ipiv,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_zgbtrs( char* trans, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    lapack_int* nrhs, const lapack_complex_double* ab,\n                    lapack_int* ldab, const lapack_int* ipiv,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_sgttrs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const float* dl, const float* d, const float* du,\n                    const float* du2, const lapack_int* ipiv, float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dgttrs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const double* dl, const double* d, const double* du,\n                    const double* du2, const lapack_int* ipiv, double* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_cgttrs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* dl,\n                    const lapack_complex_float* d,\n                    const lapack_complex_float* du,\n                    const lapack_complex_float* du2, const lapack_int* ipiv,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_zgttrs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* dl,\n                    const lapack_complex_double* d,\n                    const lapack_complex_double* du,\n                    const lapack_complex_double* du2, const lapack_int* ipiv,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_spotrs( char* uplo, lapack_int* n, lapack_int* nrhs, const float* a,\n                    lapack_int* lda, float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_dpotrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* a, lapack_int* lda, double* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_cpotrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_zpotrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_dpftrs( char* transr, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* a, double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_spftrs( char* transr, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const float* a, float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_zpftrs( char* transr, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_complex_double* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_cpftrs( char* transr, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_complex_float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_spptrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const float* ap, float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_dpptrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* ap, double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_cpptrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* ap, lapack_complex_float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zpptrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* ap, lapack_complex_double* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_spbtrs( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                    const float* ab, lapack_int* ldab, float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dpbtrs( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                    const double* ab, lapack_int* ldab, double* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_cpbtrs( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                    const lapack_complex_float* ab, lapack_int* ldab,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_zpbtrs( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                    const lapack_complex_double* ab, lapack_int* ldab,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_spttrs( lapack_int* n, lapack_int* nrhs, const float* d,\n                    const float* e, float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_dpttrs( lapack_int* n, lapack_int* nrhs, const double* d,\n                    const double* e, double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_cpttrs( char* uplo, lapack_int* n, lapack_int* nrhs, const float* d,\n                    const lapack_complex_float* e, lapack_complex_float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zpttrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* d, const lapack_complex_double* e,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_ssytrs( char* uplo, lapack_int* n, lapack_int* nrhs, const float* a,\n                    lapack_int* lda, const lapack_int* ipiv, float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dsytrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* a, lapack_int* lda, const lapack_int* ipiv,\n                    double* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_csytrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    const lapack_int* ipiv, lapack_complex_float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zsytrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_int* ipiv, lapack_complex_double* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_chetrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    const lapack_int* ipiv, lapack_complex_float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zhetrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_int* ipiv, lapack_complex_double* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_ssptrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const float* ap, const lapack_int* ipiv, float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dsptrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* ap, const lapack_int* ipiv, double* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_csptrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* ap, const lapack_int* ipiv,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_zsptrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* ap, const lapack_int* ipiv,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_chptrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* ap, const lapack_int* ipiv,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_zhptrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* ap, const lapack_int* ipiv,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_strtrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const float* a, lapack_int* lda, float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dtrtrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const double* a, lapack_int* lda,\n                    double* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_ctrtrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_ztrtrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_stptrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const float* ap, float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dtptrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const double* ap, double* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_ctptrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const lapack_complex_float* ap,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_ztptrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const lapack_complex_double* ap,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_stbtrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* kd, lapack_int* nrhs, const float* ab,\n                    lapack_int* ldab, float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_dtbtrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* kd, lapack_int* nrhs, const double* ab,\n                    lapack_int* ldab, double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_ctbtrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* kd, lapack_int* nrhs,\n                    const lapack_complex_float* ab, lapack_int* ldab,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_ztbtrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* kd, lapack_int* nrhs,\n                    const lapack_complex_double* ab, lapack_int* ldab,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_sgecon( char* norm, lapack_int* n, const float* a, lapack_int* lda,\n                    float* anorm, float* rcond, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dgecon( char* norm, lapack_int* n, const double* a, lapack_int* lda,\n                    double* anorm, double* rcond, double* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cgecon( char* norm, lapack_int* n, const lapack_complex_float* a,\n                    lapack_int* lda, float* anorm, float* rcond,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zgecon( char* norm, lapack_int* n, const lapack_complex_double* a,\n                    lapack_int* lda, double* anorm, double* rcond,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_sgbcon( char* norm, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    const float* ab, lapack_int* ldab, const lapack_int* ipiv,\n                    float* anorm, float* rcond, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dgbcon( char* norm, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    const double* ab, lapack_int* ldab, const lapack_int* ipiv,\n                    double* anorm, double* rcond, double* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cgbcon( char* norm, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    const lapack_complex_float* ab, lapack_int* ldab,\n                    const lapack_int* ipiv, float* anorm, float* rcond,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zgbcon( char* norm, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    const lapack_complex_double* ab, lapack_int* ldab,\n                    const lapack_int* ipiv, double* anorm, double* rcond,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_sgtcon( char* norm, lapack_int* n, const float* dl, const float* d,\n                    const float* du, const float* du2, const lapack_int* ipiv,\n                    float* anorm, float* rcond, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dgtcon( char* norm, lapack_int* n, const double* dl,\n                    const double* d, const double* du, const double* du2,\n                    const lapack_int* ipiv, double* anorm, double* rcond,\n                    double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cgtcon( char* norm, lapack_int* n, const lapack_complex_float* dl,\n                    const lapack_complex_float* d,\n                    const lapack_complex_float* du,\n                    const lapack_complex_float* du2, const lapack_int* ipiv,\n                    float* anorm, float* rcond, lapack_complex_float* work,\n                    lapack_int *info );\nvoid LAPACK_zgtcon( char* norm, lapack_int* n, const lapack_complex_double* dl,\n                    const lapack_complex_double* d,\n                    const lapack_complex_double* du,\n                    const lapack_complex_double* du2, const lapack_int* ipiv,\n                    double* anorm, double* rcond, lapack_complex_double* work,\n                    lapack_int *info );\nvoid LAPACK_spocon( char* uplo, lapack_int* n, const float* a, lapack_int* lda,\n                    float* anorm, float* rcond, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dpocon( char* uplo, lapack_int* n, const double* a, lapack_int* lda,\n                    double* anorm, double* rcond, double* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cpocon( char* uplo, lapack_int* n, const lapack_complex_float* a,\n                    lapack_int* lda, float* anorm, float* rcond,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zpocon( char* uplo, lapack_int* n, const lapack_complex_double* a,\n                    lapack_int* lda, double* anorm, double* rcond,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_sppcon( char* uplo, lapack_int* n, const float* ap, float* anorm,\n                    float* rcond, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dppcon( char* uplo, lapack_int* n, const double* ap, double* anorm,\n                    double* rcond, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_cppcon( char* uplo, lapack_int* n, const lapack_complex_float* ap,\n                    float* anorm, float* rcond, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zppcon( char* uplo, lapack_int* n, const lapack_complex_double* ap,\n                    double* anorm, double* rcond, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_spbcon( char* uplo, lapack_int* n, lapack_int* kd, const float* ab,\n                    lapack_int* ldab, float* anorm, float* rcond, float* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dpbcon( char* uplo, lapack_int* n, lapack_int* kd, const double* ab,\n                    lapack_int* ldab, double* anorm, double* rcond,\n                    double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cpbcon( char* uplo, lapack_int* n, lapack_int* kd,\n                    const lapack_complex_float* ab, lapack_int* ldab,\n                    float* anorm, float* rcond, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zpbcon( char* uplo, lapack_int* n, lapack_int* kd,\n                    const lapack_complex_double* ab, lapack_int* ldab,\n                    double* anorm, double* rcond, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_sptcon( lapack_int* n, const float* d, const float* e, float* anorm,\n                    float* rcond, float* work, lapack_int *info );\nvoid LAPACK_dptcon( lapack_int* n, const double* d, const double* e,\n                    double* anorm, double* rcond, double* work,\n                    lapack_int *info );\nvoid LAPACK_cptcon( lapack_int* n, const float* d,\n                    const lapack_complex_float* e, float* anorm, float* rcond,\n                    float* work, lapack_int *info );\nvoid LAPACK_zptcon( lapack_int* n, const double* d,\n                    const lapack_complex_double* e, double* anorm,\n                    double* rcond, double* work, lapack_int *info );\nvoid LAPACK_ssycon( char* uplo, lapack_int* n, const float* a, lapack_int* lda,\n                    const lapack_int* ipiv, float* anorm, float* rcond,\n                    float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dsycon( char* uplo, lapack_int* n, const double* a, lapack_int* lda,\n                    const lapack_int* ipiv, double* anorm, double* rcond,\n                    double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_csycon( char* uplo, lapack_int* n, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_int* ipiv, float* anorm,\n                    float* rcond, lapack_complex_float* work,\n                    lapack_int *info );\nvoid LAPACK_zsycon( char* uplo, lapack_int* n, const lapack_complex_double* a,\n                    lapack_int* lda, const lapack_int* ipiv, double* anorm,\n                    double* rcond, lapack_complex_double* work,\n                    lapack_int *info );\nvoid LAPACK_checon( char* uplo, lapack_int* n, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_int* ipiv, float* anorm,\n                    float* rcond, lapack_complex_float* work,\n                    lapack_int *info );\nvoid LAPACK_zhecon( char* uplo, lapack_int* n, const lapack_complex_double* a,\n                    lapack_int* lda, const lapack_int* ipiv, double* anorm,\n                    double* rcond, lapack_complex_double* work,\n                    lapack_int *info );\nvoid LAPACK_sspcon( char* uplo, lapack_int* n, const float* ap,\n                    const lapack_int* ipiv, float* anorm, float* rcond,\n                    float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dspcon( char* uplo, lapack_int* n, const double* ap,\n                    const lapack_int* ipiv, double* anorm, double* rcond,\n                    double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cspcon( char* uplo, lapack_int* n, const lapack_complex_float* ap,\n                    const lapack_int* ipiv, float* anorm, float* rcond,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zspcon( char* uplo, lapack_int* n, const lapack_complex_double* ap,\n                    const lapack_int* ipiv, double* anorm, double* rcond,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_chpcon( char* uplo, lapack_int* n, const lapack_complex_float* ap,\n                    const lapack_int* ipiv, float* anorm, float* rcond,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zhpcon( char* uplo, lapack_int* n, const lapack_complex_double* ap,\n                    const lapack_int* ipiv, double* anorm, double* rcond,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_strcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    const float* a, lapack_int* lda, float* rcond, float* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dtrcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    const double* a, lapack_int* lda, double* rcond,\n                    double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ctrcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    float* rcond, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_ztrcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    double* rcond, lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_stpcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    const float* ap, float* rcond, float* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dtpcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    const double* ap, double* rcond, double* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ctpcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    const lapack_complex_float* ap, float* rcond,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_ztpcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    const lapack_complex_double* ap, double* rcond,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_stbcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    lapack_int* kd, const float* ab, lapack_int* ldab,\n                    float* rcond, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dtbcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    lapack_int* kd, const double* ab, lapack_int* ldab,\n                    double* rcond, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_ctbcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    lapack_int* kd, const lapack_complex_float* ab,\n                    lapack_int* ldab, float* rcond, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_ztbcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    lapack_int* kd, const lapack_complex_double* ab,\n                    lapack_int* ldab, double* rcond,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_sgerfs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const float* a, lapack_int* lda, const float* af,\n                    lapack_int* ldaf, const lapack_int* ipiv, const float* b,\n                    lapack_int* ldb, float* x, lapack_int* ldx, float* ferr,\n                    float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dgerfs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const double* a, lapack_int* lda, const double* af,\n                    lapack_int* ldaf, const lapack_int* ipiv, const double* b,\n                    lapack_int* ldb, double* x, lapack_int* ldx, double* ferr,\n                    double* berr, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_cgerfs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* af, lapack_int* ldaf,\n                    const lapack_int* ipiv, const lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* x, lapack_int* ldx,\n                    float* ferr, float* berr, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zgerfs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* af, lapack_int* ldaf,\n                    const lapack_int* ipiv, const lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                    double* ferr, double* berr, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_dgerfsx( char* trans, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const double* a, lapack_int* lda, const double* af,\n                     lapack_int* ldaf, const lapack_int* ipiv, const double* r,\n                     const double* c, const double* b, lapack_int* ldb,\n                     double* x, lapack_int* ldx, double* rcond, double* berr,\n                     lapack_int* n_err_bnds, double* err_bnds_norm,\n                     double* err_bnds_comp, lapack_int* nparams, double* params,\n                     double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_sgerfsx( char* trans, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const float* a, lapack_int* lda, const float* af,\n                     lapack_int* ldaf, const lapack_int* ipiv, const float* r,\n                     const float* c, const float* b, lapack_int* ldb, float* x,\n                     lapack_int* ldx, float* rcond, float* berr,\n                     lapack_int* n_err_bnds, float* err_bnds_norm,\n                     float* err_bnds_comp, lapack_int* nparams, float* params,\n                     float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_zgerfsx( char* trans, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const lapack_complex_double* a, lapack_int* lda,\n                     const lapack_complex_double* af, lapack_int* ldaf,\n                     const lapack_int* ipiv, const double* r, const double* c,\n                     const lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                     double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params,\n                     lapack_complex_double* work, double* rwork,\n                     lapack_int *info );\nvoid LAPACK_cgerfsx( char* trans, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const lapack_complex_float* a, lapack_int* lda,\n                     const lapack_complex_float* af, lapack_int* ldaf,\n                     const lapack_int* ipiv, const float* r, const float* c,\n                     const lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                     float* berr, lapack_int* n_err_bnds, float* err_bnds_norm,\n                     float* err_bnds_comp, lapack_int* nparams, float* params,\n                     lapack_complex_float* work, float* rwork,\n                     lapack_int *info );\nvoid LAPACK_sgbrfs( char* trans, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    lapack_int* nrhs, const float* ab, lapack_int* ldab,\n                    const float* afb, lapack_int* ldafb, const lapack_int* ipiv,\n                    const float* b, lapack_int* ldb, float* x, lapack_int* ldx,\n                    float* ferr, float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dgbrfs( char* trans, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    lapack_int* nrhs, const double* ab, lapack_int* ldab,\n                    const double* afb, lapack_int* ldafb,\n                    const lapack_int* ipiv, const double* b, lapack_int* ldb,\n                    double* x, lapack_int* ldx, double* ferr, double* berr,\n                    double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cgbrfs( char* trans, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    lapack_int* nrhs, const lapack_complex_float* ab,\n                    lapack_int* ldab, const lapack_complex_float* afb,\n                    lapack_int* ldafb, const lapack_int* ipiv,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* ferr,\n                    float* berr, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zgbrfs( char* trans, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    lapack_int* nrhs, const lapack_complex_double* ab,\n                    lapack_int* ldab, const lapack_complex_double* afb,\n                    lapack_int* ldafb, const lapack_int* ipiv,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* ferr,\n                    double* berr, lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_dgbrfsx( char* trans, char* equed, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, lapack_int* nrhs, const double* ab,\n                     lapack_int* ldab, const double* afb, lapack_int* ldafb,\n                     const lapack_int* ipiv, const double* r, const double* c,\n                     const double* b, lapack_int* ldb, double* x,\n                     lapack_int* ldx, double* rcond, double* berr,\n                     lapack_int* n_err_bnds, double* err_bnds_norm,\n                     double* err_bnds_comp, lapack_int* nparams, double* params,\n                     double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_sgbrfsx( char* trans, char* equed, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, lapack_int* nrhs, const float* ab,\n                     lapack_int* ldab, const float* afb, lapack_int* ldafb,\n                     const lapack_int* ipiv, const float* r, const float* c,\n                     const float* b, lapack_int* ldb, float* x, lapack_int* ldx,\n                     float* rcond, float* berr, lapack_int* n_err_bnds,\n                     float* err_bnds_norm, float* err_bnds_comp,\n                     lapack_int* nparams, float* params, float* work,\n                     lapack_int* iwork, lapack_int *info );\nvoid LAPACK_zgbrfsx( char* trans, char* equed, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, lapack_int* nrhs,\n                     const lapack_complex_double* ab, lapack_int* ldab,\n                     const lapack_complex_double* afb, lapack_int* ldafb,\n                     const lapack_int* ipiv, const double* r, const double* c,\n                     const lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                     double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params,\n                     lapack_complex_double* work, double* rwork,\n                     lapack_int *info );\nvoid LAPACK_cgbrfsx( char* trans, char* equed, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, lapack_int* nrhs,\n                     const lapack_complex_float* ab, lapack_int* ldab,\n                     const lapack_complex_float* afb, lapack_int* ldafb,\n                     const lapack_int* ipiv, const float* r, const float* c,\n                     const lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                     float* berr, lapack_int* n_err_bnds, float* err_bnds_norm,\n                     float* err_bnds_comp, lapack_int* nparams, float* params,\n                     lapack_complex_float* work, float* rwork,\n                     lapack_int *info );\nvoid LAPACK_sgtrfs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const float* dl, const float* d, const float* du,\n                    const float* dlf, const float* df, const float* duf,\n                    const float* du2, const lapack_int* ipiv, const float* b,\n                    lapack_int* ldb, float* x, lapack_int* ldx, float* ferr,\n                    float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dgtrfs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const double* dl, const double* d, const double* du,\n                    const double* dlf, const double* df, const double* duf,\n                    const double* du2, const lapack_int* ipiv, const double* b,\n                    lapack_int* ldb, double* x, lapack_int* ldx, double* ferr,\n                    double* berr, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_cgtrfs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* dl,\n                    const lapack_complex_float* d,\n                    const lapack_complex_float* du,\n                    const lapack_complex_float* dlf,\n                    const lapack_complex_float* df,\n                    const lapack_complex_float* duf,\n                    const lapack_complex_float* du2, const lapack_int* ipiv,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* ferr,\n                    float* berr, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zgtrfs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* dl,\n                    const lapack_complex_double* d,\n                    const lapack_complex_double* du,\n                    const lapack_complex_double* dlf,\n                    const lapack_complex_double* df,\n                    const lapack_complex_double* duf,\n                    const lapack_complex_double* du2, const lapack_int* ipiv,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* ferr,\n                    double* berr, lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_sporfs( char* uplo, lapack_int* n, lapack_int* nrhs, const float* a,\n                    lapack_int* lda, const float* af, lapack_int* ldaf,\n                    const float* b, lapack_int* ldb, float* x, lapack_int* ldx,\n                    float* ferr, float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dporfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* a, lapack_int* lda, const double* af,\n                    lapack_int* ldaf, const double* b, lapack_int* ldb,\n                    double* x, lapack_int* ldx, double* ferr, double* berr,\n                    double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cporfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* af, lapack_int* ldaf,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* ferr,\n                    float* berr, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zporfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* af, lapack_int* ldaf,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* ferr,\n                    double* berr, lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_dporfsx( char* uplo, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const double* a, lapack_int* lda, const double* af,\n                     lapack_int* ldaf, const double* s, const double* b,\n                     lapack_int* ldb, double* x, lapack_int* ldx, double* rcond,\n                     double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params, double* work,\n                     lapack_int* iwork, lapack_int *info );\nvoid LAPACK_sporfsx( char* uplo, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const float* a, lapack_int* lda, const float* af,\n                     lapack_int* ldaf, const float* s, const float* b,\n                     lapack_int* ldb, float* x, lapack_int* ldx, float* rcond,\n                     float* berr, lapack_int* n_err_bnds, float* err_bnds_norm,\n                     float* err_bnds_comp, lapack_int* nparams, float* params,\n                     float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_zporfsx( char* uplo, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const lapack_complex_double* a, lapack_int* lda,\n                     const lapack_complex_double* af, lapack_int* ldaf,\n                     const double* s, const lapack_complex_double* b,\n                     lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                     double* rcond, double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params,\n                     lapack_complex_double* work, double* rwork,\n                     lapack_int *info );\nvoid LAPACK_cporfsx( char* uplo, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const lapack_complex_float* a, lapack_int* lda,\n                     const lapack_complex_float* af, lapack_int* ldaf,\n                     const float* s, const lapack_complex_float* b,\n                     lapack_int* ldb, lapack_complex_float* x, lapack_int* ldx,\n                     float* rcond, float* berr, lapack_int* n_err_bnds,\n                     float* err_bnds_norm, float* err_bnds_comp,\n                     lapack_int* nparams, float* params,\n                     lapack_complex_float* work, float* rwork,\n                     lapack_int *info );\nvoid LAPACK_spprfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const float* ap, const float* afp, const float* b,\n                    lapack_int* ldb, float* x, lapack_int* ldx, float* ferr,\n                    float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dpprfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* ap, const double* afp, const double* b,\n                    lapack_int* ldb, double* x, lapack_int* ldx, double* ferr,\n                    double* berr, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_cpprfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* ap,\n                    const lapack_complex_float* afp,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* ferr,\n                    float* berr, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zpprfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* ap,\n                    const lapack_complex_double* afp,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* ferr,\n                    double* berr, lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_spbrfs( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                    const float* ab, lapack_int* ldab, const float* afb,\n                    lapack_int* ldafb, const float* b, lapack_int* ldb,\n                    float* x, lapack_int* ldx, float* ferr, float* berr,\n                    float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dpbrfs( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                    const double* ab, lapack_int* ldab, const double* afb,\n                    lapack_int* ldafb, const double* b, lapack_int* ldb,\n                    double* x, lapack_int* ldx, double* ferr, double* berr,\n                    double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cpbrfs( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                    const lapack_complex_float* ab, lapack_int* ldab,\n                    const lapack_complex_float* afb, lapack_int* ldafb,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* ferr,\n                    float* berr, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zpbrfs( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                    const lapack_complex_double* ab, lapack_int* ldab,\n                    const lapack_complex_double* afb, lapack_int* ldafb,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* ferr,\n                    double* berr, lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_sptrfs( lapack_int* n, lapack_int* nrhs, const float* d,\n                    const float* e, const float* df, const float* ef,\n                    const float* b, lapack_int* ldb, float* x, lapack_int* ldx,\n                    float* ferr, float* berr, float* work, lapack_int *info );\nvoid LAPACK_dptrfs( lapack_int* n, lapack_int* nrhs, const double* d,\n                    const double* e, const double* df, const double* ef,\n                    const double* b, lapack_int* ldb, double* x,\n                    lapack_int* ldx, double* ferr, double* berr, double* work,\n                    lapack_int *info );\nvoid LAPACK_cptrfs( char* uplo, lapack_int* n, lapack_int* nrhs, const float* d,\n                    const lapack_complex_float* e, const float* df,\n                    const lapack_complex_float* ef,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* ferr,\n                    float* berr, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zptrfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* d, const lapack_complex_double* e,\n                    const double* df, const lapack_complex_double* ef,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* ferr,\n                    double* berr, lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_ssyrfs( char* uplo, lapack_int* n, lapack_int* nrhs, const float* a,\n                    lapack_int* lda, const float* af, lapack_int* ldaf,\n                    const lapack_int* ipiv, const float* b, lapack_int* ldb,\n                    float* x, lapack_int* ldx, float* ferr, float* berr,\n                    float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dsyrfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* a, lapack_int* lda, const double* af,\n                    lapack_int* ldaf, const lapack_int* ipiv, const double* b,\n                    lapack_int* ldb, double* x, lapack_int* ldx, double* ferr,\n                    double* berr, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_csyrfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* af, lapack_int* ldaf,\n                    const lapack_int* ipiv, const lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* x, lapack_int* ldx,\n                    float* ferr, float* berr, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zsyrfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* af, lapack_int* ldaf,\n                    const lapack_int* ipiv, const lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                    double* ferr, double* berr, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_dsyrfsx( char* uplo, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const double* a, lapack_int* lda, const double* af,\n                     lapack_int* ldaf, const lapack_int* ipiv, const double* s,\n                     const double* b, lapack_int* ldb, double* x,\n                     lapack_int* ldx, double* rcond, double* berr,\n                     lapack_int* n_err_bnds, double* err_bnds_norm,\n                     double* err_bnds_comp, lapack_int* nparams, double* params,\n                     double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ssyrfsx( char* uplo, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const float* a, lapack_int* lda, const float* af,\n                     lapack_int* ldaf, const lapack_int* ipiv, const float* s,\n                     const float* b, lapack_int* ldb, float* x, lapack_int* ldx,\n                     float* rcond, float* berr, lapack_int* n_err_bnds,\n                     float* err_bnds_norm, float* err_bnds_comp,\n                     lapack_int* nparams, float* params, float* work,\n                     lapack_int* iwork, lapack_int *info );\nvoid LAPACK_zsyrfsx( char* uplo, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const lapack_complex_double* a, lapack_int* lda,\n                     const lapack_complex_double* af, lapack_int* ldaf,\n                     const lapack_int* ipiv, const double* s,\n                     const lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                     double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params,\n                     lapack_complex_double* work, double* rwork,\n                     lapack_int *info );\nvoid LAPACK_csyrfsx( char* uplo, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const lapack_complex_float* a, lapack_int* lda,\n                     const lapack_complex_float* af, lapack_int* ldaf,\n                     const lapack_int* ipiv, const float* s,\n                     const lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                     float* berr, lapack_int* n_err_bnds, float* err_bnds_norm,\n                     float* err_bnds_comp, lapack_int* nparams, float* params,\n                     lapack_complex_float* work, float* rwork,\n                     lapack_int *info );\nvoid LAPACK_cherfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* af, lapack_int* ldaf,\n                    const lapack_int* ipiv, const lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* x, lapack_int* ldx,\n                    float* ferr, float* berr, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zherfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* af, lapack_int* ldaf,\n                    const lapack_int* ipiv, const lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                    double* ferr, double* berr, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_zherfsx( char* uplo, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const lapack_complex_double* a, lapack_int* lda,\n                     const lapack_complex_double* af, lapack_int* ldaf,\n                     const lapack_int* ipiv, const double* s,\n                     const lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                     double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params,\n                     lapack_complex_double* work, double* rwork,\n                     lapack_int *info );\nvoid LAPACK_cherfsx( char* uplo, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const lapack_complex_float* a, lapack_int* lda,\n                     const lapack_complex_float* af, lapack_int* ldaf,\n                     const lapack_int* ipiv, const float* s,\n                     const lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                     float* berr, lapack_int* n_err_bnds, float* err_bnds_norm,\n                     float* err_bnds_comp, lapack_int* nparams, float* params,\n                     lapack_complex_float* work, float* rwork,\n                     lapack_int *info );\nvoid LAPACK_ssprfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const float* ap, const float* afp, const lapack_int* ipiv,\n                    const float* b, lapack_int* ldb, float* x, lapack_int* ldx,\n                    float* ferr, float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dsprfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* ap, const double* afp, const lapack_int* ipiv,\n                    const double* b, lapack_int* ldb, double* x,\n                    lapack_int* ldx, double* ferr, double* berr, double* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_csprfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* ap,\n                    const lapack_complex_float* afp, const lapack_int* ipiv,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* ferr,\n                    float* berr, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zsprfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* ap,\n                    const lapack_complex_double* afp, const lapack_int* ipiv,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* ferr,\n                    double* berr, lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_chprfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* ap,\n                    const lapack_complex_float* afp, const lapack_int* ipiv,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* ferr,\n                    float* berr, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zhprfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* ap,\n                    const lapack_complex_double* afp, const lapack_int* ipiv,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* ferr,\n                    double* berr, lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_strrfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const float* a, lapack_int* lda,\n                    const float* b, lapack_int* ldb, const float* x,\n                    lapack_int* ldx, float* ferr, float* berr, float* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dtrrfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const double* a, lapack_int* lda,\n                    const double* b, lapack_int* ldb, const double* x,\n                    lapack_int* ldx, double* ferr, double* berr, double* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ctrrfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* b,\n                    lapack_int* ldb, const lapack_complex_float* x,\n                    lapack_int* ldx, float* ferr, float* berr,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_ztrrfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const lapack_complex_double* a,\n                    lapack_int* lda, const lapack_complex_double* b,\n                    lapack_int* ldb, const lapack_complex_double* x,\n                    lapack_int* ldx, double* ferr, double* berr,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_stprfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const float* ap, const float* b,\n                    lapack_int* ldb, const float* x, lapack_int* ldx,\n                    float* ferr, float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dtprfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const double* ap, const double* b,\n                    lapack_int* ldb, const double* x, lapack_int* ldx,\n                    double* ferr, double* berr, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_ctprfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const lapack_complex_float* ap,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    const lapack_complex_float* x, lapack_int* ldx, float* ferr,\n                    float* berr, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_ztprfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const lapack_complex_double* ap,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    const lapack_complex_double* x, lapack_int* ldx,\n                    double* ferr, double* berr, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_stbrfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* kd, lapack_int* nrhs, const float* ab,\n                    lapack_int* ldab, const float* b, lapack_int* ldb,\n                    const float* x, lapack_int* ldx, float* ferr, float* berr,\n                    float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dtbrfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* kd, lapack_int* nrhs, const double* ab,\n                    lapack_int* ldab, const double* b, lapack_int* ldb,\n                    const double* x, lapack_int* ldx, double* ferr,\n                    double* berr, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_ctbrfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* kd, lapack_int* nrhs,\n                    const lapack_complex_float* ab, lapack_int* ldab,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    const lapack_complex_float* x, lapack_int* ldx, float* ferr,\n                    float* berr, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_ztbrfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* kd, lapack_int* nrhs,\n                    const lapack_complex_double* ab, lapack_int* ldab,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    const lapack_complex_double* x, lapack_int* ldx,\n                    double* ferr, double* berr, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_sgetri( lapack_int* n, float* a, lapack_int* lda,\n                    const lapack_int* ipiv, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dgetri( lapack_int* n, double* a, lapack_int* lda,\n                    const lapack_int* ipiv, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cgetri( lapack_int* n, lapack_complex_float* a, lapack_int* lda,\n                    const lapack_int* ipiv, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zgetri( lapack_int* n, lapack_complex_double* a, lapack_int* lda,\n                    const lapack_int* ipiv, lapack_complex_double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_spotri( char* uplo, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_dpotri( char* uplo, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_cpotri( char* uplo, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_zpotri( char* uplo, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_dpftri( char* transr, char* uplo, lapack_int* n, double* a,\n                    lapack_int *info );\nvoid LAPACK_spftri( char* transr, char* uplo, lapack_int* n, float* a,\n                    lapack_int *info );\nvoid LAPACK_zpftri( char* transr, char* uplo, lapack_int* n,\n                    lapack_complex_double* a, lapack_int *info );\nvoid LAPACK_cpftri( char* transr, char* uplo, lapack_int* n,\n                    lapack_complex_float* a, lapack_int *info );\nvoid LAPACK_spptri( char* uplo, lapack_int* n, float* ap, lapack_int *info );\nvoid LAPACK_dpptri( char* uplo, lapack_int* n, double* ap, lapack_int *info );\nvoid LAPACK_cpptri( char* uplo, lapack_int* n, lapack_complex_float* ap,\n                    lapack_int *info );\nvoid LAPACK_zpptri( char* uplo, lapack_int* n, lapack_complex_double* ap,\n                    lapack_int *info );\nvoid LAPACK_ssytri( char* uplo, lapack_int* n, float* a, lapack_int* lda,\n                    const lapack_int* ipiv, float* work, lapack_int *info );\nvoid LAPACK_dsytri( char* uplo, lapack_int* n, double* a, lapack_int* lda,\n                    const lapack_int* ipiv, double* work, lapack_int *info );\nvoid LAPACK_csytri( char* uplo, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, const lapack_int* ipiv,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zsytri( char* uplo, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, const lapack_int* ipiv,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_chetri( char* uplo, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, const lapack_int* ipiv,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zhetri( char* uplo, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, const lapack_int* ipiv,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_ssptri( char* uplo, lapack_int* n, float* ap,\n                    const lapack_int* ipiv, float* work, lapack_int *info );\nvoid LAPACK_dsptri( char* uplo, lapack_int* n, double* ap,\n                    const lapack_int* ipiv, double* work, lapack_int *info );\nvoid LAPACK_csptri( char* uplo, lapack_int* n, lapack_complex_float* ap,\n                    const lapack_int* ipiv, lapack_complex_float* work,\n                    lapack_int *info );\nvoid LAPACK_zsptri( char* uplo, lapack_int* n, lapack_complex_double* ap,\n                    const lapack_int* ipiv, lapack_complex_double* work,\n                    lapack_int *info );\nvoid LAPACK_chptri( char* uplo, lapack_int* n, lapack_complex_float* ap,\n                    const lapack_int* ipiv, lapack_complex_float* work,\n                    lapack_int *info );\nvoid LAPACK_zhptri( char* uplo, lapack_int* n, lapack_complex_double* ap,\n                    const lapack_int* ipiv, lapack_complex_double* work,\n                    lapack_int *info );\nvoid LAPACK_strtri( char* uplo, char* diag, lapack_int* n, float* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_dtrtri( char* uplo, char* diag, lapack_int* n, double* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_ctrtri( char* uplo, char* diag, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_ztrtri( char* uplo, char* diag, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_dtftri( char* transr, char* uplo, char* diag, lapack_int* n,\n                    double* a, lapack_int *info );\nvoid LAPACK_stftri( char* transr, char* uplo, char* diag, lapack_int* n,\n                    float* a, lapack_int *info );\nvoid LAPACK_ztftri( char* transr, char* uplo, char* diag, lapack_int* n,\n                    lapack_complex_double* a, lapack_int *info );\nvoid LAPACK_ctftri( char* transr, char* uplo, char* diag, lapack_int* n,\n                    lapack_complex_float* a, lapack_int *info );\nvoid LAPACK_stptri( char* uplo, char* diag, lapack_int* n, float* ap,\n                    lapack_int *info );\nvoid LAPACK_dtptri( char* uplo, char* diag, lapack_int* n, double* ap,\n                    lapack_int *info );\nvoid LAPACK_ctptri( char* uplo, char* diag, lapack_int* n,\n                    lapack_complex_float* ap, lapack_int *info );\nvoid LAPACK_ztptri( char* uplo, char* diag, lapack_int* n,\n                    lapack_complex_double* ap, lapack_int *info );\nvoid LAPACK_sgeequ( lapack_int* m, lapack_int* n, const float* a,\n                    lapack_int* lda, float* r, float* c, float* rowcnd,\n                    float* colcnd, float* amax, lapack_int *info );\nvoid LAPACK_dgeequ( lapack_int* m, lapack_int* n, const double* a,\n                    lapack_int* lda, double* r, double* c, double* rowcnd,\n                    double* colcnd, double* amax, lapack_int *info );\nvoid LAPACK_cgeequ( lapack_int* m, lapack_int* n, const lapack_complex_float* a,\n                    lapack_int* lda, float* r, float* c, float* rowcnd,\n                    float* colcnd, float* amax, lapack_int *info );\nvoid LAPACK_zgeequ( lapack_int* m, lapack_int* n,\n                    const lapack_complex_double* a, lapack_int* lda, double* r,\n                    double* c, double* rowcnd, double* colcnd, double* amax,\n                    lapack_int *info );\nvoid LAPACK_dgeequb( lapack_int* m, lapack_int* n, const double* a,\n                     lapack_int* lda, double* r, double* c, double* rowcnd,\n                     double* colcnd, double* amax, lapack_int *info );\nvoid LAPACK_sgeequb( lapack_int* m, lapack_int* n, const float* a,\n                     lapack_int* lda, float* r, float* c, float* rowcnd,\n                     float* colcnd, float* amax, lapack_int *info );\nvoid LAPACK_zgeequb( lapack_int* m, lapack_int* n,\n                     const lapack_complex_double* a, lapack_int* lda, double* r,\n                     double* c, double* rowcnd, double* colcnd, double* amax,\n                     lapack_int *info );\nvoid LAPACK_cgeequb( lapack_int* m, lapack_int* n,\n                     const lapack_complex_float* a, lapack_int* lda, float* r,\n                     float* c, float* rowcnd, float* colcnd, float* amax,\n                     lapack_int *info );\nvoid LAPACK_sgbequ( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, const float* ab, lapack_int* ldab, float* r,\n                    float* c, float* rowcnd, float* colcnd, float* amax,\n                    lapack_int *info );\nvoid LAPACK_dgbequ( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, const double* ab, lapack_int* ldab,\n                    double* r, double* c, double* rowcnd, double* colcnd,\n                    double* amax, lapack_int *info );\nvoid LAPACK_cgbequ( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, const lapack_complex_float* ab,\n                    lapack_int* ldab, float* r, float* c, float* rowcnd,\n                    float* colcnd, float* amax, lapack_int *info );\nvoid LAPACK_zgbequ( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, const lapack_complex_double* ab,\n                    lapack_int* ldab, double* r, double* c, double* rowcnd,\n                    double* colcnd, double* amax, lapack_int *info );\nvoid LAPACK_dgbequb( lapack_int* m, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, const double* ab, lapack_int* ldab,\n                     double* r, double* c, double* rowcnd, double* colcnd,\n                     double* amax, lapack_int *info );\nvoid LAPACK_sgbequb( lapack_int* m, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, const float* ab, lapack_int* ldab,\n                     float* r, float* c, float* rowcnd, float* colcnd,\n                     float* amax, lapack_int *info );\nvoid LAPACK_zgbequb( lapack_int* m, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, const lapack_complex_double* ab,\n                     lapack_int* ldab, double* r, double* c, double* rowcnd,\n                     double* colcnd, double* amax, lapack_int *info );\nvoid LAPACK_cgbequb( lapack_int* m, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, const lapack_complex_float* ab,\n                     lapack_int* ldab, float* r, float* c, float* rowcnd,\n                     float* colcnd, float* amax, lapack_int *info );\nvoid LAPACK_spoequ( lapack_int* n, const float* a, lapack_int* lda, float* s,\n                    float* scond, float* amax, lapack_int *info );\nvoid LAPACK_dpoequ( lapack_int* n, const double* a, lapack_int* lda, double* s,\n                    double* scond, double* amax, lapack_int *info );\nvoid LAPACK_cpoequ( lapack_int* n, const lapack_complex_float* a,\n                    lapack_int* lda, float* s, float* scond, float* amax,\n                    lapack_int *info );\nvoid LAPACK_zpoequ( lapack_int* n, const lapack_complex_double* a,\n                    lapack_int* lda, double* s, double* scond, double* amax,\n                    lapack_int *info );\nvoid LAPACK_dpoequb( lapack_int* n, const double* a, lapack_int* lda, double* s,\n                     double* scond, double* amax, lapack_int *info );\nvoid LAPACK_spoequb( lapack_int* n, const float* a, lapack_int* lda, float* s,\n                     float* scond, float* amax, lapack_int *info );\nvoid LAPACK_zpoequb( lapack_int* n, const lapack_complex_double* a,\n                     lapack_int* lda, double* s, double* scond, double* amax,\n                     lapack_int *info );\nvoid LAPACK_cpoequb( lapack_int* n, const lapack_complex_float* a,\n                     lapack_int* lda, float* s, float* scond, float* amax,\n                     lapack_int *info );\nvoid LAPACK_sppequ( char* uplo, lapack_int* n, const float* ap, float* s,\n                    float* scond, float* amax, lapack_int *info );\nvoid LAPACK_dppequ( char* uplo, lapack_int* n, const double* ap, double* s,\n                    double* scond, double* amax, lapack_int *info );\nvoid LAPACK_cppequ( char* uplo, lapack_int* n, const lapack_complex_float* ap,\n                    float* s, float* scond, float* amax, lapack_int *info );\nvoid LAPACK_zppequ( char* uplo, lapack_int* n, const lapack_complex_double* ap,\n                    double* s, double* scond, double* amax, lapack_int *info );\nvoid LAPACK_spbequ( char* uplo, lapack_int* n, lapack_int* kd, const float* ab,\n                    lapack_int* ldab, float* s, float* scond, float* amax,\n                    lapack_int *info );\nvoid LAPACK_dpbequ( char* uplo, lapack_int* n, lapack_int* kd, const double* ab,\n                    lapack_int* ldab, double* s, double* scond, double* amax,\n                    lapack_int *info );\nvoid LAPACK_cpbequ( char* uplo, lapack_int* n, lapack_int* kd,\n                    const lapack_complex_float* ab, lapack_int* ldab, float* s,\n                    float* scond, float* amax, lapack_int *info );\nvoid LAPACK_zpbequ( char* uplo, lapack_int* n, lapack_int* kd,\n                    const lapack_complex_double* ab, lapack_int* ldab,\n                    double* s, double* scond, double* amax, lapack_int *info );\nvoid LAPACK_dsyequb( char* uplo, lapack_int* n, const double* a,\n                     lapack_int* lda, double* s, double* scond, double* amax,\n                     double* work, lapack_int *info );\nvoid LAPACK_ssyequb( char* uplo, lapack_int* n, const float* a, lapack_int* lda,\n                     float* s, float* scond, float* amax, float* work,\n                     lapack_int *info );\nvoid LAPACK_zsyequb( char* uplo, lapack_int* n, const lapack_complex_double* a,\n                     lapack_int* lda, double* s, double* scond, double* amax,\n                     lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_csyequb( char* uplo, lapack_int* n, const lapack_complex_float* a,\n                     lapack_int* lda, float* s, float* scond, float* amax,\n                     lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zheequb( char* uplo, lapack_int* n, const lapack_complex_double* a,\n                     lapack_int* lda, double* s, double* scond, double* amax,\n                     lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_cheequb( char* uplo, lapack_int* n, const lapack_complex_float* a,\n                     lapack_int* lda, float* s, float* scond, float* amax,\n                     lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_sgesv( lapack_int* n, lapack_int* nrhs, float* a, lapack_int* lda,\n                   lapack_int* ipiv, float* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_dgesv( lapack_int* n, lapack_int* nrhs, double* a, lapack_int* lda,\n                   lapack_int* ipiv, double* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_cgesv( lapack_int* n, lapack_int* nrhs, lapack_complex_float* a,\n                   lapack_int* lda, lapack_int* ipiv, lapack_complex_float* b,\n                   lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zgesv( lapack_int* n, lapack_int* nrhs, lapack_complex_double* a,\n                   lapack_int* lda, lapack_int* ipiv, lapack_complex_double* b,\n                   lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dsgesv( lapack_int* n, lapack_int* nrhs, double* a, lapack_int* lda,\n                    lapack_int* ipiv, double* b, lapack_int* ldb, double* x,\n                    lapack_int* ldx, double* work, float* swork,\n                    lapack_int* iter, lapack_int *info );\nvoid LAPACK_zcgesv( lapack_int* n, lapack_int* nrhs, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* ipiv, lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                    lapack_complex_double* work, lapack_complex_float* swork,\n                    double* rwork, lapack_int* iter, lapack_int *info );\nvoid LAPACK_sgesvx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                    float* a, lapack_int* lda, float* af, lapack_int* ldaf,\n                    lapack_int* ipiv, char* equed, float* r, float* c, float* b,\n                    lapack_int* ldb, float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dgesvx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                    double* a, lapack_int* lda, double* af, lapack_int* ldaf,\n                    lapack_int* ipiv, char* equed, double* r, double* c,\n                    double* b, lapack_int* ldb, double* x, lapack_int* ldx,\n                    double* rcond, double* ferr, double* berr, double* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cgesvx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* af, lapack_int* ldaf,\n                    lapack_int* ipiv, char* equed, float* r, float* c,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zgesvx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* af, lapack_int* ldaf,\n                    lapack_int* ipiv, char* equed, double* r, double* c,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                    double* ferr, double* berr, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_dgesvxx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                     double* a, lapack_int* lda, double* af, lapack_int* ldaf,\n                     lapack_int* ipiv, char* equed, double* r, double* c,\n                     double* b, lapack_int* ldb, double* x, lapack_int* ldx,\n                     double* rcond, double* rpvgrw, double* berr,\n                     lapack_int* n_err_bnds, double* err_bnds_norm,\n                     double* err_bnds_comp, lapack_int* nparams, double* params,\n                     double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_sgesvxx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                     float* a, lapack_int* lda, float* af, lapack_int* ldaf,\n                     lapack_int* ipiv, char* equed, float* r, float* c,\n                     float* b, lapack_int* ldb, float* x, lapack_int* ldx,\n                     float* rcond, float* rpvgrw, float* berr,\n                     lapack_int* n_err_bnds, float* err_bnds_norm,\n                     float* err_bnds_comp, lapack_int* nparams, float* params,\n                     float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_zgesvxx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                     lapack_complex_double* a, lapack_int* lda,\n                     lapack_complex_double* af, lapack_int* ldaf,\n                     lapack_int* ipiv, char* equed, double* r, double* c,\n                     lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                     double* rpvgrw, double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params,\n                     lapack_complex_double* work, double* rwork,\n                     lapack_int *info );\nvoid LAPACK_cgesvxx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                     lapack_complex_float* a, lapack_int* lda,\n                     lapack_complex_float* af, lapack_int* ldaf,\n                     lapack_int* ipiv, char* equed, float* r, float* c,\n                     lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                     float* rpvgrw, float* berr, lapack_int* n_err_bnds,\n                     float* err_bnds_norm, float* err_bnds_comp,\n                     lapack_int* nparams, float* params,\n                     lapack_complex_float* work, float* rwork,\n                     lapack_int *info );\nvoid LAPACK_sgbsv( lapack_int* n, lapack_int* kl, lapack_int* ku,\n                   lapack_int* nrhs, float* ab, lapack_int* ldab,\n                   lapack_int* ipiv, float* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_dgbsv( lapack_int* n, lapack_int* kl, lapack_int* ku,\n                   lapack_int* nrhs, double* ab, lapack_int* ldab,\n                   lapack_int* ipiv, double* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_cgbsv( lapack_int* n, lapack_int* kl, lapack_int* ku,\n                   lapack_int* nrhs, lapack_complex_float* ab, lapack_int* ldab,\n                   lapack_int* ipiv, lapack_complex_float* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_zgbsv( lapack_int* n, lapack_int* kl, lapack_int* ku,\n                   lapack_int* nrhs, lapack_complex_double* ab,\n                   lapack_int* ldab, lapack_int* ipiv, lapack_complex_double* b,\n                   lapack_int* ldb, lapack_int *info );\nvoid LAPACK_sgbsvx( char* fact, char* trans, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, lapack_int* nrhs, float* ab,\n                    lapack_int* ldab, float* afb, lapack_int* ldafb,\n                    lapack_int* ipiv, char* equed, float* r, float* c, float* b,\n                    lapack_int* ldb, float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dgbsvx( char* fact, char* trans, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, lapack_int* nrhs, double* ab,\n                    lapack_int* ldab, double* afb, lapack_int* ldafb,\n                    lapack_int* ipiv, char* equed, double* r, double* c,\n                    double* b, lapack_int* ldb, double* x, lapack_int* ldx,\n                    double* rcond, double* ferr, double* berr, double* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cgbsvx( char* fact, char* trans, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, lapack_int* nrhs, lapack_complex_float* ab,\n                    lapack_int* ldab, lapack_complex_float* afb,\n                    lapack_int* ldafb, lapack_int* ipiv, char* equed, float* r,\n                    float* c, lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zgbsvx( char* fact, char* trans, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, lapack_int* nrhs, lapack_complex_double* ab,\n                    lapack_int* ldab, lapack_complex_double* afb,\n                    lapack_int* ldafb, lapack_int* ipiv, char* equed, double* r,\n                    double* c, lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                    double* ferr, double* berr, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_dgbsvxx( char* fact, char* trans, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, lapack_int* nrhs, double* ab,\n                     lapack_int* ldab, double* afb, lapack_int* ldafb,\n                     lapack_int* ipiv, char* equed, double* r, double* c,\n                     double* b, lapack_int* ldb, double* x, lapack_int* ldx,\n                     double* rcond, double* rpvgrw, double* berr,\n                     lapack_int* n_err_bnds, double* err_bnds_norm,\n                     double* err_bnds_comp, lapack_int* nparams, double* params,\n                     double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_sgbsvxx( char* fact, char* trans, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, lapack_int* nrhs, float* ab,\n                     lapack_int* ldab, float* afb, lapack_int* ldafb,\n                     lapack_int* ipiv, char* equed, float* r, float* c,\n                     float* b, lapack_int* ldb, float* x, lapack_int* ldx,\n                     float* rcond, float* rpvgrw, float* berr,\n                     lapack_int* n_err_bnds, float* err_bnds_norm,\n                     float* err_bnds_comp, lapack_int* nparams, float* params,\n                     float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_zgbsvxx( char* fact, char* trans, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, lapack_int* nrhs,\n                     lapack_complex_double* ab, lapack_int* ldab,\n                     lapack_complex_double* afb, lapack_int* ldafb,\n                     lapack_int* ipiv, char* equed, double* r, double* c,\n                     lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                     double* rpvgrw, double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params,\n                     lapack_complex_double* work, double* rwork,\n                     lapack_int *info );\nvoid LAPACK_cgbsvxx( char* fact, char* trans, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, lapack_int* nrhs, lapack_complex_float* ab,\n                     lapack_int* ldab, lapack_complex_float* afb,\n                     lapack_int* ldafb, lapack_int* ipiv, char* equed, float* r,\n                     float* c, lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                     float* rpvgrw, float* berr, lapack_int* n_err_bnds,\n                     float* err_bnds_norm, float* err_bnds_comp,\n                     lapack_int* nparams, float* params,\n                     lapack_complex_float* work, float* rwork,\n                     lapack_int *info );\nvoid LAPACK_sgtsv( lapack_int* n, lapack_int* nrhs, float* dl, float* d,\n                   float* du, float* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dgtsv( lapack_int* n, lapack_int* nrhs, double* dl, double* d,\n                   double* du, double* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_cgtsv( lapack_int* n, lapack_int* nrhs, lapack_complex_float* dl,\n                   lapack_complex_float* d, lapack_complex_float* du,\n                   lapack_complex_float* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zgtsv( lapack_int* n, lapack_int* nrhs, lapack_complex_double* dl,\n                   lapack_complex_double* d, lapack_complex_double* du,\n                   lapack_complex_double* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_sgtsvx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                    const float* dl, const float* d, const float* du,\n                    float* dlf, float* df, float* duf, float* du2,\n                    lapack_int* ipiv, const float* b, lapack_int* ldb, float* x,\n                    lapack_int* ldx, float* rcond, float* ferr, float* berr,\n                    float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dgtsvx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                    const double* dl, const double* d, const double* du,\n                    double* dlf, double* df, double* duf, double* du2,\n                    lapack_int* ipiv, const double* b, lapack_int* ldb,\n                    double* x, lapack_int* ldx, double* rcond, double* ferr,\n                    double* berr, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_cgtsvx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* dl,\n                    const lapack_complex_float* d,\n                    const lapack_complex_float* du, lapack_complex_float* dlf,\n                    lapack_complex_float* df, lapack_complex_float* duf,\n                    lapack_complex_float* du2, lapack_int* ipiv,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zgtsvx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* dl,\n                    const lapack_complex_double* d,\n                    const lapack_complex_double* du, lapack_complex_double* dlf,\n                    lapack_complex_double* df, lapack_complex_double* duf,\n                    lapack_complex_double* du2, lapack_int* ipiv,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                    double* ferr, double* berr, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_sposv( char* uplo, lapack_int* n, lapack_int* nrhs, float* a,\n                   lapack_int* lda, float* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_dposv( char* uplo, lapack_int* n, lapack_int* nrhs, double* a,\n                   lapack_int* lda, double* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_cposv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_float* a, lapack_int* lda,\n                   lapack_complex_float* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zposv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_double* a, lapack_int* lda,\n                   lapack_complex_double* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_dsposv( char* uplo, lapack_int* n, lapack_int* nrhs, double* a,\n                    lapack_int* lda, double* b, lapack_int* ldb, double* x,\n                    lapack_int* ldx, double* work, float* swork,\n                    lapack_int* iter, lapack_int *info );\nvoid LAPACK_zcposv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx,\n                    lapack_complex_double* work, lapack_complex_float* swork,\n                    double* rwork, lapack_int* iter, lapack_int *info );\nvoid LAPACK_sposvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    float* a, lapack_int* lda, float* af, lapack_int* ldaf,\n                    char* equed, float* s, float* b, lapack_int* ldb, float* x,\n                    lapack_int* ldx, float* rcond, float* ferr, float* berr,\n                    float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dposvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    double* a, lapack_int* lda, double* af, lapack_int* ldaf,\n                    char* equed, double* s, double* b, lapack_int* ldb,\n                    double* x, lapack_int* ldx, double* rcond, double* ferr,\n                    double* berr, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_cposvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* af, lapack_int* ldaf, char* equed,\n                    float* s, lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zposvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* af, lapack_int* ldaf, char* equed,\n                    double* s, lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                    double* ferr, double* berr, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_dposvxx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                     double* a, lapack_int* lda, double* af, lapack_int* ldaf,\n                     char* equed, double* s, double* b, lapack_int* ldb,\n                     double* x, lapack_int* ldx, double* rcond, double* rpvgrw,\n                     double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params, double* work,\n                     lapack_int* iwork, lapack_int *info );\nvoid LAPACK_sposvxx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                     float* a, lapack_int* lda, float* af, lapack_int* ldaf,\n                     char* equed, float* s, float* b, lapack_int* ldb, float* x,\n                     lapack_int* ldx, float* rcond, float* rpvgrw, float* berr,\n                     lapack_int* n_err_bnds, float* err_bnds_norm,\n                     float* err_bnds_comp, lapack_int* nparams, float* params,\n                     float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_zposvxx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                     lapack_complex_double* a, lapack_int* lda,\n                     lapack_complex_double* af, lapack_int* ldaf, char* equed,\n                     double* s, lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                     double* rpvgrw, double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params,\n                     lapack_complex_double* work, double* rwork,\n                     lapack_int *info );\nvoid LAPACK_cposvxx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                     lapack_complex_float* a, lapack_int* lda,\n                     lapack_complex_float* af, lapack_int* ldaf, char* equed,\n                     float* s, lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                     float* rpvgrw, float* berr, lapack_int* n_err_bnds,\n                     float* err_bnds_norm, float* err_bnds_comp,\n                     lapack_int* nparams, float* params,\n                     lapack_complex_float* work, float* rwork,\n                     lapack_int *info );\nvoid LAPACK_sppsv( char* uplo, lapack_int* n, lapack_int* nrhs, float* ap,\n                   float* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dppsv( char* uplo, lapack_int* n, lapack_int* nrhs, double* ap,\n                   double* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_cppsv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_float* ap, lapack_complex_float* b,\n                   lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zppsv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_double* ap, lapack_complex_double* b,\n                   lapack_int* ldb, lapack_int *info );\nvoid LAPACK_sppsvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    float* ap, float* afp, char* equed, float* s, float* b,\n                    lapack_int* ldb, float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dppsvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    double* ap, double* afp, char* equed, double* s, double* b,\n                    lapack_int* ldb, double* x, lapack_int* ldx, double* rcond,\n                    double* ferr, double* berr, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_cppsvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_float* ap, lapack_complex_float* afp,\n                    char* equed, float* s, lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* x, lapack_int* ldx,\n                    float* rcond, float* ferr, float* berr,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zppsvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_double* ap, lapack_complex_double* afp,\n                    char* equed, double* s, lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                    double* rcond, double* ferr, double* berr,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_spbsv( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                   float* ab, lapack_int* ldab, float* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_dpbsv( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                   double* ab, lapack_int* ldab, double* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_cpbsv( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                   lapack_complex_float* ab, lapack_int* ldab,\n                   lapack_complex_float* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zpbsv( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                   lapack_complex_double* ab, lapack_int* ldab,\n                   lapack_complex_double* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_spbsvx( char* fact, char* uplo, lapack_int* n, lapack_int* kd,\n                    lapack_int* nrhs, float* ab, lapack_int* ldab, float* afb,\n                    lapack_int* ldafb, char* equed, float* s, float* b,\n                    lapack_int* ldb, float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dpbsvx( char* fact, char* uplo, lapack_int* n, lapack_int* kd,\n                    lapack_int* nrhs, double* ab, lapack_int* ldab, double* afb,\n                    lapack_int* ldafb, char* equed, double* s, double* b,\n                    lapack_int* ldb, double* x, lapack_int* ldx, double* rcond,\n                    double* ferr, double* berr, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_cpbsvx( char* fact, char* uplo, lapack_int* n, lapack_int* kd,\n                    lapack_int* nrhs, lapack_complex_float* ab,\n                    lapack_int* ldab, lapack_complex_float* afb,\n                    lapack_int* ldafb, char* equed, float* s,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zpbsvx( char* fact, char* uplo, lapack_int* n, lapack_int* kd,\n                    lapack_int* nrhs, lapack_complex_double* ab,\n                    lapack_int* ldab, lapack_complex_double* afb,\n                    lapack_int* ldafb, char* equed, double* s,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                    double* ferr, double* berr, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_sptsv( lapack_int* n, lapack_int* nrhs, float* d, float* e,\n                   float* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dptsv( lapack_int* n, lapack_int* nrhs, double* d, double* e,\n                   double* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_cptsv( lapack_int* n, lapack_int* nrhs, float* d,\n                   lapack_complex_float* e, lapack_complex_float* b,\n                   lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zptsv( lapack_int* n, lapack_int* nrhs, double* d,\n                   lapack_complex_double* e, lapack_complex_double* b,\n                   lapack_int* ldb, lapack_int *info );\nvoid LAPACK_sptsvx( char* fact, lapack_int* n, lapack_int* nrhs, const float* d,\n                    const float* e, float* df, float* ef, const float* b,\n                    lapack_int* ldb, float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, float* work, lapack_int *info );\nvoid LAPACK_dptsvx( char* fact, lapack_int* n, lapack_int* nrhs,\n                    const double* d, const double* e, double* df, double* ef,\n                    const double* b, lapack_int* ldb, double* x,\n                    lapack_int* ldx, double* rcond, double* ferr, double* berr,\n                    double* work, lapack_int *info );\nvoid LAPACK_cptsvx( char* fact, lapack_int* n, lapack_int* nrhs, const float* d,\n                    const lapack_complex_float* e, float* df,\n                    lapack_complex_float* ef, const lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* x, lapack_int* ldx,\n                    float* rcond, float* ferr, float* berr,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zptsvx( char* fact, lapack_int* n, lapack_int* nrhs,\n                    const double* d, const lapack_complex_double* e, double* df,\n                    lapack_complex_double* ef, const lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                    double* rcond, double* ferr, double* berr,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_ssysv( char* uplo, lapack_int* n, lapack_int* nrhs, float* a,\n                   lapack_int* lda, lapack_int* ipiv, float* b, lapack_int* ldb,\n                   float* work, lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dsysv( char* uplo, lapack_int* n, lapack_int* nrhs, double* a,\n                   lapack_int* lda, lapack_int* ipiv, double* b,\n                   lapack_int* ldb, double* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_csysv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_float* a, lapack_int* lda, lapack_int* ipiv,\n                   lapack_complex_float* b, lapack_int* ldb,\n                   lapack_complex_float* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_zsysv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_double* a, lapack_int* lda, lapack_int* ipiv,\n                   lapack_complex_double* b, lapack_int* ldb,\n                   lapack_complex_double* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_ssysvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const float* a, lapack_int* lda, float* af,\n                    lapack_int* ldaf, lapack_int* ipiv, const float* b,\n                    lapack_int* ldb, float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dsysvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* a, lapack_int* lda, double* af,\n                    lapack_int* ldaf, lapack_int* ipiv, const double* b,\n                    lapack_int* ldb, double* x, lapack_int* ldx, double* rcond,\n                    double* ferr, double* berr, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_csysvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* af, lapack_int* ldaf,\n                    lapack_int* ipiv, const lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* x, lapack_int* ldx,\n                    float* rcond, float* ferr, float* berr,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zsysvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* af, lapack_int* ldaf,\n                    lapack_int* ipiv, const lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                    double* rcond, double* ferr, double* berr,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_dsysvxx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                     double* a, lapack_int* lda, double* af, lapack_int* ldaf,\n                     lapack_int* ipiv, char* equed, double* s, double* b,\n                     lapack_int* ldb, double* x, lapack_int* ldx, double* rcond,\n                     double* rpvgrw, double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params, double* work,\n                     lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ssysvxx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                     float* a, lapack_int* lda, float* af, lapack_int* ldaf,\n                     lapack_int* ipiv, char* equed, float* s, float* b,\n                     lapack_int* ldb, float* x, lapack_int* ldx, float* rcond,\n                     float* rpvgrw, float* berr, lapack_int* n_err_bnds,\n                     float* err_bnds_norm, float* err_bnds_comp,\n                     lapack_int* nparams, float* params, float* work,\n                     lapack_int* iwork, lapack_int *info );\nvoid LAPACK_zsysvxx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                     lapack_complex_double* a, lapack_int* lda,\n                     lapack_complex_double* af, lapack_int* ldaf,\n                     lapack_int* ipiv, char* equed, double* s,\n                     lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                     double* rpvgrw, double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params,\n                     lapack_complex_double* work, double* rwork,\n                     lapack_int *info );\nvoid LAPACK_csysvxx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                     lapack_complex_float* a, lapack_int* lda,\n                     lapack_complex_float* af, lapack_int* ldaf,\n                     lapack_int* ipiv, char* equed, float* s,\n                     lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                     float* rpvgrw, float* berr, lapack_int* n_err_bnds,\n                     float* err_bnds_norm, float* err_bnds_comp,\n                     lapack_int* nparams, float* params,\n                     lapack_complex_float* work, float* rwork,\n                     lapack_int *info );\nvoid LAPACK_chesv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_float* a, lapack_int* lda, lapack_int* ipiv,\n                   lapack_complex_float* b, lapack_int* ldb,\n                   lapack_complex_float* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_zhesv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_double* a, lapack_int* lda, lapack_int* ipiv,\n                   lapack_complex_double* b, lapack_int* ldb,\n                   lapack_complex_double* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_chesvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* af, lapack_int* ldaf,\n                    lapack_int* ipiv, const lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* x, lapack_int* ldx,\n                    float* rcond, float* ferr, float* berr,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zhesvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* af, lapack_int* ldaf,\n                    lapack_int* ipiv, const lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                    double* rcond, double* ferr, double* berr,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_zhesvxx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                     lapack_complex_double* a, lapack_int* lda,\n                     lapack_complex_double* af, lapack_int* ldaf,\n                     lapack_int* ipiv, char* equed, double* s,\n                     lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                     double* rpvgrw, double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params,\n                     lapack_complex_double* work, double* rwork,\n                     lapack_int *info );\nvoid LAPACK_chesvxx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                     lapack_complex_float* a, lapack_int* lda,\n                     lapack_complex_float* af, lapack_int* ldaf,\n                     lapack_int* ipiv, char* equed, float* s,\n                     lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                     float* rpvgrw, float* berr, lapack_int* n_err_bnds,\n                     float* err_bnds_norm, float* err_bnds_comp,\n                     lapack_int* nparams, float* params,\n                     lapack_complex_float* work, float* rwork,\n                     lapack_int *info );\nvoid LAPACK_sspsv( char* uplo, lapack_int* n, lapack_int* nrhs, float* ap,\n                   lapack_int* ipiv, float* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_dspsv( char* uplo, lapack_int* n, lapack_int* nrhs, double* ap,\n                   lapack_int* ipiv, double* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_cspsv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_float* ap, lapack_int* ipiv,\n                   lapack_complex_float* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zspsv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_double* ap, lapack_int* ipiv,\n                   lapack_complex_double* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_sspsvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const float* ap, float* afp, lapack_int* ipiv,\n                    const float* b, lapack_int* ldb, float* x, lapack_int* ldx,\n                    float* rcond, float* ferr, float* berr, float* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dspsvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* ap, double* afp, lapack_int* ipiv,\n                    const double* b, lapack_int* ldb, double* x,\n                    lapack_int* ldx, double* rcond, double* ferr, double* berr,\n                    double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cspsvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* ap, lapack_complex_float* afp,\n                    lapack_int* ipiv, const lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* x, lapack_int* ldx,\n                    float* rcond, float* ferr, float* berr,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zspsvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* ap, lapack_complex_double* afp,\n                    lapack_int* ipiv, const lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                    double* rcond, double* ferr, double* berr,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_chpsv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_float* ap, lapack_int* ipiv,\n                   lapack_complex_float* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zhpsv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_double* ap, lapack_int* ipiv,\n                   lapack_complex_double* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_chpsvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* ap, lapack_complex_float* afp,\n                    lapack_int* ipiv, const lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* x, lapack_int* ldx,\n                    float* rcond, float* ferr, float* berr,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zhpsvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* ap, lapack_complex_double* afp,\n                    lapack_int* ipiv, const lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                    double* rcond, double* ferr, double* berr,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_sgeqrf( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    float* tau, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dgeqrf( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    double* tau, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cgeqrf( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* tau,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zgeqrf( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sgeqpf( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int* jpvt, float* tau, float* work,\n                    lapack_int *info );\nvoid LAPACK_dgeqpf( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int* jpvt, double* tau, double* work,\n                    lapack_int *info );\nvoid LAPACK_cgeqpf( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int* jpvt,\n                    lapack_complex_float* tau, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zgeqpf( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* jpvt,\n                    lapack_complex_double* tau, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_sgeqp3( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int* jpvt, float* tau, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dgeqp3( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int* jpvt, double* tau, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cgeqp3( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int* jpvt,\n                    lapack_complex_float* tau, lapack_complex_float* work,\n                    lapack_int* lwork, float* rwork, lapack_int *info );\nvoid LAPACK_zgeqp3( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* jpvt,\n                    lapack_complex_double* tau, lapack_complex_double* work,\n                    lapack_int* lwork, double* rwork, lapack_int *info );\nvoid LAPACK_sorgqr( lapack_int* m, lapack_int* n, lapack_int* k, float* a,\n                    lapack_int* lda, const float* tau, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dorgqr( lapack_int* m, lapack_int* n, lapack_int* k, double* a,\n                    lapack_int* lda, const double* tau, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sormqr( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const float* a, lapack_int* lda,\n                    const float* tau, float* c, lapack_int* ldc, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dormqr( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const double* a, lapack_int* lda,\n                    const double* tau, double* c, lapack_int* ldc, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cungqr( lapack_int* m, lapack_int* n, lapack_int* k,\n                    lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* tau, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zungqr( lapack_int* m, lapack_int* n, lapack_int* k,\n                    lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cunmqr( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* tau,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zunmqr( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const lapack_complex_double* a,\n                    lapack_int* lda, const lapack_complex_double* tau,\n                    lapack_complex_double* c, lapack_int* ldc,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sgelqf( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    float* tau, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dgelqf( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    double* tau, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cgelqf( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* tau,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zgelqf( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sorglq( lapack_int* m, lapack_int* n, lapack_int* k, float* a,\n                    lapack_int* lda, const float* tau, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dorglq( lapack_int* m, lapack_int* n, lapack_int* k, double* a,\n                    lapack_int* lda, const double* tau, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sormlq( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const float* a, lapack_int* lda,\n                    const float* tau, float* c, lapack_int* ldc, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dormlq( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const double* a, lapack_int* lda,\n                    const double* tau, double* c, lapack_int* ldc, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cunglq( lapack_int* m, lapack_int* n, lapack_int* k,\n                    lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* tau, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zunglq( lapack_int* m, lapack_int* n, lapack_int* k,\n                    lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cunmlq( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* tau,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zunmlq( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const lapack_complex_double* a,\n                    lapack_int* lda, const lapack_complex_double* tau,\n                    lapack_complex_double* c, lapack_int* ldc,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sgeqlf( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    float* tau, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dgeqlf( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    double* tau, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cgeqlf( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* tau,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zgeqlf( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sorgql( lapack_int* m, lapack_int* n, lapack_int* k, float* a,\n                    lapack_int* lda, const float* tau, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dorgql( lapack_int* m, lapack_int* n, lapack_int* k, double* a,\n                    lapack_int* lda, const double* tau, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cungql( lapack_int* m, lapack_int* n, lapack_int* k,\n                    lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* tau, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zungql( lapack_int* m, lapack_int* n, lapack_int* k,\n                    lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sormql( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const float* a, lapack_int* lda,\n                    const float* tau, float* c, lapack_int* ldc, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dormql( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const double* a, lapack_int* lda,\n                    const double* tau, double* c, lapack_int* ldc, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cunmql( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* tau,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zunmql( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const lapack_complex_double* a,\n                    lapack_int* lda, const lapack_complex_double* tau,\n                    lapack_complex_double* c, lapack_int* ldc,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sgerqf( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    float* tau, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dgerqf( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    double* tau, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cgerqf( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* tau,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zgerqf( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sorgrq( lapack_int* m, lapack_int* n, lapack_int* k, float* a,\n                    lapack_int* lda, const float* tau, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dorgrq( lapack_int* m, lapack_int* n, lapack_int* k, double* a,\n                    lapack_int* lda, const double* tau, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cungrq( lapack_int* m, lapack_int* n, lapack_int* k,\n                    lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* tau, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zungrq( lapack_int* m, lapack_int* n, lapack_int* k,\n                    lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sormrq( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const float* a, lapack_int* lda,\n                    const float* tau, float* c, lapack_int* ldc, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dormrq( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const double* a, lapack_int* lda,\n                    const double* tau, double* c, lapack_int* ldc, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cunmrq( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* tau,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zunmrq( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const lapack_complex_double* a,\n                    lapack_int* lda, const lapack_complex_double* tau,\n                    lapack_complex_double* c, lapack_int* ldc,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_stzrzf( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    float* tau, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dtzrzf( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    double* tau, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_ctzrzf( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* tau,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_ztzrzf( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sormrz( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, lapack_int* l, const float* a,\n                    lapack_int* lda, const float* tau, float* c,\n                    lapack_int* ldc, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dormrz( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, lapack_int* l, const double* a,\n                    lapack_int* lda, const double* tau, double* c,\n                    lapack_int* ldc, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cunmrz( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, lapack_int* l, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* tau,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zunmrz( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, lapack_int* l,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* tau, lapack_complex_double* c,\n                    lapack_int* ldc, lapack_complex_double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sggqrf( lapack_int* n, lapack_int* m, lapack_int* p, float* a,\n                    lapack_int* lda, float* taua, float* b, lapack_int* ldb,\n                    float* taub, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dggqrf( lapack_int* n, lapack_int* m, lapack_int* p, double* a,\n                    lapack_int* lda, double* taua, double* b, lapack_int* ldb,\n                    double* taub, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cggqrf( lapack_int* n, lapack_int* m, lapack_int* p,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* taua, lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* taub,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zggqrf( lapack_int* n, lapack_int* m, lapack_int* p,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* taua, lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* taub,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sggrqf( lapack_int* m, lapack_int* p, lapack_int* n, float* a,\n                    lapack_int* lda, float* taua, float* b, lapack_int* ldb,\n                    float* taub, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dggrqf( lapack_int* m, lapack_int* p, lapack_int* n, double* a,\n                    lapack_int* lda, double* taua, double* b, lapack_int* ldb,\n                    double* taub, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cggrqf( lapack_int* m, lapack_int* p, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* taua, lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* taub,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zggrqf( lapack_int* m, lapack_int* p, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* taua, lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* taub,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sgebrd( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    float* d, float* e, float* tauq, float* taup, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dgebrd( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    double* d, double* e, double* tauq, double* taup,\n                    double* work, lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cgebrd( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, float* d, float* e,\n                    lapack_complex_float* tauq, lapack_complex_float* taup,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zgebrd( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, double* d, double* e,\n                    lapack_complex_double* tauq, lapack_complex_double* taup,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sgbbrd( char* vect, lapack_int* m, lapack_int* n, lapack_int* ncc,\n                    lapack_int* kl, lapack_int* ku, float* ab, lapack_int* ldab,\n                    float* d, float* e, float* q, lapack_int* ldq, float* pt,\n                    lapack_int* ldpt, float* c, lapack_int* ldc, float* work,\n                    lapack_int *info );\nvoid LAPACK_dgbbrd( char* vect, lapack_int* m, lapack_int* n, lapack_int* ncc,\n                    lapack_int* kl, lapack_int* ku, double* ab,\n                    lapack_int* ldab, double* d, double* e, double* q,\n                    lapack_int* ldq, double* pt, lapack_int* ldpt, double* c,\n                    lapack_int* ldc, double* work, lapack_int *info );\nvoid LAPACK_cgbbrd( char* vect, lapack_int* m, lapack_int* n, lapack_int* ncc,\n                    lapack_int* kl, lapack_int* ku, lapack_complex_float* ab,\n                    lapack_int* ldab, float* d, float* e,\n                    lapack_complex_float* q, lapack_int* ldq,\n                    lapack_complex_float* pt, lapack_int* ldpt,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zgbbrd( char* vect, lapack_int* m, lapack_int* n, lapack_int* ncc,\n                    lapack_int* kl, lapack_int* ku, lapack_complex_double* ab,\n                    lapack_int* ldab, double* d, double* e,\n                    lapack_complex_double* q, lapack_int* ldq,\n                    lapack_complex_double* pt, lapack_int* ldpt,\n                    lapack_complex_double* c, lapack_int* ldc,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_sorgbr( char* vect, lapack_int* m, lapack_int* n, lapack_int* k,\n                    float* a, lapack_int* lda, const float* tau, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dorgbr( char* vect, lapack_int* m, lapack_int* n, lapack_int* k,\n                    double* a, lapack_int* lda, const double* tau, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sormbr( char* vect, char* side, char* trans, lapack_int* m,\n                    lapack_int* n, lapack_int* k, const float* a,\n                    lapack_int* lda, const float* tau, float* c,\n                    lapack_int* ldc, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dormbr( char* vect, char* side, char* trans, lapack_int* m,\n                    lapack_int* n, lapack_int* k, const double* a,\n                    lapack_int* lda, const double* tau, double* c,\n                    lapack_int* ldc, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cungbr( char* vect, lapack_int* m, lapack_int* n, lapack_int* k,\n                    lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* tau, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zungbr( char* vect, lapack_int* m, lapack_int* n, lapack_int* k,\n                    lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cunmbr( char* vect, char* side, char* trans, lapack_int* m,\n                    lapack_int* n, lapack_int* k, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* tau,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zunmbr( char* vect, char* side, char* trans, lapack_int* m,\n                    lapack_int* n, lapack_int* k,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* tau, lapack_complex_double* c,\n                    lapack_int* ldc, lapack_complex_double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sbdsqr( char* uplo, lapack_int* n, lapack_int* ncvt,\n                    lapack_int* nru, lapack_int* ncc, float* d, float* e,\n                    float* vt, lapack_int* ldvt, float* u, lapack_int* ldu,\n                    float* c, lapack_int* ldc, float* work, lapack_int *info );\nvoid LAPACK_dbdsqr( char* uplo, lapack_int* n, lapack_int* ncvt,\n                    lapack_int* nru, lapack_int* ncc, double* d, double* e,\n                    double* vt, lapack_int* ldvt, double* u, lapack_int* ldu,\n                    double* c, lapack_int* ldc, double* work,\n                    lapack_int *info );\nvoid LAPACK_cbdsqr( char* uplo, lapack_int* n, lapack_int* ncvt,\n                    lapack_int* nru, lapack_int* ncc, float* d, float* e,\n                    lapack_complex_float* vt, lapack_int* ldvt,\n                    lapack_complex_float* u, lapack_int* ldu,\n                    lapack_complex_float* c, lapack_int* ldc, float* work,\n                    lapack_int *info );\nvoid LAPACK_zbdsqr( char* uplo, lapack_int* n, lapack_int* ncvt,\n                    lapack_int* nru, lapack_int* ncc, double* d, double* e,\n                    lapack_complex_double* vt, lapack_int* ldvt,\n                    lapack_complex_double* u, lapack_int* ldu,\n                    lapack_complex_double* c, lapack_int* ldc, double* work,\n                    lapack_int *info );\nvoid LAPACK_sbdsdc( char* uplo, char* compq, lapack_int* n, float* d, float* e,\n                    float* u, lapack_int* ldu, float* vt, lapack_int* ldvt,\n                    float* q, lapack_int* iq, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dbdsdc( char* uplo, char* compq, lapack_int* n, double* d,\n                    double* e, double* u, lapack_int* ldu, double* vt,\n                    lapack_int* ldvt, double* q, lapack_int* iq, double* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ssytrd( char* uplo, lapack_int* n, float* a, lapack_int* lda,\n                    float* d, float* e, float* tau, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dsytrd( char* uplo, lapack_int* n, double* a, lapack_int* lda,\n                    double* d, double* e, double* tau, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sorgtr( char* uplo, lapack_int* n, float* a, lapack_int* lda,\n                    const float* tau, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dorgtr( char* uplo, lapack_int* n, double* a, lapack_int* lda,\n                    const double* tau, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sormtr( char* side, char* uplo, char* trans, lapack_int* m,\n                    lapack_int* n, const float* a, lapack_int* lda,\n                    const float* tau, float* c, lapack_int* ldc, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dormtr( char* side, char* uplo, char* trans, lapack_int* m,\n                    lapack_int* n, const double* a, lapack_int* lda,\n                    const double* tau, double* c, lapack_int* ldc, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_chetrd( char* uplo, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, float* d, float* e,\n                    lapack_complex_float* tau, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zhetrd( char* uplo, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, double* d, double* e,\n                    lapack_complex_double* tau, lapack_complex_double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cungtr( char* uplo, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* tau,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zungtr( char* uplo, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, const lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cunmtr( char* side, char* uplo, char* trans, lapack_int* m,\n                    lapack_int* n, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* tau,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zunmtr( char* side, char* uplo, char* trans, lapack_int* m,\n                    lapack_int* n, const lapack_complex_double* a,\n                    lapack_int* lda, const lapack_complex_double* tau,\n                    lapack_complex_double* c, lapack_int* ldc,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_ssptrd( char* uplo, lapack_int* n, float* ap, float* d, float* e,\n                    float* tau, lapack_int *info );\nvoid LAPACK_dsptrd( char* uplo, lapack_int* n, double* ap, double* d, double* e,\n                    double* tau, lapack_int *info );\nvoid LAPACK_sopgtr( char* uplo, lapack_int* n, const float* ap,\n                    const float* tau, float* q, lapack_int* ldq, float* work,\n                    lapack_int *info );\nvoid LAPACK_dopgtr( char* uplo, lapack_int* n, const double* ap,\n                    const double* tau, double* q, lapack_int* ldq, double* work,\n                    lapack_int *info );\nvoid LAPACK_sopmtr( char* side, char* uplo, char* trans, lapack_int* m,\n                    lapack_int* n, const float* ap, const float* tau, float* c,\n                    lapack_int* ldc, float* work, lapack_int *info );\nvoid LAPACK_dopmtr( char* side, char* uplo, char* trans, lapack_int* m,\n                    lapack_int* n, const double* ap, const double* tau,\n                    double* c, lapack_int* ldc, double* work,\n                    lapack_int *info );\nvoid LAPACK_chptrd( char* uplo, lapack_int* n, lapack_complex_float* ap,\n                    float* d, float* e, lapack_complex_float* tau,\n                    lapack_int *info );\nvoid LAPACK_zhptrd( char* uplo, lapack_int* n, lapack_complex_double* ap,\n                    double* d, double* e, lapack_complex_double* tau,\n                    lapack_int *info );\nvoid LAPACK_cupgtr( char* uplo, lapack_int* n, const lapack_complex_float* ap,\n                    const lapack_complex_float* tau, lapack_complex_float* q,\n                    lapack_int* ldq, lapack_complex_float* work,\n                    lapack_int *info );\nvoid LAPACK_zupgtr( char* uplo, lapack_int* n, const lapack_complex_double* ap,\n                    const lapack_complex_double* tau, lapack_complex_double* q,\n                    lapack_int* ldq, lapack_complex_double* work,\n                    lapack_int *info );\nvoid LAPACK_cupmtr( char* side, char* uplo, char* trans, lapack_int* m,\n                    lapack_int* n, const lapack_complex_float* ap,\n                    const lapack_complex_float* tau, lapack_complex_float* c,\n                    lapack_int* ldc, lapack_complex_float* work,\n                    lapack_int *info );\nvoid LAPACK_zupmtr( char* side, char* uplo, char* trans, lapack_int* m,\n                    lapack_int* n, const lapack_complex_double* ap,\n                    const lapack_complex_double* tau, lapack_complex_double* c,\n                    lapack_int* ldc, lapack_complex_double* work,\n                    lapack_int *info );\nvoid LAPACK_ssbtrd( char* vect, char* uplo, lapack_int* n, lapack_int* kd,\n                    float* ab, lapack_int* ldab, float* d, float* e, float* q,\n                    lapack_int* ldq, float* work, lapack_int *info );\nvoid LAPACK_dsbtrd( char* vect, char* uplo, lapack_int* n, lapack_int* kd,\n                    double* ab, lapack_int* ldab, double* d, double* e,\n                    double* q, lapack_int* ldq, double* work,\n                    lapack_int *info );\nvoid LAPACK_chbtrd( char* vect, char* uplo, lapack_int* n, lapack_int* kd,\n                    lapack_complex_float* ab, lapack_int* ldab, float* d,\n                    float* e, lapack_complex_float* q, lapack_int* ldq,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zhbtrd( char* vect, char* uplo, lapack_int* n, lapack_int* kd,\n                    lapack_complex_double* ab, lapack_int* ldab, double* d,\n                    double* e, lapack_complex_double* q, lapack_int* ldq,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_ssterf( lapack_int* n, float* d, float* e, lapack_int *info );\nvoid LAPACK_dsterf( lapack_int* n, double* d, double* e, lapack_int *info );\nvoid LAPACK_ssteqr( char* compz, lapack_int* n, float* d, float* e, float* z,\n                    lapack_int* ldz, float* work, lapack_int *info );\nvoid LAPACK_dsteqr( char* compz, lapack_int* n, double* d, double* e, double* z,\n                    lapack_int* ldz, double* work, lapack_int *info );\nvoid LAPACK_csteqr( char* compz, lapack_int* n, float* d, float* e,\n                    lapack_complex_float* z, lapack_int* ldz, float* work,\n                    lapack_int *info );\nvoid LAPACK_zsteqr( char* compz, lapack_int* n, double* d, double* e,\n                    lapack_complex_double* z, lapack_int* ldz, double* work,\n                    lapack_int *info );\nvoid LAPACK_sstemr( char* jobz, char* range, lapack_int* n, float* d, float* e,\n                    float* vl, float* vu, lapack_int* il, lapack_int* iu,\n                    lapack_int* m, float* w, float* z, lapack_int* ldz,\n                    lapack_int* nzc, lapack_int* isuppz, lapack_logical* tryrac,\n                    float* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dstemr( char* jobz, char* range, lapack_int* n, double* d,\n                    double* e, double* vl, double* vu, lapack_int* il,\n                    lapack_int* iu, lapack_int* m, double* w, double* z,\n                    lapack_int* ldz, lapack_int* nzc, lapack_int* isuppz,\n                    lapack_logical* tryrac, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_cstemr( char* jobz, char* range, lapack_int* n, float* d, float* e,\n                    float* vl, float* vu, lapack_int* il, lapack_int* iu,\n                    lapack_int* m, float* w, lapack_complex_float* z,\n                    lapack_int* ldz, lapack_int* nzc, lapack_int* isuppz,\n                    lapack_logical* tryrac, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_zstemr( char* jobz, char* range, lapack_int* n, double* d,\n                    double* e, double* vl, double* vu, lapack_int* il,\n                    lapack_int* iu, lapack_int* m, double* w,\n                    lapack_complex_double* z, lapack_int* ldz, lapack_int* nzc,\n                    lapack_int* isuppz, lapack_logical* tryrac, double* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_sstedc( char* compz, lapack_int* n, float* d, float* e, float* z,\n                    lapack_int* ldz, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dstedc( char* compz, lapack_int* n, double* d, double* e, double* z,\n                    lapack_int* ldz, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_cstedc( char* compz, lapack_int* n, float* d, float* e,\n                    lapack_complex_float* z, lapack_int* ldz,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int* lrwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_zstedc( char* compz, lapack_int* n, double* d, double* e,\n                    lapack_complex_double* z, lapack_int* ldz,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* lrwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_sstegr( char* jobz, char* range, lapack_int* n, float* d, float* e,\n                    float* vl, float* vu, lapack_int* il, lapack_int* iu,\n                    float* abstol, lapack_int* m, float* w, float* z,\n                    lapack_int* ldz, lapack_int* isuppz, float* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_dstegr( char* jobz, char* range, lapack_int* n, double* d,\n                    double* e, double* vl, double* vu, lapack_int* il,\n                    lapack_int* iu, double* abstol, lapack_int* m, double* w,\n                    double* z, lapack_int* ldz, lapack_int* isuppz,\n                    double* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_cstegr( char* jobz, char* range, lapack_int* n, float* d, float* e,\n                    float* vl, float* vu, lapack_int* il, lapack_int* iu,\n                    float* abstol, lapack_int* m, float* w,\n                    lapack_complex_float* z, lapack_int* ldz,\n                    lapack_int* isuppz, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_zstegr( char* jobz, char* range, lapack_int* n, double* d,\n                    double* e, double* vl, double* vu, lapack_int* il,\n                    lapack_int* iu, double* abstol, lapack_int* m, double* w,\n                    lapack_complex_double* z, lapack_int* ldz,\n                    lapack_int* isuppz, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_spteqr( char* compz, lapack_int* n, float* d, float* e, float* z,\n                    lapack_int* ldz, float* work, lapack_int *info );\nvoid LAPACK_dpteqr( char* compz, lapack_int* n, double* d, double* e, double* z,\n                    lapack_int* ldz, double* work, lapack_int *info );\nvoid LAPACK_cpteqr( char* compz, lapack_int* n, float* d, float* e,\n                    lapack_complex_float* z, lapack_int* ldz, float* work,\n                    lapack_int *info );\nvoid LAPACK_zpteqr( char* compz, lapack_int* n, double* d, double* e,\n                    lapack_complex_double* z, lapack_int* ldz, double* work,\n                    lapack_int *info );\nvoid LAPACK_sstebz( char* range, char* order, lapack_int* n, float* vl,\n                    float* vu, lapack_int* il, lapack_int* iu, float* abstol,\n                    const float* d, const float* e, lapack_int* m,\n                    lapack_int* nsplit, float* w, lapack_int* iblock,\n                    lapack_int* isplit, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dstebz( char* range, char* order, lapack_int* n, double* vl,\n                    double* vu, lapack_int* il, lapack_int* iu, double* abstol,\n                    const double* d, const double* e, lapack_int* m,\n                    lapack_int* nsplit, double* w, lapack_int* iblock,\n                    lapack_int* isplit, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_sstein( lapack_int* n, const float* d, const float* e,\n                    lapack_int* m, const float* w, const lapack_int* iblock,\n                    const lapack_int* isplit, float* z, lapack_int* ldz,\n                    float* work, lapack_int* iwork, lapack_int* ifailv,\n                    lapack_int *info );\nvoid LAPACK_dstein( lapack_int* n, const double* d, const double* e,\n                    lapack_int* m, const double* w, const lapack_int* iblock,\n                    const lapack_int* isplit, double* z, lapack_int* ldz,\n                    double* work, lapack_int* iwork, lapack_int* ifailv,\n                    lapack_int *info );\nvoid LAPACK_cstein( lapack_int* n, const float* d, const float* e,\n                    lapack_int* m, const float* w, const lapack_int* iblock,\n                    const lapack_int* isplit, lapack_complex_float* z,\n                    lapack_int* ldz, float* work, lapack_int* iwork,\n                    lapack_int* ifailv, lapack_int *info );\nvoid LAPACK_zstein( lapack_int* n, const double* d, const double* e,\n                    lapack_int* m, const double* w, const lapack_int* iblock,\n                    const lapack_int* isplit, lapack_complex_double* z,\n                    lapack_int* ldz, double* work, lapack_int* iwork,\n                    lapack_int* ifailv, lapack_int *info );\nvoid LAPACK_sdisna( char* job, lapack_int* m, lapack_int* n, const float* d,\n                    float* sep, lapack_int *info );\nvoid LAPACK_ddisna( char* job, lapack_int* m, lapack_int* n, const double* d,\n                    double* sep, lapack_int *info );\nvoid LAPACK_ssygst( lapack_int* itype, char* uplo, lapack_int* n, float* a,\n                    lapack_int* lda, const float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_dsygst( lapack_int* itype, char* uplo, lapack_int* n, double* a,\n                    lapack_int* lda, const double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_chegst( lapack_int* itype, char* uplo, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_zhegst( lapack_int* itype, char* uplo, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_sspgst( lapack_int* itype, char* uplo, lapack_int* n, float* ap,\n                    const float* bp, lapack_int *info );\nvoid LAPACK_dspgst( lapack_int* itype, char* uplo, lapack_int* n, double* ap,\n                    const double* bp, lapack_int *info );\nvoid LAPACK_chpgst( lapack_int* itype, char* uplo, lapack_int* n,\n                    lapack_complex_float* ap, const lapack_complex_float* bp,\n                    lapack_int *info );\nvoid LAPACK_zhpgst( lapack_int* itype, char* uplo, lapack_int* n,\n                    lapack_complex_double* ap, const lapack_complex_double* bp,\n                    lapack_int *info );\nvoid LAPACK_ssbgst( char* vect, char* uplo, lapack_int* n, lapack_int* ka,\n                    lapack_int* kb, float* ab, lapack_int* ldab,\n                    const float* bb, lapack_int* ldbb, float* x,\n                    lapack_int* ldx, float* work, lapack_int *info );\nvoid LAPACK_dsbgst( char* vect, char* uplo, lapack_int* n, lapack_int* ka,\n                    lapack_int* kb, double* ab, lapack_int* ldab,\n                    const double* bb, lapack_int* ldbb, double* x,\n                    lapack_int* ldx, double* work, lapack_int *info );\nvoid LAPACK_chbgst( char* vect, char* uplo, lapack_int* n, lapack_int* ka,\n                    lapack_int* kb, lapack_complex_float* ab, lapack_int* ldab,\n                    const lapack_complex_float* bb, lapack_int* ldbb,\n                    lapack_complex_float* x, lapack_int* ldx,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zhbgst( char* vect, char* uplo, lapack_int* n, lapack_int* ka,\n                    lapack_int* kb, lapack_complex_double* ab, lapack_int* ldab,\n                    const lapack_complex_double* bb, lapack_int* ldbb,\n                    lapack_complex_double* x, lapack_int* ldx,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_spbstf( char* uplo, lapack_int* n, lapack_int* kb, float* bb,\n                    lapack_int* ldbb, lapack_int *info );\nvoid LAPACK_dpbstf( char* uplo, lapack_int* n, lapack_int* kb, double* bb,\n                    lapack_int* ldbb, lapack_int *info );\nvoid LAPACK_cpbstf( char* uplo, lapack_int* n, lapack_int* kb,\n                    lapack_complex_float* bb, lapack_int* ldbb,\n                    lapack_int *info );\nvoid LAPACK_zpbstf( char* uplo, lapack_int* n, lapack_int* kb,\n                    lapack_complex_double* bb, lapack_int* ldbb,\n                    lapack_int *info );\nvoid LAPACK_sgehrd( lapack_int* n, lapack_int* ilo, lapack_int* ihi, float* a,\n                    lapack_int* lda, float* tau, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dgehrd( lapack_int* n, lapack_int* ilo, lapack_int* ihi, double* a,\n                    lapack_int* lda, double* tau, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cgehrd( lapack_int* n, lapack_int* ilo, lapack_int* ihi,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* tau, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zgehrd( lapack_int* n, lapack_int* ilo, lapack_int* ihi,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* tau, lapack_complex_double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sorghr( lapack_int* n, lapack_int* ilo, lapack_int* ihi, float* a,\n                    lapack_int* lda, const float* tau, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dorghr( lapack_int* n, lapack_int* ilo, lapack_int* ihi, double* a,\n                    lapack_int* lda, const double* tau, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sormhr( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* ilo, lapack_int* ihi, const float* a,\n                    lapack_int* lda, const float* tau, float* c,\n                    lapack_int* ldc, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dormhr( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* ilo, lapack_int* ihi, const double* a,\n                    lapack_int* lda, const double* tau, double* c,\n                    lapack_int* ldc, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cunghr( lapack_int* n, lapack_int* ilo, lapack_int* ihi,\n                    lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* tau, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zunghr( lapack_int* n, lapack_int* ilo, lapack_int* ihi,\n                    lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cunmhr( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* ilo, lapack_int* ihi,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* tau, lapack_complex_float* c,\n                    lapack_int* ldc, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zunmhr( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* ilo, lapack_int* ihi,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* tau, lapack_complex_double* c,\n                    lapack_int* ldc, lapack_complex_double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sgebal( char* job, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int* ilo, lapack_int* ihi, float* scale,\n                    lapack_int *info );\nvoid LAPACK_dgebal( char* job, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int* ilo, lapack_int* ihi, double* scale,\n                    lapack_int *info );\nvoid LAPACK_cgebal( char* job, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int* ilo, lapack_int* ihi,\n                    float* scale, lapack_int *info );\nvoid LAPACK_zgebal( char* job, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* ilo, lapack_int* ihi,\n                    double* scale, lapack_int *info );\nvoid LAPACK_sgebak( char* job, char* side, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, const float* scale, lapack_int* m,\n                    float* v, lapack_int* ldv, lapack_int *info );\nvoid LAPACK_dgebak( char* job, char* side, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, const double* scale, lapack_int* m,\n                    double* v, lapack_int* ldv, lapack_int *info );\nvoid LAPACK_cgebak( char* job, char* side, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, const float* scale, lapack_int* m,\n                    lapack_complex_float* v, lapack_int* ldv,\n                    lapack_int *info );\nvoid LAPACK_zgebak( char* job, char* side, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, const double* scale, lapack_int* m,\n                    lapack_complex_double* v, lapack_int* ldv,\n                    lapack_int *info );\nvoid LAPACK_shseqr( char* job, char* compz, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, float* h, lapack_int* ldh, float* wr,\n                    float* wi, float* z, lapack_int* ldz, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dhseqr( char* job, char* compz, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, double* h, lapack_int* ldh, double* wr,\n                    double* wi, double* z, lapack_int* ldz, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_chseqr( char* job, char* compz, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, lapack_complex_float* h, lapack_int* ldh,\n                    lapack_complex_float* w, lapack_complex_float* z,\n                    lapack_int* ldz, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zhseqr( char* job, char* compz, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, lapack_complex_double* h, lapack_int* ldh,\n                    lapack_complex_double* w, lapack_complex_double* z,\n                    lapack_int* ldz, lapack_complex_double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_shsein( char* job, char* eigsrc, char* initv,\n                    lapack_logical* select, lapack_int* n, const float* h,\n                    lapack_int* ldh, float* wr, const float* wi, float* vl,\n                    lapack_int* ldvl, float* vr, lapack_int* ldvr,\n                    lapack_int* mm, lapack_int* m, float* work,\n                    lapack_int* ifaill, lapack_int* ifailr, lapack_int *info );\nvoid LAPACK_dhsein( char* job, char* eigsrc, char* initv,\n                    lapack_logical* select, lapack_int* n, const double* h,\n                    lapack_int* ldh, double* wr, const double* wi, double* vl,\n                    lapack_int* ldvl, double* vr, lapack_int* ldvr,\n                    lapack_int* mm, lapack_int* m, double* work,\n                    lapack_int* ifaill, lapack_int* ifailr, lapack_int *info );\nvoid LAPACK_chsein( char* job, char* eigsrc, char* initv,\n                    const lapack_logical* select, lapack_int* n,\n                    const lapack_complex_float* h, lapack_int* ldh,\n                    lapack_complex_float* w, lapack_complex_float* vl,\n                    lapack_int* ldvl, lapack_complex_float* vr,\n                    lapack_int* ldvr, lapack_int* mm, lapack_int* m,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int* ifaill, lapack_int* ifailr, lapack_int *info );\nvoid LAPACK_zhsein( char* job, char* eigsrc, char* initv,\n                    const lapack_logical* select, lapack_int* n,\n                    const lapack_complex_double* h, lapack_int* ldh,\n                    lapack_complex_double* w, lapack_complex_double* vl,\n                    lapack_int* ldvl, lapack_complex_double* vr,\n                    lapack_int* ldvr, lapack_int* mm, lapack_int* m,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int* ifaill, lapack_int* ifailr, lapack_int *info );\nvoid LAPACK_strevc( char* side, char* howmny, lapack_logical* select,\n                    lapack_int* n, const float* t, lapack_int* ldt, float* vl,\n                    lapack_int* ldvl, float* vr, lapack_int* ldvr,\n                    lapack_int* mm, lapack_int* m, float* work,\n                    lapack_int *info );\nvoid LAPACK_dtrevc( char* side, char* howmny, lapack_logical* select,\n                    lapack_int* n, const double* t, lapack_int* ldt, double* vl,\n                    lapack_int* ldvl, double* vr, lapack_int* ldvr,\n                    lapack_int* mm, lapack_int* m, double* work,\n                    lapack_int *info );\nvoid LAPACK_ctrevc( char* side, char* howmny, const lapack_logical* select,\n                    lapack_int* n, lapack_complex_float* t, lapack_int* ldt,\n                    lapack_complex_float* vl, lapack_int* ldvl,\n                    lapack_complex_float* vr, lapack_int* ldvr, lapack_int* mm,\n                    lapack_int* m, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_ztrevc( char* side, char* howmny, const lapack_logical* select,\n                    lapack_int* n, lapack_complex_double* t, lapack_int* ldt,\n                    lapack_complex_double* vl, lapack_int* ldvl,\n                    lapack_complex_double* vr, lapack_int* ldvr, lapack_int* mm,\n                    lapack_int* m, lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_strsna( char* job, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const float* t, lapack_int* ldt,\n                    const float* vl, lapack_int* ldvl, const float* vr,\n                    lapack_int* ldvr, float* s, float* sep, lapack_int* mm,\n                    lapack_int* m, float* work, lapack_int* ldwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dtrsna( char* job, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const double* t, lapack_int* ldt,\n                    const double* vl, lapack_int* ldvl, const double* vr,\n                    lapack_int* ldvr, double* s, double* sep, lapack_int* mm,\n                    lapack_int* m, double* work, lapack_int* ldwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ctrsna( char* job, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const lapack_complex_float* t,\n                    lapack_int* ldt, const lapack_complex_float* vl,\n                    lapack_int* ldvl, const lapack_complex_float* vr,\n                    lapack_int* ldvr, float* s, float* sep, lapack_int* mm,\n                    lapack_int* m, lapack_complex_float* work,\n                    lapack_int* ldwork, float* rwork, lapack_int *info );\nvoid LAPACK_ztrsna( char* job, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const lapack_complex_double* t,\n                    lapack_int* ldt, const lapack_complex_double* vl,\n                    lapack_int* ldvl, const lapack_complex_double* vr,\n                    lapack_int* ldvr, double* s, double* sep, lapack_int* mm,\n                    lapack_int* m, lapack_complex_double* work,\n                    lapack_int* ldwork, double* rwork, lapack_int *info );\nvoid LAPACK_strexc( char* compq, lapack_int* n, float* t, lapack_int* ldt,\n                    float* q, lapack_int* ldq, lapack_int* ifst,\n                    lapack_int* ilst, float* work, lapack_int *info );\nvoid LAPACK_dtrexc( char* compq, lapack_int* n, double* t, lapack_int* ldt,\n                    double* q, lapack_int* ldq, lapack_int* ifst,\n                    lapack_int* ilst, double* work, lapack_int *info );\nvoid LAPACK_ctrexc( char* compq, lapack_int* n, lapack_complex_float* t,\n                    lapack_int* ldt, lapack_complex_float* q, lapack_int* ldq,\n                    lapack_int* ifst, lapack_int* ilst, lapack_int *info );\nvoid LAPACK_ztrexc( char* compq, lapack_int* n, lapack_complex_double* t,\n                    lapack_int* ldt, lapack_complex_double* q, lapack_int* ldq,\n                    lapack_int* ifst, lapack_int* ilst, lapack_int *info );\nvoid LAPACK_strsen( char* job, char* compq, const lapack_logical* select,\n                    lapack_int* n, float* t, lapack_int* ldt, float* q,\n                    lapack_int* ldq, float* wr, float* wi, lapack_int* m,\n                    float* s, float* sep, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dtrsen( char* job, char* compq, const lapack_logical* select,\n                    lapack_int* n, double* t, lapack_int* ldt, double* q,\n                    lapack_int* ldq, double* wr, double* wi, lapack_int* m,\n                    double* s, double* sep, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_ctrsen( char* job, char* compq, const lapack_logical* select,\n                    lapack_int* n, lapack_complex_float* t, lapack_int* ldt,\n                    lapack_complex_float* q, lapack_int* ldq,\n                    lapack_complex_float* w, lapack_int* m, float* s,\n                    float* sep, lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_ztrsen( char* job, char* compq, const lapack_logical* select,\n                    lapack_int* n, lapack_complex_double* t, lapack_int* ldt,\n                    lapack_complex_double* q, lapack_int* ldq,\n                    lapack_complex_double* w, lapack_int* m, double* s,\n                    double* sep, lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_strsyl( char* trana, char* tranb, lapack_int* isgn, lapack_int* m,\n                    lapack_int* n, const float* a, lapack_int* lda,\n                    const float* b, lapack_int* ldb, float* c, lapack_int* ldc,\n                    float* scale, lapack_int *info );\nvoid LAPACK_dtrsyl( char* trana, char* tranb, lapack_int* isgn, lapack_int* m,\n                    lapack_int* n, const double* a, lapack_int* lda,\n                    const double* b, lapack_int* ldb, double* c,\n                    lapack_int* ldc, double* scale, lapack_int *info );\nvoid LAPACK_ctrsyl( char* trana, char* tranb, lapack_int* isgn, lapack_int* m,\n                    lapack_int* n, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* c, lapack_int* ldc,\n                    float* scale, lapack_int *info );\nvoid LAPACK_ztrsyl( char* trana, char* tranb, lapack_int* isgn, lapack_int* m,\n                    lapack_int* n, const lapack_complex_double* a,\n                    lapack_int* lda, const lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* c, lapack_int* ldc,\n                    double* scale, lapack_int *info );\nvoid LAPACK_sgghrd( char* compq, char* compz, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, float* a, lapack_int* lda, float* b,\n                    lapack_int* ldb, float* q, lapack_int* ldq, float* z,\n                    lapack_int* ldz, lapack_int *info );\nvoid LAPACK_dgghrd( char* compq, char* compz, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, double* a, lapack_int* lda, double* b,\n                    lapack_int* ldb, double* q, lapack_int* ldq, double* z,\n                    lapack_int* ldz, lapack_int *info );\nvoid LAPACK_cgghrd( char* compq, char* compz, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* q, lapack_int* ldq,\n                    lapack_complex_float* z, lapack_int* ldz,\n                    lapack_int *info );\nvoid LAPACK_zgghrd( char* compq, char* compz, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* q, lapack_int* ldq,\n                    lapack_complex_double* z, lapack_int* ldz,\n                    lapack_int *info );\nvoid LAPACK_sggbal( char* job, lapack_int* n, float* a, lapack_int* lda,\n                    float* b, lapack_int* ldb, lapack_int* ilo, lapack_int* ihi,\n                    float* lscale, float* rscale, float* work,\n                    lapack_int *info );\nvoid LAPACK_dggbal( char* job, lapack_int* n, double* a, lapack_int* lda,\n                    double* b, lapack_int* ldb, lapack_int* ilo,\n                    lapack_int* ihi, double* lscale, double* rscale,\n                    double* work, lapack_int *info );\nvoid LAPACK_cggbal( char* job, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int* ilo, lapack_int* ihi, float* lscale,\n                    float* rscale, float* work, lapack_int *info );\nvoid LAPACK_zggbal( char* job, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int* ilo, lapack_int* ihi, double* lscale,\n                    double* rscale, double* work, lapack_int *info );\nvoid LAPACK_sggbak( char* job, char* side, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, const float* lscale, const float* rscale,\n                    lapack_int* m, float* v, lapack_int* ldv,\n                    lapack_int *info );\nvoid LAPACK_dggbak( char* job, char* side, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, const double* lscale, const double* rscale,\n                    lapack_int* m, double* v, lapack_int* ldv,\n                    lapack_int *info );\nvoid LAPACK_cggbak( char* job, char* side, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, const float* lscale, const float* rscale,\n                    lapack_int* m, lapack_complex_float* v, lapack_int* ldv,\n                    lapack_int *info );\nvoid LAPACK_zggbak( char* job, char* side, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, const double* lscale, const double* rscale,\n                    lapack_int* m, lapack_complex_double* v, lapack_int* ldv,\n                    lapack_int *info );\nvoid LAPACK_shgeqz( char* job, char* compq, char* compz, lapack_int* n,\n                    lapack_int* ilo, lapack_int* ihi, float* h, lapack_int* ldh,\n                    float* t, lapack_int* ldt, float* alphar, float* alphai,\n                    float* beta, float* q, lapack_int* ldq, float* z,\n                    lapack_int* ldz, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dhgeqz( char* job, char* compq, char* compz, lapack_int* n,\n                    lapack_int* ilo, lapack_int* ihi, double* h,\n                    lapack_int* ldh, double* t, lapack_int* ldt, double* alphar,\n                    double* alphai, double* beta, double* q, lapack_int* ldq,\n                    double* z, lapack_int* ldz, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_chgeqz( char* job, char* compq, char* compz, lapack_int* n,\n                    lapack_int* ilo, lapack_int* ihi, lapack_complex_float* h,\n                    lapack_int* ldh, lapack_complex_float* t, lapack_int* ldt,\n                    lapack_complex_float* alpha, lapack_complex_float* beta,\n                    lapack_complex_float* q, lapack_int* ldq,\n                    lapack_complex_float* z, lapack_int* ldz,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zhgeqz( char* job, char* compq, char* compz, lapack_int* n,\n                    lapack_int* ilo, lapack_int* ihi, lapack_complex_double* h,\n                    lapack_int* ldh, lapack_complex_double* t, lapack_int* ldt,\n                    lapack_complex_double* alpha, lapack_complex_double* beta,\n                    lapack_complex_double* q, lapack_int* ldq,\n                    lapack_complex_double* z, lapack_int* ldz,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_stgevc( char* side, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const float* s, lapack_int* lds,\n                    const float* p, lapack_int* ldp, float* vl,\n                    lapack_int* ldvl, float* vr, lapack_int* ldvr,\n                    lapack_int* mm, lapack_int* m, float* work,\n                    lapack_int *info );\nvoid LAPACK_dtgevc( char* side, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const double* s, lapack_int* lds,\n                    const double* p, lapack_int* ldp, double* vl,\n                    lapack_int* ldvl, double* vr, lapack_int* ldvr,\n                    lapack_int* mm, lapack_int* m, double* work,\n                    lapack_int *info );\nvoid LAPACK_ctgevc( char* side, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const lapack_complex_float* s,\n                    lapack_int* lds, const lapack_complex_float* p,\n                    lapack_int* ldp, lapack_complex_float* vl, lapack_int* ldvl,\n                    lapack_complex_float* vr, lapack_int* ldvr, lapack_int* mm,\n                    lapack_int* m, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_ztgevc( char* side, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const lapack_complex_double* s,\n                    lapack_int* lds, const lapack_complex_double* p,\n                    lapack_int* ldp, lapack_complex_double* vl,\n                    lapack_int* ldvl, lapack_complex_double* vr,\n                    lapack_int* ldvr, lapack_int* mm, lapack_int* m,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_stgexc( lapack_logical* wantq, lapack_logical* wantz, lapack_int* n,\n                    float* a, lapack_int* lda, float* b, lapack_int* ldb,\n                    float* q, lapack_int* ldq, float* z, lapack_int* ldz,\n                    lapack_int* ifst, lapack_int* ilst, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dtgexc( lapack_logical* wantq, lapack_logical* wantz, lapack_int* n,\n                    double* a, lapack_int* lda, double* b, lapack_int* ldb,\n                    double* q, lapack_int* ldq, double* z, lapack_int* ldz,\n                    lapack_int* ifst, lapack_int* ilst, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_ctgexc( lapack_logical* wantq, lapack_logical* wantz, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* q, lapack_int* ldq,\n                    lapack_complex_float* z, lapack_int* ldz, lapack_int* ifst,\n                    lapack_int* ilst, lapack_int *info );\nvoid LAPACK_ztgexc( lapack_logical* wantq, lapack_logical* wantz, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* q, lapack_int* ldq,\n                    lapack_complex_double* z, lapack_int* ldz, lapack_int* ifst,\n                    lapack_int* ilst, lapack_int *info );\nvoid LAPACK_stgsen( lapack_int* ijob, lapack_logical* wantq,\n                    lapack_logical* wantz, const lapack_logical* select,\n                    lapack_int* n, float* a, lapack_int* lda, float* b,\n                    lapack_int* ldb, float* alphar, float* alphai, float* beta,\n                    float* q, lapack_int* ldq, float* z, lapack_int* ldz,\n                    lapack_int* m, float* pl, float* pr, float* dif,\n                    float* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dtgsen( lapack_int* ijob, lapack_logical* wantq,\n                    lapack_logical* wantz, const lapack_logical* select,\n                    lapack_int* n, double* a, lapack_int* lda, double* b,\n                    lapack_int* ldb, double* alphar, double* alphai,\n                    double* beta, double* q, lapack_int* ldq, double* z,\n                    lapack_int* ldz, lapack_int* m, double* pl, double* pr,\n                    double* dif, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_ctgsen( lapack_int* ijob, lapack_logical* wantq,\n                    lapack_logical* wantz, const lapack_logical* select,\n                    lapack_int* n, lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* alpha, lapack_complex_float* beta,\n                    lapack_complex_float* q, lapack_int* ldq,\n                    lapack_complex_float* z, lapack_int* ldz, lapack_int* m,\n                    float* pl, float* pr, float* dif,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_ztgsen( lapack_int* ijob, lapack_logical* wantq,\n                    lapack_logical* wantz, const lapack_logical* select,\n                    lapack_int* n, lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* alpha, lapack_complex_double* beta,\n                    lapack_complex_double* q, lapack_int* ldq,\n                    lapack_complex_double* z, lapack_int* ldz, lapack_int* m,\n                    double* pl, double* pr, double* dif,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_stgsyl( char* trans, lapack_int* ijob, lapack_int* m, lapack_int* n,\n                    const float* a, lapack_int* lda, const float* b,\n                    lapack_int* ldb, float* c, lapack_int* ldc, const float* d,\n                    lapack_int* ldd, const float* e, lapack_int* lde, float* f,\n                    lapack_int* ldf, float* scale, float* dif, float* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dtgsyl( char* trans, lapack_int* ijob, lapack_int* m, lapack_int* n,\n                    const double* a, lapack_int* lda, const double* b,\n                    lapack_int* ldb, double* c, lapack_int* ldc,\n                    const double* d, lapack_int* ldd, const double* e,\n                    lapack_int* lde, double* f, lapack_int* ldf, double* scale,\n                    double* dif, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ctgsyl( char* trans, lapack_int* ijob, lapack_int* m, lapack_int* n,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    const lapack_complex_float* d, lapack_int* ldd,\n                    const lapack_complex_float* e, lapack_int* lde,\n                    lapack_complex_float* f, lapack_int* ldf, float* scale,\n                    float* dif, lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ztgsyl( char* trans, lapack_int* ijob, lapack_int* m, lapack_int* n,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* c, lapack_int* ldc,\n                    const lapack_complex_double* d, lapack_int* ldd,\n                    const lapack_complex_double* e, lapack_int* lde,\n                    lapack_complex_double* f, lapack_int* ldf, double* scale,\n                    double* dif, lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_stgsna( char* job, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const float* a, lapack_int* lda,\n                    const float* b, lapack_int* ldb, const float* vl,\n                    lapack_int* ldvl, const float* vr, lapack_int* ldvr,\n                    float* s, float* dif, lapack_int* mm, lapack_int* m,\n                    float* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dtgsna( char* job, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const double* a, lapack_int* lda,\n                    const double* b, lapack_int* ldb, const double* vl,\n                    lapack_int* ldvl, const double* vr, lapack_int* ldvr,\n                    double* s, double* dif, lapack_int* mm, lapack_int* m,\n                    double* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_ctgsna( char* job, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* b,\n                    lapack_int* ldb, const lapack_complex_float* vl,\n                    lapack_int* ldvl, const lapack_complex_float* vr,\n                    lapack_int* ldvr, float* s, float* dif, lapack_int* mm,\n                    lapack_int* m, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ztgsna( char* job, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const lapack_complex_double* a,\n                    lapack_int* lda, const lapack_complex_double* b,\n                    lapack_int* ldb, const lapack_complex_double* vl,\n                    lapack_int* ldvl, const lapack_complex_double* vr,\n                    lapack_int* ldvr, double* s, double* dif, lapack_int* mm,\n                    lapack_int* m, lapack_complex_double* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_sggsvp( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* p, lapack_int* n, float* a, lapack_int* lda,\n                    float* b, lapack_int* ldb, float* tola, float* tolb,\n                    lapack_int* k, lapack_int* l, float* u, lapack_int* ldu,\n                    float* v, lapack_int* ldv, float* q, lapack_int* ldq,\n                    lapack_int* iwork, float* tau, float* work,\n                    lapack_int *info );\nvoid LAPACK_dggsvp( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* p, lapack_int* n, double* a, lapack_int* lda,\n                    double* b, lapack_int* ldb, double* tola, double* tolb,\n                    lapack_int* k, lapack_int* l, double* u, lapack_int* ldu,\n                    double* v, lapack_int* ldv, double* q, lapack_int* ldq,\n                    lapack_int* iwork, double* tau, double* work,\n                    lapack_int *info );\nvoid LAPACK_cggsvp( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* p, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* b, lapack_int* ldb,\n                    float* tola, float* tolb, lapack_int* k, lapack_int* l,\n                    lapack_complex_float* u, lapack_int* ldu,\n                    lapack_complex_float* v, lapack_int* ldv,\n                    lapack_complex_float* q, lapack_int* ldq, lapack_int* iwork,\n                    float* rwork, lapack_complex_float* tau,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zggsvp( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* p, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* b, lapack_int* ldb,\n                    double* tola, double* tolb, lapack_int* k, lapack_int* l,\n                    lapack_complex_double* u, lapack_int* ldu,\n                    lapack_complex_double* v, lapack_int* ldv,\n                    lapack_complex_double* q, lapack_int* ldq,\n                    lapack_int* iwork, double* rwork,\n                    lapack_complex_double* tau, lapack_complex_double* work,\n                    lapack_int *info );\nvoid LAPACK_stgsja( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* p, lapack_int* n, lapack_int* k, lapack_int* l,\n                    float* a, lapack_int* lda, float* b, lapack_int* ldb,\n                    float* tola, float* tolb, float* alpha, float* beta,\n                    float* u, lapack_int* ldu, float* v, lapack_int* ldv,\n                    float* q, lapack_int* ldq, float* work, lapack_int* ncycle,\n                    lapack_int *info );\nvoid LAPACK_dtgsja( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* p, lapack_int* n, lapack_int* k, lapack_int* l,\n                    double* a, lapack_int* lda, double* b, lapack_int* ldb,\n                    double* tola, double* tolb, double* alpha, double* beta,\n                    double* u, lapack_int* ldu, double* v, lapack_int* ldv,\n                    double* q, lapack_int* ldq, double* work,\n                    lapack_int* ncycle, lapack_int *info );\nvoid LAPACK_ctgsja( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* p, lapack_int* n, lapack_int* k, lapack_int* l,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb, float* tola,\n                    float* tolb, float* alpha, float* beta,\n                    lapack_complex_float* u, lapack_int* ldu,\n                    lapack_complex_float* v, lapack_int* ldv,\n                    lapack_complex_float* q, lapack_int* ldq,\n                    lapack_complex_float* work, lapack_int* ncycle,\n                    lapack_int *info );\nvoid LAPACK_ztgsja( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* p, lapack_int* n, lapack_int* k, lapack_int* l,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb, double* tola,\n                    double* tolb, double* alpha, double* beta,\n                    lapack_complex_double* u, lapack_int* ldu,\n                    lapack_complex_double* v, lapack_int* ldv,\n                    lapack_complex_double* q, lapack_int* ldq,\n                    lapack_complex_double* work, lapack_int* ncycle,\n                    lapack_int *info );\nvoid LAPACK_sgels( char* trans, lapack_int* m, lapack_int* n, lapack_int* nrhs,\n                   float* a, lapack_int* lda, float* b, lapack_int* ldb,\n                   float* work, lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dgels( char* trans, lapack_int* m, lapack_int* n, lapack_int* nrhs,\n                   double* a, lapack_int* lda, double* b, lapack_int* ldb,\n                   double* work, lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cgels( char* trans, lapack_int* m, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_float* a, lapack_int* lda,\n                   lapack_complex_float* b, lapack_int* ldb,\n                   lapack_complex_float* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_zgels( char* trans, lapack_int* m, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_double* a, lapack_int* lda,\n                   lapack_complex_double* b, lapack_int* ldb,\n                   lapack_complex_double* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_sgelsy( lapack_int* m, lapack_int* n, lapack_int* nrhs, float* a,\n                    lapack_int* lda, float* b, lapack_int* ldb,\n                    lapack_int* jpvt, float* rcond, lapack_int* rank,\n                    float* work, lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dgelsy( lapack_int* m, lapack_int* n, lapack_int* nrhs, double* a,\n                    lapack_int* lda, double* b, lapack_int* ldb,\n                    lapack_int* jpvt, double* rcond, lapack_int* rank,\n                    double* work, lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cgelsy( lapack_int* m, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb, lapack_int* jpvt,\n                    float* rcond, lapack_int* rank, lapack_complex_float* work,\n                    lapack_int* lwork, float* rwork, lapack_int *info );\nvoid LAPACK_zgelsy( lapack_int* m, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb, lapack_int* jpvt,\n                    double* rcond, lapack_int* rank,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_sgelss( lapack_int* m, lapack_int* n, lapack_int* nrhs, float* a,\n                    lapack_int* lda, float* b, lapack_int* ldb, float* s,\n                    float* rcond, lapack_int* rank, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dgelss( lapack_int* m, lapack_int* n, lapack_int* nrhs, double* a,\n                    lapack_int* lda, double* b, lapack_int* ldb, double* s,\n                    double* rcond, lapack_int* rank, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cgelss( lapack_int* m, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb, float* s,\n                    float* rcond, lapack_int* rank, lapack_complex_float* work,\n                    lapack_int* lwork, float* rwork, lapack_int *info );\nvoid LAPACK_zgelss( lapack_int* m, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb, double* s,\n                    double* rcond, lapack_int* rank,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_sgelsd( lapack_int* m, lapack_int* n, lapack_int* nrhs, float* a,\n                    lapack_int* lda, float* b, lapack_int* ldb, float* s,\n                    float* rcond, lapack_int* rank, float* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dgelsd( lapack_int* m, lapack_int* n, lapack_int* nrhs, double* a,\n                    lapack_int* lda, double* b, lapack_int* ldb, double* s,\n                    double* rcond, lapack_int* rank, double* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cgelsd( lapack_int* m, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb, float* s,\n                    float* rcond, lapack_int* rank, lapack_complex_float* work,\n                    lapack_int* lwork, float* rwork, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_zgelsd( lapack_int* m, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb, double* s,\n                    double* rcond, lapack_int* rank,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_sgglse( lapack_int* m, lapack_int* n, lapack_int* p, float* a,\n                    lapack_int* lda, float* b, lapack_int* ldb, float* c,\n                    float* d, float* x, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dgglse( lapack_int* m, lapack_int* n, lapack_int* p, double* a,\n                    lapack_int* lda, double* b, lapack_int* ldb, double* c,\n                    double* d, double* x, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cgglse( lapack_int* m, lapack_int* n, lapack_int* p,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* c, lapack_complex_float* d,\n                    lapack_complex_float* x, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zgglse( lapack_int* m, lapack_int* n, lapack_int* p,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* c, lapack_complex_double* d,\n                    lapack_complex_double* x, lapack_complex_double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sggglm( lapack_int* n, lapack_int* m, lapack_int* p, float* a,\n                    lapack_int* lda, float* b, lapack_int* ldb, float* d,\n                    float* x, float* y, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dggglm( lapack_int* n, lapack_int* m, lapack_int* p, double* a,\n                    lapack_int* lda, double* b, lapack_int* ldb, double* d,\n                    double* x, double* y, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cggglm( lapack_int* n, lapack_int* m, lapack_int* p,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* d, lapack_complex_float* x,\n                    lapack_complex_float* y, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zggglm( lapack_int* n, lapack_int* m, lapack_int* p,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* d, lapack_complex_double* x,\n                    lapack_complex_double* y, lapack_complex_double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_ssyev( char* jobz, char* uplo, lapack_int* n, float* a,\n                   lapack_int* lda, float* w, float* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_dsyev( char* jobz, char* uplo, lapack_int* n, double* a,\n                   lapack_int* lda, double* w, double* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_cheev( char* jobz, char* uplo, lapack_int* n,\n                   lapack_complex_float* a, lapack_int* lda, float* w,\n                   lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                   lapack_int *info );\nvoid LAPACK_zheev( char* jobz, char* uplo, lapack_int* n,\n                   lapack_complex_double* a, lapack_int* lda, double* w,\n                   lapack_complex_double* work, lapack_int* lwork,\n                   double* rwork, lapack_int *info );\nvoid LAPACK_ssyevd( char* jobz, char* uplo, lapack_int* n, float* a,\n                    lapack_int* lda, float* w, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dsyevd( char* jobz, char* uplo, lapack_int* n, double* a,\n                    lapack_int* lda, double* w, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_cheevd( char* jobz, char* uplo, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda, float* w,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int* lrwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_zheevd( char* jobz, char* uplo, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda, double* w,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* lrwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_ssyevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    float* a, lapack_int* lda, float* vl, float* vu,\n                    lapack_int* il, lapack_int* iu, float* abstol,\n                    lapack_int* m, float* w, float* z, lapack_int* ldz,\n                    float* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_dsyevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    double* a, lapack_int* lda, double* vl, double* vu,\n                    lapack_int* il, lapack_int* iu, double* abstol,\n                    lapack_int* m, double* w, double* z, lapack_int* ldz,\n                    double* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_cheevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda, float* vl,\n                    float* vu, lapack_int* il, lapack_int* iu, float* abstol,\n                    lapack_int* m, float* w, lapack_complex_float* z,\n                    lapack_int* ldz, lapack_complex_float* work,\n                    lapack_int* lwork, float* rwork, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_zheevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda, double* vl,\n                    double* vu, lapack_int* il, lapack_int* iu, double* abstol,\n                    lapack_int* m, double* w, lapack_complex_double* z,\n                    lapack_int* ldz, lapack_complex_double* work,\n                    lapack_int* lwork, double* rwork, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_ssyevr( char* jobz, char* range, char* uplo, lapack_int* n,\n                    float* a, lapack_int* lda, float* vl, float* vu,\n                    lapack_int* il, lapack_int* iu, float* abstol,\n                    lapack_int* m, float* w, float* z, lapack_int* ldz,\n                    lapack_int* isuppz, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dsyevr( char* jobz, char* range, char* uplo, lapack_int* n,\n                    double* a, lapack_int* lda, double* vl, double* vu,\n                    lapack_int* il, lapack_int* iu, double* abstol,\n                    lapack_int* m, double* w, double* z, lapack_int* ldz,\n                    lapack_int* isuppz, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_cheevr( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda, float* vl,\n                    float* vu, lapack_int* il, lapack_int* iu, float* abstol,\n                    lapack_int* m, float* w, lapack_complex_float* z,\n                    lapack_int* ldz, lapack_int* isuppz,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int* lrwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_zheevr( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda, double* vl,\n                    double* vu, lapack_int* il, lapack_int* iu, double* abstol,\n                    lapack_int* m, double* w, lapack_complex_double* z,\n                    lapack_int* ldz, lapack_int* isuppz,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* lrwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_sspev( char* jobz, char* uplo, lapack_int* n, float* ap, float* w,\n                   float* z, lapack_int* ldz, float* work, lapack_int *info );\nvoid LAPACK_dspev( char* jobz, char* uplo, lapack_int* n, double* ap, double* w,\n                   double* z, lapack_int* ldz, double* work, lapack_int *info );\nvoid LAPACK_chpev( char* jobz, char* uplo, lapack_int* n,\n                   lapack_complex_float* ap, float* w, lapack_complex_float* z,\n                   lapack_int* ldz, lapack_complex_float* work, float* rwork,\n                   lapack_int *info );\nvoid LAPACK_zhpev( char* jobz, char* uplo, lapack_int* n,\n                   lapack_complex_double* ap, double* w,\n                   lapack_complex_double* z, lapack_int* ldz,\n                   lapack_complex_double* work, double* rwork,\n                   lapack_int *info );\nvoid LAPACK_sspevd( char* jobz, char* uplo, lapack_int* n, float* ap, float* w,\n                    float* z, lapack_int* ldz, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dspevd( char* jobz, char* uplo, lapack_int* n, double* ap,\n                    double* w, double* z, lapack_int* ldz, double* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_chpevd( char* jobz, char* uplo, lapack_int* n,\n                    lapack_complex_float* ap, float* w, lapack_complex_float* z,\n                    lapack_int* ldz, lapack_complex_float* work,\n                    lapack_int* lwork, float* rwork, lapack_int* lrwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_zhpevd( char* jobz, char* uplo, lapack_int* n,\n                    lapack_complex_double* ap, double* w,\n                    lapack_complex_double* z, lapack_int* ldz,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* lrwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_sspevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    float* ap, float* vl, float* vu, lapack_int* il,\n                    lapack_int* iu, float* abstol, lapack_int* m, float* w,\n                    float* z, lapack_int* ldz, float* work, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_dspevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    double* ap, double* vl, double* vu, lapack_int* il,\n                    lapack_int* iu, double* abstol, lapack_int* m, double* w,\n                    double* z, lapack_int* ldz, double* work, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_chpevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_complex_float* ap, float* vl, float* vu,\n                    lapack_int* il, lapack_int* iu, float* abstol,\n                    lapack_int* m, float* w, lapack_complex_float* z,\n                    lapack_int* ldz, lapack_complex_float* work, float* rwork,\n                    lapack_int* iwork, lapack_int* ifail, lapack_int *info );\nvoid LAPACK_zhpevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_complex_double* ap, double* vl, double* vu,\n                    lapack_int* il, lapack_int* iu, double* abstol,\n                    lapack_int* m, double* w, lapack_complex_double* z,\n                    lapack_int* ldz, lapack_complex_double* work, double* rwork,\n                    lapack_int* iwork, lapack_int* ifail, lapack_int *info );\nvoid LAPACK_ssbev( char* jobz, char* uplo, lapack_int* n, lapack_int* kd,\n                   float* ab, lapack_int* ldab, float* w, float* z,\n                   lapack_int* ldz, float* work, lapack_int *info );\nvoid LAPACK_dsbev( char* jobz, char* uplo, lapack_int* n, lapack_int* kd,\n                   double* ab, lapack_int* ldab, double* w, double* z,\n                   lapack_int* ldz, double* work, lapack_int *info );\nvoid LAPACK_chbev( char* jobz, char* uplo, lapack_int* n, lapack_int* kd,\n                   lapack_complex_float* ab, lapack_int* ldab, float* w,\n                   lapack_complex_float* z, lapack_int* ldz,\n                   lapack_complex_float* work, float* rwork, lapack_int *info );\nvoid LAPACK_zhbev( char* jobz, char* uplo, lapack_int* n, lapack_int* kd,\n                   lapack_complex_double* ab, lapack_int* ldab, double* w,\n                   lapack_complex_double* z, lapack_int* ldz,\n                   lapack_complex_double* work, double* rwork,\n                   lapack_int *info );\nvoid LAPACK_ssbevd( char* jobz, char* uplo, lapack_int* n, lapack_int* kd,\n                    float* ab, lapack_int* ldab, float* w, float* z,\n                    lapack_int* ldz, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dsbevd( char* jobz, char* uplo, lapack_int* n, lapack_int* kd,\n                    double* ab, lapack_int* ldab, double* w, double* z,\n                    lapack_int* ldz, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_chbevd( char* jobz, char* uplo, lapack_int* n, lapack_int* kd,\n                    lapack_complex_float* ab, lapack_int* ldab, float* w,\n                    lapack_complex_float* z, lapack_int* ldz,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int* lrwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_zhbevd( char* jobz, char* uplo, lapack_int* n, lapack_int* kd,\n                    lapack_complex_double* ab, lapack_int* ldab, double* w,\n                    lapack_complex_double* z, lapack_int* ldz,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* lrwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_ssbevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_int* kd, float* ab, lapack_int* ldab, float* q,\n                    lapack_int* ldq, float* vl, float* vu, lapack_int* il,\n                    lapack_int* iu, float* abstol, lapack_int* m, float* w,\n                    float* z, lapack_int* ldz, float* work, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_dsbevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_int* kd, double* ab, lapack_int* ldab, double* q,\n                    lapack_int* ldq, double* vl, double* vu, lapack_int* il,\n                    lapack_int* iu, double* abstol, lapack_int* m, double* w,\n                    double* z, lapack_int* ldz, double* work, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_chbevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_int* kd, lapack_complex_float* ab, lapack_int* ldab,\n                    lapack_complex_float* q, lapack_int* ldq, float* vl,\n                    float* vu, lapack_int* il, lapack_int* iu, float* abstol,\n                    lapack_int* m, float* w, lapack_complex_float* z,\n                    lapack_int* ldz, lapack_complex_float* work, float* rwork,\n                    lapack_int* iwork, lapack_int* ifail, lapack_int *info );\nvoid LAPACK_zhbevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_int* kd, lapack_complex_double* ab, lapack_int* ldab,\n                    lapack_complex_double* q, lapack_int* ldq, double* vl,\n                    double* vu, lapack_int* il, lapack_int* iu, double* abstol,\n                    lapack_int* m, double* w, lapack_complex_double* z,\n                    lapack_int* ldz, lapack_complex_double* work, double* rwork,\n                    lapack_int* iwork, lapack_int* ifail, lapack_int *info );\nvoid LAPACK_sstev( char* jobz, lapack_int* n, float* d, float* e, float* z,\n                   lapack_int* ldz, float* work, lapack_int *info );\nvoid LAPACK_dstev( char* jobz, lapack_int* n, double* d, double* e, double* z,\n                   lapack_int* ldz, double* work, lapack_int *info );\nvoid LAPACK_sstevd( char* jobz, lapack_int* n, float* d, float* e, float* z,\n                    lapack_int* ldz, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dstevd( char* jobz, lapack_int* n, double* d, double* e, double* z,\n                    lapack_int* ldz, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_sstevx( char* jobz, char* range, lapack_int* n, float* d, float* e,\n                    float* vl, float* vu, lapack_int* il, lapack_int* iu,\n                    float* abstol, lapack_int* m, float* w, float* z,\n                    lapack_int* ldz, float* work, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_dstevx( char* jobz, char* range, lapack_int* n, double* d,\n                    double* e, double* vl, double* vu, lapack_int* il,\n                    lapack_int* iu, double* abstol, lapack_int* m, double* w,\n                    double* z, lapack_int* ldz, double* work, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_sstevr( char* jobz, char* range, lapack_int* n, float* d, float* e,\n                    float* vl, float* vu, lapack_int* il, lapack_int* iu,\n                    float* abstol, lapack_int* m, float* w, float* z,\n                    lapack_int* ldz, lapack_int* isuppz, float* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_dstevr( char* jobz, char* range, lapack_int* n, double* d,\n                    double* e, double* vl, double* vu, lapack_int* il,\n                    lapack_int* iu, double* abstol, lapack_int* m, double* w,\n                    double* z, lapack_int* ldz, lapack_int* isuppz,\n                    double* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_sgees( char* jobvs, char* sort, LAPACK_S_SELECT2 select,\n                   lapack_int* n, float* a, lapack_int* lda, lapack_int* sdim,\n                   float* wr, float* wi, float* vs, lapack_int* ldvs,\n                   float* work, lapack_int* lwork, lapack_logical* bwork,\n                   lapack_int *info );\nvoid LAPACK_dgees( char* jobvs, char* sort, LAPACK_D_SELECT2 select,\n                   lapack_int* n, double* a, lapack_int* lda, lapack_int* sdim,\n                   double* wr, double* wi, double* vs, lapack_int* ldvs,\n                   double* work, lapack_int* lwork, lapack_logical* bwork,\n                   lapack_int *info );\nvoid LAPACK_cgees( char* jobvs, char* sort, LAPACK_C_SELECT1 select,\n                   lapack_int* n, lapack_complex_float* a, lapack_int* lda,\n                   lapack_int* sdim, lapack_complex_float* w,\n                   lapack_complex_float* vs, lapack_int* ldvs,\n                   lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                   lapack_logical* bwork, lapack_int *info );\nvoid LAPACK_zgees( char* jobvs, char* sort, LAPACK_Z_SELECT1 select,\n                   lapack_int* n, lapack_complex_double* a, lapack_int* lda,\n                   lapack_int* sdim, lapack_complex_double* w,\n                   lapack_complex_double* vs, lapack_int* ldvs,\n                   lapack_complex_double* work, lapack_int* lwork,\n                   double* rwork, lapack_logical* bwork, lapack_int *info );\nvoid LAPACK_sgeesx( char* jobvs, char* sort, LAPACK_S_SELECT2 select,\n                    char* sense, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int* sdim, float* wr, float* wi, float* vs,\n                    lapack_int* ldvs, float* rconde, float* rcondv, float* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_logical* bwork, lapack_int *info );\nvoid LAPACK_dgeesx( char* jobvs, char* sort, LAPACK_D_SELECT2 select,\n                    char* sense, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int* sdim, double* wr, double* wi, double* vs,\n                    lapack_int* ldvs, double* rconde, double* rcondv,\n                    double* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_logical* bwork,\n                    lapack_int *info );\nvoid LAPACK_cgeesx( char* jobvs, char* sort, LAPACK_C_SELECT1 select,\n                    char* sense, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int* sdim, lapack_complex_float* w,\n                    lapack_complex_float* vs, lapack_int* ldvs, float* rconde,\n                    float* rcondv, lapack_complex_float* work,\n                    lapack_int* lwork, float* rwork, lapack_logical* bwork,\n                    lapack_int *info );\nvoid LAPACK_zgeesx( char* jobvs, char* sort, LAPACK_Z_SELECT1 select,\n                    char* sense, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* sdim, lapack_complex_double* w,\n                    lapack_complex_double* vs, lapack_int* ldvs, double* rconde,\n                    double* rcondv, lapack_complex_double* work,\n                    lapack_int* lwork, double* rwork, lapack_logical* bwork,\n                    lapack_int *info );\nvoid LAPACK_sgeev( char* jobvl, char* jobvr, lapack_int* n, float* a,\n                   lapack_int* lda, float* wr, float* wi, float* vl,\n                   lapack_int* ldvl, float* vr, lapack_int* ldvr, float* work,\n                   lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dgeev( char* jobvl, char* jobvr, lapack_int* n, double* a,\n                   lapack_int* lda, double* wr, double* wi, double* vl,\n                   lapack_int* ldvl, double* vr, lapack_int* ldvr, double* work,\n                   lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cgeev( char* jobvl, char* jobvr, lapack_int* n,\n                   lapack_complex_float* a, lapack_int* lda,\n                   lapack_complex_float* w, lapack_complex_float* vl,\n                   lapack_int* ldvl, lapack_complex_float* vr, lapack_int* ldvr,\n                   lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                   lapack_int *info );\nvoid LAPACK_zgeev( char* jobvl, char* jobvr, lapack_int* n,\n                   lapack_complex_double* a, lapack_int* lda,\n                   lapack_complex_double* w, lapack_complex_double* vl,\n                   lapack_int* ldvl, lapack_complex_double* vr,\n                   lapack_int* ldvr, lapack_complex_double* work,\n                   lapack_int* lwork, double* rwork, lapack_int *info );\nvoid LAPACK_sgeevx( char* balanc, char* jobvl, char* jobvr, char* sense,\n                    lapack_int* n, float* a, lapack_int* lda, float* wr,\n                    float* wi, float* vl, lapack_int* ldvl, float* vr,\n                    lapack_int* ldvr, lapack_int* ilo, lapack_int* ihi,\n                    float* scale, float* abnrm, float* rconde, float* rcondv,\n                    float* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dgeevx( char* balanc, char* jobvl, char* jobvr, char* sense,\n                    lapack_int* n, double* a, lapack_int* lda, double* wr,\n                    double* wi, double* vl, lapack_int* ldvl, double* vr,\n                    lapack_int* ldvr, lapack_int* ilo, lapack_int* ihi,\n                    double* scale, double* abnrm, double* rconde,\n                    double* rcondv, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cgeevx( char* balanc, char* jobvl, char* jobvr, char* sense,\n                    lapack_int* n, lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* w, lapack_complex_float* vl,\n                    lapack_int* ldvl, lapack_complex_float* vr,\n                    lapack_int* ldvr, lapack_int* ilo, lapack_int* ihi,\n                    float* scale, float* abnrm, float* rconde, float* rcondv,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zgeevx( char* balanc, char* jobvl, char* jobvr, char* sense,\n                    lapack_int* n, lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* w, lapack_complex_double* vl,\n                    lapack_int* ldvl, lapack_complex_double* vr,\n                    lapack_int* ldvr, lapack_int* ilo, lapack_int* ihi,\n                    double* scale, double* abnrm, double* rconde,\n                    double* rcondv, lapack_complex_double* work,\n                    lapack_int* lwork, double* rwork, lapack_int *info );\nvoid LAPACK_sgesvd( char* jobu, char* jobvt, lapack_int* m, lapack_int* n,\n                    float* a, lapack_int* lda, float* s, float* u,\n                    lapack_int* ldu, float* vt, lapack_int* ldvt, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dgesvd( char* jobu, char* jobvt, lapack_int* m, lapack_int* n,\n                    double* a, lapack_int* lda, double* s, double* u,\n                    lapack_int* ldu, double* vt, lapack_int* ldvt, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cgesvd( char* jobu, char* jobvt, lapack_int* m, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda, float* s,\n                    lapack_complex_float* u, lapack_int* ldu,\n                    lapack_complex_float* vt, lapack_int* ldvt,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zgesvd( char* jobu, char* jobvt, lapack_int* m, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda, double* s,\n                    lapack_complex_double* u, lapack_int* ldu,\n                    lapack_complex_double* vt, lapack_int* ldvt,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_sgesdd( char* jobz, lapack_int* m, lapack_int* n, float* a,\n                    lapack_int* lda, float* s, float* u, lapack_int* ldu,\n                    float* vt, lapack_int* ldvt, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dgesdd( char* jobz, lapack_int* m, lapack_int* n, double* a,\n                    lapack_int* lda, double* s, double* u, lapack_int* ldu,\n                    double* vt, lapack_int* ldvt, double* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cgesdd( char* jobz, lapack_int* m, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda, float* s,\n                    lapack_complex_float* u, lapack_int* ldu,\n                    lapack_complex_float* vt, lapack_int* ldvt,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_zgesdd( char* jobz, lapack_int* m, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda, double* s,\n                    lapack_complex_double* u, lapack_int* ldu,\n                    lapack_complex_double* vt, lapack_int* ldvt,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dgejsv( char* joba, char* jobu, char* jobv, char* jobr, char* jobt,\n                    char* jobp, lapack_int* m, lapack_int* n, double* a,\n                    lapack_int* lda, double* sva, double* u, lapack_int* ldu,\n                    double* v, lapack_int* ldv, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_sgejsv( char* joba, char* jobu, char* jobv, char* jobr, char* jobt,\n                    char* jobp, lapack_int* m, lapack_int* n, float* a,\n                    lapack_int* lda, float* sva, float* u, lapack_int* ldu,\n                    float* v, lapack_int* ldv, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dgesvj( char* joba, char* jobu, char* jobv, lapack_int* m,\n                    lapack_int* n, double* a, lapack_int* lda, double* sva,\n                    lapack_int* mv, double* v, lapack_int* ldv, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sgesvj( char* joba, char* jobu, char* jobv, lapack_int* m,\n                    lapack_int* n, float* a, lapack_int* lda, float* sva,\n                    lapack_int* mv, float* v, lapack_int* ldv, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sggsvd( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* n, lapack_int* p, lapack_int* k, lapack_int* l,\n                    float* a, lapack_int* lda, float* b, lapack_int* ldb,\n                    float* alpha, float* beta, float* u, lapack_int* ldu,\n                    float* v, lapack_int* ldv, float* q, lapack_int* ldq,\n                    float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dggsvd( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* n, lapack_int* p, lapack_int* k, lapack_int* l,\n                    double* a, lapack_int* lda, double* b, lapack_int* ldb,\n                    double* alpha, double* beta, double* u, lapack_int* ldu,\n                    double* v, lapack_int* ldv, double* q, lapack_int* ldq,\n                    double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cggsvd( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* n, lapack_int* p, lapack_int* k, lapack_int* l,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb, float* alpha,\n                    float* beta, lapack_complex_float* u, lapack_int* ldu,\n                    lapack_complex_float* v, lapack_int* ldv,\n                    lapack_complex_float* q, lapack_int* ldq,\n                    lapack_complex_float* work, float* rwork, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_zggsvd( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* n, lapack_int* p, lapack_int* k, lapack_int* l,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb, double* alpha,\n                    double* beta, lapack_complex_double* u, lapack_int* ldu,\n                    lapack_complex_double* v, lapack_int* ldv,\n                    lapack_complex_double* q, lapack_int* ldq,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ssygv( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                   float* a, lapack_int* lda, float* b, lapack_int* ldb,\n                   float* w, float* work, lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dsygv( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                   double* a, lapack_int* lda, double* b, lapack_int* ldb,\n                   double* w, double* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_chegv( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                   lapack_complex_float* a, lapack_int* lda,\n                   lapack_complex_float* b, lapack_int* ldb, float* w,\n                   lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                   lapack_int *info );\nvoid LAPACK_zhegv( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                   lapack_complex_double* a, lapack_int* lda,\n                   lapack_complex_double* b, lapack_int* ldb, double* w,\n                   lapack_complex_double* work, lapack_int* lwork,\n                   double* rwork, lapack_int *info );\nvoid LAPACK_ssygvd( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                    float* a, lapack_int* lda, float* b, lapack_int* ldb,\n                    float* w, float* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dsygvd( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                    double* a, lapack_int* lda, double* b, lapack_int* ldb,\n                    double* w, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_chegvd( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb, float* w,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int* lrwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_zhegvd( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb, double* w,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* lrwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_ssygvx( lapack_int* itype, char* jobz, char* range, char* uplo,\n                    lapack_int* n, float* a, lapack_int* lda, float* b,\n                    lapack_int* ldb, float* vl, float* vu, lapack_int* il,\n                    lapack_int* iu, float* abstol, lapack_int* m, float* w,\n                    float* z, lapack_int* ldz, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* ifail, lapack_int *info );\nvoid LAPACK_dsygvx( lapack_int* itype, char* jobz, char* range, char* uplo,\n                    lapack_int* n, double* a, lapack_int* lda, double* b,\n                    lapack_int* ldb, double* vl, double* vu, lapack_int* il,\n                    lapack_int* iu, double* abstol, lapack_int* m, double* w,\n                    double* z, lapack_int* ldz, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* ifail, lapack_int *info );\nvoid LAPACK_chegvx( lapack_int* itype, char* jobz, char* range, char* uplo,\n                    lapack_int* n, lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb, float* vl,\n                    float* vu, lapack_int* il, lapack_int* iu, float* abstol,\n                    lapack_int* m, float* w, lapack_complex_float* z,\n                    lapack_int* ldz, lapack_complex_float* work,\n                    lapack_int* lwork, float* rwork, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_zhegvx( lapack_int* itype, char* jobz, char* range, char* uplo,\n                    lapack_int* n, lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb, double* vl,\n                    double* vu, lapack_int* il, lapack_int* iu, double* abstol,\n                    lapack_int* m, double* w, lapack_complex_double* z,\n                    lapack_int* ldz, lapack_complex_double* work,\n                    lapack_int* lwork, double* rwork, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_sspgv( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                   float* ap, float* bp, float* w, float* z, lapack_int* ldz,\n                   float* work, lapack_int *info );\nvoid LAPACK_dspgv( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                   double* ap, double* bp, double* w, double* z,\n                   lapack_int* ldz, double* work, lapack_int *info );\nvoid LAPACK_chpgv( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                   lapack_complex_float* ap, lapack_complex_float* bp, float* w,\n                   lapack_complex_float* z, lapack_int* ldz,\n                   lapack_complex_float* work, float* rwork, lapack_int *info );\nvoid LAPACK_zhpgv( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                   lapack_complex_double* ap, lapack_complex_double* bp,\n                   double* w, lapack_complex_double* z, lapack_int* ldz,\n                   lapack_complex_double* work, double* rwork,\n                   lapack_int *info );\nvoid LAPACK_sspgvd( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                    float* ap, float* bp, float* w, float* z, lapack_int* ldz,\n                    float* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dspgvd( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                    double* ap, double* bp, double* w, double* z,\n                    lapack_int* ldz, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_chpgvd( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                    lapack_complex_float* ap, lapack_complex_float* bp,\n                    float* w, lapack_complex_float* z, lapack_int* ldz,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int* lrwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_zhpgvd( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                    lapack_complex_double* ap, lapack_complex_double* bp,\n                    double* w, lapack_complex_double* z, lapack_int* ldz,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* lrwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_sspgvx( lapack_int* itype, char* jobz, char* range, char* uplo,\n                    lapack_int* n, float* ap, float* bp, float* vl, float* vu,\n                    lapack_int* il, lapack_int* iu, float* abstol,\n                    lapack_int* m, float* w, float* z, lapack_int* ldz,\n                    float* work, lapack_int* iwork, lapack_int* ifail,\n                    lapack_int *info );\nvoid LAPACK_dspgvx( lapack_int* itype, char* jobz, char* range, char* uplo,\n                    lapack_int* n, double* ap, double* bp, double* vl,\n                    double* vu, lapack_int* il, lapack_int* iu, double* abstol,\n                    lapack_int* m, double* w, double* z, lapack_int* ldz,\n                    double* work, lapack_int* iwork, lapack_int* ifail,\n                    lapack_int *info );\nvoid LAPACK_chpgvx( lapack_int* itype, char* jobz, char* range, char* uplo,\n                    lapack_int* n, lapack_complex_float* ap,\n                    lapack_complex_float* bp, float* vl, float* vu,\n                    lapack_int* il, lapack_int* iu, float* abstol,\n                    lapack_int* m, float* w, lapack_complex_float* z,\n                    lapack_int* ldz, lapack_complex_float* work, float* rwork,\n                    lapack_int* iwork, lapack_int* ifail, lapack_int *info );\nvoid LAPACK_zhpgvx( lapack_int* itype, char* jobz, char* range, char* uplo,\n                    lapack_int* n, lapack_complex_double* ap,\n                    lapack_complex_double* bp, double* vl, double* vu,\n                    lapack_int* il, lapack_int* iu, double* abstol,\n                    lapack_int* m, double* w, lapack_complex_double* z,\n                    lapack_int* ldz, lapack_complex_double* work, double* rwork,\n                    lapack_int* iwork, lapack_int* ifail, lapack_int *info );\nvoid LAPACK_ssbgv( char* jobz, char* uplo, lapack_int* n, lapack_int* ka,\n                   lapack_int* kb, float* ab, lapack_int* ldab, float* bb,\n                   lapack_int* ldbb, float* w, float* z, lapack_int* ldz,\n                   float* work, lapack_int *info );\nvoid LAPACK_dsbgv( char* jobz, char* uplo, lapack_int* n, lapack_int* ka,\n                   lapack_int* kb, double* ab, lapack_int* ldab, double* bb,\n                   lapack_int* ldbb, double* w, double* z, lapack_int* ldz,\n                   double* work, lapack_int *info );\nvoid LAPACK_chbgv( char* jobz, char* uplo, lapack_int* n, lapack_int* ka,\n                   lapack_int* kb, lapack_complex_float* ab, lapack_int* ldab,\n                   lapack_complex_float* bb, lapack_int* ldbb, float* w,\n                   lapack_complex_float* z, lapack_int* ldz,\n                   lapack_complex_float* work, float* rwork, lapack_int *info );\nvoid LAPACK_zhbgv( char* jobz, char* uplo, lapack_int* n, lapack_int* ka,\n                   lapack_int* kb, lapack_complex_double* ab, lapack_int* ldab,\n                   lapack_complex_double* bb, lapack_int* ldbb, double* w,\n                   lapack_complex_double* z, lapack_int* ldz,\n                   lapack_complex_double* work, double* rwork,\n                   lapack_int *info );\nvoid LAPACK_ssbgvd( char* jobz, char* uplo, lapack_int* n, lapack_int* ka,\n                    lapack_int* kb, float* ab, lapack_int* ldab, float* bb,\n                    lapack_int* ldbb, float* w, float* z, lapack_int* ldz,\n                    float* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dsbgvd( char* jobz, char* uplo, lapack_int* n, lapack_int* ka,\n                    lapack_int* kb, double* ab, lapack_int* ldab, double* bb,\n                    lapack_int* ldbb, double* w, double* z, lapack_int* ldz,\n                    double* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_chbgvd( char* jobz, char* uplo, lapack_int* n, lapack_int* ka,\n                    lapack_int* kb, lapack_complex_float* ab, lapack_int* ldab,\n                    lapack_complex_float* bb, lapack_int* ldbb, float* w,\n                    lapack_complex_float* z, lapack_int* ldz,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int* lrwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_zhbgvd( char* jobz, char* uplo, lapack_int* n, lapack_int* ka,\n                    lapack_int* kb, lapack_complex_double* ab, lapack_int* ldab,\n                    lapack_complex_double* bb, lapack_int* ldbb, double* w,\n                    lapack_complex_double* z, lapack_int* ldz,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* lrwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_ssbgvx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_int* ka, lapack_int* kb, float* ab, lapack_int* ldab,\n                    float* bb, lapack_int* ldbb, float* q, lapack_int* ldq,\n                    float* vl, float* vu, lapack_int* il, lapack_int* iu,\n                    float* abstol, lapack_int* m, float* w, float* z,\n                    lapack_int* ldz, float* work, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_dsbgvx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_int* ka, lapack_int* kb, double* ab,\n                    lapack_int* ldab, double* bb, lapack_int* ldbb, double* q,\n                    lapack_int* ldq, double* vl, double* vu, lapack_int* il,\n                    lapack_int* iu, double* abstol, lapack_int* m, double* w,\n                    double* z, lapack_int* ldz, double* work, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_chbgvx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_int* ka, lapack_int* kb, lapack_complex_float* ab,\n                    lapack_int* ldab, lapack_complex_float* bb,\n                    lapack_int* ldbb, lapack_complex_float* q, lapack_int* ldq,\n                    float* vl, float* vu, lapack_int* il, lapack_int* iu,\n                    float* abstol, lapack_int* m, float* w,\n                    lapack_complex_float* z, lapack_int* ldz,\n                    lapack_complex_float* work, float* rwork, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_zhbgvx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_int* ka, lapack_int* kb, lapack_complex_double* ab,\n                    lapack_int* ldab, lapack_complex_double* bb,\n                    lapack_int* ldbb, lapack_complex_double* q, lapack_int* ldq,\n                    double* vl, double* vu, lapack_int* il, lapack_int* iu,\n                    double* abstol, lapack_int* m, double* w,\n                    lapack_complex_double* z, lapack_int* ldz,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int* iwork, lapack_int* ifail, lapack_int *info );\nvoid LAPACK_sgges( char* jobvsl, char* jobvsr, char* sort,\n                   LAPACK_S_SELECT3 selctg, lapack_int* n, float* a,\n                   lapack_int* lda, float* b, lapack_int* ldb, lapack_int* sdim,\n                   float* alphar, float* alphai, float* beta, float* vsl,\n                   lapack_int* ldvsl, float* vsr, lapack_int* ldvsr,\n                   float* work, lapack_int* lwork, lapack_logical* bwork,\n                   lapack_int *info );\nvoid LAPACK_dgges( char* jobvsl, char* jobvsr, char* sort,\n                   LAPACK_D_SELECT3 selctg, lapack_int* n, double* a,\n                   lapack_int* lda, double* b, lapack_int* ldb,\n                   lapack_int* sdim, double* alphar, double* alphai,\n                   double* beta, double* vsl, lapack_int* ldvsl, double* vsr,\n                   lapack_int* ldvsr, double* work, lapack_int* lwork,\n                   lapack_logical* bwork, lapack_int *info );\nvoid LAPACK_cgges( char* jobvsl, char* jobvsr, char* sort,\n                   LAPACK_C_SELECT2 selctg, lapack_int* n,\n                   lapack_complex_float* a, lapack_int* lda,\n                   lapack_complex_float* b, lapack_int* ldb, lapack_int* sdim,\n                   lapack_complex_float* alpha, lapack_complex_float* beta,\n                   lapack_complex_float* vsl, lapack_int* ldvsl,\n                   lapack_complex_float* vsr, lapack_int* ldvsr,\n                   lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                   lapack_logical* bwork, lapack_int *info );\nvoid LAPACK_zgges( char* jobvsl, char* jobvsr, char* sort,\n                   LAPACK_Z_SELECT2 selctg, lapack_int* n,\n                   lapack_complex_double* a, lapack_int* lda,\n                   lapack_complex_double* b, lapack_int* ldb, lapack_int* sdim,\n                   lapack_complex_double* alpha, lapack_complex_double* beta,\n                   lapack_complex_double* vsl, lapack_int* ldvsl,\n                   lapack_complex_double* vsr, lapack_int* ldvsr,\n                   lapack_complex_double* work, lapack_int* lwork,\n                   double* rwork, lapack_logical* bwork, lapack_int *info );\nvoid LAPACK_sggesx( char* jobvsl, char* jobvsr, char* sort,\n                    LAPACK_S_SELECT3 selctg, char* sense, lapack_int* n,\n                    float* a, lapack_int* lda, float* b, lapack_int* ldb,\n                    lapack_int* sdim, float* alphar, float* alphai, float* beta,\n                    float* vsl, lapack_int* ldvsl, float* vsr,\n                    lapack_int* ldvsr, float* rconde, float* rcondv,\n                    float* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_logical* bwork,\n                    lapack_int *info );\nvoid LAPACK_dggesx( char* jobvsl, char* jobvsr, char* sort,\n                    LAPACK_D_SELECT3 selctg, char* sense, lapack_int* n,\n                    double* a, lapack_int* lda, double* b, lapack_int* ldb,\n                    lapack_int* sdim, double* alphar, double* alphai,\n                    double* beta, double* vsl, lapack_int* ldvsl, double* vsr,\n                    lapack_int* ldvsr, double* rconde, double* rcondv,\n                    double* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_logical* bwork,\n                    lapack_int *info );\nvoid LAPACK_cggesx( char* jobvsl, char* jobvsr, char* sort,\n                    LAPACK_C_SELECT2 selctg, char* sense, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb, lapack_int* sdim,\n                    lapack_complex_float* alpha, lapack_complex_float* beta,\n                    lapack_complex_float* vsl, lapack_int* ldvsl,\n                    lapack_complex_float* vsr, lapack_int* ldvsr, float* rconde,\n                    float* rcondv, lapack_complex_float* work,\n                    lapack_int* lwork, float* rwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_logical* bwork,\n                    lapack_int *info );\nvoid LAPACK_zggesx( char* jobvsl, char* jobvsr, char* sort,\n                    LAPACK_Z_SELECT2 selctg, char* sense, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb, lapack_int* sdim,\n                    lapack_complex_double* alpha, lapack_complex_double* beta,\n                    lapack_complex_double* vsl, lapack_int* ldvsl,\n                    lapack_complex_double* vsr, lapack_int* ldvsr,\n                    double* rconde, double* rcondv, lapack_complex_double* work,\n                    lapack_int* lwork, double* rwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_logical* bwork,\n                    lapack_int *info );\nvoid LAPACK_sggev( char* jobvl, char* jobvr, lapack_int* n, float* a,\n                   lapack_int* lda, float* b, lapack_int* ldb, float* alphar,\n                   float* alphai, float* beta, float* vl, lapack_int* ldvl,\n                   float* vr, lapack_int* ldvr, float* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_dggev( char* jobvl, char* jobvr, lapack_int* n, double* a,\n                   lapack_int* lda, double* b, lapack_int* ldb, double* alphar,\n                   double* alphai, double* beta, double* vl, lapack_int* ldvl,\n                   double* vr, lapack_int* ldvr, double* work,\n                   lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cggev( char* jobvl, char* jobvr, lapack_int* n,\n                   lapack_complex_float* a, lapack_int* lda,\n                   lapack_complex_float* b, lapack_int* ldb,\n                   lapack_complex_float* alpha, lapack_complex_float* beta,\n                   lapack_complex_float* vl, lapack_int* ldvl,\n                   lapack_complex_float* vr, lapack_int* ldvr,\n                   lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                   lapack_int *info );\nvoid LAPACK_zggev( char* jobvl, char* jobvr, lapack_int* n,\n                   lapack_complex_double* a, lapack_int* lda,\n                   lapack_complex_double* b, lapack_int* ldb,\n                   lapack_complex_double* alpha, lapack_complex_double* beta,\n                   lapack_complex_double* vl, lapack_int* ldvl,\n                   lapack_complex_double* vr, lapack_int* ldvr,\n                   lapack_complex_double* work, lapack_int* lwork,\n                   double* rwork, lapack_int *info );\nvoid LAPACK_sggevx( char* balanc, char* jobvl, char* jobvr, char* sense,\n                    lapack_int* n, float* a, lapack_int* lda, float* b,\n                    lapack_int* ldb, float* alphar, float* alphai, float* beta,\n                    float* vl, lapack_int* ldvl, float* vr, lapack_int* ldvr,\n                    lapack_int* ilo, lapack_int* ihi, float* lscale,\n                    float* rscale, float* abnrm, float* bbnrm, float* rconde,\n                    float* rcondv, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_logical* bwork,\n                    lapack_int *info );\nvoid LAPACK_dggevx( char* balanc, char* jobvl, char* jobvr, char* sense,\n                    lapack_int* n, double* a, lapack_int* lda, double* b,\n                    lapack_int* ldb, double* alphar, double* alphai,\n                    double* beta, double* vl, lapack_int* ldvl, double* vr,\n                    lapack_int* ldvr, lapack_int* ilo, lapack_int* ihi,\n                    double* lscale, double* rscale, double* abnrm,\n                    double* bbnrm, double* rconde, double* rcondv, double* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_logical* bwork,\n                    lapack_int *info );\nvoid LAPACK_cggevx( char* balanc, char* jobvl, char* jobvr, char* sense,\n                    lapack_int* n, lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* alpha, lapack_complex_float* beta,\n                    lapack_complex_float* vl, lapack_int* ldvl,\n                    lapack_complex_float* vr, lapack_int* ldvr, lapack_int* ilo,\n                    lapack_int* ihi, float* lscale, float* rscale, float* abnrm,\n                    float* bbnrm, float* rconde, float* rcondv,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int* iwork, lapack_logical* bwork,\n                    lapack_int *info );\nvoid LAPACK_zggevx( char* balanc, char* jobvl, char* jobvr, char* sense,\n                    lapack_int* n, lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* alpha, lapack_complex_double* beta,\n                    lapack_complex_double* vl, lapack_int* ldvl,\n                    lapack_complex_double* vr, lapack_int* ldvr,\n                    lapack_int* ilo, lapack_int* ihi, double* lscale,\n                    double* rscale, double* abnrm, double* bbnrm,\n                    double* rconde, double* rcondv, lapack_complex_double* work,\n                    lapack_int* lwork, double* rwork, lapack_int* iwork,\n                    lapack_logical* bwork, lapack_int *info );\nvoid LAPACK_dsfrk( char* transr, char* uplo, char* trans, lapack_int* n,\n                   lapack_int* k, double* alpha, const double* a,\n                   lapack_int* lda, double* beta, double* c );\nvoid LAPACK_ssfrk( char* transr, char* uplo, char* trans, lapack_int* n,\n                   lapack_int* k, float* alpha, const float* a, lapack_int* lda,\n                   float* beta, float* c );\nvoid LAPACK_zhfrk( char* transr, char* uplo, char* trans, lapack_int* n,\n                   lapack_int* k, double* alpha, const lapack_complex_double* a,\n                   lapack_int* lda, double* beta, lapack_complex_double* c );\nvoid LAPACK_chfrk( char* transr, char* uplo, char* trans, lapack_int* n,\n                   lapack_int* k, float* alpha, const lapack_complex_float* a,\n                   lapack_int* lda, float* beta, lapack_complex_float* c );\nvoid LAPACK_dtfsm( char* transr, char* side, char* uplo, char* trans,\n                   char* diag, lapack_int* m, lapack_int* n, double* alpha,\n                   const double* a, double* b, lapack_int* ldb );\nvoid LAPACK_stfsm( char* transr, char* side, char* uplo, char* trans,\n                   char* diag, lapack_int* m, lapack_int* n, float* alpha,\n                   const float* a, float* b, lapack_int* ldb );\nvoid LAPACK_ztfsm( char* transr, char* side, char* uplo, char* trans,\n                   char* diag, lapack_int* m, lapack_int* n,\n                   lapack_complex_double* alpha, const lapack_complex_double* a,\n                   lapack_complex_double* b, lapack_int* ldb );\nvoid LAPACK_ctfsm( char* transr, char* side, char* uplo, char* trans,\n                   char* diag, lapack_int* m, lapack_int* n,\n                   lapack_complex_float* alpha, const lapack_complex_float* a,\n                   lapack_complex_float* b, lapack_int* ldb );\nvoid LAPACK_dtfttp( char* transr, char* uplo, lapack_int* n, const double* arf,\n                    double* ap, lapack_int *info );\nvoid LAPACK_stfttp( char* transr, char* uplo, lapack_int* n, const float* arf,\n                    float* ap, lapack_int *info );\nvoid LAPACK_ztfttp( char* transr, char* uplo, lapack_int* n,\n                    const lapack_complex_double* arf, lapack_complex_double* ap,\n                    lapack_int *info );\nvoid LAPACK_ctfttp( char* transr, char* uplo, lapack_int* n,\n                    const lapack_complex_float* arf, lapack_complex_float* ap,\n                    lapack_int *info );\nvoid LAPACK_dtfttr( char* transr, char* uplo, lapack_int* n, const double* arf,\n                    double* a, lapack_int* lda, lapack_int *info );\nvoid LAPACK_stfttr( char* transr, char* uplo, lapack_int* n, const float* arf,\n                    float* a, lapack_int* lda, lapack_int *info );\nvoid LAPACK_ztfttr( char* transr, char* uplo, lapack_int* n,\n                    const lapack_complex_double* arf, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_ctfttr( char* transr, char* uplo, lapack_int* n,\n                    const lapack_complex_float* arf, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_dtpttf( char* transr, char* uplo, lapack_int* n, const double* ap,\n                    double* arf, lapack_int *info );\nvoid LAPACK_stpttf( char* transr, char* uplo, lapack_int* n, const float* ap,\n                    float* arf, lapack_int *info );\nvoid LAPACK_ztpttf( char* transr, char* uplo, lapack_int* n,\n                    const lapack_complex_double* ap, lapack_complex_double* arf,\n                    lapack_int *info );\nvoid LAPACK_ctpttf( char* transr, char* uplo, lapack_int* n,\n                    const lapack_complex_float* ap, lapack_complex_float* arf,\n                    lapack_int *info );\nvoid LAPACK_dtpttr( char* uplo, lapack_int* n, const double* ap, double* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_stpttr( char* uplo, lapack_int* n, const float* ap, float* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_ztpttr( char* uplo, lapack_int* n, const lapack_complex_double* ap,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_ctpttr( char* uplo, lapack_int* n, const lapack_complex_float* ap,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_dtrttf( char* transr, char* uplo, lapack_int* n, const double* a,\n                    lapack_int* lda, double* arf, lapack_int *info );\nvoid LAPACK_strttf( char* transr, char* uplo, lapack_int* n, const float* a,\n                    lapack_int* lda, float* arf, lapack_int *info );\nvoid LAPACK_ztrttf( char* transr, char* uplo, lapack_int* n,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* arf, lapack_int *info );\nvoid LAPACK_ctrttf( char* transr, char* uplo, lapack_int* n,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* arf, lapack_int *info );\nvoid LAPACK_dtrttp( char* uplo, lapack_int* n, const double* a, lapack_int* lda,\n                    double* ap, lapack_int *info );\nvoid LAPACK_strttp( char* uplo, lapack_int* n, const float* a, lapack_int* lda,\n                    float* ap, lapack_int *info );\nvoid LAPACK_ztrttp( char* uplo, lapack_int* n, const lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* ap,\n                    lapack_int *info );\nvoid LAPACK_ctrttp( char* uplo, lapack_int* n, const lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* ap,\n                    lapack_int *info );\nvoid LAPACK_sgeqrfp( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                     float* tau, float* work, lapack_int* lwork,\n                     lapack_int *info );\nvoid LAPACK_dgeqrfp( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                     double* tau, double* work, lapack_int* lwork,\n                     lapack_int *info );\nvoid LAPACK_cgeqrfp( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                     lapack_int* lda, lapack_complex_float* tau,\n                     lapack_complex_float* work, lapack_int* lwork,\n                     lapack_int *info );\nvoid LAPACK_zgeqrfp( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                     lapack_int* lda, lapack_complex_double* tau,\n                     lapack_complex_double* work, lapack_int* lwork,\n                     lapack_int *info );\nvoid LAPACK_clacgv( lapack_int* n, lapack_complex_float* x, lapack_int* incx );\nvoid LAPACK_zlacgv( lapack_int* n, lapack_complex_double* x, lapack_int* incx );\nvoid LAPACK_slarnv( lapack_int* idist, lapack_int* iseed, lapack_int* n,\n                    float* x );\nvoid LAPACK_dlarnv( lapack_int* idist, lapack_int* iseed, lapack_int* n,\n                    double* x );\nvoid LAPACK_clarnv( lapack_int* idist, lapack_int* iseed, lapack_int* n,\n                    lapack_complex_float* x );\nvoid LAPACK_zlarnv( lapack_int* idist, lapack_int* iseed, lapack_int* n,\n                    lapack_complex_double* x );\nvoid LAPACK_sgeqr2( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    float* tau, float* work, lapack_int *info );\nvoid LAPACK_dgeqr2( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    double* tau, double* work, lapack_int *info );\nvoid LAPACK_cgeqr2( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* tau,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zgeqr2( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_slacpy( char* uplo, lapack_int* m, lapack_int* n, const float* a,\n                    lapack_int* lda, float* b, lapack_int* ldb );\nvoid LAPACK_dlacpy( char* uplo, lapack_int* m, lapack_int* n, const double* a,\n                    lapack_int* lda, double* b, lapack_int* ldb );\nvoid LAPACK_clacpy( char* uplo, lapack_int* m, lapack_int* n,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb );\nvoid LAPACK_zlacpy( char* uplo, lapack_int* m, lapack_int* n,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb );\nvoid LAPACK_sgetf2( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_dgetf2( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_cgetf2( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_zgetf2( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_slaswp( lapack_int* n, float* a, lapack_int* lda, lapack_int* k1,\n                    lapack_int* k2, const lapack_int* ipiv, lapack_int* incx );\nvoid LAPACK_dlaswp( lapack_int* n, double* a, lapack_int* lda, lapack_int* k1,\n                    lapack_int* k2, const lapack_int* ipiv, lapack_int* incx );\nvoid LAPACK_claswp( lapack_int* n, lapack_complex_float* a, lapack_int* lda,\n                    lapack_int* k1, lapack_int* k2, const lapack_int* ipiv,\n                    lapack_int* incx );\nvoid LAPACK_zlaswp( lapack_int* n, lapack_complex_double* a, lapack_int* lda,\n                    lapack_int* k1, lapack_int* k2, const lapack_int* ipiv,\n                    lapack_int* incx );\nfloat LAPACK_slange( char* norm, lapack_int* m, lapack_int* n, const float* a,\n                    lapack_int* lda, float* work );\ndouble LAPACK_dlange( char* norm, lapack_int* m, lapack_int* n, const double* a,\n                    lapack_int* lda, double* work );\nfloat LAPACK_clange( char* norm, lapack_int* m, lapack_int* n,\n                    const lapack_complex_float* a, lapack_int* lda, float* work );\ndouble LAPACK_zlange( char* norm, lapack_int* m, lapack_int* n,\n                    const lapack_complex_double* a, lapack_int* lda, double* work );\nfloat LAPACK_clanhe( char* norm, char* uplo, lapack_int* n,\n                    const lapack_complex_float* a, lapack_int* lda, float* work );\ndouble LAPACK_zlanhe( char* norm, char* uplo, lapack_int* n,\n                    const lapack_complex_double* a, lapack_int* lda, double* work );\nfloat LAPACK_slansy( char* norm, char* uplo, lapack_int* n, const float* a,\n                    lapack_int* lda, float* work );\ndouble LAPACK_dlansy( char* norm, char* uplo, lapack_int* n, const double* a,\n                    lapack_int* lda, double* work );\nfloat LAPACK_clansy( char* norm, char* uplo, lapack_int* n,\n                    const lapack_complex_float* a, lapack_int* lda, float* work );\ndouble LAPACK_zlansy( char* norm, char* uplo, lapack_int* n,\n                    const lapack_complex_double* a, lapack_int* lda, double* work );\nfloat LAPACK_slantr( char* norm, char* uplo, char* diag, lapack_int* m,\n                    lapack_int* n, const float* a, lapack_int* lda, float* work );\ndouble LAPACK_dlantr( char* norm, char* uplo, char* diag, lapack_int* m,\n                    lapack_int* n, const double* a, lapack_int* lda, double* work );\nfloat LAPACK_clantr( char* norm, char* uplo, char* diag, lapack_int* m,\n                    lapack_int* n, const lapack_complex_float* a, lapack_int* lda,\n                    float* work );\ndouble LAPACK_zlantr( char* norm, char* uplo, char* diag, lapack_int* m,\n                    lapack_int* n, const lapack_complex_double* a, lapack_int* lda,\n                    double* work );\nfloat LAPACK_slamch( char* cmach );\ndouble LAPACK_dlamch( char* cmach );\nvoid LAPACK_sgelq2( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    float* tau, float* work, lapack_int *info );\nvoid LAPACK_dgelq2( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    double* tau, double* work, lapack_int *info );\nvoid LAPACK_cgelq2( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* tau,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zgelq2( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_slarfb( char* side, char* trans, char* direct, char* storev,\n                    lapack_int* m, lapack_int* n, lapack_int* k, const float* v,\n                    lapack_int* ldv, const float* t, lapack_int* ldt, float* c,\n                    lapack_int* ldc, float* work, lapack_int* ldwork );\nvoid LAPACK_dlarfb( char* side, char* trans, char* direct, char* storev,\n                    lapack_int* m, lapack_int* n, lapack_int* k,\n                    const double* v, lapack_int* ldv, const double* t,\n                    lapack_int* ldt, double* c, lapack_int* ldc, double* work,\n                    lapack_int* ldwork );\nvoid LAPACK_clarfb( char* side, char* trans, char* direct, char* storev,\n                    lapack_int* m, lapack_int* n, lapack_int* k,\n                    const lapack_complex_float* v, lapack_int* ldv,\n                    const lapack_complex_float* t, lapack_int* ldt,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    lapack_complex_float* work, lapack_int* ldwork );\nvoid LAPACK_zlarfb( char* side, char* trans, char* direct, char* storev,\n                    lapack_int* m, lapack_int* n, lapack_int* k,\n                    const lapack_complex_double* v, lapack_int* ldv,\n                    const lapack_complex_double* t, lapack_int* ldt,\n                    lapack_complex_double* c, lapack_int* ldc,\n                    lapack_complex_double* work, lapack_int* ldwork );\nvoid LAPACK_slarfg( lapack_int* n, float* alpha, float* x, lapack_int* incx,\n                    float* tau );\nvoid LAPACK_dlarfg( lapack_int* n, double* alpha, double* x, lapack_int* incx,\n                    double* tau );\nvoid LAPACK_clarfg( lapack_int* n, lapack_complex_float* alpha,\n                    lapack_complex_float* x, lapack_int* incx,\n                    lapack_complex_float* tau );\nvoid LAPACK_zlarfg( lapack_int* n, lapack_complex_double* alpha,\n                    lapack_complex_double* x, lapack_int* incx,\n                    lapack_complex_double* tau );\nvoid LAPACK_slarft( char* direct, char* storev, lapack_int* n, lapack_int* k,\n                    const float* v, lapack_int* ldv, const float* tau, float* t,\n                    lapack_int* ldt );\nvoid LAPACK_dlarft( char* direct, char* storev, lapack_int* n, lapack_int* k,\n                    const double* v, lapack_int* ldv, const double* tau,\n                    double* t, lapack_int* ldt );\nvoid LAPACK_clarft( char* direct, char* storev, lapack_int* n, lapack_int* k,\n                    const lapack_complex_float* v, lapack_int* ldv,\n                    const lapack_complex_float* tau, lapack_complex_float* t,\n                    lapack_int* ldt );\nvoid LAPACK_zlarft( char* direct, char* storev, lapack_int* n, lapack_int* k,\n                    const lapack_complex_double* v, lapack_int* ldv,\n                    const lapack_complex_double* tau, lapack_complex_double* t,\n                    lapack_int* ldt );\nvoid LAPACK_slarfx( char* side, lapack_int* m, lapack_int* n, const float* v,\n                    float* tau, float* c, lapack_int* ldc, float* work );\nvoid LAPACK_dlarfx( char* side, lapack_int* m, lapack_int* n, const double* v,\n                    double* tau, double* c, lapack_int* ldc, double* work );\nvoid LAPACK_clarfx( char* side, lapack_int* m, lapack_int* n,\n                    const lapack_complex_float* v, lapack_complex_float* tau,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    lapack_complex_float* work );\nvoid LAPACK_zlarfx( char* side, lapack_int* m, lapack_int* n,\n                    const lapack_complex_double* v, lapack_complex_double* tau,\n                    lapack_complex_double* c, lapack_int* ldc,\n                    lapack_complex_double* work );\nvoid LAPACK_slatms( lapack_int* m, lapack_int* n, char* dist, lapack_int* iseed,\n                    char* sym, float* d, lapack_int* mode, float* cond,\n                    float* dmax, lapack_int* kl, lapack_int* ku, char* pack,\n                    float* a, lapack_int* lda, float* work, lapack_int *info );\nvoid LAPACK_dlatms( lapack_int* m, lapack_int* n, char* dist, lapack_int* iseed,\n                    char* sym, double* d, lapack_int* mode, double* cond,\n                    double* dmax, lapack_int* kl, lapack_int* ku, char* pack,\n                    double* a, lapack_int* lda, double* work,\n                    lapack_int *info );\nvoid LAPACK_clatms( lapack_int* m, lapack_int* n, char* dist, lapack_int* iseed,\n                    char* sym, float* d, lapack_int* mode, float* cond,\n                    float* dmax, lapack_int* kl, lapack_int* ku, char* pack,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zlatms( lapack_int* m, lapack_int* n, char* dist, lapack_int* iseed,\n                    char* sym, double* d, lapack_int* mode, double* cond,\n                    double* dmax, lapack_int* kl, lapack_int* ku, char* pack,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_slag2d( lapack_int* m, lapack_int* n, const float* sa,\n                    lapack_int* ldsa, double* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_dlag2s( lapack_int* m, lapack_int* n, const double* a,\n                    lapack_int* lda, float* sa, lapack_int* ldsa,\n                    lapack_int *info );\nvoid LAPACK_clag2z( lapack_int* m, lapack_int* n,\n                    const lapack_complex_float* sa, lapack_int* ldsa,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_zlag2c( lapack_int* m, lapack_int* n,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_float* sa, lapack_int* ldsa,\n                    lapack_int *info );\nvoid LAPACK_slauum( char* uplo, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_dlauum( char* uplo, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_clauum( char* uplo, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_zlauum( char* uplo, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_slagge( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, const float* d, float* a, lapack_int* lda,\n                    lapack_int* iseed, float* work, lapack_int *info );\nvoid LAPACK_dlagge( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, const double* d, double* a, lapack_int* lda,\n                    lapack_int* iseed, double* work, lapack_int *info );\nvoid LAPACK_clagge( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, const float* d, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int* iseed,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zlagge( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, const double* d, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* iseed,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_slaset( char* uplo, lapack_int* m, lapack_int* n, float* alpha,\n                    float* beta, float* a, lapack_int* lda );\nvoid LAPACK_dlaset( char* uplo, lapack_int* m, lapack_int* n, double* alpha,\n                    double* beta, double* a, lapack_int* lda );\nvoid LAPACK_claset( char* uplo, lapack_int* m, lapack_int* n,\n                    lapack_complex_float* alpha, lapack_complex_float* beta,\n                    lapack_complex_float* a, lapack_int* lda );\nvoid LAPACK_zlaset( char* uplo, lapack_int* m, lapack_int* n,\n                    lapack_complex_double* alpha, lapack_complex_double* beta,\n                    lapack_complex_double* a, lapack_int* lda );\nvoid LAPACK_slasrt( char* id, lapack_int* n, float* d, lapack_int *info );\nvoid LAPACK_dlasrt( char* id, lapack_int* n, double* d, lapack_int *info );\nvoid LAPACK_claghe( lapack_int* n, lapack_int* k, const float* d,\n                    lapack_complex_float* a, lapack_int* lda, lapack_int* iseed,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zlaghe( lapack_int* n, lapack_int* k, const double* d,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_int* iseed, lapack_complex_double* work,\n                    lapack_int *info );\nvoid LAPACK_slagsy( lapack_int* n, lapack_int* k, const float* d, float* a,\n                    lapack_int* lda, lapack_int* iseed, float* work,\n                    lapack_int *info );\nvoid LAPACK_dlagsy( lapack_int* n, lapack_int* k, const double* d, double* a,\n                    lapack_int* lda, lapack_int* iseed, double* work,\n                    lapack_int *info );\nvoid LAPACK_clagsy( lapack_int* n, lapack_int* k, const float* d,\n                    lapack_complex_float* a, lapack_int* lda, lapack_int* iseed,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zlagsy( lapack_int* n, lapack_int* k, const double* d,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_int* iseed, lapack_complex_double* work,\n                    lapack_int *info );\nvoid LAPACK_slapmr( lapack_logical* forwrd, lapack_int* m, lapack_int* n,\n                    float* x, lapack_int* ldx, lapack_int* k );\nvoid LAPACK_dlapmr( lapack_logical* forwrd, lapack_int* m, lapack_int* n,\n                    double* x, lapack_int* ldx, lapack_int* k );\nvoid LAPACK_clapmr( lapack_logical* forwrd, lapack_int* m, lapack_int* n,\n                    lapack_complex_float* x, lapack_int* ldx, lapack_int* k );\nvoid LAPACK_zlapmr( lapack_logical* forwrd, lapack_int* m, lapack_int* n,\n                    lapack_complex_double* x, lapack_int* ldx, lapack_int* k );\nfloat LAPACK_slapy2( float* x, float* y );\ndouble LAPACK_dlapy2( double* x, double* y );\nfloat LAPACK_slapy3( float* x, float* y, float* z );\ndouble LAPACK_dlapy3( double* x, double* y, double* z );\nvoid LAPACK_slartgp( float* f, float* g, float* cs, float* sn, float* r );\nvoid LAPACK_dlartgp( double* f, double* g, double* cs, double* sn, double* r );\nvoid LAPACK_slartgs( float* x, float* y, float* sigma, float* cs, float* sn );\nvoid LAPACK_dlartgs( double* x, double* y, double* sigma, double* cs,\n                     double* sn );\n// LAPACK 3.3.0\nvoid LAPACK_cbbcsd( char* jobu1, char* jobu2,\n                    char* jobv1t, char* jobv2t, char* trans,\n                    lapack_int* m, lapack_int* p, lapack_int* q,\n                    float* theta, float* phi,\n                    lapack_complex_float* u1, lapack_int* ldu1,\n                    lapack_complex_float* u2, lapack_int* ldu2,\n                    lapack_complex_float* v1t, lapack_int* ldv1t,\n                    lapack_complex_float* v2t, lapack_int* ldv2t,\n                    float* b11d, float* b11e, float* b12d,\n                    float* b12e, float* b21d, float* b21e,\n                    float* b22d, float* b22e, float* rwork,\n                    lapack_int* lrwork , lapack_int *info );\nvoid LAPACK_cheswapr( char* uplo, lapack_int* n,\n                      lapack_complex_float* a, lapack_int* i1,\n                      lapack_int* i2 );\nvoid LAPACK_chetri2( char* uplo, lapack_int* n,\n                     lapack_complex_float* a, lapack_int* lda,\n                     const lapack_int* ipiv,\n                     lapack_complex_float* work, lapack_int* lwork , lapack_int *info );\nvoid LAPACK_chetri2x( char* uplo, lapack_int* n,\n                      lapack_complex_float* a, lapack_int* lda,\n                      const lapack_int* ipiv,\n                      lapack_complex_float* work, lapack_int* nb , lapack_int *info );\nvoid LAPACK_chetrs2( char* uplo, lapack_int* n,\n                     lapack_int* nrhs, const lapack_complex_float* a,\n                     lapack_int* lda, const lapack_int* ipiv,\n                     lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* work , lapack_int *info );\nvoid LAPACK_csyconv( char* uplo, char* way,\n                     lapack_int* n, lapack_complex_float* a,\n                     lapack_int* lda, const lapack_int* ipiv,\n                     lapack_complex_float* work , lapack_int *info );\nvoid LAPACK_csyswapr( char* uplo, lapack_int* n,\n                      lapack_complex_float* a, lapack_int* i1,\n                      lapack_int* i2 );\nvoid LAPACK_csytri2( char* uplo, lapack_int* n,\n                     lapack_complex_float* a, lapack_int* lda,\n                     const lapack_int* ipiv,\n                     lapack_complex_float* work, lapack_int* lwork , lapack_int *info );\nvoid LAPACK_csytri2x( char* uplo, lapack_int* n,\n                      lapack_complex_float* a, lapack_int* lda,\n                      const lapack_int* ipiv,\n                      lapack_complex_float* work, lapack_int* nb , lapack_int *info );\nvoid LAPACK_csytrs2( char* uplo, lapack_int* n,\n                     lapack_int* nrhs, const lapack_complex_float* a,\n                     lapack_int* lda, const lapack_int* ipiv,\n                     lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* work , lapack_int *info );\nvoid LAPACK_cunbdb( char* trans, char* signs,\n                    lapack_int* m, lapack_int* p, lapack_int* q,\n                    lapack_complex_float* x11, lapack_int* ldx11,\n                    lapack_complex_float* x12, lapack_int* ldx12,\n                    lapack_complex_float* x21, lapack_int* ldx21,\n                    lapack_complex_float* x22, lapack_int* ldx22,\n                    float* theta, float* phi,\n                    lapack_complex_float* taup1,\n                    lapack_complex_float* taup2,\n                    lapack_complex_float* tauq1,\n                    lapack_complex_float* tauq2,\n                    lapack_complex_float* work, lapack_int* lwork , lapack_int *info );\nvoid LAPACK_cuncsd( char* jobu1, char* jobu2,\n                    char* jobv1t, char* jobv2t, char* trans,\n                    char* signs, lapack_int* m, lapack_int* p,\n                    lapack_int* q, lapack_complex_float* x11,\n                    lapack_int* ldx11, lapack_complex_float* x12,\n                    lapack_int* ldx12, lapack_complex_float* x21,\n                    lapack_int* ldx21, lapack_complex_float* x22,\n                    lapack_int* ldx22, float* theta,\n                    lapack_complex_float* u1, lapack_int* ldu1,\n                    lapack_complex_float* u2, lapack_int* ldu2,\n                    lapack_complex_float* v1t, lapack_int* ldv1t,\n                    lapack_complex_float* v2t, lapack_int* ldv2t,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    float* rwork, lapack_int* lrwork,\n                    lapack_int* iwork , lapack_int *info );\nvoid LAPACK_dbbcsd( char* jobu1, char* jobu2,\n                    char* jobv1t, char* jobv2t, char* trans,\n                    lapack_int* m, lapack_int* p, lapack_int* q,\n                    double* theta, double* phi, double* u1,\n                    lapack_int* ldu1, double* u2, lapack_int* ldu2,\n                    double* v1t, lapack_int* ldv1t, double* v2t,\n                    lapack_int* ldv2t, double* b11d, double* b11e,\n                    double* b12d, double* b12e, double* b21d,\n                    double* b21e, double* b22d, double* b22e,\n                    double* work, lapack_int* lwork , lapack_int *info );\nvoid LAPACK_dorbdb( char* trans, char* signs,\n                    lapack_int* m, lapack_int* p, lapack_int* q,\n                    double* x11, lapack_int* ldx11, double* x12,\n                    lapack_int* ldx12, double* x21, lapack_int* ldx21,\n                    double* x22, lapack_int* ldx22, double* theta,\n                    double* phi, double* taup1, double* taup2,\n                    double* tauq1, double* tauq2, double* work,\n                    lapack_int* lwork , lapack_int *info );\nvoid LAPACK_dorcsd( char* jobu1, char* jobu2,\n                    char* jobv1t, char* jobv2t, char* trans,\n                    char* signs, lapack_int* m, lapack_int* p,\n                    lapack_int* q, double* x11, lapack_int* ldx11,\n                    double* x12, lapack_int* ldx12, double* x21,\n                    lapack_int* ldx21, double* x22, lapack_int* ldx22,\n                    double* theta, double* u1, lapack_int* ldu1,\n                    double* u2, lapack_int* ldu2, double* v1t,\n                    lapack_int* ldv1t, double* v2t, lapack_int* ldv2t,\n                    double* work, lapack_int* lwork,\n                    lapack_int* iwork , lapack_int *info );\nvoid LAPACK_dsyconv( char* uplo, char* way,\n                     lapack_int* n, double* a, lapack_int* lda,\n                     const lapack_int* ipiv, double* work , lapack_int *info );\nvoid LAPACK_dsyswapr( char* uplo, lapack_int* n,\n                      double* a, lapack_int* i1, lapack_int* i2 );\nvoid LAPACK_dsytri2( char* uplo, lapack_int* n,\n                     double* a, lapack_int* lda,\n                     const lapack_int* ipiv,\n                     lapack_complex_double* work, lapack_int* lwork , lapack_int *info );\nvoid LAPACK_dsytri2x( char* uplo, lapack_int* n,\n                      double* a, lapack_int* lda,\n                      const lapack_int* ipiv, double* work,\n                      lapack_int* nb , lapack_int *info );\nvoid LAPACK_dsytrs2( char* uplo, lapack_int* n,\n                     lapack_int* nrhs, const double* a,\n                     lapack_int* lda, const lapack_int* ipiv,\n                     double* b, lapack_int* ldb, double* work , lapack_int *info );\nvoid LAPACK_sbbcsd( char* jobu1, char* jobu2,\n                    char* jobv1t, char* jobv2t, char* trans,\n                    lapack_int* m, lapack_int* p, lapack_int* q,\n                    float* theta, float* phi, float* u1,\n                    lapack_int* ldu1, float* u2, lapack_int* ldu2,\n                    float* v1t, lapack_int* ldv1t, float* v2t,\n                    lapack_int* ldv2t, float* b11d, float* b11e,\n                    float* b12d, float* b12e, float* b21d,\n                    float* b21e, float* b22d, float* b22e,\n                    float* work, lapack_int* lwork , lapack_int *info );\nvoid LAPACK_sorbdb( char* trans, char* signs,\n                    lapack_int* m, lapack_int* p, lapack_int* q,\n                    float* x11, lapack_int* ldx11, float* x12,\n                    lapack_int* ldx12, float* x21, lapack_int* ldx21,\n                    float* x22, lapack_int* ldx22, float* theta,\n                    float* phi, float* taup1, float* taup2,\n                    float* tauq1, float* tauq2, float* work,\n                    lapack_int* lwork , lapack_int *info );\nvoid LAPACK_sorcsd( char* jobu1, char* jobu2,\n                    char* jobv1t, char* jobv2t, char* trans,\n                    char* signs, lapack_int* m, lapack_int* p,\n                    lapack_int* q, float* x11, lapack_int* ldx11,\n                    float* x12, lapack_int* ldx12, float* x21,\n                    lapack_int* ldx21, float* x22, lapack_int* ldx22,\n                    float* theta, float* u1, lapack_int* ldu1,\n                    float* u2, lapack_int* ldu2, float* v1t,\n                    lapack_int* ldv1t, float* v2t, lapack_int* ldv2t,\n                    float* work, lapack_int* lwork,\n                    lapack_int* iwork , lapack_int *info );\nvoid LAPACK_ssyconv( char* uplo, char* way,\n                     lapack_int* n, float* a, lapack_int* lda,\n                     const lapack_int* ipiv, float* work , lapack_int *info );\nvoid LAPACK_ssyswapr( char* uplo, lapack_int* n,\n                      float* a, lapack_int* i1, lapack_int* i2 );\nvoid LAPACK_ssytri2( char* uplo, lapack_int* n,\n                     float* a, lapack_int* lda,\n                     const lapack_int* ipiv,\n                     lapack_complex_float* work, lapack_int* lwork , lapack_int *info );\nvoid LAPACK_ssytri2x( char* uplo, lapack_int* n,\n                      float* a, lapack_int* lda,\n                      const lapack_int* ipiv, float* work,\n                      lapack_int* nb , lapack_int *info );\nvoid LAPACK_ssytrs2( char* uplo, lapack_int* n,\n                     lapack_int* nrhs, const float* a,\n                     lapack_int* lda, const lapack_int* ipiv,\n                     float* b, lapack_int* ldb, float* work , lapack_int *info );\nvoid LAPACK_zbbcsd( char* jobu1, char* jobu2,\n                    char* jobv1t, char* jobv2t, char* trans,\n                    lapack_int* m, lapack_int* p, lapack_int* q,\n                    double* theta, double* phi,\n                    lapack_complex_double* u1, lapack_int* ldu1,\n                    lapack_complex_double* u2, lapack_int* ldu2,\n                    lapack_complex_double* v1t, lapack_int* ldv1t,\n                    lapack_complex_double* v2t, lapack_int* ldv2t,\n                    double* b11d, double* b11e, double* b12d,\n                    double* b12e, double* b21d, double* b21e,\n                    double* b22d, double* b22e, double* rwork,\n                    lapack_int* lrwork , lapack_int *info );\nvoid LAPACK_zheswapr( char* uplo, lapack_int* n,\n                      lapack_complex_double* a, lapack_int* i1,\n                      lapack_int* i2 );\nvoid LAPACK_zhetri2( char* uplo, lapack_int* n,\n                     lapack_complex_double* a, lapack_int* lda,\n                     const lapack_int* ipiv,\n                     lapack_complex_double* work, lapack_int* lwork , lapack_int *info );\nvoid LAPACK_zhetri2x( char* uplo, lapack_int* n,\n                      lapack_complex_double* a, lapack_int* lda,\n                      const lapack_int* ipiv,\n                      lapack_complex_double* work, lapack_int* nb , lapack_int *info );\nvoid LAPACK_zhetrs2( char* uplo, lapack_int* n,\n                     lapack_int* nrhs,\n                     const lapack_complex_double* a, lapack_int* lda,\n                     const lapack_int* ipiv,\n                     lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* work , lapack_int *info );\nvoid LAPACK_zsyconv( char* uplo, char* way,\n                     lapack_int* n, lapack_complex_double* a,\n                     lapack_int* lda, const lapack_int* ipiv,\n                     lapack_complex_double* work , lapack_int *info );\nvoid LAPACK_zsyswapr( char* uplo, lapack_int* n,\n                      lapack_complex_double* a, lapack_int* i1,\n                      lapack_int* i2 );\nvoid LAPACK_zsytri2( char* uplo, lapack_int* n,\n                     lapack_complex_double* a, lapack_int* lda,\n                     const lapack_int* ipiv,\n                     lapack_complex_double* work, lapack_int* lwork , lapack_int *info );\nvoid LAPACK_zsytri2x( char* uplo, lapack_int* n,\n                      lapack_complex_double* a, lapack_int* lda,\n                      const lapack_int* ipiv,\n                      lapack_complex_double* work, lapack_int* nb , lapack_int *info );\nvoid LAPACK_zsytrs2( char* uplo, lapack_int* n,\n                     lapack_int* nrhs,\n                     const lapack_complex_double* a, lapack_int* lda,\n                     const lapack_int* ipiv,\n                     lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* work , lapack_int *info );\nvoid LAPACK_zunbdb( char* trans, char* signs,\n                    lapack_int* m, lapack_int* p, lapack_int* q,\n                    lapack_complex_double* x11, lapack_int* ldx11,\n                    lapack_complex_double* x12, lapack_int* ldx12,\n                    lapack_complex_double* x21, lapack_int* ldx21,\n                    lapack_complex_double* x22, lapack_int* ldx22,\n                    double* theta, double* phi,\n                    lapack_complex_double* taup1,\n                    lapack_complex_double* taup2,\n                    lapack_complex_double* tauq1,\n                    lapack_complex_double* tauq2,\n                    lapack_complex_double* work, lapack_int* lwork , lapack_int *info );\nvoid LAPACK_zuncsd( char* jobu1, char* jobu2,\n                    char* jobv1t, char* jobv2t, char* trans,\n                    char* signs, lapack_int* m, lapack_int* p,\n                    lapack_int* q, lapack_complex_double* x11,\n                    lapack_int* ldx11, lapack_complex_double* x12,\n                    lapack_int* ldx12, lapack_complex_double* x21,\n                    lapack_int* ldx21, lapack_complex_double* x22,\n                    lapack_int* ldx22, double* theta,\n                    lapack_complex_double* u1, lapack_int* ldu1,\n                    lapack_complex_double* u2, lapack_int* ldu2,\n                    lapack_complex_double* v1t, lapack_int* ldv1t,\n                    lapack_complex_double* v2t, lapack_int* ldv2t,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* lrwork,\n                    lapack_int* iwork , lapack_int *info );\n// LAPACK 3.4.0\nvoid LAPACK_sgemqrt( char* side, char* trans, lapack_int* m, lapack_int* n,\n                     lapack_int* k, lapack_int* nb, const float* v,\n                     lapack_int* ldv, const float* t, lapack_int* ldt, float* c,\n                     lapack_int* ldc, float* work, lapack_int *info );\nvoid LAPACK_dgemqrt( char* side, char* trans, lapack_int* m, lapack_int* n,\n                     lapack_int* k, lapack_int* nb, const double* v,\n                     lapack_int* ldv, const double* t, lapack_int* ldt,\n                     double* c, lapack_int* ldc, double* work,\n                     lapack_int *info );\nvoid LAPACK_cgemqrt( char* side, char* trans, lapack_int* m, lapack_int* n,\n                     lapack_int* k, lapack_int* nb,\n                     const lapack_complex_float* v, lapack_int* ldv,\n                     const lapack_complex_float* t, lapack_int* ldt,\n                     lapack_complex_float* c, lapack_int* ldc,\n                     lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zgemqrt( char* side, char* trans, lapack_int* m, lapack_int* n,\n                     lapack_int* k, lapack_int* nb,\n                     const lapack_complex_double* v, lapack_int* ldv,\n                     const lapack_complex_double* t, lapack_int* ldt,\n                     lapack_complex_double* c, lapack_int* ldc,\n                     lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_sgeqrt( lapack_int* m, lapack_int* n, lapack_int* nb, float* a,\n                    lapack_int* lda, float* t, lapack_int* ldt, float* work,\n                    lapack_int *info );\nvoid LAPACK_dgeqrt( lapack_int* m, lapack_int* n, lapack_int* nb, double* a,\n                    lapack_int* lda, double* t, lapack_int* ldt, double* work,\n                    lapack_int *info );\nvoid LAPACK_cgeqrt( lapack_int* m, lapack_int* n, lapack_int* nb,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* t, lapack_int* ldt,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zgeqrt( lapack_int* m, lapack_int* n, lapack_int* nb,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* t, lapack_int* ldt,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_sgeqrt2( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                     float* t, lapack_int* ldt, lapack_int *info );\nvoid LAPACK_dgeqrt2( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                     double* t, lapack_int* ldt, lapack_int *info );\nvoid LAPACK_cgeqrt2( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                     lapack_int* lda, lapack_complex_float* t, lapack_int* ldt,\n                     lapack_int *info );\nvoid LAPACK_zgeqrt2( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                     lapack_int* lda, lapack_complex_double* t, lapack_int* ldt,\n                     lapack_int *info );\nvoid LAPACK_sgeqrt3( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                     float* t, lapack_int* ldt, lapack_int *info );\nvoid LAPACK_dgeqrt3( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                     double* t, lapack_int* ldt, lapack_int *info );\nvoid LAPACK_cgeqrt3( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                     lapack_int* lda, lapack_complex_float* t, lapack_int* ldt,\n                     lapack_int *info );\nvoid LAPACK_zgeqrt3( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                     lapack_int* lda, lapack_complex_double* t, lapack_int* ldt,\n                     lapack_int *info );\nvoid LAPACK_stpmqrt( char* side, char* trans, lapack_int* m, lapack_int* n,\n                     lapack_int* k, lapack_int* l, lapack_int* nb,\n                     const float* v, lapack_int* ldv, const float* t,\n                     lapack_int* ldt, float* a, lapack_int* lda, float* b,\n                     lapack_int* ldb, float* work, lapack_int *info );\nvoid LAPACK_dtpmqrt( char* side, char* trans, lapack_int* m, lapack_int* n,\n                     lapack_int* k, lapack_int* l, lapack_int* nb,\n                     const double* v, lapack_int* ldv, const double* t,\n                     lapack_int* ldt, double* a, lapack_int* lda, double* b,\n                     lapack_int* ldb, double* work, lapack_int *info );\nvoid LAPACK_ctpmqrt( char* side, char* trans, lapack_int* m, lapack_int* n,\n                     lapack_int* k, lapack_int* l, lapack_int* nb,\n                     const lapack_complex_float* v, lapack_int* ldv,\n                     const lapack_complex_float* t, lapack_int* ldt,\n                     lapack_complex_float* a, lapack_int* lda,\n                     lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_ztpmqrt( char* side, char* trans, lapack_int* m, lapack_int* n,\n                     lapack_int* k, lapack_int* l, lapack_int* nb,\n                     const lapack_complex_double* v, lapack_int* ldv,\n                     const lapack_complex_double* t, lapack_int* ldt,\n                     lapack_complex_double* a, lapack_int* lda,\n                     lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_dtpqrt( lapack_int* m, lapack_int* n, lapack_int* l, lapack_int* nb,\n                    double* a, lapack_int* lda, double* b, lapack_int* ldb,\n                    double* t, lapack_int* ldt, double* work,\n                    lapack_int *info );\nvoid LAPACK_ctpqrt( lapack_int* m, lapack_int* n, lapack_int* l, lapack_int* nb,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* t, lapack_complex_float* b,\n                    lapack_int* ldb, lapack_int* ldt,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_ztpqrt( lapack_int* m, lapack_int* n, lapack_int* l, lapack_int* nb,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* t, lapack_int* ldt,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_stpqrt2( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                     float* b, lapack_int* ldb, float* t, lapack_int* ldt,\n                     lapack_int *info );\nvoid LAPACK_dtpqrt2( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                     double* b, lapack_int* ldb, double* t, lapack_int* ldt,\n                     lapack_int *info );\nvoid LAPACK_ctpqrt2( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                     lapack_int* lda, lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* t, lapack_int* ldt,\n                     lapack_int *info );\nvoid LAPACK_ztpqrt2( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                     lapack_int* lda, lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* t, lapack_int* ldt,\n                     lapack_int *info );\nvoid LAPACK_stprfb( char* side, char* trans, char* direct, char* storev,\n                    lapack_int* m, lapack_int* n, lapack_int* k, lapack_int* l,\n                    const float* v, lapack_int* ldv, const float* t,\n                    lapack_int* ldt, float* a, lapack_int* lda, float* b,\n                    lapack_int* ldb, const float* mywork,\n                    lapack_int* myldwork );\nvoid LAPACK_dtprfb( char* side, char* trans, char* direct, char* storev,\n                    lapack_int* m, lapack_int* n, lapack_int* k, lapack_int* l,\n                    const double* v, lapack_int* ldv, const double* t,\n                    lapack_int* ldt, double* a, lapack_int* lda, double* b,\n                    lapack_int* ldb, const double* mywork,\n                    lapack_int* myldwork );\nvoid LAPACK_ctprfb( char* side, char* trans, char* direct, char* storev,\n                    lapack_int* m, lapack_int* n, lapack_int* k, lapack_int* l,\n                    const lapack_complex_float* v, lapack_int* ldv,\n                    const lapack_complex_float* t, lapack_int* ldt,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    const float* mywork, lapack_int* myldwork );\nvoid LAPACK_ztprfb( char* side, char* trans, char* direct, char* storev,\n                    lapack_int* m, lapack_int* n, lapack_int* k, lapack_int* l,\n                    const lapack_complex_double* v, lapack_int* ldv,\n                    const lapack_complex_double* t, lapack_int* ldt,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    const double* mywork, lapack_int* myldwork );\n// LAPACK 3.X.X\nvoid LAPACK_csyr( char* uplo, lapack_int* n, lapack_complex_float* alpha,\n                      const lapack_complex_float* x, lapack_int* incx,\n                      lapack_complex_float* a, lapack_int* lda );\nvoid LAPACK_zsyr( char* uplo, lapack_int* n, lapack_complex_double* alpha,\n                      const lapack_complex_double* x, lapack_int* incx,\n                      lapack_complex_double* a, lapack_int* lda );\n\n#ifdef __cplusplus\n}\n#endif /* __cplusplus */\n\n#endif /* _LAPACKE_H_ */\n\n#endif /* _MKL_LAPACKE_H_ */\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/misc/lapacke_mangling.h",
    "content": "#ifndef LAPACK_HEADER_INCLUDED\n#define LAPACK_HEADER_INCLUDED\n\n#ifndef LAPACK_GLOBAL\n#if defined(LAPACK_GLOBAL_PATTERN_LC) || defined(ADD_)\n#define LAPACK_GLOBAL(lcname,UCNAME)  lcname##_\n#elif defined(LAPACK_GLOBAL_PATTERN_UC) || defined(UPPER)\n#define LAPACK_GLOBAL(lcname,UCNAME)  UCNAME\n#elif defined(LAPACK_GLOBAL_PATTERN_MC) || defined(NOCHANGE)\n#define LAPACK_GLOBAL(lcname,UCNAME)  lcname\n#else\n#define LAPACK_GLOBAL(lcname,UCNAME)  lcname##_\n#endif\n#endif\n\n#endif\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/plugins/ArrayCwiseBinaryOps.h",
    "content": "\n/** \\returns an expression of the coefficient wise product of \\c *this and \\a other\n  *\n  * \\sa MatrixBase::cwiseProduct\n  */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const EIGEN_CWISE_BINARY_RETURN_TYPE(Derived,OtherDerived,product)\noperator*(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  return EIGEN_CWISE_BINARY_RETURN_TYPE(Derived,OtherDerived,product)(derived(), other.derived());\n}\n\n/** \\returns an expression of the coefficient wise quotient of \\c *this and \\a other\n  *\n  * \\sa MatrixBase::cwiseQuotient\n  */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_quotient_op<Scalar,typename OtherDerived::Scalar>, const Derived, const OtherDerived>\noperator/(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  return CwiseBinaryOp<internal::scalar_quotient_op<Scalar,typename OtherDerived::Scalar>, const Derived, const OtherDerived>(derived(), other.derived());\n}\n\n/** \\returns an expression of the coefficient-wise min of \\c *this and \\a other\n  *\n  * Example: \\include Cwise_min.cpp\n  * Output: \\verbinclude Cwise_min.out\n  *\n  * \\sa max()\n  */\nEIGEN_MAKE_CWISE_BINARY_OP(min,min)\n\n/** \\returns an expression of the coefficient-wise min of \\c *this and scalar \\a other\n  *\n  * \\sa max()\n  */\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_min_op<Scalar,Scalar>, const Derived,\n                                        const CwiseNullaryOp<internal::scalar_constant_op<Scalar>, PlainObject> >\n#ifdef EIGEN_PARSED_BY_DOXYGEN\nmin\n#else\n(min)\n#endif\n(const Scalar &other) const\n{\n  return (min)(Derived::PlainObject::Constant(rows(), cols(), other));\n}\n\n/** \\returns an expression of the coefficient-wise max of \\c *this and \\a other\n  *\n  * Example: \\include Cwise_max.cpp\n  * Output: \\verbinclude Cwise_max.out\n  *\n  * \\sa min()\n  */\nEIGEN_MAKE_CWISE_BINARY_OP(max,max)\n\n/** \\returns an expression of the coefficient-wise max of \\c *this and scalar \\a other\n  *\n  * \\sa min()\n  */\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_max_op<Scalar,Scalar>, const Derived,\n                                        const CwiseNullaryOp<internal::scalar_constant_op<Scalar>, PlainObject> >\n#ifdef EIGEN_PARSED_BY_DOXYGEN\nmax\n#else\n(max)\n#endif\n(const Scalar &other) const\n{\n  return (max)(Derived::PlainObject::Constant(rows(), cols(), other));\n}\n\n/** \\returns an expression of the coefficient-wise absdiff of \\c *this and \\a other\n  *\n  * Example: \\include Cwise_absolute_difference.cpp\n  * Output: \\verbinclude Cwise_absolute_difference.out\n  *\n  * \\sa absolute_difference()\n  */\nEIGEN_MAKE_CWISE_BINARY_OP(absolute_difference,absolute_difference)\n\n/** \\returns an expression of the coefficient-wise absolute_difference of \\c *this and scalar \\a other\n  *\n  * \\sa absolute_difference()\n  */\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_absolute_difference_op<Scalar,Scalar>, const Derived,\n                                        const CwiseNullaryOp<internal::scalar_constant_op<Scalar>, PlainObject> >\n#ifdef EIGEN_PARSED_BY_DOXYGEN\nabsolute_difference\n#else\n(absolute_difference)\n#endif\n(const Scalar &other) const\n{\n  return (absolute_difference)(Derived::PlainObject::Constant(rows(), cols(), other));\n}\n\n/** \\returns an expression of the coefficient-wise power of \\c *this to the given array of \\a exponents.\n  *\n  * This function computes the coefficient-wise power.\n  *\n  * Example: \\include Cwise_array_power_array.cpp\n  * Output: \\verbinclude Cwise_array_power_array.out\n  */\nEIGEN_MAKE_CWISE_BINARY_OP(pow,pow)\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nEIGEN_MAKE_SCALAR_BINARY_OP_ONTHERIGHT(pow,pow)\n#else\n/** \\returns an expression of the coefficients of \\c *this rasied to the constant power \\a exponent\n  *\n  * \\tparam T is the scalar type of \\a exponent. It must be compatible with the scalar type of the given expression.\n  *\n  * This function computes the coefficient-wise power. The function MatrixBase::pow() in the\n  * unsupported module MatrixFunctions computes the matrix power.\n  *\n  * Example: \\include Cwise_pow.cpp\n  * Output: \\verbinclude Cwise_pow.out\n  *\n  * \\sa ArrayBase::pow(ArrayBase), square(), cube(), exp(), log()\n  */\ntemplate<typename T>\nconst CwiseBinaryOp<internal::scalar_pow_op<Scalar,T>,Derived,Constant<T> > pow(const T& exponent) const;\n#endif\n\n\n// TODO code generating macros could be moved to Macros.h and could include generation of documentation\n#define EIGEN_MAKE_CWISE_COMP_OP(OP, COMPARATOR) \\\ntemplate<typename OtherDerived> \\\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_cmp_op<Scalar, typename OtherDerived::Scalar, internal::cmp_ ## COMPARATOR>, const Derived, const OtherDerived> \\\nOP(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const \\\n{ \\\n  return CwiseBinaryOp<internal::scalar_cmp_op<Scalar, typename OtherDerived::Scalar, internal::cmp_ ## COMPARATOR>, const Derived, const OtherDerived>(derived(), other.derived()); \\\n}\\\ntypedef CwiseBinaryOp<internal::scalar_cmp_op<Scalar,Scalar, internal::cmp_ ## COMPARATOR>, const Derived, const CwiseNullaryOp<internal::scalar_constant_op<Scalar>, PlainObject> > Cmp ## COMPARATOR ## ReturnType; \\\ntypedef CwiseBinaryOp<internal::scalar_cmp_op<Scalar,Scalar, internal::cmp_ ## COMPARATOR>, const CwiseNullaryOp<internal::scalar_constant_op<Scalar>, PlainObject>, const Derived > RCmp ## COMPARATOR ## ReturnType; \\\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Cmp ## COMPARATOR ## ReturnType \\\nOP(const Scalar& s) const { \\\n  return this->OP(Derived::PlainObject::Constant(rows(), cols(), s)); \\\n} \\\nEIGEN_DEVICE_FUNC friend EIGEN_STRONG_INLINE const RCmp ## COMPARATOR ## ReturnType \\\nOP(const Scalar& s, const EIGEN_CURRENT_STORAGE_BASE_CLASS<Derived>& d) { \\\n  return Derived::PlainObject::Constant(d.rows(), d.cols(), s).OP(d); \\\n}\n\n#define EIGEN_MAKE_CWISE_COMP_R_OP(OP, R_OP, RCOMPARATOR) \\\ntemplate<typename OtherDerived> \\\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_cmp_op<typename OtherDerived::Scalar, Scalar, internal::cmp_##RCOMPARATOR>, const OtherDerived, const Derived> \\\nOP(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const \\\n{ \\\n  return CwiseBinaryOp<internal::scalar_cmp_op<typename OtherDerived::Scalar, Scalar, internal::cmp_##RCOMPARATOR>, const OtherDerived, const Derived>(other.derived(), derived()); \\\n} \\\nEIGEN_DEVICE_FUNC \\\ninline const RCmp ## RCOMPARATOR ## ReturnType \\\nOP(const Scalar& s) const { \\\n  return Derived::PlainObject::Constant(rows(), cols(), s).R_OP(*this); \\\n} \\\nfriend inline const Cmp ## RCOMPARATOR ## ReturnType \\\nOP(const Scalar& s, const Derived& d) { \\\n  return d.R_OP(Derived::PlainObject::Constant(d.rows(), d.cols(), s)); \\\n}\n\n\n\n/** \\returns an expression of the coefficient-wise \\< operator of *this and \\a other\n  *\n  * Example: \\include Cwise_less.cpp\n  * Output: \\verbinclude Cwise_less.out\n  *\n  * \\sa all(), any(), operator>(), operator<=()\n  */\nEIGEN_MAKE_CWISE_COMP_OP(operator<, LT)\n\n/** \\returns an expression of the coefficient-wise \\<= operator of *this and \\a other\n  *\n  * Example: \\include Cwise_less_equal.cpp\n  * Output: \\verbinclude Cwise_less_equal.out\n  *\n  * \\sa all(), any(), operator>=(), operator<()\n  */\nEIGEN_MAKE_CWISE_COMP_OP(operator<=, LE)\n\n/** \\returns an expression of the coefficient-wise \\> operator of *this and \\a other\n  *\n  * Example: \\include Cwise_greater.cpp\n  * Output: \\verbinclude Cwise_greater.out\n  *\n  * \\sa all(), any(), operator>=(), operator<()\n  */\nEIGEN_MAKE_CWISE_COMP_R_OP(operator>, operator<, LT)\n\n/** \\returns an expression of the coefficient-wise \\>= operator of *this and \\a other\n  *\n  * Example: \\include Cwise_greater_equal.cpp\n  * Output: \\verbinclude Cwise_greater_equal.out\n  *\n  * \\sa all(), any(), operator>(), operator<=()\n  */\nEIGEN_MAKE_CWISE_COMP_R_OP(operator>=, operator<=, LE)\n\n/** \\returns an expression of the coefficient-wise == operator of *this and \\a other\n  *\n  * \\warning this performs an exact comparison, which is generally a bad idea with floating-point types.\n  * In order to check for equality between two vectors or matrices with floating-point coefficients, it is\n  * generally a far better idea to use a fuzzy comparison as provided by isApprox() and\n  * isMuchSmallerThan().\n  *\n  * Example: \\include Cwise_equal_equal.cpp\n  * Output: \\verbinclude Cwise_equal_equal.out\n  *\n  * \\sa all(), any(), isApprox(), isMuchSmallerThan()\n  */\nEIGEN_MAKE_CWISE_COMP_OP(operator==, EQ)\n\n/** \\returns an expression of the coefficient-wise != operator of *this and \\a other\n  *\n  * \\warning this performs an exact comparison, which is generally a bad idea with floating-point types.\n  * In order to check for equality between two vectors or matrices with floating-point coefficients, it is\n  * generally a far better idea to use a fuzzy comparison as provided by isApprox() and\n  * isMuchSmallerThan().\n  *\n  * Example: \\include Cwise_not_equal.cpp\n  * Output: \\verbinclude Cwise_not_equal.out\n  *\n  * \\sa all(), any(), isApprox(), isMuchSmallerThan()\n  */\nEIGEN_MAKE_CWISE_COMP_OP(operator!=, NEQ)\n\n\n#undef EIGEN_MAKE_CWISE_COMP_OP\n#undef EIGEN_MAKE_CWISE_COMP_R_OP\n\n// scalar addition\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nEIGEN_MAKE_SCALAR_BINARY_OP(operator+,sum)\n#else\n/** \\returns an expression of \\c *this with each coeff incremented by the constant \\a scalar\n  *\n  * \\tparam T is the scalar type of \\a scalar. It must be compatible with the scalar type of the given expression.\n  *\n  * Example: \\include Cwise_plus.cpp\n  * Output: \\verbinclude Cwise_plus.out\n  *\n  * \\sa operator+=(), operator-()\n  */\ntemplate<typename T>\nconst CwiseBinaryOp<internal::scalar_sum_op<Scalar,T>,Derived,Constant<T> > operator+(const T& scalar) const;\n/** \\returns an expression of \\a expr with each coeff incremented by the constant \\a scalar\n  *\n  * \\tparam T is the scalar type of \\a scalar. It must be compatible with the scalar type of the given expression.\n  */\ntemplate<typename T> friend\nconst CwiseBinaryOp<internal::scalar_sum_op<T,Scalar>,Constant<T>,Derived> operator+(const T& scalar, const StorageBaseType& expr);\n#endif\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nEIGEN_MAKE_SCALAR_BINARY_OP(operator-,difference)\n#else\n/** \\returns an expression of \\c *this with each coeff decremented by the constant \\a scalar\n  *\n  * \\tparam T is the scalar type of \\a scalar. It must be compatible with the scalar type of the given expression.\n  *\n  * Example: \\include Cwise_minus.cpp\n  * Output: \\verbinclude Cwise_minus.out\n  *\n  * \\sa operator+=(), operator-()\n  */\ntemplate<typename T>\nconst CwiseBinaryOp<internal::scalar_difference_op<Scalar,T>,Derived,Constant<T> > operator-(const T& scalar) const;\n/** \\returns an expression of the constant matrix of value \\a scalar decremented by the coefficients of \\a expr\n  *\n  * \\tparam T is the scalar type of \\a scalar. It must be compatible with the scalar type of the given expression.\n  */\ntemplate<typename T> friend\nconst CwiseBinaryOp<internal::scalar_difference_op<T,Scalar>,Constant<T>,Derived> operator-(const T& scalar, const StorageBaseType& expr);\n#endif\n\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n  EIGEN_MAKE_SCALAR_BINARY_OP_ONTHELEFT(operator/,quotient)\n#else\n  /**\n    * \\brief Component-wise division of the scalar \\a s by array elements of \\a a.\n    *\n    * \\tparam Scalar is the scalar type of \\a x. It must be compatible with the scalar type of the given array expression (\\c Derived::Scalar).\n    */\n  template<typename T> friend\n  inline const CwiseBinaryOp<internal::scalar_quotient_op<T,Scalar>,Constant<T>,Derived>\n  operator/(const T& s,const StorageBaseType& a);\n#endif\n\n/** \\returns an expression of the coefficient-wise ^ operator of *this and \\a other\n *\n * \\warning this operator is for expression of bool only.\n *\n * Example: \\include Cwise_boolean_xor.cpp\n * Output: \\verbinclude Cwise_boolean_xor.out\n *\n * \\sa operator&&(), select()\n */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\ninline const CwiseBinaryOp<internal::scalar_boolean_xor_op, const Derived, const OtherDerived>\noperator^(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  EIGEN_STATIC_ASSERT((internal::is_same<bool,Scalar>::value && internal::is_same<bool,typename OtherDerived::Scalar>::value),\n                      THIS_METHOD_IS_ONLY_FOR_EXPRESSIONS_OF_BOOL);\n  return CwiseBinaryOp<internal::scalar_boolean_xor_op, const Derived, const OtherDerived>(derived(),other.derived());\n}\n\n// NOTE disabled until we agree on argument order\n#if 0\n/** \\cpp11 \\returns an expression of the coefficient-wise polygamma function.\n  *\n  * \\specialfunctions_module\n  *\n  * It returns the \\a n -th derivative of the digamma(psi) evaluated at \\c *this.\n  *\n  * \\warning Be careful with the order of the parameters: x.polygamma(n) is equivalent to polygamma(n,x)\n  *\n  * \\sa Eigen::polygamma()\n  */\ntemplate<typename DerivedN>\ninline const CwiseBinaryOp<internal::scalar_polygamma_op<Scalar>, const DerivedN, const Derived>\npolygamma(const EIGEN_CURRENT_STORAGE_BASE_CLASS<DerivedN> &n) const\n{\n  return CwiseBinaryOp<internal::scalar_polygamma_op<Scalar>, const DerivedN, const Derived>(n.derived(), this->derived());\n}\n#endif\n\n/** \\returns an expression of the coefficient-wise zeta function.\n  *\n  * \\specialfunctions_module\n  *\n  * It returns the Riemann zeta function of two arguments \\c *this and \\a q:\n  *\n  * \\param q is the shift, it must be > 0\n  *\n  * \\note *this is the exponent, it must be > 1.\n  * \\note This function supports only float and double scalar types. To support other scalar types, the user has\n  * to provide implementations of zeta(T,T) for any scalar type T to be supported.\n  *\n  * This method is an alias for zeta(*this,q);\n  *\n  * \\sa Eigen::zeta()\n  */\ntemplate<typename DerivedQ>\ninline const CwiseBinaryOp<internal::scalar_zeta_op<Scalar>, const Derived, const DerivedQ>\nzeta(const EIGEN_CURRENT_STORAGE_BASE_CLASS<DerivedQ> &q) const\n{\n  return CwiseBinaryOp<internal::scalar_zeta_op<Scalar>, const Derived, const DerivedQ>(this->derived(), q.derived());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/plugins/ArrayCwiseUnaryOps.h",
    "content": "\n\ntypedef CwiseUnaryOp<internal::scalar_abs_op<Scalar>, const Derived> AbsReturnType;\ntypedef CwiseUnaryOp<internal::scalar_arg_op<Scalar>, const Derived> ArgReturnType;\ntypedef CwiseUnaryOp<internal::scalar_abs2_op<Scalar>, const Derived> Abs2ReturnType;\ntypedef CwiseUnaryOp<internal::scalar_sqrt_op<Scalar>, const Derived> SqrtReturnType;\ntypedef CwiseUnaryOp<internal::scalar_rsqrt_op<Scalar>, const Derived> RsqrtReturnType;\ntypedef CwiseUnaryOp<internal::scalar_sign_op<Scalar>, const Derived> SignReturnType;\ntypedef CwiseUnaryOp<internal::scalar_inverse_op<Scalar>, const Derived> InverseReturnType;\ntypedef CwiseUnaryOp<internal::scalar_boolean_not_op<Scalar>, const Derived> BooleanNotReturnType;\n\ntypedef CwiseUnaryOp<internal::scalar_exp_op<Scalar>, const Derived> ExpReturnType;\ntypedef CwiseUnaryOp<internal::scalar_expm1_op<Scalar>, const Derived> Expm1ReturnType;\ntypedef CwiseUnaryOp<internal::scalar_log_op<Scalar>, const Derived> LogReturnType;\ntypedef CwiseUnaryOp<internal::scalar_log1p_op<Scalar>, const Derived> Log1pReturnType;\ntypedef CwiseUnaryOp<internal::scalar_log10_op<Scalar>, const Derived> Log10ReturnType;\ntypedef CwiseUnaryOp<internal::scalar_log2_op<Scalar>, const Derived> Log2ReturnType;\ntypedef CwiseUnaryOp<internal::scalar_cos_op<Scalar>, const Derived> CosReturnType;\ntypedef CwiseUnaryOp<internal::scalar_sin_op<Scalar>, const Derived> SinReturnType;\ntypedef CwiseUnaryOp<internal::scalar_tan_op<Scalar>, const Derived> TanReturnType;\ntypedef CwiseUnaryOp<internal::scalar_acos_op<Scalar>, const Derived> AcosReturnType;\ntypedef CwiseUnaryOp<internal::scalar_asin_op<Scalar>, const Derived> AsinReturnType;\ntypedef CwiseUnaryOp<internal::scalar_atan_op<Scalar>, const Derived> AtanReturnType;\ntypedef CwiseUnaryOp<internal::scalar_tanh_op<Scalar>, const Derived> TanhReturnType;\ntypedef CwiseUnaryOp<internal::scalar_logistic_op<Scalar>, const Derived> LogisticReturnType;\ntypedef CwiseUnaryOp<internal::scalar_sinh_op<Scalar>, const Derived> SinhReturnType;\n#if EIGEN_HAS_CXX11_MATH\ntypedef CwiseUnaryOp<internal::scalar_atanh_op<Scalar>, const Derived> AtanhReturnType;\ntypedef CwiseUnaryOp<internal::scalar_asinh_op<Scalar>, const Derived> AsinhReturnType;\ntypedef CwiseUnaryOp<internal::scalar_acosh_op<Scalar>, const Derived> AcoshReturnType;\n#endif\ntypedef CwiseUnaryOp<internal::scalar_cosh_op<Scalar>, const Derived> CoshReturnType;\ntypedef CwiseUnaryOp<internal::scalar_square_op<Scalar>, const Derived> SquareReturnType;\ntypedef CwiseUnaryOp<internal::scalar_cube_op<Scalar>, const Derived> CubeReturnType;\ntypedef CwiseUnaryOp<internal::scalar_round_op<Scalar>, const Derived> RoundReturnType;\ntypedef CwiseUnaryOp<internal::scalar_rint_op<Scalar>, const Derived> RintReturnType;\ntypedef CwiseUnaryOp<internal::scalar_floor_op<Scalar>, const Derived> FloorReturnType;\ntypedef CwiseUnaryOp<internal::scalar_ceil_op<Scalar>, const Derived> CeilReturnType;\ntypedef CwiseUnaryOp<internal::scalar_isnan_op<Scalar>, const Derived> IsNaNReturnType;\ntypedef CwiseUnaryOp<internal::scalar_isinf_op<Scalar>, const Derived> IsInfReturnType;\ntypedef CwiseUnaryOp<internal::scalar_isfinite_op<Scalar>, const Derived> IsFiniteReturnType;\n\n/** \\returns an expression of the coefficient-wise absolute value of \\c *this\n  *\n  * Example: \\include Cwise_abs.cpp\n  * Output: \\verbinclude Cwise_abs.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_abs\">Math functions</a>, abs2()\n  */\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const AbsReturnType\nabs() const\n{\n  return AbsReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise phase angle of \\c *this\n  *\n  * Example: \\include Cwise_arg.cpp\n  * Output: \\verbinclude Cwise_arg.out\n  *\n  * \\sa abs()\n  */\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const ArgReturnType\narg() const\n{\n  return ArgReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise squared absolute value of \\c *this\n  *\n  * Example: \\include Cwise_abs2.cpp\n  * Output: \\verbinclude Cwise_abs2.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_abs2\">Math functions</a>, abs(), square()\n  */\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const Abs2ReturnType\nabs2() const\n{\n  return Abs2ReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise exponential of *this.\n  *\n  * This function computes the coefficient-wise exponential. The function MatrixBase::exp() in the\n  * unsupported module MatrixFunctions computes the matrix exponential.\n  *\n  * Example: \\include Cwise_exp.cpp\n  * Output: \\verbinclude Cwise_exp.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_exp\">Math functions</a>, pow(), log(), sin(), cos()\n  */\nEIGEN_DEVICE_FUNC\ninline const ExpReturnType\nexp() const\n{\n  return ExpReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise exponential of *this minus 1.\n  *\n  * In exact arithmetic, \\c x.expm1() is equivalent to \\c x.exp() - 1,\n  * however, with finite precision, this function is much more accurate when \\c x is close to zero.\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_expm1\">Math functions</a>, exp()\n  */\nEIGEN_DEVICE_FUNC\ninline const Expm1ReturnType\nexpm1() const\n{\n  return Expm1ReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise logarithm of *this.\n  *\n  * This function computes the coefficient-wise logarithm. The function MatrixBase::log() in the\n  * unsupported module MatrixFunctions computes the matrix logarithm.\n  *\n  * Example: \\include Cwise_log.cpp\n  * Output: \\verbinclude Cwise_log.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_log\">Math functions</a>, log()\n  */\nEIGEN_DEVICE_FUNC\ninline const LogReturnType\nlog() const\n{\n  return LogReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise logarithm of 1 plus \\c *this.\n  *\n  * In exact arithmetic, \\c x.log() is equivalent to \\c (x+1).log(),\n  * however, with finite precision, this function is much more accurate when \\c x is close to zero.\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_log1p\">Math functions</a>, log()\n  */\nEIGEN_DEVICE_FUNC\ninline const Log1pReturnType\nlog1p() const\n{\n  return Log1pReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise base-10 logarithm of *this.\n  *\n  * This function computes the coefficient-wise base-10 logarithm.\n  *\n  * Example: \\include Cwise_log10.cpp\n  * Output: \\verbinclude Cwise_log10.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_log10\">Math functions</a>, log()\n  */\nEIGEN_DEVICE_FUNC\ninline const Log10ReturnType\nlog10() const\n{\n  return Log10ReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise base-2 logarithm of *this.\n  *\n  * This function computes the coefficient-wise base-2 logarithm.\n  *\n  */\nEIGEN_DEVICE_FUNC\ninline const Log2ReturnType\nlog2() const\n{\n  return Log2ReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise square root of *this.\n  *\n  * This function computes the coefficient-wise square root. The function MatrixBase::sqrt() in the\n  * unsupported module MatrixFunctions computes the matrix square root.\n  *\n  * Example: \\include Cwise_sqrt.cpp\n  * Output: \\verbinclude Cwise_sqrt.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_sqrt\">Math functions</a>, pow(), square()\n  */\nEIGEN_DEVICE_FUNC\ninline const SqrtReturnType\nsqrt() const\n{\n  return SqrtReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise inverse square root of *this.\n  *\n  * This function computes the coefficient-wise inverse square root.\n  *\n  * Example: \\include Cwise_sqrt.cpp\n  * Output: \\verbinclude Cwise_sqrt.out\n  *\n  * \\sa pow(), square()\n  */\nEIGEN_DEVICE_FUNC\ninline const RsqrtReturnType\nrsqrt() const\n{\n  return RsqrtReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise signum of *this.\n  *\n  * This function computes the coefficient-wise signum.\n  *\n  * Example: \\include Cwise_sign.cpp\n  * Output: \\verbinclude Cwise_sign.out\n  *\n  * \\sa pow(), square()\n  */\nEIGEN_DEVICE_FUNC\ninline const SignReturnType\nsign() const\n{\n  return SignReturnType(derived());\n}\n\n\n/** \\returns an expression of the coefficient-wise cosine of *this.\n  *\n  * This function computes the coefficient-wise cosine. The function MatrixBase::cos() in the\n  * unsupported module MatrixFunctions computes the matrix cosine.\n  *\n  * Example: \\include Cwise_cos.cpp\n  * Output: \\verbinclude Cwise_cos.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_cos\">Math functions</a>, sin(), acos()\n  */\nEIGEN_DEVICE_FUNC\ninline const CosReturnType\ncos() const\n{\n  return CosReturnType(derived());\n}\n\n\n/** \\returns an expression of the coefficient-wise sine of *this.\n  *\n  * This function computes the coefficient-wise sine. The function MatrixBase::sin() in the\n  * unsupported module MatrixFunctions computes the matrix sine.\n  *\n  * Example: \\include Cwise_sin.cpp\n  * Output: \\verbinclude Cwise_sin.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_sin\">Math functions</a>, cos(), asin()\n  */\nEIGEN_DEVICE_FUNC\ninline const SinReturnType\nsin() const\n{\n  return SinReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise tan of *this.\n  *\n  * Example: \\include Cwise_tan.cpp\n  * Output: \\verbinclude Cwise_tan.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_tan\">Math functions</a>, cos(), sin()\n  */\nEIGEN_DEVICE_FUNC\ninline const TanReturnType\ntan() const\n{\n  return TanReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise arc tan of *this.\n  *\n  * Example: \\include Cwise_atan.cpp\n  * Output: \\verbinclude Cwise_atan.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_atan\">Math functions</a>, tan(), asin(), acos()\n  */\nEIGEN_DEVICE_FUNC\ninline const AtanReturnType\natan() const\n{\n  return AtanReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise arc cosine of *this.\n  *\n  * Example: \\include Cwise_acos.cpp\n  * Output: \\verbinclude Cwise_acos.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_acos\">Math functions</a>, cos(), asin()\n  */\nEIGEN_DEVICE_FUNC\ninline const AcosReturnType\nacos() const\n{\n  return AcosReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise arc sine of *this.\n  *\n  * Example: \\include Cwise_asin.cpp\n  * Output: \\verbinclude Cwise_asin.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_asin\">Math functions</a>, sin(), acos()\n  */\nEIGEN_DEVICE_FUNC\ninline const AsinReturnType\nasin() const\n{\n  return AsinReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise hyperbolic tan of *this.\n  *\n  * Example: \\include Cwise_tanh.cpp\n  * Output: \\verbinclude Cwise_tanh.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_tanh\">Math functions</a>, tan(), sinh(), cosh()\n  */\nEIGEN_DEVICE_FUNC\ninline const TanhReturnType\ntanh() const\n{\n  return TanhReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise hyperbolic sin of *this.\n  *\n  * Example: \\include Cwise_sinh.cpp\n  * Output: \\verbinclude Cwise_sinh.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_sinh\">Math functions</a>, sin(), tanh(), cosh()\n  */\nEIGEN_DEVICE_FUNC\ninline const SinhReturnType\nsinh() const\n{\n  return SinhReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise hyperbolic cos of *this.\n  *\n  * Example: \\include Cwise_cosh.cpp\n  * Output: \\verbinclude Cwise_cosh.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_cosh\">Math functions</a>, tanh(), sinh(), cosh()\n  */\nEIGEN_DEVICE_FUNC\ninline const CoshReturnType\ncosh() const\n{\n  return CoshReturnType(derived());\n}\n\n#if EIGEN_HAS_CXX11_MATH\n/** \\returns an expression of the coefficient-wise inverse hyperbolic tan of *this.\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_atanh\">Math functions</a>, atanh(), asinh(), acosh()\n  */\nEIGEN_DEVICE_FUNC\ninline const AtanhReturnType\natanh() const\n{\n  return AtanhReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise inverse hyperbolic sin of *this.\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_asinh\">Math functions</a>, atanh(), asinh(), acosh()\n  */\nEIGEN_DEVICE_FUNC\ninline const AsinhReturnType\nasinh() const\n{\n  return AsinhReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise inverse hyperbolic cos of *this.\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_acosh\">Math functions</a>, atanh(), asinh(), acosh()\n  */\nEIGEN_DEVICE_FUNC\ninline const AcoshReturnType\nacosh() const\n{\n  return AcoshReturnType(derived());\n}\n#endif\n\n/** \\returns an expression of the coefficient-wise logistic of *this.\n  */\nEIGEN_DEVICE_FUNC\ninline const LogisticReturnType\nlogistic() const\n{\n  return LogisticReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise inverse of *this.\n  *\n  * Example: \\include Cwise_inverse.cpp\n  * Output: \\verbinclude Cwise_inverse.out\n  *\n  * \\sa operator/(), operator*()\n  */\nEIGEN_DEVICE_FUNC\ninline const InverseReturnType\ninverse() const\n{\n  return InverseReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise square of *this.\n  *\n  * Example: \\include Cwise_square.cpp\n  * Output: \\verbinclude Cwise_square.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_squareE\">Math functions</a>, abs2(), cube(), pow()\n  */\nEIGEN_DEVICE_FUNC\ninline const SquareReturnType\nsquare() const\n{\n  return SquareReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise cube of *this.\n  *\n  * Example: \\include Cwise_cube.cpp\n  * Output: \\verbinclude Cwise_cube.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_cube\">Math functions</a>, square(), pow()\n  */\nEIGEN_DEVICE_FUNC\ninline const CubeReturnType\ncube() const\n{\n  return CubeReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise rint of *this.\n  *\n  * Example: \\include Cwise_rint.cpp\n  * Output: \\verbinclude Cwise_rint.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_rint\">Math functions</a>, ceil(), floor()\n  */\nEIGEN_DEVICE_FUNC\ninline const RintReturnType\nrint() const\n{\n  return RintReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise round of *this.\n  *\n  * Example: \\include Cwise_round.cpp\n  * Output: \\verbinclude Cwise_round.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_round\">Math functions</a>, ceil(), floor()\n  */\nEIGEN_DEVICE_FUNC\ninline const RoundReturnType\nround() const\n{\n  return RoundReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise floor of *this.\n  *\n  * Example: \\include Cwise_floor.cpp\n  * Output: \\verbinclude Cwise_floor.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_floor\">Math functions</a>, ceil(), round()\n  */\nEIGEN_DEVICE_FUNC\ninline const FloorReturnType\nfloor() const\n{\n  return FloorReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise ceil of *this.\n  *\n  * Example: \\include Cwise_ceil.cpp\n  * Output: \\verbinclude Cwise_ceil.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_ceil\">Math functions</a>, floor(), round()\n  */\nEIGEN_DEVICE_FUNC\ninline const CeilReturnType\nceil() const\n{\n  return CeilReturnType(derived());\n}\n\ntemplate<int N> struct ShiftRightXpr {\n  typedef CwiseUnaryOp<internal::scalar_shift_right_op<Scalar, N>, const Derived> Type;\n};\n\n/** \\returns an expression of \\c *this with the \\a Scalar type arithmetically\n  * shifted right by \\a N bit positions.\n  *\n  * The template parameter \\a N specifies the number of bit positions to shift.\n  * \n  * \\sa shiftLeft()\n  */\ntemplate<int N>\nEIGEN_DEVICE_FUNC\ntypename ShiftRightXpr<N>::Type\nshiftRight() const\n{\n  return typename ShiftRightXpr<N>::Type(derived());\n}\n\n\ntemplate<int N> struct ShiftLeftXpr {\n  typedef CwiseUnaryOp<internal::scalar_shift_left_op<Scalar, N>, const Derived> Type;\n};\n\n/** \\returns an expression of \\c *this with the \\a Scalar type logically\n  * shifted left by \\a N bit positions.\n  *\n  * The template parameter \\a N specifies the number of bit positions to shift.\n  *\n  * \\sa shiftRight()\n  */\ntemplate<int N>\nEIGEN_DEVICE_FUNC\ntypename ShiftLeftXpr<N>::Type\nshiftLeft() const\n{\n  return typename ShiftLeftXpr<N>::Type(derived());\n}\n\n/** \\returns an expression of the coefficient-wise isnan of *this.\n  *\n  * Example: \\include Cwise_isNaN.cpp\n  * Output: \\verbinclude Cwise_isNaN.out\n  *\n  * \\sa isfinite(), isinf()\n  */\nEIGEN_DEVICE_FUNC\ninline const IsNaNReturnType\nisNaN() const\n{\n  return IsNaNReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise isinf of *this.\n  *\n  * Example: \\include Cwise_isInf.cpp\n  * Output: \\verbinclude Cwise_isInf.out\n  *\n  * \\sa isnan(), isfinite()\n  */\nEIGEN_DEVICE_FUNC\ninline const IsInfReturnType\nisInf() const\n{\n  return IsInfReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise isfinite of *this.\n  *\n  * Example: \\include Cwise_isFinite.cpp\n  * Output: \\verbinclude Cwise_isFinite.out\n  *\n  * \\sa isnan(), isinf()\n  */\nEIGEN_DEVICE_FUNC\ninline const IsFiniteReturnType\nisFinite() const\n{\n  return IsFiniteReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise ! operator of *this\n  *\n  * \\warning this operator is for expression of bool only.\n  *\n  * Example: \\include Cwise_boolean_not.cpp\n  * Output: \\verbinclude Cwise_boolean_not.out\n  *\n  * \\sa operator!=()\n  */\nEIGEN_DEVICE_FUNC\ninline const BooleanNotReturnType\noperator!() const\n{\n  EIGEN_STATIC_ASSERT((internal::is_same<bool,Scalar>::value),\n                      THIS_METHOD_IS_ONLY_FOR_EXPRESSIONS_OF_BOOL);\n  return BooleanNotReturnType(derived());\n}\n\n\n// --- SpecialFunctions module ---\n\ntypedef CwiseUnaryOp<internal::scalar_lgamma_op<Scalar>, const Derived> LgammaReturnType;\ntypedef CwiseUnaryOp<internal::scalar_digamma_op<Scalar>, const Derived> DigammaReturnType;\ntypedef CwiseUnaryOp<internal::scalar_erf_op<Scalar>, const Derived> ErfReturnType;\ntypedef CwiseUnaryOp<internal::scalar_erfc_op<Scalar>, const Derived> ErfcReturnType;\ntypedef CwiseUnaryOp<internal::scalar_ndtri_op<Scalar>, const Derived> NdtriReturnType;\n\n/** \\cpp11 \\returns an expression of the coefficient-wise ln(|gamma(*this)|).\n  *\n  * \\specialfunctions_module\n  *\n  * \\note This function supports only float and double scalar types in c++11 mode. To support other scalar types,\n  * or float/double in non c++11 mode, the user has to provide implementations of lgamma(T) for any scalar\n  * type T to be supported.\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_lgamma\">Math functions</a>, digamma()\n  */\nEIGEN_DEVICE_FUNC\ninline const LgammaReturnType\nlgamma() const\n{\n  return LgammaReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise digamma (psi, derivative of lgamma).\n  *\n  * \\specialfunctions_module\n  *\n  * \\note This function supports only float and double scalar types. To support other scalar types,\n  * the user has to provide implementations of digamma(T) for any scalar\n  * type T to be supported.\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_digamma\">Math functions</a>, Eigen::digamma(), Eigen::polygamma(), lgamma()\n  */\nEIGEN_DEVICE_FUNC\ninline const DigammaReturnType\ndigamma() const\n{\n  return DigammaReturnType(derived());\n}\n\n/** \\cpp11 \\returns an expression of the coefficient-wise Gauss error\n  * function of *this.\n  *\n  * \\specialfunctions_module\n  *\n  * \\note This function supports only float and double scalar types in c++11 mode. To support other scalar types,\n  * or float/double in non c++11 mode, the user has to provide implementations of erf(T) for any scalar\n  * type T to be supported.\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_erf\">Math functions</a>, erfc()\n  */\nEIGEN_DEVICE_FUNC\ninline const ErfReturnType\nerf() const\n{\n  return ErfReturnType(derived());\n}\n\n/** \\cpp11 \\returns an expression of the coefficient-wise Complementary error\n  * function of *this.\n  *\n  * \\specialfunctions_module\n  *\n  * \\note This function supports only float and double scalar types in c++11 mode. To support other scalar types,\n  * or float/double in non c++11 mode, the user has to provide implementations of erfc(T) for any scalar\n  * type T to be supported.\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_erfc\">Math functions</a>, erf()\n  */\nEIGEN_DEVICE_FUNC\ninline const ErfcReturnType\nerfc() const\n{\n  return ErfcReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise inverse of the CDF of the Normal distribution function\n  * function of *this.\n  *\n  * \\specialfunctions_module\n  * \n  * In other words, considering `x = ndtri(y)`, it returns the argument, x, for which the area under the\n  * Gaussian probability density function (integrated from minus infinity to x) is equal to y.\n  *\n  * \\note This function supports only float and double scalar types. To support other scalar types,\n  * the user has to provide implementations of ndtri(T) for any scalar type T to be supported.\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_ndtri\">Math functions</a>\n  */\nEIGEN_DEVICE_FUNC\ninline const NdtriReturnType\nndtri() const\n{\n  return NdtriReturnType(derived());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/plugins/BlockMethods.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2006-2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n\n/// \\internal expression type of a column */\ntypedef Block<Derived, internal::traits<Derived>::RowsAtCompileTime, 1, !IsRowMajor> ColXpr;\ntypedef const Block<const Derived, internal::traits<Derived>::RowsAtCompileTime, 1, !IsRowMajor> ConstColXpr;\n/// \\internal expression type of a row */\ntypedef Block<Derived, 1, internal::traits<Derived>::ColsAtCompileTime, IsRowMajor> RowXpr;\ntypedef const Block<const Derived, 1, internal::traits<Derived>::ColsAtCompileTime, IsRowMajor> ConstRowXpr;\n/// \\internal expression type of a block of whole columns */\ntypedef Block<Derived, internal::traits<Derived>::RowsAtCompileTime, Dynamic, !IsRowMajor> ColsBlockXpr;\ntypedef const Block<const Derived, internal::traits<Derived>::RowsAtCompileTime, Dynamic, !IsRowMajor> ConstColsBlockXpr;\n/// \\internal expression type of a block of whole rows */\ntypedef Block<Derived, Dynamic, internal::traits<Derived>::ColsAtCompileTime, IsRowMajor> RowsBlockXpr;\ntypedef const Block<const Derived, Dynamic, internal::traits<Derived>::ColsAtCompileTime, IsRowMajor> ConstRowsBlockXpr;\n/// \\internal expression type of a block of whole columns */\ntemplate<int N> struct NColsBlockXpr { typedef Block<Derived, internal::traits<Derived>::RowsAtCompileTime, N, !IsRowMajor> Type; };\ntemplate<int N> struct ConstNColsBlockXpr { typedef const Block<const Derived, internal::traits<Derived>::RowsAtCompileTime, N, !IsRowMajor> Type; };\n/// \\internal expression type of a block of whole rows */\ntemplate<int N> struct NRowsBlockXpr { typedef Block<Derived, N, internal::traits<Derived>::ColsAtCompileTime, IsRowMajor> Type; };\ntemplate<int N> struct ConstNRowsBlockXpr { typedef const Block<const Derived, N, internal::traits<Derived>::ColsAtCompileTime, IsRowMajor> Type; };\n/// \\internal expression of a block */\ntypedef Block<Derived> BlockXpr;\ntypedef const Block<const Derived> ConstBlockXpr;\n/// \\internal expression of a block of fixed sizes */\ntemplate<int Rows, int Cols> struct FixedBlockXpr { typedef Block<Derived,Rows,Cols> Type; };\ntemplate<int Rows, int Cols> struct ConstFixedBlockXpr { typedef Block<const Derived,Rows,Cols> Type; };\n\ntypedef VectorBlock<Derived> SegmentReturnType;\ntypedef const VectorBlock<const Derived> ConstSegmentReturnType;\ntemplate<int Size> struct FixedSegmentReturnType { typedef VectorBlock<Derived, Size> Type; };\ntemplate<int Size> struct ConstFixedSegmentReturnType { typedef const VectorBlock<const Derived, Size> Type; };\n\n/// \\internal inner-vector\ntypedef Block<Derived,IsRowMajor?1:Dynamic,IsRowMajor?Dynamic:1,true>       InnerVectorReturnType;\ntypedef Block<const Derived,IsRowMajor?1:Dynamic,IsRowMajor?Dynamic:1,true> ConstInnerVectorReturnType;\n\n/// \\internal set of inner-vectors\ntypedef Block<Derived,Dynamic,Dynamic,true> InnerVectorsReturnType;\ntypedef Block<const Derived,Dynamic,Dynamic,true> ConstInnerVectorsReturnType;\n\n#endif // not EIGEN_PARSED_BY_DOXYGEN\n\n/// \\returns an expression of a block in \\c *this with either dynamic or fixed sizes.\n///\n/// \\param  startRow  the first row in the block\n/// \\param  startCol  the first column in the block\n/// \\param  blockRows number of rows in the block, specified at either run-time or compile-time\n/// \\param  blockCols number of columns in the block, specified at either run-time or compile-time\n/// \\tparam NRowsType the type of the value handling the number of rows in the block, typically Index.\n/// \\tparam NColsType the type of the value handling the number of columns in the block, typically Index.\n///\n/// Example using runtime (aka dynamic) sizes: \\include MatrixBase_block_int_int_int_int.cpp\n/// Output: \\verbinclude MatrixBase_block_int_int_int_int.out\n///\n/// \\newin{3.4}:\n///\n/// The number of rows \\a blockRows and columns \\a blockCols can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments. In the later case, \\c n plays the role of a runtime fallback value in case \\c N equals Eigen::Dynamic.\n/// Here is an example with a fixed number of rows \\c NRows and dynamic number of columns \\c cols:\n/// \\code\n/// mat.block(i,j,fix<NRows>,cols)\n/// \\endcode\n///\n/// This function thus fully covers the features offered by the following overloads block<NRows,NCols>(Index, Index),\n/// and block<NRows,NCols>(Index, Index, Index, Index) that are thus obsolete. Indeed, this generic version avoids\n/// redundancy, it preserves the argument order, and prevents the need to rely on the template keyword in templated code.\n///\n/// but with less redundancy and more consistency as it does not modify the argument order\n/// and seamlessly enable hybrid fixed/dynamic sizes.\n///\n/// \\note Even in the case that the returned expression has dynamic size, in the case\n/// when it is applied to a fixed-size matrix, it inherits a fixed maximal size,\n/// which means that evaluating it does not cause a dynamic memory allocation.\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa class Block, fix, fix<N>(int)\n///\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename FixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n#else\ntypename FixedBlockXpr<...,...>::Type\n#endif\nblock(Index startRow, Index startCol, NRowsType blockRows, NColsType blockCols)\n{\n  return typename FixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type(\n            derived(), startRow, startCol, internal::get_runtime_value(blockRows), internal::get_runtime_value(blockCols));\n}\n\n/// This is the const version of block(Index,Index,NRowsType,NColsType)\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstFixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n#else\nconst typename ConstFixedBlockXpr<...,...>::Type\n#endif\nblock(Index startRow, Index startCol, NRowsType blockRows, NColsType blockCols) const\n{\n  return typename ConstFixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type(\n            derived(), startRow, startCol, internal::get_runtime_value(blockRows), internal::get_runtime_value(blockCols));\n}\n\n\n\n/// \\returns a expression of a top-right corner of \\c *this with either dynamic or fixed sizes.\n///\n/// \\param cRows the number of rows in the corner\n/// \\param cCols the number of columns in the corner\n/// \\tparam NRowsType the type of the value handling the number of rows in the block, typically Index.\n/// \\tparam NColsType the type of the value handling the number of columns in the block, typically Index.\n///\n/// Example with dynamic sizes: \\include MatrixBase_topRightCorner_int_int.cpp\n/// Output: \\verbinclude MatrixBase_topRightCorner_int_int.out\n///\n/// The number of rows \\a blockRows and columns \\a blockCols can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments. See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename FixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n#else\ntypename FixedBlockXpr<...,...>::Type\n#endif\ntopRightCorner(NRowsType cRows, NColsType cCols)\n{\n  return typename FixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), 0, cols() - internal::get_runtime_value(cCols), internal::get_runtime_value(cRows), internal::get_runtime_value(cCols));\n}\n\n/// This is the const version of topRightCorner(NRowsType, NColsType).\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstFixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n#else\nconst typename ConstFixedBlockXpr<...,...>::Type\n#endif\ntopRightCorner(NRowsType cRows, NColsType cCols) const\n{\n  return typename ConstFixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), 0, cols() - internal::get_runtime_value(cCols), internal::get_runtime_value(cRows), internal::get_runtime_value(cCols));\n}\n\n/// \\returns an expression of a fixed-size top-right corner of \\c *this.\n///\n/// \\tparam CRows the number of rows in the corner\n/// \\tparam CCols the number of columns in the corner\n///\n/// Example: \\include MatrixBase_template_int_int_topRightCorner.cpp\n/// Output: \\verbinclude MatrixBase_template_int_int_topRightCorner.out\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa class Block, block<int,int>(Index,Index)\n///\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedBlockXpr<CRows,CCols>::Type topRightCorner()\n{\n  return typename FixedBlockXpr<CRows,CCols>::Type(derived(), 0, cols() - CCols);\n}\n\n/// This is the const version of topRightCorner<int, int>().\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst typename ConstFixedBlockXpr<CRows,CCols>::Type topRightCorner() const\n{\n  return typename ConstFixedBlockXpr<CRows,CCols>::Type(derived(), 0, cols() - CCols);\n}\n\n/// \\returns an expression of a top-right corner of \\c *this.\n///\n/// \\tparam CRows number of rows in corner as specified at compile-time\n/// \\tparam CCols number of columns in corner as specified at compile-time\n/// \\param  cRows number of rows in corner as specified at run-time\n/// \\param  cCols number of columns in corner as specified at run-time\n///\n/// This function is mainly useful for corners where the number of rows is specified at compile-time\n/// and the number of columns is specified at run-time, or vice versa. The compile-time and run-time\n/// information should not contradict. In other words, \\a cRows should equal \\a CRows unless\n/// \\a CRows is \\a Dynamic, and the same for the number of columns.\n///\n/// Example: \\include MatrixBase_template_int_int_topRightCorner_int_int.cpp\n/// Output: \\verbinclude MatrixBase_template_int_int_topRightCorner_int_int.out\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa class Block\n///\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedBlockXpr<CRows,CCols>::Type topRightCorner(Index cRows, Index cCols)\n{\n  return typename FixedBlockXpr<CRows,CCols>::Type(derived(), 0, cols() - cCols, cRows, cCols);\n}\n\n/// This is the const version of topRightCorner<int, int>(Index, Index).\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst typename ConstFixedBlockXpr<CRows,CCols>::Type topRightCorner(Index cRows, Index cCols) const\n{\n  return typename ConstFixedBlockXpr<CRows,CCols>::Type(derived(), 0, cols() - cCols, cRows, cCols);\n}\n\n\n\n/// \\returns an expression of a top-left corner of \\c *this  with either dynamic or fixed sizes.\n///\n/// \\param cRows the number of rows in the corner\n/// \\param cCols the number of columns in the corner\n/// \\tparam NRowsType the type of the value handling the number of rows in the block, typically Index.\n/// \\tparam NColsType the type of the value handling the number of columns in the block, typically Index.\n///\n/// Example: \\include MatrixBase_topLeftCorner_int_int.cpp\n/// Output: \\verbinclude MatrixBase_topLeftCorner_int_int.out\n///\n/// The number of rows \\a blockRows and columns \\a blockCols can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments. See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename FixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n#else\ntypename FixedBlockXpr<...,...>::Type\n#endif\ntopLeftCorner(NRowsType cRows, NColsType cCols)\n{\n  return typename FixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), 0, 0, internal::get_runtime_value(cRows), internal::get_runtime_value(cCols));\n}\n\n/// This is the const version of topLeftCorner(Index, Index).\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstFixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n#else\nconst typename ConstFixedBlockXpr<...,...>::Type\n#endif\ntopLeftCorner(NRowsType cRows, NColsType cCols) const\n{\n  return typename ConstFixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), 0, 0, internal::get_runtime_value(cRows), internal::get_runtime_value(cCols));\n}\n\n/// \\returns an expression of a fixed-size top-left corner of \\c *this.\n///\n/// The template parameters CRows and CCols are the number of rows and columns in the corner.\n///\n/// Example: \\include MatrixBase_template_int_int_topLeftCorner.cpp\n/// Output: \\verbinclude MatrixBase_template_int_int_topLeftCorner.out\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedBlockXpr<CRows,CCols>::Type topLeftCorner()\n{\n  return typename FixedBlockXpr<CRows,CCols>::Type(derived(), 0, 0);\n}\n\n/// This is the const version of topLeftCorner<int, int>().\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst typename ConstFixedBlockXpr<CRows,CCols>::Type topLeftCorner() const\n{\n  return typename ConstFixedBlockXpr<CRows,CCols>::Type(derived(), 0, 0);\n}\n\n/// \\returns an expression of a top-left corner of \\c *this.\n///\n/// \\tparam CRows number of rows in corner as specified at compile-time\n/// \\tparam CCols number of columns in corner as specified at compile-time\n/// \\param  cRows number of rows in corner as specified at run-time\n/// \\param  cCols number of columns in corner as specified at run-time\n///\n/// This function is mainly useful for corners where the number of rows is specified at compile-time\n/// and the number of columns is specified at run-time, or vice versa. The compile-time and run-time\n/// information should not contradict. In other words, \\a cRows should equal \\a CRows unless\n/// \\a CRows is \\a Dynamic, and the same for the number of columns.\n///\n/// Example: \\include MatrixBase_template_int_int_topLeftCorner_int_int.cpp\n/// Output: \\verbinclude MatrixBase_template_int_int_topLeftCorner_int_int.out\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa class Block\n///\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedBlockXpr<CRows,CCols>::Type topLeftCorner(Index cRows, Index cCols)\n{\n  return typename FixedBlockXpr<CRows,CCols>::Type(derived(), 0, 0, cRows, cCols);\n}\n\n/// This is the const version of topLeftCorner<int, int>(Index, Index).\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst typename ConstFixedBlockXpr<CRows,CCols>::Type topLeftCorner(Index cRows, Index cCols) const\n{\n  return typename ConstFixedBlockXpr<CRows,CCols>::Type(derived(), 0, 0, cRows, cCols);\n}\n\n\n\n/// \\returns an expression of a bottom-right corner of \\c *this  with either dynamic or fixed sizes.\n///\n/// \\param cRows the number of rows in the corner\n/// \\param cCols the number of columns in the corner\n/// \\tparam NRowsType the type of the value handling the number of rows in the block, typically Index.\n/// \\tparam NColsType the type of the value handling the number of columns in the block, typically Index.\n///\n/// Example: \\include MatrixBase_bottomRightCorner_int_int.cpp\n/// Output: \\verbinclude MatrixBase_bottomRightCorner_int_int.out\n///\n/// The number of rows \\a blockRows and columns \\a blockCols can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments. See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename FixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n#else\ntypename FixedBlockXpr<...,...>::Type\n#endif\nbottomRightCorner(NRowsType cRows, NColsType cCols)\n{\n  return typename FixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), rows() - internal::get_runtime_value(cRows), cols() - internal::get_runtime_value(cCols),\n                        internal::get_runtime_value(cRows), internal::get_runtime_value(cCols));\n}\n\n/// This is the const version of bottomRightCorner(NRowsType, NColsType).\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstFixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n#else\nconst typename ConstFixedBlockXpr<...,...>::Type\n#endif\nbottomRightCorner(NRowsType cRows, NColsType cCols) const\n{\n  return typename ConstFixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), rows() - internal::get_runtime_value(cRows), cols() - internal::get_runtime_value(cCols),\n                        internal::get_runtime_value(cRows), internal::get_runtime_value(cCols));\n}\n\n/// \\returns an expression of a fixed-size bottom-right corner of \\c *this.\n///\n/// The template parameters CRows and CCols are the number of rows and columns in the corner.\n///\n/// Example: \\include MatrixBase_template_int_int_bottomRightCorner.cpp\n/// Output: \\verbinclude MatrixBase_template_int_int_bottomRightCorner.out\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedBlockXpr<CRows,CCols>::Type bottomRightCorner()\n{\n  return typename FixedBlockXpr<CRows,CCols>::Type(derived(), rows() - CRows, cols() - CCols);\n}\n\n/// This is the const version of bottomRightCorner<int, int>().\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst typename ConstFixedBlockXpr<CRows,CCols>::Type bottomRightCorner() const\n{\n  return typename ConstFixedBlockXpr<CRows,CCols>::Type(derived(), rows() - CRows, cols() - CCols);\n}\n\n/// \\returns an expression of a bottom-right corner of \\c *this.\n///\n/// \\tparam CRows number of rows in corner as specified at compile-time\n/// \\tparam CCols number of columns in corner as specified at compile-time\n/// \\param  cRows number of rows in corner as specified at run-time\n/// \\param  cCols number of columns in corner as specified at run-time\n///\n/// This function is mainly useful for corners where the number of rows is specified at compile-time\n/// and the number of columns is specified at run-time, or vice versa. The compile-time and run-time\n/// information should not contradict. In other words, \\a cRows should equal \\a CRows unless\n/// \\a CRows is \\a Dynamic, and the same for the number of columns.\n///\n/// Example: \\include MatrixBase_template_int_int_bottomRightCorner_int_int.cpp\n/// Output: \\verbinclude MatrixBase_template_int_int_bottomRightCorner_int_int.out\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa class Block\n///\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedBlockXpr<CRows,CCols>::Type bottomRightCorner(Index cRows, Index cCols)\n{\n  return typename FixedBlockXpr<CRows,CCols>::Type(derived(), rows() - cRows, cols() - cCols, cRows, cCols);\n}\n\n/// This is the const version of bottomRightCorner<int, int>(Index, Index).\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst typename ConstFixedBlockXpr<CRows,CCols>::Type bottomRightCorner(Index cRows, Index cCols) const\n{\n  return typename ConstFixedBlockXpr<CRows,CCols>::Type(derived(), rows() - cRows, cols() - cCols, cRows, cCols);\n}\n\n\n\n/// \\returns an expression of a bottom-left corner of \\c *this  with either dynamic or fixed sizes.\n///\n/// \\param cRows the number of rows in the corner\n/// \\param cCols the number of columns in the corner\n/// \\tparam NRowsType the type of the value handling the number of rows in the block, typically Index.\n/// \\tparam NColsType the type of the value handling the number of columns in the block, typically Index.\n///\n/// Example: \\include MatrixBase_bottomLeftCorner_int_int.cpp\n/// Output: \\verbinclude MatrixBase_bottomLeftCorner_int_int.out\n///\n/// The number of rows \\a blockRows and columns \\a blockCols can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments. See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename FixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n#else\ntypename FixedBlockXpr<...,...>::Type\n#endif\nbottomLeftCorner(NRowsType cRows, NColsType cCols)\n{\n  return typename FixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), rows() - internal::get_runtime_value(cRows), 0,\n                        internal::get_runtime_value(cRows), internal::get_runtime_value(cCols));\n}\n\n/// This is the const version of bottomLeftCorner(NRowsType, NColsType).\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename ConstFixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n#else\ntypename ConstFixedBlockXpr<...,...>::Type\n#endif\nbottomLeftCorner(NRowsType cRows, NColsType cCols) const\n{\n  return typename ConstFixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), rows() - internal::get_runtime_value(cRows), 0,\n                        internal::get_runtime_value(cRows), internal::get_runtime_value(cCols));\n}\n\n/// \\returns an expression of a fixed-size bottom-left corner of \\c *this.\n///\n/// The template parameters CRows and CCols are the number of rows and columns in the corner.\n///\n/// Example: \\include MatrixBase_template_int_int_bottomLeftCorner.cpp\n/// Output: \\verbinclude MatrixBase_template_int_int_bottomLeftCorner.out\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedBlockXpr<CRows,CCols>::Type bottomLeftCorner()\n{\n  return typename FixedBlockXpr<CRows,CCols>::Type(derived(), rows() - CRows, 0);\n}\n\n/// This is the const version of bottomLeftCorner<int, int>().\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst typename ConstFixedBlockXpr<CRows,CCols>::Type bottomLeftCorner() const\n{\n  return typename ConstFixedBlockXpr<CRows,CCols>::Type(derived(), rows() - CRows, 0);\n}\n\n/// \\returns an expression of a bottom-left corner of \\c *this.\n///\n/// \\tparam CRows number of rows in corner as specified at compile-time\n/// \\tparam CCols number of columns in corner as specified at compile-time\n/// \\param  cRows number of rows in corner as specified at run-time\n/// \\param  cCols number of columns in corner as specified at run-time\n///\n/// This function is mainly useful for corners where the number of rows is specified at compile-time\n/// and the number of columns is specified at run-time, or vice versa. The compile-time and run-time\n/// information should not contradict. In other words, \\a cRows should equal \\a CRows unless\n/// \\a CRows is \\a Dynamic, and the same for the number of columns.\n///\n/// Example: \\include MatrixBase_template_int_int_bottomLeftCorner_int_int.cpp\n/// Output: \\verbinclude MatrixBase_template_int_int_bottomLeftCorner_int_int.out\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa class Block\n///\ntemplate<int CRows, int CCols>\nEIGEN_STRONG_INLINE\ntypename FixedBlockXpr<CRows,CCols>::Type bottomLeftCorner(Index cRows, Index cCols)\n{\n  return typename FixedBlockXpr<CRows,CCols>::Type(derived(), rows() - cRows, 0, cRows, cCols);\n}\n\n/// This is the const version of bottomLeftCorner<int, int>(Index, Index).\ntemplate<int CRows, int CCols>\nEIGEN_STRONG_INLINE\nconst typename ConstFixedBlockXpr<CRows,CCols>::Type bottomLeftCorner(Index cRows, Index cCols) const\n{\n  return typename ConstFixedBlockXpr<CRows,CCols>::Type(derived(), rows() - cRows, 0, cRows, cCols);\n}\n\n\n\n/// \\returns a block consisting of the top rows of \\c *this.\n///\n/// \\param n the number of rows in the block\n/// \\tparam NRowsType the type of the value handling the number of rows in the block, typically Index.\n///\n/// Example: \\include MatrixBase_topRows_int.cpp\n/// Output: \\verbinclude MatrixBase_topRows_int.out\n///\n/// The number of rows \\a n can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments.\n/// See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<typename NRowsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename NRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n#else\ntypename NRowsBlockXpr<...>::Type\n#endif\ntopRows(NRowsType n)\n{\n  return typename NRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n            (derived(), 0, 0, internal::get_runtime_value(n), cols());\n}\n\n/// This is the const version of topRows(NRowsType).\ntemplate<typename NRowsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstNRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n#else\nconst typename ConstNRowsBlockXpr<...>::Type\n#endif\ntopRows(NRowsType n) const\n{\n  return typename ConstNRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n            (derived(), 0, 0, internal::get_runtime_value(n), cols());\n}\n\n/// \\returns a block consisting of the top rows of \\c *this.\n///\n/// \\tparam N the number of rows in the block as specified at compile-time\n/// \\param n the number of rows in the block as specified at run-time\n///\n/// The compile-time and run-time information should not contradict. In other words,\n/// \\a n should equal \\a N unless \\a N is \\a Dynamic.\n///\n/// Example: \\include MatrixBase_template_int_topRows.cpp\n/// Output: \\verbinclude MatrixBase_template_int_topRows.out\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename NRowsBlockXpr<N>::Type topRows(Index n = N)\n{\n  return typename NRowsBlockXpr<N>::Type(derived(), 0, 0, n, cols());\n}\n\n/// This is the const version of topRows<int>().\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename ConstNRowsBlockXpr<N>::Type topRows(Index n = N) const\n{\n  return typename ConstNRowsBlockXpr<N>::Type(derived(), 0, 0, n, cols());\n}\n\n\n\n/// \\returns a block consisting of the bottom rows of \\c *this.\n///\n/// \\param n the number of rows in the block\n/// \\tparam NRowsType the type of the value handling the number of rows in the block, typically Index.\n///\n/// Example: \\include MatrixBase_bottomRows_int.cpp\n/// Output: \\verbinclude MatrixBase_bottomRows_int.out\n///\n/// The number of rows \\a n can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments.\n/// See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<typename NRowsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename NRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n#else\ntypename NRowsBlockXpr<...>::Type\n#endif\nbottomRows(NRowsType n)\n{\n  return typename NRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n            (derived(), rows() - internal::get_runtime_value(n), 0, internal::get_runtime_value(n), cols());\n}\n\n/// This is the const version of bottomRows(NRowsType).\ntemplate<typename NRowsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstNRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n#else\nconst typename ConstNRowsBlockXpr<...>::Type\n#endif\nbottomRows(NRowsType n) const\n{\n  return typename ConstNRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n            (derived(), rows() - internal::get_runtime_value(n), 0, internal::get_runtime_value(n), cols());\n}\n\n/// \\returns a block consisting of the bottom rows of \\c *this.\n///\n/// \\tparam N the number of rows in the block as specified at compile-time\n/// \\param n the number of rows in the block as specified at run-time\n///\n/// The compile-time and run-time information should not contradict. In other words,\n/// \\a n should equal \\a N unless \\a N is \\a Dynamic.\n///\n/// Example: \\include MatrixBase_template_int_bottomRows.cpp\n/// Output: \\verbinclude MatrixBase_template_int_bottomRows.out\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename NRowsBlockXpr<N>::Type bottomRows(Index n = N)\n{\n  return typename NRowsBlockXpr<N>::Type(derived(), rows() - n, 0, n, cols());\n}\n\n/// This is the const version of bottomRows<int>().\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename ConstNRowsBlockXpr<N>::Type bottomRows(Index n = N) const\n{\n  return typename ConstNRowsBlockXpr<N>::Type(derived(), rows() - n, 0, n, cols());\n}\n\n\n\n/// \\returns a block consisting of a range of rows of \\c *this.\n///\n/// \\param startRow the index of the first row in the block\n/// \\param n the number of rows in the block\n/// \\tparam NRowsType the type of the value handling the number of rows in the block, typically Index.\n///\n/// Example: \\include DenseBase_middleRows_int.cpp\n/// Output: \\verbinclude DenseBase_middleRows_int.out\n///\n/// The number of rows \\a n can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments.\n/// See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<typename NRowsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename NRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n#else\ntypename NRowsBlockXpr<...>::Type\n#endif\nmiddleRows(Index startRow, NRowsType n)\n{\n  return typename NRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n            (derived(), startRow, 0, internal::get_runtime_value(n), cols());\n}\n\n/// This is the const version of middleRows(Index,NRowsType).\ntemplate<typename NRowsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstNRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n#else\nconst typename ConstNRowsBlockXpr<...>::Type\n#endif\nmiddleRows(Index startRow, NRowsType n) const\n{\n  return typename ConstNRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n            (derived(), startRow, 0, internal::get_runtime_value(n), cols());\n}\n\n/// \\returns a block consisting of a range of rows of \\c *this.\n///\n/// \\tparam N the number of rows in the block as specified at compile-time\n/// \\param startRow the index of the first row in the block\n/// \\param n the number of rows in the block as specified at run-time\n///\n/// The compile-time and run-time information should not contradict. In other words,\n/// \\a n should equal \\a N unless \\a N is \\a Dynamic.\n///\n/// Example: \\include DenseBase_template_int_middleRows.cpp\n/// Output: \\verbinclude DenseBase_template_int_middleRows.out\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename NRowsBlockXpr<N>::Type middleRows(Index startRow, Index n = N)\n{\n  return typename NRowsBlockXpr<N>::Type(derived(), startRow, 0, n, cols());\n}\n\n/// This is the const version of middleRows<int>().\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename ConstNRowsBlockXpr<N>::Type middleRows(Index startRow, Index n = N) const\n{\n  return typename ConstNRowsBlockXpr<N>::Type(derived(), startRow, 0, n, cols());\n}\n\n\n\n/// \\returns a block consisting of the left columns of \\c *this.\n///\n/// \\param n the number of columns in the block\n/// \\tparam NColsType the type of the value handling the number of columns in the block, typically Index.\n///\n/// Example: \\include MatrixBase_leftCols_int.cpp\n/// Output: \\verbinclude MatrixBase_leftCols_int.out\n///\n/// The number of columns \\a n can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments.\n/// See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename NColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n#else\ntypename NColsBlockXpr<...>::Type\n#endif\nleftCols(NColsType n)\n{\n  return typename NColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), 0, 0, rows(), internal::get_runtime_value(n));\n}\n\n/// This is the const version of leftCols(NColsType).\ntemplate<typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstNColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n#else\nconst typename ConstNColsBlockXpr<...>::Type\n#endif\nleftCols(NColsType n) const\n{\n  return typename ConstNColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), 0, 0, rows(), internal::get_runtime_value(n));\n}\n\n/// \\returns a block consisting of the left columns of \\c *this.\n///\n/// \\tparam N the number of columns in the block as specified at compile-time\n/// \\param n the number of columns in the block as specified at run-time\n///\n/// The compile-time and run-time information should not contradict. In other words,\n/// \\a n should equal \\a N unless \\a N is \\a Dynamic.\n///\n/// Example: \\include MatrixBase_template_int_leftCols.cpp\n/// Output: \\verbinclude MatrixBase_template_int_leftCols.out\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename NColsBlockXpr<N>::Type leftCols(Index n = N)\n{\n  return typename NColsBlockXpr<N>::Type(derived(), 0, 0, rows(), n);\n}\n\n/// This is the const version of leftCols<int>().\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename ConstNColsBlockXpr<N>::Type leftCols(Index n = N) const\n{\n  return typename ConstNColsBlockXpr<N>::Type(derived(), 0, 0, rows(), n);\n}\n\n\n\n/// \\returns a block consisting of the right columns of \\c *this.\n///\n/// \\param n the number of columns in the block\n/// \\tparam NColsType the type of the value handling the number of columns in the block, typically Index.\n///\n/// Example: \\include MatrixBase_rightCols_int.cpp\n/// Output: \\verbinclude MatrixBase_rightCols_int.out\n///\n/// The number of columns \\a n can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments.\n/// See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename NColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n#else\ntypename NColsBlockXpr<...>::Type\n#endif\nrightCols(NColsType n)\n{\n  return typename NColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), 0, cols() - internal::get_runtime_value(n), rows(), internal::get_runtime_value(n));\n}\n\n/// This is the const version of rightCols(NColsType).\ntemplate<typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstNColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n#else\nconst typename ConstNColsBlockXpr<...>::Type\n#endif\nrightCols(NColsType n) const\n{\n  return typename ConstNColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), 0, cols() - internal::get_runtime_value(n), rows(), internal::get_runtime_value(n));\n}\n\n/// \\returns a block consisting of the right columns of \\c *this.\n///\n/// \\tparam N the number of columns in the block as specified at compile-time\n/// \\param n the number of columns in the block as specified at run-time\n///\n/// The compile-time and run-time information should not contradict. In other words,\n/// \\a n should equal \\a N unless \\a N is \\a Dynamic.\n///\n/// Example: \\include MatrixBase_template_int_rightCols.cpp\n/// Output: \\verbinclude MatrixBase_template_int_rightCols.out\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename NColsBlockXpr<N>::Type rightCols(Index n = N)\n{\n  return typename NColsBlockXpr<N>::Type(derived(), 0, cols() - n, rows(), n);\n}\n\n/// This is the const version of rightCols<int>().\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename ConstNColsBlockXpr<N>::Type rightCols(Index n = N) const\n{\n  return typename ConstNColsBlockXpr<N>::Type(derived(), 0, cols() - n, rows(), n);\n}\n\n\n\n/// \\returns a block consisting of a range of columns of \\c *this.\n///\n/// \\param startCol the index of the first column in the block\n/// \\param numCols the number of columns in the block\n/// \\tparam NColsType the type of the value handling the number of columns in the block, typically Index.\n///\n/// Example: \\include DenseBase_middleCols_int.cpp\n/// Output: \\verbinclude DenseBase_middleCols_int.out\n///\n/// The number of columns \\a n can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments.\n/// See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename NColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n#else\ntypename NColsBlockXpr<...>::Type\n#endif\nmiddleCols(Index startCol, NColsType numCols)\n{\n  return typename NColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), 0, startCol, rows(), internal::get_runtime_value(numCols));\n}\n\n/// This is the const version of middleCols(Index,NColsType).\ntemplate<typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstNColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n#else\nconst typename ConstNColsBlockXpr<...>::Type\n#endif\nmiddleCols(Index startCol, NColsType numCols) const\n{\n  return typename ConstNColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), 0, startCol, rows(), internal::get_runtime_value(numCols));\n}\n\n/// \\returns a block consisting of a range of columns of \\c *this.\n///\n/// \\tparam N the number of columns in the block as specified at compile-time\n/// \\param startCol the index of the first column in the block\n/// \\param n the number of columns in the block as specified at run-time\n///\n/// The compile-time and run-time information should not contradict. In other words,\n/// \\a n should equal \\a N unless \\a N is \\a Dynamic.\n///\n/// Example: \\include DenseBase_template_int_middleCols.cpp\n/// Output: \\verbinclude DenseBase_template_int_middleCols.out\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename NColsBlockXpr<N>::Type middleCols(Index startCol, Index n = N)\n{\n  return typename NColsBlockXpr<N>::Type(derived(), 0, startCol, rows(), n);\n}\n\n/// This is the const version of middleCols<int>().\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename ConstNColsBlockXpr<N>::Type middleCols(Index startCol, Index n = N) const\n{\n  return typename ConstNColsBlockXpr<N>::Type(derived(), 0, startCol, rows(), n);\n}\n\n\n\n/// \\returns a fixed-size expression of a block of \\c *this.\n///\n/// The template parameters \\a NRows and \\a NCols are the number of\n/// rows and columns in the block.\n///\n/// \\param startRow the first row in the block\n/// \\param startCol the first column in the block\n///\n/// Example: \\include MatrixBase_block_int_int.cpp\n/// Output: \\verbinclude MatrixBase_block_int_int.out\n///\n/// \\note The usage of of this overload is discouraged from %Eigen 3.4, better used the generic\n/// block(Index,Index,NRowsType,NColsType), here is the one-to-one equivalence:\n/// \\code\n/// mat.template block<NRows,NCols>(i,j)  <-->  mat.block(i,j,fix<NRows>,fix<NCols>)\n/// \\endcode\n///\n/// \\note since block is a templated member, the keyword template has to be used\n/// if the matrix type is also a template parameter: \\code m.template block<3,3>(1,1); \\endcode\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int NRows, int NCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedBlockXpr<NRows,NCols>::Type block(Index startRow, Index startCol)\n{\n  return typename FixedBlockXpr<NRows,NCols>::Type(derived(), startRow, startCol);\n}\n\n/// This is the const version of block<>(Index, Index). */\ntemplate<int NRows, int NCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst typename ConstFixedBlockXpr<NRows,NCols>::Type block(Index startRow, Index startCol) const\n{\n  return typename ConstFixedBlockXpr<NRows,NCols>::Type(derived(), startRow, startCol);\n}\n\n/// \\returns an expression of a block of \\c *this.\n///\n/// \\tparam NRows number of rows in block as specified at compile-time\n/// \\tparam NCols number of columns in block as specified at compile-time\n/// \\param  startRow  the first row in the block\n/// \\param  startCol  the first column in the block\n/// \\param  blockRows number of rows in block as specified at run-time\n/// \\param  blockCols number of columns in block as specified at run-time\n///\n/// This function is mainly useful for blocks where the number of rows is specified at compile-time\n/// and the number of columns is specified at run-time, or vice versa. The compile-time and run-time\n/// information should not contradict. In other words, \\a blockRows should equal \\a NRows unless\n/// \\a NRows is \\a Dynamic, and the same for the number of columns.\n///\n/// Example: \\include MatrixBase_template_int_int_block_int_int_int_int.cpp\n/// Output: \\verbinclude MatrixBase_template_int_int_block_int_int_int_int.out\n///\n/// \\note The usage of of this overload is discouraged from %Eigen 3.4, better used the generic\n/// block(Index,Index,NRowsType,NColsType), here is the one-to-one complete equivalence:\n/// \\code\n/// mat.template block<NRows,NCols>(i,j,rows,cols)     <-->  mat.block(i,j,fix<NRows>(rows),fix<NCols>(cols))\n/// \\endcode\n/// If we known that, e.g., NRows==Dynamic and NCols!=Dynamic, then the equivalence becomes:\n/// \\code\n/// mat.template block<Dynamic,NCols>(i,j,rows,NCols)  <-->  mat.block(i,j,rows,fix<NCols>)\n/// \\endcode\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int NRows, int NCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedBlockXpr<NRows,NCols>::Type block(Index startRow, Index startCol,\n                                                  Index blockRows, Index blockCols)\n{\n  return typename FixedBlockXpr<NRows,NCols>::Type(derived(), startRow, startCol, blockRows, blockCols);\n}\n\n/// This is the const version of block<>(Index, Index, Index, Index).\ntemplate<int NRows, int NCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst typename ConstFixedBlockXpr<NRows,NCols>::Type block(Index startRow, Index startCol,\n                                                              Index blockRows, Index blockCols) const\n{\n  return typename ConstFixedBlockXpr<NRows,NCols>::Type(derived(), startRow, startCol, blockRows, blockCols);\n}\n\n/// \\returns an expression of the \\a i-th column of \\c *this. Note that the numbering starts at 0.\n///\n/// Example: \\include MatrixBase_col.cpp\n/// Output: \\verbinclude MatrixBase_col.out\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major)\n/**\n  * \\sa row(), class Block */\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nColXpr col(Index i)\n{\n  return ColXpr(derived(), i);\n}\n\n/// This is the const version of col().\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nConstColXpr col(Index i) const\n{\n  return ConstColXpr(derived(), i);\n}\n\n/// \\returns an expression of the \\a i-th row of \\c *this. Note that the numbering starts at 0.\n///\n/// Example: \\include MatrixBase_row.cpp\n/// Output: \\verbinclude MatrixBase_row.out\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major)\n/**\n  * \\sa col(), class Block */\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nRowXpr row(Index i)\n{\n  return RowXpr(derived(), i);\n}\n\n/// This is the const version of row(). */\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nConstRowXpr row(Index i) const\n{\n  return ConstRowXpr(derived(), i);\n}\n\n/// \\returns an expression of a segment (i.e. a vector block) in \\c *this with either dynamic or fixed sizes.\n///\n/// \\only_for_vectors\n///\n/// \\param start the first coefficient in the segment\n/// \\param n the number of coefficients in the segment\n/// \\tparam NType the type of the value handling the number of coefficients in the segment, typically Index.\n///\n/// Example: \\include MatrixBase_segment_int_int.cpp\n/// Output: \\verbinclude MatrixBase_segment_int_int.out\n///\n/// The number of coefficients \\a n can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments.\n/// See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\n/// \\note Even in the case that the returned expression has dynamic size, in the case\n/// when it is applied to a fixed-size vector, it inherits a fixed maximal size,\n/// which means that evaluating it does not cause a dynamic memory allocation.\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), fix<N>, fix<N>(int), class Block\n///\ntemplate<typename NType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename FixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n#else\ntypename FixedSegmentReturnType<...>::Type\n#endif\nsegment(Index start, NType n)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename FixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n            (derived(), start, internal::get_runtime_value(n));\n}\n\n\n/// This is the const version of segment(Index,NType).\ntemplate<typename NType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstFixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n#else\nconst typename ConstFixedSegmentReturnType<...>::Type\n#endif\nsegment(Index start, NType n) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename ConstFixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n            (derived(), start, internal::get_runtime_value(n));\n}\n\n/// \\returns an expression of the first coefficients of \\c *this with either dynamic or fixed sizes.\n///\n/// \\only_for_vectors\n///\n/// \\param n the number of coefficients in the segment\n/// \\tparam NType the type of the value handling the number of coefficients in the segment, typically Index.\n///\n/// Example: \\include MatrixBase_start_int.cpp\n/// Output: \\verbinclude MatrixBase_start_int.out\n///\n/// The number of coefficients \\a n can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments.\n/// See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\n/// \\note Even in the case that the returned expression has dynamic size, in the case\n/// when it is applied to a fixed-size vector, it inherits a fixed maximal size,\n/// which means that evaluating it does not cause a dynamic memory allocation.\n///\n/// \\sa class Block, block(Index,Index)\n///\ntemplate<typename NType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename FixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n#else\ntypename FixedSegmentReturnType<...>::Type\n#endif\nhead(NType n)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename FixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n              (derived(), 0, internal::get_runtime_value(n));\n}\n\n/// This is the const version of head(NType).\ntemplate<typename NType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstFixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n#else\nconst typename ConstFixedSegmentReturnType<...>::Type\n#endif\nhead(NType n) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename ConstFixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n            (derived(), 0, internal::get_runtime_value(n));\n}\n\n/// \\returns an expression of a last coefficients of \\c *this with either dynamic or fixed sizes.\n///\n/// \\only_for_vectors\n///\n/// \\param n the number of coefficients in the segment\n/// \\tparam NType the type of the value handling the number of coefficients in the segment, typically Index.\n///\n/// Example: \\include MatrixBase_end_int.cpp\n/// Output: \\verbinclude MatrixBase_end_int.out\n///\n/// The number of coefficients \\a n can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments.\n/// See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\n/// \\note Even in the case that the returned expression has dynamic size, in the case\n/// when it is applied to a fixed-size vector, it inherits a fixed maximal size,\n/// which means that evaluating it does not cause a dynamic memory allocation.\n///\n/// \\sa class Block, block(Index,Index)\n///\ntemplate<typename NType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename FixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n#else\ntypename FixedSegmentReturnType<...>::Type\n#endif\ntail(NType n)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename FixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n            (derived(), this->size() - internal::get_runtime_value(n), internal::get_runtime_value(n));\n}\n\n/// This is the const version of tail(Index).\ntemplate<typename NType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstFixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n#else\nconst typename ConstFixedSegmentReturnType<...>::Type\n#endif\ntail(NType n) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename ConstFixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n            (derived(), this->size() - internal::get_runtime_value(n), internal::get_runtime_value(n));\n}\n\n/// \\returns a fixed-size expression of a segment (i.e. a vector block) in \\c *this\n///\n/// \\only_for_vectors\n///\n/// \\tparam N the number of coefficients in the segment as specified at compile-time\n/// \\param start the index of the first element in the segment\n/// \\param n the number of coefficients in the segment as specified at compile-time\n///\n/// The compile-time and run-time information should not contradict. In other words,\n/// \\a n should equal \\a N unless \\a N is \\a Dynamic.\n///\n/// Example: \\include MatrixBase_template_int_segment.cpp\n/// Output: \\verbinclude MatrixBase_template_int_segment.out\n///\n/// \\sa segment(Index,NType), class Block\n///\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedSegmentReturnType<N>::Type segment(Index start, Index n = N)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename FixedSegmentReturnType<N>::Type(derived(), start, n);\n}\n\n/// This is the const version of segment<int>(Index).\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename ConstFixedSegmentReturnType<N>::Type segment(Index start, Index n = N) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename ConstFixedSegmentReturnType<N>::Type(derived(), start, n);\n}\n\n/// \\returns a fixed-size expression of the first coefficients of \\c *this.\n///\n/// \\only_for_vectors\n///\n/// \\tparam N the number of coefficients in the segment as specified at compile-time\n/// \\param  n the number of coefficients in the segment as specified at run-time\n///\n/// The compile-time and run-time information should not contradict. In other words,\n/// \\a n should equal \\a N unless \\a N is \\a Dynamic.\n///\n/// Example: \\include MatrixBase_template_int_start.cpp\n/// Output: \\verbinclude MatrixBase_template_int_start.out\n///\n/// \\sa head(NType), class Block\n///\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedSegmentReturnType<N>::Type head(Index n = N)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename FixedSegmentReturnType<N>::Type(derived(), 0, n);\n}\n\n/// This is the const version of head<int>().\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename ConstFixedSegmentReturnType<N>::Type head(Index n = N) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename ConstFixedSegmentReturnType<N>::Type(derived(), 0, n);\n}\n\n/// \\returns a fixed-size expression of the last coefficients of \\c *this.\n///\n/// \\only_for_vectors\n///\n/// \\tparam N the number of coefficients in the segment as specified at compile-time\n/// \\param  n the number of coefficients in the segment as specified at run-time\n///\n/// The compile-time and run-time information should not contradict. In other words,\n/// \\a n should equal \\a N unless \\a N is \\a Dynamic.\n///\n/// Example: \\include MatrixBase_template_int_end.cpp\n/// Output: \\verbinclude MatrixBase_template_int_end.out\n///\n/// \\sa tail(NType), class Block\n///\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedSegmentReturnType<N>::Type tail(Index n = N)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename FixedSegmentReturnType<N>::Type(derived(), size() - n);\n}\n\n/// This is the const version of tail<int>.\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename ConstFixedSegmentReturnType<N>::Type tail(Index n = N) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename ConstFixedSegmentReturnType<N>::Type(derived(), size() - n);\n}\n\n/// \\returns the \\a outer -th column (resp. row) of the matrix \\c *this if \\c *this\n/// is col-major (resp. row-major).\n///\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nInnerVectorReturnType innerVector(Index outer)\n{ return InnerVectorReturnType(derived(), outer); }\n\n/// \\returns the \\a outer -th column (resp. row) of the matrix \\c *this if \\c *this\n/// is col-major (resp. row-major). Read-only.\n///\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst ConstInnerVectorReturnType innerVector(Index outer) const\n{ return ConstInnerVectorReturnType(derived(), outer); }\n\n/// \\returns the \\a outer -th column (resp. row) of the matrix \\c *this if \\c *this\n/// is col-major (resp. row-major).\n///\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nInnerVectorsReturnType\ninnerVectors(Index outerStart, Index outerSize)\n{\n  return Block<Derived,Dynamic,Dynamic,true>(derived(),\n                                             IsRowMajor ? outerStart : 0, IsRowMajor ? 0 : outerStart,\n                                             IsRowMajor ? outerSize : rows(), IsRowMajor ? cols() : outerSize);\n\n}\n\n/// \\returns the \\a outer -th column (resp. row) of the matrix \\c *this if \\c *this\n/// is col-major (resp. row-major). Read-only.\n///\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst ConstInnerVectorsReturnType\ninnerVectors(Index outerStart, Index outerSize) const\n{\n  return Block<const Derived,Dynamic,Dynamic,true>(derived(),\n                                                  IsRowMajor ? outerStart : 0, IsRowMajor ? 0 : outerStart,\n                                                  IsRowMajor ? outerSize : rows(), IsRowMajor ? cols() : outerSize);\n\n}\n\n/** \\returns the i-th subvector (column or vector) according to the \\c Direction\n  * \\sa subVectors()\n  */\ntemplate<DirectionType Direction>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename internal::conditional<Direction==Vertical,ColXpr,RowXpr>::type\nsubVector(Index i)\n{\n  return typename internal::conditional<Direction==Vertical,ColXpr,RowXpr>::type(derived(),i);\n}\n\n/** This is the const version of subVector(Index) */\ntemplate<DirectionType Direction>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename internal::conditional<Direction==Vertical,ConstColXpr,ConstRowXpr>::type\nsubVector(Index i) const\n{\n  return typename internal::conditional<Direction==Vertical,ConstColXpr,ConstRowXpr>::type(derived(),i);\n}\n\n/** \\returns the number of subvectors (rows or columns) in the direction \\c Direction\n  * \\sa subVector(Index)\n  */\ntemplate<DirectionType Direction>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EIGEN_CONSTEXPR\nIndex subVectors() const\n{ return (Direction==Vertical)?cols():rows(); }\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/plugins/CommonCwiseBinaryOps.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// This file is a base class plugin containing common coefficient wise functions.\n\n/** \\returns an expression of the difference of \\c *this and \\a other\n  *\n  * \\note If you want to substract a given scalar from all coefficients, see Cwise::operator-().\n  *\n  * \\sa class CwiseBinaryOp, operator-=()\n  */\nEIGEN_MAKE_CWISE_BINARY_OP(operator-,difference)\n\n/** \\returns an expression of the sum of \\c *this and \\a other\n  *\n  * \\note If you want to add a given scalar to all coefficients, see Cwise::operator+().\n  *\n  * \\sa class CwiseBinaryOp, operator+=()\n  */\nEIGEN_MAKE_CWISE_BINARY_OP(operator+,sum)\n\n/** \\returns an expression of a custom coefficient-wise operator \\a func of *this and \\a other\n  *\n  * The template parameter \\a CustomBinaryOp is the type of the functor\n  * of the custom operator (see class CwiseBinaryOp for an example)\n  *\n  * Here is an example illustrating the use of custom functors:\n  * \\include class_CwiseBinaryOp.cpp\n  * Output: \\verbinclude class_CwiseBinaryOp.out\n  *\n  * \\sa class CwiseBinaryOp, operator+(), operator-(), cwiseProduct()\n  */\ntemplate<typename CustomBinaryOp, typename OtherDerived>\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseBinaryOp<CustomBinaryOp, const Derived, const OtherDerived>\nbinaryExpr(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other, const CustomBinaryOp& func = CustomBinaryOp()) const\n{\n  return CwiseBinaryOp<CustomBinaryOp, const Derived, const OtherDerived>(derived(), other.derived(), func);\n}\n\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nEIGEN_MAKE_SCALAR_BINARY_OP(operator*,product)\n#else\n/** \\returns an expression of \\c *this scaled by the scalar factor \\a scalar\n  *\n  * \\tparam T is the scalar type of \\a scalar. It must be compatible with the scalar type of the given expression.\n  */\ntemplate<typename T>\nconst CwiseBinaryOp<internal::scalar_product_op<Scalar,T>,Derived,Constant<T> > operator*(const T& scalar) const;\n/** \\returns an expression of \\a expr scaled by the scalar factor \\a scalar\n  *\n  * \\tparam T is the scalar type of \\a scalar. It must be compatible with the scalar type of the given expression.\n  */\ntemplate<typename T> friend\nconst CwiseBinaryOp<internal::scalar_product_op<T,Scalar>,Constant<T>,Derived> operator*(const T& scalar, const StorageBaseType& expr);\n#endif\n\n\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nEIGEN_MAKE_SCALAR_BINARY_OP_ONTHERIGHT(operator/,quotient)\n#else\n/** \\returns an expression of \\c *this divided by the scalar value \\a scalar\n  *\n  * \\tparam T is the scalar type of \\a scalar. It must be compatible with the scalar type of the given expression.\n  */\ntemplate<typename T>\nconst CwiseBinaryOp<internal::scalar_quotient_op<Scalar,T>,Derived,Constant<T> > operator/(const T& scalar) const;\n#endif\n\n/** \\returns an expression of the coefficient-wise boolean \\b and operator of \\c *this and \\a other\n  *\n  * \\warning this operator is for expression of bool only.\n  *\n  * Example: \\include Cwise_boolean_and.cpp\n  * Output: \\verbinclude Cwise_boolean_and.out\n  *\n  * \\sa operator||(), select()\n  */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\ninline const CwiseBinaryOp<internal::scalar_boolean_and_op, const Derived, const OtherDerived>\noperator&&(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  EIGEN_STATIC_ASSERT((internal::is_same<bool,Scalar>::value && internal::is_same<bool,typename OtherDerived::Scalar>::value),\n                      THIS_METHOD_IS_ONLY_FOR_EXPRESSIONS_OF_BOOL);\n  return CwiseBinaryOp<internal::scalar_boolean_and_op, const Derived, const OtherDerived>(derived(),other.derived());\n}\n\n/** \\returns an expression of the coefficient-wise boolean \\b or operator of \\c *this and \\a other\n  *\n  * \\warning this operator is for expression of bool only.\n  *\n  * Example: \\include Cwise_boolean_or.cpp\n  * Output: \\verbinclude Cwise_boolean_or.out\n  *\n  * \\sa operator&&(), select()\n  */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\ninline const CwiseBinaryOp<internal::scalar_boolean_or_op, const Derived, const OtherDerived>\noperator||(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  EIGEN_STATIC_ASSERT((internal::is_same<bool,Scalar>::value && internal::is_same<bool,typename OtherDerived::Scalar>::value),\n                      THIS_METHOD_IS_ONLY_FOR_EXPRESSIONS_OF_BOOL);\n  return CwiseBinaryOp<internal::scalar_boolean_or_op, const Derived, const OtherDerived>(derived(),other.derived());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/plugins/CommonCwiseUnaryOps.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// This file is a base class plugin containing common coefficient wise functions.\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n\n/** \\internal the return type of conjugate() */\ntypedef typename internal::conditional<NumTraits<Scalar>::IsComplex,\n                    const CwiseUnaryOp<internal::scalar_conjugate_op<Scalar>, const Derived>,\n                    const Derived&\n                  >::type ConjugateReturnType;\n/** \\internal the return type of real() const */\ntypedef typename internal::conditional<NumTraits<Scalar>::IsComplex,\n                    const CwiseUnaryOp<internal::scalar_real_op<Scalar>, const Derived>,\n                    const Derived&\n                  >::type RealReturnType;\n/** \\internal the return type of real() */\ntypedef typename internal::conditional<NumTraits<Scalar>::IsComplex,\n                    CwiseUnaryView<internal::scalar_real_ref_op<Scalar>, Derived>,\n                    Derived&\n                  >::type NonConstRealReturnType;\n/** \\internal the return type of imag() const */\ntypedef CwiseUnaryOp<internal::scalar_imag_op<Scalar>, const Derived> ImagReturnType;\n/** \\internal the return type of imag() */\ntypedef CwiseUnaryView<internal::scalar_imag_ref_op<Scalar>, Derived> NonConstImagReturnType;\n\ntypedef CwiseUnaryOp<internal::scalar_opposite_op<Scalar>, const Derived> NegativeReturnType;\n\n#endif // not EIGEN_PARSED_BY_DOXYGEN\n\n/// \\returns an expression of the opposite of \\c *this\n///\nEIGEN_DOC_UNARY_ADDONS(operator-,opposite)\n///\nEIGEN_DEVICE_FUNC\ninline const NegativeReturnType\noperator-() const { return NegativeReturnType(derived()); }\n\n\ntemplate<class NewType> struct CastXpr { typedef typename internal::cast_return_type<Derived,const CwiseUnaryOp<internal::scalar_cast_op<Scalar, NewType>, const Derived> >::type Type; };\n\n/// \\returns an expression of \\c *this with the \\a Scalar type casted to\n/// \\a NewScalar.\n///\n/// The template parameter \\a NewScalar is the type we are casting the scalars to.\n///\nEIGEN_DOC_UNARY_ADDONS(cast,conversion function)\n///\n/// \\sa class CwiseUnaryOp\n///\ntemplate<typename NewType>\nEIGEN_DEVICE_FUNC\ntypename CastXpr<NewType>::Type\ncast() const\n{\n  return typename CastXpr<NewType>::Type(derived());\n}\n\n/// \\returns an expression of the complex conjugate of \\c *this.\n///\nEIGEN_DOC_UNARY_ADDONS(conjugate,complex conjugate)\n///\n/// \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_conj\">Math functions</a>, MatrixBase::adjoint()\nEIGEN_DEVICE_FUNC\ninline ConjugateReturnType\nconjugate() const\n{\n  return ConjugateReturnType(derived());\n}\n\n/// \\returns an expression of the complex conjugate of \\c *this if Cond==true, returns derived() otherwise.\n///\nEIGEN_DOC_UNARY_ADDONS(conjugate,complex conjugate)\n///\n/// \\sa conjugate()\ntemplate<bool Cond>\nEIGEN_DEVICE_FUNC\ninline typename internal::conditional<Cond,ConjugateReturnType,const Derived&>::type\nconjugateIf() const\n{\n  typedef typename internal::conditional<Cond,ConjugateReturnType,const Derived&>::type ReturnType;\n  return ReturnType(derived());\n}\n\n/// \\returns a read-only expression of the real part of \\c *this.\n///\nEIGEN_DOC_UNARY_ADDONS(real,real part function)\n///\n/// \\sa imag()\nEIGEN_DEVICE_FUNC\ninline RealReturnType\nreal() const { return RealReturnType(derived()); }\n\n/// \\returns an read-only expression of the imaginary part of \\c *this.\n///\nEIGEN_DOC_UNARY_ADDONS(imag,imaginary part function)\n///\n/// \\sa real()\nEIGEN_DEVICE_FUNC\ninline const ImagReturnType\nimag() const { return ImagReturnType(derived()); }\n\n/// \\brief Apply a unary operator coefficient-wise\n/// \\param[in]  func  Functor implementing the unary operator\n/// \\tparam  CustomUnaryOp Type of \\a func\n/// \\returns An expression of a custom coefficient-wise unary operator \\a func of *this\n///\n/// The function \\c ptr_fun() from the C++ standard library can be used to make functors out of normal functions.\n///\n/// Example:\n/// \\include class_CwiseUnaryOp_ptrfun.cpp\n/// Output: \\verbinclude class_CwiseUnaryOp_ptrfun.out\n///\n/// Genuine functors allow for more possibilities, for instance it may contain a state.\n///\n/// Example:\n/// \\include class_CwiseUnaryOp.cpp\n/// Output: \\verbinclude class_CwiseUnaryOp.out\n///\nEIGEN_DOC_UNARY_ADDONS(unaryExpr,unary function)\n///\n/// \\sa unaryViewExpr, binaryExpr, class CwiseUnaryOp\n///\ntemplate<typename CustomUnaryOp>\nEIGEN_DEVICE_FUNC\ninline const CwiseUnaryOp<CustomUnaryOp, const Derived>\nunaryExpr(const CustomUnaryOp& func = CustomUnaryOp()) const\n{\n  return CwiseUnaryOp<CustomUnaryOp, const Derived>(derived(), func);\n}\n\n/// \\returns an expression of a custom coefficient-wise unary operator \\a func of *this\n///\n/// The template parameter \\a CustomUnaryOp is the type of the functor\n/// of the custom unary operator.\n///\n/// Example:\n/// \\include class_CwiseUnaryOp.cpp\n/// Output: \\verbinclude class_CwiseUnaryOp.out\n///\nEIGEN_DOC_UNARY_ADDONS(unaryViewExpr,unary function)\n///\n/// \\sa unaryExpr, binaryExpr class CwiseUnaryOp\n///\ntemplate<typename CustomViewOp>\nEIGEN_DEVICE_FUNC\ninline const CwiseUnaryView<CustomViewOp, const Derived>\nunaryViewExpr(const CustomViewOp& func = CustomViewOp()) const\n{\n  return CwiseUnaryView<CustomViewOp, const Derived>(derived(), func);\n}\n\n/// \\returns a non const expression of the real part of \\c *this.\n///\nEIGEN_DOC_UNARY_ADDONS(real,real part function)\n///\n/// \\sa imag()\nEIGEN_DEVICE_FUNC\ninline NonConstRealReturnType\nreal() { return NonConstRealReturnType(derived()); }\n\n/// \\returns a non const expression of the imaginary part of \\c *this.\n///\nEIGEN_DOC_UNARY_ADDONS(imag,imaginary part function)\n///\n/// \\sa real()\nEIGEN_DEVICE_FUNC\ninline NonConstImagReturnType\nimag() { return NonConstImagReturnType(derived()); }\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/plugins/IndexedViewMethods.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2017 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#if !defined(EIGEN_PARSED_BY_DOXYGEN)\n\n// This file is automatically included twice to generate const and non-const versions\n\n#ifndef EIGEN_INDEXED_VIEW_METHOD_2ND_PASS\n#define EIGEN_INDEXED_VIEW_METHOD_CONST const\n#define EIGEN_INDEXED_VIEW_METHOD_TYPE  ConstIndexedViewType\n#else\n#define EIGEN_INDEXED_VIEW_METHOD_CONST\n#define EIGEN_INDEXED_VIEW_METHOD_TYPE IndexedViewType\n#endif\n\n#ifndef EIGEN_INDEXED_VIEW_METHOD_2ND_PASS\nprotected:\n\n// define some aliases to ease readability\n\ntemplate<typename Indices>\nstruct IvcRowType : public internal::IndexedViewCompatibleType<Indices,RowsAtCompileTime> {};\n\ntemplate<typename Indices>\nstruct IvcColType : public internal::IndexedViewCompatibleType<Indices,ColsAtCompileTime> {};\n\ntemplate<typename Indices>\nstruct IvcType : public internal::IndexedViewCompatibleType<Indices,SizeAtCompileTime> {};\n\ntypedef typename internal::IndexedViewCompatibleType<Index,1>::type IvcIndex;\n\ntemplate<typename Indices>\ntypename IvcRowType<Indices>::type\nivcRow(const Indices& indices) const {\n  return internal::makeIndexedViewCompatible(indices, internal::variable_if_dynamic<Index,RowsAtCompileTime>(derived().rows()),Specialized);\n}\n\ntemplate<typename Indices>\ntypename IvcColType<Indices>::type\nivcCol(const Indices& indices) const {\n  return internal::makeIndexedViewCompatible(indices, internal::variable_if_dynamic<Index,ColsAtCompileTime>(derived().cols()),Specialized);\n}\n\ntemplate<typename Indices>\ntypename IvcColType<Indices>::type\nivcSize(const Indices& indices) const {\n  return internal::makeIndexedViewCompatible(indices, internal::variable_if_dynamic<Index,SizeAtCompileTime>(derived().size()),Specialized);\n}\n\npublic:\n\n#endif\n\ntemplate<typename RowIndices, typename ColIndices>\nstruct EIGEN_INDEXED_VIEW_METHOD_TYPE {\n  typedef IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,\n                      typename IvcRowType<RowIndices>::type,\n                      typename IvcColType<ColIndices>::type> type;\n};\n\n// This is the generic version\n\ntemplate<typename RowIndices, typename ColIndices>\ntypename internal::enable_if<internal::valid_indexed_view_overload<RowIndices,ColIndices>::value\n  && internal::traits<typename EIGEN_INDEXED_VIEW_METHOD_TYPE<RowIndices,ColIndices>::type>::ReturnAsIndexedView,\n  typename EIGEN_INDEXED_VIEW_METHOD_TYPE<RowIndices,ColIndices>::type >::type\noperator()(const RowIndices& rowIndices, const ColIndices& colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  return typename EIGEN_INDEXED_VIEW_METHOD_TYPE<RowIndices,ColIndices>::type\n            (derived(), ivcRow(rowIndices), ivcCol(colIndices));\n}\n\n// The following overload returns a Block<> object\n\ntemplate<typename RowIndices, typename ColIndices>\ntypename internal::enable_if<internal::valid_indexed_view_overload<RowIndices,ColIndices>::value\n  && internal::traits<typename EIGEN_INDEXED_VIEW_METHOD_TYPE<RowIndices,ColIndices>::type>::ReturnAsBlock,\n  typename internal::traits<typename EIGEN_INDEXED_VIEW_METHOD_TYPE<RowIndices,ColIndices>::type>::BlockType>::type\noperator()(const RowIndices& rowIndices, const ColIndices& colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  typedef typename internal::traits<typename EIGEN_INDEXED_VIEW_METHOD_TYPE<RowIndices,ColIndices>::type>::BlockType BlockType;\n  typename IvcRowType<RowIndices>::type actualRowIndices = ivcRow(rowIndices);\n  typename IvcColType<ColIndices>::type actualColIndices = ivcCol(colIndices);\n  return BlockType(derived(),\n                   internal::first(actualRowIndices),\n                   internal::first(actualColIndices),\n                   internal::size(actualRowIndices),\n                   internal::size(actualColIndices));\n}\n\n// The following overload returns a Scalar\n\ntemplate<typename RowIndices, typename ColIndices>\ntypename internal::enable_if<internal::valid_indexed_view_overload<RowIndices,ColIndices>::value\n  && internal::traits<typename EIGEN_INDEXED_VIEW_METHOD_TYPE<RowIndices,ColIndices>::type>::ReturnAsScalar,\n  CoeffReturnType >::type\noperator()(const RowIndices& rowIndices, const ColIndices& colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  return Base::operator()(internal::eval_expr_given_size(rowIndices,rows()),internal::eval_expr_given_size(colIndices,cols()));\n}\n\n#if EIGEN_HAS_STATIC_ARRAY_TEMPLATE\n\n// The following three overloads are needed to handle raw Index[N] arrays.\n\ntemplate<typename RowIndicesT, std::size_t RowIndicesN, typename ColIndices>\nIndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,const RowIndicesT (&)[RowIndicesN],typename IvcColType<ColIndices>::type>\noperator()(const RowIndicesT (&rowIndices)[RowIndicesN], const ColIndices& colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  return IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,const RowIndicesT (&)[RowIndicesN],typename IvcColType<ColIndices>::type>\n                    (derived(), rowIndices, ivcCol(colIndices));\n}\n\ntemplate<typename RowIndices, typename ColIndicesT, std::size_t ColIndicesN>\nIndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,typename IvcRowType<RowIndices>::type, const ColIndicesT (&)[ColIndicesN]>\noperator()(const RowIndices& rowIndices, const ColIndicesT (&colIndices)[ColIndicesN]) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  return IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,typename IvcRowType<RowIndices>::type,const ColIndicesT (&)[ColIndicesN]>\n                    (derived(), ivcRow(rowIndices), colIndices);\n}\n\ntemplate<typename RowIndicesT, std::size_t RowIndicesN, typename ColIndicesT, std::size_t ColIndicesN>\nIndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,const RowIndicesT (&)[RowIndicesN], const ColIndicesT (&)[ColIndicesN]>\noperator()(const RowIndicesT (&rowIndices)[RowIndicesN], const ColIndicesT (&colIndices)[ColIndicesN]) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  return IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,const RowIndicesT (&)[RowIndicesN],const ColIndicesT (&)[ColIndicesN]>\n                    (derived(), rowIndices, colIndices);\n}\n\n#endif // EIGEN_HAS_STATIC_ARRAY_TEMPLATE\n\n// Overloads for 1D vectors/arrays\n\ntemplate<typename Indices>\ntypename internal::enable_if<\n  IsRowMajor && (!(internal::get_compile_time_incr<typename IvcType<Indices>::type>::value==1 || internal::is_valid_index_type<Indices>::value)),\n  IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,IvcIndex,typename IvcType<Indices>::type> >::type\noperator()(const Indices& indices) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,IvcIndex,typename IvcType<Indices>::type>\n            (derived(), IvcIndex(0), ivcCol(indices));\n}\n\ntemplate<typename Indices>\ntypename internal::enable_if<\n  (!IsRowMajor) && (!(internal::get_compile_time_incr<typename IvcType<Indices>::type>::value==1 || internal::is_valid_index_type<Indices>::value)),\n  IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,typename IvcType<Indices>::type,IvcIndex> >::type\noperator()(const Indices& indices) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,typename IvcType<Indices>::type,IvcIndex>\n            (derived(), ivcRow(indices), IvcIndex(0));\n}\n\ntemplate<typename Indices>\ntypename internal::enable_if<\n  (internal::get_compile_time_incr<typename IvcType<Indices>::type>::value==1) && (!internal::is_valid_index_type<Indices>::value) && (!symbolic::is_symbolic<Indices>::value),\n  VectorBlock<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,internal::array_size<Indices>::value> >::type\noperator()(const Indices& indices) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  typename IvcType<Indices>::type actualIndices = ivcSize(indices);\n  return VectorBlock<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,internal::array_size<Indices>::value>\n            (derived(), internal::first(actualIndices), internal::size(actualIndices));\n}\n\ntemplate<typename IndexType>\ntypename internal::enable_if<symbolic::is_symbolic<IndexType>::value, CoeffReturnType >::type\noperator()(const IndexType& id) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  return Base::operator()(internal::eval_expr_given_size(id,size()));\n}\n\n#if EIGEN_HAS_STATIC_ARRAY_TEMPLATE\n\ntemplate<typename IndicesT, std::size_t IndicesN>\ntypename internal::enable_if<IsRowMajor,\n  IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,IvcIndex,const IndicesT (&)[IndicesN]> >::type\noperator()(const IndicesT (&indices)[IndicesN]) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,IvcIndex,const IndicesT (&)[IndicesN]>\n            (derived(), IvcIndex(0), indices);\n}\n\ntemplate<typename IndicesT, std::size_t IndicesN>\ntypename internal::enable_if<!IsRowMajor,\n  IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,const IndicesT (&)[IndicesN],IvcIndex> >::type\noperator()(const IndicesT (&indices)[IndicesN]) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,const IndicesT (&)[IndicesN],IvcIndex>\n            (derived(), indices, IvcIndex(0));\n}\n\n#endif // EIGEN_HAS_STATIC_ARRAY_TEMPLATE\n\n#undef EIGEN_INDEXED_VIEW_METHOD_CONST\n#undef EIGEN_INDEXED_VIEW_METHOD_TYPE\n\n#ifndef EIGEN_INDEXED_VIEW_METHOD_2ND_PASS\n#define EIGEN_INDEXED_VIEW_METHOD_2ND_PASS\n#include \"IndexedViewMethods.h\"\n#undef EIGEN_INDEXED_VIEW_METHOD_2ND_PASS\n#endif\n\n#else // EIGEN_PARSED_BY_DOXYGEN\n\n/**\n  * \\returns a generic submatrix view defined by the rows and columns indexed \\a rowIndices and \\a colIndices respectively.\n  *\n  * Each parameter must either be:\n  *  - An integer indexing a single row or column\n  *  - Eigen::all indexing the full set of respective rows or columns in increasing order\n  *  - An ArithmeticSequence as returned by the Eigen::seq and Eigen::seqN functions\n  *  - Any %Eigen's vector/array of integers or expressions\n  *  - Plain C arrays: \\c int[N]\n  *  - And more generally any type exposing the following two member functions:\n  * \\code\n  * <integral type> operator[](<integral type>) const;\n  * <integral type> size() const;\n  * \\endcode\n  * where \\c <integral \\c type>  stands for any integer type compatible with Eigen::Index (i.e. \\c std::ptrdiff_t).\n  *\n  * The last statement implies compatibility with \\c std::vector, \\c std::valarray, \\c std::array, many of the Range-v3's ranges, etc.\n  *\n  * If the submatrix can be represented using a starting position \\c (i,j) and positive sizes \\c (rows,columns), then this\n  * method will returns a Block object after extraction of the relevant information from the passed arguments. This is the case\n  * when all arguments are either:\n  *  - An integer\n  *  - Eigen::all\n  *  - An ArithmeticSequence with compile-time increment strictly equal to 1, as returned by Eigen::seq(a,b), and Eigen::seqN(a,N).\n  *\n  * Otherwise a more general IndexedView<Derived,RowIndices',ColIndices'> object will be returned, after conversion of the inputs\n  * to more suitable types \\c RowIndices' and \\c ColIndices'.\n  *\n  * For 1D vectors and arrays, you better use the operator()(const Indices&) overload, which behave the same way but taking a single parameter.\n  *\n  * See also this <a href=\"https://stackoverflow.com/questions/46110917/eigen-replicate-items-along-one-dimension-without-useless-allocations\">question</a> and its answer for an example of how to duplicate coefficients.\n  *\n  * \\sa operator()(const Indices&), class Block, class IndexedView, DenseBase::block(Index,Index,Index,Index)\n  */\ntemplate<typename RowIndices, typename ColIndices>\nIndexedView_or_Block\noperator()(const RowIndices& rowIndices, const ColIndices& colIndices);\n\n/** This is an overload of operator()(const RowIndices&, const ColIndices&) for 1D vectors or arrays\n  *\n  * \\only_for_vectors\n  */\ntemplate<typename Indices>\nIndexedView_or_VectorBlock\noperator()(const Indices& indices);\n\n#endif  // EIGEN_PARSED_BY_DOXYGEN\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/plugins/MatrixCwiseBinaryOps.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// This file is a base class plugin containing matrix specifics coefficient wise functions.\n\n/** \\returns an expression of the Schur product (coefficient wise product) of *this and \\a other\n  *\n  * Example: \\include MatrixBase_cwiseProduct.cpp\n  * Output: \\verbinclude MatrixBase_cwiseProduct.out\n  *\n  * \\sa class CwiseBinaryOp, cwiseAbs2\n  */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const EIGEN_CWISE_BINARY_RETURN_TYPE(Derived,OtherDerived,product)\ncwiseProduct(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  return EIGEN_CWISE_BINARY_RETURN_TYPE(Derived,OtherDerived,product)(derived(), other.derived());\n}\n\n/** \\returns an expression of the coefficient-wise == operator of *this and \\a other\n  *\n  * \\warning this performs an exact comparison, which is generally a bad idea with floating-point types.\n  * In order to check for equality between two vectors or matrices with floating-point coefficients, it is\n  * generally a far better idea to use a fuzzy comparison as provided by isApprox() and\n  * isMuchSmallerThan().\n  *\n  * Example: \\include MatrixBase_cwiseEqual.cpp\n  * Output: \\verbinclude MatrixBase_cwiseEqual.out\n  *\n  * \\sa cwiseNotEqual(), isApprox(), isMuchSmallerThan()\n  */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\ninline const CwiseBinaryOp<numext::equal_to<Scalar>, const Derived, const OtherDerived>\ncwiseEqual(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  return CwiseBinaryOp<numext::equal_to<Scalar>, const Derived, const OtherDerived>(derived(), other.derived());\n}\n\n/** \\returns an expression of the coefficient-wise != operator of *this and \\a other\n  *\n  * \\warning this performs an exact comparison, which is generally a bad idea with floating-point types.\n  * In order to check for equality between two vectors or matrices with floating-point coefficients, it is\n  * generally a far better idea to use a fuzzy comparison as provided by isApprox() and\n  * isMuchSmallerThan().\n  *\n  * Example: \\include MatrixBase_cwiseNotEqual.cpp\n  * Output: \\verbinclude MatrixBase_cwiseNotEqual.out\n  *\n  * \\sa cwiseEqual(), isApprox(), isMuchSmallerThan()\n  */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\ninline const CwiseBinaryOp<numext::not_equal_to<Scalar>, const Derived, const OtherDerived>\ncwiseNotEqual(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  return CwiseBinaryOp<numext::not_equal_to<Scalar>, const Derived, const OtherDerived>(derived(), other.derived());\n}\n\n/** \\returns an expression of the coefficient-wise min of *this and \\a other\n  *\n  * Example: \\include MatrixBase_cwiseMin.cpp\n  * Output: \\verbinclude MatrixBase_cwiseMin.out\n  *\n  * \\sa class CwiseBinaryOp, max()\n  */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_min_op<Scalar,Scalar>, const Derived, const OtherDerived>\ncwiseMin(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  return CwiseBinaryOp<internal::scalar_min_op<Scalar,Scalar>, const Derived, const OtherDerived>(derived(), other.derived());\n}\n\n/** \\returns an expression of the coefficient-wise min of *this and scalar \\a other\n  *\n  * \\sa class CwiseBinaryOp, min()\n  */\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_min_op<Scalar,Scalar>, const Derived, const ConstantReturnType>\ncwiseMin(const Scalar &other) const\n{\n  return cwiseMin(Derived::Constant(rows(), cols(), other));\n}\n\n/** \\returns an expression of the coefficient-wise max of *this and \\a other\n  *\n  * Example: \\include MatrixBase_cwiseMax.cpp\n  * Output: \\verbinclude MatrixBase_cwiseMax.out\n  *\n  * \\sa class CwiseBinaryOp, min()\n  */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_max_op<Scalar,Scalar>, const Derived, const OtherDerived>\ncwiseMax(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  return CwiseBinaryOp<internal::scalar_max_op<Scalar,Scalar>, const Derived, const OtherDerived>(derived(), other.derived());\n}\n\n/** \\returns an expression of the coefficient-wise max of *this and scalar \\a other\n  *\n  * \\sa class CwiseBinaryOp, min()\n  */\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_max_op<Scalar,Scalar>, const Derived, const ConstantReturnType>\ncwiseMax(const Scalar &other) const\n{\n  return cwiseMax(Derived::Constant(rows(), cols(), other));\n}\n\n\n/** \\returns an expression of the coefficient-wise quotient of *this and \\a other\n  *\n  * Example: \\include MatrixBase_cwiseQuotient.cpp\n  * Output: \\verbinclude MatrixBase_cwiseQuotient.out\n  *\n  * \\sa class CwiseBinaryOp, cwiseProduct(), cwiseInverse()\n  */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_quotient_op<Scalar>, const Derived, const OtherDerived>\ncwiseQuotient(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  return CwiseBinaryOp<internal::scalar_quotient_op<Scalar>, const Derived, const OtherDerived>(derived(), other.derived());\n}\n\ntypedef CwiseBinaryOp<internal::scalar_cmp_op<Scalar,Scalar,internal::cmp_EQ>, const Derived, const ConstantReturnType> CwiseScalarEqualReturnType;\n\n/** \\returns an expression of the coefficient-wise == operator of \\c *this and a scalar \\a s\n  *\n  * \\warning this performs an exact comparison, which is generally a bad idea with floating-point types.\n  * In order to check for equality between two vectors or matrices with floating-point coefficients, it is\n  * generally a far better idea to use a fuzzy comparison as provided by isApprox() and\n  * isMuchSmallerThan().\n  *\n  * \\sa cwiseEqual(const MatrixBase<OtherDerived> &) const\n  */\nEIGEN_DEVICE_FUNC\ninline const CwiseScalarEqualReturnType\ncwiseEqual(const Scalar& s) const\n{\n  return CwiseScalarEqualReturnType(derived(), Derived::Constant(rows(), cols(), s), internal::scalar_cmp_op<Scalar,Scalar,internal::cmp_EQ>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/plugins/MatrixCwiseUnaryOps.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// This file is included into the body of the base classes supporting matrix specific coefficient-wise functions.\n// This include MatrixBase and SparseMatrixBase.\n\n\ntypedef CwiseUnaryOp<internal::scalar_abs_op<Scalar>, const Derived> CwiseAbsReturnType;\ntypedef CwiseUnaryOp<internal::scalar_abs2_op<Scalar>, const Derived> CwiseAbs2ReturnType;\ntypedef CwiseUnaryOp<internal::scalar_arg_op<Scalar>, const Derived> CwiseArgReturnType;\ntypedef CwiseUnaryOp<internal::scalar_sqrt_op<Scalar>, const Derived> CwiseSqrtReturnType;\ntypedef CwiseUnaryOp<internal::scalar_sign_op<Scalar>, const Derived> CwiseSignReturnType;\ntypedef CwiseUnaryOp<internal::scalar_inverse_op<Scalar>, const Derived> CwiseInverseReturnType;\n\n/// \\returns an expression of the coefficient-wise absolute value of \\c *this\n///\n/// Example: \\include MatrixBase_cwiseAbs.cpp\n/// Output: \\verbinclude MatrixBase_cwiseAbs.out\n///\nEIGEN_DOC_UNARY_ADDONS(cwiseAbs,absolute value)\n///\n/// \\sa cwiseAbs2()\n///\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseAbsReturnType\ncwiseAbs() const { return CwiseAbsReturnType(derived()); }\n\n/// \\returns an expression of the coefficient-wise squared absolute value of \\c *this\n///\n/// Example: \\include MatrixBase_cwiseAbs2.cpp\n/// Output: \\verbinclude MatrixBase_cwiseAbs2.out\n///\nEIGEN_DOC_UNARY_ADDONS(cwiseAbs2,squared absolute value)\n///\n/// \\sa cwiseAbs()\n///\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseAbs2ReturnType\ncwiseAbs2() const { return CwiseAbs2ReturnType(derived()); }\n\n/// \\returns an expression of the coefficient-wise square root of *this.\n///\n/// Example: \\include MatrixBase_cwiseSqrt.cpp\n/// Output: \\verbinclude MatrixBase_cwiseSqrt.out\n///\nEIGEN_DOC_UNARY_ADDONS(cwiseSqrt,square-root)\n///\n/// \\sa cwisePow(), cwiseSquare()\n///\nEIGEN_DEVICE_FUNC\ninline const CwiseSqrtReturnType\ncwiseSqrt() const { return CwiseSqrtReturnType(derived()); }\n\n/// \\returns an expression of the coefficient-wise signum of *this.\n///\n/// Example: \\include MatrixBase_cwiseSign.cpp\n/// Output: \\verbinclude MatrixBase_cwiseSign.out\n///\nEIGEN_DOC_UNARY_ADDONS(cwiseSign,sign function)\n///\nEIGEN_DEVICE_FUNC\ninline const CwiseSignReturnType\ncwiseSign() const { return CwiseSignReturnType(derived()); }\n\n\n/// \\returns an expression of the coefficient-wise inverse of *this.\n///\n/// Example: \\include MatrixBase_cwiseInverse.cpp\n/// Output: \\verbinclude MatrixBase_cwiseInverse.out\n///\nEIGEN_DOC_UNARY_ADDONS(cwiseInverse,inverse)\n///\n/// \\sa cwiseProduct()\n///\nEIGEN_DEVICE_FUNC\ninline const CwiseInverseReturnType\ncwiseInverse() const { return CwiseInverseReturnType(derived()); }\n\n/// \\returns an expression of the coefficient-wise phase angle of \\c *this\n///\n/// Example: \\include MatrixBase_cwiseArg.cpp\n/// Output: \\verbinclude MatrixBase_cwiseArg.out\n///\nEIGEN_DOC_UNARY_ADDONS(cwiseArg,arg)\n\nEIGEN_DEVICE_FUNC\ninline const CwiseArgReturnType\ncwiseArg() const { return CwiseArgReturnType(derived()); }\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/Eigen/src/plugins/ReshapedMethods.h",
    "content": "\n#ifdef EIGEN_PARSED_BY_DOXYGEN\n\n/// \\returns an expression of \\c *this with reshaped sizes.\n///\n/// \\param nRows the number of rows in the reshaped expression, specified at either run-time or compile-time, or AutoSize\n/// \\param nCols the number of columns in the reshaped expression, specified at either run-time or compile-time, or AutoSize\n/// \\tparam Order specifies whether the coefficients should be processed in column-major-order (ColMajor), in row-major-order (RowMajor),\n///               or follows the \\em natural order of the nested expression (AutoOrder). The default is ColMajor.\n/// \\tparam NRowsType the type of the value handling the number of rows, typically Index.\n/// \\tparam NColsType the type of the value handling the number of columns, typically Index.\n///\n/// Dynamic size example: \\include MatrixBase_reshaped_int_int.cpp\n/// Output: \\verbinclude MatrixBase_reshaped_int_int.out\n///\n/// The number of rows \\a nRows and columns \\a nCols can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments. In the later case, \\c n plays the role of a runtime fallback value in case \\c N equals Eigen::Dynamic.\n/// Here is an example with a fixed number of rows and columns:\n/// \\include MatrixBase_reshaped_fixed.cpp\n/// Output: \\verbinclude MatrixBase_reshaped_fixed.out\n///\n/// Finally, one of the sizes parameter can be automatically deduced from the other one by passing AutoSize as in the following example:\n/// \\include MatrixBase_reshaped_auto.cpp\n/// Output: \\verbinclude MatrixBase_reshaped_auto.out\n/// AutoSize does preserve compile-time sizes when possible, i.e., when the sizes of the input are known at compile time \\b and\n/// that the other size is passed at compile-time using Eigen::fix<N> as above.\n///\n/// \\sa class Reshaped, fix, fix<N>(int)\n///\ntemplate<int Order = ColMajor, typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC\ninline Reshaped<Derived,...>\nreshaped(NRowsType nRows, NColsType nCols);\n\n/// This is the const version of reshaped(NRowsType,NColsType).\ntemplate<int Order = ColMajor, typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC\ninline const Reshaped<const Derived,...>\nreshaped(NRowsType nRows, NColsType nCols) const;\n\n/// \\returns an expression of \\c *this with columns (or rows) stacked to a linear column vector\n///\n/// \\tparam Order specifies whether the coefficients should be processed in column-major-order (ColMajor), in row-major-order (RowMajor),\n///               or follows the \\em natural order of the nested expression (AutoOrder). The default is ColMajor.\n///\n/// This overloads is essentially a shortcut for `A.reshaped<Order>(AutoSize,fix<1>)`.\n///\n/// - If `Order==ColMajor` (the default), then it returns a column-vector from the stacked columns of \\c *this.\n/// - If `Order==RowMajor`, then it returns a column-vector from the stacked rows of \\c *this.\n/// - If `Order==AutoOrder`, then it returns a column-vector with elements stacked following the storage order of \\c *this.\n///   This mode is the recommended one when the particular ordering of the element is not relevant.\n///\n/// Example:\n/// \\include MatrixBase_reshaped_to_vector.cpp\n/// Output: \\verbinclude MatrixBase_reshaped_to_vector.out\n///\n/// If you want more control, you can still fall back to reshaped(NRowsType,NColsType).\n///\n/// \\sa reshaped(NRowsType,NColsType), class Reshaped\n///\ntemplate<int Order = ColMajor>\nEIGEN_DEVICE_FUNC\ninline Reshaped<Derived,...>\nreshaped();\n\n/// This is the const version of reshaped().\ntemplate<int Order = ColMajor>\nEIGEN_DEVICE_FUNC\ninline const Reshaped<const Derived,...>\nreshaped() const;\n\n#else\n\n// This file is automatically included twice to generate const and non-const versions\n\n#ifndef EIGEN_RESHAPED_METHOD_2ND_PASS\n#define EIGEN_RESHAPED_METHOD_CONST const\n#else\n#define EIGEN_RESHAPED_METHOD_CONST\n#endif\n\n#ifndef EIGEN_RESHAPED_METHOD_2ND_PASS\n\n// This part is included once\n\n#endif\n\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC\ninline Reshaped<EIGEN_RESHAPED_METHOD_CONST Derived,\n                internal::get_compiletime_reshape_size<NRowsType,NColsType,SizeAtCompileTime>::value,\n                internal::get_compiletime_reshape_size<NColsType,NRowsType,SizeAtCompileTime>::value>\nreshaped(NRowsType nRows, NColsType nCols) EIGEN_RESHAPED_METHOD_CONST\n{\n  return Reshaped<EIGEN_RESHAPED_METHOD_CONST Derived,\n                  internal::get_compiletime_reshape_size<NRowsType,NColsType,SizeAtCompileTime>::value,\n                  internal::get_compiletime_reshape_size<NColsType,NRowsType,SizeAtCompileTime>::value>\n                (derived(),\n                 internal::get_runtime_reshape_size(nRows,internal::get_runtime_value(nCols),size()),\n                 internal::get_runtime_reshape_size(nCols,internal::get_runtime_value(nRows),size()));\n}\n\ntemplate<int Order, typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC\ninline Reshaped<EIGEN_RESHAPED_METHOD_CONST Derived,\n                internal::get_compiletime_reshape_size<NRowsType,NColsType,SizeAtCompileTime>::value,\n                internal::get_compiletime_reshape_size<NColsType,NRowsType,SizeAtCompileTime>::value,\n                internal::get_compiletime_reshape_order<Flags,Order>::value>\nreshaped(NRowsType nRows, NColsType nCols) EIGEN_RESHAPED_METHOD_CONST\n{\n  return Reshaped<EIGEN_RESHAPED_METHOD_CONST Derived,\n                  internal::get_compiletime_reshape_size<NRowsType,NColsType,SizeAtCompileTime>::value,\n                  internal::get_compiletime_reshape_size<NColsType,NRowsType,SizeAtCompileTime>::value,\n                  internal::get_compiletime_reshape_order<Flags,Order>::value>\n                (derived(),\n                 internal::get_runtime_reshape_size(nRows,internal::get_runtime_value(nCols),size()),\n                 internal::get_runtime_reshape_size(nCols,internal::get_runtime_value(nRows),size()));\n}\n\n// Views as linear vectors\n\nEIGEN_DEVICE_FUNC\ninline Reshaped<EIGEN_RESHAPED_METHOD_CONST Derived,SizeAtCompileTime,1>\nreshaped() EIGEN_RESHAPED_METHOD_CONST\n{\n  return Reshaped<EIGEN_RESHAPED_METHOD_CONST Derived,SizeAtCompileTime,1>(derived(),size(),1);\n}\n\ntemplate<int Order>\nEIGEN_DEVICE_FUNC\ninline Reshaped<EIGEN_RESHAPED_METHOD_CONST Derived, SizeAtCompileTime, 1,\n                internal::get_compiletime_reshape_order<Flags,Order>::value>\nreshaped() EIGEN_RESHAPED_METHOD_CONST\n{\n  EIGEN_STATIC_ASSERT(Order==RowMajor || Order==ColMajor || Order==AutoOrder, INVALID_TEMPLATE_PARAMETER);\n  return Reshaped<EIGEN_RESHAPED_METHOD_CONST Derived, SizeAtCompileTime, 1,\n                  internal::get_compiletime_reshape_order<Flags,Order>::value>\n                (derived(), size(), 1);\n}\n\n#undef EIGEN_RESHAPED_METHOD_CONST\n\n#ifndef EIGEN_RESHAPED_METHOD_2ND_PASS\n#define EIGEN_RESHAPED_METHOD_2ND_PASS\n#include \"ReshapedMethods.h\"\n#undef EIGEN_RESHAPED_METHOD_2ND_PASS\n#endif\n\n#endif // EIGEN_PARSED_BY_DOXYGEN\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/INSTALL",
    "content": "Installation instructions for Eigen\n***********************************\n\nExplanation before starting\n***************************\n\nEigen consists only of header files, hence there is nothing to compile\nbefore you can use it. Moreover, these header files do not depend on your\nplatform, they are the same for everybody.\n\nMethod 1. Installing without using CMake\n****************************************\n\nYou can use right away the headers in the Eigen/ subdirectory. In order\nto install, just copy this Eigen/ subdirectory to your favorite location.\nIf you also want the unsupported features, copy the unsupported/\nsubdirectory too.\n\nMethod 2. Installing using CMake\n********************************\n\nLet's call this directory 'source_dir' (where this INSTALL file is).\nBefore starting, create another directory which we will call 'build_dir'.\n\nDo:\n\n  cd build_dir\n  cmake source_dir\n  make install\n\nThe \"make install\" step may require administrator privileges.\n\nYou can adjust the installation destination (the \"prefix\")\nby passing the -DCMAKE_INSTALL_PREFIX=myprefix option to cmake, as is\nexplained in the message that cmake prints at the end.\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/README.md",
    "content": "**Eigen is a C++ template library for linear algebra: matrices, vectors, numerical solvers, and related algorithms.**\n\nFor more information go to http://eigen.tuxfamily.org/.\n\nFor ***pull request***, ***bug reports***, and ***feature requests***, go to https://gitlab.com/libeigen/eigen.\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/BenchSparseUtil.h",
    "content": "\n#include <Eigen/Sparse>\n#include <bench/BenchTimer.h>\n#include <set>\n\nusing namespace std;\nusing namespace Eigen;\nusing namespace Eigen;\n\n#ifndef SIZE\n#define SIZE 1024\n#endif\n\n#ifndef DENSITY\n#define DENSITY 0.01\n#endif\n\n#ifndef SCALAR\n#define SCALAR double\n#endif\n\ntypedef SCALAR Scalar;\ntypedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\ntypedef Matrix<Scalar,Dynamic,1> DenseVector;\ntypedef SparseMatrix<Scalar> EigenSparseMatrix;\n\nvoid fillMatrix(float density, int rows, int cols,  EigenSparseMatrix& dst)\n{\n  dst.reserve(double(rows)*cols*density);\n  for(int j = 0; j < cols; j++)\n  {\n    for(int i = 0; i < rows; i++)\n    {\n      Scalar v = (internal::random<float>(0,1) < density) ? internal::random<Scalar>() : 0;\n      if (v!=0)\n        dst.insert(i,j) = v;\n    }\n  }\n  dst.finalize();\n}\n\nvoid fillMatrix2(int nnzPerCol, int rows, int cols,  EigenSparseMatrix& dst)\n{\n//   std::cout << \"alloc \" << nnzPerCol*cols << \"\\n\";\n  dst.reserve(nnzPerCol*cols);\n  for(int j = 0; j < cols; j++)\n  {\n    std::set<int> aux;\n    for(int i = 0; i < nnzPerCol; i++)\n    {\n      int k = internal::random<int>(0,rows-1);\n      while (aux.find(k)!=aux.end())\n        k = internal::random<int>(0,rows-1);\n      aux.insert(k);\n\n      dst.insert(k,j) = internal::random<Scalar>();\n    }\n  }\n  dst.finalize();\n}\n\nvoid eiToDense(const EigenSparseMatrix& src, DenseMatrix& dst)\n{\n  dst.setZero();\n  for (int j=0; j<src.cols(); ++j)\n    for (EigenSparseMatrix::InnerIterator it(src.derived(), j); it; ++it)\n      dst(it.index(),j) = it.value();\n}\n\n#ifndef NOGMM\n#include \"gmm/gmm.h\"\ntypedef gmm::csc_matrix<Scalar> GmmSparse;\ntypedef gmm::col_matrix< gmm::wsvector<Scalar> > GmmDynSparse;\nvoid eiToGmm(const EigenSparseMatrix& src, GmmSparse& dst)\n{\n  GmmDynSparse tmp(src.rows(), src.cols());\n  for (int j=0; j<src.cols(); ++j)\n    for (EigenSparseMatrix::InnerIterator it(src.derived(), j); it; ++it)\n      tmp(it.index(),j) = it.value();\n  gmm::copy(tmp, dst);\n}\n#endif\n\n#ifndef NOMTL\n#include <boost/numeric/mtl/mtl.hpp>\ntypedef mtl::compressed2D<Scalar, mtl::matrix::parameters<mtl::tag::col_major> > MtlSparse;\ntypedef mtl::compressed2D<Scalar, mtl::matrix::parameters<mtl::tag::row_major> > MtlSparseRowMajor;\nvoid eiToMtl(const EigenSparseMatrix& src, MtlSparse& dst)\n{\n  mtl::matrix::inserter<MtlSparse> ins(dst);\n  for (int j=0; j<src.cols(); ++j)\n    for (EigenSparseMatrix::InnerIterator it(src.derived(), j); it; ++it)\n      ins[it.index()][j] = it.value();\n}\n#endif\n\n#ifdef CSPARSE\nextern \"C\" {\n#include \"cs.h\"\n}\nvoid eiToCSparse(const EigenSparseMatrix& src, cs* &dst)\n{\n  cs* aux = cs_spalloc (0, 0, 1, 1, 1);\n  for (int j=0; j<src.cols(); ++j)\n    for (EigenSparseMatrix::InnerIterator it(src.derived(), j); it; ++it)\n      if (!cs_entry(aux, it.index(), j, it.value()))\n      {\n        std::cout << \"cs_entry error\\n\";\n        exit(2);\n      }\n   dst = cs_compress(aux);\n//    cs_spfree(aux);\n}\n#endif // CSPARSE\n\n#ifndef NOUBLAS\n#include <boost/numeric/ublas/vector.hpp>\n#include <boost/numeric/ublas/matrix.hpp>\n#include <boost/numeric/ublas/io.hpp>\n#include <boost/numeric/ublas/triangular.hpp>\n#include <boost/numeric/ublas/vector_sparse.hpp>\n#include <boost/numeric/ublas/matrix_sparse.hpp>\n#include <boost/numeric/ublas/vector_of_vector.hpp>\n#include <boost/numeric/ublas/operation.hpp>\n\ntypedef boost::numeric::ublas::compressed_matrix<Scalar,boost::numeric::ublas::column_major> UBlasSparse;\n\nvoid eiToUblas(const EigenSparseMatrix& src, UBlasSparse& dst)\n{\n  dst.resize(src.rows(), src.cols(), false);\n  for (int j=0; j<src.cols(); ++j)\n    for (EigenSparseMatrix::InnerIterator it(src.derived(), j); it; ++it)\n      dst(it.index(),j) = it.value();\n}\n\ntemplate <typename EigenType, typename UblasType>\nvoid eiToUblasVec(const EigenType& src, UblasType& dst)\n{\n  dst.resize(src.size());\n  for (int j=0; j<src.size(); ++j)\n      dst[j] = src.coeff(j);\n}\n#endif\n\n#ifdef OSKI\nextern \"C\" {\n#include <oski/oski.h>\n}\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/BenchTimer.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BENCH_TIMERR_H\n#define EIGEN_BENCH_TIMERR_H\n\n#if defined(_WIN32) || defined(__CYGWIN__)\n# ifndef NOMINMAX\n#   define NOMINMAX\n#   define EIGEN_BT_UNDEF_NOMINMAX\n# endif\n# ifndef WIN32_LEAN_AND_MEAN\n#   define WIN32_LEAN_AND_MEAN\n#   define EIGEN_BT_UNDEF_WIN32_LEAN_AND_MEAN\n# endif\n# include <windows.h>\n#elif defined(__APPLE__)\n#include <mach/mach_time.h>\n#else\n# include <unistd.h>\n#endif\n\nstatic void escape(void *p) {\n#if EIGEN_COMP_GNUC || EIGEN_COMP_CLANG\n  asm volatile(\"\" : : \"g\"(p) : \"memory\");\n#endif\n}\n\nstatic void clobber() {\n#if EIGEN_COMP_GNUC || EIGEN_COMP_CLANG\n  asm volatile(\"\" : : : \"memory\");\n#endif\n}\n\n#include <Eigen/Core>\n\nnamespace Eigen\n{\n\nenum {\n  CPU_TIMER = 0,\n  REAL_TIMER = 1\n};\n\n/** Elapsed time timer keeping the best try.\n  *\n  * On POSIX platforms we use clock_gettime with CLOCK_PROCESS_CPUTIME_ID.\n  * On Windows we use QueryPerformanceCounter\n  *\n  * Important: on linux, you must link with -lrt\n  */\nclass BenchTimer\n{\npublic:\n\n  BenchTimer()\n  {\n#if defined(_WIN32) || defined(__CYGWIN__)\n    LARGE_INTEGER freq;\n    QueryPerformanceFrequency(&freq);\n    m_frequency = (double)freq.QuadPart;\n#endif\n    reset();\n  }\n\n  ~BenchTimer() {}\n\n  inline void reset()\n  {\n    m_bests.fill(1e9);\n    m_worsts.fill(0);\n    m_totals.setZero();\n  }\n  inline void start()\n  {\n    m_starts[CPU_TIMER]  = getCpuTime();\n    m_starts[REAL_TIMER] = getRealTime();\n  }\n  inline void stop()\n  {\n    m_times[CPU_TIMER] = getCpuTime() - m_starts[CPU_TIMER];\n    m_times[REAL_TIMER] = getRealTime() - m_starts[REAL_TIMER];\n    #if EIGEN_VERSION_AT_LEAST(2,90,0)\n    m_bests = m_bests.cwiseMin(m_times);\n    m_worsts = m_worsts.cwiseMax(m_times);\n    #else\n    m_bests(0) = std::min(m_bests(0),m_times(0));\n    m_bests(1) = std::min(m_bests(1),m_times(1));\n    m_worsts(0) = std::max(m_worsts(0),m_times(0));\n    m_worsts(1) = std::max(m_worsts(1),m_times(1));\n    #endif\n    m_totals += m_times;\n  }\n\n  /** Return the elapsed time in seconds between the last start/stop pair\n    */\n  inline double value(int TIMER = CPU_TIMER) const\n  {\n    return m_times[TIMER];\n  }\n\n  /** Return the best elapsed time in seconds\n    */\n  inline double best(int TIMER = CPU_TIMER) const\n  {\n    return m_bests[TIMER];\n  }\n\n  /** Return the worst elapsed time in seconds\n    */\n  inline double worst(int TIMER = CPU_TIMER) const\n  {\n    return m_worsts[TIMER];\n  }\n\n  /** Return the total elapsed time in seconds.\n    */\n  inline double total(int TIMER = CPU_TIMER) const\n  {\n    return m_totals[TIMER];\n  }\n\n  inline double getCpuTime() const\n  {\n#ifdef _WIN32\n    LARGE_INTEGER query_ticks;\n    QueryPerformanceCounter(&query_ticks);\n    return query_ticks.QuadPart/m_frequency;\n#elif __APPLE__\n    return double(mach_absolute_time())*1e-9;\n#else\n    timespec ts;\n    clock_gettime(CLOCK_PROCESS_CPUTIME_ID, &ts);\n    return double(ts.tv_sec) + 1e-9 * double(ts.tv_nsec);\n#endif\n  }\n\n  inline double getRealTime() const\n  {\n#ifdef _WIN32\n    SYSTEMTIME st;\n    GetSystemTime(&st);\n    return (double)st.wSecond + 1.e-3 * (double)st.wMilliseconds;\n#elif __APPLE__\n    return double(mach_absolute_time())*1e-9;\n#else\n    timespec ts;\n    clock_gettime(CLOCK_REALTIME, &ts);\n    return double(ts.tv_sec) + 1e-9 * double(ts.tv_nsec);\n#endif\n  }\n\nprotected:\n#if defined(_WIN32) || defined(__CYGWIN__)\n  double m_frequency;\n#endif\n  Vector2d m_starts;\n  Vector2d m_times;\n  Vector2d m_bests;\n  Vector2d m_worsts;\n  Vector2d m_totals;\n\npublic:\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n};\n\n#define BENCH(TIMER,TRIES,REP,CODE) { \\\n    TIMER.reset(); \\\n    for(int uglyvarname1=0; uglyvarname1<TRIES; ++uglyvarname1){ \\\n      TIMER.start(); \\\n      for(int uglyvarname2=0; uglyvarname2<REP; ++uglyvarname2){ \\\n        CODE; \\\n      } \\\n      TIMER.stop(); \\\n      clobber(); \\\n    } \\\n  }\n\n}\n\n// clean #defined tokens\n#ifdef EIGEN_BT_UNDEF_NOMINMAX\n# undef EIGEN_BT_UNDEF_NOMINMAX\n# undef NOMINMAX\n#endif\n\n#ifdef EIGEN_BT_UNDEF_WIN32_LEAN_AND_MEAN\n# undef EIGEN_BT_UNDEF_WIN32_LEAN_AND_MEAN\n# undef WIN32_LEAN_AND_MEAN\n#endif\n\n#endif // EIGEN_BENCH_TIMERR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/BenchUtil.h",
    "content": "\n#ifndef EIGEN_BENCH_UTIL_H\n#define EIGEN_BENCH_UTIL_H\n\n#include <Eigen/Core>\n#include \"BenchTimer.h\"\n\nusing namespace std;\nusing namespace Eigen;\n\n#include <boost/preprocessor/repetition/enum_params.hpp>\n#include <boost/preprocessor/repetition.hpp>\n#include <boost/preprocessor/seq.hpp>\n#include <boost/preprocessor/array.hpp>\n#include <boost/preprocessor/arithmetic.hpp>\n#include <boost/preprocessor/comparison.hpp>\n#include <boost/preprocessor/punctuation.hpp>\n#include <boost/preprocessor/punctuation/comma.hpp>\n#include <boost/preprocessor/stringize.hpp>\n\ntemplate<typename MatrixType> void initMatrix_random(MatrixType& mat) __attribute__((noinline));\ntemplate<typename MatrixType> void initMatrix_random(MatrixType& mat)\n{\n  mat.setRandom();// = MatrixType::random(mat.rows(), mat.cols());\n}\n\ntemplate<typename MatrixType> void initMatrix_identity(MatrixType& mat) __attribute__((noinline));\ntemplate<typename MatrixType> void initMatrix_identity(MatrixType& mat)\n{\n  mat.setIdentity();\n}\n\n#ifndef __INTEL_COMPILER\n#define DISABLE_SSE_EXCEPTIONS()  { \\\n  int aux; \\\n  asm( \\\n  \"stmxcsr   %[aux]           \\n\\t\" \\\n  \"orl       $32832, %[aux]   \\n\\t\" \\\n  \"ldmxcsr   %[aux]           \\n\\t\" \\\n  : : [aux] \"m\" (aux)); \\\n}\n#else\n#define DISABLE_SSE_EXCEPTIONS()  \n#endif\n\n#ifdef BENCH_GMM\n#include <gmm/gmm.h>\ntemplate <typename EigenMatrixType, typename GmmMatrixType>\nvoid eiToGmm(const EigenMatrixType& src, GmmMatrixType& dst)\n{\n  dst.resize(src.rows(),src.cols());\n  for (int j=0; j<src.cols(); ++j)\n    for (int i=0; i<src.rows(); ++i)\n      dst(i,j) = src.coeff(i,j);\n}\n#endif\n\n\n#ifdef BENCH_GSL\n#include <gsl/gsl_matrix.h>\n#include <gsl/gsl_linalg.h>\n#include <gsl/gsl_eigen.h>\ntemplate <typename EigenMatrixType>\nvoid eiToGsl(const EigenMatrixType& src, gsl_matrix** dst)\n{\n  for (int j=0; j<src.cols(); ++j)\n    for (int i=0; i<src.rows(); ++i)\n      gsl_matrix_set(*dst, i, j, src.coeff(i,j));\n}\n#endif\n\n#ifdef BENCH_UBLAS\n#include <boost/numeric/ublas/matrix.hpp>\n#include <boost/numeric/ublas/vector.hpp>\ntemplate <typename EigenMatrixType, typename UblasMatrixType>\nvoid eiToUblas(const EigenMatrixType& src, UblasMatrixType& dst)\n{\n  dst.resize(src.rows(),src.cols());\n  for (int j=0; j<src.cols(); ++j)\n    for (int i=0; i<src.rows(); ++i)\n      dst(i,j) = src.coeff(i,j);\n}\ntemplate <typename EigenType, typename UblasType>\nvoid eiToUblasVec(const EigenType& src, UblasType& dst)\n{\n  dst.resize(src.size());\n  for (int j=0; j<src.size(); ++j)\n      dst[j] = src.coeff(j);\n}\n#endif\n\n#endif // EIGEN_BENCH_UTIL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/README.txt",
    "content": "\nThis folder contains a couple of benchmark utities and Eigen benchmarks.\n\n****************************\n* bench_multi_compilers.sh *\n****************************\n\nThis script allows to run a benchmark on a set of different compilers/compiler options.\nIt takes two arguments:\n - a file defining the list of the compilers with their options\n - the .cpp file of the benchmark\n\nExamples:\n\n$ ./bench_multi_compilers.sh basicbench.cxxlist basicbenchmark.cpp\n\n    g++-4.1 -O3 -DNDEBUG -finline-limit=10000\n    3d-3x3   /   4d-4x4   /   Xd-4x4   /   Xd-20x20   /\n    0.271102   0.131416   0.422322   0.198633\n    0.201658   0.102436   0.397566   0.207282\n\n    g++-4.2 -O3 -DNDEBUG -finline-limit=10000\n    3d-3x3   /   4d-4x4   /   Xd-4x4   /   Xd-20x20   /\n    0.107805   0.0890579   0.30265   0.161843\n    0.127157   0.0712581   0.278341   0.191029\n\n    g++-4.3 -O3 -DNDEBUG -finline-limit=10000\n    3d-3x3   /   4d-4x4   /   Xd-4x4   /   Xd-20x20   /\n    0.134318   0.105291   0.3704   0.180966\n    0.137703   0.0732472   0.31225   0.202204\n\n    icpc -fast -DNDEBUG -fno-exceptions -no-inline-max-size\n    3d-3x3   /   4d-4x4   /   Xd-4x4   /   Xd-20x20   /\n    0.226145   0.0941319   0.371873   0.159433\n    0.109302   0.0837538   0.328102   0.173891\n\n\n$ ./bench_multi_compilers.sh ompbench.cxxlist ompbenchmark.cpp\n\n    g++-4.2 -O3 -DNDEBUG -finline-limit=10000 -fopenmp\n    double, fixed-size 4x4: 0.00165105s  0.0778739s\n    double, 32x32: 0.0654769s 0.075289s  => x0.869674 (2)\n    double, 128x128: 0.054148s 0.0419669s  => x1.29025 (2)\n    double, 512x512: 0.913799s 0.428533s  => x2.13239 (2)\n    double, 1024x1024: 14.5972s 9.3542s  => x1.5605 (2)\n\n    icpc -fast -DNDEBUG -fno-exceptions -no-inline-max-size -openmp\n    double, fixed-size 4x4: 0.000589848s  0.019949s\n    double, 32x32: 0.0682781s 0.0449722s  => x1.51823 (2)\n    double, 128x128: 0.0547509s 0.0435519s  => x1.25714 (2)\n    double, 512x512: 0.829436s 0.424438s  => x1.9542 (2)\n    double, 1024x1024: 14.5243s 10.7735s  => x1.34815 (2)\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/analyze-blocking-sizes.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Jacob <benoitjacob@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <iostream>\n#include <cstdint>\n#include <cstdlib>\n#include <vector>\n#include <algorithm>\n#include <fstream>\n#include <string>\n#include <cmath>\n#include <cassert>\n#include <cstring>\n#include <memory>\n\n#include <Eigen/Core>\n\nusing namespace std;\n\nconst int default_precision = 4;\n\n// see --only-cubic-sizes\nbool only_cubic_sizes = false;\n\n// see --dump-tables\nbool dump_tables = false;\n\nuint8_t log2_pot(size_t x) {\n  size_t l = 0;\n  while (x >>= 1) l++;\n  return l;\n}\n\nuint16_t compact_size_triple(size_t k, size_t m, size_t n)\n{\n  return (log2_pot(k) << 8) | (log2_pot(m) << 4) | log2_pot(n);\n}\n\n// just a helper to store a triple of K,M,N sizes for matrix product\nstruct size_triple_t\n{\n  uint16_t k, m, n;\n  size_triple_t() : k(0), m(0), n(0) {}\n  size_triple_t(size_t _k, size_t _m, size_t _n) : k(_k), m(_m), n(_n) {}\n  size_triple_t(const size_triple_t& o) : k(o.k), m(o.m), n(o.n) {}\n  size_triple_t(uint16_t compact)\n  {\n    k = 1 << ((compact & 0xf00) >> 8);\n    m = 1 << ((compact & 0x0f0) >> 4);\n    n = 1 << ((compact & 0x00f) >> 0);\n  }\n  bool is_cubic() const { return k == m && m == n; }\n};\n\nostream& operator<<(ostream& s, const size_triple_t& t)\n{\n  return s << \"(\" << t.k << \", \" << t.m << \", \" << t.n << \")\";\n}\n\nstruct inputfile_entry_t\n{\n  uint16_t product_size;\n  uint16_t pot_block_size;\n  size_triple_t nonpot_block_size;\n  float gflops;\n};\n\nstruct inputfile_t\n{\n  enum class type_t {\n    unknown,\n    all_pot_sizes,\n    default_sizes\n  };\n\n  string filename;\n  vector<inputfile_entry_t> entries;\n  type_t type;\n\n  inputfile_t(const string& fname)\n    : filename(fname)\n    , type(type_t::unknown)\n  {\n    ifstream stream(filename);\n    if (!stream.is_open()) {\n      cerr << \"couldn't open input file: \" << filename << endl;\n      exit(1);\n    }\n    string line;\n    while (getline(stream, line)) {\n      if (line.empty()) continue;\n      if (line.find(\"BEGIN MEASUREMENTS ALL POT SIZES\") == 0) {\n        if (type != type_t::unknown) {\n          cerr << \"Input file \" << filename << \" contains redundant BEGIN MEASUREMENTS lines\";\n          exit(1);\n        }\n        type = type_t::all_pot_sizes;\n        continue;\n      }\n      if (line.find(\"BEGIN MEASUREMENTS DEFAULT SIZES\") == 0) {\n        if (type != type_t::unknown) {\n          cerr << \"Input file \" << filename << \" contains redundant BEGIN MEASUREMENTS lines\";\n          exit(1);\n        }\n        type = type_t::default_sizes;\n        continue;\n      }\n      \n\n      if (type == type_t::unknown) {\n        continue;\n      }\n      switch(type) {\n        case type_t::all_pot_sizes: {\n          unsigned int product_size, block_size;\n          float gflops;\n          int sscanf_result =\n            sscanf(line.c_str(), \"%x %x %f\",\n                   &product_size,\n                   &block_size,\n                   &gflops);\n          if (3 != sscanf_result ||\n              !product_size ||\n              product_size > 0xfff ||\n              !block_size ||\n              block_size > 0xfff ||\n              !isfinite(gflops))\n          {\n            cerr << \"ill-formed input file: \" << filename << endl;\n            cerr << \"offending line:\" << endl << line << endl;\n            exit(1);\n          }\n          if (only_cubic_sizes && !size_triple_t(product_size).is_cubic()) {\n            continue;\n          }\n          inputfile_entry_t entry;\n          entry.product_size = uint16_t(product_size);\n          entry.pot_block_size = uint16_t(block_size);\n          entry.gflops = gflops;\n          entries.push_back(entry);\n          break;\n        }\n        case type_t::default_sizes: {\n          unsigned int product_size;\n          float gflops;\n          int bk, bm, bn;\n          int sscanf_result =\n            sscanf(line.c_str(), \"%x default(%d, %d, %d) %f\",\n                   &product_size,\n                   &bk, &bm, &bn,\n                   &gflops);\n          if (5 != sscanf_result ||\n              !product_size ||\n              product_size > 0xfff ||\n              !isfinite(gflops))\n          {\n            cerr << \"ill-formed input file: \" << filename << endl;\n            cerr << \"offending line:\" << endl << line << endl;\n            exit(1);\n          }\n          if (only_cubic_sizes && !size_triple_t(product_size).is_cubic()) {\n            continue;\n          }\n          inputfile_entry_t entry;\n          entry.product_size = uint16_t(product_size);\n          entry.pot_block_size = 0;\n          entry.nonpot_block_size = size_triple_t(bk, bm, bn);\n          entry.gflops = gflops;\n          entries.push_back(entry);\n          break;\n        }\n        \n        default:\n          break;\n      }\n    }\n    stream.close();\n    if (type == type_t::unknown) {\n      cerr << \"Unrecognized input file \" << filename << endl;\n      exit(1);\n    }\n    if (entries.empty()) {\n      cerr << \"didn't find any measurements in input file: \" << filename << endl;\n      exit(1);\n    }\n  }\n};\n\nstruct preprocessed_inputfile_entry_t\n{\n  uint16_t product_size;\n  uint16_t block_size;\n\n  float efficiency;\n};\n\nbool lower_efficiency(const preprocessed_inputfile_entry_t& e1, const preprocessed_inputfile_entry_t& e2)\n{\n  return e1.efficiency < e2.efficiency;\n}\n\nstruct preprocessed_inputfile_t\n{\n  string filename;\n  vector<preprocessed_inputfile_entry_t> entries;\n\n  preprocessed_inputfile_t(const inputfile_t& inputfile)\n    : filename(inputfile.filename)\n  {\n    if (inputfile.type != inputfile_t::type_t::all_pot_sizes) {\n      abort();\n    }\n    auto it = inputfile.entries.begin();\n    auto it_first_with_given_product_size = it;\n    while (it != inputfile.entries.end()) {\n      ++it;\n      if (it == inputfile.entries.end() ||\n        it->product_size != it_first_with_given_product_size->product_size)\n      {\n        import_input_file_range_one_product_size(it_first_with_given_product_size, it);\n        it_first_with_given_product_size = it;\n      }\n    }\n  }\n\nprivate:\n  void import_input_file_range_one_product_size(\n    const vector<inputfile_entry_t>::const_iterator& begin,\n    const vector<inputfile_entry_t>::const_iterator& end)\n  {\n    uint16_t product_size = begin->product_size;\n    float max_gflops = 0.0f;\n    for (auto it = begin; it != end; ++it) {\n      if (it->product_size != product_size) {\n        cerr << \"Unexpected ordering of entries in \" << filename << endl;\n        cerr << \"(Expected all entries for product size \" << hex << product_size << dec << \" to be grouped)\" << endl;\n        exit(1);\n      }\n      max_gflops = max(max_gflops, it->gflops);\n    }\n    for (auto it = begin; it != end; ++it) {\n      preprocessed_inputfile_entry_t entry;\n      entry.product_size = it->product_size;\n      entry.block_size = it->pot_block_size;\n      entry.efficiency = it->gflops / max_gflops;\n      entries.push_back(entry);\n    }\n  }\n};\n\nvoid check_all_files_in_same_exact_order(\n       const vector<preprocessed_inputfile_t>& preprocessed_inputfiles)\n{\n  if (preprocessed_inputfiles.empty()) {\n    return;\n  }\n\n  const preprocessed_inputfile_t& first_file = preprocessed_inputfiles[0];\n  const size_t num_entries = first_file.entries.size();\n\n  for (size_t i = 0; i < preprocessed_inputfiles.size(); i++) {\n    if (preprocessed_inputfiles[i].entries.size() != num_entries) {\n      cerr << \"these files have different number of entries: \"\n           << preprocessed_inputfiles[i].filename\n           << \" and \"\n           << first_file.filename\n           << endl;\n      exit(1);\n    }\n  }\n\n  for (size_t entry_index = 0; entry_index < num_entries; entry_index++) {\n    const uint16_t entry_product_size = first_file.entries[entry_index].product_size;\n    const uint16_t entry_block_size = first_file.entries[entry_index].block_size;\n    for (size_t file_index = 0; file_index < preprocessed_inputfiles.size(); file_index++) {\n      const preprocessed_inputfile_t& cur_file = preprocessed_inputfiles[file_index];\n      if (cur_file.entries[entry_index].product_size != entry_product_size ||\n          cur_file.entries[entry_index].block_size != entry_block_size)\n      {\n        cerr << \"entries not in same order between these files: \"\n             << first_file.filename\n             << \" and \"\n             << cur_file.filename\n             << endl;\n        exit(1);\n      }\n    }\n  }\n}\n\nfloat efficiency_of_subset(\n        const vector<preprocessed_inputfile_t>& preprocessed_inputfiles,\n        const vector<size_t>& subset)\n{\n  if (subset.size() <= 1) {\n    return 1.0f;\n  }\n  const preprocessed_inputfile_t& first_file = preprocessed_inputfiles[subset[0]];\n  const size_t num_entries = first_file.entries.size();\n  float efficiency = 1.0f;\n  size_t entry_index = 0;\n  size_t first_entry_index_with_this_product_size = 0;\n  uint16_t product_size = first_file.entries[0].product_size;\n  while (entry_index < num_entries) {\n    ++entry_index;\n    if (entry_index == num_entries ||\n        first_file.entries[entry_index].product_size != product_size)\n    {\n      float efficiency_this_product_size = 0.0f;\n      for (size_t e = first_entry_index_with_this_product_size; e < entry_index; e++) {\n        float efficiency_this_entry = 1.0f;\n        for (auto i = subset.begin(); i != subset.end(); ++i) {\n          efficiency_this_entry = min(efficiency_this_entry, preprocessed_inputfiles[*i].entries[e].efficiency);\n        }\n        efficiency_this_product_size = max(efficiency_this_product_size, efficiency_this_entry);\n      }\n      efficiency = min(efficiency, efficiency_this_product_size);\n      if (entry_index < num_entries) {\n        first_entry_index_with_this_product_size = entry_index;\n        product_size = first_file.entries[entry_index].product_size;\n      }\n    }\n  }\n\n  return efficiency;\n}\n\nvoid dump_table_for_subset(\n        const vector<preprocessed_inputfile_t>& preprocessed_inputfiles,\n        const vector<size_t>& subset)\n{\n  const preprocessed_inputfile_t& first_file = preprocessed_inputfiles[subset[0]];\n  const size_t num_entries = first_file.entries.size();\n  size_t entry_index = 0;\n  size_t first_entry_index_with_this_product_size = 0;\n  uint16_t product_size = first_file.entries[0].product_size;\n  size_t i = 0;\n  size_triple_t min_product_size(first_file.entries.front().product_size);\n  size_triple_t max_product_size(first_file.entries.back().product_size);\n  if (!min_product_size.is_cubic() || !max_product_size.is_cubic()) {\n    abort();\n  }\n  if (only_cubic_sizes) {\n    cerr << \"Can't generate tables with --only-cubic-sizes.\" << endl;\n    abort();\n  }\n  cout << \"struct LookupTable {\" << endl;\n  cout << \"  static const size_t BaseSize = \" << min_product_size.k << \";\" << endl;\n  const size_t NumSizes = log2_pot(max_product_size.k / min_product_size.k) + 1;\n  const size_t TableSize = NumSizes * NumSizes * NumSizes;\n  cout << \"  static const size_t NumSizes = \" << NumSizes << \";\" << endl;\n  cout << \"  static const unsigned short* Data() {\" << endl;\n  cout << \"    static const unsigned short data[\" << TableSize << \"] = {\";\n  while (entry_index < num_entries) {\n    ++entry_index;\n    if (entry_index == num_entries ||\n        first_file.entries[entry_index].product_size != product_size)\n    {\n      float best_efficiency_this_product_size = 0.0f;\n      uint16_t best_block_size_this_product_size = 0;\n      for (size_t e = first_entry_index_with_this_product_size; e < entry_index; e++) {\n        float efficiency_this_entry = 1.0f;\n        for (auto i = subset.begin(); i != subset.end(); ++i) {\n          efficiency_this_entry = min(efficiency_this_entry, preprocessed_inputfiles[*i].entries[e].efficiency);\n        }\n        if (efficiency_this_entry > best_efficiency_this_product_size) {\n          best_efficiency_this_product_size = efficiency_this_entry;\n          best_block_size_this_product_size = first_file.entries[e].block_size;\n        }\n      }\n      if ((i++) % NumSizes) {\n        cout << \" \";\n      } else {\n        cout << endl << \"      \";\n      }\n      cout << \"0x\" << hex << best_block_size_this_product_size << dec;\n      if (entry_index < num_entries) {\n        cout << \",\";\n        first_entry_index_with_this_product_size = entry_index;\n        product_size = first_file.entries[entry_index].product_size;\n      }\n    }\n  }\n  if (i != TableSize) {\n    cerr << endl << \"Wrote \" << i << \" table entries, expected \" << TableSize << endl;\n    abort();\n  }\n  cout << endl << \"    };\" << endl;\n  cout << \"    return data;\" << endl;\n  cout << \"  }\" << endl;\n  cout << \"};\" << endl;\n}\n\nfloat efficiency_of_partition(\n        const vector<preprocessed_inputfile_t>& preprocessed_inputfiles,\n        const vector<vector<size_t>>& partition)\n{\n  float efficiency = 1.0f;\n  for (auto s = partition.begin(); s != partition.end(); ++s) {\n    efficiency = min(efficiency, efficiency_of_subset(preprocessed_inputfiles, *s));\n  }\n  return efficiency;\n}\n\nvoid make_first_subset(size_t subset_size, vector<size_t>& out_subset, size_t set_size)\n{\n  assert(subset_size >= 1 && subset_size <= set_size);\n  out_subset.resize(subset_size);\n  for (size_t i = 0; i < subset_size; i++) {\n    out_subset[i] = i;\n  }\n}\n\nbool is_last_subset(const vector<size_t>& subset, size_t set_size)\n{\n  return subset[0] == set_size - subset.size();\n}\n\nvoid next_subset(vector<size_t>& inout_subset, size_t set_size)\n{\n  if (is_last_subset(inout_subset, set_size)) {\n    cerr << \"iterating past the last subset\" << endl;\n    abort();\n  }\n  size_t i = 1;\n  while (inout_subset[inout_subset.size() - i] == set_size - i) {\n    i++;\n    assert(i <= inout_subset.size());\n  }\n  size_t first_index_to_change = inout_subset.size() - i;\n  inout_subset[first_index_to_change]++;\n  size_t p = inout_subset[first_index_to_change];\n  for (size_t j = first_index_to_change + 1; j < inout_subset.size(); j++) {\n    inout_subset[j] = ++p;\n  }\n}\n\nconst size_t number_of_subsets_limit = 100;\nconst size_t always_search_subsets_of_size_at_least = 2;\n\nbool is_number_of_subsets_feasible(size_t n, size_t p)\n{ \n  assert(n>0 && p>0 && p<=n);\n  uint64_t numerator = 1, denominator = 1;\n  for (size_t i = 0; i < p; i++) {\n    numerator *= n - i;\n    denominator *= i + 1;\n    if (numerator > denominator * number_of_subsets_limit) {\n      return false;\n    }\n  }\n  return true;\n}\n\nsize_t max_feasible_subset_size(size_t n)\n{\n  assert(n > 0);\n  const size_t minresult = min<size_t>(n-1, always_search_subsets_of_size_at_least);\n  for (size_t p = 1; p <= n - 1; p++) {\n    if (!is_number_of_subsets_feasible(n, p+1)) {\n      return max(p, minresult);\n    }\n  }\n  return n - 1;\n}\n\nvoid find_subset_with_efficiency_higher_than(\n       const vector<preprocessed_inputfile_t>& preprocessed_inputfiles,\n       float required_efficiency_to_beat,\n       vector<size_t>& inout_remainder,\n       vector<size_t>& out_subset)\n{\n  out_subset.resize(0);\n\n  if (required_efficiency_to_beat >= 1.0f) {\n    cerr << \"can't beat efficiency 1.\" << endl;\n    abort();\n  }\n\n  while (!inout_remainder.empty()) {\n\n    vector<size_t> candidate_indices(inout_remainder.size());\n    for (size_t i = 0; i < candidate_indices.size(); i++) {\n      candidate_indices[i] = i;\n    }\n\n    size_t candidate_indices_subset_size = max_feasible_subset_size(candidate_indices.size());\n    while (candidate_indices_subset_size >= 1) {\n      vector<size_t> candidate_indices_subset;\n      make_first_subset(candidate_indices_subset_size,\n                        candidate_indices_subset,\n                        candidate_indices.size());\n\n      vector<size_t> best_candidate_indices_subset;\n      float best_efficiency = 0.0f;\n      vector<size_t> trial_subset = out_subset;\n      trial_subset.resize(out_subset.size() + candidate_indices_subset_size);\n      while (true)\n      {\n        for (size_t i = 0; i < candidate_indices_subset_size; i++) {\n          trial_subset[out_subset.size() + i] = inout_remainder[candidate_indices_subset[i]];\n        }\n        \n        float trial_efficiency = efficiency_of_subset(preprocessed_inputfiles, trial_subset);\n        if (trial_efficiency > best_efficiency) {\n          best_efficiency = trial_efficiency;\n          best_candidate_indices_subset = candidate_indices_subset;\n        }\n        if (is_last_subset(candidate_indices_subset, candidate_indices.size())) {\n          break;\n        }\n        next_subset(candidate_indices_subset, candidate_indices.size());\n      }\n       \n      if (best_efficiency > required_efficiency_to_beat) {\n        for (size_t i = 0; i < best_candidate_indices_subset.size(); i++) {\n          candidate_indices[i] = candidate_indices[best_candidate_indices_subset[i]];\n        }\n        candidate_indices.resize(best_candidate_indices_subset.size());\n      }\n      candidate_indices_subset_size--;\n    }\n      \n    size_t candidate_index = candidate_indices[0];\n    auto candidate_iterator = inout_remainder.begin() + candidate_index;\n    vector<size_t> trial_subset = out_subset;\n\n    trial_subset.push_back(*candidate_iterator);\n    float trial_efficiency = efficiency_of_subset(preprocessed_inputfiles, trial_subset);\n    if (trial_efficiency > required_efficiency_to_beat) {\n      out_subset.push_back(*candidate_iterator);\n      inout_remainder.erase(candidate_iterator);\n    } else {\n      break;\n    }\n  }\n}\n\nvoid find_partition_with_efficiency_higher_than(\n       const vector<preprocessed_inputfile_t>& preprocessed_inputfiles,\n       float required_efficiency_to_beat,\n       vector<vector<size_t>>& out_partition)\n{\n  out_partition.resize(0);\n\n  vector<size_t> remainder;\n  for (size_t i = 0; i < preprocessed_inputfiles.size(); i++) {\n    remainder.push_back(i);\n  }\n\n  while (!remainder.empty()) {\n    vector<size_t> new_subset;\n    find_subset_with_efficiency_higher_than(\n      preprocessed_inputfiles,\n      required_efficiency_to_beat,\n      remainder,\n      new_subset);\n    out_partition.push_back(new_subset);\n  }\n}\n\nvoid print_partition(\n       const vector<preprocessed_inputfile_t>& preprocessed_inputfiles,\n       const vector<vector<size_t>>& partition)\n{\n  float efficiency = efficiency_of_partition(preprocessed_inputfiles, partition);\n  cout << \"Partition into \" << partition.size() << \" subsets for \" << efficiency * 100.0f << \"% efficiency\"  << endl;\n  for (auto subset = partition.begin(); subset != partition.end(); ++subset) {\n    cout << \"  Subset \" << (subset - partition.begin())\n         << \", efficiency \" << efficiency_of_subset(preprocessed_inputfiles, *subset) * 100.0f << \"%:\"\n         << endl;\n    for (auto file = subset->begin(); file != subset->end(); ++file) {\n      cout << \"    \" << preprocessed_inputfiles[*file].filename << endl;\n    }\n    if (dump_tables) {\n      cout << \"  Table:\" << endl;\n      dump_table_for_subset(preprocessed_inputfiles, *subset);\n    }\n  }\n  cout << endl;\n}\n\nstruct action_t\n{\n  virtual const char* invokation_name() const { abort(); return nullptr; }\n  virtual void run(const vector<string>&) const { abort(); }\n  virtual ~action_t() {}\n};\n\nstruct partition_action_t : action_t\n{\n  virtual const char* invokation_name() const override { return \"partition\"; }\n  virtual void run(const vector<string>& input_filenames) const override\n  {\n    vector<preprocessed_inputfile_t> preprocessed_inputfiles;\n\n    if (input_filenames.empty()) {\n      cerr << \"The \" << invokation_name() << \" action needs a list of input files.\" << endl;\n      exit(1);\n    }\n\n    for (auto it = input_filenames.begin(); it != input_filenames.end(); ++it) {\n      inputfile_t inputfile(*it);\n      switch (inputfile.type) {\n        case inputfile_t::type_t::all_pot_sizes:\n          preprocessed_inputfiles.emplace_back(inputfile);\n          break;\n        case inputfile_t::type_t::default_sizes:\n          cerr << \"The \" << invokation_name() << \" action only uses measurements for all pot sizes, and \"\n               << \"has no use for \" << *it << \" which contains measurements for default sizes.\" << endl;\n          exit(1);\n          break;\n        default:\n          cerr << \"Unrecognized input file: \" << *it << endl;\n          exit(1);\n      }\n    }\n\n    check_all_files_in_same_exact_order(preprocessed_inputfiles);\n\n    float required_efficiency_to_beat = 0.0f;\n    vector<vector<vector<size_t>>> partitions;\n    cerr << \"searching for partitions...\\r\" << flush;\n    while (true)\n    {\n      vector<vector<size_t>> partition;\n      find_partition_with_efficiency_higher_than(\n        preprocessed_inputfiles,\n        required_efficiency_to_beat,\n        partition);\n      float actual_efficiency = efficiency_of_partition(preprocessed_inputfiles, partition);\n      cerr << \"partition \" << preprocessed_inputfiles.size() << \" files into \" << partition.size()\n           << \" subsets for \" << 100.0f * actual_efficiency\n           << \" % efficiency\"\n           << \"                  \\r\" << flush;\n      partitions.push_back(partition);\n      if (partition.size() == preprocessed_inputfiles.size() || actual_efficiency == 1.0f) {\n        break;\n      }\n      required_efficiency_to_beat = actual_efficiency;\n    }\n    cerr << \"                                                                  \" << endl;\n    while (true) {\n      bool repeat = false;\n      for (size_t i = 0; i < partitions.size() - 1; i++) {\n        if (partitions[i].size() >= partitions[i+1].size()) {\n          partitions.erase(partitions.begin() + i);\n          repeat = true;\n          break;\n        }\n      }\n      if (!repeat) {\n        break;\n      }\n    }\n    for (auto it = partitions.begin(); it != partitions.end(); ++it) {\n      print_partition(preprocessed_inputfiles, *it);\n    }\n  }\n};\n\nstruct evaluate_defaults_action_t : action_t\n{\n  struct results_entry_t {\n    uint16_t product_size;\n    size_triple_t default_block_size;\n    uint16_t best_pot_block_size;\n    float default_gflops;\n    float best_pot_gflops;\n    float default_efficiency;\n  };\n  friend ostream& operator<<(ostream& s, const results_entry_t& entry)\n  {\n    return s\n      << \"Product size \" << size_triple_t(entry.product_size)\n      << \": default block size \" << entry.default_block_size\n      << \" -> \" << entry.default_gflops\n      << \" GFlop/s = \" << entry.default_efficiency * 100.0f << \" %\"\n      << \" of best POT block size \" << size_triple_t(entry.best_pot_block_size)\n      << \" -> \" << entry.best_pot_gflops\n      << \" GFlop/s\" << dec;\n  }\n  static bool lower_efficiency(const results_entry_t& e1, const results_entry_t& e2) {\n    return e1.default_efficiency < e2.default_efficiency;\n  }\n  virtual const char* invokation_name() const override { return \"evaluate-defaults\"; }\n  void show_usage_and_exit() const\n  {\n    cerr << \"usage: \" << invokation_name() << \" default-sizes-data all-pot-sizes-data\" << endl;\n    cerr << \"checks how well the performance with default sizes compares to the best \"\n         << \"performance measured over all POT sizes.\" << endl;\n    exit(1);\n  }\n  virtual void run(const vector<string>& input_filenames) const override\n  {\n    if (input_filenames.size() != 2) {\n      show_usage_and_exit();\n    }\n    inputfile_t inputfile_default_sizes(input_filenames[0]);\n    inputfile_t inputfile_all_pot_sizes(input_filenames[1]);\n    if (inputfile_default_sizes.type != inputfile_t::type_t::default_sizes) {\n      cerr << inputfile_default_sizes.filename << \" is not an input file with default sizes.\" << endl;\n      show_usage_and_exit();\n    }\n    if (inputfile_all_pot_sizes.type != inputfile_t::type_t::all_pot_sizes) {\n      cerr << inputfile_all_pot_sizes.filename << \" is not an input file with all POT sizes.\" << endl;\n      show_usage_and_exit();\n    }\n    vector<results_entry_t> results;\n    vector<results_entry_t> cubic_results;\n    \n    uint16_t product_size = 0;\n    auto it_all_pot_sizes = inputfile_all_pot_sizes.entries.begin();\n    for (auto it_default_sizes = inputfile_default_sizes.entries.begin();\n         it_default_sizes != inputfile_default_sizes.entries.end();\n         ++it_default_sizes)\n    {\n      if (it_default_sizes->product_size == product_size) {\n        continue;\n      }\n      product_size = it_default_sizes->product_size;\n      while (it_all_pot_sizes != inputfile_all_pot_sizes.entries.end() &&\n             it_all_pot_sizes->product_size != product_size)\n      {\n        ++it_all_pot_sizes;\n      }\n      if (it_all_pot_sizes == inputfile_all_pot_sizes.entries.end()) {\n        break;\n      }\n      uint16_t best_pot_block_size = 0;\n      float best_pot_gflops = 0;\n      for (auto it = it_all_pot_sizes;\n           it != inputfile_all_pot_sizes.entries.end() && it->product_size == product_size;\n           ++it)\n      {\n        if (it->gflops > best_pot_gflops) {\n          best_pot_gflops = it->gflops;\n          best_pot_block_size = it->pot_block_size;\n        }\n      }\n      results_entry_t entry;\n      entry.product_size = product_size;\n      entry.default_block_size = it_default_sizes->nonpot_block_size;\n      entry.best_pot_block_size = best_pot_block_size;\n      entry.default_gflops = it_default_sizes->gflops;\n      entry.best_pot_gflops = best_pot_gflops;\n      entry.default_efficiency = entry.default_gflops / entry.best_pot_gflops;\n      results.push_back(entry);\n\n      size_triple_t t(product_size);\n      if (t.k == t.m && t.m == t.n) {\n        cubic_results.push_back(entry);\n      }\n    }\n\n    cout << \"All results:\" << endl;\n    for (auto it = results.begin(); it != results.end(); ++it) {\n      cout << *it << endl;\n    }\n    cout << endl;\n\n    sort(results.begin(), results.end(), lower_efficiency);\n    \n    const size_t n = min<size_t>(20, results.size());\n    cout << n << \" worst results:\" << endl;\n    for (size_t i = 0; i < n; i++) {\n      cout << results[i] << endl;\n    }\n    cout << endl;\n\n    cout << \"cubic results:\" << endl;\n    for (auto it = cubic_results.begin(); it != cubic_results.end(); ++it) {\n      cout << *it << endl;\n    }\n    cout << endl;\n\n    sort(cubic_results.begin(), cubic_results.end(), lower_efficiency);\n    \n    cout.precision(2);\n    vector<float> a = {0.5f, 0.20f, 0.10f, 0.05f, 0.02f, 0.01f};\n    for (auto it = a.begin(); it != a.end(); ++it) {\n      size_t n = min(results.size() - 1, size_t(*it * results.size()));\n      cout << (100.0f * n / (results.size() - 1))\n           << \" % of product sizes have default efficiency <= \"\n           << 100.0f * results[n].default_efficiency << \" %\" << endl;\n    }\n    cout.precision(default_precision);\n  }\n};\n\n\nvoid show_usage_and_exit(int argc, char* argv[],\n                         const vector<unique_ptr<action_t>>& available_actions)\n{\n  cerr << \"usage: \" << argv[0] << \" <action> [options...] <input files...>\" << endl;\n  cerr << \"available actions:\" << endl;\n  for (auto it = available_actions.begin(); it != available_actions.end(); ++it) {\n    cerr << \"  \" << (*it)->invokation_name() << endl;\n  } \n  cerr << \"the input files should each contain an output of benchmark-blocking-sizes\" << endl;\n  exit(1);\n}\n\nint main(int argc, char* argv[])\n{\n  cout.precision(default_precision);\n  cerr.precision(default_precision);\n\n  vector<unique_ptr<action_t>> available_actions;\n  available_actions.emplace_back(new partition_action_t);\n  available_actions.emplace_back(new evaluate_defaults_action_t);\n\n  vector<string> input_filenames;\n\n  action_t* action = nullptr;\n\n  if (argc < 2) {\n    show_usage_and_exit(argc, argv, available_actions);\n  }\n  for (int i = 1; i < argc; i++) {\n    bool arg_handled = false;\n    // Step 1. Try to match action invocation names.\n    for (auto it = available_actions.begin(); it != available_actions.end(); ++it) {\n      if (!strcmp(argv[i], (*it)->invokation_name())) {\n        if (!action) {\n          action = it->get();\n          arg_handled = true;\n          break;\n        } else {\n          cerr << \"can't specify more than one action!\" << endl;\n          show_usage_and_exit(argc, argv, available_actions);\n        }\n      }\n    }\n    if (arg_handled) {\n      continue;\n    }\n    // Step 2. Try to match option names.\n    if (argv[i][0] == '-') {\n      if (!strcmp(argv[i], \"--only-cubic-sizes\")) {\n        only_cubic_sizes = true;\n        arg_handled = true;\n      }\n      if (!strcmp(argv[i], \"--dump-tables\")) {\n        dump_tables = true;\n        arg_handled = true;\n      }\n      if (!arg_handled) {\n        cerr << \"Unrecognized option: \" << argv[i] << endl;\n        show_usage_and_exit(argc, argv, available_actions);\n      }\n    }\n    if (arg_handled) {\n      continue;\n    }\n    // Step 3. Default to interpreting args as input filenames.\n    input_filenames.emplace_back(argv[i]);\n  }\n\n  if (dump_tables && only_cubic_sizes) {\n    cerr << \"Incompatible options: --only-cubic-sizes and --dump-tables.\" << endl;\n    show_usage_and_exit(argc, argv, available_actions);\n  }\n\n  if (!action) {\n    show_usage_and_exit(argc, argv, available_actions);\n  }\n\n  action->run(input_filenames);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/basicbench.cxxlist",
    "content": "#!/bin/bash\n\n# CLIST[((g++))]=\"g++-3.4 -O3 -DNDEBUG\"\n# CLIST[((g++))]=\"g++-3.4 -O3 -DNDEBUG -finline-limit=20000\"\n\n# CLIST[((g++))]=\"g++-4.1 -O3 -DNDEBUG\"\n#CLIST[((g++))]=\"g++-4.1 -O3 -DNDEBUG -finline-limit=20000\"\n\n# CLIST[((g++))]=\"g++-4.2 -O3 -DNDEBUG\"\n#CLIST[((g++))]=\"g++-4.2 -O3 -DNDEBUG -finline-limit=20000\"\n# CLIST[((g++))]=\"g++-4.2 -O3 -DNDEBUG -finline-limit=20000 -fprofile-generate\"\n# CLIST[((g++))]=\"g++-4.2 -O3 -DNDEBUG -finline-limit=20000 -fprofile-use\"\n\n# CLIST[((g++))]=\"g++-4.3 -O3 -DNDEBUG\"\n#CLIST[((g++))]=\"g++-4.3 -O3 -DNDEBUG -finline-limit=20000\"\n# CLIST[((g++))]=\"g++-4.3 -O3 -DNDEBUG -finline-limit=20000 -fprofile-generate\"\n# CLIST[((g++))]=\"g++-4.3 -O3 -DNDEBUG -finline-limit=20000 -fprofile-use\"\n\n# CLIST[((g++))]=\"icpc -fast -DNDEBUG -fno-exceptions -no-inline-max-size -prof-genx\"\n# CLIST[((g++))]=\"icpc -fast -DNDEBUG -fno-exceptions -no-inline-max-size -prof-use\"\n\n#CLIST[((g++))]=\"/opt/intel/Compiler/11.1/072/bin/intel64/icpc -fast -DNDEBUG -fno-exceptions -no-inline-max-size -lrt\"\nCLIST[((g++))]=\"/home/orzel/svn/llvm/Release/bin/clang++ -O3 -DNDEBUG -DEIGEN_DONT_VECTORIZE -lrt\"\nCLIST[((g++))]=\"/home/orzel/svn/llvm/Release/bin/clang++ -O3 -DNDEBUG -lrt\"\nCLIST[((g++))]=\"g++-4.4.4 -O3 -DNDEBUG -DEIGEN_DONT_VECTORIZE -lrt\"\nCLIST[((g++))]=\"g++-4.4.4 -O3 -DNDEBUG -lrt\"\nCLIST[((g++))]=\"g++-4.5.0 -O3 -DNDEBUG -DEIGEN_DONT_VECTORIZE -lrt\"\nCLIST[((g++))]=\"g++-4.5.0 -O3 -DNDEBUG -lrt\"\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/basicbenchmark.cpp",
    "content": "\n#include <iostream>\n#include \"BenchUtil.h\"\n#include \"basicbenchmark.h\"\n\nint main(int argc, char *argv[])\n{\n  DISABLE_SSE_EXCEPTIONS();\n\n  // this is the list of matrix type and size we want to bench:\n  // ((suffix) (matrix size) (number of iterations))\n  #define MODES ((3d)(3)(4000000)) ((4d)(4)(1000000)) ((Xd)(4)(1000000)) ((Xd)(20)(10000))\n//   #define MODES ((Xd)(20)(10000))\n\n  #define _GENERATE_HEADER(R,ARG,EL) << BOOST_PP_STRINGIZE(BOOST_PP_SEQ_HEAD(EL)) << \"-\" \\\n    << BOOST_PP_STRINGIZE(BOOST_PP_SEQ_ELEM(1,EL)) << \"x\" \\\n    << BOOST_PP_STRINGIZE(BOOST_PP_SEQ_ELEM(1,EL)) << \"   /   \"\n\n  std::cout BOOST_PP_SEQ_FOR_EACH(_GENERATE_HEADER, ~, MODES ) << endl;\n\n  const int tries = 10;\n\n  #define _RUN_BENCH(R,ARG,EL) \\\n    std::cout << ARG( \\\n      BOOST_PP_CAT(Matrix, BOOST_PP_SEQ_HEAD(EL)) (\\\n         BOOST_PP_SEQ_ELEM(1,EL),BOOST_PP_SEQ_ELEM(1,EL)), BOOST_PP_SEQ_ELEM(2,EL), tries) \\\n    << \"   \";\n\n  BOOST_PP_SEQ_FOR_EACH(_RUN_BENCH, benchBasic<LazyEval>, MODES );\n  std::cout << endl;\n  BOOST_PP_SEQ_FOR_EACH(_RUN_BENCH, benchBasic<EarlyEval>, MODES );\n  std::cout << endl;\n\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/basicbenchmark.h",
    "content": "\n#ifndef EIGEN_BENCH_BASICBENCH_H\n#define EIGEN_BENCH_BASICBENCH_H\n\nenum {LazyEval, EarlyEval, OmpEval};\n\ntemplate<int Mode, typename MatrixType>\nvoid benchBasic_loop(const MatrixType& I, MatrixType& m, int iterations) __attribute__((noinline));\n\ntemplate<int Mode, typename MatrixType>\nvoid benchBasic_loop(const MatrixType& I, MatrixType& m, int iterations)\n{\n  for(int a = 0; a < iterations; a++)\n  {\n    if (Mode==LazyEval)\n    {\n      asm(\"#begin_bench_loop LazyEval\");\n      if (MatrixType::SizeAtCompileTime!=Eigen::Dynamic) asm(\"#fixedsize\");\n      m = (I + 0.00005 * (m + m.lazyProduct(m))).eval();\n    }\n    else if (Mode==OmpEval)\n    {\n      asm(\"#begin_bench_loop OmpEval\");\n      if (MatrixType::SizeAtCompileTime!=Eigen::Dynamic) asm(\"#fixedsize\");\n      m = (I + 0.00005 * (m + m.lazyProduct(m))).eval();\n    }\n    else\n    {\n      asm(\"#begin_bench_loop EarlyEval\");\n      if (MatrixType::SizeAtCompileTime!=Eigen::Dynamic) asm(\"#fixedsize\");\n      m = I + 0.00005 * (m + m * m);\n    }\n    asm(\"#end_bench_loop\");\n  }\n}\n\ntemplate<int Mode, typename MatrixType>\ndouble benchBasic(const MatrixType& mat, int size, int tries) __attribute__((noinline));\n\ntemplate<int Mode, typename MatrixType>\ndouble benchBasic(const MatrixType& mat, int iterations, int tries)\n{\n  const int rows = mat.rows();\n  const int cols = mat.cols();\n\n  MatrixType I(rows,cols);\n  MatrixType m(rows,cols);\n\n  initMatrix_identity(I);\n\n  Eigen::BenchTimer timer;\n  for(uint t=0; t<tries; ++t)\n  {\n    initMatrix_random(m);\n    timer.start();\n    benchBasic_loop<Mode>(I, m, iterations);\n    timer.stop();\n    cerr << m;\n  }\n  return timer.value();\n};\n\n#endif // EIGEN_BENCH_BASICBENCH_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/benchBlasGemm.cpp",
    "content": "// g++ -O3 -DNDEBUG -I.. -L /usr/lib64/atlas/ benchBlasGemm.cpp -o benchBlasGemm -lrt -lcblas\n// possible options:\n//    -DEIGEN_DONT_VECTORIZE\n//    -msse2\n\n// #define EIGEN_DEFAULT_TO_ROW_MAJOR\n#define _FLOAT\n\n#include <iostream>\n\n#include <Eigen/Core>\n#include \"BenchTimer.h\"\n\n// include the BLAS headers\nextern \"C\" {\n#include <cblas.h>\n}\n#include <string>\n\n#ifdef _FLOAT\ntypedef float Scalar;\n#define CBLAS_GEMM cblas_sgemm\n#else\ntypedef double Scalar;\n#define CBLAS_GEMM cblas_dgemm\n#endif\n\n\ntypedef Eigen::Matrix<Scalar,Eigen::Dynamic,Eigen::Dynamic> MyMatrix;\nvoid bench_eigengemm(MyMatrix& mc, const MyMatrix& ma, const MyMatrix& mb, int nbloops);\nvoid check_product(int M, int N, int K);\nvoid check_product(void);\n\nint main(int argc, char *argv[])\n{\n  // disable SSE exceptions\n  #ifdef __GNUC__\n  {\n    int aux;\n    asm(\n    \"stmxcsr   %[aux]           \\n\\t\"\n    \"orl       $32832, %[aux]   \\n\\t\"\n    \"ldmxcsr   %[aux]           \\n\\t\"\n    : : [aux] \"m\" (aux));\n  }\n  #endif\n\n  int nbtries=1, nbloops=1, M, N, K;\n\n  if (argc==2)\n  {\n    if (std::string(argv[1])==\"check\")\n      check_product();\n    else\n      M = N = K = atoi(argv[1]);\n  }\n  else if ((argc==3) && (std::string(argv[1])==\"auto\"))\n  {\n    M = N = K = atoi(argv[2]);\n    nbloops = 1000000000/(M*M*M);\n    if (nbloops<1)\n      nbloops = 1;\n    nbtries = 6;\n  }\n  else if (argc==4)\n  {\n    M = N = K = atoi(argv[1]);\n    nbloops = atoi(argv[2]);\n    nbtries = atoi(argv[3]);\n  }\n  else if (argc==6)\n  {\n    M = atoi(argv[1]);\n    N = atoi(argv[2]);\n    K = atoi(argv[3]);\n    nbloops = atoi(argv[4]);\n    nbtries = atoi(argv[5]);\n  }\n  else\n  {\n    std::cout << \"Usage: \" << argv[0] << \" size  \\n\";\n    std::cout << \"Usage: \" << argv[0] << \" auto size\\n\";\n    std::cout << \"Usage: \" << argv[0] << \" size nbloops nbtries\\n\";\n    std::cout << \"Usage: \" << argv[0] << \" M N K nbloops nbtries\\n\";\n    std::cout << \"Usage: \" << argv[0] << \" check\\n\";\n    std::cout << \"Options:\\n\";\n    std::cout << \"    size       unique size of the 2 matrices (integer)\\n\";\n    std::cout << \"    auto       automatically set the number of repetitions and tries\\n\";\n    std::cout << \"    nbloops    number of times the GEMM routines is executed\\n\";\n    std::cout << \"    nbtries    number of times the loop is benched (return the best try)\\n\";\n    std::cout << \"    M N K      sizes of the matrices: MxN  =  MxK * KxN (integers)\\n\";\n    std::cout << \"    check      check eigen product using cblas as a reference\\n\";\n    exit(1);\n  }\n\n  double nbmad = double(M) * double(N) * double(K) * double(nbloops);\n\n  if (!(std::string(argv[1])==\"auto\"))\n    std::cout << M << \" x \" << N << \" x \" << K << \"\\n\";\n\n  Scalar alpha, beta;\n  MyMatrix ma(M,K), mb(K,N), mc(M,N);\n  ma = MyMatrix::Random(M,K);\n  mb = MyMatrix::Random(K,N);\n  mc = MyMatrix::Random(M,N);\n\n  Eigen::BenchTimer timer;\n\n  // we simply compute c += a*b, so:\n  alpha = 1;\n  beta = 1;\n\n  // bench cblas\n  // ROWS_A, COLS_B, COLS_A, 1.0,  A, COLS_A, B, COLS_B, 0.0, C, COLS_B);\n  if (!(std::string(argv[1])==\"auto\"))\n  {\n    timer.reset();\n    for (uint k=0 ; k<nbtries ; ++k)\n    {\n        timer.start();\n        for (uint j=0 ; j<nbloops ; ++j)\n              #ifdef EIGEN_DEFAULT_TO_ROW_MAJOR\n              CBLAS_GEMM(CblasRowMajor, CblasNoTrans, CblasNoTrans, M, N, K, alpha, ma.data(), K, mb.data(), N, beta, mc.data(), N);\n              #else\n              CBLAS_GEMM(CblasColMajor, CblasNoTrans, CblasNoTrans, M, N, K, alpha, ma.data(), M, mb.data(), K, beta, mc.data(), M);\n              #endif\n        timer.stop();\n    }\n    if (!(std::string(argv[1])==\"auto\"))\n      std::cout << \"cblas: \" << timer.value() << \" (\" << 1e-3*floor(1e-6*nbmad/timer.value()) << \" GFlops/s)\\n\";\n    else\n        std::cout << M << \" : \" << timer.value() << \" ; \" << 1e-3*floor(1e-6*nbmad/timer.value()) << \"\\n\";\n  }\n\n  // clear\n  ma = MyMatrix::Random(M,K);\n  mb = MyMatrix::Random(K,N);\n  mc = MyMatrix::Random(M,N);\n\n  // eigen\n//   if (!(std::string(argv[1])==\"auto\"))\n  {\n      timer.reset();\n      for (uint k=0 ; k<nbtries ; ++k)\n      {\n          timer.start();\n          bench_eigengemm(mc, ma, mb, nbloops);\n          timer.stop();\n      }\n      if (!(std::string(argv[1])==\"auto\"))\n        std::cout << \"eigen : \" << timer.value() << \" (\" << 1e-3*floor(1e-6*nbmad/timer.value()) << \" GFlops/s)\\n\";\n      else\n        std::cout << M << \" : \" << timer.value() << \" ; \" << 1e-3*floor(1e-6*nbmad/timer.value()) << \"\\n\";\n  }\n\n  std::cout << \"l1: \" << Eigen::l1CacheSize() << std::endl;\n  std::cout << \"l2: \" << Eigen::l2CacheSize() << std::endl;\n  \n\n  return 0;\n}\n\nusing namespace Eigen;\n\nvoid bench_eigengemm(MyMatrix& mc, const MyMatrix& ma, const MyMatrix& mb, int nbloops)\n{\n  for (uint j=0 ; j<nbloops ; ++j)\n      mc.noalias() += ma * mb;\n}\n\n#define MYVERIFY(A,M) if (!(A)) { \\\n    std::cout << \"FAIL: \" << M << \"\\n\"; \\\n  }\nvoid check_product(int M, int N, int K)\n{\n  MyMatrix ma(M,K), mb(K,N), mc(M,N), maT(K,M), mbT(N,K), meigen(M,N), mref(M,N);\n  ma = MyMatrix::Random(M,K);\n  mb = MyMatrix::Random(K,N);\n  maT = ma.transpose();\n  mbT = mb.transpose();\n  mc = MyMatrix::Random(M,N);\n\n  MyMatrix::Scalar eps = 1e-4;\n\n  meigen = mref = mc;\n  CBLAS_GEMM(CblasColMajor, CblasNoTrans, CblasNoTrans, M, N, K, 1, ma.data(), M, mb.data(), K, 1, mref.data(), M);\n  meigen += ma * mb;\n  MYVERIFY(meigen.isApprox(mref, eps),\". * .\");\n\n  meigen = mref = mc;\n  CBLAS_GEMM(CblasColMajor, CblasTrans, CblasNoTrans, M, N, K, 1, maT.data(), K, mb.data(), K, 1, mref.data(), M);\n  meigen += maT.transpose() * mb;\n  MYVERIFY(meigen.isApprox(mref, eps),\"T * .\");\n\n  meigen = mref = mc;\n  CBLAS_GEMM(CblasColMajor, CblasTrans, CblasTrans, M, N, K, 1, maT.data(), K, mbT.data(), N, 1, mref.data(), M);\n  meigen += (maT.transpose()) * (mbT.transpose());\n  MYVERIFY(meigen.isApprox(mref, eps),\"T * T\");\n\n  meigen = mref = mc;\n  CBLAS_GEMM(CblasColMajor, CblasNoTrans, CblasTrans, M, N, K, 1, ma.data(), M, mbT.data(), N, 1, mref.data(), M);\n  meigen += ma * mbT.transpose();\n  MYVERIFY(meigen.isApprox(mref, eps),\". * T\");\n}\n\nvoid check_product(void)\n{\n  int M, N, K;\n  for (uint i=0; i<1000; ++i)\n  {\n    M = internal::random<int>(1,64);\n    N = internal::random<int>(1,768);\n    K = internal::random<int>(1,768);\n    M = (0 + M) * 1;\n    std::cout << M << \" x \" << N << \" x \" << K << \"\\n\";\n    check_product(M, N, K);\n  }\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/benchCholesky.cpp",
    "content": "// g++ -DNDEBUG -O3 -I.. benchCholesky.cpp  -o benchCholesky && ./benchCholesky\n// options:\n//  -DBENCH_GSL -lgsl /usr/lib/libcblas.so.3\n//  -DEIGEN_DONT_VECTORIZE\n//  -msse2\n//  -DREPEAT=100\n//  -DTRIES=10\n//  -DSCALAR=double\n\n#include <iostream>\n\n#include <Eigen/Core>\n#include <Eigen/Cholesky>\n#include <bench/BenchUtil.h>\nusing namespace Eigen;\n\n#ifndef REPEAT\n#define REPEAT 10000\n#endif\n\n#ifndef TRIES\n#define TRIES 10\n#endif\n\ntypedef float Scalar;\n\ntemplate <typename MatrixType>\n__attribute__ ((noinline)) void benchLLT(const MatrixType& m)\n{\n  int rows = m.rows();\n  int cols = m.cols();\n\n  double cost = 0;\n  for (int j=0; j<rows; ++j)\n  {\n    int r = std::max(rows - j -1,0);\n    cost += 2*(r*j+r+j);\n  }\n\n  int repeats = (REPEAT*1000)/(rows*rows);\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> SquareMatrixType;\n\n  MatrixType a = MatrixType::Random(rows,cols);\n  SquareMatrixType covMat =  a * a.adjoint();\n\n  BenchTimer timerNoSqrt, timerSqrt;\n\n  Scalar acc = 0;\n  int r = internal::random<int>(0,covMat.rows()-1);\n  int c = internal::random<int>(0,covMat.cols()-1);\n  for (int t=0; t<TRIES; ++t)\n  {\n    timerNoSqrt.start();\n    for (int k=0; k<repeats; ++k)\n    {\n      LDLT<SquareMatrixType> cholnosqrt(covMat);\n      acc += cholnosqrt.matrixL().coeff(r,c);\n    }\n    timerNoSqrt.stop();\n  }\n\n  for (int t=0; t<TRIES; ++t)\n  {\n    timerSqrt.start();\n    for (int k=0; k<repeats; ++k)\n    {\n      LLT<SquareMatrixType> chol(covMat);\n      acc += chol.matrixL().coeff(r,c);\n    }\n    timerSqrt.stop();\n  }\n\n  if (MatrixType::RowsAtCompileTime==Dynamic)\n    std::cout << \"dyn   \";\n  else\n    std::cout << \"fixed \";\n  std::cout << covMat.rows() << \" \\t\"\n            << (timerNoSqrt.best()) / repeats << \"s \"\n            << \"(\" << 1e-9 * cost*repeats/timerNoSqrt.best() << \" GFLOPS)\\t\"\n            << (timerSqrt.best()) / repeats << \"s \"\n            << \"(\" << 1e-9 * cost*repeats/timerSqrt.best() << \" GFLOPS)\\n\";\n\n\n  #ifdef BENCH_GSL\n  if (MatrixType::RowsAtCompileTime==Dynamic)\n  {\n    timerSqrt.reset();\n\n    gsl_matrix* gslCovMat = gsl_matrix_alloc(covMat.rows(),covMat.cols());\n    gsl_matrix* gslCopy = gsl_matrix_alloc(covMat.rows(),covMat.cols());\n\n    eiToGsl(covMat, &gslCovMat);\n    for (int t=0; t<TRIES; ++t)\n    {\n      timerSqrt.start();\n      for (int k=0; k<repeats; ++k)\n      {\n        gsl_matrix_memcpy(gslCopy,gslCovMat);\n        gsl_linalg_cholesky_decomp(gslCopy);\n        acc += gsl_matrix_get(gslCopy,r,c);\n      }\n      timerSqrt.stop();\n    }\n\n    std::cout << \" | \\t\"\n              << timerSqrt.value() * REPEAT / repeats << \"s\";\n\n    gsl_matrix_free(gslCovMat);\n  }\n  #endif\n  std::cout << \"\\n\";\n  // make sure the compiler does not optimize too much\n  if (acc==123)\n    std::cout << acc;\n}\n\nint main(int argc, char* argv[])\n{\n  const int dynsizes[] = {4,6,8,16,24,32,49,64,128,256,512,900,1500,0};\n  std::cout << \"size            LDLT                            LLT\";\n//   #ifdef BENCH_GSL\n//   std::cout << \"       GSL (standard + double + ATLAS)  \";\n//   #endif\n  std::cout << \"\\n\";\n  for (int i=0; dynsizes[i]>0; ++i)\n    benchLLT(Matrix<Scalar,Dynamic,Dynamic>(dynsizes[i],dynsizes[i]));\n\n  benchLLT(Matrix<Scalar,2,2>());\n  benchLLT(Matrix<Scalar,3,3>());\n  benchLLT(Matrix<Scalar,4,4>());\n  benchLLT(Matrix<Scalar,5,5>());\n  benchLLT(Matrix<Scalar,6,6>());\n  benchLLT(Matrix<Scalar,7,7>());\n  benchLLT(Matrix<Scalar,8,8>());\n  benchLLT(Matrix<Scalar,12,12>());\n  benchLLT(Matrix<Scalar,16,16>());\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/benchEigenSolver.cpp",
    "content": "\n// g++ -DNDEBUG -O3 -I.. benchEigenSolver.cpp  -o benchEigenSolver && ./benchEigenSolver\n// options:\n//  -DBENCH_GMM\n//  -DBENCH_GSL -lgsl /usr/lib/libcblas.so.3\n//  -DEIGEN_DONT_VECTORIZE\n//  -msse2\n//  -DREPEAT=100\n//  -DTRIES=10\n//  -DSCALAR=double\n\n#include <iostream>\n\n#include <Eigen/Core>\n#include <Eigen/QR>\n#include <bench/BenchUtil.h>\nusing namespace Eigen;\n\n#ifndef REPEAT\n#define REPEAT 1000\n#endif\n\n#ifndef TRIES\n#define TRIES 4\n#endif\n\n#ifndef SCALAR\n#define SCALAR float\n#endif\n\ntypedef SCALAR Scalar;\n\ntemplate <typename MatrixType>\n__attribute__ ((noinline)) void benchEigenSolver(const MatrixType& m)\n{\n  int rows = m.rows();\n  int cols = m.cols();\n\n  int stdRepeats = std::max(1,int((REPEAT*1000)/(rows*rows*sqrt(rows))));\n  int saRepeats = stdRepeats * 4;\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> SquareMatrixType;\n\n  MatrixType a = MatrixType::Random(rows,cols);\n  SquareMatrixType covMat =  a * a.adjoint();\n\n  BenchTimer timerSa, timerStd;\n\n  Scalar acc = 0;\n  int r = internal::random<int>(0,covMat.rows()-1);\n  int c = internal::random<int>(0,covMat.cols()-1);\n  {\n    SelfAdjointEigenSolver<SquareMatrixType> ei(covMat);\n    for (int t=0; t<TRIES; ++t)\n    {\n      timerSa.start();\n      for (int k=0; k<saRepeats; ++k)\n      {\n        ei.compute(covMat);\n        acc += ei.eigenvectors().coeff(r,c);\n      }\n      timerSa.stop();\n    }\n  }\n\n  {\n    EigenSolver<SquareMatrixType> ei(covMat);\n    for (int t=0; t<TRIES; ++t)\n    {\n      timerStd.start();\n      for (int k=0; k<stdRepeats; ++k)\n      {\n        ei.compute(covMat);\n        acc += ei.eigenvectors().coeff(r,c);\n      }\n      timerStd.stop();\n    }\n  }\n\n  if (MatrixType::RowsAtCompileTime==Dynamic)\n    std::cout << \"dyn   \";\n  else\n    std::cout << \"fixed \";\n  std::cout << covMat.rows() << \" \\t\"\n            << timerSa.value() * REPEAT / saRepeats << \"s \\t\"\n            << timerStd.value() * REPEAT / stdRepeats << \"s\";\n\n  #ifdef BENCH_GMM\n  if (MatrixType::RowsAtCompileTime==Dynamic)\n  {\n    timerSa.reset();\n    timerStd.reset();\n\n    gmm::dense_matrix<Scalar> gmmCovMat(covMat.rows(),covMat.cols());\n    gmm::dense_matrix<Scalar> eigvect(covMat.rows(),covMat.cols());\n    std::vector<Scalar> eigval(covMat.rows());\n    eiToGmm(covMat, gmmCovMat);\n    for (int t=0; t<TRIES; ++t)\n    {\n      timerSa.start();\n      for (int k=0; k<saRepeats; ++k)\n      {\n        gmm::symmetric_qr_algorithm(gmmCovMat, eigval, eigvect);\n        acc += eigvect(r,c);\n      }\n      timerSa.stop();\n    }\n    // the non-selfadjoint solver does not compute the eigen vectors\n//     for (int t=0; t<TRIES; ++t)\n//     {\n//       timerStd.start();\n//       for (int k=0; k<stdRepeats; ++k)\n//       {\n//         gmm::implicit_qr_algorithm(gmmCovMat, eigval, eigvect);\n//         acc += eigvect(r,c);\n//       }\n//       timerStd.stop();\n//     }\n\n    std::cout << \" | \\t\"\n              << timerSa.value() * REPEAT / saRepeats << \"s\"\n              << /*timerStd.value() * REPEAT / stdRepeats << \"s\"*/ \"   na   \";\n  }\n  #endif\n\n  #ifdef BENCH_GSL\n  if (MatrixType::RowsAtCompileTime==Dynamic)\n  {\n    timerSa.reset();\n    timerStd.reset();\n\n    gsl_matrix* gslCovMat = gsl_matrix_alloc(covMat.rows(),covMat.cols());\n    gsl_matrix* gslCopy = gsl_matrix_alloc(covMat.rows(),covMat.cols());\n    gsl_matrix* eigvect = gsl_matrix_alloc(covMat.rows(),covMat.cols());\n    gsl_vector* eigval  = gsl_vector_alloc(covMat.rows());\n    gsl_eigen_symmv_workspace* eisymm = gsl_eigen_symmv_alloc(covMat.rows());\n    \n    gsl_matrix_complex* eigvectz = gsl_matrix_complex_alloc(covMat.rows(),covMat.cols());\n    gsl_vector_complex* eigvalz  = gsl_vector_complex_alloc(covMat.rows());\n    gsl_eigen_nonsymmv_workspace* einonsymm = gsl_eigen_nonsymmv_alloc(covMat.rows());\n    \n    eiToGsl(covMat, &gslCovMat);\n    for (int t=0; t<TRIES; ++t)\n    {\n      timerSa.start();\n      for (int k=0; k<saRepeats; ++k)\n      {\n        gsl_matrix_memcpy(gslCopy,gslCovMat);\n        gsl_eigen_symmv(gslCopy, eigval, eigvect, eisymm);\n        acc += gsl_matrix_get(eigvect,r,c);\n      }\n      timerSa.stop();\n    }\n    for (int t=0; t<TRIES; ++t)\n    {\n      timerStd.start();\n      for (int k=0; k<stdRepeats; ++k)\n      {\n        gsl_matrix_memcpy(gslCopy,gslCovMat);\n        gsl_eigen_nonsymmv(gslCopy, eigvalz, eigvectz, einonsymm);\n        acc += GSL_REAL(gsl_matrix_complex_get(eigvectz,r,c));\n      }\n      timerStd.stop();\n    }\n\n    std::cout << \" | \\t\"\n              << timerSa.value() * REPEAT / saRepeats << \"s \\t\"\n              << timerStd.value() * REPEAT / stdRepeats << \"s\";\n\n    gsl_matrix_free(gslCovMat);\n    gsl_vector_free(gslCopy);\n    gsl_matrix_free(eigvect);\n    gsl_vector_free(eigval);\n    gsl_matrix_complex_free(eigvectz);\n    gsl_vector_complex_free(eigvalz);\n    gsl_eigen_symmv_free(eisymm);\n    gsl_eigen_nonsymmv_free(einonsymm);\n  }\n  #endif\n\n  std::cout << \"\\n\";\n  \n  // make sure the compiler does not optimize too much\n  if (acc==123)\n    std::cout << acc;\n}\n\nint main(int argc, char* argv[])\n{\n  const int dynsizes[] = {4,6,8,12,16,24,32,64,128,256,512,0};\n  std::cout << \"size            selfadjoint       generic\";\n  #ifdef BENCH_GMM\n  std::cout << \"        GMM++          \";\n  #endif\n  #ifdef BENCH_GSL\n  std::cout << \"       GSL (double + ATLAS)  \";\n  #endif\n  std::cout << \"\\n\";\n  for (uint i=0; dynsizes[i]>0; ++i)\n    benchEigenSolver(Matrix<Scalar,Dynamic,Dynamic>(dynsizes[i],dynsizes[i]));\n\n  benchEigenSolver(Matrix<Scalar,2,2>());\n  benchEigenSolver(Matrix<Scalar,3,3>());\n  benchEigenSolver(Matrix<Scalar,4,4>());\n  benchEigenSolver(Matrix<Scalar,6,6>());\n  benchEigenSolver(Matrix<Scalar,8,8>());\n  benchEigenSolver(Matrix<Scalar,12,12>());\n  benchEigenSolver(Matrix<Scalar,16,16>());\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/benchFFT.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Mark Borgerding mark a borgerding net\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <iostream>\n\n#include <bench/BenchUtil.h>\n#include <complex>\n#include <vector>\n#include <Eigen/Core>\n\n#include <unsupported/Eigen/FFT>\n\nusing namespace Eigen;\nusing namespace std;\n\n\ntemplate <typename T>\nstring nameof();\n\ntemplate <> string nameof<float>() {return \"float\";}\ntemplate <> string nameof<double>() {return \"double\";}\ntemplate <> string nameof<long double>() {return \"long double\";}\n\n#ifndef TYPE\n#define TYPE float\n#endif\n\n#ifndef NFFT\n#define NFFT 1024\n#endif\n#ifndef NDATA\n#define NDATA 1000000\n#endif\n\nusing namespace Eigen;\n\ntemplate <typename T>\nvoid bench(int nfft,bool fwd,bool unscaled=false, bool halfspec=false)\n{\n    typedef typename NumTraits<T>::Real Scalar;\n    typedef typename std::complex<Scalar> Complex;\n    int nits = NDATA/nfft;\n    vector<T> inbuf(nfft);\n    vector<Complex > outbuf(nfft);\n    FFT< Scalar > fft;\n\n    if (unscaled) {\n        fft.SetFlag(fft.Unscaled);\n        cout << \"unscaled \";\n    }\n    if (halfspec) {\n        fft.SetFlag(fft.HalfSpectrum);\n        cout << \"halfspec \";\n    }\n\n\n    std::fill(inbuf.begin(),inbuf.end(),0);\n    fft.fwd( outbuf , inbuf);\n\n    BenchTimer timer;\n    timer.reset();\n    for (int k=0;k<8;++k) {\n        timer.start();\n        if (fwd)\n            for(int i = 0; i < nits; i++)\n                fft.fwd( outbuf , inbuf);\n        else\n            for(int i = 0; i < nits; i++)\n                fft.inv(inbuf,outbuf);\n        timer.stop();\n    }\n\n    cout << nameof<Scalar>() << \" \";\n    double mflops = 5.*nfft*log2((double)nfft) / (1e6 * timer.value() / (double)nits );\n    if ( NumTraits<T>::IsComplex ) {\n        cout << \"complex\";\n    }else{\n        cout << \"real   \";\n        mflops /= 2;\n    }\n\n\n    if (fwd)\n        cout << \" fwd\";\n    else\n        cout << \" inv\";\n\n    cout << \" NFFT=\" << nfft << \"  \" << (double(1e-6*nfft*nits)/timer.value()) << \" MS/s  \" << mflops << \"MFLOPS\\n\";\n}\n\nint main(int argc,char ** argv)\n{\n    bench<complex<float> >(NFFT,true);\n    bench<complex<float> >(NFFT,false);\n    bench<float>(NFFT,true);\n    bench<float>(NFFT,false);\n    bench<float>(NFFT,false,true);\n    bench<float>(NFFT,false,true,true);\n\n    bench<complex<double> >(NFFT,true);\n    bench<complex<double> >(NFFT,false);\n    bench<double>(NFFT,true);\n    bench<double>(NFFT,false);\n    bench<complex<long double> >(NFFT,true);\n    bench<complex<long double> >(NFFT,false);\n    bench<long double>(NFFT,true);\n    bench<long double>(NFFT,false);\n    return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/benchGeometry.cpp",
    "content": "#include <iostream>\n#include <iomanip>\n#include <Eigen/Core>\n#include <Eigen/Geometry>\n#include <bench/BenchTimer.h>\n\nusing namespace Eigen;\nusing namespace std;\n\n#ifndef REPEAT\n#define REPEAT 1000000\n#endif\n\nenum func_opt\n{\n    TV,\n    TMATV,\n    TMATVMAT,\n};\n\n\ntemplate <class res, class arg1, class arg2, int opt>\nstruct func;\n\ntemplate <class res, class arg1, class arg2>\nstruct func<res, arg1, arg2, TV>\n{\n    static EIGEN_DONT_INLINE res run( arg1& a1, arg2& a2 )\n    {\n\tasm (\"\");\n\treturn a1 * a2;\n    }\n};\n\ntemplate <class res, class arg1, class arg2>\nstruct func<res, arg1, arg2, TMATV>\n{\n    static EIGEN_DONT_INLINE res run( arg1& a1, arg2& a2 )\n    {\n\tasm (\"\");\n\treturn a1.matrix() * a2;\n    }\n};\n\ntemplate <class res, class arg1, class arg2>\nstruct func<res, arg1, arg2, TMATVMAT>\n{\n    static EIGEN_DONT_INLINE res run( arg1& a1, arg2& a2 )\n    {\n\tasm (\"\");\n\treturn res(a1.matrix() * a2.matrix());\n    }\n};\n\ntemplate <class func, class arg1, class arg2>\nstruct test_transform\n{\n    static void run()\n    {\n\targ1 a1;\n\ta1.setIdentity();\n\targ2 a2;\n\ta2.setIdentity();\n\n\tBenchTimer timer;\n\ttimer.reset();\n\tfor (int k=0; k<10; ++k)\n\t{\n\t    timer.start();\n\t    for (int k=0; k<REPEAT; ++k)\n\t\ta2 = func::run( a1, a2 );\n\t    timer.stop();\n\t}\n\tcout << setprecision(4) << fixed << timer.value() << \"s  \" << endl;;\n    }\n};\n\n\n#define run_vec( op, scalar, mode, option, vsize ) \\\n    std::cout << #scalar << \"\\t \" << #mode << \"\\t \" << #option << \" \" << #vsize \" \"; \\\n    {\\\n\ttypedef Transform<scalar, 3, mode, option> Trans;\\\n\ttypedef Matrix<scalar, vsize, 1, option> Vec;\\\n\ttypedef func<Vec,Trans,Vec,op> Func;\\\n\ttest_transform< Func, Trans, Vec >::run();\\\n    }\n\n#define run_trans( op, scalar, mode, option ) \\\n    std::cout << #scalar << \"\\t \" << #mode << \"\\t \" << #option << \"   \"; \\\n    {\\\n\ttypedef Transform<scalar, 3, mode, option> Trans;\\\n\ttypedef func<Trans,Trans,Trans,op> Func;\\\n\ttest_transform< Func, Trans, Trans >::run();\\\n    }\n\nint main(int argc, char* argv[])\n{\n    cout << \"vec = trans * vec\" << endl;\n    run_vec(TV, float,  Isometry, AutoAlign, 3);\n    run_vec(TV, float,  Isometry, DontAlign, 3);\n    run_vec(TV, float,  Isometry, AutoAlign, 4);\n    run_vec(TV, float,  Isometry, DontAlign, 4);\n    run_vec(TV, float,  Projective, AutoAlign, 4);\n    run_vec(TV, float,  Projective, DontAlign, 4);\n    run_vec(TV, double, Isometry, AutoAlign, 3);\n    run_vec(TV, double, Isometry, DontAlign, 3);\n    run_vec(TV, double, Isometry, AutoAlign, 4);\n    run_vec(TV, double, Isometry, DontAlign, 4);\n    run_vec(TV, double, Projective, AutoAlign, 4);\n    run_vec(TV, double, Projective, DontAlign, 4);\n\n    cout << \"vec = trans.matrix() * vec\" << endl;\n    run_vec(TMATV, float,  Isometry, AutoAlign, 4);\n    run_vec(TMATV, float,  Isometry, DontAlign, 4);\n    run_vec(TMATV, double, Isometry, AutoAlign, 4);\n    run_vec(TMATV, double, Isometry, DontAlign, 4);\n\n    cout << \"trans = trans1 * trans\" << endl;\n    run_trans(TV, float,  Isometry, AutoAlign);\n    run_trans(TV, float,  Isometry, DontAlign);\n    run_trans(TV, double, Isometry, AutoAlign);\n    run_trans(TV, double, Isometry, DontAlign);\n    run_trans(TV, float,  Projective, AutoAlign);\n    run_trans(TV, float,  Projective, DontAlign);\n    run_trans(TV, double, Projective, AutoAlign);\n    run_trans(TV, double, Projective, DontAlign);\n\n    cout << \"trans = trans1.matrix() * trans.matrix()\" << endl;\n    run_trans(TMATVMAT, float,  Isometry, AutoAlign);\n    run_trans(TMATVMAT, float,  Isometry, DontAlign);\n    run_trans(TMATVMAT, double, Isometry, AutoAlign);\n    run_trans(TMATVMAT, double, Isometry, DontAlign);\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/benchVecAdd.cpp",
    "content": "\n#include <iostream>\n#include <Eigen/Core>\n#include <bench/BenchTimer.h>\nusing namespace Eigen;\n\n#ifndef SIZE\n#define SIZE 50\n#endif\n\n#ifndef REPEAT\n#define REPEAT 10000\n#endif\n\ntypedef float Scalar;\n\n__attribute__ ((noinline)) void benchVec(Scalar* a, Scalar* b, Scalar* c, int size);\n__attribute__ ((noinline)) void benchVec(MatrixXf& a, MatrixXf& b, MatrixXf& c);\n__attribute__ ((noinline)) void benchVec(VectorXf& a, VectorXf& b, VectorXf& c);\n\nint main(int argc, char* argv[])\n{\n    int size = SIZE * 8;\n    int size2 = size * size;\n    Scalar* a = internal::aligned_new<Scalar>(size2);\n    Scalar* b = internal::aligned_new<Scalar>(size2+4)+1;\n    Scalar* c = internal::aligned_new<Scalar>(size2); \n    \n    for (int i=0; i<size; ++i)\n    {\n        a[i] = b[i] = c[i] = 0;\n    }\n    \n    BenchTimer timer;\n    \n    timer.reset();\n    for (int k=0; k<10; ++k)\n    {\n        timer.start();\n        benchVec(a, b, c, size2);\n        timer.stop();\n    }\n    std::cout << timer.value() << \"s  \" << (double(size2*REPEAT)/timer.value())/(1024.*1024.*1024.) << \" GFlops\\n\";\n    return 0;\n    for (int innersize = size; innersize>2 ; --innersize)\n    {\n        if (size2%innersize==0)\n        {\n            int outersize = size2/innersize;\n            MatrixXf ma = Map<MatrixXf>(a, innersize, outersize );\n            MatrixXf mb = Map<MatrixXf>(b, innersize, outersize );\n            MatrixXf mc = Map<MatrixXf>(c, innersize, outersize );\n            timer.reset();\n            for (int k=0; k<3; ++k)\n            {\n                timer.start();\n                benchVec(ma, mb, mc);\n                timer.stop();\n            }\n            std::cout << innersize << \" x \" << outersize << \"  \" << timer.value() << \"s   \" << (double(size2*REPEAT)/timer.value())/(1024.*1024.*1024.) << \" GFlops\\n\";\n        }\n    }\n    \n    VectorXf va = Map<VectorXf>(a, size2);\n    VectorXf vb = Map<VectorXf>(b, size2);\n    VectorXf vc = Map<VectorXf>(c, size2);\n    timer.reset();\n    for (int k=0; k<3; ++k)\n    {\n        timer.start();\n        benchVec(va, vb, vc);\n        timer.stop();\n    }\n    std::cout << timer.value() << \"s   \" << (double(size2*REPEAT)/timer.value())/(1024.*1024.*1024.) << \" GFlops\\n\";\n\n    return 0;\n}\n\nvoid benchVec(MatrixXf& a, MatrixXf& b, MatrixXf& c)\n{\n    for (int k=0; k<REPEAT; ++k)\n        a = a + b;\n}\n\nvoid benchVec(VectorXf& a, VectorXf& b, VectorXf& c)\n{\n    for (int k=0; k<REPEAT; ++k)\n        a = a + b;\n}\n\nvoid benchVec(Scalar* a, Scalar* b, Scalar* c, int size)\n{\n    typedef internal::packet_traits<Scalar>::type PacketScalar;\n    const int PacketSize = internal::packet_traits<Scalar>::size;\n    PacketScalar a0, a1, a2, a3, b0, b1, b2, b3;\n    for (int k=0; k<REPEAT; ++k)\n        for (int i=0; i<size; i+=PacketSize*8)\n        {\n//             a0 = internal::pload(&a[i]);\n//             b0 = internal::pload(&b[i]);\n//             a1 = internal::pload(&a[i+1*PacketSize]);\n//             b1 = internal::pload(&b[i+1*PacketSize]);\n//             a2 = internal::pload(&a[i+2*PacketSize]);\n//             b2 = internal::pload(&b[i+2*PacketSize]);\n//             a3 = internal::pload(&a[i+3*PacketSize]);\n//             b3 = internal::pload(&b[i+3*PacketSize]);\n//             internal::pstore(&a[i], internal::padd(a0, b0));\n//             a0 = internal::pload(&a[i+4*PacketSize]);\n//             b0 = internal::pload(&b[i+4*PacketSize]);\n//             \n//             internal::pstore(&a[i+1*PacketSize], internal::padd(a1, b1));\n//             a1 = internal::pload(&a[i+5*PacketSize]);\n//             b1 = internal::pload(&b[i+5*PacketSize]);\n//             \n//             internal::pstore(&a[i+2*PacketSize], internal::padd(a2, b2));\n//             a2 = internal::pload(&a[i+6*PacketSize]);\n//             b2 = internal::pload(&b[i+6*PacketSize]);\n//             \n//             internal::pstore(&a[i+3*PacketSize], internal::padd(a3, b3));\n//             a3 = internal::pload(&a[i+7*PacketSize]);\n//             b3 = internal::pload(&b[i+7*PacketSize]);\n//             \n//             internal::pstore(&a[i+4*PacketSize], internal::padd(a0, b0));\n//             internal::pstore(&a[i+5*PacketSize], internal::padd(a1, b1));\n//             internal::pstore(&a[i+6*PacketSize], internal::padd(a2, b2));\n//             internal::pstore(&a[i+7*PacketSize], internal::padd(a3, b3));\n            \n            internal::pstore(&a[i+2*PacketSize], internal::padd(internal::ploadu(&a[i+2*PacketSize]), internal::ploadu(&b[i+2*PacketSize])));\n            internal::pstore(&a[i+3*PacketSize], internal::padd(internal::ploadu(&a[i+3*PacketSize]), internal::ploadu(&b[i+3*PacketSize])));\n            internal::pstore(&a[i+4*PacketSize], internal::padd(internal::ploadu(&a[i+4*PacketSize]), internal::ploadu(&b[i+4*PacketSize])));\n            internal::pstore(&a[i+5*PacketSize], internal::padd(internal::ploadu(&a[i+5*PacketSize]), internal::ploadu(&b[i+5*PacketSize])));\n            internal::pstore(&a[i+6*PacketSize], internal::padd(internal::ploadu(&a[i+6*PacketSize]), internal::ploadu(&b[i+6*PacketSize])));\n            internal::pstore(&a[i+7*PacketSize], internal::padd(internal::ploadu(&a[i+7*PacketSize]), internal::ploadu(&b[i+7*PacketSize])));\n        }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/bench_gemm.cpp",
    "content": "\n// g++-4.4 bench_gemm.cpp -I .. -O2 -DNDEBUG -lrt -fopenmp && OMP_NUM_THREADS=2  ./a.out\n// icpc bench_gemm.cpp -I .. -O3 -DNDEBUG -lrt -openmp  && OMP_NUM_THREADS=2  ./a.out\n\n// Compilation options:\n// \n// -DSCALAR=std::complex<double>\n// -DSCALARA=double or -DSCALARB=double\n// -DHAVE_BLAS\n// -DDECOUPLED\n//\n\n#include <iostream>\n#include <bench/BenchTimer.h>\n#include <Eigen/Core>\n\n\nusing namespace std;\nusing namespace Eigen;\n\n#ifndef SCALAR\n// #define SCALAR std::complex<float>\n#define SCALAR float\n#endif\n\n#ifndef SCALARA\n#define SCALARA SCALAR\n#endif\n\n#ifndef SCALARB\n#define SCALARB SCALAR\n#endif\n\n#ifdef ROWMAJ_A\nconst int opt_A = RowMajor;\n#else\nconst int opt_A = ColMajor;\n#endif\n\n#ifdef ROWMAJ_B\nconst int opt_B = RowMajor;\n#else\nconst int opt_B = ColMajor;\n#endif\n\ntypedef SCALAR Scalar;\ntypedef NumTraits<Scalar>::Real RealScalar;\ntypedef Matrix<SCALARA,Dynamic,Dynamic,opt_A> A;\ntypedef Matrix<SCALARB,Dynamic,Dynamic,opt_B> B;\ntypedef Matrix<Scalar,Dynamic,Dynamic> C;\ntypedef Matrix<RealScalar,Dynamic,Dynamic> M;\n\n#ifdef HAVE_BLAS\n\nextern \"C\" {\n  #include <Eigen/src/misc/blas.h>\n}\n\nstatic float fone = 1;\nstatic float fzero = 0;\nstatic double done = 1;\nstatic double szero = 0;\nstatic std::complex<float> cfone = 1;\nstatic std::complex<float> cfzero = 0;\nstatic std::complex<double> cdone = 1;\nstatic std::complex<double> cdzero = 0;\nstatic char notrans = 'N';\nstatic char trans = 'T';  \nstatic char nonunit = 'N';\nstatic char lower = 'L';\nstatic char right = 'R';\nstatic int intone = 1;\n\n#ifdef ROWMAJ_A\nconst char transA = trans;\n#else\nconst char transA = notrans;\n#endif\n\n#ifdef ROWMAJ_B\nconst char transB = trans;\n#else\nconst char transB = notrans;\n#endif\n\ntemplate<typename A,typename B>\nvoid blas_gemm(const A& a, const B& b, MatrixXf& c)\n{\n  int M = c.rows(); int N = c.cols(); int K = a.cols();\n  int lda = a.outerStride(); int ldb = b.outerStride(); int ldc = c.rows();\n\n  sgemm_(&transA,&transB,&M,&N,&K,&fone,\n         const_cast<float*>(a.data()),&lda,\n         const_cast<float*>(b.data()),&ldb,&fone,\n         c.data(),&ldc);\n}\n\ntemplate<typename A,typename B>\nvoid blas_gemm(const A& a, const B& b, MatrixXd& c)\n{\n  int M = c.rows(); int N = c.cols(); int K = a.cols();\n  int lda = a.outerStride(); int ldb = b.outerStride(); int ldc = c.rows();\n\n  dgemm_(&transA,&transB,&M,&N,&K,&done,\n         const_cast<double*>(a.data()),&lda,\n         const_cast<double*>(b.data()),&ldb,&done,\n         c.data(),&ldc);\n}\n\ntemplate<typename A,typename B>\nvoid blas_gemm(const A& a, const B& b, MatrixXcf& c)\n{\n  int M = c.rows(); int N = c.cols(); int K = a.cols();\n  int lda = a.outerStride(); int ldb = b.outerStride(); int ldc = c.rows();\n\n  cgemm_(&transA,&transB,&M,&N,&K,(float*)&cfone,\n         const_cast<float*>((const float*)a.data()),&lda,\n         const_cast<float*>((const float*)b.data()),&ldb,(float*)&cfone,\n         (float*)c.data(),&ldc);\n}\n\ntemplate<typename A,typename B>\nvoid blas_gemm(const A& a, const B& b, MatrixXcd& c)\n{\n  int M = c.rows(); int N = c.cols(); int K = a.cols();\n  int lda = a.outerStride(); int ldb = b.outerStride(); int ldc = c.rows();\n\n  zgemm_(&transA,&transB,&M,&N,&K,(double*)&cdone,\n         const_cast<double*>((const double*)a.data()),&lda,\n         const_cast<double*>((const double*)b.data()),&ldb,(double*)&cdone,\n         (double*)c.data(),&ldc);\n}\n\n\n\n#endif\n\nvoid matlab_cplx_cplx(const M& ar, const M& ai, const M& br, const M& bi, M& cr, M& ci)\n{\n  cr.noalias() += ar * br;\n  cr.noalias() -= ai * bi;\n  ci.noalias() += ar * bi;\n  ci.noalias() += ai * br;\n  // [cr ci] += [ar ai] * br + [-ai ar] * bi\n}\n\nvoid matlab_real_cplx(const M& a, const M& br, const M& bi, M& cr, M& ci)\n{\n  cr.noalias() += a * br;\n  ci.noalias() += a * bi;\n}\n\nvoid matlab_cplx_real(const M& ar, const M& ai, const M& b, M& cr, M& ci)\n{\n  cr.noalias() += ar * b;\n  ci.noalias() += ai * b;\n}\n\n\n\ntemplate<typename A, typename B, typename C>\nEIGEN_DONT_INLINE void gemm(const A& a, const B& b, C& c)\n{\n  c.noalias() += a * b;\n}\n\nint main(int argc, char ** argv)\n{\n  std::ptrdiff_t l1 = internal::queryL1CacheSize();\n  std::ptrdiff_t l2 = internal::queryTopLevelCacheSize();\n  std::cout << \"L1 cache size     = \" << (l1>0 ? l1/1024 : -1) << \" KB\\n\";\n  std::cout << \"L2/L3 cache size  = \" << (l2>0 ? l2/1024 : -1) << \" KB\\n\";\n  typedef internal::gebp_traits<Scalar,Scalar> Traits;\n  std::cout << \"Register blocking = \" << Traits::mr << \" x \" << Traits::nr << \"\\n\";\n\n  int rep = 1;    // number of repetitions per try\n  int tries = 2;  // number of tries, we keep the best\n\n  int s = 2048;\n  int m = s;\n  int n = s;\n  int p = s;\n  int cache_size1=-1, cache_size2=l2, cache_size3 = 0;\n\n  bool need_help = false;\n  for (int i=1; i<argc;)\n  {\n    if(argv[i][0]=='-')\n    {\n      if(argv[i][1]=='s')\n      {\n        ++i;\n        s = atoi(argv[i++]);\n        m = n = p = s;\n        if(argv[i][0]!='-')\n        {\n          n = atoi(argv[i++]);\n          p = atoi(argv[i++]);\n        }\n      }\n      else if(argv[i][1]=='c')\n      {\n        ++i;\n        cache_size1 = atoi(argv[i++]);\n        if(argv[i][0]!='-')\n        {\n          cache_size2 = atoi(argv[i++]);\n          if(argv[i][0]!='-')\n            cache_size3 = atoi(argv[i++]);\n        }\n      }\n      else if(argv[i][1]=='t')\n      {\n        tries = atoi(argv[++i]);\n        ++i;\n      }\n      else if(argv[i][1]=='p')\n      {\n        ++i;\n        rep = atoi(argv[i++]);\n      }\n    }\n    else\n    {\n      need_help = true;\n      break;\n    }\n  }\n\n  if(need_help)\n  {\n    std::cout << argv[0] << \" -s <matrix sizes> -c <cache sizes> -t <nb tries> -p <nb repeats>\\n\";\n    std::cout << \"   <matrix sizes> : size\\n\";\n    std::cout << \"   <matrix sizes> : rows columns depth\\n\";\n    return 1;\n  }\n\n#if EIGEN_VERSION_AT_LEAST(3,2,90)\n  if(cache_size1>0)\n    setCpuCacheSizes(cache_size1,cache_size2,cache_size3);\n#endif\n  \n  A a(m,p); a.setRandom();\n  B b(p,n); b.setRandom();\n  C c(m,n); c.setOnes();\n  C rc = c;\n\n  std::cout << \"Matrix sizes = \" << m << \"x\" << p << \" * \" << p << \"x\" << n << \"\\n\";\n  std::ptrdiff_t mc(m), nc(n), kc(p);\n  internal::computeProductBlockingSizes<Scalar,Scalar>(kc, mc, nc);\n  std::cout << \"blocking size (mc x kc) = \" << mc << \" x \" << kc << \" x \" << nc << \"\\n\";\n\n  C r = c;\n\n  // check the parallel product is correct\n  #if defined EIGEN_HAS_OPENMP\n  Eigen::initParallel();\n  int procs = omp_get_max_threads();\n  if(procs>1)\n  {\n    #ifdef HAVE_BLAS\n    blas_gemm(a,b,r);\n    #else\n    omp_set_num_threads(1);\n    r.noalias() += a * b;\n    omp_set_num_threads(procs);\n    #endif\n    c.noalias() += a * b;\n    if(!r.isApprox(c)) std::cerr << \"Warning, your parallel product is crap!\\n\\n\";\n  }\n  #elif defined HAVE_BLAS\n    blas_gemm(a,b,r);\n    c.noalias() += a * b;\n    if(!r.isApprox(c)) {\n      std::cout << (r  - c).norm()/r.norm() << \"\\n\";\n      std::cerr << \"Warning, your product is crap!\\n\\n\";\n    }\n  #else\n    if(1.*m*n*p<2000.*2000*2000)\n    {\n      gemm(a,b,c);\n      r.noalias() += a.cast<Scalar>() .lazyProduct( b.cast<Scalar>() );\n      if(!r.isApprox(c)) {\n        std::cout << (r  - c).norm()/r.norm() << \"\\n\";\n        std::cerr << \"Warning, your product is crap!\\n\\n\";\n      }\n    }\n  #endif\n\n  #ifdef HAVE_BLAS\n  BenchTimer tblas;\n  c = rc;\n  BENCH(tblas, tries, rep, blas_gemm(a,b,c));\n  std::cout << \"blas  cpu         \" << tblas.best(CPU_TIMER)/rep  << \"s  \\t\" << (double(m)*n*p*rep*2/tblas.best(CPU_TIMER))*1e-9  <<  \" GFLOPS \\t(\" << tblas.total(CPU_TIMER)  << \"s)\\n\";\n  std::cout << \"blas  real        \" << tblas.best(REAL_TIMER)/rep << \"s  \\t\" << (double(m)*n*p*rep*2/tblas.best(REAL_TIMER))*1e-9 <<  \" GFLOPS \\t(\" << tblas.total(REAL_TIMER) << \"s)\\n\";\n  #endif\n\n  // warm start\n  if(b.norm()+a.norm()==123.554) std::cout << \"\\n\";\n\n  BenchTimer tmt;\n  c = rc;\n  BENCH(tmt, tries, rep, gemm(a,b,c));\n  std::cout << \"eigen cpu         \" << tmt.best(CPU_TIMER)/rep  << \"s  \\t\" << (double(m)*n*p*rep*2/tmt.best(CPU_TIMER))*1e-9  <<  \" GFLOPS \\t(\" << tmt.total(CPU_TIMER)  << \"s)\\n\";\n  std::cout << \"eigen real        \" << tmt.best(REAL_TIMER)/rep << \"s  \\t\" << (double(m)*n*p*rep*2/tmt.best(REAL_TIMER))*1e-9 <<  \" GFLOPS \\t(\" << tmt.total(REAL_TIMER) << \"s)\\n\";\n\n  #ifdef EIGEN_HAS_OPENMP\n  if(procs>1)\n  {\n    BenchTimer tmono;\n    omp_set_num_threads(1);\n    Eigen::setNbThreads(1);\n    c = rc;\n    BENCH(tmono, tries, rep, gemm(a,b,c));\n    std::cout << \"eigen mono cpu    \" << tmono.best(CPU_TIMER)/rep  << \"s  \\t\" << (double(m)*n*p*rep*2/tmono.best(CPU_TIMER))*1e-9  <<  \" GFLOPS \\t(\" << tmono.total(CPU_TIMER)  << \"s)\\n\";\n    std::cout << \"eigen mono real   \" << tmono.best(REAL_TIMER)/rep << \"s  \\t\" << (double(m)*n*p*rep*2/tmono.best(REAL_TIMER))*1e-9 <<  \" GFLOPS \\t(\" << tmono.total(REAL_TIMER) << \"s)\\n\";\n    std::cout << \"mt speed up x\" << tmono.best(CPU_TIMER) / tmt.best(REAL_TIMER)  << \" => \" << (100.0*tmono.best(CPU_TIMER) / tmt.best(REAL_TIMER))/procs << \"%\\n\";\n  }\n  #endif\n  \n  if(1.*m*n*p<30*30*30)\n  {\n    BenchTimer tmt;\n    c = rc;\n    BENCH(tmt, tries, rep, c.noalias()+=a.lazyProduct(b));\n    std::cout << \"lazy cpu         \" << tmt.best(CPU_TIMER)/rep  << \"s  \\t\" << (double(m)*n*p*rep*2/tmt.best(CPU_TIMER))*1e-9  <<  \" GFLOPS \\t(\" << tmt.total(CPU_TIMER)  << \"s)\\n\";\n    std::cout << \"lazy real        \" << tmt.best(REAL_TIMER)/rep << \"s  \\t\" << (double(m)*n*p*rep*2/tmt.best(REAL_TIMER))*1e-9 <<  \" GFLOPS \\t(\" << tmt.total(REAL_TIMER) << \"s)\\n\";\n  }\n  \n  #ifdef DECOUPLED\n  if((NumTraits<A::Scalar>::IsComplex) && (NumTraits<B::Scalar>::IsComplex))\n  {\n    M ar(m,p); ar.setRandom();\n    M ai(m,p); ai.setRandom();\n    M br(p,n); br.setRandom();\n    M bi(p,n); bi.setRandom();\n    M cr(m,n); cr.setRandom();\n    M ci(m,n); ci.setRandom();\n    \n    BenchTimer t;\n    BENCH(t, tries, rep, matlab_cplx_cplx(ar,ai,br,bi,cr,ci));\n    std::cout << \"\\\"matlab\\\" cpu    \" << t.best(CPU_TIMER)/rep  << \"s  \\t\" << (double(m)*n*p*rep*2/t.best(CPU_TIMER))*1e-9  <<  \" GFLOPS \\t(\" << t.total(CPU_TIMER)  << \"s)\\n\";\n    std::cout << \"\\\"matlab\\\" real   \" << t.best(REAL_TIMER)/rep << \"s  \\t\" << (double(m)*n*p*rep*2/t.best(REAL_TIMER))*1e-9 <<  \" GFLOPS \\t(\" << t.total(REAL_TIMER) << \"s)\\n\";\n  }\n  if((!NumTraits<A::Scalar>::IsComplex) && (NumTraits<B::Scalar>::IsComplex))\n  {\n    M a(m,p);  a.setRandom();\n    M br(p,n); br.setRandom();\n    M bi(p,n); bi.setRandom();\n    M cr(m,n); cr.setRandom();\n    M ci(m,n); ci.setRandom();\n    \n    BenchTimer t;\n    BENCH(t, tries, rep, matlab_real_cplx(a,br,bi,cr,ci));\n    std::cout << \"\\\"matlab\\\" cpu    \" << t.best(CPU_TIMER)/rep  << \"s  \\t\" << (double(m)*n*p*rep*2/t.best(CPU_TIMER))*1e-9  <<  \" GFLOPS \\t(\" << t.total(CPU_TIMER)  << \"s)\\n\";\n    std::cout << \"\\\"matlab\\\" real   \" << t.best(REAL_TIMER)/rep << \"s  \\t\" << (double(m)*n*p*rep*2/t.best(REAL_TIMER))*1e-9 <<  \" GFLOPS \\t(\" << t.total(REAL_TIMER) << \"s)\\n\";\n  }\n  if((NumTraits<A::Scalar>::IsComplex) && (!NumTraits<B::Scalar>::IsComplex))\n  {\n    M ar(m,p); ar.setRandom();\n    M ai(m,p); ai.setRandom();\n    M b(p,n);  b.setRandom();\n    M cr(m,n); cr.setRandom();\n    M ci(m,n); ci.setRandom();\n    \n    BenchTimer t;\n    BENCH(t, tries, rep, matlab_cplx_real(ar,ai,b,cr,ci));\n    std::cout << \"\\\"matlab\\\" cpu    \" << t.best(CPU_TIMER)/rep  << \"s  \\t\" << (double(m)*n*p*rep*2/t.best(CPU_TIMER))*1e-9  <<  \" GFLOPS \\t(\" << t.total(CPU_TIMER)  << \"s)\\n\";\n    std::cout << \"\\\"matlab\\\" real   \" << t.best(REAL_TIMER)/rep << \"s  \\t\" << (double(m)*n*p*rep*2/t.best(REAL_TIMER))*1e-9 <<  \" GFLOPS \\t(\" << t.total(REAL_TIMER) << \"s)\\n\";\n  }\n  #endif\n\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/bench_move_semantics.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2020 Sebastien Boisvert <seb@boisvert.info>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"BenchTimer.h\"\n#include \"../test/MovableScalar.h\"\n\n#include <Eigen/Core>\n\n#include <iostream>\n#include <utility>\n\ntemplate <typename MatrixType>\nvoid copy_matrix(MatrixType& m)\n{\n  MatrixType tmp(m);\n  m = tmp;\n}\n\ntemplate <typename MatrixType>\nvoid move_matrix(MatrixType&& m)\n{\n  MatrixType tmp(std::move(m));\n  m = std::move(tmp);\n}\n\ntemplate<typename Scalar>\nvoid bench(const std::string& label)\n{\n  using MatrixType = Eigen::Matrix<Eigen::MovableScalar<Scalar>,1,10>;\n  Eigen::BenchTimer t;\n\n  int tries = 10;\n  int rep = 1000000;\n\n  MatrixType data = MatrixType::Random().eval();\n  MatrixType dest;\n\n  BENCH(t, tries, rep, copy_matrix(data));\n  std::cout << label << \" copy semantics: \" << 1e3*t.best(Eigen::CPU_TIMER) << \" ms\" << std::endl;\n\n  BENCH(t, tries, rep, move_matrix(std::move(data)));\n  std::cout << label << \" move semantics: \" << 1e3*t.best(Eigen::CPU_TIMER) << \" ms\" << std::endl;\n}\n\nint main()\n{\n  bench<float>(\"float\");\n  bench<double>(\"double\");\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/bench_multi_compilers.sh",
    "content": "#!/bin/bash\n\nif (($# < 2)); then\n    echo \"Usage: $0 compilerlist.txt benchfile.cpp\"\nelse\n\ncompilerlist=$1\nbenchfile=$2\n\ng=0\nsource $compilerlist\n\n# for each compiler, compile benchfile and run the benchmark\nfor (( i=0 ; i<g ; ++i )) ; do\n  # check the compiler exists\n  compiler=`echo ${CLIST[$i]} | cut -d \" \" -f 1`\n  if [ -e `which $compiler` ]; then\n    echo \"${CLIST[$i]}\"\n#     echo \"${CLIST[$i]} $benchfile -I.. -o bench~\"\n#     if [ -e ./.bench ] ; then rm .bench; fi\n    ${CLIST[$i]} $benchfile -I.. -o .bench && ./.bench 2> /dev/null\n    echo \"\"\n  else\n    echo \"compiler not found: $compiler\"\n  fi\ndone\n\nfi\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/bench_norm.cpp",
    "content": "#include <typeinfo>\n#include <iostream>\n#include <Eigen/Core>\n#include \"BenchTimer.h\"\nusing namespace Eigen;\nusing namespace std;\n\ntemplate<typename T>\nEIGEN_DONT_INLINE typename T::Scalar sqsumNorm(T& v)\n{\n  return v.norm();\n}\n\ntemplate<typename T>\nEIGEN_DONT_INLINE typename T::Scalar stableNorm(T& v)\n{\n  return v.stableNorm();\n}\n\ntemplate<typename T>\nEIGEN_DONT_INLINE typename T::Scalar hypotNorm(T& v)\n{\n  return v.hypotNorm();\n}\n\ntemplate<typename T>\nEIGEN_DONT_INLINE typename T::Scalar blueNorm(T& v)\n{\n  return v.blueNorm();\n}\n\ntemplate<typename T>\nEIGEN_DONT_INLINE typename T::Scalar lapackNorm(T& v)\n{\n  typedef typename T::Scalar Scalar;\n  int n = v.size();\n  Scalar scale = 0;\n  Scalar ssq = 1;\n  for (int i=0;i<n;++i)\n  {\n    Scalar ax = std::abs(v.coeff(i));\n    if (scale >= ax)\n    {\n      ssq += numext::abs2(ax/scale);\n    }\n    else\n    {\n      ssq = Scalar(1) + ssq * numext::abs2(scale/ax);\n      scale = ax;\n    }\n  }\n  return scale * std::sqrt(ssq);\n}\n\ntemplate<typename T>\nEIGEN_DONT_INLINE typename T::Scalar twopassNorm(T& v)\n{\n  typedef typename T::Scalar Scalar;\n  Scalar s = v.array().abs().maxCoeff();\n  return s*(v/s).norm();\n}\n\ntemplate<typename T>\nEIGEN_DONT_INLINE typename T::Scalar bl2passNorm(T& v)\n{\n  return v.stableNorm();\n}\n\ntemplate<typename T>\nEIGEN_DONT_INLINE typename T::Scalar divacNorm(T& v)\n{\n  int n =v.size() / 2;\n  for (int i=0;i<n;++i)\n    v(i) = v(2*i)*v(2*i) + v(2*i+1)*v(2*i+1);\n  n = n/2;\n  while (n>0)\n  {\n    for (int i=0;i<n;++i)\n      v(i) = v(2*i) + v(2*i+1);\n    n = n/2;\n  }\n  return std::sqrt(v(0));\n}\n\nnamespace Eigen {\nnamespace internal {\n#ifdef EIGEN_VECTORIZE\nPacket4f plt(const Packet4f& a, Packet4f& b) { return _mm_cmplt_ps(a,b); }\nPacket2d plt(const Packet2d& a, Packet2d& b) { return _mm_cmplt_pd(a,b); }\n\nPacket4f pandnot(const Packet4f& a, Packet4f& b) { return _mm_andnot_ps(a,b); }\nPacket2d pandnot(const Packet2d& a, Packet2d& b) { return _mm_andnot_pd(a,b); }\n#endif\n}\n}\n\ntemplate<typename T>\nEIGEN_DONT_INLINE typename T::Scalar pblueNorm(const T& v)\n{\n  #ifndef EIGEN_VECTORIZE\n  return v.blueNorm();\n  #else\n  typedef typename T::Scalar Scalar;\n\n  static int nmax = 0;\n  static Scalar b1, b2, s1m, s2m, overfl, rbig, relerr;\n  int n;\n\n  if(nmax <= 0)\n  {\n    int nbig, ibeta, it, iemin, iemax, iexp;\n    Scalar abig, eps;\n\n    nbig  = NumTraits<int>::highest();          // largest integer\n    ibeta = std::numeric_limits<Scalar>::radix; // NumTraits<Scalar>::Base;                    // base for floating-point numbers\n    it    = NumTraits<Scalar>::digits();        // NumTraits<Scalar>::Mantissa;                // number of base-beta digits in mantissa\n    iemin = NumTraits<Scalar>::min_exponent();  // minimum exponent\n    iemax = NumTraits<Scalar>::max_exponent();  // maximum exponent\n    rbig  = NumTraits<Scalar>::highest();       // largest floating-point number\n\n    // Check the basic machine-dependent constants.\n    if(iemin > 1 - 2*it || 1+it>iemax || (it==2 && ibeta<5)\n      || (it<=4 && ibeta <= 3 ) || it<2)\n    {\n      eigen_assert(false && \"the algorithm cannot be guaranteed on this computer\");\n    }\n    iexp  = -((1-iemin)/2);\n    b1    = std::pow(ibeta, iexp);  // lower boundary of midrange\n    iexp  = (iemax + 1 - it)/2;\n    b2    = std::pow(ibeta,iexp);   // upper boundary of midrange\n\n    iexp  = (2-iemin)/2;\n    s1m   = std::pow(ibeta,iexp);   // scaling factor for lower range\n    iexp  = - ((iemax+it)/2);\n    s2m   = std::pow(ibeta,iexp);   // scaling factor for upper range\n\n    overfl  = rbig*s2m;          // overflow boundary for abig\n    eps     = std::pow(ibeta, 1-it);\n    relerr  = std::sqrt(eps);      // tolerance for neglecting asml\n    abig    = 1.0/eps - 1.0;\n    if (Scalar(nbig)>abig)  nmax = abig;  // largest safe n\n    else                    nmax = nbig;\n  }\n\n  typedef typename internal::packet_traits<Scalar>::type Packet;\n  const int ps = internal::packet_traits<Scalar>::size;\n  Packet pasml = internal::pset1<Packet>(Scalar(0));\n  Packet pamed = internal::pset1<Packet>(Scalar(0));\n  Packet pabig = internal::pset1<Packet>(Scalar(0));\n  Packet ps2m = internal::pset1<Packet>(s2m);\n  Packet ps1m = internal::pset1<Packet>(s1m);\n  Packet pb2  = internal::pset1<Packet>(b2);\n  Packet pb1  = internal::pset1<Packet>(b1);\n  for(int j=0; j<v.size(); j+=ps)\n  {\n    Packet ax = internal::pabs(v.template packet<Aligned>(j));\n    Packet ax_s2m = internal::pmul(ax,ps2m);\n    Packet ax_s1m = internal::pmul(ax,ps1m);\n    Packet maskBig = internal::plt(pb2,ax);\n    Packet maskSml = internal::plt(ax,pb1);\n\n//     Packet maskMed = internal::pand(maskSml,maskBig);\n//     Packet scale = internal::pset1(Scalar(0));\n//     scale = internal::por(scale, internal::pand(maskBig,ps2m));\n//     scale = internal::por(scale, internal::pand(maskSml,ps1m));\n//     scale = internal::por(scale, internal::pandnot(internal::pset1(Scalar(1)),maskMed));\n//     ax = internal::pmul(ax,scale);\n//     ax = internal::pmul(ax,ax);\n//     pabig = internal::padd(pabig, internal::pand(maskBig, ax));\n//     pasml = internal::padd(pasml, internal::pand(maskSml, ax));\n//     pamed = internal::padd(pamed, internal::pandnot(ax,maskMed));\n\n\n    pabig = internal::padd(pabig, internal::pand(maskBig, internal::pmul(ax_s2m,ax_s2m)));\n    pasml = internal::padd(pasml, internal::pand(maskSml, internal::pmul(ax_s1m,ax_s1m)));\n    pamed = internal::padd(pamed, internal::pandnot(internal::pmul(ax,ax),internal::pand(maskSml,maskBig)));\n  }\n  Scalar abig = internal::predux(pabig);\n  Scalar asml = internal::predux(pasml);\n  Scalar amed = internal::predux(pamed);\n  if(abig > Scalar(0))\n  {\n    abig = std::sqrt(abig);\n    if(abig > overfl)\n    {\n      eigen_assert(false && \"overflow\");\n      return rbig;\n    }\n    if(amed > Scalar(0))\n    {\n      abig = abig/s2m;\n      amed = std::sqrt(amed);\n    }\n    else\n    {\n      return abig/s2m;\n    }\n\n  }\n  else if(asml > Scalar(0))\n  {\n    if (amed > Scalar(0))\n    {\n      abig = std::sqrt(amed);\n      amed = std::sqrt(asml) / s1m;\n    }\n    else\n    {\n      return std::sqrt(asml)/s1m;\n    }\n  }\n  else\n  {\n    return std::sqrt(amed);\n  }\n  asml = std::min(abig, amed);\n  abig = std::max(abig, amed);\n  if(asml <= abig*relerr)\n    return abig;\n  else\n    return abig * std::sqrt(Scalar(1) + numext::abs2(asml/abig));\n  #endif\n}\n\n#define BENCH_PERF(NRM) { \\\n  float af = 0; double ad = 0; std::complex<float> ac = 0; \\\n  Eigen::BenchTimer tf, td, tcf; tf.reset(); td.reset(); tcf.reset();\\\n  for (int k=0; k<tries; ++k) { \\\n    tf.start(); \\\n    for (int i=0; i<iters; ++i) { af += NRM(vf); } \\\n    tf.stop(); \\\n  } \\\n  for (int k=0; k<tries; ++k) { \\\n    td.start(); \\\n    for (int i=0; i<iters; ++i) { ad += NRM(vd); } \\\n    td.stop(); \\\n  } \\\n  /*for (int k=0; k<std::max(1,tries/3); ++k) { \\\n    tcf.start(); \\\n    for (int i=0; i<iters; ++i) { ac += NRM(vcf); } \\\n    tcf.stop(); \\\n  } */\\\n  std::cout << #NRM << \"\\t\" << tf.value() << \"   \" << td.value() <<  \"    \" << tcf.value() << \"\\n\"; \\\n}\n\nvoid check_accuracy(double basef, double based, int s)\n{\n  double yf = basef * std::abs(internal::random<double>());\n  double yd = based * std::abs(internal::random<double>());\n  VectorXf vf = VectorXf::Ones(s) * yf;\n  VectorXd vd = VectorXd::Ones(s) * yd;\n\n  std::cout << \"reference\\t\" << std::sqrt(double(s))*yf << \"\\t\" << std::sqrt(double(s))*yd << \"\\n\";\n  std::cout << \"sqsumNorm\\t\" << sqsumNorm(vf) << \"\\t\" << sqsumNorm(vd) << \"\\n\";\n  std::cout << \"hypotNorm\\t\" << hypotNorm(vf) << \"\\t\" << hypotNorm(vd) << \"\\n\";\n  std::cout << \"blueNorm\\t\" << blueNorm(vf) << \"\\t\" << blueNorm(vd) << \"\\n\";\n  std::cout << \"pblueNorm\\t\" << pblueNorm(vf) << \"\\t\" << pblueNorm(vd) << \"\\n\";\n  std::cout << \"lapackNorm\\t\" << lapackNorm(vf) << \"\\t\" << lapackNorm(vd) << \"\\n\";\n  std::cout << \"twopassNorm\\t\" << twopassNorm(vf) << \"\\t\" << twopassNorm(vd) << \"\\n\";\n  std::cout << \"bl2passNorm\\t\" << bl2passNorm(vf) << \"\\t\" << bl2passNorm(vd) << \"\\n\";\n}\n\nvoid check_accuracy_var(int ef0, int ef1, int ed0, int ed1, int s)\n{\n  VectorXf vf(s);\n  VectorXd vd(s);\n  for (int i=0; i<s; ++i)\n  {\n    vf[i] = std::abs(internal::random<double>()) * std::pow(double(10), internal::random<int>(ef0,ef1));\n    vd[i] = std::abs(internal::random<double>()) * std::pow(double(10), internal::random<int>(ed0,ed1));\n  }\n\n  //std::cout << \"reference\\t\" << internal::sqrt(double(s))*yf << \"\\t\" << internal::sqrt(double(s))*yd << \"\\n\";\n  std::cout << \"sqsumNorm\\t\"  << sqsumNorm(vf)  << \"\\t\" << sqsumNorm(vd)  << \"\\t\" << sqsumNorm(vf.cast<long double>()) << \"\\t\" << sqsumNorm(vd.cast<long double>()) << \"\\n\";\n  std::cout << \"hypotNorm\\t\"  << hypotNorm(vf)  << \"\\t\" << hypotNorm(vd)  << \"\\t\" << hypotNorm(vf.cast<long double>()) << \"\\t\" << hypotNorm(vd.cast<long double>()) << \"\\n\";\n  std::cout << \"blueNorm\\t\"   << blueNorm(vf)   << \"\\t\" << blueNorm(vd)   << \"\\t\" << blueNorm(vf.cast<long double>()) << \"\\t\" << blueNorm(vd.cast<long double>()) << \"\\n\";\n  std::cout << \"pblueNorm\\t\"  << pblueNorm(vf)  << \"\\t\" << pblueNorm(vd)  << \"\\t\" << blueNorm(vf.cast<long double>()) << \"\\t\" << blueNorm(vd.cast<long double>()) << \"\\n\";\n  std::cout << \"lapackNorm\\t\" << lapackNorm(vf) << \"\\t\" << lapackNorm(vd) << \"\\t\" << lapackNorm(vf.cast<long double>()) << \"\\t\" << lapackNorm(vd.cast<long double>()) << \"\\n\";\n  std::cout << \"twopassNorm\\t\" << twopassNorm(vf) << \"\\t\" << twopassNorm(vd) << \"\\t\" << twopassNorm(vf.cast<long double>()) << \"\\t\" << twopassNorm(vd.cast<long double>()) << \"\\n\";\n//   std::cout << \"bl2passNorm\\t\" << bl2passNorm(vf) << \"\\t\" << bl2passNorm(vd) << \"\\t\" << bl2passNorm(vf.cast<long double>()) << \"\\t\" << bl2passNorm(vd.cast<long double>()) << \"\\n\";\n}\n\nint main(int argc, char** argv)\n{\n  int tries = 10;\n  int iters = 100000;\n  double y = 1.1345743233455785456788e12 * internal::random<double>();\n  VectorXf v = VectorXf::Ones(1024) * y;\n\n// return 0;\n  int s = 10000;\n  double basef_ok = 1.1345743233455785456788e15;\n  double based_ok = 1.1345743233455785456788e95;\n\n  double basef_under = 1.1345743233455785456788e-27;\n  double based_under = 1.1345743233455785456788e-303;\n\n  double basef_over = 1.1345743233455785456788e+27;\n  double based_over = 1.1345743233455785456788e+302;\n\n  std::cout.precision(20);\n\n  std::cerr << \"\\nNo under/overflow:\\n\";\n  check_accuracy(basef_ok, based_ok, s);\n\n  std::cerr << \"\\nUnderflow:\\n\";\n  check_accuracy(basef_under, based_under, s);\n\n  std::cerr << \"\\nOverflow:\\n\";\n  check_accuracy(basef_over, based_over, s);\n\n  std::cerr << \"\\nVarying (over):\\n\";\n  for (int k=0; k<1; ++k)\n  {\n    check_accuracy_var(20,27,190,302,s);\n    std::cout << \"\\n\";\n  }\n\n  std::cerr << \"\\nVarying (under):\\n\";\n  for (int k=0; k<1; ++k)\n  {\n    check_accuracy_var(-27,20,-302,-190,s);\n    std::cout << \"\\n\";\n  }\n\n  y = 1;\n  std::cout.precision(4);\n  int s1 = 1024*1024*32;\n  std::cerr << \"Performance (out of cache, \" << s1 << \"):\\n\";\n  {\n    int iters = 1;\n    VectorXf vf = VectorXf::Random(s1) * y;\n    VectorXd vd = VectorXd::Random(s1) * y;\n    VectorXcf vcf = VectorXcf::Random(s1) * y;\n    BENCH_PERF(sqsumNorm);\n    BENCH_PERF(stableNorm);\n    BENCH_PERF(blueNorm);\n    BENCH_PERF(pblueNorm);\n    BENCH_PERF(lapackNorm);\n    BENCH_PERF(hypotNorm);\n    BENCH_PERF(twopassNorm);\n    BENCH_PERF(bl2passNorm);\n  }\n\n  std::cerr << \"\\nPerformance (in cache, \" << 512 << \"):\\n\";\n  {\n    int iters = 100000;\n    VectorXf vf = VectorXf::Random(512) * y;\n    VectorXd vd = VectorXd::Random(512) * y;\n    VectorXcf vcf = VectorXcf::Random(512) * y;\n    BENCH_PERF(sqsumNorm);\n    BENCH_PERF(stableNorm);\n    BENCH_PERF(blueNorm);\n    BENCH_PERF(pblueNorm);\n    BENCH_PERF(lapackNorm);\n    BENCH_PERF(hypotNorm);\n    BENCH_PERF(twopassNorm);\n    BENCH_PERF(bl2passNorm);\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/bench_reverse.cpp",
    "content": "\n#include <iostream>\n#include <Eigen/Core>\n#include <bench/BenchUtil.h>\nusing namespace Eigen;\n\n#ifndef REPEAT\n#define REPEAT 100000\n#endif\n\n#ifndef TRIES\n#define TRIES 20\n#endif\n\ntypedef double Scalar;\n\ntemplate <typename MatrixType>\n__attribute__ ((noinline)) void bench_reverse(const MatrixType& m)\n{\n  int rows = m.rows();\n  int cols = m.cols();\n  int size = m.size();\n\n  int repeats = (REPEAT*1000)/size;\n  MatrixType a = MatrixType::Random(rows,cols);\n  MatrixType b = MatrixType::Random(rows,cols);\n\n  BenchTimer timerB, timerH, timerV;\n\n  Scalar acc = 0;\n  int r = internal::random<int>(0,rows-1);\n  int c = internal::random<int>(0,cols-1);\n  for (int t=0; t<TRIES; ++t)\n  {\n    timerB.start();\n    for (int k=0; k<repeats; ++k)\n    {\n      asm(\"#begin foo\");\n      b = a.reverse();\n      asm(\"#end foo\");\n      acc += b.coeff(r,c);\n    }\n    timerB.stop();\n  }\n\n  if (MatrixType::RowsAtCompileTime==Dynamic)\n    std::cout << \"dyn   \";\n  else\n    std::cout << \"fixed \";\n  std::cout << rows << \" x \" << cols << \" \\t\"\n            << (timerB.value() * REPEAT) / repeats << \"s \"\n            << \"(\" << 1e-6 * size*repeats/timerB.value() << \" MFLOPS)\\t\";\n\n  std::cout << \"\\n\";\n  // make sure the compiler does not optimize too much\n  if (acc==123)\n    std::cout << acc;\n}\n\nint main(int argc, char* argv[])\n{\n  const int dynsizes[] = {4,6,8,16,24,32,49,64,128,256,512,900,0};\n  std::cout << \"size            no sqrt                           standard\";\n//   #ifdef BENCH_GSL\n//   std::cout << \"       GSL (standard + double + ATLAS)  \";\n//   #endif\n  std::cout << \"\\n\";\n  for (uint i=0; dynsizes[i]>0; ++i)\n  {\n    bench_reverse(Matrix<Scalar,Dynamic,Dynamic>(dynsizes[i],dynsizes[i]));\n    bench_reverse(Matrix<Scalar,Dynamic,1>(dynsizes[i]*dynsizes[i]));\n  }\n//   bench_reverse(Matrix<Scalar,2,2>());\n//   bench_reverse(Matrix<Scalar,3,3>());\n//   bench_reverse(Matrix<Scalar,4,4>());\n//   bench_reverse(Matrix<Scalar,5,5>());\n//   bench_reverse(Matrix<Scalar,6,6>());\n//   bench_reverse(Matrix<Scalar,7,7>());\n//   bench_reverse(Matrix<Scalar,8,8>());\n//   bench_reverse(Matrix<Scalar,12,12>());\n//   bench_reverse(Matrix<Scalar,16,16>());\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/bench_sum.cpp",
    "content": "#include <iostream>\n#include <Eigen/Core>\nusing namespace Eigen;\nusing namespace std;\n\nint main() \n{\n  typedef Matrix<SCALAR,Eigen::Dynamic,1> Vec;\n  Vec v(SIZE);\n  v.setZero();\n  v[0] = 1;\n  v[1] = 2;\n  for(int i = 0; i < 1000000; i++)\n  {\n    v.coeffRef(0) += v.sum() * SCALAR(1e-20);\n  }\n  cout << v.sum() << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/bench_unrolling",
    "content": "#!/bin/bash\n\n# gcc : CXX=\"g++  -finline-limit=10000 -ftemplate-depth-2000 --param max-inline-recursive-depth=2000\"\n# icc : CXX=\"icpc -fast -no-inline-max-size -fno-exceptions\"\nCXX=${CXX-g++  -finline-limit=10000 -ftemplate-depth-2000 --param max-inline-recursive-depth=2000} # default value\n\nfor ((i=1; i<16; ++i)); do\n    echo \"Matrix size: $i x $i :\"\n    $CXX -O3 -I.. -DNDEBUG  benchmark.cpp -DMATSIZE=$i -DEIGEN_UNROLLING_LIMIT=400 -o benchmark && time ./benchmark >/dev/null\n    $CXX -O3 -I.. -DNDEBUG -finline-limit=10000 benchmark.cpp -DMATSIZE=$i -DEIGEN_DONT_USE_UNROLLED_LOOPS=1 -o benchmark && time ./benchmark >/dev/null\n    echo \" \"\ndone\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/benchmark-blocking-sizes.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Jacob <benoitjacob@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <iostream>\n#include <cstdint>\n#include <cstdlib>\n#include <vector>\n#include <fstream>\n#include <memory>\n#include <cstdio>\n\nbool eigen_use_specific_block_size;\nint eigen_block_size_k, eigen_block_size_m, eigen_block_size_n;\n#define EIGEN_TEST_SPECIFIC_BLOCKING_SIZES eigen_use_specific_block_size\n#define EIGEN_TEST_SPECIFIC_BLOCKING_SIZE_K eigen_block_size_k\n#define EIGEN_TEST_SPECIFIC_BLOCKING_SIZE_M eigen_block_size_m\n#define EIGEN_TEST_SPECIFIC_BLOCKING_SIZE_N eigen_block_size_n\n#include <Eigen/Core>\n\n#include <bench/BenchTimer.h>\n\nusing namespace Eigen;\nusing namespace std;\n\nstatic BenchTimer timer;\n\n// how many times we repeat each measurement.\n// measurements are randomly shuffled - we're not doing\n// all N identical measurements in a row.\nconst int measurement_repetitions = 3;\n\n// Timings below this value are too short to be accurate,\n// we'll repeat measurements with more iterations until\n// we get a timing above that threshold.\nconst float min_accurate_time = 1e-2f;\n\n// See --min-working-set-size command line parameter.\nsize_t min_working_set_size = 0;\n\nfloat max_clock_speed = 0.0f;\n\n// range of sizes that we will benchmark (in all 3 K,M,N dimensions)\nconst size_t maxsize = 2048;\nconst size_t minsize = 16;\n\ntypedef MatrixXf MatrixType;\ntypedef MatrixType::Scalar Scalar;\ntypedef internal::packet_traits<Scalar>::type Packet;\n\nstatic_assert((maxsize & (maxsize - 1)) == 0, \"maxsize must be a power of two\");\nstatic_assert((minsize & (minsize - 1)) == 0, \"minsize must be a power of two\");\nstatic_assert(maxsize > minsize, \"maxsize must be larger than minsize\");\nstatic_assert(maxsize < (minsize << 16), \"maxsize must be less than (minsize<<16)\");\n\n// just a helper to store a triple of K,M,N sizes for matrix product\nstruct size_triple_t\n{\n  size_t k, m, n;\n  size_triple_t() : k(0), m(0), n(0) {}\n  size_triple_t(size_t _k, size_t _m, size_t _n) : k(_k), m(_m), n(_n) {}\n  size_triple_t(const size_triple_t& o) : k(o.k), m(o.m), n(o.n) {}\n  size_triple_t(uint16_t compact)\n  {\n    k = 1 << ((compact & 0xf00) >> 8);\n    m = 1 << ((compact & 0x0f0) >> 4);\n    n = 1 << ((compact & 0x00f) >> 0);\n  }\n};\n\nuint8_t log2_pot(size_t x) {\n  size_t l = 0;\n  while (x >>= 1) l++;\n  return l;\n}\n\n// Convert between size tripes and a compact form fitting in 12 bits\n// where each size, which must be a POT, is encoded as its log2, on 4 bits\n// so the largest representable size is 2^15 == 32k  ... big enough.\nuint16_t compact_size_triple(size_t k, size_t m, size_t n)\n{\n  return (log2_pot(k) << 8) | (log2_pot(m) << 4) | log2_pot(n);\n}\n\nuint16_t compact_size_triple(const size_triple_t& t)\n{\n  return compact_size_triple(t.k, t.m, t.n);\n}\n\n// A single benchmark. Initially only contains benchmark params.\n// Then call run(), which stores the result in the gflops field.\nstruct benchmark_t\n{\n  uint16_t compact_product_size;\n  uint16_t compact_block_size;\n  bool use_default_block_size;\n  float gflops;\n  benchmark_t()\n    : compact_product_size(0)\n    , compact_block_size(0)\n    , use_default_block_size(false)\n    , gflops(0)\n  {\n  }\n  benchmark_t(size_t pk, size_t pm, size_t pn,\n              size_t bk, size_t bm, size_t bn)\n    : compact_product_size(compact_size_triple(pk, pm, pn))\n    , compact_block_size(compact_size_triple(bk, bm, bn))\n    , use_default_block_size(false)\n    , gflops(0)\n  {}\n  benchmark_t(size_t pk, size_t pm, size_t pn)\n    : compact_product_size(compact_size_triple(pk, pm, pn))\n    , compact_block_size(0)\n    , use_default_block_size(true)\n    , gflops(0)\n  {}\n\n  void run();\n};\n\nostream& operator<<(ostream& s, const benchmark_t& b)\n{\n  s << hex << b.compact_product_size << dec;\n  if (b.use_default_block_size) {\n    size_triple_t t(b.compact_product_size);\n    Index k = t.k, m = t.m, n = t.n;\n    internal::computeProductBlockingSizes<Scalar, Scalar>(k, m, n);\n    s << \" default(\" << k << \", \" << m << \", \" << n << \")\";\n  } else {\n    s << \" \" << hex << b.compact_block_size << dec;\n  }\n  s << \" \" << b.gflops;\n  return s;\n}\n\n// We sort first by increasing benchmark parameters,\n// then by decreasing performance.\nbool operator<(const benchmark_t& b1, const benchmark_t& b2)\n{ \n  return b1.compact_product_size < b2.compact_product_size ||\n           (b1.compact_product_size == b2.compact_product_size && (\n             (b1.compact_block_size < b2.compact_block_size || (\n               b1.compact_block_size == b2.compact_block_size &&\n                 b1.gflops > b2.gflops))));\n}\n\nvoid benchmark_t::run()\n{\n  size_triple_t productsizes(compact_product_size);\n\n  if (use_default_block_size) {\n    eigen_use_specific_block_size = false;\n  } else {\n    // feed eigen with our custom blocking params\n    eigen_use_specific_block_size = true;\n    size_triple_t blocksizes(compact_block_size);\n    eigen_block_size_k = blocksizes.k;\n    eigen_block_size_m = blocksizes.m;\n    eigen_block_size_n = blocksizes.n;\n  }\n\n  // set up the matrix pool\n\n  const size_t combined_three_matrices_sizes =\n    sizeof(Scalar) *\n      (productsizes.k * productsizes.m +\n       productsizes.k * productsizes.n +\n       productsizes.m * productsizes.n);\n\n  // 64 M is large enough that nobody has a cache bigger than that,\n  // while still being small enough that everybody has this much RAM,\n  // so conveniently we don't need to special-case platforms here.\n  const size_t unlikely_large_cache_size = 64 << 20;\n\n  const size_t working_set_size =\n    min_working_set_size ? min_working_set_size : unlikely_large_cache_size;\n\n  const size_t matrix_pool_size =\n    1 + working_set_size / combined_three_matrices_sizes;\n\n  MatrixType *lhs = new MatrixType[matrix_pool_size];\n  MatrixType *rhs = new MatrixType[matrix_pool_size];\n  MatrixType *dst = new MatrixType[matrix_pool_size];\n  \n  for (size_t i = 0; i < matrix_pool_size; i++) {\n    lhs[i] = MatrixType::Zero(productsizes.m, productsizes.k);\n    rhs[i] = MatrixType::Zero(productsizes.k, productsizes.n);\n    dst[i] = MatrixType::Zero(productsizes.m, productsizes.n);\n  }\n\n  // main benchmark loop\n\n  int iters_at_a_time = 1;\n  float time_per_iter = 0.0f;\n  size_t matrix_index = 0;\n  while (true) {\n\n    double starttime = timer.getCpuTime();\n    for (int i = 0; i < iters_at_a_time; i++) {\n      dst[matrix_index].noalias() = lhs[matrix_index] * rhs[matrix_index];\n      matrix_index++;\n      if (matrix_index == matrix_pool_size) {\n        matrix_index = 0;\n      }\n    }\n    double endtime = timer.getCpuTime();\n\n    const float timing = float(endtime - starttime);\n\n    if (timing >= min_accurate_time) {\n      time_per_iter = timing / iters_at_a_time;\n      break;\n    }\n\n    iters_at_a_time *= 2;\n  }\n\n  delete[] lhs;\n  delete[] rhs;\n  delete[] dst;\n\n  gflops = 2e-9 * productsizes.k * productsizes.m * productsizes.n / time_per_iter;\n}\n\nvoid print_cpuinfo()\n{\n#ifdef __linux__\n  cout << \"contents of /proc/cpuinfo:\" << endl;\n  string line;\n  ifstream cpuinfo(\"/proc/cpuinfo\");\n  if (cpuinfo.is_open()) {\n    while (getline(cpuinfo, line)) {\n      cout << line << endl;\n    }\n    cpuinfo.close();\n  }\n  cout << endl;\n#elif defined __APPLE__\n  cout << \"output of sysctl hw:\" << endl;\n  system(\"sysctl hw\");\n  cout << endl;\n#endif\n}\n\ntemplate <typename T>\nstring type_name()\n{\n  return \"unknown\";\n}\n\ntemplate<>\nstring type_name<float>()\n{\n  return \"float\";\n}\n\ntemplate<>\nstring type_name<double>()\n{\n  return \"double\";\n}\n\nstruct action_t\n{\n  virtual const char* invokation_name() const { abort(); return nullptr; }\n  virtual void run() const { abort(); }\n  virtual ~action_t() {}\n};\n\nvoid show_usage_and_exit(int /*argc*/, char* argv[],\n                         const vector<unique_ptr<action_t>>& available_actions)\n{\n  cerr << \"usage: \" << argv[0] << \" <action> [options...]\" << endl << endl;\n  cerr << \"available actions:\" << endl << endl;\n  for (auto it = available_actions.begin(); it != available_actions.end(); ++it) {\n    cerr << \"  \" << (*it)->invokation_name() << endl;\n  }\n  cerr << endl;\n  cerr << \"options:\" << endl << endl;\n  cerr << \"  --min-working-set-size=N:\" << endl;\n  cerr << \"       Set the minimum working set size to N bytes.\" << endl;\n  cerr << \"       This is rounded up as needed to a multiple of matrix size.\" << endl;\n  cerr << \"       A larger working set lowers the chance of a warm cache.\" << endl;\n  cerr << \"       The default value 0 means use a large enough working\" << endl;\n  cerr << \"       set to likely outsize caches.\" << endl;\n  cerr << \"       A value of 1 (that is, 1 byte) would mean don't do anything to\" << endl;\n  cerr << \"       avoid warm caches.\" << endl;\n  exit(1);\n}\n     \nfloat measure_clock_speed()\n{\n  cerr << \"Measuring clock speed...                              \\r\" << flush;\n          \n  vector<float> all_gflops;\n  for (int i = 0; i < 8; i++) {\n    benchmark_t b(1024, 1024, 1024);\n    b.run();\n    all_gflops.push_back(b.gflops);\n  }\n\n  sort(all_gflops.begin(), all_gflops.end());\n  float stable_estimate = all_gflops[2] + all_gflops[3] + all_gflops[4] + all_gflops[5];\n\n  // multiply by an arbitrary constant to discourage trying doing anything with the\n  // returned values besides just comparing them with each other.\n  float result = stable_estimate * 123.456f;\n\n  return result;\n}\n\nstruct human_duration_t\n{\n  int seconds;\n  human_duration_t(int s) : seconds(s) {}\n};\n\nostream& operator<<(ostream& s, const human_duration_t& d)\n{\n  int remainder = d.seconds;\n  if (remainder > 3600) {\n    int hours = remainder / 3600;\n    s << hours << \" h \";\n    remainder -= hours * 3600;\n  }\n  if (remainder > 60) {\n    int minutes = remainder / 60;\n    s << minutes << \" min \";\n    remainder -= minutes * 60;\n  }\n  if (d.seconds < 600) {\n    s << remainder << \" s\";\n  }\n  return s;\n}\n\nconst char session_filename[] = \"/data/local/tmp/benchmark-blocking-sizes-session.data\";\n\nvoid serialize_benchmarks(const char* filename, const vector<benchmark_t>& benchmarks, size_t first_benchmark_to_run)\n{\n  FILE* file = fopen(filename, \"w\");\n  if (!file) {\n    cerr << \"Could not open file \" << filename << \" for writing.\" << endl;\n    cerr << \"Do you have write permissions on the current working directory?\" << endl;\n    exit(1);\n  }\n  size_t benchmarks_vector_size = benchmarks.size();\n  fwrite(&max_clock_speed, sizeof(max_clock_speed), 1, file);\n  fwrite(&benchmarks_vector_size, sizeof(benchmarks_vector_size), 1, file);\n  fwrite(&first_benchmark_to_run, sizeof(first_benchmark_to_run), 1, file);\n  fwrite(benchmarks.data(), sizeof(benchmark_t), benchmarks.size(), file);\n  fclose(file);\n}\n\nbool deserialize_benchmarks(const char* filename, vector<benchmark_t>& benchmarks, size_t& first_benchmark_to_run)\n{\n  FILE* file = fopen(filename, \"r\");\n  if (!file) {\n    return false;\n  }\n  if (1 != fread(&max_clock_speed, sizeof(max_clock_speed), 1, file)) {\n    return false;\n  }\n  size_t benchmarks_vector_size = 0;\n  if (1 != fread(&benchmarks_vector_size, sizeof(benchmarks_vector_size), 1, file)) {\n    return false;\n  }\n  if (1 != fread(&first_benchmark_to_run, sizeof(first_benchmark_to_run), 1, file)) {\n    return false;\n  }\n  benchmarks.resize(benchmarks_vector_size);\n  if (benchmarks.size() != fread(benchmarks.data(), sizeof(benchmark_t), benchmarks.size(), file)) {\n    return false;\n  }\n  unlink(filename);\n  return true;\n}\n\nvoid try_run_some_benchmarks(\n  vector<benchmark_t>& benchmarks,\n  double time_start,\n  size_t& first_benchmark_to_run)\n{\n  if (first_benchmark_to_run == benchmarks.size()) {\n    return;\n  }\n\n  double time_last_progress_update = 0;\n  double time_last_clock_speed_measurement = 0;\n  double time_now = 0;\n\n  size_t benchmark_index = first_benchmark_to_run;\n\n  while (true) {\n    float ratio_done = float(benchmark_index) / benchmarks.size();\n    time_now = timer.getRealTime();\n\n    // We check clock speed every minute and at the end.\n    if (benchmark_index == benchmarks.size() ||\n        time_now > time_last_clock_speed_measurement + 60.0f)\n    {\n      time_last_clock_speed_measurement = time_now;\n\n      // Ensure that clock speed is as expected\n      float current_clock_speed = measure_clock_speed();\n\n      // The tolerance needs to be smaller than the relative difference between\n      // clock speeds that a device could operate under.\n      // It seems unlikely that a device would be throttling clock speeds by\n      // amounts smaller than 2%.\n      // With a value of 1%, I was getting within noise on a Sandy Bridge.\n      const float clock_speed_tolerance = 0.02f;\n\n      if (current_clock_speed > (1 + clock_speed_tolerance) * max_clock_speed) {\n        // Clock speed is now higher than we previously measured.\n        // Either our initial measurement was inaccurate, which won't happen\n        // too many times as we are keeping the best clock speed value and\n        // and allowing some tolerance; or something really weird happened,\n        // which invalidates all benchmark results collected so far.\n        // Either way, we better restart all over again now.\n        if (benchmark_index) {\n          cerr << \"Restarting at \" << 100.0f * ratio_done\n               << \" % because clock speed increased.          \" << endl;\n        }\n        max_clock_speed = current_clock_speed;\n        first_benchmark_to_run = 0;\n        return;\n      }\n\n      bool rerun_last_tests = false;\n\n      if (current_clock_speed < (1 - clock_speed_tolerance) * max_clock_speed) {\n        cerr << \"Measurements completed so far: \"\n             << 100.0f * ratio_done\n             << \" %                             \" << endl;\n        cerr << \"Clock speed seems to be only \"\n             << current_clock_speed/max_clock_speed\n             << \" times what it used to be.\" << endl;\n\n        unsigned int seconds_to_sleep_if_lower_clock_speed = 1;\n\n        while (current_clock_speed < (1 - clock_speed_tolerance) * max_clock_speed) {\n          if (seconds_to_sleep_if_lower_clock_speed > 32) {\n            cerr << \"Sleeping longer probably won't make a difference.\" << endl;\n            cerr << \"Serializing benchmarks to \" << session_filename << endl;\n            serialize_benchmarks(session_filename, benchmarks, first_benchmark_to_run);\n            cerr << \"Now restart this benchmark, and it should pick up where we left.\" << endl;\n            exit(2);\n          }\n          rerun_last_tests = true;\n          cerr << \"Sleeping \"\n               << seconds_to_sleep_if_lower_clock_speed\n               << \" s...                                   \\r\" << endl;\n          sleep(seconds_to_sleep_if_lower_clock_speed);\n          current_clock_speed = measure_clock_speed();\n          seconds_to_sleep_if_lower_clock_speed *= 2;\n        }\n      }\n\n      if (rerun_last_tests) {\n        cerr << \"Redoing the last \"\n             << 100.0f * float(benchmark_index - first_benchmark_to_run) / benchmarks.size()\n             << \" % because clock speed had been low.   \" << endl;\n        return;\n      }\n\n      // nothing wrong with the clock speed so far, so there won't be a need to rerun\n      // benchmarks run so far in case we later encounter a lower clock speed.\n      first_benchmark_to_run = benchmark_index;\n    }\n\n    if (benchmark_index == benchmarks.size()) {\n      // We're done!\n      first_benchmark_to_run = benchmarks.size();\n      // Erase progress info\n      cerr << \"                                                            \" << endl;\n      return;\n    }\n\n    // Display progress info on stderr\n    if (time_now > time_last_progress_update + 1.0f) {\n      time_last_progress_update = time_now;\n      cerr << \"Measurements... \" << 100.0f * ratio_done\n           << \" %, ETA \"\n           << human_duration_t(float(time_now - time_start) * (1.0f - ratio_done) / ratio_done)\n           << \"                          \\r\" << flush;\n    }\n\n    // This is where we actually run a benchmark!\n    benchmarks[benchmark_index].run();\n    benchmark_index++;\n  }\n}\n\nvoid run_benchmarks(vector<benchmark_t>& benchmarks)\n{\n  size_t first_benchmark_to_run;\n  vector<benchmark_t> deserialized_benchmarks;\n  bool use_deserialized_benchmarks = false;\n  if (deserialize_benchmarks(session_filename, deserialized_benchmarks, first_benchmark_to_run)) {\n    cerr << \"Found serialized session with \"\n         << 100.0f * first_benchmark_to_run / deserialized_benchmarks.size()\n         << \" % already done\" << endl;\n    if (deserialized_benchmarks.size() == benchmarks.size() &&\n        first_benchmark_to_run > 0 &&\n        first_benchmark_to_run < benchmarks.size())\n    {\n      use_deserialized_benchmarks = true;\n    }\n  }\n\n  if (use_deserialized_benchmarks) {\n    benchmarks = deserialized_benchmarks;\n  } else {\n    // not using deserialized benchmarks, starting from scratch\n    first_benchmark_to_run = 0;\n\n    // Randomly shuffling benchmarks allows us to get accurate enough progress info,\n    // as now the cheap/expensive benchmarks are randomly mixed so they average out.\n    // It also means that if data is corrupted for some time span, the odds are that\n    // not all repetitions of a given benchmark will be corrupted.\n    random_shuffle(benchmarks.begin(), benchmarks.end());\n  }\n\n  for (int i = 0; i < 4; i++) {\n    max_clock_speed = max(max_clock_speed, measure_clock_speed());\n  }\n  \n  double time_start = 0.0;\n  while (first_benchmark_to_run < benchmarks.size()) {\n    if (first_benchmark_to_run == 0) {\n      time_start = timer.getRealTime();\n    }\n    try_run_some_benchmarks(benchmarks,\n                            time_start,\n                            first_benchmark_to_run);\n  }\n\n  // Sort timings by increasing benchmark parameters, and decreasing gflops.\n  // The latter is very important. It means that we can ignore all but the first\n  // benchmark with given parameters.\n  sort(benchmarks.begin(), benchmarks.end());\n\n  // Collect best (i.e. now first) results for each parameter values.\n  vector<benchmark_t> best_benchmarks;\n  for (auto it = benchmarks.begin(); it != benchmarks.end(); ++it) {\n    if (best_benchmarks.empty() ||\n        best_benchmarks.back().compact_product_size != it->compact_product_size ||\n        best_benchmarks.back().compact_block_size != it->compact_block_size)\n    {\n      best_benchmarks.push_back(*it);\n    }\n  }\n\n  // keep and return only the best benchmarks\n  benchmarks = best_benchmarks;\n}\n\nstruct measure_all_pot_sizes_action_t : action_t\n{\n  virtual const char* invokation_name() const { return \"all-pot-sizes\"; }\n  virtual void run() const\n  {\n    vector<benchmark_t> benchmarks;\n    for (int repetition = 0; repetition < measurement_repetitions; repetition++) {\n      for (size_t ksize = minsize; ksize <= maxsize; ksize *= 2) {\n        for (size_t msize = minsize; msize <= maxsize; msize *= 2) {\n          for (size_t nsize = minsize; nsize <= maxsize; nsize *= 2) {\n            for (size_t kblock = minsize; kblock <= ksize; kblock *= 2) {\n              for (size_t mblock = minsize; mblock <= msize; mblock *= 2) {\n                for (size_t nblock = minsize; nblock <= nsize; nblock *= 2) {\n                  benchmarks.emplace_back(ksize, msize, nsize, kblock, mblock, nblock);\n                }\n              }\n            }\n          }\n        }\n      }\n    }\n\n    run_benchmarks(benchmarks);\n\n    cout << \"BEGIN MEASUREMENTS ALL POT SIZES\" << endl;\n    for (auto it = benchmarks.begin(); it != benchmarks.end(); ++it) {\n      cout << *it << endl;\n    }\n  }\n};\n\nstruct measure_default_sizes_action_t : action_t\n{\n  virtual const char* invokation_name() const { return \"default-sizes\"; }\n  virtual void run() const\n  {\n    vector<benchmark_t> benchmarks;\n    for (int repetition = 0; repetition < measurement_repetitions; repetition++) {\n      for (size_t ksize = minsize; ksize <= maxsize; ksize *= 2) {\n        for (size_t msize = minsize; msize <= maxsize; msize *= 2) {\n          for (size_t nsize = minsize; nsize <= maxsize; nsize *= 2) {\n            benchmarks.emplace_back(ksize, msize, nsize);\n          }\n        }\n      }\n    }\n\n    run_benchmarks(benchmarks);\n\n    cout << \"BEGIN MEASUREMENTS DEFAULT SIZES\" << endl;\n    for (auto it = benchmarks.begin(); it != benchmarks.end(); ++it) {\n      cout << *it << endl;\n    }\n  }\n};\n\nint main(int argc, char* argv[])\n{\n  double time_start = timer.getRealTime();\n  cout.precision(4);\n  cerr.precision(4);\n\n  vector<unique_ptr<action_t>> available_actions;\n  available_actions.emplace_back(new measure_all_pot_sizes_action_t);\n  available_actions.emplace_back(new measure_default_sizes_action_t);\n\n  auto action = available_actions.end();\n\n  if (argc <= 1) {\n    show_usage_and_exit(argc, argv, available_actions);\n  }\n  for (auto it = available_actions.begin(); it != available_actions.end(); ++it) {\n    if (!strcmp(argv[1], (*it)->invokation_name())) {\n      action = it;\n      break;\n    }\n  }\n\n  if (action == available_actions.end()) {\n    show_usage_and_exit(argc, argv, available_actions);\n  }\n\n  for (int i = 2; i < argc; i++) {\n    if (argv[i] == strstr(argv[i], \"--min-working-set-size=\")) {\n      const char* equals_sign = strchr(argv[i], '=');\n      min_working_set_size = strtoul(equals_sign+1, nullptr, 10);\n    } else {\n      cerr << \"unrecognized option: \" << argv[i] << endl << endl;\n      show_usage_and_exit(argc, argv, available_actions);\n    }\n  }\n\n  print_cpuinfo();\n\n  cout << \"benchmark parameters:\" << endl;\n  cout << \"pointer size: \" << 8*sizeof(void*) << \" bits\" << endl;\n  cout << \"scalar type: \" << type_name<Scalar>() << endl;\n  cout << \"packet size: \" << internal::packet_traits<MatrixType::Scalar>::size << endl;\n  cout << \"minsize = \" << minsize << endl;\n  cout << \"maxsize = \" << maxsize << endl;\n  cout << \"measurement_repetitions = \" << measurement_repetitions << endl;\n  cout << \"min_accurate_time = \" << min_accurate_time << endl;\n  cout << \"min_working_set_size = \" << min_working_set_size;\n  if (min_working_set_size == 0) {\n    cout << \" (try to outsize caches)\";\n  }\n  cout << endl << endl;\n\n  (*action)->run();\n\n  double time_end = timer.getRealTime();\n  cerr << \"Finished in \" << human_duration_t(time_end - time_start) << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/benchmark.cpp",
    "content": "// g++ -O3 -DNDEBUG -DMATSIZE=<x> benchmark.cpp -o benchmark && time ./benchmark\n\n#include <iostream>\n\n#include <Eigen/Core>\n\n#ifndef MATSIZE\n#define MATSIZE 3\n#endif\n\nusing namespace std;\nusing namespace Eigen;\n\n#ifndef REPEAT\n#define REPEAT 40000000\n#endif\n\n#ifndef SCALAR\n#define SCALAR double\n#endif\n\nint main(int argc, char *argv[])\n{\n    Matrix<SCALAR,MATSIZE,MATSIZE> I = Matrix<SCALAR,MATSIZE,MATSIZE>::Ones();\n    Matrix<SCALAR,MATSIZE,MATSIZE> m;\n    for(int i = 0; i < MATSIZE; i++)\n        for(int j = 0; j < MATSIZE; j++)\n        {\n            m(i,j) = (i+MATSIZE*j);\n        }\n    asm(\"#begin\");\n    for(int a = 0; a < REPEAT; a++)\n    {\n        m = Matrix<SCALAR,MATSIZE,MATSIZE>::Ones() + 0.00005 * (m + (m*m));\n    }\n    asm(\"#end\");\n    cout << m << endl;\n    return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/benchmarkSlice.cpp",
    "content": "// g++ -O3 -DNDEBUG benchmarkX.cpp -o benchmarkX && time ./benchmarkX\n\n#include <iostream>\n\n#include <Eigen/Core>\n\nusing namespace std;\nusing namespace Eigen;\n\n#ifndef REPEAT\n#define REPEAT 10000\n#endif\n\n#ifndef SCALAR\n#define SCALAR float\n#endif\n\nint main(int argc, char *argv[])\n{\n  typedef Matrix<SCALAR, Eigen::Dynamic, Eigen::Dynamic> Mat;\n  Mat m(100, 100);\n  m.setRandom();\n\n  for(int a = 0; a < REPEAT; a++)\n  {\n    int r, c, nr, nc;\n    r = Eigen::internal::random<int>(0,10);\n    c = Eigen::internal::random<int>(0,10);\n    nr = Eigen::internal::random<int>(50,80);\n    nc = Eigen::internal::random<int>(50,80);\n    m.block(r,c,nr,nc) += Mat::Ones(nr,nc);\n    m.block(r,c,nr,nc) *= SCALAR(10);\n    m.block(r,c,nr,nc) -= Mat::constant(nr,nc,10);\n    m.block(r,c,nr,nc) /= SCALAR(10);\n  }\n  cout << m[0] << endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/benchmarkX.cpp",
    "content": "// g++ -fopenmp -I .. -O3 -DNDEBUG -finline-limit=1000 benchmarkX.cpp -o b && time ./b\n\n#include <iostream>\n\n#include <Eigen/Core>\n\nusing namespace std;\nusing namespace Eigen;\n\n#ifndef MATTYPE\n#define MATTYPE MatrixXLd\n#endif\n\n#ifndef MATSIZE\n#define MATSIZE 400\n#endif\n\n#ifndef REPEAT\n#define REPEAT 100\n#endif\n\nint main(int argc, char *argv[])\n{\n\tMATTYPE I = MATTYPE::Ones(MATSIZE,MATSIZE);\n\tMATTYPE m(MATSIZE,MATSIZE);\n\tfor(int i = 0; i < MATSIZE; i++) for(int j = 0; j < MATSIZE; j++)\n\t{\n\t\tm(i,j) = (i+j+1)/(MATSIZE*MATSIZE);\n\t}\n\tfor(int a = 0; a < REPEAT; a++)\n\t{\n\t\tm = I + 0.0001 * (m + m*m);\n\t}\n\tcout << m(0,0) << endl;\n\treturn 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/benchmarkXcwise.cpp",
    "content": "// g++ -O3 -DNDEBUG benchmarkX.cpp -o benchmarkX && time ./benchmarkX\n\n#include <iostream>\n#include <Eigen/Core>\n\nusing namespace std;\nusing namespace Eigen;\n\n#ifndef VECTYPE\n#define VECTYPE VectorXLd\n#endif\n\n#ifndef VECSIZE\n#define VECSIZE 1000000\n#endif\n\n#ifndef REPEAT\n#define REPEAT 1000\n#endif\n\nint main(int argc, char *argv[])\n{\n\tVECTYPE I = VECTYPE::Ones(VECSIZE);\n\tVECTYPE m(VECSIZE,1);\n\tfor(int i = 0; i < VECSIZE; i++)\n\t{\n\t\tm[i] = 0.1 * i/VECSIZE;\n\t}\n\tfor(int a = 0; a < REPEAT; a++)\n\t{\n\t\tm = VECTYPE::Ones(VECSIZE) + 0.00005 * (m.cwise().square() + m/4);\n\t}\n\tcout << m[0] << endl;\n\treturn 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/benchmark_suite",
    "content": "#!/bin/bash\nCXX=${CXX-g++} # default value unless caller has defined CXX\necho \"Fixed size 3x3, column-major, -DNDEBUG\"\n$CXX -O3 -I .. -DNDEBUG benchmark.cpp -o benchmark && time ./benchmark >/dev/null\necho \"Fixed size 3x3, column-major, with asserts\"\n$CXX -O3 -I .. benchmark.cpp -o benchmark && time ./benchmark >/dev/null\necho \"Fixed size 3x3, row-major, -DNDEBUG\"\n$CXX -O3 -I .. -DEIGEN_DEFAULT_TO_ROW_MAJOR -DNDEBUG benchmark.cpp -o benchmark && time ./benchmark >/dev/null\necho \"Fixed size 3x3, row-major, with asserts\"\n$CXX -O3 -I .. -DEIGEN_DEFAULT_TO_ROW_MAJOR benchmark.cpp -o benchmark && time ./benchmark >/dev/null\necho \"Dynamic size 20x20, column-major, -DNDEBUG\"\n$CXX -O3 -I .. -DNDEBUG benchmarkX.cpp -o benchmarkX && time ./benchmarkX >/dev/null\necho \"Dynamic size 20x20, column-major, with asserts\"\n$CXX -O3 -I .. benchmarkX.cpp -o benchmarkX && time ./benchmarkX >/dev/null\necho \"Dynamic size 20x20, row-major, -DNDEBUG\"\n$CXX -O3 -I .. -DEIGEN_DEFAULT_TO_ROW_MAJOR -DNDEBUG benchmarkX.cpp -o benchmarkX && time ./benchmarkX >/dev/null\necho \"Dynamic size 20x20, row-major, with asserts\"\n$CXX -O3 -I .. -DEIGEN_DEFAULT_TO_ROW_MAJOR benchmarkX.cpp -o benchmarkX && time ./benchmarkX >/dev/null\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/CMakeLists.txt",
    "content": "project(BTL)\n\ncmake_minimum_required(VERSION 2.6.2)\n\nset(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake ${Eigen_SOURCE_DIR}/cmake)\ninclude(MacroOptionalAddSubdirectory)\n\noption(BTL_NOVEC \"Disable SSE/Altivec optimizations when possible\" OFF)\n\nset(CMAKE_INCLUDE_CURRENT_DIR ON)\n\nstring(REGEX MATCH icpc IS_ICPC ${CMAKE_CXX_COMPILER})\nif(CMAKE_COMPILER_IS_GNUCXX OR IS_ICPC)\n  set(CMAKE_CXX_FLAGS \"-g0 -O3 -DNDEBUG ${CMAKE_CXX_FLAGS}\")\n  set(CMAKE_Fortran_FLAGS \"-g0 -O3 -DNDEBUG ${CMAKE_Fortran_FLAGS}\")\n  if(BTL_NOVEC)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -DEIGEN_DONT_VECTORIZE\")\n  endif(BTL_NOVEC)\nendif(CMAKE_COMPILER_IS_GNUCXX OR IS_ICPC)\n\nif(MSVC)\n  set(CMAKE_CXX_FLAGS \" /O2 /Ot /GL /fp:fast -DNDEBUG\")\n#   set(CMAKE_Fortran_FLAGS \"-g0 -O3 -DNDEBUG\")\n  if(BTL_NOVEC)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -DEIGEN_DONT_VECTORIZE\")\n  endif(BTL_NOVEC)\nendif(MSVC)\n\nif(IS_ICPC)\n  set(CMAKE_CXX_FLAGS \"-fast ${CMAKE_CXX_FLAGS}\")\n  set(CMAKE_Fortran_FLAGS \"-fast ${CMAKE_Fortran_FLAGS}\")\nendif()\n\ninclude_directories(\n  ${PROJECT_SOURCE_DIR}/actions\n  ${PROJECT_SOURCE_DIR}/generic_bench\n  ${PROJECT_SOURCE_DIR}/generic_bench/utils\n  ${PROJECT_SOURCE_DIR}/libs/STL)\n\n# find_package(MKL)\n# if (MKL_FOUND)\n#   add_definitions(-DHAVE_MKL)\n#   set(DEFAULT_LIBRARIES ${MKL_LIBRARIES})\n# endif ()\n\nfind_library(EIGEN_BTL_RT_LIBRARY rt)\n# if we cannot find it easily, then we don't need it!\nif(NOT EIGEN_BTL_RT_LIBRARY)\n  set(EIGEN_BTL_RT_LIBRARY \"\")\nendif()\n\nmacro(BTL_ADD_BENCH targetname)\n\n  foreach(_current_var ${ARGN})\n    set(_last_var ${_current_var})\n  endforeach()\n\n  set(_sources ${ARGN})\n  list(LENGTH _sources _argn_length)\n\n  list(REMOVE_ITEM _sources ON OFF TRUE FALSE)\n\n  list(LENGTH _sources _src_length)\n\n  if (${_argn_length} EQUAL ${_src_length})\n    set(_last_var ON)\n  endif ()\n\n  option(BUILD_${targetname} \"Build benchmark ${targetname}\" ${_last_var})\n\n  if(BUILD_${targetname})\n    add_executable(${targetname} ${_sources})\n    add_test(${targetname} \"${targetname}\")\n    target_link_libraries(${targetname} ${DEFAULT_LIBRARIES} ${EIGEN_BTL_RT_LIBRARY})\n  endif(BUILD_${targetname})\n\nendmacro(BTL_ADD_BENCH)\n\nmacro(btl_add_target_property target prop value)\n\n  if(BUILD_${target})\n    get_target_property(previous ${target} ${prop})\n    if(NOT previous)\n      set(previous \"\")\n    endif()\n    set_target_properties(${target} PROPERTIES ${prop} \"${previous} ${value}\")\n  endif()\n\nendmacro()\n\nenable_testing()\n\nadd_subdirectory(libs/eigen3)\nadd_subdirectory(libs/eigen2)\nadd_subdirectory(libs/tensors)\nadd_subdirectory(libs/BLAS)\nadd_subdirectory(libs/ublas)\nadd_subdirectory(libs/gmm)\nadd_subdirectory(libs/mtl4)\nadd_subdirectory(libs/blitz)\nadd_subdirectory(libs/tvmet)\nadd_subdirectory(libs/STL)\nadd_subdirectory(libs/blaze)\n\nadd_subdirectory(data)\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/COPYING",
    "content": "                    GNU GENERAL PUBLIC LICENSE\n                       Version 2, June 1991\n\n Copyright (C) 1989, 1991 Free Software Foundation, Inc.\n                       59 Temple Place, Suite 330, Boston, MA  02111-1307  USA\n Everyone is permitted to copy and distribute verbatim copies\n of this license document, but changing it is not allowed.\n\n                            Preamble\n\n  The licenses for most software are designed to take away your\nfreedom to share and change it.  By contrast, the GNU General Public\nLicense is intended to guarantee your freedom to share and change free\nsoftware--to make sure the software is free for all its users.  This\nGeneral Public License applies to most of the Free Software\nFoundation's software and to any other program whose authors commit to\nusing it.  (Some other Free Software Foundation software is covered by\nthe GNU Library General Public License instead.)  You can apply it to\nyour programs, too.\n\n  When we speak of free software, we are referring to freedom, not\nprice.  Our General Public Licenses are designed to make sure that you\nhave the freedom to distribute copies of free software (and charge for\nthis service if you wish), that you receive source code or can get it\nif you want it, that you can change the software or use pieces of it\nin new free programs; and that you know you can do these things.\n\n  To protect your rights, we need to make restrictions that forbid\nanyone to deny you these rights or to ask you to surrender the rights.\nThese restrictions translate to certain responsibilities for you if you\ndistribute copies of the software, or if you modify it.\n\n  For example, if you distribute copies of such a program, whether\ngratis or for a fee, you must give the recipients all the rights that\nyou have.  You must make sure that they, too, receive or can get the\nsource code.  And you must show them these terms so they know their\nrights.\n\n  We protect your rights with two steps: (1) copyright the software, and\n(2) offer you this license which gives you legal permission to copy,\ndistribute and/or modify the software.\n\n  Also, for each author's protection and ours, we want to make certain\nthat everyone understands that there is no warranty for this free\nsoftware.  If the software is modified by someone else and passed on, we\nwant its recipients to know that what they have is not the original, so\nthat any problems introduced by others will not reflect on the original\nauthors' reputations.\n\n  Finally, any free program is threatened constantly by software\npatents.  We wish to avoid the danger that redistributors of a free\nprogram will individually obtain patent licenses, in effect making the\nprogram proprietary.  To prevent this, we have made it clear that any\npatent must be licensed for everyone's free use or not licensed at all.\n\n  The precise terms and conditions for copying, distribution and\nmodification follow.\n\n                    GNU GENERAL PUBLIC LICENSE\n   TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION\n\n  0. This License applies to any program or other work which contains\na notice placed by the copyright holder saying it may be distributed\nunder the terms of this General Public License.  The \"Program\", below,\nrefers to any such program or work, and a \"work based on the Program\"\nmeans either the Program or any derivative work under copyright law:\nthat is to say, a work containing the Program or a portion of it,\neither verbatim or with modifications and/or translated into another\nlanguage.  (Hereinafter, translation is included without limitation in\nthe term \"modification\".)  Each licensee is addressed as \"you\".\n\nActivities other than copying, distribution and modification are not\ncovered by this License; they are outside its scope.  The act of\nrunning the Program is not restricted, and the output from the Program\nis covered only if its contents constitute a work based on the\nProgram (independent of having been made by running the Program).\nWhether that is true depends on what the Program does.\n\n  1. You may copy and distribute verbatim copies of the Program's\nsource code as you receive it, in any medium, provided that you\nconspicuously and appropriately publish on each copy an appropriate\ncopyright notice and disclaimer of warranty; keep intact all the\nnotices that refer to this License and to the absence of any warranty;\nand give any other recipients of the Program a copy of this License\nalong with the Program.\n\nYou may charge a fee for the physical act of transferring a copy, and\nyou may at your option offer warranty protection in exchange for a fee.\n\n  2. You may modify your copy or copies of the Program or any portion\nof it, thus forming a work based on the Program, and copy and\ndistribute such modifications or work under the terms of Section 1\nabove, provided that you also meet all of these conditions:\n\n    a) You must cause the modified files to carry prominent notices\n    stating that you changed the files and the date of any change.\n\n    b) You must cause any work that you distribute or publish, that in\n    whole or in part contains or is derived from the Program or any\n    part thereof, to be licensed as a whole at no charge to all third\n    parties under the terms of this License.\n\n    c) If the modified program normally reads commands interactively\n    when run, you must cause it, when started running for such\n    interactive use in the most ordinary way, to print or display an\n    announcement including an appropriate copyright notice and a\n    notice that there is no warranty (or else, saying that you provide\n    a warranty) and that users may redistribute the program under\n    these conditions, and telling the user how to view a copy of this\n    License.  (Exception: if the Program itself is interactive but\n    does not normally print such an announcement, your work based on\n    the Program is not required to print an announcement.)\n\nThese requirements apply to the modified work as a whole.  If\nidentifiable sections of that work are not derived from the Program,\nand can be reasonably considered independent and separate works in\nthemselves, then this License, and its terms, do not apply to those\nsections when you distribute them as separate works.  But when you\ndistribute the same sections as part of a whole which is a work based\non the Program, the distribution of the whole must be on the terms of\nthis License, whose permissions for other licensees extend to the\nentire whole, and thus to each and every part regardless of who wrote it.\n\nThus, it is not the intent of this section to claim rights or contest\nyour rights to work written entirely by you; rather, the intent is to\nexercise the right to control the distribution of derivative or\ncollective works based on the Program.\n\nIn addition, mere aggregation of another work not based on the Program\nwith the Program (or with a work based on the Program) on a volume of\na storage or distribution medium does not bring the other work under\nthe scope of this License.\n\n  3. You may copy and distribute the Program (or a work based on it,\nunder Section 2) in object code or executable form under the terms of\nSections 1 and 2 above provided that you also do one of the following:\n\n    a) Accompany it with the complete corresponding machine-readable\n    source code, which must be distributed under the terms of Sections\n    1 and 2 above on a medium customarily used for software interchange; or,\n\n    b) Accompany it with a written offer, valid for at least three\n    years, to give any third party, for a charge no more than your\n    cost of physically performing source distribution, a complete\n    machine-readable copy of the corresponding source code, to be\n    distributed under the terms of Sections 1 and 2 above on a medium\n    customarily used for software interchange; or,\n\n    c) Accompany it with the information you received as to the offer\n    to distribute corresponding source code.  (This alternative is\n    allowed only for noncommercial distribution and only if you\n    received the program in object code or executable form with such\n    an offer, in accord with Subsection b above.)\n\nThe source code for a work means the preferred form of the work for\nmaking modifications to it.  For an executable work, complete source\ncode means all the source code for all modules it contains, plus any\nassociated interface definition files, plus the scripts used to\ncontrol compilation and installation of the executable.  However, as a\nspecial exception, the source code distributed need not include\nanything that is normally distributed (in either source or binary\nform) with the major components (compiler, kernel, and so on) of the\noperating system on which the executable runs, unless that component\nitself accompanies the executable.\n\nIf distribution of executable or object code is made by offering\naccess to copy from a designated place, then offering equivalent\naccess to copy the source code from the same place counts as\ndistribution of the source code, even though third parties are not\ncompelled to copy the source along with the object code.\n\n  4. You may not copy, modify, sublicense, or distribute the Program\nexcept as expressly provided under this License.  Any attempt\notherwise to copy, modify, sublicense or distribute the Program is\nvoid, and will automatically terminate your rights under this License.\nHowever, parties who have received copies, or rights, from you under\nthis License will not have their licenses terminated so long as such\nparties remain in full compliance.\n\n  5. You are not required to accept this License, since you have not\nsigned it.  However, nothing else grants you permission to modify or\ndistribute the Program or its derivative works.  These actions are\nprohibited by law if you do not accept this License.  Therefore, by\nmodifying or distributing the Program (or any work based on the\nProgram), you indicate your acceptance of this License to do so, and\nall its terms and conditions for copying, distributing or modifying\nthe Program or works based on it.\n\n  6. Each time you redistribute the Program (or any work based on the\nProgram), the recipient automatically receives a license from the\noriginal licensor to copy, distribute or modify the Program subject to\nthese terms and conditions.  You may not impose any further\nrestrictions on the recipients' exercise of the rights granted herein.\nYou are not responsible for enforcing compliance by third parties to\nthis License.\n\n  7. If, as a consequence of a court judgment or allegation of patent\ninfringement or for any other reason (not limited to patent issues),\nconditions are imposed on you (whether by court order, agreement or\notherwise) that contradict the conditions of this License, they do not\nexcuse you from the conditions of this License.  If you cannot\ndistribute so as to satisfy simultaneously your obligations under this\nLicense and any other pertinent obligations, then as a consequence you\nmay not distribute the Program at all.  For example, if a patent\nlicense would not permit royalty-free redistribution of the Program by\nall those who receive copies directly or indirectly through you, then\nthe only way you could satisfy both it and this License would be to\nrefrain entirely from distribution of the Program.\n\nIf any portion of this section is held invalid or unenforceable under\nany particular circumstance, the balance of the section is intended to\napply and the section as a whole is intended to apply in other\ncircumstances.\n\nIt is not the purpose of this section to induce you to infringe any\npatents or other property right claims or to contest validity of any\nsuch claims; this section has the sole purpose of protecting the\nintegrity of the free software distribution system, which is\nimplemented by public license practices.  Many people have made\ngenerous contributions to the wide range of software distributed\nthrough that system in reliance on consistent application of that\nsystem; it is up to the author/donor to decide if he or she is willing\nto distribute software through any other system and a licensee cannot\nimpose that choice.\n\nThis section is intended to make thoroughly clear what is believed to\nbe a consequence of the rest of this License.\n\n  8. If the distribution and/or use of the Program is restricted in\ncertain countries either by patents or by copyrighted interfaces, the\noriginal copyright holder who places the Program under this License\nmay add an explicit geographical distribution limitation excluding\nthose countries, so that distribution is permitted only in or among\ncountries not thus excluded.  In such case, this License incorporates\nthe limitation as if written in the body of this License.\n\n  9. The Free Software Foundation may publish revised and/or new versions\nof the General Public License from time to time.  Such new versions will\nbe similar in spirit to the present version, but may differ in detail to\naddress new problems or concerns.\n\nEach version is given a distinguishing version number.  If the Program\nspecifies a version number of this License which applies to it and \"any\nlater version\", you have the option of following the terms and conditions\neither of that version or of any later version published by the Free\nSoftware Foundation.  If the Program does not specify a version number of\nthis License, you may choose any version ever published by the Free Software\nFoundation.\n\n  10. If you wish to incorporate parts of the Program into other free\nprograms whose distribution conditions are different, write to the author\nto ask for permission.  For software which is copyrighted by the Free\nSoftware Foundation, write to the Free Software Foundation; we sometimes\nmake exceptions for this.  Our decision will be guided by the two goals\nof preserving the free status of all derivatives of our free software and\nof promoting the sharing and reuse of software generally.\n\n                            NO WARRANTY\n\n  11. BECAUSE THE PROGRAM IS LICENSED FREE OF CHARGE, THERE IS NO WARRANTY\nFOR THE PROGRAM, TO THE EXTENT PERMITTED BY APPLICABLE LAW.  EXCEPT WHEN\nOTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR OTHER PARTIES\nPROVIDE THE PROGRAM \"AS IS\" WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED\nOR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF\nMERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.  THE ENTIRE RISK AS\nTO THE QUALITY AND PERFORMANCE OF THE PROGRAM IS WITH YOU.  SHOULD THE\nPROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF ALL NECESSARY SERVICING,\nREPAIR OR CORRECTION.\n\n  12. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING\nWILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY AND/OR\nREDISTRIBUTE THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES,\nINCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING\nOUT OF THE USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED\nTO LOSS OF DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY\nYOU OR THIRD PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER\nPROGRAMS), EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE\nPOSSIBILITY OF SUCH DAMAGES.\n\n                     END OF TERMS AND CONDITIONS\n\n            How to Apply These Terms to Your New Programs\n\n  If you develop a new program, and you want it to be of the greatest\npossible use to the public, the best way to achieve this is to make it\nfree software which everyone can redistribute and change under these terms.\n\n  To do so, attach the following notices to the program.  It is safest\nto attach them to the start of each source file to most effectively\nconvey the exclusion of warranty; and each file should have at least\nthe \"copyright\" line and a pointer to where the full notice is found.\n\n    <one line to give the program's name and a brief idea of what it does.>\n    Copyright (C) <year>  <name of author>\n\n    This program is free software; you can redistribute it and/or modify\n    it under the terms of the GNU General Public License as published by\n    the Free Software Foundation; either version 2 of the License, or\n    (at your option) any later version.\n\n    This program is distributed in the hope that it will be useful,\n    but WITHOUT ANY WARRANTY; without even the implied warranty of\n    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n    GNU General Public License for more details.\n\n    You should have received a copy of the GNU General Public License\n    along with this program; if not, write to the Free Software\n    Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA\n\n\nAlso add information on how to contact you by electronic and paper mail.\n\nIf the program is interactive, make it output a short notice like this\nwhen it starts in an interactive mode:\n\n    Gnomovision version 69, Copyright (C) year name of author\n    Gnomovision comes with ABSOLUTELY NO WARRANTY; for details type `show w'.\n    This is free software, and you are welcome to redistribute it\n    under certain conditions; type `show c' for details.\n\nThe hypothetical commands `show w' and `show c' should show the appropriate\nparts of the General Public License.  Of course, the commands you use may\nbe called something other than `show w' and `show c'; they could even be\nmouse-clicks or menu items--whatever suits your program.\n\nYou should also get your employer (if you work as a programmer) or your\nschool, if any, to sign a \"copyright disclaimer\" for the program, if\nnecessary.  Here is a sample; alter the names:\n\n  Yoyodyne, Inc., hereby disclaims all copyright interest in the program\n  `Gnomovision' (which makes passes at compilers) written by James Hacker.\n\n  <signature of Ty Coon>, 1 April 1989\n  Ty Coon, President of Vice\n\nThis General Public License does not permit incorporating your program into\nproprietary programs.  If your program is a subroutine library, you may\nconsider it more useful to permit linking proprietary applications with the\nlibrary.  If this is what you want to do, use the GNU Library General\nPublic License instead of this License.\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/README",
    "content": "Bench Template Library\n\n****************************************\nIntroduction :\n\nThe aim of this project is to compare the performance\nof available numerical libraries. The code is designed\nas generic and modular as possible. Thus, adding new\nnumerical libraries or new numerical tests should\nrequire minimal effort.\n\n\n*****************************************\n\nInstallation :\n\nBTL uses cmake / ctest:\n\n1 - create a build directory:\n\n  $ mkdir build\n  $ cd build\n\n2 - configure:\n\n  $ ccmake ..\n\n3 - run the bench using ctest:\n\n  $ ctest -V\n\nYou can run the benchmarks only on libraries matching a given regular expression:\n  ctest -V -R <regexp>\nFor instance:\n  ctest -V -R eigen2\n\nYou can also select a given set of actions defining the environment variable BTL_CONFIG this way:\n  BTL_CONFIG=\"-a action1{:action2}*\" ctest -V\nAn example:\n  BTL_CONFIG=\"-a axpy:vector_matrix:trisolve:ata\" ctest -V -R eigen2\n\nFinally, if bench results already exist (the bench*.dat files) then they merges by keeping the best for each matrix size. If you want to overwrite the previous ones you can simply add the \"--overwrite\" option:\n  BTL_CONFIG=\"-a axpy:vector_matrix:trisolve:ata --overwrite\" ctest -V -R eigen2\n\n4 : Analyze the result. different data files (.dat) are produced in each libs directories.\n If gnuplot is available, choose a directory name in the data directory to store the results and type:\n        $ cd data\n        $ mkdir my_directory\n        $ cp ../libs/*/*.dat my_directory\n Build the data utilities in this (data) directory\n        make\n Then you can look the raw data,\n        go_mean my_directory\n or smooth the data first :\n\tsmooth_all.sh my_directory\n\tgo_mean my_directory_smooth\n\n\n*************************************************\n\nFiles and directories :\n\n generic_bench : all the bench sources common to all libraries\n\n actions : sources for different action wrappers (axpy, matrix-matrix product) to be tested.\n\n libs/* : bench sources specific to each tested libraries.\n\n machine_dep : directory used to store machine specific Makefile.in\n\n data : directory used to store gnuplot scripts and data analysis utilities\n\n**************************************************\n\nPrinciples : the code modularity is achieved by defining two concepts :\n\n ****** Action concept : This is a class defining which kind\n  of test must be performed (e.g. a matrix_vector_product).\n\tAn Action should define the following methods :\n\n        *** Ctor using the size of the problem (matrix or vector size) as an argument\n\t    Action action(size);\n        *** initialize : this method initialize the calculation (e.g. initialize the matrices and vectors arguments)\n\t    action.initialize();\n\t*** calculate : this method actually launch the calculation to be benchmarked\n\t    action.calculate;\n\t*** nb_op_base() : this method returns the complexity of the calculate method (allowing the mflops evaluation)\n        *** name() : this method returns the name of the action (std::string)\n\n ****** Interface concept : This is a class or namespace defining how to use a given library and\n  its specific containers (matrix and vector). Up to now an interface should following types\n\n\t*** real_type : kind of float to be used (float or double)\n\t*** stl_vector : must correspond to std::vector<real_type>\n\t*** stl_matrix : must correspond to std::vector<stl_vector>\n\t*** gene_vector : the vector type for this interface        --> e.g. (real_type *) for the C_interface\n\t*** gene_matrix : the matrix type for this interface        --> e.g. (gene_vector *) for the C_interface\n\n\t+ the following common methods\n\n        *** free_matrix(gene_matrix & A, int N)  dealocation of a N sized gene_matrix A\n        *** free_vector(gene_vector & B)  dealocation of a N sized gene_vector B\n        *** matrix_from_stl(gene_matrix & A, stl_matrix & A_stl) copy the content of an stl_matrix A_stl into a gene_matrix A.\n\t     The allocation of A is done in this function.\n\t*** vector_to_stl(gene_vector & B, stl_vector & B_stl)  copy the content of an stl_vector B_stl into a gene_vector B.\n\t     The allocation of B is done in this function.\n        *** matrix_to_stl(gene_matrix & A, stl_matrix & A_stl) copy the content of an gene_matrix A into an stl_matrix A_stl.\n             The size of A_STL must corresponds to the size of A.\n        *** vector_to_stl(gene_vector & A, stl_vector & A_stl) copy the content of an gene_vector A into an stl_vector A_stl.\n             The size of B_STL must corresponds to the size of B.\n\t*** copy_matrix(gene_matrix & source, gene_matrix & cible, int N) : copy the content of source in cible. Both source\n\t\tand cible must be sized NxN.\n\t*** copy_vector(gene_vector & source, gene_vector & cible, int N) : copy the content of source in cible. Both source\n \t\tand cible must be sized N.\n\n\tand the following method corresponding to the action one wants to be benchmarked :\n\n\t***  matrix_vector_product(const gene_matrix & A, const gene_vector & B, gene_vector & X, int N)\n\t***  matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N)\n        ***  ata_product(const gene_matrix & A, gene_matrix & X, int N)\n\t***  aat_product(const gene_matrix & A, gene_matrix & X, int N)\n        ***  axpy(real coef, const gene_vector & X, gene_vector & Y, int N)\n\n The bench algorithm (generic_bench/bench.hh) is templated with an action itself templated with\n an interface. A typical main.cpp source stored in a given library directory libs/A_LIB\n looks like :\n\n bench< AN_ACTION < AN_INTERFACE > >( 10 , 1000 , 50 ) ;\n\n this function will produce XY data file containing measured  mflops as a function of the size for 50\n sizes between 10 and 10000.\n\n This algorithm can be adapted by providing a given Perf_Analyzer object which determines how the time\n measurements must be done. For example, the X86_Perf_Analyzer use the asm rdtsc function and provides\n a very fast and accurate (but less portable) timing method. The default is the Portable_Perf_Analyzer\n so\n\n bench< AN_ACTION < AN_INTERFACE > >( 10 , 1000 , 50 ) ;\n\n is equivalent to\n\n bench< Portable_Perf_Analyzer,AN_ACTION < AN_INTERFACE > >( 10 , 1000 , 50 ) ;\n\n If your system supports it we suggest to use a mixed implementation (X86_perf_Analyzer+Portable_Perf_Analyzer).\n replace\n     bench<Portable_Perf_Analyzer,Action>(size_min,size_max,nb_point);\n with\n     bench<Mixed_Perf_Analyzer,Action>(size_min,size_max,nb_point);\n in generic/bench.hh\n\n.\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/action_aat_product.hh",
    "content": "//=====================================================\n// File   :  action_aat_product.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_AAT_PRODUCT\n#define ACTION_AAT_PRODUCT\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_aat_product {\n\npublic :\n\n  // Ctor\n\n  Action_aat_product( int size ):_size(size)\n  {\n    MESSAGE(\"Action_aat_product Ctor\");\n\n    // STL matrix and vector initialization\n\n    init_matrix<pseudo_random>(A_stl,_size);\n    init_matrix<null_function>(X_stl,_size);\n    init_matrix<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::matrix_from_stl(X_ref,X_stl);\n\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::matrix_from_stl(X,X_stl);\n\n  }\n\n  // invalidate copy ctor\n\n  Action_aat_product( const  Action_aat_product & )\n  {\n    INFOS(\"illegal call to Action_aat_product Copy Ctor\");\n    exit(0);\n  }\n\n  // Dtor\n\n  ~Action_aat_product( void ){\n\n    MESSAGE(\"Action_aat_product Dtor\");\n\n    // deallocation\n\n    Interface::free_matrix(A,_size);\n    Interface::free_matrix(X,_size);\n\n    Interface::free_matrix(A_ref,_size);\n    Interface::free_matrix(X_ref,_size);\n\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"aat_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return double(_size)*double(_size)*double(_size);\n  }\n\n  inline void initialize( void ){\n\n    Interface::copy_matrix(A_ref,A,_size);\n    Interface::copy_matrix(X_ref,X,_size);\n\n  }\n\n  inline void calculate( void ) {\n\n      Interface::aat_product(A,X,_size);\n\n  }\n\n  void check_result( void ){\n    if (_size>128) return;\n    // calculation check\n\n    Interface::matrix_to_stl(X,resu_stl);\n\n    STL_interface<typename Interface::real_type>::aat_product(A_stl,X_stl,_size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n\n    if (error>1.e-6){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n      exit(1);\n    }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix A_stl;\n  typename Interface::stl_matrix X_stl;\n  typename Interface::stl_matrix resu_stl;\n\n  typename Interface::gene_matrix A_ref;\n  typename Interface::gene_matrix X_ref;\n\n  typename Interface::gene_matrix A;\n  typename Interface::gene_matrix X;\n\n\n  int _size;\n\n};\n\n\n#endif\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/action_ata_product.hh",
    "content": "//=====================================================\n// File   :  action_ata_product.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_ATA_PRODUCT\n#define ACTION_ATA_PRODUCT\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_ata_product {\n\npublic :\n\n  // Ctor\n\n  Action_ata_product( int size ):_size(size)\n  {\n    MESSAGE(\"Action_ata_product Ctor\");\n\n    // STL matrix and vector initialization\n\n    init_matrix<pseudo_random>(A_stl,_size);\n    init_matrix<null_function>(X_stl,_size);\n    init_matrix<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::matrix_from_stl(X_ref,X_stl);\n\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::matrix_from_stl(X,X_stl);\n\n  }\n\n  // invalidate copy ctor\n\n  Action_ata_product( const  Action_ata_product & )\n  {\n    INFOS(\"illegal call to Action_ata_product Copy Ctor\");\n    exit(0);\n  }\n\n  // Dtor\n\n  ~Action_ata_product( void ){\n\n    MESSAGE(\"Action_ata_product Dtor\");\n\n    // deallocation\n\n    Interface::free_matrix(A,_size);\n    Interface::free_matrix(X,_size);\n\n    Interface::free_matrix(A_ref,_size);\n    Interface::free_matrix(X_ref,_size);\n\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"ata_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return 2.0*_size*_size*_size;\n  }\n\n  inline void initialize( void ){\n\n    Interface::copy_matrix(A_ref,A,_size);\n    Interface::copy_matrix(X_ref,X,_size);\n\n  }\n\n  inline void calculate( void ) {\n\n      Interface::ata_product(A,X,_size);\n\n  }\n\n  void check_result( void ){\n    if (_size>128) return;\n    // calculation check\n\n    Interface::matrix_to_stl(X,resu_stl);\n\n    STL_interface<typename Interface::real_type>::ata_product(A_stl,X_stl,_size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n\n    if (error>1.e-6){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n      exit(1);\n    }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix A_stl;\n  typename Interface::stl_matrix X_stl;\n  typename Interface::stl_matrix resu_stl;\n\n  typename Interface::gene_matrix A_ref;\n  typename Interface::gene_matrix X_ref;\n\n  typename Interface::gene_matrix A;\n  typename Interface::gene_matrix X;\n\n\n  int _size;\n\n};\n\n\n#endif\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/action_atv_product.hh",
    "content": "//=====================================================\n// File   :  action_atv_product.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_ATV_PRODUCT\n#define ACTION_ATV_PRODUCT\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_atv_product {\n\npublic :\n\n  Action_atv_product( int size ) : _size(size)\n  {\n    MESSAGE(\"Action_atv_product Ctor\");\n\n    // STL matrix and vector initialization\n\n    init_matrix<pseudo_random>(A_stl,_size);\n    init_vector<pseudo_random>(B_stl,_size);\n    init_vector<null_function>(X_stl,_size);\n    init_vector<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::vector_from_stl(B_ref,B_stl);\n    Interface::vector_from_stl(X_ref,X_stl);\n\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::vector_from_stl(B,B_stl);\n    Interface::vector_from_stl(X,X_stl);\n  }\n\n  // invalidate copy ctor\n  Action_atv_product( const  Action_atv_product & )\n  {\n    INFOS(\"illegal call to Action_atv_product Copy Ctor\");\n    exit(1);\n  }\n\n  ~Action_atv_product( void )\n  {\n    MESSAGE(\"Action_atv_product Dtor\");\n\n    Interface::free_matrix(A,_size);\n    Interface::free_vector(B);\n    Interface::free_vector(X);\n\n    Interface::free_matrix(A_ref,_size);\n    Interface::free_vector(B_ref);\n    Interface::free_vector(X_ref);\n  }\n\n  static inline std::string name() { return \"atv_\" + Interface::name(); }\n\n  double nb_op_base( void ) { return 2.0*_size*_size; }\n\n  inline void initialize( void ){\n    Interface::copy_matrix(A_ref,A,_size);\n    Interface::copy_vector(B_ref,B,_size);\n    Interface::copy_vector(X_ref,X,_size);\n  }\n\n  BTL_DONT_INLINE void calculate( void ) {\n    BTL_ASM_COMMENT(\"begin atv\");\n    Interface::atv_product(A,B,X,_size);\n    BTL_ASM_COMMENT(\"end atv\");\n  }\n\n  void check_result( void )\n  {\n    if (_size>128) return;\n    Interface::vector_to_stl(X,resu_stl);\n\n    STL_interface<typename Interface::real_type>::atv_product(A_stl,B_stl,X_stl,_size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n\n    if (error>1.e-6){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n      exit(1);\n    }\n  }\n\nprivate :\n\n  typename Interface::stl_matrix A_stl;\n  typename Interface::stl_vector B_stl;\n  typename Interface::stl_vector X_stl;\n  typename Interface::stl_vector resu_stl;\n\n  typename Interface::gene_matrix A_ref;\n  typename Interface::gene_vector B_ref;\n  typename Interface::gene_vector X_ref;\n\n  typename Interface::gene_matrix A;\n  typename Interface::gene_vector B;\n  typename Interface::gene_vector X;\n\n\n  int _size;\n\n};\n\n\n#endif\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/action_axpby.hh",
    "content": "//=====================================================\n// File   :  action_axpby.hh\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_AXPBY\n#define ACTION_AXPBY\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_axpby {\n\npublic :\n\n  // Ctor\n  Action_axpby( int size ):_alpha(0.5),_beta(0.95),_size(size)\n  {\n    MESSAGE(\"Action_axpby Ctor\");\n\n    // STL vector initialization\n    init_vector<pseudo_random>(X_stl,_size);\n    init_vector<pseudo_random>(Y_stl,_size);\n    init_vector<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n    Interface::vector_from_stl(X_ref,X_stl);\n    Interface::vector_from_stl(Y_ref,Y_stl);\n\n    Interface::vector_from_stl(X,X_stl);\n    Interface::vector_from_stl(Y,Y_stl);\n  }\n\n  // invalidate copy ctor\n  Action_axpby( const  Action_axpby & )\n  {\n    INFOS(\"illegal call to Action_axpby Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n  ~Action_axpby( void ){\n    MESSAGE(\"Action_axpby Dtor\");\n\n    // deallocation\n    Interface::free_vector(X_ref);\n    Interface::free_vector(Y_ref);\n\n    Interface::free_vector(X);\n    Interface::free_vector(Y);\n  }\n\n  // action name\n  static inline std::string name( void )\n  {\n    return \"axpby_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return 3.0*_size;\n  }\n\n  inline void initialize( void ){\n    Interface::copy_vector(X_ref,X,_size);\n    Interface::copy_vector(Y_ref,Y,_size);\n  }\n\n  inline void calculate( void ) {\n    BTL_ASM_COMMENT(\"mybegin axpby\");\n    Interface::axpby(_alpha,X,_beta,Y,_size);\n    BTL_ASM_COMMENT(\"myend axpby\");\n  }\n\n  void check_result( void ){\n    if (_size>128) return;\n    // calculation check\n    Interface::vector_to_stl(Y,resu_stl);\n\n    STL_interface<typename Interface::real_type>::axpby(_alpha,X_stl,_beta,Y_stl,_size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(Y_stl,resu_stl);\n\n    if (error>1.e-6){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n      exit(2);\n    }\n  }\n\nprivate :\n\n  typename Interface::stl_vector X_stl;\n  typename Interface::stl_vector Y_stl;\n  typename Interface::stl_vector resu_stl;\n\n  typename Interface::gene_vector X_ref;\n  typename Interface::gene_vector Y_ref;\n\n  typename Interface::gene_vector X;\n  typename Interface::gene_vector Y;\n\n  typename Interface::real_type _alpha;\n  typename Interface::real_type _beta;\n\n  int _size;\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/action_axpy.hh",
    "content": "//=====================================================\n// File   :  action_axpy.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_AXPY\n#define ACTION_AXPY\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_axpy {\n\npublic :\n\n  // Ctor\n\n  Action_axpy( int size ):_coef(1.0),_size(size)\n  {\n    MESSAGE(\"Action_axpy Ctor\");\n\n    // STL vector initialization\n\n    init_vector<pseudo_random>(X_stl,_size);\n    init_vector<pseudo_random>(Y_stl,_size);\n    init_vector<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n\n    Interface::vector_from_stl(X_ref,X_stl);\n    Interface::vector_from_stl(Y_ref,Y_stl);\n\n    Interface::vector_from_stl(X,X_stl);\n    Interface::vector_from_stl(Y,Y_stl);\n\n\n  }\n\n  // invalidate copy ctor\n\n  Action_axpy( const  Action_axpy & )\n  {\n    INFOS(\"illegal call to Action_axpy Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n\n  ~Action_axpy( void ){\n\n    MESSAGE(\"Action_axpy Dtor\");\n\n    // deallocation\n\n    Interface::free_vector(X_ref);\n    Interface::free_vector(Y_ref);\n\n    Interface::free_vector(X);\n    Interface::free_vector(Y);\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"axpy_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return 2.0*_size;\n  }\n\n  inline void initialize( void ){\n    Interface::copy_vector(X_ref,X,_size);\n    Interface::copy_vector(Y_ref,Y,_size);\n  }\n\n  inline void calculate( void ) {\n    BTL_ASM_COMMENT(\"mybegin axpy\");\n    Interface::axpy(_coef,X,Y,_size);\n    BTL_ASM_COMMENT(\"myend axpy\");\n  }\n\n  void check_result( void ){\n    if (_size>128) return;\n    // calculation check\n\n    Interface::vector_to_stl(Y,resu_stl);\n\n    STL_interface<typename Interface::real_type>::axpy(_coef,X_stl,Y_stl,_size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(Y_stl,resu_stl);\n\n    if (error>1.e-6){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n      exit(0);\n    }\n\n  }\n\nprivate :\n\n  typename Interface::stl_vector X_stl;\n  typename Interface::stl_vector Y_stl;\n  typename Interface::stl_vector resu_stl;\n\n  typename Interface::gene_vector X_ref;\n  typename Interface::gene_vector Y_ref;\n\n  typename Interface::gene_vector X;\n  typename Interface::gene_vector Y;\n\n  typename Interface::real_type _coef;\n\n  int _size;\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/action_cholesky.hh",
    "content": "//=====================================================\n// File   :  action_cholesky.hh\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_CHOLESKY\n#define ACTION_CHOLESKY\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_cholesky {\n\npublic :\n\n  // Ctor\n\n  Action_cholesky( int size ):_size(size)\n  {\n    MESSAGE(\"Action_cholesky Ctor\");\n\n    // STL mat/vec initialization\n    init_matrix_symm<pseudo_random>(X_stl,_size);\n    init_matrix<null_function>(C_stl,_size);\n\n    // make sure X is invertible\n    for (int i=0; i<_size; ++i)\n      X_stl[i][i] = std::abs(X_stl[i][i]) * 1e2 + 100;\n\n    // generic matrix and vector initialization\n    Interface::matrix_from_stl(X_ref,X_stl);\n    Interface::matrix_from_stl(X,X_stl);\n    Interface::matrix_from_stl(C,C_stl);\n\n    _cost = 0;\n    for (int j=0; j<_size; ++j)\n    {\n      double r = std::max(_size - j -1,0);\n      _cost += 2*(r*j+r+j);\n    }\n  }\n\n  // invalidate copy ctor\n\n  Action_cholesky( const  Action_cholesky & )\n  {\n    INFOS(\"illegal call to Action_cholesky Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n\n  ~Action_cholesky( void ){\n\n    MESSAGE(\"Action_cholesky Dtor\");\n\n    // deallocation\n    Interface::free_matrix(X_ref,_size);\n    Interface::free_matrix(X,_size);\n    Interface::free_matrix(C,_size);\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"cholesky_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return _cost;\n  }\n\n  inline void initialize( void ){\n    Interface::copy_matrix(X_ref,X,_size);\n  }\n\n  inline void calculate( void ) {\n      Interface::cholesky(X,C,_size);\n  }\n\n  void check_result( void ){\n    // calculation check\n//     STL_interface<typename Interface::real_type>::cholesky(X_stl,C_stl,_size);\n//\n//     typename Interface::real_type error=\n//       STL_interface<typename Interface::real_type>::norm_diff(C_stl,resu_stl);\n//\n//     if (error>1.e-6){\n//       INFOS(\"WRONG CALCULATION...residual=\" << error);\n//       exit(0);\n//     }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix X_stl;\n  typename Interface::stl_matrix C_stl;\n\n  typename Interface::gene_matrix X_ref;\n  typename Interface::gene_matrix X;\n  typename Interface::gene_matrix C;\n\n  int _size;\n  double _cost;\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/action_ger.hh",
    "content": "\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_GER\n#define ACTION_GER\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_ger {\n\npublic :\n\n  // Ctor\n  BTL_DONT_INLINE Action_ger( int size ):_size(size)\n  {\n    MESSAGE(\"Action_ger Ctor\");\n\n    // STL matrix and vector initialization\n    typename Interface::stl_matrix tmp;\n    init_matrix<pseudo_random>(A_stl,_size);\n    init_vector<pseudo_random>(B_stl,_size);\n    init_vector<pseudo_random>(X_stl,_size);\n    init_vector<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::vector_from_stl(B_ref,B_stl);\n    Interface::vector_from_stl(B,B_stl);\n    Interface::vector_from_stl(X_ref,X_stl);\n    Interface::vector_from_stl(X,X_stl);\n  }\n\n  // invalidate copy ctor\n  Action_ger( const  Action_ger & )\n  {\n    INFOS(\"illegal call to Action_ger Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n  BTL_DONT_INLINE ~Action_ger( void ){\n    MESSAGE(\"Action_ger Dtor\");\n    Interface::free_matrix(A,_size);\n    Interface::free_vector(B);\n    Interface::free_vector(X);\n    Interface::free_matrix(A_ref,_size);\n    Interface::free_vector(B_ref);\n    Interface::free_vector(X_ref);\n\n  }\n\n  // action name\n  static inline std::string name( void )\n  {\n    return \"ger_\" + Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return 2.0*_size*_size;\n  }\n\n  BTL_DONT_INLINE  void initialize( void ){\n    Interface::copy_matrix(A_ref,A,_size);\n    Interface::copy_vector(B_ref,B,_size);\n    Interface::copy_vector(X_ref,X,_size);\n  }\n\n  BTL_DONT_INLINE void calculate( void ) {\n    BTL_ASM_COMMENT(\"#begin ger\");\n    Interface::ger(A,B,X,_size);\n    BTL_ASM_COMMENT(\"end ger\");\n  }\n\n  BTL_DONT_INLINE void check_result( void ){\n    // calculation check\n    Interface::vector_to_stl(X,resu_stl);\n\n    STL_interface<typename Interface::real_type>::ger(A_stl,B_stl,X_stl,_size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n\n    if (error>1.e-3){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n//       exit(0);\n    }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix A_stl;\n  typename Interface::stl_vector B_stl;\n  typename Interface::stl_vector X_stl;\n  typename Interface::stl_vector resu_stl;\n\n  typename Interface::gene_matrix A_ref;\n  typename Interface::gene_vector B_ref;\n  typename Interface::gene_vector X_ref;\n\n  typename Interface::gene_matrix A;\n  typename Interface::gene_vector B;\n  typename Interface::gene_vector X;\n\n  int _size;\n};\n\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/action_hessenberg.hh",
    "content": "//=====================================================\n// File   :  action_hessenberg.hh\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_HESSENBERG\n#define ACTION_HESSENBERG\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_hessenberg {\n\npublic :\n\n  // Ctor\n\n  Action_hessenberg( int size ):_size(size)\n  {\n    MESSAGE(\"Action_hessenberg Ctor\");\n\n    // STL vector initialization\n    init_matrix<pseudo_random>(X_stl,_size);\n\n    init_matrix<null_function>(C_stl,_size);\n    init_matrix<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n    Interface::matrix_from_stl(X_ref,X_stl);\n    Interface::matrix_from_stl(X,X_stl);\n    Interface::matrix_from_stl(C,C_stl);\n\n    _cost = 0;\n    for (int j=0; j<_size-2; ++j)\n    {\n      double r = std::max(0,_size-j-1);\n      double b = std::max(0,_size-j-2);\n      _cost += 6 + 3*b + r*r*4 + r*_size*4;\n    }\n  }\n\n  // invalidate copy ctor\n\n  Action_hessenberg( const  Action_hessenberg & )\n  {\n    INFOS(\"illegal call to Action_hessenberg Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n\n  ~Action_hessenberg( void ){\n\n    MESSAGE(\"Action_hessenberg Dtor\");\n\n    // deallocation\n    Interface::free_matrix(X_ref,_size);\n    Interface::free_matrix(X,_size);\n    Interface::free_matrix(C,_size);\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"hessenberg_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return _cost;\n  }\n\n  inline void initialize( void ){\n    Interface::copy_matrix(X_ref,X,_size);\n  }\n\n  inline void calculate( void ) {\n      Interface::hessenberg(X,C,_size);\n  }\n\n  void check_result( void ){\n    // calculation check\n    Interface::matrix_to_stl(C,resu_stl);\n\n//     STL_interface<typename Interface::real_type>::hessenberg(X_stl,C_stl,_size);\n//\n//     typename Interface::real_type error=\n//       STL_interface<typename Interface::real_type>::norm_diff(C_stl,resu_stl);\n//\n//     if (error>1.e-6){\n//       INFOS(\"WRONG CALCULATION...residual=\" << error);\n//       exit(0);\n//     }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix X_stl;\n  typename Interface::stl_matrix C_stl;\n  typename Interface::stl_matrix resu_stl;\n\n  typename Interface::gene_matrix X_ref;\n  typename Interface::gene_matrix X;\n  typename Interface::gene_matrix C;\n\n  int _size;\n  double _cost;\n};\n\ntemplate<class Interface>\nclass Action_tridiagonalization {\n\npublic :\n\n  // Ctor\n\n  Action_tridiagonalization( int size ):_size(size)\n  {\n    MESSAGE(\"Action_tridiagonalization Ctor\");\n\n    // STL vector initialization\n    init_matrix<pseudo_random>(X_stl,_size);\n    \n    for(int i=0; i<_size; ++i)\n    {\n      for(int j=0; j<i; ++j)\n        X_stl[i][j] = X_stl[j][i];\n    }\n    \n    init_matrix<null_function>(C_stl,_size);\n    init_matrix<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n    Interface::matrix_from_stl(X_ref,X_stl);\n    Interface::matrix_from_stl(X,X_stl);\n    Interface::matrix_from_stl(C,C_stl);\n\n    _cost = 0;\n    for (int j=0; j<_size-2; ++j)\n    {\n      double r = std::max(0,_size-j-1);\n      double b = std::max(0,_size-j-2);\n      _cost += 6. + 3.*b + r*r*8.;\n    }\n  }\n\n  // invalidate copy ctor\n\n  Action_tridiagonalization( const  Action_tridiagonalization & )\n  {\n    INFOS(\"illegal call to Action_tridiagonalization Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n\n  ~Action_tridiagonalization( void ){\n\n    MESSAGE(\"Action_tridiagonalization Dtor\");\n\n    // deallocation\n    Interface::free_matrix(X_ref,_size);\n    Interface::free_matrix(X,_size);\n    Interface::free_matrix(C,_size);\n  }\n\n  // action name\n\n  static inline std::string name( void ) { return \"tridiagonalization_\"+Interface::name(); }\n\n  double nb_op_base( void ){\n    return _cost;\n  }\n\n  inline void initialize( void ){\n    Interface::copy_matrix(X_ref,X,_size);\n  }\n\n  inline void calculate( void ) {\n      Interface::tridiagonalization(X,C,_size);\n  }\n\n  void check_result( void ){\n    // calculation check\n    Interface::matrix_to_stl(C,resu_stl);\n\n//     STL_interface<typename Interface::real_type>::tridiagonalization(X_stl,C_stl,_size);\n//\n//     typename Interface::real_type error=\n//       STL_interface<typename Interface::real_type>::norm_diff(C_stl,resu_stl);\n//\n//     if (error>1.e-6){\n//       INFOS(\"WRONG CALCULATION...residual=\" << error);\n//       exit(0);\n//     }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix X_stl;\n  typename Interface::stl_matrix C_stl;\n  typename Interface::stl_matrix resu_stl;\n\n  typename Interface::gene_matrix X_ref;\n  typename Interface::gene_matrix X;\n  typename Interface::gene_matrix C;\n\n  int _size;\n  double _cost;\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/action_lu_decomp.hh",
    "content": "//=====================================================\n// File   :  action_lu_decomp.hh\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_LU_DECOMP\n#define ACTION_LU_DECOMP\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_lu_decomp {\n\npublic :\n\n  // Ctor\n\n  Action_lu_decomp( int size ):_size(size)\n  {\n    MESSAGE(\"Action_lu_decomp Ctor\");\n\n    // STL vector initialization\n    init_matrix<pseudo_random>(X_stl,_size);\n\n    init_matrix<null_function>(C_stl,_size);\n    init_matrix<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n    Interface::matrix_from_stl(X_ref,X_stl);\n    Interface::matrix_from_stl(X,X_stl);\n    Interface::matrix_from_stl(C,C_stl);\n\n    _cost = 2.0*size*size*size/3.0 + size*size;\n  }\n\n  // invalidate copy ctor\n\n  Action_lu_decomp( const  Action_lu_decomp & )\n  {\n    INFOS(\"illegal call to Action_lu_decomp Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n\n  ~Action_lu_decomp( void ){\n\n    MESSAGE(\"Action_lu_decomp Dtor\");\n\n    // deallocation\n    Interface::free_matrix(X_ref,_size);\n    Interface::free_matrix(X,_size);\n    Interface::free_matrix(C,_size);\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"complete_lu_decomp_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return _cost;\n  }\n\n  inline void initialize( void ){\n    Interface::copy_matrix(X_ref,X,_size);\n  }\n\n  inline void calculate( void ) {\n      Interface::lu_decomp(X,C,_size);\n  }\n\n  void check_result( void ){\n    // calculation check\n    Interface::matrix_to_stl(C,resu_stl);\n\n//     STL_interface<typename Interface::real_type>::lu_decomp(X_stl,C_stl,_size);\n//\n//     typename Interface::real_type error=\n//       STL_interface<typename Interface::real_type>::norm_diff(C_stl,resu_stl);\n//\n//     if (error>1.e-6){\n//       INFOS(\"WRONG CALCULATION...residual=\" << error);\n//       exit(0);\n//     }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix X_stl;\n  typename Interface::stl_matrix C_stl;\n  typename Interface::stl_matrix resu_stl;\n\n  typename Interface::gene_matrix X_ref;\n  typename Interface::gene_matrix X;\n  typename Interface::gene_matrix C;\n\n  int _size;\n  double _cost;\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/action_lu_solve.hh",
    "content": "//=====================================================\n// File   :  action_lu_solve.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef ACTION_LU_SOLVE\n#define ACTION_LU_SOLVE\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_lu_solve \n{\n\npublic :\n\n  static inline std::string name( void )\n  {\n    return \"lu_solve_\"+Interface::name();\n  }\n  \n  static double nb_op_base(int size){\n    return 2.0*size*size*size/3.0;  // questionable but not really important\n  }\n\n\n  static double calculate( int nb_calc, int size ) {\n\n    // STL matrix and vector initialization\n    \n    typename Interface::stl_matrix A_stl;\n    typename Interface::stl_vector B_stl;\n    typename Interface::stl_vector X_stl;\n\n    init_matrix<pseudo_random>(A_stl,size);\n    init_vector<pseudo_random>(B_stl,size);\n    init_vector<null_function>(X_stl,size);\n\n    // generic matrix and vector initialization\n\n    typename Interface::gene_matrix A;\n    typename Interface::gene_vector B;\n    typename Interface::gene_vector X;\n\n    typename Interface::gene_matrix LU; \n\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::vector_from_stl(B,B_stl);\n    Interface::vector_from_stl(X,X_stl);\n    Interface::matrix_from_stl(LU,A_stl);\n  \n    // local variable :\n\n    typename Interface::Pivot_Vector pivot; // pivot vector\n    Interface::new_Pivot_Vector(pivot,size);\n    \n    // timer utilities\n\n    Portable_Timer chronos;\n\n    // time measurement\n\n    chronos.start();\n    \n    for (int ii=0;ii<nb_calc;ii++){\n\n      // LU factorization\n      Interface::copy_matrix(A,LU,size);\n      Interface::LU_factor(LU,pivot,size);\n      \n      // LU solve\n\n      Interface::LU_solve(LU,pivot,B,X,size);\n\n    }\n\n    // Time stop\n\n    chronos.stop();\n\n    double time=chronos.user_time();\n  \n    // check result :\n\n    typename Interface::stl_vector B_new_stl(size);\n    Interface::vector_to_stl(X,X_stl);\n\n    STL_interface<typename Interface::real_type>::matrix_vector_product(A_stl,X_stl,B_new_stl,size); \n  \n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(B_stl,B_new_stl);\n    \n    if (error>1.e-5){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n      STL_interface<typename Interface::real_type>::display_vector(B_stl);\n      STL_interface<typename Interface::real_type>::display_vector(B_new_stl);\n      exit(0);\n    }\n    \n    // deallocation and return time\n    \n    Interface::free_matrix(A,size);\n    Interface::free_vector(B);\n    Interface::free_vector(X);\n    Interface::free_Pivot_Vector(pivot);\n\n    return time;\n  }\n\n};\n  \n\n#endif\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/action_matrix_matrix_product.hh",
    "content": "//=====================================================\n// File   :  action_matrix_matrix_product.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_MATRIX_MATRIX_PRODUCT\n#define ACTION_MATRIX_MATRIX_PRODUCT\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_matrix_matrix_product {\n\npublic :\n\n  // Ctor\n\n  Action_matrix_matrix_product( int size ):_size(size)\n  {\n    MESSAGE(\"Action_matrix_matrix_product Ctor\");\n\n    // STL matrix and vector initialization\n\n    init_matrix<pseudo_random>(A_stl,_size);\n    init_matrix<pseudo_random>(B_stl,_size);\n    init_matrix<null_function>(X_stl,_size);\n    init_matrix<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::matrix_from_stl(B_ref,B_stl);\n    Interface::matrix_from_stl(X_ref,X_stl);\n\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::matrix_from_stl(B,B_stl);\n    Interface::matrix_from_stl(X,X_stl);\n\n  }\n\n  // invalidate copy ctor\n\n  Action_matrix_matrix_product( const  Action_matrix_matrix_product & )\n  {\n    INFOS(\"illegal call to Action_matrix_matrix_product Copy Ctor\");\n    exit(0);\n  }\n\n  // Dtor\n\n  ~Action_matrix_matrix_product( void ){\n\n    MESSAGE(\"Action_matrix_matrix_product Dtor\");\n\n    // deallocation\n\n    Interface::free_matrix(A,_size);\n    Interface::free_matrix(B,_size);\n    Interface::free_matrix(X,_size);\n\n    Interface::free_matrix(A_ref,_size);\n    Interface::free_matrix(B_ref,_size);\n    Interface::free_matrix(X_ref,_size);\n\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"matrix_matrix_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return 2.0*_size*_size*_size;\n  }\n\n  inline void initialize( void ){\n\n    Interface::copy_matrix(A_ref,A,_size);\n    Interface::copy_matrix(B_ref,B,_size);\n    Interface::copy_matrix(X_ref,X,_size);\n\n  }\n\n  inline void calculate( void ) {\n      Interface::matrix_matrix_product(A,B,X,_size);\n  }\n\n  void check_result( void ){\n\n    // calculation check\n    if (_size<200)\n    {\n      Interface::matrix_to_stl(X,resu_stl);\n      STL_interface<typename Interface::real_type>::matrix_matrix_product(A_stl,B_stl,X_stl,_size);\n      typename Interface::real_type error=\n        STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n      if (error>1.e-6){\n        INFOS(\"WRONG CALCULATION...residual=\" << error);\n        exit(1);\n      }\n    }\n  }\n\nprivate :\n\n  typename Interface::stl_matrix A_stl;\n  typename Interface::stl_matrix B_stl;\n  typename Interface::stl_matrix X_stl;\n  typename Interface::stl_matrix resu_stl;\n\n  typename Interface::gene_matrix A_ref;\n  typename Interface::gene_matrix B_ref;\n  typename Interface::gene_matrix X_ref;\n\n  typename Interface::gene_matrix A;\n  typename Interface::gene_matrix B;\n  typename Interface::gene_matrix X;\n\n\n  int _size;\n\n};\n\n\n#endif\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/action_matrix_matrix_product_bis.hh",
    "content": "//=====================================================\n// File   :  action_matrix_matrix_product_bis.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_MATRIX_MATRIX_PRODUCT_BIS\n#define ACTION_MATRIX_MATRIX_PRODUCT_BIS\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include \"STL_timer.hh\"\n#include <string>\n#include \"init_function.hh\"\n#include \"init_vector.hh\"\n#include \"init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_matrix_matrix_product_bis {\n\npublic :\n\n  static inline std::string name( void )\n  {\n    return \"matrix_matrix_\"+Interface::name();\n  }\n\n  static double nb_op_base(int size){\n    return 2.0*size*size*size;\n  }\n\n  static double calculate( int nb_calc, int size ) {\n\n    // STL matrix and vector initialization\n\n    typename Interface::stl_matrix A_stl;\n    typename Interface::stl_matrix B_stl;\n    typename Interface::stl_matrix X_stl;\n\n    init_matrix<pseudo_random>(A_stl,size);\n    init_matrix<pseudo_random>(B_stl,size);\n    init_matrix<null_function>(X_stl,size);\n\n    // generic matrix and vector initialization\n\n    typename Interface::gene_matrix A_ref;\n    typename Interface::gene_matrix B_ref;\n    typename Interface::gene_matrix X_ref;\n\n    typename Interface::gene_matrix A;\n    typename Interface::gene_matrix B;\n    typename Interface::gene_matrix X;\n\n\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::matrix_from_stl(B_ref,B_stl);\n    Interface::matrix_from_stl(X_ref,X_stl);\n\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::matrix_from_stl(B,B_stl);\n    Interface::matrix_from_stl(X,X_stl);\n\n\n    // STL_timer utilities\n\n    STL_timer chronos;\n\n    // Baseline evaluation\n\n    chronos.start_baseline(nb_calc);\n\n    do {\n\n      Interface::copy_matrix(A_ref,A,size);\n      Interface::copy_matrix(B_ref,B,size);\n      Interface::copy_matrix(X_ref,X,size);\n\n\n      //      Interface::matrix_matrix_product(A,B,X,size); This line must be commented !!!!\n    }\n    while(chronos.check());\n\n    chronos.report(true);\n\n    // Time measurement\n\n    chronos.start(nb_calc);\n\n    do {\n\n      Interface::copy_matrix(A_ref,A,size);\n      Interface::copy_matrix(B_ref,B,size);\n      Interface::copy_matrix(X_ref,X,size);\n\n      Interface::matrix_matrix_product(A,B,X,size); // here it is not commented !!!!\n    }\n    while(chronos.check());\n\n    chronos.report(true);\n\n    double time=chronos.calculated_time/2000.0;\n\n    // calculation check\n\n    typename Interface::stl_matrix resu_stl(size);\n\n    Interface::matrix_to_stl(X,resu_stl);\n\n    STL_interface<typename Interface::real_type>::matrix_matrix_product(A_stl,B_stl,X_stl,size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n\n    if (error>1.e-6){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n      exit(1);\n    }\n\n    // deallocation and return time\n\n    Interface::free_matrix(A,size);\n    Interface::free_matrix(B,size);\n    Interface::free_matrix(X,size);\n\n    Interface::free_matrix(A_ref,size);\n    Interface::free_matrix(B_ref,size);\n    Interface::free_matrix(X_ref,size);\n\n    return time;\n  }\n\n};\n\n\n#endif\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/action_matrix_vector_product.hh",
    "content": "//=====================================================\n// File   :  action_matrix_vector_product.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_MATRIX_VECTOR_PRODUCT\n#define ACTION_MATRIX_VECTOR_PRODUCT\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_matrix_vector_product {\n\npublic :\n\n  // Ctor\n\n  BTL_DONT_INLINE Action_matrix_vector_product( int size ):_size(size)\n  {\n    MESSAGE(\"Action_matrix_vector_product Ctor\");\n\n    // STL matrix and vector initialization\n\n    init_matrix<pseudo_random>(A_stl,_size);\n    init_vector<pseudo_random>(B_stl,_size);\n    init_vector<null_function>(X_stl,_size);\n    init_vector<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::vector_from_stl(B_ref,B_stl);\n    Interface::vector_from_stl(B,B_stl);\n    Interface::vector_from_stl(X_ref,X_stl);\n    Interface::vector_from_stl(X,X_stl);\n\n  }\n\n  // invalidate copy ctor\n\n  Action_matrix_vector_product( const  Action_matrix_vector_product & )\n  {\n    INFOS(\"illegal call to Action_matrix_vector_product Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n\n  BTL_DONT_INLINE ~Action_matrix_vector_product( void ){\n\n    MESSAGE(\"Action_matrix_vector_product Dtor\");\n\n    // deallocation\n\n    Interface::free_matrix(A,_size);\n    Interface::free_vector(B);\n    Interface::free_vector(X);\n\n    Interface::free_matrix(A_ref,_size);\n    Interface::free_vector(B_ref);\n    Interface::free_vector(X_ref);\n\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"matrix_vector_\" + Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return 2.0*_size*_size;\n  }\n\n  BTL_DONT_INLINE  void initialize( void ){\n\n    Interface::copy_matrix(A_ref,A,_size);\n    Interface::copy_vector(B_ref,B,_size);\n    Interface::copy_vector(X_ref,X,_size);\n\n  }\n\n  BTL_DONT_INLINE void calculate( void ) {\n      BTL_ASM_COMMENT(\"#begin matrix_vector_product\");\n      Interface::matrix_vector_product(A,B,X,_size);\n      BTL_ASM_COMMENT(\"end matrix_vector_product\");\n  }\n\n  BTL_DONT_INLINE void check_result( void ){\n\n    // calculation check\n\n    Interface::vector_to_stl(X,resu_stl);\n\n    STL_interface<typename Interface::real_type>::matrix_vector_product(A_stl,B_stl,X_stl,_size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n\n    if (error>1.e-5){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n      exit(0);\n    }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix A_stl;\n  typename Interface::stl_vector B_stl;\n  typename Interface::stl_vector X_stl;\n  typename Interface::stl_vector resu_stl;\n\n  typename Interface::gene_matrix A_ref;\n  typename Interface::gene_vector B_ref;\n  typename Interface::gene_vector X_ref;\n\n  typename Interface::gene_matrix A;\n  typename Interface::gene_vector B;\n  typename Interface::gene_vector X;\n\n\n  int _size;\n\n};\n\n\n#endif\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/action_partial_lu.hh",
    "content": "//=====================================================\n// File   :  action_lu_decomp.hh\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_PARTIAL_LU\n#define ACTION_PARTIAL_LU\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_partial_lu {\n\npublic :\n\n  // Ctor\n\n  Action_partial_lu( int size ):_size(size)\n  {\n    MESSAGE(\"Action_partial_lu Ctor\");\n\n    // STL vector initialization\n    init_matrix<pseudo_random>(X_stl,_size);\n    init_matrix<null_function>(C_stl,_size);\n\n    // make sure X is invertible\n    for (int i=0; i<_size; ++i)\n      X_stl[i][i] = X_stl[i][i] * 1e2 + 1;\n\n    // generic matrix and vector initialization\n    Interface::matrix_from_stl(X_ref,X_stl);\n    Interface::matrix_from_stl(X,X_stl);\n    Interface::matrix_from_stl(C,C_stl);\n\n    _cost = 2.0*size*size*size/3.0 + size*size;\n  }\n\n  // invalidate copy ctor\n\n  Action_partial_lu( const  Action_partial_lu & )\n  {\n    INFOS(\"illegal call to Action_partial_lu Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n\n  ~Action_partial_lu( void ){\n\n    MESSAGE(\"Action_partial_lu Dtor\");\n\n    // deallocation\n    Interface::free_matrix(X_ref,_size);\n    Interface::free_matrix(X,_size);\n    Interface::free_matrix(C,_size);\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"partial_lu_decomp_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return _cost;\n  }\n\n  inline void initialize( void ){\n    Interface::copy_matrix(X_ref,X,_size);\n  }\n\n  inline void calculate( void ) {\n      Interface::partial_lu_decomp(X,C,_size);\n  }\n\n  void check_result( void ){\n    // calculation check\n//     Interface::matrix_to_stl(C,resu_stl);\n\n//     STL_interface<typename Interface::real_type>::lu_decomp(X_stl,C_stl,_size);\n//\n//     typename Interface::real_type error=\n//       STL_interface<typename Interface::real_type>::norm_diff(C_stl,resu_stl);\n//\n//     if (error>1.e-6){\n//       INFOS(\"WRONG CALCULATION...residual=\" << error);\n//       exit(0);\n//     }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix X_stl;\n  typename Interface::stl_matrix C_stl;\n\n  typename Interface::gene_matrix X_ref;\n  typename Interface::gene_matrix X;\n  typename Interface::gene_matrix C;\n\n  int _size;\n  double _cost;\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/action_rot.hh",
    "content": "\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_ROT\n#define ACTION_ROT\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_rot {\n\npublic :\n\n  // Ctor\n  BTL_DONT_INLINE Action_rot( int size ):_size(size)\n  {\n    MESSAGE(\"Action_rot Ctor\");\n\n    // STL matrix and vector initialization\n    typename Interface::stl_matrix tmp;\n    init_vector<pseudo_random>(A_stl,_size);\n    init_vector<pseudo_random>(B_stl,_size);\n\n    // generic matrix and vector initialization\n    Interface::vector_from_stl(A_ref,A_stl);\n    Interface::vector_from_stl(A,A_stl);\n    Interface::vector_from_stl(B_ref,B_stl);\n    Interface::vector_from_stl(B,B_stl);\n  }\n\n  // invalidate copy ctor\n  Action_rot( const  Action_rot & )\n  {\n    INFOS(\"illegal call to Action_rot Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n  BTL_DONT_INLINE ~Action_rot( void ){\n    MESSAGE(\"Action_rot Dtor\");\n    Interface::free_vector(A);\n    Interface::free_vector(B);\n    Interface::free_vector(A_ref);\n    Interface::free_vector(B_ref);\n  }\n\n  // action name\n  static inline std::string name( void )\n  {\n    return \"rot_\" + Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return 6.0*_size;\n  }\n\n  BTL_DONT_INLINE  void initialize( void ){\n    Interface::copy_vector(A_ref,A,_size);\n    Interface::copy_vector(B_ref,B,_size);\n  }\n\n  BTL_DONT_INLINE void calculate( void ) {\n    BTL_ASM_COMMENT(\"#begin rot\");\n    Interface::rot(A,B,0.5,0.6,_size);\n    BTL_ASM_COMMENT(\"end rot\");\n  }\n\n  BTL_DONT_INLINE void check_result( void ){\n    // calculation check\n//     Interface::vector_to_stl(X,resu_stl);\n\n//     STL_interface<typename Interface::real_type>::rot(A_stl,B_stl,X_stl,_size);\n\n//     typename Interface::real_type error=\n//       STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n\n//     if (error>1.e-3){\n//       INFOS(\"WRONG CALCULATION...residual=\" << error);\n//       exit(0);\n//     }\n\n  }\n\nprivate :\n\n  typename Interface::stl_vector A_stl;\n  typename Interface::stl_vector B_stl;\n\n  typename Interface::gene_vector A_ref;\n  typename Interface::gene_vector B_ref;\n\n  typename Interface::gene_vector A;\n  typename Interface::gene_vector B;\n\n  int _size;\n};\n\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/action_symv.hh",
    "content": "//=====================================================\n// File   :  action_symv.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_SYMV\n#define ACTION_SYMV\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_symv {\n\npublic :\n\n  // Ctor\n\n  BTL_DONT_INLINE Action_symv( int size ):_size(size)\n  {\n    MESSAGE(\"Action_symv Ctor\");\n\n    // STL matrix and vector initialization\n    init_matrix_symm<pseudo_random>(A_stl,_size);\n    init_vector<pseudo_random>(B_stl,_size);\n    init_vector<null_function>(X_stl,_size);\n    init_vector<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::vector_from_stl(B_ref,B_stl);\n    Interface::vector_from_stl(B,B_stl);\n    Interface::vector_from_stl(X_ref,X_stl);\n    Interface::vector_from_stl(X,X_stl);\n\n  }\n\n  // invalidate copy ctor\n\n  Action_symv( const  Action_symv & )\n  {\n    INFOS(\"illegal call to Action_symv Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n  BTL_DONT_INLINE ~Action_symv( void ){\n    Interface::free_matrix(A,_size);\n    Interface::free_vector(B);\n    Interface::free_vector(X);\n    Interface::free_matrix(A_ref,_size);\n    Interface::free_vector(B_ref);\n    Interface::free_vector(X_ref);\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"symv_\" + Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return 2.0*_size*_size;\n  }\n\n  BTL_DONT_INLINE  void initialize( void ){\n\n    Interface::copy_matrix(A_ref,A,_size);\n    Interface::copy_vector(B_ref,B,_size);\n    Interface::copy_vector(X_ref,X,_size);\n\n  }\n\n  BTL_DONT_INLINE void calculate( void ) {\n      BTL_ASM_COMMENT(\"#begin symv\");\n      Interface::symv(A,B,X,_size);\n      BTL_ASM_COMMENT(\"end symv\");\n  }\n\n  BTL_DONT_INLINE void check_result( void ){\n    if (_size>128) return;\n    // calculation check\n    Interface::vector_to_stl(X,resu_stl);\n\n    STL_interface<typename Interface::real_type>::symv(A_stl,B_stl,X_stl,_size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n\n    if (error>1.e-5){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n      exit(0);\n    }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix A_stl;\n  typename Interface::stl_vector B_stl;\n  typename Interface::stl_vector X_stl;\n  typename Interface::stl_vector resu_stl;\n\n  typename Interface::gene_matrix A_ref;\n  typename Interface::gene_vector B_ref;\n  typename Interface::gene_vector X_ref;\n\n  typename Interface::gene_matrix A;\n  typename Interface::gene_vector B;\n  typename Interface::gene_vector X;\n\n\n  int _size;\n\n};\n\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/action_syr2.hh",
    "content": "//=====================================================\n// File   :  action_syr2.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_SYR2\n#define ACTION_SYR2\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_syr2 {\n\npublic :\n\n  // Ctor\n\n  BTL_DONT_INLINE Action_syr2( int size ):_size(size)\n  {\n    // STL matrix and vector initialization\n    typename Interface::stl_matrix tmp;\n    init_matrix<pseudo_random>(A_stl,_size);\n    init_vector<pseudo_random>(B_stl,_size);\n    init_vector<pseudo_random>(X_stl,_size);\n    init_vector<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::vector_from_stl(B_ref,B_stl);\n    Interface::vector_from_stl(B,B_stl);\n    Interface::vector_from_stl(X_ref,X_stl);\n    Interface::vector_from_stl(X,X_stl);\n  }\n\n  // invalidate copy ctor\n  Action_syr2( const  Action_syr2 & )\n  {\n    INFOS(\"illegal call to Action_syr2 Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n  BTL_DONT_INLINE ~Action_syr2( void ){\n    Interface::free_matrix(A,_size);\n    Interface::free_vector(B);\n    Interface::free_vector(X);\n    Interface::free_matrix(A_ref,_size);\n    Interface::free_vector(B_ref);\n    Interface::free_vector(X_ref);\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"syr2_\" + Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return 2.0*_size*_size;\n  }\n\n  BTL_DONT_INLINE  void initialize( void ){\n    Interface::copy_matrix(A_ref,A,_size);\n    Interface::copy_vector(B_ref,B,_size);\n    Interface::copy_vector(X_ref,X,_size);\n  }\n\n  BTL_DONT_INLINE void calculate( void ) {\n      BTL_ASM_COMMENT(\"#begin syr2\");\n      Interface::syr2(A,B,X,_size);\n      BTL_ASM_COMMENT(\"end syr2\");\n  }\n\n  BTL_DONT_INLINE void check_result( void ){\n    // calculation check\n    Interface::vector_to_stl(X,resu_stl);\n\n    STL_interface<typename Interface::real_type>::syr2(A_stl,B_stl,X_stl,_size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n\n    if (error>1.e-3){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n//       exit(0);\n    }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix A_stl;\n  typename Interface::stl_vector B_stl;\n  typename Interface::stl_vector X_stl;\n  typename Interface::stl_vector resu_stl;\n\n  typename Interface::gene_matrix A_ref;\n  typename Interface::gene_vector B_ref;\n  typename Interface::gene_vector X_ref;\n\n  typename Interface::gene_matrix A;\n  typename Interface::gene_vector B;\n  typename Interface::gene_vector X;\n\n\n  int _size;\n\n};\n\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/action_trisolve.hh",
    "content": "//=====================================================\n// File   :  action_trisolve.hh\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_TRISOLVE\n#define ACTION_TRISOLVE\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_trisolve {\n\npublic :\n\n  // Ctor\n\n  Action_trisolve( int size ):_size(size)\n  {\n    MESSAGE(\"Action_trisolve Ctor\");\n\n    // STL vector initialization\n    init_matrix<pseudo_random>(L_stl,_size);\n    init_vector<pseudo_random>(B_stl,_size);\n    init_vector<null_function>(X_stl,_size);\n    for (int j=0; j<_size; ++j)\n    {\n      for (int i=0; i<j; ++i)\n        L_stl[j][i] = 0;\n      L_stl[j][j] += 3;\n    }\n\n    init_vector<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n    Interface::matrix_from_stl(L,L_stl);\n    Interface::vector_from_stl(X,X_stl);\n    Interface::vector_from_stl(B,B_stl);\n\n    _cost = 0;\n    for (int j=0; j<_size; ++j)\n    {\n      _cost += 2*j + 1;\n    }\n  }\n\n  // invalidate copy ctor\n\n  Action_trisolve( const  Action_trisolve & )\n  {\n    INFOS(\"illegal call to Action_trisolve Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n\n  ~Action_trisolve( void ){\n\n    MESSAGE(\"Action_trisolve Dtor\");\n\n    // deallocation\n    Interface::free_matrix(L,_size);\n    Interface::free_vector(B);\n    Interface::free_vector(X);\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"trisolve_vector_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return _cost;\n  }\n\n  inline void initialize( void ){\n    //Interface::copy_vector(X_ref,X,_size);\n  }\n\n  inline void calculate( void ) {\n      Interface::trisolve_lower(L,B,X,_size);\n  }\n\n  void check_result(){\n    if (_size>128) return;\n    // calculation check\n    Interface::vector_to_stl(X,resu_stl);\n\n    STL_interface<typename Interface::real_type>::trisolve_lower(L_stl,B_stl,X_stl,_size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n\n    if (error>1.e-4){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n      exit(2);\n    } //else INFOS(\"CALCULATION OK...residual=\" << error);\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix L_stl;\n  typename Interface::stl_vector X_stl;\n  typename Interface::stl_vector B_stl;\n  typename Interface::stl_vector resu_stl;\n\n  typename Interface::gene_matrix L;\n  typename Interface::gene_vector X;\n  typename Interface::gene_vector B;\n\n  int _size;\n  double _cost;\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/action_trisolve_matrix.hh",
    "content": "//=====================================================\n// File   :  action_matrix_matrix_product.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_TRISOLVE_MATRIX_PRODUCT\n#define ACTION_TRISOLVE_MATRIX_PRODUCT\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_trisolve_matrix {\n\npublic :\n\n  // Ctor\n\n  Action_trisolve_matrix( int size ):_size(size)\n  {\n    MESSAGE(\"Action_trisolve_matrix Ctor\");\n\n    // STL matrix and vector initialization\n\n    init_matrix<pseudo_random>(A_stl,_size);\n    init_matrix<pseudo_random>(B_stl,_size);\n    init_matrix<null_function>(X_stl,_size);\n    init_matrix<null_function>(resu_stl,_size);\n\n    for (int j=0; j<_size; ++j)\n    {\n      for (int i=0; i<j; ++i)\n        A_stl[j][i] = 0;\n      A_stl[j][j] += 3;\n    }\n\n    // generic matrix and vector initialization\n\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::matrix_from_stl(B_ref,B_stl);\n    Interface::matrix_from_stl(X_ref,X_stl);\n\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::matrix_from_stl(B,B_stl);\n    Interface::matrix_from_stl(X,X_stl);\n\n    _cost = 0;\n    for (int j=0; j<_size; ++j)\n    {\n      _cost += 2*j + 1;\n    }\n    _cost *= _size;\n  }\n\n  // invalidate copy ctor\n\n  Action_trisolve_matrix( const  Action_trisolve_matrix & )\n  {\n    INFOS(\"illegal call to Action_trisolve_matrix Copy Ctor\");\n    exit(0);\n  }\n\n  // Dtor\n\n  ~Action_trisolve_matrix( void ){\n\n    MESSAGE(\"Action_trisolve_matrix Dtor\");\n\n    // deallocation\n\n    Interface::free_matrix(A,_size);\n    Interface::free_matrix(B,_size);\n    Interface::free_matrix(X,_size);\n\n    Interface::free_matrix(A_ref,_size);\n    Interface::free_matrix(B_ref,_size);\n    Interface::free_matrix(X_ref,_size);\n\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"trisolve_matrix_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return _cost;\n  }\n\n  inline void initialize( void ){\n\n    Interface::copy_matrix(A_ref,A,_size);\n    Interface::copy_matrix(B_ref,B,_size);\n    Interface::copy_matrix(X_ref,X,_size);\n\n  }\n\n  inline void calculate( void ) {\n      Interface::trisolve_lower_matrix(A,B,X,_size);\n  }\n\n  void check_result( void ){\n\n    // calculation check\n\n//     Interface::matrix_to_stl(X,resu_stl);\n//\n//     STL_interface<typename Interface::real_type>::matrix_matrix_product(A_stl,B_stl,X_stl,_size);\n//\n//     typename Interface::real_type error=\n//       STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n//\n//     if (error>1.e-6){\n//       INFOS(\"WRONG CALCULATION...residual=\" << error);\n// //       exit(1);\n//     }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix A_stl;\n  typename Interface::stl_matrix B_stl;\n  typename Interface::stl_matrix X_stl;\n  typename Interface::stl_matrix resu_stl;\n\n  typename Interface::gene_matrix A_ref;\n  typename Interface::gene_matrix B_ref;\n  typename Interface::gene_matrix X_ref;\n\n  typename Interface::gene_matrix A;\n  typename Interface::gene_matrix B;\n  typename Interface::gene_matrix X;\n\n  int _size;\n  double _cost;\n\n};\n\n\n#endif\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/action_trmm.hh",
    "content": "//=====================================================\n// File   :  action_matrix_matrix_product.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_TRMM\n#define ACTION_TRMM\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_trmm {\n\npublic :\n\n  // Ctor\n\n  Action_trmm( int size ):_size(size)\n  {\n    MESSAGE(\"Action_trmm Ctor\");\n\n    // STL matrix and vector initialization\n\n    init_matrix<pseudo_random>(A_stl,_size);\n    init_matrix<pseudo_random>(B_stl,_size);\n    init_matrix<null_function>(X_stl,_size);\n    init_matrix<null_function>(resu_stl,_size);\n\n    for (int j=0; j<_size; ++j)\n    {\n      for (int i=0; i<j; ++i)\n        A_stl[j][i] = 0;\n      A_stl[j][j] += 3;\n    }\n\n    // generic matrix and vector initialization\n\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::matrix_from_stl(B_ref,B_stl);\n    Interface::matrix_from_stl(X_ref,X_stl);\n\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::matrix_from_stl(B,B_stl);\n    Interface::matrix_from_stl(X,X_stl);\n\n    _cost = 0;\n    for (int j=0; j<_size; ++j)\n    {\n      _cost += 2*j + 1;\n    }\n    _cost *= _size;\n  }\n\n  // invalidate copy ctor\n\n  Action_trmm( const  Action_trmm & )\n  {\n    INFOS(\"illegal call to Action_trmm Copy Ctor\");\n    exit(0);\n  }\n\n  // Dtor\n\n  ~Action_trmm( void ){\n\n    MESSAGE(\"Action_trmm Dtor\");\n\n    // deallocation\n\n    Interface::free_matrix(A,_size);\n    Interface::free_matrix(B,_size);\n    Interface::free_matrix(X,_size);\n\n    Interface::free_matrix(A_ref,_size);\n    Interface::free_matrix(B_ref,_size);\n    Interface::free_matrix(X_ref,_size);\n\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"trmm_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return _cost;\n  }\n\n  inline void initialize( void ){\n\n    Interface::copy_matrix(A_ref,A,_size);\n    Interface::copy_matrix(B_ref,B,_size);\n    Interface::copy_matrix(X_ref,X,_size);\n\n  }\n\n  inline void calculate( void ) {\n      Interface::trmm(A,B,X,_size);\n  }\n\n  void check_result( void ){\n\n    // calculation check\n\n//     Interface::matrix_to_stl(X,resu_stl);\n//\n//     STL_interface<typename Interface::real_type>::matrix_matrix_product(A_stl,B_stl,X_stl,_size);\n//\n//     typename Interface::real_type error=\n//       STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n//\n//     if (error>1.e-6){\n//       INFOS(\"WRONG CALCULATION...residual=\" << error);\n// //       exit(1);\n//     }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix A_stl;\n  typename Interface::stl_matrix B_stl;\n  typename Interface::stl_matrix X_stl;\n  typename Interface::stl_matrix resu_stl;\n\n  typename Interface::gene_matrix A_ref;\n  typename Interface::gene_matrix B_ref;\n  typename Interface::gene_matrix X_ref;\n\n  typename Interface::gene_matrix A;\n  typename Interface::gene_matrix B;\n  typename Interface::gene_matrix X;\n\n  int _size;\n  double _cost;\n\n};\n\n\n#endif\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/actions/basic_actions.hh",
    "content": "\n#include \"action_axpy.hh\"\n#include \"action_axpby.hh\"\n\n#include \"action_matrix_vector_product.hh\"\n#include \"action_atv_product.hh\"\n\n#include \"action_matrix_matrix_product.hh\"\n#include \"action_ata_product.hh\"\n#include \"action_aat_product.hh\"\n\n#include \"action_trisolve.hh\"\n#include \"action_trmm.hh\"\n#include \"action_symv.hh\"\n// #include \"action_symm.hh\"\n#include \"action_syr2.hh\"\n#include \"action_ger.hh\"\n#include \"action_rot.hh\"\n\n// #include \"action_lu_solve.hh\"\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/cmake/FindACML.cmake",
    "content": "\nif (ACML_LIBRARIES)\n  set(ACML_FIND_QUIETLY TRUE)\nendif ()\n\nfind_library(ACML_LIBRARIES\n  NAMES\n  acml_mp acml_mv\n  PATHS\n  $ENV{ACMLDIR}/lib\n  $ENV{ACML_DIR}/lib\n  ${LIB_INSTALL_DIR}\n)\n\nfind_file(ACML_LIBRARIES\n  NAMES\n  libacml_mp.so\n  PATHS\n  /usr/lib\n  /usr/lib64\n  $ENV{ACMLDIR}/lib\n  ${LIB_INSTALL_DIR}\n)\n\nif(NOT ACML_LIBRARIES)\n    message(STATUS \"Multi-threaded library not found, looking for single-threaded\")\n    find_library(ACML_LIBRARIES\n        NAMES\n        acml acml_mv\n        PATHS\n        $ENV{ACMLDIR}/lib\n        $ENV{ACML_DIR}/lib\n        ${LIB_INSTALL_DIR}\n        )\n    find_file(ACML_LIBRARIES\n        libacml.so libacml_mv.so\n        PATHS\n        /usr/lib\n        /usr/lib64\n        $ENV{ACMLDIR}/lib\n        ${LIB_INSTALL_DIR}\n        )\nendif()\n\n\n\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(ACML DEFAULT_MSG ACML_LIBRARIES)\n\nmark_as_advanced(ACML_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/cmake/FindATLAS.cmake",
    "content": "\nif (ATLAS_LIBRARIES)\n  set(ATLAS_FIND_QUIETLY TRUE)\nendif ()\n\nfind_file(ATLAS_LIB libatlas.so.3 PATHS /usr/lib /usr/lib/atlas /usr/lib64 /usr/lib64/atlas $ENV{ATLASDIR} ${LIB_INSTALL_DIR})\nfind_library(ATLAS_LIB satlas PATHS $ENV{ATLASDIR} ${LIB_INSTALL_DIR})\n\nfind_file(ATLAS_LAPACK NAMES liblapack_atlas.so.3 liblapack.so.3 PATHS /usr/lib /usr/lib/atlas /usr/lib64 /usr/lib64/atlas $ENV{ATLASDIR} ${LIB_INSTALL_DIR})\nfind_library(ATLAS_LAPACK NAMES lapack_atlas lapack PATHS $ENV{ATLASDIR} ${LIB_INSTALL_DIR})\n\nfind_file(ATLAS_F77BLAS libf77blas.so.3 PATHS /usr/lib /usr/lib/atlas /usr/lib64 /usr/lib64/atlas $ENV{ATLASDIR} ${LIB_INSTALL_DIR})\nfind_library(ATLAS_F77BLAS f77blas PATHS $ENV{ATLASDIR} ${LIB_INSTALL_DIR})\n\nif(ATLAS_LIB AND ATLAS_CBLAS AND ATLAS_LAPACK AND ATLAS_F77BLAS)\n\n  set(ATLAS_LIBRARIES ${ATLAS_LAPACK}  ${ATLAS_LIB})\n  \n  # search the default lapack lib link to it\n  find_file(ATLAS_REFERENCE_LAPACK liblapack.so.3 PATHS /usr/lib /usr/lib64)\n  find_library(ATLAS_REFERENCE_LAPACK NAMES lapack)\n#   if(ATLAS_REFERENCE_LAPACK)\n#     set(ATLAS_LIBRARIES ${ATLAS_LIBRARIES} ${ATLAS_REFERENCE_LAPACK})\n#   endif()\n  \nendif()\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(ATLAS DEFAULT_MSG ATLAS_LIBRARIES)\n\nmark_as_advanced(ATLAS_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/cmake/FindBLAZE.cmake",
    "content": "# - Try to find eigen2 headers\n# Once done this will define\n#\n#  BLAZE_FOUND - system has blaze lib\n#  BLAZE_INCLUDE_DIR - the blaze include directory\n#\n# Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n# Adapted from FindEigen.cmake:\n# Copyright (c) 2006, 2007 Montel Laurent, <montel@kde.org>\n# Redistribution and use is allowed according to the terms of the BSD license.\n# For details see the accompanying COPYING-CMAKE-SCRIPTS file.\n\nif (BLAZE_INCLUDE_DIR)\n\n  # in cache already\n  set(BLAZE_FOUND TRUE)\n\nelse ()\n\nfind_path(BLAZE_INCLUDE_DIR NAMES blaze/Blaze.h\n     PATHS\n     ${INCLUDE_INSTALL_DIR}\n   )\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(BLAZE DEFAULT_MSG BLAZE_INCLUDE_DIR)\n\nmark_as_advanced(BLAZE_INCLUDE_DIR)\n\nendif()\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/cmake/FindBlitz.cmake",
    "content": "# - Try to find blitz lib\n# Once done this will define\n#\n#  BLITZ_FOUND - system has blitz lib\n#  BLITZ_INCLUDES - the blitz include directory\n#  BLITZ_LIBRARIES - The libraries needed to use blitz\n\n# Copyright (c) 2006, Montel Laurent, <montel@kde.org>\n# Copyright (c) 2007, Allen Winter, <winter@kde.org>\n# Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n# Redistribution and use is allowed according to the terms of the BSD license.\n# For details see the accompanying COPYING-CMAKE-SCRIPTS file.\n\n# include(FindLibraryWithDebug)\n\nif (BLITZ_INCLUDES AND BLITZ_LIBRARIES)\n  set(Blitz_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(BLITZ_INCLUDES\n  NAMES\n  blitz/array.h\n  PATH_SUFFIXES blitz*\n  PATHS\n  $ENV{BLITZDIR}/include\n  ${INCLUDE_INSTALL_DIR}\n)\n\nfind_library(BLITZ_LIBRARIES\n  blitz\n  PATHS\n  $ENV{BLITZDIR}/lib\n  ${LIB_INSTALL_DIR}\n)\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(Blitz DEFAULT_MSG\n                                  BLITZ_INCLUDES BLITZ_LIBRARIES)\n\nmark_as_advanced(BLITZ_INCLUDES BLITZ_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/cmake/FindCBLAS.cmake",
    "content": "# include(FindLibraryWithDebug)\n\nif (CBLAS_INCLUDES AND CBLAS_LIBRARIES)\n  set(CBLAS_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(CBLAS_INCLUDES\n  NAMES\n  cblas.h\n  PATHS\n  $ENV{CBLASDIR}/include\n  ${INCLUDE_INSTALL_DIR}\n)\n\nfind_library(CBLAS_LIBRARIES\n  cblas\n  PATHS\n  $ENV{CBLASDIR}/lib\n  ${LIB_INSTALL_DIR}\n)\n\nfind_file(CBLAS_LIBRARIES\n  libcblas.so.3\n  PATHS\n  /usr/lib\n  /usr/lib64\n  $ENV{CBLASDIR}/lib\n  ${LIB_INSTALL_DIR}\n)\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(CBLAS DEFAULT_MSG\n                                  CBLAS_INCLUDES CBLAS_LIBRARIES)\n\nmark_as_advanced(CBLAS_INCLUDES CBLAS_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/cmake/FindGMM.cmake",
    "content": "if (GMM_INCLUDE_DIR)\n  # in cache already\n  set(GMM_FOUND TRUE)\nelse ()\n\nfind_path(GMM_INCLUDE_DIR NAMES gmm/gmm.h\n     PATHS\n     ${INCLUDE_INSTALL_DIR}\n     ${GMM_INCLUDE_PATH}\n   )\n\ninclude(FindPackageHandleStandardArgs)\nFIND_PACKAGE_HANDLE_STANDARD_ARGS(GMM DEFAULT_MSG GMM_INCLUDE_DIR )\n\nmark_as_advanced(GMM_INCLUDE_DIR)\n\nendif()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/cmake/FindMKL.cmake",
    "content": "\nif (MKL_LIBRARIES)\n  set(MKL_FIND_QUIETLY TRUE)\nendif ()\n\nif(CMAKE_MINOR_VERSION GREATER 4)\n\nif(${CMAKE_HOST_SYSTEM_PROCESSOR} STREQUAL \"x86_64\")\n\nfind_library(MKL_LIBRARIES\n  mkl_core\n  PATHS\n  $ENV{MKLLIB}\n  /opt/intel/mkl/*/lib/em64t\n  /opt/intel/Compiler/*/*/mkl/lib/em64t\n  ${LIB_INSTALL_DIR}\n)\n\nfind_library(MKL_GUIDE\n  guide\n  PATHS\n  $ENV{MKLLIB}\n  /opt/intel/mkl/*/lib/em64t\n  /opt/intel/Compiler/*/*/mkl/lib/em64t\n  /opt/intel/Compiler/*/*/lib/intel64\n  ${LIB_INSTALL_DIR}\n)\n\nif(MKL_LIBRARIES AND MKL_GUIDE)\n  set(MKL_LIBRARIES ${MKL_LIBRARIES} mkl_intel_lp64 mkl_sequential ${MKL_GUIDE} pthread)\nendif()\n\nelse()\n\nfind_library(MKL_LIBRARIES\n  mkl_core\n  PATHS\n  $ENV{MKLLIB}\n  /opt/intel/mkl/*/lib/32\n  /opt/intel/Compiler/*/*/mkl/lib/32\n  ${LIB_INSTALL_DIR}\n)\n\nfind_library(MKL_GUIDE\n  guide\n  PATHS\n  $ENV{MKLLIB}\n  /opt/intel/mkl/*/lib/32\n  /opt/intel/Compiler/*/*/mkl/lib/32\n  /opt/intel/Compiler/*/*/lib/intel32\n  ${LIB_INSTALL_DIR}\n)\n\nif(MKL_LIBRARIES AND MKL_GUIDE)\n  set(MKL_LIBRARIES ${MKL_LIBRARIES} mkl_intel mkl_sequential ${MKL_GUIDE} pthread)\nendif()\n\nendif()\n\nendif()\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(MKL DEFAULT_MSG MKL_LIBRARIES)\n\nmark_as_advanced(MKL_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/cmake/FindMTL4.cmake",
    "content": "# - Try to find eigen2 headers\n# Once done this will define\n#\n#  MTL4_FOUND - system has eigen2 lib\n#  MTL4_INCLUDE_DIR - the eigen2 include directory\n#\n# Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n# Adapted from FindEigen.cmake:\n# Copyright (c) 2006, 2007 Montel Laurent, <montel@kde.org>\n# Redistribution and use is allowed according to the terms of the BSD license.\n# For details see the accompanying COPYING-CMAKE-SCRIPTS file.\n\nif (MTL4_INCLUDE_DIR)\n\n  # in cache already\n  set(MTL4_FOUND TRUE)\n\nelse ()\n\nfind_path(MTL4_INCLUDE_DIR NAMES boost/numeric/mtl/mtl.hpp\n     PATHS\n     ${INCLUDE_INSTALL_DIR}\n   )\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(MTL4 DEFAULT_MSG MTL4_INCLUDE_DIR)\n\nmark_as_advanced(MTL4_INCLUDE_DIR)\n\nendif()\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/cmake/FindOPENBLAS.cmake",
    "content": "\nif (OPENBLAS_LIBRARIES)\n  set(OPENBLAS_FIND_QUIETLY TRUE)\nendif ()\n\nfind_file(OPENBLAS_LIBRARIES NAMES libopenblas.so libopenblas.so.0 PATHS /usr/lib /usr/lib64 $ENV{OPENBLASDIR} ${LIB_INSTALL_DIR})\nfind_library(OPENBLAS_LIBRARIES openblas PATHS $ENV{OPENBLASDIR} ${LIB_INSTALL_DIR})\n\nif(OPENBLAS_LIBRARIES AND CMAKE_COMPILER_IS_GNUCXX)\n  set(OPENBLAS_LIBRARIES ${OPENBLAS_LIBRARIES} \"-lpthread -lgfortran\")\nendif()\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(OPENBLAS DEFAULT_MSG\n                                  OPENBLAS_LIBRARIES)\n\nmark_as_advanced(OPENBLAS_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/cmake/FindPackageHandleStandardArgs.cmake",
    "content": "# FIND_PACKAGE_HANDLE_STANDARD_ARGS(NAME (DEFAULT_MSG|\"Custom failure message\") VAR1 ... )\n#\n# This macro is intended to be used in FindXXX.cmake modules files.\n# It handles the REQUIRED and QUIET argument to find_package() and\n# it also sets the <UPPERCASED_NAME>_FOUND variable.\n# The package is found if all variables listed are TRUE.\n# Example:\n#\n#    FIND_PACKAGE_HANDLE_STANDARD_ARGS(LibXml2 DEFAULT_MSG LIBXML2_LIBRARIES LIBXML2_INCLUDE_DIR)\n#\n# LibXml2 is considered to be found, if both LIBXML2_LIBRARIES and \n# LIBXML2_INCLUDE_DIR are valid. Then also LIBXML2_FOUND is set to TRUE.\n# If it is not found and REQUIRED was used, it fails with FATAL_ERROR, \n# independent whether QUIET was used or not.\n#\n# If it is found, the location is reported using the VAR1 argument, so \n# here a message \"Found LibXml2: /usr/lib/libxml2.so\" will be printed out.\n# If the second argument is DEFAULT_MSG, the message in the failure case will \n# be \"Could NOT find LibXml2\", if you don't like this message you can specify\n# your own custom failure message there.\n\nmacro(FIND_PACKAGE_HANDLE_STANDARD_ARGS _NAME _FAIL_MSG _VAR1 )\n\n  if(\"${_FAIL_MSG}\" STREQUAL \"DEFAULT_MSG\")\n    if (${_NAME}_FIND_REQUIRED)\n      set(_FAIL_MESSAGE \"Could not find REQUIRED package ${_NAME}\")\n    else (${_NAME}_FIND_REQUIRED)\n      set(_FAIL_MESSAGE \"Could not find OPTIONAL package ${_NAME}\")\n    endif (${_NAME}_FIND_REQUIRED)\n  else(\"${_FAIL_MSG}\" STREQUAL \"DEFAULT_MSG\")\n    set(_FAIL_MESSAGE \"${_FAIL_MSG}\")\n  endif(\"${_FAIL_MSG}\" STREQUAL \"DEFAULT_MSG\")\n\n  string(TOUPPER ${_NAME} _NAME_UPPER)\n\n  set(${_NAME_UPPER}_FOUND TRUE)\n  if(NOT ${_VAR1})\n    set(${_NAME_UPPER}_FOUND FALSE)\n  endif(NOT ${_VAR1})\n\n  foreach(_CURRENT_VAR ${ARGN})\n    if(NOT ${_CURRENT_VAR})\n      set(${_NAME_UPPER}_FOUND FALSE)\n    endif(NOT ${_CURRENT_VAR})\n  endforeach(_CURRENT_VAR)\n\n  if (${_NAME_UPPER}_FOUND)\n    if (NOT ${_NAME}_FIND_QUIETLY)\n        message(STATUS \"Found ${_NAME}: ${${_VAR1}}\")\n    endif (NOT ${_NAME}_FIND_QUIETLY)\n  else (${_NAME_UPPER}_FOUND)\n    if (${_NAME}_FIND_REQUIRED)\n        message(FATAL_ERROR \"${_FAIL_MESSAGE}\")\n    else (${_NAME}_FIND_REQUIRED)\n      if (NOT ${_NAME}_FIND_QUIETLY)\n        message(STATUS \"${_FAIL_MESSAGE}\")\n      endif (NOT ${_NAME}_FIND_QUIETLY)\n    endif (${_NAME}_FIND_REQUIRED)\n  endif (${_NAME_UPPER}_FOUND)\nendmacro(FIND_PACKAGE_HANDLE_STANDARD_ARGS)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/cmake/FindTvmet.cmake",
    "content": "# - Try to find tvmet headers\n# Once done this will define\n#\n#  TVMET_FOUND - system has tvmet lib\n#  TVMET_INCLUDE_DIR - the tvmet include directory\n#\n# Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n# Adapted from FindEigen.cmake:\n# Copyright (c) 2006, 2007 Montel Laurent, <montel@kde.org>\n# Redistribution and use is allowed according to the terms of the BSD license.\n# For details see the accompanying COPYING-CMAKE-SCRIPTS file.\n\nif (TVMET_INCLUDE_DIR)\n\n  # in cache already\n  set(TVMET_FOUND TRUE)\n\nelse ()\n\nfind_path(TVMET_INCLUDE_DIR NAMES tvmet/tvmet.h\n     PATHS\n     ${TVMETDIR}/\n     ${INCLUDE_INSTALL_DIR}\n   )\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(Tvmet DEFAULT_MSG TVMET_INCLUDE_DIR)\n\nmark_as_advanced(TVMET_INCLUDE_DIR)\n\nendif()\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/cmake/MacroOptionalAddSubdirectory.cmake",
    "content": "# - MACRO_OPTIONAL_ADD_SUBDIRECTORY() combines add_subdirectory() with an option()\n# MACRO_OPTIONAL_ADD_SUBDIRECTORY( <dir> )\n# If you use MACRO_OPTIONAL_ADD_SUBDIRECTORY() instead of add_subdirectory(),\n# this will have two effects\n# 1 - CMake will not complain if the directory doesn't exist\n#     This makes sense if you want to distribute just one of the subdirs\n#     in a source package, e.g. just one of the subdirs in kdeextragear.\n# 2 - If the directory exists, it will offer an option to skip the \n#     subdirectory.\n#     This is useful if you want to compile only a subset of all\n#     directories.\n\n# Copyright (c) 2007, Alexander Neundorf, <neundorf@kde.org>\n#\n# Redistribution and use is allowed according to the terms of the BSD license.\n# For details see the accompanying COPYING-CMAKE-SCRIPTS file.\n\n\nmacro (MACRO_OPTIONAL_ADD_SUBDIRECTORY _dir )\n   get_filename_component(_fullPath ${_dir} ABSOLUTE)\n   if(EXISTS ${_fullPath})\n      if(${ARGC} EQUAL 2)\n        option(BUILD_${_dir} \"Build directory ${_dir}\" ${ARGV1})\n      else(${ARGC} EQUAL 2)\n        option(BUILD_${_dir} \"Build directory ${_dir}\" TRUE)\n      endif(${ARGC} EQUAL 2)\n      if(BUILD_${_dir})\n         add_subdirectory(${_dir})\n      endif(BUILD_${_dir})\n   endif(EXISTS ${_fullPath})\nendmacro (MACRO_OPTIONAL_ADD_SUBDIRECTORY)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/bench.hh",
    "content": "//=====================================================\n// File   :  bench.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:16 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef BENCH_HH\n#define BENCH_HH\n\n#include \"btl.hh\"\n#include \"bench_parameter.hh\"\n#include <iostream>\n#include \"utilities.h\"\n#include \"size_lin_log.hh\"\n#include \"xy_file.hh\"\n#include <vector>\n#include <string>\n#include \"timers/portable_perf_analyzer.hh\"\n// #include \"timers/mixed_perf_analyzer.hh\"\n// #include \"timers/x86_perf_analyzer.hh\"\n// #include \"timers/STL_perf_analyzer.hh\"\n#ifdef HAVE_MKL\nextern \"C\" void cblas_saxpy(const int, const float, const float*, const int, float *, const int);\n#endif\nusing namespace std;\n\ntemplate <template<class> class Perf_Analyzer, class Action>\nBTL_DONT_INLINE void bench( int size_min, int size_max, int nb_point )\n{\n  if (BtlConfig::skipAction(Action::name()))\n    return;\n\n  string filename=\"bench_\"+Action::name()+\".dat\";\n\n  INFOS(\"starting \" <<filename);\n\n  // utilities\n\n  std::vector<double> tab_mflops(nb_point);\n  std::vector<int> tab_sizes(nb_point);\n\n  // matrices and vector size calculations\n  size_lin_log(nb_point,size_min,size_max,tab_sizes);\n\n  std::vector<int> oldSizes;\n  std::vector<double> oldFlops;\n  bool hasOldResults = read_xy_file(filename, oldSizes, oldFlops, true);\n  int oldi = oldSizes.size() - 1;\n\n  // loop on matrix size\n  Perf_Analyzer<Action> perf_action;\n  for (int i=nb_point-1;i>=0;i--)\n  {\n    //INFOS(\"size=\" <<tab_sizes[i]<<\"   (\"<<nb_point-i<<\"/\"<<nb_point<<\")\");\n    std::cout << \" \" << \"size = \" << tab_sizes[i] << \"  \" << std::flush;\n\n    BTL_DISABLE_SSE_EXCEPTIONS();\n    #ifdef HAVE_MKL\n    {\n      float dummy;\n      cblas_saxpy(1,0,&dummy,1,&dummy,1);\n    }\n    #endif\n\n    tab_mflops[i] = perf_action.eval_mflops(tab_sizes[i]);\n    std::cout << tab_mflops[i];\n    \n    if (hasOldResults)\n    {\n      while (oldi>=0 && oldSizes[oldi]>tab_sizes[i])\n        --oldi;\n      if (oldi>=0 && oldSizes[oldi]==tab_sizes[i])\n      {\n        if (oldFlops[oldi]<tab_mflops[i])\n          std::cout << \"\\t > \";\n        else\n          std::cout << \"\\t < \";\n        std::cout << oldFlops[oldi];\n      }\n      --oldi;\n    }\n    std::cout << \" MFlops    (\" << nb_point-i << \"/\" << nb_point << \")\" << std::endl;\n  }\n\n  if (!BtlConfig::Instance.overwriteResults)\n  {\n    if (hasOldResults)\n    {\n      // merge the two data\n      std::vector<int> newSizes;\n      std::vector<double> newFlops;\n      unsigned int i=0;\n      unsigned int j=0;\n      while (i<tab_sizes.size() && j<oldSizes.size())\n      {\n        if (tab_sizes[i] == oldSizes[j])\n        {\n          newSizes.push_back(tab_sizes[i]);\n          newFlops.push_back(std::max(tab_mflops[i], oldFlops[j]));\n          ++i;\n          ++j;\n        }\n        else if (tab_sizes[i] < oldSizes[j])\n        {\n          newSizes.push_back(tab_sizes[i]);\n          newFlops.push_back(tab_mflops[i]);\n          ++i;\n        }\n        else\n        {\n          newSizes.push_back(oldSizes[j]);\n          newFlops.push_back(oldFlops[j]);\n          ++j;\n        }\n      }\n      while (i<tab_sizes.size())\n      {\n        newSizes.push_back(tab_sizes[i]);\n        newFlops.push_back(tab_mflops[i]);\n        ++i;\n      }\n      while (j<oldSizes.size())\n      {\n        newSizes.push_back(oldSizes[j]);\n        newFlops.push_back(oldFlops[j]);\n        ++j;\n      }\n      tab_mflops = newFlops;\n      tab_sizes = newSizes;\n    }\n  }\n\n  // dump the result in a file  :\n  dump_xy_file(tab_sizes,tab_mflops,filename);\n\n}\n\n// default Perf Analyzer\n\ntemplate <class Action>\nBTL_DONT_INLINE void bench( int size_min, int size_max, int nb_point ){\n\n  // if the rdtsc is not available :\n  bench<Portable_Perf_Analyzer,Action>(size_min,size_max,nb_point);\n  // if the rdtsc is available :\n//    bench<Mixed_Perf_Analyzer,Action>(size_min,size_max,nb_point);\n\n\n  // Only for small problem size. Otherwise it will be too long\n//   bench<X86_Perf_Analyzer,Action>(size_min,size_max,nb_point);\n//   bench<STL_Perf_Analyzer,Action>(size_min,size_max,nb_point);\n\n}\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/bench_parameter.hh",
    "content": "//=====================================================\n// File   :  bench_parameter.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:16 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef BENCH_PARAMETER_HH\n#define BENCH_PARAMETER_HH\n\n// minimal time for each measurement\n#define REAL_TYPE float\n// minimal time for each measurement\n#define MIN_TIME 0.2\n// nb of point on bench curves\n#define NB_POINT 100\n// min vector size for axpy bench\n#define MIN_AXPY 5\n// max vector size for axpy bench\n#define MAX_AXPY 3000000\n// min matrix size for matrix vector product bench\n#define MIN_MV 5\n// max matrix size for matrix vector product bench\n#define MAX_MV 5000\n// min matrix size for matrix matrix product bench\n#define MIN_MM 5\n// max matrix size for matrix matrix product bench\n#define MAX_MM MAX_MV\n// min matrix size for LU bench\n#define MIN_LU 5\n// max matrix size for LU bench\n#define MAX_LU 3000\n// max size for tiny vector and matrix\n#define TINY_MV_MAX_SIZE 16\n// default nb_sample for x86 timer\n#define DEFAULT_NB_SAMPLE 1000\n\n// how many times we run a single bench (keep the best perf)\n#define DEFAULT_NB_TRIES 3\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/btl.hh",
    "content": "//=====================================================\n// File   :  btl.hh\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef BTL_HH\n#define BTL_HH\n\n#include \"bench_parameter.hh\"\n#include <iostream>\n#include <algorithm>\n#include <vector>\n#include <string>\n#include \"utilities.h\"\n\n#if (defined __GNUC__)\n#define BTL_ALWAYS_INLINE __attribute__((always_inline)) inline\n#else\n#define BTL_ALWAYS_INLINE inline\n#endif\n\n#if (defined __GNUC__)\n#define BTL_DONT_INLINE __attribute__((noinline))\n#else\n#define BTL_DONT_INLINE\n#endif\n\n#if (defined __GNUC__)\n#define BTL_ASM_COMMENT(X)  asm(\"#\" X)\n#else\n#define BTL_ASM_COMMENT(X)\n#endif\n\n#ifdef __SSE__\n#include \"xmmintrin.h\"\n// This enables flush to zero (FTZ) and denormals are zero (DAZ) modes:\n#define BTL_DISABLE_SSE_EXCEPTIONS()  { _mm_setcsr(_mm_getcsr() | 0x8040); }\n#else\n#define BTL_DISABLE_SSE_EXCEPTIONS()\n#endif\n\n/** Enhanced std::string\n*/\nclass BtlString : public std::string\n{\npublic:\n    BtlString() : std::string() {}\n    BtlString(const BtlString& str) : std::string(static_cast<const std::string&>(str)) {}\n    BtlString(const std::string& str) : std::string(str) {}\n    BtlString(const char* str) : std::string(str) {}\n\n    operator const char* () const { return c_str(); }\n\n    void trim( bool left = true, bool right = true )\n    {\n        int lspaces, rspaces, len = length(), i;\n        lspaces = rspaces = 0;\n\n        if ( left )\n            for (i=0; i<len && (at(i)==' '||at(i)=='\\t'||at(i)=='\\r'||at(i)=='\\n'); ++lspaces,++i);\n\n        if ( right && lspaces < len )\n            for(i=len-1; i>=0 && (at(i)==' '||at(i)=='\\t'||at(i)=='\\r'||at(i)=='\\n'); rspaces++,i--);\n\n        *this = substr(lspaces, len-lspaces-rspaces);\n    }\n\n    std::vector<BtlString> split( const BtlString& delims = \"\\t\\n \") const\n    {\n        std::vector<BtlString> ret;\n        unsigned int numSplits = 0;\n        size_t start, pos;\n        start = 0;\n        do\n        {\n            pos = find_first_of(delims, start);\n            if (pos == start)\n            {\n                ret.push_back(\"\");\n                start = pos + 1;\n            }\n            else if (pos == npos)\n                ret.push_back( substr(start) );\n            else\n            {\n                ret.push_back( substr(start, pos - start) );\n                start = pos + 1;\n            }\n            //start = find_first_not_of(delims, start);\n            ++numSplits;\n        } while (pos != npos);\n        return ret;\n    }\n\n    bool endsWith(const BtlString& str) const\n    {\n        if(str.size()>this->size())\n            return false;\n        return this->substr(this->size()-str.size(),str.size()) == str;\n    }\n    bool contains(const BtlString& str) const\n    {\n        return this->find(str)<this->size();\n    }\n    bool beginsWith(const BtlString& str) const\n    {\n        if(str.size()>this->size())\n            return false;\n        return this->substr(0,str.size()) == str;\n    }\n\n    BtlString toLowerCase( void )\n    {\n        std::transform(begin(), end(), begin(), static_cast<int(*)(int)>(::tolower) );\n        return *this;\n    }\n    BtlString toUpperCase( void )\n    {\n        std::transform(begin(), end(), begin(), static_cast<int(*)(int)>(::toupper) );\n        return *this;\n    }\n\n    /** Case insensitive comparison.\n    */\n    bool isEquiv(const BtlString& str) const\n    {\n        BtlString str0 = *this;\n        str0.toLowerCase();\n        BtlString str1 = str;\n        str1.toLowerCase();\n        return str0 == str1;\n    }\n\n    /** Decompose the current string as a path and a file.\n        For instance: \"dir1/dir2/file.ext\" leads to path=\"dir1/dir2/\" and filename=\"file.ext\"\n    */\n    void decomposePathAndFile(BtlString& path, BtlString& filename) const\n    {\n        std::vector<BtlString> elements = this->split(\"/\\\\\");\n        path = \"\";\n        filename = elements.back();\n        elements.pop_back();\n        if (this->at(0)=='/')\n            path = \"/\";\n        for (unsigned int i=0 ; i<elements.size() ; ++i)\n            path += elements[i] + \"/\";\n    }\n};\n\nclass BtlConfig\n{\npublic:\n  BtlConfig()\n    : overwriteResults(false), checkResults(true), realclock(false), tries(DEFAULT_NB_TRIES)\n  {\n    char * _config;\n    _config = getenv (\"BTL_CONFIG\");\n    if (_config!=NULL)\n    {\n      std::vector<BtlString> config = BtlString(_config).split(\" \\t\\n\");\n      for (unsigned int i = 0; i<config.size(); i++)\n      {\n        if (config[i].beginsWith(\"-a\"))\n        {\n          if (i+1==config.size())\n          {\n            std::cerr << \"error processing option: \" << config[i] << \"\\n\";\n            exit(2);\n          }\n          Instance.m_selectedActionNames = config[i+1].split(\":\");\n\n          i += 1;\n        }\n        else if (config[i].beginsWith(\"-t\"))\n        {\n          if (i+1==config.size())\n          {\n            std::cerr << \"error processing option: \" << config[i] << \"\\n\";\n            exit(2);\n          }\n          Instance.tries = atoi(config[i+1].c_str());\n\n          i += 1;\n        }\n        else if (config[i].beginsWith(\"--overwrite\"))\n        {\n          Instance.overwriteResults = true;\n        }\n        else if (config[i].beginsWith(\"--nocheck\"))\n        {\n          Instance.checkResults = false;\n        }\n        else if (config[i].beginsWith(\"--real\"))\n        {\n          Instance.realclock = true;\n        }\n      }\n    }\n\n    BTL_DISABLE_SSE_EXCEPTIONS();\n  }\n\n  BTL_DONT_INLINE static bool skipAction(const std::string& _name)\n  {\n    if (Instance.m_selectedActionNames.empty())\n      return false;\n\n    BtlString name(_name);\n    for (unsigned int i=0; i<Instance.m_selectedActionNames.size(); ++i)\n      if (name.contains(Instance.m_selectedActionNames[i]))\n        return false;\n\n    return true;\n  }\n\n  static BtlConfig Instance;\n  bool overwriteResults;\n  bool checkResults;\n  bool realclock;\n  int tries;\n\nprotected:\n  std::vector<BtlString> m_selectedActionNames;\n};\n\n#define BTL_MAIN \\\n  BtlConfig BtlConfig::Instance\n\n#endif // BTL_HH\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/init/init_function.hh",
    "content": "//=====================================================\n// File   :  init_function.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  lun sep 30 14:23:18 CEST 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef INIT_FUNCTION_HH\n#define INIT_FUNCTION_HH\n\ndouble simple_function(int index)\n{\n  return index;\n}\n\ndouble simple_function(int index_i, int index_j)\n{\n  return index_i+index_j;\n}\n\ndouble pseudo_random(int /*index*/)\n{\n  return std::rand()/double(RAND_MAX);\n}\n\ndouble pseudo_random(int /*index_i*/, int /*index_j*/)\n{\n  return std::rand()/double(RAND_MAX);\n}\n\n\ndouble null_function(int /*index*/)\n{\n  return 0.0;\n}\n\ndouble null_function(int /*index_i*/, int /*index_j*/)\n{\n  return 0.0;\n}\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/init/init_matrix.hh",
    "content": "//=====================================================\n// File   :  init_matrix.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef INIT_MATRIX_HH\n#define INIT_MATRIX_HH\n\n// The Vector class must satisfy the following part of STL vector concept :\n//            resize() method\n//            [] operator for setting element\n//            value_type defined\ntemplate<double init_function(int,int), class Vector>\nBTL_DONT_INLINE void init_row(Vector & X, int size, int row){\n\n  X.resize(size);\n\n  for (unsigned int j=0;j<X.size();j++){\n    X[j]=typename Vector::value_type(init_function(row,j));\n  }\n}\n\n\n// Matrix is a Vector of Vector\n// The Matrix class must satisfy the following part of STL vector concept :\n//            resize() method\n//            [] operator for setting rows\ntemplate<double init_function(int,int),class Vector>\nBTL_DONT_INLINE void init_matrix(Vector &  A, int size){\n  A.resize(size);\n  for (unsigned int row=0; row<A.size() ; row++){\n    init_row<init_function>(A[row],size,row);\n  }\n}\n\ntemplate<double init_function(int,int),class Matrix>\nBTL_DONT_INLINE void init_matrix_symm(Matrix&  A, int size){\n  A.resize(size);\n  for (unsigned int row=0; row<A.size() ; row++)\n    A[row].resize(size);\n  for (unsigned int row=0; row<A.size() ; row++){\n    A[row][row] = init_function(row,row);\n    for (unsigned int col=0; col<row ; col++){\n      double x = init_function(row,col);\n      A[row][col] = A[col][row] = x;\n    }\n  }\n}\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/init/init_vector.hh",
    "content": "//=====================================================\n// File   :  init_vector.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:18 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef INIT_VECTOR_HH\n#define INIT_VECTOR_HH\n\n// The Vector class must satisfy the following part of STL vector concept :\n//            resize() method\n//            [] operator for setting element\n//            value_type defined\ntemplate<double init_function(int), class Vector>\nvoid init_vector(Vector & X, int size){\n\n  X.resize(size);\n\n  for (unsigned int i=0;i<X.size();i++){\n    X[i]=typename Vector::value_type(init_function(i));\n  }\n}\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/static/bench_static.hh",
    "content": "//=====================================================\n// File   :  bench_static.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:16 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef BENCH_STATIC_HH\n#define BENCH_STATIC_HH\n\n#include \"btl.hh\"\n#include \"bench_parameter.hh\"\n#include <iostream>\n#include \"utilities.h\"\n#include \"xy_file.hh\"\n#include \"static/static_size_generator.hh\"\n#include \"timers/portable_perf_analyzer.hh\"\n// #include \"timers/mixed_perf_analyzer.hh\"\n// #include \"timers/x86_perf_analyzer.hh\"\n\nusing namespace std;\n\n\ntemplate <template<class> class Perf_Analyzer, template<class> class Action, template<class,int> class Interface>\nBTL_DONT_INLINE  void bench_static(void)\n{\n  if (BtlConfig::skipAction(Action<Interface<REAL_TYPE,10> >::name()))\n    return;\n\n  string filename = \"bench_\" + Action<Interface<REAL_TYPE,10> >::name() + \".dat\";\n\n  INFOS(\"starting \" << filename);\n\n  const int max_size = TINY_MV_MAX_SIZE;\n\n  std::vector<double> tab_mflops;\n  std::vector<double> tab_sizes;\n\n  static_size_generator<max_size,Perf_Analyzer,Action,Interface>::go(tab_sizes,tab_mflops);\n\n  dump_xy_file(tab_sizes,tab_mflops,filename);\n}\n\n// default Perf Analyzer\ntemplate <template<class> class Action, template<class,int> class Interface>\nBTL_DONT_INLINE  void bench_static(void)\n{\n  bench_static<Portable_Perf_Analyzer,Action,Interface>();\n  //bench_static<Mixed_Perf_Analyzer,Action,Interface>();\n  //bench_static<X86_Perf_Analyzer,Action,Interface>();\n}\n\n#endif\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/static/intel_bench_fixed_size.hh",
    "content": "//=====================================================\n// File   :  intel_bench_fixed_size.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  mar dc 3 18:59:37 CET 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef _BENCH_FIXED_SIZE_HH_\n#define _BENCH_FIXED_SIZE_HH_\n\n#include \"utilities.h\"\n#include \"function_time.hh\"\n\ntemplate <class Action>\ndouble bench_fixed_size(int size, unsigned long long  & nb_calc,unsigned long long & nb_init)\n{\n  \n  Action action(size);\n  \n  double time_baseline=time_init(nb_init,action);\n\n  while (time_baseline < MIN_TIME) {\n\n    //INFOS(\"nb_init=\"<<nb_init);\n    //INFOS(\"time_baseline=\"<<time_baseline);\n    nb_init*=2;\n    time_baseline=time_init(nb_init,action);\n  }\n  \n  time_baseline=time_baseline/(double(nb_init));\n  \n  double time_action=time_calculate(nb_calc,action);\n  \n  while (time_action < MIN_TIME) {\n    \n    nb_calc*=2;\n    time_action=time_calculate(nb_calc,action);\n  }\n\n  INFOS(\"nb_init=\"<<nb_init);\n  INFOS(\"nb_calc=\"<<nb_calc);\n  \n  \n  time_action=time_action/(double(nb_calc));\n  \n  action.check_result();\n  \n  time_action=time_action-time_baseline;\n\n  return action.nb_op_base()/(time_action*1000000.0);\n\n}\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/static/static_size_generator.hh",
    "content": "//=====================================================\n// File   :  static_size_generator.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  mar dc 3 18:59:36 CET 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef _STATIC_SIZE_GENERATOR_HH\n#define _STATIC_SIZE_GENERATOR_HH\n#include <vector>\n\nusing namespace std;\n\n//recursive generation of statically defined matrix and vector sizes\n\ntemplate <int SIZE,template<class> class Perf_Analyzer, template<class> class Action, template<class,int> class Interface> \nstruct static_size_generator{\n  static void go(vector<double> & tab_sizes, vector<double> & tab_mflops)\n  {\n    tab_sizes.push_back(SIZE);\n    std::cout << tab_sizes.back() << \" \\t\" << std::flush;\n    Perf_Analyzer<Action<Interface<REAL_TYPE,SIZE> > > perf_action;\n    tab_mflops.push_back(perf_action.eval_mflops(SIZE));\n    std::cout << tab_mflops.back() << \" MFlops\" << std::endl;\n    static_size_generator<SIZE-1,Perf_Analyzer,Action,Interface>::go(tab_sizes,tab_mflops);\n  };\n};\n\n//recursion end\n\ntemplate <template<class> class Perf_Analyzer, template<class> class Action, template<class,int> class Interface> \nstruct static_size_generator<1,Perf_Analyzer,Action,Interface>{  \n  static  void go(vector<double> & tab_sizes, vector<double> & tab_mflops)\n  {\n    tab_sizes.push_back(1);\n    Perf_Analyzer<Action<Interface<REAL_TYPE,1> > > perf_action;\n    tab_mflops.push_back(perf_action.eval_mflops(1));\n  };\n};\n\n#endif\n  \n  \n  \n  \n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/timers/STL_perf_analyzer.hh",
    "content": "//=====================================================\n// File   :  STL_perf_analyzer.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  mar dc 3 18:59:35 CET 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef _STL_PERF_ANALYSER_HH\n#define _STL_PERF_ANALYSER_HH\n\n#include \"STL_timer.hh\"\n#include \"bench_parameter.hh\"\n\ntemplate<class ACTION>\nclass STL_Perf_Analyzer{\npublic:  \n  STL_Perf_Analyzer(unsigned long long nb_sample=DEFAULT_NB_SAMPLE):_nb_sample(nb_sample),_chronos()\n  {\n    MESSAGE(\"STL_Perf_Analyzer Ctor\");\n  }; \n  STL_Perf_Analyzer( const STL_Perf_Analyzer & ){\n    INFOS(\"Copy Ctor not implemented\");\n    exit(0);\n  };\n  ~STL_Perf_Analyzer( void ){\n    MESSAGE(\"STL_Perf_Analyzer Dtor\");\n  };\n  \n  \n  inline double eval_mflops(int size)\n  {\n\n    ACTION action(size);\n\n    _chronos.start_baseline(_nb_sample);\n      \n    do {\n\n      action.initialize();\n    } while (_chronos.check());\n\n    double baseline_time=_chronos.get_time();\n\n    _chronos.start(_nb_sample);\n    do {\n      action.initialize();\n      action.calculate();\n    } while (_chronos.check());\n\n    double calculate_time=_chronos.get_time();\n\n    double corrected_time=calculate_time-baseline_time;\n    \n    //    cout << size <<\" \"<<baseline_time<<\" \"<<calculate_time<<\" \"<<corrected_time<<\" \"<<action.nb_op_base() << endl;    \n    \n    return action.nb_op_base()/(corrected_time*1000000.0);\n    //return action.nb_op_base()/(calculate_time*1000000.0);\n    \n  }\nprivate:\n\n  STL_Timer _chronos;\n  unsigned long long _nb_sample;\n\n  \n};\n\n  \n  \n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/timers/STL_timer.hh",
    "content": "//=====================================================\n// File   :  STL_Timer.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  mar dc 3 18:59:35 CET 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n// STL Timer Class. Adapted (L.P.) from the timer class by Musser et Al\n// described int the Book : STL Tutorial and reference guide.\n// Define a timer class for analyzing algorithm performance.\n#include <iostream>\n#include <iomanip>\n#include <vector>\n#include <map>\n#include <algorithm>\nusing namespace std;\n\nclass STL_Timer {\npublic:\n  STL_Timer(){ baseline = false; };  // Default constructor\n  // Start a series of r trials:\n  void start(unsigned int r){\n    reps = r;\n    count = 0;\n    iterations.clear();\n    iterations.reserve(reps);\n    initial = time(0);\n  };\n  // Start a series of r trials to determine baseline time:\n  void start_baseline(unsigned int r)\n  {\n    baseline = true;\n    start(r);\n  }\n  // Returns true if the trials have been completed, else false\n  bool check()\n  {\n    ++count;\n    final = time(0);\n    if (initial < final) {\n      iterations.push_back(count);  \n      initial = final;\n      count = 0;\n    }\n    return (iterations.size() < reps);\n  };\n  // Returns the results for external use\n  double get_time( void )\n  {\n    sort(iterations.begin(), iterations.end());\n    return 1.0/iterations[reps/2];\n  };\nprivate:\n  unsigned int reps;  // Number of trials\n  // For storing loop iterations of a trial\n  vector<long> iterations;\n  // For saving initial and final times of a trial\n  time_t initial, final;\n  // For counting loop iterations of a trial\n  unsigned long count;\n  // true if this is a baseline computation, false otherwise\n  bool baseline;\n  // For recording the baseline time \n  double baseline_time;\n};\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/timers/mixed_perf_analyzer.hh",
    "content": "//=====================================================\n// File   :  mixed_perf_analyzer.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  mar dc 3 18:59:36 CET 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef _MIXED_PERF_ANALYSER_HH\n#define _MIXED_PERF_ANALYSER_HH\n\n#include \"x86_perf_analyzer.hh\"\n#include \"portable_perf_analyzer.hh\"\n\n// choose portable perf analyzer for long calculations and x86 analyser for short ones\n\n\ntemplate<class Action>\nclass Mixed_Perf_Analyzer{\n  \npublic:  \n  Mixed_Perf_Analyzer( void ):_x86pa(),_ppa(),_use_ppa(true)\n  {\n    MESSAGE(\"Mixed_Perf_Analyzer Ctor\");\n  }; \n  Mixed_Perf_Analyzer( const Mixed_Perf_Analyzer & ){\n    INFOS(\"Copy Ctor not implemented\");\n    exit(0);\n  };\n  ~Mixed_Perf_Analyzer( void ){\n    MESSAGE(\"Mixed_Perf_Analyzer Dtor\");\n  };\n    \n  \n  inline double eval_mflops(int size)\n  {\n\n    double result=0.0;\n    if (_use_ppa){      \n      result=_ppa.eval_mflops(size);\n      if (_ppa.get_nb_calc()>DEFAULT_NB_SAMPLE){_use_ppa=false;}      \n    }\n    else{      \n      result=_x86pa.eval_mflops(size);\n    }\n\n    return result;\n  }\n\nprivate:\n\n  Portable_Perf_Analyzer<Action> _ppa;\n  X86_Perf_Analyzer<Action> _x86pa;\n  bool _use_ppa;\n\n};\n\n#endif\n\n  \n    \n  \n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/timers/portable_perf_analyzer.hh",
    "content": "//=====================================================\n// File   :  portable_perf_analyzer.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  mar d�c 3 18:59:35 CET 2002\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef _PORTABLE_PERF_ANALYZER_HH\n#define _PORTABLE_PERF_ANALYZER_HH\n\n#include \"utilities.h\"\n#include \"timers/portable_timer.hh\"\n\ntemplate <class Action>\nclass Portable_Perf_Analyzer{\npublic:\n  Portable_Perf_Analyzer( ):_nb_calc(0), m_time_action(0), _chronos(){\n    MESSAGE(\"Portable_Perf_Analyzer Ctor\");\n  };\n  Portable_Perf_Analyzer( const Portable_Perf_Analyzer & ){\n    INFOS(\"Copy Ctor not implemented\");\n    exit(0);\n  };\n  ~Portable_Perf_Analyzer(){\n    MESSAGE(\"Portable_Perf_Analyzer Dtor\");\n  };\n\n  BTL_DONT_INLINE double eval_mflops(int size)\n  {\n    Action action(size);\n\n//     action.initialize();\n//     time_action = time_calculate(action);\n    while (m_time_action < MIN_TIME)\n    {\n      if(_nb_calc==0) _nb_calc = 1;\n      else            _nb_calc *= 2;\n      action.initialize();\n      m_time_action = time_calculate(action);\n    }\n\n    // optimize\n    for (int i=1; i<BtlConfig::Instance.tries; ++i)\n    {\n      Action _action(size);\n      std::cout << \" \" << _action.nb_op_base()*_nb_calc/(m_time_action*1e6) << \" \";\n      _action.initialize();\n      m_time_action = std::min(m_time_action, time_calculate(_action));\n    }\n\n    double time_action = m_time_action / (double(_nb_calc));\n\n    // check\n    if (BtlConfig::Instance.checkResults && size<128)\n    {\n      action.initialize();\n      action.calculate();\n      action.check_result();\n    }\n    return action.nb_op_base()/(time_action*1e6);\n  }\n\n  BTL_DONT_INLINE double time_calculate(Action & action)\n  {\n    // time measurement\n    action.calculate();\n    _chronos.start();\n    for (unsigned int ii=0;ii<_nb_calc;ii++)\n    {\n      action.calculate();\n    }\n    _chronos.stop();\n    return _chronos.user_time();\n  }\n\n  unsigned long long get_nb_calc()\n  {\n    return _nb_calc;\n  }\n\n\nprivate:\n  unsigned long long _nb_calc;\n  double m_time_action;\n  Portable_Timer _chronos;\n\n};\n\n#endif //_PORTABLE_PERF_ANALYZER_HH\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/timers/portable_perf_analyzer_old.hh",
    "content": "//=====================================================\n// File   :  portable_perf_analyzer.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  mar d�c 3 18:59:35 CET 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef _PORTABLE_PERF_ANALYZER_HH\n#define _PORTABLE_PERF_ANALYZER_HH\n\n#include \"utilities.h\"\n#include \"timers/portable_timer.hh\"\n\ntemplate <class Action>\nclass Portable_Perf_Analyzer{\npublic:\n  Portable_Perf_Analyzer( void ):_nb_calc(1),_nb_init(1),_chronos(){\n    MESSAGE(\"Portable_Perf_Analyzer Ctor\");\n  };\n  Portable_Perf_Analyzer( const Portable_Perf_Analyzer & ){\n    INFOS(\"Copy Ctor not implemented\");\n    exit(0);\n  };\n  ~Portable_Perf_Analyzer( void ){\n    MESSAGE(\"Portable_Perf_Analyzer Dtor\");\n  };\n\n\n\n  inline double eval_mflops(int size)\n  {\n\n    Action action(size);\n\n//     double time_baseline = time_init(action);\n//     while (time_baseline < MIN_TIME_INIT)\n//     {\n//       _nb_init *= 2;\n//       time_baseline = time_init(action);\n//     }\n//\n//     // optimize\n//     for (int i=1; i<NB_TRIES; ++i)\n//       time_baseline = std::min(time_baseline, time_init(action));\n//\n//     time_baseline = time_baseline/(double(_nb_init));\n\n    double time_action = time_calculate(action);\n    while (time_action < MIN_TIME)\n    {\n      _nb_calc *= 2;\n      time_action = time_calculate(action);\n    }\n\n    // optimize\n    for (int i=1; i<NB_TRIES; ++i)\n      time_action = std::min(time_action, time_calculate(action));\n\n//     INFOS(\"size=\"<<size);\n//     INFOS(\"_nb_init=\"<<_nb_init);\n//     INFOS(\"_nb_calc=\"<<_nb_calc);\n\n    time_action = time_action / (double(_nb_calc));\n\n    action.check_result();\n\n\n    double time_baseline = time_init(action);\n    for (int i=1; i<NB_TRIES; ++i)\n      time_baseline = std::min(time_baseline, time_init(action));\n    time_baseline = time_baseline/(double(_nb_init));\n\n\n\n//     INFOS(\"time_baseline=\"<<time_baseline);\n//     INFOS(\"time_action=\"<<time_action);\n\n    time_action = time_action - time_baseline;\n\n//     INFOS(\"time_corrected=\"<<time_action);\n\n    return action.nb_op_base()/(time_action*1000000.0);\n  }\n\n  inline double time_init(Action & action)\n  {\n    // time measurement\n    _chronos.start();\n    for (int ii=0; ii<_nb_init; ii++)\n      action.initialize();\n    _chronos.stop();\n    return _chronos.user_time();\n  }\n\n\n  inline double time_calculate(Action & action)\n  {\n    // time measurement\n    _chronos.start();\n    for (int ii=0;ii<_nb_calc;ii++)\n    {\n      action.initialize();\n      action.calculate();\n    }\n    _chronos.stop();\n    return _chronos.user_time();\n  }\n\n  unsigned long long get_nb_calc( void )\n  {\n    return _nb_calc;\n  }\n\n\nprivate:\n  unsigned long long _nb_calc;\n  unsigned long long _nb_init;\n  Portable_Timer _chronos;\n\n};\n\n#endif //_PORTABLE_PERF_ANALYZER_HH\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/timers/portable_timer.hh",
    "content": "//=====================================================\n// File   :  portable_timer.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)> from boost lib\n// Copyright (C) EDF R&D,  lun sep 30 14:23:17 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n//  simple_time extracted from the boost library\n//\n#ifndef _PORTABLE_TIMER_HH\n#define _PORTABLE_TIMER_HH\n\n#include <ctime>\n#include <cstdlib>\n\n#include <time.h>\n\n\n#define USEC_IN_SEC 1000000\n\n\n//  timer  -------------------------------------------------------------------//\n\n//  A timer object measures CPU time.\n#if defined(_MSC_VER)\n\n#define NOMINMAX\n#include <windows.h>\n\n/*#ifndef hr_timer\n#include \"hr_time.h\"\n#define hr_timer\n#endif*/\n\n class Portable_Timer\n {\n  public:\n\n   typedef struct {\n    LARGE_INTEGER start;\n    LARGE_INTEGER stop;\n   } stopWatch;\n\n\n   Portable_Timer()\n   {\n\t startVal.QuadPart = 0;\n\t stopVal.QuadPart = 0;\n\t QueryPerformanceFrequency(&frequency);\n   }\n\n   void start() { QueryPerformanceCounter(&startVal); }\n\n   void stop() { QueryPerformanceCounter(&stopVal); }\n\n   double elapsed() {\n\t LARGE_INTEGER time;\n     time.QuadPart = stopVal.QuadPart - startVal.QuadPart;\n     return LIToSecs(time);\n   }\n\n   double user_time() { return elapsed(); }\n\n\n private:\n\n   double LIToSecs(LARGE_INTEGER& L) {\n     return ((double)L.QuadPart /(double)frequency.QuadPart) ;\n   }\n\n   LARGE_INTEGER startVal;\n   LARGE_INTEGER stopVal;\n   LARGE_INTEGER frequency;\n\n\n }; // Portable_Timer\n\n#elif defined(__APPLE__)\n#include <CoreServices/CoreServices.h>\n#include <mach/mach_time.h>\n\n\nclass Portable_Timer\n{\n public:\n\n  Portable_Timer()\n  {\n  }\n\n  void start()\n  {\n    m_start_time = double(mach_absolute_time())*1e-9;;\n\n  }\n\n  void stop()\n  {\n    m_stop_time = double(mach_absolute_time())*1e-9;;\n\n  }\n\n  double elapsed()\n  {\n    return  user_time();\n  }\n\n  double user_time()\n  {\n    return m_stop_time - m_start_time;\n  }\n\n\nprivate:\n\n  double m_stop_time, m_start_time;\n\n}; // Portable_Timer (Apple)\n\n#else\n\n#include <sys/time.h>\n#include <sys/resource.h>\n#include <unistd.h>\n#include <sys/times.h>\n\nclass Portable_Timer\n{\n public:\n\n  Portable_Timer()\n  {\n    m_clkid = BtlConfig::Instance.realclock ? CLOCK_REALTIME : CLOCK_PROCESS_CPUTIME_ID;\n  }\n\n  Portable_Timer(int clkid) : m_clkid(clkid)\n  {}\n\n  void start()\n  {\n    timespec ts;\n    clock_gettime(m_clkid, &ts);\n    m_start_time = double(ts.tv_sec) + 1e-9 * double(ts.tv_nsec);\n\n  }\n\n  void stop()\n  {\n    timespec ts;\n    clock_gettime(m_clkid, &ts);\n    m_stop_time = double(ts.tv_sec) + 1e-9 * double(ts.tv_nsec);\n\n  }\n\n  double elapsed()\n  {\n    return  user_time();\n  }\n\n  double user_time()\n  {\n    return m_stop_time - m_start_time;\n  }\n\n\nprivate:\n\n  int m_clkid;\n  double m_stop_time, m_start_time;\n\n}; // Portable_Timer (Linux)\n\n#endif\n\n#endif  // PORTABLE_TIMER_HPP\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/timers/x86_perf_analyzer.hh",
    "content": "//=====================================================\n// File   :  x86_perf_analyzer.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  mar d�c 3 18:59:35 CET 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef _X86_PERF_ANALYSER_HH\n#define _X86_PERF_ANALYSER_HH\n\n#include \"x86_timer.hh\"\n#include \"bench_parameter.hh\"\n\ntemplate<class ACTION>\nclass X86_Perf_Analyzer{\npublic:\n  X86_Perf_Analyzer( unsigned long long nb_sample=DEFAULT_NB_SAMPLE):_nb_sample(nb_sample),_chronos()\n  {\n    MESSAGE(\"X86_Perf_Analyzer Ctor\");\n    _chronos.find_frequency();\n  };\n  X86_Perf_Analyzer( const X86_Perf_Analyzer & ){\n    INFOS(\"Copy Ctor not implemented\");\n    exit(0);\n  };\n  ~X86_Perf_Analyzer( void ){\n    MESSAGE(\"X86_Perf_Analyzer Dtor\");\n  };\n\n\n  inline double eval_mflops(int size)\n  {\n\n    ACTION action(size);\n\n    int nb_loop=5;\n    double calculate_time=0.0;\n    double baseline_time=0.0;\n\n    for (int j=0 ; j < nb_loop ; j++){\n\n      _chronos.clear();\n\n      for(int i=0 ; i < _nb_sample  ; i++)\n      {\n        _chronos.start();\n        action.initialize();\n        action.calculate();\n        _chronos.stop();\n        _chronos.add_get_click();\n      }\n\n      calculate_time += double(_chronos.get_shortest_clicks())/_chronos.frequency();\n\n      if (j==0) action.check_result();\n\n      _chronos.clear();\n\n      for(int i=0 ; i < _nb_sample  ; i++)\n      {\n        _chronos.start();\n        action.initialize();\n        _chronos.stop();\n        _chronos.add_get_click();\n\n      }\n\n      baseline_time+=double(_chronos.get_shortest_clicks())/_chronos.frequency();\n\n    }\n\n    double corrected_time = (calculate_time-baseline_time)/double(nb_loop);\n\n\n//     INFOS(\"_nb_sample=\"<<_nb_sample);\n//     INFOS(\"baseline_time=\"<<baseline_time);\n//     INFOS(\"calculate_time=\"<<calculate_time);\n//     INFOS(\"corrected_time=\"<<corrected_time);\n\n//    cout << size <<\" \"<<baseline_time<<\" \"<<calculate_time<<\" \"<<corrected_time<<\" \"<<action.nb_op_base() << endl;\n\n    return action.nb_op_base()/(corrected_time*1000000.0);\n    //return action.nb_op_base()/(calculate_time*1000000.0);\n  }\n\nprivate:\n\n  X86_Timer _chronos;\n  unsigned long long _nb_sample;\n\n\n};\n\n\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/timers/x86_timer.hh",
    "content": "//=====================================================\n// File   :  x86_timer.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  mar d�c 3 18:59:35 CET 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef _X86_TIMER_HH\n#define _X86_TIMER_HH\n\n#include <sys/time.h>\n#include <sys/resource.h>\n#include <unistd.h>\n#include <sys/times.h>\n//#include \"system_time.h\"\n#define u32 unsigned int\n#include <asm/msr.h>\n#include \"utilities.h\"\n#include <map>\n#include <fstream>\n#include <string>\n#include <iostream>\n\n// frequence de la becanne en Hz\n//#define FREQUENCY 648000000\n//#define FREQUENCY 1400000000\n#define FREQUENCY 1695000000\n\nusing namespace std;\n\n\nclass X86_Timer {\n\npublic :\n\n  X86_Timer( void ):_frequency(FREQUENCY),_nb_sample(0)\n  {\n    MESSAGE(\"X86_Timer Default Ctor\");    \n  }\n\n  inline void start( void ){\n\n    rdtsc(_click_start.n32[0],_click_start.n32[1]);\n\n  }\n\n\n  inline void stop( void ){\n\n    rdtsc(_click_stop.n32[0],_click_stop.n32[1]);\n\n  }\n  \n\n  inline double frequency( void ){\n    return _frequency;\n  }\n\n  double get_elapsed_time_in_second( void ){\n\n    return (_click_stop.n64-_click_start.n64)/double(FREQUENCY);\n\n\n  }    \n\n  unsigned long long  get_click( void ){\n    \n    return (_click_stop.n64-_click_start.n64);\n\n  }    \n\n  inline void find_frequency( void ){\n\n    time_t initial, final;\n    int dummy=2;\n\n    initial = time(0);\n    start();\n    do {\n      dummy+=2;\n    }\n    while(time(0)==initial);\n    // On est au debut d'un cycle d'une seconde !!!\n    initial = time(0);\n    start();\n    do {\n      dummy+=2;\n    }\n    while(time(0)==initial);\n    final=time(0);\n    stop();\n    //    INFOS(\"fine grained time : \"<<  get_elapsed_time_in_second());\n    //  INFOS(\"coarse grained time : \"<<  final-initial);\n    _frequency=_frequency*get_elapsed_time_in_second()/double(final-initial);\n    ///  INFOS(\"CPU frequency : \"<<  _frequency);        \n\n  }\n\n  void  add_get_click( void ){\n       \n    _nb_sample++;\n    _counted_clicks[get_click()]++;\n    fill_history_clicks();\n\n  }    \n\n  void dump_statistics(string filemane){\n    \n    ofstream outfile (filemane.c_str(),ios::out) ;\n\n    std::map<unsigned long long , unsigned long long>::iterator itr;\n    for(itr=_counted_clicks.begin() ; itr!=_counted_clicks.end()  ; itr++)\n      {      \n      outfile  << (*itr).first << \"  \" << (*itr).second << endl ;       \n      }      \n    \n    outfile.close();\n\n  }\n\n  void dump_history(string filemane){\n    \n    ofstream outfile (filemane.c_str(),ios::out) ;\n\n\n\n    for(int i=0 ; i<_history_mean_clicks.size() ; i++)\n      {      \n\toutfile  << i << \" \" \n\t\t << _history_mean_clicks[i] << \" \" \n\t\t << _history_shortest_clicks[i] << \" \" \n\t\t << _history_most_occured_clicks[i] << endl ;\n      }      \n    \n    outfile.close();\n\n  }\n     \n\n\n  double get_mean_clicks( void ){\n    \n    std::map<unsigned long long,unsigned long long>::iterator itr;\n    \n    unsigned long long mean_clicks=0;\n\n    for(itr=_counted_clicks.begin() ; itr!=_counted_clicks.end()  ; itr++)\n      {      \n\t\n\tmean_clicks+=(*itr).second*(*itr).first;\n      }      \n\n    return mean_clicks/double(_nb_sample);\n\n  }\n\n  double get_shortest_clicks( void ){\n    \n    return double((*_counted_clicks.begin()).first);\n\n  }\n\n  void fill_history_clicks( void ){\n\n    _history_mean_clicks.push_back(get_mean_clicks());\n    _history_shortest_clicks.push_back(get_shortest_clicks());\n    _history_most_occured_clicks.push_back(get_most_occured_clicks());\n\n  }\n\n\n  double get_most_occured_clicks( void ){\n\n    unsigned long long moc=0;\n    unsigned long long max_occurence=0;\n\n    std::map<unsigned long long,unsigned long long>::iterator itr;\n\n    for(itr=_counted_clicks.begin() ; itr!=_counted_clicks.end()  ; itr++)\n      {      \n\t\n\tif (max_occurence<=(*itr).second){\n\t  max_occurence=(*itr).second;\n\t  moc=(*itr).first;\n\t}\n      }      \n    \n    return double(moc);    \n\n  }\n  \n  void clear( void )\n  {\n    _counted_clicks.clear();\n\n    _history_mean_clicks.clear();\n    _history_shortest_clicks.clear();\n    _history_most_occured_clicks.clear();\n\n    _nb_sample=0;\n  }\n\n\n    \nprivate :\n  \n  union\n  {\n    unsigned long int n32[2] ;\n    unsigned long long n64 ;\n  } _click_start;\n\n  union\n  {\n    unsigned long int n32[2] ;\n    unsigned long long n64 ;\n  } _click_stop;\n\n  double _frequency ;\n\n  map<unsigned long long,unsigned long long> _counted_clicks;\n\n  vector<double> _history_mean_clicks;\n  vector<double> _history_shortest_clicks;\n  vector<double> _history_most_occured_clicks;\n\n  unsigned long long _nb_sample;\n\n  \n\n};\n\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/utils/size_lin_log.hh",
    "content": "//=====================================================\n// File   :  size_lin_log.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  mar dc 3 18:59:37 CET 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef SIZE_LIN_LOG\n#define SIZE_LIN_LOG\n\n#include \"size_log.hh\"\n\ntemplate<class Vector>\nvoid size_lin_log(const int nb_point, const int /*size_min*/, const int size_max, Vector & X)\n{\n  int ten=10;\n  int nine=9;\n\n  X.resize(nb_point);\n\n  if (nb_point>ten){\n\n    for (int i=0;i<nine;i++){\n      \n      X[i]=i+1;\n\n    }\n\n    Vector log_size;\n    size_log(nb_point-nine,ten,size_max,log_size);\n\n    for (int i=0;i<nb_point-nine;i++){\n      \n      X[i+nine]=log_size[i];\n\n    }\n  }\n  else{\n\n    for (int i=0;i<nb_point;i++){\n      \n      X[i]=i+1;\n\n    }\n  }\n\n //  for (int i=0;i<nb_point;i++){\n    \n//        INFOS(\"computed sizes : X[\"<<i<<\"]=\"<<X[i]);\n    \n//   }\n\n}\n  \n#endif\n    \n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/utils/size_log.hh",
    "content": "//=====================================================\n// File   :  size_log.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  lun sep 30 14:23:17 CEST 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef SIZE_LOG\n#define SIZE_LOG\n\n#include \"math.h\"\n// The Vector class must satisfy the following part of STL vector concept :\n//            resize() method\n//            [] operator for setting element\n// the vector element are int compatible.\ntemplate<class Vector>\nvoid size_log(const int nb_point, const int size_min, const int size_max, Vector & X)\n{\n  X.resize(nb_point);\n\n  float ls_min=log(float(size_min));\n  float ls_max=log(float(size_max));\n\n  float ls=0.0;\n\n  float delta_ls=(ls_max-ls_min)/(float(nb_point-1));\n\n  int size=0;\n\n  for (int i=0;i<nb_point;i++){\n\n    ls = ls_min + float(i)*delta_ls ;\n    \n    size=int(exp(ls)); \n\n    X[i]=size;\n  }\n\n}\n\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/utils/utilities.h",
    "content": "//=============================================================================\n// File      : utilities.h\n// Created   : mar jun 19 13:18:14 CEST 2001\n// Author    : Antoine YESSAYAN, Paul RASCLE, EDF\n// Project   : SALOME\n// Copyright : EDF 2001\n// $Header$\n//=============================================================================\n\n/* ---  Definition macros file to print information if _DEBUG_ is defined --- */\n\n# ifndef UTILITIES_H\n# define UTILITIES_H\n\n# include <stdlib.h>\n//# include <iostream> ok for gcc3.01\n# include <iostream>\n\n/* ---  INFOS is always defined (without _DEBUG_): to be used for warnings, with release version --- */\n\n# define HEREWEARE cout<<flush ; cerr << __FILE__ << \" [\" << __LINE__ << \"] : \" << flush ;\n# define INFOS(chain) {HEREWEARE ; cerr << chain << endl ;}\n# define PYSCRIPT(chain) {cout<<flush ; cerr << \"---PYSCRIPT--- \" << chain << endl ;}\n\n/* --- To print date and time of compilation of current source on stdout --- */\n\n# if defined ( __GNUC__ )\n# define COMPILER\t\t\"g++\" ;\n# elif defined ( __sun )\n# define COMPILER\t\t\"CC\" ;\n# elif defined ( __KCC )\n# define COMPILER\t\t\"KCC\" ;\n# elif defined ( __PGI )\n# define COMPILER\t\t\"pgCC\" ;\n# else\n# define COMPILER\t\t\"undefined\" ;\n# endif\n\n# ifdef INFOS_COMPILATION\n# error INFOS_COMPILATION already defined\n# endif\n# define INFOS_COMPILATION\t{\\\n\t\t\t\t\tcerr << flush;\\\n\t\t\t\t\tcout << __FILE__ ;\\\n\t\t\t\t\tcout << \" [\" << __LINE__ << \"] : \" ;\\\n\t\t\t\t\tcout << \"COMPILED with \" << COMPILER ;\\\n\t\t\t\t\tcout << \", \" << __DATE__ ; \\\n\t\t\t\t\tcout << \" at \" << __TIME__ << endl ;\\\n\t\t\t\t\tcout << \"\\n\\n\" ;\\\n\t\t\t\t\tcout << flush ;\\\n\t\t\t\t}\n\n# ifdef _DEBUG_\n\n/* --- the following MACROS are useful at debug time --- */\n\n# define HERE cout<<flush ; cerr << \"- Trace \" << __FILE__ << \" [\" << __LINE__ << \"] : \" << flush ;\n# define SCRUTE(var) HERE ; cerr << #var << \"=\" << var << endl ;\n# define MESSAGE(chain) {HERE ; cerr << chain << endl ;}\n# define INTERRUPTION(code) HERE ; cerr << \"INTERRUPTION return code= \" << code << endl ; exit(code) ;\n\n# ifndef ASSERT\n# define ASSERT(condition) if (!(condition)){ HERE ; cerr << \"CONDITION \" << #condition << \" NOT VERIFIED\"<< endl ; INTERRUPTION(1) ;}\n# endif /* ASSERT */\n\n#define REPERE cout<<flush ; cerr << \"   --------------\" << endl << flush ;\n#define BEGIN_OF(chain) {REPERE ; HERE ; cerr << \"Begin of: \" << chain << endl ; REPERE ; }\n#define END_OF(chain) {REPERE ; HERE ; cerr << \"Normal end of: \" << chain << endl ; REPERE ; }\n\n\n\n# else /* ifdef _DEBUG_*/\n\n# define HERE\n# define SCRUTE(var)\n# define MESSAGE(chain)\n# define INTERRUPTION(code)\n\n# ifndef ASSERT\n# define ASSERT(condition)\n# endif /* ASSERT */\n\n#define REPERE\n#define BEGIN_OF(chain)\n#define END_OF(chain)\n\n\n# endif /* ifdef _DEBUG_*/\n\n# endif /* ifndef UTILITIES_H */\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/generic_bench/utils/xy_file.hh",
    "content": "//=====================================================\n// File   :  dump_file_x_y.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  lun sep 30 14:23:20 CEST 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef XY_FILE_HH\n#define XY_FILE_HH\n#include <fstream>\n#include <iostream>\n#include <string>\n#include <vector>\nusing namespace std;\n\nbool read_xy_file(const std::string & filename, std::vector<int> & tab_sizes,\n                  std::vector<double> & tab_mflops, bool quiet = false)\n{\n\n  std::ifstream input_file (filename.c_str(),std::ios::in);\n\n  if (!input_file){\n    if (!quiet) {\n      INFOS(\"!!! Error opening \"<<filename);\n    }\n    return false;\n  }\n\n  int nb_point=0;\n  int size=0;\n  double mflops=0;\n\n  while (input_file >> size >> mflops ){\n    nb_point++;\n    tab_sizes.push_back(size);\n    tab_mflops.push_back(mflops);\n  }\n  SCRUTE(nb_point);\n\n  input_file.close();\n  return true;\n}\n\n// The Vector class must satisfy the following part of STL vector concept :\n//            resize() method\n//            [] operator for setting element\n// the vector element must have the << operator define\n\nusing namespace std;\n\ntemplate<class Vector_A, class Vector_B>\nvoid dump_xy_file(const Vector_A & X, const Vector_B & Y, const std::string & filename){\n  \n  ofstream outfile (filename.c_str(),ios::out) ;\n  int size=X.size();\n  \n  for (int i=0;i<size;i++)\n    outfile << X[i] << \" \" << Y[i] << endl;\n\n  outfile.close();\n} \n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/BLAS/CMakeLists.txt",
    "content": "\nfind_package(ATLAS)\nif (ATLAS_FOUND)\n  btl_add_bench(btl_atlas main.cpp)\n  if(BUILD_btl_atlas)\n    target_link_libraries(btl_atlas ${ATLAS_LIBRARIES})\n    set_target_properties(btl_atlas PROPERTIES COMPILE_FLAGS \"-DCBLASNAME=ATLAS -DHAS_LAPACK=1\")\n  endif()\nendif ()\n\nfind_package(MKL)\nif (MKL_FOUND)\n  btl_add_bench(btl_mkl main.cpp)\n  if(BUILD_btl_mkl)\n    target_link_libraries(btl_mkl ${MKL_LIBRARIES})\n    set_target_properties(btl_mkl PROPERTIES COMPILE_FLAGS \"-DCBLASNAME=INTEL_MKL -DHAS_LAPACK=1\")\n  endif()\nendif ()\n\n\nfind_package(OPENBLAS)\nif (OPENBLAS_FOUND)\n  btl_add_bench(btl_openblas main.cpp)\n  if(BUILD_btl_openblas)\n    target_link_libraries(btl_openblas ${OPENBLAS_LIBRARIES} )\n    set_target_properties(btl_openblas PROPERTIES COMPILE_FLAGS \"-DCBLASNAME=OPENBLAS\")\n  endif()\nendif ()\n\nfind_package(ACML)\nif (ACML_FOUND)\n  btl_add_bench(btl_acml main.cpp)\n  if(BUILD_btl_acml)\n    target_link_libraries(btl_acml ${ACML_LIBRARIES} )\n    set_target_properties(btl_acml PROPERTIES COMPILE_FLAGS \"-DCBLASNAME=ACML -DHAS_LAPACK=1\")\n  endif()\nendif ()\n\nif(Eigen_SOURCE_DIR AND CMAKE_Fortran_COMPILER_WORKS)\n  # we are inside Eigen and blas/lapack interface is compilable\n  include_directories(${Eigen_SOURCE_DIR})\n  btl_add_bench(btl_eigenblas main.cpp)\n  if(BUILD_btl_eigenblas)\n    target_link_libraries(btl_eigenblas eigen_blas eigen_lapack )\n    set_target_properties(btl_eigenblas PROPERTIES COMPILE_FLAGS \"-DCBLASNAME=EigenBLAS\")\n  endif()\nendif()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/BLAS/blas.h",
    "content": "#ifndef BLAS_H\n#define BLAS_H\n\n#define BLASFUNC(FUNC) FUNC##_\n\n#ifdef __WIN64__\ntypedef long long BLASLONG;\ntypedef unsigned long long BLASULONG;\n#else\ntypedef long BLASLONG;\ntypedef unsigned long BLASULONG;\n#endif\n\nint    BLASFUNC(xerbla)(const char *, int *info, int);\n\nfloat  BLASFUNC(sdot)  (int *, float  *, int *, float  *, int *);\nfloat  BLASFUNC(sdsdot)(int *, float  *,        float  *, int *, float  *, int *);\n\ndouble BLASFUNC(dsdot) (int *, float  *, int *, float  *, int *);\ndouble BLASFUNC(ddot)  (int *, double *, int *, double *, int *);\ndouble BLASFUNC(qdot)  (int *, double *, int *, double *, int *);\n\n#if defined(F_INTERFACE_GFORT) && !defined(__64BIT__)\nint   BLASFUNC(cdotu)  (int *, float  * , int *, float  *,  int *);\nint   BLASFUNC(cdotc)  (int *, float  *,  int *, float  *,  int *);\nvoid  BLASFUNC(zdotu)  (double *, int *, double  *, int *, double  *, int *);\nvoid  BLASFUNC(zdotc)  (double *, int *, double  *, int *, double  *, int *);\nvoid  BLASFUNC(xdotu)  (double *, int *, double  *, int *, double  *, int *);\nvoid  BLASFUNC(xdotc)  (double *, int *, double  *, int *, double  *, int *);\n#elif  defined(F_INTERFACE_F2C) || \\\n     defined(F_INTERFACE_PGI) || \\\n     defined(F_INTERFACE_GFORT) || \\\n    (defined(F_INTERFACE_PATHSCALE) && defined(__64BIT__))\nvoid  BLASFUNC(cdotu)  (float *,  int *, float  * , int *, float  *,  int *);\nvoid  BLASFUNC(cdotc)  (float *,  int *, float  *,  int *, float  *,  int *);\nvoid  BLASFUNC(zdotu)  (double *, int *, double  *, int *, double  *, int *);\nvoid  BLASFUNC(zdotc)  (double *, int *, double  *, int *, double  *, int *);\nvoid  BLASFUNC(xdotu)  (double *, int *, double  *, int *, double  *, int *);\nvoid  BLASFUNC(xdotc)  (double *, int *, double  *, int *, double  *, int *);\n#else\nstd::complex<float>   BLASFUNC(cdotu)  (int *, float  *, int *, float  *, int *);\nstd::complex<float>   BLASFUNC(cdotc)  (int *, float  *, int *, float  *, int *);\nstd::complex<double>  BLASFUNC(zdotu)  (int *, double  *, int *, double  *, int *);\nstd::complex<double>  BLASFUNC(zdotc)  (int *, double  *, int *, double  *, int *);\ndouble  BLASFUNC(xdotu)  (int *, double  *, int *, double  *, int *);\ndouble  BLASFUNC(xdotc)  (int *, double  *, int *, double  *, int *);\n#endif\n\nint  BLASFUNC(cdotuw)  (int *, float  *, int *, float  *, int *, float*);\nint  BLASFUNC(cdotcw)  (int *, float  *, int *, float  *, int *, float*);\nint  BLASFUNC(zdotuw)  (int *, double  *, int *, double  *, int *, double*);\nint  BLASFUNC(zdotcw)  (int *, double  *, int *, double  *, int *, double*);\n\nint    BLASFUNC(saxpy) (int *, float  *, float  *, int *, float  *, int *);\nint    BLASFUNC(daxpy) (int *, double *, double *, int *, double *, int *);\nint    BLASFUNC(qaxpy) (int *, double *, double *, int *, double *, int *);\nint    BLASFUNC(caxpy) (int *, float  *, float  *, int *, float  *, int *);\nint    BLASFUNC(zaxpy) (int *, double *, double *, int *, double *, int *);\nint    BLASFUNC(xaxpy) (int *, double *, double *, int *, double *, int *);\nint    BLASFUNC(caxpyc)(int *, float  *, float  *, int *, float  *, int *);\nint    BLASFUNC(zaxpyc)(int *, double *, double *, int *, double *, int *);\nint    BLASFUNC(xaxpyc)(int *, double *, double *, int *, double *, int *);\n\nint    BLASFUNC(scopy) (int *, float  *, int *, float  *, int *);\nint    BLASFUNC(dcopy) (int *, double *, int *, double *, int *);\nint    BLASFUNC(qcopy) (int *, double *, int *, double *, int *);\nint    BLASFUNC(ccopy) (int *, float  *, int *, float  *, int *);\nint    BLASFUNC(zcopy) (int *, double *, int *, double *, int *);\nint    BLASFUNC(xcopy) (int *, double *, int *, double *, int *);\n\nint    BLASFUNC(sswap) (int *, float  *, int *, float  *, int *);\nint    BLASFUNC(dswap) (int *, double *, int *, double *, int *);\nint    BLASFUNC(qswap) (int *, double *, int *, double *, int *);\nint    BLASFUNC(cswap) (int *, float  *, int *, float  *, int *);\nint    BLASFUNC(zswap) (int *, double *, int *, double *, int *);\nint    BLASFUNC(xswap) (int *, double *, int *, double *, int *);\n\nfloat  BLASFUNC(sasum) (int *, float  *, int *);\nfloat  BLASFUNC(scasum)(int *, float  *, int *);\ndouble BLASFUNC(dasum) (int *, double *, int *);\ndouble BLASFUNC(qasum) (int *, double *, int *);\ndouble BLASFUNC(dzasum)(int *, double *, int *);\ndouble BLASFUNC(qxasum)(int *, double *, int *);\n\nint    BLASFUNC(isamax)(int *, float  *, int *);\nint    BLASFUNC(idamax)(int *, double *, int *);\nint    BLASFUNC(iqamax)(int *, double *, int *);\nint    BLASFUNC(icamax)(int *, float  *, int *);\nint    BLASFUNC(izamax)(int *, double *, int *);\nint    BLASFUNC(ixamax)(int *, double *, int *);\n\nint    BLASFUNC(ismax) (int *, float  *, int *);\nint    BLASFUNC(idmax) (int *, double *, int *);\nint    BLASFUNC(iqmax) (int *, double *, int *);\nint    BLASFUNC(icmax) (int *, float  *, int *);\nint    BLASFUNC(izmax) (int *, double *, int *);\nint    BLASFUNC(ixmax) (int *, double *, int *);\n\nint    BLASFUNC(isamin)(int *, float  *, int *);\nint    BLASFUNC(idamin)(int *, double *, int *);\nint    BLASFUNC(iqamin)(int *, double *, int *);\nint    BLASFUNC(icamin)(int *, float  *, int *);\nint    BLASFUNC(izamin)(int *, double *, int *);\nint    BLASFUNC(ixamin)(int *, double *, int *);\n\nint    BLASFUNC(ismin)(int *, float  *, int *);\nint    BLASFUNC(idmin)(int *, double *, int *);\nint    BLASFUNC(iqmin)(int *, double *, int *);\nint    BLASFUNC(icmin)(int *, float  *, int *);\nint    BLASFUNC(izmin)(int *, double *, int *);\nint    BLASFUNC(ixmin)(int *, double *, int *);\n\nfloat  BLASFUNC(samax) (int *, float  *, int *);\ndouble BLASFUNC(damax) (int *, double *, int *);\ndouble BLASFUNC(qamax) (int *, double *, int *);\nfloat  BLASFUNC(scamax)(int *, float  *, int *);\ndouble BLASFUNC(dzamax)(int *, double *, int *);\ndouble BLASFUNC(qxamax)(int *, double *, int *);\n\nfloat  BLASFUNC(samin) (int *, float  *, int *);\ndouble BLASFUNC(damin) (int *, double *, int *);\ndouble BLASFUNC(qamin) (int *, double *, int *);\nfloat  BLASFUNC(scamin)(int *, float  *, int *);\ndouble BLASFUNC(dzamin)(int *, double *, int *);\ndouble BLASFUNC(qxamin)(int *, double *, int *);\n\nfloat  BLASFUNC(smax)  (int *, float  *, int *);\ndouble BLASFUNC(dmax)  (int *, double *, int *);\ndouble BLASFUNC(qmax)  (int *, double *, int *);\nfloat  BLASFUNC(scmax) (int *, float  *, int *);\ndouble BLASFUNC(dzmax) (int *, double *, int *);\ndouble BLASFUNC(qxmax) (int *, double *, int *);\n\nfloat  BLASFUNC(smin)  (int *, float  *, int *);\ndouble BLASFUNC(dmin)  (int *, double *, int *);\ndouble BLASFUNC(qmin)  (int *, double *, int *);\nfloat  BLASFUNC(scmin) (int *, float  *, int *);\ndouble BLASFUNC(dzmin) (int *, double *, int *);\ndouble BLASFUNC(qxmin) (int *, double *, int *);\n\nint    BLASFUNC(sscal) (int *,  float  *, float  *, int *);\nint    BLASFUNC(dscal) (int *,  double *, double *, int *);\nint    BLASFUNC(qscal) (int *,  double *, double *, int *);\nint    BLASFUNC(cscal) (int *,  float  *, float  *, int *);\nint    BLASFUNC(zscal) (int *,  double *, double *, int *);\nint    BLASFUNC(xscal) (int *,  double *, double *, int *);\nint    BLASFUNC(csscal)(int *,  float  *, float  *, int *);\nint    BLASFUNC(zdscal)(int *,  double *, double *, int *);\nint    BLASFUNC(xqscal)(int *,  double *, double *, int *);\n\nfloat  BLASFUNC(snrm2) (int *, float  *, int *);\nfloat  BLASFUNC(scnrm2)(int *, float  *, int *);\n\ndouble BLASFUNC(dnrm2) (int *, double *, int *);\ndouble BLASFUNC(qnrm2) (int *, double *, int *);\ndouble BLASFUNC(dznrm2)(int *, double *, int *);\ndouble BLASFUNC(qxnrm2)(int *, double *, int *);\n\nint    BLASFUNC(srot)  (int *, float  *, int *, float  *, int *, float  *, float  *);\nint    BLASFUNC(drot)  (int *, double *, int *, double *, int *, double *, double *);\nint    BLASFUNC(qrot)  (int *, double *, int *, double *, int *, double *, double *);\nint    BLASFUNC(csrot) (int *, float  *, int *, float  *, int *, float  *, float  *);\nint    BLASFUNC(zdrot) (int *, double *, int *, double *, int *, double *, double *);\nint    BLASFUNC(xqrot) (int *, double *, int *, double *, int *, double *, double *);\n\nint    BLASFUNC(srotg) (float  *, float  *, float  *, float  *);\nint    BLASFUNC(drotg) (double *, double *, double *, double *);\nint    BLASFUNC(qrotg) (double *, double *, double *, double *);\nint    BLASFUNC(crotg) (float  *, float  *, float  *, float  *);\nint    BLASFUNC(zrotg) (double *, double *, double *, double *);\nint    BLASFUNC(xrotg) (double *, double *, double *, double *);\n\nint    BLASFUNC(srotmg)(float  *, float  *, float  *, float  *, float  *);\nint    BLASFUNC(drotmg)(double *, double *, double *, double *, double *);\n\nint    BLASFUNC(srotm) (int *, float  *, int *, float  *, int *, float  *);\nint    BLASFUNC(drotm) (int *, double *, int *, double *, int *, double *);\nint    BLASFUNC(qrotm) (int *, double *, int *, double *, int *, double *);\n\n/* Level 2 routines */\n\nint BLASFUNC(sger)(int *,    int *, float *,  float *, int *,\n\t\t   float *,  int *, float *,  int *);\nint BLASFUNC(dger)(int *,    int *, double *, double *, int *,\n\t\t   double *, int *, double *, int *);\nint BLASFUNC(qger)(int *,    int *, double *, double *, int *,\n\t\t   double *, int *, double *, int *);\nint BLASFUNC(cgeru)(int *,    int *, float *,  float *, int *,\n\t\t    float *,  int *, float *,  int *);\nint BLASFUNC(cgerc)(int *,    int *, float *,  float *, int *,\n\t\t    float *,  int *, float *,  int *);\nint BLASFUNC(zgeru)(int *,    int *, double *, double *, int *,\n\t\t    double *, int *, double *, int *);\nint BLASFUNC(zgerc)(int *,    int *, double *, double *, int *,\n\t\t    double *, int *, double *, int *);\nint BLASFUNC(xgeru)(int *,    int *, double *, double *, int *,\n\t\t    double *, int *, double *, int *);\nint BLASFUNC(xgerc)(int *,    int *, double *, double *, int *,\n\t\t    double *, int *, double *, int *);\n\nint BLASFUNC(sgemv)(char *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(dgemv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(qgemv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(cgemv)(char *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zgemv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(xgemv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\n\nint BLASFUNC(strsv) (char *, char *, char *, int *, float  *, int *,\n\t\t     float  *, int *);\nint BLASFUNC(dtrsv) (char *, char *, char *, int *, double *, int *,\n\t\t     double *, int *);\nint BLASFUNC(qtrsv) (char *, char *, char *, int *, double *, int *,\n\t\t     double *, int *);\nint BLASFUNC(ctrsv) (char *, char *, char *, int *, float  *, int *,\n\t\t     float  *, int *);\nint BLASFUNC(ztrsv) (char *, char *, char *, int *, double *, int *,\n\t\t     double *, int *);\nint BLASFUNC(xtrsv) (char *, char *, char *, int *, double *, int *,\n\t\t     double *, int *);\n\nint BLASFUNC(stpsv) (char *, char *, char *, int *, float  *, float  *, int *);\nint BLASFUNC(dtpsv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(qtpsv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(ctpsv) (char *, char *, char *, int *, float  *, float  *, int *);\nint BLASFUNC(ztpsv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(xtpsv) (char *, char *, char *, int *, double *, double *, int *);\n\nint BLASFUNC(strmv) (char *, char *, char *, int *, float  *, int *,\n\t\t     float  *, int *);\nint BLASFUNC(dtrmv) (char *, char *, char *, int *, double *, int *,\n\t\t     double *, int *);\nint BLASFUNC(qtrmv) (char *, char *, char *, int *, double *, int *,\n\t\t     double *, int *);\nint BLASFUNC(ctrmv) (char *, char *, char *, int *, float  *, int *,\n\t\t     float  *, int *);\nint BLASFUNC(ztrmv) (char *, char *, char *, int *, double *, int *,\n\t\t     double *, int *);\nint BLASFUNC(xtrmv) (char *, char *, char *, int *, double *, int *,\n\t\t     double *, int *);\n\nint BLASFUNC(stpmv) (char *, char *, char *, int *, float  *, float  *, int *);\nint BLASFUNC(dtpmv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(qtpmv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(ctpmv) (char *, char *, char *, int *, float  *, float  *, int *);\nint BLASFUNC(ztpmv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(xtpmv) (char *, char *, char *, int *, double *, double *, int *);\n\nint BLASFUNC(stbmv) (char *, char *, char *, int *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(dtbmv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(qtbmv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(ctbmv) (char *, char *, char *, int *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(ztbmv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(xtbmv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\n\nint BLASFUNC(stbsv) (char *, char *, char *, int *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(dtbsv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(qtbsv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(ctbsv) (char *, char *, char *, int *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(ztbsv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(xtbsv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\n\nint BLASFUNC(ssymv) (char *, int *, float  *, float *, int *,\n\t\t     float  *, int *, float *, float *, int *);\nint BLASFUNC(dsymv) (char *, int *, double  *, double *, int *,\n\t\t     double  *, int *, double *, double *, int *);\nint BLASFUNC(qsymv) (char *, int *, double  *, double *, int *,\n\t\t     double  *, int *, double *, double *, int *);\nint BLASFUNC(csymv) (char *, int *, float  *, float *, int *,\n\t\t     float  *, int *, float *, float *, int *);\nint BLASFUNC(zsymv) (char *, int *, double  *, double *, int *,\n\t\t     double  *, int *, double *, double *, int *);\nint BLASFUNC(xsymv) (char *, int *, double  *, double *, int *,\n\t\t     double  *, int *, double *, double *, int *);\n\nint BLASFUNC(sspmv) (char *, int *, float  *, float *,\n\t\t     float  *, int *, float *, float *, int *);\nint BLASFUNC(dspmv) (char *, int *, double  *, double *,\n\t\t     double  *, int *, double *, double *, int *);\nint BLASFUNC(qspmv) (char *, int *, double  *, double *,\n\t\t     double  *, int *, double *, double *, int *);\nint BLASFUNC(cspmv) (char *, int *, float  *, float *,\n\t\t     float  *, int *, float *, float *, int *);\nint BLASFUNC(zspmv) (char *, int *, double  *, double *,\n\t\t     double  *, int *, double *, double *, int *);\nint BLASFUNC(xspmv) (char *, int *, double  *, double *,\n\t\t     double  *, int *, double *, double *, int *);\n\nint BLASFUNC(ssyr) (char *, int *, float   *, float  *, int *,\n\t\t    float  *, int *);\nint BLASFUNC(dsyr) (char *, int *, double  *, double *, int *,\n\t\t    double *, int *);\nint BLASFUNC(qsyr) (char *, int *, double  *, double *, int *,\n\t\t    double *, int *);\nint BLASFUNC(csyr) (char *, int *, float   *, float  *, int *,\n\t\t    float  *, int *);\nint BLASFUNC(zsyr) (char *, int *, double  *, double *, int *,\n\t\t    double *, int *);\nint BLASFUNC(xsyr) (char *, int *, double  *, double *, int *,\n\t\t    double *, int *);\n\nint BLASFUNC(ssyr2) (char *, int *, float   *,\n\t\t     float  *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(dsyr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *, int *);\nint BLASFUNC(qsyr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *, int *);\nint BLASFUNC(csyr2) (char *, int *, float   *,\n\t\t     float  *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(zsyr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *, int *);\nint BLASFUNC(xsyr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *, int *);\n\nint BLASFUNC(sspr) (char *, int *, float   *, float  *, int *,\n\t\t    float  *);\nint BLASFUNC(dspr) (char *, int *, double  *, double *, int *,\n\t\t    double *);\nint BLASFUNC(qspr) (char *, int *, double  *, double *, int *,\n\t\t    double *);\nint BLASFUNC(cspr) (char *, int *, float   *, float  *, int *,\n\t\t    float  *);\nint BLASFUNC(zspr) (char *, int *, double  *, double *, int *,\n\t\t    double *);\nint BLASFUNC(xspr) (char *, int *, double  *, double *, int *,\n\t\t    double *);\n\nint BLASFUNC(sspr2) (char *, int *, float   *,\n\t\t     float  *, int *, float  *, int *, float  *);\nint BLASFUNC(dspr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\nint BLASFUNC(qspr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\nint BLASFUNC(cspr2) (char *, int *, float   *,\n\t\t     float  *, int *, float  *, int *, float  *);\nint BLASFUNC(zspr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\nint BLASFUNC(xspr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\n\nint BLASFUNC(cher) (char *, int *, float   *, float  *, int *,\n\t\t    float  *, int *);\nint BLASFUNC(zher) (char *, int *, double  *, double *, int *,\n\t\t    double *, int *);\nint BLASFUNC(xher) (char *, int *, double  *, double *, int *,\n\t\t    double *, int *);\n\nint BLASFUNC(chpr) (char *, int *, float   *, float  *, int *, float  *);\nint BLASFUNC(zhpr) (char *, int *, double  *, double *, int *, double *);\nint BLASFUNC(xhpr) (char *, int *, double  *, double *, int *, double *);\n\nint BLASFUNC(cher2) (char *, int *, float   *,\n\t\t     float  *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(zher2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *, int *);\nint BLASFUNC(xher2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *, int *);\n\nint BLASFUNC(chpr2) (char *, int *, float   *,\n\t\t     float  *, int *, float  *, int *, float  *);\nint BLASFUNC(zhpr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\nint BLASFUNC(xhpr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\n\nint BLASFUNC(chemv) (char *, int *, float  *, float *, int *,\n\t\t     float  *, int *, float *, float *, int *);\nint BLASFUNC(zhemv) (char *, int *, double  *, double *, int *,\n\t\t     double  *, int *, double *, double *, int *);\nint BLASFUNC(xhemv) (char *, int *, double  *, double *, int *,\n\t\t     double  *, int *, double *, double *, int *);\n\nint BLASFUNC(chpmv) (char *, int *, float  *, float *,\n\t\t     float  *, int *, float *, float *, int *);\nint BLASFUNC(zhpmv) (char *, int *, double  *, double *,\n\t\t     double  *, int *, double *, double *, int *);\nint BLASFUNC(xhpmv) (char *, int *, double  *, double *,\n\t\t     double  *, int *, double *, double *, int *);\n\nint BLASFUNC(snorm)(char *, int *, int *, float  *, int *);\nint BLASFUNC(dnorm)(char *, int *, int *, double *, int *);\nint BLASFUNC(cnorm)(char *, int *, int *, float  *, int *);\nint BLASFUNC(znorm)(char *, int *, int *, double *, int *);\n\nint BLASFUNC(sgbmv)(char *, int *, int *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(dgbmv)(char *, int *, int *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(qgbmv)(char *, int *, int *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(cgbmv)(char *, int *, int *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zgbmv)(char *, int *, int *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(xgbmv)(char *, int *, int *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\n\nint BLASFUNC(ssbmv)(char *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(dsbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(qsbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(csbmv)(char *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zsbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(xsbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\n\nint BLASFUNC(chbmv)(char *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zhbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(xhbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\n\n/* Level 3 routines */\n\nint BLASFUNC(sgemm)(char *, char *, int *, int *, int *, float *,\n\t   float  *, int *, float  *, int *, float  *, float  *, int *);\nint BLASFUNC(dgemm)(char *, char *, int *, int *, int *, double *,\n\t   double *, int *, double *, int *, double *, double *, int *);\nint BLASFUNC(qgemm)(char *, char *, int *, int *, int *, double *,\n\t   double *, int *, double *, int *, double *, double *, int *);\nint BLASFUNC(cgemm)(char *, char *, int *, int *, int *, float *,\n\t   float  *, int *, float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zgemm)(char *, char *, int *, int *, int *, double *,\n\t   double *, int *, double *, int *, double *, double *, int *);\nint BLASFUNC(xgemm)(char *, char *, int *, int *, int *, double *,\n\t   double *, int *, double *, int *, double *, double *, int *);\n\nint BLASFUNC(cgemm3m)(char *, char *, int *, int *, int *, float *,\n\t   float  *, int *, float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zgemm3m)(char *, char *, int *, int *, int *, double *,\n\t   double *, int *, double *, int *, double *, double *, int *);\nint BLASFUNC(xgemm3m)(char *, char *, int *, int *, int *, double *,\n\t   double *, int *, double *, int *, double *, double *, int *);\n\nint BLASFUNC(sge2mm)(char *, char *, char *, int *, int *,\n\t\t     float *, float  *, int *, float  *, int *,\n\t\t     float *, float  *, int *);\nint BLASFUNC(dge2mm)(char *, char *, char *, int *, int *,\n\t\t     double *, double  *, int *, double  *, int *,\n\t\t     double *, double  *, int *);\nint BLASFUNC(cge2mm)(char *, char *, char *, int *, int *,\n\t\t     float *, float  *, int *, float  *, int *,\n\t\t     float *, float  *, int *);\nint BLASFUNC(zge2mm)(char *, char *, char *, int *, int *,\n\t\t     double *, double  *, int *, double  *, int *,\n\t\t     double *, double  *, int *);\n\nint BLASFUNC(strsm)(char *, char *, char *, char *, int *, int *,\n\t   float *,  float *, int *, float *, int *);\nint BLASFUNC(dtrsm)(char *, char *, char *, char *, int *, int *,\n\t   double *,  double *, int *, double *, int *);\nint BLASFUNC(qtrsm)(char *, char *, char *, char *, int *, int *,\n\t   double *,  double *, int *, double *, int *);\nint BLASFUNC(ctrsm)(char *, char *, char *, char *, int *, int *,\n\t   float *,  float *, int *, float *, int *);\nint BLASFUNC(ztrsm)(char *, char *, char *, char *, int *, int *,\n\t   double *,  double *, int *, double *, int *);\nint BLASFUNC(xtrsm)(char *, char *, char *, char *, int *, int *,\n\t   double *,  double *, int *, double *, int *);\n\nint BLASFUNC(strmm)(char *, char *, char *, char *, int *, int *,\n\t   float *,  float *, int *, float *, int *);\nint BLASFUNC(dtrmm)(char *, char *, char *, char *, int *, int *,\n\t   double *,  double *, int *, double *, int *);\nint BLASFUNC(qtrmm)(char *, char *, char *, char *, int *, int *,\n\t   double *,  double *, int *, double *, int *);\nint BLASFUNC(ctrmm)(char *, char *, char *, char *, int *, int *,\n\t   float *,  float *, int *, float *, int *);\nint BLASFUNC(ztrmm)(char *, char *, char *, char *, int *, int *,\n\t   double *,  double *, int *, double *, int *);\nint BLASFUNC(xtrmm)(char *, char *, char *, char *, int *, int *,\n\t   double *,  double *, int *, double *, int *);\n\nint BLASFUNC(ssymm)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float  *, int *, float  *, float  *, int *);\nint BLASFUNC(dsymm)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\nint BLASFUNC(qsymm)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\nint BLASFUNC(csymm)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zsymm)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\nint BLASFUNC(xsymm)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\n\nint BLASFUNC(csymm3m)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zsymm3m)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\nint BLASFUNC(xsymm3m)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\n\nint BLASFUNC(ssyrk)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float  *, float  *, int *);\nint BLASFUNC(dsyrk)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, double *, int *);\nint BLASFUNC(qsyrk)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, double *, int *);\nint BLASFUNC(csyrk)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float  *, float  *, int *);\nint BLASFUNC(zsyrk)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, double *, int *);\nint BLASFUNC(xsyrk)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, double *, int *);\n\nint BLASFUNC(ssyr2k)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float *, int *, float  *, float  *, int *);\nint BLASFUNC(dsyr2k)(char *, char *, int *, int *, double *, double *, int *,\n\t   double*, int *, double *, double *, int *);\nint BLASFUNC(qsyr2k)(char *, char *, int *, int *, double *, double *, int *,\n\t   double*, int *, double *, double *, int *);\nint BLASFUNC(csyr2k)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float *, int *, float  *, float  *, int *);\nint BLASFUNC(zsyr2k)(char *, char *, int *, int *, double *, double *, int *,\n\t   double*, int *, double *, double *, int *);\nint BLASFUNC(xsyr2k)(char *, char *, int *, int *, double *, double *, int *,\n\t   double*, int *, double *, double *, int *);\n\nint BLASFUNC(chemm)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zhemm)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\nint BLASFUNC(xhemm)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\n\nint BLASFUNC(chemm3m)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zhemm3m)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\nint BLASFUNC(xhemm3m)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\n\nint BLASFUNC(cherk)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float  *, float  *, int *);\nint BLASFUNC(zherk)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, double *, int *);\nint BLASFUNC(xherk)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, double *, int *);\n\nint BLASFUNC(cher2k)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float *, int *, float  *, float  *, int *);\nint BLASFUNC(zher2k)(char *, char *, int *, int *, double *, double *, int *,\n\t   double*, int *, double *, double *, int *);\nint BLASFUNC(xher2k)(char *, char *, int *, int *, double *, double *, int *,\n\t   double*, int *, double *, double *, int *);\nint BLASFUNC(cher2m)(char *, char *, char *, int *, int *, float  *, float  *, int *,\n\t   float *, int *, float  *, float  *, int *);\nint BLASFUNC(zher2m)(char *, char *, char *, int *, int *, double *, double *, int *,\n\t   double*, int *, double *, double *, int *);\nint BLASFUNC(xher2m)(char *, char *, char *, int *, int *, double *, double *, int *,\n\t   double*, int *, double *, double *, int *);\n\nint BLASFUNC(sgemt)(char *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *);\nint BLASFUNC(dgemt)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *);\nint BLASFUNC(cgemt)(char *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *);\nint BLASFUNC(zgemt)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *);\n\nint BLASFUNC(sgema)(char *, char *, int *, int *, float  *,\n\t\t    float  *, int *, float *, float  *, int *, float *, int *);\nint BLASFUNC(dgema)(char *, char *, int *, int *, double *,\n\t\t    double *, int *, double*, double *, int *, double*, int *);\nint BLASFUNC(cgema)(char *, char *, int *, int *, float  *,\n\t\t    float  *, int *, float *, float  *, int *, float *, int *);\nint BLASFUNC(zgema)(char *, char *, int *, int *, double *,\n\t\t    double *, int *, double*, double *, int *, double*, int *);\n\nint BLASFUNC(sgems)(char *, char *, int *, int *, float  *,\n\t\t    float  *, int *, float *, float  *, int *, float *, int *);\nint BLASFUNC(dgems)(char *, char *, int *, int *, double *,\n\t\t    double *, int *, double*, double *, int *, double*, int *);\nint BLASFUNC(cgems)(char *, char *, int *, int *, float  *,\n\t\t    float  *, int *, float *, float  *, int *, float *, int *);\nint BLASFUNC(zgems)(char *, char *, int *, int *, double *,\n\t\t    double *, int *, double*, double *, int *, double*, int *);\n\nint BLASFUNC(sgetf2)(int *, int *, float  *, int *, int *, int *);\nint BLASFUNC(dgetf2)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(qgetf2)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(cgetf2)(int *, int *, float  *, int *, int *, int *);\nint BLASFUNC(zgetf2)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(xgetf2)(int *, int *, double *, int *, int *, int *);\n\nint BLASFUNC(sgetrf)(int *, int *, float  *, int *, int *, int *);\nint BLASFUNC(dgetrf)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(qgetrf)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(cgetrf)(int *, int *, float  *, int *, int *, int *);\nint BLASFUNC(zgetrf)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(xgetrf)(int *, int *, double *, int *, int *, int *);\n\nint BLASFUNC(slaswp)(int *, float  *, int *, int *, int *, int *, int *);\nint BLASFUNC(dlaswp)(int *, double *, int *, int *, int *, int *, int *);\nint BLASFUNC(qlaswp)(int *, double *, int *, int *, int *, int *, int *);\nint BLASFUNC(claswp)(int *, float  *, int *, int *, int *, int *, int *);\nint BLASFUNC(zlaswp)(int *, double *, int *, int *, int *, int *, int *);\nint BLASFUNC(xlaswp)(int *, double *, int *, int *, int *, int *, int *);\n\nint BLASFUNC(sgetrs)(char *, int *, int *, float  *, int *, int *, float  *, int *, int *);\nint BLASFUNC(dgetrs)(char *, int *, int *, double *, int *, int *, double *, int *, int *);\nint BLASFUNC(qgetrs)(char *, int *, int *, double *, int *, int *, double *, int *, int *);\nint BLASFUNC(cgetrs)(char *, int *, int *, float  *, int *, int *, float  *, int *, int *);\nint BLASFUNC(zgetrs)(char *, int *, int *, double *, int *, int *, double *, int *, int *);\nint BLASFUNC(xgetrs)(char *, int *, int *, double *, int *, int *, double *, int *, int *);\n\nint BLASFUNC(sgesv)(int *, int *, float  *, int *, int *, float *, int *, int *);\nint BLASFUNC(dgesv)(int *, int *, double *, int *, int *, double*, int *, int *);\nint BLASFUNC(qgesv)(int *, int *, double *, int *, int *, double*, int *, int *);\nint BLASFUNC(cgesv)(int *, int *, float  *, int *, int *, float *, int *, int *);\nint BLASFUNC(zgesv)(int *, int *, double *, int *, int *, double*, int *, int *);\nint BLASFUNC(xgesv)(int *, int *, double *, int *, int *, double*, int *, int *);\n\nint BLASFUNC(spotf2)(char *, int *, float  *, int *, int *);\nint BLASFUNC(dpotf2)(char *, int *, double *, int *, int *);\nint BLASFUNC(qpotf2)(char *, int *, double *, int *, int *);\nint BLASFUNC(cpotf2)(char *, int *, float  *, int *, int *);\nint BLASFUNC(zpotf2)(char *, int *, double *, int *, int *);\nint BLASFUNC(xpotf2)(char *, int *, double *, int *, int *);\n\nint BLASFUNC(spotrf)(char *, int *, float  *, int *, int *);\nint BLASFUNC(dpotrf)(char *, int *, double *, int *, int *);\nint BLASFUNC(qpotrf)(char *, int *, double *, int *, int *);\nint BLASFUNC(cpotrf)(char *, int *, float  *, int *, int *);\nint BLASFUNC(zpotrf)(char *, int *, double *, int *, int *);\nint BLASFUNC(xpotrf)(char *, int *, double *, int *, int *);\n\nint BLASFUNC(slauu2)(char *, int *, float  *, int *, int *);\nint BLASFUNC(dlauu2)(char *, int *, double *, int *, int *);\nint BLASFUNC(qlauu2)(char *, int *, double *, int *, int *);\nint BLASFUNC(clauu2)(char *, int *, float  *, int *, int *);\nint BLASFUNC(zlauu2)(char *, int *, double *, int *, int *);\nint BLASFUNC(xlauu2)(char *, int *, double *, int *, int *);\n\nint BLASFUNC(slauum)(char *, int *, float  *, int *, int *);\nint BLASFUNC(dlauum)(char *, int *, double *, int *, int *);\nint BLASFUNC(qlauum)(char *, int *, double *, int *, int *);\nint BLASFUNC(clauum)(char *, int *, float  *, int *, int *);\nint BLASFUNC(zlauum)(char *, int *, double *, int *, int *);\nint BLASFUNC(xlauum)(char *, int *, double *, int *, int *);\n\nint BLASFUNC(strti2)(char *, char *, int *, float  *, int *, int *);\nint BLASFUNC(dtrti2)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(qtrti2)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(ctrti2)(char *, char *, int *, float  *, int *, int *);\nint BLASFUNC(ztrti2)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(xtrti2)(char *, char *, int *, double *, int *, int *);\n\nint BLASFUNC(strtri)(char *, char *, int *, float  *, int *, int *);\nint BLASFUNC(dtrtri)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(qtrtri)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(ctrtri)(char *, char *, int *, float  *, int *, int *);\nint BLASFUNC(ztrtri)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(xtrtri)(char *, char *, int *, double *, int *, int *);\n\nint BLASFUNC(spotri)(char *, int *, float  *, int *, int *);\nint BLASFUNC(dpotri)(char *, int *, double *, int *, int *);\nint BLASFUNC(qpotri)(char *, int *, double *, int *, int *);\nint BLASFUNC(cpotri)(char *, int *, float  *, int *, int *);\nint BLASFUNC(zpotri)(char *, int *, double *, int *, int *);\nint BLASFUNC(xpotri)(char *, int *, double *, int *, int *);\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/BLAS/blas_interface.hh",
    "content": "//=====================================================\n// File   :  blas_interface.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:28 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef blas_PRODUIT_MATRICE_VECTEUR_HH\n#define blas_PRODUIT_MATRICE_VECTEUR_HH\n\n#include <c_interface_base.h>\n#include <complex>\nextern \"C\"\n{\n#include \"blas.h\"\n\n  // Cholesky Factorization\n//   void spotrf_(const char* uplo, const int* n, float *a, const int* ld, int* info);\n//   void dpotrf_(const char* uplo, const int* n, double *a, const int* ld, int* info);\n  void ssytrd_(char *uplo, const int *n, float *a, const int *lda, float *d, float *e, float *tau, float *work, int *lwork, int *info );\n  void dsytrd_(char *uplo, const int *n, double *a, const int *lda, double *d, double *e, double *tau, double *work, int *lwork, int *info );\n  void sgehrd_( const int *n, int *ilo, int *ihi, float *a, const int *lda, float *tau, float *work, int *lwork, int *info );\n  void dgehrd_( const int *n, int *ilo, int *ihi, double *a, const int *lda, double *tau, double *work, int *lwork, int *info );\n\n  // LU row pivoting\n//   void dgetrf_( int *m, int *n, double *a, int *lda, int *ipiv, int *info );\n//   void sgetrf_(const int* m, const int* n, float *a, const int* ld, int* ipivot, int* info);\n  // LU full pivoting\n  void sgetc2_(const int* n, float *a, const int *lda, int *ipiv, int *jpiv, int*info );\n  void dgetc2_(const int* n, double *a, const int *lda, int *ipiv, int *jpiv, int*info );\n#ifdef HAS_LAPACK\n#endif\n}\n\n#define MAKE_STRING2(S) #S\n#define MAKE_STRING(S) MAKE_STRING2(S)\n\n#define CAT2(A,B) A##B\n#define CAT(A,B) CAT2(A,B)\n\n\ntemplate<class real> class blas_interface;\n\n\nstatic char notrans = 'N';\nstatic char trans = 'T';\nstatic char nonunit = 'N';\nstatic char lower = 'L';\nstatic char right = 'R';\nstatic char left = 'L';\nstatic int intone = 1;\n\n\n\n#define SCALAR        float\n#define SCALAR_PREFIX s\n#include \"blas_interface_impl.hh\"\n#undef SCALAR\n#undef SCALAR_PREFIX\n\n\n#define SCALAR        double\n#define SCALAR_PREFIX d\n#include \"blas_interface_impl.hh\"\n#undef SCALAR\n#undef SCALAR_PREFIX\n\n#endif\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/BLAS/blas_interface_impl.hh",
    "content": "\n#define BLAS_FUNC(NAME) CAT(CAT(SCALAR_PREFIX,NAME),_)\n\ntemplate<> class blas_interface<SCALAR> : public c_interface_base<SCALAR>\n{\n\npublic :\n  \n  static SCALAR fone;\n  static SCALAR fzero;\n\n  static inline std::string name()\n  {\n    return MAKE_STRING(CBLASNAME);\n  }\n\n  static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    BLAS_FUNC(gemv)(&notrans,&N,&N,&fone,A,&N,B,&intone,&fzero,X,&intone);\n  }\n\n  static inline void symv(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    BLAS_FUNC(symv)(&lower, &N,&fone,A,&N,B,&intone,&fzero,X,&intone);\n  }\n\n  static inline void syr2(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    BLAS_FUNC(syr2)(&lower,&N,&fone,B,&intone,X,&intone,A,&N);\n  }\n\n  static inline void ger(gene_matrix & A, gene_vector & X, gene_vector & Y, int N){\n    BLAS_FUNC(ger)(&N,&N,&fone,X,&intone,Y,&intone,A,&N);\n  }\n\n  static inline void rot(gene_vector & A,  gene_vector & B, SCALAR c, SCALAR s, int N){\n    BLAS_FUNC(rot)(&N,A,&intone,B,&intone,&c,&s);\n  }\n\n  static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    BLAS_FUNC(gemv)(&trans,&N,&N,&fone,A,&N,B,&intone,&fzero,X,&intone);\n  }\n\n  static inline void matrix_matrix_product(gene_matrix & A, gene_matrix & B, gene_matrix & X, int N){\n    BLAS_FUNC(gemm)(&notrans,&notrans,&N,&N,&N,&fone,A,&N,B,&N,&fzero,X,&N);\n  }\n\n  static inline void transposed_matrix_matrix_product(gene_matrix & A, gene_matrix & B, gene_matrix & X, int N){\n    BLAS_FUNC(gemm)(&notrans,&notrans,&N,&N,&N,&fone,A,&N,B,&N,&fzero,X,&N);\n  }\n\n  static inline void ata_product(gene_matrix & A, gene_matrix & X, int N){\n    BLAS_FUNC(syrk)(&lower,&trans,&N,&N,&fone,A,&N,&fzero,X,&N);\n  }\n\n  static inline void aat_product(gene_matrix & A, gene_matrix & X, int N){\n    BLAS_FUNC(syrk)(&lower,&notrans,&N,&N,&fone,A,&N,&fzero,X,&N);\n  }\n\n  static inline void axpy(SCALAR coef, const gene_vector & X, gene_vector & Y, int N){\n    BLAS_FUNC(axpy)(&N,&coef,X,&intone,Y,&intone);\n  }\n\n  static inline void axpby(SCALAR a, const gene_vector & X, SCALAR b, gene_vector & Y, int N){\n    BLAS_FUNC(scal)(&N,&b,Y,&intone);\n    BLAS_FUNC(axpy)(&N,&a,X,&intone,Y,&intone);\n  }\n\n  static inline void cholesky(const gene_matrix & X, gene_matrix & C, int N){\n    int N2 = N*N;\n    BLAS_FUNC(copy)(&N2, X, &intone, C, &intone);\n    char uplo = 'L';\n    int info = 0;\n    BLAS_FUNC(potrf)(&uplo, &N, C, &N, &info);\n    if(info!=0) std::cerr << \"potrf_ error \" << info << \"\\n\";\n  }\n\n  static inline void partial_lu_decomp(const gene_matrix & X, gene_matrix & C, int N){\n    int N2 = N*N;\n    BLAS_FUNC(copy)(&N2, X, &intone, C, &intone);\n    int info = 0;\n    int * ipiv = (int*)alloca(sizeof(int)*N);\n    BLAS_FUNC(getrf)(&N, &N, C, &N, ipiv, &info);\n    if(info!=0) std::cerr << \"getrf_ error \" << info << \"\\n\";\n  }\n  \n  static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector & X, int N){\n    BLAS_FUNC(copy)(&N, B, &intone, X, &intone);\n    BLAS_FUNC(trsv)(&lower, &notrans, &nonunit, &N, L, &N, X, &intone);\n  }\n\n  static inline void trisolve_lower_matrix(const gene_matrix & L, const gene_matrix& B, gene_matrix & X, int N){\n    BLAS_FUNC(copy)(&N, B, &intone, X, &intone);\n    BLAS_FUNC(trsm)(&right, &lower, &notrans, &nonunit, &N, &N, &fone, L, &N, X, &N);\n  }\n\n  static inline void trmm(gene_matrix & A, gene_matrix & B, gene_matrix & /*X*/, int N){\n    BLAS_FUNC(trmm)(&left, &lower, &notrans,&nonunit, &N,&N,&fone,A,&N,B,&N);\n  }\n\n  #ifdef HAS_LAPACK\n\n  static inline void lu_decomp(const gene_matrix & X, gene_matrix & C, int N){\n    int N2 = N*N;\n    BLAS_FUNC(copy)(&N2, X, &intone, C, &intone);\n    int info = 0;\n    int * ipiv = (int*)alloca(sizeof(int)*N);\n    int * jpiv = (int*)alloca(sizeof(int)*N);\n    BLAS_FUNC(getc2)(&N, C, &N, ipiv, jpiv, &info);\n  }\n\n\n\n  static inline void hessenberg(const gene_matrix & X, gene_matrix & C, int N){\n    {\n      int N2 = N*N;\n      int inc = 1;\n      BLAS_FUNC(copy)(&N2, X, &inc, C, &inc);\n    }\n    int info = 0;\n    int ilo = 1;\n    int ihi = N;\n    int bsize = 64;\n    int worksize = N*bsize;\n    SCALAR* d = new SCALAR[N+worksize];\n    BLAS_FUNC(gehrd)(&N, &ilo, &ihi, C, &N, d, d+N, &worksize, &info);\n    delete[] d;\n  }\n\n  static inline void tridiagonalization(const gene_matrix & X, gene_matrix & C, int N){\n    {\n      int N2 = N*N;\n      int inc = 1;\n      BLAS_FUNC(copy)(&N2, X, &inc, C, &inc);\n    }\n    char uplo = 'U';\n    int info = 0;\n    int bsize = 64;\n    int worksize = N*bsize;\n    SCALAR* d = new SCALAR[3*N+worksize];\n    BLAS_FUNC(sytrd)(&uplo, &N, C, &N, d, d+N, d+2*N, d+3*N, &worksize, &info);\n    delete[] d;\n  }\n  \n  #endif // HAS_LAPACK\n\n};\n\nSCALAR blas_interface<SCALAR>::fone = SCALAR(1);\nSCALAR blas_interface<SCALAR>::fzero = SCALAR(0);\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/BLAS/c_interface_base.h",
    "content": "\n#ifndef BTL_C_INTERFACE_BASE_H\n#define BTL_C_INTERFACE_BASE_H\n\n#include \"utilities.h\"\n#include <vector>\n\ntemplate<class real> class c_interface_base\n{\n\npublic:\n\n  typedef real                      real_type;\n  typedef std::vector<real>         stl_vector;\n  typedef std::vector<stl_vector >  stl_matrix;\n\n  typedef real* gene_matrix;\n  typedef real* gene_vector;\n\n  static void free_matrix(gene_matrix & A, int /*N*/){\n    delete[] A;\n  }\n\n  static void free_vector(gene_vector & B){\n    delete[] B;\n  }\n\n  static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    int N = A_stl.size();\n    A = new real[N*N];\n    for (int j=0;j<N;j++)\n      for (int i=0;i<N;i++)\n        A[i+N*j] = A_stl[j][i];\n  }\n\n  static inline void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    int N = B_stl.size();\n    B = new real[N];\n    for (int i=0;i<N;i++)\n      B[i] = B_stl[i];\n  }\n\n  static inline void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    int N = B_stl.size();\n    for (int i=0;i<N;i++)\n      B_stl[i] = B[i];\n  }\n\n  static inline void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int N = A_stl.size();\n    for (int j=0;j<N;j++){\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++)\n        A_stl[j][i] = A[i+N*j];\n    }\n  }\n\n  static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){\n    for (int i=0;i<N;i++)\n      cible[i]=source[i];\n  }\n\n  static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){\n    for (int j=0;j<N;j++){\n      for (int i=0;i<N;i++){\n        cible[i+N*j] = source[i+N*j];\n      }\n    }\n  }\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/BLAS/main.cpp",
    "content": "//=====================================================\n// File   :  main.cpp\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:28 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"blas_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\n#include \"action_cholesky.hh\"\n#include \"action_lu_decomp.hh\"\n#include \"action_partial_lu.hh\"\n#include \"action_trisolve_matrix.hh\"\n\n#ifdef HAS_LAPACK\n#include \"action_hessenberg.hh\"\n#endif\n\nBTL_MAIN;\n\nint main()\n{\n\n  bench<Action_axpy<blas_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_axpby<blas_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n\n  bench<Action_matrix_vector_product<blas_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_atv_product<blas_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_symv<blas_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_syr2<blas_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n\n  bench<Action_ger<blas_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_rot<blas_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n\n  bench<Action_matrix_matrix_product<blas_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_ata_product<blas_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_aat_product<blas_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  bench<Action_trisolve<blas_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_trisolve_matrix<blas_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  bench<Action_trmm<blas_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  bench<Action_cholesky<blas_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n  bench<Action_partial_lu<blas_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n\n  #ifdef HAS_LAPACK\n//   bench<Action_lu_decomp<blas_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n  bench<Action_hessenberg<blas_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n  bench<Action_tridiagonalization<blas_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n  #endif\n\n  //bench<Action_lu_solve<blas_LU_solve_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/STL/CMakeLists.txt",
    "content": "\nbtl_add_bench(btl_STL main.cpp OFF)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/STL/STL_interface.hh",
    "content": "//=====================================================\n// File   :  STL_interface.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:24 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef STL_INTERFACE_HH\n#define STL_INTERFACE_HH\n#include <string>\n#include <vector>\n#include \"utilities.h\"\n\nusing namespace std;\n\ntemplate<class real>\nclass STL_interface{\n\npublic :\n\n  typedef real real_type ;\n\n  typedef std::vector<real>  stl_vector;\n  typedef std::vector<stl_vector > stl_matrix;\n\n  typedef stl_matrix gene_matrix;\n\n  typedef stl_vector gene_vector;\n\n  static inline std::string name( void )\n  {\n    return \"STL\";\n  }\n\n  static void free_matrix(gene_matrix & /*A*/, int /*N*/){}\n\n  static void free_vector(gene_vector & /*B*/){}\n\n  static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    A = A_stl;\n  }\n\n  static inline void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    B = B_stl;\n  }\n\n  static inline void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    B_stl = B ;\n  }\n\n\n  static inline void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    A_stl = A ;\n  }\n\n  static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){\n    for (int i=0;i<N;i++){\n      cible[i]=source[i];\n    }\n  }\n\n\n  static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){\n    for (int i=0;i<N;i++)\n      for (int j=0;j<N;j++)\n        cible[i][j]=source[i][j];\n  }\n\n  static inline void ata_product(const gene_matrix & A, gene_matrix & X, int N)\n  {\n    real somme;\n    for (int j=0;j<N;j++){\n      for (int i=0;i<N;i++){\n        somme=0.0;\n        for (int k=0;k<N;k++)\n          somme += A[i][k]*A[j][k];\n        X[j][i]=somme;\n      }\n    }\n  }\n\n  static inline void aat_product(const gene_matrix & A, gene_matrix & X, int N)\n  {\n    real somme;\n    for (int j=0;j<N;j++){\n      for (int i=0;i<N;i++){\n        somme=0.0;\n        if(i>=j)\n        {\n          for (int k=0;k<N;k++){\n            somme+=A[k][i]*A[k][j];\n          }\n          X[j][i]=somme;\n        }\n      }\n    }\n  }\n\n\n  static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N)\n  {\n    real somme;\n    for (int j=0;j<N;j++){\n      for (int i=0;i<N;i++){\n        somme=0.0;\n        for (int k=0;k<N;k++)\n          somme+=A[k][i]*B[j][k];\n        X[j][i]=somme;\n      }\n    }\n  }\n\n  static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N)\n  {\n    real somme;\n    for (int i=0;i<N;i++){\n      somme=0.0;\n      for (int j=0;j<N;j++)\n        somme+=A[j][i]*B[j];\n      X[i]=somme;\n    }\n  }\n\n  static inline void symv(gene_matrix & A, gene_vector & B, gene_vector & X, int N)\n  {\n    for (int j=0; j<N; ++j)\n      X[j] = 0;\n    for (int j=0; j<N; ++j)\n    {\n      real t1 = B[j];\n      real t2 = 0;\n      X[j] += t1 * A[j][j];\n      for (int i=j+1; i<N; ++i) {\n        X[i] += t1 * A[j][i];\n        t2 += A[j][i] * B[i];\n      }\n      X[j] += t2;\n    }\n  }\n  \n  static inline void syr2(gene_matrix & A, gene_vector & B, gene_vector & X, int N)\n  {\n    for (int j=0; j<N; ++j)\n    {\n      for (int i=j; i<N; ++i)\n        A[j][i] += B[i]*X[j] + B[j]*X[i];\n    }\n  }\n\n  static inline void ger(gene_matrix & A, gene_vector & X, gene_vector & Y, int N)\n  {\n    for (int j=0; j<N; ++j)\n    {\n      for (int i=j; i<N; ++i)\n        A[j][i] += X[i]*Y[j];\n    }\n  }\n\n  static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N)\n  {\n    real somme;\n    for (int i=0;i<N;i++){\n      somme = 0.0;\n      for (int j=0;j<N;j++)\n        somme += A[i][j]*B[j];\n      X[i] = somme;\n    }\n  }\n\n  static inline void axpy(real coef, const gene_vector & X, gene_vector & Y, int N){\n    for (int i=0;i<N;i++)\n      Y[i]+=coef*X[i];\n  }\n\n  static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int N){\n    for (int i=0;i<N;i++)\n      Y[i] = a*X[i] + b*Y[i];\n  }\n\n  static inline void trisolve_lower(const gene_matrix & L, const gene_vector & B, gene_vector & X, int N){\n    copy_vector(B,X,N);\n    for(int i=0; i<N; ++i)\n    {\n      X[i] /= L[i][i];\n      real tmp = X[i];\n      for (int j=i+1; j<N; ++j)\n        X[j] -= tmp * L[i][j];\n    }\n  }\n\n  static inline real norm_diff(const stl_vector & A, const stl_vector & B)\n  {\n    int N=A.size();\n    real somme=0.0;\n    real somme2=0.0;\n\n    for (int i=0;i<N;i++){\n      real diff=A[i]-B[i];\n      somme+=diff*diff;\n      somme2+=A[i]*A[i];\n    }\n    return somme/somme2;\n  }\n\n  static inline real norm_diff(const stl_matrix & A, const stl_matrix & B)\n  {\n    int N=A[0].size();\n    real somme=0.0;\n    real somme2=0.0;\n\n    for (int i=0;i<N;i++){\n      for (int j=0;j<N;j++){\n        real diff=A[i][j] - B[i][j];\n        somme += diff*diff;\n        somme2 += A[i][j]*A[i][j];\n      }\n    }\n\n    return somme/somme2;\n  }\n\n  static inline void display_vector(const stl_vector & A)\n  {\n    int N=A.size();\n    for (int i=0;i<N;i++){\n      INFOS(\"A[\"<<i<<\"]=\"<<A[i]<<endl);\n    }\n  }\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/STL/main.cpp",
    "content": "//=====================================================\n// File   :  main.cpp\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:23 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_axpy<STL_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_axpby<STL_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_matrix_vector_product<STL_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_atv_product<STL_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_symv<STL_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_syr2<STL_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_matrix_matrix_product<STL_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_ata_product<STL_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_aat_product<STL_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/blaze/CMakeLists.txt",
    "content": "\nfind_package(BLAZE)\nfind_package(Boost COMPONENTS system)\nif (BLAZE_FOUND AND Boost_FOUND)\n  include_directories(${BLAZE_INCLUDE_DIR} ${Boost_INCLUDE_DIRS})\n  btl_add_bench(btl_blaze main.cpp)\n  # Note: The newest blaze version requires C++14.\n  # Ideally, we should set this depending on the version of Blaze we found\n  set_property(TARGET btl_blaze PROPERTY CXX_STANDARD 14)\n  if(BUILD_btl_blaze)\n    target_link_libraries(btl_blaze ${Boost_LIBRARIES})\n  endif()\nendif ()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/blaze/blaze_interface.hh",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef BLAZE_INTERFACE_HH\n#define BLAZE_INTERFACE_HH\n\n#include <blaze/Math.h>\n#include <blaze/Blaze.h>\n#include <Eigen/Core>\n// using namespace blaze;\n\n#include <vector>\n\ntemplate<class real>\nclass blaze_interface {\n\npublic :\n\n  typedef real real_type ;\n\n  typedef std::vector<real>        stl_vector;\n  typedef std::vector<stl_vector > stl_matrix;\n\n  typedef blaze::DynamicMatrix<real,blaze::columnMajor>  gene_matrix;\n  typedef blaze::DynamicVector<real>  gene_vector;\n\n  static inline std::string name() { return \"blaze\"; }\n\n  static void free_matrix(gene_matrix & A, int N){\n    return ;\n  }\n\n  static void free_vector(gene_vector & B){\n    return ;\n  }\n\n  static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    A.resize(A_stl[0].size(), A_stl.size());\n\n    for (int j=0; j<A_stl.size() ; j++){\n      for (int i=0; i<A_stl[j].size() ; i++){\n        A(i,j) = A_stl[j][i];\n      }\n    }\n  }\n\n  static inline void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    B.resize(B_stl.size());\n    for (int i=0; i<B_stl.size() ; i++){\n      B[i] = B_stl[i];\n    }\n  }\n\n  static inline void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    for (int i=0; i<B_stl.size() ; i++){\n      B_stl[i] = B[i];\n    }\n  }\n\n  static inline void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int N=A_stl.size();\n    for (int j=0;j<N;j++){\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++){\n        A_stl[j][i] = A(i,j);\n      }\n    }\n  }\n\n  static EIGEN_DONT_INLINE void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N){\n    X = (A*B);\n  }\n\n  static EIGEN_DONT_INLINE void transposed_matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N){\n    X = (trans(A)*trans(B));\n  }\n\n  static EIGEN_DONT_INLINE void ata_product(const gene_matrix & A, gene_matrix & X, int N){\n    X = (trans(A)*A);\n  }\n\n  static EIGEN_DONT_INLINE void aat_product(const gene_matrix & A, gene_matrix & X, int N){\n    X = (A*trans(A));\n  }\n\n  static EIGEN_DONT_INLINE void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X = (A*B);\n  }\n\n  static EIGEN_DONT_INLINE void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X = (trans(A)*B);\n  }\n\n  static EIGEN_DONT_INLINE void axpy(const real coef, const gene_vector & X, gene_vector & Y, int N){\n    Y += coef * X;\n  }\n\n  static EIGEN_DONT_INLINE void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int N){\n    Y = a*X + b*Y;\n  }\n\n//   static inline void cholesky(const gene_matrix & X, gene_matrix & C, int N){\n//     C = X;\n//     recursive_cholesky(C);\n//   }\n\n//   static inline void lu_decomp(const gene_matrix & X, gene_matrix & R, int N){\n//     R = X;\n//     std::vector<int> ipvt(N);\n//     lu_factor(R, ipvt);\n//   }\n\n//   static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector & X, int N){\n//     X = lower_trisolve(L, B);\n//   }\n\n  static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){\n    cible = source;\n  }\n\n  static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){\n    cible = source;\n  }\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/blaze/main.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"blaze_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n\n  bench<Action_axpy<blaze_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_axpby<blaze_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n\n  bench<Action_matrix_vector_product<blaze_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_atv_product<blaze_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_matrix_matrix_product<blaze_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_ata_product<blaze_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_aat_product<blaze_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/blitz/CMakeLists.txt",
    "content": "\nfind_package(Blitz)\n\nif (BLITZ_FOUND)\n  include_directories(${BLITZ_INCLUDES})\n\n  btl_add_bench(btl_blitz btl_blitz.cpp)\n  if (BUILD_btl_blitz)\n    target_link_libraries(btl_blitz ${BLITZ_LIBRARIES})\n  endif ()\n\n  btl_add_bench(btl_tiny_blitz btl_tiny_blitz.cpp OFF)\n  if (BUILD_btl_tiny_blitz)\n    target_link_libraries(btl_tiny_blitz ${BLITZ_LIBRARIES})\n  endif ()\n\nendif ()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/blitz/blitz_LU_solve_interface.hh",
    "content": "//=====================================================\n// File   :  blitz_LU_solve_interface.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  lun sep 30 14:23:31 CEST 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef BLITZ_LU_SOLVE_INTERFACE_HH\n#define BLITZ_LU_SOLVE_INTERFACE_HH\n\n#include \"blitz/array.h\"\n#include <vector>\n\nBZ_USING_NAMESPACE(blitz)\n\ntemplate<class real>\nclass blitz_LU_solve_interface : public blitz_interface<real>\n{\n\npublic :\n\n  typedef typename blitz_interface<real>::gene_matrix gene_matrix;\n  typedef typename blitz_interface<real>::gene_vector gene_vector;\n\n  typedef blitz::Array<int,1> Pivot_Vector;\n\n  inline static void new_Pivot_Vector(Pivot_Vector & pivot,int N)\n  {\n\n    pivot.resize(N);\n\n  }\n\n  inline static void free_Pivot_Vector(Pivot_Vector & pivot)\n  {\n    \n    return;\n\n  }\n\n\n  static inline real matrix_vector_product_sliced(const gene_matrix & A, gene_vector B, int row, int col_start, int col_end)\n  {\n    \n    real somme=0.;\n    \n    for (int j=col_start ; j<col_end+1 ; j++){\n\t\n\tsomme+=A(row,j)*B(j);\n\t\n    }\n\n    return somme;\n\n  }\n\n\n\n\n  static inline real matrix_matrix_product_sliced(gene_matrix & A, int row, int col_start, int col_end, gene_matrix & B, int row_shift, int col )\n  {\n    \n    real somme=0.;\n    \n    for (int j=col_start ; j<col_end+1 ; j++){\n\t\n\tsomme+=A(row,j)*B(j+row_shift,col);\n\t\n    }\n\n    return somme;\n\n  }\n\n  inline static void LU_factor(gene_matrix & LU, Pivot_Vector & pivot, int N)\n  {\n\n    ASSERT( LU.rows()==LU.cols() ) ;\n    int index_max = 0 ;\n    real big = 0. ;\n    real theSum = 0. ;\n    real dum = 0. ;\n    // Get the implicit scaling information :\n    gene_vector ImplicitScaling( N ) ;\n    for( int i=0; i<N; i++ ) {\n      big = 0. ;\n      for( int j=0; j<N; j++ ) {\n\tif( abs( LU( i, j ) )>=big ) big = abs( LU( i, j ) ) ;\n      }\n      if( big==0. ) {\n\tINFOS( \"blitz_LU_factor::Singular matrix\" ) ;\n\texit( 0 ) ;\n      }\n      ImplicitScaling( i ) = 1./big ;\n    }\n    // Loop over columns of Crout's method :\n    for( int j=0; j<N; j++ ) {\n      for( int i=0; i<j; i++ ) {\n\ttheSum = LU( i, j ) ;\n\ttheSum -= matrix_matrix_product_sliced(LU, i, 0, i-1, LU, 0, j) ;\n\t//\ttheSum -= sum( LU( i, Range( fromStart, i-1 ) )*LU( Range( fromStart, i-1 ), j ) ) ;\n\tLU( i, j ) = theSum ;\n      }\n      \n      // Search for the largest pivot element :\n      big = 0. ;\n      for( int i=j; i<N; i++ ) {\n\ttheSum = LU( i, j ) ;\n\ttheSum -= matrix_matrix_product_sliced(LU, i, 0, j-1, LU, 0, j) ;\n\t//\ttheSum -= sum( LU( i, Range( fromStart, j-1 ) )*LU( Range( fromStart, j-1 ), j ) ) ;\n\tLU( i, j ) = theSum ;\n\tif( (ImplicitScaling( i )*abs( theSum ))>=big ) {\n\t  dum = ImplicitScaling( i )*abs( theSum ) ;\n\t  big = dum ;\n\t  index_max = i ;\n\t}\n      }\n      // Interchanging rows and the scale factor :\n      if( j!=index_max ) {\n\tfor( int k=0; k<N; k++ ) {\n\t  dum = LU( index_max, k ) ;\n\t  LU( index_max, k ) = LU( j, k ) ;\n\t  LU( j, k ) = dum ;\n\t}\n\tImplicitScaling( index_max ) = ImplicitScaling( j ) ;\n      }\n      pivot( j ) = index_max ;\n      if ( LU( j, j )==0. ) LU( j, j ) = 1.e-20 ;\n      // Divide by the pivot element :\n      if( j<N ) {\n\tdum = 1./LU( j, j ) ;\n\tfor( int i=j+1; i<N; i++ ) LU( i, j ) *= dum ;\n      }\n    }\n\n  }\n\n  inline static void LU_solve(const gene_matrix & LU, const Pivot_Vector pivot, gene_vector &B, gene_vector X, int N)\n  {\n\n    // Pour conserver le meme header, on travaille sur X, copie du second-membre B\n    X = B.copy() ;\n    ASSERT( LU.rows()==LU.cols() ) ;\n    firstIndex indI ;\n    // Forward substitution :\n    int ii = 0 ;\n    real theSum = 0. ;\n    for( int i=0; i<N; i++ ) {\n      int ip = pivot( i ) ;\n      theSum = X( ip ) ;\n      //      theSum = B( ip ) ;\n      X( ip ) = X( i ) ;\n      //      B( ip ) = B( i ) ;\n      if( ii ) {\n\ttheSum -= matrix_vector_product_sliced(LU, X, i, ii-1, i-1) ;\n\t//\ttheSum -= sum( LU( i, Range( ii-1, i-1 ) )*X( Range( ii-1, i-1 ) ) ) ;\n\t//\ttheSum -= sum( LU( i, Range( ii-1, i-1 ) )*B( Range( ii-1, i-1 ) ) ) ;\n      } else if( theSum ) {\n\tii = i+1 ;\n      }\n      X( i ) = theSum ;\n      //      B( i ) = theSum ;\n    }\n    // Backsubstitution :\n    for( int i=N-1; i>=0; i-- ) {\n      theSum = X( i ) ;\n      //      theSum = B( i ) ;\n      theSum -= matrix_vector_product_sliced(LU, X, i, i+1, N) ;\n      //      theSum -= sum( LU( i, Range( i+1, toEnd ) )*X( Range( i+1, toEnd ) ) ) ;\n      //      theSum -= sum( LU( i, Range( i+1, toEnd ) )*B( Range( i+1, toEnd ) ) ) ;\n      // Store a component of the solution vector :\n      X( i ) = theSum/LU( i, i ) ;\n      //      B( i ) = theSum/LU( i, i ) ;\n    }\n\n  }\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/blitz/blitz_interface.hh",
    "content": "//=====================================================\n// File   :  blitz_interface.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:30 CEST 2002\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef BLITZ_INTERFACE_HH\n#define BLITZ_INTERFACE_HH\n\n#include <blitz/blitz.h>\n#include <blitz/array.h>\n#include <blitz/vector-et.h>\n#include <blitz/vecwhere.h>\n#include <blitz/matrix.h>\n#include <vector>\n\nBZ_USING_NAMESPACE(blitz)\n\ntemplate<class real>\nclass blitz_interface{\n\npublic :\n\n  typedef real real_type ;\n\n  typedef std::vector<real>  stl_vector;\n  typedef std::vector<stl_vector > stl_matrix;\n\n  typedef blitz::Array<real, 2>  gene_matrix;\n  typedef blitz::Array<real, 1>  gene_vector;\n//   typedef blitz::Matrix<real, blitz::ColumnMajor>  gene_matrix;\n//   typedef blitz::Vector<real> gene_vector;\n\n  static inline std::string name() { return \"blitz\"; }\n\n  static void free_matrix(gene_matrix & A, int N){}\n\n  static void free_vector(gene_vector & B){}\n\n  static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    A.resize(A_stl[0].size(),A_stl.size());\n    for (int j=0; j<A_stl.size() ; j++){\n      for (int i=0; i<A_stl[j].size() ; i++){\n        A(i,j)=A_stl[j][i];\n      }\n    }\n  }\n\n  static inline void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    B.resize(B_stl.size());\n    for (int i=0; i<B_stl.size() ; i++){\n      B(i)=B_stl[i];\n    }\n  }\n\n  static inline void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    for (int i=0; i<B_stl.size() ; i++){\n      B_stl[i]=B(i);\n    }\n  }\n\n  static inline void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int N=A_stl.size();\n    for (int j=0;j<N;j++){\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++)\n        A_stl[j][i] = A(i,j);\n    }\n  }\n\n  static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N)\n  {\n    firstIndex i;\n    secondIndex j;\n    thirdIndex k;\n    X = sum(A(i,k) * B(k,j), k);\n  }\n\n  static inline void ata_product(const gene_matrix & A, gene_matrix & X, int N)\n  {\n    firstIndex i;\n    secondIndex j;\n    thirdIndex k;\n    X = sum(A(k,i) * A(k,j), k);\n  }\n\n  static inline void aat_product(const gene_matrix & A, gene_matrix & X, int N)\n  {\n    firstIndex i;\n    secondIndex j;\n    thirdIndex k;\n    X = sum(A(i,k) * A(j,k), k);\n  }\n\n  static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N)\n  {\n    firstIndex i;\n    secondIndex j;\n    X = sum(A(i,j)*B(j),j);\n  }\n\n  static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N)\n  {\n    firstIndex i;\n    secondIndex j;\n    X = sum(A(j,i) * B(j),j);\n  }\n\n  static inline void axpy(const real coef, const gene_vector & X, gene_vector & Y, int N)\n  {\n    firstIndex i;\n    Y = Y(i) + coef * X(i);\n    //Y += coef * X;\n  }\n\n  static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){\n    cible = source;\n    //cible.template operator=<gene_matrix>(source);\n//     for (int i=0;i<N;i++){\n//       for (int j=0;j<N;j++){\n//         cible(i,j)=source(i,j);\n//       }\n//     }\n  }\n\n  static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){\n    //cible.template operator=<gene_vector>(source);\n    cible = source;\n  }\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/blitz/btl_blitz.cpp",
    "content": "//=====================================================\n// File   :  main.cpp\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:30 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"blitz_interface.hh\"\n#include \"blitz_LU_solve_interface.hh\"\n#include \"bench.hh\"\n#include \"action_matrix_vector_product.hh\"\n#include \"action_matrix_matrix_product.hh\"\n#include \"action_axpy.hh\"\n#include \"action_lu_solve.hh\"\n#include \"action_ata_product.hh\"\n#include \"action_aat_product.hh\"\n#include \"action_atv_product.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n\n  bench<Action_matrix_vector_product<blitz_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_atv_product<blitz_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n\n  bench<Action_matrix_matrix_product<blitz_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_ata_product<blitz_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_aat_product<blitz_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  bench<Action_axpy<blitz_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n\n  //bench<Action_lu_solve<blitz_LU_solve_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/blitz/btl_tiny_blitz.cpp",
    "content": "//=====================================================\n// File   :  main.cpp\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:30 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"tiny_blitz_interface.hh\"\n#include \"static/bench_static.hh\"\n#include \"action_matrix_vector_product.hh\"\n#include \"action_matrix_matrix_product.hh\"\n#include \"action_axpy.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench_static<Action_axpy,tiny_blitz_interface>();\n  bench_static<Action_matrix_matrix_product,tiny_blitz_interface>();\n  bench_static<Action_matrix_vector_product,tiny_blitz_interface>();\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/blitz/tiny_blitz_interface.hh",
    "content": "//=====================================================\n// File   :  tiny_blitz_interface.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:30 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef TINY_BLITZ_INTERFACE_HH\n#define TINY_BLITZ_INTERFACE_HH\n\n#include \"blitz/array.h\"\n#include \"blitz/tiny.h\"\n#include \"blitz/tinymat.h\"\n#include \"blitz/tinyvec.h\"\n#include <blitz/tinyvec-et.h>\n\n#include <vector>\n\nBZ_USING_NAMESPACE(blitz)\n\ntemplate<class real, int SIZE>\nclass tiny_blitz_interface\n{\n\npublic :\n\n  typedef real real_type ;\n\n  typedef std::vector<real>  stl_vector;\n  typedef std::vector<stl_vector > stl_matrix;\n\n  typedef TinyVector<real,SIZE> gene_vector;\n  typedef TinyMatrix<real,SIZE,SIZE> gene_matrix;\n\n  static inline std::string name() { return \"tiny_blitz\"; }\n\n  static void free_matrix(gene_matrix & A, int N){}\n\n  static void free_vector(gene_vector & B){}\n\n  static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    for (int j=0; j<A_stl.size() ; j++)\n      for (int i=0; i<A_stl[j].size() ; i++)\n        A(i,j)=A_stl[j][i];\n  }\n\n  static inline void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    for (int i=0; i<B_stl.size() ; i++)\n      B(i) = B_stl[i];\n  }\n\n  static inline void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    for (int i=0; i<B_stl.size() ; i++)\n      B_stl[i] = B(i);\n  }\n\n  static inline void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int N = A_stl.size();\n    for (int j=0;j<N;j++)\n    {\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++)\n        A_stl[j][i] = A(i,j);\n    }\n  }\n\n  static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){\n    for (int j=0;j<N;j++)\n      for (int i=0;i<N;i++)\n        cible(i,j) = source(i,j);\n  }\n\n  static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){\n    for (int i=0;i<N;i++){\n      cible(i) = source(i);\n    }\n  }\n\n  static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N){\n    X = product(A,B);\n  }\n\n  static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X = product(A,B);\n  }\n\n  static inline void axpy(const real coef, const gene_vector & X, gene_vector & Y, int N){\n    Y += coef * X;\n  }\n\n};\n\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/eigen2/CMakeLists.txt",
    "content": "\nfind_package(Eigen2)\n\nif(EIGEN2_FOUND)\n\n  include_directories(BEFORE ${EIGEN2_INCLUDE_DIR})\n  btl_add_bench(btl_eigen2_linear main_linear.cpp)\n  btl_add_bench(btl_eigen2_vecmat main_vecmat.cpp)\n  btl_add_bench(btl_eigen2_matmat main_matmat.cpp)\n  btl_add_bench(btl_eigen2_adv main_adv.cpp      )\n\n  btl_add_target_property(btl_eigen2_linear COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=eigen2\")\n  btl_add_target_property(btl_eigen2_vecmat COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=eigen2\")\n  btl_add_target_property(btl_eigen2_matmat COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=eigen2\")\n  btl_add_target_property(btl_eigen2_adv    COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=eigen2\")\n\n  btl_add_bench(btl_tiny_eigen2 btl_tiny_eigen2.cpp OFF)\n\nendif() # EIGEN2_FOUND\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/eigen2/btl_tiny_eigen2.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"eigen3_interface.hh\"\n#include \"static/bench_static.hh\"\n#include \"action_matrix_vector_product.hh\"\n#include \"action_matrix_matrix_product.hh\"\n#include \"action_axpy.hh\"\n#include \"action_lu_solve.hh\"\n#include \"action_ata_product.hh\"\n#include \"action_aat_product.hh\"\n#include \"action_atv_product.hh\"\n#include \"action_cholesky.hh\"\n#include \"action_trisolve.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n\n  bench_static<Action_axpy,eigen2_interface>();\n  bench_static<Action_matrix_matrix_product,eigen2_interface>();\n  bench_static<Action_matrix_vector_product,eigen2_interface>();\n  bench_static<Action_atv_product,eigen2_interface>();\n  bench_static<Action_cholesky,eigen2_interface>();\n  bench_static<Action_trisolve,eigen2_interface>();\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/eigen2/eigen2_interface.hh",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <g.gael@free.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef EIGEN2_INTERFACE_HH\n#define EIGEN2_INTERFACE_HH\n// #include <cblas.h>\n#include <Eigen/Core>\n#include <Eigen/Cholesky>\n#include <Eigen/LU>\n#include <Eigen/QR>\n#include <vector>\n#include \"btl.hh\"\n\nusing namespace Eigen;\n\ntemplate<class real, int SIZE=Dynamic>\nclass eigen2_interface\n{\n\npublic :\n\n  enum {IsFixedSize = (SIZE!=Dynamic)};\n\n  typedef real real_type;\n\n  typedef std::vector<real> stl_vector;\n  typedef std::vector<stl_vector> stl_matrix;\n\n  typedef Eigen::Matrix<real,SIZE,SIZE> gene_matrix;\n  typedef Eigen::Matrix<real,SIZE,1> gene_vector;\n\n  static inline std::string name( void )\n  {\n    #if defined(EIGEN_VECTORIZE_SSE)\n    if (SIZE==Dynamic) return \"eigen2\"; else return \"tiny_eigen2\";\n    #elif defined(EIGEN_VECTORIZE_ALTIVEC) || defined(EIGEN_VECTORIZE_VSX)\n    if (SIZE==Dynamic) return \"eigen2\"; else return \"tiny_eigen2\";\n    #else\n    if (SIZE==Dynamic) return \"eigen2_novec\"; else return \"tiny_eigen2_novec\";\n    #endif\n  }\n\n  static void free_matrix(gene_matrix & A, int N) {}\n\n  static void free_vector(gene_vector & B) {}\n\n  static BTL_DONT_INLINE void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    A.resize(A_stl[0].size(), A_stl.size());\n\n    for (int j=0; j<A_stl.size() ; j++){\n      for (int i=0; i<A_stl[j].size() ; i++){\n        A.coeffRef(i,j) = A_stl[j][i];\n      }\n    }\n  }\n\n  static BTL_DONT_INLINE  void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    B.resize(B_stl.size(),1);\n\n    for (int i=0; i<B_stl.size() ; i++){\n      B.coeffRef(i) = B_stl[i];\n    }\n  }\n\n  static BTL_DONT_INLINE  void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    for (int i=0; i<B_stl.size() ; i++){\n      B_stl[i] = B.coeff(i);\n    }\n  }\n\n  static BTL_DONT_INLINE  void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int N=A_stl.size();\n\n    for (int j=0;j<N;j++){\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++){\n        A_stl[j][i] = A.coeff(i,j);\n      }\n    }\n  }\n\n  static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N){\n    X = (A*B).lazy();\n  }\n\n  static inline void transposed_matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N){\n    X = (A.transpose()*B.transpose()).lazy();\n  }\n\n  static inline void ata_product(const gene_matrix & A, gene_matrix & X, int N){\n    X = (A.transpose()*A).lazy();\n  }\n\n  static inline void aat_product(const gene_matrix & A, gene_matrix & X, int N){\n    X = (A*A.transpose()).lazy();\n  }\n\n  static inline void matrix_vector_product(const gene_matrix & A, const gene_vector & B, gene_vector & X, int N){\n    X = (A*B)/*.lazy()*/;\n  }\n\n  static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X = (A.transpose()*B)/*.lazy()*/;\n  }\n\n  static inline void axpy(real coef, const gene_vector & X, gene_vector & Y, int N){\n    Y += coef * X;\n  }\n\n  static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int N){\n    Y = a*X + b*Y;\n  }\n\n  static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){\n    cible = source;\n  }\n\n  static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){\n    cible = source;\n  }\n\n  static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector& X, int N){\n    X = L.template marked<LowerTriangular>().solveTriangular(B);\n  }\n\n  static inline void trisolve_lower_matrix(const gene_matrix & L, const gene_matrix& B, gene_matrix& X, int N){\n    X = L.template marked<LowerTriangular>().solveTriangular(B);\n  }\n\n  static inline void cholesky(const gene_matrix & X, gene_matrix & C, int N){\n    C = X.llt().matrixL();\n//     C = X;\n//     Cholesky<gene_matrix>::computeInPlace(C);\n//     Cholesky<gene_matrix>::computeInPlaceBlock(C);\n  }\n\n  static inline void lu_decomp(const gene_matrix & X, gene_matrix & C, int N){\n    C = X.lu().matrixLU();\n//     C = X.inverse();\n  }\n\n  static inline void tridiagonalization(const gene_matrix & X, gene_matrix & C, int N){\n    C = Tridiagonalization<gene_matrix>(X).packedMatrix();\n  }\n\n  static inline void hessenberg(const gene_matrix & X, gene_matrix & C, int N){\n    C = HessenbergDecomposition<gene_matrix>(X).packedMatrix();\n  }\n\n\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/eigen2/main_adv.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"eigen2_interface.hh\"\n#include \"bench.hh\"\n#include \"action_trisolve.hh\"\n#include \"action_trisolve_matrix.hh\"\n#include \"action_cholesky.hh\"\n#include \"action_hessenberg.hh\"\n#include \"action_lu_decomp.hh\"\n// #include \"action_partial_lu.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_trisolve<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_trisolve_matrix<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_cholesky<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_lu_decomp<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_partial_lu<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  bench<Action_hessenberg<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_tridiagonalization<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/eigen2/main_linear.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"eigen2_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n\n  bench<Action_axpy<eigen2_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_axpby<eigen2_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  \n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/eigen2/main_matmat.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"eigen2_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_matrix_matrix_product<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_ata_product<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_aat_product<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_trmm<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/eigen2/main_vecmat.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"eigen2_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_matrix_vector_product<eigen2_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_atv_product<eigen2_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n//   bench<Action_symv<eigen2_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n//   bench<Action_syr2<eigen2_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n//   bench<Action_ger<eigen2_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/eigen3/CMakeLists.txt",
    "content": "\n\nif((NOT EIGEN3_INCLUDE_DIR) AND Eigen_SOURCE_DIR)\n  # unless EIGEN3_INCLUDE_DIR is defined, let's use current Eigen version\n  set(EIGEN3_INCLUDE_DIR ${Eigen_SOURCE_DIR})\n  set(EIGEN3_FOUND TRUE)\nelse()\n  find_package(Eigen3)\nendif()\n\nif (EIGEN3_FOUND)\n\n  include_directories(${EIGEN3_INCLUDE_DIR})\n  btl_add_bench(btl_eigen3_linear main_linear.cpp)\n  btl_add_bench(btl_eigen3_vecmat main_vecmat.cpp)\n  btl_add_bench(btl_eigen3_matmat main_matmat.cpp)\n  btl_add_bench(btl_eigen3_adv main_adv.cpp      )\n\n  btl_add_target_property(btl_eigen3_linear COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=eigen3\")\n  btl_add_target_property(btl_eigen3_vecmat COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=eigen3\")\n  btl_add_target_property(btl_eigen3_matmat COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=eigen3\")\n  btl_add_target_property(btl_eigen3_adv    COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=eigen3\")\n\n  option(BTL_BENCH_NOGCCVEC \"also bench Eigen explicit vec without GCC's auto vec\" OFF)\n  if(CMAKE_COMPILER_IS_GNUCXX AND BTL_BENCH_NOGCCVEC)\n    btl_add_bench(btl_eigen3_nogccvec_linear main_linear.cpp)\n    btl_add_bench(btl_eigen3_nogccvec_vecmat main_vecmat.cpp)\n    btl_add_bench(btl_eigen3_nogccvec_matmat main_matmat.cpp)\n    btl_add_bench(btl_eigen3_nogccvec_adv    main_adv.cpp   )\n\n    btl_add_target_property(btl_eigen3_nogccvec_linear COMPILE_FLAGS \"-fno-exceptions -fno-tree-vectorize -DBTL_PREFIX=eigen3_nogccvec\")\n    btl_add_target_property(btl_eigen3_nogccvec_vecmat COMPILE_FLAGS \"-fno-exceptions -fno-tree-vectorize -DBTL_PREFIX=eigen3_nogccvec\")\n    btl_add_target_property(btl_eigen3_nogccvec_matmat COMPILE_FLAGS \"-fno-exceptions -fno-tree-vectorize -DBTL_PREFIX=eigen3_nogccvec\")\n    btl_add_target_property(btl_eigen3_nogccvec_adv    COMPILE_FLAGS \"-fno-exceptions -fno-tree-vectorize -DBTL_PREFIX=eigen3_nogccvec\")\n  endif()\n\n\n  if(NOT BTL_NOVEC)\n    btl_add_bench(btl_eigen3_novec_linear main_linear.cpp OFF)\n    btl_add_bench(btl_eigen3_novec_vecmat main_vecmat.cpp OFF)\n    btl_add_bench(btl_eigen3_novec_matmat main_matmat.cpp OFF)\n    btl_add_bench(btl_eigen3_novec_adv main_adv.cpp       OFF)\n    btl_add_target_property(btl_eigen3_novec_linear COMPILE_FLAGS \"-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=eigen3_novec\")\n    btl_add_target_property(btl_eigen3_novec_vecmat COMPILE_FLAGS \"-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=eigen3_novec\")\n    btl_add_target_property(btl_eigen3_novec_matmat COMPILE_FLAGS \"-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=eigen3_novec\")\n    btl_add_target_property(btl_eigen3_novec_adv    COMPILE_FLAGS \"-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=eigen3_novec\")\n\n#     if(BUILD_btl_eigen3_adv)\n#       target_link_libraries(btl_eigen3_adv ${MKL_LIBRARIES})\n#     endif()\n\n  endif()\n\n  btl_add_bench(btl_tiny_eigen3 btl_tiny_eigen3.cpp OFF)\n\n  if(NOT BTL_NOVEC)\n    btl_add_bench(btl_tiny_eigen3_novec btl_tiny_eigen3.cpp OFF)\n    btl_add_target_property(btl_tiny_eigen3_novec    COMPILE_FLAGS \"-DBTL_PREFIX=eigen3_tiny\")\n\n    if(BUILD_btl_tiny_eigen3_novec)\n      btl_add_target_property(btl_tiny_eigen3_novec    COMPILE_FLAGS \"-DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=eigen3_tiny_novec\")\n    endif()\n  endif()\n\nendif ()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/eigen3/btl_tiny_eigen3.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"eigen3_interface.hh\"\n#include \"static/bench_static.hh\"\n#include \"action_matrix_vector_product.hh\"\n#include \"action_matrix_matrix_product.hh\"\n#include \"action_axpy.hh\"\n#include \"action_lu_solve.hh\"\n#include \"action_ata_product.hh\"\n#include \"action_aat_product.hh\"\n#include \"action_atv_product.hh\"\n#include \"action_cholesky.hh\"\n#include \"action_trisolve.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n\n  bench_static<Action_axpy,eigen2_interface>();\n  bench_static<Action_matrix_matrix_product,eigen2_interface>();\n  bench_static<Action_matrix_vector_product,eigen2_interface>();\n  bench_static<Action_atv_product,eigen2_interface>();\n  bench_static<Action_cholesky,eigen2_interface>();\n  bench_static<Action_trisolve,eigen2_interface>();\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/eigen3/eigen3_interface.hh",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef EIGEN3_INTERFACE_HH\n#define EIGEN3_INTERFACE_HH\n\n#include <Eigen/Eigen>\n#include <vector>\n#include \"btl.hh\"\n\nusing namespace Eigen;\n\ntemplate<class real, int SIZE=Dynamic>\nclass eigen3_interface\n{\n\npublic :\n\n  enum {IsFixedSize = (SIZE!=Dynamic)};\n\n  typedef real real_type;\n\n  typedef std::vector<real> stl_vector;\n  typedef std::vector<stl_vector> stl_matrix;\n\n  typedef Eigen::Matrix<real,SIZE,SIZE> gene_matrix;\n  typedef Eigen::Matrix<real,SIZE,1> gene_vector;\n\n  static inline std::string name( void )\n  {\n    return EIGEN_MAKESTRING(BTL_PREFIX);\n  }\n\n  static void free_matrix(gene_matrix & /*A*/, int /*N*/) {}\n\n  static void free_vector(gene_vector & /*B*/) {}\n\n  static BTL_DONT_INLINE void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    A.resize(A_stl[0].size(), A_stl.size());\n\n    for (unsigned int j=0; j<A_stl.size() ; j++){\n      for (unsigned int i=0; i<A_stl[j].size() ; i++){\n        A.coeffRef(i,j) = A_stl[j][i];\n      }\n    }\n  }\n\n  static BTL_DONT_INLINE  void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    B.resize(B_stl.size(),1);\n\n    for (unsigned int i=0; i<B_stl.size() ; i++){\n      B.coeffRef(i) = B_stl[i];\n    }\n  }\n\n  static BTL_DONT_INLINE  void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    for (unsigned int i=0; i<B_stl.size() ; i++){\n      B_stl[i] = B.coeff(i);\n    }\n  }\n\n  static BTL_DONT_INLINE  void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int  N=A_stl.size();\n\n    for (int j=0;j<N;j++){\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++){\n        A_stl[j][i] = A.coeff(i,j);\n      }\n    }\n  }\n\n  static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int  /*N*/){\n    X.noalias() = A*B;\n  }\n\n  static inline void transposed_matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int  /*N*/){\n    X.noalias() = A.transpose()*B.transpose();\n  }\n\n  static inline void ata_product(const gene_matrix & A, gene_matrix & X, int  /*N*/){\n    //X.noalias() = A.transpose()*A;\n    X.template triangularView<Lower>().setZero();\n    X.template selfadjointView<Lower>().rankUpdate(A.transpose());\n  }\n\n  static inline void aat_product(const gene_matrix & A, gene_matrix & X, int  /*N*/){\n    X.template triangularView<Lower>().setZero();\n    X.template selfadjointView<Lower>().rankUpdate(A);\n  }\n\n  static inline void matrix_vector_product(const gene_matrix & A, const gene_vector & B, gene_vector & X, int  /*N*/){\n    X.noalias() = A*B;\n  }\n\n  static inline void symv(const gene_matrix & A, const gene_vector & B, gene_vector & X, int  /*N*/){\n    X.noalias() = (A.template selfadjointView<Lower>() * B);\n//     internal::product_selfadjoint_vector<real,0,LowerTriangularBit,false,false>(N,A.data(),N, B.data(), 1, X.data(), 1);\n  }\n\n  template<typename Dest, typename Src> static void triassign(Dest& dst, const Src& src)\n  {\n    typedef typename Dest::Scalar Scalar;\n    typedef typename internal::packet_traits<Scalar>::type Packet;\n    const int PacketSize = sizeof(Packet)/sizeof(Scalar);\n    int size = dst.cols();\n    for(int j=0; j<size; j+=1)\n    {\n//       const int alignedEnd = alignedStart + ((innerSize-alignedStart) & ~packetAlignedMask);\n      Scalar* A0 = dst.data() + j*dst.stride();\n      int starti = j;\n      int alignedEnd = starti;\n      int alignedStart = (starti) + internal::first_aligned(&A0[starti], size-starti);\n      alignedEnd = alignedStart + ((size-alignedStart)/(2*PacketSize))*(PacketSize*2);\n\n      // do the non-vectorizable part of the assignment\n      for (int index = starti; index<alignedStart ; ++index)\n      {\n        if(Dest::Flags&RowMajorBit)\n          dst.copyCoeff(j, index, src);\n        else\n          dst.copyCoeff(index, j, src);\n      }\n\n      // do the vectorizable part of the assignment\n      for (int index = alignedStart; index<alignedEnd; index+=PacketSize)\n      {\n        if(Dest::Flags&RowMajorBit)\n          dst.template copyPacket<Src, Aligned, Unaligned>(j, index, src);\n        else\n          dst.template copyPacket<Src, Aligned, Unaligned>(index, j, src);\n      }\n\n      // do the non-vectorizable part of the assignment\n      for (int index = alignedEnd; index<size; ++index)\n      {\n        if(Dest::Flags&RowMajorBit)\n          dst.copyCoeff(j, index, src);\n        else\n          dst.copyCoeff(index, j, src);\n      }\n      //dst.col(j).tail(N-j) = src.col(j).tail(N-j);\n    }\n  }\n\n  static EIGEN_DONT_INLINE void syr2(gene_matrix & A,  gene_vector & X, gene_vector & Y, int  N){\n    // internal::product_selfadjoint_rank2_update<real,0,LowerTriangularBit>(N,A.data(),N, X.data(), 1, Y.data(), 1, -1);\n    for(int j=0; j<N; ++j)\n      A.col(j).tail(N-j) += X[j] * Y.tail(N-j) + Y[j] * X.tail(N-j);\n  }\n\n  static EIGEN_DONT_INLINE void ger(gene_matrix & A,  gene_vector & X, gene_vector & Y, int  N){\n    for(int j=0; j<N; ++j)\n      A.col(j) += X * Y[j];\n  }\n\n  static EIGEN_DONT_INLINE void rot(gene_vector & A,  gene_vector & B, real c, real s, int  /*N*/){\n    internal::apply_rotation_in_the_plane(A, B, JacobiRotation<real>(c,s));\n  }\n\n  static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int  /*N*/){\n    X.noalias() = (A.transpose()*B);\n  }\n\n  static inline void axpy(real coef, const gene_vector & X, gene_vector & Y, int  /*N*/){\n    Y += coef * X;\n  }\n\n  static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int  /*N*/){\n    Y = a*X + b*Y;\n  }\n\n  static EIGEN_DONT_INLINE void copy_matrix(const gene_matrix & source, gene_matrix & cible, int  /*N*/){\n    cible = source;\n  }\n\n  static EIGEN_DONT_INLINE void copy_vector(const gene_vector & source, gene_vector & cible, int  /*N*/){\n    cible = source;\n  }\n\n  static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector& X, int  /*N*/){\n    X = L.template triangularView<Lower>().solve(B);\n  }\n\n  static inline void trisolve_lower_matrix(const gene_matrix & L, const gene_matrix& B, gene_matrix& X, int  /*N*/){\n    X = L.template triangularView<Upper>().solve(B);\n  }\n\n  static inline void trmm(const gene_matrix & L, const gene_matrix& B, gene_matrix& X, int  /*N*/){\n    X.noalias() = L.template triangularView<Lower>() * B;\n  }\n\n  static inline void cholesky(const gene_matrix & X, gene_matrix & C, int  /*N*/){\n    C = X;\n    internal::llt_inplace<real,Lower>::blocked(C);\n    //C = X.llt().matrixL();\n//     C = X;\n//     Cholesky<gene_matrix>::computeInPlace(C);\n//     Cholesky<gene_matrix>::computeInPlaceBlock(C);\n  }\n\n  static inline void lu_decomp(const gene_matrix & X, gene_matrix & C, int  /*N*/){\n    C = X.fullPivLu().matrixLU();\n  }\n\n  static inline void partial_lu_decomp(const gene_matrix & X, gene_matrix & C, int  N){\n    Matrix<DenseIndex,1,Dynamic> piv(N);\n    DenseIndex nb;\n    C = X;\n    internal::partial_lu_inplace(C,piv,nb);\n//     C = X.partialPivLu().matrixLU();\n  }\n\n  static inline void tridiagonalization(const gene_matrix & X, gene_matrix & C, int  N){\n    typename Tridiagonalization<gene_matrix>::CoeffVectorType aux(N-1);\n    C = X;\n    internal::tridiagonalization_inplace(C, aux);\n  }\n\n  static inline void hessenberg(const gene_matrix & X, gene_matrix & C, int  /*N*/){\n    C = HessenbergDecomposition<gene_matrix>(X).packedMatrix();\n  }\n\n\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/eigen3/main_adv.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"eigen3_interface.hh\"\n#include \"bench.hh\"\n#include \"action_trisolve.hh\"\n#include \"action_trisolve_matrix.hh\"\n#include \"action_cholesky.hh\"\n#include \"action_hessenberg.hh\"\n#include \"action_lu_decomp.hh\"\n#include \"action_partial_lu.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_trisolve<eigen3_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n  bench<Action_trisolve_matrix<eigen3_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n  bench<Action_cholesky<eigen3_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n//   bench<Action_lu_decomp<eigen3_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n  bench<Action_partial_lu<eigen3_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n\n//   bench<Action_hessenberg<eigen3_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n  bench<Action_tridiagonalization<eigen3_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/eigen3/main_linear.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"eigen3_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n\n  bench<Action_axpy<eigen3_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_axpby<eigen3_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_rot<eigen3_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  \n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/eigen3/main_matmat.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"eigen3_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_matrix_matrix_product<eigen3_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_ata_product<eigen3_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_aat_product<eigen3_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_trmm<eigen3_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/eigen3/main_vecmat.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"eigen3_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_matrix_vector_product<eigen3_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_atv_product<eigen3_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_symv<eigen3_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_syr2<eigen3_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_ger<eigen3_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/gmm/CMakeLists.txt",
    "content": "\nfind_package(GMM)\nif (GMM_FOUND)\n  include_directories(${GMM_INCLUDES})\n  btl_add_bench(btl_gmm main.cpp)\nendif ()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/gmm/gmm_LU_solve_interface.hh",
    "content": "//=====================================================\n// File   :  blitz_LU_solve_interface.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  lun sep 30 14:23:31 CEST 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef BLITZ_LU_SOLVE_INTERFACE_HH\n#define BLITZ_LU_SOLVE_INTERFACE_HH\n\n#include \"blitz/array.h\"\n#include <vector>\n\nBZ_USING_NAMESPACE(blitz)\n\ntemplate<class real>\nclass blitz_LU_solve_interface : public blitz_interface<real>\n{\n\npublic :\n\n  typedef typename blitz_interface<real>::gene_matrix gene_matrix;\n  typedef typename blitz_interface<real>::gene_vector gene_vector;\n\n  typedef blitz::Array<int,1> Pivot_Vector;\n\n  inline static void new_Pivot_Vector(Pivot_Vector & pivot,int N)\n  {\n\n    pivot.resize(N);\n\n  }\n\n  inline static void free_Pivot_Vector(Pivot_Vector & pivot)\n  {\n    \n    return;\n\n  }\n\n\n  static inline real matrix_vector_product_sliced(const gene_matrix & A, gene_vector B, int row, int col_start, int col_end)\n  {\n    \n    real somme=0.;\n    \n    for (int j=col_start ; j<col_end+1 ; j++){\n\t\n\tsomme+=A(row,j)*B(j);\n\t\n    }\n\n    return somme;\n\n  }\n\n\n\n\n  static inline real matrix_matrix_product_sliced(gene_matrix & A, int row, int col_start, int col_end, gene_matrix & B, int row_shift, int col )\n  {\n    \n    real somme=0.;\n    \n    for (int j=col_start ; j<col_end+1 ; j++){\n\t\n\tsomme+=A(row,j)*B(j+row_shift,col);\n\t\n    }\n\n    return somme;\n\n  }\n\n  inline static void LU_factor(gene_matrix & LU, Pivot_Vector & pivot, int N)\n  {\n\n    ASSERT( LU.rows()==LU.cols() ) ;\n    int index_max = 0 ;\n    real big = 0. ;\n    real theSum = 0. ;\n    real dum = 0. ;\n    // Get the implicit scaling information :\n    gene_vector ImplicitScaling( N ) ;\n    for( int i=0; i<N; i++ ) {\n      big = 0. ;\n      for( int j=0; j<N; j++ ) {\n\tif( abs( LU( i, j ) )>=big ) big = abs( LU( i, j ) ) ;\n      }\n      if( big==0. ) {\n\tINFOS( \"blitz_LU_factor::Singular matrix\" ) ;\n\texit( 0 ) ;\n      }\n      ImplicitScaling( i ) = 1./big ;\n    }\n    // Loop over columns of Crout's method :\n    for( int j=0; j<N; j++ ) {\n      for( int i=0; i<j; i++ ) {\n\ttheSum = LU( i, j ) ;\n\ttheSum -= matrix_matrix_product_sliced(LU, i, 0, i-1, LU, 0, j) ;\n\t//\ttheSum -= sum( LU( i, Range( fromStart, i-1 ) )*LU( Range( fromStart, i-1 ), j ) ) ;\n\tLU( i, j ) = theSum ;\n      }\n      \n      // Search for the largest pivot element :\n      big = 0. ;\n      for( int i=j; i<N; i++ ) {\n\ttheSum = LU( i, j ) ;\n\ttheSum -= matrix_matrix_product_sliced(LU, i, 0, j-1, LU, 0, j) ;\n\t//\ttheSum -= sum( LU( i, Range( fromStart, j-1 ) )*LU( Range( fromStart, j-1 ), j ) ) ;\n\tLU( i, j ) = theSum ;\n\tif( (ImplicitScaling( i )*abs( theSum ))>=big ) {\n\t  dum = ImplicitScaling( i )*abs( theSum ) ;\n\t  big = dum ;\n\t  index_max = i ;\n\t}\n      }\n      // Interchanging rows and the scale factor :\n      if( j!=index_max ) {\n\tfor( int k=0; k<N; k++ ) {\n\t  dum = LU( index_max, k ) ;\n\t  LU( index_max, k ) = LU( j, k ) ;\n\t  LU( j, k ) = dum ;\n\t}\n\tImplicitScaling( index_max ) = ImplicitScaling( j ) ;\n      }\n      pivot( j ) = index_max ;\n      if ( LU( j, j )==0. ) LU( j, j ) = 1.e-20 ;\n      // Divide by the pivot element :\n      if( j<N ) {\n\tdum = 1./LU( j, j ) ;\n\tfor( int i=j+1; i<N; i++ ) LU( i, j ) *= dum ;\n      }\n    }\n\n  }\n\n  inline static void LU_solve(const gene_matrix & LU, const Pivot_Vector pivot, gene_vector &B, gene_vector X, int N)\n  {\n\n    // Pour conserver le meme header, on travaille sur X, copie du second-membre B\n    X = B.copy() ;\n    ASSERT( LU.rows()==LU.cols() ) ;\n    firstIndex indI ;\n    // Forward substitution :\n    int ii = 0 ;\n    real theSum = 0. ;\n    for( int i=0; i<N; i++ ) {\n      int ip = pivot( i ) ;\n      theSum = X( ip ) ;\n      //      theSum = B( ip ) ;\n      X( ip ) = X( i ) ;\n      //      B( ip ) = B( i ) ;\n      if( ii ) {\n\ttheSum -= matrix_vector_product_sliced(LU, X, i, ii-1, i-1) ;\n\t//\ttheSum -= sum( LU( i, Range( ii-1, i-1 ) )*X( Range( ii-1, i-1 ) ) ) ;\n\t//\ttheSum -= sum( LU( i, Range( ii-1, i-1 ) )*B( Range( ii-1, i-1 ) ) ) ;\n      } else if( theSum ) {\n\tii = i+1 ;\n      }\n      X( i ) = theSum ;\n      //      B( i ) = theSum ;\n    }\n    // Backsubstitution :\n    for( int i=N-1; i>=0; i-- ) {\n      theSum = X( i ) ;\n      //      theSum = B( i ) ;\n      theSum -= matrix_vector_product_sliced(LU, X, i, i+1, N) ;\n      //      theSum -= sum( LU( i, Range( i+1, toEnd ) )*X( Range( i+1, toEnd ) ) ) ;\n      //      theSum -= sum( LU( i, Range( i+1, toEnd ) )*B( Range( i+1, toEnd ) ) ) ;\n      // Store a component of the solution vector :\n      X( i ) = theSum/LU( i, i ) ;\n      //      B( i ) = theSum/LU( i, i ) ;\n    }\n\n  }\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/gmm/gmm_interface.hh",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef GMM_INTERFACE_HH\n#define GMM_INTERFACE_HH\n\n#include <gmm/gmm.h>\n#include <vector>\n\nusing namespace gmm;\n\ntemplate<class real>\nclass gmm_interface {\n\npublic :\n\n  typedef real real_type ;\n\n  typedef std::vector<real>  stl_vector;\n  typedef std::vector<stl_vector > stl_matrix;\n\n  typedef gmm::dense_matrix<real> gene_matrix;\n  typedef stl_vector gene_vector;\n\n  static inline std::string name( void )\n  {\n    return \"gmm\";\n  }\n\n  static void free_matrix(gene_matrix & A, int N){\n    return ;\n  }\n\n  static void free_vector(gene_vector & B){\n    return ;\n  }\n\n  static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    A.resize(A_stl[0].size(),A_stl.size());\n\n    for (int j=0; j<A_stl.size() ; j++){\n      for (int i=0; i<A_stl[j].size() ; i++){\n        A(i,j) = A_stl[j][i];\n      }\n    }\n  }\n\n  static inline void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    B = B_stl;\n  }\n\n  static inline void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    B_stl = B;\n  }\n\n  static inline void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int N=A_stl.size();\n\n    for (int j=0;j<N;j++){\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++){\n        A_stl[j][i] = A(i,j);\n      }\n    }\n  }\n\n  static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N){\n    gmm::mult(A,B, X);\n  }\n\n  static inline void transposed_matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N){\n    gmm::mult(gmm::transposed(A),gmm::transposed(B), X);\n  }\n\n  static inline void ata_product(const gene_matrix & A, gene_matrix & X, int N){\n    gmm::mult(gmm::transposed(A),A, X);\n  }\n\n  static inline void aat_product(const gene_matrix & A, gene_matrix & X, int N){\n    gmm::mult(A,gmm::transposed(A), X);\n  }\n\n  static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    gmm::mult(A,B,X);\n  }\n\n  static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    gmm::mult(gmm::transposed(A),B,X);\n  }\n\n  static inline void axpy(const real coef, const gene_vector & X, gene_vector & Y, int N){\n    gmm::add(gmm::scaled(X,coef), Y);\n  }\n\n  static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int N){\n    gmm::add(gmm::scaled(X,a), gmm::scaled(Y,b), Y);\n  }\n\n  static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){\n    gmm::copy(source,cible);\n  }\n\n  static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){\n    gmm::copy(source,cible);\n  }\n\n  static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector & X, int N){\n    gmm::copy(B,X);\n    gmm::lower_tri_solve(L, X, false);\n  }\n\n  static inline void partial_lu_decomp(const gene_matrix & X, gene_matrix & R, int N){\n    gmm::copy(X,R);\n    std::vector<int> ipvt(N);\n    gmm::lu_factor(R, ipvt);\n  }\n\n  static inline void hessenberg(const gene_matrix & X, gene_matrix & R, int N){\n    gmm::copy(X,R);\n    gmm::Hessenberg_reduction(R,X,false);\n  }\n\n  static inline void tridiagonalization(const gene_matrix & X, gene_matrix & R, int N){\n    gmm::copy(X,R);\n    gmm::Householder_tridiagonalization(R,X,false);\n  }\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/gmm/main.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"gmm_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n#include \"action_hessenberg.hh\"\n#include \"action_partial_lu.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n\n  bench<Action_axpy<gmm_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_axpby<gmm_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n\n  bench<Action_matrix_vector_product<gmm_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_atv_product<gmm_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n\n  bench<Action_matrix_matrix_product<gmm_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_ata_product<gmm_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_aat_product<gmm_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  bench<Action_trisolve<gmm_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  //bench<Action_lu_solve<blitz_LU_solve_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n\n  bench<Action_partial_lu<gmm_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  \n  bench<Action_hessenberg<gmm_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_tridiagonalization<gmm_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/mtl4/.kdbgrc.main",
    "content": "[General]\nDebuggerCmdStr=\nDriverName=GDB\nFileVersion=1\nOptionsSelected=\nProgramArgs=\nTTYLevel=7\nWorkingDirectory=\n\n[Memory]\nColumnWidths=80,0\nNumExprs=0\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/mtl4/CMakeLists.txt",
    "content": "\nfind_package(MTL4)\nif (MTL4_FOUND)\n  include_directories(${MTL4_INCLUDE_DIR})\n  btl_add_bench(btl_mtl4 main.cpp)\nendif ()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/mtl4/main.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"mtl4_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n#include \"action_cholesky.hh\"\n// #include \"action_lu_decomp.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n\n  bench<Action_axpy<mtl4_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_axpby<mtl4_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n\n  bench<Action_matrix_vector_product<mtl4_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_atv_product<mtl4_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_matrix_matrix_product<mtl4_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_ata_product<mtl4_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_aat_product<mtl4_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  bench<Action_trisolve<mtl4_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_cholesky<mtl4_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_lu_decomp<mtl4_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/mtl4/mtl4_LU_solve_interface.hh",
    "content": "//=====================================================\n// File   :  blitz_LU_solve_interface.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  lun sep 30 14:23:31 CEST 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef BLITZ_LU_SOLVE_INTERFACE_HH\n#define BLITZ_LU_SOLVE_INTERFACE_HH\n\n#include \"blitz/array.h\"\n#include <vector>\n\nBZ_USING_NAMESPACE(blitz)\n\ntemplate<class real>\nclass blitz_LU_solve_interface : public blitz_interface<real>\n{\n\npublic :\n\n  typedef typename blitz_interface<real>::gene_matrix gene_matrix;\n  typedef typename blitz_interface<real>::gene_vector gene_vector;\n\n  typedef blitz::Array<int,1> Pivot_Vector;\n\n  inline static void new_Pivot_Vector(Pivot_Vector & pivot,int N)\n  {\n\n    pivot.resize(N);\n\n  }\n\n  inline static void free_Pivot_Vector(Pivot_Vector & pivot)\n  {\n    \n    return;\n\n  }\n\n\n  static inline real matrix_vector_product_sliced(const gene_matrix & A, gene_vector B, int row, int col_start, int col_end)\n  {\n    \n    real somme=0.;\n    \n    for (int j=col_start ; j<col_end+1 ; j++){\n\t\n\tsomme+=A(row,j)*B(j);\n\t\n    }\n\n    return somme;\n\n  }\n\n\n\n\n  static inline real matrix_matrix_product_sliced(gene_matrix & A, int row, int col_start, int col_end, gene_matrix & B, int row_shift, int col )\n  {\n    \n    real somme=0.;\n    \n    for (int j=col_start ; j<col_end+1 ; j++){\n\t\n\tsomme+=A(row,j)*B(j+row_shift,col);\n\t\n    }\n\n    return somme;\n\n  }\n\n  inline static void LU_factor(gene_matrix & LU, Pivot_Vector & pivot, int N)\n  {\n\n    ASSERT( LU.rows()==LU.cols() ) ;\n    int index_max = 0 ;\n    real big = 0. ;\n    real theSum = 0. ;\n    real dum = 0. ;\n    // Get the implicit scaling information :\n    gene_vector ImplicitScaling( N ) ;\n    for( int i=0; i<N; i++ ) {\n      big = 0. ;\n      for( int j=0; j<N; j++ ) {\n\tif( abs( LU( i, j ) )>=big ) big = abs( LU( i, j ) ) ;\n      }\n      if( big==0. ) {\n\tINFOS( \"blitz_LU_factor::Singular matrix\" ) ;\n\texit( 0 ) ;\n      }\n      ImplicitScaling( i ) = 1./big ;\n    }\n    // Loop over columns of Crout's method :\n    for( int j=0; j<N; j++ ) {\n      for( int i=0; i<j; i++ ) {\n\ttheSum = LU( i, j ) ;\n\ttheSum -= matrix_matrix_product_sliced(LU, i, 0, i-1, LU, 0, j) ;\n\t//\ttheSum -= sum( LU( i, Range( fromStart, i-1 ) )*LU( Range( fromStart, i-1 ), j ) ) ;\n\tLU( i, j ) = theSum ;\n      }\n      \n      // Search for the largest pivot element :\n      big = 0. ;\n      for( int i=j; i<N; i++ ) {\n\ttheSum = LU( i, j ) ;\n\ttheSum -= matrix_matrix_product_sliced(LU, i, 0, j-1, LU, 0, j) ;\n\t//\ttheSum -= sum( LU( i, Range( fromStart, j-1 ) )*LU( Range( fromStart, j-1 ), j ) ) ;\n\tLU( i, j ) = theSum ;\n\tif( (ImplicitScaling( i )*abs( theSum ))>=big ) {\n\t  dum = ImplicitScaling( i )*abs( theSum ) ;\n\t  big = dum ;\n\t  index_max = i ;\n\t}\n      }\n      // Interchanging rows and the scale factor :\n      if( j!=index_max ) {\n\tfor( int k=0; k<N; k++ ) {\n\t  dum = LU( index_max, k ) ;\n\t  LU( index_max, k ) = LU( j, k ) ;\n\t  LU( j, k ) = dum ;\n\t}\n\tImplicitScaling( index_max ) = ImplicitScaling( j ) ;\n      }\n      pivot( j ) = index_max ;\n      if ( LU( j, j )==0. ) LU( j, j ) = 1.e-20 ;\n      // Divide by the pivot element :\n      if( j<N ) {\n\tdum = 1./LU( j, j ) ;\n\tfor( int i=j+1; i<N; i++ ) LU( i, j ) *= dum ;\n      }\n    }\n\n  }\n\n  inline static void LU_solve(const gene_matrix & LU, const Pivot_Vector pivot, gene_vector &B, gene_vector X, int N)\n  {\n\n    // Pour conserver le meme header, on travaille sur X, copie du second-membre B\n    X = B.copy() ;\n    ASSERT( LU.rows()==LU.cols() ) ;\n    firstIndex indI ;\n    // Forward substitution :\n    int ii = 0 ;\n    real theSum = 0. ;\n    for( int i=0; i<N; i++ ) {\n      int ip = pivot( i ) ;\n      theSum = X( ip ) ;\n      //      theSum = B( ip ) ;\n      X( ip ) = X( i ) ;\n      //      B( ip ) = B( i ) ;\n      if( ii ) {\n\ttheSum -= matrix_vector_product_sliced(LU, X, i, ii-1, i-1) ;\n\t//\ttheSum -= sum( LU( i, Range( ii-1, i-1 ) )*X( Range( ii-1, i-1 ) ) ) ;\n\t//\ttheSum -= sum( LU( i, Range( ii-1, i-1 ) )*B( Range( ii-1, i-1 ) ) ) ;\n      } else if( theSum ) {\n\tii = i+1 ;\n      }\n      X( i ) = theSum ;\n      //      B( i ) = theSum ;\n    }\n    // Backsubstitution :\n    for( int i=N-1; i>=0; i-- ) {\n      theSum = X( i ) ;\n      //      theSum = B( i ) ;\n      theSum -= matrix_vector_product_sliced(LU, X, i, i+1, N) ;\n      //      theSum -= sum( LU( i, Range( i+1, toEnd ) )*X( Range( i+1, toEnd ) ) ) ;\n      //      theSum -= sum( LU( i, Range( i+1, toEnd ) )*B( Range( i+1, toEnd ) ) ) ;\n      // Store a component of the solution vector :\n      X( i ) = theSum/LU( i, i ) ;\n      //      B( i ) = theSum/LU( i, i ) ;\n    }\n\n  }\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/mtl4/mtl4_interface.hh",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef MTL4_INTERFACE_HH\n#define MTL4_INTERFACE_HH\n\n#include <boost/numeric/mtl/mtl.hpp>\n#include <boost/numeric/mtl/utility/range_generator.hpp>\n// #include <boost/numeric/mtl/operation/cholesky.hpp>\n#include <vector>\n\nusing namespace mtl;\n\ntemplate<class real>\nclass mtl4_interface {\n\npublic :\n\n  typedef real real_type ;\n\n  typedef std::vector<real>  stl_vector;\n  typedef std::vector<stl_vector > stl_matrix;\n\n  typedef mtl::dense2D<real, mtl::matrix::parameters<mtl::tag::col_major> > gene_matrix;\n  typedef mtl::dense_vector<real>  gene_vector;\n\n  static inline std::string name() { return \"mtl4\"; }\n\n  static void free_matrix(gene_matrix & A, int N){\n    return ;\n  }\n\n  static void free_vector(gene_vector & B){\n    return ;\n  }\n\n  static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    A.change_dim(A_stl[0].size(), A_stl.size());\n\n    for (int j=0; j<A_stl.size() ; j++){\n      for (int i=0; i<A_stl[j].size() ; i++){\n        A(i,j) = A_stl[j][i];\n      }\n    }\n  }\n\n  static inline void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    B.change_dim(B_stl.size());\n    for (int i=0; i<B_stl.size() ; i++){\n      B[i] = B_stl[i];\n    }\n  }\n\n  static inline void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    for (int i=0; i<B_stl.size() ; i++){\n      B_stl[i] = B[i];\n    }\n  }\n\n  static inline void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int N=A_stl.size();\n    for (int j=0;j<N;j++){\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++){\n        A_stl[j][i] = A(i,j);\n      }\n    }\n  }\n\n  static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N){\n    X = (A*B);\n//     morton_dense<double, doppled_64_row_mask> C(N,N);\n//     C = B;\n//     X = (A*C);\n  }\n\n  static inline void transposed_matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N){\n    X = (trans(A)*trans(B));\n  }\n\n//   static inline void ata_product(const gene_matrix & A, gene_matrix & X, int N){\n//     X = (trans(A)*A);\n//   }\n\n  static inline void aat_product(const gene_matrix & A, gene_matrix & X, int N){\n    X = (A*trans(A));\n  }\n\n  static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X = (A*B);\n  }\n\n  static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X = (trans(A)*B);\n  }\n\n  static inline void axpy(const real coef, const gene_vector & X, gene_vector & Y, int N){\n    Y += coef * X;\n  }\n\n  static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int N){\n    Y = a*X + b*Y;\n  }\n\n//   static inline void cholesky(const gene_matrix & X, gene_matrix & C, int N){\n//     C = X;\n//     recursive_cholesky(C);\n//   }\n\n//   static inline void lu_decomp(const gene_matrix & X, gene_matrix & R, int N){\n//     R = X;\n//     std::vector<int> ipvt(N);\n//     lu_factor(R, ipvt);\n//   }\n\n  static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector & X, int N){\n    X = lower_trisolve(L, B);\n  }\n\n  static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){\n    cible = source;\n  }\n\n  static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){\n    cible = source;\n  }\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/tensors/CMakeLists.txt",
    "content": "\n\nif((NOT TENSOR_INCLUDE_DIR) AND Eigen_SOURCE_DIR)\n  # unless TENSOR_INCLUDE_DIR is defined, let's use current Eigen version\n  set(TENSOR_INCLUDE_DIR ${Eigen_SOURCE_DIR})\n  set(TENSOR_FOUND TRUE)\nelse()\n  find_package(Tensor)\nendif()\n\nif (TENSOR_FOUND)\n\n  include_directories(${TENSOR_INCLUDE_DIR})\n  btl_add_bench(btl_tensor_linear main_linear.cpp)\n  btl_add_bench(btl_tensor_vecmat main_vecmat.cpp)\n  btl_add_bench(btl_tensor_matmat main_matmat.cpp)\n\n  btl_add_target_property(btl_tensor_linear COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=tensor\")\n  btl_add_target_property(btl_tensor_vecmat COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=tensor\")\n  btl_add_target_property(btl_tensor_matmat COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=tensor\")\n\n  option(BTL_BENCH_NOGCCVEC \"also bench Eigen explicit vec without GCC's auto vec\" OFF)\n  if(CMAKE_COMPILER_IS_GNUCXX AND BTL_BENCH_NOGCCVEC)\n    btl_add_bench(btl_tensor_nogccvec_linear main_linear.cpp)\n    btl_add_bench(btl_tensor_nogccvec_vecmat main_vecmat.cpp)\n    btl_add_bench(btl_tensor_nogccvec_matmat main_matmat.cpp)\n\n    btl_add_target_property(btl_tensor_nogccvec_linear COMPILE_FLAGS \"-fno-exceptions -fno-tree-vectorize -DBTL_PREFIX=tensor_nogccvec\")\n    btl_add_target_property(btl_tensor_nogccvec_vecmat COMPILE_FLAGS \"-fno-exceptions -fno-tree-vectorize -DBTL_PREFIX=tensor_nogccvec\")\n    btl_add_target_property(btl_tensor_nogccvec_matmat COMPILE_FLAGS \"-fno-exceptions -fno-tree-vectorize -DBTL_PREFIX=tensor_nogccvec\")\n  endif()\n\n\n  if(NOT BTL_NOVEC)\n    btl_add_bench(btl_tensor_novec_linear main_linear.cpp OFF)\n    btl_add_bench(btl_tensor_novec_vecmat main_vecmat.cpp OFF)\n    btl_add_bench(btl_tensor_novec_matmat main_matmat.cpp OFF)\n    btl_add_target_property(btl_tensor_novec_linear COMPILE_FLAGS \"-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=tensor_novec\")\n    btl_add_target_property(btl_tensor_novec_vecmat COMPILE_FLAGS \"-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=tensor_novec\")\n    btl_add_target_property(btl_tensor_novec_matmat COMPILE_FLAGS \"-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=tensor_novec\")\n\n  endif()\n\nendif ()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/tensors/main_linear.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"utilities.h\"\n#include \"tensor_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_axpy<tensor_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_axpby<tensor_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/tensors/main_matmat.cpp",
    "content": "//=====================================================\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//=====================================================\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n//\n#include \"utilities.h\"\n#include \"tensor_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_matrix_matrix_product<tensor_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/tensors/main_vecmat.cpp",
    "content": "//=====================================================\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//=====================================================\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n//\n#include \"utilities.h\"\n#include \"tensor_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_matrix_vector_product<tensor_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/tensors/tensor_interface.hh",
    "content": "//=====================================================\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//=====================================================\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n//\n#ifndef TENSOR_INTERFACE_HH\n#define TENSOR_INTERFACE_HH\n\n#include <unsupported/Eigen/CXX11/Tensor>\n#include <vector>\n#include \"btl.hh\"\n\nusing namespace Eigen;\n\ntemplate<class real>\nclass tensor_interface\n{\npublic :\n  typedef real real_type;\n  typedef typename Eigen::Tensor<real,2>::Index Index;\n\n  typedef std::vector<real> stl_vector;\n  typedef std::vector<stl_vector> stl_matrix;\n\n  typedef Eigen::Tensor<real,2> gene_matrix;\n  typedef Eigen::Tensor<real,1> gene_vector;\n\n\n  static inline std::string name( void )\n  {\n    return EIGEN_MAKESTRING(BTL_PREFIX);\n  }\n\n  static void free_matrix(gene_matrix & /*A*/, int /*N*/) {}\n\n  static void free_vector(gene_vector & /*B*/) {}\n\n  static BTL_DONT_INLINE void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    A.resize(Eigen::array<Index,2>(A_stl[0].size(), A_stl.size()));\n\n    for (unsigned int j=0; j<A_stl.size() ; j++){\n      for (unsigned int i=0; i<A_stl[j].size() ; i++){\n        A.coeffRef(Eigen::array<Index,2>(i,j)) = A_stl[j][i];\n      }\n    }\n  }\n\n  static BTL_DONT_INLINE  void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    B.resize(B_stl.size());\n\n    for (unsigned int i=0; i<B_stl.size() ; i++){\n      B.coeffRef(i) = B_stl[i];\n    }\n  }\n\n  static BTL_DONT_INLINE  void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    for (unsigned int i=0; i<B_stl.size() ; i++){\n      B_stl[i] = B.coeff(i);\n    }\n  }\n\n  static BTL_DONT_INLINE  void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int  N=A_stl.size();\n\n    for (int j=0;j<N;j++){\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++){\n        A_stl[j][i] = A.coeff(Eigen::array<Index,2>(i,j));\n      }\n    }\n  }\n\n  static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int  /*N*/){\n    typedef typename Eigen::Tensor<real_type, 1>::DimensionPair DimPair;\n    const Eigen::array<DimPair, 1> dims(DimPair(1, 0));\n    X/*.noalias()*/ = A.contract(B, dims);\n  }\n\n  static inline void matrix_vector_product(const gene_matrix & A, const gene_vector & B, gene_vector & X, int  /*N*/){\n    typedef typename Eigen::Tensor<real_type, 1>::DimensionPair DimPair;\n    const Eigen::array<DimPair, 1> dims(DimPair(1, 0));\n    X/*.noalias()*/ = A.contract(B, dims);\n  }\n\n  static inline void axpy(real coef, const gene_vector & X, gene_vector & Y, int  /*N*/){\n    Y += X.constant(coef) * X;\n  }\n\n  static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int  /*N*/){\n    Y = X.constant(a)*X + Y.constant(b)*Y;\n  }\n\n  static EIGEN_DONT_INLINE void copy_matrix(const gene_matrix & source, gene_matrix & cible, int  /*N*/){\n    cible = source;\n  }\n\n  static EIGEN_DONT_INLINE void copy_vector(const gene_vector & source, gene_vector & cible, int  /*N*/){\n    cible = source;\n  }\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/tvmet/CMakeLists.txt",
    "content": "\nfind_package(Tvmet)\nif (TVMET_FOUND)\n  include_directories(${TVMET_INCLUDE_DIR})\n  btl_add_bench(btl_tvmet main.cpp OFF)\nendif ()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/tvmet/main.cpp",
    "content": "//=====================================================\n// File   :  main.cpp\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:30 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"tvmet_interface.hh\"\n#include \"static/bench_static.hh\"\n#include \"action_matrix_vector_product.hh\"\n#include \"action_matrix_matrix_product.hh\"\n#include \"action_atv_product.hh\"\n#include \"action_axpy.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench_static<Action_axpy,tvmet_interface>();\n  bench_static<Action_matrix_matrix_product,tvmet_interface>();\n  bench_static<Action_matrix_vector_product,tvmet_interface>();\n  bench_static<Action_atv_product,tvmet_interface>();\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/tvmet/tvmet_interface.hh",
    "content": "//=====================================================\n// File   :  tvmet_interface.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:30 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef TVMET_INTERFACE_HH\n#define TVMET_INTERFACE_HH\n\n#include <tvmet/tvmet.h>\n#include <tvmet/Vector.h>\n#include <tvmet/Matrix.h>\n\n#include <vector>\n\nusing namespace tvmet;\n\ntemplate<class real, int SIZE>\nclass tvmet_interface{\n\npublic :\n\n  typedef real real_type ;\n\n  typedef std::vector<real>  stl_vector;\n  typedef std::vector<stl_vector > stl_matrix;\n\n  typedef Vector<real,SIZE> gene_vector;\n  typedef Matrix<real,SIZE,SIZE> gene_matrix;\n\n  static inline std::string name() { return \"tiny_tvmet\"; }\n\n  static void free_matrix(gene_matrix & A, int N){}\n\n  static void free_vector(gene_vector & B){}\n\n  static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    for (int j=0; j<A_stl.size() ; j++)\n      for (int i=0; i<A_stl[j].size() ; i++)\n        A(i,j) = A_stl[j][i];\n  }\n\n  static inline void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    for (int i=0; i<B_stl.size() ; i++)\n      B[i]=B_stl[i];\n  }\n\n  static inline void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    for (int i=0; i<B_stl.size() ; i++){\n      B_stl[i]=B[i];\n    }\n  }\n\n  static inline void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int N = A_stl.size();\n    for (int j=0;j<N;j++){\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++)\n        A_stl[j][i] = A(i,j);\n    }\n  }\n\n\n  static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){\n    cible = source;\n  }\n\n  static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){\n    cible = source;\n  }\n\n  static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N){\n    X = prod(A,B);\n  }\n\n  static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X = prod(A,B);\n  }\n\n  static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X = prod(trans(A),B);\n  }\n\n  static inline void axpy(const real coef, const gene_vector & X, gene_vector & Y, int N){\n    Y+=coef*X;\n  }\n\n};\n\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/ublas/CMakeLists.txt",
    "content": "\nfind_package(Boost)\nif (Boost_FOUND)\n  include_directories(${Boost_INCLUDE_DIRS})\n  include_directories(${Boost_INCLUDES})\n  btl_add_bench(btl_ublas main.cpp)\nendif ()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/ublas/main.cpp",
    "content": "//=====================================================\n// File   :  main.cpp\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:27 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"ublas_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_axpy<ublas_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_axpby<ublas_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n\n  bench<Action_matrix_vector_product<ublas_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_atv_product<ublas_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n\n  bench<Action_matrix_matrix_product<ublas_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_ata_product<ublas_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_aat_product<ublas_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  bench<Action_trisolve<ublas_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/btl/libs/ublas/ublas_interface.hh",
    "content": "//=====================================================\n// File   :  ublas_interface.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:27 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef UBLAS_INTERFACE_HH\n#define UBLAS_INTERFACE_HH\n\n#include <boost/numeric/ublas/vector.hpp>\n#include <boost/numeric/ublas/matrix.hpp>\n#include <boost/numeric/ublas/io.hpp>\n#include <boost/numeric/ublas/triangular.hpp>\n\nusing namespace boost::numeric;\n\ntemplate <class real>\nclass ublas_interface{\n\npublic :\n\n  typedef real real_type ;\n\n  typedef std::vector<real> stl_vector;\n  typedef std::vector<stl_vector> stl_matrix;\n\n  typedef typename boost::numeric::ublas::matrix<real,boost::numeric::ublas::column_major> gene_matrix;\n  typedef typename boost::numeric::ublas::vector<real> gene_vector;\n\n  static inline std::string name( void ) { return \"ublas\"; }\n\n  static void free_matrix(gene_matrix & A, int N) {}\n\n  static void free_vector(gene_vector & B) {}\n\n  static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    A.resize(A_stl.size(),A_stl[0].size());\n    for (int j=0; j<A_stl.size() ; j++)\n      for (int i=0; i<A_stl[j].size() ; i++)\n        A(i,j)=A_stl[j][i];\n  }\n\n  static inline void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    B.resize(B_stl.size());\n    for (int i=0; i<B_stl.size() ; i++)\n      B(i)=B_stl[i];\n  }\n\n  static inline void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    for (int i=0; i<B_stl.size() ; i++)\n      B_stl[i]=B(i);\n  }\n\n  static inline void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int N=A_stl.size();\n    for (int j=0;j<N;j++)\n    {\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++)\n        A_stl[j][i]=A(i,j);\n    }\n  }\n\n  static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){\n    for (int i=0;i<N;i++){\n      cible(i) = source(i);\n    }\n  }\n\n  static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){\n    for (int i=0;i<N;i++){\n      for (int j=0;j<N;j++){\n        cible(i,j) = source(i,j);\n      }\n    }\n  }\n\n  static inline void matrix_vector_product_slow(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X =  prod(A,B);\n  }\n\n  static inline void matrix_matrix_product_slow(gene_matrix & A, gene_matrix & B, gene_matrix & X, int N){\n    X =  prod(A,B);\n  }\n\n  static inline void axpy_slow(const real coef, const gene_vector & X, gene_vector & Y, int N){\n    Y+=coef*X;\n  }\n\n  // alias free assignments\n\n  static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X.assign(prod(A,B));\n  }\n\n  static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X.assign(prod(trans(A),B));\n  }\n\n  static inline void matrix_matrix_product(gene_matrix & A, gene_matrix & B, gene_matrix & X, int N){\n    X.assign(prod(A,B));\n  }\n\n  static inline void axpy(const real coef, const gene_vector & X, gene_vector & Y, int N){\n    Y.plus_assign(coef*X);\n  }\n\n  static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int N){\n    Y = a*X + b*Y;\n  }\n\n  static inline void ata_product(gene_matrix & A, gene_matrix & X, int N){\n    // X =  prod(trans(A),A);\n    X.assign(prod(trans(A),A));\n  }\n\n  static inline void aat_product(gene_matrix & A, gene_matrix & X, int N){\n    // X =  prod(A,trans(A));\n    X.assign(prod(A,trans(A)));\n  }\n\n  static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector & X, int N){\n    X = solve(L, B, ublas::lower_tag ());\n  }\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/check_cache_queries.cpp",
    "content": "\n#define EIGEN_INTERNAL_DEBUG_CACHE_QUERY\n#include <iostream>\n#include \"../Eigen/Core\"\n\nusing namespace Eigen;\nusing namespace std;\n\n#define DUMP_CPUID(CODE) {\\\n  int abcd[4]; \\\n  abcd[0] = abcd[1] = abcd[2] = abcd[3] = 0;\\\n  EIGEN_CPUID(abcd, CODE, 0); \\\n  std::cout << \"The code \" << CODE << \" gives \" \\\n              << (int*)(abcd[0]) << \" \" << (int*)(abcd[1]) << \" \" \\\n              << (int*)(abcd[2]) << \" \" << (int*)(abcd[3]) << \" \" << std::endl; \\\n  }\n  \nint main()\n{\n  cout << \"Eigen's L1    = \" << internal::queryL1CacheSize() << endl;\n  cout << \"Eigen's L2/L3 = \" << internal::queryTopLevelCacheSize() << endl;\n  int l1, l2, l3;\n  internal::queryCacheSizes(l1, l2, l3);\n  cout << \"Eigen's L1, L2, L3       = \" << l1 << \" \" << l2 << \" \" << l3 << endl;\n  \n  #ifdef EIGEN_CPUID\n\n  int abcd[4];\n  int string[8];\n  char* string_char = (char*)(string);\n\n  // vendor ID\n  EIGEN_CPUID(abcd,0x0,0);\n  string[0] = abcd[1];\n  string[1] = abcd[3];\n  string[2] = abcd[2];\n  string[3] = 0;\n  cout << endl;\n  cout << \"vendor id = \" << string_char << endl;\n  cout << endl;\n  int max_funcs = abcd[0];\n\n  internal::queryCacheSizes_intel_codes(l1, l2, l3);\n  cout << \"Eigen's intel codes L1, L2, L3 = \" << l1 << \" \" << l2 << \" \" << l3 << endl;\n  if(max_funcs>=4)\n  {\n    internal::queryCacheSizes_intel_direct(l1, l2, l3);\n    cout << \"Eigen's intel direct L1, L2, L3 = \" << l1 << \" \" << l2 << \" \" << l3 << endl;\n  }\n  internal::queryCacheSizes_amd(l1, l2, l3);\n  cout << \"Eigen's amd L1, L2, L3         = \" << l1 << \" \" << l2 << \" \" << l3 << endl;\n  cout << endl;\n  \n  // dump Intel direct method\n  if(max_funcs>=4)\n  {\n    l1 = l2 = l3 = 0;\n    int cache_id = 0;\n    int cache_type = 0;\n    do {\n      abcd[0] = abcd[1] = abcd[2] = abcd[3] = 0;\n      EIGEN_CPUID(abcd,0x4,cache_id);\n      cache_type  = (abcd[0] & 0x0F) >> 0;\n      int cache_level = (abcd[0] & 0xE0) >> 5;  // A[7:5]\n      int ways        = (abcd[1] & 0xFFC00000) >> 22; // B[31:22]\n      int partitions  = (abcd[1] & 0x003FF000) >> 12; // B[21:12]\n      int line_size   = (abcd[1] & 0x00000FFF) >>  0; // B[11:0]\n      int sets        = (abcd[2]);                    // C[31:0]\n      int cache_size = (ways+1) * (partitions+1) * (line_size+1) * (sets+1);\n      \n      cout << \"cache[\" << cache_id << \"].type       = \" << cache_type << \"\\n\";\n      cout << \"cache[\" << cache_id << \"].level      = \" << cache_level << \"\\n\";\n      cout << \"cache[\" << cache_id << \"].ways       = \" << ways << \"\\n\";\n      cout << \"cache[\" << cache_id << \"].partitions = \" << partitions << \"\\n\";\n      cout << \"cache[\" << cache_id << \"].line_size  = \" << line_size << \"\\n\";\n      cout << \"cache[\" << cache_id << \"].sets       = \" << sets << \"\\n\";\n      cout << \"cache[\" << cache_id << \"].size       = \" << cache_size << \"\\n\";\n      \n      cache_id++;\n    } while(cache_type>0 && cache_id<16);\n  }\n  \n  // dump everything\n  std::cout << endl <<\"Raw dump:\" << endl;\n  for(int i=0; i<max_funcs; ++i)\n    DUMP_CPUID(i);\n\n  DUMP_CPUID(0x80000000);\n  DUMP_CPUID(0x80000001);\n  DUMP_CPUID(0x80000002);\n  DUMP_CPUID(0x80000003);\n  DUMP_CPUID(0x80000004);\n  DUMP_CPUID(0x80000005);\n  DUMP_CPUID(0x80000006);\n  DUMP_CPUID(0x80000007);\n  DUMP_CPUID(0x80000008);\n  #else\n  cout << \"EIGEN_CPUID is not defined\" << endl;\n  #endif\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/dense_solvers.cpp",
    "content": "#include <iostream>\n#include \"BenchTimer.h\"\n#include <Eigen/Dense>\n#include <map>\n#include <vector>\n#include <string>\n#include <sstream>\nusing namespace Eigen;\n\nstd::map<std::string,Array<float,1,8,DontAlign|RowMajor> > results;\nstd::vector<std::string> labels;\nstd::vector<Array2i> sizes;\n\ntemplate<typename Solver,typename MatrixType>\nEIGEN_DONT_INLINE\nvoid compute_norm_equation(Solver &solver, const MatrixType &A) {\n  if(A.rows()!=A.cols())\n    solver.compute(A.transpose()*A);\n  else\n    solver.compute(A);\n}\n\ntemplate<typename Solver,typename MatrixType>\nEIGEN_DONT_INLINE\nvoid compute(Solver &solver, const MatrixType &A) {\n  solver.compute(A);\n}\n\ntemplate<typename Scalar,int Size>\nvoid bench(int id, int rows, int size = Size)\n{\n  typedef Matrix<Scalar,Dynamic,Size> Mat;\n  typedef Matrix<Scalar,Dynamic,Dynamic> MatDyn;\n  typedef Matrix<Scalar,Size,Size> MatSquare;\n  Mat A(rows,size);\n  A.setRandom();\n  if(rows==size)\n    A = A*A.adjoint();\n  BenchTimer t_llt, t_ldlt, t_lu, t_fplu, t_qr, t_cpqr, t_cod, t_fpqr, t_jsvd, t_bdcsvd;\n\n  int svd_opt = ComputeThinU|ComputeThinV;\n  \n  int tries = 5;\n  int rep = 1000/size;\n  if(rep==0) rep = 1;\n//   rep = rep*rep;\n  \n  LLT<MatSquare> llt(size);\n  LDLT<MatSquare> ldlt(size);\n  PartialPivLU<MatSquare> lu(size);\n  FullPivLU<MatSquare> fplu(size,size);\n  HouseholderQR<Mat> qr(A.rows(),A.cols());\n  ColPivHouseholderQR<Mat> cpqr(A.rows(),A.cols());\n  CompleteOrthogonalDecomposition<Mat> cod(A.rows(),A.cols());\n  FullPivHouseholderQR<Mat> fpqr(A.rows(),A.cols());\n  JacobiSVD<MatDyn> jsvd(A.rows(),A.cols());\n  BDCSVD<MatDyn> bdcsvd(A.rows(),A.cols());\n  \n  BENCH(t_llt, tries, rep, compute_norm_equation(llt,A));\n  BENCH(t_ldlt, tries, rep, compute_norm_equation(ldlt,A));\n  BENCH(t_lu, tries, rep, compute_norm_equation(lu,A));\n  if(size<=1000)\n    BENCH(t_fplu, tries, rep, compute_norm_equation(fplu,A));\n  BENCH(t_qr, tries, rep, compute(qr,A));\n  BENCH(t_cpqr, tries, rep, compute(cpqr,A));\n  BENCH(t_cod, tries, rep, compute(cod,A));\n  if(size*rows<=10000000)\n    BENCH(t_fpqr, tries, rep, compute(fpqr,A));\n  if(size<500) // JacobiSVD is really too slow for too large matrices\n    BENCH(t_jsvd, tries, rep, jsvd.compute(A,svd_opt));\n//   if(size*rows<=20000000)\n    BENCH(t_bdcsvd, tries, rep, bdcsvd.compute(A,svd_opt));\n  \n  results[\"LLT\"][id] = t_llt.best();\n  results[\"LDLT\"][id] = t_ldlt.best();\n  results[\"PartialPivLU\"][id] = t_lu.best();\n  results[\"FullPivLU\"][id] = t_fplu.best();\n  results[\"HouseholderQR\"][id] = t_qr.best();\n  results[\"ColPivHouseholderQR\"][id] = t_cpqr.best();\n  results[\"CompleteOrthogonalDecomposition\"][id] = t_cod.best();\n  results[\"FullPivHouseholderQR\"][id] = t_fpqr.best();\n  results[\"JacobiSVD\"][id] = t_jsvd.best();\n  results[\"BDCSVD\"][id] = t_bdcsvd.best();\n}\n\n\nint main()\n{\n  labels.push_back(\"LLT\");\n  labels.push_back(\"LDLT\");\n  labels.push_back(\"PartialPivLU\");\n  labels.push_back(\"FullPivLU\");\n  labels.push_back(\"HouseholderQR\");\n  labels.push_back(\"ColPivHouseholderQR\");\n  labels.push_back(\"CompleteOrthogonalDecomposition\");\n  labels.push_back(\"FullPivHouseholderQR\");\n  labels.push_back(\"JacobiSVD\");\n  labels.push_back(\"BDCSVD\");\n\n  for(int i=0; i<labels.size(); ++i)\n    results[labels[i]].fill(-1);\n\n  const int small = 8;\n  sizes.push_back(Array2i(small,small));\n  sizes.push_back(Array2i(100,100));\n  sizes.push_back(Array2i(1000,1000));\n  sizes.push_back(Array2i(4000,4000));\n  sizes.push_back(Array2i(10000,small));\n  sizes.push_back(Array2i(10000,100));\n  sizes.push_back(Array2i(10000,1000));\n  sizes.push_back(Array2i(10000,4000));\n\n  using namespace std;\n\n  for(int k=0; k<sizes.size(); ++k)\n  {\n    cout << sizes[k](0) << \"x\" << sizes[k](1) << \"...\\n\";\n    bench<float,Dynamic>(k,sizes[k](0),sizes[k](1));\n  }\n\n  cout.width(32);\n  cout << \"solver/size\";\n  cout << \"  \";\n  for(int k=0; k<sizes.size(); ++k)\n  {\n    std::stringstream ss;\n    ss << sizes[k](0) << \"x\" << sizes[k](1);\n    cout.width(10); cout << ss.str(); cout << \" \";\n  }\n  cout << endl;\n\n\n  for(int i=0; i<labels.size(); ++i)\n  {\n    cout.width(32); cout << labels[i]; cout << \"  \";\n    ArrayXf r = (results[labels[i]]*100000.f).floor()/100.f;\n    for(int k=0; k<sizes.size(); ++k)\n    {\n      cout.width(10);\n      if(r(k)>=1e6)  cout << \"-\";\n      else           cout << r(k);\n      cout << \" \";\n    }\n    cout << endl;\n  }\n\n  // HTML output\n  cout << \"<table class=\\\"manual\\\">\" << endl;\n  cout << \"<tr><th>solver/size</th>\" << endl;\n  for(int k=0; k<sizes.size(); ++k)\n    cout << \"  <th>\" << sizes[k](0) << \"x\" << sizes[k](1) << \"</th>\";\n  cout << \"</tr>\" << endl;\n  for(int i=0; i<labels.size(); ++i)\n  {\n    cout << \"<tr\";\n    if(i%2==1) cout << \" class=\\\"alt\\\"\";\n    cout << \"><td>\" << labels[i] << \"</td>\";\n    ArrayXf r = (results[labels[i]]*100000.f).floor()/100.f;\n    for(int k=0; k<sizes.size(); ++k)\n    {\n      if(r(k)>=1e6) cout << \"<td>-</td>\";\n      else\n      {\n        cout << \"<td>\" << r(k);\n        if(i>0)\n          cout << \" (x\" << numext::round(10.f*results[labels[i]](k)/results[\"LLT\"](k))/10.f << \")\";\n        if(i<4 && sizes[k](0)!=sizes[k](1))\n          cout << \" <sup><a href=\\\"#note_ls\\\">*</a></sup>\";\n        cout << \"</td>\";\n      }\n    }\n    cout << \"</tr>\" << endl;\n  }\n  cout << \"</table>\" << endl;\n\n//   cout << \"LLT                             (ms)  \" << (results[\"LLT\"]*1000.).format(fmt) << \"\\n\";\n//   cout << \"LDLT                             (%)  \" << (results[\"LDLT\"]/results[\"LLT\"]).format(fmt) << \"\\n\";\n//   cout << \"PartialPivLU                     (%)  \" << (results[\"PartialPivLU\"]/results[\"LLT\"]).format(fmt) << \"\\n\";\n//   cout << \"FullPivLU                        (%)  \" << (results[\"FullPivLU\"]/results[\"LLT\"]).format(fmt) << \"\\n\";\n//   cout << \"HouseholderQR                    (%)  \" << (results[\"HouseholderQR\"]/results[\"LLT\"]).format(fmt) << \"\\n\";\n//   cout << \"ColPivHouseholderQR              (%)  \" << (results[\"ColPivHouseholderQR\"]/results[\"LLT\"]).format(fmt) << \"\\n\";\n//   cout << \"CompleteOrthogonalDecomposition  (%)  \" << (results[\"CompleteOrthogonalDecomposition\"]/results[\"LLT\"]).format(fmt) << \"\\n\";\n//   cout << \"FullPivHouseholderQR             (%)  \" << (results[\"FullPivHouseholderQR\"]/results[\"LLT\"]).format(fmt) << \"\\n\";\n//   cout << \"JacobiSVD                        (%)  \" << (results[\"JacobiSVD\"]/results[\"LLT\"]).format(fmt) << \"\\n\";\n//   cout << \"BDCSVD                           (%)  \" << (results[\"BDCSVD\"]/results[\"LLT\"]).format(fmt) << \"\\n\";\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/eig33.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// The computeRoots function included in this is based on materials\n// covered by the following copyright and license:\n// \n// Geometric Tools, LLC\n// Copyright (c) 1998-2010\n// Distributed under the Boost Software License, Version 1.0.\n// \n// Permission is hereby granted, free of charge, to any person or organization\n// obtaining a copy of the software and accompanying documentation covered by\n// this license (the \"Software\") to use, reproduce, display, distribute,\n// execute, and transmit the Software, and to prepare derivative works of the\n// Software, and to permit third-parties to whom the Software is furnished to\n// do so, all subject to the following:\n// \n// The copyright notices in the Software and this entire statement, including\n// the above license grant, this restriction and the following disclaimer,\n// must be included in all copies of the Software, in whole or in part, and\n// all derivative works of the Software, unless such copies or derivative\n// works are solely in the form of machine-executable object code generated by\n// a source language processor.\n// \n// THE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR\n// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,\n// FITNESS FOR A PARTICULAR PURPOSE, TITLE AND NON-INFRINGEMENT. IN NO EVENT\n// SHALL THE COPYRIGHT HOLDERS OR ANYONE DISTRIBUTING THE SOFTWARE BE LIABLE\n// FOR ANY DAMAGES OR OTHER LIABILITY, WHETHER IN CONTRACT, TORT OR OTHERWISE,\n// ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER\n// DEALINGS IN THE SOFTWARE.\n\n#include <iostream>\n#include <Eigen/Core>\n#include <Eigen/Eigenvalues>\n#include <Eigen/Geometry>\n#include <bench/BenchTimer.h>\n\nusing namespace Eigen;\nusing namespace std;\n\ntemplate<typename Matrix, typename Roots>\ninline void computeRoots(const Matrix& m, Roots& roots)\n{\n  typedef typename Matrix::Scalar Scalar;\n  const Scalar s_inv3 = 1.0/3.0;\n  const Scalar s_sqrt3 = std::sqrt(Scalar(3.0));\n\n  // The characteristic equation is x^3 - c2*x^2 + c1*x - c0 = 0.  The\n  // eigenvalues are the roots to this equation, all guaranteed to be\n  // real-valued, because the matrix is symmetric.\n  Scalar c0 = m(0,0)*m(1,1)*m(2,2) + Scalar(2)*m(0,1)*m(0,2)*m(1,2) - m(0,0)*m(1,2)*m(1,2) - m(1,1)*m(0,2)*m(0,2) - m(2,2)*m(0,1)*m(0,1);\n  Scalar c1 = m(0,0)*m(1,1) - m(0,1)*m(0,1) + m(0,0)*m(2,2) - m(0,2)*m(0,2) + m(1,1)*m(2,2) - m(1,2)*m(1,2);\n  Scalar c2 = m(0,0) + m(1,1) + m(2,2);\n\n  // Construct the parameters used in classifying the roots of the equation\n  // and in solving the equation for the roots in closed form.\n  Scalar c2_over_3 = c2*s_inv3;\n  Scalar a_over_3 = (c1 - c2*c2_over_3)*s_inv3;\n  if (a_over_3 > Scalar(0))\n    a_over_3 = Scalar(0);\n\n  Scalar half_b = Scalar(0.5)*(c0 + c2_over_3*(Scalar(2)*c2_over_3*c2_over_3 - c1));\n\n  Scalar q = half_b*half_b + a_over_3*a_over_3*a_over_3;\n  if (q > Scalar(0))\n    q = Scalar(0);\n\n  // Compute the eigenvalues by solving for the roots of the polynomial.\n  Scalar rho = std::sqrt(-a_over_3);\n  Scalar theta = std::atan2(std::sqrt(-q),half_b)*s_inv3;\n  Scalar cos_theta = std::cos(theta);\n  Scalar sin_theta = std::sin(theta);\n  roots(2) = c2_over_3 + Scalar(2)*rho*cos_theta;\n  roots(0) = c2_over_3 - rho*(cos_theta + s_sqrt3*sin_theta);\n  roots(1) = c2_over_3 - rho*(cos_theta - s_sqrt3*sin_theta);\n}\n\ntemplate<typename Matrix, typename Vector>\nvoid eigen33(const Matrix& mat, Matrix& evecs, Vector& evals)\n{\n  typedef typename Matrix::Scalar Scalar;\n  // Scale the matrix so its entries are in [-1,1].  The scaling is applied\n  // only when at least one matrix entry has magnitude larger than 1.\n\n  Scalar shift = mat.trace()/3;\n  Matrix scaledMat = mat;\n  scaledMat.diagonal().array() -= shift;\n  Scalar scale = scaledMat.cwiseAbs()/*.template triangularView<Lower>()*/.maxCoeff();\n  scale = std::max(scale,Scalar(1));\n  scaledMat/=scale;\n\n  // Compute the eigenvalues\n//   scaledMat.setZero();\n  computeRoots(scaledMat,evals);\n\n  // compute the eigen vectors\n  // **here we assume 3 different eigenvalues**\n\n  // \"optimized version\" which appears to be slower with gcc!\n//     Vector base;\n//     Scalar alpha, beta;\n//     base <<   scaledMat(1,0) * scaledMat(2,1),\n//               scaledMat(1,0) * scaledMat(2,0),\n//              -scaledMat(1,0) * scaledMat(1,0);\n//     for(int k=0; k<2; ++k)\n//     {\n//       alpha = scaledMat(0,0) - evals(k);\n//       beta  = scaledMat(1,1) - evals(k);\n//       evecs.col(k) = (base + Vector(-beta*scaledMat(2,0), -alpha*scaledMat(2,1), alpha*beta)).normalized();\n//     }\n//     evecs.col(2) = evecs.col(0).cross(evecs.col(1)).normalized();\n\n//   // naive version\n//   Matrix tmp;\n//   tmp = scaledMat;\n//   tmp.diagonal().array() -= evals(0);\n//   evecs.col(0) = tmp.row(0).cross(tmp.row(1)).normalized();\n// \n//   tmp = scaledMat;\n//   tmp.diagonal().array() -= evals(1);\n//   evecs.col(1) = tmp.row(0).cross(tmp.row(1)).normalized();\n// \n//   tmp = scaledMat;\n//   tmp.diagonal().array() -= evals(2);\n//   evecs.col(2) = tmp.row(0).cross(tmp.row(1)).normalized();\n  \n  // a more stable version:\n  if((evals(2)-evals(0))<=Eigen::NumTraits<Scalar>::epsilon())\n  {\n    evecs.setIdentity();\n  }\n  else\n  {\n    Matrix tmp;\n    tmp = scaledMat;\n    tmp.diagonal ().array () -= evals (2);\n    evecs.col (2) = tmp.row (0).cross (tmp.row (1)).normalized ();\n    \n    tmp = scaledMat;\n    tmp.diagonal ().array () -= evals (1);\n    evecs.col(1) = tmp.row (0).cross(tmp.row (1));\n    Scalar n1 = evecs.col(1).norm();\n    if(n1<=Eigen::NumTraits<Scalar>::epsilon())\n      evecs.col(1) = evecs.col(2).unitOrthogonal();\n    else\n      evecs.col(1) /= n1;\n    \n    // make sure that evecs[1] is orthogonal to evecs[2]\n    evecs.col(1) = evecs.col(2).cross(evecs.col(1).cross(evecs.col(2))).normalized();\n    evecs.col(0) = evecs.col(2).cross(evecs.col(1));\n  }\n  \n  // Rescale back to the original size.\n  evals *= scale;\n  evals.array()+=shift;\n}\n\nint main()\n{\n  BenchTimer t;\n  int tries = 10;\n  int rep = 400000;\n  typedef Matrix3d Mat;\n  typedef Vector3d Vec;\n  Mat A = Mat::Random(3,3);\n  A = A.adjoint() * A;\n//   Mat Q = A.householderQr().householderQ();\n//   A = Q * Vec(2.2424567,2.2424566,7.454353).asDiagonal() * Q.transpose();\n\n  SelfAdjointEigenSolver<Mat> eig(A);\n  BENCH(t, tries, rep, eig.compute(A));\n  std::cout << \"Eigen iterative:  \" << t.best() << \"s\\n\";\n  \n  BENCH(t, tries, rep, eig.computeDirect(A));\n  std::cout << \"Eigen direct   :  \" << t.best() << \"s\\n\";\n\n  Mat evecs;\n  Vec evals;\n  BENCH(t, tries, rep, eigen33(A,evecs,evals));\n  std::cout << \"Direct: \" << t.best() << \"s\\n\\n\";\n\n//   std::cerr << \"Eigenvalue/eigenvector diffs:\\n\";\n//   std::cerr << (evals - eig.eigenvalues()).transpose() << \"\\n\";\n//   for(int k=0;k<3;++k)\n//     if(evecs.col(k).dot(eig.eigenvectors().col(k))<0)\n//       evecs.col(k) = -evecs.col(k);\n//   std::cerr << evecs - eig.eigenvectors() << \"\\n\\n\";\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/geometry.cpp",
    "content": "\n#include <iostream>\n#include <Eigen/Geometry>\n#include <bench/BenchTimer.h>\n\nusing namespace std;\nusing namespace Eigen;\n\n#ifndef SCALAR\n#define SCALAR float\n#endif\n\n#ifndef SIZE\n#define SIZE 8\n#endif\n\ntypedef SCALAR Scalar;\ntypedef NumTraits<Scalar>::Real RealScalar;\ntypedef Matrix<RealScalar,Dynamic,Dynamic> A;\ntypedef Matrix</*Real*/Scalar,Dynamic,Dynamic> B;\ntypedef Matrix<Scalar,Dynamic,Dynamic> C;\ntypedef Matrix<RealScalar,Dynamic,Dynamic> M;\n\ntemplate<typename Transformation, typename Data>\nEIGEN_DONT_INLINE void transform(const Transformation& t, Data& data)\n{\n  EIGEN_ASM_COMMENT(\"begin\");\n  data = t * data;\n  EIGEN_ASM_COMMENT(\"end\");\n}\n\ntemplate<typename Scalar, typename Data>\nEIGEN_DONT_INLINE void transform(const Quaternion<Scalar>& t, Data& data)\n{\n  EIGEN_ASM_COMMENT(\"begin quat\");\n  for(int i=0;i<data.cols();++i)\n    data.col(i) = t * data.col(i);\n  EIGEN_ASM_COMMENT(\"end quat\");\n}\n\ntemplate<typename T> struct ToRotationMatrixWrapper\n{\n  enum {Dim = T::Dim};\n  typedef typename T::Scalar Scalar;\n  ToRotationMatrixWrapper(const T& o) : object(o) {}\n  T object;\n};\n\ntemplate<typename QType, typename Data>\nEIGEN_DONT_INLINE void transform(const ToRotationMatrixWrapper<QType>& t, Data& data)\n{\n  EIGEN_ASM_COMMENT(\"begin quat via mat\");\n  data = t.object.toRotationMatrix() * data;\n  EIGEN_ASM_COMMENT(\"end quat via mat\");\n}\n\ntemplate<typename Scalar, int Dim, typename Data>\nEIGEN_DONT_INLINE void transform(const Transform<Scalar,Dim,Projective>& t, Data& data)\n{\n  data = (t * data.colwise().homogeneous()).template block<Dim,Data::ColsAtCompileTime>(0,0);\n}\n\ntemplate<typename T> struct get_dim { enum { Dim = T::Dim }; };\ntemplate<typename S, int R, int C, int O, int MR, int MC>\nstruct get_dim<Matrix<S,R,C,O,MR,MC> > { enum { Dim = R }; };\n\ntemplate<typename Transformation, int N>\nstruct bench_impl\n{\n  static EIGEN_DONT_INLINE void run(const Transformation& t)\n  {\n    Matrix<typename Transformation::Scalar,get_dim<Transformation>::Dim,N> data;\n    data.setRandom();\n    bench_impl<Transformation,N-1>::run(t);\n    BenchTimer timer;\n    BENCH(timer,10,100000,transform(t,data));\n    cout.width(9);\n    cout << timer.best() << \" \";\n  }\n};\n\n\ntemplate<typename Transformation>\nstruct bench_impl<Transformation,0>\n{\n  static EIGEN_DONT_INLINE void run(const Transformation&) {}\n};\n\ntemplate<typename Transformation>\nEIGEN_DONT_INLINE void bench(const std::string& msg, const Transformation& t)\n{\n  cout << msg << \" \";\n  bench_impl<Transformation,SIZE>::run(t);\n  std::cout << \"\\n\";\n}\n\nint main(int argc, char ** argv)\n{\n  Matrix<Scalar,3,4> mat34; mat34.setRandom();\n  Transform<Scalar,3,Isometry> iso3(mat34);\n  Transform<Scalar,3,Affine> aff3(mat34);\n  Transform<Scalar,3,AffineCompact> caff3(mat34);\n  Transform<Scalar,3,Projective> proj3(mat34);\n  Quaternion<Scalar> quat;quat.setIdentity();\n  ToRotationMatrixWrapper<Quaternion<Scalar> > quatmat(quat);\n  Matrix<Scalar,3,3> mat33; mat33.setRandom();\n  \n  cout.precision(4);\n  std::cout\n     << \"N          \";\n  for(int i=0;i<SIZE;++i)\n  {\n    cout.width(9);\n    cout << i+1 << \" \";\n  }\n  cout << \"\\n\";\n  \n  bench(\"matrix 3x3\", mat33);\n  bench(\"quaternion\", quat);\n  bench(\"quat-mat  \", quatmat);\n  bench(\"isometry3 \", iso3);\n  bench(\"affine3   \", aff3);\n  bench(\"c affine3 \", caff3);\n  bench(\"proj3     \", proj3);\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/changesets.txt",
    "content": "Load hg-to-git hash maps from ./eigen_git/.git/\n#3.0.1\n#3.1.1\n#3.2.0\n3.2.4\n#574a7621809fe\n58964a85800bd  # introduce AVX\n#589cbd7e98174  # merge\n589db7d49efbb  # introduce FMA\n#590a078f442a3  # complex and AVX\n590a419cea4a0  # improve packing with ptranspose\n#59251e85c936d  # merge\n#592e497a27ddc\n593d5a795f673  # New gebp kernel: up to 3 packets x 4 register-level blocks\n#5942c3c95990d  # merge\n#596c9788d55b9  # Disable 3pX4 kernel on Altivec\n#5999aa3dc4e21  # merge\n6209452eb38f8   # before-evaluators\n#6333eba5e1101  # Implement evaluator for sparse outer products\n#663b9d314ae19\n#6655ef95fabee  # Properly detect FMA support on ARM\n#667fe25f3b8e3   # FMA has been wrongly disabled\n#668409547a0c8\n#6694304c73542   # merge default to tensors\n#67216047c8d4a   # merge default to tensors\n#67410a79ca3a3   # merge default to tensors\n#674b7271dffb5   # Generalized the gebp apis\n676bfdd9f3ac9   # Made the blocking computation aware of the l3 cache;<br/> Also optimized the blocking parameters to take<br/> into account the number of threads used for a computation.\n6782dde63499c   # generalized gemv\n6799f98650d0a   # ensured that contractions that can be reduced to a matrix vector product\n#6840918c51e60   # merge tensor\n684e972b55ec4   # change prefetching in gebp\n#68598604576d1   # merge index conversion\n68963eb0f6fe6   # clean blocking size computation\n689db05f2d01e   # rotating kernel for ARM only\n#6901b7e12847d   # result_of\n69226275b250a   # fix prefetching change for ARM\n692692136350b   # prefetching\n693a8ad8887bf   # blocking size strategy\n693bcf9bb5c1f   # avoid redundant pack_rhs\n6987550107028   # dynamic loop swapping\n69858740ce4c6   # rm dynamic loop swapping,<br/> adjust lhs's micro panel height to fully exploit L1 cache\n698cd3bbffa73   # blocking heuristic:<br/> block on the rhs in L1 if the lhs fit in L1.\n701488c15615a   # organize a little our default cache sizes,<br/> and use a saner default L1 outside of x86 (10% faster on Nexus 5)\n701e56aabf205   # Refactor computeProductBlockingSizes to make room<br/> for the possibility of using lookup tables\n701ca5c12587b   # Polish lookup tables generation\n7013589a9c115   # actual_panel_rows computation should always be resilient<br/> to parameters not consistent with the known L1 cache size, see comment\n70102babb9c0f   # Provide a empirical lookup table for blocking sizes measured on a Nexus 5.<br/> Only for float, only for Android on ARM 32bit for now.\n7088481dc21ea   # Bug 986: add support for coefficient-based<br/> product with 0 depth.\n709d7f51feb07   # Bug 992: don't select a 3p GEMM path with non-SIMD scalar types.\n759f9303cc7c5   # 3.3-alpha1\n765aba1eda71e   # help clang inlining\n770fe630c9873   # Improve numerical accuracy in LLT and triangular solve<br/> by using true scalar divisions (instead of x * (1/y))\n#8741d23430628   # Improved the matrix multiplication blocking in the case<br/> where mr is not a power of 2 (e.g on Haswell CPUs)\n878f629fe95c8   # Made the index type a template parameter to evaluateProductBlockingSizes.<br/> Use numext::mini and numext::maxi instead of <br/> std::min/std::max to compute blocking sizes.\n8975d51a7f12c   # Don't optimize the processing of the last rows of<br/> a matrix matrix product in cases that violate<br/> the assumptions made by the optimized code path.\n8986136f4fdd4   # Remove the rotating kernel.\n898e68e165a23   # Bug 256: enable vectorization with unaligned loads/stores.\n91466e99ab6a1   # Relax mixing-type constraints for binary coeff-wise operators\n91776236cdea4   # merge\n917101ea26f5e   # Include the cost of stores in unrolling\n921672076db5d   # Fix perf regression introduced in changeset e56aabf205\n9210fa9e4a15c   # Fix perf regression in dgemm introduced by changeset 5d51a7f12c\n936f6b3cf8de9   # 3.3-beta2\n944504a4404f1   # Optimize expression matching 'd?=a-b*c' as 'd?=a; d?=b*c;'\n95877e27fbeee   # 3.3-rc1\n959779774f98c   # Bug 1311: fix alignment logic in some cases<br/> of (scalar*small).lazyProduct(small)\n9729f9d8d2f62   # Disabled part of the matrix matrix peeling code<br/> that's incompatible with 512 bit registers\n979eeac81b8c0   # 3.3.0\n989c927af60ed   # Fix a performance regression in (mat*mat)*vec<br/> for which mat*mat was evaluated multiple times.\n994fe696022ec   # Operators += and -= do not resize!\n99466f65ccc36   # Ease compiler generating clean and efficient code in mat*vec\n9946a5fe86098   # Complete rewrite of column-major-matrix * vector product<br/> to deliver higher performance of modern CPU.\n99591003f3b86   # Improve performance of row-major-dense-matrix * vector products<br/> for recent CPUs.\n997eb621413c1   # Revert vec/y to vec*(1/y) in row-major TRSM\n10444bbc320468  # Bug 1435: fix aliasing issue in exressions like: A = C - B*A;\n1073624df50945  # Adds missing EIGEN_STRONG_INLINE to support MSVC<br/> properly inlining small vector calculations\n1094d428a199ab  # Bug 1562: optimize evaluation of small products<br/> of the form s*A*B by rewriting them as: s*(A.lazyProduct(B))<br/> to save a costly temporary.<br/> Measured speedup from 2x to 5x.\n1096de9e31a06d  # Introduce the macro ei_declare_local_nested_eval to<br/> help allocating on the stack local temporaries via alloca,<br/> and let outer-products makes a good use of it.\n11087b91c11207  # Bug 1578: Improve prefetching in matrix multiplication on MIPS.\n1153aa110e681b  # PR 526: Speed up multiplication of small, dynamically sized matrices\n11544ad359237a  # Vectorize row-by-row gebp loop iterations on 16 packets as well\n1157a476054879  # Bug 1624: improve matrix-matrix product on ARM 64, 20% speedup\n1160a4159dba08  # do not read buffers out of bounds\n1163c53eececb0  # Implement AVX512 vectorization of std::complex<float/double>\n11644e7746fe22  # Bug 1636: fix gemm performance issue with gcc>=6 and no FMA\n1164956678a4ef  # Bug 1515: disable gebp's 3pX4 micro kernel<br/> for MSVC<=19.14 because of register spilling.\n1165426bce7529  # fix EIGEN_GEBP_2PX4_SPILLING_WORKAROUND<br/> for non vectorized type, and non x86/64 target\n11660d90637838  # enable spilling workaround on architectures with SSE/AVX\n1166f159cf3d75  # Artificially increase l1-blocking size for AVX512.<br/> +10% speedup with current kernels.\n11686dd93f7e3b  # Make code compile again for older compilers.\n1175dbfcceabf5  # Bug: 1633: refactor gebp kernel and optimize for neon\n117670e133333d  # Bug 1661: fix regression in GEBP and AVX512\n11760f028f61cb  # GEBP: cleanup logic to choose between<br/> a 4 packets of 1 packet (=e118ce86fd+fix)\n1180de77bf5d6c  # gebp: Add new ½ and ¼ packet rows per (peeling) round on the lhs\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/gemm.cpp",
    "content": "#include \"gemm_common.h\"\n\nEIGEN_DONT_INLINE\nvoid gemm(const Mat &A, const Mat &B, Mat &C)\n{\n  C.noalias() += A * B;\n}\n\nint main(int argc, char **argv)\n{\n  return main_gemm(argc, argv, gemm);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/gemm_common.h",
    "content": "#include <iostream>\n#include <fstream>\n#include <vector>\n#include <string>\n#include \"eigen_src/Eigen/Core\"\n#include \"../BenchTimer.h\"\nusing namespace Eigen;\n\n#ifndef SCALAR\n#error SCALAR must be defined\n#endif\n\ntypedef SCALAR Scalar;\n\ntypedef Matrix<Scalar,Dynamic,Dynamic> Mat;\n\ntemplate<typename Func>\nEIGEN_DONT_INLINE\ndouble bench(long m, long n, long k, const Func& f)\n{\n  Mat A(m,k);\n  Mat B(k,n);\n  Mat C(m,n);\n  A.setRandom();\n  B.setRandom();\n  C.setZero();\n  \n  BenchTimer t;\n  \n  double up = 1e8*4/sizeof(Scalar);\n  double tm0 = 4, tm1 = 10;\n  if(NumTraits<Scalar>::IsComplex)\n  {\n    up /= 4;\n    tm0 = 2;\n    tm1 = 4;\n  }\n  \n  double flops = 2. * m * n * k;\n  long rep = std::max(1., std::min(100., up/flops) );\n  long tries = std::max(tm0, std::min(tm1, up/flops) );\n  \n  BENCH(t, tries, rep, f(A,B,C));\n  \n  return 1e-9 * rep * flops / t.best();\n}\n\ntemplate<typename Func>\nint main_gemm(int argc, char **argv, const Func& f)\n{\n  std::vector<double> results;\n  \n  std::string filename = std::string(\"gemm_settings.txt\");\n  if(argc>1)\n    filename = std::string(argv[1]);\n  std::ifstream settings(filename);\n  long m, n, k;\n  while(settings >> m >> n >> k)\n  {\n    //std::cerr << \"  Testing \" << m << \" \" << n << \" \" << k << std::endl;\n    results.push_back( bench(m, n, k, f) );\n  }\n  \n  std::cout << RowVectorXd::Map(results.data(), results.size());\n  \n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/gemm_settings.txt",
    "content": "8 8 8\n9 9 9\n24 24 24\n239 239 239\n240 240 240\n2400 24 24\n24 2400 24\n24 24 2400\n24 2400 2400\n2400 24 2400\n2400 2400 24\n2400 2400 64\n4800 23 160\n23 4800 160\n2400 2400 2400\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/gemm_square_settings.txt",
    "content": "8 8 8\n9 9 9\n12 12 12\n15 15 15\n16 16 16\n24 24 24\n102 102 102\n239 239 239\n240 240 240\n2400 2400 2400\n2463 2463 2463\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/gemv.cpp",
    "content": "#include \"gemv_common.h\"\n\nEIGEN_DONT_INLINE\nvoid gemv(const Mat &A, const Vec &B, Vec &C)\n{\n  C.noalias() += A * B;\n}\n\nint main(int argc, char **argv)\n{\n  return main_gemv(argc, argv, gemv);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/gemv_common.h",
    "content": "#include <iostream>\n#include <fstream>\n#include <vector>\n#include <string>\n#include <functional>\n#include \"eigen_src/Eigen/Core\"\n#include \"../BenchTimer.h\"\nusing namespace Eigen;\n\n#ifndef SCALAR\n#error SCALAR must be defined\n#endif\n\ntypedef SCALAR Scalar;\n\ntypedef Matrix<Scalar,Dynamic,Dynamic> Mat;\ntypedef Matrix<Scalar,Dynamic,1>       Vec;\n\ntemplate<typename Func>\nEIGEN_DONT_INLINE\ndouble bench(long m, long n, Func &f)\n{\n  Mat A(m,n);\n  Vec B(n);\n  Vec C(m);\n  A.setRandom();\n  B.setRandom();\n  C.setRandom();\n\n  BenchTimer t;\n\n  double up = 1e8/sizeof(Scalar);\n  double tm0 = 4, tm1 = 10;\n  if(NumTraits<Scalar>::IsComplex)\n  {\n    up /= 4;\n    tm0 = 2;\n    tm1 = 4;\n  }\n\n  double flops = 2. * m * n;\n  long rep = std::max(1., std::min(100., up/flops) );\n  long tries = std::max(tm0, std::min(tm1, up/flops) );\n\n  BENCH(t, tries, rep, f(A,B,C));\n\n  return 1e-9 * rep * flops / t.best();\n}\n\ntemplate<typename Func>\nint main_gemv(int argc, char **argv, Func& f)\n{\n  std::vector<double> results;\n\n  std::string filename = std::string(\"gemv_settings.txt\");\n  if(argc>1)\n    filename = std::string(argv[1]);\n  std::ifstream settings(filename);\n  long m, n;\n  while(settings >> m >> n)\n  {\n    //std::cerr << \"  Testing \" << m << \" \" << n << std::endl;\n    results.push_back( bench(m, n, f) );\n  }\n\n  std::cout << RowVectorXd::Map(results.data(), results.size());\n\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/gemv_settings.txt",
    "content": "8 8\n9 9\n24 24\n239 239\n240 240\n2400 24\n24 2400\n24 240\n2400 2400\n4800 23\n23 4800\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/gemv_square_settings.txt",
    "content": "8 8\n9 9\n12 12\n15 15\n16 16\n24 24\n53 53\n74 74\n102 102\n239 239\n240 240\n2400 2400\n2463 2463\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/gemvt.cpp",
    "content": "#include \"gemv_common.h\"\n\nEIGEN_DONT_INLINE\nvoid gemv(const Mat &A, Vec &B, const Vec &C)\n{\n  B.noalias() += A.transpose() * C;\n}\n\nint main(int argc, char **argv)\n{\n  return main_gemv(argc, argv, gemv);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/lazy_gemm.cpp",
    "content": "#include <iostream>\n#include <fstream>\n#include <vector>\n#include <Eigen/Core>\n#include \"../../BenchTimer.h\"\nusing namespace Eigen;\n\n#ifndef SCALAR\n#error SCALAR must be defined\n#endif\n\ntypedef SCALAR Scalar;\n\ntemplate<typename MatA, typename MatB, typename MatC>\nEIGEN_DONT_INLINE\nvoid lazy_gemm(const MatA &A, const MatB &B, MatC &C)\n{\n//   escape((void*)A.data());\n//   escape((void*)B.data());\n  C.noalias() += A.lazyProduct(B);\n//   escape((void*)C.data());\n}\n\ntemplate<int m, int n, int k, int TA>\nEIGEN_DONT_INLINE\ndouble bench()\n{\n  typedef Matrix<Scalar,m,k,TA> MatA;\n  typedef Matrix<Scalar,k,n> MatB;\n  typedef Matrix<Scalar,m,n> MatC;\n\n  MatA A(m,k);\n  MatB B(k,n);\n  MatC C(m,n);\n  A.setRandom();\n  B.setRandom();\n  C.setZero();\n\n  BenchTimer t;\n\n  double up = 1e7*4/sizeof(Scalar);\n  double tm0 = 10, tm1 = 20;\n\n  double flops = 2. * m * n * k;\n  long rep = std::max(10., std::min(10000., up/flops) );\n  long tries = std::max(tm0, std::min(tm1, up/flops) );\n\n  BENCH(t, tries, rep, lazy_gemm(A,B,C));\n\n  return 1e-9 * rep * flops / t.best();\n}\n\ntemplate<int m, int n, int k>\ndouble bench_t(int t)\n{\n  if(t)\n    return bench<m,n,k,RowMajor>();\n  else\n    return bench<m,n,k,0>();\n}\n\nEIGEN_DONT_INLINE\ndouble bench_mnk(int m, int n, int k, int t)\n{\n  int id = m*10000 + n*100 + k;\n  switch(id) {\n    case  10101 : return bench_t< 1, 1, 1>(t); break;\n    case  20202 : return bench_t< 2, 2, 2>(t); break;\n    case  30303 : return bench_t< 3, 3, 3>(t); break;\n    case  40404 : return bench_t< 4, 4, 4>(t); break;\n    case  50505 : return bench_t< 5, 5, 5>(t); break;\n    case  60606 : return bench_t< 6, 6, 6>(t); break;\n    case  70707 : return bench_t< 7, 7, 7>(t); break;\n    case  80808 : return bench_t< 8, 8, 8>(t); break;\n    case  90909 : return bench_t< 9, 9, 9>(t); break;\n    case 101010 : return bench_t<10,10,10>(t); break;\n    case 111111 : return bench_t<11,11,11>(t); break;\n    case 121212 : return bench_t<12,12,12>(t); break;\n  }\n  return 0;\n}\n\nint main(int argc, char **argv)\n{\n  std::vector<double> results;\n  \n  std::string filename = std::string(\"lazy_gemm_settings.txt\");\n  if(argc>1)\n    filename = std::string(argv[1]);\n  std::ifstream settings(filename);\n  long m, n, k, t;\n  while(settings >> m >> n >> k >> t)\n  {\n    //std::cerr << \"  Testing \" << m << \" \" << n << \" \" << k << std::endl;\n    results.push_back( bench_mnk(m, n, k, t) );\n  }\n  \n  std::cout << RowVectorXd::Map(results.data(), results.size());\n  \n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/lazy_gemm_settings.txt",
    "content": "1 1 1 0\n2 2 2 0\n3 3 3 0\n4 4 4 0\n4 4 4 1\n5 5 5 0\n6 6 6 0\n7 7 7 0\n7 7 7 1\n8 8 8 0\n9 9 9 0\n10 10 10 0\n11 11 11 0\n12 12 12 0\n12 12 12 1\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/llt.cpp",
    "content": "#include \"gemm_common.h\"\n#include <Eigen/Cholesky>\n\nEIGEN_DONT_INLINE\nvoid llt(const Mat &A, const Mat &B, Mat &C)\n{\n  C = A;\n  C.diagonal().array() += 1000;\n  Eigen::internal::llt_inplace<Mat::Scalar, Lower>::blocked(C);\n}\n\nint main(int argc, char **argv)\n{\n  return main_gemm(argc, argv, llt);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/make_plot.sh",
    "content": "#!/bin/bash\n\n# base name of the bench\n# it reads $1.out\n# and generates $1.pdf\nWHAT=$1\nbench=$2\nsettings_file=$3\n\nheader=\"rev \"\nwhile read line\ndo\n  if [ ! -z '$line' ]; then\n    header=\"$header  \\\"$line\\\"\"\n  fi\ndone < $settings_file\n\necho $header > $WHAT.out.header\ncat $WHAT.out >> $WHAT.out.header\n\n\necho \"set title '$WHAT'\" > $WHAT.gnuplot\necho \"set key autotitle columnhead outside \" >> $WHAT.gnuplot\necho \"set xtics rotate 1\" >> $WHAT.gnuplot\n\necho \"set term pdf color rounded enhanced fontscale 0.35 size 7in,5in\" >> $WHAT.gnuplot\necho set output \"'\"$WHAT.pdf\"'\" >> $WHAT.gnuplot\n\ncol=`cat $settings_file | wc -l`\necho \"plot for [col=2:$col+1] '$WHAT.out.header' using 0:col:xticlabels(1) with lines\" >> $WHAT.gnuplot\necho \" \" >>  $WHAT.gnuplot\n\ngnuplot -persist < $WHAT.gnuplot\n\n# generate a png file (thumbnail)\nconvert -colors 256 -background white -density 300 -resize 300  -quality 0 $WHAT.pdf -background white -flatten $WHAT.png\n\n# clean\nrm $WHAT.out.header $WHAT.gnuplot\n\n\n# generate html/svg graph\n\necho \" \" > $WHAT.html\ncat resources/chart_header.html > $WHAT.html\necho 'var customSettings = {\"TITLE\":\"\",\"SUBTITLE\":\"\",\"XLABEL\":\"\",\"YLABEL\":\"\"};' >> $WHAT.html\n#  'data' is an array of datasets (i.e. curves), each of which is an object of the form\n#  {\n#    key: <name of the curve>,\n#    color: <optional color of the curve>,\n#    values: [{\n#        r: <revision number>,\n#        v: <GFlops>\n#    }]\n#  }\necho 'var data = [' >> $WHAT.html\n\ncol=2\nwhile read line\ndo\n  if [ ! -z '$line' ]; then\n    header=\"$header  \\\"$line\\\"\"\n    echo '{\"key\":\"'$line'\",\"values\":[' >> $WHAT.html\n    i=0\n    while read line2\n    do\n      if [ ! -z \"$line2\" ]; then\n        val=`echo $line2 | cut -s -f $col -d ' '`\n        if [ -n \"$val\" ]; then # skip build failures\n          echo '{\"r\":'$i',\"v\":'$val'},' >> $WHAT.html\n        fi\n      fi\n      ((i++))\n    done < $WHAT.out\n    echo ']},'  >> $WHAT.html\n  fi\n  ((col++))\ndone < $settings_file\necho '];'  >> $WHAT.html\n\necho 'var changesets = [' >> $WHAT.html\nwhile read line2\ndo\n  if [ ! -z '$line2' ]; then\n    echo '\"'`echo $line2 | cut -f 1 -d ' '`'\",' >> $WHAT.html\n  fi\ndone < $WHAT.out\necho '];'  >> $WHAT.html\n\necho 'var changesets_details = [' >> $WHAT.html\nwhile read line2\ndo\n  if [ ! -z '$line2' ]; then\n    num=`echo \"$line2\" | cut -f 1 -d ' '`\n    comment=`grep \":$num\" changesets.txt | cut -f 2 -d '#'`\n    echo '\"'\"$comment\"'\",' >> $WHAT.html\n  fi\ndone < $WHAT.out\necho '];'  >> $WHAT.html\n\necho 'var changesets_count = [' >> $WHAT.html\ni=0\nwhile read line2\ndo\n  if [ ! -z '$line2' ]; then\n    echo $i ',' >> $WHAT.html\n  fi\n  ((i++))\ndone < $WHAT.out\necho '];'  >> $WHAT.html\n\ncat resources/chart_footer.html >> $WHAT.html\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/resources/chart_footer.html",
    "content": "      /* setup the chart and its options */                                                                                \n      var chart = nv.models.lineChart()                                                                                    \n                    .color(d3.scale.category10().range())                                                                  \n                    .margin({left: 75, bottom: 100})                                                                        \n                    .forceX([0]).forceY([0]);                                                                              \n                                                                                                                           \n      chart.x(function(datum){ return datum.r; })                                                                          \n           .xAxis.options({                                                                                                \n             axisLabel: customSettings.XLABEL || 'Changeset',\n             tickFormat: d3.format('.0f')                                                                                  \n           });\n      chart.xAxis\n        .tickValues(changesets_count)\n        .tickFormat(function(d){return changesets[d]})\n        .rotateLabels(-90);\n                                                                                                                                                                                                       \n      chart.y(function(datum){ return datum.v; })                                                    \n            .yAxis.options({                                                                                              \n              axisLabel: customSettings.YLABEL || 'GFlops'/*,\n              tickFormat: function(val){ return d3.format('.0f')(val) + ' GFlops'; }*/\n            });\n      \n      chart.tooltip.headerFormatter(function(d) { return changesets[d]\n        + ' <p style=\"font-weight:normal;text-align: left;\">'\n        + changesets_details[d] + \"</p>\"; });\n\n      //chart.useInteractiveGuideline(true);\n      d3.select('#chart').datum(data).call(chart);                                                                         \n      var plot = d3.select('#chart > g');                                                                                  \n                                                                                                                           \n      /* setup the title */                                                                                                \n      plot.append('text')                                                                                                  \n          .style('font-size', '24px')                                                                                      \n          .attr('text-anchor', 'middle').attr('x', '50%').attr('y', '20px')                                                \n          .text(customSettings.TITLE || '');                                                                                                                   \n                                                                                                                           \n      /* ensure the chart is responsive */                                                                                 \n      nv.utils.windowResize(chart.update);                                                                                 \n    </script>                                                                                                              \n  </body>                                                                                                                  \n</html>  \n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/resources/chart_header.html",
    "content": "\n<!DOCTYPE html>                                                                                                            \n<html>                                                                                                                     \n  <head>                                                                                                                   \n    <meta charset='utf-8'>                                                                                                 \n    <style>.nvd3 .nv-axis line,.nvd3 .nv-axis path{fill:none;shape-rendering:crispEdges}.nv-brush .extent,.nvd3 .background path,.nvd3 .nv-axis line,.nvd3 .nv-axis path{shape-rendering:crispEdges}.nv-distx,.nv-disty,.nv-noninteractive,.nvd3 .nv-axis,.nvd3.nv-pie .nv-label,.nvd3.nv-sparklineplus g.nv-hoverValue{pointer-events:none}.nvtooltip,svg.nvd3-svg{display:block;-webkit-touch-callout:none;-khtml-user-select:none}.nvd3 .nv-axis{opacity:1}.nvd3 .nv-axis.nv-disabled,.nvd3 .nv-controlsWrap .nv-legend .nv-check-box .nv-check{opacity:0}.nvd3 .nv-axis path{stroke:#000;stroke-opacity:.75}.nvd3 .nv-axis path.domain{stroke-opacity:.75}.nvd3 .nv-axis.nv-x path.domain{stroke-opacity:0}.nvd3 .nv-axis line{stroke:#e5e5e5}.nvd3 .nv-axis .zero line, .nvd3 .nv-axis line.zero{stroke-opacity:.75}.nvd3 .nv-axis .nv-axisMaxMin text{font-weight:700}.nvd3 .x .nv-axis .nv-axisMaxMin text,.nvd3 .x2 .nv-axis .nv-axisMaxMin text,.nvd3 .x3 .nv-axis .nv-axisMaxMin text{text-anchor:middle}.nvd3 .nv-bars rect{fill-opacity:.75;transition:fill-opacity 250ms linear;-moz-transition:fill-opacity 250ms linear;-webkit-transition:fill-opacity 250ms linear}.nvd3 .nv-bars rect.hover{fill-opacity:1}.nvd3 .nv-bars .hover rect{fill:#add8e6}.nvd3 .nv-bars text{fill:transparent}.nvd3 .nv-bars .hover text{fill:rgba(0,0,0,1)}.nvd3 .nv-discretebar .nv-groups rect,.nvd3 .nv-multibar .nv-groups rect,.nvd3 .nv-multibarHorizontal .nv-groups rect{stroke-opacity:0;transition:fill-opacity 250ms linear;-moz-transition:fill-opacity 250ms linear;-webkit-transition:fill-opacity 250ms linear}.nvd3 .nv-candlestickBar .nv-ticks rect:hover,.nvd3 .nv-discretebar .nv-groups rect:hover,.nvd3 .nv-multibar .nv-groups rect:hover,.nvd3 .nv-multibarHorizontal .nv-groups rect:hover{fill-opacity:1}.nvd3 .nv-discretebar .nv-groups text,.nvd3 .nv-multibarHorizontal .nv-groups text{font-weight:700;fill:rgba(0,0,0,1);stroke:transparent}.nvd3 .nv-boxplot circle{fill-opacity:.5}.nvd3 .nv-boxplot circle:hover,.nvd3 .nv-boxplot rect:hover{fill-opacity:1}.nvd3 line.nv-boxplot-median{stroke:#000}.nv-boxplot-tick:hover{stroke-width:2.5px}.nvd3.nv-bullet{font:10px sans-serif}.nvd3.nv-bullet .nv-measure{fill-opacity:.8}.nvd3.nv-bullet .nv-measure:hover{fill-opacity:1}.nvd3.nv-bullet .nv-marker{stroke:#000;stroke-width:2px}.nvd3.nv-bullet .nv-markerTriangle{stroke:#000;fill:#fff;stroke-width:1.5px}.nvd3.nv-bullet .nv-markerLine{stroke:#000;stroke-width:1.5px}.nvd3.nv-bullet .nv-tick line{stroke:#666;stroke-width:.5px}.nvd3.nv-bullet .nv-range.nv-s0{fill:#eee}.nvd3.nv-bullet .nv-range.nv-s1{fill:#ddd}.nvd3.nv-bullet .nv-range.nv-s2{fill:#ccc}.nvd3.nv-bullet .nv-title{font-size:14px;font-weight:700}.nvd3.nv-bullet .nv-subtitle{fill:#999}.nvd3.nv-bullet .nv-range{fill:#bababa;fill-opacity:.4}.nvd3.nv-bullet .nv-range:hover{fill-opacity:.7}.nvd3.nv-candlestickBar .nv-ticks .nv-tick{stroke-width:1px}.nvd3.nv-candlestickBar .nv-ticks .nv-tick.hover{stroke-width:2px}.nvd3.nv-candlestickBar .nv-ticks .nv-tick.positive rect{stroke:#2ca02c;fill:#2ca02c}.nvd3.nv-candlestickBar .nv-ticks .nv-tick.negative rect{stroke:#d62728;fill:#d62728}.with-transitions .nv-candlestickBar .nv-ticks .nv-tick{transition:stroke-width 250ms linear,stroke-opacity 250ms linear;-moz-transition:stroke-width 250ms linear,stroke-opacity 250ms linear;-webkit-transition:stroke-width 250ms linear,stroke-opacity 250ms linear}.nvd3.nv-candlestickBar .nv-ticks line{stroke:#333}.nv-force-node{stroke:#fff;stroke-width:1.5px}.nv-force-link{stroke:#999;stroke-opacity:.6}.nv-force-node text{stroke-width:0}.nvd3 .nv-check-box .nv-box{fill-opacity:0;stroke-width:2}.nvd3 .nv-check-box .nv-check{fill-opacity:0;stroke-width:4}.nvd3 .nv-series.nv-disabled .nv-check-box .nv-check{fill-opacity:0;stroke-opacity:0}.nvd3.nv-linePlusBar .nv-bar rect{fill-opacity:.75}.nvd3.nv-linePlusBar .nv-bar rect:hover{fill-opacity:1}.nvd3 .nv-groups path.nv-line{fill:none}.nvd3 .nv-groups path.nv-area{stroke:none}.nvd3.nv-line .nvd3.nv-scatter .nv-groups .nv-point{fill-opacity:0;stroke-opacity:0}.nvd3.nv-scatter.nv-single-point .nv-groups .nv-point{fill-opacity:.5!important;stroke-opacity:.5!important}.with-transitions .nvd3 .nv-groups .nv-point{transition:stroke-width 250ms linear,stroke-opacity 250ms linear;-moz-transition:stroke-width 250ms linear,stroke-opacity 250ms linear;-webkit-transition:stroke-width 250ms linear,stroke-opacity 250ms linear}.nvd3 .nv-groups .nv-point.hover,.nvd3.nv-scatter .nv-groups .nv-point.hover{stroke-width:7px;fill-opacity:.95!important;stroke-opacity:.95!important}.nvd3 .nv-point-paths path{stroke:#aaa;stroke-opacity:0;fill:#eee;fill-opacity:0}.nvd3 .nv-indexLine{cursor:ew-resize}svg.nvd3-svg{-webkit-user-select:none;-ms-user-select:none;-moz-user-select:none;user-select:none;width:100%;height:100%}.nvtooltip.with-3d-shadow,.with-3d-shadow .nvtooltip{-moz-box-shadow:0 5px 10px rgba(0,0,0,.2);-webkit-box-shadow:0 5px 10px rgba(0,0,0,.2);box-shadow:0 5px 10px rgba(0,0,0,.2);-webkit-border-radius:5px;-moz-border-radius:5px;border-radius:5px}.nvd3 text{font:400 12px Arial}.nvd3 .title{font:700 14px Arial}.nvd3 .nv-background{fill:#fff;fill-opacity:0}.nvd3.nv-noData{font-size:18px;font-weight:700}.nv-brush .extent{fill-opacity:.125}.nv-brush .resize path{fill:#eee;stroke:#666}.nvd3 .nv-legend .nv-series{cursor:pointer}.nvd3 .nv-legend .nv-disabled circle{fill-opacity:0}.nvd3 .nv-brush .extent{fill-opacity:0!important}.nvd3 .nv-brushBackground rect{stroke:#000;stroke-width:.4;fill:#fff;fill-opacity:.7}@media print{.nvd3 text{stroke-width:0;fill-opacity:1}}.nvd3.nv-ohlcBar .nv-ticks .nv-tick{stroke-width:1px}.nvd3.nv-ohlcBar .nv-ticks .nv-tick.hover{stroke-width:2px}.nvd3.nv-ohlcBar .nv-ticks .nv-tick.positive{stroke:#2ca02c}.nvd3.nv-ohlcBar .nv-ticks .nv-tick.negative{stroke:#d62728}.nvd3 .background path{fill:none;stroke:#EEE;stroke-opacity:.4}.nvd3 .foreground path{fill:none;stroke-opacity:.7}.nvd3 .nv-parallelCoordinates-brush .extent{fill:#fff;fill-opacity:.6;stroke:gray;shape-rendering:crispEdges}.nvd3 .nv-parallelCoordinates .hover{fill-opacity:1;stroke-width:3px}.nvd3 .missingValuesline line{fill:none;stroke:#000;stroke-width:1;stroke-opacity:1;stroke-dasharray:5,5}.nvd3.nv-pie .nv-pie-title{font-size:24px;fill:rgba(19,196,249,.59)}.nvd3.nv-pie .nv-slice text{stroke:#000;stroke-width:0}.nvd3.nv-pie path{transition:fill-opacity 250ms linear,stroke-width 250ms linear,stroke-opacity 250ms linear;-moz-transition:fill-opacity 250ms linear,stroke-width 250ms linear,stroke-opacity 250ms linear;-webkit-transition:fill-opacity 250ms linear,stroke-width 250ms linear,stroke-opacity 250ms linear;stroke:#fff;stroke-width:1px;stroke-opacity:1;fill-opacity:.7}.nvd3.nv-pie .hover path{fill-opacity:1}.nvd3.nv-pie .nv-label rect{fill-opacity:0;stroke-opacity:0}.nvd3 .nv-groups .nv-point.hover{stroke-width:20px;stroke-opacity:.5}.nvd3 .nv-scatter .nv-point.hover{fill-opacity:1}.nvd3.nv-sparkline path{fill:none}.nvd3.nv-sparklineplus .nv-hoverValue line{stroke:#333;stroke-width:1.5px}.nvd3.nv-sparklineplus,.nvd3.nv-sparklineplus g{pointer-events:all}.nvd3 .nv-interactiveGuideLine,.nvtooltip{pointer-events:none}.nvd3 .nv-hoverArea{fill-opacity:0;stroke-opacity:0}.nvd3.nv-sparklineplus .nv-xValue,.nvd3.nv-sparklineplus .nv-yValue{stroke-width:0;font-size:.9em;font-weight:400}.nvd3.nv-sparklineplus .nv-yValue{stroke:#f66}.nvd3.nv-sparklineplus .nv-maxValue{stroke:#2ca02c;fill:#2ca02c}.nvd3.nv-sparklineplus .nv-minValue{stroke:#d62728;fill:#d62728}.nvd3.nv-sparklineplus .nv-currentValue{font-weight:700;font-size:1.1em}.nvtooltip h3,.nvtooltip table td.key{font-weight:400}.nvd3.nv-stackedarea path.nv-area{fill-opacity:.7;stroke-opacity:0;transition:fill-opacity 250ms linear,stroke-opacity 250ms linear;-moz-transition:fill-opacity 250ms linear,stroke-opacity 250ms linear;-webkit-transition:fill-opacity 250ms linear,stroke-opacity 250ms linear}.nvd3.nv-stackedarea path.nv-area.hover{fill-opacity:.9}.nvd3.nv-stackedarea .nv-groups .nv-point{stroke-opacity:0;fill-opacity:0}.nvtooltip{position:absolute;color:rgba(0,0,0,1);padding:1px;z-index:10000;font-family:Arial;font-size:13px;text-align:left;white-space:nowrap;-webkit-user-select:none;-moz-user-select:none;-ms-user-select:none;user-select:none;background:rgba(255,255,255,.8);border:1px solid rgba(0,0,0,.5);border-radius:4px}.nvtooltip h3,.nvtooltip p{margin:0;text-align:center}.nvtooltip.with-transitions,.with-transitions .nvtooltip{transition:opacity 50ms linear;-moz-transition:opacity 50ms linear;-webkit-transition:opacity 50ms linear;transition-delay:200ms;-moz-transition-delay:200ms;-webkit-transition-delay:200ms}.nvtooltip.x-nvtooltip,.nvtooltip.y-nvtooltip{padding:8px}.nvtooltip h3{padding:4px 14px;line-height:18px;background-color:rgba(247,247,247,.75);color:rgba(0,0,0,1);border-bottom:1px solid #ebebeb;-webkit-border-radius:5px 5px 0 0;-moz-border-radius:5px 5px 0 0;border-radius:5px 5px 0 0}.nvtooltip p{padding:5px 14px}.nvtooltip span{display:inline-block;margin:2px 0}.nvtooltip table{margin:6px;border-spacing:0}.nvtooltip table td{padding:2px 9px 2px 0;vertical-align:middle}.nvtooltip table td.key.total{font-weight:700}.nvtooltip table td.value{text-align:right;font-weight:700}.nvtooltip table td.percent{color:#a9a9a9}.nvtooltip table tr.highlight td{padding:1px 9px 1px 0;border-bottom-style:solid;border-bottom-width:1px;border-top-style:solid;border-top-width:1px}.nvtooltip table td.legend-color-guide div{vertical-align:middle;width:12px;height:12px;border:1px solid #999}.nvtooltip .footer{padding:3px;text-align:center}.nvtooltip-pending-removal{pointer-events:none;display:none}.nvd3 line.nv-guideline{stroke:#ccc}</style>                                                             \n    <style>                                                                                                                \n      * {                                                                                                                  \n        box-sizing: border-box;                                                                                            \n      }                                                                                                                    \n      html, body {                                                                                                         \n        position: relative;                                                                                                \n        height: 100%;                                                                                                      \n        width: 100%;                                                                                                       \n        border: 0;                                                                                                         \n        margin: 0;                                                                                                         \n        padding: 0;                                                                                                        \n        font-size: 0;                                                                                                      \n      }                                                                                                                    \n      svg g {                                                                                                              \n        clip-path: none;                                                                                                   \n      }                                                                                                                    \n      svg text {                                                                                                           \n        fill: #333;                                                                                                        \n      }                                                                                                                    \n      .nv-axislabel {                                                                                                      \n        font-size: 16px !important;                                                                                        \n      }                                                                                                                    \n      .control {                                                                                                           \n        cursor: pointer;                                                                                                   \n        visibility: hidden;                                                                                                \n        pointer-events: visible;                                                                                           \n      }                                                                                                                    \n      @media (min-width: 768px) {                                                                                          \n        .control {                                                                                                         \n          visibility: visible;                                                                                             \n        }                                                                                                                  \n      }                                                                                                                    \n    </style>                                                                                                               \n    <script src=\"s1.js\"></script>                                                              \n    <script src=\"s2.js\"></script>                                                            \n  </head>                                                                                                                  \n  <body>                                                                                                                   \n    <svg id='chart'></svg> \n    <script type='text/javascript'>\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/resources/footer.html",
    "content": "</table>\n</body>\n</html>\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/resources/header.html",
    "content": "<!DOCTYPE html PUBLIC \"-//W3C//DTD XHTML 1.0 Transitional//EN\" \"http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd\">\n<html xmlns=\"http://www.w3.org/1999/xhtml\">\n<head>\n<meta http-equiv=\"Content-Type\" content=\"text/html; charset=utf-8\" />\n<title>Eigen performance monitoring</title>\n<style type=\"text/css\">\n\nbody\n{\n background:#fff;\n}\nth {\n\n}\nimg\n{\n width:auto;\n box-shadow:0px 0px 20px #cecece;\n margin: 20px 20px  20px  20px;\n  -moz-transform: scale(1);\n -moz-transition-duration: 0.4s;\n -webkit-transition-duration: 0.4s;\n -webkit-transform: scale(1);\n\n -ms-transform: scale(1);\n -ms-transition-duration: 0.4s;\n}\nimg:hover\n{\nbox-shadow: 5px 5px 20px #dcdcdc;\n -moz-transform: scale(1.1);\n -moz-transition-duration: 0.4s;\n -webkit-transition-duration: 0.4s;\n -webkit-transform: scale(1.1);\n\n -ms-transform: scale(1.1);\n -ms-transition-duration: 0.4s;\n\n}\n</style>\n</head>\n<body>\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/resources/s1.js",
    "content": "!function(){function n(n){return n&&(n.ownerDocument||n.document||n).documentElement}function t(n){return n&&(n.ownerDocument&&n.ownerDocument.defaultView||n.document&&n||n.defaultView)}function e(n,t){return t>n?-1:n>t?1:n>=t?0:NaN}function r(n){return null===n?NaN:+n}function i(n){return!isNaN(n)}function u(n){return{left:function(t,e,r,i){for(arguments.length<3&&(r=0),arguments.length<4&&(i=t.length);i>r;){var u=r+i>>>1;n(t[u],e)<0?r=u+1:i=u}return r},right:function(t,e,r,i){for(arguments.length<3&&(r=0),arguments.length<4&&(i=t.length);i>r;){var u=r+i>>>1;n(t[u],e)>0?i=u:r=u+1}return r}}}function o(n){return n.length}function a(n){for(var t=1;n*t%1;)t*=10;return t}function l(n,t){for(var e in t)Object.defineProperty(n.prototype,e,{value:t[e],enumerable:!1})}function c(){this._=Object.create(null)}function f(n){return(n+=\"\")===bo||n[0]===_o?_o+n:n}function s(n){return(n+=\"\")[0]===_o?n.slice(1):n}function h(n){return f(n)in this._}function p(n){return(n=f(n))in this._&&delete this._[n]}function g(){var n=[];for(var t in this._)n.push(s(t));return n}function v(){var n=0;for(var t in this._)++n;return n}function d(){for(var n in this._)return!1;return!0}function y(){this._=Object.create(null)}function m(n){return n}function M(n,t,e){return function(){var r=e.apply(t,arguments);return r===t?n:r}}function x(n,t){if(t in n)return t;t=t.charAt(0).toUpperCase()+t.slice(1);for(var e=0,r=wo.length;r>e;++e){var i=wo[e]+t;if(i in n)return i}}function b(){}function _(){}function w(n){function t(){for(var t,r=e,i=-1,u=r.length;++i<u;)(t=r[i].on)&&t.apply(this,arguments);return n}var e=[],r=new c;return t.on=function(t,i){var u,o=r.get(t);return arguments.length<2?o&&o.on:(o&&(o.on=null,e=e.slice(0,u=e.indexOf(o)).concat(e.slice(u+1)),r.remove(t)),i&&e.push(r.set(t,{on:i})),n)},t}function S(){ao.event.preventDefault()}function k(){for(var n,t=ao.event;n=t.sourceEvent;)t=n;return t}function N(n){for(var t=new _,e=0,r=arguments.length;++e<r;)t[arguments[e]]=w(t);return t.of=function(e,r){return function(i){try{var u=i.sourceEvent=ao.event;i.target=n,ao.event=i,t[i.type].apply(e,r)}finally{ao.event=u}}},t}function E(n){return ko(n,Co),n}function A(n){return\"function\"==typeof n?n:function(){return No(n,this)}}function C(n){return\"function\"==typeof n?n:function(){return Eo(n,this)}}function z(n,t){function e(){this.removeAttribute(n)}function r(){this.removeAttributeNS(n.space,n.local)}function i(){this.setAttribute(n,t)}function u(){this.setAttributeNS(n.space,n.local,t)}function o(){var e=t.apply(this,arguments);null==e?this.removeAttribute(n):this.setAttribute(n,e)}function a(){var e=t.apply(this,arguments);null==e?this.removeAttributeNS(n.space,n.local):this.setAttributeNS(n.space,n.local,e)}return n=ao.ns.qualify(n),null==t?n.local?r:e:\"function\"==typeof t?n.local?a:o:n.local?u:i}function L(n){return n.trim().replace(/\\s+/g,\" \")}function q(n){return new RegExp(\"(?:^|\\\\s+)\"+ao.requote(n)+\"(?:\\\\s+|$)\",\"g\")}function T(n){return(n+\"\").trim().split(/^|\\s+/)}function R(n,t){function e(){for(var e=-1;++e<i;)n[e](this,t)}function r(){for(var e=-1,r=t.apply(this,arguments);++e<i;)n[e](this,r)}n=T(n).map(D);var i=n.length;return\"function\"==typeof t?r:e}function D(n){var t=q(n);return function(e,r){if(i=e.classList)return r?i.add(n):i.remove(n);var i=e.getAttribute(\"class\")||\"\";r?(t.lastIndex=0,t.test(i)||e.setAttribute(\"class\",L(i+\" \"+n))):e.setAttribute(\"class\",L(i.replace(t,\" \")))}}function P(n,t,e){function r(){this.style.removeProperty(n)}function i(){this.style.setProperty(n,t,e)}function u(){var r=t.apply(this,arguments);null==r?this.style.removeProperty(n):this.style.setProperty(n,r,e)}return null==t?r:\"function\"==typeof t?u:i}function U(n,t){function e(){delete this[n]}function r(){this[n]=t}function i(){var e=t.apply(this,arguments);null==e?delete this[n]:this[n]=e}return null==t?e:\"function\"==typeof t?i:r}function j(n){function t(){var t=this.ownerDocument,e=this.namespaceURI;return e===zo&&t.documentElement.namespaceURI===zo?t.createElement(n):t.createElementNS(e,n)}function e(){return this.ownerDocument.createElementNS(n.space,n.local)}return\"function\"==typeof n?n:(n=ao.ns.qualify(n)).local?e:t}function F(){var n=this.parentNode;n&&n.removeChild(this)}function H(n){return{__data__:n}}function O(n){return function(){return Ao(this,n)}}function I(n){return arguments.length||(n=e),function(t,e){return t&&e?n(t.__data__,e.__data__):!t-!e}}function Y(n,t){for(var e=0,r=n.length;r>e;e++)for(var i,u=n[e],o=0,a=u.length;a>o;o++)(i=u[o])&&t(i,o,e);return n}function Z(n){return ko(n,qo),n}function V(n){var t,e;return function(r,i,u){var o,a=n[u].update,l=a.length;for(u!=e&&(e=u,t=0),i>=t&&(t=i+1);!(o=a[t])&&++t<l;);return o}}function X(n,t,e){function r(){var t=this[o];t&&(this.removeEventListener(n,t,t.$),delete this[o])}function i(){var i=l(t,co(arguments));r.call(this),this.addEventListener(n,this[o]=i,i.$=e),i._=t}function u(){var t,e=new RegExp(\"^__on([^.]+)\"+ao.requote(n)+\"$\");for(var r in this)if(t=r.match(e)){var i=this[r];this.removeEventListener(t[1],i,i.$),delete this[r]}}var o=\"__on\"+n,a=n.indexOf(\".\"),l=$;a>0&&(n=n.slice(0,a));var c=To.get(n);return c&&(n=c,l=B),a?t?i:r:t?b:u}function $(n,t){return function(e){var r=ao.event;ao.event=e,t[0]=this.__data__;try{n.apply(this,t)}finally{ao.event=r}}}function B(n,t){var e=$(n,t);return function(n){var t=this,r=n.relatedTarget;r&&(r===t||8&r.compareDocumentPosition(t))||e.call(t,n)}}function W(e){var r=\".dragsuppress-\"+ ++Do,i=\"click\"+r,u=ao.select(t(e)).on(\"touchmove\"+r,S).on(\"dragstart\"+r,S).on(\"selectstart\"+r,S);if(null==Ro&&(Ro=\"onselectstart\"in e?!1:x(e.style,\"userSelect\")),Ro){var o=n(e).style,a=o[Ro];o[Ro]=\"none\"}return function(n){if(u.on(r,null),Ro&&(o[Ro]=a),n){var t=function(){u.on(i,null)};u.on(i,function(){S(),t()},!0),setTimeout(t,0)}}}function J(n,e){e.changedTouches&&(e=e.changedTouches[0]);var r=n.ownerSVGElement||n;if(r.createSVGPoint){var i=r.createSVGPoint();if(0>Po){var u=t(n);if(u.scrollX||u.scrollY){r=ao.select(\"body\").append(\"svg\").style({position:\"absolute\",top:0,left:0,margin:0,padding:0,border:\"none\"},\"important\");var o=r[0][0].getScreenCTM();Po=!(o.f||o.e),r.remove()}}return Po?(i.x=e.pageX,i.y=e.pageY):(i.x=e.clientX,i.y=e.clientY),i=i.matrixTransform(n.getScreenCTM().inverse()),[i.x,i.y]}var a=n.getBoundingClientRect();return[e.clientX-a.left-n.clientLeft,e.clientY-a.top-n.clientTop]}function G(){return ao.event.changedTouches[0].identifier}function K(n){return n>0?1:0>n?-1:0}function Q(n,t,e){return(t[0]-n[0])*(e[1]-n[1])-(t[1]-n[1])*(e[0]-n[0])}function nn(n){return n>1?0:-1>n?Fo:Math.acos(n)}function tn(n){return n>1?Io:-1>n?-Io:Math.asin(n)}function en(n){return((n=Math.exp(n))-1/n)/2}function rn(n){return((n=Math.exp(n))+1/n)/2}function un(n){return((n=Math.exp(2*n))-1)/(n+1)}function on(n){return(n=Math.sin(n/2))*n}function an(){}function ln(n,t,e){return this instanceof ln?(this.h=+n,this.s=+t,void(this.l=+e)):arguments.length<2?n instanceof ln?new ln(n.h,n.s,n.l):_n(\"\"+n,wn,ln):new ln(n,t,e)}function cn(n,t,e){function r(n){return n>360?n-=360:0>n&&(n+=360),60>n?u+(o-u)*n/60:180>n?o:240>n?u+(o-u)*(240-n)/60:u}function i(n){return Math.round(255*r(n))}var u,o;return n=isNaN(n)?0:(n%=360)<0?n+360:n,t=isNaN(t)?0:0>t?0:t>1?1:t,e=0>e?0:e>1?1:e,o=.5>=e?e*(1+t):e+t-e*t,u=2*e-o,new mn(i(n+120),i(n),i(n-120))}function fn(n,t,e){return this instanceof fn?(this.h=+n,this.c=+t,void(this.l=+e)):arguments.length<2?n instanceof fn?new fn(n.h,n.c,n.l):n instanceof hn?gn(n.l,n.a,n.b):gn((n=Sn((n=ao.rgb(n)).r,n.g,n.b)).l,n.a,n.b):new fn(n,t,e)}function sn(n,t,e){return isNaN(n)&&(n=0),isNaN(t)&&(t=0),new hn(e,Math.cos(n*=Yo)*t,Math.sin(n)*t)}function hn(n,t,e){return this instanceof hn?(this.l=+n,this.a=+t,void(this.b=+e)):arguments.length<2?n instanceof hn?new hn(n.l,n.a,n.b):n instanceof fn?sn(n.h,n.c,n.l):Sn((n=mn(n)).r,n.g,n.b):new hn(n,t,e)}function pn(n,t,e){var r=(n+16)/116,i=r+t/500,u=r-e/200;return i=vn(i)*na,r=vn(r)*ta,u=vn(u)*ea,new mn(yn(3.2404542*i-1.5371385*r-.4985314*u),yn(-.969266*i+1.8760108*r+.041556*u),yn(.0556434*i-.2040259*r+1.0572252*u))}function gn(n,t,e){return n>0?new fn(Math.atan2(e,t)*Zo,Math.sqrt(t*t+e*e),n):new fn(NaN,NaN,n)}function vn(n){return n>.206893034?n*n*n:(n-4/29)/7.787037}function dn(n){return n>.008856?Math.pow(n,1/3):7.787037*n+4/29}function yn(n){return Math.round(255*(.00304>=n?12.92*n:1.055*Math.pow(n,1/2.4)-.055))}function mn(n,t,e){return this instanceof mn?(this.r=~~n,this.g=~~t,void(this.b=~~e)):arguments.length<2?n instanceof mn?new mn(n.r,n.g,n.b):_n(\"\"+n,mn,cn):new mn(n,t,e)}function Mn(n){return new mn(n>>16,n>>8&255,255&n)}function xn(n){return Mn(n)+\"\"}function bn(n){return 16>n?\"0\"+Math.max(0,n).toString(16):Math.min(255,n).toString(16)}function _n(n,t,e){var r,i,u,o=0,a=0,l=0;if(r=/([a-z]+)\\((.*)\\)/.exec(n=n.toLowerCase()))switch(i=r[2].split(\",\"),r[1]){case\"hsl\":return e(parseFloat(i[0]),parseFloat(i[1])/100,parseFloat(i[2])/100);case\"rgb\":return t(Nn(i[0]),Nn(i[1]),Nn(i[2]))}return(u=ua.get(n))?t(u.r,u.g,u.b):(null==n||\"#\"!==n.charAt(0)||isNaN(u=parseInt(n.slice(1),16))||(4===n.length?(o=(3840&u)>>4,o=o>>4|o,a=240&u,a=a>>4|a,l=15&u,l=l<<4|l):7===n.length&&(o=(16711680&u)>>16,a=(65280&u)>>8,l=255&u)),t(o,a,l))}function wn(n,t,e){var r,i,u=Math.min(n/=255,t/=255,e/=255),o=Math.max(n,t,e),a=o-u,l=(o+u)/2;return a?(i=.5>l?a/(o+u):a/(2-o-u),r=n==o?(t-e)/a+(e>t?6:0):t==o?(e-n)/a+2:(n-t)/a+4,r*=60):(r=NaN,i=l>0&&1>l?0:r),new ln(r,i,l)}function Sn(n,t,e){n=kn(n),t=kn(t),e=kn(e);var r=dn((.4124564*n+.3575761*t+.1804375*e)/na),i=dn((.2126729*n+.7151522*t+.072175*e)/ta),u=dn((.0193339*n+.119192*t+.9503041*e)/ea);return hn(116*i-16,500*(r-i),200*(i-u))}function kn(n){return(n/=255)<=.04045?n/12.92:Math.pow((n+.055)/1.055,2.4)}function Nn(n){var t=parseFloat(n);return\"%\"===n.charAt(n.length-1)?Math.round(2.55*t):t}function En(n){return\"function\"==typeof n?n:function(){return n}}function An(n){return function(t,e,r){return 2===arguments.length&&\"function\"==typeof e&&(r=e,e=null),Cn(t,e,n,r)}}function Cn(n,t,e,r){function i(){var n,t=l.status;if(!t&&Ln(l)||t>=200&&300>t||304===t){try{n=e.call(u,l)}catch(r){return void o.error.call(u,r)}o.load.call(u,n)}else o.error.call(u,l)}var u={},o=ao.dispatch(\"beforesend\",\"progress\",\"load\",\"error\"),a={},l=new XMLHttpRequest,c=null;return!this.XDomainRequest||\"withCredentials\"in l||!/^(http(s)?:)?\\/\\//.test(n)||(l=new XDomainRequest),\"onload\"in l?l.onload=l.onerror=i:l.onreadystatechange=function(){l.readyState>3&&i()},l.onprogress=function(n){var t=ao.event;ao.event=n;try{o.progress.call(u,l)}finally{ao.event=t}},u.header=function(n,t){return n=(n+\"\").toLowerCase(),arguments.length<2?a[n]:(null==t?delete a[n]:a[n]=t+\"\",u)},u.mimeType=function(n){return arguments.length?(t=null==n?null:n+\"\",u):t},u.responseType=function(n){return arguments.length?(c=n,u):c},u.response=function(n){return e=n,u},[\"get\",\"post\"].forEach(function(n){u[n]=function(){return u.send.apply(u,[n].concat(co(arguments)))}}),u.send=function(e,r,i){if(2===arguments.length&&\"function\"==typeof r&&(i=r,r=null),l.open(e,n,!0),null==t||\"accept\"in a||(a.accept=t+\",*/*\"),l.setRequestHeader)for(var f in a)l.setRequestHeader(f,a[f]);return null!=t&&l.overrideMimeType&&l.overrideMimeType(t),null!=c&&(l.responseType=c),null!=i&&u.on(\"error\",i).on(\"load\",function(n){i(null,n)}),o.beforesend.call(u,l),l.send(null==r?null:r),u},u.abort=function(){return l.abort(),u},ao.rebind(u,o,\"on\"),null==r?u:u.get(zn(r))}function zn(n){return 1===n.length?function(t,e){n(null==t?e:null)}:n}function Ln(n){var t=n.responseType;return t&&\"text\"!==t?n.response:n.responseText}function qn(n,t,e){var r=arguments.length;2>r&&(t=0),3>r&&(e=Date.now());var i=e+t,u={c:n,t:i,n:null};return aa?aa.n=u:oa=u,aa=u,la||(ca=clearTimeout(ca),la=1,fa(Tn)),u}function Tn(){var n=Rn(),t=Dn()-n;t>24?(isFinite(t)&&(clearTimeout(ca),ca=setTimeout(Tn,t)),la=0):(la=1,fa(Tn))}function Rn(){for(var n=Date.now(),t=oa;t;)n>=t.t&&t.c(n-t.t)&&(t.c=null),t=t.n;return n}function Dn(){for(var n,t=oa,e=1/0;t;)t.c?(t.t<e&&(e=t.t),t=(n=t).n):t=n?n.n=t.n:oa=t.n;return aa=n,e}function Pn(n,t){return t-(n?Math.ceil(Math.log(n)/Math.LN10):1)}function Un(n,t){var e=Math.pow(10,3*xo(8-t));return{scale:t>8?function(n){return n/e}:function(n){return n*e},symbol:n}}function jn(n){var t=n.decimal,e=n.thousands,r=n.grouping,i=n.currency,u=r&&e?function(n,t){for(var i=n.length,u=[],o=0,a=r[0],l=0;i>0&&a>0&&(l+a+1>t&&(a=Math.max(1,t-l)),u.push(n.substring(i-=a,i+a)),!((l+=a+1)>t));)a=r[o=(o+1)%r.length];return u.reverse().join(e)}:m;return function(n){var e=ha.exec(n),r=e[1]||\" \",o=e[2]||\">\",a=e[3]||\"-\",l=e[4]||\"\",c=e[5],f=+e[6],s=e[7],h=e[8],p=e[9],g=1,v=\"\",d=\"\",y=!1,m=!0;switch(h&&(h=+h.substring(1)),(c||\"0\"===r&&\"=\"===o)&&(c=r=\"0\",o=\"=\"),p){case\"n\":s=!0,p=\"g\";break;case\"%\":g=100,d=\"%\",p=\"f\";break;case\"p\":g=100,d=\"%\",p=\"r\";break;case\"b\":case\"o\":case\"x\":case\"X\":\"#\"===l&&(v=\"0\"+p.toLowerCase());case\"c\":m=!1;case\"d\":y=!0,h=0;break;case\"s\":g=-1,p=\"r\"}\"$\"===l&&(v=i[0],d=i[1]),\"r\"!=p||h||(p=\"g\"),null!=h&&(\"g\"==p?h=Math.max(1,Math.min(21,h)):\"e\"!=p&&\"f\"!=p||(h=Math.max(0,Math.min(20,h)))),p=pa.get(p)||Fn;var M=c&&s;return function(n){var e=d;if(y&&n%1)return\"\";var i=0>n||0===n&&0>1/n?(n=-n,\"-\"):\"-\"===a?\"\":a;if(0>g){var l=ao.formatPrefix(n,h);n=l.scale(n),e=l.symbol+d}else n*=g;n=p(n,h);var x,b,_=n.lastIndexOf(\".\");if(0>_){var w=m?n.lastIndexOf(\"e\"):-1;0>w?(x=n,b=\"\"):(x=n.substring(0,w),b=n.substring(w))}else x=n.substring(0,_),b=t+n.substring(_+1);!c&&s&&(x=u(x,1/0));var S=v.length+x.length+b.length+(M?0:i.length),k=f>S?new Array(S=f-S+1).join(r):\"\";return M&&(x=u(k+x,k.length?f-b.length:1/0)),i+=v,n=x+b,(\"<\"===o?i+n+k:\">\"===o?k+i+n:\"^\"===o?k.substring(0,S>>=1)+i+n+k.substring(S):i+(M?n:k+n))+e}}}function Fn(n){return n+\"\"}function Hn(){this._=new Date(arguments.length>1?Date.UTC.apply(this,arguments):arguments[0])}function On(n,t,e){function r(t){var e=n(t),r=u(e,1);return r-t>t-e?e:r}function i(e){return t(e=n(new va(e-1)),1),e}function u(n,e){return t(n=new va(+n),e),n}function o(n,r,u){var o=i(n),a=[];if(u>1)for(;r>o;)e(o)%u||a.push(new Date(+o)),t(o,1);else for(;r>o;)a.push(new Date(+o)),t(o,1);return a}function a(n,t,e){try{va=Hn;var r=new Hn;return r._=n,o(r,t,e)}finally{va=Date}}n.floor=n,n.round=r,n.ceil=i,n.offset=u,n.range=o;var l=n.utc=In(n);return l.floor=l,l.round=In(r),l.ceil=In(i),l.offset=In(u),l.range=a,n}function In(n){return function(t,e){try{va=Hn;var r=new Hn;return r._=t,n(r,e)._}finally{va=Date}}}function Yn(n){function t(n){function t(t){for(var e,i,u,o=[],a=-1,l=0;++a<r;)37===n.charCodeAt(a)&&(o.push(n.slice(l,a)),null!=(i=ya[e=n.charAt(++a)])&&(e=n.charAt(++a)),(u=A[e])&&(e=u(t,null==i?\"e\"===e?\" \":\"0\":i)),o.push(e),l=a+1);return o.push(n.slice(l,a)),o.join(\"\")}var r=n.length;return t.parse=function(t){var r={y:1900,m:0,d:1,H:0,M:0,S:0,L:0,Z:null},i=e(r,n,t,0);if(i!=t.length)return null;\"p\"in r&&(r.H=r.H%12+12*r.p);var u=null!=r.Z&&va!==Hn,o=new(u?Hn:va);return\"j\"in r?o.setFullYear(r.y,0,r.j):\"W\"in r||\"U\"in r?(\"w\"in r||(r.w=\"W\"in r?1:0),o.setFullYear(r.y,0,1),o.setFullYear(r.y,0,\"W\"in r?(r.w+6)%7+7*r.W-(o.getDay()+5)%7:r.w+7*r.U-(o.getDay()+6)%7)):o.setFullYear(r.y,r.m,r.d),o.setHours(r.H+(r.Z/100|0),r.M+r.Z%100,r.S,r.L),u?o._:o},t.toString=function(){return n},t}function e(n,t,e,r){for(var i,u,o,a=0,l=t.length,c=e.length;l>a;){if(r>=c)return-1;if(i=t.charCodeAt(a++),37===i){if(o=t.charAt(a++),u=C[o in ya?t.charAt(a++):o],!u||(r=u(n,e,r))<0)return-1}else if(i!=e.charCodeAt(r++))return-1}return r}function r(n,t,e){_.lastIndex=0;var r=_.exec(t.slice(e));return r?(n.w=w.get(r[0].toLowerCase()),e+r[0].length):-1}function i(n,t,e){x.lastIndex=0;var r=x.exec(t.slice(e));return r?(n.w=b.get(r[0].toLowerCase()),e+r[0].length):-1}function u(n,t,e){N.lastIndex=0;var r=N.exec(t.slice(e));return r?(n.m=E.get(r[0].toLowerCase()),e+r[0].length):-1}function o(n,t,e){S.lastIndex=0;var r=S.exec(t.slice(e));return r?(n.m=k.get(r[0].toLowerCase()),e+r[0].length):-1}function a(n,t,r){return e(n,A.c.toString(),t,r)}function l(n,t,r){return e(n,A.x.toString(),t,r)}function c(n,t,r){return e(n,A.X.toString(),t,r)}function f(n,t,e){var r=M.get(t.slice(e,e+=2).toLowerCase());return null==r?-1:(n.p=r,e)}var s=n.dateTime,h=n.date,p=n.time,g=n.periods,v=n.days,d=n.shortDays,y=n.months,m=n.shortMonths;t.utc=function(n){function e(n){try{va=Hn;var t=new va;return t._=n,r(t)}finally{va=Date}}var r=t(n);return e.parse=function(n){try{va=Hn;var t=r.parse(n);return t&&t._}finally{va=Date}},e.toString=r.toString,e},t.multi=t.utc.multi=ct;var M=ao.map(),x=Vn(v),b=Xn(v),_=Vn(d),w=Xn(d),S=Vn(y),k=Xn(y),N=Vn(m),E=Xn(m);g.forEach(function(n,t){M.set(n.toLowerCase(),t)});var A={a:function(n){return d[n.getDay()]},A:function(n){return v[n.getDay()]},b:function(n){return m[n.getMonth()]},B:function(n){return y[n.getMonth()]},c:t(s),d:function(n,t){return Zn(n.getDate(),t,2)},e:function(n,t){return Zn(n.getDate(),t,2)},H:function(n,t){return Zn(n.getHours(),t,2)},I:function(n,t){return Zn(n.getHours()%12||12,t,2)},j:function(n,t){return Zn(1+ga.dayOfYear(n),t,3)},L:function(n,t){return Zn(n.getMilliseconds(),t,3)},m:function(n,t){return Zn(n.getMonth()+1,t,2)},M:function(n,t){return Zn(n.getMinutes(),t,2)},p:function(n){return g[+(n.getHours()>=12)]},S:function(n,t){return Zn(n.getSeconds(),t,2)},U:function(n,t){return Zn(ga.sundayOfYear(n),t,2)},w:function(n){return n.getDay()},W:function(n,t){return Zn(ga.mondayOfYear(n),t,2)},x:t(h),X:t(p),y:function(n,t){return Zn(n.getFullYear()%100,t,2)},Y:function(n,t){return Zn(n.getFullYear()%1e4,t,4)},Z:at,\"%\":function(){return\"%\"}},C={a:r,A:i,b:u,B:o,c:a,d:tt,e:tt,H:rt,I:rt,j:et,L:ot,m:nt,M:it,p:f,S:ut,U:Bn,w:$n,W:Wn,x:l,X:c,y:Gn,Y:Jn,Z:Kn,\"%\":lt};return t}function Zn(n,t,e){var r=0>n?\"-\":\"\",i=(r?-n:n)+\"\",u=i.length;return r+(e>u?new Array(e-u+1).join(t)+i:i)}function Vn(n){return new RegExp(\"^(?:\"+n.map(ao.requote).join(\"|\")+\")\",\"i\")}function Xn(n){for(var t=new c,e=-1,r=n.length;++e<r;)t.set(n[e].toLowerCase(),e);return t}function $n(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e,e+1));return r?(n.w=+r[0],e+r[0].length):-1}function Bn(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e));return r?(n.U=+r[0],e+r[0].length):-1}function Wn(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e));return r?(n.W=+r[0],e+r[0].length):-1}function Jn(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e,e+4));return r?(n.y=+r[0],e+r[0].length):-1}function Gn(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e,e+2));return r?(n.y=Qn(+r[0]),e+r[0].length):-1}function Kn(n,t,e){return/^[+-]\\d{4}$/.test(t=t.slice(e,e+5))?(n.Z=-t,e+5):-1}function Qn(n){return n+(n>68?1900:2e3)}function nt(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e,e+2));return r?(n.m=r[0]-1,e+r[0].length):-1}function tt(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e,e+2));return r?(n.d=+r[0],e+r[0].length):-1}function et(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e,e+3));return r?(n.j=+r[0],e+r[0].length):-1}function rt(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e,e+2));return r?(n.H=+r[0],e+r[0].length):-1}function it(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e,e+2));return r?(n.M=+r[0],e+r[0].length):-1}function ut(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e,e+2));return r?(n.S=+r[0],e+r[0].length):-1}function ot(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e,e+3));return r?(n.L=+r[0],e+r[0].length):-1}function at(n){var t=n.getTimezoneOffset(),e=t>0?\"-\":\"+\",r=xo(t)/60|0,i=xo(t)%60;return e+Zn(r,\"0\",2)+Zn(i,\"0\",2)}function lt(n,t,e){Ma.lastIndex=0;var r=Ma.exec(t.slice(e,e+1));return r?e+r[0].length:-1}function ct(n){for(var t=n.length,e=-1;++e<t;)n[e][0]=this(n[e][0]);return function(t){for(var e=0,r=n[e];!r[1](t);)r=n[++e];return r[0](t)}}function ft(){}function st(n,t,e){var r=e.s=n+t,i=r-n,u=r-i;e.t=n-u+(t-i)}function ht(n,t){n&&wa.hasOwnProperty(n.type)&&wa[n.type](n,t)}function pt(n,t,e){var r,i=-1,u=n.length-e;for(t.lineStart();++i<u;)r=n[i],t.point(r[0],r[1],r[2]);t.lineEnd()}function gt(n,t){var e=-1,r=n.length;for(t.polygonStart();++e<r;)pt(n[e],t,1);t.polygonEnd()}function vt(){function n(n,t){n*=Yo,t=t*Yo/2+Fo/4;var e=n-r,o=e>=0?1:-1,a=o*e,l=Math.cos(t),c=Math.sin(t),f=u*c,s=i*l+f*Math.cos(a),h=f*o*Math.sin(a);ka.add(Math.atan2(h,s)),r=n,i=l,u=c}var t,e,r,i,u;Na.point=function(o,a){Na.point=n,r=(t=o)*Yo,i=Math.cos(a=(e=a)*Yo/2+Fo/4),u=Math.sin(a)},Na.lineEnd=function(){n(t,e)}}function dt(n){var t=n[0],e=n[1],r=Math.cos(e);return[r*Math.cos(t),r*Math.sin(t),Math.sin(e)]}function yt(n,t){return n[0]*t[0]+n[1]*t[1]+n[2]*t[2]}function mt(n,t){return[n[1]*t[2]-n[2]*t[1],n[2]*t[0]-n[0]*t[2],n[0]*t[1]-n[1]*t[0]]}function Mt(n,t){n[0]+=t[0],n[1]+=t[1],n[2]+=t[2]}function xt(n,t){return[n[0]*t,n[1]*t,n[2]*t]}function bt(n){var t=Math.sqrt(n[0]*n[0]+n[1]*n[1]+n[2]*n[2]);n[0]/=t,n[1]/=t,n[2]/=t}function _t(n){return[Math.atan2(n[1],n[0]),tn(n[2])]}function wt(n,t){return xo(n[0]-t[0])<Uo&&xo(n[1]-t[1])<Uo}function St(n,t){n*=Yo;var e=Math.cos(t*=Yo);kt(e*Math.cos(n),e*Math.sin(n),Math.sin(t))}function kt(n,t,e){++Ea,Ca+=(n-Ca)/Ea,za+=(t-za)/Ea,La+=(e-La)/Ea}function Nt(){function n(n,i){n*=Yo;var u=Math.cos(i*=Yo),o=u*Math.cos(n),a=u*Math.sin(n),l=Math.sin(i),c=Math.atan2(Math.sqrt((c=e*l-r*a)*c+(c=r*o-t*l)*c+(c=t*a-e*o)*c),t*o+e*a+r*l);Aa+=c,qa+=c*(t+(t=o)),Ta+=c*(e+(e=a)),Ra+=c*(r+(r=l)),kt(t,e,r)}var t,e,r;ja.point=function(i,u){i*=Yo;var o=Math.cos(u*=Yo);t=o*Math.cos(i),e=o*Math.sin(i),r=Math.sin(u),ja.point=n,kt(t,e,r)}}function Et(){ja.point=St}function At(){function n(n,t){n*=Yo;var e=Math.cos(t*=Yo),o=e*Math.cos(n),a=e*Math.sin(n),l=Math.sin(t),c=i*l-u*a,f=u*o-r*l,s=r*a-i*o,h=Math.sqrt(c*c+f*f+s*s),p=r*o+i*a+u*l,g=h&&-nn(p)/h,v=Math.atan2(h,p);Da+=g*c,Pa+=g*f,Ua+=g*s,Aa+=v,qa+=v*(r+(r=o)),Ta+=v*(i+(i=a)),Ra+=v*(u+(u=l)),kt(r,i,u)}var t,e,r,i,u;ja.point=function(o,a){t=o,e=a,ja.point=n,o*=Yo;var l=Math.cos(a*=Yo);r=l*Math.cos(o),i=l*Math.sin(o),u=Math.sin(a),kt(r,i,u)},ja.lineEnd=function(){n(t,e),ja.lineEnd=Et,ja.point=St}}function Ct(n,t){function e(e,r){return e=n(e,r),t(e[0],e[1])}return n.invert&&t.invert&&(e.invert=function(e,r){return e=t.invert(e,r),e&&n.invert(e[0],e[1])}),e}function zt(){return!0}function Lt(n,t,e,r,i){var u=[],o=[];if(n.forEach(function(n){if(!((t=n.length-1)<=0)){var t,e=n[0],r=n[t];if(wt(e,r)){i.lineStart();for(var a=0;t>a;++a)i.point((e=n[a])[0],e[1]);return void i.lineEnd()}var l=new Tt(e,n,null,!0),c=new Tt(e,null,l,!1);l.o=c,u.push(l),o.push(c),l=new Tt(r,n,null,!1),c=new Tt(r,null,l,!0),l.o=c,u.push(l),o.push(c)}}),o.sort(t),qt(u),qt(o),u.length){for(var a=0,l=e,c=o.length;c>a;++a)o[a].e=l=!l;for(var f,s,h=u[0];;){for(var p=h,g=!0;p.v;)if((p=p.n)===h)return;f=p.z,i.lineStart();do{if(p.v=p.o.v=!0,p.e){if(g)for(var a=0,c=f.length;c>a;++a)i.point((s=f[a])[0],s[1]);else r(p.x,p.n.x,1,i);p=p.n}else{if(g){f=p.p.z;for(var a=f.length-1;a>=0;--a)i.point((s=f[a])[0],s[1])}else r(p.x,p.p.x,-1,i);p=p.p}p=p.o,f=p.z,g=!g}while(!p.v);i.lineEnd()}}}function qt(n){if(t=n.length){for(var t,e,r=0,i=n[0];++r<t;)i.n=e=n[r],e.p=i,i=e;i.n=e=n[0],e.p=i}}function Tt(n,t,e,r){this.x=n,this.z=t,this.o=e,this.e=r,this.v=!1,this.n=this.p=null}function Rt(n,t,e,r){return function(i,u){function o(t,e){var r=i(t,e);n(t=r[0],e=r[1])&&u.point(t,e)}function a(n,t){var e=i(n,t);d.point(e[0],e[1])}function l(){m.point=a,d.lineStart()}function c(){m.point=o,d.lineEnd()}function f(n,t){v.push([n,t]);var e=i(n,t);x.point(e[0],e[1])}function s(){x.lineStart(),v=[]}function h(){f(v[0][0],v[0][1]),x.lineEnd();var n,t=x.clean(),e=M.buffer(),r=e.length;if(v.pop(),g.push(v),v=null,r)if(1&t){n=e[0];var i,r=n.length-1,o=-1;if(r>0){for(b||(u.polygonStart(),b=!0),u.lineStart();++o<r;)u.point((i=n[o])[0],i[1]);u.lineEnd()}}else r>1&&2&t&&e.push(e.pop().concat(e.shift())),p.push(e.filter(Dt))}var p,g,v,d=t(u),y=i.invert(r[0],r[1]),m={point:o,lineStart:l,lineEnd:c,polygonStart:function(){m.point=f,m.lineStart=s,m.lineEnd=h,p=[],g=[]},polygonEnd:function(){m.point=o,m.lineStart=l,m.lineEnd=c,p=ao.merge(p);var n=Ot(y,g);p.length?(b||(u.polygonStart(),b=!0),Lt(p,Ut,n,e,u)):n&&(b||(u.polygonStart(),b=!0),u.lineStart(),e(null,null,1,u),u.lineEnd()),b&&(u.polygonEnd(),b=!1),p=g=null},sphere:function(){u.polygonStart(),u.lineStart(),e(null,null,1,u),u.lineEnd(),u.polygonEnd()}},M=Pt(),x=t(M),b=!1;return m}}function Dt(n){return n.length>1}function Pt(){var n,t=[];return{lineStart:function(){t.push(n=[])},point:function(t,e){n.push([t,e])},lineEnd:b,buffer:function(){var e=t;return t=[],n=null,e},rejoin:function(){t.length>1&&t.push(t.pop().concat(t.shift()))}}}function Ut(n,t){return((n=n.x)[0]<0?n[1]-Io-Uo:Io-n[1])-((t=t.x)[0]<0?t[1]-Io-Uo:Io-t[1])}function jt(n){var t,e=NaN,r=NaN,i=NaN;return{lineStart:function(){n.lineStart(),t=1},point:function(u,o){var a=u>0?Fo:-Fo,l=xo(u-e);xo(l-Fo)<Uo?(n.point(e,r=(r+o)/2>0?Io:-Io),n.point(i,r),n.lineEnd(),n.lineStart(),n.point(a,r),n.point(u,r),t=0):i!==a&&l>=Fo&&(xo(e-i)<Uo&&(e-=i*Uo),xo(u-a)<Uo&&(u-=a*Uo),r=Ft(e,r,u,o),n.point(i,r),n.lineEnd(),n.lineStart(),n.point(a,r),t=0),n.point(e=u,r=o),i=a},lineEnd:function(){n.lineEnd(),e=r=NaN},clean:function(){return 2-t}}}function Ft(n,t,e,r){var i,u,o=Math.sin(n-e);return xo(o)>Uo?Math.atan((Math.sin(t)*(u=Math.cos(r))*Math.sin(e)-Math.sin(r)*(i=Math.cos(t))*Math.sin(n))/(i*u*o)):(t+r)/2}function Ht(n,t,e,r){var i;if(null==n)i=e*Io,r.point(-Fo,i),r.point(0,i),r.point(Fo,i),r.point(Fo,0),r.point(Fo,-i),r.point(0,-i),r.point(-Fo,-i),r.point(-Fo,0),r.point(-Fo,i);else if(xo(n[0]-t[0])>Uo){var u=n[0]<t[0]?Fo:-Fo;i=e*u/2,r.point(-u,i),r.point(0,i),r.point(u,i)}else r.point(t[0],t[1])}function Ot(n,t){var e=n[0],r=n[1],i=[Math.sin(e),-Math.cos(e),0],u=0,o=0;ka.reset();for(var a=0,l=t.length;l>a;++a){var c=t[a],f=c.length;if(f)for(var s=c[0],h=s[0],p=s[1]/2+Fo/4,g=Math.sin(p),v=Math.cos(p),d=1;;){d===f&&(d=0),n=c[d];var y=n[0],m=n[1]/2+Fo/4,M=Math.sin(m),x=Math.cos(m),b=y-h,_=b>=0?1:-1,w=_*b,S=w>Fo,k=g*M;if(ka.add(Math.atan2(k*_*Math.sin(w),v*x+k*Math.cos(w))),u+=S?b+_*Ho:b,S^h>=e^y>=e){var N=mt(dt(s),dt(n));bt(N);var E=mt(i,N);bt(E);var A=(S^b>=0?-1:1)*tn(E[2]);(r>A||r===A&&(N[0]||N[1]))&&(o+=S^b>=0?1:-1)}if(!d++)break;h=y,g=M,v=x,s=n}}return(-Uo>u||Uo>u&&-Uo>ka)^1&o}function It(n){function t(n,t){return Math.cos(n)*Math.cos(t)>u}function e(n){var e,u,l,c,f;return{lineStart:function(){c=l=!1,f=1},point:function(s,h){var p,g=[s,h],v=t(s,h),d=o?v?0:i(s,h):v?i(s+(0>s?Fo:-Fo),h):0;if(!e&&(c=l=v)&&n.lineStart(),v!==l&&(p=r(e,g),(wt(e,p)||wt(g,p))&&(g[0]+=Uo,g[1]+=Uo,v=t(g[0],g[1]))),v!==l)f=0,v?(n.lineStart(),p=r(g,e),n.point(p[0],p[1])):(p=r(e,g),n.point(p[0],p[1]),n.lineEnd()),e=p;else if(a&&e&&o^v){var y;d&u||!(y=r(g,e,!0))||(f=0,o?(n.lineStart(),n.point(y[0][0],y[0][1]),n.point(y[1][0],y[1][1]),n.lineEnd()):(n.point(y[1][0],y[1][1]),n.lineEnd(),n.lineStart(),n.point(y[0][0],y[0][1])))}!v||e&&wt(e,g)||n.point(g[0],g[1]),e=g,l=v,u=d},lineEnd:function(){l&&n.lineEnd(),e=null},clean:function(){return f|(c&&l)<<1}}}function r(n,t,e){var r=dt(n),i=dt(t),o=[1,0,0],a=mt(r,i),l=yt(a,a),c=a[0],f=l-c*c;if(!f)return!e&&n;var s=u*l/f,h=-u*c/f,p=mt(o,a),g=xt(o,s),v=xt(a,h);Mt(g,v);var d=p,y=yt(g,d),m=yt(d,d),M=y*y-m*(yt(g,g)-1);if(!(0>M)){var x=Math.sqrt(M),b=xt(d,(-y-x)/m);if(Mt(b,g),b=_t(b),!e)return b;var _,w=n[0],S=t[0],k=n[1],N=t[1];w>S&&(_=w,w=S,S=_);var E=S-w,A=xo(E-Fo)<Uo,C=A||Uo>E;if(!A&&k>N&&(_=k,k=N,N=_),C?A?k+N>0^b[1]<(xo(b[0]-w)<Uo?k:N):k<=b[1]&&b[1]<=N:E>Fo^(w<=b[0]&&b[0]<=S)){var z=xt(d,(-y+x)/m);return Mt(z,g),[b,_t(z)]}}}function i(t,e){var r=o?n:Fo-n,i=0;return-r>t?i|=1:t>r&&(i|=2),-r>e?i|=4:e>r&&(i|=8),i}var u=Math.cos(n),o=u>0,a=xo(u)>Uo,l=ve(n,6*Yo);return Rt(t,e,l,o?[0,-n]:[-Fo,n-Fo])}function Yt(n,t,e,r){return function(i){var u,o=i.a,a=i.b,l=o.x,c=o.y,f=a.x,s=a.y,h=0,p=1,g=f-l,v=s-c;if(u=n-l,g||!(u>0)){if(u/=g,0>g){if(h>u)return;p>u&&(p=u)}else if(g>0){if(u>p)return;u>h&&(h=u)}if(u=e-l,g||!(0>u)){if(u/=g,0>g){if(u>p)return;u>h&&(h=u)}else if(g>0){if(h>u)return;p>u&&(p=u)}if(u=t-c,v||!(u>0)){if(u/=v,0>v){if(h>u)return;p>u&&(p=u)}else if(v>0){if(u>p)return;u>h&&(h=u)}if(u=r-c,v||!(0>u)){if(u/=v,0>v){if(u>p)return;u>h&&(h=u)}else if(v>0){if(h>u)return;p>u&&(p=u)}return h>0&&(i.a={x:l+h*g,y:c+h*v}),1>p&&(i.b={x:l+p*g,y:c+p*v}),i}}}}}}function Zt(n,t,e,r){function i(r,i){return xo(r[0]-n)<Uo?i>0?0:3:xo(r[0]-e)<Uo?i>0?2:1:xo(r[1]-t)<Uo?i>0?1:0:i>0?3:2}function u(n,t){return o(n.x,t.x)}function o(n,t){var e=i(n,1),r=i(t,1);return e!==r?e-r:0===e?t[1]-n[1]:1===e?n[0]-t[0]:2===e?n[1]-t[1]:t[0]-n[0]}return function(a){function l(n){for(var t=0,e=d.length,r=n[1],i=0;e>i;++i)for(var u,o=1,a=d[i],l=a.length,c=a[0];l>o;++o)u=a[o],c[1]<=r?u[1]>r&&Q(c,u,n)>0&&++t:u[1]<=r&&Q(c,u,n)<0&&--t,c=u;return 0!==t}function c(u,a,l,c){var f=0,s=0;if(null==u||(f=i(u,l))!==(s=i(a,l))||o(u,a)<0^l>0){do c.point(0===f||3===f?n:e,f>1?r:t);while((f=(f+l+4)%4)!==s)}else c.point(a[0],a[1])}function f(i,u){return i>=n&&e>=i&&u>=t&&r>=u}function s(n,t){f(n,t)&&a.point(n,t)}function h(){C.point=g,d&&d.push(y=[]),S=!0,w=!1,b=_=NaN}function p(){v&&(g(m,M),x&&w&&E.rejoin(),v.push(E.buffer())),C.point=s,w&&a.lineEnd()}function g(n,t){n=Math.max(-Ha,Math.min(Ha,n)),t=Math.max(-Ha,Math.min(Ha,t));var e=f(n,t);if(d&&y.push([n,t]),S)m=n,M=t,x=e,S=!1,e&&(a.lineStart(),a.point(n,t));else if(e&&w)a.point(n,t);else{var r={a:{x:b,y:_},b:{x:n,y:t}};A(r)?(w||(a.lineStart(),a.point(r.a.x,r.a.y)),a.point(r.b.x,r.b.y),e||a.lineEnd(),k=!1):e&&(a.lineStart(),a.point(n,t),k=!1)}b=n,_=t,w=e}var v,d,y,m,M,x,b,_,w,S,k,N=a,E=Pt(),A=Yt(n,t,e,r),C={point:s,lineStart:h,lineEnd:p,polygonStart:function(){a=E,v=[],d=[],k=!0},polygonEnd:function(){a=N,v=ao.merge(v);var t=l([n,r]),e=k&&t,i=v.length;(e||i)&&(a.polygonStart(),e&&(a.lineStart(),c(null,null,1,a),a.lineEnd()),i&&Lt(v,u,t,c,a),a.polygonEnd()),v=d=y=null}};return C}}function Vt(n){var t=0,e=Fo/3,r=ae(n),i=r(t,e);return i.parallels=function(n){return arguments.length?r(t=n[0]*Fo/180,e=n[1]*Fo/180):[t/Fo*180,e/Fo*180]},i}function Xt(n,t){function e(n,t){var e=Math.sqrt(u-2*i*Math.sin(t))/i;return[e*Math.sin(n*=i),o-e*Math.cos(n)]}var r=Math.sin(n),i=(r+Math.sin(t))/2,u=1+r*(2*i-r),o=Math.sqrt(u)/i;return e.invert=function(n,t){var e=o-t;return[Math.atan2(n,e)/i,tn((u-(n*n+e*e)*i*i)/(2*i))]},e}function $t(){function n(n,t){Ia+=i*n-r*t,r=n,i=t}var t,e,r,i;$a.point=function(u,o){$a.point=n,t=r=u,e=i=o},$a.lineEnd=function(){n(t,e)}}function Bt(n,t){Ya>n&&(Ya=n),n>Va&&(Va=n),Za>t&&(Za=t),t>Xa&&(Xa=t)}function Wt(){function n(n,t){o.push(\"M\",n,\",\",t,u)}function t(n,t){o.push(\"M\",n,\",\",t),a.point=e}function e(n,t){o.push(\"L\",n,\",\",t)}function r(){a.point=n}function i(){o.push(\"Z\")}var u=Jt(4.5),o=[],a={point:n,lineStart:function(){a.point=t},lineEnd:r,polygonStart:function(){a.lineEnd=i},polygonEnd:function(){a.lineEnd=r,a.point=n},pointRadius:function(n){return u=Jt(n),a},result:function(){if(o.length){var n=o.join(\"\");return o=[],n}}};return a}function Jt(n){return\"m0,\"+n+\"a\"+n+\",\"+n+\" 0 1,1 0,\"+-2*n+\"a\"+n+\",\"+n+\" 0 1,1 0,\"+2*n+\"z\"}function Gt(n,t){Ca+=n,za+=t,++La}function Kt(){function n(n,r){var i=n-t,u=r-e,o=Math.sqrt(i*i+u*u);qa+=o*(t+n)/2,Ta+=o*(e+r)/2,Ra+=o,Gt(t=n,e=r)}var t,e;Wa.point=function(r,i){Wa.point=n,Gt(t=r,e=i)}}function Qt(){Wa.point=Gt}function ne(){function n(n,t){var e=n-r,u=t-i,o=Math.sqrt(e*e+u*u);qa+=o*(r+n)/2,Ta+=o*(i+t)/2,Ra+=o,o=i*n-r*t,Da+=o*(r+n),Pa+=o*(i+t),Ua+=3*o,Gt(r=n,i=t)}var t,e,r,i;Wa.point=function(u,o){Wa.point=n,Gt(t=r=u,e=i=o)},Wa.lineEnd=function(){n(t,e)}}function te(n){function t(t,e){n.moveTo(t+o,e),n.arc(t,e,o,0,Ho)}function e(t,e){n.moveTo(t,e),a.point=r}function r(t,e){n.lineTo(t,e)}function i(){a.point=t}function u(){n.closePath()}var o=4.5,a={point:t,lineStart:function(){a.point=e},lineEnd:i,polygonStart:function(){a.lineEnd=u},polygonEnd:function(){a.lineEnd=i,a.point=t},pointRadius:function(n){return o=n,a},result:b};return a}function ee(n){function t(n){return(a?r:e)(n)}function e(t){return ue(t,function(e,r){e=n(e,r),t.point(e[0],e[1])})}function r(t){function e(e,r){e=n(e,r),t.point(e[0],e[1])}function r(){M=NaN,S.point=u,t.lineStart()}function u(e,r){var u=dt([e,r]),o=n(e,r);i(M,x,m,b,_,w,M=o[0],x=o[1],m=e,b=u[0],_=u[1],w=u[2],a,t),t.point(M,x)}function o(){S.point=e,t.lineEnd()}function l(){r(),S.point=c,S.lineEnd=f}function c(n,t){u(s=n,h=t),p=M,g=x,v=b,d=_,y=w,S.point=u}function f(){i(M,x,m,b,_,w,p,g,s,v,d,y,a,t),S.lineEnd=o,o()}var s,h,p,g,v,d,y,m,M,x,b,_,w,S={point:e,lineStart:r,lineEnd:o,polygonStart:function(){t.polygonStart(),S.lineStart=l},polygonEnd:function(){t.polygonEnd(),S.lineStart=r}};return S}function i(t,e,r,a,l,c,f,s,h,p,g,v,d,y){var m=f-t,M=s-e,x=m*m+M*M;if(x>4*u&&d--){var b=a+p,_=l+g,w=c+v,S=Math.sqrt(b*b+_*_+w*w),k=Math.asin(w/=S),N=xo(xo(w)-1)<Uo||xo(r-h)<Uo?(r+h)/2:Math.atan2(_,b),E=n(N,k),A=E[0],C=E[1],z=A-t,L=C-e,q=M*z-m*L;(q*q/x>u||xo((m*z+M*L)/x-.5)>.3||o>a*p+l*g+c*v)&&(i(t,e,r,a,l,c,A,C,N,b/=S,_/=S,w,d,y),y.point(A,C),i(A,C,N,b,_,w,f,s,h,p,g,v,d,y))}}var u=.5,o=Math.cos(30*Yo),a=16;return t.precision=function(n){return arguments.length?(a=(u=n*n)>0&&16,t):Math.sqrt(u)},t}function re(n){var t=ee(function(t,e){return n([t*Zo,e*Zo])});return function(n){return le(t(n))}}function ie(n){this.stream=n}function ue(n,t){return{point:t,sphere:function(){n.sphere()},lineStart:function(){n.lineStart()},lineEnd:function(){n.lineEnd()},polygonStart:function(){n.polygonStart()},polygonEnd:function(){n.polygonEnd()}}}function oe(n){return ae(function(){return n})()}function ae(n){function t(n){return n=a(n[0]*Yo,n[1]*Yo),[n[0]*h+l,c-n[1]*h]}function e(n){return n=a.invert((n[0]-l)/h,(c-n[1])/h),n&&[n[0]*Zo,n[1]*Zo]}function r(){a=Ct(o=se(y,M,x),u);var n=u(v,d);return l=p-n[0]*h,c=g+n[1]*h,i()}function i(){return f&&(f.valid=!1,f=null),t}var u,o,a,l,c,f,s=ee(function(n,t){return n=u(n,t),[n[0]*h+l,c-n[1]*h]}),h=150,p=480,g=250,v=0,d=0,y=0,M=0,x=0,b=Fa,_=m,w=null,S=null;return t.stream=function(n){return f&&(f.valid=!1),f=le(b(o,s(_(n)))),f.valid=!0,f},t.clipAngle=function(n){return arguments.length?(b=null==n?(w=n,Fa):It((w=+n)*Yo),i()):w},t.clipExtent=function(n){return arguments.length?(S=n,_=n?Zt(n[0][0],n[0][1],n[1][0],n[1][1]):m,i()):S},t.scale=function(n){return arguments.length?(h=+n,r()):h},t.translate=function(n){return arguments.length?(p=+n[0],g=+n[1],r()):[p,g]},t.center=function(n){return arguments.length?(v=n[0]%360*Yo,d=n[1]%360*Yo,r()):[v*Zo,d*Zo]},t.rotate=function(n){return arguments.length?(y=n[0]%360*Yo,M=n[1]%360*Yo,x=n.length>2?n[2]%360*Yo:0,r()):[y*Zo,M*Zo,x*Zo]},ao.rebind(t,s,\"precision\"),function(){return u=n.apply(this,arguments),t.invert=u.invert&&e,r()}}function le(n){return ue(n,function(t,e){n.point(t*Yo,e*Yo)})}function ce(n,t){return[n,t]}function fe(n,t){return[n>Fo?n-Ho:-Fo>n?n+Ho:n,t]}function se(n,t,e){return n?t||e?Ct(pe(n),ge(t,e)):pe(n):t||e?ge(t,e):fe}function he(n){return function(t,e){return t+=n,[t>Fo?t-Ho:-Fo>t?t+Ho:t,e]}}function pe(n){var t=he(n);return t.invert=he(-n),t}function ge(n,t){function e(n,t){var e=Math.cos(t),a=Math.cos(n)*e,l=Math.sin(n)*e,c=Math.sin(t),f=c*r+a*i;return[Math.atan2(l*u-f*o,a*r-c*i),tn(f*u+l*o)]}var r=Math.cos(n),i=Math.sin(n),u=Math.cos(t),o=Math.sin(t);return e.invert=function(n,t){var e=Math.cos(t),a=Math.cos(n)*e,l=Math.sin(n)*e,c=Math.sin(t),f=c*u-l*o;return[Math.atan2(l*u+c*o,a*r+f*i),tn(f*r-a*i)]},e}function ve(n,t){var e=Math.cos(n),r=Math.sin(n);return function(i,u,o,a){var l=o*t;null!=i?(i=de(e,i),u=de(e,u),(o>0?u>i:i>u)&&(i+=o*Ho)):(i=n+o*Ho,u=n-.5*l);for(var c,f=i;o>0?f>u:u>f;f-=l)a.point((c=_t([e,-r*Math.cos(f),-r*Math.sin(f)]))[0],c[1])}}function de(n,t){var e=dt(t);e[0]-=n,bt(e);var r=nn(-e[1]);return((-e[2]<0?-r:r)+2*Math.PI-Uo)%(2*Math.PI)}function ye(n,t,e){var r=ao.range(n,t-Uo,e).concat(t);return function(n){return r.map(function(t){return[n,t]})}}function me(n,t,e){var r=ao.range(n,t-Uo,e).concat(t);return function(n){return r.map(function(t){return[t,n]})}}function Me(n){return n.source}function xe(n){return n.target}function be(n,t,e,r){var i=Math.cos(t),u=Math.sin(t),o=Math.cos(r),a=Math.sin(r),l=i*Math.cos(n),c=i*Math.sin(n),f=o*Math.cos(e),s=o*Math.sin(e),h=2*Math.asin(Math.sqrt(on(r-t)+i*o*on(e-n))),p=1/Math.sin(h),g=h?function(n){var t=Math.sin(n*=h)*p,e=Math.sin(h-n)*p,r=e*l+t*f,i=e*c+t*s,o=e*u+t*a;return[Math.atan2(i,r)*Zo,Math.atan2(o,Math.sqrt(r*r+i*i))*Zo]}:function(){return[n*Zo,t*Zo]};return g.distance=h,g}function _e(){function n(n,i){var u=Math.sin(i*=Yo),o=Math.cos(i),a=xo((n*=Yo)-t),l=Math.cos(a);Ja+=Math.atan2(Math.sqrt((a=o*Math.sin(a))*a+(a=r*u-e*o*l)*a),e*u+r*o*l),t=n,e=u,r=o}var t,e,r;Ga.point=function(i,u){t=i*Yo,e=Math.sin(u*=Yo),r=Math.cos(u),Ga.point=n},Ga.lineEnd=function(){Ga.point=Ga.lineEnd=b}}function we(n,t){function e(t,e){var r=Math.cos(t),i=Math.cos(e),u=n(r*i);return[u*i*Math.sin(t),u*Math.sin(e)]}return e.invert=function(n,e){var r=Math.sqrt(n*n+e*e),i=t(r),u=Math.sin(i),o=Math.cos(i);return[Math.atan2(n*u,r*o),Math.asin(r&&e*u/r)]},e}function Se(n,t){function e(n,t){o>0?-Io+Uo>t&&(t=-Io+Uo):t>Io-Uo&&(t=Io-Uo);var e=o/Math.pow(i(t),u);return[e*Math.sin(u*n),o-e*Math.cos(u*n)]}var r=Math.cos(n),i=function(n){return Math.tan(Fo/4+n/2)},u=n===t?Math.sin(n):Math.log(r/Math.cos(t))/Math.log(i(t)/i(n)),o=r*Math.pow(i(n),u)/u;return u?(e.invert=function(n,t){var e=o-t,r=K(u)*Math.sqrt(n*n+e*e);return[Math.atan2(n,e)/u,2*Math.atan(Math.pow(o/r,1/u))-Io]},e):Ne}function ke(n,t){function e(n,t){var e=u-t;return[e*Math.sin(i*n),u-e*Math.cos(i*n)]}var r=Math.cos(n),i=n===t?Math.sin(n):(r-Math.cos(t))/(t-n),u=r/i+n;return xo(i)<Uo?ce:(e.invert=function(n,t){var e=u-t;return[Math.atan2(n,e)/i,u-K(i)*Math.sqrt(n*n+e*e)]},e)}function Ne(n,t){return[n,Math.log(Math.tan(Fo/4+t/2))]}function Ee(n){var t,e=oe(n),r=e.scale,i=e.translate,u=e.clipExtent;return e.scale=function(){var n=r.apply(e,arguments);return n===e?t?e.clipExtent(null):e:n},e.translate=function(){var n=i.apply(e,arguments);return n===e?t?e.clipExtent(null):e:n},e.clipExtent=function(n){var o=u.apply(e,arguments);if(o===e){if(t=null==n){var a=Fo*r(),l=i();u([[l[0]-a,l[1]-a],[l[0]+a,l[1]+a]])}}else t&&(o=null);return o},e.clipExtent(null)}function Ae(n,t){return[Math.log(Math.tan(Fo/4+t/2)),-n]}function Ce(n){return n[0]}function ze(n){return n[1]}function Le(n){for(var t=n.length,e=[0,1],r=2,i=2;t>i;i++){for(;r>1&&Q(n[e[r-2]],n[e[r-1]],n[i])<=0;)--r;e[r++]=i}return e.slice(0,r)}function qe(n,t){return n[0]-t[0]||n[1]-t[1]}function Te(n,t,e){return(e[0]-t[0])*(n[1]-t[1])<(e[1]-t[1])*(n[0]-t[0])}function Re(n,t,e,r){var i=n[0],u=e[0],o=t[0]-i,a=r[0]-u,l=n[1],c=e[1],f=t[1]-l,s=r[1]-c,h=(a*(l-c)-s*(i-u))/(s*o-a*f);return[i+h*o,l+h*f]}function De(n){var t=n[0],e=n[n.length-1];return!(t[0]-e[0]||t[1]-e[1])}function Pe(){rr(this),this.edge=this.site=this.circle=null}function Ue(n){var t=cl.pop()||new Pe;return t.site=n,t}function je(n){Be(n),ol.remove(n),cl.push(n),rr(n)}function Fe(n){var t=n.circle,e=t.x,r=t.cy,i={x:e,y:r},u=n.P,o=n.N,a=[n];je(n);for(var l=u;l.circle&&xo(e-l.circle.x)<Uo&&xo(r-l.circle.cy)<Uo;)u=l.P,a.unshift(l),je(l),l=u;a.unshift(l),Be(l);for(var c=o;c.circle&&xo(e-c.circle.x)<Uo&&xo(r-c.circle.cy)<Uo;)o=c.N,a.push(c),je(c),c=o;a.push(c),Be(c);var f,s=a.length;for(f=1;s>f;++f)c=a[f],l=a[f-1],nr(c.edge,l.site,c.site,i);l=a[0],c=a[s-1],c.edge=Ke(l.site,c.site,null,i),$e(l),$e(c)}function He(n){for(var t,e,r,i,u=n.x,o=n.y,a=ol._;a;)if(r=Oe(a,o)-u,r>Uo)a=a.L;else{if(i=u-Ie(a,o),!(i>Uo)){r>-Uo?(t=a.P,e=a):i>-Uo?(t=a,e=a.N):t=e=a;break}if(!a.R){t=a;break}a=a.R}var l=Ue(n);if(ol.insert(t,l),t||e){if(t===e)return Be(t),e=Ue(t.site),ol.insert(l,e),l.edge=e.edge=Ke(t.site,l.site),$e(t),void $e(e);if(!e)return void(l.edge=Ke(t.site,l.site));Be(t),Be(e);var c=t.site,f=c.x,s=c.y,h=n.x-f,p=n.y-s,g=e.site,v=g.x-f,d=g.y-s,y=2*(h*d-p*v),m=h*h+p*p,M=v*v+d*d,x={x:(d*m-p*M)/y+f,y:(h*M-v*m)/y+s};nr(e.edge,c,g,x),l.edge=Ke(c,n,null,x),e.edge=Ke(n,g,null,x),$e(t),$e(e)}}function Oe(n,t){var e=n.site,r=e.x,i=e.y,u=i-t;if(!u)return r;var o=n.P;if(!o)return-(1/0);e=o.site;var a=e.x,l=e.y,c=l-t;if(!c)return a;var f=a-r,s=1/u-1/c,h=f/c;return s?(-h+Math.sqrt(h*h-2*s*(f*f/(-2*c)-l+c/2+i-u/2)))/s+r:(r+a)/2}function Ie(n,t){var e=n.N;if(e)return Oe(e,t);var r=n.site;return r.y===t?r.x:1/0}function Ye(n){this.site=n,this.edges=[]}function Ze(n){for(var t,e,r,i,u,o,a,l,c,f,s=n[0][0],h=n[1][0],p=n[0][1],g=n[1][1],v=ul,d=v.length;d--;)if(u=v[d],u&&u.prepare())for(a=u.edges,l=a.length,o=0;l>o;)f=a[o].end(),r=f.x,i=f.y,c=a[++o%l].start(),t=c.x,e=c.y,(xo(r-t)>Uo||xo(i-e)>Uo)&&(a.splice(o,0,new tr(Qe(u.site,f,xo(r-s)<Uo&&g-i>Uo?{x:s,y:xo(t-s)<Uo?e:g}:xo(i-g)<Uo&&h-r>Uo?{x:xo(e-g)<Uo?t:h,y:g}:xo(r-h)<Uo&&i-p>Uo?{x:h,y:xo(t-h)<Uo?e:p}:xo(i-p)<Uo&&r-s>Uo?{x:xo(e-p)<Uo?t:s,y:p}:null),u.site,null)),++l)}function Ve(n,t){return t.angle-n.angle}function Xe(){rr(this),this.x=this.y=this.arc=this.site=this.cy=null}function $e(n){var t=n.P,e=n.N;if(t&&e){var r=t.site,i=n.site,u=e.site;if(r!==u){var o=i.x,a=i.y,l=r.x-o,c=r.y-a,f=u.x-o,s=u.y-a,h=2*(l*s-c*f);if(!(h>=-jo)){var p=l*l+c*c,g=f*f+s*s,v=(s*p-c*g)/h,d=(l*g-f*p)/h,s=d+a,y=fl.pop()||new Xe;y.arc=n,y.site=i,y.x=v+o,y.y=s+Math.sqrt(v*v+d*d),y.cy=s,n.circle=y;for(var m=null,M=ll._;M;)if(y.y<M.y||y.y===M.y&&y.x<=M.x){if(!M.L){m=M.P;break}M=M.L}else{if(!M.R){m=M;break}M=M.R}ll.insert(m,y),m||(al=y)}}}}function Be(n){var t=n.circle;t&&(t.P||(al=t.N),ll.remove(t),fl.push(t),rr(t),n.circle=null)}function We(n){for(var t,e=il,r=Yt(n[0][0],n[0][1],n[1][0],n[1][1]),i=e.length;i--;)t=e[i],(!Je(t,n)||!r(t)||xo(t.a.x-t.b.x)<Uo&&xo(t.a.y-t.b.y)<Uo)&&(t.a=t.b=null,e.splice(i,1))}function Je(n,t){var e=n.b;if(e)return!0;var r,i,u=n.a,o=t[0][0],a=t[1][0],l=t[0][1],c=t[1][1],f=n.l,s=n.r,h=f.x,p=f.y,g=s.x,v=s.y,d=(h+g)/2,y=(p+v)/2;if(v===p){if(o>d||d>=a)return;if(h>g){if(u){if(u.y>=c)return}else u={x:d,y:l};e={x:d,y:c}}else{if(u){if(u.y<l)return}else u={x:d,y:c};e={x:d,y:l}}}else if(r=(h-g)/(v-p),i=y-r*d,-1>r||r>1)if(h>g){if(u){if(u.y>=c)return}else u={x:(l-i)/r,y:l};e={x:(c-i)/r,y:c}}else{if(u){if(u.y<l)return}else u={x:(c-i)/r,y:c};e={x:(l-i)/r,y:l}}else if(v>p){if(u){if(u.x>=a)return}else u={x:o,y:r*o+i};e={x:a,y:r*a+i}}else{if(u){if(u.x<o)return}else u={x:a,y:r*a+i};e={x:o,y:r*o+i}}return n.a=u,n.b=e,!0}function Ge(n,t){this.l=n,this.r=t,this.a=this.b=null}function Ke(n,t,e,r){var i=new Ge(n,t);return il.push(i),e&&nr(i,n,t,e),r&&nr(i,t,n,r),ul[n.i].edges.push(new tr(i,n,t)),ul[t.i].edges.push(new tr(i,t,n)),i}function Qe(n,t,e){var r=new Ge(n,null);return r.a=t,r.b=e,il.push(r),r}function nr(n,t,e,r){n.a||n.b?n.l===e?n.b=r:n.a=r:(n.a=r,n.l=t,n.r=e)}function tr(n,t,e){var r=n.a,i=n.b;this.edge=n,this.site=t,this.angle=e?Math.atan2(e.y-t.y,e.x-t.x):n.l===t?Math.atan2(i.x-r.x,r.y-i.y):Math.atan2(r.x-i.x,i.y-r.y)}function er(){this._=null}function rr(n){n.U=n.C=n.L=n.R=n.P=n.N=null}function ir(n,t){var e=t,r=t.R,i=e.U;i?i.L===e?i.L=r:i.R=r:n._=r,r.U=i,e.U=r,e.R=r.L,e.R&&(e.R.U=e),r.L=e}function ur(n,t){var e=t,r=t.L,i=e.U;i?i.L===e?i.L=r:i.R=r:n._=r,r.U=i,e.U=r,e.L=r.R,e.L&&(e.L.U=e),r.R=e}function or(n){for(;n.L;)n=n.L;return n}function ar(n,t){var e,r,i,u=n.sort(lr).pop();for(il=[],ul=new Array(n.length),ol=new er,ll=new er;;)if(i=al,u&&(!i||u.y<i.y||u.y===i.y&&u.x<i.x))u.x===e&&u.y===r||(ul[u.i]=new Ye(u),He(u),e=u.x,r=u.y),u=n.pop();else{if(!i)break;Fe(i.arc)}t&&(We(t),Ze(t));var o={cells:ul,edges:il};return ol=ll=il=ul=null,o}function lr(n,t){return t.y-n.y||t.x-n.x}function cr(n,t,e){return(n.x-e.x)*(t.y-n.y)-(n.x-t.x)*(e.y-n.y)}function fr(n){return n.x}function sr(n){return n.y}function hr(){return{leaf:!0,nodes:[],point:null,x:null,y:null}}function pr(n,t,e,r,i,u){if(!n(t,e,r,i,u)){var o=.5*(e+i),a=.5*(r+u),l=t.nodes;l[0]&&pr(n,l[0],e,r,o,a),l[1]&&pr(n,l[1],o,r,i,a),l[2]&&pr(n,l[2],e,a,o,u),l[3]&&pr(n,l[3],o,a,i,u)}}function gr(n,t,e,r,i,u,o){var a,l=1/0;return function c(n,f,s,h,p){if(!(f>u||s>o||r>h||i>p)){if(g=n.point){var g,v=t-n.x,d=e-n.y,y=v*v+d*d;if(l>y){var m=Math.sqrt(l=y);r=t-m,i=e-m,u=t+m,o=e+m,a=g}}for(var M=n.nodes,x=.5*(f+h),b=.5*(s+p),_=t>=x,w=e>=b,S=w<<1|_,k=S+4;k>S;++S)if(n=M[3&S])switch(3&S){case 0:c(n,f,s,x,b);break;case 1:c(n,x,s,h,b);break;case 2:c(n,f,b,x,p);break;case 3:c(n,x,b,h,p)}}}(n,r,i,u,o),a}function vr(n,t){n=ao.rgb(n),t=ao.rgb(t);var e=n.r,r=n.g,i=n.b,u=t.r-e,o=t.g-r,a=t.b-i;return function(n){return\"#\"+bn(Math.round(e+u*n))+bn(Math.round(r+o*n))+bn(Math.round(i+a*n))}}function dr(n,t){var e,r={},i={};for(e in n)e in t?r[e]=Mr(n[e],t[e]):i[e]=n[e];for(e in t)e in n||(i[e]=t[e]);return function(n){for(e in r)i[e]=r[e](n);return i}}function yr(n,t){return n=+n,t=+t,function(e){return n*(1-e)+t*e}}function mr(n,t){var e,r,i,u=hl.lastIndex=pl.lastIndex=0,o=-1,a=[],l=[];for(n+=\"\",t+=\"\";(e=hl.exec(n))&&(r=pl.exec(t));)(i=r.index)>u&&(i=t.slice(u,i),a[o]?a[o]+=i:a[++o]=i),(e=e[0])===(r=r[0])?a[o]?a[o]+=r:a[++o]=r:(a[++o]=null,l.push({i:o,x:yr(e,r)})),u=pl.lastIndex;return u<t.length&&(i=t.slice(u),a[o]?a[o]+=i:a[++o]=i),a.length<2?l[0]?(t=l[0].x,function(n){return t(n)+\"\"}):function(){return t}:(t=l.length,function(n){for(var e,r=0;t>r;++r)a[(e=l[r]).i]=e.x(n);return a.join(\"\")})}function Mr(n,t){for(var e,r=ao.interpolators.length;--r>=0&&!(e=ao.interpolators[r](n,t)););return e}function xr(n,t){var e,r=[],i=[],u=n.length,o=t.length,a=Math.min(n.length,t.length);for(e=0;a>e;++e)r.push(Mr(n[e],t[e]));for(;u>e;++e)i[e]=n[e];for(;o>e;++e)i[e]=t[e];return function(n){for(e=0;a>e;++e)i[e]=r[e](n);return i}}function br(n){return function(t){return 0>=t?0:t>=1?1:n(t)}}function _r(n){return function(t){return 1-n(1-t)}}function wr(n){return function(t){return.5*(.5>t?n(2*t):2-n(2-2*t))}}function Sr(n){return n*n}function kr(n){return n*n*n}function Nr(n){if(0>=n)return 0;if(n>=1)return 1;var t=n*n,e=t*n;return 4*(.5>n?e:3*(n-t)+e-.75)}function Er(n){return function(t){return Math.pow(t,n)}}function Ar(n){return 1-Math.cos(n*Io)}function Cr(n){return Math.pow(2,10*(n-1))}function zr(n){return 1-Math.sqrt(1-n*n)}function Lr(n,t){var e;return arguments.length<2&&(t=.45),arguments.length?e=t/Ho*Math.asin(1/n):(n=1,e=t/4),function(r){return 1+n*Math.pow(2,-10*r)*Math.sin((r-e)*Ho/t)}}function qr(n){return n||(n=1.70158),function(t){return t*t*((n+1)*t-n)}}function Tr(n){return 1/2.75>n?7.5625*n*n:2/2.75>n?7.5625*(n-=1.5/2.75)*n+.75:2.5/2.75>n?7.5625*(n-=2.25/2.75)*n+.9375:7.5625*(n-=2.625/2.75)*n+.984375}function Rr(n,t){n=ao.hcl(n),t=ao.hcl(t);var e=n.h,r=n.c,i=n.l,u=t.h-e,o=t.c-r,a=t.l-i;return isNaN(o)&&(o=0,r=isNaN(r)?t.c:r),isNaN(u)?(u=0,e=isNaN(e)?t.h:e):u>180?u-=360:-180>u&&(u+=360),function(n){return sn(e+u*n,r+o*n,i+a*n)+\"\"}}function Dr(n,t){n=ao.hsl(n),t=ao.hsl(t);var e=n.h,r=n.s,i=n.l,u=t.h-e,o=t.s-r,a=t.l-i;return isNaN(o)&&(o=0,r=isNaN(r)?t.s:r),isNaN(u)?(u=0,e=isNaN(e)?t.h:e):u>180?u-=360:-180>u&&(u+=360),function(n){return cn(e+u*n,r+o*n,i+a*n)+\"\"}}function Pr(n,t){n=ao.lab(n),t=ao.lab(t);var e=n.l,r=n.a,i=n.b,u=t.l-e,o=t.a-r,a=t.b-i;return function(n){return pn(e+u*n,r+o*n,i+a*n)+\"\"}}function Ur(n,t){return t-=n,function(e){return Math.round(n+t*e)}}function jr(n){var t=[n.a,n.b],e=[n.c,n.d],r=Hr(t),i=Fr(t,e),u=Hr(Or(e,t,-i))||0;t[0]*e[1]<e[0]*t[1]&&(t[0]*=-1,t[1]*=-1,r*=-1,i*=-1),this.rotate=(r?Math.atan2(t[1],t[0]):Math.atan2(-e[0],e[1]))*Zo,this.translate=[n.e,n.f],this.scale=[r,u],this.skew=u?Math.atan2(i,u)*Zo:0}function Fr(n,t){return n[0]*t[0]+n[1]*t[1]}function Hr(n){var t=Math.sqrt(Fr(n,n));return t&&(n[0]/=t,n[1]/=t),t}function Or(n,t,e){return n[0]+=e*t[0],n[1]+=e*t[1],n}function Ir(n){return n.length?n.pop()+\",\":\"\"}function Yr(n,t,e,r){if(n[0]!==t[0]||n[1]!==t[1]){var i=e.push(\"translate(\",null,\",\",null,\")\");r.push({i:i-4,x:yr(n[0],t[0])},{i:i-2,x:yr(n[1],t[1])})}else(t[0]||t[1])&&e.push(\"translate(\"+t+\")\")}function Zr(n,t,e,r){n!==t?(n-t>180?t+=360:t-n>180&&(n+=360),r.push({i:e.push(Ir(e)+\"rotate(\",null,\")\")-2,x:yr(n,t)})):t&&e.push(Ir(e)+\"rotate(\"+t+\")\")}function Vr(n,t,e,r){n!==t?r.push({i:e.push(Ir(e)+\"skewX(\",null,\")\")-2,x:yr(n,t)}):t&&e.push(Ir(e)+\"skewX(\"+t+\")\")}function Xr(n,t,e,r){if(n[0]!==t[0]||n[1]!==t[1]){var i=e.push(Ir(e)+\"scale(\",null,\",\",null,\")\");r.push({i:i-4,x:yr(n[0],t[0])},{i:i-2,x:yr(n[1],t[1])})}else 1===t[0]&&1===t[1]||e.push(Ir(e)+\"scale(\"+t+\")\")}function $r(n,t){var e=[],r=[];return n=ao.transform(n),t=ao.transform(t),Yr(n.translate,t.translate,e,r),Zr(n.rotate,t.rotate,e,r),Vr(n.skew,t.skew,e,r),Xr(n.scale,t.scale,e,r),n=t=null,function(n){for(var t,i=-1,u=r.length;++i<u;)e[(t=r[i]).i]=t.x(n);return e.join(\"\")}}function Br(n,t){return t=(t-=n=+n)||1/t,function(e){return(e-n)/t}}function Wr(n,t){return t=(t-=n=+n)||1/t,function(e){return Math.max(0,Math.min(1,(e-n)/t))}}function Jr(n){for(var t=n.source,e=n.target,r=Kr(t,e),i=[t];t!==r;)t=t.parent,i.push(t);for(var u=i.length;e!==r;)i.splice(u,0,e),e=e.parent;return i}function Gr(n){for(var t=[],e=n.parent;null!=e;)t.push(n),n=e,e=e.parent;return t.push(n),t}function Kr(n,t){if(n===t)return n;for(var e=Gr(n),r=Gr(t),i=e.pop(),u=r.pop(),o=null;i===u;)o=i,i=e.pop(),u=r.pop();return o}function Qr(n){n.fixed|=2}function ni(n){n.fixed&=-7}function ti(n){n.fixed|=4,n.px=n.x,n.py=n.y}function ei(n){n.fixed&=-5}function ri(n,t,e){var r=0,i=0;if(n.charge=0,!n.leaf)for(var u,o=n.nodes,a=o.length,l=-1;++l<a;)u=o[l],null!=u&&(ri(u,t,e),n.charge+=u.charge,r+=u.charge*u.cx,i+=u.charge*u.cy);if(n.point){n.leaf||(n.point.x+=Math.random()-.5,n.point.y+=Math.random()-.5);var c=t*e[n.point.index];n.charge+=n.pointCharge=c,r+=c*n.point.x,i+=c*n.point.y}n.cx=r/n.charge,n.cy=i/n.charge}function ii(n,t){return ao.rebind(n,t,\"sort\",\"children\",\"value\"),n.nodes=n,n.links=fi,n}function ui(n,t){for(var e=[n];null!=(n=e.pop());)if(t(n),(i=n.children)&&(r=i.length))for(var r,i;--r>=0;)e.push(i[r])}function oi(n,t){for(var e=[n],r=[];null!=(n=e.pop());)if(r.push(n),(u=n.children)&&(i=u.length))for(var i,u,o=-1;++o<i;)e.push(u[o]);for(;null!=(n=r.pop());)t(n)}function ai(n){return n.children}function li(n){return n.value}function ci(n,t){return t.value-n.value}function fi(n){return ao.merge(n.map(function(n){return(n.children||[]).map(function(t){return{source:n,target:t}})}))}function si(n){return n.x}function hi(n){return n.y}function pi(n,t,e){n.y0=t,n.y=e}function gi(n){return ao.range(n.length)}function vi(n){for(var t=-1,e=n[0].length,r=[];++t<e;)r[t]=0;return r}function di(n){for(var t,e=1,r=0,i=n[0][1],u=n.length;u>e;++e)(t=n[e][1])>i&&(r=e,i=t);return r}function yi(n){return n.reduce(mi,0)}function mi(n,t){return n+t[1]}function Mi(n,t){return xi(n,Math.ceil(Math.log(t.length)/Math.LN2+1))}function xi(n,t){for(var e=-1,r=+n[0],i=(n[1]-r)/t,u=[];++e<=t;)u[e]=i*e+r;return u}function bi(n){return[ao.min(n),ao.max(n)]}function _i(n,t){return n.value-t.value}function wi(n,t){var e=n._pack_next;n._pack_next=t,t._pack_prev=n,t._pack_next=e,e._pack_prev=t}function Si(n,t){n._pack_next=t,t._pack_prev=n}function ki(n,t){var e=t.x-n.x,r=t.y-n.y,i=n.r+t.r;return.999*i*i>e*e+r*r}function Ni(n){function t(n){f=Math.min(n.x-n.r,f),s=Math.max(n.x+n.r,s),h=Math.min(n.y-n.r,h),p=Math.max(n.y+n.r,p)}if((e=n.children)&&(c=e.length)){var e,r,i,u,o,a,l,c,f=1/0,s=-(1/0),h=1/0,p=-(1/0);if(e.forEach(Ei),r=e[0],r.x=-r.r,r.y=0,t(r),c>1&&(i=e[1],i.x=i.r,i.y=0,t(i),c>2))for(u=e[2],zi(r,i,u),t(u),wi(r,u),r._pack_prev=u,wi(u,i),i=r._pack_next,o=3;c>o;o++){zi(r,i,u=e[o]);var g=0,v=1,d=1;for(a=i._pack_next;a!==i;a=a._pack_next,v++)if(ki(a,u)){g=1;break}if(1==g)for(l=r._pack_prev;l!==a._pack_prev&&!ki(l,u);l=l._pack_prev,d++);g?(d>v||v==d&&i.r<r.r?Si(r,i=a):Si(r=l,i),o--):(wi(r,u),i=u,t(u))}var y=(f+s)/2,m=(h+p)/2,M=0;for(o=0;c>o;o++)u=e[o],u.x-=y,u.y-=m,M=Math.max(M,u.r+Math.sqrt(u.x*u.x+u.y*u.y));n.r=M,e.forEach(Ai)}}function Ei(n){n._pack_next=n._pack_prev=n}function Ai(n){delete n._pack_next,delete n._pack_prev}function Ci(n,t,e,r){var i=n.children;if(n.x=t+=r*n.x,n.y=e+=r*n.y,n.r*=r,i)for(var u=-1,o=i.length;++u<o;)Ci(i[u],t,e,r)}function zi(n,t,e){var r=n.r+e.r,i=t.x-n.x,u=t.y-n.y;if(r&&(i||u)){var o=t.r+e.r,a=i*i+u*u;o*=o,r*=r;var l=.5+(r-o)/(2*a),c=Math.sqrt(Math.max(0,2*o*(r+a)-(r-=a)*r-o*o))/(2*a);e.x=n.x+l*i+c*u,e.y=n.y+l*u-c*i}else e.x=n.x+r,e.y=n.y}function Li(n,t){return n.parent==t.parent?1:2}function qi(n){var t=n.children;return t.length?t[0]:n.t}function Ti(n){var t,e=n.children;return(t=e.length)?e[t-1]:n.t}function Ri(n,t,e){var r=e/(t.i-n.i);t.c-=r,t.s+=e,n.c+=r,t.z+=e,t.m+=e}function Di(n){for(var t,e=0,r=0,i=n.children,u=i.length;--u>=0;)t=i[u],t.z+=e,t.m+=e,e+=t.s+(r+=t.c)}function Pi(n,t,e){return n.a.parent===t.parent?n.a:e}function Ui(n){return 1+ao.max(n,function(n){return n.y})}function ji(n){return n.reduce(function(n,t){return n+t.x},0)/n.length}function Fi(n){var t=n.children;return t&&t.length?Fi(t[0]):n}function Hi(n){var t,e=n.children;return e&&(t=e.length)?Hi(e[t-1]):n}function Oi(n){return{x:n.x,y:n.y,dx:n.dx,dy:n.dy}}function Ii(n,t){var e=n.x+t[3],r=n.y+t[0],i=n.dx-t[1]-t[3],u=n.dy-t[0]-t[2];return 0>i&&(e+=i/2,i=0),0>u&&(r+=u/2,u=0),{x:e,y:r,dx:i,dy:u}}function Yi(n){var t=n[0],e=n[n.length-1];return e>t?[t,e]:[e,t]}function Zi(n){return n.rangeExtent?n.rangeExtent():Yi(n.range())}function Vi(n,t,e,r){var i=e(n[0],n[1]),u=r(t[0],t[1]);return function(n){return u(i(n))}}function Xi(n,t){var e,r=0,i=n.length-1,u=n[r],o=n[i];return u>o&&(e=r,r=i,i=e,e=u,u=o,o=e),n[r]=t.floor(u),n[i]=t.ceil(o),n}function $i(n){return n?{floor:function(t){return Math.floor(t/n)*n},ceil:function(t){return Math.ceil(t/n)*n}}:Sl}function Bi(n,t,e,r){var i=[],u=[],o=0,a=Math.min(n.length,t.length)-1;for(n[a]<n[0]&&(n=n.slice().reverse(),t=t.slice().reverse());++o<=a;)i.push(e(n[o-1],n[o])),u.push(r(t[o-1],t[o]));return function(t){var e=ao.bisect(n,t,1,a)-1;return u[e](i[e](t))}}function Wi(n,t,e,r){function i(){var i=Math.min(n.length,t.length)>2?Bi:Vi,l=r?Wr:Br;return o=i(n,t,l,e),a=i(t,n,l,Mr),u}function u(n){return o(n)}var o,a;return u.invert=function(n){return a(n)},u.domain=function(t){return arguments.length?(n=t.map(Number),i()):n},u.range=function(n){return arguments.length?(t=n,i()):t},u.rangeRound=function(n){return u.range(n).interpolate(Ur)},u.clamp=function(n){return arguments.length?(r=n,i()):r},u.interpolate=function(n){return arguments.length?(e=n,i()):e},u.ticks=function(t){return Qi(n,t)},u.tickFormat=function(t,e){return nu(n,t,e)},u.nice=function(t){return Gi(n,t),i()},u.copy=function(){return Wi(n,t,e,r)},i()}function Ji(n,t){return ao.rebind(n,t,\"range\",\"rangeRound\",\"interpolate\",\"clamp\")}function Gi(n,t){return Xi(n,$i(Ki(n,t)[2])),Xi(n,$i(Ki(n,t)[2])),n}function Ki(n,t){null==t&&(t=10);var e=Yi(n),r=e[1]-e[0],i=Math.pow(10,Math.floor(Math.log(r/t)/Math.LN10)),u=t/r*i;return.15>=u?i*=10:.35>=u?i*=5:.75>=u&&(i*=2),e[0]=Math.ceil(e[0]/i)*i,e[1]=Math.floor(e[1]/i)*i+.5*i,e[2]=i,e}function Qi(n,t){return ao.range.apply(ao,Ki(n,t))}function nu(n,t,e){var r=Ki(n,t);if(e){var i=ha.exec(e);if(i.shift(),\"s\"===i[8]){var u=ao.formatPrefix(Math.max(xo(r[0]),xo(r[1])));return i[7]||(i[7]=\".\"+tu(u.scale(r[2]))),i[8]=\"f\",e=ao.format(i.join(\"\")),function(n){return e(u.scale(n))+u.symbol}}i[7]||(i[7]=\".\"+eu(i[8],r)),e=i.join(\"\")}else e=\",.\"+tu(r[2])+\"f\";return ao.format(e)}function tu(n){return-Math.floor(Math.log(n)/Math.LN10+.01)}function eu(n,t){var e=tu(t[2]);return n in kl?Math.abs(e-tu(Math.max(xo(t[0]),xo(t[1]))))+ +(\"e\"!==n):e-2*(\"%\"===n)}function ru(n,t,e,r){function i(n){return(e?Math.log(0>n?0:n):-Math.log(n>0?0:-n))/Math.log(t)}function u(n){return e?Math.pow(t,n):-Math.pow(t,-n)}function o(t){return n(i(t))}return o.invert=function(t){return u(n.invert(t))},o.domain=function(t){return arguments.length?(e=t[0]>=0,n.domain((r=t.map(Number)).map(i)),o):r},o.base=function(e){return arguments.length?(t=+e,n.domain(r.map(i)),o):t},o.nice=function(){var t=Xi(r.map(i),e?Math:El);return n.domain(t),r=t.map(u),o},o.ticks=function(){var n=Yi(r),o=[],a=n[0],l=n[1],c=Math.floor(i(a)),f=Math.ceil(i(l)),s=t%1?2:t;if(isFinite(f-c)){if(e){for(;f>c;c++)for(var h=1;s>h;h++)o.push(u(c)*h);o.push(u(c))}else for(o.push(u(c));c++<f;)for(var h=s-1;h>0;h--)o.push(u(c)*h);for(c=0;o[c]<a;c++);for(f=o.length;o[f-1]>l;f--);o=o.slice(c,f)}return o},o.tickFormat=function(n,e){if(!arguments.length)return Nl;arguments.length<2?e=Nl:\"function\"!=typeof e&&(e=ao.format(e));var r=Math.max(1,t*n/o.ticks().length);return function(n){var o=n/u(Math.round(i(n)));return t-.5>o*t&&(o*=t),r>=o?e(n):\"\"}},o.copy=function(){return ru(n.copy(),t,e,r)},Ji(o,n)}function iu(n,t,e){function r(t){return n(i(t))}var i=uu(t),u=uu(1/t);return r.invert=function(t){return u(n.invert(t))},r.domain=function(t){return arguments.length?(n.domain((e=t.map(Number)).map(i)),r):e},r.ticks=function(n){return Qi(e,n)},r.tickFormat=function(n,t){return nu(e,n,t)},r.nice=function(n){return r.domain(Gi(e,n))},r.exponent=function(o){return arguments.length?(i=uu(t=o),u=uu(1/t),n.domain(e.map(i)),r):t},r.copy=function(){return iu(n.copy(),t,e)},Ji(r,n)}function uu(n){return function(t){return 0>t?-Math.pow(-t,n):Math.pow(t,n)}}function ou(n,t){function e(e){return u[((i.get(e)||(\"range\"===t.t?i.set(e,n.push(e)):NaN))-1)%u.length]}function r(t,e){return ao.range(n.length).map(function(n){return t+e*n})}var i,u,o;return e.domain=function(r){if(!arguments.length)return n;n=[],i=new c;for(var u,o=-1,a=r.length;++o<a;)i.has(u=r[o])||i.set(u,n.push(u));return e[t.t].apply(e,t.a)},e.range=function(n){return arguments.length?(u=n,o=0,t={t:\"range\",a:arguments},e):u},e.rangePoints=function(i,a){arguments.length<2&&(a=0);var l=i[0],c=i[1],f=n.length<2?(l=(l+c)/2,0):(c-l)/(n.length-1+a);return u=r(l+f*a/2,f),o=0,t={t:\"rangePoints\",a:arguments},e},e.rangeRoundPoints=function(i,a){arguments.length<2&&(a=0);var l=i[0],c=i[1],f=n.length<2?(l=c=Math.round((l+c)/2),0):(c-l)/(n.length-1+a)|0;return u=r(l+Math.round(f*a/2+(c-l-(n.length-1+a)*f)/2),f),o=0,t={t:\"rangeRoundPoints\",a:arguments},e},e.rangeBands=function(i,a,l){arguments.length<2&&(a=0),arguments.length<3&&(l=a);var c=i[1]<i[0],f=i[c-0],s=i[1-c],h=(s-f)/(n.length-a+2*l);return u=r(f+h*l,h),c&&u.reverse(),o=h*(1-a),t={t:\"rangeBands\",a:arguments},e},e.rangeRoundBands=function(i,a,l){arguments.length<2&&(a=0),arguments.length<3&&(l=a);var c=i[1]<i[0],f=i[c-0],s=i[1-c],h=Math.floor((s-f)/(n.length-a+2*l));return u=r(f+Math.round((s-f-(n.length-a)*h)/2),h),c&&u.reverse(),o=Math.round(h*(1-a)),t={t:\"rangeRoundBands\",a:arguments},e},e.rangeBand=function(){return o},e.rangeExtent=function(){return Yi(t.a[0])},e.copy=function(){return ou(n,t)},e.domain(n)}function au(n,t){function u(){var e=0,r=t.length;for(a=[];++e<r;)a[e-1]=ao.quantile(n,e/r);return o}function o(n){return isNaN(n=+n)?void 0:t[ao.bisect(a,n)]}var a;return o.domain=function(t){return arguments.length?(n=t.map(r).filter(i).sort(e),u()):n},o.range=function(n){return arguments.length?(t=n,u()):t},o.quantiles=function(){return a},o.invertExtent=function(e){return e=t.indexOf(e),0>e?[NaN,NaN]:[e>0?a[e-1]:n[0],e<a.length?a[e]:n[n.length-1]]},o.copy=function(){return au(n,t)},u()}function lu(n,t,e){function r(t){return e[Math.max(0,Math.min(o,Math.floor(u*(t-n))))]}function i(){return u=e.length/(t-n),o=e.length-1,r}var u,o;return r.domain=function(e){return arguments.length?(n=+e[0],t=+e[e.length-1],i()):[n,t]},r.range=function(n){return arguments.length?(e=n,i()):e},r.invertExtent=function(t){return t=e.indexOf(t),t=0>t?NaN:t/u+n,[t,t+1/u]},r.copy=function(){return lu(n,t,e)},i()}function cu(n,t){function e(e){return e>=e?t[ao.bisect(n,e)]:void 0}return e.domain=function(t){return arguments.length?(n=t,e):n},e.range=function(n){return arguments.length?(t=n,e):t},e.invertExtent=function(e){return e=t.indexOf(e),[n[e-1],n[e]]},e.copy=function(){return cu(n,t)},e}function fu(n){function t(n){return+n}return t.invert=t,t.domain=t.range=function(e){return arguments.length?(n=e.map(t),t):n},t.ticks=function(t){return Qi(n,t)},t.tickFormat=function(t,e){return nu(n,t,e)},t.copy=function(){return fu(n)},t}function su(){return 0}function hu(n){return n.innerRadius}function pu(n){return n.outerRadius}function gu(n){return n.startAngle}function vu(n){return n.endAngle}function du(n){return n&&n.padAngle}function yu(n,t,e,r){return(n-e)*t-(t-r)*n>0?0:1}function mu(n,t,e,r,i){var u=n[0]-t[0],o=n[1]-t[1],a=(i?r:-r)/Math.sqrt(u*u+o*o),l=a*o,c=-a*u,f=n[0]+l,s=n[1]+c,h=t[0]+l,p=t[1]+c,g=(f+h)/2,v=(s+p)/2,d=h-f,y=p-s,m=d*d+y*y,M=e-r,x=f*p-h*s,b=(0>y?-1:1)*Math.sqrt(Math.max(0,M*M*m-x*x)),_=(x*y-d*b)/m,w=(-x*d-y*b)/m,S=(x*y+d*b)/m,k=(-x*d+y*b)/m,N=_-g,E=w-v,A=S-g,C=k-v;return N*N+E*E>A*A+C*C&&(_=S,w=k),[[_-l,w-c],[_*e/M,w*e/M]]}function Mu(n){function t(t){function o(){c.push(\"M\",u(n(f),a))}for(var l,c=[],f=[],s=-1,h=t.length,p=En(e),g=En(r);++s<h;)i.call(this,l=t[s],s)?f.push([+p.call(this,l,s),+g.call(this,l,s)]):f.length&&(o(),f=[]);return f.length&&o(),c.length?c.join(\"\"):null}var e=Ce,r=ze,i=zt,u=xu,o=u.key,a=.7;return t.x=function(n){return arguments.length?(e=n,t):e},t.y=function(n){return arguments.length?(r=n,t):r},t.defined=function(n){return arguments.length?(i=n,t):i},t.interpolate=function(n){return arguments.length?(o=\"function\"==typeof n?u=n:(u=Tl.get(n)||xu).key,t):o},t.tension=function(n){return arguments.length?(a=n,t):a},t}function xu(n){return n.length>1?n.join(\"L\"):n+\"Z\"}function bu(n){return n.join(\"L\")+\"Z\"}function _u(n){for(var t=0,e=n.length,r=n[0],i=[r[0],\",\",r[1]];++t<e;)i.push(\"H\",(r[0]+(r=n[t])[0])/2,\"V\",r[1]);return e>1&&i.push(\"H\",r[0]),i.join(\"\")}function wu(n){for(var t=0,e=n.length,r=n[0],i=[r[0],\",\",r[1]];++t<e;)i.push(\"V\",(r=n[t])[1],\"H\",r[0]);return i.join(\"\")}function Su(n){for(var t=0,e=n.length,r=n[0],i=[r[0],\",\",r[1]];++t<e;)i.push(\"H\",(r=n[t])[0],\"V\",r[1]);return i.join(\"\")}function ku(n,t){return n.length<4?xu(n):n[1]+Au(n.slice(1,-1),Cu(n,t))}function Nu(n,t){return n.length<3?bu(n):n[0]+Au((n.push(n[0]),n),Cu([n[n.length-2]].concat(n,[n[1]]),t))}function Eu(n,t){return n.length<3?xu(n):n[0]+Au(n,Cu(n,t))}function Au(n,t){if(t.length<1||n.length!=t.length&&n.length!=t.length+2)return xu(n);var e=n.length!=t.length,r=\"\",i=n[0],u=n[1],o=t[0],a=o,l=1;if(e&&(r+=\"Q\"+(u[0]-2*o[0]/3)+\",\"+(u[1]-2*o[1]/3)+\",\"+u[0]+\",\"+u[1],i=n[1],l=2),t.length>1){a=t[1],u=n[l],l++,r+=\"C\"+(i[0]+o[0])+\",\"+(i[1]+o[1])+\",\"+(u[0]-a[0])+\",\"+(u[1]-a[1])+\",\"+u[0]+\",\"+u[1];for(var c=2;c<t.length;c++,l++)u=n[l],a=t[c],r+=\"S\"+(u[0]-a[0])+\",\"+(u[1]-a[1])+\",\"+u[0]+\",\"+u[1]}if(e){var f=n[l];r+=\"Q\"+(u[0]+2*a[0]/3)+\",\"+(u[1]+2*a[1]/3)+\",\"+f[0]+\",\"+f[1]}return r}function Cu(n,t){for(var e,r=[],i=(1-t)/2,u=n[0],o=n[1],a=1,l=n.length;++a<l;)e=u,u=o,o=n[a],r.push([i*(o[0]-e[0]),i*(o[1]-e[1])]);return r}function zu(n){if(n.length<3)return xu(n);var t=1,e=n.length,r=n[0],i=r[0],u=r[1],o=[i,i,i,(r=n[1])[0]],a=[u,u,u,r[1]],l=[i,\",\",u,\"L\",Ru(Pl,o),\",\",Ru(Pl,a)];for(n.push(n[e-1]);++t<=e;)r=n[t],o.shift(),o.push(r[0]),a.shift(),a.push(r[1]),Du(l,o,a);return n.pop(),l.push(\"L\",r),l.join(\"\")}function Lu(n){if(n.length<4)return xu(n);for(var t,e=[],r=-1,i=n.length,u=[0],o=[0];++r<3;)t=n[r],u.push(t[0]),o.push(t[1]);for(e.push(Ru(Pl,u)+\",\"+Ru(Pl,o)),--r;++r<i;)t=n[r],u.shift(),u.push(t[0]),o.shift(),o.push(t[1]),Du(e,u,o);return e.join(\"\")}function qu(n){for(var t,e,r=-1,i=n.length,u=i+4,o=[],a=[];++r<4;)e=n[r%i],o.push(e[0]),a.push(e[1]);for(t=[Ru(Pl,o),\",\",Ru(Pl,a)],--r;++r<u;)e=n[r%i],o.shift(),o.push(e[0]),a.shift(),a.push(e[1]),Du(t,o,a);return t.join(\"\")}function Tu(n,t){var e=n.length-1;if(e)for(var r,i,u=n[0][0],o=n[0][1],a=n[e][0]-u,l=n[e][1]-o,c=-1;++c<=e;)r=n[c],i=c/e,r[0]=t*r[0]+(1-t)*(u+i*a),r[1]=t*r[1]+(1-t)*(o+i*l);return zu(n)}function Ru(n,t){return n[0]*t[0]+n[1]*t[1]+n[2]*t[2]+n[3]*t[3]}function Du(n,t,e){n.push(\"C\",Ru(Rl,t),\",\",Ru(Rl,e),\",\",Ru(Dl,t),\",\",Ru(Dl,e),\",\",Ru(Pl,t),\",\",Ru(Pl,e))}function Pu(n,t){return(t[1]-n[1])/(t[0]-n[0])}function Uu(n){for(var t=0,e=n.length-1,r=[],i=n[0],u=n[1],o=r[0]=Pu(i,u);++t<e;)r[t]=(o+(o=Pu(i=u,u=n[t+1])))/2;return r[t]=o,r}function ju(n){for(var t,e,r,i,u=[],o=Uu(n),a=-1,l=n.length-1;++a<l;)t=Pu(n[a],n[a+1]),xo(t)<Uo?o[a]=o[a+1]=0:(e=o[a]/t,r=o[a+1]/t,i=e*e+r*r,i>9&&(i=3*t/Math.sqrt(i),o[a]=i*e,o[a+1]=i*r));for(a=-1;++a<=l;)i=(n[Math.min(l,a+1)][0]-n[Math.max(0,a-1)][0])/(6*(1+o[a]*o[a])),u.push([i||0,o[a]*i||0]);return u}function Fu(n){return n.length<3?xu(n):n[0]+Au(n,ju(n))}function Hu(n){for(var t,e,r,i=-1,u=n.length;++i<u;)t=n[i],e=t[0],r=t[1]-Io,t[0]=e*Math.cos(r),t[1]=e*Math.sin(r);return n}function Ou(n){function t(t){function l(){v.push(\"M\",a(n(y),s),f,c(n(d.reverse()),s),\"Z\")}for(var h,p,g,v=[],d=[],y=[],m=-1,M=t.length,x=En(e),b=En(i),_=e===r?function(){return p}:En(r),w=i===u?function(){return g}:En(u);++m<M;)o.call(this,h=t[m],m)?(d.push([p=+x.call(this,h,m),g=+b.call(this,h,m)]),y.push([+_.call(this,h,m),+w.call(this,h,m)])):d.length&&(l(),d=[],y=[]);return d.length&&l(),v.length?v.join(\"\"):null}var e=Ce,r=Ce,i=0,u=ze,o=zt,a=xu,l=a.key,c=a,f=\"L\",s=.7;return t.x=function(n){return arguments.length?(e=r=n,t):r},t.x0=function(n){return arguments.length?(e=n,t):e},t.x1=function(n){return arguments.length?(r=n,t):r},t.y=function(n){return arguments.length?(i=u=n,t):u},t.y0=function(n){return arguments.length?(i=n,t):i},t.y1=function(n){return arguments.length?(u=n,t):u},t.defined=function(n){return arguments.length?(o=n,t):o},t.interpolate=function(n){return arguments.length?(l=\"function\"==typeof n?a=n:(a=Tl.get(n)||xu).key,c=a.reverse||a,f=a.closed?\"M\":\"L\",t):l},t.tension=function(n){return arguments.length?(s=n,t):s},t}function Iu(n){return n.radius}function Yu(n){return[n.x,n.y]}function Zu(n){return function(){var t=n.apply(this,arguments),e=t[0],r=t[1]-Io;return[e*Math.cos(r),e*Math.sin(r)]}}function Vu(){return 64}function Xu(){return\"circle\"}function $u(n){var t=Math.sqrt(n/Fo);return\"M0,\"+t+\"A\"+t+\",\"+t+\" 0 1,1 0,\"+-t+\"A\"+t+\",\"+t+\" 0 1,1 0,\"+t+\"Z\"}function Bu(n){return function(){var t,e,r;(t=this[n])&&(r=t[e=t.active])&&(r.timer.c=null,r.timer.t=NaN,--t.count?delete t[e]:delete this[n],t.active+=.5,r.event&&r.event.interrupt.call(this,this.__data__,r.index))}}function Wu(n,t,e){return ko(n,Yl),n.namespace=t,n.id=e,n}function Ju(n,t,e,r){var i=n.id,u=n.namespace;return Y(n,\"function\"==typeof e?function(n,o,a){n[u][i].tween.set(t,r(e.call(n,n.__data__,o,a)))}:(e=r(e),function(n){n[u][i].tween.set(t,e)}))}function Gu(n){return null==n&&(n=\"\"),function(){this.textContent=n}}function Ku(n){return null==n?\"__transition__\":\"__transition_\"+n+\"__\"}function Qu(n,t,e,r,i){function u(n){var t=v.delay;return f.t=t+l,n>=t?o(n-t):void(f.c=o)}function o(e){var i=g.active,u=g[i];u&&(u.timer.c=null,u.timer.t=NaN,--g.count,delete g[i],u.event&&u.event.interrupt.call(n,n.__data__,u.index));for(var o in g)if(r>+o){var c=g[o];c.timer.c=null,c.timer.t=NaN,--g.count,delete g[o]}f.c=a,qn(function(){return f.c&&a(e||1)&&(f.c=null,f.t=NaN),1},0,l),g.active=r,v.event&&v.event.start.call(n,n.__data__,t),p=[],v.tween.forEach(function(e,r){(r=r.call(n,n.__data__,t))&&p.push(r)}),h=v.ease,s=v.duration}function a(i){for(var u=i/s,o=h(u),a=p.length;a>0;)p[--a].call(n,o);return u>=1?(v.event&&v.event.end.call(n,n.__data__,t),--g.count?delete g[r]:delete n[e],1):void 0}var l,f,s,h,p,g=n[e]||(n[e]={active:0,count:0}),v=g[r];v||(l=i.time,f=qn(u,0,l),v=g[r]={tween:new c,time:l,timer:f,delay:i.delay,duration:i.duration,ease:i.ease,index:t},i=null,++g.count)}function no(n,t,e){n.attr(\"transform\",function(n){var r=t(n);return\"translate(\"+(isFinite(r)?r:e(n))+\",0)\"})}function to(n,t,e){n.attr(\"transform\",function(n){var r=t(n);return\"translate(0,\"+(isFinite(r)?r:e(n))+\")\"})}function eo(n){return n.toISOString()}function ro(n,t,e){function r(t){return n(t)}function i(n,e){var r=n[1]-n[0],i=r/e,u=ao.bisect(Kl,i);return u==Kl.length?[t.year,Ki(n.map(function(n){return n/31536e6}),e)[2]]:u?t[i/Kl[u-1]<Kl[u]/i?u-1:u]:[tc,Ki(n,e)[2]]}return r.invert=function(t){return io(n.invert(t))},r.domain=function(t){return arguments.length?(n.domain(t),r):n.domain().map(io)},r.nice=function(n,t){function e(e){return!isNaN(e)&&!n.range(e,io(+e+1),t).length}var u=r.domain(),o=Yi(u),a=null==n?i(o,10):\"number\"==typeof n&&i(o,n);return a&&(n=a[0],t=a[1]),r.domain(Xi(u,t>1?{floor:function(t){for(;e(t=n.floor(t));)t=io(t-1);return t},ceil:function(t){for(;e(t=n.ceil(t));)t=io(+t+1);return t}}:n))},r.ticks=function(n,t){var e=Yi(r.domain()),u=null==n?i(e,10):\"number\"==typeof n?i(e,n):!n.range&&[{range:n},t];return u&&(n=u[0],t=u[1]),n.range(e[0],io(+e[1]+1),1>t?1:t)},r.tickFormat=function(){return e},r.copy=function(){return ro(n.copy(),t,e)},Ji(r,n)}function io(n){return new Date(n)}function uo(n){return JSON.parse(n.responseText)}function oo(n){var t=fo.createRange();return t.selectNode(fo.body),t.createContextualFragment(n.responseText)}var ao={version:\"3.5.17\"},lo=[].slice,co=function(n){return lo.call(n)},fo=this.document;if(fo)try{co(fo.documentElement.childNodes)[0].nodeType}catch(so){co=function(n){for(var t=n.length,e=new Array(t);t--;)e[t]=n[t];return e}}if(Date.now||(Date.now=function(){return+new Date}),fo)try{fo.createElement(\"DIV\").style.setProperty(\"opacity\",0,\"\")}catch(ho){var po=this.Element.prototype,go=po.setAttribute,vo=po.setAttributeNS,yo=this.CSSStyleDeclaration.prototype,mo=yo.setProperty;po.setAttribute=function(n,t){go.call(this,n,t+\"\")},po.setAttributeNS=function(n,t,e){vo.call(this,n,t,e+\"\")},yo.setProperty=function(n,t,e){mo.call(this,n,t+\"\",e)}}ao.ascending=e,ao.descending=function(n,t){return n>t?-1:t>n?1:t>=n?0:NaN},ao.min=function(n,t){var e,r,i=-1,u=n.length;if(1===arguments.length){for(;++i<u;)if(null!=(r=n[i])&&r>=r){e=r;break}for(;++i<u;)null!=(r=n[i])&&e>r&&(e=r)}else{for(;++i<u;)if(null!=(r=t.call(n,n[i],i))&&r>=r){e=r;break}for(;++i<u;)null!=(r=t.call(n,n[i],i))&&e>r&&(e=r)}return e},ao.max=function(n,t){var e,r,i=-1,u=n.length;if(1===arguments.length){for(;++i<u;)if(null!=(r=n[i])&&r>=r){e=r;break}for(;++i<u;)null!=(r=n[i])&&r>e&&(e=r)}else{for(;++i<u;)if(null!=(r=t.call(n,n[i],i))&&r>=r){e=r;break}for(;++i<u;)null!=(r=t.call(n,n[i],i))&&r>e&&(e=r)}return e},ao.extent=function(n,t){var e,r,i,u=-1,o=n.length;if(1===arguments.length){for(;++u<o;)if(null!=(r=n[u])&&r>=r){e=i=r;break}for(;++u<o;)null!=(r=n[u])&&(e>r&&(e=r),r>i&&(i=r))}else{for(;++u<o;)if(null!=(r=t.call(n,n[u],u))&&r>=r){e=i=r;break}for(;++u<o;)null!=(r=t.call(n,n[u],u))&&(e>r&&(e=r),r>i&&(i=r))}return[e,i]},ao.sum=function(n,t){var e,r=0,u=n.length,o=-1;if(1===arguments.length)for(;++o<u;)i(e=+n[o])&&(r+=e);else for(;++o<u;)i(e=+t.call(n,n[o],o))&&(r+=e);return r},ao.mean=function(n,t){var e,u=0,o=n.length,a=-1,l=o;if(1===arguments.length)for(;++a<o;)i(e=r(n[a]))?u+=e:--l;else for(;++a<o;)i(e=r(t.call(n,n[a],a)))?u+=e:--l;return l?u/l:void 0},ao.quantile=function(n,t){var e=(n.length-1)*t+1,r=Math.floor(e),i=+n[r-1],u=e-r;return u?i+u*(n[r]-i):i},ao.median=function(n,t){var u,o=[],a=n.length,l=-1;if(1===arguments.length)for(;++l<a;)i(u=r(n[l]))&&o.push(u);else for(;++l<a;)i(u=r(t.call(n,n[l],l)))&&o.push(u);return o.length?ao.quantile(o.sort(e),.5):void 0},ao.variance=function(n,t){var e,u,o=n.length,a=0,l=0,c=-1,f=0;if(1===arguments.length)for(;++c<o;)i(e=r(n[c]))&&(u=e-a,a+=u/++f,l+=u*(e-a));else for(;++c<o;)i(e=r(t.call(n,n[c],c)))&&(u=e-a,a+=u/++f,l+=u*(e-a));return f>1?l/(f-1):void 0},ao.deviation=function(){var n=ao.variance.apply(this,arguments);return n?Math.sqrt(n):n};var Mo=u(e);ao.bisectLeft=Mo.left,ao.bisect=ao.bisectRight=Mo.right,ao.bisector=function(n){return u(1===n.length?function(t,r){return e(n(t),r)}:n)},ao.shuffle=function(n,t,e){(u=arguments.length)<3&&(e=n.length,2>u&&(t=0));for(var r,i,u=e-t;u;)i=Math.random()*u--|0,r=n[u+t],n[u+t]=n[i+t],n[i+t]=r;return n},ao.permute=function(n,t){for(var e=t.length,r=new Array(e);e--;)r[e]=n[t[e]];return r},ao.pairs=function(n){for(var t,e=0,r=n.length-1,i=n[0],u=new Array(0>r?0:r);r>e;)u[e]=[t=i,i=n[++e]];return u},ao.transpose=function(n){if(!(i=n.length))return[];for(var t=-1,e=ao.min(n,o),r=new Array(e);++t<e;)for(var i,u=-1,a=r[t]=new Array(i);++u<i;)a[u]=n[u][t];return r},ao.zip=function(){return ao.transpose(arguments)},ao.keys=function(n){var t=[];for(var e in n)t.push(e);return t},ao.values=function(n){var t=[];for(var e in n)t.push(n[e]);return t},ao.entries=function(n){var t=[];for(var e in n)t.push({key:e,value:n[e]});return t},ao.merge=function(n){for(var t,e,r,i=n.length,u=-1,o=0;++u<i;)o+=n[u].length;for(e=new Array(o);--i>=0;)for(r=n[i],t=r.length;--t>=0;)e[--o]=r[t];return e};var xo=Math.abs;ao.range=function(n,t,e){if(arguments.length<3&&(e=1,arguments.length<2&&(t=n,n=0)),(t-n)/e===1/0)throw new Error(\"infinite range\");var r,i=[],u=a(xo(e)),o=-1;if(n*=u,t*=u,e*=u,0>e)for(;(r=n+e*++o)>t;)i.push(r/u);else for(;(r=n+e*++o)<t;)i.push(r/u);return i},ao.map=function(n,t){var e=new c;if(n instanceof c)n.forEach(function(n,t){e.set(n,t)});else if(Array.isArray(n)){var r,i=-1,u=n.length;if(1===arguments.length)for(;++i<u;)e.set(i,n[i]);else for(;++i<u;)e.set(t.call(n,r=n[i],i),r)}else for(var o in n)e.set(o,n[o]);return e};var bo=\"__proto__\",_o=\"\\x00\";l(c,{has:h,get:function(n){return this._[f(n)]},set:function(n,t){return this._[f(n)]=t},remove:p,keys:g,values:function(){var n=[];for(var t in this._)n.push(this._[t]);return n},entries:function(){var n=[];for(var t in this._)n.push({key:s(t),value:this._[t]});return n},size:v,empty:d,forEach:function(n){for(var t in this._)n.call(this,s(t),this._[t])}}),ao.nest=function(){function n(t,o,a){if(a>=u.length)return r?r.call(i,o):e?o.sort(e):o;for(var l,f,s,h,p=-1,g=o.length,v=u[a++],d=new c;++p<g;)(h=d.get(l=v(f=o[p])))?h.push(f):d.set(l,[f]);return t?(f=t(),s=function(e,r){f.set(e,n(t,r,a))}):(f={},s=function(e,r){f[e]=n(t,r,a)}),d.forEach(s),f}function t(n,e){if(e>=u.length)return n;var r=[],i=o[e++];return n.forEach(function(n,i){r.push({key:n,values:t(i,e)})}),i?r.sort(function(n,t){return i(n.key,t.key)}):r}var e,r,i={},u=[],o=[];return i.map=function(t,e){return n(e,t,0)},i.entries=function(e){return t(n(ao.map,e,0),0)},i.key=function(n){return u.push(n),i},i.sortKeys=function(n){return o[u.length-1]=n,i},i.sortValues=function(n){return e=n,i},i.rollup=function(n){return r=n,i},i},ao.set=function(n){var t=new y;if(n)for(var e=0,r=n.length;r>e;++e)t.add(n[e]);return t},l(y,{has:h,add:function(n){return this._[f(n+=\"\")]=!0,n},remove:p,values:g,size:v,empty:d,forEach:function(n){for(var t in this._)n.call(this,s(t))}}),ao.behavior={},ao.rebind=function(n,t){for(var e,r=1,i=arguments.length;++r<i;)n[e=arguments[r]]=M(n,t,t[e]);return n};var wo=[\"webkit\",\"ms\",\"moz\",\"Moz\",\"o\",\"O\"];ao.dispatch=function(){for(var n=new _,t=-1,e=arguments.length;++t<e;)n[arguments[t]]=w(n);return n},_.prototype.on=function(n,t){var e=n.indexOf(\".\"),r=\"\";if(e>=0&&(r=n.slice(e+1),n=n.slice(0,e)),n)return arguments.length<2?this[n].on(r):this[n].on(r,t);if(2===arguments.length){if(null==t)for(n in this)this.hasOwnProperty(n)&&this[n].on(r,null);return this}},ao.event=null,ao.requote=function(n){return n.replace(So,\"\\\\$&\")};var So=/[\\\\\\^\\$\\*\\+\\?\\|\\[\\]\\(\\)\\.\\{\\}]/g,ko={}.__proto__?function(n,t){n.__proto__=t}:function(n,t){for(var e in t)n[e]=t[e]},No=function(n,t){return t.querySelector(n)},Eo=function(n,t){return t.querySelectorAll(n)},Ao=function(n,t){var e=n.matches||n[x(n,\"matchesSelector\")];return(Ao=function(n,t){return e.call(n,t)})(n,t)};\"function\"==typeof Sizzle&&(No=function(n,t){return Sizzle(n,t)[0]||null},Eo=Sizzle,Ao=Sizzle.matchesSelector),ao.selection=function(){return ao.select(fo.documentElement)};var Co=ao.selection.prototype=[];Co.select=function(n){var t,e,r,i,u=[];n=A(n);for(var o=-1,a=this.length;++o<a;){u.push(t=[]),t.parentNode=(r=this[o]).parentNode;for(var l=-1,c=r.length;++l<c;)(i=r[l])?(t.push(e=n.call(i,i.__data__,l,o)),e&&\"__data__\"in i&&(e.__data__=i.__data__)):t.push(null)}return E(u)},Co.selectAll=function(n){var t,e,r=[];n=C(n);for(var i=-1,u=this.length;++i<u;)for(var o=this[i],a=-1,l=o.length;++a<l;)(e=o[a])&&(r.push(t=co(n.call(e,e.__data__,a,i))),t.parentNode=e);return E(r)};var zo=\"http://www.w3.org/1999/xhtml\",Lo={svg:\"http://www.w3.org/2000/svg\",xhtml:zo,xlink:\"http://www.w3.org/1999/xlink\",xml:\"http://www.w3.org/XML/1998/namespace\",xmlns:\"http://www.w3.org/2000/xmlns/\"};ao.ns={prefix:Lo,qualify:function(n){var t=n.indexOf(\":\"),e=n;return t>=0&&\"xmlns\"!==(e=n.slice(0,t))&&(n=n.slice(t+1)),Lo.hasOwnProperty(e)?{space:Lo[e],local:n}:n}},Co.attr=function(n,t){if(arguments.length<2){if(\"string\"==typeof n){var e=this.node();return n=ao.ns.qualify(n),n.local?e.getAttributeNS(n.space,n.local):e.getAttribute(n)}for(t in n)this.each(z(t,n[t]));return this}return this.each(z(n,t))},Co.classed=function(n,t){if(arguments.length<2){if(\"string\"==typeof n){var e=this.node(),r=(n=T(n)).length,i=-1;if(t=e.classList){for(;++i<r;)if(!t.contains(n[i]))return!1}else for(t=e.getAttribute(\"class\");++i<r;)if(!q(n[i]).test(t))return!1;return!0}for(t in n)this.each(R(t,n[t]));return this}return this.each(R(n,t))},Co.style=function(n,e,r){var i=arguments.length;if(3>i){if(\"string\"!=typeof n){2>i&&(e=\"\");for(r in n)this.each(P(r,n[r],e));return this}if(2>i){var u=this.node();return t(u).getComputedStyle(u,null).getPropertyValue(n)}r=\"\"}return this.each(P(n,e,r))},Co.property=function(n,t){if(arguments.length<2){if(\"string\"==typeof n)return this.node()[n];for(t in n)this.each(U(t,n[t]));return this}return this.each(U(n,t))},Co.text=function(n){return arguments.length?this.each(\"function\"==typeof n?function(){var t=n.apply(this,arguments);this.textContent=null==t?\"\":t}:null==n?function(){this.textContent=\"\"}:function(){this.textContent=n}):this.node().textContent},Co.html=function(n){return arguments.length?this.each(\"function\"==typeof n?function(){var t=n.apply(this,arguments);this.innerHTML=null==t?\"\":t}:null==n?function(){this.innerHTML=\"\"}:function(){this.innerHTML=n}):this.node().innerHTML},Co.append=function(n){return n=j(n),this.select(function(){return this.appendChild(n.apply(this,arguments))})},Co.insert=function(n,t){return n=j(n),t=A(t),this.select(function(){return this.insertBefore(n.apply(this,arguments),t.apply(this,arguments)||null)})},Co.remove=function(){return this.each(F)},Co.data=function(n,t){function e(n,e){var r,i,u,o=n.length,s=e.length,h=Math.min(o,s),p=new Array(s),g=new Array(s),v=new Array(o);if(t){var d,y=new c,m=new Array(o);for(r=-1;++r<o;)(i=n[r])&&(y.has(d=t.call(i,i.__data__,r))?v[r]=i:y.set(d,i),m[r]=d);for(r=-1;++r<s;)(i=y.get(d=t.call(e,u=e[r],r)))?i!==!0&&(p[r]=i,i.__data__=u):g[r]=H(u),y.set(d,!0);for(r=-1;++r<o;)r in m&&y.get(m[r])!==!0&&(v[r]=n[r])}else{for(r=-1;++r<h;)i=n[r],u=e[r],i?(i.__data__=u,p[r]=i):g[r]=H(u);for(;s>r;++r)g[r]=H(e[r]);for(;o>r;++r)v[r]=n[r]}g.update=p,g.parentNode=p.parentNode=v.parentNode=n.parentNode,a.push(g),l.push(p),f.push(v)}var r,i,u=-1,o=this.length;if(!arguments.length){for(n=new Array(o=(r=this[0]).length);++u<o;)(i=r[u])&&(n[u]=i.__data__);return n}var a=Z([]),l=E([]),f=E([]);if(\"function\"==typeof n)for(;++u<o;)e(r=this[u],n.call(r,r.parentNode.__data__,u));else for(;++u<o;)e(r=this[u],n);return l.enter=function(){return a},l.exit=function(){return f},l},Co.datum=function(n){return arguments.length?this.property(\"__data__\",n):this.property(\"__data__\")},Co.filter=function(n){var t,e,r,i=[];\"function\"!=typeof n&&(n=O(n));for(var u=0,o=this.length;o>u;u++){i.push(t=[]),t.parentNode=(e=this[u]).parentNode;for(var a=0,l=e.length;l>a;a++)(r=e[a])&&n.call(r,r.__data__,a,u)&&t.push(r)}return E(i)},Co.order=function(){for(var n=-1,t=this.length;++n<t;)for(var e,r=this[n],i=r.length-1,u=r[i];--i>=0;)(e=r[i])&&(u&&u!==e.nextSibling&&u.parentNode.insertBefore(e,u),u=e);return this},Co.sort=function(n){n=I.apply(this,arguments);for(var t=-1,e=this.length;++t<e;)this[t].sort(n);return this.order()},Co.each=function(n){return Y(this,function(t,e,r){n.call(t,t.__data__,e,r)})},Co.call=function(n){var t=co(arguments);return n.apply(t[0]=this,t),this},Co.empty=function(){return!this.node()},Co.node=function(){for(var n=0,t=this.length;t>n;n++)for(var e=this[n],r=0,i=e.length;i>r;r++){var u=e[r];if(u)return u}return null},Co.size=function(){var n=0;return Y(this,function(){++n}),n};var qo=[];ao.selection.enter=Z,ao.selection.enter.prototype=qo,qo.append=Co.append,qo.empty=Co.empty,qo.node=Co.node,qo.call=Co.call,qo.size=Co.size,qo.select=function(n){for(var t,e,r,i,u,o=[],a=-1,l=this.length;++a<l;){r=(i=this[a]).update,o.push(t=[]),t.parentNode=i.parentNode;for(var c=-1,f=i.length;++c<f;)(u=i[c])?(t.push(r[c]=e=n.call(i.parentNode,u.__data__,c,a)),e.__data__=u.__data__):t.push(null)}return E(o)},qo.insert=function(n,t){return arguments.length<2&&(t=V(this)),Co.insert.call(this,n,t)},ao.select=function(t){var e;return\"string\"==typeof t?(e=[No(t,fo)],e.parentNode=fo.documentElement):(e=[t],e.parentNode=n(t)),E([e])},ao.selectAll=function(n){var t;return\"string\"==typeof n?(t=co(Eo(n,fo)),t.parentNode=fo.documentElement):(t=co(n),t.parentNode=null),E([t])},Co.on=function(n,t,e){var r=arguments.length;if(3>r){if(\"string\"!=typeof n){2>r&&(t=!1);for(e in n)this.each(X(e,n[e],t));return this}if(2>r)return(r=this.node()[\"__on\"+n])&&r._;e=!1}return this.each(X(n,t,e))};var To=ao.map({mouseenter:\"mouseover\",mouseleave:\"mouseout\"});fo&&To.forEach(function(n){\"on\"+n in fo&&To.remove(n)});var Ro,Do=0;ao.mouse=function(n){return J(n,k())};var Po=this.navigator&&/WebKit/.test(this.navigator.userAgent)?-1:0;ao.touch=function(n,t,e){if(arguments.length<3&&(e=t,t=k().changedTouches),t)for(var r,i=0,u=t.length;u>i;++i)if((r=t[i]).identifier===e)return J(n,r)},ao.behavior.drag=function(){function n(){this.on(\"mousedown.drag\",u).on(\"touchstart.drag\",o)}function e(n,t,e,u,o){return function(){function a(){var n,e,r=t(h,v);r&&(n=r[0]-M[0],e=r[1]-M[1],g|=n|e,M=r,p({type:\"drag\",x:r[0]+c[0],y:r[1]+c[1],dx:n,dy:e}))}function l(){t(h,v)&&(y.on(u+d,null).on(o+d,null),m(g),p({type:\"dragend\"}))}var c,f=this,s=ao.event.target.correspondingElement||ao.event.target,h=f.parentNode,p=r.of(f,arguments),g=0,v=n(),d=\".drag\"+(null==v?\"\":\"-\"+v),y=ao.select(e(s)).on(u+d,a).on(o+d,l),m=W(s),M=t(h,v);i?(c=i.apply(f,arguments),c=[c.x-M[0],c.y-M[1]]):c=[0,0],p({type:\"dragstart\"})}}var r=N(n,\"drag\",\"dragstart\",\"dragend\"),i=null,u=e(b,ao.mouse,t,\"mousemove\",\"mouseup\"),o=e(G,ao.touch,m,\"touchmove\",\"touchend\");return n.origin=function(t){return arguments.length?(i=t,n):i},ao.rebind(n,r,\"on\")},ao.touches=function(n,t){return arguments.length<2&&(t=k().touches),t?co(t).map(function(t){var e=J(n,t);return e.identifier=t.identifier,e}):[]};var Uo=1e-6,jo=Uo*Uo,Fo=Math.PI,Ho=2*Fo,Oo=Ho-Uo,Io=Fo/2,Yo=Fo/180,Zo=180/Fo,Vo=Math.SQRT2,Xo=2,$o=4;ao.interpolateZoom=function(n,t){var e,r,i=n[0],u=n[1],o=n[2],a=t[0],l=t[1],c=t[2],f=a-i,s=l-u,h=f*f+s*s;if(jo>h)r=Math.log(c/o)/Vo,e=function(n){return[i+n*f,u+n*s,o*Math.exp(Vo*n*r)]};else{var p=Math.sqrt(h),g=(c*c-o*o+$o*h)/(2*o*Xo*p),v=(c*c-o*o-$o*h)/(2*c*Xo*p),d=Math.log(Math.sqrt(g*g+1)-g),y=Math.log(Math.sqrt(v*v+1)-v);r=(y-d)/Vo,e=function(n){var t=n*r,e=rn(d),a=o/(Xo*p)*(e*un(Vo*t+d)-en(d));return[i+a*f,u+a*s,o*e/rn(Vo*t+d)]}}return e.duration=1e3*r,e},ao.behavior.zoom=function(){function n(n){n.on(L,s).on(Wo+\".zoom\",p).on(\"dblclick.zoom\",g).on(R,h)}function e(n){return[(n[0]-k.x)/k.k,(n[1]-k.y)/k.k]}function r(n){return[n[0]*k.k+k.x,n[1]*k.k+k.y]}function i(n){k.k=Math.max(A[0],Math.min(A[1],n))}function u(n,t){t=r(t),k.x+=n[0]-t[0],k.y+=n[1]-t[1]}function o(t,e,r,o){t.__chart__={x:k.x,y:k.y,k:k.k},i(Math.pow(2,o)),u(d=e,r),t=ao.select(t),C>0&&(t=t.transition().duration(C)),t.call(n.event)}function a(){b&&b.domain(x.range().map(function(n){return(n-k.x)/k.k}).map(x.invert)),w&&w.domain(_.range().map(function(n){return(n-k.y)/k.k}).map(_.invert))}function l(n){z++||n({type:\"zoomstart\"})}function c(n){a(),n({type:\"zoom\",scale:k.k,translate:[k.x,k.y]})}function f(n){--z||(n({type:\"zoomend\"}),d=null)}function s(){function n(){a=1,u(ao.mouse(i),h),c(o)}function r(){s.on(q,null).on(T,null),p(a),f(o)}var i=this,o=D.of(i,arguments),a=0,s=ao.select(t(i)).on(q,n).on(T,r),h=e(ao.mouse(i)),p=W(i);Il.call(i),l(o)}function h(){function n(){var n=ao.touches(g);return p=k.k,n.forEach(function(n){n.identifier in d&&(d[n.identifier]=e(n))}),n}function t(){var t=ao.event.target;ao.select(t).on(x,r).on(b,a),_.push(t);for(var e=ao.event.changedTouches,i=0,u=e.length;u>i;++i)d[e[i].identifier]=null;var l=n(),c=Date.now();if(1===l.length){if(500>c-M){var f=l[0];o(g,f,d[f.identifier],Math.floor(Math.log(k.k)/Math.LN2)+1),S()}M=c}else if(l.length>1){var f=l[0],s=l[1],h=f[0]-s[0],p=f[1]-s[1];y=h*h+p*p}}function r(){var n,t,e,r,o=ao.touches(g);Il.call(g);for(var a=0,l=o.length;l>a;++a,r=null)if(e=o[a],r=d[e.identifier]){if(t)break;n=e,t=r}if(r){var f=(f=e[0]-n[0])*f+(f=e[1]-n[1])*f,s=y&&Math.sqrt(f/y);n=[(n[0]+e[0])/2,(n[1]+e[1])/2],t=[(t[0]+r[0])/2,(t[1]+r[1])/2],i(s*p)}M=null,u(n,t),c(v)}function a(){if(ao.event.touches.length){for(var t=ao.event.changedTouches,e=0,r=t.length;r>e;++e)delete d[t[e].identifier];for(var i in d)return void n()}ao.selectAll(_).on(m,null),w.on(L,s).on(R,h),N(),f(v)}var p,g=this,v=D.of(g,arguments),d={},y=0,m=\".zoom-\"+ao.event.changedTouches[0].identifier,x=\"touchmove\"+m,b=\"touchend\"+m,_=[],w=ao.select(g),N=W(g);t(),l(v),w.on(L,null).on(R,t)}function p(){var n=D.of(this,arguments);m?clearTimeout(m):(Il.call(this),v=e(d=y||ao.mouse(this)),l(n)),m=setTimeout(function(){m=null,f(n)},50),S(),i(Math.pow(2,.002*Bo())*k.k),u(d,v),c(n)}function g(){var n=ao.mouse(this),t=Math.log(k.k)/Math.LN2;o(this,n,e(n),ao.event.shiftKey?Math.ceil(t)-1:Math.floor(t)+1)}var v,d,y,m,M,x,b,_,w,k={x:0,y:0,k:1},E=[960,500],A=Jo,C=250,z=0,L=\"mousedown.zoom\",q=\"mousemove.zoom\",T=\"mouseup.zoom\",R=\"touchstart.zoom\",D=N(n,\"zoomstart\",\"zoom\",\"zoomend\");return Wo||(Wo=\"onwheel\"in fo?(Bo=function(){return-ao.event.deltaY*(ao.event.deltaMode?120:1)},\"wheel\"):\"onmousewheel\"in fo?(Bo=function(){return ao.event.wheelDelta},\"mousewheel\"):(Bo=function(){return-ao.event.detail},\"MozMousePixelScroll\")),n.event=function(n){n.each(function(){var n=D.of(this,arguments),t=k;Hl?ao.select(this).transition().each(\"start.zoom\",function(){k=this.__chart__||{x:0,y:0,k:1},l(n)}).tween(\"zoom:zoom\",function(){var e=E[0],r=E[1],i=d?d[0]:e/2,u=d?d[1]:r/2,o=ao.interpolateZoom([(i-k.x)/k.k,(u-k.y)/k.k,e/k.k],[(i-t.x)/t.k,(u-t.y)/t.k,e/t.k]);return function(t){var r=o(t),a=e/r[2];this.__chart__=k={x:i-r[0]*a,y:u-r[1]*a,k:a},c(n)}}).each(\"interrupt.zoom\",function(){f(n)}).each(\"end.zoom\",function(){f(n)}):(this.__chart__=k,l(n),c(n),f(n))})},n.translate=function(t){return arguments.length?(k={x:+t[0],y:+t[1],k:k.k},a(),n):[k.x,k.y]},n.scale=function(t){return arguments.length?(k={x:k.x,y:k.y,k:null},i(+t),a(),n):k.k},n.scaleExtent=function(t){return arguments.length?(A=null==t?Jo:[+t[0],+t[1]],n):A},n.center=function(t){return arguments.length?(y=t&&[+t[0],+t[1]],n):y},n.size=function(t){return arguments.length?(E=t&&[+t[0],+t[1]],n):E},n.duration=function(t){return arguments.length?(C=+t,n):C},n.x=function(t){return arguments.length?(b=t,x=t.copy(),k={x:0,y:0,k:1},n):b},n.y=function(t){return arguments.length?(w=t,_=t.copy(),k={x:0,y:0,k:1},n):w},ao.rebind(n,D,\"on\")};var Bo,Wo,Jo=[0,1/0];ao.color=an,an.prototype.toString=function(){return this.rgb()+\"\"},ao.hsl=ln;var Go=ln.prototype=new an;Go.brighter=function(n){return n=Math.pow(.7,arguments.length?n:1),new ln(this.h,this.s,this.l/n)},Go.darker=function(n){return n=Math.pow(.7,arguments.length?n:1),new ln(this.h,this.s,n*this.l)},Go.rgb=function(){return cn(this.h,this.s,this.l)},ao.hcl=fn;var Ko=fn.prototype=new an;Ko.brighter=function(n){return new fn(this.h,this.c,Math.min(100,this.l+Qo*(arguments.length?n:1)))},Ko.darker=function(n){return new fn(this.h,this.c,Math.max(0,this.l-Qo*(arguments.length?n:1)))},Ko.rgb=function(){return sn(this.h,this.c,this.l).rgb()},ao.lab=hn;var Qo=18,na=.95047,ta=1,ea=1.08883,ra=hn.prototype=new an;ra.brighter=function(n){return new hn(Math.min(100,this.l+Qo*(arguments.length?n:1)),this.a,this.b)},ra.darker=function(n){return new hn(Math.max(0,this.l-Qo*(arguments.length?n:1)),this.a,this.b)},ra.rgb=function(){return pn(this.l,this.a,this.b)},ao.rgb=mn;var ia=mn.prototype=new an;ia.brighter=function(n){n=Math.pow(.7,arguments.length?n:1);var t=this.r,e=this.g,r=this.b,i=30;return t||e||r?(t&&i>t&&(t=i),e&&i>e&&(e=i),r&&i>r&&(r=i),new mn(Math.min(255,t/n),Math.min(255,e/n),Math.min(255,r/n))):new mn(i,i,i)},ia.darker=function(n){return n=Math.pow(.7,arguments.length?n:1),new mn(n*this.r,n*this.g,n*this.b)},ia.hsl=function(){return wn(this.r,this.g,this.b)},ia.toString=function(){return\"#\"+bn(this.r)+bn(this.g)+bn(this.b)};var ua=ao.map({aliceblue:15792383,antiquewhite:16444375,aqua:65535,aquamarine:8388564,azure:15794175,beige:16119260,bisque:16770244,black:0,blanchedalmond:16772045,blue:255,blueviolet:9055202,brown:10824234,burlywood:14596231,cadetblue:6266528,chartreuse:8388352,chocolate:13789470,coral:16744272,cornflowerblue:6591981,cornsilk:16775388,crimson:14423100,cyan:65535,darkblue:139,darkcyan:35723,darkgoldenrod:12092939,darkgray:11119017,darkgreen:25600,darkgrey:11119017,darkkhaki:12433259,darkmagenta:9109643,darkolivegreen:5597999,darkorange:16747520,darkorchid:10040012,darkred:9109504,darksalmon:15308410,darkseagreen:9419919,darkslateblue:4734347,darkslategray:3100495,darkslategrey:3100495,darkturquoise:52945,darkviolet:9699539,deeppink:16716947,deepskyblue:49151,dimgray:6908265,dimgrey:6908265,dodgerblue:2003199,firebrick:11674146,floralwhite:16775920,forestgreen:2263842,fuchsia:16711935,gainsboro:14474460,ghostwhite:16316671,gold:16766720,goldenrod:14329120,gray:8421504,green:32768,greenyellow:11403055,grey:8421504,honeydew:15794160,hotpink:16738740,indianred:13458524,indigo:4915330,ivory:16777200,khaki:15787660,lavender:15132410,lavenderblush:16773365,lawngreen:8190976,lemonchiffon:16775885,lightblue:11393254,lightcoral:15761536,lightcyan:14745599,lightgoldenrodyellow:16448210,lightgray:13882323,lightgreen:9498256,lightgrey:13882323,lightpink:16758465,lightsalmon:16752762,lightseagreen:2142890,lightskyblue:8900346,lightslategray:7833753,lightslategrey:7833753,lightsteelblue:11584734,lightyellow:16777184,lime:65280,limegreen:3329330,linen:16445670,magenta:16711935,maroon:8388608,mediumaquamarine:6737322,mediumblue:205,mediumorchid:12211667,mediumpurple:9662683,mediumseagreen:3978097,mediumslateblue:8087790,mediumspringgreen:64154,mediumturquoise:4772300,mediumvioletred:13047173,midnightblue:1644912,mintcream:16121850,mistyrose:16770273,moccasin:16770229,navajowhite:16768685,navy:128,oldlace:16643558,olive:8421376,olivedrab:7048739,orange:16753920,orangered:16729344,orchid:14315734,palegoldenrod:15657130,palegreen:10025880,paleturquoise:11529966,palevioletred:14381203,papayawhip:16773077,peachpuff:16767673,peru:13468991,pink:16761035,plum:14524637,powderblue:11591910,purple:8388736,rebeccapurple:6697881,red:16711680,rosybrown:12357519,royalblue:4286945,saddlebrown:9127187,salmon:16416882,sandybrown:16032864,seagreen:3050327,seashell:16774638,sienna:10506797,silver:12632256,skyblue:8900331,slateblue:6970061,slategray:7372944,slategrey:7372944,snow:16775930,springgreen:65407,steelblue:4620980,tan:13808780,teal:32896,thistle:14204888,tomato:16737095,turquoise:4251856,violet:15631086,wheat:16113331,white:16777215,whitesmoke:16119285,yellow:16776960,yellowgreen:10145074});ua.forEach(function(n,t){ua.set(n,Mn(t))}),ao.functor=En,ao.xhr=An(m),ao.dsv=function(n,t){function e(n,e,u){arguments.length<3&&(u=e,e=null);var o=Cn(n,t,null==e?r:i(e),u);return o.row=function(n){return arguments.length?o.response(null==(e=n)?r:i(n)):e},o}function r(n){return e.parse(n.responseText)}function i(n){return function(t){return e.parse(t.responseText,n)}}function u(t){return t.map(o).join(n)}function o(n){return a.test(n)?'\"'+n.replace(/\\\"/g,'\"\"')+'\"':n}var a=new RegExp('[\"'+n+\"\\n]\"),l=n.charCodeAt(0);return e.parse=function(n,t){var r;return e.parseRows(n,function(n,e){if(r)return r(n,e-1);var i=new Function(\"d\",\"return {\"+n.map(function(n,t){return JSON.stringify(n)+\": d[\"+t+\"]\"}).join(\",\")+\"}\");r=t?function(n,e){return t(i(n),e)}:i})},e.parseRows=function(n,t){function e(){if(f>=c)return o;if(i)return i=!1,u;var t=f;if(34===n.charCodeAt(t)){for(var e=t;e++<c;)if(34===n.charCodeAt(e)){if(34!==n.charCodeAt(e+1))break;++e}f=e+2;var r=n.charCodeAt(e+1);return 13===r?(i=!0,10===n.charCodeAt(e+2)&&++f):10===r&&(i=!0),n.slice(t+1,e).replace(/\"\"/g,'\"')}for(;c>f;){var r=n.charCodeAt(f++),a=1;if(10===r)i=!0;else if(13===r)i=!0,10===n.charCodeAt(f)&&(++f,++a);else if(r!==l)continue;return n.slice(t,f-a)}return n.slice(t)}for(var r,i,u={},o={},a=[],c=n.length,f=0,s=0;(r=e())!==o;){for(var h=[];r!==u&&r!==o;)h.push(r),r=e();t&&null==(h=t(h,s++))||a.push(h)}return a},e.format=function(t){if(Array.isArray(t[0]))return e.formatRows(t);var r=new y,i=[];return t.forEach(function(n){for(var t in n)r.has(t)||i.push(r.add(t))}),[i.map(o).join(n)].concat(t.map(function(t){return i.map(function(n){return o(t[n])}).join(n)})).join(\"\\n\")},e.formatRows=function(n){return n.map(u).join(\"\\n\")},e},ao.csv=ao.dsv(\",\",\"text/csv\"),ao.tsv=ao.dsv(\"  \",\"text/tab-separated-values\");var oa,aa,la,ca,fa=this[x(this,\"requestAnimationFrame\")]||function(n){setTimeout(n,17)};ao.timer=function(){qn.apply(this,arguments)},ao.timer.flush=function(){Rn(),Dn()},ao.round=function(n,t){return t?Math.round(n*(t=Math.pow(10,t)))/t:Math.round(n)};var sa=[\"y\",\"z\",\"a\",\"f\",\"p\",\"n\",\"\\xb5\",\"m\",\"\",\"k\",\"M\",\"G\",\"T\",\"P\",\"E\",\"Z\",\"Y\"].map(Un);ao.formatPrefix=function(n,t){var e=0;return(n=+n)&&(0>n&&(n*=-1),t&&(n=ao.round(n,Pn(n,t))),e=1+Math.floor(1e-12+Math.log(n)/Math.LN10),e=Math.max(-24,Math.min(24,3*Math.floor((e-1)/3)))),sa[8+e/3]};var ha=/(?:([^{])?([<>=^]))?([+\\- ])?([$#])?(0)?(\\d+)?(,)?(\\.-?\\d+)?([a-z%])?/i,pa=ao.map({b:function(n){return n.toString(2)},c:function(n){return String.fromCharCode(n)},o:function(n){return n.toString(8)},x:function(n){return n.toString(16)},X:function(n){return n.toString(16).toUpperCase()},g:function(n,t){return n.toPrecision(t)},e:function(n,t){return n.toExponential(t)},f:function(n,t){return n.toFixed(t)},r:function(n,t){return(n=ao.round(n,Pn(n,t))).toFixed(Math.max(0,Math.min(20,Pn(n*(1+1e-15),t))))}}),ga=ao.time={},va=Date;Hn.prototype={getDate:function(){return this._.getUTCDate()},getDay:function(){return this._.getUTCDay()},getFullYear:function(){return this._.getUTCFullYear()},getHours:function(){return this._.getUTCHours()},getMilliseconds:function(){return this._.getUTCMilliseconds()},getMinutes:function(){return this._.getUTCMinutes()},getMonth:function(){return this._.getUTCMonth()},getSeconds:function(){return this._.getUTCSeconds()},getTime:function(){return this._.getTime()},getTimezoneOffset:function(){return 0},valueOf:function(){return this._.valueOf()},setDate:function(){da.setUTCDate.apply(this._,arguments)},setDay:function(){da.setUTCDay.apply(this._,arguments)},setFullYear:function(){da.setUTCFullYear.apply(this._,arguments)},setHours:function(){da.setUTCHours.apply(this._,arguments)},setMilliseconds:function(){da.setUTCMilliseconds.apply(this._,arguments)},setMinutes:function(){da.setUTCMinutes.apply(this._,arguments)},setMonth:function(){da.setUTCMonth.apply(this._,arguments)},setSeconds:function(){da.setUTCSeconds.apply(this._,arguments)},setTime:function(){da.setTime.apply(this._,arguments)}};var da=Date.prototype;ga.year=On(function(n){return n=ga.day(n),n.setMonth(0,1),n},function(n,t){n.setFullYear(n.getFullYear()+t)},function(n){return n.getFullYear()}),ga.years=ga.year.range,ga.years.utc=ga.year.utc.range,ga.day=On(function(n){var t=new va(2e3,0);return t.setFullYear(n.getFullYear(),n.getMonth(),n.getDate()),t},function(n,t){n.setDate(n.getDate()+t)},function(n){return n.getDate()-1}),ga.days=ga.day.range,ga.days.utc=ga.day.utc.range,ga.dayOfYear=function(n){var t=ga.year(n);return Math.floor((n-t-6e4*(n.getTimezoneOffset()-t.getTimezoneOffset()))/864e5)},[\"sunday\",\"monday\",\"tuesday\",\"wednesday\",\"thursday\",\"friday\",\"saturday\"].forEach(function(n,t){t=7-t;var e=ga[n]=On(function(n){return(n=ga.day(n)).setDate(n.getDate()-(n.getDay()+t)%7),n},function(n,t){n.setDate(n.getDate()+7*Math.floor(t))},function(n){var e=ga.year(n).getDay();return Math.floor((ga.dayOfYear(n)+(e+t)%7)/7)-(e!==t)});ga[n+\"s\"]=e.range,ga[n+\"s\"].utc=e.utc.range,ga[n+\"OfYear\"]=function(n){var e=ga.year(n).getDay();return Math.floor((ga.dayOfYear(n)+(e+t)%7)/7)}}),ga.week=ga.sunday,ga.weeks=ga.sunday.range,ga.weeks.utc=ga.sunday.utc.range,ga.weekOfYear=ga.sundayOfYear;var ya={\"-\":\"\",_:\" \",0:\"0\"},ma=/^\\s*\\d+/,Ma=/^%/;ao.locale=function(n){return{numberFormat:jn(n),timeFormat:Yn(n)}};var xa=ao.locale({decimal:\".\",thousands:\",\",grouping:[3],currency:[\"$\",\"\"],dateTime:\"%a %b %e %X %Y\",date:\"%m/%d/%Y\",time:\"%H:%M:%S\",periods:[\"AM\",\"PM\"],days:[\"Sunday\",\"Monday\",\"Tuesday\",\"Wednesday\",\"Thursday\",\"Friday\",\"Saturday\"],shortDays:[\"Sun\",\"Mon\",\"Tue\",\"Wed\",\"Thu\",\"Fri\",\"Sat\"],months:[\"January\",\"February\",\"March\",\"April\",\"May\",\"June\",\"July\",\"August\",\"September\",\"October\",\"November\",\"December\"],shortMonths:[\"Jan\",\"Feb\",\"Mar\",\"Apr\",\"May\",\"Jun\",\"Jul\",\"Aug\",\"Sep\",\"Oct\",\"Nov\",\"Dec\"]});ao.format=xa.numberFormat,ao.geo={},ft.prototype={s:0,t:0,add:function(n){st(n,this.t,ba),st(ba.s,this.s,this),this.s?this.t+=ba.t:this.s=ba.t},reset:function(){this.s=this.t=0},valueOf:function(){return this.s}};var ba=new ft;ao.geo.stream=function(n,t){n&&_a.hasOwnProperty(n.type)?_a[n.type](n,t):ht(n,t)};var _a={Feature:function(n,t){ht(n.geometry,t)},FeatureCollection:function(n,t){for(var e=n.features,r=-1,i=e.length;++r<i;)ht(e[r].geometry,t)}},wa={Sphere:function(n,t){t.sphere()},Point:function(n,t){n=n.coordinates,t.point(n[0],n[1],n[2])},MultiPoint:function(n,t){for(var e=n.coordinates,r=-1,i=e.length;++r<i;)n=e[r],t.point(n[0],n[1],n[2])},LineString:function(n,t){pt(n.coordinates,t,0)},MultiLineString:function(n,t){for(var e=n.coordinates,r=-1,i=e.length;++r<i;)pt(e[r],t,0)},Polygon:function(n,t){gt(n.coordinates,t)},MultiPolygon:function(n,t){for(var e=n.coordinates,r=-1,i=e.length;++r<i;)gt(e[r],t)},GeometryCollection:function(n,t){for(var e=n.geometries,r=-1,i=e.length;++r<i;)ht(e[r],t)}};ao.geo.area=function(n){return Sa=0,ao.geo.stream(n,Na),Sa};var Sa,ka=new ft,Na={sphere:function(){Sa+=4*Fo},point:b,lineStart:b,lineEnd:b,polygonStart:function(){ka.reset(),Na.lineStart=vt},polygonEnd:function(){var n=2*ka;Sa+=0>n?4*Fo+n:n,Na.lineStart=Na.lineEnd=Na.point=b}};ao.geo.bounds=function(){function n(n,t){M.push(x=[f=n,h=n]),s>t&&(s=t),t>p&&(p=t)}function t(t,e){var r=dt([t*Yo,e*Yo]);if(y){var i=mt(y,r),u=[i[1],-i[0],0],o=mt(u,i);bt(o),o=_t(o);var l=t-g,c=l>0?1:-1,v=o[0]*Zo*c,d=xo(l)>180;if(d^(v>c*g&&c*t>v)){var m=o[1]*Zo;m>p&&(p=m)}else if(v=(v+360)%360-180,d^(v>c*g&&c*t>v)){var m=-o[1]*Zo;s>m&&(s=m)}else s>e&&(s=e),e>p&&(p=e);d?g>t?a(f,t)>a(f,h)&&(h=t):a(t,h)>a(f,h)&&(f=t):h>=f?(f>t&&(f=t),t>h&&(h=t)):t>g?a(f,t)>a(f,h)&&(h=t):a(t,h)>a(f,h)&&(f=t)}else n(t,e);y=r,g=t}function e(){b.point=t}function r(){x[0]=f,x[1]=h,b.point=n,y=null}function i(n,e){if(y){var r=n-g;m+=xo(r)>180?r+(r>0?360:-360):r}else v=n,d=e;Na.point(n,e),t(n,e)}function u(){Na.lineStart()}function o(){i(v,d),Na.lineEnd(),xo(m)>Uo&&(f=-(h=180)),x[0]=f,x[1]=h,y=null}function a(n,t){return(t-=n)<0?t+360:t}function l(n,t){return n[0]-t[0]}function c(n,t){return t[0]<=t[1]?t[0]<=n&&n<=t[1]:n<t[0]||t[1]<n}var f,s,h,p,g,v,d,y,m,M,x,b={point:n,lineStart:e,lineEnd:r,polygonStart:function(){b.point=i,b.lineStart=u,b.lineEnd=o,m=0,Na.polygonStart()},polygonEnd:function(){Na.polygonEnd(),b.point=n,b.lineStart=e,b.lineEnd=r,0>ka?(f=-(h=180),s=-(p=90)):m>Uo?p=90:-Uo>m&&(s=-90),x[0]=f,x[1]=h}};return function(n){p=h=-(f=s=1/0),M=[],ao.geo.stream(n,b);var t=M.length;if(t){M.sort(l);for(var e,r=1,i=M[0],u=[i];t>r;++r)e=M[r],c(e[0],i)||c(e[1],i)?(a(i[0],e[1])>a(i[0],i[1])&&(i[1]=e[1]),a(e[0],i[1])>a(i[0],i[1])&&(i[0]=e[0])):u.push(i=e);for(var o,e,g=-(1/0),t=u.length-1,r=0,i=u[t];t>=r;i=e,++r)e=u[r],(o=a(i[1],e[0]))>g&&(g=o,f=e[0],h=i[1])}return M=x=null,f===1/0||s===1/0?[[NaN,NaN],[NaN,NaN]]:[[f,s],[h,p]]}}(),ao.geo.centroid=function(n){Ea=Aa=Ca=za=La=qa=Ta=Ra=Da=Pa=Ua=0,ao.geo.stream(n,ja);var t=Da,e=Pa,r=Ua,i=t*t+e*e+r*r;return jo>i&&(t=qa,e=Ta,r=Ra,Uo>Aa&&(t=Ca,e=za,r=La),i=t*t+e*e+r*r,jo>i)?[NaN,NaN]:[Math.atan2(e,t)*Zo,tn(r/Math.sqrt(i))*Zo]};var Ea,Aa,Ca,za,La,qa,Ta,Ra,Da,Pa,Ua,ja={sphere:b,point:St,lineStart:Nt,lineEnd:Et,polygonStart:function(){ja.lineStart=At},polygonEnd:function(){ja.lineStart=Nt}},Fa=Rt(zt,jt,Ht,[-Fo,-Fo/2]),Ha=1e9;ao.geo.clipExtent=function(){var n,t,e,r,i,u,o={stream:function(n){return i&&(i.valid=!1),i=u(n),i.valid=!0,i},extent:function(a){return arguments.length?(u=Zt(n=+a[0][0],t=+a[0][1],e=+a[1][0],r=+a[1][1]),i&&(i.valid=!1,i=null),o):[[n,t],[e,r]]}};return o.extent([[0,0],[960,500]])},(ao.geo.conicEqualArea=function(){return Vt(Xt)}).raw=Xt,ao.geo.albers=function(){return ao.geo.conicEqualArea().rotate([96,0]).center([-.6,38.7]).parallels([29.5,45.5]).scale(1070)},ao.geo.albersUsa=function(){function n(n){var u=n[0],o=n[1];return t=null,e(u,o),t||(r(u,o),t)||i(u,o),t}var t,e,r,i,u=ao.geo.albers(),o=ao.geo.conicEqualArea().rotate([154,0]).center([-2,58.5]).parallels([55,65]),a=ao.geo.conicEqualArea().rotate([157,0]).center([-3,19.9]).parallels([8,18]),l={point:function(n,e){t=[n,e]}};return n.invert=function(n){var t=u.scale(),e=u.translate(),r=(n[0]-e[0])/t,i=(n[1]-e[1])/t;return(i>=.12&&.234>i&&r>=-.425&&-.214>r?o:i>=.166&&.234>i&&r>=-.214&&-.115>r?a:u).invert(n)},n.stream=function(n){var t=u.stream(n),e=o.stream(n),r=a.stream(n);return{point:function(n,i){t.point(n,i),e.point(n,i),r.point(n,i)},sphere:function(){t.sphere(),e.sphere(),r.sphere()},lineStart:function(){t.lineStart(),e.lineStart(),r.lineStart()},lineEnd:function(){t.lineEnd(),e.lineEnd(),r.lineEnd()},polygonStart:function(){t.polygonStart(),e.polygonStart(),r.polygonStart()},polygonEnd:function(){t.polygonEnd(),e.polygonEnd(),r.polygonEnd()}}},n.precision=function(t){return arguments.length?(u.precision(t),o.precision(t),a.precision(t),n):u.precision()},n.scale=function(t){return arguments.length?(u.scale(t),o.scale(.35*t),a.scale(t),n.translate(u.translate())):u.scale()},n.translate=function(t){if(!arguments.length)return u.translate();var c=u.scale(),f=+t[0],s=+t[1];return e=u.translate(t).clipExtent([[f-.455*c,s-.238*c],[f+.455*c,s+.238*c]]).stream(l).point,r=o.translate([f-.307*c,s+.201*c]).clipExtent([[f-.425*c+Uo,s+.12*c+Uo],[f-.214*c-Uo,s+.234*c-Uo]]).stream(l).point,i=a.translate([f-.205*c,s+.212*c]).clipExtent([[f-.214*c+Uo,s+.166*c+Uo],[f-.115*c-Uo,s+.234*c-Uo]]).stream(l).point,n},n.scale(1070)};var Oa,Ia,Ya,Za,Va,Xa,$a={point:b,lineStart:b,lineEnd:b,polygonStart:function(){Ia=0,$a.lineStart=$t},polygonEnd:function(){$a.lineStart=$a.lineEnd=$a.point=b,Oa+=xo(Ia/2)}},Ba={point:Bt,lineStart:b,lineEnd:b,polygonStart:b,polygonEnd:b},Wa={point:Gt,lineStart:Kt,lineEnd:Qt,polygonStart:function(){Wa.lineStart=ne},polygonEnd:function(){Wa.point=Gt,Wa.lineStart=Kt,Wa.lineEnd=Qt}};ao.geo.path=function(){function n(n){return n&&(\"function\"==typeof a&&u.pointRadius(+a.apply(this,arguments)),o&&o.valid||(o=i(u)),ao.geo.stream(n,o)),u.result()}function t(){return o=null,n}var e,r,i,u,o,a=4.5;return n.area=function(n){return Oa=0,ao.geo.stream(n,i($a)),Oa},n.centroid=function(n){return Ca=za=La=qa=Ta=Ra=Da=Pa=Ua=0,ao.geo.stream(n,i(Wa)),Ua?[Da/Ua,Pa/Ua]:Ra?[qa/Ra,Ta/Ra]:La?[Ca/La,za/La]:[NaN,NaN]},n.bounds=function(n){return Va=Xa=-(Ya=Za=1/0),ao.geo.stream(n,i(Ba)),[[Ya,Za],[Va,Xa]]},n.projection=function(n){return arguments.length?(i=(e=n)?n.stream||re(n):m,t()):e},n.context=function(n){return arguments.length?(u=null==(r=n)?new Wt:new te(n),\"function\"!=typeof a&&u.pointRadius(a),t()):r},n.pointRadius=function(t){return arguments.length?(a=\"function\"==typeof t?t:(u.pointRadius(+t),+t),n):a},n.projection(ao.geo.albersUsa()).context(null)},ao.geo.transform=function(n){return{stream:function(t){var e=new ie(t);for(var r in n)e[r]=n[r];return e}}},ie.prototype={point:function(n,t){this.stream.point(n,t)},sphere:function(){this.stream.sphere()},lineStart:function(){this.stream.lineStart()},lineEnd:function(){this.stream.lineEnd()},polygonStart:function(){this.stream.polygonStart()},polygonEnd:function(){this.stream.polygonEnd()}},ao.geo.projection=oe,ao.geo.projectionMutator=ae,(ao.geo.equirectangular=function(){return oe(ce)}).raw=ce.invert=ce,ao.geo.rotation=function(n){function t(t){return t=n(t[0]*Yo,t[1]*Yo),t[0]*=Zo,t[1]*=Zo,t}return n=se(n[0]%360*Yo,n[1]*Yo,n.length>2?n[2]*Yo:0),t.invert=function(t){return t=n.invert(t[0]*Yo,t[1]*Yo),t[0]*=Zo,t[1]*=Zo,t},t},fe.invert=ce,ao.geo.circle=function(){function n(){var n=\"function\"==typeof r?r.apply(this,arguments):r,t=se(-n[0]*Yo,-n[1]*Yo,0).invert,i=[];return e(null,null,1,{point:function(n,e){i.push(n=t(n,e)),n[0]*=Zo,n[1]*=Zo}}),{type:\"Polygon\",coordinates:[i]}}var t,e,r=[0,0],i=6;return n.origin=function(t){return arguments.length?(r=t,n):r},n.angle=function(r){return arguments.length?(e=ve((t=+r)*Yo,i*Yo),n):t},n.precision=function(r){return arguments.length?(e=ve(t*Yo,(i=+r)*Yo),n):i},n.angle(90)},ao.geo.distance=function(n,t){var e,r=(t[0]-n[0])*Yo,i=n[1]*Yo,u=t[1]*Yo,o=Math.sin(r),a=Math.cos(r),l=Math.sin(i),c=Math.cos(i),f=Math.sin(u),s=Math.cos(u);return Math.atan2(Math.sqrt((e=s*o)*e+(e=c*f-l*s*a)*e),l*f+c*s*a)},ao.geo.graticule=function(){function n(){return{type:\"MultiLineString\",coordinates:t()}}function t(){return ao.range(Math.ceil(u/d)*d,i,d).map(h).concat(ao.range(Math.ceil(c/y)*y,l,y).map(p)).concat(ao.range(Math.ceil(r/g)*g,e,g).filter(function(n){return xo(n%d)>Uo}).map(f)).concat(ao.range(Math.ceil(a/v)*v,o,v).filter(function(n){return xo(n%y)>Uo}).map(s))}var e,r,i,u,o,a,l,c,f,s,h,p,g=10,v=g,d=90,y=360,m=2.5;return n.lines=function(){return t().map(function(n){return{type:\"LineString\",coordinates:n}})},n.outline=function(){return{type:\"Polygon\",coordinates:[h(u).concat(p(l).slice(1),h(i).reverse().slice(1),p(c).reverse().slice(1))]}},n.extent=function(t){return arguments.length?n.majorExtent(t).minorExtent(t):n.minorExtent()},n.majorExtent=function(t){return arguments.length?(u=+t[0][0],i=+t[1][0],c=+t[0][1],l=+t[1][1],u>i&&(t=u,u=i,i=t),c>l&&(t=c,c=l,l=t),n.precision(m)):[[u,c],[i,l]]},n.minorExtent=function(t){return arguments.length?(r=+t[0][0],e=+t[1][0],a=+t[0][1],o=+t[1][1],r>e&&(t=r,r=e,e=t),a>o&&(t=a,a=o,o=t),n.precision(m)):[[r,a],[e,o]]},n.step=function(t){return arguments.length?n.majorStep(t).minorStep(t):n.minorStep()},n.majorStep=function(t){return arguments.length?(d=+t[0],y=+t[1],n):[d,y]},n.minorStep=function(t){return arguments.length?(g=+t[0],v=+t[1],n):[g,v]},n.precision=function(t){return arguments.length?(m=+t,f=ye(a,o,90),s=me(r,e,m),h=ye(c,l,90),p=me(u,i,m),n):m},n.majorExtent([[-180,-90+Uo],[180,90-Uo]]).minorExtent([[-180,-80-Uo],[180,80+Uo]])},ao.geo.greatArc=function(){function n(){return{type:\"LineString\",coordinates:[t||r.apply(this,arguments),e||i.apply(this,arguments)]}}var t,e,r=Me,i=xe;return n.distance=function(){return ao.geo.distance(t||r.apply(this,arguments),e||i.apply(this,arguments))},n.source=function(e){return arguments.length?(r=e,t=\"function\"==typeof e?null:e,n):r},n.target=function(t){return arguments.length?(i=t,e=\"function\"==typeof t?null:t,n):i},n.precision=function(){return arguments.length?n:0},n},ao.geo.interpolate=function(n,t){return be(n[0]*Yo,n[1]*Yo,t[0]*Yo,t[1]*Yo)},ao.geo.length=function(n){return Ja=0,ao.geo.stream(n,Ga),Ja};var Ja,Ga={sphere:b,point:b,lineStart:_e,lineEnd:b,polygonStart:b,polygonEnd:b},Ka=we(function(n){return Math.sqrt(2/(1+n))},function(n){return 2*Math.asin(n/2)});(ao.geo.azimuthalEqualArea=function(){return oe(Ka)}).raw=Ka;var Qa=we(function(n){var t=Math.acos(n);return t&&t/Math.sin(t)},m);(ao.geo.azimuthalEquidistant=function(){return oe(Qa)}).raw=Qa,(ao.geo.conicConformal=function(){return Vt(Se)}).raw=Se,(ao.geo.conicEquidistant=function(){return Vt(ke)}).raw=ke;var nl=we(function(n){return 1/n},Math.atan);(ao.geo.gnomonic=function(){return oe(nl)}).raw=nl,Ne.invert=function(n,t){return[n,2*Math.atan(Math.exp(t))-Io]},(ao.geo.mercator=function(){return Ee(Ne)}).raw=Ne;var tl=we(function(){return 1},Math.asin);(ao.geo.orthographic=function(){return oe(tl)}).raw=tl;var el=we(function(n){return 1/(1+n)},function(n){return 2*Math.atan(n)});(ao.geo.stereographic=function(){return oe(el)}).raw=el,Ae.invert=function(n,t){return[-t,2*Math.atan(Math.exp(n))-Io]},(ao.geo.transverseMercator=function(){var n=Ee(Ae),t=n.center,e=n.rotate;return n.center=function(n){return n?t([-n[1],n[0]]):(n=t(),[n[1],-n[0]])},n.rotate=function(n){return n?e([n[0],n[1],n.length>2?n[2]+90:90]):(n=e(),[n[0],n[1],n[2]-90])},e([0,0,90])}).raw=Ae,ao.geom={},ao.geom.hull=function(n){function t(n){if(n.length<3)return[];var t,i=En(e),u=En(r),o=n.length,a=[],l=[];for(t=0;o>t;t++)a.push([+i.call(this,n[t],t),+u.call(this,n[t],t),t]);for(a.sort(qe),t=0;o>t;t++)l.push([a[t][0],-a[t][1]]);var c=Le(a),f=Le(l),s=f[0]===c[0],h=f[f.length-1]===c[c.length-1],p=[];for(t=c.length-1;t>=0;--t)p.push(n[a[c[t]][2]]);for(t=+s;t<f.length-h;++t)p.push(n[a[f[t]][2]]);return p}var e=Ce,r=ze;return arguments.length?t(n):(t.x=function(n){return arguments.length?(e=n,t):e},t.y=function(n){return arguments.length?(r=n,t):r},t)},ao.geom.polygon=function(n){return ko(n,rl),n};var rl=ao.geom.polygon.prototype=[];rl.area=function(){for(var n,t=-1,e=this.length,r=this[e-1],i=0;++t<e;)n=r,r=this[t],i+=n[1]*r[0]-n[0]*r[1];return.5*i},rl.centroid=function(n){var t,e,r=-1,i=this.length,u=0,o=0,a=this[i-1];for(arguments.length||(n=-1/(6*this.area()));++r<i;)t=a,a=this[r],e=t[0]*a[1]-a[0]*t[1],u+=(t[0]+a[0])*e,o+=(t[1]+a[1])*e;return[u*n,o*n]},rl.clip=function(n){for(var t,e,r,i,u,o,a=De(n),l=-1,c=this.length-De(this),f=this[c-1];++l<c;){for(t=n.slice(),n.length=0,i=this[l],u=t[(r=t.length-a)-1],e=-1;++e<r;)o=t[e],Te(o,f,i)?(Te(u,f,i)||n.push(Re(u,o,f,i)),n.push(o)):Te(u,f,i)&&n.push(Re(u,o,f,i)),u=o;a&&n.push(n[0]),f=i}return n};var il,ul,ol,al,ll,cl=[],fl=[];Ye.prototype.prepare=function(){for(var n,t=this.edges,e=t.length;e--;)n=t[e].edge,n.b&&n.a||t.splice(e,1);return t.sort(Ve),t.length},tr.prototype={start:function(){return this.edge.l===this.site?this.edge.a:this.edge.b},end:function(){return this.edge.l===this.site?this.edge.b:this.edge.a}},er.prototype={insert:function(n,t){var e,r,i;if(n){if(t.P=n,t.N=n.N,n.N&&(n.N.P=t),n.N=t,n.R){for(n=n.R;n.L;)n=n.L;n.L=t}else n.R=t;e=n}else this._?(n=or(this._),t.P=null,t.N=n,n.P=n.L=t,e=n):(t.P=t.N=null,this._=t,e=null);for(t.L=t.R=null,t.U=e,t.C=!0,n=t;e&&e.C;)r=e.U,e===r.L?(i=r.R,i&&i.C?(e.C=i.C=!1,r.C=!0,n=r):(n===e.R&&(ir(this,e),n=e,e=n.U),e.C=!1,r.C=!0,ur(this,r))):(i=r.L,i&&i.C?(e.C=i.C=!1,r.C=!0,n=r):(n===e.L&&(ur(this,e),n=e,e=n.U),e.C=!1,r.C=!0,ir(this,r))),e=n.U;this._.C=!1},remove:function(n){n.N&&(n.N.P=n.P),n.P&&(n.P.N=n.N),n.N=n.P=null;var t,e,r,i=n.U,u=n.L,o=n.R;if(e=u?o?or(o):u:o,i?i.L===n?i.L=e:i.R=e:this._=e,u&&o?(r=e.C,e.C=n.C,e.L=u,u.U=e,e!==o?(i=e.U,e.U=n.U,n=e.R,i.L=n,e.R=o,o.U=e):(e.U=i,i=e,n=e.R)):(r=n.C,n=e),n&&(n.U=i),!r){if(n&&n.C)return void(n.C=!1);do{if(n===this._)break;if(n===i.L){if(t=i.R,t.C&&(t.C=!1,i.C=!0,ir(this,i),t=i.R),t.L&&t.L.C||t.R&&t.R.C){t.R&&t.R.C||(t.L.C=!1,t.C=!0,ur(this,t),t=i.R),t.C=i.C,i.C=t.R.C=!1,ir(this,i),n=this._;break}}else if(t=i.L,t.C&&(t.C=!1,i.C=!0,ur(this,i),t=i.L),t.L&&t.L.C||t.R&&t.R.C){t.L&&t.L.C||(t.R.C=!1,t.C=!0,ir(this,t),t=i.L),t.C=i.C,i.C=t.L.C=!1,ur(this,i),n=this._;break}t.C=!0,n=i,i=i.U}while(!n.C);n&&(n.C=!1)}}},ao.geom.voronoi=function(n){function t(n){var t=new Array(n.length),r=a[0][0],i=a[0][1],u=a[1][0],o=a[1][1];return ar(e(n),a).cells.forEach(function(e,a){var l=e.edges,c=e.site,f=t[a]=l.length?l.map(function(n){var t=n.start();return[t.x,t.y]}):c.x>=r&&c.x<=u&&c.y>=i&&c.y<=o?[[r,o],[u,o],[u,i],[r,i]]:[];f.point=n[a]}),t}function e(n){return n.map(function(n,t){return{x:Math.round(u(n,t)/Uo)*Uo,y:Math.round(o(n,t)/Uo)*Uo,i:t}})}var r=Ce,i=ze,u=r,o=i,a=sl;return n?t(n):(t.links=function(n){return ar(e(n)).edges.filter(function(n){return n.l&&n.r}).map(function(t){return{source:n[t.l.i],target:n[t.r.i]}})},t.triangles=function(n){var t=[];return ar(e(n)).cells.forEach(function(e,r){for(var i,u,o=e.site,a=e.edges.sort(Ve),l=-1,c=a.length,f=a[c-1].edge,s=f.l===o?f.r:f.l;++l<c;)i=f,u=s,f=a[l].edge,s=f.l===o?f.r:f.l,r<u.i&&r<s.i&&cr(o,u,s)<0&&t.push([n[r],n[u.i],n[s.i]])}),t},t.x=function(n){return arguments.length?(u=En(r=n),t):r},t.y=function(n){return arguments.length?(o=En(i=n),t):i},t.clipExtent=function(n){return arguments.length?(a=null==n?sl:n,t):a===sl?null:a},t.size=function(n){return arguments.length?t.clipExtent(n&&[[0,0],n]):a===sl?null:a&&a[1]},t)};var sl=[[-1e6,-1e6],[1e6,1e6]];ao.geom.delaunay=function(n){return ao.geom.voronoi().triangles(n)},ao.geom.quadtree=function(n,t,e,r,i){function u(n){function u(n,t,e,r,i,u,o,a){if(!isNaN(e)&&!isNaN(r))if(n.leaf){var l=n.x,f=n.y;if(null!=l)if(xo(l-e)+xo(f-r)<.01)c(n,t,e,r,i,u,o,a);else{var s=n.point;n.x=n.y=n.point=null,c(n,s,l,f,i,u,o,a),c(n,t,e,r,i,u,o,a)}else n.x=e,n.y=r,n.point=t}else c(n,t,e,r,i,u,o,a)}function c(n,t,e,r,i,o,a,l){var c=.5*(i+a),f=.5*(o+l),s=e>=c,h=r>=f,p=h<<1|s;n.leaf=!1,n=n.nodes[p]||(n.nodes[p]=hr()),s?i=c:a=c,h?o=f:l=f,u(n,t,e,r,i,o,a,l)}var f,s,h,p,g,v,d,y,m,M=En(a),x=En(l);if(null!=t)v=t,d=e,y=r,m=i;else if(y=m=-(v=d=1/0),s=[],h=[],g=n.length,o)for(p=0;g>p;++p)f=n[p],f.x<v&&(v=f.x),f.y<d&&(d=f.y),f.x>y&&(y=f.x),f.y>m&&(m=f.y),s.push(f.x),h.push(f.y);else for(p=0;g>p;++p){var b=+M(f=n[p],p),_=+x(f,p);v>b&&(v=b),d>_&&(d=_),b>y&&(y=b),_>m&&(m=_),s.push(b),h.push(_)}var w=y-v,S=m-d;w>S?m=d+w:y=v+S;var k=hr();if(k.add=function(n){u(k,n,+M(n,++p),+x(n,p),v,d,y,m)},k.visit=function(n){pr(n,k,v,d,y,m)},k.find=function(n){return gr(k,n[0],n[1],v,d,y,m)},p=-1,null==t){for(;++p<g;)u(k,n[p],s[p],h[p],v,d,y,m);--p}else n.forEach(k.add);return s=h=n=f=null,k}var o,a=Ce,l=ze;return(o=arguments.length)?(a=fr,l=sr,3===o&&(i=e,r=t,e=t=0),u(n)):(u.x=function(n){return arguments.length?(a=n,u):a},u.y=function(n){return arguments.length?(l=n,u):l},u.extent=function(n){return arguments.length?(null==n?t=e=r=i=null:(t=+n[0][0],e=+n[0][1],r=+n[1][0],i=+n[1][1]),u):null==t?null:[[t,e],[r,i]]},u.size=function(n){return arguments.length?(null==n?t=e=r=i=null:(t=e=0,r=+n[0],i=+n[1]),u):null==t?null:[r-t,i-e]},u)},ao.interpolateRgb=vr,ao.interpolateObject=dr,ao.interpolateNumber=yr,ao.interpolateString=mr;var hl=/[-+]?(?:\\d+\\.?\\d*|\\.?\\d+)(?:[eE][-+]?\\d+)?/g,pl=new RegExp(hl.source,\"g\");ao.interpolate=Mr,ao.interpolators=[function(n,t){var e=typeof t;return(\"string\"===e?ua.has(t.toLowerCase())||/^(#|rgb\\(|hsl\\()/i.test(t)?vr:mr:t instanceof an?vr:Array.isArray(t)?xr:\"object\"===e&&isNaN(t)?dr:yr)(n,t)}],ao.interpolateArray=xr;var gl=function(){return m},vl=ao.map({linear:gl,poly:Er,quad:function(){return Sr},cubic:function(){return kr},sin:function(){return Ar},exp:function(){return Cr},circle:function(){return zr},elastic:Lr,back:qr,bounce:function(){return Tr}}),dl=ao.map({\"in\":m,out:_r,\"in-out\":wr,\"out-in\":function(n){return wr(_r(n))}});ao.ease=function(n){var t=n.indexOf(\"-\"),e=t>=0?n.slice(0,t):n,r=t>=0?n.slice(t+1):\"in\";return e=vl.get(e)||gl,r=dl.get(r)||m,br(r(e.apply(null,lo.call(arguments,1))))},ao.interpolateHcl=Rr,ao.interpolateHsl=Dr,ao.interpolateLab=Pr,ao.interpolateRound=Ur,ao.transform=function(n){var t=fo.createElementNS(ao.ns.prefix.svg,\"g\");return(ao.transform=function(n){if(null!=n){t.setAttribute(\"transform\",n);var e=t.transform.baseVal.consolidate()}return new jr(e?e.matrix:yl)})(n)},jr.prototype.toString=function(){return\"translate(\"+this.translate+\")rotate(\"+this.rotate+\")skewX(\"+this.skew+\")scale(\"+this.scale+\")\"};var yl={a:1,b:0,c:0,d:1,e:0,f:0};ao.interpolateTransform=$r,ao.layout={},ao.layout.bundle=function(){return function(n){for(var t=[],e=-1,r=n.length;++e<r;)t.push(Jr(n[e]));return t}},ao.layout.chord=function(){function n(){var n,c,s,h,p,g={},v=[],d=ao.range(u),y=[];for(e=[],r=[],n=0,h=-1;++h<u;){for(c=0,p=-1;++p<u;)c+=i[h][p];v.push(c),y.push(ao.range(u)),n+=c}for(o&&d.sort(function(n,t){return o(v[n],v[t])}),a&&y.forEach(function(n,t){n.sort(function(n,e){return a(i[t][n],i[t][e])})}),n=(Ho-f*u)/n,c=0,h=-1;++h<u;){for(s=c,p=-1;++p<u;){var m=d[h],M=y[m][p],x=i[m][M],b=c,_=c+=x*n;g[m+\"-\"+M]={index:m,subindex:M,startAngle:b,endAngle:_,value:x}}r[m]={index:m,startAngle:s,endAngle:c,value:v[m]},c+=f}for(h=-1;++h<u;)for(p=h-1;++p<u;){var w=g[h+\"-\"+p],S=g[p+\"-\"+h];(w.value||S.value)&&e.push(w.value<S.value?{source:S,target:w}:{source:w,target:S})}l&&t()}function t(){e.sort(function(n,t){return l((n.source.value+n.target.value)/2,(t.source.value+t.target.value)/2)})}var e,r,i,u,o,a,l,c={},f=0;return c.matrix=function(n){return arguments.length?(u=(i=n)&&i.length,e=r=null,c):i},c.padding=function(n){return arguments.length?(f=n,e=r=null,c):f},c.sortGroups=function(n){return arguments.length?(o=n,e=r=null,c):o},c.sortSubgroups=function(n){return arguments.length?(a=n,e=null,c):a},c.sortChords=function(n){return arguments.length?(l=n,e&&t(),c):l},c.chords=function(){return e||n(),e},c.groups=function(){return r||n(),r},c},ao.layout.force=function(){function n(n){return function(t,e,r,i){if(t.point!==n){var u=t.cx-n.x,o=t.cy-n.y,a=i-e,l=u*u+o*o;if(l>a*a/y){if(v>l){var c=t.charge/l;n.px-=u*c,n.py-=o*c}return!0}if(t.point&&l&&v>l){var c=t.pointCharge/l;n.px-=u*c,n.py-=o*c}}return!t.charge}}function t(n){n.px=ao.event.x,n.py=ao.event.y,l.resume()}var e,r,i,u,o,a,l={},c=ao.dispatch(\"start\",\"tick\",\"end\"),f=[1,1],s=.9,h=ml,p=Ml,g=-30,v=xl,d=.1,y=.64,M=[],x=[];return l.tick=function(){if((i*=.99)<.005)return e=null,c.end({type:\"end\",alpha:i=0}),!0;var t,r,l,h,p,v,y,m,b,_=M.length,w=x.length;for(r=0;w>r;++r)l=x[r],h=l.source,p=l.target,m=p.x-h.x,b=p.y-h.y,(v=m*m+b*b)&&(v=i*o[r]*((v=Math.sqrt(v))-u[r])/v,m*=v,b*=v,p.x-=m*(y=h.weight+p.weight?h.weight/(h.weight+p.weight):.5),p.y-=b*y,h.x+=m*(y=1-y),h.y+=b*y);if((y=i*d)&&(m=f[0]/2,b=f[1]/2,r=-1,y))for(;++r<_;)l=M[r],l.x+=(m-l.x)*y,l.y+=(b-l.y)*y;if(g)for(ri(t=ao.geom.quadtree(M),i,a),r=-1;++r<_;)(l=M[r]).fixed||t.visit(n(l));for(r=-1;++r<_;)l=M[r],l.fixed?(l.x=l.px,l.y=l.py):(l.x-=(l.px-(l.px=l.x))*s,l.y-=(l.py-(l.py=l.y))*s);c.tick({type:\"tick\",alpha:i})},l.nodes=function(n){return arguments.length?(M=n,l):M},l.links=function(n){return arguments.length?(x=n,l):x},l.size=function(n){return arguments.length?(f=n,l):f},l.linkDistance=function(n){return arguments.length?(h=\"function\"==typeof n?n:+n,l):h},l.distance=l.linkDistance,l.linkStrength=function(n){return arguments.length?(p=\"function\"==typeof n?n:+n,l):p},l.friction=function(n){return arguments.length?(s=+n,l):s},l.charge=function(n){return arguments.length?(g=\"function\"==typeof n?n:+n,l):g},l.chargeDistance=function(n){return arguments.length?(v=n*n,l):Math.sqrt(v)},l.gravity=function(n){return arguments.length?(d=+n,l):d},l.theta=function(n){return arguments.length?(y=n*n,l):Math.sqrt(y)},l.alpha=function(n){return arguments.length?(n=+n,i?n>0?i=n:(e.c=null,e.t=NaN,e=null,c.end({type:\"end\",alpha:i=0})):n>0&&(c.start({type:\"start\",alpha:i=n}),e=qn(l.tick)),l):i},l.start=function(){function n(n,r){if(!e){for(e=new Array(i),l=0;i>l;++l)e[l]=[];for(l=0;c>l;++l){var u=x[l];e[u.source.index].push(u.target),e[u.target.index].push(u.source)}}for(var o,a=e[t],l=-1,f=a.length;++l<f;)if(!isNaN(o=a[l][n]))return o;return Math.random()*r}var t,e,r,i=M.length,c=x.length,s=f[0],v=f[1];for(t=0;i>t;++t)(r=M[t]).index=t,r.weight=0;for(t=0;c>t;++t)r=x[t],\"number\"==typeof r.source&&(r.source=M[r.source]),\"number\"==typeof r.target&&(r.target=M[r.target]),++r.source.weight,++r.target.weight;for(t=0;i>t;++t)r=M[t],isNaN(r.x)&&(r.x=n(\"x\",s)),isNaN(r.y)&&(r.y=n(\"y\",v)),isNaN(r.px)&&(r.px=r.x),isNaN(r.py)&&(r.py=r.y);if(u=[],\"function\"==typeof h)for(t=0;c>t;++t)u[t]=+h.call(this,x[t],t);else for(t=0;c>t;++t)u[t]=h;if(o=[],\"function\"==typeof p)for(t=0;c>t;++t)o[t]=+p.call(this,x[t],t);else for(t=0;c>t;++t)o[t]=p;if(a=[],\"function\"==typeof g)for(t=0;i>t;++t)a[t]=+g.call(this,M[t],t);else for(t=0;i>t;++t)a[t]=g;return l.resume()},l.resume=function(){return l.alpha(.1)},l.stop=function(){return l.alpha(0)},l.drag=function(){return r||(r=ao.behavior.drag().origin(m).on(\"dragstart.force\",Qr).on(\"drag.force\",t).on(\"dragend.force\",ni)),arguments.length?void this.on(\"mouseover.force\",ti).on(\"mouseout.force\",ei).call(r):r},ao.rebind(l,c,\"on\")};var ml=20,Ml=1,xl=1/0;ao.layout.hierarchy=function(){function n(i){var u,o=[i],a=[];for(i.depth=0;null!=(u=o.pop());)if(a.push(u),(c=e.call(n,u,u.depth))&&(l=c.length)){for(var l,c,f;--l>=0;)o.push(f=c[l]),f.parent=u,f.depth=u.depth+1;r&&(u.value=0),u.children=c}else r&&(u.value=+r.call(n,u,u.depth)||0),delete u.children;return oi(i,function(n){var e,i;t&&(e=n.children)&&e.sort(t),r&&(i=n.parent)&&(i.value+=n.value)}),a}var t=ci,e=ai,r=li;return n.sort=function(e){return arguments.length?(t=e,n):t},n.children=function(t){return arguments.length?(e=t,n):e},n.value=function(t){return arguments.length?(r=t,n):r},n.revalue=function(t){return r&&(ui(t,function(n){n.children&&(n.value=0)}),oi(t,function(t){var e;t.children||(t.value=+r.call(n,t,t.depth)||0),(e=t.parent)&&(e.value+=t.value)})),t},n},ao.layout.partition=function(){function n(t,e,r,i){var u=t.children;if(t.x=e,t.y=t.depth*i,t.dx=r,t.dy=i,u&&(o=u.length)){var o,a,l,c=-1;for(r=t.value?r/t.value:0;++c<o;)n(a=u[c],e,l=a.value*r,i),e+=l}}function t(n){var e=n.children,r=0;if(e&&(i=e.length))for(var i,u=-1;++u<i;)r=Math.max(r,t(e[u]));return 1+r}function e(e,u){var o=r.call(this,e,u);return n(o[0],0,i[0],i[1]/t(o[0])),o}var r=ao.layout.hierarchy(),i=[1,1];return e.size=function(n){return arguments.length?(i=n,e):i},ii(e,r)},ao.layout.pie=function(){function n(o){var a,l=o.length,c=o.map(function(e,r){return+t.call(n,e,r)}),f=+(\"function\"==typeof r?r.apply(this,arguments):r),s=(\"function\"==typeof i?i.apply(this,arguments):i)-f,h=Math.min(Math.abs(s)/l,+(\"function\"==typeof u?u.apply(this,arguments):u)),p=h*(0>s?-1:1),g=ao.sum(c),v=g?(s-l*p)/g:0,d=ao.range(l),y=[];return null!=e&&d.sort(e===bl?function(n,t){return c[t]-c[n]}:function(n,t){return e(o[n],o[t])}),d.forEach(function(n){y[n]={data:o[n],value:a=c[n],startAngle:f,endAngle:f+=a*v+p,padAngle:h}}),y}var t=Number,e=bl,r=0,i=Ho,u=0;return n.value=function(e){return arguments.length?(t=e,n):t},n.sort=function(t){return arguments.length?(e=t,n):e},n.startAngle=function(t){return arguments.length?(r=t,n):r},n.endAngle=function(t){return arguments.length?(i=t,n):i},n.padAngle=function(t){return arguments.length?(u=t,n):u},n};var bl={};ao.layout.stack=function(){function n(a,l){if(!(h=a.length))return a;var c=a.map(function(e,r){return t.call(n,e,r)}),f=c.map(function(t){return t.map(function(t,e){return[u.call(n,t,e),o.call(n,t,e)]})}),s=e.call(n,f,l);c=ao.permute(c,s),f=ao.permute(f,s);var h,p,g,v,d=r.call(n,f,l),y=c[0].length;for(g=0;y>g;++g)for(i.call(n,c[0][g],v=d[g],f[0][g][1]),p=1;h>p;++p)i.call(n,c[p][g],v+=f[p-1][g][1],f[p][g][1]);return a}var t=m,e=gi,r=vi,i=pi,u=si,o=hi;return n.values=function(e){return arguments.length?(t=e,n):t},n.order=function(t){return arguments.length?(e=\"function\"==typeof t?t:_l.get(t)||gi,n):e},n.offset=function(t){return arguments.length?(r=\"function\"==typeof t?t:wl.get(t)||vi,n):r},n.x=function(t){return arguments.length?(u=t,n):u},n.y=function(t){return arguments.length?(o=t,n):o},n.out=function(t){return arguments.length?(i=t,n):i},n};var _l=ao.map({\"inside-out\":function(n){var t,e,r=n.length,i=n.map(di),u=n.map(yi),o=ao.range(r).sort(function(n,t){return i[n]-i[t]}),a=0,l=0,c=[],f=[];for(t=0;r>t;++t)e=o[t],l>a?(a+=u[e],c.push(e)):(l+=u[e],f.push(e));return f.reverse().concat(c)},reverse:function(n){return ao.range(n.length).reverse()},\"default\":gi}),wl=ao.map({silhouette:function(n){var t,e,r,i=n.length,u=n[0].length,o=[],a=0,l=[];for(e=0;u>e;++e){for(t=0,r=0;i>t;t++)r+=n[t][e][1];r>a&&(a=r),o.push(r)}for(e=0;u>e;++e)l[e]=(a-o[e])/2;return l},wiggle:function(n){var t,e,r,i,u,o,a,l,c,f=n.length,s=n[0],h=s.length,p=[];for(p[0]=l=c=0,e=1;h>e;++e){for(t=0,i=0;f>t;++t)i+=n[t][e][1];for(t=0,u=0,a=s[e][0]-s[e-1][0];f>t;++t){for(r=0,o=(n[t][e][1]-n[t][e-1][1])/(2*a);t>r;++r)o+=(n[r][e][1]-n[r][e-1][1])/a;u+=o*n[t][e][1]}p[e]=l-=i?u/i*a:0,c>l&&(c=l)}for(e=0;h>e;++e)p[e]-=c;return p},expand:function(n){var t,e,r,i=n.length,u=n[0].length,o=1/i,a=[];for(e=0;u>e;++e){for(t=0,r=0;i>t;t++)r+=n[t][e][1];if(r)for(t=0;i>t;t++)n[t][e][1]/=r;else for(t=0;i>t;t++)n[t][e][1]=o}for(e=0;u>e;++e)a[e]=0;return a},zero:vi});ao.layout.histogram=function(){function n(n,u){for(var o,a,l=[],c=n.map(e,this),f=r.call(this,c,u),s=i.call(this,f,c,u),u=-1,h=c.length,p=s.length-1,g=t?1:1/h;++u<p;)o=l[u]=[],o.dx=s[u+1]-(o.x=s[u]),o.y=0;if(p>0)for(u=-1;++u<h;)a=c[u],a>=f[0]&&a<=f[1]&&(o=l[ao.bisect(s,a,1,p)-1],o.y+=g,o.push(n[u]));return l}var t=!0,e=Number,r=bi,i=Mi;return n.value=function(t){return arguments.length?(e=t,n):e},n.range=function(t){return arguments.length?(r=En(t),n):r},n.bins=function(t){return arguments.length?(i=\"number\"==typeof t?function(n){return xi(n,t)}:En(t),n):i},n.frequency=function(e){return arguments.length?(t=!!e,n):t},n},ao.layout.pack=function(){function n(n,u){var o=e.call(this,n,u),a=o[0],l=i[0],c=i[1],f=null==t?Math.sqrt:\"function\"==typeof t?t:function(){return t};if(a.x=a.y=0,oi(a,function(n){n.r=+f(n.value)}),oi(a,Ni),r){var s=r*(t?1:Math.max(2*a.r/l,2*a.r/c))/2;oi(a,function(n){n.r+=s}),oi(a,Ni),oi(a,function(n){n.r-=s})}return Ci(a,l/2,c/2,t?1:1/Math.max(2*a.r/l,2*a.r/c)),o}var t,e=ao.layout.hierarchy().sort(_i),r=0,i=[1,1];return n.size=function(t){return arguments.length?(i=t,n):i},n.radius=function(e){return arguments.length?(t=null==e||\"function\"==typeof e?e:+e,n):t},n.padding=function(t){return arguments.length?(r=+t,n):r},ii(n,e)},ao.layout.tree=function(){function n(n,i){var f=o.call(this,n,i),s=f[0],h=t(s);if(oi(h,e),h.parent.m=-h.z,ui(h,r),c)ui(s,u);else{var p=s,g=s,v=s;ui(s,function(n){n.x<p.x&&(p=n),n.x>g.x&&(g=n),n.depth>v.depth&&(v=n)});var d=a(p,g)/2-p.x,y=l[0]/(g.x+a(g,p)/2+d),m=l[1]/(v.depth||1);ui(s,function(n){n.x=(n.x+d)*y,n.y=n.depth*m})}return f}function t(n){for(var t,e={A:null,children:[n]},r=[e];null!=(t=r.pop());)for(var i,u=t.children,o=0,a=u.length;a>o;++o)r.push((u[o]=i={_:u[o],parent:t,children:(i=u[o].children)&&i.slice()||[],A:null,a:null,z:0,m:0,c:0,s:0,t:null,i:o}).a=i);return e.children[0]}function e(n){var t=n.children,e=n.parent.children,r=n.i?e[n.i-1]:null;if(t.length){Di(n);var u=(t[0].z+t[t.length-1].z)/2;r?(n.z=r.z+a(n._,r._),n.m=n.z-u):n.z=u}else r&&(n.z=r.z+a(n._,r._));n.parent.A=i(n,r,n.parent.A||e[0])}function r(n){n._.x=n.z+n.parent.m,n.m+=n.parent.m}function i(n,t,e){if(t){for(var r,i=n,u=n,o=t,l=i.parent.children[0],c=i.m,f=u.m,s=o.m,h=l.m;o=Ti(o),i=qi(i),o&&i;)l=qi(l),u=Ti(u),u.a=n,r=o.z+s-i.z-c+a(o._,i._),r>0&&(Ri(Pi(o,n,e),n,r),c+=r,f+=r),s+=o.m,c+=i.m,h+=l.m,f+=u.m;o&&!Ti(u)&&(u.t=o,u.m+=s-f),i&&!qi(l)&&(l.t=i,l.m+=c-h,e=n)}return e}function u(n){n.x*=l[0],n.y=n.depth*l[1]}var o=ao.layout.hierarchy().sort(null).value(null),a=Li,l=[1,1],c=null;return n.separation=function(t){return arguments.length?(a=t,n):a},n.size=function(t){return arguments.length?(c=null==(l=t)?u:null,n):c?null:l},n.nodeSize=function(t){return arguments.length?(c=null==(l=t)?null:u,n):c?l:null},ii(n,o)},ao.layout.cluster=function(){function n(n,u){var o,a=t.call(this,n,u),l=a[0],c=0;oi(l,function(n){var t=n.children;t&&t.length?(n.x=ji(t),n.y=Ui(t)):(n.x=o?c+=e(n,o):0,n.y=0,o=n)});var f=Fi(l),s=Hi(l),h=f.x-e(f,s)/2,p=s.x+e(s,f)/2;return oi(l,i?function(n){n.x=(n.x-l.x)*r[0],n.y=(l.y-n.y)*r[1]}:function(n){n.x=(n.x-h)/(p-h)*r[0],n.y=(1-(l.y?n.y/l.y:1))*r[1]}),a}var t=ao.layout.hierarchy().sort(null).value(null),e=Li,r=[1,1],i=!1;return n.separation=function(t){return arguments.length?(e=t,n):e},n.size=function(t){return arguments.length?(i=null==(r=t),n):i?null:r},n.nodeSize=function(t){return arguments.length?(i=null!=(r=t),n):i?r:null},ii(n,t)},ao.layout.treemap=function(){function n(n,t){for(var e,r,i=-1,u=n.length;++i<u;)r=(e=n[i]).value*(0>t?0:t),e.area=isNaN(r)||0>=r?0:r}function t(e){var u=e.children;if(u&&u.length){var o,a,l,c=s(e),f=[],h=u.slice(),g=1/0,v=\"slice\"===p?c.dx:\"dice\"===p?c.dy:\"slice-dice\"===p?1&e.depth?c.dy:c.dx:Math.min(c.dx,c.dy);for(n(h,c.dx*c.dy/e.value),f.area=0;(l=h.length)>0;)f.push(o=h[l-1]),f.area+=o.area,\"squarify\"!==p||(a=r(f,v))<=g?(h.pop(),g=a):(f.area-=f.pop().area,i(f,v,c,!1),v=Math.min(c.dx,c.dy),f.length=f.area=0,g=1/0);f.length&&(i(f,v,c,!0),f.length=f.area=0),u.forEach(t)}}function e(t){var r=t.children;if(r&&r.length){var u,o=s(t),a=r.slice(),l=[];for(n(a,o.dx*o.dy/t.value),l.area=0;u=a.pop();)l.push(u),l.area+=u.area,null!=u.z&&(i(l,u.z?o.dx:o.dy,o,!a.length),l.length=l.area=0);r.forEach(e)}}function r(n,t){for(var e,r=n.area,i=0,u=1/0,o=-1,a=n.length;++o<a;)(e=n[o].area)&&(u>e&&(u=e),e>i&&(i=e));return r*=r,t*=t,r?Math.max(t*i*g/r,r/(t*u*g)):1/0}function i(n,t,e,r){var i,u=-1,o=n.length,a=e.x,c=e.y,f=t?l(n.area/t):0;if(t==e.dx){for((r||f>e.dy)&&(f=e.dy);++u<o;)i=n[u],i.x=a,i.y=c,i.dy=f,a+=i.dx=Math.min(e.x+e.dx-a,f?l(i.area/f):0);i.z=!0,i.dx+=e.x+e.dx-a,e.y+=f,e.dy-=f}else{for((r||f>e.dx)&&(f=e.dx);++u<o;)i=n[u],i.x=a,i.y=c,i.dx=f,c+=i.dy=Math.min(e.y+e.dy-c,f?l(i.area/f):0);i.z=!1,i.dy+=e.y+e.dy-c,e.x+=f,e.dx-=f}}function u(r){var i=o||a(r),u=i[0];return u.x=u.y=0,u.value?(u.dx=c[0],u.dy=c[1]):u.dx=u.dy=0,o&&a.revalue(u),n([u],u.dx*u.dy/u.value),(o?e:t)(u),h&&(o=i),i}var o,a=ao.layout.hierarchy(),l=Math.round,c=[1,1],f=null,s=Oi,h=!1,p=\"squarify\",g=.5*(1+Math.sqrt(5));return u.size=function(n){return arguments.length?(c=n,u):c},u.padding=function(n){function t(t){var e=n.call(u,t,t.depth);return null==e?Oi(t):Ii(t,\"number\"==typeof e?[e,e,e,e]:e)}function e(t){return Ii(t,n)}if(!arguments.length)return f;var r;return s=null==(f=n)?Oi:\"function\"==(r=typeof n)?t:\"number\"===r?(n=[n,n,n,n],e):e,u},u.round=function(n){return arguments.length?(l=n?Math.round:Number,u):l!=Number},u.sticky=function(n){return arguments.length?(h=n,o=null,u):h},u.ratio=function(n){return arguments.length?(g=n,u):g},u.mode=function(n){return arguments.length?(p=n+\"\",u):p},ii(u,a)},ao.random={normal:function(n,t){var e=arguments.length;return 2>e&&(t=1),1>e&&(n=0),function(){var e,r,i;do e=2*Math.random()-1,r=2*Math.random()-1,i=e*e+r*r;while(!i||i>1);return n+t*e*Math.sqrt(-2*Math.log(i)/i)}},logNormal:function(){var n=ao.random.normal.apply(ao,arguments);return function(){return Math.exp(n())}},bates:function(n){var t=ao.random.irwinHall(n);return function(){return t()/n}},irwinHall:function(n){return function(){for(var t=0,e=0;n>e;e++)t+=Math.random();return t}}},ao.scale={};var Sl={floor:m,ceil:m};ao.scale.linear=function(){return Wi([0,1],[0,1],Mr,!1)};var kl={s:1,g:1,p:1,r:1,e:1};ao.scale.log=function(){return ru(ao.scale.linear().domain([0,1]),10,!0,[1,10])};var Nl=ao.format(\".0e\"),El={floor:function(n){return-Math.ceil(-n)},ceil:function(n){return-Math.floor(-n)}};ao.scale.pow=function(){return iu(ao.scale.linear(),1,[0,1])},ao.scale.sqrt=function(){return ao.scale.pow().exponent(.5)},ao.scale.ordinal=function(){return ou([],{t:\"range\",a:[[]]})},ao.scale.category10=function(){return ao.scale.ordinal().range(Al)},ao.scale.category20=function(){return ao.scale.ordinal().range(Cl)},ao.scale.category20b=function(){return ao.scale.ordinal().range(zl)},ao.scale.category20c=function(){return ao.scale.ordinal().range(Ll)};var Al=[2062260,16744206,2924588,14034728,9725885,9197131,14907330,8355711,12369186,1556175].map(xn),Cl=[2062260,11454440,16744206,16759672,2924588,10018698,14034728,16750742,9725885,12955861,9197131,12885140,14907330,16234194,8355711,13092807,12369186,14408589,1556175,10410725].map(xn),zl=[3750777,5395619,7040719,10264286,6519097,9216594,11915115,13556636,9202993,12426809,15186514,15190932,8666169,11356490,14049643,15177372,8077683,10834324,13528509,14589654].map(xn),Ll=[3244733,7057110,10406625,13032431,15095053,16616764,16625259,16634018,3253076,7652470,10607003,13101504,7695281,10394312,12369372,14342891,6513507,9868950,12434877,14277081].map(xn);ao.scale.quantile=function(){return au([],[])},ao.scale.quantize=function(){return lu(0,1,[0,1])},ao.scale.threshold=function(){return cu([.5],[0,1])},ao.scale.identity=function(){return fu([0,1])},ao.svg={},ao.svg.arc=function(){function n(){var n=Math.max(0,+e.apply(this,arguments)),c=Math.max(0,+r.apply(this,arguments)),f=o.apply(this,arguments)-Io,s=a.apply(this,arguments)-Io,h=Math.abs(s-f),p=f>s?0:1;if(n>c&&(g=c,c=n,n=g),h>=Oo)return t(c,p)+(n?t(n,1-p):\"\")+\"Z\";var g,v,d,y,m,M,x,b,_,w,S,k,N=0,E=0,A=[];if((y=(+l.apply(this,arguments)||0)/2)&&(d=u===ql?Math.sqrt(n*n+c*c):+u.apply(this,arguments),p||(E*=-1),c&&(E=tn(d/c*Math.sin(y))),n&&(N=tn(d/n*Math.sin(y)))),c){m=c*Math.cos(f+E),M=c*Math.sin(f+E),x=c*Math.cos(s-E),b=c*Math.sin(s-E);var C=Math.abs(s-f-2*E)<=Fo?0:1;if(E&&yu(m,M,x,b)===p^C){var z=(f+s)/2;m=c*Math.cos(z),M=c*Math.sin(z),x=b=null}}else m=M=0;if(n){_=n*Math.cos(s-N),w=n*Math.sin(s-N),S=n*Math.cos(f+N),k=n*Math.sin(f+N);var L=Math.abs(f-s+2*N)<=Fo?0:1;if(N&&yu(_,w,S,k)===1-p^L){var q=(f+s)/2;_=n*Math.cos(q),w=n*Math.sin(q),S=k=null}}else _=w=0;if(h>Uo&&(g=Math.min(Math.abs(c-n)/2,+i.apply(this,arguments)))>.001){v=c>n^p?0:1;var T=g,R=g;if(Fo>h){var D=null==S?[_,w]:null==x?[m,M]:Re([m,M],[S,k],[x,b],[_,w]),P=m-D[0],U=M-D[1],j=x-D[0],F=b-D[1],H=1/Math.sin(Math.acos((P*j+U*F)/(Math.sqrt(P*P+U*U)*Math.sqrt(j*j+F*F)))/2),O=Math.sqrt(D[0]*D[0]+D[1]*D[1]);R=Math.min(g,(n-O)/(H-1)),T=Math.min(g,(c-O)/(H+1))}if(null!=x){var I=mu(null==S?[_,w]:[S,k],[m,M],c,T,p),Y=mu([x,b],[_,w],c,T,p);g===T?A.push(\"M\",I[0],\"A\",T,\",\",T,\" 0 0,\",v,\" \",I[1],\"A\",c,\",\",c,\" 0 \",1-p^yu(I[1][0],I[1][1],Y[1][0],Y[1][1]),\",\",p,\" \",Y[1],\"A\",T,\",\",T,\" 0 0,\",v,\" \",Y[0]):A.push(\"M\",I[0],\"A\",T,\",\",T,\" 0 1,\",v,\" \",Y[0])}else A.push(\"M\",m,\",\",M);if(null!=S){var Z=mu([m,M],[S,k],n,-R,p),V=mu([_,w],null==x?[m,M]:[x,b],n,-R,p);g===R?A.push(\"L\",V[0],\"A\",R,\",\",R,\" 0 0,\",v,\" \",V[1],\"A\",n,\",\",n,\" 0 \",p^yu(V[1][0],V[1][1],Z[1][0],Z[1][1]),\",\",1-p,\" \",Z[1],\"A\",R,\",\",R,\" 0 0,\",v,\" \",Z[0]):A.push(\"L\",V[0],\"A\",R,\",\",R,\" 0 0,\",v,\" \",Z[0])}else A.push(\"L\",_,\",\",w)}else A.push(\"M\",m,\",\",M),null!=x&&A.push(\"A\",c,\",\",c,\" 0 \",C,\",\",p,\" \",x,\",\",b),A.push(\"L\",_,\",\",w),null!=S&&A.push(\"A\",n,\",\",n,\" 0 \",L,\",\",1-p,\" \",S,\",\",k);return A.push(\"Z\"),A.join(\"\")}function t(n,t){return\"M0,\"+n+\"A\"+n+\",\"+n+\" 0 1,\"+t+\" 0,\"+-n+\"A\"+n+\",\"+n+\" 0 1,\"+t+\" 0,\"+n}var e=hu,r=pu,i=su,u=ql,o=gu,a=vu,l=du;return n.innerRadius=function(t){return arguments.length?(e=En(t),n):e},n.outerRadius=function(t){return arguments.length?(r=En(t),n):r},n.cornerRadius=function(t){return arguments.length?(i=En(t),n):i},n.padRadius=function(t){return arguments.length?(u=t==ql?ql:En(t),n):u},n.startAngle=function(t){return arguments.length?(o=En(t),n):o},n.endAngle=function(t){return arguments.length?(a=En(t),n):a},n.padAngle=function(t){return arguments.length?(l=En(t),n):l},n.centroid=function(){var n=(+e.apply(this,arguments)+ +r.apply(this,arguments))/2,t=(+o.apply(this,arguments)+ +a.apply(this,arguments))/2-Io;return[Math.cos(t)*n,Math.sin(t)*n]},n};var ql=\"auto\";ao.svg.line=function(){return Mu(m)};var Tl=ao.map({linear:xu,\"linear-closed\":bu,step:_u,\"step-before\":wu,\"step-after\":Su,basis:zu,\"basis-open\":Lu,\"basis-closed\":qu,bundle:Tu,cardinal:Eu,\"cardinal-open\":ku,\"cardinal-closed\":Nu,monotone:Fu});Tl.forEach(function(n,t){t.key=n,t.closed=/-closed$/.test(n)});var Rl=[0,2/3,1/3,0],Dl=[0,1/3,2/3,0],Pl=[0,1/6,2/3,1/6];ao.svg.line.radial=function(){var n=Mu(Hu);return n.radius=n.x,delete n.x,n.angle=n.y,delete n.y,n},wu.reverse=Su,Su.reverse=wu,ao.svg.area=function(){return Ou(m)},ao.svg.area.radial=function(){var n=Ou(Hu);return n.radius=n.x,delete n.x,n.innerRadius=n.x0,delete n.x0,n.outerRadius=n.x1,delete n.x1,n.angle=n.y,delete n.y,n.startAngle=n.y0,delete n.y0,n.endAngle=n.y1,delete n.y1,n},ao.svg.chord=function(){function n(n,a){var l=t(this,u,n,a),c=t(this,o,n,a);return\"M\"+l.p0+r(l.r,l.p1,l.a1-l.a0)+(e(l,c)?i(l.r,l.p1,l.r,l.p0):i(l.r,l.p1,c.r,c.p0)+r(c.r,c.p1,c.a1-c.a0)+i(c.r,c.p1,l.r,l.p0))+\"Z\"}function t(n,t,e,r){var i=t.call(n,e,r),u=a.call(n,i,r),o=l.call(n,i,r)-Io,f=c.call(n,i,r)-Io;return{r:u,a0:o,a1:f,p0:[u*Math.cos(o),u*Math.sin(o)],p1:[u*Math.cos(f),u*Math.sin(f)]}}function e(n,t){return n.a0==t.a0&&n.a1==t.a1}function r(n,t,e){return\"A\"+n+\",\"+n+\" 0 \"+ +(e>Fo)+\",1 \"+t}function i(n,t,e,r){return\"Q 0,0 \"+r}var u=Me,o=xe,a=Iu,l=gu,c=vu;return n.radius=function(t){return arguments.length?(a=En(t),n):a},n.source=function(t){return arguments.length?(u=En(t),n):u},n.target=function(t){return arguments.length?(o=En(t),n):o},n.startAngle=function(t){return arguments.length?(l=En(t),n):l},n.endAngle=function(t){return arguments.length?(c=En(t),n):c},n},ao.svg.diagonal=function(){function n(n,i){var u=t.call(this,n,i),o=e.call(this,n,i),a=(u.y+o.y)/2,l=[u,{x:u.x,y:a},{x:o.x,y:a},o];return l=l.map(r),\"M\"+l[0]+\"C\"+l[1]+\" \"+l[2]+\" \"+l[3]}var t=Me,e=xe,r=Yu;return n.source=function(e){return arguments.length?(t=En(e),n):t},n.target=function(t){return arguments.length?(e=En(t),n):e},n.projection=function(t){return arguments.length?(r=t,n):r},n},ao.svg.diagonal.radial=function(){var n=ao.svg.diagonal(),t=Yu,e=n.projection;return n.projection=function(n){return arguments.length?e(Zu(t=n)):t},n},ao.svg.symbol=function(){function n(n,r){return(Ul.get(t.call(this,n,r))||$u)(e.call(this,n,r))}var t=Xu,e=Vu;return n.type=function(e){return arguments.length?(t=En(e),n):t},n.size=function(t){return arguments.length?(e=En(t),n):e},n};var Ul=ao.map({circle:$u,cross:function(n){var t=Math.sqrt(n/5)/2;return\"M\"+-3*t+\",\"+-t+\"H\"+-t+\"V\"+-3*t+\"H\"+t+\"V\"+-t+\"H\"+3*t+\"V\"+t+\"H\"+t+\"V\"+3*t+\"H\"+-t+\"V\"+t+\"H\"+-3*t+\"Z\"},diamond:function(n){var t=Math.sqrt(n/(2*Fl)),e=t*Fl;return\"M0,\"+-t+\"L\"+e+\",0 0,\"+t+\" \"+-e+\",0Z\"},square:function(n){var t=Math.sqrt(n)/2;return\"M\"+-t+\",\"+-t+\"L\"+t+\",\"+-t+\" \"+t+\",\"+t+\" \"+-t+\",\"+t+\"Z\"},\"triangle-down\":function(n){var t=Math.sqrt(n/jl),e=t*jl/2;return\"M0,\"+e+\"L\"+t+\",\"+-e+\" \"+-t+\",\"+-e+\"Z\"},\"triangle-up\":function(n){var t=Math.sqrt(n/jl),e=t*jl/2;return\"M0,\"+-e+\"L\"+t+\",\"+e+\" \"+-t+\",\"+e+\"Z\"}});ao.svg.symbolTypes=Ul.keys();var jl=Math.sqrt(3),Fl=Math.tan(30*Yo);Co.transition=function(n){for(var t,e,r=Hl||++Zl,i=Ku(n),u=[],o=Ol||{time:Date.now(),ease:Nr,delay:0,duration:250},a=-1,l=this.length;++a<l;){u.push(t=[]);for(var c=this[a],f=-1,s=c.length;++f<s;)(e=c[f])&&Qu(e,f,i,r,o),t.push(e)}return Wu(u,i,r)},Co.interrupt=function(n){return this.each(null==n?Il:Bu(Ku(n)))};var Hl,Ol,Il=Bu(Ku()),Yl=[],Zl=0;Yl.call=Co.call,Yl.empty=Co.empty,Yl.node=Co.node,Yl.size=Co.size,ao.transition=function(n,t){return n&&n.transition?Hl?n.transition(t):n:ao.selection().transition(n)},ao.transition.prototype=Yl,Yl.select=function(n){var t,e,r,i=this.id,u=this.namespace,o=[];n=A(n);for(var a=-1,l=this.length;++a<l;){o.push(t=[]);for(var c=this[a],f=-1,s=c.length;++f<s;)(r=c[f])&&(e=n.call(r,r.__data__,f,a))?(\"__data__\"in r&&(e.__data__=r.__data__),Qu(e,f,u,i,r[u][i]),t.push(e)):t.push(null)}return Wu(o,u,i)},Yl.selectAll=function(n){var t,e,r,i,u,o=this.id,a=this.namespace,l=[];n=C(n);for(var c=-1,f=this.length;++c<f;)for(var s=this[c],h=-1,p=s.length;++h<p;)if(r=s[h]){u=r[a][o],e=n.call(r,r.__data__,h,c),l.push(t=[]);for(var g=-1,v=e.length;++g<v;)(i=e[g])&&Qu(i,g,a,o,u),t.push(i)}return Wu(l,a,o)},Yl.filter=function(n){var t,e,r,i=[];\"function\"!=typeof n&&(n=O(n));for(var u=0,o=this.length;o>u;u++){i.push(t=[]);for(var e=this[u],a=0,l=e.length;l>a;a++)(r=e[a])&&n.call(r,r.__data__,a,u)&&t.push(r)}return Wu(i,this.namespace,this.id)},Yl.tween=function(n,t){var e=this.id,r=this.namespace;return arguments.length<2?this.node()[r][e].tween.get(n):Y(this,null==t?function(t){t[r][e].tween.remove(n)}:function(i){i[r][e].tween.set(n,t)})},Yl.attr=function(n,t){function e(){this.removeAttribute(a)}function r(){this.removeAttributeNS(a.space,a.local)}function i(n){return null==n?e:(n+=\"\",function(){var t,e=this.getAttribute(a);return e!==n&&(t=o(e,n),function(n){this.setAttribute(a,t(n))})})}function u(n){return null==n?r:(n+=\"\",function(){var t,e=this.getAttributeNS(a.space,a.local);return e!==n&&(t=o(e,n),function(n){this.setAttributeNS(a.space,a.local,t(n))})})}if(arguments.length<2){for(t in n)this.attr(t,n[t]);return this}var o=\"transform\"==n?$r:Mr,a=ao.ns.qualify(n);return Ju(this,\"attr.\"+n,t,a.local?u:i)},Yl.attrTween=function(n,t){function e(n,e){var r=t.call(this,n,e,this.getAttribute(i));return r&&function(n){this.setAttribute(i,r(n))}}function r(n,e){var r=t.call(this,n,e,this.getAttributeNS(i.space,i.local));return r&&function(n){this.setAttributeNS(i.space,i.local,r(n))}}var i=ao.ns.qualify(n);return this.tween(\"attr.\"+n,i.local?r:e)},Yl.style=function(n,e,r){function i(){this.style.removeProperty(n)}function u(e){return null==e?i:(e+=\"\",function(){var i,u=t(this).getComputedStyle(this,null).getPropertyValue(n);return u!==e&&(i=Mr(u,e),function(t){this.style.setProperty(n,i(t),r)})})}var o=arguments.length;if(3>o){if(\"string\"!=typeof n){2>o&&(e=\"\");for(r in n)this.style(r,n[r],e);return this}r=\"\"}return Ju(this,\"style.\"+n,e,u)},Yl.styleTween=function(n,e,r){function i(i,u){var o=e.call(this,i,u,t(this).getComputedStyle(this,null).getPropertyValue(n));return o&&function(t){this.style.setProperty(n,o(t),r)}}return arguments.length<3&&(r=\"\"),this.tween(\"style.\"+n,i)},Yl.text=function(n){return Ju(this,\"text\",n,Gu)},Yl.remove=function(){var n=this.namespace;return this.each(\"end.transition\",function(){var t;this[n].count<2&&(t=this.parentNode)&&t.removeChild(this)})},Yl.ease=function(n){var t=this.id,e=this.namespace;return arguments.length<1?this.node()[e][t].ease:(\"function\"!=typeof n&&(n=ao.ease.apply(ao,arguments)),Y(this,function(r){r[e][t].ease=n}))},Yl.delay=function(n){var t=this.id,e=this.namespace;return arguments.length<1?this.node()[e][t].delay:Y(this,\"function\"==typeof n?function(r,i,u){r[e][t].delay=+n.call(r,r.__data__,i,u)}:(n=+n,function(r){r[e][t].delay=n}))},Yl.duration=function(n){var t=this.id,e=this.namespace;return arguments.length<1?this.node()[e][t].duration:Y(this,\"function\"==typeof n?function(r,i,u){r[e][t].duration=Math.max(1,n.call(r,r.__data__,i,u))}:(n=Math.max(1,n),function(r){r[e][t].duration=n}))},Yl.each=function(n,t){var e=this.id,r=this.namespace;if(arguments.length<2){var i=Ol,u=Hl;try{Hl=e,Y(this,function(t,i,u){Ol=t[r][e],n.call(t,t.__data__,i,u)})}finally{Ol=i,Hl=u}}else Y(this,function(i){var u=i[r][e];(u.event||(u.event=ao.dispatch(\"start\",\"end\",\"interrupt\"))).on(n,t)});return this},Yl.transition=function(){for(var n,t,e,r,i=this.id,u=++Zl,o=this.namespace,a=[],l=0,c=this.length;c>l;l++){a.push(n=[]);for(var t=this[l],f=0,s=t.length;s>f;f++)(e=t[f])&&(r=e[o][i],Qu(e,f,o,u,{time:r.time,ease:r.ease,delay:r.delay+r.duration,duration:r.duration})),n.push(e)}return Wu(a,o,u)},ao.svg.axis=function(){function n(n){n.each(function(){var n,c=ao.select(this),f=this.__chart__||e,s=this.__chart__=e.copy(),h=null==l?s.ticks?s.ticks.apply(s,a):s.domain():l,p=null==t?s.tickFormat?s.tickFormat.apply(s,a):m:t,g=c.selectAll(\".tick\").data(h,s),v=g.enter().insert(\"g\",\".domain\").attr(\"class\",\"tick\").style(\"opacity\",Uo),d=ao.transition(g.exit()).style(\"opacity\",Uo).remove(),y=ao.transition(g.order()).style(\"opacity\",1),M=Math.max(i,0)+o,x=Zi(s),b=c.selectAll(\".domain\").data([0]),_=(b.enter().append(\"path\").attr(\"class\",\"domain\"),ao.transition(b));v.append(\"line\"),v.append(\"text\");var w,S,k,N,E=v.select(\"line\"),A=y.select(\"line\"),C=g.select(\"text\").text(p),z=v.select(\"text\"),L=y.select(\"text\"),q=\"top\"===r||\"left\"===r?-1:1;if(\"bottom\"===r||\"top\"===r?(n=no,w=\"x\",k=\"y\",S=\"x2\",N=\"y2\",C.attr(\"dy\",0>q?\"0em\":\".71em\").style(\"text-anchor\",\"middle\"),_.attr(\"d\",\"M\"+x[0]+\",\"+q*u+\"V0H\"+x[1]+\"V\"+q*u)):(n=to,w=\"y\",k=\"x\",S=\"y2\",N=\"x2\",C.attr(\"dy\",\".32em\").style(\"text-anchor\",0>q?\"end\":\"start\"),_.attr(\"d\",\"M\"+q*u+\",\"+x[0]+\"H0V\"+x[1]+\"H\"+q*u)),E.attr(N,q*i),z.attr(k,q*M),A.attr(S,0).attr(N,q*i),L.attr(w,0).attr(k,q*M),s.rangeBand){var T=s,R=T.rangeBand()/2;f=s=function(n){return T(n)+R}}else f.rangeBand?f=s:d.call(n,s,f);v.call(n,f,s),y.call(n,s,s)})}var t,e=ao.scale.linear(),r=Vl,i=6,u=6,o=3,a=[10],l=null;return n.scale=function(t){return arguments.length?(e=t,n):e},n.orient=function(t){return arguments.length?(r=t in Xl?t+\"\":Vl,n):r},n.ticks=function(){return arguments.length?(a=co(arguments),n):a},n.tickValues=function(t){return arguments.length?(l=t,n):l},n.tickFormat=function(e){return arguments.length?(t=e,n):t},n.tickSize=function(t){var e=arguments.length;return e?(i=+t,u=+arguments[e-1],n):i},n.innerTickSize=function(t){return arguments.length?(i=+t,n):i},n.outerTickSize=function(t){return arguments.length?(u=+t,n):u},n.tickPadding=function(t){return arguments.length?(o=+t,n):o},n.tickSubdivide=function(){return arguments.length&&n},n};var Vl=\"bottom\",Xl={top:1,right:1,bottom:1,left:1};ao.svg.brush=function(){function n(t){t.each(function(){var t=ao.select(this).style(\"pointer-events\",\"all\").style(\"-webkit-tap-highlight-color\",\"rgba(0,0,0,0)\").on(\"mousedown.brush\",u).on(\"touchstart.brush\",u),o=t.selectAll(\".background\").data([0]);o.enter().append(\"rect\").attr(\"class\",\"background\").style(\"visibility\",\"hidden\").style(\"cursor\",\"crosshair\"),t.selectAll(\".extent\").data([0]).enter().append(\"rect\").attr(\"class\",\"extent\").style(\"cursor\",\"move\");var a=t.selectAll(\".resize\").data(v,m);a.exit().remove(),a.enter().append(\"g\").attr(\"class\",function(n){return\"resize \"+n}).style(\"cursor\",function(n){return $l[n]}).append(\"rect\").attr(\"x\",function(n){return/[ew]$/.test(n)?-3:null}).attr(\"y\",function(n){return/^[ns]/.test(n)?-3:null}).attr(\"width\",6).attr(\"height\",6).style(\"visibility\",\"hidden\"),a.style(\"display\",n.empty()?\"none\":null);var l,s=ao.transition(t),h=ao.transition(o);c&&(l=Zi(c),h.attr(\"x\",l[0]).attr(\"width\",l[1]-l[0]),r(s)),f&&(l=Zi(f),h.attr(\"y\",l[0]).attr(\"height\",l[1]-l[0]),i(s)),e(s)})}function e(n){n.selectAll(\".resize\").attr(\"transform\",function(n){return\"translate(\"+s[+/e$/.test(n)]+\",\"+h[+/^s/.test(n)]+\")\"})}function r(n){n.select(\".extent\").attr(\"x\",s[0]),n.selectAll(\".extent,.n>rect,.s>rect\").attr(\"width\",s[1]-s[0])}function i(n){n.select(\".extent\").attr(\"y\",h[0]),n.selectAll(\".extent,.e>rect,.w>rect\").attr(\"height\",h[1]-h[0])}function u(){function u(){32==ao.event.keyCode&&(C||(M=null,L[0]-=s[1],L[1]-=h[1],C=2),S())}function v(){32==ao.event.keyCode&&2==C&&(L[0]+=s[1],L[1]+=h[1],C=0,S())}function d(){var n=ao.mouse(b),t=!1;x&&(n[0]+=x[0],n[1]+=x[1]),C||(ao.event.altKey?(M||(M=[(s[0]+s[1])/2,(h[0]+h[1])/2]),L[0]=s[+(n[0]<M[0])],L[1]=h[+(n[1]<M[1])]):M=null),E&&y(n,c,0)&&(r(k),t=!0),A&&y(n,f,1)&&(i(k),t=!0),t&&(e(k),w({type:\"brush\",mode:C?\"move\":\"resize\"}))}function y(n,t,e){var r,i,u=Zi(t),l=u[0],c=u[1],f=L[e],v=e?h:s,d=v[1]-v[0];return C&&(l-=f,c-=d+f),r=(e?g:p)?Math.max(l,Math.min(c,n[e])):n[e],C?i=(r+=f)+d:(M&&(f=Math.max(l,Math.min(c,2*M[e]-r))),r>f?(i=r,r=f):i=f),v[0]!=r||v[1]!=i?(e?a=null:o=null,v[0]=r,v[1]=i,!0):void 0}function m(){d(),k.style(\"pointer-events\",\"all\").selectAll(\".resize\").style(\"display\",n.empty()?\"none\":null),ao.select(\"body\").style(\"cursor\",null),q.on(\"mousemove.brush\",null).on(\"mouseup.brush\",null).on(\"touchmove.brush\",null).on(\"touchend.brush\",null).on(\"keydown.brush\",null).on(\"keyup.brush\",null),z(),w({type:\"brushend\"})}var M,x,b=this,_=ao.select(ao.event.target),w=l.of(b,arguments),k=ao.select(b),N=_.datum(),E=!/^(n|s)$/.test(N)&&c,A=!/^(e|w)$/.test(N)&&f,C=_.classed(\"extent\"),z=W(b),L=ao.mouse(b),q=ao.select(t(b)).on(\"keydown.brush\",u).on(\"keyup.brush\",v);if(ao.event.changedTouches?q.on(\"touchmove.brush\",d).on(\"touchend.brush\",m):q.on(\"mousemove.brush\",d).on(\"mouseup.brush\",m),k.interrupt().selectAll(\"*\").interrupt(),C)L[0]=s[0]-L[0],L[1]=h[0]-L[1];else if(N){var T=+/w$/.test(N),R=+/^n/.test(N);x=[s[1-T]-L[0],h[1-R]-L[1]],L[0]=s[T],L[1]=h[R]}else ao.event.altKey&&(M=L.slice());k.style(\"pointer-events\",\"none\").selectAll(\".resize\").style(\"display\",null),ao.select(\"body\").style(\"cursor\",_.style(\"cursor\")),w({type:\"brushstart\"}),d()}var o,a,l=N(n,\"brushstart\",\"brush\",\"brushend\"),c=null,f=null,s=[0,0],h=[0,0],p=!0,g=!0,v=Bl[0];return n.event=function(n){n.each(function(){var n=l.of(this,arguments),t={x:s,y:h,i:o,j:a},e=this.__chart__||t;this.__chart__=t,Hl?ao.select(this).transition().each(\"start.brush\",function(){o=e.i,a=e.j,s=e.x,h=e.y,n({type:\"brushstart\"})}).tween(\"brush:brush\",function(){var e=xr(s,t.x),r=xr(h,t.y);return o=a=null,function(i){s=t.x=e(i),h=t.y=r(i),n({type:\"brush\",mode:\"resize\"})}}).each(\"end.brush\",function(){o=t.i,a=t.j,n({type:\"brush\",mode:\"resize\"}),n({type:\"brushend\"})}):(n({type:\"brushstart\"}),n({type:\"brush\",mode:\"resize\"}),n({type:\"brushend\"}))})},n.x=function(t){return arguments.length?(c=t,v=Bl[!c<<1|!f],n):c},n.y=function(t){return arguments.length?(f=t,v=Bl[!c<<1|!f],n):f},n.clamp=function(t){return arguments.length?(c&&f?(p=!!t[0],g=!!t[1]):c?p=!!t:f&&(g=!!t),n):c&&f?[p,g]:c?p:f?g:null},n.extent=function(t){var e,r,i,u,l;return arguments.length?(c&&(e=t[0],r=t[1],f&&(e=e[0],r=r[0]),o=[e,r],c.invert&&(e=c(e),r=c(r)),e>r&&(l=e,e=r,r=l),e==s[0]&&r==s[1]||(s=[e,r])),f&&(i=t[0],u=t[1],c&&(i=i[1],u=u[1]),a=[i,u],f.invert&&(i=f(i),u=f(u)),i>u&&(l=i,i=u,u=l),i==h[0]&&u==h[1]||(h=[i,u])),n):(c&&(o?(e=o[0],r=o[1]):(e=s[0],r=s[1],c.invert&&(e=c.invert(e),r=c.invert(r)),e>r&&(l=e,e=r,r=l))),f&&(a?(i=a[0],u=a[1]):(i=h[0],u=h[1],f.invert&&(i=f.invert(i),u=f.invert(u)),i>u&&(l=i,i=u,u=l))),c&&f?[[e,i],[r,u]]:c?[e,r]:f&&[i,u])},n.clear=function(){return n.empty()||(s=[0,0],h=[0,0],o=a=null),n},n.empty=function(){return!!c&&s[0]==s[1]||!!f&&h[0]==h[1]},ao.rebind(n,l,\"on\")};var $l={n:\"ns-resize\",e:\"ew-resize\",s:\"ns-resize\",w:\"ew-resize\",nw:\"nwse-resize\",ne:\"nesw-resize\",se:\"nwse-resize\",sw:\"nesw-resize\"},Bl=[[\"n\",\"e\",\"s\",\"w\",\"nw\",\"ne\",\"se\",\"sw\"],[\"e\",\"w\"],[\"n\",\"s\"],[]],Wl=ga.format=xa.timeFormat,Jl=Wl.utc,Gl=Jl(\"%Y-%m-%dT%H:%M:%S.%LZ\");Wl.iso=Date.prototype.toISOString&&+new Date(\"2000-01-01T00:00:00.000Z\")?eo:Gl,eo.parse=function(n){var t=new Date(n);return isNaN(t)?null:t},eo.toString=Gl.toString,ga.second=On(function(n){return new va(1e3*Math.floor(n/1e3))},function(n,t){n.setTime(n.getTime()+1e3*Math.floor(t))},function(n){return n.getSeconds()}),ga.seconds=ga.second.range,ga.seconds.utc=ga.second.utc.range,ga.minute=On(function(n){return new va(6e4*Math.floor(n/6e4))},function(n,t){n.setTime(n.getTime()+6e4*Math.floor(t))},function(n){return n.getMinutes()}),ga.minutes=ga.minute.range,ga.minutes.utc=ga.minute.utc.range,ga.hour=On(function(n){var t=n.getTimezoneOffset()/60;return new va(36e5*(Math.floor(n/36e5-t)+t))},function(n,t){n.setTime(n.getTime()+36e5*Math.floor(t))},function(n){return n.getHours()}),ga.hours=ga.hour.range,ga.hours.utc=ga.hour.utc.range,ga.month=On(function(n){return n=ga.day(n),n.setDate(1),n},function(n,t){n.setMonth(n.getMonth()+t)},function(n){return n.getMonth()}),ga.months=ga.month.range,ga.months.utc=ga.month.utc.range;var Kl=[1e3,5e3,15e3,3e4,6e4,3e5,9e5,18e5,36e5,108e5,216e5,432e5,864e5,1728e5,6048e5,2592e6,7776e6,31536e6],Ql=[[ga.second,1],[ga.second,5],[ga.second,15],[ga.second,30],[ga.minute,1],[ga.minute,5],[ga.minute,15],[ga.minute,30],[ga.hour,1],[ga.hour,3],[ga.hour,6],[ga.hour,12],[ga.day,1],[ga.day,2],[ga.week,1],[ga.month,1],[ga.month,3],[ga.year,1]],nc=Wl.multi([[\".%L\",function(n){return n.getMilliseconds()}],[\":%S\",function(n){return n.getSeconds()}],[\"%I:%M\",function(n){return n.getMinutes()}],[\"%I %p\",function(n){return n.getHours()}],[\"%a %d\",function(n){return n.getDay()&&1!=n.getDate()}],[\"%b %d\",function(n){return 1!=n.getDate()}],[\"%B\",function(n){return n.getMonth()}],[\"%Y\",zt]]),tc={range:function(n,t,e){return ao.range(Math.ceil(n/e)*e,+t,e).map(io)},floor:m,ceil:m};Ql.year=ga.year,ga.scale=function(){return ro(ao.scale.linear(),Ql,nc)};var ec=Ql.map(function(n){return[n[0].utc,n[1]]}),rc=Jl.multi([[\".%L\",function(n){return n.getUTCMilliseconds()}],[\":%S\",function(n){return n.getUTCSeconds()}],[\"%I:%M\",function(n){return n.getUTCMinutes()}],[\"%I %p\",function(n){return n.getUTCHours()}],[\"%a %d\",function(n){return n.getUTCDay()&&1!=n.getUTCDate()}],[\"%b %d\",function(n){return 1!=n.getUTCDate()}],[\"%B\",function(n){return n.getUTCMonth()}],[\"%Y\",zt]]);ec.year=ga.year.utc,ga.scale.utc=function(){return ro(ao.scale.linear(),ec,rc)},ao.text=An(function(n){return n.responseText}),ao.json=function(n,t){return Cn(n,\"application/json\",uo,t)},ao.html=function(n,t){return Cn(n,\"text/html\",oo,t)},ao.xml=An(function(n){return n.responseXML}),\"function\"==typeof define&&define.amd?(this.d3=ao,define(ao)):\"object\"==typeof module&&module.exports?module.exports=ao:this.d3=ao}();\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/resources/s2.js",
    "content": "!function(){var a={};a.dev=!1,a.tooltip=a.tooltip||{},a.utils=a.utils||{},a.models=a.models||{},a.charts={},a.logs={},a.dom={},\"undefined\"!=typeof module&&\"undefined\"!=typeof exports&&\"undefined\"==typeof d3&&(d3=require(\"d3\")),a.dispatch=d3.dispatch(\"render_start\",\"render_end\"),Function.prototype.bind||(Function.prototype.bind=function(a){if(\"function\"!=typeof this)throw new TypeError(\"Function.prototype.bind - what is trying to be bound is not callable\");var b=Array.prototype.slice.call(arguments,1),c=this,d=function(){},e=function(){return c.apply(this instanceof d&&a?this:a,b.concat(Array.prototype.slice.call(arguments)))};return d.prototype=this.prototype,e.prototype=new d,e}),a.dev&&(a.dispatch.on(\"render_start\",function(b){a.logs.startTime=+new Date}),a.dispatch.on(\"render_end\",function(b){a.logs.endTime=+new Date,a.logs.totalTime=a.logs.endTime-a.logs.startTime,a.log(\"total\",a.logs.totalTime)})),a.log=function(){if(a.dev&&window.console&&console.log&&console.log.apply)console.log.apply(console,arguments);else if(a.dev&&window.console&&\"function\"==typeof console.log&&Function.prototype.bind){var b=Function.prototype.bind.call(console.log,console);b.apply(console,arguments)}return arguments[arguments.length-1]},a.deprecated=function(a,b){console&&console.warn&&console.warn(\"nvd3 warning: `\"+a+\"` has been deprecated. \",b||\"\")},a.render=function(b){b=b||1,a.render.active=!0,a.dispatch.render_start();var c=function(){for(var d,e,f=0;b>f&&(e=a.render.queue[f]);f++)d=e.generate(),typeof e.callback==typeof Function&&e.callback(d);a.render.queue.splice(0,f),a.render.queue.length?setTimeout(c):(a.dispatch.render_end(),a.render.active=!1)};setTimeout(c)},a.render.active=!1,a.render.queue=[],a.addGraph=function(b){typeof arguments[0]==typeof Function&&(b={generate:arguments[0],callback:arguments[1]}),a.render.queue.push(b),a.render.active||a.render()},\"undefined\"!=typeof module&&\"undefined\"!=typeof exports&&(module.exports=a),\"undefined\"!=typeof window&&(window.nv=a),a.dom.write=function(a){return void 0!==window.fastdom?fastdom.mutate(a):a()},a.dom.read=function(a){return void 0!==window.fastdom?fastdom.measure(a):a()},a.interactiveGuideline=function(){\"use strict\";function b(l){l.each(function(l){function m(){var a=d3.mouse(this),d=a[0],e=a[1],h=!0,i=!1;if(k&&(d=d3.event.offsetX,e=d3.event.offsetY,\"svg\"!==d3.event.target.tagName&&(h=!1),d3.event.target.className.baseVal.match(\"nv-legend\")&&(i=!0)),h&&(d-=c.left,e-=c.top),\"mouseout\"===d3.event.type||0>d||0>e||d>o||e>p||d3.event.relatedTarget&&void 0===d3.event.relatedTarget.ownerSVGElement||i){if(k&&d3.event.relatedTarget&&void 0===d3.event.relatedTarget.ownerSVGElement&&(void 0===d3.event.relatedTarget.className||d3.event.relatedTarget.className.match(j.nvPointerEventsClass)))return;return g.elementMouseout({mouseX:d,mouseY:e}),b.renderGuideLine(null),void j.hidden(!0)}j.hidden(!1);var l=\"function\"==typeof f.rangeBands,m=void 0;if(l){var n=d3.bisect(f.range(),d)-1;if(!(f.range()[n]+f.rangeBand()>=d))return g.elementMouseout({mouseX:d,mouseY:e}),b.renderGuideLine(null),void j.hidden(!0);m=f.domain()[d3.bisect(f.range(),d)-1]}else m=f.invert(d);g.elementMousemove({mouseX:d,mouseY:e,pointXValue:m}),\"dblclick\"===d3.event.type&&g.elementDblclick({mouseX:d,mouseY:e,pointXValue:m}),\"click\"===d3.event.type&&g.elementClick({mouseX:d,mouseY:e,pointXValue:m}),\"mousedown\"===d3.event.type&&g.elementMouseDown({mouseX:d,mouseY:e,pointXValue:m}),\"mouseup\"===d3.event.type&&g.elementMouseUp({mouseX:d,mouseY:e,pointXValue:m})}var n=d3.select(this),o=d||960,p=e||400,q=n.selectAll(\"g.nv-wrap.nv-interactiveLineLayer\").data([l]),r=q.enter().append(\"g\").attr(\"class\",\" nv-wrap nv-interactiveLineLayer\");r.append(\"g\").attr(\"class\",\"nv-interactiveGuideLine\"),i&&(i.on(\"touchmove\",m).on(\"mousemove\",m,!0).on(\"mouseout\",m,!0).on(\"mousedown\",m,!0).on(\"mouseup\",m,!0).on(\"dblclick\",m).on(\"click\",m),b.guideLine=null,b.renderGuideLine=function(c){h&&(b.guideLine&&b.guideLine.attr(\"x1\")===c||a.dom.write(function(){var b=q.select(\".nv-interactiveGuideLine\").selectAll(\"line\").data(null!=c?[a.utils.NaNtoZero(c)]:[],String);b.enter().append(\"line\").attr(\"class\",\"nv-guideline\").attr(\"x1\",function(a){return a}).attr(\"x2\",function(a){return a}).attr(\"y1\",p).attr(\"y2\",0),b.exit().remove()}))})})}var c={left:0,top:0},d=null,e=null,f=d3.scale.linear(),g=d3.dispatch(\"elementMousemove\",\"elementMouseout\",\"elementClick\",\"elementDblclick\",\"elementMouseDown\",\"elementMouseUp\"),h=!0,i=null,j=a.models.tooltip(),k=window.ActiveXObject;return j.duration(0).hideDelay(0).hidden(!1),b.dispatch=g,b.tooltip=j,b.margin=function(a){return arguments.length?(c.top=\"undefined\"!=typeof a.top?a.top:c.top,c.left=\"undefined\"!=typeof a.left?a.left:c.left,b):c},b.width=function(a){return arguments.length?(d=a,b):d},b.height=function(a){return arguments.length?(e=a,b):e},b.xScale=function(a){return arguments.length?(f=a,b):f},b.showGuideLine=function(a){return arguments.length?(h=a,b):h},b.svgContainer=function(a){return arguments.length?(i=a,b):i},b},a.interactiveBisect=function(a,b,c){\"use strict\";if(!(a instanceof Array))return null;var d;d=\"function\"!=typeof c?function(a){return a.x}:c;var e=function(a,b){return d(a)-b},f=d3.bisector(e).left,g=d3.max([0,f(a,b)-1]),h=d(a[g]);if(\"undefined\"==typeof h&&(h=g),h===b)return g;var i=d3.min([g+1,a.length-1]),j=d(a[i]);return\"undefined\"==typeof j&&(j=i),Math.abs(j-b)>=Math.abs(h-b)?g:i},a.nearestValueIndex=function(a,b,c){\"use strict\";var d=1/0,e=null;return a.forEach(function(a,f){var g=Math.abs(b-a);null!=a&&d>=g&&c>g&&(d=g,e=f)}),e},a.models.tooltip=function(){\"use strict\";function b(){if(!l||!l.node()){var a=[1];l=d3.select(document.body).selectAll(\".nvtooltip\").data(a),l.enter().append(\"div\").attr(\"class\",\"nvtooltip \"+(i?i:\"xy-tooltip\")).attr(\"id\",d).style(\"top\",0).style(\"left\",0).style(\"opacity\",0).style(\"position\",\"fixed\").selectAll(\"div, table, td, tr\").classed(q,!0).classed(q,!0),l.exit().remove()}}function c(){return n&&w(e)?(a.dom.write(function(){b();var a=u(e);a&&(l.node().innerHTML=a),y()}),c):void 0}var d=\"nvtooltip-\"+Math.floor(1e5*Math.random()),e=null,f=\"w\",g=25,h=0,i=null,j=!0,k=200,l=null,m={left:null,top:null},n=!0,o=100,p=!0,q=\"nv-pointer-events-none\",r=function(a,b){return a},s=function(a){return a},t=function(a,b){return a},u=function(a){if(null===a)return\"\";var b=d3.select(document.createElement(\"table\"));if(p){var c=b.selectAll(\"thead\").data([a]).enter().append(\"thead\");c.append(\"tr\").append(\"td\").attr(\"colspan\",3).append(\"strong\").classed(\"x-value\",!0).html(s(a.value))}var d=b.selectAll(\"tbody\").data([a]).enter().append(\"tbody\"),e=d.selectAll(\"tr\").data(function(a){return a.series}).enter().append(\"tr\").classed(\"highlight\",function(a){return a.highlight});e.append(\"td\").classed(\"legend-color-guide\",!0).append(\"div\").style(\"background-color\",function(a){return a.color}),e.append(\"td\").classed(\"key\",!0).classed(\"total\",function(a){return!!a.total}).html(function(a,b){return t(a.key,b)}),e.append(\"td\").classed(\"value\",!0).html(function(a,b){return r(a.value,b)}),e.filter(function(a,b){return void 0!==a.percent}).append(\"td\").classed(\"percent\",!0).html(function(a,b){return\"(\"+d3.format(\"%\")(a.percent)+\")\"}),e.selectAll(\"td\").each(function(a){if(a.highlight){var b=d3.scale.linear().domain([0,1]).range([\"#fff\",a.color]),c=.6;d3.select(this).style(\"border-bottom-color\",b(c)).style(\"border-top-color\",b(c))}});var f=b.node().outerHTML;return void 0!==a.footer&&(f+=\"<div class='footer'>\"+a.footer+\"</div>\"),f},v=function(){var a={left:null!==d3.event?d3.event.clientX:0,top:null!==d3.event?d3.event.clientY:0};if(\"none\"!=getComputedStyle(document.body).transform){var b=document.body.getBoundingClientRect();a.left-=b.left,a.top-=b.top}return a},w=function(b){if(b&&b.series){if(a.utils.isArray(b.series))return!0;if(a.utils.isObject(b.series))return b.series=[b.series],!0}return!1},x=function(a){var b,c,d,e=l.node().offsetHeight,h=l.node().offsetWidth,i=document.documentElement.clientWidth,j=document.documentElement.clientHeight;switch(f){case\"e\":b=-h-g,c=-(e/2),a.left+b<0&&(b=g),(d=a.top+c)<0&&(c-=d),(d=a.top+c+e)>j&&(c-=d-j);break;case\"w\":b=g,c=-(e/2),a.left+b+h>i&&(b=-h-g),(d=a.top+c)<0&&(c-=d),(d=a.top+c+e)>j&&(c-=d-j);break;case\"n\":b=-(h/2)-5,c=g,a.top+c+e>j&&(c=-e-g),(d=a.left+b)<0&&(b-=d),(d=a.left+b+h)>i&&(b-=d-i);break;case\"s\":b=-(h/2),c=-e-g,a.top+c<0&&(c=g),(d=a.left+b)<0&&(b-=d),(d=a.left+b+h)>i&&(b-=d-i);break;case\"center\":b=-(h/2),c=-(e/2);break;default:b=0,c=0}return{left:b,top:c}},y=function(){a.dom.read(function(){var a=v(),b=x(a),c=a.left+b.left,d=a.top+b.top;if(j)l.interrupt().transition().delay(k).duration(0).style(\"opacity\",0);else{var e=\"translate(\"+m.left+\"px, \"+m.top+\"px)\",f=\"translate(\"+Math.round(c)+\"px, \"+Math.round(d)+\"px)\",g=d3.interpolateString(e,f),h=l.style(\"opacity\")<.1;l.interrupt().transition().duration(h?0:o).styleTween(\"transform\",function(a){return g},\"important\").styleTween(\"-webkit-transform\",function(a){return g}).style(\"-ms-transform\",f).style(\"opacity\",1)}m.left=c,m.top=d})};return c.nvPointerEventsClass=q,c.options=a.utils.optionsFunc.bind(c),c._options=Object.create({},{duration:{get:function(){return o},set:function(a){o=a}},gravity:{get:function(){return f},set:function(a){f=a}},distance:{get:function(){return g},set:function(a){g=a}},snapDistance:{get:function(){return h},set:function(a){h=a}},classes:{get:function(){return i},set:function(a){i=a}},enabled:{get:function(){return n},set:function(a){n=a}},hideDelay:{get:function(){return k},set:function(a){k=a}},contentGenerator:{get:function(){return u},set:function(a){u=a}},valueFormatter:{get:function(){return r},set:function(a){r=a}},headerFormatter:{get:function(){return s},set:function(a){s=a}},keyFormatter:{get:function(){return t},set:function(a){t=a}},headerEnabled:{get:function(){return p},set:function(a){p=a}},position:{get:function(){return v},set:function(a){v=a}},chartContainer:{get:function(){return document.body},set:function(b){a.deprecated(\"chartContainer\",\"feature removed after 1.8.3\")}},fixedTop:{get:function(){return null},set:function(b){a.deprecated(\"fixedTop\",\"feature removed after 1.8.1\")}},offset:{get:function(){return{left:0,top:0}},set:function(b){a.deprecated(\"offset\",\"use chart.tooltip.distance() instead\")}},hidden:{get:function(){return j},set:function(a){j!=a&&(j=!!a,c())}},data:{get:function(){return e},set:function(a){a.point&&(a.value=a.point.x,a.series=a.series||{},a.series.value=a.point.y,a.series.color=a.point.color||a.series.color),e=a}},node:{get:function(){return l.node()},set:function(a){}},id:{get:function(){return d},set:function(a){}}}),a.utils.initOptions(c),c},a.utils.windowSize=function(){var a={width:640,height:480};return window.innerWidth&&window.innerHeight?(a.width=window.innerWidth,a.height=window.innerHeight,a):\"CSS1Compat\"==document.compatMode&&document.documentElement&&document.documentElement.offsetWidth?(a.width=document.documentElement.offsetWidth,a.height=document.documentElement.offsetHeight,a):document.body&&document.body.offsetWidth?(a.width=document.body.offsetWidth,a.height=document.body.offsetHeight,a):a},a.utils.isArray=Array.isArray,a.utils.isObject=function(a){return null!==a&&\"object\"==typeof a},a.utils.isFunction=function(a){return\"function\"==typeof a},a.utils.isDate=function(a){return\"[object Date]\"===toString.call(a)},a.utils.isNumber=function(a){return!isNaN(a)&&\"number\"==typeof a},a.utils.windowResize=function(b){return window.addEventListener?window.addEventListener(\"resize\",b):a.log(\"ERROR: Failed to bind to window.resize with: \",b),{callback:b,clear:function(){window.removeEventListener(\"resize\",b)}}},a.utils.getColor=function(b){if(void 0===b)return a.utils.defaultColor();if(a.utils.isArray(b)){var c=d3.scale.ordinal().range(b);return function(a,b){var d=void 0===b?a:b;return a.color||c(d)}}return b},a.utils.defaultColor=function(){return a.utils.getColor(d3.scale.category20().range())},a.utils.customTheme=function(b,c,d){c=c||function(a){return a.key},d=d||d3.scale.category20().range();var e=d.length;return function(f,g){var h=c(f);return a.utils.isFunction(b[h])?b[h]():void 0!==b[h]?b[h]:(e||(e=d.length),e-=1,d[e])}},a.utils.pjax=function(b,c){var d=function(d){d3.html(d,function(d){var e=d3.select(c).node();e.parentNode.replaceChild(d3.select(d).select(c).node(),e),a.utils.pjax(b,c)})};d3.selectAll(b).on(\"click\",function(){history.pushState(this.href,this.textContent,this.href),d(this.href),d3.event.preventDefault()}),d3.select(window).on(\"popstate\",function(){d3.event.state&&d(d3.event.state)})},a.utils.calcApproxTextWidth=function(b){if(a.utils.isFunction(b.style)&&a.utils.isFunction(b.text)){var c=parseInt(b.style(\"font-size\").replace(\"px\",\"\"),10),d=b.text().length;return a.utils.NaNtoZero(d*c*.5)}return 0},a.utils.NaNtoZero=function(b){return!a.utils.isNumber(b)||isNaN(b)||null===b||b===1/0||b===-(1/0)?0:b},d3.selection.prototype.watchTransition=function(a){var b=[this].concat([].slice.call(arguments,1));return a.transition.apply(a,b)},a.utils.renderWatch=function(b,c){if(!(this instanceof a.utils.renderWatch))return new a.utils.renderWatch(b,c);var d=void 0!==c?c:250,e=[],f=this;this.models=function(a){return a=[].slice.call(arguments,0),a.forEach(function(a){a.__rendered=!1,function(a){a.dispatch.on(\"renderEnd\",function(b){a.__rendered=!0,f.renderEnd(\"model\")})}(a),e.indexOf(a)<0&&e.push(a)}),this},this.reset=function(a){void 0!==a&&(d=a),e=[]},this.transition=function(a,b,c){if(b=arguments.length>1?[].slice.call(arguments,1):[],c=b.length>1?b.pop():void 0!==d?d:250,a.__rendered=!1,e.indexOf(a)<0&&e.push(a),0===c)return a.__rendered=!0,a.delay=function(){return this},a.duration=function(){return this},a;0===a.length?a.__rendered=!0:a.every(function(a){return!a.length})?a.__rendered=!0:a.__rendered=!1;var g=0;return a.transition().duration(c).each(function(){++g}).each(\"end\",function(c,d){0===--g&&(a.__rendered=!0,f.renderEnd.apply(this,b))})},this.renderEnd=function(){e.every(function(a){return a.__rendered})&&(e.forEach(function(a){a.__rendered=!1}),b.renderEnd.apply(this,arguments))}},a.utils.deepExtend=function(b){var c=arguments.length>1?[].slice.call(arguments,1):[];c.forEach(function(c){for(var d in c){var e=a.utils.isArray(b[d]),f=a.utils.isObject(b[d]),g=a.utils.isObject(c[d]);f&&!e&&g?a.utils.deepExtend(b[d],c[d]):b[d]=c[d]}})},a.utils.state=function(){if(!(this instanceof a.utils.state))return new a.utils.state;var b={},c=function(){},d=function(){return{}},e=null,f=null;this.dispatch=d3.dispatch(\"change\",\"set\"),this.dispatch.on(\"set\",function(a){c(a,!0)}),this.getter=function(a){return d=a,this},this.setter=function(a,b){return b||(b=function(){}),c=function(c,d){a(c),d&&b()},this},this.init=function(b){e=e||{},a.utils.deepExtend(e,b)};var g=function(){var a=d();if(JSON.stringify(a)===JSON.stringify(b))return!1;for(var c in a)void 0===b[c]&&(b[c]={}),b[c]=a[c],f=!0;return!0};this.update=function(){e&&(c(e,!1),e=null),g.call(this)&&this.dispatch.change(b)}},a.utils.optionsFunc=function(b){return b&&d3.map(b).forEach(function(b,c){a.utils.isFunction(this[b])&&this[b](c)}.bind(this)),this},a.utils.calcTicksX=function(b,c){var d=1,e=0;for(e;e<c.length;e+=1){var f=c[e]&&c[e].values?c[e].values.length:0;d=f>d?f:d}return a.log(\"Requested number of ticks: \",b),a.log(\"Calculated max values to be: \",d),b=b>d?b=d-1:b,b=1>b?1:b,b=Math.floor(b),a.log(\"Calculating tick count as: \",b),b},a.utils.calcTicksY=function(b,c){return a.utils.calcTicksX(b,c)},a.utils.initOption=function(a,b){a._calls&&a._calls[b]?a[b]=a._calls[b]:(a[b]=function(c){return arguments.length?(a._overrides[b]=!0,a._options[b]=c,a):a._options[b]},a[\"_\"+b]=function(c){return arguments.length?(a._overrides[b]||(a._options[b]=c),a):a._options[b]})},a.utils.initOptions=function(b){b._overrides=b._overrides||{};var c=Object.getOwnPropertyNames(b._options||{}),d=Object.getOwnPropertyNames(b._calls||{});c=c.concat(d);for(var e in c)a.utils.initOption(b,c[e])},a.utils.inheritOptionsD3=function(a,b,c){a._d3options=c.concat(a._d3options||[]),c.unshift(b),c.unshift(a),d3.rebind.apply(this,c)},a.utils.arrayUnique=function(a){return a.sort().filter(function(b,c){return!c||b!=a[c-1]})},a.utils.symbolMap=d3.map(),a.utils.symbol=function(){function b(b,e){var f=c.call(this,b,e),g=d.call(this,b,e);return-1!==d3.svg.symbolTypes.indexOf(f)?d3.svg.symbol().type(f).size(g)():a.utils.symbolMap.get(f)(g)}var c,d=64;return b.type=function(a){return arguments.length?(c=d3.functor(a),b):c},b.size=function(a){return arguments.length?(d=d3.functor(a),b):d},b},a.utils.inheritOptions=function(b,c){var d=Object.getOwnPropertyNames(c._options||{}),e=Object.getOwnPropertyNames(c._calls||{}),f=c._inherited||[],g=c._d3options||[],h=d.concat(e).concat(f).concat(g);h.unshift(c),h.unshift(b),d3.rebind.apply(this,h),b._inherited=a.utils.arrayUnique(d.concat(e).concat(f).concat(d).concat(b._inherited||[])),b._d3options=a.utils.arrayUnique(g.concat(b._d3options||[]))},a.utils.initSVG=function(a){a.classed({\"nvd3-svg\":!0})},a.utils.sanitizeHeight=function(a,b){return a||parseInt(b.style(\"height\"),10)||400},a.utils.sanitizeWidth=function(a,b){return a||parseInt(b.style(\"width\"),10)||960},a.utils.availableHeight=function(b,c,d){return Math.max(0,a.utils.sanitizeHeight(b,c)-d.top-d.bottom)},a.utils.availableWidth=function(b,c,d){return Math.max(0,a.utils.sanitizeWidth(b,c)-d.left-d.right)},a.utils.noData=function(b,c){var d=b.options(),e=d.margin(),f=d.noData(),g=null==f?[\"No Data Available.\"]:[f],h=a.utils.availableHeight(null,c,e),i=a.utils.availableWidth(null,c,e),j=e.left+i/2,k=e.top+h/2;c.selectAll(\"g\").remove();var l=c.selectAll(\".nv-noData\").data(g);l.enter().append(\"text\").attr(\"class\",\"nvd3 nv-noData\").attr(\"dy\",\"-.7em\").style(\"text-anchor\",\"middle\"),l.attr(\"x\",j).attr(\"y\",k).text(function(a){return a})},a.utils.wrapTicks=function(a,b){a.each(function(){for(var a,c=d3.select(this),d=c.text().split(/\\s+/).reverse(),e=[],f=0,g=1.1,h=c.attr(\"y\"),i=parseFloat(c.attr(\"dy\")),j=c.text(null).append(\"tspan\").attr(\"x\",0).attr(\"y\",h).attr(\"dy\",i+\"em\");a=d.pop();)e.push(a),j.text(e.join(\" \")),j.node().getComputedTextLength()>b&&(e.pop(),j.text(e.join(\" \")),e=[a],j=c.append(\"tspan\").attr(\"x\",0).attr(\"y\",h).attr(\"dy\",++f*g+i+\"em\").text(a))})},a.utils.arrayEquals=function(b,c){if(b===c)return!0;if(!b||!c)return!1;if(b.length!=c.length)return!1;for(var d=0,e=b.length;e>d;d++)if(b[d]instanceof Array&&c[d]instanceof Array){if(!a.arrayEquals(b[d],c[d]))return!1}else if(b[d]!=c[d])return!1;return!0},a.models.axis=function(){\"use strict\";function b(g){return t.reset(),g.each(function(b){var g=d3.select(this);a.utils.initSVG(g);var q=g.selectAll(\"g.nv-wrap.nv-axis\").data([b]),r=q.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-axis\"),u=(r.append(\"g\"),q.select(\"g\"));null!==n?c.ticks(n):(\"top\"==c.orient()||\"bottom\"==c.orient())&&c.ticks(Math.abs(d.range()[1]-d.range()[0])/100),u.watchTransition(t,\"axis\").call(c),s=s||c.scale();var v=c.tickFormat();null==v&&(v=s.tickFormat());var w=u.selectAll(\"text.nv-axislabel\").data([h||null]);w.exit().remove(),void 0!==p&&u.selectAll(\"g\").select(\"text\").style(\"font-size\",p);var x,y,z;switch(c.orient()){case\"top\":w.enter().append(\"text\").attr(\"class\",\"nv-axislabel\"),z=0,1===d.range().length?z=m?2*d.range()[0]+d.rangeBand():0:2===d.range().length?z=m?d.range()[0]+d.range()[1]+d.rangeBand():d.range()[1]:d.range().length>2&&(z=d.range()[d.range().length-1]+(d.range()[1]-d.range()[0])),w.attr(\"text-anchor\",\"middle\").attr(\"y\",0).attr(\"x\",z/2),i&&(y=q.selectAll(\"g.nv-axisMaxMin\").data(d.domain()),y.enter().append(\"g\").attr(\"class\",function(a,b){return[\"nv-axisMaxMin\",\"nv-axisMaxMin-x\",0==b?\"nv-axisMin-x\":\"nv-axisMax-x\"].join(\" \")}).append(\"text\"),y.exit().remove(),y.attr(\"transform\",function(b,c){return\"translate(\"+a.utils.NaNtoZero(d(b))+\",0)\"}).select(\"text\").attr(\"dy\",\"-0.5em\").attr(\"y\",-c.tickPadding()).attr(\"text-anchor\",\"middle\").text(function(a,b){var c=v(a);return(\"\"+c).match(\"NaN\")?\"\":c}),y.watchTransition(t,\"min-max top\").attr(\"transform\",function(b,c){return\"translate(\"+a.utils.NaNtoZero(d.range()[c])+\",0)\"}));break;case\"bottom\":x=o+36;var A=30,B=0,C=u.selectAll(\"g\").select(\"text\"),D=\"\";if(j%360){C.attr(\"transform\",\"\"),C.each(function(a,b){var c=this.getBoundingClientRect(),d=c.width;B=c.height,d>A&&(A=d)}),D=\"rotate(\"+j+\" 0,\"+(B/2+c.tickPadding())+\")\";var E=Math.abs(Math.sin(j*Math.PI/180));x=(E?E*A:A)+30,C.attr(\"transform\",D).style(\"text-anchor\",j%360>0?\"start\":\"end\")}else l?C.attr(\"transform\",function(a,b){return\"translate(0,\"+(b%2==0?\"0\":\"12\")+\")\"}):C.attr(\"transform\",\"translate(0,0)\");w.enter().append(\"text\").attr(\"class\",\"nv-axislabel\"),z=0,1===d.range().length?z=m?2*d.range()[0]+d.rangeBand():0:2===d.range().length?z=m?d.range()[0]+d.range()[1]+d.rangeBand():d.range()[1]:d.range().length>2&&(z=d.range()[d.range().length-1]+(d.range()[1]-d.range()[0])),w.attr(\"text-anchor\",\"middle\").attr(\"y\",x).attr(\"x\",z/2),i&&(y=q.selectAll(\"g.nv-axisMaxMin\").data([d.domain()[0],d.domain()[d.domain().length-1]]),y.enter().append(\"g\").attr(\"class\",function(a,b){return[\"nv-axisMaxMin\",\"nv-axisMaxMin-x\",0==b?\"nv-axisMin-x\":\"nv-axisMax-x\"].join(\" \")}).append(\"text\"),y.exit().remove(),y.attr(\"transform\",function(b,c){return\"translate(\"+a.utils.NaNtoZero(d(b)+(m?d.rangeBand()/2:0))+\",0)\"}).select(\"text\").attr(\"dy\",\".71em\").attr(\"y\",c.tickPadding()).attr(\"transform\",D).style(\"text-anchor\",j?j%360>0?\"start\":\"end\":\"middle\").text(function(a,b){var c=v(a);return(\"\"+c).match(\"NaN\")?\"\":c}),y.watchTransition(t,\"min-max bottom\").attr(\"transform\",function(b,c){return\"translate(\"+a.utils.NaNtoZero(d(b)+(m?d.rangeBand()/2:0))+\",0)\"}));break;case\"right\":w.enter().append(\"text\").attr(\"class\",\"nv-axislabel\"),w.style(\"text-anchor\",k?\"middle\":\"begin\").attr(\"transform\",k?\"rotate(90)\":\"\").attr(\"y\",k?-Math.max(e.right,f)+12-(o||0):-10).attr(\"x\",k?d3.max(d.range())/2:c.tickPadding()),i&&(y=q.selectAll(\"g.nv-axisMaxMin\").data(d.domain()),y.enter().append(\"g\").attr(\"class\",function(a,b){return[\"nv-axisMaxMin\",\"nv-axisMaxMin-y\",0==b?\"nv-axisMin-y\":\"nv-axisMax-y\"].join(\" \")}).append(\"text\").style(\"opacity\",0),y.exit().remove(),y.attr(\"transform\",function(b,c){return\"translate(0,\"+a.utils.NaNtoZero(d(b))+\")\"}).select(\"text\").attr(\"dy\",\".32em\").attr(\"y\",0).attr(\"x\",c.tickPadding()).style(\"text-anchor\",\"start\").text(function(a,b){var c=v(a);return(\"\"+c).match(\"NaN\")?\"\":c}),y.watchTransition(t,\"min-max right\").attr(\"transform\",function(b,c){return\"translate(0,\"+a.utils.NaNtoZero(d.range()[c])+\")\"}).select(\"text\").style(\"opacity\",1));break;case\"left\":w.enter().append(\"text\").attr(\"class\",\"nv-axislabel\"),w.style(\"text-anchor\",k?\"middle\":\"end\").attr(\"transform\",k?\"rotate(-90)\":\"\").attr(\"y\",k?-Math.max(e.left,f)+25-(o||0):-10).attr(\"x\",k?-d3.max(d.range())/2:-c.tickPadding()),i&&(y=q.selectAll(\"g.nv-axisMaxMin\").data(d.domain()),y.enter().append(\"g\").attr(\"class\",function(a,b){return[\"nv-axisMaxMin\",\"nv-axisMaxMin-y\",0==b?\"nv-axisMin-y\":\"nv-axisMax-y\"].join(\" \")}).append(\"text\").style(\"opacity\",0),y.exit().remove(),y.attr(\"transform\",function(b,c){return\"translate(0,\"+a.utils.NaNtoZero(s(b))+\")\"}).select(\"text\").attr(\"dy\",\".32em\").attr(\"y\",0).attr(\"x\",-c.tickPadding()).attr(\"text-anchor\",\"end\").text(function(a,b){var c=v(a);return(\"\"+c).match(\"NaN\")?\"\":c}),y.watchTransition(t,\"min-max right\").attr(\"transform\",function(b,c){return\"translate(0,\"+a.utils.NaNtoZero(d.range()[c])+\")\"}).select(\"text\").style(\"opacity\",1))}if(w.text(function(a){return a}),!i||\"left\"!==c.orient()&&\"right\"!==c.orient()||(u.selectAll(\"g\").each(function(a,b){d3.select(this).select(\"text\").attr(\"opacity\",1),(d(a)<d.range()[1]+10||d(a)>d.range()[0]-10)&&((a>1e-10||-1e-10>a)&&d3.select(this).attr(\"opacity\",0),d3.select(this).select(\"text\").attr(\"opacity\",0))}),d.domain()[0]==d.domain()[1]&&0==d.domain()[0]&&q.selectAll(\"g.nv-axisMaxMin\").style(\"opacity\",function(a,b){return b?0:1})),i&&(\"top\"===c.orient()||\"bottom\"===c.orient())){var F=[];q.selectAll(\"g.nv-axisMaxMin\").each(function(a,b){try{b?F.push(d(a)-this.getBoundingClientRect().width-4):F.push(d(a)+this.getBoundingClientRect().width+4)}catch(c){b?F.push(d(a)-4):F.push(d(a)+4)}}),u.selectAll(\"g\").each(function(a,b){(d(a)<F[0]||d(a)>F[1])&&(a>1e-10||-1e-10>a?d3.select(this).remove():d3.select(this).select(\"text\").remove())})}u.selectAll(\".tick\").filter(function(a){return!parseFloat(Math.round(1e5*a)/1e6)&&void 0!==a}).classed(\"zero\",!0),s=d.copy()}),t.renderEnd(\"axis immediate\"),b}var c=d3.svg.axis(),d=d3.scale.linear(),e={top:0,right:0,bottom:0,left:0},f=75,g=60,h=null,i=!0,j=0,k=!0,l=!1,m=!1,n=null,o=0,p=void 0,q=250,r=d3.dispatch(\"renderEnd\");c.scale(d).orient(\"bottom\").tickFormat(function(a){return a});var s,t=a.utils.renderWatch(r,q);return b.axis=c,b.dispatch=r,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{axisLabelDistance:{get:function(){return o},set:function(a){o=a}},staggerLabels:{get:function(){return l},set:function(a){l=a}},rotateLabels:{get:function(){return j},set:function(a){j=a}},rotateYLabel:{get:function(){return k},set:function(a){k=a}},showMaxMin:{get:function(){return i},set:function(a){i=a}},axisLabel:{get:function(){return h},set:function(a){h=a}},height:{get:function(){return g},set:function(a){g=a}},ticks:{get:function(){return n},set:function(a){n=a}},width:{get:function(){return f},set:function(a){f=a}},fontSize:{get:function(){return p},set:function(a){p=a}},margin:{get:function(){return e},set:function(a){e.top=void 0!==a.top?a.top:e.top,e.right=void 0!==a.right?a.right:e.right,e.bottom=void 0!==a.bottom?a.bottom:e.bottom,e.left=void 0!==a.left?a.left:e.left}},duration:{get:function(){return q},set:function(a){q=a,t.reset(q)}},scale:{get:function(){return d},set:function(e){d=e,c.scale(d),m=\"function\"==typeof d.rangeBands,a.utils.inheritOptionsD3(b,d,[\"domain\",\"range\",\"rangeBand\",\"rangeBands\"])}}}),a.utils.initOptions(b),a.utils.inheritOptionsD3(b,c,[\"orient\",\"tickValues\",\"tickSubdivide\",\"tickSize\",\"tickPadding\",\"tickFormat\"]),a.utils.inheritOptionsD3(b,d,[\"domain\",\"range\",\"rangeBand\",\"rangeBands\"]),b},a.models.boxPlot=function(){\"use strict\";function b(l){return E.reset(),l.each(function(b){var l=j-i.left-i.right,F=k-i.top-i.bottom;A=d3.select(this),a.utils.initSVG(A),m.domain(c||b.map(function(a,b){return o(a,b)})).rangeBands(d||[0,l],.1);var G=[];if(!e){var H,I,J=[];b.forEach(function(a,b){var c=p(a),d=r(a),e=s(a),f=t(a),g=v(a);g&&g.forEach(function(a,b){J.push(w(a,b,void 0))}),e&&J.push(e),c&&J.push(c),d&&J.push(d),f&&J.push(f)}),H=d3.min(J),I=d3.max(J),G=[H,I]}n.domain(e||G),n.range(f||[F,0]),g=g||m,h=h||n.copy().range([n(0),n(0)]);var K=A.selectAll(\"g.nv-wrap\").data([b]);K.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap\");K.attr(\"transform\",\"translate(\"+i.left+\",\"+i.top+\")\");var L=K.selectAll(\".nv-boxplot\").data(function(a){return a}),M=L.enter().append(\"g\").style(\"stroke-opacity\",1e-6).style(\"fill-opacity\",1e-6);L.attr(\"class\",\"nv-boxplot\").attr(\"transform\",function(a,b,c){return\"translate(\"+(m(o(a,b))+.05*m.rangeBand())+\", 0)\"}).classed(\"hover\",function(a){return a.hover}),L.watchTransition(E,\"nv-boxplot: boxplots\").style(\"stroke-opacity\",1).style(\"fill-opacity\",.75).delay(function(a,c){return c*C/b.length}).attr(\"transform\",function(a,b){return\"translate(\"+(m(o(a,b))+.05*m.rangeBand())+\", 0)\"}),L.exit().remove(),M.each(function(a,b){var c=d3.select(this);[s,t].forEach(function(d){if(d(a)){var e=d===s?\"low\":\"high\";c.append(\"line\").style(\"stroke\",u(a)||z(a,b)).attr(\"class\",\"nv-boxplot-whisker nv-boxplot-\"+e),c.append(\"line\").style(\"stroke\",u(a)||z(a,b)).attr(\"class\",\"nv-boxplot-tick nv-boxplot-\"+e)}})});var N=function(){return null===D?.9*m.rangeBand():Math.min(75,.9*m.rangeBand())},O=function(){return.45*m.rangeBand()-N()/2},P=function(){return.45*m.rangeBand()+N()/2};[s,t].forEach(function(a){var b=a===s?\"low\":\"high\",c=a===s?p:r;L.select(\"line.nv-boxplot-whisker.nv-boxplot-\"+b).watchTransition(E,\"nv-boxplot: boxplots\").attr(\"x1\",.45*m.rangeBand()).attr(\"y1\",function(b,c){return n(a(b))}).attr(\"x2\",.45*m.rangeBand()).attr(\"y2\",function(a,b){return n(c(a))}),L.select(\"line.nv-boxplot-tick.nv-boxplot-\"+b).watchTransition(E,\"nv-boxplot: boxplots\").attr(\"x1\",O).attr(\"y1\",function(b,c){return n(a(b))}).attr(\"x2\",P).attr(\"y2\",function(b,c){return n(a(b))})}),[s,t].forEach(function(a){var b=a===s?\"low\":\"high\";M.selectAll(\".nv-boxplot-\"+b).on(\"mouseover\",function(b,c,d){d3.select(this).classed(\"hover\",!0),B.elementMouseover({series:{key:a(b),color:u(b)||z(b,d)},e:d3.event})}).on(\"mouseout\",function(b,c,d){d3.select(this).classed(\"hover\",!1),B.elementMouseout({series:{key:a(b),color:u(b)||z(b,d)},e:d3.event})}).on(\"mousemove\",function(a,b){B.elementMousemove({e:d3.event})})}),M.append(\"rect\").attr(\"class\",\"nv-boxplot-box\").on(\"mouseover\",function(a,b){d3.select(this).classed(\"hover\",!0),B.elementMouseover({key:o(a),value:o(a),series:[{key:\"Q3\",value:r(a),color:u(a)||z(a,b)},{key:\"Q2\",value:q(a),color:u(a)||z(a,b)},{key:\"Q1\",value:p(a),color:u(a)||z(a,b)}],data:a,index:b,e:d3.event})}).on(\"mouseout\",function(a,b){d3.select(this).classed(\"hover\",!1),B.elementMouseout({key:o(a),value:o(a),series:[{key:\"Q3\",value:r(a),color:u(a)||z(a,b)},{key:\"Q2\",value:q(a),color:u(a)||z(a,b)},{key:\"Q1\",value:p(a),color:u(a)||z(a,b)}],data:a,index:b,e:d3.event})}).on(\"mousemove\",function(a,b){B.elementMousemove({e:d3.event})}),L.select(\"rect.nv-boxplot-box\").watchTransition(E,\"nv-boxplot: boxes\").attr(\"y\",function(a,b){return n(r(a))}).attr(\"width\",N).attr(\"x\",O).attr(\"height\",function(a,b){return Math.abs(n(r(a))-n(p(a)))||1}).style(\"fill\",function(a,b){return u(a)||z(a,b)}).style(\"stroke\",function(a,b){return u(a)||z(a,b)}),M.append(\"line\").attr(\"class\",\"nv-boxplot-median\"),L.select(\"line.nv-boxplot-median\").watchTransition(E,\"nv-boxplot: boxplots line\").attr(\"x1\",O).attr(\"y1\",function(a,b){return n(q(a))}).attr(\"x2\",P).attr(\"y2\",function(a,b){return n(q(a))});var Q=L.selectAll(\".nv-boxplot-outlier\").data(function(a){return v(a)||[]});Q.enter().append(\"circle\").style(\"fill\",function(a,b,c){return y(a,b,c)||z(a,c)}).style(\"stroke\",function(a,b,c){return y(a,b,c)||z(a,c)}).style(\"z-index\",9e3).on(\"mouseover\",function(a,b,c){d3.select(this).classed(\"hover\",!0),B.elementMouseover({series:{key:x(a,b,c),color:y(a,b,c)||z(a,c)},e:d3.event})}).on(\"mouseout\",function(a,b,c){d3.select(this).classed(\"hover\",!1),B.elementMouseout({series:{key:x(a,b,c),color:y(a,b,c)||z(a,c)},e:d3.event})}).on(\"mousemove\",function(a,b){B.elementMousemove({e:d3.event})}),Q.attr(\"class\",\"nv-boxplot-outlier\"),Q.watchTransition(E,\"nv-boxplot: nv-boxplot-outlier\").attr(\"cx\",.45*m.rangeBand()).attr(\"cy\",function(a,b,c){return n(w(a,b,c))}).attr(\"r\",\"3\"),Q.exit().remove(),g=m.copy(),h=n.copy()}),E.renderEnd(\"nv-boxplot immediate\"),b}var c,d,e,f,g,h,i={top:0,right:0,bottom:0,left:0},j=960,k=500,l=Math.floor(1e4*Math.random()),m=d3.scale.ordinal(),n=d3.scale.linear(),o=function(a){return a.label},p=function(a){return a.values.Q1},q=function(a){return a.values.Q2},r=function(a){return a.values.Q3},s=function(a){return a.values.whisker_low},t=function(a){return a.values.whisker_high},u=function(a){return a.color},v=function(a){return a.values.outliers},w=function(a,b,c){return a},x=function(a,b,c){return a},y=function(a,b,c){return void 0},z=a.utils.defaultColor(),A=null,B=d3.dispatch(\"elementMouseover\",\"elementMouseout\",\"elementMousemove\",\"renderEnd\"),C=250,D=null,E=a.utils.renderWatch(B,C);return b.dispatch=B,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return j},set:function(a){j=a}},height:{get:function(){return k},set:function(a){k=a}},maxBoxWidth:{get:function(){return D},set:function(a){D=a}},x:{get:function(){return o},set:function(a){o=a}},q1:{get:function(){return p},set:function(a){p=a}},q2:{get:function(){return q},set:function(a){q=a}},q3:{get:function(){return r},set:function(a){r=a}},wl:{get:function(){return s},set:function(a){s=a}},wh:{get:function(){return t},set:function(a){t=a}},itemColor:{get:function(){return u},set:function(a){u=a}},outliers:{get:function(){return v},set:function(a){v=a;}},outlierValue:{get:function(){return w},set:function(a){w=a}},outlierLabel:{get:function(){return x},set:function(a){x=a}},outlierColor:{get:function(){return y},set:function(a){y=a}},xScale:{get:function(){return m},set:function(a){m=a}},yScale:{get:function(){return n},set:function(a){n=a}},xDomain:{get:function(){return c},set:function(a){c=a}},yDomain:{get:function(){return e},set:function(a){e=a}},xRange:{get:function(){return d},set:function(a){d=a}},yRange:{get:function(){return f},set:function(a){f=a}},id:{get:function(){return l},set:function(a){l=a}},y:{get:function(){return console.warn(\"BoxPlot 'y' chart option is deprecated. Please use model overrides instead.\"),{}},set:function(a){console.warn(\"BoxPlot 'y' chart option is deprecated. Please use model overrides instead.\")}},margin:{get:function(){return i},set:function(a){i.top=void 0!==a.top?a.top:i.top,i.right=void 0!==a.right?a.right:i.right,i.bottom=void 0!==a.bottom?a.bottom:i.bottom,i.left=void 0!==a.left?a.left:i.left}},color:{get:function(){return z},set:function(b){z=a.utils.getColor(b)}},duration:{get:function(){return C},set:function(a){C=a,E.reset(C)}}}),a.utils.initOptions(b),b},a.models.boxPlotChart=function(){\"use strict\";function b(k){return t.reset(),t.models(e),l&&t.models(f),m&&t.models(g),k.each(function(k){var p=d3.select(this);a.utils.initSVG(p);var t=(i||parseInt(p.style(\"width\"))||960)-h.left-h.right,u=(j||parseInt(p.style(\"height\"))||400)-h.top-h.bottom;if(b.update=function(){r.beforeUpdate(),p.transition().duration(s).call(b)},b.container=this,!k||!k.length){var v=p.selectAll(\".nv-noData\").data([q]);return v.enter().append(\"text\").attr(\"class\",\"nvd3 nv-noData\").attr(\"dy\",\"-.7em\").style(\"text-anchor\",\"middle\"),v.attr(\"x\",h.left+t/2).attr(\"y\",h.top+u/2).text(function(a){return a}),b}p.selectAll(\".nv-noData\").remove(),c=e.xScale(),d=e.yScale().clamp(!0);var w=p.selectAll(\"g.nv-wrap.nv-boxPlotWithAxes\").data([k]),x=w.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-boxPlotWithAxes\").append(\"g\"),y=x.append(\"defs\"),z=w.select(\"g\");x.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),x.append(\"g\").attr(\"class\",\"nv-y nv-axis\").append(\"g\").attr(\"class\",\"nv-zeroLine\").append(\"line\"),x.append(\"g\").attr(\"class\",\"nv-barsWrap\"),z.attr(\"transform\",\"translate(\"+h.left+\",\"+h.top+\")\"),n&&z.select(\".nv-y.nv-axis\").attr(\"transform\",\"translate(\"+t+\",0)\"),e.width(t).height(u);var A=z.select(\".nv-barsWrap\").datum(k.filter(function(a){return!a.disabled}));if(A.transition().call(e),y.append(\"clipPath\").attr(\"id\",\"nv-x-label-clip-\"+e.id()).append(\"rect\"),z.select(\"#nv-x-label-clip-\"+e.id()+\" rect\").attr(\"width\",c.rangeBand()*(o?2:1)).attr(\"height\",16).attr(\"x\",-c.rangeBand()/(o?1:2)),l){f.scale(c).ticks(a.utils.calcTicksX(t/100,k)).tickSize(-u,0),z.select(\".nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+d.range()[0]+\")\"),z.select(\".nv-x.nv-axis\").call(f);var B=z.select(\".nv-x.nv-axis\").selectAll(\"g\");o&&B.selectAll(\"text\").attr(\"transform\",function(a,b,c){return\"translate(0,\"+(c%2===0?\"5\":\"17\")+\")\"})}m&&(g.scale(d).ticks(Math.floor(u/36)).tickSize(-t,0),z.select(\".nv-y.nv-axis\").call(g)),z.select(\".nv-zeroLine line\").attr(\"x1\",0).attr(\"x2\",t).attr(\"y1\",d(0)).attr(\"y2\",d(0))}),t.renderEnd(\"nv-boxplot chart immediate\"),b}var c,d,e=a.models.boxPlot(),f=a.models.axis(),g=a.models.axis(),h={top:15,right:10,bottom:50,left:60},i=null,j=null,k=a.utils.getColor(),l=!0,m=!0,n=!1,o=!1,p=a.models.tooltip(),q=\"No Data Available.\",r=d3.dispatch(\"beforeUpdate\",\"renderEnd\"),s=250;f.orient(\"bottom\").showMaxMin(!1).tickFormat(function(a){return a}),g.orient(n?\"right\":\"left\").tickFormat(d3.format(\",.1f\")),p.duration(0);var t=a.utils.renderWatch(r,s);return e.dispatch.on(\"elementMouseover.tooltip\",function(a){p.data(a).hidden(!1)}),e.dispatch.on(\"elementMouseout.tooltip\",function(a){p.data(a).hidden(!0)}),e.dispatch.on(\"elementMousemove.tooltip\",function(a){p()}),b.dispatch=r,b.boxplot=e,b.xAxis=f,b.yAxis=g,b.tooltip=p,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return i},set:function(a){i=a}},height:{get:function(){return j},set:function(a){j=a}},staggerLabels:{get:function(){return o},set:function(a){o=a}},showXAxis:{get:function(){return l},set:function(a){l=a}},showYAxis:{get:function(){return m},set:function(a){m=a}},tooltipContent:{get:function(){return p},set:function(a){p=a}},noData:{get:function(){return q},set:function(a){q=a}},margin:{get:function(){return h},set:function(a){h.top=void 0!==a.top?a.top:h.top,h.right=void 0!==a.right?a.right:h.right,h.bottom=void 0!==a.bottom?a.bottom:h.bottom,h.left=void 0!==a.left?a.left:h.left}},duration:{get:function(){return s},set:function(a){s=a,t.reset(s),e.duration(s),f.duration(s),g.duration(s)}},color:{get:function(){return k},set:function(b){k=a.utils.getColor(b),e.color(k)}},rightAlignYAxis:{get:function(){return n},set:function(a){n=a,g.orient(a?\"right\":\"left\")}}}),a.utils.inheritOptions(b,e),a.utils.initOptions(b),b},a.models.bullet=function(){\"use strict\";function b(a,b){var c=a.slice();a.sort(function(a,d){var e=c.indexOf(a),f=c.indexOf(d);return d3.descending(b[e],b[f])})}function c(e){return e.each(function(c,e){var s=p-d.left-d.right,x=q-d.top-d.bottom;r=d3.select(this),a.utils.initSVG(r);var y=g.call(this,c,e).slice(),z=h.call(this,c,e).slice(),A=i.call(this,c,e).slice().sort(d3.descending),B=j.call(this,c,e).slice(),C=k.call(this,c,e).slice(),D=l.call(this,c,e).slice(),E=m.call(this,c,e).slice(),F=n.call(this,c,e).slice();b(C,y),b(D,z),b(E,A),b(F,B),y.sort(d3.descending),z.sort(d3.descending),B.sort(d3.descending);var G=d3.scale.linear().domain(d3.extent(d3.merge([o,y]))).range(f?[s,0]:[0,s]);this.__chart__||d3.scale.linear().domain([0,1/0]).range(G.range());this.__chart__=G;for(var H=(d3.min(y),d3.max(y),y[1],r.selectAll(\"g.nv-wrap.nv-bullet\").data([c])),I=H.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-bullet\"),J=I.append(\"g\"),K=H.select(\"g\"),e=0,L=y.length;L>e;e++){var M=\"nv-range nv-range\"+e;2>=e&&(M=M+\" nv-range\"+w[e]),J.append(\"rect\").attr(\"class\",M)}J.append(\"rect\").attr(\"class\",\"nv-measure\"),H.attr(\"transform\",\"translate(\"+d.left+\",\"+d.top+\")\");for(var N=function(a){return Math.abs(G(a)-G(0))},O=function(a){return G(0>a?a:0)},e=0,L=y.length;L>e;e++){var P=y[e];K.select(\"rect.nv-range\"+e).attr(\"height\",x).attr(\"width\",N(P)).attr(\"x\",O(P)).datum(P)}K.select(\"rect.nv-measure\").style(\"fill\",t).attr(\"height\",x/3).attr(\"y\",x/3).attr(\"width\",0>B?G(0)-G(B[0]):G(B[0])-G(0)).attr(\"x\",O(B)).on(\"mouseover\",function(){u.elementMouseover({value:B[0],label:F[0]||\"Current\",color:d3.select(this).style(\"fill\")})}).on(\"mousemove\",function(){u.elementMousemove({value:B[0],label:F[0]||\"Current\",color:d3.select(this).style(\"fill\")})}).on(\"mouseout\",function(){u.elementMouseout({value:B[0],label:F[0]||\"Current\",color:d3.select(this).style(\"fill\")})});var Q=x/6,R=z.map(function(a,b){return{value:a,label:D[b]}});J.selectAll(\"path.nv-markerTriangle\").data(R).enter().append(\"path\").attr(\"class\",\"nv-markerTriangle\").attr(\"d\",\"M0,\"+Q+\"L\"+Q+\",\"+-Q+\" \"+-Q+\",\"+-Q+\"Z\").on(\"mouseover\",function(a){u.elementMouseover({value:a.value,label:a.label||\"Previous\",color:d3.select(this).style(\"fill\"),pos:[G(a.value),x/2]})}).on(\"mousemove\",function(a){u.elementMousemove({value:a.value,label:a.label||\"Previous\",color:d3.select(this).style(\"fill\")})}).on(\"mouseout\",function(a,b){u.elementMouseout({value:a.value,label:a.label||\"Previous\",color:d3.select(this).style(\"fill\")})}),K.selectAll(\"path.nv-markerTriangle\").data(R).attr(\"transform\",function(a){return\"translate(\"+G(a.value)+\",\"+x/2+\")\"});var S=A.map(function(a,b){return{value:a,label:E[b]}});J.selectAll(\"path.nv-markerLine\").data(S).enter().append(\"line\").attr(\"cursor\",\"\").attr(\"class\",\"nv-markerLine\").attr(\"x1\",function(a){return G(a.value)}).attr(\"y1\",\"2\").attr(\"x2\",function(a){return G(a.value)}).attr(\"y2\",x-2).on(\"mouseover\",function(a){u.elementMouseover({value:a.value,label:a.label||\"Previous\",color:d3.select(this).style(\"fill\"),pos:[G(a.value),x/2]})}).on(\"mousemove\",function(a){u.elementMousemove({value:a.value,label:a.label||\"Previous\",color:d3.select(this).style(\"fill\")})}).on(\"mouseout\",function(a,b){u.elementMouseout({value:a.value,label:a.label||\"Previous\",color:d3.select(this).style(\"fill\")})}),K.selectAll(\"path.nv-markerLines\").data(S).attr(\"transform\",function(a){return\"translate(\"+G(a.value)+\",\"+x/2+\")\"}),H.selectAll(\".nv-range\").on(\"mouseover\",function(a,b){var c=C[b]||v[b];u.elementMouseover({value:a,label:c,color:d3.select(this).style(\"fill\")})}).on(\"mousemove\",function(){u.elementMousemove({value:B[0],label:F[0]||\"Previous\",color:d3.select(this).style(\"fill\")})}).on(\"mouseout\",function(a,b){var c=C[b]||v[b];u.elementMouseout({value:a,label:c,color:d3.select(this).style(\"fill\")})})}),c}var d={top:0,right:0,bottom:0,left:0},e=\"left\",f=!1,g=function(a){return a.ranges},h=function(a){return a.markers?a.markers:[]},i=function(a){return a.markerLines?a.markerLines:[0]},j=function(a){return a.measures},k=function(a){return a.rangeLabels?a.rangeLabels:[]},l=function(a){return a.markerLabels?a.markerLabels:[]},m=function(a){return a.markerLineLabels?a.markerLineLabels:[]},n=function(a){return a.measureLabels?a.measureLabels:[]},o=[0],p=380,q=30,r=null,s=null,t=a.utils.getColor([\"#1f77b4\"]),u=d3.dispatch(\"elementMouseover\",\"elementMouseout\",\"elementMousemove\"),v=[\"Maximum\",\"Mean\",\"Minimum\"],w=[\"Max\",\"Avg\",\"Min\"];return c.dispatch=u,c.options=a.utils.optionsFunc.bind(c),c._options=Object.create({},{ranges:{get:function(){return g},set:function(a){g=a}},markers:{get:function(){return h},set:function(a){h=a}},measures:{get:function(){return j},set:function(a){j=a}},forceX:{get:function(){return o},set:function(a){o=a}},width:{get:function(){return p},set:function(a){p=a}},height:{get:function(){return q},set:function(a){q=a}},tickFormat:{get:function(){return s},set:function(a){s=a}},margin:{get:function(){return d},set:function(a){d.top=void 0!==a.top?a.top:d.top,d.right=void 0!==a.right?a.right:d.right,d.bottom=void 0!==a.bottom?a.bottom:d.bottom,d.left=void 0!==a.left?a.left:d.left}},orient:{get:function(){return e},set:function(a){e=a,f=\"right\"==e||\"bottom\"==e}},color:{get:function(){return t},set:function(b){t=a.utils.getColor(b)}}}),a.utils.initOptions(c),c},a.models.bulletChart=function(){\"use strict\";function b(d){return d.each(function(e,o){var p=d3.select(this);a.utils.initSVG(p);var q=a.utils.availableWidth(k,p,g),r=l-g.top-g.bottom;if(b.update=function(){b(d)},b.container=this,!e||!h.call(this,e,o))return a.utils.noData(b,p),b;p.selectAll(\".nv-noData\").remove();var s=h.call(this,e,o).slice().sort(d3.descending),t=i.call(this,e,o).slice().sort(d3.descending),u=j.call(this,e,o).slice().sort(d3.descending),v=p.selectAll(\"g.nv-wrap.nv-bulletChart\").data([e]),w=v.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-bulletChart\"),x=w.append(\"g\"),y=v.select(\"g\");x.append(\"g\").attr(\"class\",\"nv-bulletWrap\"),x.append(\"g\").attr(\"class\",\"nv-titles\"),v.attr(\"transform\",\"translate(\"+g.left+\",\"+g.top+\")\");var z=d3.scale.linear().domain([0,Math.max(s[0],t[0]||0,u[0])]).range(f?[q,0]:[0,q]),A=this.__chart__||d3.scale.linear().domain([0,1/0]).range(z.range());this.__chart__=z;var B=x.select(\".nv-titles\").append(\"g\").attr(\"text-anchor\",\"end\").attr(\"transform\",\"translate(-6,\"+(l-g.top-g.bottom)/2+\")\");B.append(\"text\").attr(\"class\",\"nv-title\").text(function(a){return a.title}),B.append(\"text\").attr(\"class\",\"nv-subtitle\").attr(\"dy\",\"1em\").text(function(a){return a.subtitle}),c.width(q).height(r);var C=y.select(\".nv-bulletWrap\");d3.transition(C).call(c);var D=m||z.tickFormat(q/100),E=y.selectAll(\"g.nv-tick\").data(z.ticks(n?n:q/50),function(a){return this.textContent||D(a)}),F=E.enter().append(\"g\").attr(\"class\",\"nv-tick\").attr(\"transform\",function(a){return\"translate(\"+A(a)+\",0)\"}).style(\"opacity\",1e-6);F.append(\"line\").attr(\"y1\",r).attr(\"y2\",7*r/6),F.append(\"text\").attr(\"text-anchor\",\"middle\").attr(\"dy\",\"1em\").attr(\"y\",7*r/6).text(D);var G=d3.transition(E).attr(\"transform\",function(a){return\"translate(\"+z(a)+\",0)\"}).style(\"opacity\",1);G.select(\"line\").attr(\"y1\",r).attr(\"y2\",7*r/6),G.select(\"text\").attr(\"y\",7*r/6),d3.transition(E.exit()).attr(\"transform\",function(a){return\"translate(\"+z(a)+\",0)\"}).style(\"opacity\",1e-6).remove()}),d3.timer.flush(),b}var c=a.models.bullet(),d=a.models.tooltip(),e=\"left\",f=!1,g={top:5,right:40,bottom:20,left:120},h=function(a){return a.ranges},i=function(a){return a.markers?a.markers:[]},j=function(a){return a.measures},k=null,l=55,m=null,n=null,o=null,p=d3.dispatch();return d.duration(0).headerEnabled(!1),c.dispatch.on(\"elementMouseover.tooltip\",function(a){a.series={key:a.label,value:a.value,color:a.color},d.data(a).hidden(!1)}),c.dispatch.on(\"elementMouseout.tooltip\",function(a){d.hidden(!0)}),c.dispatch.on(\"elementMousemove.tooltip\",function(a){d()}),b.bullet=c,b.dispatch=p,b.tooltip=d,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{ranges:{get:function(){return h},set:function(a){h=a}},markers:{get:function(){return i},set:function(a){i=a}},measures:{get:function(){return j},set:function(a){j=a}},width:{get:function(){return k},set:function(a){k=a}},height:{get:function(){return l},set:function(a){l=a}},tickFormat:{get:function(){return m},set:function(a){m=a}},ticks:{get:function(){return n},set:function(a){n=a}},noData:{get:function(){return o},set:function(a){o=a}},margin:{get:function(){return g},set:function(a){g.top=void 0!==a.top?a.top:g.top,g.right=void 0!==a.right?a.right:g.right,g.bottom=void 0!==a.bottom?a.bottom:g.bottom,g.left=void 0!==a.left?a.left:g.left}},orient:{get:function(){return e},set:function(a){e=a,f=\"right\"==e||\"bottom\"==e}}}),a.utils.inheritOptions(b,c),a.utils.initOptions(b),b},a.models.candlestickBar=function(){\"use strict\";function b(x){return x.each(function(b){c=d3.select(this);var x=a.utils.availableWidth(i,c,h),y=a.utils.availableHeight(j,c,h);a.utils.initSVG(c);var A=x/b[0].values.length*.45;l.domain(d||d3.extent(b[0].values.map(n).concat(t))),v?l.range(f||[.5*x/b[0].values.length,x*(b[0].values.length-.5)/b[0].values.length]):l.range(f||[5+A/2,x-A/2-5]),m.domain(e||[d3.min(b[0].values.map(s).concat(u)),d3.max(b[0].values.map(r).concat(u))]).range(g||[y,0]),l.domain()[0]===l.domain()[1]&&(l.domain()[0]?l.domain([l.domain()[0]-.01*l.domain()[0],l.domain()[1]+.01*l.domain()[1]]):l.domain([-1,1])),m.domain()[0]===m.domain()[1]&&(m.domain()[0]?m.domain([m.domain()[0]+.01*m.domain()[0],m.domain()[1]-.01*m.domain()[1]]):m.domain([-1,1]));var B=d3.select(this).selectAll(\"g.nv-wrap.nv-candlestickBar\").data([b[0].values]),C=B.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-candlestickBar\"),D=C.append(\"defs\"),E=C.append(\"g\"),F=B.select(\"g\");E.append(\"g\").attr(\"class\",\"nv-ticks\"),B.attr(\"transform\",\"translate(\"+h.left+\",\"+h.top+\")\"),c.on(\"click\",function(a,b){z.chartClick({data:a,index:b,pos:d3.event,id:k})}),D.append(\"clipPath\").attr(\"id\",\"nv-chart-clip-path-\"+k).append(\"rect\"),B.select(\"#nv-chart-clip-path-\"+k+\" rect\").attr(\"width\",x).attr(\"height\",y),F.attr(\"clip-path\",w?\"url(#nv-chart-clip-path-\"+k+\")\":\"\");var G=B.select(\".nv-ticks\").selectAll(\".nv-tick\").data(function(a){return a});G.exit().remove();var H=G.enter().append(\"g\");G.attr(\"class\",function(a,b,c){return(p(a,b)>q(a,b)?\"nv-tick negative\":\"nv-tick positive\")+\" nv-tick-\"+c+\"-\"+b});H.append(\"line\").attr(\"class\",\"nv-candlestick-lines\").attr(\"transform\",function(a,b){return\"translate(\"+l(n(a,b))+\",0)\"}).attr(\"x1\",0).attr(\"y1\",function(a,b){return m(r(a,b))}).attr(\"x2\",0).attr(\"y2\",function(a,b){return m(s(a,b))}),H.append(\"rect\").attr(\"class\",\"nv-candlestick-rects nv-bars\").attr(\"transform\",function(a,b){return\"translate(\"+(l(n(a,b))-A/2)+\",\"+(m(o(a,b))-(p(a,b)>q(a,b)?m(q(a,b))-m(p(a,b)):0))+\")\"}).attr(\"x\",0).attr(\"y\",0).attr(\"width\",A).attr(\"height\",function(a,b){var c=p(a,b),d=q(a,b);return c>d?m(d)-m(c):m(c)-m(d)});G.select(\".nv-candlestick-lines\").transition().attr(\"transform\",function(a,b){return\"translate(\"+l(n(a,b))+\",0)\"}).attr(\"x1\",0).attr(\"y1\",function(a,b){return m(r(a,b))}).attr(\"x2\",0).attr(\"y2\",function(a,b){return m(s(a,b))}),G.select(\".nv-candlestick-rects\").transition().attr(\"transform\",function(a,b){return\"translate(\"+(l(n(a,b))-A/2)+\",\"+(m(o(a,b))-(p(a,b)>q(a,b)?m(q(a,b))-m(p(a,b)):0))+\")\"}).attr(\"x\",0).attr(\"y\",0).attr(\"width\",A).attr(\"height\",function(a,b){var c=p(a,b),d=q(a,b);return c>d?m(d)-m(c):m(c)-m(d)})}),b}var c,d,e,f,g,h={top:0,right:0,bottom:0,left:0},i=null,j=null,k=Math.floor(1e4*Math.random()),l=d3.scale.linear(),m=d3.scale.linear(),n=function(a){return a.x},o=function(a){return a.y},p=function(a){return a.open},q=function(a){return a.close},r=function(a){return a.high},s=function(a){return a.low},t=[],u=[],v=!1,w=!0,x=a.utils.defaultColor(),y=!1,z=d3.dispatch(\"stateChange\",\"changeState\",\"renderEnd\",\"chartClick\",\"elementClick\",\"elementDblClick\",\"elementMouseover\",\"elementMouseout\",\"elementMousemove\");return b.highlightPoint=function(a,d){b.clearHighlights(),c.select(\".nv-candlestickBar .nv-tick-0-\"+a).classed(\"hover\",d)},b.clearHighlights=function(){c.select(\".nv-candlestickBar .nv-tick.hover\").classed(\"hover\",!1)},b.dispatch=z,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return i},set:function(a){i=a}},height:{get:function(){return j},set:function(a){j=a}},xScale:{get:function(){return l},set:function(a){l=a}},yScale:{get:function(){return m},set:function(a){m=a}},xDomain:{get:function(){return d},set:function(a){d=a}},yDomain:{get:function(){return e},set:function(a){e=a}},xRange:{get:function(){return f},set:function(a){f=a}},yRange:{get:function(){return g},set:function(a){g=a}},forceX:{get:function(){return t},set:function(a){t=a}},forceY:{get:function(){return u},set:function(a){u=a}},padData:{get:function(){return v},set:function(a){v=a}},clipEdge:{get:function(){return w},set:function(a){w=a}},id:{get:function(){return k},set:function(a){k=a}},interactive:{get:function(){return y},set:function(a){y=a}},x:{get:function(){return n},set:function(a){n=a}},y:{get:function(){return o},set:function(a){o=a}},open:{get:function(){return p()},set:function(a){p=a}},close:{get:function(){return q()},set:function(a){q=a}},high:{get:function(){return r},set:function(a){r=a}},low:{get:function(){return s},set:function(a){s=a}},margin:{get:function(){return h},set:function(a){h.top=void 0!=a.top?a.top:h.top,h.right=void 0!=a.right?a.right:h.right,h.bottom=void 0!=a.bottom?a.bottom:h.bottom,h.left=void 0!=a.left?a.left:h.left}},color:{get:function(){return x},set:function(b){x=a.utils.getColor(b)}}}),a.utils.initOptions(b),b},a.models.cumulativeLineChart=function(){\"use strict\";function b(l){return H.reset(),H.models(f),r&&H.models(g),s&&H.models(h),l.each(function(l){function A(a,c){d3.select(b.container).style(\"cursor\",\"ew-resize\")}function E(a,b){G.x=d3.event.x,G.i=Math.round(F.invert(G.x)),K()}function H(a,c){d3.select(b.container).style(\"cursor\",\"auto\"),y.index=G.i,C.stateChange(y)}function K(){aa.data([G]);var a=b.duration();b.duration(0),b.update(),b.duration(a)}var L=d3.select(this);a.utils.initSVG(L),L.classed(\"nv-chart-\"+x,!0);var M=a.utils.availableWidth(o,L,m),N=a.utils.availableHeight(p,L,m);if(b.update=function(){0===D?L.call(b):L.transition().duration(D).call(b)},b.container=this,y.setter(J(l),b.update).getter(I(l)).update(),y.disabled=l.map(function(a){return!!a.disabled}),!z){var O;z={};for(O in y)y[O]instanceof Array?z[O]=y[O].slice(0):z[O]=y[O]}var P=d3.behavior.drag().on(\"dragstart\",A).on(\"drag\",E).on(\"dragend\",H);if(!(l&&l.length&&l.filter(function(a){return a.values.length}).length))return a.utils.noData(b,L),b;if(L.selectAll(\".nv-noData\").remove(),d=f.xScale(),e=f.yScale(),w)f.yDomain(null);else{var Q=l.filter(function(a){return!a.disabled}).map(function(a,b){var c=d3.extent(a.values,f.y());return c[0]<-.95&&(c[0]=-.95),[(c[0]-c[1])/(1+c[1]),(c[1]-c[0])/(1+c[0])]}),R=[d3.min(Q,function(a){return a[0]}),d3.max(Q,function(a){return a[1]})];f.yDomain(R)}F.domain([0,l[0].values.length-1]).range([0,M]).clamp(!0);var l=c(G.i,l),S=v?\"none\":\"all\",T=L.selectAll(\"g.nv-wrap.nv-cumulativeLine\").data([l]),U=T.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-cumulativeLine\").append(\"g\"),V=T.select(\"g\");if(U.append(\"g\").attr(\"class\",\"nv-interactive\"),U.append(\"g\").attr(\"class\",\"nv-x nv-axis\").style(\"pointer-events\",\"none\"),U.append(\"g\").attr(\"class\",\"nv-y nv-axis\"),U.append(\"g\").attr(\"class\",\"nv-background\"),U.append(\"g\").attr(\"class\",\"nv-linesWrap\").style(\"pointer-events\",S),U.append(\"g\").attr(\"class\",\"nv-avgLinesWrap\").style(\"pointer-events\",\"none\"),U.append(\"g\").attr(\"class\",\"nv-legendWrap\"),U.append(\"g\").attr(\"class\",\"nv-controlsWrap\"),q?(i.width(M),V.select(\".nv-legendWrap\").datum(l).call(i),i.height()>m.top&&(m.top=i.height(),N=a.utils.availableHeight(p,L,m)),V.select(\".nv-legendWrap\").attr(\"transform\",\"translate(0,\"+-m.top+\")\")):V.select(\".nv-legendWrap\").selectAll(\"*\").remove(),u){var W=[{key:\"Re-scale y-axis\",disabled:!w}];j.width(140).color([\"#444\",\"#444\",\"#444\"]).rightAlign(!1).margin({top:5,right:0,bottom:5,left:20}),V.select(\".nv-controlsWrap\").datum(W).attr(\"transform\",\"translate(0,\"+-m.top+\")\").call(j)}else V.select(\".nv-controlsWrap\").selectAll(\"*\").remove();T.attr(\"transform\",\"translate(\"+m.left+\",\"+m.top+\")\"),t&&V.select(\".nv-y.nv-axis\").attr(\"transform\",\"translate(\"+M+\",0)\");var X=l.filter(function(a){return a.tempDisabled});T.select(\".tempDisabled\").remove(),X.length&&T.append(\"text\").attr(\"class\",\"tempDisabled\").attr(\"x\",M/2).attr(\"y\",\"-.71em\").style(\"text-anchor\",\"end\").text(X.map(function(a){return a.key}).join(\", \")+\" values cannot be calculated for this time period.\"),v&&(k.width(M).height(N).margin({left:m.left,top:m.top}).svgContainer(L).xScale(d),T.select(\".nv-interactive\").call(k)),U.select(\".nv-background\").append(\"rect\"),V.select(\".nv-background rect\").attr(\"width\",M).attr(\"height\",N),f.y(function(a){return a.display.y}).width(M).height(N).color(l.map(function(a,b){return a.color||n(a,b)}).filter(function(a,b){return!l[b].disabled&&!l[b].tempDisabled}));var Y=V.select(\".nv-linesWrap\").datum(l.filter(function(a){return!a.disabled&&!a.tempDisabled}));Y.call(f),l.forEach(function(a,b){a.seriesIndex=b});var Z=l.filter(function(a){return!a.disabled&&!!B(a)}),$=V.select(\".nv-avgLinesWrap\").selectAll(\"line\").data(Z,function(a){return a.key}),_=function(a){var b=e(B(a));return 0>b?0:b>N?N:b};$.enter().append(\"line\").style(\"stroke-width\",2).style(\"stroke-dasharray\",\"10,10\").style(\"stroke\",function(a,b){return f.color()(a,a.seriesIndex)}).attr(\"x1\",0).attr(\"x2\",M).attr(\"y1\",_).attr(\"y2\",_),$.style(\"stroke-opacity\",function(a){var b=e(B(a));return 0>b||b>N?0:1}).attr(\"x1\",0).attr(\"x2\",M).attr(\"y1\",_).attr(\"y2\",_),$.exit().remove();var aa=Y.selectAll(\".nv-indexLine\").data([G]);aa.enter().append(\"rect\").attr(\"class\",\"nv-indexLine\").attr(\"width\",3).attr(\"x\",-2).attr(\"fill\",\"red\").attr(\"fill-opacity\",.5).style(\"pointer-events\",\"all\").call(P),aa.attr(\"transform\",function(a){return\"translate(\"+F(a.i)+\",0)\"}).attr(\"height\",N),r&&(g.scale(d)._ticks(a.utils.calcTicksX(M/70,l)).tickSize(-N,0),V.select(\".nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+e.range()[0]+\")\"),V.select(\".nv-x.nv-axis\").call(g)),s&&(h.scale(e)._ticks(a.utils.calcTicksY(N/36,l)).tickSize(-M,0),V.select(\".nv-y.nv-axis\").call(h)),V.select(\".nv-background rect\").on(\"click\",function(){G.x=d3.mouse(this)[0],G.i=Math.round(F.invert(G.x)),y.index=G.i,C.stateChange(y),K()}),f.dispatch.on(\"elementClick\",function(a){G.i=a.pointIndex,G.x=F(G.i),y.index=G.i,C.stateChange(y),K()}),j.dispatch.on(\"legendClick\",function(a,c){a.disabled=!a.disabled,w=!a.disabled,y.rescaleY=w,C.stateChange(y),b.update()}),i.dispatch.on(\"stateChange\",function(a){for(var c in a)y[c]=a[c];C.stateChange(y),b.update()}),k.dispatch.on(\"elementMousemove\",function(c){f.clearHighlights();var d,e,i,j=[];if(l.filter(function(a,b){return a.seriesIndex=b,!a.disabled}).forEach(function(g,h){e=a.interactiveBisect(g.values,c.pointXValue,b.x()),f.highlightPoint(h,e,!0);var k=g.values[e];\"undefined\"!=typeof k&&(\"undefined\"==typeof d&&(d=k),\"undefined\"==typeof i&&(i=b.xScale()(b.x()(k,e))),j.push({key:g.key,value:b.y()(k,e),color:n(g,g.seriesIndex)}))}),j.length>2){var m=b.yScale().invert(c.mouseY),o=Math.abs(b.yScale().domain()[0]-b.yScale().domain()[1]),p=.03*o,q=a.nearestValueIndex(j.map(function(a){return a.value}),m,p);null!==q&&(j[q].highlight=!0)}var r=g.tickFormat()(b.x()(d,e),e);k.tooltip.valueFormatter(function(a,b){return h.tickFormat()(a)}).data({value:r,series:j})(),k.renderGuideLine(i)}),k.dispatch.on(\"elementMouseout\",function(a){f.clearHighlights()}),C.on(\"changeState\",function(a){\"undefined\"!=typeof a.disabled&&(l.forEach(function(b,c){b.disabled=a.disabled[c]}),y.disabled=a.disabled),\"undefined\"!=typeof a.index&&(G.i=a.index,G.x=F(G.i),y.index=a.index,aa.data([G])),\"undefined\"!=typeof a.rescaleY&&(w=a.rescaleY),b.update()})}),H.renderEnd(\"cumulativeLineChart immediate\"),b}function c(a,b){return K||(K=f.y()),b.map(function(b,c){if(!b.values)return b;var d=b.values[a];if(null==d)return b;var e=K(d,a);return-.95>e&&!E?(b.tempDisabled=!0,b):(b.tempDisabled=!1,b.values=b.values.map(function(a,b){return a.display={y:(K(a,b)-e)/(1+e)},a}),b)})}var d,e,f=a.models.line(),g=a.models.axis(),h=a.models.axis(),i=a.models.legend(),j=a.models.legend(),k=a.interactiveGuideline(),l=a.models.tooltip(),m={top:30,right:30,bottom:50,left:60},n=a.utils.defaultColor(),o=null,p=null,q=!0,r=!0,s=!0,t=!1,u=!0,v=!1,w=!0,x=f.id(),y=a.utils.state(),z=null,A=null,B=function(a){return a.average},C=d3.dispatch(\"stateChange\",\"changeState\",\"renderEnd\"),D=250,E=!1;y.index=0,y.rescaleY=w,g.orient(\"bottom\").tickPadding(7),h.orient(t?\"right\":\"left\"),l.valueFormatter(function(a,b){return h.tickFormat()(a,b)}).headerFormatter(function(a,b){return g.tickFormat()(a,b)}),j.updateState(!1);var F=d3.scale.linear(),G={i:0,x:0},H=a.utils.renderWatch(C,D),I=function(a){return function(){return{active:a.map(function(a){return!a.disabled}),index:G.i,rescaleY:w}}},J=function(a){return function(b){void 0!==b.index&&(G.i=b.index),void 0!==b.rescaleY&&(w=b.rescaleY),void 0!==b.active&&a.forEach(function(a,c){a.disabled=!b.active[c]})}};f.dispatch.on(\"elementMouseover.tooltip\",function(a){var c={x:b.x()(a.point),y:b.y()(a.point),color:a.point.color};a.point=c,l.data(a).hidden(!1)}),f.dispatch.on(\"elementMouseout.tooltip\",function(a){l.hidden(!0)});var K=null;return b.dispatch=C,b.lines=f,b.legend=i,b.controls=j,b.xAxis=g,b.yAxis=h,b.interactiveLayer=k,b.state=y,b.tooltip=l,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return o},set:function(a){o=a}},height:{get:function(){return p},set:function(a){p=a}},rescaleY:{get:function(){return w},set:function(a){w=a}},showControls:{get:function(){return u},set:function(a){u=a}},showLegend:{get:function(){return q},set:function(a){q=a}},average:{get:function(){return B},set:function(a){B=a}},defaultState:{get:function(){return z},set:function(a){z=a}},noData:{get:function(){return A},set:function(a){A=a}},showXAxis:{get:function(){return r},set:function(a){r=a}},showYAxis:{get:function(){return s},set:function(a){s=a}},noErrorCheck:{get:function(){return E},set:function(a){E=a}},margin:{get:function(){return m},set:function(a){m.top=void 0!==a.top?a.top:m.top,m.right=void 0!==a.right?a.right:m.right,m.bottom=void 0!==a.bottom?a.bottom:m.bottom,m.left=void 0!==a.left?a.left:m.left}},color:{get:function(){return n},set:function(b){n=a.utils.getColor(b),i.color(n)}},useInteractiveGuideline:{get:function(){return v},set:function(a){v=a,a===!0&&(b.interactive(!1),b.useVoronoi(!1))}},rightAlignYAxis:{get:function(){return t},set:function(a){t=a,h.orient(a?\"right\":\"left\")}},duration:{get:function(){return D},set:function(a){D=a,f.duration(D),g.duration(D),h.duration(D),H.reset(D)}}}),a.utils.inheritOptions(b,f),a.utils.initOptions(b),b},a.models.discreteBar=function(){\"use strict\";function b(m){return y.reset(),m.each(function(b){var m=k-j.left-j.right,x=l-j.top-j.bottom;c=d3.select(this),a.utils.initSVG(c),b.forEach(function(a,b){a.values.forEach(function(a){a.series=b})});var z=d&&e?[]:b.map(function(a){return a.values.map(function(a,b){return{x:p(a,b),y:q(a,b),y0:a.y0}})});n.domain(d||d3.merge(z).map(function(a){return a.x})).rangeBands(f||[0,m],.1),o.domain(e||d3.extent(d3.merge(z).map(function(a){return a.y}).concat(r))),t?o.range(g||[x-(o.domain()[0]<0?12:0),o.domain()[1]>0?12:0]):o.range(g||[x,0]),h=h||n,i=i||o.copy().range([o(0),o(0)]);var A=c.selectAll(\"g.nv-wrap.nv-discretebar\").data([b]),B=A.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-discretebar\"),C=B.append(\"g\");A.select(\"g\");C.append(\"g\").attr(\"class\",\"nv-groups\"),A.attr(\"transform\",\"translate(\"+j.left+\",\"+j.top+\")\");var D=A.select(\".nv-groups\").selectAll(\".nv-group\").data(function(a){return a},function(a){return a.key});D.enter().append(\"g\").style(\"stroke-opacity\",1e-6).style(\"fill-opacity\",1e-6),D.exit().watchTransition(y,\"discreteBar: exit groups\").style(\"stroke-opacity\",1e-6).style(\"fill-opacity\",1e-6).remove(),D.attr(\"class\",function(a,b){return\"nv-group nv-series-\"+b}).classed(\"hover\",function(a){return a.hover}),D.watchTransition(y,\"discreteBar: groups\").style(\"stroke-opacity\",1).style(\"fill-opacity\",.75);var E=D.selectAll(\"g.nv-bar\").data(function(a){return a.values});E.exit().remove();var F=E.enter().append(\"g\").attr(\"transform\",function(a,b,c){return\"translate(\"+(n(p(a,b))+.05*n.rangeBand())+\", \"+o(0)+\")\"}).on(\"mouseover\",function(a,b){d3.select(this).classed(\"hover\",!0),v.elementMouseover({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"mouseout\",function(a,b){d3.select(this).classed(\"hover\",!1),v.elementMouseout({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"mousemove\",function(a,b){v.elementMousemove({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"click\",function(a,b){var c=this;v.elementClick({data:a,index:b,color:d3.select(this).style(\"fill\"),event:d3.event,element:c}),d3.event.stopPropagation()}).on(\"dblclick\",function(a,b){v.elementDblClick({data:a,index:b,color:d3.select(this).style(\"fill\")}),d3.event.stopPropagation()});F.append(\"rect\").attr(\"height\",0).attr(\"width\",.9*n.rangeBand()/b.length),t?(F.append(\"text\").attr(\"text-anchor\",\"middle\"),E.select(\"text\").text(function(a,b){return u(q(a,b))}).watchTransition(y,\"discreteBar: bars text\").attr(\"x\",.9*n.rangeBand()/2).attr(\"y\",function(a,b){return q(a,b)<0?o(q(a,b))-o(0)+12:-4})):E.selectAll(\"text\").remove(),E.attr(\"class\",function(a,b){return q(a,b)<0?\"nv-bar negative\":\"nv-bar positive\"}).style(\"fill\",function(a,b){return a.color||s(a,b)}).style(\"stroke\",function(a,b){return a.color||s(a,b)}).select(\"rect\").attr(\"class\",w).watchTransition(y,\"discreteBar: bars rect\").attr(\"width\",.9*n.rangeBand()/b.length),E.watchTransition(y,\"discreteBar: bars\").attr(\"transform\",function(a,b){var c=n(p(a,b))+.05*n.rangeBand(),d=q(a,b)<0?o(0):o(0)-o(q(a,b))<1?o(0)-1:o(q(a,b));return\"translate(\"+c+\", \"+d+\")\"}).select(\"rect\").attr(\"height\",function(a,b){return Math.max(Math.abs(o(q(a,b))-o(0)),1)}),h=n.copy(),i=o.copy()}),y.renderEnd(\"discreteBar immediate\"),b}var c,d,e,f,g,h,i,j={top:0,right:0,bottom:0,left:0},k=960,l=500,m=Math.floor(1e4*Math.random()),n=d3.scale.ordinal(),o=d3.scale.linear(),p=function(a){return a.x},q=function(a){return a.y},r=[0],s=a.utils.defaultColor(),t=!1,u=d3.format(\",.2f\"),v=d3.dispatch(\"chartClick\",\"elementClick\",\"elementDblClick\",\"elementMouseover\",\"elementMouseout\",\"elementMousemove\",\"renderEnd\"),w=\"discreteBar\",x=250,y=a.utils.renderWatch(v,x);return b.dispatch=v,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return k},set:function(a){k=a}},height:{get:function(){return l},set:function(a){l=a}},forceY:{get:function(){return r},set:function(a){r=a}},showValues:{get:function(){return t},set:function(a){t=a}},x:{get:function(){return p},set:function(a){p=a}},y:{get:function(){return q},set:function(a){q=a}},xScale:{get:function(){return n},set:function(a){n=a}},yScale:{get:function(){return o},set:function(a){o=a}},xDomain:{get:function(){return d},set:function(a){d=a}},yDomain:{get:function(){return e},set:function(a){e=a}},xRange:{get:function(){return f},set:function(a){f=a}},yRange:{get:function(){return g},set:function(a){g=a}},valueFormat:{get:function(){return u},set:function(a){u=a}},id:{get:function(){return m},set:function(a){m=a}},rectClass:{get:function(){return w},set:function(a){w=a}},margin:{get:function(){return j},set:function(a){j.top=void 0!==a.top?a.top:j.top,j.right=void 0!==a.right?a.right:j.right,j.bottom=void 0!==a.bottom?a.bottom:j.bottom,j.left=void 0!==a.left?a.left:j.left}},color:{get:function(){return s},set:function(b){s=a.utils.getColor(b)}},duration:{get:function(){return x},set:function(a){x=a,y.reset(x)}}}),a.utils.initOptions(b),b},a.models.discreteBarChart=function(){\"use strict\";function b(i){return x.reset(),x.models(e),o&&x.models(f),p&&x.models(g),i.each(function(i){var m=d3.select(this);a.utils.initSVG(m);var u=a.utils.availableWidth(k,m,j),x=a.utils.availableHeight(l,m,j);if(b.update=function(){v.beforeUpdate(),m.transition().duration(w).call(b)},b.container=this,!(i&&i.length&&i.filter(function(a){return a.values.length}).length))return a.utils.noData(b,m),b;m.selectAll(\".nv-noData\").remove(),c=e.xScale(),d=e.yScale().clamp(!0);var y=m.selectAll(\"g.nv-wrap.nv-discreteBarWithAxes\").data([i]),z=y.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-discreteBarWithAxes\").append(\"g\"),A=z.append(\"defs\"),B=y.select(\"g\");z.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),z.append(\"g\").attr(\"class\",\"nv-y nv-axis\").append(\"g\").attr(\"class\",\"nv-zeroLine\").append(\"line\"),z.append(\"g\").attr(\"class\",\"nv-barsWrap\"),z.append(\"g\").attr(\"class\",\"nv-legendWrap\"),B.attr(\"transform\",\"translate(\"+j.left+\",\"+j.top+\")\"),n?(h.width(u),B.select(\".nv-legendWrap\").datum(i).call(h),h.height()>j.top&&(j.top=h.height(),x=a.utils.availableHeight(l,m,j)),y.select(\".nv-legendWrap\").attr(\"transform\",\"translate(0,\"+-j.top+\")\")):B.select(\".nv-legendWrap\").selectAll(\"*\").remove(),q&&B.select(\".nv-y.nv-axis\").attr(\"transform\",\"translate(\"+u+\",0)\"),e.width(u).height(x);var C=B.select(\".nv-barsWrap\").datum(i.filter(function(a){return!a.disabled}));if(C.transition().call(e),A.append(\"clipPath\").attr(\"id\",\"nv-x-label-clip-\"+e.id()).append(\"rect\"),B.select(\"#nv-x-label-clip-\"+e.id()+\" rect\").attr(\"width\",c.rangeBand()*(r?2:1)).attr(\"height\",16).attr(\"x\",-c.rangeBand()/(r?1:2)),o){f.scale(c)._ticks(a.utils.calcTicksX(u/100,i)).tickSize(-x,0),B.select(\".nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+(d.range()[0]+(e.showValues()&&d.domain()[0]<0?16:0))+\")\"),B.select(\".nv-x.nv-axis\").call(f);var D=B.select(\".nv-x.nv-axis\").selectAll(\"g\");r&&D.selectAll(\"text\").attr(\"transform\",function(a,b,c){return\"translate(0,\"+(c%2==0?\"5\":\"17\")+\")\"}),t&&D.selectAll(\".tick text\").attr(\"transform\",\"rotate(\"+t+\" 0,0)\").style(\"text-anchor\",t>0?\"start\":\"end\"),s&&B.selectAll(\".tick text\").call(a.utils.wrapTicks,b.xAxis.rangeBand())}p&&(g.scale(d)._ticks(a.utils.calcTicksY(x/36,i)).tickSize(-u,0),B.select(\".nv-y.nv-axis\").call(g)),B.select(\".nv-zeroLine line\").attr(\"x1\",0).attr(\"x2\",q?-u:u).attr(\"y1\",d(0)).attr(\"y2\",d(0))}),x.renderEnd(\"discreteBar chart immediate\"),b}var c,d,e=a.models.discreteBar(),f=a.models.axis(),g=a.models.axis(),h=a.models.legend(),i=a.models.tooltip(),j={top:15,right:10,bottom:50,left:60},k=null,l=null,m=a.utils.getColor(),n=!1,o=!0,p=!0,q=!1,r=!1,s=!1,t=0,u=null,v=d3.dispatch(\"beforeUpdate\",\"renderEnd\"),w=250;f.orient(\"bottom\").showMaxMin(!1).tickFormat(function(a){return a}),g.orient(q?\"right\":\"left\").tickFormat(d3.format(\",.1f\")),i.duration(0).headerEnabled(!1).valueFormatter(function(a,b){return g.tickFormat()(a,b)}).keyFormatter(function(a,b){return f.tickFormat()(a,b)});var x=a.utils.renderWatch(v,w);return e.dispatch.on(\"elementMouseover.tooltip\",function(a){a.series={key:b.x()(a.data),value:b.y()(a.data),color:a.color},i.data(a).hidden(!1)}),e.dispatch.on(\"elementMouseout.tooltip\",function(a){i.hidden(!0)}),e.dispatch.on(\"elementMousemove.tooltip\",function(a){i()}),b.dispatch=v,b.discretebar=e,b.legend=h,b.xAxis=f,b.yAxis=g,b.tooltip=i,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return k},set:function(a){k=a}},height:{get:function(){return l},set:function(a){l=a}},showLegend:{get:function(){return n},set:function(a){n=a}},staggerLabels:{get:function(){return r},set:function(a){r=a}},rotateLabels:{get:function(){return t},set:function(a){t=a}},wrapLabels:{get:function(){return s},set:function(a){s=!!a}},showXAxis:{get:function(){return o},set:function(a){o=a}},showYAxis:{get:function(){return p},set:function(a){p=a}},noData:{get:function(){return u},set:function(a){u=a}},margin:{get:function(){return j},set:function(a){j.top=void 0!==a.top?a.top:j.top,j.right=void 0!==a.right?a.right:j.right,j.bottom=void 0!==a.bottom?a.bottom:j.bottom,j.left=void 0!==a.left?a.left:j.left}},duration:{get:function(){return w},set:function(a){w=a,x.reset(w),e.duration(w),f.duration(w),g.duration(w)}},color:{get:function(){return m},set:function(b){m=a.utils.getColor(b),e.color(m),h.color(m)}},rightAlignYAxis:{get:function(){return q},set:function(a){q=a,g.orient(a?\"right\":\"left\")}}}),a.utils.inheritOptions(b,e),a.utils.initOptions(b),b},a.models.distribution=function(){\"use strict\";function b(k){return m.reset(),k.each(function(b){var k=(e-(\"x\"===g?d.left+d.right:d.top+d.bottom),\"x\"==g?\"y\":\"x\"),l=d3.select(this);a.utils.initSVG(l),c=c||j;var n=l.selectAll(\"g.nv-distribution\").data([b]),o=n.enter().append(\"g\").attr(\"class\",\"nvd3 nv-distribution\"),p=(o.append(\"g\"),n.select(\"g\"));n.attr(\"transform\",\"translate(\"+d.left+\",\"+d.top+\")\");var q=p.selectAll(\"g.nv-dist\").data(function(a){return a},function(a){return a.key});q.enter().append(\"g\"),q.attr(\"class\",function(a,b){return\"nv-dist nv-series-\"+b}).style(\"stroke\",function(a,b){return i(a,b)});var r=q.selectAll(\"line.nv-dist\"+g).data(function(a){return a.values});r.enter().append(\"line\").attr(g+\"1\",function(a,b){return c(h(a,b))}).attr(g+\"2\",function(a,b){return c(h(a,b))}),m.transition(q.exit().selectAll(\"line.nv-dist\"+g),\"dist exit\").attr(g+\"1\",function(a,b){return j(h(a,b))}).attr(g+\"2\",function(a,b){return j(h(a,b))}).style(\"stroke-opacity\",0).remove(),r.attr(\"class\",function(a,b){return\"nv-dist\"+g+\" nv-dist\"+g+\"-\"+b}).attr(k+\"1\",0).attr(k+\"2\",f),m.transition(r,\"dist\").attr(g+\"1\",function(a,b){return j(h(a,b))}).attr(g+\"2\",function(a,b){return j(h(a,b))}),c=j.copy()}),m.renderEnd(\"distribution immediate\"),b}var c,d={top:0,right:0,bottom:0,left:0},e=400,f=8,g=\"x\",h=function(a){return a[g]},i=a.utils.defaultColor(),j=d3.scale.linear(),k=250,l=d3.dispatch(\"renderEnd\"),m=a.utils.renderWatch(l,k);return b.options=a.utils.optionsFunc.bind(b),b.dispatch=l,b.margin=function(a){return arguments.length?(d.top=\"undefined\"!=typeof a.top?a.top:d.top,d.right=\"undefined\"!=typeof a.right?a.right:d.right,d.bottom=\"undefined\"!=typeof a.bottom?a.bottom:d.bottom,d.left=\"undefined\"!=typeof a.left?a.left:d.left,b):d},b.width=function(a){return arguments.length?(e=a,b):e},b.axis=function(a){return arguments.length?(g=a,b):g},b.size=function(a){return arguments.length?(f=a,b):f},b.getData=function(a){return arguments.length?(h=d3.functor(a),b):h},b.scale=function(a){return arguments.length?(j=a,b):j},b.color=function(c){return arguments.length?(i=a.utils.getColor(c),b):i},b.duration=function(a){return arguments.length?(k=a,m.reset(k),b):k},b},a.models.focus=function(b){\"use strict\";function c(t){return s.reset(),s.models(b),m&&s.models(f),n&&s.models(g),t.each(function(s){function t(a){var b=+(\"e\"==a),c=b?1:-1,d=y/3;return\"M\"+.5*c+\",\"+d+\"A6,6 0 0 \"+b+\" \"+6.5*c+\",\"+(d+6)+\"V\"+(2*d-6)+\"A6,6 0 0 \"+b+\" \"+.5*c+\",\"+2*d+\"ZM\"+2.5*c+\",\"+(d+8)+\"V\"+(2*d-8)+\"M\"+4.5*c+\",\"+(d+8)+\"V\"+(2*d-8)}function u(){h.empty()||h.extent(p),D.data([h.empty()?d.domain():p]).each(function(a,b){var c=d(a[0])-d.range()[0],e=x-d(a[1]);d3.select(this).select(\".left\").attr(\"width\",0>c?0:c),d3.select(this).select(\".right\").attr(\"x\",d(a[1])).attr(\"width\",0>e?0:e)})}function v(){p=h.empty()?null:h.extent();var a=h.empty()?d.domain():h.extent();Math.abs(a[0]-a[1])<=1||(r.brush({extent:a,brush:h}),u(),r.onBrush(a))}var w=d3.select(this);a.utils.initSVG(w);var x=a.utils.availableWidth(k,w,i),y=l-i.top-i.bottom;c.update=function(){0===q?w.call(c):w.transition().duration(q).call(c)},c.container=this,d=b.xScale(),e=b.yScale();var z=w.selectAll(\"g.nv-focus\").data([s]),A=z.enter().append(\"g\").attr(\"class\",\"nvd3 nv-focus\").append(\"g\"),B=z.select(\"g\");z.attr(\"transform\",\"translate(\"+i.left+\",\"+i.top+\")\"),A.append(\"g\").attr(\"class\",\"nv-background\").append(\"rect\"),A.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),A.append(\"g\").attr(\"class\",\"nv-y nv-axis\"),A.append(\"g\").attr(\"class\",\"nv-contentWrap\"),A.append(\"g\").attr(\"class\",\"nv-brushBackground\"),A.append(\"g\").attr(\"class\",\"nv-x nv-brush\"),o&&B.select(\".nv-y.nv-axis\").attr(\"transform\",\"translate(\"+x+\",0)\"),B.select(\".nv-background rect\").attr(\"width\",x).attr(\"height\",y),b.width(x).height(y).color(s.map(function(a,b){return a.color||j(a,b)}).filter(function(a,b){return!s[b].disabled}));var C=B.select(\".nv-contentWrap\").datum(s.filter(function(a){return!a.disabled}));d3.transition(C).call(b),h.x(d).on(\"brush\",function(){v()}),p&&h.extent(p);var D=B.select(\".nv-brushBackground\").selectAll(\"g\").data([p||h.extent()]),E=D.enter().append(\"g\");E.append(\"rect\").attr(\"class\",\"left\").attr(\"x\",0).attr(\"y\",0).attr(\"height\",y),E.append(\"rect\").attr(\"class\",\"right\").attr(\"x\",0).attr(\"y\",0).attr(\"height\",y);var F=B.select(\".nv-x.nv-brush\").call(h);F.selectAll(\"rect\").attr(\"height\",y),F.selectAll(\".resize\").append(\"path\").attr(\"d\",t),v(),B.select(\".nv-background rect\").attr(\"width\",x).attr(\"height\",y),m&&(f.scale(d)._ticks(a.utils.calcTicksX(x/100,s)).tickSize(-y,0),B.select(\".nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+e.range()[0]+\")\"),d3.transition(B.select(\".nv-x.nv-axis\")).call(f)),n&&(g.scale(e)._ticks(a.utils.calcTicksY(y/36,s)).tickSize(-x,0),d3.transition(B.select(\".nv-y.nv-axis\")).call(g)),B.select(\".nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+e.range()[0]+\")\")}),s.renderEnd(\"focus immediate\"),c}var d,e,b=b||a.models.line(),f=a.models.axis(),g=a.models.axis(),h=d3.svg.brush(),i={top:10,right:0,bottom:30,left:0},j=a.utils.defaultColor(),k=null,l=70,m=!0,n=!1,o=!1,p=null,q=250,r=d3.dispatch(\"brush\",\"onBrush\",\"renderEnd\");b.interactive(!1),b.pointActive(function(a){return!1});var s=a.utils.renderWatch(r,q);return c.dispatch=r,c.content=b,c.brush=h,c.xAxis=f,c.yAxis=g,c.options=a.utils.optionsFunc.bind(c),c._options=Object.create({},{width:{get:function(){return k},set:function(a){k=a}},height:{get:function(){return l},set:function(a){l=a}},showXAxis:{get:function(){return m},set:function(a){m=a}},showYAxis:{get:function(){return n},set:function(a){n=a}},brushExtent:{get:function(){return p},set:function(a){p=a}},margin:{get:function(){return i},set:function(a){i.top=void 0!==a.top?a.top:i.top,i.right=void 0!==a.right?a.right:i.right,i.bottom=void 0!==a.bottom?a.bottom:i.bottom,i.left=void 0!==a.left?a.left:i.left}},duration:{get:function(){return q},set:function(a){q=a,s.reset(q),b.duration(q),f.duration(q),g.duration(q)}},color:{get:function(){return j},set:function(c){j=a.utils.getColor(c),b.color(j)}},interpolate:{get:function(){return b.interpolate()},set:function(a){b.interpolate(a)}},xTickFormat:{get:function(){return f.tickFormat()},set:function(a){f.tickFormat(a)}},yTickFormat:{get:function(){return g.tickFormat()},set:function(a){g.tickFormat(a)}},x:{get:function(){return b.x()},set:function(a){b.x(a)}},y:{get:function(){return b.y()},set:function(a){b.y(a)}},rightAlignYAxis:{get:function(){return o},set:function(a){o=a,g.orient(o?\"right\":\"left\")}}}),a.utils.inheritOptions(c,b),a.utils.initOptions(c),c},a.models.forceDirectedGraph=function(){\"use strict\";function b(g){return u.reset(),g.each(function(g){f=d3.select(this),a.utils.initSVG(f);var j=a.utils.availableWidth(d,f,c),u=a.utils.availableHeight(e,f,c);if(f.attr(\"width\",j).attr(\"height\",u),!(g&&g.links&&g.nodes))return a.utils.noData(b,f),b;f.selectAll(\".nv-noData\").remove(),f.selectAll(\"*\").remove();var v=new Set;g.nodes.forEach(function(a){var b=Object.keys(a);b.forEach(function(a){v.add(a)})});var w=d3.layout.force().nodes(g.nodes).links(g.links).size([j,u]).linkStrength(k).friction(l).linkDistance(m).charge(n).gravity(o).theta(p).alpha(q).start(),x=f.selectAll(\".link\").data(g.links).enter().append(\"line\").attr(\"class\",\"nv-force-link\").style(\"stroke-width\",function(a){return Math.sqrt(a.value)}),y=f.selectAll(\".node\").data(g.nodes).enter().append(\"g\").attr(\"class\",\"nv-force-node\").call(w.drag);y.append(\"circle\").attr(\"r\",r).style(\"fill\",function(a){return h(a)}).on(\"mouseover\",function(a){f.select(\".nv-series-\"+a.seriesIndex+\" .nv-distx-\"+a.pointIndex).attr(\"y1\",a.py),f.select(\".nv-series-\"+a.seriesIndex+\" .nv-disty-\"+a.pointIndex).attr(\"x2\",a.px);var b=h(a);a.series=[],v.forEach(function(c){a.series.push({color:b,key:c,value:a[c]})}),i.data(a).hidden(!1)}).on(\"mouseout\",function(a){i.hidden(!0)}),i.headerFormatter(function(a){return\"Node\"}),t(x),s(y),w.on(\"tick\",function(){x.attr(\"x1\",function(a){return a.source.x}).attr(\"y1\",function(a){return a.source.y}).attr(\"x2\",function(a){return a.target.x}).attr(\"y2\",function(a){return a.target.y}),y.attr(\"transform\",function(a){return\"translate(\"+a.x+\", \"+a.y+\")\"})})}),b}var c={top:2,right:0,bottom:2,left:0},d=400,e=32,f=null,g=d3.dispatch(\"renderEnd\"),h=a.utils.getColor([\"#000\"]),i=a.models.tooltip(),j=null,k=.1,l=.9,m=30,n=-120,o=.1,p=.8,q=.1,r=5,s=function(a){},t=function(a){},u=a.utils.renderWatch(g);return b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return d},set:function(a){d=a}},height:{get:function(){return e},set:function(a){e=a}},linkStrength:{get:function(){return k},set:function(a){k=a}},friction:{get:function(){return l},set:function(a){l=a}},linkDist:{get:function(){return m},set:function(a){m=a}},charge:{get:function(){return n},set:function(a){n=a}},gravity:{get:function(){return o},set:function(a){o=a}},theta:{get:function(){return p},set:function(a){p=a}},alpha:{get:function(){return q},set:function(a){q=a}},radius:{get:function(){return r},set:function(a){r=a}},x:{get:function(){return getX},set:function(a){getX=d3.functor(a)}},y:{get:function(){return getY},set:function(a){getY=d3.functor(a)}},margin:{get:function(){return c},set:function(a){c.top=void 0!==a.top?a.top:c.top,c.right=void 0!==a.right?a.right:c.right,c.bottom=void 0!==a.bottom?a.bottom:c.bottom,c.left=void 0!==a.left?a.left:c.left}},color:{get:function(){return h},set:function(b){h=a.utils.getColor(b)}},noData:{get:function(){return j},set:function(a){j=a}},nodeExtras:{get:function(){return s},set:function(a){s=a}},linkExtras:{get:function(){return t},set:function(a){t=a}}}),b.dispatch=g,b.tooltip=i,a.utils.initOptions(b),b},a.models.furiousLegend=function(){\"use strict\";function b(r){function s(a,b){return\"furious\"!=q?\"#000\":o?a.disengaged?h(a,b):\"#fff\":o?void 0:a.disabled?h(a,b):\"#fff\"}function t(a,b){return o&&\"furious\"==q?a.disengaged?\"#fff\":h(a,b):a.disabled?\"#fff\":h(a,b)}return r.each(function(b){var r=d-c.left-c.right,u=d3.select(this);a.utils.initSVG(u);var v=u.selectAll(\"g.nv-legend\").data([b]),w=(v.enter().append(\"g\").attr(\"class\",\"nvd3 nv-legend\").append(\"g\"),v.select(\"g\"));v.attr(\"transform\",\"translate(\"+c.left+\",\"+c.top+\")\");var x,y=w.selectAll(\".nv-series\").data(function(a){return\"furious\"!=q?a:a.filter(function(a){return o?!0:!a.disengaged})}),z=y.enter().append(\"g\").attr(\"class\",\"nv-series\");if(\"classic\"==q)z.append(\"circle\").style(\"stroke-width\",2).attr(\"class\",\"nv-legend-symbol\").attr(\"r\",5),x=y.select(\"circle\");else if(\"furious\"==q){z.append(\"rect\").style(\"stroke-width\",2).attr(\"class\",\"nv-legend-symbol\").attr(\"rx\",3).attr(\"ry\",3),x=y.select(\"rect\"),z.append(\"g\").attr(\"class\",\"nv-check-box\").property(\"innerHTML\",'<path d=\"M0.5,5 L22.5,5 L22.5,26.5 L0.5,26.5 L0.5,5 Z\" class=\"nv-box\"></path><path d=\"M5.5,12.8618467 L11.9185089,19.2803556 L31,0.198864511\" class=\"nv-check\"></path>').attr(\"transform\",\"translate(-10,-8)scale(0.5)\");var A=y.select(\".nv-check-box\");A.each(function(a,b){d3.select(this).selectAll(\"path\").attr(\"stroke\",s(a,b))})}z.append(\"text\").attr(\"text-anchor\",\"start\").attr(\"class\",\"nv-legend-text\").attr(\"dy\",\".32em\").attr(\"dx\",\"8\");var B=y.select(\"text.nv-legend-text\");y.on(\"mouseover\",function(a,b){p.legendMouseover(a,b)}).on(\"mouseout\",function(a,b){p.legendMouseout(a,b)}).on(\"click\",function(a,b){p.legendClick(a,b);var c=y.data();if(m){if(\"classic\"==q)n?(c.forEach(function(a){a.disabled=!0}),a.disabled=!1):(a.disabled=!a.disabled,c.every(function(a){return a.disabled})&&c.forEach(function(a){a.disabled=!1}));else if(\"furious\"==q)if(o)a.disengaged=!a.disengaged,a.userDisabled=void 0==a.userDisabled?!!a.disabled:a.userDisabled,a.disabled=a.disengaged||a.userDisabled;else if(!o){a.disabled=!a.disabled,a.userDisabled=a.disabled;var d=c.filter(function(a){return!a.disengaged});d.every(function(a){return a.userDisabled})&&c.forEach(function(a){a.disabled=a.userDisabled=!1})}p.stateChange({disabled:c.map(function(a){return!!a.disabled}),disengaged:c.map(function(a){return!!a.disengaged})})}}).on(\"dblclick\",function(a,b){if((\"furious\"!=q||!o)&&(p.legendDblclick(a,b),m)){var c=y.data();c.forEach(function(a){a.disabled=!0,\"furious\"==q&&(a.userDisabled=a.disabled)}),a.disabled=!1,\"furious\"==q&&(a.userDisabled=a.disabled),p.stateChange({disabled:c.map(function(a){return!!a.disabled})})}}),y.classed(\"nv-disabled\",function(a){return a.userDisabled}),y.exit().remove(),B.attr(\"fill\",s).text(function(a){return g(f(a))});var C;switch(q){case\"furious\":C=23;break;case\"classic\":C=20}if(j){var D=[];y.each(function(b,c){var d;if(g(f(b))&&g(f(b)).length>i){var e=g(f(b)).substring(0,i);d=d3.select(this).select(\"text\").text(e+\"...\"),d3.select(this).append(\"svg:title\").text(g(f(b)))}else d=d3.select(this).select(\"text\");var h;try{if(h=d.node().getComputedTextLength(),0>=h)throw Error()}catch(j){h=a.utils.calcApproxTextWidth(d)}D.push(h+k)});for(var E=0,F=0,G=[];r>F&&E<D.length;)G[E]=D[E],F+=D[E++];for(0===E&&(E=1);F>r&&E>1;){G=[],E--;for(var H=0;H<D.length;H++)D[H]>(G[H%E]||0)&&(G[H%E]=D[H]);F=G.reduce(function(a,b,c,d){return a+b})}for(var I=[],J=0,K=0;E>J;J++)I[J]=K,K+=G[J];y.attr(\"transform\",function(a,b){return\"translate(\"+I[b%E]+\",\"+(5+Math.floor(b/E)*C)+\")\"}),l?w.attr(\"transform\",\"translate(\"+(d-c.right-F)+\",\"+c.top+\")\"):w.attr(\"transform\",\"translate(0,\"+c.top+\")\"),e=c.top+c.bottom+Math.ceil(D.length/E)*C}else{var L,M=5,N=5,O=0;y.attr(\"transform\",function(a,b){var e=d3.select(this).select(\"text\").node().getComputedTextLength()+k;return L=N,d<c.left+c.right+L+e&&(N=L=5,M+=C),N+=e,N>O&&(O=N),\"translate(\"+L+\",\"+M+\")\"}),w.attr(\"transform\",\"translate(\"+(d-c.right-O)+\",\"+c.top+\")\"),e=c.top+c.bottom+M+15}\"furious\"==q&&x.attr(\"width\",function(a,b){return B[0][b].getComputedTextLength()+27}).attr(\"height\",18).attr(\"y\",-9).attr(\"x\",-15),x.style(\"fill\",t).style(\"stroke\",function(a,b){return a.color||h(a,b)})}),b}var c={top:5,right:0,bottom:5,left:0},d=400,e=20,f=function(a){return a.key},g=function(a){return a},h=a.utils.getColor(),i=20,j=!0,k=28,l=!0,m=!0,n=!1,o=!1,p=d3.dispatch(\"legendClick\",\"legendDblclick\",\"legendMouseover\",\"legendMouseout\",\"stateChange\"),q=\"classic\";return b.dispatch=p,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return d},set:function(a){d=a}},height:{get:function(){return e},set:function(a){e=a}},key:{get:function(){return f},set:function(a){f=a}},keyFormatter:{get:function(){return g},set:function(a){g=a}},align:{get:function(){return j},set:function(a){j=a}},rightAlign:{get:function(){return l},set:function(a){l=a}},maxKeyLength:{get:function(){return i},set:function(a){i=a}},padding:{get:function(){return k},set:function(a){k=a}},updateState:{get:function(){return m},set:function(a){m=a}},radioButtonMode:{get:function(){return n},set:function(a){n=a}},expanded:{get:function(){return o},set:function(a){o=a}},vers:{get:function(){return q},set:function(a){q=a}},margin:{get:function(){return c},set:function(a){c.top=void 0!==a.top?a.top:c.top,c.right=void 0!==a.right?a.right:c.right,c.bottom=void 0!==a.bottom?a.bottom:c.bottom,c.left=void 0!==a.left?a.left:c.left}},color:{get:function(){return h},set:function(b){h=a.utils.getColor(b)}}}),a.utils.initOptions(b),b},a.models.historicalBar=function(){\"use strict\";function b(x){return x.each(function(b){w.reset(),k=d3.select(this);var x=a.utils.availableWidth(h,k,g),y=a.utils.availableHeight(i,k,g);a.utils.initSVG(k),l.domain(c||d3.extent(b[0].values.map(n).concat(p))),r?l.range(e||[.5*x/b[0].values.length,x*(b[0].values.length-.5)/b[0].values.length]):l.range(e||[0,x]),m.domain(d||d3.extent(b[0].values.map(o).concat(q))).range(f||[y,0]),l.domain()[0]===l.domain()[1]&&(l.domain()[0]?l.domain([l.domain()[0]-.01*l.domain()[0],l.domain()[1]+.01*l.domain()[1]]):l.domain([-1,1])),m.domain()[0]===m.domain()[1]&&(m.domain()[0]?m.domain([m.domain()[0]+.01*m.domain()[0],m.domain()[1]-.01*m.domain()[1]]):m.domain([-1,1]));var z=k.selectAll(\"g.nv-wrap.nv-historicalBar-\"+j).data([b[0].values]),A=z.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-historicalBar-\"+j),B=A.append(\"defs\"),C=A.append(\"g\"),D=z.select(\"g\");C.append(\"g\").attr(\"class\",\"nv-bars\"),z.attr(\"transform\",\"translate(\"+g.left+\",\"+g.top+\")\"),k.on(\"click\",function(a,b){u.chartClick({data:a,index:b,pos:d3.event,id:j})}),B.append(\"clipPath\").attr(\"id\",\"nv-chart-clip-path-\"+j).append(\"rect\"),z.select(\"#nv-chart-clip-path-\"+j+\" rect\").attr(\"width\",x).attr(\"height\",y),D.attr(\"clip-path\",s?\"url(#nv-chart-clip-path-\"+j+\")\":\"\");var E=z.select(\".nv-bars\").selectAll(\".nv-bar\").data(function(a){return a},function(a,b){return n(a,b)});E.exit().remove(),E.enter().append(\"rect\").attr(\"x\",0).attr(\"y\",function(b,c){return a.utils.NaNtoZero(m(Math.max(0,o(b,c))))}).attr(\"height\",function(b,c){return a.utils.NaNtoZero(Math.abs(m(o(b,c))-m(0)))}).attr(\"transform\",function(a,c){return\"translate(\"+(l(n(a,c))-x/b[0].values.length*.45)+\",0)\"}).on(\"mouseover\",function(a,b){v&&(d3.select(this).classed(\"hover\",!0),u.elementMouseover({data:a,index:b,color:d3.select(this).style(\"fill\")}))}).on(\"mouseout\",function(a,b){v&&(d3.select(this).classed(\"hover\",!1),u.elementMouseout({data:a,index:b,color:d3.select(this).style(\"fill\")}))}).on(\"mousemove\",function(a,b){v&&u.elementMousemove({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"click\",function(a,b){v&&(u.elementClick({data:a,index:b,color:d3.select(this).style(\"fill\")}),d3.event.stopPropagation())}).on(\"dblclick\",function(a,b){v&&(u.elementDblClick({data:a,index:b,color:d3.select(this).style(\"fill\")}),d3.event.stopPropagation())}),E.attr(\"fill\",function(a,b){return t(a,b)}).attr(\"class\",function(a,b,c){return(o(a,b)<0?\"nv-bar negative\":\"nv-bar positive\")+\" nv-bar-\"+c+\"-\"+b}).watchTransition(w,\"bars\").attr(\"transform\",function(a,c){return\"translate(\"+(l(n(a,c))-x/b[0].values.length*.45)+\",0)\"}).attr(\"width\",x/b[0].values.length*.9),E.watchTransition(w,\"bars\").attr(\"y\",function(b,c){var d=o(b,c)<0?m(0):m(0)-m(o(b,c))<1?m(0)-1:m(o(b,c));return a.utils.NaNtoZero(d)}).attr(\"height\",function(b,c){return a.utils.NaNtoZero(Math.max(Math.abs(m(o(b,c))-m(0)),1))})}),w.renderEnd(\"historicalBar immediate\"),b}var c,d,e,f,g={top:0,right:0,bottom:0,left:0},h=null,i=null,j=Math.floor(1e4*Math.random()),k=null,l=d3.scale.linear(),m=d3.scale.linear(),n=function(a){return a.x},o=function(a){return a.y},p=[],q=[0],r=!1,s=!0,t=a.utils.defaultColor(),u=d3.dispatch(\"chartClick\",\"elementClick\",\"elementDblClick\",\"elementMouseover\",\"elementMouseout\",\"elementMousemove\",\"renderEnd\"),v=!0,w=a.utils.renderWatch(u,0);return b.highlightPoint=function(a,b){k.select(\".nv-bars .nv-bar-0-\"+a).classed(\"hover\",b)},b.clearHighlights=function(){k.select(\".nv-bars .nv-bar.hover\").classed(\"hover\",!1)},b.dispatch=u,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return h},set:function(a){h=a}},height:{get:function(){return i},set:function(a){i=a}},forceX:{get:function(){return p},set:function(a){p=a}},forceY:{get:function(){return q},set:function(a){q=a}},padData:{get:function(){return r},set:function(a){r=a}},x:{get:function(){return n},set:function(a){n=a}},y:{get:function(){return o},set:function(a){o=a}},xScale:{get:function(){return l},set:function(a){l=a}},yScale:{get:function(){return m},set:function(a){m=a}},xDomain:{get:function(){return c},set:function(a){c=a}},yDomain:{get:function(){return d},set:function(a){d=a}},xRange:{get:function(){return e},set:function(a){e=a}},yRange:{get:function(){return f},set:function(a){f=a}},clipEdge:{get:function(){return s},set:function(a){s=a}},id:{get:function(){return j},set:function(a){j=a}},interactive:{get:function(){return v},set:function(a){v=a}},margin:{get:function(){return g},set:function(a){g.top=void 0!==a.top?a.top:g.top,g.right=void 0!==a.right?a.right:g.right,g.bottom=void 0!==a.bottom?a.bottom:g.bottom,g.left=void 0!==a.left?a.left:g.left}},color:{get:function(){return t},set:function(b){t=a.utils.getColor(b)}}}),a.utils.initOptions(b),b},a.models.historicalBarChart=function(b){\"use strict\";function c(b){return b.each(function(k){z.reset(),z.models(f),q&&z.models(g),r&&z.models(h);var w=d3.select(this);a.utils.initSVG(w);var A=a.utils.availableWidth(n,w,l),B=a.utils.availableHeight(o,w,l);if(c.update=function(){w.transition().duration(y).call(c)},c.container=this,u.disabled=k.map(function(a){return!!a.disabled}),!v){var C;v={};for(C in u)u[C]instanceof Array?v[C]=u[C].slice(0):v[C]=u[C]}if(!(k&&k.length&&k.filter(function(a){return a.values.length}).length))return a.utils.noData(c,w),c;w.selectAll(\".nv-noData\").remove(),d=f.xScale(),e=f.yScale();var D=w.selectAll(\"g.nv-wrap.nv-historicalBarChart\").data([k]),E=D.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-historicalBarChart\").append(\"g\"),F=D.select(\"g\");E.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),E.append(\"g\").attr(\"class\",\"nv-y nv-axis\"),E.append(\"g\").attr(\"class\",\"nv-barsWrap\"),E.append(\"g\").attr(\"class\",\"nv-legendWrap\"),E.append(\"g\").attr(\"class\",\"nv-interactive\"),p?(i.width(A),F.select(\".nv-legendWrap\").datum(k).call(i),i.height()>l.top&&(l.top=i.height(),B=a.utils.availableHeight(o,w,l)),D.select(\".nv-legendWrap\").attr(\"transform\",\"translate(0,\"+-l.top+\")\")):F.select(\".nv-legendWrap\").selectAll(\"*\").remove(),D.attr(\"transform\",\"translate(\"+l.left+\",\"+l.top+\")\"),s&&F.select(\".nv-y.nv-axis\").attr(\"transform\",\"translate(\"+A+\",0)\"),t&&(j.width(A).height(B).margin({left:l.left,top:l.top}).svgContainer(w).xScale(d),D.select(\".nv-interactive\").call(j)),f.width(A).height(B).color(k.map(function(a,b){return a.color||m(a,b)}).filter(function(a,b){return!k[b].disabled}));var G=F.select(\".nv-barsWrap\").datum(k.filter(function(a){return!a.disabled}));G.transition().call(f),q&&(g.scale(d)._ticks(a.utils.calcTicksX(A/100,k)).tickSize(-B,0),F.select(\".nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+e.range()[0]+\")\"),F.select(\".nv-x.nv-axis\").transition().call(g)),r&&(h.scale(e)._ticks(a.utils.calcTicksY(B/36,k)).tickSize(-A,0),F.select(\".nv-y.nv-axis\").transition().call(h)),j.dispatch.on(\"elementMousemove\",function(b){f.clearHighlights();var d,e,i,l=[];k.filter(function(a,b){return a.seriesIndex=b,!a.disabled}).forEach(function(g,h){e=a.interactiveBisect(g.values,b.pointXValue,c.x()),f.highlightPoint(e,!0);var j=g.values[e];void 0!==j&&(void 0===d&&(d=j),void 0===i&&(i=c.xScale()(c.x()(j,e))),l.push({key:g.key,value:c.y()(j,e),color:m(g,g.seriesIndex),data:g.values[e]}))});var n=g.tickFormat()(c.x()(d,e));j.tooltip.valueFormatter(function(a,b){return h.tickFormat()(a)}).data({value:n,index:e,series:l})(),j.renderGuideLine(i)}),j.dispatch.on(\"elementMouseout\",function(a){x.tooltipHide(),f.clearHighlights()}),i.dispatch.on(\"legendClick\",function(a,d){a.disabled=!a.disabled,k.filter(function(a){return!a.disabled}).length||k.map(function(a){return a.disabled=!1,D.selectAll(\".nv-series\").classed(\"disabled\",!1),a}),u.disabled=k.map(function(a){return!!a.disabled}),x.stateChange(u),b.transition().call(c)}),i.dispatch.on(\"legendDblclick\",function(a){k.forEach(function(a){a.disabled=!0}),a.disabled=!1,u.disabled=k.map(function(a){return!!a.disabled}),x.stateChange(u),c.update()}),x.on(\"changeState\",function(a){\"undefined\"!=typeof a.disabled&&(k.forEach(function(b,c){b.disabled=a.disabled[c]}),u.disabled=a.disabled),c.update()})}),z.renderEnd(\"historicalBarChart immediate\"),c}var d,e,f=b||a.models.historicalBar(),g=a.models.axis(),h=a.models.axis(),i=a.models.legend(),j=a.interactiveGuideline(),k=a.models.tooltip(),l={top:30,right:90,bottom:50,left:90},m=a.utils.defaultColor(),n=null,o=null,p=!1,q=!0,r=!0,s=!1,t=!1,u={},v=null,w=null,x=d3.dispatch(\"tooltipHide\",\"stateChange\",\"changeState\",\"renderEnd\"),y=250;g.orient(\"bottom\").tickPadding(7),h.orient(s?\"right\":\"left\"),k.duration(0).headerEnabled(!1).valueFormatter(function(a,b){return h.tickFormat()(a,b)}).headerFormatter(function(a,b){return g.tickFormat()(a,b)});var z=a.utils.renderWatch(x,0);return f.dispatch.on(\"elementMouseover.tooltip\",function(a){a.series={key:c.x()(a.data),value:c.y()(a.data),color:a.color},k.data(a).hidden(!1)}),f.dispatch.on(\"elementMouseout.tooltip\",function(a){k.hidden(!0)}),f.dispatch.on(\"elementMousemove.tooltip\",function(a){k()}),c.dispatch=x,c.bars=f,c.legend=i,c.xAxis=g,c.yAxis=h,c.interactiveLayer=j,c.tooltip=k,c.options=a.utils.optionsFunc.bind(c),c._options=Object.create({},{width:{get:function(){return n},set:function(a){n=a}},height:{get:function(){return o},set:function(a){o=a}},showLegend:{get:function(){return p},set:function(a){p=a}},showXAxis:{get:function(){return q},set:function(a){q=a}},showYAxis:{get:function(){return r},set:function(a){r=a}},defaultState:{get:function(){return v},set:function(a){v=a}},noData:{get:function(){return w},set:function(a){w=a}},margin:{get:function(){return l},set:function(a){l.top=void 0!==a.top?a.top:l.top,l.right=void 0!==a.right?a.right:l.right,l.bottom=void 0!==a.bottom?a.bottom:l.bottom,l.left=void 0!==a.left?a.left:l.left}},color:{get:function(){return m},set:function(b){m=a.utils.getColor(b),i.color(m),f.color(m)}},duration:{get:function(){return y},set:function(a){y=a,z.reset(y),h.duration(y),g.duration(y)}},rightAlignYAxis:{get:function(){return s},set:function(a){s=a,h.orient(a?\"right\":\"left\")}},useInteractiveGuideline:{get:function(){return t},set:function(a){t=a,a===!0&&c.interactive(!1)}}}),a.utils.inheritOptions(c,f),a.utils.initOptions(c),c},a.models.ohlcBarChart=function(){var b=a.models.historicalBarChart(a.models.ohlcBar());return b.useInteractiveGuideline(!0),b.interactiveLayer.tooltip.contentGenerator(function(a){var c=a.series[0].data,d=c.open<c.close?\"2ca02c\":\"d62728\";return'<h3 style=\"color: #'+d+'\">'+a.value+\"</h3><table><tr><td>open:</td><td>\"+b.yAxis.tickFormat()(c.open)+\"</td></tr><tr><td>close:</td><td>\"+b.yAxis.tickFormat()(c.close)+\"</td></tr><tr><td>high</td><td>\"+b.yAxis.tickFormat()(c.high)+\"</td></tr><tr><td>low:</td><td>\"+b.yAxis.tickFormat()(c.low)+\"</td></tr></table>\"}),b},a.models.candlestickBarChart=function(){var b=a.models.historicalBarChart(a.models.candlestickBar());return b.useInteractiveGuideline(!0),b.interactiveLayer.tooltip.contentGenerator(function(a){var c=a.series[0].data,d=c.open<c.close?\"2ca02c\":\"d62728\";return'<h3 style=\"color: #'+d+'\">'+a.value+\"</h3><table><tr><td>open:</td><td>\"+b.yAxis.tickFormat()(c.open)+\"</td></tr><tr><td>close:</td><td>\"+b.yAxis.tickFormat()(c.close)+\"</td></tr><tr><td>high</td><td>\"+b.yAxis.tickFormat()(c.high)+\"</td></tr><tr><td>low:</td><td>\"+b.yAxis.tickFormat()(c.low)+\"</td></tr></table>\"}),b},a.models.legend=function(){\"use strict\";function b(r){function s(a,b){return\"furious\"!=q?\"#000\":o?a.disengaged?\"#000\":\"#fff\":o?void 0:(a.color||(a.color=h(a,b)),a.disabled?a.color:\"#fff\")}function t(a,b){return o&&\"furious\"==q&&a.disengaged?\"#eee\":a.color||h(a,b)}function u(a,b){return o&&\"furious\"==q?1:a.disabled?0:1}return r.each(function(b){var h=d-c.left-c.right,r=d3.select(this);a.utils.initSVG(r);var v=r.selectAll(\"g.nv-legend\").data([b]),w=v.enter().append(\"g\").attr(\"class\",\"nvd3 nv-legend\").append(\"g\"),x=v.select(\"g\");v.attr(\"transform\",\"translate(\"+c.left+\",\"+c.top+\")\");var y,z,A=x.selectAll(\".nv-series\").data(function(a){return\"furious\"!=q?a:a.filter(function(a){return o?!0:!a.disengaged})}),B=A.enter().append(\"g\").attr(\"class\",\"nv-series\");switch(q){case\"furious\":z=23;break;case\"classic\":z=20}if(\"classic\"==q)B.append(\"circle\").style(\"stroke-width\",2).attr(\"class\",\"nv-legend-symbol\").attr(\"r\",5),y=A.select(\".nv-legend-symbol\");else if(\"furious\"==q){B.append(\"rect\").style(\"stroke-width\",2).attr(\"class\",\"nv-legend-symbol\").attr(\"rx\",3).attr(\"ry\",3),y=A.select(\".nv-legend-symbol\"),B.append(\"g\").attr(\"class\",\"nv-check-box\").property(\"innerHTML\",'<path d=\"M0.5,5 L22.5,5 L22.5,26.5 L0.5,26.5 L0.5,5 Z\" class=\"nv-box\"></path><path d=\"M5.5,12.8618467 L11.9185089,19.2803556 L31,0.198864511\" class=\"nv-check\"></path>').attr(\"transform\",\"translate(-10,-8)scale(0.5)\");var C=A.select(\".nv-check-box\");C.each(function(a,b){d3.select(this).selectAll(\"path\").attr(\"stroke\",s(a,b))})}B.append(\"text\").attr(\"text-anchor\",\"start\").attr(\"class\",\"nv-legend-text\").attr(\"dy\",\".32em\").attr(\"dx\",\"8\");var D=A.select(\"text.nv-legend-text\");A.on(\"mouseover\",function(a,b){p.legendMouseover(a,b)}).on(\"mouseout\",function(a,b){p.legendMouseout(a,b)}).on(\"click\",function(a,b){p.legendClick(a,b);var c=A.data();if(m){if(\"classic\"==q)n?(c.forEach(function(a){a.disabled=!0}),a.disabled=!1):(a.disabled=!a.disabled,c.every(function(a){return a.disabled})&&c.forEach(function(a){a.disabled=!1}));else if(\"furious\"==q)if(o)a.disengaged=!a.disengaged,a.userDisabled=void 0==a.userDisabled?!!a.disabled:a.userDisabled,a.disabled=a.disengaged||a.userDisabled;else if(!o){a.disabled=!a.disabled,a.userDisabled=a.disabled;var d=c.filter(function(a){return!a.disengaged});d.every(function(a){return a.userDisabled})&&c.forEach(function(a){a.disabled=a.userDisabled=!1})}p.stateChange({disabled:c.map(function(a){return!!a.disabled}),disengaged:c.map(function(a){return!!a.disengaged})})}}).on(\"dblclick\",function(a,b){if((\"furious\"!=q||!o)&&(p.legendDblclick(a,b),m)){var c=A.data();c.forEach(function(a){a.disabled=!0,\"furious\"==q&&(a.userDisabled=a.disabled)}),a.disabled=!1,\"furious\"==q&&(a.userDisabled=a.disabled),p.stateChange({disabled:c.map(function(a){return!!a.disabled})})}}),A.classed(\"nv-disabled\",function(a){return a.userDisabled}),A.exit().remove(),D.attr(\"fill\",s).text(function(a){return g(f(a))});var E=0;if(j){var F=[];A.each(function(b,c){var d;if(g(f(b))&&g(f(b)).length>i){var e=g(f(b)).substring(0,i);d=d3.select(this).select(\"text\").text(e+\"...\"),d3.select(this).append(\"svg:title\").text(g(f(b)))}else d=d3.select(this).select(\"text\");var h;try{if(h=d.node().getComputedTextLength(),0>=h)throw Error()}catch(j){h=a.utils.calcApproxTextWidth(d)}F.push(h+k)});var G=0,H=[];for(E=0;h>E&&G<F.length;)H[G]=F[G],E+=F[G++];for(0===G&&(G=1);E>h&&G>1;){H=[],G--;for(var I=0;I<F.length;I++)F[I]>(H[I%G]||0)&&(H[I%G]=F[I]);E=H.reduce(function(a,b,c,d){return a+b})}for(var J=[],K=0,L=0;G>K;K++)J[K]=L,L+=H[K];A.attr(\"transform\",function(a,b){return\"translate(\"+J[b%G]+\",\"+(5+Math.floor(b/G)*z)+\")\"}),l?x.attr(\"transform\",\"translate(\"+(d-c.right-E)+\",\"+c.top+\")\"):x.attr(\"transform\",\"translate(0,\"+c.top+\")\"),e=c.top+c.bottom+Math.ceil(F.length/G)*z}else{var M,N=5,O=5,P=0;A.attr(\"transform\",function(a,b){var e=d3.select(this).select(\"text\").node().getComputedTextLength()+k;return M=O,d<c.left+c.right+M+e&&(O=M=5,N+=z),O+=e,O>P&&(P=O),M+P>E&&(E=M+P),\"translate(\"+M+\",\"+N+\")\"}),x.attr(\"transform\",\"translate(\"+(d-c.right-P)+\",\"+c.top+\")\"),e=c.top+c.bottom+N+15}if(\"furious\"==q){y.attr(\"width\",function(a,b){return D[0][b].getComputedTextLength()+27}).attr(\"height\",18).attr(\"y\",-9).attr(\"x\",-15),w.insert(\"rect\",\":first-child\").attr(\"class\",\"nv-legend-bg\").attr(\"fill\",\"#eee\").attr(\"opacity\",0);var Q=x.select(\".nv-legend-bg\");Q.transition().duration(300).attr(\"x\",-z).attr(\"width\",E+z-12).attr(\"height\",e+10).attr(\"y\",-c.top-10).attr(\"opacity\",o?1:0)}y.style(\"fill\",t).style(\"fill-opacity\",u).style(\"stroke\",t)}),b}var c={top:5,right:0,bottom:5,left:0},d=400,e=20,f=function(a){return a.key},g=function(a){return a},h=a.utils.getColor(),i=20,j=!0,k=32,l=!0,m=!0,n=!1,o=!1,p=d3.dispatch(\"legendClick\",\"legendDblclick\",\"legendMouseover\",\"legendMouseout\",\"stateChange\"),q=\"classic\";return b.dispatch=p,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return d},set:function(a){d=a}},height:{get:function(){return e},set:function(a){e=a}},key:{get:function(){return f},set:function(a){f=a}},keyFormatter:{get:function(){return g},set:function(a){g=a}},align:{get:function(){return j},set:function(a){j=a}},maxKeyLength:{get:function(){return i},set:function(a){i=a}},rightAlign:{get:function(){return l},set:function(a){l=a}},padding:{get:function(){return k},set:function(a){k=a}},updateState:{get:function(){return m},set:function(a){m=a}},radioButtonMode:{get:function(){return n},set:function(a){n=a}},expanded:{get:function(){return o},set:function(a){o=a}},vers:{get:function(){return q},set:function(a){q=a}},margin:{get:function(){return c},set:function(a){c.top=void 0!==a.top?a.top:c.top,c.right=void 0!==a.right?a.right:c.right,c.bottom=void 0!==a.bottom?a.bottom:c.bottom,c.left=void 0!==a.left?a.left:c.left}},color:{get:function(){return h},set:function(b){h=a.utils.getColor(b)}}}),a.utils.initOptions(b),b},a.models.line=function(){\"use strict\";function b(r){return v.reset(),v.models(e),r.each(function(b){i=d3.select(this);var r=a.utils.availableWidth(g,i,f),s=a.utils.availableHeight(h,i,f);a.utils.initSVG(i),c=e.xScale(),d=e.yScale(),t=t||c,u=u||d;var w=i.selectAll(\"g.nv-wrap.nv-line\").data([b]),x=w.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-line\"),y=x.append(\"defs\"),z=x.append(\"g\"),A=w.select(\"g\");z.append(\"g\").attr(\"class\",\"nv-groups\"),z.append(\"g\").attr(\"class\",\"nv-scatterWrap\"),w.attr(\"transform\",\"translate(\"+f.left+\",\"+f.top+\")\"),e.width(r).height(s);var B=w.select(\".nv-scatterWrap\");B.call(e),y.append(\"clipPath\").attr(\"id\",\"nv-edge-clip-\"+e.id()).append(\"rect\"),w.select(\"#nv-edge-clip-\"+e.id()+\" rect\").attr(\"width\",r).attr(\"height\",s>0?s:0),A.attr(\"clip-path\",p?\"url(#nv-edge-clip-\"+e.id()+\")\":\"\"),B.attr(\"clip-path\",p?\"url(#nv-edge-clip-\"+e.id()+\")\":\"\");var C=w.select(\".nv-groups\").selectAll(\".nv-group\").data(function(a){return a},function(a){return a.key});C.enter().append(\"g\").style(\"stroke-opacity\",1e-6).style(\"stroke-width\",function(a){return a.strokeWidth||j}).style(\"fill-opacity\",1e-6),C.exit().remove(),C.attr(\"class\",function(a,b){return(a.classed||\"\")+\" nv-group nv-series-\"+b}).classed(\"hover\",function(a){return a.hover}).style(\"fill\",function(a,b){return k(a,b)}).style(\"stroke\",function(a,b){return k(a,b)}),C.watchTransition(v,\"line: groups\").style(\"stroke-opacity\",1).style(\"fill-opacity\",function(a){return a.fillOpacity||.5});var D=C.selectAll(\"path.nv-area\").data(function(a){return o(a)?[a]:[]});D.enter().append(\"path\").attr(\"class\",\"nv-area\").attr(\"d\",function(b){return d3.svg.area().interpolate(q).defined(n).x(function(b,c){return a.utils.NaNtoZero(t(l(b,c)))}).y0(function(b,c){return a.utils.NaNtoZero(u(m(b,c)))}).y1(function(a,b){return u(d.domain()[0]<=0?d.domain()[1]>=0?0:d.domain()[1]:d.domain()[0])}).apply(this,[b.values])}),C.exit().selectAll(\"path.nv-area\").remove(),D.watchTransition(v,\"line: areaPaths\").attr(\"d\",function(b){return d3.svg.area().interpolate(q).defined(n).x(function(b,d){return a.utils.NaNtoZero(c(l(b,d)))}).y0(function(b,c){return a.utils.NaNtoZero(d(m(b,c)))}).y1(function(a,b){return d(d.domain()[0]<=0?d.domain()[1]>=0?0:d.domain()[1]:d.domain()[0])}).apply(this,[b.values])});var E=C.selectAll(\"path.nv-line\").data(function(a){return[a.values]});E.enter().append(\"path\").attr(\"class\",\"nv-line\").attr(\"d\",d3.svg.line().interpolate(q).defined(n).x(function(b,c){return a.utils.NaNtoZero(t(l(b,c)))}).y(function(b,c){return a.utils.NaNtoZero(u(m(b,c)))})),E.watchTransition(v,\"line: linePaths\").attr(\"d\",d3.svg.line().interpolate(q).defined(n).x(function(b,d){return a.utils.NaNtoZero(c(l(b,d)))}).y(function(b,c){return a.utils.NaNtoZero(d(m(b,c)))})),t=c.copy(),u=d.copy()}),v.renderEnd(\"line immediate\"),b}var c,d,e=a.models.scatter(),f={top:0,right:0,bottom:0,left:0},g=960,h=500,i=null,j=1.5,k=a.utils.defaultColor(),l=function(a){return a.x},m=function(a){return a.y},n=function(a,b){return!isNaN(m(a,b))&&null!==m(a,b)},o=function(a){return a.area},p=!1,q=\"linear\",r=250,s=d3.dispatch(\"elementClick\",\"elementMouseover\",\"elementMouseout\",\"renderEnd\");e.pointSize(16).pointDomain([16,256]);var t,u,v=a.utils.renderWatch(s,r);return b.dispatch=s,b.scatter=e,e.dispatch.on(\"elementClick\",function(){s.elementClick.apply(this,arguments)}),e.dispatch.on(\"elementMouseover\",function(){s.elementMouseover.apply(this,arguments)}),e.dispatch.on(\"elementMouseout\",function(){s.elementMouseout.apply(this,arguments)}),b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return g},set:function(a){g=a}},height:{get:function(){return h},set:function(a){h=a}},defined:{get:function(){return n},set:function(a){n=a}},interpolate:{get:function(){return q},set:function(a){q=a}},clipEdge:{get:function(){return p},set:function(a){p=a}},margin:{get:function(){return f},set:function(a){f.top=void 0!==a.top?a.top:f.top,f.right=void 0!==a.right?a.right:f.right,f.bottom=void 0!==a.bottom?a.bottom:f.bottom,f.left=void 0!==a.left?a.left:f.left}},duration:{get:function(){return r},set:function(a){r=a,v.reset(r),e.duration(r)}},isArea:{get:function(){return o},set:function(a){o=d3.functor(a)}},x:{get:function(){return l},set:function(a){l=a,e.x(a)}},y:{get:function(){return m},set:function(a){m=a,e.y(a)}},color:{get:function(){return k},set:function(b){k=a.utils.getColor(b),e.color(k)}}}),a.utils.inheritOptions(b,e),a.utils.initOptions(b),b},a.models.lineChart=function(){\"use strict\";function b(j){return B.reset(),B.models(e),r&&B.models(f),s&&B.models(g),j.each(function(j){function y(){r&&L.select(\".nv-focus .nv-x.nv-axis\").transition().duration(A).call(f)}function B(){s&&L.select(\".nv-focus .nv-y.nv-axis\").transition().duration(A).call(g)}function E(a){var b=L.select(\".nv-focus .nv-linesWrap\").datum(j.filter(function(a){return!a.disabled}).map(function(b,c){return{key:b.key,area:b.area,classed:b.classed,values:b.values.filter(function(b,c){return e.x()(b,c)>=a[0]&&e.x()(b,c)<=a[1]}),disableTooltip:b.disableTooltip}}));b.transition().duration(A).call(e),y(),B()}var F=d3.select(this);a.utils.initSVG(F);var G=a.utils.availableWidth(n,F,l),H=a.utils.availableHeight(o,F,l)-(v?k.height():0);if(b.update=function(){0===A?F.call(b):F.transition().duration(A).call(b)},b.container=this,w.setter(D(j),b.update).getter(C(j)).update(),w.disabled=j.map(function(a){return!!a.disabled}),!x){var I;x={};for(I in w)w[I]instanceof Array?x[I]=w[I].slice(0):x[I]=w[I]}if(!(j&&j.length&&j.filter(function(a){return a.values.length}).length))return a.utils.noData(b,F),b;F.selectAll(\".nv-noData\").remove(),k.dispatch.on(\"onBrush\",function(a){E(a)}),c=e.xScale(),d=e.yScale();var J=F.selectAll(\"g.nv-wrap.nv-lineChart\").data([j]),K=J.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-lineChart\").append(\"g\"),L=J.select(\"g\");K.append(\"g\").attr(\"class\",\"nv-legendWrap\");var M=K.append(\"g\").attr(\"class\",\"nv-focus\");M.append(\"g\").attr(\"class\",\"nv-background\").append(\"rect\"),M.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),M.append(\"g\").attr(\"class\",\"nv-y nv-axis\"),M.append(\"g\").attr(\"class\",\"nv-linesWrap\"),M.append(\"g\").attr(\"class\",\"nv-interactive\");K.append(\"g\").attr(\"class\",\"nv-focusWrap\");p?(h.width(G),L.select(\".nv-legendWrap\").datum(j).call(h),\"bottom\"===q?J.select(\".nv-legendWrap\").attr(\"transform\",\"translate(0,\"+H+\")\"):\"top\"===q&&(h.height()>l.top&&(l.top=h.height(),H=a.utils.availableHeight(o,F,l)-(v?k.height():0)),J.select(\".nv-legendWrap\").attr(\"transform\",\"translate(0,\"+-l.top+\")\"))):L.select(\".nv-legendWrap\").selectAll(\"*\").remove(),J.attr(\"transform\",\"translate(\"+l.left+\",\"+l.top+\")\"),t&&L.select(\".nv-y.nv-axis\").attr(\"transform\",\"translate(\"+G+\",0)\"),u&&(i.width(G).height(H).margin({left:l.left,top:l.top}).svgContainer(F).xScale(c),J.select(\".nv-interactive\").call(i)),L.select(\".nv-focus .nv-background rect\").attr(\"width\",G).attr(\"height\",H),e.width(G).height(H).color(j.map(function(a,b){return a.color||m(a,b)}).filter(function(a,b){return!j[b].disabled}));var N=L.select(\".nv-linesWrap\").datum(j.filter(function(a){return!a.disabled}));if(r&&f.scale(c)._ticks(a.utils.calcTicksX(G/100,j)).tickSize(-H,0),s&&g.scale(d)._ticks(a.utils.calcTicksY(H/36,j)).tickSize(-G,0),L.select(\".nv-focus .nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+H+\")\"),v){k.width(G),L.select(\".nv-focusWrap\").attr(\"transform\",\"translate(0,\"+(H+l.bottom+k.margin().top)+\")\").datum(j.filter(function(a){return!a.disabled})).call(k);var O=k.brush.empty()?k.xDomain():k.brush.extent();null!==O&&E(O)}else N.call(e),y(),B();h.dispatch.on(\"stateChange\",function(a){for(var c in a)w[c]=a[c];z.stateChange(w),b.update()}),i.dispatch.on(\"elementMousemove\",function(d){e.clearHighlights();var f,h,l,n=[];if(j.filter(function(a,b){return a.seriesIndex=b,!a.disabled&&!a.disableTooltip}).forEach(function(g,i){var j=v?k.brush.empty()?k.xScale().domain():k.brush.extent():c.domain(),o=g.values.filter(function(a,b){return e.x()(a,b)>=j[0]&&e.x()(a,b)<=j[1]});h=a.interactiveBisect(o,d.pointXValue,e.x());var p=o[h],q=b.y()(p,h);null!==q&&e.highlightPoint(g.seriesIndex,h,!0),void 0!==p&&(void 0===f&&(f=p),void 0===l&&(l=b.xScale()(b.x()(p,h))),n.push({key:g.key,value:q,color:m(g,g.seriesIndex),data:p}))}),n.length>2){var o=b.yScale().invert(d.mouseY),p=Math.abs(b.yScale().domain()[0]-b.yScale().domain()[1]),q=.03*p,r=a.nearestValueIndex(n.map(function(a){return a.value}),o,q);null!==r&&(n[r].highlight=!0)}var s=function(a,b){return null==a?\"N/A\":g.tickFormat()(a)};i.tooltip.valueFormatter(i.tooltip.valueFormatter()||s).data({value:b.x()(f,h),index:h,series:n})(),i.renderGuideLine(l)}),i.dispatch.on(\"elementClick\",function(c){var d,f=[];j.filter(function(a,b){return a.seriesIndex=b,!a.disabled}).forEach(function(e){var g=a.interactiveBisect(e.values,c.pointXValue,b.x()),h=e.values[g];if(\"undefined\"!=typeof h){\"undefined\"==typeof d&&(d=b.xScale()(b.x()(h,g)));var i=b.yScale()(b.y()(h,g));f.push({point:h,pointIndex:g,pos:[d,i],seriesIndex:e.seriesIndex,series:e})}}),e.dispatch.elementClick(f)}),i.dispatch.on(\"elementMouseout\",function(a){e.clearHighlights()}),z.on(\"changeState\",function(a){\"undefined\"!=typeof a.disabled&&j.length===a.disabled.length&&(j.forEach(function(b,c){b.disabled=a.disabled[c]}),w.disabled=a.disabled),b.update()})}),B.renderEnd(\"lineChart immediate\"),b}var c,d,e=a.models.line(),f=a.models.axis(),g=a.models.axis(),h=a.models.legend(),i=a.interactiveGuideline(),j=a.models.tooltip(),k=a.models.focus(a.models.line()),l={top:30,right:20,bottom:50,left:60},m=a.utils.defaultColor(),n=null,o=null,p=!0,q=\"top\",r=!0,s=!0,t=!1,u=!1,v=!1,w=a.utils.state(),x=null,y=null,z=d3.dispatch(\"tooltipShow\",\"tooltipHide\",\"stateChange\",\"changeState\",\"renderEnd\"),A=250;f.orient(\"bottom\").tickPadding(7),g.orient(t?\"right\":\"left\"),e.clipEdge(!0).duration(0),j.valueFormatter(function(a,b){return g.tickFormat()(a,b)}).headerFormatter(function(a,b){return f.tickFormat()(a,b)}),i.tooltip.valueFormatter(function(a,b){return g.tickFormat()(a,b)}).headerFormatter(function(a,b){return f.tickFormat()(a,b)});var B=a.utils.renderWatch(z,A),C=function(a){return function(){return{active:a.map(function(a){return!a.disabled})}}},D=function(a){return function(b){void 0!==b.active&&a.forEach(function(a,c){a.disabled=!b.active[c]})}};return e.dispatch.on(\"elementMouseover.tooltip\",function(a){a.series.disableTooltip||j.data(a).hidden(!1)}),e.dispatch.on(\"elementMouseout.tooltip\",function(a){j.hidden(!0)}),b.dispatch=z,b.lines=e,b.legend=h,b.focus=k,b.xAxis=f,b.x2Axis=k.xAxis,b.yAxis=g,b.y2Axis=k.yAxis,b.interactiveLayer=i,b.tooltip=j,b.state=w,b.dispatch=z,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return n},set:function(a){n=a}},height:{get:function(){return o},set:function(a){o=a}},showLegend:{get:function(){return p},set:function(a){p=a}},legendPosition:{get:function(){return q},set:function(a){q=a}},showXAxis:{get:function(){return r},set:function(a){r=a}},showYAxis:{get:function(){return s},set:function(a){s=a}},defaultState:{get:function(){return x},set:function(a){x=a}},noData:{get:function(){return y},set:function(a){y=a}},focusEnable:{get:function(){return v},set:function(a){v=a}},focusHeight:{get:function(){return k.height()},set:function(a){k.height(a)}},focusShowAxisX:{get:function(){return k.showXAxis()},set:function(a){k.showXAxis(a)}},focusShowAxisY:{get:function(){return k.showYAxis()},set:function(a){k.showYAxis(a)}},brushExtent:{get:function(){return k.brushExtent()},set:function(a){k.brushExtent(a)}},focusMargin:{get:function(){return k.margin},set:function(a){k.margin.top=void 0!==a.top?a.top:k.margin.top,k.margin.right=void 0!==a.right?a.right:k.margin.right,k.margin.bottom=void 0!==a.bottom?a.bottom:k.margin.bottom,k.margin.left=void 0!==a.left?a.left:k.margin.left}},margin:{get:function(){return l},set:function(a){l.top=void 0!==a.top?a.top:l.top,l.right=void 0!==a.right?a.right:l.right,l.bottom=void 0!==a.bottom?a.bottom:l.bottom,l.left=void 0!==a.left?a.left:l.left}},duration:{get:function(){return A},set:function(a){A=a,B.reset(A),e.duration(A),k.duration(A),f.duration(A),g.duration(A)}},color:{get:function(){return m},set:function(b){m=a.utils.getColor(b),h.color(m),e.color(m),k.color(m)}},interpolate:{get:function(){return e.interpolate()},set:function(a){e.interpolate(a),k.interpolate(a)}},xTickFormat:{get:function(){return f.tickFormat()},set:function(a){f.tickFormat(a),k.xTickFormat(a)}},yTickFormat:{get:function(){return g.tickFormat()},set:function(a){g.tickFormat(a),k.yTickFormat(a)}},x:{get:function(){return e.x()},set:function(a){e.x(a),k.x(a)}},y:{get:function(){return e.y()},set:function(a){e.y(a),k.y(a)}},rightAlignYAxis:{get:function(){return t},set:function(a){t=a,g.orient(t?\"right\":\"left\")}},useInteractiveGuideline:{get:function(){return u},set:function(a){u=a,u&&(e.interactive(!1),e.useVoronoi(!1))}}}),a.utils.inheritOptions(b,e),a.utils.initOptions(b),b},a.models.lineWithFocusChart=function(){return a.models.lineChart().margin({bottom:30}).focusEnable(!0)},a.models.linePlusBarChart=function(){\"use strict\";function b(v){return v.each(function(v){function J(a){var b=+(\"e\"==a),c=b?1:-1,d=Z/3;return\"M\"+.5*c+\",\"+d+\"A6,6 0 0 \"+b+\" \"+6.5*c+\",\"+(d+6)+\"V\"+(2*d-6)+\"A6,6 0 0 \"+b+\" \"+.5*c+\",\"+2*d+\"ZM\"+2.5*c+\",\"+(d+8)+\"V\"+(2*d-8)+\"M\"+4.5*c+\",\"+(d+8)+\"V\"+(2*d-8)}function R(){u.empty()||u.extent(I),ma.data([u.empty()?e.domain():I]).each(function(a,b){var c=e(a[0])-e.range()[0],d=e.range()[1]-e(a[1]);d3.select(this).select(\".left\").attr(\"width\",0>c?0:c),d3.select(this).select(\".right\").attr(\"x\",e(a[1])).attr(\"width\",0>d?0:d)})}function S(){I=u.empty()?null:u.extent(),c=u.empty()?e.domain():u.extent(),K.brush({extent:c,brush:u}),R(),l.width(X).height(Y).color(v.map(function(a,b){return a.color||C(a,b)}).filter(function(a,b){return!v[b].disabled&&v[b].bar})),j.width(X).height(Y).color(v.map(function(a,b){return a.color||C(a,b)}).filter(function(a,b){return!v[b].disabled&&!v[b].bar}));var b=fa.select(\".nv-focus .nv-barsWrap\").datum(_.length?_.map(function(a,b){return{key:a.key,values:a.values.filter(function(a,b){return l.x()(a,b)>=c[0]&&l.x()(a,b)<=c[1]})}}):[{values:[]}]),h=fa.select(\".nv-focus .nv-linesWrap\").datum(V(aa)?[{values:[]}]:aa.filter(function(a){return!a.disabled}).map(function(a,b){return{area:a.area,fillOpacity:a.fillOpacity,strokeWidth:a.strokeWidth,key:a.key,values:a.values.filter(function(a,b){return j.x()(a,b)>=c[0]&&j.x()(a,b)<=c[1]})}}));d=_.length&&!Q?l.xScale():j.xScale(),n.scale(d)._ticks(a.utils.calcTicksX(X/100,v)).tickSize(-Y,0),n.domain([Math.ceil(c[0]),Math.floor(c[1])]),fa.select(\".nv-x.nv-axis\").transition().duration(L).call(n),b.transition().duration(L).call(l),h.transition().duration(L).call(j),fa.select(\".nv-focus .nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+f.range()[0]+\")\"),p.scale(f)._ticks(a.utils.calcTicksY(Y/36,v)).tickSize(-X,0),q.scale(g)._ticks(a.utils.calcTicksY(Y/36,v)),Q?q.tickSize(aa.length?0:-X,0):q.tickSize(_.length?0:-X,0);var i=_.length?1:0,k=aa.length&&!V(aa)?1:0,m=Q?k:i,o=Q?i:k;fa.select(\".nv-focus .nv-y1.nv-axis\").style(\"opacity\",m),fa.select(\".nv-focus .nv-y2.nv-axis\").style(\"opacity\",o).attr(\"transform\",\"translate(\"+d.range()[1]+\",0)\"),fa.select(\".nv-focus .nv-y1.nv-axis\").transition().duration(L).call(p),fa.select(\".nv-focus .nv-y2.nv-axis\").transition().duration(L).call(q)}var W=d3.select(this);a.utils.initSVG(W);var X=a.utils.availableWidth(y,W,w),Y=a.utils.availableHeight(z,W,w)-(E?H:0),Z=H-x.top-x.bottom;if(b.update=function(){W.transition().duration(L).call(b)},b.container=this,M.setter(U(v),b.update).getter(T(v)).update(),M.disabled=v.map(function(a){return!!a.disabled}),!N){var $;N={};for($ in M)M[$]instanceof Array?N[$]=M[$].slice(0):N[$]=M[$]}if(!(v&&v.length&&v.filter(function(a){return a.values.length}).length))return a.utils.noData(b,W),b;W.selectAll(\".nv-noData\").remove();var _=v.filter(function(a){return!a.disabled&&a.bar}),aa=v.filter(function(a){return!a.bar});d=_.length&&!Q?l.xScale():j.xScale(),e=o.scale(),f=Q?j.yScale():l.yScale(),g=Q?l.yScale():j.yScale(),h=Q?k.yScale():m.yScale(),i=Q?m.yScale():k.yScale();var ba=v.filter(function(a){return!a.disabled&&(Q?!a.bar:a.bar)}).map(function(a){return a.values.map(function(a,b){return{x:A(a,b),y:B(a,b)}})}),ca=v.filter(function(a){return!a.disabled&&(Q?a.bar:!a.bar)}).map(function(a){return a.values.map(function(a,b){return{x:A(a,b),y:B(a,b)}})});d.range([0,X]),e.domain(d3.extent(d3.merge(ba.concat(ca)),function(a){return a.x})).range([0,X]);var da=W.selectAll(\"g.nv-wrap.nv-linePlusBar\").data([v]),ea=da.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-linePlusBar\").append(\"g\"),fa=da.select(\"g\");ea.append(\"g\").attr(\"class\",\"nv-legendWrap\");var ga=ea.append(\"g\").attr(\"class\",\"nv-focus\");ga.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),ga.append(\"g\").attr(\"class\",\"nv-y1 nv-axis\"),ga.append(\"g\").attr(\"class\",\"nv-y2 nv-axis\"),ga.append(\"g\").attr(\"class\",\"nv-barsWrap\"),ga.append(\"g\").attr(\"class\",\"nv-linesWrap\");var ha=ea.append(\"g\").attr(\"class\",\"nv-context\");if(ha.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),ha.append(\"g\").attr(\"class\",\"nv-y1 nv-axis\"),ha.append(\"g\").attr(\"class\",\"nv-y2 nv-axis\"),ha.append(\"g\").attr(\"class\",\"nv-barsWrap\"),ha.append(\"g\").attr(\"class\",\"nv-linesWrap\"),ha.append(\"g\").attr(\"class\",\"nv-brushBackground\"),ha.append(\"g\").attr(\"class\",\"nv-x nv-brush\"),D){var ia=t.align()?X/2:X,ja=t.align()?ia:0;t.width(ia),fa.select(\".nv-legendWrap\").datum(v.map(function(a){return a.originalKey=void 0===a.originalKey?a.key:a.originalKey,Q?a.key=a.originalKey+(a.bar?P:O):a.key=a.originalKey+(a.bar?O:P),a})).call(t),t.height()>w.top&&(w.top=t.height(),Y=a.utils.availableHeight(z,W,w)-H),fa.select(\".nv-legendWrap\").attr(\"transform\",\"translate(\"+ja+\",\"+-w.top+\")\")}else fa.select(\".nv-legendWrap\").selectAll(\"*\").remove();da.attr(\"transform\",\"translate(\"+w.left+\",\"+w.top+\")\"),fa.select(\".nv-context\").style(\"display\",E?\"initial\":\"none\"),m.width(X).height(Z).color(v.map(function(a,b){return a.color||C(a,b)}).filter(function(a,b){return!v[b].disabled&&v[b].bar})),k.width(X).height(Z).color(v.map(function(a,b){return a.color||C(a,b)}).filter(function(a,b){return!v[b].disabled&&!v[b].bar}));var ka=fa.select(\".nv-context .nv-barsWrap\").datum(_.length?_:[{values:[]}]),la=fa.select(\".nv-context .nv-linesWrap\").datum(V(aa)?[{values:[]}]:aa.filter(function(a){return!a.disabled}));fa.select(\".nv-context\").attr(\"transform\",\"translate(0,\"+(Y+w.bottom+x.top)+\")\"),ka.transition().call(m),la.transition().call(k),G&&(o._ticks(a.utils.calcTicksX(X/100,v)).tickSize(-Z,0),fa.select(\".nv-context .nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+h.range()[0]+\")\"),fa.select(\".nv-context .nv-x.nv-axis\").transition().call(o)),F&&(r.scale(h)._ticks(Z/36).tickSize(-X,0),s.scale(i)._ticks(Z/36).tickSize(_.length?0:-X,0),fa.select(\".nv-context .nv-y3.nv-axis\").style(\"opacity\",_.length?1:0).attr(\"transform\",\"translate(0,\"+e.range()[0]+\")\"),fa.select(\".nv-context .nv-y2.nv-axis\").style(\"opacity\",aa.length?1:0).attr(\"transform\",\"translate(\"+e.range()[1]+\",0)\"),fa.select(\".nv-context .nv-y1.nv-axis\").transition().call(r),fa.select(\".nv-context .nv-y2.nv-axis\").transition().call(s)),u.x(e).on(\"brush\",S),I&&u.extent(I);var ma=fa.select(\".nv-brushBackground\").selectAll(\"g\").data([I||u.extent()]),na=ma.enter().append(\"g\");na.append(\"rect\").attr(\"class\",\"left\").attr(\"x\",0).attr(\"y\",0).attr(\"height\",Z),na.append(\"rect\").attr(\"class\",\"right\").attr(\"x\",0).attr(\"y\",0).attr(\"height\",Z);var oa=fa.select(\".nv-x.nv-brush\").call(u);oa.selectAll(\"rect\").attr(\"height\",Z),oa.selectAll(\".resize\").append(\"path\").attr(\"d\",J),t.dispatch.on(\"stateChange\",function(a){for(var c in a)M[c]=a[c];K.stateChange(M),b.update()}),K.on(\"changeState\",function(a){\"undefined\"!=typeof a.disabled&&(v.forEach(function(b,c){b.disabled=a.disabled[c]}),M.disabled=a.disabled),b.update()}),S()}),b}var c,d,e,f,g,h,i,j=a.models.line(),k=a.models.line(),l=a.models.historicalBar(),m=a.models.historicalBar(),n=a.models.axis(),o=a.models.axis(),p=a.models.axis(),q=a.models.axis(),r=a.models.axis(),s=a.models.axis(),t=a.models.legend(),u=d3.svg.brush(),v=a.models.tooltip(),w={top:30,right:30,bottom:30,left:60},x={top:0,right:30,bottom:20,left:60},y=null,z=null,A=function(a){return a.x},B=function(a){return a.y},C=a.utils.defaultColor(),D=!0,E=!0,F=!1,G=!0,H=50,I=null,J=null,K=d3.dispatch(\"brush\",\"stateChange\",\"changeState\"),L=0,M=a.utils.state(),N=null,O=\" (left axis)\",P=\" (right axis)\",Q=!1;j.clipEdge(!0),k.interactive(!1),k.pointActive(function(a){return!1}),n.orient(\"bottom\").tickPadding(5),p.orient(\"left\"),q.orient(\"right\"),o.orient(\"bottom\").tickPadding(5),r.orient(\"left\"),s.orient(\"right\"),v.headerEnabled(!0).headerFormatter(function(a,b){return n.tickFormat()(a,b)});var R=function(){return Q?{main:q,focus:s}:{main:p,focus:r}},S=function(){return Q?{main:p,focus:r}:{main:q,focus:s}},T=function(a){return function(){return{active:a.map(function(a){return!a.disabled})}}},U=function(a){return function(b){void 0!==b.active&&a.forEach(function(a,c){a.disabled=!b.active[c]})}},V=function(a){return a.every(function(a){return a.disabled})};return j.dispatch.on(\"elementMouseover.tooltip\",function(a){v.duration(100).valueFormatter(function(a,b){return S().main.tickFormat()(a,b)}).data(a).hidden(!1)}),j.dispatch.on(\"elementMouseout.tooltip\",function(a){v.hidden(!0)}),l.dispatch.on(\"elementMouseover.tooltip\",function(a){a.value=b.x()(a.data),a.series={value:b.y()(a.data),color:a.color},v.duration(0).valueFormatter(function(a,b){return R().main.tickFormat()(a,b)}).data(a).hidden(!1)}),l.dispatch.on(\"elementMouseout.tooltip\",function(a){v.hidden(!0)}),l.dispatch.on(\"elementMousemove.tooltip\",function(a){v()}),b.dispatch=K,b.legend=t,b.lines=j,b.lines2=k,b.bars=l,b.bars2=m,b.xAxis=n,b.x2Axis=o,b.y1Axis=p,b.y2Axis=q,b.y3Axis=r,b.y4Axis=s,b.tooltip=v,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return y},set:function(a){y=a}},height:{get:function(){return z},set:function(a){z=a}},showLegend:{get:function(){return D},set:function(a){D=a}},brushExtent:{get:function(){return I},set:function(a){I=a}},noData:{get:function(){return J},set:function(a){J=a}},focusEnable:{get:function(){return E},set:function(a){E=a}},focusHeight:{get:function(){return H},set:function(a){H=a}},focusShowAxisX:{get:function(){return G},set:function(a){G=a}},focusShowAxisY:{get:function(){return F},set:function(a){F=a}},legendLeftAxisHint:{get:function(){return O},set:function(a){O=a}},legendRightAxisHint:{get:function(){return P},set:function(a){P=a}},margin:{get:function(){return w},set:function(a){w.top=void 0!==a.top?a.top:w.top,w.right=void 0!==a.right?a.right:w.right,w.bottom=void 0!==a.bottom?a.bottom:w.bottom,w.left=void 0!==a.left?a.left:w.left}},focusMargin:{get:function(){return x},set:function(a){x.top=void 0!==a.top?a.top:x.top,x.right=void 0!==a.right?a.right:x.right,x.bottom=void 0!==a.bottom?a.bottom:x.bottom,x.left=void 0!==a.left?a.left:x.left}},duration:{get:function(){return L},set:function(a){L=a}},color:{get:function(){return C},set:function(b){C=a.utils.getColor(b),t.color(C)}},x:{get:function(){return A},set:function(a){A=a,j.x(a),k.x(a),l.x(a),m.x(a)}},y:{get:function(){return B},set:function(a){B=a,j.y(a),k.y(a),l.y(a),m.y(a)}},switchYAxisOrder:{get:function(){return Q},set:function(a){if(Q!==a){var b=p;p=q,q=b;var c=r;r=s,s=c}Q=a,p.orient(\"left\"),q.orient(\"right\"),r.orient(\"left\"),s.orient(\"right\")}}}),a.utils.inheritOptions(b,j),a.utils.initOptions(b),b},a.models.multiBar=function(){\"use strict\";function b(F){return D.reset(),F.each(function(b){var F=k-j.left-j.right,G=l-j.top-j.bottom;p=d3.select(this),a.utils.initSVG(p);var H=0;if(x&&b.length&&(x=[{values:b[0].values.map(function(a){return{x:a.x,y:0,series:a.series,size:.01}})}]),u){var I=d3.layout.stack().offset(v).values(function(a){return a.values}).y(r)(!b.length&&x?x:b);I.forEach(function(a,c){a.nonStackable?(b[c].nonStackableSeries=H++,I[c]=b[c]):c>0&&I[c-1].nonStackable&&I[c].values.map(function(a,b){a.y0-=I[c-1].values[b].y,a.y1=a.y0+a.y})}),b=I}b.forEach(function(a,b){a.values.forEach(function(c){c.series=b,c.key=a.key})}),u&&b.length>0&&b[0].values.map(function(a,c){var d=0,e=0;b.map(function(a,f){if(!b[f].nonStackable){var g=a.values[c];g.size=Math.abs(g.y),g.y<0?(g.y1=e,e-=g.size):(g.y1=g.size+d,d+=g.size)}})});var J=d&&e?[]:b.map(function(a,b){return a.values.map(function(a,c){return{x:q(a,c),y:r(a,c),y0:a.y0,y1:a.y1,idx:b}})});m.domain(d||d3.merge(J).map(function(a){return a.x})).rangeBands(f||[0,F],A),n.domain(e||d3.extent(d3.merge(J).map(function(a){var c=a.y;return u&&!b[a.idx].nonStackable&&(c=a.y>0?a.y1:a.y1+a.y),c}).concat(s))).range(g||[G,0]),m.domain()[0]===m.domain()[1]&&(m.domain()[0]?m.domain([m.domain()[0]-.01*m.domain()[0],m.domain()[1]+.01*m.domain()[1]]):m.domain([-1,1])),n.domain()[0]===n.domain()[1]&&(n.domain()[0]?n.domain([n.domain()[0]+.01*n.domain()[0],n.domain()[1]-.01*n.domain()[1]]):n.domain([-1,1])),h=h||m,i=i||n;var K=p.selectAll(\"g.nv-wrap.nv-multibar\").data([b]),L=K.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-multibar\"),M=L.append(\"defs\"),N=L.append(\"g\"),O=K.select(\"g\");N.append(\"g\").attr(\"class\",\"nv-groups\"),K.attr(\"transform\",\"translate(\"+j.left+\",\"+j.top+\")\"),M.append(\"clipPath\").attr(\"id\",\"nv-edge-clip-\"+o).append(\"rect\"),K.select(\"#nv-edge-clip-\"+o+\" rect\").attr(\"width\",F).attr(\"height\",G),O.attr(\"clip-path\",t?\"url(#nv-edge-clip-\"+o+\")\":\"\");var P=K.select(\".nv-groups\").selectAll(\".nv-group\").data(function(a){return a},function(a,b){return b});P.enter().append(\"g\").style(\"stroke-opacity\",1e-6).style(\"fill-opacity\",1e-6);var Q=D.transition(P.exit().selectAll(\"rect.nv-bar\"),\"multibarExit\",Math.min(100,z)).attr(\"y\",function(a,c,d){var e=i(0)||0;return u&&b[a.series]&&!b[a.series].nonStackable&&(e=i(a.y0)),e}).attr(\"height\",0).remove();Q.delay&&Q.delay(function(a,b){var c=b*(z/(E+1))-b;return c}),P.attr(\"class\",function(a,b){return\"nv-group nv-series-\"+b}).classed(\"hover\",function(a){return a.hover}).style(\"fill\",function(a,b){return w(a,b)}).style(\"stroke\",function(a,b){return w(a,b)}),P.style(\"stroke-opacity\",1).style(\"fill-opacity\",B);var R=P.selectAll(\"rect.nv-bar\").data(function(a){return x&&!b.length?x.values:a.values});R.exit().remove();R.enter().append(\"rect\").attr(\"class\",function(a,b){return r(a,b)<0?\"nv-bar negative\":\"nv-bar positive\"}).attr(\"x\",function(a,c,d){return u&&!b[d].nonStackable?0:d*m.rangeBand()/b.length}).attr(\"y\",function(a,c,d){return i(u&&!b[d].nonStackable?a.y0:0)||0}).attr(\"height\",0).attr(\"width\",function(a,c,d){return m.rangeBand()/(u&&!b[d].nonStackable?1:b.length)}).attr(\"transform\",function(a,b){return\"translate(\"+m(q(a,b))+\",0)\"});R.style(\"fill\",function(a,b,c){return w(a,c,b)}).style(\"stroke\",function(a,b,c){return w(a,c,b)}).on(\"mouseover\",function(a,b){d3.select(this).classed(\"hover\",!0),C.elementMouseover({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"mouseout\",function(a,b){d3.select(this).classed(\"hover\",!1),C.elementMouseout({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"mousemove\",function(a,b){C.elementMousemove({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"click\",function(a,b){var c=this;C.elementClick({data:a,index:b,color:d3.select(this).style(\"fill\"),event:d3.event,element:c}),d3.event.stopPropagation()}).on(\"dblclick\",function(a,b){C.elementDblClick({data:a,index:b,color:d3.select(this).style(\"fill\")}),d3.event.stopPropagation()}),R.attr(\"class\",function(a,b){return r(a,b)<0?\"nv-bar negative\":\"nv-bar positive\"}).attr(\"transform\",function(a,b){return\"translate(\"+m(q(a,b))+\",0)\"}),y&&(c||(c=b.map(function(){return!0})),R.style(\"fill\",function(a,b,d){return d3.rgb(y(a,b)).darker(c.map(function(a,b){return b}).filter(function(a,b){return!c[b]})[d]).toString()}).style(\"stroke\",function(a,b,d){return d3.rgb(y(a,b)).darker(c.map(function(a,b){return b}).filter(function(a,b){return!c[b]})[d]).toString()}));var S=R.watchTransition(D,\"multibar\",Math.min(250,z)).delay(function(a,c){return c*z/b[0].values.length});u?S.attr(\"y\",function(a,c,d){var e=0;return e=b[d].nonStackable?r(a,c)<0?n(0):n(0)-n(r(a,c))<-1?n(0)-1:n(r(a,c))||0:n(a.y1)}).attr(\"height\",function(a,c,d){return b[d].nonStackable?Math.max(Math.abs(n(r(a,c))-n(0)),0)||0:Math.max(Math.abs(n(a.y+a.y0)-n(a.y0)),0)}).attr(\"x\",function(a,c,d){var e=0;return b[d].nonStackable&&(e=a.series*m.rangeBand()/b.length,b.length!==H&&(e=b[d].nonStackableSeries*m.rangeBand()/(2*H))),e}).attr(\"width\",function(a,c,d){if(b[d].nonStackable){var e=m.rangeBand()/H;return b.length!==H&&(e=m.rangeBand()/(2*H)),e}return m.rangeBand()}):S.attr(\"x\",function(a,c){return a.series*m.rangeBand()/b.length}).attr(\"width\",m.rangeBand()/b.length).attr(\"y\",function(a,b){return r(a,b)<0?n(0):n(0)-n(r(a,b))<1?n(0)-1:n(r(a,b))||0}).attr(\"height\",function(a,b){return Math.max(Math.abs(n(r(a,b))-n(0)),1)||0}),h=m.copy(),i=n.copy(),b[0]&&b[0].values&&(E=b[0].values.length)}),D.renderEnd(\"multibar immediate\"),b}var c,d,e,f,g,h,i,j={top:0,right:0,bottom:0,left:0},k=960,l=500,m=d3.scale.ordinal(),n=d3.scale.linear(),o=Math.floor(1e4*Math.random()),p=null,q=function(a){return a.x},r=function(a){return a.y},s=[0],t=!0,u=!1,v=\"zero\",w=a.utils.defaultColor(),x=!1,y=null,z=500,A=.1,B=.75,C=d3.dispatch(\"chartClick\",\"elementClick\",\"elementDblClick\",\"elementMouseover\",\"elementMouseout\",\"elementMousemove\",\"renderEnd\"),D=a.utils.renderWatch(C,z),E=0;return b.dispatch=C,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return k},set:function(a){k=a}},height:{get:function(){return l},set:function(a){l=a}},x:{get:function(){return q},set:function(a){q=a}},y:{get:function(){return r},set:function(a){r=a}},xScale:{get:function(){return m},set:function(a){m=a}},yScale:{get:function(){return n},set:function(a){n=a}},xDomain:{get:function(){return d},set:function(a){d=a}},yDomain:{get:function(){return e},set:function(a){e=a}},xRange:{get:function(){return f},set:function(a){f=a}},yRange:{get:function(){return g},set:function(a){g=a}},forceY:{get:function(){return s},set:function(a){s=a}},stacked:{get:function(){return u},set:function(a){u=a}},stackOffset:{get:function(){return v},set:function(a){v=a}},clipEdge:{get:function(){return t},set:function(a){t=a}},disabled:{get:function(){return c},set:function(a){c=a}},id:{get:function(){return o},set:function(a){o=a}},hideable:{get:function(){return x},set:function(a){x=a}},groupSpacing:{get:function(){return A},set:function(a){A=a}},fillOpacity:{get:function(){return B},set:function(a){B=a}},margin:{get:function(){return j},set:function(a){j.top=void 0!==a.top?a.top:j.top,j.right=void 0!==a.right?a.right:j.right,j.bottom=void 0!==a.bottom?a.bottom:j.bottom,j.left=void 0!==a.left?a.left:j.left}},duration:{get:function(){return z},set:function(a){z=a,D.reset(z)}},color:{get:function(){return w},set:function(b){w=a.utils.getColor(b)}},barColor:{get:function(){return y},set:function(b){y=b?a.utils.getColor(b):null}}}),a.utils.initOptions(b),b},a.models.multiBarChart=function(){\"use strict\";function b(B){return G.reset(),G.models(e),s&&G.models(f),t&&G.models(g),B.each(function(B){var G=d3.select(this);a.utils.initSVG(G);var K=a.utils.availableWidth(m,G,l),L=a.utils.availableHeight(n,G,l);if(b.update=function(){0===E?G.call(b):G.transition().duration(E).call(b)},b.container=this,z.setter(J(B),b.update).getter(I(B)).update(),z.disabled=B.map(function(a){return!!a.disabled}),!A){var M;A={};for(M in z)z[M]instanceof Array?A[M]=z[M].slice(0):A[M]=z[M]}if(!(B&&B.length&&B.filter(function(a){return a.values.length}).length))return a.utils.noData(b,G),b;G.selectAll(\".nv-noData\").remove(),c=e.xScale(),d=e.yScale();var N=G.selectAll(\"g.nv-wrap.nv-multiBarWithLegend\").data([B]),O=N.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-multiBarWithLegend\").append(\"g\"),P=N.select(\"g\");if(O.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),O.append(\"g\").attr(\"class\",\"nv-y nv-axis\"),O.append(\"g\").attr(\"class\",\"nv-barsWrap\"),O.append(\"g\").attr(\"class\",\"nv-legendWrap\"),O.append(\"g\").attr(\"class\",\"nv-controlsWrap\"),O.append(\"g\").attr(\"class\",\"nv-interactive\"),r?(i.width(K-D()),P.select(\".nv-legendWrap\").datum(B).call(i),i.height()>l.top&&(l.top=i.height(),L=a.utils.availableHeight(n,G,l)),P.select(\".nv-legendWrap\").attr(\"transform\",\"translate(\"+D()+\",\"+-l.top+\")\")):P.select(\".nv-legendWrap\").selectAll(\"*\").remove(),p){var Q=[{key:q.grouped||\"Grouped\",disabled:e.stacked()},{key:q.stacked||\"Stacked\",disabled:!e.stacked()}];j.width(D()).color([\"#444\",\"#444\",\"#444\"]),P.select(\".nv-controlsWrap\").datum(Q).attr(\"transform\",\"translate(0,\"+-l.top+\")\").call(j)}else P.select(\".nv-controlsWrap\").selectAll(\"*\").remove();N.attr(\"transform\",\"translate(\"+l.left+\",\"+l.top+\")\"),u&&P.select(\".nv-y.nv-axis\").attr(\"transform\",\"translate(\"+K+\",0)\"),e.disabled(B.map(function(a){return a.disabled})).width(K).height(L).color(B.map(function(a,b){return a.color||o(a,b)}).filter(function(a,b){return!B[b].disabled}));var R=P.select(\".nv-barsWrap\").datum(B.filter(function(a){return!a.disabled}));if(R.call(e),s){f.scale(c)._ticks(a.utils.calcTicksX(K/100,B)).tickSize(-L,0),P.select(\".nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+d.range()[0]+\")\"),P.select(\".nv-x.nv-axis\").call(f);var S=P.select(\".nv-x.nv-axis > g\").selectAll(\"g\");if(S.selectAll(\"line, text\").style(\"opacity\",1),w){var T=function(a,b){return\"translate(\"+a+\",\"+b+\")\"},U=5,V=17;S.selectAll(\"text\").attr(\"transform\",function(a,b,c){return T(0,c%2==0?U:V)});var W=d3.selectAll(\".nv-x.nv-axis .nv-wrap g g text\")[0].length;P.selectAll(\".nv-x.nv-axis .nv-axisMaxMin text\").attr(\"transform\",function(a,b){return T(0,0===b||W%2!==0?V:U)})}x&&P.selectAll(\".tick text\").call(a.utils.wrapTicks,b.xAxis.rangeBand()),v&&S.filter(function(a,b){return b%Math.ceil(B[0].values.length/(K/100))!==0}).selectAll(\"text, line\").style(\"opacity\",0),y&&S.selectAll(\".tick text\").attr(\"transform\",\"rotate(\"+y+\" 0,0)\").style(\"text-anchor\",y>0?\"start\":\"end\"),P.select(\".nv-x.nv-axis\").selectAll(\"g.nv-axisMaxMin text\").style(\"opacity\",1)}t&&(g.scale(d)._ticks(a.utils.calcTicksY(L/36,B)).tickSize(-K,0),P.select(\".nv-y.nv-axis\").call(g)),F&&(h.width(K).height(L).margin({left:l.left,top:l.top}).svgContainer(G).xScale(c),N.select(\".nv-interactive\").call(h)),i.dispatch.on(\"stateChange\",function(a){for(var c in a)z[c]=a[c];C.stateChange(z),b.update()}),j.dispatch.on(\"legendClick\",function(a,c){if(a.disabled){switch(Q=Q.map(function(a){return a.disabled=!0,a}),a.disabled=!1,a.key){case\"Grouped\":case q.grouped:e.stacked(!1);break;case\"Stacked\":case q.stacked:e.stacked(!0)}z.stacked=e.stacked(),C.stateChange(z),b.update()}}),C.on(\"changeState\",function(a){\"undefined\"!=typeof a.disabled&&(B.forEach(function(b,c){b.disabled=a.disabled[c]}),z.disabled=a.disabled),\"undefined\"!=typeof a.stacked&&(e.stacked(a.stacked),z.stacked=a.stacked,H=a.stacked),b.update()}),F?(h.dispatch.on(\"elementMousemove\",function(a){if(void 0!=a.pointXValue){var d,e,f,g,i=[];B.filter(function(a,b){return a.seriesIndex=b,!a.disabled}).forEach(function(h,j){e=c.domain().indexOf(a.pointXValue);var k=h.values[e];void 0!==k&&(g=k.x,void 0===d&&(d=k),void 0===f&&(f=a.mouseX),i.push({key:h.key,value:b.y()(k,e),color:o(h,h.seriesIndex),data:h.values[e]}))}),h.tooltip.data({value:g,index:e,series:i})(),h.renderGuideLine(f)}}),h.dispatch.on(\"elementMouseout\",function(a){h.tooltip.hidden(!0)})):(e.dispatch.on(\"elementMouseover.tooltip\",function(a){a.value=b.x()(a.data),a.series={key:a.data.key,value:b.y()(a.data),color:a.color},k.data(a).hidden(!1)}),e.dispatch.on(\"elementMouseout.tooltip\",function(a){k.hidden(!0)}),e.dispatch.on(\"elementMousemove.tooltip\",function(a){k()}))}),G.renderEnd(\"multibarchart immediate\"),b}var c,d,e=a.models.multiBar(),f=a.models.axis(),g=a.models.axis(),h=a.interactiveGuideline(),i=a.models.legend(),j=a.models.legend(),k=a.models.tooltip(),l={top:30,right:20,bottom:50,left:60},m=null,n=null,o=a.utils.defaultColor(),p=!0,q={},r=!0,s=!0,t=!0,u=!1,v=!0,w=!1,x=!1,y=0,z=a.utils.state(),A=null,B=null,C=d3.dispatch(\"stateChange\",\"changeState\",\"renderEnd\"),D=function(){return p?180:0},E=250,F=!1;z.stacked=!1,e.stacked(!1),f.orient(\"bottom\").tickPadding(7).showMaxMin(!1).tickFormat(function(a){return a}),g.orient(u?\"right\":\"left\").tickFormat(d3.format(\",.1f\")),k.duration(0).valueFormatter(function(a,b){return g.tickFormat()(a,b)}).headerFormatter(function(a,b){return f.tickFormat()(a,b)}),j.updateState(!1);var G=a.utils.renderWatch(C),H=!1,I=function(a){return function(){return{active:a.map(function(a){return!a.disabled}),stacked:H}}},J=function(a){return function(b){void 0!==b.stacked&&(H=b.stacked),void 0!==b.active&&a.forEach(function(a,c){a.disabled=!b.active[c]})}};return b.dispatch=C,b.multibar=e,b.legend=i,b.controls=j,b.xAxis=f,b.yAxis=g,b.state=z,b.tooltip=k,b.interactiveLayer=h,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return m},set:function(a){m=a}},height:{get:function(){return n},set:function(a){n=a}},showLegend:{get:function(){return r},set:function(a){r=a}},showControls:{get:function(){return p},set:function(a){p=a}},controlLabels:{get:function(){return q},set:function(a){q=a}},showXAxis:{get:function(){return s},set:function(a){s=a}},showYAxis:{get:function(){return t},set:function(a){t=a}},defaultState:{get:function(){return A},set:function(a){A=a}},noData:{get:function(){return B},set:function(a){B=a}},reduceXTicks:{get:function(){return v},set:function(a){v=a}},rotateLabels:{get:function(){return y},set:function(a){y=a}},staggerLabels:{get:function(){return w},set:function(a){w=a}},wrapLabels:{get:function(){return x},set:function(a){x=!!a}},margin:{get:function(){return l},set:function(a){l.top=void 0!==a.top?a.top:l.top,l.right=void 0!==a.right?a.right:l.right,l.bottom=void 0!==a.bottom?a.bottom:l.bottom,l.left=void 0!==a.left?a.left:l.left}},duration:{get:function(){return E},set:function(a){E=a,e.duration(E),f.duration(E),g.duration(E),G.reset(E)}},color:{get:function(){return o},set:function(b){o=a.utils.getColor(b),i.color(o)}},rightAlignYAxis:{get:function(){return u},set:function(a){u=a,g.orient(u?\"right\":\"left\")}},useInteractiveGuideline:{get:function(){return F},set:function(a){F=a}},barColor:{get:function(){return e.barColor},set:function(a){e.barColor(a),i.color(function(a,b){return d3.rgb(\"#ccc\").darker(1.5*b).toString()})}}}),a.utils.inheritOptions(b,e),a.utils.initOptions(b),b},a.models.multiBarHorizontal=function(){\"use strict\";function b(m){return F.reset(),m.each(function(b){var m=k-j.left-j.right,D=l-j.top-j.bottom;n=d3.select(this),a.utils.initSVG(n),w&&(b=d3.layout.stack().offset(\"zero\").values(function(a){return a.values}).y(r)(b)),b.forEach(function(a,b){a.values.forEach(function(c){c.series=b,c.key=a.key})}),w&&b[0].values.map(function(a,c){var d=0,e=0;b.map(function(a){var b=a.values[c];b.size=Math.abs(b.y),b.y<0?(b.y1=e-b.size,e-=b.size):(b.y1=d,d+=b.size)})});var G=d&&e?[]:b.map(function(a){return a.values.map(function(a,b){return{x:q(a,b),y:r(a,b),y0:a.y0,y1:a.y1}})});o.domain(d||d3.merge(G).map(function(a){return a.x})).rangeBands(f||[0,D],A),p.domain(e||d3.extent(d3.merge(G).map(function(a){return w?a.y>0?a.y1+a.y:a.y1:a.y}).concat(t))),x&&!w?p.range(g||[p.domain()[0]<0?z:0,m-(p.domain()[1]>0?z:0)]):p.range(g||[0,m]),h=h||o,i=i||d3.scale.linear().domain(p.domain()).range([p(0),p(0)]);var H=d3.select(this).selectAll(\"g.nv-wrap.nv-multibarHorizontal\").data([b]),I=H.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-multibarHorizontal\"),J=(I.append(\"defs\"),I.append(\"g\"));H.select(\"g\");J.append(\"g\").attr(\"class\",\"nv-groups\"),H.attr(\"transform\",\"translate(\"+j.left+\",\"+j.top+\")\");var K=H.select(\".nv-groups\").selectAll(\".nv-group\").data(function(a){return a},function(a,b){return b});K.enter().append(\"g\").style(\"stroke-opacity\",1e-6).style(\"fill-opacity\",1e-6),K.exit().watchTransition(F,\"multibarhorizontal: exit groups\").style(\"stroke-opacity\",1e-6).style(\"fill-opacity\",1e-6).remove(),K.attr(\"class\",function(a,b){return\"nv-group nv-series-\"+b}).classed(\"hover\",function(a){return a.hover}).style(\"fill\",function(a,b){return u(a,b)}).style(\"stroke\",function(a,b){return u(a,b)}),K.watchTransition(F,\"multibarhorizontal: groups\").style(\"stroke-opacity\",1).style(\"fill-opacity\",B);var L=K.selectAll(\"g.nv-bar\").data(function(a){return a.values});L.exit().remove();var M=L.enter().append(\"g\").attr(\"transform\",function(a,c,d){return\"translate(\"+i(w?a.y0:0)+\",\"+(w?0:d*o.rangeBand()/b.length+o(q(a,c)))+\")\"});M.append(\"rect\").attr(\"width\",0).attr(\"height\",o.rangeBand()/(w?1:b.length)),L.on(\"mouseover\",function(a,b){d3.select(this).classed(\"hover\",!0),E.elementMouseover({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"mouseout\",function(a,b){d3.select(this).classed(\"hover\",!1),E.elementMouseout({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"mouseout\",function(a,b){E.elementMouseout({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"mousemove\",function(a,b){E.elementMousemove({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"click\",function(a,b){var c=this;E.elementClick({data:a,index:b,color:d3.select(this).style(\"fill\"),event:d3.event,element:c}),d3.event.stopPropagation()}).on(\"dblclick\",function(a,b){E.elementDblClick({data:a,index:b,color:d3.select(this).style(\"fill\")}),d3.event.stopPropagation()}),s(b[0],0)&&(M.append(\"polyline\"),L.select(\"polyline\").attr(\"fill\",\"none\").attr(\"points\",function(a,c){var d=s(a,c),e=.8*o.rangeBand()/(2*(w?1:b.length));d=d.length?d:[-Math.abs(d),Math.abs(d)],d=d.map(function(a){return p(a)-p(0)});var f=[[d[0],-e],[d[0],e],[d[0],0],[d[1],0],[d[1],-e],[d[1],e]];return f.map(function(a){return a.join(\",\")}).join(\" \")}).attr(\"transform\",function(a,c){var d=o.rangeBand()/(2*(w?1:b.length));return\"translate(\"+(r(a,c)<0?0:p(r(a,c))-p(0))+\", \"+d+\")\"})),M.append(\"text\"),x&&!w?(L.select(\"text\").attr(\"text-anchor\",function(a,b){return r(a,b)<0?\"end\":\"start\"}).attr(\"y\",o.rangeBand()/(2*b.length)).attr(\"dy\",\".32em\").text(function(a,b){var c=C(r(a,b)),d=s(a,b);return void 0===d?c:d.length?c+\"+\"+C(Math.abs(d[1]))+\"-\"+C(Math.abs(d[0])):c+\"±\"+C(Math.abs(d))}),L.watchTransition(F,\"multibarhorizontal: bars\").select(\"text\").attr(\"x\",function(a,b){return r(a,b)<0?-4:p(r(a,b))-p(0)+4})):L.selectAll(\"text\").text(\"\"),y&&!w?(M.append(\"text\").classed(\"nv-bar-label\",!0),L.select(\"text.nv-bar-label\").attr(\"text-anchor\",function(a,b){return r(a,b)<0?\"start\":\"end\"}).attr(\"y\",o.rangeBand()/(2*b.length)).attr(\"dy\",\".32em\").text(function(a,b){return q(a,b)}),L.watchTransition(F,\"multibarhorizontal: bars\").select(\"text.nv-bar-label\").attr(\"x\",function(a,b){return r(a,b)<0?p(0)-p(r(a,b))+4:-4})):L.selectAll(\"text.nv-bar-label\").text(\"\"),L.attr(\"class\",function(a,b){return r(a,b)<0?\"nv-bar negative\":\"nv-bar positive\"}),v&&(c||(c=b.map(function(){return!0})),L.style(\"fill\",function(a,b,d){return d3.rgb(v(a,b)).darker(c.map(function(a,b){return b}).filter(function(a,b){return!c[b]})[d]).toString()}).style(\"stroke\",function(a,b,d){return d3.rgb(v(a,b)).darker(c.map(function(a,b){return b}).filter(function(a,b){return!c[b]})[d]).toString()})),w?L.watchTransition(F,\"multibarhorizontal: bars\").attr(\"transform\",function(a,b){return\"translate(\"+p(a.y1)+\",\"+o(q(a,b))+\")\"}).select(\"rect\").attr(\"width\",function(a,b){return Math.abs(p(r(a,b)+a.y0)-p(a.y0))||0}).attr(\"height\",o.rangeBand()):L.watchTransition(F,\"multibarhorizontal: bars\").attr(\"transform\",function(a,c){return\"translate(\"+p(r(a,c)<0?r(a,c):0)+\",\"+(a.series*o.rangeBand()/b.length+o(q(a,c)))+\")\"}).select(\"rect\").attr(\"height\",o.rangeBand()/b.length).attr(\"width\",function(a,b){return Math.max(Math.abs(p(r(a,b))-p(0)),1)||0}),h=o.copy(),i=p.copy()}),F.renderEnd(\"multibarHorizontal immediate\"),b}var c,d,e,f,g,h,i,j={top:0,right:0,bottom:0,left:0},k=960,l=500,m=Math.floor(1e4*Math.random()),n=null,o=d3.scale.ordinal(),p=d3.scale.linear(),q=function(a){return a.x},r=function(a){return a.y},s=function(a){return a.yErr},t=[0],u=a.utils.defaultColor(),v=null,w=!1,x=!1,y=!1,z=60,A=.1,B=.75,C=d3.format(\",.2f\"),D=250,E=d3.dispatch(\"chartClick\",\"elementClick\",\"elementDblClick\",\"elementMouseover\",\"elementMouseout\",\"elementMousemove\",\"renderEnd\"),F=a.utils.renderWatch(E,D);return b.dispatch=E,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return k},set:function(a){k=a}},height:{get:function(){return l},set:function(a){l=a}},x:{get:function(){return q},set:function(a){q=a}},y:{get:function(){return r},set:function(a){r=a}},yErr:{get:function(){return s},set:function(a){s=a}},xScale:{get:function(){return o},set:function(a){o=a}},yScale:{get:function(){return p},set:function(a){p=a}},xDomain:{get:function(){return d},set:function(a){d=a}},yDomain:{get:function(){return e},set:function(a){e=a}},xRange:{get:function(){return f},set:function(a){f=a}},yRange:{get:function(){return g},set:function(a){g=a}},forceY:{get:function(){return t},set:function(a){t=a}},stacked:{get:function(){return w},set:function(a){w=a}},showValues:{get:function(){return x},set:function(a){x=a}},disabled:{get:function(){return c},set:function(a){c=a}},id:{get:function(){return m},set:function(a){m=a}},valueFormat:{get:function(){return C},set:function(a){C=a}},valuePadding:{get:function(){return z},set:function(a){z=a}},groupSpacing:{get:function(){return A},set:function(a){A=a}},fillOpacity:{get:function(){return B},set:function(a){B=a}},margin:{get:function(){return j},set:function(a){j.top=void 0!==a.top?a.top:j.top,j.right=void 0!==a.right?a.right:j.right,j.bottom=void 0!==a.bottom?a.bottom:j.bottom,j.left=void 0!==a.left?a.left:j.left}},duration:{get:function(){return D},set:function(a){D=a,F.reset(D)}},color:{get:function(){return u},set:function(b){u=a.utils.getColor(b)}},barColor:{get:function(){return v},set:function(b){v=b?a.utils.getColor(b):null}}}),a.utils.initOptions(b),b},a.models.multiBarHorizontalChart=function(){\"use strict\";function b(j){return C.reset(),C.models(e),r&&C.models(f),s&&C.models(g),j.each(function(j){var w=d3.select(this);a.utils.initSVG(w);var C=a.utils.availableWidth(l,w,k),D=a.utils.availableHeight(m,w,k);if(b.update=function(){w.transition().duration(z).call(b)},b.container=this,t=e.stacked(),u.setter(B(j),b.update).getter(A(j)).update(),u.disabled=j.map(function(a){return!!a.disabled}),!v){var E;v={};for(E in u)u[E]instanceof Array?v[E]=u[E].slice(0):v[E]=u[E]}if(!(j&&j.length&&j.filter(function(a){return a.values.length}).length))return a.utils.noData(b,w),b;w.selectAll(\".nv-noData\").remove(),c=e.xScale(),d=e.yScale().clamp(!0);var F=w.selectAll(\"g.nv-wrap.nv-multiBarHorizontalChart\").data([j]),G=F.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-multiBarHorizontalChart\").append(\"g\"),H=F.select(\"g\");if(G.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),G.append(\"g\").attr(\"class\",\"nv-y nv-axis\").append(\"g\").attr(\"class\",\"nv-zeroLine\").append(\"line\"),G.append(\"g\").attr(\"class\",\"nv-barsWrap\"),G.append(\"g\").attr(\"class\",\"nv-legendWrap\"),G.append(\"g\").attr(\"class\",\"nv-controlsWrap\"),q?(h.width(C-y()),H.select(\".nv-legendWrap\").datum(j).call(h),h.height()>k.top&&(k.top=h.height(),D=a.utils.availableHeight(m,w,k)),H.select(\".nv-legendWrap\").attr(\"transform\",\"translate(\"+y()+\",\"+-k.top+\")\")):H.select(\".nv-legendWrap\").selectAll(\"*\").remove(),o){var I=[{key:p.grouped||\"Grouped\",disabled:e.stacked()},{key:p.stacked||\"Stacked\",disabled:!e.stacked()}];i.width(y()).color([\"#444\",\"#444\",\"#444\"]),H.select(\".nv-controlsWrap\").datum(I).attr(\"transform\",\"translate(0,\"+-k.top+\")\").call(i)}else H.select(\".nv-controlsWrap\").selectAll(\"*\").remove();F.attr(\"transform\",\"translate(\"+k.left+\",\"+k.top+\")\"),e.disabled(j.map(function(a){return a.disabled})).width(C).height(D).color(j.map(function(a,b){return a.color||n(a,b)}).filter(function(a,b){return!j[b].disabled}));var J=H.select(\".nv-barsWrap\").datum(j.filter(function(a){return!a.disabled}));if(J.transition().call(e),r){f.scale(c)._ticks(a.utils.calcTicksY(D/24,j)).tickSize(-C,0),H.select(\".nv-x.nv-axis\").call(f);var K=H.select(\".nv-x.nv-axis\").selectAll(\"g\");K.selectAll(\"line, text\")}s&&(g.scale(d)._ticks(a.utils.calcTicksX(C/100,j)).tickSize(-D,0),H.select(\".nv-y.nv-axis\").attr(\"transform\",\"translate(0,\"+D+\")\"),H.select(\".nv-y.nv-axis\").call(g)),H.select(\".nv-zeroLine line\").attr(\"x1\",d(0)).attr(\"x2\",d(0)).attr(\"y1\",0).attr(\"y2\",-D),h.dispatch.on(\"stateChange\",function(a){for(var c in a)u[c]=a[c];x.stateChange(u),b.update()}),i.dispatch.on(\"legendClick\",function(a,c){if(a.disabled){switch(I=I.map(function(a){return a.disabled=!0,a}),a.disabled=!1,a.key){case\"Grouped\":case p.grouped:e.stacked(!1);break;case\"Stacked\":case p.stacked:e.stacked(!0)}u.stacked=e.stacked(),x.stateChange(u),t=e.stacked(),b.update()}}),x.on(\"changeState\",function(a){\"undefined\"!=typeof a.disabled&&(j.forEach(function(b,c){b.disabled=a.disabled[c]}),u.disabled=a.disabled),\"undefined\"!=typeof a.stacked&&(e.stacked(a.stacked),u.stacked=a.stacked,t=a.stacked),b.update()})}),C.renderEnd(\"multibar horizontal chart immediate\"),b}var c,d,e=a.models.multiBarHorizontal(),f=a.models.axis(),g=a.models.axis(),h=a.models.legend().height(30),i=a.models.legend().height(30),j=a.models.tooltip(),k={top:30,right:20,bottom:50,left:60},l=null,m=null,n=a.utils.defaultColor(),o=!0,p={},q=!0,r=!0,s=!0,t=!1,u=a.utils.state(),v=null,w=null,x=d3.dispatch(\"stateChange\",\"changeState\",\"renderEnd\"),y=function(){return o?180:0},z=250;u.stacked=!1,e.stacked(t),f.orient(\"left\").tickPadding(5).showMaxMin(!1).tickFormat(function(a){return a}),g.orient(\"bottom\").tickFormat(d3.format(\",.1f\")),j.duration(0).valueFormatter(function(a,b){return g.tickFormat()(a,b)}).headerFormatter(function(a,b){return f.tickFormat()(a,b)}),i.updateState(!1);var A=function(a){return function(){return{active:a.map(function(a){return!a.disabled}),stacked:t}}},B=function(a){return function(b){void 0!==b.stacked&&(t=b.stacked),void 0!==b.active&&a.forEach(function(a,c){a.disabled=!b.active[c]})}},C=a.utils.renderWatch(x,z);return e.dispatch.on(\"elementMouseover.tooltip\",function(a){a.value=b.x()(a.data),a.series={key:a.data.key,value:b.y()(a.data),color:a.color},j.data(a).hidden(!1)}),e.dispatch.on(\"elementMouseout.tooltip\",function(a){j.hidden(!0)}),e.dispatch.on(\"elementMousemove.tooltip\",function(a){j()}),b.dispatch=x,b.multibar=e,b.legend=h,b.controls=i,b.xAxis=f,b.yAxis=g,b.state=u,b.tooltip=j,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return l},set:function(a){l=a}},height:{get:function(){return m},set:function(a){m=a}},showLegend:{get:function(){return q},set:function(a){q=a}},showControls:{get:function(){return o},set:function(a){o=a}},controlLabels:{get:function(){return p},set:function(a){p=a}},showXAxis:{get:function(){return r},set:function(a){r=a}},showYAxis:{get:function(){return s},set:function(a){s=a}},defaultState:{get:function(){return v},set:function(a){v=a}},noData:{get:function(){return w},set:function(a){w=a}},margin:{get:function(){return k},set:function(a){k.top=void 0!==a.top?a.top:k.top,k.right=void 0!==a.right?a.right:k.right,k.bottom=void 0!==a.bottom?a.bottom:k.bottom,k.left=void 0!==a.left?a.left:k.left}},duration:{get:function(){return z},set:function(a){z=a,C.reset(z),e.duration(z),f.duration(z),g.duration(z)}},color:{get:function(){return n},set:function(b){n=a.utils.getColor(b),h.color(n)}},barColor:{get:function(){return e.barColor},set:function(a){e.barColor(a),h.color(function(a,b){return d3.rgb(\"#ccc\").darker(1.5*b).toString()})}}}),a.utils.inheritOptions(b,e),a.utils.initOptions(b),b},a.models.multiChart=function(){\"use strict\";function b(j){return j.each(function(j){function n(a){var b=2===j[a.seriesIndex].yAxis?E:D;a.value=a.point.x,a.series={value:a.point.y,color:a.point.color,key:a.series.key},G.duration(0).headerFormatter(function(a,b){return C.tickFormat()(a,b)}).valueFormatter(function(a,c){return b.tickFormat()(a,c)}).data(a).hidden(!1)}function H(a){var b=2===j[a.seriesIndex].yAxis?E:D;a.value=a.point.x,a.series={value:a.point.y,color:a.point.color,key:a.series.key},G.duration(100).headerFormatter(function(a,b){return C.tickFormat()(a,b)}).valueFormatter(function(a,c){return b.tickFormat()(a,c)}).data(a).hidden(!1)}function J(a){var b=2===j[a.seriesIndex].yAxis?E:D;a.point.x=A.x()(a.point),a.point.y=A.y()(a.point),G.duration(0).headerFormatter(function(a,b){return C.tickFormat()(a,b)}).valueFormatter(function(a,c){return b.tickFormat()(a,c)}).data(a).hidden(!1)}function K(a){var b=2===j[a.data.series].yAxis?E:D;a.value=y.x()(a.data),a.series={value:y.y()(a.data),color:a.color,key:a.data.key},G.duration(0).headerFormatter(function(a,b){return C.tickFormat()(a,b)}).valueFormatter(function(a,c){return b.tickFormat()(a,c)}).data(a).hidden(!1)}function L(){for(var a=0,b=I.length;b>a;a++){var c=I[a];try{c.clearHighlights()}catch(d){}}}function M(a,b,c){for(var d=0,e=I.length;e>d;d++){var f=I[d];try{f.highlightPoint(a,b,c)}catch(g){}}}var N=d3.select(this);a.utils.initSVG(N),b.update=function(){N.transition().call(b)},b.container=this;var O=a.utils.availableWidth(g,N,e),P=a.utils.availableHeight(h,N,e),Q=j.filter(function(a){return\"line\"==a.type&&1==a.yAxis}),R=j.filter(function(a){return\"line\"==a.type&&2==a.yAxis}),S=j.filter(function(a){return\"scatter\"==a.type&&1==a.yAxis}),T=j.filter(function(a){return\"scatter\"==a.type&&2==a.yAxis}),U=j.filter(function(a){return\"bar\"==a.type&&1==a.yAxis}),V=j.filter(function(a){return\"bar\"==a.type&&2==a.yAxis}),W=j.filter(function(a){return\"area\"==a.type&&1==a.yAxis}),X=j.filter(function(a){return\"area\"==a.type&&2==a.yAxis});if(!(j&&j.length&&j.filter(function(a){return a.values.length}).length))return a.utils.noData(b,N),b;N.selectAll(\".nv-noData\").remove();var Y=j.filter(function(a){return!a.disabled&&1==a.yAxis}).map(function(a){return a.values.map(function(a,b){return{x:k(a),y:l(a)}})}),Z=j.filter(function(a){return!a.disabled&&2==a.yAxis}).map(function(a){return a.values.map(function(a,b){return{x:k(a),y:l(a)}})});r.domain(d3.extent(d3.merge(Y.concat(Z)),function(a){return a.x})).range([0,O]);var $=N.selectAll(\"g.wrap.multiChart\").data([j]),_=$.enter().append(\"g\").attr(\"class\",\"wrap nvd3 multiChart\").append(\"g\");_.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),_.append(\"g\").attr(\"class\",\"nv-y1 nv-axis\"),_.append(\"g\").attr(\"class\",\"nv-y2 nv-axis\"),_.append(\"g\").attr(\"class\",\"stack1Wrap\"),_.append(\"g\").attr(\"class\",\"stack2Wrap\"),_.append(\"g\").attr(\"class\",\"bars1Wrap\"),_.append(\"g\").attr(\"class\",\"bars2Wrap\"),_.append(\"g\").attr(\"class\",\"scatters1Wrap\"),_.append(\"g\").attr(\"class\",\"scatters2Wrap\"),_.append(\"g\").attr(\"class\",\"lines1Wrap\"),_.append(\"g\").attr(\"class\",\"lines2Wrap\"),_.append(\"g\").attr(\"class\",\"legendWrap\"),_.append(\"g\").attr(\"class\",\"nv-interactive\");var aa=$.select(\"g\"),ba=j.map(function(a,b){return j[b].color||f(a,b)});if(i){var ca=F.align()?O/2:O,da=F.align()?ca:0;F.width(ca),F.color(ba),aa.select(\".legendWrap\").datum(j.map(function(a){return a.originalKey=void 0===a.originalKey?a.key:a.originalKey,a.key=a.originalKey+(1==a.yAxis?\"\":q),a})).call(F),F.height()>e.top&&(e.top=F.height(),P=a.utils.availableHeight(h,N,e)),aa.select(\".legendWrap\").attr(\"transform\",\"translate(\"+da+\",\"+-e.top+\")\")}else aa.select(\".legendWrap\").selectAll(\"*\").remove();u.width(O).height(P).interpolate(m).color(ba.filter(function(a,b){return!j[b].disabled&&1==j[b].yAxis&&\"line\"==j[b].type})),v.width(O).height(P).interpolate(m).color(ba.filter(function(a,b){return!j[b].disabled&&2==j[b].yAxis&&\"line\"==j[b].type})),w.width(O).height(P).color(ba.filter(function(a,b){return!j[b].disabled&&1==j[b].yAxis&&\"scatter\"==j[b].type})),x.width(O).height(P).color(ba.filter(function(a,b){return!j[b].disabled&&2==j[b].yAxis&&\"scatter\"==j[b].type})),y.width(O).height(P).color(ba.filter(function(a,b){return!j[b].disabled&&1==j[b].yAxis&&\"bar\"==j[b].type})),z.width(O).height(P).color(ba.filter(function(a,b){return!j[b].disabled&&2==j[b].yAxis&&\"bar\"==j[b].type})),A.width(O).height(P).interpolate(m).color(ba.filter(function(a,b){return!j[b].disabled&&1==j[b].yAxis&&\"area\"==j[b].type})),B.width(O).height(P).interpolate(m).color(ba.filter(function(a,b){return!j[b].disabled&&2==j[b].yAxis&&\"area\"==j[b].type})),aa.attr(\"transform\",\"translate(\"+e.left+\",\"+e.top+\")\");var ea=aa.select(\".lines1Wrap\").datum(Q.filter(function(a){return!a.disabled})),fa=aa.select(\".scatters1Wrap\").datum(S.filter(function(a){return!a.disabled})),ga=aa.select(\".bars1Wrap\").datum(U.filter(function(a){return!a.disabled})),ha=aa.select(\".stack1Wrap\").datum(W.filter(function(a){return!a.disabled})),ia=aa.select(\".lines2Wrap\").datum(R.filter(function(a){return!a.disabled})),ja=aa.select(\".scatters2Wrap\").datum(T.filter(function(a){return!a.disabled})),ka=aa.select(\".bars2Wrap\").datum(V.filter(function(a){return!a.disabled})),la=aa.select(\".stack2Wrap\").datum(X.filter(function(a){return!a.disabled})),ma=W.length?W.map(function(a){return a.values}).reduce(function(a,b){return a.map(function(a,c){return{x:a.x,y:a.y+b[c].y}})}).concat([{x:0,y:0}]):[],na=X.length?X.map(function(a){return a.values}).reduce(function(a,b){return a.map(function(a,c){return{x:a.x,y:a.y+b[c].y}})}).concat([{x:0,y:0}]):[];s.domain(c||d3.extent(d3.merge(Y).concat(ma),function(a){return a.y})).range([0,P]),t.domain(d||d3.extent(d3.merge(Z).concat(na),function(a){return a.y})).range([0,P]),u.yDomain(s.domain()),w.yDomain(s.domain()),y.yDomain(s.domain()),A.yDomain(s.domain()),v.yDomain(t.domain()),x.yDomain(t.domain()),z.yDomain(t.domain()),B.yDomain(t.domain()),W.length&&d3.transition(ha).call(A),X.length&&d3.transition(la).call(B),U.length&&d3.transition(ga).call(y),V.length&&d3.transition(ka).call(z),Q.length&&d3.transition(ea).call(u),R.length&&d3.transition(ia).call(v),S.length&&d3.transition(fa).call(w),T.length&&d3.transition(ja).call(x),C._ticks(a.utils.calcTicksX(O/100,j)).tickSize(-P,0),aa.select(\".nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+P+\")\"),d3.transition(aa.select(\".nv-x.nv-axis\")).call(C),D._ticks(a.utils.calcTicksY(P/36,j)).tickSize(-O,0),d3.transition(aa.select(\".nv-y1.nv-axis\")).call(D),E._ticks(a.utils.calcTicksY(P/36,j)).tickSize(-O,0),d3.transition(aa.select(\".nv-y2.nv-axis\")).call(E),aa.select(\".nv-y1.nv-axis\").classed(\"nv-disabled\",Y.length?!1:!0).attr(\"transform\",\"translate(\"+r.range()[0]+\",0)\"),aa.select(\".nv-y2.nv-axis\").classed(\"nv-disabled\",Z.length?!1:!0).attr(\"transform\",\"translate(\"+r.range()[1]+\",0)\"),F.dispatch.on(\"stateChange\",function(a){b.update()}),p&&(o.width(O).height(P).margin({left:e.left,top:e.top}).svgContainer(N).xScale(r),$.select(\".nv-interactive\").call(o)),p?(o.dispatch.on(\"elementMousemove\",function(c){L();var d,e,g,h=[];j.filter(function(a,b){return a.seriesIndex=b,!a.disabled}).forEach(function(i,j){var k=r.domain(),l=i.values.filter(function(a,c){return b.x()(a,c)>=k[0]&&b.x()(a,c)<=k[1]});e=a.interactiveBisect(l,c.pointXValue,b.x());var m=l[e],n=b.y()(m,e);null!==n&&M(j,e,!0),void 0!==m&&(void 0===d&&(d=m),void 0===g&&(g=r(b.x()(m,e))),h.push({key:i.key,value:n,color:f(i,i.seriesIndex),data:m,yAxis:2==i.yAxis?E:D}))});var i=function(a,b){var c=h[b].yAxis;return null==a?\"N/A\":c.tickFormat()(a)};o.tooltip.headerFormatter(function(a,b){return C.tickFormat()(a,b)}).valueFormatter(o.tooltip.valueFormatter()||i).data({value:b.x()(d,e),index:e,series:h})(),o.renderGuideLine(g)}),o.dispatch.on(\"elementMouseout\",function(a){L()})):(u.dispatch.on(\"elementMouseover.tooltip\",n),v.dispatch.on(\"elementMouseover.tooltip\",n),u.dispatch.on(\"elementMouseout.tooltip\",function(a){G.hidden(!0)}),v.dispatch.on(\"elementMouseout.tooltip\",function(a){G.hidden(!0)}),w.dispatch.on(\"elementMouseover.tooltip\",H),x.dispatch.on(\"elementMouseover.tooltip\",H),w.dispatch.on(\"elementMouseout.tooltip\",function(a){G.hidden(!0)}),x.dispatch.on(\"elementMouseout.tooltip\",function(a){G.hidden(!0)}),A.dispatch.on(\"elementMouseover.tooltip\",J),B.dispatch.on(\"elementMouseover.tooltip\",J),A.dispatch.on(\"elementMouseout.tooltip\",function(a){G.hidden(!0)}),B.dispatch.on(\"elementMouseout.tooltip\",function(a){G.hidden(!0)}),y.dispatch.on(\"elementMouseover.tooltip\",K),z.dispatch.on(\"elementMouseover.tooltip\",K),y.dispatch.on(\"elementMouseout.tooltip\",function(a){G.hidden(!0)}),z.dispatch.on(\"elementMouseout.tooltip\",function(a){G.hidden(!0)}),y.dispatch.on(\"elementMousemove.tooltip\",function(a){G()}),z.dispatch.on(\"elementMousemove.tooltip\",function(a){G()}))}),b}var c,d,e={top:30,right:20,bottom:50,left:60},f=a.utils.defaultColor(),g=null,h=null,i=!0,j=null,k=function(a){return a.x},l=function(a){return a.y},m=\"linear\",n=!0,o=a.interactiveGuideline(),p=!1,q=\" (right axis)\",r=d3.scale.linear(),s=d3.scale.linear(),t=d3.scale.linear(),u=a.models.line().yScale(s),v=a.models.line().yScale(t),w=a.models.scatter().yScale(s),x=a.models.scatter().yScale(t),y=a.models.multiBar().stacked(!1).yScale(s),z=a.models.multiBar().stacked(!1).yScale(t),A=a.models.stackedArea().yScale(s),B=a.models.stackedArea().yScale(t),C=a.models.axis().scale(r).orient(\"bottom\").tickPadding(5),D=a.models.axis().scale(s).orient(\"left\"),E=a.models.axis().scale(t).orient(\"right\"),F=a.models.legend().height(30),G=a.models.tooltip(),H=d3.dispatch(),I=[u,v,w,x,y,z,A,B];return b.dispatch=H,b.legend=F,b.lines1=u,b.lines2=v,b.scatters1=w,b.scatters2=x,b.bars1=y,b.bars2=z,b.stack1=A,b.stack2=B,b.xAxis=C,b.yAxis1=D,b.yAxis2=E,b.tooltip=G,b.interactiveLayer=o,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return g},set:function(a){g=a}},height:{get:function(){return h},set:function(a){h=a}},showLegend:{get:function(){return i},set:function(a){i=a}},yDomain1:{get:function(){return c},set:function(a){c=a}},yDomain2:{get:function(){return d},set:function(a){d=a}},noData:{get:function(){return j},set:function(a){j=a}},interpolate:{get:function(){return m},set:function(a){m=a}},legendRightAxisHint:{get:function(){return q},set:function(a){q=a}},margin:{get:function(){return e},set:function(a){e.top=void 0!==a.top?a.top:e.top,e.right=void 0!==a.right?a.right:e.right,e.bottom=void 0!==a.bottom?a.bottom:e.bottom,e.left=void 0!==a.left?a.left:e.left}},color:{get:function(){return f},set:function(b){f=a.utils.getColor(b)}},x:{get:function(){return k},set:function(a){k=a,u.x(a),v.x(a),w.x(a),x.x(a),y.x(a),z.x(a),A.x(a),B.x(a)}},y:{get:function(){return l},set:function(a){l=a,u.y(a),v.y(a),w.y(a),x.y(a),A.y(a),B.y(a),y.y(a),z.y(a)}},useVoronoi:{get:function(){return n},set:function(a){n=a,u.useVoronoi(a),v.useVoronoi(a),A.useVoronoi(a),B.useVoronoi(a)}},useInteractiveGuideline:{get:function(){return p},set:function(a){p=a,p&&(u.interactive(!1),u.useVoronoi(!1),v.interactive(!1),v.useVoronoi(!1),A.interactive(!1),A.useVoronoi(!1),B.interactive(!1),B.useVoronoi(!1),w.interactive(!1),x.interactive(!1))}}}),a.utils.initOptions(b),b},a.models.ohlcBar=function(){\"use strict\";function b(y){return y.each(function(b){k=d3.select(this);var y=a.utils.availableWidth(h,k,g),A=a.utils.availableHeight(i,k,g);a.utils.initSVG(k);var B=y/b[0].values.length*.9;l.domain(c||d3.extent(b[0].values.map(n).concat(t))),v?l.range(e||[.5*y/b[0].values.length,y*(b[0].values.length-.5)/b[0].values.length]):l.range(e||[5+B/2,y-B/2-5]),m.domain(d||[d3.min(b[0].values.map(s).concat(u)),d3.max(b[0].values.map(r).concat(u))]).range(f||[A,0]),l.domain()[0]===l.domain()[1]&&(l.domain()[0]?l.domain([l.domain()[0]-.01*l.domain()[0],l.domain()[1]+.01*l.domain()[1]]):l.domain([-1,1])),m.domain()[0]===m.domain()[1]&&(m.domain()[0]?m.domain([m.domain()[0]+.01*m.domain()[0],m.domain()[1]-.01*m.domain()[1]]):m.domain([-1,1]));var C=d3.select(this).selectAll(\"g.nv-wrap.nv-ohlcBar\").data([b[0].values]),D=C.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-ohlcBar\"),E=D.append(\"defs\"),F=D.append(\"g\"),G=C.select(\"g\");F.append(\"g\").attr(\"class\",\"nv-ticks\"),C.attr(\"transform\",\"translate(\"+g.left+\",\"+g.top+\")\"),k.on(\"click\",function(a,b){z.chartClick({data:a,index:b,pos:d3.event,id:j})}),E.append(\"clipPath\").attr(\"id\",\"nv-chart-clip-path-\"+j).append(\"rect\"),C.select(\"#nv-chart-clip-path-\"+j+\" rect\").attr(\"width\",y).attr(\"height\",A),G.attr(\"clip-path\",w?\"url(#nv-chart-clip-path-\"+j+\")\":\"\");var H=C.select(\".nv-ticks\").selectAll(\".nv-tick\").data(function(a){return a});H.exit().remove(),H.enter().append(\"path\").attr(\"class\",function(a,b,c){return(p(a,b)>q(a,b)?\"nv-tick negative\":\"nv-tick positive\")+\" nv-tick-\"+c+\"-\"+b}).attr(\"d\",function(a,b){return\"m0,0l0,\"+(m(p(a,b))-m(r(a,b)))+\"l\"+-B/2+\",0l\"+B/2+\",0l0,\"+(m(s(a,b))-m(p(a,b)))+\"l0,\"+(m(q(a,b))-m(s(a,b)))+\"l\"+B/2+\",0l\"+-B/2+\",0z\"}).attr(\"transform\",function(a,b){return\"translate(\"+l(n(a,b))+\",\"+m(r(a,b))+\")\"}).attr(\"fill\",function(a,b){return x[0]}).attr(\"stroke\",function(a,b){return x[0]}).attr(\"x\",0).attr(\"y\",function(a,b){return m(Math.max(0,o(a,b)))}).attr(\"height\",function(a,b){return Math.abs(m(o(a,b))-m(0))}),H.attr(\"class\",function(a,b,c){return(p(a,b)>q(a,b)?\"nv-tick negative\":\"nv-tick positive\")+\" nv-tick-\"+c+\"-\"+b}),d3.transition(H).attr(\"transform\",function(a,b){return\"translate(\"+l(n(a,b))+\",\"+m(r(a,b))+\")\"}).attr(\"d\",function(a,c){var d=y/b[0].values.length*.9;return\"m0,0l0,\"+(m(p(a,c))-m(r(a,c)))+\"l\"+-d/2+\",0l\"+d/2+\",0l0,\"+(m(s(a,c))-m(p(a,c)))+\"l0,\"+(m(q(a,c))-m(s(a,c)))+\"l\"+d/2+\",0l\"+-d/2+\",0z\"})}),b}var c,d,e,f,g={top:0,right:0,bottom:0,left:0},h=null,i=null,j=Math.floor(1e4*Math.random()),k=null,l=d3.scale.linear(),m=d3.scale.linear(),n=function(a){return a.x},o=function(a){return a.y},p=function(a){return a.open},q=function(a){return a.close},r=function(a){return a.high},s=function(a){return a.low},t=[],u=[],v=!1,w=!0,x=a.utils.defaultColor(),y=!1,z=d3.dispatch(\"stateChange\",\"changeState\",\"renderEnd\",\"chartClick\",\"elementClick\",\"elementDblClick\",\"elementMouseover\",\"elementMouseout\",\"elementMousemove\");return b.highlightPoint=function(a,c){b.clearHighlights(),k.select(\".nv-ohlcBar .nv-tick-0-\"+a).classed(\"hover\",c)},b.clearHighlights=function(){k.select(\".nv-ohlcBar .nv-tick.hover\").classed(\"hover\",!1)},b.dispatch=z,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return h},set:function(a){h=a}},height:{get:function(){return i},set:function(a){i=a}},xScale:{get:function(){return l},set:function(a){l=a}},yScale:{get:function(){return m},set:function(a){m=a}},xDomain:{get:function(){return c},set:function(a){c=a}},yDomain:{get:function(){return d},set:function(a){d=a}},xRange:{get:function(){return e},set:function(a){e=a}},yRange:{get:function(){return f},set:function(a){f=a}},forceX:{get:function(){return t},set:function(a){t=a}},forceY:{get:function(){return u},set:function(a){u=a}},padData:{get:function(){return v},set:function(a){v=a}},clipEdge:{get:function(){return w},set:function(a){w=a}},id:{get:function(){return j},set:function(a){j=a}},interactive:{get:function(){return y},set:function(a){y=a}},x:{get:function(){return n},set:function(a){n=a}},y:{get:function(){return o},set:function(a){o=a}},open:{get:function(){return p()},set:function(a){p=a}},close:{get:function(){return q()},set:function(a){q=a}},high:{get:function(){return r},set:function(a){r=a}},low:{get:function(){return s},set:function(a){s=a}},margin:{get:function(){return g},set:function(a){g.top=void 0!=a.top?a.top:g.top,g.right=void 0!=a.right?a.right:g.right,g.bottom=void 0!=a.bottom?a.bottom:g.bottom,g.left=void 0!=a.left?a.left:g.left}},color:{get:function(){return x},set:function(b){x=a.utils.getColor(b)}}}),a.utils.initOptions(b),b},a.models.parallelCoordinates=function(){\"use strict\";function b(B){return A.reset(),B.each(function(b){function A(a){return x(o.map(function(b){if(isNaN(a.values[b.key])||isNaN(parseFloat(a.values[b.key]))||O){var c=l[b.key].domain(),d=l[b.key].range(),e=c[0]-(c[1]-c[0])/9;if(v.indexOf(b.key)<0){var f=d3.scale.linear().domain([e,c[1]]).range([j-12,d[1]]);l[b.key].brush.y(f),v.push(b.key)}if(isNaN(a.values[b.key])||isNaN(parseFloat(a.values[b.key])))return[k(b.key),l[b.key](e)]}return void 0!==U&&(v.length>0||O?(U.style(\"display\",\"inline\"),V.style(\"display\",\"inline\")):(U.style(\"display\",\"none\"),V.style(\"display\",\"none\"))),[k(b.key),l[b.key](a.values[b.key])]}))}function B(a){s.forEach(function(b){var c=l[b.dimension].brush.y().domain();b.hasOnlyNaN&&(b.extent[1]=(l[b.dimension].domain()[1]-c[0])*(b.extent[1]-b.extent[0])/(N[b.dimension]-b.extent[0])+c[0]),b.hasNaN&&(b.extent[0]=c[0]),a&&l[b.dimension].brush.extent(b.extent)}),e.select(\".nv-brushBackground\").each(function(a){d3.select(this).call(l[a.key].brush)}).selectAll(\"rect\").attr(\"x\",-8).attr(\"width\",16),F()}function C(){q===!1&&(q=!0,B(!0))}function D(){$=p.filter(function(a){return!l[a].brush.empty()}),_=$.map(function(a){return l[a].brush.extent()}),s=[],$.forEach(function(a,b){s[b]={dimension:a,extent:_[b],hasNaN:!1,hasOnlyNaN:!1}}),t=[],c.style(\"display\",function(a){var b=$.every(function(b,c){return(isNaN(a.values[b])||isNaN(parseFloat(a.values[b])))&&_[c][0]==l[b].brush.y().domain()[0]?!0:_[c][0]<=a.values[b]&&a.values[b]<=_[c][1]&&!isNaN(parseFloat(a.values[b]))});return b&&t.push(a),b?null:\"none\"}),F(),z.brush({filters:s,active:t})}function E(){var a=$.length>0?!0:!1;s.forEach(function(a){a.extent[0]===l[a.dimension].brush.y().domain()[0]&&v.indexOf(a.dimension)>=0&&(a.hasNaN=!0),a.extent[1]<l[a.dimension].domain()[0]&&(a.hasOnlyNaN=!0)}),z.brushEnd(t,a)}function F(){e.select(\".nv-axis\").each(function(a,b){var c=s.filter(function(b){return b.dimension==a.key});P[a.key]=l[a.key].domain(),0!=c.length&&q&&(P[a.key]=[],c[0].extent[1]>l[a.key].domain()[0]&&(P[a.key]=[c[0].extent[1]]),c[0].extent[0]>=l[a.key].domain()[0]&&P[a.key].push(c[0].extent[0])),d3.select(this).call(y.scale(l[a.key]).tickFormat(a.format).tickValues(P[a.key]))})}function G(a){u[a.key]=this.parentNode.__origin__=k(a.key),d.attr(\"visibility\",\"hidden\")}function H(a){u[a.key]=Math.min(i,Math.max(0,this.parentNode.__origin__+=d3.event.x)),c.attr(\"d\",A),o.sort(function(a,b){return J(a.key)-J(b.key)}),o.forEach(function(a,b){return a.currentPosition=b}),k.domain(o.map(function(a){return a.key})),e.attr(\"transform\",function(a){return\"translate(\"+J(a.key)+\")\"})}function I(a,b){delete this.parentNode.__origin__,delete u[a.key],d3.select(this.parentNode).attr(\"transform\",\"translate(\"+k(a.key)+\")\"),c.attr(\"d\",A),d.attr(\"d\",A).attr(\"visibility\",null),z.dimensionsOrder(o)}function J(a){var b=u[a];return null==b?k(a):b}var K=d3.select(this);if(i=a.utils.availableWidth(g,K,f),j=a.utils.availableHeight(h,K,f),a.utils.initSVG(K),void 0===b[0].values){var L=[];b.forEach(function(a){var b={},c=Object.keys(a);c.forEach(function(c){\"name\"!==c&&(b[c]=a[c])}),L.push({key:a.name,values:b})}),b=L}var M=b.map(function(a){return a.values});0===t.length&&(t=b),p=n.sort(function(a,b){return a.currentPosition-b.currentPosition}).map(function(a){return a.key}),o=n.filter(function(a){return!a.disabled}),k.rangePoints([0,i],1).domain(o.map(function(a){return a.key}));var N={},O=!1,P=[];p.forEach(function(a){var b=d3.extent(M,function(b){return+b[a]}),c=b[0],d=b[1],e=!1;(isNaN(c)||isNaN(d))&&(e=!0,c=0,d=0),c===d&&(c-=1,d+=1);var f=s.filter(function(b){return b.dimension==a});0!==f.length&&(e?(c=l[a].domain()[0],d=l[a].domain()[1]):!f[0].hasOnlyNaN&&q?(c=c>f[0].extent[0]?f[0].extent[0]:c,d=d<f[0].extent[1]?f[0].extent[1]:d):f[0].hasNaN&&(d=d<f[0].extent[1]?f[0].extent[1]:d,N[a]=l[a].domain()[1],O=!0)),l[a]=d3.scale.linear().domain([c,d]).range([.9*(j-12),0]),v=[],l[a].brush=d3.svg.brush().y(l[a]).on(\"brushstart\",C).on(\"brush\",D).on(\"brushend\",E)});var Q=K.selectAll(\"g.nv-wrap.nv-parallelCoordinates\").data([b]),R=Q.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-parallelCoordinates\"),S=R.append(\"g\"),T=Q.select(\"g\");S.append(\"g\").attr(\"class\",\"nv-parallelCoordinates background\"),S.append(\"g\").attr(\"class\",\"nv-parallelCoordinates foreground\"),S.append(\"g\").attr(\"class\",\"nv-parallelCoordinates missingValuesline\"),Q.attr(\"transform\",\"translate(\"+f.left+\",\"+f.top+\")\"),x.interpolate(\"cardinal\").tension(w),y.orient(\"left\");var U,V,W=d3.behavior.drag().on(\"dragstart\",G).on(\"drag\",H).on(\"dragend\",I),X=k.range()[1]-k.range()[0];if(!isNaN(X)){var Y=[0+X/2,j-12,i-X/2,j-12];U=Q.select(\".missingValuesline\").selectAll(\"line\").data([Y]),U.enter().append(\"line\"),U.exit().remove(),U.attr(\"x1\",function(a){return a[0]}).attr(\"y1\",function(a){return a[1]}).attr(\"x2\",function(a){return a[2]}).attr(\"y2\",function(a){return a[3]}),V=Q.select(\".missingValuesline\").selectAll(\"text\").data([m]),V.append(\"text\").data([m]),V.enter().append(\"text\"),V.exit().remove(),V.attr(\"y\",j).attr(\"x\",i-92-X/2).text(function(a){return a})}d=Q.select(\".background\").selectAll(\"path\").data(b),d.enter().append(\"path\"),d.exit().remove(),d.attr(\"d\",A),c=Q.select(\".foreground\").selectAll(\"path\").data(b),c.enter().append(\"path\"),c.exit().remove(),c.attr(\"d\",A).style(\"stroke-width\",function(a,b){return isNaN(a.strokeWidth)&&(a.strokeWidth=1),a.strokeWidth}).attr(\"stroke\",function(a,b){return a.color||r(a,b)}),c.on(\"mouseover\",function(a,b){d3.select(this).classed(\"hover\",!0).style(\"stroke-width\",a.strokeWidth+2+\"px\").style(\"stroke-opacity\",1),z.elementMouseover({label:a.name,color:a.color||r(a,b),values:a.values,dimensions:o})}),c.on(\"mouseout\",function(a,b){d3.select(this).classed(\"hover\",!1).style(\"stroke-width\",a.strokeWidth+\"px\").style(\"stroke-opacity\",.7),z.elementMouseout({label:a.name,index:b})}),c.on(\"mousemove\",function(a,b){z.elementMousemove()}),c.on(\"click\",function(a){z.elementClick({id:a.id})}),e=T.selectAll(\".dimension\").data(o);var Z=e.enter().append(\"g\").attr(\"class\",\"nv-parallelCoordinates dimension\");e.attr(\"transform\",function(a){return\"translate(\"+k(a.key)+\",0)\"}),Z.append(\"g\").attr(\"class\",\"nv-axis\"),Z.append(\"text\").attr(\"class\",\"nv-label\").style(\"cursor\",\"move\").attr(\"dy\",\"-1em\").attr(\"text-anchor\",\"middle\").on(\"mouseover\",function(a,b){z.elementMouseover({label:a.tooltip||a.key,color:a.color})}).on(\"mouseout\",function(a,b){z.elementMouseout({label:a.tooltip})}).on(\"mousemove\",function(a,b){z.elementMousemove()}).call(W),Z.append(\"g\").attr(\"class\",\"nv-brushBackground\"),e.exit().remove(),e.select(\".nv-label\").text(function(a){return a.key}),B(q);var $=p.filter(function(a){return!l[a].brush.empty()}),_=$.map(function(a){return l[a].brush.extent()}),aa=t.slice(0);t=[],c.style(\"display\",function(a){var b=$.every(function(b,c){return(isNaN(a.values[b])||isNaN(parseFloat(a.values[b])))&&_[c][0]==l[b].brush.y().domain()[0]?!0:_[c][0]<=a.values[b]&&a.values[b]<=_[c][1]&&!isNaN(parseFloat(a.values[b]))});return b&&t.push(a),b?null:\"none\"}),(s.length>0||!a.utils.arrayEquals(t,aa))&&z.activeChanged(t)}),b}var c,d,e,f={top:30,right:0,bottom:10,left:0},g=null,h=null,i=null,j=null,k=d3.scale.ordinal(),l={},m=\"undefined values\",n=[],o=[],p=[],q=!0,r=a.utils.defaultColor(),s=[],t=[],u=[],v=[],w=1,x=d3.svg.line(),y=d3.svg.axis(),z=d3.dispatch(\"brushstart\",\"brush\",\"brushEnd\",\"dimensionsOrder\",\"stateChange\",\"elementClick\",\"elementMouseover\",\"elementMouseout\",\"elementMousemove\",\"renderEnd\",\"activeChanged\"),A=a.utils.renderWatch(z);return b.dispatch=z,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return g},set:function(a){g=a}},height:{get:function(){return h},set:function(a){h=a}},dimensionData:{get:function(){return n},set:function(a){n=a}},displayBrush:{get:function(){return q},set:function(a){q=a}},filters:{get:function(){return s},set:function(a){s=a}},active:{get:function(){return t},set:function(a){t=a}},lineTension:{get:function(){return w},set:function(a){w=a}},undefinedValuesLabel:{get:function(){return m},set:function(a){m=a}},dimensions:{get:function(){return n.map(function(a){return a.key})},set:function(b){a.deprecated(\"dimensions\",\"use dimensionData instead\"),0===n.length?b.forEach(function(a){n.push({key:a})}):b.forEach(function(a,b){n[b].key=a})}},dimensionNames:{get:function(){return n.map(function(a){return a.key})},set:function(b){a.deprecated(\"dimensionNames\",\"use dimensionData instead\"),p=[],0===n.length?b.forEach(function(a){n.push({key:a})}):b.forEach(function(a,b){n[b].key=a})}},dimensionFormats:{get:function(){return n.map(function(a){return a.format})},set:function(b){a.deprecated(\"dimensionFormats\",\"use dimensionData instead\"),0===n.length?b.forEach(function(a){n.push({format:a})}):b.forEach(function(a,b){n[b].format=a})}},margin:{get:function(){return f},set:function(a){f.top=void 0!==a.top?a.top:f.top,f.right=void 0!==a.right?a.right:f.right,f.bottom=void 0!==a.bottom?a.bottom:f.bottom,f.left=void 0!==a.left?a.left:f.left}},color:{get:function(){return r},set:function(b){r=a.utils.getColor(b)}}}),a.utils.initOptions(b),b},a.models.parallelCoordinatesChart=function(){\"use strict\";function b(e){return r.reset(),r.models(c),e.each(function(e){var j=d3.select(this);a.utils.initSVG(j);var o=a.utils.availableWidth(g,j,f),p=a.utils.availableHeight(h,j,f);if(b.update=function(){j.call(b)},b.container=this,k.setter(t(l),b.update).getter(s(l)).update(),k.disabled=l.map(function(a){return!!a.disabled}),l=l.map(function(a){return a.disabled=!!a.disabled,a}),l.forEach(function(a,b){a.originalPosition=isNaN(a.originalPosition)?b:a.originalPosition,a.currentPosition=isNaN(a.currentPosition)?b:a.currentPosition}),!n){var r;n={};for(r in k)k[r]instanceof Array?n[r]=k[r].slice(0):n[r]=k[r]}if(!e||!e.length)return a.utils.noData(b,j),b;j.selectAll(\".nv-noData\").remove();var u=j.selectAll(\"g.nv-wrap.nv-parallelCoordinatesChart\").data([e]),v=u.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-parallelCoordinatesChart\").append(\"g\"),w=u.select(\"g\");v.append(\"g\").attr(\"class\",\"nv-parallelCoordinatesWrap\"),v.append(\"g\").attr(\"class\",\"nv-legendWrap\"),w.select(\"rect\").attr(\"width\",o).attr(\"height\",p>0?p:0),i?(d.width(o).color(function(a){return\"rgb(188,190,192)\"}),w.select(\".nv-legendWrap\").datum(l.sort(function(a,b){return a.originalPosition-b.originalPosition})).call(d),d.height()>f.top&&(f.top=d.height(),p=a.utils.availableHeight(h,j,f)),u.select(\".nv-legendWrap\").attr(\"transform\",\"translate( 0 ,\"+-f.top+\")\")):w.select(\".nv-legendWrap\").selectAll(\"*\").remove(),u.attr(\"transform\",\"translate(\"+f.left+\",\"+f.top+\")\"),c.width(o).height(p).dimensionData(l).displayBrush(m);var x=w.select(\".nv-parallelCoordinatesWrap \").datum(e);x.transition().call(c),c.dispatch.on(\"brushEnd\",function(a,b){b?(m=!0,q.brushEnd(a)):m=!1}),d.dispatch.on(\"stateChange\",function(a){for(var c in a)k[c]=a[c];q.stateChange(k),b.update()}),c.dispatch.on(\"dimensionsOrder\",function(a){l.sort(function(a,b){return a.currentPosition-b.currentPosition});var b=!1;l.forEach(function(a,c){a.currentPosition=c,a.currentPosition!==a.originalPosition&&(b=!0)}),q.dimensionsOrder(l,b)}),q.on(\"changeState\",function(a){\"undefined\"!=typeof a.disabled&&(l.forEach(function(b,c){b.disabled=a.disabled[c]}),k.disabled=a.disabled),b.update()})}),r.renderEnd(\"parraleleCoordinateChart immediate\"),b}var c=a.models.parallelCoordinates(),d=a.models.legend(),e=a.models.tooltip(),f=(a.models.tooltip(),{top:0,right:0,bottom:0,left:0}),g=null,h=null,i=!0,j=a.utils.defaultColor(),k=a.utils.state(),l=[],m=!0,n=null,o=null,p=\"undefined\",q=d3.dispatch(\"dimensionsOrder\",\"brushEnd\",\"stateChange\",\"changeState\",\"renderEnd\"),r=a.utils.renderWatch(q),s=function(a){return function(){return{active:a.map(function(a){return!a.disabled})}}},t=function(a){return function(b){void 0!==b.active&&a.forEach(function(a,c){a.disabled=!b.active[c]})}};return e.contentGenerator(function(a){var b='<table><thead><tr><td class=\"legend-color-guide\"><div style=\"background-color:'+a.color+'\"></div></td><td><strong>'+a.key+\"</strong></td></tr></thead>\";return 0!==a.series.length&&(b+='<tbody><tr><td height =\"10px\"></td></tr>',a.series.forEach(function(a){b=b+'<tr><td class=\"legend-color-guide\"><div style=\"background-color:'+a.color+'\"></div></td><td class=\"key\">'+a.key+'</td><td class=\"value\">'+a.value+\"</td></tr>\"}),b+=\"</tbody>\"),b+=\"</table>\"}),c.dispatch.on(\"elementMouseover.tooltip\",function(a){var b={key:a.label,color:a.color,series:[]};a.values&&(Object.keys(a.values).forEach(function(c){var d=a.dimensions.filter(function(a){return a.key===c})[0];if(d){var e;e=isNaN(a.values[c])||isNaN(parseFloat(a.values[c]))?p:d.format(a.values[c]),b.series.push({idx:d.currentPosition,key:c,value:e,color:d.color})}}),b.series.sort(function(a,b){return a.idx-b.idx})),e.data(b).hidden(!1)}),c.dispatch.on(\"elementMouseout.tooltip\",function(a){e.hidden(!0)}),c.dispatch.on(\"elementMousemove.tooltip\",function(){e()}),b.dispatch=q,b.parallelCoordinates=c,b.legend=d,b.tooltip=e,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return g},set:function(a){g=a}},height:{get:function(){return h},set:function(a){h=a}},showLegend:{get:function(){return i},set:function(a){i=a}},defaultState:{get:function(){return n},set:function(a){n=a}},dimensionData:{get:function(){return l},set:function(a){l=a}},displayBrush:{get:function(){return m},set:function(a){m=a}},noData:{get:function(){return o},set:function(a){o=a}},nanValue:{get:function(){return p},set:function(a){p=a}},margin:{get:function(){return f},set:function(a){f.top=void 0!==a.top?a.top:f.top,f.right=void 0!==a.right?a.right:f.right,f.bottom=void 0!==a.bottom?a.bottom:f.bottom,f.left=void 0!==a.left?a.left:f.left}},color:{get:function(){return j},set:function(b){j=a.utils.getColor(b),d.color(j),c.color(j)}}}),a.utils.inheritOptions(b,c),a.utils.initOptions(b),b},a.models.pie=function(){\"use strict\";function b(F){return E.reset(),F.each(function(b){function F(a,b){a.endAngle=isNaN(a.endAngle)?0:a.endAngle,a.startAngle=isNaN(a.startAngle)?0:a.startAngle,p||(a.innerRadius=0);var c=d3.interpolate(this._current,a);return this._current=c(0),function(a){return C[b](c(a))}}var G=d-c.left-c.right,H=e-c.top-c.bottom,I=Math.min(G,H)/2,J=[],K=[];if(i=d3.select(this),0===A.length)for(var L=I-I/5,M=y*I,N=0;N<b[0].length;N++)J.push(L),K.push(M);else r?(J=A.map(function(a){return(a.outer-a.outer/5)*I}),K=A.map(function(a){return(a.inner-a.inner/5)*I}),y=d3.min(A.map(function(a){return a.inner-a.inner/5}))):(J=A.map(function(a){return a.outer*I}),K=A.map(function(a){return a.inner*I}),y=d3.min(A.map(function(a){return a.inner})));a.utils.initSVG(i);var O=i.selectAll(\".nv-wrap.nv-pie\").data(b),P=O.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-pie nv-chart-\"+h),Q=P.append(\"g\"),R=O.select(\"g\"),S=Q.append(\"g\").attr(\"class\",\"nv-pie\");Q.append(\"g\").attr(\"class\",\"nv-pieLabels\"),O.attr(\"transform\",\"translate(\"+c.left+\",\"+c.top+\")\"),R.select(\".nv-pie\").attr(\"transform\",\"translate(\"+G/2+\",\"+H/2+\")\"),R.select(\".nv-pieLabels\").attr(\"transform\",\"translate(\"+G/2+\",\"+H/2+\")\"),i.on(\"click\",function(a,b){B.chartClick({data:a,index:b,pos:d3.event,id:h})}),C=[],D=[];for(var N=0;N<b[0].length;N++){var T=d3.svg.arc().outerRadius(J[N]),U=d3.svg.arc().outerRadius(J[N]+5);u!==!1&&(T.startAngle(u),U.startAngle(u)),w!==!1&&(T.endAngle(w),U.endAngle(w)),p&&(T.innerRadius(K[N]),U.innerRadius(K[N])),T.cornerRadius&&x&&(T.cornerRadius(x),U.cornerRadius(x)),C.push(T),D.push(U)}var V=d3.layout.pie().sort(null).value(function(a){return a.disabled?0:g(a)});V.padAngle&&v&&V.padAngle(v),p&&q&&(S.append(\"text\").attr(\"class\",\"nv-pie-title\"),O.select(\".nv-pie-title\").style(\"text-anchor\",\"middle\").text(function(a){return q}).style(\"font-size\",Math.min(G,H)*y*2/(q.length+2)+\"px\").attr(\"dy\",\"0.35em\").attr(\"transform\",function(a,b){return\"translate(0, \"+s+\")\"}));var W=O.select(\".nv-pie\").selectAll(\".nv-slice\").data(V),X=O.select(\".nv-pieLabels\").selectAll(\".nv-label\").data(V);W.exit().remove(),X.exit().remove();var Y=W.enter().append(\"g\");Y.attr(\"class\",\"nv-slice\"),Y.on(\"mouseover\",function(a,b){d3.select(this).classed(\"hover\",!0),r&&d3.select(this).select(\"path\").transition().duration(70).attr(\"d\",D[b]),B.elementMouseover({data:a.data,index:b,color:d3.select(this).style(\"fill\"),percent:(a.endAngle-a.startAngle)/(2*Math.PI)})}),Y.on(\"mouseout\",function(a,b){d3.select(this).classed(\"hover\",!1),r&&d3.select(this).select(\"path\").transition().duration(50).attr(\"d\",C[b]),B.elementMouseout({data:a.data,index:b})}),Y.on(\"mousemove\",function(a,b){B.elementMousemove({data:a.data,index:b})}),Y.on(\"click\",function(a,b){var c=this;B.elementClick({data:a.data,index:b,color:d3.select(this).style(\"fill\"),event:d3.event,element:c})}),Y.on(\"dblclick\",function(a,b){B.elementDblClick({data:a.data,index:b,color:d3.select(this).style(\"fill\")})}),W.attr(\"fill\",function(a,b){return j(a.data,b)}),W.attr(\"stroke\",function(a,b){return j(a.data,b)});Y.append(\"path\").each(function(a){this._current=a});if(W.select(\"path\").transition().duration(z).attr(\"d\",function(a,b){return C[b](a)}).attrTween(\"d\",F),l){for(var Z=[],N=0;N<b[0].length;N++)Z.push(C[N]),m?p&&(Z[N]=d3.svg.arc().outerRadius(C[N].outerRadius()),u!==!1&&Z[N].startAngle(u),w!==!1&&Z[N].endAngle(w)):p||Z[N].innerRadius(0);X.enter().append(\"g\").classed(\"nv-label\",!0).each(function(a,b){var c=d3.select(this);c.attr(\"transform\",function(a,b){if(t){a.outerRadius=J[b]+10,a.innerRadius=J[b]+15;var c=(a.startAngle+a.endAngle)/2*(180/Math.PI);return(a.startAngle+a.endAngle)/2<Math.PI?c-=90:c+=90,\"translate(\"+Z[b].centroid(a)+\") rotate(\"+c+\")\"}return a.outerRadius=I+10,a.innerRadius=I+15,\"translate(\"+Z[b].centroid(a)+\")\"}),c.append(\"rect\").style(\"stroke\",\"#fff\").style(\"fill\",\"#fff\").attr(\"rx\",3).attr(\"ry\",3),c.append(\"text\").style(\"text-anchor\",t?(a.startAngle+a.endAngle)/2<Math.PI?\"start\":\"end\":\"middle\").style(\"fill\",\"#000\")});var $={},_=14,aa=140,ba=function(a){return Math.floor(a[0]/aa)*aa+\",\"+Math.floor(a[1]/_)*_},ca=function(a){return(a.endAngle-a.startAngle)/(2*Math.PI)};X.watchTransition(E,\"pie labels\").attr(\"transform\",function(a,b){if(t){a.outerRadius=J[b]+10,a.innerRadius=J[b]+15;var c=(a.startAngle+a.endAngle)/2*(180/Math.PI);return(a.startAngle+a.endAngle)/2<Math.PI?c-=90:c+=90,\"translate(\"+Z[b].centroid(a)+\") rotate(\"+c+\")\"}a.outerRadius=I+10,a.innerRadius=I+15;var d=Z[b].centroid(a),e=ca(a);if(a.value&&e>=o){var f=ba(d);$[f]&&(d[1]-=_),$[ba(d)]=!0}return\"translate(\"+d+\")\"}),X.select(\".nv-label text\").style(\"text-anchor\",function(a,b){return t?(a.startAngle+a.endAngle)/2<Math.PI?\"start\":\"end\":\"middle\"}).text(function(a,b){var c=ca(a),d=\"\";if(!a.value||o>c)return\"\";if(\"function\"==typeof n)d=n(a,b,{key:f(a.data),value:g(a.data),percent:k(c)});else switch(n){case\"key\":d=f(a.data);break;case\"value\":d=k(g(a.data));break;case\"percent\":d=d3.format(\"%\")(c)}return d})}}),E.renderEnd(\"pie immediate\"),b}var c={top:0,right:0,bottom:0,left:0},d=500,e=500,f=function(a){return a.x},g=function(a){return a.y},h=Math.floor(1e4*Math.random()),i=null,j=a.utils.defaultColor(),k=d3.format(\",.2f\"),l=!0,m=!1,n=\"key\",o=.02,p=!1,q=!1,r=!0,s=0,t=!1,u=!1,v=!1,w=!1,x=0,y=.5,z=250,A=[],B=d3.dispatch(\"chartClick\",\"elementClick\",\"elementDblClick\",\"elementMouseover\",\"elementMouseout\",\"elementMousemove\",\"renderEnd\"),C=[],D=[],E=a.utils.renderWatch(B);return b.dispatch=B,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{arcsRadius:{get:function(){return A},set:function(a){A=a}},width:{get:function(){return d},set:function(a){d=a}},height:{get:function(){return e},set:function(a){e=a}},showLabels:{get:function(){return l},set:function(a){l=a}},title:{get:function(){return q},set:function(a){q=a}},titleOffset:{get:function(){return s},set:function(a){s=a}},labelThreshold:{get:function(){return o},set:function(a){o=a}},valueFormat:{get:function(){return k},set:function(a){k=a}},x:{get:function(){return f},set:function(a){f=a}},id:{get:function(){return h},set:function(a){h=a}},endAngle:{get:function(){return w},set:function(a){w=a}},startAngle:{get:function(){return u},set:function(a){u=a}},padAngle:{get:function(){return v},set:function(a){v=a}},cornerRadius:{get:function(){return x},set:function(a){x=a}},donutRatio:{get:function(){return y},set:function(a){y=a}},labelsOutside:{get:function(){return m},set:function(a){m=a}},labelSunbeamLayout:{get:function(){return t},set:function(a){t=a}},donut:{get:function(){return p},set:function(a){p=a}},growOnHover:{get:function(){return r},set:function(a){r=a}},pieLabelsOutside:{get:function(){return m},set:function(b){m=b,a.deprecated(\"pieLabelsOutside\",\"use labelsOutside instead\")}},donutLabelsOutside:{get:function(){return m},set:function(b){m=b,a.deprecated(\"donutLabelsOutside\",\"use labelsOutside instead\")}},labelFormat:{get:function(){return k},set:function(b){k=b,a.deprecated(\"labelFormat\",\"use valueFormat instead\")}},margin:{get:function(){return c},set:function(a){c.top=\"undefined\"!=typeof a.top?a.top:c.top,c.right=\"undefined\"!=typeof a.right?a.right:c.right,c.bottom=\"undefined\"!=typeof a.bottom?a.bottom:c.bottom,c.left=\"undefined\"!=typeof a.left?a.left:c.left}},duration:{get:function(){return z},set:function(a){z=a,E.reset(z)}},y:{get:function(){return g},set:function(a){g=d3.functor(a)}},color:{get:function(){return j},set:function(b){j=a.utils.getColor(b)}},labelType:{get:function(){return n},set:function(a){n=a||\"key\"}}}),a.utils.initOptions(b),b},a.models.pieChart=function(){\"use strict\";function b(e){return r.reset(),r.models(c),e.each(function(e){var i=d3.select(this);a.utils.initSVG(i);var l=a.utils.availableWidth(g,i,f),o=a.utils.availableHeight(h,i,f);if(b.update=function(){i.transition().call(b)},b.container=this,m.setter(t(e),b.update).getter(s(e)).update(),m.disabled=e.map(function(a){return!!a.disabled}),!n){var p;n={};for(p in m)m[p]instanceof Array?n[p]=m[p].slice(0):n[p]=m[p]}if(!e||!e.length)return a.utils.noData(b,i),b;i.selectAll(\".nv-noData\").remove();var r=i.selectAll(\"g.nv-wrap.nv-pieChart\").data([e]),u=r.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-pieChart\").append(\"g\"),v=r.select(\"g\");if(u.append(\"g\").attr(\"class\",\"nv-pieWrap\"),u.append(\"g\").attr(\"class\",\"nv-legendWrap\"),j){if(\"top\"===k)d.width(l).key(c.x()),r.select(\".nv-legendWrap\").datum(e).call(d),d.height()>f.top&&(f.top=d.height(),o=a.utils.availableHeight(h,i,f)),r.select(\".nv-legendWrap\").attr(\"transform\",\"translate(0,\"+-f.top+\")\");else if(\"right\"===k){var w=a.models.legend().width();w>l/2&&(w=l/2),d.height(o).key(c.x()),d.width(w),l-=d.width(),r.select(\".nv-legendWrap\").datum(e).call(d).attr(\"transform\",\"translate(\"+l+\",0)\")}}else v.select(\".nv-legendWrap\").selectAll(\"*\").remove();r.attr(\"transform\",\"translate(\"+f.left+\",\"+f.top+\")\"),c.width(l).height(o);var x=v.select(\".nv-pieWrap\").datum([e]);d3.transition(x).call(c),d.dispatch.on(\"stateChange\",function(a){for(var c in a)m[c]=a[c];q.stateChange(m),b.update()}),q.on(\"changeState\",function(a){\"undefined\"!=typeof a.disabled&&(e.forEach(function(b,c){b.disabled=a.disabled[c]}),m.disabled=a.disabled),b.update()})}),r.renderEnd(\"pieChart immediate\"),b}var c=a.models.pie(),d=a.models.legend(),e=a.models.tooltip(),f={top:30,right:20,bottom:20,left:20},g=null,h=null,i=!1,j=!0,k=\"top\",l=a.utils.defaultColor(),m=a.utils.state(),n=null,o=null,p=250,q=d3.dispatch(\"stateChange\",\"changeState\",\"renderEnd\");e.duration(0).headerEnabled(!1).valueFormatter(function(a,b){return c.valueFormat()(a,b)});var r=a.utils.renderWatch(q),s=function(a){return function(){return{active:a.map(function(a){return!a.disabled})}}},t=function(a){return function(b){void 0!==b.active&&a.forEach(function(a,c){a.disabled=!b.active[c]})}};return c.dispatch.on(\"elementMouseover.tooltip\",function(a){a.series={key:b.x()(a.data),value:b.y()(a.data),color:a.color,percent:a.percent},i||(delete a.percent,delete a.series.percent),e.data(a).hidden(!1)}),c.dispatch.on(\"elementMouseout.tooltip\",function(a){e.hidden(!0)}),c.dispatch.on(\"elementMousemove.tooltip\",function(a){e()}),b.legend=d,b.dispatch=q,b.pie=c,b.tooltip=e,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return g},set:function(a){g=a}},height:{get:function(){return h},set:function(a){h=a}},noData:{get:function(){return o},set:function(a){o=a}},showTooltipPercent:{get:function(){return i},set:function(a){i=a}},showLegend:{get:function(){return j},set:function(a){j=a}},legendPosition:{get:function(){return k},set:function(a){k=a}},defaultState:{get:function(){return n},set:function(a){n=a}},color:{get:function(){return l},set:function(a){l=a,d.color(l),c.color(l)}},duration:{get:function(){return p},set:function(a){p=a,r.reset(p),c.duration(p)}},margin:{get:function(){return f},set:function(a){f.top=void 0!==a.top?a.top:f.top,f.right=void 0!==a.right?a.right:f.right,f.bottom=void 0!==a.bottom?a.bottom:f.bottom,f.left=void 0!==a.left?a.left:f.left}}}),a.utils.inheritOptions(b,c),a.utils.initOptions(b),b},a.models.scatter=function(){\"use strict\";function b(a){var b,c;return b=i=i||{},c=a[0].series,b=b[c]=b[c]||{},c=a[1],b=b[c]=b[c]||{}}function c(a){var c,d,e=a[0],f=b(a),g=!1;for(c=1;c<arguments.length;c++)d=arguments[c],f[d]===e[d]&&f.hasOwnProperty(d)||(f[d]=e[d],g=!0);return g}function d(b){return U.reset(),b.each(function(b){function i(){if(T=!1,!z)return!1;if(P===!0){var c=d3.merge(b.map(function(b,c){return b.values.map(function(b,d){var e=s(b,d),f=t(b,d);return[a.utils.NaNtoZero(p(e))+1e-4*Math.random(),a.utils.NaNtoZero(q(f))+1e-4*Math.random(),c,d,b]}).filter(function(a,b){return A(a[4],b)})}));if(0==c.length)return!1;c.length<3&&(c.push([p.range()[0]-20,q.range()[0]-20,null,null]),c.push([p.range()[1]+20,q.range()[1]+20,null,null]),c.push([p.range()[0]-20,q.range()[0]+20,null,null]),c.push([p.range()[1]+20,q.range()[1]-20,null,null]));var d=d3.geom.polygon([[-10,-10],[-10,l+10],[k+10,l+10],[k+10,-10]]),e=d3.geom.voronoi(c).map(function(a,b){return{data:d.clip(a),series:c[b][2],point:c[b][3]}});_.select(\".nv-point-paths\").selectAll(\"path\").remove();var f=_.select(\".nv-point-paths\").selectAll(\"path\").data(e),g=f.enter().append(\"svg:path\").attr(\"d\",function(a){return a&&a.data&&0!==a.data.length?\"M\"+a.data.join(\",\")+\"Z\":\"M 0 0\"}).attr(\"id\",function(a,b){return\"nv-path-\"+b}).attr(\"clip-path\",function(a,b){return\"url(#nv-clip-\"+n+\"-\"+b+\")\"});if(F&&g.style(\"fill\",d3.rgb(230,230,230)).style(\"fill-opacity\",.4).style(\"stroke-opacity\",1).style(\"stroke\",d3.rgb(200,200,200)),E){_.select(\".nv-point-clips\").selectAll(\"*\").remove();var h=_.select(\".nv-point-clips\").selectAll(\"clipPath\").data(c);h.enter().append(\"svg:clipPath\").attr(\"id\",function(a,b){return\"nv-clip-\"+n+\"-\"+b}).append(\"svg:circle\").attr(\"cx\",function(a){return a[0]}).attr(\"cy\",function(a){return a[1]}).attr(\"r\",G)}var i=function(a,c){if(T)return 0;var d=b[a.series];if(void 0!==d){var e=d.values[a.point];e.color=m(d,a.series),e.x=s(e),e.y=t(e);var f=o.node().getBoundingClientRect(),g=window.pageYOffset||document.documentElement.scrollTop,h=window.pageXOffset||document.documentElement.scrollLeft,i={left:p(s(e,a.point))+f.left+h+j.left+10,top:q(t(e,a.point))+f.top+g+j.top+10};c({point:e,series:d,pos:i,relativePos:[p(s(e,a.point))+j.left,q(t(e,a.point))+j.top],seriesIndex:a.series,pointIndex:a.point})}};f.on(\"click\",function(a){i(a,O.elementClick)}).on(\"dblclick\",function(a){i(a,O.elementDblClick)}).on(\"mouseover\",function(a){i(a,O.elementMouseover)}).on(\"mouseout\",function(a,b){i(a,O.elementMouseout)})}else _.select(\".nv-groups\").selectAll(\".nv-group\").selectAll(\".nv-point\").on(\"click\",function(a,c){if(T||!b[a.series])return 0;var d=b[a.series],e=d.values[c],f=this;O.elementClick({point:e,series:d,pos:[p(s(e,c))+j.left,q(t(e,c))+j.top],relativePos:[p(s(e,c))+j.left,q(t(e,c))+j.top],seriesIndex:a.series,pointIndex:c,event:d3.event,element:f})}).on(\"dblclick\",function(a,c){if(T||!b[a.series])return 0;var d=b[a.series],e=d.values[c];O.elementDblClick({point:e,series:d,pos:[p(s(e,c))+j.left,q(t(e,c))+j.top],relativePos:[p(s(e,c))+j.left,q(t(e,c))+j.top],seriesIndex:a.series,pointIndex:c})}).on(\"mouseover\",function(a,c){if(T||!b[a.series])return 0;var d=b[a.series],e=d.values[c];O.elementMouseover({point:e,series:d,pos:[p(s(e,c))+j.left,q(t(e,c))+j.top],relativePos:[p(s(e,c))+j.left,q(t(e,c))+j.top],seriesIndex:a.series,pointIndex:c,color:m(a,c)})}).on(\"mouseout\",function(a,c){if(T||!b[a.series])return 0;var d=b[a.series],e=d.values[c];O.elementMouseout({point:e,series:d,pos:[p(s(e,c))+j.left,q(t(e,c))+j.top],relativePos:[p(s(e,c))+j.left,q(t(e,c))+j.top],seriesIndex:a.series,pointIndex:c,color:m(a,c)})})}o=d3.select(this);var Q=a.utils.availableWidth(k,o,j),W=a.utils.availableHeight(l,o,j);a.utils.initSVG(o),b.forEach(function(a,b){a.values.forEach(function(a){a.series=b})});var X=d.yScale().name===d3.scale.log().name?!0:!1,Y=H&&I&&L?[]:d3.merge(b.map(function(a){return a.values.map(function(a,b){return{x:s(a,b),y:t(a,b),size:u(a,b)}})}));if(p.domain(H||d3.extent(Y.map(function(a){return a.x}).concat(w))),B&&b[0]?p.range(J||[(Q*C+Q)/(2*b[0].values.length),Q-Q*(1+C)/(2*b[0].values.length)]):p.range(J||[0,Q]),X){var Z=d3.min(Y.map(function(a){return 0!==a.y?a.y:void 0}));q.clamp(!0).domain(I||d3.extent(Y.map(function(a){return 0!==a.y?a.y:.1*Z}).concat(x))).range(K||[W,0])}else q.domain(I||d3.extent(Y.map(function(a){return a.y}).concat(x))).range(K||[W,0]);r.domain(L||d3.extent(Y.map(function(a){return a.size}).concat(y))).range(M||V),N=p.domain()[0]===p.domain()[1]||q.domain()[0]===q.domain()[1],p.domain()[0]===p.domain()[1]&&(p.domain()[0]?p.domain([p.domain()[0]-.01*p.domain()[0],p.domain()[1]+.01*p.domain()[1]]):p.domain([-1,1])),q.domain()[0]===q.domain()[1]&&(q.domain()[0]?q.domain([q.domain()[0]-.01*q.domain()[0],q.domain()[1]+.01*q.domain()[1]]):q.domain([-1,1])),isNaN(p.domain()[0])&&p.domain([-1,1]),isNaN(q.domain()[0])&&q.domain([-1,1]),e=e||p,f=f||q,g=g||r;var $=p(1)!==e(1)||q(1)!==f(1)||r(1)!==g(1),_=o.selectAll(\"g.nv-wrap.nv-scatter\").data([b]),aa=_.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-scatter nv-chart-\"+n),ba=aa.append(\"defs\"),ca=aa.append(\"g\"),da=_.select(\"g\");_.classed(\"nv-single-point\",N),ca.append(\"g\").attr(\"class\",\"nv-groups\"),ca.append(\"g\").attr(\"class\",\"nv-point-paths\"),aa.append(\"g\").attr(\"class\",\"nv-point-clips\"),_.attr(\"transform\",\"translate(\"+j.left+\",\"+j.top+\")\"),ba.append(\"clipPath\").attr(\"id\",\"nv-edge-clip-\"+n).append(\"rect\"),_.select(\"#nv-edge-clip-\"+n+\" rect\").attr(\"width\",Q).attr(\"height\",W>0?W:0),da.attr(\"clip-path\",D?\"url(#nv-edge-clip-\"+n+\")\":\"\"),T=!0;var ea=_.select(\".nv-groups\").selectAll(\".nv-group\").data(function(a){return a},function(a){return a.key});ea.enter().append(\"g\").style(\"stroke-opacity\",1e-6).style(\"fill-opacity\",1e-6),ea.exit().remove(),ea.attr(\"class\",function(a,b){return(a.classed||\"\")+\" nv-group nv-series-\"+b}).classed(\"nv-noninteractive\",!z).classed(\"hover\",function(a){return a.hover}),ea.watchTransition(U,\"scatter: groups\").style(\"fill\",function(a,b){return m(a,b)}).style(\"stroke\",function(a,b){return m(a,b)}).style(\"stroke-opacity\",1).style(\"fill-opacity\",.5);var fa=ea.selectAll(\"path.nv-point\").data(function(a){return a.values.map(function(a,b){return[a,b]}).filter(function(a,b){return A(a[0],b)})});if(fa.enter().append(\"path\").attr(\"class\",function(a){return\"nv-point nv-point-\"+a[1]}).style(\"fill\",function(a){return a.color}).style(\"stroke\",function(a){return a.color}).attr(\"transform\",function(b){return\"translate(\"+a.utils.NaNtoZero(e(s(b[0],b[1])))+\",\"+a.utils.NaNtoZero(f(t(b[0],b[1])))+\")\"}).attr(\"d\",a.utils.symbol().type(function(a){return v(a[0])}).size(function(a){return r(u(a[0],a[1]))})),fa.exit().remove(),ea.exit().selectAll(\"path.nv-point\").watchTransition(U,\"scatter exit\").attr(\"transform\",function(b){return\"translate(\"+a.utils.NaNtoZero(p(s(b[0],b[1])))+\",\"+a.utils.NaNtoZero(q(t(b[0],b[1])))+\")\"}).remove(),fa.filter(function(a){return $||c(a,\"x\",\"y\")}).watchTransition(U,\"scatter points\").attr(\"transform\",function(b){return\"translate(\"+a.utils.NaNtoZero(p(s(b[0],b[1])))+\",\"+a.utils.NaNtoZero(q(t(b[0],b[1])))+\")\"}),fa.filter(function(a){return $||c(a,\"shape\",\"size\")}).watchTransition(U,\"scatter points\").attr(\"d\",a.utils.symbol().type(function(a){return v(a[0])}).size(function(a){return r(u(a[0],a[1]))})),S){var ga=ea.selectAll(\".nv-label\").data(function(a){return a.values.map(function(a,b){return[a,b]}).filter(function(a,b){return A(a[0],b)})});ga.enter().append(\"text\").style(\"fill\",function(a,b){return a.color}).style(\"stroke-opacity\",0).style(\"fill-opacity\",1).attr(\"transform\",function(b){var c=a.utils.NaNtoZero(e(s(b[0],b[1])))+Math.sqrt(r(u(b[0],b[1]))/Math.PI)+2;return\"translate(\"+c+\",\"+a.utils.NaNtoZero(f(t(b[0],b[1])))+\")\"}).text(function(a,b){return a[0].label}),ga.exit().remove(),ea.exit().selectAll(\"path.nv-label\").watchTransition(U,\"scatter exit\").attr(\"transform\",function(b){var c=a.utils.NaNtoZero(p(s(b[0],b[1])))+Math.sqrt(r(u(b[0],b[1]))/Math.PI)+2;return\"translate(\"+c+\",\"+a.utils.NaNtoZero(q(t(b[0],b[1])))+\")\"}).remove(),ga.each(function(a){d3.select(this).classed(\"nv-label\",!0).classed(\"nv-label-\"+a[1],!1).classed(\"hover\",!1)}),ga.watchTransition(U,\"scatter labels\").attr(\"transform\",function(b){var c=a.utils.NaNtoZero(p(s(b[0],b[1])))+Math.sqrt(r(u(b[0],b[1]))/Math.PI)+2;return\"translate(\"+c+\",\"+a.utils.NaNtoZero(q(t(b[0],b[1])))+\")\"})}R?(clearTimeout(h),h=setTimeout(i,R)):i(),e=p.copy(),f=q.copy(),g=r.copy()}),U.renderEnd(\"scatter immediate\"),d}var e,f,g,h,i,j={top:0,right:0,bottom:0,left:0},k=null,l=null,m=a.utils.defaultColor(),n=Math.floor(1e5*Math.random()),o=null,p=d3.scale.linear(),q=d3.scale.linear(),r=d3.scale.linear(),s=function(a){return a.x},t=function(a){return a.y},u=function(a){return a.size||1},v=function(a){return a.shape||\"circle\"},w=[],x=[],y=[],z=!0,A=function(a){return!a.notActive},B=!1,C=.1,D=!1,E=!0,F=!1,G=function(){return 25},H=null,I=null,J=null,K=null,L=null,M=null,N=!1,O=d3.dispatch(\"elementClick\",\"elementDblClick\",\"elementMouseover\",\"elementMouseout\",\"renderEnd\"),P=!0,Q=250,R=300,S=!1,T=!1,U=a.utils.renderWatch(O,Q),V=[16,256];return d.dispatch=O,d.options=a.utils.optionsFunc.bind(d),d._calls=new function(){this.clearHighlights=function(){return a.dom.write(function(){o.selectAll(\".nv-point.hover\").classed(\"hover\",!1)}),null},this.highlightPoint=function(b,c,d){a.dom.write(function(){o.select(\".nv-groups\").selectAll(\".nv-series-\"+b).selectAll(\".nv-point-\"+c).classed(\"hover\",d)})}},O.on(\"elementMouseover.point\",function(a){z&&d._calls.highlightPoint(a.seriesIndex,a.pointIndex,!0)}),O.on(\"elementMouseout.point\",function(a){z&&d._calls.highlightPoint(a.seriesIndex,a.pointIndex,!1)}),d._options=Object.create({},{width:{get:function(){return k},set:function(a){k=a}},height:{get:function(){return l},set:function(a){l=a}},xScale:{get:function(){return p},set:function(a){p=a}},yScale:{get:function(){return q},set:function(a){q=a}},pointScale:{get:function(){return r},set:function(a){r=a}},xDomain:{get:function(){return H},set:function(a){H=a}},yDomain:{get:function(){return I},set:function(a){I=a}},pointDomain:{get:function(){return L},set:function(a){L=a}},xRange:{get:function(){return J},set:function(a){J=a}},yRange:{get:function(){return K},set:function(a){K=a}},pointRange:{get:function(){return M},set:function(a){M=a}},forceX:{get:function(){return w},set:function(a){w=a}},forceY:{get:function(){return x},set:function(a){x=a}},forcePoint:{get:function(){return y},set:function(a){y=a}},interactive:{get:function(){return z},set:function(a){z=a}},pointActive:{get:function(){return A},set:function(a){A=a}},padDataOuter:{get:function(){return C},set:function(a){C=a}},padData:{get:function(){return B},set:function(a){B=a}},clipEdge:{get:function(){return D},set:function(a){D=a}},clipVoronoi:{get:function(){return E},set:function(a){E=a}},clipRadius:{get:function(){return G},set:function(a){G=a}},showVoronoi:{get:function(){return F},set:function(a){F=a}},id:{get:function(){return n},set:function(a){n=a}},interactiveUpdateDelay:{get:function(){return R},set:function(a){R=a}},showLabels:{get:function(){return S},set:function(a){S=a}},x:{get:function(){return s},set:function(a){s=d3.functor(a)}},y:{get:function(){return t},set:function(a){t=d3.functor(a)}},pointSize:{get:function(){return u},set:function(a){u=d3.functor(a)}},pointShape:{get:function(){return v},set:function(a){v=d3.functor(a)}},margin:{get:function(){return j},set:function(a){j.top=void 0!==a.top?a.top:j.top,j.right=void 0!==a.right?a.right:j.right,j.bottom=void 0!==a.bottom?a.bottom:j.bottom,j.left=void 0!==a.left?a.left:j.left}},duration:{get:function(){return Q},set:function(a){Q=a,U.reset(Q)}},color:{get:function(){return m},set:function(b){m=a.utils.getColor(b)}},useVoronoi:{get:function(){return P},set:function(a){P=a,P===!1&&(E=!1)}}}),a.utils.initOptions(d),d},a.models.scatterChart=function(){\"use strict\";function b(z){return E.reset(),E.models(c),t&&E.models(d),u&&E.models(e),q&&E.models(g),r&&E.models(h),z.each(function(z){m=d3.select(this),a.utils.initSVG(m);var H=a.utils.availableWidth(k,m,j),I=a.utils.availableHeight(l,m,j);if(b.update=function(){0===A?m.call(b):m.transition().duration(A).call(b)},b.container=this,w.setter(G(z),b.update).getter(F(z)).update(),w.disabled=z.map(function(a){return!!a.disabled}),!x){var J;x={};for(J in w)w[J]instanceof Array?x[J]=w[J].slice(0):x[J]=w[J]}if(!(z&&z.length&&z.filter(function(a){return a.values.length}).length))return a.utils.noData(b,m),E.renderEnd(\"scatter immediate\"),b;m.selectAll(\".nv-noData\").remove(),o=c.xScale(),p=c.yScale();var K=m.selectAll(\"g.nv-wrap.nv-scatterChart\").data([z]),L=K.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-scatterChart nv-chart-\"+c.id()),M=L.append(\"g\"),N=K.select(\"g\");if(M.append(\"rect\").attr(\"class\",\"nvd3 nv-background\").style(\"pointer-events\",\"none\"),M.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),M.append(\"g\").attr(\"class\",\"nv-y nv-axis\"),M.append(\"g\").attr(\"class\",\"nv-scatterWrap\"),M.append(\"g\").attr(\"class\",\"nv-regressionLinesWrap\"),M.append(\"g\").attr(\"class\",\"nv-distWrap\"),M.append(\"g\").attr(\"class\",\"nv-legendWrap\"),v&&N.select(\".nv-y.nv-axis\").attr(\"transform\",\"translate(\"+H+\",0)\"),s){var O=H;f.width(O),K.select(\".nv-legendWrap\").datum(z).call(f),f.height()>j.top&&(j.top=f.height(),I=a.utils.availableHeight(l,m,j)),K.select(\".nv-legendWrap\").attr(\"transform\",\"translate(0,\"+-j.top+\")\")}else N.select(\".nv-legendWrap\").selectAll(\"*\").remove();K.attr(\"transform\",\"translate(\"+j.left+\",\"+j.top+\")\"),c.width(H).height(I).color(z.map(function(a,b){return a.color=a.color||n(a,b),a.color}).filter(function(a,b){return!z[b].disabled})).showLabels(B),K.select(\".nv-scatterWrap\").datum(z.filter(function(a){return!a.disabled})).call(c),K.select(\".nv-regressionLinesWrap\").attr(\"clip-path\",\"url(#nv-edge-clip-\"+c.id()+\")\");var P=K.select(\".nv-regressionLinesWrap\").selectAll(\".nv-regLines\").data(function(a){return a});P.enter().append(\"g\").attr(\"class\",\"nv-regLines\");var Q=P.selectAll(\".nv-regLine\").data(function(a){return[a]});Q.enter().append(\"line\").attr(\"class\",\"nv-regLine\").style(\"stroke-opacity\",0),Q.filter(function(a){return a.intercept&&a.slope}).watchTransition(E,\"scatterPlusLineChart: regline\").attr(\"x1\",o.range()[0]).attr(\"x2\",o.range()[1]).attr(\"y1\",function(a,b){return p(o.domain()[0]*a.slope+a.intercept)}).attr(\"y2\",function(a,b){return p(o.domain()[1]*a.slope+a.intercept)}).style(\"stroke\",function(a,b,c){return n(a,c)}).style(\"stroke-opacity\",function(a,b){return a.disabled||\"undefined\"==typeof a.slope||\"undefined\"==typeof a.intercept?0:1}),t&&(d.scale(o)._ticks(a.utils.calcTicksX(H/100,z)).tickSize(-I,0),N.select(\".nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+p.range()[0]+\")\").call(d)),u&&(e.scale(p)._ticks(a.utils.calcTicksY(I/36,z)).tickSize(-H,0),N.select(\".nv-y.nv-axis\").call(e)),q&&(g.getData(c.x()).scale(o).width(H).color(z.map(function(a,b){return a.color||n(a,b)}).filter(function(a,b){return!z[b].disabled})),M.select(\".nv-distWrap\").append(\"g\").attr(\"class\",\"nv-distributionX\"),N.select(\".nv-distributionX\").attr(\"transform\",\"translate(0,\"+p.range()[0]+\")\").datum(z.filter(function(a){return!a.disabled})).call(g)),r&&(h.getData(c.y()).scale(p).width(I).color(z.map(function(a,b){return a.color||n(a,b)}).filter(function(a,b){return!z[b].disabled})),M.select(\".nv-distWrap\").append(\"g\").attr(\"class\",\"nv-distributionY\"),N.select(\".nv-distributionY\").attr(\"transform\",\"translate(\"+(v?H:-h.size())+\",0)\").datum(z.filter(function(a){return!a.disabled})).call(h)),f.dispatch.on(\"stateChange\",function(a){for(var c in a)w[c]=a[c];y.stateChange(w),b.update()}),y.on(\"changeState\",function(a){\"undefined\"!=typeof a.disabled&&(z.forEach(function(b,c){b.disabled=a.disabled[c]}),w.disabled=a.disabled),b.update()}),c.dispatch.on(\"elementMouseout.tooltip\",function(a){i.hidden(!0),m.select(\".nv-chart-\"+c.id()+\" .nv-series-\"+a.seriesIndex+\" .nv-distx-\"+a.pointIndex).attr(\"y1\",0),m.select(\".nv-chart-\"+c.id()+\" .nv-series-\"+a.seriesIndex+\" .nv-disty-\"+a.pointIndex).attr(\"x2\",h.size())}),c.dispatch.on(\"elementMouseover.tooltip\",function(a){m.select(\".nv-series-\"+a.seriesIndex+\" .nv-distx-\"+a.pointIndex).attr(\"y1\",a.relativePos[1]-I),m.select(\".nv-series-\"+a.seriesIndex+\" .nv-disty-\"+a.pointIndex).attr(\"x2\",a.relativePos[0]+g.size()),i.data(a).hidden(!1)}),C=o.copy(),D=p.copy()}),E.renderEnd(\"scatter with line immediate\"),b}var c=a.models.scatter(),d=a.models.axis(),e=a.models.axis(),f=a.models.legend(),g=a.models.distribution(),h=a.models.distribution(),i=a.models.tooltip(),j={top:30,right:20,bottom:50,left:75},k=null,l=null,m=null,n=a.utils.defaultColor(),o=c.xScale(),p=c.yScale(),q=!1,r=!1,s=!0,t=!0,u=!0,v=!1,w=a.utils.state(),x=null,y=d3.dispatch(\"stateChange\",\"changeState\",\"renderEnd\"),z=null,A=250,B=!1;c.xScale(o).yScale(p),d.orient(\"bottom\").tickPadding(10),e.orient(v?\"right\":\"left\").tickPadding(10),g.axis(\"x\"),h.axis(\"y\"),i.headerFormatter(function(a,b){return d.tickFormat()(a,b)}).valueFormatter(function(a,b){return e.tickFormat()(a,b)});var C,D,E=a.utils.renderWatch(y,A),F=function(a){return function(){return{active:a.map(function(a){return!a.disabled})}}},G=function(a){return function(b){void 0!==b.active&&a.forEach(function(a,c){a.disabled=!b.active[c]})}};return b.dispatch=y,b.scatter=c,b.legend=f,b.xAxis=d,b.yAxis=e,b.distX=g,b.distY=h,b.tooltip=i,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return k},set:function(a){k=a}},height:{get:function(){return l},set:function(a){l=a}},container:{get:function(){return m},set:function(a){m=a}},showDistX:{get:function(){return q},set:function(a){q=a}},showDistY:{get:function(){return r},set:function(a){r=a}},showLegend:{get:function(){return s},set:function(a){s=a}},showXAxis:{get:function(){return t},set:function(a){t=a}},showYAxis:{get:function(){return u},set:function(a){u=a}},defaultState:{get:function(){return x},set:function(a){x=a}},noData:{get:function(){return z},set:function(a){z=a}},duration:{get:function(){return A},set:function(a){A=a}},showLabels:{get:function(){return B},set:function(a){B=a}},margin:{get:function(){return j},set:function(a){j.top=void 0!==a.top?a.top:j.top,j.right=void 0!==a.right?a.right:j.right,j.bottom=void 0!==a.bottom?a.bottom:j.bottom,j.left=void 0!==a.left?a.left:j.left}},rightAlignYAxis:{get:function(){return v},set:function(a){v=a,e.orient(a?\"right\":\"left\")}},color:{get:function(){return n},set:function(b){n=a.utils.getColor(b),f.color(n),g.color(n),h.color(n)}}}),a.utils.inheritOptions(b,c),a.utils.initOptions(b),b},a.models.sparkline=function(){\"use strict\";function b(k){return t.reset(),k.each(function(b){var k=h-g.left-g.right,s=i-g.top-g.bottom;j=d3.select(this),a.utils.initSVG(j),l.domain(c||d3.extent(b,n)).range(e||[0,k]),m.domain(d||d3.extent(b,o)).range(f||[s,0]);var t=j.selectAll(\"g.nv-wrap.nv-sparkline\").data([b]),u=t.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-sparkline\");u.append(\"g\"),t.select(\"g\");t.attr(\"transform\",\"translate(\"+g.left+\",\"+g.top+\")\");var v=t.selectAll(\"path\").data(function(a){return[a]});v.enter().append(\"path\"),v.exit().remove(),v.style(\"stroke\",function(a,b){return a.color||p(a,b)}).attr(\"d\",d3.svg.line().x(function(a,b){return l(n(a,b))}).y(function(a,b){return m(o(a,b))}));var w=t.selectAll(\"circle.nv-point\").data(function(a){function b(b){if(-1!=b){var c=a[b];return c.pointIndex=b,c}return null}var c=a.map(function(a,b){return o(a,b)}),d=b(c.lastIndexOf(m.domain()[1])),e=b(c.indexOf(m.domain()[0])),f=b(c.length-1);return[q?e:null,q?d:null,r?f:null].filter(function(a){return null!=a})});w.enter().append(\"circle\"),w.exit().remove(),w.attr(\"cx\",function(a,b){return l(n(a,a.pointIndex))}).attr(\"cy\",function(a,b){return m(o(a,a.pointIndex))}).attr(\"r\",2).attr(\"class\",function(a,b){return n(a,a.pointIndex)==l.domain()[1]?\"nv-point nv-currentValue\":o(a,a.pointIndex)==m.domain()[0]?\"nv-point nv-minValue\":\"nv-point nv-maxValue\"})}),t.renderEnd(\"sparkline immediate\"),b}var c,d,e,f,g={top:2,right:0,bottom:2,left:0},h=400,i=32,j=null,k=!0,l=d3.scale.linear(),m=d3.scale.linear(),n=function(a){return a.x},o=function(a){return a.y},p=a.utils.getColor([\"#000\"]),q=!0,r=!0,s=d3.dispatch(\"renderEnd\"),t=a.utils.renderWatch(s);return b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return h},set:function(a){h=a}},height:{get:function(){return i},set:function(a){i=a}},xDomain:{get:function(){return c},set:function(a){c=a}},yDomain:{get:function(){return d},set:function(a){d=a}},xRange:{get:function(){return e},set:function(a){e=a}},yRange:{get:function(){return f},set:function(a){f=a}},xScale:{get:function(){return l},set:function(a){l=a}},yScale:{get:function(){return m},set:function(a){m=a}},animate:{get:function(){return k},set:function(a){k=a}},showMinMaxPoints:{get:function(){return q},set:function(a){q=a}},showCurrentPoint:{get:function(){return r},set:function(a){r=a}},x:{get:function(){return n},set:function(a){n=d3.functor(a)}},y:{get:function(){return o},set:function(a){o=d3.functor(a)}},margin:{get:function(){return g},set:function(a){g.top=void 0!==a.top?a.top:g.top,g.right=void 0!==a.right?a.right:g.right,g.bottom=void 0!==a.bottom?a.bottom:g.bottom,g.left=void 0!==a.left?a.left:g.left}},color:{get:function(){return p},set:function(b){p=a.utils.getColor(b)}}}),b.dispatch=s,a.utils.initOptions(b),b},a.models.sparklinePlus=function(){\"use strict\";function b(p){return r.reset(),r.models(e),p.each(function(p){function q(){if(!j){var a=z.selectAll(\".nv-hoverValue\").data(i),b=a.enter().append(\"g\").attr(\"class\",\"nv-hoverValue\").style(\"stroke-opacity\",0).style(\"fill-opacity\",0);a.exit().transition().duration(250).style(\"stroke-opacity\",0).style(\"fill-opacity\",0).remove(),a.attr(\"transform\",function(a){return\"translate(\"+c(e.x()(p[a],a))+\",0)\"}).transition().duration(250).style(\"stroke-opacity\",1).style(\"fill-opacity\",1),i.length&&(b.append(\"line\").attr(\"x1\",0).attr(\"y1\",-f.top).attr(\"x2\",0).attr(\"y2\",u),b.append(\"text\").attr(\"class\",\"nv-xValue\").attr(\"x\",-6).attr(\"y\",-f.top).attr(\"text-anchor\",\"end\").attr(\"dy\",\".9em\"),z.select(\".nv-hoverValue .nv-xValue\").text(k(e.x()(p[i[0]],i[0]))),b.append(\"text\").attr(\"class\",\"nv-yValue\").attr(\"x\",6).attr(\"y\",-f.top).attr(\"text-anchor\",\"start\").attr(\"dy\",\".9em\"),z.select(\".nv-hoverValue .nv-yValue\").text(l(e.y()(p[i[0]],i[0]))))}}function r(){function a(a,b){for(var c=Math.abs(e.x()(a[0],0)-b),d=0,f=0;f<a.length;f++)Math.abs(e.x()(a[f],f)-b)<c&&(c=Math.abs(e.x()(a[f],f)-b),d=f);return d}if(!j){var b=d3.mouse(this)[0]-f.left;i=[a(p,Math.round(c.invert(b)))],q()}}var s=d3.select(this);a.utils.initSVG(s);var t=a.utils.availableWidth(g,s,f),u=a.utils.availableHeight(h,s,f);if(b.update=function(){s.call(b)},b.container=this,!p||!p.length)return a.utils.noData(b,s),b;s.selectAll(\".nv-noData\").remove();var v=e.y()(p[p.length-1],p.length-1);c=e.xScale(),d=e.yScale();var w=s.selectAll(\"g.nv-wrap.nv-sparklineplus\").data([p]),x=w.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-sparklineplus\"),y=x.append(\"g\"),z=w.select(\"g\");y.append(\"g\").attr(\"class\",\"nv-sparklineWrap\"),y.append(\"g\").attr(\"class\",\"nv-valueWrap\"),y.append(\"g\").attr(\"class\",\"nv-hoverArea\"),w.attr(\"transform\",\"translate(\"+f.left+\",\"+f.top+\")\");var A=z.select(\".nv-sparklineWrap\");if(e.width(t).height(u),A.call(e),m){var B=z.select(\".nv-valueWrap\"),C=B.selectAll(\".nv-currentValue\").data([v]);C.enter().append(\"text\").attr(\"class\",\"nv-currentValue\").attr(\"dx\",o?-8:8).attr(\"dy\",\".9em\").style(\"text-anchor\",o?\"end\":\"start\"),C.attr(\"x\",t+(o?f.right:0)).attr(\"y\",n?function(a){return d(a)}:0).style(\"fill\",e.color()(p[p.length-1],p.length-1)).text(l(v))}y.select(\".nv-hoverArea\").append(\"rect\").on(\"mousemove\",r).on(\"click\",function(){j=!j}).on(\"mouseout\",function(){i=[],q()}),z.select(\".nv-hoverArea rect\").attr(\"transform\",function(a){return\"translate(\"+-f.left+\",\"+-f.top+\")\"}).attr(\"width\",t+f.left+f.right).attr(\"height\",u+f.top)}),r.renderEnd(\"sparklinePlus immediate\"),b}var c,d,e=a.models.sparkline(),f={top:15,right:100,bottom:10,left:50},g=null,h=null,i=[],j=!1,k=d3.format(\",r\"),l=d3.format(\",.2f\"),m=!0,n=!0,o=!1,p=null,q=d3.dispatch(\"renderEnd\"),r=a.utils.renderWatch(q);return b.dispatch=q,b.sparkline=e,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return g},set:function(a){g=a}},height:{get:function(){return h},set:function(a){h=a}},xTickFormat:{get:function(){return k},set:function(a){k=a}},yTickFormat:{get:function(){return l},set:function(a){l=a}},showLastValue:{get:function(){return m},set:function(a){m=a}},alignValue:{get:function(){return n},set:function(a){n=a}},rightAlignValue:{get:function(){return o},set:function(a){o=a}},noData:{get:function(){return p},set:function(a){p=a}},margin:{get:function(){return f},set:function(a){f.top=void 0!==a.top?a.top:f.top,f.right=void 0!==a.right?a.right:f.right,f.bottom=void 0!==a.bottom?a.bottom:f.bottom,f.left=void 0!==a.left?a.left:f.left}}}),a.utils.inheritOptions(b,e),a.utils.initOptions(b),b},a.models.stackedArea=function(){\"use strict\";function b(n){return v.reset(),v.models(s),n.each(function(n){var t=f-e.left-e.right,w=g-e.top-e.bottom;j=d3.select(this),a.utils.initSVG(j),c=s.xScale(),d=s.yScale();var x=n;n.forEach(function(a,b){a.seriesIndex=b,a.values=a.values.map(function(a,c){return a.index=c,a.seriesIndex=b,a})});var y=n.filter(function(a){return!a.disabled});n=d3.layout.stack().order(p).offset(o).values(function(a){return a.values}).x(k).y(l).out(function(a,b,c){a.display={y:c,y0:b}})(y);var z=j.selectAll(\"g.nv-wrap.nv-stackedarea\").data([n]),A=z.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-stackedarea\"),B=A.append(\"defs\"),C=A.append(\"g\"),D=z.select(\"g\");C.append(\"g\").attr(\"class\",\"nv-areaWrap\"),C.append(\"g\").attr(\"class\",\"nv-scatterWrap\"),z.attr(\"transform\",\"translate(\"+e.left+\",\"+e.top+\")\"),0==s.forceY().length&&s.forceY().push(0),s.width(t).height(w).x(k).y(function(a){return void 0!==a.display?a.display.y+a.display.y0:void 0}).color(n.map(function(a,b){return a.color=a.color||h(a,a.seriesIndex),a.color}));var E=D.select(\".nv-scatterWrap\").datum(n);E.call(s),B.append(\"clipPath\").attr(\"id\",\"nv-edge-clip-\"+i).append(\"rect\"),z.select(\"#nv-edge-clip-\"+i+\" rect\").attr(\"width\",t).attr(\"height\",w),D.attr(\"clip-path\",r?\"url(#nv-edge-clip-\"+i+\")\":\"\");var F=d3.svg.area().defined(m).x(function(a,b){return c(k(a,b))}).y0(function(a){return d(a.display.y0)}).y1(function(a){return d(a.display.y+a.display.y0)}).interpolate(q),G=d3.svg.area().defined(m).x(function(a,b){return c(k(a,b))}).y0(function(a){return d(a.display.y0)}).y1(function(a){return d(a.display.y0)}),H=D.select(\".nv-areaWrap\").selectAll(\"path.nv-area\").data(function(a){return a});H.enter().append(\"path\").attr(\"class\",function(a,b){return\"nv-area nv-area-\"+b}).attr(\"d\",function(a,b){return G(a.values,a.seriesIndex)}).on(\"mouseover\",function(a,b){d3.select(this).classed(\"hover\",!0),u.areaMouseover({point:a,series:a.key,pos:[d3.event.pageX,d3.event.pageY],seriesIndex:a.seriesIndex})}).on(\"mouseout\",function(a,b){d3.select(this).classed(\"hover\",!1),u.areaMouseout({point:a,series:a.key,pos:[d3.event.pageX,d3.event.pageY],seriesIndex:a.seriesIndex})}).on(\"click\",function(a,b){d3.select(this).classed(\"hover\",!1),u.areaClick({point:a,series:a.key,pos:[d3.event.pageX,d3.event.pageY],seriesIndex:a.seriesIndex})}),H.exit().remove(),H.style(\"fill\",function(a,b){return a.color||h(a,a.seriesIndex)}).style(\"stroke\",function(a,b){return a.color||h(a,a.seriesIndex)}),H.watchTransition(v,\"stackedArea path\").attr(\"d\",function(a,b){return F(a.values,b)}),s.dispatch.on(\"elementMouseover.area\",function(a){D.select(\".nv-chart-\"+i+\" .nv-area-\"+a.seriesIndex).classed(\"hover\",!0)}),s.dispatch.on(\"elementMouseout.area\",function(a){D.select(\".nv-chart-\"+i+\" .nv-area-\"+a.seriesIndex).classed(\"hover\",!1)}),b.d3_stackedOffset_stackPercent=function(a){var b,c,d,e=a.length,f=a[0].length,g=[];for(c=0;f>c;++c){for(b=0,d=0;b<x.length;b++)d+=l(x[b].values[c]);if(d)for(b=0;e>b;b++)a[b][c][1]/=d;else for(b=0;e>b;b++)a[b][c][1]=0}for(c=0;f>c;++c)g[c]=0;return g}}),v.renderEnd(\"stackedArea immediate\"),b}var c,d,e={top:0,right:0,bottom:0,left:0},f=960,g=500,h=a.utils.defaultColor(),i=Math.floor(1e5*Math.random()),j=null,k=function(a){return a.x},l=function(a){return a.y},m=function(a,b){return!isNaN(l(a,b))&&null!==l(a,b)},n=\"stack\",o=\"zero\",p=\"default\",q=\"linear\",r=!1,s=a.models.scatter(),t=250,u=d3.dispatch(\"areaClick\",\"areaMouseover\",\"areaMouseout\",\"renderEnd\",\"elementClick\",\"elementMouseover\",\"elementMouseout\");s.pointSize(2.2).pointDomain([2.2,2.2]);var v=a.utils.renderWatch(u,t);return b.dispatch=u,b.scatter=s,s.dispatch.on(\"elementClick\",function(){u.elementClick.apply(this,arguments)}),s.dispatch.on(\"elementMouseover\",function(){u.elementMouseover.apply(this,arguments)}),s.dispatch.on(\"elementMouseout\",function(){u.elementMouseout.apply(this,arguments)}),b.interpolate=function(a){return arguments.length?(q=a,b):q},b.duration=function(a){return arguments.length?(t=a,v.reset(t),s.duration(t),b):t},b.dispatch=u,b.scatter=s,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return f},set:function(a){f=a}},height:{get:function(){return g},set:function(a){g=a}},defined:{get:function(){return m},set:function(a){m=a}},clipEdge:{get:function(){return r},set:function(a){r=a}},offset:{get:function(){return o},set:function(a){o=a}},order:{get:function(){return p},set:function(a){p=a}},interpolate:{get:function(){return q},set:function(a){q=a}},x:{get:function(){return k},set:function(a){k=d3.functor(a)}},y:{get:function(){return l},set:function(a){l=d3.functor(a)}},margin:{get:function(){return e},set:function(a){e.top=void 0!==a.top?a.top:e.top,e.right=void 0!==a.right?a.right:e.right,e.bottom=void 0!==a.bottom?a.bottom:e.bottom,e.left=void 0!==a.left?a.left:e.left}},color:{get:function(){return h},set:function(b){h=a.utils.getColor(b)}},style:{get:function(){return n},set:function(a){switch(n=a){case\"stack\":b.offset(\"zero\"),b.order(\"default\");break;case\"stream\":b.offset(\"wiggle\"),b.order(\"inside-out\");break;case\"stream-center\":b.offset(\"silhouette\"),b.order(\"inside-out\");break;case\"expand\":b.offset(\"expand\"),b.order(\"default\");break;case\"stack_percent\":b.offset(b.d3_stackedOffset_stackPercent),b.order(\"default\")}}},duration:{get:function(){return t},set:function(a){t=a,v.reset(t),s.duration(t)}}}),a.utils.inheritOptions(b,s),a.utils.initOptions(b),b},a.models.stackedAreaChart=function(){\"use strict\";function b(k){return J.reset(),J.models(e),s&&J.models(f),t&&J.models(g),k.each(function(k){function B(){s&&V.select(\".nv-focus .nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+R+\")\").transition().duration(G).call(f)}function J(){if(t){if(\"expand\"===e.style()||\"stack_percent\"===e.style()){var a=g.tickFormat();H&&a===N||(H=a),g.tickFormat(N)}else H&&(g.tickFormat(H),H=null);V.select(\".nv-focus .nv-y.nv-axis\").transition().duration(0).call(g)}}function O(a){var b=V.select(\".nv-focus .nv-stackedWrap\").datum(k.filter(function(a){return!a.disabled}).map(function(b,c){return{key:b.key,area:b.area,classed:b.classed,values:b.values.filter(function(b,c){return e.x()(b,c)>=a[0]&&e.x()(b,c)<=a[1]}),disableTooltip:b.disableTooltip}}));b.transition().duration(G).call(e),B(),J()}var P=d3.select(this);a.utils.initSVG(P);var Q=a.utils.availableWidth(n,P,m),R=a.utils.availableHeight(o,P,m)-(v?l.height():0);if(b.update=function(){P.transition().duration(G).call(b)},b.container=this,z.setter(M(k),b.update).getter(L(k)).update(),z.disabled=k.map(function(a){return!!a.disabled}),!A){var S;A={};for(S in z)z[S]instanceof Array?A[S]=z[S].slice(0):A[S]=z[S]}if(!(k&&k.length&&k.filter(function(a){return a.values.length}).length))return a.utils.noData(b,P),b;P.selectAll(\".nv-noData\").remove(),c=e.xScale(),d=e.yScale();var T=P.selectAll(\"g.nv-wrap.nv-stackedAreaChart\").data([k]),U=T.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-stackedAreaChart\").append(\"g\"),V=T.select(\"g\");U.append(\"g\").attr(\"class\",\"nv-legendWrap\"),U.append(\"g\").attr(\"class\",\"nv-controlsWrap\");var W=U.append(\"g\").attr(\"class\",\"nv-focus\");W.append(\"g\").attr(\"class\",\"nv-background\").append(\"rect\"),W.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),W.append(\"g\").attr(\"class\",\"nv-y nv-axis\"),W.append(\"g\").attr(\"class\",\"nv-stackedWrap\"),W.append(\"g\").attr(\"class\",\"nv-interactive\");U.append(\"g\").attr(\"class\",\"nv-focusWrap\");if(r){var X=q?Q-D:Q;h.width(X),V.select(\".nv-legendWrap\").datum(k).call(h),h.height()>m.top&&(m.top=h.height(),R=a.utils.availableHeight(o,P,m)-(v?l.height():0)),V.select(\".nv-legendWrap\").attr(\"transform\",\"translate(\"+(Q-X)+\",\"+-m.top+\")\")}else V.select(\".nv-legendWrap\").selectAll(\"*\").remove();if(q){var Y=[{key:F.stacked||\"Stacked\",metaKey:\"Stacked\",disabled:\"stack\"!=e.style(),style:\"stack\"},{key:F.stream||\"Stream\",metaKey:\"Stream\",disabled:\"stream\"!=e.style(),style:\"stream\"},{key:F.expanded||\"Expanded\",metaKey:\"Expanded\",disabled:\"expand\"!=e.style(),style:\"expand\"},{key:F.stack_percent||\"Stack %\",metaKey:\"Stack_Percent\",disabled:\"stack_percent\"!=e.style(),style:\"stack_percent\"}];D=E.length/3*260,Y=Y.filter(function(a){return-1!==E.indexOf(a.metaKey)}),i.width(D).color([\"#444\",\"#444\",\"#444\"]),V.select(\".nv-controlsWrap\").datum(Y).call(i),Math.max(i.height(),h.height())>m.top&&(m.top=Math.max(i.height(),h.height()),R=a.utils.availableHeight(o,P,m)),V.select(\".nv-controlsWrap\").attr(\"transform\",\"translate(0,\"+-m.top+\")\")}else V.select(\".nv-controlsWrap\").selectAll(\"*\").remove();T.attr(\"transform\",\"translate(\"+m.left+\",\"+m.top+\")\"),u&&V.select(\".nv-y.nv-axis\").attr(\"transform\",\"translate(\"+Q+\",0)\"),w&&(j.width(Q).height(R).margin({left:m.left,top:m.top}).svgContainer(P).xScale(c),T.select(\".nv-interactive\").call(j)),V.select(\".nv-focus .nv-background rect\").attr(\"width\",Q).attr(\"height\",R),e.width(Q).height(R).color(k.map(function(a,b){return a.color||p(a,b)}).filter(function(a,b){return!k[b].disabled}));var Z=V.select(\".nv-focus .nv-stackedWrap\").datum(k.filter(function(a){return!a.disabled}));if(s&&f.scale(c)._ticks(a.utils.calcTicksX(Q/100,k)).tickSize(-R,0),t){var $;$=\"wiggle\"===e.offset()?0:a.utils.calcTicksY(R/36,k),g.scale(d)._ticks($).tickSize(-Q,0)}if(v){l.width(Q),V.select(\".nv-focusWrap\").attr(\"transform\",\"translate(0,\"+(R+m.bottom+l.margin().top)+\")\").datum(k.filter(function(a){return!a.disabled})).call(l);var _=l.brush.empty()?l.xDomain():l.brush.extent();null!==_&&O(_)}else Z.transition().call(e),B(),J();e.dispatch.on(\"areaClick.toggle\",function(a){1===k.filter(function(a){return!a.disabled}).length?k.forEach(function(a){a.disabled=!1}):k.forEach(function(b,c){b.disabled=c!=a.seriesIndex}),z.disabled=k.map(function(a){return!!a.disabled}),C.stateChange(z),b.update()}),h.dispatch.on(\"stateChange\",function(a){for(var c in a)z[c]=a[c];C.stateChange(z),b.update()}),i.dispatch.on(\"legendClick\",function(a,c){a.disabled&&(Y=Y.map(function(a){return a.disabled=!0,a}),a.disabled=!1,e.style(a.style),z.style=e.style(),C.stateChange(z),b.update())}),j.dispatch.on(\"elementMousemove\",function(c){e.clearHighlights();var d,f,g,h=[],i=0,l=!0;if(k.filter(function(a,b){return a.seriesIndex=b,!a.disabled}).forEach(function(j,k){f=a.interactiveBisect(j.values,c.pointXValue,b.x());var m=j.values[f],n=b.y()(m,f);if(null!=n&&e.highlightPoint(k,f,!0),\"undefined\"!=typeof m){\"undefined\"==typeof d&&(d=m),\"undefined\"==typeof g&&(g=b.xScale()(b.x()(m,f)));var o=\"expand\"==e.style()?m.display.y:b.y()(m,f);h.push({key:j.key,value:o,color:p(j,j.seriesIndex),point:m}),x&&\"expand\"!=e.style()&&null!=o&&(i+=o,l=!1)}}),h.reverse(),h.length>2){var m=b.yScale().invert(c.mouseY),n=null;h.forEach(function(a,b){m=Math.abs(m);var c=Math.abs(a.point.display.y0),d=Math.abs(a.point.display.y);return m>=c&&d+c>=m?void(n=b):void 0}),null!=n&&(h[n].highlight=!0)}x&&\"expand\"!=e.style()&&h.length>=2&&!l&&h.push({key:y,value:i,total:!0});var o=b.x()(d,f),q=j.tooltip.valueFormatter();\"expand\"===e.style()||\"stack_percent\"===e.style()?(I||(I=q),q=d3.format(\".1%\")):I&&(q=I,I=null),j.tooltip.valueFormatter(q).data({value:o,series:h})(),j.renderGuideLine(g)}),j.dispatch.on(\"elementMouseout\",function(a){e.clearHighlights()}),l.dispatch.on(\"onBrush\",function(a){O(a)}),C.on(\"changeState\",function(a){\"undefined\"!=typeof a.disabled&&k.length===a.disabled.length&&(k.forEach(function(b,c){b.disabled=a.disabled[c]}),z.disabled=a.disabled),\"undefined\"!=typeof a.style&&(e.style(a.style),K=a.style),b.update()})}),J.renderEnd(\"stacked Area chart immediate\"),b}var c,d,e=a.models.stackedArea(),f=a.models.axis(),g=a.models.axis(),h=a.models.legend(),i=a.models.legend(),j=a.interactiveGuideline(),k=a.models.tooltip(),l=a.models.focus(a.models.stackedArea()),m={top:30,right:25,bottom:50,left:60},n=null,o=null,p=a.utils.defaultColor(),q=!0,r=!0,s=!0,t=!0,u=!1,v=!1,w=!1,x=!0,y=\"TOTAL\",z=a.utils.state(),A=null,B=null,C=d3.dispatch(\"stateChange\",\"changeState\",\"renderEnd\"),D=250,E=[\"Stacked\",\"Stream\",\"Expanded\"],F={},G=250;z.style=e.style(),f.orient(\"bottom\").tickPadding(7),g.orient(u?\"right\":\"left\"),k.headerFormatter(function(a,b){return f.tickFormat()(a,b)}).valueFormatter(function(a,b){return g.tickFormat()(a,b)}),j.tooltip.headerFormatter(function(a,b){return f.tickFormat()(a,b)}).valueFormatter(function(a,b){return null==a?\"N/A\":g.tickFormat()(a,b)});var H=null,I=null;i.updateState(!1);var J=a.utils.renderWatch(C),K=e.style(),L=function(a){return function(){return{active:a.map(function(a){return!a.disabled}),style:e.style()}}},M=function(a){return function(b){void 0!==b.style&&(K=b.style),void 0!==b.active&&a.forEach(function(a,c){a.disabled=!b.active[c]})}},N=d3.format(\"%\");return e.dispatch.on(\"elementMouseover.tooltip\",function(a){a.point.x=e.x()(a.point),a.point.y=e.y()(a.point),k.data(a).hidden(!1)}),e.dispatch.on(\"elementMouseout.tooltip\",function(a){k.hidden(!0)}),b.dispatch=C,b.stacked=e,b.legend=h,b.controls=i,b.xAxis=f,b.x2Axis=l.xAxis,b.yAxis=g,b.y2Axis=l.yAxis,b.interactiveLayer=j,b.tooltip=k,b.focus=l,b.dispatch=C,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return n},set:function(a){n=a}},height:{get:function(){return o},set:function(a){o=a}},showLegend:{get:function(){return r},set:function(a){r=a}},showXAxis:{get:function(){return s},set:function(a){s=a}},showYAxis:{get:function(){return t},set:function(a){t=a}},defaultState:{get:function(){return A},set:function(a){A=a}},noData:{get:function(){return B},set:function(a){B=a}},showControls:{get:function(){return q},set:function(a){q=a}},controlLabels:{get:function(){return F},set:function(a){F=a}},controlOptions:{get:function(){return E},set:function(a){E=a}},showTotalInTooltip:{get:function(){return x},set:function(a){x=a}},totalLabel:{get:function(){return y},set:function(a){y=a}},focusEnable:{get:function(){return v},set:function(a){v=a}},focusHeight:{get:function(){return l.height()},set:function(a){l.height(a)}},brushExtent:{get:function(){return l.brushExtent()},set:function(a){l.brushExtent(a)}},margin:{get:function(){return m},set:function(a){m.top=void 0!==a.top?a.top:m.top,m.right=void 0!==a.right?a.right:m.right,m.bottom=void 0!==a.bottom?a.bottom:m.bottom,m.left=void 0!==a.left?a.left:m.left}},focusMargin:{get:function(){return l.margin},set:function(a){l.margin.top=void 0!==a.top?a.top:l.margin.top,l.margin.right=void 0!==a.right?a.right:l.margin.right,l.margin.bottom=void 0!==a.bottom?a.bottom:l.margin.bottom,l.margin.left=void 0!==a.left?a.left:l.margin.left}},duration:{get:function(){return G},set:function(a){G=a,J.reset(G),e.duration(G),f.duration(G),g.duration(G)}},color:{get:function(){return p},set:function(b){p=a.utils.getColor(b),h.color(p),e.color(p),l.color(p)}},x:{get:function(){return e.x()},set:function(a){e.x(a),l.x(a)}},y:{get:function(){return e.y()},set:function(a){e.y(a),l.y(a)}},rightAlignYAxis:{get:function(){return u},set:function(a){u=a,g.orient(u?\"right\":\"left\")}},useInteractiveGuideline:{get:function(){return w},set:function(a){w=!!a,b.interactive(!a),b.useVoronoi(!a),e.scatter.interactive(!a)}}}),a.utils.inheritOptions(b,e),a.utils.initOptions(b),b},a.models.stackedAreaWithFocusChart=function(){return a.models.stackedAreaChart().margin({bottom:30}).focusEnable(!0)},a.models.sunburst=function(){\"use strict\";function b(a){var b=c(a);return b>90?180:0}function c(a){var b=Math.max(0,Math.min(2*Math.PI,F(a.x))),c=Math.max(0,Math.min(2*Math.PI,F(a.x+a.dx))),d=(b+c)/2*(180/Math.PI)-90;return d}function d(a){var b=Math.max(0,Math.min(2*Math.PI,F(a.x))),c=Math.max(0,Math.min(2*Math.PI,F(a.x+a.dx)));return(c-b)/(2*Math.PI)}function e(a){var b=Math.max(0,Math.min(2*Math.PI,F(a.x))),c=Math.max(0,Math.min(2*Math.PI,F(a.x+a.dx))),d=c-b;return d>z}function f(a,b){var c=d3.interpolate(F.domain(),[l.x,l.x+l.dx]),d=d3.interpolate(G.domain(),[l.y,1]),e=d3.interpolate(G.range(),[l.y?20:0,o]);return 0===b?function(){return J(a)}:function(b){return F.domain(c(b)),G.domain(d(b)).range(e(b)),J(a)}}function g(a){var b=d3.interpolate({x:a.x0,dx:a.dx0,y:a.y0,dy:a.dy0},a);return function(c){var d=b(c);return a.x0=d.x,a.dx0=d.dx,a.y0=d.y,a.dy0=d.dy,J(d)}}function h(a){var b=B(a);I[b]||(I[b]={});var c=I[b];c.dx=a.dx,c.x=a.x,c.dy=a.dy,c.y=a.y}function i(a){a.forEach(function(a){var b=B(a),c=I[b];c?(a.dx0=c.dx,a.x0=c.x,a.dy0=c.dy,a.y0=c.y):(a.dx0=a.dx,a.x0=a.x,a.dy0=a.dy,a.y0=a.y),h(a)})}function j(a){var d=v.selectAll(\"text\"),g=v.selectAll(\"path\");d.transition().attr(\"opacity\",0),l=a,g.transition().duration(D).attrTween(\"d\",f).each(\"end\",function(d){if(d.x>=a.x&&d.x<a.x+a.dx&&d.depth>=a.depth){var f=d3.select(this.parentNode),g=f.select(\"text\");g.transition().duration(D).text(function(a){return y(a)}).attr(\"opacity\",function(a){return e(a)?1:0}).attr(\"transform\",function(){var e=this.getBBox().width;if(0===d.depth)return\"translate(\"+e/2*-1+\",0)\";if(d.depth===a.depth)return\"translate(\"+(G(d.y)+5)+\",0)\";var f=c(d),g=b(d);return 0===g?\"rotate(\"+f+\")translate(\"+(G(d.y)+5)+\",0)\":\"rotate(\"+f+\")translate(\"+(G(d.y)+e+5)+\",0)rotate(\"+g+\")\"})}})}function k(f){return K.reset(),f.each(function(f){v=d3.select(this),m=a.utils.availableWidth(q,v,p),n=a.utils.availableHeight(r,v,p),o=Math.min(m,n)/2,G.range([0,o]);var h=v.select(\"g.nvd3.nv-wrap.nv-sunburst\");h[0][0]?h.attr(\"transform\",\"translate(\"+(m/2+p.left+p.right)+\",\"+(n/2+p.top+p.bottom)+\")\"):h=v.append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-sunburst nv-chart-\"+u).attr(\"transform\",\"translate(\"+(m/2+p.left+p.right)+\",\"+(n/2+p.top+p.bottom)+\")\"),v.on(\"click\",function(a,b){E.chartClick({data:a,index:b,pos:d3.event,id:u})}),H.value(t[s]||t.count);var k=H.nodes(f[0]).reverse();i(k);var l=h.selectAll(\".arc-container\").data(k,B),z=l.enter().append(\"g\").attr(\"class\",\"arc-container\");z.append(\"path\").attr(\"d\",J).style(\"fill\",function(a){return a.color?a.color:w(C?(a.children?a:a.parent).name:a.name)}).style(\"stroke\",\"#FFF\").on(\"click\",j).on(\"mouseover\",function(a,b){d3.select(this).classed(\"hover\",!0).style(\"opacity\",.8),E.elementMouseover({data:a,color:d3.select(this).style(\"fill\"),percent:d(a)})}).on(\"mouseout\",function(a,b){d3.select(this).classed(\"hover\",!1).style(\"opacity\",1),E.elementMouseout({data:a})}).on(\"mousemove\",function(a,b){E.elementMousemove({data:a})}),l.each(function(a){d3.select(this).select(\"path\").transition().duration(D).attrTween(\"d\",g)}),x&&(l.selectAll(\"text\").remove(),l.append(\"text\").text(function(a){return y(a)}).transition().duration(D).attr(\"opacity\",function(a){return e(a)?1:0}).attr(\"transform\",function(a){var d=this.getBBox().width;if(0===a.depth)return\"rotate(0)translate(\"+d/2*-1+\",0)\";var e=c(a),f=b(a);return 0===f?\"rotate(\"+e+\")translate(\"+(G(a.y)+5)+\",0)\":\"rotate(\"+e+\")translate(\"+(G(a.y)+d+5)+\",0)rotate(\"+f+\")\"})),j(k[k.length-1]),l.exit().transition().duration(D).attr(\"opacity\",0).each(\"end\",function(a){var b=B(a);I[b]=void 0}).remove()}),K.renderEnd(\"sunburst immediate\"),k}var l,m,n,o,p={top:0,right:0,bottom:0,left:0},q=600,r=600,s=\"count\",t={count:function(a){return 1},value:function(a){return a.value||a.size},size:function(a){return a.value||a.size}},u=Math.floor(1e4*Math.random()),v=null,w=a.utils.defaultColor(),x=!1,y=function(a){return\"count\"===s?a.name+\" #\"+a.value:a.name+\" \"+(a.value||a.size)},z=.02,A=function(a,b){return a.name>b.name},B=function(a,b){return a.name},C=!0,D=500,E=d3.dispatch(\"chartClick\",\"elementClick\",\"elementDblClick\",\"elementMousemove\",\"elementMouseover\",\"elementMouseout\",\"renderEnd\"),F=d3.scale.linear().range([0,2*Math.PI]),G=d3.scale.sqrt(),H=d3.layout.partition().sort(A),I={},J=d3.svg.arc().startAngle(function(a){return Math.max(0,Math.min(2*Math.PI,F(a.x)))}).endAngle(function(a){return Math.max(0,Math.min(2*Math.PI,F(a.x+a.dx)))}).innerRadius(function(a){return Math.max(0,G(a.y))}).outerRadius(function(a){return Math.max(0,G(a.y+a.dy))}),K=a.utils.renderWatch(E);return k.dispatch=E,k.options=a.utils.optionsFunc.bind(k),k._options=Object.create({},{width:{get:function(){return q},set:function(a){q=a}},height:{get:function(){return r},set:function(a){r=a}},mode:{get:function(){return s},set:function(a){s=a}},id:{get:function(){return u},set:function(a){u=a}},duration:{get:function(){return D},set:function(a){D=a}},groupColorByParent:{get:function(){return C},set:function(a){C=!!a}},showLabels:{get:function(){return x},set:function(a){x=!!a}},labelFormat:{get:function(){return y},set:function(a){y=a}},labelThreshold:{get:function(){return z},set:function(a){z=a}},sort:{get:function(){return A},set:function(a){A=a}},key:{get:function(){return B},set:function(a){B=a}},margin:{get:function(){return p},set:function(a){p.top=void 0!=a.top?a.top:p.top,p.right=void 0!=a.right?a.right:p.right,p.bottom=void 0!=a.bottom?a.bottom:p.bottom,p.left=void 0!=a.left?a.left:p.left}},color:{get:function(){return w},set:function(b){w=a.utils.getColor(b)}}}),a.utils.initOptions(k),k},a.models.sunburstChart=function(){\"use strict\";function b(d){return n.reset(),n.models(c),d.each(function(d){var h=d3.select(this);a.utils.initSVG(h);var i=a.utils.availableWidth(f,h,e),j=a.utils.availableHeight(g,h,e);return b.update=function(){0===l?h.call(b):h.transition().duration(l).call(b)},b.container=h,d&&d.length?(h.selectAll(\".nv-noData\").remove(),c.width(i).height(j).margin(e),void h.call(c)):(a.utils.noData(b,h),b)}),n.renderEnd(\"sunburstChart immediate\"),b}var c=a.models.sunburst(),d=a.models.tooltip(),e={top:30,right:20,bottom:20,left:20},f=null,g=null,h=a.utils.defaultColor(),i=!1,j=(Math.round(1e5*Math.random()),null),k=null,l=250,m=d3.dispatch(\"stateChange\",\"changeState\",\"renderEnd\"),n=a.utils.renderWatch(m);return d.duration(0).headerEnabled(!1).valueFormatter(function(a){return a}),c.dispatch.on(\"elementMouseover.tooltip\",function(a){a.series={key:a.data.name,value:a.data.value||a.data.size,color:a.color,percent:a.percent},i||(delete a.percent,delete a.series.percent),d.data(a).hidden(!1)}),c.dispatch.on(\"elementMouseout.tooltip\",function(a){d.hidden(!0)}),c.dispatch.on(\"elementMousemove.tooltip\",function(a){d()}),b.dispatch=m,b.sunburst=c,b.tooltip=d,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{noData:{get:function(){return k},set:function(a){k=a}},defaultState:{get:function(){return j},set:function(a){j=a}},showTooltipPercent:{get:function(){return i},set:function(a){i=a}},color:{get:function(){return h},set:function(a){h=a,c.color(h)}},duration:{get:function(){return l},set:function(a){l=a,n.reset(l),c.duration(l)}},margin:{get:function(){return e},set:function(a){e.top=void 0!==a.top?a.top:e.top,e.right=void 0!==a.right?a.right:e.right,e.bottom=void 0!==a.bottom?a.bottom:e.bottom,e.left=void 0!==a.left?a.left:e.left,c.margin(e)}}}),a.utils.inheritOptions(b,c),a.utils.initOptions(b),b},a.version=\"1.8.4-dev\"}();"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/run.sh",
    "content": "#!/bin/bash\n\n# ./run.sh gemm gemm_settings.txt\n# ./run.sh lazy_gemm lazy_gemm_settings.txt\n# ./run.sh gemv gemv_settings.txt\n# ./run.sh trmv_up gemv_square_settings.txt\n# ...\n\n# Examples of environment variables to be set:\n#   PREFIX=\"haswell-fma-\"\n#   CXX_FLAGS=\"-mfma\"\n#   CXX=clang++\n\n# Options:\n#   -up : enforce the recomputation of existing data, and keep best results as a merging strategy\n#   -s  : recompute selected changesets only and keep bests\n#   -np : no plotting of results, just generate the data\n\nbench=$1\nsettings_file=$2\n\nif [[ \"$*\" =~ '-up' ]]; then\n  update=true\nelse\n  update=false\nfi\n\nif [[ \"$*\" =~ '-s' ]]; then\n  selected=true\nelse\n  selected=false\nfi\n\nif [[ \"$*\" =~ '-np' ]]; then\n  do_plot=false\nelse\n  do_plot=true\nfi\n\n\nWORKING_DIR=${PREFIX:?\"default\"}\n\nif [ -z \"$PREFIX\" ]; then\n  WORKING_DIR_PREFIX=\"$WORKING_DIR/\"\nelse\n  WORKING_DIR_PREFIX=\"$WORKING_DIR/$PREFIX-\"\nfi\necho \"WORKING_DIR_PREFIX=$WORKING_DIR_PREFIX\"\nmkdir -p $WORKING_DIR\n\nglobal_args=\"$*\"\n\nif $selected ; then\n echo \"Recompute selected changesets only and keep bests\"\nelif $update ; then\n echo \"(Re-)Compute all changesets and keep bests\"\nelse\n echo \"Skip previously computed changesets\"\nfi\n\n\n\nif [ ! -d \"eigen_src\" ]; then\n  git clone https://gitlab.com/libeigen/eigen.git eigen_src\nelse\n  cd eigen_src\n  git pull\n  cd ..\nfi\n\nif [ -z \"$CXX\" ]; then\n  CXX=g++\nfi\n\nfunction make_backup\n{\n  if [ -f \"$1.out\" ]; then\n    mv \"$1.out\" \"$1.backup\"\n  fi\n}\n\nfunction merge\n{\n  count1=`echo $1 |  wc -w`\n  count2=`echo $2 |  wc -w`\n  \n  if [ $count1 == $count2 ]; then\n    a=( $1 ); b=( $2 )\n    res=\"\"\n    for (( i=0 ; i<$count1 ; i++ )); do\n      ai=${a[$i]}; bi=${b[$i]}\n      tmp=`echo \"if ($ai > $bi) $ai else $bi \" | bc -l`\n      res=\"$res $tmp\"\n    done\n    echo $res\n\n  else\n    echo $1\n  fi\n}\n\nfunction test_current \n{\n  rev=$1\n  scalar=$2\n  name=$3\n  \n  prev=\"\"\n  if [ -e \"$name.backup\" ]; then\n    prev=`grep $rev \"$name.backup\" | cut -d ' ' -f 2-`\n  fi\n  res=$prev\n  count_rev=`echo $prev |  wc -w`\n  count_ref=`cat $settings_file |  wc -l`\n  if echo \"$global_args\" | grep \"$rev\" > /dev/null; then\n    rev_found=true\n  else\n    rev_found=false\n  fi\n#  echo $update et $selected et $rev_found because $rev et \"$global_args\"\n#  echo $count_rev et $count_ref\n  if $update || [ $count_rev != $count_ref ] || ( $selected &&  $rev_found ); then\n    echo \"RUN: $CXX -O3 -DNDEBUG -march=native $CXX_FLAGS -I eigen_src $bench.cpp -DSCALAR=$scalar -o $name\"\n    if $CXX -O3 -DNDEBUG -march=native $CXX_FLAGS -I eigen_src $bench.cpp -DSCALAR=$scalar -o $name; then\n      curr=`./$name $settings_file`\n      if [ $count_rev == $count_ref ]; then\n        echo \"merge previous $prev\"\n        echo \"with new       $curr\"\n      else\n        echo \"got            $curr\"\n      fi\n      res=`merge \"$curr\" \"$prev\"`\n#       echo $res\n      echo \"$rev $res\" >> $name.out\n    else\n      echo \"Compilation failed, skip rev $rev\"\n    fi\n  else\n    echo \"Skip existing results for $rev / $name\"\n    echo \"$rev $res\" >> $name.out\n  fi\n}\n\nmake_backup $WORKING_DIR_PREFIX\"s\"$bench\nmake_backup $WORKING_DIR_PREFIX\"d\"$bench\nmake_backup $WORKING_DIR_PREFIX\"c\"$bench\n\ncut -f1 -d\"#\" < changesets.txt | grep -E '[[:alnum:]]' | while read rev\ndo\n  if [ ! -z '$rev' ]; then\n    rev2=`echo $rev | cut -f 2 -d':'`\n    echo \"Testing rev $rev, $rev2\"\n    cd eigen_src\n    git checkout $rev2 > /dev/null\n    actual_rev=`git rev-parse --short HEAD`\n    cd ..\n    \n    test_current $actual_rev float                  $WORKING_DIR_PREFIX\"s\"$bench\n    test_current $actual_rev double                 $WORKING_DIR_PREFIX\"d\"$bench\n    test_current $actual_rev \"std::complex<double>\" $WORKING_DIR_PREFIX\"c\"$bench\n  fi\n  \ndone\n\necho \"Float:\"\ncat $WORKING_DIR_PREFIX\"s\"\"$bench.out\"\necho \" \"\n\necho \"Double:\"\ncat $WORKING_DIR_PREFIX\"d\"\"$bench.out\"\necho \"\"\n\necho \"Complex:\"\ncat $WORKING_DIR_PREFIX\"c\"\"$bench.out\"\necho \"\"\n\nif $do_plot ; then\n\n./make_plot.sh $WORKING_DIR_PREFIX\"s\"$bench $bench $settings_file\n./make_plot.sh $WORKING_DIR_PREFIX\"d\"$bench $bench $settings_file\n./make_plot.sh $WORKING_DIR_PREFIX\"c\"$bench $bench $settings_file\n\nfi\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/runall.sh",
    "content": "#!/bin/bash\n\n# ./runall.sh \"Title\"\n\n# Examples of environment variables to be set:\n#   PREFIX=\"haswell-fma-\"\n#   CXX_FLAGS=\"-mfma\"\n#   CXX=clang++\n\n# Options:\n#   -up : enforce the recomputation of existing data, and keep best results as a merging strategy\n#   -s  : recompute selected changesets only and keep bests\n#   -np : no plotting of results, just generate the data\n\nif [[ \"$*\" =~ '-np' ]]; then\n  do_plot=false\nelse\n  do_plot=true\nfi\n\n./run.sh gemm gemm_settings.txt $*\n./run.sh lazy_gemm lazy_gemm_settings.txt $*\n./run.sh gemv gemv_settings.txt $*\n./run.sh gemvt gemv_settings.txt $*\n./run.sh trmv_up gemv_square_settings.txt $*\n./run.sh trmv_lo gemv_square_settings.txt $*\n./run.sh trmv_upt gemv_square_settings.txt $*\n./run.sh trmv_lot gemv_square_settings.txt $*\n./run.sh llt gemm_square_settings.txt $*\n\nif $do_plot ; then\n\n# generate html file\n\nfunction print_td {\n  echo '<td><a href=\"'$PREFIX'-'$1\"$2\"'.html\"><img src=\"'$PREFIX'-'$1\"$2\"'.png\" title=\"'$3'\"></a></td>' >> $htmlfile\n}\n\nfunction print_tr {\n  echo '<tr><th colspan=\"3\">'\"$2\"'</th></tr>' >> $htmlfile\n  echo '<tr>' >> $htmlfile\n  print_td s $1 float\n  print_td d $1 double\n  print_td c $1 complex\n  echo '</tr>' >> $htmlfile\n}\n\nif [ -n \"$PREFIX\" ]; then\n\n\ncp resources/s1.js $PREFIX/\ncp resources/s2.js $PREFIX/\n\nhtmlfile=\"$PREFIX/index.html\"\ncat resources/header.html > $htmlfile\n\necho '<h1>'$1'</h1>' >> $htmlfile\necho '<table>' >> $htmlfile\nprint_tr gemm       'C += A &middot; B   &nbsp; (gemm)'\nprint_tr lazy_gemm  'C += A &middot; B   &nbsp; (gemm lazy)'\nprint_tr gemv       'y += A &middot; x   &nbsp; (gemv)'\nprint_tr gemvt      'y += A<sup>T</sup> &middot; x  &nbsp; (gemv)'\nprint_tr trmv_up    'y += U &middot; x   &nbsp; (trmv)'\nprint_tr trmv_upt   'y += U<sup>T</sup> &middot; x  &nbsp; (trmv)'\nprint_tr trmv_lo    'y += L &middot; x   &nbsp; (trmv)'\nprint_tr trmv_lot   'y += L<sup>T</sup> &middot; x  &nbsp; (trmv)'\nprint_tr trmv_lot   'L &middot; L<sup>T<sup> = A &nbsp;  (Cholesky,potrf)'\n\ncat resources/footer.html >> $htmlfile\n\nfi\nfi\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/trmv_lo.cpp",
    "content": "#include \"gemv_common.h\"\n\nEIGEN_DONT_INLINE\nvoid trmv(const Mat &A, const Vec &B, Vec &C)\n{\n  C.noalias() += A.triangularView<Lower>() * B;\n}\n\nint main(int argc, char **argv)\n{\n  return main_gemv(argc, argv, trmv);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/trmv_lot.cpp",
    "content": "#include \"gemv_common.h\"\n\nEIGEN_DONT_INLINE\nvoid trmv(const Mat &A, Vec &B, const Vec &C)\n{\n  B.noalias() += A.transpose().triangularView<Lower>() * C;\n}\n\nint main(int argc, char **argv)\n{\n  return main_gemv(argc, argv, trmv);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/trmv_up.cpp",
    "content": "#include \"gemv_common.h\"\n\nEIGEN_DONT_INLINE\nvoid trmv(const Mat &A, const Vec &B, Vec &C)\n{\n  C.noalias() += A.triangularView<Upper>() * B;\n}\n\nint main(int argc, char **argv)\n{\n  return main_gemv(argc, argv, trmv);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/perf_monitoring/trmv_upt.cpp",
    "content": "#include \"gemv_common.h\"\n\nEIGEN_DONT_INLINE\nvoid trmv(const Mat &A, Vec &B, const Vec &C)\n{\n  B.noalias() += A.transpose().triangularView<Upper>() * C;\n}\n\nint main(int argc, char **argv)\n{\n  return main_gemv(argc, argv, trmv);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/product_threshold.cpp",
    "content": "\n#include <iostream>\n#include <Eigen/Core>\n#include <bench/BenchTimer.h>\n\nusing namespace Eigen;\nusing namespace std;\n\n#define END 9\n\ntemplate<int S> struct map_size { enum { ret = S }; };\ntemplate<>  struct map_size<10> { enum { ret = 20 }; };\ntemplate<>  struct map_size<11> { enum { ret = 50 }; };\ntemplate<>  struct map_size<12> { enum { ret = 100 }; };\ntemplate<>  struct map_size<13> { enum { ret = 300 }; };\n\ntemplate<int M, int N,int K> struct alt_prod\n{\n  enum {\n    ret = M==1 && N==1 ? InnerProduct\n        : K==1 ? OuterProduct\n        : M==1 ? GemvProduct\n        : N==1 ? GemvProduct\n        : GemmProduct\n  };\n};\n        \nvoid print_mode(int mode)\n{\n  if(mode==InnerProduct) std::cout << \"i\";\n  if(mode==OuterProduct) std::cout << \"o\";\n  if(mode==CoeffBasedProductMode) std::cout << \"c\";\n  if(mode==LazyCoeffBasedProductMode) std::cout << \"l\";\n  if(mode==GemvProduct) std::cout << \"v\";\n  if(mode==GemmProduct) std::cout << \"m\";\n}\n\ntemplate<int Mode, typename Lhs, typename Rhs, typename Res>\nEIGEN_DONT_INLINE void prod(const Lhs& a, const Rhs& b, Res& c)\n{\n  c.noalias() += typename ProductReturnType<Lhs,Rhs,Mode>::Type(a,b);\n}\n\ntemplate<int M, int N, int K, typename Scalar, int Mode>\nEIGEN_DONT_INLINE void bench_prod()\n{\n  typedef Matrix<Scalar,M,K> Lhs; Lhs a; a.setRandom();\n  typedef Matrix<Scalar,K,N> Rhs; Rhs b; b.setRandom();\n  typedef Matrix<Scalar,M,N> Res; Res c; c.setRandom();\n\n  BenchTimer t;\n  double n = 2.*double(M)*double(N)*double(K);\n  int rep = 100000./n;\n  rep /= 2;\n  if(rep<1) rep = 1;\n  do {\n    rep *= 2;\n    t.reset();\n    BENCH(t,1,rep,prod<CoeffBasedProductMode>(a,b,c));\n  } while(t.best()<0.1);\n  \n  t.reset();\n  BENCH(t,5,rep,prod<Mode>(a,b,c));\n\n  print_mode(Mode);\n  std::cout << int(1e-6*n*rep/t.best()) << \"\\t\";\n}\n\ntemplate<int N> struct print_n;\ntemplate<int M, int N, int K> struct loop_on_m;\ntemplate<int M, int N, int K, typename Scalar, int Mode> struct loop_on_n;\n\ntemplate<int M, int N, int K>\nstruct loop_on_k\n{\n  static void run()\n  {\n    std::cout << \"K=\" << K << \"\\t\";\n    print_n<N>::run();\n    std::cout << \"\\n\";\n\n    loop_on_m<M,N,K>::run();\n    std::cout << \"\\n\\n\";\n\n    loop_on_k<M,N,K+1>::run();\n  }\n};\n\ntemplate<int M, int N>\nstruct loop_on_k<M,N,END> { static void run(){} };\n\n\ntemplate<int M, int N, int K>\nstruct loop_on_m\n{\n  static void run()\n  {\n    std::cout << M << \"f\\t\";\n    loop_on_n<M,N,K,float,CoeffBasedProductMode>::run();\n    std::cout << \"\\n\";\n    \n    std::cout << M << \"f\\t\";\n    loop_on_n<M,N,K,float,-1>::run();\n    std::cout << \"\\n\";\n\n    loop_on_m<M+1,N,K>::run();\n  }\n};\n\ntemplate<int N, int K>\nstruct loop_on_m<END,N,K> { static void run(){} };\n\ntemplate<int M, int N, int K, typename Scalar, int Mode>\nstruct loop_on_n\n{\n  static void run()\n  {\n    bench_prod<M,N,K,Scalar,Mode==-1? alt_prod<M,N,K>::ret : Mode>();\n    \n    loop_on_n<M,N+1,K,Scalar,Mode>::run();\n  }\n};\n\ntemplate<int M, int K, typename Scalar, int Mode>\nstruct loop_on_n<M,END,K,Scalar,Mode> { static void run(){} };\n\ntemplate<int N> struct print_n\n{\n  static void run()\n  {\n    std::cout << map_size<N>::ret << \"\\t\";\n    print_n<N+1>::run();\n  }\n};\n\ntemplate<> struct print_n<END> { static void run(){} };\n\nint main()\n{\n  loop_on_k<1,1,1>::run();\n  \n  return 0; \n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/quat_slerp.cpp",
    "content": "\n#include <iostream>\n#include <Eigen/Geometry>\n#include <bench/BenchTimer.h>\nusing namespace Eigen;\nusing namespace std;\n\n\n\ntemplate<typename Q>\nEIGEN_DONT_INLINE Q nlerp(const Q& a, const Q& b, typename Q::Scalar t)\n{\n  return Q((a.coeffs() * (1.0-t) + b.coeffs() * t).normalized());\n}\n\ntemplate<typename Q>\nEIGEN_DONT_INLINE Q slerp_eigen(const Q& a, const Q& b, typename Q::Scalar t)\n{\n  return a.slerp(t,b);\n}\n\ntemplate<typename Q>\nEIGEN_DONT_INLINE Q slerp_legacy(const Q& a, const Q& b, typename Q::Scalar t)\n{\n  typedef typename Q::Scalar Scalar;\n  static const Scalar one = Scalar(1) - dummy_precision<Scalar>();\n  Scalar d = a.dot(b);\n  Scalar absD = internal::abs(d);\n  if (absD>=one)\n    return a;\n\n  // theta is the angle between the 2 quaternions\n  Scalar theta = std::acos(absD);\n  Scalar sinTheta = internal::sin(theta);\n\n  Scalar scale0 = internal::sin( ( Scalar(1) - t ) * theta) / sinTheta;\n  Scalar scale1 = internal::sin( ( t * theta) ) / sinTheta;\n  if (d<0)\n    scale1 = -scale1;\n\n  return Q(scale0 * a.coeffs() + scale1 * b.coeffs());\n}\n\ntemplate<typename Q>\nEIGEN_DONT_INLINE Q slerp_legacy_nlerp(const Q& a, const Q& b, typename Q::Scalar t)\n{\n  typedef typename Q::Scalar Scalar;\n  static const Scalar one = Scalar(1) - epsilon<Scalar>();\n  Scalar d = a.dot(b);\n  Scalar absD = internal::abs(d);\n  \n  Scalar scale0;\n  Scalar scale1;\n  \n  if (absD>=one)\n  {\n    scale0 = Scalar(1) - t;\n    scale1 = t;\n  }\n  else\n  {\n    // theta is the angle between the 2 quaternions\n    Scalar theta = std::acos(absD);\n    Scalar sinTheta = internal::sin(theta);\n\n    scale0 = internal::sin( ( Scalar(1) - t ) * theta) / sinTheta;\n    scale1 = internal::sin( ( t * theta) ) / sinTheta;\n    if (d<0)\n      scale1 = -scale1;\n  }\n\n  return Q(scale0 * a.coeffs() + scale1 * b.coeffs());\n}\n\ntemplate<typename T>\ninline T sin_over_x(T x)\n{\n  if (T(1) + x*x == T(1))\n    return T(1);\n  else\n    return std::sin(x)/x;\n}\n\ntemplate<typename Q>\nEIGEN_DONT_INLINE Q slerp_rw(const Q& a, const Q& b, typename Q::Scalar t)\n{\n  typedef typename Q::Scalar Scalar;\n  \n  Scalar d = a.dot(b);\n  Scalar theta;\n  if (d<0.0)\n    theta = /*M_PI -*/ Scalar(2)*std::asin( (a.coeffs()+b.coeffs()).norm()/2 );\n  else\n    theta = Scalar(2)*std::asin( (a.coeffs()-b.coeffs()).norm()/2 );\n  \n  // theta is the angle between the 2 quaternions\n//   Scalar theta = std::acos(absD);\n  Scalar sinOverTheta = sin_over_x(theta);\n\n  Scalar scale0 = (Scalar(1)-t)*sin_over_x( ( Scalar(1) - t ) * theta) / sinOverTheta;\n  Scalar scale1 = t * sin_over_x( ( t * theta) ) / sinOverTheta;\n  if (d<0)\n    scale1 = -scale1;\n\n  return Quaternion<Scalar>(scale0 * a.coeffs() + scale1 * b.coeffs());\n}\n\ntemplate<typename Q>\nEIGEN_DONT_INLINE Q slerp_gael(const Q& a, const Q& b, typename Q::Scalar t)\n{\n  typedef typename Q::Scalar Scalar;\n  \n  Scalar d = a.dot(b);\n  Scalar theta;\n//   theta = Scalar(2) * atan2((a.coeffs()-b.coeffs()).norm(),(a.coeffs()+b.coeffs()).norm());\n//   if (d<0.0)\n//     theta = M_PI-theta;\n  \n  if (d<0.0)\n    theta = /*M_PI -*/ Scalar(2)*std::asin( (-a.coeffs()-b.coeffs()).norm()/2 );\n  else\n    theta = Scalar(2)*std::asin( (a.coeffs()-b.coeffs()).norm()/2 );\n  \n  \n  Scalar scale0;\n  Scalar scale1;\n  if(theta*theta-Scalar(6)==-Scalar(6))\n  {\n    scale0 = Scalar(1) - t;\n    scale1 = t;\n  }\n  else\n  {\n    Scalar sinTheta = std::sin(theta);\n    scale0 = internal::sin( ( Scalar(1) - t ) * theta) / sinTheta;\n    scale1 = internal::sin( ( t * theta) ) / sinTheta;\n    if (d<0)\n      scale1 = -scale1;\n  }\n\n  return Quaternion<Scalar>(scale0 * a.coeffs() + scale1 * b.coeffs());\n}\n\nint main()\n{\n  typedef double RefScalar;\n  typedef float TestScalar;\n  \n  typedef Quaternion<RefScalar>  Qd;\n  typedef Quaternion<TestScalar> Qf;\n  \n  unsigned int g_seed = (unsigned int) time(NULL);\n  std::cout << g_seed << \"\\n\";\n//   g_seed = 1259932496;\n  srand(g_seed);\n  \n  Matrix<RefScalar,Dynamic,1> maxerr(7);\n  maxerr.setZero();\n  \n  Matrix<RefScalar,Dynamic,1> avgerr(7);\n  avgerr.setZero();\n  \n  cout << \"double=>float=>double       nlerp        eigen        legacy(snap)         legacy(nlerp)        rightway         gael's criteria\\n\";\n  \n  int rep = 100;\n  int iters = 40;\n  for (int w=0; w<rep; ++w)\n  {\n    Qf a, b;\n    a.coeffs().setRandom();\n    a.normalize();\n    b.coeffs().setRandom();\n    b.normalize();\n    \n    Qf c[6];\n    \n    Qd ar(a.cast<RefScalar>());\n    Qd br(b.cast<RefScalar>());\n    Qd cr;\n    \n    \n    \n    cout.precision(8);\n    cout << std::scientific;\n    for (int i=0; i<iters; ++i)\n    {\n      RefScalar t = 0.65;\n      cr = slerp_rw(ar,br,t);\n      \n      Qf refc = cr.cast<TestScalar>();\n      c[0] = nlerp(a,b,t);\n      c[1] = slerp_eigen(a,b,t);\n      c[2] = slerp_legacy(a,b,t);\n      c[3] = slerp_legacy_nlerp(a,b,t);\n      c[4] = slerp_rw(a,b,t);\n      c[5] = slerp_gael(a,b,t);\n      \n      VectorXd err(7);\n      err[0] = (cr.coeffs()-refc.cast<RefScalar>().coeffs()).norm();\n//       std::cout << err[0] << \"    \";\n      for (int k=0; k<6; ++k)\n      {\n        err[k+1] = (c[k].coeffs()-refc.coeffs()).norm();\n//         std::cout << err[k+1] << \"    \";\n      }\n      maxerr = maxerr.cwise().max(err);\n      avgerr += err;\n//       std::cout << \"\\n\";\n      b = cr.cast<TestScalar>();\n      br = cr;\n    }\n//     std::cout << \"\\n\";\n  }\n  avgerr /= RefScalar(rep*iters);\n  cout << \"\\n\\nAccuracy:\\n\"\n       << \"  max: \" << maxerr.transpose() << \"\\n\";\n  cout << \"  avg: \" << avgerr.transpose() << \"\\n\";\n  \n  // perf bench\n  Quaternionf a,b;\n  a.coeffs().setRandom();\n  a.normalize();\n  b.coeffs().setRandom();\n  b.normalize();\n  //b = a;\n  float s = 0.65;\n    \n  #define BENCH(FUNC) {\\\n    BenchTimer t; \\\n    for(int k=0; k<2; ++k) {\\\n      t.start(); \\\n      for(int i=0; i<1000000; ++i) \\\n        FUNC(a,b,s); \\\n      t.stop(); \\\n    } \\\n    cout << \"  \" << #FUNC << \" => \\t \" << t.value() << \"s\\n\"; \\\n  }\n  \n  cout << \"\\nSpeed:\\n\" << std::fixed;\n  BENCH(nlerp);\n  BENCH(slerp_eigen);\n  BENCH(slerp_legacy);\n  BENCH(slerp_legacy_nlerp);\n  BENCH(slerp_rw);\n  BENCH(slerp_gael);\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/quatmul.cpp",
    "content": "#include <iostream>\n#include <Eigen/Core>\n#include <Eigen/Geometry>\n#include <bench/BenchTimer.h>\n\nusing namespace Eigen; \n\ntemplate<typename Quat>\nEIGEN_DONT_INLINE void quatmul_default(const Quat& a, const Quat& b, Quat& c)\n{\n  c = a * b;\n}\n\ntemplate<typename Quat>\nEIGEN_DONT_INLINE void quatmul_novec(const Quat& a, const Quat& b, Quat& c)\n{\n  c = internal::quat_product<0, Quat, Quat, typename Quat::Scalar, Aligned>::run(a,b);\n}\n\ntemplate<typename Quat> void bench(const std::string& label)\n{\n  int tries = 10;\n  int rep = 1000000;\n  BenchTimer t;\n  \n  Quat a(4, 1, 2, 3);\n  Quat b(2, 3, 4, 5);\n  Quat c;\n  \n  std::cout.precision(3);\n  \n  BENCH(t, tries, rep, quatmul_default(a,b,c));\n  std::cout << label << \" default \" << 1e3*t.best(CPU_TIMER) << \"ms  \\t\" << 1e-6*double(rep)/(t.best(CPU_TIMER)) << \" M mul/s\\n\";\n  \n  BENCH(t, tries, rep, quatmul_novec(a,b,c));\n  std::cout << label << \" novec   \" << 1e3*t.best(CPU_TIMER) << \"ms  \\t\" << 1e-6*double(rep)/(t.best(CPU_TIMER)) << \" M mul/s\\n\";\n}\n\nint main()\n{\n  bench<Quaternionf>(\"float \");\n  bench<Quaterniond>(\"double\");\n\n  return 0;\n\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/sparse_cholesky.cpp",
    "content": "// #define EIGEN_TAUCS_SUPPORT\n// #define EIGEN_CHOLMOD_SUPPORT\n#include <iostream>\n#include <Eigen/Sparse>\n\n// g++ -DSIZE=10000 -DDENSITY=0.001  sparse_cholesky.cpp -I.. -DDENSEMATRI -O3 -g0 -DNDEBUG   -DNBTRIES=1 -I /home/gael/Coding/LinearAlgebra/taucs_full/src/ -I/home/gael/Coding/LinearAlgebra/taucs_full/build/linux/  -L/home/gael/Coding/LinearAlgebra/taucs_full/lib/linux/ -ltaucs /home/gael/Coding/LinearAlgebra/GotoBLAS/libgoto.a -lpthread -I /home/gael/Coding/LinearAlgebra/SuiteSparse/CHOLMOD/Include/ $CHOLLIB -I /home/gael/Coding/LinearAlgebra/SuiteSparse/UFconfig/ /home/gael/Coding/LinearAlgebra/SuiteSparse/CCOLAMD/Lib/libccolamd.a   /home/gael/Coding/LinearAlgebra/SuiteSparse/CHOLMOD/Lib/libcholmod.a -lmetis /home/gael/Coding/LinearAlgebra/SuiteSparse/AMD/Lib/libamd.a  /home/gael/Coding/LinearAlgebra/SuiteSparse/CAMD/Lib/libcamd.a   /home/gael/Coding/LinearAlgebra/SuiteSparse/CCOLAMD/Lib/libccolamd.a  /home/gael/Coding/LinearAlgebra/SuiteSparse/COLAMD/Lib/libcolamd.a -llapack && ./a.out\n\n#define NOGMM\n#define NOMTL\n\n#ifndef SIZE\n#define SIZE 10\n#endif\n\n#ifndef DENSITY\n#define DENSITY 0.01\n#endif\n\n#ifndef REPEAT\n#define REPEAT 1\n#endif\n\n#include \"BenchSparseUtil.h\"\n\n#ifndef MINDENSITY\n#define MINDENSITY 0.0004\n#endif\n\n#ifndef NBTRIES\n#define NBTRIES 10\n#endif\n\n#define BENCH(X) \\\n  timer.reset(); \\\n  for (int _j=0; _j<NBTRIES; ++_j) { \\\n    timer.start(); \\\n    for (int _k=0; _k<REPEAT; ++_k) { \\\n        X  \\\n  } timer.stop(); }\n\n// typedef SparseMatrix<Scalar,UpperTriangular> EigenSparseTriMatrix;\ntypedef SparseMatrix<Scalar,SelfAdjoint|LowerTriangular> EigenSparseSelfAdjointMatrix;\n\nvoid fillSpdMatrix(float density, int rows, int cols,  EigenSparseSelfAdjointMatrix& dst)\n{\n  dst.startFill(rows*cols*density);\n  for(int j = 0; j < cols; j++)\n  {\n    dst.fill(j,j) = internal::random<Scalar>(10,20);\n    for(int i = j+1; i < rows; i++)\n    {\n      Scalar v = (internal::random<float>(0,1) < density) ? internal::random<Scalar>() : 0;\n      if (v!=0)\n        dst.fill(i,j) = v;\n    }\n\n  }\n  dst.endFill();\n}\n\n#include <Eigen/Cholesky>\n\ntemplate<int Backend>\nvoid doEigen(const char* name, const EigenSparseSelfAdjointMatrix& sm1, int flags = 0)\n{\n  std::cout << name << \"...\" << std::flush;\n  BenchTimer timer;\n  timer.start();\n  SparseLLT<EigenSparseSelfAdjointMatrix,Backend> chol(sm1, flags);\n  timer.stop();\n  std::cout << \":\\t\" << timer.value() << endl;\n\n  std::cout << \"  nnz: \" << sm1.nonZeros() << \" => \" << chol.matrixL().nonZeros() << \"\\n\";\n//   std::cout << \"sparse\\n\" << chol.matrixL() << \"%\\n\";\n}\n\nint main(int argc, char *argv[])\n{\n  int rows = SIZE;\n  int cols = SIZE;\n  float density = DENSITY;\n  BenchTimer timer;\n\n  VectorXf b = VectorXf::Random(cols);\n  VectorXf x = VectorXf::Random(cols);\n\n  bool densedone = false;\n\n  //for (float density = DENSITY; density>=MINDENSITY; density*=0.5)\n//   float density = 0.5;\n  {\n    EigenSparseSelfAdjointMatrix sm1(rows, cols);\n    std::cout << \"Generate sparse matrix (might take a while)...\\n\";\n    fillSpdMatrix(density, rows, cols, sm1);\n    std::cout << \"DONE\\n\\n\";\n\n    // dense matrices\n    #ifdef DENSEMATRIX\n    if (!densedone)\n    {\n      densedone = true;\n      std::cout << \"Eigen Dense\\t\" << density*100 << \"%\\n\";\n      DenseMatrix m1(rows,cols);\n      eiToDense(sm1, m1);\n      m1 = (m1 + m1.transpose()).eval();\n      m1.diagonal() *= 0.5;\n\n//       BENCH(LLT<DenseMatrix> chol(m1);)\n//       std::cout << \"dense:\\t\" << timer.value() << endl;\n\n      BenchTimer timer;\n      timer.start();\n      LLT<DenseMatrix> chol(m1);\n      timer.stop();\n      std::cout << \"dense:\\t\" << timer.value() << endl;\n      int count = 0;\n      for (int j=0; j<cols; ++j)\n        for (int i=j; i<rows; ++i)\n          if (!internal::isMuchSmallerThan(internal::abs(chol.matrixL()(i,j)), 0.1))\n            count++;\n      std::cout << \"dense: \" << \"nnz = \" << count << \"\\n\";\n//       std::cout << \"dense:\\n\" << m1 << \"\\n\\n\" << chol.matrixL() << endl;\n    }\n    #endif\n\n    // eigen sparse matrices\n    doEigen<Eigen::DefaultBackend>(\"Eigen/Sparse\", sm1, Eigen::IncompleteFactorization);\n\n    #ifdef EIGEN_CHOLMOD_SUPPORT\n    doEigen<Eigen::Cholmod>(\"Eigen/Cholmod\", sm1, Eigen::IncompleteFactorization);\n    #endif\n\n    #ifdef EIGEN_TAUCS_SUPPORT\n    doEigen<Eigen::Taucs>(\"Eigen/Taucs\", sm1, Eigen::IncompleteFactorization);\n    #endif\n\n    #if 0\n    // TAUCS\n    {\n      taucs_ccs_matrix A = sm1.asTaucsMatrix();\n\n      //BENCH(taucs_ccs_matrix* chol = taucs_ccs_factor_llt(&A, 0, 0);)\n//       BENCH(taucs_supernodal_factor_to_ccs(taucs_ccs_factor_llt_ll(&A));)\n//       std::cout << \"taucs:\\t\" << timer.value() << endl;\n\n      taucs_ccs_matrix* chol = taucs_ccs_factor_llt(&A, 0, 0);\n\n      for (int j=0; j<cols; ++j)\n      {\n        for (int i=chol->colptr[j]; i<chol->colptr[j+1]; ++i)\n          std::cout << chol->values.d[i] << \" \";\n      }\n    }\n\n    // CHOLMOD\n    #ifdef EIGEN_CHOLMOD_SUPPORT\n    {\n      cholmod_common c;\n      cholmod_start (&c);\n      cholmod_sparse A;\n      cholmod_factor *L;\n\n      A = sm1.asCholmodMatrix();\n      BenchTimer timer;\n//       timer.reset();\n      timer.start();\n      std::vector<int> perm(cols);\n//       std::vector<int> set(ncols);\n      for (int i=0; i<cols; ++i)\n        perm[i] = i;\n//       c.nmethods = 1;\n//       c.method[0] = 1;\n\n      c.nmethods = 1;\n      c.method [0].ordering = CHOLMOD_NATURAL;\n      c.postorder = 0;\n      c.final_ll = 1;\n\n      L = cholmod_analyze_p(&A, &perm[0], &perm[0], cols, &c);\n      timer.stop();\n      std::cout << \"cholmod/analyze:\\t\" << timer.value() << endl;\n      timer.reset();\n      timer.start();\n      cholmod_factorize(&A, L, &c);\n      timer.stop();\n      std::cout << \"cholmod/factorize:\\t\" << timer.value() << endl;\n\n      cholmod_sparse* cholmat = cholmod_factor_to_sparse(L, &c);\n\n      cholmod_print_factor(L, \"Factors\", &c);\n\n      cholmod_print_sparse(cholmat, \"Chol\", &c);\n      cholmod_write_sparse(stdout, cholmat, 0, 0, &c);\n//\n//       cholmod_print_sparse(&A, \"A\", &c);\n//       cholmod_write_sparse(stdout, &A, 0, 0, &c);\n\n\n//       for (int j=0; j<cols; ++j)\n//       {\n//           for (int i=chol->colptr[j]; i<chol->colptr[j+1]; ++i)\n//             std::cout << chol->values.s[i] << \" \";\n//       }\n    }\n    #endif\n\n    #endif\n\n\n\n  }\n\n\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/sparse_dense_product.cpp",
    "content": "\n//g++ -O3 -g0 -DNDEBUG  sparse_product.cpp -I.. -I/home/gael/Coding/LinearAlgebra/mtl4/ -DDENSITY=0.005 -DSIZE=10000 && ./a.out\n//g++ -O3 -g0 -DNDEBUG  sparse_product.cpp -I.. -I/home/gael/Coding/LinearAlgebra/mtl4/ -DDENSITY=0.05 -DSIZE=2000 && ./a.out\n// -DNOGMM -DNOMTL -DCSPARSE\n// -I /home/gael/Coding/LinearAlgebra/CSparse/Include/ /home/gael/Coding/LinearAlgebra/CSparse/Lib/libcsparse.a\n#ifndef SIZE\n#define SIZE 650000\n#endif\n\n#ifndef DENSITY\n#define DENSITY 0.01\n#endif\n\n#ifndef REPEAT\n#define REPEAT 1\n#endif\n\n#include \"BenchSparseUtil.h\"\n\n#ifndef MINDENSITY\n#define MINDENSITY 0.0004\n#endif\n\n#ifndef NBTRIES\n#define NBTRIES 10\n#endif\n\n#define BENCH(X) \\\n  timer.reset(); \\\n  for (int _j=0; _j<NBTRIES; ++_j) { \\\n    timer.start(); \\\n    for (int _k=0; _k<REPEAT; ++_k) { \\\n        X  \\\n  } timer.stop(); }\n\n\n#ifdef CSPARSE\ncs* cs_sorted_multiply(const cs* a, const cs* b)\n{\n  cs* A = cs_transpose (a, 1) ;\n  cs* B = cs_transpose (b, 1) ;\n  cs* D = cs_multiply (B,A) ;   /* D = B'*A' */\n  cs_spfree (A) ;\n  cs_spfree (B) ;\n  cs_dropzeros (D) ;      /* drop zeros from D */\n  cs* C = cs_transpose (D, 1) ;   /* C = D', so that C is sorted */\n  cs_spfree (D) ;\n  return C;\n}\n#endif\n\nint main(int argc, char *argv[])\n{\n  int rows = SIZE;\n  int cols = SIZE;\n  float density = DENSITY;\n\n  EigenSparseMatrix sm1(rows,cols);\n  DenseVector v1(cols), v2(cols);\n  v1.setRandom();\n\n  BenchTimer timer;\n  for (float density = DENSITY; density>=MINDENSITY; density*=0.5)\n  {\n    //fillMatrix(density, rows, cols, sm1);\n    fillMatrix2(7, rows, cols, sm1);\n\n    // dense matrices\n    #ifdef DENSEMATRIX\n    {\n      std::cout << \"Eigen Dense\\t\" << density*100 << \"%\\n\";\n      DenseMatrix m1(rows,cols);\n      eiToDense(sm1, m1);\n\n      timer.reset();\n      timer.start();\n      for (int k=0; k<REPEAT; ++k)\n        v2 = m1 * v1;\n      timer.stop();\n      std::cout << \"   a * v:\\t\" << timer.best() << \"  \" << double(REPEAT)/timer.best() << \" * / sec \" << endl;\n\n      timer.reset();\n      timer.start();\n      for (int k=0; k<REPEAT; ++k)\n        v2 = m1.transpose() * v1;\n      timer.stop();\n      std::cout << \"   a' * v:\\t\" << timer.best() << endl;\n    }\n    #endif\n\n    // eigen sparse matrices\n    {\n      std::cout << \"Eigen sparse\\t\" << sm1.nonZeros()/float(sm1.rows()*sm1.cols())*100 << \"%\\n\";\n\n      BENCH(asm(\"#myc\"); v2 = sm1 * v1; asm(\"#myd\");)\n      std::cout << \"   a * v:\\t\" << timer.best()/REPEAT << \"  \" << double(REPEAT)/timer.best(REAL_TIMER) << \" * / sec \" << endl;\n\n\n      BENCH( { asm(\"#mya\"); v2 = sm1.transpose() * v1; asm(\"#myb\"); })\n\n      std::cout << \"   a' * v:\\t\" << timer.best()/REPEAT << endl;\n    }\n\n//     {\n//       DynamicSparseMatrix<Scalar> m1(sm1);\n//       std::cout << \"Eigen dyn-sparse\\t\" << m1.nonZeros()/float(m1.rows()*m1.cols())*100 << \"%\\n\";\n//\n//       BENCH(for (int k=0; k<REPEAT; ++k) v2 = m1 * v1;)\n//       std::cout << \"   a * v:\\t\" << timer.value() << endl;\n//\n//       BENCH(for (int k=0; k<REPEAT; ++k) v2 = m1.transpose() * v1;)\n//       std::cout << \"   a' * v:\\t\" << timer.value() << endl;\n//     }\n\n    // GMM++\n    #ifndef NOGMM\n    {\n      std::cout << \"GMM++ sparse\\t\" << density*100 << \"%\\n\";\n      //GmmDynSparse  gmmT3(rows,cols);\n      GmmSparse m1(rows,cols);\n      eiToGmm(sm1, m1);\n\n      std::vector<Scalar> gmmV1(cols), gmmV2(cols);\n      Map<Matrix<Scalar,Dynamic,1> >(&gmmV1[0], cols) = v1;\n      Map<Matrix<Scalar,Dynamic,1> >(&gmmV2[0], cols) = v2;\n\n      BENCH( asm(\"#myx\"); gmm::mult(m1, gmmV1, gmmV2); asm(\"#myy\"); )\n      std::cout << \"   a * v:\\t\" << timer.value() << endl;\n\n      BENCH( gmm::mult(gmm::transposed(m1), gmmV1, gmmV2); )\n      std::cout << \"   a' * v:\\t\" << timer.value() << endl;\n    }\n    #endif\n    \n    #ifndef NOUBLAS\n    {\n      std::cout << \"ublas sparse\\t\" << density*100 << \"%\\n\";\n      UBlasSparse m1(rows,cols);\n      eiToUblas(sm1, m1);\n      \n      boost::numeric::ublas::vector<Scalar> uv1, uv2;\n      eiToUblasVec(v1,uv1);\n      eiToUblasVec(v2,uv2);\n\n//       std::vector<Scalar> gmmV1(cols), gmmV2(cols);\n//       Map<Matrix<Scalar,Dynamic,1> >(&gmmV1[0], cols) = v1;\n//       Map<Matrix<Scalar,Dynamic,1> >(&gmmV2[0], cols) = v2;\n\n      BENCH( uv2 = boost::numeric::ublas::prod(m1, uv1); )\n      std::cout << \"   a * v:\\t\" << timer.value() << endl;\n\n//       BENCH( boost::ublas::prod(gmm::transposed(m1), gmmV1, gmmV2); )\n//       std::cout << \"   a' * v:\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    // MTL4\n    #ifndef NOMTL\n    {\n      std::cout << \"MTL4\\t\" << density*100 << \"%\\n\";\n      MtlSparse m1(rows,cols);\n      eiToMtl(sm1, m1);\n      mtl::dense_vector<Scalar> mtlV1(cols, 1.0);\n      mtl::dense_vector<Scalar> mtlV2(cols, 1.0);\n\n      timer.reset();\n      timer.start();\n      for (int k=0; k<REPEAT; ++k)\n        mtlV2 = m1 * mtlV1;\n      timer.stop();\n      std::cout << \"   a * v:\\t\" << timer.value() << endl;\n\n      timer.reset();\n      timer.start();\n      for (int k=0; k<REPEAT; ++k)\n        mtlV2 = trans(m1) * mtlV1;\n      timer.stop();\n      std::cout << \"   a' * v:\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    std::cout << \"\\n\\n\";\n  }\n\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/sparse_lu.cpp",
    "content": "\n// g++ -I.. sparse_lu.cpp -O3 -g0 -I /usr/include/superlu/ -lsuperlu -lgfortran -DSIZE=1000 -DDENSITY=.05 && ./a.out\n\n#define EIGEN_SUPERLU_SUPPORT\n#define EIGEN_UMFPACK_SUPPORT\n#include <Eigen/Sparse>\n\n#define NOGMM\n#define NOMTL\n\n#ifndef SIZE\n#define SIZE 10\n#endif\n\n#ifndef DENSITY\n#define DENSITY 0.01\n#endif\n\n#ifndef REPEAT\n#define REPEAT 1\n#endif\n\n#include \"BenchSparseUtil.h\"\n\n#ifndef MINDENSITY\n#define MINDENSITY 0.0004\n#endif\n\n#ifndef NBTRIES\n#define NBTRIES 10\n#endif\n\n#define BENCH(X) \\\n  timer.reset(); \\\n  for (int _j=0; _j<NBTRIES; ++_j) { \\\n    timer.start(); \\\n    for (int _k=0; _k<REPEAT; ++_k) { \\\n        X  \\\n  } timer.stop(); }\n\ntypedef Matrix<Scalar,Dynamic,1> VectorX;\n\n#include <Eigen/LU>\n\ntemplate<int Backend>\nvoid doEigen(const char* name, const EigenSparseMatrix& sm1, const VectorX& b, VectorX& x, int flags = 0)\n{\n  std::cout << name << \"...\" << std::flush;\n  BenchTimer timer; timer.start();\n  SparseLU<EigenSparseMatrix,Backend> lu(sm1, flags);\n  timer.stop();\n  if (lu.succeeded())\n    std::cout << \":\\t\" << timer.value() << endl;\n  else\n  {\n    std::cout << \":\\t FAILED\" << endl;\n    return;\n  }\n\n  bool ok;\n  timer.reset(); timer.start();\n  ok = lu.solve(b,&x);\n  timer.stop();\n  if (ok)\n    std::cout << \"  solve:\\t\" << timer.value() << endl;\n  else\n    std::cout << \"  solve:\\t\" << \" FAILED\" << endl;\n\n  //std::cout << x.transpose() << \"\\n\";\n}\n\nint main(int argc, char *argv[])\n{\n  int rows = SIZE;\n  int cols = SIZE;\n  float density = DENSITY;\n  BenchTimer timer;\n\n  VectorX b = VectorX::Random(cols);\n  VectorX x = VectorX::Random(cols);\n\n  bool densedone = false;\n\n  //for (float density = DENSITY; density>=MINDENSITY; density*=0.5)\n//   float density = 0.5;\n  {\n    EigenSparseMatrix sm1(rows, cols);\n    fillMatrix(density, rows, cols, sm1);\n\n    // dense matrices\n    #ifdef DENSEMATRIX\n    if (!densedone)\n    {\n      densedone = true;\n      std::cout << \"Eigen Dense\\t\" << density*100 << \"%\\n\";\n      DenseMatrix m1(rows,cols);\n      eiToDense(sm1, m1);\n\n      BenchTimer timer;\n      timer.start();\n      FullPivLU<DenseMatrix> lu(m1);\n      timer.stop();\n      std::cout << \"Eigen/dense:\\t\" << timer.value() << endl;\n\n      timer.reset();\n      timer.start();\n      lu.solve(b,&x);\n      timer.stop();\n      std::cout << \"  solve:\\t\" << timer.value() << endl;\n//       std::cout << b.transpose() << \"\\n\";\n//       std::cout << x.transpose() << \"\\n\";\n    }\n    #endif\n\n    #ifdef EIGEN_UMFPACK_SUPPORT\n    x.setZero();\n    doEigen<Eigen::UmfPack>(\"Eigen/UmfPack (auto)\", sm1, b, x, 0);\n    #endif\n\n    #ifdef EIGEN_SUPERLU_SUPPORT\n    x.setZero();\n    doEigen<Eigen::SuperLU>(\"Eigen/SuperLU (nat)\", sm1, b, x, Eigen::NaturalOrdering);\n//     doEigen<Eigen::SuperLU>(\"Eigen/SuperLU (MD AT+A)\", sm1, b, x, Eigen::MinimumDegree_AT_PLUS_A);\n//     doEigen<Eigen::SuperLU>(\"Eigen/SuperLU (MD ATA)\", sm1, b, x, Eigen::MinimumDegree_ATA);\n    doEigen<Eigen::SuperLU>(\"Eigen/SuperLU (COLAMD)\", sm1, b, x, Eigen::ColApproxMinimumDegree);\n    #endif\n\n  }\n\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/sparse_product.cpp",
    "content": "\n//g++ -O3 -g0 -DNDEBUG  sparse_product.cpp -I.. -I/home/gael/Coding/LinearAlgebra/mtl4/ -DDENSITY=0.005 -DSIZE=10000 && ./a.out\n//g++ -O3 -g0 -DNDEBUG  sparse_product.cpp -I.. -I/home/gael/Coding/LinearAlgebra/mtl4/ -DDENSITY=0.05 -DSIZE=2000 && ./a.out\n// -DNOGMM -DNOMTL -DCSPARSE\n// -I /home/gael/Coding/LinearAlgebra/CSparse/Include/ /home/gael/Coding/LinearAlgebra/CSparse/Lib/libcsparse.a\n\n#include <typeinfo>\n\n#ifndef SIZE\n#define SIZE 1000000\n#endif\n\n#ifndef NNZPERCOL\n#define NNZPERCOL 6\n#endif\n\n#ifndef REPEAT\n#define REPEAT 1\n#endif\n\n#include <algorithm>\n#include \"BenchTimer.h\"\n#include \"BenchUtil.h\"\n#include \"BenchSparseUtil.h\"\n\n#ifndef NBTRIES\n#define NBTRIES 1\n#endif\n\n#define BENCH(X) \\\n  timer.reset(); \\\n  for (int _j=0; _j<NBTRIES; ++_j) { \\\n    timer.start(); \\\n    for (int _k=0; _k<REPEAT; ++_k) { \\\n        X  \\\n  } timer.stop(); }\n\n// #ifdef MKL\n//\n// #include \"mkl_types.h\"\n// #include \"mkl_spblas.h\"\n//\n// template<typename Lhs,typename Rhs,typename Res>\n// void mkl_multiply(const Lhs& lhs, const Rhs& rhs, Res& res)\n// {\n//   char n = 'N';\n//   float alpha = 1;\n//   char matdescra[6];\n//   matdescra[0] = 'G';\n//   matdescra[1] = 0;\n//   matdescra[2] = 0;\n//   matdescra[3] = 'C';\n//   mkl_scscmm(&n, lhs.rows(), rhs.cols(), lhs.cols(), &alpha, matdescra,\n//              lhs._valuePtr(), lhs._innerIndexPtr(), lhs.outerIndexPtr(),\n//              pntre, b, &ldb, &beta, c, &ldc);\n// //   mkl_somatcopy('C', 'T', lhs.rows(), lhs.cols(), 1,\n// //                 lhs._valuePtr(), lhs.rows(), DST, dst_stride);\n// }\n//\n// #endif\n\n\n#ifdef CSPARSE\ncs* cs_sorted_multiply(const cs* a, const cs* b)\n{\n//   return cs_multiply(a,b);\n\n  cs* A = cs_transpose(a, 1);\n  cs* B = cs_transpose(b, 1);\n  cs* D = cs_multiply(B,A);   /* D = B'*A' */\n  cs_spfree (A) ;\n  cs_spfree (B) ;\n  cs_dropzeros (D) ;      /* drop zeros from D */\n  cs* C = cs_transpose (D, 1) ;   /* C = D', so that C is sorted */\n  cs_spfree (D) ;\n  return C;\n\n//   cs* A = cs_transpose(a, 1);\n//   cs* C = cs_transpose(A, 1);\n//   return C;\n}\n\ncs* cs_sorted_multiply2(const cs* a, const cs* b)\n{\n  cs* D = cs_multiply(a,b);\n  cs* E = cs_transpose(D,1);\n  cs_spfree(D);\n  cs* C = cs_transpose(E,1);\n  cs_spfree(E);\n  return C;\n}\n#endif\n\nvoid bench_sort();\n\nint main(int argc, char *argv[])\n{\n//   bench_sort();\n\n  int rows = SIZE;\n  int cols = SIZE;\n  float density = DENSITY;\n\n  EigenSparseMatrix sm1(rows,cols), sm2(rows,cols), sm3(rows,cols), sm4(rows,cols);\n\n  BenchTimer timer;\n  for (int nnzPerCol = NNZPERCOL; nnzPerCol>1; nnzPerCol/=1.1)\n  {\n    sm1.setZero();\n    sm2.setZero();\n    fillMatrix2(nnzPerCol, rows, cols, sm1);\n    fillMatrix2(nnzPerCol, rows, cols, sm2);\n//     std::cerr << \"filling OK\\n\";\n\n    // dense matrices\n    #ifdef DENSEMATRIX\n    {\n      std::cout << \"Eigen Dense\\t\" << nnzPerCol << \"%\\n\";\n      DenseMatrix m1(rows,cols), m2(rows,cols), m3(rows,cols);\n      eiToDense(sm1, m1);\n      eiToDense(sm2, m2);\n\n      timer.reset();\n      timer.start();\n      for (int k=0; k<REPEAT; ++k)\n        m3 = m1 * m2;\n      timer.stop();\n      std::cout << \"   a * b:\\t\" << timer.value() << endl;\n\n      timer.reset();\n      timer.start();\n      for (int k=0; k<REPEAT; ++k)\n        m3 = m1.transpose() * m2;\n      timer.stop();\n      std::cout << \"   a' * b:\\t\" << timer.value() << endl;\n\n      timer.reset();\n      timer.start();\n      for (int k=0; k<REPEAT; ++k)\n        m3 = m1.transpose() * m2.transpose();\n      timer.stop();\n      std::cout << \"   a' * b':\\t\" << timer.value() << endl;\n\n      timer.reset();\n      timer.start();\n      for (int k=0; k<REPEAT; ++k)\n        m3 = m1 * m2.transpose();\n      timer.stop();\n      std::cout << \"   a * b':\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    // eigen sparse matrices\n    {\n      std::cout << \"Eigen sparse\\t\" << sm1.nonZeros()/(float(sm1.rows())*float(sm1.cols()))*100 << \"% * \"\n                << sm2.nonZeros()/(float(sm2.rows())*float(sm2.cols()))*100 << \"%\\n\";\n\n      BENCH(sm3 = sm1 * sm2; )\n      std::cout << \"   a * b:\\t\" << timer.value() << endl;\n\n//       BENCH(sm3 = sm1.transpose() * sm2; )\n//       std::cout << \"   a' * b:\\t\" << timer.value() << endl;\n// //\n//       BENCH(sm3 = sm1.transpose() * sm2.transpose(); )\n//       std::cout << \"   a' * b':\\t\" << timer.value() << endl;\n// //\n//       BENCH(sm3 = sm1 * sm2.transpose(); )\n//       std::cout << \"   a * b' :\\t\" << timer.value() << endl;\n\n\n//       std::cout << \"\\n\";\n//\n//       BENCH( sm3._experimentalNewProduct(sm1, sm2); )\n//       std::cout << \"   a * b:\\t\" << timer.value() << endl;\n//\n//       BENCH(sm3._experimentalNewProduct(sm1.transpose(),sm2); )\n//       std::cout << \"   a' * b:\\t\" << timer.value() << endl;\n// //\n//       BENCH(sm3._experimentalNewProduct(sm1.transpose(),sm2.transpose()); )\n//       std::cout << \"   a' * b':\\t\" << timer.value() << endl;\n// //\n//       BENCH(sm3._experimentalNewProduct(sm1, sm2.transpose());)\n//       std::cout << \"   a * b' :\\t\" << timer.value() << endl;\n    }\n\n    // eigen dyn-sparse matrices\n    /*{\n      DynamicSparseMatrix<Scalar> m1(sm1), m2(sm2), m3(sm3);\n      std::cout << \"Eigen dyn-sparse\\t\" << m1.nonZeros()/(float(m1.rows())*float(m1.cols()))*100 << \"% * \"\n                << m2.nonZeros()/(float(m2.rows())*float(m2.cols()))*100 << \"%\\n\";\n\n//       timer.reset();\n//       timer.start();\n      BENCH(for (int k=0; k<REPEAT; ++k) m3 = m1 * m2;)\n//       timer.stop();\n      std::cout << \"   a * b:\\t\" << timer.value() << endl;\n//       std::cout << sm3 << \"\\n\";\n\n      timer.reset();\n      timer.start();\n//       std::cerr << \"transpose...\\n\";\n//       EigenSparseMatrix sm4 = sm1.transpose();\n//       std::cout << sm4.nonZeros() << \" == \" << sm1.nonZeros() << \"\\n\";\n//       exit(1);\n//       std::cerr << \"transpose OK\\n\";\n//       std::cout << sm1 << \"\\n\\n\" << sm1.transpose() << \"\\n\\n\" << sm4.transpose() << \"\\n\\n\";\n      BENCH(for (int k=0; k<REPEAT; ++k) m3 = m1.transpose() * m2;)\n//       timer.stop();\n      std::cout << \"   a' * b:\\t\" << timer.value() << endl;\n\n//       timer.reset();\n//       timer.start();\n      BENCH( for (int k=0; k<REPEAT; ++k) m3 = m1.transpose() * m2.transpose(); )\n//       timer.stop();\n      std::cout << \"   a' * b':\\t\" << timer.value() << endl;\n\n//       timer.reset();\n//       timer.start();\n      BENCH( for (int k=0; k<REPEAT; ++k) m3 = m1 * m2.transpose(); )\n//       timer.stop();\n      std::cout << \"   a * b' :\\t\" << timer.value() << endl;\n    }*/\n\n    // CSparse\n    #ifdef CSPARSE\n    {\n      std::cout << \"CSparse \\t\" << nnzPerCol << \"%\\n\";\n      cs *m1, *m2, *m3;\n      eiToCSparse(sm1, m1);\n      eiToCSparse(sm2, m2);\n\n      BENCH(\n      {\n        m3 = cs_sorted_multiply(m1, m2);\n        if (!m3)\n        {\n          std::cerr << \"cs_multiply failed\\n\";\n        }\n//         cs_print(m3, 0);\n        cs_spfree(m3);\n      }\n      );\n//       timer.stop();\n      std::cout << \"   a * b:\\t\" << timer.value() << endl;\n\n//       BENCH( { m3 = cs_sorted_multiply2(m1, m2); cs_spfree(m3); } );\n//       std::cout << \"   a * b:\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    #ifndef NOUBLAS\n    {\n      std::cout << \"ublas\\t\" << nnzPerCol << \"%\\n\";\n      UBlasSparse m1(rows,cols), m2(rows,cols), m3(rows,cols);\n      eiToUblas(sm1, m1);\n      eiToUblas(sm2, m2);\n\n      BENCH(boost::numeric::ublas::prod(m1, m2, m3););\n      std::cout << \"   a * b:\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    // GMM++\n    #ifndef NOGMM\n    {\n      std::cout << \"GMM++ sparse\\t\" << nnzPerCol << \"%\\n\";\n      GmmDynSparse  gmmT3(rows,cols);\n      GmmSparse m1(rows,cols), m2(rows,cols), m3(rows,cols);\n      eiToGmm(sm1, m1);\n      eiToGmm(sm2, m2);\n\n      BENCH(gmm::mult(m1, m2, gmmT3););\n      std::cout << \"   a * b:\\t\" << timer.value() << endl;\n\n//       BENCH(gmm::mult(gmm::transposed(m1), m2, gmmT3););\n//       std::cout << \"   a' * b:\\t\" << timer.value() << endl;\n//\n//       if (rows<500)\n//       {\n//         BENCH(gmm::mult(gmm::transposed(m1), gmm::transposed(m2), gmmT3););\n//         std::cout << \"   a' * b':\\t\" << timer.value() << endl;\n//\n//         BENCH(gmm::mult(m1, gmm::transposed(m2), gmmT3););\n//         std::cout << \"   a * b':\\t\" << timer.value() << endl;\n//       }\n//       else\n//       {\n//         std::cout << \"   a' * b':\\t\" << \"forever\" << endl;\n//         std::cout << \"   a * b':\\t\" << \"forever\" << endl;\n//       }\n    }\n    #endif\n\n    // MTL4\n    #ifndef NOMTL\n    {\n      std::cout << \"MTL4\\t\" << nnzPerCol << \"%\\n\";\n      MtlSparse m1(rows,cols), m2(rows,cols), m3(rows,cols);\n      eiToMtl(sm1, m1);\n      eiToMtl(sm2, m2);\n\n      BENCH(m3 = m1 * m2;);\n      std::cout << \"   a * b:\\t\" << timer.value() << endl;\n\n//       BENCH(m3 = trans(m1) * m2;);\n//       std::cout << \"   a' * b:\\t\" << timer.value() << endl;\n//\n//       BENCH(m3 = trans(m1) * trans(m2););\n//       std::cout << \"  a' * b':\\t\" << timer.value() << endl;\n//\n//       BENCH(m3 = m1 * trans(m2););\n//       std::cout << \"   a * b' :\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    std::cout << \"\\n\\n\";\n  }\n\n  return 0;\n}\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/sparse_randomsetter.cpp",
    "content": "\n#define NOGMM\n#define NOMTL\n#define EIGEN_GOOGLEHASH_SUPPORT 1\n\n#include <map>\n#include <ext/hash_map>\n#include <google/dense_hash_map>\n#include <google/sparse_hash_map>\n\n#ifndef SIZE\n#define SIZE 10000\n#endif\n\n#ifndef DENSITY\n#define DENSITY 0.01\n#endif\n\n#ifndef REPEAT\n#define REPEAT 1\n#endif\n\n#include \"BenchSparseUtil.h\"\n\n#ifndef MINDENSITY\n#define MINDENSITY 0.0004\n#endif\n\n#ifndef NBTRIES\n#define NBTRIES 10\n#endif\n\n#define BENCH(X) \\\n  timer.reset(); \\\n  for (int _j=0; _j<NBTRIES; ++_j) { \\\n    timer.start(); \\\n    for (int _k=0; _k<REPEAT; ++_k) { \\\n        X  \\\n  } timer.stop(); }\n\n\nstatic double rtime;\nstatic double nentries;\n\ntemplate<typename SetterType>\nvoid dostuff(const char* name, EigenSparseMatrix& sm1)\n{\n  int rows = sm1.rows();\n  int cols = sm1.cols();\n  sm1.setZero();\n  BenchTimer t;\n  SetterType* set1 = new SetterType(sm1);\n  t.reset(); t.start();\n  for (int k=0; k<nentries; ++k)\n    (*set1)(internal::random<int>(0,rows-1),internal::random<int>(0,cols-1)) += 1;\n  t.stop();\n  std::cout << \"std::map =>      \\t\" << t.value()-rtime\n            << \" nnz=\" << set1->nonZeros() << std::flush;\n\n  // getchar();\n\n  t.reset(); t.start(); delete set1; t.stop();\n  std::cout << \"  back: \\t\" << t.value() << \"\\n\";\n}\n    \nint main(int argc, char *argv[])\n{\n  int rows = SIZE;\n  int cols = SIZE;\n  float density = DENSITY;\n\n  EigenSparseMatrix sm1(rows,cols), sm2(rows,cols);\n\n\n  nentries = rows*cols*density;\n  std::cout << \"n = \" << nentries << \"\\n\";\n  int dummy;\n  BenchTimer t;\n\n  t.reset(); t.start();\n  for (int k=0; k<nentries; ++k)\n    dummy = internal::random<int>(0,rows-1) + internal::random<int>(0,cols-1);\n  t.stop();\n  rtime = t.value();\n  std::cout << \"rtime = \" << rtime << \" (\" << dummy << \")\\n\\n\";\n  const int Bits = 6;\n  for (;;)\n  {\n    dostuff<RandomSetter<EigenSparseMatrix,StdMapTraits,Bits> >(\"std::map     \", sm1);\n    dostuff<RandomSetter<EigenSparseMatrix,GnuHashMapTraits,Bits> >(\"gnu::hash_map\", sm1);\n    dostuff<RandomSetter<EigenSparseMatrix,GoogleDenseHashMapTraits,Bits> >(\"google::dense\", sm1);\n    dostuff<RandomSetter<EigenSparseMatrix,GoogleSparseHashMapTraits,Bits> >(\"google::sparse\", sm1);\n\n//     {\n//       RandomSetter<EigenSparseMatrix,GnuHashMapTraits,Bits> set1(sm1);\n//       t.reset(); t.start();\n//       for (int k=0; k<n; ++k)\n//         set1(internal::random<int>(0,rows-1),internal::random<int>(0,cols-1)) += 1;\n//       t.stop();\n//       std::cout << \"gnu::hash_map => \\t\" << t.value()-rtime\n//                 << \" nnz=\" << set1.nonZeros() << \"\\n\";getchar();\n//     }\n//     {\n//       RandomSetter<EigenSparseMatrix,GoogleDenseHashMapTraits,Bits> set1(sm1);\n//       t.reset(); t.start();\n//       for (int k=0; k<n; ++k)\n//         set1(internal::random<int>(0,rows-1),internal::random<int>(0,cols-1)) += 1;\n//       t.stop();\n//       std::cout << \"google::dense => \\t\" << t.value()-rtime\n//                 << \" nnz=\" << set1.nonZeros() << \"\\n\";getchar();\n//     }\n//     {\n//       RandomSetter<EigenSparseMatrix,GoogleSparseHashMapTraits,Bits> set1(sm1);\n//       t.reset(); t.start();\n//       for (int k=0; k<n; ++k)\n//         set1(internal::random<int>(0,rows-1),internal::random<int>(0,cols-1)) += 1;\n//       t.stop();\n//       std::cout << \"google::sparse => \\t\" << t.value()-rtime\n//                 << \" nnz=\" << set1.nonZeros() << \"\\n\";getchar();\n//     }\n    std::cout << \"\\n\\n\";\n  }\n\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/sparse_setter.cpp",
    "content": "\n//g++ -O3 -g0 -DNDEBUG  sparse_product.cpp -I.. -I/home/gael/Coding/LinearAlgebra/mtl4/ -DDENSITY=0.005 -DSIZE=10000 && ./a.out\n//g++ -O3 -g0 -DNDEBUG  sparse_product.cpp -I.. -I/home/gael/Coding/LinearAlgebra/mtl4/ -DDENSITY=0.05 -DSIZE=2000 && ./a.out\n// -DNOGMM -DNOMTL -DCSPARSE\n// -I /home/gael/Coding/LinearAlgebra/CSparse/Include/ /home/gael/Coding/LinearAlgebra/CSparse/Lib/libcsparse.a\n#ifndef SIZE\n#define SIZE 100000\n#endif\n\n#ifndef NBPERROW\n#define NBPERROW 24\n#endif\n\n#ifndef REPEAT\n#define REPEAT 2\n#endif\n\n#ifndef NBTRIES\n#define NBTRIES 2\n#endif\n\n#ifndef KK\n#define KK 10\n#endif\n\n#ifndef NOGOOGLE\n#define EIGEN_GOOGLEHASH_SUPPORT\n#include <google/sparse_hash_map>\n#endif\n\n#include \"BenchSparseUtil.h\"\n\n#define CHECK_MEM\n// #define CHECK_MEM  std/**/::cout << \"check mem\\n\"; getchar();\n\n#define BENCH(X) \\\n  timer.reset(); \\\n  for (int _j=0; _j<NBTRIES; ++_j) { \\\n    timer.start(); \\\n    for (int _k=0; _k<REPEAT; ++_k) { \\\n        X  \\\n  } timer.stop(); }\n\ntypedef std::vector<Vector2i> Coordinates;\ntypedef std::vector<float> Values;\n\nEIGEN_DONT_INLINE Scalar* setinnerrand_eigen(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_eigen_dynamic(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_eigen_compact(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_eigen_sumeq(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_eigen_gnu_hash(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_eigen_google_dense(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_eigen_google_sparse(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_scipy(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_ublas_mapped(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_ublas_coord(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_ublas_compressed(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_ublas_genvec(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_mtl(const Coordinates& coords, const Values& vals);\n\nint main(int argc, char *argv[])\n{\n  int rows = SIZE;\n  int cols = SIZE;\n  bool fullyrand = true;\n\n  BenchTimer timer;\n  Coordinates coords;\n  Values values;\n  if(fullyrand)\n  {\n    Coordinates pool;\n    pool.reserve(cols*NBPERROW);\n    std::cerr << \"fill pool\" << \"\\n\";\n    for (int i=0; i<cols*NBPERROW; )\n    {\n//       DynamicSparseMatrix<int> stencil(SIZE,SIZE);\n      Vector2i ij(internal::random<int>(0,rows-1),internal::random<int>(0,cols-1));\n//       if(stencil.coeffRef(ij.x(), ij.y())==0)\n      {\n//         stencil.coeffRef(ij.x(), ij.y()) = 1;\n        pool.push_back(ij);\n\n      }\n      ++i;\n    }\n    std::cerr << \"pool ok\" << \"\\n\";\n    int n = cols*NBPERROW*KK;\n    coords.reserve(n);\n    values.reserve(n);\n    for (int i=0; i<n; ++i)\n    {\n      int i = internal::random<int>(0,pool.size());\n      coords.push_back(pool[i]);\n      values.push_back(internal::random<Scalar>());\n    }\n  }\n  else\n  {\n    for (int j=0; j<cols; ++j)\n    for (int i=0; i<NBPERROW; ++i)\n    {\n      coords.push_back(Vector2i(internal::random<int>(0,rows-1),j));\n      values.push_back(internal::random<Scalar>());\n    }\n  }\n  std::cout << \"nnz = \" << coords.size()  << \"\\n\";\n  CHECK_MEM\n\n    // dense matrices\n    #ifdef DENSEMATRIX\n    {\n      BENCH(setrand_eigen_dense(coords,values);)\n      std::cout << \"Eigen Dense\\t\" << timer.value() << \"\\n\";\n    }\n    #endif\n\n    // eigen sparse matrices\n//     if (!fullyrand)\n//     {\n//       BENCH(setinnerrand_eigen(coords,values);)\n//       std::cout << \"Eigen fillrand\\t\" << timer.value() << \"\\n\";\n//     }\n    {\n      BENCH(setrand_eigen_dynamic(coords,values);)\n      std::cout << \"Eigen dynamic\\t\" << timer.value() << \"\\n\";\n    }\n//     {\n//       BENCH(setrand_eigen_compact(coords,values);)\n//       std::cout << \"Eigen compact\\t\" << timer.value() << \"\\n\";\n//     }\n    {\n      BENCH(setrand_eigen_sumeq(coords,values);)\n      std::cout << \"Eigen sumeq\\t\" << timer.value() << \"\\n\";\n    }\n    {\n//       BENCH(setrand_eigen_gnu_hash(coords,values);)\n//       std::cout << \"Eigen std::map\\t\" << timer.value() << \"\\n\";\n    }\n    {\n      BENCH(setrand_scipy(coords,values);)\n      std::cout << \"scipy\\t\" << timer.value() << \"\\n\";\n    }\n    #ifndef NOGOOGLE\n    {\n      BENCH(setrand_eigen_google_dense(coords,values);)\n      std::cout << \"Eigen google dense\\t\" << timer.value() << \"\\n\";\n    }\n    {\n      BENCH(setrand_eigen_google_sparse(coords,values);)\n      std::cout << \"Eigen google sparse\\t\" << timer.value() << \"\\n\";\n    }\n    #endif\n\n    #ifndef NOUBLAS\n    {\n//       BENCH(setrand_ublas_mapped(coords,values);)\n//       std::cout << \"ublas mapped\\t\" << timer.value() << \"\\n\";\n    }\n    {\n      BENCH(setrand_ublas_genvec(coords,values);)\n      std::cout << \"ublas vecofvec\\t\" << timer.value() << \"\\n\";\n    }\n    /*{\n      timer.reset();\n      timer.start();\n      for (int k=0; k<REPEAT; ++k)\n        setrand_ublas_compressed(coords,values);\n      timer.stop();\n      std::cout << \"ublas comp\\t\" << timer.value() << \"\\n\";\n    }\n    {\n      timer.reset();\n      timer.start();\n      for (int k=0; k<REPEAT; ++k)\n        setrand_ublas_coord(coords,values);\n      timer.stop();\n      std::cout << \"ublas coord\\t\" << timer.value() << \"\\n\";\n    }*/\n    #endif\n\n\n    // MTL4\n    #ifndef NOMTL\n    {\n      BENCH(setrand_mtl(coords,values));\n      std::cout << \"MTL\\t\" << timer.value() << \"\\n\";\n    }\n    #endif\n\n  return 0;\n}\n\nEIGEN_DONT_INLINE Scalar* setinnerrand_eigen(const Coordinates& coords, const Values& vals)\n{\n  using namespace Eigen;\n  SparseMatrix<Scalar> mat(SIZE,SIZE);\n  //mat.startFill(2000000/*coords.size()*/);\n  for (int i=0; i<coords.size(); ++i)\n  {\n    mat.insert(coords[i].x(), coords[i].y()) = vals[i];\n  }\n  mat.finalize();\n  CHECK_MEM;\n  return 0;\n}\n\nEIGEN_DONT_INLINE Scalar* setrand_eigen_dynamic(const Coordinates& coords, const Values& vals)\n{\n  using namespace Eigen;\n  DynamicSparseMatrix<Scalar> mat(SIZE,SIZE);\n  mat.reserve(coords.size()/10);\n  for (int i=0; i<coords.size(); ++i)\n  {\n    mat.coeffRef(coords[i].x(), coords[i].y()) += vals[i];\n  }\n  mat.finalize();\n  CHECK_MEM;\n  return &mat.coeffRef(coords[0].x(), coords[0].y());\n}\n\nEIGEN_DONT_INLINE Scalar* setrand_eigen_sumeq(const Coordinates& coords, const Values& vals)\n{\n  using namespace Eigen;\n  int n = coords.size()/KK;\n  DynamicSparseMatrix<Scalar> mat(SIZE,SIZE);\n  for (int j=0; j<KK; ++j)\n  {\n    DynamicSparseMatrix<Scalar> aux(SIZE,SIZE);\n    mat.reserve(n);\n    for (int i=j*n; i<(j+1)*n; ++i)\n    {\n      aux.insert(coords[i].x(), coords[i].y()) += vals[i];\n    }\n    aux.finalize();\n    mat += aux;\n  }\n  return &mat.coeffRef(coords[0].x(), coords[0].y());\n}\n\nEIGEN_DONT_INLINE Scalar* setrand_eigen_compact(const Coordinates& coords, const Values& vals)\n{\n  using namespace Eigen;\n  DynamicSparseMatrix<Scalar> setter(SIZE,SIZE);\n  setter.reserve(coords.size()/10);\n  for (int i=0; i<coords.size(); ++i)\n  {\n    setter.coeffRef(coords[i].x(), coords[i].y()) += vals[i];\n  }\n  SparseMatrix<Scalar> mat = setter;\n  CHECK_MEM;\n  return &mat.coeffRef(coords[0].x(), coords[0].y());\n}\n\nEIGEN_DONT_INLINE Scalar* setrand_eigen_gnu_hash(const Coordinates& coords, const Values& vals)\n{\n  using namespace Eigen;\n  SparseMatrix<Scalar> mat(SIZE,SIZE);\n  {\n    RandomSetter<SparseMatrix<Scalar>, StdMapTraits > setter(mat);\n    for (int i=0; i<coords.size(); ++i)\n    {\n      setter(coords[i].x(), coords[i].y()) += vals[i];\n    }\n    CHECK_MEM;\n  }\n  return &mat.coeffRef(coords[0].x(), coords[0].y());\n}\n\n#ifndef NOGOOGLE\nEIGEN_DONT_INLINE Scalar* setrand_eigen_google_dense(const Coordinates& coords, const Values& vals)\n{\n  using namespace Eigen;\n  SparseMatrix<Scalar> mat(SIZE,SIZE);\n  {\n    RandomSetter<SparseMatrix<Scalar>, GoogleDenseHashMapTraits> setter(mat);\n    for (int i=0; i<coords.size(); ++i)\n      setter(coords[i].x(), coords[i].y()) += vals[i];\n    CHECK_MEM;\n  }\n  return &mat.coeffRef(coords[0].x(), coords[0].y());\n}\n\nEIGEN_DONT_INLINE Scalar* setrand_eigen_google_sparse(const Coordinates& coords, const Values& vals)\n{\n  using namespace Eigen;\n  SparseMatrix<Scalar> mat(SIZE,SIZE);\n  {\n    RandomSetter<SparseMatrix<Scalar>, GoogleSparseHashMapTraits> setter(mat);\n    for (int i=0; i<coords.size(); ++i)\n      setter(coords[i].x(), coords[i].y()) += vals[i];\n    CHECK_MEM;\n  }\n  return &mat.coeffRef(coords[0].x(), coords[0].y());\n}\n#endif\n\n\ntemplate <class T>\nvoid coo_tocsr(const int n_row,\n               const int n_col,\n               const int nnz,\n               const Coordinates Aij,\n               const Values Ax,\n                     int Bp[],\n                     int Bj[],\n                     T Bx[])\n{\n    //compute number of non-zero entries per row of A coo_tocsr\n    std::fill(Bp, Bp + n_row, 0);\n\n    for (int n = 0; n < nnz; n++){\n        Bp[Aij[n].x()]++;\n    }\n\n    //cumsum the nnz per row to get Bp[]\n    for(int i = 0, cumsum = 0; i < n_row; i++){\n        int temp = Bp[i];\n        Bp[i] = cumsum;\n        cumsum += temp;\n    }\n    Bp[n_row] = nnz;\n\n    //write Aj,Ax into Bj,Bx\n    for(int n = 0; n < nnz; n++){\n        int row  = Aij[n].x();\n        int dest = Bp[row];\n\n        Bj[dest] = Aij[n].y();\n        Bx[dest] = Ax[n];\n\n        Bp[row]++;\n    }\n\n    for(int i = 0, last = 0; i <= n_row; i++){\n        int temp = Bp[i];\n        Bp[i]  = last;\n        last   = temp;\n    }\n\n    //now Bp,Bj,Bx form a CSR representation (with possible duplicates)\n}\n\ntemplate< class T1, class T2 >\nbool kv_pair_less(const std::pair<T1,T2>& x, const std::pair<T1,T2>& y){\n    return x.first < y.first;\n}\n\n\ntemplate<class I, class T>\nvoid csr_sort_indices(const I n_row,\n                      const I Ap[],\n                            I Aj[],\n                            T Ax[])\n{\n    std::vector< std::pair<I,T> > temp;\n\n    for(I i = 0; i < n_row; i++){\n        I row_start = Ap[i];\n        I row_end   = Ap[i+1];\n\n        temp.clear();\n\n        for(I jj = row_start; jj < row_end; jj++){\n            temp.push_back(std::make_pair(Aj[jj],Ax[jj]));\n        }\n\n        std::sort(temp.begin(),temp.end(),kv_pair_less<I,T>);\n\n        for(I jj = row_start, n = 0; jj < row_end; jj++, n++){\n            Aj[jj] = temp[n].first;\n            Ax[jj] = temp[n].second;\n        }\n    }\n}\n\ntemplate <class I, class T>\nvoid csr_sum_duplicates(const I n_row,\n                        const I n_col,\n                              I Ap[],\n                              I Aj[],\n                              T Ax[])\n{\n    I nnz = 0;\n    I row_end = 0;\n    for(I i = 0; i < n_row; i++){\n        I jj = row_end;\n        row_end = Ap[i+1];\n        while( jj < row_end ){\n            I j = Aj[jj];\n            T x = Ax[jj];\n            jj++;\n            while( jj < row_end && Aj[jj] == j ){\n                x += Ax[jj];\n                jj++;\n            }\n            Aj[nnz] = j;\n            Ax[nnz] = x;\n            nnz++;\n        }\n        Ap[i+1] = nnz;\n    }\n}\n\nEIGEN_DONT_INLINE Scalar* setrand_scipy(const Coordinates& coords, const Values& vals)\n{\n  using namespace Eigen;\n  SparseMatrix<Scalar> mat(SIZE,SIZE);\n  mat.resizeNonZeros(coords.size());\n//   std::cerr << \"setrand_scipy...\\n\";\n  coo_tocsr<Scalar>(SIZE,SIZE, coords.size(), coords, vals, mat._outerIndexPtr(), mat._innerIndexPtr(), mat._valuePtr());\n//   std::cerr << \"coo_tocsr ok\\n\";\n\n  csr_sort_indices(SIZE, mat._outerIndexPtr(), mat._innerIndexPtr(), mat._valuePtr());\n\n  csr_sum_duplicates(SIZE, SIZE, mat._outerIndexPtr(), mat._innerIndexPtr(), mat._valuePtr());\n\n  mat.resizeNonZeros(mat._outerIndexPtr()[SIZE]);\n\n  return &mat.coeffRef(coords[0].x(), coords[0].y());\n}\n\n\n#ifndef NOUBLAS\nEIGEN_DONT_INLINE Scalar* setrand_ublas_mapped(const Coordinates& coords, const Values& vals)\n{\n  using namespace boost;\n  using namespace boost::numeric;\n  using namespace boost::numeric::ublas;\n  mapped_matrix<Scalar> aux(SIZE,SIZE);\n  for (int i=0; i<coords.size(); ++i)\n  {\n    aux(coords[i].x(), coords[i].y()) += vals[i];\n  }\n  CHECK_MEM;\n  compressed_matrix<Scalar> mat(aux);\n  return 0;// &mat(coords[0].x(), coords[0].y());\n}\n/*EIGEN_DONT_INLINE Scalar* setrand_ublas_coord(const Coordinates& coords, const Values& vals)\n{\n  using namespace boost;\n  using namespace boost::numeric;\n  using namespace boost::numeric::ublas;\n  coordinate_matrix<Scalar> aux(SIZE,SIZE);\n  for (int i=0; i<coords.size(); ++i)\n  {\n    aux(coords[i].x(), coords[i].y()) = vals[i];\n  }\n  compressed_matrix<Scalar> mat(aux);\n  return 0;//&mat(coords[0].x(), coords[0].y());\n}\nEIGEN_DONT_INLINE Scalar* setrand_ublas_compressed(const Coordinates& coords, const Values& vals)\n{\n  using namespace boost;\n  using namespace boost::numeric;\n  using namespace boost::numeric::ublas;\n  compressed_matrix<Scalar> mat(SIZE,SIZE);\n  for (int i=0; i<coords.size(); ++i)\n  {\n    mat(coords[i].x(), coords[i].y()) = vals[i];\n  }\n  return 0;//&mat(coords[0].x(), coords[0].y());\n}*/\nEIGEN_DONT_INLINE Scalar* setrand_ublas_genvec(const Coordinates& coords, const Values& vals)\n{\n  using namespace boost;\n  using namespace boost::numeric;\n  using namespace boost::numeric::ublas;\n\n//   ublas::vector<coordinate_vector<Scalar> > foo;\n  generalized_vector_of_vector<Scalar, row_major, ublas::vector<coordinate_vector<Scalar> > > aux(SIZE,SIZE);\n  for (int i=0; i<coords.size(); ++i)\n  {\n    aux(coords[i].x(), coords[i].y()) += vals[i];\n  }\n  CHECK_MEM;\n  compressed_matrix<Scalar,row_major> mat(aux);\n  return 0;//&mat(coords[0].x(), coords[0].y());\n}\n#endif\n\n#ifndef NOMTL\nEIGEN_DONT_INLINE void setrand_mtl(const Coordinates& coords, const Values& vals);\n#endif\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/sparse_transpose.cpp",
    "content": "\n//g++ -O3 -g0 -DNDEBUG  sparse_transpose.cpp -I.. -I/home/gael/Coding/LinearAlgebra/mtl4/ -DDENSITY=0.005 -DSIZE=10000 && ./a.out\n// -DNOGMM -DNOMTL\n// -DCSPARSE -I /home/gael/Coding/LinearAlgebra/CSparse/Include/ /home/gael/Coding/LinearAlgebra/CSparse/Lib/libcsparse.a\n\n#ifndef SIZE\n#define SIZE 10000\n#endif\n\n#ifndef DENSITY\n#define DENSITY 0.01\n#endif\n\n#ifndef REPEAT\n#define REPEAT 1\n#endif\n\n#include \"BenchSparseUtil.h\"\n\n#ifndef MINDENSITY\n#define MINDENSITY 0.0004\n#endif\n\n#ifndef NBTRIES\n#define NBTRIES 10\n#endif\n\n#define BENCH(X) \\\n  timer.reset(); \\\n  for (int _j=0; _j<NBTRIES; ++_j) { \\\n    timer.start(); \\\n    for (int _k=0; _k<REPEAT; ++_k) { \\\n        X  \\\n  } timer.stop(); }\n\nint main(int argc, char *argv[])\n{\n  int rows = SIZE;\n  int cols = SIZE;\n  float density = DENSITY;\n\n  EigenSparseMatrix sm1(rows,cols), sm3(rows,cols);\n\n  BenchTimer timer;\n  for (float density = DENSITY; density>=MINDENSITY; density*=0.5)\n  {\n    fillMatrix(density, rows, cols, sm1);\n\n    // dense matrices\n    #ifdef DENSEMATRIX\n    {\n      DenseMatrix m1(rows,cols), m3(rows,cols);\n      eiToDense(sm1, m1);\n      BENCH(for (int k=0; k<REPEAT; ++k) m3 = m1.transpose();)\n      std::cout << \"  Eigen dense:\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    std::cout << \"Non zeros: \" << sm1.nonZeros()/float(sm1.rows()*sm1.cols())*100 << \"%\\n\";\n\n    // eigen sparse matrices\n    {\n      BENCH(for (int k=0; k<REPEAT; ++k) sm3 = sm1.transpose();)\n      std::cout << \"  Eigen:\\t\" << timer.value() << endl;\n    }\n\n    // CSparse\n    #ifdef CSPARSE\n    {\n      cs *m1, *m3;\n      eiToCSparse(sm1, m1);\n\n      BENCH(for (int k=0; k<REPEAT; ++k) { m3 = cs_transpose(m1,1); cs_spfree(m3);})\n      std::cout << \"  CSparse:\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    // GMM++\n    #ifndef NOGMM\n    {\n      GmmDynSparse  gmmT3(rows,cols);\n      GmmSparse m1(rows,cols), m3(rows,cols);\n      eiToGmm(sm1, m1);\n      BENCH(for (int k=0; k<REPEAT; ++k) gmm::copy(gmm::transposed(m1),m3);)\n      std::cout << \"  GMM:\\t\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    // MTL4\n    #ifndef NOMTL\n    {\n      MtlSparse m1(rows,cols), m3(rows,cols);\n      eiToMtl(sm1, m1);\n      BENCH(for (int k=0; k<REPEAT; ++k) m3 = trans(m1);)\n      std::cout << \"  MTL4:\\t\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    std::cout << \"\\n\\n\";\n  }\n\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/sparse_trisolver.cpp",
    "content": "\n//g++ -O3 -g0 -DNDEBUG  sparse_product.cpp -I.. -I/home/gael/Coding/LinearAlgebra/mtl4/ -DDENSITY=0.005 -DSIZE=10000 && ./a.out\n//g++ -O3 -g0 -DNDEBUG  sparse_product.cpp -I.. -I/home/gael/Coding/LinearAlgebra/mtl4/ -DDENSITY=0.05 -DSIZE=2000 && ./a.out\n// -DNOGMM -DNOMTL\n// -I /home/gael/Coding/LinearAlgebra/CSparse/Include/ /home/gael/Coding/LinearAlgebra/CSparse/Lib/libcsparse.a\n\n#ifndef SIZE\n#define SIZE 10000\n#endif\n\n#ifndef DENSITY\n#define DENSITY 0.01\n#endif\n\n#ifndef REPEAT\n#define REPEAT 1\n#endif\n\n#include \"BenchSparseUtil.h\"\n\n#ifndef MINDENSITY\n#define MINDENSITY 0.0004\n#endif\n\n#ifndef NBTRIES\n#define NBTRIES 10\n#endif\n\n#define BENCH(X) \\\n  timer.reset(); \\\n  for (int _j=0; _j<NBTRIES; ++_j) { \\\n    timer.start(); \\\n    for (int _k=0; _k<REPEAT; ++_k) { \\\n        X  \\\n  } timer.stop(); }\n\ntypedef SparseMatrix<Scalar,UpperTriangular> EigenSparseTriMatrix;\ntypedef SparseMatrix<Scalar,RowMajorBit|UpperTriangular> EigenSparseTriMatrixRow;\n\nvoid fillMatrix(float density, int rows, int cols,  EigenSparseTriMatrix& dst)\n{\n  dst.startFill(rows*cols*density);\n  for(int j = 0; j < cols; j++)\n  {\n    for(int i = 0; i < j; i++)\n    {\n      Scalar v = (internal::random<float>(0,1) < density) ? internal::random<Scalar>() : 0;\n      if (v!=0)\n        dst.fill(i,j) = v;\n    }\n    dst.fill(j,j) = internal::random<Scalar>();\n  }\n  dst.endFill();\n}\n\nint main(int argc, char *argv[])\n{\n  int rows = SIZE;\n  int cols = SIZE;\n  float density = DENSITY;\n  BenchTimer timer;\n  #if 1\n  EigenSparseTriMatrix sm1(rows,cols);\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n  DenseVector b = DenseVector::Random(cols);\n  DenseVector x = DenseVector::Random(cols);\n\n  bool densedone = false;\n\n  for (float density = DENSITY; density>=MINDENSITY; density*=0.5)\n  {\n    EigenSparseTriMatrix sm1(rows, cols);\n    fillMatrix(density, rows, cols, sm1);\n\n    // dense matrices\n    #ifdef DENSEMATRIX\n    if (!densedone)\n    {\n      densedone = true;\n      std::cout << \"Eigen Dense\\t\" << density*100 << \"%\\n\";\n      DenseMatrix m1(rows,cols);\n      Matrix<Scalar,Dynamic,Dynamic,Dynamic,Dynamic,RowMajorBit> m2(rows,cols);\n      eiToDense(sm1, m1);\n      m2 = m1;\n\n      BENCH(x = m1.marked<UpperTriangular>().solveTriangular(b);)\n      std::cout << \"   colmajor^-1 * b:\\t\" << timer.value() << endl;\n//       std::cerr << x.transpose() << \"\\n\";\n\n      BENCH(x = m2.marked<UpperTriangular>().solveTriangular(b);)\n      std::cout << \"   rowmajor^-1 * b:\\t\" << timer.value() << endl;\n//       std::cerr << x.transpose() << \"\\n\";\n    }\n    #endif\n\n    // eigen sparse matrices\n    {\n      std::cout << \"Eigen sparse\\t\" << density*100 << \"%\\n\";\n      EigenSparseTriMatrixRow sm2 = sm1;\n\n      BENCH(x = sm1.solveTriangular(b);)\n      std::cout << \"   colmajor^-1 * b:\\t\" << timer.value() << endl;\n//       std::cerr << x.transpose() << \"\\n\";\n\n      BENCH(x = sm2.solveTriangular(b);)\n      std::cout << \"   rowmajor^-1 * b:\\t\" << timer.value() << endl;\n//       std::cerr << x.transpose() << \"\\n\";\n\n//       x = b;\n//       BENCH(sm1.inverseProductInPlace(x);)\n//       std::cout << \"   colmajor^-1 * b:\\t\" << timer.value() << \" (inplace)\" << endl;\n//       std::cerr << x.transpose() << \"\\n\";\n//\n//       x = b;\n//       BENCH(sm2.inverseProductInPlace(x);)\n//       std::cout << \"   rowmajor^-1 * b:\\t\" << timer.value() << \" (inplace)\" << endl;\n//       std::cerr << x.transpose() << \"\\n\";\n    }\n\n\n\n    // CSparse\n    #ifdef CSPARSE\n    {\n      std::cout << \"CSparse \\t\" << density*100 << \"%\\n\";\n      cs *m1;\n      eiToCSparse(sm1, m1);\n\n      BENCH(x = b; if (!cs_lsolve (m1, x.data())){std::cerr << \"cs_lsolve failed\\n\"; break;}; )\n      std::cout << \"   colmajor^-1 * b:\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    // GMM++\n    #ifndef NOGMM\n    {\n      std::cout << \"GMM++ sparse\\t\" << density*100 << \"%\\n\";\n      GmmSparse m1(rows,cols);\n      gmm::csr_matrix<Scalar> m2;\n      eiToGmm(sm1, m1);\n      gmm::copy(m1,m2);\n      std::vector<Scalar> gmmX(cols), gmmB(cols);\n      Map<Matrix<Scalar,Dynamic,1> >(&gmmX[0], cols) = x;\n      Map<Matrix<Scalar,Dynamic,1> >(&gmmB[0], cols) = b;\n\n      gmmX = gmmB;\n      BENCH(gmm::upper_tri_solve(m1, gmmX, false);)\n      std::cout << \"   colmajor^-1 * b:\\t\" << timer.value() << endl;\n//       std::cerr << Map<Matrix<Scalar,Dynamic,1> >(&gmmX[0], cols).transpose() << \"\\n\";\n\n      gmmX = gmmB;\n      BENCH(gmm::upper_tri_solve(m2, gmmX, false);)\n      timer.stop();\n      std::cout << \"   rowmajor^-1 * b:\\t\" << timer.value() << endl;\n//       std::cerr << Map<Matrix<Scalar,Dynamic,1> >(&gmmX[0], cols).transpose() << \"\\n\";\n    }\n    #endif\n\n    // MTL4\n    #ifndef NOMTL\n    {\n      std::cout << \"MTL4\\t\" << density*100 << \"%\\n\";\n      MtlSparse m1(rows,cols);\n      MtlSparseRowMajor m2(rows,cols);\n      eiToMtl(sm1, m1);\n      m2 = m1;\n      mtl::dense_vector<Scalar> x(rows, 1.0);\n      mtl::dense_vector<Scalar> b(rows, 1.0);\n\n      BENCH(x = mtl::upper_trisolve(m1,b);)\n      std::cout << \"   colmajor^-1 * b:\\t\" << timer.value() << endl;\n//       std::cerr << x << \"\\n\";\n\n      BENCH(x = mtl::upper_trisolve(m2,b);)\n      std::cout << \"   rowmajor^-1 * b:\\t\" << timer.value() << endl;\n//       std::cerr << x << \"\\n\";\n    }\n    #endif\n\n\n    std::cout << \"\\n\\n\";\n  }\n  #endif\n\n  #if 0\n    // bench small matrices (in-place versus return bye value)\n    {\n      timer.reset();\n      for (int _j=0; _j<10; ++_j) {\n        Matrix4f m = Matrix4f::Random();\n        Vector4f b = Vector4f::Random();\n        Vector4f x = Vector4f::Random();\n        timer.start();\n        for (int _k=0; _k<1000000; ++_k) {\n          b = m.inverseProduct(b);\n        }\n        timer.stop();\n      }\n      std::cout << \"4x4 :\\t\" << timer.value() << endl;\n    }\n\n    {\n      timer.reset();\n      for (int _j=0; _j<10; ++_j) {\n        Matrix4f m = Matrix4f::Random();\n        Vector4f b = Vector4f::Random();\n        Vector4f x = Vector4f::Random();\n        timer.start();\n        for (int _k=0; _k<1000000; ++_k) {\n          m.inverseProductInPlace(x);\n        }\n        timer.stop();\n      }\n      std::cout << \"4x4 IP :\\t\" << timer.value() << endl;\n    }\n  #endif\n\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/spbench/CMakeLists.txt",
    "content": "\n\nset(BLAS_FOUND TRUE)\nset(LAPACK_FOUND TRUE)\nset(BLAS_LIBRARIES eigen_blas_static)\nset(LAPACK_LIBRARIES eigen_lapack_static)\n\nset(SPARSE_LIBS \"\")\n\n# find_library(PARDISO_LIBRARIES pardiso412-GNU450-X86-64)\n# if(PARDISO_LIBRARIES)\n#   add_definitions(\"-DEIGEN_PARDISO_SUPPORT\")\n#   set(SPARSE_LIBS ${SPARSE_LIBS} ${PARDISO_LIBRARIES})\n# endif()\n\nfind_package(CHOLMOD)\nif(CHOLMOD_FOUND AND BLAS_FOUND AND LAPACK_FOUND)\n  add_definitions(\"-DEIGEN_CHOLMOD_SUPPORT\")\n  include_directories(${CHOLMOD_INCLUDES})\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${CHOLMOD_LIBRARIES} ${BLAS_LIBRARIES} ${LAPACK_LIBRARIES})\n  set(CHOLMOD_ALL_LIBS  ${CHOLMOD_LIBRARIES} ${BLAS_LIBRARIES} ${LAPACK_LIBRARIES})\nendif()\n\nfind_package(UMFPACK)\nif(UMFPACK_FOUND AND BLAS_FOUND)\n  add_definitions(\"-DEIGEN_UMFPACK_SUPPORT\")\n  include_directories(${UMFPACK_INCLUDES})\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${UMFPACK_LIBRARIES} ${BLAS_LIBRARIES})\n  set(UMFPACK_ALL_LIBS ${UMFPACK_LIBRARIES} ${BLAS_LIBRARIES})\nendif()\n\nfind_package(KLU)\nif(KLU_FOUND)\n  add_definitions(\"-DEIGEN_KLU_SUPPORT\")\n  include_directories(${KLU_INCLUDES})\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${KLU_LIBRARIES})\nendif()\n\nfind_package(SuperLU 4.0)\nif(SuperLU_FOUND AND BLAS_FOUND)\n  add_definitions(\"-DEIGEN_SUPERLU_SUPPORT\")\n  include_directories(${SUPERLU_INCLUDES})\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${SUPERLU_LIBRARIES} ${BLAS_LIBRARIES})\n  set(SUPERLU_ALL_LIBS ${SUPERLU_LIBRARIES} ${BLAS_LIBRARIES})\nendif()\n\n\nfind_package(PASTIX QUIET COMPONENTS METIS SCOTCH)\n# check that the PASTIX found is a version without MPI\nfind_path(PASTIX_pastix_nompi.h_INCLUDE_DIRS\n  NAMES pastix_nompi.h\n  HINTS ${PASTIX_INCLUDE_DIRS}\n)\nif (NOT PASTIX_pastix_nompi.h_INCLUDE_DIRS)\n  message(STATUS \"A version of Pastix has been found but pastix_nompi.h does not exist in the include directory.\"\n                 \" Because Eigen tests require a version without MPI, we disable the Pastix backend.\")\nendif()\nif(PASTIX_FOUND AND PASTIX_pastix_nompi.h_INCLUDE_DIRS AND BLAS_FOUND)\n  add_definitions(\"-DEIGEN_PASTIX_SUPPORT\")\n  include_directories(${PASTIX_INCLUDE_DIRS_DEP})\n  if(SCOTCH_FOUND)\n    include_directories(${SCOTCH_INCLUDE_DIRS})\n    set(PASTIX_LIBRARIES ${PASTIX_LIBRARIES} ${SCOTCH_LIBRARIES})\n  elseif(METIS_FOUND)\n    include_directories(${METIS_INCLUDE_DIRS})\n    set(PASTIX_LIBRARIES ${PASTIX_LIBRARIES} ${METIS_LIBRARIES})  \n  endif()\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${PASTIX_LIBRARIES_DEP} ${ORDERING_LIBRARIES})\n  set(PASTIX_ALL_LIBS ${PASTIX_LIBRARIES_DEP})\nendif()\n\nif(METIS_FOUND)\n  include_directories(${METIS_INCLUDE_DIRS})\n  set (SPARSE_LIBS ${SPARSE_LIBS} ${METIS_LIBRARIES})\n  add_definitions(\"-DEIGEN_METIS_SUPPORT\")\nendif()\n\nfind_library(RT_LIBRARY rt)\nif(RT_LIBRARY)\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${RT_LIBRARY})\nendif()\n\nadd_executable(spbenchsolver spbenchsolver.cpp)\ntarget_link_libraries (spbenchsolver ${SPARSE_LIBS})\n\nadd_executable(spsolver sp_solver.cpp)\ntarget_link_libraries (spsolver ${SPARSE_LIBS})\n\n\nadd_executable(test_sparseLU test_sparseLU.cpp)\ntarget_link_libraries (test_sparseLU ${SPARSE_LIBS})\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/spbench/sp_solver.cpp",
    "content": "// Small bench routine for Eigen available in Eigen\n// (C) Desire NUENTSA WAKAM, INRIA\n\n#include <iostream>\n#include <fstream>\n#include <iomanip>\n#include <Eigen/Jacobi>\n#include <Eigen/Householder>\n#include <Eigen/IterativeLinearSolvers>\n#include <Eigen/LU>\n#include <unsupported/Eigen/SparseExtra>\n//#include <Eigen/SparseLU>\n#include <Eigen/SuperLUSupport>\n// #include <unsupported/Eigen/src/IterativeSolvers/Scaling.h>\n#include <bench/BenchTimer.h>\n#include <unsupported/Eigen/IterativeSolvers>\nusing namespace std;\nusing namespace Eigen;\n\nint main(int argc, char **args)\n{\n  SparseMatrix<double, ColMajor> A; \n  typedef SparseMatrix<double, ColMajor>::Index Index;\n  typedef Matrix<double, Dynamic, Dynamic> DenseMatrix;\n  typedef Matrix<double, Dynamic, 1> DenseRhs;\n  VectorXd b, x, tmp;\n  BenchTimer timer,totaltime; \n  //SparseLU<SparseMatrix<double, ColMajor> >   solver;\n//   SuperLU<SparseMatrix<double, ColMajor> >   solver;\n  ConjugateGradient<SparseMatrix<double, ColMajor>, Lower,IncompleteCholesky<double,Lower> > solver; \n  ifstream matrix_file; \n  string line;\n  int  n;\n  // Set parameters\n//   solver.iparm(IPARM_THREAD_NBR) = 4;\n  /* Fill the matrix with sparse matrix stored in Matrix-Market coordinate column-oriented format */\n  if (argc < 2) assert(false && \"please, give the matrix market file \");\n  \n  timer.start();\n  totaltime.start();\n  loadMarket(A, args[1]);\n  cout << \"End charging matrix \" << endl;\n  bool iscomplex=false, isvector=false;\n  int sym;\n  getMarketHeader(args[1], sym, iscomplex, isvector);\n  if (iscomplex) { cout<< \" Not for complex matrices \\n\"; return -1; }\n  if (isvector) { cout << \"The provided file is not a matrix file\\n\"; return -1;}\n  if (sym != 0) { // symmetric matrices, only the lower part is stored\n    SparseMatrix<double, ColMajor> temp; \n    temp = A;\n    A = temp.selfadjointView<Lower>();\n  }\n  timer.stop();\n  \n  n = A.cols();\n  // ====== TESTS FOR SPARSE TUTORIAL ======\n//   cout<< \"OuterSize \" << A.outerSize() << \" inner \" << A.innerSize() << endl; \n//   SparseMatrix<double, RowMajor> mat1(A); \n//   SparseMatrix<double, RowMajor> mat2;\n//   cout << \" norm of A \" << mat1.norm() << endl; ;\n//   PermutationMatrix<Dynamic, Dynamic, int> perm(n);\n//   perm.resize(n,1);\n//   perm.indices().setLinSpaced(n, 0, n-1);\n//   mat2 = perm * mat1;\n//   mat.subrows();\n//   mat2.resize(n,n); \n//   mat2.reserve(10);\n//   mat2.setConstant();\n//   std::cout<< \"NORM \" << mat1.squaredNorm()<< endl;  \n\n  cout<< \"Time to load the matrix \" << timer.value() <<endl;\n  /* Fill the right hand side */\n\n//   solver.set_restart(374);\n  if (argc > 2)\n    loadMarketVector(b, args[2]);\n  else \n  {\n    b.resize(n);\n    tmp.resize(n);\n//       tmp.setRandom();\n    for (int i = 0; i < n; i++) tmp(i) = i; \n    b = A * tmp ;\n  }\n//   Scaling<SparseMatrix<double> > scal; \n//   scal.computeRef(A);\n//   b = scal.LeftScaling().cwiseProduct(b);\n\n  /* Compute the factorization */\n  cout<< \"Starting the factorization \"<< endl; \n  timer.reset();\n  timer.start(); \n  cout<< \"Size of Input Matrix \"<< b.size()<<\"\\n\\n\";\n  cout<< \"Rows and columns \"<< A.rows() <<\" \" <<A.cols() <<\"\\n\";\n  solver.compute(A);\n//   solver.analyzePattern(A);\n//   solver.factorize(A);\n  if (solver.info() != Success) {\n    std::cout<< \"The solver failed \\n\";\n    return -1; \n  }\n  timer.stop(); \n  float time_comp = timer.value(); \n  cout <<\" Compute Time \" << time_comp<< endl; \n  \n  timer.reset();\n  timer.start();\n  x = solver.solve(b);\n//   x = scal.RightScaling().cwiseProduct(x);\n  timer.stop();\n  float time_solve = timer.value(); \n  cout<< \" Time to solve \" << time_solve << endl; \n \n  /* Check the accuracy */\n  VectorXd tmp2 = b - A*x;\n  double tempNorm = tmp2.norm()/b.norm();\n  cout << \"Relative norm of the computed solution : \" << tempNorm <<\"\\n\";\n//   cout << \"Iterations : \" << solver.iterations() << \"\\n\"; \n  \n  totaltime.stop();\n  cout << \"Total time \" << totaltime.value() << \"\\n\";\n//  std::cout<<x.transpose()<<\"\\n\";\n  \n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/spbench/spbench.dtd",
    "content": "<!ELEMENT BENCH (AVAILSOLVER+,LINEARSYSTEM+)>\n  <!ELEMENT AVAILSOLVER (SOLVER+)>\n    <!ELEMENT SOLVER (TYPE,PACKAGE)>\n      <!ELEMENT TYPE (#PCDATA)>  <!-- One of LU, LLT, LDLT, ITER -->\n      <!ELEMENT PACKAGE (#PCDATA)>  <!-- Derived from a library -->\n  <!ELEMENT LINEARSYSTEM (MATRIX,SOLVER_STAT+,BEST_SOLVER,GLOBAL_PARAMS*)>\n    <!ELEMENT MATRIX (NAME,SIZE,ENTRIES,PATTERN?,SYMMETRY,POSDEF?,ARITHMETIC,RHS*)>\n      <!ELEMENT NAME (#PCDATA)>\n      <!ELEMENT SIZE (#PCDATA)>\n      <!ELEMENT ENTRIES (#PCDATA)> <!-- The number of nonzeros elements -->\n      <!ELEMENT PATTERN (#PCDATA)>  <!-- Is structural pattern symmetric or not -->\n      <!ELEMENT SYMMETRY (#PCDATA)> <!-- symmmetry with numerical values -->\n      <!ELEMENT POSDEF (#PCDATA)> <!-- Is the matrix positive definite or not -->\n      <!ELEMENT ARITHMETIC (#PCDATA)> \n      <!ELEMENT RHS (SOURCE)>  <!-- A matrix can have one or more right hand side associated. -->\n        <!ELEMENT SOURCE (#PCDATA)> <!-- Source of the right hand side, either generated or provided -->\n    <!ELEMENT SOLVER_STAT (PARAMS*,TIME,ERROR,ITER?)>\n      <!ELEMENT PARAMS (#PCDATA)>\n      <!ELEMENT TIME (COMPUTE,SOLVE,TOTAL)>\n        <!ELEMENT COMPUTE (#PCDATA)> <!-- Time to analyze,to factorize, or to setup the preconditioner-->\n        <!ELEMENT SOLVE (#PCDATA)> <!-- Time to solve with all the available rhs -->\n        <!ELEMENT TOTAL (#PCDATA)>\n      <!ELEMENT ERROR (#PCDATA)> <!-- Either the relative error or the relative residual norm -->\n      <!ELEMENT ITER (#PCDATA)> <!-- Number of iterations -->\n    <!ELEMENT BEST_SOLVER CDATA> <!-- Id of the best solver -->\n    <!ELEMENT GLOBAL_PARAMS (#PCDATA)> <!-- Parameters shared by all solvers -->\n\n<!ATTLIST SOLVER ID CDATA #REQUIRED>\n<!ATTLIST SOLVER_STAT ID CDATA #REQUIRED>\n<!ATTLIST BEST_SOLVER ID CDATA #REQUIRED>\n<!ATTLIST RHS ID CDATA #IMPLIED>"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/spbench/spbenchsolver.cpp",
    "content": "#include <bench/spbench/spbenchsolver.h>\n\nvoid bench_printhelp()\n{\n    cout<< \" \\nbenchsolver : performs a benchmark of all the solvers available in Eigen \\n\\n\";\n    cout<< \" MATRIX FOLDER : \\n\";\n    cout<< \" The matrices for the benchmark should be collected in a folder specified with an environment variable EIGEN_MATRIXDIR \\n\";\n    cout<< \" The matrices are stored using the matrix market coordinate format \\n\";\n    cout<< \" The matrix and associated right-hand side (rhs) files are named respectively \\n\";\n    cout<< \" as MatrixName.mtx and MatrixName_b.mtx. If the rhs does not exist, a random one is generated. \\n\";\n    cout<< \" If a matrix is SPD, the matrix should be named as MatrixName_SPD.mtx \\n\";\n    cout<< \" If a true solution exists, it should be named as MatrixName_x.mtx; \\n\"     ;\n    cout<< \" it will be used to compute the norm of the error relative to the computed solutions\\n\\n\";\n    cout<< \" OPTIONS : \\n\"; \n    cout<< \" -h or --help \\n    print this help and return\\n\\n\";\n    cout<< \" -d matrixdir \\n    Use matrixdir as the matrix folder instead of the one specified in the environment variable EIGEN_MATRIXDIR\\n\\n\"; \n    cout<< \" -o outputfile.xml \\n    Output the statistics to a xml file \\n\\n\";\n    cout<< \" --eps <RelErr> Sets the relative tolerance for iterative solvers (default 1e-08) \\n\\n\";\n    cout<< \" --maxits <MaxIts> Sets the maximum number of iterations (default 1000) \\n\\n\";\n    \n}\nint main(int argc, char ** args)\n{\n  \n  bool help = ( get_options(argc, args, \"-h\") || get_options(argc, args, \"--help\") );\n  if(help) {\n    bench_printhelp();\n    return 0;\n  }\n\n  // Get the location of the test matrices\n  string matrix_dir;\n  if (!get_options(argc, args, \"-d\", &matrix_dir))\n  {\n    if(getenv(\"EIGEN_MATRIXDIR\") == NULL){\n      std::cerr << \"Please, specify the location of the matrices with -d mat_folder or the environment variable EIGEN_MATRIXDIR \\n\";\n      std::cerr << \" Run with --help to see the list of all the available options \\n\";\n      return -1;\n    }\n    matrix_dir = getenv(\"EIGEN_MATRIXDIR\");\n  }\n     \n  std::ofstream statbuf;\n  string statFile ;\n  \n  // Get the file to write the statistics\n  bool statFileExists = get_options(argc, args, \"-o\", &statFile);\n  if(statFileExists)\n  {\n    statbuf.open(statFile.c_str(), std::ios::out);\n    if(statbuf.good()){\n      statFileExists = true; \n      printStatheader(statbuf);\n      statbuf.close();\n    }\n    else\n      std::cerr << \"Unable to open the provided file for writing... \\n\";\n  }       \n  \n  // Get the maximum number of iterations and the tolerance\n  int maxiters = 1000; \n  double tol = 1e-08; \n  string inval; \n  if (get_options(argc, args, \"--eps\", &inval))\n    tol = atof(inval.c_str()); \n  if(get_options(argc, args, \"--maxits\", &inval))\n    maxiters = atoi(inval.c_str()); \n  \n  string current_dir; \n  // Test the real-arithmetics matrices\n  Browse_Matrices<double>(matrix_dir, statFileExists, statFile,maxiters, tol);\n  \n  // Test the complex-arithmetics matrices\n  Browse_Matrices<std::complex<double> >(matrix_dir, statFileExists, statFile, maxiters, tol); \n  \n  if(statFileExists)\n  {\n    statbuf.open(statFile.c_str(), std::ios::app); \n    statbuf << \"</BENCH> \\n\";\n    cout << \"\\n Output written in \" << statFile << \" ...\\n\";\n    statbuf.close();\n  }\n\n  return 0;\n}\n\n      \n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/spbench/spbenchsolver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#include <iostream>\n#include <fstream>\n#include <Eigen/SparseCore>\n#include <bench/BenchTimer.h>\n#include <cstdlib>\n#include <string>\n#include <Eigen/Cholesky>\n#include <Eigen/Jacobi>\n#include <Eigen/Householder>\n#include <Eigen/IterativeLinearSolvers>\n#include <unsupported/Eigen/IterativeSolvers>\n#include <Eigen/LU>\n#include <unsupported/Eigen/SparseExtra>\n#include <Eigen/SparseLU>\n\n#include \"spbenchstyle.h\"\n\n#ifdef EIGEN_METIS_SUPPORT\n#include <Eigen/MetisSupport>\n#endif\n\n#ifdef EIGEN_CHOLMOD_SUPPORT\n#include <Eigen/CholmodSupport>\n#endif\n\n#ifdef EIGEN_UMFPACK_SUPPORT\n#include <Eigen/UmfPackSupport>\n#endif\n\n#ifdef EIGEN_KLU_SUPPORT\n#include <Eigen/KLUSupport>\n#endif\n\n#ifdef EIGEN_PARDISO_SUPPORT\n#include <Eigen/PardisoSupport>\n#endif\n\n#ifdef EIGEN_SUPERLU_SUPPORT\n#include <Eigen/SuperLUSupport>\n#endif\n\n#ifdef EIGEN_PASTIX_SUPPORT\n#include <Eigen/PaStiXSupport>\n#endif\n\n// CONSTANTS\n#define EIGEN_UMFPACK  10\n#define EIGEN_KLU  11\n#define EIGEN_SUPERLU  20\n#define EIGEN_PASTIX  30\n#define EIGEN_PARDISO  40\n#define EIGEN_SPARSELU_COLAMD 50\n#define EIGEN_SPARSELU_METIS 51\n#define EIGEN_BICGSTAB  60\n#define EIGEN_BICGSTAB_ILUT  61\n#define EIGEN_GMRES 70\n#define EIGEN_GMRES_ILUT 71\n#define EIGEN_SIMPLICIAL_LDLT  80\n#define EIGEN_CHOLMOD_LDLT  90\n#define EIGEN_PASTIX_LDLT  100\n#define EIGEN_PARDISO_LDLT  110\n#define EIGEN_SIMPLICIAL_LLT  120\n#define EIGEN_CHOLMOD_SUPERNODAL_LLT  130\n#define EIGEN_CHOLMOD_SIMPLICIAL_LLT  140\n#define EIGEN_PASTIX_LLT  150\n#define EIGEN_PARDISO_LLT  160\n#define EIGEN_CG  170\n#define EIGEN_CG_PRECOND  180\n\nusing namespace Eigen;\nusing namespace std; \n\n\n// Global variables for input parameters\nint MaximumIters; // Maximum number of iterations\ndouble RelErr; // Relative error of the computed solution\ndouble best_time_val; // Current best time overall solvers \nint best_time_id; //  id of the best solver for the current system \n\ntemplate<typename T> inline typename NumTraits<T>::Real test_precision() { return NumTraits<T>::dummy_precision(); }\ntemplate<> inline float test_precision<float>() { return 1e-3f; }                                                             \ntemplate<> inline double test_precision<double>() { return 1e-6; }                                                            \ntemplate<> inline float test_precision<std::complex<float> >() { return test_precision<float>(); }\ntemplate<> inline double test_precision<std::complex<double> >() { return test_precision<double>(); }\n\nvoid printStatheader(std::ofstream& out)\n{\n  // Print XML header\n  // NOTE It would have been much easier to write these XML documents using external libraries like tinyXML or Xerces-C++.\n  \n  out << \"<?xml version='1.0' encoding='UTF-8'?> \\n\";\n  out << \"<?xml-stylesheet type='text/xsl' href='#stylesheet' ?> \\n\"; \n  out << \"<!DOCTYPE BENCH  [\\n<!ATTLIST xsl:stylesheet\\n id\\t ID  #REQUIRED>\\n]>\";\n  out << \"\\n\\n<!-- Generated by the Eigen library -->\\n\"; \n  \n  out << \"\\n<BENCH> \\n\" ; //root XML element \n  // Print the xsl style section\n  printBenchStyle(out); \n  // List all available solvers \n  out << \" <AVAILSOLVER> \\n\";\n#ifdef EIGEN_UMFPACK_SUPPORT\n  out <<\"  <SOLVER ID='\" << EIGEN_UMFPACK << \"'>\\n\"; \n  out << \"   <TYPE> LU </TYPE> \\n\";\n  out << \"   <PACKAGE> UMFPACK </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n#endif\n#ifdef EIGEN_KLU_SUPPORT\n  out <<\"  <SOLVER ID='\" << EIGEN_KLU << \"'>\\n\";\n  out << \"   <TYPE> LU </TYPE> \\n\";\n  out << \"   <PACKAGE> KLU </PACKAGE> \\n\";\n  out << \"  </SOLVER> \\n\";\n#endif\n#ifdef EIGEN_SUPERLU_SUPPORT\n  out <<\"  <SOLVER ID='\" << EIGEN_SUPERLU << \"'>\\n\"; \n  out << \"   <TYPE> LU </TYPE> \\n\";\n  out << \"   <PACKAGE> SUPERLU </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n#endif\n#ifdef EIGEN_CHOLMOD_SUPPORT\n  out <<\"  <SOLVER ID='\" << EIGEN_CHOLMOD_SIMPLICIAL_LLT << \"'>\\n\"; \n  out << \"   <TYPE> LLT SP</TYPE> \\n\";\n  out << \"   <PACKAGE> CHOLMOD </PACKAGE> \\n\";\n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_CHOLMOD_SUPERNODAL_LLT << \"'>\\n\"; \n  out << \"   <TYPE> LLT</TYPE> \\n\";\n  out << \"   <PACKAGE> CHOLMOD </PACKAGE> \\n\";\n  out << \"  </SOLVER> \\n\";\n  \n  out <<\"  <SOLVER ID='\" << EIGEN_CHOLMOD_LDLT << \"'>\\n\"; \n  out << \"   <TYPE> LDLT </TYPE> \\n\";\n  out << \"   <PACKAGE> CHOLMOD </PACKAGE> \\n\";  \n  out << \"  </SOLVER> \\n\"; \n#endif\n#ifdef EIGEN_PARDISO_SUPPORT\n  out <<\"  <SOLVER ID='\" << EIGEN_PARDISO << \"'>\\n\"; \n  out << \"   <TYPE> LU </TYPE> \\n\";\n  out << \"   <PACKAGE> PARDISO </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_PARDISO_LLT << \"'>\\n\"; \n  out << \"   <TYPE> LLT </TYPE> \\n\";\n  out << \"   <PACKAGE> PARDISO </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_PARDISO_LDLT << \"'>\\n\"; \n  out << \"   <TYPE> LDLT </TYPE> \\n\";\n  out << \"   <PACKAGE> PARDISO </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n#endif\n#ifdef EIGEN_PASTIX_SUPPORT\n  out <<\"  <SOLVER ID='\" << EIGEN_PASTIX << \"'>\\n\"; \n  out << \"   <TYPE> LU </TYPE> \\n\";\n  out << \"   <PACKAGE> PASTIX </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_PASTIX_LLT << \"'>\\n\"; \n  out << \"   <TYPE> LLT </TYPE> \\n\";\n  out << \"   <PACKAGE> PASTIX </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_PASTIX_LDLT << \"'>\\n\"; \n  out << \"   <TYPE> LDLT </TYPE> \\n\";\n  out << \"   <PACKAGE> PASTIX </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n#endif\n  \n  out <<\"  <SOLVER ID='\" << EIGEN_BICGSTAB << \"'>\\n\"; \n  out << \"   <TYPE> BICGSTAB </TYPE> \\n\";\n  out << \"   <PACKAGE> EIGEN </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_BICGSTAB_ILUT << \"'>\\n\"; \n  out << \"   <TYPE> BICGSTAB_ILUT </TYPE> \\n\";\n  out << \"   <PACKAGE> EIGEN </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_GMRES_ILUT << \"'>\\n\"; \n  out << \"   <TYPE> GMRES_ILUT </TYPE> \\n\";\n  out << \"   <PACKAGE> EIGEN </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_SIMPLICIAL_LDLT << \"'>\\n\"; \n  out << \"   <TYPE> LDLT </TYPE> \\n\";\n  out << \"   <PACKAGE> EIGEN </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_SIMPLICIAL_LLT << \"'>\\n\"; \n  out << \"   <TYPE> LLT </TYPE> \\n\";\n  out << \"   <PACKAGE> EIGEN </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_CG << \"'>\\n\"; \n  out << \"   <TYPE> CG </TYPE> \\n\";\n  out << \"   <PACKAGE> EIGEN </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_SPARSELU_COLAMD << \"'>\\n\"; \n  out << \"   <TYPE> LU_COLAMD </TYPE> \\n\";\n  out << \"   <PACKAGE> EIGEN </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n#ifdef EIGEN_METIS_SUPPORT\n  out <<\"  <SOLVER ID='\" << EIGEN_SPARSELU_METIS << \"'>\\n\"; \n  out << \"   <TYPE> LU_METIS </TYPE> \\n\";\n  out << \"   <PACKAGE> EIGEN </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n#endif\n  out << \" </AVAILSOLVER> \\n\"; \n  \n}\n\n\ntemplate<typename Solver, typename Scalar>\nvoid call_solver(Solver &solver, const int solver_id, const typename Solver::MatrixType& A, const Matrix<Scalar, Dynamic, 1>& b, const Matrix<Scalar, Dynamic, 1>& refX,std::ofstream& statbuf)\n{\n  \n  double total_time;\n  double compute_time;\n  double solve_time; \n  double rel_error;\n  Matrix<Scalar, Dynamic, 1> x; \n  BenchTimer timer; \n  timer.reset();\n  timer.start();\n  solver.compute(A); \n  if (solver.info() != Success)\n  {\n    std::cerr << \"Solver failed ... \\n\";\n    return;\n  }\n  timer.stop();\n  compute_time = timer.value();\n  statbuf << \"    <TIME>\\n\"; \n  statbuf << \"     <COMPUTE> \" << timer.value() << \"</COMPUTE>\\n\";\n  std::cout<< \"COMPUTE TIME : \" << timer.value() <<std::endl; \n    \n  timer.reset();\n  timer.start();\n  x = solver.solve(b); \n  if (solver.info() == NumericalIssue)\n  {\n    std::cerr << \"Solver failed ... \\n\";\n    return;\n  }\n  timer.stop();\n  solve_time = timer.value();\n  statbuf << \"     <SOLVE> \" << timer.value() << \"</SOLVE>\\n\"; \n  std::cout<< \"SOLVE TIME : \" << timer.value() <<std::endl; \n  \n  total_time = solve_time + compute_time;\n  statbuf << \"     <TOTAL> \" << total_time << \"</TOTAL>\\n\"; \n  std::cout<< \"TOTAL TIME : \" << total_time <<std::endl; \n  statbuf << \"    </TIME>\\n\"; \n  \n  // Verify the relative error\n  if(refX.size() != 0)\n    rel_error = (refX - x).norm()/refX.norm();\n  else \n  {\n    // Compute the relative residual norm\n    Matrix<Scalar, Dynamic, 1> temp; \n    temp = A * x; \n    rel_error = (b-temp).norm()/b.norm();\n  }\n  statbuf << \"    <ERROR> \" << rel_error << \"</ERROR>\\n\"; \n  std::cout<< \"REL. ERROR : \" << rel_error << \"\\n\\n\" ;\n  if ( rel_error <= RelErr )\n  {\n    // check the best time if convergence\n    if(!best_time_val || (best_time_val > total_time))\n    {\n      best_time_val = total_time;\n      best_time_id = solver_id;\n    }\n  }\n}\n\ntemplate<typename Solver, typename Scalar>\nvoid call_directsolver(Solver& solver, const int solver_id, const typename Solver::MatrixType& A, const Matrix<Scalar, Dynamic, 1>& b, const Matrix<Scalar, Dynamic, 1>& refX, std::string& statFile)\n{\n    std::ofstream statbuf(statFile.c_str(), std::ios::app);\n    statbuf << \"   <SOLVER_STAT ID='\" << solver_id <<\"'>\\n\"; \n    call_solver(solver, solver_id, A, b, refX,statbuf);\n    statbuf << \"   </SOLVER_STAT>\\n\";\n    statbuf.close();\n}\n\ntemplate<typename Solver, typename Scalar>\nvoid call_itersolver(Solver &solver, const int solver_id, const typename Solver::MatrixType& A, const Matrix<Scalar, Dynamic, 1>& b, const Matrix<Scalar, Dynamic, 1>& refX, std::string& statFile)\n{\n  solver.setTolerance(RelErr); \n  solver.setMaxIterations(MaximumIters);\n  \n  std::ofstream statbuf(statFile.c_str(), std::ios::app);\n  statbuf << \" <SOLVER_STAT ID='\" << solver_id <<\"'>\\n\"; \n  call_solver(solver, solver_id, A, b, refX,statbuf); \n  statbuf << \"   <ITER> \"<< solver.iterations() << \"</ITER>\\n\";\n  statbuf << \" </SOLVER_STAT>\\n\";\n  std::cout << \"ITERATIONS : \" << solver.iterations() <<\"\\n\\n\\n\"; \n  \n}\n\n\ntemplate <typename Scalar>\nvoid SelectSolvers(const SparseMatrix<Scalar>&A, unsigned int sym, Matrix<Scalar, Dynamic, 1>& b, const Matrix<Scalar, Dynamic, 1>& refX, std::string& statFile)\n{\n  typedef SparseMatrix<Scalar, ColMajor> SpMat; \n  // First, deal with Nonsymmetric and symmetric matrices\n  best_time_id = 0; \n  best_time_val = 0.0;\n  //UMFPACK\n  #ifdef EIGEN_UMFPACK_SUPPORT\n  {\n    cout << \"Solving with UMFPACK LU ... \\n\"; \n    UmfPackLU<SpMat> solver; \n    call_directsolver(solver, EIGEN_UMFPACK, A, b, refX,statFile); \n  }\n  #endif\n  //KLU\n  #ifdef EIGEN_KLU_SUPPORT\n  {\n    cout << \"Solving with KLU LU ... \\n\";\n    KLU<SpMat> solver;\n    call_directsolver(solver, EIGEN_KLU, A, b, refX,statFile);\n  }\n  #endif\n    //SuperLU\n  #ifdef EIGEN_SUPERLU_SUPPORT\n  {\n    cout << \"\\nSolving with SUPERLU ... \\n\"; \n    SuperLU<SpMat> solver;\n    call_directsolver(solver, EIGEN_SUPERLU, A, b, refX,statFile); \n  }\n  #endif\n    \n   // PaStix LU\n  #ifdef EIGEN_PASTIX_SUPPORT\n  {\n    cout << \"\\nSolving with PASTIX LU ... \\n\"; \n    PastixLU<SpMat> solver; \n    call_directsolver(solver, EIGEN_PASTIX, A, b, refX,statFile) ;\n  }\n  #endif\n\n   //PARDISO LU\n  #ifdef EIGEN_PARDISO_SUPPORT\n  {\n    cout << \"\\nSolving with PARDISO LU ... \\n\"; \n    PardisoLU<SpMat>  solver; \n    call_directsolver(solver, EIGEN_PARDISO, A, b, refX,statFile);\n  }\n  #endif\n  \n  // Eigen SparseLU METIS\n  cout << \"\\n Solving with Sparse LU AND COLAMD ... \\n\";\n  SparseLU<SpMat, COLAMDOrdering<int> >   solver;\n  call_directsolver(solver, EIGEN_SPARSELU_COLAMD, A, b, refX, statFile); \n  // Eigen SparseLU METIS\n  #ifdef EIGEN_METIS_SUPPORT\n  {\n    cout << \"\\n Solving with Sparse LU AND METIS ... \\n\";\n    SparseLU<SpMat, MetisOrdering<int> >   solver;\n    call_directsolver(solver, EIGEN_SPARSELU_METIS, A, b, refX, statFile); \n  }\n  #endif\n  \n  //BiCGSTAB\n  {\n    cout << \"\\nSolving with BiCGSTAB ... \\n\"; \n    BiCGSTAB<SpMat> solver; \n    call_itersolver(solver, EIGEN_BICGSTAB, A, b, refX,statFile);\n  }\n  //BiCGSTAB+ILUT\n  {\n    cout << \"\\nSolving with BiCGSTAB and ILUT ... \\n\"; \n    BiCGSTAB<SpMat, IncompleteLUT<Scalar> > solver; \n    call_itersolver(solver, EIGEN_BICGSTAB_ILUT, A, b, refX,statFile); \n  }\n  \n   \n  //GMRES\n//   {\n//     cout << \"\\nSolving with GMRES ... \\n\"; \n//     GMRES<SpMat> solver; \n//     call_itersolver(solver, EIGEN_GMRES, A, b, refX,statFile); \n//   }\n  //GMRES+ILUT\n  {\n    cout << \"\\nSolving with GMRES and ILUT ... \\n\"; \n    GMRES<SpMat, IncompleteLUT<Scalar> > solver; \n    call_itersolver(solver, EIGEN_GMRES_ILUT, A, b, refX,statFile);\n  }\n  \n  // Hermitian and not necessarily positive-definites\n  if (sym != NonSymmetric)\n  {\n    // Internal Cholesky\n    {\n      cout << \"\\nSolving with Simplicial LDLT ... \\n\"; \n      SimplicialLDLT<SpMat, Lower> solver;\n      call_directsolver(solver, EIGEN_SIMPLICIAL_LDLT, A, b, refX,statFile); \n    }\n    \n    // CHOLMOD\n    #ifdef EIGEN_CHOLMOD_SUPPORT\n    {\n      cout << \"\\nSolving with CHOLMOD LDLT ... \\n\"; \n      CholmodDecomposition<SpMat, Lower> solver;\n      solver.setMode(CholmodLDLt);\n       call_directsolver(solver,EIGEN_CHOLMOD_LDLT, A, b, refX,statFile);\n    }\n    #endif\n    \n    //PASTIX LLT\n    #ifdef EIGEN_PASTIX_SUPPORT\n    {\n      cout << \"\\nSolving with PASTIX LDLT ... \\n\"; \n      PastixLDLT<SpMat, Lower> solver; \n      call_directsolver(solver,EIGEN_PASTIX_LDLT, A, b, refX,statFile); \n    }\n    #endif\n    \n    //PARDISO LLT\n    #ifdef EIGEN_PARDISO_SUPPORT\n    {\n      cout << \"\\nSolving with PARDISO LDLT ... \\n\"; \n      PardisoLDLT<SpMat, Lower> solver; \n      call_directsolver(solver,EIGEN_PARDISO_LDLT, A, b, refX,statFile); \n    }\n    #endif\n  }\n\n   // Now, symmetric POSITIVE DEFINITE matrices\n  if (sym == SPD)\n  {\n    \n    //Internal Sparse Cholesky\n    {\n      cout << \"\\nSolving with SIMPLICIAL LLT ... \\n\"; \n      SimplicialLLT<SpMat, Lower> solver; \n      call_directsolver(solver,EIGEN_SIMPLICIAL_LLT, A, b, refX,statFile); \n    }\n    \n    // CHOLMOD\n    #ifdef EIGEN_CHOLMOD_SUPPORT\n    {\n      // CholMOD SuperNodal LLT\n      cout << \"\\nSolving with CHOLMOD LLT (Supernodal)... \\n\"; \n      CholmodDecomposition<SpMat, Lower> solver;\n      solver.setMode(CholmodSupernodalLLt);\n       call_directsolver(solver,EIGEN_CHOLMOD_SUPERNODAL_LLT, A, b, refX,statFile);\n      // CholMod Simplicial LLT\n      cout << \"\\nSolving with CHOLMOD LLT (Simplicial) ... \\n\"; \n      solver.setMode(CholmodSimplicialLLt);\n      call_directsolver(solver,EIGEN_CHOLMOD_SIMPLICIAL_LLT, A, b, refX,statFile);\n    }\n    #endif\n    \n    //PASTIX LLT\n    #ifdef EIGEN_PASTIX_SUPPORT\n    {\n      cout << \"\\nSolving with PASTIX LLT ... \\n\"; \n      PastixLLT<SpMat, Lower> solver; \n      call_directsolver(solver,EIGEN_PASTIX_LLT, A, b, refX,statFile);\n    }\n    #endif\n    \n    //PARDISO LLT\n    #ifdef EIGEN_PARDISO_SUPPORT\n    {\n      cout << \"\\nSolving with PARDISO LLT ... \\n\"; \n      PardisoLLT<SpMat, Lower> solver; \n      call_directsolver(solver,EIGEN_PARDISO_LLT, A, b, refX,statFile); \n    }\n    #endif\n    \n    // Internal CG\n    {\n      cout << \"\\nSolving with CG ... \\n\"; \n      ConjugateGradient<SpMat, Lower> solver; \n      call_itersolver(solver,EIGEN_CG, A, b, refX,statFile);\n    }\n    //CG+IdentityPreconditioner\n//     {\n//       cout << \"\\nSolving with CG and IdentityPreconditioner ... \\n\"; \n//       ConjugateGradient<SpMat, Lower, IdentityPreconditioner> solver; \n//       call_itersolver(solver,EIGEN_CG_PRECOND, A, b, refX,statFile);\n//     }\n  } // End SPD matrices \n}\n\n/* Browse all the matrices available in the specified folder \n * and solve the associated linear system.\n * The results of each solve are printed in the standard output\n * and optionally in the provided html file\n */\ntemplate <typename Scalar>\nvoid Browse_Matrices(const string folder, bool statFileExists, std::string& statFile, int maxiters, double tol)\n{\n  MaximumIters = maxiters; // Maximum number of iterations, global variable \n  RelErr = tol;  //Relative residual error  as stopping criterion for iterative solvers\n  MatrixMarketIterator<Scalar> it(folder);\n  for ( ; it; ++it)\n  {\n    //print the infos for this linear system \n    if(statFileExists)\n    {\n      std::ofstream statbuf(statFile.c_str(), std::ios::app);\n      statbuf << \"<LINEARSYSTEM> \\n\";\n      statbuf << \"   <MATRIX> \\n\";\n      statbuf << \"     <NAME> \" << it.matname() << \" </NAME>\\n\"; \n      statbuf << \"     <SIZE> \" << it.matrix().rows() << \" </SIZE>\\n\"; \n      statbuf << \"     <ENTRIES> \" << it.matrix().nonZeros() << \"</ENTRIES>\\n\";\n      if (it.sym()!=NonSymmetric)\n      {\n        statbuf << \"     <SYMMETRY> Symmetric </SYMMETRY>\\n\" ; \n        if (it.sym() == SPD) \n          statbuf << \"     <POSDEF> YES </POSDEF>\\n\"; \n        else \n          statbuf << \"     <POSDEF> NO </POSDEF>\\n\"; \n          \n      }\n      else\n      {\n        statbuf << \"     <SYMMETRY> NonSymmetric </SYMMETRY>\\n\" ; \n        statbuf << \"     <POSDEF> NO </POSDEF>\\n\"; \n      }\n      statbuf << \"   </MATRIX> \\n\";\n      statbuf.close();\n    }\n    \n    cout<< \"\\n\\n===================================================== \\n\";\n    cout<< \" ======  SOLVING WITH MATRIX \" << it.matname() << \" ====\\n\";\n    cout<< \" =================================================== \\n\\n\";\n    Matrix<Scalar, Dynamic, 1> refX;\n    if(it.hasrefX()) refX = it.refX();\n    // Call all suitable solvers for this linear system \n    SelectSolvers<Scalar>(it.matrix(), it.sym(), it.rhs(), refX, statFile);\n    \n    if(statFileExists)\n    {\n      std::ofstream statbuf(statFile.c_str(), std::ios::app);\n      statbuf << \"  <BEST_SOLVER ID='\"<< best_time_id\n              << \"'></BEST_SOLVER>\\n\"; \n      statbuf << \" </LINEARSYSTEM> \\n\"; \n      statbuf.close();\n    }\n  } \n} \n\nbool get_options(int argc, char **args, string option, string* value=0)\n{\n  int idx = 1, found=false; \n  while (idx<argc && !found){\n    if (option.compare(args[idx]) == 0){\n      found = true; \n      if(value) *value = args[idx+1];\n    }\n    idx+=2;\n  }\n  return found; \n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/spbench/spbenchstyle.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef SPBENCHSTYLE_H\n#define SPBENCHSTYLE_H\n\nvoid printBenchStyle(std::ofstream& out)\n{\n  out << \"<xsl:stylesheet id='stylesheet' version='1.0' \\\n      xmlns:xsl='http://www.w3.org/1999/XSL/Transform' >\\n \\\n      <xsl:template match='xsl:stylesheet' />\\n \\\n      <xsl:template match='/'> <!-- Root of the document -->\\n \\\n      <html>\\n \\\n        <head> \\n \\\n          <style type='text/css'> \\n \\\n            td { white-space: nowrap;}\\n \\\n          </style>\\n \\\n        </head>\\n \\\n        <body>\";\n  out<<\"<table border='1' width='100%' height='100%'>\\n \\\n        <TR> <!-- Write the table header -->\\n \\\n        <TH>Matrix</TH> <TH>N</TH> <TH> NNZ</TH>  <TH> Sym</TH>  <TH> SPD</TH> <TH> </TH>\\n \\\n          <xsl:for-each select='BENCH/AVAILSOLVER/SOLVER'>\\n \\\n            <xsl:sort select='@ID' data-type='number'/>\\n \\\n            <TH>\\n \\\n              <xsl:value-of select='TYPE' />\\n \\\n              <xsl:text></xsl:text>\\n \\\n              <xsl:value-of select='PACKAGE' />\\n \\\n              <xsl:text></xsl:text>\\n \\\n            </TH>\\n \\\n          </xsl:for-each>\\n \\\n        </TR>\";\n        \n  out<<\"  <xsl:for-each select='BENCH/LINEARSYSTEM'>\\n \\\n          <TR> <!-- print statistics for one linear system-->\\n \\\n            <TH rowspan='4'> <xsl:value-of select='MATRIX/NAME' /> </TH>\\n \\\n            <TD rowspan='4'> <xsl:value-of select='MATRIX/SIZE' /> </TD>\\n \\\n            <TD rowspan='4'> <xsl:value-of select='MATRIX/ENTRIES' /> </TD>\\n \\\n            <TD rowspan='4'> <xsl:value-of select='MATRIX/SYMMETRY' /> </TD>\\n \\\n            <TD rowspan='4'> <xsl:value-of select='MATRIX/POSDEF' /> </TD>\\n \\\n            <TH> Compute Time </TH>\\n \\\n            <xsl:for-each select='SOLVER_STAT'>\\n \\\n              <xsl:sort select='@ID' data-type='number'/>\\n \\\n              <TD> <xsl:value-of select='TIME/COMPUTE' /> </TD>\\n \\\n            </xsl:for-each>\\n \\\n          </TR>\";\n  out<<\"  <TR>\\n \\\n            <TH> Solve Time </TH>\\n \\\n            <xsl:for-each select='SOLVER_STAT'>\\n \\\n              <xsl:sort select='@ID' data-type='number'/>\\n \\\n              <TD> <xsl:value-of select='TIME/SOLVE' /> </TD>\\n \\\n            </xsl:for-each>\\n \\\n          </TR>\\n \\\n          <TR>\\n \\\n            <TH> Total Time </TH>\\n \\\n            <xsl:for-each select='SOLVER_STAT'>\\n \\\n              <xsl:sort select='@ID' data-type='number'/>\\n \\\n              <xsl:choose>\\n \\\n                <xsl:when test='@ID=../BEST_SOLVER/@ID'>\\n \\\n                  <TD style='background-color:red'> <xsl:value-of select='TIME/TOTAL' />  </TD>\\n \\\n                </xsl:when>\\n \\\n                <xsl:otherwise>\\n \\\n                  <TD>  <xsl:value-of select='TIME/TOTAL' /></TD>\\n \\\n                </xsl:otherwise>\\n \\\n              </xsl:choose>\\n \\\n            </xsl:for-each>\\n \\\n          </TR>\";\n  out<<\"  <TR>\\n \\\n              <TH> Error </TH>\\n \\\n              <xsl:for-each select='SOLVER_STAT'>\\n \\\n                <xsl:sort select='@ID' data-type='number'/>\\n \\\n                <TD> <xsl:value-of select='ERROR' />\\n \\\n                <xsl:if test='ITER'>\\n \\\n                  <xsl:text>(</xsl:text>\\n \\\n                  <xsl:value-of select='ITER' />\\n \\\n                  <xsl:text>)</xsl:text>\\n \\\n                </xsl:if> </TD>\\n \\\n              </xsl:for-each>\\n \\\n            </TR>\\n \\\n          </xsl:for-each>\\n \\\n      </table>\\n \\\n    </body>\\n \\\n    </html>\\n \\\n  </xsl:template>\\n \\\n  </xsl:stylesheet>\\n\\n\";\n  \n}\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/spbench/test_sparseLU.cpp",
    "content": "// Small bench routine for Eigen available in Eigen\n// (C) Desire NUENTSA WAKAM, INRIA\n\n#include <iostream>\n#include <fstream>\n#include <iomanip>\n#include <unsupported/Eigen/SparseExtra>\n#include <Eigen/SparseLU>\n#include <bench/BenchTimer.h>\n#ifdef EIGEN_METIS_SUPPORT\n#include <Eigen/MetisSupport>\n#endif\n\nusing namespace std;\nusing namespace Eigen;\n\nint main(int argc, char **args)\n{\n//   typedef complex<double> scalar; \n  typedef double scalar; \n  SparseMatrix<scalar, ColMajor> A; \n  typedef SparseMatrix<scalar, ColMajor>::Index Index;\n  typedef Matrix<scalar, Dynamic, Dynamic> DenseMatrix;\n  typedef Matrix<scalar, Dynamic, 1> DenseRhs;\n  Matrix<scalar, Dynamic, 1> b, x, tmp;\n//   SparseLU<SparseMatrix<scalar, ColMajor>, AMDOrdering<int> >   solver;\n// #ifdef EIGEN_METIS_SUPPORT\n//   SparseLU<SparseMatrix<scalar, ColMajor>, MetisOrdering<int> > solver; \n//   std::cout<< \"ORDERING : METIS\\n\"; \n// #else\n  SparseLU<SparseMatrix<scalar, ColMajor>, COLAMDOrdering<int> >  solver;\n  std::cout<< \"ORDERING : COLAMD\\n\"; \n// #endif\n  \n  ifstream matrix_file; \n  string line;\n  int  n;\n  BenchTimer timer; \n  \n  // Set parameters\n  /* Fill the matrix with sparse matrix stored in Matrix-Market coordinate column-oriented format */\n  if (argc < 2) assert(false && \"please, give the matrix market file \");\n  loadMarket(A, args[1]);\n  cout << \"End charging matrix \" << endl;\n  bool iscomplex=false, isvector=false;\n  int sym;\n  getMarketHeader(args[1], sym, iscomplex, isvector);\n//   if (iscomplex) { cout<< \" Not for complex matrices \\n\"; return -1; }\n  if (isvector) { cout << \"The provided file is not a matrix file\\n\"; return -1;}\n  if (sym != 0) { // symmetric matrices, only the lower part is stored\n    SparseMatrix<scalar, ColMajor> temp; \n    temp = A;\n    A = temp.selfadjointView<Lower>();\n  }\n  n = A.cols();\n  /* Fill the right hand side */\n\n  if (argc > 2)\n    loadMarketVector(b, args[2]);\n  else \n  {\n    b.resize(n);\n    tmp.resize(n);\n//       tmp.setRandom();\n    for (int i = 0; i < n; i++) tmp(i) = i; \n    b = A * tmp ;\n  }\n\n  /* Compute the factorization */\n//   solver.isSymmetric(true);\n  timer.start(); \n//   solver.compute(A);\n  solver.analyzePattern(A); \n  timer.stop(); \n  cout << \"Time to analyze \" << timer.value() << std::endl;\n  timer.reset(); \n  timer.start(); \n  solver.factorize(A); \n  timer.stop(); \n  cout << \"Factorize Time \" << timer.value() << std::endl;\n  timer.reset(); \n  timer.start(); \n  x = solver.solve(b);\n  timer.stop();\n  cout << \"solve time \" << timer.value() << std::endl; \n  /* Check the accuracy */\n  Matrix<scalar, Dynamic, 1> tmp2 = b - A*x;\n  scalar tempNorm = tmp2.norm()/b.norm();\n  cout << \"Relative norm of the computed solution : \" << tempNorm <<\"\\n\";\n  cout << \"Number of nonzeros in the factor : \" << solver.nnzL() + solver.nnzU() << std::endl; \n  \n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/spmv.cpp",
    "content": "\n//g++-4.4 -DNOMTL  -Wl,-rpath /usr/local/lib/oski -L /usr/local/lib/oski/ -l oski -l oski_util -l oski_util_Tid  -DOSKI -I ~/Coding/LinearAlgebra/mtl4/  spmv.cpp  -I .. -O2 -DNDEBUG -lrt  -lm -l oski_mat_CSC_Tid  -loskilt && ./a.out r200000 c200000 n100 t1 p1\n\n#define SCALAR double\n\n#include <iostream>\n#include <algorithm>\n#include \"BenchTimer.h\"\n#include \"BenchSparseUtil.h\"\n\n#define SPMV_BENCH(CODE) BENCH(t,tries,repeats,CODE);\n\n// #ifdef MKL\n//\n// #include \"mkl_types.h\"\n// #include \"mkl_spblas.h\"\n//\n// template<typename Lhs,typename Rhs,typename Res>\n// void mkl_multiply(const Lhs& lhs, const Rhs& rhs, Res& res)\n// {\n//   char n = 'N';\n//   float alpha = 1;\n//   char matdescra[6];\n//   matdescra[0] = 'G';\n//   matdescra[1] = 0;\n//   matdescra[2] = 0;\n//   matdescra[3] = 'C';\n//   mkl_scscmm(&n, lhs.rows(), rhs.cols(), lhs.cols(), &alpha, matdescra,\n//              lhs._valuePtr(), lhs._innerIndexPtr(), lhs.outerIndexPtr(),\n//              pntre, b, &ldb, &beta, c, &ldc);\n// //   mkl_somatcopy('C', 'T', lhs.rows(), lhs.cols(), 1,\n// //                 lhs._valuePtr(), lhs.rows(), DST, dst_stride);\n// }\n//\n// #endif\n\nint main(int argc, char *argv[])\n{\n  int size = 10000;\n  int rows = size;\n  int cols = size;\n  int nnzPerCol = 40;\n  int tries = 2;\n  int repeats = 2;\n\n  bool need_help = false;\n  for(int i = 1; i < argc; i++)\n  {\n    if(argv[i][0] == 'r')\n    {\n      rows = atoi(argv[i]+1);\n    }\n    else if(argv[i][0] == 'c')\n    {\n      cols = atoi(argv[i]+1);\n    }\n    else if(argv[i][0] == 'n')\n    {\n      nnzPerCol = atoi(argv[i]+1);\n    }\n    else if(argv[i][0] == 't')\n    {\n      tries = atoi(argv[i]+1);\n    }\n    else if(argv[i][0] == 'p')\n    {\n      repeats = atoi(argv[i]+1);\n    }\n    else\n    {\n      need_help = true;\n    }\n  }\n  if(need_help)\n  {\n    std::cout << argv[0] << \" r<nb rows> c<nb columns> n<non zeros per column> t<nb tries> p<nb repeats>\\n\";\n    return 1;\n  }\n\n  std::cout << \"SpMV \" << rows << \" x \" << cols << \" with \" << nnzPerCol << \" non zeros per column. (\" << repeats << \" repeats, and \" << tries << \" tries)\\n\\n\";\n\n  EigenSparseMatrix sm(rows,cols);\n  DenseVector dv(cols), res(rows);\n  dv.setRandom();\n\n  BenchTimer t;\n  while (nnzPerCol>=4)\n  {\n    std::cout << \"nnz: \" << nnzPerCol << \"\\n\";\n    sm.setZero();\n    fillMatrix2(nnzPerCol, rows, cols, sm);\n\n    // dense matrices\n    #ifdef DENSEMATRIX\n    {\n      DenseMatrix dm(rows,cols), (rows,cols);\n      eiToDense(sm, dm);\n\n      SPMV_BENCH(res = dm * sm);\n      std::cout << \"Dense       \" << t.value()/repeats << \"\\t\";\n\n      SPMV_BENCH(res = dm.transpose() * sm);\n      std::cout << t.value()/repeats << endl;\n    }\n    #endif\n\n    // eigen sparse matrices\n    {\n      SPMV_BENCH(res.noalias() += sm * dv; )\n      std::cout << \"Eigen       \" << t.value()/repeats << \"\\t\";\n\n      SPMV_BENCH(res.noalias() += sm.transpose() * dv; )\n      std::cout << t.value()/repeats << endl;\n    }\n\n    // CSparse\n    #ifdef CSPARSE\n    {\n      std::cout << \"CSparse \\n\";\n      cs *csm;\n      eiToCSparse(sm, csm);\n\n//       BENCH();\n//       timer.stop();\n//       std::cout << \"   a * b:\\t\" << timer.value() << endl;\n\n//       BENCH( { m3 = cs_sorted_multiply2(m1, m2); cs_spfree(m3); } );\n//       std::cout << \"   a * b:\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    #ifdef OSKI\n    {\n      oski_matrix_t om;\n      oski_vecview_t ov, ores;\n      oski_Init();\n      om = oski_CreateMatCSC(sm._outerIndexPtr(), sm._innerIndexPtr(), sm._valuePtr(), rows, cols,\n                             SHARE_INPUTMAT, 1, INDEX_ZERO_BASED);\n      ov = oski_CreateVecView(dv.data(), cols, STRIDE_UNIT);\n      ores = oski_CreateVecView(res.data(), rows, STRIDE_UNIT);\n\n      SPMV_BENCH( oski_MatMult(om, OP_NORMAL, 1, ov, 0, ores) );\n      std::cout << \"OSKI        \" << t.value()/repeats << \"\\t\";\n\n      SPMV_BENCH( oski_MatMult(om, OP_TRANS, 1, ov, 0, ores) );\n      std::cout << t.value()/repeats << \"\\n\";\n\n      // tune\n      t.reset();\n      t.start();\n      oski_SetHintMatMult(om, OP_NORMAL, 1.0, SYMBOLIC_VEC, 0.0, SYMBOLIC_VEC, ALWAYS_TUNE_AGGRESSIVELY);\n      oski_TuneMat(om);\n      t.stop();\n      double tuning = t.value();\n\n      SPMV_BENCH( oski_MatMult(om, OP_NORMAL, 1, ov, 0, ores) );\n      std::cout << \"OSKI tuned  \" << t.value()/repeats << \"\\t\";\n\n      SPMV_BENCH( oski_MatMult(om, OP_TRANS, 1, ov, 0, ores) );\n      std::cout << t.value()/repeats << \"\\t(\" << tuning <<  \")\\n\";\n\n\n      oski_DestroyMat(om);\n      oski_DestroyVecView(ov);\n      oski_DestroyVecView(ores);\n      oski_Close();\n    }\n    #endif\n\n    #ifndef NOUBLAS\n    {\n      using namespace boost::numeric;\n      UblasMatrix um(rows,cols);\n      eiToUblas(sm, um);\n\n      boost::numeric::ublas::vector<Scalar> uv(cols), ures(rows);\n      Map<Matrix<Scalar,Dynamic,1> >(&uv[0], cols) = dv;\n      Map<Matrix<Scalar,Dynamic,1> >(&ures[0], rows) = res;\n\n      SPMV_BENCH(ublas::axpy_prod(um, uv, ures, true));\n      std::cout << \"ublas       \" << t.value()/repeats << \"\\t\";\n\n      SPMV_BENCH(ublas::axpy_prod(boost::numeric::ublas::trans(um), uv, ures, true));\n      std::cout << t.value()/repeats << endl;\n    }\n    #endif\n\n    // GMM++\n    #ifndef NOGMM\n    {\n      GmmSparse gm(rows,cols);\n      eiToGmm(sm, gm);\n\n      std::vector<Scalar> gv(cols), gres(rows);\n      Map<Matrix<Scalar,Dynamic,1> >(&gv[0], cols) = dv;\n      Map<Matrix<Scalar,Dynamic,1> >(&gres[0], rows) = res;\n\n      SPMV_BENCH(gmm::mult(gm, gv, gres));\n      std::cout << \"GMM++       \" << t.value()/repeats << \"\\t\";\n\n      SPMV_BENCH(gmm::mult(gmm::transposed(gm), gv, gres));\n      std::cout << t.value()/repeats << endl;\n    }\n    #endif\n\n    // MTL4\n    #ifndef NOMTL\n    {\n      MtlSparse mm(rows,cols);\n      eiToMtl(sm, mm);\n      mtl::dense_vector<Scalar> mv(cols, 1.0);\n      mtl::dense_vector<Scalar> mres(rows, 1.0);\n\n      SPMV_BENCH(mres = mm * mv);\n      std::cout << \"MTL4        \" << t.value()/repeats << \"\\t\";\n\n      SPMV_BENCH(mres = trans(mm) * mv);\n      std::cout << t.value()/repeats << endl;\n    }\n    #endif\n\n    std::cout << \"\\n\";\n\n    if(nnzPerCol==1)\n      break;\n    nnzPerCol -= nnzPerCol/2;\n  }\n\n  return 0;\n}\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/tensors/README",
    "content": "The tensor benchmark suite is made of several parts.\n\nThe first part is a generic suite, in which each benchmark comes in 2 flavors: one that runs on CPU, and one that runs on GPU.\n\nTo compile the floating point CPU benchmarks, simply call:\ng++ tensor_benchmarks_cpu.cc benchmark_main.cc -I ../../ -std=c++11 -O3 -DNDEBUG -pthread -mavx -o benchmarks_cpu\n\nTo compile the floating point GPU benchmarks, simply call:\nnvcc tensor_benchmarks_gpu.cu benchmark_main.cc -I ../../ -std=c++11 -O2 -DNDEBUG -use_fast_math -ftz=true -arch compute_35 -o benchmarks_gpu\n\nWe also provide a version of the generic GPU tensor benchmarks that uses half floats (aka fp16) instead of regular floats. To compile these benchmarks, simply call the command line below. You'll need a recent GPU that supports compute capability 5.3 or higher to run them and nvcc 7.5 or higher to compile the code.\nnvcc tensor_benchmarks_fp16_gpu.cu benchmark_main.cc -I ../../ -std=c++11 -O2 -DNDEBUG -use_fast_math -ftz=true -arch compute_53 -o benchmarks_fp16_gpu\n\nTo compile and run the benchmark for SYCL, using ComputeCpp, simply run the\nfollowing commands:\n1. export COMPUTECPP_PACKAGE_ROOT_DIR={PATH TO COMPUTECPP ROOT DIRECTORY}\n2. bash eigen_sycl_bench.sh\n\nLast but not least, we also provide a suite of benchmarks to measure the scalability of the contraction code on CPU. To compile these benchmarks, call\ng++ contraction_benchmarks_cpu.cc benchmark_main.cc -I ../../ -std=c++11 -O3 -DNDEBUG -pthread -mavx -o benchmarks_cpu\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/tensors/benchmark.h",
    "content": "/*\n * Copyright (C) 2012 The Android Open Source Project\n *\n * Licensed under the Apache License, Version 2.0 (the \"License\");\n * you may not use this file except in compliance with the License.\n * You may obtain a copy of the License at\n *\n *      http://www.apache.org/licenses/LICENSE-2.0\n *\n * Unless required by applicable law or agreed to in writing, software\n * distributed under the License is distributed on an \"AS IS\" BASIS,\n * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n * See the License for the specific language governing permissions and\n * limitations under the License.\n */\n#include <stddef.h>\n#include <stdint.h>\n#include <vector>\n\nnamespace testing {\nclass Benchmark {\n public:\n  Benchmark(const char* name, void (*fn)(int)) {\n    Register(name, fn, NULL);\n  }\n  Benchmark(const char* name, void (*fn_range)(int, int)) {\n    Register(name, NULL, fn_range);\n  }\n  Benchmark* Arg(int x);\n  Benchmark* Range(int lo, int hi);\n  const char* Name();\n  bool ShouldRun(int argc, char* argv[]);\n  void Run();\n private:\n  const char* name_;\n  void (*fn_)(int);\n  void (*fn_range_)(int, int);\n  std::vector<int> args_;\n  void Register(const char* name, void (*fn)(int), void (*fn_range)(int, int));\n  void RunRepeatedlyWithArg(int iterations, int arg);\n  void RunWithArg(int arg);\n};\n}  // namespace testing\nvoid SetBenchmarkFlopsProcessed(int64_t);\nvoid StopBenchmarkTiming();\nvoid StartBenchmarkTiming();\n#define BENCHMARK(f) \\\n    static ::testing::Benchmark* _benchmark_##f __attribute__((unused)) = \\\n        (new ::testing::Benchmark(#f, f))\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/tensors/benchmark_main.cc",
    "content": "/*\n * Copyright (C) 2012 The Android Open Source Project\n *\n * Licensed under the Apache License, Version 2.0 (the \"License\");\n * you may not use this file except in compliance with the License.\n * You may obtain a copy of the License at\n *\n *      http://www.apache.org/licenses/LICENSE-2.0\n *\n * Unless required by applicable law or agreed to in writing, software\n * distributed under the License is distributed on an \"AS IS\" BASIS,\n * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n * See the License for the specific language governing permissions and\n * limitations under the License.\n */\n#include \"benchmark.h\"\n#include <regex.h>\n#include <stdio.h>\n#include <stdlib.h>\n#include <string.h>\n#include <string>\n#include <inttypes.h>\n#include <time.h>\n#include <map>\n\nstatic int64_t g_flops_processed;\nstatic int64_t g_benchmark_total_time_ns;\nstatic int64_t g_benchmark_start_time_ns;\ntypedef std::map<std::string, ::testing::Benchmark*> BenchmarkMap;\ntypedef BenchmarkMap::iterator BenchmarkMapIt;\n\nBenchmarkMap& gBenchmarks() {\n  static BenchmarkMap g_benchmarks;\n  return g_benchmarks;\n}\n\nstatic int g_name_column_width = 20;\n\nstatic int Round(int n) {\n  int base = 1;\n  while (base*10 < n) {\n    base *= 10;\n  }\n  if (n < 2*base) {\n    return 2*base;\n  }\n  if (n < 5*base) {\n    return 5*base;\n  }\n  return 10*base;\n}\n\n#ifdef __APPLE__\n  #include <mach/mach_time.h>\n  static mach_timebase_info_data_t g_time_info;\n  static void __attribute__((constructor)) init_info() {\n    mach_timebase_info(&g_time_info);\n  }\n#endif\n\nstatic int64_t NanoTime() {\n#if defined(__APPLE__)\n  uint64_t t = mach_absolute_time();\n  return t * g_time_info.numer / g_time_info.denom;\n#else\n  struct timespec t;\n  t.tv_sec = t.tv_nsec = 0;\n  clock_gettime(CLOCK_MONOTONIC, &t);\n  return static_cast<int64_t>(t.tv_sec) * 1000000000LL + t.tv_nsec;\n#endif\n}\n\nnamespace testing {\nBenchmark* Benchmark::Arg(int arg) {\n  args_.push_back(arg);\n  return this;\n}\n\nBenchmark* Benchmark::Range(int lo, int hi) {\n  const int kRangeMultiplier = 8;\n  if (hi < lo) {\n    int temp = hi;\n    hi = lo;\n    lo = temp;\n  }\n  while (lo < hi) {\n    args_.push_back(lo);\n    lo *= kRangeMultiplier;\n  }\n  // We always run the hi number.\n  args_.push_back(hi);\n  return this;\n}\n\nconst char* Benchmark::Name() {\n  return name_;\n}\nbool Benchmark::ShouldRun(int argc, char* argv[]) {\n  if (argc == 1) {\n    return true;  // With no arguments, we run all benchmarks.\n  }\n  // Otherwise, we interpret each argument as a regular expression and\n  // see if any of our benchmarks match.\n  for (int i = 1; i < argc; i++) {\n    regex_t re;\n    if (regcomp(&re, argv[i], 0) != 0) {\n      fprintf(stderr, \"couldn't compile \\\"%s\\\" as a regular expression!\\n\", argv[i]);\n      exit(EXIT_FAILURE);\n    }\n    int match = regexec(&re, name_, 0, NULL, 0);\n    regfree(&re);\n    if (match != REG_NOMATCH) {\n      return true;\n    }\n  }\n  return false;\n}\nvoid Benchmark::Register(const char* name, void (*fn)(int), void (*fn_range)(int, int)) {\n  name_ = name;\n  fn_ = fn;\n  fn_range_ = fn_range;\n  if (fn_ == NULL && fn_range_ == NULL) {\n    fprintf(stderr, \"%s: missing function\\n\", name_);\n    exit(EXIT_FAILURE);\n  }\n  gBenchmarks().insert(std::make_pair(name, this));\n}\nvoid Benchmark::Run() {\n  if (fn_ != NULL) {\n    RunWithArg(0);\n  } else {\n    if (args_.empty()) {\n      fprintf(stderr, \"%s: no args!\\n\", name_);\n      exit(EXIT_FAILURE);\n    }\n    for (size_t i = 0; i < args_.size(); ++i) {\n      RunWithArg(args_[i]);\n    }\n  }\n}\nvoid Benchmark::RunRepeatedlyWithArg(int iterations, int arg) {\n  g_flops_processed = 0;\n  g_benchmark_total_time_ns = 0;\n  g_benchmark_start_time_ns = NanoTime();\n  if (fn_ != NULL) {\n    fn_(iterations);\n  } else {\n    fn_range_(iterations, arg);\n  }\n  if (g_benchmark_start_time_ns != 0) {\n    g_benchmark_total_time_ns += NanoTime() - g_benchmark_start_time_ns;\n  }\n}\nvoid Benchmark::RunWithArg(int arg) {\n  // run once in case it's expensive\n  int iterations = 1;\n  RunRepeatedlyWithArg(iterations, arg);\n  while (g_benchmark_total_time_ns < 1e9 && iterations < 1e9) {\n    int last = iterations;\n    if (g_benchmark_total_time_ns/iterations == 0) {\n      iterations = 1e9;\n    } else {\n      iterations = 1e9 / (g_benchmark_total_time_ns/iterations);\n    }\n    iterations = std::max(last + 1, std::min(iterations + iterations/2, 100*last));\n    iterations = Round(iterations);\n    RunRepeatedlyWithArg(iterations, arg);\n  }\n  char throughput[100];\n  throughput[0] = '\\0';\n  if (g_benchmark_total_time_ns > 0 && g_flops_processed > 0) {\n    double mflops_processed = static_cast<double>(g_flops_processed)/1e6;\n    double seconds = static_cast<double>(g_benchmark_total_time_ns)/1e9;\n    snprintf(throughput, sizeof(throughput), \" %8.2f MFlops/s\", mflops_processed/seconds);\n  }\n  char full_name[100];\n  if (fn_range_ != NULL) {\n    if (arg >= (1<<20)) {\n      snprintf(full_name, sizeof(full_name), \"%s/%dM\", name_, arg/(1<<20));\n    } else if (arg >= (1<<10)) {\n      snprintf(full_name, sizeof(full_name), \"%s/%dK\", name_, arg/(1<<10));\n    } else {\n      snprintf(full_name, sizeof(full_name), \"%s/%d\", name_, arg);\n    }\n  } else {\n    snprintf(full_name, sizeof(full_name), \"%s\", name_);\n  }\n  printf(\"%-*s %10d %10\" PRId64 \"%s\\n\", g_name_column_width, full_name,\n         iterations, g_benchmark_total_time_ns/iterations, throughput);\n  fflush(stdout);\n}\n}  // namespace testing\nvoid SetBenchmarkFlopsProcessed(int64_t x) {\n  g_flops_processed = x;\n}\nvoid StopBenchmarkTiming() {\n  if (g_benchmark_start_time_ns != 0) {\n    g_benchmark_total_time_ns += NanoTime() - g_benchmark_start_time_ns;\n  }\n  g_benchmark_start_time_ns = 0;\n}\nvoid StartBenchmarkTiming() {\n  if (g_benchmark_start_time_ns == 0) {\n    g_benchmark_start_time_ns = NanoTime();\n  }\n}\nint main(int argc, char* argv[]) {\n  if (gBenchmarks().empty()) {\n    fprintf(stderr, \"No benchmarks registered!\\n\");\n    exit(EXIT_FAILURE);\n  }\n  for (BenchmarkMapIt it = gBenchmarks().begin(); it != gBenchmarks().end(); ++it) {\n    int name_width = static_cast<int>(strlen(it->second->Name()));\n    g_name_column_width = std::max(g_name_column_width, name_width);\n  }\n  bool need_header = true;\n  for (BenchmarkMapIt it = gBenchmarks().begin(); it != gBenchmarks().end(); ++it) {\n    ::testing::Benchmark* b = it->second;\n    if (b->ShouldRun(argc, argv)) {\n      if (need_header) {\n        printf(\"%-*s %10s %10s\\n\", g_name_column_width, \"\", \"iterations\", \"ns/op\");\n        fflush(stdout);\n        need_header = false;\n      }\n      b->Run();\n    }\n  }\n  if (need_header) {\n    fprintf(stderr, \"No matching benchmarks!\\n\");\n    fprintf(stderr, \"Available benchmarks:\\n\");\n    for (BenchmarkMapIt it = gBenchmarks().begin(); it != gBenchmarks().end(); ++it) {\n      fprintf(stderr, \"  %s\\n\", it->second->Name());\n    }\n    exit(EXIT_FAILURE);\n  }\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/tensors/contraction_benchmarks_cpu.cc",
    "content": "#define EIGEN_USE_THREADS\n\n#include <string>\n\n#include \"tensor_benchmarks.h\"\n\n#define CREATE_THREAD_POOL(threads)             \\\nEigen::ThreadPool pool(threads);                \\\nEigen::ThreadPoolDevice device(&pool, threads);\n\n\n// Contractions for number of threads ranging from 1 to 32\n// Dimensions are Rows, Cols, Depth\n#define BM_ContractionCPU(D1, D2, D3)                                         \\\n  static void BM_##Contraction##_##D1##x##D2##x##D3(int iters, int Threads) { \\\n    StopBenchmarkTiming();                                                    \\\n    CREATE_THREAD_POOL(Threads);                                              \\\n    BenchmarkSuite<Eigen::ThreadPoolDevice, float> suite(device, D1, D2, D3); \\\n    suite.contraction(iters);                                                 \\\n  }                                                                           \\\n  BENCHMARK_RANGE(BM_##Contraction##_##D1##x##D2##x##D3, 1, 32);\n\n\n// Vector Matrix and Matrix Vector products\nBM_ContractionCPU(1, 2000, 500);\nBM_ContractionCPU(2000, 1, 500);\n\n// Various skinny matrices\nBM_ContractionCPU(250, 3, 512);\nBM_ContractionCPU(1500, 3, 512);\n\nBM_ContractionCPU(512, 800, 4);\nBM_ContractionCPU(512, 80, 800);\nBM_ContractionCPU(512, 80, 13522);\nBM_ContractionCPU(1, 80, 13522);\n\nBM_ContractionCPU(3200, 512, 4);\nBM_ContractionCPU(3200, 512, 80);\nBM_ContractionCPU(3200, 80, 512);\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/tensors/eigen_sycl_bench.sh",
    "content": "rm -f tensor_benchmark_sycl\n: \"${COMPUTECPP_PACKAGE_ROOT_DIR:?Need to set COMPUTECPP_PACKAGE_ROOT_DIR}\"\necho \"COMPUTECPP_PACKAGE_ROOT_DIR is set to: \"$COMPUTECPP_PACKAGE_ROOT_DIR\n${COMPUTECPP_PACKAGE_ROOT_DIR}/bin/compute++ \\\ntensor_benchmarks_sycl.cc \\\nbenchmark_main.cc \\\n-I ../../ \\\n-I ${COMPUTECPP_PACKAGE_ROOT_DIR}/include/ \\\n-std=c++11 \\\n-march=native \\\n-O3 \\\n-DNDEBUG \\\n-DEIGEN_MPL2_ONLY \\\n-DEIGEN_USE_SYCL=1 \\\n-DEIGEN_SYCL_LOCAL_MEM=1 \\\n-no-serial-memop \\\n-mllvm \\\n-inline-threshold=10000 \\\n-fsycl-ih-last \\\n-sycl-driver \\\n-Xclang -cl-mad-enable \\\n-lOpenCL \\\n-lComputeCpp \\\n-lpthread \\\n-o \\\ntensor_benchmark_sycl\\\n${@:1}\n\nexport LD_LIBRARY_PATH=${COMPUTECPP_PACKAGE_ROOT_DIR}/lib:$LD_LIBRARY_PATH\n./tensor_benchmark_sycl\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/tensors/eigen_sycl_bench_contract.sh",
    "content": "rm -f tensor_contract_sycl_bench\n: \"${COMPUTECPP_PACKAGE_ROOT_DIR:?Need to set COMPUTECPP_PACKAGE_ROOT_DIR}\"\necho \"COMPUTECPP_PACKAGE_ROOT_DIR is set to: \"$COMPUTECPP_PACKAGE_ROOT_DIR\n${COMPUTECPP_PACKAGE_ROOT_DIR}/bin/compute++  tensor_contract_sycl_bench.cc -I ../../ -I ${COMPUTECPP_PACKAGE_ROOT_DIR}/include/ -std=c++11 -O3 -DNDEBUG -DEIGEN_MPL2_ONLY -DEIGEN_USE_SYCL=1 -no-serial-memop -mllvm -inline-threshold=10000 -fsycl-ih-last -sycl-driver -Xclang -cl-mad-enable -lOpenCL -lComputeCpp -lpthread -o tensor_contract_sycl_bench ${@:1}\nexport LD_LIBRARY_PATH=${COMPUTECPP_PACKAGE_ROOT_DIR}/lib:$LD_LIBRARY_PATH\n./tensor_contract_sycl_bench\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/tensors/tensor_benchmarks.h",
    "content": "#ifndef THIRD_PARTY_EIGEN3_TENSOR_BENCHMARKS_H_\n#define THIRD_PARTY_EIGEN3_TENSOR_BENCHMARKS_H_\n\ntypedef int TensorIndex;\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int\n\n#include \"unsupported/Eigen/CXX11/Tensor\"\n#include \"benchmark.h\"\n\n#define BENCHMARK_RANGE(bench, lo, hi) \\\n  BENCHMARK(bench)->Range(lo, hi)\n\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\n// TODO(bsteiner): also templatize on the input type since we have users\n// for int8 as well as floats.\ntemplate <typename Device, typename T> class BenchmarkSuite {\n public:\n  BenchmarkSuite(const Device& device, size_t m, size_t k, size_t n)\n      : m_(m), k_(k), n_(n), device_(device) {\n    initialize();\n  }\n\n  BenchmarkSuite(const Device& device, size_t m)\n      : m_(m), k_(m), n_(m), device_(device) {\n    initialize();\n  }\n\n  BenchmarkSuite(const Device& device, size_t m, size_t k)\n      : m_(1), k_(k), n_(m), device_(device) {\n    initialize();\n  }\n\n  ~BenchmarkSuite() {\n    device_.deallocate(a_);\n    device_.deallocate(b_);\n    device_.deallocate(c_);\n  }\n\n  void memcpy(int num_iters) {\n    eigen_assert(m_ == k_ && k_ == n_);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      device_.memcpy(c_, a_, m_ * m_ * sizeof(T));\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      device_.memcpy(c_, a_, m_ * m_ * sizeof(T));\n    }\n    // Record the number of values copied per second\n    finalizeBenchmark(static_cast<int64_t>(m_) * m_ * num_iters);\n  }\n\n  void typeCasting(int num_iters) {\n    eigen_assert(m_ == n_);\n    Eigen::array<TensorIndex, 2> sizes;\n    if (sizeof(T) >= sizeof(int)) {\n      sizes[0] = m_;\n      sizes[1] = k_;\n    } else {\n      sizes[0] = m_ * sizeof(T) / sizeof(int);\n      sizes[1] = k_ * sizeof(T) / sizeof(int);\n    }\n    const TensorMap<Tensor<int, 2, 0, TensorIndex>, Eigen::Aligned> A((int*)a_, sizes);\n    TensorMap<Tensor<T, 2, 0, TensorIndex>, Eigen::Aligned> B(b_, sizes);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      B.device(device_) = A.template cast<T>();\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      B.device(device_) = A.template cast<T>();\n    }\n    // Record the number of values copied per second\n    finalizeBenchmark(static_cast<int64_t>(m_) * k_ * num_iters);\n  }\n\n  void random(int num_iters) {\n    eigen_assert(m_ == k_ && k_ == n_);\n    Eigen::array<TensorIndex, 2> sizes;\n    sizes[0] = m_;\n    sizes[1] = m_;\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> C(c_, sizes);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      C.device(device_) = C.random();\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = C.random();\n    }\n    // Record the number of random numbers generated per second\n    finalizeBenchmark(static_cast<int64_t>(m_) * m_ * num_iters);\n  }\n\n  void slicing(int num_iters) {\n    eigen_assert(m_ == k_ && k_ == n_);\n    Eigen::array<TensorIndex, 2> sizes;\n    sizes[0] = m_;\n    sizes[1] = m_;\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> A(a_, sizes);\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> B(b_, sizes);\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> C(c_, sizes);\n\n    const Eigen::DSizes<TensorIndex, 2> quarter_sizes(m_/2, m_/2);\n    const Eigen::DSizes<TensorIndex, 2> first_quadrant(0, 0);\n    const Eigen::DSizes<TensorIndex, 2> second_quadrant(0, m_/2);\n    const Eigen::DSizes<TensorIndex, 2> third_quadrant(m_/2, 0);\n    const Eigen::DSizes<TensorIndex, 2> fourth_quadrant(m_/2, m_/2);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      C.slice(first_quadrant, quarter_sizes).device(device_) =\n          A.slice(first_quadrant, quarter_sizes);\n      C.slice(second_quadrant, quarter_sizes).device(device_) =\n          B.slice(second_quadrant, quarter_sizes);\n      C.slice(third_quadrant, quarter_sizes).device(device_) =\n          A.slice(third_quadrant, quarter_sizes);\n      C.slice(fourth_quadrant, quarter_sizes).device(device_) =\n          B.slice(fourth_quadrant, quarter_sizes);\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.slice(first_quadrant, quarter_sizes).device(device_) =\n          A.slice(first_quadrant, quarter_sizes);\n      C.slice(second_quadrant, quarter_sizes).device(device_) =\n          B.slice(second_quadrant, quarter_sizes);\n      C.slice(third_quadrant, quarter_sizes).device(device_) =\n          A.slice(third_quadrant, quarter_sizes);\n      C.slice(fourth_quadrant, quarter_sizes).device(device_) =\n          B.slice(fourth_quadrant, quarter_sizes);\n    }\n    // Record the number of values copied from the rhs slice to the lhs slice\n    // each second\n    finalizeBenchmark(static_cast<int64_t>(m_) * m_ * num_iters);\n  }\n\n  void rowChip(int num_iters) {\n    Eigen::array<TensorIndex, 2> input_size;\n    input_size[0] = k_;\n    input_size[1] = n_;\n    const TensorMap<Tensor<T, 2, 0, TensorIndex>, Eigen::Aligned> B(b_, input_size);\n    Eigen::array<TensorIndex, 1> output_size;\n    output_size[0] = n_;\n    TensorMap<Tensor<T, 1, 0, TensorIndex>, Eigen::Aligned> C(c_, output_size);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      C.device(device_) = B.chip(iter % k_, 0);\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = B.chip(iter % k_, 0);\n    }\n    // Record the number of values copied from the rhs chip to the lhs.\n    finalizeBenchmark(static_cast<int64_t>(n_) * num_iters);\n  }\n\n  void colChip(int num_iters) {\n    Eigen::array<TensorIndex, 2> input_size;\n    input_size[0] = k_;\n    input_size[1] = n_;\n    const TensorMap<Tensor<T, 2, 0, TensorIndex>, Eigen::Aligned> B(b_, input_size);\n    Eigen::array<TensorIndex, 1> output_size;\n    output_size[0] = n_;\n    TensorMap<Tensor<T, 1, 0, TensorIndex>, Eigen::Aligned> C(c_, output_size);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      C.device(device_) = B.chip(iter % n_, 1);\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = B.chip(iter % n_, 1);\n    }\n    // Record the number of values copied from the rhs chip to the lhs.\n    finalizeBenchmark(static_cast<int64_t>(n_) * num_iters);\n  }\n\n  void shuffling(int num_iters) {\n    eigen_assert(m_ == n_);\n    Eigen::array<TensorIndex, 2> size_a;\n    size_a[0] = m_;\n    size_a[1] = k_;\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> A(a_, size_a);\n    Eigen::array<TensorIndex, 2> size_b;\n    size_b[0] = k_;\n    size_b[1] = m_;\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> B(b_, size_b);\n\n    Eigen::array<int, 2> shuffle;\n    shuffle[0] = 1;\n    shuffle[1] = 0;\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      B.device(device_) = A.shuffle(shuffle);\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      B.device(device_) = A.shuffle(shuffle);\n    }\n    // Record the number of values shuffled from A and copied to B each second\n    finalizeBenchmark(static_cast<int64_t>(m_) * k_ * num_iters);\n  }\n\n void padding(int num_iters) {\n    eigen_assert(m_ == k_);\n    Eigen::array<TensorIndex, 2> size_a;\n    size_a[0] = m_;\n    size_a[1] = k_-3;\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> A(a_, size_a);\n    Eigen::array<TensorIndex, 2> size_b;\n    size_b[0] = k_;\n    size_b[1] = m_;\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> B(b_, size_b);\n\n#if defined(EIGEN_HAS_INDEX_LIST)\n    Eigen::IndexPairList<Eigen::type2indexpair<0, 0>,\n                         Eigen::type2indexpair<2, 1> > paddings;\n#else\n    Eigen::array<Eigen::IndexPair<TensorIndex>, 2> paddings;\n    paddings[0] = Eigen::IndexPair<TensorIndex>(0, 0);\n    paddings[1] = Eigen::IndexPair<TensorIndex>(2, 1);\n#endif\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      B.device(device_) = A.pad(paddings);\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      B.device(device_) = A.pad(paddings);\n    }\n    // Record the number of values copied from the padded tensor A each second\n    finalizeBenchmark(static_cast<int64_t>(m_) * k_ * num_iters);\n  }\n\n void striding(int num_iters) {\n    eigen_assert(m_ == k_);\n    Eigen::array<TensorIndex, 2> size_a;\n    size_a[0] = m_;\n    size_a[1] = k_;\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> A(a_, size_a);\n    Eigen::array<TensorIndex, 2> size_b;\n    size_b[0] = m_;\n    size_b[1] = k_/2;\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> B(b_, size_b);\n\n#ifndef EIGEN_HAS_INDEX_LIST\n    Eigen::array<TensorIndex, 2> strides;\n    strides[0] = 1;\n    strides[1] = 2;\n#else\n    // Take advantage of cxx11 to give the compiler information it can use to\n    // optimize the code.\n    Eigen::IndexList<Eigen::type2index<1>, Eigen::type2index<2> > strides;\n#endif\n\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      B.device(device_) = A.stride(strides);\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      B.device(device_) = A.stride(strides);\n    }\n    // Record the number of values copied from the padded tensor A each second\n    finalizeBenchmark(static_cast<int64_t>(m_) * k_ * num_iters);\n  }\n\n\n  void broadcasting(int num_iters) {\n    Eigen::array<TensorIndex, 2> size_a;\n    size_a[0] = m_;\n    size_a[1] = 1;\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> A(a_, size_a);\n    Eigen::array<TensorIndex, 2> size_c;\n    size_c[0] = m_;\n    size_c[1] = n_;\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> C(c_, size_c);\n\n#ifndef EIGEN_HAS_INDEX_LIST\n    Eigen::array<int, 2> broadcast;\n    broadcast[0] = 1;\n    broadcast[1] = n_;\n#else\n    // Take advantage of cxx11 to give the compiler information it can use to\n    // optimize the code.\n    Eigen::IndexList<Eigen::type2index<1>, int> broadcast;\n    broadcast.set(1, n_);\n#endif\n\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      C.device(device_) = A.broadcast(broadcast);\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = A.broadcast(broadcast);\n    }\n    // Record the number of values broadcasted from A and copied to C each second\n    finalizeBenchmark(static_cast<int64_t>(m_) * n_ * num_iters);\n  }\n\n  void coeffWiseOp(int num_iters) {\n    eigen_assert(m_ == k_ && k_ == n_);\n    Eigen::array<TensorIndex, 2> sizes;\n    sizes[0] = m_;\n    sizes[1] = m_;\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> A(a_, sizes);\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> B(b_, sizes);\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> C(c_, sizes);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      C.device(device_) = A * A.constant(static_cast<T>(3.14)) + B * B.constant(static_cast<T>(2.7));\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = A * A.constant(static_cast<T>(3.14)) + B * B.constant(static_cast<T>(2.7));\n    }\n    // Record the number of FLOP executed per second (2 multiplications and\n    // 1 addition per value)\n    finalizeBenchmark(static_cast<int64_t>(3) * m_ * m_ * num_iters);\n  }\n\n  void algebraicFunc(int num_iters) {\n    eigen_assert(m_ == k_ && k_ == n_);\n    Eigen::array<TensorIndex, 2> sizes;\n    sizes[0] = m_;\n    sizes[1] = m_;\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> A(a_, sizes);\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> B(b_, sizes);\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> C(c_, sizes);\n\n#ifdef EIGEN_USE_SYCL // warmup for sycl\nfor (int iter = 0; iter < 10; ++iter) {\n      C.device(device_) = A.rsqrt() + B.sqrt() * B.square();\n}\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = A.rsqrt() + B.sqrt() * B.square();\n    }\n    // Record the number of FLOP executed per second (assuming one operation\n    // per value)\n    finalizeBenchmark(static_cast<int64_t>(m_) * m_ * num_iters);\n  }\n\n  void transcendentalFunc(int num_iters) {\n    eigen_assert(m_ == k_ && k_ == n_);\n    Eigen::array<TensorIndex, 2> sizes;\n    sizes[0] = m_;\n    sizes[1] = m_;\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> A(a_, sizes);\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> B(b_, sizes);\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> C(c_, sizes);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      C.device(device_) = A.exp() + B.log();\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = A.exp() + B.log();\n    }\n    // Record the number of FLOP executed per second (assuming one operation\n    // per value)\n    finalizeBenchmark(static_cast<int64_t>(m_) * m_ * num_iters);\n  }\n\n // Row reduction\n  void rowReduction(int num_iters) {\n    Eigen::array<TensorIndex, 2> input_size;\n    input_size[0] = k_;\n    input_size[1] = n_;\n    const TensorMap<Tensor<T, 2, 0, TensorIndex>, Eigen::Aligned> B(b_, input_size);\n    Eigen::array<TensorIndex, 1> output_size;\n    output_size[0] = n_;\n    TensorMap<Tensor<T, 1, 0, TensorIndex>, Eigen::Aligned> C(c_, output_size);\n\n#ifndef EIGEN_HAS_INDEX_LIST\n    Eigen::array<TensorIndex, 1> sum_along_dim;\n    sum_along_dim[0] = 0;\n#else\n    // Take advantage of cxx11 to give the compiler information it can use to\n    // optimize the code.\n    Eigen::IndexList<Eigen::type2index<0>> sum_along_dim;\n#endif\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n  for (int iter = 0; iter < 10; ++iter) {\n    C.device(device_) = B.sum(sum_along_dim);\n  }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = B.sum(sum_along_dim);\n    }\n    // Record the number of FLOP executed per second (assuming one operation\n    // per value)\n    finalizeBenchmark(static_cast<int64_t>(k_) * n_ * num_iters);\n  }\n\n  // Column reduction\n  void colReduction(int num_iters) {\n    Eigen::array<TensorIndex, 2> input_size;\n    input_size[0] = k_;\n    input_size[1] = n_;\n    const TensorMap<Tensor<T, 2, 0, TensorIndex>, Eigen::Aligned> B(\n        b_, input_size);\n    Eigen::array<TensorIndex, 1> output_size;\n    output_size[0] = k_;\n    TensorMap<Tensor<T, 1, 0, TensorIndex>, Eigen::Aligned> A(\n        a_, output_size);\n\n#ifndef EIGEN_HAS_INDEX_LIST\n    Eigen::array<TensorIndex, 1> sum_along_dim;\n    sum_along_dim[0] = 1;\n#else\n    // Take advantage of cxx11 to give the compiler information it can use to\n    // optimize the code.\n    Eigen::IndexList<Eigen::type2index<1>> sum_along_dim;\n#endif\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n  for (int iter = 0; iter < 10; ++iter) {\n    A.device(device_) = B.sum(sum_along_dim);\n  }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      A.device(device_) = B.sum(sum_along_dim);\n    }\n    // Record the number of FLOP executed per second (assuming one operation\n    // per value)\n    finalizeBenchmark(static_cast<int64_t>(k_) * n_ * num_iters);\n  }\n\n  // Full reduction\n  void fullReduction(int num_iters) {\n    Eigen::array<TensorIndex, 2> input_size;\n    input_size[0] = k_;\n    input_size[1] = n_;\n    const TensorMap<Tensor<T, 2, 0, TensorIndex>, Eigen::Aligned> B(\n        b_, input_size);\n    Eigen::array<TensorIndex, 0> output_size;\n    TensorMap<Tensor<T, 0, 0, TensorIndex>, Eigen::Aligned> C(\n        c_, output_size);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      C.device(device_) = B.sum();\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = B.sum();\n    }\n    // Record the number of FLOP executed per second (assuming one operation\n    // per value)\n    finalizeBenchmark(static_cast<int64_t>(k_) * n_ * num_iters);\n  }\n\n  \n\n  // do a contraction which is equivalent to a matrix multiplication\n  void contraction(int num_iters) {\n      contraction<static_cast<int>(Eigen::ColMajor)>(num_iters, false, false);\n  }\n\n    void contractionRowMajor(int num_iters) {\n      contraction<static_cast<int>(Eigen::RowMajor)>(num_iters, false, false);\n  }\n    \n  void contractionRowMajorAT(int num_iters) {\n      contraction<static_cast<int>(Eigen::RowMajor)>(num_iters, true, false);\n  }\n\n  void contractionRowMajorBT(int num_iters) {\n      contraction<static_cast<int>(Eigen::RowMajor)>(num_iters, false, true);\n  }\n\n  void contractionRowMajorABT(int num_iters) {\n      contraction<static_cast<int>(Eigen::RowMajor)>(num_iters, true, true);\n  }\n\n  void convolution(int num_iters, int kernel_x, int kernel_y) {\n    Eigen::array<TensorIndex, 2> input_sizes;\n    input_sizes[0] = m_;\n    input_sizes[1] = n_;\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> A(a_, input_sizes);\n    Eigen::array<TensorIndex, 2> kernel_sizes;\n    kernel_sizes[0] = kernel_x;\n    kernel_sizes[1] = kernel_y;\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> B(b_, kernel_sizes);\n    Eigen::array<TensorIndex, 2> result_sizes;\n    result_sizes[0] = m_ - kernel_x + 1;\n    result_sizes[1] = n_ - kernel_y + 1;\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> C(c_, result_sizes);\n    Eigen::array<TensorIndex, 2> dims;\n    dims[0] = 0;\n    dims[1] = 1;\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      C.device(device_) = A.convolve(B, dims);\n     }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = A.convolve(B, dims);\n    }\n    // Record the number of FLOPs executed per second (kernel_size\n    // multiplications and additions for each value in the resulting tensor)\n    finalizeBenchmark(static_cast<int64_t>(2) *\n        (m_ - kernel_x + 1) * (n_ - kernel_y + 1) * kernel_x * kernel_y * num_iters);\n  }\n\n private:\n // do a contraction which is equivalent to a matrix multiplication\n  template<int Layout>\n  void contraction(int num_iters, bool trans_a, bool trans_b) {\n    Eigen::array<TensorIndex, 2> sizeA;\n    sizeA[0] = (trans_a ? k_: m_);\n    sizeA[1] = (trans_a ? m_:  k_);\n    Eigen::array<TensorIndex, 2> sizeB;\n    sizeB[0] = (trans_b ? n_: k_);\n    sizeB[1] = (trans_b ? k_: n_);\n    Eigen::array<TensorIndex, 2> sizeC;\n    sizeC[0] = m_;\n    sizeC[1] = n_;\n\n    const TensorMap<Tensor<T, 2, Layout>, Eigen::Aligned> A(a_, sizeA);\n    const TensorMap<Tensor<T, 2, Layout>, Eigen::Aligned> B(b_, sizeB);\n    TensorMap<Tensor<T, 2, Layout>, Eigen::Aligned> C(c_, sizeC);\n\n    typedef typename Tensor<T, 2, Layout>::DimensionPair DimPair;\n    Eigen::array<DimPair, 1> dims;\n    TensorIndex a_contract_dim = (trans_a ? 0 : 1);\n    TensorIndex b_contract_dim = (trans_b ? 1 : 0);\n    dims[0] = DimPair(a_contract_dim, b_contract_dim);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      C.device(device_) = A.contract(B, dims);\n     }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = A.contract(B, dims);\n    }\n    // Record the number of FLOP executed per second (size_ multiplications and\n    // additions for each value in the resulting tensor)\n    finalizeBenchmark(static_cast<int64_t>(2) * m_ * n_ * k_ * num_iters);\n  }\n\n  void initialize() {\n    a_ = (T *) device_.allocate(m_ * k_ * sizeof(T));\n    b_ = (T *) device_.allocate(k_ * n_ * sizeof(T));\n    c_ = (T *) device_.allocate(m_ * n_ * sizeof(T));\n\n    // Initialize the content of the memory pools to prevent asan from\n    // complaining.\n    device_.fill(a_, a_ + m_ * k_, T(12));\n    device_.fill(b_, b_ + k_ * n_, T(23));\n    device_.fill(c_, c_ + m_ * n_, T(31));\n\n  }\n\n  inline void finalizeBenchmark(int64_t num_items) {\n#if defined(EIGEN_USE_GPU) && defined(__CUDACC__)\n    if (Eigen::internal::is_same<Device, Eigen::GpuDevice>::value) {\n      device_.synchronize();\n    }\n#elif defined(EIGEN_USE_SYCL)\n    if (Eigen::internal::is_same<Device, Eigen::SyclDevice>::value) {\n      device_.synchronize();\n    }\n\n#endif\n    StopBenchmarkTiming();\n    SetBenchmarkFlopsProcessed(num_items);\n  }\n\n\n  TensorIndex m_;\n  TensorIndex k_;\n  TensorIndex n_;\n  T* a_;\n  T* b_;\n  T* c_;\n  Device device_;\n};\n#endif  // THIRD_PARTY_EIGEN3_TENSOR_BENCHMARKS_H_\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/tensors/tensor_benchmarks_cpu.cc",
    "content": "#define EIGEN_USE_THREADS\n\n#include <string>\n\n#include \"tensor_benchmarks.h\"\n\n#define CREATE_THREAD_POOL(threads)             \\\nEigen::ThreadPool pool(threads);                \\\nEigen::ThreadPoolDevice device(&pool, threads);\n\n// Simple functions\n#define BM_FuncCPU(FUNC, THREADS)                                    \\\n  static void BM_##FUNC##_##THREADS##T(int iters, int N) {           \\\n    StopBenchmarkTiming();                                           \\\n    CREATE_THREAD_POOL(THREADS);                                     \\\n    BenchmarkSuite<Eigen::ThreadPoolDevice, float> suite(device, N); \\\n    suite.FUNC(iters);                                               \\\n  }                                                                  \\\n  BENCHMARK_RANGE(BM_##FUNC##_##THREADS##T, 10, 5000);\n\nBM_FuncCPU(memcpy, 4);\nBM_FuncCPU(memcpy, 8);\nBM_FuncCPU(memcpy, 12);\n\nBM_FuncCPU(typeCasting, 4);\nBM_FuncCPU(typeCasting, 8);\nBM_FuncCPU(typeCasting, 12);\n\nBM_FuncCPU(random, 4);\nBM_FuncCPU(random, 8);\nBM_FuncCPU(random, 12);\n\nBM_FuncCPU(slicing, 4);\nBM_FuncCPU(slicing, 8);\nBM_FuncCPU(slicing, 12);\n\nBM_FuncCPU(rowChip, 4);\nBM_FuncCPU(rowChip, 8);\nBM_FuncCPU(rowChip, 12);\n\nBM_FuncCPU(colChip, 4);\nBM_FuncCPU(colChip, 8);\nBM_FuncCPU(colChip, 12);\n\nBM_FuncCPU(shuffling, 4);\nBM_FuncCPU(shuffling, 8);\nBM_FuncCPU(shuffling, 12);\n\nBM_FuncCPU(padding, 4);\nBM_FuncCPU(padding, 8);\nBM_FuncCPU(padding, 12);\n\nBM_FuncCPU(striding, 4);\nBM_FuncCPU(striding, 8);\nBM_FuncCPU(striding, 12);\n\nBM_FuncCPU(broadcasting, 4);\nBM_FuncCPU(broadcasting, 8);\nBM_FuncCPU(broadcasting, 12);\n\nBM_FuncCPU(coeffWiseOp, 4);\nBM_FuncCPU(coeffWiseOp, 8);\nBM_FuncCPU(coeffWiseOp, 12);\n\nBM_FuncCPU(algebraicFunc, 4);\nBM_FuncCPU(algebraicFunc, 8);\nBM_FuncCPU(algebraicFunc, 12);\n\nBM_FuncCPU(transcendentalFunc, 4);\nBM_FuncCPU(transcendentalFunc, 8);\nBM_FuncCPU(transcendentalFunc, 12);\n\nBM_FuncCPU(rowReduction, 4);\nBM_FuncCPU(rowReduction, 8);\nBM_FuncCPU(rowReduction, 12);\n\nBM_FuncCPU(colReduction, 4);\nBM_FuncCPU(colReduction, 8);\nBM_FuncCPU(colReduction, 12);\n\n\n// Contractions\n#define BM_FuncWithInputDimsCPU(FUNC, D1, D2, D3, THREADS)                      \\\n  static void BM_##FUNC##_##D1##x##D2##x##D3##_##THREADS##T(int iters, int N) { \\\n    StopBenchmarkTiming();                                                      \\\n    if (THREADS == 1) {                                                         \\\n      Eigen::DefaultDevice device;                                              \\\n      BenchmarkSuite<Eigen::DefaultDevice, float> suite(device, D1, D2, D3);    \\\n      suite.FUNC(iters);                                                        \\\n    } else {                                                                    \\\n      CREATE_THREAD_POOL(THREADS);                                              \\\n      BenchmarkSuite<Eigen::ThreadPoolDevice, float> suite(device, D1, D2, D3); \\\n      suite.FUNC(iters);                                                        \\\n    }                                                                           \\\n  }                                                                             \\\n  BENCHMARK_RANGE(BM_##FUNC##_##D1##x##D2##x##D3##_##THREADS##T, 10, 5000);\n\n\nBM_FuncWithInputDimsCPU(contraction, N, N, N, 1);\nBM_FuncWithInputDimsCPU(contraction, N, N, N, 4);\nBM_FuncWithInputDimsCPU(contraction, N, N, N, 8);\nBM_FuncWithInputDimsCPU(contraction, N, N, N, 12);\nBM_FuncWithInputDimsCPU(contraction, N, N, N, 16);\n\nBM_FuncWithInputDimsCPU(contraction, 64, N, N, 1);\nBM_FuncWithInputDimsCPU(contraction, 64, N, N, 4);\nBM_FuncWithInputDimsCPU(contraction, 64, N, N, 8);\nBM_FuncWithInputDimsCPU(contraction, 64, N, N, 12);\nBM_FuncWithInputDimsCPU(contraction, 64, N, N, 16);\n\nBM_FuncWithInputDimsCPU(contraction, N, 64, N, 1);\nBM_FuncWithInputDimsCPU(contraction, N, 64, N, 4);\nBM_FuncWithInputDimsCPU(contraction, N, 64, N, 8);\nBM_FuncWithInputDimsCPU(contraction, N, 64, N, 12);\nBM_FuncWithInputDimsCPU(contraction, N, 64, N, 16);\n\nBM_FuncWithInputDimsCPU(contraction, N, N, 64, 1);\nBM_FuncWithInputDimsCPU(contraction, N, N, 64, 4);\nBM_FuncWithInputDimsCPU(contraction, N, N, 64, 8);\nBM_FuncWithInputDimsCPU(contraction, N, N, 64, 12);\nBM_FuncWithInputDimsCPU(contraction, N, N, 64, 16);\n\nBM_FuncWithInputDimsCPU(contraction, 1, N, N, 1);\nBM_FuncWithInputDimsCPU(contraction, 1, N, N, 4);\nBM_FuncWithInputDimsCPU(contraction, 1, N, N, 8);\nBM_FuncWithInputDimsCPU(contraction, 1, N, N, 12);\nBM_FuncWithInputDimsCPU(contraction, 1, N, N, 16);\n\nBM_FuncWithInputDimsCPU(contraction, N, N, 1, 1);\nBM_FuncWithInputDimsCPU(contraction, N, N, 1, 4);\nBM_FuncWithInputDimsCPU(contraction, N, N, 1, 8);\nBM_FuncWithInputDimsCPU(contraction, N, N, 1, 12);\nBM_FuncWithInputDimsCPU(contraction, N, N, 1, 16);\n\n\n// Convolutions\n#define BM_FuncWithKernelDimsCPU(FUNC, DIM1, DIM2, THREADS)                    \\\n  static void BM_##FUNC##_##DIM1##x##DIM2##_##THREADS##T(int iters, int N) {   \\\n    StopBenchmarkTiming();                                                     \\\n    CREATE_THREAD_POOL(THREADS);                                               \\\n    BenchmarkSuite<Eigen::ThreadPoolDevice, float> suite(device, N);\t       \\\n    suite.FUNC(iters, DIM1, DIM2);                                             \\\n  }                                                                            \\\n  BENCHMARK_RANGE(BM_##FUNC##_##DIM1##x##DIM2##_##THREADS##T, 128, 5000);\n\nBM_FuncWithKernelDimsCPU(convolution, 7, 1, 4);\nBM_FuncWithKernelDimsCPU(convolution, 7, 1, 8);\nBM_FuncWithKernelDimsCPU(convolution, 7, 1, 12);\n\nBM_FuncWithKernelDimsCPU(convolution, 1, 7, 4);\nBM_FuncWithKernelDimsCPU(convolution, 1, 7, 8);\nBM_FuncWithKernelDimsCPU(convolution, 1, 7, 12);\n\nBM_FuncWithKernelDimsCPU(convolution, 7, 4, 4);\nBM_FuncWithKernelDimsCPU(convolution, 7, 4, 8);\nBM_FuncWithKernelDimsCPU(convolution, 7, 4, 12);\n\nBM_FuncWithKernelDimsCPU(convolution, 4, 7, 4);\nBM_FuncWithKernelDimsCPU(convolution, 4, 7, 8);\nBM_FuncWithKernelDimsCPU(convolution, 4, 7, 12);\n\nBM_FuncWithKernelDimsCPU(convolution, 7, 64, 4);\nBM_FuncWithKernelDimsCPU(convolution, 7, 64, 8);\nBM_FuncWithKernelDimsCPU(convolution, 7, 64, 12);\n\nBM_FuncWithKernelDimsCPU(convolution, 64, 7, 4);\nBM_FuncWithKernelDimsCPU(convolution, 64, 7, 8);\nBM_FuncWithKernelDimsCPU(convolution, 64, 7, 12);\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/tensors/tensor_benchmarks_fp16_gpu.cu",
    "content": "#define EIGEN_USE_GPU\n\n#include <cuda.h>\n#include <cuda_runtime.h>\n#include <iostream>\n\n#include \"tensor_benchmarks.h\"\n\n// Simple functions\n#define BM_FuncGPU(FUNC)                                                       \\\n  static void BM_##FUNC(int iters, int N) {                                    \\\n    StopBenchmarkTiming();                                                     \\\n    Eigen::CudaStreamDevice stream;                                            \\\n    Eigen::GpuDevice device(&stream);                                          \\\n    BenchmarkSuite<Eigen::GpuDevice, Eigen::half> suite(device, N);            \\\n    cudaDeviceSynchronize();                                                   \\\n    suite.FUNC(iters);                                                         \\\n  }                                                                            \\\n  BENCHMARK_RANGE(BM_##FUNC, 10, 5000);\n\nBM_FuncGPU(memcpy);\nBM_FuncGPU(typeCasting);\n//BM_FuncGPU(random);\nBM_FuncGPU(slicing);\nBM_FuncGPU(rowChip);\nBM_FuncGPU(colChip);\nBM_FuncGPU(shuffling);\nBM_FuncGPU(padding);\nBM_FuncGPU(striding);\nBM_FuncGPU(broadcasting);\nBM_FuncGPU(coeffWiseOp);\nBM_FuncGPU(algebraicFunc);\nBM_FuncGPU(transcendentalFunc);\nBM_FuncGPU(rowReduction);\nBM_FuncGPU(colReduction);\nBM_FuncGPU(fullReduction);\n\n\n// Contractions\n#define BM_FuncWithInputDimsGPU(FUNC, D1, D2, D3)                              \\\n  static void BM_##FUNC##_##D1##x##D2##x##D3(int iters, int N) {               \\\n    StopBenchmarkTiming();                                                     \\\n    Eigen::CudaStreamDevice stream;                                            \\\n    Eigen::GpuDevice device(&stream);                                          \\\n    BenchmarkSuite<Eigen::GpuDevice, Eigen::half> suite(device, D1, D2, D3);   \\\n    cudaDeviceSynchronize();                                                   \\\n    suite.FUNC(iters);                                                         \\\n  }                                                                            \\\n  BENCHMARK_RANGE(BM_##FUNC##_##D1##x##D2##x##D3, 10, 5000);\n\n\nBM_FuncWithInputDimsGPU(contraction, N, N, N);\nBM_FuncWithInputDimsGPU(contraction, 64, N, N);\nBM_FuncWithInputDimsGPU(contraction, N, 64, N);\nBM_FuncWithInputDimsGPU(contraction, N, N, 64);\n\n\n// Convolutions\n#define BM_FuncWithKernelDimsGPU(FUNC, DIM1, DIM2)                             \\\n  static void BM_##FUNC##_##DIM1##x##DIM2(int iters, int N) {                  \\\n    StopBenchmarkTiming();                                                     \\\n    Eigen::CudaStreamDevice stream;                                            \\\n    Eigen::GpuDevice device(&stream);                                          \\\n    BenchmarkSuite<Eigen::GpuDevice, Eigen::half> suite(device, N);            \\\n    cudaDeviceSynchronize();                                                   \\\n    suite.FUNC(iters, DIM1, DIM2);                                             \\\n  }                                                                            \\\n  BENCHMARK_RANGE(BM_##FUNC##_##DIM1##x##DIM2, 128, 5000);\n\n/*\nBM_FuncWithKernelDimsGPU(convolution, 7, 1);\nBM_FuncWithKernelDimsGPU(convolution, 1, 7);\nBM_FuncWithKernelDimsGPU(convolution, 7, 4);\nBM_FuncWithKernelDimsGPU(convolution, 4, 7);\nBM_FuncWithKernelDimsGPU(convolution, 7, 64);\nBM_FuncWithKernelDimsGPU(convolution, 64, 7);\n*/\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/tensors/tensor_benchmarks_gpu.cu",
    "content": "#define EIGEN_USE_GPU\n\n#include <cuda.h>\n#include <cuda_runtime.h>\n#include <iostream>\n\n#include \"tensor_benchmarks.h\"\n\n// Simple functions\n#define BM_FuncGPU(FUNC)                                                       \\\n  static void BM_##FUNC(int iters, int N) {                                    \\\n    StopBenchmarkTiming();                                                     \\\n    Eigen::CudaStreamDevice stream;                                            \\\n    Eigen::GpuDevice device(&stream);                                          \\\n    BenchmarkSuite<Eigen::GpuDevice, float> suite(device, N);                  \\\n    cudaDeviceSynchronize();                                                   \\\n    suite.FUNC(iters);                                                         \\\n  }                                                                            \\\n  BENCHMARK_RANGE(BM_##FUNC, 10, 5000);\n\nBM_FuncGPU(memcpy);\nBM_FuncGPU(typeCasting);\nBM_FuncGPU(random);\nBM_FuncGPU(slicing);\nBM_FuncGPU(rowChip);\nBM_FuncGPU(colChip);\nBM_FuncGPU(shuffling);\nBM_FuncGPU(padding);\nBM_FuncGPU(striding);\nBM_FuncGPU(broadcasting);\nBM_FuncGPU(coeffWiseOp);\nBM_FuncGPU(algebraicFunc);\nBM_FuncGPU(transcendentalFunc);\nBM_FuncGPU(rowReduction);\nBM_FuncGPU(colReduction);\nBM_FuncGPU(fullReduction);\n\n\n// Contractions\n#define BM_FuncWithInputDimsGPU(FUNC, D1, D2, D3)                              \\\n  static void BM_##FUNC##_##D1##x##D2##x##D3(int iters, int N) {               \\\n    StopBenchmarkTiming();                                                     \\\n    Eigen::CudaStreamDevice stream;                                            \\\n    Eigen::GpuDevice device(&stream);                                          \\\n    BenchmarkSuite<Eigen::GpuDevice, float> suite(device, D1, D2, D3);         \\\n    cudaDeviceSynchronize();                                                   \\\n    suite.FUNC(iters);                                                         \\\n  }                                                                            \\\n  BENCHMARK_RANGE(BM_##FUNC##_##D1##x##D2##x##D3, 10, 5000);\n\n\nBM_FuncWithInputDimsGPU(contraction, N, N, N);\nBM_FuncWithInputDimsGPU(contraction, 64, N, N);\nBM_FuncWithInputDimsGPU(contraction, N, 64, N);\nBM_FuncWithInputDimsGPU(contraction, N, N, 64);\n\n\n// Convolutions\n#define BM_FuncWithKernelDimsGPU(FUNC, DIM1, DIM2)                             \\\n  static void BM_##FUNC##_##DIM1##x##DIM2(int iters, int N) {                  \\\n    StopBenchmarkTiming();                                                     \\\n    Eigen::CudaStreamDevice stream;                                            \\\n    Eigen::GpuDevice device(&stream);                                          \\\n    BenchmarkSuite<Eigen::GpuDevice, float> suite(device, N);                  \\\n    cudaDeviceSynchronize();                                                   \\\n    suite.FUNC(iters, DIM1, DIM2);                                             \\\n  }                                                                            \\\n  BENCHMARK_RANGE(BM_##FUNC##_##DIM1##x##DIM2, 128, 5000);\n\nBM_FuncWithKernelDimsGPU(convolution, 7, 1);\nBM_FuncWithKernelDimsGPU(convolution, 1, 7);\nBM_FuncWithKernelDimsGPU(convolution, 7, 4);\nBM_FuncWithKernelDimsGPU(convolution, 4, 7);\nBM_FuncWithKernelDimsGPU(convolution, 7, 64);\nBM_FuncWithKernelDimsGPU(convolution, 64, 7);\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/tensors/tensor_benchmarks_sycl.cc",
    "content": "#ifdef EIGEN_USE_SYCL\n\n#include <CL/sycl.hpp>\n#include <iostream>\n\n#include \"tensor_benchmarks.h\"\n\ncl::sycl::gpu_selector selector;\nEigen::QueueInterface queue(selector);\n#define BM_FuncWithInput2DimsGPU(FUNC, D1, D2)                      \\\n  static void BM_##FUNC##_##D1##x##D2(int iters, int N) {           \\\n    StopBenchmarkTiming();                                          \\\n    Eigen::SyclDevice device(&queue);                               \\\n    BenchmarkSuite<Eigen::SyclDevice, float> suite(device, D1, D2); \\\n    suite.FUNC(iters);                                              \\\n  }                                                                 \\\n  BENCHMARK_RANGE(BM_##FUNC##_##D1##x##D2, 10, 10);\n\nBM_FuncWithInput2DimsGPU(rowReduction, 256, 100352);\nBM_FuncWithInput2DimsGPU(rowReduction, 64, 100352);\nBM_FuncWithInput2DimsGPU(rowReduction, 512, 25088);\nBM_FuncWithInput2DimsGPU(rowReduction, 128, 25088);\nBM_FuncWithInput2DimsGPU(rowReduction, 102, 6272);\nBM_FuncWithInput2DimsGPU(rowReduction, 256, 6272);\nBM_FuncWithInput2DimsGPU(rowReduction, 204, 1568);\nBM_FuncWithInput2DimsGPU(rowReduction, 512, 1568);\nBM_FuncWithInput2DimsGPU(rowReduction, 1024, 1568);\nBM_FuncWithInput2DimsGPU(rowReduction, 2048, 1568);\n\nBM_FuncWithInput2DimsGPU(colReduction, 100352, 256);\nBM_FuncWithInput2DimsGPU(colReduction, 100352, 64);\nBM_FuncWithInput2DimsGPU(colReduction, 25088, 512);\nBM_FuncWithInput2DimsGPU(colReduction, 6272, 102);\nBM_FuncWithInput2DimsGPU(colReduction, 25088, 128);\nBM_FuncWithInput2DimsGPU(colReduction, 6272, 256);\nBM_FuncWithInput2DimsGPU(colReduction, 1568, 204);\nBM_FuncWithInput2DimsGPU(colReduction, 1568, 512);\nBM_FuncWithInput2DimsGPU(colReduction, 1568, 1024);\nBM_FuncWithInput2DimsGPU(colReduction, 1568, 2048);\nBM_FuncWithInput2DimsGPU(fullReduction, 1001, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 2050048, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 2097152, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 2048, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 262144, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 256, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 589824, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 1024, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 524288, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 512, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 2359296, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 1048576, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 131072, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 16384, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 9408, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 64, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 4096, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 36864, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 32768, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 128, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 147456, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 65536, 1);\n#define BM_FuncGPU(FUNC)                                       \\\n  static void BM_##FUNC(int iters, int N) {                    \\\n    StopBenchmarkTiming();                                     \\\n    Eigen::SyclDevice device(&queue);                          \\\n    BenchmarkSuite<Eigen::SyclDevice, float> suite(device, N); \\\n    suite.FUNC(iters);                                         \\\n  }                                                            \\\n  BENCHMARK_RANGE(BM_##FUNC, 10, 5000);\n\nBM_FuncGPU(rowReduction);\nBM_FuncGPU(colReduction);\nBM_FuncGPU(fullReduction);\n\nBM_FuncGPU(memcpy);\nBM_FuncGPU(typeCasting);\nBM_FuncGPU(random);\nBM_FuncGPU(slicing);\nBM_FuncGPU(rowChip);\nBM_FuncGPU(colChip);\nBM_FuncGPU(shuffling);\nBM_FuncGPU(padding);\nBM_FuncGPU(striding);\nBM_FuncGPU(broadcasting);\nBM_FuncGPU(coeffWiseOp);\nBM_FuncGPU(algebraicFunc);\nBM_FuncGPU(transcendentalFunc);\n// Contractions\n#define BM_FuncWithInputDimsGPU(FUNC, D1, D2, D3)                       \\\n  static void BM_##FUNC##_##D1##x##D2##x##D3(int iters, int N) {        \\\n    StopBenchmarkTiming();                                              \\\n    Eigen::SyclDevice device(&queue);                                   \\\n    BenchmarkSuite<Eigen::SyclDevice, float> suite(device, D1, D2, D3); \\\n    suite.FUNC(iters);                                                  \\\n  }                                                                     \\\n  BENCHMARK_RANGE(BM_##FUNC##_##D1##x##D2##x##D3, 10, 5000);\n\nBM_FuncWithInputDimsGPU(contraction, N, N, N);\nBM_FuncWithInputDimsGPU(contraction, 64, N, N);\nBM_FuncWithInputDimsGPU(contraction, N, 64, N);\nBM_FuncWithInputDimsGPU(contraction, N, N, 64);\n\nBM_FuncWithInputDimsGPU(contractionRowMajor, N, N, N);\nBM_FuncWithInputDimsGPU(contractionRowMajor, 64, N, N);\nBM_FuncWithInputDimsGPU(contractionRowMajor, N, 64, N);\nBM_FuncWithInputDimsGPU(contractionRowMajor, N, N, 64);\n\nBM_FuncWithInputDimsGPU(contractionRowMajorAT, N, N, N);\nBM_FuncWithInputDimsGPU(contractionRowMajorAT, 64, N, N);\nBM_FuncWithInputDimsGPU(contractionRowMajorAT, N, 64, N);\nBM_FuncWithInputDimsGPU(contractionRowMajorAT, N, N, 64);\n\nBM_FuncWithInputDimsGPU(contractionRowMajorBT, N, N, N);\nBM_FuncWithInputDimsGPU(contractionRowMajorBT, 64, N, N);\nBM_FuncWithInputDimsGPU(contractionRowMajorBT, N, 64, N);\nBM_FuncWithInputDimsGPU(contractionRowMajorBT, N, N, 64);\n\n\nBM_FuncWithInputDimsGPU(contractionRowMajorABT, N, N, N);\nBM_FuncWithInputDimsGPU(contractionRowMajorABT, 64, N, N);\nBM_FuncWithInputDimsGPU(contractionRowMajorABT, N, 64, N);\nBM_FuncWithInputDimsGPU(contractionRowMajorABT, N, N, 64);\n\n// Convolutions\n#define BM_FuncWithKernelDimsGPU(FUNC, DIM1, DIM2)             \\\n  static void BM_##FUNC##_##DIM1##x##DIM2(int iters, int N) {  \\\n    StopBenchmarkTiming();                                     \\\n    Eigen::SyclDevice device(&queue);                          \\\n    BenchmarkSuite<Eigen::SyclDevice, float> suite(device, N); \\\n    suite.FUNC(iters, DIM1, DIM2);                             \\\n  }                                                            \\\n  BENCHMARK_RANGE(BM_##FUNC##_##DIM1##x##DIM2, 128, 5000);\n\nBM_FuncWithKernelDimsGPU(convolution, 7, 1);\nBM_FuncWithKernelDimsGPU(convolution, 1, 7);\nBM_FuncWithKernelDimsGPU(convolution, 7, 4);\nBM_FuncWithKernelDimsGPU(convolution, 4, 7);\nBM_FuncWithKernelDimsGPU(convolution, 7, 64);\nBM_FuncWithKernelDimsGPU(convolution, 64, 7);\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/tensors/tensor_contract_sycl_bench.cc",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n#ifndef EIGEN_BENCH_CONTRACT_SYCL\n#define EIGEN_BENCH_CONTRACT_SYCL\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#include <SYCL/sycl.hpp>\n#include <fstream>\n#include <iostream>\n#include <chrono>\n#include <ctime>\n\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\nstd::ofstream out(\"Result.txt\");\n\nstd::chrono::time_point<std::chrono::system_clock> get_time(){\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  return std::chrono::system_clock::now();\n}\n\ntemplate<typename Start, typename End, typename TensorIndex>\nvoid finalizeBenchmark(Start start, End end, TensorIndex m_, TensorIndex k_, TensorIndex n_ , TensorIndex num_iters, std::string name){\n\n  std::chrono::duration<double> elapsed_seconds = end-start;\n  std::cout <<\"Kernel Name : \" << name << \", M : \" << m_ << \",  N : \" << n_ << \", K : \" << k_ << \" GFLOP/s : \" <<\n  static_cast<float>((static_cast<int64_t>(2) * m_ * n_ * k_ * num_iters)/ elapsed_seconds.count()) * 1e-9 << \"\\n\";\n    out <<\"Kernel Name : \" << name << \", M : \" << m_ << \",  N : \" << n_ << \", K : \" << k_ << \" GFLOP/s : \" <<\n    static_cast<float>((static_cast<int64_t>(2) * m_ * n_ * k_ * num_iters)/ elapsed_seconds.count()) * 1e-9 << \"\\n\";\n}\n\n// do a contraction which is equivalent to a matrix multiplication\ntemplate<typename T, typename Device, typename TensorIndex>\nvoid contraction(const Device& device_, TensorIndex num_iters, TensorIndex m_, TensorIndex k_, TensorIndex n_) {\n  T* a_;\n  T* b_;\n  T* c_;\n  a_ = (T *) device_.allocate(m_ * k_ * sizeof(T));\n  b_ = (T *) device_.allocate(k_ * n_ * sizeof(T));\n  c_ = (T *) device_.allocate(m_ * n_ * sizeof(T));\n\n  // Initialize the content of the memory pools to prevent asan from\n  // complaining.\n  device_.fill(a_, m_ * k_, T(12));\n  device_.fill(b_, k_ * n_, T(23));\n  device_.fill(c_, m_ * n_, T(31));\n\n  Eigen::array<TensorIndex, 2> sizeA;\n  sizeA[0] = m_;\n  sizeA[1] = k_;\n  Eigen::array<TensorIndex, 2> sizeB;\n  sizeB[0] = k_;\n  sizeB[1] = n_;\n  Eigen::array<TensorIndex, 2> sizeC;\n  sizeC[0] = m_;\n  sizeC[1] = n_;\n\n  const TensorMap<Tensor<T, 2>, Eigen::Aligned> A(a_, sizeA);\n  const TensorMap<Tensor<T, 2>, Eigen::Aligned> B(b_, sizeB);\n  TensorMap<Tensor<T, 2>, Eigen::Aligned> C(c_, sizeC);\n\n  typedef typename Tensor<T, 2>::DimensionPair DimPair;\n  Eigen::array<DimPair, 1> dims;\n  dims[0] = DimPair(1, 0);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n  for (int iter = 0; iter < 10; ++iter) {\n    C.device(device_) = A.contract(B, dims);\n   }\n#endif\n  auto start = get_time();\n  for (int iter = 0; iter < num_iters; ++iter) {\n    C.device(device_) = A.contract(B, dims);\n  }\n auto end = get_time();\n  // Record the number of FLOPs executed per second (size_ multiplications and\n  // additions for each value in the resulting tensor)\n  finalizeBenchmark(start, end, m_, k_, n_, num_iters, \"contraction\");\n  device_.deallocate(a_);\n  device_.deallocate(b_);\n  device_.deallocate(c_);\n  device_.synchronize();\n}\n\n\n\n// do a contraction which is equivalent to a matrix multiplication\ntemplate<typename T, typename Device, typename TensorIndex>\nvoid contractionRowMajor(const Device& device_, TensorIndex num_iters, TensorIndex m_, TensorIndex k_, TensorIndex n_) {\n  T* a_;\n  T* b_;\n  T* c_;\n  a_ = (T *) device_.allocate(m_ * k_ * sizeof(T));\n  b_ = (T *) device_.allocate(k_ * n_ * sizeof(T));\n  c_ = (T *) device_.allocate(m_ * n_ * sizeof(T));\n\n  // Initialize the content of the memory pools to prevent asan from\n  // complaining.\n  device_.memset(a_, 12, m_ * k_ * sizeof(T));\n  device_.memset(b_, 23, k_ * n_ * sizeof(T));\n  device_.memset(c_, 31, m_ * n_ * sizeof(T));\n\n  Eigen::array<TensorIndex, 2> sizeA;\n  sizeA[0] = m_;\n  sizeA[1] = k_;\n  Eigen::array<TensorIndex, 2> sizeB;\n  sizeB[0] = k_;\n  sizeB[1] = n_;\n  Eigen::array<TensorIndex, 2> sizeC;\n  sizeC[0] = m_;\n  sizeC[1] = n_;\n\n  const TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> A(a_, sizeA);\n  const TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> B(b_, sizeB);\n  TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> C(c_, sizeC);\n\n  typedef typename Tensor<T, 2>::DimensionPair DimPair;\n  Eigen::array<DimPair, 1> dims;\n  dims[0] = DimPair(1, 0);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n  for (int iter = 0; iter < 10; ++iter) {\n    C.device(device_) = A.contract(B, dims);\n   }\n#endif\n  auto start = get_time();\n  for (int iter = 0; iter < num_iters; ++iter) {\n    C.device(device_) = A.contract(B, dims);\n  }\n  auto end = get_time();\n  // Record the number of FLOPs executed per second (size_ multiplications and\n  // additions for each value in the resulting tensor)\n  finalizeBenchmark(start, end, m_, k_, n_, num_iters, \"contractionRowMajor\");\n  device_.deallocate(a_);\n  device_.deallocate(b_);\n  device_.deallocate(c_);\n  device_.synchronize();\n}\n\n\ntemplate<typename T, typename Device, typename TensorIndex>\nvoid contractionAT(const Device& device_, TensorIndex num_iters, TensorIndex m_, TensorIndex k_, TensorIndex n_) {\n  T* a_;\n  T* b_;\n  T* c_;\n  a_ = (T *) device_.allocate(m_ * k_ * sizeof(T));\n  b_ = (T *) device_.allocate(k_ * n_ * sizeof(T));\n  c_ = (T *) device_.allocate(m_ * n_ * sizeof(T));\n\n  // Initialize the content of the memory pools to prevent asan from\n  // complaining.\n  device_.memset(a_, 12, m_ * k_ * sizeof(T));\n  device_.memset(b_, 23, k_ * n_ * sizeof(T));\n  device_.memset(c_, 31, m_ * n_ * sizeof(T));\n  Eigen::array<TensorIndex, 2> sizeA;\n  sizeA[0] = k_;\n  sizeA[1] = m_;\n  Eigen::array<TensorIndex, 2> sizeB;\n  sizeB[0] = k_;\n  sizeB[1] = n_;\n  Eigen::array<TensorIndex, 2> sizeC;\n  sizeC[0] = m_;\n  sizeC[1] = n_;\n\n  const TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> A(a_, sizeA);\n  const TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> B(b_, sizeB);\n  TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> C(c_, sizeC);\n\n  typedef typename Tensor<T, 2>::DimensionPair DimPair;\n  Eigen::array<DimPair, 1> dims;\n  dims[0] = DimPair(0, 0);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n  for (int iter = 0; iter < 10; ++iter) {\n    C.device(device_) = A.contract(B, dims);\n   }\n#endif\n  auto start = get_time();\n  for (int iter = 0; iter < num_iters; ++iter) {\n    C.device(device_) = A.contract(B, dims);\n  }\n  auto end = get_time();\n  // Record the number of FLOPs executed per second (size_ multiplications and\n  // additions for each value in the resulting tensor)\n  finalizeBenchmark(start, end, m_, k_, n_, num_iters, \"contractionAT\");\n  device_.deallocate(a_);\n  device_.deallocate(b_);\n  device_.deallocate(c_);\n  device_.synchronize();\n\n}\n\ntemplate<typename T, typename Device, typename TensorIndex>\nvoid contractionBT(const Device& device_, TensorIndex num_iters, TensorIndex m_, TensorIndex k_, TensorIndex n_) {\n  T* a_;\n  T* b_;\n  T* c_;\n  a_ = (T *) device_.allocate(m_ * k_ * sizeof(T));\n  b_ = (T *) device_.allocate(k_ * n_ * sizeof(T));\n  c_ = (T *) device_.allocate(m_ * n_ * sizeof(T));\n\n  // Initialize the content of the memory pools to prevent asan from\n  // complaining.\n  device_.memset(a_, 12, m_ * k_ * sizeof(T));\n  device_.memset(b_, 23, k_ * n_ * sizeof(T));\n  device_.memset(c_, 31, m_ * n_ * sizeof(T));\n\n  Eigen::array<TensorIndex, 2> sizeA;\n  sizeA[0] = m_;\n  sizeA[1] = k_;\n  Eigen::array<TensorIndex, 2> sizeB;\n  sizeB[0] = n_;\n  sizeB[1] = k_;\n  Eigen::array<TensorIndex, 2> sizeC;\n  sizeC[0] = m_;\n  sizeC[1] = n_;\n\n  const TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> A(a_, sizeA);\n  const TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> B(b_, sizeB);\n  TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> C(c_, sizeC);\n\n  typedef typename Tensor<T, 2>::DimensionPair DimPair;\n  Eigen::array<DimPair, 1> dims;\n  dims[0] = DimPair(1, 1);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n  for (int iter = 0; iter < 10; ++iter) {\n    C.device(device_) = A.contract(B, dims);\n   }\n#endif\n  auto start = get_time();\n  for (int iter = 0; iter < num_iters; ++iter) {\n    C.device(device_) = A.contract(B, dims);\n  }\n  auto end = get_time();\n  // Record the number of FLOPs executed per second (size_ multiplications and\n  // additions for each value in the resulting tensor)\n  finalizeBenchmark(start, end, m_, k_, n_, num_iters, \"contractionBT\");\n  device_.deallocate(a_);\n  device_.deallocate(b_);\n  device_.deallocate(c_);\n  device_.synchronize();\n\n}\n\ntemplate<typename T, typename Device, typename TensorIndex>\nvoid contractionABT(const Device& device_, TensorIndex num_iters, TensorIndex m_, TensorIndex k_, TensorIndex n_) {\n  T* a_;\n  T* b_;\n  T* c_;\n  a_ = (T *) device_.allocate(m_ * k_ * sizeof(T));\n  b_ = (T *) device_.allocate(k_ * n_ * sizeof(T));\n  c_ = (T *) device_.allocate(m_ * n_ * sizeof(T));\n\n  // Initialize the content of the memory pools to prevent asan from\n  // complaining.\n  device_.memset(a_, 12, m_ * k_ * sizeof(T));\n  device_.memset(b_, 23, k_ * n_ * sizeof(T));\n  device_.memset(c_, 31, m_ * n_ * sizeof(T));\n\n  Eigen::array<TensorIndex, 2> sizeA;\n  sizeA[0] = k_;\n  sizeA[1] = m_;\n  Eigen::array<TensorIndex, 2> sizeB;\n  sizeB[0] = n_;\n  sizeB[1] = k_;\n  Eigen::array<TensorIndex, 2> sizeC;\n  sizeC[0] = m_;\n  sizeC[1] = n_;\n\n  const TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> A(a_, sizeA);\n  const TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> B(b_, sizeB);\n  TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> C(c_, sizeC);\n\n  typedef typename Tensor<T, 2>::DimensionPair DimPair;\n  Eigen::array<DimPair, 1> dims;\n  dims[0] = DimPair(0, 1);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n  for (int iter = 0; iter < 10; ++iter) {\n    C.device(device_) = A.contract(B, dims);\n   }\n#endif\n  auto start = get_time();\n  for (int iter = 0; iter < num_iters; ++iter) {\n    C.device(device_) = A.contract(B, dims);\n  }\n  auto end = get_time();\n  // Record the number of FLOPs executed per second (size_ multiplications and\n  // additions for each value in the resulting tensor)\n  finalizeBenchmark(start, end, m_, k_, n_, num_iters, \"contractionABT\");\n  device_.deallocate(a_);\n  device_.deallocate(b_);\n  device_.deallocate(c_);\n  device_.synchronize();\n}\n\nint main() {\n  cl::sycl::gpu_selector selector;\n  Eigen::QueueInterface queue(selector);\n  Eigen::SyclDevice device(&queue);\n  int64_t num_iters =20;\n  for(int64_t m = 32; m <= 4096; m *= 2)\n    for(int64_t k = 32; k <= 4096; k *= 2)\n      for(int64_t n = 32; n <= 4096; n*= 2){\n        (contraction<float>(device, num_iters, m, k, n));\n        (contractionRowMajor<float>(device, num_iters, m, k, n));\n        (contractionAT<float>(device, num_iters, m, k, n));\n        (contractionBT<float>(device, num_iters, m, k, n));\n        (contractionABT<float>(device, num_iters, m, k, n));\n      }\n  return 0;\n  }\n\n#endif // EIGEN_BENCH_CONTRACT_SYCL\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/bench/vdw_new.cpp",
    "content": "#include <iostream>\n#include <Eigen/Core>\n\nusing namespace Eigen;\n\n#ifndef SCALAR\n#define SCALAR float\n#endif\n\n#ifndef SIZE\n#define SIZE 10000\n#endif\n\n#ifndef REPEAT\n#define REPEAT 10000\n#endif\n\ntypedef Matrix<SCALAR, Eigen::Dynamic, 1> Vec;\n\nusing namespace std;\n\nSCALAR E_VDW(const Vec &interactions1, const Vec &interactions2)\n{\n  return (interactions2.cwise()/interactions1)\n         .cwise().cube()\n         .cwise().square()\n         .cwise().square()\n         .sum();\n}\n\nint main() \n{\n  //\n  //          1   2   3   4  ... (interactions)\n  // ka       .   .   .   .  ...\n  // rab      .   .   .   .  ...\n  // energy   .   .   .   .  ...\n  // ...     ... ... ... ... ...\n  // (variables\n  //    for\n  // interaction)\n  //\n  Vec interactions1(SIZE), interactions2(SIZE); // SIZE is the number of vdw interactions in our system\n  // SetupCalculations()\n  SCALAR rab = 1.0;  \n  interactions1.setConstant(2.4);\n  interactions2.setConstant(rab);\n  \n  // Energy()\n  SCALAR energy = 0.0;\n  for (unsigned int i = 0; i<REPEAT; ++i) {\n    energy += E_VDW(interactions1, interactions2);\n    energy *= 1 + 1e-20 * i; // prevent compiler from optimizing the loop\n  }\n  cout << \"energy = \" << energy << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/BandTriangularSolver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BAND_TRIANGULARSOLVER_H\n#define EIGEN_BAND_TRIANGULARSOLVER_H\n\nnamespace internal {\n\n /* \\internal\n  * Solve Ax=b with A a band triangular matrix\n  * TODO: extend it to matrices for x abd b */\ntemplate<typename Index, int Mode, typename LhsScalar, bool ConjLhs, typename RhsScalar, int StorageOrder>\nstruct band_solve_triangular_selector;\n\n\ntemplate<typename Index, int Mode, typename LhsScalar, bool ConjLhs, typename RhsScalar>\nstruct band_solve_triangular_selector<Index,Mode,LhsScalar,ConjLhs,RhsScalar,RowMajor>\n{\n  typedef Map<const Matrix<LhsScalar,Dynamic,Dynamic,RowMajor>, 0, OuterStride<> > LhsMap;\n  typedef Map<Matrix<RhsScalar,Dynamic,1> > RhsMap;\n  enum { IsLower = (Mode&Lower) ? 1 : 0 };\n  static void run(Index size, Index k, const LhsScalar* _lhs, Index lhsStride, RhsScalar* _other)\n  {\n    const LhsMap lhs(_lhs,size,k+1,OuterStride<>(lhsStride));\n    RhsMap other(_other,size,1);\n    typename internal::conditional<\n                          ConjLhs,\n                          const CwiseUnaryOp<typename internal::scalar_conjugate_op<LhsScalar>,LhsMap>,\n                          const LhsMap&>\n                        ::type cjLhs(lhs);\n                        \n    for(int col=0 ; col<other.cols() ; ++col)\n    {\n      for(int ii=0; ii<size; ++ii)\n      {\n        int i = IsLower ? ii : size-ii-1;\n        int actual_k = (std::min)(k,ii);\n        int actual_start = IsLower ? k-actual_k : 1;\n        \n        if(actual_k>0)\n          other.coeffRef(i,col) -= cjLhs.row(i).segment(actual_start,actual_k).transpose()\n                                  .cwiseProduct(other.col(col).segment(IsLower ? i-actual_k : i+1,actual_k)).sum();\n\n        if((Mode&UnitDiag)==0)\n          other.coeffRef(i,col) /= cjLhs(i,IsLower ? k : 0);\n      }\n    }\n  }\n  \n};\n\ntemplate<typename Index, int Mode, typename LhsScalar, bool ConjLhs, typename RhsScalar>\nstruct band_solve_triangular_selector<Index,Mode,LhsScalar,ConjLhs,RhsScalar,ColMajor>\n{\n  typedef Map<const Matrix<LhsScalar,Dynamic,Dynamic,ColMajor>, 0, OuterStride<> > LhsMap;\n  typedef Map<Matrix<RhsScalar,Dynamic,1> > RhsMap;\n  enum { IsLower = (Mode&Lower) ? 1 : 0 };\n  static void run(Index size, Index k, const LhsScalar* _lhs, Index lhsStride, RhsScalar* _other)\n  {\n    const LhsMap lhs(_lhs,k+1,size,OuterStride<>(lhsStride));\n    RhsMap other(_other,size,1);\n    typename internal::conditional<\n                          ConjLhs,\n                          const CwiseUnaryOp<typename internal::scalar_conjugate_op<LhsScalar>,LhsMap>,\n                          const LhsMap&>\n                        ::type cjLhs(lhs);\n                        \n    for(int col=0 ; col<other.cols() ; ++col)\n    {\n      for(int ii=0; ii<size; ++ii)\n      {\n        int i = IsLower ? ii : size-ii-1;\n        int actual_k = (std::min)(k,size-ii-1);\n        int actual_start = IsLower ? 1 : k-actual_k;\n        \n        if((Mode&UnitDiag)==0)\n          other.coeffRef(i,col) /= cjLhs(IsLower ? 0 : k, i);\n\n        if(actual_k>0)\n          other.col(col).segment(IsLower ? i+1 : i-actual_k, actual_k)\n              -= other.coeff(i,col) * cjLhs.col(i).segment(actual_start,actual_k);\n        \n      }\n    }\n  }\n};\n\n\n} // end namespace internal\n\n#endif // EIGEN_BAND_TRIANGULARSOLVER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/CMakeLists.txt",
    "content": "\nproject(EigenBlas CXX)\n\ninclude(CheckLanguage)\ncheck_language(Fortran)\nif(CMAKE_Fortran_COMPILER)\n  enable_language(Fortran)\n  set(EIGEN_Fortran_COMPILER_WORKS ON)\nelse()\n  set(EIGEN_Fortran_COMPILER_WORKS OFF)\nendif()\n\nadd_custom_target(blas)\n\nset(EigenBlas_SRCS  single.cpp double.cpp complex_single.cpp complex_double.cpp xerbla.cpp\n                    f2c/srotm.c   f2c/srotmg.c  f2c/drotm.c f2c/drotmg.c\n                    f2c/lsame.c   f2c/dspmv.c   f2c/ssbmv.c f2c/chbmv.c\n                    f2c/sspmv.c   f2c/zhbmv.c   f2c/chpmv.c f2c/dsbmv.c\n                    f2c/zhpmv.c   f2c/dtbmv.c   f2c/stbmv.c f2c/ctbmv.c\n                    f2c/ztbmv.c   f2c/d_cnjg.c  f2c/r_cnjg.c\n   )\n\nif (EIGEN_Fortran_COMPILER_WORKS)\n  set(EigenBlas_SRCS ${EigenBlas_SRCS} fortran/complexdots.f)\nelse()\n  set(EigenBlas_SRCS ${EigenBlas_SRCS} f2c/complexdots.c)\nendif()\n\nset(EIGEN_BLAS_TARGETS \"\")\n\nadd_library(eigen_blas_static ${EigenBlas_SRCS})\nlist(APPEND EIGEN_BLAS_TARGETS eigen_blas_static)\n\nif (EIGEN_BUILD_SHARED_LIBS)\n  add_library(eigen_blas SHARED ${EigenBlas_SRCS})\n  list(APPEND EIGEN_BLAS_TARGETS eigen_blas)\nendif()\n\nforeach(target IN LISTS EIGEN_BLAS_TARGETS)\n  if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO)\n      target_link_libraries(${target} ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO})\n  endif()\n\n  add_dependencies(blas ${target})\n  install(TARGETS ${target}\n          RUNTIME DESTINATION bin\n          LIBRARY DESTINATION lib\n          ARCHIVE DESTINATION lib)\nendforeach()\n\nif(EIGEN_Fortran_COMPILER_WORKS)\n\nif(BUILD_TESTING)\n  if(EIGEN_LEAVE_TEST_IN_ALL_TARGET)\n    add_subdirectory(testing) # can't do EXCLUDE_FROM_ALL here, breaks CTest\n  else()\n    add_subdirectory(testing EXCLUDE_FROM_ALL)\n  endif()\nendif()\n\nendif()\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/GeneralRank1Update.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_GENERAL_RANK1UPDATE_H\n#define EIGEN_GENERAL_RANK1UPDATE_H\n\nnamespace internal {\n\n/* Optimized matrix += alpha * uv' */\ntemplate<typename Scalar, typename Index, int StorageOrder, bool ConjLhs, bool ConjRhs>\nstruct general_rank1_update;\n\ntemplate<typename Scalar, typename Index, bool ConjLhs, bool ConjRhs>\nstruct general_rank1_update<Scalar,Index,ColMajor,ConjLhs,ConjRhs>\n{\n  static void run(Index rows, Index cols, Scalar* mat, Index stride, const Scalar* u, const Scalar* v, Scalar alpha)\n  {\n    typedef Map<const Matrix<Scalar,Dynamic,1> > OtherMap;\n    typedef typename conj_expr_if<ConjLhs,OtherMap>::type ConjRhsType;\n    conj_if<ConjRhs> cj;\n\n    for (Index i=0; i<cols; ++i)\n      Map<Matrix<Scalar,Dynamic,1> >(mat+stride*i,rows) += alpha * cj(v[i]) * ConjRhsType(OtherMap(u,rows));\n  }\n};\n\ntemplate<typename Scalar, typename Index, bool ConjLhs, bool ConjRhs>\nstruct general_rank1_update<Scalar,Index,RowMajor,ConjLhs,ConjRhs>\n{\n  static void run(Index rows, Index cols, Scalar* mat, Index stride, const Scalar* u, const Scalar* v, Scalar alpha)\n  {\n    general_rank1_update<Scalar,Index,ColMajor,ConjRhs,ConjRhs>::run(rows,cols,mat,stride,u,v,alpha);\n  }\n};\n\n} // end namespace internal\n\n#endif // EIGEN_GENERAL_RANK1UPDATE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/PackedSelfadjointProduct.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SELFADJOINT_PACKED_PRODUCT_H\n#define EIGEN_SELFADJOINT_PACKED_PRODUCT_H\n\nnamespace internal {\n\n/* Optimized matrix += alpha * uv'\n * The matrix is in packed form.\n */\ntemplate<typename Scalar, typename Index, int StorageOrder, int UpLo, bool ConjLhs, bool ConjRhs>\nstruct selfadjoint_packed_rank1_update;\n\ntemplate<typename Scalar, typename Index, int UpLo, bool ConjLhs, bool ConjRhs>\nstruct selfadjoint_packed_rank1_update<Scalar,Index,ColMajor,UpLo,ConjLhs,ConjRhs>\n{\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  static void run(Index size, Scalar* mat, const Scalar* vec, RealScalar alpha)\n  {\n    typedef Map<const Matrix<Scalar,Dynamic,1> > OtherMap;\n    typedef typename conj_expr_if<ConjLhs,OtherMap>::type ConjRhsType;\n    conj_if<ConjRhs> cj;\n\n    for (Index i=0; i<size; ++i)\n    {\n      Map<Matrix<Scalar,Dynamic,1> >(mat, UpLo==Lower ? size-i : (i+1)) += alpha * cj(vec[i]) * ConjRhsType(OtherMap(vec+(UpLo==Lower ? i : 0), UpLo==Lower ? size-i : (i+1)));\n      //FIXME This should be handled outside.\n      mat[UpLo==Lower ? 0 : i] = numext::real(mat[UpLo==Lower ? 0 : i]);\n      mat += UpLo==Lower ? size-i : (i+1);\n    }\n  }\n};\n\ntemplate<typename Scalar, typename Index, int UpLo, bool ConjLhs, bool ConjRhs>\nstruct selfadjoint_packed_rank1_update<Scalar,Index,RowMajor,UpLo,ConjLhs,ConjRhs>\n{\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  static void run(Index size, Scalar* mat, const Scalar* vec, RealScalar alpha)\n  {\n    selfadjoint_packed_rank1_update<Scalar,Index,ColMajor,UpLo==Lower?Upper:Lower,ConjRhs,ConjLhs>::run(size,mat,vec,alpha);\n  }\n};\n\n} // end namespace internal\n\n#endif // EIGEN_SELFADJOINT_PACKED_PRODUCT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/PackedTriangularMatrixVector.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_PACKED_TRIANGULAR_MATRIX_VECTOR_H\n#define EIGEN_PACKED_TRIANGULAR_MATRIX_VECTOR_H\n\nnamespace internal {\n\ntemplate<typename Index, int Mode, typename LhsScalar, bool ConjLhs, typename RhsScalar, bool ConjRhs, int StorageOrder>\nstruct packed_triangular_matrix_vector_product;\n\ntemplate<typename Index, int Mode, typename LhsScalar, bool ConjLhs, typename RhsScalar, bool ConjRhs>\nstruct packed_triangular_matrix_vector_product<Index,Mode,LhsScalar,ConjLhs,RhsScalar,ConjRhs,ColMajor>\n{\n  typedef typename ScalarBinaryOpTraits<LhsScalar, RhsScalar>::ReturnType ResScalar;\n  enum {\n    IsLower     = (Mode & Lower)   ==Lower,\n    HasUnitDiag = (Mode & UnitDiag)==UnitDiag,\n    HasZeroDiag = (Mode & ZeroDiag)==ZeroDiag\n  };\n  static void run(Index size, const LhsScalar* lhs, const RhsScalar* rhs, ResScalar* res, ResScalar alpha)\n  {\n    internal::conj_if<ConjRhs> cj;\n    typedef Map<const Matrix<LhsScalar,Dynamic,1> > LhsMap;\n    typedef typename conj_expr_if<ConjLhs,LhsMap>::type ConjLhsType;\n    typedef Map<Matrix<ResScalar,Dynamic,1> > ResMap;\n\n    for (Index i=0; i<size; ++i)\n    {\n      Index s = IsLower&&(HasUnitDiag||HasZeroDiag) ? 1 : 0;\n      Index r = IsLower ? size-i: i+1;\n      if (EIGEN_IMPLIES(HasUnitDiag||HasZeroDiag, (--r)>0))\n\tResMap(res+(IsLower ? s+i : 0),r) += alpha * cj(rhs[i]) * ConjLhsType(LhsMap(lhs+s,r));\n      if (HasUnitDiag)\n\tres[i] += alpha * cj(rhs[i]);\n      lhs += IsLower ? size-i: i+1;\n    }\n  };\n};\n\ntemplate<typename Index, int Mode, typename LhsScalar, bool ConjLhs, typename RhsScalar, bool ConjRhs>\nstruct packed_triangular_matrix_vector_product<Index,Mode,LhsScalar,ConjLhs,RhsScalar,ConjRhs,RowMajor>\n{\n  typedef typename ScalarBinaryOpTraits<LhsScalar, RhsScalar>::ReturnType ResScalar;\n  enum {\n    IsLower     = (Mode & Lower)   ==Lower,\n    HasUnitDiag = (Mode & UnitDiag)==UnitDiag,\n    HasZeroDiag = (Mode & ZeroDiag)==ZeroDiag\n  };\n  static void run(Index size, const LhsScalar* lhs, const RhsScalar* rhs, ResScalar* res, ResScalar alpha)\n  {\n    internal::conj_if<ConjRhs> cj;\n    typedef Map<const Matrix<LhsScalar,Dynamic,1> > LhsMap;\n    typedef typename conj_expr_if<ConjLhs,LhsMap>::type ConjLhsType;\n    typedef Map<const Matrix<RhsScalar,Dynamic,1> > RhsMap;\n    typedef typename conj_expr_if<ConjRhs,RhsMap>::type ConjRhsType;\n\n    for (Index i=0; i<size; ++i)\n    {\n      Index s = !IsLower&&(HasUnitDiag||HasZeroDiag) ? 1 : 0;\n      Index r = IsLower ? i+1 : size-i;\n      if (EIGEN_IMPLIES(HasUnitDiag||HasZeroDiag, (--r)>0))\n\tres[i] += alpha * (ConjLhsType(LhsMap(lhs+s,r)).cwiseProduct(ConjRhsType(RhsMap(rhs+(IsLower ? 0 : s+i),r)))).sum();\n      if (HasUnitDiag)\n\tres[i] += alpha * cj(rhs[i]);\n      lhs += IsLower ? i+1 : size-i;\n    }\n  };\n};\n\n} // end namespace internal\n\n#endif // EIGEN_PACKED_TRIANGULAR_MATRIX_VECTOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/PackedTriangularSolverVector.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_PACKED_TRIANGULAR_SOLVER_VECTOR_H\n#define EIGEN_PACKED_TRIANGULAR_SOLVER_VECTOR_H\n\nnamespace internal {\n\ntemplate<typename LhsScalar, typename RhsScalar, typename Index, int Side, int Mode, bool Conjugate, int StorageOrder>\nstruct packed_triangular_solve_vector;\n\n// forward and backward substitution, row-major, rhs is a vector\ntemplate<typename LhsScalar, typename RhsScalar, typename Index, int Mode, bool Conjugate>\nstruct packed_triangular_solve_vector<LhsScalar, RhsScalar, Index, OnTheLeft, Mode, Conjugate, RowMajor>\n{\n  enum {\n    IsLower = (Mode&Lower)==Lower\n  };\n  static void run(Index size, const LhsScalar* lhs, RhsScalar* rhs)\n  {\n    internal::conj_if<Conjugate> cj;\n    typedef Map<const Matrix<LhsScalar,Dynamic,1> > LhsMap;\n    typedef typename conj_expr_if<Conjugate,LhsMap>::type ConjLhsType;\n\n    lhs += IsLower ? 0 : (size*(size+1)>>1)-1;\n    for(Index pi=0; pi<size; ++pi)\n    {\n      Index i = IsLower ? pi : size-pi-1;\n      Index s = IsLower ? 0 : 1;\n      if (pi>0)\n\trhs[i] -= (ConjLhsType(LhsMap(lhs+s,pi))\n\t    .cwiseProduct(Map<const Matrix<RhsScalar,Dynamic,1> >(rhs+(IsLower ? 0 : i+1),pi))).sum();\n      if (!(Mode & UnitDiag))\n\trhs[i] /= cj(lhs[IsLower ? i : 0]);\n      IsLower ? lhs += pi+1 : lhs -= pi+2;\n    }\n  }\n};\n\n// forward and backward substitution, column-major, rhs is a vector\ntemplate<typename LhsScalar, typename RhsScalar, typename Index, int Mode, bool Conjugate>\nstruct packed_triangular_solve_vector<LhsScalar, RhsScalar, Index, OnTheLeft, Mode, Conjugate, ColMajor>\n{\n  enum {\n    IsLower = (Mode&Lower)==Lower\n  };\n  static void run(Index size, const LhsScalar* lhs, RhsScalar* rhs)\n  {\n    internal::conj_if<Conjugate> cj;\n    typedef Map<const Matrix<LhsScalar,Dynamic,1> > LhsMap;\n    typedef typename conj_expr_if<Conjugate,LhsMap>::type ConjLhsType;\n\n    lhs += IsLower ? 0 : size*(size-1)>>1;\n    for(Index pi=0; pi<size; ++pi)\n    {\n      Index i = IsLower ? pi : size-pi-1;\n      Index r = size - pi - 1;\n      if (!(Mode & UnitDiag))\n\trhs[i] /= cj(lhs[IsLower ? 0 : i]);\n      if (r>0)\n\tMap<Matrix<RhsScalar,Dynamic,1> >(rhs+(IsLower? i+1 : 0),r) -=\n\t    rhs[i] * ConjLhsType(LhsMap(lhs+(IsLower? 1 : 0),r));\n      IsLower ? lhs += size-pi : lhs -= r;\n    }\n  }\n};\n\ntemplate<typename LhsScalar, typename RhsScalar, typename Index, int Mode, bool Conjugate, int StorageOrder>\nstruct packed_triangular_solve_vector<LhsScalar, RhsScalar, Index, OnTheRight, Mode, Conjugate, StorageOrder>\n{\n  static void run(Index size, const LhsScalar* lhs, RhsScalar* rhs)\n  {\n    packed_triangular_solve_vector<LhsScalar,RhsScalar,Index,OnTheLeft,\n\t((Mode&Upper)==Upper ? Lower : Upper) | (Mode&UnitDiag),\n\tConjugate,StorageOrder==RowMajor?ColMajor:RowMajor\n      >::run(size, lhs, rhs);\n  }\n};\n\n} // end namespace internal\n\n#endif // EIGEN_PACKED_TRIANGULAR_SOLVER_VECTOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/README.txt",
    "content": "\nThis directory contains a BLAS library built on top of Eigen.\n\nThis module is not built by default. In order to compile it, you need to\ntype 'make blas' from within your build dir.\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/Rank2Update.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_RANK2UPDATE_H\n#define EIGEN_RANK2UPDATE_H\n\nnamespace internal {\n\n/* Optimized selfadjoint matrix += alpha * uv' + conj(alpha)*vu'\n * This is the low-level version of SelfadjointRank2Update.h\n */\ntemplate<typename Scalar, typename Index, int UpLo>\nstruct rank2_update_selector\n{\n  static void run(Index size, Scalar* mat, Index stride, const Scalar* u, const Scalar* v, Scalar alpha)\n  {\n    typedef Map<const Matrix<Scalar,Dynamic,1> > OtherMap;\n    for (Index i=0; i<size; ++i)\n    {\n      Map<Matrix<Scalar,Dynamic,1> >(mat+stride*i+(UpLo==Lower ? i : 0), UpLo==Lower ? size-i : (i+1)) +=\n      numext::conj(alpha) * numext::conj(u[i]) * OtherMap(v+(UpLo==Lower ? i : 0), UpLo==Lower ? size-i : (i+1))\n                + alpha * numext::conj(v[i]) * OtherMap(u+(UpLo==Lower ? i : 0), UpLo==Lower ? size-i : (i+1));\n    }\n  }\n};\n\n/* Optimized selfadjoint matrix += alpha * uv' + conj(alpha)*vu'\n * The matrix is in packed form.\n */\ntemplate<typename Scalar, typename Index, int UpLo>\nstruct packed_rank2_update_selector\n{\n  static void run(Index size, Scalar* mat, const Scalar* u, const Scalar* v, Scalar alpha)\n  {\n    typedef Map<const Matrix<Scalar,Dynamic,1> > OtherMap;\n    Index offset = 0;\n    for (Index i=0; i<size; ++i)\n    {\n      Map<Matrix<Scalar,Dynamic,1> >(mat+offset, UpLo==Lower ? size-i : (i+1)) +=\n      numext::conj(alpha) * numext::conj(u[i]) * OtherMap(v+(UpLo==Lower ? i : 0), UpLo==Lower ? size-i : (i+1))\n                + alpha * numext::conj(v[i]) * OtherMap(u+(UpLo==Lower ? i : 0), UpLo==Lower ? size-i : (i+1));\n      //FIXME This should be handled outside.\n      mat[offset+(UpLo==Lower ? 0 : i)] = numext::real(mat[offset+(UpLo==Lower ? 0 : i)]);\n      offset += UpLo==Lower ? size-i : (i+1);\n    }\n  }\n};\n\n} // end namespace internal\n\n#endif // EIGEN_RANK2UPDATE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/common.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BLAS_COMMON_H\n#define EIGEN_BLAS_COMMON_H\n\n#ifdef __GNUC__\n# if __GNUC__<5\n// GCC < 5.0 does not like the global Scalar typedef\n// we just keep shadow-warnings disabled permanently\n#  define EIGEN_PERMANENTLY_DISABLE_STUPID_WARNINGS\n# endif\n#endif\n\n#include \"../Eigen/Core\"\n#include \"../Eigen/Jacobi\"\n\n#include <complex>\n\n#ifndef SCALAR\n#error the token SCALAR must be defined to compile this file\n#endif\n\n#include \"../Eigen/src/misc/blas.h\"\n\n#define NOTR    0\n#define TR      1\n#define ADJ     2\n\n#define LEFT    0\n#define RIGHT   1\n\n#define UP      0\n#define LO      1\n\n#define NUNIT   0\n#define UNIT    1\n\n#define INVALID 0xff\n\n#define OP(X)   (   ((X)=='N' || (X)=='n') ? NOTR   \\\n                  : ((X)=='T' || (X)=='t') ? TR     \\\n                  : ((X)=='C' || (X)=='c') ? ADJ    \\\n                  : INVALID)\n\n#define SIDE(X) (   ((X)=='L' || (X)=='l') ? LEFT   \\\n                  : ((X)=='R' || (X)=='r') ? RIGHT  \\\n                  : INVALID)\n\n#define UPLO(X) (   ((X)=='U' || (X)=='u') ? UP     \\\n                  : ((X)=='L' || (X)=='l') ? LO     \\\n                  : INVALID)\n\n#define DIAG(X) (   ((X)=='N' || (X)=='n') ? NUNIT  \\\n                  : ((X)=='U' || (X)=='u') ? UNIT   \\\n                  : INVALID)\n\n\ninline bool check_op(const char* op)\n{\n  return OP(*op)!=0xff;\n}\n\ninline bool check_side(const char* side)\n{\n  return SIDE(*side)!=0xff;\n}\n\ninline bool check_uplo(const char* uplo)\n{\n  return UPLO(*uplo)!=0xff;\n}\n\n\nnamespace Eigen {\n#include \"BandTriangularSolver.h\"\n#include \"GeneralRank1Update.h\"\n#include \"PackedSelfadjointProduct.h\"\n#include \"PackedTriangularMatrixVector.h\"\n#include \"PackedTriangularSolverVector.h\"\n#include \"Rank2Update.h\"\n}\n\nusing namespace Eigen;\n\ntypedef SCALAR Scalar;\ntypedef NumTraits<Scalar>::Real RealScalar;\ntypedef std::complex<RealScalar> Complex;\n\nenum\n{\n  IsComplex = Eigen::NumTraits<SCALAR>::IsComplex,\n  Conj = IsComplex\n};\n\ntypedef Matrix<Scalar,Dynamic,Dynamic,ColMajor> PlainMatrixType;\ntypedef Map<Matrix<Scalar,Dynamic,Dynamic,ColMajor>, 0, OuterStride<> > MatrixType;\ntypedef Map<const Matrix<Scalar,Dynamic,Dynamic,ColMajor>, 0, OuterStride<> > ConstMatrixType;\ntypedef Map<Matrix<Scalar,Dynamic,1>, 0, InnerStride<Dynamic> > StridedVectorType;\ntypedef Map<Matrix<Scalar,Dynamic,1> > CompactVectorType;\n\ntemplate<typename T>\nMap<Matrix<T,Dynamic,Dynamic,ColMajor>, 0, OuterStride<> >\nmatrix(T* data, int rows, int cols, int stride)\n{\n  return Map<Matrix<T,Dynamic,Dynamic,ColMajor>, 0, OuterStride<> >(data, rows, cols, OuterStride<>(stride));\n}\n\ntemplate<typename T>\nMap<const Matrix<T,Dynamic,Dynamic,ColMajor>, 0, OuterStride<> >\nmatrix(const T* data, int rows, int cols, int stride)\n{\n  return Map<const Matrix<T,Dynamic,Dynamic,ColMajor>, 0, OuterStride<> >(data, rows, cols, OuterStride<>(stride));\n}\n\ntemplate<typename T>\nMap<Matrix<T,Dynamic,1>, 0, InnerStride<Dynamic> > make_vector(T* data, int size, int incr)\n{\n  return Map<Matrix<T,Dynamic,1>, 0, InnerStride<Dynamic> >(data, size, InnerStride<Dynamic>(incr));\n}\n\ntemplate<typename T>\nMap<const Matrix<T,Dynamic,1>, 0, InnerStride<Dynamic> > make_vector(const T* data, int size, int incr)\n{\n  return Map<const Matrix<T,Dynamic,1>, 0, InnerStride<Dynamic> >(data, size, InnerStride<Dynamic>(incr));\n}\n\ntemplate<typename T>\nMap<Matrix<T,Dynamic,1> > make_vector(T* data, int size)\n{\n  return Map<Matrix<T,Dynamic,1> >(data, size);\n}\n\ntemplate<typename T>\nMap<const Matrix<T,Dynamic,1> > make_vector(const T* data, int size)\n{\n  return Map<const Matrix<T,Dynamic,1> >(data, size);\n}\n\ntemplate<typename T>\nT* get_compact_vector(T* x, int n, int incx)\n{\n  if(incx==1)\n    return x;\n\n  typename Eigen::internal::remove_const<T>::type* ret = new Scalar[n];\n  if(incx<0) make_vector(ret,n) = make_vector(x,n,-incx).reverse();\n  else       make_vector(ret,n) = make_vector(x,n, incx);\n  return ret;\n}\n\ntemplate<typename T>\nT* copy_back(T* x_cpy, T* x, int n, int incx)\n{\n  if(x_cpy==x)\n    return 0;\n\n  if(incx<0) make_vector(x,n,-incx).reverse() = make_vector(x_cpy,n);\n  else       make_vector(x,n, incx)           = make_vector(x_cpy,n);\n  return x_cpy;\n}\n\n#ifndef EIGEN_BLAS_FUNC_SUFFIX\n#define EIGEN_BLAS_FUNC_SUFFIX _\n#endif\n\n#define EIGEN_BLAS_FUNC(X) EIGEN_CAT(SCALAR_SUFFIX, EIGEN_CAT(X, EIGEN_BLAS_FUNC_SUFFIX))\n\n#endif // EIGEN_BLAS_COMMON_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/complex_double.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define SCALAR        std::complex<double>\n#define SCALAR_SUFFIX z\n#define SCALAR_SUFFIX_UP \"Z\"\n#define REAL_SCALAR_SUFFIX d\n#define ISCOMPLEX     1\n\n#include \"level1_impl.h\"\n#include \"level1_cplx_impl.h\"\n#include \"level2_impl.h\"\n#include \"level2_cplx_impl.h\"\n#include \"level3_impl.h\"\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/complex_single.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define SCALAR        std::complex<float>\n#define SCALAR_SUFFIX c\n#define SCALAR_SUFFIX_UP \"C\"\n#define REAL_SCALAR_SUFFIX s\n#define ISCOMPLEX     1\n\n#include \"level1_impl.h\"\n#include \"level1_cplx_impl.h\"\n#include \"level2_impl.h\"\n#include \"level2_cplx_impl.h\"\n#include \"level3_impl.h\"\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/double.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2012 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define SCALAR        double\n#define SCALAR_SUFFIX d\n#define SCALAR_SUFFIX_UP \"D\"\n#define ISCOMPLEX     0\n\n#include \"level1_impl.h\"\n#include \"level1_real_impl.h\"\n#include \"level2_impl.h\"\n#include \"level2_real_impl.h\"\n#include \"level3_impl.h\"\n\ndouble EIGEN_BLAS_FUNC(sdot)(int* n, float* x, int* incx, float* y, int* incy)\n{\n  if(*n<=0) return 0;\n\n  if(*incx==1 && *incy==1)    return (make_vector(x,*n).cast<double>().cwiseProduct(make_vector(y,*n).cast<double>())).sum();\n  else if(*incx>0 && *incy>0) return (make_vector(x,*n,*incx).cast<double>().cwiseProduct(make_vector(y,*n,*incy).cast<double>())).sum();\n  else if(*incx<0 && *incy>0) return (make_vector(x,*n,-*incx).reverse().cast<double>().cwiseProduct(make_vector(y,*n,*incy).cast<double>())).sum();\n  else if(*incx>0 && *incy<0) return (make_vector(x,*n,*incx).cast<double>().cwiseProduct(make_vector(y,*n,-*incy).reverse().cast<double>())).sum();\n  else if(*incx<0 && *incy<0) return (make_vector(x,*n,-*incx).reverse().cast<double>().cwiseProduct(make_vector(y,*n,-*incy).reverse().cast<double>())).sum();\n  else return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/chbmv.c",
    "content": "/* chbmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int chbmv_(char *uplo, integer *n, integer *k, complex *\n\talpha, complex *a, integer *lda, complex *x, integer *incx, complex *\n\tbeta, complex *y, integer *incy, ftnlen uplo_len)\n{\n    /* System generated locals */\n    integer a_dim1, a_offset, i__1, i__2, i__3, i__4, i__5;\n    real r__1;\n    complex q__1, q__2, q__3, q__4;\n\n    /* Builtin functions */\n    void r_cnjg(complex *, complex *);\n\n    /* Local variables */\n    integer i__, j, l, ix, iy, jx, jy, kx, ky, info;\n    complex temp1, temp2;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    integer kplus1;\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  CHBMV  performs the matrix-vector  operation */\n\n/*     y := alpha*A*x + beta*y, */\n\n/*  where alpha and beta are scalars, x and y are n element vectors and */\n/*  A is an n by n hermitian band matrix, with k super-diagonals. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the upper or lower */\n/*           triangular part of the band matrix A is being supplied as */\n/*           follows: */\n\n/*              UPLO = 'U' or 'u'   The upper triangular part of A is */\n/*                                  being supplied. */\n\n/*              UPLO = 'L' or 'l'   The lower triangular part of A is */\n/*                                  being supplied. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  K      - INTEGER. */\n/*           On entry, K specifies the number of super-diagonals of the */\n/*           matrix A. K must satisfy  0 .le. K. */\n/*           Unchanged on exit. */\n\n/*  ALPHA  - COMPLEX         . */\n/*           On entry, ALPHA specifies the scalar alpha. */\n/*           Unchanged on exit. */\n\n/*  A      - COMPLEX          array of DIMENSION ( LDA, n ). */\n/*           Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the upper triangular */\n/*           band part of the hermitian matrix, supplied column by */\n/*           column, with the leading diagonal of the matrix in row */\n/*           ( k + 1 ) of the array, the first super-diagonal starting at */\n/*           position 2 in row k, and so on. The top left k by k triangle */\n/*           of the array A is not referenced. */\n/*           The following program segment will transfer the upper */\n/*           triangular part of a hermitian band matrix from conventional */\n/*           full matrix storage to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = K + 1 - J */\n/*                    DO 10, I = MAX( 1, J - K ), J */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the lower triangular */\n/*           band part of the hermitian matrix, supplied column by */\n/*           column, with the leading diagonal of the matrix in row 1 of */\n/*           the array, the first sub-diagonal starting at position 1 in */\n/*           row 2, and so on. The bottom right k by k triangle of the */\n/*           array A is not referenced. */\n/*           The following program segment will transfer the lower */\n/*           triangular part of a hermitian band matrix from conventional */\n/*           full matrix storage to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = 1 - J */\n/*                    DO 10, I = J, MIN( N, J + K ) */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Note that the imaginary parts of the diagonal elements need */\n/*           not be set and are assumed to be zero. */\n/*           Unchanged on exit. */\n\n/*  LDA    - INTEGER. */\n/*           On entry, LDA specifies the first dimension of A as declared */\n/*           in the calling (sub) program. LDA must be at least */\n/*           ( k + 1 ). */\n/*           Unchanged on exit. */\n\n/*  X      - COMPLEX          array of DIMENSION at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the */\n/*           vector x. */\n/*           Unchanged on exit. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  BETA   - COMPLEX         . */\n/*           On entry, BETA specifies the scalar beta. */\n/*           Unchanged on exit. */\n\n/*  Y      - COMPLEX          array of DIMENSION at least */\n/*           ( 1 + ( n - 1 )*abs( INCY ) ). */\n/*           Before entry, the incremented array Y must contain the */\n/*           vector y. On exit, Y is overwritten by the updated vector y. */\n\n/*  INCY   - INTEGER. */\n/*           On entry, INCY specifies the increment for the elements of */\n/*           Y. INCY must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    a_dim1 = *lda;\n    a_offset = 1 + a_dim1;\n    a -= a_offset;\n    --x;\n    --y;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (*n < 0) {\n\tinfo = 2;\n    } else if (*k < 0) {\n\tinfo = 3;\n    } else if (*lda < *k + 1) {\n\tinfo = 6;\n    } else if (*incx == 0) {\n\tinfo = 8;\n    } else if (*incy == 0) {\n\tinfo = 11;\n    }\n    if (info != 0) {\n\txerbla_(\"CHBMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0 || (alpha->r == 0.f && alpha->i == 0.f && (beta->r == 1.f && \n                                                           beta->i == 0.f))) {\n\treturn 0;\n    }\n\n/*     Set up the start points in  X  and  Y. */\n\n    if (*incx > 0) {\n\tkx = 1;\n    } else {\n\tkx = 1 - (*n - 1) * *incx;\n    }\n    if (*incy > 0) {\n\tky = 1;\n    } else {\n\tky = 1 - (*n - 1) * *incy;\n    }\n\n/*     Start the operations. In this version the elements of the array A */\n/*     are accessed sequentially with one pass through A. */\n\n/*     First form  y := beta*y. */\n\n    if (beta->r != 1.f || beta->i != 0.f) {\n\tif (*incy == 1) {\n\t    if (beta->r == 0.f && beta->i == 0.f) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = i__;\n\t\t    y[i__2].r = 0.f, y[i__2].i = 0.f;\n/* L10: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = i__;\n\t\t    i__3 = i__;\n\t\t    q__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, \n\t\t\t    q__1.i = beta->r * y[i__3].i + beta->i * y[i__3]\n\t\t\t    .r;\n\t\t    y[i__2].r = q__1.r, y[i__2].i = q__1.i;\n/* L20: */\n\t\t}\n\t    }\n\t} else {\n\t    iy = ky;\n\t    if (beta->r == 0.f && beta->i == 0.f) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = iy;\n\t\t    y[i__2].r = 0.f, y[i__2].i = 0.f;\n\t\t    iy += *incy;\n/* L30: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = iy;\n\t\t    i__3 = iy;\n\t\t    q__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, \n\t\t\t    q__1.i = beta->r * y[i__3].i + beta->i * y[i__3]\n\t\t\t    .r;\n\t\t    y[i__2].r = q__1.r, y[i__2].i = q__1.i;\n\t\t    iy += *incy;\n/* L40: */\n\t\t}\n\t    }\n\t}\n    }\n    if (alpha->r == 0.f && alpha->i == 0.f) {\n\treturn 0;\n    }\n    if (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\n/*        Form  y  when upper triangle of A is stored. */\n\n\tkplus1 = *k + 1;\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__2 = j;\n\t\tq__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, q__1.i =\n\t\t\t alpha->r * x[i__2].i + alpha->i * x[i__2].r;\n\t\ttemp1.r = q__1.r, temp1.i = q__1.i;\n\t\ttemp2.r = 0.f, temp2.i = 0.f;\n\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\ti__2 = 1, i__3 = j - *k;\n\t\ti__4 = j - 1;\n\t\tfor (i__ = max(i__2,i__3); i__ <= i__4; ++i__) {\n\t\t    i__2 = i__;\n\t\t    i__3 = i__;\n\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t    q__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, \n\t\t\t    q__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5]\n\t\t\t    .r;\n\t\t    q__1.r = y[i__3].r + q__2.r, q__1.i = y[i__3].i + q__2.i;\n\t\t    y[i__2].r = q__1.r, y[i__2].i = q__1.i;\n\t\t    r_cnjg(&q__3, &a[l + i__ + j * a_dim1]);\n\t\t    i__2 = i__;\n\t\t    q__2.r = q__3.r * x[i__2].r - q__3.i * x[i__2].i, q__2.i =\n\t\t\t     q__3.r * x[i__2].i + q__3.i * x[i__2].r;\n\t\t    q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i;\n\t\t    temp2.r = q__1.r, temp2.i = q__1.i;\n/* L50: */\n\t\t}\n\t\ti__4 = j;\n\t\ti__2 = j;\n\t\ti__3 = kplus1 + j * a_dim1;\n\t\tr__1 = a[i__3].r;\n\t\tq__3.r = r__1 * temp1.r, q__3.i = r__1 * temp1.i;\n\t\tq__2.r = y[i__2].r + q__3.r, q__2.i = y[i__2].i + q__3.i;\n\t\tq__4.r = alpha->r * temp2.r - alpha->i * temp2.i, q__4.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tq__1.r = q__2.r + q__4.r, q__1.i = q__2.i + q__4.i;\n\t\ty[i__4].r = q__1.r, y[i__4].i = q__1.i;\n/* L60: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__4 = jx;\n\t\tq__1.r = alpha->r * x[i__4].r - alpha->i * x[i__4].i, q__1.i =\n\t\t\t alpha->r * x[i__4].i + alpha->i * x[i__4].r;\n\t\ttemp1.r = q__1.r, temp1.i = q__1.i;\n\t\ttemp2.r = 0.f, temp2.i = 0.f;\n\t\tix = kx;\n\t\tiy = ky;\n\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\ti__4 = 1, i__2 = j - *k;\n\t\ti__3 = j - 1;\n\t\tfor (i__ = max(i__4,i__2); i__ <= i__3; ++i__) {\n\t\t    i__4 = iy;\n\t\t    i__2 = iy;\n\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t    q__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, \n\t\t\t    q__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5]\n\t\t\t    .r;\n\t\t    q__1.r = y[i__2].r + q__2.r, q__1.i = y[i__2].i + q__2.i;\n\t\t    y[i__4].r = q__1.r, y[i__4].i = q__1.i;\n\t\t    r_cnjg(&q__3, &a[l + i__ + j * a_dim1]);\n\t\t    i__4 = ix;\n\t\t    q__2.r = q__3.r * x[i__4].r - q__3.i * x[i__4].i, q__2.i =\n\t\t\t     q__3.r * x[i__4].i + q__3.i * x[i__4].r;\n\t\t    q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i;\n\t\t    temp2.r = q__1.r, temp2.i = q__1.i;\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n/* L70: */\n\t\t}\n\t\ti__3 = jy;\n\t\ti__4 = jy;\n\t\ti__2 = kplus1 + j * a_dim1;\n\t\tr__1 = a[i__2].r;\n\t\tq__3.r = r__1 * temp1.r, q__3.i = r__1 * temp1.i;\n\t\tq__2.r = y[i__4].r + q__3.r, q__2.i = y[i__4].i + q__3.i;\n\t\tq__4.r = alpha->r * temp2.r - alpha->i * temp2.i, q__4.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tq__1.r = q__2.r + q__4.r, q__1.i = q__2.i + q__4.i;\n\t\ty[i__3].r = q__1.r, y[i__3].i = q__1.i;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tif (j > *k) {\n\t\t    kx += *incx;\n\t\t    ky += *incy;\n\t\t}\n/* L80: */\n\t    }\n\t}\n    } else {\n\n/*        Form  y  when lower triangle of A is stored. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__3 = j;\n\t\tq__1.r = alpha->r * x[i__3].r - alpha->i * x[i__3].i, q__1.i =\n\t\t\t alpha->r * x[i__3].i + alpha->i * x[i__3].r;\n\t\ttemp1.r = q__1.r, temp1.i = q__1.i;\n\t\ttemp2.r = 0.f, temp2.i = 0.f;\n\t\ti__3 = j;\n\t\ti__4 = j;\n\t\ti__2 = j * a_dim1 + 1;\n\t\tr__1 = a[i__2].r;\n\t\tq__2.r = r__1 * temp1.r, q__2.i = r__1 * temp1.i;\n\t\tq__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i;\n\t\ty[i__3].r = q__1.r, y[i__3].i = q__1.i;\n\t\tl = 1 - j;\n/* Computing MIN */\n\t\ti__4 = *n, i__2 = j + *k;\n\t\ti__3 = min(i__4,i__2);\n\t\tfor (i__ = j + 1; i__ <= i__3; ++i__) {\n\t\t    i__4 = i__;\n\t\t    i__2 = i__;\n\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t    q__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, \n\t\t\t    q__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5]\n\t\t\t    .r;\n\t\t    q__1.r = y[i__2].r + q__2.r, q__1.i = y[i__2].i + q__2.i;\n\t\t    y[i__4].r = q__1.r, y[i__4].i = q__1.i;\n\t\t    r_cnjg(&q__3, &a[l + i__ + j * a_dim1]);\n\t\t    i__4 = i__;\n\t\t    q__2.r = q__3.r * x[i__4].r - q__3.i * x[i__4].i, q__2.i =\n\t\t\t     q__3.r * x[i__4].i + q__3.i * x[i__4].r;\n\t\t    q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i;\n\t\t    temp2.r = q__1.r, temp2.i = q__1.i;\n/* L90: */\n\t\t}\n\t\ti__3 = j;\n\t\ti__4 = j;\n\t\tq__2.r = alpha->r * temp2.r - alpha->i * temp2.i, q__2.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tq__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i;\n\t\ty[i__3].r = q__1.r, y[i__3].i = q__1.i;\n/* L100: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__3 = jx;\n\t\tq__1.r = alpha->r * x[i__3].r - alpha->i * x[i__3].i, q__1.i =\n\t\t\t alpha->r * x[i__3].i + alpha->i * x[i__3].r;\n\t\ttemp1.r = q__1.r, temp1.i = q__1.i;\n\t\ttemp2.r = 0.f, temp2.i = 0.f;\n\t\ti__3 = jy;\n\t\ti__4 = jy;\n\t\ti__2 = j * a_dim1 + 1;\n\t\tr__1 = a[i__2].r;\n\t\tq__2.r = r__1 * temp1.r, q__2.i = r__1 * temp1.i;\n\t\tq__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i;\n\t\ty[i__3].r = q__1.r, y[i__3].i = q__1.i;\n\t\tl = 1 - j;\n\t\tix = jx;\n\t\tiy = jy;\n/* Computing MIN */\n\t\ti__4 = *n, i__2 = j + *k;\n\t\ti__3 = min(i__4,i__2);\n\t\tfor (i__ = j + 1; i__ <= i__3; ++i__) {\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n\t\t    i__4 = iy;\n\t\t    i__2 = iy;\n\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t    q__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, \n\t\t\t    q__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5]\n\t\t\t    .r;\n\t\t    q__1.r = y[i__2].r + q__2.r, q__1.i = y[i__2].i + q__2.i;\n\t\t    y[i__4].r = q__1.r, y[i__4].i = q__1.i;\n\t\t    r_cnjg(&q__3, &a[l + i__ + j * a_dim1]);\n\t\t    i__4 = ix;\n\t\t    q__2.r = q__3.r * x[i__4].r - q__3.i * x[i__4].i, q__2.i =\n\t\t\t     q__3.r * x[i__4].i + q__3.i * x[i__4].r;\n\t\t    q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i;\n\t\t    temp2.r = q__1.r, temp2.i = q__1.i;\n/* L110: */\n\t\t}\n\t\ti__3 = jy;\n\t\ti__4 = jy;\n\t\tq__2.r = alpha->r * temp2.r - alpha->i * temp2.i, q__2.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tq__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i;\n\t\ty[i__3].r = q__1.r, y[i__3].i = q__1.i;\n\t\tjx += *incx;\n\t\tjy += *incy;\n/* L120: */\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of CHBMV . */\n\n} /* chbmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/chpmv.c",
    "content": "/* chpmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int chpmv_(char *uplo, integer *n, complex *alpha, complex *\n\tap, complex *x, integer *incx, complex *beta, complex *y, integer *\n\tincy, ftnlen uplo_len)\n{\n    /* System generated locals */\n    integer i__1, i__2, i__3, i__4, i__5;\n    real r__1;\n    complex q__1, q__2, q__3, q__4;\n\n    /* Builtin functions */\n    void r_cnjg(complex *, complex *);\n\n    /* Local variables */\n    integer i__, j, k, kk, ix, iy, jx, jy, kx, ky, info;\n    complex temp1, temp2;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  CHPMV  performs the matrix-vector operation */\n\n/*     y := alpha*A*x + beta*y, */\n\n/*  where alpha and beta are scalars, x and y are n element vectors and */\n/*  A is an n by n hermitian matrix, supplied in packed form. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the upper or lower */\n/*           triangular part of the matrix A is supplied in the packed */\n/*           array AP as follows: */\n\n/*              UPLO = 'U' or 'u'   The upper triangular part of A is */\n/*                                  supplied in AP. */\n\n/*              UPLO = 'L' or 'l'   The lower triangular part of A is */\n/*                                  supplied in AP. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  ALPHA  - COMPLEX         . */\n/*           On entry, ALPHA specifies the scalar alpha. */\n/*           Unchanged on exit. */\n\n/*  AP     - COMPLEX          array of DIMENSION at least */\n/*           ( ( n*( n + 1 ) )/2 ). */\n/*           Before entry with UPLO = 'U' or 'u', the array AP must */\n/*           contain the upper triangular part of the hermitian matrix */\n/*           packed sequentially, column by column, so that AP( 1 ) */\n/*           contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 1, 2 ) */\n/*           and a( 2, 2 ) respectively, and so on. */\n/*           Before entry with UPLO = 'L' or 'l', the array AP must */\n/*           contain the lower triangular part of the hermitian matrix */\n/*           packed sequentially, column by column, so that AP( 1 ) */\n/*           contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 2, 1 ) */\n/*           and a( 3, 1 ) respectively, and so on. */\n/*           Note that the imaginary parts of the diagonal elements need */\n/*           not be set and are assumed to be zero. */\n/*           Unchanged on exit. */\n\n/*  X      - COMPLEX          array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the n */\n/*           element vector x. */\n/*           Unchanged on exit. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  BETA   - COMPLEX         . */\n/*           On entry, BETA specifies the scalar beta. When BETA is */\n/*           supplied as zero then Y need not be set on input. */\n/*           Unchanged on exit. */\n\n/*  Y      - COMPLEX          array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCY ) ). */\n/*           Before entry, the incremented array Y must contain the n */\n/*           element vector y. On exit, Y is overwritten by the updated */\n/*           vector y. */\n\n/*  INCY   - INTEGER. */\n/*           On entry, INCY specifies the increment for the elements of */\n/*           Y. INCY must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    --y;\n    --x;\n    --ap;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (*n < 0) {\n\tinfo = 2;\n    } else if (*incx == 0) {\n\tinfo = 6;\n    } else if (*incy == 0) {\n\tinfo = 9;\n    }\n    if (info != 0) {\n\txerbla_(\"CHPMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0 || (alpha->r == 0.f && alpha->i == 0.f && (beta->r == 1.f && \n                                                           beta->i == 0.f))) {\n\treturn 0;\n    }\n\n/*     Set up the start points in  X  and  Y. */\n\n    if (*incx > 0) {\n\tkx = 1;\n    } else {\n\tkx = 1 - (*n - 1) * *incx;\n    }\n    if (*incy > 0) {\n\tky = 1;\n    } else {\n\tky = 1 - (*n - 1) * *incy;\n    }\n\n/*     Start the operations. In this version the elements of the array AP */\n/*     are accessed sequentially with one pass through AP. */\n\n/*     First form  y := beta*y. */\n\n    if (beta->r != 1.f || beta->i != 0.f) {\n\tif (*incy == 1) {\n\t    if (beta->r == 0.f && beta->i == 0.f) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = i__;\n\t\t    y[i__2].r = 0.f, y[i__2].i = 0.f;\n/* L10: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = i__;\n\t\t    i__3 = i__;\n\t\t    q__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, \n\t\t\t    q__1.i = beta->r * y[i__3].i + beta->i * y[i__3]\n\t\t\t    .r;\n\t\t    y[i__2].r = q__1.r, y[i__2].i = q__1.i;\n/* L20: */\n\t\t}\n\t    }\n\t} else {\n\t    iy = ky;\n\t    if (beta->r == 0.f && beta->i == 0.f) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = iy;\n\t\t    y[i__2].r = 0.f, y[i__2].i = 0.f;\n\t\t    iy += *incy;\n/* L30: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = iy;\n\t\t    i__3 = iy;\n\t\t    q__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, \n\t\t\t    q__1.i = beta->r * y[i__3].i + beta->i * y[i__3]\n\t\t\t    .r;\n\t\t    y[i__2].r = q__1.r, y[i__2].i = q__1.i;\n\t\t    iy += *incy;\n/* L40: */\n\t\t}\n\t    }\n\t}\n    }\n    if (alpha->r == 0.f && alpha->i == 0.f) {\n\treturn 0;\n    }\n    kk = 1;\n    if (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\n/*        Form  y  when AP contains the upper triangle. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__2 = j;\n\t\tq__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, q__1.i =\n\t\t\t alpha->r * x[i__2].i + alpha->i * x[i__2].r;\n\t\ttemp1.r = q__1.r, temp1.i = q__1.i;\n\t\ttemp2.r = 0.f, temp2.i = 0.f;\n\t\tk = kk;\n\t\ti__2 = j - 1;\n\t\tfor (i__ = 1; i__ <= i__2; ++i__) {\n\t\t    i__3 = i__;\n\t\t    i__4 = i__;\n\t\t    i__5 = k;\n\t\t    q__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, \n\t\t\t    q__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5]\n\t\t\t    .r;\n\t\t    q__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i;\n\t\t    y[i__3].r = q__1.r, y[i__3].i = q__1.i;\n\t\t    r_cnjg(&q__3, &ap[k]);\n\t\t    i__3 = i__;\n\t\t    q__2.r = q__3.r * x[i__3].r - q__3.i * x[i__3].i, q__2.i =\n\t\t\t     q__3.r * x[i__3].i + q__3.i * x[i__3].r;\n\t\t    q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i;\n\t\t    temp2.r = q__1.r, temp2.i = q__1.i;\n\t\t    ++k;\n/* L50: */\n\t\t}\n\t\ti__2 = j;\n\t\ti__3 = j;\n\t\ti__4 = kk + j - 1;\n\t\tr__1 = ap[i__4].r;\n\t\tq__3.r = r__1 * temp1.r, q__3.i = r__1 * temp1.i;\n\t\tq__2.r = y[i__3].r + q__3.r, q__2.i = y[i__3].i + q__3.i;\n\t\tq__4.r = alpha->r * temp2.r - alpha->i * temp2.i, q__4.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tq__1.r = q__2.r + q__4.r, q__1.i = q__2.i + q__4.i;\n\t\ty[i__2].r = q__1.r, y[i__2].i = q__1.i;\n\t\tkk += j;\n/* L60: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__2 = jx;\n\t\tq__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, q__1.i =\n\t\t\t alpha->r * x[i__2].i + alpha->i * x[i__2].r;\n\t\ttemp1.r = q__1.r, temp1.i = q__1.i;\n\t\ttemp2.r = 0.f, temp2.i = 0.f;\n\t\tix = kx;\n\t\tiy = ky;\n\t\ti__2 = kk + j - 2;\n\t\tfor (k = kk; k <= i__2; ++k) {\n\t\t    i__3 = iy;\n\t\t    i__4 = iy;\n\t\t    i__5 = k;\n\t\t    q__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, \n\t\t\t    q__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5]\n\t\t\t    .r;\n\t\t    q__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i;\n\t\t    y[i__3].r = q__1.r, y[i__3].i = q__1.i;\n\t\t    r_cnjg(&q__3, &ap[k]);\n\t\t    i__3 = ix;\n\t\t    q__2.r = q__3.r * x[i__3].r - q__3.i * x[i__3].i, q__2.i =\n\t\t\t     q__3.r * x[i__3].i + q__3.i * x[i__3].r;\n\t\t    q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i;\n\t\t    temp2.r = q__1.r, temp2.i = q__1.i;\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n/* L70: */\n\t\t}\n\t\ti__2 = jy;\n\t\ti__3 = jy;\n\t\ti__4 = kk + j - 1;\n\t\tr__1 = ap[i__4].r;\n\t\tq__3.r = r__1 * temp1.r, q__3.i = r__1 * temp1.i;\n\t\tq__2.r = y[i__3].r + q__3.r, q__2.i = y[i__3].i + q__3.i;\n\t\tq__4.r = alpha->r * temp2.r - alpha->i * temp2.i, q__4.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tq__1.r = q__2.r + q__4.r, q__1.i = q__2.i + q__4.i;\n\t\ty[i__2].r = q__1.r, y[i__2].i = q__1.i;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tkk += j;\n/* L80: */\n\t    }\n\t}\n    } else {\n\n/*        Form  y  when AP contains the lower triangle. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__2 = j;\n\t\tq__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, q__1.i =\n\t\t\t alpha->r * x[i__2].i + alpha->i * x[i__2].r;\n\t\ttemp1.r = q__1.r, temp1.i = q__1.i;\n\t\ttemp2.r = 0.f, temp2.i = 0.f;\n\t\ti__2 = j;\n\t\ti__3 = j;\n\t\ti__4 = kk;\n\t\tr__1 = ap[i__4].r;\n\t\tq__2.r = r__1 * temp1.r, q__2.i = r__1 * temp1.i;\n\t\tq__1.r = y[i__3].r + q__2.r, q__1.i = y[i__3].i + q__2.i;\n\t\ty[i__2].r = q__1.r, y[i__2].i = q__1.i;\n\t\tk = kk + 1;\n\t\ti__2 = *n;\n\t\tfor (i__ = j + 1; i__ <= i__2; ++i__) {\n\t\t    i__3 = i__;\n\t\t    i__4 = i__;\n\t\t    i__5 = k;\n\t\t    q__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, \n\t\t\t    q__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5]\n\t\t\t    .r;\n\t\t    q__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i;\n\t\t    y[i__3].r = q__1.r, y[i__3].i = q__1.i;\n\t\t    r_cnjg(&q__3, &ap[k]);\n\t\t    i__3 = i__;\n\t\t    q__2.r = q__3.r * x[i__3].r - q__3.i * x[i__3].i, q__2.i =\n\t\t\t     q__3.r * x[i__3].i + q__3.i * x[i__3].r;\n\t\t    q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i;\n\t\t    temp2.r = q__1.r, temp2.i = q__1.i;\n\t\t    ++k;\n/* L90: */\n\t\t}\n\t\ti__2 = j;\n\t\ti__3 = j;\n\t\tq__2.r = alpha->r * temp2.r - alpha->i * temp2.i, q__2.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tq__1.r = y[i__3].r + q__2.r, q__1.i = y[i__3].i + q__2.i;\n\t\ty[i__2].r = q__1.r, y[i__2].i = q__1.i;\n\t\tkk += *n - j + 1;\n/* L100: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__2 = jx;\n\t\tq__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, q__1.i =\n\t\t\t alpha->r * x[i__2].i + alpha->i * x[i__2].r;\n\t\ttemp1.r = q__1.r, temp1.i = q__1.i;\n\t\ttemp2.r = 0.f, temp2.i = 0.f;\n\t\ti__2 = jy;\n\t\ti__3 = jy;\n\t\ti__4 = kk;\n\t\tr__1 = ap[i__4].r;\n\t\tq__2.r = r__1 * temp1.r, q__2.i = r__1 * temp1.i;\n\t\tq__1.r = y[i__3].r + q__2.r, q__1.i = y[i__3].i + q__2.i;\n\t\ty[i__2].r = q__1.r, y[i__2].i = q__1.i;\n\t\tix = jx;\n\t\tiy = jy;\n\t\ti__2 = kk + *n - j;\n\t\tfor (k = kk + 1; k <= i__2; ++k) {\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n\t\t    i__3 = iy;\n\t\t    i__4 = iy;\n\t\t    i__5 = k;\n\t\t    q__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, \n\t\t\t    q__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5]\n\t\t\t    .r;\n\t\t    q__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i;\n\t\t    y[i__3].r = q__1.r, y[i__3].i = q__1.i;\n\t\t    r_cnjg(&q__3, &ap[k]);\n\t\t    i__3 = ix;\n\t\t    q__2.r = q__3.r * x[i__3].r - q__3.i * x[i__3].i, q__2.i =\n\t\t\t     q__3.r * x[i__3].i + q__3.i * x[i__3].r;\n\t\t    q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i;\n\t\t    temp2.r = q__1.r, temp2.i = q__1.i;\n/* L110: */\n\t\t}\n\t\ti__2 = jy;\n\t\ti__3 = jy;\n\t\tq__2.r = alpha->r * temp2.r - alpha->i * temp2.i, q__2.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tq__1.r = y[i__3].r + q__2.r, q__1.i = y[i__3].i + q__2.i;\n\t\ty[i__2].r = q__1.r, y[i__2].i = q__1.i;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tkk += *n - j + 1;\n/* L120: */\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of CHPMV . */\n\n} /* chpmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/complexdots.c",
    "content": "/* This file has been modified to use the standard gfortran calling\n   convention, rather than the f2c calling convention.\n\n   It does not require -ff2c when compiled with gfortran.\n*/\n\n/* complexdots.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\ncomplex cdotc_(integer *n, complex *cx, integer \n\t*incx, complex *cy, integer *incy)\n{\n    complex res;\n    extern /* Subroutine */ int cdotcw_(integer *, complex *, integer *, \n\t    complex *, integer *, complex *);\n\n    /* Parameter adjustments */\n    --cy;\n    --cx;\n\n    /* Function Body */\n    cdotcw_(n, &cx[1], incx, &cy[1], incy, &res);\n    return res;\n} /* cdotc_ */\n\ncomplex cdotu_(integer *n, complex *cx, integer \n\t*incx, complex *cy, integer *incy)\n{\n    complex res;\n    extern /* Subroutine */ int cdotuw_(integer *, complex *, integer *, \n\t    complex *, integer *, complex *);\n\n    /* Parameter adjustments */\n    --cy;\n    --cx;\n\n    /* Function Body */\n    cdotuw_(n, &cx[1], incx, &cy[1], incy, &res);\n    return res;\n} /* cdotu_ */\n\ndoublecomplex zdotc_(integer *n, doublecomplex *cx, integer *incx, \n                     doublecomplex *cy, integer *incy)\n{\n    doublecomplex res;\n    extern /* Subroutine */ int zdotcw_(integer *, doublecomplex *, integer *,\n\t     doublecomplex *, integer *, doublecomplex *);\n\n    /* Parameter adjustments */\n    --cy;\n    --cx;\n\n    /* Function Body */\n    zdotcw_(n, &cx[1], incx, &cy[1], incy, &res);\n    return res;\n} /* zdotc_ */\n\ndoublecomplex zdotu_(integer *n, doublecomplex *cx, integer *incx, \n                     doublecomplex *cy, integer *incy)\n{\n    doublecomplex res;\n    extern /* Subroutine */ int zdotuw_(integer *, doublecomplex *, integer *,\n\t     doublecomplex *, integer *, doublecomplex *);\n\n    /* Parameter adjustments */\n    --cy;\n    --cx;\n\n    /* Function Body */\n    zdotuw_(n, &cx[1], incx, &cy[1], incy, &res);\n    return res;\n} /* zdotu_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/ctbmv.c",
    "content": "/* ctbmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int ctbmv_(char *uplo, char *trans, char *diag, integer *n, \n\tinteger *k, complex *a, integer *lda, complex *x, integer *incx, \n\tftnlen uplo_len, ftnlen trans_len, ftnlen diag_len)\n{\n    /* System generated locals */\n    integer a_dim1, a_offset, i__1, i__2, i__3, i__4, i__5;\n    complex q__1, q__2, q__3;\n\n    /* Builtin functions */\n    void r_cnjg(complex *, complex *);\n\n    /* Local variables */\n    integer i__, j, l, ix, jx, kx, info;\n    complex temp;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    integer kplus1;\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n    logical noconj, nounit;\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  CTBMV  performs one of the matrix-vector operations */\n\n/*     x := A*x,   or   x := A'*x,   or   x := conjg( A' )*x, */\n\n/*  where x is an n element vector and  A is an n by n unit, or non-unit, */\n/*  upper or lower triangular band matrix, with ( k + 1 ) diagonals. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the matrix is an upper or */\n/*           lower triangular matrix as follows: */\n\n/*              UPLO = 'U' or 'u'   A is an upper triangular matrix. */\n\n/*              UPLO = 'L' or 'l'   A is a lower triangular matrix. */\n\n/*           Unchanged on exit. */\n\n/*  TRANS  - CHARACTER*1. */\n/*           On entry, TRANS specifies the operation to be performed as */\n/*           follows: */\n\n/*              TRANS = 'N' or 'n'   x := A*x. */\n\n/*              TRANS = 'T' or 't'   x := A'*x. */\n\n/*              TRANS = 'C' or 'c'   x := conjg( A' )*x. */\n\n/*           Unchanged on exit. */\n\n/*  DIAG   - CHARACTER*1. */\n/*           On entry, DIAG specifies whether or not A is unit */\n/*           triangular as follows: */\n\n/*              DIAG = 'U' or 'u'   A is assumed to be unit triangular. */\n\n/*              DIAG = 'N' or 'n'   A is not assumed to be unit */\n/*                                  triangular. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  K      - INTEGER. */\n/*           On entry with UPLO = 'U' or 'u', K specifies the number of */\n/*           super-diagonals of the matrix A. */\n/*           On entry with UPLO = 'L' or 'l', K specifies the number of */\n/*           sub-diagonals of the matrix A. */\n/*           K must satisfy  0 .le. K. */\n/*           Unchanged on exit. */\n\n/*  A      - COMPLEX          array of DIMENSION ( LDA, n ). */\n/*           Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the upper triangular */\n/*           band part of the matrix of coefficients, supplied column by */\n/*           column, with the leading diagonal of the matrix in row */\n/*           ( k + 1 ) of the array, the first super-diagonal starting at */\n/*           position 2 in row k, and so on. The top left k by k triangle */\n/*           of the array A is not referenced. */\n/*           The following program segment will transfer an upper */\n/*           triangular band matrix from conventional full matrix storage */\n/*           to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = K + 1 - J */\n/*                    DO 10, I = MAX( 1, J - K ), J */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the lower triangular */\n/*           band part of the matrix of coefficients, supplied column by */\n/*           column, with the leading diagonal of the matrix in row 1 of */\n/*           the array, the first sub-diagonal starting at position 1 in */\n/*           row 2, and so on. The bottom right k by k triangle of the */\n/*           array A is not referenced. */\n/*           The following program segment will transfer a lower */\n/*           triangular band matrix from conventional full matrix storage */\n/*           to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = 1 - J */\n/*                    DO 10, I = J, MIN( N, J + K ) */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Note that when DIAG = 'U' or 'u' the elements of the array A */\n/*           corresponding to the diagonal elements of the matrix are not */\n/*           referenced, but are assumed to be unity. */\n/*           Unchanged on exit. */\n\n/*  LDA    - INTEGER. */\n/*           On entry, LDA specifies the first dimension of A as declared */\n/*           in the calling (sub) program. LDA must be at least */\n/*           ( k + 1 ). */\n/*           Unchanged on exit. */\n\n/*  X      - COMPLEX          array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the n */\n/*           element vector x. On exit, X is overwritten with the */\n/*           transformed vector x. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    a_dim1 = *lda;\n    a_offset = 1 + a_dim1;\n    a -= a_offset;\n    --x;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (! lsame_(trans, \"N\", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, \n\t    \"T\", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, \"C\", (ftnlen)1, (\n\t    ftnlen)1)) {\n\tinfo = 2;\n    } else if (! lsame_(diag, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(diag, \n\t    \"N\", (ftnlen)1, (ftnlen)1)) {\n\tinfo = 3;\n    } else if (*n < 0) {\n\tinfo = 4;\n    } else if (*k < 0) {\n\tinfo = 5;\n    } else if (*lda < *k + 1) {\n\tinfo = 7;\n    } else if (*incx == 0) {\n\tinfo = 9;\n    }\n    if (info != 0) {\n\txerbla_(\"CTBMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0) {\n\treturn 0;\n    }\n\n    noconj = lsame_(trans, \"T\", (ftnlen)1, (ftnlen)1);\n    nounit = lsame_(diag, \"N\", (ftnlen)1, (ftnlen)1);\n\n/*     Set up the start point in X if the increment is not unity. This */\n/*     will be  ( N - 1 )*INCX   too small for descending loops. */\n\n    if (*incx <= 0) {\n\tkx = 1 - (*n - 1) * *incx;\n    } else if (*incx != 1) {\n\tkx = 1;\n    }\n\n/*     Start the operations. In this version the elements of A are */\n/*     accessed sequentially with one pass through A. */\n\n    if (lsame_(trans, \"N\", (ftnlen)1, (ftnlen)1)) {\n\n/*         Form  x := A*x. */\n\n\tif (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\t    kplus1 = *k + 1;\n\t    if (*incx == 1) {\n\t\ti__1 = *n;\n\t\tfor (j = 1; j <= i__1; ++j) {\n\t\t    i__2 = j;\n\t\t    if (x[i__2].r != 0.f || x[i__2].i != 0.f) {\n\t\t\ti__2 = j;\n\t\t\ttemp.r = x[i__2].r, temp.i = x[i__2].i;\n\t\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\t\ti__2 = 1, i__3 = j - *k;\n\t\t\ti__4 = j - 1;\n\t\t\tfor (i__ = max(i__2,i__3); i__ <= i__4; ++i__) {\n\t\t\t    i__2 = i__;\n\t\t\t    i__3 = i__;\n\t\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t\t    q__2.r = temp.r * a[i__5].r - temp.i * a[i__5].i, \n\t\t\t\t    q__2.i = temp.r * a[i__5].i + temp.i * a[\n\t\t\t\t    i__5].r;\n\t\t\t    q__1.r = x[i__3].r + q__2.r, q__1.i = x[i__3].i + \n\t\t\t\t    q__2.i;\n\t\t\t    x[i__2].r = q__1.r, x[i__2].i = q__1.i;\n/* L10: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    i__4 = j;\n\t\t\t    i__2 = j;\n\t\t\t    i__3 = kplus1 + j * a_dim1;\n\t\t\t    q__1.r = x[i__2].r * a[i__3].r - x[i__2].i * a[\n\t\t\t\t    i__3].i, q__1.i = x[i__2].r * a[i__3].i + \n\t\t\t\t    x[i__2].i * a[i__3].r;\n\t\t\t    x[i__4].r = q__1.r, x[i__4].i = q__1.i;\n\t\t\t}\n\t\t    }\n/* L20: */\n\t\t}\n\t    } else {\n\t\tjx = kx;\n\t\ti__1 = *n;\n\t\tfor (j = 1; j <= i__1; ++j) {\n\t\t    i__4 = jx;\n\t\t    if (x[i__4].r != 0.f || x[i__4].i != 0.f) {\n\t\t\ti__4 = jx;\n\t\t\ttemp.r = x[i__4].r, temp.i = x[i__4].i;\n\t\t\tix = kx;\n\t\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\t\ti__4 = 1, i__2 = j - *k;\n\t\t\ti__3 = j - 1;\n\t\t\tfor (i__ = max(i__4,i__2); i__ <= i__3; ++i__) {\n\t\t\t    i__4 = ix;\n\t\t\t    i__2 = ix;\n\t\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t\t    q__2.r = temp.r * a[i__5].r - temp.i * a[i__5].i, \n\t\t\t\t    q__2.i = temp.r * a[i__5].i + temp.i * a[\n\t\t\t\t    i__5].r;\n\t\t\t    q__1.r = x[i__2].r + q__2.r, q__1.i = x[i__2].i + \n\t\t\t\t    q__2.i;\n\t\t\t    x[i__4].r = q__1.r, x[i__4].i = q__1.i;\n\t\t\t    ix += *incx;\n/* L30: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    i__3 = jx;\n\t\t\t    i__4 = jx;\n\t\t\t    i__2 = kplus1 + j * a_dim1;\n\t\t\t    q__1.r = x[i__4].r * a[i__2].r - x[i__4].i * a[\n\t\t\t\t    i__2].i, q__1.i = x[i__4].r * a[i__2].i + \n\t\t\t\t    x[i__4].i * a[i__2].r;\n\t\t\t    x[i__3].r = q__1.r, x[i__3].i = q__1.i;\n\t\t\t}\n\t\t    }\n\t\t    jx += *incx;\n\t\t    if (j > *k) {\n\t\t\tkx += *incx;\n\t\t    }\n/* L40: */\n\t\t}\n\t    }\n\t} else {\n\t    if (*incx == 1) {\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    i__1 = j;\n\t\t    if (x[i__1].r != 0.f || x[i__1].i != 0.f) {\n\t\t\ti__1 = j;\n\t\t\ttemp.r = x[i__1].r, temp.i = x[i__1].i;\n\t\t\tl = 1 - j;\n/* Computing MIN */\n\t\t\ti__1 = *n, i__3 = j + *k;\n\t\t\ti__4 = j + 1;\n\t\t\tfor (i__ = min(i__1,i__3); i__ >= i__4; --i__) {\n\t\t\t    i__1 = i__;\n\t\t\t    i__3 = i__;\n\t\t\t    i__2 = l + i__ + j * a_dim1;\n\t\t\t    q__2.r = temp.r * a[i__2].r - temp.i * a[i__2].i, \n\t\t\t\t    q__2.i = temp.r * a[i__2].i + temp.i * a[\n\t\t\t\t    i__2].r;\n\t\t\t    q__1.r = x[i__3].r + q__2.r, q__1.i = x[i__3].i + \n\t\t\t\t    q__2.i;\n\t\t\t    x[i__1].r = q__1.r, x[i__1].i = q__1.i;\n/* L50: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    i__4 = j;\n\t\t\t    i__1 = j;\n\t\t\t    i__3 = j * a_dim1 + 1;\n\t\t\t    q__1.r = x[i__1].r * a[i__3].r - x[i__1].i * a[\n\t\t\t\t    i__3].i, q__1.i = x[i__1].r * a[i__3].i + \n\t\t\t\t    x[i__1].i * a[i__3].r;\n\t\t\t    x[i__4].r = q__1.r, x[i__4].i = q__1.i;\n\t\t\t}\n\t\t    }\n/* L60: */\n\t\t}\n\t    } else {\n\t\tkx += (*n - 1) * *incx;\n\t\tjx = kx;\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    i__4 = jx;\n\t\t    if (x[i__4].r != 0.f || x[i__4].i != 0.f) {\n\t\t\ti__4 = jx;\n\t\t\ttemp.r = x[i__4].r, temp.i = x[i__4].i;\n\t\t\tix = kx;\n\t\t\tl = 1 - j;\n/* Computing MIN */\n\t\t\ti__4 = *n, i__1 = j + *k;\n\t\t\ti__3 = j + 1;\n\t\t\tfor (i__ = min(i__4,i__1); i__ >= i__3; --i__) {\n\t\t\t    i__4 = ix;\n\t\t\t    i__1 = ix;\n\t\t\t    i__2 = l + i__ + j * a_dim1;\n\t\t\t    q__2.r = temp.r * a[i__2].r - temp.i * a[i__2].i, \n\t\t\t\t    q__2.i = temp.r * a[i__2].i + temp.i * a[\n\t\t\t\t    i__2].r;\n\t\t\t    q__1.r = x[i__1].r + q__2.r, q__1.i = x[i__1].i + \n\t\t\t\t    q__2.i;\n\t\t\t    x[i__4].r = q__1.r, x[i__4].i = q__1.i;\n\t\t\t    ix -= *incx;\n/* L70: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    i__3 = jx;\n\t\t\t    i__4 = jx;\n\t\t\t    i__1 = j * a_dim1 + 1;\n\t\t\t    q__1.r = x[i__4].r * a[i__1].r - x[i__4].i * a[\n\t\t\t\t    i__1].i, q__1.i = x[i__4].r * a[i__1].i + \n\t\t\t\t    x[i__4].i * a[i__1].r;\n\t\t\t    x[i__3].r = q__1.r, x[i__3].i = q__1.i;\n\t\t\t}\n\t\t    }\n\t\t    jx -= *incx;\n\t\t    if (*n - j >= *k) {\n\t\t\tkx -= *incx;\n\t\t    }\n/* L80: */\n\t\t}\n\t    }\n\t}\n    } else {\n\n/*        Form  x := A'*x  or  x := conjg( A' )*x. */\n\n\tif (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\t    kplus1 = *k + 1;\n\t    if (*incx == 1) {\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    i__3 = j;\n\t\t    temp.r = x[i__3].r, temp.i = x[i__3].i;\n\t\t    l = kplus1 - j;\n\t\t    if (noconj) {\n\t\t\tif (nounit) {\n\t\t\t    i__3 = kplus1 + j * a_dim1;\n\t\t\t    q__1.r = temp.r * a[i__3].r - temp.i * a[i__3].i, \n\t\t\t\t    q__1.i = temp.r * a[i__3].i + temp.i * a[\n\t\t\t\t    i__3].r;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t}\n/* Computing MAX */\n\t\t\ti__4 = 1, i__1 = j - *k;\n\t\t\ti__3 = max(i__4,i__1);\n\t\t\tfor (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\t    i__4 = l + i__ + j * a_dim1;\n\t\t\t    i__1 = i__;\n\t\t\t    q__2.r = a[i__4].r * x[i__1].r - a[i__4].i * x[\n\t\t\t\t    i__1].i, q__2.i = a[i__4].r * x[i__1].i + \n\t\t\t\t    a[i__4].i * x[i__1].r;\n\t\t\t    q__1.r = temp.r + q__2.r, q__1.i = temp.i + \n\t\t\t\t    q__2.i;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n/* L90: */\n\t\t\t}\n\t\t    } else {\n\t\t\tif (nounit) {\n\t\t\t    r_cnjg(&q__2, &a[kplus1 + j * a_dim1]);\n\t\t\t    q__1.r = temp.r * q__2.r - temp.i * q__2.i, \n\t\t\t\t    q__1.i = temp.r * q__2.i + temp.i * \n\t\t\t\t    q__2.r;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t}\n/* Computing MAX */\n\t\t\ti__4 = 1, i__1 = j - *k;\n\t\t\ti__3 = max(i__4,i__1);\n\t\t\tfor (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\t    r_cnjg(&q__3, &a[l + i__ + j * a_dim1]);\n\t\t\t    i__4 = i__;\n\t\t\t    q__2.r = q__3.r * x[i__4].r - q__3.i * x[i__4].i, \n\t\t\t\t    q__2.i = q__3.r * x[i__4].i + q__3.i * x[\n\t\t\t\t    i__4].r;\n\t\t\t    q__1.r = temp.r + q__2.r, q__1.i = temp.i + \n\t\t\t\t    q__2.i;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n/* L100: */\n\t\t\t}\n\t\t    }\n\t\t    i__3 = j;\n\t\t    x[i__3].r = temp.r, x[i__3].i = temp.i;\n/* L110: */\n\t\t}\n\t    } else {\n\t\tkx += (*n - 1) * *incx;\n\t\tjx = kx;\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    i__3 = jx;\n\t\t    temp.r = x[i__3].r, temp.i = x[i__3].i;\n\t\t    kx -= *incx;\n\t\t    ix = kx;\n\t\t    l = kplus1 - j;\n\t\t    if (noconj) {\n\t\t\tif (nounit) {\n\t\t\t    i__3 = kplus1 + j * a_dim1;\n\t\t\t    q__1.r = temp.r * a[i__3].r - temp.i * a[i__3].i, \n\t\t\t\t    q__1.i = temp.r * a[i__3].i + temp.i * a[\n\t\t\t\t    i__3].r;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t}\n/* Computing MAX */\n\t\t\ti__4 = 1, i__1 = j - *k;\n\t\t\ti__3 = max(i__4,i__1);\n\t\t\tfor (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\t    i__4 = l + i__ + j * a_dim1;\n\t\t\t    i__1 = ix;\n\t\t\t    q__2.r = a[i__4].r * x[i__1].r - a[i__4].i * x[\n\t\t\t\t    i__1].i, q__2.i = a[i__4].r * x[i__1].i + \n\t\t\t\t    a[i__4].i * x[i__1].r;\n\t\t\t    q__1.r = temp.r + q__2.r, q__1.i = temp.i + \n\t\t\t\t    q__2.i;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t    ix -= *incx;\n/* L120: */\n\t\t\t}\n\t\t    } else {\n\t\t\tif (nounit) {\n\t\t\t    r_cnjg(&q__2, &a[kplus1 + j * a_dim1]);\n\t\t\t    q__1.r = temp.r * q__2.r - temp.i * q__2.i, \n\t\t\t\t    q__1.i = temp.r * q__2.i + temp.i * \n\t\t\t\t    q__2.r;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t}\n/* Computing MAX */\n\t\t\ti__4 = 1, i__1 = j - *k;\n\t\t\ti__3 = max(i__4,i__1);\n\t\t\tfor (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\t    r_cnjg(&q__3, &a[l + i__ + j * a_dim1]);\n\t\t\t    i__4 = ix;\n\t\t\t    q__2.r = q__3.r * x[i__4].r - q__3.i * x[i__4].i, \n\t\t\t\t    q__2.i = q__3.r * x[i__4].i + q__3.i * x[\n\t\t\t\t    i__4].r;\n\t\t\t    q__1.r = temp.r + q__2.r, q__1.i = temp.i + \n\t\t\t\t    q__2.i;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t    ix -= *incx;\n/* L130: */\n\t\t\t}\n\t\t    }\n\t\t    i__3 = jx;\n\t\t    x[i__3].r = temp.r, x[i__3].i = temp.i;\n\t\t    jx -= *incx;\n/* L140: */\n\t\t}\n\t    }\n\t} else {\n\t    if (*incx == 1) {\n\t\ti__3 = *n;\n\t\tfor (j = 1; j <= i__3; ++j) {\n\t\t    i__4 = j;\n\t\t    temp.r = x[i__4].r, temp.i = x[i__4].i;\n\t\t    l = 1 - j;\n\t\t    if (noconj) {\n\t\t\tif (nounit) {\n\t\t\t    i__4 = j * a_dim1 + 1;\n\t\t\t    q__1.r = temp.r * a[i__4].r - temp.i * a[i__4].i, \n\t\t\t\t    q__1.i = temp.r * a[i__4].i + temp.i * a[\n\t\t\t\t    i__4].r;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t}\n/* Computing MIN */\n\t\t\ti__1 = *n, i__2 = j + *k;\n\t\t\ti__4 = min(i__1,i__2);\n\t\t\tfor (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\t    i__1 = l + i__ + j * a_dim1;\n\t\t\t    i__2 = i__;\n\t\t\t    q__2.r = a[i__1].r * x[i__2].r - a[i__1].i * x[\n\t\t\t\t    i__2].i, q__2.i = a[i__1].r * x[i__2].i + \n\t\t\t\t    a[i__1].i * x[i__2].r;\n\t\t\t    q__1.r = temp.r + q__2.r, q__1.i = temp.i + \n\t\t\t\t    q__2.i;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n/* L150: */\n\t\t\t}\n\t\t    } else {\n\t\t\tif (nounit) {\n\t\t\t    r_cnjg(&q__2, &a[j * a_dim1 + 1]);\n\t\t\t    q__1.r = temp.r * q__2.r - temp.i * q__2.i, \n\t\t\t\t    q__1.i = temp.r * q__2.i + temp.i * \n\t\t\t\t    q__2.r;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t}\n/* Computing MIN */\n\t\t\ti__1 = *n, i__2 = j + *k;\n\t\t\ti__4 = min(i__1,i__2);\n\t\t\tfor (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\t    r_cnjg(&q__3, &a[l + i__ + j * a_dim1]);\n\t\t\t    i__1 = i__;\n\t\t\t    q__2.r = q__3.r * x[i__1].r - q__3.i * x[i__1].i, \n\t\t\t\t    q__2.i = q__3.r * x[i__1].i + q__3.i * x[\n\t\t\t\t    i__1].r;\n\t\t\t    q__1.r = temp.r + q__2.r, q__1.i = temp.i + \n\t\t\t\t    q__2.i;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n/* L160: */\n\t\t\t}\n\t\t    }\n\t\t    i__4 = j;\n\t\t    x[i__4].r = temp.r, x[i__4].i = temp.i;\n/* L170: */\n\t\t}\n\t    } else {\n\t\tjx = kx;\n\t\ti__3 = *n;\n\t\tfor (j = 1; j <= i__3; ++j) {\n\t\t    i__4 = jx;\n\t\t    temp.r = x[i__4].r, temp.i = x[i__4].i;\n\t\t    kx += *incx;\n\t\t    ix = kx;\n\t\t    l = 1 - j;\n\t\t    if (noconj) {\n\t\t\tif (nounit) {\n\t\t\t    i__4 = j * a_dim1 + 1;\n\t\t\t    q__1.r = temp.r * a[i__4].r - temp.i * a[i__4].i, \n\t\t\t\t    q__1.i = temp.r * a[i__4].i + temp.i * a[\n\t\t\t\t    i__4].r;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t}\n/* Computing MIN */\n\t\t\ti__1 = *n, i__2 = j + *k;\n\t\t\ti__4 = min(i__1,i__2);\n\t\t\tfor (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\t    i__1 = l + i__ + j * a_dim1;\n\t\t\t    i__2 = ix;\n\t\t\t    q__2.r = a[i__1].r * x[i__2].r - a[i__1].i * x[\n\t\t\t\t    i__2].i, q__2.i = a[i__1].r * x[i__2].i + \n\t\t\t\t    a[i__1].i * x[i__2].r;\n\t\t\t    q__1.r = temp.r + q__2.r, q__1.i = temp.i + \n\t\t\t\t    q__2.i;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t    ix += *incx;\n/* L180: */\n\t\t\t}\n\t\t    } else {\n\t\t\tif (nounit) {\n\t\t\t    r_cnjg(&q__2, &a[j * a_dim1 + 1]);\n\t\t\t    q__1.r = temp.r * q__2.r - temp.i * q__2.i, \n\t\t\t\t    q__1.i = temp.r * q__2.i + temp.i * \n\t\t\t\t    q__2.r;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t}\n/* Computing MIN */\n\t\t\ti__1 = *n, i__2 = j + *k;\n\t\t\ti__4 = min(i__1,i__2);\n\t\t\tfor (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\t    r_cnjg(&q__3, &a[l + i__ + j * a_dim1]);\n\t\t\t    i__1 = ix;\n\t\t\t    q__2.r = q__3.r * x[i__1].r - q__3.i * x[i__1].i, \n\t\t\t\t    q__2.i = q__3.r * x[i__1].i + q__3.i * x[\n\t\t\t\t    i__1].r;\n\t\t\t    q__1.r = temp.r + q__2.r, q__1.i = temp.i + \n\t\t\t\t    q__2.i;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t    ix += *incx;\n/* L190: */\n\t\t\t}\n\t\t    }\n\t\t    i__4 = jx;\n\t\t    x[i__4].r = temp.r, x[i__4].i = temp.i;\n\t\t    jx += *incx;\n/* L200: */\n\t\t}\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of CTBMV . */\n\n} /* ctbmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/d_cnjg.c",
    "content": "#include \"datatypes.h\"    \n\nvoid d_cnjg(doublecomplex *r, doublecomplex *z) {\n    r->r = z->r;\n    r->i = -(z->i);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/datatypes.h",
    "content": "/* This contains a limited subset of the typedefs exposed by f2c\n   for use by the Eigen BLAS C-only implementation.\n*/\n\n#ifndef __EIGEN_DATATYPES_H__\n#define __EIGEN_DATATYPES_H__\n\ntypedef int integer;\ntypedef unsigned int uinteger;\ntypedef float real;\ntypedef double doublereal;\ntypedef struct { real r, i; } complex;\ntypedef struct { doublereal r, i; } doublecomplex;\ntypedef int ftnlen;\ntypedef int logical;\n\n#define abs(x) ((x) >= 0 ? (x) : -(x))\n#define dabs(x) (doublereal)abs(x)\n#define min(a,b) ((a) <= (b) ? (a) : (b))\n#define max(a,b) ((a) >= (b) ? (a) : (b))\n#define dmin(a,b) (doublereal)min(a,b)\n#define dmax(a,b) (doublereal)max(a,b)\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/drotm.c",
    "content": "/* drotm.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int drotm_(integer *n, doublereal *dx, integer *incx, \n\tdoublereal *dy, integer *incy, doublereal *dparam)\n{\n    /* Initialized data */\n\n    static doublereal zero = 0.;\n    static doublereal two = 2.;\n\n    /* System generated locals */\n    integer i__1, i__2;\n\n    /* Local variables */\n    integer i__;\n    doublereal w, z__;\n    integer kx, ky;\n    doublereal dh11, dh12, dh21, dh22, dflag;\n    integer nsteps;\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*     APPLY THE MODIFIED GIVENS TRANSFORMATION, H, TO THE 2 BY N MATRIX */\n\n/*     (DX**T) , WHERE **T INDICATES TRANSPOSE. THE ELEMENTS OF DX ARE IN */\n/*     (DY**T) */\n\n/*     DX(LX+I*INCX), I = 0 TO N-1, WHERE LX = 1 IF INCX .GE. 0, ELSE */\n/*     LX = (-INCX)*N, AND SIMILARLY FOR SY USING LY AND INCY. */\n/*     WITH DPARAM(1)=DFLAG, H HAS ONE OF THE FOLLOWING FORMS.. */\n\n/*     DFLAG=-1.D0     DFLAG=0.D0        DFLAG=1.D0     DFLAG=-2.D0 */\n\n/*       (DH11  DH12)    (1.D0  DH12)    (DH11  1.D0)    (1.D0  0.D0) */\n/*     H=(          )    (          )    (          )    (          ) */\n/*       (DH21  DH22),   (DH21  1.D0),   (-1.D0 DH22),   (0.D0  1.D0). */\n/*     SEE DROTMG FOR A DESCRIPTION OF DATA STORAGE IN DPARAM. */\n\n/*  Arguments */\n/*  ========= */\n\n/*  N      (input) INTEGER */\n/*         number of elements in input vector(s) */\n\n/*  DX     (input/output) DOUBLE PRECISION array, dimension N */\n/*         double precision vector with N elements */\n\n/*  INCX   (input) INTEGER */\n/*         storage spacing between elements of DX */\n\n/*  DY     (input/output) DOUBLE PRECISION array, dimension N */\n/*         double precision vector with N elements */\n\n/*  INCY   (input) INTEGER */\n/*         storage spacing between elements of DY */\n\n/*  DPARAM (input/output)  DOUBLE PRECISION array, dimension 5 */\n/*     DPARAM(1)=DFLAG */\n/*     DPARAM(2)=DH11 */\n/*     DPARAM(3)=DH21 */\n/*     DPARAM(4)=DH12 */\n/*     DPARAM(5)=DH22 */\n\n/*  ===================================================================== */\n\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. Data statements .. */\n    /* Parameter adjustments */\n    --dparam;\n    --dy;\n    --dx;\n\n    /* Function Body */\n/*     .. */\n\n    dflag = dparam[1];\n    if (*n <= 0 || dflag + two == zero) {\n\tgoto L140;\n    }\n    if (! (*incx == *incy && *incx > 0)) {\n\tgoto L70;\n    }\n\n    nsteps = *n * *incx;\n    if (dflag < 0.) {\n\tgoto L50;\n    } else if (dflag == 0) {\n\tgoto L10;\n    } else {\n\tgoto L30;\n    }\nL10:\n    dh12 = dparam[4];\n    dh21 = dparam[3];\n    i__1 = nsteps;\n    i__2 = *incx;\n    for (i__ = 1; i__2 < 0 ? i__ >= i__1 : i__ <= i__1; i__ += i__2) {\n\tw = dx[i__];\n\tz__ = dy[i__];\n\tdx[i__] = w + z__ * dh12;\n\tdy[i__] = w * dh21 + z__;\n/* L20: */\n    }\n    goto L140;\nL30:\n    dh11 = dparam[2];\n    dh22 = dparam[5];\n    i__2 = nsteps;\n    i__1 = *incx;\n    for (i__ = 1; i__1 < 0 ? i__ >= i__2 : i__ <= i__2; i__ += i__1) {\n\tw = dx[i__];\n\tz__ = dy[i__];\n\tdx[i__] = w * dh11 + z__;\n\tdy[i__] = -w + dh22 * z__;\n/* L40: */\n    }\n    goto L140;\nL50:\n    dh11 = dparam[2];\n    dh12 = dparam[4];\n    dh21 = dparam[3];\n    dh22 = dparam[5];\n    i__1 = nsteps;\n    i__2 = *incx;\n    for (i__ = 1; i__2 < 0 ? i__ >= i__1 : i__ <= i__1; i__ += i__2) {\n\tw = dx[i__];\n\tz__ = dy[i__];\n\tdx[i__] = w * dh11 + z__ * dh12;\n\tdy[i__] = w * dh21 + z__ * dh22;\n/* L60: */\n    }\n    goto L140;\nL70:\n    kx = 1;\n    ky = 1;\n    if (*incx < 0) {\n\tkx = (1 - *n) * *incx + 1;\n    }\n    if (*incy < 0) {\n\tky = (1 - *n) * *incy + 1;\n    }\n\n    if (dflag < 0.) {\n\tgoto L120;\n    } else if (dflag == 0) {\n\tgoto L80;\n    } else {\n\tgoto L100;\n    }\nL80:\n    dh12 = dparam[4];\n    dh21 = dparam[3];\n    i__2 = *n;\n    for (i__ = 1; i__ <= i__2; ++i__) {\n\tw = dx[kx];\n\tz__ = dy[ky];\n\tdx[kx] = w + z__ * dh12;\n\tdy[ky] = w * dh21 + z__;\n\tkx += *incx;\n\tky += *incy;\n/* L90: */\n    }\n    goto L140;\nL100:\n    dh11 = dparam[2];\n    dh22 = dparam[5];\n    i__2 = *n;\n    for (i__ = 1; i__ <= i__2; ++i__) {\n\tw = dx[kx];\n\tz__ = dy[ky];\n\tdx[kx] = w * dh11 + z__;\n\tdy[ky] = -w + dh22 * z__;\n\tkx += *incx;\n\tky += *incy;\n/* L110: */\n    }\n    goto L140;\nL120:\n    dh11 = dparam[2];\n    dh12 = dparam[4];\n    dh21 = dparam[3];\n    dh22 = dparam[5];\n    i__2 = *n;\n    for (i__ = 1; i__ <= i__2; ++i__) {\n\tw = dx[kx];\n\tz__ = dy[ky];\n\tdx[kx] = w * dh11 + z__ * dh12;\n\tdy[ky] = w * dh21 + z__ * dh22;\n\tkx += *incx;\n\tky += *incy;\n/* L130: */\n    }\nL140:\n    return 0;\n} /* drotm_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/drotmg.c",
    "content": "/* drotmg.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int drotmg_(doublereal *dd1, doublereal *dd2, doublereal *\n\tdx1, doublereal *dy1, doublereal *dparam)\n{\n    /* Initialized data */\n\n    static doublereal zero = 0.;\n    static doublereal one = 1.;\n    static doublereal two = 2.;\n    static doublereal gam = 4096.;\n    static doublereal gamsq = 16777216.;\n    static doublereal rgamsq = 5.9604645e-8;\n\n    /* Format strings */\n    static char fmt_120[] = \"\";\n    static char fmt_150[] = \"\";\n    static char fmt_180[] = \"\";\n    static char fmt_210[] = \"\";\n\n    /* System generated locals */\n    doublereal d__1;\n\n    /* Local variables */\n    doublereal du, dp1, dp2, dq1, dq2, dh11, dh12, dh21, dh22;\n    integer igo;\n    doublereal dflag, dtemp;\n\n    /* Assigned format variables */\n    static char *igo_fmt;\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*     CONSTRUCT THE MODIFIED GIVENS TRANSFORMATION MATRIX H WHICH ZEROS */\n/*     THE SECOND COMPONENT OF THE 2-VECTOR  (DSQRT(DD1)*DX1,DSQRT(DD2)* */\n/*     DY2)**T. */\n/*     WITH DPARAM(1)=DFLAG, H HAS ONE OF THE FOLLOWING FORMS.. */\n\n/*     DFLAG=-1.D0     DFLAG=0.D0        DFLAG=1.D0     DFLAG=-2.D0 */\n\n/*       (DH11  DH12)    (1.D0  DH12)    (DH11  1.D0)    (1.D0  0.D0) */\n/*     H=(          )    (          )    (          )    (          ) */\n/*       (DH21  DH22),   (DH21  1.D0),   (-1.D0 DH22),   (0.D0  1.D0). */\n/*     LOCATIONS 2-4 OF DPARAM CONTAIN DH11, DH21, DH12, AND DH22 */\n/*     RESPECTIVELY. (VALUES OF 1.D0, -1.D0, OR 0.D0 IMPLIED BY THE */\n/*     VALUE OF DPARAM(1) ARE NOT STORED IN DPARAM.) */\n\n/*     THE VALUES OF GAMSQ AND RGAMSQ SET IN THE DATA STATEMENT MAY BE */\n/*     INEXACT.  THIS IS OK AS THEY ARE ONLY USED FOR TESTING THE SIZE */\n/*     OF DD1 AND DD2.  ALL ACTUAL SCALING OF DATA IS DONE USING GAM. */\n\n\n/*  Arguments */\n/*  ========= */\n\n/*  DD1    (input/output) DOUBLE PRECISION */\n\n/*  DD2    (input/output) DOUBLE PRECISION */\n\n/*  DX1    (input/output) DOUBLE PRECISION */\n\n/*  DY1    (input) DOUBLE PRECISION */\n\n/*  DPARAM (input/output)  DOUBLE PRECISION array, dimension 5 */\n/*     DPARAM(1)=DFLAG */\n/*     DPARAM(2)=DH11 */\n/*     DPARAM(3)=DH21 */\n/*     DPARAM(4)=DH12 */\n/*     DPARAM(5)=DH22 */\n\n/*  ===================================================================== */\n\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n/*     .. Data statements .. */\n\n    /* Parameter adjustments */\n    --dparam;\n\n    /* Function Body */\n/*     .. */\n    if (! (*dd1 < zero)) {\n\tgoto L10;\n    }\n/*       GO ZERO-H-D-AND-DX1.. */\n    goto L60;\nL10:\n/*     CASE-DD1-NONNEGATIVE */\n    dp2 = *dd2 * *dy1;\n    if (! (dp2 == zero)) {\n\tgoto L20;\n    }\n    dflag = -two;\n    goto L260;\n/*     REGULAR-CASE.. */\nL20:\n    dp1 = *dd1 * *dx1;\n    dq2 = dp2 * *dy1;\n    dq1 = dp1 * *dx1;\n\n    if (! (abs(dq1) > abs(dq2))) {\n\tgoto L40;\n    }\n    dh21 = -(*dy1) / *dx1;\n    dh12 = dp2 / dp1;\n\n    du = one - dh12 * dh21;\n\n    if (! (du <= zero)) {\n\tgoto L30;\n    }\n/*         GO ZERO-H-D-AND-DX1.. */\n    goto L60;\nL30:\n    dflag = zero;\n    *dd1 /= du;\n    *dd2 /= du;\n    *dx1 *= du;\n/*         GO SCALE-CHECK.. */\n    goto L100;\nL40:\n    if (! (dq2 < zero)) {\n\tgoto L50;\n    }\n/*         GO ZERO-H-D-AND-DX1.. */\n    goto L60;\nL50:\n    dflag = one;\n    dh11 = dp1 / dp2;\n    dh22 = *dx1 / *dy1;\n    du = one + dh11 * dh22;\n    dtemp = *dd2 / du;\n    *dd2 = *dd1 / du;\n    *dd1 = dtemp;\n    *dx1 = *dy1 * du;\n/*         GO SCALE-CHECK */\n    goto L100;\n/*     PROCEDURE..ZERO-H-D-AND-DX1.. */\nL60:\n    dflag = -one;\n    dh11 = zero;\n    dh12 = zero;\n    dh21 = zero;\n    dh22 = zero;\n\n    *dd1 = zero;\n    *dd2 = zero;\n    *dx1 = zero;\n/*         RETURN.. */\n    goto L220;\n/*     PROCEDURE..FIX-H.. */\nL70:\n    if (! (dflag >= zero)) {\n\tgoto L90;\n    }\n\n    if (! (dflag == zero)) {\n\tgoto L80;\n    }\n    dh11 = one;\n    dh22 = one;\n    dflag = -one;\n    goto L90;\nL80:\n    dh21 = -one;\n    dh12 = one;\n    dflag = -one;\nL90:\n    switch (igo) {\n\tcase 0: goto L120;\n\tcase 1: goto L150;\n\tcase 2: goto L180;\n\tcase 3: goto L210;\n    }\n/*     PROCEDURE..SCALE-CHECK */\nL100:\nL110:\n    if (! (*dd1 <= rgamsq)) {\n\tgoto L130;\n    }\n    if (*dd1 == zero) {\n\tgoto L160;\n    }\n    igo = 0;\n    igo_fmt = fmt_120;\n/*              FIX-H.. */\n    goto L70;\nL120:\n/* Computing 2nd power */\n    d__1 = gam;\n    *dd1 *= d__1 * d__1;\n    *dx1 /= gam;\n    dh11 /= gam;\n    dh12 /= gam;\n    goto L110;\nL130:\nL140:\n    if (! (*dd1 >= gamsq)) {\n\tgoto L160;\n    }\n    igo = 1;\n    igo_fmt = fmt_150;\n/*              FIX-H.. */\n    goto L70;\nL150:\n/* Computing 2nd power */\n    d__1 = gam;\n    *dd1 /= d__1 * d__1;\n    *dx1 *= gam;\n    dh11 *= gam;\n    dh12 *= gam;\n    goto L140;\nL160:\nL170:\n    if (! (abs(*dd2) <= rgamsq)) {\n\tgoto L190;\n    }\n    if (*dd2 == zero) {\n\tgoto L220;\n    }\n    igo = 2;\n    igo_fmt = fmt_180;\n/*              FIX-H.. */\n    goto L70;\nL180:\n/* Computing 2nd power */\n    d__1 = gam;\n    *dd2 *= d__1 * d__1;\n    dh21 /= gam;\n    dh22 /= gam;\n    goto L170;\nL190:\nL200:\n    if (! (abs(*dd2) >= gamsq)) {\n\tgoto L220;\n    }\n    igo = 3;\n    igo_fmt = fmt_210;\n/*              FIX-H.. */\n    goto L70;\nL210:\n/* Computing 2nd power */\n    d__1 = gam;\n    *dd2 /= d__1 * d__1;\n    dh21 *= gam;\n    dh22 *= gam;\n    goto L200;\nL220:\n    if (dflag < 0.) {\n\tgoto L250;\n    } else if (dflag == 0) {\n\tgoto L230;\n    } else {\n\tgoto L240;\n    }\nL230:\n    dparam[3] = dh21;\n    dparam[4] = dh12;\n    goto L260;\nL240:\n    dparam[2] = dh11;\n    dparam[5] = dh22;\n    goto L260;\nL250:\n    dparam[2] = dh11;\n    dparam[3] = dh21;\n    dparam[4] = dh12;\n    dparam[5] = dh22;\nL260:\n    dparam[1] = dflag;\n    return 0;\n} /* drotmg_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/dsbmv.c",
    "content": "/* dsbmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int dsbmv_(char *uplo, integer *n, integer *k, doublereal *\n\talpha, doublereal *a, integer *lda, doublereal *x, integer *incx, \n\tdoublereal *beta, doublereal *y, integer *incy, ftnlen uplo_len)\n{\n    /* System generated locals */\n    integer a_dim1, a_offset, i__1, i__2, i__3, i__4;\n\n    /* Local variables */\n    integer i__, j, l, ix, iy, jx, jy, kx, ky, info;\n    doublereal temp1, temp2;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    integer kplus1;\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  DSBMV  performs the matrix-vector  operation */\n\n/*     y := alpha*A*x + beta*y, */\n\n/*  where alpha and beta are scalars, x and y are n element vectors and */\n/*  A is an n by n symmetric band matrix, with k super-diagonals. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the upper or lower */\n/*           triangular part of the band matrix A is being supplied as */\n/*           follows: */\n\n/*              UPLO = 'U' or 'u'   The upper triangular part of A is */\n/*                                  being supplied. */\n\n/*              UPLO = 'L' or 'l'   The lower triangular part of A is */\n/*                                  being supplied. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  K      - INTEGER. */\n/*           On entry, K specifies the number of super-diagonals of the */\n/*           matrix A. K must satisfy  0 .le. K. */\n/*           Unchanged on exit. */\n\n/*  ALPHA  - DOUBLE PRECISION. */\n/*           On entry, ALPHA specifies the scalar alpha. */\n/*           Unchanged on exit. */\n\n/*  A      - DOUBLE PRECISION array of DIMENSION ( LDA, n ). */\n/*           Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the upper triangular */\n/*           band part of the symmetric matrix, supplied column by */\n/*           column, with the leading diagonal of the matrix in row */\n/*           ( k + 1 ) of the array, the first super-diagonal starting at */\n/*           position 2 in row k, and so on. The top left k by k triangle */\n/*           of the array A is not referenced. */\n/*           The following program segment will transfer the upper */\n/*           triangular part of a symmetric band matrix from conventional */\n/*           full matrix storage to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = K + 1 - J */\n/*                    DO 10, I = MAX( 1, J - K ), J */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the lower triangular */\n/*           band part of the symmetric matrix, supplied column by */\n/*           column, with the leading diagonal of the matrix in row 1 of */\n/*           the array, the first sub-diagonal starting at position 1 in */\n/*           row 2, and so on. The bottom right k by k triangle of the */\n/*           array A is not referenced. */\n/*           The following program segment will transfer the lower */\n/*           triangular part of a symmetric band matrix from conventional */\n/*           full matrix storage to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = 1 - J */\n/*                    DO 10, I = J, MIN( N, J + K ) */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Unchanged on exit. */\n\n/*  LDA    - INTEGER. */\n/*           On entry, LDA specifies the first dimension of A as declared */\n/*           in the calling (sub) program. LDA must be at least */\n/*           ( k + 1 ). */\n/*           Unchanged on exit. */\n\n/*  X      - DOUBLE PRECISION array of DIMENSION at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the */\n/*           vector x. */\n/*           Unchanged on exit. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  BETA   - DOUBLE PRECISION. */\n/*           On entry, BETA specifies the scalar beta. */\n/*           Unchanged on exit. */\n\n/*  Y      - DOUBLE PRECISION array of DIMENSION at least */\n/*           ( 1 + ( n - 1 )*abs( INCY ) ). */\n/*           Before entry, the incremented array Y must contain the */\n/*           vector y. On exit, Y is overwritten by the updated vector y. */\n\n/*  INCY   - INTEGER. */\n/*           On entry, INCY specifies the increment for the elements of */\n/*           Y. INCY must not be zero. */\n/*           Unchanged on exit. */\n\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    a_dim1 = *lda;\n    a_offset = 1 + a_dim1;\n    a -= a_offset;\n    --x;\n    --y;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (*n < 0) {\n\tinfo = 2;\n    } else if (*k < 0) {\n\tinfo = 3;\n    } else if (*lda < *k + 1) {\n\tinfo = 6;\n    } else if (*incx == 0) {\n\tinfo = 8;\n    } else if (*incy == 0) {\n\tinfo = 11;\n    }\n    if (info != 0) {\n\txerbla_(\"DSBMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0 || (*alpha == 0. && *beta == 1.)) {\n\treturn 0;\n    }\n\n/*     Set up the start points in  X  and  Y. */\n\n    if (*incx > 0) {\n\tkx = 1;\n    } else {\n\tkx = 1 - (*n - 1) * *incx;\n    }\n    if (*incy > 0) {\n\tky = 1;\n    } else {\n\tky = 1 - (*n - 1) * *incy;\n    }\n\n/*     Start the operations. In this version the elements of the array A */\n/*     are accessed sequentially with one pass through A. */\n\n/*     First form  y := beta*y. */\n\n    if (*beta != 1.) {\n\tif (*incy == 1) {\n\t    if (*beta == 0.) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[i__] = 0.;\n/* L10: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[i__] = *beta * y[i__];\n/* L20: */\n\t\t}\n\t    }\n\t} else {\n\t    iy = ky;\n\t    if (*beta == 0.) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[iy] = 0.;\n\t\t    iy += *incy;\n/* L30: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[iy] = *beta * y[iy];\n\t\t    iy += *incy;\n/* L40: */\n\t\t}\n\t    }\n\t}\n    }\n    if (*alpha == 0.) {\n\treturn 0;\n    }\n    if (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\n/*        Form  y  when upper triangle of A is stored. */\n\n\tkplus1 = *k + 1;\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[j];\n\t\ttemp2 = 0.;\n\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\ti__2 = 1, i__3 = j - *k;\n\t\ti__4 = j - 1;\n\t\tfor (i__ = max(i__2,i__3); i__ <= i__4; ++i__) {\n\t\t    y[i__] += temp1 * a[l + i__ + j * a_dim1];\n\t\t    temp2 += a[l + i__ + j * a_dim1] * x[i__];\n/* L50: */\n\t\t}\n\t\ty[j] = y[j] + temp1 * a[kplus1 + j * a_dim1] + *alpha * temp2;\n/* L60: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[jx];\n\t\ttemp2 = 0.;\n\t\tix = kx;\n\t\tiy = ky;\n\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\ti__4 = 1, i__2 = j - *k;\n\t\ti__3 = j - 1;\n\t\tfor (i__ = max(i__4,i__2); i__ <= i__3; ++i__) {\n\t\t    y[iy] += temp1 * a[l + i__ + j * a_dim1];\n\t\t    temp2 += a[l + i__ + j * a_dim1] * x[ix];\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n/* L70: */\n\t\t}\n\t\ty[jy] = y[jy] + temp1 * a[kplus1 + j * a_dim1] + *alpha * \n\t\t\ttemp2;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tif (j > *k) {\n\t\t    kx += *incx;\n\t\t    ky += *incy;\n\t\t}\n/* L80: */\n\t    }\n\t}\n    } else {\n\n/*        Form  y  when lower triangle of A is stored. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[j];\n\t\ttemp2 = 0.;\n\t\ty[j] += temp1 * a[j * a_dim1 + 1];\n\t\tl = 1 - j;\n/* Computing MIN */\n\t\ti__4 = *n, i__2 = j + *k;\n\t\ti__3 = min(i__4,i__2);\n\t\tfor (i__ = j + 1; i__ <= i__3; ++i__) {\n\t\t    y[i__] += temp1 * a[l + i__ + j * a_dim1];\n\t\t    temp2 += a[l + i__ + j * a_dim1] * x[i__];\n/* L90: */\n\t\t}\n\t\ty[j] += *alpha * temp2;\n/* L100: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[jx];\n\t\ttemp2 = 0.;\n\t\ty[jy] += temp1 * a[j * a_dim1 + 1];\n\t\tl = 1 - j;\n\t\tix = jx;\n\t\tiy = jy;\n/* Computing MIN */\n\t\ti__4 = *n, i__2 = j + *k;\n\t\ti__3 = min(i__4,i__2);\n\t\tfor (i__ = j + 1; i__ <= i__3; ++i__) {\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n\t\t    y[iy] += temp1 * a[l + i__ + j * a_dim1];\n\t\t    temp2 += a[l + i__ + j * a_dim1] * x[ix];\n/* L110: */\n\t\t}\n\t\ty[jy] += *alpha * temp2;\n\t\tjx += *incx;\n\t\tjy += *incy;\n/* L120: */\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of DSBMV . */\n\n} /* dsbmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/dspmv.c",
    "content": "/* dspmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int dspmv_(char *uplo, integer *n, doublereal *alpha, \n\tdoublereal *ap, doublereal *x, integer *incx, doublereal *beta, \n\tdoublereal *y, integer *incy, ftnlen uplo_len)\n{\n    /* System generated locals */\n    integer i__1, i__2;\n\n    /* Local variables */\n    integer i__, j, k, kk, ix, iy, jx, jy, kx, ky, info;\n    doublereal temp1, temp2;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  DSPMV  performs the matrix-vector operation */\n\n/*     y := alpha*A*x + beta*y, */\n\n/*  where alpha and beta are scalars, x and y are n element vectors and */\n/*  A is an n by n symmetric matrix, supplied in packed form. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the upper or lower */\n/*           triangular part of the matrix A is supplied in the packed */\n/*           array AP as follows: */\n\n/*              UPLO = 'U' or 'u'   The upper triangular part of A is */\n/*                                  supplied in AP. */\n\n/*              UPLO = 'L' or 'l'   The lower triangular part of A is */\n/*                                  supplied in AP. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  ALPHA  - DOUBLE PRECISION. */\n/*           On entry, ALPHA specifies the scalar alpha. */\n/*           Unchanged on exit. */\n\n/*  AP     - DOUBLE PRECISION array of DIMENSION at least */\n/*           ( ( n*( n + 1 ) )/2 ). */\n/*           Before entry with UPLO = 'U' or 'u', the array AP must */\n/*           contain the upper triangular part of the symmetric matrix */\n/*           packed sequentially, column by column, so that AP( 1 ) */\n/*           contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 1, 2 ) */\n/*           and a( 2, 2 ) respectively, and so on. */\n/*           Before entry with UPLO = 'L' or 'l', the array AP must */\n/*           contain the lower triangular part of the symmetric matrix */\n/*           packed sequentially, column by column, so that AP( 1 ) */\n/*           contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 2, 1 ) */\n/*           and a( 3, 1 ) respectively, and so on. */\n/*           Unchanged on exit. */\n\n/*  X      - DOUBLE PRECISION array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the n */\n/*           element vector x. */\n/*           Unchanged on exit. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  BETA   - DOUBLE PRECISION. */\n/*           On entry, BETA specifies the scalar beta. When BETA is */\n/*           supplied as zero then Y need not be set on input. */\n/*           Unchanged on exit. */\n\n/*  Y      - DOUBLE PRECISION array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCY ) ). */\n/*           Before entry, the incremented array Y must contain the n */\n/*           element vector y. On exit, Y is overwritten by the updated */\n/*           vector y. */\n\n/*  INCY   - INTEGER. */\n/*           On entry, INCY specifies the increment for the elements of */\n/*           Y. INCY must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    --y;\n    --x;\n    --ap;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (*n < 0) {\n\tinfo = 2;\n    } else if (*incx == 0) {\n\tinfo = 6;\n    } else if (*incy == 0) {\n\tinfo = 9;\n    }\n    if (info != 0) {\n\txerbla_(\"DSPMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0 || (*alpha == 0. && *beta == 1.)) {\n\treturn 0;\n    }\n\n/*     Set up the start points in  X  and  Y. */\n\n    if (*incx > 0) {\n\tkx = 1;\n    } else {\n\tkx = 1 - (*n - 1) * *incx;\n    }\n    if (*incy > 0) {\n\tky = 1;\n    } else {\n\tky = 1 - (*n - 1) * *incy;\n    }\n\n/*     Start the operations. In this version the elements of the array AP */\n/*     are accessed sequentially with one pass through AP. */\n\n/*     First form  y := beta*y. */\n\n    if (*beta != 1.) {\n\tif (*incy == 1) {\n\t    if (*beta == 0.) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[i__] = 0.;\n/* L10: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[i__] = *beta * y[i__];\n/* L20: */\n\t\t}\n\t    }\n\t} else {\n\t    iy = ky;\n\t    if (*beta == 0.) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[iy] = 0.;\n\t\t    iy += *incy;\n/* L30: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[iy] = *beta * y[iy];\n\t\t    iy += *incy;\n/* L40: */\n\t\t}\n\t    }\n\t}\n    }\n    if (*alpha == 0.) {\n\treturn 0;\n    }\n    kk = 1;\n    if (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\n/*        Form  y  when AP contains the upper triangle. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[j];\n\t\ttemp2 = 0.;\n\t\tk = kk;\n\t\ti__2 = j - 1;\n\t\tfor (i__ = 1; i__ <= i__2; ++i__) {\n\t\t    y[i__] += temp1 * ap[k];\n\t\t    temp2 += ap[k] * x[i__];\n\t\t    ++k;\n/* L50: */\n\t\t}\n\t\ty[j] = y[j] + temp1 * ap[kk + j - 1] + *alpha * temp2;\n\t\tkk += j;\n/* L60: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[jx];\n\t\ttemp2 = 0.;\n\t\tix = kx;\n\t\tiy = ky;\n\t\ti__2 = kk + j - 2;\n\t\tfor (k = kk; k <= i__2; ++k) {\n\t\t    y[iy] += temp1 * ap[k];\n\t\t    temp2 += ap[k] * x[ix];\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n/* L70: */\n\t\t}\n\t\ty[jy] = y[jy] + temp1 * ap[kk + j - 1] + *alpha * temp2;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tkk += j;\n/* L80: */\n\t    }\n\t}\n    } else {\n\n/*        Form  y  when AP contains the lower triangle. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[j];\n\t\ttemp2 = 0.;\n\t\ty[j] += temp1 * ap[kk];\n\t\tk = kk + 1;\n\t\ti__2 = *n;\n\t\tfor (i__ = j + 1; i__ <= i__2; ++i__) {\n\t\t    y[i__] += temp1 * ap[k];\n\t\t    temp2 += ap[k] * x[i__];\n\t\t    ++k;\n/* L90: */\n\t\t}\n\t\ty[j] += *alpha * temp2;\n\t\tkk += *n - j + 1;\n/* L100: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[jx];\n\t\ttemp2 = 0.;\n\t\ty[jy] += temp1 * ap[kk];\n\t\tix = jx;\n\t\tiy = jy;\n\t\ti__2 = kk + *n - j;\n\t\tfor (k = kk + 1; k <= i__2; ++k) {\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n\t\t    y[iy] += temp1 * ap[k];\n\t\t    temp2 += ap[k] * x[ix];\n/* L110: */\n\t\t}\n\t\ty[jy] += *alpha * temp2;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tkk += *n - j + 1;\n/* L120: */\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of DSPMV . */\n\n} /* dspmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/dtbmv.c",
    "content": "/* dtbmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int dtbmv_(char *uplo, char *trans, char *diag, integer *n, \n\tinteger *k, doublereal *a, integer *lda, doublereal *x, integer *incx,\n\t ftnlen uplo_len, ftnlen trans_len, ftnlen diag_len)\n{\n    /* System generated locals */\n    integer a_dim1, a_offset, i__1, i__2, i__3, i__4;\n\n    /* Local variables */\n    integer i__, j, l, ix, jx, kx, info;\n    doublereal temp;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    integer kplus1;\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n    logical nounit;\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  DTBMV  performs one of the matrix-vector operations */\n\n/*     x := A*x,   or   x := A'*x, */\n\n/*  where x is an n element vector and  A is an n by n unit, or non-unit, */\n/*  upper or lower triangular band matrix, with ( k + 1 ) diagonals. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the matrix is an upper or */\n/*           lower triangular matrix as follows: */\n\n/*              UPLO = 'U' or 'u'   A is an upper triangular matrix. */\n\n/*              UPLO = 'L' or 'l'   A is a lower triangular matrix. */\n\n/*           Unchanged on exit. */\n\n/*  TRANS  - CHARACTER*1. */\n/*           On entry, TRANS specifies the operation to be performed as */\n/*           follows: */\n\n/*              TRANS = 'N' or 'n'   x := A*x. */\n\n/*              TRANS = 'T' or 't'   x := A'*x. */\n\n/*              TRANS = 'C' or 'c'   x := A'*x. */\n\n/*           Unchanged on exit. */\n\n/*  DIAG   - CHARACTER*1. */\n/*           On entry, DIAG specifies whether or not A is unit */\n/*           triangular as follows: */\n\n/*              DIAG = 'U' or 'u'   A is assumed to be unit triangular. */\n\n/*              DIAG = 'N' or 'n'   A is not assumed to be unit */\n/*                                  triangular. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  K      - INTEGER. */\n/*           On entry with UPLO = 'U' or 'u', K specifies the number of */\n/*           super-diagonals of the matrix A. */\n/*           On entry with UPLO = 'L' or 'l', K specifies the number of */\n/*           sub-diagonals of the matrix A. */\n/*           K must satisfy  0 .le. K. */\n/*           Unchanged on exit. */\n\n/*  A      - DOUBLE PRECISION array of DIMENSION ( LDA, n ). */\n/*           Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the upper triangular */\n/*           band part of the matrix of coefficients, supplied column by */\n/*           column, with the leading diagonal of the matrix in row */\n/*           ( k + 1 ) of the array, the first super-diagonal starting at */\n/*           position 2 in row k, and so on. The top left k by k triangle */\n/*           of the array A is not referenced. */\n/*           The following program segment will transfer an upper */\n/*           triangular band matrix from conventional full matrix storage */\n/*           to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = K + 1 - J */\n/*                    DO 10, I = MAX( 1, J - K ), J */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the lower triangular */\n/*           band part of the matrix of coefficients, supplied column by */\n/*           column, with the leading diagonal of the matrix in row 1 of */\n/*           the array, the first sub-diagonal starting at position 1 in */\n/*           row 2, and so on. The bottom right k by k triangle of the */\n/*           array A is not referenced. */\n/*           The following program segment will transfer a lower */\n/*           triangular band matrix from conventional full matrix storage */\n/*           to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = 1 - J */\n/*                    DO 10, I = J, MIN( N, J + K ) */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Note that when DIAG = 'U' or 'u' the elements of the array A */\n/*           corresponding to the diagonal elements of the matrix are not */\n/*           referenced, but are assumed to be unity. */\n/*           Unchanged on exit. */\n\n/*  LDA    - INTEGER. */\n/*           On entry, LDA specifies the first dimension of A as declared */\n/*           in the calling (sub) program. LDA must be at least */\n/*           ( k + 1 ). */\n/*           Unchanged on exit. */\n\n/*  X      - DOUBLE PRECISION array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the n */\n/*           element vector x. On exit, X is overwritten with the */\n/*           transformed vector x. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    a_dim1 = *lda;\n    a_offset = 1 + a_dim1;\n    a -= a_offset;\n    --x;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (! lsame_(trans, \"N\", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, \n\t    \"T\", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, \"C\", (ftnlen)1, (\n\t    ftnlen)1)) {\n\tinfo = 2;\n    } else if (! lsame_(diag, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(diag, \n\t    \"N\", (ftnlen)1, (ftnlen)1)) {\n\tinfo = 3;\n    } else if (*n < 0) {\n\tinfo = 4;\n    } else if (*k < 0) {\n\tinfo = 5;\n    } else if (*lda < *k + 1) {\n\tinfo = 7;\n    } else if (*incx == 0) {\n\tinfo = 9;\n    }\n    if (info != 0) {\n\txerbla_(\"DTBMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0) {\n\treturn 0;\n    }\n\n    nounit = lsame_(diag, \"N\", (ftnlen)1, (ftnlen)1);\n\n/*     Set up the start point in X if the increment is not unity. This */\n/*     will be  ( N - 1 )*INCX   too small for descending loops. */\n\n    if (*incx <= 0) {\n\tkx = 1 - (*n - 1) * *incx;\n    } else if (*incx != 1) {\n\tkx = 1;\n    }\n\n/*     Start the operations. In this version the elements of A are */\n/*     accessed sequentially with one pass through A. */\n\n    if (lsame_(trans, \"N\", (ftnlen)1, (ftnlen)1)) {\n\n/*         Form  x := A*x. */\n\n\tif (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\t    kplus1 = *k + 1;\n\t    if (*incx == 1) {\n\t\ti__1 = *n;\n\t\tfor (j = 1; j <= i__1; ++j) {\n\t\t    if (x[j] != 0.) {\n\t\t\ttemp = x[j];\n\t\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\t\ti__2 = 1, i__3 = j - *k;\n\t\t\ti__4 = j - 1;\n\t\t\tfor (i__ = max(i__2,i__3); i__ <= i__4; ++i__) {\n\t\t\t    x[i__] += temp * a[l + i__ + j * a_dim1];\n/* L10: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    x[j] *= a[kplus1 + j * a_dim1];\n\t\t\t}\n\t\t    }\n/* L20: */\n\t\t}\n\t    } else {\n\t\tjx = kx;\n\t\ti__1 = *n;\n\t\tfor (j = 1; j <= i__1; ++j) {\n\t\t    if (x[jx] != 0.) {\n\t\t\ttemp = x[jx];\n\t\t\tix = kx;\n\t\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\t\ti__4 = 1, i__2 = j - *k;\n\t\t\ti__3 = j - 1;\n\t\t\tfor (i__ = max(i__4,i__2); i__ <= i__3; ++i__) {\n\t\t\t    x[ix] += temp * a[l + i__ + j * a_dim1];\n\t\t\t    ix += *incx;\n/* L30: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    x[jx] *= a[kplus1 + j * a_dim1];\n\t\t\t}\n\t\t    }\n\t\t    jx += *incx;\n\t\t    if (j > *k) {\n\t\t\tkx += *incx;\n\t\t    }\n/* L40: */\n\t\t}\n\t    }\n\t} else {\n\t    if (*incx == 1) {\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    if (x[j] != 0.) {\n\t\t\ttemp = x[j];\n\t\t\tl = 1 - j;\n/* Computing MIN */\n\t\t\ti__1 = *n, i__3 = j + *k;\n\t\t\ti__4 = j + 1;\n\t\t\tfor (i__ = min(i__1,i__3); i__ >= i__4; --i__) {\n\t\t\t    x[i__] += temp * a[l + i__ + j * a_dim1];\n/* L50: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    x[j] *= a[j * a_dim1 + 1];\n\t\t\t}\n\t\t    }\n/* L60: */\n\t\t}\n\t    } else {\n\t\tkx += (*n - 1) * *incx;\n\t\tjx = kx;\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    if (x[jx] != 0.) {\n\t\t\ttemp = x[jx];\n\t\t\tix = kx;\n\t\t\tl = 1 - j;\n/* Computing MIN */\n\t\t\ti__4 = *n, i__1 = j + *k;\n\t\t\ti__3 = j + 1;\n\t\t\tfor (i__ = min(i__4,i__1); i__ >= i__3; --i__) {\n\t\t\t    x[ix] += temp * a[l + i__ + j * a_dim1];\n\t\t\t    ix -= *incx;\n/* L70: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    x[jx] *= a[j * a_dim1 + 1];\n\t\t\t}\n\t\t    }\n\t\t    jx -= *incx;\n\t\t    if (*n - j >= *k) {\n\t\t\tkx -= *incx;\n\t\t    }\n/* L80: */\n\t\t}\n\t    }\n\t}\n    } else {\n\n/*        Form  x := A'*x. */\n\n\tif (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\t    kplus1 = *k + 1;\n\t    if (*incx == 1) {\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    temp = x[j];\n\t\t    l = kplus1 - j;\n\t\t    if (nounit) {\n\t\t\ttemp *= a[kplus1 + j * a_dim1];\n\t\t    }\n/* Computing MAX */\n\t\t    i__4 = 1, i__1 = j - *k;\n\t\t    i__3 = max(i__4,i__1);\n\t\t    for (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\ttemp += a[l + i__ + j * a_dim1] * x[i__];\n/* L90: */\n\t\t    }\n\t\t    x[j] = temp;\n/* L100: */\n\t\t}\n\t    } else {\n\t\tkx += (*n - 1) * *incx;\n\t\tjx = kx;\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    temp = x[jx];\n\t\t    kx -= *incx;\n\t\t    ix = kx;\n\t\t    l = kplus1 - j;\n\t\t    if (nounit) {\n\t\t\ttemp *= a[kplus1 + j * a_dim1];\n\t\t    }\n/* Computing MAX */\n\t\t    i__4 = 1, i__1 = j - *k;\n\t\t    i__3 = max(i__4,i__1);\n\t\t    for (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\ttemp += a[l + i__ + j * a_dim1] * x[ix];\n\t\t\tix -= *incx;\n/* L110: */\n\t\t    }\n\t\t    x[jx] = temp;\n\t\t    jx -= *incx;\n/* L120: */\n\t\t}\n\t    }\n\t} else {\n\t    if (*incx == 1) {\n\t\ti__3 = *n;\n\t\tfor (j = 1; j <= i__3; ++j) {\n\t\t    temp = x[j];\n\t\t    l = 1 - j;\n\t\t    if (nounit) {\n\t\t\ttemp *= a[j * a_dim1 + 1];\n\t\t    }\n/* Computing MIN */\n\t\t    i__1 = *n, i__2 = j + *k;\n\t\t    i__4 = min(i__1,i__2);\n\t\t    for (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\ttemp += a[l + i__ + j * a_dim1] * x[i__];\n/* L130: */\n\t\t    }\n\t\t    x[j] = temp;\n/* L140: */\n\t\t}\n\t    } else {\n\t\tjx = kx;\n\t\ti__3 = *n;\n\t\tfor (j = 1; j <= i__3; ++j) {\n\t\t    temp = x[jx];\n\t\t    kx += *incx;\n\t\t    ix = kx;\n\t\t    l = 1 - j;\n\t\t    if (nounit) {\n\t\t\ttemp *= a[j * a_dim1 + 1];\n\t\t    }\n/* Computing MIN */\n\t\t    i__1 = *n, i__2 = j + *k;\n\t\t    i__4 = min(i__1,i__2);\n\t\t    for (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\ttemp += a[l + i__ + j * a_dim1] * x[ix];\n\t\t\tix += *incx;\n/* L150: */\n\t\t    }\n\t\t    x[jx] = temp;\n\t\t    jx += *incx;\n/* L160: */\n\t\t}\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of DTBMV . */\n\n} /* dtbmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/lsame.c",
    "content": "/* lsame.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\nlogical lsame_(char *ca, char *cb, ftnlen ca_len, ftnlen cb_len)\n{\n    /* System generated locals */\n    logical ret_val;\n\n    /* Local variables */\n    integer inta, intb, zcode;\n\n\n/*  -- LAPACK auxiliary routine (version 3.1) -- */\n/*     Univ. of Tennessee, Univ. of California Berkeley and NAG Ltd.. */\n/*     November 2006 */\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  LSAME returns .TRUE. if CA is the same letter as CB regardless of */\n/*  case. */\n\n/*  Arguments */\n/*  ========= */\n\n/*  CA      (input) CHARACTER*1 */\n\n/*  CB      (input) CHARACTER*1 */\n/*          CA and CB specify the single characters to be compared. */\n\n/* ===================================================================== */\n\n/*     .. Intrinsic Functions .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n\n/*     Test if the characters are equal */\n\n    ret_val = *(unsigned char *)ca == *(unsigned char *)cb;\n    if (ret_val) {\n\treturn ret_val;\n    }\n\n/*     Now test for equivalence if both characters are alphabetic. */\n\n    zcode = 'Z';\n\n/*     Use 'Z' rather than 'A' so that ASCII can be detected on Prime */\n/*     machines, on which ICHAR returns a value with bit 8 set. */\n/*     ICHAR('A') on Prime machines returns 193 which is the same as */\n/*     ICHAR('A') on an EBCDIC machine. */\n\n    inta = *(unsigned char *)ca;\n    intb = *(unsigned char *)cb;\n\n    if (zcode == 90 || zcode == 122) {\n\n/*        ASCII is assumed - ZCODE is the ASCII code of either lower or */\n/*        upper case 'Z'. */\n\n\tif (inta >= 97 && inta <= 122) {\n\t    inta += -32;\n\t}\n\tif (intb >= 97 && intb <= 122) {\n\t    intb += -32;\n\t}\n\n    } else if (zcode == 233 || zcode == 169) {\n\n/*        EBCDIC is assumed - ZCODE is the EBCDIC code of either lower or */\n/*        upper case 'Z'. */\n\n\tif ((inta >= 129 && inta <= 137) || (inta >= 145 && inta <= 153) || \n            (inta >= 162 && inta <= 169)) {\n\t    inta += 64;\n\t}\n\tif ((intb >= 129 && intb <= 137) || (intb >= 145 && intb <= 153) || \n            (intb >= 162 && intb <= 169)) {\n\t    intb += 64;\n\t}\n\n    } else if (zcode == 218 || zcode == 250) {\n\n/*        ASCII is assumed, on Prime machines - ZCODE is the ASCII code */\n/*        plus 128 of either lower or upper case 'Z'. */\n\n\tif (inta >= 225 && inta <= 250) {\n\t    inta += -32;\n\t}\n\tif (intb >= 225 && intb <= 250) {\n\t    intb += -32;\n\t}\n    }\n    ret_val = inta == intb;\n\n/*     RETURN */\n\n/*     End of LSAME */\n\n    return ret_val;\n} /* lsame_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/r_cnjg.c",
    "content": "#include \"datatypes.h\"    \n\nvoid r_cnjg(complex *r, complex *z) {\n    r->r = z->r;\n    r->i = -(z->i);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/srotm.c",
    "content": "/* srotm.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int srotm_(integer *n, real *sx, integer *incx, real *sy, \n\tinteger *incy, real *sparam)\n{\n    /* Initialized data */\n\n    static real zero = 0.f;\n    static real two = 2.f;\n\n    /* System generated locals */\n    integer i__1, i__2;\n\n    /* Local variables */\n    integer i__;\n    real w, z__;\n    integer kx, ky;\n    real sh11, sh12, sh21, sh22, sflag;\n    integer nsteps;\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*     APPLY THE MODIFIED GIVENS TRANSFORMATION, H, TO THE 2 BY N MATRIX */\n\n/*     (SX**T) , WHERE **T INDICATES TRANSPOSE. THE ELEMENTS OF SX ARE IN */\n/*     (DX**T) */\n\n/*     SX(LX+I*INCX), I = 0 TO N-1, WHERE LX = 1 IF INCX .GE. 0, ELSE */\n/*     LX = (-INCX)*N, AND SIMILARLY FOR SY USING USING LY AND INCY. */\n/*     WITH SPARAM(1)=SFLAG, H HAS ONE OF THE FOLLOWING FORMS.. */\n\n/*     SFLAG=-1.E0     SFLAG=0.E0        SFLAG=1.E0     SFLAG=-2.E0 */\n\n/*       (SH11  SH12)    (1.E0  SH12)    (SH11  1.E0)    (1.E0  0.E0) */\n/*     H=(          )    (          )    (          )    (          ) */\n/*       (SH21  SH22),   (SH21  1.E0),   (-1.E0 SH22),   (0.E0  1.E0). */\n/*     SEE  SROTMG FOR A DESCRIPTION OF DATA STORAGE IN SPARAM. */\n\n\n/*  Arguments */\n/*  ========= */\n\n/*  N      (input) INTEGER */\n/*         number of elements in input vector(s) */\n\n/*  SX     (input/output) REAL array, dimension N */\n/*         double precision vector with N elements */\n\n/*  INCX   (input) INTEGER */\n/*         storage spacing between elements of SX */\n\n/*  SY     (input/output) REAL array, dimension N */\n/*         double precision vector with N elements */\n\n/*  INCY   (input) INTEGER */\n/*         storage spacing between elements of SY */\n\n/*  SPARAM (input/output)  REAL array, dimension 5 */\n/*     SPARAM(1)=SFLAG */\n/*     SPARAM(2)=SH11 */\n/*     SPARAM(3)=SH21 */\n/*     SPARAM(4)=SH12 */\n/*     SPARAM(5)=SH22 */\n\n/*  ===================================================================== */\n\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. Data statements .. */\n    /* Parameter adjustments */\n    --sparam;\n    --sy;\n    --sx;\n\n    /* Function Body */\n/*     .. */\n\n    sflag = sparam[1];\n    if (*n <= 0 || sflag + two == zero) {\n\tgoto L140;\n    }\n    if (! (*incx == *incy && *incx > 0)) {\n\tgoto L70;\n    }\n\n    nsteps = *n * *incx;\n    if (sflag < 0.f) {\n\tgoto L50;\n    } else if (sflag == 0) {\n\tgoto L10;\n    } else {\n\tgoto L30;\n    }\nL10:\n    sh12 = sparam[4];\n    sh21 = sparam[3];\n    i__1 = nsteps;\n    i__2 = *incx;\n    for (i__ = 1; i__2 < 0 ? i__ >= i__1 : i__ <= i__1; i__ += i__2) {\n\tw = sx[i__];\n\tz__ = sy[i__];\n\tsx[i__] = w + z__ * sh12;\n\tsy[i__] = w * sh21 + z__;\n/* L20: */\n    }\n    goto L140;\nL30:\n    sh11 = sparam[2];\n    sh22 = sparam[5];\n    i__2 = nsteps;\n    i__1 = *incx;\n    for (i__ = 1; i__1 < 0 ? i__ >= i__2 : i__ <= i__2; i__ += i__1) {\n\tw = sx[i__];\n\tz__ = sy[i__];\n\tsx[i__] = w * sh11 + z__;\n\tsy[i__] = -w + sh22 * z__;\n/* L40: */\n    }\n    goto L140;\nL50:\n    sh11 = sparam[2];\n    sh12 = sparam[4];\n    sh21 = sparam[3];\n    sh22 = sparam[5];\n    i__1 = nsteps;\n    i__2 = *incx;\n    for (i__ = 1; i__2 < 0 ? i__ >= i__1 : i__ <= i__1; i__ += i__2) {\n\tw = sx[i__];\n\tz__ = sy[i__];\n\tsx[i__] = w * sh11 + z__ * sh12;\n\tsy[i__] = w * sh21 + z__ * sh22;\n/* L60: */\n    }\n    goto L140;\nL70:\n    kx = 1;\n    ky = 1;\n    if (*incx < 0) {\n\tkx = (1 - *n) * *incx + 1;\n    }\n    if (*incy < 0) {\n\tky = (1 - *n) * *incy + 1;\n    }\n\n    if (sflag < 0.f) {\n\tgoto L120;\n    } else if (sflag == 0) {\n\tgoto L80;\n    } else {\n\tgoto L100;\n    }\nL80:\n    sh12 = sparam[4];\n    sh21 = sparam[3];\n    i__2 = *n;\n    for (i__ = 1; i__ <= i__2; ++i__) {\n\tw = sx[kx];\n\tz__ = sy[ky];\n\tsx[kx] = w + z__ * sh12;\n\tsy[ky] = w * sh21 + z__;\n\tkx += *incx;\n\tky += *incy;\n/* L90: */\n    }\n    goto L140;\nL100:\n    sh11 = sparam[2];\n    sh22 = sparam[5];\n    i__2 = *n;\n    for (i__ = 1; i__ <= i__2; ++i__) {\n\tw = sx[kx];\n\tz__ = sy[ky];\n\tsx[kx] = w * sh11 + z__;\n\tsy[ky] = -w + sh22 * z__;\n\tkx += *incx;\n\tky += *incy;\n/* L110: */\n    }\n    goto L140;\nL120:\n    sh11 = sparam[2];\n    sh12 = sparam[4];\n    sh21 = sparam[3];\n    sh22 = sparam[5];\n    i__2 = *n;\n    for (i__ = 1; i__ <= i__2; ++i__) {\n\tw = sx[kx];\n\tz__ = sy[ky];\n\tsx[kx] = w * sh11 + z__ * sh12;\n\tsy[ky] = w * sh21 + z__ * sh22;\n\tkx += *incx;\n\tky += *incy;\n/* L130: */\n    }\nL140:\n    return 0;\n} /* srotm_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/srotmg.c",
    "content": "/* srotmg.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int srotmg_(real *sd1, real *sd2, real *sx1, real *sy1, real \n\t*sparam)\n{\n    /* Initialized data */\n\n    static real zero = 0.f;\n    static real one = 1.f;\n    static real two = 2.f;\n    static real gam = 4096.f;\n    static real gamsq = 16777200.f;\n    static real rgamsq = 5.96046e-8f;\n\n    /* Format strings */\n    static char fmt_120[] = \"\";\n    static char fmt_150[] = \"\";\n    static char fmt_180[] = \"\";\n    static char fmt_210[] = \"\";\n\n    /* System generated locals */\n    real r__1;\n\n    /* Local variables */\n    real su, sp1, sp2, sq1, sq2, sh11, sh12, sh21, sh22;\n    integer igo;\n    real sflag, stemp;\n\n    /* Assigned format variables */\n    static char *igo_fmt;\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*     CONSTRUCT THE MODIFIED GIVENS TRANSFORMATION MATRIX H WHICH ZEROS */\n/*     THE SECOND COMPONENT OF THE 2-VECTOR  (SQRT(SD1)*SX1,SQRT(SD2)* */\n/*     SY2)**T. */\n/*     WITH SPARAM(1)=SFLAG, H HAS ONE OF THE FOLLOWING FORMS.. */\n\n/*     SFLAG=-1.E0     SFLAG=0.E0        SFLAG=1.E0     SFLAG=-2.E0 */\n\n/*       (SH11  SH12)    (1.E0  SH12)    (SH11  1.E0)    (1.E0  0.E0) */\n/*     H=(          )    (          )    (          )    (          ) */\n/*       (SH21  SH22),   (SH21  1.E0),   (-1.E0 SH22),   (0.E0  1.E0). */\n/*     LOCATIONS 2-4 OF SPARAM CONTAIN SH11,SH21,SH12, AND SH22 */\n/*     RESPECTIVELY. (VALUES OF 1.E0, -1.E0, OR 0.E0 IMPLIED BY THE */\n/*     VALUE OF SPARAM(1) ARE NOT STORED IN SPARAM.) */\n\n/*     THE VALUES OF GAMSQ AND RGAMSQ SET IN THE DATA STATEMENT MAY BE */\n/*     INEXACT.  THIS IS OK AS THEY ARE ONLY USED FOR TESTING THE SIZE */\n/*     OF SD1 AND SD2.  ALL ACTUAL SCALING OF DATA IS DONE USING GAM. */\n\n\n/*  Arguments */\n/*  ========= */\n\n\n/*  SD1    (input/output) REAL */\n\n/*  SD2    (input/output) REAL */\n\n/*  SX1    (input/output) REAL */\n\n/*  SY1    (input) REAL */\n\n\n/*  SPARAM (input/output)  REAL array, dimension 5 */\n/*     SPARAM(1)=SFLAG */\n/*     SPARAM(2)=SH11 */\n/*     SPARAM(3)=SH21 */\n/*     SPARAM(4)=SH12 */\n/*     SPARAM(5)=SH22 */\n\n/*  ===================================================================== */\n\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n/*     .. Data statements .. */\n\n    /* Parameter adjustments */\n    --sparam;\n\n    /* Function Body */\n/*     .. */\n    if (! (*sd1 < zero)) {\n\tgoto L10;\n    }\n/*       GO ZERO-H-D-AND-SX1.. */\n    goto L60;\nL10:\n/*     CASE-SD1-NONNEGATIVE */\n    sp2 = *sd2 * *sy1;\n    if (! (sp2 == zero)) {\n\tgoto L20;\n    }\n    sflag = -two;\n    goto L260;\n/*     REGULAR-CASE.. */\nL20:\n    sp1 = *sd1 * *sx1;\n    sq2 = sp2 * *sy1;\n    sq1 = sp1 * *sx1;\n\n    if (! (dabs(sq1) > dabs(sq2))) {\n\tgoto L40;\n    }\n    sh21 = -(*sy1) / *sx1;\n    sh12 = sp2 / sp1;\n\n    su = one - sh12 * sh21;\n\n    if (! (su <= zero)) {\n\tgoto L30;\n    }\n/*         GO ZERO-H-D-AND-SX1.. */\n    goto L60;\nL30:\n    sflag = zero;\n    *sd1 /= su;\n    *sd2 /= su;\n    *sx1 *= su;\n/*         GO SCALE-CHECK.. */\n    goto L100;\nL40:\n    if (! (sq2 < zero)) {\n\tgoto L50;\n    }\n/*         GO ZERO-H-D-AND-SX1.. */\n    goto L60;\nL50:\n    sflag = one;\n    sh11 = sp1 / sp2;\n    sh22 = *sx1 / *sy1;\n    su = one + sh11 * sh22;\n    stemp = *sd2 / su;\n    *sd2 = *sd1 / su;\n    *sd1 = stemp;\n    *sx1 = *sy1 * su;\n/*         GO SCALE-CHECK */\n    goto L100;\n/*     PROCEDURE..ZERO-H-D-AND-SX1.. */\nL60:\n    sflag = -one;\n    sh11 = zero;\n    sh12 = zero;\n    sh21 = zero;\n    sh22 = zero;\n\n    *sd1 = zero;\n    *sd2 = zero;\n    *sx1 = zero;\n/*         RETURN.. */\n    goto L220;\n/*     PROCEDURE..FIX-H.. */\nL70:\n    if (! (sflag >= zero)) {\n\tgoto L90;\n    }\n\n    if (! (sflag == zero)) {\n\tgoto L80;\n    }\n    sh11 = one;\n    sh22 = one;\n    sflag = -one;\n    goto L90;\nL80:\n    sh21 = -one;\n    sh12 = one;\n    sflag = -one;\nL90:\n    switch (igo) {\n\tcase 0: goto L120;\n\tcase 1: goto L150;\n\tcase 2: goto L180;\n\tcase 3: goto L210;\n    }\n/*     PROCEDURE..SCALE-CHECK */\nL100:\nL110:\n    if (! (*sd1 <= rgamsq)) {\n\tgoto L130;\n    }\n    if (*sd1 == zero) {\n\tgoto L160;\n    }\n    igo = 0;\n    igo_fmt = fmt_120;\n/*              FIX-H.. */\n    goto L70;\nL120:\n/* Computing 2nd power */\n    r__1 = gam;\n    *sd1 *= r__1 * r__1;\n    *sx1 /= gam;\n    sh11 /= gam;\n    sh12 /= gam;\n    goto L110;\nL130:\nL140:\n    if (! (*sd1 >= gamsq)) {\n\tgoto L160;\n    }\n    igo = 1;\n    igo_fmt = fmt_150;\n/*              FIX-H.. */\n    goto L70;\nL150:\n/* Computing 2nd power */\n    r__1 = gam;\n    *sd1 /= r__1 * r__1;\n    *sx1 *= gam;\n    sh11 *= gam;\n    sh12 *= gam;\n    goto L140;\nL160:\nL170:\n    if (! (dabs(*sd2) <= rgamsq)) {\n\tgoto L190;\n    }\n    if (*sd2 == zero) {\n\tgoto L220;\n    }\n    igo = 2;\n    igo_fmt = fmt_180;\n/*              FIX-H.. */\n    goto L70;\nL180:\n/* Computing 2nd power */\n    r__1 = gam;\n    *sd2 *= r__1 * r__1;\n    sh21 /= gam;\n    sh22 /= gam;\n    goto L170;\nL190:\nL200:\n    if (! (dabs(*sd2) >= gamsq)) {\n\tgoto L220;\n    }\n    igo = 3;\n    igo_fmt = fmt_210;\n/*              FIX-H.. */\n    goto L70;\nL210:\n/* Computing 2nd power */\n    r__1 = gam;\n    *sd2 /= r__1 * r__1;\n    sh21 *= gam;\n    sh22 *= gam;\n    goto L200;\nL220:\n    if (sflag < 0.f) {\n\tgoto L250;\n    } else if (sflag == 0) {\n\tgoto L230;\n    } else {\n\tgoto L240;\n    }\nL230:\n    sparam[3] = sh21;\n    sparam[4] = sh12;\n    goto L260;\nL240:\n    sparam[2] = sh11;\n    sparam[5] = sh22;\n    goto L260;\nL250:\n    sparam[2] = sh11;\n    sparam[3] = sh21;\n    sparam[4] = sh12;\n    sparam[5] = sh22;\nL260:\n    sparam[1] = sflag;\n    return 0;\n} /* srotmg_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/ssbmv.c",
    "content": "/* ssbmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int ssbmv_(char *uplo, integer *n, integer *k, real *alpha, \n\treal *a, integer *lda, real *x, integer *incx, real *beta, real *y, \n\tinteger *incy, ftnlen uplo_len)\n{\n    /* System generated locals */\n    integer a_dim1, a_offset, i__1, i__2, i__3, i__4;\n\n    /* Local variables */\n    integer i__, j, l, ix, iy, jx, jy, kx, ky, info;\n    real temp1, temp2;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    integer kplus1;\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  SSBMV  performs the matrix-vector  operation */\n\n/*     y := alpha*A*x + beta*y, */\n\n/*  where alpha and beta are scalars, x and y are n element vectors and */\n/*  A is an n by n symmetric band matrix, with k super-diagonals. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the upper or lower */\n/*           triangular part of the band matrix A is being supplied as */\n/*           follows: */\n\n/*              UPLO = 'U' or 'u'   The upper triangular part of A is */\n/*                                  being supplied. */\n\n/*              UPLO = 'L' or 'l'   The lower triangular part of A is */\n/*                                  being supplied. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  K      - INTEGER. */\n/*           On entry, K specifies the number of super-diagonals of the */\n/*           matrix A. K must satisfy  0 .le. K. */\n/*           Unchanged on exit. */\n\n/*  ALPHA  - REAL            . */\n/*           On entry, ALPHA specifies the scalar alpha. */\n/*           Unchanged on exit. */\n\n/*  A      - REAL             array of DIMENSION ( LDA, n ). */\n/*           Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the upper triangular */\n/*           band part of the symmetric matrix, supplied column by */\n/*           column, with the leading diagonal of the matrix in row */\n/*           ( k + 1 ) of the array, the first super-diagonal starting at */\n/*           position 2 in row k, and so on. The top left k by k triangle */\n/*           of the array A is not referenced. */\n/*           The following program segment will transfer the upper */\n/*           triangular part of a symmetric band matrix from conventional */\n/*           full matrix storage to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = K + 1 - J */\n/*                    DO 10, I = MAX( 1, J - K ), J */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the lower triangular */\n/*           band part of the symmetric matrix, supplied column by */\n/*           column, with the leading diagonal of the matrix in row 1 of */\n/*           the array, the first sub-diagonal starting at position 1 in */\n/*           row 2, and so on. The bottom right k by k triangle of the */\n/*           array A is not referenced. */\n/*           The following program segment will transfer the lower */\n/*           triangular part of a symmetric band matrix from conventional */\n/*           full matrix storage to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = 1 - J */\n/*                    DO 10, I = J, MIN( N, J + K ) */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Unchanged on exit. */\n\n/*  LDA    - INTEGER. */\n/*           On entry, LDA specifies the first dimension of A as declared */\n/*           in the calling (sub) program. LDA must be at least */\n/*           ( k + 1 ). */\n/*           Unchanged on exit. */\n\n/*  X      - REAL             array of DIMENSION at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the */\n/*           vector x. */\n/*           Unchanged on exit. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  BETA   - REAL            . */\n/*           On entry, BETA specifies the scalar beta. */\n/*           Unchanged on exit. */\n\n/*  Y      - REAL             array of DIMENSION at least */\n/*           ( 1 + ( n - 1 )*abs( INCY ) ). */\n/*           Before entry, the incremented array Y must contain the */\n/*           vector y. On exit, Y is overwritten by the updated vector y. */\n\n/*  INCY   - INTEGER. */\n/*           On entry, INCY specifies the increment for the elements of */\n/*           Y. INCY must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    a_dim1 = *lda;\n    a_offset = 1 + a_dim1;\n    a -= a_offset;\n    --x;\n    --y;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (*n < 0) {\n\tinfo = 2;\n    } else if (*k < 0) {\n\tinfo = 3;\n    } else if (*lda < *k + 1) {\n\tinfo = 6;\n    } else if (*incx == 0) {\n\tinfo = 8;\n    } else if (*incy == 0) {\n\tinfo = 11;\n    }\n    if (info != 0) {\n\txerbla_(\"SSBMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0 || (*alpha == 0.f && *beta == 1.f)) {\n\treturn 0;\n    }\n\n/*     Set up the start points in  X  and  Y. */\n\n    if (*incx > 0) {\n\tkx = 1;\n    } else {\n\tkx = 1 - (*n - 1) * *incx;\n    }\n    if (*incy > 0) {\n\tky = 1;\n    } else {\n\tky = 1 - (*n - 1) * *incy;\n    }\n\n/*     Start the operations. In this version the elements of the array A */\n/*     are accessed sequentially with one pass through A. */\n\n/*     First form  y := beta*y. */\n\n    if (*beta != 1.f) {\n\tif (*incy == 1) {\n\t    if (*beta == 0.f) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[i__] = 0.f;\n/* L10: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[i__] = *beta * y[i__];\n/* L20: */\n\t\t}\n\t    }\n\t} else {\n\t    iy = ky;\n\t    if (*beta == 0.f) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[iy] = 0.f;\n\t\t    iy += *incy;\n/* L30: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[iy] = *beta * y[iy];\n\t\t    iy += *incy;\n/* L40: */\n\t\t}\n\t    }\n\t}\n    }\n    if (*alpha == 0.f) {\n\treturn 0;\n    }\n    if (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\n/*        Form  y  when upper triangle of A is stored. */\n\n\tkplus1 = *k + 1;\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[j];\n\t\ttemp2 = 0.f;\n\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\ti__2 = 1, i__3 = j - *k;\n\t\ti__4 = j - 1;\n\t\tfor (i__ = max(i__2,i__3); i__ <= i__4; ++i__) {\n\t\t    y[i__] += temp1 * a[l + i__ + j * a_dim1];\n\t\t    temp2 += a[l + i__ + j * a_dim1] * x[i__];\n/* L50: */\n\t\t}\n\t\ty[j] = y[j] + temp1 * a[kplus1 + j * a_dim1] + *alpha * temp2;\n/* L60: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[jx];\n\t\ttemp2 = 0.f;\n\t\tix = kx;\n\t\tiy = ky;\n\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\ti__4 = 1, i__2 = j - *k;\n\t\ti__3 = j - 1;\n\t\tfor (i__ = max(i__4,i__2); i__ <= i__3; ++i__) {\n\t\t    y[iy] += temp1 * a[l + i__ + j * a_dim1];\n\t\t    temp2 += a[l + i__ + j * a_dim1] * x[ix];\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n/* L70: */\n\t\t}\n\t\ty[jy] = y[jy] + temp1 * a[kplus1 + j * a_dim1] + *alpha * \n\t\t\ttemp2;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tif (j > *k) {\n\t\t    kx += *incx;\n\t\t    ky += *incy;\n\t\t}\n/* L80: */\n\t    }\n\t}\n    } else {\n\n/*        Form  y  when lower triangle of A is stored. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[j];\n\t\ttemp2 = 0.f;\n\t\ty[j] += temp1 * a[j * a_dim1 + 1];\n\t\tl = 1 - j;\n/* Computing MIN */\n\t\ti__4 = *n, i__2 = j + *k;\n\t\ti__3 = min(i__4,i__2);\n\t\tfor (i__ = j + 1; i__ <= i__3; ++i__) {\n\t\t    y[i__] += temp1 * a[l + i__ + j * a_dim1];\n\t\t    temp2 += a[l + i__ + j * a_dim1] * x[i__];\n/* L90: */\n\t\t}\n\t\ty[j] += *alpha * temp2;\n/* L100: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[jx];\n\t\ttemp2 = 0.f;\n\t\ty[jy] += temp1 * a[j * a_dim1 + 1];\n\t\tl = 1 - j;\n\t\tix = jx;\n\t\tiy = jy;\n/* Computing MIN */\n\t\ti__4 = *n, i__2 = j + *k;\n\t\ti__3 = min(i__4,i__2);\n\t\tfor (i__ = j + 1; i__ <= i__3; ++i__) {\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n\t\t    y[iy] += temp1 * a[l + i__ + j * a_dim1];\n\t\t    temp2 += a[l + i__ + j * a_dim1] * x[ix];\n/* L110: */\n\t\t}\n\t\ty[jy] += *alpha * temp2;\n\t\tjx += *incx;\n\t\tjy += *incy;\n/* L120: */\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of SSBMV . */\n\n} /* ssbmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/sspmv.c",
    "content": "/* sspmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int sspmv_(char *uplo, integer *n, real *alpha, real *ap, \n\treal *x, integer *incx, real *beta, real *y, integer *incy, ftnlen \n\tuplo_len)\n{\n    /* System generated locals */\n    integer i__1, i__2;\n\n    /* Local variables */\n    integer i__, j, k, kk, ix, iy, jx, jy, kx, ky, info;\n    real temp1, temp2;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  SSPMV  performs the matrix-vector operation */\n\n/*     y := alpha*A*x + beta*y, */\n\n/*  where alpha and beta are scalars, x and y are n element vectors and */\n/*  A is an n by n symmetric matrix, supplied in packed form. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the upper or lower */\n/*           triangular part of the matrix A is supplied in the packed */\n/*           array AP as follows: */\n\n/*              UPLO = 'U' or 'u'   The upper triangular part of A is */\n/*                                  supplied in AP. */\n\n/*              UPLO = 'L' or 'l'   The lower triangular part of A is */\n/*                                  supplied in AP. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  ALPHA  - REAL            . */\n/*           On entry, ALPHA specifies the scalar alpha. */\n/*           Unchanged on exit. */\n\n/*  AP     - REAL             array of DIMENSION at least */\n/*           ( ( n*( n + 1 ) )/2 ). */\n/*           Before entry with UPLO = 'U' or 'u', the array AP must */\n/*           contain the upper triangular part of the symmetric matrix */\n/*           packed sequentially, column by column, so that AP( 1 ) */\n/*           contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 1, 2 ) */\n/*           and a( 2, 2 ) respectively, and so on. */\n/*           Before entry with UPLO = 'L' or 'l', the array AP must */\n/*           contain the lower triangular part of the symmetric matrix */\n/*           packed sequentially, column by column, so that AP( 1 ) */\n/*           contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 2, 1 ) */\n/*           and a( 3, 1 ) respectively, and so on. */\n/*           Unchanged on exit. */\n\n/*  X      - REAL             array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the n */\n/*           element vector x. */\n/*           Unchanged on exit. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  BETA   - REAL            . */\n/*           On entry, BETA specifies the scalar beta. When BETA is */\n/*           supplied as zero then Y need not be set on input. */\n/*           Unchanged on exit. */\n\n/*  Y      - REAL             array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCY ) ). */\n/*           Before entry, the incremented array Y must contain the n */\n/*           element vector y. On exit, Y is overwritten by the updated */\n/*           vector y. */\n\n/*  INCY   - INTEGER. */\n/*           On entry, INCY specifies the increment for the elements of */\n/*           Y. INCY must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    --y;\n    --x;\n    --ap;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (*n < 0) {\n\tinfo = 2;\n    } else if (*incx == 0) {\n\tinfo = 6;\n    } else if (*incy == 0) {\n\tinfo = 9;\n    }\n    if (info != 0) {\n\txerbla_(\"SSPMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0 || (*alpha == 0.f && *beta == 1.f)) {\n\treturn 0;\n    }\n\n/*     Set up the start points in  X  and  Y. */\n\n    if (*incx > 0) {\n\tkx = 1;\n    } else {\n\tkx = 1 - (*n - 1) * *incx;\n    }\n    if (*incy > 0) {\n\tky = 1;\n    } else {\n\tky = 1 - (*n - 1) * *incy;\n    }\n\n/*     Start the operations. In this version the elements of the array AP */\n/*     are accessed sequentially with one pass through AP. */\n\n/*     First form  y := beta*y. */\n\n    if (*beta != 1.f) {\n\tif (*incy == 1) {\n\t    if (*beta == 0.f) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[i__] = 0.f;\n/* L10: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[i__] = *beta * y[i__];\n/* L20: */\n\t\t}\n\t    }\n\t} else {\n\t    iy = ky;\n\t    if (*beta == 0.f) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[iy] = 0.f;\n\t\t    iy += *incy;\n/* L30: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[iy] = *beta * y[iy];\n\t\t    iy += *incy;\n/* L40: */\n\t\t}\n\t    }\n\t}\n    }\n    if (*alpha == 0.f) {\n\treturn 0;\n    }\n    kk = 1;\n    if (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\n/*        Form  y  when AP contains the upper triangle. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[j];\n\t\ttemp2 = 0.f;\n\t\tk = kk;\n\t\ti__2 = j - 1;\n\t\tfor (i__ = 1; i__ <= i__2; ++i__) {\n\t\t    y[i__] += temp1 * ap[k];\n\t\t    temp2 += ap[k] * x[i__];\n\t\t    ++k;\n/* L50: */\n\t\t}\n\t\ty[j] = y[j] + temp1 * ap[kk + j - 1] + *alpha * temp2;\n\t\tkk += j;\n/* L60: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[jx];\n\t\ttemp2 = 0.f;\n\t\tix = kx;\n\t\tiy = ky;\n\t\ti__2 = kk + j - 2;\n\t\tfor (k = kk; k <= i__2; ++k) {\n\t\t    y[iy] += temp1 * ap[k];\n\t\t    temp2 += ap[k] * x[ix];\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n/* L70: */\n\t\t}\n\t\ty[jy] = y[jy] + temp1 * ap[kk + j - 1] + *alpha * temp2;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tkk += j;\n/* L80: */\n\t    }\n\t}\n    } else {\n\n/*        Form  y  when AP contains the lower triangle. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[j];\n\t\ttemp2 = 0.f;\n\t\ty[j] += temp1 * ap[kk];\n\t\tk = kk + 1;\n\t\ti__2 = *n;\n\t\tfor (i__ = j + 1; i__ <= i__2; ++i__) {\n\t\t    y[i__] += temp1 * ap[k];\n\t\t    temp2 += ap[k] * x[i__];\n\t\t    ++k;\n/* L90: */\n\t\t}\n\t\ty[j] += *alpha * temp2;\n\t\tkk += *n - j + 1;\n/* L100: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[jx];\n\t\ttemp2 = 0.f;\n\t\ty[jy] += temp1 * ap[kk];\n\t\tix = jx;\n\t\tiy = jy;\n\t\ti__2 = kk + *n - j;\n\t\tfor (k = kk + 1; k <= i__2; ++k) {\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n\t\t    y[iy] += temp1 * ap[k];\n\t\t    temp2 += ap[k] * x[ix];\n/* L110: */\n\t\t}\n\t\ty[jy] += *alpha * temp2;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tkk += *n - j + 1;\n/* L120: */\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of SSPMV . */\n\n} /* sspmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/stbmv.c",
    "content": "/* stbmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int stbmv_(char *uplo, char *trans, char *diag, integer *n, \n\tinteger *k, real *a, integer *lda, real *x, integer *incx, ftnlen \n\tuplo_len, ftnlen trans_len, ftnlen diag_len)\n{\n    /* System generated locals */\n    integer a_dim1, a_offset, i__1, i__2, i__3, i__4;\n\n    /* Local variables */\n    integer i__, j, l, ix, jx, kx, info;\n    real temp;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    integer kplus1;\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n    logical nounit;\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  STBMV  performs one of the matrix-vector operations */\n\n/*     x := A*x,   or   x := A'*x, */\n\n/*  where x is an n element vector and  A is an n by n unit, or non-unit, */\n/*  upper or lower triangular band matrix, with ( k + 1 ) diagonals. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the matrix is an upper or */\n/*           lower triangular matrix as follows: */\n\n/*              UPLO = 'U' or 'u'   A is an upper triangular matrix. */\n\n/*              UPLO = 'L' or 'l'   A is a lower triangular matrix. */\n\n/*           Unchanged on exit. */\n\n/*  TRANS  - CHARACTER*1. */\n/*           On entry, TRANS specifies the operation to be performed as */\n/*           follows: */\n\n/*              TRANS = 'N' or 'n'   x := A*x. */\n\n/*              TRANS = 'T' or 't'   x := A'*x. */\n\n/*              TRANS = 'C' or 'c'   x := A'*x. */\n\n/*           Unchanged on exit. */\n\n/*  DIAG   - CHARACTER*1. */\n/*           On entry, DIAG specifies whether or not A is unit */\n/*           triangular as follows: */\n\n/*              DIAG = 'U' or 'u'   A is assumed to be unit triangular. */\n\n/*              DIAG = 'N' or 'n'   A is not assumed to be unit */\n/*                                  triangular. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  K      - INTEGER. */\n/*           On entry with UPLO = 'U' or 'u', K specifies the number of */\n/*           super-diagonals of the matrix A. */\n/*           On entry with UPLO = 'L' or 'l', K specifies the number of */\n/*           sub-diagonals of the matrix A. */\n/*           K must satisfy  0 .le. K. */\n/*           Unchanged on exit. */\n\n/*  A      - REAL             array of DIMENSION ( LDA, n ). */\n/*           Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the upper triangular */\n/*           band part of the matrix of coefficients, supplied column by */\n/*           column, with the leading diagonal of the matrix in row */\n/*           ( k + 1 ) of the array, the first super-diagonal starting at */\n/*           position 2 in row k, and so on. The top left k by k triangle */\n/*           of the array A is not referenced. */\n/*           The following program segment will transfer an upper */\n/*           triangular band matrix from conventional full matrix storage */\n/*           to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = K + 1 - J */\n/*                    DO 10, I = MAX( 1, J - K ), J */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the lower triangular */\n/*           band part of the matrix of coefficients, supplied column by */\n/*           column, with the leading diagonal of the matrix in row 1 of */\n/*           the array, the first sub-diagonal starting at position 1 in */\n/*           row 2, and so on. The bottom right k by k triangle of the */\n/*           array A is not referenced. */\n/*           The following program segment will transfer a lower */\n/*           triangular band matrix from conventional full matrix storage */\n/*           to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = 1 - J */\n/*                    DO 10, I = J, MIN( N, J + K ) */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Note that when DIAG = 'U' or 'u' the elements of the array A */\n/*           corresponding to the diagonal elements of the matrix are not */\n/*           referenced, but are assumed to be unity. */\n/*           Unchanged on exit. */\n\n/*  LDA    - INTEGER. */\n/*           On entry, LDA specifies the first dimension of A as declared */\n/*           in the calling (sub) program. LDA must be at least */\n/*           ( k + 1 ). */\n/*           Unchanged on exit. */\n\n/*  X      - REAL             array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the n */\n/*           element vector x. On exit, X is overwritten with the */\n/*           transformed vector x. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    a_dim1 = *lda;\n    a_offset = 1 + a_dim1;\n    a -= a_offset;\n    --x;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (! lsame_(trans, \"N\", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, \n\t    \"T\", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, \"C\", (ftnlen)1, (\n\t    ftnlen)1)) {\n\tinfo = 2;\n    } else if (! lsame_(diag, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(diag, \n\t    \"N\", (ftnlen)1, (ftnlen)1)) {\n\tinfo = 3;\n    } else if (*n < 0) {\n\tinfo = 4;\n    } else if (*k < 0) {\n\tinfo = 5;\n    } else if (*lda < *k + 1) {\n\tinfo = 7;\n    } else if (*incx == 0) {\n\tinfo = 9;\n    }\n    if (info != 0) {\n\txerbla_(\"STBMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0) {\n\treturn 0;\n    }\n\n    nounit = lsame_(diag, \"N\", (ftnlen)1, (ftnlen)1);\n\n/*     Set up the start point in X if the increment is not unity. This */\n/*     will be  ( N - 1 )*INCX   too small for descending loops. */\n\n    if (*incx <= 0) {\n\tkx = 1 - (*n - 1) * *incx;\n    } else if (*incx != 1) {\n\tkx = 1;\n    }\n\n/*     Start the operations. In this version the elements of A are */\n/*     accessed sequentially with one pass through A. */\n\n    if (lsame_(trans, \"N\", (ftnlen)1, (ftnlen)1)) {\n\n/*         Form  x := A*x. */\n\n\tif (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\t    kplus1 = *k + 1;\n\t    if (*incx == 1) {\n\t\ti__1 = *n;\n\t\tfor (j = 1; j <= i__1; ++j) {\n\t\t    if (x[j] != 0.f) {\n\t\t\ttemp = x[j];\n\t\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\t\ti__2 = 1, i__3 = j - *k;\n\t\t\ti__4 = j - 1;\n\t\t\tfor (i__ = max(i__2,i__3); i__ <= i__4; ++i__) {\n\t\t\t    x[i__] += temp * a[l + i__ + j * a_dim1];\n/* L10: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    x[j] *= a[kplus1 + j * a_dim1];\n\t\t\t}\n\t\t    }\n/* L20: */\n\t\t}\n\t    } else {\n\t\tjx = kx;\n\t\ti__1 = *n;\n\t\tfor (j = 1; j <= i__1; ++j) {\n\t\t    if (x[jx] != 0.f) {\n\t\t\ttemp = x[jx];\n\t\t\tix = kx;\n\t\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\t\ti__4 = 1, i__2 = j - *k;\n\t\t\ti__3 = j - 1;\n\t\t\tfor (i__ = max(i__4,i__2); i__ <= i__3; ++i__) {\n\t\t\t    x[ix] += temp * a[l + i__ + j * a_dim1];\n\t\t\t    ix += *incx;\n/* L30: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    x[jx] *= a[kplus1 + j * a_dim1];\n\t\t\t}\n\t\t    }\n\t\t    jx += *incx;\n\t\t    if (j > *k) {\n\t\t\tkx += *incx;\n\t\t    }\n/* L40: */\n\t\t}\n\t    }\n\t} else {\n\t    if (*incx == 1) {\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    if (x[j] != 0.f) {\n\t\t\ttemp = x[j];\n\t\t\tl = 1 - j;\n/* Computing MIN */\n\t\t\ti__1 = *n, i__3 = j + *k;\n\t\t\ti__4 = j + 1;\n\t\t\tfor (i__ = min(i__1,i__3); i__ >= i__4; --i__) {\n\t\t\t    x[i__] += temp * a[l + i__ + j * a_dim1];\n/* L50: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    x[j] *= a[j * a_dim1 + 1];\n\t\t\t}\n\t\t    }\n/* L60: */\n\t\t}\n\t    } else {\n\t\tkx += (*n - 1) * *incx;\n\t\tjx = kx;\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    if (x[jx] != 0.f) {\n\t\t\ttemp = x[jx];\n\t\t\tix = kx;\n\t\t\tl = 1 - j;\n/* Computing MIN */\n\t\t\ti__4 = *n, i__1 = j + *k;\n\t\t\ti__3 = j + 1;\n\t\t\tfor (i__ = min(i__4,i__1); i__ >= i__3; --i__) {\n\t\t\t    x[ix] += temp * a[l + i__ + j * a_dim1];\n\t\t\t    ix -= *incx;\n/* L70: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    x[jx] *= a[j * a_dim1 + 1];\n\t\t\t}\n\t\t    }\n\t\t    jx -= *incx;\n\t\t    if (*n - j >= *k) {\n\t\t\tkx -= *incx;\n\t\t    }\n/* L80: */\n\t\t}\n\t    }\n\t}\n    } else {\n\n/*        Form  x := A'*x. */\n\n\tif (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\t    kplus1 = *k + 1;\n\t    if (*incx == 1) {\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    temp = x[j];\n\t\t    l = kplus1 - j;\n\t\t    if (nounit) {\n\t\t\ttemp *= a[kplus1 + j * a_dim1];\n\t\t    }\n/* Computing MAX */\n\t\t    i__4 = 1, i__1 = j - *k;\n\t\t    i__3 = max(i__4,i__1);\n\t\t    for (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\ttemp += a[l + i__ + j * a_dim1] * x[i__];\n/* L90: */\n\t\t    }\n\t\t    x[j] = temp;\n/* L100: */\n\t\t}\n\t    } else {\n\t\tkx += (*n - 1) * *incx;\n\t\tjx = kx;\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    temp = x[jx];\n\t\t    kx -= *incx;\n\t\t    ix = kx;\n\t\t    l = kplus1 - j;\n\t\t    if (nounit) {\n\t\t\ttemp *= a[kplus1 + j * a_dim1];\n\t\t    }\n/* Computing MAX */\n\t\t    i__4 = 1, i__1 = j - *k;\n\t\t    i__3 = max(i__4,i__1);\n\t\t    for (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\ttemp += a[l + i__ + j * a_dim1] * x[ix];\n\t\t\tix -= *incx;\n/* L110: */\n\t\t    }\n\t\t    x[jx] = temp;\n\t\t    jx -= *incx;\n/* L120: */\n\t\t}\n\t    }\n\t} else {\n\t    if (*incx == 1) {\n\t\ti__3 = *n;\n\t\tfor (j = 1; j <= i__3; ++j) {\n\t\t    temp = x[j];\n\t\t    l = 1 - j;\n\t\t    if (nounit) {\n\t\t\ttemp *= a[j * a_dim1 + 1];\n\t\t    }\n/* Computing MIN */\n\t\t    i__1 = *n, i__2 = j + *k;\n\t\t    i__4 = min(i__1,i__2);\n\t\t    for (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\ttemp += a[l + i__ + j * a_dim1] * x[i__];\n/* L130: */\n\t\t    }\n\t\t    x[j] = temp;\n/* L140: */\n\t\t}\n\t    } else {\n\t\tjx = kx;\n\t\ti__3 = *n;\n\t\tfor (j = 1; j <= i__3; ++j) {\n\t\t    temp = x[jx];\n\t\t    kx += *incx;\n\t\t    ix = kx;\n\t\t    l = 1 - j;\n\t\t    if (nounit) {\n\t\t\ttemp *= a[j * a_dim1 + 1];\n\t\t    }\n/* Computing MIN */\n\t\t    i__1 = *n, i__2 = j + *k;\n\t\t    i__4 = min(i__1,i__2);\n\t\t    for (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\ttemp += a[l + i__ + j * a_dim1] * x[ix];\n\t\t\tix += *incx;\n/* L150: */\n\t\t    }\n\t\t    x[jx] = temp;\n\t\t    jx += *incx;\n/* L160: */\n\t\t}\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of STBMV . */\n\n} /* stbmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/zhbmv.c",
    "content": "/* zhbmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int zhbmv_(char *uplo, integer *n, integer *k, doublecomplex \n\t*alpha, doublecomplex *a, integer *lda, doublecomplex *x, integer *\n\tincx, doublecomplex *beta, doublecomplex *y, integer *incy, ftnlen \n\tuplo_len)\n{\n    /* System generated locals */\n    integer a_dim1, a_offset, i__1, i__2, i__3, i__4, i__5;\n    doublereal d__1;\n    doublecomplex z__1, z__2, z__3, z__4;\n\n    /* Builtin functions */\n    void d_cnjg(doublecomplex *, doublecomplex *);\n\n    /* Local variables */\n    integer i__, j, l, ix, iy, jx, jy, kx, ky, info;\n    doublecomplex temp1, temp2;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    integer kplus1;\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  ZHBMV  performs the matrix-vector  operation */\n\n/*     y := alpha*A*x + beta*y, */\n\n/*  where alpha and beta are scalars, x and y are n element vectors and */\n/*  A is an n by n hermitian band matrix, with k super-diagonals. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the upper or lower */\n/*           triangular part of the band matrix A is being supplied as */\n/*           follows: */\n\n/*              UPLO = 'U' or 'u'   The upper triangular part of A is */\n/*                                  being supplied. */\n\n/*              UPLO = 'L' or 'l'   The lower triangular part of A is */\n/*                                  being supplied. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  K      - INTEGER. */\n/*           On entry, K specifies the number of super-diagonals of the */\n/*           matrix A. K must satisfy  0 .le. K. */\n/*           Unchanged on exit. */\n\n/*  ALPHA  - COMPLEX*16      . */\n/*           On entry, ALPHA specifies the scalar alpha. */\n/*           Unchanged on exit. */\n\n/*  A      - COMPLEX*16       array of DIMENSION ( LDA, n ). */\n/*           Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the upper triangular */\n/*           band part of the hermitian matrix, supplied column by */\n/*           column, with the leading diagonal of the matrix in row */\n/*           ( k + 1 ) of the array, the first super-diagonal starting at */\n/*           position 2 in row k, and so on. The top left k by k triangle */\n/*           of the array A is not referenced. */\n/*           The following program segment will transfer the upper */\n/*           triangular part of a hermitian band matrix from conventional */\n/*           full matrix storage to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = K + 1 - J */\n/*                    DO 10, I = MAX( 1, J - K ), J */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the lower triangular */\n/*           band part of the hermitian matrix, supplied column by */\n/*           column, with the leading diagonal of the matrix in row 1 of */\n/*           the array, the first sub-diagonal starting at position 1 in */\n/*           row 2, and so on. The bottom right k by k triangle of the */\n/*           array A is not referenced. */\n/*           The following program segment will transfer the lower */\n/*           triangular part of a hermitian band matrix from conventional */\n/*           full matrix storage to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = 1 - J */\n/*                    DO 10, I = J, MIN( N, J + K ) */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Note that the imaginary parts of the diagonal elements need */\n/*           not be set and are assumed to be zero. */\n/*           Unchanged on exit. */\n\n/*  LDA    - INTEGER. */\n/*           On entry, LDA specifies the first dimension of A as declared */\n/*           in the calling (sub) program. LDA must be at least */\n/*           ( k + 1 ). */\n/*           Unchanged on exit. */\n\n/*  X      - COMPLEX*16       array of DIMENSION at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the */\n/*           vector x. */\n/*           Unchanged on exit. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  BETA   - COMPLEX*16      . */\n/*           On entry, BETA specifies the scalar beta. */\n/*           Unchanged on exit. */\n\n/*  Y      - COMPLEX*16       array of DIMENSION at least */\n/*           ( 1 + ( n - 1 )*abs( INCY ) ). */\n/*           Before entry, the incremented array Y must contain the */\n/*           vector y. On exit, Y is overwritten by the updated vector y. */\n\n/*  INCY   - INTEGER. */\n/*           On entry, INCY specifies the increment for the elements of */\n/*           Y. INCY must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    a_dim1 = *lda;\n    a_offset = 1 + a_dim1;\n    a -= a_offset;\n    --x;\n    --y;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (*n < 0) {\n\tinfo = 2;\n    } else if (*k < 0) {\n\tinfo = 3;\n    } else if (*lda < *k + 1) {\n\tinfo = 6;\n    } else if (*incx == 0) {\n\tinfo = 8;\n    } else if (*incy == 0) {\n\tinfo = 11;\n    }\n    if (info != 0) {\n\txerbla_(\"ZHBMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0 || (alpha->r == 0. && alpha->i == 0. && (beta->r == 1. && \n                                                         beta->i == 0.))) {\n\treturn 0;\n    }\n\n/*     Set up the start points in  X  and  Y. */\n\n    if (*incx > 0) {\n\tkx = 1;\n    } else {\n\tkx = 1 - (*n - 1) * *incx;\n    }\n    if (*incy > 0) {\n\tky = 1;\n    } else {\n\tky = 1 - (*n - 1) * *incy;\n    }\n\n/*     Start the operations. In this version the elements of the array A */\n/*     are accessed sequentially with one pass through A. */\n\n/*     First form  y := beta*y. */\n\n    if (beta->r != 1. || beta->i != 0.) {\n\tif (*incy == 1) {\n\t    if (beta->r == 0. && beta->i == 0.) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = i__;\n\t\t    y[i__2].r = 0., y[i__2].i = 0.;\n/* L10: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = i__;\n\t\t    i__3 = i__;\n\t\t    z__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, \n\t\t\t    z__1.i = beta->r * y[i__3].i + beta->i * y[i__3]\n\t\t\t    .r;\n\t\t    y[i__2].r = z__1.r, y[i__2].i = z__1.i;\n/* L20: */\n\t\t}\n\t    }\n\t} else {\n\t    iy = ky;\n\t    if (beta->r == 0. && beta->i == 0.) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = iy;\n\t\t    y[i__2].r = 0., y[i__2].i = 0.;\n\t\t    iy += *incy;\n/* L30: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = iy;\n\t\t    i__3 = iy;\n\t\t    z__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, \n\t\t\t    z__1.i = beta->r * y[i__3].i + beta->i * y[i__3]\n\t\t\t    .r;\n\t\t    y[i__2].r = z__1.r, y[i__2].i = z__1.i;\n\t\t    iy += *incy;\n/* L40: */\n\t\t}\n\t    }\n\t}\n    }\n    if (alpha->r == 0. && alpha->i == 0.) {\n\treturn 0;\n    }\n    if (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\n/*        Form  y  when upper triangle of A is stored. */\n\n\tkplus1 = *k + 1;\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__2 = j;\n\t\tz__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, z__1.i =\n\t\t\t alpha->r * x[i__2].i + alpha->i * x[i__2].r;\n\t\ttemp1.r = z__1.r, temp1.i = z__1.i;\n\t\ttemp2.r = 0., temp2.i = 0.;\n\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\ti__2 = 1, i__3 = j - *k;\n\t\ti__4 = j - 1;\n\t\tfor (i__ = max(i__2,i__3); i__ <= i__4; ++i__) {\n\t\t    i__2 = i__;\n\t\t    i__3 = i__;\n\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t    z__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, \n\t\t\t    z__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5]\n\t\t\t    .r;\n\t\t    z__1.r = y[i__3].r + z__2.r, z__1.i = y[i__3].i + z__2.i;\n\t\t    y[i__2].r = z__1.r, y[i__2].i = z__1.i;\n\t\t    d_cnjg(&z__3, &a[l + i__ + j * a_dim1]);\n\t\t    i__2 = i__;\n\t\t    z__2.r = z__3.r * x[i__2].r - z__3.i * x[i__2].i, z__2.i =\n\t\t\t     z__3.r * x[i__2].i + z__3.i * x[i__2].r;\n\t\t    z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i;\n\t\t    temp2.r = z__1.r, temp2.i = z__1.i;\n/* L50: */\n\t\t}\n\t\ti__4 = j;\n\t\ti__2 = j;\n\t\ti__3 = kplus1 + j * a_dim1;\n\t\td__1 = a[i__3].r;\n\t\tz__3.r = d__1 * temp1.r, z__3.i = d__1 * temp1.i;\n\t\tz__2.r = y[i__2].r + z__3.r, z__2.i = y[i__2].i + z__3.i;\n\t\tz__4.r = alpha->r * temp2.r - alpha->i * temp2.i, z__4.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tz__1.r = z__2.r + z__4.r, z__1.i = z__2.i + z__4.i;\n\t\ty[i__4].r = z__1.r, y[i__4].i = z__1.i;\n/* L60: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__4 = jx;\n\t\tz__1.r = alpha->r * x[i__4].r - alpha->i * x[i__4].i, z__1.i =\n\t\t\t alpha->r * x[i__4].i + alpha->i * x[i__4].r;\n\t\ttemp1.r = z__1.r, temp1.i = z__1.i;\n\t\ttemp2.r = 0., temp2.i = 0.;\n\t\tix = kx;\n\t\tiy = ky;\n\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\ti__4 = 1, i__2 = j - *k;\n\t\ti__3 = j - 1;\n\t\tfor (i__ = max(i__4,i__2); i__ <= i__3; ++i__) {\n\t\t    i__4 = iy;\n\t\t    i__2 = iy;\n\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t    z__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, \n\t\t\t    z__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5]\n\t\t\t    .r;\n\t\t    z__1.r = y[i__2].r + z__2.r, z__1.i = y[i__2].i + z__2.i;\n\t\t    y[i__4].r = z__1.r, y[i__4].i = z__1.i;\n\t\t    d_cnjg(&z__3, &a[l + i__ + j * a_dim1]);\n\t\t    i__4 = ix;\n\t\t    z__2.r = z__3.r * x[i__4].r - z__3.i * x[i__4].i, z__2.i =\n\t\t\t     z__3.r * x[i__4].i + z__3.i * x[i__4].r;\n\t\t    z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i;\n\t\t    temp2.r = z__1.r, temp2.i = z__1.i;\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n/* L70: */\n\t\t}\n\t\ti__3 = jy;\n\t\ti__4 = jy;\n\t\ti__2 = kplus1 + j * a_dim1;\n\t\td__1 = a[i__2].r;\n\t\tz__3.r = d__1 * temp1.r, z__3.i = d__1 * temp1.i;\n\t\tz__2.r = y[i__4].r + z__3.r, z__2.i = y[i__4].i + z__3.i;\n\t\tz__4.r = alpha->r * temp2.r - alpha->i * temp2.i, z__4.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tz__1.r = z__2.r + z__4.r, z__1.i = z__2.i + z__4.i;\n\t\ty[i__3].r = z__1.r, y[i__3].i = z__1.i;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tif (j > *k) {\n\t\t    kx += *incx;\n\t\t    ky += *incy;\n\t\t}\n/* L80: */\n\t    }\n\t}\n    } else {\n\n/*        Form  y  when lower triangle of A is stored. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__3 = j;\n\t\tz__1.r = alpha->r * x[i__3].r - alpha->i * x[i__3].i, z__1.i =\n\t\t\t alpha->r * x[i__3].i + alpha->i * x[i__3].r;\n\t\ttemp1.r = z__1.r, temp1.i = z__1.i;\n\t\ttemp2.r = 0., temp2.i = 0.;\n\t\ti__3 = j;\n\t\ti__4 = j;\n\t\ti__2 = j * a_dim1 + 1;\n\t\td__1 = a[i__2].r;\n\t\tz__2.r = d__1 * temp1.r, z__2.i = d__1 * temp1.i;\n\t\tz__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i;\n\t\ty[i__3].r = z__1.r, y[i__3].i = z__1.i;\n\t\tl = 1 - j;\n/* Computing MIN */\n\t\ti__4 = *n, i__2 = j + *k;\n\t\ti__3 = min(i__4,i__2);\n\t\tfor (i__ = j + 1; i__ <= i__3; ++i__) {\n\t\t    i__4 = i__;\n\t\t    i__2 = i__;\n\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t    z__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, \n\t\t\t    z__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5]\n\t\t\t    .r;\n\t\t    z__1.r = y[i__2].r + z__2.r, z__1.i = y[i__2].i + z__2.i;\n\t\t    y[i__4].r = z__1.r, y[i__4].i = z__1.i;\n\t\t    d_cnjg(&z__3, &a[l + i__ + j * a_dim1]);\n\t\t    i__4 = i__;\n\t\t    z__2.r = z__3.r * x[i__4].r - z__3.i * x[i__4].i, z__2.i =\n\t\t\t     z__3.r * x[i__4].i + z__3.i * x[i__4].r;\n\t\t    z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i;\n\t\t    temp2.r = z__1.r, temp2.i = z__1.i;\n/* L90: */\n\t\t}\n\t\ti__3 = j;\n\t\ti__4 = j;\n\t\tz__2.r = alpha->r * temp2.r - alpha->i * temp2.i, z__2.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tz__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i;\n\t\ty[i__3].r = z__1.r, y[i__3].i = z__1.i;\n/* L100: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__3 = jx;\n\t\tz__1.r = alpha->r * x[i__3].r - alpha->i * x[i__3].i, z__1.i =\n\t\t\t alpha->r * x[i__3].i + alpha->i * x[i__3].r;\n\t\ttemp1.r = z__1.r, temp1.i = z__1.i;\n\t\ttemp2.r = 0., temp2.i = 0.;\n\t\ti__3 = jy;\n\t\ti__4 = jy;\n\t\ti__2 = j * a_dim1 + 1;\n\t\td__1 = a[i__2].r;\n\t\tz__2.r = d__1 * temp1.r, z__2.i = d__1 * temp1.i;\n\t\tz__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i;\n\t\ty[i__3].r = z__1.r, y[i__3].i = z__1.i;\n\t\tl = 1 - j;\n\t\tix = jx;\n\t\tiy = jy;\n/* Computing MIN */\n\t\ti__4 = *n, i__2 = j + *k;\n\t\ti__3 = min(i__4,i__2);\n\t\tfor (i__ = j + 1; i__ <= i__3; ++i__) {\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n\t\t    i__4 = iy;\n\t\t    i__2 = iy;\n\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t    z__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, \n\t\t\t    z__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5]\n\t\t\t    .r;\n\t\t    z__1.r = y[i__2].r + z__2.r, z__1.i = y[i__2].i + z__2.i;\n\t\t    y[i__4].r = z__1.r, y[i__4].i = z__1.i;\n\t\t    d_cnjg(&z__3, &a[l + i__ + j * a_dim1]);\n\t\t    i__4 = ix;\n\t\t    z__2.r = z__3.r * x[i__4].r - z__3.i * x[i__4].i, z__2.i =\n\t\t\t     z__3.r * x[i__4].i + z__3.i * x[i__4].r;\n\t\t    z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i;\n\t\t    temp2.r = z__1.r, temp2.i = z__1.i;\n/* L110: */\n\t\t}\n\t\ti__3 = jy;\n\t\ti__4 = jy;\n\t\tz__2.r = alpha->r * temp2.r - alpha->i * temp2.i, z__2.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tz__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i;\n\t\ty[i__3].r = z__1.r, y[i__3].i = z__1.i;\n\t\tjx += *incx;\n\t\tjy += *incy;\n/* L120: */\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of ZHBMV . */\n\n} /* zhbmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/zhpmv.c",
    "content": "/* zhpmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int zhpmv_(char *uplo, integer *n, doublecomplex *alpha, \n\tdoublecomplex *ap, doublecomplex *x, integer *incx, doublecomplex *\n\tbeta, doublecomplex *y, integer *incy, ftnlen uplo_len)\n{\n    /* System generated locals */\n    integer i__1, i__2, i__3, i__4, i__5;\n    doublereal d__1;\n    doublecomplex z__1, z__2, z__3, z__4;\n\n    /* Builtin functions */\n    void d_cnjg(doublecomplex *, doublecomplex *);\n\n    /* Local variables */\n    integer i__, j, k, kk, ix, iy, jx, jy, kx, ky, info;\n    doublecomplex temp1, temp2;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  ZHPMV  performs the matrix-vector operation */\n\n/*     y := alpha*A*x + beta*y, */\n\n/*  where alpha and beta are scalars, x and y are n element vectors and */\n/*  A is an n by n hermitian matrix, supplied in packed form. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the upper or lower */\n/*           triangular part of the matrix A is supplied in the packed */\n/*           array AP as follows: */\n\n/*              UPLO = 'U' or 'u'   The upper triangular part of A is */\n/*                                  supplied in AP. */\n\n/*              UPLO = 'L' or 'l'   The lower triangular part of A is */\n/*                                  supplied in AP. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  ALPHA  - COMPLEX*16      . */\n/*           On entry, ALPHA specifies the scalar alpha. */\n/*           Unchanged on exit. */\n\n/*  AP     - COMPLEX*16       array of DIMENSION at least */\n/*           ( ( n*( n + 1 ) )/2 ). */\n/*           Before entry with UPLO = 'U' or 'u', the array AP must */\n/*           contain the upper triangular part of the hermitian matrix */\n/*           packed sequentially, column by column, so that AP( 1 ) */\n/*           contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 1, 2 ) */\n/*           and a( 2, 2 ) respectively, and so on. */\n/*           Before entry with UPLO = 'L' or 'l', the array AP must */\n/*           contain the lower triangular part of the hermitian matrix */\n/*           packed sequentially, column by column, so that AP( 1 ) */\n/*           contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 2, 1 ) */\n/*           and a( 3, 1 ) respectively, and so on. */\n/*           Note that the imaginary parts of the diagonal elements need */\n/*           not be set and are assumed to be zero. */\n/*           Unchanged on exit. */\n\n/*  X      - COMPLEX*16       array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the n */\n/*           element vector x. */\n/*           Unchanged on exit. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  BETA   - COMPLEX*16      . */\n/*           On entry, BETA specifies the scalar beta. When BETA is */\n/*           supplied as zero then Y need not be set on input. */\n/*           Unchanged on exit. */\n\n/*  Y      - COMPLEX*16       array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCY ) ). */\n/*           Before entry, the incremented array Y must contain the n */\n/*           element vector y. On exit, Y is overwritten by the updated */\n/*           vector y. */\n\n/*  INCY   - INTEGER. */\n/*           On entry, INCY specifies the increment for the elements of */\n/*           Y. INCY must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    --y;\n    --x;\n    --ap;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (*n < 0) {\n\tinfo = 2;\n    } else if (*incx == 0) {\n\tinfo = 6;\n    } else if (*incy == 0) {\n\tinfo = 9;\n    }\n    if (info != 0) {\n\txerbla_(\"ZHPMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0 || (alpha->r == 0. && alpha->i == 0. && (beta->r == 1. && \n                                                         beta->i == 0.))) {\n\treturn 0;\n    }\n\n/*     Set up the start points in  X  and  Y. */\n\n    if (*incx > 0) {\n\tkx = 1;\n    } else {\n\tkx = 1 - (*n - 1) * *incx;\n    }\n    if (*incy > 0) {\n\tky = 1;\n    } else {\n\tky = 1 - (*n - 1) * *incy;\n    }\n\n/*     Start the operations. In this version the elements of the array AP */\n/*     are accessed sequentially with one pass through AP. */\n\n/*     First form  y := beta*y. */\n\n    if (beta->r != 1. || beta->i != 0.) {\n\tif (*incy == 1) {\n\t    if (beta->r == 0. && beta->i == 0.) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = i__;\n\t\t    y[i__2].r = 0., y[i__2].i = 0.;\n/* L10: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = i__;\n\t\t    i__3 = i__;\n\t\t    z__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, \n\t\t\t    z__1.i = beta->r * y[i__3].i + beta->i * y[i__3]\n\t\t\t    .r;\n\t\t    y[i__2].r = z__1.r, y[i__2].i = z__1.i;\n/* L20: */\n\t\t}\n\t    }\n\t} else {\n\t    iy = ky;\n\t    if (beta->r == 0. && beta->i == 0.) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = iy;\n\t\t    y[i__2].r = 0., y[i__2].i = 0.;\n\t\t    iy += *incy;\n/* L30: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = iy;\n\t\t    i__3 = iy;\n\t\t    z__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, \n\t\t\t    z__1.i = beta->r * y[i__3].i + beta->i * y[i__3]\n\t\t\t    .r;\n\t\t    y[i__2].r = z__1.r, y[i__2].i = z__1.i;\n\t\t    iy += *incy;\n/* L40: */\n\t\t}\n\t    }\n\t}\n    }\n    if (alpha->r == 0. && alpha->i == 0.) {\n\treturn 0;\n    }\n    kk = 1;\n    if (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\n/*        Form  y  when AP contains the upper triangle. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__2 = j;\n\t\tz__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, z__1.i =\n\t\t\t alpha->r * x[i__2].i + alpha->i * x[i__2].r;\n\t\ttemp1.r = z__1.r, temp1.i = z__1.i;\n\t\ttemp2.r = 0., temp2.i = 0.;\n\t\tk = kk;\n\t\ti__2 = j - 1;\n\t\tfor (i__ = 1; i__ <= i__2; ++i__) {\n\t\t    i__3 = i__;\n\t\t    i__4 = i__;\n\t\t    i__5 = k;\n\t\t    z__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, \n\t\t\t    z__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5]\n\t\t\t    .r;\n\t\t    z__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i;\n\t\t    y[i__3].r = z__1.r, y[i__3].i = z__1.i;\n\t\t    d_cnjg(&z__3, &ap[k]);\n\t\t    i__3 = i__;\n\t\t    z__2.r = z__3.r * x[i__3].r - z__3.i * x[i__3].i, z__2.i =\n\t\t\t     z__3.r * x[i__3].i + z__3.i * x[i__3].r;\n\t\t    z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i;\n\t\t    temp2.r = z__1.r, temp2.i = z__1.i;\n\t\t    ++k;\n/* L50: */\n\t\t}\n\t\ti__2 = j;\n\t\ti__3 = j;\n\t\ti__4 = kk + j - 1;\n\t\td__1 = ap[i__4].r;\n\t\tz__3.r = d__1 * temp1.r, z__3.i = d__1 * temp1.i;\n\t\tz__2.r = y[i__3].r + z__3.r, z__2.i = y[i__3].i + z__3.i;\n\t\tz__4.r = alpha->r * temp2.r - alpha->i * temp2.i, z__4.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tz__1.r = z__2.r + z__4.r, z__1.i = z__2.i + z__4.i;\n\t\ty[i__2].r = z__1.r, y[i__2].i = z__1.i;\n\t\tkk += j;\n/* L60: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__2 = jx;\n\t\tz__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, z__1.i =\n\t\t\t alpha->r * x[i__2].i + alpha->i * x[i__2].r;\n\t\ttemp1.r = z__1.r, temp1.i = z__1.i;\n\t\ttemp2.r = 0., temp2.i = 0.;\n\t\tix = kx;\n\t\tiy = ky;\n\t\ti__2 = kk + j - 2;\n\t\tfor (k = kk; k <= i__2; ++k) {\n\t\t    i__3 = iy;\n\t\t    i__4 = iy;\n\t\t    i__5 = k;\n\t\t    z__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, \n\t\t\t    z__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5]\n\t\t\t    .r;\n\t\t    z__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i;\n\t\t    y[i__3].r = z__1.r, y[i__3].i = z__1.i;\n\t\t    d_cnjg(&z__3, &ap[k]);\n\t\t    i__3 = ix;\n\t\t    z__2.r = z__3.r * x[i__3].r - z__3.i * x[i__3].i, z__2.i =\n\t\t\t     z__3.r * x[i__3].i + z__3.i * x[i__3].r;\n\t\t    z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i;\n\t\t    temp2.r = z__1.r, temp2.i = z__1.i;\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n/* L70: */\n\t\t}\n\t\ti__2 = jy;\n\t\ti__3 = jy;\n\t\ti__4 = kk + j - 1;\n\t\td__1 = ap[i__4].r;\n\t\tz__3.r = d__1 * temp1.r, z__3.i = d__1 * temp1.i;\n\t\tz__2.r = y[i__3].r + z__3.r, z__2.i = y[i__3].i + z__3.i;\n\t\tz__4.r = alpha->r * temp2.r - alpha->i * temp2.i, z__4.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tz__1.r = z__2.r + z__4.r, z__1.i = z__2.i + z__4.i;\n\t\ty[i__2].r = z__1.r, y[i__2].i = z__1.i;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tkk += j;\n/* L80: */\n\t    }\n\t}\n    } else {\n\n/*        Form  y  when AP contains the lower triangle. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__2 = j;\n\t\tz__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, z__1.i =\n\t\t\t alpha->r * x[i__2].i + alpha->i * x[i__2].r;\n\t\ttemp1.r = z__1.r, temp1.i = z__1.i;\n\t\ttemp2.r = 0., temp2.i = 0.;\n\t\ti__2 = j;\n\t\ti__3 = j;\n\t\ti__4 = kk;\n\t\td__1 = ap[i__4].r;\n\t\tz__2.r = d__1 * temp1.r, z__2.i = d__1 * temp1.i;\n\t\tz__1.r = y[i__3].r + z__2.r, z__1.i = y[i__3].i + z__2.i;\n\t\ty[i__2].r = z__1.r, y[i__2].i = z__1.i;\n\t\tk = kk + 1;\n\t\ti__2 = *n;\n\t\tfor (i__ = j + 1; i__ <= i__2; ++i__) {\n\t\t    i__3 = i__;\n\t\t    i__4 = i__;\n\t\t    i__5 = k;\n\t\t    z__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, \n\t\t\t    z__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5]\n\t\t\t    .r;\n\t\t    z__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i;\n\t\t    y[i__3].r = z__1.r, y[i__3].i = z__1.i;\n\t\t    d_cnjg(&z__3, &ap[k]);\n\t\t    i__3 = i__;\n\t\t    z__2.r = z__3.r * x[i__3].r - z__3.i * x[i__3].i, z__2.i =\n\t\t\t     z__3.r * x[i__3].i + z__3.i * x[i__3].r;\n\t\t    z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i;\n\t\t    temp2.r = z__1.r, temp2.i = z__1.i;\n\t\t    ++k;\n/* L90: */\n\t\t}\n\t\ti__2 = j;\n\t\ti__3 = j;\n\t\tz__2.r = alpha->r * temp2.r - alpha->i * temp2.i, z__2.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tz__1.r = y[i__3].r + z__2.r, z__1.i = y[i__3].i + z__2.i;\n\t\ty[i__2].r = z__1.r, y[i__2].i = z__1.i;\n\t\tkk += *n - j + 1;\n/* L100: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__2 = jx;\n\t\tz__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, z__1.i =\n\t\t\t alpha->r * x[i__2].i + alpha->i * x[i__2].r;\n\t\ttemp1.r = z__1.r, temp1.i = z__1.i;\n\t\ttemp2.r = 0., temp2.i = 0.;\n\t\ti__2 = jy;\n\t\ti__3 = jy;\n\t\ti__4 = kk;\n\t\td__1 = ap[i__4].r;\n\t\tz__2.r = d__1 * temp1.r, z__2.i = d__1 * temp1.i;\n\t\tz__1.r = y[i__3].r + z__2.r, z__1.i = y[i__3].i + z__2.i;\n\t\ty[i__2].r = z__1.r, y[i__2].i = z__1.i;\n\t\tix = jx;\n\t\tiy = jy;\n\t\ti__2 = kk + *n - j;\n\t\tfor (k = kk + 1; k <= i__2; ++k) {\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n\t\t    i__3 = iy;\n\t\t    i__4 = iy;\n\t\t    i__5 = k;\n\t\t    z__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, \n\t\t\t    z__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5]\n\t\t\t    .r;\n\t\t    z__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i;\n\t\t    y[i__3].r = z__1.r, y[i__3].i = z__1.i;\n\t\t    d_cnjg(&z__3, &ap[k]);\n\t\t    i__3 = ix;\n\t\t    z__2.r = z__3.r * x[i__3].r - z__3.i * x[i__3].i, z__2.i =\n\t\t\t     z__3.r * x[i__3].i + z__3.i * x[i__3].r;\n\t\t    z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i;\n\t\t    temp2.r = z__1.r, temp2.i = z__1.i;\n/* L110: */\n\t\t}\n\t\ti__2 = jy;\n\t\ti__3 = jy;\n\t\tz__2.r = alpha->r * temp2.r - alpha->i * temp2.i, z__2.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tz__1.r = y[i__3].r + z__2.r, z__1.i = y[i__3].i + z__2.i;\n\t\ty[i__2].r = z__1.r, y[i__2].i = z__1.i;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tkk += *n - j + 1;\n/* L120: */\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of ZHPMV . */\n\n} /* zhpmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/f2c/ztbmv.c",
    "content": "/* ztbmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int ztbmv_(char *uplo, char *trans, char *diag, integer *n, \n\tinteger *k, doublecomplex *a, integer *lda, doublecomplex *x, integer \n\t*incx, ftnlen uplo_len, ftnlen trans_len, ftnlen diag_len)\n{\n    /* System generated locals */\n    integer a_dim1, a_offset, i__1, i__2, i__3, i__4, i__5;\n    doublecomplex z__1, z__2, z__3;\n\n    /* Builtin functions */\n    void d_cnjg(doublecomplex *, doublecomplex *);\n\n    /* Local variables */\n    integer i__, j, l, ix, jx, kx, info;\n    doublecomplex temp;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    integer kplus1;\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n    logical noconj, nounit;\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  ZTBMV  performs one of the matrix-vector operations */\n\n/*     x := A*x,   or   x := A'*x,   or   x := conjg( A' )*x, */\n\n/*  where x is an n element vector and  A is an n by n unit, or non-unit, */\n/*  upper or lower triangular band matrix, with ( k + 1 ) diagonals. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the matrix is an upper or */\n/*           lower triangular matrix as follows: */\n\n/*              UPLO = 'U' or 'u'   A is an upper triangular matrix. */\n\n/*              UPLO = 'L' or 'l'   A is a lower triangular matrix. */\n\n/*           Unchanged on exit. */\n\n/*  TRANS  - CHARACTER*1. */\n/*           On entry, TRANS specifies the operation to be performed as */\n/*           follows: */\n\n/*              TRANS = 'N' or 'n'   x := A*x. */\n\n/*              TRANS = 'T' or 't'   x := A'*x. */\n\n/*              TRANS = 'C' or 'c'   x := conjg( A' )*x. */\n\n/*           Unchanged on exit. */\n\n/*  DIAG   - CHARACTER*1. */\n/*           On entry, DIAG specifies whether or not A is unit */\n/*           triangular as follows: */\n\n/*              DIAG = 'U' or 'u'   A is assumed to be unit triangular. */\n\n/*              DIAG = 'N' or 'n'   A is not assumed to be unit */\n/*                                  triangular. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  K      - INTEGER. */\n/*           On entry with UPLO = 'U' or 'u', K specifies the number of */\n/*           super-diagonals of the matrix A. */\n/*           On entry with UPLO = 'L' or 'l', K specifies the number of */\n/*           sub-diagonals of the matrix A. */\n/*           K must satisfy  0 .le. K. */\n/*           Unchanged on exit. */\n\n/*  A      - COMPLEX*16       array of DIMENSION ( LDA, n ). */\n/*           Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the upper triangular */\n/*           band part of the matrix of coefficients, supplied column by */\n/*           column, with the leading diagonal of the matrix in row */\n/*           ( k + 1 ) of the array, the first super-diagonal starting at */\n/*           position 2 in row k, and so on. The top left k by k triangle */\n/*           of the array A is not referenced. */\n/*           The following program segment will transfer an upper */\n/*           triangular band matrix from conventional full matrix storage */\n/*           to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = K + 1 - J */\n/*                    DO 10, I = MAX( 1, J - K ), J */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the lower triangular */\n/*           band part of the matrix of coefficients, supplied column by */\n/*           column, with the leading diagonal of the matrix in row 1 of */\n/*           the array, the first sub-diagonal starting at position 1 in */\n/*           row 2, and so on. The bottom right k by k triangle of the */\n/*           array A is not referenced. */\n/*           The following program segment will transfer a lower */\n/*           triangular band matrix from conventional full matrix storage */\n/*           to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = 1 - J */\n/*                    DO 10, I = J, MIN( N, J + K ) */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Note that when DIAG = 'U' or 'u' the elements of the array A */\n/*           corresponding to the diagonal elements of the matrix are not */\n/*           referenced, but are assumed to be unity. */\n/*           Unchanged on exit. */\n\n/*  LDA    - INTEGER. */\n/*           On entry, LDA specifies the first dimension of A as declared */\n/*           in the calling (sub) program. LDA must be at least */\n/*           ( k + 1 ). */\n/*           Unchanged on exit. */\n\n/*  X      - COMPLEX*16       array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the n */\n/*           element vector x. On exit, X is overwritten with the */\n/*           transformed vector x. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    a_dim1 = *lda;\n    a_offset = 1 + a_dim1;\n    a -= a_offset;\n    --x;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (! lsame_(trans, \"N\", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, \n\t    \"T\", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, \"C\", (ftnlen)1, (\n\t    ftnlen)1)) {\n\tinfo = 2;\n    } else if (! lsame_(diag, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(diag, \n\t    \"N\", (ftnlen)1, (ftnlen)1)) {\n\tinfo = 3;\n    } else if (*n < 0) {\n\tinfo = 4;\n    } else if (*k < 0) {\n\tinfo = 5;\n    } else if (*lda < *k + 1) {\n\tinfo = 7;\n    } else if (*incx == 0) {\n\tinfo = 9;\n    }\n    if (info != 0) {\n\txerbla_(\"ZTBMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0) {\n\treturn 0;\n    }\n\n    noconj = lsame_(trans, \"T\", (ftnlen)1, (ftnlen)1);\n    nounit = lsame_(diag, \"N\", (ftnlen)1, (ftnlen)1);\n\n/*     Set up the start point in X if the increment is not unity. This */\n/*     will be  ( N - 1 )*INCX   too small for descending loops. */\n\n    if (*incx <= 0) {\n\tkx = 1 - (*n - 1) * *incx;\n    } else if (*incx != 1) {\n\tkx = 1;\n    }\n\n/*     Start the operations. In this version the elements of A are */\n/*     accessed sequentially with one pass through A. */\n\n    if (lsame_(trans, \"N\", (ftnlen)1, (ftnlen)1)) {\n\n/*         Form  x := A*x. */\n\n\tif (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\t    kplus1 = *k + 1;\n\t    if (*incx == 1) {\n\t\ti__1 = *n;\n\t\tfor (j = 1; j <= i__1; ++j) {\n\t\t    i__2 = j;\n\t\t    if (x[i__2].r != 0. || x[i__2].i != 0.) {\n\t\t\ti__2 = j;\n\t\t\ttemp.r = x[i__2].r, temp.i = x[i__2].i;\n\t\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\t\ti__2 = 1, i__3 = j - *k;\n\t\t\ti__4 = j - 1;\n\t\t\tfor (i__ = max(i__2,i__3); i__ <= i__4; ++i__) {\n\t\t\t    i__2 = i__;\n\t\t\t    i__3 = i__;\n\t\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t\t    z__2.r = temp.r * a[i__5].r - temp.i * a[i__5].i, \n\t\t\t\t    z__2.i = temp.r * a[i__5].i + temp.i * a[\n\t\t\t\t    i__5].r;\n\t\t\t    z__1.r = x[i__3].r + z__2.r, z__1.i = x[i__3].i + \n\t\t\t\t    z__2.i;\n\t\t\t    x[i__2].r = z__1.r, x[i__2].i = z__1.i;\n/* L10: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    i__4 = j;\n\t\t\t    i__2 = j;\n\t\t\t    i__3 = kplus1 + j * a_dim1;\n\t\t\t    z__1.r = x[i__2].r * a[i__3].r - x[i__2].i * a[\n\t\t\t\t    i__3].i, z__1.i = x[i__2].r * a[i__3].i + \n\t\t\t\t    x[i__2].i * a[i__3].r;\n\t\t\t    x[i__4].r = z__1.r, x[i__4].i = z__1.i;\n\t\t\t}\n\t\t    }\n/* L20: */\n\t\t}\n\t    } else {\n\t\tjx = kx;\n\t\ti__1 = *n;\n\t\tfor (j = 1; j <= i__1; ++j) {\n\t\t    i__4 = jx;\n\t\t    if (x[i__4].r != 0. || x[i__4].i != 0.) {\n\t\t\ti__4 = jx;\n\t\t\ttemp.r = x[i__4].r, temp.i = x[i__4].i;\n\t\t\tix = kx;\n\t\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\t\ti__4 = 1, i__2 = j - *k;\n\t\t\ti__3 = j - 1;\n\t\t\tfor (i__ = max(i__4,i__2); i__ <= i__3; ++i__) {\n\t\t\t    i__4 = ix;\n\t\t\t    i__2 = ix;\n\t\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t\t    z__2.r = temp.r * a[i__5].r - temp.i * a[i__5].i, \n\t\t\t\t    z__2.i = temp.r * a[i__5].i + temp.i * a[\n\t\t\t\t    i__5].r;\n\t\t\t    z__1.r = x[i__2].r + z__2.r, z__1.i = x[i__2].i + \n\t\t\t\t    z__2.i;\n\t\t\t    x[i__4].r = z__1.r, x[i__4].i = z__1.i;\n\t\t\t    ix += *incx;\n/* L30: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    i__3 = jx;\n\t\t\t    i__4 = jx;\n\t\t\t    i__2 = kplus1 + j * a_dim1;\n\t\t\t    z__1.r = x[i__4].r * a[i__2].r - x[i__4].i * a[\n\t\t\t\t    i__2].i, z__1.i = x[i__4].r * a[i__2].i + \n\t\t\t\t    x[i__4].i * a[i__2].r;\n\t\t\t    x[i__3].r = z__1.r, x[i__3].i = z__1.i;\n\t\t\t}\n\t\t    }\n\t\t    jx += *incx;\n\t\t    if (j > *k) {\n\t\t\tkx += *incx;\n\t\t    }\n/* L40: */\n\t\t}\n\t    }\n\t} else {\n\t    if (*incx == 1) {\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    i__1 = j;\n\t\t    if (x[i__1].r != 0. || x[i__1].i != 0.) {\n\t\t\ti__1 = j;\n\t\t\ttemp.r = x[i__1].r, temp.i = x[i__1].i;\n\t\t\tl = 1 - j;\n/* Computing MIN */\n\t\t\ti__1 = *n, i__3 = j + *k;\n\t\t\ti__4 = j + 1;\n\t\t\tfor (i__ = min(i__1,i__3); i__ >= i__4; --i__) {\n\t\t\t    i__1 = i__;\n\t\t\t    i__3 = i__;\n\t\t\t    i__2 = l + i__ + j * a_dim1;\n\t\t\t    z__2.r = temp.r * a[i__2].r - temp.i * a[i__2].i, \n\t\t\t\t    z__2.i = temp.r * a[i__2].i + temp.i * a[\n\t\t\t\t    i__2].r;\n\t\t\t    z__1.r = x[i__3].r + z__2.r, z__1.i = x[i__3].i + \n\t\t\t\t    z__2.i;\n\t\t\t    x[i__1].r = z__1.r, x[i__1].i = z__1.i;\n/* L50: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    i__4 = j;\n\t\t\t    i__1 = j;\n\t\t\t    i__3 = j * a_dim1 + 1;\n\t\t\t    z__1.r = x[i__1].r * a[i__3].r - x[i__1].i * a[\n\t\t\t\t    i__3].i, z__1.i = x[i__1].r * a[i__3].i + \n\t\t\t\t    x[i__1].i * a[i__3].r;\n\t\t\t    x[i__4].r = z__1.r, x[i__4].i = z__1.i;\n\t\t\t}\n\t\t    }\n/* L60: */\n\t\t}\n\t    } else {\n\t\tkx += (*n - 1) * *incx;\n\t\tjx = kx;\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    i__4 = jx;\n\t\t    if (x[i__4].r != 0. || x[i__4].i != 0.) {\n\t\t\ti__4 = jx;\n\t\t\ttemp.r = x[i__4].r, temp.i = x[i__4].i;\n\t\t\tix = kx;\n\t\t\tl = 1 - j;\n/* Computing MIN */\n\t\t\ti__4 = *n, i__1 = j + *k;\n\t\t\ti__3 = j + 1;\n\t\t\tfor (i__ = min(i__4,i__1); i__ >= i__3; --i__) {\n\t\t\t    i__4 = ix;\n\t\t\t    i__1 = ix;\n\t\t\t    i__2 = l + i__ + j * a_dim1;\n\t\t\t    z__2.r = temp.r * a[i__2].r - temp.i * a[i__2].i, \n\t\t\t\t    z__2.i = temp.r * a[i__2].i + temp.i * a[\n\t\t\t\t    i__2].r;\n\t\t\t    z__1.r = x[i__1].r + z__2.r, z__1.i = x[i__1].i + \n\t\t\t\t    z__2.i;\n\t\t\t    x[i__4].r = z__1.r, x[i__4].i = z__1.i;\n\t\t\t    ix -= *incx;\n/* L70: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    i__3 = jx;\n\t\t\t    i__4 = jx;\n\t\t\t    i__1 = j * a_dim1 + 1;\n\t\t\t    z__1.r = x[i__4].r * a[i__1].r - x[i__4].i * a[\n\t\t\t\t    i__1].i, z__1.i = x[i__4].r * a[i__1].i + \n\t\t\t\t    x[i__4].i * a[i__1].r;\n\t\t\t    x[i__3].r = z__1.r, x[i__3].i = z__1.i;\n\t\t\t}\n\t\t    }\n\t\t    jx -= *incx;\n\t\t    if (*n - j >= *k) {\n\t\t\tkx -= *incx;\n\t\t    }\n/* L80: */\n\t\t}\n\t    }\n\t}\n    } else {\n\n/*        Form  x := A'*x  or  x := conjg( A' )*x. */\n\n\tif (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\t    kplus1 = *k + 1;\n\t    if (*incx == 1) {\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    i__3 = j;\n\t\t    temp.r = x[i__3].r, temp.i = x[i__3].i;\n\t\t    l = kplus1 - j;\n\t\t    if (noconj) {\n\t\t\tif (nounit) {\n\t\t\t    i__3 = kplus1 + j * a_dim1;\n\t\t\t    z__1.r = temp.r * a[i__3].r - temp.i * a[i__3].i, \n\t\t\t\t    z__1.i = temp.r * a[i__3].i + temp.i * a[\n\t\t\t\t    i__3].r;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t}\n/* Computing MAX */\n\t\t\ti__4 = 1, i__1 = j - *k;\n\t\t\ti__3 = max(i__4,i__1);\n\t\t\tfor (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\t    i__4 = l + i__ + j * a_dim1;\n\t\t\t    i__1 = i__;\n\t\t\t    z__2.r = a[i__4].r * x[i__1].r - a[i__4].i * x[\n\t\t\t\t    i__1].i, z__2.i = a[i__4].r * x[i__1].i + \n\t\t\t\t    a[i__4].i * x[i__1].r;\n\t\t\t    z__1.r = temp.r + z__2.r, z__1.i = temp.i + \n\t\t\t\t    z__2.i;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n/* L90: */\n\t\t\t}\n\t\t    } else {\n\t\t\tif (nounit) {\n\t\t\t    d_cnjg(&z__2, &a[kplus1 + j * a_dim1]);\n\t\t\t    z__1.r = temp.r * z__2.r - temp.i * z__2.i, \n\t\t\t\t    z__1.i = temp.r * z__2.i + temp.i * \n\t\t\t\t    z__2.r;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t}\n/* Computing MAX */\n\t\t\ti__4 = 1, i__1 = j - *k;\n\t\t\ti__3 = max(i__4,i__1);\n\t\t\tfor (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\t    d_cnjg(&z__3, &a[l + i__ + j * a_dim1]);\n\t\t\t    i__4 = i__;\n\t\t\t    z__2.r = z__3.r * x[i__4].r - z__3.i * x[i__4].i, \n\t\t\t\t    z__2.i = z__3.r * x[i__4].i + z__3.i * x[\n\t\t\t\t    i__4].r;\n\t\t\t    z__1.r = temp.r + z__2.r, z__1.i = temp.i + \n\t\t\t\t    z__2.i;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n/* L100: */\n\t\t\t}\n\t\t    }\n\t\t    i__3 = j;\n\t\t    x[i__3].r = temp.r, x[i__3].i = temp.i;\n/* L110: */\n\t\t}\n\t    } else {\n\t\tkx += (*n - 1) * *incx;\n\t\tjx = kx;\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    i__3 = jx;\n\t\t    temp.r = x[i__3].r, temp.i = x[i__3].i;\n\t\t    kx -= *incx;\n\t\t    ix = kx;\n\t\t    l = kplus1 - j;\n\t\t    if (noconj) {\n\t\t\tif (nounit) {\n\t\t\t    i__3 = kplus1 + j * a_dim1;\n\t\t\t    z__1.r = temp.r * a[i__3].r - temp.i * a[i__3].i, \n\t\t\t\t    z__1.i = temp.r * a[i__3].i + temp.i * a[\n\t\t\t\t    i__3].r;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t}\n/* Computing MAX */\n\t\t\ti__4 = 1, i__1 = j - *k;\n\t\t\ti__3 = max(i__4,i__1);\n\t\t\tfor (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\t    i__4 = l + i__ + j * a_dim1;\n\t\t\t    i__1 = ix;\n\t\t\t    z__2.r = a[i__4].r * x[i__1].r - a[i__4].i * x[\n\t\t\t\t    i__1].i, z__2.i = a[i__4].r * x[i__1].i + \n\t\t\t\t    a[i__4].i * x[i__1].r;\n\t\t\t    z__1.r = temp.r + z__2.r, z__1.i = temp.i + \n\t\t\t\t    z__2.i;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t    ix -= *incx;\n/* L120: */\n\t\t\t}\n\t\t    } else {\n\t\t\tif (nounit) {\n\t\t\t    d_cnjg(&z__2, &a[kplus1 + j * a_dim1]);\n\t\t\t    z__1.r = temp.r * z__2.r - temp.i * z__2.i, \n\t\t\t\t    z__1.i = temp.r * z__2.i + temp.i * \n\t\t\t\t    z__2.r;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t}\n/* Computing MAX */\n\t\t\ti__4 = 1, i__1 = j - *k;\n\t\t\ti__3 = max(i__4,i__1);\n\t\t\tfor (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\t    d_cnjg(&z__3, &a[l + i__ + j * a_dim1]);\n\t\t\t    i__4 = ix;\n\t\t\t    z__2.r = z__3.r * x[i__4].r - z__3.i * x[i__4].i, \n\t\t\t\t    z__2.i = z__3.r * x[i__4].i + z__3.i * x[\n\t\t\t\t    i__4].r;\n\t\t\t    z__1.r = temp.r + z__2.r, z__1.i = temp.i + \n\t\t\t\t    z__2.i;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t    ix -= *incx;\n/* L130: */\n\t\t\t}\n\t\t    }\n\t\t    i__3 = jx;\n\t\t    x[i__3].r = temp.r, x[i__3].i = temp.i;\n\t\t    jx -= *incx;\n/* L140: */\n\t\t}\n\t    }\n\t} else {\n\t    if (*incx == 1) {\n\t\ti__3 = *n;\n\t\tfor (j = 1; j <= i__3; ++j) {\n\t\t    i__4 = j;\n\t\t    temp.r = x[i__4].r, temp.i = x[i__4].i;\n\t\t    l = 1 - j;\n\t\t    if (noconj) {\n\t\t\tif (nounit) {\n\t\t\t    i__4 = j * a_dim1 + 1;\n\t\t\t    z__1.r = temp.r * a[i__4].r - temp.i * a[i__4].i, \n\t\t\t\t    z__1.i = temp.r * a[i__4].i + temp.i * a[\n\t\t\t\t    i__4].r;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t}\n/* Computing MIN */\n\t\t\ti__1 = *n, i__2 = j + *k;\n\t\t\ti__4 = min(i__1,i__2);\n\t\t\tfor (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\t    i__1 = l + i__ + j * a_dim1;\n\t\t\t    i__2 = i__;\n\t\t\t    z__2.r = a[i__1].r * x[i__2].r - a[i__1].i * x[\n\t\t\t\t    i__2].i, z__2.i = a[i__1].r * x[i__2].i + \n\t\t\t\t    a[i__1].i * x[i__2].r;\n\t\t\t    z__1.r = temp.r + z__2.r, z__1.i = temp.i + \n\t\t\t\t    z__2.i;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n/* L150: */\n\t\t\t}\n\t\t    } else {\n\t\t\tif (nounit) {\n\t\t\t    d_cnjg(&z__2, &a[j * a_dim1 + 1]);\n\t\t\t    z__1.r = temp.r * z__2.r - temp.i * z__2.i, \n\t\t\t\t    z__1.i = temp.r * z__2.i + temp.i * \n\t\t\t\t    z__2.r;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t}\n/* Computing MIN */\n\t\t\ti__1 = *n, i__2 = j + *k;\n\t\t\ti__4 = min(i__1,i__2);\n\t\t\tfor (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\t    d_cnjg(&z__3, &a[l + i__ + j * a_dim1]);\n\t\t\t    i__1 = i__;\n\t\t\t    z__2.r = z__3.r * x[i__1].r - z__3.i * x[i__1].i, \n\t\t\t\t    z__2.i = z__3.r * x[i__1].i + z__3.i * x[\n\t\t\t\t    i__1].r;\n\t\t\t    z__1.r = temp.r + z__2.r, z__1.i = temp.i + \n\t\t\t\t    z__2.i;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n/* L160: */\n\t\t\t}\n\t\t    }\n\t\t    i__4 = j;\n\t\t    x[i__4].r = temp.r, x[i__4].i = temp.i;\n/* L170: */\n\t\t}\n\t    } else {\n\t\tjx = kx;\n\t\ti__3 = *n;\n\t\tfor (j = 1; j <= i__3; ++j) {\n\t\t    i__4 = jx;\n\t\t    temp.r = x[i__4].r, temp.i = x[i__4].i;\n\t\t    kx += *incx;\n\t\t    ix = kx;\n\t\t    l = 1 - j;\n\t\t    if (noconj) {\n\t\t\tif (nounit) {\n\t\t\t    i__4 = j * a_dim1 + 1;\n\t\t\t    z__1.r = temp.r * a[i__4].r - temp.i * a[i__4].i, \n\t\t\t\t    z__1.i = temp.r * a[i__4].i + temp.i * a[\n\t\t\t\t    i__4].r;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t}\n/* Computing MIN */\n\t\t\ti__1 = *n, i__2 = j + *k;\n\t\t\ti__4 = min(i__1,i__2);\n\t\t\tfor (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\t    i__1 = l + i__ + j * a_dim1;\n\t\t\t    i__2 = ix;\n\t\t\t    z__2.r = a[i__1].r * x[i__2].r - a[i__1].i * x[\n\t\t\t\t    i__2].i, z__2.i = a[i__1].r * x[i__2].i + \n\t\t\t\t    a[i__1].i * x[i__2].r;\n\t\t\t    z__1.r = temp.r + z__2.r, z__1.i = temp.i + \n\t\t\t\t    z__2.i;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t    ix += *incx;\n/* L180: */\n\t\t\t}\n\t\t    } else {\n\t\t\tif (nounit) {\n\t\t\t    d_cnjg(&z__2, &a[j * a_dim1 + 1]);\n\t\t\t    z__1.r = temp.r * z__2.r - temp.i * z__2.i, \n\t\t\t\t    z__1.i = temp.r * z__2.i + temp.i * \n\t\t\t\t    z__2.r;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t}\n/* Computing MIN */\n\t\t\ti__1 = *n, i__2 = j + *k;\n\t\t\ti__4 = min(i__1,i__2);\n\t\t\tfor (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\t    d_cnjg(&z__3, &a[l + i__ + j * a_dim1]);\n\t\t\t    i__1 = ix;\n\t\t\t    z__2.r = z__3.r * x[i__1].r - z__3.i * x[i__1].i, \n\t\t\t\t    z__2.i = z__3.r * x[i__1].i + z__3.i * x[\n\t\t\t\t    i__1].r;\n\t\t\t    z__1.r = temp.r + z__2.r, z__1.i = temp.i + \n\t\t\t\t    z__2.i;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t    ix += *incx;\n/* L190: */\n\t\t\t}\n\t\t    }\n\t\t    i__4 = jx;\n\t\t    x[i__4].r = temp.r, x[i__4].i = temp.i;\n\t\t    jx += *incx;\n/* L200: */\n\t\t}\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of ZTBMV . */\n\n} /* ztbmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/fortran/complexdots.f",
    "content": "      COMPLEX FUNCTION CDOTC(N,CX,INCX,CY,INCY)\n      INTEGER INCX,INCY,N\n      COMPLEX CX(*),CY(*)\n      COMPLEX RES\n      EXTERNAL CDOTCW\n      \n      CALL CDOTCW(N,CX,INCX,CY,INCY,RES)\n      CDOTC = RES\n      RETURN\n      END\n      \n      COMPLEX FUNCTION CDOTU(N,CX,INCX,CY,INCY)\n      INTEGER INCX,INCY,N\n      COMPLEX CX(*),CY(*)\n      COMPLEX RES\n      EXTERNAL CDOTUW\n      \n      CALL CDOTUW(N,CX,INCX,CY,INCY,RES)\n      CDOTU = RES\n      RETURN\n      END\n      \n      DOUBLE COMPLEX FUNCTION ZDOTC(N,CX,INCX,CY,INCY)\n      INTEGER INCX,INCY,N\n      DOUBLE COMPLEX CX(*),CY(*)\n      DOUBLE COMPLEX RES\n      EXTERNAL ZDOTCW\n      \n      CALL ZDOTCW(N,CX,INCX,CY,INCY,RES)\n      ZDOTC = RES\n      RETURN\n      END\n      \n      DOUBLE COMPLEX FUNCTION ZDOTU(N,CX,INCX,CY,INCY)\n      INTEGER INCX,INCY,N\n      DOUBLE COMPLEX CX(*),CY(*)\n      DOUBLE COMPLEX RES\n      EXTERNAL ZDOTUW\n      \n      CALL ZDOTUW(N,CX,INCX,CY,INCY,RES)\n      ZDOTU = RES\n      RETURN\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/level1_cplx_impl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"common.h\"\n\nstruct scalar_norm1_op {\n  typedef RealScalar result_type;\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_norm1_op)\n  inline RealScalar operator() (const Scalar& a) const { return numext::norm1(a); }\n};\nnamespace Eigen {\n  namespace internal {\n    template<> struct functor_traits<scalar_norm1_op >\n    {\n      enum { Cost = 3 * NumTraits<Scalar>::AddCost, PacketAccess = 0 };\n    };\n  }\n}\n\n// computes the sum of magnitudes of all vector elements or, for a complex vector x, the sum\n// res = |Rex1| + |Imx1| + |Rex2| + |Imx2| + ... + |Rexn| + |Imxn|, where x is a vector of order n\nRealScalar EIGEN_CAT(REAL_SCALAR_SUFFIX, EIGEN_BLAS_FUNC(asum))(int *n, RealScalar *px, int *incx)\n{\n//   std::cerr << \"__asum \" << *n << \" \" << *incx << \"\\n\";\n  Complex* x = reinterpret_cast<Complex*>(px);\n\n  if(*n<=0) return 0;\n\n  if(*incx==1)  return make_vector(x,*n).unaryExpr<scalar_norm1_op>().sum();\n  else          return make_vector(x,*n,std::abs(*incx)).unaryExpr<scalar_norm1_op>().sum();\n}\n\nint EIGEN_CAT(i, EIGEN_BLAS_FUNC(amax))(int *n, RealScalar *px, int *incx)\n{\n  if(*n<=0) return 0;\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n\n  DenseIndex ret;\n  if(*incx==1)  make_vector(x,*n).unaryExpr<scalar_norm1_op>().maxCoeff(&ret);\n  else          make_vector(x,*n,std::abs(*incx)).unaryExpr<scalar_norm1_op>().maxCoeff(&ret);\n  return int(ret)+1;\n}\n\nint EIGEN_CAT(i, EIGEN_BLAS_FUNC(amin))(int *n, RealScalar *px, int *incx)\n{\n  if(*n<=0) return 0;\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n\n  DenseIndex ret;\n  if(*incx==1)  make_vector(x,*n).unaryExpr<scalar_norm1_op>().minCoeff(&ret);\n  else          make_vector(x,*n,std::abs(*incx)).unaryExpr<scalar_norm1_op>().minCoeff(&ret);\n  return int(ret)+1;\n}\n\n// computes a dot product of a conjugated vector with another vector.\nint EIGEN_BLAS_FUNC(dotcw)(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar* pres)\n{\n//   std::cerr << \"_dotc \" << *n << \" \" << *incx << \" \" << *incy << \"\\n\";\n  Scalar* res = reinterpret_cast<Scalar*>(pres);\n\n  if(*n<=0)\n  {\n    *res = Scalar(0);\n    return 0;\n  }\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n\n  if(*incx==1 && *incy==1)    *res = (make_vector(x,*n).dot(make_vector(y,*n)));\n  else if(*incx>0 && *incy>0) *res = (make_vector(x,*n,*incx).dot(make_vector(y,*n,*incy)));\n  else if(*incx<0 && *incy>0) *res = (make_vector(x,*n,-*incx).reverse().dot(make_vector(y,*n,*incy)));\n  else if(*incx>0 && *incy<0) *res = (make_vector(x,*n,*incx).dot(make_vector(y,*n,-*incy).reverse()));\n  else if(*incx<0 && *incy<0) *res = (make_vector(x,*n,-*incx).reverse().dot(make_vector(y,*n,-*incy).reverse()));\n  return 0;\n}\n\n// computes a vector-vector dot product without complex conjugation.\nint EIGEN_BLAS_FUNC(dotuw)(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar* pres)\n{\n  Scalar* res = reinterpret_cast<Scalar*>(pres);\n\n  if(*n<=0)\n  {\n    *res = Scalar(0);\n    return 0;\n  }\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n\n  if(*incx==1 && *incy==1)    *res = (make_vector(x,*n).cwiseProduct(make_vector(y,*n))).sum();\n  else if(*incx>0 && *incy>0) *res = (make_vector(x,*n,*incx).cwiseProduct(make_vector(y,*n,*incy))).sum();\n  else if(*incx<0 && *incy>0) *res = (make_vector(x,*n,-*incx).reverse().cwiseProduct(make_vector(y,*n,*incy))).sum();\n  else if(*incx>0 && *incy<0) *res = (make_vector(x,*n,*incx).cwiseProduct(make_vector(y,*n,-*incy).reverse())).sum();\n  else if(*incx<0 && *incy<0) *res = (make_vector(x,*n,-*incx).reverse().cwiseProduct(make_vector(y,*n,-*incy).reverse())).sum();\n  return 0;\n}\n\nRealScalar EIGEN_CAT(REAL_SCALAR_SUFFIX, EIGEN_BLAS_FUNC(nrm2))(int *n, RealScalar *px, int *incx)\n{\n//   std::cerr << \"__nrm2 \" << *n << \" \" << *incx << \"\\n\";\n  if(*n<=0) return 0;\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n\n  if(*incx==1)\n    return make_vector(x,*n).stableNorm();\n\n  return make_vector(x,*n,*incx).stableNorm();\n}\n\nint EIGEN_BLAS_FUNC(EIGEN_CAT(REAL_SCALAR_SUFFIX, rot))(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pc, RealScalar *ps)\n{\n  if(*n<=0) return 0;\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  RealScalar c = *pc;\n  RealScalar s = *ps;\n\n  StridedVectorType vx(make_vector(x,*n,std::abs(*incx)));\n  StridedVectorType vy(make_vector(y,*n,std::abs(*incy)));\n\n  Reverse<StridedVectorType> rvx(vx);\n  Reverse<StridedVectorType> rvy(vy);\n\n  // TODO implement mixed real-scalar rotations\n       if(*incx<0 && *incy>0) internal::apply_rotation_in_the_plane(rvx, vy, JacobiRotation<Scalar>(c,s));\n  else if(*incx>0 && *incy<0) internal::apply_rotation_in_the_plane(vx, rvy, JacobiRotation<Scalar>(c,s));\n  else                        internal::apply_rotation_in_the_plane(vx, vy,  JacobiRotation<Scalar>(c,s));\n\n  return 0;\n}\n\nint EIGEN_BLAS_FUNC(EIGEN_CAT(REAL_SCALAR_SUFFIX, scal))(int *n, RealScalar *palpha, RealScalar *px, int *incx)\n{\n  if(*n<=0) return 0;\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  RealScalar alpha = *palpha;\n\n//   std::cerr << \"__scal \" << *n << \" \" << alpha << \" \" << *incx << \"\\n\";\n\n  if(*incx==1)  make_vector(x,*n) *= alpha;\n  else          make_vector(x,*n,std::abs(*incx)) *= alpha;\n\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/level1_impl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"common.h\"\n\nint EIGEN_BLAS_FUNC(axpy)(const int *n, const RealScalar *palpha, const RealScalar *px, const int *incx, RealScalar *py, const int *incy)\n{\n  const Scalar* x = reinterpret_cast<const Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar alpha  = *reinterpret_cast<const Scalar*>(palpha);\n\n  if(*n<=0) return 0;\n\n  if(*incx==1 && *incy==1)    make_vector(y,*n) += alpha * make_vector(x,*n);\n  else if(*incx>0 && *incy>0) make_vector(y,*n,*incy) += alpha * make_vector(x,*n,*incx);\n  else if(*incx>0 && *incy<0) make_vector(y,*n,-*incy).reverse() += alpha * make_vector(x,*n,*incx);\n  else if(*incx<0 && *incy>0) make_vector(y,*n,*incy) += alpha * make_vector(x,*n,-*incx).reverse();\n  else if(*incx<0 && *incy<0) make_vector(y,*n,-*incy).reverse() += alpha * make_vector(x,*n,-*incx).reverse();\n\n  return 0;\n}\n\nint EIGEN_BLAS_FUNC(copy)(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)\n{\n  if(*n<=0) return 0;\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n\n  // be careful, *incx==0 is allowed !!\n  if(*incx==1 && *incy==1)\n    make_vector(y,*n) = make_vector(x,*n);\n  else\n  {\n    if(*incx<0) x = x - (*n-1)*(*incx);\n    if(*incy<0) y = y - (*n-1)*(*incy);\n    for(int i=0;i<*n;++i)\n    {\n      *y = *x;\n      x += *incx;\n      y += *incy;\n    }\n  }\n\n  return 0;\n}\n\nint EIGEN_BLAS_FUNC(rotg)(RealScalar *pa, RealScalar *pb, RealScalar *pc, RealScalar *ps)\n{\n  using std::sqrt;\n  using std::abs;\n\n  Scalar& a = *reinterpret_cast<Scalar*>(pa);\n  Scalar& b = *reinterpret_cast<Scalar*>(pb);\n  RealScalar* c = pc;\n  Scalar* s = reinterpret_cast<Scalar*>(ps);\n\n  #if !ISCOMPLEX\n  Scalar r,z;\n  Scalar aa = abs(a);\n  Scalar ab = abs(b);\n  if((aa+ab)==Scalar(0))\n  {\n    *c = 1;\n    *s = 0;\n    r = 0;\n    z = 0;\n  }\n  else\n  {\n    r = sqrt(a*a + b*b);\n    Scalar amax = aa>ab ? a : b;\n    r = amax>0 ? r : -r;\n    *c = a/r;\n    *s = b/r;\n    z = 1;\n    if (aa > ab) z = *s;\n    if (ab > aa && *c!=RealScalar(0))\n      z = Scalar(1)/ *c;\n  }\n  *pa = r;\n  *pb = z;\n  #else\n  Scalar alpha;\n  RealScalar norm,scale;\n  if(abs(a)==RealScalar(0))\n  {\n    *c = RealScalar(0);\n    *s = Scalar(1);\n    a = b;\n  }\n  else\n  {\n    scale = abs(a) + abs(b);\n    norm = scale*sqrt((numext::abs2(a/scale)) + (numext::abs2(b/scale)));\n    alpha = a/abs(a);\n    *c = abs(a)/norm;\n    *s = alpha*numext::conj(b)/norm;\n    a = alpha*norm;\n  }\n  #endif\n\n//   JacobiRotation<Scalar> r;\n//   r.makeGivens(a,b);\n//   *c = r.c();\n//   *s = r.s();\n\n  return 0;\n}\n\nint EIGEN_BLAS_FUNC(scal)(int *n, RealScalar *palpha, RealScalar *px, int *incx)\n{\n  if(*n<=0) return 0;\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar alpha = *reinterpret_cast<Scalar*>(palpha);\n\n  if(*incx==1)  make_vector(x,*n) *= alpha;\n  else          make_vector(x,*n,std::abs(*incx)) *= alpha;\n\n  return 0;\n}\n\nint EIGEN_BLAS_FUNC(swap)(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)\n{\n  if(*n<=0) return 0;\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n\n  if(*incx==1 && *incy==1)    make_vector(y,*n).swap(make_vector(x,*n));\n  else if(*incx>0 && *incy>0) make_vector(y,*n,*incy).swap(make_vector(x,*n,*incx));\n  else if(*incx>0 && *incy<0) make_vector(y,*n,-*incy).reverse().swap(make_vector(x,*n,*incx));\n  else if(*incx<0 && *incy>0) make_vector(y,*n,*incy).swap(make_vector(x,*n,-*incx).reverse());\n  else if(*incx<0 && *incy<0) make_vector(y,*n,-*incy).reverse().swap(make_vector(x,*n,-*incx).reverse());\n\n  return 1;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/level1_real_impl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"common.h\"\n\n// computes the sum of magnitudes of all vector elements or, for a complex vector x, the sum\n// res = |Rex1| + |Imx1| + |Rex2| + |Imx2| + ... + |Rexn| + |Imxn|, where x is a vector of order n\nRealScalar EIGEN_BLAS_FUNC(asum)(int *n, RealScalar *px, int *incx)\n{\n//   std::cerr << \"_asum \" << *n << \" \" << *incx << \"\\n\";\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n\n  if(*n<=0) return 0;\n\n  if(*incx==1)  return make_vector(x,*n).cwiseAbs().sum();\n  else          return make_vector(x,*n,std::abs(*incx)).cwiseAbs().sum();\n}\n\nint EIGEN_CAT(i, EIGEN_BLAS_FUNC(amax))(int *n, RealScalar *px, int *incx)\n{\n  if(*n<=0) return 0;\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n\n  DenseIndex ret;\n  if(*incx==1)  make_vector(x,*n).cwiseAbs().maxCoeff(&ret);\n  else          make_vector(x,*n,std::abs(*incx)).cwiseAbs().maxCoeff(&ret);\n  return int(ret)+1;\n}\n\nint EIGEN_CAT(i, EIGEN_BLAS_FUNC(amin))(int *n, RealScalar *px, int *incx)\n{\n  if(*n<=0) return 0;\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n\n  DenseIndex ret;\n  if(*incx==1)  make_vector(x,*n).cwiseAbs().minCoeff(&ret);\n  else          make_vector(x,*n,std::abs(*incx)).cwiseAbs().minCoeff(&ret);\n  return int(ret)+1;\n}\n\n// computes a vector-vector dot product.\nScalar EIGEN_BLAS_FUNC(dot)(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)\n{\n//   std::cerr << \"_dot \" << *n << \" \" << *incx << \" \" << *incy << \"\\n\";\n\n  if(*n<=0) return 0;\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n\n  if(*incx==1 && *incy==1)    return (make_vector(x,*n).cwiseProduct(make_vector(y,*n))).sum();\n  else if(*incx>0 && *incy>0) return (make_vector(x,*n,*incx).cwiseProduct(make_vector(y,*n,*incy))).sum();\n  else if(*incx<0 && *incy>0) return (make_vector(x,*n,-*incx).reverse().cwiseProduct(make_vector(y,*n,*incy))).sum();\n  else if(*incx>0 && *incy<0) return (make_vector(x,*n,*incx).cwiseProduct(make_vector(y,*n,-*incy).reverse())).sum();\n  else if(*incx<0 && *incy<0) return (make_vector(x,*n,-*incx).reverse().cwiseProduct(make_vector(y,*n,-*incy).reverse())).sum();\n  else return 0;\n}\n\n// computes the Euclidean norm of a vector.\n// FIXME\nScalar EIGEN_BLAS_FUNC(nrm2)(int *n, RealScalar *px, int *incx)\n{\n//   std::cerr << \"_nrm2 \" << *n << \" \" << *incx << \"\\n\";\n  if(*n<=0) return 0;\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n\n  if(*incx==1)  return make_vector(x,*n).stableNorm();\n  else          return make_vector(x,*n,std::abs(*incx)).stableNorm();\n}\n\nint EIGEN_BLAS_FUNC(rot)(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pc, RealScalar *ps)\n{\n//   std::cerr << \"_rot \" << *n << \" \" << *incx << \" \" << *incy << \"\\n\";\n  if(*n<=0) return 0;\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar c = *reinterpret_cast<Scalar*>(pc);\n  Scalar s = *reinterpret_cast<Scalar*>(ps);\n\n  StridedVectorType vx(make_vector(x,*n,std::abs(*incx)));\n  StridedVectorType vy(make_vector(y,*n,std::abs(*incy)));\n\n  Reverse<StridedVectorType> rvx(vx);\n  Reverse<StridedVectorType> rvy(vy);\n\n       if(*incx<0 && *incy>0) internal::apply_rotation_in_the_plane(rvx, vy, JacobiRotation<Scalar>(c,s));\n  else if(*incx>0 && *incy<0) internal::apply_rotation_in_the_plane(vx, rvy, JacobiRotation<Scalar>(c,s));\n  else                        internal::apply_rotation_in_the_plane(vx, vy,  JacobiRotation<Scalar>(c,s));\n\n\n  return 0;\n}\n\n/*\n// performs rotation of points in the modified plane.\nint EIGEN_BLAS_FUNC(rotm)(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *param)\n{\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n\n  // TODO\n\n  return 0;\n}\n\n// computes the modified parameters for a Givens rotation.\nint EIGEN_BLAS_FUNC(rotmg)(RealScalar *d1, RealScalar *d2, RealScalar *x1, RealScalar *x2, RealScalar *param)\n{\n  // TODO\n\n  return 0;\n}\n*/\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/level2_cplx_impl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"common.h\"\n\n/**  ZHEMV  performs the matrix-vector  operation\n  *\n  *     y := alpha*A*x + beta*y,\n  *\n  *  where alpha and beta are scalars, x and y are n element vectors and\n  *  A is an n by n hermitian matrix.\n  */\nint EIGEN_BLAS_FUNC(hemv)(const char *uplo, const int *n, const RealScalar *palpha, const RealScalar *pa, const int *lda,\n                          const RealScalar *px, const int *incx, const RealScalar *pbeta, RealScalar *py, const int *incy)\n{\n  typedef void (*functype)(int, const Scalar*, int, const Scalar*, Scalar*, Scalar);\n  static const functype func[2] = {\n    // array index: UP\n    (internal::selfadjoint_matrix_vector_product<Scalar,int,ColMajor,Upper,false,false>::run),\n    // array index: LO\n    (internal::selfadjoint_matrix_vector_product<Scalar,int,ColMajor,Lower,false,false>::run),\n  };\n\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  const Scalar* x = reinterpret_cast<const Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar alpha  = *reinterpret_cast<const Scalar*>(palpha);\n  Scalar beta   = *reinterpret_cast<const Scalar*>(pbeta);\n\n  // check arguments\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)        info = 1;\n  else if(*n<0)                   info = 2;\n  else if(*lda<std::max(1,*n))    info = 5;\n  else if(*incx==0)               info = 7;\n  else if(*incy==0)               info = 10;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"HEMV \",&info,6);\n\n  if(*n==0)\n    return 1;\n\n  const Scalar* actual_x = get_compact_vector(x,*n,*incx);\n  Scalar* actual_y = get_compact_vector(y,*n,*incy);\n\n  if(beta!=Scalar(1))\n  {\n    if(beta==Scalar(0)) make_vector(actual_y, *n).setZero();\n    else                make_vector(actual_y, *n) *= beta;\n  }\n\n  if(alpha!=Scalar(0))\n  {\n    int code = UPLO(*uplo);\n    if(code>=2 || func[code]==0)\n      return 0;\n\n    func[code](*n, a, *lda, actual_x, actual_y, alpha);\n  }\n\n  if(actual_x!=x) delete[] actual_x;\n  if(actual_y!=y) delete[] copy_back(actual_y,y,*n,*incy);\n\n  return 1;\n}\n\n/**  ZHBMV  performs the matrix-vector  operation\n  *\n  *     y := alpha*A*x + beta*y,\n  *\n  *  where alpha and beta are scalars, x and y are n element vectors and\n  *  A is an n by n hermitian band matrix, with k super-diagonals.\n  */\n// int EIGEN_BLAS_FUNC(hbmv)(char *uplo, int *n, int *k, RealScalar *alpha, RealScalar *a, int *lda,\n//                           RealScalar *x, int *incx, RealScalar *beta, RealScalar *y, int *incy)\n// {\n//   return 1;\n// }\n\n/**  ZHPMV  performs the matrix-vector operation\n  *\n  *     y := alpha*A*x + beta*y,\n  *\n  *  where alpha and beta are scalars, x and y are n element vectors and\n  *  A is an n by n hermitian matrix, supplied in packed form.\n  */\n// int EIGEN_BLAS_FUNC(hpmv)(char *uplo, int *n, RealScalar *alpha, RealScalar *ap, RealScalar *x, int *incx, RealScalar *beta, RealScalar *y, int *incy)\n// {\n//   return 1;\n// }\n\n/**  ZHPR    performs the hermitian rank 1 operation\n  *\n  *     A := alpha*x*conjg( x' ) + A,\n  *\n  *  where alpha is a real scalar, x is an n element vector and A is an\n  *  n by n hermitian matrix, supplied in packed form.\n  */\nint EIGEN_BLAS_FUNC(hpr)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *pap)\n{\n  typedef void (*functype)(int, Scalar*, const Scalar*, RealScalar);\n  static const functype func[2] = {\n    // array index: UP\n    (internal::selfadjoint_packed_rank1_update<Scalar,int,ColMajor,Upper,false,Conj>::run),\n    // array index: LO\n    (internal::selfadjoint_packed_rank1_update<Scalar,int,ColMajor,Lower,false,Conj>::run),\n  };\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* ap = reinterpret_cast<Scalar*>(pap);\n  RealScalar alpha = *palpha;\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"HPR  \",&info,6);\n\n  if(alpha==Scalar(0))\n    return 1;\n\n  Scalar* x_cpy = get_compact_vector(x, *n, *incx);\n\n  int code = UPLO(*uplo);\n  if(code>=2 || func[code]==0)\n    return 0;\n\n  func[code](*n, ap, x_cpy, alpha);\n\n  if(x_cpy!=x)  delete[] x_cpy;\n\n  return 1;\n}\n\n/**  ZHPR2  performs the hermitian rank 2 operation\n  *\n  *     A := alpha*x*conjg( y' ) + conjg( alpha )*y*conjg( x' ) + A,\n  *\n  *  where alpha is a scalar, x and y are n element vectors and A is an\n  *  n by n hermitian matrix, supplied in packed form.\n  */\nint EIGEN_BLAS_FUNC(hpr2)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pap)\n{\n  typedef void (*functype)(int, Scalar*, const Scalar*, const Scalar*, Scalar);\n  static const functype func[2] = {\n    // array index: UP\n    (internal::packed_rank2_update_selector<Scalar,int,Upper>::run),\n    // array index: LO\n    (internal::packed_rank2_update_selector<Scalar,int,Lower>::run),\n  };\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar* ap = reinterpret_cast<Scalar*>(pap);\n  Scalar alpha = *reinterpret_cast<Scalar*>(palpha);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  else if(*incy==0)                                                   info = 7;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"HPR2 \",&info,6);\n\n  if(alpha==Scalar(0))\n    return 1;\n\n  Scalar* x_cpy = get_compact_vector(x, *n, *incx);\n  Scalar* y_cpy = get_compact_vector(y, *n, *incy);\n\n  int code = UPLO(*uplo);\n  if(code>=2 || func[code]==0)\n    return 0;\n\n  func[code](*n, ap, x_cpy, y_cpy, alpha);\n\n  if(x_cpy!=x)  delete[] x_cpy;\n  if(y_cpy!=y)  delete[] y_cpy;\n\n  return 1;\n}\n\n/**  ZHER   performs the hermitian rank 1 operation\n  *\n  *     A := alpha*x*conjg( x' ) + A,\n  *\n  *  where alpha is a real scalar, x is an n element vector and A is an\n  *  n by n hermitian matrix.\n  */\nint EIGEN_BLAS_FUNC(her)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *pa, int *lda)\n{\n  typedef void (*functype)(int, Scalar*, int, const Scalar*, const Scalar*, const Scalar&);\n  static const functype func[2] = {\n    // array index: UP\n    (selfadjoint_rank1_update<Scalar,int,ColMajor,Upper,false,Conj>::run),\n    // array index: LO\n    (selfadjoint_rank1_update<Scalar,int,ColMajor,Lower,false,Conj>::run),\n  };\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  RealScalar alpha = *reinterpret_cast<RealScalar*>(palpha);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  else if(*lda<std::max(1,*n))                                        info = 7;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"HER  \",&info,6);\n\n  if(alpha==RealScalar(0))\n    return 1;\n\n  Scalar* x_cpy = get_compact_vector(x, *n, *incx);\n\n  int code = UPLO(*uplo);\n  if(code>=2 || func[code]==0)\n    return 0;\n\n  func[code](*n, a, *lda, x_cpy, x_cpy, alpha);\n\n  matrix(a,*n,*n,*lda).diagonal().imag().setZero();\n\n  if(x_cpy!=x)  delete[] x_cpy;\n\n  return 1;\n}\n\n/**  ZHER2  performs the hermitian rank 2 operation\n  *\n  *     A := alpha*x*conjg( y' ) + conjg( alpha )*y*conjg( x' ) + A,\n  *\n  *  where alpha is a scalar, x and y are n element vectors and A is an n\n  *  by n hermitian matrix.\n  */\nint EIGEN_BLAS_FUNC(her2)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pa, int *lda)\n{\n  typedef void (*functype)(int, Scalar*, int, const Scalar*, const Scalar*, Scalar);\n  static const functype func[2] = {\n    // array index: UP\n    (internal::rank2_update_selector<Scalar,int,Upper>::run),\n    // array index: LO\n    (internal::rank2_update_selector<Scalar,int,Lower>::run),\n  };\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  Scalar alpha = *reinterpret_cast<Scalar*>(palpha);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  else if(*incy==0)                                                   info = 7;\n  else if(*lda<std::max(1,*n))                                        info = 9;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"HER2 \",&info,6);\n\n  if(alpha==Scalar(0))\n    return 1;\n\n  Scalar* x_cpy = get_compact_vector(x, *n, *incx);\n  Scalar* y_cpy = get_compact_vector(y, *n, *incy);\n\n  int code = UPLO(*uplo);\n  if(code>=2 || func[code]==0)\n    return 0;\n\n  func[code](*n, a, *lda, x_cpy, y_cpy, alpha);\n\n  matrix(a,*n,*n,*lda).diagonal().imag().setZero();\n\n  if(x_cpy!=x)  delete[] x_cpy;\n  if(y_cpy!=y)  delete[] y_cpy;\n\n  return 1;\n}\n\n/**  ZGERU  performs the rank 1 operation\n  *\n  *     A := alpha*x*y' + A,\n  *\n  *  where alpha is a scalar, x is an m element vector, y is an n element\n  *  vector and A is an m by n matrix.\n  */\nint EIGEN_BLAS_FUNC(geru)(int *m, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pa, int *lda)\n{\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  Scalar alpha = *reinterpret_cast<Scalar*>(palpha);\n\n  int info = 0;\n       if(*m<0)                                                       info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  else if(*incy==0)                                                   info = 7;\n  else if(*lda<std::max(1,*m))                                        info = 9;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"GERU \",&info,6);\n\n  if(alpha==Scalar(0))\n    return 1;\n\n  Scalar* x_cpy = get_compact_vector(x,*m,*incx);\n  Scalar* y_cpy = get_compact_vector(y,*n,*incy);\n\n  internal::general_rank1_update<Scalar,int,ColMajor,false,false>::run(*m, *n, a, *lda, x_cpy, y_cpy, alpha);\n\n  if(x_cpy!=x)  delete[] x_cpy;\n  if(y_cpy!=y)  delete[] y_cpy;\n\n  return 1;\n}\n\n/**  ZGERC  performs the rank 1 operation\n  *\n  *     A := alpha*x*conjg( y' ) + A,\n  *\n  *  where alpha is a scalar, x is an m element vector, y is an n element\n  *  vector and A is an m by n matrix.\n  */\nint EIGEN_BLAS_FUNC(gerc)(int *m, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pa, int *lda)\n{\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  Scalar alpha = *reinterpret_cast<Scalar*>(palpha);\n\n  int info = 0;\n       if(*m<0)                                                       info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  else if(*incy==0)                                                   info = 7;\n  else if(*lda<std::max(1,*m))                                        info = 9;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"GERC \",&info,6);\n\n  if(alpha==Scalar(0))\n    return 1;\n\n  Scalar* x_cpy = get_compact_vector(x,*m,*incx);\n  Scalar* y_cpy = get_compact_vector(y,*n,*incy);\n\n  internal::general_rank1_update<Scalar,int,ColMajor,false,Conj>::run(*m, *n, a, *lda, x_cpy, y_cpy, alpha);\n\n  if(x_cpy!=x)  delete[] x_cpy;\n  if(y_cpy!=y)  delete[] y_cpy;\n\n  return 1;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/level2_impl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"common.h\"\n\ntemplate<typename Index, typename Scalar, int StorageOrder, bool ConjugateLhs, bool ConjugateRhs>\nstruct general_matrix_vector_product_wrapper\n{\n  static void run(Index rows, Index cols,const Scalar *lhs, Index lhsStride, const Scalar *rhs, Index rhsIncr, Scalar* res, Index resIncr, Scalar alpha)\n  {\n    typedef internal::const_blas_data_mapper<Scalar,Index,StorageOrder> LhsMapper;\n    typedef internal::const_blas_data_mapper<Scalar,Index,RowMajor> RhsMapper;\n    \n    internal::general_matrix_vector_product\n        <Index,Scalar,LhsMapper,StorageOrder,ConjugateLhs,Scalar,RhsMapper,ConjugateRhs>::run(\n        rows, cols, LhsMapper(lhs, lhsStride), RhsMapper(rhs, rhsIncr), res, resIncr, alpha);\n  }\n};\n\nint EIGEN_BLAS_FUNC(gemv)(const char *opa, const int *m, const int *n, const RealScalar *palpha,\n                          const RealScalar *pa, const int *lda, const RealScalar *pb, const int *incb, const RealScalar *pbeta, RealScalar *pc, const int *incc)\n{\n  typedef void (*functype)(int, int, const Scalar *, int, const Scalar *, int , Scalar *, int, Scalar);\n  static const functype func[4] = {\n    // array index: NOTR\n    (general_matrix_vector_product_wrapper<int,Scalar,ColMajor,false,false>::run),\n    // array index: TR  \n    (general_matrix_vector_product_wrapper<int,Scalar,RowMajor,false,false>::run),\n    // array index: ADJ \n    (general_matrix_vector_product_wrapper<int,Scalar,RowMajor,Conj ,false>::run),\n    0\n  };\n\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  const Scalar* b = reinterpret_cast<const Scalar*>(pb);\n  Scalar* c = reinterpret_cast<Scalar*>(pc);\n  Scalar alpha  = *reinterpret_cast<const Scalar*>(palpha);\n  Scalar beta   = *reinterpret_cast<const Scalar*>(pbeta);\n\n  // check arguments\n  int info = 0;\n  if(OP(*opa)==INVALID)           info = 1;\n  else if(*m<0)                   info = 2;\n  else if(*n<0)                   info = 3;\n  else if(*lda<std::max(1,*m))    info = 6;\n  else if(*incb==0)               info = 8;\n  else if(*incc==0)               info = 11;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"GEMV \",&info,6);\n\n  if(*m==0 || *n==0 || (alpha==Scalar(0) && beta==Scalar(1)))\n    return 0;\n\n  int actual_m = *m;\n  int actual_n = *n;\n  int code = OP(*opa);\n  if(code!=NOTR)\n    std::swap(actual_m,actual_n);\n\n  const Scalar* actual_b = get_compact_vector(b,actual_n,*incb);\n  Scalar* actual_c = get_compact_vector(c,actual_m,*incc);\n\n  if(beta!=Scalar(1))\n  {\n    if(beta==Scalar(0)) make_vector(actual_c, actual_m).setZero();\n    else                make_vector(actual_c, actual_m) *= beta;\n  }\n\n  if(code>=4 || func[code]==0)\n    return 0;\n\n  func[code](actual_m, actual_n, a, *lda, actual_b, 1, actual_c, 1, alpha);\n\n  if(actual_b!=b) delete[] actual_b;\n  if(actual_c!=c) delete[] copy_back(actual_c,c,actual_m,*incc);\n\n  return 1;\n}\n\nint EIGEN_BLAS_FUNC(trsv)(const char *uplo, const char *opa, const char *diag, const int *n, const RealScalar *pa, const int *lda, RealScalar *pb, const int *incb)\n{\n  typedef void (*functype)(int, const Scalar *, int, Scalar *);\n  static const functype func[16] = {\n    // array index: NOTR  | (UP << 2) | (NUNIT << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|0,       false,ColMajor>::run),\n    // array index: TR    | (UP << 2) | (NUNIT << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|0,       false,RowMajor>::run),\n    // array index: ADJ   | (UP << 2) | (NUNIT << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|0,       Conj, RowMajor>::run),\n    0,\n    // array index: NOTR  | (LO << 2) | (NUNIT << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|0,       false,ColMajor>::run),\n    // array index: TR    | (LO << 2) | (NUNIT << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|0,       false,RowMajor>::run),\n    // array index: ADJ   | (LO << 2) | (NUNIT << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|0,       Conj, RowMajor>::run),\n    0,\n    // array index: NOTR  | (UP << 2) | (UNIT  << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|UnitDiag,false,ColMajor>::run),\n    // array index: TR    | (UP << 2) | (UNIT  << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|UnitDiag,false,RowMajor>::run),\n    // array index: ADJ   | (UP << 2) | (UNIT  << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|UnitDiag,Conj, RowMajor>::run),\n    0,\n    // array index: NOTR  | (LO << 2) | (UNIT  << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|UnitDiag,false,ColMajor>::run),\n    // array index: TR    | (LO << 2) | (UNIT  << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|UnitDiag,false,RowMajor>::run),\n    // array index: ADJ   | (LO << 2) | (UNIT  << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|UnitDiag,Conj, RowMajor>::run),\n    0\n  };\n\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  Scalar* b = reinterpret_cast<Scalar*>(pb);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(OP(*opa)==INVALID)                                          info = 2;\n  else if(DIAG(*diag)==INVALID)                                       info = 3;\n  else if(*n<0)                                                       info = 4;\n  else if(*lda<std::max(1,*n))                                        info = 6;\n  else if(*incb==0)                                                   info = 8;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"TRSV \",&info,6);\n\n  Scalar* actual_b = get_compact_vector(b,*n,*incb);\n\n  int code = OP(*opa) | (UPLO(*uplo) << 2) | (DIAG(*diag) << 3);\n  func[code](*n, a, *lda, actual_b);\n\n  if(actual_b!=b) delete[] copy_back(actual_b,b,*n,*incb);\n\n  return 0;\n}\n\n\n\nint EIGEN_BLAS_FUNC(trmv)(const char *uplo, const char *opa, const char *diag, const int *n, const RealScalar *pa, const int *lda, RealScalar *pb, const int *incb)\n{\n  typedef void (*functype)(int, int, const Scalar *, int, const Scalar *, int, Scalar *, int, const Scalar&);\n  static const functype func[16] = {\n    // array index: NOTR  | (UP << 2) | (NUNIT << 3)\n    (internal::triangular_matrix_vector_product<int,Upper|0,       Scalar,false,Scalar,false,ColMajor>::run),\n    // array index: TR    | (UP << 2) | (NUNIT << 3)\n    (internal::triangular_matrix_vector_product<int,Lower|0,       Scalar,false,Scalar,false,RowMajor>::run),\n    // array index: ADJ   | (UP << 2) | (NUNIT << 3)\n    (internal::triangular_matrix_vector_product<int,Lower|0,       Scalar,Conj, Scalar,false,RowMajor>::run),\n    0,\n    // array index: NOTR  | (LO << 2) | (NUNIT << 3)\n    (internal::triangular_matrix_vector_product<int,Lower|0,       Scalar,false,Scalar,false,ColMajor>::run),\n    // array index: TR    | (LO << 2) | (NUNIT << 3)\n    (internal::triangular_matrix_vector_product<int,Upper|0,       Scalar,false,Scalar,false,RowMajor>::run),\n    // array index: ADJ   | (LO << 2) | (NUNIT << 3)\n    (internal::triangular_matrix_vector_product<int,Upper|0,       Scalar,Conj, Scalar,false,RowMajor>::run),\n    0,\n    // array index: NOTR  | (UP << 2) | (UNIT  << 3)\n    (internal::triangular_matrix_vector_product<int,Upper|UnitDiag,Scalar,false,Scalar,false,ColMajor>::run),\n    // array index: TR    | (UP << 2) | (UNIT  << 3)\n    (internal::triangular_matrix_vector_product<int,Lower|UnitDiag,Scalar,false,Scalar,false,RowMajor>::run),\n    // array index: ADJ   | (UP << 2) | (UNIT  << 3)\n    (internal::triangular_matrix_vector_product<int,Lower|UnitDiag,Scalar,Conj, Scalar,false,RowMajor>::run),\n    0,\n    // array index: NOTR  | (LO << 2) | (UNIT  << 3)\n    (internal::triangular_matrix_vector_product<int,Lower|UnitDiag,Scalar,false,Scalar,false,ColMajor>::run),\n    // array index: TR    | (LO << 2) | (UNIT  << 3)\n    (internal::triangular_matrix_vector_product<int,Upper|UnitDiag,Scalar,false,Scalar,false,RowMajor>::run),\n    // array index: ADJ   | (LO << 2) | (UNIT  << 3)\n    (internal::triangular_matrix_vector_product<int,Upper|UnitDiag,Scalar,Conj, Scalar,false,RowMajor>::run),\n    0\n  };\n\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  Scalar* b = reinterpret_cast<Scalar*>(pb);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(OP(*opa)==INVALID)                                          info = 2;\n  else if(DIAG(*diag)==INVALID)                                       info = 3;\n  else if(*n<0)                                                       info = 4;\n  else if(*lda<std::max(1,*n))                                        info = 6;\n  else if(*incb==0)                                                   info = 8;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"TRMV \",&info,6);\n\n  if(*n==0)\n    return 1;\n\n  Scalar* actual_b = get_compact_vector(b,*n,*incb);\n  Matrix<Scalar,Dynamic,1> res(*n);\n  res.setZero();\n\n  int code = OP(*opa) | (UPLO(*uplo) << 2) | (DIAG(*diag) << 3);\n  if(code>=16 || func[code]==0)\n    return 0;\n\n  func[code](*n, *n, a, *lda, actual_b, 1, res.data(), 1, Scalar(1));\n\n  copy_back(res.data(),b,*n,*incb);\n  if(actual_b!=b) delete[] actual_b;\n\n  return 1;\n}\n\n/**  GBMV  performs one of the matrix-vector operations\n  *\n  *     y := alpha*A*x + beta*y,   or   y := alpha*A'*x + beta*y,\n  *\n  *  where alpha and beta are scalars, x and y are vectors and A is an\n  *  m by n band matrix, with kl sub-diagonals and ku super-diagonals.\n  */\nint EIGEN_BLAS_FUNC(gbmv)(char *trans, int *m, int *n, int *kl, int *ku, RealScalar *palpha, RealScalar *pa, int *lda,\n                          RealScalar *px, int *incx, RealScalar *pbeta, RealScalar *py, int *incy)\n{\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  const Scalar* x = reinterpret_cast<const Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar alpha = *reinterpret_cast<const Scalar*>(palpha);\n  Scalar beta = *reinterpret_cast<const Scalar*>(pbeta);\n  int coeff_rows = *kl+*ku+1;\n\n  int info = 0;\n       if(OP(*trans)==INVALID)                                        info = 1;\n  else if(*m<0)                                                       info = 2;\n  else if(*n<0)                                                       info = 3;\n  else if(*kl<0)                                                      info = 4;\n  else if(*ku<0)                                                      info = 5;\n  else if(*lda<coeff_rows)                                            info = 8;\n  else if(*incx==0)                                                   info = 10;\n  else if(*incy==0)                                                   info = 13;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"GBMV \",&info,6);\n\n  if(*m==0 || *n==0 || (alpha==Scalar(0) && beta==Scalar(1)))\n    return 0;\n\n  int actual_m = *m;\n  int actual_n = *n;\n  if(OP(*trans)!=NOTR)\n    std::swap(actual_m,actual_n);\n\n  const Scalar* actual_x = get_compact_vector(x,actual_n,*incx);\n  Scalar* actual_y = get_compact_vector(y,actual_m,*incy);\n\n  if(beta!=Scalar(1))\n  {\n    if(beta==Scalar(0)) make_vector(actual_y, actual_m).setZero();\n    else                make_vector(actual_y, actual_m) *= beta;\n  }\n\n  ConstMatrixType mat_coeffs(a,coeff_rows,*n,*lda);\n\n  int nb = std::min(*n,(*m)+(*ku));\n  for(int j=0; j<nb; ++j)\n  {\n    int start = std::max(0,j - *ku);\n    int end = std::min((*m)-1,j + *kl);\n    int len = end - start + 1;\n    int offset = (*ku) - j + start;\n    if(OP(*trans)==NOTR)\n      make_vector(actual_y+start,len) += (alpha*actual_x[j]) * mat_coeffs.col(j).segment(offset,len);\n    else if(OP(*trans)==TR)\n      actual_y[j] += alpha * ( mat_coeffs.col(j).segment(offset,len).transpose() * make_vector(actual_x+start,len) ).value();\n    else\n      actual_y[j] += alpha * ( mat_coeffs.col(j).segment(offset,len).adjoint()   * make_vector(actual_x+start,len) ).value();\n  }\n\n  if(actual_x!=x) delete[] actual_x;\n  if(actual_y!=y) delete[] copy_back(actual_y,y,actual_m,*incy);\n\n  return 0;\n}\n\n#if 0\n/**  TBMV  performs one of the matrix-vector operations\n  *\n  *     x := A*x,   or   x := A'*x,\n  *\n  *  where x is an n element vector and  A is an n by n unit, or non-unit,\n  *  upper or lower triangular band matrix, with ( k + 1 ) diagonals.\n  */\nint EIGEN_BLAS_FUNC(tbmv)(char *uplo, char *opa, char *diag, int *n, int *k, RealScalar *pa, int *lda, RealScalar *px, int *incx)\n{\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  int coeff_rows = *k + 1;\n\n  int info = 0;\n       if(UPLO(*uplo)==INVALID)                                       info = 1;\n  else if(OP(*opa)==INVALID)                                          info = 2;\n  else if(DIAG(*diag)==INVALID)                                       info = 3;\n  else if(*n<0)                                                       info = 4;\n  else if(*k<0)                                                       info = 5;\n  else if(*lda<coeff_rows)                                            info = 7;\n  else if(*incx==0)                                                   info = 9;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"TBMV \",&info,6);\n\n  if(*n==0)\n    return 0;\n\n  int actual_n = *n;\n\n  Scalar* actual_x = get_compact_vector(x,actual_n,*incx);\n\n  MatrixType mat_coeffs(a,coeff_rows,*n,*lda);\n\n  int ku = UPLO(*uplo)==UPPER ? *k : 0;\n  int kl = UPLO(*uplo)==LOWER ? *k : 0;\n\n  for(int j=0; j<*n; ++j)\n  {\n    int start = std::max(0,j - ku);\n    int end = std::min((*m)-1,j + kl);\n    int len = end - start + 1;\n    int offset = (ku) - j + start;\n\n    if(OP(*trans)==NOTR)\n      make_vector(actual_y+start,len) += (alpha*actual_x[j]) * mat_coeffs.col(j).segment(offset,len);\n    else if(OP(*trans)==TR)\n      actual_y[j] += alpha * ( mat_coeffs.col(j).segment(offset,len).transpose() * make_vector(actual_x+start,len) ).value();\n    else\n      actual_y[j] += alpha * ( mat_coeffs.col(j).segment(offset,len).adjoint()   * make_vector(actual_x+start,len) ).value();\n  }\n\n  if(actual_x!=x) delete[] actual_x;\n  if(actual_y!=y) delete[] copy_back(actual_y,y,actual_m,*incy);\n\n  return 0;\n}\n#endif\n\n/**  DTBSV  solves one of the systems of equations\n  *\n  *     A*x = b,   or   A'*x = b,\n  *\n  *  where b and x are n element vectors and A is an n by n unit, or\n  *  non-unit, upper or lower triangular band matrix, with ( k + 1 )\n  *  diagonals.\n  *\n  *  No test for singularity or near-singularity is included in this\n  *  routine. Such tests must be performed before calling this routine.\n  */\nint EIGEN_BLAS_FUNC(tbsv)(char *uplo, char *op, char *diag, int *n, int *k, RealScalar *pa, int *lda, RealScalar *px, int *incx)\n{\n  typedef void (*functype)(int, int, const Scalar *, int, Scalar *);\n  static const functype func[16] = {\n    // array index: NOTR  | (UP << 2) | (NUNIT << 3)\n    (internal::band_solve_triangular_selector<int,Upper|0,       Scalar,false,Scalar,ColMajor>::run),\n    // array index: TR    | (UP << 2) | (NUNIT << 3)\n    (internal::band_solve_triangular_selector<int,Lower|0,       Scalar,false,Scalar,RowMajor>::run),\n    // array index: ADJ   | (UP << 2) | (NUNIT << 3)\n    (internal::band_solve_triangular_selector<int,Lower|0,       Scalar,Conj, Scalar,RowMajor>::run),\n    0,\n    // array index: NOTR  | (LO << 2) | (NUNIT << 3)\n    (internal::band_solve_triangular_selector<int,Lower|0,       Scalar,false,Scalar,ColMajor>::run),\n    // array index: TR    | (LO << 2) | (NUNIT << 3)\n    (internal::band_solve_triangular_selector<int,Upper|0,       Scalar,false,Scalar,RowMajor>::run),\n    // array index: ADJ   | (LO << 2) | (NUNIT << 3)\n    (internal::band_solve_triangular_selector<int,Upper|0,       Scalar,Conj, Scalar,RowMajor>::run),\n    0,\n    // array index: NOTR  | (UP << 2) | (UNIT  << 3)\n    (internal::band_solve_triangular_selector<int,Upper|UnitDiag,Scalar,false,Scalar,ColMajor>::run),\n    // array index: TR    | (UP << 2) | (UNIT  << 3)\n    (internal::band_solve_triangular_selector<int,Lower|UnitDiag,Scalar,false,Scalar,RowMajor>::run),\n    // array index: ADJ   | (UP << 2) | (UNIT  << 3)\n    (internal::band_solve_triangular_selector<int,Lower|UnitDiag,Scalar,Conj, Scalar,RowMajor>::run),\n    0,\n    // array index: NOTR  | (LO << 2) | (UNIT  << 3)\n    (internal::band_solve_triangular_selector<int,Lower|UnitDiag,Scalar,false,Scalar,ColMajor>::run),\n    // array index: TR    | (LO << 2) | (UNIT  << 3)\n    (internal::band_solve_triangular_selector<int,Upper|UnitDiag,Scalar,false,Scalar,RowMajor>::run),\n    // array index: ADJ   | (LO << 2) | (UNIT  << 3)\n    (internal::band_solve_triangular_selector<int,Upper|UnitDiag,Scalar,Conj, Scalar,RowMajor>::run),\n    0,\n  };\n\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  int coeff_rows = *k+1;\n\n  int info = 0;\n       if(UPLO(*uplo)==INVALID)                                       info = 1;\n  else if(OP(*op)==INVALID)                                           info = 2;\n  else if(DIAG(*diag)==INVALID)                                       info = 3;\n  else if(*n<0)                                                       info = 4;\n  else if(*k<0)                                                       info = 5;\n  else if(*lda<coeff_rows)                                            info = 7;\n  else if(*incx==0)                                                   info = 9;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"TBSV \",&info,6);\n\n  if(*n==0 || (*k==0 && DIAG(*diag)==UNIT))\n    return 0;\n\n  int actual_n = *n;\n\n  Scalar* actual_x = get_compact_vector(x,actual_n,*incx);\n\n  int code = OP(*op) | (UPLO(*uplo) << 2) | (DIAG(*diag) << 3);\n  if(code>=16 || func[code]==0)\n    return 0;\n\n  func[code](*n, *k, a, *lda, actual_x);\n\n  if(actual_x!=x) delete[] copy_back(actual_x,x,actual_n,*incx);\n\n  return 0;\n}\n\n/**  DTPMV  performs one of the matrix-vector operations\n  *\n  *     x := A*x,   or   x := A'*x,\n  *\n  *  where x is an n element vector and  A is an n by n unit, or non-unit,\n  *  upper or lower triangular matrix, supplied in packed form.\n  */\nint EIGEN_BLAS_FUNC(tpmv)(char *uplo, char *opa, char *diag, int *n, RealScalar *pap, RealScalar *px, int *incx)\n{\n  typedef void (*functype)(int, const Scalar*, const Scalar*, Scalar*, Scalar);\n  static const functype func[16] = {\n    // array index: NOTR  | (UP << 2) | (NUNIT << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Upper|0,       Scalar,false,Scalar,false,ColMajor>::run),\n    // array index: TR    | (UP << 2) | (NUNIT << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Lower|0,       Scalar,false,Scalar,false,RowMajor>::run),\n    // array index: ADJ   | (UP << 2) | (NUNIT << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Lower|0,       Scalar,Conj, Scalar,false,RowMajor>::run),\n    0,\n    // array index: NOTR  | (LO << 2) | (NUNIT << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Lower|0,       Scalar,false,Scalar,false,ColMajor>::run),\n    // array index: TR    | (LO << 2) | (NUNIT << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Upper|0,       Scalar,false,Scalar,false,RowMajor>::run),\n    // array index: ADJ   | (LO << 2) | (NUNIT << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Upper|0,       Scalar,Conj, Scalar,false,RowMajor>::run),\n    0,\n    // array index: NOTR  | (UP << 2) | (UNIT  << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Upper|UnitDiag,Scalar,false,Scalar,false,ColMajor>::run),\n    // array index: TR    | (UP << 2) | (UNIT  << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Lower|UnitDiag,Scalar,false,Scalar,false,RowMajor>::run),\n    // array index: ADJ   | (UP << 2) | (UNIT  << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Lower|UnitDiag,Scalar,Conj, Scalar,false,RowMajor>::run),\n    0,\n    // array index: NOTR  | (LO << 2) | (UNIT  << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Lower|UnitDiag,Scalar,false,Scalar,false,ColMajor>::run),\n    // array index: TR    | (LO << 2) | (UNIT  << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Upper|UnitDiag,Scalar,false,Scalar,false,RowMajor>::run),\n    // array index: ADJ   | (LO << 2) | (UNIT  << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Upper|UnitDiag,Scalar,Conj, Scalar,false,RowMajor>::run),\n    0\n  };\n\n  Scalar* ap = reinterpret_cast<Scalar*>(pap);\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(OP(*opa)==INVALID)                                          info = 2;\n  else if(DIAG(*diag)==INVALID)                                       info = 3;\n  else if(*n<0)                                                       info = 4;\n  else if(*incx==0)                                                   info = 7;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"TPMV \",&info,6);\n\n  if(*n==0)\n    return 1;\n\n  Scalar* actual_x = get_compact_vector(x,*n,*incx);\n  Matrix<Scalar,Dynamic,1> res(*n);\n  res.setZero();\n\n  int code = OP(*opa) | (UPLO(*uplo) << 2) | (DIAG(*diag) << 3);\n  if(code>=16 || func[code]==0)\n    return 0;\n\n  func[code](*n, ap, actual_x, res.data(), Scalar(1));\n\n  copy_back(res.data(),x,*n,*incx);\n  if(actual_x!=x) delete[] actual_x;\n\n  return 1;\n}\n\n/**  DTPSV  solves one of the systems of equations\n  *\n  *     A*x = b,   or   A'*x = b,\n  *\n  *  where b and x are n element vectors and A is an n by n unit, or\n  *  non-unit, upper or lower triangular matrix, supplied in packed form.\n  *\n  *  No test for singularity or near-singularity is included in this\n  *  routine. Such tests must be performed before calling this routine.\n  */\nint EIGEN_BLAS_FUNC(tpsv)(char *uplo, char *opa, char *diag, int *n, RealScalar *pap, RealScalar *px, int *incx)\n{\n  typedef void (*functype)(int, const Scalar*, Scalar*);\n  static const functype func[16] = {\n    // array index: NOTR  | (UP << 2) | (NUNIT << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|0,       false,ColMajor>::run),\n    // array index: TR    | (UP << 2) | (NUNIT << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|0,       false,RowMajor>::run),\n    // array index: ADJ   | (UP << 2) | (NUNIT << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|0,       Conj, RowMajor>::run),\n    0,\n    // array index: NOTR  | (LO << 2) | (NUNIT << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|0,       false,ColMajor>::run),\n    // array index: TR    | (LO << 2) | (NUNIT << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|0,       false,RowMajor>::run),\n    // array index: ADJ   | (LO << 2) | (NUNIT << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|0,       Conj, RowMajor>::run),\n    0,\n    // array index: NOTR  | (UP << 2) | (UNIT  << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|UnitDiag,false,ColMajor>::run),\n    // array index: TR    | (UP << 2) | (UNIT  << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|UnitDiag,false,RowMajor>::run),\n    // array index: ADJ   | (UP << 2) | (UNIT  << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|UnitDiag,Conj, RowMajor>::run),\n    0,\n    // array index: NOTR  | (LO << 2) | (UNIT  << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|UnitDiag,false,ColMajor>::run),\n    // array index: TR    | (LO << 2) | (UNIT  << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|UnitDiag,false,RowMajor>::run),\n    // array index: ADJ   | (LO << 2) | (UNIT  << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|UnitDiag,Conj, RowMajor>::run),\n    0\n  };\n\n  Scalar* ap = reinterpret_cast<Scalar*>(pap);\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(OP(*opa)==INVALID)                                          info = 2;\n  else if(DIAG(*diag)==INVALID)                                       info = 3;\n  else if(*n<0)                                                       info = 4;\n  else if(*incx==0)                                                   info = 7;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"TPSV \",&info,6);\n\n  Scalar* actual_x = get_compact_vector(x,*n,*incx);\n\n  int code = OP(*opa) | (UPLO(*uplo) << 2) | (DIAG(*diag) << 3);\n  func[code](*n, ap, actual_x);\n\n  if(actual_x!=x) delete[] copy_back(actual_x,x,*n,*incx);\n\n  return 1;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/level2_real_impl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"common.h\"\n\n// y = alpha*A*x + beta*y\nint EIGEN_BLAS_FUNC(symv) (const char *uplo, const int *n, const RealScalar *palpha, const RealScalar *pa, const int *lda,\n                           const RealScalar *px, const int *incx, const RealScalar *pbeta, RealScalar *py, const int *incy)\n{\n  typedef void (*functype)(int, const Scalar*, int, const Scalar*, Scalar*, Scalar);\n  static const functype func[2] = {\n    // array index: UP\n    (internal::selfadjoint_matrix_vector_product<Scalar,int,ColMajor,Upper,false,false>::run),\n    // array index: LO\n    (internal::selfadjoint_matrix_vector_product<Scalar,int,ColMajor,Lower,false,false>::run),\n  };\n\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  const Scalar* x = reinterpret_cast<const Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar alpha  = *reinterpret_cast<const Scalar*>(palpha);\n  Scalar beta   = *reinterpret_cast<const Scalar*>(pbeta);\n\n  // check arguments\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)        info = 1;\n  else if(*n<0)                   info = 2;\n  else if(*lda<std::max(1,*n))    info = 5;\n  else if(*incx==0)               info = 7;\n  else if(*incy==0)               info = 10;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"SYMV \",&info,6);\n\n  if(*n==0)\n    return 0;\n\n  const Scalar* actual_x = get_compact_vector(x,*n,*incx);\n  Scalar* actual_y = get_compact_vector(y,*n,*incy);\n\n  if(beta!=Scalar(1))\n  {\n    if(beta==Scalar(0)) make_vector(actual_y, *n).setZero();\n    else                make_vector(actual_y, *n) *= beta;\n  }\n\n  int code = UPLO(*uplo);\n  if(code>=2 || func[code]==0)\n    return 0;\n\n  func[code](*n, a, *lda, actual_x, actual_y, alpha);\n\n  if(actual_x!=x) delete[] actual_x;\n  if(actual_y!=y) delete[] copy_back(actual_y,y,*n,*incy);\n\n  return 1;\n}\n\n// C := alpha*x*x' + C\nint EIGEN_BLAS_FUNC(syr)(const char *uplo, const int *n, const RealScalar *palpha, const RealScalar *px, const int *incx, RealScalar *pc, const int *ldc)\n{\n\n  typedef void (*functype)(int, Scalar*, int, const Scalar*, const Scalar*, const Scalar&);\n  static const functype func[2] = {\n    // array index: UP\n    (selfadjoint_rank1_update<Scalar,int,ColMajor,Upper,false,Conj>::run),\n    // array index: LO\n    (selfadjoint_rank1_update<Scalar,int,ColMajor,Lower,false,Conj>::run),\n  };\n\n  const Scalar* x = reinterpret_cast<const Scalar*>(px);\n  Scalar* c = reinterpret_cast<Scalar*>(pc);\n  Scalar alpha = *reinterpret_cast<const Scalar*>(palpha);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  else if(*ldc<std::max(1,*n))                                        info = 7;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"SYR  \",&info,6);\n\n  if(*n==0 || alpha==Scalar(0)) return 1;\n\n  // if the increment is not 1, let's copy it to a temporary vector to enable vectorization\n  const Scalar* x_cpy = get_compact_vector(x,*n,*incx);\n\n  int code = UPLO(*uplo);\n  if(code>=2 || func[code]==0)\n    return 0;\n\n  func[code](*n, c, *ldc, x_cpy, x_cpy, alpha);\n\n  if(x_cpy!=x)  delete[] x_cpy;\n\n  return 1;\n}\n\n// C := alpha*x*y' + alpha*y*x' + C\nint EIGEN_BLAS_FUNC(syr2)(const char *uplo, const int *n, const RealScalar *palpha, const RealScalar *px, const int *incx, const RealScalar *py, const int *incy, RealScalar *pc, const int *ldc)\n{\n  typedef void (*functype)(int, Scalar*, int, const Scalar*, const Scalar*, Scalar);\n  static const functype func[2] = {\n    // array index: UP\n    (internal::rank2_update_selector<Scalar,int,Upper>::run),\n    // array index: LO\n    (internal::rank2_update_selector<Scalar,int,Lower>::run),\n  };\n\n  const Scalar* x = reinterpret_cast<const Scalar*>(px);\n  const Scalar* y = reinterpret_cast<const Scalar*>(py);\n  Scalar* c = reinterpret_cast<Scalar*>(pc);\n  Scalar alpha = *reinterpret_cast<const Scalar*>(palpha);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  else if(*incy==0)                                                   info = 7;\n  else if(*ldc<std::max(1,*n))                                        info = 9;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"SYR2 \",&info,6);\n\n  if(alpha==Scalar(0))\n    return 1;\n\n  const Scalar* x_cpy = get_compact_vector(x,*n,*incx);\n  const Scalar* y_cpy = get_compact_vector(y,*n,*incy);\n\n  int code = UPLO(*uplo);\n  if(code>=2 || func[code]==0)\n    return 0;\n\n  func[code](*n, c, *ldc, x_cpy, y_cpy, alpha);\n\n  if(x_cpy!=x)  delete[] x_cpy;\n  if(y_cpy!=y)  delete[] y_cpy;\n\n//   int code = UPLO(*uplo);\n//   if(code>=2 || func[code]==0)\n//     return 0;\n\n//   func[code](*n, a, *inca, b, *incb, c, *ldc, alpha);\n  return 1;\n}\n\n/**  DSBMV  performs the matrix-vector  operation\n  *\n  *     y := alpha*A*x + beta*y,\n  *\n  *  where alpha and beta are scalars, x and y are n element vectors and\n  *  A is an n by n symmetric band matrix, with k super-diagonals.\n  */\n// int EIGEN_BLAS_FUNC(sbmv)( char *uplo, int *n, int *k, RealScalar *alpha, RealScalar *a, int *lda,\n//                            RealScalar *x, int *incx, RealScalar *beta, RealScalar *y, int *incy)\n// {\n//   return 1;\n// }\n\n\n/**  DSPMV  performs the matrix-vector operation\n  *\n  *     y := alpha*A*x + beta*y,\n  *\n  *  where alpha and beta are scalars, x and y are n element vectors and\n  *  A is an n by n symmetric matrix, supplied in packed form.\n  *\n  */\n// int EIGEN_BLAS_FUNC(spmv)(char *uplo, int *n, RealScalar *alpha, RealScalar *ap, RealScalar *x, int *incx, RealScalar *beta, RealScalar *y, int *incy)\n// {\n//   return 1;\n// }\n\n/**  DSPR    performs the symmetric rank 1 operation\n  *\n  *     A := alpha*x*x' + A,\n  *\n  *  where alpha is a real scalar, x is an n element vector and A is an\n  *  n by n symmetric matrix, supplied in packed form.\n  */\nint EIGEN_BLAS_FUNC(spr)(char *uplo, int *n, Scalar *palpha, Scalar *px, int *incx, Scalar *pap)\n{\n  typedef void (*functype)(int, Scalar*, const Scalar*, Scalar);\n  static const functype func[2] = {\n    // array index: UP\n    (internal::selfadjoint_packed_rank1_update<Scalar,int,ColMajor,Upper,false,false>::run),\n    // array index: LO\n    (internal::selfadjoint_packed_rank1_update<Scalar,int,ColMajor,Lower,false,false>::run),\n  };\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* ap = reinterpret_cast<Scalar*>(pap);\n  Scalar alpha = *reinterpret_cast<Scalar*>(palpha);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"SPR  \",&info,6);\n\n  if(alpha==Scalar(0))\n    return 1;\n\n  Scalar* x_cpy = get_compact_vector(x, *n, *incx);\n\n  int code = UPLO(*uplo);\n  if(code>=2 || func[code]==0)\n    return 0;\n\n  func[code](*n, ap, x_cpy, alpha);\n\n  if(x_cpy!=x)  delete[] x_cpy;\n\n  return 1;\n}\n\n/**  DSPR2  performs the symmetric rank 2 operation\n  *\n  *     A := alpha*x*y' + alpha*y*x' + A,\n  *\n  *  where alpha is a scalar, x and y are n element vectors and A is an\n  *  n by n symmetric matrix, supplied in packed form.\n  */\nint EIGEN_BLAS_FUNC(spr2)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pap)\n{\n  typedef void (*functype)(int, Scalar*, const Scalar*, const Scalar*, Scalar);\n  static const functype func[2] = {\n    // array index: UP\n    (internal::packed_rank2_update_selector<Scalar,int,Upper>::run),\n    // array index: LO\n    (internal::packed_rank2_update_selector<Scalar,int,Lower>::run),\n  };\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar* ap = reinterpret_cast<Scalar*>(pap);\n  Scalar alpha = *reinterpret_cast<Scalar*>(palpha);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  else if(*incy==0)                                                   info = 7;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"SPR2 \",&info,6);\n\n  if(alpha==Scalar(0))\n    return 1;\n\n  Scalar* x_cpy = get_compact_vector(x, *n, *incx);\n  Scalar* y_cpy = get_compact_vector(y, *n, *incy);\n\n  int code = UPLO(*uplo);\n  if(code>=2 || func[code]==0)\n    return 0;\n\n  func[code](*n, ap, x_cpy, y_cpy, alpha);\n\n  if(x_cpy!=x)  delete[] x_cpy;\n  if(y_cpy!=y)  delete[] y_cpy;\n\n  return 1;\n}\n\n/**  DGER   performs the rank 1 operation\n  *\n  *     A := alpha*x*y' + A,\n  *\n  *  where alpha is a scalar, x is an m element vector, y is an n element\n  *  vector and A is an m by n matrix.\n  */\nint EIGEN_BLAS_FUNC(ger)(int *m, int *n, Scalar *palpha, Scalar *px, int *incx, Scalar *py, int *incy, Scalar *pa, int *lda)\n{\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  Scalar alpha = *reinterpret_cast<Scalar*>(palpha);\n\n  int info = 0;\n       if(*m<0)                                                       info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  else if(*incy==0)                                                   info = 7;\n  else if(*lda<std::max(1,*m))                                        info = 9;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"GER  \",&info,6);\n\n  if(alpha==Scalar(0))\n    return 1;\n\n  Scalar* x_cpy = get_compact_vector(x,*m,*incx);\n  Scalar* y_cpy = get_compact_vector(y,*n,*incy);\n\n  internal::general_rank1_update<Scalar,int,ColMajor,false,false>::run(*m, *n, a, *lda, x_cpy, y_cpy, alpha);\n\n  if(x_cpy!=x)  delete[] x_cpy;\n  if(y_cpy!=y)  delete[] y_cpy;\n\n  return 1;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/level3_impl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n#include <iostream>\n#include \"common.h\"\n\nint EIGEN_BLAS_FUNC(gemm)(const char *opa, const char *opb, const int *m, const int *n, const int *k, const RealScalar *palpha,\n                          const RealScalar *pa, const int *lda, const RealScalar *pb, const int *ldb, const RealScalar *pbeta, RealScalar *pc, const int *ldc)\n{\n//   std::cerr << \"in gemm \" << *opa << \" \" << *opb << \" \" << *m << \" \" << *n << \" \" << *k << \" \" << *lda << \" \" << *ldb << \" \" << *ldc << \" \" << *palpha << \" \" << *pbeta << \"\\n\";\n  typedef void (*functype)(DenseIndex, DenseIndex, DenseIndex, const Scalar *, DenseIndex, const Scalar *, DenseIndex, Scalar *, DenseIndex, DenseIndex, Scalar, internal::level3_blocking<Scalar,Scalar>&, Eigen::internal::GemmParallelInfo<DenseIndex>*);\n  static const functype func[12] = {\n    // array index: NOTR  | (NOTR << 2)\n    (internal::general_matrix_matrix_product<DenseIndex,Scalar,ColMajor,false,Scalar,ColMajor,false,ColMajor,1>::run),\n    // array index: TR    | (NOTR << 2)\n    (internal::general_matrix_matrix_product<DenseIndex,Scalar,RowMajor,false,Scalar,ColMajor,false,ColMajor,1>::run),\n    // array index: ADJ   | (NOTR << 2)\n    (internal::general_matrix_matrix_product<DenseIndex,Scalar,RowMajor,Conj, Scalar,ColMajor,false,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (TR   << 2)\n    (internal::general_matrix_matrix_product<DenseIndex,Scalar,ColMajor,false,Scalar,RowMajor,false,ColMajor,1>::run),\n    // array index: TR    | (TR   << 2)\n    (internal::general_matrix_matrix_product<DenseIndex,Scalar,RowMajor,false,Scalar,RowMajor,false,ColMajor,1>::run),\n    // array index: ADJ   | (TR   << 2)\n    (internal::general_matrix_matrix_product<DenseIndex,Scalar,RowMajor,Conj, Scalar,RowMajor,false,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (ADJ  << 2)\n    (internal::general_matrix_matrix_product<DenseIndex,Scalar,ColMajor,false,Scalar,RowMajor,Conj, ColMajor,1>::run),\n    // array index: TR    | (ADJ  << 2)\n    (internal::general_matrix_matrix_product<DenseIndex,Scalar,RowMajor,false,Scalar,RowMajor,Conj, ColMajor,1>::run),\n    // array index: ADJ   | (ADJ  << 2)\n    (internal::general_matrix_matrix_product<DenseIndex,Scalar,RowMajor,Conj, Scalar,RowMajor,Conj, ColMajor,1>::run),\n    0\n  };\n\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  const Scalar* b = reinterpret_cast<const Scalar*>(pb);\n  Scalar* c = reinterpret_cast<Scalar*>(pc);\n  Scalar alpha  = *reinterpret_cast<const Scalar*>(palpha);\n  Scalar beta   = *reinterpret_cast<const Scalar*>(pbeta);\n\n  int info = 0;\n  if(OP(*opa)==INVALID)                                               info = 1;\n  else if(OP(*opb)==INVALID)                                          info = 2;\n  else if(*m<0)                                                       info = 3;\n  else if(*n<0)                                                       info = 4;\n  else if(*k<0)                                                       info = 5;\n  else if(*lda<std::max(1,(OP(*opa)==NOTR)?*m:*k))                    info = 8;\n  else if(*ldb<std::max(1,(OP(*opb)==NOTR)?*k:*n))                    info = 10;\n  else if(*ldc<std::max(1,*m))                                        info = 13;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"GEMM \",&info,6);\n\n  if (*m == 0 || *n == 0)\n    return 0;\n\n  if(beta!=Scalar(1))\n  {\n    if(beta==Scalar(0)) matrix(c, *m, *n, *ldc).setZero();\n    else                matrix(c, *m, *n, *ldc) *= beta;\n  }\n\n  if(*k == 0)\n    return 0;\n\n  internal::gemm_blocking_space<ColMajor,Scalar,Scalar,Dynamic,Dynamic,Dynamic> blocking(*m,*n,*k,1,true);\n\n  int code = OP(*opa) | (OP(*opb) << 2);\n  func[code](*m, *n, *k, a, *lda, b, *ldb, c, 1, *ldc, alpha, blocking, 0);\n  return 0;\n}\n\nint EIGEN_BLAS_FUNC(trsm)(const char *side, const char *uplo, const char *opa, const char *diag, const int *m, const int *n,\n                          const RealScalar *palpha,  const RealScalar *pa, const int *lda, RealScalar *pb, const int *ldb)\n{\n//   std::cerr << \"in trsm \" << *side << \" \" << *uplo << \" \" << *opa << \" \" << *diag << \" \" << *m << \",\" << *n << \" \" << *palpha << \" \" << *lda << \" \" << *ldb<< \"\\n\";\n  typedef void (*functype)(DenseIndex, DenseIndex, const Scalar *, DenseIndex, Scalar *, DenseIndex, DenseIndex, internal::level3_blocking<Scalar,Scalar>&);\n  static const functype func[32] = {\n    // array index: NOTR  | (LEFT  << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Upper|0,          false,ColMajor,ColMajor,1>::run),\n    // array index: TR    | (LEFT  << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Lower|0,          false,RowMajor,ColMajor,1>::run),\n    // array index: ADJ   | (LEFT  << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Lower|0,          Conj, RowMajor,ColMajor,1>::run),\\\n    0,\n    // array index: NOTR  | (RIGHT << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Upper|0,          false,ColMajor,ColMajor,1>::run),\n    // array index: TR    | (RIGHT << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Lower|0,          false,RowMajor,ColMajor,1>::run),\n    // array index: ADJ   | (RIGHT << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Lower|0,          Conj, RowMajor,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (LEFT  << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Lower|0,          false,ColMajor,ColMajor,1>::run),\n    // array index: TR    | (LEFT  << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Upper|0,          false,RowMajor,ColMajor,1>::run),\n    // array index: ADJ   | (LEFT  << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Upper|0,          Conj, RowMajor,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (RIGHT << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Lower|0,          false,ColMajor,ColMajor,1>::run),\n    // array index: TR    | (RIGHT << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Upper|0,          false,RowMajor,ColMajor,1>::run),\n    // array index: ADJ   | (RIGHT << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Upper|0,          Conj, RowMajor,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (LEFT  << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Upper|UnitDiag,false,ColMajor,ColMajor,1>::run),\n    // array index: TR    | (LEFT  << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Lower|UnitDiag,false,RowMajor,ColMajor,1>::run),\n    // array index: ADJ   | (LEFT  << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Lower|UnitDiag,Conj, RowMajor,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (RIGHT << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Upper|UnitDiag,false,ColMajor,ColMajor,1>::run),\n    // array index: TR    | (RIGHT << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Lower|UnitDiag,false,RowMajor,ColMajor,1>::run),\n    // array index: ADJ   | (RIGHT << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Lower|UnitDiag,Conj, RowMajor,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (LEFT  << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Lower|UnitDiag,false,ColMajor,ColMajor,1>::run),\n    // array index: TR    | (LEFT  << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Upper|UnitDiag,false,RowMajor,ColMajor,1>::run),\n    // array index: ADJ   | (LEFT  << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Upper|UnitDiag,Conj, RowMajor,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (RIGHT << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Lower|UnitDiag,false,ColMajor,ColMajor,1>::run),\n    // array index: TR    | (RIGHT << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Upper|UnitDiag,false,RowMajor,ColMajor,1>::run),\n    // array index: ADJ   | (RIGHT << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Upper|UnitDiag,Conj, RowMajor,ColMajor,1>::run),\n    0\n  };\n\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  Scalar* b = reinterpret_cast<Scalar*>(pb);\n  Scalar  alpha = *reinterpret_cast<const Scalar*>(palpha);\n\n  int info = 0;\n  if(SIDE(*side)==INVALID)                                            info = 1;\n  else if(UPLO(*uplo)==INVALID)                                       info = 2;\n  else if(OP(*opa)==INVALID)                                          info = 3;\n  else if(DIAG(*diag)==INVALID)                                       info = 4;\n  else if(*m<0)                                                       info = 5;\n  else if(*n<0)                                                       info = 6;\n  else if(*lda<std::max(1,(SIDE(*side)==LEFT)?*m:*n))                 info = 9;\n  else if(*ldb<std::max(1,*m))                                        info = 11;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"TRSM \",&info,6);\n\n  if(*m==0 || *n==0)\n    return 0;\n\n  int code = OP(*opa) | (SIDE(*side) << 2) | (UPLO(*uplo) << 3) | (DIAG(*diag) << 4);\n\n  if(SIDE(*side)==LEFT)\n  {\n    internal::gemm_blocking_space<ColMajor,Scalar,Scalar,Dynamic,Dynamic,Dynamic,4> blocking(*m,*n,*m,1,false);\n    func[code](*m, *n, a, *lda, b, 1, *ldb, blocking);\n  }\n  else\n  {\n    internal::gemm_blocking_space<ColMajor,Scalar,Scalar,Dynamic,Dynamic,Dynamic,4> blocking(*m,*n,*n,1,false);\n    func[code](*n, *m, a, *lda, b, 1, *ldb, blocking);\n  }\n\n  if(alpha!=Scalar(1))\n    matrix(b,*m,*n,*ldb) *= alpha;\n\n  return 0;\n}\n\n\n// b = alpha*op(a)*b  for side = 'L'or'l'\n// b = alpha*b*op(a)  for side = 'R'or'r'\nint EIGEN_BLAS_FUNC(trmm)(const char *side, const char *uplo, const char *opa, const char *diag, const int *m, const int *n,\n                          const RealScalar *palpha, const RealScalar *pa, const int *lda, RealScalar *pb, const int *ldb)\n{\n//   std::cerr << \"in trmm \" << *side << \" \" << *uplo << \" \" << *opa << \" \" << *diag << \" \" << *m << \" \" << *n << \" \" << *lda << \" \" << *ldb << \" \" << *palpha << \"\\n\";\n  typedef void (*functype)(DenseIndex, DenseIndex, DenseIndex, const Scalar *, DenseIndex, const Scalar *, DenseIndex, Scalar *, DenseIndex, DenseIndex, const Scalar&, internal::level3_blocking<Scalar,Scalar>&);\n  static const functype func[32] = {\n    // array index: NOTR  | (LEFT  << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|0,          true, ColMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: TR    | (LEFT  << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|0,          true, RowMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: ADJ   | (LEFT  << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|0,          true, RowMajor,Conj, ColMajor,false,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (RIGHT << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|0,          false,ColMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: TR    | (RIGHT << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|0,          false,ColMajor,false,RowMajor,false,ColMajor,1>::run),\n    // array index: ADJ   | (RIGHT << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|0,          false,ColMajor,false,RowMajor,Conj, ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (LEFT  << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|0,          true, ColMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: TR    | (LEFT  << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|0,          true, RowMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: ADJ   | (LEFT  << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|0,          true, RowMajor,Conj, ColMajor,false,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (RIGHT << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|0,          false,ColMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: TR    | (RIGHT << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|0,          false,ColMajor,false,RowMajor,false,ColMajor,1>::run),\n    // array index: ADJ   | (RIGHT << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|0,          false,ColMajor,false,RowMajor,Conj, ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (LEFT  << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|UnitDiag,true, ColMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: TR    | (LEFT  << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|UnitDiag,true, RowMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: ADJ   | (LEFT  << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|UnitDiag,true, RowMajor,Conj, ColMajor,false,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (RIGHT << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|UnitDiag,false,ColMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: TR    | (RIGHT << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|UnitDiag,false,ColMajor,false,RowMajor,false,ColMajor,1>::run),\n    // array index: ADJ   | (RIGHT << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|UnitDiag,false,ColMajor,false,RowMajor,Conj, ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (LEFT  << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|UnitDiag,true, ColMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: TR    | (LEFT  << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|UnitDiag,true, RowMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: ADJ   | (LEFT  << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|UnitDiag,true, RowMajor,Conj, ColMajor,false,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (RIGHT << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|UnitDiag,false,ColMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: TR    | (RIGHT << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|UnitDiag,false,ColMajor,false,RowMajor,false,ColMajor,1>::run),\n    // array index: ADJ   | (RIGHT << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|UnitDiag,false,ColMajor,false,RowMajor,Conj, ColMajor,1>::run),\n    0\n  };\n\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  Scalar* b = reinterpret_cast<Scalar*>(pb);\n  Scalar  alpha = *reinterpret_cast<const Scalar*>(palpha);\n\n  int info = 0;\n  if(SIDE(*side)==INVALID)                                            info = 1;\n  else if(UPLO(*uplo)==INVALID)                                       info = 2;\n  else if(OP(*opa)==INVALID)                                          info = 3;\n  else if(DIAG(*diag)==INVALID)                                       info = 4;\n  else if(*m<0)                                                       info = 5;\n  else if(*n<0)                                                       info = 6;\n  else if(*lda<std::max(1,(SIDE(*side)==LEFT)?*m:*n))                 info = 9;\n  else if(*ldb<std::max(1,*m))                                        info = 11;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"TRMM \",&info,6);\n\n  int code = OP(*opa) | (SIDE(*side) << 2) | (UPLO(*uplo) << 3) | (DIAG(*diag) << 4);\n\n  if(*m==0 || *n==0)\n    return 1;\n\n  // FIXME find a way to avoid this copy\n  Matrix<Scalar,Dynamic,Dynamic,ColMajor> tmp = matrix(b,*m,*n,*ldb);\n  matrix(b,*m,*n,*ldb).setZero();\n\n  if(SIDE(*side)==LEFT)\n  {\n    internal::gemm_blocking_space<ColMajor,Scalar,Scalar,Dynamic,Dynamic,Dynamic,4> blocking(*m,*n,*m,1,false);\n    func[code](*m, *n, *m, a, *lda, tmp.data(), tmp.outerStride(), b, 1, *ldb, alpha, blocking);\n  }\n  else\n  {\n    internal::gemm_blocking_space<ColMajor,Scalar,Scalar,Dynamic,Dynamic,Dynamic,4> blocking(*m,*n,*n,1,false);\n    func[code](*m, *n, *n, tmp.data(), tmp.outerStride(), a, *lda, b, 1, *ldb, alpha, blocking);\n  }\n  return 1;\n}\n\n// c = alpha*a*b + beta*c  for side = 'L'or'l'\n// c = alpha*b*a + beta*c  for side = 'R'or'r\nint EIGEN_BLAS_FUNC(symm)(const char *side, const char *uplo, const int *m, const int *n, const RealScalar *palpha,\n                          const RealScalar *pa, const int *lda, const RealScalar *pb, const int *ldb, const RealScalar *pbeta, RealScalar *pc, const int *ldc)\n{\n//   std::cerr << \"in symm \" << *side << \" \" << *uplo << \" \" << *m << \"x\" << *n << \" lda:\" << *lda << \" ldb:\" << *ldb << \" ldc:\" << *ldc << \" alpha:\" << *palpha << \" beta:\" << *pbeta << \"\\n\";\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  const Scalar* b = reinterpret_cast<const Scalar*>(pb);\n  Scalar* c = reinterpret_cast<Scalar*>(pc);\n  Scalar alpha = *reinterpret_cast<const Scalar*>(palpha);\n  Scalar beta  = *reinterpret_cast<const Scalar*>(pbeta);\n\n  int info = 0;\n  if(SIDE(*side)==INVALID)                                            info = 1;\n  else if(UPLO(*uplo)==INVALID)                                       info = 2;\n  else if(*m<0)                                                       info = 3;\n  else if(*n<0)                                                       info = 4;\n  else if(*lda<std::max(1,(SIDE(*side)==LEFT)?*m:*n))                 info = 7;\n  else if(*ldb<std::max(1,*m))                                        info = 9;\n  else if(*ldc<std::max(1,*m))                                        info = 12;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"SYMM \",&info,6);\n\n  if(beta!=Scalar(1))\n  {\n    if(beta==Scalar(0)) matrix(c, *m, *n, *ldc).setZero();\n    else                matrix(c, *m, *n, *ldc) *= beta;\n  }\n\n  if(*m==0 || *n==0)\n  {\n    return 1;\n  }\n\n  int size = (SIDE(*side)==LEFT) ? (*m) : (*n);\n  #if ISCOMPLEX\n  // FIXME add support for symmetric complex matrix\n  Matrix<Scalar,Dynamic,Dynamic,ColMajor> matA(size,size);\n  if(UPLO(*uplo)==UP)\n  {\n    matA.triangularView<Upper>() = matrix(a,size,size,*lda);\n    matA.triangularView<Lower>() = matrix(a,size,size,*lda).transpose();\n  }\n  else if(UPLO(*uplo)==LO)\n  {\n    matA.triangularView<Lower>() = matrix(a,size,size,*lda);\n    matA.triangularView<Upper>() = matrix(a,size,size,*lda).transpose();\n  }\n  if(SIDE(*side)==LEFT)\n    matrix(c, *m, *n, *ldc) += alpha * matA * matrix(b, *m, *n, *ldb);\n  else if(SIDE(*side)==RIGHT)\n    matrix(c, *m, *n, *ldc) += alpha * matrix(b, *m, *n, *ldb) * matA;\n  #else\n  internal::gemm_blocking_space<ColMajor,Scalar,Scalar,Dynamic,Dynamic,Dynamic> blocking(*m,*n,size,1,false);\n\n  if(SIDE(*side)==LEFT)\n    if(UPLO(*uplo)==UP)       internal::product_selfadjoint_matrix<Scalar, DenseIndex, RowMajor,true,false, ColMajor,false,false, ColMajor,1>::run(*m, *n, a, *lda, b, *ldb, c, 1, *ldc, alpha, blocking);\n    else if(UPLO(*uplo)==LO)  internal::product_selfadjoint_matrix<Scalar, DenseIndex, ColMajor,true,false, ColMajor,false,false, ColMajor,1>::run(*m, *n, a, *lda, b, *ldb, c, 1, *ldc, alpha, blocking);\n    else                      return 0;\n  else if(SIDE(*side)==RIGHT)\n    if(UPLO(*uplo)==UP)       internal::product_selfadjoint_matrix<Scalar, DenseIndex, ColMajor,false,false, RowMajor,true,false, ColMajor,1>::run(*m, *n, b, *ldb, a, *lda, c, 1, *ldc, alpha, blocking);\n    else if(UPLO(*uplo)==LO)  internal::product_selfadjoint_matrix<Scalar, DenseIndex, ColMajor,false,false, ColMajor,true,false, ColMajor,1>::run(*m, *n, b, *ldb, a, *lda, c, 1, *ldc, alpha, blocking);\n    else                      return 0;\n  else\n    return 0;\n  #endif\n\n  return 0;\n}\n\n// c = alpha*a*a' + beta*c  for op = 'N'or'n'\n// c = alpha*a'*a + beta*c  for op = 'T'or't','C'or'c'\nint EIGEN_BLAS_FUNC(syrk)(const char *uplo, const char *op, const int *n, const int *k,\n                          const RealScalar *palpha, const RealScalar *pa, const int *lda, const RealScalar *pbeta, RealScalar *pc, const int *ldc)\n{\n//   std::cerr << \"in syrk \" << *uplo << \" \" << *op << \" \" << *n << \" \" << *k << \" \" << *palpha << \" \" << *lda << \" \" << *pbeta << \" \" << *ldc << \"\\n\";\n  #if !ISCOMPLEX\n  typedef void (*functype)(DenseIndex, DenseIndex, const Scalar *, DenseIndex, const Scalar *, DenseIndex, Scalar *, DenseIndex, DenseIndex, const Scalar&, internal::level3_blocking<Scalar,Scalar>&);\n  static const functype func[8] = {\n    // array index: NOTR  | (UP << 2)\n    (internal::general_matrix_matrix_triangular_product<DenseIndex,Scalar,ColMajor,false,Scalar,RowMajor,ColMajor,Conj, 1, Upper>::run),\n    // array index: TR    | (UP << 2)\n    (internal::general_matrix_matrix_triangular_product<DenseIndex,Scalar,RowMajor,false,Scalar,ColMajor,ColMajor,Conj, 1, Upper>::run),\n    // array index: ADJ   | (UP << 2)\n    (internal::general_matrix_matrix_triangular_product<DenseIndex,Scalar,RowMajor,Conj, Scalar,ColMajor,ColMajor,false,1, Upper>::run),\n    0,\n    // array index: NOTR  | (LO << 2)\n    (internal::general_matrix_matrix_triangular_product<DenseIndex,Scalar,ColMajor,false,Scalar,RowMajor,ColMajor,Conj, 1, Lower>::run),\n    // array index: TR    | (LO << 2)\n    (internal::general_matrix_matrix_triangular_product<DenseIndex,Scalar,RowMajor,false,Scalar,ColMajor,ColMajor,Conj, 1, Lower>::run),\n    // array index: ADJ   | (LO << 2)\n    (internal::general_matrix_matrix_triangular_product<DenseIndex,Scalar,RowMajor,Conj, Scalar,ColMajor,ColMajor,false,1, Lower>::run),\n    0\n  };\n  #endif\n\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  Scalar* c = reinterpret_cast<Scalar*>(pc);\n  Scalar alpha = *reinterpret_cast<const Scalar*>(palpha);\n  Scalar beta  = *reinterpret_cast<const Scalar*>(pbeta);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(OP(*op)==INVALID || (ISCOMPLEX && OP(*op)==ADJ) )           info = 2;\n  else if(*n<0)                                                       info = 3;\n  else if(*k<0)                                                       info = 4;\n  else if(*lda<std::max(1,(OP(*op)==NOTR)?*n:*k))                     info = 7;\n  else if(*ldc<std::max(1,*n))                                        info = 10;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"SYRK \",&info,6);\n\n  if(beta!=Scalar(1))\n  {\n    if(UPLO(*uplo)==UP)\n      if(beta==Scalar(0)) matrix(c, *n, *n, *ldc).triangularView<Upper>().setZero();\n      else                matrix(c, *n, *n, *ldc).triangularView<Upper>() *= beta;\n    else\n      if(beta==Scalar(0)) matrix(c, *n, *n, *ldc).triangularView<Lower>().setZero();\n      else                matrix(c, *n, *n, *ldc).triangularView<Lower>() *= beta;\n  }\n\n  if(*n==0 || *k==0)\n    return 0;\n\n  #if ISCOMPLEX\n  // FIXME add support for symmetric complex matrix\n  if(UPLO(*uplo)==UP)\n  {\n    if(OP(*op)==NOTR)\n      matrix(c, *n, *n, *ldc).triangularView<Upper>() += alpha * matrix(a,*n,*k,*lda) * matrix(a,*n,*k,*lda).transpose();\n    else\n      matrix(c, *n, *n, *ldc).triangularView<Upper>() += alpha * matrix(a,*k,*n,*lda).transpose() * matrix(a,*k,*n,*lda);\n  }\n  else\n  {\n    if(OP(*op)==NOTR)\n      matrix(c, *n, *n, *ldc).triangularView<Lower>() += alpha * matrix(a,*n,*k,*lda) * matrix(a,*n,*k,*lda).transpose();\n    else\n      matrix(c, *n, *n, *ldc).triangularView<Lower>() += alpha * matrix(a,*k,*n,*lda).transpose() * matrix(a,*k,*n,*lda);\n  }\n  #else\n  internal::gemm_blocking_space<ColMajor,Scalar,Scalar,Dynamic,Dynamic,Dynamic> blocking(*n,*n,*k,1,false);\n\n  int code = OP(*op) | (UPLO(*uplo) << 2);\n  func[code](*n, *k, a, *lda, a, *lda, c, 1, *ldc, alpha, blocking);\n  #endif\n\n  return 0;\n}\n\n// c = alpha*a*b' + alpha*b*a' + beta*c  for op = 'N'or'n'\n// c = alpha*a'*b + alpha*b'*a + beta*c  for op = 'T'or't'\nint EIGEN_BLAS_FUNC(syr2k)(const char *uplo, const char *op, const int *n, const int *k, const RealScalar *palpha,\n                           const RealScalar *pa, const int *lda, const RealScalar *pb, const int *ldb, const RealScalar *pbeta, RealScalar *pc, const int *ldc)\n{\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  const Scalar* b = reinterpret_cast<const Scalar*>(pb);\n  Scalar* c = reinterpret_cast<Scalar*>(pc);\n  Scalar alpha = *reinterpret_cast<const Scalar*>(palpha);\n  Scalar beta  = *reinterpret_cast<const Scalar*>(pbeta);\n\n//   std::cerr << \"in syr2k \" << *uplo << \" \" << *op << \" \" << *n << \" \" << *k << \" \" << alpha << \" \" << *lda << \" \" << *ldb << \" \" << beta << \" \" << *ldc << \"\\n\";\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(OP(*op)==INVALID || (ISCOMPLEX && OP(*op)==ADJ) )           info = 2;\n  else if(*n<0)                                                       info = 3;\n  else if(*k<0)                                                       info = 4;\n  else if(*lda<std::max(1,(OP(*op)==NOTR)?*n:*k))                     info = 7;\n  else if(*ldb<std::max(1,(OP(*op)==NOTR)?*n:*k))                     info = 9;\n  else if(*ldc<std::max(1,*n))                                        info = 12;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"SYR2K\",&info,6);\n\n  if(beta!=Scalar(1))\n  {\n    if(UPLO(*uplo)==UP)\n      if(beta==Scalar(0)) matrix(c, *n, *n, *ldc).triangularView<Upper>().setZero();\n      else                matrix(c, *n, *n, *ldc).triangularView<Upper>() *= beta;\n    else\n      if(beta==Scalar(0)) matrix(c, *n, *n, *ldc).triangularView<Lower>().setZero();\n      else                matrix(c, *n, *n, *ldc).triangularView<Lower>() *= beta;\n  }\n\n  if(*k==0)\n    return 1;\n\n  if(OP(*op)==NOTR)\n  {\n    if(UPLO(*uplo)==UP)\n    {\n      matrix(c, *n, *n, *ldc).triangularView<Upper>()\n        += alpha *matrix(a, *n, *k, *lda)*matrix(b, *n, *k, *ldb).transpose()\n        +  alpha*matrix(b, *n, *k, *ldb)*matrix(a, *n, *k, *lda).transpose();\n    }\n    else if(UPLO(*uplo)==LO)\n      matrix(c, *n, *n, *ldc).triangularView<Lower>()\n        += alpha*matrix(a, *n, *k, *lda)*matrix(b, *n, *k, *ldb).transpose()\n        +  alpha*matrix(b, *n, *k, *ldb)*matrix(a, *n, *k, *lda).transpose();\n  }\n  else if(OP(*op)==TR || OP(*op)==ADJ)\n  {\n    if(UPLO(*uplo)==UP)\n      matrix(c, *n, *n, *ldc).triangularView<Upper>()\n        += alpha*matrix(a, *k, *n, *lda).transpose()*matrix(b, *k, *n, *ldb)\n        +  alpha*matrix(b, *k, *n, *ldb).transpose()*matrix(a, *k, *n, *lda);\n    else if(UPLO(*uplo)==LO)\n      matrix(c, *n, *n, *ldc).triangularView<Lower>()\n        += alpha*matrix(a, *k, *n, *lda).transpose()*matrix(b, *k, *n, *ldb)\n        +  alpha*matrix(b, *k, *n, *ldb).transpose()*matrix(a, *k, *n, *lda);\n  }\n\n  return 0;\n}\n\n\n#if ISCOMPLEX\n\n// c = alpha*a*b + beta*c  for side = 'L'or'l'\n// c = alpha*b*a + beta*c  for side = 'R'or'r\nint EIGEN_BLAS_FUNC(hemm)(const char *side, const char *uplo, const int *m, const int *n, const RealScalar *palpha,\n                          const RealScalar *pa, const int *lda, const RealScalar *pb, const int *ldb, const RealScalar *pbeta, RealScalar *pc, const int *ldc)\n{\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  const Scalar* b = reinterpret_cast<const Scalar*>(pb);\n  Scalar* c = reinterpret_cast<Scalar*>(pc);\n  Scalar alpha = *reinterpret_cast<const Scalar*>(palpha);\n  Scalar beta  = *reinterpret_cast<const Scalar*>(pbeta);\n\n//   std::cerr << \"in hemm \" << *side << \" \" << *uplo << \" \" << *m << \" \" << *n << \" \" << alpha << \" \" << *lda << \" \" << beta << \" \" << *ldc << \"\\n\";\n\n  int info = 0;\n  if(SIDE(*side)==INVALID)                                            info = 1;\n  else if(UPLO(*uplo)==INVALID)                                       info = 2;\n  else if(*m<0)                                                       info = 3;\n  else if(*n<0)                                                       info = 4;\n  else if(*lda<std::max(1,(SIDE(*side)==LEFT)?*m:*n))                 info = 7;\n  else if(*ldb<std::max(1,*m))                                        info = 9;\n  else if(*ldc<std::max(1,*m))                                        info = 12;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"HEMM \",&info,6);\n\n  if(beta==Scalar(0))       matrix(c, *m, *n, *ldc).setZero();\n  else if(beta!=Scalar(1))  matrix(c, *m, *n, *ldc) *= beta;\n\n  if(*m==0 || *n==0)\n  {\n    return 1;\n  }\n\n  int size = (SIDE(*side)==LEFT) ? (*m) : (*n);\n  internal::gemm_blocking_space<ColMajor,Scalar,Scalar,Dynamic,Dynamic,Dynamic> blocking(*m,*n,size,1,false);\n\n  if(SIDE(*side)==LEFT)\n  {\n    if(UPLO(*uplo)==UP)       internal::product_selfadjoint_matrix<Scalar,DenseIndex,RowMajor,true,Conj,  ColMajor,false,false, ColMajor, 1>\n                                ::run(*m, *n, a, *lda, b, *ldb, c, 1, *ldc, alpha, blocking);\n    else if(UPLO(*uplo)==LO)  internal::product_selfadjoint_matrix<Scalar,DenseIndex,ColMajor,true,false, ColMajor,false,false, ColMajor,1>\n                                ::run(*m, *n, a, *lda, b, *ldb, c, 1, *ldc, alpha, blocking);\n    else                      return 0;\n  }\n  else if(SIDE(*side)==RIGHT)\n  {\n    if(UPLO(*uplo)==UP)       matrix(c,*m,*n,*ldc) += alpha * matrix(b,*m,*n,*ldb) * matrix(a,*n,*n,*lda).selfadjointView<Upper>();/*internal::product_selfadjoint_matrix<Scalar,DenseIndex,ColMajor,false,false, RowMajor,true,Conj,  ColMajor, 1>\n                                ::run(*m, *n, b, *ldb, a, *lda, c, 1, *ldc, alpha, blocking);*/\n    else if(UPLO(*uplo)==LO)  internal::product_selfadjoint_matrix<Scalar,DenseIndex,ColMajor,false,false, ColMajor,true,false, ColMajor,1>\n                                ::run(*m, *n, b, *ldb, a, *lda, c, 1, *ldc, alpha, blocking);\n    else                      return 0;\n  }\n  else\n  {\n    return 0;\n  }\n\n  return 0;\n}\n\n// c = alpha*a*conj(a') + beta*c  for op = 'N'or'n'\n// c = alpha*conj(a')*a + beta*c  for op  = 'C'or'c'\nint EIGEN_BLAS_FUNC(herk)(const char *uplo, const char *op, const int *n, const int *k,\n                          const RealScalar *palpha, const RealScalar *pa, const int *lda, const RealScalar *pbeta, RealScalar *pc, const int *ldc)\n{\n//   std::cerr << \"in herk \" << *uplo << \" \" << *op << \" \" << *n << \" \" << *k << \" \" << *palpha << \" \" << *lda << \" \" << *pbeta << \" \" << *ldc << \"\\n\";\n\n  typedef void (*functype)(DenseIndex, DenseIndex, const Scalar *, DenseIndex, const Scalar *, DenseIndex, Scalar *, DenseIndex, DenseIndex, const Scalar&, internal::level3_blocking<Scalar,Scalar>&);\n  static const functype func[8] = {\n    // array index: NOTR  | (UP << 2)\n    (internal::general_matrix_matrix_triangular_product<DenseIndex,Scalar,ColMajor,false,Scalar,RowMajor,Conj, ColMajor,1,Upper>::run),\n    0,\n    // array index: ADJ   | (UP << 2)\n    (internal::general_matrix_matrix_triangular_product<DenseIndex,Scalar,RowMajor,Conj, Scalar,ColMajor,false,ColMajor,1,Upper>::run),\n    0,\n    // array index: NOTR  | (LO << 2)\n    (internal::general_matrix_matrix_triangular_product<DenseIndex,Scalar,ColMajor,false,Scalar,RowMajor,Conj, ColMajor,1,Lower>::run),\n    0,\n    // array index: ADJ   | (LO << 2)\n    (internal::general_matrix_matrix_triangular_product<DenseIndex,Scalar,RowMajor,Conj, Scalar,ColMajor,false,ColMajor,1,Lower>::run),\n    0\n  };\n\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  Scalar* c = reinterpret_cast<Scalar*>(pc);\n  RealScalar alpha = *palpha;\n  RealScalar beta  = *pbeta;\n\n//   std::cerr << \"in herk \" << *uplo << \" \" << *op << \" \" << *n << \" \" << *k << \" \" << alpha << \" \" << *lda << \" \" << beta << \" \" << *ldc << \"\\n\";\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if((OP(*op)==INVALID) || (OP(*op)==TR))                        info = 2;\n  else if(*n<0)                                                       info = 3;\n  else if(*k<0)                                                       info = 4;\n  else if(*lda<std::max(1,(OP(*op)==NOTR)?*n:*k))                     info = 7;\n  else if(*ldc<std::max(1,*n))                                        info = 10;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"HERK \",&info,6);\n\n  int code = OP(*op) | (UPLO(*uplo) << 2);\n\n  if(beta!=RealScalar(1))\n  {\n    if(UPLO(*uplo)==UP)\n      if(beta==Scalar(0)) matrix(c, *n, *n, *ldc).triangularView<Upper>().setZero();\n      else                matrix(c, *n, *n, *ldc).triangularView<StrictlyUpper>() *= beta;\n    else\n      if(beta==Scalar(0)) matrix(c, *n, *n, *ldc).triangularView<Lower>().setZero();\n      else                matrix(c, *n, *n, *ldc).triangularView<StrictlyLower>() *= beta;\n\n    if(beta!=Scalar(0))\n    {\n      matrix(c, *n, *n, *ldc).diagonal().real() *= beta;\n      matrix(c, *n, *n, *ldc).diagonal().imag().setZero();\n    }\n  }\n\n  if(*k>0 && alpha!=RealScalar(0))\n  {\n    internal::gemm_blocking_space<ColMajor,Scalar,Scalar,Dynamic,Dynamic,Dynamic> blocking(*n,*n,*k,1,false);\n    func[code](*n, *k, a, *lda, a, *lda, c, 1, *ldc, alpha, blocking);\n    matrix(c, *n, *n, *ldc).diagonal().imag().setZero();\n  }\n  return 0;\n}\n\n// c = alpha*a*conj(b') + conj(alpha)*b*conj(a') + beta*c,  for op = 'N'or'n'\n// c = alpha*conj(a')*b + conj(alpha)*conj(b')*a + beta*c,  for op = 'C'or'c'\nint EIGEN_BLAS_FUNC(her2k)(const char *uplo, const char *op, const int *n, const int *k,\n                           const RealScalar *palpha, const RealScalar *pa, const int *lda, const RealScalar *pb, const int *ldb, const RealScalar *pbeta, RealScalar *pc, const int *ldc)\n{\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  const Scalar* b = reinterpret_cast<const Scalar*>(pb);\n  Scalar* c = reinterpret_cast<Scalar*>(pc);\n  Scalar alpha = *reinterpret_cast<const Scalar*>(palpha);\n  RealScalar beta  = *pbeta;\n\n//   std::cerr << \"in her2k \" << *uplo << \" \" << *op << \" \" << *n << \" \" << *k << \" \" << alpha << \" \" << *lda << \" \" << *ldb << \" \" << beta << \" \" << *ldc << \"\\n\";\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if((OP(*op)==INVALID) || (OP(*op)==TR))                        info = 2;\n  else if(*n<0)                                                       info = 3;\n  else if(*k<0)                                                       info = 4;\n  else if(*lda<std::max(1,(OP(*op)==NOTR)?*n:*k))                     info = 7;\n  else if(*ldb<std::max(1,(OP(*op)==NOTR)?*n:*k))                     info = 9;\n  else if(*ldc<std::max(1,*n))                                        info = 12;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"HER2K\",&info,6);\n\n  if(beta!=RealScalar(1))\n  {\n    if(UPLO(*uplo)==UP)\n      if(beta==Scalar(0)) matrix(c, *n, *n, *ldc).triangularView<Upper>().setZero();\n      else                matrix(c, *n, *n, *ldc).triangularView<StrictlyUpper>() *= beta;\n    else\n      if(beta==Scalar(0)) matrix(c, *n, *n, *ldc).triangularView<Lower>().setZero();\n      else                matrix(c, *n, *n, *ldc).triangularView<StrictlyLower>() *= beta;\n\n    if(beta!=Scalar(0))\n    {\n      matrix(c, *n, *n, *ldc).diagonal().real() *= beta;\n      matrix(c, *n, *n, *ldc).diagonal().imag().setZero();\n    }\n  }\n  else if(*k>0 && alpha!=Scalar(0))\n    matrix(c, *n, *n, *ldc).diagonal().imag().setZero();\n\n  if(*k==0)\n    return 1;\n\n  if(OP(*op)==NOTR)\n  {\n    if(UPLO(*uplo)==UP)\n    {\n      matrix(c, *n, *n, *ldc).triangularView<Upper>()\n        +=            alpha *matrix(a, *n, *k, *lda)*matrix(b, *n, *k, *ldb).adjoint()\n        +  numext::conj(alpha)*matrix(b, *n, *k, *ldb)*matrix(a, *n, *k, *lda).adjoint();\n    }\n    else if(UPLO(*uplo)==LO)\n      matrix(c, *n, *n, *ldc).triangularView<Lower>()\n        += alpha*matrix(a, *n, *k, *lda)*matrix(b, *n, *k, *ldb).adjoint()\n        +  numext::conj(alpha)*matrix(b, *n, *k, *ldb)*matrix(a, *n, *k, *lda).adjoint();\n  }\n  else if(OP(*op)==ADJ)\n  {\n    if(UPLO(*uplo)==UP)\n      matrix(c, *n, *n, *ldc).triangularView<Upper>()\n        +=             alpha*matrix(a, *k, *n, *lda).adjoint()*matrix(b, *k, *n, *ldb)\n        +  numext::conj(alpha)*matrix(b, *k, *n, *ldb).adjoint()*matrix(a, *k, *n, *lda);\n    else if(UPLO(*uplo)==LO)\n      matrix(c, *n, *n, *ldc).triangularView<Lower>()\n        +=             alpha*matrix(a, *k, *n, *lda).adjoint()*matrix(b, *k, *n, *ldb)\n        +  numext::conj(alpha)*matrix(b, *k, *n, *ldb).adjoint()*matrix(a, *k, *n, *lda);\n  }\n\n  return 1;\n}\n\n#endif // ISCOMPLEX\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/single.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define SCALAR        float\n#define SCALAR_SUFFIX s\n#define SCALAR_SUFFIX_UP \"S\"\n#define ISCOMPLEX     0\n\n#include \"level1_impl.h\"\n#include \"level1_real_impl.h\"\n#include \"level2_impl.h\"\n#include \"level2_real_impl.h\"\n#include \"level3_impl.h\"\n\nfloat EIGEN_BLAS_FUNC(dsdot)(int* n, float* alpha, float* x, int* incx, float* y, int* incy)\n{ return double(*alpha) + BLASFUNC(dsdot)(n, x, incx, y, incy); }\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/testing/CMakeLists.txt",
    "content": "\nmacro(ei_add_blas_test testname)\n\n  set(targetname ${testname})\n\n  set(filename ${testname}.f)\n  add_executable(${targetname} ${filename})\n\n  target_link_libraries(${targetname} eigen_blas)\n\n  if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO)\n    target_link_libraries(${targetname} ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO})\n  endif()\n\n  target_link_libraries(${targetname} ${EXTERNAL_LIBS})\n\n  add_test(${testname} \"${Eigen_SOURCE_DIR}/blas/testing/runblastest.sh\" \"${testname}\" \"${Eigen_SOURCE_DIR}/blas/testing/${testname}.dat\")\n  add_dependencies(buildtests ${targetname})\n  \nendmacro()\n\nei_add_blas_test(sblat1)\nei_add_blas_test(sblat2)\nei_add_blas_test(sblat3)\n\nei_add_blas_test(dblat1)\nei_add_blas_test(dblat2)\nei_add_blas_test(dblat3)\n\nei_add_blas_test(cblat1)\nei_add_blas_test(cblat2)\nei_add_blas_test(cblat3)\n\nei_add_blas_test(zblat1)\nei_add_blas_test(zblat2)\nei_add_blas_test(zblat3)\n\n# add_custom_target(level1)\n# add_dependencies(level1 sblat1)\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/testing/cblat1.f",
    "content": "*> \\brief \\b CBLAT1\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM CBLAT1\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*>    Test program for the COMPLEX Level 1 BLAS.\n*>    Based upon the original BLAS test routine together with:\n*>\n*>    F06GAF Example Program Text\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup complex_blas_testing\n*\n*  =====================================================================\n      PROGRAM CBLAT1\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER          NOUT\n      PARAMETER        (NOUT=6)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, MODE, N\n      LOGICAL          PASS\n*     .. Local Scalars ..\n      REAL             SFAC\n      INTEGER          IC\n*     .. External Subroutines ..\n      EXTERNAL         CHECK1, CHECK2, HEADER\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Data statements ..\n      DATA             SFAC/9.765625E-4/\n*     .. Executable Statements ..\n      WRITE (NOUT,99999)\n      DO 20 IC = 1, 10\n         ICASE = IC\n         CALL HEADER\n*\n*        Initialize PASS, INCX, INCY, and MODE for a new case.\n*        The value 9999 for INCX, INCY or MODE will appear in the\n*        detailed  output, if any, for cases that do not involve\n*        these parameters.\n*\n         PASS = .TRUE.\n         INCX = 9999\n         INCY = 9999\n         MODE = 9999\n         IF (ICASE.LE.5) THEN\n            CALL CHECK2(SFAC)\n         ELSE IF (ICASE.GE.6) THEN\n            CALL CHECK1(SFAC)\n         END IF\n*        -- Print\n         IF (PASS) WRITE (NOUT,99998)\n   20 CONTINUE\n      STOP\n*\n99999 FORMAT (' Complex BLAS Test Program Results',/1X)\n99998 FORMAT ('                                    ----- PASS -----')\n      END\n      SUBROUTINE HEADER\n*     .. Parameters ..\n      INTEGER          NOUT\n      PARAMETER        (NOUT=6)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, MODE, N\n      LOGICAL          PASS\n*     .. Local Arrays ..\n      CHARACTER*6      L(10)\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Data statements ..\n      DATA             L(1)/'CDOTC '/\n      DATA             L(2)/'CDOTU '/\n      DATA             L(3)/'CAXPY '/\n      DATA             L(4)/'CCOPY '/\n      DATA             L(5)/'CSWAP '/\n      DATA             L(6)/'SCNRM2'/\n      DATA             L(7)/'SCASUM'/\n      DATA             L(8)/'CSCAL '/\n      DATA             L(9)/'CSSCAL'/\n      DATA             L(10)/'ICAMAX'/\n*     .. Executable Statements ..\n      WRITE (NOUT,99999) ICASE, L(ICASE)\n      RETURN\n*\n99999 FORMAT (/' Test of subprogram number',I3,12X,A6)\n      END\n      SUBROUTINE CHECK1(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      REAL              SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, MODE, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      COMPLEX           CA\n      REAL              SA\n      INTEGER           I, J, LEN, NP1\n*     .. Local Arrays ..\n      COMPLEX           CTRUE5(8,5,2), CTRUE6(8,5,2), CV(8,5,2), CX(8),\n     +                  MWPCS(5), MWPCT(5)\n      REAL              STRUE2(5), STRUE4(5)\n      INTEGER           ITRUE3(5)\n*     .. External Functions ..\n      REAL              SCASUM, SCNRM2\n      INTEGER           ICAMAX\n      EXTERNAL          SCASUM, SCNRM2, ICAMAX\n*     .. External Subroutines ..\n      EXTERNAL          CSCAL, CSSCAL, CTEST, ITEST1, STEST1\n*     .. Intrinsic Functions ..\n      INTRINSIC         MAX\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Data statements ..\n      DATA              SA, CA/0.3E0, (0.4E0,-0.7E0)/\n      DATA              ((CV(I,J,1),I=1,8),J=1,5)/(0.1E0,0.1E0),\n     +                  (1.0E0,2.0E0), (1.0E0,2.0E0), (1.0E0,2.0E0),\n     +                  (1.0E0,2.0E0), (1.0E0,2.0E0), (1.0E0,2.0E0),\n     +                  (1.0E0,2.0E0), (0.3E0,-0.4E0), (3.0E0,4.0E0),\n     +                  (3.0E0,4.0E0), (3.0E0,4.0E0), (3.0E0,4.0E0),\n     +                  (3.0E0,4.0E0), (3.0E0,4.0E0), (3.0E0,4.0E0),\n     +                  (0.1E0,-0.3E0), (0.5E0,-0.1E0), (5.0E0,6.0E0),\n     +                  (5.0E0,6.0E0), (5.0E0,6.0E0), (5.0E0,6.0E0),\n     +                  (5.0E0,6.0E0), (5.0E0,6.0E0), (0.1E0,0.1E0),\n     +                  (-0.6E0,0.1E0), (0.1E0,-0.3E0), (7.0E0,8.0E0),\n     +                  (7.0E0,8.0E0), (7.0E0,8.0E0), (7.0E0,8.0E0),\n     +                  (7.0E0,8.0E0), (0.3E0,0.1E0), (0.5E0,0.0E0),\n     +                  (0.0E0,0.5E0), (0.0E0,0.2E0), (2.0E0,3.0E0),\n     +                  (2.0E0,3.0E0), (2.0E0,3.0E0), (2.0E0,3.0E0)/\n      DATA              ((CV(I,J,2),I=1,8),J=1,5)/(0.1E0,0.1E0),\n     +                  (4.0E0,5.0E0), (4.0E0,5.0E0), (4.0E0,5.0E0),\n     +                  (4.0E0,5.0E0), (4.0E0,5.0E0), (4.0E0,5.0E0),\n     +                  (4.0E0,5.0E0), (0.3E0,-0.4E0), (6.0E0,7.0E0),\n     +                  (6.0E0,7.0E0), (6.0E0,7.0E0), (6.0E0,7.0E0),\n     +                  (6.0E0,7.0E0), (6.0E0,7.0E0), (6.0E0,7.0E0),\n     +                  (0.1E0,-0.3E0), (8.0E0,9.0E0), (0.5E0,-0.1E0),\n     +                  (2.0E0,5.0E0), (2.0E0,5.0E0), (2.0E0,5.0E0),\n     +                  (2.0E0,5.0E0), (2.0E0,5.0E0), (0.1E0,0.1E0),\n     +                  (3.0E0,6.0E0), (-0.6E0,0.1E0), (4.0E0,7.0E0),\n     +                  (0.1E0,-0.3E0), (7.0E0,2.0E0), (7.0E0,2.0E0),\n     +                  (7.0E0,2.0E0), (0.3E0,0.1E0), (5.0E0,8.0E0),\n     +                  (0.5E0,0.0E0), (6.0E0,9.0E0), (0.0E0,0.5E0),\n     +                  (8.0E0,3.0E0), (0.0E0,0.2E0), (9.0E0,4.0E0)/\n      DATA              STRUE2/0.0E0, 0.5E0, 0.6E0, 0.7E0, 0.8E0/\n      DATA              STRUE4/0.0E0, 0.7E0, 1.0E0, 1.3E0, 1.6E0/\n      DATA              ((CTRUE5(I,J,1),I=1,8),J=1,5)/(0.1E0,0.1E0),\n     +                  (1.0E0,2.0E0), (1.0E0,2.0E0), (1.0E0,2.0E0),\n     +                  (1.0E0,2.0E0), (1.0E0,2.0E0), (1.0E0,2.0E0),\n     +                  (1.0E0,2.0E0), (-0.16E0,-0.37E0), (3.0E0,4.0E0),\n     +                  (3.0E0,4.0E0), (3.0E0,4.0E0), (3.0E0,4.0E0),\n     +                  (3.0E0,4.0E0), (3.0E0,4.0E0), (3.0E0,4.0E0),\n     +                  (-0.17E0,-0.19E0), (0.13E0,-0.39E0),\n     +                  (5.0E0,6.0E0), (5.0E0,6.0E0), (5.0E0,6.0E0),\n     +                  (5.0E0,6.0E0), (5.0E0,6.0E0), (5.0E0,6.0E0),\n     +                  (0.11E0,-0.03E0), (-0.17E0,0.46E0),\n     +                  (-0.17E0,-0.19E0), (7.0E0,8.0E0), (7.0E0,8.0E0),\n     +                  (7.0E0,8.0E0), (7.0E0,8.0E0), (7.0E0,8.0E0),\n     +                  (0.19E0,-0.17E0), (0.20E0,-0.35E0),\n     +                  (0.35E0,0.20E0), (0.14E0,0.08E0),\n     +                  (2.0E0,3.0E0), (2.0E0,3.0E0), (2.0E0,3.0E0),\n     +                  (2.0E0,3.0E0)/\n      DATA              ((CTRUE5(I,J,2),I=1,8),J=1,5)/(0.1E0,0.1E0),\n     +                  (4.0E0,5.0E0), (4.0E0,5.0E0), (4.0E0,5.0E0),\n     +                  (4.0E0,5.0E0), (4.0E0,5.0E0), (4.0E0,5.0E0),\n     +                  (4.0E0,5.0E0), (-0.16E0,-0.37E0), (6.0E0,7.0E0),\n     +                  (6.0E0,7.0E0), (6.0E0,7.0E0), (6.0E0,7.0E0),\n     +                  (6.0E0,7.0E0), (6.0E0,7.0E0), (6.0E0,7.0E0),\n     +                  (-0.17E0,-0.19E0), (8.0E0,9.0E0),\n     +                  (0.13E0,-0.39E0), (2.0E0,5.0E0), (2.0E0,5.0E0),\n     +                  (2.0E0,5.0E0), (2.0E0,5.0E0), (2.0E0,5.0E0),\n     +                  (0.11E0,-0.03E0), (3.0E0,6.0E0),\n     +                  (-0.17E0,0.46E0), (4.0E0,7.0E0),\n     +                  (-0.17E0,-0.19E0), (7.0E0,2.0E0), (7.0E0,2.0E0),\n     +                  (7.0E0,2.0E0), (0.19E0,-0.17E0), (5.0E0,8.0E0),\n     +                  (0.20E0,-0.35E0), (6.0E0,9.0E0),\n     +                  (0.35E0,0.20E0), (8.0E0,3.0E0),\n     +                  (0.14E0,0.08E0), (9.0E0,4.0E0)/\n      DATA              ((CTRUE6(I,J,1),I=1,8),J=1,5)/(0.1E0,0.1E0),\n     +                  (1.0E0,2.0E0), (1.0E0,2.0E0), (1.0E0,2.0E0),\n     +                  (1.0E0,2.0E0), (1.0E0,2.0E0), (1.0E0,2.0E0),\n     +                  (1.0E0,2.0E0), (0.09E0,-0.12E0), (3.0E0,4.0E0),\n     +                  (3.0E0,4.0E0), (3.0E0,4.0E0), (3.0E0,4.0E0),\n     +                  (3.0E0,4.0E0), (3.0E0,4.0E0), (3.0E0,4.0E0),\n     +                  (0.03E0,-0.09E0), (0.15E0,-0.03E0),\n     +                  (5.0E0,6.0E0), (5.0E0,6.0E0), (5.0E0,6.0E0),\n     +                  (5.0E0,6.0E0), (5.0E0,6.0E0), (5.0E0,6.0E0),\n     +                  (0.03E0,0.03E0), (-0.18E0,0.03E0),\n     +                  (0.03E0,-0.09E0), (7.0E0,8.0E0), (7.0E0,8.0E0),\n     +                  (7.0E0,8.0E0), (7.0E0,8.0E0), (7.0E0,8.0E0),\n     +                  (0.09E0,0.03E0), (0.15E0,0.00E0),\n     +                  (0.00E0,0.15E0), (0.00E0,0.06E0), (2.0E0,3.0E0),\n     +                  (2.0E0,3.0E0), (2.0E0,3.0E0), (2.0E0,3.0E0)/\n      DATA              ((CTRUE6(I,J,2),I=1,8),J=1,5)/(0.1E0,0.1E0),\n     +                  (4.0E0,5.0E0), (4.0E0,5.0E0), (4.0E0,5.0E0),\n     +                  (4.0E0,5.0E0), (4.0E0,5.0E0), (4.0E0,5.0E0),\n     +                  (4.0E0,5.0E0), (0.09E0,-0.12E0), (6.0E0,7.0E0),\n     +                  (6.0E0,7.0E0), (6.0E0,7.0E0), (6.0E0,7.0E0),\n     +                  (6.0E0,7.0E0), (6.0E0,7.0E0), (6.0E0,7.0E0),\n     +                  (0.03E0,-0.09E0), (8.0E0,9.0E0),\n     +                  (0.15E0,-0.03E0), (2.0E0,5.0E0), (2.0E0,5.0E0),\n     +                  (2.0E0,5.0E0), (2.0E0,5.0E0), (2.0E0,5.0E0),\n     +                  (0.03E0,0.03E0), (3.0E0,6.0E0),\n     +                  (-0.18E0,0.03E0), (4.0E0,7.0E0),\n     +                  (0.03E0,-0.09E0), (7.0E0,2.0E0), (7.0E0,2.0E0),\n     +                  (7.0E0,2.0E0), (0.09E0,0.03E0), (5.0E0,8.0E0),\n     +                  (0.15E0,0.00E0), (6.0E0,9.0E0), (0.00E0,0.15E0),\n     +                  (8.0E0,3.0E0), (0.00E0,0.06E0), (9.0E0,4.0E0)/\n      DATA              ITRUE3/0, 1, 2, 2, 2/\n*     .. Executable Statements ..\n      DO 60 INCX = 1, 2\n         DO 40 NP1 = 1, 5\n            N = NP1 - 1\n            LEN = 2*MAX(N,1)\n*           .. Set vector arguments ..\n            DO 20 I = 1, LEN\n               CX(I) = CV(I,NP1,INCX)\n   20       CONTINUE\n            IF (ICASE.EQ.6) THEN\n*              .. SCNRM2 ..\n               CALL STEST1(SCNRM2(N,CX,INCX),STRUE2(NP1),STRUE2(NP1),\n     +                     SFAC)\n            ELSE IF (ICASE.EQ.7) THEN\n*              .. SCASUM ..\n               CALL STEST1(SCASUM(N,CX,INCX),STRUE4(NP1),STRUE4(NP1),\n     +                     SFAC)\n            ELSE IF (ICASE.EQ.8) THEN\n*              .. CSCAL ..\n               CALL CSCAL(N,CA,CX,INCX)\n               CALL CTEST(LEN,CX,CTRUE5(1,NP1,INCX),CTRUE5(1,NP1,INCX),\n     +                    SFAC)\n            ELSE IF (ICASE.EQ.9) THEN\n*              .. CSSCAL ..\n               CALL CSSCAL(N,SA,CX,INCX)\n               CALL CTEST(LEN,CX,CTRUE6(1,NP1,INCX),CTRUE6(1,NP1,INCX),\n     +                    SFAC)\n            ELSE IF (ICASE.EQ.10) THEN\n*              .. ICAMAX ..\n               CALL ITEST1(ICAMAX(N,CX,INCX),ITRUE3(NP1))\n            ELSE\n               WRITE (NOUT,*) ' Shouldn''t be here in CHECK1'\n               STOP\n            END IF\n*\n   40    CONTINUE\n   60 CONTINUE\n*\n      INCX = 1\n      IF (ICASE.EQ.8) THEN\n*        CSCAL\n*        Add a test for alpha equal to zero.\n         CA = (0.0E0,0.0E0)\n         DO 80 I = 1, 5\n            MWPCT(I) = (0.0E0,0.0E0)\n            MWPCS(I) = (1.0E0,1.0E0)\n   80    CONTINUE\n         CALL CSCAL(5,CA,CX,INCX)\n         CALL CTEST(5,CX,MWPCT,MWPCS,SFAC)\n      ELSE IF (ICASE.EQ.9) THEN\n*        CSSCAL\n*        Add a test for alpha equal to zero.\n         SA = 0.0E0\n         DO 100 I = 1, 5\n            MWPCT(I) = (0.0E0,0.0E0)\n            MWPCS(I) = (1.0E0,1.0E0)\n  100    CONTINUE\n         CALL CSSCAL(5,SA,CX,INCX)\n         CALL CTEST(5,CX,MWPCT,MWPCS,SFAC)\n*        Add a test for alpha equal to one.\n         SA = 1.0E0\n         DO 120 I = 1, 5\n            MWPCT(I) = CX(I)\n            MWPCS(I) = CX(I)\n  120    CONTINUE\n         CALL CSSCAL(5,SA,CX,INCX)\n         CALL CTEST(5,CX,MWPCT,MWPCS,SFAC)\n*        Add a test for alpha equal to minus one.\n         SA = -1.0E0\n         DO 140 I = 1, 5\n            MWPCT(I) = -CX(I)\n            MWPCS(I) = -CX(I)\n  140    CONTINUE\n         CALL CSSCAL(5,SA,CX,INCX)\n         CALL CTEST(5,CX,MWPCT,MWPCS,SFAC)\n      END IF\n      RETURN\n      END\n      SUBROUTINE CHECK2(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      REAL              SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, MODE, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      COMPLEX           CA\n      INTEGER           I, J, KI, KN, KSIZE, LENX, LENY, MX, MY\n*     .. Local Arrays ..\n      COMPLEX           CDOT(1), CSIZE1(4), CSIZE2(7,2), CSIZE3(14),\n     +                  CT10X(7,4,4), CT10Y(7,4,4), CT6(4,4), CT7(4,4),\n     +                  CT8(7,4,4), CX(7), CX1(7), CY(7), CY1(7)\n      INTEGER           INCXS(4), INCYS(4), LENS(4,2), NS(4)\n*     .. External Functions ..\n      COMPLEX           CDOTC, CDOTU\n      EXTERNAL          CDOTC, CDOTU\n*     .. External Subroutines ..\n      EXTERNAL          CAXPY, CCOPY, CSWAP, CTEST\n*     .. Intrinsic Functions ..\n      INTRINSIC         ABS, MIN\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Data statements ..\n      DATA              CA/(0.4E0,-0.7E0)/\n      DATA              INCXS/1, 2, -2, -1/\n      DATA              INCYS/1, -2, 1, -2/\n      DATA              LENS/1, 1, 2, 4, 1, 1, 3, 7/\n      DATA              NS/0, 1, 2, 4/\n      DATA              CX1/(0.7E0,-0.8E0), (-0.4E0,-0.7E0),\n     +                  (-0.1E0,-0.9E0), (0.2E0,-0.8E0),\n     +                  (-0.9E0,-0.4E0), (0.1E0,0.4E0), (-0.6E0,0.6E0)/\n      DATA              CY1/(0.6E0,-0.6E0), (-0.9E0,0.5E0),\n     +                  (0.7E0,-0.6E0), (0.1E0,-0.5E0), (-0.1E0,-0.2E0),\n     +                  (-0.5E0,-0.3E0), (0.8E0,-0.7E0)/\n      DATA              ((CT8(I,J,1),I=1,7),J=1,4)/(0.6E0,-0.6E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.32E0,-1.41E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.32E0,-1.41E0),\n     +                  (-1.55E0,0.5E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.32E0,-1.41E0), (-1.55E0,0.5E0),\n     +                  (0.03E0,-0.89E0), (-0.38E0,-0.96E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0)/\n      DATA              ((CT8(I,J,2),I=1,7),J=1,4)/(0.6E0,-0.6E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.32E0,-1.41E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (-0.07E0,-0.89E0),\n     +                  (-0.9E0,0.5E0), (0.42E0,-1.41E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.78E0,0.06E0), (-0.9E0,0.5E0),\n     +                  (0.06E0,-0.13E0), (0.1E0,-0.5E0),\n     +                  (-0.77E0,-0.49E0), (-0.5E0,-0.3E0),\n     +                  (0.52E0,-1.51E0)/\n      DATA              ((CT8(I,J,3),I=1,7),J=1,4)/(0.6E0,-0.6E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.32E0,-1.41E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (-0.07E0,-0.89E0),\n     +                  (-1.18E0,-0.31E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.78E0,0.06E0), (-1.54E0,0.97E0),\n     +                  (0.03E0,-0.89E0), (-0.18E0,-1.31E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0)/\n      DATA              ((CT8(I,J,4),I=1,7),J=1,4)/(0.6E0,-0.6E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.32E0,-1.41E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.32E0,-1.41E0), (-0.9E0,0.5E0),\n     +                  (0.05E0,-0.6E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.32E0,-1.41E0),\n     +                  (-0.9E0,0.5E0), (0.05E0,-0.6E0), (0.1E0,-0.5E0),\n     +                  (-0.77E0,-0.49E0), (-0.5E0,-0.3E0),\n     +                  (0.32E0,-1.16E0)/\n      DATA              CT7/(0.0E0,0.0E0), (-0.06E0,-0.90E0),\n     +                  (0.65E0,-0.47E0), (-0.34E0,-1.22E0),\n     +                  (0.0E0,0.0E0), (-0.06E0,-0.90E0),\n     +                  (-0.59E0,-1.46E0), (-1.04E0,-0.04E0),\n     +                  (0.0E0,0.0E0), (-0.06E0,-0.90E0),\n     +                  (-0.83E0,0.59E0), (0.07E0,-0.37E0),\n     +                  (0.0E0,0.0E0), (-0.06E0,-0.90E0),\n     +                  (-0.76E0,-1.15E0), (-1.33E0,-1.82E0)/\n      DATA              CT6/(0.0E0,0.0E0), (0.90E0,0.06E0),\n     +                  (0.91E0,-0.77E0), (1.80E0,-0.10E0),\n     +                  (0.0E0,0.0E0), (0.90E0,0.06E0), (1.45E0,0.74E0),\n     +                  (0.20E0,0.90E0), (0.0E0,0.0E0), (0.90E0,0.06E0),\n     +                  (-0.55E0,0.23E0), (0.83E0,-0.39E0),\n     +                  (0.0E0,0.0E0), (0.90E0,0.06E0), (1.04E0,0.79E0),\n     +                  (1.95E0,1.22E0)/\n      DATA              ((CT10X(I,J,1),I=1,7),J=1,4)/(0.7E0,-0.8E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.6E0,-0.6E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.6E0,-0.6E0), (-0.9E0,0.5E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.6E0,-0.6E0),\n     +                  (-0.9E0,0.5E0), (0.7E0,-0.6E0), (0.1E0,-0.5E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0)/\n      DATA              ((CT10X(I,J,2),I=1,7),J=1,4)/(0.7E0,-0.8E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.6E0,-0.6E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.7E0,-0.6E0), (-0.4E0,-0.7E0),\n     +                  (0.6E0,-0.6E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.8E0,-0.7E0),\n     +                  (-0.4E0,-0.7E0), (-0.1E0,-0.2E0),\n     +                  (0.2E0,-0.8E0), (0.7E0,-0.6E0), (0.1E0,0.4E0),\n     +                  (0.6E0,-0.6E0)/\n      DATA              ((CT10X(I,J,3),I=1,7),J=1,4)/(0.7E0,-0.8E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.6E0,-0.6E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (-0.9E0,0.5E0), (-0.4E0,-0.7E0),\n     +                  (0.6E0,-0.6E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.1E0,-0.5E0),\n     +                  (-0.4E0,-0.7E0), (0.7E0,-0.6E0), (0.2E0,-0.8E0),\n     +                  (-0.9E0,0.5E0), (0.1E0,0.4E0), (0.6E0,-0.6E0)/\n      DATA              ((CT10X(I,J,4),I=1,7),J=1,4)/(0.7E0,-0.8E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.6E0,-0.6E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.6E0,-0.6E0), (0.7E0,-0.6E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.6E0,-0.6E0),\n     +                  (0.7E0,-0.6E0), (-0.1E0,-0.2E0), (0.8E0,-0.7E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0)/\n      DATA              ((CT10Y(I,J,1),I=1,7),J=1,4)/(0.6E0,-0.6E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.7E0,-0.8E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.7E0,-0.8E0), (-0.4E0,-0.7E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.7E0,-0.8E0),\n     +                  (-0.4E0,-0.7E0), (-0.1E0,-0.9E0),\n     +                  (0.2E0,-0.8E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0)/\n      DATA              ((CT10Y(I,J,2),I=1,7),J=1,4)/(0.6E0,-0.6E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.7E0,-0.8E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (-0.1E0,-0.9E0), (-0.9E0,0.5E0),\n     +                  (0.7E0,-0.8E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (-0.6E0,0.6E0),\n     +                  (-0.9E0,0.5E0), (-0.9E0,-0.4E0), (0.1E0,-0.5E0),\n     +                  (-0.1E0,-0.9E0), (-0.5E0,-0.3E0),\n     +                  (0.7E0,-0.8E0)/\n      DATA              ((CT10Y(I,J,3),I=1,7),J=1,4)/(0.6E0,-0.6E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.7E0,-0.8E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (-0.1E0,-0.9E0), (0.7E0,-0.8E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (-0.6E0,0.6E0),\n     +                  (-0.9E0,-0.4E0), (-0.1E0,-0.9E0),\n     +                  (0.7E0,-0.8E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0)/\n      DATA              ((CT10Y(I,J,4),I=1,7),J=1,4)/(0.6E0,-0.6E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.7E0,-0.8E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.7E0,-0.8E0), (-0.9E0,0.5E0),\n     +                  (-0.4E0,-0.7E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.7E0,-0.8E0),\n     +                  (-0.9E0,0.5E0), (-0.4E0,-0.7E0), (0.1E0,-0.5E0),\n     +                  (-0.1E0,-0.9E0), (-0.5E0,-0.3E0),\n     +                  (0.2E0,-0.8E0)/\n      DATA              CSIZE1/(0.0E0,0.0E0), (0.9E0,0.9E0),\n     +                  (1.63E0,1.73E0), (2.90E0,2.78E0)/\n      DATA              CSIZE3/(0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (1.17E0,1.17E0),\n     +                  (1.17E0,1.17E0), (1.17E0,1.17E0),\n     +                  (1.17E0,1.17E0), (1.17E0,1.17E0),\n     +                  (1.17E0,1.17E0), (1.17E0,1.17E0)/\n      DATA              CSIZE2/(0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (1.54E0,1.54E0),\n     +                  (1.54E0,1.54E0), (1.54E0,1.54E0),\n     +                  (1.54E0,1.54E0), (1.54E0,1.54E0),\n     +                  (1.54E0,1.54E0), (1.54E0,1.54E0)/\n*     .. Executable Statements ..\n      DO 60 KI = 1, 4\n         INCX = INCXS(KI)\n         INCY = INCYS(KI)\n         MX = ABS(INCX)\n         MY = ABS(INCY)\n*\n         DO 40 KN = 1, 4\n            N = NS(KN)\n            KSIZE = MIN(2,KN)\n            LENX = LENS(KN,MX)\n            LENY = LENS(KN,MY)\n*           .. initialize all argument arrays ..\n            DO 20 I = 1, 7\n               CX(I) = CX1(I)\n               CY(I) = CY1(I)\n   20       CONTINUE\n            IF (ICASE.EQ.1) THEN\n*              .. CDOTC ..\n               CDOT(1) = CDOTC(N,CX,INCX,CY,INCY)\n               CALL CTEST(1,CDOT,CT6(KN,KI),CSIZE1(KN),SFAC)\n            ELSE IF (ICASE.EQ.2) THEN\n*              .. CDOTU ..\n               CDOT(1) = CDOTU(N,CX,INCX,CY,INCY)\n               CALL CTEST(1,CDOT,CT7(KN,KI),CSIZE1(KN),SFAC)\n            ELSE IF (ICASE.EQ.3) THEN\n*              .. CAXPY ..\n               CALL CAXPY(N,CA,CX,INCX,CY,INCY)\n               CALL CTEST(LENY,CY,CT8(1,KN,KI),CSIZE2(1,KSIZE),SFAC)\n            ELSE IF (ICASE.EQ.4) THEN\n*              .. CCOPY ..\n               CALL CCOPY(N,CX,INCX,CY,INCY)\n               CALL CTEST(LENY,CY,CT10Y(1,KN,KI),CSIZE3,1.0E0)\n            ELSE IF (ICASE.EQ.5) THEN\n*              .. CSWAP ..\n               CALL CSWAP(N,CX,INCX,CY,INCY)\n               CALL CTEST(LENX,CX,CT10X(1,KN,KI),CSIZE3,1.0E0)\n               CALL CTEST(LENY,CY,CT10Y(1,KN,KI),CSIZE3,1.0E0)\n            ELSE\n               WRITE (NOUT,*) ' Shouldn''t be here in CHECK2'\n               STOP\n            END IF\n*\n   40    CONTINUE\n   60 CONTINUE\n      RETURN\n      END\n      SUBROUTINE STEST(LEN,SCOMP,STRUE,SSIZE,SFAC)\n*     ********************************* STEST **************************\n*\n*     THIS SUBR COMPARES ARRAYS  SCOMP() AND STRUE() OF LENGTH LEN TO\n*     SEE IF THE TERM BY TERM DIFFERENCES, MULTIPLIED BY SFAC, ARE\n*     NEGLIGIBLE.\n*\n*     C. L. LAWSON, JPL, 1974 DEC 10\n*\n*     .. Parameters ..\n      INTEGER          NOUT\n      REAL             ZERO\n      PARAMETER        (NOUT=6, ZERO=0.0E0)\n*     .. Scalar Arguments ..\n      REAL             SFAC\n      INTEGER          LEN\n*     .. Array Arguments ..\n      REAL             SCOMP(LEN), SSIZE(LEN), STRUE(LEN)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, MODE, N\n      LOGICAL          PASS\n*     .. Local Scalars ..\n      REAL             SD\n      INTEGER          I\n*     .. External Functions ..\n      REAL             SDIFF\n      EXTERNAL         SDIFF\n*     .. Intrinsic Functions ..\n      INTRINSIC        ABS\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Executable Statements ..\n*\n      DO 40 I = 1, LEN\n         SD = SCOMP(I) - STRUE(I)\n         IF (ABS(SFAC*SD) .LE. ABS(SSIZE(I))*EPSILON(ZERO))\n     +       GO TO 40\n*\n*                             HERE    SCOMP(I) IS NOT CLOSE TO STRUE(I).\n*\n         IF ( .NOT. PASS) GO TO 20\n*                             PRINT FAIL MESSAGE AND HEADER.\n         PASS = .FALSE.\n         WRITE (NOUT,99999)\n         WRITE (NOUT,99998)\n   20    WRITE (NOUT,99997) ICASE, N, INCX, INCY, MODE, I, SCOMP(I),\n     +     STRUE(I), SD, SSIZE(I)\n   40 CONTINUE\n      RETURN\n*\n99999 FORMAT ('                                       FAIL')\n99998 FORMAT (/' CASE  N INCX INCY MODE  I                            ',\n     +       ' COMP(I)                             TRUE(I)  DIFFERENCE',\n     +       '     SIZE(I)',/1X)\n99997 FORMAT (1X,I4,I3,3I5,I3,2E36.8,2E12.4)\n      END\n      SUBROUTINE STEST1(SCOMP1,STRUE1,SSIZE,SFAC)\n*     ************************* STEST1 *****************************\n*\n*     THIS IS AN INTERFACE SUBROUTINE TO ACCOMMODATE THE FORTRAN\n*     REQUIREMENT THAT WHEN A DUMMY ARGUMENT IS AN ARRAY, THE\n*     ACTUAL ARGUMENT MUST ALSO BE AN ARRAY OR AN ARRAY ELEMENT.\n*\n*     C.L. LAWSON, JPL, 1978 DEC 6\n*\n*     .. Scalar Arguments ..\n      REAL              SCOMP1, SFAC, STRUE1\n*     .. Array Arguments ..\n      REAL              SSIZE(*)\n*     .. Local Arrays ..\n      REAL              SCOMP(1), STRUE(1)\n*     .. External Subroutines ..\n      EXTERNAL          STEST\n*     .. Executable Statements ..\n*\n      SCOMP(1) = SCOMP1\n      STRUE(1) = STRUE1\n      CALL STEST(1,SCOMP,STRUE,SSIZE,SFAC)\n*\n      RETURN\n      END\n      REAL             FUNCTION SDIFF(SA,SB)\n*     ********************************* SDIFF **************************\n*     COMPUTES DIFFERENCE OF TWO NUMBERS.  C. L. LAWSON, JPL 1974 FEB 15\n*\n*     .. Scalar Arguments ..\n      REAL                            SA, SB\n*     .. Executable Statements ..\n      SDIFF = SA - SB\n      RETURN\n      END\n      SUBROUTINE CTEST(LEN,CCOMP,CTRUE,CSIZE,SFAC)\n*     **************************** CTEST *****************************\n*\n*     C.L. LAWSON, JPL, 1978 DEC 6\n*\n*     .. Scalar Arguments ..\n      REAL             SFAC\n      INTEGER          LEN\n*     .. Array Arguments ..\n      COMPLEX          CCOMP(LEN), CSIZE(LEN), CTRUE(LEN)\n*     .. Local Scalars ..\n      INTEGER          I\n*     .. Local Arrays ..\n      REAL             SCOMP(20), SSIZE(20), STRUE(20)\n*     .. External Subroutines ..\n      EXTERNAL         STEST\n*     .. Intrinsic Functions ..\n      INTRINSIC        AIMAG, REAL\n*     .. Executable Statements ..\n      DO 20 I = 1, LEN\n         SCOMP(2*I-1) = REAL(CCOMP(I))\n         SCOMP(2*I) = AIMAG(CCOMP(I))\n         STRUE(2*I-1) = REAL(CTRUE(I))\n         STRUE(2*I) = AIMAG(CTRUE(I))\n         SSIZE(2*I-1) = REAL(CSIZE(I))\n         SSIZE(2*I) = AIMAG(CSIZE(I))\n   20 CONTINUE\n*\n      CALL STEST(2*LEN,SCOMP,STRUE,SSIZE,SFAC)\n      RETURN\n      END\n      SUBROUTINE ITEST1(ICOMP,ITRUE)\n*     ********************************* ITEST1 *************************\n*\n*     THIS SUBROUTINE COMPARES THE VARIABLES ICOMP AND ITRUE FOR\n*     EQUALITY.\n*     C. L. LAWSON, JPL, 1974 DEC 10\n*\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      INTEGER           ICOMP, ITRUE\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, MODE, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      INTEGER           ID\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Executable Statements ..\n      IF (ICOMP.EQ.ITRUE) GO TO 40\n*\n*                            HERE ICOMP IS NOT EQUAL TO ITRUE.\n*\n      IF ( .NOT. PASS) GO TO 20\n*                             PRINT FAIL MESSAGE AND HEADER.\n      PASS = .FALSE.\n      WRITE (NOUT,99999)\n      WRITE (NOUT,99998)\n   20 ID = ICOMP - ITRUE\n      WRITE (NOUT,99997) ICASE, N, INCX, INCY, MODE, ICOMP, ITRUE, ID\n   40 CONTINUE\n      RETURN\n*\n99999 FORMAT ('                                       FAIL')\n99998 FORMAT (/' CASE  N INCX INCY MODE                               ',\n     +       ' COMP                                TRUE     DIFFERENCE',\n     +       /1X)\n99997 FORMAT (1X,I4,I3,3I5,2I36,I12)\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/testing/cblat2.f",
    "content": "*> \\brief \\b CBLAT2\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM CBLAT2\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> Test program for the COMPLEX          Level 2 Blas.\n*>\n*> The program must be driven by a short data file. The first 18 records\n*> of the file are read using list-directed input, the last 17 records\n*> are read using the format ( A6, L2 ). An annotated example of a data\n*> file can be obtained by deleting the first 3 characters from the\n*> following 35 lines:\n*> 'cblat2.out'      NAME OF SUMMARY OUTPUT FILE\n*> 6                 UNIT NUMBER OF SUMMARY FILE\n*> 'CBLA2T.SNAP'     NAME OF SNAPSHOT OUTPUT FILE\n*> -1                UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0)\n*> F        LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD.\n*> F        LOGICAL FLAG, T TO STOP ON FAILURES.\n*> T        LOGICAL FLAG, T TO TEST ERROR EXITS.\n*> 16.0     THRESHOLD VALUE OF TEST RATIO\n*> 6                 NUMBER OF VALUES OF N\n*> 0 1 2 3 5 9       VALUES OF N\n*> 4                 NUMBER OF VALUES OF K\n*> 0 1 2 4           VALUES OF K\n*> 4                 NUMBER OF VALUES OF INCX AND INCY\n*> 1 2 -1 -2         VALUES OF INCX AND INCY\n*> 3                 NUMBER OF VALUES OF ALPHA\n*> (0.0,0.0) (1.0,0.0) (0.7,-0.9)       VALUES OF ALPHA\n*> 3                 NUMBER OF VALUES OF BETA\n*> (0.0,0.0) (1.0,0.0) (1.3,-1.1)       VALUES OF BETA\n*> CGEMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CGBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CHEMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CHBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CHPMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CTRMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CTBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CTPMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CTRSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CTBSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CTPSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CGERC  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CGERU  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CHER   T PUT F FOR NO TEST. SAME COLUMNS.\n*> CHPR   T PUT F FOR NO TEST. SAME COLUMNS.\n*> CHER2  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CHPR2  T PUT F FOR NO TEST. SAME COLUMNS.\n*>\n*> Further Details\n*> ===============\n*>\n*>    See:\n*>\n*>       Dongarra J. J., Du Croz J. J., Hammarling S.  and Hanson R. J..\n*>       An  extended  set of Fortran  Basic Linear Algebra Subprograms.\n*>\n*>       Technical  Memoranda  Nos. 41 (revision 3) and 81,  Mathematics\n*>       and  Computer Science  Division,  Argonne  National Laboratory,\n*>       9700 South Cass Avenue, Argonne, Illinois 60439, US.\n*>\n*>       Or\n*>\n*>       NAG  Technical Reports TR3/87 and TR4/87,  Numerical Algorithms\n*>       Group  Ltd.,  NAG  Central  Office,  256  Banbury  Road, Oxford\n*>       OX2 7DE, UK,  and  Numerical Algorithms Group Inc.,  1101  31st\n*>       Street,  Suite 100,  Downers Grove,  Illinois 60515-1263,  USA.\n*>\n*>\n*> -- Written on 10-August-1987.\n*>    Richard Hanson, Sandia National Labs.\n*>    Jeremy Du Croz, NAG Central Office.\n*>\n*>    10-9-00:  Change STATUS='NEW' to 'UNKNOWN' so that the testers\n*>              can be run multiple times without deleting generated\n*>              output files (susan)\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup complex_blas_testing\n*\n*  =====================================================================\n      PROGRAM CBLAT2\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER            NIN\n      PARAMETER          ( NIN = 5 )\n      INTEGER            NSUBS\n      PARAMETER          ( NSUBS = 17 )\n      COMPLEX            ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), ONE = ( 1.0, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n      INTEGER            NMAX, INCMAX\n      PARAMETER          ( NMAX = 65, INCMAX = 2 )\n      INTEGER            NINMAX, NIDMAX, NKBMAX, NALMAX, NBEMAX\n      PARAMETER          ( NINMAX = 7, NIDMAX = 9, NKBMAX = 7,\n     $                   NALMAX = 7, NBEMAX = 7 )\n*     .. Local Scalars ..\n      REAL               EPS, ERR, THRESH\n      INTEGER            I, ISNUM, J, N, NALF, NBET, NIDIM, NINC, NKB,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, LTESTT, REWI, SAME, SFATAL, TRACE,\n     $                   TSTERR\n      CHARACTER*1        TRANS\n      CHARACTER*6        SNAMET\n      CHARACTER*32       SNAPS, SUMMRY\n*     .. Local Arrays ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ),\n     $                   ALF( NALMAX ), AS( NMAX*NMAX ), BET( NBEMAX ),\n     $                   X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( 2*NMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDMAX ), INC( NINMAX ), KB( NKBMAX )\n      LOGICAL            LTEST( NSUBS )\n      CHARACTER*6        SNAMES( NSUBS )\n*     .. External Functions ..\n      REAL               SDIFF\n      LOGICAL            LCE\n      EXTERNAL           SDIFF, LCE\n*     .. External Subroutines ..\n      EXTERNAL           CCHK1, CCHK2, CCHK3, CCHK4, CCHK5, CCHK6,\n     $                   CCHKE, CMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Data statements ..\n      DATA               SNAMES/'CGEMV ', 'CGBMV ', 'CHEMV ', 'CHBMV ',\n     $                   'CHPMV ', 'CTRMV ', 'CTBMV ', 'CTPMV ',\n     $                   'CTRSV ', 'CTBSV ', 'CTPSV ', 'CGERC ',\n     $                   'CGERU ', 'CHER  ', 'CHPR  ', 'CHER2 ',\n     $                   'CHPR2 '/\n*     .. Executable Statements ..\n*\n*     Read name and unit number for summary output file and open file.\n*\n      READ( NIN, FMT = * )SUMMRY\n      READ( NIN, FMT = * )NOUT\n      OPEN( NOUT, FILE = SUMMRY, STATUS = 'UNKNOWN' )\n      NOUTC = NOUT\n*\n*     Read name and unit number for snapshot output file and open file.\n*\n      READ( NIN, FMT = * )SNAPS\n      READ( NIN, FMT = * )NTRA\n      TRACE = NTRA.GE.0\n      IF( TRACE )THEN\n         OPEN( NTRA, FILE = SNAPS, STATUS = 'UNKNOWN' )\n      END IF\n*     Read the flag that directs rewinding of the snapshot file.\n      READ( NIN, FMT = * )REWI\n      REWI = REWI.AND.TRACE\n*     Read the flag that directs stopping on any failure.\n      READ( NIN, FMT = * )SFATAL\n*     Read the flag that indicates whether error exits are to be tested.\n      READ( NIN, FMT = * )TSTERR\n*     Read the threshold value of the test ratio\n      READ( NIN, FMT = * )THRESH\n*\n*     Read and check the parameter values for the tests.\n*\n*     Values of N\n      READ( NIN, FMT = * )NIDIM\n      IF( NIDIM.LT.1.OR.NIDIM.GT.NIDMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'N', NIDMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( IDIM( I ), I = 1, NIDIM )\n      DO 10 I = 1, NIDIM\n         IF( IDIM( I ).LT.0.OR.IDIM( I ).GT.NMAX )THEN\n            WRITE( NOUT, FMT = 9996 )NMAX\n            GO TO 230\n         END IF\n   10 CONTINUE\n*     Values of K\n      READ( NIN, FMT = * )NKB\n      IF( NKB.LT.1.OR.NKB.GT.NKBMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'K', NKBMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( KB( I ), I = 1, NKB )\n      DO 20 I = 1, NKB\n         IF( KB( I ).LT.0 )THEN\n            WRITE( NOUT, FMT = 9995 )\n            GO TO 230\n         END IF\n   20 CONTINUE\n*     Values of INCX and INCY\n      READ( NIN, FMT = * )NINC\n      IF( NINC.LT.1.OR.NINC.GT.NINMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'INCX AND INCY', NINMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( INC( I ), I = 1, NINC )\n      DO 30 I = 1, NINC\n         IF( INC( I ).EQ.0.OR.ABS( INC( I ) ).GT.INCMAX )THEN\n            WRITE( NOUT, FMT = 9994 )INCMAX\n            GO TO 230\n         END IF\n   30 CONTINUE\n*     Values of ALPHA\n      READ( NIN, FMT = * )NALF\n      IF( NALF.LT.1.OR.NALF.GT.NALMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'ALPHA', NALMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( ALF( I ), I = 1, NALF )\n*     Values of BETA\n      READ( NIN, FMT = * )NBET\n      IF( NBET.LT.1.OR.NBET.GT.NBEMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'BETA', NBEMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( BET( I ), I = 1, NBET )\n*\n*     Report values of parameters.\n*\n      WRITE( NOUT, FMT = 9993 )\n      WRITE( NOUT, FMT = 9992 )( IDIM( I ), I = 1, NIDIM )\n      WRITE( NOUT, FMT = 9991 )( KB( I ), I = 1, NKB )\n      WRITE( NOUT, FMT = 9990 )( INC( I ), I = 1, NINC )\n      WRITE( NOUT, FMT = 9989 )( ALF( I ), I = 1, NALF )\n      WRITE( NOUT, FMT = 9988 )( BET( I ), I = 1, NBET )\n      IF( .NOT.TSTERR )THEN\n         WRITE( NOUT, FMT = * )\n         WRITE( NOUT, FMT = 9980 )\n      END IF\n      WRITE( NOUT, FMT = * )\n      WRITE( NOUT, FMT = 9999 )THRESH\n      WRITE( NOUT, FMT = * )\n*\n*     Read names of subroutines and flags which indicate\n*     whether they are to be tested.\n*\n      DO 40 I = 1, NSUBS\n         LTEST( I ) = .FALSE.\n   40 CONTINUE\n   50 READ( NIN, FMT = 9984, END = 80 )SNAMET, LTESTT\n      DO 60 I = 1, NSUBS\n         IF( SNAMET.EQ.SNAMES( I ) )\n     $      GO TO 70\n   60 CONTINUE\n      WRITE( NOUT, FMT = 9986 )SNAMET\n      STOP\n   70 LTEST( I ) = LTESTT\n      GO TO 50\n*\n   80 CONTINUE\n      CLOSE ( NIN )\n*\n*     Compute EPS (the machine precision).\n*\n      EPS = EPSILON(RZERO)\n      WRITE( NOUT, FMT = 9998 )EPS\n*\n*     Check the reliability of CMVCH using exact data.\n*\n      N = MIN( 32, NMAX )\n      DO 120 J = 1, N\n         DO 110 I = 1, N\n            A( I, J ) = MAX( I - J + 1, 0 )\n  110    CONTINUE\n         X( J ) = J\n         Y( J ) = ZERO\n  120 CONTINUE\n      DO 130 J = 1, N\n         YY( J ) = J*( ( J + 1 )*J )/2 - ( ( J + 1 )*J*( J - 1 ) )/3\n  130 CONTINUE\n*     YY holds the exact result. On exit from CMVCH YT holds\n*     the result computed by CMVCH.\n      TRANS = 'N'\n      CALL CMVCH( TRANS, N, N, ONE, A, NMAX, X, 1, ZERO, Y, 1, YT, G,\n     $            YY, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LCE( YY, YT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9985 )TRANS, SAME, ERR\n         STOP\n      END IF\n      TRANS = 'T'\n      CALL CMVCH( TRANS, N, N, ONE, A, NMAX, X, -1, ZERO, Y, -1, YT, G,\n     $            YY, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LCE( YY, YT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9985 )TRANS, SAME, ERR\n         STOP\n      END IF\n*\n*     Test each subroutine in turn.\n*\n      DO 210 ISNUM = 1, NSUBS\n         WRITE( NOUT, FMT = * )\n         IF( .NOT.LTEST( ISNUM ) )THEN\n*           Subprogram is not to be tested.\n            WRITE( NOUT, FMT = 9983 )SNAMES( ISNUM )\n         ELSE\n            SRNAMT = SNAMES( ISNUM )\n*           Test error exits.\n            IF( TSTERR )THEN\n               CALL CCHKE( ISNUM, SNAMES( ISNUM ), NOUT )\n               WRITE( NOUT, FMT = * )\n            END IF\n*           Test computations.\n            INFOT = 0\n            OK = .TRUE.\n            FATAL = .FALSE.\n            GO TO ( 140, 140, 150, 150, 150, 160, 160,\n     $              160, 160, 160, 160, 170, 170, 180,\n     $              180, 190, 190 )ISNUM\n*           Test CGEMV, 01, and CGBMV, 02.\n  140       CALL CCHK1( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF,\n     $                  NBET, BET, NINC, INC, NMAX, INCMAX, A, AA, AS,\n     $                  X, XX, XS, Y, YY, YS, YT, G )\n            GO TO 200\n*           Test CHEMV, 03, CHBMV, 04, and CHPMV, 05.\n  150       CALL CCHK2( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF,\n     $                  NBET, BET, NINC, INC, NMAX, INCMAX, A, AA, AS,\n     $                  X, XX, XS, Y, YY, YS, YT, G )\n            GO TO 200\n*           Test CTRMV, 06, CTBMV, 07, CTPMV, 08,\n*           CTRSV, 09, CTBSV, 10, and CTPSV, 11.\n  160       CALL CCHK3( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, Y, YY, YS, YT, G, Z )\n            GO TO 200\n*           Test CGERC, 12, CGERU, 13.\n  170       CALL CCHK4( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n            GO TO 200\n*           Test CHER, 14, and CHPR, 15.\n  180       CALL CCHK5( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n            GO TO 200\n*           Test CHER2, 16, and CHPR2, 17.\n  190       CALL CCHK6( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n*\n  200       IF( FATAL.AND.SFATAL )\n     $         GO TO 220\n         END IF\n  210 CONTINUE\n      WRITE( NOUT, FMT = 9982 )\n      GO TO 240\n*\n  220 CONTINUE\n      WRITE( NOUT, FMT = 9981 )\n      GO TO 240\n*\n  230 CONTINUE\n      WRITE( NOUT, FMT = 9987 )\n*\n  240 CONTINUE\n      IF( TRACE )\n     $   CLOSE ( NTRA )\n      CLOSE ( NOUT )\n      STOP\n*\n 9999 FORMAT( ' ROUTINES PASS COMPUTATIONAL TESTS IF TEST RATIO IS LES',\n     $      'S THAN', F8.2 )\n 9998 FORMAT( ' RELATIVE MACHINE PRECISION IS TAKEN TO BE', 1P, E9.1 )\n 9997 FORMAT( ' NUMBER OF VALUES OF ', A, ' IS LESS THAN 1 OR GREATER ',\n     $      'THAN ', I2 )\n 9996 FORMAT( ' VALUE OF N IS LESS THAN 0 OR GREATER THAN ', I2 )\n 9995 FORMAT( ' VALUE OF K IS LESS THAN 0' )\n 9994 FORMAT( ' ABSOLUTE VALUE OF INCX OR INCY IS 0 OR GREATER THAN ',\n     $      I2 )\n 9993 FORMAT( ' TESTS OF THE COMPLEX          LEVEL 2 BLAS', //' THE F',\n     $      'OLLOWING PARAMETER VALUES WILL BE USED:' )\n 9992 FORMAT( '   FOR N              ', 9I6 )\n 9991 FORMAT( '   FOR K              ', 7I6 )\n 9990 FORMAT( '   FOR INCX AND INCY  ', 7I6 )\n 9989 FORMAT( '   FOR ALPHA          ',\n     $      7( '(', F4.1, ',', F4.1, ')  ', : ) )\n 9988 FORMAT( '   FOR BETA           ',\n     $      7( '(', F4.1, ',', F4.1, ')  ', : ) )\n 9987 FORMAT( ' AMEND DATA FILE OR INCREASE ARRAY SIZES IN PROGRAM',\n     $      /' ******* TESTS ABANDONED *******' )\n 9986 FORMAT( ' SUBPROGRAM NAME ', A6, ' NOT RECOGNIZED', /' ******* T',\n     $      'ESTS ABANDONED *******' )\n 9985 FORMAT( ' ERROR IN CMVCH -  IN-LINE DOT PRODUCTS ARE BEING EVALU',\n     $      'ATED WRONGLY.', /' CMVCH WAS CALLED WITH TRANS = ', A1,\n     $      ' AND RETURNED SAME = ', L1, ' AND ERR = ', F12.3, '.', /\n     $   ' THIS MAY BE DUE TO FAULTS IN THE ARITHMETIC OR THE COMPILER.'\n     $      , /' ******* TESTS ABANDONED *******' )\n 9984 FORMAT( A6, L2 )\n 9983 FORMAT( 1X, A6, ' WAS NOT TESTED' )\n 9982 FORMAT( /' END OF TESTS' )\n 9981 FORMAT( /' ******* FATAL ERROR - TESTS ABANDONED *******' )\n 9980 FORMAT( ' ERROR-EXITS WILL NOT BE TESTED' )\n*\n*     End of CBLAT2.\n*\n      END\n      SUBROUTINE CCHK1( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF, NBET,\n     $                  BET, NINC, INC, NMAX, INCMAX, A, AA, AS, X, XX,\n     $                  XS, Y, YY, YS, YT, G )\n*\n*  Tests CGEMV and CGBMV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO, HALF\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), HALF = ( 0.5, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NALF, NBET, NIDIM, NINC, NKB, NMAX,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), BET( NBET ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XX( NMAX*INCMAX ),\n     $                   Y( NMAX ), YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, ALS, BETA, BLS, TRANSL\n      REAL               ERR, ERRMAX\n      INTEGER            I, IA, IB, IC, IKU, IM, IN, INCX, INCXS, INCY,\n     $                   INCYS, IX, IY, KL, KLS, KU, KUS, LAA, LDA,\n     $                   LDAS, LX, LY, M, ML, MS, N, NARGS, NC, ND, NK,\n     $                   NL, NS\n      LOGICAL            BANDED, FULL, NULL, RESET, SAME, TRAN\n      CHARACTER*1        TRANS, TRANSS\n      CHARACTER*3        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CGBMV, CGEMV, CMAKE, CMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'NTC'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'E'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 11\n      ELSE IF( BANDED )THEN\n         NARGS = 13\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 120 IN = 1, NIDIM\n         N = IDIM( IN )\n         ND = N/2 + 1\n*\n         DO 110 IM = 1, 2\n            IF( IM.EQ.1 )\n     $         M = MAX( N - ND, 0 )\n            IF( IM.EQ.2 )\n     $         M = MIN( N + ND, NMAX )\n*\n            IF( BANDED )THEN\n               NK = NKB\n            ELSE\n               NK = 1\n            END IF\n            DO 100 IKU = 1, NK\n               IF( BANDED )THEN\n                  KU = KB( IKU )\n                  KL = MAX( KU - 1, 0 )\n               ELSE\n                  KU = N - 1\n                  KL = M - 1\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               IF( BANDED )THEN\n                  LDA = KL + KU + 1\n               ELSE\n                  LDA = M\n               END IF\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 100\n               LAA = LDA*N\n               NULL = N.LE.0.OR.M.LE.0\n*\n*              Generate the matrix A.\n*\n               TRANSL = ZERO\n               CALL CMAKE( SNAME( 2: 3 ), ' ', ' ', M, N, A, NMAX, AA,\n     $                     LDA, KL, KU, RESET, TRANSL )\n*\n               DO 90 IC = 1, 3\n                  TRANS = ICH( IC: IC )\n                  TRAN = TRANS.EQ.'T'.OR.TRANS.EQ.'C'\n*\n                  IF( TRAN )THEN\n                     ML = N\n                     NL = M\n                  ELSE\n                     ML = M\n                     NL = N\n                  END IF\n*\n                  DO 80 IX = 1, NINC\n                     INCX = INC( IX )\n                     LX = ABS( INCX )*NL\n*\n*                    Generate the vector X.\n*\n                     TRANSL = HALF\n                     CALL CMAKE( 'GE', ' ', ' ', 1, NL, X, 1, XX,\n     $                           ABS( INCX ), 0, NL - 1, RESET, TRANSL )\n                     IF( NL.GT.1 )THEN\n                        X( NL/2 ) = ZERO\n                        XX( 1 + ABS( INCX )*( NL/2 - 1 ) ) = ZERO\n                     END IF\n*\n                     DO 70 IY = 1, NINC\n                        INCY = INC( IY )\n                        LY = ABS( INCY )*ML\n*\n                        DO 60 IA = 1, NALF\n                           ALPHA = ALF( IA )\n*\n                           DO 50 IB = 1, NBET\n                              BETA = BET( IB )\n*\n*                             Generate the vector Y.\n*\n                              TRANSL = ZERO\n                              CALL CMAKE( 'GE', ' ', ' ', 1, ML, Y, 1,\n     $                                    YY, ABS( INCY ), 0, ML - 1,\n     $                                    RESET, TRANSL )\n*\n                              NC = NC + 1\n*\n*                             Save every datum before calling the\n*                             subroutine.\n*\n                              TRANSS = TRANS\n                              MS = M\n                              NS = N\n                              KLS = KL\n                              KUS = KU\n                              ALS = ALPHA\n                              DO 10 I = 1, LAA\n                                 AS( I ) = AA( I )\n   10                         CONTINUE\n                              LDAS = LDA\n                              DO 20 I = 1, LX\n                                 XS( I ) = XX( I )\n   20                         CONTINUE\n                              INCXS = INCX\n                              BLS = BETA\n                              DO 30 I = 1, LY\n                                 YS( I ) = YY( I )\n   30                         CONTINUE\n                              INCYS = INCY\n*\n*                             Call the subroutine.\n*\n                              IF( FULL )THEN\n                                 IF( TRACE )\n     $                              WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                              TRANS, M, N, ALPHA, LDA, INCX, BETA,\n     $                              INCY\n                                 IF( REWI )\n     $                              REWIND NTRA\n                                 CALL CGEMV( TRANS, M, N, ALPHA, AA,\n     $                                       LDA, XX, INCX, BETA, YY,\n     $                                       INCY )\n                              ELSE IF( BANDED )THEN\n                                 IF( TRACE )\n     $                              WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                              TRANS, M, N, KL, KU, ALPHA, LDA,\n     $                              INCX, BETA, INCY\n                                 IF( REWI )\n     $                              REWIND NTRA\n                                 CALL CGBMV( TRANS, M, N, KL, KU, ALPHA,\n     $                                       AA, LDA, XX, INCX, BETA,\n     $                                       YY, INCY )\n                              END IF\n*\n*                             Check if error-exit was taken incorrectly.\n*\n                              IF( .NOT.OK )THEN\n                                 WRITE( NOUT, FMT = 9993 )\n                                 FATAL = .TRUE.\n                                 GO TO 130\n                              END IF\n*\n*                             See what data changed inside subroutines.\n*\n                              ISAME( 1 ) = TRANS.EQ.TRANSS\n                              ISAME( 2 ) = MS.EQ.M\n                              ISAME( 3 ) = NS.EQ.N\n                              IF( FULL )THEN\n                                 ISAME( 4 ) = ALS.EQ.ALPHA\n                                 ISAME( 5 ) = LCE( AS, AA, LAA )\n                                 ISAME( 6 ) = LDAS.EQ.LDA\n                                 ISAME( 7 ) = LCE( XS, XX, LX )\n                                 ISAME( 8 ) = INCXS.EQ.INCX\n                                 ISAME( 9 ) = BLS.EQ.BETA\n                                 IF( NULL )THEN\n                                    ISAME( 10 ) = LCE( YS, YY, LY )\n                                 ELSE\n                                    ISAME( 10 ) = LCERES( 'GE', ' ', 1,\n     $                                            ML, YS, YY,\n     $                                            ABS( INCY ) )\n                                 END IF\n                                 ISAME( 11 ) = INCYS.EQ.INCY\n                              ELSE IF( BANDED )THEN\n                                 ISAME( 4 ) = KLS.EQ.KL\n                                 ISAME( 5 ) = KUS.EQ.KU\n                                 ISAME( 6 ) = ALS.EQ.ALPHA\n                                 ISAME( 7 ) = LCE( AS, AA, LAA )\n                                 ISAME( 8 ) = LDAS.EQ.LDA\n                                 ISAME( 9 ) = LCE( XS, XX, LX )\n                                 ISAME( 10 ) = INCXS.EQ.INCX\n                                 ISAME( 11 ) = BLS.EQ.BETA\n                                 IF( NULL )THEN\n                                    ISAME( 12 ) = LCE( YS, YY, LY )\n                                 ELSE\n                                    ISAME( 12 ) = LCERES( 'GE', ' ', 1,\n     $                                            ML, YS, YY,\n     $                                            ABS( INCY ) )\n                                 END IF\n                                 ISAME( 13 ) = INCYS.EQ.INCY\n                              END IF\n*\n*                             If data was incorrectly changed, report\n*                             and return.\n*\n                              SAME = .TRUE.\n                              DO 40 I = 1, NARGS\n                                 SAME = SAME.AND.ISAME( I )\n                                 IF( .NOT.ISAME( I ) )\n     $                              WRITE( NOUT, FMT = 9998 )I\n   40                         CONTINUE\n                              IF( .NOT.SAME )THEN\n                                 FATAL = .TRUE.\n                                 GO TO 130\n                              END IF\n*\n                              IF( .NOT.NULL )THEN\n*\n*                                Check the result.\n*\n                                 CALL CMVCH( TRANS, M, N, ALPHA, A,\n     $                                       NMAX, X, INCX, BETA, Y,\n     $                                       INCY, YT, G, YY, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                                 ERRMAX = MAX( ERRMAX, ERR )\n*                                If got really bad answer, report and\n*                                return.\n                                 IF( FATAL )\n     $                              GO TO 130\n                              ELSE\n*                                Avoid repeating tests with M.le.0 or\n*                                N.le.0.\n                                 GO TO 110\n                              END IF\n*\n   50                      CONTINUE\n*\n   60                   CONTINUE\n*\n   70                CONTINUE\n*\n   80             CONTINUE\n*\n   90          CONTINUE\n*\n  100       CONTINUE\n*\n  110    CONTINUE\n*\n  120 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 140\n*\n  130 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, TRANS, M, N, ALPHA, LDA,\n     $      INCX, BETA, INCY\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, TRANS, M, N, KL, KU,\n     $      ALPHA, LDA, INCX, BETA, INCY\n      END IF\n*\n  140 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 4( I3, ',' ), '(',\n     $      F4.1, ',', F4.1, '), A,', I3, ', X,', I2, ',(', F4.1, ',',\n     $      F4.1, '), Y,', I2, ') .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 2( I3, ',' ), '(',\n     $      F4.1, ',', F4.1, '), A,', I3, ', X,', I2, ',(', F4.1, ',',\n     $      F4.1, '), Y,', I2, ')         .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK1.\n*\n      END\n      SUBROUTINE CCHK2( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF, NBET,\n     $                  BET, NINC, INC, NMAX, INCMAX, A, AA, AS, X, XX,\n     $                  XS, Y, YY, YS, YT, G )\n*\n*  Tests CHEMV, CHBMV and CHPMV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO, HALF\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), HALF = ( 0.5, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NALF, NBET, NIDIM, NINC, NKB, NMAX,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), BET( NBET ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XX( NMAX*INCMAX ),\n     $                   Y( NMAX ), YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, ALS, BETA, BLS, TRANSL\n      REAL               ERR, ERRMAX\n      INTEGER            I, IA, IB, IC, IK, IN, INCX, INCXS, INCY,\n     $                   INCYS, IX, IY, K, KS, LAA, LDA, LDAS, LX, LY,\n     $                   N, NARGS, NC, NK, NS\n      LOGICAL            BANDED, FULL, NULL, PACKED, RESET, SAME\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CHBMV, CHEMV, CHPMV, CMAKE, CMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'E'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 10\n      ELSE IF( BANDED )THEN\n         NARGS = 11\n      ELSE IF( PACKED )THEN\n         NARGS = 9\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 110 IN = 1, NIDIM\n         N = IDIM( IN )\n*\n         IF( BANDED )THEN\n            NK = NKB\n         ELSE\n            NK = 1\n         END IF\n         DO 100 IK = 1, NK\n            IF( BANDED )THEN\n               K = KB( IK )\n            ELSE\n               K = N - 1\n            END IF\n*           Set LDA to 1 more than minimum value if room.\n            IF( BANDED )THEN\n               LDA = K + 1\n            ELSE\n               LDA = N\n            END IF\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 100\n            IF( PACKED )THEN\n               LAA = ( N*( N + 1 ) )/2\n            ELSE\n               LAA = LDA*N\n            END IF\n            NULL = N.LE.0\n*\n            DO 90 IC = 1, 2\n               UPLO = ICH( IC: IC )\n*\n*              Generate the matrix A.\n*\n               TRANSL = ZERO\n               CALL CMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A, NMAX, AA,\n     $                     LDA, K, K, RESET, TRANSL )\n*\n               DO 80 IX = 1, NINC\n                  INCX = INC( IX )\n                  LX = ABS( INCX )*N\n*\n*                 Generate the vector X.\n*\n                  TRANSL = HALF\n                  CALL CMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX,\n     $                        ABS( INCX ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     X( N/2 ) = ZERO\n                     XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 70 IY = 1, NINC\n                     INCY = INC( IY )\n                     LY = ABS( INCY )*N\n*\n                     DO 60 IA = 1, NALF\n                        ALPHA = ALF( IA )\n*\n                        DO 50 IB = 1, NBET\n                           BETA = BET( IB )\n*\n*                          Generate the vector Y.\n*\n                           TRANSL = ZERO\n                           CALL CMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                                 ABS( INCY ), 0, N - 1, RESET,\n     $                                 TRANSL )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           UPLOS = UPLO\n                           NS = N\n                           KS = K\n                           ALS = ALPHA\n                           DO 10 I = 1, LAA\n                              AS( I ) = AA( I )\n   10                      CONTINUE\n                           LDAS = LDA\n                           DO 20 I = 1, LX\n                              XS( I ) = XX( I )\n   20                      CONTINUE\n                           INCXS = INCX\n                           BLS = BETA\n                           DO 30 I = 1, LY\n                              YS( I ) = YY( I )\n   30                      CONTINUE\n                           INCYS = INCY\n*\n*                          Call the subroutine.\n*\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, N, ALPHA, LDA, INCX, BETA, INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CHEMV( UPLO, N, ALPHA, AA, LDA, XX,\n     $                                    INCX, BETA, YY, INCY )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, N, K, ALPHA, LDA, INCX, BETA,\n     $                           INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CHBMV( UPLO, N, K, ALPHA, AA, LDA,\n     $                                    XX, INCX, BETA, YY, INCY )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, N, ALPHA, INCX, BETA, INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CHPMV( UPLO, N, ALPHA, AA, XX, INCX,\n     $                                    BETA, YY, INCY )\n                           END IF\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9992 )\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = UPLO.EQ.UPLOS\n                           ISAME( 2 ) = NS.EQ.N\n                           IF( FULL )THEN\n                              ISAME( 3 ) = ALS.EQ.ALPHA\n                              ISAME( 4 ) = LCE( AS, AA, LAA )\n                              ISAME( 5 ) = LDAS.EQ.LDA\n                              ISAME( 6 ) = LCE( XS, XX, LX )\n                              ISAME( 7 ) = INCXS.EQ.INCX\n                              ISAME( 8 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 9 ) = LCE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 9 ) = LCERES( 'GE', ' ', 1, N,\n     $                                        YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 10 ) = INCYS.EQ.INCY\n                           ELSE IF( BANDED )THEN\n                              ISAME( 3 ) = KS.EQ.K\n                              ISAME( 4 ) = ALS.EQ.ALPHA\n                              ISAME( 5 ) = LCE( AS, AA, LAA )\n                              ISAME( 6 ) = LDAS.EQ.LDA\n                              ISAME( 7 ) = LCE( XS, XX, LX )\n                              ISAME( 8 ) = INCXS.EQ.INCX\n                              ISAME( 9 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 10 ) = LCE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 10 ) = LCERES( 'GE', ' ', 1, N,\n     $                                         YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 11 ) = INCYS.EQ.INCY\n                           ELSE IF( PACKED )THEN\n                              ISAME( 3 ) = ALS.EQ.ALPHA\n                              ISAME( 4 ) = LCE( AS, AA, LAA )\n                              ISAME( 5 ) = LCE( XS, XX, LX )\n                              ISAME( 6 ) = INCXS.EQ.INCX\n                              ISAME( 7 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 8 ) = LCE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 8 ) = LCERES( 'GE', ' ', 1, N,\n     $                                        YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 9 ) = INCYS.EQ.INCY\n                           END IF\n*\n*                          If data was incorrectly changed, report and\n*                          return.\n*\n                           SAME = .TRUE.\n                           DO 40 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   40                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n*\n*                             Check the result.\n*\n                              CALL CMVCH( 'N', N, N, ALPHA, A, NMAX, X,\n     $                                    INCX, BETA, Y, INCY, YT, G,\n     $                                    YY, EPS, ERR, FATAL, NOUT,\n     $                                    .TRUE. )\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 120\n                           ELSE\n*                             Avoid repeating tests with N.le.0\n                              GO TO 110\n                           END IF\n*\n   50                   CONTINUE\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, ALPHA, LDA, INCX,\n     $      BETA, INCY\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, K, ALPHA, LDA,\n     $      INCX, BETA, INCY\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, UPLO, N, ALPHA, INCX,\n     $      BETA, INCY\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',(', F4.1, ',',\n     $      F4.1, '), AP, X,', I2, ',(', F4.1, ',', F4.1, '), Y,', I2,\n     $      ')                .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 2( I3, ',' ), '(',\n     $      F4.1, ',', F4.1, '), A,', I3, ', X,', I2, ',(', F4.1, ',',\n     $      F4.1, '), Y,', I2, ')         .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',(', F4.1, ',',\n     $      F4.1, '), A,', I3, ', X,', I2, ',(', F4.1, ',', F4.1, '), ',\n     $      'Y,', I2, ')             .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK2.\n*\n      END\n      SUBROUTINE CCHK3( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, XT, G, Z )\n*\n*  Tests CTRMV, CTBMV, CTPMV, CTRSV, CTBSV and CTPSV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO, HALF, ONE\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), HALF = ( 0.5, 0.0 ),\n     $                   ONE = ( 1.0, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NIDIM, NINC, NKB, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ),\n     $                   AS( NMAX*NMAX ), X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XT( NMAX ), XX( NMAX*INCMAX ), Z( NMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      COMPLEX            TRANSL\n      REAL               ERR, ERRMAX\n      INTEGER            I, ICD, ICT, ICU, IK, IN, INCX, INCXS, IX, K,\n     $                   KS, LAA, LDA, LDAS, LX, N, NARGS, NC, NK, NS\n      LOGICAL            BANDED, FULL, NULL, PACKED, RESET, SAME\n      CHARACTER*1        DIAG, DIAGS, TRANS, TRANSS, UPLO, UPLOS\n      CHARACTER*2        ICHD, ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CMAKE, CMVCH, CTBMV, CTBSV, CTPMV, CTPSV,\n     $                   CTRMV, CTRSV\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHU/'UL'/, ICHT/'NTC'/, ICHD/'UN'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'R'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 8\n      ELSE IF( BANDED )THEN\n         NARGS = 9\n      ELSE IF( PACKED )THEN\n         NARGS = 7\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*     Set up zero vector for CMVCH.\n      DO 10 I = 1, NMAX\n         Z( I ) = ZERO\n   10 CONTINUE\n*\n      DO 110 IN = 1, NIDIM\n         N = IDIM( IN )\n*\n         IF( BANDED )THEN\n            NK = NKB\n         ELSE\n            NK = 1\n         END IF\n         DO 100 IK = 1, NK\n            IF( BANDED )THEN\n               K = KB( IK )\n            ELSE\n               K = N - 1\n            END IF\n*           Set LDA to 1 more than minimum value if room.\n            IF( BANDED )THEN\n               LDA = K + 1\n            ELSE\n               LDA = N\n            END IF\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 100\n            IF( PACKED )THEN\n               LAA = ( N*( N + 1 ) )/2\n            ELSE\n               LAA = LDA*N\n            END IF\n            NULL = N.LE.0\n*\n            DO 90 ICU = 1, 2\n               UPLO = ICHU( ICU: ICU )\n*\n               DO 80 ICT = 1, 3\n                  TRANS = ICHT( ICT: ICT )\n*\n                  DO 70 ICD = 1, 2\n                     DIAG = ICHD( ICD: ICD )\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL CMAKE( SNAME( 2: 3 ), UPLO, DIAG, N, N, A,\n     $                           NMAX, AA, LDA, K, K, RESET, TRANSL )\n*\n                     DO 60 IX = 1, NINC\n                        INCX = INC( IX )\n                        LX = ABS( INCX )*N\n*\n*                       Generate the vector X.\n*\n                        TRANSL = HALF\n                        CALL CMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX,\n     $                              ABS( INCX ), 0, N - 1, RESET,\n     $                              TRANSL )\n                        IF( N.GT.1 )THEN\n                           X( N/2 ) = ZERO\n                           XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n                        END IF\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        DIAGS = DIAG\n                        NS = N\n                        KS = K\n                        DO 20 I = 1, LAA\n                           AS( I ) = AA( I )\n   20                   CONTINUE\n                        LDAS = LDA\n                        DO 30 I = 1, LX\n                           XS( I ) = XX( I )\n   30                   CONTINUE\n                        INCXS = INCX\n*\n*                       Call the subroutine.\n*\n                        IF( SNAME( 4: 5 ).EQ.'MV' )THEN\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CTRMV( UPLO, TRANS, DIAG, N, AA, LDA,\n     $                                    XX, INCX )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, K, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CTBMV( UPLO, TRANS, DIAG, N, K, AA,\n     $                                    LDA, XX, INCX )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CTPMV( UPLO, TRANS, DIAG, N, AA, XX,\n     $                                    INCX )\n                           END IF\n                        ELSE IF( SNAME( 4: 5 ).EQ.'SV' )THEN\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CTRSV( UPLO, TRANS, DIAG, N, AA, LDA,\n     $                                    XX, INCX )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, K, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CTBSV( UPLO, TRANS, DIAG, N, K, AA,\n     $                                    LDA, XX, INCX )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CTPSV( UPLO, TRANS, DIAG, N, AA, XX,\n     $                                    INCX )\n                           END IF\n                        END IF\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9992 )\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLO.EQ.UPLOS\n                        ISAME( 2 ) = TRANS.EQ.TRANSS\n                        ISAME( 3 ) = DIAG.EQ.DIAGS\n                        ISAME( 4 ) = NS.EQ.N\n                        IF( FULL )THEN\n                           ISAME( 5 ) = LCE( AS, AA, LAA )\n                           ISAME( 6 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 7 ) = LCE( XS, XX, LX )\n                           ELSE\n                              ISAME( 7 ) = LCERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 8 ) = INCXS.EQ.INCX\n                        ELSE IF( BANDED )THEN\n                           ISAME( 5 ) = KS.EQ.K\n                           ISAME( 6 ) = LCE( AS, AA, LAA )\n                           ISAME( 7 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 8 ) = LCE( XS, XX, LX )\n                           ELSE\n                              ISAME( 8 ) = LCERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 9 ) = INCXS.EQ.INCX\n                        ELSE IF( PACKED )THEN\n                           ISAME( 5 ) = LCE( AS, AA, LAA )\n                           IF( NULL )THEN\n                              ISAME( 6 ) = LCE( XS, XX, LX )\n                           ELSE\n                              ISAME( 6 ) = LCERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 7 ) = INCXS.EQ.INCX\n                        END IF\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n                           IF( SNAME( 4: 5 ).EQ.'MV' )THEN\n*\n*                             Check the result.\n*\n                              CALL CMVCH( TRANS, N, N, ONE, A, NMAX, X,\n     $                                    INCX, ZERO, Z, INCX, XT, G,\n     $                                    XX, EPS, ERR, FATAL, NOUT,\n     $                                    .TRUE. )\n                           ELSE IF( SNAME( 4: 5 ).EQ.'SV' )THEN\n*\n*                             Compute approximation to original vector.\n*\n                              DO 50 I = 1, N\n                                 Z( I ) = XX( 1 + ( I - 1 )*\n     $                                    ABS( INCX ) )\n                                 XX( 1 + ( I - 1 )*ABS( INCX ) )\n     $                              = X( I )\n   50                         CONTINUE\n                              CALL CMVCH( TRANS, N, N, ONE, A, NMAX, Z,\n     $                                    INCX, ZERO, X, INCX, XT, G,\n     $                                    XX, EPS, ERR, FATAL, NOUT,\n     $                                    .FALSE. )\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 120\n                        ELSE\n*                          Avoid repeating tests with N.le.0.\n                           GO TO 110\n                        END IF\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, TRANS, DIAG, N, LDA,\n     $      INCX\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, DIAG, N, K,\n     $      LDA, INCX\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, UPLO, TRANS, DIAG, N, INCX\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), I3, ', AP, ',\n     $      'X,', I2, ')                                      .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), 2( I3, ',' ),\n     $      ' A,', I3, ', X,', I2, ')                               .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), I3, ', A,',\n     $      I3, ', X,', I2, ')                                   .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK3.\n*\n      END\n      SUBROUTINE CCHK4( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests CGERC and CGERU.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO, HALF, ONE\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), HALF = ( 0.5, 0.0 ),\n     $                   ONE = ( 1.0, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, ALS, TRANSL\n      REAL               ERR, ERRMAX\n      INTEGER            I, IA, IM, IN, INCX, INCXS, INCY, INCYS, IX,\n     $                   IY, J, LAA, LDA, LDAS, LX, LY, M, MS, N, NARGS,\n     $                   NC, ND, NS\n      LOGICAL            CONJ, NULL, RESET, SAME\n*     .. Local Arrays ..\n      COMPLEX            W( 1 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CGERC, CGERU, CMAKE, CMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, CONJG, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n      CONJ = SNAME( 5: 5 ).EQ.'C'\n*     Define the number of arguments.\n      NARGS = 9\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 120 IN = 1, NIDIM\n         N = IDIM( IN )\n         ND = N/2 + 1\n*\n         DO 110 IM = 1, 2\n            IF( IM.EQ.1 )\n     $         M = MAX( N - ND, 0 )\n            IF( IM.EQ.2 )\n     $         M = MIN( N + ND, NMAX )\n*\n*           Set LDA to 1 more than minimum value if room.\n            LDA = M\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 110\n            LAA = LDA*N\n            NULL = N.LE.0.OR.M.LE.0\n*\n            DO 100 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*M\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL CMAKE( 'GE', ' ', ' ', 1, M, X, 1, XX, ABS( INCX ),\n     $                     0, M - 1, RESET, TRANSL )\n               IF( M.GT.1 )THEN\n                  X( M/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( M/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 90 IY = 1, NINC\n                  INCY = INC( IY )\n                  LY = ABS( INCY )*N\n*\n*                 Generate the vector Y.\n*\n                  TRANSL = ZERO\n                  CALL CMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                        ABS( INCY ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     Y( N/2 ) = ZERO\n                     YY( 1 + ABS( INCY )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 80 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL CMAKE( SNAME( 2: 3 ), ' ', ' ', M, N, A, NMAX,\n     $                           AA, LDA, M - 1, N - 1, RESET, TRANSL )\n*\n                     NC = NC + 1\n*\n*                    Save every datum before calling the subroutine.\n*\n                     MS = M\n                     NS = N\n                     ALS = ALPHA\n                     DO 10 I = 1, LAA\n                        AS( I ) = AA( I )\n   10                CONTINUE\n                     LDAS = LDA\n                     DO 20 I = 1, LX\n                        XS( I ) = XX( I )\n   20                CONTINUE\n                     INCXS = INCX\n                     DO 30 I = 1, LY\n                        YS( I ) = YY( I )\n   30                CONTINUE\n                     INCYS = INCY\n*\n*                    Call the subroutine.\n*\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9994 )NC, SNAME, M, N,\n     $                  ALPHA, INCX, INCY, LDA\n                     IF( CONJ )THEN\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL CGERC( M, N, ALPHA, XX, INCX, YY, INCY, AA,\n     $                              LDA )\n                     ELSE\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL CGERU( M, N, ALPHA, XX, INCX, YY, INCY, AA,\n     $                              LDA )\n                     END IF\n*\n*                    Check if error-exit was taken incorrectly.\n*\n                     IF( .NOT.OK )THEN\n                        WRITE( NOUT, FMT = 9993 )\n                        FATAL = .TRUE.\n                        GO TO 140\n                     END IF\n*\n*                    See what data changed inside subroutine.\n*\n                     ISAME( 1 ) = MS.EQ.M\n                     ISAME( 2 ) = NS.EQ.N\n                     ISAME( 3 ) = ALS.EQ.ALPHA\n                     ISAME( 4 ) = LCE( XS, XX, LX )\n                     ISAME( 5 ) = INCXS.EQ.INCX\n                     ISAME( 6 ) = LCE( YS, YY, LY )\n                     ISAME( 7 ) = INCYS.EQ.INCY\n                     IF( NULL )THEN\n                        ISAME( 8 ) = LCE( AS, AA, LAA )\n                     ELSE\n                        ISAME( 8 ) = LCERES( 'GE', ' ', M, N, AS, AA,\n     $                               LDA )\n                     END IF\n                     ISAME( 9 ) = LDAS.EQ.LDA\n*\n*                    If data was incorrectly changed, report and return.\n*\n                     SAME = .TRUE.\n                     DO 40 I = 1, NARGS\n                        SAME = SAME.AND.ISAME( I )\n                        IF( .NOT.ISAME( I ) )\n     $                     WRITE( NOUT, FMT = 9998 )I\n   40                CONTINUE\n                     IF( .NOT.SAME )THEN\n                        FATAL = .TRUE.\n                        GO TO 140\n                     END IF\n*\n                     IF( .NOT.NULL )THEN\n*\n*                       Check the result column by column.\n*\n                        IF( INCX.GT.0 )THEN\n                           DO 50 I = 1, M\n                              Z( I ) = X( I )\n   50                      CONTINUE\n                        ELSE\n                           DO 60 I = 1, M\n                              Z( I ) = X( M - I + 1 )\n   60                      CONTINUE\n                        END IF\n                        DO 70 J = 1, N\n                           IF( INCY.GT.0 )THEN\n                              W( 1 ) = Y( J )\n                           ELSE\n                              W( 1 ) = Y( N - J + 1 )\n                           END IF\n                           IF( CONJ )\n     $                        W( 1 ) = CONJG( W( 1 ) )\n                           CALL CMVCH( 'N', M, 1, ALPHA, Z, NMAX, W, 1,\n     $                                 ONE, A( 1, J ), 1, YT, G,\n     $                                 AA( 1 + ( J - 1 )*LDA ), EPS,\n     $                                 ERR, FATAL, NOUT, .TRUE. )\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 130\n   70                   CONTINUE\n                     ELSE\n*                       Avoid repeating tests with M.le.0 or N.le.0.\n                        GO TO 110\n                     END IF\n*\n   80             CONTINUE\n*\n   90          CONTINUE\n*\n  100       CONTINUE\n*\n  110    CONTINUE\n*\n  120 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 150\n*\n  130 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  140 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9994 )NC, SNAME, M, N, ALPHA, INCX, INCY, LDA\n*\n  150 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( I3, ',' ), '(', F4.1, ',', F4.1,\n     $      '), X,', I2, ', Y,', I2, ', A,', I3, ')                   ',\n     $      '      .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK4.\n*\n      END\n      SUBROUTINE CCHK5( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests CHER and CHPR.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO, HALF, ONE\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), HALF = ( 0.5, 0.0 ),\n     $                   ONE = ( 1.0, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, TRANSL\n      REAL               ERR, ERRMAX, RALPHA, RALS\n      INTEGER            I, IA, IC, IN, INCX, INCXS, IX, J, JA, JJ, LAA,\n     $                   LDA, LDAS, LJ, LX, N, NARGS, NC, NS\n      LOGICAL            FULL, NULL, PACKED, RESET, SAME, UPPER\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      COMPLEX            W( 1 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CHER, CHPR, CMAKE, CMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, CMPLX, CONJG, MAX, REAL\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'E'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 7\n      ELSE IF( PACKED )THEN\n         NARGS = 6\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 100 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDA to 1 more than minimum value if room.\n         LDA = N\n         IF( LDA.LT.NMAX )\n     $      LDA = LDA + 1\n*        Skip tests if not enough room.\n         IF( LDA.GT.NMAX )\n     $      GO TO 100\n         IF( PACKED )THEN\n            LAA = ( N*( N + 1 ) )/2\n         ELSE\n            LAA = LDA*N\n         END IF\n*\n         DO 90 IC = 1, 2\n            UPLO = ICH( IC: IC )\n            UPPER = UPLO.EQ.'U'\n*\n            DO 80 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*N\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL CMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX, ABS( INCX ),\n     $                     0, N - 1, RESET, TRANSL )\n               IF( N.GT.1 )THEN\n                  X( N/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 70 IA = 1, NALF\n                  RALPHA = REAL( ALF( IA ) )\n                  ALPHA = CMPLX( RALPHA, RZERO )\n                  NULL = N.LE.0.OR.RALPHA.EQ.RZERO\n*\n*                 Generate the matrix A.\n*\n                  TRANSL = ZERO\n                  CALL CMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A, NMAX,\n     $                        AA, LDA, N - 1, N - 1, RESET, TRANSL )\n*\n                  NC = NC + 1\n*\n*                 Save every datum before calling the subroutine.\n*\n                  UPLOS = UPLO\n                  NS = N\n                  RALS = RALPHA\n                  DO 10 I = 1, LAA\n                     AS( I ) = AA( I )\n   10             CONTINUE\n                  LDAS = LDA\n                  DO 20 I = 1, LX\n                     XS( I ) = XX( I )\n   20             CONTINUE\n                  INCXS = INCX\n*\n*                 Call the subroutine.\n*\n                  IF( FULL )THEN\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO, N,\n     $                  RALPHA, INCX, LDA\n                     IF( REWI )\n     $                  REWIND NTRA\n                     CALL CHER( UPLO, N, RALPHA, XX, INCX, AA, LDA )\n                  ELSE IF( PACKED )THEN\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO, N,\n     $                  RALPHA, INCX\n                     IF( REWI )\n     $                  REWIND NTRA\n                     CALL CHPR( UPLO, N, RALPHA, XX, INCX, AA )\n                  END IF\n*\n*                 Check if error-exit was taken incorrectly.\n*\n                  IF( .NOT.OK )THEN\n                     WRITE( NOUT, FMT = 9992 )\n                     FATAL = .TRUE.\n                     GO TO 120\n                  END IF\n*\n*                 See what data changed inside subroutines.\n*\n                  ISAME( 1 ) = UPLO.EQ.UPLOS\n                  ISAME( 2 ) = NS.EQ.N\n                  ISAME( 3 ) = RALS.EQ.RALPHA\n                  ISAME( 4 ) = LCE( XS, XX, LX )\n                  ISAME( 5 ) = INCXS.EQ.INCX\n                  IF( NULL )THEN\n                     ISAME( 6 ) = LCE( AS, AA, LAA )\n                  ELSE\n                     ISAME( 6 ) = LCERES( SNAME( 2: 3 ), UPLO, N, N, AS,\n     $                            AA, LDA )\n                  END IF\n                  IF( .NOT.PACKED )THEN\n                     ISAME( 7 ) = LDAS.EQ.LDA\n                  END IF\n*\n*                 If data was incorrectly changed, report and return.\n*\n                  SAME = .TRUE.\n                  DO 30 I = 1, NARGS\n                     SAME = SAME.AND.ISAME( I )\n                     IF( .NOT.ISAME( I ) )\n     $                  WRITE( NOUT, FMT = 9998 )I\n   30             CONTINUE\n                  IF( .NOT.SAME )THEN\n                     FATAL = .TRUE.\n                     GO TO 120\n                  END IF\n*\n                  IF( .NOT.NULL )THEN\n*\n*                    Check the result column by column.\n*\n                     IF( INCX.GT.0 )THEN\n                        DO 40 I = 1, N\n                           Z( I ) = X( I )\n   40                   CONTINUE\n                     ELSE\n                        DO 50 I = 1, N\n                           Z( I ) = X( N - I + 1 )\n   50                   CONTINUE\n                     END IF\n                     JA = 1\n                     DO 60 J = 1, N\n                        W( 1 ) = CONJG( Z( J ) )\n                        IF( UPPER )THEN\n                           JJ = 1\n                           LJ = J\n                        ELSE\n                           JJ = J\n                           LJ = N - J + 1\n                        END IF\n                        CALL CMVCH( 'N', LJ, 1, ALPHA, Z( JJ ), LJ, W,\n     $                              1, ONE, A( JJ, J ), 1, YT, G,\n     $                              AA( JA ), EPS, ERR, FATAL, NOUT,\n     $                              .TRUE. )\n                        IF( FULL )THEN\n                           IF( UPPER )THEN\n                              JA = JA + LDA\n                           ELSE\n                              JA = JA + LDA + 1\n                           END IF\n                        ELSE\n                           JA = JA + LJ\n                        END IF\n                        ERRMAX = MAX( ERRMAX, ERR )\n*                       If got really bad answer, report and return.\n                        IF( FATAL )\n     $                     GO TO 110\n   60                CONTINUE\n                  ELSE\n*                    Avoid repeating tests if N.le.0.\n                     IF( N.LE.0 )\n     $                  GO TO 100\n                  END IF\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  110 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, RALPHA, INCX, LDA\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, RALPHA, INCX\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', AP)                                         .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', A,', I3, ')                                      .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK5.\n*\n      END\n      SUBROUTINE CCHK6( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests CHER2 and CHPR2.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO, HALF, ONE\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), HALF = ( 0.5, 0.0 ),\n     $                   ONE = ( 1.0, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX, 2 )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, ALS, TRANSL\n      REAL               ERR, ERRMAX\n      INTEGER            I, IA, IC, IN, INCX, INCXS, INCY, INCYS, IX,\n     $                   IY, J, JA, JJ, LAA, LDA, LDAS, LJ, LX, LY, N,\n     $                   NARGS, NC, NS\n      LOGICAL            FULL, NULL, PACKED, RESET, SAME, UPPER\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      COMPLEX            W( 2 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CHER2, CHPR2, CMAKE, CMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, CONJG, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'E'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 9\n      ELSE IF( PACKED )THEN\n         NARGS = 8\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 140 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDA to 1 more than minimum value if room.\n         LDA = N\n         IF( LDA.LT.NMAX )\n     $      LDA = LDA + 1\n*        Skip tests if not enough room.\n         IF( LDA.GT.NMAX )\n     $      GO TO 140\n         IF( PACKED )THEN\n            LAA = ( N*( N + 1 ) )/2\n         ELSE\n            LAA = LDA*N\n         END IF\n*\n         DO 130 IC = 1, 2\n            UPLO = ICH( IC: IC )\n            UPPER = UPLO.EQ.'U'\n*\n            DO 120 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*N\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL CMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX, ABS( INCX ),\n     $                     0, N - 1, RESET, TRANSL )\n               IF( N.GT.1 )THEN\n                  X( N/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 110 IY = 1, NINC\n                  INCY = INC( IY )\n                  LY = ABS( INCY )*N\n*\n*                 Generate the vector Y.\n*\n                  TRANSL = ZERO\n                  CALL CMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                        ABS( INCY ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     Y( N/2 ) = ZERO\n                     YY( 1 + ABS( INCY )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 100 IA = 1, NALF\n                     ALPHA = ALF( IA )\n                     NULL = N.LE.0.OR.ALPHA.EQ.ZERO\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL CMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A,\n     $                           NMAX, AA, LDA, N - 1, N - 1, RESET,\n     $                           TRANSL )\n*\n                     NC = NC + 1\n*\n*                    Save every datum before calling the subroutine.\n*\n                     UPLOS = UPLO\n                     NS = N\n                     ALS = ALPHA\n                     DO 10 I = 1, LAA\n                        AS( I ) = AA( I )\n   10                CONTINUE\n                     LDAS = LDA\n                     DO 20 I = 1, LX\n                        XS( I ) = XX( I )\n   20                CONTINUE\n                     INCXS = INCX\n                     DO 30 I = 1, LY\n                        YS( I ) = YY( I )\n   30                CONTINUE\n                     INCYS = INCY\n*\n*                    Call the subroutine.\n*\n                     IF( FULL )THEN\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO, N,\n     $                     ALPHA, INCX, INCY, LDA\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL CHER2( UPLO, N, ALPHA, XX, INCX, YY, INCY,\n     $                              AA, LDA )\n                     ELSE IF( PACKED )THEN\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO, N,\n     $                     ALPHA, INCX, INCY\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL CHPR2( UPLO, N, ALPHA, XX, INCX, YY, INCY,\n     $                              AA )\n                     END IF\n*\n*                    Check if error-exit was taken incorrectly.\n*\n                     IF( .NOT.OK )THEN\n                        WRITE( NOUT, FMT = 9992 )\n                        FATAL = .TRUE.\n                        GO TO 160\n                     END IF\n*\n*                    See what data changed inside subroutines.\n*\n                     ISAME( 1 ) = UPLO.EQ.UPLOS\n                     ISAME( 2 ) = NS.EQ.N\n                     ISAME( 3 ) = ALS.EQ.ALPHA\n                     ISAME( 4 ) = LCE( XS, XX, LX )\n                     ISAME( 5 ) = INCXS.EQ.INCX\n                     ISAME( 6 ) = LCE( YS, YY, LY )\n                     ISAME( 7 ) = INCYS.EQ.INCY\n                     IF( NULL )THEN\n                        ISAME( 8 ) = LCE( AS, AA, LAA )\n                     ELSE\n                        ISAME( 8 ) = LCERES( SNAME( 2: 3 ), UPLO, N, N,\n     $                               AS, AA, LDA )\n                     END IF\n                     IF( .NOT.PACKED )THEN\n                        ISAME( 9 ) = LDAS.EQ.LDA\n                     END IF\n*\n*                    If data was incorrectly changed, report and return.\n*\n                     SAME = .TRUE.\n                     DO 40 I = 1, NARGS\n                        SAME = SAME.AND.ISAME( I )\n                        IF( .NOT.ISAME( I ) )\n     $                     WRITE( NOUT, FMT = 9998 )I\n   40                CONTINUE\n                     IF( .NOT.SAME )THEN\n                        FATAL = .TRUE.\n                        GO TO 160\n                     END IF\n*\n                     IF( .NOT.NULL )THEN\n*\n*                       Check the result column by column.\n*\n                        IF( INCX.GT.0 )THEN\n                           DO 50 I = 1, N\n                              Z( I, 1 ) = X( I )\n   50                      CONTINUE\n                        ELSE\n                           DO 60 I = 1, N\n                              Z( I, 1 ) = X( N - I + 1 )\n   60                      CONTINUE\n                        END IF\n                        IF( INCY.GT.0 )THEN\n                           DO 70 I = 1, N\n                              Z( I, 2 ) = Y( I )\n   70                      CONTINUE\n                        ELSE\n                           DO 80 I = 1, N\n                              Z( I, 2 ) = Y( N - I + 1 )\n   80                      CONTINUE\n                        END IF\n                        JA = 1\n                        DO 90 J = 1, N\n                           W( 1 ) = ALPHA*CONJG( Z( J, 2 ) )\n                           W( 2 ) = CONJG( ALPHA )*CONJG( Z( J, 1 ) )\n                           IF( UPPER )THEN\n                              JJ = 1\n                              LJ = J\n                           ELSE\n                              JJ = J\n                              LJ = N - J + 1\n                           END IF\n                           CALL CMVCH( 'N', LJ, 2, ONE, Z( JJ, 1 ),\n     $                                 NMAX, W, 1, ONE, A( JJ, J ), 1,\n     $                                 YT, G, AA( JA ), EPS, ERR, FATAL,\n     $                                 NOUT, .TRUE. )\n                           IF( FULL )THEN\n                              IF( UPPER )THEN\n                                 JA = JA + LDA\n                              ELSE\n                                 JA = JA + LDA + 1\n                              END IF\n                           ELSE\n                              JA = JA + LJ\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 150\n   90                   CONTINUE\n                     ELSE\n*                       Avoid repeating tests with N.le.0.\n                        IF( N.LE.0 )\n     $                     GO TO 140\n                     END IF\n*\n  100             CONTINUE\n*\n  110          CONTINUE\n*\n  120       CONTINUE\n*\n  130    CONTINUE\n*\n  140 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 170\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  160 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, ALPHA, INCX,\n     $      INCY, LDA\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, ALPHA, INCX, INCY\n      END IF\n*\n  170 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',(', F4.1, ',',\n     $      F4.1, '), X,', I2, ', Y,', I2, ', AP)                     ',\n     $      '       .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',(', F4.1, ',',\n     $      F4.1, '), X,', I2, ', Y,', I2, ', A,', I3, ')             ',\n     $      '            .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK6.\n*\n      END\n      SUBROUTINE CCHKE( ISNUM, SRNAMT, NOUT )\n*\n*  Tests the error exits from the Level 2 Blas.\n*  Requires a special version of the error-handling routine XERBLA.\n*  ALPHA, RALPHA, BETA, A, X and Y should not need to be defined.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            ISNUM, NOUT\n      CHARACTER*6        SRNAMT\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, BETA\n      REAL               RALPHA\n*     .. Local Arrays ..\n      COMPLEX            A( 1, 1 ), X( 1 ), Y( 1 )\n*     .. External Subroutines ..\n      EXTERNAL           CGBMV, CGEMV, CGERC, CGERU, CHBMV, CHEMV, CHER,\n     $                   CHER2, CHKXER, CHPMV, CHPR, CHPR2, CTBMV,\n     $                   CTBSV, CTPMV, CTPSV, CTRMV, CTRSV\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n*     OK is set to .FALSE. by the special version of XERBLA or by CHKXER\n*     if anything is wrong.\n      OK = .TRUE.\n*     LERR is set to .TRUE. by the special version of XERBLA each time\n*     it is called, and is then tested and re-set by CHKXER.\n      LERR = .FALSE.\n      GO TO ( 10, 20, 30, 40, 50, 60, 70, 80,\n     $        90, 100, 110, 120, 130, 140, 150, 160,\n     $        170 )ISNUM\n   10 INFOT = 1\n      CALL CGEMV( '/', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CGEMV( 'N', -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGEMV( 'N', 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CGEMV( 'N', 2, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGEMV( 'N', 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CGEMV( 'N', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   20 INFOT = 1\n      CALL CGBMV( '/', 0, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CGBMV( 'N', -1, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGBMV( 'N', 0, -1, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CGBMV( 'N', 0, 0, -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGBMV( 'N', 2, 0, 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGBMV( 'N', 0, 0, 1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CGBMV( 'N', 0, 0, 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL CGBMV( 'N', 0, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   30 INFOT = 1\n      CALL CHEMV( '/', 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CHEMV( 'U', -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CHEMV( 'U', 2, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHEMV( 'U', 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CHEMV( 'U', 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   40 INFOT = 1\n      CALL CHBMV( '/', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CHBMV( 'U', -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHBMV( 'U', 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CHBMV( 'U', 0, 1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CHBMV( 'U', 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CHBMV( 'U', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   50 INFOT = 1\n      CALL CHPMV( '/', 0, ALPHA, A, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CHPMV( 'U', -1, ALPHA, A, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CHPMV( 'U', 0, ALPHA, A, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CHPMV( 'U', 0, ALPHA, A, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   60 INFOT = 1\n      CALL CTRMV( '/', 'N', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CTRMV( 'U', '/', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CTRMV( 'U', 'N', '/', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CTRMV( 'U', 'N', 'N', -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMV( 'U', 'N', 'N', 2, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CTRMV( 'U', 'N', 'N', 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   70 INFOT = 1\n      CALL CTBMV( '/', 'N', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CTBMV( 'U', '/', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CTBMV( 'U', 'N', '/', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CTBMV( 'U', 'N', 'N', -1, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTBMV( 'U', 'N', 'N', 0, -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CTBMV( 'U', 'N', 'N', 0, 1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTBMV( 'U', 'N', 'N', 0, 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   80 INFOT = 1\n      CALL CTPMV( '/', 'N', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CTPMV( 'U', '/', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CTPMV( 'U', 'N', '/', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CTPMV( 'U', 'N', 'N', -1, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CTPMV( 'U', 'N', 'N', 0, A, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   90 INFOT = 1\n      CALL CTRSV( '/', 'N', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CTRSV( 'U', '/', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CTRSV( 'U', 'N', '/', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CTRSV( 'U', 'N', 'N', -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSV( 'U', 'N', 'N', 2, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CTRSV( 'U', 'N', 'N', 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  100 INFOT = 1\n      CALL CTBSV( '/', 'N', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CTBSV( 'U', '/', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CTBSV( 'U', 'N', '/', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CTBSV( 'U', 'N', 'N', -1, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTBSV( 'U', 'N', 'N', 0, -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CTBSV( 'U', 'N', 'N', 0, 1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTBSV( 'U', 'N', 'N', 0, 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  110 INFOT = 1\n      CALL CTPSV( '/', 'N', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CTPSV( 'U', '/', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CTPSV( 'U', 'N', '/', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CTPSV( 'U', 'N', 'N', -1, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CTPSV( 'U', 'N', 'N', 0, A, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  120 INFOT = 1\n      CALL CGERC( -1, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CGERC( 0, -1, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGERC( 0, 0, ALPHA, X, 0, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CGERC( 0, 0, ALPHA, X, 1, Y, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CGERC( 2, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  130 INFOT = 1\n      CALL CGERU( -1, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CGERU( 0, -1, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGERU( 0, 0, ALPHA, X, 0, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CGERU( 0, 0, ALPHA, X, 1, Y, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CGERU( 2, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  140 INFOT = 1\n      CALL CHER( '/', 0, RALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CHER( 'U', -1, RALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CHER( 'U', 0, RALPHA, X, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHER( 'U', 2, RALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  150 INFOT = 1\n      CALL CHPR( '/', 0, RALPHA, X, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CHPR( 'U', -1, RALPHA, X, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CHPR( 'U', 0, RALPHA, X, 0, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  160 INFOT = 1\n      CALL CHER2( '/', 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CHER2( 'U', -1, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CHER2( 'U', 0, ALPHA, X, 0, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHER2( 'U', 0, ALPHA, X, 1, Y, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CHER2( 'U', 2, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  170 INFOT = 1\n      CALL CHPR2( '/', 0, ALPHA, X, 1, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CHPR2( 'U', -1, ALPHA, X, 1, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CHPR2( 'U', 0, ALPHA, X, 0, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHPR2( 'U', 0, ALPHA, X, 1, Y, 0, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n  180 IF( OK )THEN\n         WRITE( NOUT, FMT = 9999 )SRNAMT\n      ELSE\n         WRITE( NOUT, FMT = 9998 )SRNAMT\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE TESTS OF ERROR-EXITS' )\n 9998 FORMAT( ' ******* ', A6, ' FAILED THE TESTS OF ERROR-EXITS *****',\n     $      '**' )\n*\n*     End of CCHKE.\n*\n      END\n      SUBROUTINE CMAKE( TYPE, UPLO, DIAG, M, N, A, NMAX, AA, LDA, KL,\n     $                  KU, RESET, TRANSL )\n*\n*  Generates values for an M by N matrix A within the bandwidth\n*  defined by KL and KU.\n*  Stores the values in the array AA in the data structure required\n*  by the routine, with unwanted elements set to rogue value.\n*\n*  TYPE is 'GE', 'GB', 'HE', 'HB', 'HP', 'TR', 'TB' OR 'TP'.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), ONE = ( 1.0, 0.0 ) )\n      COMPLEX            ROGUE\n      PARAMETER          ( ROGUE = ( -1.0E10, 1.0E10 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n      REAL               RROGUE\n      PARAMETER          ( RROGUE = -1.0E10 )\n*     .. Scalar Arguments ..\n      COMPLEX            TRANSL\n      INTEGER            KL, KU, LDA, M, N, NMAX\n      LOGICAL            RESET\n      CHARACTER*1        DIAG, UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, * ), AA( * )\n*     .. Local Scalars ..\n      INTEGER            I, I1, I2, I3, IBEG, IEND, IOFF, J, JJ, KK\n      LOGICAL            GEN, LOWER, SYM, TRI, UNIT, UPPER\n*     .. External Functions ..\n      COMPLEX            CBEG\n      EXTERNAL           CBEG\n*     .. Intrinsic Functions ..\n      INTRINSIC          CMPLX, CONJG, MAX, MIN, REAL\n*     .. Executable Statements ..\n      GEN = TYPE( 1: 1 ).EQ.'G'\n      SYM = TYPE( 1: 1 ).EQ.'H'\n      TRI = TYPE( 1: 1 ).EQ.'T'\n      UPPER = ( SYM.OR.TRI ).AND.UPLO.EQ.'U'\n      LOWER = ( SYM.OR.TRI ).AND.UPLO.EQ.'L'\n      UNIT = TRI.AND.DIAG.EQ.'U'\n*\n*     Generate data in array A.\n*\n      DO 20 J = 1, N\n         DO 10 I = 1, M\n            IF( GEN.OR.( UPPER.AND.I.LE.J ).OR.( LOWER.AND.I.GE.J ) )\n     $          THEN\n               IF( ( I.LE.J.AND.J - I.LE.KU ).OR.\n     $             ( I.GE.J.AND.I - J.LE.KL ) )THEN\n                  A( I, J ) = CBEG( RESET ) + TRANSL\n               ELSE\n                  A( I, J ) = ZERO\n               END IF\n               IF( I.NE.J )THEN\n                  IF( SYM )THEN\n                     A( J, I ) = CONJG( A( I, J ) )\n                  ELSE IF( TRI )THEN\n                     A( J, I ) = ZERO\n                  END IF\n               END IF\n            END IF\n   10    CONTINUE\n         IF( SYM )\n     $      A( J, J ) = CMPLX( REAL( A( J, J ) ), RZERO )\n         IF( TRI )\n     $      A( J, J ) = A( J, J ) + ONE\n         IF( UNIT )\n     $      A( J, J ) = ONE\n   20 CONTINUE\n*\n*     Store elements in array AS in data structure required by routine.\n*\n      IF( TYPE.EQ.'GE' )THEN\n         DO 50 J = 1, N\n            DO 30 I = 1, M\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   30       CONTINUE\n            DO 40 I = M + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   40       CONTINUE\n   50    CONTINUE\n      ELSE IF( TYPE.EQ.'GB' )THEN\n         DO 90 J = 1, N\n            DO 60 I1 = 1, KU + 1 - J\n               AA( I1 + ( J - 1 )*LDA ) = ROGUE\n   60       CONTINUE\n            DO 70 I2 = I1, MIN( KL + KU + 1, KU + 1 + M - J )\n               AA( I2 + ( J - 1 )*LDA ) = A( I2 + J - KU - 1, J )\n   70       CONTINUE\n            DO 80 I3 = I2, LDA\n               AA( I3 + ( J - 1 )*LDA ) = ROGUE\n   80       CONTINUE\n   90    CONTINUE\n      ELSE IF( TYPE.EQ.'HE'.OR.TYPE.EQ.'TR' )THEN\n         DO 130 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IF( UNIT )THEN\n                  IEND = J - 1\n               ELSE\n                  IEND = J\n               END IF\n            ELSE\n               IF( UNIT )THEN\n                  IBEG = J + 1\n               ELSE\n                  IBEG = J\n               END IF\n               IEND = N\n            END IF\n            DO 100 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  100       CONTINUE\n            DO 110 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n  110       CONTINUE\n            DO 120 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  120       CONTINUE\n            IF( SYM )THEN\n               JJ = J + ( J - 1 )*LDA\n               AA( JJ ) = CMPLX( REAL( AA( JJ ) ), RROGUE )\n            END IF\n  130    CONTINUE\n      ELSE IF( TYPE.EQ.'HB'.OR.TYPE.EQ.'TB' )THEN\n         DO 170 J = 1, N\n            IF( UPPER )THEN\n               KK = KL + 1\n               IBEG = MAX( 1, KL + 2 - J )\n               IF( UNIT )THEN\n                  IEND = KL\n               ELSE\n                  IEND = KL + 1\n               END IF\n            ELSE\n               KK = 1\n               IF( UNIT )THEN\n                  IBEG = 2\n               ELSE\n                  IBEG = 1\n               END IF\n               IEND = MIN( KL + 1, 1 + M - J )\n            END IF\n            DO 140 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  140       CONTINUE\n            DO 150 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I + J - KK, J )\n  150       CONTINUE\n            DO 160 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  160       CONTINUE\n            IF( SYM )THEN\n               JJ = KK + ( J - 1 )*LDA\n               AA( JJ ) = CMPLX( REAL( AA( JJ ) ), RROGUE )\n            END IF\n  170    CONTINUE\n      ELSE IF( TYPE.EQ.'HP'.OR.TYPE.EQ.'TP' )THEN\n         IOFF = 0\n         DO 190 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 180 I = IBEG, IEND\n               IOFF = IOFF + 1\n               AA( IOFF ) = A( I, J )\n               IF( I.EQ.J )THEN\n                  IF( UNIT )\n     $               AA( IOFF ) = ROGUE\n                  IF( SYM )\n     $               AA( IOFF ) = CMPLX( REAL( AA( IOFF ) ), RROGUE )\n               END IF\n  180       CONTINUE\n  190    CONTINUE\n      END IF\n      RETURN\n*\n*     End of CMAKE.\n*\n      END\n      SUBROUTINE CMVCH( TRANS, M, N, ALPHA, A, NMAX, X, INCX, BETA, Y,\n     $                  INCY, YT, G, YY, EPS, ERR, FATAL, NOUT, MV )\n*\n*  Checks the results of the computational tests.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ) )\n      REAL               RZERO, RONE\n      PARAMETER          ( RZERO = 0.0, RONE = 1.0 )\n*     .. Scalar Arguments ..\n      COMPLEX            ALPHA, BETA\n      REAL               EPS, ERR\n      INTEGER            INCX, INCY, M, N, NMAX, NOUT\n      LOGICAL            FATAL, MV\n      CHARACTER*1        TRANS\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, * ), X( * ), Y( * ), YT( * ), YY( * )\n      REAL               G( * )\n*     .. Local Scalars ..\n      COMPLEX            C\n      REAL               ERRI\n      INTEGER            I, INCXL, INCYL, IY, J, JX, KX, KY, ML, NL\n      LOGICAL            CTRAN, TRAN\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, AIMAG, CONJG, MAX, REAL, SQRT\n*     .. Statement Functions ..\n      REAL               ABS1\n*     .. Statement Function definitions ..\n      ABS1( C ) = ABS( REAL( C ) ) + ABS( AIMAG( C ) )\n*     .. Executable Statements ..\n      TRAN = TRANS.EQ.'T'\n      CTRAN = TRANS.EQ.'C'\n      IF( TRAN.OR.CTRAN )THEN\n         ML = N\n         NL = M\n      ELSE\n         ML = M\n         NL = N\n      END IF\n      IF( INCX.LT.0 )THEN\n         KX = NL\n         INCXL = -1\n      ELSE\n         KX = 1\n         INCXL = 1\n      END IF\n      IF( INCY.LT.0 )THEN\n         KY = ML\n         INCYL = -1\n      ELSE\n         KY = 1\n         INCYL = 1\n      END IF\n*\n*     Compute expected result in YT using data in A, X and Y.\n*     Compute gauges in G.\n*\n      IY = KY\n      DO 40 I = 1, ML\n         YT( IY ) = ZERO\n         G( IY ) = RZERO\n         JX = KX\n         IF( TRAN )THEN\n            DO 10 J = 1, NL\n               YT( IY ) = YT( IY ) + A( J, I )*X( JX )\n               G( IY ) = G( IY ) + ABS1( A( J, I ) )*ABS1( X( JX ) )\n               JX = JX + INCXL\n   10       CONTINUE\n         ELSE IF( CTRAN )THEN\n            DO 20 J = 1, NL\n               YT( IY ) = YT( IY ) + CONJG( A( J, I ) )*X( JX )\n               G( IY ) = G( IY ) + ABS1( A( J, I ) )*ABS1( X( JX ) )\n               JX = JX + INCXL\n   20       CONTINUE\n         ELSE\n            DO 30 J = 1, NL\n               YT( IY ) = YT( IY ) + A( I, J )*X( JX )\n               G( IY ) = G( IY ) + ABS1( A( I, J ) )*ABS1( X( JX ) )\n               JX = JX + INCXL\n   30       CONTINUE\n         END IF\n         YT( IY ) = ALPHA*YT( IY ) + BETA*Y( IY )\n         G( IY ) = ABS1( ALPHA )*G( IY ) + ABS1( BETA )*ABS1( Y( IY ) )\n         IY = IY + INCYL\n   40 CONTINUE\n*\n*     Compute the error ratio for this result.\n*\n      ERR = ZERO\n      DO 50 I = 1, ML\n         ERRI = ABS( YT( I ) - YY( 1 + ( I - 1 )*ABS( INCY ) ) )/EPS\n         IF( G( I ).NE.RZERO )\n     $      ERRI = ERRI/G( I )\n         ERR = MAX( ERR, ERRI )\n         IF( ERR*SQRT( EPS ).GE.RONE )\n     $      GO TO 60\n   50 CONTINUE\n*     If the loop completes, all results are at least half accurate.\n      GO TO 80\n*\n*     Report fatal error.\n*\n   60 FATAL = .TRUE.\n      WRITE( NOUT, FMT = 9999 )\n      DO 70 I = 1, ML\n         IF( MV )THEN\n            WRITE( NOUT, FMT = 9998 )I, YT( I ),\n     $         YY( 1 + ( I - 1 )*ABS( INCY ) )\n         ELSE\n            WRITE( NOUT, FMT = 9998 )I,\n     $         YY( 1 + ( I - 1 )*ABS( INCY ) ), YT( I )\n         END IF\n   70 CONTINUE\n*\n   80 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ******* FATAL ERROR - COMPUTED RESULT IS LESS THAN HAL',\n     $      'F ACCURATE *******', /'                       EXPECTED RE',\n     $      'SULT                    COMPUTED RESULT' )\n 9998 FORMAT( 1X, I7, 2( '  (', G15.6, ',', G15.6, ')' ) )\n*\n*     End of CMVCH.\n*\n      END\n      LOGICAL FUNCTION LCE( RI, RJ, LR )\n*\n*  Tests if two arrays are identical.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LR\n*     .. Array Arguments ..\n      COMPLEX            RI( * ), RJ( * )\n*     .. Local Scalars ..\n      INTEGER            I\n*     .. Executable Statements ..\n      DO 10 I = 1, LR\n         IF( RI( I ).NE.RJ( I ) )\n     $      GO TO 20\n   10 CONTINUE\n      LCE = .TRUE.\n      GO TO 30\n   20 CONTINUE\n      LCE = .FALSE.\n   30 RETURN\n*\n*     End of LCE.\n*\n      END\n      LOGICAL FUNCTION LCERES( TYPE, UPLO, M, N, AA, AS, LDA )\n*\n*  Tests if selected elements in two arrays are equal.\n*\n*  TYPE is 'GE', 'HE' or 'HP'.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LDA, M, N\n      CHARACTER*1        UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      COMPLEX            AA( LDA, * ), AS( LDA, * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J\n      LOGICAL            UPPER\n*     .. Executable Statements ..\n      UPPER = UPLO.EQ.'U'\n      IF( TYPE.EQ.'GE' )THEN\n         DO 20 J = 1, N\n            DO 10 I = M + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   10       CONTINUE\n   20    CONTINUE\n      ELSE IF( TYPE.EQ.'HE' )THEN\n         DO 50 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 30 I = 1, IBEG - 1\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   30       CONTINUE\n            DO 40 I = IEND + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   40       CONTINUE\n   50    CONTINUE\n      END IF\n*\n      LCERES = .TRUE.\n      GO TO 80\n   70 CONTINUE\n      LCERES = .FALSE.\n   80 RETURN\n*\n*     End of LCERES.\n*\n      END\n      COMPLEX FUNCTION CBEG( RESET )\n*\n*  Generates complex numbers as pairs of random numbers uniformly\n*  distributed between -0.5 and 0.5.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      LOGICAL            RESET\n*     .. Local Scalars ..\n      INTEGER            I, IC, J, MI, MJ\n*     .. Save statement ..\n      SAVE               I, IC, J, MI, MJ\n*     .. Intrinsic Functions ..\n      INTRINSIC          CMPLX\n*     .. Executable Statements ..\n      IF( RESET )THEN\n*        Initialize local variables.\n         MI = 891\n         MJ = 457\n         I = 7\n         J = 7\n         IC = 0\n         RESET = .FALSE.\n      END IF\n*\n*     The sequence of values of I or J is bounded between 1 and 999.\n*     If initial I or J = 1,2,3,6,7 or 9, the period will be 50.\n*     If initial I or J = 4 or 8, the period will be 25.\n*     If initial I or J = 5, the period will be 10.\n*     IC is used to break up the period by skipping 1 value of I or J\n*     in 6.\n*\n      IC = IC + 1\n   10 I = I*MI\n      J = J*MJ\n      I = I - 1000*( I/1000 )\n      J = J - 1000*( J/1000 )\n      IF( IC.GE.5 )THEN\n         IC = 0\n         GO TO 10\n      END IF\n      CBEG = CMPLX( ( I - 500 )/1001.0, ( J - 500 )/1001.0 )\n      RETURN\n*\n*     End of CBEG.\n*\n      END\n      REAL FUNCTION SDIFF( X, Y )\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*\n*     .. Scalar Arguments ..\n      REAL               X, Y\n*     .. Executable Statements ..\n      SDIFF = X - Y\n      RETURN\n*\n*     End of SDIFF.\n*\n      END\n      SUBROUTINE CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n*  Tests whether XERBLA has detected an error when it should.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Executable Statements ..\n      IF( .NOT.LERR )THEN\n         WRITE( NOUT, FMT = 9999 )INFOT, SRNAMT\n         OK = .FALSE.\n      END IF\n      LERR = .FALSE.\n      RETURN\n*\n 9999 FORMAT( ' ***** ILLEGAL VALUE OF PARAMETER NUMBER ', I2, ' NOT D',\n     $      'ETECTED BY ', A6, ' *****' )\n*\n*     End of CHKXER.\n*\n      END\n      SUBROUTINE XERBLA( SRNAME, INFO )\n*\n*  This is a special version of XERBLA to be used only as part of\n*  the test program for testing error exits from the Level 2 BLAS\n*  routines.\n*\n*  XERBLA  is an error handler for the Level 2 BLAS routines.\n*\n*  It is called by the Level 2 BLAS routines if an input parameter is\n*  invalid.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFO\n      CHARACTER*6        SRNAME\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUT, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Executable Statements ..\n      LERR = .TRUE.\n      IF( INFO.NE.INFOT )THEN\n         IF( INFOT.NE.0 )THEN\n            WRITE( NOUT, FMT = 9999 )INFO, INFOT\n         ELSE\n            WRITE( NOUT, FMT = 9997 )INFO\n         END IF\n         OK = .FALSE.\n      END IF\n      IF( SRNAME.NE.SRNAMT )THEN\n         WRITE( NOUT, FMT = 9998 )SRNAME, SRNAMT\n         OK = .FALSE.\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6, ' INSTEAD',\n     $      ' OF ', I2, ' *******' )\n 9998 FORMAT( ' ******* XERBLA WAS CALLED WITH SRNAME = ', A6, ' INSTE',\n     $      'AD OF ', A6, ' *******' )\n 9997 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6,\n     $      ' *******' )\n*\n*     End of XERBLA\n*\n      END\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/testing/cblat3.f",
    "content": "*> \\brief \\b CBLAT3\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM CBLAT3\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> Test program for the COMPLEX          Level 3 Blas.\n*>\n*> The program must be driven by a short data file. The first 14 records\n*> of the file are read using list-directed input, the last 9 records\n*> are read using the format ( A6, L2 ). An annotated example of a data\n*> file can be obtained by deleting the first 3 characters from the\n*> following 23 lines:\n*> 'cblat3.out'      NAME OF SUMMARY OUTPUT FILE\n*> 6                 UNIT NUMBER OF SUMMARY FILE\n*> 'CBLAT3.SNAP'     NAME OF SNAPSHOT OUTPUT FILE\n*> -1                UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0)\n*> F        LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD.\n*> F        LOGICAL FLAG, T TO STOP ON FAILURES.\n*> T        LOGICAL FLAG, T TO TEST ERROR EXITS.\n*> 16.0     THRESHOLD VALUE OF TEST RATIO\n*> 6                 NUMBER OF VALUES OF N\n*> 0 1 2 3 5 9       VALUES OF N\n*> 3                 NUMBER OF VALUES OF ALPHA\n*> (0.0,0.0) (1.0,0.0) (0.7,-0.9)       VALUES OF ALPHA\n*> 3                 NUMBER OF VALUES OF BETA\n*> (0.0,0.0) (1.0,0.0) (1.3,-1.1)       VALUES OF BETA\n*> CGEMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CHEMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CSYMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CTRMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CTRSM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CHERK  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CSYRK  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CHER2K T PUT F FOR NO TEST. SAME COLUMNS.\n*> CSYR2K T PUT F FOR NO TEST. SAME COLUMNS.\n*>\n*> Further Details\n*> ===============\n*>\n*> See:\n*>\n*>    Dongarra J. J., Du Croz J. J., Duff I. S. and Hammarling S.\n*>    A Set of Level 3 Basic Linear Algebra Subprograms.\n*>\n*>    Technical Memorandum No.88 (Revision 1), Mathematics and\n*>    Computer Science Division, Argonne National Laboratory, 9700\n*>    South Cass Avenue, Argonne, Illinois 60439, US.\n*>\n*> -- Written on 8-February-1989.\n*>    Jack Dongarra, Argonne National Laboratory.\n*>    Iain Duff, AERE Harwell.\n*>    Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*>    Sven Hammarling, Numerical Algorithms Group Ltd.\n*>\n*>    10-9-00:  Change STATUS='NEW' to 'UNKNOWN' so that the testers\n*>              can be run multiple times without deleting generated\n*>              output files (susan)\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup complex_blas_testing\n*\n*  =====================================================================\n      PROGRAM CBLAT3\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER            NIN\n      PARAMETER          ( NIN = 5 )\n      INTEGER            NSUBS\n      PARAMETER          ( NSUBS = 9 )\n      COMPLEX            ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), ONE = ( 1.0, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n      INTEGER            NMAX\n      PARAMETER          ( NMAX = 65 )\n      INTEGER            NIDMAX, NALMAX, NBEMAX\n      PARAMETER          ( NIDMAX = 9, NALMAX = 7, NBEMAX = 7 )\n*     .. Local Scalars ..\n      REAL               EPS, ERR, THRESH\n      INTEGER            I, ISNUM, J, N, NALF, NBET, NIDIM, NOUT, NTRA\n      LOGICAL            FATAL, LTESTT, REWI, SAME, SFATAL, TRACE,\n     $                   TSTERR\n      CHARACTER*1        TRANSA, TRANSB\n      CHARACTER*6        SNAMET\n      CHARACTER*32       SNAPS, SUMMRY\n*     .. Local Arrays ..\n      COMPLEX            AA( NMAX*NMAX ), AB( NMAX, 2*NMAX ),\n     $                   ALF( NALMAX ), AS( NMAX*NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBEMAX ),\n     $                   BS( NMAX*NMAX ), C( NMAX, NMAX ),\n     $                   CC( NMAX*NMAX ), CS( NMAX*NMAX ), CT( NMAX ),\n     $                   W( 2*NMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDMAX )\n      LOGICAL            LTEST( NSUBS )\n      CHARACTER*6        SNAMES( NSUBS )\n*     .. External Functions ..\n      REAL               SDIFF\n      LOGICAL            LCE\n      EXTERNAL           SDIFF, LCE\n*     .. External Subroutines ..\n      EXTERNAL           CCHK1, CCHK2, CCHK3, CCHK4, CCHK5, CCHKE, CMMCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Data statements ..\n      DATA               SNAMES/'CGEMM ', 'CHEMM ', 'CSYMM ', 'CTRMM ',\n     $                   'CTRSM ', 'CHERK ', 'CSYRK ', 'CHER2K',\n     $                   'CSYR2K'/\n*     .. Executable Statements ..\n*\n*     Read name and unit number for summary output file and open file.\n*\n      READ( NIN, FMT = * )SUMMRY\n      READ( NIN, FMT = * )NOUT\n      OPEN( NOUT, FILE = SUMMRY )\n      NOUTC = NOUT\n*\n*     Read name and unit number for snapshot output file and open file.\n*\n      READ( NIN, FMT = * )SNAPS\n      READ( NIN, FMT = * )NTRA\n      TRACE = NTRA.GE.0\n      IF( TRACE )THEN\n         OPEN( NTRA, FILE = SNAPS )\n      END IF\n*     Read the flag that directs rewinding of the snapshot file.\n      READ( NIN, FMT = * )REWI\n      REWI = REWI.AND.TRACE\n*     Read the flag that directs stopping on any failure.\n      READ( NIN, FMT = * )SFATAL\n*     Read the flag that indicates whether error exits are to be tested.\n      READ( NIN, FMT = * )TSTERR\n*     Read the threshold value of the test ratio\n      READ( NIN, FMT = * )THRESH\n*\n*     Read and check the parameter values for the tests.\n*\n*     Values of N\n      READ( NIN, FMT = * )NIDIM\n      IF( NIDIM.LT.1.OR.NIDIM.GT.NIDMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'N', NIDMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( IDIM( I ), I = 1, NIDIM )\n      DO 10 I = 1, NIDIM\n         IF( IDIM( I ).LT.0.OR.IDIM( I ).GT.NMAX )THEN\n            WRITE( NOUT, FMT = 9996 )NMAX\n            GO TO 220\n         END IF\n   10 CONTINUE\n*     Values of ALPHA\n      READ( NIN, FMT = * )NALF\n      IF( NALF.LT.1.OR.NALF.GT.NALMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'ALPHA', NALMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( ALF( I ), I = 1, NALF )\n*     Values of BETA\n      READ( NIN, FMT = * )NBET\n      IF( NBET.LT.1.OR.NBET.GT.NBEMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'BETA', NBEMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( BET( I ), I = 1, NBET )\n*\n*     Report values of parameters.\n*\n      WRITE( NOUT, FMT = 9995 )\n      WRITE( NOUT, FMT = 9994 )( IDIM( I ), I = 1, NIDIM )\n      WRITE( NOUT, FMT = 9993 )( ALF( I ), I = 1, NALF )\n      WRITE( NOUT, FMT = 9992 )( BET( I ), I = 1, NBET )\n      IF( .NOT.TSTERR )THEN\n         WRITE( NOUT, FMT = * )\n         WRITE( NOUT, FMT = 9984 )\n      END IF\n      WRITE( NOUT, FMT = * )\n      WRITE( NOUT, FMT = 9999 )THRESH\n      WRITE( NOUT, FMT = * )\n*\n*     Read names of subroutines and flags which indicate\n*     whether they are to be tested.\n*\n      DO 20 I = 1, NSUBS\n         LTEST( I ) = .FALSE.\n   20 CONTINUE\n   30 READ( NIN, FMT = 9988, END = 60 )SNAMET, LTESTT\n      DO 40 I = 1, NSUBS\n         IF( SNAMET.EQ.SNAMES( I ) )\n     $      GO TO 50\n   40 CONTINUE\n      WRITE( NOUT, FMT = 9990 )SNAMET\n      STOP\n   50 LTEST( I ) = LTESTT\n      GO TO 30\n*\n   60 CONTINUE\n      CLOSE ( NIN )\n*\n*     Compute EPS (the machine precision).\n*\n      EPS = EPSILON(RZERO)\n      WRITE( NOUT, FMT = 9998 )EPS\n*\n*     Check the reliability of CMMCH using exact data.\n*\n      N = MIN( 32, NMAX )\n      DO 100 J = 1, N\n         DO 90 I = 1, N\n            AB( I, J ) = MAX( I - J + 1, 0 )\n   90    CONTINUE\n         AB( J, NMAX + 1 ) = J\n         AB( 1, NMAX + J ) = J\n         C( J, 1 ) = ZERO\n  100 CONTINUE\n      DO 110 J = 1, N\n         CC( J ) = J*( ( J + 1 )*J )/2 - ( ( J + 1 )*J*( J - 1 ) )/3\n  110 CONTINUE\n*     CC holds the exact result. On exit from CMMCH CT holds\n*     the result computed by CMMCH.\n      TRANSA = 'N'\n      TRANSB = 'N'\n      CALL CMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LCE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      TRANSB = 'C'\n      CALL CMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LCE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      DO 120 J = 1, N\n         AB( J, NMAX + 1 ) = N - J + 1\n         AB( 1, NMAX + J ) = N - J + 1\n  120 CONTINUE\n      DO 130 J = 1, N\n         CC( N - J + 1 ) = J*( ( J + 1 )*J )/2 -\n     $                     ( ( J + 1 )*J*( J - 1 ) )/3\n  130 CONTINUE\n      TRANSA = 'C'\n      TRANSB = 'N'\n      CALL CMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LCE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      TRANSB = 'C'\n      CALL CMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LCE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n*\n*     Test each subroutine in turn.\n*\n      DO 200 ISNUM = 1, NSUBS\n         WRITE( NOUT, FMT = * )\n         IF( .NOT.LTEST( ISNUM ) )THEN\n*           Subprogram is not to be tested.\n            WRITE( NOUT, FMT = 9987 )SNAMES( ISNUM )\n         ELSE\n            SRNAMT = SNAMES( ISNUM )\n*           Test error exits.\n            IF( TSTERR )THEN\n               CALL CCHKE( ISNUM, SNAMES( ISNUM ), NOUT )\n               WRITE( NOUT, FMT = * )\n            END IF\n*           Test computations.\n            INFOT = 0\n            OK = .TRUE.\n            FATAL = .FALSE.\n            GO TO ( 140, 150, 150, 160, 160, 170, 170,\n     $              180, 180 )ISNUM\n*           Test CGEMM, 01.\n  140       CALL CCHK1( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test CHEMM, 02, CSYMM, 03.\n  150       CALL CCHK2( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test CTRMM, 04, CTRSM, 05.\n  160       CALL CCHK3( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NMAX, AB,\n     $                  AA, AS, AB( 1, NMAX + 1 ), BB, BS, CT, G, C )\n            GO TO 190\n*           Test CHERK, 06, CSYRK, 07.\n  170       CALL CCHK4( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test CHER2K, 08, CSYR2K, 09.\n  180       CALL CCHK5( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, BB, BS, C, CC, CS, CT, G, W )\n            GO TO 190\n*\n  190       IF( FATAL.AND.SFATAL )\n     $         GO TO 210\n         END IF\n  200 CONTINUE\n      WRITE( NOUT, FMT = 9986 )\n      GO TO 230\n*\n  210 CONTINUE\n      WRITE( NOUT, FMT = 9985 )\n      GO TO 230\n*\n  220 CONTINUE\n      WRITE( NOUT, FMT = 9991 )\n*\n  230 CONTINUE\n      IF( TRACE )\n     $   CLOSE ( NTRA )\n      CLOSE ( NOUT )\n      STOP\n*\n 9999 FORMAT( ' ROUTINES PASS COMPUTATIONAL TESTS IF TEST RATIO IS LES',\n     $      'S THAN', F8.2 )\n 9998 FORMAT( ' RELATIVE MACHINE PRECISION IS TAKEN TO BE', 1P, E9.1 )\n 9997 FORMAT( ' NUMBER OF VALUES OF ', A, ' IS LESS THAN 1 OR GREATER ',\n     $      'THAN ', I2 )\n 9996 FORMAT( ' VALUE OF N IS LESS THAN 0 OR GREATER THAN ', I2 )\n 9995 FORMAT( ' TESTS OF THE COMPLEX          LEVEL 3 BLAS', //' THE F',\n     $      'OLLOWING PARAMETER VALUES WILL BE USED:' )\n 9994 FORMAT( '   FOR N              ', 9I6 )\n 9993 FORMAT( '   FOR ALPHA          ',\n     $      7( '(', F4.1, ',', F4.1, ')  ', : ) )\n 9992 FORMAT( '   FOR BETA           ',\n     $      7( '(', F4.1, ',', F4.1, ')  ', : ) )\n 9991 FORMAT( ' AMEND DATA FILE OR INCREASE ARRAY SIZES IN PROGRAM',\n     $      /' ******* TESTS ABANDONED *******' )\n 9990 FORMAT( ' SUBPROGRAM NAME ', A6, ' NOT RECOGNIZED', /' ******* T',\n     $      'ESTS ABANDONED *******' )\n 9989 FORMAT( ' ERROR IN CMMCH -  IN-LINE DOT PRODUCTS ARE BEING EVALU',\n     $      'ATED WRONGLY.', /' CMMCH WAS CALLED WITH TRANSA = ', A1,\n     $      ' AND TRANSB = ', A1, /' AND RETURNED SAME = ', L1, ' AND ',\n     $      'ERR = ', F12.3, '.', /' THIS MAY BE DUE TO FAULTS IN THE ',\n     $      'ARITHMETIC OR THE COMPILER.', /' ******* TESTS ABANDONED ',\n     $      '*******' )\n 9988 FORMAT( A6, L2 )\n 9987 FORMAT( 1X, A6, ' WAS NOT TESTED' )\n 9986 FORMAT( /' END OF TESTS' )\n 9985 FORMAT( /' ******* FATAL ERROR - TESTS ABANDONED *******' )\n 9984 FORMAT( ' ERROR-EXITS WILL NOT BE TESTED' )\n*\n*     End of CBLAT3.\n*\n      END\n      SUBROUTINE CCHK1( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests CGEMM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, ALS, BETA, BLS\n      REAL               ERR, ERRMAX\n      INTEGER            I, IA, IB, ICA, ICB, IK, IM, IN, K, KS, LAA,\n     $                   LBB, LCC, LDA, LDAS, LDB, LDBS, LDC, LDCS, M,\n     $                   MA, MB, MS, N, NA, NARGS, NB, NC, NS\n      LOGICAL            NULL, RESET, SAME, TRANA, TRANB\n      CHARACTER*1        TRANAS, TRANBS, TRANSA, TRANSB\n      CHARACTER*3        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CGEMM, CMAKE, CMMCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'NTC'/\n*     .. Executable Statements ..\n*\n      NARGS = 13\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 110 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 100 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDC to 1 more than minimum value if room.\n            LDC = M\n            IF( LDC.LT.NMAX )\n     $         LDC = LDC + 1\n*           Skip tests if not enough room.\n            IF( LDC.GT.NMAX )\n     $         GO TO 100\n            LCC = LDC*N\n            NULL = N.LE.0.OR.M.LE.0\n*\n            DO 90 IK = 1, NIDIM\n               K = IDIM( IK )\n*\n               DO 80 ICA = 1, 3\n                  TRANSA = ICH( ICA: ICA )\n                  TRANA = TRANSA.EQ.'T'.OR.TRANSA.EQ.'C'\n*\n                  IF( TRANA )THEN\n                     MA = K\n                     NA = M\n                  ELSE\n                     MA = M\n                     NA = K\n                  END IF\n*                 Set LDA to 1 more than minimum value if room.\n                  LDA = MA\n                  IF( LDA.LT.NMAX )\n     $               LDA = LDA + 1\n*                 Skip tests if not enough room.\n                  IF( LDA.GT.NMAX )\n     $               GO TO 80\n                  LAA = LDA*NA\n*\n*                 Generate the matrix A.\n*\n                  CALL CMAKE( 'GE', ' ', ' ', MA, NA, A, NMAX, AA, LDA,\n     $                        RESET, ZERO )\n*\n                  DO 70 ICB = 1, 3\n                     TRANSB = ICH( ICB: ICB )\n                     TRANB = TRANSB.EQ.'T'.OR.TRANSB.EQ.'C'\n*\n                     IF( TRANB )THEN\n                        MB = N\n                        NB = K\n                     ELSE\n                        MB = K\n                        NB = N\n                     END IF\n*                    Set LDB to 1 more than minimum value if room.\n                     LDB = MB\n                     IF( LDB.LT.NMAX )\n     $                  LDB = LDB + 1\n*                    Skip tests if not enough room.\n                     IF( LDB.GT.NMAX )\n     $                  GO TO 70\n                     LBB = LDB*NB\n*\n*                    Generate the matrix B.\n*\n                     CALL CMAKE( 'GE', ' ', ' ', MB, NB, B, NMAX, BB,\n     $                           LDB, RESET, ZERO )\n*\n                     DO 60 IA = 1, NALF\n                        ALPHA = ALF( IA )\n*\n                        DO 50 IB = 1, NBET\n                           BETA = BET( IB )\n*\n*                          Generate the matrix C.\n*\n                           CALL CMAKE( 'GE', ' ', ' ', M, N, C, NMAX,\n     $                                 CC, LDC, RESET, ZERO )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           TRANAS = TRANSA\n                           TRANBS = TRANSB\n                           MS = M\n                           NS = N\n                           KS = K\n                           ALS = ALPHA\n                           DO 10 I = 1, LAA\n                              AS( I ) = AA( I )\n   10                      CONTINUE\n                           LDAS = LDA\n                           DO 20 I = 1, LBB\n                              BS( I ) = BB( I )\n   20                      CONTINUE\n                           LDBS = LDB\n                           BLS = BETA\n                           DO 30 I = 1, LCC\n                              CS( I ) = CC( I )\n   30                      CONTINUE\n                           LDCS = LDC\n*\n*                          Call the subroutine.\n*\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                        TRANSA, TRANSB, M, N, K, ALPHA, LDA, LDB,\n     $                        BETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL CGEMM( TRANSA, TRANSB, M, N, K, ALPHA,\n     $                                 AA, LDA, BB, LDB, BETA, CC, LDC )\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9994 )\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = TRANSA.EQ.TRANAS\n                           ISAME( 2 ) = TRANSB.EQ.TRANBS\n                           ISAME( 3 ) = MS.EQ.M\n                           ISAME( 4 ) = NS.EQ.N\n                           ISAME( 5 ) = KS.EQ.K\n                           ISAME( 6 ) = ALS.EQ.ALPHA\n                           ISAME( 7 ) = LCE( AS, AA, LAA )\n                           ISAME( 8 ) = LDAS.EQ.LDA\n                           ISAME( 9 ) = LCE( BS, BB, LBB )\n                           ISAME( 10 ) = LDBS.EQ.LDB\n                           ISAME( 11 ) = BLS.EQ.BETA\n                           IF( NULL )THEN\n                              ISAME( 12 ) = LCE( CS, CC, LCC )\n                           ELSE\n                              ISAME( 12 ) = LCERES( 'GE', ' ', M, N, CS,\n     $                                      CC, LDC )\n                           END IF\n                           ISAME( 13 ) = LDCS.EQ.LDC\n*\n*                          If data was incorrectly changed, report\n*                          and return.\n*\n                           SAME = .TRUE.\n                           DO 40 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   40                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n*\n*                             Check the result.\n*\n                              CALL CMMCH( TRANSA, TRANSB, M, N, K,\n     $                                    ALPHA, A, NMAX, B, NMAX, BETA,\n     $                                    C, NMAX, CT, G, CC, LDC, EPS,\n     $                                    ERR, FATAL, NOUT, .TRUE. )\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 120\n                           END IF\n*\n   50                   CONTINUE\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, TRANSA, TRANSB, M, N, K,\n     $   ALPHA, LDA, LDB, BETA, LDC\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',''', A1, ''',',\n     $      3( I3, ',' ), '(', F4.1, ',', F4.1, '), A,', I3, ', B,', I3,\n     $      ',(', F4.1, ',', F4.1, '), C,', I3, ').' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK1.\n*\n      END\n      SUBROUTINE CCHK2( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests CHEMM and CSYMM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, ALS, BETA, BLS\n      REAL               ERR, ERRMAX\n      INTEGER            I, IA, IB, ICS, ICU, IM, IN, LAA, LBB, LCC,\n     $                   LDA, LDAS, LDB, LDBS, LDC, LDCS, M, MS, N, NA,\n     $                   NARGS, NC, NS\n      LOGICAL            CONJ, LEFT, NULL, RESET, SAME\n      CHARACTER*1        SIDE, SIDES, UPLO, UPLOS\n      CHARACTER*2        ICHS, ICHU\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CHEMM, CMAKE, CMMCH, CSYMM\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHS/'LR'/, ICHU/'UL'/\n*     .. Executable Statements ..\n      CONJ = SNAME( 2: 3 ).EQ.'HE'\n*\n      NARGS = 12\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 100 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 90 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDC to 1 more than minimum value if room.\n            LDC = M\n            IF( LDC.LT.NMAX )\n     $         LDC = LDC + 1\n*           Skip tests if not enough room.\n            IF( LDC.GT.NMAX )\n     $         GO TO 90\n            LCC = LDC*N\n            NULL = N.LE.0.OR.M.LE.0\n*           Set LDB to 1 more than minimum value if room.\n            LDB = M\n            IF( LDB.LT.NMAX )\n     $         LDB = LDB + 1\n*           Skip tests if not enough room.\n            IF( LDB.GT.NMAX )\n     $         GO TO 90\n            LBB = LDB*N\n*\n*           Generate the matrix B.\n*\n            CALL CMAKE( 'GE', ' ', ' ', M, N, B, NMAX, BB, LDB, RESET,\n     $                  ZERO )\n*\n            DO 80 ICS = 1, 2\n               SIDE = ICHS( ICS: ICS )\n               LEFT = SIDE.EQ.'L'\n*\n               IF( LEFT )THEN\n                  NA = M\n               ELSE\n                  NA = N\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = NA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 80\n               LAA = LDA*NA\n*\n               DO 70 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n*\n*                 Generate the hermitian or symmetric matrix A.\n*\n                  CALL CMAKE( SNAME( 2: 3 ), UPLO, ' ', NA, NA, A, NMAX,\n     $                        AA, LDA, RESET, ZERO )\n*\n                  DO 60 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n                     DO 50 IB = 1, NBET\n                        BETA = BET( IB )\n*\n*                       Generate the matrix C.\n*\n                        CALL CMAKE( 'GE', ' ', ' ', M, N, C, NMAX, CC,\n     $                              LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the\n*                       subroutine.\n*\n                        SIDES = SIDE\n                        UPLOS = UPLO\n                        MS = M\n                        NS = N\n                        ALS = ALPHA\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        DO 20 I = 1, LBB\n                           BS( I ) = BB( I )\n   20                   CONTINUE\n                        LDBS = LDB\n                        BLS = BETA\n                        DO 30 I = 1, LCC\n                           CS( I ) = CC( I )\n   30                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9995 )NC, SNAME, SIDE,\n     $                     UPLO, M, N, ALPHA, LDA, LDB, BETA, LDC\n                        IF( REWI )\n     $                     REWIND NTRA\n                        IF( CONJ )THEN\n                           CALL CHEMM( SIDE, UPLO, M, N, ALPHA, AA, LDA,\n     $                                 BB, LDB, BETA, CC, LDC )\n                        ELSE\n                           CALL CSYMM( SIDE, UPLO, M, N, ALPHA, AA, LDA,\n     $                                 BB, LDB, BETA, CC, LDC )\n                        END IF\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9994 )\n                           FATAL = .TRUE.\n                           GO TO 110\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = SIDES.EQ.SIDE\n                        ISAME( 2 ) = UPLOS.EQ.UPLO\n                        ISAME( 3 ) = MS.EQ.M\n                        ISAME( 4 ) = NS.EQ.N\n                        ISAME( 5 ) = ALS.EQ.ALPHA\n                        ISAME( 6 ) = LCE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        ISAME( 8 ) = LCE( BS, BB, LBB )\n                        ISAME( 9 ) = LDBS.EQ.LDB\n                        ISAME( 10 ) = BLS.EQ.BETA\n                        IF( NULL )THEN\n                           ISAME( 11 ) = LCE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 11 ) = LCERES( 'GE', ' ', M, N, CS,\n     $                                   CC, LDC )\n                        END IF\n                        ISAME( 12 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 110\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result.\n*\n                           IF( LEFT )THEN\n                              CALL CMMCH( 'N', 'N', M, N, M, ALPHA, A,\n     $                                    NMAX, B, NMAX, BETA, C, NMAX,\n     $                                    CT, G, CC, LDC, EPS, ERR,\n     $                                    FATAL, NOUT, .TRUE. )\n                           ELSE\n                              CALL CMMCH( 'N', 'N', M, N, N, ALPHA, B,\n     $                                    NMAX, A, NMAX, BETA, C, NMAX,\n     $                                    CT, G, CC, LDC, EPS, ERR,\n     $                                    FATAL, NOUT, .TRUE. )\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and\n*                          return.\n                           IF( FATAL )\n     $                        GO TO 110\n                        END IF\n*\n   50                CONTINUE\n*\n   60             CONTINUE\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 120\n*\n  110 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, SIDE, UPLO, M, N, ALPHA, LDA,\n     $   LDB, BETA, LDC\n*\n  120 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      '(', F4.1, ',', F4.1, '), A,', I3, ', B,', I3, ',(', F4.1,\n     $      ',', F4.1, '), C,', I3, ')    .' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK2.\n*\n      END\n      SUBROUTINE CCHK3( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NMAX, A, AA, AS,\n     $                  B, BB, BS, CT, G, C )\n*\n*  Tests CTRMM and CTRSM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), ONE = ( 1.0, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            NALF, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CT( NMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, ALS\n      REAL               ERR, ERRMAX\n      INTEGER            I, IA, ICD, ICS, ICT, ICU, IM, IN, J, LAA, LBB,\n     $                   LDA, LDAS, LDB, LDBS, M, MS, N, NA, NARGS, NC,\n     $                   NS\n      LOGICAL            LEFT, NULL, RESET, SAME\n      CHARACTER*1        DIAG, DIAGS, SIDE, SIDES, TRANAS, TRANSA, UPLO,\n     $                   UPLOS\n      CHARACTER*2        ICHD, ICHS, ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CMAKE, CMMCH, CTRMM, CTRSM\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHU/'UL'/, ICHT/'NTC'/, ICHD/'UN'/, ICHS/'LR'/\n*     .. Executable Statements ..\n*\n      NARGS = 11\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*     Set up zero matrix for CMMCH.\n      DO 20 J = 1, NMAX\n         DO 10 I = 1, NMAX\n            C( I, J ) = ZERO\n   10    CONTINUE\n   20 CONTINUE\n*\n      DO 140 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 130 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDB to 1 more than minimum value if room.\n            LDB = M\n            IF( LDB.LT.NMAX )\n     $         LDB = LDB + 1\n*           Skip tests if not enough room.\n            IF( LDB.GT.NMAX )\n     $         GO TO 130\n            LBB = LDB*N\n            NULL = M.LE.0.OR.N.LE.0\n*\n            DO 120 ICS = 1, 2\n               SIDE = ICHS( ICS: ICS )\n               LEFT = SIDE.EQ.'L'\n               IF( LEFT )THEN\n                  NA = M\n               ELSE\n                  NA = N\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = NA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 130\n               LAA = LDA*NA\n*\n               DO 110 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n*\n                  DO 100 ICT = 1, 3\n                     TRANSA = ICHT( ICT: ICT )\n*\n                     DO 90 ICD = 1, 2\n                        DIAG = ICHD( ICD: ICD )\n*\n                        DO 80 IA = 1, NALF\n                           ALPHA = ALF( IA )\n*\n*                          Generate the matrix A.\n*\n                           CALL CMAKE( 'TR', UPLO, DIAG, NA, NA, A,\n     $                                 NMAX, AA, LDA, RESET, ZERO )\n*\n*                          Generate the matrix B.\n*\n                           CALL CMAKE( 'GE', ' ', ' ', M, N, B, NMAX,\n     $                                 BB, LDB, RESET, ZERO )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           SIDES = SIDE\n                           UPLOS = UPLO\n                           TRANAS = TRANSA\n                           DIAGS = DIAG\n                           MS = M\n                           NS = N\n                           ALS = ALPHA\n                           DO 30 I = 1, LAA\n                              AS( I ) = AA( I )\n   30                      CONTINUE\n                           LDAS = LDA\n                           DO 40 I = 1, LBB\n                              BS( I ) = BB( I )\n   40                      CONTINUE\n                           LDBS = LDB\n*\n*                          Call the subroutine.\n*\n                           IF( SNAME( 4: 5 ).EQ.'MM' )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           SIDE, UPLO, TRANSA, DIAG, M, N, ALPHA,\n     $                           LDA, LDB\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CTRMM( SIDE, UPLO, TRANSA, DIAG, M,\n     $                                    N, ALPHA, AA, LDA, BB, LDB )\n                           ELSE IF( SNAME( 4: 5 ).EQ.'SM' )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           SIDE, UPLO, TRANSA, DIAG, M, N, ALPHA,\n     $                           LDA, LDB\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CTRSM( SIDE, UPLO, TRANSA, DIAG, M,\n     $                                    N, ALPHA, AA, LDA, BB, LDB )\n                           END IF\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9994 )\n                              FATAL = .TRUE.\n                              GO TO 150\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = SIDES.EQ.SIDE\n                           ISAME( 2 ) = UPLOS.EQ.UPLO\n                           ISAME( 3 ) = TRANAS.EQ.TRANSA\n                           ISAME( 4 ) = DIAGS.EQ.DIAG\n                           ISAME( 5 ) = MS.EQ.M\n                           ISAME( 6 ) = NS.EQ.N\n                           ISAME( 7 ) = ALS.EQ.ALPHA\n                           ISAME( 8 ) = LCE( AS, AA, LAA )\n                           ISAME( 9 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 10 ) = LCE( BS, BB, LBB )\n                           ELSE\n                              ISAME( 10 ) = LCERES( 'GE', ' ', M, N, BS,\n     $                                      BB, LDB )\n                           END IF\n                           ISAME( 11 ) = LDBS.EQ.LDB\n*\n*                          If data was incorrectly changed, report and\n*                          return.\n*\n                           SAME = .TRUE.\n                           DO 50 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   50                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 150\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n                              IF( SNAME( 4: 5 ).EQ.'MM' )THEN\n*\n*                                Check the result.\n*\n                                 IF( LEFT )THEN\n                                    CALL CMMCH( TRANSA, 'N', M, N, M,\n     $                                          ALPHA, A, NMAX, B, NMAX,\n     $                                          ZERO, C, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .TRUE. )\n                                 ELSE\n                                    CALL CMMCH( 'N', TRANSA, M, N, N,\n     $                                          ALPHA, B, NMAX, A, NMAX,\n     $                                          ZERO, C, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .TRUE. )\n                                 END IF\n                              ELSE IF( SNAME( 4: 5 ).EQ.'SM' )THEN\n*\n*                                Compute approximation to original\n*                                matrix.\n*\n                                 DO 70 J = 1, N\n                                    DO 60 I = 1, M\n                                       C( I, J ) = BB( I + ( J - 1 )*\n     $                                             LDB )\n                                       BB( I + ( J - 1 )*LDB ) = ALPHA*\n     $                                    B( I, J )\n   60                               CONTINUE\n   70                            CONTINUE\n*\n                                 IF( LEFT )THEN\n                                    CALL CMMCH( TRANSA, 'N', M, N, M,\n     $                                          ONE, A, NMAX, C, NMAX,\n     $                                          ZERO, B, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .FALSE. )\n                                 ELSE\n                                    CALL CMMCH( 'N', TRANSA, M, N, N,\n     $                                          ONE, C, NMAX, A, NMAX,\n     $                                          ZERO, B, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .FALSE. )\n                                 END IF\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 150\n                           END IF\n*\n   80                   CONTINUE\n*\n   90                CONTINUE\n*\n  100             CONTINUE\n*\n  110          CONTINUE\n*\n  120       CONTINUE\n*\n  130    CONTINUE\n*\n  140 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 160\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, SIDE, UPLO, TRANSA, DIAG, M,\n     $   N, ALPHA, LDA, LDB\n*\n  160 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 4( '''', A1, ''',' ), 2( I3, ',' ),\n     $      '(', F4.1, ',', F4.1, '), A,', I3, ', B,', I3, ')         ',\n     $      '      .' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK3.\n*\n      END\n      SUBROUTINE CCHK4( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests CHERK and CSYRK.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ) )\n      REAL               RONE, RZERO\n      PARAMETER          ( RONE = 1.0, RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, ALS, BETA, BETS\n      REAL               ERR, ERRMAX, RALPHA, RALS, RBETA, RBETS\n      INTEGER            I, IA, IB, ICT, ICU, IK, IN, J, JC, JJ, K, KS,\n     $                   LAA, LCC, LDA, LDAS, LDC, LDCS, LJ, MA, N, NA,\n     $                   NARGS, NC, NS\n      LOGICAL            CONJ, NULL, RESET, SAME, TRAN, UPPER\n      CHARACTER*1        TRANS, TRANSS, TRANST, UPLO, UPLOS\n      CHARACTER*2        ICHT, ICHU\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CHERK, CMAKE, CMMCH, CSYRK\n*     .. Intrinsic Functions ..\n      INTRINSIC          CMPLX, MAX, REAL\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHT/'NC'/, ICHU/'UL'/\n*     .. Executable Statements ..\n      CONJ = SNAME( 2: 3 ).EQ.'HE'\n*\n      NARGS = 10\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 100 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDC to 1 more than minimum value if room.\n         LDC = N\n         IF( LDC.LT.NMAX )\n     $      LDC = LDC + 1\n*        Skip tests if not enough room.\n         IF( LDC.GT.NMAX )\n     $      GO TO 100\n         LCC = LDC*N\n*\n         DO 90 IK = 1, NIDIM\n            K = IDIM( IK )\n*\n            DO 80 ICT = 1, 2\n               TRANS = ICHT( ICT: ICT )\n               TRAN = TRANS.EQ.'C'\n               IF( TRAN.AND..NOT.CONJ )\n     $            TRANS = 'T'\n               IF( TRAN )THEN\n                  MA = K\n                  NA = N\n               ELSE\n                  MA = N\n                  NA = K\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = MA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 80\n               LAA = LDA*NA\n*\n*              Generate the matrix A.\n*\n               CALL CMAKE( 'GE', ' ', ' ', MA, NA, A, NMAX, AA, LDA,\n     $                     RESET, ZERO )\n*\n               DO 70 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n                  UPPER = UPLO.EQ.'U'\n*\n                  DO 60 IA = 1, NALF\n                     ALPHA = ALF( IA )\n                     IF( CONJ )THEN\n                        RALPHA = REAL( ALPHA )\n                        ALPHA = CMPLX( RALPHA, RZERO )\n                     END IF\n*\n                     DO 50 IB = 1, NBET\n                        BETA = BET( IB )\n                        IF( CONJ )THEN\n                           RBETA = REAL( BETA )\n                           BETA = CMPLX( RBETA, RZERO )\n                        END IF\n                        NULL = N.LE.0\n                        IF( CONJ )\n     $                     NULL = NULL.OR.( ( K.LE.0.OR.RALPHA.EQ.\n     $                            RZERO ).AND.RBETA.EQ.RONE )\n*\n*                       Generate the matrix C.\n*\n                        CALL CMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, C,\n     $                              NMAX, CC, LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        NS = N\n                        KS = K\n                        IF( CONJ )THEN\n                           RALS = RALPHA\n                        ELSE\n                           ALS = ALPHA\n                        END IF\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        IF( CONJ )THEN\n                           RBETS = RBETA\n                        ELSE\n                           BETS = BETA\n                        END IF\n                        DO 20 I = 1, LCC\n                           CS( I ) = CC( I )\n   20                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( CONJ )THEN\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO,\n     $                        TRANS, N, K, RALPHA, LDA, RBETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL CHERK( UPLO, TRANS, N, K, RALPHA, AA,\n     $                                 LDA, RBETA, CC, LDC )\n                        ELSE\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO,\n     $                        TRANS, N, K, ALPHA, LDA, BETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL CSYRK( UPLO, TRANS, N, K, ALPHA, AA,\n     $                                 LDA, BETA, CC, LDC )\n                        END IF\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9992 )\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLOS.EQ.UPLO\n                        ISAME( 2 ) = TRANSS.EQ.TRANS\n                        ISAME( 3 ) = NS.EQ.N\n                        ISAME( 4 ) = KS.EQ.K\n                        IF( CONJ )THEN\n                           ISAME( 5 ) = RALS.EQ.RALPHA\n                        ELSE\n                           ISAME( 5 ) = ALS.EQ.ALPHA\n                        END IF\n                        ISAME( 6 ) = LCE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        IF( CONJ )THEN\n                           ISAME( 8 ) = RBETS.EQ.RBETA\n                        ELSE\n                           ISAME( 8 ) = BETS.EQ.BETA\n                        END IF\n                        IF( NULL )THEN\n                           ISAME( 9 ) = LCE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 9 ) = LCERES( SNAME( 2: 3 ), UPLO, N,\n     $                                  N, CS, CC, LDC )\n                        END IF\n                        ISAME( 10 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 30 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   30                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result column by column.\n*\n                           IF( CONJ )THEN\n                              TRANST = 'C'\n                           ELSE\n                              TRANST = 'T'\n                           END IF\n                           JC = 1\n                           DO 40 J = 1, N\n                              IF( UPPER )THEN\n                                 JJ = 1\n                                 LJ = J\n                              ELSE\n                                 JJ = J\n                                 LJ = N - J + 1\n                              END IF\n                              IF( TRAN )THEN\n                                 CALL CMMCH( TRANST, 'N', LJ, 1, K,\n     $                                       ALPHA, A( 1, JJ ), NMAX,\n     $                                       A( 1, J ), NMAX, BETA,\n     $                                       C( JJ, J ), NMAX, CT, G,\n     $                                       CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              ELSE\n                                 CALL CMMCH( 'N', TRANST, LJ, 1, K,\n     $                                       ALPHA, A( JJ, 1 ), NMAX,\n     $                                       A( J, 1 ), NMAX, BETA,\n     $                                       C( JJ, J ), NMAX, CT, G,\n     $                                       CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              END IF\n                              IF( UPPER )THEN\n                                 JC = JC + LDC\n                              ELSE\n                                 JC = JC + LDC + 1\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 110\n   40                      CONTINUE\n                        END IF\n*\n   50                CONTINUE\n*\n   60             CONTINUE\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  110 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9995 )J\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( CONJ )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, N, K, RALPHA,\n     $      LDA, RBETA, LDC\n      ELSE\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, TRANS, N, K, ALPHA,\n     $      LDA, BETA, LDC\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      F4.1, ', A,', I3, ',', F4.1, ', C,', I3, ')               ',\n     $      '          .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      '(', F4.1, ',', F4.1, ') , A,', I3, ',(', F4.1, ',', F4.1,\n     $      '), C,', I3, ')          .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK4.\n*\n      END\n      SUBROUTINE CCHK5( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  AB, AA, AS, BB, BS, C, CC, CS, CT, G, W )\n*\n*  Tests CHER2K and CSYR2K.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), ONE = ( 1.0, 0.0 ) )\n      REAL               RONE, RZERO\n      PARAMETER          ( RONE = 1.0, RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            AA( NMAX*NMAX ), AB( 2*NMAX*NMAX ),\n     $                   ALF( NALF ), AS( NMAX*NMAX ), BB( NMAX*NMAX ),\n     $                   BET( NBET ), BS( NMAX*NMAX ), C( NMAX, NMAX ),\n     $                   CC( NMAX*NMAX ), CS( NMAX*NMAX ), CT( NMAX ),\n     $                   W( 2*NMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, ALS, BETA, BETS\n      REAL               ERR, ERRMAX, RBETA, RBETS\n      INTEGER            I, IA, IB, ICT, ICU, IK, IN, J, JC, JJ, JJAB,\n     $                   K, KS, LAA, LBB, LCC, LDA, LDAS, LDB, LDBS,\n     $                   LDC, LDCS, LJ, MA, N, NA, NARGS, NC, NS\n      LOGICAL            CONJ, NULL, RESET, SAME, TRAN, UPPER\n      CHARACTER*1        TRANS, TRANSS, TRANST, UPLO, UPLOS\n      CHARACTER*2        ICHT, ICHU\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CHER2K, CMAKE, CMMCH, CSYR2K\n*     .. Intrinsic Functions ..\n      INTRINSIC          CMPLX, CONJG, MAX, REAL\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHT/'NC'/, ICHU/'UL'/\n*     .. Executable Statements ..\n      CONJ = SNAME( 2: 3 ).EQ.'HE'\n*\n      NARGS = 12\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 130 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDC to 1 more than minimum value if room.\n         LDC = N\n         IF( LDC.LT.NMAX )\n     $      LDC = LDC + 1\n*        Skip tests if not enough room.\n         IF( LDC.GT.NMAX )\n     $      GO TO 130\n         LCC = LDC*N\n*\n         DO 120 IK = 1, NIDIM\n            K = IDIM( IK )\n*\n            DO 110 ICT = 1, 2\n               TRANS = ICHT( ICT: ICT )\n               TRAN = TRANS.EQ.'C'\n               IF( TRAN.AND..NOT.CONJ )\n     $            TRANS = 'T'\n               IF( TRAN )THEN\n                  MA = K\n                  NA = N\n               ELSE\n                  MA = N\n                  NA = K\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = MA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 110\n               LAA = LDA*NA\n*\n*              Generate the matrix A.\n*\n               IF( TRAN )THEN\n                  CALL CMAKE( 'GE', ' ', ' ', MA, NA, AB, 2*NMAX, AA,\n     $                        LDA, RESET, ZERO )\n               ELSE\n                  CALL CMAKE( 'GE', ' ', ' ', MA, NA, AB, NMAX, AA, LDA,\n     $                        RESET, ZERO )\n               END IF\n*\n*              Generate the matrix B.\n*\n               LDB = LDA\n               LBB = LAA\n               IF( TRAN )THEN\n                  CALL CMAKE( 'GE', ' ', ' ', MA, NA, AB( K + 1 ),\n     $                        2*NMAX, BB, LDB, RESET, ZERO )\n               ELSE\n                  CALL CMAKE( 'GE', ' ', ' ', MA, NA, AB( K*NMAX + 1 ),\n     $                        NMAX, BB, LDB, RESET, ZERO )\n               END IF\n*\n               DO 100 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n                  UPPER = UPLO.EQ.'U'\n*\n                  DO 90 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n                     DO 80 IB = 1, NBET\n                        BETA = BET( IB )\n                        IF( CONJ )THEN\n                           RBETA = REAL( BETA )\n                           BETA = CMPLX( RBETA, RZERO )\n                        END IF\n                        NULL = N.LE.0\n                        IF( CONJ )\n     $                     NULL = NULL.OR.( ( K.LE.0.OR.ALPHA.EQ.\n     $                            ZERO ).AND.RBETA.EQ.RONE )\n*\n*                       Generate the matrix C.\n*\n                        CALL CMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, C,\n     $                              NMAX, CC, LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        NS = N\n                        KS = K\n                        ALS = ALPHA\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        DO 20 I = 1, LBB\n                           BS( I ) = BB( I )\n   20                   CONTINUE\n                        LDBS = LDB\n                        IF( CONJ )THEN\n                           RBETS = RBETA\n                        ELSE\n                           BETS = BETA\n                        END IF\n                        DO 30 I = 1, LCC\n                           CS( I ) = CC( I )\n   30                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( CONJ )THEN\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO,\n     $                        TRANS, N, K, ALPHA, LDA, LDB, RBETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL CHER2K( UPLO, TRANS, N, K, ALPHA, AA,\n     $                                  LDA, BB, LDB, RBETA, CC, LDC )\n                        ELSE\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO,\n     $                        TRANS, N, K, ALPHA, LDA, LDB, BETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL CSYR2K( UPLO, TRANS, N, K, ALPHA, AA,\n     $                                  LDA, BB, LDB, BETA, CC, LDC )\n                        END IF\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9992 )\n                           FATAL = .TRUE.\n                           GO TO 150\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLOS.EQ.UPLO\n                        ISAME( 2 ) = TRANSS.EQ.TRANS\n                        ISAME( 3 ) = NS.EQ.N\n                        ISAME( 4 ) = KS.EQ.K\n                        ISAME( 5 ) = ALS.EQ.ALPHA\n                        ISAME( 6 ) = LCE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        ISAME( 8 ) = LCE( BS, BB, LBB )\n                        ISAME( 9 ) = LDBS.EQ.LDB\n                        IF( CONJ )THEN\n                           ISAME( 10 ) = RBETS.EQ.RBETA\n                        ELSE\n                           ISAME( 10 ) = BETS.EQ.BETA\n                        END IF\n                        IF( NULL )THEN\n                           ISAME( 11 ) = LCE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 11 ) = LCERES( 'HE', UPLO, N, N, CS,\n     $                                   CC, LDC )\n                        END IF\n                        ISAME( 12 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 150\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result column by column.\n*\n                           IF( CONJ )THEN\n                              TRANST = 'C'\n                           ELSE\n                              TRANST = 'T'\n                           END IF\n                           JJAB = 1\n                           JC = 1\n                           DO 70 J = 1, N\n                              IF( UPPER )THEN\n                                 JJ = 1\n                                 LJ = J\n                              ELSE\n                                 JJ = J\n                                 LJ = N - J + 1\n                              END IF\n                              IF( TRAN )THEN\n                                 DO 50 I = 1, K\n                                    W( I ) = ALPHA*AB( ( J - 1 )*2*\n     $                                       NMAX + K + I )\n                                    IF( CONJ )THEN\n                                       W( K + I ) = CONJG( ALPHA )*\n     $                                              AB( ( J - 1 )*2*\n     $                                              NMAX + I )\n                                    ELSE\n                                       W( K + I ) = ALPHA*\n     $                                              AB( ( J - 1 )*2*\n     $                                              NMAX + I )\n                                    END IF\n   50                            CONTINUE\n                                 CALL CMMCH( TRANST, 'N', LJ, 1, 2*K,\n     $                                       ONE, AB( JJAB ), 2*NMAX, W,\n     $                                       2*NMAX, BETA, C( JJ, J ),\n     $                                       NMAX, CT, G, CC( JC ), LDC,\n     $                                       EPS, ERR, FATAL, NOUT,\n     $                                       .TRUE. )\n                              ELSE\n                                 DO 60 I = 1, K\n                                    IF( CONJ )THEN\n                                       W( I ) = ALPHA*CONJG( AB( ( K +\n     $                                          I - 1 )*NMAX + J ) )\n                                       W( K + I ) = CONJG( ALPHA*\n     $                                              AB( ( I - 1 )*NMAX +\n     $                                              J ) )\n                                    ELSE\n                                       W( I ) = ALPHA*AB( ( K + I - 1 )*\n     $                                          NMAX + J )\n                                       W( K + I ) = ALPHA*\n     $                                              AB( ( I - 1 )*NMAX +\n     $                                              J )\n                                    END IF\n   60                            CONTINUE\n                                 CALL CMMCH( 'N', 'N', LJ, 1, 2*K, ONE,\n     $                                       AB( JJ ), NMAX, W, 2*NMAX,\n     $                                       BETA, C( JJ, J ), NMAX, CT,\n     $                                       G, CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              END IF\n                              IF( UPPER )THEN\n                                 JC = JC + LDC\n                              ELSE\n                                 JC = JC + LDC + 1\n                                 IF( TRAN )\n     $                              JJAB = JJAB + 2*NMAX\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 140\n   70                      CONTINUE\n                        END IF\n*\n   80                CONTINUE\n*\n   90             CONTINUE\n*\n  100          CONTINUE\n*\n  110       CONTINUE\n*\n  120    CONTINUE\n*\n  130 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 160\n*\n  140 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9995 )J\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( CONJ )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, N, K, ALPHA,\n     $      LDA, LDB, RBETA, LDC\n      ELSE\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, TRANS, N, K, ALPHA,\n     $      LDA, LDB, BETA, LDC\n      END IF\n*\n  160 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      '(', F4.1, ',', F4.1, '), A,', I3, ', B,', I3, ',', F4.1,\n     $      ', C,', I3, ')           .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      '(', F4.1, ',', F4.1, '), A,', I3, ', B,', I3, ',(', F4.1,\n     $      ',', F4.1, '), C,', I3, ')    .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK5.\n*\n      END\n      SUBROUTINE CCHKE( ISNUM, SRNAMT, NOUT )\n*\n*  Tests the error exits from the Level 3 Blas.\n*  Requires a special version of the error-handling routine XERBLA.\n*  A, B and C should not need to be defined.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*  3-19-92:  Initialize ALPHA, BETA, RALPHA, and RBETA  (eca)\n*  3-19-92:  Fix argument 12 in calls to CSYMM and CHEMM\n*            with INFOT = 9  (eca)\n*\n*     .. Scalar Arguments ..\n      INTEGER            ISNUM, NOUT\n      CHARACTER*6        SRNAMT\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Parameters ..\n      REAL               ONE, TWO\n      PARAMETER          ( ONE = 1.0E0, TWO = 2.0E0 )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, BETA\n      REAL               RALPHA, RBETA\n*     .. Local Arrays ..\n      COMPLEX            A( 2, 1 ), B( 2, 1 ), C( 2, 1 )\n*     .. External Subroutines ..\n      EXTERNAL           CGEMM, CHEMM, CHER2K, CHERK, CHKXER, CSYMM,\n     $                   CSYR2K, CSYRK, CTRMM, CTRSM\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n*     OK is set to .FALSE. by the special version of XERBLA or by CHKXER\n*     if anything is wrong.\n      OK = .TRUE.\n*     LERR is set to .TRUE. by the special version of XERBLA each time\n*     it is called, and is then tested and re-set by CHKXER.\n      LERR = .FALSE.\n*\n*     Initialize ALPHA, BETA, RALPHA, and RBETA.\n*\n      ALPHA = CMPLX( ONE, -ONE )\n      BETA = CMPLX( TWO, -TWO )\n      RALPHA = ONE\n      RBETA = TWO\n*\n      GO TO ( 10, 20, 30, 40, 50, 60, 70, 80,\n     $        90 )ISNUM\n   10 INFOT = 1\n      CALL CGEMM( '/', 'N', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 1\n      CALL CGEMM( '/', 'C', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 1\n      CALL CGEMM( '/', 'T', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CGEMM( 'N', '/', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CGEMM( 'C', '/', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CGEMM( 'T', '/', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGEMM( 'N', 'N', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGEMM( 'N', 'C', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGEMM( 'N', 'T', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGEMM( 'C', 'N', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGEMM( 'C', 'C', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGEMM( 'C', 'T', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGEMM( 'T', 'N', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGEMM( 'T', 'C', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGEMM( 'T', 'T', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CGEMM( 'N', 'N', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CGEMM( 'N', 'C', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CGEMM( 'N', 'T', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CGEMM( 'C', 'N', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CGEMM( 'C', 'C', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CGEMM( 'C', 'T', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CGEMM( 'T', 'N', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CGEMM( 'T', 'C', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CGEMM( 'T', 'T', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGEMM( 'N', 'N', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGEMM( 'N', 'C', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGEMM( 'N', 'T', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGEMM( 'C', 'N', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGEMM( 'C', 'C', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGEMM( 'C', 'T', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGEMM( 'T', 'N', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGEMM( 'T', 'C', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGEMM( 'T', 'T', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGEMM( 'N', 'N', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGEMM( 'N', 'C', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGEMM( 'N', 'T', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGEMM( 'C', 'N', 0, 0, 2, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGEMM( 'C', 'C', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGEMM( 'C', 'T', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGEMM( 'T', 'N', 0, 0, 2, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGEMM( 'T', 'C', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGEMM( 'T', 'T', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CGEMM( 'N', 'N', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CGEMM( 'C', 'N', 0, 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CGEMM( 'T', 'N', 0, 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CGEMM( 'N', 'C', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CGEMM( 'C', 'C', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CGEMM( 'T', 'C', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CGEMM( 'N', 'T', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CGEMM( 'C', 'T', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CGEMM( 'T', 'T', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL CGEMM( 'N', 'N', 2, 0, 0, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL CGEMM( 'N', 'C', 2, 0, 0, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL CGEMM( 'N', 'T', 2, 0, 0, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL CGEMM( 'C', 'N', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL CGEMM( 'C', 'C', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL CGEMM( 'C', 'T', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL CGEMM( 'T', 'N', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL CGEMM( 'T', 'C', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL CGEMM( 'T', 'T', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   20 INFOT = 1\n      CALL CHEMM( '/', 'U', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CHEMM( 'L', '/', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHEMM( 'L', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHEMM( 'R', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHEMM( 'L', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHEMM( 'R', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHEMM( 'L', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHEMM( 'R', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHEMM( 'L', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHEMM( 'R', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHEMM( 'L', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHEMM( 'R', 'U', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHEMM( 'L', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHEMM( 'R', 'L', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CHEMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CHEMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CHEMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CHEMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CHEMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CHEMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CHEMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CHEMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   30 INFOT = 1\n      CALL CSYMM( '/', 'U', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CSYMM( 'L', '/', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYMM( 'L', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYMM( 'R', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYMM( 'L', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYMM( 'R', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYMM( 'L', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYMM( 'R', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYMM( 'L', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYMM( 'R', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYMM( 'L', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYMM( 'R', 'U', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYMM( 'L', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYMM( 'R', 'L', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   40 INFOT = 1\n      CALL CTRMM( '/', 'U', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CTRMM( 'L', '/', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CTRMM( 'L', 'U', '/', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CTRMM( 'L', 'U', 'N', '/', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'L', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'L', 'U', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'L', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'R', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'R', 'U', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'R', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'L', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'L', 'L', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'L', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'R', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'R', 'L', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'R', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'L', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'L', 'U', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'L', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'R', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'R', 'U', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'R', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'L', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'L', 'L', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'L', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'R', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'R', 'L', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'R', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'L', 'U', 'C', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'R', 'U', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'R', 'U', 'C', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'R', 'U', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'L', 'L', 'C', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'R', 'L', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'R', 'L', 'C', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'R', 'L', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'L', 'U', 'C', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'R', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'R', 'U', 'C', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'R', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'L', 'L', 'C', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'R', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'R', 'L', 'C', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'R', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   50 INFOT = 1\n      CALL CTRSM( '/', 'U', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CTRSM( 'L', '/', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CTRSM( 'L', 'U', '/', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CTRSM( 'L', 'U', 'N', '/', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'L', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'L', 'U', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'L', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'R', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'R', 'U', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'R', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'L', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'L', 'L', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'L', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'R', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'R', 'L', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'R', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'L', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'L', 'U', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'L', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'R', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'R', 'U', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'R', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'L', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'L', 'L', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'L', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'R', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'R', 'L', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'R', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'L', 'U', 'C', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'R', 'U', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'R', 'U', 'C', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'R', 'U', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'L', 'L', 'C', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'R', 'L', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'R', 'L', 'C', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'R', 'L', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'L', 'U', 'C', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'R', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'R', 'U', 'C', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'R', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'L', 'L', 'C', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'R', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'R', 'L', 'C', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'R', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   60 INFOT = 1\n      CALL CHERK( '/', 'N', 0, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CHERK( 'U', 'T', 0, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHERK( 'U', 'N', -1, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHERK( 'U', 'C', -1, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHERK( 'L', 'N', -1, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHERK( 'L', 'C', -1, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHERK( 'U', 'N', 0, -1, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHERK( 'U', 'C', 0, -1, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHERK( 'L', 'N', 0, -1, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHERK( 'L', 'C', 0, -1, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHERK( 'U', 'N', 2, 0, RALPHA, A, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHERK( 'U', 'C', 0, 2, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHERK( 'L', 'N', 2, 0, RALPHA, A, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHERK( 'L', 'C', 0, 2, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CHERK( 'U', 'N', 2, 0, RALPHA, A, 2, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CHERK( 'U', 'C', 2, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CHERK( 'L', 'N', 2, 0, RALPHA, A, 2, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CHERK( 'L', 'C', 2, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   70 INFOT = 1\n      CALL CSYRK( '/', 'N', 0, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CSYRK( 'U', 'C', 0, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYRK( 'U', 'N', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYRK( 'U', 'T', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYRK( 'L', 'N', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYRK( 'L', 'T', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYRK( 'U', 'N', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYRK( 'U', 'T', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYRK( 'L', 'N', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYRK( 'L', 'T', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYRK( 'U', 'N', 2, 0, ALPHA, A, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYRK( 'U', 'T', 0, 2, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYRK( 'L', 'N', 2, 0, ALPHA, A, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYRK( 'L', 'T', 0, 2, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CSYRK( 'U', 'N', 2, 0, ALPHA, A, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CSYRK( 'U', 'T', 2, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CSYRK( 'L', 'N', 2, 0, ALPHA, A, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CSYRK( 'L', 'T', 2, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   80 INFOT = 1\n      CALL CHER2K( '/', 'N', 0, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CHER2K( 'U', 'T', 0, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHER2K( 'U', 'N', -1, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHER2K( 'U', 'C', -1, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHER2K( 'L', 'N', -1, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHER2K( 'L', 'C', -1, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHER2K( 'U', 'N', 0, -1, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHER2K( 'U', 'C', 0, -1, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHER2K( 'L', 'N', 0, -1, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHER2K( 'L', 'C', 0, -1, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHER2K( 'U', 'N', 2, 0, ALPHA, A, 1, B, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHER2K( 'U', 'C', 0, 2, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHER2K( 'L', 'N', 2, 0, ALPHA, A, 1, B, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHER2K( 'L', 'C', 0, 2, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CHER2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CHER2K( 'U', 'C', 0, 2, ALPHA, A, 2, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CHER2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CHER2K( 'L', 'C', 0, 2, ALPHA, A, 2, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CHER2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 2, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CHER2K( 'U', 'C', 2, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CHER2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 2, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CHER2K( 'L', 'C', 2, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   90 INFOT = 1\n      CALL CSYR2K( '/', 'N', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CSYR2K( 'U', 'C', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYR2K( 'U', 'N', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYR2K( 'U', 'T', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYR2K( 'L', 'N', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYR2K( 'L', 'T', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYR2K( 'U', 'N', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYR2K( 'U', 'T', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYR2K( 'L', 'N', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYR2K( 'L', 'T', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYR2K( 'U', 'N', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYR2K( 'U', 'T', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYR2K( 'L', 'N', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYR2K( 'L', 'T', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CSYR2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CSYR2K( 'U', 'T', 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CSYR2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CSYR2K( 'L', 'T', 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CSYR2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CSYR2K( 'U', 'T', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CSYR2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CSYR2K( 'L', 'T', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n  100 IF( OK )THEN\n         WRITE( NOUT, FMT = 9999 )SRNAMT\n      ELSE\n         WRITE( NOUT, FMT = 9998 )SRNAMT\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE TESTS OF ERROR-EXITS' )\n 9998 FORMAT( ' ******* ', A6, ' FAILED THE TESTS OF ERROR-EXITS *****',\n     $      '**' )\n*\n*     End of CCHKE.\n*\n      END\n      SUBROUTINE CMAKE( TYPE, UPLO, DIAG, M, N, A, NMAX, AA, LDA, RESET,\n     $                  TRANSL )\n*\n*  Generates values for an M by N matrix A.\n*  Stores the values in the array AA in the data structure required\n*  by the routine, with unwanted elements set to rogue value.\n*\n*  TYPE is 'GE', 'HE', 'SY' or 'TR'.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), ONE = ( 1.0, 0.0 ) )\n      COMPLEX            ROGUE\n      PARAMETER          ( ROGUE = ( -1.0E10, 1.0E10 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n      REAL               RROGUE\n      PARAMETER          ( RROGUE = -1.0E10 )\n*     .. Scalar Arguments ..\n      COMPLEX            TRANSL\n      INTEGER            LDA, M, N, NMAX\n      LOGICAL            RESET\n      CHARACTER*1        DIAG, UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, * ), AA( * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J, JJ\n      LOGICAL            GEN, HER, LOWER, SYM, TRI, UNIT, UPPER\n*     .. External Functions ..\n      COMPLEX            CBEG\n      EXTERNAL           CBEG\n*     .. Intrinsic Functions ..\n      INTRINSIC          CMPLX, CONJG, REAL\n*     .. Executable Statements ..\n      GEN = TYPE.EQ.'GE'\n      HER = TYPE.EQ.'HE'\n      SYM = TYPE.EQ.'SY'\n      TRI = TYPE.EQ.'TR'\n      UPPER = ( HER.OR.SYM.OR.TRI ).AND.UPLO.EQ.'U'\n      LOWER = ( HER.OR.SYM.OR.TRI ).AND.UPLO.EQ.'L'\n      UNIT = TRI.AND.DIAG.EQ.'U'\n*\n*     Generate data in array A.\n*\n      DO 20 J = 1, N\n         DO 10 I = 1, M\n            IF( GEN.OR.( UPPER.AND.I.LE.J ).OR.( LOWER.AND.I.GE.J ) )\n     $          THEN\n               A( I, J ) = CBEG( RESET ) + TRANSL\n               IF( I.NE.J )THEN\n*                 Set some elements to zero\n                  IF( N.GT.3.AND.J.EQ.N/2 )\n     $               A( I, J ) = ZERO\n                  IF( HER )THEN\n                     A( J, I ) = CONJG( A( I, J ) )\n                  ELSE IF( SYM )THEN\n                     A( J, I ) = A( I, J )\n                  ELSE IF( TRI )THEN\n                     A( J, I ) = ZERO\n                  END IF\n               END IF\n            END IF\n   10    CONTINUE\n         IF( HER )\n     $      A( J, J ) = CMPLX( REAL( A( J, J ) ), RZERO )\n         IF( TRI )\n     $      A( J, J ) = A( J, J ) + ONE\n         IF( UNIT )\n     $      A( J, J ) = ONE\n   20 CONTINUE\n*\n*     Store elements in array AS in data structure required by routine.\n*\n      IF( TYPE.EQ.'GE' )THEN\n         DO 50 J = 1, N\n            DO 30 I = 1, M\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   30       CONTINUE\n            DO 40 I = M + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   40       CONTINUE\n   50    CONTINUE\n      ELSE IF( TYPE.EQ.'HE'.OR.TYPE.EQ.'SY'.OR.TYPE.EQ.'TR' )THEN\n         DO 90 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IF( UNIT )THEN\n                  IEND = J - 1\n               ELSE\n                  IEND = J\n               END IF\n            ELSE\n               IF( UNIT )THEN\n                  IBEG = J + 1\n               ELSE\n                  IBEG = J\n               END IF\n               IEND = N\n            END IF\n            DO 60 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   60       CONTINUE\n            DO 70 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   70       CONTINUE\n            DO 80 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   80       CONTINUE\n            IF( HER )THEN\n               JJ = J + ( J - 1 )*LDA\n               AA( JJ ) = CMPLX( REAL( AA( JJ ) ), RROGUE )\n            END IF\n   90    CONTINUE\n      END IF\n      RETURN\n*\n*     End of CMAKE.\n*\n      END\n      SUBROUTINE CMMCH( TRANSA, TRANSB, M, N, KK, ALPHA, A, LDA, B, LDB,\n     $                  BETA, C, LDC, CT, G, CC, LDCC, EPS, ERR, FATAL,\n     $                  NOUT, MV )\n*\n*  Checks the results of the computational tests.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ) )\n      REAL               RZERO, RONE\n      PARAMETER          ( RZERO = 0.0, RONE = 1.0 )\n*     .. Scalar Arguments ..\n      COMPLEX            ALPHA, BETA\n      REAL               EPS, ERR\n      INTEGER            KK, LDA, LDB, LDC, LDCC, M, N, NOUT\n      LOGICAL            FATAL, MV\n      CHARACTER*1        TRANSA, TRANSB\n*     .. Array Arguments ..\n      COMPLEX            A( LDA, * ), B( LDB, * ), C( LDC, * ),\n     $                   CC( LDCC, * ), CT( * )\n      REAL               G( * )\n*     .. Local Scalars ..\n      COMPLEX            CL\n      REAL               ERRI\n      INTEGER            I, J, K\n      LOGICAL            CTRANA, CTRANB, TRANA, TRANB\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, AIMAG, CONJG, MAX, REAL, SQRT\n*     .. Statement Functions ..\n      REAL               ABS1\n*     .. Statement Function definitions ..\n      ABS1( CL ) = ABS( REAL( CL ) ) + ABS( AIMAG( CL ) )\n*     .. Executable Statements ..\n      TRANA = TRANSA.EQ.'T'.OR.TRANSA.EQ.'C'\n      TRANB = TRANSB.EQ.'T'.OR.TRANSB.EQ.'C'\n      CTRANA = TRANSA.EQ.'C'\n      CTRANB = TRANSB.EQ.'C'\n*\n*     Compute expected result, one column at a time, in CT using data\n*     in A, B and C.\n*     Compute gauges in G.\n*\n      DO 220 J = 1, N\n*\n         DO 10 I = 1, M\n            CT( I ) = ZERO\n            G( I ) = RZERO\n   10    CONTINUE\n         IF( .NOT.TRANA.AND..NOT.TRANB )THEN\n            DO 30 K = 1, KK\n               DO 20 I = 1, M\n                  CT( I ) = CT( I ) + A( I, K )*B( K, J )\n                  G( I ) = G( I ) + ABS1( A( I, K ) )*ABS1( B( K, J ) )\n   20          CONTINUE\n   30       CONTINUE\n         ELSE IF( TRANA.AND..NOT.TRANB )THEN\n            IF( CTRANA )THEN\n               DO 50 K = 1, KK\n                  DO 40 I = 1, M\n                     CT( I ) = CT( I ) + CONJG( A( K, I ) )*B( K, J )\n                     G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                        ABS1( B( K, J ) )\n   40             CONTINUE\n   50          CONTINUE\n            ELSE\n               DO 70 K = 1, KK\n                  DO 60 I = 1, M\n                     CT( I ) = CT( I ) + A( K, I )*B( K, J )\n                     G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                        ABS1( B( K, J ) )\n   60             CONTINUE\n   70          CONTINUE\n            END IF\n         ELSE IF( .NOT.TRANA.AND.TRANB )THEN\n            IF( CTRANB )THEN\n               DO 90 K = 1, KK\n                  DO 80 I = 1, M\n                     CT( I ) = CT( I ) + A( I, K )*CONJG( B( J, K ) )\n                     G( I ) = G( I ) + ABS1( A( I, K ) )*\n     $                        ABS1( B( J, K ) )\n   80             CONTINUE\n   90          CONTINUE\n            ELSE\n               DO 110 K = 1, KK\n                  DO 100 I = 1, M\n                     CT( I ) = CT( I ) + A( I, K )*B( J, K )\n                     G( I ) = G( I ) + ABS1( A( I, K ) )*\n     $                        ABS1( B( J, K ) )\n  100             CONTINUE\n  110          CONTINUE\n            END IF\n         ELSE IF( TRANA.AND.TRANB )THEN\n            IF( CTRANA )THEN\n               IF( CTRANB )THEN\n                  DO 130 K = 1, KK\n                     DO 120 I = 1, M\n                        CT( I ) = CT( I ) + CONJG( A( K, I ) )*\n     $                            CONJG( B( J, K ) )\n                        G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                           ABS1( B( J, K ) )\n  120                CONTINUE\n  130             CONTINUE\n               ELSE\n                  DO 150 K = 1, KK\n                     DO 140 I = 1, M\n                        CT( I ) = CT( I ) + CONJG( A( K, I ) )*B( J, K )\n                        G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                           ABS1( B( J, K ) )\n  140                CONTINUE\n  150             CONTINUE\n               END IF\n            ELSE\n               IF( CTRANB )THEN\n                  DO 170 K = 1, KK\n                     DO 160 I = 1, M\n                        CT( I ) = CT( I ) + A( K, I )*CONJG( B( J, K ) )\n                        G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                           ABS1( B( J, K ) )\n  160                CONTINUE\n  170             CONTINUE\n               ELSE\n                  DO 190 K = 1, KK\n                     DO 180 I = 1, M\n                        CT( I ) = CT( I ) + A( K, I )*B( J, K )\n                        G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                           ABS1( B( J, K ) )\n  180                CONTINUE\n  190             CONTINUE\n               END IF\n            END IF\n         END IF\n         DO 200 I = 1, M\n            CT( I ) = ALPHA*CT( I ) + BETA*C( I, J )\n            G( I ) = ABS1( ALPHA )*G( I ) +\n     $               ABS1( BETA )*ABS1( C( I, J ) )\n  200    CONTINUE\n*\n*        Compute the error ratio for this result.\n*\n         ERR = ZERO\n         DO 210 I = 1, M\n            ERRI = ABS1( CT( I ) - CC( I, J ) )/EPS\n            IF( G( I ).NE.RZERO )\n     $         ERRI = ERRI/G( I )\n            ERR = MAX( ERR, ERRI )\n            IF( ERR*SQRT( EPS ).GE.RONE )\n     $         GO TO 230\n  210    CONTINUE\n*\n  220 CONTINUE\n*\n*     If the loop completes, all results are at least half accurate.\n      GO TO 250\n*\n*     Report fatal error.\n*\n  230 FATAL = .TRUE.\n      WRITE( NOUT, FMT = 9999 )\n      DO 240 I = 1, M\n         IF( MV )THEN\n            WRITE( NOUT, FMT = 9998 )I, CT( I ), CC( I, J )\n         ELSE\n            WRITE( NOUT, FMT = 9998 )I, CC( I, J ), CT( I )\n         END IF\n  240 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9997 )J\n*\n  250 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ******* FATAL ERROR - COMPUTED RESULT IS LESS THAN HAL',\n     $      'F ACCURATE *******', /'                       EXPECTED RE',\n     $      'SULT                    COMPUTED RESULT' )\n 9998 FORMAT( 1X, I7, 2( '  (', G15.6, ',', G15.6, ')' ) )\n 9997 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n*\n*     End of CMMCH.\n*\n      END\n      LOGICAL FUNCTION LCE( RI, RJ, LR )\n*\n*  Tests if two arrays are identical.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LR\n*     .. Array Arguments ..\n      COMPLEX            RI( * ), RJ( * )\n*     .. Local Scalars ..\n      INTEGER            I\n*     .. Executable Statements ..\n      DO 10 I = 1, LR\n         IF( RI( I ).NE.RJ( I ) )\n     $      GO TO 20\n   10 CONTINUE\n      LCE = .TRUE.\n      GO TO 30\n   20 CONTINUE\n      LCE = .FALSE.\n   30 RETURN\n*\n*     End of LCE.\n*\n      END\n      LOGICAL FUNCTION LCERES( TYPE, UPLO, M, N, AA, AS, LDA )\n*\n*  Tests if selected elements in two arrays are equal.\n*\n*  TYPE is 'GE' or 'HE' or 'SY'.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LDA, M, N\n      CHARACTER*1        UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      COMPLEX            AA( LDA, * ), AS( LDA, * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J\n      LOGICAL            UPPER\n*     .. Executable Statements ..\n      UPPER = UPLO.EQ.'U'\n      IF( TYPE.EQ.'GE' )THEN\n         DO 20 J = 1, N\n            DO 10 I = M + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   10       CONTINUE\n   20    CONTINUE\n      ELSE IF( TYPE.EQ.'HE'.OR.TYPE.EQ.'SY' )THEN\n         DO 50 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 30 I = 1, IBEG - 1\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   30       CONTINUE\n            DO 40 I = IEND + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   40       CONTINUE\n   50    CONTINUE\n      END IF\n*\n      LCERES = .TRUE.\n      GO TO 80\n   70 CONTINUE\n      LCERES = .FALSE.\n   80 RETURN\n*\n*     End of LCERES.\n*\n      END\n      COMPLEX FUNCTION CBEG( RESET )\n*\n*  Generates complex numbers as pairs of random numbers uniformly\n*  distributed between -0.5 and 0.5.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      LOGICAL            RESET\n*     .. Local Scalars ..\n      INTEGER            I, IC, J, MI, MJ\n*     .. Save statement ..\n      SAVE               I, IC, J, MI, MJ\n*     .. Intrinsic Functions ..\n      INTRINSIC          CMPLX\n*     .. Executable Statements ..\n      IF( RESET )THEN\n*        Initialize local variables.\n         MI = 891\n         MJ = 457\n         I = 7\n         J = 7\n         IC = 0\n         RESET = .FALSE.\n      END IF\n*\n*     The sequence of values of I or J is bounded between 1 and 999.\n*     If initial I or J = 1,2,3,6,7 or 9, the period will be 50.\n*     If initial I or J = 4 or 8, the period will be 25.\n*     If initial I or J = 5, the period will be 10.\n*     IC is used to break up the period by skipping 1 value of I or J\n*     in 6.\n*\n      IC = IC + 1\n   10 I = I*MI\n      J = J*MJ\n      I = I - 1000*( I/1000 )\n      J = J - 1000*( J/1000 )\n      IF( IC.GE.5 )THEN\n         IC = 0\n         GO TO 10\n      END IF\n      CBEG = CMPLX( ( I - 500 )/1001.0, ( J - 500 )/1001.0 )\n      RETURN\n*\n*     End of CBEG.\n*\n      END\n      REAL FUNCTION SDIFF( X, Y )\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      REAL               X, Y\n*     .. Executable Statements ..\n      SDIFF = X - Y\n      RETURN\n*\n*     End of SDIFF.\n*\n      END\n      SUBROUTINE CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n*  Tests whether XERBLA has detected an error when it should.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Executable Statements ..\n      IF( .NOT.LERR )THEN\n         WRITE( NOUT, FMT = 9999 )INFOT, SRNAMT\n         OK = .FALSE.\n      END IF\n      LERR = .FALSE.\n      RETURN\n*\n 9999 FORMAT( ' ***** ILLEGAL VALUE OF PARAMETER NUMBER ', I2, ' NOT D',\n     $      'ETECTED BY ', A6, ' *****' )\n*\n*     End of CHKXER.\n*\n      END\n      SUBROUTINE XERBLA( SRNAME, INFO )\n*\n*  This is a special version of XERBLA to be used only as part of\n*  the test program for testing error exits from the Level 3 BLAS\n*  routines.\n*\n*  XERBLA  is an error handler for the Level 3 BLAS routines.\n*\n*  It is called by the Level 3 BLAS routines if an input parameter is\n*  invalid.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFO\n      CHARACTER*6        SRNAME\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUT, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Executable Statements ..\n      LERR = .TRUE.\n      IF( INFO.NE.INFOT )THEN\n         IF( INFOT.NE.0 )THEN\n            WRITE( NOUT, FMT = 9999 )INFO, INFOT\n         ELSE\n            WRITE( NOUT, FMT = 9997 )INFO\n         END IF\n         OK = .FALSE.\n      END IF\n      IF( SRNAME.NE.SRNAMT )THEN\n         WRITE( NOUT, FMT = 9998 )SRNAME, SRNAMT\n         OK = .FALSE.\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6, ' INSTEAD',\n     $      ' OF ', I2, ' *******' )\n 9998 FORMAT( ' ******* XERBLA WAS CALLED WITH SRNAME = ', A6, ' INSTE',\n     $      'AD OF ', A6, ' *******' )\n 9997 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6,\n     $      ' *******' )\n*\n*     End of XERBLA\n*\n      END\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/testing/dblat1.f",
    "content": "*> \\brief \\b DBLAT1\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM DBLAT1\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*>    Test program for the DOUBLE PRECISION Level 1 BLAS.\n*>\n*>    Based upon the original BLAS test routine together with:\n*>    F06EAF Example Program Text\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup double_blas_testing\n*\n*  =====================================================================\n      PROGRAM DBLAT1\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER          NOUT\n      PARAMETER        (NOUT=6)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, N\n      LOGICAL          PASS\n*     .. Local Scalars ..\n      DOUBLE PRECISION SFAC\n      INTEGER          IC\n*     .. External Subroutines ..\n      EXTERNAL         CHECK0, CHECK1, CHECK2, CHECK3, HEADER\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      DATA             SFAC/9.765625D-4/\n*     .. Executable Statements ..\n      WRITE (NOUT,99999)\n      DO 20 IC = 1, 13\n         ICASE = IC\n         CALL HEADER\n*\n*        .. Initialize  PASS,  INCX,  and INCY for a new case. ..\n*        .. the value 9999 for INCX or INCY will appear in the ..\n*        .. detailed  output, if any, for cases  that do not involve ..\n*        .. these parameters ..\n*\n         PASS = .TRUE.\n         INCX = 9999\n         INCY = 9999\n         IF (ICASE.EQ.3 .OR. ICASE.EQ.11) THEN\n            CALL CHECK0(SFAC)\n         ELSE IF (ICASE.EQ.7 .OR. ICASE.EQ.8 .OR. ICASE.EQ.9 .OR.\n     +            ICASE.EQ.10) THEN\n            CALL CHECK1(SFAC)\n         ELSE IF (ICASE.EQ.1 .OR. ICASE.EQ.2 .OR. ICASE.EQ.5 .OR.\n     +            ICASE.EQ.6 .OR. ICASE.EQ.12 .OR. ICASE.EQ.13) THEN\n            CALL CHECK2(SFAC)\n         ELSE IF (ICASE.EQ.4) THEN\n            CALL CHECK3(SFAC)\n         END IF\n*        -- Print\n         IF (PASS) WRITE (NOUT,99998)\n   20 CONTINUE\n      STOP\n*\n99999 FORMAT (' Real BLAS Test Program Results',/1X)\n99998 FORMAT ('                                    ----- PASS -----')\n      END\n      SUBROUTINE HEADER\n*     .. Parameters ..\n      INTEGER          NOUT\n      PARAMETER        (NOUT=6)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, N\n      LOGICAL          PASS\n*     .. Local Arrays ..\n      CHARACTER*6      L(13)\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      DATA             L(1)/' DDOT '/\n      DATA             L(2)/'DAXPY '/\n      DATA             L(3)/'DROTG '/\n      DATA             L(4)/' DROT '/\n      DATA             L(5)/'DCOPY '/\n      DATA             L(6)/'DSWAP '/\n      DATA             L(7)/'DNRM2 '/\n      DATA             L(8)/'DASUM '/\n      DATA             L(9)/'DSCAL '/\n      DATA             L(10)/'IDAMAX'/\n      DATA             L(11)/'DROTMG'/\n      DATA             L(12)/'DROTM '/\n      DATA             L(13)/'DSDOT '/\n*     .. Executable Statements ..\n      WRITE (NOUT,99999) ICASE, L(ICASE)\n      RETURN\n*\n99999 FORMAT (/' Test of subprogram number',I3,12X,A6)\n      END\n      SUBROUTINE CHECK0(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION  SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      DOUBLE PRECISION  SA, SB, SC, SS, D12\n      INTEGER           I, K\n*     .. Local Arrays ..\n      DOUBLE PRECISION  DA1(8), DATRUE(8), DB1(8), DBTRUE(8), DC1(8),\n     $                  DS1(8), DAB(4,9), DTEMP(9), DTRUE(9,9)\n*     .. External Subroutines ..\n      EXTERNAL          DROTG, DROTMG, STEST1\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      DATA              DA1/0.3D0, 0.4D0, -0.3D0, -0.4D0, -0.3D0, 0.0D0,\n     +                  0.0D0, 1.0D0/\n      DATA              DB1/0.4D0, 0.3D0, 0.4D0, 0.3D0, -0.4D0, 0.0D0,\n     +                  1.0D0, 0.0D0/\n      DATA              DC1/0.6D0, 0.8D0, -0.6D0, 0.8D0, 0.6D0, 1.0D0,\n     +                  0.0D0, 1.0D0/\n      DATA              DS1/0.8D0, 0.6D0, 0.8D0, -0.6D0, 0.8D0, 0.0D0,\n     +                  1.0D0, 0.0D0/\n      DATA              DATRUE/0.5D0, 0.5D0, 0.5D0, -0.5D0, -0.5D0,\n     +                  0.0D0, 1.0D0, 1.0D0/\n      DATA              DBTRUE/0.0D0, 0.6D0, 0.0D0, -0.6D0, 0.0D0,\n     +                  0.0D0, 1.0D0, 0.0D0/\n*     INPUT FOR MODIFIED GIVENS\n      DATA DAB/ .1D0,.3D0,1.2D0,.2D0,\n     A          .7D0, .2D0, .6D0, 4.2D0,\n     B          0.D0,0.D0,0.D0,0.D0,\n     C          4.D0, -1.D0, 2.D0, 4.D0,\n     D          6.D-10, 2.D-2, 1.D5, 10.D0,\n     E          4.D10, 2.D-2, 1.D-5, 10.D0,\n     F          2.D-10, 4.D-2, 1.D5, 10.D0,\n     G          2.D10, 4.D-2, 1.D-5, 10.D0,\n     H          4.D0, -2.D0, 8.D0, 4.D0    /\n*    TRUE RESULTS FOR MODIFIED GIVENS\n      DATA DTRUE/0.D0,0.D0, 1.3D0, .2D0, 0.D0,0.D0,0.D0, .5D0, 0.D0,\n     A           0.D0,0.D0, 4.5D0, 4.2D0, 1.D0, .5D0, 0.D0,0.D0,0.D0,\n     B           0.D0,0.D0,0.D0,0.D0, -2.D0, 0.D0,0.D0,0.D0,0.D0,\n     C           0.D0,0.D0,0.D0, 4.D0, -1.D0, 0.D0,0.D0,0.D0,0.D0,\n     D           0.D0, 15.D-3, 0.D0, 10.D0, -1.D0, 0.D0, -1.D-4,\n     E           0.D0, 1.D0,\n     F           0.D0,0.D0, 6144.D-5, 10.D0, -1.D0, 4096.D0, -1.D6,\n     G           0.D0, 1.D0,\n     H           0.D0,0.D0,15.D0,10.D0,-1.D0, 5.D-5, 0.D0,1.D0,0.D0,\n     I           0.D0,0.D0, 15.D0, 10.D0, -1. D0, 5.D5, -4096.D0,\n     J           1.D0, 4096.D-6,\n     K           0.D0,0.D0, 7.D0, 4.D0, 0.D0,0.D0, -.5D0, -.25D0, 0.D0/\n*                   4096 = 2 ** 12\n      DATA D12  /4096.D0/\n      DTRUE(1,1) = 12.D0 / 130.D0\n      DTRUE(2,1) = 36.D0 / 130.D0\n      DTRUE(7,1) = -1.D0 / 6.D0\n      DTRUE(1,2) = 14.D0 / 75.D0\n      DTRUE(2,2) = 49.D0 / 75.D0\n      DTRUE(9,2) = 1.D0 / 7.D0\n      DTRUE(1,5) = 45.D-11 * (D12 * D12)\n      DTRUE(3,5) = 4.D5 / (3.D0 * D12)\n      DTRUE(6,5) = 1.D0 / D12\n      DTRUE(8,5) = 1.D4 / (3.D0 * D12)\n      DTRUE(1,6) = 4.D10 / (1.5D0 * D12 * D12)\n      DTRUE(2,6) = 2.D-2 / 1.5D0\n      DTRUE(8,6) = 5.D-7 * D12\n      DTRUE(1,7) = 4.D0 / 150.D0\n      DTRUE(2,7) = (2.D-10 / 1.5D0) * (D12 * D12)\n      DTRUE(7,7) = -DTRUE(6,5)\n      DTRUE(9,7) = 1.D4 / D12\n      DTRUE(1,8) = DTRUE(1,7)\n      DTRUE(2,8) = 2.D10 / (1.5D0 * D12 * D12)\n      DTRUE(1,9) = 32.D0 / 7.D0\n      DTRUE(2,9) = -16.D0 / 7.D0\n*     .. Executable Statements ..\n*\n*     Compute true values which cannot be prestored\n*     in decimal notation\n*\n      DBTRUE(1) = 1.0D0/0.6D0\n      DBTRUE(3) = -1.0D0/0.6D0\n      DBTRUE(5) = 1.0D0/0.6D0\n*\n      DO 20 K = 1, 8\n*        .. Set N=K for identification in output if any ..\n         N = K\n         IF (ICASE.EQ.3) THEN\n*           .. DROTG ..\n            IF (K.GT.8) GO TO 40\n            SA = DA1(K)\n            SB = DB1(K)\n            CALL DROTG(SA,SB,SC,SS)\n            CALL STEST1(SA,DATRUE(K),DATRUE(K),SFAC)\n            CALL STEST1(SB,DBTRUE(K),DBTRUE(K),SFAC)\n            CALL STEST1(SC,DC1(K),DC1(K),SFAC)\n            CALL STEST1(SS,DS1(K),DS1(K),SFAC)\n         ELSEIF (ICASE.EQ.11) THEN\n*           .. DROTMG ..\n            DO I=1,4\n               DTEMP(I)= DAB(I,K)\n               DTEMP(I+4) = 0.0\n            END DO\n            DTEMP(9) = 0.0\n            CALL DROTMG(DTEMP(1),DTEMP(2),DTEMP(3),DTEMP(4),DTEMP(5))\n            CALL STEST(9,DTEMP,DTRUE(1,K),DTRUE(1,K),SFAC)\n         ELSE\n            WRITE (NOUT,*) ' Shouldn''t be here in CHECK0'\n            STOP\n         END IF\n   20 CONTINUE\n   40 RETURN\n      END\n      SUBROUTINE CHECK1(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION  SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      INTEGER           I, LEN, NP1\n*     .. Local Arrays ..\n      DOUBLE PRECISION  DTRUE1(5), DTRUE3(5), DTRUE5(8,5,2), DV(8,5,2),\n     +                  SA(10), STEMP(1), STRUE(8), SX(8)\n      INTEGER           ITRUE2(5)\n*     .. External Functions ..\n      DOUBLE PRECISION  DASUM, DNRM2\n      INTEGER           IDAMAX\n      EXTERNAL          DASUM, DNRM2, IDAMAX\n*     .. External Subroutines ..\n      EXTERNAL          ITEST1, DSCAL, STEST, STEST1\n*     .. Intrinsic Functions ..\n      INTRINSIC         MAX\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      DATA              SA/0.3D0, -1.0D0, 0.0D0, 1.0D0, 0.3D0, 0.3D0,\n     +                  0.3D0, 0.3D0, 0.3D0, 0.3D0/\n      DATA              DV/0.1D0, 2.0D0, 2.0D0, 2.0D0, 2.0D0, 2.0D0,\n     +                  2.0D0, 2.0D0, 0.3D0, 3.0D0, 3.0D0, 3.0D0, 3.0D0,\n     +                  3.0D0, 3.0D0, 3.0D0, 0.3D0, -0.4D0, 4.0D0,\n     +                  4.0D0, 4.0D0, 4.0D0, 4.0D0, 4.0D0, 0.2D0,\n     +                  -0.6D0, 0.3D0, 5.0D0, 5.0D0, 5.0D0, 5.0D0,\n     +                  5.0D0, 0.1D0, -0.3D0, 0.5D0, -0.1D0, 6.0D0,\n     +                  6.0D0, 6.0D0, 6.0D0, 0.1D0, 8.0D0, 8.0D0, 8.0D0,\n     +                  8.0D0, 8.0D0, 8.0D0, 8.0D0, 0.3D0, 9.0D0, 9.0D0,\n     +                  9.0D0, 9.0D0, 9.0D0, 9.0D0, 9.0D0, 0.3D0, 2.0D0,\n     +                  -0.4D0, 2.0D0, 2.0D0, 2.0D0, 2.0D0, 2.0D0,\n     +                  0.2D0, 3.0D0, -0.6D0, 5.0D0, 0.3D0, 2.0D0,\n     +                  2.0D0, 2.0D0, 0.1D0, 4.0D0, -0.3D0, 6.0D0,\n     +                  -0.5D0, 7.0D0, -0.1D0, 3.0D0/\n      DATA              DTRUE1/0.0D0, 0.3D0, 0.5D0, 0.7D0, 0.6D0/\n      DATA              DTRUE3/0.0D0, 0.3D0, 0.7D0, 1.1D0, 1.0D0/\n      DATA              DTRUE5/0.10D0, 2.0D0, 2.0D0, 2.0D0, 2.0D0,\n     +                  2.0D0, 2.0D0, 2.0D0, -0.3D0, 3.0D0, 3.0D0,\n     +                  3.0D0, 3.0D0, 3.0D0, 3.0D0, 3.0D0, 0.0D0, 0.0D0,\n     +                  4.0D0, 4.0D0, 4.0D0, 4.0D0, 4.0D0, 4.0D0,\n     +                  0.20D0, -0.60D0, 0.30D0, 5.0D0, 5.0D0, 5.0D0,\n     +                  5.0D0, 5.0D0, 0.03D0, -0.09D0, 0.15D0, -0.03D0,\n     +                  6.0D0, 6.0D0, 6.0D0, 6.0D0, 0.10D0, 8.0D0,\n     +                  8.0D0, 8.0D0, 8.0D0, 8.0D0, 8.0D0, 8.0D0,\n     +                  0.09D0, 9.0D0, 9.0D0, 9.0D0, 9.0D0, 9.0D0,\n     +                  9.0D0, 9.0D0, 0.09D0, 2.0D0, -0.12D0, 2.0D0,\n     +                  2.0D0, 2.0D0, 2.0D0, 2.0D0, 0.06D0, 3.0D0,\n     +                  -0.18D0, 5.0D0, 0.09D0, 2.0D0, 2.0D0, 2.0D0,\n     +                  0.03D0, 4.0D0, -0.09D0, 6.0D0, -0.15D0, 7.0D0,\n     +                  -0.03D0, 3.0D0/\n      DATA              ITRUE2/0, 1, 2, 2, 3/\n*     .. Executable Statements ..\n      DO 80 INCX = 1, 2\n         DO 60 NP1 = 1, 5\n            N = NP1 - 1\n            LEN = 2*MAX(N,1)\n*           .. Set vector arguments ..\n            DO 20 I = 1, LEN\n               SX(I) = DV(I,NP1,INCX)\n   20       CONTINUE\n*\n            IF (ICASE.EQ.7) THEN\n*              .. DNRM2 ..\n               STEMP(1) = DTRUE1(NP1)\n               CALL STEST1(DNRM2(N,SX,INCX),STEMP(1),STEMP,SFAC)\n            ELSE IF (ICASE.EQ.8) THEN\n*              .. DASUM ..\n               STEMP(1) = DTRUE3(NP1)\n               CALL STEST1(DASUM(N,SX,INCX),STEMP(1),STEMP,SFAC)\n            ELSE IF (ICASE.EQ.9) THEN\n*              .. DSCAL ..\n               CALL DSCAL(N,SA((INCX-1)*5+NP1),SX,INCX)\n               DO 40 I = 1, LEN\n                  STRUE(I) = DTRUE5(I,NP1,INCX)\n   40          CONTINUE\n               CALL STEST(LEN,SX,STRUE,STRUE,SFAC)\n            ELSE IF (ICASE.EQ.10) THEN\n*              .. IDAMAX ..\n               CALL ITEST1(IDAMAX(N,SX,INCX),ITRUE2(NP1))\n            ELSE\n               WRITE (NOUT,*) ' Shouldn''t be here in CHECK1'\n               STOP\n            END IF\n   60    CONTINUE\n   80 CONTINUE\n      RETURN\n      END\n      SUBROUTINE CHECK2(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION  SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      DOUBLE PRECISION  SA\n      INTEGER           I, J, KI, KN, KNI, KPAR, KSIZE, LENX, LENY,\n     $                  MX, MY \n*     .. Local Arrays ..\n      DOUBLE PRECISION  DT10X(7,4,4), DT10Y(7,4,4), DT7(4,4),\n     $                  DT8(7,4,4), DX1(7),\n     $                  DY1(7), SSIZE1(4), SSIZE2(14,2), SSIZE(7),\n     $                  STX(7), STY(7), SX(7), SY(7),\n     $                  DPAR(5,4), DT19X(7,4,16),DT19XA(7,4,4),\n     $                  DT19XB(7,4,4), DT19XC(7,4,4),DT19XD(7,4,4),\n     $                  DT19Y(7,4,16), DT19YA(7,4,4),DT19YB(7,4,4),\n     $                  DT19YC(7,4,4), DT19YD(7,4,4), DTEMP(5)\n      INTEGER           INCXS(4), INCYS(4), LENS(4,2), NS(4)\n*     .. External Functions ..\n      DOUBLE PRECISION  DDOT, DSDOT\n      EXTERNAL          DDOT, DSDOT\n*     .. External Subroutines ..\n      EXTERNAL          DAXPY, DCOPY, DROTM, DSWAP, STEST, STEST1\n*     .. Intrinsic Functions ..\n      INTRINSIC         ABS, MIN\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      EQUIVALENCE (DT19X(1,1,1),DT19XA(1,1,1)),(DT19X(1,1,5),\n     A   DT19XB(1,1,1)),(DT19X(1,1,9),DT19XC(1,1,1)),\n     B   (DT19X(1,1,13),DT19XD(1,1,1))\n      EQUIVALENCE (DT19Y(1,1,1),DT19YA(1,1,1)),(DT19Y(1,1,5),\n     A   DT19YB(1,1,1)),(DT19Y(1,1,9),DT19YC(1,1,1)),\n     B   (DT19Y(1,1,13),DT19YD(1,1,1))\n\n      DATA              SA/0.3D0/\n      DATA              INCXS/1, 2, -2, -1/\n      DATA              INCYS/1, -2, 1, -2/\n      DATA              LENS/1, 1, 2, 4, 1, 1, 3, 7/\n      DATA              NS/0, 1, 2, 4/\n      DATA              DX1/0.6D0, 0.1D0, -0.5D0, 0.8D0, 0.9D0, -0.3D0,\n     +                  -0.4D0/\n      DATA              DY1/0.5D0, -0.9D0, 0.3D0, 0.7D0, -0.6D0, 0.2D0,\n     +                  0.8D0/\n      DATA              DT7/0.0D0, 0.30D0, 0.21D0, 0.62D0, 0.0D0,\n     +                  0.30D0, -0.07D0, 0.85D0, 0.0D0, 0.30D0, -0.79D0,\n     +                  -0.74D0, 0.0D0, 0.30D0, 0.33D0, 1.27D0/\n      DATA              DT8/0.5D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.68D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.68D0, -0.87D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.68D0, -0.87D0, 0.15D0,\n     +                  0.94D0, 0.0D0, 0.0D0, 0.0D0, 0.5D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.68D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.35D0, -0.9D0, 0.48D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.38D0, -0.9D0, 0.57D0, 0.7D0, -0.75D0,\n     +                  0.2D0, 0.98D0, 0.5D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.68D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.35D0, -0.72D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.38D0,\n     +                  -0.63D0, 0.15D0, 0.88D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.5D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.68D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.68D0, -0.9D0, 0.33D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.68D0, -0.9D0, 0.33D0, 0.7D0,\n     +                  -0.75D0, 0.2D0, 1.04D0/\n      DATA              DT10X/0.6D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.5D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.5D0, -0.9D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.5D0, -0.9D0, 0.3D0, 0.7D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.6D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.5D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.3D0, 0.1D0, 0.5D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.8D0, 0.1D0, -0.6D0,\n     +                  0.8D0, 0.3D0, -0.3D0, 0.5D0, 0.6D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.5D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, -0.9D0,\n     +                  0.1D0, 0.5D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.7D0,\n     +                  0.1D0, 0.3D0, 0.8D0, -0.9D0, -0.3D0, 0.5D0,\n     +                  0.6D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.5D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.5D0, 0.3D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.5D0, 0.3D0, -0.6D0, 0.8D0, 0.0D0, 0.0D0,\n     +                  0.0D0/\n      DATA              DT10Y/0.5D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.6D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.6D0, 0.1D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.6D0, 0.1D0, -0.5D0, 0.8D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.5D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.6D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, -0.5D0, -0.9D0, 0.6D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, -0.4D0, -0.9D0, 0.9D0,\n     +                  0.7D0, -0.5D0, 0.2D0, 0.6D0, 0.5D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.6D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, -0.5D0,\n     +                  0.6D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  -0.4D0, 0.9D0, -0.5D0, 0.6D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.5D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.6D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.6D0, -0.9D0, 0.1D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.6D0, -0.9D0, 0.1D0, 0.7D0,\n     +                  -0.5D0, 0.2D0, 0.8D0/\n      DATA              SSIZE1/0.0D0, 0.3D0, 1.6D0, 3.2D0/\n      DATA              SSIZE2/0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 1.17D0, 1.17D0, 1.17D0, 1.17D0, 1.17D0,\n     +                  1.17D0, 1.17D0, 1.17D0, 1.17D0, 1.17D0, 1.17D0,\n     +                  1.17D0, 1.17D0, 1.17D0/\n*\n*                         FOR DROTM\n*\n      DATA DPAR/-2.D0,  0.D0,0.D0,0.D0,0.D0,\n     A          -1.D0,  2.D0, -3.D0, -4.D0,  5.D0,\n     B           0.D0,  0.D0,  2.D0, -3.D0,  0.D0,\n     C           1.D0,  5.D0,  2.D0,  0.D0, -4.D0/\n*                        TRUE X RESULTS F0R ROTATIONS DROTM\n      DATA DT19XA/.6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     A            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     B            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     C            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     D            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     E           -.8D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     F           -.9D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     G           3.5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     H            .6D0,   .1D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     I           -.8D0,  3.8D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     J           -.9D0,  2.8D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     K           3.5D0,  -.4D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     L            .6D0,   .1D0,  -.5D0,   .8D0,          0.D0,0.D0,0.D0,\n     M           -.8D0,  3.8D0, -2.2D0, -1.2D0,          0.D0,0.D0,0.D0,\n     N           -.9D0,  2.8D0, -1.4D0, -1.3D0,          0.D0,0.D0,0.D0,\n     O           3.5D0,  -.4D0, -2.2D0,  4.7D0,          0.D0,0.D0,0.D0/\n*\n      DATA DT19XB/.6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     A            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     B            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     C            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     D            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     E           -.8D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     F           -.9D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     G           3.5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     H            .6D0,   .1D0,  -.5D0,             0.D0,0.D0,0.D0,0.D0,\n     I           0.D0,    .1D0, -3.0D0,             0.D0,0.D0,0.D0,0.D0,\n     J           -.3D0,   .1D0, -2.0D0,             0.D0,0.D0,0.D0,0.D0,\n     K           3.3D0,   .1D0, -2.0D0,             0.D0,0.D0,0.D0,0.D0,\n     L            .6D0,   .1D0,  -.5D0,   .8D0,   .9D0,  -.3D0,  -.4D0,\n     M          -2.0D0,   .1D0,  1.4D0,   .8D0,   .6D0,  -.3D0, -2.8D0,\n     N          -1.8D0,   .1D0,  1.3D0,   .8D0,  0.D0,   -.3D0, -1.9D0,\n     O           3.8D0,   .1D0, -3.1D0,   .8D0,  4.8D0,  -.3D0, -1.5D0 /\n*\n      DATA DT19XC/.6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     A            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     B            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     C            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     D            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     E           -.8D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     F           -.9D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     G           3.5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     H            .6D0,   .1D0,  -.5D0,             0.D0,0.D0,0.D0,0.D0,\n     I           4.8D0,   .1D0, -3.0D0,             0.D0,0.D0,0.D0,0.D0,\n     J           3.3D0,   .1D0, -2.0D0,             0.D0,0.D0,0.D0,0.D0,\n     K           2.1D0,   .1D0, -2.0D0,             0.D0,0.D0,0.D0,0.D0,\n     L            .6D0,   .1D0,  -.5D0,   .8D0,   .9D0,  -.3D0,  -.4D0,\n     M          -1.6D0,   .1D0, -2.2D0,   .8D0,  5.4D0,  -.3D0, -2.8D0,\n     N          -1.5D0,   .1D0, -1.4D0,   .8D0,  3.6D0,  -.3D0, -1.9D0,\n     O           3.7D0,   .1D0, -2.2D0,   .8D0,  3.6D0,  -.3D0, -1.5D0 /\n*\n      DATA DT19XD/.6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     A            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     B            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     C            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     D            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     E           -.8D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     F           -.9D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     G           3.5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     H            .6D0,   .1D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     I           -.8D0, -1.0D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     J           -.9D0,  -.8D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     K           3.5D0,   .8D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     L            .6D0,   .1D0,  -.5D0,   .8D0,          0.D0,0.D0,0.D0,\n     M           -.8D0, -1.0D0,  1.4D0, -1.6D0,          0.D0,0.D0,0.D0,\n     N           -.9D0,  -.8D0,  1.3D0, -1.6D0,          0.D0,0.D0,0.D0,\n     O           3.5D0,   .8D0, -3.1D0,  4.8D0,          0.D0,0.D0,0.D0/\n*                        TRUE Y RESULTS FOR ROTATIONS DROTM\n      DATA DT19YA/.5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     A            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     B            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     C            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     D            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     E            .7D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     F           1.7D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     G          -2.6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     H            .5D0,  -.9D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     I            .7D0, -4.8D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     J           1.7D0,  -.7D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     K          -2.6D0,  3.5D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     L            .5D0,  -.9D0,   .3D0,   .7D0,          0.D0,0.D0,0.D0,\n     M            .7D0, -4.8D0,  3.0D0,  1.1D0,          0.D0,0.D0,0.D0,\n     N           1.7D0,  -.7D0,  -.7D0,  2.3D0,          0.D0,0.D0,0.D0,\n     O          -2.6D0,  3.5D0,  -.7D0, -3.6D0,          0.D0,0.D0,0.D0/\n*\n      DATA DT19YB/.5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     A            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     B            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     C            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     D            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     E            .7D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     F           1.7D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     G          -2.6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     H            .5D0,  -.9D0,   .3D0,             0.D0,0.D0,0.D0,0.D0,\n     I           4.0D0,  -.9D0,  -.3D0,             0.D0,0.D0,0.D0,0.D0,\n     J           -.5D0,  -.9D0,  1.5D0,             0.D0,0.D0,0.D0,0.D0,\n     K          -1.5D0,  -.9D0, -1.8D0,             0.D0,0.D0,0.D0,0.D0,\n     L            .5D0,  -.9D0,   .3D0,   .7D0,  -.6D0,   .2D0,   .8D0,\n     M           3.7D0,  -.9D0, -1.2D0,   .7D0, -1.5D0,   .2D0,  2.2D0,\n     N           -.3D0,  -.9D0,  2.1D0,   .7D0, -1.6D0,   .2D0,  2.0D0,\n     O          -1.6D0,  -.9D0, -2.1D0,   .7D0,  2.9D0,   .2D0, -3.8D0 /\n*\n      DATA DT19YC/.5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     A            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     B            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     C            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     D            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     E            .7D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     F           1.7D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     G          -2.6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     H            .5D0,  -.9D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     I           4.0D0, -6.3D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     J           -.5D0,   .3D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     K          -1.5D0,  3.0D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     L            .5D0,  -.9D0,   .3D0,   .7D0,          0.D0,0.D0,0.D0,\n     M           3.7D0, -7.2D0,  3.0D0,  1.7D0,          0.D0,0.D0,0.D0,\n     N           -.3D0,   .9D0,  -.7D0,  1.9D0,          0.D0,0.D0,0.D0,\n     O          -1.6D0,  2.7D0,  -.7D0, -3.4D0,          0.D0,0.D0,0.D0/\n*\n      DATA DT19YD/.5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     A            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     B            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     C            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     D            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     E            .7D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     F           1.7D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     G          -2.6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     H            .5D0,  -.9D0,   .3D0,             0.D0,0.D0,0.D0,0.D0,\n     I            .7D0,  -.9D0,  1.2D0,             0.D0,0.D0,0.D0,0.D0,\n     J           1.7D0,  -.9D0,   .5D0,             0.D0,0.D0,0.D0,0.D0,\n     K          -2.6D0,  -.9D0, -1.3D0,             0.D0,0.D0,0.D0,0.D0,\n     L            .5D0,  -.9D0,   .3D0,   .7D0,  -.6D0,   .2D0,   .8D0,\n     M            .7D0,  -.9D0,  1.2D0,   .7D0, -1.5D0,   .2D0,  1.6D0,\n     N           1.7D0,  -.9D0,   .5D0,   .7D0, -1.6D0,   .2D0,  2.4D0,\n     O          -2.6D0,  -.9D0, -1.3D0,   .7D0,  2.9D0,   .2D0, -4.0D0 /\n*    \n*     .. Executable Statements ..\n*\n      DO 120 KI = 1, 4\n         INCX = INCXS(KI)\n         INCY = INCYS(KI)\n         MX = ABS(INCX)\n         MY = ABS(INCY)\n*\n         DO 100 KN = 1, 4\n            N = NS(KN)\n            KSIZE = MIN(2,KN)\n            LENX = LENS(KN,MX)\n            LENY = LENS(KN,MY)\n*           .. Initialize all argument arrays ..\n            DO 20 I = 1, 7\n               SX(I) = DX1(I)\n               SY(I) = DY1(I)\n   20       CONTINUE\n*\n            IF (ICASE.EQ.1) THEN\n*              .. DDOT ..\n               CALL STEST1(DDOT(N,SX,INCX,SY,INCY),DT7(KN,KI),SSIZE1(KN)\n     +                     ,SFAC)\n            ELSE IF (ICASE.EQ.2) THEN\n*              .. DAXPY ..\n               CALL DAXPY(N,SA,SX,INCX,SY,INCY)\n               DO 40 J = 1, LENY\n                  STY(J) = DT8(J,KN,KI)\n   40          CONTINUE\n               CALL STEST(LENY,SY,STY,SSIZE2(1,KSIZE),SFAC)\n            ELSE IF (ICASE.EQ.5) THEN\n*              .. DCOPY ..\n               DO 60 I = 1, 7\n                  STY(I) = DT10Y(I,KN,KI)\n   60          CONTINUE\n               CALL DCOPY(N,SX,INCX,SY,INCY)\n               CALL STEST(LENY,SY,STY,SSIZE2(1,1),1.0D0)\n            ELSE IF (ICASE.EQ.6) THEN\n*              .. DSWAP ..\n               CALL DSWAP(N,SX,INCX,SY,INCY)\n               DO 80 I = 1, 7\n                  STX(I) = DT10X(I,KN,KI)\n                  STY(I) = DT10Y(I,KN,KI)\n   80          CONTINUE\n               CALL STEST(LENX,SX,STX,SSIZE2(1,1),1.0D0)\n               CALL STEST(LENY,SY,STY,SSIZE2(1,1),1.0D0)\n            ELSE IF (ICASE.EQ.12) THEN\n*              .. DROTM ..\n               KNI=KN+4*(KI-1)\n               DO KPAR=1,4\n                  DO I=1,7\n                     SX(I) = DX1(I)\n                     SY(I) = DY1(I)\n                     STX(I)= DT19X(I,KPAR,KNI)\n                     STY(I)= DT19Y(I,KPAR,KNI)\n                  END DO\n*\n                  DO I=1,5\n                     DTEMP(I) = DPAR(I,KPAR)\n                  END DO\n*\n                  DO  I=1,LENX\n                     SSIZE(I)=STX(I)\n                  END DO\n*                   SEE REMARK ABOVE ABOUT DT11X(1,2,7)\n*                       AND DT11X(5,3,8).\n                  IF ((KPAR .EQ. 2) .AND. (KNI .EQ. 7))\n     $               SSIZE(1) = 2.4D0\n                  IF ((KPAR .EQ. 3) .AND. (KNI .EQ. 8))\n     $               SSIZE(5) = 1.8D0\n*\n                  CALL   DROTM(N,SX,INCX,SY,INCY,DTEMP)\n                  CALL   STEST(LENX,SX,STX,SSIZE,SFAC)\n                  CALL   STEST(LENY,SY,STY,STY,SFAC)\n               END DO\n            ELSE IF (ICASE.EQ.13) THEN\n*              .. DSDOT ..\n            CALL TESTDSDOT(REAL(DSDOT(N,REAL(SX),INCX,REAL(SY),INCY)),\n     $                 REAL(DT7(KN,KI)),REAL(SSIZE1(KN)), .3125E-1)\n            ELSE\n               WRITE (NOUT,*) ' Shouldn''t be here in CHECK2'\n               STOP\n            END IF\n  100    CONTINUE\n  120 CONTINUE\n      RETURN\n      END\n      SUBROUTINE CHECK3(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION  SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      DOUBLE PRECISION  SC, SS\n      INTEGER           I, K, KI, KN, KSIZE, LENX, LENY, MX, MY\n*     .. Local Arrays ..\n      DOUBLE PRECISION  COPYX(5), COPYY(5), DT9X(7,4,4), DT9Y(7,4,4),\n     +                  DX1(7), DY1(7), MWPC(11), MWPS(11), MWPSTX(5),\n     +                  MWPSTY(5), MWPTX(11,5), MWPTY(11,5), MWPX(5),\n     +                  MWPY(5), SSIZE2(14,2), STX(7), STY(7), SX(7),\n     +                  SY(7)\n      INTEGER           INCXS(4), INCYS(4), LENS(4,2), MWPINX(11),\n     +                  MWPINY(11), MWPN(11), NS(4)\n*     .. External Subroutines ..\n      EXTERNAL          DROT, STEST\n*     .. Intrinsic Functions ..\n      INTRINSIC         ABS, MIN\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      DATA              INCXS/1, 2, -2, -1/\n      DATA              INCYS/1, -2, 1, -2/\n      DATA              LENS/1, 1, 2, 4, 1, 1, 3, 7/\n      DATA              NS/0, 1, 2, 4/\n      DATA              DX1/0.6D0, 0.1D0, -0.5D0, 0.8D0, 0.9D0, -0.3D0,\n     +                  -0.4D0/\n      DATA              DY1/0.5D0, -0.9D0, 0.3D0, 0.7D0, -0.6D0, 0.2D0,\n     +                  0.8D0/\n      DATA              SC, SS/0.8D0, 0.6D0/\n      DATA              DT9X/0.6D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.78D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.78D0, -0.46D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.78D0, -0.46D0, -0.22D0,\n     +                  1.06D0, 0.0D0, 0.0D0, 0.0D0, 0.6D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.78D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.66D0, 0.1D0, -0.1D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.96D0, 0.1D0, -0.76D0, 0.8D0, 0.90D0,\n     +                  -0.3D0, -0.02D0, 0.6D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.78D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, -0.06D0, 0.1D0,\n     +                  -0.1D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.90D0,\n     +                  0.1D0, -0.22D0, 0.8D0, 0.18D0, -0.3D0, -0.02D0,\n     +                  0.6D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.78D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.78D0, 0.26D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.78D0, 0.26D0, -0.76D0, 1.12D0,\n     +                  0.0D0, 0.0D0, 0.0D0/\n      DATA              DT9Y/0.5D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.04D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.04D0, -0.78D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.04D0, -0.78D0, 0.54D0,\n     +                  0.08D0, 0.0D0, 0.0D0, 0.0D0, 0.5D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.04D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.7D0,\n     +                  -0.9D0, -0.12D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.64D0, -0.9D0, -0.30D0, 0.7D0, -0.18D0, 0.2D0,\n     +                  0.28D0, 0.5D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.04D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.7D0, -1.08D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.64D0, -1.26D0,\n     +                  0.54D0, 0.20D0, 0.0D0, 0.0D0, 0.0D0, 0.5D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.04D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.04D0, -0.9D0, 0.18D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.04D0, -0.9D0, 0.18D0, 0.7D0,\n     +                  -0.18D0, 0.2D0, 0.16D0/\n      DATA              SSIZE2/0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 1.17D0, 1.17D0, 1.17D0, 1.17D0, 1.17D0,\n     +                  1.17D0, 1.17D0, 1.17D0, 1.17D0, 1.17D0, 1.17D0,\n     +                  1.17D0, 1.17D0, 1.17D0/\n*     .. Executable Statements ..\n*\n      DO 60 KI = 1, 4\n         INCX = INCXS(KI)\n         INCY = INCYS(KI)\n         MX = ABS(INCX)\n         MY = ABS(INCY)\n*\n         DO 40 KN = 1, 4\n            N = NS(KN)\n            KSIZE = MIN(2,KN)\n            LENX = LENS(KN,MX)\n            LENY = LENS(KN,MY)\n*\n            IF (ICASE.EQ.4) THEN\n*              .. DROT ..\n               DO 20 I = 1, 7\n                  SX(I) = DX1(I)\n                  SY(I) = DY1(I)\n                  STX(I) = DT9X(I,KN,KI)\n                  STY(I) = DT9Y(I,KN,KI)\n   20          CONTINUE\n               CALL DROT(N,SX,INCX,SY,INCY,SC,SS)\n               CALL STEST(LENX,SX,STX,SSIZE2(1,KSIZE),SFAC)\n               CALL STEST(LENY,SY,STY,SSIZE2(1,KSIZE),SFAC)\n            ELSE\n               WRITE (NOUT,*) ' Shouldn''t be here in CHECK3'\n               STOP\n            END IF\n   40    CONTINUE\n   60 CONTINUE\n*\n      MWPC(1) = 1\n      DO 80 I = 2, 11\n         MWPC(I) = 0\n   80 CONTINUE\n      MWPS(1) = 0\n      DO 100 I = 2, 6\n         MWPS(I) = 1\n  100 CONTINUE\n      DO 120 I = 7, 11\n         MWPS(I) = -1\n  120 CONTINUE\n      MWPINX(1) = 1\n      MWPINX(2) = 1\n      MWPINX(3) = 1\n      MWPINX(4) = -1\n      MWPINX(5) = 1\n      MWPINX(6) = -1\n      MWPINX(7) = 1\n      MWPINX(8) = 1\n      MWPINX(9) = -1\n      MWPINX(10) = 1\n      MWPINX(11) = -1\n      MWPINY(1) = 1\n      MWPINY(2) = 1\n      MWPINY(3) = -1\n      MWPINY(4) = -1\n      MWPINY(5) = 2\n      MWPINY(6) = 1\n      MWPINY(7) = 1\n      MWPINY(8) = -1\n      MWPINY(9) = -1\n      MWPINY(10) = 2\n      MWPINY(11) = 1\n      DO 140 I = 1, 11\n         MWPN(I) = 5\n  140 CONTINUE\n      MWPN(5) = 3\n      MWPN(10) = 3\n      DO 160 I = 1, 5\n         MWPX(I) = I\n         MWPY(I) = I\n         MWPTX(1,I) = I\n         MWPTY(1,I) = I\n         MWPTX(2,I) = I\n         MWPTY(2,I) = -I\n         MWPTX(3,I) = 6 - I\n         MWPTY(3,I) = I - 6\n         MWPTX(4,I) = I\n         MWPTY(4,I) = -I\n         MWPTX(6,I) = 6 - I\n         MWPTY(6,I) = I - 6\n         MWPTX(7,I) = -I\n         MWPTY(7,I) = I\n         MWPTX(8,I) = I - 6\n         MWPTY(8,I) = 6 - I\n         MWPTX(9,I) = -I\n         MWPTY(9,I) = I\n         MWPTX(11,I) = I - 6\n         MWPTY(11,I) = 6 - I\n  160 CONTINUE\n      MWPTX(5,1) = 1\n      MWPTX(5,2) = 3\n      MWPTX(5,3) = 5\n      MWPTX(5,4) = 4\n      MWPTX(5,5) = 5\n      MWPTY(5,1) = -1\n      MWPTY(5,2) = 2\n      MWPTY(5,3) = -2\n      MWPTY(5,4) = 4\n      MWPTY(5,5) = -3\n      MWPTX(10,1) = -1\n      MWPTX(10,2) = -3\n      MWPTX(10,3) = -5\n      MWPTX(10,4) = 4\n      MWPTX(10,5) = 5\n      MWPTY(10,1) = 1\n      MWPTY(10,2) = 2\n      MWPTY(10,3) = 2\n      MWPTY(10,4) = 4\n      MWPTY(10,5) = 3\n      DO 200 I = 1, 11\n         INCX = MWPINX(I)\n         INCY = MWPINY(I)\n         DO 180 K = 1, 5\n            COPYX(K) = MWPX(K)\n            COPYY(K) = MWPY(K)\n            MWPSTX(K) = MWPTX(I,K)\n            MWPSTY(K) = MWPTY(I,K)\n  180    CONTINUE\n         CALL DROT(MWPN(I),COPYX,INCX,COPYY,INCY,MWPC(I),MWPS(I))\n         CALL STEST(5,COPYX,MWPSTX,MWPSTX,SFAC)\n         CALL STEST(5,COPYY,MWPSTY,MWPSTY,SFAC)\n  200 CONTINUE\n      RETURN\n      END\n      SUBROUTINE STEST(LEN,SCOMP,STRUE,SSIZE,SFAC)\n*     ********************************* STEST **************************\n*\n*     THIS SUBR COMPARES ARRAYS  SCOMP() AND STRUE() OF LENGTH LEN TO\n*     SEE IF THE TERM BY TERM DIFFERENCES, MULTIPLIED BY SFAC, ARE\n*     NEGLIGIBLE.\n*\n*     C. L. LAWSON, JPL, 1974 DEC 10\n*\n*     .. Parameters ..\n      INTEGER          NOUT\n      DOUBLE PRECISION ZERO\n      PARAMETER        (NOUT=6, ZERO=0.0D0)\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION SFAC\n      INTEGER          LEN\n*     .. Array Arguments ..\n      DOUBLE PRECISION SCOMP(LEN), SSIZE(LEN), STRUE(LEN)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, N\n      LOGICAL          PASS\n*     .. Local Scalars ..\n      DOUBLE PRECISION SD\n      INTEGER          I\n*     .. External Functions ..\n      DOUBLE PRECISION SDIFF\n      EXTERNAL         SDIFF\n*     .. Intrinsic Functions ..\n      INTRINSIC        ABS\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Executable Statements ..\n*\n      DO 40 I = 1, LEN\n         SD = SCOMP(I) - STRUE(I)\n         IF (ABS(SFAC*SD) .LE. ABS(SSIZE(I))*EPSILON(ZERO))\n     +       GO TO 40\n*\n*                             HERE    SCOMP(I) IS NOT CLOSE TO STRUE(I).\n*\n         IF ( .NOT. PASS) GO TO 20\n*                             PRINT FAIL MESSAGE AND HEADER.\n         PASS = .FALSE.\n         WRITE (NOUT,99999)\n         WRITE (NOUT,99998)\n   20    WRITE (NOUT,99997) ICASE, N, INCX, INCY, I, SCOMP(I),\n     +     STRUE(I), SD, SSIZE(I)\n   40 CONTINUE\n      RETURN\n*\n99999 FORMAT ('                                       FAIL')\n99998 FORMAT (/' CASE  N INCX INCY  I                            ',\n     +       ' COMP(I)                             TRUE(I)  DIFFERENCE',\n     +       '     SIZE(I)',/1X)\n99997 FORMAT (1X,I4,I3,2I5,I3,2D36.8,2D12.4)\n      END\n      SUBROUTINE TESTDSDOT(SCOMP,STRUE,SSIZE,SFAC)\n*     ********************************* STEST **************************\n*\n*     THIS SUBR COMPARES ARRAYS  SCOMP() AND STRUE() OF LENGTH LEN TO\n*     SEE IF THE TERM BY TERM DIFFERENCES, MULTIPLIED BY SFAC, ARE\n*     NEGLIGIBLE.\n*\n*     C. L. LAWSON, JPL, 1974 DEC 10\n*\n*     .. Parameters ..\n      INTEGER          NOUT\n      REAL             ZERO\n      PARAMETER        (NOUT=6, ZERO=0.0E0)\n*     .. Scalar Arguments ..\n      REAL             SFAC, SCOMP, SSIZE, STRUE\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, N\n      LOGICAL          PASS\n*     .. Local Scalars ..\n      REAL             SD\n*     .. Intrinsic Functions ..\n      INTRINSIC        ABS\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Executable Statements ..\n*\n         SD = SCOMP - STRUE\n         IF (ABS(SFAC*SD) .LE. ABS(SSIZE) * EPSILON(ZERO))\n     +       GO TO 40\n*\n*                             HERE    SCOMP(I) IS NOT CLOSE TO STRUE(I).\n*\n         IF ( .NOT. PASS) GO TO 20\n*                             PRINT FAIL MESSAGE AND HEADER.\n         PASS = .FALSE.\n         WRITE (NOUT,99999)\n         WRITE (NOUT,99998)\n   20    WRITE (NOUT,99997) ICASE, N, INCX, INCY, SCOMP,\n     +     STRUE, SD, SSIZE\n   40 CONTINUE\n      RETURN\n*\n99999 FORMAT ('                                       FAIL')\n99998 FORMAT (/' CASE  N INCX INCY                           ',\n     +       ' COMP(I)                             TRUE(I)  DIFFERENCE',\n     +       '     SIZE(I)',/1X)\n99997 FORMAT (1X,I4,I3,1I5,I3,2E36.8,2E12.4)\n      END\n      SUBROUTINE STEST1(SCOMP1,STRUE1,SSIZE,SFAC)\n*     ************************* STEST1 *****************************\n*\n*     THIS IS AN INTERFACE SUBROUTINE TO ACCOMMODATE THE FORTRAN\n*     REQUIREMENT THAT WHEN A DUMMY ARGUMENT IS AN ARRAY, THE\n*     ACTUAL ARGUMENT MUST ALSO BE AN ARRAY OR AN ARRAY ELEMENT.\n*\n*     C.L. LAWSON, JPL, 1978 DEC 6\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION  SCOMP1, SFAC, STRUE1\n*     .. Array Arguments ..\n      DOUBLE PRECISION  SSIZE(*)\n*     .. Local Arrays ..\n      DOUBLE PRECISION  SCOMP(1), STRUE(1)\n*     .. External Subroutines ..\n      EXTERNAL          STEST\n*     .. Executable Statements ..\n*\n      SCOMP(1) = SCOMP1\n      STRUE(1) = STRUE1\n      CALL STEST(1,SCOMP,STRUE,SSIZE,SFAC)\n*\n      RETURN\n      END\n      DOUBLE PRECISION FUNCTION SDIFF(SA,SB)\n*     ********************************* SDIFF **************************\n*     COMPUTES DIFFERENCE OF TWO NUMBERS.  C. L. LAWSON, JPL 1974 FEB 15\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION                SA, SB\n*     .. Executable Statements ..\n      SDIFF = SA - SB\n      RETURN\n      END\n      SUBROUTINE ITEST1(ICOMP,ITRUE)\n*     ********************************* ITEST1 *************************\n*\n*     THIS SUBROUTINE COMPARES THE VARIABLES ICOMP AND ITRUE FOR\n*     EQUALITY.\n*     C. L. LAWSON, JPL, 1974 DEC 10\n*\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      INTEGER           ICOMP, ITRUE\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      INTEGER           ID\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Executable Statements ..\n*\n      IF (ICOMP.EQ.ITRUE) GO TO 40\n*\n*                            HERE ICOMP IS NOT EQUAL TO ITRUE.\n*\n      IF ( .NOT. PASS) GO TO 20\n*                             PRINT FAIL MESSAGE AND HEADER.\n      PASS = .FALSE.\n      WRITE (NOUT,99999)\n      WRITE (NOUT,99998)\n   20 ID = ICOMP - ITRUE\n      WRITE (NOUT,99997) ICASE, N, INCX, INCY, ICOMP, ITRUE, ID\n   40 CONTINUE\n      RETURN\n*\n99999 FORMAT ('                                       FAIL')\n99998 FORMAT (/' CASE  N INCX INCY                               ',\n     +       ' COMP                                TRUE     DIFFERENCE',\n     +       /1X)\n99997 FORMAT (1X,I4,I3,2I5,2I36,I12)\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/testing/dblat2.f",
    "content": "*> \\brief \\b DBLAT2\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM DBLAT2\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> Test program for the DOUBLE PRECISION Level 2 Blas.\n*>\n*> The program must be driven by a short data file. The first 18 records\n*> of the file are read using list-directed input, the last 16 records\n*> are read using the format ( A6, L2 ). An annotated example of a data\n*> file can be obtained by deleting the first 3 characters from the\n*> following 34 lines:\n*> 'dblat2.out'      NAME OF SUMMARY OUTPUT FILE\n*> 6                 UNIT NUMBER OF SUMMARY FILE\n*> 'DBLAT2.SNAP'     NAME OF SNAPSHOT OUTPUT FILE\n*> -1                UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0)\n*> F        LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD.\n*> F        LOGICAL FLAG, T TO STOP ON FAILURES.\n*> T        LOGICAL FLAG, T TO TEST ERROR EXITS.\n*> 16.0     THRESHOLD VALUE OF TEST RATIO\n*> 6                 NUMBER OF VALUES OF N\n*> 0 1 2 3 5 9       VALUES OF N\n*> 4                 NUMBER OF VALUES OF K\n*> 0 1 2 4           VALUES OF K\n*> 4                 NUMBER OF VALUES OF INCX AND INCY\n*> 1 2 -1 -2         VALUES OF INCX AND INCY\n*> 3                 NUMBER OF VALUES OF ALPHA\n*> 0.0 1.0 0.7       VALUES OF ALPHA\n*> 3                 NUMBER OF VALUES OF BETA\n*> 0.0 1.0 0.9       VALUES OF BETAC\n*> DGEMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DGBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DSYMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DSBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DSPMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DTRMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DTBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DTPMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DTRSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DTBSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DTPSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DGER   T PUT F FOR NO TEST. SAME COLUMNS.\n*> DSYR   T PUT F FOR NO TEST. SAME COLUMNS.\n*> DSPR   T PUT F FOR NO TEST. SAME COLUMNS.\n*> DSYR2  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DSPR2  T PUT F FOR NO TEST. SAME COLUMNS.\n*>\n*> Further Details\n*> ===============\n*>\n*>    See:\n*>\n*>       Dongarra J. J., Du Croz J. J., Hammarling S.  and Hanson R. J..\n*>       An  extended  set of Fortran  Basic Linear Algebra Subprograms.\n*>\n*>       Technical  Memoranda  Nos. 41 (revision 3) and 81,  Mathematics\n*>       and  Computer Science  Division,  Argonne  National Laboratory,\n*>       9700 South Cass Avenue, Argonne, Illinois 60439, US.\n*>\n*>       Or\n*>\n*>       NAG  Technical Reports TR3/87 and TR4/87,  Numerical Algorithms\n*>       Group  Ltd.,  NAG  Central  Office,  256  Banbury  Road, Oxford\n*>       OX2 7DE, UK,  and  Numerical Algorithms Group Inc.,  1101  31st\n*>       Street,  Suite 100,  Downers Grove,  Illinois 60515-1263,  USA.\n*>\n*>\n*> -- Written on 10-August-1987.\n*>    Richard Hanson, Sandia National Labs.\n*>    Jeremy Du Croz, NAG Central Office.\n*>\n*>    10-9-00:  Change STATUS='NEW' to 'UNKNOWN' so that the testers\n*>              can be run multiple times without deleting generated\n*>              output files (susan)\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup double_blas_testing\n*\n*  =====================================================================\n      PROGRAM DBLAT2\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER            NIN\n      PARAMETER          ( NIN = 5 )\n      INTEGER            NSUBS\n      PARAMETER          ( NSUBS = 16 )\n      DOUBLE PRECISION   ZERO, ONE\n      PARAMETER          ( ZERO = 0.0D0, ONE = 1.0D0 )\n      INTEGER            NMAX, INCMAX\n      PARAMETER          ( NMAX = 65, INCMAX = 2 )\n      INTEGER            NINMAX, NIDMAX, NKBMAX, NALMAX, NBEMAX\n      PARAMETER          ( NINMAX = 7, NIDMAX = 9, NKBMAX = 7,\n     $                   NALMAX = 7, NBEMAX = 7 )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   EPS, ERR, THRESH\n      INTEGER            I, ISNUM, J, N, NALF, NBET, NIDIM, NINC, NKB,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, LTESTT, REWI, SAME, SFATAL, TRACE,\n     $                   TSTERR\n      CHARACTER*1        TRANS\n      CHARACTER*6        SNAMET\n      CHARACTER*32       SNAPS, SUMMRY\n*     .. Local Arrays ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ),\n     $                   ALF( NALMAX ), AS( NMAX*NMAX ), BET( NBEMAX ),\n     $                   G( NMAX ), X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( 2*NMAX )\n      INTEGER            IDIM( NIDMAX ), INC( NINMAX ), KB( NKBMAX )\n      LOGICAL            LTEST( NSUBS )\n      CHARACTER*6        SNAMES( NSUBS )\n*     .. External Functions ..\n      DOUBLE PRECISION   DDIFF\n      LOGICAL            LDE\n      EXTERNAL           DDIFF, LDE\n*     .. External Subroutines ..\n      EXTERNAL           DCHK1, DCHK2, DCHK3, DCHK4, DCHK5, DCHK6,\n     $                   DCHKE, DMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Data statements ..\n      DATA               SNAMES/'DGEMV ', 'DGBMV ', 'DSYMV ', 'DSBMV ',\n     $                   'DSPMV ', 'DTRMV ', 'DTBMV ', 'DTPMV ',\n     $                   'DTRSV ', 'DTBSV ', 'DTPSV ', 'DGER  ',\n     $                   'DSYR  ', 'DSPR  ', 'DSYR2 ', 'DSPR2 '/\n*     .. Executable Statements ..\n*\n*     Read name and unit number for summary output file and open file.\n*\n      READ( NIN, FMT = * )SUMMRY\n      READ( NIN, FMT = * )NOUT\n      OPEN( NOUT, FILE = SUMMRY, STATUS = 'UNKNOWN' )\n      NOUTC = NOUT\n*\n*     Read name and unit number for snapshot output file and open file.\n*\n      READ( NIN, FMT = * )SNAPS\n      READ( NIN, FMT = * )NTRA\n      TRACE = NTRA.GE.0\n      IF( TRACE )THEN\n         OPEN( NTRA, FILE = SNAPS, STATUS = 'UNKNOWN' )\n      END IF\n*     Read the flag that directs rewinding of the snapshot file.\n      READ( NIN, FMT = * )REWI\n      REWI = REWI.AND.TRACE\n*     Read the flag that directs stopping on any failure.\n      READ( NIN, FMT = * )SFATAL\n*     Read the flag that indicates whether error exits are to be tested.\n      READ( NIN, FMT = * )TSTERR\n*     Read the threshold value of the test ratio\n      READ( NIN, FMT = * )THRESH\n*\n*     Read and check the parameter values for the tests.\n*\n*     Values of N\n      READ( NIN, FMT = * )NIDIM\n      IF( NIDIM.LT.1.OR.NIDIM.GT.NIDMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'N', NIDMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( IDIM( I ), I = 1, NIDIM )\n      DO 10 I = 1, NIDIM\n         IF( IDIM( I ).LT.0.OR.IDIM( I ).GT.NMAX )THEN\n            WRITE( NOUT, FMT = 9996 )NMAX\n            GO TO 230\n         END IF\n   10 CONTINUE\n*     Values of K\n      READ( NIN, FMT = * )NKB\n      IF( NKB.LT.1.OR.NKB.GT.NKBMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'K', NKBMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( KB( I ), I = 1, NKB )\n      DO 20 I = 1, NKB\n         IF( KB( I ).LT.0 )THEN\n            WRITE( NOUT, FMT = 9995 )\n            GO TO 230\n         END IF\n   20 CONTINUE\n*     Values of INCX and INCY\n      READ( NIN, FMT = * )NINC\n      IF( NINC.LT.1.OR.NINC.GT.NINMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'INCX AND INCY', NINMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( INC( I ), I = 1, NINC )\n      DO 30 I = 1, NINC\n         IF( INC( I ).EQ.0.OR.ABS( INC( I ) ).GT.INCMAX )THEN\n            WRITE( NOUT, FMT = 9994 )INCMAX\n            GO TO 230\n         END IF\n   30 CONTINUE\n*     Values of ALPHA\n      READ( NIN, FMT = * )NALF\n      IF( NALF.LT.1.OR.NALF.GT.NALMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'ALPHA', NALMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( ALF( I ), I = 1, NALF )\n*     Values of BETA\n      READ( NIN, FMT = * )NBET\n      IF( NBET.LT.1.OR.NBET.GT.NBEMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'BETA', NBEMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( BET( I ), I = 1, NBET )\n*\n*     Report values of parameters.\n*\n      WRITE( NOUT, FMT = 9993 )\n      WRITE( NOUT, FMT = 9992 )( IDIM( I ), I = 1, NIDIM )\n      WRITE( NOUT, FMT = 9991 )( KB( I ), I = 1, NKB )\n      WRITE( NOUT, FMT = 9990 )( INC( I ), I = 1, NINC )\n      WRITE( NOUT, FMT = 9989 )( ALF( I ), I = 1, NALF )\n      WRITE( NOUT, FMT = 9988 )( BET( I ), I = 1, NBET )\n      IF( .NOT.TSTERR )THEN\n         WRITE( NOUT, FMT = * )\n         WRITE( NOUT, FMT = 9980 )\n      END IF\n      WRITE( NOUT, FMT = * )\n      WRITE( NOUT, FMT = 9999 )THRESH\n      WRITE( NOUT, FMT = * )\n*\n*     Read names of subroutines and flags which indicate\n*     whether they are to be tested.\n*\n      DO 40 I = 1, NSUBS\n         LTEST( I ) = .FALSE.\n   40 CONTINUE\n   50 READ( NIN, FMT = 9984, END = 80 )SNAMET, LTESTT\n      DO 60 I = 1, NSUBS\n         IF( SNAMET.EQ.SNAMES( I ) )\n     $      GO TO 70\n   60 CONTINUE\n      WRITE( NOUT, FMT = 9986 )SNAMET\n      STOP\n   70 LTEST( I ) = LTESTT\n      GO TO 50\n*\n   80 CONTINUE\n      CLOSE ( NIN )\n*\n*     Compute EPS (the machine precision).\n*\n      EPS = EPSILON(ZERO)\n      WRITE( NOUT, FMT = 9998 )EPS\n*\n*     Check the reliability of DMVCH using exact data.\n*\n      N = MIN( 32, NMAX )\n      DO 120 J = 1, N\n         DO 110 I = 1, N\n            A( I, J ) = MAX( I - J + 1, 0 )\n  110    CONTINUE\n         X( J ) = J\n         Y( J ) = ZERO\n  120 CONTINUE\n      DO 130 J = 1, N\n         YY( J ) = J*( ( J + 1 )*J )/2 - ( ( J + 1 )*J*( J - 1 ) )/3\n  130 CONTINUE\n*     YY holds the exact result. On exit from DMVCH YT holds\n*     the result computed by DMVCH.\n      TRANS = 'N'\n      CALL DMVCH( TRANS, N, N, ONE, A, NMAX, X, 1, ZERO, Y, 1, YT, G,\n     $            YY, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LDE( YY, YT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9985 )TRANS, SAME, ERR\n         STOP\n      END IF\n      TRANS = 'T'\n      CALL DMVCH( TRANS, N, N, ONE, A, NMAX, X, -1, ZERO, Y, -1, YT, G,\n     $            YY, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LDE( YY, YT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9985 )TRANS, SAME, ERR\n         STOP\n      END IF\n*\n*     Test each subroutine in turn.\n*\n      DO 210 ISNUM = 1, NSUBS\n         WRITE( NOUT, FMT = * )\n         IF( .NOT.LTEST( ISNUM ) )THEN\n*           Subprogram is not to be tested.\n            WRITE( NOUT, FMT = 9983 )SNAMES( ISNUM )\n         ELSE\n            SRNAMT = SNAMES( ISNUM )\n*           Test error exits.\n            IF( TSTERR )THEN\n               CALL DCHKE( ISNUM, SNAMES( ISNUM ), NOUT )\n               WRITE( NOUT, FMT = * )\n            END IF\n*           Test computations.\n            INFOT = 0\n            OK = .TRUE.\n            FATAL = .FALSE.\n            GO TO ( 140, 140, 150, 150, 150, 160, 160,\n     $              160, 160, 160, 160, 170, 180, 180,\n     $              190, 190 )ISNUM\n*           Test DGEMV, 01, and DGBMV, 02.\n  140       CALL DCHK1( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF,\n     $                  NBET, BET, NINC, INC, NMAX, INCMAX, A, AA, AS,\n     $                  X, XX, XS, Y, YY, YS, YT, G )\n            GO TO 200\n*           Test DSYMV, 03, DSBMV, 04, and DSPMV, 05.\n  150       CALL DCHK2( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF,\n     $                  NBET, BET, NINC, INC, NMAX, INCMAX, A, AA, AS,\n     $                  X, XX, XS, Y, YY, YS, YT, G )\n            GO TO 200\n*           Test DTRMV, 06, DTBMV, 07, DTPMV, 08,\n*           DTRSV, 09, DTBSV, 10, and DTPSV, 11.\n  160       CALL DCHK3( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, Y, YY, YS, YT, G, Z )\n            GO TO 200\n*           Test DGER, 12.\n  170       CALL DCHK4( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n            GO TO 200\n*           Test DSYR, 13, and DSPR, 14.\n  180       CALL DCHK5( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n            GO TO 200\n*           Test DSYR2, 15, and DSPR2, 16.\n  190       CALL DCHK6( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n*\n  200       IF( FATAL.AND.SFATAL )\n     $         GO TO 220\n         END IF\n  210 CONTINUE\n      WRITE( NOUT, FMT = 9982 )\n      GO TO 240\n*\n  220 CONTINUE\n      WRITE( NOUT, FMT = 9981 )\n      GO TO 240\n*\n  230 CONTINUE\n      WRITE( NOUT, FMT = 9987 )\n*\n  240 CONTINUE\n      IF( TRACE )\n     $   CLOSE ( NTRA )\n      CLOSE ( NOUT )\n      STOP\n*\n 9999 FORMAT( ' ROUTINES PASS COMPUTATIONAL TESTS IF TEST RATIO IS LES',\n     $      'S THAN', F8.2 )\n 9998 FORMAT( ' RELATIVE MACHINE PRECISION IS TAKEN TO BE', 1P, D9.1 )\n 9997 FORMAT( ' NUMBER OF VALUES OF ', A, ' IS LESS THAN 1 OR GREATER ',\n     $      'THAN ', I2 )\n 9996 FORMAT( ' VALUE OF N IS LESS THAN 0 OR GREATER THAN ', I2 )\n 9995 FORMAT( ' VALUE OF K IS LESS THAN 0' )\n 9994 FORMAT( ' ABSOLUTE VALUE OF INCX OR INCY IS 0 OR GREATER THAN ',\n     $      I2 )\n 9993 FORMAT( ' TESTS OF THE DOUBLE PRECISION LEVEL 2 BLAS', //' THE F',\n     $      'OLLOWING PARAMETER VALUES WILL BE USED:' )\n 9992 FORMAT( '   FOR N              ', 9I6 )\n 9991 FORMAT( '   FOR K              ', 7I6 )\n 9990 FORMAT( '   FOR INCX AND INCY  ', 7I6 )\n 9989 FORMAT( '   FOR ALPHA          ', 7F6.1 )\n 9988 FORMAT( '   FOR BETA           ', 7F6.1 )\n 9987 FORMAT( ' AMEND DATA FILE OR INCREASE ARRAY SIZES IN PROGRAM',\n     $      /' ******* TESTS ABANDONED *******' )\n 9986 FORMAT( ' SUBPROGRAM NAME ', A6, ' NOT RECOGNIZED', /' ******* T',\n     $      'ESTS ABANDONED *******' )\n 9985 FORMAT( ' ERROR IN DMVCH -  IN-LINE DOT PRODUCTS ARE BEING EVALU',\n     $      'ATED WRONGLY.', /' DMVCH WAS CALLED WITH TRANS = ', A1,\n     $      ' AND RETURNED SAME = ', L1, ' AND ERR = ', F12.3, '.', /\n     $   ' THIS MAY BE DUE TO FAULTS IN THE ARITHMETIC OR THE COMPILER.'\n     $      , /' ******* TESTS ABANDONED *******' )\n 9984 FORMAT( A6, L2 )\n 9983 FORMAT( 1X, A6, ' WAS NOT TESTED' )\n 9982 FORMAT( /' END OF TESTS' )\n 9981 FORMAT( /' ******* FATAL ERROR - TESTS ABANDONED *******' )\n 9980 FORMAT( ' ERROR-EXITS WILL NOT BE TESTED' )\n*\n*     End of DBLAT2.\n*\n      END\n      SUBROUTINE DCHK1( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF, NBET,\n     $                  BET, NINC, INC, NMAX, INCMAX, A, AA, AS, X, XX,\n     $                  XS, Y, YY, YS, YT, G )\n*\n*  Tests DGEMV and DGBMV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, HALF\n      PARAMETER          ( ZERO = 0.0D0, HALF = 0.5D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NALF, NBET, NIDIM, NINC, NKB, NMAX,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), BET( NBET ), G( NMAX ),\n     $                   X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, ALS, BETA, BLS, ERR, ERRMAX, TRANSL\n      INTEGER            I, IA, IB, IC, IKU, IM, IN, INCX, INCXS, INCY,\n     $                   INCYS, IX, IY, KL, KLS, KU, KUS, LAA, LDA,\n     $                   LDAS, LX, LY, M, ML, MS, N, NARGS, NC, ND, NK,\n     $                   NL, NS\n      LOGICAL            BANDED, FULL, NULL, RESET, SAME, TRAN\n      CHARACTER*1        TRANS, TRANSS\n      CHARACTER*3        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DGBMV, DGEMV, DMAKE, DMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'NTC'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'E'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 11\n      ELSE IF( BANDED )THEN\n         NARGS = 13\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 120 IN = 1, NIDIM\n         N = IDIM( IN )\n         ND = N/2 + 1\n*\n         DO 110 IM = 1, 2\n            IF( IM.EQ.1 )\n     $         M = MAX( N - ND, 0 )\n            IF( IM.EQ.2 )\n     $         M = MIN( N + ND, NMAX )\n*\n            IF( BANDED )THEN\n               NK = NKB\n            ELSE\n               NK = 1\n            END IF\n            DO 100 IKU = 1, NK\n               IF( BANDED )THEN\n                  KU = KB( IKU )\n                  KL = MAX( KU - 1, 0 )\n               ELSE\n                  KU = N - 1\n                  KL = M - 1\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               IF( BANDED )THEN\n                  LDA = KL + KU + 1\n               ELSE\n                  LDA = M\n               END IF\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 100\n               LAA = LDA*N\n               NULL = N.LE.0.OR.M.LE.0\n*\n*              Generate the matrix A.\n*\n               TRANSL = ZERO\n               CALL DMAKE( SNAME( 2: 3 ), ' ', ' ', M, N, A, NMAX, AA,\n     $                     LDA, KL, KU, RESET, TRANSL )\n*\n               DO 90 IC = 1, 3\n                  TRANS = ICH( IC: IC )\n                  TRAN = TRANS.EQ.'T'.OR.TRANS.EQ.'C'\n*\n                  IF( TRAN )THEN\n                     ML = N\n                     NL = M\n                  ELSE\n                     ML = M\n                     NL = N\n                  END IF\n*\n                  DO 80 IX = 1, NINC\n                     INCX = INC( IX )\n                     LX = ABS( INCX )*NL\n*\n*                    Generate the vector X.\n*\n                     TRANSL = HALF\n                     CALL DMAKE( 'GE', ' ', ' ', 1, NL, X, 1, XX,\n     $                           ABS( INCX ), 0, NL - 1, RESET, TRANSL )\n                     IF( NL.GT.1 )THEN\n                        X( NL/2 ) = ZERO\n                        XX( 1 + ABS( INCX )*( NL/2 - 1 ) ) = ZERO\n                     END IF\n*\n                     DO 70 IY = 1, NINC\n                        INCY = INC( IY )\n                        LY = ABS( INCY )*ML\n*\n                        DO 60 IA = 1, NALF\n                           ALPHA = ALF( IA )\n*\n                           DO 50 IB = 1, NBET\n                              BETA = BET( IB )\n*\n*                             Generate the vector Y.\n*\n                              TRANSL = ZERO\n                              CALL DMAKE( 'GE', ' ', ' ', 1, ML, Y, 1,\n     $                                    YY, ABS( INCY ), 0, ML - 1,\n     $                                    RESET, TRANSL )\n*\n                              NC = NC + 1\n*\n*                             Save every datum before calling the\n*                             subroutine.\n*\n                              TRANSS = TRANS\n                              MS = M\n                              NS = N\n                              KLS = KL\n                              KUS = KU\n                              ALS = ALPHA\n                              DO 10 I = 1, LAA\n                                 AS( I ) = AA( I )\n   10                         CONTINUE\n                              LDAS = LDA\n                              DO 20 I = 1, LX\n                                 XS( I ) = XX( I )\n   20                         CONTINUE\n                              INCXS = INCX\n                              BLS = BETA\n                              DO 30 I = 1, LY\n                                 YS( I ) = YY( I )\n   30                         CONTINUE\n                              INCYS = INCY\n*\n*                             Call the subroutine.\n*\n                              IF( FULL )THEN\n                                 IF( TRACE )\n     $                              WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                              TRANS, M, N, ALPHA, LDA, INCX, BETA,\n     $                              INCY\n                                 IF( REWI )\n     $                              REWIND NTRA\n                                 CALL DGEMV( TRANS, M, N, ALPHA, AA,\n     $                                       LDA, XX, INCX, BETA, YY,\n     $                                       INCY )\n                              ELSE IF( BANDED )THEN\n                                 IF( TRACE )\n     $                              WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                              TRANS, M, N, KL, KU, ALPHA, LDA,\n     $                              INCX, BETA, INCY\n                                 IF( REWI )\n     $                              REWIND NTRA\n                                 CALL DGBMV( TRANS, M, N, KL, KU, ALPHA,\n     $                                       AA, LDA, XX, INCX, BETA,\n     $                                       YY, INCY )\n                              END IF\n*\n*                             Check if error-exit was taken incorrectly.\n*\n                              IF( .NOT.OK )THEN\n                                 WRITE( NOUT, FMT = 9993 )\n                                 FATAL = .TRUE.\n                                 GO TO 130\n                              END IF\n*\n*                             See what data changed inside subroutines.\n*\n                              ISAME( 1 ) = TRANS.EQ.TRANSS\n                              ISAME( 2 ) = MS.EQ.M\n                              ISAME( 3 ) = NS.EQ.N\n                              IF( FULL )THEN\n                                 ISAME( 4 ) = ALS.EQ.ALPHA\n                                 ISAME( 5 ) = LDE( AS, AA, LAA )\n                                 ISAME( 6 ) = LDAS.EQ.LDA\n                                 ISAME( 7 ) = LDE( XS, XX, LX )\n                                 ISAME( 8 ) = INCXS.EQ.INCX\n                                 ISAME( 9 ) = BLS.EQ.BETA\n                                 IF( NULL )THEN\n                                    ISAME( 10 ) = LDE( YS, YY, LY )\n                                 ELSE\n                                    ISAME( 10 ) = LDERES( 'GE', ' ', 1,\n     $                                            ML, YS, YY,\n     $                                            ABS( INCY ) )\n                                 END IF\n                                 ISAME( 11 ) = INCYS.EQ.INCY\n                              ELSE IF( BANDED )THEN\n                                 ISAME( 4 ) = KLS.EQ.KL\n                                 ISAME( 5 ) = KUS.EQ.KU\n                                 ISAME( 6 ) = ALS.EQ.ALPHA\n                                 ISAME( 7 ) = LDE( AS, AA, LAA )\n                                 ISAME( 8 ) = LDAS.EQ.LDA\n                                 ISAME( 9 ) = LDE( XS, XX, LX )\n                                 ISAME( 10 ) = INCXS.EQ.INCX\n                                 ISAME( 11 ) = BLS.EQ.BETA\n                                 IF( NULL )THEN\n                                    ISAME( 12 ) = LDE( YS, YY, LY )\n                                 ELSE\n                                    ISAME( 12 ) = LDERES( 'GE', ' ', 1,\n     $                                            ML, YS, YY,\n     $                                            ABS( INCY ) )\n                                 END IF\n                                 ISAME( 13 ) = INCYS.EQ.INCY\n                              END IF\n*\n*                             If data was incorrectly changed, report\n*                             and return.\n*\n                              SAME = .TRUE.\n                              DO 40 I = 1, NARGS\n                                 SAME = SAME.AND.ISAME( I )\n                                 IF( .NOT.ISAME( I ) )\n     $                              WRITE( NOUT, FMT = 9998 )I\n   40                         CONTINUE\n                              IF( .NOT.SAME )THEN\n                                 FATAL = .TRUE.\n                                 GO TO 130\n                              END IF\n*\n                              IF( .NOT.NULL )THEN\n*\n*                                Check the result.\n*\n                                 CALL DMVCH( TRANS, M, N, ALPHA, A,\n     $                                       NMAX, X, INCX, BETA, Y,\n     $                                       INCY, YT, G, YY, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                                 ERRMAX = MAX( ERRMAX, ERR )\n*                                If got really bad answer, report and\n*                                return.\n                                 IF( FATAL )\n     $                              GO TO 130\n                              ELSE\n*                                Avoid repeating tests with M.le.0 or\n*                                N.le.0.\n                                 GO TO 110\n                              END IF\n*\n   50                      CONTINUE\n*\n   60                   CONTINUE\n*\n   70                CONTINUE\n*\n   80             CONTINUE\n*\n   90          CONTINUE\n*\n  100       CONTINUE\n*\n  110    CONTINUE\n*\n  120 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 140\n*\n  130 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, TRANS, M, N, ALPHA, LDA,\n     $      INCX, BETA, INCY\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, TRANS, M, N, KL, KU,\n     $      ALPHA, LDA, INCX, BETA, INCY\n      END IF\n*\n  140 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 4( I3, ',' ), F4.1,\n     $      ', A,', I3, ', X,', I2, ',', F4.1, ', Y,', I2, ') .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 2( I3, ',' ), F4.1,\n     $      ', A,', I3, ', X,', I2, ',', F4.1, ', Y,', I2,\n     $      ')         .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK1.\n*\n      END\n      SUBROUTINE DCHK2( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF, NBET,\n     $                  BET, NINC, INC, NMAX, INCMAX, A, AA, AS, X, XX,\n     $                  XS, Y, YY, YS, YT, G )\n*\n*  Tests DSYMV, DSBMV and DSPMV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, HALF\n      PARAMETER          ( ZERO = 0.0D0, HALF = 0.5D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NALF, NBET, NIDIM, NINC, NKB, NMAX,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), BET( NBET ), G( NMAX ),\n     $                   X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, ALS, BETA, BLS, ERR, ERRMAX, TRANSL\n      INTEGER            I, IA, IB, IC, IK, IN, INCX, INCXS, INCY,\n     $                   INCYS, IX, IY, K, KS, LAA, LDA, LDAS, LX, LY,\n     $                   N, NARGS, NC, NK, NS\n      LOGICAL            BANDED, FULL, NULL, PACKED, RESET, SAME\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DMAKE, DMVCH, DSBMV, DSPMV, DSYMV\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'Y'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 10\n      ELSE IF( BANDED )THEN\n         NARGS = 11\n      ELSE IF( PACKED )THEN\n         NARGS = 9\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 110 IN = 1, NIDIM\n         N = IDIM( IN )\n*\n         IF( BANDED )THEN\n            NK = NKB\n         ELSE\n            NK = 1\n         END IF\n         DO 100 IK = 1, NK\n            IF( BANDED )THEN\n               K = KB( IK )\n            ELSE\n               K = N - 1\n            END IF\n*           Set LDA to 1 more than minimum value if room.\n            IF( BANDED )THEN\n               LDA = K + 1\n            ELSE\n               LDA = N\n            END IF\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 100\n            IF( PACKED )THEN\n               LAA = ( N*( N + 1 ) )/2\n            ELSE\n               LAA = LDA*N\n            END IF\n            NULL = N.LE.0\n*\n            DO 90 IC = 1, 2\n               UPLO = ICH( IC: IC )\n*\n*              Generate the matrix A.\n*\n               TRANSL = ZERO\n               CALL DMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A, NMAX, AA,\n     $                     LDA, K, K, RESET, TRANSL )\n*\n               DO 80 IX = 1, NINC\n                  INCX = INC( IX )\n                  LX = ABS( INCX )*N\n*\n*                 Generate the vector X.\n*\n                  TRANSL = HALF\n                  CALL DMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX,\n     $                        ABS( INCX ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     X( N/2 ) = ZERO\n                     XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 70 IY = 1, NINC\n                     INCY = INC( IY )\n                     LY = ABS( INCY )*N\n*\n                     DO 60 IA = 1, NALF\n                        ALPHA = ALF( IA )\n*\n                        DO 50 IB = 1, NBET\n                           BETA = BET( IB )\n*\n*                          Generate the vector Y.\n*\n                           TRANSL = ZERO\n                           CALL DMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                                 ABS( INCY ), 0, N - 1, RESET,\n     $                                 TRANSL )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           UPLOS = UPLO\n                           NS = N\n                           KS = K\n                           ALS = ALPHA\n                           DO 10 I = 1, LAA\n                              AS( I ) = AA( I )\n   10                      CONTINUE\n                           LDAS = LDA\n                           DO 20 I = 1, LX\n                              XS( I ) = XX( I )\n   20                      CONTINUE\n                           INCXS = INCX\n                           BLS = BETA\n                           DO 30 I = 1, LY\n                              YS( I ) = YY( I )\n   30                      CONTINUE\n                           INCYS = INCY\n*\n*                          Call the subroutine.\n*\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, N, ALPHA, LDA, INCX, BETA, INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DSYMV( UPLO, N, ALPHA, AA, LDA, XX,\n     $                                    INCX, BETA, YY, INCY )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, N, K, ALPHA, LDA, INCX, BETA,\n     $                           INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DSBMV( UPLO, N, K, ALPHA, AA, LDA,\n     $                                    XX, INCX, BETA, YY, INCY )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, N, ALPHA, INCX, BETA, INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DSPMV( UPLO, N, ALPHA, AA, XX, INCX,\n     $                                    BETA, YY, INCY )\n                           END IF\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9992 )\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = UPLO.EQ.UPLOS\n                           ISAME( 2 ) = NS.EQ.N\n                           IF( FULL )THEN\n                              ISAME( 3 ) = ALS.EQ.ALPHA\n                              ISAME( 4 ) = LDE( AS, AA, LAA )\n                              ISAME( 5 ) = LDAS.EQ.LDA\n                              ISAME( 6 ) = LDE( XS, XX, LX )\n                              ISAME( 7 ) = INCXS.EQ.INCX\n                              ISAME( 8 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 9 ) = LDE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 9 ) = LDERES( 'GE', ' ', 1, N,\n     $                                        YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 10 ) = INCYS.EQ.INCY\n                           ELSE IF( BANDED )THEN\n                              ISAME( 3 ) = KS.EQ.K\n                              ISAME( 4 ) = ALS.EQ.ALPHA\n                              ISAME( 5 ) = LDE( AS, AA, LAA )\n                              ISAME( 6 ) = LDAS.EQ.LDA\n                              ISAME( 7 ) = LDE( XS, XX, LX )\n                              ISAME( 8 ) = INCXS.EQ.INCX\n                              ISAME( 9 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 10 ) = LDE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 10 ) = LDERES( 'GE', ' ', 1, N,\n     $                                         YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 11 ) = INCYS.EQ.INCY\n                           ELSE IF( PACKED )THEN\n                              ISAME( 3 ) = ALS.EQ.ALPHA\n                              ISAME( 4 ) = LDE( AS, AA, LAA )\n                              ISAME( 5 ) = LDE( XS, XX, LX )\n                              ISAME( 6 ) = INCXS.EQ.INCX\n                              ISAME( 7 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 8 ) = LDE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 8 ) = LDERES( 'GE', ' ', 1, N,\n     $                                        YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 9 ) = INCYS.EQ.INCY\n                           END IF\n*\n*                          If data was incorrectly changed, report and\n*                          return.\n*\n                           SAME = .TRUE.\n                           DO 40 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   40                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n*\n*                             Check the result.\n*\n                              CALL DMVCH( 'N', N, N, ALPHA, A, NMAX, X,\n     $                                    INCX, BETA, Y, INCY, YT, G,\n     $                                    YY, EPS, ERR, FATAL, NOUT,\n     $                                    .TRUE. )\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 120\n                           ELSE\n*                             Avoid repeating tests with N.le.0\n                              GO TO 110\n                           END IF\n*\n   50                   CONTINUE\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, ALPHA, LDA, INCX,\n     $      BETA, INCY\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, K, ALPHA, LDA,\n     $      INCX, BETA, INCY\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, UPLO, N, ALPHA, INCX,\n     $      BETA, INCY\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', AP',\n     $      ', X,', I2, ',', F4.1, ', Y,', I2, ')                .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 2( I3, ',' ), F4.1,\n     $      ', A,', I3, ', X,', I2, ',', F4.1, ', Y,', I2,\n     $      ')         .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', A,',\n     $      I3, ', X,', I2, ',', F4.1, ', Y,', I2, ')             .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK2.\n*\n      END\n      SUBROUTINE DCHK3( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, XT, G, Z )\n*\n*  Tests DTRMV, DTBMV, DTPMV, DTRSV, DTBSV and DTPSV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, HALF, ONE\n      PARAMETER          ( ZERO = 0.0D0, HALF = 0.5D0, ONE = 1.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NIDIM, NINC, NKB, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ),\n     $                   AS( NMAX*NMAX ), G( NMAX ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XT( NMAX ),\n     $                   XX( NMAX*INCMAX ), Z( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ERR, ERRMAX, TRANSL\n      INTEGER            I, ICD, ICT, ICU, IK, IN, INCX, INCXS, IX, K,\n     $                   KS, LAA, LDA, LDAS, LX, N, NARGS, NC, NK, NS\n      LOGICAL            BANDED, FULL, NULL, PACKED, RESET, SAME\n      CHARACTER*1        DIAG, DIAGS, TRANS, TRANSS, UPLO, UPLOS\n      CHARACTER*2        ICHD, ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DMAKE, DMVCH, DTBMV, DTBSV, DTPMV, DTPSV,\n     $                   DTRMV, DTRSV\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHU/'UL'/, ICHT/'NTC'/, ICHD/'UN'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'R'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 8\n      ELSE IF( BANDED )THEN\n         NARGS = 9\n      ELSE IF( PACKED )THEN\n         NARGS = 7\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*     Set up zero vector for DMVCH.\n      DO 10 I = 1, NMAX\n         Z( I ) = ZERO\n   10 CONTINUE\n*\n      DO 110 IN = 1, NIDIM\n         N = IDIM( IN )\n*\n         IF( BANDED )THEN\n            NK = NKB\n         ELSE\n            NK = 1\n         END IF\n         DO 100 IK = 1, NK\n            IF( BANDED )THEN\n               K = KB( IK )\n            ELSE\n               K = N - 1\n            END IF\n*           Set LDA to 1 more than minimum value if room.\n            IF( BANDED )THEN\n               LDA = K + 1\n            ELSE\n               LDA = N\n            END IF\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 100\n            IF( PACKED )THEN\n               LAA = ( N*( N + 1 ) )/2\n            ELSE\n               LAA = LDA*N\n            END IF\n            NULL = N.LE.0\n*\n            DO 90 ICU = 1, 2\n               UPLO = ICHU( ICU: ICU )\n*\n               DO 80 ICT = 1, 3\n                  TRANS = ICHT( ICT: ICT )\n*\n                  DO 70 ICD = 1, 2\n                     DIAG = ICHD( ICD: ICD )\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL DMAKE( SNAME( 2: 3 ), UPLO, DIAG, N, N, A,\n     $                           NMAX, AA, LDA, K, K, RESET, TRANSL )\n*\n                     DO 60 IX = 1, NINC\n                        INCX = INC( IX )\n                        LX = ABS( INCX )*N\n*\n*                       Generate the vector X.\n*\n                        TRANSL = HALF\n                        CALL DMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX,\n     $                              ABS( INCX ), 0, N - 1, RESET,\n     $                              TRANSL )\n                        IF( N.GT.1 )THEN\n                           X( N/2 ) = ZERO\n                           XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n                        END IF\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        DIAGS = DIAG\n                        NS = N\n                        KS = K\n                        DO 20 I = 1, LAA\n                           AS( I ) = AA( I )\n   20                   CONTINUE\n                        LDAS = LDA\n                        DO 30 I = 1, LX\n                           XS( I ) = XX( I )\n   30                   CONTINUE\n                        INCXS = INCX\n*\n*                       Call the subroutine.\n*\n                        IF( SNAME( 4: 5 ).EQ.'MV' )THEN\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DTRMV( UPLO, TRANS, DIAG, N, AA, LDA,\n     $                                    XX, INCX )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, K, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DTBMV( UPLO, TRANS, DIAG, N, K, AA,\n     $                                    LDA, XX, INCX )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DTPMV( UPLO, TRANS, DIAG, N, AA, XX,\n     $                                    INCX )\n                           END IF\n                        ELSE IF( SNAME( 4: 5 ).EQ.'SV' )THEN\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DTRSV( UPLO, TRANS, DIAG, N, AA, LDA,\n     $                                    XX, INCX )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, K, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DTBSV( UPLO, TRANS, DIAG, N, K, AA,\n     $                                    LDA, XX, INCX )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DTPSV( UPLO, TRANS, DIAG, N, AA, XX,\n     $                                    INCX )\n                           END IF\n                        END IF\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9992 )\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLO.EQ.UPLOS\n                        ISAME( 2 ) = TRANS.EQ.TRANSS\n                        ISAME( 3 ) = DIAG.EQ.DIAGS\n                        ISAME( 4 ) = NS.EQ.N\n                        IF( FULL )THEN\n                           ISAME( 5 ) = LDE( AS, AA, LAA )\n                           ISAME( 6 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 7 ) = LDE( XS, XX, LX )\n                           ELSE\n                              ISAME( 7 ) = LDERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 8 ) = INCXS.EQ.INCX\n                        ELSE IF( BANDED )THEN\n                           ISAME( 5 ) = KS.EQ.K\n                           ISAME( 6 ) = LDE( AS, AA, LAA )\n                           ISAME( 7 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 8 ) = LDE( XS, XX, LX )\n                           ELSE\n                              ISAME( 8 ) = LDERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 9 ) = INCXS.EQ.INCX\n                        ELSE IF( PACKED )THEN\n                           ISAME( 5 ) = LDE( AS, AA, LAA )\n                           IF( NULL )THEN\n                              ISAME( 6 ) = LDE( XS, XX, LX )\n                           ELSE\n                              ISAME( 6 ) = LDERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 7 ) = INCXS.EQ.INCX\n                        END IF\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n                           IF( SNAME( 4: 5 ).EQ.'MV' )THEN\n*\n*                             Check the result.\n*\n                              CALL DMVCH( TRANS, N, N, ONE, A, NMAX, X,\n     $                                    INCX, ZERO, Z, INCX, XT, G,\n     $                                    XX, EPS, ERR, FATAL, NOUT,\n     $                                    .TRUE. )\n                           ELSE IF( SNAME( 4: 5 ).EQ.'SV' )THEN\n*\n*                             Compute approximation to original vector.\n*\n                              DO 50 I = 1, N\n                                 Z( I ) = XX( 1 + ( I - 1 )*\n     $                                    ABS( INCX ) )\n                                 XX( 1 + ( I - 1 )*ABS( INCX ) )\n     $                              = X( I )\n   50                         CONTINUE\n                              CALL DMVCH( TRANS, N, N, ONE, A, NMAX, Z,\n     $                                    INCX, ZERO, X, INCX, XT, G,\n     $                                    XX, EPS, ERR, FATAL, NOUT,\n     $                                    .FALSE. )\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 120\n                        ELSE\n*                          Avoid repeating tests with N.le.0.\n                           GO TO 110\n                        END IF\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, TRANS, DIAG, N, LDA,\n     $      INCX\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, DIAG, N, K,\n     $      LDA, INCX\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, UPLO, TRANS, DIAG, N, INCX\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), I3, ', AP, ',\n     $      'X,', I2, ')                        .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), 2( I3, ',' ),\n     $      ' A,', I3, ', X,', I2, ')                 .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), I3, ', A,',\n     $      I3, ', X,', I2, ')                     .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK3.\n*\n      END\n      SUBROUTINE DCHK4( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests DGER.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, HALF, ONE\n      PARAMETER          ( ZERO = 0.0D0, HALF = 0.5D0, ONE = 1.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), G( NMAX ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XX( NMAX*INCMAX ),\n     $                   Y( NMAX ), YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, ALS, ERR, ERRMAX, TRANSL\n      INTEGER            I, IA, IM, IN, INCX, INCXS, INCY, INCYS, IX,\n     $                   IY, J, LAA, LDA, LDAS, LX, LY, M, MS, N, NARGS,\n     $                   NC, ND, NS\n      LOGICAL            NULL, RESET, SAME\n*     .. Local Arrays ..\n      DOUBLE PRECISION   W( 1 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DGER, DMAKE, DMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n*     Define the number of arguments.\n      NARGS = 9\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 120 IN = 1, NIDIM\n         N = IDIM( IN )\n         ND = N/2 + 1\n*\n         DO 110 IM = 1, 2\n            IF( IM.EQ.1 )\n     $         M = MAX( N - ND, 0 )\n            IF( IM.EQ.2 )\n     $         M = MIN( N + ND, NMAX )\n*\n*           Set LDA to 1 more than minimum value if room.\n            LDA = M\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 110\n            LAA = LDA*N\n            NULL = N.LE.0.OR.M.LE.0\n*\n            DO 100 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*M\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL DMAKE( 'GE', ' ', ' ', 1, M, X, 1, XX, ABS( INCX ),\n     $                     0, M - 1, RESET, TRANSL )\n               IF( M.GT.1 )THEN\n                  X( M/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( M/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 90 IY = 1, NINC\n                  INCY = INC( IY )\n                  LY = ABS( INCY )*N\n*\n*                 Generate the vector Y.\n*\n                  TRANSL = ZERO\n                  CALL DMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                        ABS( INCY ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     Y( N/2 ) = ZERO\n                     YY( 1 + ABS( INCY )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 80 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL DMAKE( SNAME( 2: 3 ), ' ', ' ', M, N, A, NMAX,\n     $                           AA, LDA, M - 1, N - 1, RESET, TRANSL )\n*\n                     NC = NC + 1\n*\n*                    Save every datum before calling the subroutine.\n*\n                     MS = M\n                     NS = N\n                     ALS = ALPHA\n                     DO 10 I = 1, LAA\n                        AS( I ) = AA( I )\n   10                CONTINUE\n                     LDAS = LDA\n                     DO 20 I = 1, LX\n                        XS( I ) = XX( I )\n   20                CONTINUE\n                     INCXS = INCX\n                     DO 30 I = 1, LY\n                        YS( I ) = YY( I )\n   30                CONTINUE\n                     INCYS = INCY\n*\n*                    Call the subroutine.\n*\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9994 )NC, SNAME, M, N,\n     $                  ALPHA, INCX, INCY, LDA\n                     IF( REWI )\n     $                  REWIND NTRA\n                     CALL DGER( M, N, ALPHA, XX, INCX, YY, INCY, AA,\n     $                          LDA )\n*\n*                    Check if error-exit was taken incorrectly.\n*\n                     IF( .NOT.OK )THEN\n                        WRITE( NOUT, FMT = 9993 )\n                        FATAL = .TRUE.\n                        GO TO 140\n                     END IF\n*\n*                    See what data changed inside subroutine.\n*\n                     ISAME( 1 ) = MS.EQ.M\n                     ISAME( 2 ) = NS.EQ.N\n                     ISAME( 3 ) = ALS.EQ.ALPHA\n                     ISAME( 4 ) = LDE( XS, XX, LX )\n                     ISAME( 5 ) = INCXS.EQ.INCX\n                     ISAME( 6 ) = LDE( YS, YY, LY )\n                     ISAME( 7 ) = INCYS.EQ.INCY\n                     IF( NULL )THEN\n                        ISAME( 8 ) = LDE( AS, AA, LAA )\n                     ELSE\n                        ISAME( 8 ) = LDERES( 'GE', ' ', M, N, AS, AA,\n     $                               LDA )\n                     END IF\n                     ISAME( 9 ) = LDAS.EQ.LDA\n*\n*                    If data was incorrectly changed, report and return.\n*\n                     SAME = .TRUE.\n                     DO 40 I = 1, NARGS\n                        SAME = SAME.AND.ISAME( I )\n                        IF( .NOT.ISAME( I ) )\n     $                     WRITE( NOUT, FMT = 9998 )I\n   40                CONTINUE\n                     IF( .NOT.SAME )THEN\n                        FATAL = .TRUE.\n                        GO TO 140\n                     END IF\n*\n                     IF( .NOT.NULL )THEN\n*\n*                       Check the result column by column.\n*\n                        IF( INCX.GT.0 )THEN\n                           DO 50 I = 1, M\n                              Z( I ) = X( I )\n   50                      CONTINUE\n                        ELSE\n                           DO 60 I = 1, M\n                              Z( I ) = X( M - I + 1 )\n   60                      CONTINUE\n                        END IF\n                        DO 70 J = 1, N\n                           IF( INCY.GT.0 )THEN\n                              W( 1 ) = Y( J )\n                           ELSE\n                              W( 1 ) = Y( N - J + 1 )\n                           END IF\n                           CALL DMVCH( 'N', M, 1, ALPHA, Z, NMAX, W, 1,\n     $                                 ONE, A( 1, J ), 1, YT, G,\n     $                                 AA( 1 + ( J - 1 )*LDA ), EPS,\n     $                                 ERR, FATAL, NOUT, .TRUE. )\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 130\n   70                   CONTINUE\n                     ELSE\n*                       Avoid repeating tests with M.le.0 or N.le.0.\n                        GO TO 110\n                     END IF\n*\n   80             CONTINUE\n*\n   90          CONTINUE\n*\n  100       CONTINUE\n*\n  110    CONTINUE\n*\n  120 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 150\n*\n  130 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  140 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9994 )NC, SNAME, M, N, ALPHA, INCX, INCY, LDA\n*\n  150 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( I3, ',' ), F4.1, ', X,', I2,\n     $      ', Y,', I2, ', A,', I3, ')                  .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK4.\n*\n      END\n      SUBROUTINE DCHK5( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests DSYR and DSPR.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, HALF, ONE\n      PARAMETER          ( ZERO = 0.0D0, HALF = 0.5D0, ONE = 1.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), G( NMAX ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XX( NMAX*INCMAX ),\n     $                   Y( NMAX ), YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, ALS, ERR, ERRMAX, TRANSL\n      INTEGER            I, IA, IC, IN, INCX, INCXS, IX, J, JA, JJ, LAA,\n     $                   LDA, LDAS, LJ, LX, N, NARGS, NC, NS\n      LOGICAL            FULL, NULL, PACKED, RESET, SAME, UPPER\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      DOUBLE PRECISION   W( 1 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DMAKE, DMVCH, DSPR, DSYR\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'Y'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 7\n      ELSE IF( PACKED )THEN\n         NARGS = 6\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 100 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDA to 1 more than minimum value if room.\n         LDA = N\n         IF( LDA.LT.NMAX )\n     $      LDA = LDA + 1\n*        Skip tests if not enough room.\n         IF( LDA.GT.NMAX )\n     $      GO TO 100\n         IF( PACKED )THEN\n            LAA = ( N*( N + 1 ) )/2\n         ELSE\n            LAA = LDA*N\n         END IF\n*\n         DO 90 IC = 1, 2\n            UPLO = ICH( IC: IC )\n            UPPER = UPLO.EQ.'U'\n*\n            DO 80 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*N\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL DMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX, ABS( INCX ),\n     $                     0, N - 1, RESET, TRANSL )\n               IF( N.GT.1 )THEN\n                  X( N/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 70 IA = 1, NALF\n                  ALPHA = ALF( IA )\n                  NULL = N.LE.0.OR.ALPHA.EQ.ZERO\n*\n*                 Generate the matrix A.\n*\n                  TRANSL = ZERO\n                  CALL DMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A, NMAX,\n     $                        AA, LDA, N - 1, N - 1, RESET, TRANSL )\n*\n                  NC = NC + 1\n*\n*                 Save every datum before calling the subroutine.\n*\n                  UPLOS = UPLO\n                  NS = N\n                  ALS = ALPHA\n                  DO 10 I = 1, LAA\n                     AS( I ) = AA( I )\n   10             CONTINUE\n                  LDAS = LDA\n                  DO 20 I = 1, LX\n                     XS( I ) = XX( I )\n   20             CONTINUE\n                  INCXS = INCX\n*\n*                 Call the subroutine.\n*\n                  IF( FULL )THEN\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO, N,\n     $                  ALPHA, INCX, LDA\n                     IF( REWI )\n     $                  REWIND NTRA\n                     CALL DSYR( UPLO, N, ALPHA, XX, INCX, AA, LDA )\n                  ELSE IF( PACKED )THEN\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO, N,\n     $                  ALPHA, INCX\n                     IF( REWI )\n     $                  REWIND NTRA\n                     CALL DSPR( UPLO, N, ALPHA, XX, INCX, AA )\n                  END IF\n*\n*                 Check if error-exit was taken incorrectly.\n*\n                  IF( .NOT.OK )THEN\n                     WRITE( NOUT, FMT = 9992 )\n                     FATAL = .TRUE.\n                     GO TO 120\n                  END IF\n*\n*                 See what data changed inside subroutines.\n*\n                  ISAME( 1 ) = UPLO.EQ.UPLOS\n                  ISAME( 2 ) = NS.EQ.N\n                  ISAME( 3 ) = ALS.EQ.ALPHA\n                  ISAME( 4 ) = LDE( XS, XX, LX )\n                  ISAME( 5 ) = INCXS.EQ.INCX\n                  IF( NULL )THEN\n                     ISAME( 6 ) = LDE( AS, AA, LAA )\n                  ELSE\n                     ISAME( 6 ) = LDERES( SNAME( 2: 3 ), UPLO, N, N, AS,\n     $                            AA, LDA )\n                  END IF\n                  IF( .NOT.PACKED )THEN\n                     ISAME( 7 ) = LDAS.EQ.LDA\n                  END IF\n*\n*                 If data was incorrectly changed, report and return.\n*\n                  SAME = .TRUE.\n                  DO 30 I = 1, NARGS\n                     SAME = SAME.AND.ISAME( I )\n                     IF( .NOT.ISAME( I ) )\n     $                  WRITE( NOUT, FMT = 9998 )I\n   30             CONTINUE\n                  IF( .NOT.SAME )THEN\n                     FATAL = .TRUE.\n                     GO TO 120\n                  END IF\n*\n                  IF( .NOT.NULL )THEN\n*\n*                    Check the result column by column.\n*\n                     IF( INCX.GT.0 )THEN\n                        DO 40 I = 1, N\n                           Z( I ) = X( I )\n   40                   CONTINUE\n                     ELSE\n                        DO 50 I = 1, N\n                           Z( I ) = X( N - I + 1 )\n   50                   CONTINUE\n                     END IF\n                     JA = 1\n                     DO 60 J = 1, N\n                        W( 1 ) = Z( J )\n                        IF( UPPER )THEN\n                           JJ = 1\n                           LJ = J\n                        ELSE\n                           JJ = J\n                           LJ = N - J + 1\n                        END IF\n                        CALL DMVCH( 'N', LJ, 1, ALPHA, Z( JJ ), LJ, W,\n     $                              1, ONE, A( JJ, J ), 1, YT, G,\n     $                              AA( JA ), EPS, ERR, FATAL, NOUT,\n     $                              .TRUE. )\n                        IF( FULL )THEN\n                           IF( UPPER )THEN\n                              JA = JA + LDA\n                           ELSE\n                              JA = JA + LDA + 1\n                           END IF\n                        ELSE\n                           JA = JA + LJ\n                        END IF\n                        ERRMAX = MAX( ERRMAX, ERR )\n*                       If got really bad answer, report and return.\n                        IF( FATAL )\n     $                     GO TO 110\n   60                CONTINUE\n                  ELSE\n*                    Avoid repeating tests if N.le.0.\n                     IF( N.LE.0 )\n     $                  GO TO 100\n                  END IF\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  110 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, ALPHA, INCX, LDA\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, ALPHA, INCX\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', AP)                           .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', A,', I3, ')                        .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK5.\n*\n      END\n      SUBROUTINE DCHK6( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests DSYR2 and DSPR2.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, HALF, ONE\n      PARAMETER          ( ZERO = 0.0D0, HALF = 0.5D0, ONE = 1.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), G( NMAX ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XX( NMAX*INCMAX ),\n     $                   Y( NMAX ), YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX, 2 )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, ALS, ERR, ERRMAX, TRANSL\n      INTEGER            I, IA, IC, IN, INCX, INCXS, INCY, INCYS, IX,\n     $                   IY, J, JA, JJ, LAA, LDA, LDAS, LJ, LX, LY, N,\n     $                   NARGS, NC, NS\n      LOGICAL            FULL, NULL, PACKED, RESET, SAME, UPPER\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      DOUBLE PRECISION   W( 2 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DMAKE, DMVCH, DSPR2, DSYR2\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'Y'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 9\n      ELSE IF( PACKED )THEN\n         NARGS = 8\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 140 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDA to 1 more than minimum value if room.\n         LDA = N\n         IF( LDA.LT.NMAX )\n     $      LDA = LDA + 1\n*        Skip tests if not enough room.\n         IF( LDA.GT.NMAX )\n     $      GO TO 140\n         IF( PACKED )THEN\n            LAA = ( N*( N + 1 ) )/2\n         ELSE\n            LAA = LDA*N\n         END IF\n*\n         DO 130 IC = 1, 2\n            UPLO = ICH( IC: IC )\n            UPPER = UPLO.EQ.'U'\n*\n            DO 120 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*N\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL DMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX, ABS( INCX ),\n     $                     0, N - 1, RESET, TRANSL )\n               IF( N.GT.1 )THEN\n                  X( N/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 110 IY = 1, NINC\n                  INCY = INC( IY )\n                  LY = ABS( INCY )*N\n*\n*                 Generate the vector Y.\n*\n                  TRANSL = ZERO\n                  CALL DMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                        ABS( INCY ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     Y( N/2 ) = ZERO\n                     YY( 1 + ABS( INCY )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 100 IA = 1, NALF\n                     ALPHA = ALF( IA )\n                     NULL = N.LE.0.OR.ALPHA.EQ.ZERO\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL DMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A,\n     $                           NMAX, AA, LDA, N - 1, N - 1, RESET,\n     $                           TRANSL )\n*\n                     NC = NC + 1\n*\n*                    Save every datum before calling the subroutine.\n*\n                     UPLOS = UPLO\n                     NS = N\n                     ALS = ALPHA\n                     DO 10 I = 1, LAA\n                        AS( I ) = AA( I )\n   10                CONTINUE\n                     LDAS = LDA\n                     DO 20 I = 1, LX\n                        XS( I ) = XX( I )\n   20                CONTINUE\n                     INCXS = INCX\n                     DO 30 I = 1, LY\n                        YS( I ) = YY( I )\n   30                CONTINUE\n                     INCYS = INCY\n*\n*                    Call the subroutine.\n*\n                     IF( FULL )THEN\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO, N,\n     $                     ALPHA, INCX, INCY, LDA\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL DSYR2( UPLO, N, ALPHA, XX, INCX, YY, INCY,\n     $                              AA, LDA )\n                     ELSE IF( PACKED )THEN\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO, N,\n     $                     ALPHA, INCX, INCY\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL DSPR2( UPLO, N, ALPHA, XX, INCX, YY, INCY,\n     $                              AA )\n                     END IF\n*\n*                    Check if error-exit was taken incorrectly.\n*\n                     IF( .NOT.OK )THEN\n                        WRITE( NOUT, FMT = 9992 )\n                        FATAL = .TRUE.\n                        GO TO 160\n                     END IF\n*\n*                    See what data changed inside subroutines.\n*\n                     ISAME( 1 ) = UPLO.EQ.UPLOS\n                     ISAME( 2 ) = NS.EQ.N\n                     ISAME( 3 ) = ALS.EQ.ALPHA\n                     ISAME( 4 ) = LDE( XS, XX, LX )\n                     ISAME( 5 ) = INCXS.EQ.INCX\n                     ISAME( 6 ) = LDE( YS, YY, LY )\n                     ISAME( 7 ) = INCYS.EQ.INCY\n                     IF( NULL )THEN\n                        ISAME( 8 ) = LDE( AS, AA, LAA )\n                     ELSE\n                        ISAME( 8 ) = LDERES( SNAME( 2: 3 ), UPLO, N, N,\n     $                               AS, AA, LDA )\n                     END IF\n                     IF( .NOT.PACKED )THEN\n                        ISAME( 9 ) = LDAS.EQ.LDA\n                     END IF\n*\n*                    If data was incorrectly changed, report and return.\n*\n                     SAME = .TRUE.\n                     DO 40 I = 1, NARGS\n                        SAME = SAME.AND.ISAME( I )\n                        IF( .NOT.ISAME( I ) )\n     $                     WRITE( NOUT, FMT = 9998 )I\n   40                CONTINUE\n                     IF( .NOT.SAME )THEN\n                        FATAL = .TRUE.\n                        GO TO 160\n                     END IF\n*\n                     IF( .NOT.NULL )THEN\n*\n*                       Check the result column by column.\n*\n                        IF( INCX.GT.0 )THEN\n                           DO 50 I = 1, N\n                              Z( I, 1 ) = X( I )\n   50                      CONTINUE\n                        ELSE\n                           DO 60 I = 1, N\n                              Z( I, 1 ) = X( N - I + 1 )\n   60                      CONTINUE\n                        END IF\n                        IF( INCY.GT.0 )THEN\n                           DO 70 I = 1, N\n                              Z( I, 2 ) = Y( I )\n   70                      CONTINUE\n                        ELSE\n                           DO 80 I = 1, N\n                              Z( I, 2 ) = Y( N - I + 1 )\n   80                      CONTINUE\n                        END IF\n                        JA = 1\n                        DO 90 J = 1, N\n                           W( 1 ) = Z( J, 2 )\n                           W( 2 ) = Z( J, 1 )\n                           IF( UPPER )THEN\n                              JJ = 1\n                              LJ = J\n                           ELSE\n                              JJ = J\n                              LJ = N - J + 1\n                           END IF\n                           CALL DMVCH( 'N', LJ, 2, ALPHA, Z( JJ, 1 ),\n     $                                 NMAX, W, 1, ONE, A( JJ, J ), 1,\n     $                                 YT, G, AA( JA ), EPS, ERR, FATAL,\n     $                                 NOUT, .TRUE. )\n                           IF( FULL )THEN\n                              IF( UPPER )THEN\n                                 JA = JA + LDA\n                              ELSE\n                                 JA = JA + LDA + 1\n                              END IF\n                           ELSE\n                              JA = JA + LJ\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 150\n   90                   CONTINUE\n                     ELSE\n*                       Avoid repeating tests with N.le.0.\n                        IF( N.LE.0 )\n     $                     GO TO 140\n                     END IF\n*\n  100             CONTINUE\n*\n  110          CONTINUE\n*\n  120       CONTINUE\n*\n  130    CONTINUE\n*\n  140 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 170\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  160 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, ALPHA, INCX,\n     $      INCY, LDA\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, ALPHA, INCX, INCY\n      END IF\n*\n  170 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', Y,', I2, ', AP)                     .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', Y,', I2, ', A,', I3, ')                  .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK6.\n*\n      END\n      SUBROUTINE DCHKE( ISNUM, SRNAMT, NOUT )\n*\n*  Tests the error exits from the Level 2 Blas.\n*  Requires a special version of the error-handling routine XERBLA.\n*  ALPHA, BETA, A, X and Y should not need to be defined.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            ISNUM, NOUT\n      CHARACTER*6        SRNAMT\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, BETA\n*     .. Local Arrays ..\n      DOUBLE PRECISION   A( 1, 1 ), X( 1 ), Y( 1 )\n*     .. External Subroutines ..\n      EXTERNAL           CHKXER, DGBMV, DGEMV, DGER, DSBMV, DSPMV, DSPR,\n     $                   DSPR2, DSYMV, DSYR, DSYR2, DTBMV, DTBSV, DTPMV,\n     $                   DTPSV, DTRMV, DTRSV\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n*     OK is set to .FALSE. by the special version of XERBLA or by CHKXER\n*     if anything is wrong.\n      OK = .TRUE.\n*     LERR is set to .TRUE. by the special version of XERBLA each time\n*     it is called, and is then tested and re-set by CHKXER.\n      LERR = .FALSE.\n      GO TO ( 10, 20, 30, 40, 50, 60, 70, 80,\n     $        90, 100, 110, 120, 130, 140, 150,\n     $        160 )ISNUM\n   10 INFOT = 1\n      CALL DGEMV( '/', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DGEMV( 'N', -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DGEMV( 'N', 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DGEMV( 'N', 2, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL DGEMV( 'N', 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DGEMV( 'N', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   20 INFOT = 1\n      CALL DGBMV( '/', 0, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DGBMV( 'N', -1, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DGBMV( 'N', 0, -1, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DGBMV( 'N', 0, 0, -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DGBMV( 'N', 2, 0, 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL DGBMV( 'N', 0, 0, 1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL DGBMV( 'N', 0, 0, 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL DGBMV( 'N', 0, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   30 INFOT = 1\n      CALL DSYMV( '/', 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DSYMV( 'U', -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DSYMV( 'U', 2, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYMV( 'U', 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL DSYMV( 'U', 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   40 INFOT = 1\n      CALL DSBMV( '/', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DSBMV( 'U', -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSBMV( 'U', 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DSBMV( 'U', 0, 1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL DSBMV( 'U', 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DSBMV( 'U', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   50 INFOT = 1\n      CALL DSPMV( '/', 0, ALPHA, A, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DSPMV( 'U', -1, ALPHA, A, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DSPMV( 'U', 0, ALPHA, A, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DSPMV( 'U', 0, ALPHA, A, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   60 INFOT = 1\n      CALL DTRMV( '/', 'N', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DTRMV( 'U', '/', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DTRMV( 'U', 'N', '/', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DTRMV( 'U', 'N', 'N', -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRMV( 'U', 'N', 'N', 2, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL DTRMV( 'U', 'N', 'N', 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   70 INFOT = 1\n      CALL DTBMV( '/', 'N', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DTBMV( 'U', '/', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DTBMV( 'U', 'N', '/', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DTBMV( 'U', 'N', 'N', -1, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTBMV( 'U', 'N', 'N', 0, -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DTBMV( 'U', 'N', 'N', 0, 1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTBMV( 'U', 'N', 'N', 0, 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   80 INFOT = 1\n      CALL DTPMV( '/', 'N', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DTPMV( 'U', '/', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DTPMV( 'U', 'N', '/', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DTPMV( 'U', 'N', 'N', -1, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DTPMV( 'U', 'N', 'N', 0, A, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   90 INFOT = 1\n      CALL DTRSV( '/', 'N', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DTRSV( 'U', '/', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DTRSV( 'U', 'N', '/', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DTRSV( 'U', 'N', 'N', -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRSV( 'U', 'N', 'N', 2, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL DTRSV( 'U', 'N', 'N', 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  100 INFOT = 1\n      CALL DTBSV( '/', 'N', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DTBSV( 'U', '/', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DTBSV( 'U', 'N', '/', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DTBSV( 'U', 'N', 'N', -1, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTBSV( 'U', 'N', 'N', 0, -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DTBSV( 'U', 'N', 'N', 0, 1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTBSV( 'U', 'N', 'N', 0, 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  110 INFOT = 1\n      CALL DTPSV( '/', 'N', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DTPSV( 'U', '/', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DTPSV( 'U', 'N', '/', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DTPSV( 'U', 'N', 'N', -1, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DTPSV( 'U', 'N', 'N', 0, A, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  120 INFOT = 1\n      CALL DGER( -1, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DGER( 0, -1, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DGER( 0, 0, ALPHA, X, 0, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DGER( 0, 0, ALPHA, X, 1, Y, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DGER( 2, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  130 INFOT = 1\n      CALL DSYR( '/', 0, ALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DSYR( 'U', -1, ALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DSYR( 'U', 0, ALPHA, X, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYR( 'U', 2, ALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  140 INFOT = 1\n      CALL DSPR( '/', 0, ALPHA, X, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DSPR( 'U', -1, ALPHA, X, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DSPR( 'U', 0, ALPHA, X, 0, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  150 INFOT = 1\n      CALL DSYR2( '/', 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DSYR2( 'U', -1, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DSYR2( 'U', 0, ALPHA, X, 0, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYR2( 'U', 0, ALPHA, X, 1, Y, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DSYR2( 'U', 2, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  160 INFOT = 1\n      CALL DSPR2( '/', 0, ALPHA, X, 1, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DSPR2( 'U', -1, ALPHA, X, 1, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DSPR2( 'U', 0, ALPHA, X, 0, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSPR2( 'U', 0, ALPHA, X, 1, Y, 0, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n  170 IF( OK )THEN\n         WRITE( NOUT, FMT = 9999 )SRNAMT\n      ELSE\n         WRITE( NOUT, FMT = 9998 )SRNAMT\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE TESTS OF ERROR-EXITS' )\n 9998 FORMAT( ' ******* ', A6, ' FAILED THE TESTS OF ERROR-EXITS *****',\n     $      '**' )\n*\n*     End of DCHKE.\n*\n      END\n      SUBROUTINE DMAKE( TYPE, UPLO, DIAG, M, N, A, NMAX, AA, LDA, KL,\n     $                  KU, RESET, TRANSL )\n*\n*  Generates values for an M by N matrix A within the bandwidth\n*  defined by KL and KU.\n*  Stores the values in the array AA in the data structure required\n*  by the routine, with unwanted elements set to rogue value.\n*\n*  TYPE is 'GE', 'GB', 'SY', 'SB', 'SP', 'TR', 'TB' OR 'TP'.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, ONE\n      PARAMETER          ( ZERO = 0.0D0, ONE = 1.0D0 )\n      DOUBLE PRECISION   ROGUE\n      PARAMETER          ( ROGUE = -1.0D10 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   TRANSL\n      INTEGER            KL, KU, LDA, M, N, NMAX\n      LOGICAL            RESET\n      CHARACTER*1        DIAG, UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, * ), AA( * )\n*     .. Local Scalars ..\n      INTEGER            I, I1, I2, I3, IBEG, IEND, IOFF, J, KK\n      LOGICAL            GEN, LOWER, SYM, TRI, UNIT, UPPER\n*     .. External Functions ..\n      DOUBLE PRECISION   DBEG\n      EXTERNAL           DBEG\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX, MIN\n*     .. Executable Statements ..\n      GEN = TYPE( 1: 1 ).EQ.'G'\n      SYM = TYPE( 1: 1 ).EQ.'S'\n      TRI = TYPE( 1: 1 ).EQ.'T'\n      UPPER = ( SYM.OR.TRI ).AND.UPLO.EQ.'U'\n      LOWER = ( SYM.OR.TRI ).AND.UPLO.EQ.'L'\n      UNIT = TRI.AND.DIAG.EQ.'U'\n*\n*     Generate data in array A.\n*\n      DO 20 J = 1, N\n         DO 10 I = 1, M\n            IF( GEN.OR.( UPPER.AND.I.LE.J ).OR.( LOWER.AND.I.GE.J ) )\n     $          THEN\n               IF( ( I.LE.J.AND.J - I.LE.KU ).OR.\n     $             ( I.GE.J.AND.I - J.LE.KL ) )THEN\n                  A( I, J ) = DBEG( RESET ) + TRANSL\n               ELSE\n                  A( I, J ) = ZERO\n               END IF\n               IF( I.NE.J )THEN\n                  IF( SYM )THEN\n                     A( J, I ) = A( I, J )\n                  ELSE IF( TRI )THEN\n                     A( J, I ) = ZERO\n                  END IF\n               END IF\n            END IF\n   10    CONTINUE\n         IF( TRI )\n     $      A( J, J ) = A( J, J ) + ONE\n         IF( UNIT )\n     $      A( J, J ) = ONE\n   20 CONTINUE\n*\n*     Store elements in array AS in data structure required by routine.\n*\n      IF( TYPE.EQ.'GE' )THEN\n         DO 50 J = 1, N\n            DO 30 I = 1, M\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   30       CONTINUE\n            DO 40 I = M + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   40       CONTINUE\n   50    CONTINUE\n      ELSE IF( TYPE.EQ.'GB' )THEN\n         DO 90 J = 1, N\n            DO 60 I1 = 1, KU + 1 - J\n               AA( I1 + ( J - 1 )*LDA ) = ROGUE\n   60       CONTINUE\n            DO 70 I2 = I1, MIN( KL + KU + 1, KU + 1 + M - J )\n               AA( I2 + ( J - 1 )*LDA ) = A( I2 + J - KU - 1, J )\n   70       CONTINUE\n            DO 80 I3 = I2, LDA\n               AA( I3 + ( J - 1 )*LDA ) = ROGUE\n   80       CONTINUE\n   90    CONTINUE\n      ELSE IF( TYPE.EQ.'SY'.OR.TYPE.EQ.'TR' )THEN\n         DO 130 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IF( UNIT )THEN\n                  IEND = J - 1\n               ELSE\n                  IEND = J\n               END IF\n            ELSE\n               IF( UNIT )THEN\n                  IBEG = J + 1\n               ELSE\n                  IBEG = J\n               END IF\n               IEND = N\n            END IF\n            DO 100 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  100       CONTINUE\n            DO 110 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n  110       CONTINUE\n            DO 120 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  120       CONTINUE\n  130    CONTINUE\n      ELSE IF( TYPE.EQ.'SB'.OR.TYPE.EQ.'TB' )THEN\n         DO 170 J = 1, N\n            IF( UPPER )THEN\n               KK = KL + 1\n               IBEG = MAX( 1, KL + 2 - J )\n               IF( UNIT )THEN\n                  IEND = KL\n               ELSE\n                  IEND = KL + 1\n               END IF\n            ELSE\n               KK = 1\n               IF( UNIT )THEN\n                  IBEG = 2\n               ELSE\n                  IBEG = 1\n               END IF\n               IEND = MIN( KL + 1, 1 + M - J )\n            END IF\n            DO 140 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  140       CONTINUE\n            DO 150 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I + J - KK, J )\n  150       CONTINUE\n            DO 160 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  160       CONTINUE\n  170    CONTINUE\n      ELSE IF( TYPE.EQ.'SP'.OR.TYPE.EQ.'TP' )THEN\n         IOFF = 0\n         DO 190 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 180 I = IBEG, IEND\n               IOFF = IOFF + 1\n               AA( IOFF ) = A( I, J )\n               IF( I.EQ.J )THEN\n                  IF( UNIT )\n     $               AA( IOFF ) = ROGUE\n               END IF\n  180       CONTINUE\n  190    CONTINUE\n      END IF\n      RETURN\n*\n*     End of DMAKE.\n*\n      END\n      SUBROUTINE DMVCH( TRANS, M, N, ALPHA, A, NMAX, X, INCX, BETA, Y,\n     $                  INCY, YT, G, YY, EPS, ERR, FATAL, NOUT, MV )\n*\n*  Checks the results of the computational tests.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, ONE\n      PARAMETER          ( ZERO = 0.0D0, ONE = 1.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   ALPHA, BETA, EPS, ERR\n      INTEGER            INCX, INCY, M, N, NMAX, NOUT\n      LOGICAL            FATAL, MV\n      CHARACTER*1        TRANS\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, * ), G( * ), X( * ), Y( * ), YT( * ),\n     $                   YY( * )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ERRI\n      INTEGER            I, INCXL, INCYL, IY, J, JX, KX, KY, ML, NL\n      LOGICAL            TRAN\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, SQRT\n*     .. Executable Statements ..\n      TRAN = TRANS.EQ.'T'.OR.TRANS.EQ.'C'\n      IF( TRAN )THEN\n         ML = N\n         NL = M\n      ELSE\n         ML = M\n         NL = N\n      END IF\n      IF( INCX.LT.0 )THEN\n         KX = NL\n         INCXL = -1\n      ELSE\n         KX = 1\n         INCXL = 1\n      END IF\n      IF( INCY.LT.0 )THEN\n         KY = ML\n         INCYL = -1\n      ELSE\n         KY = 1\n         INCYL = 1\n      END IF\n*\n*     Compute expected result in YT using data in A, X and Y.\n*     Compute gauges in G.\n*\n      IY = KY\n      DO 30 I = 1, ML\n         YT( IY ) = ZERO\n         G( IY ) = ZERO\n         JX = KX\n         IF( TRAN )THEN\n            DO 10 J = 1, NL\n               YT( IY ) = YT( IY ) + A( J, I )*X( JX )\n               G( IY ) = G( IY ) + ABS( A( J, I )*X( JX ) )\n               JX = JX + INCXL\n   10       CONTINUE\n         ELSE\n            DO 20 J = 1, NL\n               YT( IY ) = YT( IY ) + A( I, J )*X( JX )\n               G( IY ) = G( IY ) + ABS( A( I, J )*X( JX ) )\n               JX = JX + INCXL\n   20       CONTINUE\n         END IF\n         YT( IY ) = ALPHA*YT( IY ) + BETA*Y( IY )\n         G( IY ) = ABS( ALPHA )*G( IY ) + ABS( BETA*Y( IY ) )\n         IY = IY + INCYL\n   30 CONTINUE\n*\n*     Compute the error ratio for this result.\n*\n      ERR = ZERO\n      DO 40 I = 1, ML\n         ERRI = ABS( YT( I ) - YY( 1 + ( I - 1 )*ABS( INCY ) ) )/EPS\n         IF( G( I ).NE.ZERO )\n     $      ERRI = ERRI/G( I )\n         ERR = MAX( ERR, ERRI )\n         IF( ERR*SQRT( EPS ).GE.ONE )\n     $      GO TO 50\n   40 CONTINUE\n*     If the loop completes, all results are at least half accurate.\n      GO TO 70\n*\n*     Report fatal error.\n*\n   50 FATAL = .TRUE.\n      WRITE( NOUT, FMT = 9999 )\n      DO 60 I = 1, ML\n         IF( MV )THEN\n            WRITE( NOUT, FMT = 9998 )I, YT( I ),\n     $         YY( 1 + ( I - 1 )*ABS( INCY ) )\n         ELSE\n            WRITE( NOUT, FMT = 9998 )I,\n     $         YY( 1 + ( I - 1 )*ABS( INCY ) ), YT( I )\n         END IF\n   60 CONTINUE\n*\n   70 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ******* FATAL ERROR - COMPUTED RESULT IS LESS THAN HAL',\n     $      'F ACCURATE *******', /'           EXPECTED RESULT   COMPU',\n     $      'TED RESULT' )\n 9998 FORMAT( 1X, I7, 2G18.6 )\n*\n*     End of DMVCH.\n*\n      END\n      LOGICAL FUNCTION LDE( RI, RJ, LR )\n*\n*  Tests if two arrays are identical.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LR\n*     .. Array Arguments ..\n      DOUBLE PRECISION   RI( * ), RJ( * )\n*     .. Local Scalars ..\n      INTEGER            I\n*     .. Executable Statements ..\n      DO 10 I = 1, LR\n         IF( RI( I ).NE.RJ( I ) )\n     $      GO TO 20\n   10 CONTINUE\n      LDE = .TRUE.\n      GO TO 30\n   20 CONTINUE\n      LDE = .FALSE.\n   30 RETURN\n*\n*     End of LDE.\n*\n      END\n      LOGICAL FUNCTION LDERES( TYPE, UPLO, M, N, AA, AS, LDA )\n*\n*  Tests if selected elements in two arrays are equal.\n*\n*  TYPE is 'GE', 'SY' or 'SP'.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LDA, M, N\n      CHARACTER*1        UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      DOUBLE PRECISION   AA( LDA, * ), AS( LDA, * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J\n      LOGICAL            UPPER\n*     .. Executable Statements ..\n      UPPER = UPLO.EQ.'U'\n      IF( TYPE.EQ.'GE' )THEN\n         DO 20 J = 1, N\n            DO 10 I = M + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   10       CONTINUE\n   20    CONTINUE\n      ELSE IF( TYPE.EQ.'SY' )THEN\n         DO 50 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 30 I = 1, IBEG - 1\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   30       CONTINUE\n            DO 40 I = IEND + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   40       CONTINUE\n   50    CONTINUE\n      END IF\n*\n      LDERES = .TRUE.\n      GO TO 80\n   70 CONTINUE\n      LDERES = .FALSE.\n   80 RETURN\n*\n*     End of LDERES.\n*\n      END\n      DOUBLE PRECISION FUNCTION DBEG( RESET )\n*\n*  Generates random numbers uniformly distributed between -0.5 and 0.5.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      LOGICAL            RESET\n*     .. Local Scalars ..\n      INTEGER            I, IC, MI\n*     .. Save statement ..\n      SAVE               I, IC, MI\n*     .. Intrinsic Functions ..\n      INTRINSIC          DBLE\n*     .. Executable Statements ..\n      IF( RESET )THEN\n*        Initialize local variables.\n         MI = 891\n         I = 7\n         IC = 0\n         RESET = .FALSE.\n      END IF\n*\n*     The sequence of values of I is bounded between 1 and 999.\n*     If initial I = 1,2,3,6,7 or 9, the period will be 50.\n*     If initial I = 4 or 8, the period will be 25.\n*     If initial I = 5, the period will be 10.\n*     IC is used to break up the period by skipping 1 value of I in 6.\n*\n      IC = IC + 1\n   10 I = I*MI\n      I = I - 1000*( I/1000 )\n      IF( IC.GE.5 )THEN\n         IC = 0\n         GO TO 10\n      END IF\n      DBEG = DBLE( I - 500 )/1001.0D0\n      RETURN\n*\n*     End of DBEG.\n*\n      END\n      DOUBLE PRECISION FUNCTION DDIFF( X, Y )\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   X, Y\n*     .. Executable Statements ..\n      DDIFF = X - Y\n      RETURN\n*\n*     End of DDIFF.\n*\n      END\n      SUBROUTINE CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n*  Tests whether XERBLA has detected an error when it should.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Executable Statements ..\n      IF( .NOT.LERR )THEN\n         WRITE( NOUT, FMT = 9999 )INFOT, SRNAMT\n         OK = .FALSE.\n      END IF\n      LERR = .FALSE.\n      RETURN\n*\n 9999 FORMAT( ' ***** ILLEGAL VALUE OF PARAMETER NUMBER ', I2, ' NOT D',\n     $      'ETECTED BY ', A6, ' *****' )\n*\n*     End of CHKXER.\n*\n      END\n      SUBROUTINE XERBLA( SRNAME, INFO )\n*\n*  This is a special version of XERBLA to be used only as part of\n*  the test program for testing error exits from the Level 2 BLAS\n*  routines.\n*\n*  XERBLA  is an error handler for the Level 2 BLAS routines.\n*\n*  It is called by the Level 2 BLAS routines if an input parameter is\n*  invalid.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFO\n      CHARACTER*6        SRNAME\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUT, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Executable Statements ..\n      LERR = .TRUE.\n      IF( INFO.NE.INFOT )THEN\n         IF( INFOT.NE.0 )THEN\n            WRITE( NOUT, FMT = 9999 )INFO, INFOT\n         ELSE\n            WRITE( NOUT, FMT = 9997 )INFO\n         END IF\n         OK = .FALSE.\n      END IF\n      IF( SRNAME.NE.SRNAMT )THEN\n         WRITE( NOUT, FMT = 9998 )SRNAME, SRNAMT\n         OK = .FALSE.\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6, ' INSTEAD',\n     $      ' OF ', I2, ' *******' )\n 9998 FORMAT( ' ******* XERBLA WAS CALLED WITH SRNAME = ', A6, ' INSTE',\n     $      'AD OF ', A6, ' *******' )\n 9997 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6,\n     $      ' *******' )\n*\n*     End of XERBLA\n*\n      END\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/testing/dblat3.f",
    "content": "*> \\brief \\b DBLAT3\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM DBLAT3\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> Test program for the DOUBLE PRECISION Level 3 Blas.\n*>\n*> The program must be driven by a short data file. The first 14 records\n*> of the file are read using list-directed input, the last 6 records\n*> are read using the format ( A6, L2 ). An annotated example of a data\n*> file can be obtained by deleting the first 3 characters from the\n*> following 20 lines:\n*> 'dblat3.out'      NAME OF SUMMARY OUTPUT FILE\n*> 6                 UNIT NUMBER OF SUMMARY FILE\n*> 'DBLAT3.SNAP'     NAME OF SNAPSHOT OUTPUT FILE\n*> -1                UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0)\n*> F        LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD.\n*> F        LOGICAL FLAG, T TO STOP ON FAILURES.\n*> T        LOGICAL FLAG, T TO TEST ERROR EXITS.\n*> 16.0     THRESHOLD VALUE OF TEST RATIO\n*> 6                 NUMBER OF VALUES OF N\n*> 0 1 2 3 5 9       VALUES OF N\n*> 3                 NUMBER OF VALUES OF ALPHA\n*> 0.0 1.0 0.7       VALUES OF ALPHA\n*> 3                 NUMBER OF VALUES OF BETA\n*> 0.0 1.0 1.3       VALUES OF BETA\n*> DGEMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DSYMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DTRMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DTRSM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DSYRK  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DSYR2K T PUT F FOR NO TEST. SAME COLUMNS.\n*>\n*> Further Details\n*> ===============\n*>\n*> See:\n*>\n*>    Dongarra J. J., Du Croz J. J., Duff I. S. and Hammarling S.\n*>    A Set of Level 3 Basic Linear Algebra Subprograms.\n*>\n*>    Technical Memorandum No.88 (Revision 1), Mathematics and\n*>    Computer Science Division, Argonne National Laboratory, 9700\n*>    South Cass Avenue, Argonne, Illinois 60439, US.\n*>\n*> -- Written on 8-February-1989.\n*>    Jack Dongarra, Argonne National Laboratory.\n*>    Iain Duff, AERE Harwell.\n*>    Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*>    Sven Hammarling, Numerical Algorithms Group Ltd.\n*>\n*>    10-9-00:  Change STATUS='NEW' to 'UNKNOWN' so that the testers\n*>              can be run multiple times without deleting generated\n*>              output files (susan)\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup double_blas_testing\n*\n*  =====================================================================\n      PROGRAM DBLAT3\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER            NIN\n      PARAMETER          ( NIN = 5 )\n      INTEGER            NSUBS\n      PARAMETER          ( NSUBS = 6 )\n      DOUBLE PRECISION   ZERO, ONE\n      PARAMETER          ( ZERO = 0.0D0, ONE = 1.0D0 )\n      INTEGER            NMAX\n      PARAMETER          ( NMAX = 65 )\n      INTEGER            NIDMAX, NALMAX, NBEMAX\n      PARAMETER          ( NIDMAX = 9, NALMAX = 7, NBEMAX = 7 )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   EPS, ERR, THRESH\n      INTEGER            I, ISNUM, J, N, NALF, NBET, NIDIM, NOUT, NTRA\n      LOGICAL            FATAL, LTESTT, REWI, SAME, SFATAL, TRACE,\n     $                   TSTERR\n      CHARACTER*1        TRANSA, TRANSB\n      CHARACTER*6        SNAMET\n      CHARACTER*32       SNAPS, SUMMRY\n*     .. Local Arrays ..\n      DOUBLE PRECISION   AA( NMAX*NMAX ), AB( NMAX, 2*NMAX ),\n     $                   ALF( NALMAX ), AS( NMAX*NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBEMAX ),\n     $                   BS( NMAX*NMAX ), C( NMAX, NMAX ),\n     $                   CC( NMAX*NMAX ), CS( NMAX*NMAX ), CT( NMAX ),\n     $                   G( NMAX ), W( 2*NMAX )\n      INTEGER            IDIM( NIDMAX )\n      LOGICAL            LTEST( NSUBS )\n      CHARACTER*6        SNAMES( NSUBS )\n*     .. External Functions ..\n      DOUBLE PRECISION   DDIFF\n      LOGICAL            LDE\n      EXTERNAL           DDIFF, LDE\n*     .. External Subroutines ..\n      EXTERNAL           DCHK1, DCHK2, DCHK3, DCHK4, DCHK5, DCHKE, DMMCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Data statements ..\n      DATA               SNAMES/'DGEMM ', 'DSYMM ', 'DTRMM ', 'DTRSM ',\n     $                   'DSYRK ', 'DSYR2K'/\n*     .. Executable Statements ..\n*\n*     Read name and unit number for summary output file and open file.\n*\n      READ( NIN, FMT = * )SUMMRY\n      READ( NIN, FMT = * )NOUT\n      OPEN( NOUT, FILE = SUMMRY, STATUS = 'UNKNOWN' )\n      NOUTC = NOUT\n*\n*     Read name and unit number for snapshot output file and open file.\n*\n      READ( NIN, FMT = * )SNAPS\n      READ( NIN, FMT = * )NTRA\n      TRACE = NTRA.GE.0\n      IF( TRACE )THEN\n         OPEN( NTRA, FILE = SNAPS, STATUS = 'UNKNOWN' )\n      END IF\n*     Read the flag that directs rewinding of the snapshot file.\n      READ( NIN, FMT = * )REWI\n      REWI = REWI.AND.TRACE\n*     Read the flag that directs stopping on any failure.\n      READ( NIN, FMT = * )SFATAL\n*     Read the flag that indicates whether error exits are to be tested.\n      READ( NIN, FMT = * )TSTERR\n*     Read the threshold value of the test ratio\n      READ( NIN, FMT = * )THRESH\n*\n*     Read and check the parameter values for the tests.\n*\n*     Values of N\n      READ( NIN, FMT = * )NIDIM\n      IF( NIDIM.LT.1.OR.NIDIM.GT.NIDMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'N', NIDMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( IDIM( I ), I = 1, NIDIM )\n      DO 10 I = 1, NIDIM\n         IF( IDIM( I ).LT.0.OR.IDIM( I ).GT.NMAX )THEN\n            WRITE( NOUT, FMT = 9996 )NMAX\n            GO TO 220\n         END IF\n   10 CONTINUE\n*     Values of ALPHA\n      READ( NIN, FMT = * )NALF\n      IF( NALF.LT.1.OR.NALF.GT.NALMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'ALPHA', NALMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( ALF( I ), I = 1, NALF )\n*     Values of BETA\n      READ( NIN, FMT = * )NBET\n      IF( NBET.LT.1.OR.NBET.GT.NBEMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'BETA', NBEMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( BET( I ), I = 1, NBET )\n*\n*     Report values of parameters.\n*\n      WRITE( NOUT, FMT = 9995 )\n      WRITE( NOUT, FMT = 9994 )( IDIM( I ), I = 1, NIDIM )\n      WRITE( NOUT, FMT = 9993 )( ALF( I ), I = 1, NALF )\n      WRITE( NOUT, FMT = 9992 )( BET( I ), I = 1, NBET )\n      IF( .NOT.TSTERR )THEN\n         WRITE( NOUT, FMT = * )\n         WRITE( NOUT, FMT = 9984 )\n      END IF\n      WRITE( NOUT, FMT = * )\n      WRITE( NOUT, FMT = 9999 )THRESH\n      WRITE( NOUT, FMT = * )\n*\n*     Read names of subroutines and flags which indicate\n*     whether they are to be tested.\n*\n      DO 20 I = 1, NSUBS\n         LTEST( I ) = .FALSE.\n   20 CONTINUE\n   30 READ( NIN, FMT = 9988, END = 60 )SNAMET, LTESTT\n      DO 40 I = 1, NSUBS\n         IF( SNAMET.EQ.SNAMES( I ) )\n     $      GO TO 50\n   40 CONTINUE\n      WRITE( NOUT, FMT = 9990 )SNAMET\n      STOP\n   50 LTEST( I ) = LTESTT\n      GO TO 30\n*\n   60 CONTINUE\n      CLOSE ( NIN )\n*\n*     Compute EPS (the machine precision).\n*\n      EPS = EPSILON(ZERO)\n      WRITE( NOUT, FMT = 9998 )EPS\n*\n*     Check the reliability of DMMCH using exact data.\n*\n      N = MIN( 32, NMAX )\n      DO 100 J = 1, N\n         DO 90 I = 1, N\n            AB( I, J ) = MAX( I - J + 1, 0 )\n   90    CONTINUE\n         AB( J, NMAX + 1 ) = J\n         AB( 1, NMAX + J ) = J\n         C( J, 1 ) = ZERO\n  100 CONTINUE\n      DO 110 J = 1, N\n         CC( J ) = J*( ( J + 1 )*J )/2 - ( ( J + 1 )*J*( J - 1 ) )/3\n  110 CONTINUE\n*     CC holds the exact result. On exit from DMMCH CT holds\n*     the result computed by DMMCH.\n      TRANSA = 'N'\n      TRANSB = 'N'\n      CALL DMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LDE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      TRANSB = 'T'\n      CALL DMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LDE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      DO 120 J = 1, N\n         AB( J, NMAX + 1 ) = N - J + 1\n         AB( 1, NMAX + J ) = N - J + 1\n  120 CONTINUE\n      DO 130 J = 1, N\n         CC( N - J + 1 ) = J*( ( J + 1 )*J )/2 -\n     $                     ( ( J + 1 )*J*( J - 1 ) )/3\n  130 CONTINUE\n      TRANSA = 'T'\n      TRANSB = 'N'\n      CALL DMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LDE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      TRANSB = 'T'\n      CALL DMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LDE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n*\n*     Test each subroutine in turn.\n*\n      DO 200 ISNUM = 1, NSUBS\n         WRITE( NOUT, FMT = * )\n         IF( .NOT.LTEST( ISNUM ) )THEN\n*           Subprogram is not to be tested.\n            WRITE( NOUT, FMT = 9987 )SNAMES( ISNUM )\n         ELSE\n            SRNAMT = SNAMES( ISNUM )\n*           Test error exits.\n            IF( TSTERR )THEN\n               CALL DCHKE( ISNUM, SNAMES( ISNUM ), NOUT )\n               WRITE( NOUT, FMT = * )\n            END IF\n*           Test computations.\n            INFOT = 0\n            OK = .TRUE.\n            FATAL = .FALSE.\n            GO TO ( 140, 150, 160, 160, 170, 180 )ISNUM\n*           Test DGEMM, 01.\n  140       CALL DCHK1( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test DSYMM, 02.\n  150       CALL DCHK2( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test DTRMM, 03, DTRSM, 04.\n  160       CALL DCHK3( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NMAX, AB,\n     $                  AA, AS, AB( 1, NMAX + 1 ), BB, BS, CT, G, C )\n            GO TO 190\n*           Test DSYRK, 05.\n  170       CALL DCHK4( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test DSYR2K, 06.\n  180       CALL DCHK5( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, BB, BS, C, CC, CS, CT, G, W )\n            GO TO 190\n*\n  190       IF( FATAL.AND.SFATAL )\n     $         GO TO 210\n         END IF\n  200 CONTINUE\n      WRITE( NOUT, FMT = 9986 )\n      GO TO 230\n*\n  210 CONTINUE\n      WRITE( NOUT, FMT = 9985 )\n      GO TO 230\n*\n  220 CONTINUE\n      WRITE( NOUT, FMT = 9991 )\n*\n  230 CONTINUE\n      IF( TRACE )\n     $   CLOSE ( NTRA )\n      CLOSE ( NOUT )\n      STOP\n*\n 9999 FORMAT( ' ROUTINES PASS COMPUTATIONAL TESTS IF TEST RATIO IS LES',\n     $      'S THAN', F8.2 )\n 9998 FORMAT( ' RELATIVE MACHINE PRECISION IS TAKEN TO BE', 1P, D9.1 )\n 9997 FORMAT( ' NUMBER OF VALUES OF ', A, ' IS LESS THAN 1 OR GREATER ',\n     $      'THAN ', I2 )\n 9996 FORMAT( ' VALUE OF N IS LESS THAN 0 OR GREATER THAN ', I2 )\n 9995 FORMAT( ' TESTS OF THE DOUBLE PRECISION LEVEL 3 BLAS', //' THE F',\n     $      'OLLOWING PARAMETER VALUES WILL BE USED:' )\n 9994 FORMAT( '   FOR N              ', 9I6 )\n 9993 FORMAT( '   FOR ALPHA          ', 7F6.1 )\n 9992 FORMAT( '   FOR BETA           ', 7F6.1 )\n 9991 FORMAT( ' AMEND DATA FILE OR INCREASE ARRAY SIZES IN PROGRAM',\n     $      /' ******* TESTS ABANDONED *******' )\n 9990 FORMAT( ' SUBPROGRAM NAME ', A6, ' NOT RECOGNIZED', /' ******* T',\n     $      'ESTS ABANDONED *******' )\n 9989 FORMAT( ' ERROR IN DMMCH -  IN-LINE DOT PRODUCTS ARE BEING EVALU',\n     $      'ATED WRONGLY.', /' DMMCH WAS CALLED WITH TRANSA = ', A1,\n     $      ' AND TRANSB = ', A1, /' AND RETURNED SAME = ', L1, ' AND ',\n     $      'ERR = ', F12.3, '.', /' THIS MAY BE DUE TO FAULTS IN THE ',\n     $      'ARITHMETIC OR THE COMPILER.', /' ******* TESTS ABANDONED ',\n     $      '*******' )\n 9988 FORMAT( A6, L2 )\n 9987 FORMAT( 1X, A6, ' WAS NOT TESTED' )\n 9986 FORMAT( /' END OF TESTS' )\n 9985 FORMAT( /' ******* FATAL ERROR - TESTS ABANDONED *******' )\n 9984 FORMAT( ' ERROR-EXITS WILL NOT BE TESTED' )\n*\n*     End of DBLAT3.\n*\n      END\n      SUBROUTINE DCHK1( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests DGEMM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO\n      PARAMETER          ( ZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX ), G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, ALS, BETA, BLS, ERR, ERRMAX\n      INTEGER            I, IA, IB, ICA, ICB, IK, IM, IN, K, KS, LAA,\n     $                   LBB, LCC, LDA, LDAS, LDB, LDBS, LDC, LDCS, M,\n     $                   MA, MB, MS, N, NA, NARGS, NB, NC, NS\n      LOGICAL            NULL, RESET, SAME, TRANA, TRANB\n      CHARACTER*1        TRANAS, TRANBS, TRANSA, TRANSB\n      CHARACTER*3        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DGEMM, DMAKE, DMMCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'NTC'/\n*     .. Executable Statements ..\n*\n      NARGS = 13\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 110 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 100 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDC to 1 more than minimum value if room.\n            LDC = M\n            IF( LDC.LT.NMAX )\n     $         LDC = LDC + 1\n*           Skip tests if not enough room.\n            IF( LDC.GT.NMAX )\n     $         GO TO 100\n            LCC = LDC*N\n            NULL = N.LE.0.OR.M.LE.0\n*\n            DO 90 IK = 1, NIDIM\n               K = IDIM( IK )\n*\n               DO 80 ICA = 1, 3\n                  TRANSA = ICH( ICA: ICA )\n                  TRANA = TRANSA.EQ.'T'.OR.TRANSA.EQ.'C'\n*\n                  IF( TRANA )THEN\n                     MA = K\n                     NA = M\n                  ELSE\n                     MA = M\n                     NA = K\n                  END IF\n*                 Set LDA to 1 more than minimum value if room.\n                  LDA = MA\n                  IF( LDA.LT.NMAX )\n     $               LDA = LDA + 1\n*                 Skip tests if not enough room.\n                  IF( LDA.GT.NMAX )\n     $               GO TO 80\n                  LAA = LDA*NA\n*\n*                 Generate the matrix A.\n*\n                  CALL DMAKE( 'GE', ' ', ' ', MA, NA, A, NMAX, AA, LDA,\n     $                        RESET, ZERO )\n*\n                  DO 70 ICB = 1, 3\n                     TRANSB = ICH( ICB: ICB )\n                     TRANB = TRANSB.EQ.'T'.OR.TRANSB.EQ.'C'\n*\n                     IF( TRANB )THEN\n                        MB = N\n                        NB = K\n                     ELSE\n                        MB = K\n                        NB = N\n                     END IF\n*                    Set LDB to 1 more than minimum value if room.\n                     LDB = MB\n                     IF( LDB.LT.NMAX )\n     $                  LDB = LDB + 1\n*                    Skip tests if not enough room.\n                     IF( LDB.GT.NMAX )\n     $                  GO TO 70\n                     LBB = LDB*NB\n*\n*                    Generate the matrix B.\n*\n                     CALL DMAKE( 'GE', ' ', ' ', MB, NB, B, NMAX, BB,\n     $                           LDB, RESET, ZERO )\n*\n                     DO 60 IA = 1, NALF\n                        ALPHA = ALF( IA )\n*\n                        DO 50 IB = 1, NBET\n                           BETA = BET( IB )\n*\n*                          Generate the matrix C.\n*\n                           CALL DMAKE( 'GE', ' ', ' ', M, N, C, NMAX,\n     $                                 CC, LDC, RESET, ZERO )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           TRANAS = TRANSA\n                           TRANBS = TRANSB\n                           MS = M\n                           NS = N\n                           KS = K\n                           ALS = ALPHA\n                           DO 10 I = 1, LAA\n                              AS( I ) = AA( I )\n   10                      CONTINUE\n                           LDAS = LDA\n                           DO 20 I = 1, LBB\n                              BS( I ) = BB( I )\n   20                      CONTINUE\n                           LDBS = LDB\n                           BLS = BETA\n                           DO 30 I = 1, LCC\n                              CS( I ) = CC( I )\n   30                      CONTINUE\n                           LDCS = LDC\n*\n*                          Call the subroutine.\n*\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                        TRANSA, TRANSB, M, N, K, ALPHA, LDA, LDB,\n     $                        BETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL DGEMM( TRANSA, TRANSB, M, N, K, ALPHA,\n     $                                 AA, LDA, BB, LDB, BETA, CC, LDC )\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9994 )\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = TRANSA.EQ.TRANAS\n                           ISAME( 2 ) = TRANSB.EQ.TRANBS\n                           ISAME( 3 ) = MS.EQ.M\n                           ISAME( 4 ) = NS.EQ.N\n                           ISAME( 5 ) = KS.EQ.K\n                           ISAME( 6 ) = ALS.EQ.ALPHA\n                           ISAME( 7 ) = LDE( AS, AA, LAA )\n                           ISAME( 8 ) = LDAS.EQ.LDA\n                           ISAME( 9 ) = LDE( BS, BB, LBB )\n                           ISAME( 10 ) = LDBS.EQ.LDB\n                           ISAME( 11 ) = BLS.EQ.BETA\n                           IF( NULL )THEN\n                              ISAME( 12 ) = LDE( CS, CC, LCC )\n                           ELSE\n                              ISAME( 12 ) = LDERES( 'GE', ' ', M, N, CS,\n     $                                      CC, LDC )\n                           END IF\n                           ISAME( 13 ) = LDCS.EQ.LDC\n*\n*                          If data was incorrectly changed, report\n*                          and return.\n*\n                           SAME = .TRUE.\n                           DO 40 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   40                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n*\n*                             Check the result.\n*\n                              CALL DMMCH( TRANSA, TRANSB, M, N, K,\n     $                                    ALPHA, A, NMAX, B, NMAX, BETA,\n     $                                    C, NMAX, CT, G, CC, LDC, EPS,\n     $                                    ERR, FATAL, NOUT, .TRUE. )\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 120\n                           END IF\n*\n   50                   CONTINUE\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, TRANSA, TRANSB, M, N, K,\n     $   ALPHA, LDA, LDB, BETA, LDC\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',''', A1, ''',',\n     $      3( I3, ',' ), F4.1, ', A,', I3, ', B,', I3, ',', F4.1, ', ',\n     $      'C,', I3, ').' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK1.\n*\n      END\n      SUBROUTINE DCHK2( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests DSYMM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO\n      PARAMETER          ( ZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX ), G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, ALS, BETA, BLS, ERR, ERRMAX\n      INTEGER            I, IA, IB, ICS, ICU, IM, IN, LAA, LBB, LCC,\n     $                   LDA, LDAS, LDB, LDBS, LDC, LDCS, M, MS, N, NA,\n     $                   NARGS, NC, NS\n      LOGICAL            LEFT, NULL, RESET, SAME\n      CHARACTER*1        SIDE, SIDES, UPLO, UPLOS\n      CHARACTER*2        ICHS, ICHU\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DMAKE, DMMCH, DSYMM\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHS/'LR'/, ICHU/'UL'/\n*     .. Executable Statements ..\n*\n      NARGS = 12\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 100 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 90 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDC to 1 more than minimum value if room.\n            LDC = M\n            IF( LDC.LT.NMAX )\n     $         LDC = LDC + 1\n*           Skip tests if not enough room.\n            IF( LDC.GT.NMAX )\n     $         GO TO 90\n            LCC = LDC*N\n            NULL = N.LE.0.OR.M.LE.0\n*\n*           Set LDB to 1 more than minimum value if room.\n            LDB = M\n            IF( LDB.LT.NMAX )\n     $         LDB = LDB + 1\n*           Skip tests if not enough room.\n            IF( LDB.GT.NMAX )\n     $         GO TO 90\n            LBB = LDB*N\n*\n*           Generate the matrix B.\n*\n            CALL DMAKE( 'GE', ' ', ' ', M, N, B, NMAX, BB, LDB, RESET,\n     $                  ZERO )\n*\n            DO 80 ICS = 1, 2\n               SIDE = ICHS( ICS: ICS )\n               LEFT = SIDE.EQ.'L'\n*\n               IF( LEFT )THEN\n                  NA = M\n               ELSE\n                  NA = N\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = NA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 80\n               LAA = LDA*NA\n*\n               DO 70 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n*\n*                 Generate the symmetric matrix A.\n*\n                  CALL DMAKE( 'SY', UPLO, ' ', NA, NA, A, NMAX, AA, LDA,\n     $                        RESET, ZERO )\n*\n                  DO 60 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n                     DO 50 IB = 1, NBET\n                        BETA = BET( IB )\n*\n*                       Generate the matrix C.\n*\n                        CALL DMAKE( 'GE', ' ', ' ', M, N, C, NMAX, CC,\n     $                              LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the\n*                       subroutine.\n*\n                        SIDES = SIDE\n                        UPLOS = UPLO\n                        MS = M\n                        NS = N\n                        ALS = ALPHA\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        DO 20 I = 1, LBB\n                           BS( I ) = BB( I )\n   20                   CONTINUE\n                        LDBS = LDB\n                        BLS = BETA\n                        DO 30 I = 1, LCC\n                           CS( I ) = CC( I )\n   30                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9995 )NC, SNAME, SIDE,\n     $                     UPLO, M, N, ALPHA, LDA, LDB, BETA, LDC\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL DSYMM( SIDE, UPLO, M, N, ALPHA, AA, LDA,\n     $                              BB, LDB, BETA, CC, LDC )\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9994 )\n                           FATAL = .TRUE.\n                           GO TO 110\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = SIDES.EQ.SIDE\n                        ISAME( 2 ) = UPLOS.EQ.UPLO\n                        ISAME( 3 ) = MS.EQ.M\n                        ISAME( 4 ) = NS.EQ.N\n                        ISAME( 5 ) = ALS.EQ.ALPHA\n                        ISAME( 6 ) = LDE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        ISAME( 8 ) = LDE( BS, BB, LBB )\n                        ISAME( 9 ) = LDBS.EQ.LDB\n                        ISAME( 10 ) = BLS.EQ.BETA\n                        IF( NULL )THEN\n                           ISAME( 11 ) = LDE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 11 ) = LDERES( 'GE', ' ', M, N, CS,\n     $                                   CC, LDC )\n                        END IF\n                        ISAME( 12 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 110\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result.\n*\n                           IF( LEFT )THEN\n                              CALL DMMCH( 'N', 'N', M, N, M, ALPHA, A,\n     $                                    NMAX, B, NMAX, BETA, C, NMAX,\n     $                                    CT, G, CC, LDC, EPS, ERR,\n     $                                    FATAL, NOUT, .TRUE. )\n                           ELSE\n                              CALL DMMCH( 'N', 'N', M, N, N, ALPHA, B,\n     $                                    NMAX, A, NMAX, BETA, C, NMAX,\n     $                                    CT, G, CC, LDC, EPS, ERR,\n     $                                    FATAL, NOUT, .TRUE. )\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and\n*                          return.\n                           IF( FATAL )\n     $                        GO TO 110\n                        END IF\n*\n   50                CONTINUE\n*\n   60             CONTINUE\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 120\n*\n  110 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, SIDE, UPLO, M, N, ALPHA, LDA,\n     $   LDB, BETA, LDC\n*\n  120 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      F4.1, ', A,', I3, ', B,', I3, ',', F4.1, ', C,', I3, ')   ',\n     $      ' .' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK2.\n*\n      END\n      SUBROUTINE DCHK3( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NMAX, A, AA, AS,\n     $                  B, BB, BS, CT, G, C )\n*\n*  Tests DTRMM and DTRSM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, ONE\n      PARAMETER          ( ZERO = 0.0D0, ONE = 1.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            NALF, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CT( NMAX ), G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, ALS, ERR, ERRMAX\n      INTEGER            I, IA, ICD, ICS, ICT, ICU, IM, IN, J, LAA, LBB,\n     $                   LDA, LDAS, LDB, LDBS, M, MS, N, NA, NARGS, NC,\n     $                   NS\n      LOGICAL            LEFT, NULL, RESET, SAME\n      CHARACTER*1        DIAG, DIAGS, SIDE, SIDES, TRANAS, TRANSA, UPLO,\n     $                   UPLOS\n      CHARACTER*2        ICHD, ICHS, ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DMAKE, DMMCH, DTRMM, DTRSM\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHU/'UL'/, ICHT/'NTC'/, ICHD/'UN'/, ICHS/'LR'/\n*     .. Executable Statements ..\n*\n      NARGS = 11\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*     Set up zero matrix for DMMCH.\n      DO 20 J = 1, NMAX\n         DO 10 I = 1, NMAX\n            C( I, J ) = ZERO\n   10    CONTINUE\n   20 CONTINUE\n*\n      DO 140 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 130 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDB to 1 more than minimum value if room.\n            LDB = M\n            IF( LDB.LT.NMAX )\n     $         LDB = LDB + 1\n*           Skip tests if not enough room.\n            IF( LDB.GT.NMAX )\n     $         GO TO 130\n            LBB = LDB*N\n            NULL = M.LE.0.OR.N.LE.0\n*\n            DO 120 ICS = 1, 2\n               SIDE = ICHS( ICS: ICS )\n               LEFT = SIDE.EQ.'L'\n               IF( LEFT )THEN\n                  NA = M\n               ELSE\n                  NA = N\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = NA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 130\n               LAA = LDA*NA\n*\n               DO 110 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n*\n                  DO 100 ICT = 1, 3\n                     TRANSA = ICHT( ICT: ICT )\n*\n                     DO 90 ICD = 1, 2\n                        DIAG = ICHD( ICD: ICD )\n*\n                        DO 80 IA = 1, NALF\n                           ALPHA = ALF( IA )\n*\n*                          Generate the matrix A.\n*\n                           CALL DMAKE( 'TR', UPLO, DIAG, NA, NA, A,\n     $                                 NMAX, AA, LDA, RESET, ZERO )\n*\n*                          Generate the matrix B.\n*\n                           CALL DMAKE( 'GE', ' ', ' ', M, N, B, NMAX,\n     $                                 BB, LDB, RESET, ZERO )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           SIDES = SIDE\n                           UPLOS = UPLO\n                           TRANAS = TRANSA\n                           DIAGS = DIAG\n                           MS = M\n                           NS = N\n                           ALS = ALPHA\n                           DO 30 I = 1, LAA\n                              AS( I ) = AA( I )\n   30                      CONTINUE\n                           LDAS = LDA\n                           DO 40 I = 1, LBB\n                              BS( I ) = BB( I )\n   40                      CONTINUE\n                           LDBS = LDB\n*\n*                          Call the subroutine.\n*\n                           IF( SNAME( 4: 5 ).EQ.'MM' )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           SIDE, UPLO, TRANSA, DIAG, M, N, ALPHA,\n     $                           LDA, LDB\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DTRMM( SIDE, UPLO, TRANSA, DIAG, M,\n     $                                    N, ALPHA, AA, LDA, BB, LDB )\n                           ELSE IF( SNAME( 4: 5 ).EQ.'SM' )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           SIDE, UPLO, TRANSA, DIAG, M, N, ALPHA,\n     $                           LDA, LDB\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DTRSM( SIDE, UPLO, TRANSA, DIAG, M,\n     $                                    N, ALPHA, AA, LDA, BB, LDB )\n                           END IF\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9994 )\n                              FATAL = .TRUE.\n                              GO TO 150\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = SIDES.EQ.SIDE\n                           ISAME( 2 ) = UPLOS.EQ.UPLO\n                           ISAME( 3 ) = TRANAS.EQ.TRANSA\n                           ISAME( 4 ) = DIAGS.EQ.DIAG\n                           ISAME( 5 ) = MS.EQ.M\n                           ISAME( 6 ) = NS.EQ.N\n                           ISAME( 7 ) = ALS.EQ.ALPHA\n                           ISAME( 8 ) = LDE( AS, AA, LAA )\n                           ISAME( 9 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 10 ) = LDE( BS, BB, LBB )\n                           ELSE\n                              ISAME( 10 ) = LDERES( 'GE', ' ', M, N, BS,\n     $                                      BB, LDB )\n                           END IF\n                           ISAME( 11 ) = LDBS.EQ.LDB\n*\n*                          If data was incorrectly changed, report and\n*                          return.\n*\n                           SAME = .TRUE.\n                           DO 50 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   50                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 150\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n                              IF( SNAME( 4: 5 ).EQ.'MM' )THEN\n*\n*                                Check the result.\n*\n                                 IF( LEFT )THEN\n                                    CALL DMMCH( TRANSA, 'N', M, N, M,\n     $                                          ALPHA, A, NMAX, B, NMAX,\n     $                                          ZERO, C, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .TRUE. )\n                                 ELSE\n                                    CALL DMMCH( 'N', TRANSA, M, N, N,\n     $                                          ALPHA, B, NMAX, A, NMAX,\n     $                                          ZERO, C, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .TRUE. )\n                                 END IF\n                              ELSE IF( SNAME( 4: 5 ).EQ.'SM' )THEN\n*\n*                                Compute approximation to original\n*                                matrix.\n*\n                                 DO 70 J = 1, N\n                                    DO 60 I = 1, M\n                                       C( I, J ) = BB( I + ( J - 1 )*\n     $                                             LDB )\n                                       BB( I + ( J - 1 )*LDB ) = ALPHA*\n     $                                    B( I, J )\n   60                               CONTINUE\n   70                            CONTINUE\n*\n                                 IF( LEFT )THEN\n                                    CALL DMMCH( TRANSA, 'N', M, N, M,\n     $                                          ONE, A, NMAX, C, NMAX,\n     $                                          ZERO, B, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .FALSE. )\n                                 ELSE\n                                    CALL DMMCH( 'N', TRANSA, M, N, N,\n     $                                          ONE, C, NMAX, A, NMAX,\n     $                                          ZERO, B, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .FALSE. )\n                                 END IF\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 150\n                           END IF\n*\n   80                   CONTINUE\n*\n   90                CONTINUE\n*\n  100             CONTINUE\n*\n  110          CONTINUE\n*\n  120       CONTINUE\n*\n  130    CONTINUE\n*\n  140 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 160\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, SIDE, UPLO, TRANSA, DIAG, M,\n     $   N, ALPHA, LDA, LDB\n*\n  160 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 4( '''', A1, ''',' ), 2( I3, ',' ),\n     $      F4.1, ', A,', I3, ', B,', I3, ')        .' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK3.\n*\n      END\n      SUBROUTINE DCHK4( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests DSYRK.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO\n      PARAMETER          ( ZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX ), G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, ALS, BETA, BETS, ERR, ERRMAX\n      INTEGER            I, IA, IB, ICT, ICU, IK, IN, J, JC, JJ, K, KS,\n     $                   LAA, LCC, LDA, LDAS, LDC, LDCS, LJ, MA, N, NA,\n     $                   NARGS, NC, NS\n      LOGICAL            NULL, RESET, SAME, TRAN, UPPER\n      CHARACTER*1        TRANS, TRANSS, UPLO, UPLOS\n      CHARACTER*2        ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DMAKE, DMMCH, DSYRK\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHT/'NTC'/, ICHU/'UL'/\n*     .. Executable Statements ..\n*\n      NARGS = 10\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 100 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDC to 1 more than minimum value if room.\n         LDC = N\n         IF( LDC.LT.NMAX )\n     $      LDC = LDC + 1\n*        Skip tests if not enough room.\n         IF( LDC.GT.NMAX )\n     $      GO TO 100\n         LCC = LDC*N\n         NULL = N.LE.0\n*\n         DO 90 IK = 1, NIDIM\n            K = IDIM( IK )\n*\n            DO 80 ICT = 1, 3\n               TRANS = ICHT( ICT: ICT )\n               TRAN = TRANS.EQ.'T'.OR.TRANS.EQ.'C'\n               IF( TRAN )THEN\n                  MA = K\n                  NA = N\n               ELSE\n                  MA = N\n                  NA = K\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = MA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 80\n               LAA = LDA*NA\n*\n*              Generate the matrix A.\n*\n               CALL DMAKE( 'GE', ' ', ' ', MA, NA, A, NMAX, AA, LDA,\n     $                     RESET, ZERO )\n*\n               DO 70 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n                  UPPER = UPLO.EQ.'U'\n*\n                  DO 60 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n                     DO 50 IB = 1, NBET\n                        BETA = BET( IB )\n*\n*                       Generate the matrix C.\n*\n                        CALL DMAKE( 'SY', UPLO, ' ', N, N, C, NMAX, CC,\n     $                              LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        NS = N\n                        KS = K\n                        ALS = ALPHA\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        BETS = BETA\n                        DO 20 I = 1, LCC\n                           CS( I ) = CC( I )\n   20                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO,\n     $                     TRANS, N, K, ALPHA, LDA, BETA, LDC\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL DSYRK( UPLO, TRANS, N, K, ALPHA, AA, LDA,\n     $                              BETA, CC, LDC )\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9993 )\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLOS.EQ.UPLO\n                        ISAME( 2 ) = TRANSS.EQ.TRANS\n                        ISAME( 3 ) = NS.EQ.N\n                        ISAME( 4 ) = KS.EQ.K\n                        ISAME( 5 ) = ALS.EQ.ALPHA\n                        ISAME( 6 ) = LDE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        ISAME( 8 ) = BETS.EQ.BETA\n                        IF( NULL )THEN\n                           ISAME( 9 ) = LDE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 9 ) = LDERES( 'SY', UPLO, N, N, CS,\n     $                                  CC, LDC )\n                        END IF\n                        ISAME( 10 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 30 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   30                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result column by column.\n*\n                           JC = 1\n                           DO 40 J = 1, N\n                              IF( UPPER )THEN\n                                 JJ = 1\n                                 LJ = J\n                              ELSE\n                                 JJ = J\n                                 LJ = N - J + 1\n                              END IF\n                              IF( TRAN )THEN\n                                 CALL DMMCH( 'T', 'N', LJ, 1, K, ALPHA,\n     $                                       A( 1, JJ ), NMAX,\n     $                                       A( 1, J ), NMAX, BETA,\n     $                                       C( JJ, J ), NMAX, CT, G,\n     $                                       CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              ELSE\n                                 CALL DMMCH( 'N', 'T', LJ, 1, K, ALPHA,\n     $                                       A( JJ, 1 ), NMAX,\n     $                                       A( J, 1 ), NMAX, BETA,\n     $                                       C( JJ, J ), NMAX, CT, G,\n     $                                       CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              END IF\n                              IF( UPPER )THEN\n                                 JC = JC + LDC\n                              ELSE\n                                 JC = JC + LDC + 1\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 110\n   40                      CONTINUE\n                        END IF\n*\n   50                CONTINUE\n*\n   60             CONTINUE\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  110 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9995 )J\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, N, K, ALPHA,\n     $   LDA, BETA, LDC\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      F4.1, ', A,', I3, ',', F4.1, ', C,', I3, ')           .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK4.\n*\n      END\n      SUBROUTINE DCHK5( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  AB, AA, AS, BB, BS, C, CC, CS, CT, G, W )\n*\n*  Tests DSYR2K.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO\n      PARAMETER          ( ZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   AA( NMAX*NMAX ), AB( 2*NMAX*NMAX ),\n     $                   ALF( NALF ), AS( NMAX*NMAX ), BB( NMAX*NMAX ),\n     $                   BET( NBET ), BS( NMAX*NMAX ), C( NMAX, NMAX ),\n     $                   CC( NMAX*NMAX ), CS( NMAX*NMAX ), CT( NMAX ),\n     $                   G( NMAX ), W( 2*NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, ALS, BETA, BETS, ERR, ERRMAX\n      INTEGER            I, IA, IB, ICT, ICU, IK, IN, J, JC, JJ, JJAB,\n     $                   K, KS, LAA, LBB, LCC, LDA, LDAS, LDB, LDBS,\n     $                   LDC, LDCS, LJ, MA, N, NA, NARGS, NC, NS\n      LOGICAL            NULL, RESET, SAME, TRAN, UPPER\n      CHARACTER*1        TRANS, TRANSS, UPLO, UPLOS\n      CHARACTER*2        ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DMAKE, DMMCH, DSYR2K\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHT/'NTC'/, ICHU/'UL'/\n*     .. Executable Statements ..\n*\n      NARGS = 12\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 130 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDC to 1 more than minimum value if room.\n         LDC = N\n         IF( LDC.LT.NMAX )\n     $      LDC = LDC + 1\n*        Skip tests if not enough room.\n         IF( LDC.GT.NMAX )\n     $      GO TO 130\n         LCC = LDC*N\n         NULL = N.LE.0\n*\n         DO 120 IK = 1, NIDIM\n            K = IDIM( IK )\n*\n            DO 110 ICT = 1, 3\n               TRANS = ICHT( ICT: ICT )\n               TRAN = TRANS.EQ.'T'.OR.TRANS.EQ.'C'\n               IF( TRAN )THEN\n                  MA = K\n                  NA = N\n               ELSE\n                  MA = N\n                  NA = K\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = MA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 110\n               LAA = LDA*NA\n*\n*              Generate the matrix A.\n*\n               IF( TRAN )THEN\n                  CALL DMAKE( 'GE', ' ', ' ', MA, NA, AB, 2*NMAX, AA,\n     $                        LDA, RESET, ZERO )\n               ELSE\n                  CALL DMAKE( 'GE', ' ', ' ', MA, NA, AB, NMAX, AA, LDA,\n     $                        RESET, ZERO )\n               END IF\n*\n*              Generate the matrix B.\n*\n               LDB = LDA\n               LBB = LAA\n               IF( TRAN )THEN\n                  CALL DMAKE( 'GE', ' ', ' ', MA, NA, AB( K + 1 ),\n     $                        2*NMAX, BB, LDB, RESET, ZERO )\n               ELSE\n                  CALL DMAKE( 'GE', ' ', ' ', MA, NA, AB( K*NMAX + 1 ),\n     $                        NMAX, BB, LDB, RESET, ZERO )\n               END IF\n*\n               DO 100 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n                  UPPER = UPLO.EQ.'U'\n*\n                  DO 90 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n                     DO 80 IB = 1, NBET\n                        BETA = BET( IB )\n*\n*                       Generate the matrix C.\n*\n                        CALL DMAKE( 'SY', UPLO, ' ', N, N, C, NMAX, CC,\n     $                              LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        NS = N\n                        KS = K\n                        ALS = ALPHA\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        DO 20 I = 1, LBB\n                           BS( I ) = BB( I )\n   20                   CONTINUE\n                        LDBS = LDB\n                        BETS = BETA\n                        DO 30 I = 1, LCC\n                           CS( I ) = CC( I )\n   30                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO,\n     $                     TRANS, N, K, ALPHA, LDA, LDB, BETA, LDC\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL DSYR2K( UPLO, TRANS, N, K, ALPHA, AA, LDA,\n     $                               BB, LDB, BETA, CC, LDC )\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9993 )\n                           FATAL = .TRUE.\n                           GO TO 150\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLOS.EQ.UPLO\n                        ISAME( 2 ) = TRANSS.EQ.TRANS\n                        ISAME( 3 ) = NS.EQ.N\n                        ISAME( 4 ) = KS.EQ.K\n                        ISAME( 5 ) = ALS.EQ.ALPHA\n                        ISAME( 6 ) = LDE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        ISAME( 8 ) = LDE( BS, BB, LBB )\n                        ISAME( 9 ) = LDBS.EQ.LDB\n                        ISAME( 10 ) = BETS.EQ.BETA\n                        IF( NULL )THEN\n                           ISAME( 11 ) = LDE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 11 ) = LDERES( 'SY', UPLO, N, N, CS,\n     $                                   CC, LDC )\n                        END IF\n                        ISAME( 12 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 150\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result column by column.\n*\n                           JJAB = 1\n                           JC = 1\n                           DO 70 J = 1, N\n                              IF( UPPER )THEN\n                                 JJ = 1\n                                 LJ = J\n                              ELSE\n                                 JJ = J\n                                 LJ = N - J + 1\n                              END IF\n                              IF( TRAN )THEN\n                                 DO 50 I = 1, K\n                                    W( I ) = AB( ( J - 1 )*2*NMAX + K +\n     $                                       I )\n                                    W( K + I ) = AB( ( J - 1 )*2*NMAX +\n     $                                           I )\n   50                            CONTINUE\n                                 CALL DMMCH( 'T', 'N', LJ, 1, 2*K,\n     $                                       ALPHA, AB( JJAB ), 2*NMAX,\n     $                                       W, 2*NMAX, BETA,\n     $                                       C( JJ, J ), NMAX, CT, G,\n     $                                       CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              ELSE\n                                 DO 60 I = 1, K\n                                    W( I ) = AB( ( K + I - 1 )*NMAX +\n     $                                       J )\n                                    W( K + I ) = AB( ( I - 1 )*NMAX +\n     $                                           J )\n   60                            CONTINUE\n                                 CALL DMMCH( 'N', 'N', LJ, 1, 2*K,\n     $                                       ALPHA, AB( JJ ), NMAX, W,\n     $                                       2*NMAX, BETA, C( JJ, J ),\n     $                                       NMAX, CT, G, CC( JC ), LDC,\n     $                                       EPS, ERR, FATAL, NOUT,\n     $                                       .TRUE. )\n                              END IF\n                              IF( UPPER )THEN\n                                 JC = JC + LDC\n                              ELSE\n                                 JC = JC + LDC + 1\n                                 IF( TRAN )\n     $                              JJAB = JJAB + 2*NMAX\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 140\n   70                      CONTINUE\n                        END IF\n*\n   80                CONTINUE\n*\n   90             CONTINUE\n*\n  100          CONTINUE\n*\n  110       CONTINUE\n*\n  120    CONTINUE\n*\n  130 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 160\n*\n  140 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9995 )J\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, N, K, ALPHA,\n     $   LDA, LDB, BETA, LDC\n*\n  160 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      F4.1, ', A,', I3, ', B,', I3, ',', F4.1, ', C,', I3, ')   ',\n     $      ' .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK5.\n*\n      END\n      SUBROUTINE DCHKE( ISNUM, SRNAMT, NOUT )\n*\n*  Tests the error exits from the Level 3 Blas.\n*  Requires a special version of the error-handling routine XERBLA.\n*  A, B and C should not need to be defined.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*  3-19-92:  Initialize ALPHA and BETA  (eca)\n*  3-19-92:  Fix argument 12 in calls to SSYMM with INFOT = 9  (eca)\n*\n*     .. Scalar Arguments ..\n      INTEGER            ISNUM, NOUT\n      CHARACTER*6        SRNAMT\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Parameters ..\n      DOUBLE PRECISION   ONE, TWO\n      PARAMETER          ( ONE = 1.0D0, TWO = 2.0D0 )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, BETA\n*     .. Local Arrays ..\n      DOUBLE PRECISION   A( 2, 1 ), B( 2, 1 ), C( 2, 1 )\n*     .. External Subroutines ..\n      EXTERNAL           CHKXER, DGEMM, DSYMM, DSYR2K, DSYRK, DTRMM,\n     $                   DTRSM\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n*     OK is set to .FALSE. by the special version of XERBLA or by CHKXER\n*     if anything is wrong.\n      OK = .TRUE.\n*     LERR is set to .TRUE. by the special version of XERBLA each time\n*     it is called, and is then tested and re-set by CHKXER.\n      LERR = .FALSE.\n*\n*     Initialize ALPHA and BETA.\n*\n      ALPHA = ONE\n      BETA = TWO\n*\n      GO TO ( 10, 20, 30, 40, 50, 60 )ISNUM\n   10 INFOT = 1\n      CALL DGEMM( '/', 'N', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 1\n      CALL DGEMM( '/', 'T', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DGEMM( 'N', '/', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DGEMM( 'T', '/', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DGEMM( 'N', 'N', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DGEMM( 'N', 'T', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DGEMM( 'T', 'N', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DGEMM( 'T', 'T', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DGEMM( 'N', 'N', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DGEMM( 'N', 'T', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DGEMM( 'T', 'N', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DGEMM( 'T', 'T', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DGEMM( 'N', 'N', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DGEMM( 'N', 'T', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DGEMM( 'T', 'N', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DGEMM( 'T', 'T', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL DGEMM( 'N', 'N', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL DGEMM( 'N', 'T', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL DGEMM( 'T', 'N', 0, 0, 2, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL DGEMM( 'T', 'T', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL DGEMM( 'N', 'N', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL DGEMM( 'T', 'N', 0, 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL DGEMM( 'N', 'T', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL DGEMM( 'T', 'T', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL DGEMM( 'N', 'N', 2, 0, 0, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL DGEMM( 'N', 'T', 2, 0, 0, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL DGEMM( 'T', 'N', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL DGEMM( 'T', 'T', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 70\n   20 INFOT = 1\n      CALL DSYMM( '/', 'U', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DSYMM( 'L', '/', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYMM( 'L', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYMM( 'R', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYMM( 'L', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYMM( 'R', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYMM( 'L', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYMM( 'R', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYMM( 'L', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYMM( 'R', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYMM( 'L', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYMM( 'R', 'U', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYMM( 'L', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYMM( 'R', 'L', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL DSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL DSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL DSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL DSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 70\n   30 INFOT = 1\n      CALL DTRMM( '/', 'U', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DTRMM( 'L', '/', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DTRMM( 'L', 'U', '/', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DTRMM( 'L', 'U', 'N', '/', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRMM( 'L', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRMM( 'L', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRMM( 'R', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRMM( 'R', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRMM( 'L', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRMM( 'L', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRMM( 'R', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRMM( 'R', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRMM( 'L', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRMM( 'L', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRMM( 'R', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRMM( 'R', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRMM( 'L', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRMM( 'L', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRMM( 'R', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRMM( 'R', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRMM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRMM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRMM( 'R', 'U', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRMM( 'R', 'U', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRMM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRMM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRMM( 'R', 'L', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRMM( 'R', 'L', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRMM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRMM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRMM( 'R', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRMM( 'R', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRMM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRMM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRMM( 'R', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRMM( 'R', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 70\n   40 INFOT = 1\n      CALL DTRSM( '/', 'U', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DTRSM( 'L', '/', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DTRSM( 'L', 'U', '/', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DTRSM( 'L', 'U', 'N', '/', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRSM( 'L', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRSM( 'L', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRSM( 'R', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRSM( 'R', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRSM( 'L', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRSM( 'L', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRSM( 'R', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRSM( 'R', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRSM( 'L', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRSM( 'L', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRSM( 'R', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRSM( 'R', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRSM( 'L', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRSM( 'L', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRSM( 'R', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRSM( 'R', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRSM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRSM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRSM( 'R', 'U', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRSM( 'R', 'U', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRSM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRSM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRSM( 'R', 'L', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRSM( 'R', 'L', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRSM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRSM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRSM( 'R', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRSM( 'R', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRSM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRSM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRSM( 'R', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRSM( 'R', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 70\n   50 INFOT = 1\n      CALL DSYRK( '/', 'N', 0, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DSYRK( 'U', '/', 0, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYRK( 'U', 'N', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYRK( 'U', 'T', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYRK( 'L', 'N', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYRK( 'L', 'T', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYRK( 'U', 'N', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYRK( 'U', 'T', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYRK( 'L', 'N', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYRK( 'L', 'T', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYRK( 'U', 'N', 2, 0, ALPHA, A, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYRK( 'U', 'T', 0, 2, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYRK( 'L', 'N', 2, 0, ALPHA, A, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYRK( 'L', 'T', 0, 2, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL DSYRK( 'U', 'N', 2, 0, ALPHA, A, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL DSYRK( 'U', 'T', 2, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL DSYRK( 'L', 'N', 2, 0, ALPHA, A, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL DSYRK( 'L', 'T', 2, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 70\n   60 INFOT = 1\n      CALL DSYR2K( '/', 'N', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DSYR2K( 'U', '/', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYR2K( 'U', 'N', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYR2K( 'U', 'T', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYR2K( 'L', 'N', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYR2K( 'L', 'T', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYR2K( 'U', 'N', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYR2K( 'U', 'T', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYR2K( 'L', 'N', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYR2K( 'L', 'T', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYR2K( 'U', 'N', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYR2K( 'U', 'T', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYR2K( 'L', 'N', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYR2K( 'L', 'T', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DSYR2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DSYR2K( 'U', 'T', 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DSYR2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DSYR2K( 'L', 'T', 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL DSYR2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL DSYR2K( 'U', 'T', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL DSYR2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL DSYR2K( 'L', 'T', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n   70 IF( OK )THEN\n         WRITE( NOUT, FMT = 9999 )SRNAMT\n      ELSE\n         WRITE( NOUT, FMT = 9998 )SRNAMT\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE TESTS OF ERROR-EXITS' )\n 9998 FORMAT( ' ******* ', A6, ' FAILED THE TESTS OF ERROR-EXITS *****',\n     $      '**' )\n*\n*     End of DCHKE.\n*\n      END\n      SUBROUTINE DMAKE( TYPE, UPLO, DIAG, M, N, A, NMAX, AA, LDA, RESET,\n     $                  TRANSL )\n*\n*  Generates values for an M by N matrix A.\n*  Stores the values in the array AA in the data structure required\n*  by the routine, with unwanted elements set to rogue value.\n*\n*  TYPE is 'GE', 'SY' or 'TR'.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, ONE\n      PARAMETER          ( ZERO = 0.0D0, ONE = 1.0D0 )\n      DOUBLE PRECISION   ROGUE\n      PARAMETER          ( ROGUE = -1.0D10 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   TRANSL\n      INTEGER            LDA, M, N, NMAX\n      LOGICAL            RESET\n      CHARACTER*1        DIAG, UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, * ), AA( * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J\n      LOGICAL            GEN, LOWER, SYM, TRI, UNIT, UPPER\n*     .. External Functions ..\n      DOUBLE PRECISION   DBEG\n      EXTERNAL           DBEG\n*     .. Executable Statements ..\n      GEN = TYPE.EQ.'GE'\n      SYM = TYPE.EQ.'SY'\n      TRI = TYPE.EQ.'TR'\n      UPPER = ( SYM.OR.TRI ).AND.UPLO.EQ.'U'\n      LOWER = ( SYM.OR.TRI ).AND.UPLO.EQ.'L'\n      UNIT = TRI.AND.DIAG.EQ.'U'\n*\n*     Generate data in array A.\n*\n      DO 20 J = 1, N\n         DO 10 I = 1, M\n            IF( GEN.OR.( UPPER.AND.I.LE.J ).OR.( LOWER.AND.I.GE.J ) )\n     $          THEN\n               A( I, J ) = DBEG( RESET ) + TRANSL\n               IF( I.NE.J )THEN\n*                 Set some elements to zero\n                  IF( N.GT.3.AND.J.EQ.N/2 )\n     $               A( I, J ) = ZERO\n                  IF( SYM )THEN\n                     A( J, I ) = A( I, J )\n                  ELSE IF( TRI )THEN\n                     A( J, I ) = ZERO\n                  END IF\n               END IF\n            END IF\n   10    CONTINUE\n         IF( TRI )\n     $      A( J, J ) = A( J, J ) + ONE\n         IF( UNIT )\n     $      A( J, J ) = ONE\n   20 CONTINUE\n*\n*     Store elements in array AS in data structure required by routine.\n*\n      IF( TYPE.EQ.'GE' )THEN\n         DO 50 J = 1, N\n            DO 30 I = 1, M\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   30       CONTINUE\n            DO 40 I = M + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   40       CONTINUE\n   50    CONTINUE\n      ELSE IF( TYPE.EQ.'SY'.OR.TYPE.EQ.'TR' )THEN\n         DO 90 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IF( UNIT )THEN\n                  IEND = J - 1\n               ELSE\n                  IEND = J\n               END IF\n            ELSE\n               IF( UNIT )THEN\n                  IBEG = J + 1\n               ELSE\n                  IBEG = J\n               END IF\n               IEND = N\n            END IF\n            DO 60 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   60       CONTINUE\n            DO 70 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   70       CONTINUE\n            DO 80 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   80       CONTINUE\n   90    CONTINUE\n      END IF\n      RETURN\n*\n*     End of DMAKE.\n*\n      END\n      SUBROUTINE DMMCH( TRANSA, TRANSB, M, N, KK, ALPHA, A, LDA, B, LDB,\n     $                  BETA, C, LDC, CT, G, CC, LDCC, EPS, ERR, FATAL,\n     $                  NOUT, MV )\n*\n*  Checks the results of the computational tests.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, ONE\n      PARAMETER          ( ZERO = 0.0D0, ONE = 1.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   ALPHA, BETA, EPS, ERR\n      INTEGER            KK, LDA, LDB, LDC, LDCC, M, N, NOUT\n      LOGICAL            FATAL, MV\n      CHARACTER*1        TRANSA, TRANSB\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( LDA, * ), B( LDB, * ), C( LDC, * ),\n     $                   CC( LDCC, * ), CT( * ), G( * )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ERRI\n      INTEGER            I, J, K\n      LOGICAL            TRANA, TRANB\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, SQRT\n*     .. Executable Statements ..\n      TRANA = TRANSA.EQ.'T'.OR.TRANSA.EQ.'C'\n      TRANB = TRANSB.EQ.'T'.OR.TRANSB.EQ.'C'\n*\n*     Compute expected result, one column at a time, in CT using data\n*     in A, B and C.\n*     Compute gauges in G.\n*\n      DO 120 J = 1, N\n*\n         DO 10 I = 1, M\n            CT( I ) = ZERO\n            G( I ) = ZERO\n   10    CONTINUE\n         IF( .NOT.TRANA.AND..NOT.TRANB )THEN\n            DO 30 K = 1, KK\n               DO 20 I = 1, M\n                  CT( I ) = CT( I ) + A( I, K )*B( K, J )\n                  G( I ) = G( I ) + ABS( A( I, K ) )*ABS( B( K, J ) )\n   20          CONTINUE\n   30       CONTINUE\n         ELSE IF( TRANA.AND..NOT.TRANB )THEN\n            DO 50 K = 1, KK\n               DO 40 I = 1, M\n                  CT( I ) = CT( I ) + A( K, I )*B( K, J )\n                  G( I ) = G( I ) + ABS( A( K, I ) )*ABS( B( K, J ) )\n   40          CONTINUE\n   50       CONTINUE\n         ELSE IF( .NOT.TRANA.AND.TRANB )THEN\n            DO 70 K = 1, KK\n               DO 60 I = 1, M\n                  CT( I ) = CT( I ) + A( I, K )*B( J, K )\n                  G( I ) = G( I ) + ABS( A( I, K ) )*ABS( B( J, K ) )\n   60          CONTINUE\n   70       CONTINUE\n         ELSE IF( TRANA.AND.TRANB )THEN\n            DO 90 K = 1, KK\n               DO 80 I = 1, M\n                  CT( I ) = CT( I ) + A( K, I )*B( J, K )\n                  G( I ) = G( I ) + ABS( A( K, I ) )*ABS( B( J, K ) )\n   80          CONTINUE\n   90       CONTINUE\n         END IF\n         DO 100 I = 1, M\n            CT( I ) = ALPHA*CT( I ) + BETA*C( I, J )\n            G( I ) = ABS( ALPHA )*G( I ) + ABS( BETA )*ABS( C( I, J ) )\n  100    CONTINUE\n*\n*        Compute the error ratio for this result.\n*\n         ERR = ZERO\n         DO 110 I = 1, M\n            ERRI = ABS( CT( I ) - CC( I, J ) )/EPS\n            IF( G( I ).NE.ZERO )\n     $         ERRI = ERRI/G( I )\n            ERR = MAX( ERR, ERRI )\n            IF( ERR*SQRT( EPS ).GE.ONE )\n     $         GO TO 130\n  110    CONTINUE\n*\n  120 CONTINUE\n*\n*     If the loop completes, all results are at least half accurate.\n      GO TO 150\n*\n*     Report fatal error.\n*\n  130 FATAL = .TRUE.\n      WRITE( NOUT, FMT = 9999 )\n      DO 140 I = 1, M\n         IF( MV )THEN\n            WRITE( NOUT, FMT = 9998 )I, CT( I ), CC( I, J )\n         ELSE\n            WRITE( NOUT, FMT = 9998 )I, CC( I, J ), CT( I )\n         END IF\n  140 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9997 )J\n*\n  150 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ******* FATAL ERROR - COMPUTED RESULT IS LESS THAN HAL',\n     $      'F ACCURATE *******', /'           EXPECTED RESULT   COMPU',\n     $      'TED RESULT' )\n 9998 FORMAT( 1X, I7, 2G18.6 )\n 9997 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n*\n*     End of DMMCH.\n*\n      END\n      LOGICAL FUNCTION LDE( RI, RJ, LR )\n*\n*  Tests if two arrays are identical.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LR\n*     .. Array Arguments ..\n      DOUBLE PRECISION   RI( * ), RJ( * )\n*     .. Local Scalars ..\n      INTEGER            I\n*     .. Executable Statements ..\n      DO 10 I = 1, LR\n         IF( RI( I ).NE.RJ( I ) )\n     $      GO TO 20\n   10 CONTINUE\n      LDE = .TRUE.\n      GO TO 30\n   20 CONTINUE\n      LDE = .FALSE.\n   30 RETURN\n*\n*     End of LDE.\n*\n      END\n      LOGICAL FUNCTION LDERES( TYPE, UPLO, M, N, AA, AS, LDA )\n*\n*  Tests if selected elements in two arrays are equal.\n*\n*  TYPE is 'GE' or 'SY'.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LDA, M, N\n      CHARACTER*1        UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      DOUBLE PRECISION   AA( LDA, * ), AS( LDA, * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J\n      LOGICAL            UPPER\n*     .. Executable Statements ..\n      UPPER = UPLO.EQ.'U'\n      IF( TYPE.EQ.'GE' )THEN\n         DO 20 J = 1, N\n            DO 10 I = M + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   10       CONTINUE\n   20    CONTINUE\n      ELSE IF( TYPE.EQ.'SY' )THEN\n         DO 50 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 30 I = 1, IBEG - 1\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   30       CONTINUE\n            DO 40 I = IEND + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   40       CONTINUE\n   50    CONTINUE\n      END IF\n*\n      LDERES = .TRUE.\n      GO TO 80\n   70 CONTINUE\n      LDERES = .FALSE.\n   80 RETURN\n*\n*     End of LDERES.\n*\n      END\n      DOUBLE PRECISION FUNCTION DBEG( RESET )\n*\n*  Generates random numbers uniformly distributed between -0.5 and 0.5.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      LOGICAL            RESET\n*     .. Local Scalars ..\n      INTEGER            I, IC, MI\n*     .. Save statement ..\n      SAVE               I, IC, MI\n*     .. Executable Statements ..\n      IF( RESET )THEN\n*        Initialize local variables.\n         MI = 891\n         I = 7\n         IC = 0\n         RESET = .FALSE.\n      END IF\n*\n*     The sequence of values of I is bounded between 1 and 999.\n*     If initial I = 1,2,3,6,7 or 9, the period will be 50.\n*     If initial I = 4 or 8, the period will be 25.\n*     If initial I = 5, the period will be 10.\n*     IC is used to break up the period by skipping 1 value of I in 6.\n*\n      IC = IC + 1\n   10 I = I*MI\n      I = I - 1000*( I/1000 )\n      IF( IC.GE.5 )THEN\n         IC = 0\n         GO TO 10\n      END IF\n      DBEG = ( I - 500 )/1001.0D0\n      RETURN\n*\n*     End of DBEG.\n*\n      END\n      DOUBLE PRECISION FUNCTION DDIFF( X, Y )\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   X, Y\n*     .. Executable Statements ..\n      DDIFF = X - Y\n      RETURN\n*\n*     End of DDIFF.\n*\n      END\n      SUBROUTINE CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n*  Tests whether XERBLA has detected an error when it should.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Executable Statements ..\n      IF( .NOT.LERR )THEN\n         WRITE( NOUT, FMT = 9999 )INFOT, SRNAMT\n         OK = .FALSE.\n      END IF\n      LERR = .FALSE.\n      RETURN\n*\n 9999 FORMAT( ' ***** ILLEGAL VALUE OF PARAMETER NUMBER ', I2, ' NOT D',\n     $      'ETECTED BY ', A6, ' *****' )\n*\n*     End of CHKXER.\n*\n      END\n      SUBROUTINE XERBLA( SRNAME, INFO )\n*\n*  This is a special version of XERBLA to be used only as part of\n*  the test program for testing error exits from the Level 3 BLAS\n*  routines.\n*\n*  XERBLA  is an error handler for the Level 3 BLAS routines.\n*\n*  It is called by the Level 3 BLAS routines if an input parameter is\n*  invalid.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFO\n      CHARACTER*6        SRNAME\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUT, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Executable Statements ..\n      LERR = .TRUE.\n      IF( INFO.NE.INFOT )THEN\n         IF( INFOT.NE.0 )THEN\n            WRITE( NOUT, FMT = 9999 )INFO, INFOT\n         ELSE\n            WRITE( NOUT, FMT = 9997 )INFO\n         END IF\n         OK = .FALSE.\n      END IF\n      IF( SRNAME.NE.SRNAMT )THEN\n         WRITE( NOUT, FMT = 9998 )SRNAME, SRNAMT\n         OK = .FALSE.\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6, ' INSTEAD',\n     $      ' OF ', I2, ' *******' )\n 9998 FORMAT( ' ******* XERBLA WAS CALLED WITH SRNAME = ', A6, ' INSTE',\n     $      'AD OF ', A6, ' *******' )\n 9997 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6,\n     $      ' *******' )\n*\n*     End of XERBLA\n*\n      END\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/testing/runblastest.sh",
    "content": "#!/bin/bash\n\nblack='\\E[30m'\nred='\\E[31m'\ngreen='\\E[32m'\nyellow='\\E[33m'\nblue='\\E[34m'\nmagenta='\\E[35m'\ncyan='\\E[36m'\nwhite='\\E[37m'\n\nif [ -f $2 ]; then\n  data=$2\n  if [ -f $1.summ ]; then rm $1.summ; fi\n  if [ -f $1.snap ]; then rm $1.snap; fi\nelse\n  data=$1\nfi\n\nif ! ./$1 < $data > /dev/null 2> .runtest.log ; then\n  echo -e  $red Test $1 failed: $black\n  echo -e $blue\n  cat .runtest.log\n  echo -e $black\n  exit 1\nelse\n  if [ -f $1.summ ]; then\n    if [ `grep \"FATAL ERROR\" $1.summ | wc -l` -gt 0 ]; then\n      echo -e  $red \"Test $1 failed (FATAL ERROR, read the file $1.summ for details)\" $black\n      echo -e $blue\n      cat .runtest.log\n      echo -e $black\n      exit 1;\n    fi\n\n    if [ `grep \"FAILED THE TESTS OF ERROR-EXITS\" $1.summ | wc -l` -gt 0 ]; then\n      echo -e  $red \"Test $1 failed (FAILED THE TESTS OF ERROR-EXITS, read the file $1.summ for details)\" $black\n      echo -e $blue\n      cat .runtest.log\n      echo -e $black\n      exit 1;\n    fi      \n  fi\n  echo -e $green Test $1 passed$black\nfi\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/testing/sblat1.f",
    "content": "*> \\brief \\b SBLAT1\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM SBLAT1\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*>    Test program for the REAL Level 1 BLAS.\n*>\n*>    Based upon the original BLAS test routine together with:\n*>    F06EAF Example Program Text\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup single_blas_testing\n*\n*  =====================================================================\n      PROGRAM SBLAT1\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER          NOUT\n      PARAMETER        (NOUT=6)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, N\n      LOGICAL          PASS\n*     .. Local Scalars ..\n      REAL             SFAC\n      INTEGER          IC\n*     .. External Subroutines ..\n      EXTERNAL         CHECK0, CHECK1, CHECK2, CHECK3, HEADER\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      DATA             SFAC/9.765625E-4/\n*     .. Executable Statements ..\n      WRITE (NOUT,99999)\n      DO 20 IC = 1, 13\n         ICASE = IC\n         CALL HEADER\n*\n*        .. Initialize  PASS,  INCX,  and INCY for a new case. ..\n*        .. the value 9999 for INCX or INCY will appear in the ..\n*        .. detailed  output, if any, for cases  that do not involve ..\n*        .. these parameters ..\n*\n         PASS = .TRUE.\n         INCX = 9999\n         INCY = 9999\n         IF (ICASE.EQ.3 .OR. ICASE.EQ.11) THEN\n            CALL CHECK0(SFAC)\n         ELSE IF (ICASE.EQ.7 .OR. ICASE.EQ.8 .OR. ICASE.EQ.9 .OR.\n     +            ICASE.EQ.10) THEN\n            CALL CHECK1(SFAC)\n         ELSE IF (ICASE.EQ.1 .OR. ICASE.EQ.2 .OR. ICASE.EQ.5 .OR.\n     +            ICASE.EQ.6 .OR. ICASE.EQ.12 .OR. ICASE.EQ.13) THEN\n            CALL CHECK2(SFAC)\n         ELSE IF (ICASE.EQ.4) THEN\n            CALL CHECK3(SFAC)\n         END IF\n*        -- Print\n         IF (PASS) WRITE (NOUT,99998)\n   20 CONTINUE\n      STOP\n*\n99999 FORMAT (' Real BLAS Test Program Results',/1X)\n99998 FORMAT ('                                    ----- PASS -----')\n      END\n      SUBROUTINE HEADER\n*     .. Parameters ..\n      INTEGER          NOUT\n      PARAMETER        (NOUT=6)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, N\n      LOGICAL          PASS\n*     .. Local Arrays ..\n      CHARACTER*6      L(13)\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      DATA             L(1)/' SDOT '/\n      DATA             L(2)/'SAXPY '/\n      DATA             L(3)/'SROTG '/\n      DATA             L(4)/' SROT '/\n      DATA             L(5)/'SCOPY '/\n      DATA             L(6)/'SSWAP '/\n      DATA             L(7)/'SNRM2 '/\n      DATA             L(8)/'SASUM '/\n      DATA             L(9)/'SSCAL '/\n      DATA             L(10)/'ISAMAX'/\n      DATA             L(11)/'SROTMG'/\n      DATA             L(12)/'SROTM '/\n      DATA             L(13)/'SDSDOT'/\n*     .. Executable Statements ..\n      WRITE (NOUT,99999) ICASE, L(ICASE)\n      RETURN\n*\n99999 FORMAT (/' Test of subprogram number',I3,12X,A6)\n      END\n      SUBROUTINE CHECK0(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      REAL              SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      REAL              D12, SA, SB, SC, SS\n      INTEGER           I, K\n*     .. Local Arrays ..\n      REAL              DA1(8), DATRUE(8), DB1(8), DBTRUE(8), DC1(8),\n     +                  DS1(8), DAB(4,9), DTEMP(9), DTRUE(9,9)\n*     .. External Subroutines ..\n      EXTERNAL          SROTG, SROTMG, STEST1\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      DATA              DA1/0.3E0, 0.4E0, -0.3E0, -0.4E0, -0.3E0, 0.0E0,\n     +                  0.0E0, 1.0E0/\n      DATA              DB1/0.4E0, 0.3E0, 0.4E0, 0.3E0, -0.4E0, 0.0E0,\n     +                  1.0E0, 0.0E0/\n      DATA              DC1/0.6E0, 0.8E0, -0.6E0, 0.8E0, 0.6E0, 1.0E0,\n     +                  0.0E0, 1.0E0/\n      DATA              DS1/0.8E0, 0.6E0, 0.8E0, -0.6E0, 0.8E0, 0.0E0,\n     +                  1.0E0, 0.0E0/\n      DATA              DATRUE/0.5E0, 0.5E0, 0.5E0, -0.5E0, -0.5E0,\n     +                  0.0E0, 1.0E0, 1.0E0/\n      DATA              DBTRUE/0.0E0, 0.6E0, 0.0E0, -0.6E0, 0.0E0,\n     +                  0.0E0, 1.0E0, 0.0E0/\n*     INPUT FOR MODIFIED GIVENS\n      DATA DAB/ .1E0,.3E0,1.2E0,.2E0,\n     A          .7E0, .2E0, .6E0, 4.2E0,\n     B          0.E0,0.E0,0.E0,0.E0,\n     C          4.E0, -1.E0, 2.E0, 4.E0,\n     D          6.E-10, 2.E-2, 1.E5, 10.E0,\n     E          4.E10, 2.E-2, 1.E-5, 10.E0,\n     F          2.E-10, 4.E-2, 1.E5, 10.E0,\n     G          2.E10, 4.E-2, 1.E-5, 10.E0,\n     H          4.E0, -2.E0, 8.E0, 4.E0    /\n*    TRUE RESULTS FOR MODIFIED GIVENS\n      DATA DTRUE/0.E0,0.E0, 1.3E0, .2E0, 0.E0,0.E0,0.E0, .5E0, 0.E0,\n     A           0.E0,0.E0, 4.5E0, 4.2E0, 1.E0, .5E0, 0.E0,0.E0,0.E0,\n     B           0.E0,0.E0,0.E0,0.E0, -2.E0, 0.E0,0.E0,0.E0,0.E0,\n     C           0.E0,0.E0,0.E0, 4.E0, -1.E0, 0.E0,0.E0,0.E0,0.E0,\n     D           0.E0, 15.E-3, 0.E0, 10.E0, -1.E0, 0.E0, -1.E-4,\n     E           0.E0, 1.E0,\n     F           0.E0,0.E0, 6144.E-5, 10.E0, -1.E0, 4096.E0, -1.E6,\n     G           0.E0, 1.E0,\n     H           0.E0,0.E0,15.E0,10.E0,-1.E0, 5.E-5, 0.E0,1.E0,0.E0,\n     I           0.E0,0.E0, 15.E0, 10.E0, -1. E0, 5.E5, -4096.E0,\n     J           1.E0, 4096.E-6,\n     K           0.E0,0.E0, 7.E0, 4.E0, 0.E0,0.E0, -.5E0, -.25E0, 0.E0/\n*                   4096 = 2 ** 12\n      DATA D12  /4096.E0/\n      DTRUE(1,1) = 12.E0 / 130.E0\n      DTRUE(2,1) = 36.E0 / 130.E0\n      DTRUE(7,1) = -1.E0 / 6.E0\n      DTRUE(1,2) = 14.E0 / 75.E0\n      DTRUE(2,2) = 49.E0 / 75.E0\n      DTRUE(9,2) = 1.E0 / 7.E0\n      DTRUE(1,5) = 45.E-11 * (D12 * D12)\n      DTRUE(3,5) = 4.E5 / (3.E0 * D12)\n      DTRUE(6,5) = 1.E0 / D12\n      DTRUE(8,5) = 1.E4 / (3.E0 * D12)\n      DTRUE(1,6) = 4.E10 / (1.5E0 * D12 * D12)\n      DTRUE(2,6) = 2.E-2 / 1.5E0\n      DTRUE(8,6) = 5.E-7 * D12\n      DTRUE(1,7) = 4.E0 / 150.E0\n      DTRUE(2,7) = (2.E-10 / 1.5E0) * (D12 * D12)\n      DTRUE(7,7) = -DTRUE(6,5)\n      DTRUE(9,7) = 1.E4 / D12\n      DTRUE(1,8) = DTRUE(1,7)\n      DTRUE(2,8) = 2.E10 / (1.5E0 * D12 * D12)\n      DTRUE(1,9) = 32.E0 / 7.E0\n      DTRUE(2,9) = -16.E0 / 7.E0\n*     .. Executable Statements ..\n*\n*     Compute true values which cannot be prestored\n*     in decimal notation\n*\n      DBTRUE(1) = 1.0E0/0.6E0\n      DBTRUE(3) = -1.0E0/0.6E0\n      DBTRUE(5) = 1.0E0/0.6E0\n*\n      DO 20 K = 1, 8\n*        .. Set N=K for identification in output if any ..\n         N = K\n         IF (ICASE.EQ.3) THEN\n*           .. SROTG ..\n            IF (K.GT.8) GO TO 40\n            SA = DA1(K)\n            SB = DB1(K)\n            CALL SROTG(SA,SB,SC,SS)\n            CALL STEST1(SA,DATRUE(K),DATRUE(K),SFAC)\n            CALL STEST1(SB,DBTRUE(K),DBTRUE(K),SFAC)\n            CALL STEST1(SC,DC1(K),DC1(K),SFAC)\n            CALL STEST1(SS,DS1(K),DS1(K),SFAC)\n         ELSEIF (ICASE.EQ.11) THEN\n*           .. SROTMG ..\n            DO I=1,4\n               DTEMP(I)= DAB(I,K)\n               DTEMP(I+4) = 0.0\n            END DO\n            DTEMP(9) = 0.0\n            CALL SROTMG(DTEMP(1),DTEMP(2),DTEMP(3),DTEMP(4),DTEMP(5))\n            CALL STEST(9,DTEMP,DTRUE(1,K),DTRUE(1,K),SFAC)\n         ELSE\n            WRITE (NOUT,*) ' Shouldn''t be here in CHECK0'\n            STOP\n         END IF\n   20 CONTINUE\n   40 RETURN\n      END\n      SUBROUTINE CHECK1(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      REAL              SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      INTEGER           I, LEN, NP1\n*     .. Local Arrays ..\n      REAL              DTRUE1(5), DTRUE3(5), DTRUE5(8,5,2), DV(8,5,2),\n     +                  SA(10), STEMP(1), STRUE(8), SX(8)\n      INTEGER           ITRUE2(5)\n*     .. External Functions ..\n      REAL              SASUM, SNRM2\n      INTEGER           ISAMAX\n      EXTERNAL          SASUM, SNRM2, ISAMAX\n*     .. External Subroutines ..\n      EXTERNAL          ITEST1, SSCAL, STEST, STEST1\n*     .. Intrinsic Functions ..\n      INTRINSIC         MAX\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      DATA              SA/0.3E0, -1.0E0, 0.0E0, 1.0E0, 0.3E0, 0.3E0,\n     +                  0.3E0, 0.3E0, 0.3E0, 0.3E0/\n      DATA              DV/0.1E0, 2.0E0, 2.0E0, 2.0E0, 2.0E0, 2.0E0,\n     +                  2.0E0, 2.0E0, 0.3E0, 3.0E0, 3.0E0, 3.0E0, 3.0E0,\n     +                  3.0E0, 3.0E0, 3.0E0, 0.3E0, -0.4E0, 4.0E0,\n     +                  4.0E0, 4.0E0, 4.0E0, 4.0E0, 4.0E0, 0.2E0,\n     +                  -0.6E0, 0.3E0, 5.0E0, 5.0E0, 5.0E0, 5.0E0,\n     +                  5.0E0, 0.1E0, -0.3E0, 0.5E0, -0.1E0, 6.0E0,\n     +                  6.0E0, 6.0E0, 6.0E0, 0.1E0, 8.0E0, 8.0E0, 8.0E0,\n     +                  8.0E0, 8.0E0, 8.0E0, 8.0E0, 0.3E0, 9.0E0, 9.0E0,\n     +                  9.0E0, 9.0E0, 9.0E0, 9.0E0, 9.0E0, 0.3E0, 2.0E0,\n     +                  -0.4E0, 2.0E0, 2.0E0, 2.0E0, 2.0E0, 2.0E0,\n     +                  0.2E0, 3.0E0, -0.6E0, 5.0E0, 0.3E0, 2.0E0,\n     +                  2.0E0, 2.0E0, 0.1E0, 4.0E0, -0.3E0, 6.0E0,\n     +                  -0.5E0, 7.0E0, -0.1E0, 3.0E0/\n      DATA              DTRUE1/0.0E0, 0.3E0, 0.5E0, 0.7E0, 0.6E0/\n      DATA              DTRUE3/0.0E0, 0.3E0, 0.7E0, 1.1E0, 1.0E0/\n      DATA              DTRUE5/0.10E0, 2.0E0, 2.0E0, 2.0E0, 2.0E0,\n     +                  2.0E0, 2.0E0, 2.0E0, -0.3E0, 3.0E0, 3.0E0,\n     +                  3.0E0, 3.0E0, 3.0E0, 3.0E0, 3.0E0, 0.0E0, 0.0E0,\n     +                  4.0E0, 4.0E0, 4.0E0, 4.0E0, 4.0E0, 4.0E0,\n     +                  0.20E0, -0.60E0, 0.30E0, 5.0E0, 5.0E0, 5.0E0,\n     +                  5.0E0, 5.0E0, 0.03E0, -0.09E0, 0.15E0, -0.03E0,\n     +                  6.0E0, 6.0E0, 6.0E0, 6.0E0, 0.10E0, 8.0E0,\n     +                  8.0E0, 8.0E0, 8.0E0, 8.0E0, 8.0E0, 8.0E0,\n     +                  0.09E0, 9.0E0, 9.0E0, 9.0E0, 9.0E0, 9.0E0,\n     +                  9.0E0, 9.0E0, 0.09E0, 2.0E0, -0.12E0, 2.0E0,\n     +                  2.0E0, 2.0E0, 2.0E0, 2.0E0, 0.06E0, 3.0E0,\n     +                  -0.18E0, 5.0E0, 0.09E0, 2.0E0, 2.0E0, 2.0E0,\n     +                  0.03E0, 4.0E0, -0.09E0, 6.0E0, -0.15E0, 7.0E0,\n     +                  -0.03E0, 3.0E0/\n      DATA              ITRUE2/0, 1, 2, 2, 3/\n*     .. Executable Statements ..\n      DO 80 INCX = 1, 2\n         DO 60 NP1 = 1, 5\n            N = NP1 - 1\n            LEN = 2*MAX(N,1)\n*           .. Set vector arguments ..\n            DO 20 I = 1, LEN\n               SX(I) = DV(I,NP1,INCX)\n   20       CONTINUE\n*\n            IF (ICASE.EQ.7) THEN\n*              .. SNRM2 ..\n               STEMP(1) = DTRUE1(NP1)\n               CALL STEST1(SNRM2(N,SX,INCX),STEMP(1),STEMP,SFAC)\n            ELSE IF (ICASE.EQ.8) THEN\n*              .. SASUM ..\n               STEMP(1) = DTRUE3(NP1)\n               CALL STEST1(SASUM(N,SX,INCX),STEMP(1),STEMP,SFAC)\n            ELSE IF (ICASE.EQ.9) THEN\n*              .. SSCAL ..\n               CALL SSCAL(N,SA((INCX-1)*5+NP1),SX,INCX)\n               DO 40 I = 1, LEN\n                  STRUE(I) = DTRUE5(I,NP1,INCX)\n   40          CONTINUE\n               CALL STEST(LEN,SX,STRUE,STRUE,SFAC)\n            ELSE IF (ICASE.EQ.10) THEN\n*              .. ISAMAX ..\n               CALL ITEST1(ISAMAX(N,SX,INCX),ITRUE2(NP1))\n            ELSE\n               WRITE (NOUT,*) ' Shouldn''t be here in CHECK1'\n               STOP\n            END IF\n   60    CONTINUE\n   80 CONTINUE\n      RETURN\n      END\n      SUBROUTINE CHECK2(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      REAL              SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      REAL              SA\n      INTEGER           I, J, KI, KN, KNI, KPAR, KSIZE, LENX, LENY,\n     $                  MX, MY \n*     .. Local Arrays ..\n      REAL              DT10X(7,4,4), DT10Y(7,4,4), DT7(4,4),\n     $                  DT8(7,4,4), DX1(7),\n     $                  DY1(7), SSIZE1(4), SSIZE2(14,2), SSIZE3(4),\n     $                  SSIZE(7), STX(7), STY(7), SX(7), SY(7),\n     $                  DPAR(5,4), DT19X(7,4,16),DT19XA(7,4,4),\n     $                  DT19XB(7,4,4), DT19XC(7,4,4),DT19XD(7,4,4),\n     $                  DT19Y(7,4,16), DT19YA(7,4,4),DT19YB(7,4,4),\n     $                  DT19YC(7,4,4), DT19YD(7,4,4), DTEMP(5),\n     $                  ST7B(4,4)\n      INTEGER           INCXS(4), INCYS(4), LENS(4,2), NS(4)\n*     .. External Functions ..\n      REAL              SDOT, SDSDOT\n      EXTERNAL          SDOT, SDSDOT\n*     .. External Subroutines ..\n      EXTERNAL          SAXPY, SCOPY, SROTM, SSWAP, STEST, STEST1\n*     .. Intrinsic Functions ..\n      INTRINSIC         ABS, MIN\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      EQUIVALENCE (DT19X(1,1,1),DT19XA(1,1,1)),(DT19X(1,1,5),\n     A   DT19XB(1,1,1)),(DT19X(1,1,9),DT19XC(1,1,1)),\n     B   (DT19X(1,1,13),DT19XD(1,1,1))\n      EQUIVALENCE (DT19Y(1,1,1),DT19YA(1,1,1)),(DT19Y(1,1,5),\n     A   DT19YB(1,1,1)),(DT19Y(1,1,9),DT19YC(1,1,1)),\n     B   (DT19Y(1,1,13),DT19YD(1,1,1))\n\n      DATA              SA/0.3E0/\n      DATA              INCXS/1, 2, -2, -1/\n      DATA              INCYS/1, -2, 1, -2/\n      DATA              LENS/1, 1, 2, 4, 1, 1, 3, 7/\n      DATA              NS/0, 1, 2, 4/\n      DATA              DX1/0.6E0, 0.1E0, -0.5E0, 0.8E0, 0.9E0, -0.3E0,\n     +                  -0.4E0/\n      DATA              DY1/0.5E0, -0.9E0, 0.3E0, 0.7E0, -0.6E0, 0.2E0,\n     +                  0.8E0/\n      DATA              DT7/0.0E0, 0.30E0, 0.21E0, 0.62E0, 0.0E0,\n     +                  0.30E0, -0.07E0, 0.85E0, 0.0E0, 0.30E0, -0.79E0,\n     +                  -0.74E0, 0.0E0, 0.30E0, 0.33E0, 1.27E0/\n      DATA              ST7B/ .1, .4, .31, .72,     .1, .4, .03, .95,\n     +                  .1, .4, -.69, -.64,   .1, .4, .43, 1.37/\n      DATA              DT8/0.5E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.68E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.68E0, -0.87E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.68E0, -0.87E0, 0.15E0,\n     +                  0.94E0, 0.0E0, 0.0E0, 0.0E0, 0.5E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.68E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.35E0, -0.9E0, 0.48E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.38E0, -0.9E0, 0.57E0, 0.7E0, -0.75E0,\n     +                  0.2E0, 0.98E0, 0.5E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.68E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.35E0, -0.72E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.38E0,\n     +                  -0.63E0, 0.15E0, 0.88E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.5E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.68E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.68E0, -0.9E0, 0.33E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.68E0, -0.9E0, 0.33E0, 0.7E0,\n     +                  -0.75E0, 0.2E0, 1.04E0/\n      DATA              DT10X/0.6E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.5E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.5E0, -0.9E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.5E0, -0.9E0, 0.3E0, 0.7E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.6E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.5E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.3E0, 0.1E0, 0.5E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.8E0, 0.1E0, -0.6E0,\n     +                  0.8E0, 0.3E0, -0.3E0, 0.5E0, 0.6E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.5E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, -0.9E0,\n     +                  0.1E0, 0.5E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.7E0,\n     +                  0.1E0, 0.3E0, 0.8E0, -0.9E0, -0.3E0, 0.5E0,\n     +                  0.6E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.5E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.5E0, 0.3E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.5E0, 0.3E0, -0.6E0, 0.8E0, 0.0E0, 0.0E0,\n     +                  0.0E0/\n      DATA              DT10Y/0.5E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.6E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.6E0, 0.1E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.6E0, 0.1E0, -0.5E0, 0.8E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.5E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.6E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, -0.5E0, -0.9E0, 0.6E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, -0.4E0, -0.9E0, 0.9E0,\n     +                  0.7E0, -0.5E0, 0.2E0, 0.6E0, 0.5E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.6E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, -0.5E0,\n     +                  0.6E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  -0.4E0, 0.9E0, -0.5E0, 0.6E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.5E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.6E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.6E0, -0.9E0, 0.1E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.6E0, -0.9E0, 0.1E0, 0.7E0,\n     +                  -0.5E0, 0.2E0, 0.8E0/\n      DATA              SSIZE1/0.0E0, 0.3E0, 1.6E0, 3.2E0/\n      DATA              SSIZE2/0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 1.17E0, 1.17E0, 1.17E0, 1.17E0, 1.17E0,\n     +                  1.17E0, 1.17E0, 1.17E0, 1.17E0, 1.17E0, 1.17E0,\n     +                  1.17E0, 1.17E0, 1.17E0/\n      DATA              SSIZE3/ .1, .4, 1.7, 3.3 /\n*\n*                         FOR DROTM\n*\n      DATA DPAR/-2.E0,  0.E0,0.E0,0.E0,0.E0,\n     A          -1.E0,  2.E0, -3.E0, -4.E0,  5.E0,\n     B           0.E0,  0.E0,  2.E0, -3.E0,  0.E0,\n     C           1.E0,  5.E0,  2.E0,  0.E0, -4.E0/\n*                        TRUE X RESULTS F0R ROTATIONS DROTM\n      DATA DT19XA/.6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     A            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     B            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     C            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     D            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     E           -.8E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     F           -.9E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     G           3.5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     H            .6E0,   .1E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     I           -.8E0,  3.8E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     J           -.9E0,  2.8E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     K           3.5E0,  -.4E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     L            .6E0,   .1E0,  -.5E0,   .8E0,          0.E0,0.E0,0.E0,\n     M           -.8E0,  3.8E0, -2.2E0, -1.2E0,          0.E0,0.E0,0.E0,\n     N           -.9E0,  2.8E0, -1.4E0, -1.3E0,          0.E0,0.E0,0.E0,\n     O           3.5E0,  -.4E0, -2.2E0,  4.7E0,          0.E0,0.E0,0.E0/\n*\n      DATA DT19XB/.6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     A            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     B            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     C            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     D            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     E           -.8E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     F           -.9E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     G           3.5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     H            .6E0,   .1E0,  -.5E0,             0.E0,0.E0,0.E0,0.E0,\n     I           0.E0,    .1E0, -3.0E0,             0.E0,0.E0,0.E0,0.E0,\n     J           -.3E0,   .1E0, -2.0E0,             0.E0,0.E0,0.E0,0.E0,\n     K           3.3E0,   .1E0, -2.0E0,             0.E0,0.E0,0.E0,0.E0,\n     L            .6E0,   .1E0,  -.5E0,   .8E0,   .9E0,  -.3E0,  -.4E0,\n     M          -2.0E0,   .1E0,  1.4E0,   .8E0,   .6E0,  -.3E0, -2.8E0,\n     N          -1.8E0,   .1E0,  1.3E0,   .8E0,  0.E0,   -.3E0, -1.9E0,\n     O           3.8E0,   .1E0, -3.1E0,   .8E0,  4.8E0,  -.3E0, -1.5E0 /\n*\n      DATA DT19XC/.6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     A            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     B            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     C            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     D            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     E           -.8E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     F           -.9E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     G           3.5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     H            .6E0,   .1E0,  -.5E0,             0.E0,0.E0,0.E0,0.E0,\n     I           4.8E0,   .1E0, -3.0E0,             0.E0,0.E0,0.E0,0.E0,\n     J           3.3E0,   .1E0, -2.0E0,             0.E0,0.E0,0.E0,0.E0,\n     K           2.1E0,   .1E0, -2.0E0,             0.E0,0.E0,0.E0,0.E0,\n     L            .6E0,   .1E0,  -.5E0,   .8E0,   .9E0,  -.3E0,  -.4E0,\n     M          -1.6E0,   .1E0, -2.2E0,   .8E0,  5.4E0,  -.3E0, -2.8E0,\n     N          -1.5E0,   .1E0, -1.4E0,   .8E0,  3.6E0,  -.3E0, -1.9E0,\n     O           3.7E0,   .1E0, -2.2E0,   .8E0,  3.6E0,  -.3E0, -1.5E0 /\n*\n      DATA DT19XD/.6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     A            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     B            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     C            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     D            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     E           -.8E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     F           -.9E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     G           3.5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     H            .6E0,   .1E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     I           -.8E0, -1.0E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     J           -.9E0,  -.8E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     K           3.5E0,   .8E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     L            .6E0,   .1E0,  -.5E0,   .8E0,          0.E0,0.E0,0.E0,\n     M           -.8E0, -1.0E0,  1.4E0, -1.6E0,          0.E0,0.E0,0.E0,\n     N           -.9E0,  -.8E0,  1.3E0, -1.6E0,          0.E0,0.E0,0.E0,\n     O           3.5E0,   .8E0, -3.1E0,  4.8E0,          0.E0,0.E0,0.E0/\n*                        TRUE Y RESULTS FOR ROTATIONS DROTM\n      DATA DT19YA/.5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     A            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     B            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     C            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     D            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     E            .7E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     F           1.7E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     G          -2.6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     H            .5E0,  -.9E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     I            .7E0, -4.8E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     J           1.7E0,  -.7E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     K          -2.6E0,  3.5E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     L            .5E0,  -.9E0,   .3E0,   .7E0,          0.E0,0.E0,0.E0,\n     M            .7E0, -4.8E0,  3.0E0,  1.1E0,          0.E0,0.E0,0.E0,\n     N           1.7E0,  -.7E0,  -.7E0,  2.3E0,          0.E0,0.E0,0.E0,\n     O          -2.6E0,  3.5E0,  -.7E0, -3.6E0,          0.E0,0.E0,0.E0/\n*\n      DATA DT19YB/.5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     A            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     B            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     C            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     D            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     E            .7E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     F           1.7E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     G          -2.6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     H            .5E0,  -.9E0,   .3E0,             0.E0,0.E0,0.E0,0.E0,\n     I           4.0E0,  -.9E0,  -.3E0,             0.E0,0.E0,0.E0,0.E0,\n     J           -.5E0,  -.9E0,  1.5E0,             0.E0,0.E0,0.E0,0.E0,\n     K          -1.5E0,  -.9E0, -1.8E0,             0.E0,0.E0,0.E0,0.E0,\n     L            .5E0,  -.9E0,   .3E0,   .7E0,  -.6E0,   .2E0,   .8E0,\n     M           3.7E0,  -.9E0, -1.2E0,   .7E0, -1.5E0,   .2E0,  2.2E0,\n     N           -.3E0,  -.9E0,  2.1E0,   .7E0, -1.6E0,   .2E0,  2.0E0,\n     O          -1.6E0,  -.9E0, -2.1E0,   .7E0,  2.9E0,   .2E0, -3.8E0 /\n*\n      DATA DT19YC/.5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     A            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     B            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     C            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     D            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     E            .7E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     F           1.7E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     G          -2.6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     H            .5E0,  -.9E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     I           4.0E0, -6.3E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     J           -.5E0,   .3E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     K          -1.5E0,  3.0E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     L            .5E0,  -.9E0,   .3E0,   .7E0,          0.E0,0.E0,0.E0,\n     M           3.7E0, -7.2E0,  3.0E0,  1.7E0,          0.E0,0.E0,0.E0,\n     N           -.3E0,   .9E0,  -.7E0,  1.9E0,          0.E0,0.E0,0.E0,\n     O          -1.6E0,  2.7E0,  -.7E0, -3.4E0,          0.E0,0.E0,0.E0/\n*\n      DATA DT19YD/.5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     A            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     B            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     C            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     D            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     E            .7E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     F           1.7E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     G          -2.6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     H            .5E0,  -.9E0,   .3E0,             0.E0,0.E0,0.E0,0.E0,\n     I            .7E0,  -.9E0,  1.2E0,             0.E0,0.E0,0.E0,0.E0,\n     J           1.7E0,  -.9E0,   .5E0,             0.E0,0.E0,0.E0,0.E0,\n     K          -2.6E0,  -.9E0, -1.3E0,             0.E0,0.E0,0.E0,0.E0,\n     L            .5E0,  -.9E0,   .3E0,   .7E0,  -.6E0,   .2E0,   .8E0,\n     M            .7E0,  -.9E0,  1.2E0,   .7E0, -1.5E0,   .2E0,  1.6E0,\n     N           1.7E0,  -.9E0,   .5E0,   .7E0, -1.6E0,   .2E0,  2.4E0,\n     O          -2.6E0,  -.9E0, -1.3E0,   .7E0,  2.9E0,   .2E0, -4.0E0 /\n*\n*     .. Executable Statements ..\n*\n      DO 120 KI = 1, 4\n         INCX = INCXS(KI)\n         INCY = INCYS(KI)\n         MX = ABS(INCX)\n         MY = ABS(INCY)\n*\n         DO 100 KN = 1, 4\n            N = NS(KN)\n            KSIZE = MIN(2,KN)\n            LENX = LENS(KN,MX)\n            LENY = LENS(KN,MY)\n*           .. Initialize all argument arrays ..\n            DO 20 I = 1, 7\n               SX(I) = DX1(I)\n               SY(I) = DY1(I)\n   20       CONTINUE\n*\n            IF (ICASE.EQ.1) THEN\n*              .. SDOT ..\n               CALL STEST1(SDOT(N,SX,INCX,SY,INCY),DT7(KN,KI),SSIZE1(KN)\n     +                     ,SFAC)\n            ELSE IF (ICASE.EQ.2) THEN\n*              .. SAXPY ..\n               CALL SAXPY(N,SA,SX,INCX,SY,INCY)\n               DO 40 J = 1, LENY\n                  STY(J) = DT8(J,KN,KI)\n   40          CONTINUE\n               CALL STEST(LENY,SY,STY,SSIZE2(1,KSIZE),SFAC)\n            ELSE IF (ICASE.EQ.5) THEN\n*              .. SCOPY ..\n               DO 60 I = 1, 7\n                  STY(I) = DT10Y(I,KN,KI)\n   60          CONTINUE\n               CALL SCOPY(N,SX,INCX,SY,INCY)\n               CALL STEST(LENY,SY,STY,SSIZE2(1,1),1.0E0)\n            ELSE IF (ICASE.EQ.6) THEN\n*              .. SSWAP ..\n               CALL SSWAP(N,SX,INCX,SY,INCY)\n               DO 80 I = 1, 7\n                  STX(I) = DT10X(I,KN,KI)\n                  STY(I) = DT10Y(I,KN,KI)\n   80          CONTINUE\n               CALL STEST(LENX,SX,STX,SSIZE2(1,1),1.0E0)\n               CALL STEST(LENY,SY,STY,SSIZE2(1,1),1.0E0)\n            ELSEIF (ICASE.EQ.12) THEN\n*              .. SROTM ..\n               KNI=KN+4*(KI-1)\n               DO KPAR=1,4\n                  DO I=1,7\n                     SX(I) = DX1(I)\n                     SY(I) = DY1(I)\n                     STX(I)= DT19X(I,KPAR,KNI)\n                     STY(I)= DT19Y(I,KPAR,KNI)\n                  END DO\n*\n                  DO I=1,5\n                     DTEMP(I) = DPAR(I,KPAR)\n                  END DO\n*\n                  DO  I=1,LENX\n                     SSIZE(I)=STX(I)\n                  END DO\n*                   SEE REMARK ABOVE ABOUT DT11X(1,2,7)\n*                       AND DT11X(5,3,8).\n                  IF ((KPAR .EQ. 2) .AND. (KNI .EQ. 7))\n     $               SSIZE(1) = 2.4E0\n                  IF ((KPAR .EQ. 3) .AND. (KNI .EQ. 8))\n     $               SSIZE(5) = 1.8E0\n*\n                  CALL   SROTM(N,SX,INCX,SY,INCY,DTEMP)\n                  CALL   STEST(LENX,SX,STX,SSIZE,SFAC)\n                  CALL   STEST(LENY,SY,STY,STY,SFAC)\n               END DO\n            ELSEIF (ICASE.EQ.13) THEN\n*              .. SDSROT ..\n               CALL STEST1 (SDSDOT(N,.1,SX,INCX,SY,INCY),\n     $                 ST7B(KN,KI),SSIZE3(KN),SFAC)\n            ELSE\n               WRITE (NOUT,*) ' Shouldn''t be here in CHECK2'\n               STOP\n            END IF\n  100    CONTINUE\n  120 CONTINUE\n      RETURN\n      END\n      SUBROUTINE CHECK3(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      REAL              SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      REAL              SC, SS\n      INTEGER           I, K, KI, KN, KSIZE, LENX, LENY, MX, MY\n*     .. Local Arrays ..\n      REAL              COPYX(5), COPYY(5), DT9X(7,4,4), DT9Y(7,4,4),\n     +                  DX1(7), DY1(7), MWPC(11), MWPS(11), MWPSTX(5),\n     +                  MWPSTY(5), MWPTX(11,5), MWPTY(11,5), MWPX(5),\n     +                  MWPY(5), SSIZE2(14,2), STX(7), STY(7), SX(7),\n     +                  SY(7)\n      INTEGER           INCXS(4), INCYS(4), LENS(4,2), MWPINX(11),\n     +                  MWPINY(11), MWPN(11), NS(4)\n*     .. External Subroutines ..\n      EXTERNAL          SROT, STEST\n*     .. Intrinsic Functions ..\n      INTRINSIC         ABS, MIN\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      DATA              INCXS/1, 2, -2, -1/\n      DATA              INCYS/1, -2, 1, -2/\n      DATA              LENS/1, 1, 2, 4, 1, 1, 3, 7/\n      DATA              NS/0, 1, 2, 4/\n      DATA              DX1/0.6E0, 0.1E0, -0.5E0, 0.8E0, 0.9E0, -0.3E0,\n     +                  -0.4E0/\n      DATA              DY1/0.5E0, -0.9E0, 0.3E0, 0.7E0, -0.6E0, 0.2E0,\n     +                  0.8E0/\n      DATA              SC, SS/0.8E0, 0.6E0/\n      DATA              DT9X/0.6E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.78E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.78E0, -0.46E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.78E0, -0.46E0, -0.22E0,\n     +                  1.06E0, 0.0E0, 0.0E0, 0.0E0, 0.6E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.78E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.66E0, 0.1E0, -0.1E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.96E0, 0.1E0, -0.76E0, 0.8E0, 0.90E0,\n     +                  -0.3E0, -0.02E0, 0.6E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.78E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, -0.06E0, 0.1E0,\n     +                  -0.1E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.90E0,\n     +                  0.1E0, -0.22E0, 0.8E0, 0.18E0, -0.3E0, -0.02E0,\n     +                  0.6E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.78E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.78E0, 0.26E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.78E0, 0.26E0, -0.76E0, 1.12E0,\n     +                  0.0E0, 0.0E0, 0.0E0/\n      DATA              DT9Y/0.5E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.04E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.04E0, -0.78E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.04E0, -0.78E0, 0.54E0,\n     +                  0.08E0, 0.0E0, 0.0E0, 0.0E0, 0.5E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.04E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.7E0,\n     +                  -0.9E0, -0.12E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.64E0, -0.9E0, -0.30E0, 0.7E0, -0.18E0, 0.2E0,\n     +                  0.28E0, 0.5E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.04E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.7E0, -1.08E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.64E0, -1.26E0,\n     +                  0.54E0, 0.20E0, 0.0E0, 0.0E0, 0.0E0, 0.5E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.04E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.04E0, -0.9E0, 0.18E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.04E0, -0.9E0, 0.18E0, 0.7E0,\n     +                  -0.18E0, 0.2E0, 0.16E0/\n      DATA              SSIZE2/0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 1.17E0, 1.17E0, 1.17E0, 1.17E0, 1.17E0,\n     +                  1.17E0, 1.17E0, 1.17E0, 1.17E0, 1.17E0, 1.17E0,\n     +                  1.17E0, 1.17E0, 1.17E0/\n*     .. Executable Statements ..\n*\n      DO 60 KI = 1, 4\n         INCX = INCXS(KI)\n         INCY = INCYS(KI)\n         MX = ABS(INCX)\n         MY = ABS(INCY)\n*\n         DO 40 KN = 1, 4\n            N = NS(KN)\n            KSIZE = MIN(2,KN)\n            LENX = LENS(KN,MX)\n            LENY = LENS(KN,MY)\n*\n            IF (ICASE.EQ.4) THEN\n*              .. SROT ..\n               DO 20 I = 1, 7\n                  SX(I) = DX1(I)\n                  SY(I) = DY1(I)\n                  STX(I) = DT9X(I,KN,KI)\n                  STY(I) = DT9Y(I,KN,KI)\n   20          CONTINUE\n               CALL SROT(N,SX,INCX,SY,INCY,SC,SS)\n               CALL STEST(LENX,SX,STX,SSIZE2(1,KSIZE),SFAC)\n               CALL STEST(LENY,SY,STY,SSIZE2(1,KSIZE),SFAC)\n            ELSE\n               WRITE (NOUT,*) ' Shouldn''t be here in CHECK3'\n               STOP\n            END IF\n   40    CONTINUE\n   60 CONTINUE\n*\n      MWPC(1) = 1\n      DO 80 I = 2, 11\n         MWPC(I) = 0\n   80 CONTINUE\n      MWPS(1) = 0\n      DO 100 I = 2, 6\n         MWPS(I) = 1\n  100 CONTINUE\n      DO 120 I = 7, 11\n         MWPS(I) = -1\n  120 CONTINUE\n      MWPINX(1) = 1\n      MWPINX(2) = 1\n      MWPINX(3) = 1\n      MWPINX(4) = -1\n      MWPINX(5) = 1\n      MWPINX(6) = -1\n      MWPINX(7) = 1\n      MWPINX(8) = 1\n      MWPINX(9) = -1\n      MWPINX(10) = 1\n      MWPINX(11) = -1\n      MWPINY(1) = 1\n      MWPINY(2) = 1\n      MWPINY(3) = -1\n      MWPINY(4) = -1\n      MWPINY(5) = 2\n      MWPINY(6) = 1\n      MWPINY(7) = 1\n      MWPINY(8) = -1\n      MWPINY(9) = -1\n      MWPINY(10) = 2\n      MWPINY(11) = 1\n      DO 140 I = 1, 11\n         MWPN(I) = 5\n  140 CONTINUE\n      MWPN(5) = 3\n      MWPN(10) = 3\n      DO 160 I = 1, 5\n         MWPX(I) = I\n         MWPY(I) = I\n         MWPTX(1,I) = I\n         MWPTY(1,I) = I\n         MWPTX(2,I) = I\n         MWPTY(2,I) = -I\n         MWPTX(3,I) = 6 - I\n         MWPTY(3,I) = I - 6\n         MWPTX(4,I) = I\n         MWPTY(4,I) = -I\n         MWPTX(6,I) = 6 - I\n         MWPTY(6,I) = I - 6\n         MWPTX(7,I) = -I\n         MWPTY(7,I) = I\n         MWPTX(8,I) = I - 6\n         MWPTY(8,I) = 6 - I\n         MWPTX(9,I) = -I\n         MWPTY(9,I) = I\n         MWPTX(11,I) = I - 6\n         MWPTY(11,I) = 6 - I\n  160 CONTINUE\n      MWPTX(5,1) = 1\n      MWPTX(5,2) = 3\n      MWPTX(5,3) = 5\n      MWPTX(5,4) = 4\n      MWPTX(5,5) = 5\n      MWPTY(5,1) = -1\n      MWPTY(5,2) = 2\n      MWPTY(5,3) = -2\n      MWPTY(5,4) = 4\n      MWPTY(5,5) = -3\n      MWPTX(10,1) = -1\n      MWPTX(10,2) = -3\n      MWPTX(10,3) = -5\n      MWPTX(10,4) = 4\n      MWPTX(10,5) = 5\n      MWPTY(10,1) = 1\n      MWPTY(10,2) = 2\n      MWPTY(10,3) = 2\n      MWPTY(10,4) = 4\n      MWPTY(10,5) = 3\n      DO 200 I = 1, 11\n         INCX = MWPINX(I)\n         INCY = MWPINY(I)\n         DO 180 K = 1, 5\n            COPYX(K) = MWPX(K)\n            COPYY(K) = MWPY(K)\n            MWPSTX(K) = MWPTX(I,K)\n            MWPSTY(K) = MWPTY(I,K)\n  180    CONTINUE\n         CALL SROT(MWPN(I),COPYX,INCX,COPYY,INCY,MWPC(I),MWPS(I))\n         CALL STEST(5,COPYX,MWPSTX,MWPSTX,SFAC)\n         CALL STEST(5,COPYY,MWPSTY,MWPSTY,SFAC)\n  200 CONTINUE\n      RETURN\n      END\n      SUBROUTINE STEST(LEN,SCOMP,STRUE,SSIZE,SFAC)\n*     ********************************* STEST **************************\n*\n*     THIS SUBR COMPARES ARRAYS  SCOMP() AND STRUE() OF LENGTH LEN TO\n*     SEE IF THE TERM BY TERM DIFFERENCES, MULTIPLIED BY SFAC, ARE\n*     NEGLIGIBLE.\n*\n*     C. L. LAWSON, JPL, 1974 DEC 10\n*\n*     .. Parameters ..\n      INTEGER          NOUT\n      REAL             ZERO\n      PARAMETER        (NOUT=6, ZERO=0.0E0)\n*     .. Scalar Arguments ..\n      REAL             SFAC\n      INTEGER          LEN\n*     .. Array Arguments ..\n      REAL             SCOMP(LEN), SSIZE(LEN), STRUE(LEN)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, N\n      LOGICAL          PASS\n*     .. Local Scalars ..\n      REAL             SD\n      INTEGER          I\n*     .. External Functions ..\n      REAL             SDIFF\n      EXTERNAL         SDIFF\n*     .. Intrinsic Functions ..\n      INTRINSIC        ABS\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Executable Statements ..\n*\n      DO 40 I = 1, LEN\n         SD = SCOMP(I) - STRUE(I)\n         IF (ABS(SFAC*SD) .LE. ABS(SSIZE(I))*EPSILON(ZERO))\n     +       GO TO 40\n*\n*                             HERE    SCOMP(I) IS NOT CLOSE TO STRUE(I).\n*\n         IF ( .NOT. PASS) GO TO 20\n*                             PRINT FAIL MESSAGE AND HEADER.\n         PASS = .FALSE.\n         WRITE (NOUT,99999)\n         WRITE (NOUT,99998)\n   20    WRITE (NOUT,99997) ICASE, N, INCX, INCY, I, SCOMP(I),\n     +     STRUE(I), SD, SSIZE(I)\n   40 CONTINUE\n      RETURN\n*\n99999 FORMAT ('                                       FAIL')\n99998 FORMAT (/' CASE  N INCX INCY  I                            ',\n     +       ' COMP(I)                             TRUE(I)  DIFFERENCE',\n     +       '     SIZE(I)',/1X)\n99997 FORMAT (1X,I4,I3,2I5,I3,2E36.8,2E12.4)\n      END\n      SUBROUTINE STEST1(SCOMP1,STRUE1,SSIZE,SFAC)\n*     ************************* STEST1 *****************************\n*\n*     THIS IS AN INTERFACE SUBROUTINE TO ACCOMMODATE THE FORTRAN\n*     REQUIREMENT THAT WHEN A DUMMY ARGUMENT IS AN ARRAY, THE\n*     ACTUAL ARGUMENT MUST ALSO BE AN ARRAY OR AN ARRAY ELEMENT.\n*\n*     C.L. LAWSON, JPL, 1978 DEC 6\n*\n*     .. Scalar Arguments ..\n      REAL              SCOMP1, SFAC, STRUE1\n*     .. Array Arguments ..\n      REAL              SSIZE(*)\n*     .. Local Arrays ..\n      REAL              SCOMP(1), STRUE(1)\n*     .. External Subroutines ..\n      EXTERNAL          STEST\n*     .. Executable Statements ..\n*\n      SCOMP(1) = SCOMP1\n      STRUE(1) = STRUE1\n      CALL STEST(1,SCOMP,STRUE,SSIZE,SFAC)\n*\n      RETURN\n      END\n      REAL             FUNCTION SDIFF(SA,SB)\n*     ********************************* SDIFF **************************\n*     COMPUTES DIFFERENCE OF TWO NUMBERS.  C. L. LAWSON, JPL 1974 FEB 15\n*\n*     .. Scalar Arguments ..\n      REAL                            SA, SB\n*     .. Executable Statements ..\n      SDIFF = SA - SB\n      RETURN\n      END\n      SUBROUTINE ITEST1(ICOMP,ITRUE)\n*     ********************************* ITEST1 *************************\n*\n*     THIS SUBROUTINE COMPARES THE VARIABLES ICOMP AND ITRUE FOR\n*     EQUALITY.\n*     C. L. LAWSON, JPL, 1974 DEC 10\n*\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      INTEGER           ICOMP, ITRUE\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      INTEGER           ID\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Executable Statements ..\n*\n      IF (ICOMP.EQ.ITRUE) GO TO 40\n*\n*                            HERE ICOMP IS NOT EQUAL TO ITRUE.\n*\n      IF ( .NOT. PASS) GO TO 20\n*                             PRINT FAIL MESSAGE AND HEADER.\n      PASS = .FALSE.\n      WRITE (NOUT,99999)\n      WRITE (NOUT,99998)\n   20 ID = ICOMP - ITRUE\n      WRITE (NOUT,99997) ICASE, N, INCX, INCY, ICOMP, ITRUE, ID\n   40 CONTINUE\n      RETURN\n*\n99999 FORMAT ('                                       FAIL')\n99998 FORMAT (/' CASE  N INCX INCY                               ',\n     +       ' COMP                                TRUE     DIFFERENCE',\n     +       /1X)\n99997 FORMAT (1X,I4,I3,2I5,2I36,I12)\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/testing/sblat2.f",
    "content": "*> \\brief \\b SBLAT2\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM SBLAT2\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> Test program for the REAL Level 2 Blas.\n*>\n*> The program must be driven by a short data file. The first 18 records\n*> of the file are read using list-directed input, the last 16 records\n*> are read using the format ( A6, L2 ). An annotated example of a data\n*> file can be obtained by deleting the first 3 characters from the\n*> following 34 lines:\n*> 'sblat2.out'      NAME OF SUMMARY OUTPUT FILE\n*> 6                 UNIT NUMBER OF SUMMARY FILE\n*> 'SBLAT2.SNAP'     NAME OF SNAPSHOT OUTPUT FILE\n*> -1                UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0)\n*> F        LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD.\n*> F        LOGICAL FLAG, T TO STOP ON FAILURES.\n*> T        LOGICAL FLAG, T TO TEST ERROR EXITS.\n*> 16.0     THRESHOLD VALUE OF TEST RATIO\n*> 6                 NUMBER OF VALUES OF N\n*> 0 1 2 3 5 9       VALUES OF N\n*> 4                 NUMBER OF VALUES OF K\n*> 0 1 2 4           VALUES OF K\n*> 4                 NUMBER OF VALUES OF INCX AND INCY\n*> 1 2 -1 -2         VALUES OF INCX AND INCY\n*> 3                 NUMBER OF VALUES OF ALPHA\n*> 0.0 1.0 0.7       VALUES OF ALPHA\n*> 3                 NUMBER OF VALUES OF BETA\n*> 0.0 1.0 0.9       VALUES OF BETA\n*> SGEMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> SGBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> SSYMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> SSBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> SSPMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> STRMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> STBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> STPMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> STRSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> STBSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> STPSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> SGER   T PUT F FOR NO TEST. SAME COLUMNS.\n*> SSYR   T PUT F FOR NO TEST. SAME COLUMNS.\n*> SSPR   T PUT F FOR NO TEST. SAME COLUMNS.\n*> SSYR2  T PUT F FOR NO TEST. SAME COLUMNS.\n*> SSPR2  T PUT F FOR NO TEST. SAME COLUMNS.\n*>\n*> Further Details\n*> ===============\n*>\n*>    See:\n*>\n*>       Dongarra J. J., Du Croz J. J., Hammarling S.  and Hanson R. J..\n*>       An  extended  set of Fortran  Basic Linear Algebra Subprograms.\n*>\n*>       Technical  Memoranda  Nos. 41 (revision 3) and 81,  Mathematics\n*>       and  Computer Science  Division,  Argonne  National Laboratory,\n*>       9700 South Cass Avenue, Argonne, Illinois 60439, US.\n*>\n*>       Or\n*>\n*>       NAG  Technical Reports TR3/87 and TR4/87,  Numerical Algorithms\n*>       Group  Ltd.,  NAG  Central  Office,  256  Banbury  Road, Oxford\n*>       OX2 7DE, UK,  and  Numerical Algorithms Group Inc.,  1101  31st\n*>       Street,  Suite 100,  Downers Grove,  Illinois 60515-1263,  USA.\n*>\n*>\n*> -- Written on 10-August-1987.\n*>    Richard Hanson, Sandia National Labs.\n*>    Jeremy Du Croz, NAG Central Office.\n*>\n*>    10-9-00:  Change STATUS='NEW' to 'UNKNOWN' so that the testers\n*>              can be run multiple times without deleting generated\n*>              output files (susan)\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup single_blas_testing\n*\n*  =====================================================================\n      PROGRAM SBLAT2\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER            NIN\n      PARAMETER          ( NIN = 5 )\n      INTEGER            NSUBS\n      PARAMETER          ( NSUBS = 16 )\n      REAL               ZERO, ONE\n      PARAMETER          ( ZERO = 0.0, ONE = 1.0 )\n      INTEGER            NMAX, INCMAX\n      PARAMETER          ( NMAX = 65, INCMAX = 2 )\n      INTEGER            NINMAX, NIDMAX, NKBMAX, NALMAX, NBEMAX\n      PARAMETER          ( NINMAX = 7, NIDMAX = 9, NKBMAX = 7,\n     $                   NALMAX = 7, NBEMAX = 7 )\n*     .. Local Scalars ..\n      REAL               EPS, ERR, THRESH\n      INTEGER            I, ISNUM, J, N, NALF, NBET, NIDIM, NINC, NKB,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, LTESTT, REWI, SAME, SFATAL, TRACE,\n     $                   TSTERR\n      CHARACTER*1        TRANS\n      CHARACTER*6        SNAMET\n      CHARACTER*32       SNAPS, SUMMRY\n*     .. Local Arrays ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ),\n     $                   ALF( NALMAX ), AS( NMAX*NMAX ), BET( NBEMAX ),\n     $                   G( NMAX ), X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( 2*NMAX )\n      INTEGER            IDIM( NIDMAX ), INC( NINMAX ), KB( NKBMAX )\n      LOGICAL            LTEST( NSUBS )\n      CHARACTER*6        SNAMES( NSUBS )\n*     .. External Functions ..\n      REAL               SDIFF\n      LOGICAL            LSE\n      EXTERNAL           SDIFF, LSE\n*     .. External Subroutines ..\n      EXTERNAL           SCHK1, SCHK2, SCHK3, SCHK4, SCHK5, SCHK6,\n     $                   SCHKE, SMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Data statements ..\n      DATA               SNAMES/'SGEMV ', 'SGBMV ', 'SSYMV ', 'SSBMV ',\n     $                   'SSPMV ', 'STRMV ', 'STBMV ', 'STPMV ',\n     $                   'STRSV ', 'STBSV ', 'STPSV ', 'SGER  ',\n     $                   'SSYR  ', 'SSPR  ', 'SSYR2 ', 'SSPR2 '/\n*     .. Executable Statements ..\n*\n*     Read name and unit number for summary output file and open file.\n*\n      READ( NIN, FMT = * )SUMMRY\n      READ( NIN, FMT = * )NOUT\n      OPEN( NOUT, FILE = SUMMRY, STATUS = 'UNKNOWN' )\n      NOUTC = NOUT\n*\n*     Read name and unit number for snapshot output file and open file.\n*\n      READ( NIN, FMT = * )SNAPS\n      READ( NIN, FMT = * )NTRA\n      TRACE = NTRA.GE.0\n      IF( TRACE )THEN\n         OPEN( NTRA, FILE = SNAPS, STATUS = 'UNKNOWN' )\n      END IF\n*     Read the flag that directs rewinding of the snapshot file.\n      READ( NIN, FMT = * )REWI\n      REWI = REWI.AND.TRACE\n*     Read the flag that directs stopping on any failure.\n      READ( NIN, FMT = * )SFATAL\n*     Read the flag that indicates whether error exits are to be tested.\n      READ( NIN, FMT = * )TSTERR\n*     Read the threshold value of the test ratio\n      READ( NIN, FMT = * )THRESH\n*\n*     Read and check the parameter values for the tests.\n*\n*     Values of N\n      READ( NIN, FMT = * )NIDIM\n      IF( NIDIM.LT.1.OR.NIDIM.GT.NIDMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'N', NIDMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( IDIM( I ), I = 1, NIDIM )\n      DO 10 I = 1, NIDIM\n         IF( IDIM( I ).LT.0.OR.IDIM( I ).GT.NMAX )THEN\n            WRITE( NOUT, FMT = 9996 )NMAX\n            GO TO 230\n         END IF\n   10 CONTINUE\n*     Values of K\n      READ( NIN, FMT = * )NKB\n      IF( NKB.LT.1.OR.NKB.GT.NKBMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'K', NKBMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( KB( I ), I = 1, NKB )\n      DO 20 I = 1, NKB\n         IF( KB( I ).LT.0 )THEN\n            WRITE( NOUT, FMT = 9995 )\n            GO TO 230\n         END IF\n   20 CONTINUE\n*     Values of INCX and INCY\n      READ( NIN, FMT = * )NINC\n      IF( NINC.LT.1.OR.NINC.GT.NINMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'INCX AND INCY', NINMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( INC( I ), I = 1, NINC )\n      DO 30 I = 1, NINC\n         IF( INC( I ).EQ.0.OR.ABS( INC( I ) ).GT.INCMAX )THEN\n            WRITE( NOUT, FMT = 9994 )INCMAX\n            GO TO 230\n         END IF\n   30 CONTINUE\n*     Values of ALPHA\n      READ( NIN, FMT = * )NALF\n      IF( NALF.LT.1.OR.NALF.GT.NALMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'ALPHA', NALMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( ALF( I ), I = 1, NALF )\n*     Values of BETA\n      READ( NIN, FMT = * )NBET\n      IF( NBET.LT.1.OR.NBET.GT.NBEMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'BETA', NBEMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( BET( I ), I = 1, NBET )\n*\n*     Report values of parameters.\n*\n      WRITE( NOUT, FMT = 9993 )\n      WRITE( NOUT, FMT = 9992 )( IDIM( I ), I = 1, NIDIM )\n      WRITE( NOUT, FMT = 9991 )( KB( I ), I = 1, NKB )\n      WRITE( NOUT, FMT = 9990 )( INC( I ), I = 1, NINC )\n      WRITE( NOUT, FMT = 9989 )( ALF( I ), I = 1, NALF )\n      WRITE( NOUT, FMT = 9988 )( BET( I ), I = 1, NBET )\n      IF( .NOT.TSTERR )THEN\n         WRITE( NOUT, FMT = * )\n         WRITE( NOUT, FMT = 9980 )\n      END IF\n      WRITE( NOUT, FMT = * )\n      WRITE( NOUT, FMT = 9999 )THRESH\n      WRITE( NOUT, FMT = * )\n*\n*     Read names of subroutines and flags which indicate\n*     whether they are to be tested.\n*\n      DO 40 I = 1, NSUBS\n         LTEST( I ) = .FALSE.\n   40 CONTINUE\n   50 READ( NIN, FMT = 9984, END = 80 )SNAMET, LTESTT\n      DO 60 I = 1, NSUBS\n         IF( SNAMET.EQ.SNAMES( I ) )\n     $      GO TO 70\n   60 CONTINUE\n      WRITE( NOUT, FMT = 9986 )SNAMET\n      STOP\n   70 LTEST( I ) = LTESTT\n      GO TO 50\n*\n   80 CONTINUE\n      CLOSE ( NIN )\n*\n*     Compute EPS (the machine precision).\n*\n      EPS = EPSILON(ZERO)\n      WRITE( NOUT, FMT = 9998 )EPS\n*\n*     Check the reliability of SMVCH using exact data.\n*\n      N = MIN( 32, NMAX )\n      DO 120 J = 1, N\n         DO 110 I = 1, N\n            A( I, J ) = MAX( I - J + 1, 0 )\n  110    CONTINUE\n         X( J ) = J\n         Y( J ) = ZERO\n  120 CONTINUE\n      DO 130 J = 1, N\n         YY( J ) = J*( ( J + 1 )*J )/2 - ( ( J + 1 )*J*( J - 1 ) )/3\n  130 CONTINUE\n*     YY holds the exact result. On exit from SMVCH YT holds\n*     the result computed by SMVCH.\n      TRANS = 'N'\n      CALL SMVCH( TRANS, N, N, ONE, A, NMAX, X, 1, ZERO, Y, 1, YT, G,\n     $            YY, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LSE( YY, YT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9985 )TRANS, SAME, ERR\n         STOP\n      END IF\n      TRANS = 'T'\n      CALL SMVCH( TRANS, N, N, ONE, A, NMAX, X, -1, ZERO, Y, -1, YT, G,\n     $            YY, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LSE( YY, YT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9985 )TRANS, SAME, ERR\n         STOP\n      END IF\n*\n*     Test each subroutine in turn.\n*\n      DO 210 ISNUM = 1, NSUBS\n         WRITE( NOUT, FMT = * )\n         IF( .NOT.LTEST( ISNUM ) )THEN\n*           Subprogram is not to be tested.\n            WRITE( NOUT, FMT = 9983 )SNAMES( ISNUM )\n         ELSE\n            SRNAMT = SNAMES( ISNUM )\n*           Test error exits.\n            IF( TSTERR )THEN\n               CALL SCHKE( ISNUM, SNAMES( ISNUM ), NOUT )\n               WRITE( NOUT, FMT = * )\n            END IF\n*           Test computations.\n            INFOT = 0\n            OK = .TRUE.\n            FATAL = .FALSE.\n            GO TO ( 140, 140, 150, 150, 150, 160, 160,\n     $              160, 160, 160, 160, 170, 180, 180,\n     $              190, 190 )ISNUM\n*           Test SGEMV, 01, and SGBMV, 02.\n  140       CALL SCHK1( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF,\n     $                  NBET, BET, NINC, INC, NMAX, INCMAX, A, AA, AS,\n     $                  X, XX, XS, Y, YY, YS, YT, G )\n            GO TO 200\n*           Test SSYMV, 03, SSBMV, 04, and SSPMV, 05.\n  150       CALL SCHK2( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF,\n     $                  NBET, BET, NINC, INC, NMAX, INCMAX, A, AA, AS,\n     $                  X, XX, XS, Y, YY, YS, YT, G )\n            GO TO 200\n*           Test STRMV, 06, STBMV, 07, STPMV, 08,\n*           STRSV, 09, STBSV, 10, and STPSV, 11.\n  160       CALL SCHK3( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, Y, YY, YS, YT, G, Z )\n            GO TO 200\n*           Test SGER, 12.\n  170       CALL SCHK4( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n            GO TO 200\n*           Test SSYR, 13, and SSPR, 14.\n  180       CALL SCHK5( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n            GO TO 200\n*           Test SSYR2, 15, and SSPR2, 16.\n  190       CALL SCHK6( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n*\n  200       IF( FATAL.AND.SFATAL )\n     $         GO TO 220\n         END IF\n  210 CONTINUE\n      WRITE( NOUT, FMT = 9982 )\n      GO TO 240\n*\n  220 CONTINUE\n      WRITE( NOUT, FMT = 9981 )\n      GO TO 240\n*\n  230 CONTINUE\n      WRITE( NOUT, FMT = 9987 )\n*\n  240 CONTINUE\n      IF( TRACE )\n     $   CLOSE ( NTRA )\n      CLOSE ( NOUT )\n      STOP\n*\n 9999 FORMAT( ' ROUTINES PASS COMPUTATIONAL TESTS IF TEST RATIO IS LES',\n     $      'S THAN', F8.2 )\n 9998 FORMAT( ' RELATIVE MACHINE PRECISION IS TAKEN TO BE', 1P, E9.1 )\n 9997 FORMAT( ' NUMBER OF VALUES OF ', A, ' IS LESS THAN 1 OR GREATER ',\n     $      'THAN ', I2 )\n 9996 FORMAT( ' VALUE OF N IS LESS THAN 0 OR GREATER THAN ', I2 )\n 9995 FORMAT( ' VALUE OF K IS LESS THAN 0' )\n 9994 FORMAT( ' ABSOLUTE VALUE OF INCX OR INCY IS 0 OR GREATER THAN ',\n     $      I2 )\n 9993 FORMAT( ' TESTS OF THE REAL             LEVEL 2 BLAS', //' THE F',\n     $      'OLLOWING PARAMETER VALUES WILL BE USED:' )\n 9992 FORMAT( '   FOR N              ', 9I6 )\n 9991 FORMAT( '   FOR K              ', 7I6 )\n 9990 FORMAT( '   FOR INCX AND INCY  ', 7I6 )\n 9989 FORMAT( '   FOR ALPHA          ', 7F6.1 )\n 9988 FORMAT( '   FOR BETA           ', 7F6.1 )\n 9987 FORMAT( ' AMEND DATA FILE OR INCREASE ARRAY SIZES IN PROGRAM',\n     $      /' ******* TESTS ABANDONED *******' )\n 9986 FORMAT( ' SUBPROGRAM NAME ', A6, ' NOT RECOGNIZED', /' ******* T',\n     $      'ESTS ABANDONED *******' )\n 9985 FORMAT( ' ERROR IN SMVCH -  IN-LINE DOT PRODUCTS ARE BEING EVALU',\n     $      'ATED WRONGLY.', /' SMVCH WAS CALLED WITH TRANS = ', A1,\n     $      ' AND RETURNED SAME = ', L1, ' AND ERR = ', F12.3, '.', /\n     $   ' THIS MAY BE DUE TO FAULTS IN THE ARITHMETIC OR THE COMPILER.'\n     $      , /' ******* TESTS ABANDONED *******' )\n 9984 FORMAT( A6, L2 )\n 9983 FORMAT( 1X, A6, ' WAS NOT TESTED' )\n 9982 FORMAT( /' END OF TESTS' )\n 9981 FORMAT( /' ******* FATAL ERROR - TESTS ABANDONED *******' )\n 9980 FORMAT( ' ERROR-EXITS WILL NOT BE TESTED' )\n*\n*     End of SBLAT2.\n*\n      END\n      SUBROUTINE SCHK1( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF, NBET,\n     $                  BET, NINC, INC, NMAX, INCMAX, A, AA, AS, X, XX,\n     $                  XS, Y, YY, YS, YT, G )\n*\n*  Tests SGEMV and SGBMV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      REAL               ZERO, HALF\n      PARAMETER          ( ZERO = 0.0, HALF = 0.5 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NALF, NBET, NIDIM, NINC, NKB, NMAX,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), BET( NBET ), G( NMAX ),\n     $                   X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      REAL               ALPHA, ALS, BETA, BLS, ERR, ERRMAX, TRANSL\n      INTEGER            I, IA, IB, IC, IKU, IM, IN, INCX, INCXS, INCY,\n     $                   INCYS, IX, IY, KL, KLS, KU, KUS, LAA, LDA,\n     $                   LDAS, LX, LY, M, ML, MS, N, NARGS, NC, ND, NK,\n     $                   NL, NS\n      LOGICAL            BANDED, FULL, NULL, RESET, SAME, TRAN\n      CHARACTER*1        TRANS, TRANSS\n      CHARACTER*3        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SGBMV, SGEMV, SMAKE, SMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'NTC'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'E'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 11\n      ELSE IF( BANDED )THEN\n         NARGS = 13\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 120 IN = 1, NIDIM\n         N = IDIM( IN )\n         ND = N/2 + 1\n*\n         DO 110 IM = 1, 2\n            IF( IM.EQ.1 )\n     $         M = MAX( N - ND, 0 )\n            IF( IM.EQ.2 )\n     $         M = MIN( N + ND, NMAX )\n*\n            IF( BANDED )THEN\n               NK = NKB\n            ELSE\n               NK = 1\n            END IF\n            DO 100 IKU = 1, NK\n               IF( BANDED )THEN\n                  KU = KB( IKU )\n                  KL = MAX( KU - 1, 0 )\n               ELSE\n                  KU = N - 1\n                  KL = M - 1\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               IF( BANDED )THEN\n                  LDA = KL + KU + 1\n               ELSE\n                  LDA = M\n               END IF\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 100\n               LAA = LDA*N\n               NULL = N.LE.0.OR.M.LE.0\n*\n*              Generate the matrix A.\n*\n               TRANSL = ZERO\n               CALL SMAKE( SNAME( 2: 3 ), ' ', ' ', M, N, A, NMAX, AA,\n     $                     LDA, KL, KU, RESET, TRANSL )\n*\n               DO 90 IC = 1, 3\n                  TRANS = ICH( IC: IC )\n                  TRAN = TRANS.EQ.'T'.OR.TRANS.EQ.'C'\n*\n                  IF( TRAN )THEN\n                     ML = N\n                     NL = M\n                  ELSE\n                     ML = M\n                     NL = N\n                  END IF\n*\n                  DO 80 IX = 1, NINC\n                     INCX = INC( IX )\n                     LX = ABS( INCX )*NL\n*\n*                    Generate the vector X.\n*\n                     TRANSL = HALF\n                     CALL SMAKE( 'GE', ' ', ' ', 1, NL, X, 1, XX,\n     $                           ABS( INCX ), 0, NL - 1, RESET, TRANSL )\n                     IF( NL.GT.1 )THEN\n                        X( NL/2 ) = ZERO\n                        XX( 1 + ABS( INCX )*( NL/2 - 1 ) ) = ZERO\n                     END IF\n*\n                     DO 70 IY = 1, NINC\n                        INCY = INC( IY )\n                        LY = ABS( INCY )*ML\n*\n                        DO 60 IA = 1, NALF\n                           ALPHA = ALF( IA )\n*\n                           DO 50 IB = 1, NBET\n                              BETA = BET( IB )\n*\n*                             Generate the vector Y.\n*\n                              TRANSL = ZERO\n                              CALL SMAKE( 'GE', ' ', ' ', 1, ML, Y, 1,\n     $                                    YY, ABS( INCY ), 0, ML - 1,\n     $                                    RESET, TRANSL )\n*\n                              NC = NC + 1\n*\n*                             Save every datum before calling the\n*                             subroutine.\n*\n                              TRANSS = TRANS\n                              MS = M\n                              NS = N\n                              KLS = KL\n                              KUS = KU\n                              ALS = ALPHA\n                              DO 10 I = 1, LAA\n                                 AS( I ) = AA( I )\n   10                         CONTINUE\n                              LDAS = LDA\n                              DO 20 I = 1, LX\n                                 XS( I ) = XX( I )\n   20                         CONTINUE\n                              INCXS = INCX\n                              BLS = BETA\n                              DO 30 I = 1, LY\n                                 YS( I ) = YY( I )\n   30                         CONTINUE\n                              INCYS = INCY\n*\n*                             Call the subroutine.\n*\n                              IF( FULL )THEN\n                                 IF( TRACE )\n     $                              WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                              TRANS, M, N, ALPHA, LDA, INCX, BETA,\n     $                              INCY\n                                 IF( REWI )\n     $                              REWIND NTRA\n                                 CALL SGEMV( TRANS, M, N, ALPHA, AA,\n     $                                       LDA, XX, INCX, BETA, YY,\n     $                                       INCY )\n                              ELSE IF( BANDED )THEN\n                                 IF( TRACE )\n     $                              WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                              TRANS, M, N, KL, KU, ALPHA, LDA,\n     $                              INCX, BETA, INCY\n                                 IF( REWI )\n     $                              REWIND NTRA\n                                 CALL SGBMV( TRANS, M, N, KL, KU, ALPHA,\n     $                                       AA, LDA, XX, INCX, BETA,\n     $                                       YY, INCY )\n                              END IF\n*\n*                             Check if error-exit was taken incorrectly.\n*\n                              IF( .NOT.OK )THEN\n                                 WRITE( NOUT, FMT = 9993 )\n                                 FATAL = .TRUE.\n                                 GO TO 130\n                              END IF\n*\n*                             See what data changed inside subroutines.\n*\n                              ISAME( 1 ) = TRANS.EQ.TRANSS\n                              ISAME( 2 ) = MS.EQ.M\n                              ISAME( 3 ) = NS.EQ.N\n                              IF( FULL )THEN\n                                 ISAME( 4 ) = ALS.EQ.ALPHA\n                                 ISAME( 5 ) = LSE( AS, AA, LAA )\n                                 ISAME( 6 ) = LDAS.EQ.LDA\n                                 ISAME( 7 ) = LSE( XS, XX, LX )\n                                 ISAME( 8 ) = INCXS.EQ.INCX\n                                 ISAME( 9 ) = BLS.EQ.BETA\n                                 IF( NULL )THEN\n                                    ISAME( 10 ) = LSE( YS, YY, LY )\n                                 ELSE\n                                    ISAME( 10 ) = LSERES( 'GE', ' ', 1,\n     $                                            ML, YS, YY,\n     $                                            ABS( INCY ) )\n                                 END IF\n                                 ISAME( 11 ) = INCYS.EQ.INCY\n                              ELSE IF( BANDED )THEN\n                                 ISAME( 4 ) = KLS.EQ.KL\n                                 ISAME( 5 ) = KUS.EQ.KU\n                                 ISAME( 6 ) = ALS.EQ.ALPHA\n                                 ISAME( 7 ) = LSE( AS, AA, LAA )\n                                 ISAME( 8 ) = LDAS.EQ.LDA\n                                 ISAME( 9 ) = LSE( XS, XX, LX )\n                                 ISAME( 10 ) = INCXS.EQ.INCX\n                                 ISAME( 11 ) = BLS.EQ.BETA\n                                 IF( NULL )THEN\n                                    ISAME( 12 ) = LSE( YS, YY, LY )\n                                 ELSE\n                                    ISAME( 12 ) = LSERES( 'GE', ' ', 1,\n     $                                            ML, YS, YY,\n     $                                            ABS( INCY ) )\n                                 END IF\n                                 ISAME( 13 ) = INCYS.EQ.INCY\n                              END IF\n*\n*                             If data was incorrectly changed, report\n*                             and return.\n*\n                              SAME = .TRUE.\n                              DO 40 I = 1, NARGS\n                                 SAME = SAME.AND.ISAME( I )\n                                 IF( .NOT.ISAME( I ) )\n     $                              WRITE( NOUT, FMT = 9998 )I\n   40                         CONTINUE\n                              IF( .NOT.SAME )THEN\n                                 FATAL = .TRUE.\n                                 GO TO 130\n                              END IF\n*\n                              IF( .NOT.NULL )THEN\n*\n*                                Check the result.\n*\n                                 CALL SMVCH( TRANS, M, N, ALPHA, A,\n     $                                       NMAX, X, INCX, BETA, Y,\n     $                                       INCY, YT, G, YY, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                                 ERRMAX = MAX( ERRMAX, ERR )\n*                                If got really bad answer, report and\n*                                return.\n                                 IF( FATAL )\n     $                              GO TO 130\n                              ELSE\n*                                Avoid repeating tests with M.le.0 or\n*                                N.le.0.\n                                 GO TO 110\n                              END IF\n*\n   50                      CONTINUE\n*\n   60                   CONTINUE\n*\n   70                CONTINUE\n*\n   80             CONTINUE\n*\n   90          CONTINUE\n*\n  100       CONTINUE\n*\n  110    CONTINUE\n*\n  120 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 140\n*\n  130 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, TRANS, M, N, ALPHA, LDA,\n     $      INCX, BETA, INCY\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, TRANS, M, N, KL, KU,\n     $      ALPHA, LDA, INCX, BETA, INCY\n      END IF\n*\n  140 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 4( I3, ',' ), F4.1,\n     $      ', A,', I3, ', X,', I2, ',', F4.1, ', Y,', I2, ') .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 2( I3, ',' ), F4.1,\n     $      ', A,', I3, ', X,', I2, ',', F4.1, ', Y,', I2,\n     $      ')         .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK1.\n*\n      END\n      SUBROUTINE SCHK2( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF, NBET,\n     $                  BET, NINC, INC, NMAX, INCMAX, A, AA, AS, X, XX,\n     $                  XS, Y, YY, YS, YT, G )\n*\n*  Tests SSYMV, SSBMV and SSPMV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      REAL               ZERO, HALF\n      PARAMETER          ( ZERO = 0.0, HALF = 0.5 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NALF, NBET, NIDIM, NINC, NKB, NMAX,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), BET( NBET ), G( NMAX ),\n     $                   X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      REAL               ALPHA, ALS, BETA, BLS, ERR, ERRMAX, TRANSL\n      INTEGER            I, IA, IB, IC, IK, IN, INCX, INCXS, INCY,\n     $                   INCYS, IX, IY, K, KS, LAA, LDA, LDAS, LX, LY,\n     $                   N, NARGS, NC, NK, NS\n      LOGICAL            BANDED, FULL, NULL, PACKED, RESET, SAME\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SMAKE, SMVCH, SSBMV, SSPMV, SSYMV\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'Y'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 10\n      ELSE IF( BANDED )THEN\n         NARGS = 11\n      ELSE IF( PACKED )THEN\n         NARGS = 9\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 110 IN = 1, NIDIM\n         N = IDIM( IN )\n*\n         IF( BANDED )THEN\n            NK = NKB\n         ELSE\n            NK = 1\n         END IF\n         DO 100 IK = 1, NK\n            IF( BANDED )THEN\n               K = KB( IK )\n            ELSE\n               K = N - 1\n            END IF\n*           Set LDA to 1 more than minimum value if room.\n            IF( BANDED )THEN\n               LDA = K + 1\n            ELSE\n               LDA = N\n            END IF\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 100\n            IF( PACKED )THEN\n               LAA = ( N*( N + 1 ) )/2\n            ELSE\n               LAA = LDA*N\n            END IF\n            NULL = N.LE.0\n*\n            DO 90 IC = 1, 2\n               UPLO = ICH( IC: IC )\n*\n*              Generate the matrix A.\n*\n               TRANSL = ZERO\n               CALL SMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A, NMAX, AA,\n     $                     LDA, K, K, RESET, TRANSL )\n*\n               DO 80 IX = 1, NINC\n                  INCX = INC( IX )\n                  LX = ABS( INCX )*N\n*\n*                 Generate the vector X.\n*\n                  TRANSL = HALF\n                  CALL SMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX,\n     $                        ABS( INCX ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     X( N/2 ) = ZERO\n                     XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 70 IY = 1, NINC\n                     INCY = INC( IY )\n                     LY = ABS( INCY )*N\n*\n                     DO 60 IA = 1, NALF\n                        ALPHA = ALF( IA )\n*\n                        DO 50 IB = 1, NBET\n                           BETA = BET( IB )\n*\n*                          Generate the vector Y.\n*\n                           TRANSL = ZERO\n                           CALL SMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                                 ABS( INCY ), 0, N - 1, RESET,\n     $                                 TRANSL )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           UPLOS = UPLO\n                           NS = N\n                           KS = K\n                           ALS = ALPHA\n                           DO 10 I = 1, LAA\n                              AS( I ) = AA( I )\n   10                      CONTINUE\n                           LDAS = LDA\n                           DO 20 I = 1, LX\n                              XS( I ) = XX( I )\n   20                      CONTINUE\n                           INCXS = INCX\n                           BLS = BETA\n                           DO 30 I = 1, LY\n                              YS( I ) = YY( I )\n   30                      CONTINUE\n                           INCYS = INCY\n*\n*                          Call the subroutine.\n*\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, N, ALPHA, LDA, INCX, BETA, INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL SSYMV( UPLO, N, ALPHA, AA, LDA, XX,\n     $                                    INCX, BETA, YY, INCY )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, N, K, ALPHA, LDA, INCX, BETA,\n     $                           INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL SSBMV( UPLO, N, K, ALPHA, AA, LDA,\n     $                                    XX, INCX, BETA, YY, INCY )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, N, ALPHA, INCX, BETA, INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL SSPMV( UPLO, N, ALPHA, AA, XX, INCX,\n     $                                    BETA, YY, INCY )\n                           END IF\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9992 )\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = UPLO.EQ.UPLOS\n                           ISAME( 2 ) = NS.EQ.N\n                           IF( FULL )THEN\n                              ISAME( 3 ) = ALS.EQ.ALPHA\n                              ISAME( 4 ) = LSE( AS, AA, LAA )\n                              ISAME( 5 ) = LDAS.EQ.LDA\n                              ISAME( 6 ) = LSE( XS, XX, LX )\n                              ISAME( 7 ) = INCXS.EQ.INCX\n                              ISAME( 8 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 9 ) = LSE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 9 ) = LSERES( 'GE', ' ', 1, N,\n     $                                        YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 10 ) = INCYS.EQ.INCY\n                           ELSE IF( BANDED )THEN\n                              ISAME( 3 ) = KS.EQ.K\n                              ISAME( 4 ) = ALS.EQ.ALPHA\n                              ISAME( 5 ) = LSE( AS, AA, LAA )\n                              ISAME( 6 ) = LDAS.EQ.LDA\n                              ISAME( 7 ) = LSE( XS, XX, LX )\n                              ISAME( 8 ) = INCXS.EQ.INCX\n                              ISAME( 9 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 10 ) = LSE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 10 ) = LSERES( 'GE', ' ', 1, N,\n     $                                         YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 11 ) = INCYS.EQ.INCY\n                           ELSE IF( PACKED )THEN\n                              ISAME( 3 ) = ALS.EQ.ALPHA\n                              ISAME( 4 ) = LSE( AS, AA, LAA )\n                              ISAME( 5 ) = LSE( XS, XX, LX )\n                              ISAME( 6 ) = INCXS.EQ.INCX\n                              ISAME( 7 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 8 ) = LSE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 8 ) = LSERES( 'GE', ' ', 1, N,\n     $                                        YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 9 ) = INCYS.EQ.INCY\n                           END IF\n*\n*                          If data was incorrectly changed, report and\n*                          return.\n*\n                           SAME = .TRUE.\n                           DO 40 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   40                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n*\n*                             Check the result.\n*\n                              CALL SMVCH( 'N', N, N, ALPHA, A, NMAX, X,\n     $                                    INCX, BETA, Y, INCY, YT, G,\n     $                                    YY, EPS, ERR, FATAL, NOUT,\n     $                                    .TRUE. )\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 120\n                           ELSE\n*                             Avoid repeating tests with N.le.0\n                              GO TO 110\n                           END IF\n*\n   50                   CONTINUE\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, ALPHA, LDA, INCX,\n     $      BETA, INCY\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, K, ALPHA, LDA,\n     $      INCX, BETA, INCY\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, UPLO, N, ALPHA, INCX,\n     $      BETA, INCY\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', AP',\n     $      ', X,', I2, ',', F4.1, ', Y,', I2, ')                .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 2( I3, ',' ), F4.1,\n     $      ', A,', I3, ', X,', I2, ',', F4.1, ', Y,', I2,\n     $      ')         .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', A,',\n     $      I3, ', X,', I2, ',', F4.1, ', Y,', I2, ')             .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK2.\n*\n      END\n      SUBROUTINE SCHK3( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, XT, G, Z )\n*\n*  Tests STRMV, STBMV, STPMV, STRSV, STBSV and STPSV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      REAL               ZERO, HALF, ONE\n      PARAMETER          ( ZERO = 0.0, HALF = 0.5, ONE = 1.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NIDIM, NINC, NKB, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ),\n     $                   AS( NMAX*NMAX ), G( NMAX ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XT( NMAX ),\n     $                   XX( NMAX*INCMAX ), Z( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      REAL               ERR, ERRMAX, TRANSL\n      INTEGER            I, ICD, ICT, ICU, IK, IN, INCX, INCXS, IX, K,\n     $                   KS, LAA, LDA, LDAS, LX, N, NARGS, NC, NK, NS\n      LOGICAL            BANDED, FULL, NULL, PACKED, RESET, SAME\n      CHARACTER*1        DIAG, DIAGS, TRANS, TRANSS, UPLO, UPLOS\n      CHARACTER*2        ICHD, ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SMAKE, SMVCH, STBMV, STBSV, STPMV, STPSV,\n     $                   STRMV, STRSV\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHU/'UL'/, ICHT/'NTC'/, ICHD/'UN'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'R'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 8\n      ELSE IF( BANDED )THEN\n         NARGS = 9\n      ELSE IF( PACKED )THEN\n         NARGS = 7\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*     Set up zero vector for SMVCH.\n      DO 10 I = 1, NMAX\n         Z( I ) = ZERO\n   10 CONTINUE\n*\n      DO 110 IN = 1, NIDIM\n         N = IDIM( IN )\n*\n         IF( BANDED )THEN\n            NK = NKB\n         ELSE\n            NK = 1\n         END IF\n         DO 100 IK = 1, NK\n            IF( BANDED )THEN\n               K = KB( IK )\n            ELSE\n               K = N - 1\n            END IF\n*           Set LDA to 1 more than minimum value if room.\n            IF( BANDED )THEN\n               LDA = K + 1\n            ELSE\n               LDA = N\n            END IF\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 100\n            IF( PACKED )THEN\n               LAA = ( N*( N + 1 ) )/2\n            ELSE\n               LAA = LDA*N\n            END IF\n            NULL = N.LE.0\n*\n            DO 90 ICU = 1, 2\n               UPLO = ICHU( ICU: ICU )\n*\n               DO 80 ICT = 1, 3\n                  TRANS = ICHT( ICT: ICT )\n*\n                  DO 70 ICD = 1, 2\n                     DIAG = ICHD( ICD: ICD )\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL SMAKE( SNAME( 2: 3 ), UPLO, DIAG, N, N, A,\n     $                           NMAX, AA, LDA, K, K, RESET, TRANSL )\n*\n                     DO 60 IX = 1, NINC\n                        INCX = INC( IX )\n                        LX = ABS( INCX )*N\n*\n*                       Generate the vector X.\n*\n                        TRANSL = HALF\n                        CALL SMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX,\n     $                              ABS( INCX ), 0, N - 1, RESET,\n     $                              TRANSL )\n                        IF( N.GT.1 )THEN\n                           X( N/2 ) = ZERO\n                           XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n                        END IF\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        DIAGS = DIAG\n                        NS = N\n                        KS = K\n                        DO 20 I = 1, LAA\n                           AS( I ) = AA( I )\n   20                   CONTINUE\n                        LDAS = LDA\n                        DO 30 I = 1, LX\n                           XS( I ) = XX( I )\n   30                   CONTINUE\n                        INCXS = INCX\n*\n*                       Call the subroutine.\n*\n                        IF( SNAME( 4: 5 ).EQ.'MV' )THEN\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL STRMV( UPLO, TRANS, DIAG, N, AA, LDA,\n     $                                    XX, INCX )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, K, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL STBMV( UPLO, TRANS, DIAG, N, K, AA,\n     $                                    LDA, XX, INCX )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL STPMV( UPLO, TRANS, DIAG, N, AA, XX,\n     $                                    INCX )\n                           END IF\n                        ELSE IF( SNAME( 4: 5 ).EQ.'SV' )THEN\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL STRSV( UPLO, TRANS, DIAG, N, AA, LDA,\n     $                                    XX, INCX )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, K, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL STBSV( UPLO, TRANS, DIAG, N, K, AA,\n     $                                    LDA, XX, INCX )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL STPSV( UPLO, TRANS, DIAG, N, AA, XX,\n     $                                    INCX )\n                           END IF\n                        END IF\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9992 )\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLO.EQ.UPLOS\n                        ISAME( 2 ) = TRANS.EQ.TRANSS\n                        ISAME( 3 ) = DIAG.EQ.DIAGS\n                        ISAME( 4 ) = NS.EQ.N\n                        IF( FULL )THEN\n                           ISAME( 5 ) = LSE( AS, AA, LAA )\n                           ISAME( 6 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 7 ) = LSE( XS, XX, LX )\n                           ELSE\n                              ISAME( 7 ) = LSERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 8 ) = INCXS.EQ.INCX\n                        ELSE IF( BANDED )THEN\n                           ISAME( 5 ) = KS.EQ.K\n                           ISAME( 6 ) = LSE( AS, AA, LAA )\n                           ISAME( 7 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 8 ) = LSE( XS, XX, LX )\n                           ELSE\n                              ISAME( 8 ) = LSERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 9 ) = INCXS.EQ.INCX\n                        ELSE IF( PACKED )THEN\n                           ISAME( 5 ) = LSE( AS, AA, LAA )\n                           IF( NULL )THEN\n                              ISAME( 6 ) = LSE( XS, XX, LX )\n                           ELSE\n                              ISAME( 6 ) = LSERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 7 ) = INCXS.EQ.INCX\n                        END IF\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n                           IF( SNAME( 4: 5 ).EQ.'MV' )THEN\n*\n*                             Check the result.\n*\n                              CALL SMVCH( TRANS, N, N, ONE, A, NMAX, X,\n     $                                    INCX, ZERO, Z, INCX, XT, G,\n     $                                    XX, EPS, ERR, FATAL, NOUT,\n     $                                    .TRUE. )\n                           ELSE IF( SNAME( 4: 5 ).EQ.'SV' )THEN\n*\n*                             Compute approximation to original vector.\n*\n                              DO 50 I = 1, N\n                                 Z( I ) = XX( 1 + ( I - 1 )*\n     $                                    ABS( INCX ) )\n                                 XX( 1 + ( I - 1 )*ABS( INCX ) )\n     $                              = X( I )\n   50                         CONTINUE\n                              CALL SMVCH( TRANS, N, N, ONE, A, NMAX, Z,\n     $                                    INCX, ZERO, X, INCX, XT, G,\n     $                                    XX, EPS, ERR, FATAL, NOUT,\n     $                                    .FALSE. )\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 120\n                        ELSE\n*                          Avoid repeating tests with N.le.0.\n                           GO TO 110\n                        END IF\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, TRANS, DIAG, N, LDA,\n     $      INCX\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, DIAG, N, K,\n     $      LDA, INCX\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, UPLO, TRANS, DIAG, N, INCX\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), I3, ', AP, ',\n     $      'X,', I2, ')                        .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), 2( I3, ',' ),\n     $      ' A,', I3, ', X,', I2, ')                 .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), I3, ', A,',\n     $      I3, ', X,', I2, ')                     .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK3.\n*\n      END\n      SUBROUTINE SCHK4( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests SGER.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      REAL               ZERO, HALF, ONE\n      PARAMETER          ( ZERO = 0.0, HALF = 0.5, ONE = 1.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), G( NMAX ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XX( NMAX*INCMAX ),\n     $                   Y( NMAX ), YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      REAL               ALPHA, ALS, ERR, ERRMAX, TRANSL\n      INTEGER            I, IA, IM, IN, INCX, INCXS, INCY, INCYS, IX,\n     $                   IY, J, LAA, LDA, LDAS, LX, LY, M, MS, N, NARGS,\n     $                   NC, ND, NS\n      LOGICAL            NULL, RESET, SAME\n*     .. Local Arrays ..\n      REAL               W( 1 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SGER, SMAKE, SMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n*     Define the number of arguments.\n      NARGS = 9\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 120 IN = 1, NIDIM\n         N = IDIM( IN )\n         ND = N/2 + 1\n*\n         DO 110 IM = 1, 2\n            IF( IM.EQ.1 )\n     $         M = MAX( N - ND, 0 )\n            IF( IM.EQ.2 )\n     $         M = MIN( N + ND, NMAX )\n*\n*           Set LDA to 1 more than minimum value if room.\n            LDA = M\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 110\n            LAA = LDA*N\n            NULL = N.LE.0.OR.M.LE.0\n*\n            DO 100 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*M\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL SMAKE( 'GE', ' ', ' ', 1, M, X, 1, XX, ABS( INCX ),\n     $                     0, M - 1, RESET, TRANSL )\n               IF( M.GT.1 )THEN\n                  X( M/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( M/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 90 IY = 1, NINC\n                  INCY = INC( IY )\n                  LY = ABS( INCY )*N\n*\n*                 Generate the vector Y.\n*\n                  TRANSL = ZERO\n                  CALL SMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                        ABS( INCY ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     Y( N/2 ) = ZERO\n                     YY( 1 + ABS( INCY )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 80 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL SMAKE( SNAME( 2: 3 ), ' ', ' ', M, N, A, NMAX,\n     $                           AA, LDA, M - 1, N - 1, RESET, TRANSL )\n*\n                     NC = NC + 1\n*\n*                    Save every datum before calling the subroutine.\n*\n                     MS = M\n                     NS = N\n                     ALS = ALPHA\n                     DO 10 I = 1, LAA\n                        AS( I ) = AA( I )\n   10                CONTINUE\n                     LDAS = LDA\n                     DO 20 I = 1, LX\n                        XS( I ) = XX( I )\n   20                CONTINUE\n                     INCXS = INCX\n                     DO 30 I = 1, LY\n                        YS( I ) = YY( I )\n   30                CONTINUE\n                     INCYS = INCY\n*\n*                    Call the subroutine.\n*\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9994 )NC, SNAME, M, N,\n     $                  ALPHA, INCX, INCY, LDA\n                     IF( REWI )\n     $                  REWIND NTRA\n                     CALL SGER( M, N, ALPHA, XX, INCX, YY, INCY, AA,\n     $                          LDA )\n*\n*                    Check if error-exit was taken incorrectly.\n*\n                     IF( .NOT.OK )THEN\n                        WRITE( NOUT, FMT = 9993 )\n                        FATAL = .TRUE.\n                        GO TO 140\n                     END IF\n*\n*                    See what data changed inside subroutine.\n*\n                     ISAME( 1 ) = MS.EQ.M\n                     ISAME( 2 ) = NS.EQ.N\n                     ISAME( 3 ) = ALS.EQ.ALPHA\n                     ISAME( 4 ) = LSE( XS, XX, LX )\n                     ISAME( 5 ) = INCXS.EQ.INCX\n                     ISAME( 6 ) = LSE( YS, YY, LY )\n                     ISAME( 7 ) = INCYS.EQ.INCY\n                     IF( NULL )THEN\n                        ISAME( 8 ) = LSE( AS, AA, LAA )\n                     ELSE\n                        ISAME( 8 ) = LSERES( 'GE', ' ', M, N, AS, AA,\n     $                               LDA )\n                     END IF\n                     ISAME( 9 ) = LDAS.EQ.LDA\n*\n*                    If data was incorrectly changed, report and return.\n*\n                     SAME = .TRUE.\n                     DO 40 I = 1, NARGS\n                        SAME = SAME.AND.ISAME( I )\n                        IF( .NOT.ISAME( I ) )\n     $                     WRITE( NOUT, FMT = 9998 )I\n   40                CONTINUE\n                     IF( .NOT.SAME )THEN\n                        FATAL = .TRUE.\n                        GO TO 140\n                     END IF\n*\n                     IF( .NOT.NULL )THEN\n*\n*                       Check the result column by column.\n*\n                        IF( INCX.GT.0 )THEN\n                           DO 50 I = 1, M\n                              Z( I ) = X( I )\n   50                      CONTINUE\n                        ELSE\n                           DO 60 I = 1, M\n                              Z( I ) = X( M - I + 1 )\n   60                      CONTINUE\n                        END IF\n                        DO 70 J = 1, N\n                           IF( INCY.GT.0 )THEN\n                              W( 1 ) = Y( J )\n                           ELSE\n                              W( 1 ) = Y( N - J + 1 )\n                           END IF\n                           CALL SMVCH( 'N', M, 1, ALPHA, Z, NMAX, W, 1,\n     $                                 ONE, A( 1, J ), 1, YT, G,\n     $                                 AA( 1 + ( J - 1 )*LDA ), EPS,\n     $                                 ERR, FATAL, NOUT, .TRUE. )\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 130\n   70                   CONTINUE\n                     ELSE\n*                       Avoid repeating tests with M.le.0 or N.le.0.\n                        GO TO 110\n                     END IF\n*\n   80             CONTINUE\n*\n   90          CONTINUE\n*\n  100       CONTINUE\n*\n  110    CONTINUE\n*\n  120 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 150\n*\n  130 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  140 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9994 )NC, SNAME, M, N, ALPHA, INCX, INCY, LDA\n*\n  150 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( I3, ',' ), F4.1, ', X,', I2,\n     $      ', Y,', I2, ', A,', I3, ')                  .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK4.\n*\n      END\n      SUBROUTINE SCHK5( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests SSYR and SSPR.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      REAL               ZERO, HALF, ONE\n      PARAMETER          ( ZERO = 0.0, HALF = 0.5, ONE = 1.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), G( NMAX ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XX( NMAX*INCMAX ),\n     $                   Y( NMAX ), YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      REAL               ALPHA, ALS, ERR, ERRMAX, TRANSL\n      INTEGER            I, IA, IC, IN, INCX, INCXS, IX, J, JA, JJ, LAA,\n     $                   LDA, LDAS, LJ, LX, N, NARGS, NC, NS\n      LOGICAL            FULL, NULL, PACKED, RESET, SAME, UPPER\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      REAL               W( 1 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SMAKE, SMVCH, SSPR, SSYR\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'Y'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 7\n      ELSE IF( PACKED )THEN\n         NARGS = 6\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 100 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDA to 1 more than minimum value if room.\n         LDA = N\n         IF( LDA.LT.NMAX )\n     $      LDA = LDA + 1\n*        Skip tests if not enough room.\n         IF( LDA.GT.NMAX )\n     $      GO TO 100\n         IF( PACKED )THEN\n            LAA = ( N*( N + 1 ) )/2\n         ELSE\n            LAA = LDA*N\n         END IF\n*\n         DO 90 IC = 1, 2\n            UPLO = ICH( IC: IC )\n            UPPER = UPLO.EQ.'U'\n*\n            DO 80 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*N\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL SMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX, ABS( INCX ),\n     $                     0, N - 1, RESET, TRANSL )\n               IF( N.GT.1 )THEN\n                  X( N/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 70 IA = 1, NALF\n                  ALPHA = ALF( IA )\n                  NULL = N.LE.0.OR.ALPHA.EQ.ZERO\n*\n*                 Generate the matrix A.\n*\n                  TRANSL = ZERO\n                  CALL SMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A, NMAX,\n     $                        AA, LDA, N - 1, N - 1, RESET, TRANSL )\n*\n                  NC = NC + 1\n*\n*                 Save every datum before calling the subroutine.\n*\n                  UPLOS = UPLO\n                  NS = N\n                  ALS = ALPHA\n                  DO 10 I = 1, LAA\n                     AS( I ) = AA( I )\n   10             CONTINUE\n                  LDAS = LDA\n                  DO 20 I = 1, LX\n                     XS( I ) = XX( I )\n   20             CONTINUE\n                  INCXS = INCX\n*\n*                 Call the subroutine.\n*\n                  IF( FULL )THEN\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO, N,\n     $                  ALPHA, INCX, LDA\n                     IF( REWI )\n     $                  REWIND NTRA\n                     CALL SSYR( UPLO, N, ALPHA, XX, INCX, AA, LDA )\n                  ELSE IF( PACKED )THEN\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO, N,\n     $                  ALPHA, INCX\n                     IF( REWI )\n     $                  REWIND NTRA\n                     CALL SSPR( UPLO, N, ALPHA, XX, INCX, AA )\n                  END IF\n*\n*                 Check if error-exit was taken incorrectly.\n*\n                  IF( .NOT.OK )THEN\n                     WRITE( NOUT, FMT = 9992 )\n                     FATAL = .TRUE.\n                     GO TO 120\n                  END IF\n*\n*                 See what data changed inside subroutines.\n*\n                  ISAME( 1 ) = UPLO.EQ.UPLOS\n                  ISAME( 2 ) = NS.EQ.N\n                  ISAME( 3 ) = ALS.EQ.ALPHA\n                  ISAME( 4 ) = LSE( XS, XX, LX )\n                  ISAME( 5 ) = INCXS.EQ.INCX\n                  IF( NULL )THEN\n                     ISAME( 6 ) = LSE( AS, AA, LAA )\n                  ELSE\n                     ISAME( 6 ) = LSERES( SNAME( 2: 3 ), UPLO, N, N, AS,\n     $                            AA, LDA )\n                  END IF\n                  IF( .NOT.PACKED )THEN\n                     ISAME( 7 ) = LDAS.EQ.LDA\n                  END IF\n*\n*                 If data was incorrectly changed, report and return.\n*\n                  SAME = .TRUE.\n                  DO 30 I = 1, NARGS\n                     SAME = SAME.AND.ISAME( I )\n                     IF( .NOT.ISAME( I ) )\n     $                  WRITE( NOUT, FMT = 9998 )I\n   30             CONTINUE\n                  IF( .NOT.SAME )THEN\n                     FATAL = .TRUE.\n                     GO TO 120\n                  END IF\n*\n                  IF( .NOT.NULL )THEN\n*\n*                    Check the result column by column.\n*\n                     IF( INCX.GT.0 )THEN\n                        DO 40 I = 1, N\n                           Z( I ) = X( I )\n   40                   CONTINUE\n                     ELSE\n                        DO 50 I = 1, N\n                           Z( I ) = X( N - I + 1 )\n   50                   CONTINUE\n                     END IF\n                     JA = 1\n                     DO 60 J = 1, N\n                        W( 1 ) = Z( J )\n                        IF( UPPER )THEN\n                           JJ = 1\n                           LJ = J\n                        ELSE\n                           JJ = J\n                           LJ = N - J + 1\n                        END IF\n                        CALL SMVCH( 'N', LJ, 1, ALPHA, Z( JJ ), LJ, W,\n     $                              1, ONE, A( JJ, J ), 1, YT, G,\n     $                              AA( JA ), EPS, ERR, FATAL, NOUT,\n     $                              .TRUE. )\n                        IF( FULL )THEN\n                           IF( UPPER )THEN\n                              JA = JA + LDA\n                           ELSE\n                              JA = JA + LDA + 1\n                           END IF\n                        ELSE\n                           JA = JA + LJ\n                        END IF\n                        ERRMAX = MAX( ERRMAX, ERR )\n*                       If got really bad answer, report and return.\n                        IF( FATAL )\n     $                     GO TO 110\n   60                CONTINUE\n                  ELSE\n*                    Avoid repeating tests if N.le.0.\n                     IF( N.LE.0 )\n     $                  GO TO 100\n                  END IF\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  110 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, ALPHA, INCX, LDA\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, ALPHA, INCX\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', AP)                           .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', A,', I3, ')                        .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK5.\n*\n      END\n      SUBROUTINE SCHK6( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests SSYR2 and SSPR2.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      REAL               ZERO, HALF, ONE\n      PARAMETER          ( ZERO = 0.0, HALF = 0.5, ONE = 1.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), G( NMAX ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XX( NMAX*INCMAX ),\n     $                   Y( NMAX ), YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX, 2 )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      REAL               ALPHA, ALS, ERR, ERRMAX, TRANSL\n      INTEGER            I, IA, IC, IN, INCX, INCXS, INCY, INCYS, IX,\n     $                   IY, J, JA, JJ, LAA, LDA, LDAS, LJ, LX, LY, N,\n     $                   NARGS, NC, NS\n      LOGICAL            FULL, NULL, PACKED, RESET, SAME, UPPER\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      REAL               W( 2 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SMAKE, SMVCH, SSPR2, SSYR2\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'Y'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 9\n      ELSE IF( PACKED )THEN\n         NARGS = 8\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 140 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDA to 1 more than minimum value if room.\n         LDA = N\n         IF( LDA.LT.NMAX )\n     $      LDA = LDA + 1\n*        Skip tests if not enough room.\n         IF( LDA.GT.NMAX )\n     $      GO TO 140\n         IF( PACKED )THEN\n            LAA = ( N*( N + 1 ) )/2\n         ELSE\n            LAA = LDA*N\n         END IF\n*\n         DO 130 IC = 1, 2\n            UPLO = ICH( IC: IC )\n            UPPER = UPLO.EQ.'U'\n*\n            DO 120 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*N\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL SMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX, ABS( INCX ),\n     $                     0, N - 1, RESET, TRANSL )\n               IF( N.GT.1 )THEN\n                  X( N/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 110 IY = 1, NINC\n                  INCY = INC( IY )\n                  LY = ABS( INCY )*N\n*\n*                 Generate the vector Y.\n*\n                  TRANSL = ZERO\n                  CALL SMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                        ABS( INCY ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     Y( N/2 ) = ZERO\n                     YY( 1 + ABS( INCY )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 100 IA = 1, NALF\n                     ALPHA = ALF( IA )\n                     NULL = N.LE.0.OR.ALPHA.EQ.ZERO\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL SMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A,\n     $                           NMAX, AA, LDA, N - 1, N - 1, RESET,\n     $                           TRANSL )\n*\n                     NC = NC + 1\n*\n*                    Save every datum before calling the subroutine.\n*\n                     UPLOS = UPLO\n                     NS = N\n                     ALS = ALPHA\n                     DO 10 I = 1, LAA\n                        AS( I ) = AA( I )\n   10                CONTINUE\n                     LDAS = LDA\n                     DO 20 I = 1, LX\n                        XS( I ) = XX( I )\n   20                CONTINUE\n                     INCXS = INCX\n                     DO 30 I = 1, LY\n                        YS( I ) = YY( I )\n   30                CONTINUE\n                     INCYS = INCY\n*\n*                    Call the subroutine.\n*\n                     IF( FULL )THEN\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO, N,\n     $                     ALPHA, INCX, INCY, LDA\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL SSYR2( UPLO, N, ALPHA, XX, INCX, YY, INCY,\n     $                              AA, LDA )\n                     ELSE IF( PACKED )THEN\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO, N,\n     $                     ALPHA, INCX, INCY\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL SSPR2( UPLO, N, ALPHA, XX, INCX, YY, INCY,\n     $                              AA )\n                     END IF\n*\n*                    Check if error-exit was taken incorrectly.\n*\n                     IF( .NOT.OK )THEN\n                        WRITE( NOUT, FMT = 9992 )\n                        FATAL = .TRUE.\n                        GO TO 160\n                     END IF\n*\n*                    See what data changed inside subroutines.\n*\n                     ISAME( 1 ) = UPLO.EQ.UPLOS\n                     ISAME( 2 ) = NS.EQ.N\n                     ISAME( 3 ) = ALS.EQ.ALPHA\n                     ISAME( 4 ) = LSE( XS, XX, LX )\n                     ISAME( 5 ) = INCXS.EQ.INCX\n                     ISAME( 6 ) = LSE( YS, YY, LY )\n                     ISAME( 7 ) = INCYS.EQ.INCY\n                     IF( NULL )THEN\n                        ISAME( 8 ) = LSE( AS, AA, LAA )\n                     ELSE\n                        ISAME( 8 ) = LSERES( SNAME( 2: 3 ), UPLO, N, N,\n     $                               AS, AA, LDA )\n                     END IF\n                     IF( .NOT.PACKED )THEN\n                        ISAME( 9 ) = LDAS.EQ.LDA\n                     END IF\n*\n*                    If data was incorrectly changed, report and return.\n*\n                     SAME = .TRUE.\n                     DO 40 I = 1, NARGS\n                        SAME = SAME.AND.ISAME( I )\n                        IF( .NOT.ISAME( I ) )\n     $                     WRITE( NOUT, FMT = 9998 )I\n   40                CONTINUE\n                     IF( .NOT.SAME )THEN\n                        FATAL = .TRUE.\n                        GO TO 160\n                     END IF\n*\n                     IF( .NOT.NULL )THEN\n*\n*                       Check the result column by column.\n*\n                        IF( INCX.GT.0 )THEN\n                           DO 50 I = 1, N\n                              Z( I, 1 ) = X( I )\n   50                      CONTINUE\n                        ELSE\n                           DO 60 I = 1, N\n                              Z( I, 1 ) = X( N - I + 1 )\n   60                      CONTINUE\n                        END IF\n                        IF( INCY.GT.0 )THEN\n                           DO 70 I = 1, N\n                              Z( I, 2 ) = Y( I )\n   70                      CONTINUE\n                        ELSE\n                           DO 80 I = 1, N\n                              Z( I, 2 ) = Y( N - I + 1 )\n   80                      CONTINUE\n                        END IF\n                        JA = 1\n                        DO 90 J = 1, N\n                           W( 1 ) = Z( J, 2 )\n                           W( 2 ) = Z( J, 1 )\n                           IF( UPPER )THEN\n                              JJ = 1\n                              LJ = J\n                           ELSE\n                              JJ = J\n                              LJ = N - J + 1\n                           END IF\n                           CALL SMVCH( 'N', LJ, 2, ALPHA, Z( JJ, 1 ),\n     $                                 NMAX, W, 1, ONE, A( JJ, J ), 1,\n     $                                 YT, G, AA( JA ), EPS, ERR, FATAL,\n     $                                 NOUT, .TRUE. )\n                           IF( FULL )THEN\n                              IF( UPPER )THEN\n                                 JA = JA + LDA\n                              ELSE\n                                 JA = JA + LDA + 1\n                              END IF\n                           ELSE\n                              JA = JA + LJ\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 150\n   90                   CONTINUE\n                     ELSE\n*                       Avoid repeating tests with N.le.0.\n                        IF( N.LE.0 )\n     $                     GO TO 140\n                     END IF\n*\n  100             CONTINUE\n*\n  110          CONTINUE\n*\n  120       CONTINUE\n*\n  130    CONTINUE\n*\n  140 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 170\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  160 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, ALPHA, INCX,\n     $      INCY, LDA\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, ALPHA, INCX, INCY\n      END IF\n*\n  170 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', Y,', I2, ', AP)                     .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', Y,', I2, ', A,', I3, ')                  .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK6.\n*\n      END\n      SUBROUTINE SCHKE( ISNUM, SRNAMT, NOUT )\n*\n*  Tests the error exits from the Level 2 Blas.\n*  Requires a special version of the error-handling routine XERBLA.\n*  ALPHA, BETA, A, X and Y should not need to be defined.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            ISNUM, NOUT\n      CHARACTER*6        SRNAMT\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Local Scalars ..\n      REAL               ALPHA, BETA\n*     .. Local Arrays ..\n      REAL               A( 1, 1 ), X( 1 ), Y( 1 )\n*     .. External Subroutines ..\n      EXTERNAL           CHKXER, SGBMV, SGEMV, SGER, SSBMV, SSPMV, SSPR,\n     $                   SSPR2, SSYMV, SSYR, SSYR2, STBMV, STBSV, STPMV,\n     $                   STPSV, STRMV, STRSV\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n*     OK is set to .FALSE. by the special version of XERBLA or by CHKXER\n*     if anything is wrong.\n      OK = .TRUE.\n*     LERR is set to .TRUE. by the special version of XERBLA each time\n*     it is called, and is then tested and re-set by CHKXER.\n      LERR = .FALSE.\n      GO TO ( 10, 20, 30, 40, 50, 60, 70, 80,\n     $        90, 100, 110, 120, 130, 140, 150,\n     $        160 )ISNUM\n   10 INFOT = 1\n      CALL SGEMV( '/', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SGEMV( 'N', -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SGEMV( 'N', 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL SGEMV( 'N', 2, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL SGEMV( 'N', 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL SGEMV( 'N', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   20 INFOT = 1\n      CALL SGBMV( '/', 0, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SGBMV( 'N', -1, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SGBMV( 'N', 0, -1, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SGBMV( 'N', 0, 0, -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SGBMV( 'N', 2, 0, 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL SGBMV( 'N', 0, 0, 1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL SGBMV( 'N', 0, 0, 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL SGBMV( 'N', 0, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   30 INFOT = 1\n      CALL SSYMV( '/', 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SSYMV( 'U', -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SSYMV( 'U', 2, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYMV( 'U', 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL SSYMV( 'U', 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   40 INFOT = 1\n      CALL SSBMV( '/', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SSBMV( 'U', -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSBMV( 'U', 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL SSBMV( 'U', 0, 1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL SSBMV( 'U', 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL SSBMV( 'U', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   50 INFOT = 1\n      CALL SSPMV( '/', 0, ALPHA, A, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SSPMV( 'U', -1, ALPHA, A, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL SSPMV( 'U', 0, ALPHA, A, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SSPMV( 'U', 0, ALPHA, A, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   60 INFOT = 1\n      CALL STRMV( '/', 'N', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL STRMV( 'U', '/', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL STRMV( 'U', 'N', '/', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL STRMV( 'U', 'N', 'N', -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRMV( 'U', 'N', 'N', 2, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL STRMV( 'U', 'N', 'N', 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   70 INFOT = 1\n      CALL STBMV( '/', 'N', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL STBMV( 'U', '/', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL STBMV( 'U', 'N', '/', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL STBMV( 'U', 'N', 'N', -1, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STBMV( 'U', 'N', 'N', 0, -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL STBMV( 'U', 'N', 'N', 0, 1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STBMV( 'U', 'N', 'N', 0, 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   80 INFOT = 1\n      CALL STPMV( '/', 'N', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL STPMV( 'U', '/', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL STPMV( 'U', 'N', '/', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL STPMV( 'U', 'N', 'N', -1, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL STPMV( 'U', 'N', 'N', 0, A, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   90 INFOT = 1\n      CALL STRSV( '/', 'N', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL STRSV( 'U', '/', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL STRSV( 'U', 'N', '/', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL STRSV( 'U', 'N', 'N', -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRSV( 'U', 'N', 'N', 2, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL STRSV( 'U', 'N', 'N', 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  100 INFOT = 1\n      CALL STBSV( '/', 'N', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL STBSV( 'U', '/', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL STBSV( 'U', 'N', '/', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL STBSV( 'U', 'N', 'N', -1, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STBSV( 'U', 'N', 'N', 0, -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL STBSV( 'U', 'N', 'N', 0, 1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STBSV( 'U', 'N', 'N', 0, 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  110 INFOT = 1\n      CALL STPSV( '/', 'N', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL STPSV( 'U', '/', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL STPSV( 'U', 'N', '/', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL STPSV( 'U', 'N', 'N', -1, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL STPSV( 'U', 'N', 'N', 0, A, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  120 INFOT = 1\n      CALL SGER( -1, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SGER( 0, -1, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SGER( 0, 0, ALPHA, X, 0, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SGER( 0, 0, ALPHA, X, 1, Y, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SGER( 2, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  130 INFOT = 1\n      CALL SSYR( '/', 0, ALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SSYR( 'U', -1, ALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SSYR( 'U', 0, ALPHA, X, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYR( 'U', 2, ALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  140 INFOT = 1\n      CALL SSPR( '/', 0, ALPHA, X, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SSPR( 'U', -1, ALPHA, X, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SSPR( 'U', 0, ALPHA, X, 0, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  150 INFOT = 1\n      CALL SSYR2( '/', 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SSYR2( 'U', -1, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SSYR2( 'U', 0, ALPHA, X, 0, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYR2( 'U', 0, ALPHA, X, 1, Y, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SSYR2( 'U', 2, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  160 INFOT = 1\n      CALL SSPR2( '/', 0, ALPHA, X, 1, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SSPR2( 'U', -1, ALPHA, X, 1, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SSPR2( 'U', 0, ALPHA, X, 0, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSPR2( 'U', 0, ALPHA, X, 1, Y, 0, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n  170 IF( OK )THEN\n         WRITE( NOUT, FMT = 9999 )SRNAMT\n      ELSE\n         WRITE( NOUT, FMT = 9998 )SRNAMT\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE TESTS OF ERROR-EXITS' )\n 9998 FORMAT( ' ******* ', A6, ' FAILED THE TESTS OF ERROR-EXITS *****',\n     $      '**' )\n*\n*     End of SCHKE.\n*\n      END\n      SUBROUTINE SMAKE( TYPE, UPLO, DIAG, M, N, A, NMAX, AA, LDA, KL,\n     $                  KU, RESET, TRANSL )\n*\n*  Generates values for an M by N matrix A within the bandwidth\n*  defined by KL and KU.\n*  Stores the values in the array AA in the data structure required\n*  by the routine, with unwanted elements set to rogue value.\n*\n*  TYPE is 'GE', 'GB', 'SY', 'SB', 'SP', 'TR', 'TB' OR 'TP'.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      REAL               ZERO, ONE\n      PARAMETER          ( ZERO = 0.0, ONE = 1.0 )\n      REAL               ROGUE\n      PARAMETER          ( ROGUE = -1.0E10 )\n*     .. Scalar Arguments ..\n      REAL               TRANSL\n      INTEGER            KL, KU, LDA, M, N, NMAX\n      LOGICAL            RESET\n      CHARACTER*1        DIAG, UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      REAL               A( NMAX, * ), AA( * )\n*     .. Local Scalars ..\n      INTEGER            I, I1, I2, I3, IBEG, IEND, IOFF, J, KK\n      LOGICAL            GEN, LOWER, SYM, TRI, UNIT, UPPER\n*     .. External Functions ..\n      REAL               SBEG\n      EXTERNAL           SBEG\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX, MIN\n*     .. Executable Statements ..\n      GEN = TYPE( 1: 1 ).EQ.'G'\n      SYM = TYPE( 1: 1 ).EQ.'S'\n      TRI = TYPE( 1: 1 ).EQ.'T'\n      UPPER = ( SYM.OR.TRI ).AND.UPLO.EQ.'U'\n      LOWER = ( SYM.OR.TRI ).AND.UPLO.EQ.'L'\n      UNIT = TRI.AND.DIAG.EQ.'U'\n*\n*     Generate data in array A.\n*\n      DO 20 J = 1, N\n         DO 10 I = 1, M\n            IF( GEN.OR.( UPPER.AND.I.LE.J ).OR.( LOWER.AND.I.GE.J ) )\n     $          THEN\n               IF( ( I.LE.J.AND.J - I.LE.KU ).OR.\n     $             ( I.GE.J.AND.I - J.LE.KL ) )THEN\n                  A( I, J ) = SBEG( RESET ) + TRANSL\n               ELSE\n                  A( I, J ) = ZERO\n               END IF\n               IF( I.NE.J )THEN\n                  IF( SYM )THEN\n                     A( J, I ) = A( I, J )\n                  ELSE IF( TRI )THEN\n                     A( J, I ) = ZERO\n                  END IF\n               END IF\n            END IF\n   10    CONTINUE\n         IF( TRI )\n     $      A( J, J ) = A( J, J ) + ONE\n         IF( UNIT )\n     $      A( J, J ) = ONE\n   20 CONTINUE\n*\n*     Store elements in array AS in data structure required by routine.\n*\n      IF( TYPE.EQ.'GE' )THEN\n         DO 50 J = 1, N\n            DO 30 I = 1, M\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   30       CONTINUE\n            DO 40 I = M + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   40       CONTINUE\n   50    CONTINUE\n      ELSE IF( TYPE.EQ.'GB' )THEN\n         DO 90 J = 1, N\n            DO 60 I1 = 1, KU + 1 - J\n               AA( I1 + ( J - 1 )*LDA ) = ROGUE\n   60       CONTINUE\n            DO 70 I2 = I1, MIN( KL + KU + 1, KU + 1 + M - J )\n               AA( I2 + ( J - 1 )*LDA ) = A( I2 + J - KU - 1, J )\n   70       CONTINUE\n            DO 80 I3 = I2, LDA\n               AA( I3 + ( J - 1 )*LDA ) = ROGUE\n   80       CONTINUE\n   90    CONTINUE\n      ELSE IF( TYPE.EQ.'SY'.OR.TYPE.EQ.'TR' )THEN\n         DO 130 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IF( UNIT )THEN\n                  IEND = J - 1\n               ELSE\n                  IEND = J\n               END IF\n            ELSE\n               IF( UNIT )THEN\n                  IBEG = J + 1\n               ELSE\n                  IBEG = J\n               END IF\n               IEND = N\n            END IF\n            DO 100 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  100       CONTINUE\n            DO 110 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n  110       CONTINUE\n            DO 120 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  120       CONTINUE\n  130    CONTINUE\n      ELSE IF( TYPE.EQ.'SB'.OR.TYPE.EQ.'TB' )THEN\n         DO 170 J = 1, N\n            IF( UPPER )THEN\n               KK = KL + 1\n               IBEG = MAX( 1, KL + 2 - J )\n               IF( UNIT )THEN\n                  IEND = KL\n               ELSE\n                  IEND = KL + 1\n               END IF\n            ELSE\n               KK = 1\n               IF( UNIT )THEN\n                  IBEG = 2\n               ELSE\n                  IBEG = 1\n               END IF\n               IEND = MIN( KL + 1, 1 + M - J )\n            END IF\n            DO 140 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  140       CONTINUE\n            DO 150 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I + J - KK, J )\n  150       CONTINUE\n            DO 160 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  160       CONTINUE\n  170    CONTINUE\n      ELSE IF( TYPE.EQ.'SP'.OR.TYPE.EQ.'TP' )THEN\n         IOFF = 0\n         DO 190 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 180 I = IBEG, IEND\n               IOFF = IOFF + 1\n               AA( IOFF ) = A( I, J )\n               IF( I.EQ.J )THEN\n                  IF( UNIT )\n     $               AA( IOFF ) = ROGUE\n               END IF\n  180       CONTINUE\n  190    CONTINUE\n      END IF\n      RETURN\n*\n*     End of SMAKE.\n*\n      END\n      SUBROUTINE SMVCH( TRANS, M, N, ALPHA, A, NMAX, X, INCX, BETA, Y,\n     $                  INCY, YT, G, YY, EPS, ERR, FATAL, NOUT, MV )\n*\n*  Checks the results of the computational tests.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      REAL               ZERO, ONE\n      PARAMETER          ( ZERO = 0.0, ONE = 1.0 )\n*     .. Scalar Arguments ..\n      REAL               ALPHA, BETA, EPS, ERR\n      INTEGER            INCX, INCY, M, N, NMAX, NOUT\n      LOGICAL            FATAL, MV\n      CHARACTER*1        TRANS\n*     .. Array Arguments ..\n      REAL               A( NMAX, * ), G( * ), X( * ), Y( * ), YT( * ),\n     $                   YY( * )\n*     .. Local Scalars ..\n      REAL               ERRI\n      INTEGER            I, INCXL, INCYL, IY, J, JX, KX, KY, ML, NL\n      LOGICAL            TRAN\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, SQRT\n*     .. Executable Statements ..\n      TRAN = TRANS.EQ.'T'.OR.TRANS.EQ.'C'\n      IF( TRAN )THEN\n         ML = N\n         NL = M\n      ELSE\n         ML = M\n         NL = N\n      END IF\n      IF( INCX.LT.0 )THEN\n         KX = NL\n         INCXL = -1\n      ELSE\n         KX = 1\n         INCXL = 1\n      END IF\n      IF( INCY.LT.0 )THEN\n         KY = ML\n         INCYL = -1\n      ELSE\n         KY = 1\n         INCYL = 1\n      END IF\n*\n*     Compute expected result in YT using data in A, X and Y.\n*     Compute gauges in G.\n*\n      IY = KY\n      DO 30 I = 1, ML\n         YT( IY ) = ZERO\n         G( IY ) = ZERO\n         JX = KX\n         IF( TRAN )THEN\n            DO 10 J = 1, NL\n               YT( IY ) = YT( IY ) + A( J, I )*X( JX )\n               G( IY ) = G( IY ) + ABS( A( J, I )*X( JX ) )\n               JX = JX + INCXL\n   10       CONTINUE\n         ELSE\n            DO 20 J = 1, NL\n               YT( IY ) = YT( IY ) + A( I, J )*X( JX )\n               G( IY ) = G( IY ) + ABS( A( I, J )*X( JX ) )\n               JX = JX + INCXL\n   20       CONTINUE\n         END IF\n         YT( IY ) = ALPHA*YT( IY ) + BETA*Y( IY )\n         G( IY ) = ABS( ALPHA )*G( IY ) + ABS( BETA*Y( IY ) )\n         IY = IY + INCYL\n   30 CONTINUE\n*\n*     Compute the error ratio for this result.\n*\n      ERR = ZERO\n      DO 40 I = 1, ML\n         ERRI = ABS( YT( I ) - YY( 1 + ( I - 1 )*ABS( INCY ) ) )/EPS\n         IF( G( I ).NE.ZERO )\n     $      ERRI = ERRI/G( I )\n         ERR = MAX( ERR, ERRI )\n         IF( ERR*SQRT( EPS ).GE.ONE )\n     $      GO TO 50\n   40 CONTINUE\n*     If the loop completes, all results are at least half accurate.\n      GO TO 70\n*\n*     Report fatal error.\n*\n   50 FATAL = .TRUE.\n      WRITE( NOUT, FMT = 9999 )\n      DO 60 I = 1, ML\n         IF( MV )THEN\n            WRITE( NOUT, FMT = 9998 )I, YT( I ),\n     $         YY( 1 + ( I - 1 )*ABS( INCY ) )\n         ELSE\n            WRITE( NOUT, FMT = 9998 )I, \n     $         YY( 1 + ( I - 1 )*ABS( INCY ) ), YT(I)\n         END IF\n   60 CONTINUE\n*\n   70 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ******* FATAL ERROR - COMPUTED RESULT IS LESS THAN HAL',\n     $      'F ACCURATE *******', /'           EXPECTED RESULT   COMPU',\n     $      'TED RESULT' )\n 9998 FORMAT( 1X, I7, 2G18.6 )\n*\n*     End of SMVCH.\n*\n      END\n      LOGICAL FUNCTION LSE( RI, RJ, LR )\n*\n*  Tests if two arrays are identical.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LR\n*     .. Array Arguments ..\n      REAL               RI( * ), RJ( * )\n*     .. Local Scalars ..\n      INTEGER            I\n*     .. Executable Statements ..\n      DO 10 I = 1, LR\n         IF( RI( I ).NE.RJ( I ) )\n     $      GO TO 20\n   10 CONTINUE\n      LSE = .TRUE.\n      GO TO 30\n   20 CONTINUE\n      LSE = .FALSE.\n   30 RETURN\n*\n*     End of LSE.\n*\n      END\n      LOGICAL FUNCTION LSERES( TYPE, UPLO, M, N, AA, AS, LDA )\n*\n*  Tests if selected elements in two arrays are equal.\n*\n*  TYPE is 'GE', 'SY' or 'SP'.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LDA, M, N\n      CHARACTER*1        UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      REAL               AA( LDA, * ), AS( LDA, * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J\n      LOGICAL            UPPER\n*     .. Executable Statements ..\n      UPPER = UPLO.EQ.'U'\n      IF( TYPE.EQ.'GE' )THEN\n         DO 20 J = 1, N\n            DO 10 I = M + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   10       CONTINUE\n   20    CONTINUE\n      ELSE IF( TYPE.EQ.'SY' )THEN\n         DO 50 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 30 I = 1, IBEG - 1\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   30       CONTINUE\n            DO 40 I = IEND + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   40       CONTINUE\n   50    CONTINUE\n      END IF\n*\n      LSERES = .TRUE.\n      GO TO 80\n   70 CONTINUE\n      LSERES = .FALSE.\n   80 RETURN\n*\n*     End of LSERES.\n*\n      END\n      REAL FUNCTION SBEG( RESET )\n*\n*  Generates random numbers uniformly distributed between -0.5 and 0.5.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      LOGICAL            RESET\n*     .. Local Scalars ..\n      INTEGER            I, IC, MI\n*     .. Save statement ..\n      SAVE               I, IC, MI\n*     .. Intrinsic Functions ..\n      INTRINSIC          REAL\n*     .. Executable Statements ..\n      IF( RESET )THEN\n*        Initialize local variables.\n         MI = 891\n         I = 7\n         IC = 0\n         RESET = .FALSE.\n      END IF\n*\n*     The sequence of values of I is bounded between 1 and 999.\n*     If initial I = 1,2,3,6,7 or 9, the period will be 50.\n*     If initial I = 4 or 8, the period will be 25.\n*     If initial I = 5, the period will be 10.\n*     IC is used to break up the period by skipping 1 value of I in 6.\n*\n      IC = IC + 1\n   10 I = I*MI\n      I = I - 1000*( I/1000 )\n      IF( IC.GE.5 )THEN\n         IC = 0\n         GO TO 10\n      END IF\n      SBEG = REAL( I - 500 )/1001.0\n      RETURN\n*\n*     End of SBEG.\n*\n      END\n      REAL FUNCTION SDIFF( X, Y )\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*\n*     .. Scalar Arguments ..\n      REAL               X, Y\n*     .. Executable Statements ..\n      SDIFF = X - Y\n      RETURN\n*\n*     End of SDIFF.\n*\n      END\n      SUBROUTINE CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n*  Tests whether XERBLA has detected an error when it should.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Executable Statements ..\n      IF( .NOT.LERR )THEN\n         WRITE( NOUT, FMT = 9999 )INFOT, SRNAMT\n         OK = .FALSE.\n      END IF\n      LERR = .FALSE.\n      RETURN\n*\n 9999 FORMAT( ' ***** ILLEGAL VALUE OF PARAMETER NUMBER ', I2, ' NOT D',\n     $      'ETECTED BY ', A6, ' *****' )\n*\n*     End of CHKXER.\n*\n      END\n      SUBROUTINE XERBLA( SRNAME, INFO )\n*\n*  This is a special version of XERBLA to be used only as part of\n*  the test program for testing error exits from the Level 2 BLAS\n*  routines.\n*\n*  XERBLA  is an error handler for the Level 2 BLAS routines.\n*\n*  It is called by the Level 2 BLAS routines if an input parameter is\n*  invalid.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFO\n      CHARACTER*6        SRNAME\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUT, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Executable Statements ..\n      LERR = .TRUE.\n      IF( INFO.NE.INFOT )THEN\n         IF( INFOT.NE.0 )THEN\n            WRITE( NOUT, FMT = 9999 )INFO, INFOT\n         ELSE\n            WRITE( NOUT, FMT = 9997 )INFO\n         END IF\n         OK = .FALSE.\n      END IF\n      IF( SRNAME.NE.SRNAMT )THEN\n         WRITE( NOUT, FMT = 9998 )SRNAME, SRNAMT\n         OK = .FALSE.\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6, ' INSTEAD',\n     $      ' OF ', I2, ' *******' )\n 9998 FORMAT( ' ******* XERBLA WAS CALLED WITH SRNAME = ', A6, ' INSTE',\n     $      'AD OF ', A6, ' *******' )\n 9997 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6,\n     $      ' *******' )\n*\n*     End of XERBLA\n*\n      END\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/testing/sblat3.f",
    "content": "*> \\brief \\b SBLAT3\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM SBLAT3\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> Test program for the REAL             Level 3 Blas.\n*>\n*> The program must be driven by a short data file. The first 14 records\n*> of the file are read using list-directed input, the last 6 records\n*> are read using the format ( A6, L2 ). An annotated example of a data\n*> file can be obtained by deleting the first 3 characters from the\n*> following 20 lines:\n*> 'sblat3.out'      NAME OF SUMMARY OUTPUT FILE\n*> 6                 UNIT NUMBER OF SUMMARY FILE\n*> 'SBLAT3.SNAP'     NAME OF SNAPSHOT OUTPUT FILE\n*> -1                UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0)\n*> F        LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD.\n*> F        LOGICAL FLAG, T TO STOP ON FAILURES.\n*> T        LOGICAL FLAG, T TO TEST ERROR EXITS.\n*> 16.0     THRESHOLD VALUE OF TEST RATIO\n*> 6                 NUMBER OF VALUES OF N\n*> 0 1 2 3 5 9       VALUES OF N\n*> 3                 NUMBER OF VALUES OF ALPHA\n*> 0.0 1.0 0.7       VALUES OF ALPHA\n*> 3                 NUMBER OF VALUES OF BETA\n*> 0.0 1.0 1.3       VALUES OF BETA\n*> SGEMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> SSYMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> STRMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> STRSM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> SSYRK  T PUT F FOR NO TEST. SAME COLUMNS.\n*> SSYR2K T PUT F FOR NO TEST. SAME COLUMNS.\n*>\n*> Further Details\n*> ===============\n*>\n*> See:\n*>\n*>    Dongarra J. J., Du Croz J. J., Duff I. S. and Hammarling S.\n*>    A Set of Level 3 Basic Linear Algebra Subprograms.\n*>\n*>    Technical Memorandum No.88 (Revision 1), Mathematics and\n*>    Computer Science Division, Argonne National Laboratory, 9700\n*>    South Cass Avenue, Argonne, Illinois 60439, US.\n*>\n*> -- Written on 8-February-1989.\n*>    Jack Dongarra, Argonne National Laboratory.\n*>    Iain Duff, AERE Harwell.\n*>    Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*>    Sven Hammarling, Numerical Algorithms Group Ltd.\n*>\n*>    10-9-00:  Change STATUS='NEW' to 'UNKNOWN' so that the testers\n*>              can be run multiple times without deleting generated\n*>              output files (susan)\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup single_blas_testing\n*\n*  =====================================================================\n      PROGRAM SBLAT3\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER            NIN\n      PARAMETER          ( NIN = 5 )\n      INTEGER            NSUBS\n      PARAMETER          ( NSUBS = 6 )\n      REAL               ZERO, ONE\n      PARAMETER          ( ZERO = 0.0, ONE = 1.0 )\n      INTEGER            NMAX\n      PARAMETER          ( NMAX = 65 )\n      INTEGER            NIDMAX, NALMAX, NBEMAX\n      PARAMETER          ( NIDMAX = 9, NALMAX = 7, NBEMAX = 7 )\n*     .. Local Scalars ..\n      REAL               EPS, ERR, THRESH\n      INTEGER            I, ISNUM, J, N, NALF, NBET, NIDIM, NOUT, NTRA\n      LOGICAL            FATAL, LTESTT, REWI, SAME, SFATAL, TRACE,\n     $                   TSTERR\n      CHARACTER*1        TRANSA, TRANSB\n      CHARACTER*6        SNAMET\n      CHARACTER*32       SNAPS, SUMMRY\n*     .. Local Arrays ..\n      REAL               AA( NMAX*NMAX ), AB( NMAX, 2*NMAX ),\n     $                   ALF( NALMAX ), AS( NMAX*NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBEMAX ),\n     $                   BS( NMAX*NMAX ), C( NMAX, NMAX ),\n     $                   CC( NMAX*NMAX ), CS( NMAX*NMAX ), CT( NMAX ),\n     $                   G( NMAX ), W( 2*NMAX )\n      INTEGER            IDIM( NIDMAX )\n      LOGICAL            LTEST( NSUBS )\n      CHARACTER*6        SNAMES( NSUBS )\n*     .. External Functions ..\n      REAL               SDIFF\n      LOGICAL            LSE\n      EXTERNAL           SDIFF, LSE\n*     .. External Subroutines ..\n      EXTERNAL           SCHK1, SCHK2, SCHK3, SCHK4, SCHK5, SCHKE, SMMCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Data statements ..\n      DATA               SNAMES/'SGEMM ', 'SSYMM ', 'STRMM ', 'STRSM ',\n     $                   'SSYRK ', 'SSYR2K'/\n*     .. Executable Statements ..\n*\n*     Read name and unit number for summary output file and open file.\n*\n      READ( NIN, FMT = * )SUMMRY\n      READ( NIN, FMT = * )NOUT\n      OPEN( NOUT, FILE = SUMMRY )\n      NOUTC = NOUT\n*\n*     Read name and unit number for snapshot output file and open file.\n*\n      READ( NIN, FMT = * )SNAPS\n      READ( NIN, FMT = * )NTRA\n      TRACE = NTRA.GE.0\n      IF( TRACE )THEN\n         OPEN( NTRA, FILE = SNAPS )\n      END IF\n*     Read the flag that directs rewinding of the snapshot file.\n      READ( NIN, FMT = * )REWI\n      REWI = REWI.AND.TRACE\n*     Read the flag that directs stopping on any failure.\n      READ( NIN, FMT = * )SFATAL\n*     Read the flag that indicates whether error exits are to be tested.\n      READ( NIN, FMT = * )TSTERR\n*     Read the threshold value of the test ratio\n      READ( NIN, FMT = * )THRESH\n*\n*     Read and check the parameter values for the tests.\n*\n*     Values of N\n      READ( NIN, FMT = * )NIDIM\n      IF( NIDIM.LT.1.OR.NIDIM.GT.NIDMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'N', NIDMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( IDIM( I ), I = 1, NIDIM )\n      DO 10 I = 1, NIDIM\n         IF( IDIM( I ).LT.0.OR.IDIM( I ).GT.NMAX )THEN\n            WRITE( NOUT, FMT = 9996 )NMAX\n            GO TO 220\n         END IF\n   10 CONTINUE\n*     Values of ALPHA\n      READ( NIN, FMT = * )NALF\n      IF( NALF.LT.1.OR.NALF.GT.NALMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'ALPHA', NALMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( ALF( I ), I = 1, NALF )\n*     Values of BETA\n      READ( NIN, FMT = * )NBET\n      IF( NBET.LT.1.OR.NBET.GT.NBEMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'BETA', NBEMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( BET( I ), I = 1, NBET )\n*\n*     Report values of parameters.\n*\n      WRITE( NOUT, FMT = 9995 )\n      WRITE( NOUT, FMT = 9994 )( IDIM( I ), I = 1, NIDIM )\n      WRITE( NOUT, FMT = 9993 )( ALF( I ), I = 1, NALF )\n      WRITE( NOUT, FMT = 9992 )( BET( I ), I = 1, NBET )\n      IF( .NOT.TSTERR )THEN\n         WRITE( NOUT, FMT = * )\n         WRITE( NOUT, FMT = 9984 )\n      END IF\n      WRITE( NOUT, FMT = * )\n      WRITE( NOUT, FMT = 9999 )THRESH\n      WRITE( NOUT, FMT = * )\n*\n*     Read names of subroutines and flags which indicate\n*     whether they are to be tested.\n*\n      DO 20 I = 1, NSUBS\n         LTEST( I ) = .FALSE.\n   20 CONTINUE\n   30 READ( NIN, FMT = 9988, END = 60 )SNAMET, LTESTT\n      DO 40 I = 1, NSUBS\n         IF( SNAMET.EQ.SNAMES( I ) )\n     $      GO TO 50\n   40 CONTINUE\n      WRITE( NOUT, FMT = 9990 )SNAMET\n      STOP\n   50 LTEST( I ) = LTESTT\n      GO TO 30\n*\n   60 CONTINUE\n      CLOSE ( NIN )\n*\n*     Compute EPS (the machine precision).\n*\n      EPS = EPSILON(ZERO)\n      WRITE( NOUT, FMT = 9998 )EPS\n*\n*     Check the reliability of SMMCH using exact data.\n*\n      N = MIN( 32, NMAX )\n      DO 100 J = 1, N\n         DO 90 I = 1, N\n            AB( I, J ) = MAX( I - J + 1, 0 )\n   90    CONTINUE\n         AB( J, NMAX + 1 ) = J\n         AB( 1, NMAX + J ) = J\n         C( J, 1 ) = ZERO\n  100 CONTINUE\n      DO 110 J = 1, N\n         CC( J ) = J*( ( J + 1 )*J )/2 - ( ( J + 1 )*J*( J - 1 ) )/3\n  110 CONTINUE\n*     CC holds the exact result. On exit from SMMCH CT holds\n*     the result computed by SMMCH.\n      TRANSA = 'N'\n      TRANSB = 'N'\n      CALL SMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LSE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      TRANSB = 'T'\n      CALL SMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LSE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      DO 120 J = 1, N\n         AB( J, NMAX + 1 ) = N - J + 1\n         AB( 1, NMAX + J ) = N - J + 1\n  120 CONTINUE\n      DO 130 J = 1, N\n         CC( N - J + 1 ) = J*( ( J + 1 )*J )/2 -\n     $                     ( ( J + 1 )*J*( J - 1 ) )/3\n  130 CONTINUE\n      TRANSA = 'T'\n      TRANSB = 'N'\n      CALL SMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LSE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      TRANSB = 'T'\n      CALL SMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LSE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n*\n*     Test each subroutine in turn.\n*\n      DO 200 ISNUM = 1, NSUBS\n         WRITE( NOUT, FMT = * )\n         IF( .NOT.LTEST( ISNUM ) )THEN\n*           Subprogram is not to be tested.\n            WRITE( NOUT, FMT = 9987 )SNAMES( ISNUM )\n         ELSE\n            SRNAMT = SNAMES( ISNUM )\n*           Test error exits.\n            IF( TSTERR )THEN\n               CALL SCHKE( ISNUM, SNAMES( ISNUM ), NOUT )\n               WRITE( NOUT, FMT = * )\n            END IF\n*           Test computations.\n            INFOT = 0\n            OK = .TRUE.\n            FATAL = .FALSE.\n            GO TO ( 140, 150, 160, 160, 170, 180 )ISNUM\n*           Test SGEMM, 01.\n  140       CALL SCHK1( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test SSYMM, 02.\n  150       CALL SCHK2( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test STRMM, 03, STRSM, 04.\n  160       CALL SCHK3( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NMAX, AB,\n     $                  AA, AS, AB( 1, NMAX + 1 ), BB, BS, CT, G, C )\n            GO TO 190\n*           Test SSYRK, 05.\n  170       CALL SCHK4( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test SSYR2K, 06.\n  180       CALL SCHK5( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, BB, BS, C, CC, CS, CT, G, W )\n            GO TO 190\n*\n  190       IF( FATAL.AND.SFATAL )\n     $         GO TO 210\n         END IF\n  200 CONTINUE\n      WRITE( NOUT, FMT = 9986 )\n      GO TO 230\n*\n  210 CONTINUE\n      WRITE( NOUT, FMT = 9985 )\n      GO TO 230\n*\n  220 CONTINUE\n      WRITE( NOUT, FMT = 9991 )\n*\n  230 CONTINUE\n      IF( TRACE )\n     $   CLOSE ( NTRA )\n      CLOSE ( NOUT )\n      STOP\n*\n 9999 FORMAT( ' ROUTINES PASS COMPUTATIONAL TESTS IF TEST RATIO IS LES',\n     $      'S THAN', F8.2 )\n 9998 FORMAT( ' RELATIVE MACHINE PRECISION IS TAKEN TO BE', 1P, E9.1 )\n 9997 FORMAT( ' NUMBER OF VALUES OF ', A, ' IS LESS THAN 1 OR GREATER ',\n     $      'THAN ', I2 )\n 9996 FORMAT( ' VALUE OF N IS LESS THAN 0 OR GREATER THAN ', I2 )\n 9995 FORMAT( ' TESTS OF THE REAL             LEVEL 3 BLAS', //' THE F',\n     $      'OLLOWING PARAMETER VALUES WILL BE USED:' )\n 9994 FORMAT( '   FOR N              ', 9I6 )\n 9993 FORMAT( '   FOR ALPHA          ', 7F6.1 )\n 9992 FORMAT( '   FOR BETA           ', 7F6.1 )\n 9991 FORMAT( ' AMEND DATA FILE OR INCREASE ARRAY SIZES IN PROGRAM',\n     $      /' ******* TESTS ABANDONED *******' )\n 9990 FORMAT( ' SUBPROGRAM NAME ', A6, ' NOT RECOGNIZED', /' ******* T',\n     $      'ESTS ABANDONED *******' )\n 9989 FORMAT( ' ERROR IN SMMCH -  IN-LINE DOT PRODUCTS ARE BEING EVALU',\n     $      'ATED WRONGLY.', /' SMMCH WAS CALLED WITH TRANSA = ', A1,\n     $      ' AND TRANSB = ', A1, /' AND RETURNED SAME = ', L1, ' AND ',\n     $      'ERR = ', F12.3, '.', /' THIS MAY BE DUE TO FAULTS IN THE ',\n     $      'ARITHMETIC OR THE COMPILER.', /' ******* TESTS ABANDONED ',\n     $      '*******' )\n 9988 FORMAT( A6, L2 )\n 9987 FORMAT( 1X, A6, ' WAS NOT TESTED' )\n 9986 FORMAT( /' END OF TESTS' )\n 9985 FORMAT( /' ******* FATAL ERROR - TESTS ABANDONED *******' )\n 9984 FORMAT( ' ERROR-EXITS WILL NOT BE TESTED' )\n*\n*     End of SBLAT3.\n*\n      END\n      SUBROUTINE SCHK1( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests SGEMM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      REAL               ZERO\n      PARAMETER          ( ZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX ), G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      REAL               ALPHA, ALS, BETA, BLS, ERR, ERRMAX\n      INTEGER            I, IA, IB, ICA, ICB, IK, IM, IN, K, KS, LAA,\n     $                   LBB, LCC, LDA, LDAS, LDB, LDBS, LDC, LDCS, M,\n     $                   MA, MB, MS, N, NA, NARGS, NB, NC, NS\n      LOGICAL            NULL, RESET, SAME, TRANA, TRANB\n      CHARACTER*1        TRANAS, TRANBS, TRANSA, TRANSB\n      CHARACTER*3        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SGEMM, SMAKE, SMMCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'NTC'/\n*     .. Executable Statements ..\n*\n      NARGS = 13\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 110 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 100 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDC to 1 more than minimum value if room.\n            LDC = M\n            IF( LDC.LT.NMAX )\n     $         LDC = LDC + 1\n*           Skip tests if not enough room.\n            IF( LDC.GT.NMAX )\n     $         GO TO 100\n            LCC = LDC*N\n            NULL = N.LE.0.OR.M.LE.0\n*\n            DO 90 IK = 1, NIDIM\n               K = IDIM( IK )\n*\n               DO 80 ICA = 1, 3\n                  TRANSA = ICH( ICA: ICA )\n                  TRANA = TRANSA.EQ.'T'.OR.TRANSA.EQ.'C'\n*\n                  IF( TRANA )THEN\n                     MA = K\n                     NA = M\n                  ELSE\n                     MA = M\n                     NA = K\n                  END IF\n*                 Set LDA to 1 more than minimum value if room.\n                  LDA = MA\n                  IF( LDA.LT.NMAX )\n     $               LDA = LDA + 1\n*                 Skip tests if not enough room.\n                  IF( LDA.GT.NMAX )\n     $               GO TO 80\n                  LAA = LDA*NA\n*\n*                 Generate the matrix A.\n*\n                  CALL SMAKE( 'GE', ' ', ' ', MA, NA, A, NMAX, AA, LDA,\n     $                        RESET, ZERO )\n*\n                  DO 70 ICB = 1, 3\n                     TRANSB = ICH( ICB: ICB )\n                     TRANB = TRANSB.EQ.'T'.OR.TRANSB.EQ.'C'\n*\n                     IF( TRANB )THEN\n                        MB = N\n                        NB = K\n                     ELSE\n                        MB = K\n                        NB = N\n                     END IF\n*                    Set LDB to 1 more than minimum value if room.\n                     LDB = MB\n                     IF( LDB.LT.NMAX )\n     $                  LDB = LDB + 1\n*                    Skip tests if not enough room.\n                     IF( LDB.GT.NMAX )\n     $                  GO TO 70\n                     LBB = LDB*NB\n*\n*                    Generate the matrix B.\n*\n                     CALL SMAKE( 'GE', ' ', ' ', MB, NB, B, NMAX, BB,\n     $                           LDB, RESET, ZERO )\n*\n                     DO 60 IA = 1, NALF\n                        ALPHA = ALF( IA )\n*\n                        DO 50 IB = 1, NBET\n                           BETA = BET( IB )\n*\n*                          Generate the matrix C.\n*\n                           CALL SMAKE( 'GE', ' ', ' ', M, N, C, NMAX,\n     $                                 CC, LDC, RESET, ZERO )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           TRANAS = TRANSA\n                           TRANBS = TRANSB\n                           MS = M\n                           NS = N\n                           KS = K\n                           ALS = ALPHA\n                           DO 10 I = 1, LAA\n                              AS( I ) = AA( I )\n   10                      CONTINUE\n                           LDAS = LDA\n                           DO 20 I = 1, LBB\n                              BS( I ) = BB( I )\n   20                      CONTINUE\n                           LDBS = LDB\n                           BLS = BETA\n                           DO 30 I = 1, LCC\n                              CS( I ) = CC( I )\n   30                      CONTINUE\n                           LDCS = LDC\n*\n*                          Call the subroutine.\n*\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                        TRANSA, TRANSB, M, N, K, ALPHA, LDA, LDB,\n     $                        BETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL SGEMM( TRANSA, TRANSB, M, N, K, ALPHA,\n     $                                 AA, LDA, BB, LDB, BETA, CC, LDC )\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9994 )\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = TRANSA.EQ.TRANAS\n                           ISAME( 2 ) = TRANSB.EQ.TRANBS\n                           ISAME( 3 ) = MS.EQ.M\n                           ISAME( 4 ) = NS.EQ.N\n                           ISAME( 5 ) = KS.EQ.K\n                           ISAME( 6 ) = ALS.EQ.ALPHA\n                           ISAME( 7 ) = LSE( AS, AA, LAA )\n                           ISAME( 8 ) = LDAS.EQ.LDA\n                           ISAME( 9 ) = LSE( BS, BB, LBB )\n                           ISAME( 10 ) = LDBS.EQ.LDB\n                           ISAME( 11 ) = BLS.EQ.BETA\n                           IF( NULL )THEN\n                              ISAME( 12 ) = LSE( CS, CC, LCC )\n                           ELSE\n                              ISAME( 12 ) = LSERES( 'GE', ' ', M, N, CS,\n     $                                      CC, LDC )\n                           END IF\n                           ISAME( 13 ) = LDCS.EQ.LDC\n*\n*                          If data was incorrectly changed, report\n*                          and return.\n*\n                           SAME = .TRUE.\n                           DO 40 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   40                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n*\n*                             Check the result.\n*\n                              CALL SMMCH( TRANSA, TRANSB, M, N, K,\n     $                                    ALPHA, A, NMAX, B, NMAX, BETA,\n     $                                    C, NMAX, CT, G, CC, LDC, EPS,\n     $                                    ERR, FATAL, NOUT, .TRUE. )\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 120\n                           END IF\n*\n   50                   CONTINUE\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, TRANSA, TRANSB, M, N, K,\n     $   ALPHA, LDA, LDB, BETA, LDC\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',''', A1, ''',',\n     $      3( I3, ',' ), F4.1, ', A,', I3, ', B,', I3, ',', F4.1, ', ',\n     $      'C,', I3, ').' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK1.\n*\n      END\n      SUBROUTINE SCHK2( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests SSYMM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      REAL               ZERO\n      PARAMETER          ( ZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX ), G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      REAL               ALPHA, ALS, BETA, BLS, ERR, ERRMAX\n      INTEGER            I, IA, IB, ICS, ICU, IM, IN, LAA, LBB, LCC,\n     $                   LDA, LDAS, LDB, LDBS, LDC, LDCS, M, MS, N, NA,\n     $                   NARGS, NC, NS\n      LOGICAL            LEFT, NULL, RESET, SAME\n      CHARACTER*1        SIDE, SIDES, UPLO, UPLOS\n      CHARACTER*2        ICHS, ICHU\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SMAKE, SMMCH, SSYMM\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHS/'LR'/, ICHU/'UL'/\n*     .. Executable Statements ..\n*\n      NARGS = 12\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 100 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 90 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDC to 1 more than minimum value if room.\n            LDC = M\n            IF( LDC.LT.NMAX )\n     $         LDC = LDC + 1\n*           Skip tests if not enough room.\n            IF( LDC.GT.NMAX )\n     $         GO TO 90\n            LCC = LDC*N\n            NULL = N.LE.0.OR.M.LE.0\n*\n*           Set LDB to 1 more than minimum value if room.\n            LDB = M\n            IF( LDB.LT.NMAX )\n     $         LDB = LDB + 1\n*           Skip tests if not enough room.\n            IF( LDB.GT.NMAX )\n     $         GO TO 90\n            LBB = LDB*N\n*\n*           Generate the matrix B.\n*\n            CALL SMAKE( 'GE', ' ', ' ', M, N, B, NMAX, BB, LDB, RESET,\n     $                  ZERO )\n*\n            DO 80 ICS = 1, 2\n               SIDE = ICHS( ICS: ICS )\n               LEFT = SIDE.EQ.'L'\n*\n               IF( LEFT )THEN\n                  NA = M\n               ELSE\n                  NA = N\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = NA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 80\n               LAA = LDA*NA\n*\n               DO 70 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n*\n*                 Generate the symmetric matrix A.\n*\n                  CALL SMAKE( 'SY', UPLO, ' ', NA, NA, A, NMAX, AA, LDA,\n     $                        RESET, ZERO )\n*\n                  DO 60 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n                     DO 50 IB = 1, NBET\n                        BETA = BET( IB )\n*\n*                       Generate the matrix C.\n*\n                        CALL SMAKE( 'GE', ' ', ' ', M, N, C, NMAX, CC,\n     $                              LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the\n*                       subroutine.\n*\n                        SIDES = SIDE\n                        UPLOS = UPLO\n                        MS = M\n                        NS = N\n                        ALS = ALPHA\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        DO 20 I = 1, LBB\n                           BS( I ) = BB( I )\n   20                   CONTINUE\n                        LDBS = LDB\n                        BLS = BETA\n                        DO 30 I = 1, LCC\n                           CS( I ) = CC( I )\n   30                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9995 )NC, SNAME, SIDE,\n     $                     UPLO, M, N, ALPHA, LDA, LDB, BETA, LDC\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL SSYMM( SIDE, UPLO, M, N, ALPHA, AA, LDA,\n     $                              BB, LDB, BETA, CC, LDC )\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9994 )\n                           FATAL = .TRUE.\n                           GO TO 110\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = SIDES.EQ.SIDE\n                        ISAME( 2 ) = UPLOS.EQ.UPLO\n                        ISAME( 3 ) = MS.EQ.M\n                        ISAME( 4 ) = NS.EQ.N\n                        ISAME( 5 ) = ALS.EQ.ALPHA\n                        ISAME( 6 ) = LSE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        ISAME( 8 ) = LSE( BS, BB, LBB )\n                        ISAME( 9 ) = LDBS.EQ.LDB\n                        ISAME( 10 ) = BLS.EQ.BETA\n                        IF( NULL )THEN\n                           ISAME( 11 ) = LSE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 11 ) = LSERES( 'GE', ' ', M, N, CS,\n     $                                   CC, LDC )\n                        END IF\n                        ISAME( 12 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 110\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result.\n*\n                           IF( LEFT )THEN\n                              CALL SMMCH( 'N', 'N', M, N, M, ALPHA, A,\n     $                                    NMAX, B, NMAX, BETA, C, NMAX,\n     $                                    CT, G, CC, LDC, EPS, ERR,\n     $                                    FATAL, NOUT, .TRUE. )\n                           ELSE\n                              CALL SMMCH( 'N', 'N', M, N, N, ALPHA, B,\n     $                                    NMAX, A, NMAX, BETA, C, NMAX,\n     $                                    CT, G, CC, LDC, EPS, ERR,\n     $                                    FATAL, NOUT, .TRUE. )\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and\n*                          return.\n                           IF( FATAL )\n     $                        GO TO 110\n                        END IF\n*\n   50                CONTINUE\n*\n   60             CONTINUE\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 120\n*\n  110 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, SIDE, UPLO, M, N, ALPHA, LDA,\n     $   LDB, BETA, LDC\n*\n  120 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      F4.1, ', A,', I3, ', B,', I3, ',', F4.1, ', C,', I3, ')   ',\n     $      ' .' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK2.\n*\n      END\n      SUBROUTINE SCHK3( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NMAX, A, AA, AS,\n     $                  B, BB, BS, CT, G, C )\n*\n*  Tests STRMM and STRSM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      REAL               ZERO, ONE\n      PARAMETER          ( ZERO = 0.0, ONE = 1.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            NALF, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CT( NMAX ), G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      REAL               ALPHA, ALS, ERR, ERRMAX\n      INTEGER            I, IA, ICD, ICS, ICT, ICU, IM, IN, J, LAA, LBB,\n     $                   LDA, LDAS, LDB, LDBS, M, MS, N, NA, NARGS, NC,\n     $                   NS\n      LOGICAL            LEFT, NULL, RESET, SAME\n      CHARACTER*1        DIAG, DIAGS, SIDE, SIDES, TRANAS, TRANSA, UPLO,\n     $                   UPLOS\n      CHARACTER*2        ICHD, ICHS, ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SMAKE, SMMCH, STRMM, STRSM\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHU/'UL'/, ICHT/'NTC'/, ICHD/'UN'/, ICHS/'LR'/\n*     .. Executable Statements ..\n*\n      NARGS = 11\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*     Set up zero matrix for SMMCH.\n      DO 20 J = 1, NMAX\n         DO 10 I = 1, NMAX\n            C( I, J ) = ZERO\n   10    CONTINUE\n   20 CONTINUE\n*\n      DO 140 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 130 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDB to 1 more than minimum value if room.\n            LDB = M\n            IF( LDB.LT.NMAX )\n     $         LDB = LDB + 1\n*           Skip tests if not enough room.\n            IF( LDB.GT.NMAX )\n     $         GO TO 130\n            LBB = LDB*N\n            NULL = M.LE.0.OR.N.LE.0\n*\n            DO 120 ICS = 1, 2\n               SIDE = ICHS( ICS: ICS )\n               LEFT = SIDE.EQ.'L'\n               IF( LEFT )THEN\n                  NA = M\n               ELSE\n                  NA = N\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = NA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 130\n               LAA = LDA*NA\n*\n               DO 110 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n*\n                  DO 100 ICT = 1, 3\n                     TRANSA = ICHT( ICT: ICT )\n*\n                     DO 90 ICD = 1, 2\n                        DIAG = ICHD( ICD: ICD )\n*\n                        DO 80 IA = 1, NALF\n                           ALPHA = ALF( IA )\n*\n*                          Generate the matrix A.\n*\n                           CALL SMAKE( 'TR', UPLO, DIAG, NA, NA, A,\n     $                                 NMAX, AA, LDA, RESET, ZERO )\n*\n*                          Generate the matrix B.\n*\n                           CALL SMAKE( 'GE', ' ', ' ', M, N, B, NMAX,\n     $                                 BB, LDB, RESET, ZERO )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           SIDES = SIDE\n                           UPLOS = UPLO\n                           TRANAS = TRANSA\n                           DIAGS = DIAG\n                           MS = M\n                           NS = N\n                           ALS = ALPHA\n                           DO 30 I = 1, LAA\n                              AS( I ) = AA( I )\n   30                      CONTINUE\n                           LDAS = LDA\n                           DO 40 I = 1, LBB\n                              BS( I ) = BB( I )\n   40                      CONTINUE\n                           LDBS = LDB\n*\n*                          Call the subroutine.\n*\n                           IF( SNAME( 4: 5 ).EQ.'MM' )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           SIDE, UPLO, TRANSA, DIAG, M, N, ALPHA,\n     $                           LDA, LDB\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL STRMM( SIDE, UPLO, TRANSA, DIAG, M,\n     $                                    N, ALPHA, AA, LDA, BB, LDB )\n                           ELSE IF( SNAME( 4: 5 ).EQ.'SM' )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           SIDE, UPLO, TRANSA, DIAG, M, N, ALPHA,\n     $                           LDA, LDB\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL STRSM( SIDE, UPLO, TRANSA, DIAG, M,\n     $                                    N, ALPHA, AA, LDA, BB, LDB )\n                           END IF\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9994 )\n                              FATAL = .TRUE.\n                              GO TO 150\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = SIDES.EQ.SIDE\n                           ISAME( 2 ) = UPLOS.EQ.UPLO\n                           ISAME( 3 ) = TRANAS.EQ.TRANSA\n                           ISAME( 4 ) = DIAGS.EQ.DIAG\n                           ISAME( 5 ) = MS.EQ.M\n                           ISAME( 6 ) = NS.EQ.N\n                           ISAME( 7 ) = ALS.EQ.ALPHA\n                           ISAME( 8 ) = LSE( AS, AA, LAA )\n                           ISAME( 9 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 10 ) = LSE( BS, BB, LBB )\n                           ELSE\n                              ISAME( 10 ) = LSERES( 'GE', ' ', M, N, BS,\n     $                                      BB, LDB )\n                           END IF\n                           ISAME( 11 ) = LDBS.EQ.LDB\n*\n*                          If data was incorrectly changed, report and\n*                          return.\n*\n                           SAME = .TRUE.\n                           DO 50 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   50                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 150\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n                              IF( SNAME( 4: 5 ).EQ.'MM' )THEN\n*\n*                                Check the result.\n*\n                                 IF( LEFT )THEN\n                                    CALL SMMCH( TRANSA, 'N', M, N, M,\n     $                                          ALPHA, A, NMAX, B, NMAX,\n     $                                          ZERO, C, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .TRUE. )\n                                 ELSE\n                                    CALL SMMCH( 'N', TRANSA, M, N, N,\n     $                                          ALPHA, B, NMAX, A, NMAX,\n     $                                          ZERO, C, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .TRUE. )\n                                 END IF\n                              ELSE IF( SNAME( 4: 5 ).EQ.'SM' )THEN\n*\n*                                Compute approximation to original\n*                                matrix.\n*\n                                 DO 70 J = 1, N\n                                    DO 60 I = 1, M\n                                       C( I, J ) = BB( I + ( J - 1 )*\n     $                                             LDB )\n                                       BB( I + ( J - 1 )*LDB ) = ALPHA*\n     $                                    B( I, J )\n   60                               CONTINUE\n   70                            CONTINUE\n*\n                                 IF( LEFT )THEN\n                                    CALL SMMCH( TRANSA, 'N', M, N, M,\n     $                                          ONE, A, NMAX, C, NMAX,\n     $                                          ZERO, B, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .FALSE. )\n                                 ELSE\n                                    CALL SMMCH( 'N', TRANSA, M, N, N,\n     $                                          ONE, C, NMAX, A, NMAX,\n     $                                          ZERO, B, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .FALSE. )\n                                 END IF\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 150\n                           END IF\n*\n   80                   CONTINUE\n*\n   90                CONTINUE\n*\n  100             CONTINUE\n*\n  110          CONTINUE\n*\n  120       CONTINUE\n*\n  130    CONTINUE\n*\n  140 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 160\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, SIDE, UPLO, TRANSA, DIAG, M,\n     $   N, ALPHA, LDA, LDB\n*\n  160 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 4( '''', A1, ''',' ), 2( I3, ',' ),\n     $      F4.1, ', A,', I3, ', B,', I3, ')        .' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK3.\n*\n      END\n      SUBROUTINE SCHK4( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests SSYRK.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      REAL               ZERO\n      PARAMETER          ( ZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX ), G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      REAL               ALPHA, ALS, BETA, BETS, ERR, ERRMAX\n      INTEGER            I, IA, IB, ICT, ICU, IK, IN, J, JC, JJ, K, KS,\n     $                   LAA, LCC, LDA, LDAS, LDC, LDCS, LJ, MA, N, NA,\n     $                   NARGS, NC, NS\n      LOGICAL            NULL, RESET, SAME, TRAN, UPPER\n      CHARACTER*1        TRANS, TRANSS, UPLO, UPLOS\n      CHARACTER*2        ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SMAKE, SMMCH, SSYRK\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHT/'NTC'/, ICHU/'UL'/\n*     .. Executable Statements ..\n*\n      NARGS = 10\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 100 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDC to 1 more than minimum value if room.\n         LDC = N\n         IF( LDC.LT.NMAX )\n     $      LDC = LDC + 1\n*        Skip tests if not enough room.\n         IF( LDC.GT.NMAX )\n     $      GO TO 100\n         LCC = LDC*N\n         NULL = N.LE.0\n*\n         DO 90 IK = 1, NIDIM\n            K = IDIM( IK )\n*\n            DO 80 ICT = 1, 3\n               TRANS = ICHT( ICT: ICT )\n               TRAN = TRANS.EQ.'T'.OR.TRANS.EQ.'C'\n               IF( TRAN )THEN\n                  MA = K\n                  NA = N\n               ELSE\n                  MA = N\n                  NA = K\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = MA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 80\n               LAA = LDA*NA\n*\n*              Generate the matrix A.\n*\n               CALL SMAKE( 'GE', ' ', ' ', MA, NA, A, NMAX, AA, LDA,\n     $                     RESET, ZERO )\n*\n               DO 70 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n                  UPPER = UPLO.EQ.'U'\n*\n                  DO 60 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n                     DO 50 IB = 1, NBET\n                        BETA = BET( IB )\n*\n*                       Generate the matrix C.\n*\n                        CALL SMAKE( 'SY', UPLO, ' ', N, N, C, NMAX, CC,\n     $                              LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        NS = N\n                        KS = K\n                        ALS = ALPHA\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        BETS = BETA\n                        DO 20 I = 1, LCC\n                           CS( I ) = CC( I )\n   20                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO,\n     $                     TRANS, N, K, ALPHA, LDA, BETA, LDC\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL SSYRK( UPLO, TRANS, N, K, ALPHA, AA, LDA,\n     $                              BETA, CC, LDC )\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9993 )\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLOS.EQ.UPLO\n                        ISAME( 2 ) = TRANSS.EQ.TRANS\n                        ISAME( 3 ) = NS.EQ.N\n                        ISAME( 4 ) = KS.EQ.K\n                        ISAME( 5 ) = ALS.EQ.ALPHA\n                        ISAME( 6 ) = LSE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        ISAME( 8 ) = BETS.EQ.BETA\n                        IF( NULL )THEN\n                           ISAME( 9 ) = LSE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 9 ) = LSERES( 'SY', UPLO, N, N, CS,\n     $                                  CC, LDC )\n                        END IF\n                        ISAME( 10 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 30 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   30                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result column by column.\n*\n                           JC = 1\n                           DO 40 J = 1, N\n                              IF( UPPER )THEN\n                                 JJ = 1\n                                 LJ = J\n                              ELSE\n                                 JJ = J\n                                 LJ = N - J + 1\n                              END IF\n                              IF( TRAN )THEN\n                                 CALL SMMCH( 'T', 'N', LJ, 1, K, ALPHA,\n     $                                       A( 1, JJ ), NMAX,\n     $                                       A( 1, J ), NMAX, BETA,\n     $                                       C( JJ, J ), NMAX, CT, G,\n     $                                       CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              ELSE\n                                 CALL SMMCH( 'N', 'T', LJ, 1, K, ALPHA,\n     $                                       A( JJ, 1 ), NMAX,\n     $                                       A( J, 1 ), NMAX, BETA,\n     $                                       C( JJ, J ), NMAX, CT, G,\n     $                                       CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              END IF\n                              IF( UPPER )THEN\n                                 JC = JC + LDC\n                              ELSE\n                                 JC = JC + LDC + 1\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 110\n   40                      CONTINUE\n                        END IF\n*\n   50                CONTINUE\n*\n   60             CONTINUE\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  110 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9995 )J\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, N, K, ALPHA,\n     $   LDA, BETA, LDC\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      F4.1, ', A,', I3, ',', F4.1, ', C,', I3, ')           .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK4.\n*\n      END\n      SUBROUTINE SCHK5( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  AB, AA, AS, BB, BS, C, CC, CS, CT, G, W )\n*\n*  Tests SSYR2K.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      REAL               ZERO\n      PARAMETER          ( ZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               AA( NMAX*NMAX ), AB( 2*NMAX*NMAX ),\n     $                   ALF( NALF ), AS( NMAX*NMAX ), BB( NMAX*NMAX ),\n     $                   BET( NBET ), BS( NMAX*NMAX ), C( NMAX, NMAX ),\n     $                   CC( NMAX*NMAX ), CS( NMAX*NMAX ), CT( NMAX ),\n     $                   G( NMAX ), W( 2*NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      REAL               ALPHA, ALS, BETA, BETS, ERR, ERRMAX\n      INTEGER            I, IA, IB, ICT, ICU, IK, IN, J, JC, JJ, JJAB,\n     $                   K, KS, LAA, LBB, LCC, LDA, LDAS, LDB, LDBS,\n     $                   LDC, LDCS, LJ, MA, N, NA, NARGS, NC, NS\n      LOGICAL            NULL, RESET, SAME, TRAN, UPPER\n      CHARACTER*1        TRANS, TRANSS, UPLO, UPLOS\n      CHARACTER*2        ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SMAKE, SMMCH, SSYR2K\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHT/'NTC'/, ICHU/'UL'/\n*     .. Executable Statements ..\n*\n      NARGS = 12\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 130 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDC to 1 more than minimum value if room.\n         LDC = N\n         IF( LDC.LT.NMAX )\n     $      LDC = LDC + 1\n*        Skip tests if not enough room.\n         IF( LDC.GT.NMAX )\n     $      GO TO 130\n         LCC = LDC*N\n         NULL = N.LE.0\n*\n         DO 120 IK = 1, NIDIM\n            K = IDIM( IK )\n*\n            DO 110 ICT = 1, 3\n               TRANS = ICHT( ICT: ICT )\n               TRAN = TRANS.EQ.'T'.OR.TRANS.EQ.'C'\n               IF( TRAN )THEN\n                  MA = K\n                  NA = N\n               ELSE\n                  MA = N\n                  NA = K\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = MA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 110\n               LAA = LDA*NA\n*\n*              Generate the matrix A.\n*\n               IF( TRAN )THEN\n                  CALL SMAKE( 'GE', ' ', ' ', MA, NA, AB, 2*NMAX, AA,\n     $                        LDA, RESET, ZERO )\n               ELSE\n                  CALL SMAKE( 'GE', ' ', ' ', MA, NA, AB, NMAX, AA, LDA,\n     $                        RESET, ZERO )\n               END IF\n*\n*              Generate the matrix B.\n*\n               LDB = LDA\n               LBB = LAA\n               IF( TRAN )THEN\n                  CALL SMAKE( 'GE', ' ', ' ', MA, NA, AB( K + 1 ),\n     $                        2*NMAX, BB, LDB, RESET, ZERO )\n               ELSE\n                  CALL SMAKE( 'GE', ' ', ' ', MA, NA, AB( K*NMAX + 1 ),\n     $                        NMAX, BB, LDB, RESET, ZERO )\n               END IF\n*\n               DO 100 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n                  UPPER = UPLO.EQ.'U'\n*\n                  DO 90 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n                     DO 80 IB = 1, NBET\n                        BETA = BET( IB )\n*\n*                       Generate the matrix C.\n*\n                        CALL SMAKE( 'SY', UPLO, ' ', N, N, C, NMAX, CC,\n     $                              LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        NS = N\n                        KS = K\n                        ALS = ALPHA\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        DO 20 I = 1, LBB\n                           BS( I ) = BB( I )\n   20                   CONTINUE\n                        LDBS = LDB\n                        BETS = BETA\n                        DO 30 I = 1, LCC\n                           CS( I ) = CC( I )\n   30                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO,\n     $                     TRANS, N, K, ALPHA, LDA, LDB, BETA, LDC\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL SSYR2K( UPLO, TRANS, N, K, ALPHA, AA, LDA,\n     $                               BB, LDB, BETA, CC, LDC )\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9993 )\n                           FATAL = .TRUE.\n                           GO TO 150\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLOS.EQ.UPLO\n                        ISAME( 2 ) = TRANSS.EQ.TRANS\n                        ISAME( 3 ) = NS.EQ.N\n                        ISAME( 4 ) = KS.EQ.K\n                        ISAME( 5 ) = ALS.EQ.ALPHA\n                        ISAME( 6 ) = LSE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        ISAME( 8 ) = LSE( BS, BB, LBB )\n                        ISAME( 9 ) = LDBS.EQ.LDB\n                        ISAME( 10 ) = BETS.EQ.BETA\n                        IF( NULL )THEN\n                           ISAME( 11 ) = LSE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 11 ) = LSERES( 'SY', UPLO, N, N, CS,\n     $                                   CC, LDC )\n                        END IF\n                        ISAME( 12 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 150\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result column by column.\n*\n                           JJAB = 1\n                           JC = 1\n                           DO 70 J = 1, N\n                              IF( UPPER )THEN\n                                 JJ = 1\n                                 LJ = J\n                              ELSE\n                                 JJ = J\n                                 LJ = N - J + 1\n                              END IF\n                              IF( TRAN )THEN\n                                 DO 50 I = 1, K\n                                    W( I ) = AB( ( J - 1 )*2*NMAX + K +\n     $                                       I )\n                                    W( K + I ) = AB( ( J - 1 )*2*NMAX +\n     $                                           I )\n   50                            CONTINUE\n                                 CALL SMMCH( 'T', 'N', LJ, 1, 2*K,\n     $                                       ALPHA, AB( JJAB ), 2*NMAX,\n     $                                       W, 2*NMAX, BETA,\n     $                                       C( JJ, J ), NMAX, CT, G,\n     $                                       CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              ELSE\n                                 DO 60 I = 1, K\n                                    W( I ) = AB( ( K + I - 1 )*NMAX +\n     $                                       J )\n                                    W( K + I ) = AB( ( I - 1 )*NMAX +\n     $                                           J )\n   60                            CONTINUE\n                                 CALL SMMCH( 'N', 'N', LJ, 1, 2*K,\n     $                                       ALPHA, AB( JJ ), NMAX, W,\n     $                                       2*NMAX, BETA, C( JJ, J ),\n     $                                       NMAX, CT, G, CC( JC ), LDC,\n     $                                       EPS, ERR, FATAL, NOUT,\n     $                                       .TRUE. )\n                              END IF\n                              IF( UPPER )THEN\n                                 JC = JC + LDC\n                              ELSE\n                                 JC = JC + LDC + 1\n                                 IF( TRAN )\n     $                              JJAB = JJAB + 2*NMAX\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 140\n   70                      CONTINUE\n                        END IF\n*\n   80                CONTINUE\n*\n   90             CONTINUE\n*\n  100          CONTINUE\n*\n  110       CONTINUE\n*\n  120    CONTINUE\n*\n  130 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 160\n*\n  140 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9995 )J\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, N, K, ALPHA,\n     $   LDA, LDB, BETA, LDC\n*\n  160 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      F4.1, ', A,', I3, ', B,', I3, ',', F4.1, ', C,', I3, ')   ',\n     $      ' .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK5.\n*\n      END\n      SUBROUTINE SCHKE( ISNUM, SRNAMT, NOUT )\n*\n*  Tests the error exits from the Level 3 Blas.\n*  Requires a special version of the error-handling routine XERBLA.\n*  A, B and C should not need to be defined.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*  3-19-92:  Initialize ALPHA and BETA  (eca)\n*  3-19-92:  Fix argument 12 in calls to SSYMM with INFOT = 9  (eca)\n*\n*     .. Scalar Arguments ..\n      INTEGER            ISNUM, NOUT\n      CHARACTER*6        SRNAMT\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Parameters ..\n      REAL               ONE, TWO\n      PARAMETER          ( ONE = 1.0E0, TWO = 2.0E0 )\n*     .. Local Scalars ..\n      REAL               ALPHA, BETA\n*     .. Local Arrays ..\n      REAL               A( 2, 1 ), B( 2, 1 ), C( 2, 1 )\n*     .. External Subroutines ..\n      EXTERNAL           CHKXER, SGEMM, SSYMM, SSYR2K, SSYRK, STRMM,\n     $                   STRSM\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n*     OK is set to .FALSE. by the special version of XERBLA or by CHKXER\n*     if anything is wrong.\n      OK = .TRUE.\n*     LERR is set to .TRUE. by the special version of XERBLA each time\n*     it is called, and is then tested and re-set by CHKXER.\n      LERR = .FALSE.\n*\n*     Initialize ALPHA and BETA.\n*\n      ALPHA = ONE\n      BETA = TWO\n*\n      GO TO ( 10, 20, 30, 40, 50, 60 )ISNUM\n   10 INFOT = 1\n      CALL SGEMM( '/', 'N', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 1\n      CALL SGEMM( '/', 'T', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SGEMM( 'N', '/', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SGEMM( 'T', '/', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SGEMM( 'N', 'N', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SGEMM( 'N', 'T', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SGEMM( 'T', 'N', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SGEMM( 'T', 'T', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SGEMM( 'N', 'N', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SGEMM( 'N', 'T', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SGEMM( 'T', 'N', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SGEMM( 'T', 'T', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SGEMM( 'N', 'N', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SGEMM( 'N', 'T', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SGEMM( 'T', 'N', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SGEMM( 'T', 'T', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL SGEMM( 'N', 'N', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL SGEMM( 'N', 'T', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL SGEMM( 'T', 'N', 0, 0, 2, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL SGEMM( 'T', 'T', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL SGEMM( 'N', 'N', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL SGEMM( 'T', 'N', 0, 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL SGEMM( 'N', 'T', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL SGEMM( 'T', 'T', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL SGEMM( 'N', 'N', 2, 0, 0, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL SGEMM( 'N', 'T', 2, 0, 0, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL SGEMM( 'T', 'N', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL SGEMM( 'T', 'T', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 70\n   20 INFOT = 1\n      CALL SSYMM( '/', 'U', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SSYMM( 'L', '/', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYMM( 'L', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYMM( 'R', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYMM( 'L', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYMM( 'R', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYMM( 'L', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYMM( 'R', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYMM( 'L', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYMM( 'R', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYMM( 'L', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYMM( 'R', 'U', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYMM( 'L', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYMM( 'R', 'L', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL SSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL SSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL SSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL SSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 70\n   30 INFOT = 1\n      CALL STRMM( '/', 'U', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL STRMM( 'L', '/', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL STRMM( 'L', 'U', '/', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL STRMM( 'L', 'U', 'N', '/', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRMM( 'L', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRMM( 'L', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRMM( 'R', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRMM( 'R', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRMM( 'L', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRMM( 'L', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRMM( 'R', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRMM( 'R', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRMM( 'L', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRMM( 'L', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRMM( 'R', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRMM( 'R', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRMM( 'L', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRMM( 'L', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRMM( 'R', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRMM( 'R', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRMM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRMM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRMM( 'R', 'U', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRMM( 'R', 'U', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRMM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRMM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRMM( 'R', 'L', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRMM( 'R', 'L', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRMM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRMM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRMM( 'R', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRMM( 'R', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRMM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRMM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRMM( 'R', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRMM( 'R', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 70\n   40 INFOT = 1\n      CALL STRSM( '/', 'U', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL STRSM( 'L', '/', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL STRSM( 'L', 'U', '/', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL STRSM( 'L', 'U', 'N', '/', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRSM( 'L', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRSM( 'L', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRSM( 'R', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRSM( 'R', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRSM( 'L', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRSM( 'L', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRSM( 'R', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRSM( 'R', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRSM( 'L', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRSM( 'L', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRSM( 'R', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRSM( 'R', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRSM( 'L', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRSM( 'L', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRSM( 'R', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRSM( 'R', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRSM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRSM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRSM( 'R', 'U', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRSM( 'R', 'U', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRSM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRSM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRSM( 'R', 'L', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRSM( 'R', 'L', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRSM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRSM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRSM( 'R', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRSM( 'R', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRSM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRSM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRSM( 'R', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRSM( 'R', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 70\n   50 INFOT = 1\n      CALL SSYRK( '/', 'N', 0, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SSYRK( 'U', '/', 0, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYRK( 'U', 'N', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYRK( 'U', 'T', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYRK( 'L', 'N', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYRK( 'L', 'T', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYRK( 'U', 'N', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYRK( 'U', 'T', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYRK( 'L', 'N', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYRK( 'L', 'T', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYRK( 'U', 'N', 2, 0, ALPHA, A, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYRK( 'U', 'T', 0, 2, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYRK( 'L', 'N', 2, 0, ALPHA, A, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYRK( 'L', 'T', 0, 2, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL SSYRK( 'U', 'N', 2, 0, ALPHA, A, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL SSYRK( 'U', 'T', 2, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL SSYRK( 'L', 'N', 2, 0, ALPHA, A, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL SSYRK( 'L', 'T', 2, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 70\n   60 INFOT = 1\n      CALL SSYR2K( '/', 'N', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SSYR2K( 'U', '/', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYR2K( 'U', 'N', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYR2K( 'U', 'T', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYR2K( 'L', 'N', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYR2K( 'L', 'T', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYR2K( 'U', 'N', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYR2K( 'U', 'T', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYR2K( 'L', 'N', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYR2K( 'L', 'T', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYR2K( 'U', 'N', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYR2K( 'U', 'T', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYR2K( 'L', 'N', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYR2K( 'L', 'T', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SSYR2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SSYR2K( 'U', 'T', 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SSYR2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SSYR2K( 'L', 'T', 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL SSYR2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL SSYR2K( 'U', 'T', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL SSYR2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL SSYR2K( 'L', 'T', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n   70 IF( OK )THEN\n         WRITE( NOUT, FMT = 9999 )SRNAMT\n      ELSE\n         WRITE( NOUT, FMT = 9998 )SRNAMT\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE TESTS OF ERROR-EXITS' )\n 9998 FORMAT( ' ******* ', A6, ' FAILED THE TESTS OF ERROR-EXITS *****',\n     $      '**' )\n*\n*     End of SCHKE.\n*\n      END\n      SUBROUTINE SMAKE( TYPE, UPLO, DIAG, M, N, A, NMAX, AA, LDA, RESET,\n     $                  TRANSL )\n*\n*  Generates values for an M by N matrix A.\n*  Stores the values in the array AA in the data structure required\n*  by the routine, with unwanted elements set to rogue value.\n*\n*  TYPE is 'GE', 'SY' or 'TR'.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      REAL               ZERO, ONE\n      PARAMETER          ( ZERO = 0.0, ONE = 1.0 )\n      REAL               ROGUE\n      PARAMETER          ( ROGUE = -1.0E10 )\n*     .. Scalar Arguments ..\n      REAL               TRANSL\n      INTEGER            LDA, M, N, NMAX\n      LOGICAL            RESET\n      CHARACTER*1        DIAG, UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      REAL               A( NMAX, * ), AA( * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J\n      LOGICAL            GEN, LOWER, SYM, TRI, UNIT, UPPER\n*     .. External Functions ..\n      REAL               SBEG\n      EXTERNAL           SBEG\n*     .. Executable Statements ..\n      GEN = TYPE.EQ.'GE'\n      SYM = TYPE.EQ.'SY'\n      TRI = TYPE.EQ.'TR'\n      UPPER = ( SYM.OR.TRI ).AND.UPLO.EQ.'U'\n      LOWER = ( SYM.OR.TRI ).AND.UPLO.EQ.'L'\n      UNIT = TRI.AND.DIAG.EQ.'U'\n*\n*     Generate data in array A.\n*\n      DO 20 J = 1, N\n         DO 10 I = 1, M\n            IF( GEN.OR.( UPPER.AND.I.LE.J ).OR.( LOWER.AND.I.GE.J ) )\n     $          THEN\n               A( I, J ) = SBEG( RESET ) + TRANSL\n               IF( I.NE.J )THEN\n*                 Set some elements to zero\n                  IF( N.GT.3.AND.J.EQ.N/2 )\n     $               A( I, J ) = ZERO\n                  IF( SYM )THEN\n                     A( J, I ) = A( I, J )\n                  ELSE IF( TRI )THEN\n                     A( J, I ) = ZERO\n                  END IF\n               END IF\n            END IF\n   10    CONTINUE\n         IF( TRI )\n     $      A( J, J ) = A( J, J ) + ONE\n         IF( UNIT )\n     $      A( J, J ) = ONE\n   20 CONTINUE\n*\n*     Store elements in array AS in data structure required by routine.\n*\n      IF( TYPE.EQ.'GE' )THEN\n         DO 50 J = 1, N\n            DO 30 I = 1, M\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   30       CONTINUE\n            DO 40 I = M + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   40       CONTINUE\n   50    CONTINUE\n      ELSE IF( TYPE.EQ.'SY'.OR.TYPE.EQ.'TR' )THEN\n         DO 90 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IF( UNIT )THEN\n                  IEND = J - 1\n               ELSE\n                  IEND = J\n               END IF\n            ELSE\n               IF( UNIT )THEN\n                  IBEG = J + 1\n               ELSE\n                  IBEG = J\n               END IF\n               IEND = N\n            END IF\n            DO 60 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   60       CONTINUE\n            DO 70 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   70       CONTINUE\n            DO 80 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   80       CONTINUE\n   90    CONTINUE\n      END IF\n      RETURN\n*\n*     End of SMAKE.\n*\n      END\n      SUBROUTINE SMMCH( TRANSA, TRANSB, M, N, KK, ALPHA, A, LDA, B, LDB,\n     $                  BETA, C, LDC, CT, G, CC, LDCC, EPS, ERR, FATAL,\n     $                  NOUT, MV )\n*\n*  Checks the results of the computational tests.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      REAL               ZERO, ONE\n      PARAMETER          ( ZERO = 0.0, ONE = 1.0 )\n*     .. Scalar Arguments ..\n      REAL               ALPHA, BETA, EPS, ERR\n      INTEGER            KK, LDA, LDB, LDC, LDCC, M, N, NOUT\n      LOGICAL            FATAL, MV\n      CHARACTER*1        TRANSA, TRANSB\n*     .. Array Arguments ..\n      REAL               A( LDA, * ), B( LDB, * ), C( LDC, * ),\n     $                   CC( LDCC, * ), CT( * ), G( * )\n*     .. Local Scalars ..\n      REAL               ERRI\n      INTEGER            I, J, K\n      LOGICAL            TRANA, TRANB\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, SQRT\n*     .. Executable Statements ..\n      TRANA = TRANSA.EQ.'T'.OR.TRANSA.EQ.'C'\n      TRANB = TRANSB.EQ.'T'.OR.TRANSB.EQ.'C'\n*\n*     Compute expected result, one column at a time, in CT using data\n*     in A, B and C.\n*     Compute gauges in G.\n*\n      DO 120 J = 1, N\n*\n         DO 10 I = 1, M\n            CT( I ) = ZERO\n            G( I ) = ZERO\n   10    CONTINUE\n         IF( .NOT.TRANA.AND..NOT.TRANB )THEN\n            DO 30 K = 1, KK\n               DO 20 I = 1, M\n                  CT( I ) = CT( I ) + A( I, K )*B( K, J )\n                  G( I ) = G( I ) + ABS( A( I, K ) )*ABS( B( K, J ) )\n   20          CONTINUE\n   30       CONTINUE\n         ELSE IF( TRANA.AND..NOT.TRANB )THEN\n            DO 50 K = 1, KK\n               DO 40 I = 1, M\n                  CT( I ) = CT( I ) + A( K, I )*B( K, J )\n                  G( I ) = G( I ) + ABS( A( K, I ) )*ABS( B( K, J ) )\n   40          CONTINUE\n   50       CONTINUE\n         ELSE IF( .NOT.TRANA.AND.TRANB )THEN\n            DO 70 K = 1, KK\n               DO 60 I = 1, M\n                  CT( I ) = CT( I ) + A( I, K )*B( J, K )\n                  G( I ) = G( I ) + ABS( A( I, K ) )*ABS( B( J, K ) )\n   60          CONTINUE\n   70       CONTINUE\n         ELSE IF( TRANA.AND.TRANB )THEN\n            DO 90 K = 1, KK\n               DO 80 I = 1, M\n                  CT( I ) = CT( I ) + A( K, I )*B( J, K )\n                  G( I ) = G( I ) + ABS( A( K, I ) )*ABS( B( J, K ) )\n   80          CONTINUE\n   90       CONTINUE\n         END IF\n         DO 100 I = 1, M\n            CT( I ) = ALPHA*CT( I ) + BETA*C( I, J )\n            G( I ) = ABS( ALPHA )*G( I ) + ABS( BETA )*ABS( C( I, J ) )\n  100    CONTINUE\n*\n*        Compute the error ratio for this result.\n*\n         ERR = ZERO\n         DO 110 I = 1, M\n            ERRI = ABS( CT( I ) - CC( I, J ) )/EPS\n            IF( G( I ).NE.ZERO )\n     $         ERRI = ERRI/G( I )\n            ERR = MAX( ERR, ERRI )\n            IF( ERR*SQRT( EPS ).GE.ONE )\n     $         GO TO 130\n  110    CONTINUE\n*\n  120 CONTINUE\n*\n*     If the loop completes, all results are at least half accurate.\n      GO TO 150\n*\n*     Report fatal error.\n*\n  130 FATAL = .TRUE.\n      WRITE( NOUT, FMT = 9999 )\n      DO 140 I = 1, M\n         IF( MV )THEN\n            WRITE( NOUT, FMT = 9998 )I, CT( I ), CC( I, J )\n         ELSE\n            WRITE( NOUT, FMT = 9998 )I, CC( I, J ), CT( I )\n         END IF\n  140 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9997 )J\n*\n  150 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ******* FATAL ERROR - COMPUTED RESULT IS LESS THAN HAL',\n     $      'F ACCURATE *******', /'           EXPECTED RESULT   COMPU',\n     $      'TED RESULT' )\n 9998 FORMAT( 1X, I7, 2G18.6 )\n 9997 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n*\n*     End of SMMCH.\n*\n      END\n      LOGICAL FUNCTION LSE( RI, RJ, LR )\n*\n*  Tests if two arrays are identical.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LR\n*     .. Array Arguments ..\n      REAL               RI( * ), RJ( * )\n*     .. Local Scalars ..\n      INTEGER            I\n*     .. Executable Statements ..\n      DO 10 I = 1, LR\n         IF( RI( I ).NE.RJ( I ) )\n     $      GO TO 20\n   10 CONTINUE\n      LSE = .TRUE.\n      GO TO 30\n   20 CONTINUE\n      LSE = .FALSE.\n   30 RETURN\n*\n*     End of LSE.\n*\n      END\n      LOGICAL FUNCTION LSERES( TYPE, UPLO, M, N, AA, AS, LDA )\n*\n*  Tests if selected elements in two arrays are equal.\n*\n*  TYPE is 'GE' or 'SY'.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LDA, M, N\n      CHARACTER*1        UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      REAL               AA( LDA, * ), AS( LDA, * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J\n      LOGICAL            UPPER\n*     .. Executable Statements ..\n      UPPER = UPLO.EQ.'U'\n      IF( TYPE.EQ.'GE' )THEN\n         DO 20 J = 1, N\n            DO 10 I = M + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   10       CONTINUE\n   20    CONTINUE\n      ELSE IF( TYPE.EQ.'SY' )THEN\n         DO 50 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 30 I = 1, IBEG - 1\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   30       CONTINUE\n            DO 40 I = IEND + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   40       CONTINUE\n   50    CONTINUE\n      END IF\n*\n      LSERES = .TRUE.\n      GO TO 80\n   70 CONTINUE\n      LSERES = .FALSE.\n   80 RETURN\n*\n*     End of LSERES.\n*\n      END\n      REAL FUNCTION SBEG( RESET )\n*\n*  Generates random numbers uniformly distributed between -0.5 and 0.5.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      LOGICAL            RESET\n*     .. Local Scalars ..\n      INTEGER            I, IC, MI\n*     .. Save statement ..\n      SAVE               I, IC, MI\n*     .. Executable Statements ..\n      IF( RESET )THEN\n*        Initialize local variables.\n         MI = 891\n         I = 7\n         IC = 0\n         RESET = .FALSE.\n      END IF\n*\n*     The sequence of values of I is bounded between 1 and 999.\n*     If initial I = 1,2,3,6,7 or 9, the period will be 50.\n*     If initial I = 4 or 8, the period will be 25.\n*     If initial I = 5, the period will be 10.\n*     IC is used to break up the period by skipping 1 value of I in 6.\n*\n      IC = IC + 1\n   10 I = I*MI\n      I = I - 1000*( I/1000 )\n      IF( IC.GE.5 )THEN\n         IC = 0\n         GO TO 10\n      END IF\n      SBEG = ( I - 500 )/1001.0\n      RETURN\n*\n*     End of SBEG.\n*\n      END\n      REAL FUNCTION SDIFF( X, Y )\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      REAL               X, Y\n*     .. Executable Statements ..\n      SDIFF = X - Y\n      RETURN\n*\n*     End of SDIFF.\n*\n      END\n      SUBROUTINE CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n*  Tests whether XERBLA has detected an error when it should.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Executable Statements ..\n      IF( .NOT.LERR )THEN\n         WRITE( NOUT, FMT = 9999 )INFOT, SRNAMT\n         OK = .FALSE.\n      END IF\n      LERR = .FALSE.\n      RETURN\n*\n 9999 FORMAT( ' ***** ILLEGAL VALUE OF PARAMETER NUMBER ', I2, ' NOT D',\n     $      'ETECTED BY ', A6, ' *****' )\n*\n*     End of CHKXER.\n*\n      END\n      SUBROUTINE XERBLA( SRNAME, INFO )\n*\n*  This is a special version of XERBLA to be used only as part of\n*  the test program for testing error exits from the Level 3 BLAS\n*  routines.\n*\n*  XERBLA  is an error handler for the Level 3 BLAS routines.\n*\n*  It is called by the Level 3 BLAS routines if an input parameter is\n*  invalid.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFO\n      CHARACTER*6        SRNAME\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUT, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Executable Statements ..\n      LERR = .TRUE.\n      IF( INFO.NE.INFOT )THEN\n         IF( INFOT.NE.0 )THEN\n            WRITE( NOUT, FMT = 9999 )INFO, INFOT\n         ELSE\n            WRITE( NOUT, FMT = 9997 )INFO\n         END IF\n         OK = .FALSE.\n      END IF\n      IF( SRNAME.NE.SRNAMT )THEN\n         WRITE( NOUT, FMT = 9998 )SRNAME, SRNAMT\n         OK = .FALSE.\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6, ' INSTEAD',\n     $      ' OF ', I2, ' *******' )\n 9998 FORMAT( ' ******* XERBLA WAS CALLED WITH SRNAME = ', A6, ' INSTE',\n     $      'AD OF ', A6, ' *******' )\n 9997 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6,\n     $      ' *******' )\n*\n*     End of XERBLA\n*\n      END\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/testing/zblat1.f",
    "content": "*> \\brief \\b ZBLAT1\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM ZBLAT1\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*>    Test program for the COMPLEX*16 Level 1 BLAS.\n*>\n*>    Based upon the original BLAS test routine together with:\n*>    F06GAF Example Program Text\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup complex16_blas_testing\n*\n*  =====================================================================\n      PROGRAM ZBLAT1\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER          NOUT\n      PARAMETER        (NOUT=6)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, MODE, N\n      LOGICAL          PASS\n*     .. Local Scalars ..\n      DOUBLE PRECISION SFAC\n      INTEGER          IC\n*     .. External Subroutines ..\n      EXTERNAL         CHECK1, CHECK2, HEADER\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Data statements ..\n      DATA             SFAC/9.765625D-4/\n*     .. Executable Statements ..\n      WRITE (NOUT,99999)\n      DO 20 IC = 1, 10\n         ICASE = IC\n         CALL HEADER\n*\n*        Initialize PASS, INCX, INCY, and MODE for a new case.\n*        The value 9999 for INCX, INCY or MODE will appear in the\n*        detailed  output, if any, for cases that do not involve\n*        these parameters.\n*\n         PASS = .TRUE.\n         INCX = 9999\n         INCY = 9999\n         MODE = 9999\n         IF (ICASE.LE.5) THEN\n            CALL CHECK2(SFAC)\n         ELSE IF (ICASE.GE.6) THEN\n            CALL CHECK1(SFAC)\n         END IF\n*        -- Print\n         IF (PASS) WRITE (NOUT,99998)\n   20 CONTINUE\n      STOP\n*\n99999 FORMAT (' Complex BLAS Test Program Results',/1X)\n99998 FORMAT ('                                    ----- PASS -----')\n      END\n      SUBROUTINE HEADER\n*     .. Parameters ..\n      INTEGER          NOUT\n      PARAMETER        (NOUT=6)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, MODE, N\n      LOGICAL          PASS\n*     .. Local Arrays ..\n      CHARACTER*6      L(10)\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Data statements ..\n      DATA             L(1)/'ZDOTC '/\n      DATA             L(2)/'ZDOTU '/\n      DATA             L(3)/'ZAXPY '/\n      DATA             L(4)/'ZCOPY '/\n      DATA             L(5)/'ZSWAP '/\n      DATA             L(6)/'DZNRM2'/\n      DATA             L(7)/'DZASUM'/\n      DATA             L(8)/'ZSCAL '/\n      DATA             L(9)/'ZDSCAL'/\n      DATA             L(10)/'IZAMAX'/\n*     .. Executable Statements ..\n      WRITE (NOUT,99999) ICASE, L(ICASE)\n      RETURN\n*\n99999 FORMAT (/' Test of subprogram number',I3,12X,A6)\n      END\n      SUBROUTINE CHECK1(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION  SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, MODE, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      COMPLEX*16        CA\n      DOUBLE PRECISION  SA\n      INTEGER           I, J, LEN, NP1\n*     .. Local Arrays ..\n      COMPLEX*16        CTRUE5(8,5,2), CTRUE6(8,5,2), CV(8,5,2), CX(8),\n     +                  MWPCS(5), MWPCT(5)\n      DOUBLE PRECISION  STRUE2(5), STRUE4(5)\n      INTEGER           ITRUE3(5)\n*     .. External Functions ..\n      DOUBLE PRECISION  DZASUM, DZNRM2\n      INTEGER           IZAMAX\n      EXTERNAL          DZASUM, DZNRM2, IZAMAX\n*     .. External Subroutines ..\n      EXTERNAL          ZSCAL, ZDSCAL, CTEST, ITEST1, STEST1\n*     .. Intrinsic Functions ..\n      INTRINSIC         MAX\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Data statements ..\n      DATA              SA, CA/0.3D0, (0.4D0,-0.7D0)/\n      DATA              ((CV(I,J,1),I=1,8),J=1,5)/(0.1D0,0.1D0),\n     +                  (1.0D0,2.0D0), (1.0D0,2.0D0), (1.0D0,2.0D0),\n     +                  (1.0D0,2.0D0), (1.0D0,2.0D0), (1.0D0,2.0D0),\n     +                  (1.0D0,2.0D0), (0.3D0,-0.4D0), (3.0D0,4.0D0),\n     +                  (3.0D0,4.0D0), (3.0D0,4.0D0), (3.0D0,4.0D0),\n     +                  (3.0D0,4.0D0), (3.0D0,4.0D0), (3.0D0,4.0D0),\n     +                  (0.1D0,-0.3D0), (0.5D0,-0.1D0), (5.0D0,6.0D0),\n     +                  (5.0D0,6.0D0), (5.0D0,6.0D0), (5.0D0,6.0D0),\n     +                  (5.0D0,6.0D0), (5.0D0,6.0D0), (0.1D0,0.1D0),\n     +                  (-0.6D0,0.1D0), (0.1D0,-0.3D0), (7.0D0,8.0D0),\n     +                  (7.0D0,8.0D0), (7.0D0,8.0D0), (7.0D0,8.0D0),\n     +                  (7.0D0,8.0D0), (0.3D0,0.1D0), (0.5D0,0.0D0),\n     +                  (0.0D0,0.5D0), (0.0D0,0.2D0), (2.0D0,3.0D0),\n     +                  (2.0D0,3.0D0), (2.0D0,3.0D0), (2.0D0,3.0D0)/\n      DATA              ((CV(I,J,2),I=1,8),J=1,5)/(0.1D0,0.1D0),\n     +                  (4.0D0,5.0D0), (4.0D0,5.0D0), (4.0D0,5.0D0),\n     +                  (4.0D0,5.0D0), (4.0D0,5.0D0), (4.0D0,5.0D0),\n     +                  (4.0D0,5.0D0), (0.3D0,-0.4D0), (6.0D0,7.0D0),\n     +                  (6.0D0,7.0D0), (6.0D0,7.0D0), (6.0D0,7.0D0),\n     +                  (6.0D0,7.0D0), (6.0D0,7.0D0), (6.0D0,7.0D0),\n     +                  (0.1D0,-0.3D0), (8.0D0,9.0D0), (0.5D0,-0.1D0),\n     +                  (2.0D0,5.0D0), (2.0D0,5.0D0), (2.0D0,5.0D0),\n     +                  (2.0D0,5.0D0), (2.0D0,5.0D0), (0.1D0,0.1D0),\n     +                  (3.0D0,6.0D0), (-0.6D0,0.1D0), (4.0D0,7.0D0),\n     +                  (0.1D0,-0.3D0), (7.0D0,2.0D0), (7.0D0,2.0D0),\n     +                  (7.0D0,2.0D0), (0.3D0,0.1D0), (5.0D0,8.0D0),\n     +                  (0.5D0,0.0D0), (6.0D0,9.0D0), (0.0D0,0.5D0),\n     +                  (8.0D0,3.0D0), (0.0D0,0.2D0), (9.0D0,4.0D0)/\n      DATA              STRUE2/0.0D0, 0.5D0, 0.6D0, 0.7D0, 0.8D0/\n      DATA              STRUE4/0.0D0, 0.7D0, 1.0D0, 1.3D0, 1.6D0/\n      DATA              ((CTRUE5(I,J,1),I=1,8),J=1,5)/(0.1D0,0.1D0),\n     +                  (1.0D0,2.0D0), (1.0D0,2.0D0), (1.0D0,2.0D0),\n     +                  (1.0D0,2.0D0), (1.0D0,2.0D0), (1.0D0,2.0D0),\n     +                  (1.0D0,2.0D0), (-0.16D0,-0.37D0), (3.0D0,4.0D0),\n     +                  (3.0D0,4.0D0), (3.0D0,4.0D0), (3.0D0,4.0D0),\n     +                  (3.0D0,4.0D0), (3.0D0,4.0D0), (3.0D0,4.0D0),\n     +                  (-0.17D0,-0.19D0), (0.13D0,-0.39D0),\n     +                  (5.0D0,6.0D0), (5.0D0,6.0D0), (5.0D0,6.0D0),\n     +                  (5.0D0,6.0D0), (5.0D0,6.0D0), (5.0D0,6.0D0),\n     +                  (0.11D0,-0.03D0), (-0.17D0,0.46D0),\n     +                  (-0.17D0,-0.19D0), (7.0D0,8.0D0), (7.0D0,8.0D0),\n     +                  (7.0D0,8.0D0), (7.0D0,8.0D0), (7.0D0,8.0D0),\n     +                  (0.19D0,-0.17D0), (0.20D0,-0.35D0),\n     +                  (0.35D0,0.20D0), (0.14D0,0.08D0),\n     +                  (2.0D0,3.0D0), (2.0D0,3.0D0), (2.0D0,3.0D0),\n     +                  (2.0D0,3.0D0)/\n      DATA              ((CTRUE5(I,J,2),I=1,8),J=1,5)/(0.1D0,0.1D0),\n     +                  (4.0D0,5.0D0), (4.0D0,5.0D0), (4.0D0,5.0D0),\n     +                  (4.0D0,5.0D0), (4.0D0,5.0D0), (4.0D0,5.0D0),\n     +                  (4.0D0,5.0D0), (-0.16D0,-0.37D0), (6.0D0,7.0D0),\n     +                  (6.0D0,7.0D0), (6.0D0,7.0D0), (6.0D0,7.0D0),\n     +                  (6.0D0,7.0D0), (6.0D0,7.0D0), (6.0D0,7.0D0),\n     +                  (-0.17D0,-0.19D0), (8.0D0,9.0D0),\n     +                  (0.13D0,-0.39D0), (2.0D0,5.0D0), (2.0D0,5.0D0),\n     +                  (2.0D0,5.0D0), (2.0D0,5.0D0), (2.0D0,5.0D0),\n     +                  (0.11D0,-0.03D0), (3.0D0,6.0D0),\n     +                  (-0.17D0,0.46D0), (4.0D0,7.0D0),\n     +                  (-0.17D0,-0.19D0), (7.0D0,2.0D0), (7.0D0,2.0D0),\n     +                  (7.0D0,2.0D0), (0.19D0,-0.17D0), (5.0D0,8.0D0),\n     +                  (0.20D0,-0.35D0), (6.0D0,9.0D0),\n     +                  (0.35D0,0.20D0), (8.0D0,3.0D0),\n     +                  (0.14D0,0.08D0), (9.0D0,4.0D0)/\n      DATA              ((CTRUE6(I,J,1),I=1,8),J=1,5)/(0.1D0,0.1D0),\n     +                  (1.0D0,2.0D0), (1.0D0,2.0D0), (1.0D0,2.0D0),\n     +                  (1.0D0,2.0D0), (1.0D0,2.0D0), (1.0D0,2.0D0),\n     +                  (1.0D0,2.0D0), (0.09D0,-0.12D0), (3.0D0,4.0D0),\n     +                  (3.0D0,4.0D0), (3.0D0,4.0D0), (3.0D0,4.0D0),\n     +                  (3.0D0,4.0D0), (3.0D0,4.0D0), (3.0D0,4.0D0),\n     +                  (0.03D0,-0.09D0), (0.15D0,-0.03D0),\n     +                  (5.0D0,6.0D0), (5.0D0,6.0D0), (5.0D0,6.0D0),\n     +                  (5.0D0,6.0D0), (5.0D0,6.0D0), (5.0D0,6.0D0),\n     +                  (0.03D0,0.03D0), (-0.18D0,0.03D0),\n     +                  (0.03D0,-0.09D0), (7.0D0,8.0D0), (7.0D0,8.0D0),\n     +                  (7.0D0,8.0D0), (7.0D0,8.0D0), (7.0D0,8.0D0),\n     +                  (0.09D0,0.03D0), (0.15D0,0.00D0),\n     +                  (0.00D0,0.15D0), (0.00D0,0.06D0), (2.0D0,3.0D0),\n     +                  (2.0D0,3.0D0), (2.0D0,3.0D0), (2.0D0,3.0D0)/\n      DATA              ((CTRUE6(I,J,2),I=1,8),J=1,5)/(0.1D0,0.1D0),\n     +                  (4.0D0,5.0D0), (4.0D0,5.0D0), (4.0D0,5.0D0),\n     +                  (4.0D0,5.0D0), (4.0D0,5.0D0), (4.0D0,5.0D0),\n     +                  (4.0D0,5.0D0), (0.09D0,-0.12D0), (6.0D0,7.0D0),\n     +                  (6.0D0,7.0D0), (6.0D0,7.0D0), (6.0D0,7.0D0),\n     +                  (6.0D0,7.0D0), (6.0D0,7.0D0), (6.0D0,7.0D0),\n     +                  (0.03D0,-0.09D0), (8.0D0,9.0D0),\n     +                  (0.15D0,-0.03D0), (2.0D0,5.0D0), (2.0D0,5.0D0),\n     +                  (2.0D0,5.0D0), (2.0D0,5.0D0), (2.0D0,5.0D0),\n     +                  (0.03D0,0.03D0), (3.0D0,6.0D0),\n     +                  (-0.18D0,0.03D0), (4.0D0,7.0D0),\n     +                  (0.03D0,-0.09D0), (7.0D0,2.0D0), (7.0D0,2.0D0),\n     +                  (7.0D0,2.0D0), (0.09D0,0.03D0), (5.0D0,8.0D0),\n     +                  (0.15D0,0.00D0), (6.0D0,9.0D0), (0.00D0,0.15D0),\n     +                  (8.0D0,3.0D0), (0.00D0,0.06D0), (9.0D0,4.0D0)/\n      DATA              ITRUE3/0, 1, 2, 2, 2/\n*     .. Executable Statements ..\n      DO 60 INCX = 1, 2\n         DO 40 NP1 = 1, 5\n            N = NP1 - 1\n            LEN = 2*MAX(N,1)\n*           .. Set vector arguments ..\n            DO 20 I = 1, LEN\n               CX(I) = CV(I,NP1,INCX)\n   20       CONTINUE\n            IF (ICASE.EQ.6) THEN\n*              .. DZNRM2 ..\n               CALL STEST1(DZNRM2(N,CX,INCX),STRUE2(NP1),STRUE2(NP1),\n     +                     SFAC)\n            ELSE IF (ICASE.EQ.7) THEN\n*              .. DZASUM ..\n               CALL STEST1(DZASUM(N,CX,INCX),STRUE4(NP1),STRUE4(NP1),\n     +                     SFAC)\n            ELSE IF (ICASE.EQ.8) THEN\n*              .. ZSCAL ..\n               CALL ZSCAL(N,CA,CX,INCX)\n               CALL CTEST(LEN,CX,CTRUE5(1,NP1,INCX),CTRUE5(1,NP1,INCX),\n     +                    SFAC)\n            ELSE IF (ICASE.EQ.9) THEN\n*              .. ZDSCAL ..\n               CALL ZDSCAL(N,SA,CX,INCX)\n               CALL CTEST(LEN,CX,CTRUE6(1,NP1,INCX),CTRUE6(1,NP1,INCX),\n     +                    SFAC)\n            ELSE IF (ICASE.EQ.10) THEN\n*              .. IZAMAX ..\n               CALL ITEST1(IZAMAX(N,CX,INCX),ITRUE3(NP1))\n            ELSE\n               WRITE (NOUT,*) ' Shouldn''t be here in CHECK1'\n               STOP\n            END IF\n*\n   40    CONTINUE\n   60 CONTINUE\n*\n      INCX = 1\n      IF (ICASE.EQ.8) THEN\n*        ZSCAL\n*        Add a test for alpha equal to zero.\n         CA = (0.0D0,0.0D0)\n         DO 80 I = 1, 5\n            MWPCT(I) = (0.0D0,0.0D0)\n            MWPCS(I) = (1.0D0,1.0D0)\n   80    CONTINUE\n         CALL ZSCAL(5,CA,CX,INCX)\n         CALL CTEST(5,CX,MWPCT,MWPCS,SFAC)\n      ELSE IF (ICASE.EQ.9) THEN\n*        ZDSCAL\n*        Add a test for alpha equal to zero.\n         SA = 0.0D0\n         DO 100 I = 1, 5\n            MWPCT(I) = (0.0D0,0.0D0)\n            MWPCS(I) = (1.0D0,1.0D0)\n  100    CONTINUE\n         CALL ZDSCAL(5,SA,CX,INCX)\n         CALL CTEST(5,CX,MWPCT,MWPCS,SFAC)\n*        Add a test for alpha equal to one.\n         SA = 1.0D0\n         DO 120 I = 1, 5\n            MWPCT(I) = CX(I)\n            MWPCS(I) = CX(I)\n  120    CONTINUE\n         CALL ZDSCAL(5,SA,CX,INCX)\n         CALL CTEST(5,CX,MWPCT,MWPCS,SFAC)\n*        Add a test for alpha equal to minus one.\n         SA = -1.0D0\n         DO 140 I = 1, 5\n            MWPCT(I) = -CX(I)\n            MWPCS(I) = -CX(I)\n  140    CONTINUE\n         CALL ZDSCAL(5,SA,CX,INCX)\n         CALL CTEST(5,CX,MWPCT,MWPCS,SFAC)\n      END IF\n      RETURN\n      END\n      SUBROUTINE CHECK2(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION  SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, MODE, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      COMPLEX*16        CA\n      INTEGER           I, J, KI, KN, KSIZE, LENX, LENY, MX, MY\n*     .. Local Arrays ..\n      COMPLEX*16        CDOT(1), CSIZE1(4), CSIZE2(7,2), CSIZE3(14),\n     +                  CT10X(7,4,4), CT10Y(7,4,4), CT6(4,4), CT7(4,4),\n     +                  CT8(7,4,4), CX(7), CX1(7), CY(7), CY1(7)\n      INTEGER           INCXS(4), INCYS(4), LENS(4,2), NS(4)\n*     .. External Functions ..\n      COMPLEX*16        ZDOTC, ZDOTU\n      EXTERNAL          ZDOTC, ZDOTU\n*     .. External Subroutines ..\n      EXTERNAL          ZAXPY, ZCOPY, ZSWAP, CTEST\n*     .. Intrinsic Functions ..\n      INTRINSIC         ABS, MIN\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Data statements ..\n      DATA              CA/(0.4D0,-0.7D0)/\n      DATA              INCXS/1, 2, -2, -1/\n      DATA              INCYS/1, -2, 1, -2/\n      DATA              LENS/1, 1, 2, 4, 1, 1, 3, 7/\n      DATA              NS/0, 1, 2, 4/\n      DATA              CX1/(0.7D0,-0.8D0), (-0.4D0,-0.7D0),\n     +                  (-0.1D0,-0.9D0), (0.2D0,-0.8D0),\n     +                  (-0.9D0,-0.4D0), (0.1D0,0.4D0), (-0.6D0,0.6D0)/\n      DATA              CY1/(0.6D0,-0.6D0), (-0.9D0,0.5D0),\n     +                  (0.7D0,-0.6D0), (0.1D0,-0.5D0), (-0.1D0,-0.2D0),\n     +                  (-0.5D0,-0.3D0), (0.8D0,-0.7D0)/\n      DATA              ((CT8(I,J,1),I=1,7),J=1,4)/(0.6D0,-0.6D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.32D0,-1.41D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.32D0,-1.41D0),\n     +                  (-1.55D0,0.5D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.32D0,-1.41D0), (-1.55D0,0.5D0),\n     +                  (0.03D0,-0.89D0), (-0.38D0,-0.96D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0)/\n      DATA              ((CT8(I,J,2),I=1,7),J=1,4)/(0.6D0,-0.6D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.32D0,-1.41D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (-0.07D0,-0.89D0),\n     +                  (-0.9D0,0.5D0), (0.42D0,-1.41D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.78D0,0.06D0), (-0.9D0,0.5D0),\n     +                  (0.06D0,-0.13D0), (0.1D0,-0.5D0),\n     +                  (-0.77D0,-0.49D0), (-0.5D0,-0.3D0),\n     +                  (0.52D0,-1.51D0)/\n      DATA              ((CT8(I,J,3),I=1,7),J=1,4)/(0.6D0,-0.6D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.32D0,-1.41D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (-0.07D0,-0.89D0),\n     +                  (-1.18D0,-0.31D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.78D0,0.06D0), (-1.54D0,0.97D0),\n     +                  (0.03D0,-0.89D0), (-0.18D0,-1.31D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0)/\n      DATA              ((CT8(I,J,4),I=1,7),J=1,4)/(0.6D0,-0.6D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.32D0,-1.41D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.32D0,-1.41D0), (-0.9D0,0.5D0),\n     +                  (0.05D0,-0.6D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.32D0,-1.41D0),\n     +                  (-0.9D0,0.5D0), (0.05D0,-0.6D0), (0.1D0,-0.5D0),\n     +                  (-0.77D0,-0.49D0), (-0.5D0,-0.3D0),\n     +                  (0.32D0,-1.16D0)/\n      DATA              CT7/(0.0D0,0.0D0), (-0.06D0,-0.90D0),\n     +                  (0.65D0,-0.47D0), (-0.34D0,-1.22D0),\n     +                  (0.0D0,0.0D0), (-0.06D0,-0.90D0),\n     +                  (-0.59D0,-1.46D0), (-1.04D0,-0.04D0),\n     +                  (0.0D0,0.0D0), (-0.06D0,-0.90D0),\n     +                  (-0.83D0,0.59D0), (0.07D0,-0.37D0),\n     +                  (0.0D0,0.0D0), (-0.06D0,-0.90D0),\n     +                  (-0.76D0,-1.15D0), (-1.33D0,-1.82D0)/\n      DATA              CT6/(0.0D0,0.0D0), (0.90D0,0.06D0),\n     +                  (0.91D0,-0.77D0), (1.80D0,-0.10D0),\n     +                  (0.0D0,0.0D0), (0.90D0,0.06D0), (1.45D0,0.74D0),\n     +                  (0.20D0,0.90D0), (0.0D0,0.0D0), (0.90D0,0.06D0),\n     +                  (-0.55D0,0.23D0), (0.83D0,-0.39D0),\n     +                  (0.0D0,0.0D0), (0.90D0,0.06D0), (1.04D0,0.79D0),\n     +                  (1.95D0,1.22D0)/\n      DATA              ((CT10X(I,J,1),I=1,7),J=1,4)/(0.7D0,-0.8D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.6D0,-0.6D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.6D0,-0.6D0), (-0.9D0,0.5D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.6D0,-0.6D0),\n     +                  (-0.9D0,0.5D0), (0.7D0,-0.6D0), (0.1D0,-0.5D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0)/\n      DATA              ((CT10X(I,J,2),I=1,7),J=1,4)/(0.7D0,-0.8D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.6D0,-0.6D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.7D0,-0.6D0), (-0.4D0,-0.7D0),\n     +                  (0.6D0,-0.6D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.8D0,-0.7D0),\n     +                  (-0.4D0,-0.7D0), (-0.1D0,-0.2D0),\n     +                  (0.2D0,-0.8D0), (0.7D0,-0.6D0), (0.1D0,0.4D0),\n     +                  (0.6D0,-0.6D0)/\n      DATA              ((CT10X(I,J,3),I=1,7),J=1,4)/(0.7D0,-0.8D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.6D0,-0.6D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (-0.9D0,0.5D0), (-0.4D0,-0.7D0),\n     +                  (0.6D0,-0.6D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.1D0,-0.5D0),\n     +                  (-0.4D0,-0.7D0), (0.7D0,-0.6D0), (0.2D0,-0.8D0),\n     +                  (-0.9D0,0.5D0), (0.1D0,0.4D0), (0.6D0,-0.6D0)/\n      DATA              ((CT10X(I,J,4),I=1,7),J=1,4)/(0.7D0,-0.8D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.6D0,-0.6D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.6D0,-0.6D0), (0.7D0,-0.6D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.6D0,-0.6D0),\n     +                  (0.7D0,-0.6D0), (-0.1D0,-0.2D0), (0.8D0,-0.7D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0)/\n      DATA              ((CT10Y(I,J,1),I=1,7),J=1,4)/(0.6D0,-0.6D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.7D0,-0.8D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.7D0,-0.8D0), (-0.4D0,-0.7D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.7D0,-0.8D0),\n     +                  (-0.4D0,-0.7D0), (-0.1D0,-0.9D0),\n     +                  (0.2D0,-0.8D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0)/\n      DATA              ((CT10Y(I,J,2),I=1,7),J=1,4)/(0.6D0,-0.6D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.7D0,-0.8D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (-0.1D0,-0.9D0), (-0.9D0,0.5D0),\n     +                  (0.7D0,-0.8D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (-0.6D0,0.6D0),\n     +                  (-0.9D0,0.5D0), (-0.9D0,-0.4D0), (0.1D0,-0.5D0),\n     +                  (-0.1D0,-0.9D0), (-0.5D0,-0.3D0),\n     +                  (0.7D0,-0.8D0)/\n      DATA              ((CT10Y(I,J,3),I=1,7),J=1,4)/(0.6D0,-0.6D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.7D0,-0.8D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (-0.1D0,-0.9D0), (0.7D0,-0.8D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (-0.6D0,0.6D0),\n     +                  (-0.9D0,-0.4D0), (-0.1D0,-0.9D0),\n     +                  (0.7D0,-0.8D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0)/\n      DATA              ((CT10Y(I,J,4),I=1,7),J=1,4)/(0.6D0,-0.6D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.7D0,-0.8D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.7D0,-0.8D0), (-0.9D0,0.5D0),\n     +                  (-0.4D0,-0.7D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.7D0,-0.8D0),\n     +                  (-0.9D0,0.5D0), (-0.4D0,-0.7D0), (0.1D0,-0.5D0),\n     +                  (-0.1D0,-0.9D0), (-0.5D0,-0.3D0),\n     +                  (0.2D0,-0.8D0)/\n      DATA              CSIZE1/(0.0D0,0.0D0), (0.9D0,0.9D0),\n     +                  (1.63D0,1.73D0), (2.90D0,2.78D0)/\n      DATA              CSIZE3/(0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (1.17D0,1.17D0),\n     +                  (1.17D0,1.17D0), (1.17D0,1.17D0),\n     +                  (1.17D0,1.17D0), (1.17D0,1.17D0),\n     +                  (1.17D0,1.17D0), (1.17D0,1.17D0)/\n      DATA              CSIZE2/(0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (1.54D0,1.54D0),\n     +                  (1.54D0,1.54D0), (1.54D0,1.54D0),\n     +                  (1.54D0,1.54D0), (1.54D0,1.54D0),\n     +                  (1.54D0,1.54D0), (1.54D0,1.54D0)/\n*     .. Executable Statements ..\n      DO 60 KI = 1, 4\n         INCX = INCXS(KI)\n         INCY = INCYS(KI)\n         MX = ABS(INCX)\n         MY = ABS(INCY)\n*\n         DO 40 KN = 1, 4\n            N = NS(KN)\n            KSIZE = MIN(2,KN)\n            LENX = LENS(KN,MX)\n            LENY = LENS(KN,MY)\n*           .. initialize all argument arrays ..\n            DO 20 I = 1, 7\n               CX(I) = CX1(I)\n               CY(I) = CY1(I)\n   20       CONTINUE\n            IF (ICASE.EQ.1) THEN\n*              .. ZDOTC ..\n               CDOT(1) = ZDOTC(N,CX,INCX,CY,INCY)\n               CALL CTEST(1,CDOT,CT6(KN,KI),CSIZE1(KN),SFAC)\n            ELSE IF (ICASE.EQ.2) THEN\n*              .. ZDOTU ..\n               CDOT(1) = ZDOTU(N,CX,INCX,CY,INCY)\n               CALL CTEST(1,CDOT,CT7(KN,KI),CSIZE1(KN),SFAC)\n            ELSE IF (ICASE.EQ.3) THEN\n*              .. ZAXPY ..\n               CALL ZAXPY(N,CA,CX,INCX,CY,INCY)\n               CALL CTEST(LENY,CY,CT8(1,KN,KI),CSIZE2(1,KSIZE),SFAC)\n            ELSE IF (ICASE.EQ.4) THEN\n*              .. ZCOPY ..\n               CALL ZCOPY(N,CX,INCX,CY,INCY)\n               CALL CTEST(LENY,CY,CT10Y(1,KN,KI),CSIZE3,1.0D0)\n            ELSE IF (ICASE.EQ.5) THEN\n*              .. ZSWAP ..\n               CALL ZSWAP(N,CX,INCX,CY,INCY)\n               CALL CTEST(LENX,CX,CT10X(1,KN,KI),CSIZE3,1.0D0)\n               CALL CTEST(LENY,CY,CT10Y(1,KN,KI),CSIZE3,1.0D0)\n            ELSE\n               WRITE (NOUT,*) ' Shouldn''t be here in CHECK2'\n               STOP\n            END IF\n*\n   40    CONTINUE\n   60 CONTINUE\n      RETURN\n      END\n      SUBROUTINE STEST(LEN,SCOMP,STRUE,SSIZE,SFAC)\n*     ********************************* STEST **************************\n*\n*     THIS SUBR COMPARES ARRAYS  SCOMP() AND STRUE() OF LENGTH LEN TO\n*     SEE IF THE TERM BY TERM DIFFERENCES, MULTIPLIED BY SFAC, ARE\n*     NEGLIGIBLE.\n*\n*     C. L. LAWSON, JPL, 1974 DEC 10\n*\n*     .. Parameters ..\n      INTEGER          NOUT\n      DOUBLE PRECISION ZERO\n      PARAMETER        (NOUT=6, ZERO=0.0D0)\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION SFAC\n      INTEGER          LEN\n*     .. Array Arguments ..\n      DOUBLE PRECISION SCOMP(LEN), SSIZE(LEN), STRUE(LEN)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, MODE, N\n      LOGICAL          PASS\n*     .. Local Scalars ..\n      DOUBLE PRECISION SD\n      INTEGER          I\n*     .. External Functions ..\n      DOUBLE PRECISION SDIFF\n      EXTERNAL         SDIFF\n*     .. Intrinsic Functions ..\n      INTRINSIC        ABS\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Executable Statements ..\n*\n      DO 40 I = 1, LEN\n         SD = SCOMP(I) - STRUE(I)\n         IF (ABS(SFAC*SD) .LE. ABS(SSIZE(I))*EPSILON(ZERO))\n     +       GO TO 40\n*\n*                             HERE    SCOMP(I) IS NOT CLOSE TO STRUE(I).\n*\n         IF ( .NOT. PASS) GO TO 20\n*                             PRINT FAIL MESSAGE AND HEADER.\n         PASS = .FALSE.\n         WRITE (NOUT,99999)\n         WRITE (NOUT,99998)\n   20    WRITE (NOUT,99997) ICASE, N, INCX, INCY, MODE, I, SCOMP(I),\n     +     STRUE(I), SD, SSIZE(I)\n   40 CONTINUE\n      RETURN\n*\n99999 FORMAT ('                                       FAIL')\n99998 FORMAT (/' CASE  N INCX INCY MODE  I                            ',\n     +       ' COMP(I)                             TRUE(I)  DIFFERENCE',\n     +       '     SIZE(I)',/1X)\n99997 FORMAT (1X,I4,I3,3I5,I3,2D36.8,2D12.4)\n      END\n      SUBROUTINE STEST1(SCOMP1,STRUE1,SSIZE,SFAC)\n*     ************************* STEST1 *****************************\n*\n*     THIS IS AN INTERFACE SUBROUTINE TO ACCOMMODATE THE FORTRAN\n*     REQUIREMENT THAT WHEN A DUMMY ARGUMENT IS AN ARRAY, THE\n*     ACTUAL ARGUMENT MUST ALSO BE AN ARRAY OR AN ARRAY ELEMENT.\n*\n*     C.L. LAWSON, JPL, 1978 DEC 6\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION  SCOMP1, SFAC, STRUE1\n*     .. Array Arguments ..\n      DOUBLE PRECISION  SSIZE(*)\n*     .. Local Arrays ..\n      DOUBLE PRECISION  SCOMP(1), STRUE(1)\n*     .. External Subroutines ..\n      EXTERNAL          STEST\n*     .. Executable Statements ..\n*\n      SCOMP(1) = SCOMP1\n      STRUE(1) = STRUE1\n      CALL STEST(1,SCOMP,STRUE,SSIZE,SFAC)\n*\n      RETURN\n      END\n      DOUBLE PRECISION FUNCTION SDIFF(SA,SB)\n*     ********************************* SDIFF **************************\n*     COMPUTES DIFFERENCE OF TWO NUMBERS.  C. L. LAWSON, JPL 1974 FEB 15\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION                SA, SB\n*     .. Executable Statements ..\n      SDIFF = SA - SB\n      RETURN\n      END\n      SUBROUTINE CTEST(LEN,CCOMP,CTRUE,CSIZE,SFAC)\n*     **************************** CTEST *****************************\n*\n*     C.L. LAWSON, JPL, 1978 DEC 6\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION SFAC\n      INTEGER          LEN\n*     .. Array Arguments ..\n      COMPLEX*16       CCOMP(LEN), CSIZE(LEN), CTRUE(LEN)\n*     .. Local Scalars ..\n      INTEGER          I\n*     .. Local Arrays ..\n      DOUBLE PRECISION SCOMP(20), SSIZE(20), STRUE(20)\n*     .. External Subroutines ..\n      EXTERNAL         STEST\n*     .. Intrinsic Functions ..\n      INTRINSIC        DIMAG, DBLE\n*     .. Executable Statements ..\n      DO 20 I = 1, LEN\n         SCOMP(2*I-1) = DBLE(CCOMP(I))\n         SCOMP(2*I) = DIMAG(CCOMP(I))\n         STRUE(2*I-1) = DBLE(CTRUE(I))\n         STRUE(2*I) = DIMAG(CTRUE(I))\n         SSIZE(2*I-1) = DBLE(CSIZE(I))\n         SSIZE(2*I) = DIMAG(CSIZE(I))\n   20 CONTINUE\n*\n      CALL STEST(2*LEN,SCOMP,STRUE,SSIZE,SFAC)\n      RETURN\n      END\n      SUBROUTINE ITEST1(ICOMP,ITRUE)\n*     ********************************* ITEST1 *************************\n*\n*     THIS SUBROUTINE COMPARES THE VARIABLES ICOMP AND ITRUE FOR\n*     EQUALITY.\n*     C. L. LAWSON, JPL, 1974 DEC 10\n*\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      INTEGER           ICOMP, ITRUE\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, MODE, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      INTEGER           ID\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Executable Statements ..\n      IF (ICOMP.EQ.ITRUE) GO TO 40\n*\n*                            HERE ICOMP IS NOT EQUAL TO ITRUE.\n*\n      IF ( .NOT. PASS) GO TO 20\n*                             PRINT FAIL MESSAGE AND HEADER.\n      PASS = .FALSE.\n      WRITE (NOUT,99999)\n      WRITE (NOUT,99998)\n   20 ID = ICOMP - ITRUE\n      WRITE (NOUT,99997) ICASE, N, INCX, INCY, MODE, ICOMP, ITRUE, ID\n   40 CONTINUE\n      RETURN\n*\n99999 FORMAT ('                                       FAIL')\n99998 FORMAT (/' CASE  N INCX INCY MODE                               ',\n     +       ' COMP                                TRUE     DIFFERENCE',\n     +       /1X)\n99997 FORMAT (1X,I4,I3,3I5,2I36,I12)\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/testing/zblat2.f",
    "content": "*> \\brief \\b ZBLAT2\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM ZBLAT2\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> Test program for the COMPLEX*16       Level 2 Blas.\n*>\n*> The program must be driven by a short data file. The first 18 records\n*> of the file are read using list-directed input, the last 17 records\n*> are read using the format ( A6, L2 ). An annotated example of a data\n*> file can be obtained by deleting the first 3 characters from the\n*> following 35 lines:\n*> 'zblat2.out'      NAME OF SUMMARY OUTPUT FILE\n*> 6                 UNIT NUMBER OF SUMMARY FILE\n*> 'CBLA2T.SNAP'     NAME OF SNAPSHOT OUTPUT FILE\n*> -1                UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0)\n*> F        LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD.\n*> F        LOGICAL FLAG, T TO STOP ON FAILURES.\n*> T        LOGICAL FLAG, T TO TEST ERROR EXITS.\n*> 16.0     THRESHOLD VALUE OF TEST RATIO\n*> 6                 NUMBER OF VALUES OF N\n*> 0 1 2 3 5 9       VALUES OF N\n*> 4                 NUMBER OF VALUES OF K\n*> 0 1 2 4           VALUES OF K\n*> 4                 NUMBER OF VALUES OF INCX AND INCY\n*> 1 2 -1 -2         VALUES OF INCX AND INCY\n*> 3                 NUMBER OF VALUES OF ALPHA\n*> (0.0,0.0) (1.0,0.0) (0.7,-0.9)       VALUES OF ALPHA\n*> 3                 NUMBER OF VALUES OF BETA\n*> (0.0,0.0) (1.0,0.0) (1.3,-1.1)       VALUES OF BETA\n*> ZGEMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZGBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZHEMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZHBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZHPMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZTRMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZTBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZTPMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZTRSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZTBSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZTPSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZGERC  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZGERU  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZHER   T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZHPR   T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZHER2  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZHPR2  T PUT F FOR NO TEST. SAME COLUMNS.\n*>\n*> Further Details\n*> ===============\n*>\n*>    See:\n*>\n*>       Dongarra J. J., Du Croz J. J., Hammarling S.  and Hanson R. J..\n*>       An  extended  set of Fortran  Basic Linear Algebra Subprograms.\n*>\n*>       Technical  Memoranda  Nos. 41 (revision 3) and 81,  Mathematics\n*>       and  Computer Science  Division,  Argonne  National Laboratory,\n*>       9700 South Cass Avenue, Argonne, Illinois 60439, US.\n*>\n*>       Or\n*>\n*>       NAG  Technical Reports TR3/87 and TR4/87,  Numerical Algorithms\n*>       Group  Ltd.,  NAG  Central  Office,  256  Banbury  Road, Oxford\n*>       OX2 7DE, UK,  and  Numerical Algorithms Group Inc.,  1101  31st\n*>       Street,  Suite 100,  Downers Grove,  Illinois 60515-1263,  USA.\n*>\n*>\n*> -- Written on 10-August-1987.\n*>    Richard Hanson, Sandia National Labs.\n*>    Jeremy Du Croz, NAG Central Office.\n*>\n*>    10-9-00:  Change STATUS='NEW' to 'UNKNOWN' so that the testers\n*>              can be run multiple times without deleting generated\n*>              output files (susan)\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup complex16_blas_testing\n*\n*  =====================================================================\n      PROGRAM ZBLAT2\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER            NIN\n      PARAMETER          ( NIN = 5 )\n      INTEGER            NSUBS\n      PARAMETER          ( NSUBS = 17 )\n      COMPLEX*16         ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   ONE = ( 1.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n      INTEGER            NMAX, INCMAX\n      PARAMETER          ( NMAX = 65, INCMAX = 2 )\n      INTEGER            NINMAX, NIDMAX, NKBMAX, NALMAX, NBEMAX\n      PARAMETER          ( NINMAX = 7, NIDMAX = 9, NKBMAX = 7,\n     $                   NALMAX = 7, NBEMAX = 7 )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   EPS, ERR, THRESH\n      INTEGER            I, ISNUM, J, N, NALF, NBET, NIDIM, NINC, NKB,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, LTESTT, REWI, SAME, SFATAL, TRACE,\n     $                   TSTERR\n      CHARACTER*1        TRANS\n      CHARACTER*6        SNAMET\n      CHARACTER*32       SNAPS, SUMMRY\n*     .. Local Arrays ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ),\n     $                   ALF( NALMAX ), AS( NMAX*NMAX ), BET( NBEMAX ),\n     $                   X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( 2*NMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDMAX ), INC( NINMAX ), KB( NKBMAX )\n      LOGICAL            LTEST( NSUBS )\n      CHARACTER*6        SNAMES( NSUBS )\n*     .. External Functions ..\n      DOUBLE PRECISION   DDIFF\n      LOGICAL            LZE\n      EXTERNAL           DDIFF, LZE\n*     .. External Subroutines ..\n      EXTERNAL           ZCHK1, ZCHK2, ZCHK3, ZCHK4, ZCHK5, ZCHK6,\n     $                   ZCHKE, ZMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Data statements ..\n      DATA               SNAMES/'ZGEMV ', 'ZGBMV ', 'ZHEMV ', 'ZHBMV ',\n     $                   'ZHPMV ', 'ZTRMV ', 'ZTBMV ', 'ZTPMV ',\n     $                   'ZTRSV ', 'ZTBSV ', 'ZTPSV ', 'ZGERC ',\n     $                   'ZGERU ', 'ZHER  ', 'ZHPR  ', 'ZHER2 ',\n     $                   'ZHPR2 '/\n*     .. Executable Statements ..\n*\n*     Read name and unit number for summary output file and open file.\n*\n      READ( NIN, FMT = * )SUMMRY\n      READ( NIN, FMT = * )NOUT\n      OPEN( NOUT, FILE = SUMMRY, STATUS = 'UNKNOWN' )\n      NOUTC = NOUT\n*\n*     Read name and unit number for snapshot output file and open file.\n*\n      READ( NIN, FMT = * )SNAPS\n      READ( NIN, FMT = * )NTRA\n      TRACE = NTRA.GE.0\n      IF( TRACE )THEN\n         OPEN( NTRA, FILE = SNAPS, STATUS = 'UNKNOWN' )\n      END IF\n*     Read the flag that directs rewinding of the snapshot file.\n      READ( NIN, FMT = * )REWI\n      REWI = REWI.AND.TRACE\n*     Read the flag that directs stopping on any failure.\n      READ( NIN, FMT = * )SFATAL\n*     Read the flag that indicates whether error exits are to be tested.\n      READ( NIN, FMT = * )TSTERR\n*     Read the threshold value of the test ratio\n      READ( NIN, FMT = * )THRESH\n*\n*     Read and check the parameter values for the tests.\n*\n*     Values of N\n      READ( NIN, FMT = * )NIDIM\n      IF( NIDIM.LT.1.OR.NIDIM.GT.NIDMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'N', NIDMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( IDIM( I ), I = 1, NIDIM )\n      DO 10 I = 1, NIDIM\n         IF( IDIM( I ).LT.0.OR.IDIM( I ).GT.NMAX )THEN\n            WRITE( NOUT, FMT = 9996 )NMAX\n            GO TO 230\n         END IF\n   10 CONTINUE\n*     Values of K\n      READ( NIN, FMT = * )NKB\n      IF( NKB.LT.1.OR.NKB.GT.NKBMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'K', NKBMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( KB( I ), I = 1, NKB )\n      DO 20 I = 1, NKB\n         IF( KB( I ).LT.0 )THEN\n            WRITE( NOUT, FMT = 9995 )\n            GO TO 230\n         END IF\n   20 CONTINUE\n*     Values of INCX and INCY\n      READ( NIN, FMT = * )NINC\n      IF( NINC.LT.1.OR.NINC.GT.NINMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'INCX AND INCY', NINMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( INC( I ), I = 1, NINC )\n      DO 30 I = 1, NINC\n         IF( INC( I ).EQ.0.OR.ABS( INC( I ) ).GT.INCMAX )THEN\n            WRITE( NOUT, FMT = 9994 )INCMAX\n            GO TO 230\n         END IF\n   30 CONTINUE\n*     Values of ALPHA\n      READ( NIN, FMT = * )NALF\n      IF( NALF.LT.1.OR.NALF.GT.NALMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'ALPHA', NALMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( ALF( I ), I = 1, NALF )\n*     Values of BETA\n      READ( NIN, FMT = * )NBET\n      IF( NBET.LT.1.OR.NBET.GT.NBEMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'BETA', NBEMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( BET( I ), I = 1, NBET )\n*\n*     Report values of parameters.\n*\n      WRITE( NOUT, FMT = 9993 )\n      WRITE( NOUT, FMT = 9992 )( IDIM( I ), I = 1, NIDIM )\n      WRITE( NOUT, FMT = 9991 )( KB( I ), I = 1, NKB )\n      WRITE( NOUT, FMT = 9990 )( INC( I ), I = 1, NINC )\n      WRITE( NOUT, FMT = 9989 )( ALF( I ), I = 1, NALF )\n      WRITE( NOUT, FMT = 9988 )( BET( I ), I = 1, NBET )\n      IF( .NOT.TSTERR )THEN\n         WRITE( NOUT, FMT = * )\n         WRITE( NOUT, FMT = 9980 )\n      END IF\n      WRITE( NOUT, FMT = * )\n      WRITE( NOUT, FMT = 9999 )THRESH\n      WRITE( NOUT, FMT = * )\n*\n*     Read names of subroutines and flags which indicate\n*     whether they are to be tested.\n*\n      DO 40 I = 1, NSUBS\n         LTEST( I ) = .FALSE.\n   40 CONTINUE\n   50 READ( NIN, FMT = 9984, END = 80 )SNAMET, LTESTT\n      DO 60 I = 1, NSUBS\n         IF( SNAMET.EQ.SNAMES( I ) )\n     $      GO TO 70\n   60 CONTINUE\n      WRITE( NOUT, FMT = 9986 )SNAMET\n      STOP\n   70 LTEST( I ) = LTESTT\n      GO TO 50\n*\n   80 CONTINUE\n      CLOSE ( NIN )\n*\n*     Compute EPS (the machine precision).\n*\n      EPS = EPSILON(RZERO)\n      WRITE( NOUT, FMT = 9998 )EPS\n*\n*     Check the reliability of ZMVCH using exact data.\n*\n      N = MIN( 32, NMAX )\n      DO 120 J = 1, N\n         DO 110 I = 1, N\n            A( I, J ) = MAX( I - J + 1, 0 )\n  110    CONTINUE\n         X( J ) = J\n         Y( J ) = ZERO\n  120 CONTINUE\n      DO 130 J = 1, N\n         YY( J ) = J*( ( J + 1 )*J )/2 - ( ( J + 1 )*J*( J - 1 ) )/3\n  130 CONTINUE\n*     YY holds the exact result. On exit from ZMVCH YT holds\n*     the result computed by ZMVCH.\n      TRANS = 'N'\n      CALL ZMVCH( TRANS, N, N, ONE, A, NMAX, X, 1, ZERO, Y, 1, YT, G,\n     $            YY, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LZE( YY, YT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9985 )TRANS, SAME, ERR\n         STOP\n      END IF\n      TRANS = 'T'\n      CALL ZMVCH( TRANS, N, N, ONE, A, NMAX, X, -1, ZERO, Y, -1, YT, G,\n     $            YY, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LZE( YY, YT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9985 )TRANS, SAME, ERR\n         STOP\n      END IF\n*\n*     Test each subroutine in turn.\n*\n      DO 210 ISNUM = 1, NSUBS\n         WRITE( NOUT, FMT = * )\n         IF( .NOT.LTEST( ISNUM ) )THEN\n*           Subprogram is not to be tested.\n            WRITE( NOUT, FMT = 9983 )SNAMES( ISNUM )\n         ELSE\n            SRNAMT = SNAMES( ISNUM )\n*           Test error exits.\n            IF( TSTERR )THEN\n               CALL ZCHKE( ISNUM, SNAMES( ISNUM ), NOUT )\n               WRITE( NOUT, FMT = * )\n            END IF\n*           Test computations.\n            INFOT = 0\n            OK = .TRUE.\n            FATAL = .FALSE.\n            GO TO ( 140, 140, 150, 150, 150, 160, 160,\n     $              160, 160, 160, 160, 170, 170, 180,\n     $              180, 190, 190 )ISNUM\n*           Test ZGEMV, 01, and ZGBMV, 02.\n  140       CALL ZCHK1( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF,\n     $                  NBET, BET, NINC, INC, NMAX, INCMAX, A, AA, AS,\n     $                  X, XX, XS, Y, YY, YS, YT, G )\n            GO TO 200\n*           Test ZHEMV, 03, ZHBMV, 04, and ZHPMV, 05.\n  150       CALL ZCHK2( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF,\n     $                  NBET, BET, NINC, INC, NMAX, INCMAX, A, AA, AS,\n     $                  X, XX, XS, Y, YY, YS, YT, G )\n            GO TO 200\n*           Test ZTRMV, 06, ZTBMV, 07, ZTPMV, 08,\n*           ZTRSV, 09, ZTBSV, 10, and ZTPSV, 11.\n  160       CALL ZCHK3( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, Y, YY, YS, YT, G, Z )\n            GO TO 200\n*           Test ZGERC, 12, ZGERU, 13.\n  170       CALL ZCHK4( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n            GO TO 200\n*           Test ZHER, 14, and ZHPR, 15.\n  180       CALL ZCHK5( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n            GO TO 200\n*           Test ZHER2, 16, and ZHPR2, 17.\n  190       CALL ZCHK6( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n*\n  200       IF( FATAL.AND.SFATAL )\n     $         GO TO 220\n         END IF\n  210 CONTINUE\n      WRITE( NOUT, FMT = 9982 )\n      GO TO 240\n*\n  220 CONTINUE\n      WRITE( NOUT, FMT = 9981 )\n      GO TO 240\n*\n  230 CONTINUE\n      WRITE( NOUT, FMT = 9987 )\n*\n  240 CONTINUE\n      IF( TRACE )\n     $   CLOSE ( NTRA )\n      CLOSE ( NOUT )\n      STOP\n*\n 9999 FORMAT( ' ROUTINES PASS COMPUTATIONAL TESTS IF TEST RATIO IS LES',\n     $      'S THAN', F8.2 )\n 9998 FORMAT( ' RELATIVE MACHINE PRECISION IS TAKEN TO BE', 1P, D9.1 )\n 9997 FORMAT( ' NUMBER OF VALUES OF ', A, ' IS LESS THAN 1 OR GREATER ',\n     $      'THAN ', I2 )\n 9996 FORMAT( ' VALUE OF N IS LESS THAN 0 OR GREATER THAN ', I2 )\n 9995 FORMAT( ' VALUE OF K IS LESS THAN 0' )\n 9994 FORMAT( ' ABSOLUTE VALUE OF INCX OR INCY IS 0 OR GREATER THAN ',\n     $      I2 )\n 9993 FORMAT( ' TESTS OF THE COMPLEX*16       LEVEL 2 BLAS', //' THE F',\n     $      'OLLOWING PARAMETER VALUES WILL BE USED:' )\n 9992 FORMAT( '   FOR N              ', 9I6 )\n 9991 FORMAT( '   FOR K              ', 7I6 )\n 9990 FORMAT( '   FOR INCX AND INCY  ', 7I6 )\n 9989 FORMAT( '   FOR ALPHA          ',\n     $      7( '(', F4.1, ',', F4.1, ')  ', : ) )\n 9988 FORMAT( '   FOR BETA           ',\n     $      7( '(', F4.1, ',', F4.1, ')  ', : ) )\n 9987 FORMAT( ' AMEND DATA FILE OR INCREASE ARRAY SIZES IN PROGRAM',\n     $      /' ******* TESTS ABANDONED *******' )\n 9986 FORMAT( ' SUBPROGRAM NAME ', A6, ' NOT RECOGNIZED', /' ******* T',\n     $      'ESTS ABANDONED *******' )\n 9985 FORMAT( ' ERROR IN ZMVCH -  IN-LINE DOT PRODUCTS ARE BEING EVALU',\n     $      'ATED WRONGLY.', /' ZMVCH WAS CALLED WITH TRANS = ', A1,\n     $      ' AND RETURNED SAME = ', L1, ' AND ERR = ', F12.3, '.', /\n     $   ' THIS MAY BE DUE TO FAULTS IN THE ARITHMETIC OR THE COMPILER.'\n     $      , /' ******* TESTS ABANDONED *******' )\n 9984 FORMAT( A6, L2 )\n 9983 FORMAT( 1X, A6, ' WAS NOT TESTED' )\n 9982 FORMAT( /' END OF TESTS' )\n 9981 FORMAT( /' ******* FATAL ERROR - TESTS ABANDONED *******' )\n 9980 FORMAT( ' ERROR-EXITS WILL NOT BE TESTED' )\n*\n*     End of ZBLAT2.\n*\n      END\n      SUBROUTINE ZCHK1( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF, NBET,\n     $                  BET, NINC, INC, NMAX, INCMAX, A, AA, AS, X, XX,\n     $                  XS, Y, YY, YS, YT, G )\n*\n*  Tests ZGEMV and ZGBMV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO, HALF\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   HALF = ( 0.5D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NALF, NBET, NIDIM, NINC, NKB, NMAX,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), BET( NBET ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XX( NMAX*INCMAX ),\n     $                   Y( NMAX ), YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, ALS, BETA, BLS, TRANSL\n      DOUBLE PRECISION   ERR, ERRMAX\n      INTEGER            I, IA, IB, IC, IKU, IM, IN, INCX, INCXS, INCY,\n     $                   INCYS, IX, IY, KL, KLS, KU, KUS, LAA, LDA,\n     $                   LDAS, LX, LY, M, ML, MS, N, NARGS, NC, ND, NK,\n     $                   NL, NS\n      LOGICAL            BANDED, FULL, NULL, RESET, SAME, TRAN\n      CHARACTER*1        TRANS, TRANSS\n      CHARACTER*3        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZGBMV, ZGEMV, ZMAKE, ZMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'NTC'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'E'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 11\n      ELSE IF( BANDED )THEN\n         NARGS = 13\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 120 IN = 1, NIDIM\n         N = IDIM( IN )\n         ND = N/2 + 1\n*\n         DO 110 IM = 1, 2\n            IF( IM.EQ.1 )\n     $         M = MAX( N - ND, 0 )\n            IF( IM.EQ.2 )\n     $         M = MIN( N + ND, NMAX )\n*\n            IF( BANDED )THEN\n               NK = NKB\n            ELSE\n               NK = 1\n            END IF\n            DO 100 IKU = 1, NK\n               IF( BANDED )THEN\n                  KU = KB( IKU )\n                  KL = MAX( KU - 1, 0 )\n               ELSE\n                  KU = N - 1\n                  KL = M - 1\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               IF( BANDED )THEN\n                  LDA = KL + KU + 1\n               ELSE\n                  LDA = M\n               END IF\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 100\n               LAA = LDA*N\n               NULL = N.LE.0.OR.M.LE.0\n*\n*              Generate the matrix A.\n*\n               TRANSL = ZERO\n               CALL ZMAKE( SNAME( 2: 3 ), ' ', ' ', M, N, A, NMAX, AA,\n     $                     LDA, KL, KU, RESET, TRANSL )\n*\n               DO 90 IC = 1, 3\n                  TRANS = ICH( IC: IC )\n                  TRAN = TRANS.EQ.'T'.OR.TRANS.EQ.'C'\n*\n                  IF( TRAN )THEN\n                     ML = N\n                     NL = M\n                  ELSE\n                     ML = M\n                     NL = N\n                  END IF\n*\n                  DO 80 IX = 1, NINC\n                     INCX = INC( IX )\n                     LX = ABS( INCX )*NL\n*\n*                    Generate the vector X.\n*\n                     TRANSL = HALF\n                     CALL ZMAKE( 'GE', ' ', ' ', 1, NL, X, 1, XX,\n     $                           ABS( INCX ), 0, NL - 1, RESET, TRANSL )\n                     IF( NL.GT.1 )THEN\n                        X( NL/2 ) = ZERO\n                        XX( 1 + ABS( INCX )*( NL/2 - 1 ) ) = ZERO\n                     END IF\n*\n                     DO 70 IY = 1, NINC\n                        INCY = INC( IY )\n                        LY = ABS( INCY )*ML\n*\n                        DO 60 IA = 1, NALF\n                           ALPHA = ALF( IA )\n*\n                           DO 50 IB = 1, NBET\n                              BETA = BET( IB )\n*\n*                             Generate the vector Y.\n*\n                              TRANSL = ZERO\n                              CALL ZMAKE( 'GE', ' ', ' ', 1, ML, Y, 1,\n     $                                    YY, ABS( INCY ), 0, ML - 1,\n     $                                    RESET, TRANSL )\n*\n                              NC = NC + 1\n*\n*                             Save every datum before calling the\n*                             subroutine.\n*\n                              TRANSS = TRANS\n                              MS = M\n                              NS = N\n                              KLS = KL\n                              KUS = KU\n                              ALS = ALPHA\n                              DO 10 I = 1, LAA\n                                 AS( I ) = AA( I )\n   10                         CONTINUE\n                              LDAS = LDA\n                              DO 20 I = 1, LX\n                                 XS( I ) = XX( I )\n   20                         CONTINUE\n                              INCXS = INCX\n                              BLS = BETA\n                              DO 30 I = 1, LY\n                                 YS( I ) = YY( I )\n   30                         CONTINUE\n                              INCYS = INCY\n*\n*                             Call the subroutine.\n*\n                              IF( FULL )THEN\n                                 IF( TRACE )\n     $                              WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                              TRANS, M, N, ALPHA, LDA, INCX, BETA,\n     $                              INCY\n                                 IF( REWI )\n     $                              REWIND NTRA\n                                 CALL ZGEMV( TRANS, M, N, ALPHA, AA,\n     $                                       LDA, XX, INCX, BETA, YY,\n     $                                       INCY )\n                              ELSE IF( BANDED )THEN\n                                 IF( TRACE )\n     $                              WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                              TRANS, M, N, KL, KU, ALPHA, LDA,\n     $                              INCX, BETA, INCY\n                                 IF( REWI )\n     $                              REWIND NTRA\n                                 CALL ZGBMV( TRANS, M, N, KL, KU, ALPHA,\n     $                                       AA, LDA, XX, INCX, BETA,\n     $                                       YY, INCY )\n                              END IF\n*\n*                             Check if error-exit was taken incorrectly.\n*\n                              IF( .NOT.OK )THEN\n                                 WRITE( NOUT, FMT = 9993 )\n                                 FATAL = .TRUE.\n                                 GO TO 130\n                              END IF\n*\n*                             See what data changed inside subroutines.\n*\n                              ISAME( 1 ) = TRANS.EQ.TRANSS\n                              ISAME( 2 ) = MS.EQ.M\n                              ISAME( 3 ) = NS.EQ.N\n                              IF( FULL )THEN\n                                 ISAME( 4 ) = ALS.EQ.ALPHA\n                                 ISAME( 5 ) = LZE( AS, AA, LAA )\n                                 ISAME( 6 ) = LDAS.EQ.LDA\n                                 ISAME( 7 ) = LZE( XS, XX, LX )\n                                 ISAME( 8 ) = INCXS.EQ.INCX\n                                 ISAME( 9 ) = BLS.EQ.BETA\n                                 IF( NULL )THEN\n                                    ISAME( 10 ) = LZE( YS, YY, LY )\n                                 ELSE\n                                    ISAME( 10 ) = LZERES( 'GE', ' ', 1,\n     $                                            ML, YS, YY,\n     $                                            ABS( INCY ) )\n                                 END IF\n                                 ISAME( 11 ) = INCYS.EQ.INCY\n                              ELSE IF( BANDED )THEN\n                                 ISAME( 4 ) = KLS.EQ.KL\n                                 ISAME( 5 ) = KUS.EQ.KU\n                                 ISAME( 6 ) = ALS.EQ.ALPHA\n                                 ISAME( 7 ) = LZE( AS, AA, LAA )\n                                 ISAME( 8 ) = LDAS.EQ.LDA\n                                 ISAME( 9 ) = LZE( XS, XX, LX )\n                                 ISAME( 10 ) = INCXS.EQ.INCX\n                                 ISAME( 11 ) = BLS.EQ.BETA\n                                 IF( NULL )THEN\n                                    ISAME( 12 ) = LZE( YS, YY, LY )\n                                 ELSE\n                                    ISAME( 12 ) = LZERES( 'GE', ' ', 1,\n     $                                            ML, YS, YY,\n     $                                            ABS( INCY ) )\n                                 END IF\n                                 ISAME( 13 ) = INCYS.EQ.INCY\n                              END IF\n*\n*                             If data was incorrectly changed, report\n*                             and return.\n*\n                              SAME = .TRUE.\n                              DO 40 I = 1, NARGS\n                                 SAME = SAME.AND.ISAME( I )\n                                 IF( .NOT.ISAME( I ) )\n     $                              WRITE( NOUT, FMT = 9998 )I\n   40                         CONTINUE\n                              IF( .NOT.SAME )THEN\n                                 FATAL = .TRUE.\n                                 GO TO 130\n                              END IF\n*\n                              IF( .NOT.NULL )THEN\n*\n*                                Check the result.\n*\n                                 CALL ZMVCH( TRANS, M, N, ALPHA, A,\n     $                                       NMAX, X, INCX, BETA, Y,\n     $                                       INCY, YT, G, YY, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                                 ERRMAX = MAX( ERRMAX, ERR )\n*                                If got really bad answer, report and\n*                                return.\n                                 IF( FATAL )\n     $                              GO TO 130\n                              ELSE\n*                                Avoid repeating tests with M.le.0 or\n*                                N.le.0.\n                                 GO TO 110\n                              END IF\n*\n   50                      CONTINUE\n*\n   60                   CONTINUE\n*\n   70                CONTINUE\n*\n   80             CONTINUE\n*\n   90          CONTINUE\n*\n  100       CONTINUE\n*\n  110    CONTINUE\n*\n  120 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 140\n*\n  130 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, TRANS, M, N, ALPHA, LDA,\n     $      INCX, BETA, INCY\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, TRANS, M, N, KL, KU,\n     $      ALPHA, LDA, INCX, BETA, INCY\n      END IF\n*\n  140 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 4( I3, ',' ), '(',\n     $      F4.1, ',', F4.1, '), A,', I3, ', X,', I2, ',(', F4.1, ',',\n     $      F4.1, '), Y,', I2, ') .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 2( I3, ',' ), '(',\n     $      F4.1, ',', F4.1, '), A,', I3, ', X,', I2, ',(', F4.1, ',',\n     $      F4.1, '), Y,', I2, ')         .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK1.\n*\n      END\n      SUBROUTINE ZCHK2( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF, NBET,\n     $                  BET, NINC, INC, NMAX, INCMAX, A, AA, AS, X, XX,\n     $                  XS, Y, YY, YS, YT, G )\n*\n*  Tests ZHEMV, ZHBMV and ZHPMV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO, HALF\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   HALF = ( 0.5D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NALF, NBET, NIDIM, NINC, NKB, NMAX,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), BET( NBET ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XX( NMAX*INCMAX ),\n     $                   Y( NMAX ), YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, ALS, BETA, BLS, TRANSL\n      DOUBLE PRECISION   ERR, ERRMAX\n      INTEGER            I, IA, IB, IC, IK, IN, INCX, INCXS, INCY,\n     $                   INCYS, IX, IY, K, KS, LAA, LDA, LDAS, LX, LY,\n     $                   N, NARGS, NC, NK, NS\n      LOGICAL            BANDED, FULL, NULL, PACKED, RESET, SAME\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZHBMV, ZHEMV, ZHPMV, ZMAKE, ZMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'E'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 10\n      ELSE IF( BANDED )THEN\n         NARGS = 11\n      ELSE IF( PACKED )THEN\n         NARGS = 9\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 110 IN = 1, NIDIM\n         N = IDIM( IN )\n*\n         IF( BANDED )THEN\n            NK = NKB\n         ELSE\n            NK = 1\n         END IF\n         DO 100 IK = 1, NK\n            IF( BANDED )THEN\n               K = KB( IK )\n            ELSE\n               K = N - 1\n            END IF\n*           Set LDA to 1 more than minimum value if room.\n            IF( BANDED )THEN\n               LDA = K + 1\n            ELSE\n               LDA = N\n            END IF\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 100\n            IF( PACKED )THEN\n               LAA = ( N*( N + 1 ) )/2\n            ELSE\n               LAA = LDA*N\n            END IF\n            NULL = N.LE.0\n*\n            DO 90 IC = 1, 2\n               UPLO = ICH( IC: IC )\n*\n*              Generate the matrix A.\n*\n               TRANSL = ZERO\n               CALL ZMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A, NMAX, AA,\n     $                     LDA, K, K, RESET, TRANSL )\n*\n               DO 80 IX = 1, NINC\n                  INCX = INC( IX )\n                  LX = ABS( INCX )*N\n*\n*                 Generate the vector X.\n*\n                  TRANSL = HALF\n                  CALL ZMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX,\n     $                        ABS( INCX ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     X( N/2 ) = ZERO\n                     XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 70 IY = 1, NINC\n                     INCY = INC( IY )\n                     LY = ABS( INCY )*N\n*\n                     DO 60 IA = 1, NALF\n                        ALPHA = ALF( IA )\n*\n                        DO 50 IB = 1, NBET\n                           BETA = BET( IB )\n*\n*                          Generate the vector Y.\n*\n                           TRANSL = ZERO\n                           CALL ZMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                                 ABS( INCY ), 0, N - 1, RESET,\n     $                                 TRANSL )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           UPLOS = UPLO\n                           NS = N\n                           KS = K\n                           ALS = ALPHA\n                           DO 10 I = 1, LAA\n                              AS( I ) = AA( I )\n   10                      CONTINUE\n                           LDAS = LDA\n                           DO 20 I = 1, LX\n                              XS( I ) = XX( I )\n   20                      CONTINUE\n                           INCXS = INCX\n                           BLS = BETA\n                           DO 30 I = 1, LY\n                              YS( I ) = YY( I )\n   30                      CONTINUE\n                           INCYS = INCY\n*\n*                          Call the subroutine.\n*\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, N, ALPHA, LDA, INCX, BETA, INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZHEMV( UPLO, N, ALPHA, AA, LDA, XX,\n     $                                    INCX, BETA, YY, INCY )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, N, K, ALPHA, LDA, INCX, BETA,\n     $                           INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZHBMV( UPLO, N, K, ALPHA, AA, LDA,\n     $                                    XX, INCX, BETA, YY, INCY )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, N, ALPHA, INCX, BETA, INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZHPMV( UPLO, N, ALPHA, AA, XX, INCX,\n     $                                    BETA, YY, INCY )\n                           END IF\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9992 )\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = UPLO.EQ.UPLOS\n                           ISAME( 2 ) = NS.EQ.N\n                           IF( FULL )THEN\n                              ISAME( 3 ) = ALS.EQ.ALPHA\n                              ISAME( 4 ) = LZE( AS, AA, LAA )\n                              ISAME( 5 ) = LDAS.EQ.LDA\n                              ISAME( 6 ) = LZE( XS, XX, LX )\n                              ISAME( 7 ) = INCXS.EQ.INCX\n                              ISAME( 8 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 9 ) = LZE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 9 ) = LZERES( 'GE', ' ', 1, N,\n     $                                        YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 10 ) = INCYS.EQ.INCY\n                           ELSE IF( BANDED )THEN\n                              ISAME( 3 ) = KS.EQ.K\n                              ISAME( 4 ) = ALS.EQ.ALPHA\n                              ISAME( 5 ) = LZE( AS, AA, LAA )\n                              ISAME( 6 ) = LDAS.EQ.LDA\n                              ISAME( 7 ) = LZE( XS, XX, LX )\n                              ISAME( 8 ) = INCXS.EQ.INCX\n                              ISAME( 9 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 10 ) = LZE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 10 ) = LZERES( 'GE', ' ', 1, N,\n     $                                         YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 11 ) = INCYS.EQ.INCY\n                           ELSE IF( PACKED )THEN\n                              ISAME( 3 ) = ALS.EQ.ALPHA\n                              ISAME( 4 ) = LZE( AS, AA, LAA )\n                              ISAME( 5 ) = LZE( XS, XX, LX )\n                              ISAME( 6 ) = INCXS.EQ.INCX\n                              ISAME( 7 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 8 ) = LZE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 8 ) = LZERES( 'GE', ' ', 1, N,\n     $                                        YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 9 ) = INCYS.EQ.INCY\n                           END IF\n*\n*                          If data was incorrectly changed, report and\n*                          return.\n*\n                           SAME = .TRUE.\n                           DO 40 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   40                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n*\n*                             Check the result.\n*\n                              CALL ZMVCH( 'N', N, N, ALPHA, A, NMAX, X,\n     $                                    INCX, BETA, Y, INCY, YT, G,\n     $                                    YY, EPS, ERR, FATAL, NOUT,\n     $                                    .TRUE. )\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 120\n                           ELSE\n*                             Avoid repeating tests with N.le.0\n                              GO TO 110\n                           END IF\n*\n   50                   CONTINUE\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, ALPHA, LDA, INCX,\n     $      BETA, INCY\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, K, ALPHA, LDA,\n     $      INCX, BETA, INCY\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, UPLO, N, ALPHA, INCX,\n     $      BETA, INCY\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',(', F4.1, ',',\n     $      F4.1, '), AP, X,', I2, ',(', F4.1, ',', F4.1, '), Y,', I2,\n     $      ')                .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 2( I3, ',' ), '(',\n     $      F4.1, ',', F4.1, '), A,', I3, ', X,', I2, ',(', F4.1, ',',\n     $      F4.1, '), Y,', I2, ')         .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',(', F4.1, ',',\n     $      F4.1, '), A,', I3, ', X,', I2, ',(', F4.1, ',', F4.1, '), ',\n     $      'Y,', I2, ')             .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK2.\n*\n      END\n      SUBROUTINE ZCHK3( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, XT, G, Z )\n*\n*  Tests ZTRMV, ZTBMV, ZTPMV, ZTRSV, ZTBSV and ZTPSV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO, HALF, ONE\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   HALF = ( 0.5D0, 0.0D0 ),\n     $                   ONE = ( 1.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NIDIM, NINC, NKB, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ),\n     $                   AS( NMAX*NMAX ), X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XT( NMAX ), XX( NMAX*INCMAX ), Z( NMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      COMPLEX*16         TRANSL\n      DOUBLE PRECISION   ERR, ERRMAX\n      INTEGER            I, ICD, ICT, ICU, IK, IN, INCX, INCXS, IX, K,\n     $                   KS, LAA, LDA, LDAS, LX, N, NARGS, NC, NK, NS\n      LOGICAL            BANDED, FULL, NULL, PACKED, RESET, SAME\n      CHARACTER*1        DIAG, DIAGS, TRANS, TRANSS, UPLO, UPLOS\n      CHARACTER*2        ICHD, ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZMAKE, ZMVCH, ZTBMV, ZTBSV, ZTPMV, ZTPSV,\n     $                   ZTRMV, ZTRSV\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHU/'UL'/, ICHT/'NTC'/, ICHD/'UN'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'R'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 8\n      ELSE IF( BANDED )THEN\n         NARGS = 9\n      ELSE IF( PACKED )THEN\n         NARGS = 7\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*     Set up zero vector for ZMVCH.\n      DO 10 I = 1, NMAX\n         Z( I ) = ZERO\n   10 CONTINUE\n*\n      DO 110 IN = 1, NIDIM\n         N = IDIM( IN )\n*\n         IF( BANDED )THEN\n            NK = NKB\n         ELSE\n            NK = 1\n         END IF\n         DO 100 IK = 1, NK\n            IF( BANDED )THEN\n               K = KB( IK )\n            ELSE\n               K = N - 1\n            END IF\n*           Set LDA to 1 more than minimum value if room.\n            IF( BANDED )THEN\n               LDA = K + 1\n            ELSE\n               LDA = N\n            END IF\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 100\n            IF( PACKED )THEN\n               LAA = ( N*( N + 1 ) )/2\n            ELSE\n               LAA = LDA*N\n            END IF\n            NULL = N.LE.0\n*\n            DO 90 ICU = 1, 2\n               UPLO = ICHU( ICU: ICU )\n*\n               DO 80 ICT = 1, 3\n                  TRANS = ICHT( ICT: ICT )\n*\n                  DO 70 ICD = 1, 2\n                     DIAG = ICHD( ICD: ICD )\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL ZMAKE( SNAME( 2: 3 ), UPLO, DIAG, N, N, A,\n     $                           NMAX, AA, LDA, K, K, RESET, TRANSL )\n*\n                     DO 60 IX = 1, NINC\n                        INCX = INC( IX )\n                        LX = ABS( INCX )*N\n*\n*                       Generate the vector X.\n*\n                        TRANSL = HALF\n                        CALL ZMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX,\n     $                              ABS( INCX ), 0, N - 1, RESET,\n     $                              TRANSL )\n                        IF( N.GT.1 )THEN\n                           X( N/2 ) = ZERO\n                           XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n                        END IF\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        DIAGS = DIAG\n                        NS = N\n                        KS = K\n                        DO 20 I = 1, LAA\n                           AS( I ) = AA( I )\n   20                   CONTINUE\n                        LDAS = LDA\n                        DO 30 I = 1, LX\n                           XS( I ) = XX( I )\n   30                   CONTINUE\n                        INCXS = INCX\n*\n*                       Call the subroutine.\n*\n                        IF( SNAME( 4: 5 ).EQ.'MV' )THEN\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZTRMV( UPLO, TRANS, DIAG, N, AA, LDA,\n     $                                    XX, INCX )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, K, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZTBMV( UPLO, TRANS, DIAG, N, K, AA,\n     $                                    LDA, XX, INCX )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZTPMV( UPLO, TRANS, DIAG, N, AA, XX,\n     $                                    INCX )\n                           END IF\n                        ELSE IF( SNAME( 4: 5 ).EQ.'SV' )THEN\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZTRSV( UPLO, TRANS, DIAG, N, AA, LDA,\n     $                                    XX, INCX )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, K, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZTBSV( UPLO, TRANS, DIAG, N, K, AA,\n     $                                    LDA, XX, INCX )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZTPSV( UPLO, TRANS, DIAG, N, AA, XX,\n     $                                    INCX )\n                           END IF\n                        END IF\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9992 )\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLO.EQ.UPLOS\n                        ISAME( 2 ) = TRANS.EQ.TRANSS\n                        ISAME( 3 ) = DIAG.EQ.DIAGS\n                        ISAME( 4 ) = NS.EQ.N\n                        IF( FULL )THEN\n                           ISAME( 5 ) = LZE( AS, AA, LAA )\n                           ISAME( 6 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 7 ) = LZE( XS, XX, LX )\n                           ELSE\n                              ISAME( 7 ) = LZERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 8 ) = INCXS.EQ.INCX\n                        ELSE IF( BANDED )THEN\n                           ISAME( 5 ) = KS.EQ.K\n                           ISAME( 6 ) = LZE( AS, AA, LAA )\n                           ISAME( 7 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 8 ) = LZE( XS, XX, LX )\n                           ELSE\n                              ISAME( 8 ) = LZERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 9 ) = INCXS.EQ.INCX\n                        ELSE IF( PACKED )THEN\n                           ISAME( 5 ) = LZE( AS, AA, LAA )\n                           IF( NULL )THEN\n                              ISAME( 6 ) = LZE( XS, XX, LX )\n                           ELSE\n                              ISAME( 6 ) = LZERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 7 ) = INCXS.EQ.INCX\n                        END IF\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n                           IF( SNAME( 4: 5 ).EQ.'MV' )THEN\n*\n*                             Check the result.\n*\n                              CALL ZMVCH( TRANS, N, N, ONE, A, NMAX, X,\n     $                                    INCX, ZERO, Z, INCX, XT, G,\n     $                                    XX, EPS, ERR, FATAL, NOUT,\n     $                                    .TRUE. )\n                           ELSE IF( SNAME( 4: 5 ).EQ.'SV' )THEN\n*\n*                             Compute approximation to original vector.\n*\n                              DO 50 I = 1, N\n                                 Z( I ) = XX( 1 + ( I - 1 )*\n     $                                    ABS( INCX ) )\n                                 XX( 1 + ( I - 1 )*ABS( INCX ) )\n     $                              = X( I )\n   50                         CONTINUE\n                              CALL ZMVCH( TRANS, N, N, ONE, A, NMAX, Z,\n     $                                    INCX, ZERO, X, INCX, XT, G,\n     $                                    XX, EPS, ERR, FATAL, NOUT,\n     $                                    .FALSE. )\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 120\n                        ELSE\n*                          Avoid repeating tests with N.le.0.\n                           GO TO 110\n                        END IF\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, TRANS, DIAG, N, LDA,\n     $      INCX\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, DIAG, N, K,\n     $      LDA, INCX\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, UPLO, TRANS, DIAG, N, INCX\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), I3, ', AP, ',\n     $      'X,', I2, ')                                      .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), 2( I3, ',' ),\n     $      ' A,', I3, ', X,', I2, ')                               .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), I3, ', A,',\n     $      I3, ', X,', I2, ')                                   .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK3.\n*\n      END\n      SUBROUTINE ZCHK4( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests ZGERC and ZGERU.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO, HALF, ONE\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   HALF = ( 0.5D0, 0.0D0 ),\n     $                   ONE = ( 1.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, ALS, TRANSL\n      DOUBLE PRECISION   ERR, ERRMAX\n      INTEGER            I, IA, IM, IN, INCX, INCXS, INCY, INCYS, IX,\n     $                   IY, J, LAA, LDA, LDAS, LX, LY, M, MS, N, NARGS,\n     $                   NC, ND, NS\n      LOGICAL            CONJ, NULL, RESET, SAME\n*     .. Local Arrays ..\n      COMPLEX*16         W( 1 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZGERC, ZGERU, ZMAKE, ZMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, DCONJG, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n      CONJ = SNAME( 5: 5 ).EQ.'C'\n*     Define the number of arguments.\n      NARGS = 9\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 120 IN = 1, NIDIM\n         N = IDIM( IN )\n         ND = N/2 + 1\n*\n         DO 110 IM = 1, 2\n            IF( IM.EQ.1 )\n     $         M = MAX( N - ND, 0 )\n            IF( IM.EQ.2 )\n     $         M = MIN( N + ND, NMAX )\n*\n*           Set LDA to 1 more than minimum value if room.\n            LDA = M\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 110\n            LAA = LDA*N\n            NULL = N.LE.0.OR.M.LE.0\n*\n            DO 100 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*M\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL ZMAKE( 'GE', ' ', ' ', 1, M, X, 1, XX, ABS( INCX ),\n     $                     0, M - 1, RESET, TRANSL )\n               IF( M.GT.1 )THEN\n                  X( M/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( M/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 90 IY = 1, NINC\n                  INCY = INC( IY )\n                  LY = ABS( INCY )*N\n*\n*                 Generate the vector Y.\n*\n                  TRANSL = ZERO\n                  CALL ZMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                        ABS( INCY ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     Y( N/2 ) = ZERO\n                     YY( 1 + ABS( INCY )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 80 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL ZMAKE( SNAME( 2: 3 ), ' ', ' ', M, N, A, NMAX,\n     $                           AA, LDA, M - 1, N - 1, RESET, TRANSL )\n*\n                     NC = NC + 1\n*\n*                    Save every datum before calling the subroutine.\n*\n                     MS = M\n                     NS = N\n                     ALS = ALPHA\n                     DO 10 I = 1, LAA\n                        AS( I ) = AA( I )\n   10                CONTINUE\n                     LDAS = LDA\n                     DO 20 I = 1, LX\n                        XS( I ) = XX( I )\n   20                CONTINUE\n                     INCXS = INCX\n                     DO 30 I = 1, LY\n                        YS( I ) = YY( I )\n   30                CONTINUE\n                     INCYS = INCY\n*\n*                    Call the subroutine.\n*\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9994 )NC, SNAME, M, N,\n     $                  ALPHA, INCX, INCY, LDA\n                     IF( CONJ )THEN\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL ZGERC( M, N, ALPHA, XX, INCX, YY, INCY, AA,\n     $                              LDA )\n                     ELSE\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL ZGERU( M, N, ALPHA, XX, INCX, YY, INCY, AA,\n     $                              LDA )\n                     END IF\n*\n*                    Check if error-exit was taken incorrectly.\n*\n                     IF( .NOT.OK )THEN\n                        WRITE( NOUT, FMT = 9993 )\n                        FATAL = .TRUE.\n                        GO TO 140\n                     END IF\n*\n*                    See what data changed inside subroutine.\n*\n                     ISAME( 1 ) = MS.EQ.M\n                     ISAME( 2 ) = NS.EQ.N\n                     ISAME( 3 ) = ALS.EQ.ALPHA\n                     ISAME( 4 ) = LZE( XS, XX, LX )\n                     ISAME( 5 ) = INCXS.EQ.INCX\n                     ISAME( 6 ) = LZE( YS, YY, LY )\n                     ISAME( 7 ) = INCYS.EQ.INCY\n                     IF( NULL )THEN\n                        ISAME( 8 ) = LZE( AS, AA, LAA )\n                     ELSE\n                        ISAME( 8 ) = LZERES( 'GE', ' ', M, N, AS, AA,\n     $                               LDA )\n                     END IF\n                     ISAME( 9 ) = LDAS.EQ.LDA\n*\n*                    If data was incorrectly changed, report and return.\n*\n                     SAME = .TRUE.\n                     DO 40 I = 1, NARGS\n                        SAME = SAME.AND.ISAME( I )\n                        IF( .NOT.ISAME( I ) )\n     $                     WRITE( NOUT, FMT = 9998 )I\n   40                CONTINUE\n                     IF( .NOT.SAME )THEN\n                        FATAL = .TRUE.\n                        GO TO 140\n                     END IF\n*\n                     IF( .NOT.NULL )THEN\n*\n*                       Check the result column by column.\n*\n                        IF( INCX.GT.0 )THEN\n                           DO 50 I = 1, M\n                              Z( I ) = X( I )\n   50                      CONTINUE\n                        ELSE\n                           DO 60 I = 1, M\n                              Z( I ) = X( M - I + 1 )\n   60                      CONTINUE\n                        END IF\n                        DO 70 J = 1, N\n                           IF( INCY.GT.0 )THEN\n                              W( 1 ) = Y( J )\n                           ELSE\n                              W( 1 ) = Y( N - J + 1 )\n                           END IF\n                           IF( CONJ )\n     $                        W( 1 ) = DCONJG( W( 1 ) )\n                           CALL ZMVCH( 'N', M, 1, ALPHA, Z, NMAX, W, 1,\n     $                                 ONE, A( 1, J ), 1, YT, G,\n     $                                 AA( 1 + ( J - 1 )*LDA ), EPS,\n     $                                 ERR, FATAL, NOUT, .TRUE. )\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 130\n   70                   CONTINUE\n                     ELSE\n*                       Avoid repeating tests with M.le.0 or N.le.0.\n                        GO TO 110\n                     END IF\n*\n   80             CONTINUE\n*\n   90          CONTINUE\n*\n  100       CONTINUE\n*\n  110    CONTINUE\n*\n  120 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 150\n*\n  130 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  140 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9994 )NC, SNAME, M, N, ALPHA, INCX, INCY, LDA\n*\n  150 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( I3, ',' ), '(', F4.1, ',', F4.1,\n     $      '), X,', I2, ', Y,', I2, ', A,', I3, ')                   ',\n     $      '      .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK4.\n*\n      END\n      SUBROUTINE ZCHK5( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests ZHER and ZHPR.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO, HALF, ONE\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   HALF = ( 0.5D0, 0.0D0 ),\n     $                   ONE = ( 1.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, TRANSL\n      DOUBLE PRECISION   ERR, ERRMAX, RALPHA, RALS\n      INTEGER            I, IA, IC, IN, INCX, INCXS, IX, J, JA, JJ, LAA,\n     $                   LDA, LDAS, LJ, LX, N, NARGS, NC, NS\n      LOGICAL            FULL, NULL, PACKED, RESET, SAME, UPPER\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      COMPLEX*16         W( 1 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZHER, ZHPR, ZMAKE, ZMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, DBLE, DCMPLX, DCONJG, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'E'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 7\n      ELSE IF( PACKED )THEN\n         NARGS = 6\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 100 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDA to 1 more than minimum value if room.\n         LDA = N\n         IF( LDA.LT.NMAX )\n     $      LDA = LDA + 1\n*        Skip tests if not enough room.\n         IF( LDA.GT.NMAX )\n     $      GO TO 100\n         IF( PACKED )THEN\n            LAA = ( N*( N + 1 ) )/2\n         ELSE\n            LAA = LDA*N\n         END IF\n*\n         DO 90 IC = 1, 2\n            UPLO = ICH( IC: IC )\n            UPPER = UPLO.EQ.'U'\n*\n            DO 80 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*N\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL ZMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX, ABS( INCX ),\n     $                     0, N - 1, RESET, TRANSL )\n               IF( N.GT.1 )THEN\n                  X( N/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 70 IA = 1, NALF\n                  RALPHA = DBLE( ALF( IA ) )\n                  ALPHA = DCMPLX( RALPHA, RZERO )\n                  NULL = N.LE.0.OR.RALPHA.EQ.RZERO\n*\n*                 Generate the matrix A.\n*\n                  TRANSL = ZERO\n                  CALL ZMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A, NMAX,\n     $                        AA, LDA, N - 1, N - 1, RESET, TRANSL )\n*\n                  NC = NC + 1\n*\n*                 Save every datum before calling the subroutine.\n*\n                  UPLOS = UPLO\n                  NS = N\n                  RALS = RALPHA\n                  DO 10 I = 1, LAA\n                     AS( I ) = AA( I )\n   10             CONTINUE\n                  LDAS = LDA\n                  DO 20 I = 1, LX\n                     XS( I ) = XX( I )\n   20             CONTINUE\n                  INCXS = INCX\n*\n*                 Call the subroutine.\n*\n                  IF( FULL )THEN\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO, N,\n     $                  RALPHA, INCX, LDA\n                     IF( REWI )\n     $                  REWIND NTRA\n                     CALL ZHER( UPLO, N, RALPHA, XX, INCX, AA, LDA )\n                  ELSE IF( PACKED )THEN\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO, N,\n     $                  RALPHA, INCX\n                     IF( REWI )\n     $                  REWIND NTRA\n                     CALL ZHPR( UPLO, N, RALPHA, XX, INCX, AA )\n                  END IF\n*\n*                 Check if error-exit was taken incorrectly.\n*\n                  IF( .NOT.OK )THEN\n                     WRITE( NOUT, FMT = 9992 )\n                     FATAL = .TRUE.\n                     GO TO 120\n                  END IF\n*\n*                 See what data changed inside subroutines.\n*\n                  ISAME( 1 ) = UPLO.EQ.UPLOS\n                  ISAME( 2 ) = NS.EQ.N\n                  ISAME( 3 ) = RALS.EQ.RALPHA\n                  ISAME( 4 ) = LZE( XS, XX, LX )\n                  ISAME( 5 ) = INCXS.EQ.INCX\n                  IF( NULL )THEN\n                     ISAME( 6 ) = LZE( AS, AA, LAA )\n                  ELSE\n                     ISAME( 6 ) = LZERES( SNAME( 2: 3 ), UPLO, N, N, AS,\n     $                            AA, LDA )\n                  END IF\n                  IF( .NOT.PACKED )THEN\n                     ISAME( 7 ) = LDAS.EQ.LDA\n                  END IF\n*\n*                 If data was incorrectly changed, report and return.\n*\n                  SAME = .TRUE.\n                  DO 30 I = 1, NARGS\n                     SAME = SAME.AND.ISAME( I )\n                     IF( .NOT.ISAME( I ) )\n     $                  WRITE( NOUT, FMT = 9998 )I\n   30             CONTINUE\n                  IF( .NOT.SAME )THEN\n                     FATAL = .TRUE.\n                     GO TO 120\n                  END IF\n*\n                  IF( .NOT.NULL )THEN\n*\n*                    Check the result column by column.\n*\n                     IF( INCX.GT.0 )THEN\n                        DO 40 I = 1, N\n                           Z( I ) = X( I )\n   40                   CONTINUE\n                     ELSE\n                        DO 50 I = 1, N\n                           Z( I ) = X( N - I + 1 )\n   50                   CONTINUE\n                     END IF\n                     JA = 1\n                     DO 60 J = 1, N\n                        W( 1 ) = DCONJG( Z( J ) )\n                        IF( UPPER )THEN\n                           JJ = 1\n                           LJ = J\n                        ELSE\n                           JJ = J\n                           LJ = N - J + 1\n                        END IF\n                        CALL ZMVCH( 'N', LJ, 1, ALPHA, Z( JJ ), LJ, W,\n     $                              1, ONE, A( JJ, J ), 1, YT, G,\n     $                              AA( JA ), EPS, ERR, FATAL, NOUT,\n     $                              .TRUE. )\n                        IF( FULL )THEN\n                           IF( UPPER )THEN\n                              JA = JA + LDA\n                           ELSE\n                              JA = JA + LDA + 1\n                           END IF\n                        ELSE\n                           JA = JA + LJ\n                        END IF\n                        ERRMAX = MAX( ERRMAX, ERR )\n*                       If got really bad answer, report and return.\n                        IF( FATAL )\n     $                     GO TO 110\n   60                CONTINUE\n                  ELSE\n*                    Avoid repeating tests if N.le.0.\n                     IF( N.LE.0 )\n     $                  GO TO 100\n                  END IF\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  110 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, RALPHA, INCX, LDA\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, RALPHA, INCX\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', AP)                                         .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', A,', I3, ')                                      .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK5.\n*\n      END\n      SUBROUTINE ZCHK6( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests ZHER2 and ZHPR2.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO, HALF, ONE\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   HALF = ( 0.5D0, 0.0D0 ),\n     $                   ONE = ( 1.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX, 2 )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, ALS, TRANSL\n      DOUBLE PRECISION   ERR, ERRMAX\n      INTEGER            I, IA, IC, IN, INCX, INCXS, INCY, INCYS, IX,\n     $                   IY, J, JA, JJ, LAA, LDA, LDAS, LJ, LX, LY, N,\n     $                   NARGS, NC, NS\n      LOGICAL            FULL, NULL, PACKED, RESET, SAME, UPPER\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      COMPLEX*16         W( 2 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZHER2, ZHPR2, ZMAKE, ZMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, DCONJG, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'E'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 9\n      ELSE IF( PACKED )THEN\n         NARGS = 8\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 140 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDA to 1 more than minimum value if room.\n         LDA = N\n         IF( LDA.LT.NMAX )\n     $      LDA = LDA + 1\n*        Skip tests if not enough room.\n         IF( LDA.GT.NMAX )\n     $      GO TO 140\n         IF( PACKED )THEN\n            LAA = ( N*( N + 1 ) )/2\n         ELSE\n            LAA = LDA*N\n         END IF\n*\n         DO 130 IC = 1, 2\n            UPLO = ICH( IC: IC )\n            UPPER = UPLO.EQ.'U'\n*\n            DO 120 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*N\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL ZMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX, ABS( INCX ),\n     $                     0, N - 1, RESET, TRANSL )\n               IF( N.GT.1 )THEN\n                  X( N/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 110 IY = 1, NINC\n                  INCY = INC( IY )\n                  LY = ABS( INCY )*N\n*\n*                 Generate the vector Y.\n*\n                  TRANSL = ZERO\n                  CALL ZMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                        ABS( INCY ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     Y( N/2 ) = ZERO\n                     YY( 1 + ABS( INCY )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 100 IA = 1, NALF\n                     ALPHA = ALF( IA )\n                     NULL = N.LE.0.OR.ALPHA.EQ.ZERO\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL ZMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A,\n     $                           NMAX, AA, LDA, N - 1, N - 1, RESET,\n     $                           TRANSL )\n*\n                     NC = NC + 1\n*\n*                    Save every datum before calling the subroutine.\n*\n                     UPLOS = UPLO\n                     NS = N\n                     ALS = ALPHA\n                     DO 10 I = 1, LAA\n                        AS( I ) = AA( I )\n   10                CONTINUE\n                     LDAS = LDA\n                     DO 20 I = 1, LX\n                        XS( I ) = XX( I )\n   20                CONTINUE\n                     INCXS = INCX\n                     DO 30 I = 1, LY\n                        YS( I ) = YY( I )\n   30                CONTINUE\n                     INCYS = INCY\n*\n*                    Call the subroutine.\n*\n                     IF( FULL )THEN\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO, N,\n     $                     ALPHA, INCX, INCY, LDA\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL ZHER2( UPLO, N, ALPHA, XX, INCX, YY, INCY,\n     $                              AA, LDA )\n                     ELSE IF( PACKED )THEN\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO, N,\n     $                     ALPHA, INCX, INCY\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL ZHPR2( UPLO, N, ALPHA, XX, INCX, YY, INCY,\n     $                              AA )\n                     END IF\n*\n*                    Check if error-exit was taken incorrectly.\n*\n                     IF( .NOT.OK )THEN\n                        WRITE( NOUT, FMT = 9992 )\n                        FATAL = .TRUE.\n                        GO TO 160\n                     END IF\n*\n*                    See what data changed inside subroutines.\n*\n                     ISAME( 1 ) = UPLO.EQ.UPLOS\n                     ISAME( 2 ) = NS.EQ.N\n                     ISAME( 3 ) = ALS.EQ.ALPHA\n                     ISAME( 4 ) = LZE( XS, XX, LX )\n                     ISAME( 5 ) = INCXS.EQ.INCX\n                     ISAME( 6 ) = LZE( YS, YY, LY )\n                     ISAME( 7 ) = INCYS.EQ.INCY\n                     IF( NULL )THEN\n                        ISAME( 8 ) = LZE( AS, AA, LAA )\n                     ELSE\n                        ISAME( 8 ) = LZERES( SNAME( 2: 3 ), UPLO, N, N,\n     $                               AS, AA, LDA )\n                     END IF\n                     IF( .NOT.PACKED )THEN\n                        ISAME( 9 ) = LDAS.EQ.LDA\n                     END IF\n*\n*                    If data was incorrectly changed, report and return.\n*\n                     SAME = .TRUE.\n                     DO 40 I = 1, NARGS\n                        SAME = SAME.AND.ISAME( I )\n                        IF( .NOT.ISAME( I ) )\n     $                     WRITE( NOUT, FMT = 9998 )I\n   40                CONTINUE\n                     IF( .NOT.SAME )THEN\n                        FATAL = .TRUE.\n                        GO TO 160\n                     END IF\n*\n                     IF( .NOT.NULL )THEN\n*\n*                       Check the result column by column.\n*\n                        IF( INCX.GT.0 )THEN\n                           DO 50 I = 1, N\n                              Z( I, 1 ) = X( I )\n   50                      CONTINUE\n                        ELSE\n                           DO 60 I = 1, N\n                              Z( I, 1 ) = X( N - I + 1 )\n   60                      CONTINUE\n                        END IF\n                        IF( INCY.GT.0 )THEN\n                           DO 70 I = 1, N\n                              Z( I, 2 ) = Y( I )\n   70                      CONTINUE\n                        ELSE\n                           DO 80 I = 1, N\n                              Z( I, 2 ) = Y( N - I + 1 )\n   80                      CONTINUE\n                        END IF\n                        JA = 1\n                        DO 90 J = 1, N\n                           W( 1 ) = ALPHA*DCONJG( Z( J, 2 ) )\n                           W( 2 ) = DCONJG( ALPHA )*DCONJG( Z( J, 1 ) )\n                           IF( UPPER )THEN\n                              JJ = 1\n                              LJ = J\n                           ELSE\n                              JJ = J\n                              LJ = N - J + 1\n                           END IF\n                           CALL ZMVCH( 'N', LJ, 2, ONE, Z( JJ, 1 ),\n     $                                 NMAX, W, 1, ONE, A( JJ, J ), 1,\n     $                                 YT, G, AA( JA ), EPS, ERR, FATAL,\n     $                                 NOUT, .TRUE. )\n                           IF( FULL )THEN\n                              IF( UPPER )THEN\n                                 JA = JA + LDA\n                              ELSE\n                                 JA = JA + LDA + 1\n                              END IF\n                           ELSE\n                              JA = JA + LJ\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 150\n   90                   CONTINUE\n                     ELSE\n*                       Avoid repeating tests with N.le.0.\n                        IF( N.LE.0 )\n     $                     GO TO 140\n                     END IF\n*\n  100             CONTINUE\n*\n  110          CONTINUE\n*\n  120       CONTINUE\n*\n  130    CONTINUE\n*\n  140 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 170\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  160 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, ALPHA, INCX,\n     $      INCY, LDA\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, ALPHA, INCX, INCY\n      END IF\n*\n  170 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',(', F4.1, ',',\n     $      F4.1, '), X,', I2, ', Y,', I2, ', AP)                     ',\n     $      '       .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',(', F4.1, ',',\n     $      F4.1, '), X,', I2, ', Y,', I2, ', A,', I3, ')             ',\n     $      '            .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK6.\n*\n      END\n      SUBROUTINE ZCHKE( ISNUM, SRNAMT, NOUT )\n*\n*  Tests the error exits from the Level 2 Blas.\n*  Requires a special version of the error-handling routine XERBLA.\n*  ALPHA, RALPHA, BETA, A, X and Y should not need to be defined.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            ISNUM, NOUT\n      CHARACTER*6        SRNAMT\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, BETA\n      DOUBLE PRECISION   RALPHA\n*     .. Local Arrays ..\n      COMPLEX*16         A( 1, 1 ), X( 1 ), Y( 1 )\n*     .. External Subroutines ..\n      EXTERNAL           CHKXER, ZGBMV, ZGEMV, ZGERC, ZGERU, ZHBMV,\n     $                   ZHEMV, ZHER, ZHER2, ZHPMV, ZHPR, ZHPR2, ZTBMV,\n     $                   ZTBSV, ZTPMV, ZTPSV, ZTRMV, ZTRSV\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n*     OK is set to .FALSE. by the special version of XERBLA or by CHKXER\n*     if anything is wrong.\n      OK = .TRUE.\n*     LERR is set to .TRUE. by the special version of XERBLA each time\n*     it is called, and is then tested and re-set by CHKXER.\n      LERR = .FALSE.\n      GO TO ( 10, 20, 30, 40, 50, 60, 70, 80,\n     $        90, 100, 110, 120, 130, 140, 150, 160,\n     $        170 )ISNUM\n   10 INFOT = 1\n      CALL ZGEMV( '/', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZGEMV( 'N', -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGEMV( 'N', 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZGEMV( 'N', 2, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGEMV( 'N', 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZGEMV( 'N', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   20 INFOT = 1\n      CALL ZGBMV( '/', 0, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZGBMV( 'N', -1, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGBMV( 'N', 0, -1, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZGBMV( 'N', 0, 0, -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGBMV( 'N', 2, 0, 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGBMV( 'N', 0, 0, 1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZGBMV( 'N', 0, 0, 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL ZGBMV( 'N', 0, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   30 INFOT = 1\n      CALL ZHEMV( '/', 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZHEMV( 'U', -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZHEMV( 'U', 2, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHEMV( 'U', 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZHEMV( 'U', 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   40 INFOT = 1\n      CALL ZHBMV( '/', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZHBMV( 'U', -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHBMV( 'U', 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZHBMV( 'U', 0, 1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZHBMV( 'U', 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZHBMV( 'U', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   50 INFOT = 1\n      CALL ZHPMV( '/', 0, ALPHA, A, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZHPMV( 'U', -1, ALPHA, A, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZHPMV( 'U', 0, ALPHA, A, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZHPMV( 'U', 0, ALPHA, A, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   60 INFOT = 1\n      CALL ZTRMV( '/', 'N', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZTRMV( 'U', '/', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZTRMV( 'U', 'N', '/', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZTRMV( 'U', 'N', 'N', -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMV( 'U', 'N', 'N', 2, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZTRMV( 'U', 'N', 'N', 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   70 INFOT = 1\n      CALL ZTBMV( '/', 'N', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZTBMV( 'U', '/', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZTBMV( 'U', 'N', '/', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZTBMV( 'U', 'N', 'N', -1, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTBMV( 'U', 'N', 'N', 0, -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZTBMV( 'U', 'N', 'N', 0, 1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTBMV( 'U', 'N', 'N', 0, 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   80 INFOT = 1\n      CALL ZTPMV( '/', 'N', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZTPMV( 'U', '/', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZTPMV( 'U', 'N', '/', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZTPMV( 'U', 'N', 'N', -1, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZTPMV( 'U', 'N', 'N', 0, A, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   90 INFOT = 1\n      CALL ZTRSV( '/', 'N', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZTRSV( 'U', '/', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZTRSV( 'U', 'N', '/', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZTRSV( 'U', 'N', 'N', -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSV( 'U', 'N', 'N', 2, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZTRSV( 'U', 'N', 'N', 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  100 INFOT = 1\n      CALL ZTBSV( '/', 'N', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZTBSV( 'U', '/', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZTBSV( 'U', 'N', '/', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZTBSV( 'U', 'N', 'N', -1, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTBSV( 'U', 'N', 'N', 0, -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZTBSV( 'U', 'N', 'N', 0, 1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTBSV( 'U', 'N', 'N', 0, 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  110 INFOT = 1\n      CALL ZTPSV( '/', 'N', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZTPSV( 'U', '/', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZTPSV( 'U', 'N', '/', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZTPSV( 'U', 'N', 'N', -1, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZTPSV( 'U', 'N', 'N', 0, A, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  120 INFOT = 1\n      CALL ZGERC( -1, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZGERC( 0, -1, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGERC( 0, 0, ALPHA, X, 0, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZGERC( 0, 0, ALPHA, X, 1, Y, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZGERC( 2, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  130 INFOT = 1\n      CALL ZGERU( -1, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZGERU( 0, -1, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGERU( 0, 0, ALPHA, X, 0, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZGERU( 0, 0, ALPHA, X, 1, Y, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZGERU( 2, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  140 INFOT = 1\n      CALL ZHER( '/', 0, RALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZHER( 'U', -1, RALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZHER( 'U', 0, RALPHA, X, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHER( 'U', 2, RALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  150 INFOT = 1\n      CALL ZHPR( '/', 0, RALPHA, X, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZHPR( 'U', -1, RALPHA, X, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZHPR( 'U', 0, RALPHA, X, 0, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  160 INFOT = 1\n      CALL ZHER2( '/', 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZHER2( 'U', -1, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZHER2( 'U', 0, ALPHA, X, 0, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHER2( 'U', 0, ALPHA, X, 1, Y, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZHER2( 'U', 2, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  170 INFOT = 1\n      CALL ZHPR2( '/', 0, ALPHA, X, 1, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZHPR2( 'U', -1, ALPHA, X, 1, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZHPR2( 'U', 0, ALPHA, X, 0, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHPR2( 'U', 0, ALPHA, X, 1, Y, 0, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n  180 IF( OK )THEN\n         WRITE( NOUT, FMT = 9999 )SRNAMT\n      ELSE\n         WRITE( NOUT, FMT = 9998 )SRNAMT\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE TESTS OF ERROR-EXITS' )\n 9998 FORMAT( ' ******* ', A6, ' FAILED THE TESTS OF ERROR-EXITS *****',\n     $      '**' )\n*\n*     End of ZCHKE.\n*\n      END\n      SUBROUTINE ZMAKE( TYPE, UPLO, DIAG, M, N, A, NMAX, AA, LDA, KL,\n     $                  KU, RESET, TRANSL )\n*\n*  Generates values for an M by N matrix A within the bandwidth\n*  defined by KL and KU.\n*  Stores the values in the array AA in the data structure required\n*  by the routine, with unwanted elements set to rogue value.\n*\n*  TYPE is 'GE', 'GB', 'HE', 'HB', 'HP', 'TR', 'TB' OR 'TP'.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   ONE = ( 1.0D0, 0.0D0 ) )\n      COMPLEX*16         ROGUE\n      PARAMETER          ( ROGUE = ( -1.0D10, 1.0D10 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n      DOUBLE PRECISION   RROGUE\n      PARAMETER          ( RROGUE = -1.0D10 )\n*     .. Scalar Arguments ..\n      COMPLEX*16         TRANSL\n      INTEGER            KL, KU, LDA, M, N, NMAX\n      LOGICAL            RESET\n      CHARACTER*1        DIAG, UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, * ), AA( * )\n*     .. Local Scalars ..\n      INTEGER            I, I1, I2, I3, IBEG, IEND, IOFF, J, JJ, KK\n      LOGICAL            GEN, LOWER, SYM, TRI, UNIT, UPPER\n*     .. External Functions ..\n      COMPLEX*16         ZBEG\n      EXTERNAL           ZBEG\n*     .. Intrinsic Functions ..\n      INTRINSIC          DBLE, DCMPLX, DCONJG, MAX, MIN\n*     .. Executable Statements ..\n      GEN = TYPE( 1: 1 ).EQ.'G'\n      SYM = TYPE( 1: 1 ).EQ.'H'\n      TRI = TYPE( 1: 1 ).EQ.'T'\n      UPPER = ( SYM.OR.TRI ).AND.UPLO.EQ.'U'\n      LOWER = ( SYM.OR.TRI ).AND.UPLO.EQ.'L'\n      UNIT = TRI.AND.DIAG.EQ.'U'\n*\n*     Generate data in array A.\n*\n      DO 20 J = 1, N\n         DO 10 I = 1, M\n            IF( GEN.OR.( UPPER.AND.I.LE.J ).OR.( LOWER.AND.I.GE.J ) )\n     $          THEN\n               IF( ( I.LE.J.AND.J - I.LE.KU ).OR.\n     $             ( I.GE.J.AND.I - J.LE.KL ) )THEN\n                  A( I, J ) = ZBEG( RESET ) + TRANSL\n               ELSE\n                  A( I, J ) = ZERO\n               END IF\n               IF( I.NE.J )THEN\n                  IF( SYM )THEN\n                     A( J, I ) = DCONJG( A( I, J ) )\n                  ELSE IF( TRI )THEN\n                     A( J, I ) = ZERO\n                  END IF\n               END IF\n            END IF\n   10    CONTINUE\n         IF( SYM )\n     $      A( J, J ) = DCMPLX( DBLE( A( J, J ) ), RZERO )\n         IF( TRI )\n     $      A( J, J ) = A( J, J ) + ONE\n         IF( UNIT )\n     $      A( J, J ) = ONE\n   20 CONTINUE\n*\n*     Store elements in array AS in data structure required by routine.\n*\n      IF( TYPE.EQ.'GE' )THEN\n         DO 50 J = 1, N\n            DO 30 I = 1, M\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   30       CONTINUE\n            DO 40 I = M + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   40       CONTINUE\n   50    CONTINUE\n      ELSE IF( TYPE.EQ.'GB' )THEN\n         DO 90 J = 1, N\n            DO 60 I1 = 1, KU + 1 - J\n               AA( I1 + ( J - 1 )*LDA ) = ROGUE\n   60       CONTINUE\n            DO 70 I2 = I1, MIN( KL + KU + 1, KU + 1 + M - J )\n               AA( I2 + ( J - 1 )*LDA ) = A( I2 + J - KU - 1, J )\n   70       CONTINUE\n            DO 80 I3 = I2, LDA\n               AA( I3 + ( J - 1 )*LDA ) = ROGUE\n   80       CONTINUE\n   90    CONTINUE\n      ELSE IF( TYPE.EQ.'HE'.OR.TYPE.EQ.'TR' )THEN\n         DO 130 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IF( UNIT )THEN\n                  IEND = J - 1\n               ELSE\n                  IEND = J\n               END IF\n            ELSE\n               IF( UNIT )THEN\n                  IBEG = J + 1\n               ELSE\n                  IBEG = J\n               END IF\n               IEND = N\n            END IF\n            DO 100 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  100       CONTINUE\n            DO 110 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n  110       CONTINUE\n            DO 120 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  120       CONTINUE\n            IF( SYM )THEN\n               JJ = J + ( J - 1 )*LDA\n               AA( JJ ) = DCMPLX( DBLE( AA( JJ ) ), RROGUE )\n            END IF\n  130    CONTINUE\n      ELSE IF( TYPE.EQ.'HB'.OR.TYPE.EQ.'TB' )THEN\n         DO 170 J = 1, N\n            IF( UPPER )THEN\n               KK = KL + 1\n               IBEG = MAX( 1, KL + 2 - J )\n               IF( UNIT )THEN\n                  IEND = KL\n               ELSE\n                  IEND = KL + 1\n               END IF\n            ELSE\n               KK = 1\n               IF( UNIT )THEN\n                  IBEG = 2\n               ELSE\n                  IBEG = 1\n               END IF\n               IEND = MIN( KL + 1, 1 + M - J )\n            END IF\n            DO 140 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  140       CONTINUE\n            DO 150 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I + J - KK, J )\n  150       CONTINUE\n            DO 160 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  160       CONTINUE\n            IF( SYM )THEN\n               JJ = KK + ( J - 1 )*LDA\n               AA( JJ ) = DCMPLX( DBLE( AA( JJ ) ), RROGUE )\n            END IF\n  170    CONTINUE\n      ELSE IF( TYPE.EQ.'HP'.OR.TYPE.EQ.'TP' )THEN\n         IOFF = 0\n         DO 190 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 180 I = IBEG, IEND\n               IOFF = IOFF + 1\n               AA( IOFF ) = A( I, J )\n               IF( I.EQ.J )THEN\n                  IF( UNIT )\n     $               AA( IOFF ) = ROGUE\n                  IF( SYM )\n     $               AA( IOFF ) = DCMPLX( DBLE( AA( IOFF ) ), RROGUE )\n               END IF\n  180       CONTINUE\n  190    CONTINUE\n      END IF\n      RETURN\n*\n*     End of ZMAKE.\n*\n      END\n      SUBROUTINE ZMVCH( TRANS, M, N, ALPHA, A, NMAX, X, INCX, BETA, Y,\n     $                  INCY, YT, G, YY, EPS, ERR, FATAL, NOUT, MV )\n*\n*  Checks the results of the computational tests.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO, RONE\n      PARAMETER          ( RZERO = 0.0D0, RONE = 1.0D0 )\n*     .. Scalar Arguments ..\n      COMPLEX*16         ALPHA, BETA\n      DOUBLE PRECISION   EPS, ERR\n      INTEGER            INCX, INCY, M, N, NMAX, NOUT\n      LOGICAL            FATAL, MV\n      CHARACTER*1        TRANS\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, * ), X( * ), Y( * ), YT( * ), YY( * )\n      DOUBLE PRECISION   G( * )\n*     .. Local Scalars ..\n      COMPLEX*16         C\n      DOUBLE PRECISION   ERRI\n      INTEGER            I, INCXL, INCYL, IY, J, JX, KX, KY, ML, NL\n      LOGICAL            CTRAN, TRAN\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, DBLE, DCONJG, DIMAG, MAX, SQRT\n*     .. Statement Functions ..\n      DOUBLE PRECISION   ABS1\n*     .. Statement Function definitions ..\n      ABS1( C ) = ABS( DBLE( C ) ) + ABS( DIMAG( C ) )\n*     .. Executable Statements ..\n      TRAN = TRANS.EQ.'T'\n      CTRAN = TRANS.EQ.'C'\n      IF( TRAN.OR.CTRAN )THEN\n         ML = N\n         NL = M\n      ELSE\n         ML = M\n         NL = N\n      END IF\n      IF( INCX.LT.0 )THEN\n         KX = NL\n         INCXL = -1\n      ELSE\n         KX = 1\n         INCXL = 1\n      END IF\n      IF( INCY.LT.0 )THEN\n         KY = ML\n         INCYL = -1\n      ELSE\n         KY = 1\n         INCYL = 1\n      END IF\n*\n*     Compute expected result in YT using data in A, X and Y.\n*     Compute gauges in G.\n*\n      IY = KY\n      DO 40 I = 1, ML\n         YT( IY ) = ZERO\n         G( IY ) = RZERO\n         JX = KX\n         IF( TRAN )THEN\n            DO 10 J = 1, NL\n               YT( IY ) = YT( IY ) + A( J, I )*X( JX )\n               G( IY ) = G( IY ) + ABS1( A( J, I ) )*ABS1( X( JX ) )\n               JX = JX + INCXL\n   10       CONTINUE\n         ELSE IF( CTRAN )THEN\n            DO 20 J = 1, NL\n               YT( IY ) = YT( IY ) + DCONJG( A( J, I ) )*X( JX )\n               G( IY ) = G( IY ) + ABS1( A( J, I ) )*ABS1( X( JX ) )\n               JX = JX + INCXL\n   20       CONTINUE\n         ELSE\n            DO 30 J = 1, NL\n               YT( IY ) = YT( IY ) + A( I, J )*X( JX )\n               G( IY ) = G( IY ) + ABS1( A( I, J ) )*ABS1( X( JX ) )\n               JX = JX + INCXL\n   30       CONTINUE\n         END IF\n         YT( IY ) = ALPHA*YT( IY ) + BETA*Y( IY )\n         G( IY ) = ABS1( ALPHA )*G( IY ) + ABS1( BETA )*ABS1( Y( IY ) )\n         IY = IY + INCYL\n   40 CONTINUE\n*\n*     Compute the error ratio for this result.\n*\n      ERR = ZERO\n      DO 50 I = 1, ML\n         ERRI = ABS( YT( I ) - YY( 1 + ( I - 1 )*ABS( INCY ) ) )/EPS\n         IF( G( I ).NE.RZERO )\n     $      ERRI = ERRI/G( I )\n         ERR = MAX( ERR, ERRI )\n         IF( ERR*SQRT( EPS ).GE.RONE )\n     $      GO TO 60\n   50 CONTINUE\n*     If the loop completes, all results are at least half accurate.\n      GO TO 80\n*\n*     Report fatal error.\n*\n   60 FATAL = .TRUE.\n      WRITE( NOUT, FMT = 9999 )\n      DO 70 I = 1, ML\n         IF( MV )THEN\n            WRITE( NOUT, FMT = 9998 )I, YT( I ),\n     $         YY( 1 + ( I - 1 )*ABS( INCY ) )\n         ELSE\n            WRITE( NOUT, FMT = 9998 )I,\n     $         YY( 1 + ( I - 1 )*ABS( INCY ) ), YT( I )\n         END IF\n   70 CONTINUE\n*\n   80 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ******* FATAL ERROR - COMPUTED RESULT IS LESS THAN HAL',\n     $      'F ACCURATE *******', /'                       EXPECTED RE',\n     $      'SULT                    COMPUTED RESULT' )\n 9998 FORMAT( 1X, I7, 2( '  (', G15.6, ',', G15.6, ')' ) )\n*\n*     End of ZMVCH.\n*\n      END\n      LOGICAL FUNCTION LZE( RI, RJ, LR )\n*\n*  Tests if two arrays are identical.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LR\n*     .. Array Arguments ..\n      COMPLEX*16         RI( * ), RJ( * )\n*     .. Local Scalars ..\n      INTEGER            I\n*     .. Executable Statements ..\n      DO 10 I = 1, LR\n         IF( RI( I ).NE.RJ( I ) )\n     $      GO TO 20\n   10 CONTINUE\n      LZE = .TRUE.\n      GO TO 30\n   20 CONTINUE\n      LZE = .FALSE.\n   30 RETURN\n*\n*     End of LZE.\n*\n      END\n      LOGICAL FUNCTION LZERES( TYPE, UPLO, M, N, AA, AS, LDA )\n*\n*  Tests if selected elements in two arrays are equal.\n*\n*  TYPE is 'GE', 'HE' or 'HP'.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LDA, M, N\n      CHARACTER*1        UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      COMPLEX*16         AA( LDA, * ), AS( LDA, * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J\n      LOGICAL            UPPER\n*     .. Executable Statements ..\n      UPPER = UPLO.EQ.'U'\n      IF( TYPE.EQ.'GE' )THEN\n         DO 20 J = 1, N\n            DO 10 I = M + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   10       CONTINUE\n   20    CONTINUE\n      ELSE IF( TYPE.EQ.'HE' )THEN\n         DO 50 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 30 I = 1, IBEG - 1\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   30       CONTINUE\n            DO 40 I = IEND + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   40       CONTINUE\n   50    CONTINUE\n      END IF\n*\n      LZERES = .TRUE.\n      GO TO 80\n   70 CONTINUE\n      LZERES = .FALSE.\n   80 RETURN\n*\n*     End of LZERES.\n*\n      END\n      COMPLEX*16 FUNCTION ZBEG( RESET )\n*\n*  Generates complex numbers as pairs of random numbers uniformly\n*  distributed between -0.5 and 0.5.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      LOGICAL            RESET\n*     .. Local Scalars ..\n      INTEGER            I, IC, J, MI, MJ\n*     .. Save statement ..\n      SAVE               I, IC, J, MI, MJ\n*     .. Intrinsic Functions ..\n      INTRINSIC          DCMPLX\n*     .. Executable Statements ..\n      IF( RESET )THEN\n*        Initialize local variables.\n         MI = 891\n         MJ = 457\n         I = 7\n         J = 7\n         IC = 0\n         RESET = .FALSE.\n      END IF\n*\n*     The sequence of values of I or J is bounded between 1 and 999.\n*     If initial I or J = 1,2,3,6,7 or 9, the period will be 50.\n*     If initial I or J = 4 or 8, the period will be 25.\n*     If initial I or J = 5, the period will be 10.\n*     IC is used to break up the period by skipping 1 value of I or J\n*     in 6.\n*\n      IC = IC + 1\n   10 I = I*MI\n      J = J*MJ\n      I = I - 1000*( I/1000 )\n      J = J - 1000*( J/1000 )\n      IF( IC.GE.5 )THEN\n         IC = 0\n         GO TO 10\n      END IF\n      ZBEG = DCMPLX( ( I - 500 )/1001.0D0, ( J - 500 )/1001.0D0 )\n      RETURN\n*\n*     End of ZBEG.\n*\n      END\n      DOUBLE PRECISION FUNCTION DDIFF( X, Y )\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   X, Y\n*     .. Executable Statements ..\n      DDIFF = X - Y\n      RETURN\n*\n*     End of DDIFF.\n*\n      END\n      SUBROUTINE CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n*  Tests whether XERBLA has detected an error when it should.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Executable Statements ..\n      IF( .NOT.LERR )THEN\n         WRITE( NOUT, FMT = 9999 )INFOT, SRNAMT\n         OK = .FALSE.\n      END IF\n      LERR = .FALSE.\n      RETURN\n*\n 9999 FORMAT( ' ***** ILLEGAL VALUE OF PARAMETER NUMBER ', I2, ' NOT D',\n     $      'ETECTED BY ', A6, ' *****' )\n*\n*     End of CHKXER.\n*\n      END\n      SUBROUTINE XERBLA( SRNAME, INFO )\n*\n*  This is a special version of XERBLA to be used only as part of\n*  the test program for testing error exits from the Level 2 BLAS\n*  routines.\n*\n*  XERBLA  is an error handler for the Level 2 BLAS routines.\n*\n*  It is called by the Level 2 BLAS routines if an input parameter is\n*  invalid.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFO\n      CHARACTER*6        SRNAME\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUT, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Executable Statements ..\n      LERR = .TRUE.\n      IF( INFO.NE.INFOT )THEN\n         IF( INFOT.NE.0 )THEN\n            WRITE( NOUT, FMT = 9999 )INFO, INFOT\n         ELSE\n            WRITE( NOUT, FMT = 9997 )INFO\n         END IF\n         OK = .FALSE.\n      END IF\n      IF( SRNAME.NE.SRNAMT )THEN\n         WRITE( NOUT, FMT = 9998 )SRNAME, SRNAMT\n         OK = .FALSE.\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6, ' INSTEAD',\n     $      ' OF ', I2, ' *******' )\n 9998 FORMAT( ' ******* XERBLA WAS CALLED WITH SRNAME = ', A6, ' INSTE',\n     $      'AD OF ', A6, ' *******' )\n 9997 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6,\n     $      ' *******' )\n*\n*     End of XERBLA\n*\n      END\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/testing/zblat3.f",
    "content": "*> \\brief \\b ZBLAT3\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM ZBLAT3\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> Test program for the COMPLEX*16       Level 3 Blas.\n*>\n*> The program must be driven by a short data file. The first 14 records\n*> of the file are read using list-directed input, the last 9 records\n*> are read using the format ( A6, L2 ). An annotated example of a data\n*> file can be obtained by deleting the first 3 characters from the\n*> following 23 lines:\n*> 'zblat3.out'      NAME OF SUMMARY OUTPUT FILE\n*> 6                 UNIT NUMBER OF SUMMARY FILE\n*> 'ZBLAT3.SNAP'     NAME OF SNAPSHOT OUTPUT FILE\n*> -1                UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0)\n*> F        LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD.\n*> F        LOGICAL FLAG, T TO STOP ON FAILURES.\n*> T        LOGICAL FLAG, T TO TEST ERROR EXITS.\n*> 16.0     THRESHOLD VALUE OF TEST RATIO\n*> 6                 NUMBER OF VALUES OF N\n*> 0 1 2 3 5 9       VALUES OF N\n*> 3                 NUMBER OF VALUES OF ALPHA\n*> (0.0,0.0) (1.0,0.0) (0.7,-0.9)       VALUES OF ALPHA\n*> 3                 NUMBER OF VALUES OF BETA\n*> (0.0,0.0) (1.0,0.0) (1.3,-1.1)       VALUES OF BETA\n*> ZGEMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZHEMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZSYMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZTRMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZTRSM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZHERK  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZSYRK  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZHER2K T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZSYR2K T PUT F FOR NO TEST. SAME COLUMNS.\n*>\n*> \n*> Further Details\n*> ===============\n*>\n*> See:\n*>\n*>    Dongarra J. J., Du Croz J. J., Duff I. S. and Hammarling S.\n*>    A Set of Level 3 Basic Linear Algebra Subprograms.\n*>\n*>    Technical Memorandum No.88 (Revision 1), Mathematics and\n*>    Computer Science Division, Argonne National Laboratory, 9700\n*>    South Cass Avenue, Argonne, Illinois 60439, US.\n*>\n*> -- Written on 8-February-1989.\n*>    Jack Dongarra, Argonne National Laboratory.\n*>    Iain Duff, AERE Harwell.\n*>    Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*>    Sven Hammarling, Numerical Algorithms Group Ltd.\n*>\n*>    10-9-00:  Change STATUS='NEW' to 'UNKNOWN' so that the testers\n*>              can be run multiple times without deleting generated\n*>              output files (susan)\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup complex16_blas_testing\n*\n*  =====================================================================\n      PROGRAM ZBLAT3\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER            NIN\n      PARAMETER          ( NIN = 5 )\n      INTEGER            NSUBS\n      PARAMETER          ( NSUBS = 9 )\n      COMPLEX*16         ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   ONE = ( 1.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n      INTEGER            NMAX\n      PARAMETER          ( NMAX = 65 )\n      INTEGER            NIDMAX, NALMAX, NBEMAX\n      PARAMETER          ( NIDMAX = 9, NALMAX = 7, NBEMAX = 7 )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   EPS, ERR, THRESH\n      INTEGER            I, ISNUM, J, N, NALF, NBET, NIDIM, NOUT, NTRA\n      LOGICAL            FATAL, LTESTT, REWI, SAME, SFATAL, TRACE,\n     $                   TSTERR\n      CHARACTER*1        TRANSA, TRANSB\n      CHARACTER*6        SNAMET\n      CHARACTER*32       SNAPS, SUMMRY\n*     .. Local Arrays ..\n      COMPLEX*16         AA( NMAX*NMAX ), AB( NMAX, 2*NMAX ),\n     $                   ALF( NALMAX ), AS( NMAX*NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBEMAX ),\n     $                   BS( NMAX*NMAX ), C( NMAX, NMAX ),\n     $                   CC( NMAX*NMAX ), CS( NMAX*NMAX ), CT( NMAX ),\n     $                   W( 2*NMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDMAX )\n      LOGICAL            LTEST( NSUBS )\n      CHARACTER*6        SNAMES( NSUBS )\n*     .. External Functions ..\n      DOUBLE PRECISION   DDIFF\n      LOGICAL            LZE\n      EXTERNAL           DDIFF, LZE\n*     .. External Subroutines ..\n      EXTERNAL           ZCHK1, ZCHK2, ZCHK3, ZCHK4, ZCHK5, ZCHKE, ZMMCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Data statements ..\n      DATA               SNAMES/'ZGEMM ', 'ZHEMM ', 'ZSYMM ', 'ZTRMM ',\n     $                   'ZTRSM ', 'ZHERK ', 'ZSYRK ', 'ZHER2K',\n     $                   'ZSYR2K'/\n*     .. Executable Statements ..\n*\n*     Read name and unit number for summary output file and open file.\n*\n      READ( NIN, FMT = * )SUMMRY\n      READ( NIN, FMT = * )NOUT\n      OPEN( NOUT, FILE = SUMMRY, STATUS = 'UNKNOWN' )\n      NOUTC = NOUT\n*\n*     Read name and unit number for snapshot output file and open file.\n*\n      READ( NIN, FMT = * )SNAPS\n      READ( NIN, FMT = * )NTRA\n      TRACE = NTRA.GE.0\n      IF( TRACE )THEN\n         OPEN( NTRA, FILE = SNAPS, STATUS = 'UNKNOWN' )\n      END IF\n*     Read the flag that directs rewinding of the snapshot file.\n      READ( NIN, FMT = * )REWI\n      REWI = REWI.AND.TRACE\n*     Read the flag that directs stopping on any failure.\n      READ( NIN, FMT = * )SFATAL\n*     Read the flag that indicates whether error exits are to be tested.\n      READ( NIN, FMT = * )TSTERR\n*     Read the threshold value of the test ratio\n      READ( NIN, FMT = * )THRESH\n*\n*     Read and check the parameter values for the tests.\n*\n*     Values of N\n      READ( NIN, FMT = * )NIDIM\n      IF( NIDIM.LT.1.OR.NIDIM.GT.NIDMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'N', NIDMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( IDIM( I ), I = 1, NIDIM )\n      DO 10 I = 1, NIDIM\n         IF( IDIM( I ).LT.0.OR.IDIM( I ).GT.NMAX )THEN\n            WRITE( NOUT, FMT = 9996 )NMAX\n            GO TO 220\n         END IF\n   10 CONTINUE\n*     Values of ALPHA\n      READ( NIN, FMT = * )NALF\n      IF( NALF.LT.1.OR.NALF.GT.NALMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'ALPHA', NALMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( ALF( I ), I = 1, NALF )\n*     Values of BETA\n      READ( NIN, FMT = * )NBET\n      IF( NBET.LT.1.OR.NBET.GT.NBEMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'BETA', NBEMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( BET( I ), I = 1, NBET )\n*\n*     Report values of parameters.\n*\n      WRITE( NOUT, FMT = 9995 )\n      WRITE( NOUT, FMT = 9994 )( IDIM( I ), I = 1, NIDIM )\n      WRITE( NOUT, FMT = 9993 )( ALF( I ), I = 1, NALF )\n      WRITE( NOUT, FMT = 9992 )( BET( I ), I = 1, NBET )\n      IF( .NOT.TSTERR )THEN\n         WRITE( NOUT, FMT = * )\n         WRITE( NOUT, FMT = 9984 )\n      END IF\n      WRITE( NOUT, FMT = * )\n      WRITE( NOUT, FMT = 9999 )THRESH\n      WRITE( NOUT, FMT = * )\n*\n*     Read names of subroutines and flags which indicate\n*     whether they are to be tested.\n*\n      DO 20 I = 1, NSUBS\n         LTEST( I ) = .FALSE.\n   20 CONTINUE\n   30 READ( NIN, FMT = 9988, END = 60 )SNAMET, LTESTT\n      DO 40 I = 1, NSUBS\n         IF( SNAMET.EQ.SNAMES( I ) )\n     $      GO TO 50\n   40 CONTINUE\n      WRITE( NOUT, FMT = 9990 )SNAMET\n      STOP\n   50 LTEST( I ) = LTESTT\n      GO TO 30\n*\n   60 CONTINUE\n      CLOSE ( NIN )\n*\n*     Compute EPS (the machine precision).\n*\n      EPS = EPSILON(RZERO)\n      WRITE( NOUT, FMT = 9998 )EPS\n*\n*     Check the reliability of ZMMCH using exact data.\n*\n      N = MIN( 32, NMAX )\n      DO 100 J = 1, N\n         DO 90 I = 1, N\n            AB( I, J ) = MAX( I - J + 1, 0 )\n   90    CONTINUE\n         AB( J, NMAX + 1 ) = J\n         AB( 1, NMAX + J ) = J\n         C( J, 1 ) = ZERO\n  100 CONTINUE\n      DO 110 J = 1, N\n         CC( J ) = J*( ( J + 1 )*J )/2 - ( ( J + 1 )*J*( J - 1 ) )/3\n  110 CONTINUE\n*     CC holds the exact result. On exit from ZMMCH CT holds\n*     the result computed by ZMMCH.\n      TRANSA = 'N'\n      TRANSB = 'N'\n      CALL ZMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LZE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      TRANSB = 'C'\n      CALL ZMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LZE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      DO 120 J = 1, N\n         AB( J, NMAX + 1 ) = N - J + 1\n         AB( 1, NMAX + J ) = N - J + 1\n  120 CONTINUE\n      DO 130 J = 1, N\n         CC( N - J + 1 ) = J*( ( J + 1 )*J )/2 -\n     $                     ( ( J + 1 )*J*( J - 1 ) )/3\n  130 CONTINUE\n      TRANSA = 'C'\n      TRANSB = 'N'\n      CALL ZMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LZE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      TRANSB = 'C'\n      CALL ZMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LZE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n*\n*     Test each subroutine in turn.\n*\n      DO 200 ISNUM = 1, NSUBS\n         WRITE( NOUT, FMT = * )\n         IF( .NOT.LTEST( ISNUM ) )THEN\n*           Subprogram is not to be tested.\n            WRITE( NOUT, FMT = 9987 )SNAMES( ISNUM )\n         ELSE\n            SRNAMT = SNAMES( ISNUM )\n*           Test error exits.\n            IF( TSTERR )THEN\n               CALL ZCHKE( ISNUM, SNAMES( ISNUM ), NOUT )\n               WRITE( NOUT, FMT = * )\n            END IF\n*           Test computations.\n            INFOT = 0\n            OK = .TRUE.\n            FATAL = .FALSE.\n            GO TO ( 140, 150, 150, 160, 160, 170, 170,\n     $              180, 180 )ISNUM\n*           Test ZGEMM, 01.\n  140       CALL ZCHK1( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test ZHEMM, 02, ZSYMM, 03.\n  150       CALL ZCHK2( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test ZTRMM, 04, ZTRSM, 05.\n  160       CALL ZCHK3( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NMAX, AB,\n     $                  AA, AS, AB( 1, NMAX + 1 ), BB, BS, CT, G, C )\n            GO TO 190\n*           Test ZHERK, 06, ZSYRK, 07.\n  170       CALL ZCHK4( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test ZHER2K, 08, ZSYR2K, 09.\n  180       CALL ZCHK5( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, BB, BS, C, CC, CS, CT, G, W )\n            GO TO 190\n*\n  190       IF( FATAL.AND.SFATAL )\n     $         GO TO 210\n         END IF\n  200 CONTINUE\n      WRITE( NOUT, FMT = 9986 )\n      GO TO 230\n*\n  210 CONTINUE\n      WRITE( NOUT, FMT = 9985 )\n      GO TO 230\n*\n  220 CONTINUE\n      WRITE( NOUT, FMT = 9991 )\n*\n  230 CONTINUE\n      IF( TRACE )\n     $   CLOSE ( NTRA )\n      CLOSE ( NOUT )\n      STOP\n*\n 9999 FORMAT( ' ROUTINES PASS COMPUTATIONAL TESTS IF TEST RATIO IS LES',\n     $      'S THAN', F8.2 )\n 9998 FORMAT( ' RELATIVE MACHINE PRECISION IS TAKEN TO BE', 1P, D9.1 )\n 9997 FORMAT( ' NUMBER OF VALUES OF ', A, ' IS LESS THAN 1 OR GREATER ',\n     $      'THAN ', I2 )\n 9996 FORMAT( ' VALUE OF N IS LESS THAN 0 OR GREATER THAN ', I2 )\n 9995 FORMAT( ' TESTS OF THE COMPLEX*16       LEVEL 3 BLAS', //' THE F',\n     $      'OLLOWING PARAMETER VALUES WILL BE USED:' )\n 9994 FORMAT( '   FOR N              ', 9I6 )\n 9993 FORMAT( '   FOR ALPHA          ',\n     $      7( '(', F4.1, ',', F4.1, ')  ', : ) )\n 9992 FORMAT( '   FOR BETA           ',\n     $      7( '(', F4.1, ',', F4.1, ')  ', : ) )\n 9991 FORMAT( ' AMEND DATA FILE OR INCREASE ARRAY SIZES IN PROGRAM',\n     $      /' ******* TESTS ABANDONED *******' )\n 9990 FORMAT( ' SUBPROGRAM NAME ', A6, ' NOT RECOGNIZED', /' ******* T',\n     $      'ESTS ABANDONED *******' )\n 9989 FORMAT( ' ERROR IN ZMMCH -  IN-LINE DOT PRODUCTS ARE BEING EVALU',\n     $      'ATED WRONGLY.', /' ZMMCH WAS CALLED WITH TRANSA = ', A1,\n     $      ' AND TRANSB = ', A1, /' AND RETURNED SAME = ', L1, ' AND ',\n     $      'ERR = ', F12.3, '.', /' THIS MAY BE DUE TO FAULTS IN THE ',\n     $      'ARITHMETIC OR THE COMPILER.', /' ******* TESTS ABANDONED ',\n     $      '*******' )\n 9988 FORMAT( A6, L2 )\n 9987 FORMAT( 1X, A6, ' WAS NOT TESTED' )\n 9986 FORMAT( /' END OF TESTS' )\n 9985 FORMAT( /' ******* FATAL ERROR - TESTS ABANDONED *******' )\n 9984 FORMAT( ' ERROR-EXITS WILL NOT BE TESTED' )\n*\n*     End of ZBLAT3.\n*\n      END\n      SUBROUTINE ZCHK1( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests ZGEMM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, ALS, BETA, BLS\n      DOUBLE PRECISION   ERR, ERRMAX\n      INTEGER            I, IA, IB, ICA, ICB, IK, IM, IN, K, KS, LAA,\n     $                   LBB, LCC, LDA, LDAS, LDB, LDBS, LDC, LDCS, M,\n     $                   MA, MB, MS, N, NA, NARGS, NB, NC, NS\n      LOGICAL            NULL, RESET, SAME, TRANA, TRANB\n      CHARACTER*1        TRANAS, TRANBS, TRANSA, TRANSB\n      CHARACTER*3        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZGEMM, ZMAKE, ZMMCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'NTC'/\n*     .. Executable Statements ..\n*\n      NARGS = 13\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 110 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 100 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDC to 1 more than minimum value if room.\n            LDC = M\n            IF( LDC.LT.NMAX )\n     $         LDC = LDC + 1\n*           Skip tests if not enough room.\n            IF( LDC.GT.NMAX )\n     $         GO TO 100\n            LCC = LDC*N\n            NULL = N.LE.0.OR.M.LE.0\n*\n            DO 90 IK = 1, NIDIM\n               K = IDIM( IK )\n*\n               DO 80 ICA = 1, 3\n                  TRANSA = ICH( ICA: ICA )\n                  TRANA = TRANSA.EQ.'T'.OR.TRANSA.EQ.'C'\n*\n                  IF( TRANA )THEN\n                     MA = K\n                     NA = M\n                  ELSE\n                     MA = M\n                     NA = K\n                  END IF\n*                 Set LDA to 1 more than minimum value if room.\n                  LDA = MA\n                  IF( LDA.LT.NMAX )\n     $               LDA = LDA + 1\n*                 Skip tests if not enough room.\n                  IF( LDA.GT.NMAX )\n     $               GO TO 80\n                  LAA = LDA*NA\n*\n*                 Generate the matrix A.\n*\n                  CALL ZMAKE( 'GE', ' ', ' ', MA, NA, A, NMAX, AA, LDA,\n     $                        RESET, ZERO )\n*\n                  DO 70 ICB = 1, 3\n                     TRANSB = ICH( ICB: ICB )\n                     TRANB = TRANSB.EQ.'T'.OR.TRANSB.EQ.'C'\n*\n                     IF( TRANB )THEN\n                        MB = N\n                        NB = K\n                     ELSE\n                        MB = K\n                        NB = N\n                     END IF\n*                    Set LDB to 1 more than minimum value if room.\n                     LDB = MB\n                     IF( LDB.LT.NMAX )\n     $                  LDB = LDB + 1\n*                    Skip tests if not enough room.\n                     IF( LDB.GT.NMAX )\n     $                  GO TO 70\n                     LBB = LDB*NB\n*\n*                    Generate the matrix B.\n*\n                     CALL ZMAKE( 'GE', ' ', ' ', MB, NB, B, NMAX, BB,\n     $                           LDB, RESET, ZERO )\n*\n                     DO 60 IA = 1, NALF\n                        ALPHA = ALF( IA )\n*\n                        DO 50 IB = 1, NBET\n                           BETA = BET( IB )\n*\n*                          Generate the matrix C.\n*\n                           CALL ZMAKE( 'GE', ' ', ' ', M, N, C, NMAX,\n     $                                 CC, LDC, RESET, ZERO )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           TRANAS = TRANSA\n                           TRANBS = TRANSB\n                           MS = M\n                           NS = N\n                           KS = K\n                           ALS = ALPHA\n                           DO 10 I = 1, LAA\n                              AS( I ) = AA( I )\n   10                      CONTINUE\n                           LDAS = LDA\n                           DO 20 I = 1, LBB\n                              BS( I ) = BB( I )\n   20                      CONTINUE\n                           LDBS = LDB\n                           BLS = BETA\n                           DO 30 I = 1, LCC\n                              CS( I ) = CC( I )\n   30                      CONTINUE\n                           LDCS = LDC\n*\n*                          Call the subroutine.\n*\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                        TRANSA, TRANSB, M, N, K, ALPHA, LDA, LDB,\n     $                        BETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL ZGEMM( TRANSA, TRANSB, M, N, K, ALPHA,\n     $                                 AA, LDA, BB, LDB, BETA, CC, LDC )\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9994 )\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = TRANSA.EQ.TRANAS\n                           ISAME( 2 ) = TRANSB.EQ.TRANBS\n                           ISAME( 3 ) = MS.EQ.M\n                           ISAME( 4 ) = NS.EQ.N\n                           ISAME( 5 ) = KS.EQ.K\n                           ISAME( 6 ) = ALS.EQ.ALPHA\n                           ISAME( 7 ) = LZE( AS, AA, LAA )\n                           ISAME( 8 ) = LDAS.EQ.LDA\n                           ISAME( 9 ) = LZE( BS, BB, LBB )\n                           ISAME( 10 ) = LDBS.EQ.LDB\n                           ISAME( 11 ) = BLS.EQ.BETA\n                           IF( NULL )THEN\n                              ISAME( 12 ) = LZE( CS, CC, LCC )\n                           ELSE\n                              ISAME( 12 ) = LZERES( 'GE', ' ', M, N, CS,\n     $                                      CC, LDC )\n                           END IF\n                           ISAME( 13 ) = LDCS.EQ.LDC\n*\n*                          If data was incorrectly changed, report\n*                          and return.\n*\n                           SAME = .TRUE.\n                           DO 40 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   40                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n*\n*                             Check the result.\n*\n                              CALL ZMMCH( TRANSA, TRANSB, M, N, K,\n     $                                    ALPHA, A, NMAX, B, NMAX, BETA,\n     $                                    C, NMAX, CT, G, CC, LDC, EPS,\n     $                                    ERR, FATAL, NOUT, .TRUE. )\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 120\n                           END IF\n*\n   50                   CONTINUE\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, TRANSA, TRANSB, M, N, K,\n     $   ALPHA, LDA, LDB, BETA, LDC\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',''', A1, ''',',\n     $      3( I3, ',' ), '(', F4.1, ',', F4.1, '), A,', I3, ', B,', I3,\n     $      ',(', F4.1, ',', F4.1, '), C,', I3, ').' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK1.\n*\n      END\n      SUBROUTINE ZCHK2( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests ZHEMM and ZSYMM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, ALS, BETA, BLS\n      DOUBLE PRECISION   ERR, ERRMAX\n      INTEGER            I, IA, IB, ICS, ICU, IM, IN, LAA, LBB, LCC,\n     $                   LDA, LDAS, LDB, LDBS, LDC, LDCS, M, MS, N, NA,\n     $                   NARGS, NC, NS\n      LOGICAL            CONJ, LEFT, NULL, RESET, SAME\n      CHARACTER*1        SIDE, SIDES, UPLO, UPLOS\n      CHARACTER*2        ICHS, ICHU\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZHEMM, ZMAKE, ZMMCH, ZSYMM\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHS/'LR'/, ICHU/'UL'/\n*     .. Executable Statements ..\n      CONJ = SNAME( 2: 3 ).EQ.'HE'\n*\n      NARGS = 12\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 100 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 90 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDC to 1 more than minimum value if room.\n            LDC = M\n            IF( LDC.LT.NMAX )\n     $         LDC = LDC + 1\n*           Skip tests if not enough room.\n            IF( LDC.GT.NMAX )\n     $         GO TO 90\n            LCC = LDC*N\n            NULL = N.LE.0.OR.M.LE.0\n*           Set LDB to 1 more than minimum value if room.\n            LDB = M\n            IF( LDB.LT.NMAX )\n     $         LDB = LDB + 1\n*           Skip tests if not enough room.\n            IF( LDB.GT.NMAX )\n     $         GO TO 90\n            LBB = LDB*N\n*\n*           Generate the matrix B.\n*\n            CALL ZMAKE( 'GE', ' ', ' ', M, N, B, NMAX, BB, LDB, RESET,\n     $                  ZERO )\n*\n            DO 80 ICS = 1, 2\n               SIDE = ICHS( ICS: ICS )\n               LEFT = SIDE.EQ.'L'\n*\n               IF( LEFT )THEN\n                  NA = M\n               ELSE\n                  NA = N\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = NA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 80\n               LAA = LDA*NA\n*\n               DO 70 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n*\n*                 Generate the hermitian or symmetric matrix A.\n*\n                  CALL ZMAKE( SNAME( 2: 3 ), UPLO, ' ', NA, NA, A, NMAX,\n     $                        AA, LDA, RESET, ZERO )\n*\n                  DO 60 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n                     DO 50 IB = 1, NBET\n                        BETA = BET( IB )\n*\n*                       Generate the matrix C.\n*\n                        CALL ZMAKE( 'GE', ' ', ' ', M, N, C, NMAX, CC,\n     $                              LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the\n*                       subroutine.\n*\n                        SIDES = SIDE\n                        UPLOS = UPLO\n                        MS = M\n                        NS = N\n                        ALS = ALPHA\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        DO 20 I = 1, LBB\n                           BS( I ) = BB( I )\n   20                   CONTINUE\n                        LDBS = LDB\n                        BLS = BETA\n                        DO 30 I = 1, LCC\n                           CS( I ) = CC( I )\n   30                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9995 )NC, SNAME, SIDE,\n     $                     UPLO, M, N, ALPHA, LDA, LDB, BETA, LDC\n                        IF( REWI )\n     $                     REWIND NTRA\n                        IF( CONJ )THEN\n                           CALL ZHEMM( SIDE, UPLO, M, N, ALPHA, AA, LDA,\n     $                                 BB, LDB, BETA, CC, LDC )\n                        ELSE\n                           CALL ZSYMM( SIDE, UPLO, M, N, ALPHA, AA, LDA,\n     $                                 BB, LDB, BETA, CC, LDC )\n                        END IF\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9994 )\n                           FATAL = .TRUE.\n                           GO TO 110\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = SIDES.EQ.SIDE\n                        ISAME( 2 ) = UPLOS.EQ.UPLO\n                        ISAME( 3 ) = MS.EQ.M\n                        ISAME( 4 ) = NS.EQ.N\n                        ISAME( 5 ) = ALS.EQ.ALPHA\n                        ISAME( 6 ) = LZE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        ISAME( 8 ) = LZE( BS, BB, LBB )\n                        ISAME( 9 ) = LDBS.EQ.LDB\n                        ISAME( 10 ) = BLS.EQ.BETA\n                        IF( NULL )THEN\n                           ISAME( 11 ) = LZE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 11 ) = LZERES( 'GE', ' ', M, N, CS,\n     $                                   CC, LDC )\n                        END IF\n                        ISAME( 12 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 110\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result.\n*\n                           IF( LEFT )THEN\n                              CALL ZMMCH( 'N', 'N', M, N, M, ALPHA, A,\n     $                                    NMAX, B, NMAX, BETA, C, NMAX,\n     $                                    CT, G, CC, LDC, EPS, ERR,\n     $                                    FATAL, NOUT, .TRUE. )\n                           ELSE\n                              CALL ZMMCH( 'N', 'N', M, N, N, ALPHA, B,\n     $                                    NMAX, A, NMAX, BETA, C, NMAX,\n     $                                    CT, G, CC, LDC, EPS, ERR,\n     $                                    FATAL, NOUT, .TRUE. )\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and\n*                          return.\n                           IF( FATAL )\n     $                        GO TO 110\n                        END IF\n*\n   50                CONTINUE\n*\n   60             CONTINUE\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 120\n*\n  110 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, SIDE, UPLO, M, N, ALPHA, LDA,\n     $   LDB, BETA, LDC\n*\n  120 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      '(', F4.1, ',', F4.1, '), A,', I3, ', B,', I3, ',(', F4.1,\n     $      ',', F4.1, '), C,', I3, ')    .' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK2.\n*\n      END\n      SUBROUTINE ZCHK3( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NMAX, A, AA, AS,\n     $                  B, BB, BS, CT, G, C )\n*\n*  Tests ZTRMM and ZTRSM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   ONE = ( 1.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            NALF, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CT( NMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, ALS\n      DOUBLE PRECISION   ERR, ERRMAX\n      INTEGER            I, IA, ICD, ICS, ICT, ICU, IM, IN, J, LAA, LBB,\n     $                   LDA, LDAS, LDB, LDBS, M, MS, N, NA, NARGS, NC,\n     $                   NS\n      LOGICAL            LEFT, NULL, RESET, SAME\n      CHARACTER*1        DIAG, DIAGS, SIDE, SIDES, TRANAS, TRANSA, UPLO,\n     $                   UPLOS\n      CHARACTER*2        ICHD, ICHS, ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZMAKE, ZMMCH, ZTRMM, ZTRSM\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHU/'UL'/, ICHT/'NTC'/, ICHD/'UN'/, ICHS/'LR'/\n*     .. Executable Statements ..\n*\n      NARGS = 11\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*     Set up zero matrix for ZMMCH.\n      DO 20 J = 1, NMAX\n         DO 10 I = 1, NMAX\n            C( I, J ) = ZERO\n   10    CONTINUE\n   20 CONTINUE\n*\n      DO 140 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 130 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDB to 1 more than minimum value if room.\n            LDB = M\n            IF( LDB.LT.NMAX )\n     $         LDB = LDB + 1\n*           Skip tests if not enough room.\n            IF( LDB.GT.NMAX )\n     $         GO TO 130\n            LBB = LDB*N\n            NULL = M.LE.0.OR.N.LE.0\n*\n            DO 120 ICS = 1, 2\n               SIDE = ICHS( ICS: ICS )\n               LEFT = SIDE.EQ.'L'\n               IF( LEFT )THEN\n                  NA = M\n               ELSE\n                  NA = N\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = NA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 130\n               LAA = LDA*NA\n*\n               DO 110 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n*\n                  DO 100 ICT = 1, 3\n                     TRANSA = ICHT( ICT: ICT )\n*\n                     DO 90 ICD = 1, 2\n                        DIAG = ICHD( ICD: ICD )\n*\n                        DO 80 IA = 1, NALF\n                           ALPHA = ALF( IA )\n*\n*                          Generate the matrix A.\n*\n                           CALL ZMAKE( 'TR', UPLO, DIAG, NA, NA, A,\n     $                                 NMAX, AA, LDA, RESET, ZERO )\n*\n*                          Generate the matrix B.\n*\n                           CALL ZMAKE( 'GE', ' ', ' ', M, N, B, NMAX,\n     $                                 BB, LDB, RESET, ZERO )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           SIDES = SIDE\n                           UPLOS = UPLO\n                           TRANAS = TRANSA\n                           DIAGS = DIAG\n                           MS = M\n                           NS = N\n                           ALS = ALPHA\n                           DO 30 I = 1, LAA\n                              AS( I ) = AA( I )\n   30                      CONTINUE\n                           LDAS = LDA\n                           DO 40 I = 1, LBB\n                              BS( I ) = BB( I )\n   40                      CONTINUE\n                           LDBS = LDB\n*\n*                          Call the subroutine.\n*\n                           IF( SNAME( 4: 5 ).EQ.'MM' )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           SIDE, UPLO, TRANSA, DIAG, M, N, ALPHA,\n     $                           LDA, LDB\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZTRMM( SIDE, UPLO, TRANSA, DIAG, M,\n     $                                    N, ALPHA, AA, LDA, BB, LDB )\n                           ELSE IF( SNAME( 4: 5 ).EQ.'SM' )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           SIDE, UPLO, TRANSA, DIAG, M, N, ALPHA,\n     $                           LDA, LDB\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZTRSM( SIDE, UPLO, TRANSA, DIAG, M,\n     $                                    N, ALPHA, AA, LDA, BB, LDB )\n                           END IF\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9994 )\n                              FATAL = .TRUE.\n                              GO TO 150\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = SIDES.EQ.SIDE\n                           ISAME( 2 ) = UPLOS.EQ.UPLO\n                           ISAME( 3 ) = TRANAS.EQ.TRANSA\n                           ISAME( 4 ) = DIAGS.EQ.DIAG\n                           ISAME( 5 ) = MS.EQ.M\n                           ISAME( 6 ) = NS.EQ.N\n                           ISAME( 7 ) = ALS.EQ.ALPHA\n                           ISAME( 8 ) = LZE( AS, AA, LAA )\n                           ISAME( 9 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 10 ) = LZE( BS, BB, LBB )\n                           ELSE\n                              ISAME( 10 ) = LZERES( 'GE', ' ', M, N, BS,\n     $                                      BB, LDB )\n                           END IF\n                           ISAME( 11 ) = LDBS.EQ.LDB\n*\n*                          If data was incorrectly changed, report and\n*                          return.\n*\n                           SAME = .TRUE.\n                           DO 50 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   50                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 150\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n                              IF( SNAME( 4: 5 ).EQ.'MM' )THEN\n*\n*                                Check the result.\n*\n                                 IF( LEFT )THEN\n                                    CALL ZMMCH( TRANSA, 'N', M, N, M,\n     $                                          ALPHA, A, NMAX, B, NMAX,\n     $                                          ZERO, C, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .TRUE. )\n                                 ELSE\n                                    CALL ZMMCH( 'N', TRANSA, M, N, N,\n     $                                          ALPHA, B, NMAX, A, NMAX,\n     $                                          ZERO, C, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .TRUE. )\n                                 END IF\n                              ELSE IF( SNAME( 4: 5 ).EQ.'SM' )THEN\n*\n*                                Compute approximation to original\n*                                matrix.\n*\n                                 DO 70 J = 1, N\n                                    DO 60 I = 1, M\n                                       C( I, J ) = BB( I + ( J - 1 )*\n     $                                             LDB )\n                                       BB( I + ( J - 1 )*LDB ) = ALPHA*\n     $                                    B( I, J )\n   60                               CONTINUE\n   70                            CONTINUE\n*\n                                 IF( LEFT )THEN\n                                    CALL ZMMCH( TRANSA, 'N', M, N, M,\n     $                                          ONE, A, NMAX, C, NMAX,\n     $                                          ZERO, B, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .FALSE. )\n                                 ELSE\n                                    CALL ZMMCH( 'N', TRANSA, M, N, N,\n     $                                          ONE, C, NMAX, A, NMAX,\n     $                                          ZERO, B, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .FALSE. )\n                                 END IF\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 150\n                           END IF\n*\n   80                   CONTINUE\n*\n   90                CONTINUE\n*\n  100             CONTINUE\n*\n  110          CONTINUE\n*\n  120       CONTINUE\n*\n  130    CONTINUE\n*\n  140 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 160\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, SIDE, UPLO, TRANSA, DIAG, M,\n     $   N, ALPHA, LDA, LDB\n*\n  160 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 4( '''', A1, ''',' ), 2( I3, ',' ),\n     $      '(', F4.1, ',', F4.1, '), A,', I3, ', B,', I3, ')         ',\n     $      '      .' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK3.\n*\n      END\n      SUBROUTINE ZCHK4( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests ZHERK and ZSYRK.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RONE, RZERO\n      PARAMETER          ( RONE = 1.0D0, RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, ALS, BETA, BETS\n      DOUBLE PRECISION   ERR, ERRMAX, RALPHA, RALS, RBETA, RBETS\n      INTEGER            I, IA, IB, ICT, ICU, IK, IN, J, JC, JJ, K, KS,\n     $                   LAA, LCC, LDA, LDAS, LDC, LDCS, LJ, MA, N, NA,\n     $                   NARGS, NC, NS\n      LOGICAL            CONJ, NULL, RESET, SAME, TRAN, UPPER\n      CHARACTER*1        TRANS, TRANSS, TRANST, UPLO, UPLOS\n      CHARACTER*2        ICHT, ICHU\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZHERK, ZMAKE, ZMMCH, ZSYRK\n*     .. Intrinsic Functions ..\n      INTRINSIC          DCMPLX, MAX, DBLE\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHT/'NC'/, ICHU/'UL'/\n*     .. Executable Statements ..\n      CONJ = SNAME( 2: 3 ).EQ.'HE'\n*\n      NARGS = 10\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 100 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDC to 1 more than minimum value if room.\n         LDC = N\n         IF( LDC.LT.NMAX )\n     $      LDC = LDC + 1\n*        Skip tests if not enough room.\n         IF( LDC.GT.NMAX )\n     $      GO TO 100\n         LCC = LDC*N\n*\n         DO 90 IK = 1, NIDIM\n            K = IDIM( IK )\n*\n            DO 80 ICT = 1, 2\n               TRANS = ICHT( ICT: ICT )\n               TRAN = TRANS.EQ.'C'\n               IF( TRAN.AND..NOT.CONJ )\n     $            TRANS = 'T'\n               IF( TRAN )THEN\n                  MA = K\n                  NA = N\n               ELSE\n                  MA = N\n                  NA = K\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = MA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 80\n               LAA = LDA*NA\n*\n*              Generate the matrix A.\n*\n               CALL ZMAKE( 'GE', ' ', ' ', MA, NA, A, NMAX, AA, LDA,\n     $                     RESET, ZERO )\n*\n               DO 70 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n                  UPPER = UPLO.EQ.'U'\n*\n                  DO 60 IA = 1, NALF\n                     ALPHA = ALF( IA )\n                     IF( CONJ )THEN\n                        RALPHA = DBLE( ALPHA )\n                        ALPHA = DCMPLX( RALPHA, RZERO )\n                     END IF\n*\n                     DO 50 IB = 1, NBET\n                        BETA = BET( IB )\n                        IF( CONJ )THEN\n                           RBETA = DBLE( BETA )\n                           BETA = DCMPLX( RBETA, RZERO )\n                        END IF\n                        NULL = N.LE.0\n                        IF( CONJ )\n     $                     NULL = NULL.OR.( ( K.LE.0.OR.RALPHA.EQ.\n     $                            RZERO ).AND.RBETA.EQ.RONE )\n*\n*                       Generate the matrix C.\n*\n                        CALL ZMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, C,\n     $                              NMAX, CC, LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        NS = N\n                        KS = K\n                        IF( CONJ )THEN\n                           RALS = RALPHA\n                        ELSE\n                           ALS = ALPHA\n                        END IF\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        IF( CONJ )THEN\n                           RBETS = RBETA\n                        ELSE\n                           BETS = BETA\n                        END IF\n                        DO 20 I = 1, LCC\n                           CS( I ) = CC( I )\n   20                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( CONJ )THEN\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO,\n     $                        TRANS, N, K, RALPHA, LDA, RBETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL ZHERK( UPLO, TRANS, N, K, RALPHA, AA,\n     $                                 LDA, RBETA, CC, LDC )\n                        ELSE\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO,\n     $                        TRANS, N, K, ALPHA, LDA, BETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL ZSYRK( UPLO, TRANS, N, K, ALPHA, AA,\n     $                                 LDA, BETA, CC, LDC )\n                        END IF\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9992 )\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLOS.EQ.UPLO\n                        ISAME( 2 ) = TRANSS.EQ.TRANS\n                        ISAME( 3 ) = NS.EQ.N\n                        ISAME( 4 ) = KS.EQ.K\n                        IF( CONJ )THEN\n                           ISAME( 5 ) = RALS.EQ.RALPHA\n                        ELSE\n                           ISAME( 5 ) = ALS.EQ.ALPHA\n                        END IF\n                        ISAME( 6 ) = LZE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        IF( CONJ )THEN\n                           ISAME( 8 ) = RBETS.EQ.RBETA\n                        ELSE\n                           ISAME( 8 ) = BETS.EQ.BETA\n                        END IF\n                        IF( NULL )THEN\n                           ISAME( 9 ) = LZE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 9 ) = LZERES( SNAME( 2: 3 ), UPLO, N,\n     $                                  N, CS, CC, LDC )\n                        END IF\n                        ISAME( 10 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 30 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   30                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result column by column.\n*\n                           IF( CONJ )THEN\n                              TRANST = 'C'\n                           ELSE\n                              TRANST = 'T'\n                           END IF\n                           JC = 1\n                           DO 40 J = 1, N\n                              IF( UPPER )THEN\n                                 JJ = 1\n                                 LJ = J\n                              ELSE\n                                 JJ = J\n                                 LJ = N - J + 1\n                              END IF\n                              IF( TRAN )THEN\n                                 CALL ZMMCH( TRANST, 'N', LJ, 1, K,\n     $                                       ALPHA, A( 1, JJ ), NMAX,\n     $                                       A( 1, J ), NMAX, BETA,\n     $                                       C( JJ, J ), NMAX, CT, G,\n     $                                       CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              ELSE\n                                 CALL ZMMCH( 'N', TRANST, LJ, 1, K,\n     $                                       ALPHA, A( JJ, 1 ), NMAX,\n     $                                       A( J, 1 ), NMAX, BETA,\n     $                                       C( JJ, J ), NMAX, CT, G,\n     $                                       CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              END IF\n                              IF( UPPER )THEN\n                                 JC = JC + LDC\n                              ELSE\n                                 JC = JC + LDC + 1\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 110\n   40                      CONTINUE\n                        END IF\n*\n   50                CONTINUE\n*\n   60             CONTINUE\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  110 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9995 )J\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( CONJ )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, N, K, RALPHA,\n     $      LDA, RBETA, LDC\n      ELSE\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, TRANS, N, K, ALPHA,\n     $      LDA, BETA, LDC\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      F4.1, ', A,', I3, ',', F4.1, ', C,', I3, ')               ',\n     $      '          .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      '(', F4.1, ',', F4.1, ') , A,', I3, ',(', F4.1, ',', F4.1,\n     $      '), C,', I3, ')          .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK4.\n*\n      END\n      SUBROUTINE ZCHK5( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  AB, AA, AS, BB, BS, C, CC, CS, CT, G, W )\n*\n*  Tests ZHER2K and ZSYR2K.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   ONE = ( 1.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RONE, RZERO\n      PARAMETER          ( RONE = 1.0D0, RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         AA( NMAX*NMAX ), AB( 2*NMAX*NMAX ),\n     $                   ALF( NALF ), AS( NMAX*NMAX ), BB( NMAX*NMAX ),\n     $                   BET( NBET ), BS( NMAX*NMAX ), C( NMAX, NMAX ),\n     $                   CC( NMAX*NMAX ), CS( NMAX*NMAX ), CT( NMAX ),\n     $                   W( 2*NMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, ALS, BETA, BETS\n      DOUBLE PRECISION   ERR, ERRMAX, RBETA, RBETS\n      INTEGER            I, IA, IB, ICT, ICU, IK, IN, J, JC, JJ, JJAB,\n     $                   K, KS, LAA, LBB, LCC, LDA, LDAS, LDB, LDBS,\n     $                   LDC, LDCS, LJ, MA, N, NA, NARGS, NC, NS\n      LOGICAL            CONJ, NULL, RESET, SAME, TRAN, UPPER\n      CHARACTER*1        TRANS, TRANSS, TRANST, UPLO, UPLOS\n      CHARACTER*2        ICHT, ICHU\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZHER2K, ZMAKE, ZMMCH, ZSYR2K\n*     .. Intrinsic Functions ..\n      INTRINSIC          DCMPLX, DCONJG, MAX, DBLE\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHT/'NC'/, ICHU/'UL'/\n*     .. Executable Statements ..\n      CONJ = SNAME( 2: 3 ).EQ.'HE'\n*\n      NARGS = 12\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 130 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDC to 1 more than minimum value if room.\n         LDC = N\n         IF( LDC.LT.NMAX )\n     $      LDC = LDC + 1\n*        Skip tests if not enough room.\n         IF( LDC.GT.NMAX )\n     $      GO TO 130\n         LCC = LDC*N\n*\n         DO 120 IK = 1, NIDIM\n            K = IDIM( IK )\n*\n            DO 110 ICT = 1, 2\n               TRANS = ICHT( ICT: ICT )\n               TRAN = TRANS.EQ.'C'\n               IF( TRAN.AND..NOT.CONJ )\n     $            TRANS = 'T'\n               IF( TRAN )THEN\n                  MA = K\n                  NA = N\n               ELSE\n                  MA = N\n                  NA = K\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = MA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 110\n               LAA = LDA*NA\n*\n*              Generate the matrix A.\n*\n               IF( TRAN )THEN\n                  CALL ZMAKE( 'GE', ' ', ' ', MA, NA, AB, 2*NMAX, AA,\n     $                        LDA, RESET, ZERO )\n               ELSE\n                  CALL ZMAKE( 'GE', ' ', ' ', MA, NA, AB, NMAX, AA, LDA,\n     $                        RESET, ZERO )\n               END IF\n*\n*              Generate the matrix B.\n*\n               LDB = LDA\n               LBB = LAA\n               IF( TRAN )THEN\n                  CALL ZMAKE( 'GE', ' ', ' ', MA, NA, AB( K + 1 ),\n     $                        2*NMAX, BB, LDB, RESET, ZERO )\n               ELSE\n                  CALL ZMAKE( 'GE', ' ', ' ', MA, NA, AB( K*NMAX + 1 ),\n     $                        NMAX, BB, LDB, RESET, ZERO )\n               END IF\n*\n               DO 100 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n                  UPPER = UPLO.EQ.'U'\n*\n                  DO 90 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n                     DO 80 IB = 1, NBET\n                        BETA = BET( IB )\n                        IF( CONJ )THEN\n                           RBETA = DBLE( BETA )\n                           BETA = DCMPLX( RBETA, RZERO )\n                        END IF\n                        NULL = N.LE.0\n                        IF( CONJ )\n     $                     NULL = NULL.OR.( ( K.LE.0.OR.ALPHA.EQ.\n     $                            ZERO ).AND.RBETA.EQ.RONE )\n*\n*                       Generate the matrix C.\n*\n                        CALL ZMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, C,\n     $                              NMAX, CC, LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        NS = N\n                        KS = K\n                        ALS = ALPHA\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        DO 20 I = 1, LBB\n                           BS( I ) = BB( I )\n   20                   CONTINUE\n                        LDBS = LDB\n                        IF( CONJ )THEN\n                           RBETS = RBETA\n                        ELSE\n                           BETS = BETA\n                        END IF\n                        DO 30 I = 1, LCC\n                           CS( I ) = CC( I )\n   30                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( CONJ )THEN\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO,\n     $                        TRANS, N, K, ALPHA, LDA, LDB, RBETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL ZHER2K( UPLO, TRANS, N, K, ALPHA, AA,\n     $                                  LDA, BB, LDB, RBETA, CC, LDC )\n                        ELSE\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO,\n     $                        TRANS, N, K, ALPHA, LDA, LDB, BETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL ZSYR2K( UPLO, TRANS, N, K, ALPHA, AA,\n     $                                  LDA, BB, LDB, BETA, CC, LDC )\n                        END IF\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9992 )\n                           FATAL = .TRUE.\n                           GO TO 150\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLOS.EQ.UPLO\n                        ISAME( 2 ) = TRANSS.EQ.TRANS\n                        ISAME( 3 ) = NS.EQ.N\n                        ISAME( 4 ) = KS.EQ.K\n                        ISAME( 5 ) = ALS.EQ.ALPHA\n                        ISAME( 6 ) = LZE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        ISAME( 8 ) = LZE( BS, BB, LBB )\n                        ISAME( 9 ) = LDBS.EQ.LDB\n                        IF( CONJ )THEN\n                           ISAME( 10 ) = RBETS.EQ.RBETA\n                        ELSE\n                           ISAME( 10 ) = BETS.EQ.BETA\n                        END IF\n                        IF( NULL )THEN\n                           ISAME( 11 ) = LZE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 11 ) = LZERES( 'HE', UPLO, N, N, CS,\n     $                                   CC, LDC )\n                        END IF\n                        ISAME( 12 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 150\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result column by column.\n*\n                           IF( CONJ )THEN\n                              TRANST = 'C'\n                           ELSE\n                              TRANST = 'T'\n                           END IF\n                           JJAB = 1\n                           JC = 1\n                           DO 70 J = 1, N\n                              IF( UPPER )THEN\n                                 JJ = 1\n                                 LJ = J\n                              ELSE\n                                 JJ = J\n                                 LJ = N - J + 1\n                              END IF\n                              IF( TRAN )THEN\n                                 DO 50 I = 1, K\n                                    W( I ) = ALPHA*AB( ( J - 1 )*2*\n     $                                       NMAX + K + I )\n                                    IF( CONJ )THEN\n                                       W( K + I ) = DCONJG( ALPHA )*\n     $                                              AB( ( J - 1 )*2*\n     $                                              NMAX + I )\n                                    ELSE\n                                       W( K + I ) = ALPHA*\n     $                                              AB( ( J - 1 )*2*\n     $                                              NMAX + I )\n                                    END IF\n   50                            CONTINUE\n                                 CALL ZMMCH( TRANST, 'N', LJ, 1, 2*K,\n     $                                       ONE, AB( JJAB ), 2*NMAX, W,\n     $                                       2*NMAX, BETA, C( JJ, J ),\n     $                                       NMAX, CT, G, CC( JC ), LDC,\n     $                                       EPS, ERR, FATAL, NOUT,\n     $                                       .TRUE. )\n                              ELSE\n                                 DO 60 I = 1, K\n                                    IF( CONJ )THEN\n                                       W( I ) = ALPHA*DCONJG( AB( ( K +\n     $                                          I - 1 )*NMAX + J ) )\n                                       W( K + I ) = DCONJG( ALPHA*\n     $                                              AB( ( I - 1 )*NMAX +\n     $                                              J ) )\n                                    ELSE\n                                       W( I ) = ALPHA*AB( ( K + I - 1 )*\n     $                                          NMAX + J )\n                                       W( K + I ) = ALPHA*\n     $                                              AB( ( I - 1 )*NMAX +\n     $                                              J )\n                                    END IF\n   60                            CONTINUE\n                                 CALL ZMMCH( 'N', 'N', LJ, 1, 2*K, ONE,\n     $                                       AB( JJ ), NMAX, W, 2*NMAX,\n     $                                       BETA, C( JJ, J ), NMAX, CT,\n     $                                       G, CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              END IF\n                              IF( UPPER )THEN\n                                 JC = JC + LDC\n                              ELSE\n                                 JC = JC + LDC + 1\n                                 IF( TRAN )\n     $                              JJAB = JJAB + 2*NMAX\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 140\n   70                      CONTINUE\n                        END IF\n*\n   80                CONTINUE\n*\n   90             CONTINUE\n*\n  100          CONTINUE\n*\n  110       CONTINUE\n*\n  120    CONTINUE\n*\n  130 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 160\n*\n  140 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9995 )J\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( CONJ )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, N, K, ALPHA,\n     $      LDA, LDB, RBETA, LDC\n      ELSE\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, TRANS, N, K, ALPHA,\n     $      LDA, LDB, BETA, LDC\n      END IF\n*\n  160 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      '(', F4.1, ',', F4.1, '), A,', I3, ', B,', I3, ',', F4.1,\n     $      ', C,', I3, ')           .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      '(', F4.1, ',', F4.1, '), A,', I3, ', B,', I3, ',(', F4.1,\n     $      ',', F4.1, '), C,', I3, ')    .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK5.\n*\n      END\n      SUBROUTINE ZCHKE( ISNUM, SRNAMT, NOUT )\n*\n*  Tests the error exits from the Level 3 Blas.\n*  Requires a special version of the error-handling routine XERBLA.\n*  A, B and C should not need to be defined.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*  3-19-92:  Initialize ALPHA, BETA, RALPHA, and RBETA  (eca)\n*  3-19-92:  Fix argument 12 in calls to ZSYMM and ZHEMM\n*            with INFOT = 9  (eca)\n*  10-9-00:  Declared INTRINSIC DCMPLX (susan)\n*\n*     .. Scalar Arguments ..\n      INTEGER            ISNUM, NOUT\n      CHARACTER*6        SRNAMT\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Parameters ..\n      REAL               ONE, TWO\n      PARAMETER          ( ONE = 1.0D0, TWO = 2.0D0 )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, BETA\n      DOUBLE PRECISION   RALPHA, RBETA\n*     .. Local Arrays ..\n      COMPLEX*16         A( 2, 1 ), B( 2, 1 ), C( 2, 1 )\n*     .. External Subroutines ..\n      EXTERNAL           ZGEMM, ZHEMM, ZHER2K, ZHERK, CHKXER, ZSYMM,\n     $                   ZSYR2K, ZSYRK, ZTRMM, ZTRSM\n*     .. Intrinsic Functions ..\n      INTRINSIC          DCMPLX\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n*     OK is set to .FALSE. by the special version of XERBLA or by CHKXER\n*     if anything is wrong.\n      OK = .TRUE.\n*     LERR is set to .TRUE. by the special version of XERBLA each time\n*     it is called, and is then tested and re-set by CHKXER.\n      LERR = .FALSE.\n*\n*     Initialize ALPHA, BETA, RALPHA, and RBETA.\n*\n      ALPHA = DCMPLX( ONE, -ONE )\n      BETA = DCMPLX( TWO, -TWO )\n      RALPHA = ONE\n      RBETA = TWO\n*\n      GO TO ( 10, 20, 30, 40, 50, 60, 70, 80,\n     $        90 )ISNUM\n   10 INFOT = 1\n      CALL ZGEMM( '/', 'N', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 1\n      CALL ZGEMM( '/', 'C', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 1\n      CALL ZGEMM( '/', 'T', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZGEMM( 'N', '/', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZGEMM( 'C', '/', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZGEMM( 'T', '/', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGEMM( 'N', 'N', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGEMM( 'N', 'C', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGEMM( 'N', 'T', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGEMM( 'C', 'N', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGEMM( 'C', 'C', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGEMM( 'C', 'T', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGEMM( 'T', 'N', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGEMM( 'T', 'C', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGEMM( 'T', 'T', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZGEMM( 'N', 'N', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZGEMM( 'N', 'C', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZGEMM( 'N', 'T', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZGEMM( 'C', 'N', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZGEMM( 'C', 'C', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZGEMM( 'C', 'T', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZGEMM( 'T', 'N', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZGEMM( 'T', 'C', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZGEMM( 'T', 'T', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGEMM( 'N', 'N', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGEMM( 'N', 'C', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGEMM( 'N', 'T', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGEMM( 'C', 'N', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGEMM( 'C', 'C', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGEMM( 'C', 'T', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGEMM( 'T', 'N', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGEMM( 'T', 'C', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGEMM( 'T', 'T', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGEMM( 'N', 'N', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGEMM( 'N', 'C', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGEMM( 'N', 'T', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGEMM( 'C', 'N', 0, 0, 2, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGEMM( 'C', 'C', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGEMM( 'C', 'T', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGEMM( 'T', 'N', 0, 0, 2, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGEMM( 'T', 'C', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGEMM( 'T', 'T', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZGEMM( 'N', 'N', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZGEMM( 'C', 'N', 0, 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZGEMM( 'T', 'N', 0, 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZGEMM( 'N', 'C', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZGEMM( 'C', 'C', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZGEMM( 'T', 'C', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZGEMM( 'N', 'T', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZGEMM( 'C', 'T', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZGEMM( 'T', 'T', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL ZGEMM( 'N', 'N', 2, 0, 0, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL ZGEMM( 'N', 'C', 2, 0, 0, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL ZGEMM( 'N', 'T', 2, 0, 0, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL ZGEMM( 'C', 'N', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL ZGEMM( 'C', 'C', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL ZGEMM( 'C', 'T', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL ZGEMM( 'T', 'N', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL ZGEMM( 'T', 'C', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL ZGEMM( 'T', 'T', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   20 INFOT = 1\n      CALL ZHEMM( '/', 'U', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZHEMM( 'L', '/', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHEMM( 'L', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHEMM( 'R', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHEMM( 'L', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHEMM( 'R', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHEMM( 'L', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHEMM( 'R', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHEMM( 'L', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHEMM( 'R', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHEMM( 'L', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHEMM( 'R', 'U', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHEMM( 'L', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHEMM( 'R', 'L', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZHEMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZHEMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZHEMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZHEMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZHEMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZHEMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZHEMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZHEMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   30 INFOT = 1\n      CALL ZSYMM( '/', 'U', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZSYMM( 'L', '/', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYMM( 'L', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYMM( 'R', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYMM( 'L', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYMM( 'R', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYMM( 'L', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYMM( 'R', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYMM( 'L', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYMM( 'R', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYMM( 'L', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYMM( 'R', 'U', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYMM( 'L', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYMM( 'R', 'L', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   40 INFOT = 1\n      CALL ZTRMM( '/', 'U', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZTRMM( 'L', '/', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZTRMM( 'L', 'U', '/', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZTRMM( 'L', 'U', 'N', '/', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'L', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'L', 'U', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'L', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'R', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'R', 'U', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'R', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'L', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'L', 'L', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'L', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'R', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'R', 'L', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'R', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'L', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'L', 'U', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'L', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'R', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'R', 'U', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'R', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'L', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'L', 'L', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'L', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'R', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'R', 'L', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'R', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'L', 'U', 'C', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'R', 'U', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'R', 'U', 'C', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'R', 'U', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'L', 'L', 'C', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'R', 'L', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'R', 'L', 'C', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'R', 'L', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'L', 'U', 'C', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'R', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'R', 'U', 'C', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'R', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'L', 'L', 'C', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'R', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'R', 'L', 'C', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'R', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   50 INFOT = 1\n      CALL ZTRSM( '/', 'U', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZTRSM( 'L', '/', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZTRSM( 'L', 'U', '/', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZTRSM( 'L', 'U', 'N', '/', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'L', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'L', 'U', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'L', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'R', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'R', 'U', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'R', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'L', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'L', 'L', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'L', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'R', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'R', 'L', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'R', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'L', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'L', 'U', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'L', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'R', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'R', 'U', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'R', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'L', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'L', 'L', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'L', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'R', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'R', 'L', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'R', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'L', 'U', 'C', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'R', 'U', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'R', 'U', 'C', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'R', 'U', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'L', 'L', 'C', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'R', 'L', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'R', 'L', 'C', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'R', 'L', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'L', 'U', 'C', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'R', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'R', 'U', 'C', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'R', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'L', 'L', 'C', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'R', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'R', 'L', 'C', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'R', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   60 INFOT = 1\n      CALL ZHERK( '/', 'N', 0, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZHERK( 'U', 'T', 0, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHERK( 'U', 'N', -1, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHERK( 'U', 'C', -1, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHERK( 'L', 'N', -1, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHERK( 'L', 'C', -1, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHERK( 'U', 'N', 0, -1, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHERK( 'U', 'C', 0, -1, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHERK( 'L', 'N', 0, -1, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHERK( 'L', 'C', 0, -1, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHERK( 'U', 'N', 2, 0, RALPHA, A, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHERK( 'U', 'C', 0, 2, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHERK( 'L', 'N', 2, 0, RALPHA, A, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHERK( 'L', 'C', 0, 2, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZHERK( 'U', 'N', 2, 0, RALPHA, A, 2, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZHERK( 'U', 'C', 2, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZHERK( 'L', 'N', 2, 0, RALPHA, A, 2, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZHERK( 'L', 'C', 2, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   70 INFOT = 1\n      CALL ZSYRK( '/', 'N', 0, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZSYRK( 'U', 'C', 0, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYRK( 'U', 'N', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYRK( 'U', 'T', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYRK( 'L', 'N', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYRK( 'L', 'T', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYRK( 'U', 'N', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYRK( 'U', 'T', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYRK( 'L', 'N', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYRK( 'L', 'T', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYRK( 'U', 'N', 2, 0, ALPHA, A, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYRK( 'U', 'T', 0, 2, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYRK( 'L', 'N', 2, 0, ALPHA, A, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYRK( 'L', 'T', 0, 2, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZSYRK( 'U', 'N', 2, 0, ALPHA, A, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZSYRK( 'U', 'T', 2, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZSYRK( 'L', 'N', 2, 0, ALPHA, A, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZSYRK( 'L', 'T', 2, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   80 INFOT = 1\n      CALL ZHER2K( '/', 'N', 0, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZHER2K( 'U', 'T', 0, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHER2K( 'U', 'N', -1, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHER2K( 'U', 'C', -1, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHER2K( 'L', 'N', -1, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHER2K( 'L', 'C', -1, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHER2K( 'U', 'N', 0, -1, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHER2K( 'U', 'C', 0, -1, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHER2K( 'L', 'N', 0, -1, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHER2K( 'L', 'C', 0, -1, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHER2K( 'U', 'N', 2, 0, ALPHA, A, 1, B, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHER2K( 'U', 'C', 0, 2, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHER2K( 'L', 'N', 2, 0, ALPHA, A, 1, B, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHER2K( 'L', 'C', 0, 2, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZHER2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZHER2K( 'U', 'C', 0, 2, ALPHA, A, 2, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZHER2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZHER2K( 'L', 'C', 0, 2, ALPHA, A, 2, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZHER2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 2, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZHER2K( 'U', 'C', 2, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZHER2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 2, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZHER2K( 'L', 'C', 2, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   90 INFOT = 1\n      CALL ZSYR2K( '/', 'N', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZSYR2K( 'U', 'C', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYR2K( 'U', 'N', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYR2K( 'U', 'T', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYR2K( 'L', 'N', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYR2K( 'L', 'T', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYR2K( 'U', 'N', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYR2K( 'U', 'T', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYR2K( 'L', 'N', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYR2K( 'L', 'T', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYR2K( 'U', 'N', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYR2K( 'U', 'T', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYR2K( 'L', 'N', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYR2K( 'L', 'T', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZSYR2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZSYR2K( 'U', 'T', 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZSYR2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZSYR2K( 'L', 'T', 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZSYR2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZSYR2K( 'U', 'T', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZSYR2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZSYR2K( 'L', 'T', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n  100 IF( OK )THEN\n         WRITE( NOUT, FMT = 9999 )SRNAMT\n      ELSE\n         WRITE( NOUT, FMT = 9998 )SRNAMT\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE TESTS OF ERROR-EXITS' )\n 9998 FORMAT( ' ******* ', A6, ' FAILED THE TESTS OF ERROR-EXITS *****',\n     $      '**' )\n*\n*     End of ZCHKE.\n*\n      END\n      SUBROUTINE ZMAKE( TYPE, UPLO, DIAG, M, N, A, NMAX, AA, LDA, RESET,\n     $                  TRANSL )\n*\n*  Generates values for an M by N matrix A.\n*  Stores the values in the array AA in the data structure required\n*  by the routine, with unwanted elements set to rogue value.\n*\n*  TYPE is 'GE', 'HE', 'SY' or 'TR'.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   ONE = ( 1.0D0, 0.0D0 ) )\n      COMPLEX*16         ROGUE\n      PARAMETER          ( ROGUE = ( -1.0D10, 1.0D10 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n      DOUBLE PRECISION   RROGUE\n      PARAMETER          ( RROGUE = -1.0D10 )\n*     .. Scalar Arguments ..\n      COMPLEX*16         TRANSL\n      INTEGER            LDA, M, N, NMAX\n      LOGICAL            RESET\n      CHARACTER*1        DIAG, UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, * ), AA( * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J, JJ\n      LOGICAL            GEN, HER, LOWER, SYM, TRI, UNIT, UPPER\n*     .. External Functions ..\n      COMPLEX*16         ZBEG\n      EXTERNAL           ZBEG\n*     .. Intrinsic Functions ..\n      INTRINSIC          DCMPLX, DCONJG, DBLE\n*     .. Executable Statements ..\n      GEN = TYPE.EQ.'GE'\n      HER = TYPE.EQ.'HE'\n      SYM = TYPE.EQ.'SY'\n      TRI = TYPE.EQ.'TR'\n      UPPER = ( HER.OR.SYM.OR.TRI ).AND.UPLO.EQ.'U'\n      LOWER = ( HER.OR.SYM.OR.TRI ).AND.UPLO.EQ.'L'\n      UNIT = TRI.AND.DIAG.EQ.'U'\n*\n*     Generate data in array A.\n*\n      DO 20 J = 1, N\n         DO 10 I = 1, M\n            IF( GEN.OR.( UPPER.AND.I.LE.J ).OR.( LOWER.AND.I.GE.J ) )\n     $          THEN\n               A( I, J ) = ZBEG( RESET ) + TRANSL\n               IF( I.NE.J )THEN\n*                 Set some elements to zero\n                  IF( N.GT.3.AND.J.EQ.N/2 )\n     $               A( I, J ) = ZERO\n                  IF( HER )THEN\n                     A( J, I ) = DCONJG( A( I, J ) )\n                  ELSE IF( SYM )THEN\n                     A( J, I ) = A( I, J )\n                  ELSE IF( TRI )THEN\n                     A( J, I ) = ZERO\n                  END IF\n               END IF\n            END IF\n   10    CONTINUE\n         IF( HER )\n     $      A( J, J ) = DCMPLX( DBLE( A( J, J ) ), RZERO )\n         IF( TRI )\n     $      A( J, J ) = A( J, J ) + ONE\n         IF( UNIT )\n     $      A( J, J ) = ONE\n   20 CONTINUE\n*\n*     Store elements in array AS in data structure required by routine.\n*\n      IF( TYPE.EQ.'GE' )THEN\n         DO 50 J = 1, N\n            DO 30 I = 1, M\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   30       CONTINUE\n            DO 40 I = M + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   40       CONTINUE\n   50    CONTINUE\n      ELSE IF( TYPE.EQ.'HE'.OR.TYPE.EQ.'SY'.OR.TYPE.EQ.'TR' )THEN\n         DO 90 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IF( UNIT )THEN\n                  IEND = J - 1\n               ELSE\n                  IEND = J\n               END IF\n            ELSE\n               IF( UNIT )THEN\n                  IBEG = J + 1\n               ELSE\n                  IBEG = J\n               END IF\n               IEND = N\n            END IF\n            DO 60 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   60       CONTINUE\n            DO 70 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   70       CONTINUE\n            DO 80 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   80       CONTINUE\n            IF( HER )THEN\n               JJ = J + ( J - 1 )*LDA\n               AA( JJ ) = DCMPLX( DBLE( AA( JJ ) ), RROGUE )\n            END IF\n   90    CONTINUE\n      END IF\n      RETURN\n*\n*     End of ZMAKE.\n*\n      END\n      SUBROUTINE ZMMCH( TRANSA, TRANSB, M, N, KK, ALPHA, A, LDA, B, LDB,\n     $                  BETA, C, LDC, CT, G, CC, LDCC, EPS, ERR, FATAL,\n     $                  NOUT, MV )\n*\n*  Checks the results of the computational tests.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO, RONE\n      PARAMETER          ( RZERO = 0.0D0, RONE = 1.0D0 )\n*     .. Scalar Arguments ..\n      COMPLEX*16         ALPHA, BETA\n      DOUBLE PRECISION   EPS, ERR\n      INTEGER            KK, LDA, LDB, LDC, LDCC, M, N, NOUT\n      LOGICAL            FATAL, MV\n      CHARACTER*1        TRANSA, TRANSB\n*     .. Array Arguments ..\n      COMPLEX*16         A( LDA, * ), B( LDB, * ), C( LDC, * ),\n     $                   CC( LDCC, * ), CT( * )\n      DOUBLE PRECISION   G( * )\n*     .. Local Scalars ..\n      COMPLEX*16         CL\n      DOUBLE PRECISION   ERRI\n      INTEGER            I, J, K\n      LOGICAL            CTRANA, CTRANB, TRANA, TRANB\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, DIMAG, DCONJG, MAX, DBLE, SQRT\n*     .. Statement Functions ..\n      DOUBLE PRECISION   ABS1\n*     .. Statement Function definitions ..\n      ABS1( CL ) = ABS( DBLE( CL ) ) + ABS( DIMAG( CL ) )\n*     .. Executable Statements ..\n      TRANA = TRANSA.EQ.'T'.OR.TRANSA.EQ.'C'\n      TRANB = TRANSB.EQ.'T'.OR.TRANSB.EQ.'C'\n      CTRANA = TRANSA.EQ.'C'\n      CTRANB = TRANSB.EQ.'C'\n*\n*     Compute expected result, one column at a time, in CT using data\n*     in A, B and C.\n*     Compute gauges in G.\n*\n      DO 220 J = 1, N\n*\n         DO 10 I = 1, M\n            CT( I ) = ZERO\n            G( I ) = RZERO\n   10    CONTINUE\n         IF( .NOT.TRANA.AND..NOT.TRANB )THEN\n            DO 30 K = 1, KK\n               DO 20 I = 1, M\n                  CT( I ) = CT( I ) + A( I, K )*B( K, J )\n                  G( I ) = G( I ) + ABS1( A( I, K ) )*ABS1( B( K, J ) )\n   20          CONTINUE\n   30       CONTINUE\n         ELSE IF( TRANA.AND..NOT.TRANB )THEN\n            IF( CTRANA )THEN\n               DO 50 K = 1, KK\n                  DO 40 I = 1, M\n                     CT( I ) = CT( I ) + DCONJG( A( K, I ) )*B( K, J )\n                     G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                        ABS1( B( K, J ) )\n   40             CONTINUE\n   50          CONTINUE\n            ELSE\n               DO 70 K = 1, KK\n                  DO 60 I = 1, M\n                     CT( I ) = CT( I ) + A( K, I )*B( K, J )\n                     G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                        ABS1( B( K, J ) )\n   60             CONTINUE\n   70          CONTINUE\n            END IF\n         ELSE IF( .NOT.TRANA.AND.TRANB )THEN\n            IF( CTRANB )THEN\n               DO 90 K = 1, KK\n                  DO 80 I = 1, M\n                     CT( I ) = CT( I ) + A( I, K )*DCONJG( B( J, K ) )\n                     G( I ) = G( I ) + ABS1( A( I, K ) )*\n     $                        ABS1( B( J, K ) )\n   80             CONTINUE\n   90          CONTINUE\n            ELSE\n               DO 110 K = 1, KK\n                  DO 100 I = 1, M\n                     CT( I ) = CT( I ) + A( I, K )*B( J, K )\n                     G( I ) = G( I ) + ABS1( A( I, K ) )*\n     $                        ABS1( B( J, K ) )\n  100             CONTINUE\n  110          CONTINUE\n            END IF\n         ELSE IF( TRANA.AND.TRANB )THEN\n            IF( CTRANA )THEN\n               IF( CTRANB )THEN\n                  DO 130 K = 1, KK\n                     DO 120 I = 1, M\n                        CT( I ) = CT( I ) + DCONJG( A( K, I ) )*\n     $                            DCONJG( B( J, K ) )\n                        G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                           ABS1( B( J, K ) )\n  120                CONTINUE\n  130             CONTINUE\n               ELSE\n                  DO 150 K = 1, KK\n                     DO 140 I = 1, M\n                        CT( I ) = CT( I ) + DCONJG( A( K, I ) )*\n     $                            B( J, K )\n                        G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                           ABS1( B( J, K ) )\n  140                CONTINUE\n  150             CONTINUE\n               END IF\n            ELSE\n               IF( CTRANB )THEN\n                  DO 170 K = 1, KK\n                     DO 160 I = 1, M\n                        CT( I ) = CT( I ) + A( K, I )*\n     $                            DCONJG( B( J, K ) )\n                        G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                           ABS1( B( J, K ) )\n  160                CONTINUE\n  170             CONTINUE\n               ELSE\n                  DO 190 K = 1, KK\n                     DO 180 I = 1, M\n                        CT( I ) = CT( I ) + A( K, I )*B( J, K )\n                        G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                           ABS1( B( J, K ) )\n  180                CONTINUE\n  190             CONTINUE\n               END IF\n            END IF\n         END IF\n         DO 200 I = 1, M\n            CT( I ) = ALPHA*CT( I ) + BETA*C( I, J )\n            G( I ) = ABS1( ALPHA )*G( I ) +\n     $               ABS1( BETA )*ABS1( C( I, J ) )\n  200    CONTINUE\n*\n*        Compute the error ratio for this result.\n*\n         ERR = ZERO\n         DO 210 I = 1, M\n            ERRI = ABS1( CT( I ) - CC( I, J ) )/EPS\n            IF( G( I ).NE.RZERO )\n     $         ERRI = ERRI/G( I )\n            ERR = MAX( ERR, ERRI )\n            IF( ERR*SQRT( EPS ).GE.RONE )\n     $         GO TO 230\n  210    CONTINUE\n*\n  220 CONTINUE\n*\n*     If the loop completes, all results are at least half accurate.\n      GO TO 250\n*\n*     Report fatal error.\n*\n  230 FATAL = .TRUE.\n      WRITE( NOUT, FMT = 9999 )\n      DO 240 I = 1, M\n         IF( MV )THEN\n            WRITE( NOUT, FMT = 9998 )I, CT( I ), CC( I, J )\n         ELSE\n            WRITE( NOUT, FMT = 9998 )I, CC( I, J ), CT( I )\n         END IF\n  240 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9997 )J\n*\n  250 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ******* FATAL ERROR - COMPUTED RESULT IS LESS THAN HAL',\n     $      'F ACCURATE *******', /'                       EXPECTED RE',\n     $      'SULT                    COMPUTED RESULT' )\n 9998 FORMAT( 1X, I7, 2( '  (', G15.6, ',', G15.6, ')' ) )\n 9997 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n*\n*     End of ZMMCH.\n*\n      END\n      LOGICAL FUNCTION LZE( RI, RJ, LR )\n*\n*  Tests if two arrays are identical.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LR\n*     .. Array Arguments ..\n      COMPLEX*16         RI( * ), RJ( * )\n*     .. Local Scalars ..\n      INTEGER            I\n*     .. Executable Statements ..\n      DO 10 I = 1, LR\n         IF( RI( I ).NE.RJ( I ) )\n     $      GO TO 20\n   10 CONTINUE\n      LZE = .TRUE.\n      GO TO 30\n   20 CONTINUE\n      LZE = .FALSE.\n   30 RETURN\n*\n*     End of LZE.\n*\n      END\n      LOGICAL FUNCTION LZERES( TYPE, UPLO, M, N, AA, AS, LDA )\n*\n*  Tests if selected elements in two arrays are equal.\n*\n*  TYPE is 'GE' or 'HE' or 'SY'.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LDA, M, N\n      CHARACTER*1        UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      COMPLEX*16         AA( LDA, * ), AS( LDA, * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J\n      LOGICAL            UPPER\n*     .. Executable Statements ..\n      UPPER = UPLO.EQ.'U'\n      IF( TYPE.EQ.'GE' )THEN\n         DO 20 J = 1, N\n            DO 10 I = M + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   10       CONTINUE\n   20    CONTINUE\n      ELSE IF( TYPE.EQ.'HE'.OR.TYPE.EQ.'SY' )THEN\n         DO 50 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 30 I = 1, IBEG - 1\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   30       CONTINUE\n            DO 40 I = IEND + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   40       CONTINUE\n   50    CONTINUE\n      END IF\n*\n      LZERES = .TRUE.\n      GO TO 80\n   70 CONTINUE\n      LZERES = .FALSE.\n   80 RETURN\n*\n*     End of LZERES.\n*\n      END\n      COMPLEX*16     FUNCTION ZBEG( RESET )\n*\n*  Generates complex numbers as pairs of random numbers uniformly\n*  distributed between -0.5 and 0.5.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      LOGICAL            RESET\n*     .. Local Scalars ..\n      INTEGER            I, IC, J, MI, MJ\n*     .. Save statement ..\n      SAVE               I, IC, J, MI, MJ\n*     .. Intrinsic Functions ..\n      INTRINSIC          DCMPLX\n*     .. Executable Statements ..\n      IF( RESET )THEN\n*        Initialize local variables.\n         MI = 891\n         MJ = 457\n         I = 7\n         J = 7\n         IC = 0\n         RESET = .FALSE.\n      END IF\n*\n*     The sequence of values of I or J is bounded between 1 and 999.\n*     If initial I or J = 1,2,3,6,7 or 9, the period will be 50.\n*     If initial I or J = 4 or 8, the period will be 25.\n*     If initial I or J = 5, the period will be 10.\n*     IC is used to break up the period by skipping 1 value of I or J\n*     in 6.\n*\n      IC = IC + 1\n   10 I = I*MI\n      J = J*MJ\n      I = I - 1000*( I/1000 )\n      J = J - 1000*( J/1000 )\n      IF( IC.GE.5 )THEN\n         IC = 0\n         GO TO 10\n      END IF\n      ZBEG = DCMPLX( ( I - 500 )/1001.0D0, ( J - 500 )/1001.0D0 )\n      RETURN\n*\n*     End of ZBEG.\n*\n      END\n      DOUBLE PRECISION FUNCTION DDIFF( X, Y )\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   X, Y\n*     .. Executable Statements ..\n      DDIFF = X - Y\n      RETURN\n*\n*     End of DDIFF.\n*\n      END\n      SUBROUTINE CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n*  Tests whether XERBLA has detected an error when it should.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Executable Statements ..\n      IF( .NOT.LERR )THEN\n         WRITE( NOUT, FMT = 9999 )INFOT, SRNAMT\n         OK = .FALSE.\n      END IF\n      LERR = .FALSE.\n      RETURN\n*\n 9999 FORMAT( ' ***** ILLEGAL VALUE OF PARAMETER NUMBER ', I2, ' NOT D',\n     $      'ETECTED BY ', A6, ' *****' )\n*\n*     End of CHKXER.\n*\n      END\n      SUBROUTINE XERBLA( SRNAME, INFO )\n*\n*  This is a special version of XERBLA to be used only as part of\n*  the test program for testing error exits from the Level 3 BLAS\n*  routines.\n*\n*  XERBLA  is an error handler for the Level 3 BLAS routines.\n*\n*  It is called by the Level 3 BLAS routines if an input parameter is\n*  invalid.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFO\n      CHARACTER*6        SRNAME\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUT, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Executable Statements ..\n      LERR = .TRUE.\n      IF( INFO.NE.INFOT )THEN\n         IF( INFOT.NE.0 )THEN\n            WRITE( NOUT, FMT = 9999 )INFO, INFOT\n         ELSE\n            WRITE( NOUT, FMT = 9997 )INFO\n         END IF\n         OK = .FALSE.\n      END IF\n      IF( SRNAME.NE.SRNAMT )THEN\n         WRITE( NOUT, FMT = 9998 )SRNAME, SRNAMT\n         OK = .FALSE.\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6, ' INSTEAD',\n     $      ' OF ', I2, ' *******' )\n 9998 FORMAT( ' ******* XERBLA WAS CALLED WITH SRNAME = ', A6, ' INSTE',\n     $      'AD OF ', A6, ' *******' )\n 9997 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6,\n     $      ' *******' )\n*\n*     End of XERBLA\n*\n      END\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/blas/xerbla.cpp",
    "content": "\n#include <stdio.h>\n\n#if (defined __GNUC__) && (!defined __MINGW32__) && (!defined __CYGWIN__)\n#define EIGEN_WEAK_LINKING __attribute__ ((weak))\n#else\n#define EIGEN_WEAK_LINKING\n#endif\n\n#ifdef __cplusplus\nextern \"C\"\n{\n#endif\n\nEIGEN_WEAK_LINKING int xerbla_(const char * msg, int *info, int)\n{\n  printf(\"Eigen BLAS ERROR #%i: %s\\n\", *info, msg );\n  return 0;\n}\n\n#ifdef __cplusplus\n}\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/ci/CTest2JUnit.xsl",
    "content": "<xsl:stylesheet xmlns:xsl=\"http://www.w3.org/1999/XSL/Transform\" version=\"1.0\">\n<xsl:output method=\"xml\" indent=\"yes\"/>\n    <xsl:template match=\"/Site\">\n\t<xsl:variable name=\"Name\"><xsl:value-of select=\"@Name\"/></xsl:variable>\n\t<xsl:variable name=\"Hostname\"><xsl:value-of select=\"@Hostname\"/></xsl:variable>\n\t<xsl:variable name=\"TestCount\"><xsl:value-of select=\"count(//TestList/Test)\"/> </xsl:variable>\n\t<xsl:variable name=\"ErrorCount\"><xsl:value-of select=\"count(//TestList/Test[@Status='error'])\"/> </xsl:variable>\n\t<xsl:variable name=\"FailureCount\"><xsl:value-of select=\"count(//Testing/Test[@Status='failed'])\"/> </xsl:variable>\n\t<testsuite name=\"{$Name}\" hostname=\"{$Hostname}\" errors=\"0\" failures=\"{$FailureCount}\" tests=\"{$TestCount}\">\n\t    <xsl:variable name=\"BuildName\"><xsl:value-of select=\"@BuildName\"/></xsl:variable>\n\t    <xsl:variable name=\"BuildStamp\"><xsl:value-of select=\"@BuildStamp\"/></xsl:variable>\n\t    <xsl:variable name=\"Generator\"><xsl:value-of select=\"@Generator\"/></xsl:variable>\n\t    <xsl:variable name=\"CompilerName\"><xsl:value-of select=\"@CompilerName\"/></xsl:variable>\n\t    <xsl:variable name=\"OSName\"><xsl:value-of select=\"@OSName\"/></xsl:variable>\n\t    <xsl:variable name=\"OSRelease\"><xsl:value-of select=\"@OSRelease\"/></xsl:variable>\n\t    <xsl:variable name=\"OSVersion\"><xsl:value-of select=\"@OSVersion\"/></xsl:variable>\n\t    <xsl:variable name=\"OSPlatform\"><xsl:value-of select=\"@OSPlatform\"/></xsl:variable>\n\t    <xsl:variable name=\"Is64Bits\"><xsl:value-of select=\"@Is64Bits\"/></xsl:variable>\n\t    <xsl:variable name=\"VendorString\"><xsl:value-of select=\"@VendorString\"/></xsl:variable>\n\t    <xsl:variable name=\"VendorID\"><xsl:value-of select=\"@VendorID\"/></xsl:variable>\n\t    <xsl:variable name=\"FamilyID\"><xsl:value-of select=\"@FamilyID\"/></xsl:variable>\n\t    <xsl:variable name=\"ModelID\"><xsl:value-of select=\"@ModelID\"/></xsl:variable>\n\t    <xsl:variable name=\"ProcessorCacheSize\"><xsl:value-of select=\"@ProcessorCacheSize\"/></xsl:variable>\n\t    <xsl:variable name=\"NumberOfLogicalCPU\"><xsl:value-of select=\"@NumberOfLogicalCPU\"/></xsl:variable>\n\t    <xsl:variable name=\"NumberOfPhysicalCPU\"><xsl:value-of select=\"@NumberOfPhysicalCPU\"/></xsl:variable>\n\t    <xsl:variable name=\"TotalVirtualMemory\"><xsl:value-of select=\"@TotalVirtualMemory\"/></xsl:variable>\n\t    <xsl:variable name=\"TotalPhysicalMemory\"><xsl:value-of select=\"@TotalPhysicalMemory\"/></xsl:variable>\n\t    <xsl:variable name=\"LogicalProcessorsPerPhysical\"><xsl:value-of select=\"@LogicalProcessorsPerPhysical\"/></xsl:variable>\n\t    <xsl:variable name=\"ProcessorClockFrequency\"><xsl:value-of select=\"@ProcessorClockFrequency\"/></xsl:variable>\n\t    <properties>\n\t\t<property name=\"BuildName\" value=\"{$BuildName}\" />\n\t\t<property name=\"BuildStamp\" value=\"{$BuildStamp}\" />\n\t\t<property name=\"Name\" value=\"{$Name}\" />\n\t\t<property name=\"Generator\" value=\"{$Generator}\" />\n\t\t<property name=\"CompilerName\" value=\"{$CompilerName}\" />\n\t\t<property name=\"OSName\" value=\"{$OSName}\" />\n\t\t<property name=\"Hostname\" value=\"{$Hostname}\" />\n\t\t<property name=\"OSRelease\" value=\"{$OSRelease}\" />\n\t\t<property name=\"OSVersion\" value=\"{$OSVersion}\" />\n\t\t<property name=\"OSPlatform\" value=\"{$OSPlatform}\" />\n\t\t<property name=\"Is64Bits\" value=\"{$Is64Bits}\" />\n\t\t<property name=\"VendorString\" value=\"{$VendorString}\" />\n\t\t<property name=\"VendorID\" value=\"{$VendorID}\" />\n\t\t<property name=\"FamilyID\" value=\"{$FamilyID}\" />\n\t\t<property name=\"ModelID\" value=\"{$ModelID}\" />\n\t\t<property name=\"ProcessorCacheSize\" value=\"{$ProcessorCacheSize}\" />\n\t\t<property name=\"NumberOfLogicalCPU\" value=\"{$NumberOfLogicalCPU}\" />\n\t\t<property name=\"NumberOfPhysicalCPU\" value=\"{$NumberOfPhysicalCPU}\" />\n\t\t<property name=\"TotalVirtualMemory\" value=\"{$TotalVirtualMemory}\" />\n\t\t<property name=\"TotalPhysicalMemory\" value=\"{$TotalPhysicalMemory}\" />\n\t\t<property name=\"LogicalProcessorsPerPhysical\" value=\"{$LogicalProcessorsPerPhysical}\" />\n\t\t<property name=\"ProcessorClockFrequency\" value=\"{$ProcessorClockFrequency}\" />\n\t    </properties>\n\t    <xsl:apply-templates select=\"Testing/Test\"/>\n\n\t    <system-out>\n\t\tBuildName: <xsl:value-of select=\"$BuildName\" />\n\t\tBuildStamp: <xsl:value-of select=\"$BuildStamp\" />\n\t\tName: <xsl:value-of select=\"$Name\" />\n\t\tGenerator: <xsl:value-of select=\"$Generator\" />\n\t\tCompilerName: <xsl:value-of select=\"$CompilerName\" />\n\t\tOSName: <xsl:value-of select=\"$OSName\" />\n\t\tHostname: <xsl:value-of select=\"$Hostname\" />\n\t\tOSRelease: <xsl:value-of select=\"$OSRelease\" />\n\t\tOSVersion: <xsl:value-of select=\"$OSVersion\" />\n\t\tOSPlatform: <xsl:value-of select=\"$OSPlatform\" />\n\t\tIs64Bits: <xsl:value-of select=\"$Is64Bits\" />\n\t\tVendorString: <xsl:value-of select=\"$VendorString\" />\n\t\tVendorID: <xsl:value-of select=\"$VendorID\" />\n\t\tFamilyID: <xsl:value-of select=\"$FamilyID\" />\n\t\tModelID: <xsl:value-of select=\"$ModelID\" />\n\t\tProcessorCacheSize: <xsl:value-of select=\"$ProcessorCacheSize\" />\n\t\tNumberOfLogicalCPU: <xsl:value-of select=\"$NumberOfLogicalCPU\" />\n\t\tNumberOfPhysicalCPU: <xsl:value-of select=\"$NumberOfPhysicalCPU\" />\n\t\tTotalVirtualMemory: <xsl:value-of select=\"$TotalVirtualMemory\" />\n\t\tTotalPhysicalMemory: <xsl:value-of select=\"$TotalPhysicalMemory\" />\n\t\tLogicalProcessorsPerPhysical: <xsl:value-of select=\"$LogicalProcessorsPerPhysical\" />\n\t\tProcessorClockFrequency: <xsl:value-of select=\"$ProcessorClockFrequency\" />\n\t    </system-out>\n\t</testsuite>\n    </xsl:template>\n\n    <xsl:template match=\"Testing/Test\">\n\t<xsl:variable name=\"testcasename\"><xsl:value-of select= \"Name\"/></xsl:variable>\n\t<xsl:variable name=\"testclassname\"><xsl:value-of select= \" concat('this', substring(Path,2))\"/></xsl:variable>\n\t<xsl:variable name=\"exectime\">\n\t    <xsl:for-each select=\"Results/NamedMeasurement\">\n\t\t<xsl:if test=\"@name = 'Execution Time'\">\n\t\t    <xsl:value-of select=\".\"/>\n\t\t</xsl:if>\n\t    </xsl:for-each>\n\t</xsl:variable>\n\n\t<testcase name=\"{$testcasename}\" classname=\"{$testclassname}\" time=\"{$exectime}\">\n\t    <xsl:if test=\"@Status = 'passed'\">\n\t    </xsl:if>\n\t    <xsl:if test=\"@Status = 'failed'\">\n\t\t<xsl:variable name=\"failtype\">\n\t\t    <xsl:for-each select=\"Results/NamedMeasurement\">\n\t\t\t<xsl:if test=\"@name = 'Exit Code'\">\n\t\t\t    <xsl:value-of select=\".\"/>\n\t\t\t</xsl:if>\n\t\t    </xsl:for-each>\n\t\t</xsl:variable>\n\t\t<xsl:variable name=\"failcode\">\n\t\t    <xsl:for-each select=\"Results/NamedMeasurement\">\n\t\t\t<xsl:if test=\"@name = 'Exit Value'\">\n\t\t\t    <xsl:value-of select=\".\"/>\n\t\t\t</xsl:if>\n\t\t    </xsl:for-each>\n\t\t</xsl:variable>\n\t\t<failure message=\"{$failtype} ({$failcode})\"><xsl:value-of select=\"Results/Measurement/Value/text()\" /></failure>\n\t    </xsl:if>\n\t    <xsl:if test=\"@Status = 'notrun'\">\n\t\t<skipped><xsl:value-of select=\"Results/Measurement/Value/text()\" /></skipped>\n\t    </xsl:if>\n\t</testcase>\n    </xsl:template>\n\n</xsl:stylesheet>\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/ci/README.md",
    "content": "## Eigen CI infrastructure\n\nEigen's CI infrastructure uses two stages: A `build` stage to build the unit-test\nsuite and a `test` stage to run the unit-tests.\n\n### Build Stage\n\nThe build stage consists of the following jobs:\n\n| Job Name                                 | Arch      | OS             | Compiler   | C++11   |\n|------------------------------------------|-----------|----------------|------------|---------|\n| `build:x86-64:linux:gcc-4.8:cxx11-on`    | `x86-64`  | `Ubuntu 18.04` | `GCC-4.8`  | `On`    |\n| `build:x86-64:linux:gcc-9:cxx11-on`      | `x86-64`  | `Ubuntu 18.04` | `GCC-9`    | `On`    |\n| `build:x86-64:linux:gcc-10:cxx11-on`     | `x86-64`  | `Ubuntu 18.04` | `GCC-10`   | `On`    |\n| `build:x86-64:linux:clang-10:cxx11-on`   | `x86-64`  | `Ubuntu 18.04` | `Clang-10` | `On`    |\n| `build:aarch64:linux:gcc-10:cxx11-on`    | `AArch64` | `Ubuntu 18.04` | `GCC-10`   | `On`    |\n| `build:aarch64:linux:clang-10:cxx11-on`  | `AArch64` | `Ubuntu 18.04` | `Clang-10` | `On`    |\n\n### Test stage\n\nIn principle every build-job has a corresponding test-job, however testing supported and unsupported modules is divided into separate jobs. The test jobs in detail:\n\n### Job dependecies\n\n| Job Name                                            | Arch      | OS             | Compiler   | C++11   | Module\n|-----------------------------------------------------|-----------|----------------|------------|---------|--------\n| `test:x86-64:linux:gcc-4.8:cxx11-on:official`       | `x86-64`  | `Ubuntu 18.04` | `GCC-4.8`  | `On`    | `Official`\n| `test:x86-64:linux:gcc-4.8:cxx11-on:unsupported`    | `x86-64`  | `Ubuntu 18.04` | `GCC-4.8`  | `On`    | `Unsupported`\n| `test:x86-64:linux:gcc-9:cxx11-on:official`         | `x86-64`  | `Ubuntu 18.04` | `GCC-9`    | `On`    | `Official`\n| `test:x86-64:linux:gcc-9:cxx11-on:unsupported`      | `x86-64`  | `Ubuntu 18.04` | `GCC-9`    | `On`    | `Unsupported`\n| `test:x86-64:linux:gcc-10:cxx11-on:official`        | `x86-64`  | `Ubuntu 18.04` | `GCC-10`   | `On`    | `Official`\n| `test:x86-64:linux:gcc-10:cxx11-on:unsupported`     | `x86-64`  | `Ubuntu 18.04` | `GCC-10`   | `On`    | `Unsupported`\n| `test:x86-64:linux:clang-10:cxx11-on:official`      | `x86-64`  | `Ubuntu 18.04` | `Clang-10` | `On`    | `Official`\n| `test:x86-64:linux:clang-10:cxx11-on:unsupported`   | `x86-64`  | `Ubuntu 18.04` | `Clang-10` | `On`    | `Unsupported`\n| `test:aarch64:linux:gcc-10:cxx11-on:official`       | `AArch64` | `Ubuntu 18.04` | `GCC-10`   | `On`    | `Official`\n| `test:aarch64:linux:gcc-10:cxx11-on:unsupported`    | `AArch64` | `Ubuntu 18.04` | `GCC-10`   | `On`    | `Unsupported`\n| `test:aarch64:linux:clang-10:cxx11-on:official`     | `AArch64` | `Ubuntu 18.04` | `Clang-10` | `On`    | `Official`\n| `test:aarch64:linux:clang-10:cxx11-on:unsupported`  | `AArch64` | `Ubuntu 18.04` | `Clang-10` | `On`    | `Unsupported`\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/ci/smoketests.gitlab-ci.yml",
    "content": ".buildsmoketests:linux:base:\n  stage: buildsmoketests\n  image: ubuntu:18.04\n  before_script:\n    - apt-get update -y\n    - apt-get install -y --no-install-recommends software-properties-common\n    - add-apt-repository -y  ppa:ubuntu-toolchain-r/test\n    - apt-get update\n    - apt-get install --no-install-recommends -y ${EIGEN_CI_CXX_COMPILER}\n      ${EIGEN_CI_CC_COMPILER} cmake ninja-build\n  script:\n    - mkdir -p ${BUILDDIR} && cd ${BUILDDIR}\n    - CXX=${EIGEN_CI_CXX_COMPILER} CC=${EIGEN_CI_CC_COMPILER} cmake -G\n      ${EIGEN_CI_CMAKE_GENEATOR} -DEIGEN_TEST_CXX11=${EIGEN_TEST_CXX11}\n      ${EIGEN_CI_ADDITIONAL_ARGS} ..\n    - cmake --build . --target buildsmoketests\n  artifacts:\n    name: \"$CI_JOB_NAME-$CI_COMMIT_REF_NAME\"\n    paths:\n      - ${BUILDDIR}/\n    expire_in: 5 days\n  only:\n    - merge_requests\n\nbuildsmoketests:x86-64:linux:gcc-10:cxx11-on:\n  extends: .buildsmoketests:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: \"g++-10\"\n    EIGEN_CI_CC_COMPILER: \"gcc-10\"\n    EIGEN_TEST_CXX11: \"on\"\n\nbuildsmoketests:x86-64:linux:clang-10:cxx11-on:\n  extends: .buildsmoketests:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: \"clang++-10\"\n    EIGEN_CI_CC_COMPILER: \"clang-10\"\n    EIGEN_TEST_CXX11: \"on\"\n\n.smoketests:linux:base:\n  stage: smoketests\n  image: ubuntu:18.04\n  before_script:\n    - apt-get update -y\n    - apt-get install -y --no-install-recommends software-properties-common\n    - add-apt-repository -y ppa:ubuntu-toolchain-r/test\n    - apt-get update\n    - apt-get install --no-install-recommends -y ${EIGEN_CI_CXX_COMPILER}\n      ${EIGEN_CI_CC_COMPILER} cmake ninja-build xsltproc\n  script:\n    - export CXX=${EIGEN_CI_CXX_COMPILER}\n    - export CC=${EIGEN_CI_CC_COMPILER}\n    - cd ${BUILDDIR} && ctest --output-on-failure --no-compress-output\n      --build-no-clean -T test -L smoketest\n  after_script:\n    - apt-get update -y\n    - apt-get install --no-install-recommends -y xsltproc\n    - cd ${BUILDDIR}\n    - xsltproc ../ci/CTest2JUnit.xsl Testing/`head -n 1 < Testing/TAG`/Test.xml > \"JUnitTestResults_$CI_JOB_ID.xml\"\n  artifacts:\n    reports:\n      junit:\n        - ${BUILDDIR}/JUnitTestResults_$CI_JOB_ID.xml\n    expire_in: 5 days\n  only:\n    - merge_requests\n\nsmoketests:x86-64:linux:gcc-10:cxx11-on:\n  extends: .smoketests:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: g++-10\n    EIGEN_CI_CC_COMPILER: gcc-10\n  needs: [ \"buildsmoketests:x86-64:linux:gcc-10:cxx11-on\" ]\n\nsmoketests:x86-64:linux:clang-10:cxx11-on:\n  extends: .smoketests:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: clang++-10\n    EIGEN_CI_CC_COMPILER: clang-10\n  needs: [ \"buildsmoketests:x86-64:linux:clang-10:cxx11-on\" ]\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/ci/test.gitlab-ci.yml",
    "content": ".test:linux:base:\n  stage: test\n  image: ubuntu:18.04\n  retry: 2\n  before_script:\n    - apt-get update -y\n    - apt-get install -y --no-install-recommends software-properties-common\n    - add-apt-repository -y ppa:ubuntu-toolchain-r/test\n    - apt-get update\n    - apt-get install --no-install-recommends -y ${EIGEN_CI_CXX_COMPILER}\n      ${EIGEN_CI_CC_COMPILER} cmake ninja-build xsltproc\n  script:\n    - export CXX=${EIGEN_CI_CXX_COMPILER}\n    - export CC=${EIGEN_CI_CC_COMPILER}\n    - cd ${BUILDDIR} && ctest --output-on-failure --no-compress-output\n      --build-no-clean -T test -L ${EIGEN_CI_TEST_LABEL}\n  after_script:\n    - apt-get update -y\n    - apt-get install --no-install-recommends -y xsltproc\n    - cd ${BUILDDIR}\n    - xsltproc ../ci/CTest2JUnit.xsl Testing/`head -n 1 < Testing/TAG`/Test.xml > \"JUnitTestResults_$CI_JOB_ID.xml\"\n  artifacts:\n    reports:\n      junit:\n        - ${BUILDDIR}/JUnitTestResults_$CI_JOB_ID.xml\n    expire_in: 5 days\n  only:\n    - schedules\n\n##### x86-64 ###################################################################\n# GCC-4.8\n.test:x86-64:linux:gcc-4.8:cxx11-on:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: g++-4.8\n    EIGEN_CI_CC_COMPILER: gcc-4.8\n  needs: [ \"build:x86-64:linux:gcc-4.8:cxx11-on\" ]\n  tags: \n    - eigen-runner\n    - linux\n    - x86-64\n\ntest:x86-64:linux:gcc-4.8:cxx11-on:official:\n  extends: .test:x86-64:linux:gcc-4.8:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:x86-64:linux:gcc-4.8:cxx11-on:unsupported:\n  extends: .test:x86-64:linux:gcc-4.8:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n# GCC-9\n.test:x86-64:linux:gcc-9:cxx11-on:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: g++-9\n    EIGEN_CI_CC_COMPILER: gcc-9\n  needs: [ \"build:x86-64:linux:gcc-9:cxx11-on\" ]\n  tags: \n    - eigen-runner\n    - linux\n    - x86-64\n\ntest:x86-64:linux:gcc-9:cxx11-on:official:\n  extends: .test:x86-64:linux:gcc-9:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:x86-64:linux:gcc-9:cxx11-on:unsupported:\n  extends: .test:x86-64:linux:gcc-9:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n# GCC-10\n.test:x86-64:linux:gcc-10:cxx11-on:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: g++-10\n    EIGEN_CI_CC_COMPILER: gcc-10\n  needs: [ \"build:x86-64:linux:gcc-10:cxx11-on\" ]\n  tags: \n    - eigen-runner\n    - linux\n    - x86-64\n\ntest:x86-64:linux:gcc-10:cxx11-on:official:\n  extends: .test:x86-64:linux:gcc-10:cxx11-on\n  allow_failure: true\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:x86-64:linux:gcc-10:cxx11-on:unsupported:\n  extends: .test:x86-64:linux:gcc-10:cxx11-on\n  allow_failure: true\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n# Clang 10\n.test:x86-64:linux:clang-10:cxx11-on:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: clang++-10\n    EIGEN_CI_CC_COMPILER: clang-10\n  needs: [ \"build:x86-64:linux:clang-10:cxx11-on\" ]\n  tags: \n    - eigen-runner\n    - linux\n    - x86-64\n\ntest:x86-64:linux:clang-10:cxx11-on:official:\n  extends: .test:x86-64:linux:clang-10:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:x86-64:linux:clang-10:cxx11-on:unsupported:\n  extends: .test:x86-64:linux:clang-10:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n##### AArch64 ##################################################################\n# GCC-10\n.test:aarch64:linux:gcc-10:cxx11-on:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: g++-10\n    EIGEN_CI_CC_COMPILER: gcc-10\n  needs: [ \"build:aarch64:linux:gcc-10:cxx11-on\" ]\n  tags: \n    - eigen-runner\n    - linux\n    - aarch64\n\ntest:aarch64:linux:gcc-10:cxx11-on:official:\n  extends: .test:aarch64:linux:gcc-10:cxx11-on\n  allow_failure: true\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:aarch64:linux:gcc-10:cxx11-on:unsupported:\n  extends: .test:aarch64:linux:gcc-10:cxx11-on\n  allow_failure: true\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n# Clang 10\n.test:aarch64:linux:clang-10:cxx11-on:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: clang++-10\n    EIGEN_CI_CC_COMPILER: clang-10\n  needs: [ \"build:aarch64:linux:clang-10:cxx11-on\" ]\n  tags: \n    - eigen-runner\n    - linux\n    - aarch64\n\ntest:aarch64:linux:clang-10:cxx11-on:official:\n  extends: .test:aarch64:linux:clang-10:cxx11-on\n  allow_failure: true\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:aarch64:linux:clang-10:cxx11-on:unsupported:\n  extends: .test:aarch64:linux:clang-10:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n##### ppc64le ##################################################################\n# GCC-10\n.test:ppc64le:linux:gcc-10:cxx11-on:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: g++-10\n    EIGEN_CI_CC_COMPILER: gcc-10\n  needs: [ \"build:ppc64le:linux:gcc-10:cxx11-on\" ]\n  allow_failure: true\n  tags: \n    - eigen-runner\n    - linux\n    - ppc64le\n\ntest:ppc64le:linux:gcc-10:cxx11-on:official:\n  extends: .test:ppc64le:linux:gcc-10:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:ppc64le:linux:gcc-10:cxx11-on:unsupported:\n  extends: .test:ppc64le:linux:gcc-10:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n# Clang 10\n.test:ppc64le:linux:clang-10:cxx11-on:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: clang++-10\n    EIGEN_CI_CC_COMPILER: clang-10\n  needs: [ \"build:ppc64le:linux:clang-10:cxx11-on\" ]\n  allow_failure: true\n  tags: \n    - eigen-runner\n    - linux\n    - ppc64le\n\ntest:ppc64le:linux:clang-10:cxx11-on:official:\n  extends: .test:ppc64le:linux:clang-10:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:ppc64le:linux:clang-10:cxx11-on:unsupported:\n  extends: .test:ppc64le:linux:clang-10:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/ComputeCppCompilerChecks.cmake",
    "content": "cmake_minimum_required(VERSION 3.4.3)\n\nif(CMAKE_COMPILER_IS_GNUCXX)\n  if (CMAKE_CXX_COMPILER_VERSION VERSION_LESS 4.8)\n    message(FATAL_ERROR \"host compiler - gcc version must be > 4.8\")\n  endif()\nelseif (\"${CMAKE_CXX_COMPILER_ID}\" STREQUAL \"Clang\")\n  if (${CMAKE_CXX_COMPILER_VERSION} VERSION_LESS 3.6)\n    message(FATAL_ERROR \"host compiler - clang version must be > 3.6\")\n  endif()\nendif()\n\nif(MSVC)\n  set(ComputeCpp_STL_CHECK_SRC __STL_check)\n  file(WRITE ${CMAKE_CURRENT_BINARY_DIR}/${ComputeCpp_STL_CHECK_SRC}.cpp\n    \"#include <ios>\\n\"\n    \"int main() { return 0; }\\n\")\n  execute_process(\n    COMMAND ${ComputeCpp_DEVICE_COMPILER_EXECUTABLE}\n            ${COMPUTECPP_DEVICE_COMPILER_FLAGS}\n            -isystem ${ComputeCpp_INCLUDE_DIRS}\n            -o ${ComputeCpp_STL_CHECK_SRC}.sycl\n            -c ${ComputeCpp_STL_CHECK_SRC}.cpp\n    WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}\n    RESULT_VARIABLE ComputeCpp_STL_CHECK_RESULT\n    ERROR_QUIET\n    OUTPUT_QUIET)\n  if(NOT ${ComputeCpp_STL_CHECK_RESULT} EQUAL 0)\n    # Try disabling compiler version checks\n    execute_process(\n      COMMAND ${ComputeCpp_DEVICE_COMPILER_EXECUTABLE}\n              ${COMPUTECPP_DEVICE_COMPILER_FLAGS}\n              -D_ALLOW_COMPILER_AND_STL_VERSION_MISMATCH\n              -isystem ${ComputeCpp_INCLUDE_DIRS}\n              -o ${ComputeCpp_STL_CHECK_SRC}.cpp.sycl\n              -c ${ComputeCpp_STL_CHECK_SRC}.cpp\n      WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}\n      RESULT_VARIABLE ComputeCpp_STL_CHECK_RESULT\n      ERROR_QUIET\n      OUTPUT_QUIET)\n    if(NOT ${ComputeCpp_STL_CHECK_RESULT} EQUAL 0)\n      message(STATUS \"Device compiler cannot consume hosted STL headers. Using any parts of the STL will likely result in device compiler errors.\")\n    else()\n    message(STATUS \"Device compiler does not meet certain STL version requirements. Disabling version checks and hoping for the best.\")\n      list(APPEND COMPUTECPP_DEVICE_COMPILER_FLAGS -D_ALLOW_COMPILER_AND_STL_VERSION_MISMATCH)\n    endif()\n  endif()\n  file(REMOVE ${CMAKE_CURRENT_BINARY_DIR}/${ComputeCpp_STL_CHECK_SRC}.cpp\n              ${CMAKE_CURRENT_BINARY_DIR}/${ComputeCpp_STL_CHECK_SRC}.cpp.sycl)\nendif(MSVC)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/ComputeCppIRMap.cmake",
    "content": "cmake_minimum_required(VERSION 3.4.3)\n\n# These should match the types of IR output by compute++\nset(IR_MAP_spir bc)\nset(IR_MAP_spir64 bc)\nset(IR_MAP_spir32 bc)\nset(IR_MAP_spirv spv)\nset(IR_MAP_spirv64 spv)\nset(IR_MAP_spirv32 spv)\nset(IR_MAP_aorta-x86_64 o)\nset(IR_MAP_aorta-aarch64 o)\nset(IR_MAP_aorta-rcar-cve o)\nset(IR_MAP_custom-spir64 bc)\nset(IR_MAP_custom-spir32 bc)\nset(IR_MAP_custom-spirv64 spv)\nset(IR_MAP_custom-spirv32 spv)\nset(IR_MAP_ptx64 s)\nset(IR_MAP_amdgcn s)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/Eigen3Config.cmake.in",
    "content": "# This file exports the Eigen3::Eigen CMake target which should be passed to the\n# target_link_libraries command.\n\n@PACKAGE_INIT@\n\nif (NOT TARGET Eigen3::Eigen)\n  include (\"${CMAKE_CURRENT_LIST_DIR}/Eigen3Targets.cmake\")\nendif (NOT TARGET Eigen3::Eigen)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/EigenConfigureTesting.cmake",
    "content": "include(EigenTesting)\ninclude(CheckCXXSourceCompiles)\n\n# configure the \"site\" and \"buildname\" \nei_set_sitename()\n\n# retrieve and store the build string\nei_set_build_string()\n\nadd_custom_target(buildtests)\nadd_custom_target(check COMMAND \"ctest\")\nadd_dependencies(check buildtests)\n\n# check whether /bin/bash exists (disabled as not used anymore)\n# find_file(EIGEN_BIN_BASH_EXISTS \"/bin/bash\" PATHS \"/\" NO_DEFAULT_PATH)\n\n# This call activates testing and generates the DartConfiguration.tcl\ninclude(CTest)\n\nset(EIGEN_TEST_BUILD_FLAGS \"\" CACHE STRING \"Options passed to the build command of unit tests\")\nset(EIGEN_DASHBOARD_BUILD_TARGET \"buildtests\" CACHE STRING \"Target to be built in dashboard mode, default is buildtests\")\nset(EIGEN_CTEST_ERROR_EXCEPTION \"\" CACHE STRING \"Regular expression for build error messages to be filtered out\")\n\n# Overwrite default DartConfiguration.tcl such that ctest can build our unit tests.\n# Recall that our unit tests are not in the \"all\" target, so we have to explicitly ask ctest to build our custom 'buildtests' target.\n# At this stage, we can also add custom flags to the build tool through the user defined EIGEN_TEST_BUILD_FLAGS variable.\nfile(READ  \"${CMAKE_CURRENT_BINARY_DIR}/DartConfiguration.tcl\" EIGEN_DART_CONFIG_FILE)\n# try to grab the default flags\nstring(REGEX MATCH \"MakeCommand:.*-- (.*)\\nDefaultCTestConfigurationType\" EIGEN_DUMMY ${EIGEN_DART_CONFIG_FILE})\nif(NOT CMAKE_MATCH_1)\nstring(REGEX MATCH \"MakeCommand:.*[^c]make (.*)\\nDefaultCTestConfigurationType\" EIGEN_DUMMY ${EIGEN_DART_CONFIG_FILE})\nendif()\nstring(REGEX REPLACE \"MakeCommand:.*DefaultCTestConfigurationType\" \"MakeCommand: ${CMAKE_COMMAND} --build . --target ${EIGEN_DASHBOARD_BUILD_TARGET} --config \\\"\\${CTEST_CONFIGURATION_TYPE}\\\" -- ${CMAKE_MATCH_1} ${EIGEN_TEST_BUILD_FLAGS}\\nDefaultCTestConfigurationType\"\n       EIGEN_DART_CONFIG_FILE2 ${EIGEN_DART_CONFIG_FILE})\nfile(WRITE \"${CMAKE_CURRENT_BINARY_DIR}/DartConfiguration.tcl\" ${EIGEN_DART_CONFIG_FILE2})\n\nconfigure_file(${CMAKE_CURRENT_SOURCE_DIR}/CTestCustom.cmake.in ${CMAKE_BINARY_DIR}/CTestCustom.cmake)\n\n# some documentation of this function would be nice\nei_init_testing()\n\n# configure Eigen related testing options\noption(EIGEN_NO_ASSERTION_CHECKING \"Disable checking of assertions using exceptions\" OFF)\noption(EIGEN_DEBUG_ASSERTS \"Enable advanced debugging of assertions\" OFF)\n\nif(CMAKE_COMPILER_IS_GNUCXX)\n  option(EIGEN_COVERAGE_TESTING \"Enable/disable gcov\" OFF)\n  if(EIGEN_COVERAGE_TESTING)\n    set(COVERAGE_FLAGS \"-fprofile-arcs -ftest-coverage\")\n    set(CTEST_CUSTOM_COVERAGE_EXCLUDE \"/test/\")\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} ${COVERAGE_FLAGS}\")\n  endif()\n  \nelseif(MSVC)\n  set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} /D_CRT_SECURE_NO_WARNINGS /D_SCL_SECURE_NO_WARNINGS\")\nendif()\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/EigenDetermineOSVersion.cmake",
    "content": "# The utility function DetermineOSVersion aims at providing an\n# improved version of the CMake variable ${CMAKE_SYSTEM} on Windows\n# machines.\n#\n# Usage:\n#  include(EigenDetermineOSVersion)\n#  DetermineOSVersion(OS_VERSION)\n#  message(\"OS: ${OS_VERSION}\")\n\n# - A little helper variable which should not be directly called\nfunction(DetermineShortWindowsName WIN_VERSION win_num_version)\n   if    (${win_num_version} VERSION_EQUAL \"6.1\")\n       set(_version \"win7\")\n   elseif(${win_num_version} VERSION_EQUAL \"6.0\")\n       set(_version \"winVista\")\n   elseif(${win_num_version} VERSION_EQUAL \"5.2\")\n       set(_version \"winXpProf\")\n   elseif(${win_num_version} VERSION_EQUAL \"5.1\")\n       set(_version \"winXp\")\n   elseif(${win_num_version} VERSION_EQUAL \"5.0\")\n       set(_version \"win2000Prof\")\n   else()\n       set(_version \"unknownWin\")\n   endif()\n   set(${WIN_VERSION} ${_version} PARENT_SCOPE)\nendfunction()\n\nfunction(DetermineOSVersion OS_VERSION)\n  if (WIN32 AND CMAKE_HOST_SYSTEM_NAME MATCHES Windows)\n    file (TO_NATIVE_PATH \"$ENV{COMSPEC}\" SHELL)\n    exec_program( ${SHELL} ARGS \"/c\" \"ver\" OUTPUT_VARIABLE ver_output)\n\t\t\t\t\n      string(REGEX MATCHALL \"[0-9]+\"\n           ver_list \"${ver_output}\")\n      list(GET ver_list 0 _major)\t\t   \n      list(GET ver_list 1 _minor)\n\t\t\t\t\n    set(win_num_version ${_major}.${_minor})\n    DetermineShortWindowsName(win_version \"${win_num_version}\")\n    if(win_version)\n      set(${OS_VERSION} ${win_version} PARENT_SCOPE)\n    endif()\n  else()\n    set(${OS_VERSION} ${CMAKE_SYSTEM} PARENT_SCOPE)\n  endif()\nendfunction()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/EigenDetermineVSServicePack.cmake",
    "content": "include(CMakeDetermineVSServicePack)\n\n# The code is almost identical to the CMake version. The only difference is that we remove\n# _DetermineVSServicePack_FastCheckVersionWithCompiler which lead to errors on some systems.\nfunction(EigenDetermineVSServicePack _pack)\n    if(NOT DETERMINED_VS_SERVICE_PACK OR NOT ${_pack})\n        if(NOT DETERMINED_VS_SERVICE_PACK)\n            _DetermineVSServicePack_CheckVersionWithTryCompile(DETERMINED_VS_SERVICE_PACK _cl_version)\n            if(NOT DETERMINED_VS_SERVICE_PACK)\n                _DetermineVSServicePack_CheckVersionWithTryRun(DETERMINED_VS_SERVICE_PACK _cl_version)\n            endif()\n        endif()\n\n        if(DETERMINED_VS_SERVICE_PACK)\n            if(_cl_version)\n                # Call helper function to determine VS version\n                _DetermineVSServicePackFromCompiler(_sp \"${_cl_version}\")\n              \n                # temporary fix, until CMake catches up\n                if (NOT _sp)\n                    if(${_cl_version} VERSION_EQUAL \"17.00.50727.1\")\n                        set(_sp \"vc110\")\n                    elseif(${_cl_version} VERSION_EQUAL \"17.00.51106.1\")\n                        set(_sp \"vc110sp1\")\n                    elseif(${_cl_version} VERSION_EQUAL \"17.00.60315.1\")\n                        set(_sp \"vc110sp2\")\n                    elseif(${_cl_version} VERSION_EQUAL \"17.00.60610.1\")\n                        set(_sp \"vc110sp3\")\n                    else()\n                        set(_sp ${CMAKE_CXX_COMPILER_VERSION})\n                    endif()\n                endif()\n                \n                if(_sp)\n                    set(${_pack} ${_sp} CACHE INTERNAL\n                        \"The Visual Studio Release with Service Pack\")\n                endif()\n            endif()\n        endif()\n    endif()\nendfunction()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/EigenSmokeTestList.cmake",
    "content": "# List of tests that will be build and run during Eigen's smoke testing. If one\n# of these tests doesn't exists or cannot be build with the current configuration\n# it will just be skipped.\nset(ei_smoke_test_list\n  adjoint_1\n  alignedvector3\n  array_cwise_7\n  array_cwise_8\n  array_for_matrix_1\n  array_of_string\n  array_replicate_1\n  array_reverse_1\n  autodiff_1\n  autodiff_scalar_1\n  bandmatrix\n  bdcsvd_9\n  bessel_functions_1\n  bfloat16_float\n  blasutil_1\n  block_5\n  BVH\n  cholesky_1\n  cholmod_support_23\n  cholmod_support_24\n  conservative_resize_1\n  constructor_1\n  corners_1\n  ctorleakmiscmatrices_4\n  dense_storage\n  determinant_1\n  diagonal_1\n  diagonal_2\n  diagonalmatrices_1\n  dynalloc\n  eigensolver_complex_1\n  eigensolver_selfadjoint_8\n  EulerAngles_1\n  exceptions\n  fastmath\n  first_aligned\n  geo_alignedbox_2\n  geo_eulerangles_1\n  geo_homogeneous_1\n  geo_hyperplane_1\n  geo_orthomethods_1\n  geo_parametrizedline_1\n  geo_transformations_7\n  half_float\n  hessenberg_1\n  hessenberg_6qr_10\n  householder_8\n  indexed_view_1\n  inplace_decomposition_1\n  integer_types_1\n  inverse_1\n  is_same_dense\n  jacobi_1\n  jacobisvd_1\n  kronecker_product\n  linearstructure_1\n  mapped_matrix_1\n  mapstaticmethods_1\n  mapstride_1\n  matrix_square_root_1\n  meta\n  minres_2\n  miscmatrices_1\n  mixingtypes_7\n  nestbyvalue\n  nesting_ops_1\n  nomalloc_1\n  nullary_1\n  num_dimensions\n  NumericalDiff\n  numext\n  packetmath\n  permutationmatrices_1\n  polynomialsolver_1\n  prec_inverse_4x4_1\n  product_extra_5\n  product_selfadjoint_1\n  product_small_7\n  product_symm_1\n  product_syrk_1\n  product_trmm_1\n  product_trmv_1\n  product_trsolve_5\n  qr_1\n  qr_colpivoting_7\n  qr_fullpivoting_4\n  rand\n  real_qz_1\n  redux_1\n  ref_1\n  resize\n  rvalue_types_1\n  schur_complex_1\n  schur_real_1\n  selfadjoint_1\n  sizeof\n  sizeoverflow\n  smallvectors\n  sparse_basic_3\n  sparse_block_1\n  sparse_extra_4\n  sparse_permutations_2\n  sparse_product_4\n  sparse_ref_1\n  sparse_solvers_1\n  sparse_vector_1\n  special_functions_1\n  special_numbers_1\n  special_packetmath_1\n  spqr_support_2\n  stable_norm_1\n  stddeque_1\n  stddeque_overload_1\n  stdlist_1\n  stdlist_overload_1\n  stdvector_1\n  stdvector_overload_1\n  stl_iterators_1\n  swap_1\n  symbolic_index_1\n  triangular_1\n  type_aliaslu_9\n  umeyama_3\n  unalignedassert\n  unalignedcount\n  vectorwiseop_1\n  visitor_1)"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/EigenTesting.cmake",
    "content": "\nmacro(ei_add_property prop value)\n  get_property(previous GLOBAL PROPERTY ${prop})\n  if ((NOT previous) OR (previous STREQUAL \"\"))\n    set_property(GLOBAL PROPERTY ${prop} \"${value}\")\n  else()\n    set_property(GLOBAL PROPERTY ${prop} \"${previous} ${value}\")\n  endif()\nendmacro()\n\n#internal. See documentation of ei_add_test for details.\nmacro(ei_add_test_internal testname testname_with_suffix)\n  set(targetname ${testname_with_suffix})\n\n  if(EIGEN_ADD_TEST_FILENAME_EXTENSION)\n    set(filename ${testname}.${EIGEN_ADD_TEST_FILENAME_EXTENSION})\n  else()\n    set(filename ${testname}.cpp)\n  endif()\n\n  # Add the current target to the list of subtest targets\n  get_property(EIGEN_SUBTESTS_LIST GLOBAL PROPERTY EIGEN_SUBTESTS_LIST)\n  set(EIGEN_SUBTESTS_LIST \"${EIGEN_SUBTESTS_LIST}${targetname}\\n\")\n  set_property(GLOBAL PROPERTY EIGEN_SUBTESTS_LIST \"${EIGEN_SUBTESTS_LIST}\")\n\n  if(EIGEN_ADD_TEST_FILENAME_EXTENSION STREQUAL cu)\n    if(EIGEN_TEST_HIP)\n      hip_reset_flags()\n      hip_add_executable(${targetname} ${filename} HIPCC_OPTIONS \"-DEIGEN_USE_HIP ${ARGV2}\")\n    elseif(EIGEN_TEST_CUDA_CLANG)\n      set_source_files_properties(${filename} PROPERTIES LANGUAGE CXX)\n      \n      if(CUDA_64_BIT_DEVICE_CODE AND (EXISTS \"${CUDA_TOOLKIT_ROOT_DIR}/lib64\"))\n        link_directories(\"${CUDA_TOOLKIT_ROOT_DIR}/lib64\")\n      else()\n        link_directories(\"${CUDA_TOOLKIT_ROOT_DIR}/lib\")\n      endif()\n\n      if (${ARGC} GREATER 2)\n        add_executable(${targetname} ${filename})\n      else()\n        add_executable(${targetname} ${filename} OPTIONS ${ARGV2})\n      endif()\n      set(CUDA_CLANG_LINK_LIBRARIES \"cudart_static\" \"cuda\" \"dl\" \"pthread\")\n      if (CMAKE_SYSTEM_NAME STREQUAL \"Linux\")\n      set(CUDA_CLANG_LINK_LIBRARIES ${CUDA_CLANG_LINK_LIBRARIES} \"rt\")\n      endif()\n      target_link_libraries(${targetname} ${CUDA_CLANG_LINK_LIBRARIES})\n    else()\n      if (${ARGC} GREATER 2)\n        cuda_add_executable(${targetname} ${filename} OPTIONS ${ARGV2})\n      else()\n        cuda_add_executable(${targetname} ${filename})\n      endif()\n    endif()\n  else()\n    add_executable(${targetname} ${filename})\n  endif()\n\n  if (targetname MATCHES \"^eigen2_\")\n    add_dependencies(eigen2_buildtests ${targetname})\n  else()\n    add_dependencies(buildtests ${targetname})\n  endif()\n\n  if(EIGEN_NO_ASSERTION_CHECKING)\n    ei_add_target_property(${targetname} COMPILE_FLAGS \"-DEIGEN_NO_ASSERTION_CHECKING=1\")\n  else()\n    if(EIGEN_DEBUG_ASSERTS)\n      ei_add_target_property(${targetname} COMPILE_FLAGS \"-DEIGEN_DEBUG_ASSERTS=1\")\n    endif()\n  endif()\n\n  ei_add_target_property(${targetname} COMPILE_FLAGS \"-DEIGEN_TEST_MAX_SIZE=${EIGEN_TEST_MAX_SIZE}\")\n\n  if(MSVC)\n    ei_add_target_property(${targetname} COMPILE_FLAGS \"/bigobj\")\n  endif()\n\n  # let the user pass flags.\n  if(${ARGC} GREATER 2)\n    ei_add_target_property(${targetname} COMPILE_FLAGS \"${ARGV2}\")\n  endif()\n\n  if(EIGEN_TEST_CUSTOM_CXX_FLAGS)\n    ei_add_target_property(${targetname} COMPILE_FLAGS \"${EIGEN_TEST_CUSTOM_CXX_FLAGS}\")\n  endif()\n\n  if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO)\n    target_link_libraries(${targetname} ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO})\n  endif()\n  if(EXTERNAL_LIBS)\n    target_link_libraries(${targetname} ${EXTERNAL_LIBS})\n  endif()\n  if(EIGEN_TEST_CUSTOM_LINKER_FLAGS)\n    target_link_libraries(${targetname} ${EIGEN_TEST_CUSTOM_LINKER_FLAGS})\n  endif()\n\n  if(${ARGC} GREATER 3)\n    set(libs_to_link ${ARGV3})\n    # it could be that some cmake module provides a bad library string \" \"  (just spaces),\n    # and that severely breaks target_link_libraries (\"can't link to -l-lstdc++\" errors).\n    # so we check for strings containing only spaces.\n    string(STRIP \"${libs_to_link}\" libs_to_link_stripped)\n    string(LENGTH \"${libs_to_link_stripped}\" libs_to_link_stripped_length)\n    if(${libs_to_link_stripped_length} GREATER 0)\n      # notice: no double quotes around ${libs_to_link} here. It may be a list.\n      target_link_libraries(${targetname} ${libs_to_link})\n    endif()\n  endif()\n\n  add_test(${testname_with_suffix} \"${targetname}\")\n\n  # Specify target and test labels according to EIGEN_CURRENT_SUBPROJECT\n  get_property(current_subproject GLOBAL PROPERTY EIGEN_CURRENT_SUBPROJECT)\n  if ((current_subproject) AND (NOT (current_subproject STREQUAL \"\")))\n    set_property(TARGET ${targetname} PROPERTY LABELS \"Build${current_subproject}\")\n    add_dependencies(\"Build${current_subproject}\" ${targetname})\n    set_property(TEST ${testname_with_suffix} PROPERTY LABELS \"${current_subproject}\")\n  endif()\n  if(EIGEN_SYCL)\n    # Force include of the SYCL file at the end to avoid errors.\n    set_property(TARGET ${targetname} PROPERTY COMPUTECPP_INCLUDE_AFTER 1)\n    # Set COMPILE_FLAGS to COMPILE_DEFINITIONS instead to avoid having to duplicate the flags\n    # to the device compiler.\n    get_target_property(target_compile_flags ${targetname} COMPILE_FLAGS)\n    separate_arguments(target_compile_flags)\n    foreach(flag ${target_compile_flags})\n      if(${flag} MATCHES \"^-D.*\")\n        string(REPLACE \"-D\" \"\" definition_flag ${flag})\n        set_property(TARGET ${targetname} APPEND PROPERTY COMPILE_DEFINITIONS ${definition_flag})\n        list(REMOVE_ITEM target_compile_flags ${flag})\n      endif()\n    endforeach()\n    set_property(TARGET ${targetname} PROPERTY COMPILE_FLAGS ${target_compile_flags})\n    # Link against pthread and add sycl to target\n    set(THREADS_PREFER_PTHREAD_FLAG ON)\n    find_package(Threads REQUIRED)\n    target_link_libraries(${targetname} Threads::Threads)\n    add_sycl_to_target(TARGET ${targetname} SOURCES ${filename})\n  endif(EIGEN_SYCL)\nendmacro(ei_add_test_internal)\n# Macro to add a test\n#\n# the unique mandatory parameter testname must correspond to a file\n# <testname>.cpp which follows this pattern:\n#\n# #include \"main.h\"\n# void test_<testname>() { ... }\n#\n# Depending on the contents of that file, this macro can have 2 behaviors,\n# see below.\n#\n# The optional 2nd parameter is libraries to link to.\n#\n# A. Default behavior\n#\n# this macro adds an executable <testname> as well as a ctest test\n# named <testname> too.\n#\n# On platforms with bash simply run:\n#   \"ctest -V\" or \"ctest -V -R <testname>\"\n# On other platform use ctest as usual\n#\n# B. Multi-part behavior\n#\n# If the source file matches the regexp\n#    CALL_SUBTEST_[0-9]+|EIGEN_TEST_PART_[0-9]+\n# then it is interpreted as a multi-part test. The behavior then depends on the\n# CMake option EIGEN_SPLIT_LARGE_TESTS, which is ON by default.\n#\n# If EIGEN_SPLIT_LARGE_TESTS is OFF, the behavior is the same as in A (the multi-part\n# aspect is ignored).\n#\n# If EIGEN_SPLIT_LARGE_TESTS is ON, the test is split into multiple executables\n#   test_<testname>_<N>\n# where N runs from 1 to the greatest occurrence found in the source file. Each of these\n# executables is built passing -DEIGEN_TEST_PART_N. This allows to split large tests\n# into smaller executables.\n#\n# Moreover, targets <testname> are still generated, they\n# have the effect of building all the parts of the test.\n#\n# Again, ctest -R allows to run all matching tests.\nmacro(ei_add_test testname)\n  get_property(EIGEN_TESTS_LIST GLOBAL PROPERTY EIGEN_TESTS_LIST)\n  set(EIGEN_TESTS_LIST \"${EIGEN_TESTS_LIST}${testname}\\n\")\n  set_property(GLOBAL PROPERTY EIGEN_TESTS_LIST \"${EIGEN_TESTS_LIST}\")\n\n  if(EIGEN_ADD_TEST_FILENAME_EXTENSION)\n    set(filename ${testname}.${EIGEN_ADD_TEST_FILENAME_EXTENSION})\n  else()\n    set(filename ${testname}.cpp)\n  endif()\n\n  file(READ \"${filename}\" test_source)\n  string(REGEX MATCHALL \"CALL_SUBTEST_[0-9]+|EIGEN_TEST_PART_[0-9]+|EIGEN_SUFFIXES(;[0-9]+)+\"\n         occurrences \"${test_source}\")\n  string(REGEX REPLACE \"CALL_SUBTEST_|EIGEN_TEST_PART_|EIGEN_SUFFIXES\" \"\" suffixes \"${occurrences}\")\n  list(REMOVE_DUPLICATES suffixes)\n  set(explicit_suffixes \"\")\n  if( (NOT EIGEN_SPLIT_LARGE_TESTS) AND suffixes)\n    # Check whether we have EIGEN_TEST_PART_* statements, in which case we likely must enforce splitting.\n    # For instance, indexed_view activate a different c++ version for each part.\n    string(REGEX MATCHALL \"EIGEN_TEST_PART_[0-9]+\" occurrences \"${test_source}\")\n    string(REGEX REPLACE \"EIGEN_TEST_PART_\" \"\" explicit_suffixes \"${occurrences}\")\n    list(REMOVE_DUPLICATES explicit_suffixes)\n  endif()\n  if( (EIGEN_SPLIT_LARGE_TESTS AND suffixes) OR explicit_suffixes)\n    add_custom_target(${testname})\n    foreach(suffix ${suffixes})\n      ei_add_test_internal(${testname} ${testname}_${suffix}\n        \"${ARGV1} -DEIGEN_TEST_PART_${suffix}=1\" \"${ARGV2}\")\n      add_dependencies(${testname} ${testname}_${suffix})\n    endforeach()\n  else()\n    ei_add_test_internal(${testname} ${testname} \"${ARGV1} -DEIGEN_TEST_PART_ALL=1\" \"${ARGV2}\")\n  endif()\nendmacro()\n\n# adds a failtest, i.e. a test that succeed if the program fails to compile\n# note that the test runner for these is CMake itself, when passed -DEIGEN_FAILTEST=ON\n# so here we're just running CMake commands immediately, we're not adding any targets.\nmacro(ei_add_failtest testname)\n\n  set(test_target_ok ${testname}_ok)\n  set(test_target_ko ${testname}_ko)\n\n  # Add executables\n  add_executable(${test_target_ok} ${testname}.cpp)\n  add_executable(${test_target_ko} ${testname}.cpp)\n\n  # Remove them from the normal build process\n  set_target_properties(${test_target_ok} ${test_target_ko} PROPERTIES\n                        EXCLUDE_FROM_ALL TRUE\n                        EXCLUDE_FROM_DEFAULT_BUILD TRUE)\n\n  # Configure the failing test\n  target_compile_definitions(${test_target_ko} PRIVATE EIGEN_SHOULD_FAIL_TO_BUILD)\n\n  # Add the tests to ctest.\n  add_test(NAME ${test_target_ok}\n          COMMAND ${CMAKE_COMMAND} --build . --target ${test_target_ok} --config $<CONFIGURATION>\n          WORKING_DIRECTORY ${CMAKE_BINARY_DIR})\n  add_test(NAME ${test_target_ko}\n          COMMAND ${CMAKE_COMMAND} --build . --target ${test_target_ko} --config $<CONFIGURATION>\n          WORKING_DIRECTORY ${CMAKE_BINARY_DIR})\n\n  # Expect the second test to fail\n  set_tests_properties(${test_target_ko} PROPERTIES WILL_FAIL TRUE)\nendmacro()\n\n# print a summary of the different options\nmacro(ei_testing_print_summary)\n  message(STATUS \"************************************************************\")\n  message(STATUS \"***    Eigen's unit tests configuration summary          ***\")\n  message(STATUS \"************************************************************\")\n  message(STATUS \"\")\n  message(STATUS \"Build type:        ${CMAKE_BUILD_TYPE}\")\n  message(STATUS \"Build site:        ${SITE}\")\n  message(STATUS \"Build string:      ${BUILDNAME}\")\n  get_property(EIGEN_TESTING_SUMMARY GLOBAL PROPERTY EIGEN_TESTING_SUMMARY)\n  get_property(EIGEN_TESTED_BACKENDS GLOBAL PROPERTY EIGEN_TESTED_BACKENDS)\n  get_property(EIGEN_MISSING_BACKENDS GLOBAL PROPERTY EIGEN_MISSING_BACKENDS)\n  message(STATUS \"Enabled backends:  ${EIGEN_TESTED_BACKENDS}\")\n  message(STATUS \"Disabled backends: ${EIGEN_MISSING_BACKENDS}\")\n\n  if(EIGEN_DEFAULT_TO_ROW_MAJOR)\n    message(STATUS \"Default order:     Row-major\")\n  else()\n    message(STATUS \"Default order:     Column-major\")\n  endif()\n\n  if(EIGEN_TEST_NO_EXPLICIT_ALIGNMENT)\n    message(STATUS \"Explicit alignment (hence vectorization) disabled\")\n  elseif(EIGEN_TEST_NO_EXPLICIT_VECTORIZATION)\n    message(STATUS \"Explicit vectorization disabled (alignment kept enabled)\")\n  else()\n\n  message(STATUS \"Maximal matrix/vector size: ${EIGEN_TEST_MAX_SIZE}\")\n\n    if(EIGEN_TEST_SSE2)\n      message(STATUS \"SSE2:              ON\")\n    else()\n      message(STATUS \"SSE2:              Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_SSE3)\n      message(STATUS \"SSE3:              ON\")\n    else()\n      message(STATUS \"SSE3:              Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_SSSE3)\n      message(STATUS \"SSSE3:             ON\")\n    else()\n      message(STATUS \"SSSE3:             Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_SSE4_1)\n      message(STATUS \"SSE4.1:            ON\")\n    else()\n      message(STATUS \"SSE4.1:            Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_SSE4_2)\n      message(STATUS \"SSE4.2:            ON\")\n    else()\n      message(STATUS \"SSE4.2:            Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_AVX)\n      message(STATUS \"AVX:               ON\")\n    else()\n      message(STATUS \"AVX:               Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_AVX2)\n      message(STATUS \"AVX2:              ON\")\n    else()\n      message(STATUS \"AVX2:              Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_FMA)\n      message(STATUS \"FMA:               ON\")\n    else()\n      message(STATUS \"FMA:               Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_AVX512)\n      message(STATUS \"AVX512:            ON\")\n    else()\n      message(STATUS \"AVX512:            Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_AVX512DQ)\n      message(STATUS \"AVX512DQ:          ON\")\n    else()\n      message(STATUS \"AVX512DQ:          Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_ALTIVEC)\n      message(STATUS \"Altivec:           ON\")\n    else()\n      message(STATUS \"Altivec:           Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_VSX)\n      message(STATUS \"VSX:               ON\")\n    else()\n      message(STATUS \"VSX:               Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_MSA)\n      message(STATUS \"MIPS MSA:          ON\")\n    else()\n      message(STATUS \"MIPS MSA:          Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_NEON)\n      message(STATUS \"ARM NEON:          ON\")\n    else()\n      message(STATUS \"ARM NEON:          Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_NEON64)\n      message(STATUS \"ARMv8 NEON:        ON\")\n    else()\n      message(STATUS \"ARMv8 NEON:        Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_ZVECTOR)\n      message(STATUS \"S390X ZVECTOR:     ON\")\n    else()\n      message(STATUS \"S390X ZVECTOR:     Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_CXX11)\n      message(STATUS \"C++11:             ON\")\n    else()\n      message(STATUS \"C++11:             OFF\")\n    endif()\n\n    if(EIGEN_TEST_SYCL)\n      if(EIGEN_SYCL_TRISYCL)\n        message(STATUS \"SYCL:              ON (using triSYCL)\")\n      else()\n        message(STATUS \"SYCL:              ON (using computeCPP)\")\n      endif()\n    else()\n      message(STATUS \"SYCL:              OFF\")\n    endif()\n    if(EIGEN_TEST_CUDA)\n      if(EIGEN_TEST_CUDA_CLANG)\n        message(STATUS \"CUDA:              ON (using clang)\")\n      else()\n        message(STATUS \"CUDA:              ON (using nvcc)\")\n      endif()\n    else()\n      message(STATUS \"CUDA:              OFF\")\n    endif()\n    if(EIGEN_TEST_HIP)\n      message(STATUS \"HIP:               ON (using hipcc)\")\n    else()\n      message(STATUS \"HIP:               OFF\")\n    endif()\n\n  endif() # vectorization / alignment options\n\n  message(STATUS \"\\n${EIGEN_TESTING_SUMMARY}\")\n\n  message(STATUS \"************************************************************\")\nendmacro()\n\nmacro(ei_init_testing)\n  define_property(GLOBAL PROPERTY EIGEN_CURRENT_SUBPROJECT BRIEF_DOCS \" \" FULL_DOCS \" \")\n  define_property(GLOBAL PROPERTY EIGEN_TESTED_BACKENDS BRIEF_DOCS \" \" FULL_DOCS \" \")\n  define_property(GLOBAL PROPERTY EIGEN_MISSING_BACKENDS BRIEF_DOCS \" \" FULL_DOCS \" \")\n  define_property(GLOBAL PROPERTY EIGEN_TESTING_SUMMARY BRIEF_DOCS \" \" FULL_DOCS \" \")\n  define_property(GLOBAL PROPERTY EIGEN_TESTS_LIST BRIEF_DOCS \" \" FULL_DOCS \" \")\n  define_property(GLOBAL PROPERTY EIGEN_SUBTESTS_LIST BRIEF_DOCS \" \" FULL_DOCS \" \")\n\n  set_property(GLOBAL PROPERTY EIGEN_TESTED_BACKENDS \"\")\n  set_property(GLOBAL PROPERTY EIGEN_MISSING_BACKENDS \"\")\n  set_property(GLOBAL PROPERTY EIGEN_TESTING_SUMMARY \"\")\n  set_property(GLOBAL PROPERTY EIGEN_TESTS_LIST \"\")\n  set_property(GLOBAL PROPERTY EIGEN_SUBTESTS_LIST \"\")\n\n  define_property(GLOBAL PROPERTY EIGEN_FAILTEST_FAILURE_COUNT BRIEF_DOCS \" \" FULL_DOCS \" \")\n  define_property(GLOBAL PROPERTY EIGEN_FAILTEST_COUNT BRIEF_DOCS \" \" FULL_DOCS \" \")\n\n  set_property(GLOBAL PROPERTY EIGEN_FAILTEST_FAILURE_COUNT \"0\")\n  set_property(GLOBAL PROPERTY EIGEN_FAILTEST_COUNT \"0\")\n\n  # uncomment anytime you change the ei_get_compilerver_from_cxx_version_string macro\n  # ei_test_get_compilerver_from_cxx_version_string()\nendmacro()\n\nmacro(ei_set_sitename)\n  # if the sitename is not yet set, try to set it\n  if(NOT ${SITE} OR ${SITE} STREQUAL \"\")\n    set(eigen_computername $ENV{COMPUTERNAME})\n    set(eigen_hostname $ENV{HOSTNAME})\n    if(eigen_hostname)\n      set(SITE ${eigen_hostname})\n    elseif(eigen_computername)\n      set(SITE ${eigen_computername})\n    endif()\n  endif()\n  # in case it is already set, enforce lower case\n  if(SITE)\n    string(TOLOWER ${SITE} SITE)\n  endif()\nendmacro()\n\nmacro(ei_get_compilerver VAR)\n    if(MSVC)\n      # on windows system, we use a modified CMake script\n      include(EigenDetermineVSServicePack)\n      EigenDetermineVSServicePack( my_service_pack )\n\n      if( my_service_pack )\n        set(${VAR} ${my_service_pack})\n      else()\n        set(${VAR} \"na\")\n      endif()\n    elseif(${CMAKE_CXX_COMPILER_ID} MATCHES \"PGI\")\n      set(${VAR} \"${CMAKE_CXX_COMPILER_ID}-${CMAKE_CXX_COMPILER_VERSION}\")\n    else()\n    # on all other system we rely on ${CMAKE_CXX_COMPILER}\n    # supporting a \"--version\" or \"/version\" flag\n\n    if(WIN32 AND ${CMAKE_CXX_COMPILER_ID} EQUAL \"Intel\")\n      set(EIGEN_CXX_FLAG_VERSION \"/version\")\n    else()\n      set(EIGEN_CXX_FLAG_VERSION \"--version\")\n    endif()\n\n    execute_process(COMMAND ${CMAKE_CXX_COMPILER} ${EIGEN_CXX_FLAG_VERSION}\n                    OUTPUT_VARIABLE eigen_cxx_compiler_version_string OUTPUT_STRIP_TRAILING_WHITESPACE)\n    string(REGEX REPLACE \"^[ \\n\\r]+\" \"\" eigen_cxx_compiler_version_string ${eigen_cxx_compiler_version_string})\n    string(REGEX REPLACE \"[\\n\\r].*\"  \"\"  eigen_cxx_compiler_version_string  ${eigen_cxx_compiler_version_string})\n\n    ei_get_compilerver_from_cxx_version_string(\"${eigen_cxx_compiler_version_string}\" CNAME CVER)\n    set(${VAR} \"${CNAME}-${CVER}\")\n\n  endif()\nendmacro()\n\n# Extract compiler name and version from a raw version string\n# WARNING: if you edit this macro, then please test it by uncommenting\n# the testing macro call in ei_init_testing() of the EigenTesting.cmake file.\n# See also the ei_test_get_compilerver_from_cxx_version_string macro at the end\n# of the file\nmacro(ei_get_compilerver_from_cxx_version_string VERSTRING CNAME CVER)\n  # extract possible compiler names\n  string(REGEX MATCH \"g\\\\+\\\\+\"      ei_has_gpp    ${VERSTRING})\n  string(REGEX MATCH \"llvm|LLVM\"    ei_has_llvm   ${VERSTRING})\n  string(REGEX MATCH \"gcc|GCC\"      ei_has_gcc    ${VERSTRING})\n  string(REGEX MATCH \"icpc|ICC\"     ei_has_icpc   ${VERSTRING})\n  string(REGEX MATCH \"clang|CLANG\"  ei_has_clang  ${VERSTRING})\n  string(REGEX MATCH \"mingw32\"      ei_has_mingw  ${VERSTRING})\n\n  # combine them\n  if((ei_has_llvm) AND (ei_has_gpp OR ei_has_gcc))\n    set(${CNAME} \"llvm-g++\")\n  elseif((ei_has_llvm) AND (ei_has_clang))\n    set(${CNAME} \"llvm-clang++\")\n  elseif(ei_has_clang)\n    set(${CNAME} \"clang++\")\n  elseif ((ei_has_mingw) AND (ei_has_gpp OR ei_has_gcc))\n    set(${CNAME} \"mingw32-g++\")\n  elseif(ei_has_icpc)\n    set(${CNAME} \"icpc\")\n  elseif(ei_has_gpp OR ei_has_gcc)\n    set(${CNAME} \"g++\")\n  else()\n    set(${CNAME} \"_\")\n  endif()\n\n  # extract possible version numbers\n  # first try to extract 3 isolated numbers:\n  string(REGEX MATCH \" [0-9]+\\\\.[0-9]+\\\\.[0-9]+\" eicver ${VERSTRING})\n  if(NOT eicver)\n    # try to extract 2 isolated ones:\n    string(REGEX MATCH \" [0-9]+\\\\.[0-9]+\" eicver ${VERSTRING})\n    if(NOT eicver)\n      # try to extract 3:\n      string(REGEX MATCH \"[^0-9][0-9]+\\\\.[0-9]+\\\\.[0-9]+\" eicver ${VERSTRING})\n      if(NOT eicver)\n        # try to extract 2:\n        string(REGEX MATCH \"[^0-9][0-9]+\\\\.[0-9]+\" eicver ${VERSTRING})\n        if (NOT eicver AND ei_has_mingw)\n          # try to extract 1 number plus suffix:\n          string(REGEX MATCH \"[^0-9][0-9]+-win32\" eicver ${VERSTRING})          \n        endif()\n      endif()\n    endif()\n  endif()\n  \n  if (NOT eicver)\n    set(eicver \" _\")\n  endif()\n\n  string(REGEX REPLACE \".(.*)\" \"\\\\1\" ${CVER} ${eicver})\n\nendmacro()\n\nmacro(ei_get_cxxflags VAR)\n  set(${VAR} \"\")\n  ei_is_64bit_env(IS_64BIT_ENV)\n  if(EIGEN_TEST_NEON)\n    set(${VAR} NEON)\n  elseif(EIGEN_TEST_NEON64)\n    set(${VAR} NEON)\n  elseif(EIGEN_TEST_ZVECTOR)\n    set(${VAR} ZVECTOR)\n  elseif(EIGEN_TEST_VSX)\n    set(${VAR} VSX)\n  elseif(EIGEN_TEST_ALTIVEC)\n    set(${VAR} ALVEC)\n  elseif(EIGEN_TEST_FMA)\n    set(${VAR} FMA)\n  elseif(EIGEN_TEST_AVX)\n    set(${VAR} AVX)\n  elseif(EIGEN_TEST_SSE4_2)\n    set(${VAR} SSE42)\n  elseif(EIGEN_TEST_SSE4_1)\n    set(${VAR} SSE41)\n  elseif(EIGEN_TEST_SSSE3)\n    set(${VAR} SSSE3)\n  elseif(EIGEN_TEST_SSE3)\n    set(${VAR} SSE3)\n  elseif(EIGEN_TEST_SSE2 OR IS_64BIT_ENV)\n    set(${VAR} SSE2)\n  elseif(EIGEN_TEST_MSA)\n    set(${VAR} MSA)\n  endif()\n\n  if(EIGEN_TEST_OPENMP)\n    if (${VAR} STREQUAL \"\")\n      set(${VAR} OMP)\n    else()\n      set(${VAR} ${${VAR}}-OMP)\n    endif()\n  endif()\n\n  if(EIGEN_DEFAULT_TO_ROW_MAJOR)\n    if (${VAR} STREQUAL \"\")\n      set(${VAR} ROW)\n    else()\n      set(${VAR} ${${VAR}}-ROWMAJ)\n    endif()\n  endif()\nendmacro()\n\nmacro(ei_set_build_string)\n  ei_get_compilerver(LOCAL_COMPILER_VERSION)\n  ei_get_cxxflags(LOCAL_COMPILER_FLAGS)\n\n  include(EigenDetermineOSVersion)\n  DetermineOSVersion(OS_VERSION)\n\n  set(TMP_BUILD_STRING ${OS_VERSION}-${LOCAL_COMPILER_VERSION})\n\n  if (NOT ${LOCAL_COMPILER_FLAGS} STREQUAL  \"\")\n    set(TMP_BUILD_STRING ${TMP_BUILD_STRING}-${LOCAL_COMPILER_FLAGS})\n  endif()\n\n  if(EIGEN_TEST_EXTERNAL_BLAS)\n    set(TMP_BUILD_STRING ${TMP_BUILD_STRING}-external_blas)\n  endif()\n\n  ei_is_64bit_env(IS_64BIT_ENV)\n  if(NOT IS_64BIT_ENV)\n    set(TMP_BUILD_STRING ${TMP_BUILD_STRING}-32bit)\n  else()\n    set(TMP_BUILD_STRING ${TMP_BUILD_STRING}-64bit)\n  endif()\n\n  if(EIGEN_TEST_CXX11)\n    set(TMP_BUILD_STRING ${TMP_BUILD_STRING}-cxx11)\n  endif()\n\n  if(EIGEN_BUILD_STRING_SUFFIX)\n    set(TMP_BUILD_STRING ${TMP_BUILD_STRING}-${EIGEN_BUILD_STRING_SUFFIX})\n  endif()\n\n  string(TOLOWER ${TMP_BUILD_STRING} BUILDNAME)\nendmacro()\n\nmacro(ei_is_64bit_env VAR)\n  if(CMAKE_SIZEOF_VOID_P EQUAL 8)\n    set(${VAR} 1)\n  elseif(CMAKE_SIZEOF_VOID_P EQUAL 4)\n    set(${VAR} 0)\n  else()\n    message(WARNING \"Unsupported pointer size. Please contact the authors.\")\n  endif()\nendmacro()\n\n\n# helper macro for testing ei_get_compilerver_from_cxx_version_string\n# STR: raw version string\n# REFNAME: expected compiler name\n# REFVER: expected compiler version\nmacro(ei_test1_get_compilerver_from_cxx_version_string STR REFNAME REFVER)\n  ei_get_compilerver_from_cxx_version_string(${STR} CNAME CVER)\n  if((NOT ${REFNAME} STREQUAL ${CNAME}) OR (NOT ${REFVER} STREQUAL ${CVER}))\n    message(\"STATUS ei_get_compilerver_from_cxx_version_string error:\")\n    message(\"Expected \\\"${REFNAME}-${REFVER}\\\", got \\\"${CNAME}-${CVER}\\\"\")\n  endif()\nendmacro()\n\n# macro for testing ei_get_compilerver_from_cxx_version_string\n# feel free to add more version strings\nmacro(ei_test_get_compilerver_from_cxx_version_string)\n  ei_test1_get_compilerver_from_cxx_version_string(\"g++ (SUSE Linux) 4.5.3 20110428 [gcc-4_5-branch revision 173117]\" \"g++\" \"4.5.3\")\n  ei_test1_get_compilerver_from_cxx_version_string(\"c++ (GCC) 4.5.1 20100924 (Red Hat 4.5.1-4)\" \"g++\" \"4.5.1\")\n  ei_test1_get_compilerver_from_cxx_version_string(\"icpc (ICC) 11.0 20081105\" \"icpc\" \"11.0\")\n  ei_test1_get_compilerver_from_cxx_version_string(\"g++-3.4 (GCC) 3.4.6\" \"g++\" \"3.4.6\")\n  ei_test1_get_compilerver_from_cxx_version_string(\"SUSE Linux clang version 3.0 (branches/release_30 145598) (based on LLVM 3.0)\" \"llvm-clang++\" \"3.0\")\n  ei_test1_get_compilerver_from_cxx_version_string(\"icpc (ICC) 12.0.5 20110719\" \"icpc\" \"12.0.5\")\n  ei_test1_get_compilerver_from_cxx_version_string(\"Apple clang version 2.1 (tags/Apple/clang-163.7.1) (based on LLVM 3.0svn)\" \"llvm-clang++\" \"2.1\")\n  ei_test1_get_compilerver_from_cxx_version_string(\"i686-apple-darwin11-llvm-g++-4.2 (GCC) 4.2.1 (Based on Apple Inc. build 5658) (LLVM build 2335.15.00)\" \"llvm-g++\" \"4.2.1\")\n  ei_test1_get_compilerver_from_cxx_version_string(\"g++-mp-4.4 (GCC) 4.4.6\" \"g++\" \"4.4.6\")\n  ei_test1_get_compilerver_from_cxx_version_string(\"g++-mp-4.4 (GCC) 2011\" \"g++\" \"4.4\")\n  ei_test1_get_compilerver_from_cxx_version_string(\"x86_64-w64-mingw32-g++ (GCC) 10-win32 20210110\" \"mingw32-g++\" \"10-win32\")\nendmacro()\n\n# Split all tests listed in EIGEN_TESTS_LIST into num_splits many targets\n# named buildtestspartN with N = { 0, ..., num_splits-1}.\n#\n# The intention behind the existance of this macro is the size of Eigen's\n# testsuite. Together with the relativly big compile-times building all tests\n# can take a substantial amount of time depending on the available hardware.\n# \n# The last buildtestspartN target will build possible remaining tests.\n#\n# An example:\n#\n#   EIGEN_TESTS_LIST= [ test1, test2, test3, test4, test5, test6, test7 ]\n#\n# A call to ei_split_testsuite(3) creates the following targets with dependencies\n#\n#   Target                      Dependencies\n#   ------                      ------------\n#   buildtestspart0             test1, test2\n#   buildtestspart1             test3, test4\n#   buildtestspart2             test5, test6, test7\n#\nmacro(ei_split_testsuite num_splits)\n  get_property(EIGEN_TESTS_LIST GLOBAL PROPERTY EIGEN_TESTS_LIST)\n\n  # Translate EIGEN_TESTS_LIST into a CMake list\n  string(REGEX REPLACE \"\\n\" \" \" EIGEN_TESTS_LIST \"${EIGEN_TESTS_LIST}\")\n  set(EIGEN_TESTS_LIST \"${EIGEN_TESTS_LIST}\")\n  separate_arguments(EIGEN_TESTS_LIST)\n\n  set(eigen_test_count \"0\")\n  foreach(t IN ITEMS ${EIGEN_TESTS_LIST})\n    math(EXPR eigen_test_count \"${eigen_test_count}+1\")\n  endforeach()\n\n  # Get number of tests per target\n  math(EXPR num_tests_per_target \"${eigen_test_count}/${num_splits} - ${eigen_test_count}/${num_splits} % 1\")\n\n  set(test_idx \"0\")\n  math(EXPR target_bound \"${num_splits}-1\")\n  foreach(part RANGE \"0\" \"${target_bound}\")\n    # Create target\n    set(current_target \"buildtestspart${part}\")\n    add_custom_target(\"${current_target}\")\n    math(EXPR upper_bound \"${test_idx} + ${num_tests_per_target} - 1\")\n    foreach(test_idx RANGE \"${test_idx}\" \"${upper_bound}\")\n      list(GET EIGEN_TESTS_LIST \"${test_idx}\" curr_test)\n      add_dependencies(\"${current_target}\" \"${curr_test}\")\n    endforeach()\n    math(EXPR test_idx \"${test_idx} + ${num_tests_per_target}\")\n  endforeach()\n  \n  # Handle the possibly remaining tests\n  math(EXPR test_idx \"${num_splits} * ${num_tests_per_target}\")\n  math(EXPR target_bound \"${eigen_test_count} - 1\")\n  foreach(test_idx RANGE \"${test_idx}\" \"${target_bound}\")\n    list(GET EIGEN_TESTS_LIST \"${test_idx}\" curr_test)\n    add_dependencies(\"${current_target}\" \"${curr_test}\")\n  endforeach()\nendmacro(ei_split_testsuite num_splits)\n\n# Defines the custom command buildsmoketests to build a number of tests\n# specified in smoke_test_list.\n# \n# Test in smoke_test_list can be either test targets (e.g. packetmath) or\n# subtests targets (e.g. packetmath_2). If any of the test are not available\n# in the current configuration they are just skipped. \n#\n# All tests added via this macro are labeled with the smoketest label. This\n# allows running smoketests only using ctest.\n#\n# Smoke tests are intended to be run before the whole test suite is invoked,\n# e.g., to smoke test patches.\nmacro(ei_add_smoke_tests smoke_test_list)\n  # Set the build target to build smoketests\n  set(buildtarget \"buildsmoketests\")\n  add_custom_target(\"${buildtarget}\")\n\n  # Get list of all tests and translate it into a CMake list\n  get_property(EIGEN_TESTS_LIST GLOBAL PROPERTY EIGEN_TESTS_LIST)\n  string(REGEX REPLACE \"\\n\" \" \" EIGEN_TESTS_LIST \"${EIGEN_TESTS_LIST}\")\n  set(EIGEN_TESTS_LIST \"${EIGEN_TESTS_LIST}\")\n  separate_arguments(EIGEN_TESTS_LIST)\n\n  # Check if the test in smoke_test_list is a currently valid test target\n  foreach(test IN ITEMS ${smoke_test_list})\n    # Add tests in smoke_test_list to our smoke test target but only if the test\n    # is currently available, i.e., is in EIGEN_SUBTESTS_LIST\n    if (\"${test}\" IN_LIST EIGEN_TESTS_LIST)\n      add_dependencies(\"${buildtarget}\" \"${test}\")\n      # In the case of a test we match all subtests\n      set(ctest_regex \"${ctest_regex}^${test}_[0-9]+$$|\")\n    endif()\n  endforeach()\n\n  # Get list of all subtests and translate it into a CMake list\n  get_property(EIGEN_SUBTESTS_LIST GLOBAL PROPERTY EIGEN_SUBTESTS_LIST)\n  string(REGEX REPLACE \"\\n\" \" \" EIGEN_SUBTESTS_LIST \"${EIGEN_SUBTESTS_LIST}\")\n  set(EIGEN_SUBTESTS_LIST \"${EIGEN_SUBTESTS_LIST}\")\n  separate_arguments(EIGEN_SUBTESTS_LIST)\n\n  # Check if the test in smoke_test_list is a currently valid subtest target\n  foreach(test IN ITEMS ${smoke_test_list})\n    # Add tests in smoke_test_list to our smoke test target but only if the test\n    # is currently available, i.e., is in EIGEN_SUBTESTS_LIST\n    if (\"${test}\" IN_LIST EIGEN_SUBTESTS_LIST)\n      add_dependencies(\"${buildtarget}\" \"${test}\")\n      # Add label smoketest to be able to run smoketests using ctest\n      get_property(test_labels TEST ${test} PROPERTY LABELS)\n      set_property(TEST ${test} PROPERTY LABELS \"${test_labels};smoketest\")\n    endif()\n  endforeach()\nendmacro(ei_add_smoke_tests)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/EigenUninstall.cmake",
    "content": "################ CMake Uninstall Template #######################\n# CMake Template file for uninstallation of files\n# mentioned in 'install_manifest.txt'\n#\n# Used by uinstall target\n#################################################################\n\nset(MANIFEST \"${CMAKE_CURRENT_BINARY_DIR}/install_manifest.txt\")\n\nif(EXISTS ${MANIFEST})\n  message(STATUS \"============== Uninstalling Eigen  ===================\")\n\n  file(STRINGS ${MANIFEST} files)\n  foreach(file ${files})\n    if(EXISTS ${file})\n      message(STATUS \"Removing file: '${file}'\")\n\n      execute_process(\n        COMMAND ${CMAKE_COMMAND} -E remove ${file}\n        OUTPUT_VARIABLE rm_out\n        RESULT_VARIABLE rm_retval\n        )\n\n      if(NOT \"${rm_retval}\" STREQUAL 0)\n        message(FATAL_ERROR \"Failed to remove file: '${file}'.\")\n      endif()\n    else()\n      message(STATUS \"File '${file}' does not exist.\")\n    endif()\n  endforeach()\n\n  message(STATUS \"========== Finished Uninstalling Eigen  ==============\")\nelse()\n  message(STATUS \"Cannot find install manifest: '${MANIFEST}'\")\n  message(STATUS \"Probably make install has not been performed\")\n  message(STATUS \"   or install_manifest.txt has been deleted.\")\nendif()\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindAdolc.cmake",
    "content": "\nif (ADOLC_INCLUDES AND ADOLC_LIBRARIES)\n  set(ADOLC_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(ADOLC_INCLUDES\n  NAMES adolc/adtl.h\n  PATHS $ENV{ADOLCDIR} $ENV{ADOLCDIR}/include ${INCLUDE_INSTALL_DIR}\n)\n\nfind_library(ADOLC_LIBRARIES \n  adolc \n  PATHS $ENV{ADOLCDIR} ${LIB_INSTALL_DIR} \n  PATH_SUFFIXES lib lib64)\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(Adolc DEFAULT_MSG\n                                  ADOLC_INCLUDES ADOLC_LIBRARIES)\n\nmark_as_advanced(ADOLC_INCLUDES ADOLC_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindBLAS.cmake",
    "content": "###\n#\n# @copyright (c) 2009-2014 The University of Tennessee and The University\n#                          of Tennessee Research Foundation.\n#                          All rights reserved.\n# @copyright (c) 2012-2016 Inria. All rights reserved.\n# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved.\n#\n###\n#\n# - Find BLAS library\n# This module finds an installed fortran library that implements the BLAS\n# linear-algebra interface (see http://www.netlib.org/blas/).\n# The list of libraries searched for is taken\n# from the autoconf macro file, acx_blas.m4 (distributed at\n# http://ac-archive.sourceforge.net/ac-archive/acx_blas.html).\n#\n# This module sets the following variables:\n#  BLAS_FOUND - set to true if a library implementing the BLAS interface\n#    is found\n#  BLAS_LINKER_FLAGS - uncached list of required linker flags (excluding -l\n#    and -L).\n#  BLAS_COMPILER_FLAGS - uncached list of required compiler flags (including -I for mkl headers).\n#  BLAS_LIBRARIES - uncached list of libraries (using full path name) to\n#    link against to use BLAS\n#  BLAS95_LIBRARIES - uncached list of libraries (using full path name)\n#    to link against to use BLAS95 interface\n#  BLAS95_FOUND - set to true if a library implementing the BLAS f95 interface\n#    is found\n#  BLA_STATIC  if set on this determines what kind of linkage we do (static)\n#  BLA_VENDOR  if set checks only the specified vendor, if not set checks\n#     all the possibilities\n#  BLAS_VENDOR_FOUND stores the BLAS vendor found \n#  BLA_F95     if set on tries to find the f95 interfaces for BLAS/LAPACK\n# The user can give specific paths where to find the libraries adding cmake\n# options at configure (ex: cmake path/to/project -DBLAS_DIR=path/to/blas):\n#  BLAS_DIR            - Where to find the base directory of blas\n#  BLAS_INCDIR         - Where to find the header files\n#  BLAS_LIBDIR         - Where to find the library files\n# The module can also look for the following environment variables if paths\n# are not given as cmake variable: BLAS_DIR, BLAS_INCDIR, BLAS_LIBDIR\n# For MKL case and if no paths are given as hints, we will try to use the MKLROOT\n# environment variable\n#  BLAS_VERBOSE Print some additional information during BLAS libraries detection\n##########\n### List of vendors (BLA_VENDOR) valid in this module\n########## List of vendors (BLA_VENDOR) valid in this module\n##  Open (for OpenBlas), Eigen (for EigenBlas), Goto, ATLAS PhiPACK,\n##  CXML, DXML, SunPerf, SCSL, SGIMATH, IBMESSL, IBMESSLMT\n##  Intel10_32 (intel mkl v10 32 bit), Intel10_64lp (intel mkl v10 64 bit,lp thread model, lp64 model),\n##  Intel10_64lp_seq (intel mkl v10 64 bit,sequential code, lp64 model),\n##  Intel( older versions of mkl 32 and 64 bit),\n##  ACML, ACML_MP, ACML_GPU, Apple, NAS, Generic\n# C/CXX should be enabled to use Intel mkl\n###\n# We handle different modes to find the dependency\n#\n# - Detection if already installed on the system\n#   - BLAS libraries can be detected from different ways\n#     Here is the order of precedence:\n#     1) we look in cmake variable BLAS_LIBDIR or BLAS_DIR (we guess the libdirs) if defined\n#     2) we look in environment variable BLAS_LIBDIR or BLAS_DIR (we guess the libdirs) if defined\n#     3) we look in common environnment variables depending on the system (INCLUDE, C_INCLUDE_PATH, CPATH - LIB, DYLD_LIBRARY_PATH, LD_LIBRARY_PATH)\n#     4) we look in common system paths depending on the system, see for example paths contained in the following cmake variables:\n#       - CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES, CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES\n#       - CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES, CMAKE_C_IMPLICIT_LINK_DIRECTORIES\n#\n\n#=============================================================================\n# Copyright 2007-2009 Kitware, Inc.\n#\n# Distributed under the OSI-approved BSD License (the \"License\");\n# see accompanying file Copyright.txt for details.\n#\n# This software is distributed WITHOUT ANY WARRANTY; without even the\n# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.\n# See the License for more information.\n#=============================================================================\n# (To distribute this file outside of CMake, substitute the full\n#  License text for the above reference.)\n\n## Some macros to print status when search for headers and libs\n# This macro informs why the _lib_to_find file has not been found\nmacro(Print_Find_Library_Blas_Status _libname _lib_to_find)\n\n  # save _libname upper/lower case\n  string(TOUPPER ${_libname} LIBNAME)\n  string(TOLOWER ${_libname} libname)\n\n  # print status\n  #message(\" \")\n  if(${LIBNAME}_LIBDIR)\n    message(\"${Yellow}${LIBNAME}_LIBDIR is defined but ${_lib_to_find}\"\n      \"has not been found in ${ARGN}${ColourReset}\")\n  else()\n    if(${LIBNAME}_DIR)\n      message(\"${Yellow}${LIBNAME}_DIR is defined but ${_lib_to_find}\"\n\t\"has not been found in ${ARGN}${ColourReset}\")\n    else()\n      message(\"${Yellow}${_lib_to_find} not found.\"\n\t\"Nor ${LIBNAME}_DIR neither ${LIBNAME}_LIBDIR\"\n\t\"are defined so that we look for ${_lib_to_find} in\"\n\t\"system paths (Linux: LD_LIBRARY_PATH, Windows: LIB,\"\n\t\"Mac: DYLD_LIBRARY_PATH,\"\n\t\"CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES,\"\n\t\"CMAKE_C_IMPLICIT_LINK_DIRECTORIES)${ColourReset}\")\n      if(_lib_env)\n\tmessage(\"${Yellow}${_lib_to_find} has not been found in\"\n\t  \"${_lib_env}${ColourReset}\")\n      endif()\n    endif()\n  endif()\n  message(\"${BoldYellow}Please indicate where to find ${_lib_to_find}. You have three options:\\n\"\n    \"- Option 1: Provide the Installation directory of BLAS library with cmake option: -D${LIBNAME}_DIR=your/path/to/${libname}/\\n\"\n    \"- Option 2: Provide the directory where to find the library with cmake option: -D${LIBNAME}_LIBDIR=your/path/to/${libname}/lib/\\n\"\n    \"- Option 3: Update your environment variable (Linux: LD_LIBRARY_PATH, Windows: LIB, Mac: DYLD_LIBRARY_PATH)\\n\"\n    \"- Option 4: If your library provides a PkgConfig file, make sure pkg-config finds your library${ColourReset}\")\n\nendmacro()\n\n# This macro informs why the _lib_to_find file has not been found\nmacro(Print_Find_Library_Blas_CheckFunc_Status _name)\n\n  # save _libname upper/lower case\n  string(TOUPPER ${_name} FUNCNAME)\n  string(TOLOWER ${_name} funcname)\n\n  # print status\n  #message(\" \")\n  message(\"${Red}Libs have been found but check of symbol ${_name} failed \"\n    \"with following libraries ${ARGN}${ColourReset}\")\n  message(\"${BoldRed}Please open your error file CMakeFiles/CMakeError.log\"\n    \"to figure out why it fails${ColourReset}\")\n  #message(\" \")\n\nendmacro()\n\nif (NOT BLAS_FOUND)\n  set(BLAS_DIR \"\" CACHE PATH \"Installation directory of BLAS library\")\n  if (NOT BLAS_FIND_QUIETLY)\n    message(STATUS \"A cache variable, namely BLAS_DIR, has been set to specify the install directory of BLAS\")\n  endif()\nendif()\n\noption(BLAS_VERBOSE \"Print some additional information during BLAS libraries detection\" OFF)\nmark_as_advanced(BLAS_VERBOSE)\n\ninclude(CheckFunctionExists)\ninclude(CheckFortranFunctionExists)\ninclude(CMakeFindDependencyMacro)\n\nset(_blas_ORIG_CMAKE_FIND_LIBRARY_SUFFIXES ${CMAKE_FIND_LIBRARY_SUFFIXES})\n\n# Check the language being used\nget_property( _LANGUAGES_ GLOBAL PROPERTY ENABLED_LANGUAGES )\nif( _LANGUAGES_ MATCHES Fortran AND CMAKE_Fortran_COMPILER)\n  set( _CHECK_FORTRAN TRUE )\nelseif( (_LANGUAGES_ MATCHES C) OR (_LANGUAGES_ MATCHES CXX) )\n  set( _CHECK_FORTRAN FALSE )\nelse()\n  if(BLAS_FIND_REQUIRED)\n    message(FATAL_ERROR \"FindBLAS requires Fortran, C, or C++ to be enabled.\")\n  else()\n    message(STATUS \"Looking for BLAS... - NOT found (Unsupported languages)\")\n    return()\n  endif()\nendif()\n\nmacro(Check_Fortran_Libraries LIBRARIES _prefix _name _flags _list _thread)\n  # This macro checks for the existence of the combination of fortran libraries\n  # given by _list.  If the combination is found, this macro checks (using the\n  # Check_Fortran_Function_Exists macro) whether can link against that library\n  # combination using the name of a routine given by _name using the linker\n  # flags given by _flags.  If the combination of libraries is found and passes\n  # the link test, LIBRARIES is set to the list of complete library paths that\n  # have been found.  Otherwise, LIBRARIES is set to FALSE.\n\n  # N.B. _prefix is the prefix applied to the names of all cached variables that\n  # are generated internally and marked advanced by this macro.\n\n  set(_libdir ${ARGN})\n\n  set(_libraries_work TRUE)\n  set(${LIBRARIES})\n  set(_combined_name)\n  set(ENV_MKLROOT \"$ENV{MKLROOT}\")\n  set(ENV_BLAS_DIR \"$ENV{BLAS_DIR}\")\n  set(ENV_BLAS_LIBDIR \"$ENV{BLAS_LIBDIR}\")\n  if (NOT _libdir)\n    if (BLAS_LIBDIR)\n      list(APPEND _libdir \"${BLAS_LIBDIR}\")\n    elseif (BLAS_DIR)\n      list(APPEND _libdir \"${BLAS_DIR}\")\n      list(APPEND _libdir \"${BLAS_DIR}/lib\")\n      if(\"${CMAKE_SIZEOF_VOID_P}\" EQUAL \"8\")\n\tlist(APPEND _libdir \"${BLAS_DIR}/lib64\")\n\tlist(APPEND _libdir \"${BLAS_DIR}/lib/intel64\")\n      else()\n\tlist(APPEND _libdir \"${BLAS_DIR}/lib32\")\n\tlist(APPEND _libdir \"${BLAS_DIR}/lib/ia32\")\n      endif()\n    elseif(ENV_BLAS_LIBDIR)\n      list(APPEND _libdir \"${ENV_BLAS_LIBDIR}\")\n    elseif(ENV_BLAS_DIR)\n      list(APPEND _libdir \"${ENV_BLAS_DIR}\")\n      list(APPEND _libdir \"${ENV_BLAS_DIR}/lib\")\n      if(\"${CMAKE_SIZEOF_VOID_P}\" EQUAL \"8\")\n\tlist(APPEND _libdir \"${ENV_BLAS_DIR}/lib64\")\n\tlist(APPEND _libdir \"${ENV_BLAS_DIR}/lib/intel64\")\n      else()\n\tlist(APPEND _libdir \"${ENV_BLAS_DIR}/lib32\")\n\tlist(APPEND _libdir \"${ENV_BLAS_DIR}/lib/ia32\")\n      endif()\n    else()\n      if (ENV_MKLROOT)\n\tlist(APPEND _libdir \"${ENV_MKLROOT}/lib\")\n\tif(\"${CMAKE_SIZEOF_VOID_P}\" EQUAL \"8\")\n\t  list(APPEND _libdir \"${ENV_MKLROOT}/lib64\")\n\t  list(APPEND _libdir \"${ENV_MKLROOT}/lib/intel64\")\n\telse()\n\t  list(APPEND _libdir \"${ENV_MKLROOT}/lib32\")\n\t  list(APPEND _libdir \"${ENV_MKLROOT}/lib/ia32\")\n\tendif()\n      endif()\n      if (WIN32)\n\tstring(REPLACE \":\" \";\" _libdir2 \"$ENV{LIB}\")\n      elseif (APPLE)\n\tstring(REPLACE \":\" \";\" _libdir2 \"$ENV{DYLD_LIBRARY_PATH}\")\n      else ()\n\tstring(REPLACE \":\" \";\" _libdir2 \"$ENV{LD_LIBRARY_PATH}\")\n      endif ()\n      list(APPEND _libdir \"${_libdir2}\")\n      list(APPEND _libdir \"${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}\")\n      list(APPEND _libdir \"${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}\")\n    endif()\n  endif ()\n\n  if (BLAS_VERBOSE)\n    message(\"${Cyan}Try to find BLAS libraries: ${_list}\")\n  endif ()\n\n  foreach(_library ${_list})\n    set(_combined_name ${_combined_name}_${_library})\n\n    if(_libraries_work)\n      if (BLA_STATIC)\n\tif (WIN32)\n\t  set(CMAKE_FIND_LIBRARY_SUFFIXES .lib ${CMAKE_FIND_LIBRARY_SUFFIXES})\n\tendif ()\n\tif (APPLE)\n\t  set(CMAKE_FIND_LIBRARY_SUFFIXES .lib ${CMAKE_FIND_LIBRARY_SUFFIXES})\n\telse ()\n\t  set(CMAKE_FIND_LIBRARY_SUFFIXES .a ${CMAKE_FIND_LIBRARY_SUFFIXES})\n\tendif ()\n      else ()\n\tif (CMAKE_SYSTEM_NAME STREQUAL \"Linux\")\n\t  # for ubuntu's libblas3gf and liblapack3gf packages\n\t  set(CMAKE_FIND_LIBRARY_SUFFIXES ${CMAKE_FIND_LIBRARY_SUFFIXES} .so.3gf)\n\tendif ()\n      endif ()\n      find_library(${_prefix}_${_library}_LIBRARY\n\tNAMES ${_library}\n\tHINTS ${_libdir}\n\tNO_DEFAULT_PATH\n\t)\n      mark_as_advanced(${_prefix}_${_library}_LIBRARY)\n      # Print status if not found\n      # -------------------------\n      if (NOT ${_prefix}_${_library}_LIBRARY AND NOT BLAS_FIND_QUIETLY AND BLAS_VERBOSE)\n\tPrint_Find_Library_Blas_Status(blas ${_library} ${_libdir})\n      endif ()\n      set(${LIBRARIES} ${${LIBRARIES}} ${${_prefix}_${_library}_LIBRARY})\n      set(_libraries_work ${${_prefix}_${_library}_LIBRARY})\n    endif()\n  endforeach()\n\n  if(_libraries_work)\n    # Test this combination of libraries.\n    if (CMAKE_SYSTEM_NAME STREQUAL \"Linux\" AND BLA_STATIC)\n      list(INSERT ${LIBRARIES} 0 \"-Wl,--start-group\")\n      list(APPEND ${LIBRARIES} \"-Wl,--end-group\")\n    endif()\n    set(CMAKE_REQUIRED_LIBRARIES \"${_flags};${${LIBRARIES}};${_thread}\")\n    set(CMAKE_REQUIRED_FLAGS \"${BLAS_COMPILER_FLAGS}\")\n    if (BLAS_VERBOSE)\n      message(\"${Cyan}BLAS libs found for BLA_VENDOR ${BLA_VENDOR}.\"\n\t\"Try to compile symbol ${_name} with following libraries:\"\n\t\"${CMAKE_REQUIRED_LIBRARIES}\")\n    endif ()\n    if(NOT BLAS_FOUND)\n      unset(${_prefix}${_combined_name}_WORKS CACHE)\n    endif()\n    if (_CHECK_FORTRAN)\n      if (CMAKE_Fortran_COMPILER_ID STREQUAL \"GNU\")\n\tstring(REPLACE \"mkl_intel_lp64\" \"mkl_gf_lp64\" CMAKE_REQUIRED_LIBRARIES \"${CMAKE_REQUIRED_LIBRARIES}\")\n\tstring(REPLACE \"mkl_intel_ilp64\" \"mkl_gf_ilp64\" CMAKE_REQUIRED_LIBRARIES \"${CMAKE_REQUIRED_LIBRARIES}\")\n      endif()\n      check_fortran_function_exists(\"${_name}\" ${_prefix}${_combined_name}_WORKS)\n    else()\n      check_function_exists(\"${_name}_\" ${_prefix}${_combined_name}_WORKS)\n    endif()\n    mark_as_advanced(${_prefix}${_combined_name}_WORKS)\n    set(_libraries_work ${${_prefix}${_combined_name}_WORKS})\n    # Print status if not found\n    # -------------------------\n    if (NOT _libraries_work AND NOT BLAS_FIND_QUIETLY AND BLAS_VERBOSE)\n      Print_Find_Library_Blas_CheckFunc_Status(${_name} ${CMAKE_REQUIRED_LIBRARIES})\n    endif ()\n    set(CMAKE_REQUIRED_LIBRARIES)\n  endif()\n\n  if(_libraries_work)\n    set(${LIBRARIES} ${${LIBRARIES}} ${_thread})\n  else()\n    set(${LIBRARIES} FALSE)\n  endif()\n\nendmacro()\n\n\nset(BLAS_LINKER_FLAGS)\nset(BLAS_LIBRARIES)\nset(BLAS95_LIBRARIES)\nif ($ENV{BLA_VENDOR} MATCHES \".+\")\n  set(BLA_VENDOR $ENV{BLA_VENDOR})\nelse ()\n  if(NOT BLA_VENDOR)\n    set(BLA_VENDOR \"All\")\n  endif()\nendif ()\n\n#BLAS in intel mkl 10 library? (em64t 64bit)\nif (BLA_VENDOR MATCHES \"Intel*\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES OR BLA_VENDOR MATCHES \"Intel*\")\n    # Looking for include\n    # -------------------\n\n    # Add system include paths to search include\n    # ------------------------------------------\n    unset(_inc_env)\n    set(ENV_MKLROOT \"$ENV{MKLROOT}\")\n    set(ENV_BLAS_DIR \"$ENV{BLAS_DIR}\")\n    set(ENV_BLAS_INCDIR \"$ENV{BLAS_INCDIR}\")\n    if(ENV_BLAS_INCDIR)\n      list(APPEND _inc_env \"${ENV_BLAS_INCDIR}\")\n    elseif(ENV_BLAS_DIR)\n      list(APPEND _inc_env \"${ENV_BLAS_DIR}\")\n      list(APPEND _inc_env \"${ENV_BLAS_DIR}/include\")\n    else()\n      if (ENV_MKLROOT)\n\tlist(APPEND _inc_env \"${ENV_MKLROOT}/include\")\n      endif()\n      # system variables\n      if(WIN32)\n\tstring(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE}\")\n\tlist(APPEND _inc_env \"${_path_env}\")\n      else()\n\tstring(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE}\")\n\tlist(APPEND _inc_env \"${_path_env}\")\n\tstring(REPLACE \":\" \";\" _path_env \"$ENV{C_INCLUDE_PATH}\")\n\tlist(APPEND _inc_env \"${_path_env}\")\n\tstring(REPLACE \":\" \";\" _path_env \"$ENV{CPATH}\")\n\tlist(APPEND _inc_env \"${_path_env}\")\n\tstring(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE_PATH}\")\n\tlist(APPEND _inc_env \"${_path_env}\")\n      endif()\n    endif()\n    list(APPEND _inc_env \"${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}\")\n    list(APPEND _inc_env \"${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}\")\n    list(REMOVE_DUPLICATES _inc_env)\n\n    # set paths where to look for\n    set(PATH_TO_LOOK_FOR \"${_inc_env}\")\n\n    # Try to find the fftw header in the given paths\n    # -------------------------------------------------\n    # call cmake macro to find the header path\n    if(BLAS_INCDIR)\n      set(BLAS_mkl.h_DIRS \"BLAS_mkl.h_DIRS-NOTFOUND\")\n      find_path(BLAS_mkl.h_DIRS\n\tNAMES mkl.h\n\tHINTS ${BLAS_INCDIR})\n    else()\n      if(BLAS_DIR)\n\tset(BLAS_mkl.h_DIRS \"BLAS_mkl.h_DIRS-NOTFOUND\")\n\tfind_path(BLAS_mkl.h_DIRS\n\t  NAMES mkl.h\n\t  HINTS ${BLAS_DIR}\n\t  PATH_SUFFIXES \"include\")\n      else()\n\tset(BLAS_mkl.h_DIRS \"BLAS_mkl.h_DIRS-NOTFOUND\")\n\tfind_path(BLAS_mkl.h_DIRS\n\t  NAMES mkl.h\n\t  HINTS ${PATH_TO_LOOK_FOR})\n      endif()\n    endif()\n    mark_as_advanced(BLAS_mkl.h_DIRS)\n\n    # If found, add path to cmake variable\n    # ------------------------------------\n    if (BLAS_mkl.h_DIRS)\n      set(BLAS_INCLUDE_DIRS \"${BLAS_mkl.h_DIRS}\")\n    else ()\n      set(BLAS_INCLUDE_DIRS \"BLAS_INCLUDE_DIRS-NOTFOUND\")\n      if(NOT BLAS_FIND_QUIETLY)\n\tmessage(STATUS \"Looking for BLAS -- mkl.h not found\")\n      endif()\n    endif()\n\n    if (WIN32)\n      string(REPLACE \":\" \";\" _libdir \"$ENV{LIB}\")\n    elseif (APPLE)\n      string(REPLACE \":\" \";\" _libdir \"$ENV{DYLD_LIBRARY_PATH}\")\n    else ()\n      string(REPLACE \":\" \";\" _libdir \"$ENV{LD_LIBRARY_PATH}\")\n    endif ()\n    list(APPEND _libdir \"${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}\")\n    list(APPEND _libdir \"${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}\")\n    # libiomp5\n    # --------\n    set(OMP_iomp5_LIBRARY \"OMP_iomp5_LIBRARY-NOTFOUND\")\n    find_library(OMP_iomp5_LIBRARY\n      NAMES iomp5\n      HINTS ${_libdir}\n      )\n    mark_as_advanced(OMP_iomp5_LIBRARY)\n    set(OMP_LIB \"\")\n    # libgomp\n    # -------\n    set(OMP_gomp_LIBRARY \"OMP_gomp_LIBRARY-NOTFOUND\")\n    find_library(OMP_gomp_LIBRARY\n      NAMES gomp\n      HINTS ${_libdir}\n      )\n    mark_as_advanced(OMP_gomp_LIBRARY)\n    # choose one or another depending on the compilo\n    if (CMAKE_C_COMPILER_ID STREQUAL \"GNU\")\n      if (OMP_gomp_LIBRARY)\n\tset(OMP_LIB \"${OMP_gomp_LIBRARY}\")\n      endif()\n    else()\n      if (OMP_iomp5_LIBRARY)\n\tset(OMP_LIB \"${OMP_iomp5_LIBRARY}\")\n      endif()\n    endif()\n\n    if (UNIX AND NOT WIN32)\n      # m\n      find_library(M_LIBRARY\n\tNAMES m\n\tHINTS ${_libdir})\n      mark_as_advanced(M_LIBRARY)\n      if(M_LIBRARY)\n\tset(LM \"-lm\")\n      else()\n\tset(LM \"\")\n      endif()\n      # Fortran\n      set(LGFORTRAN \"\")\n      if (CMAKE_C_COMPILER_ID MATCHES \"GNU\")\n\tfind_library(\n\t  FORTRAN_gfortran_LIBRARY\n\t  NAMES gfortran\n\t  HINTS ${_libdir}\n\t  )\n\tmark_as_advanced(FORTRAN_gfortran_LIBRARY)\n\tif (FORTRAN_gfortran_LIBRARY)\n\t  set(LGFORTRAN \"${FORTRAN_gfortran_LIBRARY}\")\n\tendif()\n      elseif (CMAKE_C_COMPILER_ID MATCHES \"Intel\")\n\tfind_library(\n\t  FORTRAN_ifcore_LIBRARY\n\t  NAMES ifcore\n\t  HINTS ${_libdir}\n\t  )\n\tmark_as_advanced(FORTRAN_ifcore_LIBRARY)\n\tif (FORTRAN_ifcore_LIBRARY)\n\t  set(LGFORTRAN \"{FORTRAN_ifcore_LIBRARY}\")\n\tendif()\n      endif()\n      set(BLAS_COMPILER_FLAGS \"\")\n      if (NOT BLA_VENDOR STREQUAL \"Intel10_64lp_seq\")\n\tif (CMAKE_C_COMPILER_ID STREQUAL \"Intel\")\n\t  list(APPEND BLAS_COMPILER_FLAGS \"-openmp\")\n\tendif()\n\tif (CMAKE_C_COMPILER_ID STREQUAL \"GNU\")\n\t  list(APPEND BLAS_COMPILER_FLAGS \"-fopenmp\")\n\tendif()\n      endif()\n      if (CMAKE_C_COMPILER_ID STREQUAL \"GNU\")\n\tif (BLA_VENDOR STREQUAL \"Intel10_32\")\n\t  list(APPEND BLAS_COMPILER_FLAGS \"-m32\")\n\telse()\n\t  list(APPEND BLAS_COMPILER_FLAGS \"-m64\")\n\tendif()\n\tif (NOT BLA_VENDOR STREQUAL \"Intel10_64lp_seq\")\n\t  list(APPEND OMP_LIB \"-ldl\")\n\tendif()\n\tif (ENV_MKLROOT)\n\t  list(APPEND BLAS_COMPILER_FLAGS \"-I${ENV_MKLROOT}/include\")\n\tendif()\n      endif()\n\n      set(additional_flags \"\")\n      if (CMAKE_C_COMPILER_ID STREQUAL \"GNU\" AND CMAKE_SYSTEM_NAME STREQUAL \"Linux\")\n\tset(additional_flags \"-Wl,--no-as-needed\")\n      endif()\n    endif ()\n\n    if (_LANGUAGES_ MATCHES C OR _LANGUAGES_ MATCHES CXX)\n      if(BLAS_FIND_QUIETLY OR NOT BLAS_FIND_REQUIRED)\n\tfind_dependency(Threads)\n      else()\n\tfind_dependency(Threads REQUIRED)\n      endif()\n\n      set(BLAS_SEARCH_LIBS \"\")\n\n      if(BLA_F95)\n\n\tset(BLAS_mkl_SEARCH_SYMBOL SGEMM)\n\tset(_LIBRARIES BLAS95_LIBRARIES)\n\tif (WIN32)\n\t  if (BLA_STATIC)\n\t    set(BLAS_mkl_DLL_SUFFIX \"\")\n\t  else()\n\t    set(BLAS_mkl_DLL_SUFFIX \"_dll\")\n\t  endif()\n\n\t  # Find the main file (32-bit or 64-bit)\n\t  set(BLAS_SEARCH_LIBS_WIN_MAIN \"\")\n\t  if (BLA_VENDOR STREQUAL \"Intel10_32\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS_WIN_MAIN\n\t      \"mkl_blas95${BLAS_mkl_DLL_SUFFIX} mkl_intel_c${BLAS_mkl_DLL_SUFFIX}\")\n\t  endif()\n\t  if (BLA_VENDOR STREQUAL \"Intel10_64lp*\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS_WIN_MAIN\n\t      \"mkl_blas95_lp64${BLAS_mkl_DLL_SUFFIX} mkl_intel_lp64${BLAS_mkl_DLL_SUFFIX}\")\n\t  endif ()\n\n\t  # Add threading/sequential libs\n\t  set(BLAS_SEARCH_LIBS_WIN_THREAD \"\")\n\t  if (BLA_VENDOR STREQUAL \"*_seq\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS_WIN_THREAD\n\t      \"mkl_sequential${BLAS_mkl_DLL_SUFFIX}\")\n\t  endif()\n\t  if (NOT BLA_VENDOR STREQUAL \"*_seq\" OR BLA_VENDOR STREQUAL \"All\")\n\t    # old version\n\t    list(APPEND BLAS_SEARCH_LIBS_WIN_THREAD\n\t      \"libguide40 mkl_intel_thread${BLAS_mkl_DLL_SUFFIX}\")\n\t    # mkl >= 10.3\n\t    list(APPEND BLAS_SEARCH_LIBS_WIN_THREAD\n\t      \"libiomp5md mkl_intel_thread${BLAS_mkl_DLL_SUFFIX}\")\n\t  endif()\n\n\t  # Cartesian product of the above\n\t  foreach (MAIN ${BLAS_SEARCH_LIBS_WIN_MAIN})\n\t    foreach (THREAD ${BLAS_SEARCH_LIBS_WIN_THREAD})\n\t      list(APPEND BLAS_SEARCH_LIBS\n\t\t\"${MAIN} ${THREAD} mkl_core${BLAS_mkl_DLL_SUFFIX}\")\n\t    endforeach()\n\t  endforeach()\n\telse ()\n\t  if (BLA_VENDOR STREQUAL \"Intel10_32\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS\n\t      \"mkl_blas95 mkl_intel mkl_intel_thread mkl_core guide\")\n\t  endif ()\n\t  if (BLA_VENDOR STREQUAL \"Intel10_64lp\" OR BLA_VENDOR STREQUAL \"All\")\n\t    # old version\n\t    list(APPEND BLAS_SEARCH_LIBS\n\t      \"mkl_blas95 mkl_intel_lp64 mkl_intel_thread mkl_core guide\")\n\t    # mkl >= 10.3\n\t    if (CMAKE_C_COMPILER_ID STREQUAL \"Intel\")\n\t      list(APPEND BLAS_SEARCH_LIBS\n\t\t\"mkl_blas95_lp64 mkl_intel_lp64 mkl_intel_thread mkl_core\")\n\t    endif()\n\t    if (CMAKE_C_COMPILER_ID STREQUAL \"GNU\")\n\t      list(APPEND BLAS_SEARCH_LIBS\n\t\t\"mkl_blas95_lp64 mkl_intel_lp64 mkl_gnu_thread mkl_core\")\n\t    endif()\n\t  endif ()\n\t  if (BLA_VENDOR STREQUAL \"Intel10_64lp_seq\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS\n\t      \"mkl_intel_lp64 mkl_sequential mkl_core\")\n\t    if (BLA_VENDOR STREQUAL \"Intel10_64lp_seq\")\n\t      set(OMP_LIB \"\")\n\t    endif()\n\t  endif ()\n\tendif ()\n\n      else ()\n\n\tset(BLAS_mkl_SEARCH_SYMBOL sgemm)\n\tset(_LIBRARIES BLAS_LIBRARIES)\n\tif (WIN32)\n\t  if (BLA_STATIC)\n\t    set(BLAS_mkl_DLL_SUFFIX \"\")\n\t  else()\n\t    set(BLAS_mkl_DLL_SUFFIX \"_dll\")\n\t  endif()\n\n\t  # Find the main file (32-bit or 64-bit)\n\t  set(BLAS_SEARCH_LIBS_WIN_MAIN \"\")\n\t  if (BLA_VENDOR STREQUAL \"Intel10_32\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS_WIN_MAIN\n\t      \"mkl_intel_c${BLAS_mkl_DLL_SUFFIX}\")\n\t  endif()\n\t  if (BLA_VENDOR STREQUAL \"Intel10_64lp*\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS_WIN_MAIN\n\t      \"mkl_intel_lp64${BLAS_mkl_DLL_SUFFIX}\")\n\t  endif ()\n\n\t  # Add threading/sequential libs\n\t  set(BLAS_SEARCH_LIBS_WIN_THREAD \"\")\n\t  if (NOT BLA_VENDOR STREQUAL \"*_seq\" OR BLA_VENDOR STREQUAL \"All\")\n\t    # old version\n\t    list(APPEND BLAS_SEARCH_LIBS_WIN_THREAD\n\t      \"libguide40 mkl_intel_thread${BLAS_mkl_DLL_SUFFIX}\")\n\t    # mkl >= 10.3\n\t    list(APPEND BLAS_SEARCH_LIBS_WIN_THREAD\n\t      \"libiomp5md mkl_intel_thread${BLAS_mkl_DLL_SUFFIX}\")\n\t  endif()\n\t  if (BLA_VENDOR STREQUAL \"*_seq\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS_WIN_THREAD\n\t      \"mkl_sequential${BLAS_mkl_DLL_SUFFIX}\")\n\t  endif()\n\n\t  # Cartesian product of the above\n\t  foreach (MAIN ${BLAS_SEARCH_LIBS_WIN_MAIN})\n\t    foreach (THREAD ${BLAS_SEARCH_LIBS_WIN_THREAD})\n\t      list(APPEND BLAS_SEARCH_LIBS\n\t\t\"${MAIN} ${THREAD} mkl_core${BLAS_mkl_DLL_SUFFIX}\")\n\t    endforeach()\n\t  endforeach()\n\telse ()\n\t  if (BLA_VENDOR STREQUAL \"Intel10_32\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS\n\t      \"mkl_intel mkl_intel_thread mkl_core guide\")\n\t  endif ()\n\t  if (BLA_VENDOR STREQUAL \"Intel10_64lp\" OR BLA_VENDOR STREQUAL \"All\")\n\t    # old version\n\t    list(APPEND BLAS_SEARCH_LIBS\n\t      \"mkl_intel_lp64 mkl_intel_thread mkl_core guide\")\n\t    # mkl >= 10.3\n\t    if (CMAKE_C_COMPILER_ID STREQUAL \"Intel\")\n\t      list(APPEND BLAS_SEARCH_LIBS\n\t\t\"mkl_intel_lp64 mkl_intel_thread mkl_core\")\n\t    endif()\n\t    if (CMAKE_C_COMPILER_ID STREQUAL \"GNU\")\n\t      list(APPEND BLAS_SEARCH_LIBS\n\t\t\"mkl_intel_lp64 mkl_gnu_thread mkl_core\")\n\t    endif()\n\t  endif ()\n\t  if (BLA_VENDOR STREQUAL \"Intel10_64lp_seq\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS\n\t      \"mkl_intel_lp64 mkl_sequential mkl_core\")\n\t    if (BLA_VENDOR STREQUAL \"Intel10_64lp_seq\")\n\t      set(OMP_LIB \"\")\n\t    endif()\n\t  endif ()\n\t  #older vesions of intel mkl libs\n\t  if (BLA_VENDOR STREQUAL \"Intel\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS\n\t      \"mkl\")\n\t    list(APPEND BLAS_SEARCH_LIBS\n\t      \"mkl_ia32\")\n\t    list(APPEND BLAS_SEARCH_LIBS\n\t      \"mkl_em64t\")\n\t  endif ()\n\tendif ()\n\n      endif ()\n\n      foreach (IT ${BLAS_SEARCH_LIBS})\n\tstring(REPLACE \" \" \";\" SEARCH_LIBS ${IT})\n\tif (${_LIBRARIES})\n\telse ()\n\t  check_fortran_libraries(\n\t    ${_LIBRARIES}\n\t    BLAS\n\t    ${BLAS_mkl_SEARCH_SYMBOL}\n\t    \"${additional_flags}\"\n\t    \"${SEARCH_LIBS}\"\n\t    \"${OMP_LIB};${CMAKE_THREAD_LIBS_INIT};${LM}\"\n\t    )\n\t  if(_LIBRARIES)\n\t    set(BLAS_LINKER_FLAGS \"${additional_flags}\")\n\t  endif()\n\tendif()\n      endforeach ()\n      if(NOT BLAS_FIND_QUIETLY)\n        if(${_LIBRARIES})\n          message(STATUS \"Looking for MKL BLAS: found\")\n        else()\n          message(STATUS \"Looking for MKL BLAS: not found\")\n        endif()\n      endif()\n      if (${_LIBRARIES} AND NOT BLAS_VENDOR_FOUND)\n          set (BLAS_VENDOR_FOUND \"Intel MKL\")\n      endif()\n    endif ()\n  endif()\nendif ()\n\n\nif (BLA_VENDOR STREQUAL \"Goto\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    # gotoblas (http://www.tacc.utexas.edu/tacc-projects/gotoblas2)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"goto2\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for Goto BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for Goto BLAS: not found\")\n      endif()\n    endif()\n  endif()\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"Goto\")\n  endif()\n\nendif ()\n\n\n# OpenBlas\nif (BLA_VENDOR STREQUAL \"Open\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    # openblas (http://www.openblas.net/)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"openblas\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for Open BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for Open BLAS: not found\")\n      endif()\n    endif()\n  endif()\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"Openblas\")\n  endif()\n\nendif ()\n\n\n# EigenBlas\nif (BLA_VENDOR STREQUAL \"Eigen\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    # eigenblas (http://eigen.tuxfamily.org/index.php?title=Main_Page)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"eigen_blas\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n\tmessage(STATUS \"Looking for Eigen BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for Eigen BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if(NOT BLAS_LIBRARIES)\n    # eigenblas (http://eigen.tuxfamily.org/index.php?title=Main_Page)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"eigen_blas_static\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for Eigen BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for Eigen BLAS: not found\")\n      endif()\n    endif()\n  endif()\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"Eigen\")\n  endif()\n\nendif ()\n\n\nif (BLA_VENDOR STREQUAL \"ATLAS\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    # BLAS in ATLAS library? (http://math-atlas.sourceforge.net/)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      dgemm\n      \"\"\n      \"f77blas;atlas\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for Atlas BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for Atlas BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"Atlas\")\n  endif()\n\nendif ()\n\n\n# BLAS in PhiPACK libraries? (requires generic BLAS lib, too)\nif (BLA_VENDOR STREQUAL \"PhiPACK\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"sgemm;dgemm;blas\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for PhiPACK BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for PhiPACK BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"PhiPACK\")\n  endif()\n\nendif ()\n\n\n# BLAS in Alpha CXML library?\nif (BLA_VENDOR STREQUAL \"CXML\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"cxml\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for CXML BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for CXML BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"CXML\")\n  endif()\n\nendif ()\n\n\n# BLAS in Alpha DXML library? (now called CXML, see above)\nif (BLA_VENDOR STREQUAL \"DXML\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"dxml\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for DXML BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for DXML BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"DXML\")\n  endif()\n  \nendif ()\n\n\n# BLAS in Sun Performance library?\nif (BLA_VENDOR STREQUAL \"SunPerf\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"-xlic_lib=sunperf\"\n      \"sunperf;sunmath\"\n      \"\"\n      )\n    if(BLAS_LIBRARIES)\n      set(BLAS_LINKER_FLAGS \"-xlic_lib=sunperf\")\n    endif()\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for SunPerf BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for SunPerf BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"SunPerf\")\n  endif()\n\nendif ()\n\n\n# BLAS in SCSL library?  (SGI/Cray Scientific Library)\nif (BLA_VENDOR STREQUAL \"SCSL\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"scsl\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for SCSL BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for SCSL BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"SunPerf\")\n  endif()\n\nendif ()\n\n\n# BLAS in SGIMATH library?\nif (BLA_VENDOR STREQUAL \"SGIMATH\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"complib.sgimath\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for SGIMATH BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for SGIMATH BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"SGIMATH\")\n  endif()\n\nendif ()\n\n\n# BLAS in IBM ESSL library (requires generic BLAS lib, too)\nif (BLA_VENDOR STREQUAL \"IBMESSL\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"essl;xlfmath;xlf90_r;blas\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for IBM ESSL BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for IBM ESSL BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"IBM ESSL\")\n  endif()\n\nendif ()\n\n# BLAS in IBM ESSL_MT library (requires generic BLAS lib, too)\nif (BLA_VENDOR STREQUAL \"IBMESSLMT\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"esslsmp;xlsmp;xlfmath;xlf90_r;blas\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for IBM ESSL MT BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for IBM ESSL MT BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"IBM ESSL MT\")\n  endif()\n\nendif ()\n\n\n#BLAS in acml library?\nif (BLA_VENDOR MATCHES \"ACML.*\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if( ((BLA_VENDOR STREQUAL \"ACML\") AND (NOT BLAS_ACML_LIB_DIRS)) OR\n      ((BLA_VENDOR STREQUAL \"ACML_MP\") AND (NOT BLAS_ACML_MP_LIB_DIRS)) OR\n      ((BLA_VENDOR STREQUAL \"ACML_GPU\") AND (NOT BLAS_ACML_GPU_LIB_DIRS)))\n\n    # try to find acml in \"standard\" paths\n    if( WIN32 )\n      file( GLOB _ACML_ROOT \"C:/AMD/acml*/ACML-EULA.txt\" )\n    else()\n      file( GLOB _ACML_ROOT \"/opt/acml*/ACML-EULA.txt\" )\n    endif()\n    if( WIN32 )\n      file( GLOB _ACML_GPU_ROOT \"C:/AMD/acml*/GPGPUexamples\" )\n    else()\n      file( GLOB _ACML_GPU_ROOT \"/opt/acml*/GPGPUexamples\" )\n    endif()\n    list(GET _ACML_ROOT 0 _ACML_ROOT)\n    list(GET _ACML_GPU_ROOT 0 _ACML_GPU_ROOT)\n\n    if( _ACML_ROOT )\n\n      get_filename_component( _ACML_ROOT ${_ACML_ROOT} PATH )\n      if( SIZEOF_INTEGER EQUAL 8 )\n\tset( _ACML_PATH_SUFFIX \"_int64\" )\n      else()\n\tset( _ACML_PATH_SUFFIX \"\" )\n      endif()\n      if( CMAKE_Fortran_COMPILER_ID STREQUAL \"Intel\" )\n\tset( _ACML_COMPILER32 \"ifort32\" )\n\tset( _ACML_COMPILER64 \"ifort64\" )\n      elseif( CMAKE_Fortran_COMPILER_ID STREQUAL \"SunPro\" )\n\tset( _ACML_COMPILER32 \"sun32\" )\n\tset( _ACML_COMPILER64 \"sun64\" )\n      elseif( CMAKE_Fortran_COMPILER_ID STREQUAL \"PGI\" )\n\tset( _ACML_COMPILER32 \"pgi32\" )\n\tif( WIN32 )\n\t  set( _ACML_COMPILER64 \"win64\" )\n\telse()\n\t  set( _ACML_COMPILER64 \"pgi64\" )\n\tendif()\n      elseif( CMAKE_Fortran_COMPILER_ID STREQUAL \"Open64\" )\n\t# 32 bit builds not supported on Open64 but for code simplicity\n\t# We'll just use the same directory twice\n\tset( _ACML_COMPILER32 \"open64_64\" )\n\tset( _ACML_COMPILER64 \"open64_64\" )\n      elseif( CMAKE_Fortran_COMPILER_ID STREQUAL \"NAG\" )\n\tset( _ACML_COMPILER32 \"nag32\" )\n\tset( _ACML_COMPILER64 \"nag64\" )\n      else()\n\tset( _ACML_COMPILER32 \"gfortran32\" )\n\tset( _ACML_COMPILER64 \"gfortran64\" )\n      endif()\n\n      if( BLA_VENDOR STREQUAL \"ACML_MP\" )\n\tset(_ACML_MP_LIB_DIRS\n\t  \"${_ACML_ROOT}/${_ACML_COMPILER32}_mp${_ACML_PATH_SUFFIX}/lib\"\n\t  \"${_ACML_ROOT}/${_ACML_COMPILER64}_mp${_ACML_PATH_SUFFIX}/lib\" )\n      else()\n\tset(_ACML_LIB_DIRS\n\t  \"${_ACML_ROOT}/${_ACML_COMPILER32}${_ACML_PATH_SUFFIX}/lib\"\n\t  \"${_ACML_ROOT}/${_ACML_COMPILER64}${_ACML_PATH_SUFFIX}/lib\" )\n      endif()\n\n    endif()\n\n  elseif(BLAS_${BLA_VENDOR}_LIB_DIRS)\n\n    set(_${BLA_VENDOR}_LIB_DIRS ${BLAS_${BLA_VENDOR}_LIB_DIRS})\n\n  endif()\n\n  if( BLA_VENDOR STREQUAL \"ACML_MP\" )\n    foreach( BLAS_ACML_MP_LIB_DIRS ${_ACML_MP_LIB_DIRS})\n      check_fortran_libraries (\n\tBLAS_LIBRARIES\n\tBLAS\n\tsgemm\n\t\"\" \"acml_mp;acml_mv\" \"\" ${BLAS_ACML_MP_LIB_DIRS}\n\t)\n      if( BLAS_LIBRARIES )\n\tbreak()\n      endif()\n    endforeach()\n  elseif( BLA_VENDOR STREQUAL \"ACML_GPU\" )\n    foreach( BLAS_ACML_GPU_LIB_DIRS ${_ACML_GPU_LIB_DIRS})\n      check_fortran_libraries (\n\tBLAS_LIBRARIES\n\tBLAS\n\tsgemm\n\t\"\" \"acml;acml_mv;CALBLAS\" \"\" ${BLAS_ACML_GPU_LIB_DIRS}\n\t)\n      if( BLAS_LIBRARIES )\n\tbreak()\n      endif()\n    endforeach()\n  else()\n    foreach( BLAS_ACML_LIB_DIRS ${_ACML_LIB_DIRS} )\n      check_fortran_libraries (\n\tBLAS_LIBRARIES\n\tBLAS\n\tsgemm\n\t\"\" \"acml;acml_mv\" \"\" ${BLAS_ACML_LIB_DIRS}\n\t)\n      if( BLAS_LIBRARIES )\n\tbreak()\n      endif()\n    endforeach()\n  endif()\n\n  # Either acml or acml_mp should be in LD_LIBRARY_PATH but not both\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"acml;acml_mv\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for ACML BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for ACML BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"acml_mp;acml_mv\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for ACML BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for ACML BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"acml;acml_mv;CALBLAS\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for ACML BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for ACML BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"ACML\")\n  endif()\n\nendif () # ACML\n\n\n# Apple BLAS library?\nif (BLA_VENDOR STREQUAL \"Apple\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      dgemm\n      \"\"\n      \"Accelerate\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for Apple BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for Apple BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"Apple Accelerate\")\n  endif()\n\nendif ()\n\n\nif (BLA_VENDOR STREQUAL \"NAS\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if ( NOT BLAS_LIBRARIES )\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      dgemm\n      \"\"\n      \"vecLib\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for NAS BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for NAS BLAS: not found\")\n      endif()\n    endif()\n  endif ()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"NAS\")\n  endif()\n\nendif ()\n\n\n# Generic BLAS library?\nif (BLA_VENDOR STREQUAL \"Generic\" OR BLA_VENDOR STREQUAL \"All\")\n\n  set(BLAS_SEARCH_LIBS \"blas;blas_LINUX;blas_MAC;blas_WINDOWS;refblas\")\n  foreach (SEARCH_LIB ${BLAS_SEARCH_LIBS})\n    if (BLAS_LIBRARIES)\n    else ()\n      check_fortran_libraries(\n\tBLAS_LIBRARIES\n\tBLAS\n\tsgemm\n\t\"\"\n\t\"${SEARCH_LIB}\"\n\t\"${LGFORTRAN}\"\n\t)\n      if(NOT BLAS_FIND_QUIETLY)\n\tif(BLAS_LIBRARIES)\n\t  message(STATUS \"Looking for Generic BLAS: found\")\n\telse()\n\t  message(STATUS \"Looking for Generic BLAS: not found\")\n\tendif()\n      endif()\n    endif()\n  endforeach ()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"Netlib or other Generic libblas\")\n  endif()\n\nendif ()\n\n\nif(BLA_F95)\n\n  if(BLAS95_LIBRARIES)\n    set(BLAS95_FOUND TRUE)\n  else()\n    set(BLAS95_FOUND FALSE)\n  endif()\n\n  if(NOT BLAS_FIND_QUIETLY)\n    if(BLAS95_FOUND)\n      message(STATUS \"A library with BLAS95 API found.\")\n      message(STATUS \"BLAS_LIBRARIES ${BLAS_LIBRARIES}\")\n    else()\n      message(WARNING \"BLA_VENDOR has been set to ${BLA_VENDOR} but blas 95 libraries could not be found or check of symbols failed.\"\n\t\"\\nPlease indicate where to find blas libraries. You have three options:\\n\"\n\t\"- Option 1: Provide the installation directory of BLAS library with cmake option: -DBLAS_DIR=your/path/to/blas\\n\"\n\t\"- Option 2: Provide the directory where to find BLAS libraries with cmake option: -DBLAS_LIBDIR=your/path/to/blas/libs\\n\"\n\t\"- Option 3: Update your environment variable (Linux: LD_LIBRARY_PATH, Windows: LIB, Mac: DYLD_LIBRARY_PATH)\\n\"\n\t\"\\nTo follow libraries detection more precisely you can activate a verbose mode with -DBLAS_VERBOSE=ON at cmake configure.\"\n\t\"\\nYou could also specify a BLAS vendor to look for by setting -DBLA_VENDOR=blas_vendor_name.\"\n\t\"\\nList of possible BLAS vendor: Goto, ATLAS PhiPACK, CXML, DXML, SunPerf, SCSL, SGIMATH, IBMESSL, Intel10_32 (intel mkl v10 32 bit),\"\n\t\"Intel10_64lp (intel mkl v10 64 bit, lp thread model, lp64 model), Intel10_64lp_seq (intel mkl v10 64 bit, sequential code, lp64 model),\"\n\t\"Intel( older versions of mkl 32 and 64 bit), ACML, ACML_MP, ACML_GPU, Apple, NAS, Generic\")\n      if(BLAS_FIND_REQUIRED)\n\tmessage(FATAL_ERROR\n\t  \"A required library with BLAS95 API not found. Please specify library location.\")\n      else()\n\tmessage(STATUS\n\t  \"A library with BLAS95 API not found. Please specify library location.\")\n      endif()\n    endif()\n  endif()\n\n  set(BLAS_FOUND TRUE)\n  set(BLAS_LIBRARIES \"${BLAS95_LIBRARIES}\")\n\nelse()\n\n  if(BLAS_LIBRARIES)\n    set(BLAS_FOUND TRUE)\n  else()\n    set(BLAS_FOUND FALSE)\n  endif()\n\n  if(NOT BLAS_FIND_QUIETLY)\n    if(BLAS_FOUND)\n      message(STATUS \"A library with BLAS API found.\")\n      message(STATUS \"BLAS_LIBRARIES ${BLAS_LIBRARIES}\")\n    else()\n      message(WARNING \"BLA_VENDOR has been set to ${BLA_VENDOR} but blas libraries could not be found or check of symbols failed.\"\n\t\"\\nPlease indicate where to find blas libraries. You have three options:\\n\"\n\t\"- Option 1: Provide the installation directory of BLAS library with cmake option: -DBLAS_DIR=your/path/to/blas\\n\"\n\t\"- Option 2: Provide the directory where to find BLAS libraries with cmake option: -DBLAS_LIBDIR=your/path/to/blas/libs\\n\"\n\t\"- Option 3: Update your environment variable (Linux: LD_LIBRARY_PATH, Windows: LIB, Mac: DYLD_LIBRARY_PATH)\\n\"\n\t\"\\nTo follow libraries detection more precisely you can activate a verbose mode with -DBLAS_VERBOSE=ON at cmake configure.\"\n\t\"\\nYou could also specify a BLAS vendor to look for by setting -DBLA_VENDOR=blas_vendor_name.\"\n\t\"\\nList of possible BLAS vendor: Goto, ATLAS PhiPACK, CXML, DXML, SunPerf, SCSL, SGIMATH, IBMESSL, Intel10_32 (intel mkl v10 32 bit),\"\n\t\"Intel10_64lp (intel mkl v10 64 bit, lp thread model, lp64 model), Intel10_64lp_seq (intel mkl v10 64 bit, sequential code, lp64 model),\"\n\t\"Intel( older versions of mkl 32 and 64 bit), ACML, ACML_MP, ACML_GPU, Apple, NAS, Generic\")\n      if(BLAS_FIND_REQUIRED)\n\tmessage(FATAL_ERROR\n\t  \"A required library with BLAS API not found. Please specify library location.\")\n      else()\n\tmessage(STATUS\n\t  \"A library with BLAS API not found. Please specify library location.\")\n      endif()\n    endif()\n  endif()\n\nendif()\n\nset(CMAKE_FIND_LIBRARY_SUFFIXES ${_blas_ORIG_CMAKE_FIND_LIBRARY_SUFFIXES})\n\nif (BLAS_FOUND)\n  list(GET BLAS_LIBRARIES 0 first_lib)\n  get_filename_component(first_lib_path \"${first_lib}\" PATH)\n  if (${first_lib_path} MATCHES \"(/lib(32|64)?$)|(/lib/intel64$|/lib/ia32$)\")\n    string(REGEX REPLACE \"(/lib(32|64)?$)|(/lib/intel64$|/lib/ia32$)\" \"\" not_cached_dir \"${first_lib_path}\")\n    set(BLAS_DIR_FOUND \"${not_cached_dir}\" CACHE PATH \"Installation directory of BLAS library\" FORCE)\n  else()\n    set(BLAS_DIR_FOUND \"${first_lib_path}\" CACHE PATH \"Installation directory of BLAS library\" FORCE)\n  endif()\nendif()\nmark_as_advanced(BLAS_DIR)\nmark_as_advanced(BLAS_DIR_FOUND)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindBLASEXT.cmake",
    "content": "###\n#\n# @copyright (c) 2009-2014 The University of Tennessee and The University\n#                          of Tennessee Research Foundation.\n#                          All rights reserved.\n# @copyright (c) 2012-2016 Inria. All rights reserved.\n# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved.\n#\n###\n#\n# - Find BLAS EXTENDED for MORSE projects: find include dirs and libraries\n#\n# This module allows to find BLAS libraries by calling the official FindBLAS module\n# and handles the creation of different library lists whether the user wishes to link\n# with a sequential BLAS or a multihreaded (BLAS_SEQ_LIBRARIES and BLAS_PAR_LIBRARIES).\n# BLAS is detected with a FindBLAS call then if the BLAS vendor is Intel10_64lp, ACML\n# or IBMESSLMT then the module attempts to find the corresponding multithreaded libraries.\n#\n# The following variables have been added to manage links with sequential or multithreaded\n# versions:\n#  BLAS_INCLUDE_DIRS  - BLAS include directories\n#  BLAS_LIBRARY_DIRS  - Link directories for BLAS libraries\n#  BLAS_SEQ_LIBRARIES - BLAS component libraries to be linked (sequential)\n#  BLAS_PAR_LIBRARIES - BLAS component libraries to be linked (multithreaded)\n\n#=============================================================================\n# Copyright 2012-2013 Inria\n# Copyright 2012-2013 Emmanuel Agullo\n# Copyright 2012-2013 Mathieu Faverge\n# Copyright 2012      Cedric Castagnede\n# Copyright 2013-2016 Florent Pruvost\n#\n# Distributed under the OSI-approved BSD License (the \"License\");\n# see accompanying file MORSE-Copyright.txt for details.\n#\n# This software is distributed WITHOUT ANY WARRANTY; without even the\n# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.\n# See the License for more information.\n#=============================================================================\n# (To distribute this file outside of Morse, substitute the full\n#  License text for the above reference.)\n\n# macro to factorize this call\ninclude(CMakeFindDependencyMacro)\nmacro(find_package_blas)\n  if(BLASEXT_FIND_REQUIRED)\n    if(BLASEXT_FIND_QUIETLY)\n      find_dependency(BLAS REQUIRED QUIET)\n    else()\n      find_dependency(BLAS REQUIRED)\n    endif()\n  else()\n    if(BLASEXT_FIND_QUIETLY)\n      find_dependency(BLAS QUIET)\n    else()\n      find_dependency(BLAS)\n    endif()\n  endif()\nendmacro()\n\n# add a cache variable to let the user specify the BLAS vendor\nset(BLA_VENDOR \"\" CACHE STRING \"list of possible BLAS vendor:\n    Open, Eigen, Goto, ATLAS PhiPACK, CXML, DXML, SunPerf, SCSL, SGIMATH, IBMESSL, IBMESSLMT,\n    Intel10_32 (intel mkl v10 32 bit),\n    Intel10_64lp (intel mkl v10 64 bit, lp thread model, lp64 model),\n    Intel10_64lp_seq (intel mkl v10 64 bit, sequential code, lp64 model),\n    Intel( older versions of mkl 32 and 64 bit),\n    ACML, ACML_MP, ACML_GPU, Apple, NAS, Generic\")\n\nif(NOT BLASEXT_FIND_QUIETLY)\n  message(STATUS \"In FindBLASEXT\")\n  message(STATUS \"If you want to force the use of one specific library, \"\n    \"\\n   please specify the BLAS vendor by setting -DBLA_VENDOR=blas_vendor_name\"\n    \"\\n   at cmake configure.\")\n  message(STATUS \"List of possible BLAS vendor: Goto, ATLAS PhiPACK, CXML, \"\n    \"\\n   DXML, SunPerf, SCSL, SGIMATH, IBMESSL, IBMESSLMT, Intel10_32 (intel mkl v10 32 bit),\"\n    \"\\n   Intel10_64lp (intel mkl v10 64 bit, lp thread model, lp64 model),\"\n    \"\\n   Intel10_64lp_seq (intel mkl v10 64 bit, sequential code, lp64 model),\"\n    \"\\n   Intel( older versions of mkl 32 and 64 bit),\"\n    \"\\n   ACML, ACML_MP, ACML_GPU, Apple, NAS, Generic\")\nendif()\n\nif (NOT BLAS_FOUND)\n  # First try to detect two cases:\n  # 1: only SEQ libs are handled\n  # 2: both SEQ and PAR libs are handled\n  find_package_blas()\nendif ()\n\n# detect the cases where SEQ and PAR libs are handled\nif(BLA_VENDOR STREQUAL \"All\" AND\n    (BLAS_mkl_core_LIBRARY OR BLAS_mkl_core_dll_LIBRARY)\n    )\n  set(BLA_VENDOR \"Intel\")\n  if(BLAS_mkl_intel_LIBRARY)\n    set(BLA_VENDOR \"Intel10_32\")\n  endif()\n  if(BLAS_mkl_intel_lp64_LIBRARY)\n    set(BLA_VENDOR \"Intel10_64lp\")\n  endif()\n  if(NOT BLASEXT_FIND_QUIETLY)\n    message(STATUS \"A BLAS library has been found (${BLAS_LIBRARIES}) but we\"\n      \"\\n   have also potentially detected some multithreaded BLAS libraries from the MKL.\"\n      \"\\n   We try to find both libraries lists (Sequential/Multithreaded).\")\n  endif()\n  set(BLAS_FOUND \"\")\nelseif(BLA_VENDOR STREQUAL \"All\" AND BLAS_acml_LIBRARY)\n  set(BLA_VENDOR \"ACML\")\n  if(NOT BLASEXT_FIND_QUIETLY)\n    message(STATUS \"A BLAS library has been found (${BLAS_LIBRARIES}) but we\"\n      \"\\n   have also potentially detected some multithreaded BLAS libraries from the ACML.\"\n      \"\\n   We try to find both libraries lists (Sequential/Multithreaded).\")\n  endif()\n  set(BLAS_FOUND \"\")\nelseif(BLA_VENDOR STREQUAL \"All\" AND BLAS_essl_LIBRARY)\n  set(BLA_VENDOR \"IBMESSL\")\n  if(NOT BLASEXT_FIND_QUIETLY)\n    message(STATUS \"A BLAS library has been found (${BLAS_LIBRARIES}) but we\"\n      \"\\n   have also potentially detected some multithreaded BLAS libraries from the ESSL.\"\n      \"\\n   We try to find both libraries lists (Sequential/Multithreaded).\")\n  endif()\n  set(BLAS_FOUND \"\")\nendif()\n\n# Intel case\nif(BLA_VENDOR MATCHES \"Intel*\")\n\n  ###\n  # look for include path if the BLAS vendor is Intel\n  ###\n\n  # gather system include paths\n  unset(_inc_env)\n  if(WIN32)\n    string(REPLACE \":\" \";\" _inc_env \"$ENV{INCLUDE}\")\n  else()\n    string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{C_INCLUDE_PATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{CPATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE_PATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n  endif()\n  list(APPEND _inc_env \"${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}\")\n  list(APPEND _inc_env \"${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}\")\n  set(ENV_MKLROOT \"$ENV{MKLROOT}\")\n  if (ENV_MKLROOT)\n    list(APPEND _inc_env \"${ENV_MKLROOT}/include\")\n  endif()\n  list(REMOVE_DUPLICATES _inc_env)\n\n  # find mkl.h inside known include paths\n  set(BLAS_mkl.h_INCLUDE_DIRS \"BLAS_mkl.h_INCLUDE_DIRS-NOTFOUND\")\n  if(BLAS_INCDIR)\n    set(BLAS_mkl.h_INCLUDE_DIRS \"BLAS_mkl.h_INCLUDE_DIRS-NOTFOUND\")\n    find_path(BLAS_mkl.h_INCLUDE_DIRS\n      NAMES mkl.h\n      HINTS ${BLAS_INCDIR})\n  else()\n    if(BLAS_DIR)\n      set(BLAS_mkl.h_INCLUDE_DIRS \"BLAS_mkl.h_INCLUDE_DIRS-NOTFOUND\")\n      find_path(BLAS_mkl.h_INCLUDE_DIRS\n\tNAMES mkl.h\n\tHINTS ${BLAS_DIR}\n\tPATH_SUFFIXES include)\n    else()\n      set(BLAS_mkl.h_INCLUDE_DIRS \"BLAS_mkl.h_INCLUDE_DIRS-NOTFOUND\")\n      find_path(BLAS_mkl.h_INCLUDE_DIRS\n\tNAMES mkl.h\n\tHINTS ${_inc_env})\n    endif()\n  endif()\n  mark_as_advanced(BLAS_mkl.h_INCLUDE_DIRS)\n  ## Print status if not found\n  ## -------------------------\n  #if (NOT BLAS_mkl.h_INCLUDE_DIRS AND MORSE_VERBOSE)\n  #    Print_Find_Header_Status(blas mkl.h)\n  #endif ()\n  set(BLAS_INCLUDE_DIRS \"\")\n  if(BLAS_mkl.h_INCLUDE_DIRS)\n    list(APPEND BLAS_INCLUDE_DIRS \"${BLAS_mkl.h_INCLUDE_DIRS}\" )\n  endif()\n\n  ###\n  # look for libs\n  ###\n  # if Intel 10 64 bit -> look for sequential and multithreaded versions\n  if(BLA_VENDOR MATCHES \"Intel10_64lp*\")\n\n    ## look for the sequential version\n    set(BLA_VENDOR \"Intel10_64lp_seq\")\n    if(NOT BLASEXT_FIND_QUIETLY)\n      message(STATUS \"Look for the sequential version Intel10_64lp_seq\")\n    endif()\n    find_package_blas()\n    if(BLAS_FOUND)\n      set(BLAS_SEQ_LIBRARIES \"${BLAS_LIBRARIES}\")\n    else()\n      set(BLAS_SEQ_LIBRARIES \"${BLAS_SEQ_LIBRARIES-NOTFOUND}\")\n    endif()\n\n    ## look for the multithreaded version\n    set(BLA_VENDOR \"Intel10_64lp\")\n    if(NOT BLASEXT_FIND_QUIETLY)\n      message(STATUS \"Look for the multithreaded version Intel10_64lp\")\n    endif()\n    find_package_blas()\n    if(BLAS_FOUND)\n      set(BLAS_PAR_LIBRARIES \"${BLAS_LIBRARIES}\")\n    else()\n      set(BLAS_PAR_LIBRARIES \"${BLAS_PAR_LIBRARIES-NOTFOUND}\")\n    endif()\n\n  else()\n\n    if(BLAS_FOUND)\n      set(BLAS_SEQ_LIBRARIES \"${BLAS_LIBRARIES}\")\n    else()\n      set(BLAS_SEQ_LIBRARIES \"${BLAS_SEQ_LIBRARIES-NOTFOUND}\")\n    endif()\n\n  endif()\n\n  # ACML case\nelseif(BLA_VENDOR MATCHES \"ACML*\")\n\n  ## look for the sequential version\n  set(BLA_VENDOR \"ACML\")\n  find_package_blas()\n  if(BLAS_FOUND)\n    set(BLAS_SEQ_LIBRARIES \"${BLAS_LIBRARIES}\")\n  else()\n    set(BLAS_SEQ_LIBRARIES \"${BLAS_SEQ_LIBRARIES-NOTFOUND}\")\n  endif()\n\n  ## look for the multithreaded version\n  set(BLA_VENDOR \"ACML_MP\")\n  find_package_blas()\n  if(BLAS_FOUND)\n    set(BLAS_PAR_LIBRARIES \"${BLAS_LIBRARIES}\")\n  else()\n    set(BLAS_PAR_LIBRARIES \"${BLAS_PAR_LIBRARIES-NOTFOUND}\")\n  endif()\n\n  # IBMESSL case\nelseif(BLA_VENDOR MATCHES \"IBMESSL*\")\n\n  ## look for the sequential version\n  set(BLA_VENDOR \"IBMESSL\")\n  find_package_blas()\n  if(BLAS_FOUND)\n    set(BLAS_SEQ_LIBRARIES \"${BLAS_LIBRARIES}\")\n  else()\n    set(BLAS_SEQ_LIBRARIES \"${BLAS_SEQ_LIBRARIES-NOTFOUND}\")\n  endif()\n\n  ## look for the multithreaded version\n  set(BLA_VENDOR \"IBMESSLMT\")\n  find_package_blas()\n  if(BLAS_FOUND)\n    set(BLAS_PAR_LIBRARIES \"${BLAS_LIBRARIES}\")\n  else()\n    set(BLAS_PAR_LIBRARIES \"${BLAS_PAR_LIBRARIES-NOTFOUND}\")\n  endif()\n\nelse()\n\n  if(BLAS_FOUND)\n    # define the SEQ libs as the BLAS_LIBRARIES\n    set(BLAS_SEQ_LIBRARIES \"${BLAS_LIBRARIES}\")\n  else()\n    set(BLAS_SEQ_LIBRARIES \"${BLAS_SEQ_LIBRARIES-NOTFOUND}\")\n  endif()\n  set(BLAS_PAR_LIBRARIES \"${BLAS_PAR_LIBRARIES-NOTFOUND}\")\n\nendif()\n\n\nif(BLAS_SEQ_LIBRARIES)\n  set(BLAS_LIBRARIES \"${BLAS_SEQ_LIBRARIES}\")\nendif()\n\n# extract libs paths\n# remark: because it is not given by find_package(BLAS)\nset(BLAS_LIBRARY_DIRS \"\")\nstring(REPLACE \" \" \";\" BLAS_LIBRARIES \"${BLAS_LIBRARIES}\")\nforeach(blas_lib ${BLAS_LIBRARIES})\n  if (EXISTS \"${blas_lib}\")\n    get_filename_component(a_blas_lib_dir \"${blas_lib}\" PATH)\n    list(APPEND BLAS_LIBRARY_DIRS \"${a_blas_lib_dir}\" )\n  else()\n    string(REPLACE \"-L\" \"\" blas_lib \"${blas_lib}\")\n    if (EXISTS \"${blas_lib}\")\n      list(APPEND BLAS_LIBRARY_DIRS \"${blas_lib}\" )\n    else()\n      get_filename_component(a_blas_lib_dir \"${blas_lib}\" PATH)\n      if (EXISTS \"${a_blas_lib_dir}\")\n\tlist(APPEND BLAS_LIBRARY_DIRS \"${a_blas_lib_dir}\" )\n      endif()\n    endif()\n  endif()\nendforeach()\nif (BLAS_LIBRARY_DIRS)\n  list(REMOVE_DUPLICATES BLAS_LIBRARY_DIRS)\nendif ()\n\n# check that BLAS has been found\n# ---------------------------------\ninclude(FindPackageHandleStandardArgs)\nif(BLA_VENDOR MATCHES \"Intel*\")\n  if(BLA_VENDOR MATCHES \"Intel10_64lp*\")\n    if(NOT BLASEXT_FIND_QUIETLY)\n      message(STATUS \"BLAS found is Intel MKL:\"\n\t\"\\n   we manage two lists of libs, one sequential and one parallel if found\"\n\t\"\\n   (see BLAS_SEQ_LIBRARIES and BLAS_PAR_LIBRARIES)\")\n      message(STATUS \"BLAS sequential libraries stored in BLAS_SEQ_LIBRARIES\")\n    endif()\n    find_package_handle_standard_args(BLASEXT DEFAULT_MSG\n      BLAS_SEQ_LIBRARIES\n      BLAS_LIBRARY_DIRS\n      BLAS_INCLUDE_DIRS)\n    if(BLAS_PAR_LIBRARIES)\n      if(NOT BLASEXT_FIND_QUIETLY)\n\tmessage(STATUS \"BLAS parallel libraries stored in BLAS_PAR_LIBRARIES\")\n      endif()\n      find_package_handle_standard_args(BLASEXT DEFAULT_MSG\n\tBLAS_PAR_LIBRARIES)\n    endif()\n  else()\n    if(NOT BLASEXT_FIND_QUIETLY)\n      message(STATUS \"BLAS sequential libraries stored in BLAS_SEQ_LIBRARIES\")\n    endif()\n    find_package_handle_standard_args(BLASEXT DEFAULT_MSG\n      BLAS_SEQ_LIBRARIES\n      BLAS_LIBRARY_DIRS\n      BLAS_INCLUDE_DIRS)\n  endif()\nelseif(BLA_VENDOR MATCHES \"ACML*\")\n  if(NOT BLASEXT_FIND_QUIETLY)\n    message(STATUS \"BLAS found is ACML:\"\n      \"\\n   we manage two lists of libs, one sequential and one parallel if found\"\n      \"\\n   (see BLAS_SEQ_LIBRARIES and BLAS_PAR_LIBRARIES)\")\n    message(STATUS \"BLAS sequential libraries stored in BLAS_SEQ_LIBRARIES\")\n  endif()\n  find_package_handle_standard_args(BLASEXT DEFAULT_MSG\n    BLAS_SEQ_LIBRARIES\n    BLAS_LIBRARY_DIRS)\n  if(BLAS_PAR_LIBRARIES)\n    if(NOT BLASEXT_FIND_QUIETLY)\n      message(STATUS \"BLAS parallel libraries stored in BLAS_PAR_LIBRARIES\")\n    endif()\n    find_package_handle_standard_args(BLASEXT DEFAULT_MSG\n      BLAS_PAR_LIBRARIES)\n  endif()\nelseif(BLA_VENDOR MATCHES \"IBMESSL*\")\n  if(NOT BLASEXT_FIND_QUIETLY)\n    message(STATUS \"BLAS found is ESSL:\"\n      \"\\n   we manage two lists of libs, one sequential and one parallel if found\"\n      \"\\n   (see BLAS_SEQ_LIBRARIES and BLAS_PAR_LIBRARIES)\")\n    message(STATUS \"BLAS sequential libraries stored in BLAS_SEQ_LIBRARIES\")\n  endif()\n  find_package_handle_standard_args(BLASEXT DEFAULT_MSG\n    BLAS_SEQ_LIBRARIES\n    BLAS_LIBRARY_DIRS)\n  if(BLAS_PAR_LIBRARIES)\n    if(NOT BLASEXT_FIND_QUIETLY)\n      message(STATUS \"BLAS parallel libraries stored in BLAS_PAR_LIBRARIES\")\n    endif()\n    find_package_handle_standard_args(BLASEXT DEFAULT_MSG\n      BLAS_PAR_LIBRARIES)\n  endif()\nelse()\n  if(NOT BLASEXT_FIND_QUIETLY)\n    message(STATUS \"BLAS sequential libraries stored in BLAS_SEQ_LIBRARIES\")\n  endif()\n  find_package_handle_standard_args(BLASEXT DEFAULT_MSG\n    BLAS_SEQ_LIBRARIES\n    BLAS_LIBRARY_DIRS)\nendif()\n\n# Callers expect BLAS_FOUND to be set as well.\nset(BLAS_FOUND BLASEXT_FOUND)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindCHOLMOD.cmake",
    "content": "# CHOLMOD lib usually requires linking to a blas and lapack library.\n# It is up to the user of this module to find a BLAS and link to it.\n\nif (CHOLMOD_INCLUDES AND CHOLMOD_LIBRARIES)\n  set(CHOLMOD_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(CHOLMOD_INCLUDES\n  NAMES\n  cholmod.h\n  PATHS\n  $ENV{CHOLMODDIR}\n  ${INCLUDE_INSTALL_DIR}\n  PATH_SUFFIXES\n  suitesparse\n  ufsparse\n)\n\nfind_library(CHOLMOD_LIBRARIES cholmod PATHS $ENV{CHOLMODDIR} ${LIB_INSTALL_DIR})\n\nif(CHOLMOD_LIBRARIES)\n\n  get_filename_component(CHOLMOD_LIBDIR ${CHOLMOD_LIBRARIES} PATH)\n\n  find_library(AMD_LIBRARY amd PATHS ${CHOLMOD_LIBDIR} $ENV{CHOLMODDIR} ${LIB_INSTALL_DIR})\n  if (AMD_LIBRARY)\n    set(CHOLMOD_LIBRARIES ${CHOLMOD_LIBRARIES} ${AMD_LIBRARY})\n  else ()\n    set(CHOLMOD_LIBRARIES FALSE)\n  endif ()\n\nendif()\n\nif(CHOLMOD_LIBRARIES)\n\n  find_library(COLAMD_LIBRARY colamd PATHS ${CHOLMOD_LIBDIR} $ENV{CHOLMODDIR} ${LIB_INSTALL_DIR})\n  if (COLAMD_LIBRARY)\n    set(CHOLMOD_LIBRARIES ${CHOLMOD_LIBRARIES} ${COLAMD_LIBRARY})\n  else ()\n    set(CHOLMOD_LIBRARIES FALSE)\n  endif ()\n\nendif()\n\nif(CHOLMOD_LIBRARIES)\n\n  find_library(CAMD_LIBRARY camd PATHS ${CHOLMOD_LIBDIR} $ENV{CHOLMODDIR} ${LIB_INSTALL_DIR})\n  if (CAMD_LIBRARY)\n    set(CHOLMOD_LIBRARIES ${CHOLMOD_LIBRARIES} ${CAMD_LIBRARY})\n  else ()\n    set(CHOLMOD_LIBRARIES FALSE)\n  endif ()\n\nendif()\n\nif(CHOLMOD_LIBRARIES)\n\n  find_library(CCOLAMD_LIBRARY ccolamd PATHS ${CHOLMOD_LIBDIR} $ENV{CHOLMODDIR} ${LIB_INSTALL_DIR})\n  if (CCOLAMD_LIBRARY)\n    set(CHOLMOD_LIBRARIES ${CHOLMOD_LIBRARIES} ${CCOLAMD_LIBRARY})\n  else ()\n    set(CHOLMOD_LIBRARIES FALSE)\n  endif ()\n\nendif()\n\nif(CHOLMOD_LIBRARIES)\n\n  find_library(CHOLMOD_METIS_LIBRARY metis PATHS ${CHOLMOD_LIBDIR} $ENV{CHOLMODDIR} ${LIB_INSTALL_DIR})\n  if (CHOLMOD_METIS_LIBRARY)\n    set(CHOLMOD_LIBRARIES ${CHOLMOD_LIBRARIES} ${CHOLMOD_METIS_LIBRARY})\n  endif ()\n\nendif()\n\nif(CHOLMOD_LIBRARIES)\n\n  find_library(SUITESPARSE_LIBRARY SuiteSparse PATHS ${CHOLMOD_LIBDIR} $ENV{CHOLMODDIR} ${LIB_INSTALL_DIR})\n  if (SUITESPARSE_LIBRARY)\n    set(CHOLMOD_LIBRARIES ${CHOLMOD_LIBRARIES} ${SUITESPARSE_LIBRARY})\n  endif ()\n  \nendif()\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(CHOLMOD DEFAULT_MSG\n                                  CHOLMOD_INCLUDES CHOLMOD_LIBRARIES)\n\nmark_as_advanced(CHOLMOD_INCLUDES CHOLMOD_LIBRARIES AMD_LIBRARY COLAMD_LIBRARY SUITESPARSE_LIBRARY CAMD_LIBRARY CCOLAMD_LIBRARY CHOLMOD_METIS_LIBRARY)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindComputeCpp.cmake",
    "content": "#.rst:\n# FindComputeCpp\n#---------------\n#\n#   Copyright 2016-2018 Codeplay Software Ltd.\n#\n#   Licensed under the Apache License, Version 2.0 (the \"License\");\n#   you may not use these files except in compliance with the License.\n#   You may obtain a copy of the License at\n#\n#       http://www.apache.org/licenses/LICENSE-2.0\n#\n#\n#   Unless required by applicable law or agreed to in writing, software\n#   distributed under the License is distributed on an \"AS IS\" BASIS,\n#   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#   See the License for the specific language governing permissions and\n#   limitations under the License.\n\n#########################\n#  FindComputeCpp.cmake\n#########################\n#\n#  Tools for finding and building with ComputeCpp.\n#\n#  User must define ComputeCpp_DIR pointing to the ComputeCpp\n#  installation.\n#\n#  Latest version of this file can be found at:\n#    https://github.com/codeplaysoftware/computecpp-sdk\n\ncmake_minimum_required(VERSION 3.4.3)\ninclude(FindPackageHandleStandardArgs)\ninclude(ComputeCppIRMap)\n\nset(COMPUTECPP_USER_FLAGS \"\" CACHE STRING \"User flags for compute++\")\nseparate_arguments(COMPUTECPP_USER_FLAGS)\nmark_as_advanced(COMPUTECPP_USER_FLAGS)\n\nset(COMPUTECPP_BITCODE \"spir64\" CACHE STRING\n  \"Bitcode type to use as SYCL target in compute++\")\nmark_as_advanced(COMPUTECPP_BITCODE)\n\ninclude(CMakeFindDependencyMacro)\nfind_dependency(OpenCL REQUIRED)\n\n# Find ComputeCpp package\n\nif(DEFINED ComputeCpp_DIR)\n  set(computecpp_find_hint ${ComputeCpp_DIR})\nelseif(DEFINED ENV{COMPUTECPP_DIR})\n  set(computecpp_find_hint $ENV{COMPUTECPP_DIR})\nendif()\n\n# Used for running executables on the host\nset(computecpp_host_find_hint ${computecpp_find_hint})\n\nif(CMAKE_CROSSCOMPILING)\n  # ComputeCpp_HOST_DIR is used to find executables that are run on the host\n  if(DEFINED ComputeCpp_HOST_DIR)\n    set(computecpp_host_find_hint ${ComputeCpp_HOST_DIR})\n  elseif(DEFINED ENV{COMPUTECPP_HOST_DIR})\n    set(computecpp_host_find_hint $ENV{COMPUTECPP_HOST_DIR})\n  endif()\nendif()\n\nfind_program(ComputeCpp_DEVICE_COMPILER_EXECUTABLE compute++\n  HINTS ${computecpp_host_find_hint}\n  PATH_SUFFIXES bin\n  NO_SYSTEM_ENVIRONMENT_PATH)\n\nfind_program(ComputeCpp_INFO_EXECUTABLE computecpp_info\n  HINTS ${computecpp_host_find_hint}\n  PATH_SUFFIXES bin\n  NO_SYSTEM_ENVIRONMENT_PATH)\n\nfind_library(COMPUTECPP_RUNTIME_LIBRARY\n  NAMES ComputeCpp ComputeCpp_vs2015\n  HINTS ${computecpp_find_hint}\n  PATH_SUFFIXES lib\n  DOC \"ComputeCpp Runtime Library\")\n\nfind_library(COMPUTECPP_RUNTIME_LIBRARY_DEBUG\n  NAMES ComputeCpp_d ComputeCpp ComputeCpp_vs2015_d\n  HINTS ${computecpp_find_hint}\n  PATH_SUFFIXES lib\n  DOC \"ComputeCpp Debug Runtime Library\")\n\nfind_path(ComputeCpp_INCLUDE_DIRS\n  NAMES \"CL/sycl.hpp\"\n  HINTS ${computecpp_find_hint}/include\n  DOC \"The ComputeCpp include directory\")\nget_filename_component(ComputeCpp_INCLUDE_DIRS ${ComputeCpp_INCLUDE_DIRS} ABSOLUTE)\n\nget_filename_component(computecpp_canonical_root_dir \"${ComputeCpp_INCLUDE_DIRS}/..\" ABSOLUTE)\nset(ComputeCpp_ROOT_DIR \"${computecpp_canonical_root_dir}\" CACHE PATH\n    \"The root of the ComputeCpp install\")\n\nif(NOT ComputeCpp_INFO_EXECUTABLE)\n  message(WARNING \"Can't find computecpp_info - check ComputeCpp_DIR\")\nelse()\n  execute_process(COMMAND ${ComputeCpp_INFO_EXECUTABLE} \"--dump-version\"\n    OUTPUT_VARIABLE ComputeCpp_VERSION\n    RESULT_VARIABLE ComputeCpp_INFO_EXECUTABLE_RESULT OUTPUT_STRIP_TRAILING_WHITESPACE)\n  if(NOT ComputeCpp_INFO_EXECUTABLE_RESULT EQUAL \"0\")\n    message(WARNING \"Package version - Error obtaining version!\")\n  endif()\n\n  execute_process(COMMAND ${ComputeCpp_INFO_EXECUTABLE} \"--dump-is-supported\"\n    OUTPUT_VARIABLE COMPUTECPP_PLATFORM_IS_SUPPORTED\n    RESULT_VARIABLE ComputeCpp_INFO_EXECUTABLE_RESULT OUTPUT_STRIP_TRAILING_WHITESPACE)\n  if(NOT ComputeCpp_INFO_EXECUTABLE_RESULT EQUAL \"0\")\n    message(WARNING \"platform - Error checking platform support!\")\n  else()\n    mark_as_advanced(COMPUTECPP_PLATFORM_IS_SUPPORTED)\n    if (COMPUTECPP_PLATFORM_IS_SUPPORTED)\n      message(STATUS \"platform - your system can support ComputeCpp\")\n    else()\n      message(STATUS \"platform - your system is not officially supported\")\n    endif()\n  endif()\nendif()\n\nfind_package_handle_standard_args(ComputeCpp\n  REQUIRED_VARS ComputeCpp_ROOT_DIR\n                ComputeCpp_DEVICE_COMPILER_EXECUTABLE\n                ComputeCpp_INFO_EXECUTABLE\n                COMPUTECPP_RUNTIME_LIBRARY\n                COMPUTECPP_RUNTIME_LIBRARY_DEBUG\n                ComputeCpp_INCLUDE_DIRS\n  VERSION_VAR ComputeCpp_VERSION)\nmark_as_advanced(ComputeCpp_ROOT_DIR\n                 ComputeCpp_DEVICE_COMPILER_EXECUTABLE\n                 ComputeCpp_INFO_EXECUTABLE\n                 COMPUTECPP_RUNTIME_LIBRARY\n                 COMPUTECPP_RUNTIME_LIBRARY_DEBUG\n                 ComputeCpp_INCLUDE_DIRS\n                 ComputeCpp_VERSION)\n\nif(NOT ComputeCpp_FOUND)\n  return()\nendif()\n\nlist(APPEND COMPUTECPP_DEVICE_COMPILER_FLAGS -O2 -mllvm -inline-threshold=1000 -intelspirmetadata)\nmark_as_advanced(COMPUTECPP_DEVICE_COMPILER_FLAGS)\n\nif(CMAKE_CROSSCOMPILING)\n  if(NOT COMPUTECPP_DONT_USE_TOOLCHAIN)\n    list(APPEND COMPUTECPP_DEVICE_COMPILER_FLAGS --gcc-toolchain=${COMPUTECPP_TOOLCHAIN_DIR})\n  endif()\n  list(APPEND COMPUTECPP_DEVICE_COMPILER_FLAGS --sysroot=${COMPUTECPP_SYSROOT_DIR})\n  list(APPEND COMPUTECPP_DEVICE_COMPILER_FLAGS -target ${COMPUTECPP_TARGET_TRIPLE})\nendif()\n\nlist(APPEND COMPUTECPP_DEVICE_COMPILER_FLAGS -sycl-target ${COMPUTECPP_BITCODE})\nmessage(STATUS \"compute++ flags - ${COMPUTECPP_DEVICE_COMPILER_FLAGS}\")\n\ninclude(ComputeCppCompilerChecks)\n\nif(NOT TARGET OpenCL::OpenCL)\n  add_library(OpenCL::OpenCL UNKNOWN IMPORTED)\n  set_target_properties(OpenCL::OpenCL PROPERTIES\n    IMPORTED_LOCATION             \"${OpenCL_LIBRARIES}\"\n    INTERFACE_INCLUDE_DIRECTORIES \"${OpenCL_INCLUDE_DIRS}\"\n  )\nendif()\n\nif(NOT TARGET ComputeCpp::ComputeCpp)\n  add_library(ComputeCpp::ComputeCpp UNKNOWN IMPORTED)\n  set_target_properties(ComputeCpp::ComputeCpp PROPERTIES\n    IMPORTED_LOCATION_DEBUG          \"${COMPUTECPP_RUNTIME_LIBRARY_DEBUG}\"\n    IMPORTED_LOCATION_RELWITHDEBINFO \"${COMPUTECPP_RUNTIME_LIBRARY}\"\n    IMPORTED_LOCATION                \"${COMPUTECPP_RUNTIME_LIBRARY}\"\n    INTERFACE_INCLUDE_DIRECTORIES    \"${ComputeCpp_INCLUDE_DIRS}\"\n    INTERFACE_LINK_LIBRARIES         \"OpenCL::OpenCL\"\n  )\nendif()\n\n# This property allows targets to specify that their sources should be\n# compiled with the integration header included after the user's\n# sources, not before (e.g. when an enum is used in a kernel name, this\n# is not technically valid SYCL code but can work with ComputeCpp)\ndefine_property(\n  TARGET PROPERTY COMPUTECPP_INCLUDE_AFTER\n  BRIEF_DOCS \"Include integration header after user source\"\n  FULL_DOCS \"Changes compiler arguments such that the source file is\n  actually the integration header, and the .cpp file is included on\n  the command line so that it is seen by the compiler first. Enables\n  non-standards-conformant SYCL code to compile with ComputeCpp.\"\n)\ndefine_property(\n  TARGET PROPERTY INTERFACE_COMPUTECPP_FLAGS\n  BRIEF_DOCS \"Interface compile flags to provide compute++\"\n  FULL_DOCS  \"Set additional compile flags to pass to compute++ when compiling\n  any target which links to this one.\"\n)\ndefine_property(\n  SOURCE PROPERTY COMPUTECPP_SOURCE_FLAGS\n  BRIEF_DOCS \"Source file compile flags for compute++\"\n  FULL_DOCS  \"Set additional compile flags for compiling the SYCL integration\n  header for the given source file.\"\n)\n\n####################\n#   __build_ir\n####################\n#\n#  Adds a custom target for running compute++ and adding a dependency for the\n#  resulting integration header and kernel binary.\n#\n#  TARGET : Name of the target.\n#  SOURCE : Source file to be compiled.\n#  COUNTER : Counter included in name of custom target. Different counter\n#       values prevent duplicated names of custom target when source files with\n#       the same name, but located in different directories, are used for the\n#       same target.\n#\nfunction(__build_ir)\n  set(options)\n  set(one_value_args\n    TARGET\n    SOURCE\n    COUNTER\n  )\n  set(multi_value_args)\n  cmake_parse_arguments(SDK_BUILD_IR\n    \"${options}\"\n    \"${one_value_args}\"\n    \"${multi_value_args}\"\n    ${ARGN}\n  )\n  get_filename_component(sourceFileName ${SDK_BUILD_IR_SOURCE} NAME)\n\n  # Set the path to the integration header.\n  # The .sycl filename must depend on the target so that different targets\n  # using the same source file will be generated with a different rule.\n  set(baseSyclName ${CMAKE_CURRENT_BINARY_DIR}/${SDK_BUILD_IR_TARGET}_${sourceFileName})\n  set(outputSyclFile ${baseSyclName}.sycl)\n  set(outputDeviceFile ${baseSyclName}.${IR_MAP_${COMPUTECPP_BITCODE}})\n  set(depFileName ${baseSyclName}.sycl.d)\n\n  set(include_directories \"$<TARGET_PROPERTY:${SDK_BUILD_IR_TARGET},INCLUDE_DIRECTORIES>\")\n  set(compile_definitions \"$<TARGET_PROPERTY:${SDK_BUILD_IR_TARGET},COMPILE_DEFINITIONS>\")\n  set(generated_include_directories\n    $<$<BOOL:${include_directories}>:-I\\\"$<JOIN:${include_directories},\\\"\\t-I\\\">\\\">)\n  set(generated_compile_definitions\n    $<$<BOOL:${compile_definitions}>:-D$<JOIN:${compile_definitions},\\t-D>>)\n\n  # Obtain language standard of the file\n  set(device_compiler_cxx_standard)\n  get_target_property(targetCxxStandard ${SDK_BUILD_IR_TARGET} CXX_STANDARD)\n  if (targetCxxStandard MATCHES 17)\n    set(device_compiler_cxx_standard \"-std=c++1z\")\n  elseif (targetCxxStandard MATCHES 14)\n    set(device_compiler_cxx_standard \"-std=c++14\")\n  elseif (targetCxxStandard MATCHES 11)\n    set(device_compiler_cxx_standard \"-std=c++11\")\n  elseif (targetCxxStandard MATCHES 98)\n    message(FATAL_ERROR \"SYCL applications cannot be compiled using C++98\")\n  else ()\n    set(device_compiler_cxx_standard \"\")\n  endif()\n\n  get_property(source_compile_flags\n    SOURCE ${SDK_BUILD_IR_SOURCE}\n    PROPERTY COMPUTECPP_SOURCE_FLAGS\n  )\n  separate_arguments(source_compile_flags)\n  if(source_compile_flags)\n    list(APPEND computecpp_source_flags ${source_compile_flags})\n  endif()\n\n  list(APPEND COMPUTECPP_DEVICE_COMPILER_FLAGS\n    ${device_compiler_cxx_standard}\n    ${COMPUTECPP_USER_FLAGS}\n    ${computecpp_source_flags}\n  )\n\n  set(ir_dependencies ${SDK_BUILD_IR_SOURCE})\n  get_target_property(target_libraries ${SDK_BUILD_IR_TARGET} LINK_LIBRARIES)\n  if(target_libraries)\n    foreach(library ${target_libraries})\n      if(TARGET ${library})\n        list(APPEND ir_dependencies ${library})\n      endif()\n    endforeach()\n  endif()\n\n  # Depfile support was only added in CMake 3.7\n  # CMake throws an error if it is unsupported by the generator (i. e. not ninja)\n  if((NOT CMAKE_VERSION VERSION_LESS 3.7.0) AND\n          CMAKE_GENERATOR MATCHES \"Ninja\")\n    file(RELATIVE_PATH relOutputFile ${CMAKE_BINARY_DIR} ${outputDeviceFile})\n    set(generate_depfile -MMD -MF ${depFileName} -MT ${relOutputFile})\n    set(enable_depfile DEPFILE ${depFileName})\n  endif()\n\n  # Add custom command for running compute++\n  add_custom_command(\n    OUTPUT ${outputDeviceFile} ${outputSyclFile}\n    COMMAND ${ComputeCpp_DEVICE_COMPILER_EXECUTABLE}\n            ${COMPUTECPP_DEVICE_COMPILER_FLAGS}\n            ${generated_include_directories}\n            ${generated_compile_definitions}\n            -sycl-ih ${outputSyclFile}\n            -o ${outputDeviceFile}\n            -c ${SDK_BUILD_IR_SOURCE}\n            ${generate_depfile}\n    DEPENDS ${ir_dependencies}\n    IMPLICIT_DEPENDS CXX ${SDK_BUILD_IR_SOURCE}\n    ${enable_depfile}\n    WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}\n    COMMENT \"Building ComputeCpp integration header file ${outputSyclFile}\")\n\n  # Name: (user-defined name)_(source file)_(counter)_ih\n  set(headerTargetName\n    ${SDK_BUILD_IR_TARGET}_${sourceFileName}_${SDK_BUILD_IR_COUNTER}_ih)\n\n  if(NOT MSVC)\n    # Add a custom target for the generated integration header\n    add_custom_target(${headerTargetName} DEPENDS ${outputDeviceFile} ${outputSyclFile})\n    add_dependencies(${SDK_BUILD_IR_TARGET} ${headerTargetName})\n  endif()\n\n  # This property can be set on a per-target basis to indicate that the\n  # integration header should appear after the main source listing\n  get_target_property(includeAfter ${SDK_ADD_SYCL_TARGET} COMPUTECPP_INCLUDE_AFTER)\n\n  if(includeAfter)\n    # Change the source file to the integration header - e.g.\n    # g++ -c source_file_name.cpp.sycl\n    get_target_property(current_sources ${SDK_BUILD_IR_TARGET} SOURCES)\n    # Remove absolute path to source file\n    list(REMOVE_ITEM current_sources ${SDK_BUILD_IR_SOURCE})\n    # Remove relative path to source file\n    string(REPLACE \"${CMAKE_CURRENT_SOURCE_DIR}/\" \"\"\n      rel_source_file ${SDK_BUILD_IR_SOURCE}\n    )\n    list(REMOVE_ITEM current_sources ${rel_source_file})\n    # Add SYCL header to source list\n    list(APPEND current_sources ${outputSyclFile})\n    set_property(TARGET ${SDK_BUILD_IR_TARGET}\n      PROPERTY SOURCES ${current_sources})\n    # CMake/gcc don't know what language a .sycl file is, so tell them\n    set_property(SOURCE ${outputSyclFile} PROPERTY LANGUAGE CXX)\n    set(includedFile ${SDK_BUILD_IR_SOURCE})\n    set(cppFile ${outputSyclFile})\n  else()\n    set_property(SOURCE ${outputSyclFile} PROPERTY HEADER_FILE_ONLY ON)\n    set(includedFile ${outputSyclFile})\n    set(cppFile ${SDK_BUILD_IR_SOURCE})\n  endif()\n\n  # Force inclusion of the integration header for the host compiler\n  if(MSVC)\n    # Group SYCL files inside Visual Studio\n    source_group(\"SYCL\" FILES ${outputSyclFile})\n\n    if(includeAfter)\n      # Allow the source file to be edited using Visual Studio.\n      # It will be added as a header file so it won't be compiled.\n      set_property(SOURCE ${SDK_BUILD_IR_SOURCE} PROPERTY HEADER_FILE_ONLY true)\n    endif()\n\n    # Add both source and the sycl files to the VS solution.\n    target_sources(${SDK_BUILD_IR_TARGET} PUBLIC ${SDK_BUILD_IR_SOURCE} ${outputSyclFile})\n\n    set(forceIncludeFlags \"/FI${includedFile} /TP\")\n  else()\n    set(forceIncludeFlags \"-include ${includedFile} -x c++\")\n  endif()\n\n  set_property(\n    SOURCE ${cppFile}\n    APPEND_STRING PROPERTY COMPILE_FLAGS \"${forceIncludeFlags}\"\n  )\n\nendfunction(__build_ir)\n\n#######################\n#  add_sycl_to_target\n#######################\n#\n#  Adds a SYCL compilation custom command associated with an existing\n#  target and sets a dependancy on that new command.\n#\n#  TARGET : Name of the target to add SYCL to.\n#  SOURCES : Source files to be compiled for SYCL.\n#\nfunction(add_sycl_to_target)\n  set(options)\n  set(one_value_args\n    TARGET\n  )\n  set(multi_value_args\n    SOURCES\n  )\n  cmake_parse_arguments(SDK_ADD_SYCL\n    \"${options}\"\n    \"${one_value_args}\"\n    \"${multi_value_args}\"\n    ${ARGN}\n  )\n\n  set_target_properties(${SDK_ADD_SYCL_TARGET} PROPERTIES LINKER_LANGUAGE CXX)\n\n  # If the CXX compiler is set to compute++ enable the driver.\n  get_filename_component(cmakeCxxCompilerFileName \"${CMAKE_CXX_COMPILER}\" NAME)\n  if(\"${cmakeCxxCompilerFileName}\" STREQUAL \"compute++\")\n    if(MSVC)\n      message(FATAL_ERROR \"The compiler driver is not supported by this system,\n                           revert the CXX compiler to your default host compiler.\")\n    endif()\n\n    get_target_property(includeAfter ${SDK_ADD_SYCL_TARGET} COMPUTECPP_INCLUDE_AFTER)\n    if(includeAfter)\n      list(APPEND COMPUTECPP_USER_FLAGS -fsycl-ih-last)\n    endif()\n    list(INSERT COMPUTECPP_DEVICE_COMPILER_FLAGS 0 -sycl-driver)\n    # Prepend COMPUTECPP_DEVICE_COMPILER_FLAGS and append COMPUTECPP_USER_FLAGS\n    foreach(prop COMPILE_OPTIONS INTERFACE_COMPILE_OPTIONS)\n      get_target_property(target_compile_options ${SDK_ADD_SYCL_TARGET} ${prop})\n      if(NOT target_compile_options)\n        set(target_compile_options \"\")\n      endif()\n      set_property(\n        TARGET ${SDK_ADD_SYCL_TARGET}\n        PROPERTY ${prop}\n        ${COMPUTECPP_DEVICE_COMPILER_FLAGS}\n        ${target_compile_options}\n        ${COMPUTECPP_USER_FLAGS}\n      )\n    endforeach()\n  else()\n    set(fileCounter 0)\n    list(INSERT COMPUTECPP_DEVICE_COMPILER_FLAGS 0 -sycl)\n    # Add custom target to run compute++ and generate the integration header\n    foreach(sourceFile ${SDK_ADD_SYCL_SOURCES})\n      if(NOT IS_ABSOLUTE ${sourceFile})\n        set(sourceFile \"${CMAKE_CURRENT_SOURCE_DIR}/${sourceFile}\")\n      endif()\n      __build_ir(\n        TARGET     ${SDK_ADD_SYCL_TARGET}\n        SOURCE     ${sourceFile}\n        COUNTER    ${fileCounter}\n      )\n      MATH(EXPR fileCounter \"${fileCounter} + 1\")\n    endforeach()\n  endif()\n\n  set_property(TARGET ${SDK_ADD_SYCL_TARGET}\n    APPEND PROPERTY LINK_LIBRARIES ComputeCpp::ComputeCpp)\n  set_property(TARGET ${SDK_ADD_SYCL_TARGET}\n    APPEND PROPERTY INTERFACE_LINK_LIBRARIES ComputeCpp::ComputeCpp)\nendfunction(add_sycl_to_target)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindFFTW.cmake",
    "content": "# - Find the FFTW library\n#\n# Usage:\n#   find_package(FFTW [REQUIRED] [QUIET] )\n#     \n# It sets the following variables:\n#   FFTW_FOUND               ... true if fftw is found on the system\n#   FFTW_LIBRARIES           ... full path to fftw library\n#   FFTW_INCLUDES            ... fftw include directory\n#\n# The following variables will be checked by the function\n#   FFTW_USE_STATIC_LIBS    ... if true, only static libraries are found\n#   FFTW_ROOT               ... if set, the libraries are exclusively searched\n#                               under this path\n#   FFTW_LIBRARY            ... fftw library to use\n#   FFTW_INCLUDE_DIR        ... fftw include directory\n#\n\n#If environment variable FFTWDIR is specified, it has same effect as FFTW_ROOT\nif( NOT FFTW_ROOT AND ENV{FFTWDIR} )\n  set( FFTW_ROOT $ENV{FFTWDIR} )\nendif()\n\n# Check if we can use PkgConfig\ninclude(CMakeFindDependencyMacro)\nfind_dependency(PkgConfig)\n\n#Determine from PKG\nif( PKG_CONFIG_FOUND AND NOT FFTW_ROOT )\n  pkg_check_modules( PKG_FFTW QUIET \"fftw3\" )\nendif()\n\n#Check whether to search static or dynamic libs\nset( CMAKE_FIND_LIBRARY_SUFFIXES_SAV ${CMAKE_FIND_LIBRARY_SUFFIXES} )\n\nif( ${FFTW_USE_STATIC_LIBS} )\n  set( CMAKE_FIND_LIBRARY_SUFFIXES ${CMAKE_STATIC_LIBRARY_SUFFIX} )\nelse()\n  set( CMAKE_FIND_LIBRARY_SUFFIXES ${CMAKE_SHARED_LIBRARY_SUFFIX} )\nendif()\n\nif( FFTW_ROOT )\n\n  #find libs\n  find_library(\n    FFTW_LIB\n    NAMES \"fftw3\"\n    PATHS ${FFTW_ROOT}\n    PATH_SUFFIXES \"lib\" \"lib64\"\n    NO_DEFAULT_PATH\n  )\n\n  find_library(\n    FFTWF_LIB\n    NAMES \"fftw3f\"\n    PATHS ${FFTW_ROOT}\n    PATH_SUFFIXES \"lib\" \"lib64\"\n    NO_DEFAULT_PATH\n  )\n\n  find_library(\n    FFTWL_LIB\n    NAMES \"fftw3l\"\n    PATHS ${FFTW_ROOT}\n    PATH_SUFFIXES \"lib\" \"lib64\"\n    NO_DEFAULT_PATH\n  )\n\n  #find includes\n  find_path(\n    FFTW_INCLUDES\n    NAMES \"fftw3.h\"\n    PATHS ${FFTW_ROOT}\n    PATH_SUFFIXES \"include\"\n    NO_DEFAULT_PATH\n  )\n\nelse()\n\n  find_library(\n    FFTW_LIB\n    NAMES \"fftw3\"\n    PATHS ${PKG_FFTW_LIBRARY_DIRS} ${LIB_INSTALL_DIR}\n  )\n\n  find_library(\n    FFTWF_LIB\n    NAMES \"fftw3f\"\n    PATHS ${PKG_FFTW_LIBRARY_DIRS} ${LIB_INSTALL_DIR}\n  )\n\n\n  find_library(\n    FFTWL_LIB\n    NAMES \"fftw3l\"\n    PATHS ${PKG_FFTW_LIBRARY_DIRS} ${LIB_INSTALL_DIR}\n  )\n\n  find_path(\n    FFTW_INCLUDES\n    NAMES \"fftw3.h\"\n    PATHS ${PKG_FFTW_INCLUDE_DIRS} ${INCLUDE_INSTALL_DIR}\n  )\n\nendif()\n\nset(FFTW_LIBRARIES ${FFTW_LIB} ${FFTWF_LIB})\n\nif(FFTWL_LIB)\n  set(FFTW_LIBRARIES ${FFTW_LIBRARIES} ${FFTWL_LIB})\nendif()\n\nset( CMAKE_FIND_LIBRARY_SUFFIXES ${CMAKE_FIND_LIBRARY_SUFFIXES_SAV} )\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(FFTW DEFAULT_MSG\n                                  FFTW_INCLUDES FFTW_LIBRARIES)\n\nmark_as_advanced(FFTW_INCLUDES FFTW_LIBRARIES FFTW_LIB FFTWF_LIB FFTWL_LIB)\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindGLEW.cmake",
    "content": "# Copyright (c) 2009 Boudewijn Rempt <boud@valdyas.org>                                                                                          \n#                                                                                                                                                \n# Redistribution and use is allowed according to the terms of the BSD license.                                                                   \n# For details see the accompanying COPYING-CMAKE-SCRIPTS file. \n# \n# - try to find glew library and include files\n#  GLEW_INCLUDE_DIR, where to find GL/glew.h, etc.\n#  GLEW_LIBRARIES, the libraries to link against\n#  GLEW_FOUND, If false, do not try to use GLEW.\n# Also defined, but not for general use are:\n#  GLEW_GLEW_LIBRARY = the full path to the glew library.\n\nif (WIN32)\n\n  if(CYGWIN)\n\n    find_path( GLEW_INCLUDE_DIR GL/glew.h)\n\n    find_library( GLEW_GLEW_LIBRARY glew32\n      ${OPENGL_LIBRARY_DIR}\n      /usr/lib/w32api\n      /usr/X11R6/lib\n    )\n\n\n  else(CYGWIN)\n  \n    find_path( GLEW_INCLUDE_DIR GL/glew.h\n      $ENV{GLEW_ROOT_PATH}/include\n    )\n\n    find_library( GLEW_GLEW_LIBRARY\n      NAMES glew glew32\n      PATHS\n      $ENV{GLEW_ROOT_PATH}/lib\n      ${OPENGL_LIBRARY_DIR}\n    )\n\n  endif(CYGWIN)\n\nelse (WIN32)\n\n  if (APPLE)\n# These values for Apple could probably do with improvement.\n    find_path( GLEW_INCLUDE_DIR glew.h\n      /System/Library/Frameworks/GLEW.framework/Versions/A/Headers\n      ${OPENGL_LIBRARY_DIR}\n    )\n    set(GLEW_GLEW_LIBRARY \"-framework GLEW\" CACHE STRING \"GLEW library for OSX\")\n    set(GLEW_cocoa_LIBRARY \"-framework Cocoa\" CACHE STRING \"Cocoa framework for OSX\")\n  else (APPLE)\n\n    find_path( GLEW_INCLUDE_DIR GL/glew.h\n      /usr/include/GL\n      /usr/openwin/share/include\n      /usr/openwin/include\n      /usr/X11R6/include\n      /usr/include/X11\n      /opt/graphics/OpenGL/include\n      /opt/graphics/OpenGL/contrib/libglew\n    )\n\n    find_library( GLEW_GLEW_LIBRARY GLEW\n      /usr/openwin/lib\n      /usr/X11R6/lib\n    )\n\n  endif (APPLE)\n\nendif (WIN32)\n\nset( GLEW_FOUND \"NO\" )\nif(GLEW_INCLUDE_DIR)\n  if(GLEW_GLEW_LIBRARY)\n    # Is -lXi and -lXmu required on all platforms that have it?\n    # If not, we need some way to figure out what platform we are on.\n    set( GLEW_LIBRARIES\n      ${GLEW_GLEW_LIBRARY}\n      ${GLEW_cocoa_LIBRARY}\n    )\n    set( GLEW_FOUND \"YES\" )\n\n#The following deprecated settings are for backwards compatibility with CMake1.4\n    set (GLEW_LIBRARY ${GLEW_LIBRARIES})\n    set (GLEW_INCLUDE_PATH ${GLEW_INCLUDE_DIR})\n\n  endif(GLEW_GLEW_LIBRARY)\nendif(GLEW_INCLUDE_DIR)\n\nif(GLEW_FOUND)\n  if(NOT GLEW_FIND_QUIETLY)\n    message(STATUS \"Found Glew: ${GLEW_LIBRARIES}\")\n  endif(NOT GLEW_FIND_QUIETLY)\nelse(GLEW_FOUND)\n  if(GLEW_FIND_REQUIRED)\n    message(FATAL_ERROR \"Could not find Glew\")\n  endif(GLEW_FIND_REQUIRED)\nendif(GLEW_FOUND)\n\nmark_as_advanced(\n  GLEW_INCLUDE_DIR\n  GLEW_GLEW_LIBRARY\n  GLEW_Xmu_LIBRARY\n  GLEW_Xi_LIBRARY\n)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindGMP.cmake",
    "content": "# Try to find the GNU Multiple Precision Arithmetic Library (GMP)\n# See http://gmplib.org/\n\nif (GMP_INCLUDES AND GMP_LIBRARIES)\n  set(GMP_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(GMP_INCLUDES\n  NAMES\n  gmp.h\n  PATHS\n  $ENV{GMPDIR}\n  ${INCLUDE_INSTALL_DIR}\n)\n\nfind_library(GMP_LIBRARIES gmp PATHS $ENV{GMPDIR} ${LIB_INSTALL_DIR})\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(GMP DEFAULT_MSG\n                                  GMP_INCLUDES GMP_LIBRARIES)\nmark_as_advanced(GMP_INCLUDES GMP_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindGSL.cmake",
    "content": "# Try to find gnu scientific library GSL\n# See \n# http://www.gnu.org/software/gsl/  and\n# http://gnuwin32.sourceforge.net/packages/gsl.htm\n#\n# Once run this will define: \n# \n# GSL_FOUND       = system has GSL lib\n#\n# GSL_LIBRARIES   = full path to the libraries\n#    on Unix/Linux with additional linker flags from \"gsl-config --libs\"\n# \n# CMAKE_GSL_CXX_FLAGS  = Unix compiler flags for GSL, essentially \"`gsl-config --cxxflags`\"\n#\n# GSL_INCLUDE_DIR      = where to find headers \n#\n# GSL_LINK_DIRECTORIES = link directories, useful for rpath on Unix\n# GSL_EXE_LINKER_FLAGS = rpath on Unix\n#\n# Felix Woelk 07/2004\n# Jan Woetzel\n#\n# www.mip.informatik.uni-kiel.de\n# --------------------------------\n\nif(WIN32)\n  # JW tested with gsl-1.8, Windows XP, MSVS 7.1\n  set(GSL_POSSIBLE_ROOT_DIRS\n    ${GSL_ROOT_DIR}\n    $ENV{GSL_ROOT_DIR}\n    ${GSL_DIR}\n    ${GSL_HOME}    \n    $ENV{GSL_DIR}\n    $ENV{GSL_HOME}\n    $ENV{EXTRA}\n    \"C:/Program Files/GnuWin32\"\n    )\n  find_path(GSL_INCLUDE_DIR\n    NAMES gsl/gsl_cdf.h gsl/gsl_randist.h\n    PATHS ${GSL_POSSIBLE_ROOT_DIRS}\n    PATH_SUFFIXES include\n    DOC \"GSL header include dir\"\n    )\n  \n  find_library(GSL_GSL_LIBRARY\n    NAMES libgsl.dll.a gsl libgsl\n    PATHS  ${GSL_POSSIBLE_ROOT_DIRS}\n    PATH_SUFFIXES lib\n    DOC \"GSL library\" )\n  \n  if(NOT GSL_GSL_LIBRARY)\n\tfind_file(GSL_GSL_LIBRARY\n\t\tNAMES libgsl.dll.a\n\t\tPATHS  ${GSL_POSSIBLE_ROOT_DIRS}\n\t\tPATH_SUFFIXES lib\n\t\tDOC \"GSL library\")\n  endif()\n  \n  find_library(GSL_GSLCBLAS_LIBRARY\n    NAMES libgslcblas.dll.a gslcblas libgslcblas\n    PATHS  ${GSL_POSSIBLE_ROOT_DIRS}\n    PATH_SUFFIXES lib\n    DOC \"GSL cblas library dir\" )\n  \n  if(NOT GSL_GSLCBLAS_LIBRARY)\n\tfind_file(GSL_GSLCBLAS_LIBRARY\n\t\tNAMES libgslcblas.dll.a\n\t\tPATHS  ${GSL_POSSIBLE_ROOT_DIRS}\n\t\tPATH_SUFFIXES lib\n\t\tDOC \"GSL library\")\n  endif()\n  \n  set(GSL_LIBRARIES ${GSL_GSL_LIBRARY})\n\n  #message(\"DBG\\n\"\n  #  \"GSL_GSL_LIBRARY=${GSL_GSL_LIBRARY}\\n\"\n  #  \"GSL_GSLCBLAS_LIBRARY=${GSL_GSLCBLAS_LIBRARY}\\n\"\n  #  \"GSL_LIBRARIES=${GSL_LIBRARIES}\")\n\n\nelse(WIN32)\n  \n  if(UNIX) \n    set(GSL_CONFIG_PREFER_PATH \n      \"$ENV{GSL_DIR}/bin\"\n      \"$ENV{GSL_DIR}\"\n      \"$ENV{GSL_HOME}/bin\" \n      \"$ENV{GSL_HOME}\" \n      CACHE STRING \"preferred path to GSL (gsl-config)\")\n    find_program(GSL_CONFIG gsl-config\n      ${GSL_CONFIG_PREFER_PATH}\n      /usr/bin/\n      )\n    # message(\"DBG GSL_CONFIG ${GSL_CONFIG}\")\n    \n    if (GSL_CONFIG) \n      # set CXXFLAGS to be fed into CXX_FLAGS by the user:\n      set(GSL_CXX_FLAGS \"`${GSL_CONFIG} --cflags`\")\n      \n      # set INCLUDE_DIRS to prefix+include\n      exec_program(${GSL_CONFIG}\n        ARGS --prefix\n        OUTPUT_VARIABLE GSL_PREFIX)\n      set(GSL_INCLUDE_DIR ${GSL_PREFIX}/include CACHE STRING INTERNAL)\n\n      # set link libraries and link flags\n      #set(GSL_LIBRARIES \"`${GSL_CONFIG} --libs`\")\n      exec_program(${GSL_CONFIG}\n        ARGS --libs\n        OUTPUT_VARIABLE GSL_LIBRARIES )\n        \n      # extract link dirs for rpath  \n      exec_program(${GSL_CONFIG}\n        ARGS --libs\n        OUTPUT_VARIABLE GSL_CONFIG_LIBS )\n      \n      # extract version\n      exec_program(${GSL_CONFIG}\n        ARGS --version\n        OUTPUT_VARIABLE GSL_FULL_VERSION )\n      \n      # split version as major/minor\n      string(REGEX MATCH \"(.)\\\\..*\" GSL_VERSION_MAJOR_ \"${GSL_FULL_VERSION}\")\n      set(GSL_VERSION_MAJOR ${CMAKE_MATCH_1})\n      string(REGEX MATCH \".\\\\.(.*)\" GSL_VERSION_MINOR_ \"${GSL_FULL_VERSION}\")\n      set(GSL_VERSION_MINOR ${CMAKE_MATCH_1})\n\n      # split off the link dirs (for rpath)\n      # use regular expression to match wildcard equivalent \"-L*<endchar>\"\n      # with <endchar> is a space or a semicolon\n      string(REGEX MATCHALL \"[-][L]([^ ;])+\" \n        GSL_LINK_DIRECTORIES_WITH_PREFIX \n        \"${GSL_CONFIG_LIBS}\" )\n      #      message(\"DBG  GSL_LINK_DIRECTORIES_WITH_PREFIX=${GSL_LINK_DIRECTORIES_WITH_PREFIX}\")\n\n      # remove prefix -L because we need the pure directory for LINK_DIRECTORIES\n      \n      if (GSL_LINK_DIRECTORIES_WITH_PREFIX)\n        string(REGEX REPLACE \"[-][L]\" \"\" GSL_LINK_DIRECTORIES ${GSL_LINK_DIRECTORIES_WITH_PREFIX} )\n      endif (GSL_LINK_DIRECTORIES_WITH_PREFIX)\n      set(GSL_EXE_LINKER_FLAGS \"-Wl,-rpath,${GSL_LINK_DIRECTORIES}\" CACHE STRING INTERNAL)\n      #      message(\"DBG  GSL_LINK_DIRECTORIES=${GSL_LINK_DIRECTORIES}\")\n      #      message(\"DBG  GSL_EXE_LINKER_FLAGS=${GSL_EXE_LINKER_FLAGS}\")\n\n      #      add_definitions(\"-DHAVE_GSL\")\n      #      set(GSL_DEFINITIONS \"-DHAVE_GSL\")\n      mark_as_advanced(\n        GSL_CXX_FLAGS\n        GSL_INCLUDE_DIR\n        GSL_LIBRARIES\n        GSL_LINK_DIRECTORIES\n        GSL_DEFINITIONS\n        )\n      message(STATUS \"Using GSL from ${GSL_PREFIX}\")\n      \n    else(GSL_CONFIG)\n      message(\"FindGSL.cmake: gsl-config not found. Please set it manually. GSL_CONFIG=${GSL_CONFIG}\")\n    endif(GSL_CONFIG)\n\n  endif(UNIX)\nendif(WIN32)\n\n\nif(GSL_LIBRARIES)\n  if(GSL_INCLUDE_DIR OR GSL_CXX_FLAGS)\n\n    set(GSL_FOUND 1)\n    \n  endif(GSL_INCLUDE_DIR OR GSL_CXX_FLAGS)\nendif(GSL_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindGoogleHash.cmake",
    "content": "\nif (GOOGLEHASH_INCLUDES AND GOOGLEHASH_LIBRARIES)\n  set(GOOGLEHASH_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(GOOGLEHASH_INCLUDES\n  NAMES\n  google/dense_hash_map\n  PATHS\n  ${INCLUDE_INSTALL_DIR}\n)\n\nif(GOOGLEHASH_INCLUDES)\n  # let's make sure it compiles with the current compiler\n  file(WRITE ${CMAKE_BINARY_DIR}/googlehash_test.cpp\n  \"#include <google/sparse_hash_map>\\n#include <google/dense_hash_map>\\nint main(int argc, char** argv) { google::dense_hash_map<int,float> a; google::sparse_hash_map<int,float> b; return 0;}\\n\")\n  try_compile(GOOGLEHASH_COMPILE ${CMAKE_BINARY_DIR} ${CMAKE_BINARY_DIR}/googlehash_test.cpp OUTPUT_VARIABLE GOOGLEHASH_COMPILE_RESULT)\nendif()\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(GoogleHash DEFAULT_MSG GOOGLEHASH_INCLUDES GOOGLEHASH_COMPILE)\n\nmark_as_advanced(GOOGLEHASH_INCLUDES)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindHWLOC.cmake",
    "content": "###\n#\n# @copyright (c) 2009-2014 The University of Tennessee and The University\n#                          of Tennessee Research Foundation.\n#                          All rights reserved.\n# @copyright (c) 2012-2014 Inria. All rights reserved.\n# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved.\n#\n###\n#\n# - Find HWLOC include dirs and libraries\n# Use this module by invoking find_package with the form:\n#  find_package(HWLOC\n#               [REQUIRED]) # Fail with error if hwloc is not found\n#\n# This module finds headers and hwloc library.\n# Results are reported in variables:\n#  HWLOC_FOUND           - True if headers and requested libraries were found\n#  HWLOC_INCLUDE_DIRS    - hwloc include directories\n#  HWLOC_LIBRARY_DIRS    - Link directories for hwloc libraries\n#  HWLOC_LIBRARIES       - hwloc component libraries to be linked\n#\n# The user can give specific paths where to find the libraries adding cmake\n# options at configure (ex: cmake path/to/project -DHWLOC_DIR=path/to/hwloc):\n#  HWLOC_DIR             - Where to find the base directory of hwloc\n#  HWLOC_INCDIR          - Where to find the header files\n#  HWLOC_LIBDIR          - Where to find the library files\n# The module can also look for the following environment variables if paths\n# are not given as cmake variable: HWLOC_DIR, HWLOC_INCDIR, HWLOC_LIBDIR\n\n#=============================================================================\n# Copyright 2012-2013 Inria\n# Copyright 2012-2013 Emmanuel Agullo\n# Copyright 2012-2013 Mathieu Faverge\n# Copyright 2012      Cedric Castagnede\n# Copyright 2013      Florent Pruvost\n#\n# Distributed under the OSI-approved BSD License (the \"License\");\n# see accompanying file MORSE-Copyright.txt for details.\n#\n# This software is distributed WITHOUT ANY WARRANTY; without even the\n# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.\n# See the License for more information.\n#=============================================================================\n# (To distribute this file outside of Morse, substitute the full\n#  License text for the above reference.)\n\ninclude(CheckStructHasMember)\ninclude(CheckCSourceCompiles)\n\nif (NOT HWLOC_FOUND)\n  set(HWLOC_DIR \"\" CACHE PATH \"Installation directory of HWLOC library\")\n  if (NOT HWLOC_FIND_QUIETLY)\n    message(STATUS \"A cache variable, namely HWLOC_DIR, has been set to specify the install directory of HWLOC\")\n  endif()\nendif()\n\nset(ENV_HWLOC_DIR \"$ENV{HWLOC_DIR}\")\nset(ENV_HWLOC_INCDIR \"$ENV{HWLOC_INCDIR}\")\nset(ENV_HWLOC_LIBDIR \"$ENV{HWLOC_LIBDIR}\")\nset(HWLOC_GIVEN_BY_USER \"FALSE\")\nif ( HWLOC_DIR OR ( HWLOC_INCDIR AND HWLOC_LIBDIR) OR ENV_HWLOC_DIR OR (ENV_HWLOC_INCDIR AND ENV_HWLOC_LIBDIR) )\n  set(HWLOC_GIVEN_BY_USER \"TRUE\")\nendif()\n\n# Optionally use pkg-config to detect include/library dirs (if pkg-config is available)\n# -------------------------------------------------------------------------------------\ninclude(CMakeFindDependencyMacro)\n# include(FindPkgConfig)\nfind_dependency(PkgConfig QUIET)\nif( PKG_CONFIG_EXECUTABLE AND NOT HWLOC_GIVEN_BY_USER )\n\n  pkg_search_module(HWLOC hwloc)\n  if (NOT HWLOC_FIND_QUIETLY)\n    if (HWLOC_FOUND AND HWLOC_LIBRARIES)\n      message(STATUS \"Looking for HWLOC - found using PkgConfig\")\n      #if(NOT HWLOC_INCLUDE_DIRS)\n      #    message(\"${Magenta}HWLOC_INCLUDE_DIRS is empty using PkgConfig.\"\n      #        \"Perhaps the path to hwloc headers is already present in your\"\n      #        \"C(PLUS)_INCLUDE_PATH environment variable.${ColourReset}\")\n      #endif()\n    else()\n      message(STATUS \"${Magenta}Looking for HWLOC - not found using PkgConfig.\"\n\t\"\\n   Perhaps you should add the directory containing hwloc.pc to\"\n\t\"\\n   the PKG_CONFIG_PATH environment variable.${ColourReset}\")\n    endif()\n  endif()\n\nendif()\n\nif( (NOT PKG_CONFIG_EXECUTABLE) OR (PKG_CONFIG_EXECUTABLE AND NOT HWLOC_FOUND) OR (HWLOC_GIVEN_BY_USER) )\n\n  if (NOT HWLOC_FIND_QUIETLY)\n    message(STATUS \"Looking for HWLOC - PkgConfig not used\")\n  endif()\n\n  # Looking for include\n  # -------------------\n\n  # Add system include paths to search include\n  # ------------------------------------------\n  unset(_inc_env)\n  if(ENV_HWLOC_INCDIR)\n    list(APPEND _inc_env \"${ENV_HWLOC_INCDIR}\")\n  elseif(ENV_HWLOC_DIR)\n    list(APPEND _inc_env \"${ENV_HWLOC_DIR}\")\n    list(APPEND _inc_env \"${ENV_HWLOC_DIR}/include\")\n    list(APPEND _inc_env \"${ENV_HWLOC_DIR}/include/hwloc\")\n  else()\n    if(WIN32)\n      string(REPLACE \":\" \";\" _inc_env \"$ENV{INCLUDE}\")\n    else()\n      string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE}\")\n      list(APPEND _inc_env \"${_path_env}\")\n      string(REPLACE \":\" \";\" _path_env \"$ENV{C_INCLUDE_PATH}\")\n      list(APPEND _inc_env \"${_path_env}\")\n      string(REPLACE \":\" \";\" _path_env \"$ENV{CPATH}\")\n      list(APPEND _inc_env \"${_path_env}\")\n      string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE_PATH}\")\n      list(APPEND _inc_env \"${_path_env}\")\n    endif()\n  endif()\n  list(APPEND _inc_env \"${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}\")\n  list(APPEND _inc_env \"${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}\")\n  list(REMOVE_DUPLICATES _inc_env)\n\n  # set paths where to look for\n  set(PATH_TO_LOOK_FOR \"${_inc_env}\")\n\n  # Try to find the hwloc header in the given paths\n  # -------------------------------------------------\n  # call cmake macro to find the header path\n  if(HWLOC_INCDIR)\n    set(HWLOC_hwloc.h_DIRS \"HWLOC_hwloc.h_DIRS-NOTFOUND\")\n    find_path(HWLOC_hwloc.h_DIRS\n      NAMES hwloc.h\n      HINTS ${HWLOC_INCDIR})\n  else()\n    if(HWLOC_DIR)\n      set(HWLOC_hwloc.h_DIRS \"HWLOC_hwloc.h_DIRS-NOTFOUND\")\n      find_path(HWLOC_hwloc.h_DIRS\n\tNAMES hwloc.h\n\tHINTS ${HWLOC_DIR}\n\tPATH_SUFFIXES \"include\" \"include/hwloc\")\n    else()\n      set(HWLOC_hwloc.h_DIRS \"HWLOC_hwloc.h_DIRS-NOTFOUND\")\n      find_path(HWLOC_hwloc.h_DIRS\n\tNAMES hwloc.h\n\tHINTS ${PATH_TO_LOOK_FOR}\n\tPATH_SUFFIXES \"hwloc\")\n    endif()\n  endif()\n  mark_as_advanced(HWLOC_hwloc.h_DIRS)\n\n  # Add path to cmake variable\n  # ------------------------------------\n  if (HWLOC_hwloc.h_DIRS)\n    set(HWLOC_INCLUDE_DIRS \"${HWLOC_hwloc.h_DIRS}\")\n  else ()\n    set(HWLOC_INCLUDE_DIRS \"HWLOC_INCLUDE_DIRS-NOTFOUND\")\n    if(NOT HWLOC_FIND_QUIETLY)\n      message(STATUS \"Looking for hwloc -- hwloc.h not found\")\n    endif()\n  endif ()\n\n  if (HWLOC_INCLUDE_DIRS)\n    list(REMOVE_DUPLICATES HWLOC_INCLUDE_DIRS)\n  endif ()\n\n\n  # Looking for lib\n  # ---------------\n\n  # Add system library paths to search lib\n  # --------------------------------------\n  unset(_lib_env)\n  if(ENV_HWLOC_LIBDIR)\n    list(APPEND _lib_env \"${ENV_HWLOC_LIBDIR}\")\n  elseif(ENV_HWLOC_DIR)\n    list(APPEND _lib_env \"${ENV_HWLOC_DIR}\")\n    list(APPEND _lib_env \"${ENV_HWLOC_DIR}/lib\")\n  else()\n    if(WIN32)\n      string(REPLACE \":\" \";\" _lib_env \"$ENV{LIB}\")\n    else()\n      if(APPLE)\n\tstring(REPLACE \":\" \";\" _lib_env \"$ENV{DYLD_LIBRARY_PATH}\")\n      else()\n\tstring(REPLACE \":\" \";\" _lib_env \"$ENV{LD_LIBRARY_PATH}\")\n      endif()\n      list(APPEND _lib_env \"${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}\")\n      list(APPEND _lib_env \"${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}\")\n    endif()\n  endif()\n  list(REMOVE_DUPLICATES _lib_env)\n\n  # set paths where to look for\n  set(PATH_TO_LOOK_FOR \"${_lib_env}\")\n\n  # Try to find the hwloc lib in the given paths\n  # ----------------------------------------------\n\n  # call cmake macro to find the lib path\n  if(HWLOC_LIBDIR)\n    set(HWLOC_hwloc_LIBRARY \"HWLOC_hwloc_LIBRARY-NOTFOUND\")\n    find_library(HWLOC_hwloc_LIBRARY\n      NAMES hwloc\n      HINTS ${HWLOC_LIBDIR})\n  else()\n    if(HWLOC_DIR)\n      set(HWLOC_hwloc_LIBRARY \"HWLOC_hwloc_LIBRARY-NOTFOUND\")\n      find_library(HWLOC_hwloc_LIBRARY\n\tNAMES hwloc\n\tHINTS ${HWLOC_DIR}\n\tPATH_SUFFIXES lib lib32 lib64)\n    else()\n      set(HWLOC_hwloc_LIBRARY \"HWLOC_hwloc_LIBRARY-NOTFOUND\")\n      find_library(HWLOC_hwloc_LIBRARY\n\tNAMES hwloc\n\tHINTS ${PATH_TO_LOOK_FOR})\n    endif()\n  endif()\n  mark_as_advanced(HWLOC_hwloc_LIBRARY)\n\n  # If found, add path to cmake variable\n  # ------------------------------------\n  if (HWLOC_hwloc_LIBRARY)\n    get_filename_component(hwloc_lib_path ${HWLOC_hwloc_LIBRARY} PATH)\n    # set cmake variables (respects naming convention)\n    set(HWLOC_LIBRARIES    \"${HWLOC_hwloc_LIBRARY}\")\n    set(HWLOC_LIBRARY_DIRS \"${hwloc_lib_path}\")\n  else ()\n    set(HWLOC_LIBRARIES    \"HWLOC_LIBRARIES-NOTFOUND\")\n    set(HWLOC_LIBRARY_DIRS \"HWLOC_LIBRARY_DIRS-NOTFOUND\")\n    if(NOT HWLOC_FIND_QUIETLY)\n      message(STATUS \"Looking for hwloc -- lib hwloc not found\")\n    endif()\n  endif ()\n\n  if (HWLOC_LIBRARY_DIRS)\n    list(REMOVE_DUPLICATES HWLOC_LIBRARY_DIRS)\n  endif ()\n\n  # check a function to validate the find\n  if(HWLOC_LIBRARIES)\n\n    set(REQUIRED_INCDIRS)\n    set(REQUIRED_LIBDIRS)\n    set(REQUIRED_LIBS)\n\n    # HWLOC\n    if (HWLOC_INCLUDE_DIRS)\n      set(REQUIRED_INCDIRS \"${HWLOC_INCLUDE_DIRS}\")\n    endif()\n    if (HWLOC_LIBRARY_DIRS)\n      set(REQUIRED_LIBDIRS \"${HWLOC_LIBRARY_DIRS}\")\n    endif()\n    set(REQUIRED_LIBS \"${HWLOC_LIBRARIES}\")\n\n    # set required libraries for link\n    set(CMAKE_REQUIRED_INCLUDES \"${REQUIRED_INCDIRS}\")\n    set(CMAKE_REQUIRED_LIBRARIES)\n    foreach(lib_dir ${REQUIRED_LIBDIRS})\n      list(APPEND CMAKE_REQUIRED_LIBRARIES \"-L${lib_dir}\")\n    endforeach()\n    list(APPEND CMAKE_REQUIRED_LIBRARIES \"${REQUIRED_LIBS}\")\n    string(REGEX REPLACE \"^ -\" \"-\" CMAKE_REQUIRED_LIBRARIES \"${CMAKE_REQUIRED_LIBRARIES}\")\n\n    # test link\n    unset(HWLOC_WORKS CACHE)\n    include(CheckFunctionExists)\n    check_function_exists(hwloc_topology_init HWLOC_WORKS)\n    mark_as_advanced(HWLOC_WORKS)\n\n    if(NOT HWLOC_WORKS)\n      if(NOT HWLOC_FIND_QUIETLY)\n\tmessage(STATUS \"Looking for hwloc : test of hwloc_topology_init with hwloc library fails\")\n\tmessage(STATUS \"CMAKE_REQUIRED_LIBRARIES: ${CMAKE_REQUIRED_LIBRARIES}\")\n\tmessage(STATUS \"CMAKE_REQUIRED_INCLUDES: ${CMAKE_REQUIRED_INCLUDES}\")\n\tmessage(STATUS \"Check in CMakeFiles/CMakeError.log to figure out why it fails\")\n      endif()\n    endif()\n    set(CMAKE_REQUIRED_INCLUDES)\n    set(CMAKE_REQUIRED_FLAGS)\n    set(CMAKE_REQUIRED_LIBRARIES)\n  endif()\n\nendif()\n\nif (HWLOC_LIBRARIES)\n  if (HWLOC_LIBRARY_DIRS)\n    list(GET HWLOC_LIBRARY_DIRS 0 first_lib_path)\n  else()\n    list(GET HWLOC_LIBRARIES 0 first_lib)\n    get_filename_component(first_lib_path \"${first_lib}\" PATH)\n  endif()\n  if (${first_lib_path} MATCHES \"/lib(32|64)?$\")\n    string(REGEX REPLACE \"/lib(32|64)?$\" \"\" not_cached_dir \"${first_lib_path}\")\n    set(HWLOC_DIR_FOUND \"${not_cached_dir}\" CACHE PATH \"Installation directory of HWLOC library\" FORCE)\n  else()\n    set(HWLOC_DIR_FOUND \"${first_lib_path}\" CACHE PATH \"Installation directory of HWLOC library\" FORCE)\n  endif()\nendif()\nmark_as_advanced(HWLOC_DIR)\nmark_as_advanced(HWLOC_DIR_FOUND)\n\n# check that HWLOC has been found\n# -------------------------------\ninclude(FindPackageHandleStandardArgs)\nif (PKG_CONFIG_EXECUTABLE AND HWLOC_FOUND)\n  find_package_handle_standard_args(HWLOC DEFAULT_MSG\n    HWLOC_LIBRARIES)\nelse()\n  find_package_handle_standard_args(HWLOC DEFAULT_MSG\n    HWLOC_LIBRARIES\n    HWLOC_WORKS)\nendif()\n\nif (HWLOC_FOUND)\n  set(HWLOC_SAVE_CMAKE_REQUIRED_INCLUDES ${CMAKE_REQUIRED_INCLUDES})\n  list(APPEND CMAKE_REQUIRED_INCLUDES ${HWLOC_INCLUDE_DIRS})\n\n  # test headers to guess the version\n  check_struct_has_member( \"struct hwloc_obj\" parent hwloc.h HAVE_HWLOC_PARENT_MEMBER )\n  check_struct_has_member( \"struct hwloc_cache_attr_s\" size hwloc.h HAVE_HWLOC_CACHE_ATTR )\n  check_c_source_compiles( \"#include <hwloc.h>\n\t    int main(void) { hwloc_obj_t o; o->type = HWLOC_OBJ_PU; return 0;}\" HAVE_HWLOC_OBJ_PU)\n  include(CheckLibraryExists)\n  check_library_exists(${HWLOC_LIBRARIES} hwloc_bitmap_free \"\" HAVE_HWLOC_BITMAP)\n\n  set(CMAKE_REQUIRED_INCLUDES ${HWLOC_SAVE_CMAKE_REQUIRED_INCLUDES})\nendif()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindKLU.cmake",
    "content": "# KLU lib usually requires linking to a blas library.\n# It is up to the user of this module to find a BLAS and link to it.\n\nif (KLU_INCLUDES AND KLU_LIBRARIES)\n  set(KLU_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(KLU_INCLUDES\n  NAMES\n  klu.h\n  PATHS\n  $ENV{KLUDIR}\n  ${INCLUDE_INSTALL_DIR}\n  PATH_SUFFIXES\n  suitesparse\n  ufsparse\n)\n\nfind_library(KLU_LIBRARIES klu PATHS $ENV{KLUDIR} ${LIB_INSTALL_DIR})\n\nif(KLU_LIBRARIES)\n\n  if(NOT KLU_LIBDIR)\n    get_filename_component(KLU_LIBDIR ${KLU_LIBRARIES} PATH)\n  endif()\n\n  find_library(COLAMD_LIBRARY colamd PATHS ${KLU_LIBDIR} $ENV{KLUDIR} ${LIB_INSTALL_DIR})\n  if(COLAMD_LIBRARY)\n    set(KLU_LIBRARIES ${KLU_LIBRARIES} ${COLAMD_LIBRARY})\n  endif ()\n  \n  find_library(AMD_LIBRARY amd PATHS ${KLU_LIBDIR} $ENV{KLUDIR} ${LIB_INSTALL_DIR})\n  if(AMD_LIBRARY)\n    set(KLU_LIBRARIES ${KLU_LIBRARIES} ${AMD_LIBRARY})\n  endif ()\n\n  find_library(BTF_LIBRARY btf PATHS $ENV{KLU_LIBDIR} $ENV{KLUDIR} ${LIB_INSTALL_DIR})\n  if(BTF_LIBRARY)\n    set(KLU_LIBRARIES ${KLU_LIBRARIES} ${BTF_LIBRARY})\n  endif()\n\nendif()\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(KLU DEFAULT_MSG\n                                  KLU_INCLUDES KLU_LIBRARIES)\n\nmark_as_advanced(KLU_INCLUDES KLU_LIBRARIES AMD_LIBRARY COLAMD_LIBRARY BTF_LIBRARY)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindLAPACK.cmake",
    "content": "# Find LAPACK library\n#\n# This module finds an installed library that implements the LAPACK\n# linear-algebra interface (see http://www.netlib.org/lapack/).\n# The approach follows mostly that taken for the autoconf macro file, acx_lapack.m4\n# (distributed at http://ac-archive.sourceforge.net/ac-archive/acx_lapack.html).\n#\n# This module sets the following variables:\n#  LAPACK_FOUND - set to true if a library implementing the LAPACK interface\n#    is found\n#  LAPACK_INCLUDE_DIR - Directories containing the LAPACK header files\n#  LAPACK_DEFINITIONS - Compilation options to use LAPACK\n#  LAPACK_LINKER_FLAGS - Linker flags to use LAPACK (excluding -l\n#    and -L).\n#  LAPACK_LIBRARIES_DIR - Directories containing the LAPACK libraries.\n#     May be null if LAPACK_LIBRARIES contains libraries name using full path.\n#  LAPACK_LIBRARIES - List of libraries to link against LAPACK interface.\n#     May be null if the compiler supports auto-link (e.g. VC++).\n#  LAPACK_USE_FILE - The name of the cmake module to include to compile\n#     applications or libraries using LAPACK.\n#\n# This module was modified by CGAL team:\n# - find libraries for a C++ compiler, instead of Fortran\n# - added LAPACK_INCLUDE_DIR, LAPACK_DEFINITIONS and LAPACK_LIBRARIES_DIR\n# - removed LAPACK95_LIBRARIES\n\n\ninclude(CheckFunctionExists)\ninclude(CMakeFindDependencyMacro)\n\n# This macro checks for the existence of the combination of fortran libraries\n# given by _list.  If the combination is found, this macro checks (using the\n# check_function_exists macro) whether can link against that library\n# combination using the name of a routine given by _name using the linker\n# flags given by _flags.  If the combination of libraries is found and passes\n# the link test, LIBRARIES is set to the list of complete library paths that\n# have been found and DEFINITIONS to the required definitions.\n# Otherwise, LIBRARIES is set to FALSE.\n# N.B. _prefix is the prefix applied to the names of all cached variables that\n# are generated internally and marked advanced by this macro.\nmacro(check_lapack_libraries DEFINITIONS LIBRARIES _prefix _name _flags _list _blas _path)\n  #message(\"DEBUG: check_lapack_libraries(${_list} in ${_path} with ${_blas})\")\n\n  # Check for the existence of the libraries given by _list\n  set(_libraries_found TRUE)\n  set(_libraries_work FALSE)\n  set(${DEFINITIONS} \"\")\n  set(${LIBRARIES} \"\")\n  set(_combined_name)\n  foreach(_library ${_list})\n    set(_combined_name ${_combined_name}_${_library})\n\n    if(_libraries_found)\n      # search first in ${_path}\n      find_library(${_prefix}_${_library}_LIBRARY\n                  NAMES ${_library}\n                  PATHS ${_path} NO_DEFAULT_PATH\n                  )\n      # if not found, search in environment variables and system\n      if ( WIN32 )\n        find_library(${_prefix}_${_library}_LIBRARY\n                    NAMES ${_library}\n                    PATHS ENV LIB\n                    )\n      elseif ( APPLE )\n        find_library(${_prefix}_${_library}_LIBRARY\n                    NAMES ${_library}\n                    PATHS /usr/local/lib /usr/lib /usr/local/lib64 /usr/lib64 ENV DYLD_LIBRARY_PATH\n                    )\n      else ()\n        find_library(${_prefix}_${_library}_LIBRARY\n                    NAMES ${_library}\n                    PATHS /usr/local/lib /usr/lib /usr/local/lib64 /usr/lib64 ENV LD_LIBRARY_PATH\n                    )\n      endif()\n      mark_as_advanced(${_prefix}_${_library}_LIBRARY)\n      set(${LIBRARIES} ${${LIBRARIES}} ${${_prefix}_${_library}_LIBRARY})\n      set(_libraries_found ${${_prefix}_${_library}_LIBRARY})\n    endif()\n  endforeach()\n  if(_libraries_found)\n    set(_libraries_found ${${LIBRARIES}})\n  endif()\n\n  # Test this combination of libraries with the Fortran/f2c interface.\n  # We test the Fortran interface first as it is well standardized.\n  if(_libraries_found AND NOT _libraries_work)\n    set(${DEFINITIONS}  \"-D${_prefix}_USE_F2C\")\n    set(${LIBRARIES}    ${_libraries_found})\n    # Some C++ linkers require the f2c library to link with Fortran libraries.\n    # I do not know which ones, thus I just add the f2c library if it is available.\n    find_dependency( F2C QUIET )\n    if ( F2C_FOUND )\n      set(${DEFINITIONS}  ${${DEFINITIONS}} ${F2C_DEFINITIONS})\n      set(${LIBRARIES}    ${${LIBRARIES}} ${F2C_LIBRARIES})\n    endif()\n    set(CMAKE_REQUIRED_DEFINITIONS  ${${DEFINITIONS}})\n    set(CMAKE_REQUIRED_LIBRARIES    ${_flags} ${${LIBRARIES}} ${_blas})\n    #message(\"DEBUG: CMAKE_REQUIRED_DEFINITIONS = ${CMAKE_REQUIRED_DEFINITIONS}\")\n    #message(\"DEBUG: CMAKE_REQUIRED_LIBRARIES = ${CMAKE_REQUIRED_LIBRARIES}\")\n    # Check if function exists with f2c calling convention (ie a trailing underscore)\n    check_function_exists(${_name}_ ${_prefix}_${_name}_${_combined_name}_f2c_WORKS)\n    set(CMAKE_REQUIRED_DEFINITIONS} \"\")\n    set(CMAKE_REQUIRED_LIBRARIES    \"\")\n    mark_as_advanced(${_prefix}_${_name}_${_combined_name}_f2c_WORKS)\n    set(_libraries_work ${${_prefix}_${_name}_${_combined_name}_f2c_WORKS})\n  endif()\n\n  # If not found, test this combination of libraries with a C interface.\n  # A few implementations (ie ACML) provide a C interface. Unfortunately, there is no standard.\n  if(_libraries_found AND NOT _libraries_work)\n    set(${DEFINITIONS} \"\")\n    set(${LIBRARIES}   ${_libraries_found})\n    set(CMAKE_REQUIRED_DEFINITIONS \"\")\n    set(CMAKE_REQUIRED_LIBRARIES   ${_flags} ${${LIBRARIES}} ${_blas})\n    #message(\"DEBUG: CMAKE_REQUIRED_LIBRARIES = ${CMAKE_REQUIRED_LIBRARIES}\")\n    check_function_exists(${_name} ${_prefix}_${_name}${_combined_name}_WORKS)\n    set(CMAKE_REQUIRED_LIBRARIES \"\")\n    mark_as_advanced(${_prefix}_${_name}${_combined_name}_WORKS)\n    set(_libraries_work ${${_prefix}_${_name}${_combined_name}_WORKS})\n  endif()\n\n  # on failure\n  if(NOT _libraries_work)\n    set(${DEFINITIONS} \"\")\n    set(${LIBRARIES}   FALSE)\n  endif()\n  #message(\"DEBUG: ${DEFINITIONS} = ${${DEFINITIONS}}\")\n  #message(\"DEBUG: ${LIBRARIES} = ${${LIBRARIES}}\")\nendmacro()\n\n\n#\n# main\n#\n\n# LAPACK requires BLAS\nif(LAPACK_FIND_QUIETLY OR NOT LAPACK_FIND_REQUIRED)\n  find_dependency(BLAS)\nelse()\n  find_dependency(BLAS REQUIRED)\nendif()\n\nif (NOT BLAS_FOUND)\n\n  message(STATUS \"LAPACK requires BLAS.\")\n  set(LAPACK_FOUND FALSE)\n\n# Is it already configured?\nelseif (LAPACK_LIBRARIES_DIR OR LAPACK_LIBRARIES)\n\n  set(LAPACK_FOUND TRUE)\n\nelse()\n\n  # reset variables\n  set( LAPACK_INCLUDE_DIR \"\" )\n  set( LAPACK_DEFINITIONS \"\" )\n  set( LAPACK_LINKER_FLAGS \"\" ) # unused (yet)\n  set( LAPACK_LIBRARIES \"\" )\n  set( LAPACK_LIBRARIES_DIR \"\" )\n\n    #\n    # If Unix, search for LAPACK function in possible libraries\n    #\n\n    #intel mkl lapack?\n    if(NOT LAPACK_LIBRARIES)\n      check_lapack_libraries(\n      LAPACK_DEFINITIONS\n      LAPACK_LIBRARIES\n      LAPACK\n      cheev\n      \"\"\n      \"mkl_lapack\"\n      \"${BLAS_LIBRARIES}\"\n      \"${CGAL_TAUCS_LIBRARIES_DIR} ENV LAPACK_LIB_DIR\"\n      )\n    endif()\n\n    #acml lapack?\n    if(NOT LAPACK_LIBRARIES)\n      check_lapack_libraries(\n      LAPACK_DEFINITIONS\n      LAPACK_LIBRARIES\n      LAPACK\n      cheev\n      \"\"\n      \"acml\"\n      \"${BLAS_LIBRARIES}\"\n      \"${CGAL_TAUCS_LIBRARIES_DIR} ENV LAPACK_LIB_DIR\"\n      )\n    endif()\n\n    # Apple LAPACK library?\n    if(NOT LAPACK_LIBRARIES)\n      check_lapack_libraries(\n      LAPACK_DEFINITIONS\n      LAPACK_LIBRARIES\n      LAPACK\n      cheev\n      \"\"\n      \"Accelerate\"\n      \"${BLAS_LIBRARIES}\"\n      \"${CGAL_TAUCS_LIBRARIES_DIR} ENV LAPACK_LIB_DIR\"\n      )\n    endif()\n\n    if ( NOT LAPACK_LIBRARIES )\n      check_lapack_libraries(\n      LAPACK_DEFINITIONS\n      LAPACK_LIBRARIES\n      LAPACK\n      cheev\n      \"\"\n      \"vecLib\"\n      \"${BLAS_LIBRARIES}\"\n      \"${CGAL_TAUCS_LIBRARIES_DIR} ENV LAPACK_LIB_DIR\"\n      )\n    endif ()\n\n    # Generic LAPACK library?\n    # This configuration *must* be the last try as this library is notably slow.\n    if ( NOT LAPACK_LIBRARIES )\n      check_lapack_libraries(\n      LAPACK_DEFINITIONS\n      LAPACK_LIBRARIES\n      LAPACK\n      cheev\n      \"\"\n      \"lapack\"\n      \"${BLAS_LIBRARIES}\"\n      \"${CGAL_TAUCS_LIBRARIES_DIR} ENV LAPACK_LIB_DIR\"\n      )\n    endif()\n\n  if(LAPACK_LIBRARIES_DIR OR LAPACK_LIBRARIES)\n    set(LAPACK_FOUND TRUE)\n  else()\n    set(LAPACK_FOUND FALSE)\n  endif()\n\n  if(NOT LAPACK_FIND_QUIETLY)\n    if(LAPACK_FOUND)\n      message(STATUS \"A library with LAPACK API found.\")\n    else()\n      if(LAPACK_FIND_REQUIRED)\n        message(FATAL_ERROR \"A required library with LAPACK API not found. Please specify library location.\")\n      else()\n        message(STATUS \"A library with LAPACK API not found. Please specify library location.\")\n      endif()\n    endif()\n  endif()\n\n  # Add variables to cache\n  set( LAPACK_INCLUDE_DIR   \"${LAPACK_INCLUDE_DIR}\"\n                            CACHE PATH \"Directories containing the LAPACK header files\" FORCE )\n  set( LAPACK_DEFINITIONS   \"${LAPACK_DEFINITIONS}\"\n                            CACHE STRING \"Compilation options to use LAPACK\" FORCE )\n  set( LAPACK_LINKER_FLAGS  \"${LAPACK_LINKER_FLAGS}\"\n                            CACHE STRING \"Linker flags to use LAPACK\" FORCE )\n  set( LAPACK_LIBRARIES     \"${LAPACK_LIBRARIES}\"\n                            CACHE FILEPATH \"LAPACK libraries name\" FORCE )\n  set( LAPACK_LIBRARIES_DIR \"${LAPACK_LIBRARIES_DIR}\"\n                            CACHE PATH \"Directories containing the LAPACK libraries\" FORCE )\n\n  #message(\"DEBUG: LAPACK_INCLUDE_DIR = ${LAPACK_INCLUDE_DIR}\")\n  #message(\"DEBUG: LAPACK_DEFINITIONS = ${LAPACK_DEFINITIONS}\")\n  #message(\"DEBUG: LAPACK_LINKER_FLAGS = ${LAPACK_LINKER_FLAGS}\")\n  #message(\"DEBUG: LAPACK_LIBRARIES = ${LAPACK_LIBRARIES}\")\n  #message(\"DEBUG: LAPACK_LIBRARIES_DIR = ${LAPACK_LIBRARIES_DIR}\")\n  #message(\"DEBUG: LAPACK_FOUND = ${LAPACK_FOUND}\")\n\nendif()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindMPFR.cmake",
    "content": "# Try to find the MPFR library\n# See http://www.mpfr.org/\n#\n# This module supports requiring a minimum version, e.g. you can do\n#   find_package(MPFR 2.3.0)\n# to require version 2.3.0 to newer of MPFR.\n#\n# Once done this will define\n#\n#  MPFR_FOUND - system has MPFR lib with correct version\n#  MPFR_INCLUDES - the MPFR include directory\n#  MPFR_LIBRARIES - the MPFR library\n#  MPFR_VERSION - MPFR version\n\n# Copyright (c) 2006, 2007 Montel Laurent, <montel@kde.org>\n# Copyright (c) 2008, 2009 Gael Guennebaud, <g.gael@free.fr>\n# Copyright (c) 2010 Jitse Niesen, <jitse@maths.leeds.ac.uk>\n# Redistribution and use is allowed according to the terms of the BSD license.\n\n# Set MPFR_INCLUDES\n\nfind_path(MPFR_INCLUDES\n  NAMES\n  mpfr.h\n  PATHS\n  $ENV{GMPDIR}\n  ${INCLUDE_INSTALL_DIR}\n)\n\n# Set MPFR_FIND_VERSION to 1.0.0 if no minimum version is specified\n\nif(NOT MPFR_FIND_VERSION)\n  if(NOT MPFR_FIND_VERSION_MAJOR)\n    set(MPFR_FIND_VERSION_MAJOR 1)\n  endif()\n  if(NOT MPFR_FIND_VERSION_MINOR)\n    set(MPFR_FIND_VERSION_MINOR 0)\n  endif()\n  if(NOT MPFR_FIND_VERSION_PATCH)\n    set(MPFR_FIND_VERSION_PATCH 0)\n  endif()\n\n  set(MPFR_FIND_VERSION \"${MPFR_FIND_VERSION_MAJOR}.${MPFR_FIND_VERSION_MINOR}.${MPFR_FIND_VERSION_PATCH}\")\nendif()\n\n\nif(MPFR_INCLUDES)\n\n  # Set MPFR_VERSION\n  \n  file(READ \"${MPFR_INCLUDES}/mpfr.h\" _mpfr_version_header)\n  \n  string(REGEX MATCH \"define[ \\t]+MPFR_VERSION_MAJOR[ \\t]+([0-9]+)\" _mpfr_major_version_match \"${_mpfr_version_header}\")\n  set(MPFR_MAJOR_VERSION \"${CMAKE_MATCH_1}\")\n  string(REGEX MATCH \"define[ \\t]+MPFR_VERSION_MINOR[ \\t]+([0-9]+)\" _mpfr_minor_version_match \"${_mpfr_version_header}\")\n  set(MPFR_MINOR_VERSION \"${CMAKE_MATCH_1}\")\n  string(REGEX MATCH \"define[ \\t]+MPFR_VERSION_PATCHLEVEL[ \\t]+([0-9]+)\" _mpfr_patchlevel_version_match \"${_mpfr_version_header}\")\n  set(MPFR_PATCHLEVEL_VERSION \"${CMAKE_MATCH_1}\")\n  \n  set(MPFR_VERSION ${MPFR_MAJOR_VERSION}.${MPFR_MINOR_VERSION}.${MPFR_PATCHLEVEL_VERSION})\n  \n  # Check whether found version exceeds minimum version\n  \n  if(${MPFR_VERSION} VERSION_LESS ${MPFR_FIND_VERSION})\n    set(MPFR_VERSION_OK FALSE)\n    message(STATUS \"MPFR version ${MPFR_VERSION} found in ${MPFR_INCLUDES}, \"\n                   \"but at least version ${MPFR_FIND_VERSION} is required\")\n  else()\n    set(MPFR_VERSION_OK TRUE)\n  endif()\n\nendif()\n\n# Set MPFR_LIBRARIES\n\nfind_library(MPFR_LIBRARIES mpfr PATHS $ENV{GMPDIR} ${LIB_INSTALL_DIR})\n\n# Epilogue\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(MPFR DEFAULT_MSG\n                                  MPFR_INCLUDES MPFR_LIBRARIES MPFR_VERSION_OK)\nmark_as_advanced(MPFR_INCLUDES MPFR_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindMPREAL.cmake",
    "content": "# Try to find the MPFR C++ (MPREAL) library\n# See http://www.holoborodko.com/pavel/mpreal/\n#\n# This module supports requiring a minimum version, e.g. you can do\n#   find_package(MPREAL 1.8.6)\n# to require version 1.8.6 or newer of MPREAL C++.\n#\n# Once done this will define\n#\n#  MPREAL_FOUND - system has MPREAL lib with correct version\n#  MPREAL_INCLUDES - MPREAL required include directories\n#  MPREAL_LIBRARIES - MPREAL required libraries\n#  MPREAL_VERSION - MPREAL version\n\n# Copyright (c) 2020 The Eigen Authors.\n# Redistribution and use is allowed according to the terms of the BSD license.\n\ninclude(CMakeFindDependencyMacro)\nfind_dependency(MPFR)\nfind_dependency(GMP)\n\n# Set MPREAL_INCLUDES\nfind_path(MPREAL_INCLUDES\n  NAMES\n  mpreal.h\n  PATHS\n  $ENV{GMPDIR}\n  ${INCLUDE_INSTALL_DIR}\n)\n\n# Set MPREAL_FIND_VERSION to 1.0.0 if no minimum version is specified\n\nif(NOT MPREAL_FIND_VERSION)\n  if(NOT MPREAL_FIND_VERSION_MAJOR)\n    set(MPREAL_FIND_VERSION_MAJOR 1)\n  endif()\n  if(NOT MPREAL_FIND_VERSION_MINOR)\n    set(MPREAL_FIND_VERSION_MINOR 0)\n  endif()\n  if(NOT MPREAL_FIND_VERSION_PATCH)\n    set(MPREAL_FIND_VERSION_PATCH 0)\n  endif()\n\n  set(MPREAL_FIND_VERSION \"${MPREAL_FIND_VERSION_MAJOR}.${MPREAL_FIND_VERSION_MINOR}.${MPREAL_FIND_VERSION_PATCH}\")\nendif()\n\n# Check bugs\n# - https://github.com/advanpix/mpreal/issues/7\n# - https://github.com/advanpix/mpreal/issues/9\nset(MPREAL_TEST_PROGRAM \"\n#include <mpreal.h>\n#include <algorithm>\nint main(int argc, char** argv) {\n  const mpfr::mpreal one  =    1.0;\n  const mpfr::mpreal zero =    0.0;\n  using namespace std;\n  const mpfr::mpreal smaller = min(one, zero);\n  return 0;\n}\")\n\nif(MPREAL_INCLUDES)\n\n  # Set MPREAL_VERSION\n  \n  file(READ \"${MPREAL_INCLUDES}/mpreal.h\" _mpreal_version_header)\n  \n  string(REGEX MATCH \"define[ \\t]+MPREAL_VERSION_MAJOR[ \\t]+([0-9]+)\" _mpreal_major_version_match \"${_mpreal_version_header}\")\n  set(MPREAL_MAJOR_VERSION \"${CMAKE_MATCH_1}\")\n  string(REGEX MATCH \"define[ \\t]+MPREAL_VERSION_MINOR[ \\t]+([0-9]+)\" _mpreal_minor_version_match \"${_mpreal_version_header}\")\n  set(MPREAL_MINOR_VERSION \"${CMAKE_MATCH_1}\")\n  string(REGEX MATCH \"define[ \\t]+MPREAL_VERSION_PATCHLEVEL[ \\t]+([0-9]+)\" _mpreal_patchlevel_version_match \"${_mpreal_version_header}\")\n  set(MPREAL_PATCHLEVEL_VERSION \"${CMAKE_MATCH_1}\")\n  \n  set(MPREAL_VERSION ${MPREAL_MAJOR_VERSION}.${MPREAL_MINOR_VERSION}.${MPREAL_PATCHLEVEL_VERSION})\n  \n  # Check whether found version exceeds minimum version\n  \n  if(${MPREAL_VERSION} VERSION_LESS ${MPREAL_FIND_VERSION})\n    set(MPREAL_VERSION_OK FALSE)\n    message(STATUS \"MPREAL version ${MPREAL_VERSION} found in ${MPREAL_INCLUDES}, \"\n                   \"but at least version ${MPREAL_FIND_VERSION} is required\")\n  else()\n    set(MPREAL_VERSION_OK TRUE)\n    \n    list(APPEND MPREAL_INCLUDES \"${MPFR_INCLUDES}\" \"${GMP_INCLUDES}\")\n    list(REMOVE_DUPLICATES MPREAL_INCLUDES)\n    \n    list(APPEND MPREAL_LIBRARIES \"${MPFR_LIBRARIES}\" \"${GMP_LIBRARIES}\")\n    list(REMOVE_DUPLICATES MPREAL_LIBRARIES)\n    \n    # Make sure it compiles with the current compiler.\n    unset(MPREAL_WORKS CACHE)\n    include(CheckCXXSourceCompiles)\n    set(CMAKE_REQUIRED_INCLUDES \"${MPREAL_INCLUDES}\")\n    set(CMAKE_REQUIRED_LIBRARIES \"${MPREAL_LIBRARIES}\")\n    check_cxx_source_compiles(\"${MPREAL_TEST_PROGRAM}\" MPREAL_WORKS)\n  endif()\nendif()\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(MPREAL DEFAULT_MSG\n                                  MPREAL_INCLUDES MPREAL_VERSION_OK MPREAL_WORKS)\nmark_as_advanced(MPREAL_INCLUDES)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindMetis.cmake",
    "content": "###\n#\n# @copyright (c) 2009-2014 The University of Tennessee and The University\n#                          of Tennessee Research Foundation.\n#                          All rights reserved.\n# @copyright (c) 2012-2014 Inria. All rights reserved.\n# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved.\n#\n###\n#\n# - Find METIS include dirs and libraries\n# Use this module by invoking find_package with the form:\n#  find_package(METIS\n#               [REQUIRED]             # Fail with error if metis is not found\n#              )\n#\n# This module finds headers and metis library.\n# Results are reported in variables:\n#  METIS_FOUND           - True if headers and requested libraries were found\n#  METIS_INCLUDE_DIRS    - metis include directories\n#  METIS_LIBRARY_DIRS    - Link directories for metis libraries\n#  METIS_LIBRARIES       - metis component libraries to be linked\n#\n# The user can give specific paths where to find the libraries adding cmake\n# options at configure (ex: cmake path/to/project -DMETIS_DIR=path/to/metis):\n#  METIS_DIR             - Where to find the base directory of metis\n#  METIS_INCDIR          - Where to find the header files\n#  METIS_LIBDIR          - Where to find the library files\n# The module can also look for the following environment variables if paths\n# are not given as cmake variable: METIS_DIR, METIS_INCDIR, METIS_LIBDIR\n\n#=============================================================================\n# Copyright 2012-2013 Inria\n# Copyright 2012-2013 Emmanuel Agullo\n# Copyright 2012-2013 Mathieu Faverge\n# Copyright 2012      Cedric Castagnede\n# Copyright 2013      Florent Pruvost\n#\n# Distributed under the OSI-approved BSD License (the \"License\");\n# see accompanying file MORSE-Copyright.txt for details.\n#\n# This software is distributed WITHOUT ANY WARRANTY; without even the\n# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.\n# See the License for more information.\n#=============================================================================\n# (To distribute this file outside of Morse, substitute the full\n#  License text for the above reference.)\n\nif (NOT METIS_FOUND)\n  set(METIS_DIR \"\" CACHE PATH \"Installation directory of METIS library\")\n  if (NOT METIS_FIND_QUIETLY)\n    message(STATUS \"A cache variable, namely METIS_DIR, has been set to specify the install directory of METIS\")\n  endif()\nendif()\n\n# Looking for include\n# -------------------\n\n# Add system include paths to search include\n# ------------------------------------------\nunset(_inc_env)\nset(ENV_METIS_DIR \"$ENV{METIS_DIR}\")\nset(ENV_METIS_INCDIR \"$ENV{METIS_INCDIR}\")\nif(ENV_METIS_INCDIR)\n  list(APPEND _inc_env \"${ENV_METIS_INCDIR}\")\nelseif(ENV_METIS_DIR)\n  list(APPEND _inc_env \"${ENV_METIS_DIR}\")\n  list(APPEND _inc_env \"${ENV_METIS_DIR}/include\")\n  list(APPEND _inc_env \"${ENV_METIS_DIR}/include/metis\")\nelse()\n  if(WIN32)\n    string(REPLACE \":\" \";\" _inc_env \"$ENV{INCLUDE}\")\n  else()\n    string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{C_INCLUDE_PATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{CPATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE_PATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n  endif()\nendif()\nlist(APPEND _inc_env \"${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}\")\nlist(APPEND _inc_env \"${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}\")\nlist(REMOVE_DUPLICATES _inc_env)\n\n\n# Try to find the metis header in the given paths\n# -------------------------------------------------\n# call cmake macro to find the header path\nif(METIS_INCDIR)\n  set(METIS_metis.h_DIRS \"METIS_metis.h_DIRS-NOTFOUND\")\n  find_path(METIS_metis.h_DIRS\n    NAMES metis.h\n    HINTS ${METIS_INCDIR})\nelse()\n  if(METIS_DIR)\n    set(METIS_metis.h_DIRS \"METIS_metis.h_DIRS-NOTFOUND\")\n    find_path(METIS_metis.h_DIRS\n      NAMES metis.h\n      HINTS ${METIS_DIR}\n      PATH_SUFFIXES \"include\" \"include/metis\")\n  else()\n    set(METIS_metis.h_DIRS \"METIS_metis.h_DIRS-NOTFOUND\")\n    find_path(METIS_metis.h_DIRS\n      NAMES metis.h\n      HINTS ${_inc_env})\n  endif()\nendif()\nmark_as_advanced(METIS_metis.h_DIRS)\n\n\n# If found, add path to cmake variable\n# ------------------------------------\nif (METIS_metis.h_DIRS)\n  set(METIS_INCLUDE_DIRS \"${METIS_metis.h_DIRS}\")\nelse ()\n  set(METIS_INCLUDE_DIRS \"METIS_INCLUDE_DIRS-NOTFOUND\")\n  if(NOT METIS_FIND_QUIETLY)\n    message(STATUS \"Looking for metis -- metis.h not found\")\n  endif()\nendif()\n\n\n# Looking for lib\n# ---------------\n\n# Add system library paths to search lib\n# --------------------------------------\nunset(_lib_env)\nset(ENV_METIS_LIBDIR \"$ENV{METIS_LIBDIR}\")\nif(ENV_METIS_LIBDIR)\n  list(APPEND _lib_env \"${ENV_METIS_LIBDIR}\")\nelseif(ENV_METIS_DIR)\n  list(APPEND _lib_env \"${ENV_METIS_DIR}\")\n  list(APPEND _lib_env \"${ENV_METIS_DIR}/lib\")\nelse()\n  if(WIN32)\n    string(REPLACE \":\" \";\" _lib_env \"$ENV{LIB}\")\n  else()\n    if(APPLE)\n      string(REPLACE \":\" \";\" _lib_env \"$ENV{DYLD_LIBRARY_PATH}\")\n    else()\n      string(REPLACE \":\" \";\" _lib_env \"$ENV{LD_LIBRARY_PATH}\")\n    endif()\n    list(APPEND _lib_env \"${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}\")\n    list(APPEND _lib_env \"${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}\")\n  endif()\nendif()\nlist(REMOVE_DUPLICATES _lib_env)\n\n# Try to find the metis lib in the given paths\n# ----------------------------------------------\n# call cmake macro to find the lib path\nif(METIS_LIBDIR)\n  set(METIS_metis_LIBRARY \"METIS_metis_LIBRARY-NOTFOUND\")\n  find_library(METIS_metis_LIBRARY\n    NAMES metis\n    HINTS ${METIS_LIBDIR})\nelse()\n  if(METIS_DIR)\n    set(METIS_metis_LIBRARY \"METIS_metis_LIBRARY-NOTFOUND\")\n    find_library(METIS_metis_LIBRARY\n      NAMES metis\n      HINTS ${METIS_DIR}\n      PATH_SUFFIXES lib lib32 lib64)\n  else()\n    set(METIS_metis_LIBRARY \"METIS_metis_LIBRARY-NOTFOUND\")\n    find_library(METIS_metis_LIBRARY\n      NAMES metis\n      HINTS ${_lib_env})\n  endif()\nendif()\nmark_as_advanced(METIS_metis_LIBRARY)\n\n\n# If found, add path to cmake variable\n# ------------------------------------\nif (METIS_metis_LIBRARY)\n  get_filename_component(metis_lib_path \"${METIS_metis_LIBRARY}\" PATH)\n  # set cmake variables\n  set(METIS_LIBRARIES    \"${METIS_metis_LIBRARY}\")\n  set(METIS_LIBRARY_DIRS \"${metis_lib_path}\")\nelse ()\n  set(METIS_LIBRARIES    \"METIS_LIBRARIES-NOTFOUND\")\n  set(METIS_LIBRARY_DIRS \"METIS_LIBRARY_DIRS-NOTFOUND\")\n  if(NOT METIS_FIND_QUIETLY)\n    message(STATUS \"Looking for metis -- lib metis not found\")\n  endif()\nendif ()\n\n# check a function to validate the find\nif(METIS_LIBRARIES)\n\n  set(REQUIRED_INCDIRS)\n  set(REQUIRED_LIBDIRS)\n  set(REQUIRED_LIBS)\n\n  # METIS\n  if (METIS_INCLUDE_DIRS)\n    set(REQUIRED_INCDIRS  \"${METIS_INCLUDE_DIRS}\")\n  endif()\n  if (METIS_LIBRARY_DIRS)\n    set(REQUIRED_LIBDIRS \"${METIS_LIBRARY_DIRS}\")\n  endif()\n  set(REQUIRED_LIBS \"${METIS_LIBRARIES}\")\n  # m\n  find_library(M_LIBRARY NAMES m)\n  mark_as_advanced(M_LIBRARY)\n  if(M_LIBRARY)\n    list(APPEND REQUIRED_LIBS \"-lm\")\n  endif()\n\n  # set required libraries for link\n  set(CMAKE_REQUIRED_INCLUDES \"${REQUIRED_INCDIRS}\")\n  set(CMAKE_REQUIRED_LIBRARIES)\n  foreach(lib_dir ${REQUIRED_LIBDIRS})\n    list(APPEND CMAKE_REQUIRED_LIBRARIES \"-L${lib_dir}\")\n  endforeach()\n  list(APPEND CMAKE_REQUIRED_LIBRARIES \"${REQUIRED_LIBS}\")\n  string(REGEX REPLACE \"^ -\" \"-\" CMAKE_REQUIRED_LIBRARIES \"${CMAKE_REQUIRED_LIBRARIES}\")\n\n  # test link\n  unset(METIS_WORKS CACHE)\n  include(CheckFunctionExists)\n  check_function_exists(METIS_NodeND METIS_WORKS)\n  mark_as_advanced(METIS_WORKS)\n\n  if(NOT METIS_WORKS)\n    if(NOT METIS_FIND_QUIETLY)\n      message(STATUS \"Looking for METIS : test of METIS_NodeND with METIS library fails\")\n      message(STATUS \"CMAKE_REQUIRED_LIBRARIES: ${CMAKE_REQUIRED_LIBRARIES}\")\n      message(STATUS \"CMAKE_REQUIRED_INCLUDES: ${CMAKE_REQUIRED_INCLUDES}\")\n      message(STATUS \"Check in CMakeFiles/CMakeError.log to figure out why it fails\")\n    endif()\n  endif()\n  set(CMAKE_REQUIRED_INCLUDES)\n  set(CMAKE_REQUIRED_FLAGS)\n  set(CMAKE_REQUIRED_LIBRARIES)\nendif()\n\nif (METIS_LIBRARIES)\n  list(GET METIS_LIBRARIES 0 first_lib)\n  get_filename_component(first_lib_path \"${first_lib}\" PATH)\n  if (${first_lib_path} MATCHES \"/lib(32|64)?$\")\n    string(REGEX REPLACE \"/lib(32|64)?$\" \"\" not_cached_dir \"${first_lib_path}\")\n    set(METIS_DIR_FOUND \"${not_cached_dir}\" CACHE PATH \"Installation directory of METIS library\" FORCE)\n  else()\n    set(METIS_DIR_FOUND \"${first_lib_path}\" CACHE PATH \"Installation directory of METIS library\" FORCE)\n  endif()\nendif()\nmark_as_advanced(METIS_DIR)\nmark_as_advanced(METIS_DIR_FOUND)\n\n# check that METIS has been found\n# ---------------------------------\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(METIS DEFAULT_MSG\n  METIS_LIBRARIES\n  METIS_WORKS\n  METIS_INCLUDE_DIRS)\n#\n# TODO: Add possibility to check for specific functions in the library\n#\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindPASTIX.cmake",
    "content": "###\n#\n# @copyright (c) 2009-2014 The University of Tennessee and The University\n#                          of Tennessee Research Foundation.\n#                          All rights reserved.\n# @copyright (c) 2012-2014 Inria. All rights reserved.\n# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved.\n#\n###\n#\n# - Find PASTIX include dirs and libraries\n# Use this module by invoking find_package with the form:\n#  find_package(PASTIX\n#               [REQUIRED] # Fail with error if pastix is not found\n#               [COMPONENTS <comp1> <comp2> ...] # dependencies\n#              )\n#\n#  PASTIX depends on the following libraries:\n#   - Threads, m, rt\n#   - MPI\n#   - HWLOC\n#   - BLAS\n#\n#  COMPONENTS are optional libraries PASTIX could be linked with,\n#  Use it to drive detection of a specific compilation chain\n#  COMPONENTS can be some of the following:\n#   - MPI: to activate detection of the parallel MPI version (default)\n#        it looks for Threads, HWLOC, BLAS, MPI and ScaLAPACK libraries\n#   - SEQ: to activate detection of the sequential version (exclude MPI version)\n#   - STARPU: to activate detection of StarPU version\n#   it looks for MPI version of StarPU (default behaviour)\n#   if SEQ and STARPU are given, it looks for a StarPU without MPI\n#   - STARPU_CUDA: to activate detection of StarPU with CUDA\n#   - STARPU_FXT: to activate detection of StarPU with FxT\n#   - SCOTCH: to activate detection of PASTIX linked with SCOTCH\n#   - PTSCOTCH: to activate detection of PASTIX linked with SCOTCH\n#   - METIS: to activate detection of PASTIX linked with SCOTCH\n#\n# This module finds headers and pastix library.\n# Results are reported in variables:\n#  PASTIX_FOUND            - True if headers and requested libraries were found\n#  PASTIX_LINKER_FLAGS     - list of required linker flags (excluding -l and -L)\n#  PASTIX_INCLUDE_DIRS     - pastix include directories\n#  PASTIX_LIBRARY_DIRS     - Link directories for pastix libraries\n#  PASTIX_LIBRARIES        - pastix libraries\n#  PASTIX_INCLUDE_DIRS_DEP - pastix + dependencies include directories\n#  PASTIX_LIBRARY_DIRS_DEP - pastix + dependencies link directories\n#  PASTIX_LIBRARIES_DEP    - pastix libraries + dependencies\n#\n# The user can give specific paths where to find the libraries adding cmake\n# options at configure (ex: cmake path/to/project -DPASTIX_DIR=path/to/pastix):\n#  PASTIX_DIR              - Where to find the base directory of pastix\n#  PASTIX_INCDIR           - Where to find the header files\n#  PASTIX_LIBDIR           - Where to find the library files\n# The module can also look for the following environment variables if paths\n# are not given as cmake variable: PASTIX_DIR, PASTIX_INCDIR, PASTIX_LIBDIR\n\n#=============================================================================\n# Copyright 2012-2013 Inria\n# Copyright 2012-2013 Emmanuel Agullo\n# Copyright 2012-2013 Mathieu Faverge\n# Copyright 2012      Cedric Castagnede\n# Copyright 2013      Florent Pruvost\n#\n# Distributed under the OSI-approved BSD License (the \"License\");\n# see accompanying file MORSE-Copyright.txt for details.\n#\n# This software is distributed WITHOUT ANY WARRANTY; without even the\n# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.\n# See the License for more information.\n#=============================================================================\n# (To distribute this file outside of Morse, substitute the full\n#  License text for the above reference.)\n\n\nif (NOT PASTIX_FOUND)\n  set(PASTIX_DIR \"\" CACHE PATH \"Installation directory of PASTIX library\")\n  if (NOT PASTIX_FIND_QUIETLY)\n    message(STATUS \"A cache variable, namely PASTIX_DIR, has been set to specify the install directory of PASTIX\")\n  endif()\nendif()\n\n# Set the version to find\nset(PASTIX_LOOK_FOR_MPI ON)\nset(PASTIX_LOOK_FOR_SEQ OFF)\nset(PASTIX_LOOK_FOR_STARPU OFF)\nset(PASTIX_LOOK_FOR_STARPU_CUDA OFF)\nset(PASTIX_LOOK_FOR_STARPU_FXT OFF)\nset(PASTIX_LOOK_FOR_SCOTCH ON)\nset(PASTIX_LOOK_FOR_PTSCOTCH OFF)\nset(PASTIX_LOOK_FOR_METIS OFF)\n\nif( PASTIX_FIND_COMPONENTS )\n  foreach( component ${PASTIX_FIND_COMPONENTS} )\n    if (${component} STREQUAL \"SEQ\")\n      # means we look for the sequential version of PaStiX (without MPI)\n      set(PASTIX_LOOK_FOR_SEQ ON)\n      set(PASTIX_LOOK_FOR_MPI OFF)\n    endif()\n    if (${component} STREQUAL \"MPI\")\n      # means we look for the MPI version of PaStiX (default)\n      set(PASTIX_LOOK_FOR_SEQ OFF)\n      set(PASTIX_LOOK_FOR_MPI ON)\n    endif()\n    if (${component} STREQUAL \"STARPU\")\n      # means we look for PaStiX with StarPU\n      set(PASTIX_LOOK_FOR_STARPU ON)\n    endif()\n    if (${component} STREQUAL \"STARPU_CUDA\")\n      # means we look for PaStiX with StarPU + CUDA\n      set(PASTIX_LOOK_FOR_STARPU ON)\n      set(PASTIX_LOOK_FOR_STARPU_CUDA ON)\n    endif()\n    if (${component} STREQUAL \"STARPU_FXT\")\n      # means we look for PaStiX with StarPU + FxT\n      set(PASTIX_LOOK_FOR_STARPU_FXT ON)\n    endif()\n    if (${component} STREQUAL \"SCOTCH\")\n      set(PASTIX_LOOK_FOR_SCOTCH ON)\n    endif()\n    if (${component} STREQUAL \"PTSCOTCH\")\n      set(PASTIX_LOOK_FOR_PTSCOTCH ON)\n    endif()\n    if (${component} STREQUAL \"METIS\")\n      set(PASTIX_LOOK_FOR_METIS ON)\n    endif()\n  endforeach()\nendif()\n\n# Dependencies detection\n# ----------------------\n\n\n# Required dependencies\n# ---------------------\ninclude(CMakeFindDependencyMacro)\nif (NOT PASTIX_FIND_QUIETLY)\n  message(STATUS \"Looking for PASTIX - Try to detect pthread\")\nendif()\nif (PASTIX_FIND_REQUIRED)\n  find_dependency(Threads REQUIRED QUIET)\nelse()\n  find_dependency(Threads QUIET)\nendif()\nset(PASTIX_EXTRA_LIBRARIES \"\")\nif( THREADS_FOUND )\n  list(APPEND PASTIX_EXTRA_LIBRARIES ${CMAKE_THREAD_LIBS_INIT})\nendif ()\n\n# Add math library to the list of extra\n# it normally exists on all common systems provided with a C compiler\nif (NOT PASTIX_FIND_QUIETLY)\n  message(STATUS \"Looking for PASTIX - Try to detect libm\")\nendif()\nset(PASTIX_M_LIBRARIES \"\")\nif(UNIX OR WIN32)\n  find_library(\n    PASTIX_M_m_LIBRARY\n    NAMES m\n    )\n  mark_as_advanced(PASTIX_M_m_LIBRARY)\n  if (PASTIX_M_m_LIBRARY)\n    list(APPEND PASTIX_M_LIBRARIES \"${PASTIX_M_m_LIBRARY}\")\n    list(APPEND PASTIX_EXTRA_LIBRARIES \"${PASTIX_M_m_LIBRARY}\")\n  else()\n    if (PASTIX_FIND_REQUIRED)\n      message(FATAL_ERROR \"Could NOT find libm on your system.\"\n\t\"Are you sure to a have a C compiler installed?\")\n    endif()\n  endif()\nendif()\n\n# Try to find librt (libposix4 - POSIX.1b Realtime Extensions library)\n# on Unix systems except Apple ones because it does not exist on it\nif (NOT PASTIX_FIND_QUIETLY)\n  message(STATUS \"Looking for PASTIX - Try to detect librt\")\nendif()\nset(PASTIX_RT_LIBRARIES \"\")\nif(UNIX AND NOT APPLE)\n  find_library(\n    PASTIX_RT_rt_LIBRARY\n    NAMES rt\n    )\n  mark_as_advanced(PASTIX_RT_rt_LIBRARY)\n  if (PASTIX_RT_rt_LIBRARY)\n    list(APPEND PASTIX_RT_LIBRARIES \"${PASTIX_RT_rt_LIBRARY}\")\n    list(APPEND PASTIX_EXTRA_LIBRARIES \"${PASTIX_RT_rt_LIBRARY}\")\n  else()\n    if (PASTIX_FIND_REQUIRED)\n      message(FATAL_ERROR \"Could NOT find librt on your system\")\n    endif()\n  endif()\nendif()\n\n# PASTIX depends on HWLOC\n#------------------------\nif (NOT PASTIX_FIND_QUIETLY)\n  message(STATUS \"Looking for PASTIX - Try to detect HWLOC\")\nendif()\nif (PASTIX_FIND_REQUIRED)\n  find_dependency(HWLOC REQUIRED QUIET)\nelse()\n  find_dependency(HWLOC QUIET)\nendif()\n\n# PASTIX depends on BLAS\n#-----------------------\nif (NOT PASTIX_FIND_QUIETLY)\n  message(STATUS \"Looking for PASTIX - Try to detect BLAS\")\nendif()\nif (PASTIX_FIND_REQUIRED)\n  find_dependency(BLASEXT REQUIRED QUIET)\nelse()\n  find_dependency(BLASEXT QUIET)\nendif()\n\n# Optional dependencies\n# ---------------------\n\n# PASTIX may depend on MPI\n#-------------------------\nif (NOT MPI_FOUND AND PASTIX_LOOK_FOR_MPI)\n  if (NOT PASTIX_FIND_QUIETLY)\n    message(STATUS \"Looking for PASTIX - Try to detect MPI\")\n  endif()\n  # allows to use an external mpi compilation by setting compilers with\n  # -DMPI_C_COMPILER=path/to/mpicc -DMPI_Fortran_COMPILER=path/to/mpif90\n  # at cmake configure\n  if(NOT MPI_C_COMPILER)\n    set(MPI_C_COMPILER mpicc)\n  endif()\n  if (PASTIX_FIND_REQUIRED AND PASTIX_FIND_REQUIRED_MPI)\n    find_dependency(MPI REQUIRED QUIET)\n  else()\n    find_dependency(MPI QUIET)\n  endif()\n  if (MPI_FOUND)\n    mark_as_advanced(MPI_LIBRARY)\n    mark_as_advanced(MPI_EXTRA_LIBRARY)\n  endif()\nendif ()\n\n# PASTIX may depend on STARPU\n#----------------------------\nif( NOT STARPU_FOUND AND PASTIX_LOOK_FOR_STARPU)\n\n  if (NOT PASTIX_FIND_QUIETLY)\n    message(STATUS \"Looking for PASTIX - Try to detect StarPU\")\n  endif()\n\n  set(PASTIX_STARPU_VERSION \"1.1\" CACHE STRING \"oldest STARPU version desired\")\n\n  # create list of components in order to make a single call to find_package(starpu...)\n  # we explicitly need a StarPU version built with hwloc\n  set(STARPU_COMPONENT_LIST \"HWLOC\")\n\n  # StarPU may depend on MPI\n  # allows to use an external mpi compilation by setting compilers with\n  # -DMPI_C_COMPILER=path/to/mpicc -DMPI_Fortran_COMPILER=path/to/mpif90\n  # at cmake configure\n  if (PASTIX_LOOK_FOR_MPI)\n    if(NOT MPI_C_COMPILER)\n      set(MPI_C_COMPILER mpicc)\n    endif()\n    list(APPEND STARPU_COMPONENT_LIST \"MPI\")\n  endif()\n  if (PASTIX_LOOK_FOR_STARPU_CUDA)\n    list(APPEND STARPU_COMPONENT_LIST \"CUDA\")\n  endif()\n  if (PASTIX_LOOK_FOR_STARPU_FXT)\n    list(APPEND STARPU_COMPONENT_LIST \"FXT\")\n  endif()\n  # set the list of optional dependencies we may discover\n  if (PASTIX_FIND_REQUIRED AND PASTIX_FIND_REQUIRED_STARPU)\n    find_dependency(STARPU ${PASTIX_STARPU_VERSION} REQUIRED\n      COMPONENTS ${STARPU_COMPONENT_LIST})\n  else()\n    find_dependency(STARPU ${PASTIX_STARPU_VERSION}\n      COMPONENTS ${STARPU_COMPONENT_LIST})\n  endif()\n\nendif()\n\n# PASTIX may depends on SCOTCH\n#-----------------------------\nif (NOT SCOTCH_FOUND AND PASTIX_LOOK_FOR_SCOTCH)\n  if (NOT PASTIX_FIND_QUIETLY)\n    message(STATUS \"Looking for PASTIX - Try to detect SCOTCH\")\n  endif()\n  if (PASTIX_FIND_REQUIRED AND PASTIX_FIND_REQUIRED_SCOTCH)\n    find_dependency(SCOTCH REQUIRED QUIET)\n  else()\n    find_dependency(SCOTCH QUIET)\n  endif()\nendif()\n\n# PASTIX may depends on PTSCOTCH\n#-------------------------------\nif (NOT PTSCOTCH_FOUND AND PASTIX_LOOK_FOR_PTSCOTCH)\n  if (NOT PASTIX_FIND_QUIETLY)\n    message(STATUS \"Looking for PASTIX - Try to detect PTSCOTCH\")\n  endif()\n  if (PASTIX_FIND_REQUIRED AND PASTIX_FIND_REQUIRED_PTSCOTCH)\n    find_dependency(PTSCOTCH REQUIRED QUIET)\n  else()\n    find_dependency(PTSCOTCH QUIET)\n  endif()\nendif()\n\n# PASTIX may depends on METIS\n#----------------------------\nif (NOT METIS_FOUND AND PASTIX_LOOK_FOR_METIS)\n  if (NOT PASTIX_FIND_QUIETLY)\n    message(STATUS \"Looking for PASTIX - Try to detect METIS\")\n  endif()\n  if (PASTIX_FIND_REQUIRED AND PASTIX_FIND_REQUIRED_METIS)\n    find_dependency(METIS REQUIRED QUIET)\n  else()\n    find_dependency(METIS QUIET)\n  endif()\nendif()\n\n# Error if pastix required and no partitioning lib found\nif (PASTIX_FIND_REQUIRED AND NOT SCOTCH_FOUND AND NOT PTSCOTCH_FOUND AND NOT METIS_FOUND)\n  message(FATAL_ERROR \"Could NOT find any partitioning library on your system\"\n    \" (install scotch, ptscotch or metis)\")\nendif()\n\n\n# Looking for PaStiX\n# ------------------\n\n# Looking for include\n# -------------------\n\n# Add system include paths to search include\n# ------------------------------------------\nunset(_inc_env)\nset(ENV_PASTIX_DIR \"$ENV{PASTIX_DIR}\")\nset(ENV_PASTIX_INCDIR \"$ENV{PASTIX_INCDIR}\")\nif(ENV_PASTIX_INCDIR)\n  list(APPEND _inc_env \"${ENV_PASTIX_INCDIR}\")\nelseif(ENV_PASTIX_DIR)\n  list(APPEND _inc_env \"${ENV_PASTIX_DIR}\")\n  list(APPEND _inc_env \"${ENV_PASTIX_DIR}/include\")\n  list(APPEND _inc_env \"${ENV_PASTIX_DIR}/include/pastix\")\nelse()\n  if(WIN32)\n    string(REPLACE \":\" \";\" _inc_env \"$ENV{INCLUDE}\")\n  else()\n    string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{C_INCLUDE_PATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{CPATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE_PATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n  endif()\nendif()\nlist(APPEND _inc_env \"${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}\")\nlist(APPEND _inc_env \"${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}\")\nlist(REMOVE_DUPLICATES _inc_env)\n\n\n# Try to find the pastix header in the given paths\n# ---------------------------------------------------\n# call cmake macro to find the header path\nif(PASTIX_INCDIR)\n  set(PASTIX_pastix.h_DIRS \"PASTIX_pastix.h_DIRS-NOTFOUND\")\n  find_path(PASTIX_pastix.h_DIRS\n    NAMES pastix.h\n    HINTS ${PASTIX_INCDIR})\nelse()\n  if(PASTIX_DIR)\n    set(PASTIX_pastix.h_DIRS \"PASTIX_pastix.h_DIRS-NOTFOUND\")\n    find_path(PASTIX_pastix.h_DIRS\n      NAMES pastix.h\n      HINTS ${PASTIX_DIR}\n      PATH_SUFFIXES \"include\" \"include/pastix\")\n  else()\n    set(PASTIX_pastix.h_DIRS \"PASTIX_pastix.h_DIRS-NOTFOUND\")\n    find_path(PASTIX_pastix.h_DIRS\n      NAMES pastix.h\n      HINTS ${_inc_env}\n      PATH_SUFFIXES \"pastix\")\n  endif()\nendif()\nmark_as_advanced(PASTIX_pastix.h_DIRS)\n\n# If found, add path to cmake variable\n# ------------------------------------\nif (PASTIX_pastix.h_DIRS)\n  set(PASTIX_INCLUDE_DIRS \"${PASTIX_pastix.h_DIRS}\")\nelse ()\n  set(PASTIX_INCLUDE_DIRS \"PASTIX_INCLUDE_DIRS-NOTFOUND\")\n  if(NOT PASTIX_FIND_QUIETLY)\n    message(STATUS \"Looking for pastix -- pastix.h not found\")\n  endif()\nendif()\n\n\n# Looking for lib\n# ---------------\n\n# Add system library paths to search lib\n# --------------------------------------\nunset(_lib_env)\nset(ENV_PASTIX_LIBDIR \"$ENV{PASTIX_LIBDIR}\")\nif(ENV_PASTIX_LIBDIR)\n  list(APPEND _lib_env \"${ENV_PASTIX_LIBDIR}\")\nelseif(ENV_PASTIX_DIR)\n  list(APPEND _lib_env \"${ENV_PASTIX_DIR}\")\n  list(APPEND _lib_env \"${ENV_PASTIX_DIR}/lib\")\nelse()\n  if(WIN32)\n    string(REPLACE \":\" \";\" _lib_env \"$ENV{LIB}\")\n  else()\n    if(APPLE)\n      string(REPLACE \":\" \";\" _lib_env \"$ENV{DYLD_LIBRARY_PATH}\")\n    else()\n      string(REPLACE \":\" \";\" _lib_env \"$ENV{LD_LIBRARY_PATH}\")\n    endif()\n    list(APPEND _lib_env \"${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}\")\n    list(APPEND _lib_env \"${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}\")\n  endif()\nendif()\nlist(REMOVE_DUPLICATES _lib_env)\n\n# Try to find the pastix lib in the given paths\n# ------------------------------------------------\n\n# create list of libs to find\nset(PASTIX_libs_to_find \"pastix_murge;pastix\")\n\n# call cmake macro to find the lib path\nif(PASTIX_LIBDIR)\n  foreach(pastix_lib ${PASTIX_libs_to_find})\n    set(PASTIX_${pastix_lib}_LIBRARY \"PASTIX_${pastix_lib}_LIBRARY-NOTFOUND\")\n    find_library(PASTIX_${pastix_lib}_LIBRARY\n      NAMES ${pastix_lib}\n      HINTS ${PASTIX_LIBDIR})\n  endforeach()\nelse()\n  if(PASTIX_DIR)\n    foreach(pastix_lib ${PASTIX_libs_to_find})\n      set(PASTIX_${pastix_lib}_LIBRARY \"PASTIX_${pastix_lib}_LIBRARY-NOTFOUND\")\n      find_library(PASTIX_${pastix_lib}_LIBRARY\n\tNAMES ${pastix_lib}\n\tHINTS ${PASTIX_DIR}\n\tPATH_SUFFIXES lib lib32 lib64)\n    endforeach()\n  else()\n    foreach(pastix_lib ${PASTIX_libs_to_find})\n      set(PASTIX_${pastix_lib}_LIBRARY \"PASTIX_${pastix_lib}_LIBRARY-NOTFOUND\")\n      find_library(PASTIX_${pastix_lib}_LIBRARY\n\tNAMES ${pastix_lib}\n\tHINTS ${_lib_env})\n    endforeach()\n  endif()\nendif()\n\n# If found, add path to cmake variable\n# ------------------------------------\nforeach(pastix_lib ${PASTIX_libs_to_find})\n\n  get_filename_component(${pastix_lib}_lib_path ${PASTIX_${pastix_lib}_LIBRARY} PATH)\n  # set cmake variables (respects naming convention)\n  if (PASTIX_LIBRARIES)\n    list(APPEND PASTIX_LIBRARIES \"${PASTIX_${pastix_lib}_LIBRARY}\")\n  else()\n    set(PASTIX_LIBRARIES \"${PASTIX_${pastix_lib}_LIBRARY}\")\n  endif()\n  if (PASTIX_LIBRARY_DIRS)\n    list(APPEND PASTIX_LIBRARY_DIRS \"${${pastix_lib}_lib_path}\")\n  else()\n    set(PASTIX_LIBRARY_DIRS \"${${pastix_lib}_lib_path}\")\n  endif()\n  mark_as_advanced(PASTIX_${pastix_lib}_LIBRARY)\n\nendforeach()\n\n# check a function to validate the find\nif(PASTIX_LIBRARIES)\n\n  set(REQUIRED_LDFLAGS)\n  set(REQUIRED_INCDIRS)\n  set(REQUIRED_LIBDIRS)\n  set(REQUIRED_LIBS)\n\n  # PASTIX\n  if (PASTIX_INCLUDE_DIRS)\n    set(REQUIRED_INCDIRS \"${PASTIX_INCLUDE_DIRS}\")\n  endif()\n  foreach(libdir ${PASTIX_LIBRARY_DIRS})\n    if (libdir)\n      list(APPEND REQUIRED_LIBDIRS \"${libdir}\")\n    endif()\n  endforeach()\n  set(REQUIRED_LIBS \"${PASTIX_LIBRARIES}\")\n  # STARPU\n  if (PASTIX_LOOK_FOR_STARPU AND STARPU_FOUND)\n    if (STARPU_INCLUDE_DIRS_DEP)\n      list(APPEND REQUIRED_INCDIRS \"${STARPU_INCLUDE_DIRS_DEP}\")\n    elseif (STARPU_INCLUDE_DIRS)\n      list(APPEND REQUIRED_INCDIRS \"${STARPU_INCLUDE_DIRS}\")\n    endif()\n    if(STARPU_LIBRARY_DIRS_DEP)\n      list(APPEND REQUIRED_LIBDIRS \"${STARPU_LIBRARY_DIRS_DEP}\")\n    elseif(STARPU_LIBRARY_DIRS)\n      list(APPEND REQUIRED_LIBDIRS \"${STARPU_LIBRARY_DIRS}\")\n    endif()\n    if (STARPU_LIBRARIES_DEP)\n      list(APPEND REQUIRED_LIBS \"${STARPU_LIBRARIES_DEP}\")\n    elseif (STARPU_LIBRARIES)\n      foreach(lib ${STARPU_LIBRARIES})\n\tif (EXISTS ${lib} OR ${lib} MATCHES \"^-\")\n\t  list(APPEND REQUIRED_LIBS \"${lib}\")\n\telse()\n\t  list(APPEND REQUIRED_LIBS \"-l${lib}\")\n\tendif()\n      endforeach()\n    endif()\n  endif()\n  # CUDA\n  if (PASTIX_LOOK_FOR_STARPU_CUDA AND CUDA_FOUND)\n    if (CUDA_INCLUDE_DIRS)\n      list(APPEND REQUIRED_INCDIRS \"${CUDA_INCLUDE_DIRS}\")\n    endif()\n    foreach(libdir ${CUDA_LIBRARY_DIRS})\n      if (libdir)\n\tlist(APPEND REQUIRED_LIBDIRS \"${libdir}\")\n      endif()\n    endforeach()\n    list(APPEND REQUIRED_LIBS \"${CUDA_CUBLAS_LIBRARIES};${CUDA_LIBRARIES}\")\n  endif()\n  # MPI\n  if (PASTIX_LOOK_FOR_MPI AND MPI_FOUND)\n    if (MPI_C_INCLUDE_PATH)\n      list(APPEND REQUIRED_INCDIRS \"${MPI_C_INCLUDE_PATH}\")\n    endif()\n    if (MPI_C_LINK_FLAGS)\n      if (${MPI_C_LINK_FLAGS} MATCHES \"  -\")\n\tstring(REGEX REPLACE \" -\" \"-\" MPI_C_LINK_FLAGS ${MPI_C_LINK_FLAGS})\n      endif()\n      list(APPEND REQUIRED_LDFLAGS \"${MPI_C_LINK_FLAGS}\")\n    endif()\n    list(APPEND REQUIRED_LIBS \"${MPI_C_LIBRARIES}\")\n  endif()\n  # HWLOC\n  if (HWLOC_FOUND)\n    if (HWLOC_INCLUDE_DIRS)\n      list(APPEND REQUIRED_INCDIRS \"${HWLOC_INCLUDE_DIRS}\")\n    endif()\n    foreach(libdir ${HWLOC_LIBRARY_DIRS})\n      if (libdir)\n\tlist(APPEND REQUIRED_LIBDIRS \"${libdir}\")\n      endif()\n    endforeach()\n    foreach(lib ${HWLOC_LIBRARIES})\n      if (EXISTS ${lib} OR ${lib} MATCHES \"^-\")\n\tlist(APPEND REQUIRED_LIBS \"${lib}\")\n      else()\n\tlist(APPEND REQUIRED_LIBS \"-l${lib}\")\n      endif()\n    endforeach()\n  endif()\n  # BLAS\n  if (BLAS_FOUND)\n    if (BLAS_INCLUDE_DIRS)\n      list(APPEND REQUIRED_INCDIRS \"${BLAS_INCLUDE_DIRS}\")\n    endif()\n    foreach(libdir ${BLAS_LIBRARY_DIRS})\n      if (libdir)\n\tlist(APPEND REQUIRED_LIBDIRS \"${libdir}\")\n      endif()\n    endforeach()\n    list(APPEND REQUIRED_LIBS \"${BLAS_LIBRARIES}\")\n    if (BLAS_LINKER_FLAGS)\n      list(APPEND REQUIRED_LDFLAGS \"${BLAS_LINKER_FLAGS}\")\n    endif()\n  endif()\n  # SCOTCH\n  if (PASTIX_LOOK_FOR_SCOTCH AND SCOTCH_FOUND)\n    if (SCOTCH_INCLUDE_DIRS)\n      list(APPEND REQUIRED_INCDIRS \"${SCOTCH_INCLUDE_DIRS}\")\n    endif()\n    foreach(libdir ${SCOTCH_LIBRARY_DIRS})\n      if (libdir)\n\tlist(APPEND REQUIRED_LIBDIRS \"${libdir}\")\n      endif()\n    endforeach()\n    list(APPEND REQUIRED_LIBS \"${SCOTCH_LIBRARIES}\")\n  endif()\n  # PTSCOTCH\n  if (PASTIX_LOOK_FOR_PTSCOTCH AND PTSCOTCH_FOUND)\n    if (PTSCOTCH_INCLUDE_DIRS)\n      list(APPEND REQUIRED_INCDIRS \"${PTSCOTCH_INCLUDE_DIRS}\")\n    endif()\n    foreach(libdir ${PTSCOTCH_LIBRARY_DIRS})\n      if (libdir)\n\tlist(APPEND REQUIRED_LIBDIRS \"${libdir}\")\n      endif()\n    endforeach()\n    list(APPEND REQUIRED_LIBS \"${PTSCOTCH_LIBRARIES}\")\n  endif()\n  # METIS\n  if (PASTIX_LOOK_FOR_METIS AND METIS_FOUND)\n    if (METIS_INCLUDE_DIRS)\n      list(APPEND REQUIRED_INCDIRS \"${METIS_INCLUDE_DIRS}\")\n    endif()\n    foreach(libdir ${METIS_LIBRARY_DIRS})\n      if (libdir)\n\tlist(APPEND REQUIRED_LIBDIRS \"${libdir}\")\n      endif()\n    endforeach()\n    list(APPEND REQUIRED_LIBS \"${METIS_LIBRARIES}\")\n  endif()\n  # Fortran\n  if (CMAKE_C_COMPILER_ID MATCHES \"GNU\")\n    find_library(\n      FORTRAN_gfortran_LIBRARY\n      NAMES gfortran\n      HINTS ${_lib_env}\n      )\n    mark_as_advanced(FORTRAN_gfortran_LIBRARY)\n    if (FORTRAN_gfortran_LIBRARY)\n      list(APPEND REQUIRED_LIBS \"${FORTRAN_gfortran_LIBRARY}\")\n    endif()\n  elseif (CMAKE_C_COMPILER_ID MATCHES \"Intel\")\n    find_library(\n      FORTRAN_ifcore_LIBRARY\n      NAMES ifcore\n      HINTS ${_lib_env}\n      )\n    mark_as_advanced(FORTRAN_ifcore_LIBRARY)\n    if (FORTRAN_ifcore_LIBRARY)\n      list(APPEND REQUIRED_LIBS \"${FORTRAN_ifcore_LIBRARY}\")\n    endif()\n  endif()\n  # EXTRA LIBS such that pthread, m, rt\n  list(APPEND REQUIRED_LIBS ${PASTIX_EXTRA_LIBRARIES})\n\n  # set required libraries for link\n  set(CMAKE_REQUIRED_INCLUDES \"${REQUIRED_INCDIRS}\")\n  set(CMAKE_REQUIRED_LIBRARIES)\n  list(APPEND CMAKE_REQUIRED_LIBRARIES \"${REQUIRED_LDFLAGS}\")\n  foreach(lib_dir ${REQUIRED_LIBDIRS})\n    list(APPEND CMAKE_REQUIRED_LIBRARIES \"-L${lib_dir}\")\n  endforeach()\n  list(APPEND CMAKE_REQUIRED_LIBRARIES \"${REQUIRED_LIBS}\")\n  list(APPEND CMAKE_REQUIRED_FLAGS \"${REQUIRED_FLAGS}\")\n  string(REGEX REPLACE \"^ -\" \"-\" CMAKE_REQUIRED_LIBRARIES \"${CMAKE_REQUIRED_LIBRARIES}\")\n\n  # test link\n  unset(PASTIX_WORKS CACHE)\n  include(CheckFunctionExists)\n  check_function_exists(pastix PASTIX_WORKS)\n  mark_as_advanced(PASTIX_WORKS)\n\n  if(PASTIX_WORKS)\n    # save link with dependencies\n    set(PASTIX_LIBRARIES_DEP \"${REQUIRED_LIBS}\")\n    set(PASTIX_LIBRARY_DIRS_DEP \"${REQUIRED_LIBDIRS}\")\n    set(PASTIX_INCLUDE_DIRS_DEP \"${REQUIRED_INCDIRS}\")\n    set(PASTIX_LINKER_FLAGS \"${REQUIRED_LDFLAGS}\")\n    list(REMOVE_DUPLICATES PASTIX_LIBRARY_DIRS_DEP)\n    list(REMOVE_DUPLICATES PASTIX_INCLUDE_DIRS_DEP)\n    list(REMOVE_DUPLICATES PASTIX_LINKER_FLAGS)\n  else()\n    if(NOT PASTIX_FIND_QUIETLY)\n      message(STATUS \"Looking for PASTIX : test of pastix() fails\")\n      message(STATUS \"CMAKE_REQUIRED_LIBRARIES: ${CMAKE_REQUIRED_LIBRARIES}\")\n      message(STATUS \"CMAKE_REQUIRED_INCLUDES: ${CMAKE_REQUIRED_INCLUDES}\")\n      message(STATUS \"Check in CMakeFiles/CMakeError.log to figure out why it fails\")\n      message(STATUS \"Maybe PASTIX is linked with specific libraries. \"\n\t\"Have you tried with COMPONENTS (MPI/SEQ, STARPU, STARPU_CUDA, SCOTCH, PTSCOTCH, METIS)? \"\n\t\"See the explanation in FindPASTIX.cmake.\")\n    endif()\n  endif()\n  set(CMAKE_REQUIRED_INCLUDES)\n  set(CMAKE_REQUIRED_FLAGS)\n  set(CMAKE_REQUIRED_LIBRARIES)\nendif()\n\nif (PASTIX_LIBRARIES)\n  list(GET PASTIX_LIBRARIES 0 first_lib)\n  get_filename_component(first_lib_path \"${first_lib}\" PATH)\n  if (${first_lib_path} MATCHES \"/lib(32|64)?$\")\n    string(REGEX REPLACE \"/lib(32|64)?$\" \"\" not_cached_dir \"${first_lib_path}\")\n    set(PASTIX_DIR_FOUND \"${not_cached_dir}\" CACHE PATH \"Installation directory of PASTIX library\" FORCE)\n  else()\n    set(PASTIX_DIR_FOUND \"${first_lib_path}\" CACHE PATH \"Installation directory of PASTIX library\" FORCE)\n  endif()\nendif()\nmark_as_advanced(PASTIX_DIR)\nmark_as_advanced(PASTIX_DIR_FOUND)\n\n# check that PASTIX has been found\n# ---------------------------------\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(PASTIX DEFAULT_MSG\n  PASTIX_LIBRARIES\n  PASTIX_WORKS)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindPTSCOTCH.cmake",
    "content": "###\n#\n# @copyright (c) 2009-2014 The University of Tennessee and The University\n#                          of Tennessee Research Foundation.\n#                          All rights reserved.\n# @copyright (c) 2012-2016 Inria. All rights reserved.\n# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved.\n#\n###\n#\n# - Find PTSCOTCH include dirs and libraries\n# Use this module by invoking find_package with the form:\n#  find_package(PTSCOTCH\n#               [REQUIRED]             # Fail with error if ptscotch is not found\n#               [COMPONENTS <comp1> <comp2> ...] # dependencies\n#              )\n#\n#  PTSCOTCH depends on the following libraries:\n#   - Threads\n#   - MPI\n#\n#  COMPONENTS can be some of the following:\n#   - ESMUMPS: to activate detection of PT-Scotch with the esmumps interface\n#\n# This module finds headers and ptscotch library.\n# Results are reported in variables:\n#  PTSCOTCH_FOUND            - True if headers and requested libraries were found\n#  PTSCOTCH_LINKER_FLAGS     - list of required linker flags (excluding -l and -L)\n#  PTSCOTCH_INCLUDE_DIRS     - ptscotch include directories\n#  PTSCOTCH_LIBRARY_DIRS     - Link directories for ptscotch libraries\n#  PTSCOTCH_LIBRARIES        - ptscotch component libraries to be linked\n#  PTSCOTCH_INCLUDE_DIRS_DEP - ptscotch + dependencies include directories\n#  PTSCOTCH_LIBRARY_DIRS_DEP - ptscotch + dependencies link directories\n#  PTSCOTCH_LIBRARIES_DEP    - ptscotch libraries + dependencies\n#  PTSCOTCH_INTSIZE          - Number of octets occupied by a SCOTCH_Num\n#\n# The user can give specific paths where to find the libraries adding cmake\n# options at configure (ex: cmake path/to/project -DPTSCOTCH=path/to/ptscotch):\n#  PTSCOTCH_DIR              - Where to find the base directory of ptscotch\n#  PTSCOTCH_INCDIR           - Where to find the header files\n#  PTSCOTCH_LIBDIR           - Where to find the library files\n# The module can also look for the following environment variables if paths\n# are not given as cmake variable: PTSCOTCH_DIR, PTSCOTCH_INCDIR, PTSCOTCH_LIBDIR\n\n#=============================================================================\n# Copyright 2012-2013 Inria\n# Copyright 2012-2013 Emmanuel Agullo\n# Copyright 2012-2013 Mathieu Faverge\n# Copyright 2012      Cedric Castagnede\n# Copyright 2013-2016 Florent Pruvost\n#\n# Distributed under the OSI-approved BSD License (the \"License\");\n# see accompanying file MORSE-Copyright.txt for details.\n#\n# This software is distributed WITHOUT ANY WARRANTY; without even the\n# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.\n# See the License for more information.\n#=============================================================================\n# (To distribute this file outside of Morse, substitute the full\n#  License text for the above reference.)\n\nif (NOT PTSCOTCH_FOUND)\n  set(PTSCOTCH_DIR \"\" CACHE PATH \"Installation directory of PTSCOTCH library\")\n  if (NOT PTSCOTCH_FIND_QUIETLY)\n    message(STATUS \"A cache variable, namely PTSCOTCH_DIR, has been set to specify the install directory of PTSCOTCH\")\n  endif()\nendif()\n\n# Set the version to find\nset(PTSCOTCH_LOOK_FOR_ESMUMPS OFF)\n\nif( PTSCOTCH_FIND_COMPONENTS )\n  foreach( component ${PTSCOTCH_FIND_COMPONENTS} )\n    if (${component} STREQUAL \"ESMUMPS\")\n      # means we look for esmumps library\n      set(PTSCOTCH_LOOK_FOR_ESMUMPS ON)\n    endif()\n  endforeach()\nendif()\n\n# PTSCOTCH depends on Threads, try to find it\ninclude(CMakeFindDependencyMacro)\nif (NOT THREADS_FOUND)\n  if (PTSCOTCH_FIND_REQUIRED)\n    find_dependency(Threads REQUIRED)\n  else()\n    find_dependency(Threads)\n  endif()\nendif()\n\n# PTSCOTCH depends on MPI, try to find it\nif (NOT MPI_FOUND)\n  if (PTSCOTCH_FIND_REQUIRED)\n    find_dependency(MPI REQUIRED)\n  else()\n    find_dependency(MPI)\n  endif()\nendif()\n\n# Looking for include\n# -------------------\n\n# Add system include paths to search include\n# ------------------------------------------\nunset(_inc_env)\nset(ENV_PTSCOTCH_DIR \"$ENV{PTSCOTCH_DIR}\")\nset(ENV_PTSCOTCH_INCDIR \"$ENV{PTSCOTCH_INCDIR}\")\nif(ENV_PTSCOTCH_INCDIR)\n  list(APPEND _inc_env \"${ENV_PTSCOTCH_INCDIR}\")\nelseif(ENV_PTSCOTCH_DIR)\n  list(APPEND _inc_env \"${ENV_PTSCOTCH_DIR}\")\n  list(APPEND _inc_env \"${ENV_PTSCOTCH_DIR}/include\")\n  list(APPEND _inc_env \"${ENV_PTSCOTCH_DIR}/include/ptscotch\")\nelse()\n  if(WIN32)\n    string(REPLACE \":\" \";\" _inc_env \"$ENV{INCLUDE}\")\n  else()\n    string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{C_INCLUDE_PATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{CPATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE_PATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n  endif()\nendif()\nlist(APPEND _inc_env \"${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}\")\nlist(APPEND _inc_env \"${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}\")\nlist(REMOVE_DUPLICATES _inc_env)\n\n\n# Try to find the ptscotch header in the given paths\n# -------------------------------------------------\n\nset(PTSCOTCH_hdrs_to_find \"ptscotch.h;scotch.h\")\n\n# call cmake macro to find the header path\nif(PTSCOTCH_INCDIR)\n  foreach(ptscotch_hdr ${PTSCOTCH_hdrs_to_find})\n    set(PTSCOTCH_${ptscotch_hdr}_DIRS \"PTSCOTCH_${ptscotch_hdr}_DIRS-NOTFOUND\")\n    find_path(PTSCOTCH_${ptscotch_hdr}_DIRS\n      NAMES ${ptscotch_hdr}\n      HINTS ${PTSCOTCH_INCDIR})\n    mark_as_advanced(PTSCOTCH_${ptscotch_hdr}_DIRS)\n  endforeach()\nelse()\n  if(PTSCOTCH_DIR)\n    foreach(ptscotch_hdr ${PTSCOTCH_hdrs_to_find})\n      set(PTSCOTCH_${ptscotch_hdr}_DIRS \"PTSCOTCH_${ptscotch_hdr}_DIRS-NOTFOUND\")\n      find_path(PTSCOTCH_${ptscotch_hdr}_DIRS\n        NAMES ${ptscotch_hdr}\n        HINTS ${PTSCOTCH_DIR}\n        PATH_SUFFIXES \"include\" \"include/scotch\")\n      mark_as_advanced(PTSCOTCH_${ptscotch_hdr}_DIRS)\n    endforeach()\n  else()\n    foreach(ptscotch_hdr ${PTSCOTCH_hdrs_to_find})\n      set(PTSCOTCH_${ptscotch_hdr}_DIRS \"PTSCOTCH_${ptscotch_hdr}_DIRS-NOTFOUND\")\n      find_path(PTSCOTCH_${ptscotch_hdr}_DIRS\n        NAMES ${ptscotch_hdr}\n        HINTS ${_inc_env}\n        PATH_SUFFIXES \"scotch\")\n      mark_as_advanced(PTSCOTCH_${ptscotch_hdr}_DIRS)\n    endforeach()\n  endif()\nendif()\n\n# If found, add path to cmake variable\n# ------------------------------------\nforeach(ptscotch_hdr ${PTSCOTCH_hdrs_to_find})\n  if (PTSCOTCH_${ptscotch_hdr}_DIRS)\n    list(APPEND PTSCOTCH_INCLUDE_DIRS \"${PTSCOTCH_${ptscotch_hdr}_DIRS}\")\n  else ()\n    if (NOT PTSCOTCH_FIND_QUIETLY)\n      message(STATUS \"Looking for ptscotch -- ${ptscotch_hdr} not found\")\n    endif()\n  endif()\nendforeach()\nlist(REMOVE_DUPLICATES PTSCOTCH_INCLUDE_DIRS)\n\n# Looking for lib\n# ---------------\n\n# Add system library paths to search lib\n# --------------------------------------\nunset(_lib_env)\nset(ENV_PTSCOTCH_LIBDIR \"$ENV{PTSCOTCH_LIBDIR}\")\nif(ENV_PTSCOTCH_LIBDIR)\n  list(APPEND _lib_env \"${ENV_PTSCOTCH_LIBDIR}\")\nelseif(ENV_PTSCOTCH_DIR)\n  list(APPEND _lib_env \"${ENV_PTSCOTCH_DIR}\")\n  list(APPEND _lib_env \"${ENV_PTSCOTCH_DIR}/lib\")\nelse()\n  if(WIN32)\n    string(REPLACE \":\" \";\" _lib_env \"$ENV{LIB}\")\n  else()\n    if(APPLE)\n      string(REPLACE \":\" \";\" _lib_env \"$ENV{DYLD_LIBRARY_PATH}\")\n    else()\n      string(REPLACE \":\" \";\" _lib_env \"$ENV{LD_LIBRARY_PATH}\")\n    endif()\n    list(APPEND _lib_env \"${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}\")\n    list(APPEND _lib_env \"${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}\")\n  endif()\nendif()\nlist(REMOVE_DUPLICATES _lib_env)\n\n# Try to find the ptscotch lib in the given paths\n# ----------------------------------------------\n\nset(PTSCOTCH_libs_to_find \"ptscotch;ptscotcherr\")\nif (PTSCOTCH_LOOK_FOR_ESMUMPS)\n  list(INSERT PTSCOTCH_libs_to_find 0 \"ptesmumps\")\n  list(APPEND PTSCOTCH_libs_to_find   \"esmumps\"  )\nendif()\nlist(APPEND PTSCOTCH_libs_to_find \"scotch;scotcherr\")\n\n# call cmake macro to find the lib path\nif(PTSCOTCH_LIBDIR)\n  foreach(ptscotch_lib ${PTSCOTCH_libs_to_find})\n    set(PTSCOTCH_${ptscotch_lib}_LIBRARY \"PTSCOTCH_${ptscotch_lib}_LIBRARY-NOTFOUND\")\n    find_library(PTSCOTCH_${ptscotch_lib}_LIBRARY\n      NAMES ${ptscotch_lib}\n      HINTS ${PTSCOTCH_LIBDIR})\n  endforeach()\nelse()\n  if(PTSCOTCH_DIR)\n    foreach(ptscotch_lib ${PTSCOTCH_libs_to_find})\n      set(PTSCOTCH_${ptscotch_lib}_LIBRARY \"PTSCOTCH_${ptscotch_lib}_LIBRARY-NOTFOUND\")\n      find_library(PTSCOTCH_${ptscotch_lib}_LIBRARY\n        NAMES ${ptscotch_lib}\n        HINTS ${PTSCOTCH_DIR}\n        PATH_SUFFIXES lib lib32 lib64)\n    endforeach()\n  else()\n    foreach(ptscotch_lib ${PTSCOTCH_libs_to_find})\n      set(PTSCOTCH_${ptscotch_lib}_LIBRARY \"PTSCOTCH_${ptscotch_lib}_LIBRARY-NOTFOUND\")\n      find_library(PTSCOTCH_${ptscotch_lib}_LIBRARY\n        NAMES ${ptscotch_lib}\n        HINTS ${_lib_env})\n    endforeach()\n  endif()\nendif()\n\nset(PTSCOTCH_LIBRARIES \"\")\nset(PTSCOTCH_LIBRARY_DIRS \"\")\n# If found, add path to cmake variable\n# ------------------------------------\nforeach(ptscotch_lib ${PTSCOTCH_libs_to_find})\n\n  if (PTSCOTCH_${ptscotch_lib}_LIBRARY)\n    get_filename_component(${ptscotch_lib}_lib_path \"${PTSCOTCH_${ptscotch_lib}_LIBRARY}\" PATH)\n    # set cmake variables\n    list(APPEND PTSCOTCH_LIBRARIES \"${PTSCOTCH_${ptscotch_lib}_LIBRARY}\")\n    list(APPEND PTSCOTCH_LIBRARY_DIRS \"${${ptscotch_lib}_lib_path}\")\n  else ()\n    if (NOT PTSCOTCH_FIND_QUIETLY)\n      message(STATUS \"Looking for ptscotch -- lib ${ptscotch_lib} not found\")\n    endif()\n  endif ()\n\n  mark_as_advanced(PTSCOTCH_${ptscotch_lib}_LIBRARY)\n\nendforeach()\nlist(REMOVE_DUPLICATES PTSCOTCH_LIBRARY_DIRS)\n\n# check a function to validate the find\nif(PTSCOTCH_LIBRARIES)\n\n  set(REQUIRED_LDFLAGS)\n  set(REQUIRED_INCDIRS)\n  set(REQUIRED_LIBDIRS)\n  set(REQUIRED_LIBS)\n\n  # PTSCOTCH\n  if (PTSCOTCH_INCLUDE_DIRS)\n    set(REQUIRED_INCDIRS  \"${PTSCOTCH_INCLUDE_DIRS}\")\n  endif()\n  if (PTSCOTCH_LIBRARY_DIRS)\n    set(REQUIRED_LIBDIRS \"${PTSCOTCH_LIBRARY_DIRS}\")\n  endif()\n  set(REQUIRED_LIBS \"${PTSCOTCH_LIBRARIES}\")\n  # MPI\n  if (MPI_FOUND)\n    if (MPI_C_INCLUDE_PATH)\n      list(APPEND CMAKE_REQUIRED_INCLUDES \"${MPI_C_INCLUDE_PATH}\")\n    endif()\n    if (MPI_C_LINK_FLAGS)\n      if (${MPI_C_LINK_FLAGS} MATCHES \"  -\")\n\tstring(REGEX REPLACE \" -\" \"-\" MPI_C_LINK_FLAGS ${MPI_C_LINK_FLAGS})\n      endif()\n      list(APPEND REQUIRED_LDFLAGS \"${MPI_C_LINK_FLAGS}\")\n    endif()\n    list(APPEND REQUIRED_LIBS \"${MPI_C_LIBRARIES}\")\n  endif()\n  # THREADS\n  if(CMAKE_THREAD_LIBS_INIT)\n    list(APPEND REQUIRED_LIBS \"${CMAKE_THREAD_LIBS_INIT}\")\n  endif()\n  set(Z_LIBRARY \"Z_LIBRARY-NOTFOUND\")\n  find_library(Z_LIBRARY NAMES z)\n  mark_as_advanced(Z_LIBRARY)\n  if(Z_LIBRARY)\n    list(APPEND REQUIRED_LIBS \"-lz\")\n  endif()\n  set(M_LIBRARY \"M_LIBRARY-NOTFOUND\")\n  find_library(M_LIBRARY NAMES m)\n  mark_as_advanced(M_LIBRARY)\n  if(M_LIBRARY)\n    list(APPEND REQUIRED_LIBS \"-lm\")\n  endif()\n  set(RT_LIBRARY \"RT_LIBRARY-NOTFOUND\")\n  find_library(RT_LIBRARY NAMES rt)\n  mark_as_advanced(RT_LIBRARY)\n  if(RT_LIBRARY)\n    list(APPEND REQUIRED_LIBS \"-lrt\")\n  endif()\n\n  # set required libraries for link\n  set(CMAKE_REQUIRED_INCLUDES \"${REQUIRED_INCDIRS}\")\n  set(CMAKE_REQUIRED_LIBRARIES)\n  list(APPEND CMAKE_REQUIRED_LIBRARIES \"${REQUIRED_LDFLAGS}\")\n  foreach(lib_dir ${REQUIRED_LIBDIRS})\n    list(APPEND CMAKE_REQUIRED_LIBRARIES \"-L${lib_dir}\")\n  endforeach()\n  list(APPEND CMAKE_REQUIRED_LIBRARIES \"${REQUIRED_LIBS}\")\n  list(APPEND CMAKE_REQUIRED_FLAGS \"${REQUIRED_FLAGS}\")\n  string(REGEX REPLACE \"^ -\" \"-\" CMAKE_REQUIRED_LIBRARIES \"${CMAKE_REQUIRED_LIBRARIES}\")\n\n  # test link\n  unset(PTSCOTCH_WORKS CACHE)\n  include(CheckFunctionExists)\n  check_function_exists(SCOTCH_dgraphInit PTSCOTCH_WORKS)\n  mark_as_advanced(PTSCOTCH_WORKS)\n\n  if(PTSCOTCH_WORKS)\n    # save link with dependencies\n    set(PTSCOTCH_LIBRARIES_DEP \"${REQUIRED_LIBS}\")\n    set(PTSCOTCH_LIBRARY_DIRS_DEP \"${REQUIRED_LIBDIRS}\")\n    set(PTSCOTCH_INCLUDE_DIRS_DEP \"${REQUIRED_INCDIRS}\")\n    set(PTSCOTCH_LINKER_FLAGS \"${REQUIRED_LDFLAGS}\")\n    list(REMOVE_DUPLICATES PTSCOTCH_LIBRARY_DIRS_DEP)\n    list(REMOVE_DUPLICATES PTSCOTCH_INCLUDE_DIRS_DEP)\n    list(REMOVE_DUPLICATES PTSCOTCH_LINKER_FLAGS)\n  else()\n    if(NOT PTSCOTCH_FIND_QUIETLY)\n      message(STATUS \"Looking for PTSCOTCH : test of SCOTCH_dgraphInit with PTSCOTCH library fails\")\n      message(STATUS \"CMAKE_REQUIRED_LIBRARIES: ${CMAKE_REQUIRED_LIBRARIES}\")\n      message(STATUS \"CMAKE_REQUIRED_INCLUDES: ${CMAKE_REQUIRED_INCLUDES}\")\n      message(STATUS \"Check in CMakeFiles/CMakeError.log to figure out why it fails\")\n    endif()\n  endif()\n  set(CMAKE_REQUIRED_INCLUDES)\n  set(CMAKE_REQUIRED_FLAGS)\n  set(CMAKE_REQUIRED_LIBRARIES)\nendif()\n\nif (PTSCOTCH_LIBRARIES)\n  list(GET PTSCOTCH_LIBRARIES 0 first_lib)\n  get_filename_component(first_lib_path \"${first_lib}\" PATH)\n  if (${first_lib_path} MATCHES \"/lib(32|64)?$\")\n    string(REGEX REPLACE \"/lib(32|64)?$\" \"\" not_cached_dir \"${first_lib_path}\")\n    set(PTSCOTCH_DIR_FOUND \"${not_cached_dir}\" CACHE PATH \"Installation directory of PTSCOTCH library\" FORCE)\n  else()\n    set(PTSCOTCH_DIR_FOUND \"${first_lib_path}\" CACHE PATH \"Installation directory of PTSCOTCH library\" FORCE)\n  endif()\nendif()\nmark_as_advanced(PTSCOTCH_DIR)\nmark_as_advanced(PTSCOTCH_DIR_FOUND)\n\n# Check the size of SCOTCH_Num\n# ---------------------------------\nset(CMAKE_REQUIRED_INCLUDES ${PTSCOTCH_INCLUDE_DIRS})\n\ninclude(CheckCSourceRuns)\n#stdio.h and stdint.h should be included by scotch.h directly\nset(PTSCOTCH_C_TEST_SCOTCH_Num_4 \"\n#include <stdio.h>\n#include <stdint.h>\n#include <ptscotch.h>\nint main(int argc, char **argv) {\n  if (sizeof(SCOTCH_Num) == 4)\n    return 0;\n  else\n    return 1;\n}\n\")\n\nset(PTSCOTCH_C_TEST_SCOTCH_Num_8 \"\n#include <stdio.h>\n#include <stdint.h>\n#include <ptscotch.h>\nint main(int argc, char **argv) {\n  if (sizeof(SCOTCH_Num) == 8)\n    return 0;\n  else\n    return 1;\n}\n\")\ncheck_c_source_runs(\"${PTSCOTCH_C_TEST_SCOTCH_Num_4}\" PTSCOTCH_Num_4)\nif(NOT PTSCOTCH_Num_4)\n  check_c_source_runs(\"${PTSCOTCH_C_TEST_SCOTCH_Num_8}\" PTSCOTCH_Num_8)\n  if(NOT PTSCOTCH_Num_8)\n    set(PTSCOTCH_INTSIZE -1)\n  else()\n    set(PTSCOTCH_INTSIZE 8)\n  endif()\nelse()\n  set(PTSCOTCH_INTSIZE 4)\nendif()\nset(CMAKE_REQUIRED_INCLUDES \"\")\n\n# check that PTSCOTCH has been found\n# ---------------------------------\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(PTSCOTCH DEFAULT_MSG\n  PTSCOTCH_LIBRARIES\n  PTSCOTCH_WORKS)\n#\n# TODO: Add possibility to check for specific functions in the library\n#\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindSCOTCH.cmake",
    "content": "###\n#\n# @copyright (c) 2009-2014 The University of Tennessee and The University\n#                          of Tennessee Research Foundation.\n#                          All rights reserved.\n# @copyright (c) 2012-2014 Inria. All rights reserved.\n# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved.\n#\n###\n#\n# - Find SCOTCH include dirs and libraries\n# Use this module by invoking find_package with the form:\n#  find_package(SCOTCH\n#               [REQUIRED]             # Fail with error if scotch is not found\n#               [COMPONENTS <comp1> <comp2> ...] # dependencies\n#              )\n#\n#  COMPONENTS can be some of the following:\n#   - ESMUMPS: to activate detection of Scotch with the esmumps interface\n#\n# This module finds headers and scotch library.\n# Results are reported in variables:\n#  SCOTCH_FOUND           - True if headers and requested libraries were found\n#  SCOTCH_INCLUDE_DIRS    - scotch include directories\n#  SCOTCH_LIBRARY_DIRS    - Link directories for scotch libraries\n#  SCOTCH_LIBRARIES       - scotch component libraries to be linked\n#  SCOTCH_INTSIZE         - Number of octets occupied by a SCOTCH_Num\n#\n# The user can give specific paths where to find the libraries adding cmake\n# options at configure (ex: cmake path/to/project -DSCOTCH=path/to/scotch):\n#  SCOTCH_DIR             - Where to find the base directory of scotch\n#  SCOTCH_INCDIR          - Where to find the header files\n#  SCOTCH_LIBDIR          - Where to find the library files\n# The module can also look for the following environment variables if paths\n# are not given as cmake variable: SCOTCH_DIR, SCOTCH_INCDIR, SCOTCH_LIBDIR\n\n#=============================================================================\n# Copyright 2012-2013 Inria\n# Copyright 2012-2013 Emmanuel Agullo\n# Copyright 2012-2013 Mathieu Faverge\n# Copyright 2012      Cedric Castagnede\n# Copyright 2013      Florent Pruvost\n#\n# Distributed under the OSI-approved BSD License (the \"License\");\n# see accompanying file MORSE-Copyright.txt for details.\n#\n# This software is distributed WITHOUT ANY WARRANTY; without even the\n# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.\n# See the License for more information.\n#=============================================================================\n# (To distribute this file outside of Morse, substitute the full\n#  License text for the above reference.)\n\nif (NOT SCOTCH_FOUND)\n  set(SCOTCH_DIR \"\" CACHE PATH \"Installation directory of SCOTCH library\")\n  if (NOT SCOTCH_FIND_QUIETLY)\n    message(STATUS \"A cache variable, namely SCOTCH_DIR, has been set to specify the install directory of SCOTCH\")\n  endif()\nendif()\n\n# Set the version to find\nset(SCOTCH_LOOK_FOR_ESMUMPS OFF)\n\nif( SCOTCH_FIND_COMPONENTS )\n  foreach( component ${SCOTCH_FIND_COMPONENTS} )\n    if (${component} STREQUAL \"ESMUMPS\")\n      # means we look for esmumps library\n      set(SCOTCH_LOOK_FOR_ESMUMPS ON)\n    endif()\n  endforeach()\nendif()\n\n# SCOTCH may depend on Threads, try to find it\ninclude(CMakeFindDependencyMacro)\nif (NOT THREADS_FOUND)\n  if (SCOTCH_FIND_REQUIRED)\n    find_dependency(Threads REQUIRED)\n  else()\n    find_dependency(Threads)\n  endif()\nendif()\n\n# Looking for include\n# -------------------\n\n# Add system include paths to search include\n# ------------------------------------------\nunset(_inc_env)\nset(ENV_SCOTCH_DIR \"$ENV{SCOTCH_DIR}\")\nset(ENV_SCOTCH_INCDIR \"$ENV{SCOTCH_INCDIR}\")\nif(ENV_SCOTCH_INCDIR)\n  list(APPEND _inc_env \"${ENV_SCOTCH_INCDIR}\")\nelseif(ENV_SCOTCH_DIR)\n  list(APPEND _inc_env \"${ENV_SCOTCH_DIR}\")\n  list(APPEND _inc_env \"${ENV_SCOTCH_DIR}/include\")\n  list(APPEND _inc_env \"${ENV_SCOTCH_DIR}/include/scotch\")\nelse()\n  if(WIN32)\n    string(REPLACE \":\" \";\" _inc_env \"$ENV{INCLUDE}\")\n  else()\n    string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{C_INCLUDE_PATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{CPATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE_PATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n  endif()\nendif()\nlist(APPEND _inc_env \"${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}\")\nlist(APPEND _inc_env \"${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}\")\nlist(REMOVE_DUPLICATES _inc_env)\n\n\n# Try to find the scotch header in the given paths\n# -------------------------------------------------\n# call cmake macro to find the header path\nif(SCOTCH_INCDIR)\n  set(SCOTCH_scotch.h_DIRS \"SCOTCH_scotch.h_DIRS-NOTFOUND\")\n  find_path(SCOTCH_scotch.h_DIRS\n    NAMES scotch.h\n    HINTS ${SCOTCH_INCDIR})\nelse()\n  if(SCOTCH_DIR)\n    set(SCOTCH_scotch.h_DIRS \"SCOTCH_scotch.h_DIRS-NOTFOUND\")\n    find_path(SCOTCH_scotch.h_DIRS\n      NAMES scotch.h\n      HINTS ${SCOTCH_DIR}\n      PATH_SUFFIXES \"include\" \"include/scotch\")\n  else()\n    set(SCOTCH_scotch.h_DIRS \"SCOTCH_scotch.h_DIRS-NOTFOUND\")\n    find_path(SCOTCH_scotch.h_DIRS\n      NAMES scotch.h\n      HINTS ${_inc_env}\n      PATH_SUFFIXES \"scotch\")\n  endif()\nendif()\nmark_as_advanced(SCOTCH_scotch.h_DIRS)\n\n# If found, add path to cmake variable\n# ------------------------------------\nif (SCOTCH_scotch.h_DIRS)\n  set(SCOTCH_INCLUDE_DIRS \"${SCOTCH_scotch.h_DIRS}\")\nelse ()\n  set(SCOTCH_INCLUDE_DIRS \"SCOTCH_INCLUDE_DIRS-NOTFOUND\")\n  if (NOT SCOTCH_FIND_QUIETLY)\n    message(STATUS \"Looking for scotch -- scotch.h not found\")\n  endif()\nendif()\nlist(REMOVE_DUPLICATES SCOTCH_INCLUDE_DIRS)\n\n# Looking for lib\n# ---------------\n\n# Add system library paths to search lib\n# --------------------------------------\nunset(_lib_env)\nset(ENV_SCOTCH_LIBDIR \"$ENV{SCOTCH_LIBDIR}\")\nif(ENV_SCOTCH_LIBDIR)\n  list(APPEND _lib_env \"${ENV_SCOTCH_LIBDIR}\")\nelseif(ENV_SCOTCH_DIR)\n  list(APPEND _lib_env \"${ENV_SCOTCH_DIR}\")\n  list(APPEND _lib_env \"${ENV_SCOTCH_DIR}/lib\")\nelse()\n  if(WIN32)\n    string(REPLACE \":\" \";\" _lib_env \"$ENV{LIB}\")\n  else()\n    if(APPLE)\n      string(REPLACE \":\" \";\" _lib_env \"$ENV{DYLD_LIBRARY_PATH}\")\n    else()\n      string(REPLACE \":\" \";\" _lib_env \"$ENV{LD_LIBRARY_PATH}\")\n    endif()\n    list(APPEND _lib_env \"${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}\")\n    list(APPEND _lib_env \"${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}\")\n  endif()\nendif()\nlist(REMOVE_DUPLICATES _lib_env)\n\n# Try to find the scotch lib in the given paths\n# ----------------------------------------------\n\nset(SCOTCH_libs_to_find \"scotch;scotcherrexit\")\nif (SCOTCH_LOOK_FOR_ESMUMPS)\n  list(INSERT SCOTCH_libs_to_find 0 \"esmumps\")\nendif()\n\n# call cmake macro to find the lib path\nif(SCOTCH_LIBDIR)\n  foreach(scotch_lib ${SCOTCH_libs_to_find})\n    set(SCOTCH_${scotch_lib}_LIBRARY \"SCOTCH_${scotch_lib}_LIBRARY-NOTFOUND\")\n    find_library(SCOTCH_${scotch_lib}_LIBRARY\n      NAMES ${scotch_lib}\n      HINTS ${SCOTCH_LIBDIR})\n  endforeach()\nelse()\n  if(SCOTCH_DIR)\n    foreach(scotch_lib ${SCOTCH_libs_to_find})\n      set(SCOTCH_${scotch_lib}_LIBRARY \"SCOTCH_${scotch_lib}_LIBRARY-NOTFOUND\")\n      find_library(SCOTCH_${scotch_lib}_LIBRARY\n\tNAMES ${scotch_lib}\n\tHINTS ${SCOTCH_DIR}\n\tPATH_SUFFIXES lib lib32 lib64)\n    endforeach()\n  else()\n    foreach(scotch_lib ${SCOTCH_libs_to_find})\n      set(SCOTCH_${scotch_lib}_LIBRARY \"SCOTCH_${scotch_lib}_LIBRARY-NOTFOUND\")\n      find_library(SCOTCH_${scotch_lib}_LIBRARY\n\tNAMES ${scotch_lib}\n\tHINTS ${_lib_env})\n    endforeach()\n  endif()\nendif()\n\nset(SCOTCH_LIBRARIES \"\")\nset(SCOTCH_LIBRARY_DIRS \"\")\n# If found, add path to cmake variable\n# ------------------------------------\nforeach(scotch_lib ${SCOTCH_libs_to_find})\n\n  if (SCOTCH_${scotch_lib}_LIBRARY)\n    get_filename_component(${scotch_lib}_lib_path \"${SCOTCH_${scotch_lib}_LIBRARY}\" PATH)\n    # set cmake variables\n    list(APPEND SCOTCH_LIBRARIES \"${SCOTCH_${scotch_lib}_LIBRARY}\")\n    list(APPEND SCOTCH_LIBRARY_DIRS \"${${scotch_lib}_lib_path}\")\n  else ()\n    list(APPEND SCOTCH_LIBRARIES \"${SCOTCH_${scotch_lib}_LIBRARY}\")\n    if (NOT SCOTCH_FIND_QUIETLY)\n      message(STATUS \"Looking for scotch -- lib ${scotch_lib} not found\")\n    endif()\n  endif ()\n\n  mark_as_advanced(SCOTCH_${scotch_lib}_LIBRARY)\n\nendforeach()\nlist(REMOVE_DUPLICATES SCOTCH_LIBRARY_DIRS)\n\n# check a function to validate the find\nif(SCOTCH_LIBRARIES)\n\n  set(REQUIRED_INCDIRS)\n  set(REQUIRED_LIBDIRS)\n  set(REQUIRED_LIBS)\n\n  # SCOTCH\n  if (SCOTCH_INCLUDE_DIRS)\n    set(REQUIRED_INCDIRS  \"${SCOTCH_INCLUDE_DIRS}\")\n  endif()\n  if (SCOTCH_LIBRARY_DIRS)\n    set(REQUIRED_LIBDIRS \"${SCOTCH_LIBRARY_DIRS}\")\n  endif()\n  set(REQUIRED_LIBS \"${SCOTCH_LIBRARIES}\")\n  # THREADS\n  if(CMAKE_THREAD_LIBS_INIT)\n    list(APPEND REQUIRED_LIBS \"${CMAKE_THREAD_LIBS_INIT}\")\n  endif()\n  set(Z_LIBRARY \"Z_LIBRARY-NOTFOUND\")\n  find_library(Z_LIBRARY NAMES z)\n  mark_as_advanced(Z_LIBRARY)\n  if(Z_LIBRARY)\n    list(APPEND REQUIRED_LIBS \"-lz\")\n  endif()\n  set(M_LIBRARY \"M_LIBRARY-NOTFOUND\")\n  find_library(M_LIBRARY NAMES m)\n  mark_as_advanced(M_LIBRARY)\n  if(M_LIBRARY)\n    list(APPEND REQUIRED_LIBS \"-lm\")\n  endif()\n  set(RT_LIBRARY \"RT_LIBRARY-NOTFOUND\")\n  find_library(RT_LIBRARY NAMES rt)\n  mark_as_advanced(RT_LIBRARY)\n  if(RT_LIBRARY)\n    list(APPEND REQUIRED_LIBS \"-lrt\")\n  endif()\n\n  # set required libraries for link\n  set(CMAKE_REQUIRED_INCLUDES \"${REQUIRED_INCDIRS}\")\n  set(CMAKE_REQUIRED_LIBRARIES)\n  foreach(lib_dir ${REQUIRED_LIBDIRS})\n    list(APPEND CMAKE_REQUIRED_LIBRARIES \"-L${lib_dir}\")\n  endforeach()\n  list(APPEND CMAKE_REQUIRED_LIBRARIES \"${REQUIRED_LIBS}\")\n  string(REGEX REPLACE \"^ -\" \"-\" CMAKE_REQUIRED_LIBRARIES \"${CMAKE_REQUIRED_LIBRARIES}\")\n\n  # test link\n  unset(SCOTCH_WORKS CACHE)\n  include(CheckFunctionExists)\n  check_function_exists(SCOTCH_graphInit SCOTCH_WORKS)\n  mark_as_advanced(SCOTCH_WORKS)\n\n  if(SCOTCH_WORKS)\n    # save link with dependencies\n    set(SCOTCH_LIBRARIES \"${REQUIRED_LIBS}\")\n  else()\n    if(NOT SCOTCH_FIND_QUIETLY)\n      message(STATUS \"Looking for SCOTCH : test of SCOTCH_graphInit with SCOTCH library fails\")\n      message(STATUS \"CMAKE_REQUIRED_LIBRARIES: ${CMAKE_REQUIRED_LIBRARIES}\")\n      message(STATUS \"CMAKE_REQUIRED_INCLUDES: ${CMAKE_REQUIRED_INCLUDES}\")\n      message(STATUS \"Check in CMakeFiles/CMakeError.log to figure out why it fails\")\n    endif()\n  endif()\n  set(CMAKE_REQUIRED_INCLUDES)\n  set(CMAKE_REQUIRED_FLAGS)\n  set(CMAKE_REQUIRED_LIBRARIES)\nendif()\n\nif (SCOTCH_LIBRARIES)\n  list(GET SCOTCH_LIBRARIES 0 first_lib)\n  get_filename_component(first_lib_path \"${first_lib}\" PATH)\n  if (${first_lib_path} MATCHES \"/lib(32|64)?$\")\n    string(REGEX REPLACE \"/lib(32|64)?$\" \"\" not_cached_dir \"${first_lib_path}\")\n    set(SCOTCH_DIR_FOUND \"${not_cached_dir}\" CACHE PATH \"Installation directory of SCOTCH library\" FORCE)\n  else()\n    set(SCOTCH_DIR_FOUND \"${first_lib_path}\" CACHE PATH \"Installation directory of SCOTCH library\" FORCE)\n  endif()\nendif()\nmark_as_advanced(SCOTCH_DIR)\nmark_as_advanced(SCOTCH_DIR_FOUND)\n\n# Check the size of SCOTCH_Num\n# ---------------------------------\nset(CMAKE_REQUIRED_INCLUDES ${SCOTCH_INCLUDE_DIRS})\n\ninclude(CheckCSourceRuns)\n#stdio.h and stdint.h should be included by scotch.h directly\nset(SCOTCH_C_TEST_SCOTCH_Num_4 \"\n#include <stdio.h>\n#include <stdint.h>\n#include <scotch.h>\nint main(int argc, char **argv) {\n  if (sizeof(SCOTCH_Num) == 4)\n    return 0;\n  else\n    return 1;\n}\n\")\n\nset(SCOTCH_C_TEST_SCOTCH_Num_8 \"\n#include <stdio.h>\n#include <stdint.h>\n#include <scotch.h>\nint main(int argc, char **argv) {\n  if (sizeof(SCOTCH_Num) == 8)\n    return 0;\n  else\n    return 1;\n}\n\")\ncheck_c_source_runs(\"${SCOTCH_C_TEST_SCOTCH_Num_4}\" SCOTCH_Num_4)\nif(NOT SCOTCH_Num_4)\n  check_c_source_runs(\"${SCOTCH_C_TEST_SCOTCH_Num_8}\" SCOTCH_Num_8)\n  if(NOT SCOTCH_Num_8)\n    set(SCOTCH_INTSIZE -1)\n  else()\n    set(SCOTCH_INTSIZE 8)\n  endif()\nelse()\n  set(SCOTCH_INTSIZE 4)\nendif()\nset(CMAKE_REQUIRED_INCLUDES \"\")\n\n# check that SCOTCH has been found\n# ---------------------------------\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(SCOTCH DEFAULT_MSG\n  SCOTCH_LIBRARIES\n  SCOTCH_WORKS)\n#\n# TODO: Add possibility to check for specific functions in the library\n#\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindSPQR.cmake",
    "content": "# SPQR lib usually requires linking to a blas and lapack library.\n# It is up to the user of this module to find a BLAS and link to it.\n\n# SPQR lib requires Cholmod, colamd and amd as well. \n# FindCholmod.cmake can be used to find those packages before finding spqr\n\nif (SPQR_INCLUDES AND SPQR_LIBRARIES)\n  set(SPQR_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(SPQR_INCLUDES\n  NAMES\n  SuiteSparseQR.hpp\n  PATHS\n  $ENV{SPQRDIR}\n  ${INCLUDE_INSTALL_DIR}\n  PATH_SUFFIXES\n  suitesparse\n  ufsparse\n)\n\nfind_library(SPQR_LIBRARIES spqr $ENV{SPQRDIR} ${LIB_INSTALL_DIR})\n\nif(SPQR_LIBRARIES)\n\n  find_library(SUITESPARSE_LIBRARY SuiteSparse PATHS $ENV{SPQRDIR} ${LIB_INSTALL_DIR})\n  if (SUITESPARSE_LIBRARY)\n    set(SPQR_LIBRARIES ${SPQR_LIBRARIES} ${SUITESPARSE_LIBRARY})\n  endif()\n\n  find_library(CHOLMOD_LIBRARY cholmod PATHS $ENV{UMFPACK_LIBDIR} $ENV{UMFPACKDIR} ${LIB_INSTALL_DIR})\n  if(CHOLMOD_LIBRARY)\n    set(SPQR_LIBRARIES ${SPQR_LIBRARIES} ${CHOLMOD_LIBRARY})\n  endif()\n  \nendif()\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(SPQR DEFAULT_MSG SPQR_INCLUDES SPQR_LIBRARIES)\n\nmark_as_advanced(SPQR_INCLUDES SPQR_LIBRARIES)"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindStandardMathLibrary.cmake",
    "content": "# - Try to find how to link to the standard math library, if anything at all is needed to do.\n# On most platforms this is automatic, but for example it's not automatic on QNX.\n#\n# Once done this will define\n#\n#  STANDARD_MATH_LIBRARY_FOUND - we found how to successfully link to the standard math library\n#  STANDARD_MATH_LIBRARY - the name of the standard library that one has to link to.\n#                            -- this will be left empty if it's automatic (most platforms).\n#                            -- this will be set to \"m\" on platforms where one must explicitly\n#                               pass the \"-lm\" linker flag.\n#\n# Copyright (c) 2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n#               2020 Susi Lehtola <susi.lehtola@gmail.com>\n# Redistribution and use is allowed according to the terms of the 2-clause BSD license.\n\n\ninclude(CheckCXXSourceCompiles)\n\n# a little test program for c++ math functions.\n# notice the std:: is required on some platforms such as QNX\n# notice the (void) is required if -Wall (-Wunused-value) is added to CMAKE_CXX_FLAG\n\n# We read in the arguments from standard input to avoid the compiler optimizing away the calls\nset(find_standard_math_library_test_program\n\"\n#include<cmath>\nint main(int argc, char **){\n  return int(std::sin(double(argc)) + std::log(double(argc)));\n}\")\n\n# first try compiling/linking the test program without any linker flags\n\nset(CMAKE_REQUIRED_FLAGS \"\")\nset(CMAKE_REQUIRED_LIBRARIES \"\")\nCHECK_CXX_SOURCE_COMPILES(\n  \"${find_standard_math_library_test_program}\"\n  standard_math_library_linked_to_automatically\n)\n\nif(standard_math_library_linked_to_automatically)\n\n  # the test program linked successfully without any linker flag.\n  set(STANDARD_MATH_LIBRARY \"\")\n  set(STANDARD_MATH_LIBRARY_FOUND TRUE)\n\nelse()\n\n  # the test program did not link successfully without any linker flag.\n  # This is a very uncommon case that so far we only saw on QNX. The next try is the\n  # standard name 'm' for the standard math library.\n\n  set(CMAKE_REQUIRED_LIBRARIES \"m\")\n  CHECK_CXX_SOURCE_COMPILES(\n    \"${find_standard_math_library_test_program}\"\n    standard_math_library_linked_to_as_m)\n\n  if(standard_math_library_linked_to_as_m)\n\n    # the test program linked successfully when linking to the 'm' library\n    set(STANDARD_MATH_LIBRARY \"m\")\n    set(STANDARD_MATH_LIBRARY_FOUND TRUE)\n\n  else()\n\n    # the test program still doesn't link successfully\n    set(STANDARD_MATH_LIBRARY_FOUND FALSE)\n\n  endif()\n\nendif()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindSuperLU.cmake",
    "content": "\n# Umfpack lib usually requires linking to a blas library.\n# It is up to the user of this module to find a BLAS and link to it.\n\nif (SUPERLU_INCLUDES AND SUPERLU_LIBRARIES)\n  set(SUPERLU_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(SUPERLU_INCLUDES\n  NAMES\n  supermatrix.h\n  PATHS\n  $ENV{SUPERLUDIR}\n  ${INCLUDE_INSTALL_DIR}\n  PATH_SUFFIXES\n  superlu\n  SRC\n)\n\nfind_library(SUPERLU_LIBRARIES\n  NAMES \"superlu_5.2.1\" \"superlu_5.2\" \"superlu_5.1.1\" \"superlu_5.1\" \"superlu_5.0\" \"superlu_4.3\" \"superlu_4.2\" \"superlu_4.1\" \"superlu_4.0\" \"superlu_3.1\" \"superlu_3.0\" \"superlu\"\n  PATHS $ENV{SUPERLUDIR} ${LIB_INSTALL_DIR}\n  PATH_SUFFIXES lib)\n\nif(SUPERLU_INCLUDES AND SUPERLU_LIBRARIES)\n\ninclude(CheckCXXSourceCompiles)\ninclude(CMakePushCheckState)\ncmake_push_check_state()\n\nset(CMAKE_REQUIRED_INCLUDES ${CMAKE_REQUIRED_INCLUDES} ${SUPERLU_INCLUDES})\n\n# check whether struct mem_usage_t is globally defined\ncheck_cxx_source_compiles(\"\ntypedef int int_t;\n#include <supermatrix.h>\n#include <slu_util.h>\nint main() {\n  mem_usage_t mem;\n  return 0;\n}\"\nSUPERLU_HAS_GLOBAL_MEM_USAGE_T)\n\n\ncheck_cxx_source_compiles(\"\ntypedef int int_t;\n#include <supermatrix.h>\n#include <superlu_enum_consts.h>\nint main() {\n  return SLU_SINGLE;\n}\"\nSUPERLU_HAS_CLEAN_ENUMS)\n\ncheck_cxx_source_compiles(\"\ntypedef int int_t;\n#include <supermatrix.h>\n#include <slu_util.h>\nint main(void)\n{\n  GlobalLU_t glu;\n  return 0;\n}\"\nSUPERLU_HAS_GLOBALLU_T)\n\nif(SUPERLU_HAS_GLOBALLU_T)\n  # at least 5.0\n  set(SUPERLU_VERSION_VAR \"5.0\")\nelseif(SUPERLU_HAS_CLEAN_ENUMS)\n  # at least 4.3\n  set(SUPERLU_VERSION_VAR \"4.3\")\nelseif(SUPERLU_HAS_GLOBAL_MEM_USAGE_T)\n  # at least 4.0\n  set(SUPERLU_VERSION_VAR \"4.0\")\nelse()\n  set(SUPERLU_VERSION_VAR \"3.0\")\nendif()\n\ncmake_pop_check_state()\n\nif(SuperLU_FIND_VERSION)\n  if(${SUPERLU_VERSION_VAR} VERSION_LESS ${SuperLU_FIND_VERSION})\n    set(SUPERLU_VERSION_OK FALSE)\n  else()\n    set(SUPERLU_VERSION_OK TRUE)\n  endif()\nelse()\n  set(SUPERLU_VERSION_OK TRUE)\nendif()\n\nendif()\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(SuperLU\n                                  REQUIRED_VARS SUPERLU_INCLUDES SUPERLU_LIBRARIES SUPERLU_VERSION_OK\n                                  VERSION_VAR SUPERLU_VERSION_VAR)\n\nmark_as_advanced(SUPERLU_INCLUDES SUPERLU_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindTriSYCL.cmake",
    "content": "#.rst:\n# FindTriSYCL\n#---------------\n#\n# TODO : insert Copyright and licence\n\n#########################\n#  FindTriSYCL.cmake\n#########################\n#\n#  Tools for finding and building with TriSYCL.\n#\n#  User must define TRISYCL_INCLUDE_DIR pointing to the triSYCL\n#  include directory.\n#\n#  Latest version of this file can be found at:\n#    https://github.com/triSYCL/triSYCL\n\n# Requite CMake version 3.5 or higher\ncmake_minimum_required (VERSION 3.5)\n\n# Check that a supported host compiler can be found\nif(CMAKE_COMPILER_IS_GNUCXX)\n  # Require at least gcc 5.4\n  if (CMAKE_CXX_COMPILER_VERSION VERSION_LESS 5.4)\n    message(FATAL_ERROR\n      \"host compiler - Not found! (gcc version must be at least 5.4)\")\n  else()\n    message(STATUS \"host compiler - gcc ${CMAKE_CXX_COMPILER_VERSION}\")\n  endif()\nelseif (\"${CMAKE_CXX_COMPILER_ID}\" STREQUAL \"Clang\")\n  # Require at least clang 3.9\n  if (${CMAKE_CXX_COMPILER_VERSION} VERSION_LESS 3.9)\n    message(FATAL_ERROR\n      \"host compiler - Not found! (clang version must be at least 3.9)\")\n  else()\n    message(STATUS \"host compiler - clang ${CMAKE_CXX_COMPILER_VERSION}\")\n  endif()\nelse()\n  message(WARNING\n    \"host compiler - Not found! (triSYCL supports GCC and Clang)\")\nendif()\n\n#triSYCL options\noption(TRISYCL_OPENMP \"triSYCL multi-threading with OpenMP\" ON)\noption(TRISYCL_OPENCL \"triSYCL OpenCL interoperability mode\" OFF)\noption(TRISYCL_NO_ASYNC \"triSYCL use synchronous kernel execution\" OFF)\noption(TRISYCL_DEBUG \"triSCYL use debug mode\" OFF)\noption(TRISYCL_DEBUG_STRUCTORS \"triSYCL trace of object lifetimes\" OFF)\noption(TRISYCL_TRACE_KERNEL \"triSYCL trace of kernel execution\" OFF)\n\nmark_as_advanced(TRISYCL_OPENMP)\nmark_as_advanced(TRISYCL_OPENCL)\nmark_as_advanced(TRISYCL_NO_ASYNC)\nmark_as_advanced(TRISYCL_DEBUG)\nmark_as_advanced(TRISYCL_DEBUG_STRUCTORS)\nmark_as_advanced(TRISYCL_TRACE_KERNEL)\n\n#triSYCL definitions\nset(CL_SYCL_LANGUAGE_VERSION 220 CACHE STRING\n  \"Host language version to be used by trisYCL (default is: 220)\")\nset(TRISYCL_CL_LANGUAGE_VERSION 220 CACHE STRING\n  \"Device language version to be used by trisYCL (default is: 220)\")\n# triSYCL now requires c++17\nset(CMAKE_CXX_STANDARD 17)\nset(CXX_STANDARD_REQUIRED ON)\n\n\n# Find OpenCL package\ninclude(CMakeFindDependencyMacro)\nif(TRISYCL_OPENCL)\n  find_dependency(OpenCL REQUIRED)\n  if(UNIX)\n    set(BOOST_COMPUTE_INCPATH /usr/include/compute CACHE PATH\n      \"Path to Boost.Compute headers (default is: /usr/include/compute)\")\n  endif()\nendif()\n\n# Find OpenMP package\nif(TRISYCL_OPENMP)\n  find_dependency(OpenMP REQUIRED)\nendif()\n\n# Find Boost\nfind_dependency(Boost 1.58 REQUIRED COMPONENTS chrono log)\n\n# If debug or trace we need boost log\nif(TRISYCL_DEBUG OR TRISYCL_DEBUG_STRUCTORS OR TRISYCL_TRACE_KERNEL)\n  set(LOG_NEEDED ON)\nelse()\n  set(LOG_NEEDED OFF)\nendif()\n\nfind_dependency(Threads REQUIRED)\n\n# Find triSYCL directory\nif (TRISYCL_INCLUDES AND TRISYCL_LIBRARIES)\n  set(TRISYCL_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(TRISYCL_INCLUDE_DIR\n  NAMES sycl.hpp\n  PATHS $ENV{TRISYCLDIR} $ENV{TRISYCLDIR}/include ${INCLUDE_INSTALL_DIR}\n  PATH_SUFFIXES triSYCL\n)\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(TriSYCL DEFAULT_MSG\n                                  TRISYCL_INCLUDE_DIR)\n\nif(NOT TRISYCL_INCLUDE_DIR)\n  message(FATAL_ERROR\n    \"triSYCL include directory - Not found! (please set TRISYCL_INCLUDE_DIR\")\nelse()\n  message(STATUS \"triSYCL include directory - Found ${TRISYCL_INCLUDE_DIR}\")\nendif()\n\ninclude(CMakeParseArguments)\n#######################\n#  add_sycl_to_target\n#######################\nfunction(add_sycl_to_target)\n  set(options)\n  set(one_value_args\n    TARGET\n  )\n  set(multi_value_args\n    SOURCES\n  )\n  cmake_parse_arguments(ADD_SYCL_ARGS\n    \"${options}\"\n    \"${one_value_args}\"\n    \"${multi_value_args}\"\n    ${ARGN}\n  )\n\n  # Add include directories to the \"#include <>\" paths\n  target_include_directories (${ADD_SYCL_ARGS_TARGET} PUBLIC\n    ${TRISYCL_INCLUDE_DIR}\n    ${Boost_INCLUDE_DIRS}\n    $<$<BOOL:${TRISYCL_OPENCL}>:${OpenCL_INCLUDE_DIRS}>\n    $<$<BOOL:${TRISYCL_OPENCL}>:${BOOST_COMPUTE_INCPATH}>)\n\n  # Link dependencies\n  target_link_libraries(${ADD_SYCL_ARGS_TARGET}\n    $<$<BOOL:${TRISYCL_OPENCL}>:${OpenCL_LIBRARIES}>\n    Threads::Threads\n    $<$<BOOL:${LOG_NEEDED}>:Boost::log>\n    Boost::chrono)\n\n  # Compile definitions\n  target_compile_definitions(${ADD_SYCL_ARGS_TARGET} PUBLIC\n    EIGEN_SYCL_TRISYCL\n    $<$<BOOL:${TRISYCL_NO_ASYNC}>:TRISYCL_NO_ASYNC>\n    $<$<BOOL:${TRISYCL_OPENCL}>:TRISYCL_OPENCL>\n    $<$<BOOL:${TRISYCL_DEBUG}>:TRISYCL_DEBUG>\n    $<$<BOOL:${TRISYCL_DEBUG_STRUCTORS}>:TRISYCL_DEBUG_STRUCTORS>\n    $<$<BOOL:${TRISYCL_TRACE_KERNEL}>:TRISYCL_TRACE_KERNEL>\n    $<$<BOOL:${LOG_NEEDED}>:BOOST_LOG_DYN_LINK>)\n\n  # C++ and OpenMP requirements\n  target_compile_options(${ADD_SYCL_ARGS_TARGET} PUBLIC\n    ${TRISYCL_COMPILE_OPTIONS}\n    $<$<BOOL:${TRISYCL_OPENMP}>:${OpenMP_CXX_FLAGS}>)\n\n  if(${TRISYCL_OPENMP} AND (NOT WIN32))\n    # Does not support generator expressions\n    set_target_properties(${ADD_SYCL_ARGS_TARGET}\n      PROPERTIES\n      LINK_FLAGS ${OpenMP_CXX_FLAGS})\n  endif()\n\nendfunction()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/FindUMFPACK.cmake",
    "content": "# Umfpack lib usually requires linking to a blas library.\n# It is up to the user of this module to find a BLAS and link to it.\n\nif (UMFPACK_INCLUDES AND UMFPACK_LIBRARIES)\n  set(UMFPACK_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(UMFPACK_INCLUDES\n  NAMES\n  umfpack.h\n  PATHS\n  $ENV{UMFPACKDIR}\n  ${INCLUDE_INSTALL_DIR}\n  PATH_SUFFIXES\n  suitesparse\n  ufsparse\n)\n\nfind_library(UMFPACK_LIBRARIES umfpack PATHS $ENV{UMFPACKDIR} ${LIB_INSTALL_DIR})\n\nif(UMFPACK_LIBRARIES)\n\n  if(NOT UMFPACK_LIBDIR)\n    get_filename_component(UMFPACK_LIBDIR ${UMFPACK_LIBRARIES} PATH)\n  endif()\n\n  find_library(COLAMD_LIBRARY colamd PATHS ${UMFPACK_LIBDIR} $ENV{UMFPACKDIR} ${LIB_INSTALL_DIR})\n  if(COLAMD_LIBRARY)\n    set(UMFPACK_LIBRARIES ${UMFPACK_LIBRARIES} ${COLAMD_LIBRARY})\n  endif ()\n  \n  find_library(AMD_LIBRARY amd PATHS ${UMFPACK_LIBDIR} $ENV{UMFPACKDIR} ${LIB_INSTALL_DIR})\n  if(AMD_LIBRARY)\n    set(UMFPACK_LIBRARIES ${UMFPACK_LIBRARIES} ${AMD_LIBRARY})\n  endif ()\n\n  find_library(SUITESPARSE_LIBRARY SuiteSparse PATHS ${UMFPACK_LIBDIR} $ENV{UMFPACKDIR} ${LIB_INSTALL_DIR})\n  if(SUITESPARSE_LIBRARY)\n    set(UMFPACK_LIBRARIES ${UMFPACK_LIBRARIES} ${SUITESPARSE_LIBRARY})\n  endif ()\n\n  find_library(CHOLMOD_LIBRARY cholmod PATHS $ENV{UMFPACK_LIBDIR} $ENV{UMFPACKDIR} ${LIB_INSTALL_DIR})\n  if(CHOLMOD_LIBRARY)\n    set(UMFPACK_LIBRARIES ${UMFPACK_LIBRARIES} ${CHOLMOD_LIBRARY})\n  endif()\n\nendif()\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(UMFPACK DEFAULT_MSG\n                                  UMFPACK_INCLUDES UMFPACK_LIBRARIES)\n\nmark_as_advanced(UMFPACK_INCLUDES UMFPACK_LIBRARIES AMD_LIBRARY COLAMD_LIBRARY CHOLMOD_LIBRARY SUITESPARSE_LIBRARY)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/cmake/RegexUtils.cmake",
    "content": "function(escape_string_as_regex _str_out _str_in)\n  string(REGEX REPLACE \"\\\\\\\\\" \"\\\\\\\\\\\\\\\\\" FILETEST2 \"${_str_in}\")\n  string(REGEX REPLACE \"([.$+*?|-])\" \"\\\\\\\\\\\\1\" FILETEST2 \"${FILETEST2}\")\n  string(REGEX REPLACE \"\\\\^\" \"\\\\\\\\^\" FILETEST2 \"${FILETEST2}\")\n  string(REGEX REPLACE \"\\\\(\" \"\\\\\\\\(\" FILETEST2 \"${FILETEST2}\")\n  string(REGEX REPLACE \"\\\\)\" \"\\\\\\\\)\" FILETEST2 \"${FILETEST2}\")\n  string(REGEX REPLACE \"\\\\[\" \"\\\\\\\\[\" FILETEST2 \"${FILETEST2}\")\n  string(REGEX REPLACE \"\\\\]\" \"\\\\\\\\]\" FILETEST2 \"${FILETEST2}\")\n  set(${_str_out} \"${FILETEST2}\" PARENT_SCOPE)\nendfunction()\n\nfunction(test_escape_string_as_regex)\n  set(test1 \"\\\\.^$-+*()[]?|\")\n  escape_string_as_regex(test2 \"${test1}\")\n  set(testRef \"\\\\\\\\\\\\.\\\\^\\\\$\\\\-\\\\+\\\\*\\\\(\\\\)\\\\[\\\\]\\\\?\\\\|\")\n  if(NOT test2 STREQUAL testRef)\n\tmessage(\"Error in the escape_string_for_regex function : \\n   ${test1} was escaped as ${test2}, should be ${testRef}\")\n  endif()\nendfunction()"
  },
  {
    "path": "VO_Module/thirdparty/eigen/debug/gdb/__init__.py",
    "content": "# Intentionally empty\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/debug/gdb/printers.py",
    "content": "# -*- coding: utf-8 -*-\n# This file is part of Eigen, a lightweight C++ template library\n# for linear algebra.\n#\n# Copyright (C) 2009 Benjamin Schindler <bschindler@inf.ethz.ch>\n#\n# This Source Code Form is subject to the terms of the Mozilla Public\n# License, v. 2.0. If a copy of the MPL was not distributed with this\n# file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n# Pretty printers for Eigen::Matrix\n# This is still pretty basic as the python extension to gdb is still pretty basic. \n# It cannot handle complex eigen types and it doesn't support many of the other eigen types\n# This code supports fixed size as well as dynamic size matrices\n\n# To use it:\n#\n# * Create a directory and put the file as well as an empty __init__.py in \n#   that directory.\n# * Create a ~/.gdbinit file, that contains the following:\n#      python\n#      import sys\n#      sys.path.insert(0, '/path/to/eigen/printer/directory')\n#      from printers import register_eigen_printers\n#      register_eigen_printers(None)\n#      end\n\nimport gdb\nimport re\nimport itertools\nfrom bisect import bisect_left\n\n\n# Basic row/column iteration code for use with Sparse and Dense matrices\nclass _MatrixEntryIterator(object):\n\t\n\tdef __init__(self, rows, cols, row_major):\n\t\tself.rows = rows\n\t\tself.cols = cols\n\t\tself.currentRow = 0\n\t\tself.currentCol = 0\n\t\tself.rowMajor = row_major\n\n\tdef __iter__(self):\n\t\treturn self\n\n\tdef next(self):\n\t\treturn self.__next__()  # Python 2.x compatibility\n\n\tdef __next__(self):\n\t\trow = self.currentRow\n\t\tcol = self.currentCol\n\t\tif self.rowMajor == 0:\n\t\t\tif self.currentCol >= self.cols:\n\t\t\t\traise StopIteration\n\t\t\t\t\n\t\t\tself.currentRow = self.currentRow + 1\n\t\t\tif self.currentRow >= self.rows:\n\t\t\t\tself.currentRow = 0\n\t\t\t\tself.currentCol = self.currentCol + 1\n\t\telse:\n\t\t\tif self.currentRow >= self.rows:\n\t\t\t\traise StopIteration\n\t\t\t\t\n\t\t\tself.currentCol = self.currentCol + 1\n\t\t\tif self.currentCol >= self.cols:\n\t\t\t\tself.currentCol = 0\n\t\t\t\tself.currentRow = self.currentRow + 1\n\n\t\treturn row, col\n\n\nclass EigenMatrixPrinter:\n\t\"\"\"Print Eigen Matrix or Array of some kind\"\"\"\n\n\tdef __init__(self, variety, val):\n\t\t\"\"\"Extract all the necessary information\"\"\"\n\t\t\n\t\t# Save the variety (presumably \"Matrix\" or \"Array\") for later usage\n\t\tself.variety = variety\n\t\t\n\t\t# The gdb extension does not support value template arguments - need to extract them by hand\n\t\ttypeinfo = val.type\n\t\tif typeinfo.code == gdb.TYPE_CODE_REF:\n\t\t\ttypeinfo = typeinfo.target()\n\t\tself.type = typeinfo.unqualified().strip_typedefs()\n\t\ttag = self.type.tag\n\t\tregex = re.compile('<.*>')\n\t\tm = regex.findall(tag)[0][1:-1]\n\t\ttemplate_params = m.split(',')\n\t\ttemplate_params = [x.replace(\" \", \"\") for x in template_params]\n\t\t\n\t\tif template_params[1] in ['-0x00000000000000001', '-0x000000001', '-1']:\n\t\t\tself.rows = val['m_storage']['m_rows']\n\t\telse:\n\t\t\tself.rows = int(template_params[1])\n\t\t\n\t\tif template_params[2] in ['-0x00000000000000001', '-0x000000001', '-1']:\n\t\t\tself.cols = val['m_storage']['m_cols']\n\t\telse:\n\t\t\tself.cols = int(template_params[2])\n\t\t\n\t\tself.options = 0  # default value\n\t\tif len(template_params) > 3:\n\t\t\tself.options = template_params[3]\n\t\t\n\t\tself.rowMajor = (int(self.options) & 0x1)\n\t\t\n\t\tself.innerType = self.type.template_argument(0)\n\t\t\n\t\tself.val = val\n\t\t\n\t\t# Fixed size matrices have a struct as their storage, so we need to walk through this\n\t\tself.data = self.val['m_storage']['m_data']\n\t\tif self.data.type.code == gdb.TYPE_CODE_STRUCT:\n\t\t\tself.data = self.data['array']\n\t\t\tself.data = self.data.cast(self.innerType.pointer())\n\t\t\t\n\tclass _Iterator(_MatrixEntryIterator):\n\t\tdef __init__(self, rows, cols, data_ptr, row_major):\n\t\t\tsuper(EigenMatrixPrinter._Iterator, self).__init__(rows, cols, row_major)\n\n\t\t\tself.dataPtr = data_ptr\n\n\t\tdef __next__(self):\n\t\t\trow, col = super(EigenMatrixPrinter._Iterator, self).__next__()\n\t\t\t\n\t\t\titem = self.dataPtr.dereference()\n\t\t\tself.dataPtr = self.dataPtr + 1\n\t\t\tif self.cols == 1:  # if it's a column vector\n\t\t\t\treturn '[%d]' % (row,), item\n\t\t\telif self.rows == 1:  # if it's a row vector\n\t\t\t\treturn '[%d]' % (col,), item\n\t\t\treturn '[%d,%d]' % (row, col), item\n\t\t\t\n\tdef children(self):\n\t\t\n\t\treturn self._Iterator(self.rows, self.cols, self.data, self.rowMajor)\n\t\t\n\tdef to_string(self):\n\t\treturn \"Eigen::%s<%s,%d,%d,%s> (data ptr: %s)\" % (\n\t\t\tself.variety, self.innerType, self.rows, self.cols,\n\t\t\t\"RowMajor\" if self.rowMajor else \"ColMajor\", self.data)\n\n\nclass EigenSparseMatrixPrinter:\n\t\"\"\"Print an Eigen SparseMatrix\"\"\"\n\n\tdef __init__(self, val):\n\t\t\"\"\"Extract all the necessary information\"\"\"\n\n\t\ttypeinfo = val.type\n\t\tif typeinfo.code == gdb.TYPE_CODE_REF:\n\t\t\ttypeinfo = typeinfo.target()\n\t\tself.type = typeinfo.unqualified().strip_typedefs()\n\t\ttag = self.type.tag\n\t\tregex = re.compile('<.*>')\n\t\tm = regex.findall(tag)[0][1:-1]\n\t\ttemplate_params = m.split(',')\n\t\ttemplate_params = [x.replace(\" \", \"\") for x in template_params]\n\n\t\tself.options = 0\n\t\tif len(template_params) > 1:\n\t\t\tself.options = template_params[1]\n\t\t\n\t\tself.rowMajor = (int(self.options) & 0x1)\n\t\t\n\t\tself.innerType = self.type.template_argument(0)\n\t\t\n\t\tself.val = val\n\n\t\tself.data = self.val['m_data']\n\t\tself.data = self.data.cast(self.innerType.pointer())\n\n\tclass _Iterator(_MatrixEntryIterator):\n\t\tdef __init__(self, rows, cols, val, row_major):\n\t\t\tsuper(EigenSparseMatrixPrinter._Iterator, self).__init__(rows, cols, row_major)\n\n\t\t\tself.val = val\n\t\t\t\n\t\tdef __next__(self):\n\t\t\trow, col = super(EigenSparseMatrixPrinter._Iterator, self).__next__()\n\t\t\t\t\n\t\t\t# repeat calculations from SparseMatrix.h:\n\t\t\touter = row if self.rowMajor else col\n\t\t\tinner = col if self.rowMajor else row\n\t\t\tstart = self.val['m_outerIndex'][outer]\n\t\t\tend = (\n\t\t\t\t(start + self.val['m_innerNonZeros'][outer])\n\t\t\t\tif self.val['m_innerNonZeros'] else self.val['m_outerIndex'][outer+1]\n\t\t\t)\n\n\t\t\t# and from CompressedStorage.h:\n\t\t\tdata = self.val['m_data']\n\t\t\tif start >= end:\n\t\t\t\titem = 0\n\t\t\telif (end > start) and (inner == data['m_indices'][end-1]):\n\t\t\t\titem = data['m_values'][end-1]\n\t\t\telse:\n\t\t\t\t# create Python index list from the target range within m_indices\n\t\t\t\tindices = [data['m_indices'][x] for x in range(int(start), int(end)-1)]\n\t\t\t\t# find the index with binary search\n\t\t\t\tidx = int(start) + bisect_left(indices, inner)\n\t\t\t\tif idx < end and data['m_indices'][idx] == inner:\n\t\t\t\t\titem = data['m_values'][idx]\n\t\t\t\telse:\n\t\t\t\t\titem = 0\n\n\t\t\treturn '[%d,%d]' % (row, col), item\n\n\tdef children(self):\n\t\tif self.data:\n\t\t\treturn self._Iterator(self.rows(), self.cols(), self.val, self.rowMajor)\n\n\t\treturn iter([])   # empty matrix, for now\n\n\tdef rows(self):\n\t\treturn self.val['m_outerSize'] if self.rowMajor else self.val['m_innerSize']\n\n\tdef cols(self):\n\t\treturn self.val['m_innerSize'] if self.rowMajor else self.val['m_outerSize']\n\n\tdef to_string(self):\n\n\t\tif self.data:\n\t\t\tstatus = (\"not compressed\" if self.val['m_innerNonZeros'] else \"compressed\")\n\t\telse:\n\t\t\tstatus = \"empty\"\n\t\tdimensions = \"%d x %d\" % (self.rows(), self.cols())\n\t\tlayout = \"row\" if self.rowMajor else \"column\"\n\n\t\treturn \"Eigen::SparseMatrix<%s>, %s, %s major, %s\" % (\n\t\t\tself.innerType, dimensions, layout, status)\n\n\nclass EigenQuaternionPrinter:\n\t\"\"\"Print an Eigen Quaternion\"\"\"\n\t\n\tdef __init__(self, val):\n\t\t\"\"\"Extract all the necessary information\"\"\"\n\t\t# The gdb extension does not support value template arguments - need to extract them by hand\n\t\ttypeinfo = val.type\n\t\tif typeinfo.code == gdb.TYPE_CODE_REF:\n\t\t\ttypeinfo = typeinfo.target()\n\t\tself.type = typeinfo.unqualified().strip_typedefs()\n\t\tself.innerType = self.type.template_argument(0)\n\t\tself.val = val\n\t\t\n\t\t# Quaternions have a struct as their storage, so we need to walk through this\n\t\tself.data = self.val['m_coeffs']['m_storage']['m_data']['array']\n\t\tself.data = self.data.cast(self.innerType.pointer())\n\t\t\t\n\tclass _Iterator:\n\t\tdef __init__(self, data_ptr):\n\t\t\tself.dataPtr = data_ptr\n\t\t\tself.currentElement = 0\n\t\t\tself.elementNames = ['x', 'y', 'z', 'w']\n\t\t\t\n\t\tdef __iter__(self):\n\t\t\treturn self\n\t\n\t\tdef next(self):\n\t\t\treturn self.__next__()  # Python 2.x compatibility\n\n\t\tdef __next__(self):\n\t\t\telement = self.currentElement\n\t\t\t\n\t\t\tif self.currentElement >= 4:  # there are 4 elements in a quaternion\n\t\t\t\traise StopIteration\n\t\t\t\n\t\t\tself.currentElement = self.currentElement + 1\n\t\t\t\n\t\t\titem = self.dataPtr.dereference()\n\t\t\tself.dataPtr = self.dataPtr + 1\n\t\t\treturn '[%s]' % (self.elementNames[element],), item\n\t\t\t\n\tdef children(self):\n\t\t\n\t\treturn self._Iterator(self.data)\n\t\n\tdef to_string(self):\n\t\treturn \"Eigen::Quaternion<%s> (data ptr: %s)\" % (self.innerType, self.data)\n\n\ndef cast_eigen_block_to_matrix(val):\n\t# Get the type of the variable (and convert to a string)\n\t# Example: 'const Eigen::Block<Eigen::Block<Eigen::Matrix<double, -1, -1, 0, -1, -1>, -1, -1, false> const, -1, -1, false>'\n\ttype = str(val.type)\n\n\t# Extract the Eigen::Matrix type from the Block:\n\t# From the previous example: Eigen::Matrix<double, -1, -1, 0, -1, -1>\n\tbegin = type.find('Eigen::Matrix<')\n\tend = type.find('>', begin) + 1\n\n\t# Convert the Eigen::Block to an Eigen::Matrix\n\treturn val.cast(gdb.lookup_type(type[begin:end]))\n\n\ndef build_eigen_dictionary():\n\tpretty_printers_dict[re.compile('^Eigen::Quaternion<.*>$')] = lambda val: EigenQuaternionPrinter(val)\n\tpretty_printers_dict[re.compile('^Eigen::Matrix<.*>$')] = lambda val: EigenMatrixPrinter(\"Matrix\", val)\n\tpretty_printers_dict[re.compile('^Eigen::Block<.*>$')] =\\\n\t\tlambda val: EigenMatrixPrinter(\"Matrix\", cast_eigen_block_to_matrix(val))\n\tpretty_printers_dict[re.compile('^Eigen::VectorBlock<.*>$')] =\\\n\t\tlambda val: EigenMatrixPrinter(\"Matrix\", cast_eigen_block_to_matrix(val))\n\tpretty_printers_dict[re.compile('^Eigen::SparseMatrix<.*>$')] = lambda val: EigenSparseMatrixPrinter(val)\n\tpretty_printers_dict[re.compile('^Eigen::Array<.*>$')] = lambda val: EigenMatrixPrinter(\"Array\",  val)\n\n\ndef register_eigen_printers(obj):\n\t\"\"\"Register eigen pretty-printers with objfile Obj\"\"\"\n\n\tif obj is None:\n\t\tobj = gdb\n\tobj.pretty_printers.append(lookup_function)\n\n\ndef lookup_function(val):\n\t\"\"\"Look-up and return a pretty-printer that can print val.\"\"\"\n\t\n\ttypeinfo = val.type\n\t\n\tif typeinfo.code == gdb.TYPE_CODE_REF:\n\t\ttypeinfo = typeinfo.target()\n\t\n\ttypeinfo = typeinfo.unqualified().strip_typedefs()\n\t\n\ttypename = typeinfo.tag\n\tif typename is None:\n\t\treturn None\n\t\n\tfor function in pretty_printers_dict:\n\t\tif function.search(typename):\n\t\t\treturn pretty_printers_dict[function](val)\n\t\n\treturn None\n\n\npretty_printers_dict = {}\n\nbuild_eigen_dictionary()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/debug/msvc/eigen.natvis",
    "content": "<?xml version=\"1.0\" encoding=\"utf-8\"?>\n\n<AutoVisualizer xmlns=\"http://schemas.microsoft.com/vstudio/debugger/natvis/2010\">\n\n  <!-- Fixed x Fixed Matrix -->\n  <Type Name=\"Eigen::Matrix&lt;*,*,*,*,*,*&gt;\">      \n      <AlternativeType Name=\"Eigen::Array&lt;*,-1,-1,*,*,*&gt;\"/>\n      <DisplayString>[{$T2}, {$T3}] (fixed matrix)</DisplayString>\n      <Expand>\n        <ArrayItems Condition=\"Flags%2\"> <!-- row major layout -->\n          <Rank>2</Rank>\n          <Size>$i==0 ? $T2 : $T3</Size>\n          <ValuePointer>m_storage.m_data.array</ValuePointer>\n        </ArrayItems>\n        <ArrayItems Condition=\"!(Flags%2)\"> <!-- column major layout -->\n          <Direction>Backward</Direction>\n          <Rank>2</Rank>\n          <Size>$i==0 ? $T2 : $T3</Size>\n          <ValuePointer>m_storage.m_data.array</ValuePointer>\n        </ArrayItems>\n      </Expand>\n  </Type>\n  \n  <!-- 2 x 2 Matrix -->\n  <Type Name=\"Eigen::Matrix&lt;*,2,2,*,*,*&gt;\">      \n      <AlternativeType Name=\"Eigen::Array&lt;*,2,2,*,*,*&gt;\"/>\n      <DisplayString>[2, 2] (fixed matrix)</DisplayString>\n      <Expand>\n        <Synthetic Name=\"[row 0]\" Condition=\"Flags%2\">\n          <DisplayString>({m_storage.m_data.array[0]}, {m_storage.m_data.array[1]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 0]\" Condition=\"!(Flags%2)\">\n          <DisplayString>({m_storage.m_data.array[0]}, {m_storage.m_data.array[2]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 1]\" Condition=\"Flags%2\">\n          <DisplayString>({m_storage.m_data.array[2]}, {m_storage.m_data.array[3]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 1]\" Condition=\"!(Flags%2)\">\n          <DisplayString>({m_storage.m_data.array[1]}, {m_storage.m_data.array[3]})</DisplayString>\n        </Synthetic>        \n      </Expand>\n  </Type>\n  \n  <!-- 3 x 3 Matrix -->\n  <Type Name=\"Eigen::Matrix&lt;*,3,3,*,*,*&gt;\">      \n      <AlternativeType Name=\"Eigen::Array&lt;*,3,3,*,*,*&gt;\"/>\n      <DisplayString>[3, 3] (fixed matrix)</DisplayString>\n      <Expand>\n        <Synthetic Name=\"[row 0]\" Condition=\"Flags%2\">\n          <DisplayString>({m_storage.m_data.array[0]}, {m_storage.m_data.array[1]}, {m_storage.m_data.array[2]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 0]\" Condition=\"!(Flags%2)\">\n          <DisplayString>({m_storage.m_data.array[0]}, {m_storage.m_data.array[3]}, {m_storage.m_data.array[6]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 1]\" Condition=\"Flags%2\">\n          <DisplayString>({m_storage.m_data.array[3]}, {m_storage.m_data.array[4]}, {m_storage.m_data.array[5]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 1]\" Condition=\"!(Flags%2)\">\n          <DisplayString>({m_storage.m_data.array[1]}, {m_storage.m_data.array[4]}, {m_storage.m_data.array[7]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 2]\" Condition=\"Flags%2\">\n          <DisplayString>({m_storage.m_data.array[6]}, {m_storage.m_data.array[7]}, {m_storage.m_data.array[8]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 2]\" Condition=\"!(Flags%2)\">\n          <DisplayString>({m_storage.m_data.array[2]}, {m_storage.m_data.array[5]}, {m_storage.m_data.array[8]})</DisplayString>\n        </Synthetic>        \n      </Expand>\n  </Type>\n  \n  <!-- 4 x 4 Matrix -->\n  <Type Name=\"Eigen::Matrix&lt;*,4,4,*,*,*&gt;\">      \n      <AlternativeType Name=\"Eigen::Array&lt;*,4,4,*,*,*&gt;\"/>\n      <DisplayString>[4, 4] (fixed matrix)</DisplayString>\n      <Expand>\n        <Synthetic Name=\"[row 0]\" Condition=\"Flags%2\">\n          <DisplayString>({m_storage.m_data.array[0]}, {m_storage.m_data.array[1]}, {m_storage.m_data.array[2]}, {m_storage.m_data.array[3]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 0]\" Condition=\"!(Flags%2)\">\n          <DisplayString>({m_storage.m_data.array[0]}, {m_storage.m_data.array[4]}, {m_storage.m_data.array[8]}, {m_storage.m_data.array[12]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 1]\" Condition=\"Flags%2\">\n          <DisplayString>({m_storage.m_data.array[4]}, {m_storage.m_data.array[5]}, {m_storage.m_data.array[6]}, {m_storage.m_data.array[7]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 1]\" Condition=\"!(Flags%2)\">\n          <DisplayString>({m_storage.m_data.array[1]}, {m_storage.m_data.array[5]}, {m_storage.m_data.array[9]}, {m_storage.m_data.array[13]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 2]\" Condition=\"Flags%2\">\n          <DisplayString>({m_storage.m_data.array[8]}, {m_storage.m_data.array[9]}, {m_storage.m_data.array[10]}, {m_storage.m_data.array[11]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 2]\" Condition=\"!(Flags%2)\">\n          <DisplayString>({m_storage.m_data.array[2]}, {m_storage.m_data.array[6]}, {m_storage.m_data.array[10]}, {m_storage.m_data.array[14]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 3]\" Condition=\"Flags%2\">\n          <DisplayString>({m_storage.m_data.array[12]}, {m_storage.m_data.array[13]}, {m_storage.m_data.array[14]}, {m_storage.m_data.array[15]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 3]\" Condition=\"!(Flags%2)\">\n          <DisplayString>({m_storage.m_data.array[3]}, {m_storage.m_data.array[7]}, {m_storage.m_data.array[11]}, {m_storage.m_data.array[15]})</DisplayString>\n        </Synthetic>        \n      </Expand>\n  </Type>  \n  \n  <!-- Dynamic x Dynamic Matrix -->\n  <Type Name=\"Eigen::Matrix&lt;*,-1,-1,*,*,*&gt;\">      \n      <AlternativeType Name=\"Eigen::Array&lt;*,-1,-1,*,*,*&gt;\"/>\n      <DisplayString Condition=\"m_storage.m_data == 0\">empty</DisplayString>\n      <DisplayString Condition=\"m_storage.m_data != 0\">[{m_storage.m_rows}, {m_storage.m_cols}] (dynamic matrix)</DisplayString>\n      <Expand>\n        <ArrayItems Condition=\"Flags%2\"> <!-- row major layout -->\n          <Rank>2</Rank>\n          <Size>$i==0 ? m_storage.m_rows : m_storage.m_cols</Size>\n          <ValuePointer>m_storage.m_data</ValuePointer>\n        </ArrayItems>\n        <ArrayItems Condition=\"!(Flags%2)\"> <!-- column major layout -->\n          <Direction>Backward</Direction>\n          <Rank>2</Rank>\n          <Size>$i==0 ? m_storage.m_rows : m_storage.m_cols</Size>\n          <ValuePointer>m_storage.m_data</ValuePointer>\n        </ArrayItems>\n      </Expand>\n  </Type>\n  \n  <!-- Fixed x Dynamic Matrix -->\n  <Type Name=\"Eigen::Matrix&lt;*,*,-1,*,*,*&gt;\">\n      <AlternativeType Name=\"Eigen::Array&lt;*,*,-1,*,*,*&gt;\"/>\n      <DisplayString Condition=\"m_storage.m_data == 0\">empty</DisplayString>\n      <DisplayString Condition=\"m_storage.m_data != 0\">[{$T2}, {m_storage.m_cols}] (dynamic column matrix)</DisplayString>\n      <Expand>\n        <ArrayItems Condition=\"Flags%2\"> <!-- row major layout -->\n          <Rank>2</Rank>\n          <Size>$i==0 ? $T2 : m_storage.m_cols</Size>\n          <ValuePointer>m_storage.m_data</ValuePointer>\n        </ArrayItems>\n        <ArrayItems Condition=\"!(Flags%2)\"> <!-- column major layout -->\n          <Direction>Backward</Direction>\n          <Rank>2</Rank>\n          <Size>$i==0 ? $T2 : m_storage.m_cols</Size>\n          <ValuePointer>m_storage.m_data</ValuePointer>\n        </ArrayItems>\n      </Expand>\n  </Type>\n  \n  <!-- Dynamic x Fixed Matrix -->\n  <Type Name=\"Eigen::Matrix&lt;*,-1,*,*,*,*&gt;\">\n      <AlternativeType Name=\"Eigen::Array&lt;*,-1,*,*,*,*&gt;\"/>\n      <DisplayString Condition=\"m_storage.m_data == 0\">empty</DisplayString>\n      <DisplayString Condition=\"m_storage.m_data != 0\">[{m_storage.m_rows}, {$T2}] (dynamic row matrix)</DisplayString>\n      <Expand>\n        <ArrayItems Condition=\"Flags%2\"> <!-- row major layout -->\n          <Rank>2</Rank>\n          <Size>$i==0 ? m_storage.m_rows : $T2</Size>\n          <ValuePointer>m_storage.m_data</ValuePointer>\n        </ArrayItems>\n        <ArrayItems Condition=\"!(Flags%2)\"> <!-- column major layout -->\n          <Direction>Backward</Direction>\n          <Rank>2</Rank>\n          <Size>$i==0 ? m_storage.m_rows : $T2</Size>\n          <ValuePointer>m_storage.m_data</ValuePointer>\n        </ArrayItems>\n      </Expand>\n  </Type>\n  \n  <!-- Dynamic Column Vector -->\n  <Type Name=\"Eigen::Matrix&lt;*,1,-1,*,*,*&gt;\">\n      <AlternativeType Name=\"Eigen::Array&lt;*,1,-1,*,*,*&gt;\"/>\n      <DisplayString Condition=\"m_storage.m_data == 0\">empty</DisplayString>\n      <DisplayString Condition=\"m_storage.m_data != 0\">[{m_storage.m_cols}] (dynamic column vector)</DisplayString>\n      <Expand>\n        <Item Name=\"[size]\">m_storage.m_cols</Item>\n        <ArrayItems>\n          <Size>m_storage.m_cols</Size>\n          <ValuePointer>m_storage.m_data</ValuePointer>\n        </ArrayItems>\n      </Expand>\n  </Type>\n  \n  <!-- Dynamic Row Vector -->\n  <Type Name=\"Eigen::Matrix&lt;*,-1,1,*,*,*&gt;\">\n      <AlternativeType Name=\"Eigen::Array&lt;*,-1,1,*,*,*&gt;\"/>\n      <DisplayString Condition=\"m_storage.m_data == 0\">empty</DisplayString>\n      <DisplayString Condition=\"m_storage.m_data != 0\">[{m_storage.m_rows}] (dynamic row vector)</DisplayString>\n      <Expand>\n        <Item Name=\"[size]\">m_storage.m_rows</Item>\n        <ArrayItems>\n          <Size>m_storage.m_rows</Size>\n          <ValuePointer>m_storage.m_data</ValuePointer>\n        </ArrayItems>\n      </Expand>\n  </Type>\n  \n  <!-- Fixed Vector -->\n  <Type Name=\"Eigen::Matrix&lt;*,1,1,*,*,*&gt;\">\n      <AlternativeType Name=\"Eigen::Array&lt;*,1,1,*,*,*&gt;\"/>\n      <DisplayString>[1] ({m_storage.m_data.array[0]})</DisplayString>\n      <Expand>\n        <Item Name=\"[x]\">m_storage.m_data.array[0]</Item>\n      </Expand>\n  </Type>\n  \n  <Type Name=\"Eigen::Matrix&lt;*,2,1,*,*,*&gt;\">\n      <AlternativeType Name=\"Eigen::Matrix&lt;*,1,2,*,*,*&gt;\"/>\n      <AlternativeType Name=\"Eigen::Array&lt;*,2,1,*,*,*&gt;\"/>\n      <AlternativeType Name=\"Eigen::Array&lt;*,1,2,*,*,*&gt;\"/>\n      <DisplayString>[2] ({m_storage.m_data.array[0]}, {m_storage.m_data.array[1]})</DisplayString>\n      <Expand>\n        <Item Name=\"[x]\">m_storage.m_data.array[0]</Item>\n        <Item Name=\"[y]\">m_storage.m_data.array[1]</Item>\n      </Expand>\n  </Type>\n  \n  <Type Name=\"Eigen::Matrix&lt;*,3,1,*,*,*&gt;\">\n      <AlternativeType Name=\"Eigen::Matrix&lt;*,1,3,*,*,*&gt;\"/>\n      <AlternativeType Name=\"Eigen::Array&lt;*,3,1,*,*,*&gt;\"/>\n      <AlternativeType Name=\"Eigen::Array&lt;*,1,3,*,*,*&gt;\"/>\n      <DisplayString>[3] ({m_storage.m_data.array[0]}, {m_storage.m_data.array[1]}, {m_storage.m_data.array[2]})</DisplayString>\n      <Expand>\n        <Item Name=\"[x]\">m_storage.m_data.array[0]</Item>\n        <Item Name=\"[y]\">m_storage.m_data.array[1]</Item>\n        <Item Name=\"[z]\">m_storage.m_data.array[2]</Item>\n      </Expand>\n  </Type>\n  \n    <Type Name=\"Eigen::Matrix&lt;*,4,1,*,*,*&gt;\">\n      <AlternativeType Name=\"Eigen::Matrix&lt;*,1,4,*,*,*&gt;\"/>\n      <AlternativeType Name=\"Eigen::Array&lt;*,4,1,*,*,*&gt;\"/>\n      <AlternativeType Name=\"Eigen::Array&lt;*,1,4,*,*,*&gt;\"/>\n      <DisplayString>[4] ({m_storage.m_data.array[0]}, {m_storage.m_data.array[1]}, {m_storage.m_data.array[2]}, {m_storage.m_data.array[3]})</DisplayString>\n      <Expand>\n        <Item Name=\"[x]\">m_storage.m_data.array[0]</Item>\n        <Item Name=\"[y]\">m_storage.m_data.array[1]</Item>\n        <Item Name=\"[z]\">m_storage.m_data.array[2]</Item>\n        <Item Name=\"[w]\">m_storage.m_data.array[3]</Item>\n      </Expand>\n  </Type>\n\n</AutoVisualizer>\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/CMakeLists.txt",
    "content": "project(EigenDemos)\n\nadd_custom_target(demos)\n\nif(NOT EIGEN_TEST_NOQT)\n  find_package(Qt4)\n  if(QT4_FOUND)\n    add_subdirectory(mandelbrot)\n    add_subdirectory(opengl)\n  else()\n    message(STATUS \"Qt4 not found, so disabling the mandelbrot and opengl demos\")\n  endif()\nendif()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/mandelbrot/CMakeLists.txt",
    "content": "find_package(Qt4 REQUIRED)\n\nset(CMAKE_INCLUDE_CURRENT_DIR ON)\n\nif (CMAKE_COMPILER_IS_GNUCXX)\n   set ( CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -O2\")\n   add_definitions ( \"-DNDEBUG\" )\nendif ()\n\ninclude_directories( ${QT_INCLUDE_DIR} )\n\nset(mandelbrot_SRCS\n    mandelbrot.cpp\n)\n\nqt4_automoc(${mandelbrot_SRCS})\n\nadd_executable(mandelbrot ${mandelbrot_SRCS})\nadd_dependencies(demos mandelbrot)\n\ntarget_link_libraries(mandelbrot ${QT_QTCORE_LIBRARY} ${QT_QTGUI_LIBRARY})\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/mandelbrot/README",
    "content": "*** Mandelbrot demo ***\n\nControls:\n* Left mouse button to center view at a point.\n* Drag vertically with left mouse button to zoom in and out.\n\nBe sure to enable SSE2 or AltiVec to improve performance.\n\nThe number of iterations, and the choice between single and double precision, are\ndetermined at runtime depending on the zoom level.\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/mandelbrot/mandelbrot.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"mandelbrot.h\"\n#include <iostream>\n#include<QtGui/QPainter>\n#include<QtGui/QImage>\n#include<QtGui/QMouseEvent>\n#include<QtCore/QTime>\n\nvoid MandelbrotWidget::resizeEvent(QResizeEvent *)\n{\n  if(size < width() * height())\n  {\n    std::cout << \"reallocate buffer\" << std::endl;\n    size = width() * height();\n    if(buffer) delete[]buffer;\n    buffer = new unsigned char[4*size];\n  }\n}\n\ntemplate<typename T> struct iters_before_test { enum { ret = 8 }; };\ntemplate<> struct iters_before_test<double> { enum { ret = 16 }; };\n\ntemplate<typename Real> void MandelbrotThread::render(int img_width, int img_height)\n{\n  enum { packetSize = Eigen::internal::packet_traits<Real>::size }; // number of reals in a Packet\n  typedef Eigen::Array<Real, packetSize, 1> Packet; // wrap a Packet as a vector\n\n  enum { iters_before_test = iters_before_test<Real>::ret };\n  max_iter = (max_iter / iters_before_test) * iters_before_test;\n  const int alignedWidth = (img_width/packetSize)*packetSize;\n  unsigned char *const buffer = widget->buffer;\n  const double xradius = widget->xradius;\n  const double yradius = xradius * img_height / img_width;\n  const int threadcount = widget->threadcount;\n  typedef Eigen::Array<Real, 2, 1> Vector2;\n  Vector2 start(widget->center.x() - widget->xradius, widget->center.y() - yradius);\n  Vector2 step(2*widget->xradius/img_width, 2*yradius/img_height);\n  total_iter = 0;\n\n  for(int y = id; y < img_height; y += threadcount)\n  {\n    int pix = y * img_width;\n\n    // for each pixel, we're going to do the iteration z := z^2 + c where z and c are complex numbers, \n    // starting with z = c = complex coord of the pixel. pzi and pzr denote the real and imaginary parts of z.\n    // pci and pcr denote the real and imaginary parts of c.\n\n    Packet pzi_start, pci_start;\n    for(int i = 0; i < packetSize; i++) pzi_start[i] = pci_start[i] = start.y() + y * step.y();\n\n    for(int x = 0; x < alignedWidth; x += packetSize, pix += packetSize)\n    {\n      Packet pcr, pci = pci_start, pzr, pzi = pzi_start, pzr_buf;\n      for(int i = 0; i < packetSize; i++) pzr[i] = pcr[i] = start.x() + (x+i) * step.x();\n\n      // do the iterations. Every iters_before_test iterations we check for divergence,\n      // in which case we can stop iterating.\n      int j = 0;\n      typedef Eigen::Matrix<int, packetSize, 1> Packeti;\n      Packeti pix_iter = Packeti::Zero(), // number of iteration per pixel in the packet\n              pix_dont_diverge; // whether or not each pixel has already diverged\n      do\n      {\n        for(int i = 0; i < iters_before_test/4; i++) // peel the inner loop by 4\n        {\n#         define ITERATE \\\n            pzr_buf = pzr; \\\n            pzr = pzr.square(); \\\n            pzr -= pzi.square(); \\\n            pzr += pcr; \\\n            pzi = (2*pzr_buf)*pzi; \\\n            pzi += pci;\n          ITERATE ITERATE ITERATE ITERATE\n        }\n        pix_dont_diverge = ((pzr.square() + pzi.square())\n                           .eval() // temporary fix as what follows is not yet vectorized by Eigen\n                           <= Packet::Constant(4))\n                                // the 4 here is not a magic value, it's a math fact that if\n                                // the square modulus is >4 then divergence is inevitable.\n                           .template cast<int>();\n        pix_iter += iters_before_test * pix_dont_diverge;\n        j++;\n        total_iter += iters_before_test * packetSize;\n      }\n      while(j < max_iter/iters_before_test && pix_dont_diverge.any()); // any() is not yet vectorized by Eigen\n\n      // compute pixel colors\n      for(int i = 0; i < packetSize; i++)\n      {\n        buffer[4*(pix+i)] = 255*pix_iter[i]/max_iter;\n        buffer[4*(pix+i)+1] = 0;\n        buffer[4*(pix+i)+2] = 0;\n      }\n    }\n\n    // if the width is not a multiple of packetSize, fill the remainder in black\n    for(int x = alignedWidth; x < img_width; x++, pix++)\n      buffer[4*pix] = buffer[4*pix+1] = buffer[4*pix+2] = 0;\n  }\n  return;\n}\n\nvoid MandelbrotThread::run()\n{\n  setTerminationEnabled(true);\n  double resolution = widget->xradius*2/widget->width();\n  max_iter = 128;\n  if(resolution < 1e-4f) max_iter += 128 * ( - 4 - std::log10(resolution));\n  int img_width = widget->width()/widget->draft;\n  int img_height = widget->height()/widget->draft;\n  single_precision = resolution > 1e-7f;\n\n  if(single_precision)\n    render<float>(img_width, img_height);\n  else\n    render<double>(img_width, img_height);\n}\n\nvoid MandelbrotWidget::paintEvent(QPaintEvent *)\n{\n  static float max_speed = 0;\n  long long total_iter = 0;\n\n  QTime time;\n  time.start();\n  for(int th = 0; th < threadcount; th++)\n    threads[th]->start(QThread::LowPriority);\n  for(int th = 0; th < threadcount; th++)\n  {\n    threads[th]->wait();\n    total_iter += threads[th]->total_iter;\n  }\n  int elapsed = time.elapsed();\n\n  if(draft == 1)\n  {\n    float speed = elapsed ? float(total_iter)*1000/elapsed : 0;\n    max_speed = std::max(max_speed, speed);\n    std::cout << threadcount << \" threads, \"\n              << elapsed << \" ms, \"\n              << speed << \" iters/s (max \" << max_speed << \")\" << std::endl;\n    int packetSize = threads[0]->single_precision\n                   ? int(Eigen::internal::packet_traits<float>::size)\n                   : int(Eigen::internal::packet_traits<double>::size);\n    setWindowTitle(QString(\"resolution \")+QString::number(xradius*2/width(), 'e', 2)\n                  +QString(\", %1 iterations per pixel, \").arg(threads[0]->max_iter)\n                  +(threads[0]->single_precision ? QString(\"single \") : QString(\"double \"))\n                  +QString(\"precision, \")\n                  +(packetSize==1 ? QString(\"no vectorization\")\n                                  : QString(\"vectorized (%1 per packet)\").arg(packetSize)));\n  }\n  \n  QImage image(buffer, width()/draft, height()/draft, QImage::Format_RGB32);\n  QPainter painter(this);\n  painter.drawImage(QPoint(0, 0), image.scaled(width(), height()));\n\n  if(draft>1)\n  {\n    draft /= 2;\n    setWindowTitle(QString(\"recomputing at 1/%1 resolution...\").arg(draft));\n    update();\n  }\n}\n\nvoid MandelbrotWidget::mousePressEvent(QMouseEvent *event)\n{\n  if( event->buttons() & Qt::LeftButton )\n  {\n    lastpos = event->pos();\n    double yradius = xradius * height() / width();\n    center = Eigen::Vector2d(center.x() + (event->pos().x() - width()/2) * xradius * 2 / width(),\n                             center.y() + (event->pos().y() - height()/2) * yradius * 2 / height());\n    draft = 16;\n    for(int th = 0; th < threadcount; th++)\n      threads[th]->terminate();\n    update();\n  }\n}\n\nvoid MandelbrotWidget::mouseMoveEvent(QMouseEvent *event)\n{\n  QPoint delta = event->pos() - lastpos;\n  lastpos = event->pos();\n  if( event->buttons() & Qt::LeftButton )\n  {\n    double t = 1 + 5 * double(delta.y()) / height();\n    if(t < 0.5) t = 0.5;\n    if(t > 2) t = 2;\n    xradius *= t;\n    draft = 16;\n    for(int th = 0; th < threadcount; th++)\n      threads[th]->terminate();\n    update();\n  }\n}\n\nint main(int argc, char *argv[])\n{\n  QApplication app(argc, argv);\n  MandelbrotWidget w;\n  w.show();\n  return app.exec();\n}\n\n#include \"mandelbrot.moc\"\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/mandelbrot/mandelbrot.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef MANDELBROT_H\n#define MANDELBROT_H\n\n#include <Eigen/Core>\n#include <QtGui/QApplication>\n#include <QtGui/QWidget>\n#include <QtCore/QThread>\n\nclass MandelbrotWidget;\n\nclass MandelbrotThread : public QThread\n{\n    friend class MandelbrotWidget;\n    MandelbrotWidget *widget;\n    long long total_iter;\n    int id, max_iter;\n    bool single_precision;\n\n  public:\n    MandelbrotThread(MandelbrotWidget *w, int i) : widget(w), id(i) {}\n    void run();\n    template<typename Real> void render(int img_width, int img_height);\n};\n\nclass MandelbrotWidget : public QWidget\n{\n    Q_OBJECT\n\n    friend class MandelbrotThread;\n    Eigen::Vector2d center;\n    double xradius;\n    int size;\n    unsigned char *buffer;\n    QPoint lastpos;\n    int draft;\n    MandelbrotThread **threads;\n    int threadcount;\n\n  protected:\n    void resizeEvent(QResizeEvent *);\n    void paintEvent(QPaintEvent *);\n    void mousePressEvent(QMouseEvent *event);\n    void mouseMoveEvent(QMouseEvent *event);\n\n  public:\n    MandelbrotWidget() : QWidget(), center(0,0), xradius(2),\n                         size(0), buffer(0), draft(16)\n    {\n      setAutoFillBackground(false);\n      threadcount = QThread::idealThreadCount();\n      threads = new MandelbrotThread*[threadcount];\n      for(int th = 0; th < threadcount; th++) threads[th] = new MandelbrotThread(this, th);\n    }\n    ~MandelbrotWidget()\n    {\n      if(buffer) delete[]buffer;\n      for(int th = 0; th < threadcount; th++) delete threads[th];\n      delete[] threads;\n    }\n};\n\n#endif // MANDELBROT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/mix_eigen_and_c/README",
    "content": "This is an example of how one can wrap some of Eigen into a C library.\n\nTo try this with GCC, do:\n\n  g++ -c binary_library.cpp -O2 -msse2 -I ../..\n  gcc example.c binary_library.o -o example -lstdc++\n  ./example\n\nTODO: add CMakeLists, add more explanations here\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/mix_eigen_and_c/binary_library.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// This C++ file compiles to binary code that can be linked to by your C program,\n// thanks to the extern \"C\" syntax used in the declarations in binary_library.h.\n\n#include \"binary_library.h\"\n\n#include <Eigen/Core>\n\nusing namespace Eigen;\n\n/************************* pointer conversion methods **********************************************/\n\n////// class MatrixXd //////\n\ninline MatrixXd& c_to_eigen(C_MatrixXd* ptr)\n{\n  return *reinterpret_cast<MatrixXd*>(ptr);\n}\n\ninline const MatrixXd& c_to_eigen(const C_MatrixXd* ptr)\n{\n  return *reinterpret_cast<const MatrixXd*>(ptr);\n}\n\ninline C_MatrixXd* eigen_to_c(MatrixXd& ref)\n{\n  return reinterpret_cast<C_MatrixXd*>(&ref);\n}\n\ninline const C_MatrixXd* eigen_to_c(const MatrixXd& ref)\n{\n  return reinterpret_cast<const C_MatrixXd*>(&ref);\n}\n\n////// class Map<MatrixXd> //////\n\ninline Map<MatrixXd>& c_to_eigen(C_Map_MatrixXd* ptr)\n{\n  return *reinterpret_cast<Map<MatrixXd>*>(ptr);\n}\n\ninline const Map<MatrixXd>& c_to_eigen(const C_Map_MatrixXd* ptr)\n{\n  return *reinterpret_cast<const Map<MatrixXd>*>(ptr);\n}\n\ninline C_Map_MatrixXd* eigen_to_c(Map<MatrixXd>& ref)\n{\n  return reinterpret_cast<C_Map_MatrixXd*>(&ref);\n}\n\ninline const C_Map_MatrixXd* eigen_to_c(const Map<MatrixXd>& ref)\n{\n  return reinterpret_cast<const C_Map_MatrixXd*>(&ref);\n}\n\n\n/************************* implementation of classes **********************************************/\n\n\n////// class MatrixXd //////\n\n\nC_MatrixXd* MatrixXd_new(int rows, int cols)\n{\n  return eigen_to_c(*new MatrixXd(rows,cols));\n}\n\nvoid MatrixXd_delete(C_MatrixXd *m)\n{\n  delete &c_to_eigen(m);\n}\n\ndouble* MatrixXd_data(C_MatrixXd *m)\n{\n  return c_to_eigen(m).data();\n}\n\nvoid MatrixXd_set_zero(C_MatrixXd *m)\n{\n  c_to_eigen(m).setZero();\n}\n\nvoid MatrixXd_resize(C_MatrixXd *m, int rows, int cols)\n{\n  c_to_eigen(m).resize(rows,cols);\n}\n\nvoid MatrixXd_copy(C_MatrixXd *dst, const C_MatrixXd *src)\n{\n  c_to_eigen(dst) = c_to_eigen(src);\n}\n\nvoid MatrixXd_copy_map(C_MatrixXd *dst, const C_Map_MatrixXd *src)\n{\n  c_to_eigen(dst) = c_to_eigen(src);\n}\n\nvoid MatrixXd_set_coeff(C_MatrixXd *m, int i, int j, double coeff)\n{\n  c_to_eigen(m)(i,j) = coeff;\n}\n\ndouble MatrixXd_get_coeff(const C_MatrixXd *m, int i, int j)\n{\n  return c_to_eigen(m)(i,j);\n}\n\nvoid MatrixXd_print(const C_MatrixXd *m)\n{\n  std::cout << c_to_eigen(m) << std::endl;\n}\n\nvoid MatrixXd_multiply(const C_MatrixXd *m1, const C_MatrixXd *m2, C_MatrixXd *result)\n{\n  c_to_eigen(result) = c_to_eigen(m1) * c_to_eigen(m2);\n}\n\nvoid MatrixXd_add(const C_MatrixXd *m1, const C_MatrixXd *m2, C_MatrixXd *result)\n{\n  c_to_eigen(result) = c_to_eigen(m1) + c_to_eigen(m2);\n}\n\n\n\n////// class Map_MatrixXd //////\n\n\nC_Map_MatrixXd* Map_MatrixXd_new(double *array, int rows, int cols)\n{\n  return eigen_to_c(*new Map<MatrixXd>(array,rows,cols));\n}\n\nvoid Map_MatrixXd_delete(C_Map_MatrixXd *m)\n{\n  delete &c_to_eigen(m);\n}\n\nvoid Map_MatrixXd_set_zero(C_Map_MatrixXd *m)\n{\n  c_to_eigen(m).setZero();\n}\n\nvoid Map_MatrixXd_copy(C_Map_MatrixXd *dst, const C_Map_MatrixXd *src)\n{\n  c_to_eigen(dst) = c_to_eigen(src);\n}\n\nvoid Map_MatrixXd_copy_matrix(C_Map_MatrixXd *dst, const C_MatrixXd *src)\n{\n  c_to_eigen(dst) = c_to_eigen(src);\n}\n\nvoid Map_MatrixXd_set_coeff(C_Map_MatrixXd *m, int i, int j, double coeff)\n{\n  c_to_eigen(m)(i,j) = coeff;\n}\n\ndouble Map_MatrixXd_get_coeff(const C_Map_MatrixXd *m, int i, int j)\n{\n  return c_to_eigen(m)(i,j);\n}\n\nvoid Map_MatrixXd_print(const C_Map_MatrixXd *m)\n{\n  std::cout << c_to_eigen(m) << std::endl;\n}\n\nvoid Map_MatrixXd_multiply(const C_Map_MatrixXd *m1, const C_Map_MatrixXd *m2, C_Map_MatrixXd *result)\n{\n  c_to_eigen(result) = c_to_eigen(m1) * c_to_eigen(m2);\n}\n\nvoid Map_MatrixXd_add(const C_Map_MatrixXd *m1, const C_Map_MatrixXd *m2, C_Map_MatrixXd *result)\n{\n  c_to_eigen(result) = c_to_eigen(m1) + c_to_eigen(m2);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/mix_eigen_and_c/binary_library.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// This is a pure C header, no C++ here.\n// The functions declared here will be implemented in C++ but\n// we don't have to know, because thanks to the extern \"C\" syntax,\n// they will be compiled to C object code.\n\n#ifdef __cplusplus\nextern \"C\"\n{\n#endif\n\n  // just dummy empty structs to give different pointer types,\n  // instead of using void* which would be type unsafe\n  struct C_MatrixXd {};\n  struct C_Map_MatrixXd {};\n\n  // the C_MatrixXd class, wraps some of the functionality\n  // of Eigen::MatrixXd.\n  struct C_MatrixXd* MatrixXd_new(int rows, int cols);\n  void    MatrixXd_delete     (struct C_MatrixXd *m);\n  double* MatrixXd_data       (struct C_MatrixXd *m);\n  void    MatrixXd_set_zero   (struct C_MatrixXd *m);\n  void    MatrixXd_resize     (struct C_MatrixXd *m, int rows, int cols);\n  void    MatrixXd_copy       (struct C_MatrixXd *dst,\n                               const struct C_MatrixXd *src);\n  void    MatrixXd_copy_map   (struct C_MatrixXd *dst,\n                               const struct C_Map_MatrixXd *src);  \n  void    MatrixXd_set_coeff  (struct C_MatrixXd *m,\n                               int i, int j, double coeff);\n  double  MatrixXd_get_coeff  (const struct C_MatrixXd *m,\n                               int i, int j);\n  void    MatrixXd_print      (const struct C_MatrixXd *m);\n  void    MatrixXd_add        (const struct C_MatrixXd *m1,\n                               const struct C_MatrixXd *m2,\n                               struct C_MatrixXd *result);  \n  void    MatrixXd_multiply   (const struct C_MatrixXd *m1,\n                               const struct C_MatrixXd *m2,\n                               struct C_MatrixXd *result);\n  \n  // the C_Map_MatrixXd class, wraps some of the functionality\n  // of Eigen::Map<MatrixXd>\n  struct C_Map_MatrixXd* Map_MatrixXd_new(double *array, int rows, int cols);\n  void   Map_MatrixXd_delete     (struct C_Map_MatrixXd *m);\n  void   Map_MatrixXd_set_zero   (struct C_Map_MatrixXd *m);\n  void   Map_MatrixXd_copy       (struct C_Map_MatrixXd *dst,\n                                  const struct C_Map_MatrixXd *src);\n  void   Map_MatrixXd_copy_matrix(struct C_Map_MatrixXd *dst,\n                                  const struct C_MatrixXd *src);  \n  void   Map_MatrixXd_set_coeff  (struct C_Map_MatrixXd *m,\n                                  int i, int j, double coeff);\n  double Map_MatrixXd_get_coeff  (const struct C_Map_MatrixXd *m,\n                                  int i, int j);\n  void   Map_MatrixXd_print      (const struct C_Map_MatrixXd *m);\n  void   Map_MatrixXd_add        (const struct C_Map_MatrixXd *m1,\n                                  const struct C_Map_MatrixXd *m2,\n                                  struct C_Map_MatrixXd *result);  \n  void   Map_MatrixXd_multiply   (const struct C_Map_MatrixXd *m1,\n                                  const struct C_Map_MatrixXd *m2,\n                                  struct C_Map_MatrixXd *result);\n\n#ifdef __cplusplus\n} // end extern \"C\"\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/mix_eigen_and_c/example.c",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"binary_library.h\"\n#include \"stdio.h\"\n\nvoid demo_MatrixXd()\n{\n  struct C_MatrixXd *matrix1, *matrix2, *result;\n  printf(\"*** demo_MatrixXd ***\\n\");\n  \n  matrix1 = MatrixXd_new(3, 3);\n  MatrixXd_set_zero(matrix1);\n  MatrixXd_set_coeff(matrix1, 0, 1, 2.5);\n  MatrixXd_set_coeff(matrix1, 1, 0, 1.4);\n  printf(\"Here is matrix1:\\n\");\n  MatrixXd_print(matrix1);\n\n  matrix2 = MatrixXd_new(3, 3);\n  MatrixXd_multiply(matrix1, matrix1, matrix2);\n  printf(\"Here is matrix1*matrix1:\\n\");\n  MatrixXd_print(matrix2);\n\n  MatrixXd_delete(matrix1);\n  MatrixXd_delete(matrix2);\n}\n\n// this helper function takes a plain C array and prints it in one line\nvoid print_array(double *array, int n)\n{\n  struct C_Map_MatrixXd *m = Map_MatrixXd_new(array, 1, n);\n  Map_MatrixXd_print(m);\n  Map_MatrixXd_delete(m);\n}\n\nvoid demo_Map_MatrixXd()\n{\n  struct C_Map_MatrixXd *map;\n  double array[5];\n  int i;\n  printf(\"*** demo_Map_MatrixXd ***\\n\");\n  \n  for(i = 0; i < 5; ++i) array[i] = i;\n  printf(\"Initially, the array is:\\n\");\n  print_array(array, 5);\n  \n  map = Map_MatrixXd_new(array, 5, 1);\n  Map_MatrixXd_add(map, map, map);\n  Map_MatrixXd_delete(map);\n\n  printf(\"Now the array is:\\n\");\n  print_array(array, 5);\n}\n\nint main()\n{\n  demo_MatrixXd();\n  demo_Map_MatrixXd();\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/opengl/CMakeLists.txt",
    "content": "find_package(Qt4)\nfind_package(OpenGL)\n\nif(QT4_FOUND AND OPENGL_FOUND)\n\n  set(QT_USE_QTOPENGL TRUE)\n  include(${QT_USE_FILE})\n\n  set(CMAKE_INCLUDE_CURRENT_DIR ON)\n\n  include_directories( ${QT_INCLUDE_DIR} )\n\n  set(quaternion_demo_SRCS  gpuhelper.cpp icosphere.cpp camera.cpp trackball.cpp quaternion_demo.cpp)\n\n  qt4_automoc(${quaternion_demo_SRCS})\n\n  add_executable(quaternion_demo ${quaternion_demo_SRCS})\n  add_dependencies(demos quaternion_demo)\n\n  target_link_libraries(quaternion_demo\n    ${QT_QTCORE_LIBRARY}    ${QT_QTGUI_LIBRARY}\n    ${QT_QTOPENGL_LIBRARY}  ${OPENGL_LIBRARIES} )\n\nelse()\n\n  message(STATUS \"OpenGL demo disabled because Qt4 and/or OpenGL have not been found.\")\n\nendif()"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/opengl/README",
    "content": "\nNavigation:\n left button:           rotate around the target\n middle button:         zoom\n left button + ctrl     quake rotate (rotate around camera position)\n middle button + ctrl   walk (progress along camera's z direction)\n left button:           pan (translate in the XY camera's plane)\n\nR : move the camera to initial position\nA : start/stop animation\nC : clear the animation\nG : add a key frame\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/opengl/camera.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"camera.h\"\n\n#include \"gpuhelper.h\"\n#include <GL/glu.h>\n\n#include \"Eigen/LU\"\nusing namespace Eigen;\n\nCamera::Camera()\n    : mViewIsUptodate(false), mProjIsUptodate(false)\n{\n    mViewMatrix.setIdentity();\n    \n    mFovY = M_PI/3.;\n    mNearDist = 1.;\n    mFarDist = 50000.;\n    \n    mVpX = 0;\n    mVpY = 0;\n\n    setPosition(Vector3f::Constant(100.));\n    setTarget(Vector3f::Zero());\n}\n\nCamera& Camera::operator=(const Camera& other)\n{\n    mViewIsUptodate = false;\n    mProjIsUptodate = false;\n    \n    mVpX = other.mVpX;\n    mVpY = other.mVpY;\n    mVpWidth = other.mVpWidth;\n    mVpHeight = other.mVpHeight;\n\n    mTarget = other.mTarget;\n    mFovY = other.mFovY;\n    mNearDist = other.mNearDist;\n    mFarDist = other.mFarDist;\n    \n    mViewMatrix = other.mViewMatrix;\n    mProjectionMatrix = other.mProjectionMatrix;\n\n    return *this;\n}\n\nCamera::Camera(const Camera& other)\n{\n    *this = other;\n}\n\nCamera::~Camera()\n{\n}\n\n\nvoid Camera::setViewport(uint offsetx, uint offsety, uint width, uint height)\n{\n    mVpX = offsetx;\n    mVpY = offsety;\n    mVpWidth = width;\n    mVpHeight = height;\n    \n    mProjIsUptodate = false;\n}\n\nvoid Camera::setViewport(uint width, uint height)\n{\n    mVpWidth = width;\n    mVpHeight = height;\n    \n    mProjIsUptodate = false;\n}\n\nvoid Camera::setFovY(float value)\n{\n    mFovY = value;\n    mProjIsUptodate = false;\n}\n\nVector3f Camera::direction(void) const\n{\n    return - (orientation() * Vector3f::UnitZ());\n}\nVector3f Camera::up(void) const\n{\n    return orientation() * Vector3f::UnitY();\n}\nVector3f Camera::right(void) const\n{\n    return orientation() * Vector3f::UnitX();\n}\n\nvoid Camera::setDirection(const Vector3f& newDirection)\n{\n    // TODO implement it computing the rotation between newDirection and current dir ?\n    Vector3f up = this->up();\n    \n    Matrix3f camAxes;\n\n    camAxes.col(2) = (-newDirection).normalized();\n    camAxes.col(0) = up.cross( camAxes.col(2) ).normalized();\n    camAxes.col(1) = camAxes.col(2).cross( camAxes.col(0) ).normalized();\n    setOrientation(Quaternionf(camAxes));\n    \n    mViewIsUptodate = false;\n}\n\nvoid Camera::setTarget(const Vector3f& target)\n{\n    mTarget = target;\n    if (!mTarget.isApprox(position()))\n    {\n        Vector3f newDirection = mTarget - position();\n        setDirection(newDirection.normalized());\n    }\n}\n\nvoid Camera::setPosition(const Vector3f& p)\n{\n    mFrame.position = p;\n    mViewIsUptodate = false;\n}\n\nvoid Camera::setOrientation(const Quaternionf& q)\n{\n    mFrame.orientation = q;\n    mViewIsUptodate = false;\n}\n\nvoid Camera::setFrame(const Frame& f)\n{\n  mFrame = f;\n  mViewIsUptodate = false;\n}\n\nvoid Camera::rotateAroundTarget(const Quaternionf& q)\n{\n    Matrix4f mrot, mt, mtm;\n    \n    // update the transform matrix\n    updateViewMatrix();\n    Vector3f t = mViewMatrix * mTarget;\n\n    mViewMatrix = Translation3f(t)\n                * q\n                * Translation3f(-t)\n                * mViewMatrix;\n    \n    Quaternionf qa(mViewMatrix.linear());\n    qa = qa.conjugate();\n    setOrientation(qa);\n    setPosition(- (qa * mViewMatrix.translation()) );\n\n    mViewIsUptodate = true;\n}\n\nvoid Camera::localRotate(const Quaternionf& q)\n{\n    float dist = (position() - mTarget).norm();\n    setOrientation(orientation() * q);\n    mTarget = position() + dist * direction();\n    mViewIsUptodate = false;\n}\n\nvoid Camera::zoom(float d)\n{\n    float dist = (position() - mTarget).norm();\n    if(dist > d)\n    {\n        setPosition(position() + direction() * d);\n        mViewIsUptodate = false;\n    }\n}\n\nvoid Camera::localTranslate(const Vector3f& t)\n{\n  Vector3f trans = orientation() * t;\n  setPosition( position() + trans );\n  setTarget( mTarget + trans );\n\n  mViewIsUptodate = false;\n}\n\nvoid Camera::updateViewMatrix(void) const\n{\n    if(!mViewIsUptodate)\n    {\n        Quaternionf q = orientation().conjugate();\n        mViewMatrix.linear() = q.toRotationMatrix();\n        mViewMatrix.translation() = - (mViewMatrix.linear() * position());\n\n        mViewIsUptodate = true;\n    }\n}\n\nconst Affine3f& Camera::viewMatrix(void) const\n{\n  updateViewMatrix();\n  return mViewMatrix;\n}\n\nvoid Camera::updateProjectionMatrix(void) const\n{\n  if(!mProjIsUptodate)\n  {\n    mProjectionMatrix.setIdentity();\n    float aspect = float(mVpWidth)/float(mVpHeight);\n    float theta = mFovY*0.5;\n    float range = mFarDist - mNearDist;\n    float invtan = 1./tan(theta);\n\n    mProjectionMatrix(0,0) = invtan / aspect;\n    mProjectionMatrix(1,1) = invtan;\n    mProjectionMatrix(2,2) = -(mNearDist + mFarDist) / range;\n    mProjectionMatrix(3,2) = -1;\n    mProjectionMatrix(2,3) = -2 * mNearDist * mFarDist / range;\n    mProjectionMatrix(3,3) = 0;\n    \n    mProjIsUptodate = true;\n  }\n}\n\nconst Matrix4f& Camera::projectionMatrix(void) const\n{\n  updateProjectionMatrix();\n  return mProjectionMatrix;\n}\n\nvoid Camera::activateGL(void)\n{\n  glViewport(vpX(), vpY(), vpWidth(), vpHeight());\n  gpu.loadMatrix(projectionMatrix(),GL_PROJECTION);\n  gpu.loadMatrix(viewMatrix().matrix(),GL_MODELVIEW);\n}\n\n\nVector3f Camera::unProject(const Vector2f& uv, float depth) const\n{\n    Matrix4f inv = mViewMatrix.inverse().matrix();\n    return unProject(uv, depth, inv);\n}\n\nVector3f Camera::unProject(const Vector2f& uv, float depth, const Matrix4f& invModelview) const\n{\n    updateViewMatrix();\n    updateProjectionMatrix();\n    \n    Vector3f a(2.*uv.x()/float(mVpWidth)-1., 2.*uv.y()/float(mVpHeight)-1., 1.);\n    a.x() *= depth/mProjectionMatrix(0,0);\n    a.y() *= depth/mProjectionMatrix(1,1);\n    a.z() = -depth;\n    // FIXME /\\/|\n    Vector4f b = invModelview * Vector4f(a.x(), a.y(), a.z(), 1.);\n    return Vector3f(b.x(), b.y(), b.z());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/opengl/camera.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CAMERA_H\n#define EIGEN_CAMERA_H\n\n#include <Eigen/Geometry>\n#include <QObject>\n// #include <frame.h>\n\nclass Frame\n{\n  public:\n    EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n    \n    inline Frame(const Eigen::Vector3f& pos = Eigen::Vector3f::Zero(),\n                 const Eigen::Quaternionf& o = Eigen::Quaternionf())\n      : orientation(o), position(pos)\n    {}\n    Frame lerp(float alpha, const Frame& other) const\n    {\n      return Frame((1.f-alpha)*position + alpha * other.position,\n                   orientation.slerp(alpha,other.orientation));\n    }\n\n    Eigen::Quaternionf orientation;\n    Eigen::Vector3f position;\n};\n\nclass Camera\n{\n  public:\n    EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n\n    Camera(void);\n    \n    Camera(const Camera& other);\n    \n    virtual ~Camera();\n    \n    Camera& operator=(const Camera& other);\n    \n    void setViewport(uint offsetx, uint offsety, uint width, uint height);\n    void setViewport(uint width, uint height);\n    \n    inline uint vpX(void) const { return mVpX; }\n    inline uint vpY(void) const { return mVpY; }\n    inline uint vpWidth(void) const { return mVpWidth; }\n    inline uint vpHeight(void) const { return mVpHeight; }\n\n    inline float fovY(void) const { return mFovY; }\n    void setFovY(float value);\n    \n    void setPosition(const Eigen::Vector3f& pos);\n    inline const Eigen::Vector3f& position(void) const { return mFrame.position; }\n\n    void setOrientation(const Eigen::Quaternionf& q);\n    inline const Eigen::Quaternionf& orientation(void) const { return mFrame.orientation; }\n\n    void setFrame(const Frame& f);\n    const Frame& frame(void) const { return mFrame; }\n    \n    void setDirection(const Eigen::Vector3f& newDirection);\n    Eigen::Vector3f direction(void) const;\n    void setUp(const Eigen::Vector3f& vectorUp);\n    Eigen::Vector3f up(void) const;\n    Eigen::Vector3f right(void) const;\n    \n    void setTarget(const Eigen::Vector3f& target);\n    inline const Eigen::Vector3f& target(void) { return mTarget; }\n    \n    const Eigen::Affine3f& viewMatrix(void) const;\n    const Eigen::Matrix4f& projectionMatrix(void) const;\n    \n    void rotateAroundTarget(const Eigen::Quaternionf& q);\n    void localRotate(const Eigen::Quaternionf& q);\n    void zoom(float d);\n    \n    void localTranslate(const Eigen::Vector3f& t);\n    \n    /** Setup OpenGL matrices and viewport */\n    void activateGL(void);\n    \n    Eigen::Vector3f unProject(const Eigen::Vector2f& uv, float depth, const Eigen::Matrix4f& invModelview) const;\n    Eigen::Vector3f unProject(const Eigen::Vector2f& uv, float depth) const;\n    \n  protected:\n    void updateViewMatrix(void) const;\n    void updateProjectionMatrix(void) const;\n\n  protected:\n\n    uint mVpX, mVpY;\n    uint mVpWidth, mVpHeight;\n\n    Frame mFrame;\n    \n    mutable Eigen::Affine3f mViewMatrix;\n    mutable Eigen::Matrix4f mProjectionMatrix;\n\n    mutable bool mViewIsUptodate;\n    mutable bool mProjIsUptodate;\n\n    // used by rotateAroundTarget\n    Eigen::Vector3f mTarget;\n    \n    float mFovY;\n    float mNearDist;\n    float mFarDist;\n};\n\n#endif // EIGEN_CAMERA_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/opengl/gpuhelper.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"gpuhelper.h\"\n#include \"icosphere.h\"\n#include <GL/glu.h>\n// PLEASE don't look at this old code... ;)\n\n#include <fstream>\n#include <algorithm>\n\nGpuHelper gpu;\n\nGpuHelper::GpuHelper()\n{\n    mVpWidth = mVpHeight = 0;\n    mCurrentMatrixTarget = 0;\n    mInitialized = false;\n}\n\nGpuHelper::~GpuHelper()\n{\n}\n\nvoid GpuHelper::pushProjectionMode2D(ProjectionMode2D pm)\n{\n    // switch to 2D projection\n    pushMatrix(Matrix4f::Identity(),GL_PROJECTION);\n\n    if(pm==PM_Normalized)\n    {\n        //glOrtho(-1., 1., -1., 1., 0., 1.);\n    }\n    else if(pm==PM_Viewport)\n    {\n        GLint vp[4];\n        glGetIntegerv(GL_VIEWPORT, vp);\n        glOrtho(0., vp[2], 0., vp[3], -1., 1.);\n    }\n\n    pushMatrix(Matrix4f::Identity(),GL_MODELVIEW);\n}\n\nvoid GpuHelper::popProjectionMode2D(void)\n{\n    popMatrix(GL_PROJECTION);\n    popMatrix(GL_MODELVIEW);\n}\n\nvoid GpuHelper::drawVector(const Vector3f& position, const Vector3f& vec, const Color& color, float aspect /* = 50.*/)\n{\n    static GLUquadricObj *cylindre = gluNewQuadric();\n    glColor4fv(color.data());\n    float length = vec.norm();\n    pushMatrix(GL_MODELVIEW);\n    glTranslatef(position.x(), position.y(), position.z());\n    Vector3f ax = Matrix3f::Identity().col(2).cross(vec);\n    ax.normalize();\n    Vector3f tmp = vec;\n    tmp.normalize();\n    float angle = 180.f/M_PI * acos(tmp.z());\n    if (angle>1e-3)\n        glRotatef(angle, ax.x(), ax.y(), ax.z());\n    gluCylinder(cylindre, length/aspect, length/aspect, 0.8*length, 10, 10);\n    glTranslatef(0.0,0.0,0.8*length);\n    gluCylinder(cylindre, 2.0*length/aspect, 0.0, 0.2*length, 10, 10);\n\n    popMatrix(GL_MODELVIEW);\n}\n\nvoid GpuHelper::drawVectorBox(const Vector3f& position, const Vector3f& vec, const Color& color, float aspect)\n{\n    static GLUquadricObj *cylindre = gluNewQuadric();\n    glColor4fv(color.data());\n    float length = vec.norm();\n    pushMatrix(GL_MODELVIEW);\n    glTranslatef(position.x(), position.y(), position.z());\n    Vector3f ax = Matrix3f::Identity().col(2).cross(vec);\n    ax.normalize();\n    Vector3f tmp = vec;\n    tmp.normalize();\n    float angle = 180.f/M_PI * acos(tmp.z());\n    if (angle>1e-3)\n        glRotatef(angle, ax.x(), ax.y(), ax.z());\n    gluCylinder(cylindre, length/aspect, length/aspect, 0.8*length, 10, 10);\n    glTranslatef(0.0,0.0,0.8*length);\n    glScalef(4.0*length/aspect,4.0*length/aspect,4.0*length/aspect);\n    drawUnitCube();\n    popMatrix(GL_MODELVIEW);\n}\n\nvoid GpuHelper::drawUnitCube(void)\n{\n    static float vertices[][3] = {\n        {-0.5,-0.5,-0.5},\n        { 0.5,-0.5,-0.5},\n        {-0.5, 0.5,-0.5},\n        { 0.5, 0.5,-0.5},\n        {-0.5,-0.5, 0.5},\n        { 0.5,-0.5, 0.5},\n        {-0.5, 0.5, 0.5},\n        { 0.5, 0.5, 0.5}};\n\n    glBegin(GL_QUADS);\n    glNormal3f(0,0,-1); glVertex3fv(vertices[0]); glVertex3fv(vertices[2]); glVertex3fv(vertices[3]); glVertex3fv(vertices[1]);\n    glNormal3f(0,0, 1); glVertex3fv(vertices[4]); glVertex3fv(vertices[5]); glVertex3fv(vertices[7]); glVertex3fv(vertices[6]);\n    glNormal3f(0,-1,0); glVertex3fv(vertices[0]); glVertex3fv(vertices[1]); glVertex3fv(vertices[5]); glVertex3fv(vertices[4]);\n    glNormal3f(0, 1,0); glVertex3fv(vertices[2]); glVertex3fv(vertices[6]); glVertex3fv(vertices[7]); glVertex3fv(vertices[3]);\n    glNormal3f(-1,0,0); glVertex3fv(vertices[0]); glVertex3fv(vertices[4]); glVertex3fv(vertices[6]); glVertex3fv(vertices[2]);\n    glNormal3f( 1,0,0); glVertex3fv(vertices[1]); glVertex3fv(vertices[3]); glVertex3fv(vertices[7]); glVertex3fv(vertices[5]);\n    glEnd();\n}\n\nvoid GpuHelper::drawUnitSphere(int level)\n{\n  static IcoSphere sphere;\n  sphere.draw(level);\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/opengl/gpuhelper.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_GPUHELPER_H\n#define EIGEN_GPUHELPER_H\n\n#include <Eigen/Geometry>\n#include <GL/gl.h>\n#include <vector>\n\nusing namespace Eigen;\n\ntypedef Vector4f Color;\n\nclass GpuHelper\n{\n  public:\n\n    GpuHelper();\n\n    ~GpuHelper();\n\n    enum ProjectionMode2D { PM_Normalized = 1, PM_Viewport = 2 };\n    void pushProjectionMode2D(ProjectionMode2D pm);\n    void popProjectionMode2D();\n\n    /** Multiply the OpenGL matrix \\a matrixTarget by the matrix \\a mat.\n        Essentially, this helper function automatically calls glMatrixMode(matrixTarget) if required\n        and does a proper call to the right glMultMatrix*() function according to the scalar type\n        and storage order.\n        \\warning glMatrixMode() must never be called directly. If you are unsure, use forceMatrixMode().\n        \\sa Matrix, loadMatrix(), forceMatrixMode()\n    */\n    template<typename Scalar, int Flags_>\n    void multMatrix(const Matrix<Scalar,4,4, Flags_, 4,4>& mat, GLenum matrixTarget);\n\n    /** Load the matrix \\a mat to the OpenGL matrix \\a matrixTarget.\n        Essentially, this helper function automatically calls glMatrixMode(matrixTarget) if required\n        and does a proper call to the right glLoadMatrix*() or glLoadIdentity() function according to the scalar type\n        and storage order.\n        \\warning glMatrixMode() must never be called directly. If you are unsure, use forceMatrixMode().\n        \\sa Matrix, multMatrix(), forceMatrixMode()\n    */\n    template<typename Scalar, int Flags_>\n    void loadMatrix(const Eigen::Matrix<Scalar,4,4, Flags_, 4,4>& mat, GLenum matrixTarget);\n\n    template<typename Scalar, typename Derived>\n    void loadMatrix(\n        const Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<Scalar>,Derived>&,\n        GLenum matrixTarget);\n\n    /** Make the matrix \\a matrixTarget the current OpenGL matrix target.\n        Call this function before loadMatrix() or multMatrix() if you cannot guarantee that glMatrixMode()\n        has never been called after the last loadMatrix() or multMatrix() calls.\n        \\todo provides a debug mode checking the sanity of the cached matrix mode.\n    */\n    inline void forceMatrixTarget(GLenum matrixTarget) {glMatrixMode(mCurrentMatrixTarget=matrixTarget);}\n\n    inline void setMatrixTarget(GLenum matrixTarget);\n\n    /** Push the OpenGL matrix \\a matrixTarget and load \\a mat.\n    */\n    template<typename Scalar, int Flags_>\n    inline void pushMatrix(const Matrix<Scalar,4,4, Flags_, 4,4>& mat, GLenum matrixTarget);\n\n    template<typename Scalar, typename Derived>\n    void pushMatrix(\n        const Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<Scalar>,Derived>&,\n        GLenum matrixTarget);\n\n    /** Push and clone the OpenGL matrix \\a matrixTarget\n    */\n    inline void pushMatrix(GLenum matrixTarget);\n\n    /** Pop the OpenGL matrix \\a matrixTarget\n    */\n    inline void popMatrix(GLenum matrixTarget);\n\n    void drawVector(const Vector3f& position, const Vector3f& vec, const Color& color, float aspect = 50.);\n    void drawVectorBox(const Vector3f& position, const Vector3f& vec, const Color& color, float aspect = 50.);\n    void drawUnitCube(void);\n    void drawUnitSphere(int level=0);\n\n    /// draw the \\a nofElement first elements\n    inline void draw(GLenum mode, uint nofElement);\n\n    /// draw a range of elements\n    inline void draw(GLenum mode, uint start, uint end);\n\n    /// draw an indexed subset\n    inline void draw(GLenum mode, const std::vector<uint>* pIndexes);\n\nprotected:\n\n    void update(void);\n\n    GLuint mColorBufferId;\n    int mVpWidth, mVpHeight;\n    GLenum mCurrentMatrixTarget;\n    bool mInitialized;\n};\n\n/** Singleton shortcut\n*/\nextern GpuHelper gpu;\n\n\n/** \\internal\n*/\ntemplate<bool RowMajor, int Flags_> struct GlMatrixHelper;\n\ntemplate<int Flags_> struct GlMatrixHelper<false,Flags_>\n{\n    static void loadMatrix(const Matrix<float, 4,4, Flags_, 4,4>&  mat) { glLoadMatrixf(mat.data()); }\n    static void loadMatrix(const Matrix<double,4,4, Flags_, 4,4>& mat) { glLoadMatrixd(mat.data()); }\n    static void multMatrix(const Matrix<float, 4,4, Flags_, 4,4>&  mat) { glMultMatrixf(mat.data()); }\n    static void multMatrix(const Matrix<double,4,4, Flags_, 4,4>& mat) { glMultMatrixd(mat.data()); }\n};\n\ntemplate<int Flags_> struct GlMatrixHelper<true,Flags_>\n{\n    static void loadMatrix(const Matrix<float, 4,4, Flags_, 4,4>&  mat) { glLoadMatrixf(mat.transpose().eval().data()); }\n    static void loadMatrix(const Matrix<double,4,4, Flags_, 4,4>& mat) { glLoadMatrixd(mat.transpose().eval().data()); }\n    static void multMatrix(const Matrix<float, 4,4, Flags_, 4,4>&  mat) { glMultMatrixf(mat.transpose().eval().data()); }\n    static void multMatrix(const Matrix<double,4,4, Flags_, 4,4>& mat) { glMultMatrixd(mat.transpose().eval().data()); }\n};\n\ninline void GpuHelper::setMatrixTarget(GLenum matrixTarget)\n{\n    if (matrixTarget != mCurrentMatrixTarget)\n        glMatrixMode(mCurrentMatrixTarget=matrixTarget);\n}\n\ntemplate<typename Scalar, int Flags_>\nvoid GpuHelper::multMatrix(const Matrix<Scalar,4,4, Flags_, 4,4>& mat, GLenum matrixTarget)\n{\n    setMatrixTarget(matrixTarget);\n    GlMatrixHelper<Flags_&Eigen::RowMajorBit, Flags_>::multMatrix(mat);\n}\n\ntemplate<typename Scalar, typename Derived>\nvoid GpuHelper::loadMatrix(\n    const Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<Scalar>,Derived>&,\n    GLenum matrixTarget)\n{\n    setMatrixTarget(matrixTarget);\n    glLoadIdentity();\n}\n\ntemplate<typename Scalar, int Flags_>\nvoid GpuHelper::loadMatrix(const Eigen::Matrix<Scalar,4,4, Flags_, 4,4>& mat, GLenum matrixTarget)\n{\n    setMatrixTarget(matrixTarget);\n    GlMatrixHelper<(Flags_&Eigen::RowMajorBit)!=0, Flags_>::loadMatrix(mat);\n}\n\ninline void GpuHelper::pushMatrix(GLenum matrixTarget)\n{\n    setMatrixTarget(matrixTarget);\n    glPushMatrix();\n}\n\ntemplate<typename Scalar, int Flags_>\ninline void GpuHelper::pushMatrix(const Matrix<Scalar,4,4, Flags_, 4,4>& mat, GLenum matrixTarget)\n{\n    pushMatrix(matrixTarget);\n    GlMatrixHelper<Flags_&Eigen::RowMajorBit,Flags_>::loadMatrix(mat);\n}\n\ntemplate<typename Scalar, typename Derived>\nvoid GpuHelper::pushMatrix(\n    const Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<Scalar>,Derived>&,\n    GLenum matrixTarget)\n{\n    pushMatrix(matrixTarget);\n    glLoadIdentity();\n}\n\ninline void GpuHelper::popMatrix(GLenum matrixTarget)\n{\n    setMatrixTarget(matrixTarget);\n    glPopMatrix();\n}\n\ninline void GpuHelper::draw(GLenum mode, uint nofElement)\n{\n    glDrawArrays(mode, 0, nofElement);\n}\n\n\ninline void GpuHelper::draw(GLenum mode, const std::vector<uint>* pIndexes)\n{\n    glDrawElements(mode, pIndexes->size(), GL_UNSIGNED_INT, &(pIndexes->front()));\n}\n\ninline void GpuHelper::draw(GLenum mode, uint start, uint end)\n{\n    glDrawArrays(mode, start, end-start);\n}\n\n#endif // EIGEN_GPUHELPER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/opengl/icosphere.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"icosphere.h\"\n\n#include <GL/gl.h>\n#include <map>\n\nusing namespace Eigen;\n\n//--------------------------------------------------------------------------------\n// icosahedron data\n//--------------------------------------------------------------------------------\n#define X .525731112119133606\n#define Z .850650808352039932\n\nstatic GLfloat vdata[12][3] = {\n   {-X, 0.0, Z}, {X, 0.0, Z}, {-X, 0.0, -Z}, {X, 0.0, -Z},\n   {0.0, Z, X}, {0.0, Z, -X}, {0.0, -Z, X}, {0.0, -Z, -X},\n   {Z, X, 0.0}, {-Z, X, 0.0}, {Z, -X, 0.0}, {-Z, -X, 0.0}\n};\n\nstatic GLint tindices[20][3] = {\n   {0,4,1}, {0,9,4}, {9,5,4}, {4,5,8}, {4,8,1},\n   {8,10,1}, {8,3,10}, {5,3,8}, {5,2,3}, {2,7,3},\n   {7,10,3}, {7,6,10}, {7,11,6}, {11,0,6}, {0,1,6},\n   {6,1,10}, {9,0,11}, {9,11,2}, {9,2,5}, {7,2,11} };\n//--------------------------------------------------------------------------------\n\nIcoSphere::IcoSphere(unsigned int levels)\n{\n  // init with an icosahedron\n  for (int i = 0; i < 12; i++)\n    mVertices.push_back(Map<Vector3f>(vdata[i]));\n  mIndices.push_back(new std::vector<int>);\n  std::vector<int>& indices = *mIndices.back();\n  for (int i = 0; i < 20; i++)\n  {\n    for (int k = 0; k < 3; k++)\n      indices.push_back(tindices[i][k]);\n  }\n  mListIds.push_back(0);\n\n  while(mIndices.size()<levels)\n    _subdivide();\n}\n\nconst std::vector<int>& IcoSphere::indices(int level) const\n{\n  while (level>=int(mIndices.size()))\n    const_cast<IcoSphere*>(this)->_subdivide();\n  return *mIndices[level];\n}\n\nvoid IcoSphere::_subdivide(void)\n{\n  typedef unsigned long long Key;\n  std::map<Key,int> edgeMap;\n  const std::vector<int>& indices = *mIndices.back();\n  mIndices.push_back(new std::vector<int>);\n  std::vector<int>& refinedIndices = *mIndices.back();\n  int end = indices.size();\n  for (int i=0; i<end; i+=3)\n  {\n    int ids0[3],  // indices of outer vertices\n        ids1[3];  // indices of edge vertices\n    for (int k=0; k<3; ++k)\n    {\n      int k1 = (k+1)%3;\n      int e0 = indices[i+k];\n      int e1 = indices[i+k1];\n      ids0[k] = e0;\n      if (e1>e0)\n        std::swap(e0,e1);\n      Key edgeKey = Key(e0) | (Key(e1)<<32);\n      std::map<Key,int>::iterator it = edgeMap.find(edgeKey);\n      if (it==edgeMap.end())\n      {\n        ids1[k] = mVertices.size();\n        edgeMap[edgeKey] = ids1[k];\n        mVertices.push_back( (mVertices[e0]+mVertices[e1]).normalized() );\n      }\n      else\n        ids1[k] = it->second;\n    }\n    refinedIndices.push_back(ids0[0]); refinedIndices.push_back(ids1[0]); refinedIndices.push_back(ids1[2]);\n    refinedIndices.push_back(ids0[1]); refinedIndices.push_back(ids1[1]); refinedIndices.push_back(ids1[0]);\n    refinedIndices.push_back(ids0[2]); refinedIndices.push_back(ids1[2]); refinedIndices.push_back(ids1[1]);\n    refinedIndices.push_back(ids1[0]); refinedIndices.push_back(ids1[1]); refinedIndices.push_back(ids1[2]);\n  }\n  mListIds.push_back(0);\n}\n\nvoid IcoSphere::draw(int level)\n{\n  while (level>=int(mIndices.size()))\n    const_cast<IcoSphere*>(this)->_subdivide();\n  if (mListIds[level]==0)\n  {\n    mListIds[level] = glGenLists(1);\n    glNewList(mListIds[level], GL_COMPILE);\n      glVertexPointer(3, GL_FLOAT, 0, mVertices[0].data());\n      glNormalPointer(GL_FLOAT, 0, mVertices[0].data());\n      glEnableClientState(GL_VERTEX_ARRAY);\n      glEnableClientState(GL_NORMAL_ARRAY);\n      glDrawElements(GL_TRIANGLES, mIndices[level]->size(), GL_UNSIGNED_INT, &(mIndices[level]->at(0)));\n      glDisableClientState(GL_VERTEX_ARRAY);\n      glDisableClientState(GL_NORMAL_ARRAY);\n    glEndList();\n  }\n  glCallList(mListIds[level]);\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/opengl/icosphere.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ICOSPHERE_H\n#define EIGEN_ICOSPHERE_H\n\n#include <Eigen/Core>\n#include <vector>\n\nclass IcoSphere\n{\n  public:\n    IcoSphere(unsigned int levels=1);\n    const std::vector<Eigen::Vector3f>& vertices() const { return mVertices; }\n    const std::vector<int>& indices(int level) const;\n    void draw(int level);\n  protected:\n    void _subdivide();\n    std::vector<Eigen::Vector3f> mVertices;\n    std::vector<std::vector<int>*> mIndices;\n    std::vector<int> mListIds;\n};\n\n#endif // EIGEN_ICOSPHERE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/opengl/quaternion_demo.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"quaternion_demo.h\"\n#include \"icosphere.h\"\n\n#include <Eigen/Geometry>\n#include <Eigen/QR>\n#include <Eigen/LU>\n\n#include <iostream>\n#include <QEvent>\n#include <QMouseEvent>\n#include <QInputDialog>\n#include <QGridLayout>\n#include <QButtonGroup>\n#include <QRadioButton>\n#include <QDockWidget>\n#include <QPushButton>\n#include <QGroupBox>\n\nusing namespace Eigen;\n\nclass FancySpheres\n{\n  public:\n    EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n    \n    FancySpheres()\n    {\n      const int levels = 4;\n      const float scale = 0.33;\n      float radius = 100;\n      std::vector<int> parents;\n\n      // leval 0\n      mCenters.push_back(Vector3f::Zero());\n      parents.push_back(-1);\n      mRadii.push_back(radius);\n\n      // generate level 1 using icosphere vertices\n      radius *= 0.45;\n      {\n        float dist = mRadii[0]*0.9;\n        for (int i=0; i<12; ++i)\n        {\n          mCenters.push_back(mIcoSphere.vertices()[i] * dist);\n          mRadii.push_back(radius);\n          parents.push_back(0);\n        }\n      }\n\n      static const float angles [10] = {\n        0, 0,\n        M_PI, 0.*M_PI,\n        M_PI, 0.5*M_PI,\n        M_PI, 1.*M_PI,\n        M_PI, 1.5*M_PI\n      };\n\n      // generate other levels\n      int start = 1;\n      for (int l=1; l<levels; l++)\n      {\n        radius *= scale;\n        int end = mCenters.size();\n        for (int i=start; i<end; ++i)\n        {\n          Vector3f c = mCenters[i];\n          Vector3f ax0 = (c - mCenters[parents[i]]).normalized();\n          Vector3f ax1 = ax0.unitOrthogonal();\n          Quaternionf q;\n          q.setFromTwoVectors(Vector3f::UnitZ(), ax0);\n          Affine3f t = Translation3f(c) * q * Scaling(mRadii[i]+radius);\n          for (int j=0; j<5; ++j)\n          {\n            Vector3f newC = c + ( (AngleAxisf(angles[j*2+1], ax0)\n                                * AngleAxisf(angles[j*2+0] * (l==1 ? 0.35 : 0.5), ax1)) * ax0)\n                                * (mRadii[i] + radius*0.8);\n            mCenters.push_back(newC);\n            mRadii.push_back(radius);\n            parents.push_back(i);\n          }\n        }\n        start = end;\n      }\n    }\n\n    void draw()\n    {\n      int end = mCenters.size();\n      glEnable(GL_NORMALIZE);\n      for (int i=0; i<end; ++i)\n      {\n        Affine3f t = Translation3f(mCenters[i]) * Scaling(mRadii[i]);\n        gpu.pushMatrix(GL_MODELVIEW);\n        gpu.multMatrix(t.matrix(),GL_MODELVIEW);\n        mIcoSphere.draw(2);\n        gpu.popMatrix(GL_MODELVIEW);\n      }\n      glDisable(GL_NORMALIZE);\n    }\n  protected:\n    std::vector<Vector3f> mCenters;\n    std::vector<float> mRadii;\n    IcoSphere mIcoSphere;\n};\n\n\n// generic linear interpolation method\ntemplate<typename T> T lerp(float t, const T& a, const T& b)\n{\n  return a*(1-t) + b*t;\n}\n\n// quaternion slerp\ntemplate<> Quaternionf lerp(float t, const Quaternionf& a, const Quaternionf& b)\n{ return a.slerp(t,b); }\n\n// linear interpolation of a frame using the type OrientationType\n// to perform the interpolation of the orientations\ntemplate<typename OrientationType>\ninline static Frame lerpFrame(float alpha, const Frame& a, const Frame& b)\n{\n  return Frame(lerp(alpha,a.position,b.position),\n               Quaternionf(lerp(alpha,OrientationType(a.orientation),OrientationType(b.orientation))));\n}\n\ntemplate<typename Scalar_> class EulerAngles\n{\npublic:\n  enum { Dim = 3 };\n  typedef Scalar_ Scalar;\n  typedef Matrix<Scalar,3,3> Matrix3;\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef Quaternion<Scalar> QuaternionType;\n\nprotected:\n\n  Vector3 m_angles;\n\npublic:\n\n  EulerAngles() {}\n  inline EulerAngles(Scalar a0, Scalar a1, Scalar a2) : m_angles(a0, a1, a2) {}\n  inline EulerAngles(const QuaternionType& q) { *this = q; }\n\n  const Vector3& coeffs() const { return m_angles; }\n  Vector3& coeffs() { return m_angles; }\n\n  EulerAngles& operator=(const QuaternionType& q)\n  {\n    Matrix3 m = q.toRotationMatrix();\n    return *this = m;\n  }\n\n  EulerAngles& operator=(const Matrix3& m)\n  {\n    // mat =  cy*cz          -cy*sz           sy\n    //        cz*sx*sy+cx*sz  cx*cz-sx*sy*sz -cy*sx\n    //       -cx*cz*sy+sx*sz  cz*sx+cx*sy*sz  cx*cy\n    m_angles.coeffRef(1) = std::asin(m.coeff(0,2));\n    m_angles.coeffRef(0) = std::atan2(-m.coeff(1,2),m.coeff(2,2));\n    m_angles.coeffRef(2) = std::atan2(-m.coeff(0,1),m.coeff(0,0));\n    return *this;\n  }\n\n  Matrix3 toRotationMatrix(void) const\n  {\n    Vector3 c = m_angles.array().cos();\n    Vector3 s = m_angles.array().sin();\n    Matrix3 res;\n    res <<  c.y()*c.z(),                    -c.y()*s.z(),                   s.y(),\n            c.z()*s.x()*s.y()+c.x()*s.z(),  c.x()*c.z()-s.x()*s.y()*s.z(),  -c.y()*s.x(),\n            -c.x()*c.z()*s.y()+s.x()*s.z(), c.z()*s.x()+c.x()*s.y()*s.z(),  c.x()*c.y();\n    return res;\n  }\n\n  operator QuaternionType() { return QuaternionType(toRotationMatrix()); }\n};\n\n// Euler angles slerp\ntemplate<> EulerAngles<float> lerp(float t, const EulerAngles<float>& a, const EulerAngles<float>& b)\n{\n  EulerAngles<float> res;\n  res.coeffs() = lerp(t, a.coeffs(), b.coeffs());\n  return res;\n}\n\n\nRenderingWidget::RenderingWidget()\n{\n  mAnimate = false;\n  mCurrentTrackingMode = TM_NO_TRACK;\n  mNavMode = NavTurnAround;\n  mLerpMode = LerpQuaternion;\n  mRotationMode = RotationStable;\n  mTrackball.setCamera(&mCamera);\n\n  // required to capture key press events\n  setFocusPolicy(Qt::ClickFocus);\n}\n\nvoid RenderingWidget::grabFrame(void)\n{\n    // ask user for a time\n    bool ok = false;\n    double t = 0;\n    if (!m_timeline.empty())\n      t = (--m_timeline.end())->first + 1.;\n    t = QInputDialog::getDouble(this, \"Eigen's RenderingWidget\", \"time value: \",\n      t, 0, 1e3, 1, &ok);\n    if (ok)\n    {\n      Frame aux;\n      aux.orientation = mCamera.viewMatrix().linear();\n      aux.position = mCamera.viewMatrix().translation();\n      m_timeline[t] = aux;\n    }\n}\n\nvoid RenderingWidget::drawScene()\n{\n  static FancySpheres sFancySpheres;\n  float length = 50;\n  gpu.drawVector(Vector3f::Zero(), length*Vector3f::UnitX(), Color(1,0,0,1));\n  gpu.drawVector(Vector3f::Zero(), length*Vector3f::UnitY(), Color(0,1,0,1));\n  gpu.drawVector(Vector3f::Zero(), length*Vector3f::UnitZ(), Color(0,0,1,1));\n\n  // draw the fractal object\n  float sqrt3 = std::sqrt(3.);\n  glLightfv(GL_LIGHT0, GL_AMBIENT, Vector4f(0.5,0.5,0.5,1).data());\n  glLightfv(GL_LIGHT0, GL_DIFFUSE, Vector4f(0.5,1,0.5,1).data());\n  glLightfv(GL_LIGHT0, GL_SPECULAR, Vector4f(1,1,1,1).data());\n  glLightfv(GL_LIGHT0, GL_POSITION, Vector4f(-sqrt3,-sqrt3,sqrt3,0).data());\n\n  glLightfv(GL_LIGHT1, GL_AMBIENT, Vector4f(0,0,0,1).data());\n  glLightfv(GL_LIGHT1, GL_DIFFUSE, Vector4f(1,0.5,0.5,1).data());\n  glLightfv(GL_LIGHT1, GL_SPECULAR, Vector4f(1,1,1,1).data());\n  glLightfv(GL_LIGHT1, GL_POSITION, Vector4f(-sqrt3,sqrt3,-sqrt3,0).data());\n\n  glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT, Vector4f(0.7, 0.7, 0.7, 1).data());\n  glMaterialfv(GL_FRONT_AND_BACK, GL_DIFFUSE, Vector4f(0.8, 0.75, 0.6, 1).data());\n  glMaterialfv(GL_FRONT_AND_BACK, GL_SPECULAR, Vector4f(1, 1, 1, 1).data());\n  glMaterialf(GL_FRONT_AND_BACK, GL_SHININESS, 64);\n\n  glEnable(GL_LIGHTING);\n  glEnable(GL_LIGHT0);\n  glEnable(GL_LIGHT1);\n\n  sFancySpheres.draw();\n  glVertexPointer(3, GL_FLOAT, 0, mVertices[0].data());\n  glNormalPointer(GL_FLOAT, 0, mNormals[0].data());\n  glEnableClientState(GL_VERTEX_ARRAY);\n  glEnableClientState(GL_NORMAL_ARRAY);\n  glDrawArrays(GL_TRIANGLES, 0, mVertices.size());\n  glDisableClientState(GL_VERTEX_ARRAY);\n  glDisableClientState(GL_NORMAL_ARRAY);\n\n  glDisable(GL_LIGHTING);\n}\n\nvoid RenderingWidget::animate()\n{\n  m_alpha += double(m_timer.interval()) * 1e-3;\n\n  TimeLine::const_iterator hi = m_timeline.upper_bound(m_alpha);\n  TimeLine::const_iterator lo = hi;\n  --lo;\n\n  Frame currentFrame;\n\n  if(hi==m_timeline.end())\n  {\n    // end\n    currentFrame = lo->second;\n    stopAnimation();\n  }\n  else if(hi==m_timeline.begin())\n  {\n    // start\n    currentFrame = hi->second;\n  }\n  else\n  {\n    float s = (m_alpha - lo->first)/(hi->first - lo->first);\n    if (mLerpMode==LerpEulerAngles)\n      currentFrame = ::lerpFrame<EulerAngles<float> >(s, lo->second, hi->second);\n    else if (mLerpMode==LerpQuaternion)\n      currentFrame = ::lerpFrame<Eigen::Quaternionf>(s, lo->second, hi->second);\n    else\n    {\n      std::cerr << \"Invalid rotation interpolation mode (abort)\\n\";\n      exit(2);\n    }\n    currentFrame.orientation.coeffs().normalize();\n  }\n\n  currentFrame.orientation = currentFrame.orientation.inverse();\n  currentFrame.position = - (currentFrame.orientation * currentFrame.position);\n  mCamera.setFrame(currentFrame);\n\n  updateGL();\n}\n\nvoid RenderingWidget::keyPressEvent(QKeyEvent * e)\n{\n    switch(e->key())\n    {\n      case Qt::Key_Up:\n        mCamera.zoom(2);\n        break;\n      case Qt::Key_Down:\n        mCamera.zoom(-2);\n        break;\n      // add a frame\n      case Qt::Key_G:\n        grabFrame();\n        break;\n      // clear the time line\n      case Qt::Key_C:\n        m_timeline.clear();\n        break;\n      // move the camera to initial pos\n      case Qt::Key_R:\n        resetCamera();\n        break;\n      // start/stop the animation\n      case Qt::Key_A:\n        if (mAnimate)\n        {\n          stopAnimation();\n        }\n        else\n        {\n          m_alpha = 0;\n          connect(&m_timer, SIGNAL(timeout()), this, SLOT(animate()));\n          m_timer.start(1000/30);\n          mAnimate = true;\n        }\n        break;\n      default:\n        break;\n    }\n\n    updateGL();\n}\n\nvoid RenderingWidget::stopAnimation()\n{\n  disconnect(&m_timer, SIGNAL(timeout()), this, SLOT(animate()));\n  m_timer.stop();\n  mAnimate = false;\n  m_alpha = 0;\n}\n\nvoid RenderingWidget::mousePressEvent(QMouseEvent* e)\n{\n  mMouseCoords = Vector2i(e->pos().x(), e->pos().y());\n  bool fly = (mNavMode==NavFly) || (e->modifiers()&Qt::ControlModifier);\n  switch(e->button())\n  {\n    case Qt::LeftButton:\n      if(fly)\n      {\n        mCurrentTrackingMode = TM_LOCAL_ROTATE;\n        mTrackball.start(Trackball::Local);\n      }\n      else\n      {\n        mCurrentTrackingMode = TM_ROTATE_AROUND;\n        mTrackball.start(Trackball::Around);\n      }\n      mTrackball.track(mMouseCoords);\n      break;\n    case Qt::MidButton:\n      if(fly)\n        mCurrentTrackingMode = TM_FLY_Z;\n      else\n        mCurrentTrackingMode = TM_ZOOM;\n      break;\n    case Qt::RightButton:\n        mCurrentTrackingMode = TM_FLY_PAN;\n      break;\n    default:\n      break;\n  }\n}\nvoid RenderingWidget::mouseReleaseEvent(QMouseEvent*)\n{\n    mCurrentTrackingMode = TM_NO_TRACK;\n    updateGL();\n}\n\nvoid RenderingWidget::mouseMoveEvent(QMouseEvent* e)\n{\n    // tracking\n    if(mCurrentTrackingMode != TM_NO_TRACK)\n    {\n        float dx =   float(e->x() - mMouseCoords.x()) / float(mCamera.vpWidth());\n        float dy = - float(e->y() - mMouseCoords.y()) / float(mCamera.vpHeight());\n\n        // speedup the transformations\n        if(e->modifiers() & Qt::ShiftModifier)\n        {\n          dx *= 10.;\n          dy *= 10.;\n        }\n\n        switch(mCurrentTrackingMode)\n        {\n          case TM_ROTATE_AROUND:\n          case TM_LOCAL_ROTATE:\n            if (mRotationMode==RotationStable)\n            {\n              // use the stable trackball implementation mapping\n              // the 2D coordinates to 3D points on a sphere.\n              mTrackball.track(Vector2i(e->pos().x(), e->pos().y()));\n            }\n            else\n            {\n              // standard approach mapping the x and y displacements as rotations\n              // around the camera's X and Y axes.\n              Quaternionf q = AngleAxisf( dx*M_PI, Vector3f::UnitY())\n                            * AngleAxisf(-dy*M_PI, Vector3f::UnitX());\n              if (mCurrentTrackingMode==TM_LOCAL_ROTATE)\n                mCamera.localRotate(q);\n              else\n                mCamera.rotateAroundTarget(q);\n            }\n            break;\n          case TM_ZOOM :\n            mCamera.zoom(dy*100);\n            break;\n          case TM_FLY_Z :\n            mCamera.localTranslate(Vector3f(0, 0, -dy*200));\n            break;\n          case TM_FLY_PAN :\n            mCamera.localTranslate(Vector3f(dx*200, dy*200, 0));\n            break;\n          default:\n            break;\n        }\n\n        updateGL();\n    }\n\n    mMouseCoords = Vector2i(e->pos().x(), e->pos().y());\n}\n\nvoid RenderingWidget::paintGL()\n{\n  glEnable(GL_DEPTH_TEST);\n  glDisable(GL_CULL_FACE);\n  glPolygonMode(GL_FRONT_AND_BACK,GL_FILL);\n  glDisable(GL_COLOR_MATERIAL);\n  glDisable(GL_BLEND);\n  glDisable(GL_ALPHA_TEST);\n  glDisable(GL_TEXTURE_1D);\n  glDisable(GL_TEXTURE_2D);\n  glDisable(GL_TEXTURE_3D);\n\n  // Clear buffers\n  glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);\n\n  mCamera.activateGL();\n\n  drawScene();\n}\n\nvoid RenderingWidget::initializeGL()\n{\n  glClearColor(1., 1., 1., 0.);\n  glLightModeli(GL_LIGHT_MODEL_LOCAL_VIEWER, 1);\n  glDepthMask(GL_TRUE);\n  glColorMask(GL_TRUE, GL_TRUE, GL_TRUE, GL_TRUE);\n\n  mCamera.setPosition(Vector3f(-200, -200, -200));\n  mCamera.setTarget(Vector3f(0, 0, 0));\n  mInitFrame.orientation = mCamera.orientation().inverse();\n  mInitFrame.position = mCamera.viewMatrix().translation();\n}\n\nvoid RenderingWidget::resizeGL(int width, int height)\n{\n    mCamera.setViewport(width,height);\n}\n\nvoid RenderingWidget::setNavMode(int m)\n{\n  mNavMode = NavMode(m);\n}\n\nvoid RenderingWidget::setLerpMode(int m)\n{\n  mLerpMode = LerpMode(m);\n}\n\nvoid RenderingWidget::setRotationMode(int m)\n{\n  mRotationMode = RotationMode(m);\n}\n\nvoid RenderingWidget::resetCamera()\n{\n  if (mAnimate)\n    stopAnimation();\n  m_timeline.clear();\n  Frame aux0 = mCamera.frame();\n  aux0.orientation = aux0.orientation.inverse();\n  aux0.position = mCamera.viewMatrix().translation();\n  m_timeline[0] = aux0;\n\n  Vector3f currentTarget = mCamera.target();\n  mCamera.setTarget(Vector3f::Zero());\n\n  // compute the rotation duration to move the camera to the target\n  Frame aux1 = mCamera.frame();\n  aux1.orientation = aux1.orientation.inverse();\n  aux1.position = mCamera.viewMatrix().translation();\n  float duration = aux0.orientation.angularDistance(aux1.orientation) * 0.9;\n  if (duration<0.1) duration = 0.1;\n\n  // put the camera at that time step:\n  aux1 = aux0.lerp(duration/2,mInitFrame);\n  // and make it look at the target again\n  aux1.orientation = aux1.orientation.inverse();\n  aux1.position = - (aux1.orientation * aux1.position);\n  mCamera.setFrame(aux1);\n  mCamera.setTarget(Vector3f::Zero());\n\n  // add this camera keyframe\n  aux1.orientation = aux1.orientation.inverse();\n  aux1.position = mCamera.viewMatrix().translation();\n  m_timeline[duration] = aux1;\n\n  m_timeline[2] = mInitFrame;\n  m_alpha = 0;\n  animate();\n  connect(&m_timer, SIGNAL(timeout()), this, SLOT(animate()));\n  m_timer.start(1000/30);\n  mAnimate = true;\n}\n\nQWidget* RenderingWidget::createNavigationControlWidget()\n{\n  QWidget* panel = new QWidget();\n  QVBoxLayout* layout = new QVBoxLayout();\n\n  {\n    QPushButton* but = new QPushButton(\"reset\");\n    but->setToolTip(\"move the camera to initial position (with animation)\");\n    layout->addWidget(but);\n    connect(but, SIGNAL(clicked()), this, SLOT(resetCamera()));\n  }\n  {\n    // navigation mode\n    QGroupBox* box = new QGroupBox(\"navigation mode\");\n    QVBoxLayout* boxLayout = new QVBoxLayout;\n    QButtonGroup* group = new QButtonGroup(panel);\n    QRadioButton* but;\n    but = new QRadioButton(\"turn around\");\n    but->setToolTip(\"look around an object\");\n    group->addButton(but, NavTurnAround);\n    boxLayout->addWidget(but);\n    but = new QRadioButton(\"fly\");\n    but->setToolTip(\"free navigation like a spaceship\\n(this mode can also be enabled pressing the \\\"shift\\\" key)\");\n    group->addButton(but, NavFly);\n    boxLayout->addWidget(but);\n    group->button(mNavMode)->setChecked(true);\n    connect(group, SIGNAL(buttonClicked(int)), this, SLOT(setNavMode(int)));\n    box->setLayout(boxLayout);\n    layout->addWidget(box);\n  }\n  {\n    // track ball, rotation mode\n    QGroupBox* box = new QGroupBox(\"rotation mode\");\n    QVBoxLayout* boxLayout = new QVBoxLayout;\n    QButtonGroup* group = new QButtonGroup(panel);\n    QRadioButton* but;\n    but = new QRadioButton(\"stable trackball\");\n    group->addButton(but, RotationStable);\n    boxLayout->addWidget(but);\n    but->setToolTip(\"use the stable trackball implementation mapping\\nthe 2D coordinates to 3D points on a sphere\");\n    but = new QRadioButton(\"standard rotation\");\n    group->addButton(but, RotationStandard);\n    boxLayout->addWidget(but);\n    but->setToolTip(\"standard approach mapping the x and y displacements\\nas rotations around the camera's X and Y axes\");\n    group->button(mRotationMode)->setChecked(true);\n    connect(group, SIGNAL(buttonClicked(int)), this, SLOT(setRotationMode(int)));\n    box->setLayout(boxLayout);\n    layout->addWidget(box);\n  }\n  {\n    // interpolation mode\n    QGroupBox* box = new QGroupBox(\"spherical interpolation\");\n    QVBoxLayout* boxLayout = new QVBoxLayout;\n    QButtonGroup* group = new QButtonGroup(panel);\n    QRadioButton* but;\n    but = new QRadioButton(\"quaternion slerp\");\n    group->addButton(but, LerpQuaternion);\n    boxLayout->addWidget(but);\n    but->setToolTip(\"use quaternion spherical interpolation\\nto interpolate orientations\");\n    but = new QRadioButton(\"euler angles\");\n    group->addButton(but, LerpEulerAngles);\n    boxLayout->addWidget(but);\n    but->setToolTip(\"use Euler angles to interpolate orientations\");\n    group->button(mNavMode)->setChecked(true);\n    connect(group, SIGNAL(buttonClicked(int)), this, SLOT(setLerpMode(int)));\n    box->setLayout(boxLayout);\n    layout->addWidget(box);\n  }\n  layout->addItem(new QSpacerItem(0,0,QSizePolicy::Minimum,QSizePolicy::Expanding));\n  panel->setLayout(layout);\n  return panel;\n}\n\nQuaternionDemo::QuaternionDemo()\n{\n  mRenderingWidget = new RenderingWidget();\n  setCentralWidget(mRenderingWidget);\n\n  QDockWidget* panel = new QDockWidget(\"navigation\", this);\n  panel->setAllowedAreas((QFlags<Qt::DockWidgetArea>)(Qt::RightDockWidgetArea | Qt::LeftDockWidgetArea));\n  addDockWidget(Qt::RightDockWidgetArea, panel);\n  panel->setWidget(mRenderingWidget->createNavigationControlWidget());\n}\n\nint main(int argc, char *argv[])\n{\n  std::cout << \"Navigation:\\n\";\n  std::cout << \"  left button:           rotate around the target\\n\";\n  std::cout << \"  middle button:         zoom\\n\";\n  std::cout << \"  left button + ctrl     quake rotate (rotate around camera position)\\n\";\n  std::cout << \"  middle button + ctrl   walk (progress along camera's z direction)\\n\";\n  std::cout << \"  left button:           pan (translate in the XY camera's plane)\\n\\n\";\n  std::cout << \"R : move the camera to initial position\\n\";\n  std::cout << \"A : start/stop animation\\n\";\n  std::cout << \"C : clear the animation\\n\";\n  std::cout << \"G : add a key frame\\n\";\n\n  QApplication app(argc, argv);\n  QuaternionDemo demo;\n  demo.resize(600,500);\n  demo.show();\n  return app.exec();\n}\n\n#include \"quaternion_demo.moc\"\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/opengl/quaternion_demo.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_QUATERNION_DEMO_H\n#define EIGEN_QUATERNION_DEMO_H\n\n#include \"gpuhelper.h\"\n#include \"camera.h\"\n#include \"trackball.h\"\n#include <map>\n#include <QTimer>\n#include <QtGui/QApplication>\n#include <QtOpenGL/QGLWidget>\n#include <QtGui/QMainWindow>\n\nclass RenderingWidget : public QGLWidget\n{\n  Q_OBJECT\n\n    typedef std::map<float,Frame> TimeLine;\n    TimeLine m_timeline;\n    Frame lerpFrame(float t);\n\n    Frame mInitFrame;\n    bool mAnimate;\n    float m_alpha;\n\n    enum TrackMode {\n      TM_NO_TRACK=0, TM_ROTATE_AROUND, TM_ZOOM,\n      TM_LOCAL_ROTATE, TM_FLY_Z, TM_FLY_PAN\n    };\n\n    enum NavMode {\n      NavTurnAround,\n      NavFly\n    };\n\n    enum LerpMode {\n      LerpQuaternion,\n      LerpEulerAngles\n    };\n\n    enum RotationMode {\n      RotationStable,\n      RotationStandard\n    };\n\n    Camera mCamera;\n    TrackMode mCurrentTrackingMode;\n    NavMode mNavMode;\n    LerpMode mLerpMode;\n    RotationMode mRotationMode;\n    Vector2i mMouseCoords;\n    Trackball mTrackball;\n\n    QTimer m_timer;\n\n    void setupCamera();\n\n    std::vector<Vector3f> mVertices;\n    std::vector<Vector3f> mNormals;\n    std::vector<int> mIndices;\n\n  protected slots:\n\n    virtual void animate(void);\n    virtual void drawScene(void);\n\n    virtual void grabFrame(void);\n    virtual void stopAnimation();\n\n    virtual void setNavMode(int);\n    virtual void setLerpMode(int);\n    virtual void setRotationMode(int);\n    virtual void resetCamera();\n\n  protected:\n\n    virtual void initializeGL();\n    virtual void resizeGL(int width, int height);\n    virtual void paintGL();\n    \n    //--------------------------------------------------------------------------------\n    virtual void mousePressEvent(QMouseEvent * e);\n    virtual void mouseReleaseEvent(QMouseEvent * e);\n    virtual void mouseMoveEvent(QMouseEvent * e);\n    virtual void keyPressEvent(QKeyEvent * e);\n    //--------------------------------------------------------------------------------\n\n  public: \n    EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n    \n    RenderingWidget();\n    ~RenderingWidget() { }\n\n    QWidget* createNavigationControlWidget();\n};\n\nclass QuaternionDemo : public QMainWindow\n{\n  Q_OBJECT\n  public:\n    QuaternionDemo();\n  protected:\n    RenderingWidget* mRenderingWidget;\n};\n\n#endif // EIGEN_QUATERNION_DEMO_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/opengl/trackball.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"trackball.h\"\n#include \"camera.h\"\n\nusing namespace Eigen;\n\nvoid Trackball::track(const Vector2i& point2D)\n{\n  if (mpCamera==0)\n    return;\n  Vector3f newPoint3D;\n  bool newPointOk = mapToSphere(point2D, newPoint3D);\n\n  if (mLastPointOk && newPointOk)\n  {\n    Vector3f axis = mLastPoint3D.cross(newPoint3D).normalized();\n    float cos_angle = mLastPoint3D.dot(newPoint3D);\n    if ( std::abs(cos_angle) < 1.0 )\n    {\n      float angle = 2. * acos(cos_angle);\n      if (mMode==Around)\n        mpCamera->rotateAroundTarget(Quaternionf(AngleAxisf(angle, axis)));\n      else\n        mpCamera->localRotate(Quaternionf(AngleAxisf(-angle, axis)));\n    }\n  }\n\n  mLastPoint3D = newPoint3D;\n  mLastPointOk = newPointOk;\n}\n\nbool Trackball::mapToSphere(const Vector2i& p2, Vector3f& v3)\n{\n  if ((p2.x() >= 0) && (p2.x() <= int(mpCamera->vpWidth())) &&\n      (p2.y() >= 0) && (p2.y() <= int(mpCamera->vpHeight())) )\n  {\n    double x  = (double)(p2.x() - 0.5*mpCamera->vpWidth())  / (double)mpCamera->vpWidth();\n    double y  = (double)(0.5*mpCamera->vpHeight() - p2.y()) / (double)mpCamera->vpHeight();\n    double sinx         = sin(M_PI * x * 0.5);\n    double siny         = sin(M_PI * y * 0.5);\n    double sinx2siny2   = sinx * sinx + siny * siny;\n\n    v3.x() = sinx;\n    v3.y() = siny;\n    v3.z() = sinx2siny2 < 1.0 ? sqrt(1.0 - sinx2siny2) : 0.0;\n\n    return true;\n  }\n  else\n    return false;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/demos/opengl/trackball.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_TRACKBALL_H\n#define EIGEN_TRACKBALL_H\n\n#include <Eigen/Geometry>\n\nclass Camera;\n\nclass Trackball\n{\n  public:\n\n    enum Mode {Around, Local};\n\n    Trackball() : mpCamera(0) {}\n\n    void start(Mode m = Around) { mMode = m; mLastPointOk = false; }\n\n    void setCamera(Camera* pCam) { mpCamera = pCam; }\n\n    void track(const Eigen::Vector2i& newPoint2D);\n\n  protected:\n\n    bool mapToSphere( const Eigen::Vector2i& p2, Eigen::Vector3f& v3);\n\n    Camera* mpCamera;\n    Eigen::Vector3f mLastPoint3D;\n    Mode mMode;\n    bool mLastPointOk;\n\n};\n\n#endif // EIGEN_TRACKBALL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/AsciiQuickReference.txt",
    "content": "// A simple quickref for Eigen. Add anything that's missing.\n// Main author: Keir Mierle\n\n#include <Eigen/Dense>\n\nMatrix<double, 3, 3> A;               // Fixed rows and cols. Same as Matrix3d.\nMatrix<double, 3, Dynamic> B;         // Fixed rows, dynamic cols.\nMatrix<double, Dynamic, Dynamic> C;   // Full dynamic. Same as MatrixXd.\nMatrix<double, 3, 3, RowMajor> E;     // Row major; default is column-major.\nMatrix3f P, Q, R;                     // 3x3 float matrix.\nVector3f x, y, z;                     // 3x1 float matrix.\nRowVector3f a, b, c;                  // 1x3 float matrix.\nVectorXd v;                           // Dynamic column vector of doubles\ndouble s;                            \n\n// Basic usage\n// Eigen          // Matlab           // comments\nx.size()          // length(x)        // vector size\nC.rows()          // size(C,1)        // number of rows\nC.cols()          // size(C,2)        // number of columns\nx(i)              // x(i+1)           // Matlab is 1-based\nC(i,j)            // C(i+1,j+1)       //\n\nA.resize(4, 4);   // Runtime error if assertions are on.\nB.resize(4, 9);   // Runtime error if assertions are on.\nA.resize(3, 3);   // Ok; size didn't change.\nB.resize(3, 9);   // Ok; only dynamic cols changed.\n                  \nA << 1, 2, 3,     // Initialize A. The elements can also be\n     4, 5, 6,     // matrices, which are stacked along cols\n     7, 8, 9;     // and then the rows are stacked.\nB << A, A, A;     // B is three horizontally stacked A's.\nA.fill(10);       // Fill A with all 10's.\n\n// Eigen                                    // Matlab\nMatrixXd::Identity(rows,cols)               // eye(rows,cols)\nC.setIdentity(rows,cols)                    // C = eye(rows,cols)\nMatrixXd::Zero(rows,cols)                   // zeros(rows,cols)\nC.setZero(rows,cols)                        // C = zeros(rows,cols)\nMatrixXd::Ones(rows,cols)                   // ones(rows,cols)\nC.setOnes(rows,cols)                        // C = ones(rows,cols)\nMatrixXd::Random(rows,cols)                 // rand(rows,cols)*2-1            // MatrixXd::Random returns uniform random numbers in (-1, 1).\nC.setRandom(rows,cols)                      // C = rand(rows,cols)*2-1\nVectorXd::LinSpaced(size,low,high)          // linspace(low,high,size)'\nv.setLinSpaced(size,low,high)               // v = linspace(low,high,size)'\nVectorXi::LinSpaced(((hi-low)/step)+1,      // low:step:hi\n                    low,low+step*(size-1))  //\n\n\n// Matrix slicing and blocks. All expressions listed here are read/write.\n// Templated size versions are faster. Note that Matlab is 1-based (a size N\n// vector is x(1)...x(N)).\n/******************************************************************************/\n/*                  PLEASE HELP US IMPROVING THIS SECTION                     */\n/* Eigen 3.4 supports a much improved API for sub-matrices, including,        */\n/* slicing and indexing from arrays:                                          */\n/* http://eigen.tuxfamily.org/dox-devel/group__TutorialSlicingIndexing.html   */\n/******************************************************************************/\n// Eigen                           // Matlab\nx.head(n)                          // x(1:n)\nx.head<n>()                        // x(1:n)\nx.tail(n)                          // x(end - n + 1: end)\nx.tail<n>()                        // x(end - n + 1: end)\nx.segment(i, n)                    // x(i+1 : i+n)\nx.segment<n>(i)                    // x(i+1 : i+n)\nP.block(i, j, rows, cols)          // P(i+1 : i+rows, j+1 : j+cols)\nP.block<rows, cols>(i, j)          // P(i+1 : i+rows, j+1 : j+cols)\nP.row(i)                           // P(i+1, :)\nP.col(j)                           // P(:, j+1)\nP.leftCols<cols>()                 // P(:, 1:cols)\nP.leftCols(cols)                   // P(:, 1:cols)\nP.middleCols<cols>(j)              // P(:, j+1:j+cols)\nP.middleCols(j, cols)              // P(:, j+1:j+cols)\nP.rightCols<cols>()                // P(:, end-cols+1:end)\nP.rightCols(cols)                  // P(:, end-cols+1:end)\nP.topRows<rows>()                  // P(1:rows, :)\nP.topRows(rows)                    // P(1:rows, :)\nP.middleRows<rows>(i)              // P(i+1:i+rows, :)\nP.middleRows(i, rows)              // P(i+1:i+rows, :)\nP.bottomRows<rows>()               // P(end-rows+1:end, :)\nP.bottomRows(rows)                 // P(end-rows+1:end, :)\nP.topLeftCorner(rows, cols)        // P(1:rows, 1:cols)\nP.topRightCorner(rows, cols)       // P(1:rows, end-cols+1:end)\nP.bottomLeftCorner(rows, cols)     // P(end-rows+1:end, 1:cols)\nP.bottomRightCorner(rows, cols)    // P(end-rows+1:end, end-cols+1:end)\nP.topLeftCorner<rows,cols>()       // P(1:rows, 1:cols)\nP.topRightCorner<rows,cols>()      // P(1:rows, end-cols+1:end)\nP.bottomLeftCorner<rows,cols>()    // P(end-rows+1:end, 1:cols)\nP.bottomRightCorner<rows,cols>()   // P(end-rows+1:end, end-cols+1:end)\n\n// Of particular note is Eigen's swap function which is highly optimized.\n// Eigen                           // Matlab\nR.row(i) = P.col(j);               // R(i, :) = P(:, j)\nR.col(j1).swap(mat1.col(j2));      // R(:, [j1 j2]) = R(:, [j2, j1])\n\n// Views, transpose, etc;\n/******************************************************************************/\n/*                  PLEASE HELP US IMPROVING THIS SECTION                     */\n/* Eigen 3.4 supports a new API for reshaping:                                */\n/* http://eigen.tuxfamily.org/dox-devel/group__TutorialReshape.html           */\n/******************************************************************************/\n// Eigen                           // Matlab\nR.adjoint()                        // R'\nR.transpose()                      // R.' or conj(R')       // Read-write\nR.diagonal()                       // diag(R)               // Read-write\nx.asDiagonal()                     // diag(x)\nR.transpose().colwise().reverse()  // rot90(R)              // Read-write\nR.rowwise().reverse()              // fliplr(R)\nR.colwise().reverse()              // flipud(R)\nR.replicate(i,j)                   // repmat(P,i,j)\n\n\n// All the same as Matlab, but matlab doesn't have *= style operators.\n// Matrix-vector.  Matrix-matrix.   Matrix-scalar.\ny  = M*x;          R  = P*Q;        R  = P*s;\na  = b*M;          R  = P - Q;      R  = s*P;\na *= M;            R  = P + Q;      R  = P/s;\n                   R *= Q;          R  = s*P;\n                   R += Q;          R *= s;\n                   R -= Q;          R /= s;\n\n// Vectorized operations on each element independently\n// Eigen                       // Matlab\nR = P.cwiseProduct(Q);         // R = P .* Q\nR = P.array() * s.array();     // R = P .* s\nR = P.cwiseQuotient(Q);        // R = P ./ Q\nR = P.array() / Q.array();     // R = P ./ Q\nR = P.array() + s.array();     // R = P + s\nR = P.array() - s.array();     // R = P - s\nR.array() += s;                // R = R + s\nR.array() -= s;                // R = R - s\nR.array() < Q.array();         // R < Q\nR.array() <= Q.array();        // R <= Q\nR.cwiseInverse();              // 1 ./ P\nR.array().inverse();           // 1 ./ P\nR.array().sin()                // sin(P)\nR.array().cos()                // cos(P)\nR.array().pow(s)               // P .^ s\nR.array().square()             // P .^ 2\nR.array().cube()               // P .^ 3\nR.cwiseSqrt()                  // sqrt(P)\nR.array().sqrt()               // sqrt(P)\nR.array().exp()                // exp(P)\nR.array().log()                // log(P)\nR.cwiseMax(P)                  // max(R, P)\nR.array().max(P.array())       // max(R, P)\nR.cwiseMin(P)                  // min(R, P)\nR.array().min(P.array())       // min(R, P)\nR.cwiseAbs()                   // abs(P)\nR.array().abs()                // abs(P)\nR.cwiseAbs2()                  // abs(P.^2)\nR.array().abs2()               // abs(P.^2)\n(R.array() < s).select(P,Q );  // (R < s ? P : Q)\nR = (Q.array()==0).select(P,R) // R(Q==0) = P(Q==0)\nR = P.unaryExpr(ptr_fun(func)) // R = arrayfun(func, P)   // with: scalar func(const scalar &x);\n\n\n// Reductions.\nint r, c;\n// Eigen                  // Matlab\nR.minCoeff()              // min(R(:))\nR.maxCoeff()              // max(R(:))\ns = R.minCoeff(&r, &c)    // [s, i] = min(R(:)); [r, c] = ind2sub(size(R), i);\ns = R.maxCoeff(&r, &c)    // [s, i] = max(R(:)); [r, c] = ind2sub(size(R), i);\nR.sum()                   // sum(R(:))\nR.colwise().sum()         // sum(R)\nR.rowwise().sum()         // sum(R, 2) or sum(R')'\nR.prod()                  // prod(R(:))\nR.colwise().prod()        // prod(R)\nR.rowwise().prod()        // prod(R, 2) or prod(R')'\nR.trace()                 // trace(R)\nR.all()                   // all(R(:))\nR.colwise().all()         // all(R)\nR.rowwise().all()         // all(R, 2)\nR.any()                   // any(R(:))\nR.colwise().any()         // any(R)\nR.rowwise().any()         // any(R, 2)\n\n// Dot products, norms, etc.\n// Eigen                  // Matlab\nx.norm()                  // norm(x).    Note that norm(R) doesn't work in Eigen.\nx.squaredNorm()           // dot(x, x)   Note the equivalence is not true for complex\nx.dot(y)                  // dot(x, y)\nx.cross(y)                // cross(x, y) Requires #include <Eigen/Geometry>\n\n//// Type conversion\n// Eigen                  // Matlab\nA.cast<double>();         // double(A)\nA.cast<float>();          // single(A)\nA.cast<int>();            // int32(A)\nA.real();                 // real(A)\nA.imag();                 // imag(A)\n// if the original type equals destination type, no work is done\n\n// Note that for most operations Eigen requires all operands to have the same type:\nMatrixXf F = MatrixXf::Zero(3,3);\nA += F;                // illegal in Eigen. In Matlab A = A+F is allowed\nA += F.cast<double>(); // F converted to double and then added (generally, conversion happens on-the-fly)\n\n// Eigen can map existing memory into Eigen matrices.\nfloat array[3];\nVector3f::Map(array).fill(10);            // create a temporary Map over array and sets entries to 10\nint data[4] = {1, 2, 3, 4};\nMatrix2i mat2x2(data);                    // copies data into mat2x2\nMatrix2i::Map(data) = 2*mat2x2;           // overwrite elements of data with 2*mat2x2\nMatrixXi::Map(data, 2, 2) += mat2x2;      // adds mat2x2 to elements of data (alternative syntax if size is not know at compile time)\n\n// Solve Ax = b. Result stored in x. Matlab: x = A \\ b.\nx = A.ldlt().solve(b));  // A sym. p.s.d.    #include <Eigen/Cholesky>\nx = A.llt() .solve(b));  // A sym. p.d.      #include <Eigen/Cholesky>\nx = A.lu()  .solve(b));  // Stable and fast. #include <Eigen/LU>\nx = A.qr()  .solve(b));  // No pivoting.     #include <Eigen/QR>\nx = A.svd() .solve(b));  // Stable, slowest. #include <Eigen/SVD>\n// .ldlt() -> .matrixL() and .matrixD()\n// .llt()  -> .matrixL()\n// .lu()   -> .matrixL() and .matrixU()\n// .qr()   -> .matrixQ() and .matrixR()\n// .svd()  -> .matrixU(), .singularValues(), and .matrixV()\n\n// Eigenvalue problems\n// Eigen                          // Matlab\nA.eigenvalues();                  // eig(A);\nEigenSolver<Matrix3d> eig(A);     // [vec val] = eig(A)\neig.eigenvalues();                // diag(val)\neig.eigenvectors();               // vec\n// For self-adjoint matrices use SelfAdjointEigenSolver<>\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/B01_Experimental.dox",
    "content": "namespace Eigen {\n\n/** \\page Experimental Experimental parts of Eigen\n\n\\eigenAutoToc\n\n\\section Experimental_summary Summary\n\nWith the 2.0 release, Eigen's API is, to a large extent, stable. However, we wish to retain the freedom to make API incompatible changes. To that effect, we call many parts of Eigen \"experimental\" which means that they are not subject to API stability guarantee.\n\nOur goal is that for the 2.1 release (expected in July 2009) most of these parts become API-stable too.\n\nWe are aware that API stability is a major concern for our users. That's why it's a priority for us to reach it, but at the same time we're being serious about not calling Eigen API-stable too early.\n\nExperimental features may at any time:\n\\li be removed;\n\\li be subject to an API incompatible change;\n\\li introduce API or ABI incompatible changes in your own code if you let them affect your API or ABI.\n\n\\section Experimental_modules Experimental modules\n\nThe following modules are considered entirely experimental, and we make no firm API stability guarantee about them for the time being:\n\\li SVD\n\\li QR\n\\li Cholesky\n\\li Sparse\n\\li Geometry (this one should be mostly stable, but it's a little too early to make a formal guarantee)\n\n\\section Experimental_core Experimental parts of the Core module\n\nIn the Core module, the only classes subject to ABI stability guarantee (meaning that you can use it for data members in your public ABI) is:\n\\li Matrix\n\\li Map\n\nAll other classes offer no ABI guarantee, e.g. the layout of their data can be changed.\n\nThe only classes subject to (even partial) API stability guarantee (meaning that you can safely construct and use objects) are:\n\\li MatrixBase : partial API stability (see below)\n\\li Matrix : full API stability (except for experimental stuff inherited from MatrixBase)\n\\li Map : full API stability (except for experimental stuff inherited from MatrixBase)\n\nAll other classes offer no direct API guarantee, e.g. their methods can be changed; however notice that most classes inherit MatrixBase and that this is where most of their API comes from -- so in practice most of the API is stable.\n\nA few MatrixBase methods are considered experimental, hence not part of any API stability guarantee:\n\\li all methods documented as internal\n\\li all methods hidden in the Doxygen documentation\n\\li all methods marked as experimental\n\\li all methods defined in experimental modules\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/CMakeLists.txt",
    "content": "project(EigenDoc)\n\nset_directory_properties(PROPERTIES EXCLUDE_FROM_ALL TRUE)\n\nproject(EigenDoc)\n\nif(CMAKE_COMPILER_IS_GNUCXX)\n  if(CMAKE_SYSTEM_NAME MATCHES Linux)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -O1 -g1\")\n  endif()\nendif()\n\noption(EIGEN_INTERNAL_DOCUMENTATION \"Build internal documentation\" OFF)\noption(EIGEN_DOC_USE_MATHJAX \"Use MathJax for rendering math in HTML docs\" ON)\n\n# Set some Doxygen flags\nset(EIGEN_DOXY_PROJECT_NAME             \"Eigen\")\nset(EIGEN_DOXY_OUTPUT_DIRECTORY_SUFFIX  \"\")\nset(EIGEN_DOXY_INPUT                    \"\\\"${Eigen_SOURCE_DIR}/Eigen\\\" \\\"${Eigen_SOURCE_DIR}/doc\\\"\")\nset(EIGEN_DOXY_HTML_COLORSTYLE_HUE      \"220\")\nset(EIGEN_DOXY_TAGFILES                 \"\")\n\nif(EIGEN_INTERNAL_DOCUMENTATION)\n  set(EIGEN_DOXY_INTERNAL                 \"YES\")\nelse()\n  set(EIGEN_DOXY_INTERNAL                 \"NO\")\nendif()\n\nif (EIGEN_DOC_USE_MATHJAX)\n  set(EIGEN_DOXY_USE_MATHJAX \"YES\")\nelse ()\n  set(EIGEN_DOXY_USE_MATHJAX \"NO\")\nendif()\n\nconfigure_file(\n  ${CMAKE_CURRENT_SOURCE_DIR}/Doxyfile.in\n  ${CMAKE_CURRENT_BINARY_DIR}/Doxyfile\n)\n\nset(EIGEN_DOXY_PROJECT_NAME             \"Eigen-unsupported\")\nset(EIGEN_DOXY_OUTPUT_DIRECTORY_SUFFIX  \"/unsupported\")\nset(EIGEN_DOXY_INPUT                    \"\\\"${Eigen_SOURCE_DIR}/unsupported/Eigen\\\" \\\"${Eigen_SOURCE_DIR}/unsupported/doc\\\"\")\nset(EIGEN_DOXY_HTML_COLORSTYLE_HUE      \"0\")\nset(EIGEN_DOXY_TAGFILES                 \"\\\"${Eigen_BINARY_DIR}/doc/Eigen.doxytags=..\\\"\")\n#set(EIGEN_DOXY_TAGFILES                 \"\")\n\nconfigure_file(\n  ${CMAKE_CURRENT_SOURCE_DIR}/Doxyfile.in\n  ${CMAKE_CURRENT_BINARY_DIR}/Doxyfile-unsupported\n)\n\nconfigure_file(\n  ${CMAKE_CURRENT_SOURCE_DIR}/eigendoxy_header.html.in\n  ${CMAKE_CURRENT_BINARY_DIR}/eigendoxy_header.html\n)\n\nconfigure_file(\n  ${CMAKE_CURRENT_SOURCE_DIR}/eigendoxy_footer.html.in\n  ${CMAKE_CURRENT_BINARY_DIR}/eigendoxy_footer.html\n)\n\nconfigure_file(\n  ${CMAKE_CURRENT_SOURCE_DIR}/eigendoxy_layout.xml.in\n  ${CMAKE_CURRENT_BINARY_DIR}/eigendoxy_layout.xml\n)\n\nconfigure_file(\n  ${Eigen_SOURCE_DIR}/unsupported/doc/eigendoxy_layout.xml.in\n  ${Eigen_BINARY_DIR}/doc/unsupported/eigendoxy_layout.xml\n)\n\nset(examples_targets \"\")\nset(snippets_targets \"\")\n\nadd_definitions(\"-DEIGEN_MAKING_DOCS\")\nadd_custom_target(all_examples)\n\nadd_subdirectory(examples)\nadd_subdirectory(special_examples)\nadd_subdirectory(snippets)\n\nadd_custom_target(\n  doc-eigen-prerequisites\n  ALL\n  COMMAND ${CMAKE_COMMAND} -E make_directory ${CMAKE_CURRENT_BINARY_DIR}/html/\n  COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/eigen_navtree_hacks.js           ${CMAKE_CURRENT_BINARY_DIR}/html/\n  COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/Eigen_Silly_Professor_64x64.png  ${CMAKE_CURRENT_BINARY_DIR}/html/\n  COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/ftv2pnode.png                    ${CMAKE_CURRENT_BINARY_DIR}/html/\n  COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/ftv2node.png                     ${CMAKE_CURRENT_BINARY_DIR}/html/\n  COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/AsciiQuickReference.txt          ${CMAKE_CURRENT_BINARY_DIR}/html/\n  WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}\n)\n\nadd_custom_target(\n  doc-unsupported-prerequisites\n  ALL\n  COMMAND ${CMAKE_COMMAND} -E make_directory ${Eigen_BINARY_DIR}/doc/html/unsupported\n  COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/eigen_navtree_hacks.js           ${CMAKE_CURRENT_BINARY_DIR}/html/unsupported/\n  COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/Eigen_Silly_Professor_64x64.png  ${CMAKE_CURRENT_BINARY_DIR}/html/unsupported/\n  COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/ftv2pnode.png                    ${CMAKE_CURRENT_BINARY_DIR}/html/unsupported/\n  COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/ftv2node.png                     ${CMAKE_CURRENT_BINARY_DIR}/html/unsupported/\n  WORKING_DIRECTORY ${Eigen_BINARY_DIR}/doc\n)\n\nadd_dependencies(doc-eigen-prerequisites all_snippets all_examples)\nadd_dependencies(doc-unsupported-prerequisites unsupported_snippets unsupported_examples)\n\nadd_custom_target(doc ALL\n  COMMAND doxygen\n  COMMAND doxygen Doxyfile-unsupported\n  COMMAND ${CMAKE_COMMAND} -E copy ${Eigen_BINARY_DIR}/doc/html/group__TopicUnalignedArrayAssert.html ${Eigen_BINARY_DIR}/doc/html/TopicUnalignedArrayAssert.html\n  COMMAND ${CMAKE_COMMAND} -E rename html eigen-doc\n  COMMAND ${CMAKE_COMMAND} -E remove eigen-doc/eigen-doc.tgz eigen-doc/unsupported/_formulas.log eigen-doc/_formulas.log\n  COMMAND ${CMAKE_COMMAND} -E tar cfz eigen-doc.tgz eigen-doc\n  COMMAND ${CMAKE_COMMAND} -E rename eigen-doc.tgz eigen-doc/eigen-doc.tgz\n  COMMAND ${CMAKE_COMMAND} -E rename eigen-doc html\n  WORKING_DIRECTORY ${Eigen_BINARY_DIR}/doc)\n\nadd_dependencies(doc doc-eigen-prerequisites doc-unsupported-prerequisites)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/ClassHierarchy.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicClassHierarchy The class hierarchy\n\nThis page explains the design of the core classes in Eigen's class hierarchy and how they fit together. Casual\nusers probably need not concern themselves with these details, but it may be useful for both advanced users\nand Eigen developers.\n\n\\eigenAutoToc\n\n\n\\section TopicClassHierarchyPrinciples Principles\n\nEigen's class hierarchy is designed so that virtual functions are avoided where their overhead would\nsignificantly impair performance. Instead, Eigen achieves polymorphism with the Curiously Recurring Template\nPattern (CRTP). In this pattern, the base class (for instance, \\c MatrixBase) is in fact a template class, and\nthe derived class (for instance, \\c Matrix) inherits the base class with the derived class itself as a\ntemplate argument (in this case, \\c Matrix inherits from \\c MatrixBase&lt;Matrix&gt;). This allows Eigen to\nresolve the polymorphic function calls at compile time.\n\nIn addition, the design avoids multiple inheritance. One reason for this is that in our experience, some\ncompilers (like MSVC) fail to perform empty base class optimization, which is crucial for our fixed-size\ntypes.\n\n\n\\section TopicClassHierarchyCoreClasses The core classes\n\nThese are the classes that you need to know about if you want to write functions that accept or return Eigen\nobjects.\n\n  - Matrix means plain dense matrix. If \\c m is a \\c %Matrix, then, for instance, \\c m+m is no longer a \n    \\c %Matrix, it is a \"matrix expression\".\n  - MatrixBase means dense matrix expression. This means that a \\c %MatrixBase is something that can be\n    added, matrix-multiplied, LU-decomposed, QR-decomposed... All matrix expression classes, including \n    \\c %Matrix itself, inherit \\c %MatrixBase.\n  - Array means plain dense array. If \\c x is an \\c %Array, then, for instance, \\c x+x is no longer an \n    \\c %Array, it is an \"array expression\".\n  - ArrayBase means dense array expression. This means that an \\c %ArrayBase is something that can be\n    added, array-multiplied, and on which you can perform all sorts of array operations... All array\n    expression classes, including \\c %Array itself, inherit \\c %ArrayBase.\n  - DenseBase means dense (matrix or array) expression. Both \\c %ArrayBase and \\c %MatrixBase inherit\n    \\c %DenseBase. \\c %DenseBase is where all the methods go that apply to dense expressions regardless of\n    whether they are matrix or array expressions. For example, the \\link DenseBase::block() block(...) \\endlink\n    methods are in \\c %DenseBase.\n\n\\section TopicClassHierarchyBaseClasses Base classes\n\nThese classes serve as base classes for the five core classes mentioned above. They are more internal and so\nless interesting for users of the Eigen library.\n\n  - PlainObjectBase means dense (matrix or array) plain object, i.e. something that stores its own dense\n    array of coefficients. This is where, for instance, the \\link PlainObjectBase::resize() resize() \\endlink\n    methods go. \\c %PlainObjectBase is inherited by \\c %Matrix and by \\c %Array. But above, we said that \n    \\c %Matrix inherits \\c %MatrixBase and \\c %Array inherits \\c %ArrayBase. So does that mean multiple\n    inheritance? No, because \\c %PlainObjectBase \\e itself inherits \\c %MatrixBase or \\c %ArrayBase depending\n    on whether we are in the matrix or array case. When we said above that \\c %Matrix inherited \n    \\c %MatrixBase, we omitted to say it does so indirectly via \\c %PlainObjectBase. Same for \\c %Array.\n  - DenseCoeffsBase means something that has dense coefficient accessors. It is a base class for\n    \\c %DenseBase. The reason for \\c %DenseCoeffsBase to exist is that the set of available coefficient\n    accessors is very different depending on whether a dense expression has direct memory access or not (the\n    \\c DirectAccessBit flag). For example, if \\c x is a plain matrix, then \\c x has direct access, and \n    \\c x.transpose() and \\c x.block(...) also have direct access, because their coefficients can be read right\n    off memory, but for example, \\c x+x does not have direct memory access, because obtaining any of its\n    coefficients requires a computation (an addition), it can't be just read off memory.\n  - EigenBase means anything that can be evaluated into a plain dense matrix or array (even if that would\n    be a bad idea). \\c %EigenBase is really the absolute base class for anything that remotely looks like a\n    matrix or array. It is a base class for \\c %DenseCoeffsBase, so it sits below all our dense class\n    hierarchy, but it is not limited to dense expressions. For example, \\c %EigenBase is also inherited by\n    diagonal matrices, sparse matrices, etc...\n\n\n\\section TopicClassHierarchyInheritanceDiagrams Inheritance diagrams\n\nThe inheritance diagram for Matrix looks as follows:\n\n<pre>\nEigenBase&lt;%Matrix&gt;\n  <-- DenseCoeffsBase&lt;%Matrix&gt;    (direct access case)\n    <-- DenseBase&lt;%Matrix&gt;\n      <-- MatrixBase&lt;%Matrix&gt;\n        <-- PlainObjectBase&lt;%Matrix&gt;    (matrix case)\n          <-- Matrix\n</pre>\n\nThe inheritance diagram for Array looks as follows:\n\n<pre>\nEigenBase&lt;%Array&gt;\n  <-- DenseCoeffsBase&lt;%Array&gt;    (direct access case)\n    <-- DenseBase&lt;%Array&gt;\n      <-- ArrayBase&lt;%Array&gt;\n        <-- PlainObjectBase&lt;%Array&gt;    (array case)\n          <-- Array\n</pre>\n\nThe inheritance diagram for some other matrix expression class, here denoted by \\c SomeMatrixXpr, looks as\nfollows:\n\n<pre>\nEigenBase&lt;SomeMatrixXpr&gt;\n  <-- DenseCoeffsBase&lt;SomeMatrixXpr&gt;    (direct access or no direct access case)\n    <-- DenseBase&lt;SomeMatrixXpr&gt;\n      <-- MatrixBase&lt;SomeMatrixXpr&gt;\n        <-- SomeMatrixXpr\n</pre>\n\nThe inheritance diagram for some other array expression class, here denoted by \\c SomeArrayXpr, looks as\nfollows:\n\n<pre>\nEigenBase&lt;SomeArrayXpr&gt;\n  <-- DenseCoeffsBase&lt;SomeArrayXpr&gt;    (direct access or no direct access case)\n    <-- DenseBase&lt;SomeArrayXpr&gt;\n      <-- ArrayBase&lt;SomeArrayXpr&gt;\n        <-- SomeArrayXpr\n</pre>\n\nFinally, consider an example of something that is not a dense expression, for instance a diagonal matrix. The\ncorresponding inheritance diagram is:\n\n<pre>\nEigenBase&lt;%DiagonalMatrix&gt;\n  <-- DiagonalBase&lt;%DiagonalMatrix&gt;\n    <-- DiagonalMatrix\n</pre>\n\n\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/CoeffwiseMathFunctionsTable.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage CoeffwiseMathFunctions Catalog of coefficient-wise math functions\n\n\n<!-- <span style=\"font-size:300%; color:red; font-weight: 900;\">!WORK IN PROGRESS!</span> -->\n\nThis table presents a catalog of the coefficient-wise math functions supported by %Eigen.\nIn this table, \\c a, \\c b, refer to Array objects or expressions, and \\c m refers to a linear algebra Matrix/Vector object. Standard scalar types are abbreviated as follows:\n  - \\c int: \\c i32\n  - \\c float: \\c f\n  - \\c double: \\c d\n  - \\c std::complex<float>: \\c cf\n  - \\c std::complex<double>: \\c cd\n\nFor each row, the first column list the equivalent calls for arrays, and matrices when supported. Of course, all functions are available for matrices by first casting it as an array: \\c m.array().\n\nThe third column gives some hints in the underlying scalar implementation. In most cases, %Eigen does not implement itself the math function but relies on the STL for standard scalar types, or user-provided functions for custom scalar types.\nFor instance, some simply calls the respective function of the STL while preserving <a href=\"http://en.cppreference.com/w/cpp/language/adl\">argument-dependent lookup</a> for custom types.\nThe following:\n\\code\nusing std::foo;\nfoo(a[i]);\n\\endcode\nmeans that the STL's function \\c std::foo will be potentially called if it is compatible with the underlying scalar type. If not, then the user must ensure that an overload of the function foo is available for the given scalar type (usually defined in the same namespace as the given scalar type).\nThis also means that, unless specified, if the function \\c std::foo is available only in some recent c++ versions (e.g., c++11), then the respective %Eigen's function/method will be usable on standard types only if the compiler support the required c++ version.\n\n<table class=\"manual-hl\">\n<tr>\n<th>API</th><th>Description</th><th>Default scalar implementation</th><th>SIMD</th>\n</tr>\n<tr><td colspan=\"4\"></td></tr>\n<tr><th colspan=\"4\">Basic operations</th></tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_abs\n  a.\\link ArrayBase::abs abs\\endlink(); \\n\n  \\link Eigen::abs abs\\endlink(a); \\n\n  m.\\link MatrixBase::cwiseAbs cwiseAbs\\endlink();\n  </td>\n  <td>absolute value (\\f$ |a_i| \\f$) </td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/fabs\">std::abs</a>; \\n\n  abs(a[i]);\n  </td>\n  <td>SSE2, AVX (i32,f,d)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_inverse\n  a.\\link ArrayBase::inverse inverse\\endlink(); \\n\n  \\link Eigen::inverse inverse\\endlink(a); \\n\n  m.\\link MatrixBase::cwiseInverse cwiseInverse\\endlink();\n  </td>\n  <td>inverse value (\\f$ 1/a_i \\f$) </td>\n  <td class=\"code\">\n  1/a[i];\n  </td>\n  <td>All engines (f,d,fc,fd)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_conj\n  a.\\link ArrayBase::conjugate conjugate\\endlink(); \\n\n  \\link Eigen::conj conj\\endlink(a); \\n\n  m.\\link MatrixBase::conjugate conjugate\\endlink();\n  </td>\n  <td><a href=\"https://en.wikipedia.org/wiki/Complex_conjugate\">complex conjugate</a> (\\f$ \\bar{a_i} \\f$),\\n\n  no-op for real </td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/complex/conj\">std::conj</a>; \\n\n  conj(a[i]);\n  </td>\n  <td>All engines (fc,fd)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_arg\n  a.\\link ArrayBase::arg arg\\endlink(); \\n\n  \\link Eigen::arg arg\\endlink(a); \\n\n  m.\\link MatrixBase::cwiseArg cwiseArg\\endlink();\n  </td>\n  <td>phase angle of complex number</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/complex/arg\">std::arg</a>; \\n\n  arg(a[i]);\n  </td>\n  <td>All engines (fc,fd)</td>\n</tr>\n<tr>\n<th colspan=\"4\">Exponential functions</th>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_exp\n  a.\\link ArrayBase::exp exp\\endlink(); \\n\n  \\link Eigen::exp exp\\endlink(a);\n  </td>\n  <td>\\f$ e \\f$ raised to the given power (\\f$ e^{a_i} \\f$) </td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/exp\">std::exp</a>; \\n\n  exp(a[i]);\n  </td>\n  <td>SSE2, AVX (f,d)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_log\n  a.\\link ArrayBase::log log\\endlink(); \\n\n  \\link Eigen::log log\\endlink(a);\n  </td>\n  <td>natural (base \\f$ e \\f$) logarithm (\\f$ \\ln({a_i}) \\f$)</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/log\">std::log</a>; \\n\n  log(a[i]);\n  </td>\n  <td>SSE2, AVX (f)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_log1p\n  a.\\link ArrayBase::log1p log1p\\endlink(); \\n\n  \\link Eigen::log1p log1p\\endlink(a);\n  </td>\n  <td>natural (base \\f$ e \\f$) logarithm of 1 plus \\n the given number (\\f$ \\ln({1+a_i}) \\f$)</td>\n  <td>built-in generic implementation based on \\c log,\\n\n  plus \\c using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/log1p\">\\c std::log1p </a>; \\cpp11</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_log10\n  a.\\link ArrayBase::log10 log10\\endlink(); \\n\n  \\link Eigen::log10 log10\\endlink(a);\n  </td>\n  <td>base 10 logarithm (\\f$ \\log_{10}({a_i}) \\f$)</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/log10\">std::log10</a>; \\n\n  log10(a[i]);\n  </td>\n  <td></td>\n</tr>\n<tr>\n<th colspan=\"4\">Power functions</th>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_pow\n  a.\\link ArrayBase::pow pow\\endlink(b); \\n\n  \\link ArrayBase::pow(const Eigen::ArrayBase< Derived > &x, const Eigen::ArrayBase< ExponentDerived > &exponents) pow\\endlink(a,b);\n  </td>\n  <!-- For some reason Doxygen thinks that pow is in ArrayBase namespace -->\n  <td>raises a number to the given power (\\f$ a_i ^ {b_i} \\f$) \\n \\c a and \\c b can be either an array or scalar.</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/pow\">std::pow</a>; \\n\n  pow(a[i],b[i]);\\n\n  (plus builtin for integer types)</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_sqrt\n  a.\\link ArrayBase::sqrt sqrt\\endlink(); \\n\n  \\link Eigen::sqrt sqrt\\endlink(a);\\n\n  m.\\link MatrixBase::cwiseSqrt cwiseSqrt\\endlink();\n  </td>\n  <td>computes square root (\\f$ \\sqrt a_i \\f$)</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/sqrt\">std::sqrt</a>; \\n\n  sqrt(a[i]);</td>\n  <td>SSE2, AVX (f,d)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_rsqrt\n  a.\\link ArrayBase::rsqrt rsqrt\\endlink(); \\n\n  \\link Eigen::rsqrt rsqrt\\endlink(a);\n  </td>\n  <td><a href=\"https://en.wikipedia.org/wiki/Fast_inverse_square_root\">reciprocal square root</a> (\\f$ 1/{\\sqrt a_i} \\f$)</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/sqrt\">std::sqrt</a>; \\n\n  1/sqrt(a[i]); \\n\n  </td>\n  <td>SSE2, AVX, AltiVec, ZVector (f,d)\\n\n  (approx + 1 Newton iteration)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_square\n  a.\\link ArrayBase::square square\\endlink(); \\n\n  \\link Eigen::square square\\endlink(a);\n  </td>\n  <td>computes square power (\\f$ a_i^2 \\f$)</td>\n  <td class=\"code\">\n  a[i]*a[i]</td>\n  <td>All (i32,f,d,cf,cd)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_cube\n  a.\\link ArrayBase::cube cube\\endlink(); \\n\n  \\link Eigen::cube cube\\endlink(a);\n  </td>\n  <td>computes cubic power (\\f$ a_i^3 \\f$)</td>\n  <td class=\"code\">\n  a[i]*a[i]*a[i]</td>\n  <td>All (i32,f,d,cf,cd)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_abs2\n  a.\\link ArrayBase::abs2 abs2\\endlink(); \\n\n  \\link Eigen::abs2 abs2\\endlink(a);\\n\n  m.\\link MatrixBase::cwiseAbs2 cwiseAbs2\\endlink();\n  </td>\n  <td>computes the squared absolute value (\\f$ |a_i|^2 \\f$)</td>\n  <td class=\"code\">\n  real:    a[i]*a[i] \\n\n  complex:  real(a[i])*real(a[i]) \\n\n  &nbsp;&nbsp;&nbsp;&nbsp;&nbsp;&nbsp; + imag(a[i])*imag(a[i])</td>\n  <td>All (i32,f,d)</td>\n</tr>\n<tr>\n<th colspan=\"4\">Trigonometric functions</th>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_sin\n  a.\\link ArrayBase::sin sin\\endlink(); \\n\n  \\link Eigen::sin sin\\endlink(a);\n  </td>\n  <td>computes sine</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/sin\">std::sin</a>; \\n\n  sin(a[i]);</td>\n  <td>SSE2, AVX (f)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_cos\n  a.\\link ArrayBase::cos cos\\endlink(); \\n\n  \\link Eigen::cos cos\\endlink(a);\n  </td>\n  <td>computes cosine</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/cos\">std::cos</a>; \\n\n  cos(a[i]);</td>\n  <td>SSE2, AVX (f)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_tan\n  a.\\link ArrayBase::tan tan\\endlink(); \\n\n  \\link Eigen::tan tan\\endlink(a);\n  </td>\n  <td>computes tangent</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/tan\">std::tan</a>; \\n\n  tan(a[i]);</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_asin\n  a.\\link ArrayBase::asin asin\\endlink(); \\n\n  \\link Eigen::asin asin\\endlink(a);\n  </td>\n  <td>computes arc sine (\\f$ \\sin^{-1} a_i \\f$)</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/asin\">std::asin</a>; \\n\n  asin(a[i]);</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_acos\n  a.\\link ArrayBase::acos acos\\endlink(); \\n\n  \\link Eigen::acos acos\\endlink(a);\n  </td>\n  <td>computes arc cosine  (\\f$ \\cos^{-1} a_i \\f$)</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/acos\">std::acos</a>; \\n\n  acos(a[i]);</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_atan\n  a.\\link ArrayBase::atan atan\\endlink(); \\n\n  \\link Eigen::atan atan\\endlink(a);\n  </td>\n  <td>computes arc tangent (\\f$ \\tan^{-1} a_i \\f$)</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/atan\">std::atan</a>; \\n\n  atan(a[i]);</td>\n  <td></td>\n</tr>\n<tr>\n<th colspan=\"4\">Hyperbolic functions</th>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_sinh\n  a.\\link ArrayBase::sinh sinh\\endlink(); \\n\n  \\link Eigen::sinh sinh\\endlink(a);\n  </td>\n  <td>computes hyperbolic sine</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/sinh\">std::sinh</a>; \\n\n  sinh(a[i]);</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_cosh\n  a.\\link ArrayBase::cosh cohs\\endlink(); \\n\n  \\link Eigen::cosh cosh\\endlink(a);\n  </td>\n  <td>computes hyperbolic cosine</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/cosh\">std::cosh</a>; \\n\n  cosh(a[i]);</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_tanh\n  a.\\link ArrayBase::tanh tanh\\endlink(); \\n\n  \\link Eigen::tanh tanh\\endlink(a);\n  </td>\n  <td>computes hyperbolic tangent</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/tanh\">std::tanh</a>; \\n\n  tanh(a[i]);</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_asinh\n  a.\\link ArrayBase::asinh asinh\\endlink(); \\n\n  \\link Eigen::asinh asinh\\endlink(a);\n  </td>\n  <td>computes inverse hyperbolic sine</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/asinh\">std::asinh</a>; \\n\n  asinh(a[i]);</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_acosh\n  a.\\link ArrayBase::acosh cohs\\endlink(); \\n\n  \\link Eigen::acosh acosh\\endlink(a);\n  </td>\n  <td>computes hyperbolic cosine</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/acosh\">std::acosh</a>; \\n\n  acosh(a[i]);</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_atanh\n  a.\\link ArrayBase::atanh atanh\\endlink(); \\n\n  \\link Eigen::atanh atanh\\endlink(a);\n  </td>\n  <td>computes hyperbolic tangent</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/atanh\">std::atanh</a>; \\n\n  atanh(a[i]);</td>\n  <td></td>\n</tr>\n<tr>\n<th colspan=\"4\">Nearest integer floating point operations</th>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_ceil\n  a.\\link ArrayBase::ceil ceil\\endlink(); \\n\n  \\link Eigen::ceil ceil\\endlink(a);\n  </td>\n  <td>nearest integer not less than the given value</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/ceil\">std::ceil</a>; \\n\n  ceil(a[i]);</td>\n  <td>SSE4,AVX,ZVector (f,d)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_floor\n  a.\\link ArrayBase::floor floor\\endlink(); \\n\n  \\link Eigen::floor floor\\endlink(a);\n  </td>\n  <td>nearest integer not greater than the given value</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/floor\">std::floor</a>; \\n\n  floor(a[i]);</td>\n  <td>SSE4,AVX,ZVector (f,d)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_round\n  a.\\link ArrayBase::round round\\endlink(); \\n\n  \\link Eigen::round round\\endlink(a);\n  </td>\n  <td>nearest integer, \\n rounding away from zero in halfway cases</td>\n  <td>built-in generic implementation \\n based on \\c floor and \\c ceil,\\n\n  plus \\c using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/round\">\\c std::round </a>; \\cpp11</td>\n  <td>SSE4,AVX,ZVector (f,d)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_rint\n  a.\\link ArrayBase::rint rint\\endlink(); \\n\n  \\link Eigen::rint rint\\endlink(a);\n  </td>\n  <td>nearest integer, \\n rounding to nearest even in halfway cases</td>\n  <td>built-in generic implementation using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/rint\">\\c std::rint </a>; \\cpp11\n  or <a href=\"http://en.cppreference.com/w/c/numeric/math/rint\">\\c rintf </a>; </td>\n  <td>SSE4,AVX (f,d)</td>\n</tr>\n<tr>\n<th colspan=\"4\">Floating point manipulation functions</th>\n</tr>\n<tr>\n<th colspan=\"4\">Classification and comparison</th>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_isfinite\n  a.\\link ArrayBase::isFinite isFinite\\endlink(); \\n\n  \\link Eigen::isfinite isfinite\\endlink(a);\n  </td>\n  <td>checks if the given number has finite value</td>\n  <td>built-in generic implementation,\\n\n  plus \\c using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/isfinite\">\\c std::isfinite </a>; \\cpp11</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_isinf\n  a.\\link ArrayBase::isInf isInf\\endlink(); \\n\n  \\link Eigen::isinf isinf\\endlink(a);\n  </td>\n  <td>checks if the given number is infinite</td>\n  <td>built-in generic implementation,\\n\n  plus \\c using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/isinf\">\\c std::isinf </a>; \\cpp11</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_isnan\n  a.\\link ArrayBase::isNaN isNaN\\endlink(); \\n\n  \\link Eigen::isnan isnan\\endlink(a);\n  </td>\n  <td>checks if the given number is not a number</td>\n  <td>built-in generic implementation,\\n\n  plus \\c using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/isnan\">\\c std::isnan </a>; \\cpp11</td>\n  <td></td>\n</tr>\n<tr>\n<th colspan=\"4\">Error and gamma functions</th>\n</tr>\n<tr> <td colspan=\"4\">  Require \\c \\#include \\c <unsupported/Eigen/SpecialFunctions> </td></tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_erf\n  a.\\link ArrayBase::erf erf\\endlink(); \\n\n  \\link Eigen::erf erf\\endlink(a);\n  </td>\n  <td>error function</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/erf\">std::erf</a>; \\cpp11 \\n\n  erf(a[i]);\n  </td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_erfc\n  a.\\link ArrayBase::erfc erfc\\endlink(); \\n\n  \\link Eigen::erfc erfc\\endlink(a);\n  </td>\n  <td>complementary error function</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/erfc\">std::erfc</a>; \\cpp11 \\n\n  erfc(a[i]);\n  </td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_lgamma\n  a.\\link ArrayBase::lgamma lgamma\\endlink(); \\n\n  \\link Eigen::lgamma lgamma\\endlink(a);\n  </td>\n  <td>natural logarithm of the gamma function</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/lgamma\">std::lgamma</a>; \\cpp11 \\n\n  lgamma(a[i]);\n  </td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_digamma\n  a.\\link ArrayBase::digamma digamma\\endlink(); \\n\n  \\link Eigen::digamma digamma\\endlink(a);\n  </td>\n  <td><a href=\"https://en.wikipedia.org/wiki/Digamma_function\">logarithmic derivative of the gamma function</a></td>\n  <td>\n  built-in for float and double\n  </td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_igamma\n  \\link Eigen::igamma igamma\\endlink(a,x);\n  </td>\n  <td><a href=\"https://en.wikipedia.org/wiki/Incomplete_gamma_function\">lower incomplete gamma integral</a>\n  \\n \\f$ \\gamma(a_i,x_i)= \\frac{1}{|a_i|} \\int_{0}^{x_i}e^{\\text{-}t} t^{a_i-1} \\mathrm{d} t \\f$</td>\n  <td>\n  built-in for float and double,\\n but requires \\cpp11\n  </td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_igammac\n  \\link Eigen::igammac igammac\\endlink(a,x);\n  </td>\n  <td><a href=\"https://en.wikipedia.org/wiki/Incomplete_gamma_function\">upper incomplete gamma integral</a>\n  \\n \\f$ \\Gamma(a_i,x_i) = \\frac{1}{|a_i|} \\int_{x_i}^{\\infty}e^{\\text{-}t} t^{a_i-1} \\mathrm{d} t \\f$</td>\n  <td>\n  built-in for float and double,\\n but requires \\cpp11\n  </td>\n  <td></td>\n</tr>\n<tr>\n<th colspan=\"4\">Special functions</th>\n</tr>\n<tr> <td colspan=\"4\">  Require \\c \\#include \\c <unsupported/Eigen/SpecialFunctions> </td></tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_polygamma\n  \\link Eigen::polygamma polygamma\\endlink(n,x);\n  </td>\n  <td><a href=\"https://en.wikipedia.org/wiki/Polygamma_function\">n-th derivative of digamma at x</a></td>\n  <td>\n  built-in generic based on\\n <a href=\"#cwisetable_lgamma\">\\c lgamma </a>,\n  <a href=\"#cwisetable_digamma\"> \\c digamma </a>\n  and <a href=\"#cwisetable_zeta\">\\c zeta </a>.\n  </td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_betainc\n  \\link Eigen::betainc betainc\\endlink(a,b,x);\n  </td>\n  <td><a href=\"https://en.wikipedia.org/wiki/Beta_function#Incomplete_beta_function\">Incomplete beta function</a></td>\n  <td>\n  built-in for float and double,\\n but requires \\cpp11\n  </td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_zeta\n  \\link Eigen::zeta zeta\\endlink(a,b); \\n\n  a.\\link ArrayBase::zeta zeta\\endlink(b);\n  </td>\n  <td><a href=\"https://en.wikipedia.org/wiki/Hurwitz_zeta_function\">Hurwitz zeta function</a>\n  \\n \\f$ \\zeta(a_i,b_i)=\\sum_{k=0}^{\\infty}(b_i+k)^{\\text{-}a_i} \\f$</td>\n  <td>\n  built-in for float and double\n  </td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_ndtri\n  a.\\link ArrayBase::ndtri ndtri\\endlink(); \\n\n  \\link Eigen::ndtri ndtri\\endlink(a);\n  </td>\n  <td>Inverse of the CDF of the Normal distribution function</td>\n  <td>\n  built-in for float and double\n  </td>\n  <td></td>\n</tr>\n<tr><td colspan=\"4\"></td></tr>\n</table>\n\n\\n\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/CustomizingEigen_CustomScalar.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicCustomizing_CustomScalar Using custom scalar types\n\\anchor user_defined_scalars\n\nBy default, Eigen currently supports standard floating-point types (\\c float, \\c double, \\c std::complex<float>, \\c std::complex<double>, \\c long \\c double), as well as all native integer types (e.g., \\c int, \\c unsigned \\c int, \\c short, etc.), and \\c bool.\nOn x86-64 systems, \\c long \\c double permits to locally enforces the use of x87 registers with extended accuracy (in comparison to SSE).\n\nIn order to add support for a custom type \\c T you need:\n-# make sure the common operator (+,-,*,/,etc.) are supported by the type \\c T\n-# add a specialization of struct Eigen::NumTraits<T> (see \\ref NumTraits)\n-# define the math functions that makes sense for your type. This includes standard ones like sqrt, pow, sin, tan, conj, real, imag, etc, as well as abs2 which is Eigen specific.\n     (see the file Eigen/src/Core/MathFunctions.h)\n\nThe math function should be defined in the same namespace than \\c T, or in the \\c std namespace though that second approach is not recommended.\n\nHere is a concrete example adding support for the Adolc's \\c adouble type. <a href=\"https://projects.coin-or.org/ADOL-C\">Adolc</a> is an automatic differentiation library. The type \\c adouble is basically a real value tracking the values of any number of partial derivatives.\n\n\\code\n#ifndef ADOLCSUPPORT_H\n#define ADOLCSUPPORT_H\n\n#define ADOLC_TAPELESS\n#include <adolc/adouble.h>\n#include <Eigen/Core>\n\nnamespace Eigen {\n\ntemplate<> struct NumTraits<adtl::adouble>\n : NumTraits<double> // permits to get the epsilon, dummy_precision, lowest, highest functions\n{\n  typedef adtl::adouble Real;\n  typedef adtl::adouble NonInteger;\n  typedef adtl::adouble Nested;\n\n  enum {\n    IsComplex = 0,\n    IsInteger = 0,\n    IsSigned = 1,\n    RequireInitialization = 1,\n    ReadCost = 1,\n    AddCost = 3,\n    MulCost = 3\n  };\n};\n\n}\n\nnamespace adtl {\n\ninline const adouble& conj(const adouble& x)  { return x; }\ninline const adouble& real(const adouble& x)  { return x; }\ninline adouble imag(const adouble&)    { return 0.; }\ninline adouble abs(const adouble&  x)  { return fabs(x); }\ninline adouble abs2(const adouble& x)  { return x*x; }\n\n}\n\n#endif // ADOLCSUPPORT_H\n\\endcode\n\nThis other example adds support for the \\c mpq_class type from <a href=\"https://gmplib.org/\">GMP</a>. It shows in particular how to change the way Eigen picks the best pivot during LU factorization. It selects the coefficient with the highest score, where the score is by default the absolute value of a number, but we can define a different score, for instance to prefer pivots with a more compact representation (this is an example, not a recommendation). Note that the scores should always be non-negative and only zero is allowed to have a score of zero. Also, this can interact badly with thresholds for inexact scalar types.\n\n\\code\n#include <gmpxx.h>\n#include <Eigen/Core>\n#include <boost/operators.hpp>\n\nnamespace Eigen {\n  template<> struct NumTraits<mpq_class> : GenericNumTraits<mpq_class>\n  {\n    typedef mpq_class Real;\n    typedef mpq_class NonInteger;\n    typedef mpq_class Nested;\n\n    static inline Real epsilon() { return 0; }\n    static inline Real dummy_precision() { return 0; }\n    static inline int digits10() { return 0; }\n\n    enum {\n      IsInteger = 0,\n      IsSigned = 1,\n      IsComplex = 0,\n      RequireInitialization = 1,\n      ReadCost = 6,\n      AddCost = 150,\n      MulCost = 100\n    };\n  };\n\n  namespace internal {\n\n    template<> struct scalar_score_coeff_op<mpq_class> {\n      struct result_type : boost::totally_ordered1<result_type> {\n        std::size_t len;\n        result_type(int i = 0) : len(i) {} // Eigen uses Score(0) and Score()\n        result_type(mpq_class const& q) :\n          len(mpz_size(q.get_num_mpz_t())+\n              mpz_size(q.get_den_mpz_t())-1) {}\n        friend bool operator<(result_type x, result_type y) {\n          // 0 is the worst possible pivot\n          if (x.len == 0) return y.len > 0;\n          if (y.len == 0) return false;\n          // Prefer a pivot with a small representation\n          return x.len > y.len;\n        }\n        friend bool operator==(result_type x, result_type y) {\n          // Only used to test if the score is 0\n          return x.len == y.len;\n        }\n      };\n      result_type operator()(mpq_class const& x) const { return x; }\n    };\n  }\n}\n\\endcode\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/CustomizingEigen_InheritingMatrix.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicCustomizing_InheritingMatrix Inheriting from Matrix\n\nBefore inheriting from Matrix, be really, I mean REALLY, sure that using\nEIGEN_MATRIX_PLUGIN is not what you really want (see previous section).\nIf you just need to add few members to Matrix, this is the way to go.\n\nAn example of when you actually need to inherit Matrix, is when you\nhave several layers of heritage such as \nMyVerySpecificVector1, MyVerySpecificVector2 -> MyVector1 -> Matrix and\nMyVerySpecificVector3, MyVerySpecificVector4 -> MyVector2 -> Matrix.\n\nIn order for your object to work within the %Eigen framework, you need to\ndefine a few members in your inherited class.\n\nHere is a minimalistic example:\n\n\\include CustomizingEigen_Inheritance.cpp\n\nOutput: \\verbinclude CustomizingEigen_Inheritance.out\n\nThis is the kind of error you can get if you don't provide those methods\n\\verbatim\nerror: no match for ‘operator=’ in ‘v = Eigen::operator*(\nconst Eigen::MatrixBase<Eigen::Matrix<double, -0x000000001, 1, 0, -0x000000001, 1> >::Scalar&, \nconst Eigen::MatrixBase<Eigen::Matrix<double, -0x000000001, 1> >::StorageBaseType&)\n(((const Eigen::MatrixBase<Eigen::Matrix<double, -0x000000001, 1> >::StorageBaseType&)\n((const Eigen::MatrixBase<Eigen::Matrix<double, -0x000000001, 1> >::StorageBaseType*)(& v))))’\n\\endverbatim\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/CustomizingEigen_NullaryExpr.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicCustomizing_NullaryExpr Matrix manipulation via nullary-expressions\n\n\nThe main purpose of the class CwiseNullaryOp is to define \\em procedural matrices such as constant or random matrices as returned by the Ones(), Zero(), Constant(), Identity() and Random() methods.\nNevertheless, with some imagination it is possible to accomplish very sophisticated matrix manipulation with minimal efforts such that \\ref TopicNewExpressionType \"implementing new expression\" is rarely needed.\n\n\\section NullaryExpr_Circulant Example 1: circulant matrix\n\nTo explore these possibilities let us start with the  \\em circulant example of the \\ref TopicNewExpressionType \"implementing new expression\" topic.\nLet us recall that a circulant matrix is a matrix where each column is the same as the\ncolumn to the left, except that it is cyclically shifted downwards.\nFor example, here is a 4-by-4 circulant matrix:\n\\f[ \\begin{bmatrix}\n    1 & 8 & 4 & 2 \\\\\n    2 & 1 & 8 & 4 \\\\\n    4 & 2 & 1 & 8 \\\\\n    8 & 4 & 2 & 1\n\\end{bmatrix} \\f]\nA circulant matrix is uniquely determined by its first column. We wish\nto write a function \\c makeCirculant which, given the first column,\nreturns an expression representing the circulant matrix.\n\nFor this exercise, the return type of \\c makeCirculant will be a CwiseNullaryOp that we need to instantiate with:\n1 - a proper \\c circulant_functor storing the input vector and implementing the adequate coefficient accessor \\c operator(i,j)\n2 - a template instantiation of class Matrix conveying compile-time information such as the scalar type, sizes, and preferred storage layout.\n\nCalling \\c ArgType the type of the input vector, we can construct the equivalent squared Matrix type as follows:\n\n\\snippet make_circulant2.cpp square\n\nThis little helper structure will help us to implement our \\c makeCirculant function as follows:\n\n\\snippet make_circulant2.cpp makeCirculant\n\nAs usual, our function takes as argument a \\c MatrixBase (see this \\ref TopicFunctionTakingEigenTypes \"page\" for more details).\nThen, the CwiseNullaryOp object is constructed through the DenseBase::NullaryExpr static method with the adequate runtime sizes.\n\nThen, we need to implement our \\c circulant_functor, which is a straightforward exercise:\n\n\\snippet make_circulant2.cpp circulant_func\n\nWe are now all set to try our new feature:\n\n\\snippet make_circulant2.cpp main\n\n\nIf all the fragments are combined, the following output is produced,\nshowing that the program works as expected:\n\n\\include make_circulant2.out\n\nThis implementation of \\c makeCirculant is much simpler than \\ref TopicNewExpressionType \"defining a new expression\" from scratch.\n\n\n\\section NullaryExpr_Indexing Example 2: indexing rows and columns\n\nThe goal here is to mimic MatLab's ability to index a matrix through two vectors of indices referencing the rows and columns to be picked respectively, like this:\n\n\\snippet nullary_indexing.out main1\n\nTo this end, let us first write a nullary-functor storing references to the input matrix and to the two arrays of indices, and implementing the required \\c operator()(i,j):\n\n\\snippet nullary_indexing.cpp functor\n\nThen, let's create an \\c indexing(A,rows,cols) function creating the nullary expression:\n\n\\snippet nullary_indexing.cpp function\n\nFinally, here is an example of how this function can be used:\n\n\\snippet nullary_indexing.cpp main1\n\nThis straightforward implementation is already quite powerful as the row or column index arrays can also be expressions to perform offsetting, modulo, striding, reverse, etc.\n\n\\snippet nullary_indexing.cpp main2\n\nand the output is:\n\n\\snippet nullary_indexing.out main2\n\n*/\n\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/CustomizingEigen_Plugins.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicCustomizing_Plugins Extending MatrixBase (and other classes)\n\nIn this section we will see how to add custom methods to MatrixBase. Since all expressions and matrix types inherit MatrixBase, adding a method to MatrixBase make it immediately available to all expressions ! A typical use case is, for instance, to make Eigen compatible with another API.\n\nYou certainly know that in C++ it is not possible to add methods to an existing class. So how that's possible ? Here the trick is to include in the declaration of MatrixBase a file defined by the preprocessor token \\c EIGEN_MATRIXBASE_PLUGIN:\n\\code\nclass MatrixBase {\n  // ...\n  #ifdef EIGEN_MATRIXBASE_PLUGIN\n  #include EIGEN_MATRIXBASE_PLUGIN\n  #endif\n};\n\\endcode\nTherefore to extend MatrixBase with your own methods you just have to create a file with your method declaration and define EIGEN_MATRIXBASE_PLUGIN before you include any Eigen's header file.\n\nYou can extend many of the other classes used in Eigen by defining similarly named preprocessor symbols. For instance, define \\c EIGEN_ARRAYBASE_PLUGIN if you want to extend the ArrayBase class. A full list of classes that can be extended in this way and the corresponding preprocessor symbols can be found on our page \\ref TopicPreprocessorDirectives.\n\nHere is an example of an extension file for adding methods to MatrixBase: \\n\n\\b MatrixBaseAddons.h\n\\code\ninline Scalar at(uint i, uint j) const { return this->operator()(i,j); }\ninline Scalar& at(uint i, uint j) { return this->operator()(i,j); }\ninline Scalar at(uint i) const { return this->operator[](i); }\ninline Scalar& at(uint i) { return this->operator[](i); }\n\ninline RealScalar squaredLength() const { return squaredNorm(); }\ninline RealScalar length() const { return norm(); }\ninline RealScalar invLength(void) const { return fast_inv_sqrt(squaredNorm()); }\n\ntemplate<typename OtherDerived>\ninline Scalar squaredDistanceTo(const MatrixBase<OtherDerived>& other) const\n{ return (derived() - other.derived()).squaredNorm(); }\n\ntemplate<typename OtherDerived>\ninline RealScalar distanceTo(const MatrixBase<OtherDerived>& other) const\n{ return internal::sqrt(derived().squaredDistanceTo(other)); }\n\ninline void scaleTo(RealScalar l) { RealScalar vl = norm(); if (vl>1e-9) derived() *= (l/vl); }\n\ninline Transpose<Derived> transposed() {return this->transpose();}\ninline const Transpose<Derived> transposed() const {return this->transpose();}\n\ninline uint minComponentId(void) const  { int i; this->minCoeff(&i); return i; }\ninline uint maxComponentId(void) const  { int i; this->maxCoeff(&i); return i; }\n\ntemplate<typename OtherDerived>\nvoid makeFloor(const MatrixBase<OtherDerived>& other) { derived() = derived().cwiseMin(other.derived()); }\ntemplate<typename OtherDerived>\nvoid makeCeil(const MatrixBase<OtherDerived>& other) { derived() = derived().cwiseMax(other.derived()); }\n\nconst CwiseBinaryOp<internal::scalar_sum_op<Scalar>, const Derived, const ConstantReturnType>\noperator+(const Scalar& scalar) const\n{ return CwiseBinaryOp<internal::scalar_sum_op<Scalar>, const Derived, const ConstantReturnType>(derived(), Constant(rows(),cols(),scalar)); }\n\nfriend const CwiseBinaryOp<internal::scalar_sum_op<Scalar>, const ConstantReturnType, Derived>\noperator+(const Scalar& scalar, const MatrixBase<Derived>& mat)\n{ return CwiseBinaryOp<internal::scalar_sum_op<Scalar>, const ConstantReturnType, Derived>(Constant(rows(),cols(),scalar), mat.derived()); }\n\\endcode\n\nThen one can the following declaration in the config.h or whatever prerequisites header file of his project:\n\\code\n#define EIGEN_MATRIXBASE_PLUGIN \"MatrixBaseAddons.h\"\n\\endcode\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/DenseDecompositionBenchmark.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage DenseDecompositionBenchmark Benchmark of dense decompositions\n\nThis page presents a speed comparison of the dense matrix decompositions offered by %Eigen for a wide range of square matrices and overconstrained problems.\n\nFor a more general overview on the features and numerical robustness of linear solvers and decompositions, check this \\link TopicLinearAlgebraDecompositions table \\endlink.\n\nThis benchmark has been run on a laptop equipped with an Intel core i7 \\@ 2,6 GHz, and compiled with clang with \\b AVX and \\b FMA instruction sets enabled but without multi-threading.\nIt uses \\b single \\b precision \\b float numbers. For double, you can get a good estimate by multiplying the timings by a factor 2.\n\nThe square matrices are symmetric, and for the overconstrained matrices, the reported timmings include the cost to compute the symmetric covariance matrix \\f$ A^T A \\f$ for the first four solvers based on Cholesky and LU, as denoted by the \\b * symbol (top-right corner part of the table).\nTimings are in \\b milliseconds, and factors are relative to the LLT decomposition which is the fastest but also the least general and robust.\n\n<table class=\"manual\">\n<tr><th>solver/size</th>\n  <th>8x8</th>  <th>100x100</th>  <th>1000x1000</th>  <th>4000x4000</th>  <th>10000x8</th>  <th>10000x100</th>  <th>10000x1000</th>  <th>10000x4000</th></tr>\n<tr><td>LLT</td><td>0.05</td><td>0.42</td><td>5.83</td><td>374.55</td><td>6.79 <sup><a href=\"#note_ls\">*</a></sup></td><td>30.15 <sup><a href=\"#note_ls\">*</a></sup></td><td>236.34 <sup><a href=\"#note_ls\">*</a></sup></td><td>3847.17 <sup><a href=\"#note_ls\">*</a></sup></td></tr>\n<tr class=\"alt\"><td>LDLT</td><td>0.07 (x1.3)</td><td>0.65 (x1.5)</td><td>26.86 (x4.6)</td><td>2361.18 (x6.3)</td><td>6.81 (x1) <sup><a href=\"#note_ls\">*</a></sup></td><td>31.91 (x1.1) <sup><a href=\"#note_ls\">*</a></sup></td><td>252.61 (x1.1) <sup><a href=\"#note_ls\">*</a></sup></td><td>5807.66 (x1.5) <sup><a href=\"#note_ls\">*</a></sup></td></tr>\n<tr><td>PartialPivLU</td><td>0.08 (x1.5)</td><td>0.69 (x1.6)</td><td>15.63 (x2.7)</td><td>709.32 (x1.9)</td><td>6.81 (x1) <sup><a href=\"#note_ls\">*</a></sup></td><td>31.32 (x1) <sup><a href=\"#note_ls\">*</a></sup></td><td>241.68 (x1) <sup><a href=\"#note_ls\">*</a></sup></td><td>4270.48 (x1.1) <sup><a href=\"#note_ls\">*</a></sup></td></tr>\n<tr class=\"alt\"><td>FullPivLU</td><td>0.1 (x1.9)</td><td>4.48 (x10.6)</td><td>281.33 (x48.2)</td><td>-</td><td>6.83 (x1) <sup><a href=\"#note_ls\">*</a></sup></td><td>32.67 (x1.1) <sup><a href=\"#note_ls\">*</a></sup></td><td>498.25 (x2.1) <sup><a href=\"#note_ls\">*</a></sup></td><td>-</td></tr>\n<tr><td>HouseholderQR</td><td>0.19 (x3.5)</td><td>2.18 (x5.2)</td><td>23.42 (x4)</td><td>1337.52 (x3.6)</td><td>34.26 (x5)</td><td>129.01 (x4.3)</td><td>377.37 (x1.6)</td><td>4839.1 (x1.3)</td></tr>\n<tr class=\"alt\"><td>ColPivHouseholderQR</td><td>0.23 (x4.3)</td><td>2.23 (x5.3)</td><td>103.34 (x17.7)</td><td>9987.16 (x26.7)</td><td>36.05 (x5.3)</td><td>163.18 (x5.4)</td><td>2354.08 (x10)</td><td>37860.5 (x9.8)</td></tr>\n<tr><td>CompleteOrthogonalDecomposition</td><td>0.23 (x4.3)</td><td>2.22 (x5.2)</td><td>99.44 (x17.1)</td><td>10555.3 (x28.2)</td><td>35.75 (x5.3)</td><td>169.39 (x5.6)</td><td>2150.56 (x9.1)</td><td>36981.8 (x9.6)</td></tr>\n<tr class=\"alt\"><td>FullPivHouseholderQR</td><td>0.23 (x4.3)</td><td>4.64 (x11)</td><td>289.1 (x49.6)</td><td>-</td><td>69.38 (x10.2)</td><td>446.73 (x14.8)</td><td>4852.12 (x20.5)</td><td>-</td></tr>\n<tr><td>JacobiSVD</td><td>1.01 (x18.6)</td><td>71.43 (x168.4)</td><td>-</td><td>-</td><td>113.81 (x16.7)</td><td>1179.66 (x39.1)</td><td>-</td><td>-</td></tr>\n<tr class=\"alt\"><td>BDCSVD</td><td>1.07 (x19.7)</td><td>21.83 (x51.5)</td><td>331.77 (x56.9)</td><td>18587.9 (x49.6)</td><td>110.53 (x16.3)</td><td>397.67 (x13.2)</td><td>2975 (x12.6)</td><td>48593.2 (x12.6)</td></tr>\n</table>\n\n<a name=\"note_ls\">\\b *: </a> This decomposition do not support direct least-square solving for over-constrained problems, and the reported timing include the cost to form the symmetric covariance matrix \\f$ A^T A \\f$.\n\n\\b Observations:\n + LLT is always the fastest solvers.\n + For largely over-constrained problems, the cost of Cholesky/LU decompositions is dominated by the computation of the symmetric covariance matrix.\n + For large problem sizes, only the decomposition implementing a cache-friendly blocking strategy scale well. Those include LLT, PartialPivLU, HouseholderQR, and BDCSVD. This explain why for a 4k x 4k matrix, HouseholderQR is faster than LDLT. In the future, LDLT and ColPivHouseholderQR will also implement blocking strategies.\n + CompleteOrthogonalDecomposition is based on ColPivHouseholderQR and they thus achieve the same level of performance.\n\nThe above table has been generated by the <a href=\"https://gitlab.com/libeigen/eigen/raw/master/bench/dense_solvers.cpp\">bench/dense_solvers.cpp</a> file, feel-free to hack it to generate a table matching your hardware, compiler, and favorite problem sizes.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/Doxyfile.in",
    "content": "# Doxyfile 1.8.1.1\n\n# This file describes the settings to be used by the documentation system\n# doxygen (www.doxygen.org) for a project.\n#\n# All text after a hash (#) is considered a comment and will be ignored.\n# The format is:\n#       TAG = value [value, ...]\n# For lists items can also be appended using:\n#       TAG += value [value, ...]\n# Values that contain spaces should be placed between quotes (\" \").\n\n#---------------------------------------------------------------------------\n# Project related configuration options\n#---------------------------------------------------------------------------\n\n# This tag specifies the encoding used for all characters in the config file\n# that follow. The default is UTF-8 which is also the encoding used for all\n# text before the first occurrence of this tag. Doxygen uses libiconv (or the\n# iconv built into libc) for the transcoding. See\n# http://www.gnu.org/software/libiconv for the list of possible encodings.\n\nDOXYFILE_ENCODING      = UTF-8\n\n# The PROJECT_NAME tag is a single word (or sequence of words) that should\n# identify the project. Note that if you do not use Doxywizard you need\n# to put quotes around the project name if it contains spaces.\n\nPROJECT_NAME           = ${EIGEN_DOXY_PROJECT_NAME}\n\n# The PROJECT_NUMBER tag can be used to enter a project or revision number.\n# This could be handy for archiving the generated documentation or\n# if some version control system is used.\n\n# EIGEN_VERSION is set in the root CMakeLists.txt\n\nPROJECT_NUMBER         = \"${EIGEN_VERSION}\"\n\n# Using the PROJECT_BRIEF tag one can provide an optional one line description\n# for a project that appears at the top of each page and should give viewer\n# a quick idea about the purpose of the project. Keep the description short.\n\nPROJECT_BRIEF          =\n\n# With the PROJECT_LOGO tag one can specify an logo or icon that is\n# included in the documentation. The maximum height of the logo should not\n# exceed 55 pixels and the maximum width should not exceed 200 pixels.\n# Doxygen will copy the logo to the output directory.\n\nPROJECT_LOGO           = \"${Eigen_SOURCE_DIR}/doc/Eigen_Silly_Professor_64x64.png\"\n\n# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute)\n# base path where the generated documentation will be put.\n# If a relative path is entered, it will be relative to the location\n# where doxygen was started. If left blank the current directory will be used.\n\nOUTPUT_DIRECTORY       = \"${Eigen_BINARY_DIR}/doc${EIGEN_DOXY_OUTPUT_DIRECTORY_SUFFIX}\"\n\n# If the CREATE_SUBDIRS tag is set to YES, then doxygen will create\n# 4096 sub-directories (in 2 levels) under the output directory of each output\n# format and will distribute the generated files over these directories.\n# Enabling this option can be useful when feeding doxygen a huge amount of\n# source files, where putting all generated files in the same directory would\n# otherwise cause performance problems for the file system.\n\nCREATE_SUBDIRS         = NO\n\n# The OUTPUT_LANGUAGE tag is used to specify the language in which all\n# documentation generated by doxygen is written. Doxygen will use this\n# information to generate all constant output in the proper language.\n# The default language is English, other supported languages are:\n# Afrikaans, Arabic, Brazilian, Catalan, Chinese, Chinese-Traditional,\n# Croatian, Czech, Danish, Dutch, Esperanto, Farsi, Finnish, French, German,\n# Greek, Hungarian, Italian, Japanese, Japanese-en (Japanese with English\n# messages), Korean, Korean-en, Lithuanian, Norwegian, Macedonian, Persian,\n# Polish, Portuguese, Romanian, Russian, Serbian, Serbian-Cyrillic, Slovak,\n# Slovene, Spanish, Swedish, Ukrainian, and Vietnamese.\n\nOUTPUT_LANGUAGE        = English\n\n# If the BRIEF_MEMBER_DESC tag is set to YES (the default) Doxygen will\n# include brief member descriptions after the members that are listed in\n# the file and class documentation (similar to JavaDoc).\n# Set to NO to disable this.\n\nBRIEF_MEMBER_DESC      = YES\n\n# If the REPEAT_BRIEF tag is set to YES (the default) Doxygen will prepend\n# the brief description of a member or function before the detailed description.\n# Note: if both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the\n# brief descriptions will be completely suppressed.\n\nREPEAT_BRIEF           = YES\n\n# This tag implements a quasi-intelligent brief description abbreviator\n# that is used to form the text in various listings. Each string\n# in this list, if found as the leading text of the brief description, will be\n# stripped from the text and the result after processing the whole list, is\n# used as the annotated text. Otherwise, the brief description is used as-is.\n# If left blank, the following values are used (\"$name\" is automatically\n# replaced with the name of the entity): \"The $name class\" \"The $name widget\"\n# \"The $name file\" \"is\" \"provides\" \"specifies\" \"contains\"\n# \"represents\" \"a\" \"an\" \"the\"\n\nABBREVIATE_BRIEF       = \"The $name class\" \\\n                         \"The $name widget\" \\\n                         \"The $name file\" \\\n                         is \\\n                         provides \\\n                         specifies \\\n                         contains \\\n                         represents \\\n                         a \\\n                         an \\\n                         the\n\n# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then\n# Doxygen will generate a detailed section even if there is only a brief\n# description.\n\nALWAYS_DETAILED_SEC    = NO\n\n# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all\n# inherited members of a class in the documentation of that class as if those\n# members were ordinary class members. Constructors, destructors and assignment\n# operators of the base classes will not be shown.\n\nINLINE_INHERITED_MEMB  = NO\n\n# If the FULL_PATH_NAMES tag is set to YES then Doxygen will prepend the full\n# path before files name in the file list and in the header files. If set\n# to NO the shortest path that makes the file name unique will be used.\n\nFULL_PATH_NAMES        = NO\n\n# If the FULL_PATH_NAMES tag is set to YES then the STRIP_FROM_PATH tag\n# can be used to strip a user-defined part of the path. Stripping is\n# only done if one of the specified strings matches the left-hand part of\n# the path. The tag can be used to show relative paths in the file list.\n# If left blank the directory from which doxygen is run is used as the\n# path to strip.\n\nSTRIP_FROM_PATH        =\n\n# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of\n# the path mentioned in the documentation of a class, which tells\n# the reader which header file to include in order to use a class.\n# If left blank only the name of the header file containing the class\n# definition is used. Otherwise one should specify the include paths that\n# are normally passed to the compiler using the -I flag.\n\nSTRIP_FROM_INC_PATH    =\n\n# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter\n# (but less readable) file names. This can be useful if your file system\n# doesn't support long names like on DOS, Mac, or CD-ROM.\n\nSHORT_NAMES            = NO\n\n# If the JAVADOC_AUTOBRIEF tag is set to YES then Doxygen\n# will interpret the first line (until the first dot) of a JavaDoc-style\n# comment as the brief description. If set to NO, the JavaDoc\n# comments will behave just like regular Qt-style comments\n# (thus requiring an explicit @brief command for a brief description.)\n\nJAVADOC_AUTOBRIEF      = NO\n\n# If the QT_AUTOBRIEF tag is set to YES then Doxygen will\n# interpret the first line (until the first dot) of a Qt-style\n# comment as the brief description. If set to NO, the comments\n# will behave just like regular Qt-style comments (thus requiring\n# an explicit \\brief command for a brief description.)\n\nQT_AUTOBRIEF           = NO\n\n# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make Doxygen\n# treat a multi-line C++ special comment block (i.e. a block of //! or ///\n# comments) as a brief description. This used to be the default behaviour.\n# The new default is to treat a multi-line C++ comment block as a detailed\n# description. Set this tag to YES if you prefer the old behaviour instead.\n\nMULTILINE_CPP_IS_BRIEF = NO\n\n# If the INHERIT_DOCS tag is set to YES (the default) then an undocumented\n# member inherits the documentation from any documented member that it\n# re-implements.\n\nINHERIT_DOCS           = YES\n\n# If the SEPARATE_MEMBER_PAGES tag is set to YES, then doxygen will produce\n# a new page for each member. If set to NO, the documentation of a member will\n# be part of the file/class/namespace that contains it.\n\nSEPARATE_MEMBER_PAGES  = NO\n\n# The TAB_SIZE tag can be used to set the number of spaces in a tab.\n# Doxygen uses this value to replace tabs by spaces in code fragments.\n\nTAB_SIZE               = 8\n\n# This tag can be used to specify a number of aliases that acts\n# as commands in the documentation. An alias has the form \"name=value\".\n# For example adding \"sideeffect=\\par Side Effects:\\n\" will allow you to\n# put the command \\sideeffect (or @sideeffect) in the documentation, which\n# will result in a user-defined paragraph with heading \"Side Effects:\".\n# You can put \\n's in the value part of an alias to insert newlines.\n\nALIASES                = \"only_for_vectors=This is only for vectors (either row-vectors or column-vectors), i.e. matrices which are known at compile-time to have either one row or one column.\" \\\n                         \"not_reentrant=\\warning This function is not re-entrant.\" \\\n                         \"array_module=This is defined in the %Array module. \\code #include <Eigen/Array> \\endcode\" \\\n                         \"cholesky_module=This is defined in the %Cholesky module. \\code #include <Eigen/Cholesky> \\endcode\" \\\n                         \"eigenvalues_module=This is defined in the %Eigenvalues module. \\code #include <Eigen/Eigenvalues> \\endcode\" \\\n                         \"geometry_module=This is defined in the %Geometry module. \\code #include <Eigen/Geometry> \\endcode\" \\\n                         \"householder_module=This is defined in the %Householder module. \\code #include <Eigen/Householder> \\endcode\" \\\n                         \"jacobi_module=This is defined in the %Jacobi module. \\code #include <Eigen/Jacobi> \\endcode\" \\\n                         \"lu_module=This is defined in the %LU module. \\code #include <Eigen/LU> \\endcode\" \\\n                         \"qr_module=This is defined in the %QR module. \\code #include <Eigen/QR> \\endcode\" \\\n                         \"svd_module=This is defined in the %SVD module. \\code #include <Eigen/SVD> \\endcode\" \\\n                         \"specialfunctions_module=This is defined in the \\b unsupported SpecialFunctions module. \\code #include <Eigen/SpecialFunctions> \\endcode\" \\\n                         \"label=\\bug\" \\\n                         \"matrixworld=<a href='#matrixonly' style='color:green;text-decoration: none;'>*</a>\" \\\n                         \"arrayworld=<a href='#arrayonly' style='color:blue;text-decoration: none;'>*</a>\" \\\n                         \"note_about_arbitrary_choice_of_solution=If there exists more than one solution, this method will arbitrarily choose one.\" \\\n                         \"note_about_using_kernel_to_study_multiple_solutions=If you need a complete analysis of the space of solutions, take the one solution obtained by this method and add to it elements of the kernel, as determined by kernel().\" \\\n                         \"note_about_checking_solutions=This method just tries to find as good a solution as possible. If you want to check whether a solution exists or if it is accurate, just call this function to get a result and then compute the error of this result, or use MatrixBase::isApprox() directly, for instance like this: \\code bool a_solution_exists = (A*result).isApprox(b, precision); \\endcode This method avoids dividing by zero, so that the non-existence of a solution doesn't by itself mean that you'll get \\c inf or \\c nan values.\" \\\n                         \"note_try_to_help_rvo=This function returns the result by value. In order to make that efficient, it is implemented as just a return statement using a special constructor, hopefully allowing the compiler to perform a RVO (return value optimization).\" \\\n                         \"nonstableyet=\\warning This is not considered to be part of the stable public API yet. Changes may happen in future releases. See \\ref Experimental \\\"Experimental parts of Eigen\\\"\" \\\n                         \"implsparsesolverconcept=This class follows the \\link TutorialSparseSolverConcept sparse solver concept \\endlink.\" \\\n                         \"blank= \" \\\n                         \"cpp11=<span class='cpp11'>[c++11]</span>\" \\\n                         \"cpp14=<span class='cpp14'>[c++14]</span>\" \\\n                         \"cpp17=<span class='cpp17'>[c++17]</span>\" \\\n                         \"newin{1}=<span class='newin3x'>New in %Eigen \\1.</span>\"\n                         \n\nALIASES += \"eigenAutoToc=  \"\nALIASES += \"eigenManualPage=\\defgroup\"\n\n# This tag can be used to specify a number of word-keyword mappings (TCL only).\n# A mapping has the form \"name=value\". For example adding\n# \"class=itcl::class\" will allow you to use the command class in the\n# itcl::class meaning.\n\nTCL_SUBST              =\n\n# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C\n# sources only. Doxygen will then generate output that is more tailored for C.\n# For instance, some of the names that are used will be different. The list\n# of all members will be omitted, etc.\n\nOPTIMIZE_OUTPUT_FOR_C  = NO\n\n# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java\n# sources only. Doxygen will then generate output that is more tailored for\n# Java. For instance, namespaces will be presented as packages, qualified\n# scopes will look different, etc.\n\nOPTIMIZE_OUTPUT_JAVA   = NO\n\n# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran\n# sources only. Doxygen will then generate output that is more tailored for\n# Fortran.\n\nOPTIMIZE_FOR_FORTRAN   = NO\n\n# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL\n# sources. Doxygen will then generate output that is tailored for\n# VHDL.\n\nOPTIMIZE_OUTPUT_VHDL   = NO\n\n# Doxygen selects the parser to use depending on the extension of the files it\n# parses. With this tag you can assign which parser to use for a given extension.\n# Doxygen has a built-in mapping, but you can override or extend it using this\n# tag. The format is ext=language, where ext is a file extension, and language\n# is one of the parsers supported by doxygen: IDL, Java, Javascript, CSharp, C,\n# C++, D, PHP, Objective-C, Python, Fortran, VHDL, C, C++. For instance to make\n# doxygen treat .inc files as Fortran files (default is PHP), and .f files as C\n# (default is Fortran), use: inc=Fortran f=C. Note that for custom extensions\n# you also need to set FILE_PATTERNS otherwise the files are not read by doxygen.\n\nEXTENSION_MAPPING      = .h=C++ no_extension=C++\n\n# If MARKDOWN_SUPPORT is enabled (the default) then doxygen pre-processes all\n# comments according to the Markdown format, which allows for more readable\n# documentation. See http://daringfireball.net/projects/markdown/ for details.\n# The output of markdown processing is further processed by doxygen, so you\n# can mix doxygen, HTML, and XML commands with Markdown formatting.\n# Disable only in case of backward compatibilities issues.\n\nMARKDOWN_SUPPORT       = YES\n\n# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want\n# to include (a tag file for) the STL sources as input, then you should\n# set this tag to YES in order to let doxygen match functions declarations and\n# definitions whose arguments contain STL classes (e.g. func(std::string); v.s.\n# func(std::string) {}). This also makes the inheritance and collaboration\n# diagrams that involve STL classes more complete and accurate.\n\nBUILTIN_STL_SUPPORT    = NO\n\n# If you use Microsoft's C++/CLI language, you should set this option to YES to\n# enable parsing support.\n\nCPP_CLI_SUPPORT        = NO\n\n# Set the SIP_SUPPORT tag to YES if your project consists of sip sources only.\n# Doxygen will parse them like normal C++ but will assume all classes use public\n# instead of private inheritance when no explicit protection keyword is present.\n\nSIP_SUPPORT            = NO\n\n# For Microsoft's IDL there are propget and propput attributes to indicate getter\n# and setter methods for a property. Setting this option to YES (the default)\n# will make doxygen replace the get and set methods by a property in the\n# documentation. This will only work if the methods are indeed getting or\n# setting a simple type. If this is not the case, or you want to show the\n# methods anyway, you should set this option to NO.\n\nIDL_PROPERTY_SUPPORT   = YES\n\n# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC\n# tag is set to YES, then doxygen will reuse the documentation of the first\n# member in the group (if any) for the other members of the group. By default\n# all members of a group must be documented explicitly.\n\nDISTRIBUTE_GROUP_DOC   = YES\n\n# Set the SUBGROUPING tag to YES (the default) to allow class member groups of\n# the same type (for instance a group of public functions) to be put as a\n# subgroup of that type (e.g. under the Public Functions section). Set it to\n# NO to prevent subgrouping. Alternatively, this can be done per class using\n# the \\nosubgrouping command.\n\nSUBGROUPING            = YES\n\n# When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and\n# unions are shown inside the group in which they are included (e.g. using\n# @ingroup) instead of on a separate page (for HTML and Man pages) or\n# section (for LaTeX and RTF).\n\nINLINE_GROUPED_CLASSES = NO\n\n# When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and\n# unions with only public data fields will be shown inline in the documentation\n# of the scope in which they are defined (i.e. file, namespace, or group\n# documentation), provided this scope is documented. If set to NO (the default),\n# structs, classes, and unions are shown on a separate page (for HTML and Man\n# pages) or section (for LaTeX and RTF).\n\nINLINE_SIMPLE_STRUCTS  = NO\n\n# When TYPEDEF_HIDES_STRUCT is enabled, a typedef of a struct, union, or enum\n# is documented as struct, union, or enum with the name of the typedef. So\n# typedef struct TypeS {} TypeT, will appear in the documentation as a struct\n# with name TypeT. When disabled the typedef will appear as a member of a file,\n# namespace, or class. And the struct will be named TypeS. This can typically\n# be useful for C code in case the coding convention dictates that all compound\n# types are typedef'ed and only the typedef is referenced, never the tag name.\n\nTYPEDEF_HIDES_STRUCT   = NO\n\n# The SYMBOL_CACHE_SIZE determines the size of the internal cache use to\n# determine which symbols to keep in memory and which to flush to disk.\n# When the cache is full, less often used symbols will be written to disk.\n# For small to medium size projects (<1000 input files) the default value is\n# probably good enough. For larger projects a too small cache size can cause\n# doxygen to be busy swapping symbols to and from disk most of the time\n# causing a significant performance penalty.\n# If the system has enough physical memory increasing the cache will improve the\n# performance by keeping more symbols in memory. Note that the value works on\n# a logarithmic scale so increasing the size by one will roughly double the\n# memory usage. The cache size is given by this formula:\n# 2^(16+SYMBOL_CACHE_SIZE). The valid range is 0..9, the default is 0,\n# corresponding to a cache size of 2^16 = 65536 symbols.\n\n# SYMBOL_CACHE_SIZE      = 0\n\n# Similar to the SYMBOL_CACHE_SIZE the size of the symbol lookup cache can be\n# set using LOOKUP_CACHE_SIZE. This cache is used to resolve symbols given\n# their name and scope. Since this can be an expensive process and often the\n# same symbol appear multiple times in the code, doxygen keeps a cache of\n# pre-resolved symbols. If the cache is too small doxygen will become slower.\n# If the cache is too large, memory is wasted. The cache size is given by this\n# formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range is 0..9, the default is 0,\n# corresponding to a cache size of 2^16 = 65536 symbols.\n\nLOOKUP_CACHE_SIZE      = 0\n\n#---------------------------------------------------------------------------\n# Build related configuration options\n#---------------------------------------------------------------------------\n\n# If the EXTRACT_ALL tag is set to YES doxygen will assume all entities in\n# documentation are documented, even if no documentation was available.\n# Private class members and static file members will be hidden unless\n# the EXTRACT_PRIVATE and EXTRACT_STATIC tags are set to YES\n\nEXTRACT_ALL            = NO\n\n# If the EXTRACT_PRIVATE tag is set to YES all private members of a class\n# will be included in the documentation.\n\nEXTRACT_PRIVATE        = NO\n\n# If the EXTRACT_PACKAGE tag is set to YES all members with package or internal scope will be included in the documentation.\n\nEXTRACT_PACKAGE        = NO\n\n# If the EXTRACT_STATIC tag is set to YES all static members of a file\n# will be included in the documentation.\n\nEXTRACT_STATIC         = YES\n\n# If the EXTRACT_LOCAL_CLASSES tag is set to YES classes (and structs)\n# defined locally in source files will be included in the documentation.\n# If set to NO only classes defined in header files are included.\n\nEXTRACT_LOCAL_CLASSES  = NO\n\n# This flag is only useful for Objective-C code. When set to YES local\n# methods, which are defined in the implementation section but not in\n# the interface are included in the documentation.\n# If set to NO (the default) only methods in the interface are included.\n\nEXTRACT_LOCAL_METHODS  = NO\n\n# If this flag is set to YES, the members of anonymous namespaces will be\n# extracted and appear in the documentation as a namespace called\n# 'anonymous_namespace{file}', where file will be replaced with the base\n# name of the file that contains the anonymous namespace. By default\n# anonymous namespaces are hidden.\n\nEXTRACT_ANON_NSPACES   = NO\n\n# If the HIDE_UNDOC_MEMBERS tag is set to YES, Doxygen will hide all\n# undocumented members of documented classes, files or namespaces.\n# If set to NO (the default) these members will be included in the\n# various overviews, but no documentation section is generated.\n# This option has no effect if EXTRACT_ALL is enabled.\n\nHIDE_UNDOC_MEMBERS     = YES\n\n# If the HIDE_UNDOC_CLASSES tag is set to YES, Doxygen will hide all\n# undocumented classes that are normally visible in the class hierarchy.\n# If set to NO (the default) these classes will be included in the various\n# overviews. This option has no effect if EXTRACT_ALL is enabled.\n\nHIDE_UNDOC_CLASSES     = YES\n\n# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, Doxygen will hide all\n# friend (class|struct|union) declarations.\n# If set to NO (the default) these declarations will be included in the\n# documentation.\n\nHIDE_FRIEND_COMPOUNDS  = YES\n\n# If the HIDE_IN_BODY_DOCS tag is set to YES, Doxygen will hide any\n# documentation blocks found inside the body of a function.\n# If set to NO (the default) these blocks will be appended to the\n# function's detailed documentation block.\n\nHIDE_IN_BODY_DOCS      = NO\n\n# The INTERNAL_DOCS tag determines if documentation\n# that is typed after a \\internal command is included. If the tag is set\n# to NO (the default) then the documentation will be excluded.\n# Set it to YES to include the internal documentation.\n\nINTERNAL_DOCS          = ${EIGEN_DOXY_INTERNAL}\n\n# If the CASE_SENSE_NAMES tag is set to NO then Doxygen will only generate\n# file names in lower-case letters. If set to YES upper-case letters are also\n# allowed. This is useful if you have classes or files whose names only differ\n# in case and if your file system supports case sensitive file names. Windows\n# and Mac users are advised to set this option to NO.\n\nCASE_SENSE_NAMES       = YES\n\n# If the HIDE_SCOPE_NAMES tag is set to NO (the default) then Doxygen\n# will show members with their full class and namespace scopes in the\n# documentation. If set to YES the scope will be hidden.\n\nHIDE_SCOPE_NAMES       = NO\n\n# If the SHOW_INCLUDE_FILES tag is set to YES (the default) then Doxygen\n# will put a list of the files that are included by a file in the documentation\n# of that file.\n\nSHOW_INCLUDE_FILES     = ${EIGEN_DOXY_INTERNAL}\n\n# If the FORCE_LOCAL_INCLUDES tag is set to YES then Doxygen\n# will list include files with double quotes in the documentation\n# rather than with sharp brackets.\n\nFORCE_LOCAL_INCLUDES   = NO\n\n# If the INLINE_INFO tag is set to YES (the default) then a tag [inline]\n# is inserted in the documentation for inline members.\n\nINLINE_INFO            = YES\n\n# If the SORT_MEMBER_DOCS tag is set to YES (the default) then doxygen\n# will sort the (detailed) documentation of file and class members\n# alphabetically by member name. If set to NO the members will appear in\n# declaration order.\n\nSORT_MEMBER_DOCS       = YES\n\n# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the\n# brief documentation of file, namespace and class members alphabetically\n# by member name. If set to NO (the default) the members will appear in\n# declaration order.\n\nSORT_BRIEF_DOCS        = YES\n\n# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen\n# will sort the (brief and detailed) documentation of class members so that\n# constructors and destructors are listed first. If set to NO (the default)\n# the constructors will appear in the respective orders defined by\n# SORT_MEMBER_DOCS and SORT_BRIEF_DOCS.\n# This tag will be ignored for brief docs if SORT_BRIEF_DOCS is set to NO\n# and ignored for detailed docs if SORT_MEMBER_DOCS is set to NO.\n\nSORT_MEMBERS_CTORS_1ST = NO\n\n# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the\n# hierarchy of group names into alphabetical order. If set to NO (the default)\n# the group names will appear in their defined order.\n\nSORT_GROUP_NAMES       = NO\n\n# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be\n# sorted by fully-qualified names, including namespaces. If set to\n# NO (the default), the class list will be sorted only by class name,\n# not including the namespace part.\n# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES.\n# Note: This option applies only to the class list, not to the\n# alphabetical list.\n\nSORT_BY_SCOPE_NAME     = NO\n\n# If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to\n# do proper type resolution of all parameters of a function it will reject a\n# match between the prototype and the implementation of a member function even\n# if there is only one candidate or it is obvious which candidate to choose\n# by doing a simple string match. By disabling STRICT_PROTO_MATCHING doxygen\n# will still accept a match between prototype and implementation in such cases.\n\nSTRICT_PROTO_MATCHING  = NO\n\n# The GENERATE_TODOLIST tag can be used to enable (YES) or\n# disable (NO) the todo list. This list is created by putting \\todo\n# commands in the documentation.\n\nGENERATE_TODOLIST      = ${EIGEN_DOXY_INTERNAL}\n\n# The GENERATE_TESTLIST tag can be used to enable (YES) or\n# disable (NO) the test list. This list is created by putting \\test\n# commands in the documentation.\n\nGENERATE_TESTLIST      = NO\n\n# The GENERATE_BUGLIST tag can be used to enable (YES) or\n# disable (NO) the bug list. This list is created by putting \\bug\n# commands in the documentation.\n\nGENERATE_BUGLIST       = ${EIGEN_DOXY_INTERNAL}\n\n# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or\n# disable (NO) the deprecated list. This list is created by putting\n# \\deprecated commands in the documentation.\n\nGENERATE_DEPRECATEDLIST= YES\n\n# The ENABLED_SECTIONS tag can be used to enable conditional\n# documentation sections, marked by \\if sectionname ... \\endif.\n\nENABLED_SECTIONS       =\n\n# The MAX_INITIALIZER_LINES tag determines the maximum number of lines\n# the initial value of a variable or macro consists of for it to appear in\n# the documentation. If the initializer consists of more lines than specified\n# here it will be hidden. Use a value of 0 to hide initializers completely.\n# The appearance of the initializer of individual variables and macros in the\n# documentation can be controlled using \\showinitializer or \\hideinitializer\n# command in the documentation regardless of this setting.\n\nMAX_INITIALIZER_LINES  = 0\n\n# Set the SHOW_USED_FILES tag to NO to disable the list of files generated\n# at the bottom of the documentation of classes and structs. If set to YES the\n# list will mention the files that were used to generate the documentation.\n\nSHOW_USED_FILES        = YES\n\n# Set the SHOW_FILES tag to NO to disable the generation of the Files page.\n# This will remove the Files entry from the Quick Index and from the\n# Folder Tree View (if specified). The default is YES.\n\nSHOW_FILES             = YES\n\n# Set the SHOW_NAMESPACES tag to NO to disable the generation of the\n# Namespaces page.\n# This will remove the Namespaces entry from the Quick Index\n# and from the Folder Tree View (if specified). The default is YES.\n\nSHOW_NAMESPACES        = NO\n\n# The FILE_VERSION_FILTER tag can be used to specify a program or script that\n# doxygen should invoke to get the current version for each file (typically from\n# the version control system). Doxygen will invoke the program by executing (via\n# popen()) the command <command> <input-file>, where <command> is the value of\n# the FILE_VERSION_FILTER tag, and <input-file> is the name of an input file\n# provided by doxygen. Whatever the program writes to standard output\n# is used as the file version. See the manual for examples.\n\nFILE_VERSION_FILTER    =\n\n# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed\n# by doxygen. The layout file controls the global structure of the generated\n# output files in an output format independent way. To create the layout file\n# that represents doxygen's defaults, run doxygen with the -l option.\n# You can optionally specify a file name after the option, if omitted\n# DoxygenLayout.xml will be used as the name of the layout file.\n\nLAYOUT_FILE            = \"${Eigen_BINARY_DIR}/doc${EIGEN_DOXY_OUTPUT_DIRECTORY_SUFFIX}/eigendoxy_layout.xml\"\n\n# The CITE_BIB_FILES tag can be used to specify one or more bib files\n# containing the references data. This must be a list of .bib files. The\n# .bib extension is automatically appended if omitted. Using this command\n# requires the bibtex tool to be installed. See also\n# http://en.wikipedia.org/wiki/BibTeX for more info. For LaTeX the style\n# of the bibliography can be controlled using LATEX_BIB_STYLE. To use this\n# feature you need bibtex and perl available in the search path.\n\nCITE_BIB_FILES         =\n\n#---------------------------------------------------------------------------\n# configuration options related to warning and progress messages\n#---------------------------------------------------------------------------\n\n# The QUIET tag can be used to turn on/off the messages that are generated\n# by doxygen. Possible values are YES and NO. If left blank NO is used.\n\nQUIET                  = NO\n\n# The WARNINGS tag can be used to turn on/off the warning messages that are\n# generated by doxygen. Possible values are YES and NO. If left blank\n# NO is used.\n\nWARNINGS               = YES\n\n# If WARN_IF_UNDOCUMENTED is set to YES, then doxygen will generate warnings\n# for undocumented members. If EXTRACT_ALL is set to YES then this flag will\n# automatically be disabled.\n\nWARN_IF_UNDOCUMENTED   = NO\n\n# If WARN_IF_DOC_ERROR is set to YES, doxygen will generate warnings for\n# potential errors in the documentation, such as not documenting some\n# parameters in a documented function, or documenting parameters that\n# don't exist or using markup commands wrongly.\n\nWARN_IF_DOC_ERROR      = YES\n\n# The WARN_NO_PARAMDOC option can be enabled to get warnings for\n# functions that are documented, but have no documentation for their parameters\n# or return value. If set to NO (the default) doxygen will only warn about\n# wrong or incomplete parameter documentation, but not about the absence of\n# documentation.\n\nWARN_NO_PARAMDOC       = NO\n\n# The WARN_FORMAT tag determines the format of the warning messages that\n# doxygen can produce. The string should contain the $file, $line, and $text\n# tags, which will be replaced by the file and line number from which the\n# warning originated and the warning text. Optionally the format may contain\n# $version, which will be replaced by the version of the file (if it could\n# be obtained via FILE_VERSION_FILTER)\n\nWARN_FORMAT            = \"$file:$line: $text\"\n\n# The WARN_LOGFILE tag can be used to specify a file to which warning\n# and error messages should be written. If left blank the output is written\n# to stderr.\n\nWARN_LOGFILE           =\n\n#---------------------------------------------------------------------------\n# configuration options related to the input files\n#---------------------------------------------------------------------------\n\n# The INPUT tag can be used to specify the files and/or directories that contain\n# documented source files. You may enter file names like \"myfile.cpp\" or\n# directories like \"/usr/src/myproject\". Separate the files or directories\n# with spaces.\n\nINPUT                  = ${EIGEN_DOXY_INPUT}\n\n# This tag can be used to specify the character encoding of the source files\n# that doxygen parses. Internally doxygen uses the UTF-8 encoding, which is\n# also the default input encoding. Doxygen uses libiconv (or the iconv built\n# into libc) for the transcoding. See http://www.gnu.org/software/libiconv for\n# the list of possible encodings.\n\nINPUT_ENCODING         = UTF-8\n\n# If the value of the INPUT tag contains directories, you can use the\n# FILE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp\n# and *.h) to filter out the source-files in the directories. If left\n# blank the following patterns are tested:\n# *.c *.cc *.cxx *.cpp *.c++ *.d *.java *.ii *.ixx *.ipp *.i++ *.inl *.h *.hh\n# *.hxx *.hpp *.h++ *.idl *.odl *.cs *.php *.php3 *.inc *.m *.mm *.dox *.py\n# *.f90 *.f *.for *.vhd *.vhdl\n\nFILE_PATTERNS          = *\n\n# The RECURSIVE tag can be used to turn specify whether or not subdirectories\n# should be searched for input files as well. Possible values are YES and NO.\n# If left blank NO is used.\n\nRECURSIVE              = YES\n\n# The EXCLUDE tag can be used to specify files and/or directories that should be\n# excluded from the INPUT source files. This way you can easily exclude a\n# subdirectory from a directory tree whose root is specified with the INPUT tag.\n# Note that relative paths are relative to the directory from which doxygen is\n# run.\n\nEXCLUDE                = \"${Eigen_SOURCE_DIR}/Eigen/src/Core/products\" \\\n                         \"${Eigen_SOURCE_DIR}/Eigen/Eigen2Support\" \\\n                         \"${Eigen_SOURCE_DIR}/Eigen/src/Eigen2Support\" \\\n                         \"${Eigen_SOURCE_DIR}/doc/examples\" \\\n                         \"${Eigen_SOURCE_DIR}/doc/special_examples\" \\\n                         \"${Eigen_SOURCE_DIR}/doc/snippets\" \\\n                         \"${Eigen_SOURCE_DIR}/unsupported/doc/examples\" \\\n                         \"${Eigen_SOURCE_DIR}/unsupported/doc/snippets\"\n\n# Forward declarations of class templates cause the title of the main page for\n# the class template to not contain the template signature.  This only happens\n# when the \\class command is used to document the class.  Possibly caused\n# by https://github.com/doxygen/doxygen/issues/7698.  Confirmed fixed by\n# doxygen release 1.8.19.\n\nEXCLUDE += \"${Eigen_SOURCE_DIR}/Eigen/src/Core/util/ForwardDeclarations.h\"\n\n# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or\n# directories that are symbolic links (a Unix file system feature) are excluded\n# from the input.\n\nEXCLUDE_SYMLINKS       = NO\n\n# If the value of the INPUT tag contains directories, you can use the\n# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude\n# certain files from those directories. Note that the wildcards are matched\n# against the file with absolute path, so to exclude all test directories\n# for example use the pattern */test/*\n\nEXCLUDE_PATTERNS       = CMake* \\\n                         *.txt \\\n                         *.sh \\\n                         *.orig \\\n                         *.diff \\\n                         diff \\\n                         *~ \\\n                         *. \\\n                         *.sln \\\n                         *.sdf \\\n                         *.tmp \\\n                         *.vcxproj \\\n                         *.filters \\\n                         *.user \\\n                         *.suo\n\n# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names\n# (namespaces, classes, functions, etc.) that should be excluded from the\n# output. The symbol name can be a fully qualified name, a word, or if the\n# wildcard * is used, a substring. Examples: ANamespace, AClass,\n# AClass::ANamespace, ANamespace::*Test\n\nEXCLUDE_SYMBOLS        = internal::* \\\n                         Flagged* \\\n                         *InnerIterator* \\\n                         DenseStorage<* \\\n                         \n\n# The EXAMPLE_PATH tag can be used to specify one or more files or\n# directories that contain example code fragments that are included (see\n# the \\include command).\n\nEXAMPLE_PATH           = \"${Eigen_SOURCE_DIR}/doc/snippets\" \\\n                         \"${Eigen_BINARY_DIR}/doc/snippets\" \\\n                         \"${Eigen_SOURCE_DIR}/doc/examples\" \\\n                         \"${Eigen_BINARY_DIR}/doc/examples\" \\\n                         \"${Eigen_SOURCE_DIR}/doc/special_examples\" \\\n                         \"${Eigen_BINARY_DIR}/doc/special_examples\" \\\n                         \"${Eigen_SOURCE_DIR}/unsupported/doc/snippets\" \\\n                         \"${Eigen_BINARY_DIR}/unsupported/doc/snippets\" \\\n                         \"${Eigen_SOURCE_DIR}/unsupported/doc/examples\" \\\n                         \"${Eigen_BINARY_DIR}/unsupported/doc/examples\"\n\n# If the value of the EXAMPLE_PATH tag contains directories, you can use the\n# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp\n# and *.h) to filter out the source-files in the directories. If left\n# blank all files are included.\n\nEXAMPLE_PATTERNS       = *\n\n# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be\n# searched for input files to be used with the \\include or \\dontinclude\n# commands irrespective of the value of the RECURSIVE tag.\n# Possible values are YES and NO. If left blank NO is used.\n\nEXAMPLE_RECURSIVE      = NO\n\n# The IMAGE_PATH tag can be used to specify one or more files or\n# directories that contain image that are included in the documentation (see\n# the \\image command).\n\nIMAGE_PATH             = ${Eigen_BINARY_DIR}/doc/html\n\n# The INPUT_FILTER tag can be used to specify a program that doxygen should\n# invoke to filter for each input file. Doxygen will invoke the filter program\n# by executing (via popen()) the command <filter> <input-file>, where <filter>\n# is the value of the INPUT_FILTER tag, and <input-file> is the name of an\n# input file. Doxygen will then use the output that the filter program writes\n# to standard output.\n# If FILTER_PATTERNS is specified, this tag will be\n# ignored.\n\nINPUT_FILTER           =\n\n# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern\n# basis.\n# Doxygen will compare the file name with each pattern and apply the\n# filter if there is a match.\n# The filters are a list of the form:\n# pattern=filter (like *.cpp=my_cpp_filter). See INPUT_FILTER for further\n# info on how filters are used. If FILTER_PATTERNS is empty or if\n# non of the patterns match the file name, INPUT_FILTER is applied.\n\nFILTER_PATTERNS        =\n\n# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using\n# INPUT_FILTER) will be used to filter the input files when producing source\n# files to browse (i.e. when SOURCE_BROWSER is set to YES).\n\nFILTER_SOURCE_FILES    = NO\n\n# The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file\n# pattern. A pattern will override the setting for FILTER_PATTERN (if any)\n# and it is also possible to disable source filtering for a specific pattern\n# using *.ext= (so without naming a filter). This option only has effect when\n# FILTER_SOURCE_FILES is enabled.\n\nFILTER_SOURCE_PATTERNS =\n\n#---------------------------------------------------------------------------\n# configuration options related to source browsing\n#---------------------------------------------------------------------------\n\n# If the SOURCE_BROWSER tag is set to YES then a list of source files will\n# be generated. Documented entities will be cross-referenced with these sources.\n# Note: To get rid of all source code in the generated output, make sure also\n# VERBATIM_HEADERS is set to NO.\n\nSOURCE_BROWSER         = NO\n\n# Setting the INLINE_SOURCES tag to YES will include the body\n# of functions and classes directly in the documentation.\n\nINLINE_SOURCES         = NO\n\n# Setting the STRIP_CODE_COMMENTS tag to YES (the default) will instruct\n# doxygen to hide any special comment blocks from generated source code\n# fragments. Normal C, C++ and Fortran comments will always remain visible.\n\nSTRIP_CODE_COMMENTS    = YES\n\n# If the REFERENCED_BY_RELATION tag is set to YES\n# then for each documented function all documented\n# functions referencing it will be listed.\n\nREFERENCED_BY_RELATION = NO\n\n# If the REFERENCES_RELATION tag is set to YES\n# then for each documented function all documented entities\n# called/used by that function will be listed.\n\nREFERENCES_RELATION    = NO\n\n# If the REFERENCES_LINK_SOURCE tag is set to YES (the default)\n# and SOURCE_BROWSER tag is set to YES, then the hyperlinks from\n# functions in REFERENCES_RELATION and REFERENCED_BY_RELATION lists will\n# link to the source code.\n# Otherwise they will link to the documentation.\n\nREFERENCES_LINK_SOURCE = YES\n\n# If the USE_HTAGS tag is set to YES then the references to source code\n# will point to the HTML generated by the htags(1) tool instead of doxygen\n# built-in source browser. The htags tool is part of GNU's global source\n# tagging system (see http://www.gnu.org/software/global/global.html). You\n# will need version 4.8.6 or higher.\n\nUSE_HTAGS              = NO\n\n# If the VERBATIM_HEADERS tag is set to YES (the default) then Doxygen\n# will generate a verbatim copy of the header file for each class for\n# which an include is specified. Set to NO to disable this.\n\nVERBATIM_HEADERS       = YES\n\n#---------------------------------------------------------------------------\n# configuration options related to the alphabetical class index\n#---------------------------------------------------------------------------\n\n# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index\n# of all compounds will be generated. Enable this if the project\n# contains a lot of classes, structs, unions or interfaces.\n\nALPHABETICAL_INDEX     = NO\n\n# If the alphabetical index is enabled (see ALPHABETICAL_INDEX) then\n# the COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns\n# in which this list will be split (can be a number in the range [1..20])\n\nCOLS_IN_ALPHA_INDEX    = 5\n\n# In case all classes in a project start with a common prefix, all\n# classes will be put under the same header in the alphabetical index.\n# The IGNORE_PREFIX tag can be used to specify one or more prefixes that\n# should be ignored while generating the index headers.\n\nIGNORE_PREFIX          =\n\n#---------------------------------------------------------------------------\n# configuration options related to the HTML output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_HTML tag is set to YES (the default) Doxygen will\n# generate HTML output.\n\nGENERATE_HTML          = YES\n\n# The HTML_OUTPUT tag is used to specify where the HTML docs will be put.\n# If a relative path is entered the value of OUTPUT_DIRECTORY will be\n# put in front of it. If left blank `html' will be used as the default path.\n\nHTML_OUTPUT            = \"${Eigen_BINARY_DIR}/doc/html${EIGEN_DOXY_OUTPUT_DIRECTORY_SUFFIX}\"\n\n# The HTML_FILE_EXTENSION tag can be used to specify the file extension for\n# each generated HTML page (for example: .htm,.php,.asp). If it is left blank\n# doxygen will generate files with .html extension.\n\nHTML_FILE_EXTENSION    = .html\n\n# The HTML_HEADER tag can be used to specify a personal HTML header for\n# each generated HTML page. If it is left blank doxygen will generate a\n# standard header. Note that when using a custom header you are responsible\n#  for the proper inclusion of any scripts and style sheets that doxygen\n# needs, which is dependent on the configuration options used.\n# It is advised to generate a default header using \"doxygen -w html\n# header.html footer.html stylesheet.css YourConfigFile\" and then modify\n# that header. Note that the header is subject to change so you typically\n# have to redo this when upgrading to a newer version of doxygen or when\n# changing the value of configuration settings such as GENERATE_TREEVIEW!\n\nHTML_HEADER            = \"${Eigen_BINARY_DIR}/doc/eigendoxy_header.html\"\n\n# The HTML_FOOTER tag can be used to specify a personal HTML footer for\n# each generated HTML page. If it is left blank doxygen will generate a\n# standard footer.\n\nHTML_FOOTER            = \"${Eigen_BINARY_DIR}/doc/eigendoxy_footer.html\"\n\n# The HTML_STYLESHEET tag can be used to specify a user-defined cascading\n# style sheet that is used by each HTML page. It can be used to\n# fine-tune the look of the HTML output. If the tag is left blank doxygen\n# will generate a default style sheet. Note that doxygen will try to copy\n# the style sheet file to the HTML output directory, so don't put your own\n# style sheet in the HTML output directory as well, or it will be erased!\n\nHTML_STYLESHEET        = \n\n# The HTML_EXTRA_FILES tag can be used to specify one or more extra images or\n# other source files which should be copied to the HTML output directory. Note\n# that these files will be copied to the base HTML output directory. Use the\n# $relpath$ marker in the HTML_HEADER and/or HTML_FOOTER files to load these\n# files. In the HTML_STYLESHEET file, use the file name only. Also note that\n# the files will be copied as-is; there are no commands or markers available.\n\nHTML_EXTRA_FILES       = \"${Eigen_SOURCE_DIR}/doc/eigendoxy.css\"\n\n# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output.\n# Doxygen will adjust the colors in the style sheet and background images\n# according to this color. Hue is specified as an angle on a colorwheel,\n# see http://en.wikipedia.org/wiki/Hue for more information.\n# For instance the value 0 represents red, 60 is yellow, 120 is green,\n# 180 is cyan, 240 is blue, 300 purple, and 360 is red again.\n# The allowed range is 0 to 359.\n# The default is 220.\n\nHTML_COLORSTYLE_HUE    = ${EIGEN_DOXY_HTML_COLORSTYLE_HUE}\n\n# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of\n# the colors in the HTML output. For a value of 0 the output will use\n# grayscales only. A value of 255 will produce the most vivid colors.\n\nHTML_COLORSTYLE_SAT    = 100\n\n# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to\n# the luminance component of the colors in the HTML output. Values below\n# 100 gradually make the output lighter, whereas values above 100 make\n# the output darker. The value divided by 100 is the actual gamma applied,\n# so 80 represents a gamma of 0.8, The value 220 represents a gamma of 2.2,\n# and 100 does not change the gamma.\n\nHTML_COLORSTYLE_GAMMA  = 80\n\n# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML\n# page will contain the date and time when the page was generated. Setting\n# this to NO can help when comparing the output of multiple runs.\n\nHTML_TIMESTAMP         = YES\n\n# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML\n# documentation will contain sections that can be hidden and shown after the\n# page has loaded.\n\nHTML_DYNAMIC_SECTIONS  = YES\n\n# With HTML_INDEX_NUM_ENTRIES one can control the preferred number of\n# entries shown in the various tree structured indices initially; the user\n# can expand and collapse entries dynamically later on. Doxygen will expand\n# the tree to such a level that at most the specified number of entries are\n# visible (unless a fully collapsed tree already exceeds this amount).\n# So setting the number of entries 1 will produce a full collapsed tree by\n# default. 0 is a special value representing an infinite number of entries\n# and will result in a full expanded tree by default.\n\nHTML_INDEX_NUM_ENTRIES = 100\n\n# If the GENERATE_DOCSET tag is set to YES, additional index files\n# will be generated that can be used as input for Apple's Xcode 3\n# integrated development environment, introduced with OSX 10.5 (Leopard).\n# To create a documentation set, doxygen will generate a Makefile in the\n# HTML output directory. Running make will produce the docset in that\n# directory and running \"make install\" will install the docset in\n# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find\n# it at startup.\n# See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html\n# for more information.\n\nGENERATE_DOCSET        = NO\n\n# When GENERATE_DOCSET tag is set to YES, this tag determines the name of the\n# feed. A documentation feed provides an umbrella under which multiple\n# documentation sets from a single provider (such as a company or product suite)\n# can be grouped.\n\nDOCSET_FEEDNAME        = \"Doxygen generated docs\"\n\n# When GENERATE_DOCSET tag is set to YES, this tag specifies a string that\n# should uniquely identify the documentation set bundle. This should be a\n# reverse domain-name style string, e.g. com.mycompany.MyDocSet. Doxygen\n# will append .docset to the name.\n\nDOCSET_BUNDLE_ID       = org.doxygen.Project\n\n# When GENERATE_PUBLISHER_ID tag specifies a string that should uniquely identify\n# the documentation publisher. This should be a reverse domain-name style\n# string, e.g. com.mycompany.MyDocSet.documentation.\n\nDOCSET_PUBLISHER_ID    = org.doxygen.Publisher\n\n# The GENERATE_PUBLISHER_NAME tag identifies the documentation publisher.\n\nDOCSET_PUBLISHER_NAME  = Publisher\n\n# If the GENERATE_HTMLHELP tag is set to YES, additional index files\n# will be generated that can be used as input for tools like the\n# Microsoft HTML help workshop to generate a compiled HTML help file (.chm)\n# of the generated HTML documentation.\n\nGENERATE_HTMLHELP      = NO\n\n# If the GENERATE_HTMLHELP tag is set to YES, the CHM_FILE tag can\n# be used to specify the file name of the resulting .chm file. You\n# can add a path in front of the file if the result should not be\n# written to the html output directory.\n\nCHM_FILE               =\n\n# If the GENERATE_HTMLHELP tag is set to YES, the HHC_LOCATION tag can\n# be used to specify the location (absolute path including file name) of\n# the HTML help compiler (hhc.exe). If non-empty doxygen will try to run\n# the HTML help compiler on the generated index.hhp.\n\nHHC_LOCATION           =\n\n# If the GENERATE_HTMLHELP tag is set to YES, the GENERATE_CHI flag\n# controls if a separate .chi index file is generated (YES) or that\n# it should be included in the master .chm file (NO).\n\nGENERATE_CHI           = NO\n\n# If the GENERATE_HTMLHELP tag is set to YES, the CHM_INDEX_ENCODING\n# is used to encode HtmlHelp index (hhk), content (hhc) and project file\n# content.\n\nCHM_INDEX_ENCODING     =\n\n# If the GENERATE_HTMLHELP tag is set to YES, the BINARY_TOC flag\n# controls whether a binary table of contents is generated (YES) or a\n# normal table of contents (NO) in the .chm file.\n\nBINARY_TOC             = NO\n\n# The TOC_EXPAND flag can be set to YES to add extra items for group members\n# to the contents of the HTML help documentation and to the tree view.\n\nTOC_EXPAND             = NO\n\n# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and\n# QHP_VIRTUAL_FOLDER are set, an additional index file will be generated\n# that can be used as input for Qt's qhelpgenerator to generate a\n# Qt Compressed Help (.qch) of the generated HTML documentation.\n\nGENERATE_QHP           = NO\n\n# If the QHG_LOCATION tag is specified, the QCH_FILE tag can\n# be used to specify the file name of the resulting .qch file.\n# The path specified is relative to the HTML output folder.\n\nQCH_FILE               =\n\n# The QHP_NAMESPACE tag specifies the namespace to use when generating\n# Qt Help Project output. For more information please see\n# http://doc.trolltech.com/qthelpproject.html#namespace\n\nQHP_NAMESPACE          = org.doxygen.Project\n\n# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating\n# Qt Help Project output. For more information please see\n# http://doc.trolltech.com/qthelpproject.html#virtual-folders\n\nQHP_VIRTUAL_FOLDER     = doc\n\n# If QHP_CUST_FILTER_NAME is set, it specifies the name of a custom filter to\n# add. For more information please see\n# http://doc.trolltech.com/qthelpproject.html#custom-filters\n\nQHP_CUST_FILTER_NAME   =\n\n# The QHP_CUST_FILT_ATTRS tag specifies the list of the attributes of the\n# custom filter to add. For more information please see\n# <a href=\"http://doc.trolltech.com/qthelpproject.html#custom-filters\">\n# Qt Help Project / Custom Filters</a>.\n\nQHP_CUST_FILTER_ATTRS  =\n\n# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this\n# project's\n# filter section matches.\n# <a href=\"http://doc.trolltech.com/qthelpproject.html#filter-attributes\">\n# Qt Help Project / Filter Attributes</a>.\n\nQHP_SECT_FILTER_ATTRS  =\n\n# If the GENERATE_QHP tag is set to YES, the QHG_LOCATION tag can\n# be used to specify the location of Qt's qhelpgenerator.\n# If non-empty doxygen will try to run qhelpgenerator on the generated\n# .qhp file.\n\nQHG_LOCATION           =\n\n# If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files\n#  will be generated, which together with the HTML files, form an Eclipse help\n# plugin. To install this plugin and make it available under the help contents\n# menu in Eclipse, the contents of the directory containing the HTML and XML\n# files needs to be copied into the plugins directory of eclipse. The name of\n# the directory within the plugins directory should be the same as\n# the ECLIPSE_DOC_ID value. After copying Eclipse needs to be restarted before\n# the help appears.\n\nGENERATE_ECLIPSEHELP   = NO\n\n# A unique identifier for the eclipse help plugin. When installing the plugin\n# the directory name containing the HTML and XML files should also have\n# this name.\n\nECLIPSE_DOC_ID         = org.doxygen.Project\n\n# The DISABLE_INDEX tag can be used to turn on/off the condensed index (tabs)\n# at top of each HTML page. The value NO (the default) enables the index and\n# the value YES disables it. Since the tabs have the same information as the\n# navigation tree you can set this option to NO if you already set\n# GENERATE_TREEVIEW to YES.\n\nDISABLE_INDEX          = YES\n\n# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index\n# structure should be generated to display hierarchical information.\n# If the tag value is set to YES, a side panel will be generated\n# containing a tree-like index structure (just like the one that\n# is generated for HTML Help). For this to work a browser that supports\n# JavaScript, DHTML, CSS and frames is required (i.e. any modern browser).\n# Windows users are probably better off using the HTML help feature.\n# Since the tree basically has the same information as the tab index you\n# could consider to set DISABLE_INDEX to NO when enabling this option.\n\nGENERATE_TREEVIEW      = YES\n\n# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values\n# (range [0,1..20]) that doxygen will group on one line in the generated HTML\n# documentation. Note that a value of 0 will completely suppress the enum\n# values from appearing in the overview section.\n\nENUM_VALUES_PER_LINE   = 1\n\n# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be\n# used to set the initial width (in pixels) of the frame in which the tree\n# is shown.\n\nTREEVIEW_WIDTH         = 250\n\n# When the EXT_LINKS_IN_WINDOW option is set to YES doxygen will open\n# links to external symbols imported via tag files in a separate window.\n\nEXT_LINKS_IN_WINDOW    = NO\n\n# Use this tag to change the font size of Latex formulas included\n# as images in the HTML documentation. The default is 10. Note that\n# when you change the font size after a successful doxygen run you need\n# to manually remove any form_*.png images from the HTML output directory\n# to force them to be regenerated.\n\nFORMULA_FONTSIZE       = 12\n\n# Use the FORMULA_TRANPARENT tag to determine whether or not the images\n# generated for formulas are transparent PNGs. Transparent PNGs are\n# not supported properly for IE 6.0, but are supported on all modern browsers.\n# Note that when changing this option you need to delete any form_*.png files\n# in the HTML output before the changes have effect.\n\nFORMULA_TRANSPARENT    = YES\n\n# Enable the USE_MATHJAX option to render LaTeX formulas using MathJax\n# (see http://www.mathjax.org) which uses client side Javascript for the\n# rendering instead of using prerendered bitmaps. Use this if you do not\n# have LaTeX installed or if you want to formulas look prettier in the HTML\n# output. When enabled you may also need to install MathJax separately and\n# configure the path to it using the MATHJAX_RELPATH option.\n\nUSE_MATHJAX            = @EIGEN_DOXY_USE_MATHJAX@\n\n# When MathJax is enabled you need to specify the location relative to the\n# HTML output directory using the MATHJAX_RELPATH option. The destination\n# directory should contain the MathJax.js script. For instance, if the mathjax\n# directory is located at the same level as the HTML output directory, then\n# MATHJAX_RELPATH should be ../mathjax. The default value points to\n# the MathJax Content Delivery Network so you can quickly see the result without\n# installing MathJax.\n# However, it is strongly recommended to install a local\n# copy of MathJax from http://www.mathjax.org before deployment.\n\nMATHJAX_RELPATH        = https://cdn.mathjax.org/mathjax/latest\n\n# The MATHJAX_EXTENSIONS tag can be used to specify one or MathJax extension\n# names that should be enabled during MathJax rendering.\n\nMATHJAX_EXTENSIONS     = TeX/AMSmath TeX/AMSsymbols\n\n# When the SEARCHENGINE tag is enabled doxygen will generate a search box\n# for the HTML output. The underlying search engine uses javascript\n# and DHTML and should work on any modern browser. Note that when using\n# HTML help (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets\n# (GENERATE_DOCSET) there is already a search function so this one should\n# typically be disabled. For large projects the javascript based search engine\n# can be slow, then enabling SERVER_BASED_SEARCH may provide a better solution.\n\nSEARCHENGINE           = YES\n\n# When the SERVER_BASED_SEARCH tag is enabled the search engine will be\n# implemented using a PHP enabled web server instead of at the web client\n# using Javascript. Doxygen will generate the search PHP script and index\n# file to put on the web server. The advantage of the server\n# based approach is that it scales better to large projects and allows\n# full text search. The disadvantages are that it is more difficult to setup\n# and does not have live searching capabilities.\n\nSERVER_BASED_SEARCH    = NO\n\n#---------------------------------------------------------------------------\n# configuration options related to the LaTeX output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_LATEX tag is set to YES (the default) Doxygen will\n# generate Latex output.\n\nGENERATE_LATEX         = NO\n\n# The LATEX_OUTPUT tag is used to specify where the LaTeX docs will be put.\n# If a relative path is entered the value of OUTPUT_DIRECTORY will be\n# put in front of it. If left blank `latex' will be used as the default path.\n\nLATEX_OUTPUT           = latex\n\n# The LATEX_CMD_NAME tag can be used to specify the LaTeX command name to be\n# invoked. If left blank `latex' will be used as the default command name.\n# Note that when enabling USE_PDFLATEX this option is only used for\n# generating bitmaps for formulas in the HTML output, but not in the\n# Makefile that is written to the output directory.\n\nLATEX_CMD_NAME         = latex\n\n# The MAKEINDEX_CMD_NAME tag can be used to specify the command name to\n# generate index for LaTeX. If left blank `makeindex' will be used as the\n# default command name.\n\nMAKEINDEX_CMD_NAME     = makeindex\n\n# If the COMPACT_LATEX tag is set to YES Doxygen generates more compact\n# LaTeX documents. This may be useful for small projects and may help to\n# save some trees in general.\n\nCOMPACT_LATEX          = NO\n\n# The PAPER_TYPE tag can be used to set the paper type that is used\n# by the printer. Possible values are: a4, letter, legal and\n# executive. If left blank a4wide will be used.\n\nPAPER_TYPE             = a4wide\n\n# The EXTRA_PACKAGES tag can be to specify one or more names of LaTeX\n# packages that should be included in the LaTeX output.\n\nEXTRA_PACKAGES         = amssymb \\\n                         amsmath\n\n# The LATEX_HEADER tag can be used to specify a personal LaTeX header for\n# the generated latex document. The header should contain everything until\n# the first chapter. If it is left blank doxygen will generate a\n# standard header. Notice: only use this tag if you know what you are doing!\n\nLATEX_HEADER           =\n\n# The LATEX_FOOTER tag can be used to specify a personal LaTeX footer for\n# the generated latex document. The footer should contain everything after\n# the last chapter. If it is left blank doxygen will generate a\n# standard footer. Notice: only use this tag if you know what you are doing!\n\nLATEX_FOOTER           =\n\n# If the PDF_HYPERLINKS tag is set to YES, the LaTeX that is generated\n# is prepared for conversion to pdf (using ps2pdf). The pdf file will\n# contain links (just like the HTML output) instead of page references\n# This makes the output suitable for online browsing using a pdf viewer.\n\nPDF_HYPERLINKS         = NO\n\n# If the USE_PDFLATEX tag is set to YES, pdflatex will be used instead of\n# plain latex in the generated Makefile. Set this option to YES to get a\n# higher quality PDF documentation.\n\nUSE_PDFLATEX           = NO\n\n# If the LATEX_BATCHMODE tag is set to YES, doxygen will add the \\\\batchmode.\n# command to the generated LaTeX files. This will instruct LaTeX to keep\n# running if errors occur, instead of asking the user for help.\n# This option is also used when generating formulas in HTML.\n\nLATEX_BATCHMODE        = NO\n\n# If LATEX_HIDE_INDICES is set to YES then doxygen will not\n# include the index chapters (such as File Index, Compound Index, etc.)\n# in the output.\n\nLATEX_HIDE_INDICES     = NO\n\n# If LATEX_SOURCE_CODE is set to YES then doxygen will include\n# source code with syntax highlighting in the LaTeX output.\n# Note that which sources are shown also depends on other settings\n# such as SOURCE_BROWSER.\n\nLATEX_SOURCE_CODE      = NO\n\n# The LATEX_BIB_STYLE tag can be used to specify the style to use for the\n# bibliography, e.g. plainnat, or ieeetr. The default style is \"plain\". See\n# http://en.wikipedia.org/wiki/BibTeX for more info.\n\nLATEX_BIB_STYLE        = plain\n\n#---------------------------------------------------------------------------\n# configuration options related to the RTF output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_RTF tag is set to YES Doxygen will generate RTF output\n# The RTF output is optimized for Word 97 and may not look very pretty with\n# other RTF readers or editors.\n\nGENERATE_RTF           = NO\n\n# The RTF_OUTPUT tag is used to specify where the RTF docs will be put.\n# If a relative path is entered the value of OUTPUT_DIRECTORY will be\n# put in front of it. If left blank `rtf' will be used as the default path.\n\nRTF_OUTPUT             = rtf\n\n# If the COMPACT_RTF tag is set to YES Doxygen generates more compact\n# RTF documents. This may be useful for small projects and may help to\n# save some trees in general.\n\nCOMPACT_RTF            = NO\n\n# If the RTF_HYPERLINKS tag is set to YES, the RTF that is generated\n# will contain hyperlink fields. The RTF file will\n# contain links (just like the HTML output) instead of page references.\n# This makes the output suitable for online browsing using WORD or other\n# programs which support those fields.\n# Note: wordpad (write) and others do not support links.\n\nRTF_HYPERLINKS         = NO\n\n# Load style sheet definitions from file. Syntax is similar to doxygen's\n# config file, i.e. a series of assignments. You only have to provide\n# replacements, missing definitions are set to their default value.\n\nRTF_STYLESHEET_FILE    =\n\n# Set optional variables used in the generation of an rtf document.\n# Syntax is similar to doxygen's config file.\n\nRTF_EXTENSIONS_FILE    =\n\n#---------------------------------------------------------------------------\n# configuration options related to the man page output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_MAN tag is set to YES (the default) Doxygen will\n# generate man pages\n\nGENERATE_MAN           = NO\n\n# The MAN_OUTPUT tag is used to specify where the man pages will be put.\n# If a relative path is entered the value of OUTPUT_DIRECTORY will be\n# put in front of it. If left blank `man' will be used as the default path.\n\nMAN_OUTPUT             = man\n\n# The MAN_EXTENSION tag determines the extension that is added to\n# the generated man pages (default is the subroutine's section .3)\n\nMAN_EXTENSION          = .3\n\n# If the MAN_LINKS tag is set to YES and Doxygen generates man output,\n# then it will generate one additional man file for each entity\n# documented in the real man page(s). These additional files\n# only source the real man page, but without them the man command\n# would be unable to find the correct page. The default is NO.\n\nMAN_LINKS              = NO\n\n#---------------------------------------------------------------------------\n# configuration options related to the XML output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_XML tag is set to YES Doxygen will\n# generate an XML file that captures the structure of\n# the code including all documentation.\n\nGENERATE_XML           = NO\n\n# The XML_OUTPUT tag is used to specify where the XML pages will be put.\n# If a relative path is entered the value of OUTPUT_DIRECTORY will be\n# put in front of it. If left blank `xml' will be used as the default path.\n\nXML_OUTPUT             = xml\n\n# The XML_SCHEMA tag can be used to specify an XML schema,\n# which can be used by a validating XML parser to check the\n# syntax of the XML files.\n\n# XML_SCHEMA             =\n\n# The XML_DTD tag can be used to specify an XML DTD,\n# which can be used by a validating XML parser to check the\n# syntax of the XML files.\n\n# XML_DTD                =\n\n# If the XML_PROGRAMLISTING tag is set to YES Doxygen will\n# dump the program listings (including syntax highlighting\n# and cross-referencing information) to the XML output. Note that\n# enabling this will significantly increase the size of the XML output.\n\nXML_PROGRAMLISTING     = YES\n\n#---------------------------------------------------------------------------\n# configuration options for the AutoGen Definitions output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_AUTOGEN_DEF tag is set to YES Doxygen will\n# generate an AutoGen Definitions (see autogen.sf.net) file\n# that captures the structure of the code including all\n# documentation. Note that this feature is still experimental\n# and incomplete at the moment.\n\nGENERATE_AUTOGEN_DEF   = NO\n\n#---------------------------------------------------------------------------\n# configuration options related to the Perl module output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_PERLMOD tag is set to YES Doxygen will\n# generate a Perl module file that captures the structure of\n# the code including all documentation. Note that this\n# feature is still experimental and incomplete at the\n# moment.\n\nGENERATE_PERLMOD       = NO\n\n# If the PERLMOD_LATEX tag is set to YES Doxygen will generate\n# the necessary Makefile rules, Perl scripts and LaTeX code to be able\n# to generate PDF and DVI output from the Perl module output.\n\nPERLMOD_LATEX          = NO\n\n# If the PERLMOD_PRETTY tag is set to YES the Perl module output will be\n# nicely formatted so it can be parsed by a human reader.\n# This is useful\n# if you want to understand what is going on.\n# On the other hand, if this\n# tag is set to NO the size of the Perl module output will be much smaller\n# and Perl will parse it just the same.\n\nPERLMOD_PRETTY         = YES\n\n# The names of the make variables in the generated doxyrules.make file\n# are prefixed with the string contained in PERLMOD_MAKEVAR_PREFIX.\n# This is useful so different doxyrules.make files included by the same\n# Makefile don't overwrite each other's variables.\n\nPERLMOD_MAKEVAR_PREFIX =\n\n#---------------------------------------------------------------------------\n# Configuration options related to the preprocessor\n#---------------------------------------------------------------------------\n\n# If the ENABLE_PREPROCESSING tag is set to YES (the default) Doxygen will\n# evaluate all C-preprocessor directives found in the sources and include\n# files.\n\nENABLE_PREPROCESSING   = YES\n\n# If the MACRO_EXPANSION tag is set to YES Doxygen will expand all macro\n# names in the source code. If set to NO (the default) only conditional\n# compilation will be performed. Macro expansion can be done in a controlled\n# way by setting EXPAND_ONLY_PREDEF to YES.\n\nMACRO_EXPANSION        = YES\n\n# If the EXPAND_ONLY_PREDEF and MACRO_EXPANSION tags are both set to YES\n# then the macro expansion is limited to the macros specified with the\n# PREDEFINED and EXPAND_AS_DEFINED tags.\n\nEXPAND_ONLY_PREDEF     = YES\n\n# If the SEARCH_INCLUDES tag is set to YES (the default) the includes files\n# pointed to by INCLUDE_PATH will be searched when a #include is found.\n\nSEARCH_INCLUDES        = YES\n\n# The INCLUDE_PATH tag can be used to specify one or more directories that\n# contain include files that are not input files but should be processed by\n# the preprocessor.\n\nINCLUDE_PATH           = \"${Eigen_SOURCE_DIR}/Eigen/src/plugins\"\n\n# You can use the INCLUDE_FILE_PATTERNS tag to specify one or more wildcard\n# patterns (like *.h and *.hpp) to filter out the header-files in the\n# directories. If left blank, the patterns specified with FILE_PATTERNS will\n# be used.\n\nINCLUDE_FILE_PATTERNS  =\n\n# The PREDEFINED tag can be used to specify one or more macro names that\n# are defined before the preprocessor is started (similar to the -D option of\n# gcc). The argument of the tag is a list of macros of the form: name\n# or name=definition (no spaces). If the definition and the = are\n# omitted =1 is assumed. To prevent a macro definition from being\n# undefined via #undef or recursively expanded use the := operator\n# instead of the = operator.\n\nPREDEFINED             = EIGEN_EMPTY_STRUCT \\\n                         EIGEN_PARSED_BY_DOXYGEN \\\n                         EIGEN_VECTORIZE \\\n                         EIGEN_QT_SUPPORT \\\n                         EIGEN_STRONG_INLINE=inline \\\n                         EIGEN_DEVICE_FUNC= \\\n                         EIGEN_HAS_CXX11=1 \\\n                         EIGEN_HAS_CXX11_MATH=1 \\\n                         \"EIGEN_MAKE_CWISE_BINARY_OP(METHOD,FUNCTOR)=template<typename OtherDerived> const CwiseBinaryOp<FUNCTOR<Scalar>, const Derived, const OtherDerived> METHOD(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const;\" \\\n                         \"EIGEN_CWISE_PRODUCT_RETURN_TYPE(LHS,RHS)=CwiseBinaryOp<internal::scalar_product_op<LHS::Scalar,RHS::Scalar>, const LHS, const RHS>\"\\\n                         \"EIGEN_CAT2(a,b)= a ## b\"\\\n                         \"EIGEN_CAT(a,b)=EIGEN_CAT2(a,b)\"\\\n                         \"EIGEN_CWISE_BINARY_RETURN_TYPE(LHS,RHS,OPNAME)=CwiseBinaryOp<EIGEN_CAT(EIGEN_CAT(internal::scalar_,OPNAME),_op)<LHS::Scalar, RHS::Scalar>, const LHS, const RHS>\"\\\n                         \"EIGEN_ALIGN_TO_BOUNDARY(x)=\"\\\n                         DOXCOMMA=,\n\n\n# If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then\n# this tag can be used to specify a list of macro names that should be expanded.\n# The macro definition that is found in the sources will be used.\n# Use the PREDEFINED tag if you want to use a different macro definition that\n# overrules the definition found in the source code.\n\nEXPAND_AS_DEFINED      = EIGEN_MAKE_TYPEDEFS \\\n                         EIGEN_MAKE_FIXED_TYPEDEFS \\\n                         EIGEN_MAKE_TYPEDEFS_ALL_SIZES \\\n                         EIGEN_MAKE_ARRAY_TYPEDEFS \\\n                         EIGEN_MAKE_ARRAY_FIXED_TYPEDEFS \\\n                         EIGEN_MAKE_ARRAY_TYPEDEFS_ALL_SIZES \\\n                         EIGEN_CWISE_UNOP_RETURN_TYPE \\\n                         EIGEN_CWISE_BINOP_RETURN_TYPE \\\n                         EIGEN_CURRENT_STORAGE_BASE_CLASS \\\n                         EIGEN_MATHFUNC_IMPL \\\n                         _EIGEN_GENERIC_PUBLIC_INTERFACE \\\n                         EIGEN_ARRAY_DECLARE_GLOBAL_UNARY \\\n                         EIGEN_EMPTY \\\n                         EIGEN_EULER_ANGLES_TYPEDEFS \\\n                         EIGEN_EULER_ANGLES_SINGLE_TYPEDEF \\\n                         EIGEN_EULER_SYSTEM_TYPEDEF \\\n                         EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY \\\n                         EIGEN_MATRIX_FUNCTION \\\n                         EIGEN_MATRIX_FUNCTION_1 \\\n                         EIGEN_DOC_UNARY_ADDONS \\\n                         EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL \\\n                         EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF\n\n\n# If the SKIP_FUNCTION_MACROS tag is set to YES (the default) then\n# doxygen's preprocessor will remove all references to function-like macros\n# that are alone on a line, have an all uppercase name, and do not end with a\n# semicolon, because these will confuse the parser if not removed.\n\nSKIP_FUNCTION_MACROS   = YES\n\n#---------------------------------------------------------------------------\n# Configuration::additions related to external references\n#---------------------------------------------------------------------------\n\n# The TAGFILES option can be used to specify one or more tagfiles. For each\n# tag file the location of the external documentation should be added. The\n# format of a tag file without this location is as follows:\n#\n# TAGFILES = file1 file2 ...\n# Adding location for the tag files is done as follows:\n#\n# TAGFILES = file1=loc1 \"file2 = loc2\" ...\n# where \"loc1\" and \"loc2\" can be relative or absolute paths\n# or URLs. Note that each tag file must have a unique name (where the name does\n# NOT include the path). If a tag file is not located in the directory in which\n# doxygen is run, you must also specify the path to the tagfile here.\n\nTAGFILES               = ${EIGEN_DOXY_TAGFILES}\n# \"${Eigen_BINARY_DIR}/doc/eigen-unsupported.doxytags =unsupported\"\n\n# When a file name is specified after GENERATE_TAGFILE, doxygen will create\n# a tag file that is based on the input files it reads.\n\nGENERATE_TAGFILE       = \"${Eigen_BINARY_DIR}/doc/${EIGEN_DOXY_PROJECT_NAME}.doxytags\"\n\n# If the ALLEXTERNALS tag is set to YES all external classes will be listed\n# in the class index. If set to NO only the inherited external classes\n# will be listed.\n\nALLEXTERNALS           = NO\n\n# If the EXTERNAL_GROUPS tag is set to YES all external groups will be listed\n# in the modules index. If set to NO, only the current project's groups will\n# be listed.\n\nEXTERNAL_GROUPS        = NO\n\n# The PERL_PATH should be the absolute path and name of the perl script\n# interpreter (i.e. the result of `which perl').\n\nPERL_PATH              = /usr/bin/perl\n\n#---------------------------------------------------------------------------\n# Configuration options related to the dot tool\n#---------------------------------------------------------------------------\n\n# If the CLASS_DIAGRAMS tag is set to YES (the default) Doxygen will\n# generate a inheritance diagram (in HTML, RTF and LaTeX) for classes with base\n# or super classes. Setting the tag to NO turns the diagrams off. Note that\n# this option also works with HAVE_DOT disabled, but it is recommended to\n# install and use dot, since it yields more powerful graphs.\n\nCLASS_DIAGRAMS         = YES\n\n# You can define message sequence charts within doxygen comments using the \\msc\n# command. Doxygen will then run the mscgen tool (see\n# http://www.mcternan.me.uk/mscgen/) to produce the chart and insert it in the\n# documentation. The MSCGEN_PATH tag allows you to specify the directory where\n# the mscgen tool resides. If left empty the tool is assumed to be found in the\n# default search path.\n\nMSCGEN_PATH            =\n\n# If set to YES, the inheritance and collaboration graphs will hide\n# inheritance and usage relations if the target is undocumented\n# or is not a class.\n\nHIDE_UNDOC_RELATIONS   = NO\n\n# If you set the HAVE_DOT tag to YES then doxygen will assume the dot tool is\n# available from the path. This tool is part of Graphviz, a graph visualization\n# toolkit from AT&T and Lucent Bell Labs. The other options in this section\n# have no effect if this option is set to NO (the default)\n\nHAVE_DOT               = YES\n\n# The DOT_NUM_THREADS specifies the number of dot invocations doxygen is\n# allowed to run in parallel. When set to 0 (the default) doxygen will\n# base this on the number of processors available in the system. You can set it\n# explicitly to a value larger than 0 to get control over the balance\n# between CPU load and processing speed.\n\nDOT_NUM_THREADS        = 0\n\n# By default doxygen will use the Helvetica font for all dot files that\n# doxygen generates. When you want a differently looking font you can specify\n# the font name using DOT_FONTNAME. You need to make sure dot is able to find\n# the font, which can be done by putting it in a standard location or by setting\n# the DOTFONTPATH environment variable or by setting DOT_FONTPATH to the\n# directory containing the font.\n\nDOT_FONTNAME           = \n\n# The DOT_FONTSIZE tag can be used to set the size of the font of dot graphs.\n# The default size is 10pt.\n\nDOT_FONTSIZE           = 10\n\n# By default doxygen will tell dot to use the Helvetica font.\n# If you specify a different font using DOT_FONTNAME you can use DOT_FONTPATH to\n# set the path where dot can find it.\n\nDOT_FONTPATH           =\n\n# If the CLASS_GRAPH and HAVE_DOT tags are set to YES then doxygen\n# will generate a graph for each documented class showing the direct and\n# indirect inheritance relations. Setting this tag to YES will force the\n# CLASS_DIAGRAMS tag to NO.\n\nCLASS_GRAPH            = YES\n\n# If the COLLABORATION_GRAPH and HAVE_DOT tags are set to YES then doxygen\n# will generate a graph for each documented class showing the direct and\n# indirect implementation dependencies (inheritance, containment, and\n# class references variables) of the class with other documented classes.\n\nCOLLABORATION_GRAPH    = NO\n\n# If the GROUP_GRAPHS and HAVE_DOT tags are set to YES then doxygen\n# will generate a graph for groups, showing the direct groups dependencies\n\nGROUP_GRAPHS           = NO\n\n# If the UML_LOOK tag is set to YES doxygen will generate inheritance and\n# collaboration diagrams in a style similar to the OMG's Unified Modeling\n# Language.\n\nUML_LOOK               = YES\n\n# If the UML_LOOK tag is enabled, the fields and methods are shown inside\n# the class node. If there are many fields or methods and many nodes the\n# graph may become too big to be useful. The UML_LIMIT_NUM_FIELDS\n# threshold limits the number of items for each type to make the size more\n# manageable. Set this to 0 for no limit. Note that the threshold may be\n# exceeded by 50% before the limit is enforced.\n\nUML_LIMIT_NUM_FIELDS   = 10\n\n# If set to YES, the inheritance and collaboration graphs will show the\n# relations between templates and their instances.\n\nTEMPLATE_RELATIONS     = NO\n\n# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDE_GRAPH, and HAVE_DOT\n# tags are set to YES then doxygen will generate a graph for each documented\n# file showing the direct and indirect include dependencies of the file with\n# other documented files.\n\nINCLUDE_GRAPH          = NO\n\n# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDED_BY_GRAPH, and\n# HAVE_DOT tags are set to YES then doxygen will generate a graph for each\n# documented header file showing the documented files that directly or\n# indirectly include this file.\n\nINCLUDED_BY_GRAPH      = NO\n\n# If the CALL_GRAPH and HAVE_DOT options are set to YES then\n# doxygen will generate a call dependency graph for every global function\n# or class method. Note that enabling this option will significantly increase\n# the time of a run. So in most cases it will be better to enable call graphs\n# for selected functions only using the \\callgraph command.\n\nCALL_GRAPH             = NO\n\n# If the CALLER_GRAPH and HAVE_DOT tags are set to YES then\n# doxygen will generate a caller dependency graph for every global function\n# or class method. Note that enabling this option will significantly increase\n# the time of a run. So in most cases it will be better to enable caller\n# graphs for selected functions only using the \\callergraph command.\n\nCALLER_GRAPH           = NO\n\n# If the GRAPHICAL_HIERARCHY and HAVE_DOT tags are set to YES then doxygen\n# will generate a graphical hierarchy of all classes instead of a textual one.\n\nGRAPHICAL_HIERARCHY    = NO\n\n# If the DIRECTORY_GRAPH and HAVE_DOT tags are set to YES\n# then doxygen will show the dependencies a directory has on other directories\n# in a graphical way. The dependency relations are determined by the #include\n# relations between the files in the directories.\n\nDIRECTORY_GRAPH        = NO\n\n# The DOT_IMAGE_FORMAT tag can be used to set the image format of the images\n# generated by dot. Possible values are svg, png, jpg, or gif.\n# If left blank png will be used. If you choose svg you need to set\n# HTML_FILE_EXTENSION to xhtml in order to make the SVG files\n# visible in IE 9+ (other browsers do not have this requirement).\n\nDOT_IMAGE_FORMAT       = png\n\n# If DOT_IMAGE_FORMAT is set to svg, then this option can be set to YES to\n# enable generation of interactive SVG images that allow zooming and panning.\n# Note that this requires a modern browser other than Internet Explorer.\n# Tested and working are Firefox, Chrome, Safari, and Opera. For IE 9+ you\n# need to set HTML_FILE_EXTENSION to xhtml in order to make the SVG files\n# visible. Older versions of IE do not have SVG support.\n\nINTERACTIVE_SVG        = NO\n\n# The tag DOT_PATH can be used to specify the path where the dot tool can be\n# found. If left blank, it is assumed the dot tool can be found in the path.\n\nDOT_PATH               =\n\n# The DOTFILE_DIRS tag can be used to specify one or more directories that\n# contain dot files that are included in the documentation (see the\n# \\dotfile command).\n\nDOTFILE_DIRS           =\n\n# The MSCFILE_DIRS tag can be used to specify one or more directories that\n# contain msc files that are included in the documentation (see the\n# \\mscfile command).\n\nMSCFILE_DIRS           =\n\n# The DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of\n# nodes that will be shown in the graph. If the number of nodes in a graph\n# becomes larger than this value, doxygen will truncate the graph, which is\n# visualized by representing a node as a red box. Note that doxygen if the\n# number of direct children of the root node in a graph is already larger than\n# DOT_GRAPH_MAX_NODES then the graph will not be shown at all. Also note\n# that the size of a graph can be further restricted by MAX_DOT_GRAPH_DEPTH.\n\nDOT_GRAPH_MAX_NODES    = 50\n\n# The MAX_DOT_GRAPH_DEPTH tag can be used to set the maximum depth of the\n# graphs generated by dot. A depth value of 3 means that only nodes reachable\n# from the root by following a path via at most 3 edges will be shown. Nodes\n# that lay further from the root node will be omitted. Note that setting this\n# option to 1 or 2 may greatly reduce the computation time needed for large\n# code bases. Also note that the size of a graph can be further restricted by\n# DOT_GRAPH_MAX_NODES. Using a depth of 0 means no depth restriction.\n\nMAX_DOT_GRAPH_DEPTH    = 0\n\n# Set the DOT_TRANSPARENT tag to YES to generate images with a transparent\n# background. This is disabled by default, because dot on Windows does not\n# seem to support this out of the box. Warning: Depending on the platform used,\n# enabling this option may lead to badly anti-aliased labels on the edges of\n# a graph (i.e. they become hard to read).\n\nDOT_TRANSPARENT        = NO\n\n# Set the DOT_MULTI_TARGETS tag to YES allow dot to generate multiple output\n# files in one run (i.e. multiple -o and -T options on the command line). This\n# makes dot run faster, but since only newer versions of dot (>1.8.10)\n# support this, this feature is disabled by default.\n\nDOT_MULTI_TARGETS      = NO\n\n# If the GENERATE_LEGEND tag is set to YES (the default) Doxygen will\n# generate a legend page explaining the meaning of the various boxes and\n# arrows in the dot generated graphs.\n\nGENERATE_LEGEND        = YES\n\n# If the DOT_CLEANUP tag is set to YES (the default) Doxygen will\n# remove the intermediate dot files that are used to generate\n# the various graphs.\n\nDOT_CLEANUP            = YES\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/FixedSizeVectorizable.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TopicFixedSizeVectorizable Fixed-size vectorizable %Eigen objects\n\nThe goal of this page is to explain what we mean by \"fixed-size vectorizable\".\n\n\\section FixedSizeVectorizable_summary Executive Summary\n\nAn Eigen object is called \"fixed-size vectorizable\" if it has fixed size and that size is a multiple of 16 bytes.\n\nExamples include:\n\\li Eigen::Vector2d\n\\li Eigen::Vector4d\n\\li Eigen::Vector4f\n\\li Eigen::Matrix2d\n\\li Eigen::Matrix2f\n\\li Eigen::Matrix4d\n\\li Eigen::Matrix4f\n\\li Eigen::Affine3d\n\\li Eigen::Affine3f\n\\li Eigen::Quaterniond\n\\li Eigen::Quaternionf\n\n\\section FixedSizeVectorizable_explanation Explanation\n\nFirst, \"fixed-size\" should be clear: an %Eigen object has fixed size if its number of rows and its number of columns are fixed at compile-time. So for example \\ref Matrix3f has fixed size, but \\ref MatrixXf doesn't (the opposite of fixed-size is dynamic-size).\n\nThe array of coefficients of a fixed-size %Eigen object is a plain \"static array\", it is not dynamically allocated. For example, the data behind a \\ref Matrix4f is just a \"float array[16]\".\n\nFixed-size objects are typically very small, which means that we want to handle them with zero runtime overhead -- both in terms of memory usage and of speed.\n\nNow, vectorization works with 128-bit packets (e.g., SSE, AltiVec, NEON), 256-bit packets (e.g., AVX), or 512-bit packets (e.g., AVX512). Moreover, for performance reasons, these packets are most efficiently read and written if they have the same alignment as the packet size, that is 16 bytes, 32 bytes, and 64 bytes respectively.\n\nSo it turns out that the best way that fixed-size %Eigen objects can be vectorized, is if their size is a multiple of 16 bytes (or more). %Eigen will then request 16-byte alignment (or more) for these objects, and henceforth rely on these objects being aligned to achieve maximal efficiency.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/FunctionsTakingEigenTypes.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicFunctionTakingEigenTypes Writing Functions Taking %Eigen Types as Parameters\n\n%Eigen's use of expression templates results in potentially every expression being of a different type. If you pass such an expression to a function taking a parameter of type Matrix, your expression will implicitly be evaluated into a temporary Matrix, which will then be passed to the function. This means that you lose the benefit of expression templates. Concretely, this has two drawbacks:\n \\li The evaluation into a temporary may be useless and inefficient;\n \\li This only allows the function to read from the expression, not to write to it.\n\nFortunately, all this myriad of expression types have in common that they all inherit a few common, templated base classes. By letting your function take templated parameters of these base types, you can let them play nicely with %Eigen's expression templates.\n\n\\eigenAutoToc\n\n\\section TopicFirstExamples Some First Examples\n\nThis section will provide simple examples for different types of objects %Eigen is offering. Before starting with the actual examples, we need to recapitulate which base objects we can work with (see also \\ref TopicClassHierarchy).\n\n \\li MatrixBase: The common base class for all dense matrix expressions (as opposed to array expressions, as opposed to sparse and special matrix classes). Use it in functions that are meant to work only on dense matrices.\n \\li ArrayBase: The common base class for all dense array expressions (as opposed to matrix expressions, etc). Use it in functions that are meant to work only on arrays.\n \\li DenseBase: The common base class for all dense matrix expression, that is, the base class for both \\c MatrixBase and \\c ArrayBase. It can be used in functions that are meant to work on both matrices and arrays.\n \\li EigenBase: The base class unifying all types of objects that can be evaluated into dense matrices or arrays, for example special matrix classes such as diagonal matrices, permutation matrices, etc. It can be used in functions that are meant to work on any such general type.\n\n<b> %EigenBase Example </b><br/><br/>\nPrints the dimensions of the most generic object present in %Eigen. It could be any matrix expressions, any dense or sparse matrix and any array.\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include function_taking_eigenbase.cpp\n</td>\n<td>\n\\verbinclude function_taking_eigenbase.out\n</td></tr></table>\n<b> %DenseBase Example </b><br/><br/>\nPrints a sub-block of the dense expression. Accepts any dense matrix or array expression, but no sparse objects and no special matrix classes such as DiagonalMatrix.\n\\code\ntemplate <typename Derived>\nvoid print_block(const DenseBase<Derived>& b, int x, int y, int r, int c)\n{\n  std::cout << \"block: \" << b.block(x,y,r,c) << std::endl;\n}\n\\endcode\n<b> %ArrayBase Example </b><br/><br/>\nPrints the maximum coefficient of the array or array-expression.\n\\code\ntemplate <typename Derived>\nvoid print_max_coeff(const ArrayBase<Derived> &a)\n{\n  std::cout << \"max: \" << a.maxCoeff() << std::endl;\n}\n\\endcode\n<b> %MatrixBase Example </b><br/><br/>\nPrints the inverse condition number of the given matrix or matrix-expression.\n\\code\ntemplate <typename Derived>\nvoid print_inv_cond(const MatrixBase<Derived>& a)\n{\n  const typename JacobiSVD<typename Derived::PlainObject>::SingularValuesType&\n    sing_vals = a.jacobiSvd().singularValues();\n  std::cout << \"inv cond: \" << sing_vals(sing_vals.size()-1) / sing_vals(0) << std::endl;\n}\n\\endcode\n<b> Multiple templated arguments example </b><br/><br/>\nCalculate the Euclidean distance between two points.\n\\code\ntemplate <typename DerivedA,typename DerivedB>\ntypename DerivedA::Scalar squaredist(const MatrixBase<DerivedA>& p1,const MatrixBase<DerivedB>& p2)\n{\n  return (p1-p2).squaredNorm();\n}\n\\endcode\nNotice that we used two template parameters, one per argument. This permits the function to handle inputs of different types, e.g.,\n\\code\nsquaredist(v1,2*v2)\n\\endcode\nwhere the first argument \\c v1 is a vector and the second argument \\c 2*v2 is an expression.\n<br/><br/>\n\nThese examples are just intended to give the reader a first impression of how functions can be written which take a plain and constant Matrix or Array argument. They are also intended to give the reader an idea about the most common base classes being the optimal candidates for functions. In the next section we will look in more detail at an example and the different ways it can be implemented, while discussing each implementation's problems and advantages. For the discussion below, Matrix and Array as well as MatrixBase and ArrayBase can be exchanged and all arguments still hold.\n\n\n\\section TopicUsingRefClass How to write generic, but non-templated function?\n\nIn all the previous examples, the functions had to be template functions. This approach allows to write very generic code, but it is often desirable to write non templated functions and still keep some level of genericity to avoid stupid copies of the arguments. The typical example is to write functions accepting both a MatrixXf or a block of a MatrixXf. This is exactly the purpose of the Ref class. Here is a simple example:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include function_taking_ref.cpp\n</td>\n<td>\n\\verbinclude function_taking_ref.out\n</td></tr></table>\nIn the first two calls to inv_cond, no copy occur because the memory layout of the arguments matches the memory layout accepted by Ref<MatrixXf>. However, in the last call, we have a generic expression that will be automatically evaluated into a temporary MatrixXf by the Ref<> object.\n\nA Ref object can also be writable. Here is an example of a function computing the covariance matrix of two input matrices where each row is an observation:\n\\code\nvoid cov(const Ref<const MatrixXf> x, const Ref<const MatrixXf> y, Ref<MatrixXf> C)\n{\n  const float num_observations = static_cast<float>(x.rows());\n  const RowVectorXf x_mean = x.colwise().sum() / num_observations;\n  const RowVectorXf y_mean = y.colwise().sum() / num_observations;\n  C = (x.rowwise() - x_mean).transpose() * (y.rowwise() - y_mean) / num_observations;\n}\n\\endcode\nand here are two examples calling cov without any copy:\n\\code\nMatrixXf m1, m2, m3\ncov(m1, m2, m3);\ncov(m1.leftCols<3>(), m2.leftCols<3>(), m3.topLeftCorner<3,3>());\n\\endcode\nThe Ref<> class has two other optional template arguments allowing to control the kind of memory layout that can be accepted without any copy. See the class Ref documentation for the details.\n\n\\section TopicPlainFunctionsWorking In which cases do functions taking plain Matrix or Array arguments work?\n\nWithout using template functions, and without the Ref class, a naive implementation of the previous cov function might look like this\n\\code\nMatrixXf cov(const MatrixXf& x, const MatrixXf& y)\n{\n  const float num_observations = static_cast<float>(x.rows());\n  const RowVectorXf x_mean = x.colwise().sum() / num_observations;\n  const RowVectorXf y_mean = y.colwise().sum() / num_observations;\n  return (x.rowwise() - x_mean).transpose() * (y.rowwise() - y_mean) / num_observations;\n}\n\\endcode\nand contrary to what one might think at first, this implementation is fine unless you require a generic implementation that works with double matrices too and unless you do not care about temporary objects. Why is that the case? Where are temporaries involved? How can code as given below compile?\n\\code\nMatrixXf x,y,z;\nMatrixXf C = cov(x,y+z);\n\\endcode\nIn this special case, the example is fine and will be working because both parameters are declared as \\e const references. The compiler creates a temporary and evaluates the expression x+z into this temporary. Once the function is processed, the temporary is released and the result is assigned to C.\n\n\\b Note: Functions taking \\e const references to Matrix (or Array) can process expressions at the cost of temporaries.\n\n\n\\section TopicPlainFunctionsFailing In which cases do functions taking a plain Matrix or Array argument fail?\n\nHere, we consider a slightly modified version of the function given above. This time, we do not want to return the result but pass an additional non-const parameter which allows us to store the result. A first naive implementation might look as follows.\n\\code\n// Note: This code is flawed!\nvoid cov(const MatrixXf& x, const MatrixXf& y, MatrixXf& C)\n{\n  const float num_observations = static_cast<float>(x.rows());\n  const RowVectorXf x_mean = x.colwise().sum() / num_observations;\n  const RowVectorXf y_mean = y.colwise().sum() / num_observations;\n  C = (x.rowwise() - x_mean).transpose() * (y.rowwise() - y_mean) / num_observations;\n}\n\\endcode\nWhen trying to execute the following code\n\\code\nMatrixXf C = MatrixXf::Zero(3,6);\ncov(x,y, C.block(0,0,3,3));\n\\endcode\nthe compiler will fail, because it is not possible to convert the expression returned by \\c MatrixXf::block() into a non-const \\c MatrixXf&. This is the case because the compiler wants to protect you from writing your result to a temporary object. In this special case this protection is not intended -- we want to write to a temporary object. So how can we overcome this problem? \n\nThe solution which is preferred at the moment is based on a little \\em hack. One needs to pass a const reference to the matrix and internally the constness needs to be cast away. The correct implementation for C98 compliant compilers would be\n\\code\ntemplate <typename Derived, typename OtherDerived>\nvoid cov(const MatrixBase<Derived>& x, const MatrixBase<Derived>& y, MatrixBase<OtherDerived> const & C)\n{\n  typedef typename Derived::Scalar Scalar;\n  typedef typename internal::plain_row_type<Derived>::type RowVectorType;\n\n  const Scalar num_observations = static_cast<Scalar>(x.rows());\n\n  const RowVectorType x_mean = x.colwise().sum() / num_observations;\n  const RowVectorType y_mean = y.colwise().sum() / num_observations;\n\n  const_cast< MatrixBase<OtherDerived>& >(C) =\n    (x.rowwise() - x_mean).transpose() * (y.rowwise() - y_mean) / num_observations;\n}\n\\endcode\nThe implementation above does now not only work with temporary expressions but it also allows to use the function with matrices of arbitrary floating point scalar types.\n\n\\b Note: The const cast hack will only work with templated functions. It will not work with the MatrixXf implementation because it is not possible to cast a Block expression to a Matrix reference!\n\n\n\n\\section TopicResizingInGenericImplementations How to resize matrices in generic implementations?\n\nOne might think we are done now, right? This is not completely true because in order for our covariance function to be generically applicable, we want the following code to work\n\\code\nMatrixXf x = MatrixXf::Random(100,3);\nMatrixXf y = MatrixXf::Random(100,3);\nMatrixXf C;\ncov(x, y, C);\n\\endcode\nThis is not the case anymore, when we are using an implementation taking MatrixBase as a parameter. In general, %Eigen supports automatic resizing but it is not possible to do so on expressions. Why should resizing of a matrix Block be allowed? It is a reference to a sub-matrix and we definitely don't want to resize that. So how can we incorporate resizing if we cannot resize on MatrixBase? The solution is to resize the derived object as in this implementation.\n\\code\ntemplate <typename Derived, typename OtherDerived>\nvoid cov(const MatrixBase<Derived>& x, const MatrixBase<Derived>& y, MatrixBase<OtherDerived> const & C_)\n{\n  typedef typename Derived::Scalar Scalar;\n  typedef typename internal::plain_row_type<Derived>::type RowVectorType;\n\n  const Scalar num_observations = static_cast<Scalar>(x.rows());\n\n  const RowVectorType x_mean = x.colwise().sum() / num_observations;\n  const RowVectorType y_mean = y.colwise().sum() / num_observations;\n\n  MatrixBase<OtherDerived>& C = const_cast< MatrixBase<OtherDerived>& >(C_);\n  \n  C.derived().resize(x.cols(),x.cols()); // resize the derived object\n  C = (x.rowwise() - x_mean).transpose() * (y.rowwise() - y_mean) / num_observations;\n}\n\\endcode\nThis implementation is now working for parameters being expressions and for parameters being matrices and having the wrong size. Resizing the expressions does not do any harm in this case unless they actually require resizing. That means, passing an expression with the wrong dimensions will result in a run-time error (in debug mode only) while passing expressions of the correct size will just work fine.\n\n\\b Note: In the above discussion the terms Matrix and Array and MatrixBase and ArrayBase can be exchanged and all arguments still hold.\n\n\\section TopicSummary Summary\n\n  - To summarize, the implementation of functions taking non-writable (const referenced) objects is not a big issue and does not lead to problematic situations in terms of compiling and running your program. However, a naive implementation is likely to introduce unnecessary temporary objects in your code. In order to avoid evaluating parameters into temporaries, pass them as (const) references to MatrixBase or ArrayBase (so templatize your function).\n\n  - Functions taking writable (non-const) parameters must take const references and cast away constness within the function body.\n\n  - Functions that take as parameters MatrixBase (or ArrayBase) objects, and potentially need to resize them (in the case where they are resizable), must call resize() on the derived class, as returned by derived().\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/HiPerformance.dox",
    "content": "\nnamespace Eigen {\n\n/** \\page TopicWritingEfficientProductExpression Writing efficient matrix product expressions\n\nIn general achieving good performance with Eigen does no require any special effort:\nsimply write your expressions in the most high level way. This is especially true\nfor small fixed size matrices. For large matrices, however, it might be useful to\ntake some care when writing your expressions in order to minimize useless evaluations\nand optimize the performance.\nIn this page we will give a brief overview of the Eigen's internal mechanism to simplify\nand evaluate complex product expressions, and discuss the current limitations.\nIn particular we will focus on expressions matching level 2 and 3 BLAS routines, i.e,\nall kind of matrix products and triangular solvers.\n\nIndeed, in Eigen we have implemented a set of highly optimized routines which are very similar\nto BLAS's ones. Unlike BLAS, those routines are made available to user via a high level and\nnatural API. Each of these routines can compute in a single evaluation a wide variety of expressions.\nGiven an expression, the challenge is then to map it to a minimal set of routines.\nAs explained latter, this mechanism has some limitations, and knowing them will allow\nyou to write faster code by making your expressions more Eigen friendly.\n\n\\section GEMM General Matrix-Matrix product (GEMM)\n\nLet's start with the most common primitive: the matrix product of general dense matrices.\nIn the BLAS world this corresponds to the GEMM routine. Our equivalent primitive can\nperform the following operation:\n\\f$ C.noalias() += \\alpha op1(A) op2(B) \\f$\nwhere A, B, and C are column and/or row major matrices (or sub-matrices),\nalpha is a scalar value, and op1, op2 can be transpose, adjoint, conjugate, or the identity.\nWhen Eigen detects a matrix product, it analyzes both sides of the product to extract a\nunique scalar factor alpha, and for each side, its effective storage order, shape, and conjugation states.\nMore precisely each side is simplified by iteratively removing trivial expressions such as scalar multiple,\nnegation and conjugation. Transpose and Block expressions are not evaluated and they only modify the storage order\nand shape. All other expressions are immediately evaluated.\nFor instance, the following expression:\n\\code m1.noalias() -= s4 * (s1 * m2.adjoint() * (-(s3*m3).conjugate()*s2))  \\endcode\nis automatically simplified to:\n\\code m1.noalias() += (s1*s2*conj(s3)*s4) * m2.adjoint() * m3.conjugate() \\endcode\nwhich exactly matches our GEMM routine.\n\n\\subsection GEMM_Limitations Limitations\nUnfortunately, this simplification mechanism is not perfect yet and not all expressions which could be\nhandled by a single GEMM-like call are correctly detected.\n<table class=\"manual\" style=\"width:100%\">\n<tr>\n<th>Not optimal expression</th>\n<th>Evaluated as</th>\n<th>Optimal version (single evaluation)</th>\n<th>Comments</th>\n</tr>\n<tr>\n<td>\\code\nm1 += m2 * m3; \\endcode</td>\n<td>\\code\ntemp = m2 * m3;\nm1 += temp; \\endcode</td>\n<td>\\code\nm1.noalias() += m2 * m3; \\endcode</td>\n<td>Use .noalias() to tell Eigen the result and right-hand-sides do not alias. \n    Otherwise the product m2 * m3 is evaluated into a temporary.</td>\n</tr>\n<tr class=\"alt\">\n<td></td>\n<td></td>\n<td>\\code\nm1.noalias() += s1 * (m2 * m3); \\endcode</td>\n<td>This is a special feature of Eigen. Here the product between a scalar\n    and a matrix product does not evaluate the matrix product but instead it\n    returns a matrix product expression tracking the scalar scaling factor. <br>\n    Without this optimization, the matrix product would be evaluated into a\n    temporary as in the next example.</td>\n</tr>\n<tr>\n<td>\\code\nm1.noalias() += (m2 * m3).adjoint(); \\endcode</td>\n<td>\\code\ntemp = m2 * m3;\nm1 += temp.adjoint(); \\endcode</td>\n<td>\\code\nm1.noalias() += m3.adjoint()\n*              * m2.adjoint(); \\endcode</td>\n<td>This is because the product expression has the EvalBeforeNesting bit which\n    enforces the evaluation of the product by the Tranpose expression.</td>\n</tr>\n<tr class=\"alt\">\n<td>\\code\nm1 = m1 + m2 * m3; \\endcode</td>\n<td>\\code\ntemp = m2 * m3;\nm1 = m1 + temp; \\endcode</td>\n<td>\\code m1.noalias() += m2 * m3; \\endcode</td>\n<td>Here there is no way to detect at compile time that the two m1 are the same,\n    and so the matrix product will be immediately evaluated.</td>\n</tr>\n<tr>\n<td>\\code\nm1.noalias() = m4 + m2 * m3; \\endcode</td>\n<td>\\code\ntemp = m2 * m3;\nm1 = m4 + temp; \\endcode</td>\n<td>\\code\nm1 = m4;\nm1.noalias() += m2 * m3; \\endcode</td>\n<td>First of all, here the .noalias() in the first expression is useless because\n    m2*m3 will be evaluated anyway. However, note how this expression can be rewritten\n    so that no temporary is required. (tip: for very small fixed size matrix\n    it is slightly better to rewrite it like this: m1.noalias() = m2 * m3; m1 += m4;</td>\n</tr>\n<tr class=\"alt\">\n<td>\\code\nm1.noalias() += (s1*m2).block(..) * m3; \\endcode</td>\n<td>\\code\ntemp = (s1*m2).block(..);\nm1 += temp * m3; \\endcode</td>\n<td>\\code\nm1.noalias() += s1 * m2.block(..) * m3; \\endcode</td>\n<td>This is because our expression analyzer is currently not able to extract trivial\n    expressions nested in a Block expression. Therefore the nested scalar\n    multiple cannot be properly extracted.</td>\n</tr>\n</table>\n\nOf course all these remarks hold for all other kind of products involving triangular or selfadjoint matrices.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/InplaceDecomposition.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage InplaceDecomposition Inplace matrix decompositions\n\nStarting from %Eigen 3.3, the LU, Cholesky, and QR decompositions can operate \\em inplace, that is, directly within the given input matrix.\nThis feature is especially useful when dealing with huge matrices, and or when the available memory is very limited (embedded systems).\n\nTo this end, the respective decomposition class must be instantiated with a Ref<> matrix type, and the decomposition object must be constructed with the input matrix as argument. As an example, let us consider an inplace LU decomposition with partial pivoting.\n\nLet's start with the basic inclusions, and declaration of a 2x2 matrix \\c A:\n\n<table class=\"example\">\n<tr><th>code</th><th>output</th></tr>\n<tr>\n  <td>\\snippet TutorialInplaceLU.cpp init\n  </td>\n  <td>\\snippet TutorialInplaceLU.out init\n  </td>\n</tr>\n</table>\n\nNo surprise here! Then, let's declare our inplace LU object \\c lu, and check the content of the matrix \\c A:\n\n<table class=\"example\">\n<tr>\n  <td>\\snippet TutorialInplaceLU.cpp declaration\n  </td>\n  <td>\\snippet TutorialInplaceLU.out declaration\n  </td>\n</tr>\n</table>\n\nHere, the \\c lu object computes and stores the \\c L and \\c U factors within the memory held by the matrix \\c A.\nThe coefficients of \\c A have thus been destroyed during the factorization, and replaced by the L and U factors as one can verify:\n\n<table class=\"example\">\n<tr>\n  <td>\\snippet TutorialInplaceLU.cpp matrixLU\n  </td>\n  <td>\\snippet TutorialInplaceLU.out matrixLU\n  </td>\n</tr>\n</table>\n\nThen, one can use the \\c lu object as usual, for instance to solve the Ax=b problem:\n<table class=\"example\">\n<tr>\n  <td>\\snippet TutorialInplaceLU.cpp solve\n  </td>\n  <td>\\snippet TutorialInplaceLU.out solve\n  </td>\n</tr>\n</table>\n\nHere, since the content of the original matrix \\c A has been lost, we had to declared a new matrix \\c A0 to verify the result.\n\nSince the memory is shared between \\c A and \\c lu, modifying the matrix \\c A will make \\c lu invalid.\nThis can easily be verified by modifying the content of \\c A and trying to solve the initial problem again:\n\n<table class=\"example\">\n<tr>\n  <td>\\snippet TutorialInplaceLU.cpp modifyA\n  </td>\n  <td>\\snippet TutorialInplaceLU.out modifyA\n  </td>\n</tr>\n</table>\n\nNote that there is no shared pointer under the hood, it is the \\b responsibility \\b of \\b the \\b user to keep the input matrix \\c A in life as long as \\c lu is living.\n\nIf one wants to update the factorization with the modified A, one has to call the compute method as usual:\n<table class=\"example\">\n<tr>\n  <td>\\snippet TutorialInplaceLU.cpp recompute\n  </td>\n  <td>\\snippet TutorialInplaceLU.out recompute\n  </td>\n</tr>\n</table>\n\nNote that calling compute does not change the memory which is referenced by the \\c lu object. Therefore, if the compute method is called with another matrix \\c A1 different than \\c A, then the content of \\c A1 won't be modified. This is still the content of \\c A that will be used to store the L and U factors of the matrix \\c A1.\nThis can easily be verified as follows:\n<table class=\"example\">\n<tr>\n  <td>\\snippet TutorialInplaceLU.cpp recompute_bis0\n </td>\n  <td>\\snippet TutorialInplaceLU.out recompute_bis0\n </td>\n</tr>\n</table>\nThe matrix \\c A1 is unchanged, and one can thus solve A1*x=b, and directly check the residual without any copy of \\c A1:\n<table class=\"example\">\n<tr>\n  <td>\\snippet TutorialInplaceLU.cpp recompute_bis1\n  </td>\n  <td>\\snippet TutorialInplaceLU.out recompute_bis1\n </td>\n</tr>\n</table>\n\n\nHere is the list of matrix decompositions supporting this inplace mechanism:\n\n- class LLT\n- class LDLT\n- class PartialPivLU\n- class FullPivLU\n- class HouseholderQR\n- class ColPivHouseholderQR\n- class FullPivHouseholderQR\n- class CompleteOrthogonalDecomposition\n\n*/\n\n}"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/InsideEigenExample.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicInsideEigenExample What happens inside Eigen, on a simple example\n\n\\eigenAutoToc\n\n<hr>\n\n\nConsider the following example program:\n\n\\code\n#include<Eigen/Core>\n\nint main()\n{\n  int size = 50;\n  // VectorXf is a vector of floats, with dynamic size.\n  Eigen::VectorXf u(size), v(size), w(size);\n  u = v + w;\n}\n\\endcode\n\nThe goal of this page is to understand how Eigen compiles it, assuming that SSE2 vectorization is enabled (GCC option -msse2).\n\n\\section WhyInteresting Why it's interesting\n\nMaybe you think, that the above example program is so simple, that compiling it shouldn't involve anything interesting. So before starting, let us explain what is nontrivial in compiling it correctly -- that is, producing optimized code -- so that the complexity of Eigen, that we'll explain here, is really useful.\n\nLook at the line of code\n\\code\n  u = v + w;   //   (*)\n\\endcode\n\nThe first important thing about compiling it, is that the arrays should be traversed only once, like\n\\code\n  for(int i = 0; i < size; i++) u[i] = v[i] + w[i];\n\\endcode\nThe problem is that if we make a naive C++ library where the VectorXf class has an operator+ returning a VectorXf, then the line of code (*) will amount to:\n\\code\n  VectorXf tmp = v + w;\n  VectorXf u = tmp;\n\\endcode\nObviously, the introduction of the temporary \\a tmp here is useless. It has a very bad effect on performance, first because the creation of \\a tmp requires a dynamic memory allocation in this context, and second as there are now two for loops:\n\\code\n  for(int i = 0; i < size; i++) tmp[i] = v[i] + w[i];\n  for(int i = 0; i < size; i++) u[i] = tmp[i];\n\\endcode\nTraversing the arrays twice instead of once is terrible for performance, as it means that we do many redundant memory accesses.\n\nThe second important thing about compiling the above program, is to make correct use of SSE2 instructions. Notice that Eigen also supports AltiVec and that all the discussion that we make here applies also to AltiVec.\n\nSSE2, like AltiVec, is a set of instructions allowing to perform computations on packets of 128 bits at once. Since a float is 32 bits, this means that SSE2 instructions can handle 4 floats at once. This means that, if correctly used, they can make our computation go up to 4x faster.\n\nHowever, in the above program, we have chosen size=50, so our vectors consist of 50 float's, and 50 is not a multiple of 4. This means that we cannot hope to do all of that computation using SSE2 instructions. The second best thing, to which we should aim, is to handle the 48 first coefficients with SSE2 instructions, since 48 is the biggest multiple of 4 below 50, and then handle separately, without SSE2, the 49th and 50th coefficients. Something like this:\n\n\\code\n  for(int i = 0; i < 4*(size/4); i+=4) u.packet(i)  = v.packet(i) + w.packet(i);\n  for(int i = 4*(size/4); i < size; i++) u[i] = v[i] + w[i];\n\\endcode\n\nSo let us look line by line at our example program, and let's follow Eigen as it compiles it.\n\n\\section ConstructingVectors Constructing vectors\n\nLet's analyze the first line:\n\n\\code\n  Eigen::VectorXf u(size), v(size), w(size);\n\\endcode\n\nFirst of all, VectorXf is the following typedef:\n\\code\n  typedef Matrix<float, Dynamic, 1> VectorXf;\n\\endcode\n\nThe class template Matrix is declared in src/Core/util/ForwardDeclarations.h with 6 template parameters, but the last 3 are automatically determined by the first 3. So you don't need to worry about them for now. Here, Matrix\\<float, Dynamic, 1\\> means a matrix of floats, with a dynamic number of rows and 1 column.\n\nThe Matrix class inherits a base class, MatrixBase. Don't worry about it, for now it suffices to say that MatrixBase is what unifies matrices/vectors and all the expressions types -- more on that below.\n\nWhen we do\n\\code\n  Eigen::VectorXf u(size);\n\\endcode\nthe constructor that is called is Matrix::Matrix(int), in src/Core/Matrix.h. Besides some assertions, all it does is to construct the \\a m_storage member, which is of type DenseStorage\\<float, Dynamic, Dynamic, 1\\>.\n\nYou may wonder, isn't it overengineering to have the storage in a separate class? The reason is that the Matrix class template covers all kinds of matrices and vector: both fixed-size and dynamic-size. The storage method is not the same in these two cases. For fixed-size, the matrix coefficients are stored as a plain member array. For dynamic-size, the coefficients will be stored as a pointer to a dynamically-allocated array. Because of this, we need to abstract storage away from the Matrix class. That's DenseStorage.\n\nLet's look at this constructor, in src/Core/DenseStorage.h. You can see that there are many partial template specializations of DenseStorages here, treating separately the cases where dimensions are Dynamic or fixed at compile-time. The partial specialization that we are looking at is:\n\\code\ntemplate<typename T, int Cols_> class DenseStorage<T, Dynamic, Dynamic, Cols_>\n\\endcode\n\nHere, the constructor called is DenseStorage::DenseStorage(int size, int rows, int columns)\nwith size=50, rows=50, columns=1.\n\nHere is this constructor:\n\\code\ninline DenseStorage(int size, int rows, int) : m_data(internal::aligned_new<T>(size)), m_rows(rows) {}\n\\endcode\n\nHere, the \\a m_data member is the actual array of coefficients of the matrix. As you see, it is dynamically allocated. Rather than calling new[] or malloc(), as you can see, we have our own internal::aligned_new defined in src/Core/util/Memory.h. What it does is that if vectorization is enabled, then it uses a platform-specific call to allocate a 128-bit-aligned array, as that is very useful for vectorization with both SSE2 and AltiVec. If vectorization is disabled, it amounts to the standard new[].\n\nAs you can see, the constructor also sets the \\a m_rows member to \\a size. Notice that there is no \\a m_columns member: indeed, in this partial specialization of DenseStorage, we know the number of columns at compile-time, since the Cols_ template parameter is different from Dynamic. Namely, in our case, Cols_ is 1, which is to say that our vector is just a matrix with 1 column. Hence, there is no need to store the number of columns as a runtime variable.\n\nWhen you call VectorXf::data() to get the pointer to the array of coefficients, it returns DenseStorage::data() which returns the \\a m_data member.\n\nWhen you call VectorXf::size() to get the size of the vector, this is actually a method in the base class MatrixBase. It determines that the vector is a column-vector, since ColsAtCompileTime==1 (this comes from the template parameters in the typedef VectorXf). It deduces that the size is the number of rows, so it returns VectorXf::rows(), which returns DenseStorage::rows(), which returns the \\a m_rows member, which was set to \\a size by the constructor.\n\n\\section ConstructionOfSumXpr Construction of the sum expression\n\nNow that our vectors are constructed, let's move on to the next line:\n\n\\code\nu = v + w;\n\\endcode\n\nThe executive summary is that operator+ returns a \"sum of vectors\" expression, but doesn't actually perform the computation. It is the operator=, whose call occurs thereafter, that does the computation.\n\nLet us now see what Eigen does when it sees this:\n\n\\code\nv + w\n\\endcode\n\nHere, v and w are of type VectorXf, which is a typedef for a specialization of Matrix (as we explained above), which is a subclass of MatrixBase. So what is being called is\n\n\\code\nMatrixBase::operator+(const MatrixBase&)\n\\endcode\n\nThe return type of this operator is\n\\code\nCwiseBinaryOp<internal::scalar_sum_op<float>, VectorXf, VectorXf>\n\\endcode\nThe CwiseBinaryOp class is our first encounter with an expression template. As we said, the operator+ doesn't by itself perform any computation, it just returns an abstract \"sum of vectors\" expression. Since there are also \"difference of vectors\" and \"coefficient-wise product of vectors\" expressions, we unify them all as \"coefficient-wise binary operations\", which we abbreviate as \"CwiseBinaryOp\". \"Coefficient-wise\" means that the operations is performed coefficient by coefficient. \"binary\" means that there are two operands -- we are adding two vectors with one another.\n\nNow you might ask, what if we did something like\n\n\\code\nv + w + u;\n\\endcode\n\nThe first v + w would return a CwiseBinaryOp as above, so in order for this to compile, we'd need to define an operator+ also in the class CwiseBinaryOp... at this point it starts looking like a nightmare: are we going to have to define all operators in each of the expression classes (as you guessed, CwiseBinaryOp is only one of many) ? This looks like a dead end!\n\nThe solution is that CwiseBinaryOp itself, as well as Matrix and all the other expression types, is a subclass of MatrixBase. So it is enough to define once and for all the operators in class MatrixBase.\n\nSince MatrixBase is the common base class of different subclasses, the aspects that depend on the subclass must be abstracted from MatrixBase. This is called polymorphism.\n\nThe classical approach to polymorphism in C++ is by means of virtual functions. This is dynamic polymorphism. Here we don't want dynamic polymorphism because the whole design of Eigen is based around the assumption that all the complexity, all the abstraction, gets resolved at compile-time. This is crucial: if the abstraction can't get resolved at compile-time, Eigen's compile-time optimization mechanisms become useless, not to mention that if that abstraction has to be resolved at runtime it'll incur an overhead by itself.\n\nHere, what we want is to have a single class MatrixBase as the base of many subclasses, in such a way that each MatrixBase object (be it a matrix, or vector, or any kind of expression) knows at compile-time (as opposed to run-time) of which particular subclass it is an object (i.e. whether it is a matrix, or an expression, and what kind of expression).\n\nThe solution is the <a href=\"http://en.wikipedia.org/wiki/Curiously_Recurring_Template_Pattern\">Curiously Recurring Template Pattern</a>. Let's do the break now. Hopefully you can read this wikipedia page during the break if needed, but it won't be allowed during the exam.\n\nIn short, MatrixBase takes a template parameter \\a Derived. Whenever we define a subclass Subclass, we actually make Subclass inherit MatrixBase\\<Subclass\\>. The point is that different subclasses inherit different MatrixBase types. Thanks to this, whenever we have an object of a subclass, and we call on it some MatrixBase method, we still remember even from inside the MatrixBase method which particular subclass we're talking about.\n\nThis means that we can put almost all the methods and operators in the base class MatrixBase, and have only the bare minimum in the subclasses. If you look at the subclasses in Eigen, like for instance the CwiseBinaryOp class, they have very few methods. There are coeff() and sometimes coeffRef() methods for access to the coefficients, there are rows() and cols() methods returning the number of rows and columns, but there isn't much more than that. All the meat is in MatrixBase, so it only needs to be coded once for all kinds of expressions, matrices, and vectors.\n\nSo let's end this digression and come back to the piece of code from our example program that we were currently analyzing,\n\n\\code\nv + w\n\\endcode\n\nNow that MatrixBase is a good friend, let's write fully the prototype of the operator+ that gets called here (this code is from src/Core/MatrixBase.h):\n\n\\code\ntemplate<typename Derived>\nclass MatrixBase\n{\n  // ...\n\n  template<typename OtherDerived>\n  const CwiseBinaryOp<internal::scalar_sum_op<typename internal::traits<Derived>::Scalar>, Derived, OtherDerived>\n  operator+(const MatrixBase<OtherDerived> &other) const;\n\n  // ...\n};\n\\endcode\n\nHere of course, \\a Derived and \\a OtherDerived are VectorXf.\n\nAs we said, CwiseBinaryOp is also used for other operations such as substration, so it takes another template parameter determining the operation that will be applied to coefficients. This template parameter is a functor, that is, a class in which we have an operator() so it behaves like a function. Here, the functor used is internal::scalar_sum_op. It is defined in src/Core/Functors.h.\n\nLet us now explain the internal::traits here. The internal::scalar_sum_op class takes one template parameter: the type of the numbers to handle. Here of course we want to pass the scalar type (a.k.a. numeric type) of VectorXf, which is \\c float. How do we determine which is the scalar type of \\a Derived ? Throughout Eigen, all matrix and expression types define a typedef \\a Scalar which gives its scalar type. For example, VectorXf::Scalar is a typedef for \\c float. So here, if life was easy, we could find the numeric type of \\a Derived as just\n\\code\ntypename Derived::Scalar\n\\endcode\nUnfortunately, we can't do that here, as the compiler would complain that the type Derived hasn't yet been defined. So we use a workaround: in src/Core/util/ForwardDeclarations.h, we declared (not defined!) all our subclasses, like Matrix, and we also declared the following class template:\n\\code\ntemplate<typename T> struct internal::traits;\n\\endcode\nIn src/Core/Matrix.h, right \\em before the definition of class Matrix, we define a partial specialization of internal::traits for T=Matrix\\<any template parameters\\>. In this specialization of internal::traits, we define the Scalar typedef. So when we actually define Matrix, it is legal to refer to \"typename internal::traits\\<Matrix\\>::Scalar\".\n\nAnyway, we have declared our operator+. In our case, where \\a Derived and \\a OtherDerived are VectorXf, the above declaration amounts to:\n\\code\nclass MatrixBase<VectorXf>\n{\n  // ...\n\n  const CwiseBinaryOp<internal::scalar_sum_op<float>, VectorXf, VectorXf>\n  operator+(const MatrixBase<VectorXf> &other) const;\n\n  // ...\n};\n\\endcode\n\nLet's now jump to src/Core/CwiseBinaryOp.h to see how it is defined. As you can see there, all it does is to return a CwiseBinaryOp object, and this object is just storing references to the left-hand-side and right-hand-side expressions -- here, these are the vectors \\a v and \\a w. Well, the CwiseBinaryOp object is also storing an instance of the (empty) functor class, but you shouldn't worry about it as that is a minor implementation detail.\n\nThus, the operator+ hasn't performed any actual computation. To summarize, the operation \\a v + \\a w just returned an object of type CwiseBinaryOp which did nothing else than just storing references to \\a v and \\a w.\n\n\\section Assignment The assignment\n\n<div class=\"warningbox\">\n<strong>PLEASE HELP US IMPROVING THIS SECTION.</strong>\nThis page reflects how %Eigen worked until 3.2, but since %Eigen 3.3 the assignment is more sophisticated as it involves an Assignment expression, and the creation of so called evaluator which are responsible for the evaluation of each kind of expressions.\n</div>\n\nAt this point, the expression \\a v + \\a w has finished evaluating, so, in the process of compiling the line of code\n\\code\nu = v + w;\n\\endcode\nwe now enter the operator=.\n\nWhat operator= is being called here? The vector u is an object of class VectorXf, i.e. Matrix. In src/Core/Matrix.h, inside the definition of class Matrix, we see this:\n\\code\n    template<typename OtherDerived>\n    inline Matrix& operator=(const MatrixBase<OtherDerived>& other)\n    {\n      eigen_assert(m_storage.data()!=0 && \"you cannot use operator= with a non initialized matrix (instead use set()\");\n      return Base::operator=(other.derived());\n    }\n\\endcode\nHere, Base is a typedef for MatrixBase\\<Matrix\\>. So, what is being called is the operator= of MatrixBase. Let's see its prototype in src/Core/MatrixBase.h:\n\\code\n    template<typename OtherDerived>\n    Derived& operator=(const MatrixBase<OtherDerived>& other);\n\\endcode\nHere, \\a Derived is VectorXf (since u is a VectorXf) and \\a OtherDerived is CwiseBinaryOp. More specifically, as explained in the previous section, \\a OtherDerived is:\n\\code\nCwiseBinaryOp<internal::scalar_sum_op<float>, VectorXf, VectorXf>\n\\endcode\nSo the full prototype of the operator= being called is:\n\\code\nVectorXf& MatrixBase<VectorXf>::operator=(const MatrixBase<CwiseBinaryOp<internal::scalar_sum_op<float>, VectorXf, VectorXf> > & other);\n\\endcode\nThis operator= literally reads \"copying a sum of two VectorXf's into another VectorXf\".\n\nLet's now look at the implementation of this operator=. It resides in the file src/Core/Assign.h.\n\nWhat we can see there is:\n\\code\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\ninline Derived& MatrixBase<Derived>\n  ::operator=(const MatrixBase<OtherDerived>& other)\n{\n  return internal::assign_selector<Derived,OtherDerived>::run(derived(), other.derived());\n}\n\\endcode\n\nOK so our next task is to understand internal::assign_selector :)\n\nHere is its declaration (all that is still in the same file src/Core/Assign.h)\n\\code\ntemplate<typename Derived, typename OtherDerived,\n         bool EvalBeforeAssigning = int(OtherDerived::Flags) & EvalBeforeAssigningBit,\n         bool NeedToTranspose = Derived::IsVectorAtCompileTime\n                && OtherDerived::IsVectorAtCompileTime\n                && int(Derived::RowsAtCompileTime) == int(OtherDerived::ColsAtCompileTime)\n                && int(Derived::ColsAtCompileTime) == int(OtherDerived::RowsAtCompileTime)\n                && int(Derived::SizeAtCompileTime) != 1>\nstruct internal::assign_selector;\n\\endcode\n\nSo internal::assign_selector takes 4 template parameters, but the 2 last ones are automatically determined by the 2 first ones.\n\nEvalBeforeAssigning is here to enforce the EvalBeforeAssigningBit. As explained <a href=\"TopicLazyEvaluation.html\">here</a>, certain expressions have this flag which makes them automatically evaluate into temporaries before assigning them to another expression. This is the case of the Product expression, in order to avoid strange aliasing effects when doing \"m = m * m;\" However, of course here our CwiseBinaryOp expression doesn't have the EvalBeforeAssigningBit: we said since the beginning that we didn't want a temporary to be introduced here. So if you go to src/Core/CwiseBinaryOp.h, you'll see that the Flags in internal::traits\\<CwiseBinaryOp\\> don't include the EvalBeforeAssigningBit. The Flags member of CwiseBinaryOp is then imported from the internal::traits by the EIGEN_GENERIC_PUBLIC_INTERFACE macro. Anyway, here the template parameter EvalBeforeAssigning has the value \\c false.\n\nNeedToTranspose is here for the case where the user wants to copy a row-vector into a column-vector. We allow this as a special exception to the general rule that in assignments we require the dimesions to match. Anyway, here both the left-hand and right-hand sides are column vectors, in the sense that ColsAtCompileTime is equal to 1. So NeedToTranspose is \\c false too.\n\nSo, here we are in the partial specialization:\n\\code\ninternal::assign_selector<Derived, OtherDerived, false, false>\n\\endcode\n\nHere's how it is defined:\n\\code\ntemplate<typename Derived, typename OtherDerived>\nstruct internal::assign_selector<Derived,OtherDerived,false,false> {\n  static Derived& run(Derived& dst, const OtherDerived& other) { return dst.lazyAssign(other.derived()); }\n};\n\\endcode\n\nOK so now our next job is to understand how lazyAssign works :)\n\n\\code\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\ninline Derived& MatrixBase<Derived>\n  ::lazyAssign(const MatrixBase<OtherDerived>& other)\n{\n  EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Derived,OtherDerived)\n  eigen_assert(rows() == other.rows() && cols() == other.cols());\n  internal::assign_impl<Derived, OtherDerived>::run(derived(),other.derived());\n  return derived();\n}\n\\endcode\n\nWhat do we see here? Some assertions, and then the only interesting line is:\n\\code\n  internal::assign_impl<Derived, OtherDerived>::run(derived(),other.derived());\n\\endcode\n\nOK so now we want to know what is inside internal::assign_impl.\n\nHere is its declaration:\n\\code\ntemplate<typename Derived1, typename Derived2,\n         int Vectorization = internal::assign_traits<Derived1, Derived2>::Vectorization,\n         int Unrolling = internal::assign_traits<Derived1, Derived2>::Unrolling>\nstruct internal::assign_impl;\n\\endcode\nAgain, internal::assign_selector takes 4 template parameters, but the 2 last ones are automatically determined by the 2 first ones.\n\nThese two parameters \\a Vectorization and \\a Unrolling are determined by a helper class internal::assign_traits. Its job is to determine which vectorization strategy to use (that is \\a Vectorization) and which unrolling strategy to use (that is \\a Unrolling).\n\nWe'll not enter into the details of how these strategies are chosen (this is in the implementation of internal::assign_traits at the top of the same file). Let's just say that here \\a Vectorization has the value \\a LinearVectorization, and \\a Unrolling has the value \\a NoUnrolling (the latter is obvious since our vectors have dynamic size so there's no way to unroll the loop at compile-time).\n\nSo the partial specialization of internal::assign_impl that we're looking at is:\n\\code\ninternal::assign_impl<Derived1, Derived2, LinearVectorization, NoUnrolling>\n\\endcode\n\nHere is how it's defined:\n\\code\ntemplate<typename Derived1, typename Derived2>\nstruct internal::assign_impl<Derived1, Derived2, LinearVectorization, NoUnrolling>\n{\n  static void run(Derived1 &dst, const Derived2 &src)\n  {\n    const int size = dst.size();\n    const int packetSize = internal::packet_traits<typename Derived1::Scalar>::size;\n    const int alignedStart = internal::assign_traits<Derived1,Derived2>::DstIsAligned ? 0\n                           : internal::first_aligned(&dst.coeffRef(0), size);\n    const int alignedEnd = alignedStart + ((size-alignedStart)/packetSize)*packetSize;\n\n    for(int index = 0; index < alignedStart; index++)\n      dst.copyCoeff(index, src);\n\n    for(int index = alignedStart; index < alignedEnd; index += packetSize)\n    {\n      dst.template copyPacket<Derived2, Aligned, internal::assign_traits<Derived1,Derived2>::SrcAlignment>(index, src);\n    }\n\n    for(int index = alignedEnd; index < size; index++)\n      dst.copyCoeff(index, src);\n  }\n};\n\\endcode\n\nHere's how it works. \\a LinearVectorization means that the left-hand and right-hand side expression can be accessed linearly i.e. you can refer to their coefficients by one integer \\a index, as opposed to having to refer to its coefficients by two integers \\a row, \\a column.\n\nAs we said at the beginning, vectorization works with blocks of 4 floats. Here, \\a PacketSize is 4.\n\nThere are two potential problems that we need to deal with:\n\\li first, vectorization works much better if the packets are 128-bit-aligned. This is especially important for write access. So when writing to the coefficients of \\a dst, we want to group these coefficients by packets of 4 such that each of these packets is 128-bit-aligned. In general, this requires to skip a few coefficients at the beginning of \\a dst. This is the purpose of \\a alignedStart. We then copy these first few coefficients one by one, not by packets. However, in our case, the \\a dst expression is a VectorXf and remember that in the construction of the vectors we allocated aligned arrays. Thanks to \\a DstIsAligned, Eigen remembers that without having to do any runtime check, so \\a alignedStart is zero and this part is avoided altogether.\n\\li second, the number of coefficients to copy is not in general a multiple of \\a packetSize. Here, there are 50 coefficients to copy and \\a packetSize is 4. So we'll have to copy the last 2 coefficients one by one, not by packets. Here, \\a alignedEnd is 48.\n\nNow come the actual loops.\n\nFirst, the vectorized part: the 48 first coefficients out of 50 will be copied by packets of 4:\n\\code\n  for(int index = alignedStart; index < alignedEnd; index += packetSize)\n  {\n    dst.template copyPacket<Derived2, Aligned, internal::assign_traits<Derived1,Derived2>::SrcAlignment>(index, src);\n  }\n\\endcode\n\nWhat is copyPacket? It is defined in src/Core/Coeffs.h:\n\\code\ntemplate<typename Derived>\ntemplate<typename OtherDerived, int StoreMode, int LoadMode>\ninline void MatrixBase<Derived>::copyPacket(int index, const MatrixBase<OtherDerived>& other)\n{\n  eigen_internal_assert(index >= 0 && index < size());\n  derived().template writePacket<StoreMode>(index,\n    other.derived().template packet<LoadMode>(index));\n}\n\\endcode\n\nOK, what are writePacket() and packet() here?\n\nFirst, writePacket() here is a method on the left-hand side VectorXf. So we go to src/Core/Matrix.h to look at its definition:\n\\code\ntemplate<int StoreMode>\ninline void writePacket(int index, const PacketScalar& x)\n{\n  internal::pstoret<Scalar, PacketScalar, StoreMode>(m_storage.data() + index, x);\n}\n\\endcode\nHere, \\a StoreMode is \\a #Aligned, indicating that we are doing a 128-bit-aligned write access, \\a PacketScalar is a type representing a \"SSE packet of 4 floats\" and internal::pstoret is a function writing such a packet in memory. Their definitions are architecture-specific, we find them in src/Core/arch/SSE/PacketMath.h:\n\nThe line in src/Core/arch/SSE/PacketMath.h that determines the PacketScalar type (via a typedef in Matrix.h) is:\n\\code\ntemplate<> struct internal::packet_traits<float>  { typedef __m128  type; enum {size=4}; };\n\\endcode\nHere, __m128 is a SSE-specific type. Notice that the enum \\a size here is what was used to define \\a packetSize above.\n\nAnd here is the implementation of internal::pstoret:\n\\code\ntemplate<> inline void internal::pstore(float*  to, const __m128&  from) { _mm_store_ps(to, from); }\n\\endcode\nHere, __mm_store_ps is a SSE-specific intrinsic function, representing a single SSE instruction. The difference between internal::pstore and internal::pstoret is that internal::pstoret is a dispatcher handling both the aligned and unaligned cases, you find its definition in src/Core/GenericPacketMath.h:\n\\code\ntemplate<typename Scalar, typename Packet, int LoadMode>\ninline void internal::pstoret(Scalar* to, const Packet& from)\n{\n  if(LoadMode == Aligned)\n    internal::pstore(to, from);\n  else\n    internal::pstoreu(to, from);\n}\n\\endcode\n\nOK, that explains how writePacket() works. Now let's look into the packet() call. Remember that we are analyzing this line of code inside copyPacket():\n\\code\nderived().template writePacket<StoreMode>(index,\n    other.derived().template packet<LoadMode>(index));\n\\endcode\n\nHere, \\a other is our sum expression \\a v + \\a w. The .derived() is just casting from MatrixBase to the subclass which here is CwiseBinaryOp. So let's go to src/Core/CwiseBinaryOp.h:\n\\code\nclass CwiseBinaryOp\n{\n  // ...\n    template<int LoadMode>\n    inline PacketScalar packet(int index) const\n    {\n      return m_functor.packetOp(m_lhs.template packet<LoadMode>(index), m_rhs.template packet<LoadMode>(index));\n    }\n};\n\\endcode\nHere, \\a m_lhs is the vector \\a v, and \\a m_rhs is the vector \\a w. So the packet() function here is Matrix::packet(). The template parameter \\a LoadMode is \\a #Aligned. So we're looking at\n\\code\nclass Matrix\n{\n  // ...\n    template<int LoadMode>\n    inline PacketScalar packet(int index) const\n    {\n      return internal::ploadt<Scalar, LoadMode>(m_storage.data() + index);\n    }\n};\n\\endcode\nWe let you look up the definition of internal::ploadt in GenericPacketMath.h and the internal::pload in src/Core/arch/SSE/PacketMath.h. It is very similar to the above for internal::pstore.\n\nLet's go back to CwiseBinaryOp::packet(). Once the packets from the vectors \\a v and \\a w have been returned, what does this function do? It calls m_functor.packetOp() on them. What is m_functor? Here we must remember what particular template specialization of CwiseBinaryOp we're dealing with:\n\\code\nCwiseBinaryOp<internal::scalar_sum_op<float>, VectorXf, VectorXf>\n\\endcode\nSo m_functor is an object of the empty class internal::scalar_sum_op<float>. As we mentioned above, don't worry about why we constructed an object of this empty class at all -- it's an implementation detail, the point is that some other functors need to store member data.\n\nAnyway, internal::scalar_sum_op is defined in src/Core/Functors.h:\n\\code\ntemplate<typename Scalar> struct internal::scalar_sum_op EIGEN_EMPTY_STRUCT {\n  inline const Scalar operator() (const Scalar& a, const Scalar& b) const { return a + b; }\n  template<typename PacketScalar>\n  inline const PacketScalar packetOp(const PacketScalar& a, const PacketScalar& b) const\n  { return internal::padd(a,b); }\n};\n\\endcode\nAs you can see, all what packetOp() does is to call internal::padd on the two packets. Here is the definition of internal::padd from src/Core/arch/SSE/PacketMath.h:\n\\code\ntemplate<> inline __m128  internal::padd(const __m128&  a, const __m128&  b) { return _mm_add_ps(a,b); }\n\\endcode\nHere, _mm_add_ps is a SSE-specific intrinsic function, representing a single SSE instruction.\n\nTo summarize, the loop\n\\code\n  for(int index = alignedStart; index < alignedEnd; index += packetSize)\n  {\n    dst.template copyPacket<Derived2, Aligned, internal::assign_traits<Derived1,Derived2>::SrcAlignment>(index, src);\n  }\n\\endcode\nhas been compiled to the following code: for \\a index going from 0 to the 11 ( = 48/4 - 1), read the i-th packet (of 4 floats) from the vector v and the i-th packet from the vector w using two __mm_load_ps SSE instructions, then add them together using a __mm_add_ps instruction, then store the result using a __mm_store_ps instruction.\n\nThere remains the second loop handling the last few (here, the last 2) coefficients:\n\\code\n  for(int index = alignedEnd; index < size; index++)\n    dst.copyCoeff(index, src);\n\\endcode\nHowever, it works just like the one we just explained, it is just simpler because there is no SSE vectorization involved here. copyPacket() becomes copyCoeff(), packet() becomes coeff(), writePacket() becomes coeffRef(). If you followed us this far, you can probably understand this part by yourself.\n\nWe see that all the C++ abstraction of Eigen goes away during compilation and that we indeed are precisely controlling which assembly instructions we emit. Such is the beauty of C++! Since we have such precise control over the emitted assembly instructions, but such complex logic to choose the right instructions, we can say that Eigen really behaves like an optimizing compiler. If you prefer, you could say that Eigen behaves like a script for the compiler. In a sense, C++ template metaprogramming is scripting the compiler -- and it's been shown that this scripting language is Turing-complete. See <a href=\"http://en.wikipedia.org/wiki/Template_metaprogramming\"> Wikipedia</a>.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/LeastSquares.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage LeastSquares Solving linear least squares systems\n\nThis page describes how to solve linear least squares systems using %Eigen. An overdetermined system\nof equations, say \\a Ax = \\a b, has no solutions. In this case, it makes sense to search for the\nvector \\a x which is closest to being a solution, in the sense that the difference \\a Ax - \\a b is\nas small as possible. This \\a x is called the least square solution (if the Euclidean norm is used).\n\nThe three methods discussed on this page are the SVD decomposition, the QR decomposition and normal\nequations. Of these, the SVD decomposition is generally the most accurate but the slowest, normal\nequations is the fastest but least accurate, and the QR decomposition is in between.\n\n\\eigenAutoToc\n\n\n\\section LeastSquaresSVD Using the SVD decomposition\n\nThe \\link BDCSVD::solve() solve() \\endlink method in the BDCSVD class can be directly used to\nsolve linear squares systems. It is not enough to compute only the singular values (the default for\nthis class); you also need the singular vectors but the thin SVD decomposition suffices for\ncomputing least squares solutions:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include TutorialLinAlgSVDSolve.cpp </td>\n  <td>\\verbinclude TutorialLinAlgSVDSolve.out </td>\n</tr>\n</table>\n\nThis is example from the page \\link TutorialLinearAlgebra Linear algebra and decompositions \\endlink.\nIf you just need to solve the least squares problem, but are not interested in the SVD per se, a\nfaster alternative method is CompleteOrthogonalDecomposition. \n\n\n\\section LeastSquaresQR Using the QR decomposition\n\nThe solve() method in QR decomposition classes also computes the least squares solution. There are\nthree QR decomposition classes: HouseholderQR (no pivoting, fast but unstable if your matrix is\nnot rull rank), ColPivHouseholderQR (column pivoting, thus a bit slower but more stable) and\nFullPivHouseholderQR (full pivoting, so slowest and slightly more stable than ColPivHouseholderQR).\nHere is an example with column pivoting:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include LeastSquaresQR.cpp </td>\n  <td>\\verbinclude LeastSquaresQR.out </td>\n</tr>\n</table>\n\n\n\\section LeastSquaresNormalEquations Using normal equations\n\nFinding the least squares solution of \\a Ax = \\a b is equivalent to solving the normal equation\n<i>A</i><sup>T</sup><i>Ax</i> = <i>A</i><sup>T</sup><i>b</i>. This leads to the following code\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include LeastSquaresNormalEquations.cpp </td>\n  <td>\\verbinclude LeastSquaresNormalEquations.out </td>\n</tr>\n</table>\n\nThis method is usually the fastest, especially when \\a A is \"tall and skinny\". However, if the\nmatrix \\a A is even mildly ill-conditioned, this is not a good method, because the condition number\nof <i>A</i><sup>T</sup><i>A</i> is the square of the condition number of \\a A. This means that you\nlose roughly twice as many digits of accuracy using the normal equation, compared to the more stable\nmethods mentioned above.\n\n*/\n\n}"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/Manual.dox",
    "content": "\n// This file strutures pages and modules into a convenient hierarchical structure.\n\nnamespace Eigen {\n\n/** \\page UserManual_CustomizingEigen Extending/Customizing Eigen\n  %Eigen can be extended in several ways, for instance, by defining global methods, by inserting custom methods within main %Eigen's classes through the \\ref TopicCustomizing_Plugins \"plugin\" mechanism, by adding support to \\ref TopicCustomizing_CustomScalar \"custom scalar types\" etc. See below for the respective sub-topics.\n  - \\subpage TopicCustomizing_Plugins\n  - \\subpage TopicCustomizing_InheritingMatrix\n  - \\subpage TopicCustomizing_CustomScalar\n  - \\subpage TopicCustomizing_NullaryExpr\n  - \\subpage TopicNewExpressionType\n  \\sa \\ref TopicPreprocessorDirectives\n*/\n\n\n/** \\page UserManual_Generalities General topics\n  - \\subpage TopicFunctionTakingEigenTypes\n  - \\subpage TopicPreprocessorDirectives\n  - \\subpage TopicAssertions\n  - \\subpage TopicMultiThreading\n  - \\subpage TopicUsingBlasLapack\n  - \\subpage TopicUsingIntelMKL\n  - \\subpage TopicCUDA\n  - \\subpage TopicPitfalls\n  - \\subpage TopicTemplateKeyword\n  - \\subpage UserManual_UnderstandingEigen\n  - \\subpage TopicCMakeGuide\n*/\n\n/** \\page UserManual_UnderstandingEigen Understanding Eigen\n  - \\subpage TopicInsideEigenExample\n  - \\subpage TopicClassHierarchy\n  - \\subpage TopicLazyEvaluation\n*/\n\n/** \\page UnclassifiedPages Unclassified pages\n  - \\subpage TopicResizing\n  - \\subpage TopicVectorization\n  - \\subpage TopicEigenExpressionTemplates\n  - \\subpage TopicScalarTypes\n  - \\subpage GettingStarted\n  - \\subpage TutorialSparse_example_details\n  - \\subpage TopicWritingEfficientProductExpression\n  - \\subpage Experimental\n*/\n\n\n/** \\defgroup Support_modules Support modules\n  * Category of modules which add support for external libraries.\n  */\n\n\n/** \\defgroup DenseMatrixManipulation_chapter Dense matrix and array manipulation */\n/** \\defgroup DenseMatrixManipulation_Alignement Alignment issues */\n/** \\defgroup DenseMatrixManipulation_Reference Reference */\n\n/** \\addtogroup TutorialMatrixClass\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TutorialMatrixArithmetic\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TutorialArrayClass\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TutorialBlockOperations\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TutorialSlicingIndexing\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TutorialAdvancedInitialization\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TutorialReductionsVisitorsBroadcasting\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TutorialReshape\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TutorialSTL\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TutorialMapClass\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TopicAliasing\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TopicStorageOrders\n    \\ingroup DenseMatrixManipulation_chapter */\n\n/** \\addtogroup DenseMatrixManipulation_Alignement\n    \\ingroup DenseMatrixManipulation_chapter        */\n/**     \\addtogroup TopicUnalignedArrayAssert\n        \\ingroup DenseMatrixManipulation_Alignement */\n/**     \\addtogroup TopicFixedSizeVectorizable\n        \\ingroup DenseMatrixManipulation_Alignement */\n/**     \\addtogroup TopicStructHavingEigenMembers\n        \\ingroup DenseMatrixManipulation_Alignement */\n/**     \\addtogroup TopicStlContainers\n        \\ingroup DenseMatrixManipulation_Alignement */\n/**     \\addtogroup TopicPassingByValue\n        \\ingroup DenseMatrixManipulation_Alignement */\n/**     \\addtogroup TopicWrongStackAlignment\n        \\ingroup DenseMatrixManipulation_Alignement */\n    \n/** \\addtogroup DenseMatrixManipulation_Reference\n    \\ingroup DenseMatrixManipulation_chapter       */\n/**     \\addtogroup Core_Module\n        \\ingroup DenseMatrixManipulation_Reference */  \n/**     \\addtogroup Jacobi_Module\n        \\ingroup DenseMatrixManipulation_Reference */ \n/**     \\addtogroup Householder_Module\n        \\ingroup DenseMatrixManipulation_Reference */ \n\n/** \\addtogroup CoeffwiseMathFunctions\n    \\ingroup DenseMatrixManipulation_chapter */\n\n/** \\addtogroup QuickRefPage\n    \\ingroup DenseMatrixManipulation_chapter */\n\n\n/** \\defgroup DenseLinearSolvers_chapter Dense linear problems and decompositions */\n/** \\defgroup DenseLinearSolvers_Reference Reference */\n\n/** \\addtogroup TutorialLinearAlgebra\n    \\ingroup DenseLinearSolvers_chapter */\n/** \\addtogroup TopicLinearAlgebraDecompositions\n    \\ingroup DenseLinearSolvers_chapter */\n/** \\addtogroup LeastSquares \n    \\ingroup DenseLinearSolvers_chapter */\n/** \\addtogroup InplaceDecomposition\n    \\ingroup DenseLinearSolvers_chapter */\n/** \\addtogroup DenseDecompositionBenchmark\n    \\ingroup DenseLinearSolvers_chapter */\n\n/** \\addtogroup DenseLinearSolvers_Reference\n    \\ingroup DenseLinearSolvers_chapter */\n/** \\addtogroup Cholesky_Module\n    \\ingroup DenseLinearSolvers_Reference */\n/** \\addtogroup LU_Module\n    \\ingroup DenseLinearSolvers_Reference */\n/** \\addtogroup QR_Module\n    \\ingroup DenseLinearSolvers_Reference */\n/** \\addtogroup SVD_Module\n    \\ingroup DenseLinearSolvers_Reference*/\n/** \\addtogroup Eigenvalues_Module\n    \\ingroup DenseLinearSolvers_Reference */\n\n\n\n\n/** \\defgroup Sparse_chapter Sparse linear algebra */\n/** \\defgroup Sparse_Reference Reference */\n\n/** \\addtogroup TutorialSparse\n    \\ingroup Sparse_chapter */\n/** \\addtogroup TopicSparseSystems\n    \\ingroup Sparse_chapter */\n/** \\addtogroup MatrixfreeSolverExample\n    \\ingroup Sparse_chapter */\n\n/** \\addtogroup Sparse_Reference\n    \\ingroup Sparse_chapter */\n/** \\addtogroup SparseCore_Module\n    \\ingroup Sparse_Reference */\n/** \\addtogroup OrderingMethods_Module\n    \\ingroup Sparse_Reference */\n/** \\addtogroup SparseCholesky_Module\n    \\ingroup Sparse_Reference */\n/** \\addtogroup SparseLU_Module\n    \\ingroup Sparse_Reference */\n/** \\addtogroup SparseQR_Module\n    \\ingroup Sparse_Reference */\n/** \\addtogroup IterativeLinearSolvers_Module\n    \\ingroup Sparse_Reference */\n/** \\addtogroup Sparse_Module\n    \\ingroup Sparse_Reference */\n/** \\addtogroup Support_modules\n    \\ingroup Sparse_Reference */    \n\n/** \\addtogroup SparseQuickRefPage\n    \\ingroup Sparse_chapter */\n\n\n/** \\defgroup Geometry_chapter Geometry */\n/** \\defgroup Geometry_Reference Reference */\n\n/** \\addtogroup TutorialGeometry\n    \\ingroup Geometry_chapter */\n    \n/** \\addtogroup Geometry_Reference\n    \\ingroup Geometry_chapter */\n/** \\addtogroup Geometry_Module\n    \\ingroup Geometry_Reference */\n/** \\addtogroup Splines_Module\n    \\ingroup Geometry_Reference */\n\n/** \\internal \\brief Namespace containing low-level routines from the %Eigen library. */\nnamespace internal {}\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/MatrixfreeSolverExample.dox",
    "content": "\nnamespace Eigen {\n\n/**\n\n\\eigenManualPage MatrixfreeSolverExample Matrix-free solvers\n\nIterative solvers such as ConjugateGradient and BiCGSTAB can be used in a matrix free context. To this end, user must provide a wrapper class inheriting EigenBase<> and implementing the following methods:\n - \\c Index \\c rows() and \\c Index \\c cols(): returns number of rows and columns respectively\n - \\c operator* with your type and an %Eigen dense column vector (its actual implementation goes in a specialization of the internal::generic_product_impl class)\n\n\\c Eigen::internal::traits<> must also be specialized for the wrapper type.\n\nHere is a complete example wrapping an Eigen::SparseMatrix:\n\\include matrixfree_cg.cpp\nOutput: \\verbinclude matrixfree_cg.out\n\n*/\n\n}"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/NewExpressionType.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicNewExpressionType Adding a new expression type\n\n<!--<span style=\"font-size:130%; color:red; font-weight: 900;\"></span>-->\n\\warning\nDisclaimer: this page is tailored to very advanced users who are not afraid of dealing with some %Eigen's internal aspects.\nIn most cases, a custom expression can be avoided by either using custom \\ref MatrixBase::unaryExpr \"unary\" or \\ref MatrixBase::binaryExpr \"binary\" functors,\nwhile extremely complex matrix manipulations can be achieved by a nullary functors as described in the \\ref TopicCustomizing_NullaryExpr \"previous page\".\n\nThis page describes with the help of an example how to implement a new\nlight-weight expression type in %Eigen. This consists of three parts:\nthe expression type itself, a traits class containing compile-time\ninformation about the expression, and the evaluator class which is\nused to evaluate the expression to a matrix.\n\n\\b TO \\b DO: Write a page explaining the design, with details on\nvectorization etc., and refer to that page here.\n\n\n\\eigenAutoToc\n\n\\section TopicSetting The setting\n\nA circulant matrix is a matrix where each column is the same as the\ncolumn to the left, except that it is cyclically shifted downwards.\nFor example, here is a 4-by-4 circulant matrix:\n\\f[ \\begin{bmatrix} \n    1 & 8 & 4 & 2 \\\\ \n    2 & 1 & 8 & 4 \\\\\n    4 & 2 & 1 & 8 \\\\\n    8 & 4 & 2 & 1\n\\end{bmatrix} \\f]\nA circulant matrix is uniquely determined by its first column. We wish\nto write a function \\c makeCirculant which, given the first column,\nreturns an expression representing the circulant matrix.\n\nFor simplicity, we restrict the \\c makeCirculant function to dense\nmatrices. It may make sense to also allow arrays, or sparse matrices,\nbut we will not do so here. We also do not want to support\nvectorization.\n\n\n\\section TopicPreamble Getting started\n\nWe will present the file implementing the \\c makeCirculant function\npart by part. We start by including the appropriate header files and\nforward declaring the expression class, which we will call\n\\c Circulant. The \\c makeCirculant function will return an object of\nthis type. The class \\c Circulant is in fact a class template; the\ntemplate argument \\c ArgType refers to the type of the vector passed\nto the \\c makeCirculant function.\n\n\\include make_circulant.cpp.preamble\n\n\n\\section TopicTraits The traits class\n\nFor every expression class \\c X, there should be a traits class \n\\c Traits<X> in the \\c Eigen::internal namespace containing\ninformation about \\c X known as compile time.\n\nAs explained in \\ref TopicSetting, we designed the \\c Circulant\nexpression class to refer to dense matrices. The entries of the\ncirculant matrix have the same type as the entries of the vector\npassed to the \\c makeCirculant function. The type used to index the\nentries is also the same. Again for simplicity, we will only return\ncolumn-major matrices. Finally, the circulant matrix is a square\nmatrix (number of rows equals number of columns), and the number of\nrows equals the number of rows of the column vector passed to the\n\\c makeCirculant function. If this is a dynamic-size vector, then the\nsize of the circulant matrix is not known at compile-time.\n\nThis leads to the following code:\n\n\\include make_circulant.cpp.traits\n\n\n\\section TopicExpression The expression class\n\nThe next step is to define the expression class itself. In our case,\nwe want to inherit from \\c MatrixBase in order to expose the interface\nfor dense matrices. In the constructor, we check that we are passed a\ncolumn vector (see \\ref TopicAssertions) and we store the vector from\nwhich we are going to build the circulant matrix in the member\nvariable \\c m_arg. Finally, the expression class should compute the\nsize of the corresponding circulant matrix. As explained above, this\nis a square matrix with as many columns as the vector used to\nconstruct the matrix.\n\n\\b TO \\b DO: What about the \\c Nested typedef? It seems to be\nnecessary; is this only temporary?\n\n\\include make_circulant.cpp.expression\n\n\n\\section TopicEvaluator The evaluator\n\nThe last big fragment implements the evaluator for the \\c Circulant\nexpression. The evaluator computes the entries of the circulant\nmatrix; this is done in the \\c .coeff() member function. The entries\nare computed by finding the corresponding entry of the vector from\nwhich the circulant matrix is constructed. Getting this entry may\nactually be non-trivial when the circulant matrix is constructed from\na vector which is given by a complicated expression, so we use the\nevaluator which corresponds to the vector.\n\nThe \\c CoeffReadCost constant records the cost of computing an entry\nof the circulant matrix; we ignore the index computation and say that\nthis is the same as the cost of computing an entry of the vector from\nwhich the circulant matrix is constructed.\n\nIn the constructor, we save the evaluator for the column vector which\ndefined the circulant matrix. We also save the size of that vector;\nremember that we can query an expression object to find the size but\nnot the evaluator. \n\n\\include make_circulant.cpp.evaluator\n\n\n\\section TopicEntry The entry point\n\nAfter all this, the \\c makeCirculant function is very simple. It\nsimply creates an expression object and returns it.\n\n\\include make_circulant.cpp.entry\n\n\n\\section TopicMain A simple main function for testing\n\nFinally, a short \\c main function that shows how the \\c makeCirculant\nfunction can be called.\n\n\\include make_circulant.cpp.main\n\nIf all the fragments are combined, the following output is produced,\nshowing that the program works as expected:\n\n\\include make_circulant.out\n\n*/\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/Overview.dox",
    "content": "namespace Eigen {\n\n/** \\mainpage notitle\n\nThis is the API documentation for Eigen3. You can <a href=\"eigen-doc.tgz\">download</a> it as a tgz archive for offline reading.\n\nFor a first contact with Eigen, the best place is to have a look at the \\link GettingStarted getting started \\endlink page that show you how to write and compile your first program with Eigen.\n\nThen, the \\b quick \\b reference \\b pages give you a quite complete description of the API in a very condensed format that is specially useful to recall the syntax of a particular feature, or to have a quick look at the API. They currently cover the two following feature sets, and more will come in the future:\n  - \\link QuickRefPage [QuickRef] Dense matrix and array manipulations \\endlink\n  - \\link SparseQuickRefPage [QuickRef] Sparse linear algebra \\endlink\n\nYou're a MatLab user? There is also a <a href=\"AsciiQuickReference.txt\">short ASCII reference</a> with Matlab translations.\n  \nThe \\b main \\b documentation is organized into \\em chapters covering different domains of features.\nThey are themselves composed of \\em user \\em manual pages describing the different features in a comprehensive way, and \\em reference pages that gives you access to the API documentation through the related Eigen's \\em modules and \\em classes.\n\nUnder the \\subpage UserManual_CustomizingEigen section, you will find discussions and examples on extending %Eigen's features and supporting custom scalar types.\n\nUnder the \\subpage UserManual_Generalities section, you will find documentation on more general topics such as preprocessor directives, controlling assertions, multi-threading, MKL support, some Eigen's internal insights, and much more...\n\nFinally, do not miss the search engine, useful to quickly get to the documentation of a given class or function.\n\nWant more? Checkout the <a href=\"unsupported/index.html\">\\em unsupported \\em modules </a> documentation.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/PassingByValue.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TopicPassingByValue Passing Eigen objects by value to functions\n\nPassing objects by value is almost always a very bad idea in C++, as this means useless copies, and one should pass them by reference instead.\n\nWith %Eigen, this is even more important: passing \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen objects\" by value is not only inefficient, it can be illegal or make your program crash! And the reason is that these %Eigen objects have alignment modifiers that aren't respected when they are passed by value.\n\nFor example, a function like this, where \\c v is passed by value:\n\n\\code\nvoid my_function(Eigen::Vector2d v);\n\\endcode\n\nneeds to be rewritten as follows, passing \\c v by const reference:\n\n\\code\nvoid my_function(const Eigen::Vector2d& v);\n\\endcode\n\nLikewise if you have a class having an %Eigen object as member:\n\n\\code\nstruct Foo\n{\n  Eigen::Vector2d v;\n};\nvoid my_function(Foo v);\n\\endcode\n\nThis function also needs to be rewritten like this:\n\\code\nvoid my_function(const Foo& v);\n\\endcode\n\nNote that on the other hand, there is no problem with functions that return objects by value.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/Pitfalls.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicPitfalls Common pitfalls\n\n\n\\section TopicPitfalls_template_keyword Compilation error with template methods\n\nSee this \\link TopicTemplateKeyword page \\endlink.\n\n\n\\section TopicPitfalls_aliasing Aliasing\n\nDon't miss this \\link TopicAliasing page \\endlink on aliasing,\nespecially if you got wrong results in statements where the destination appears on the right hand side of the expression.\n\n\n\\section TopicPitfalls_alignment_issue Alignment Issues (runtime assertion)\n\n%Eigen does explicit vectorization, and while that is appreciated by many users, that also leads to some issues in special situations where data alignment is compromised.\nIndeed, prior to C++17,  C++ does not have quite good enough support for explicit data alignment.\nIn that case your program hits an assertion failure (that is, a \"controlled crash\") with a message that tells you to consult this page:\n\\code\nhttp://eigen.tuxfamily.org/dox/group__TopicUnalignedArrayAssert.html\n\\endcode\nHave a look at \\link TopicUnalignedArrayAssert it \\endlink and see for yourself if that's something that you can cope with.\nIt contains detailed information about how to deal with each known cause for that issue.\n\nNow what if you don't care about vectorization and so don't want to be annoyed with these alignment issues? Then read \\link getrid how to get rid of them \\endlink.\n\n\n\\section TopicPitfalls_auto_keyword C++11 and the auto keyword\n\nIn short: do not use the auto keywords with %Eigen's expressions, unless you are 100% sure about what you are doing. In particular, do not use the auto keyword as a replacement for a \\c Matrix<> type. Here is an example:\n\n\\code\nMatrixXd A, B;\nauto C = A*B;\nfor(...) { ... w = C * v;  ...}\n\\endcode\n\nIn this example, the type of C is not a \\c MatrixXd but an abstract expression representing a matrix product and storing references to \\c A and \\c B.\nTherefore, the product of \\c A*B will be carried out multiple times, once per iteration of the for loop.\nMoreover, if the coefficients of `A` or `B` change during the iteration, then `C` will evaluate to different values as in the following example:\n\n\\code\nMatrixXd A = ..., B = ...;\nauto C = A*B;\nMatrixXd R1 = C;\nA = ...;\nMatrixXd R2 = C;\n\\endcode\nfor which we end up with `R1` &ne; `R2`.\n\n\nHere is another example leading to a segfault:\n\\code\nauto C = ((A+B).eval()).transpose();\n// do something with C\n\\endcode\nThe problem is that \\c eval() returns a temporary object (in this case a \\c MatrixXd) which is then referenced by the \\c Transpose<> expression.\nHowever, this temporary is deleted right after the first line, and then the \\c C expression references a dead object.\nOne possible fix consists in applying \\c eval() on the whole expression:\n\\code\nauto C = (A+B).transpose().eval();\n\\endcode\n\nThe same issue might occur when sub expressions are automatically evaluated by %Eigen as in the following example:\n\\code\nVectorXd u, v;\nauto C = u + (A*v).normalized();\n// do something with C\n\\endcode\nHere the \\c normalized() method has to evaluate the expensive product \\c A*v to avoid evaluating it twice.\nAgain, one possible fix is to call \\c .eval() on the whole expression:\n\\code\nauto C = (u + (A*v).normalized()).eval();\n\\endcode\nIn this case, \\c C will be a regular \\c VectorXd object.\nNote that DenseBase::eval() is smart enough to avoid copies when the underlying expression is already a plain \\c Matrix<>.\n\n\n\\section TopicPitfalls_header_issues Header Issues (failure to compile)\n\nWith all libraries, one must check the documentation for which header to include.\nThe same is true with %Eigen, but slightly worse: with %Eigen, a method in a class may require an additional \\c \\#include over what the class itself requires!\nFor example, if you want to use the \\c cross() method on a vector (it computes a cross-product) then you need to:\n\\code\n#include<Eigen/Geometry>\n\\endcode\nWe try to always document this, but do tell us if we forgot an occurrence.\n\n\n\\section TopicPitfalls_ternary_operator Ternary operator\n\nIn short: avoid the use of the ternary operator <code>(COND ? THEN : ELSE)</code> with %Eigen's expressions for the \\c THEN and \\c ELSE statements.\nTo see why, let's consider the following example:\n\\code\nVector3f A;\nA << 1, 2, 3;\nVector3f B = ((1 < 0) ? (A.reverse()) : A);\n\\endcode\nThis example will return <code>B = 3, 2, 1</code>. Do you see why?\nThe reason is that in c++ the type of the \\c ELSE statement is inferred from the type of the \\c THEN expression such that both match.\nSince \\c THEN is a <code>Reverse<Vector3f></code>, the \\c ELSE statement A is converted to a <code>Reverse<Vector3f></code>, and the compiler thus generates:\n\\code\nVector3f B = ((1 < 0) ? (A.reverse()) : Reverse<Vector3f>(A));\n\\endcode\nIn this very particular case, a workaround would be to call A.reverse().eval() for the \\c THEN statement, but the safest and fastest is really to avoid this ternary operator with %Eigen's expressions and use a if/else construct.\n\n\n\\section TopicPitfalls_pass_by_value Pass-by-value\n\nIf you don't know why passing-by-value is wrong with %Eigen, read this \\link TopicPassingByValue page \\endlink first.\n\nWhile you may be extremely careful and use care to make sure that all of your code that explicitly uses %Eigen types is pass-by-reference you have to watch out for templates which define the argument types at compile time.\n\nIf a template has a function that takes arguments pass-by-value, and the relevant template parameter ends up being an %Eigen type, then you will of course have the same alignment problems that you would in an explicitly defined function passing %Eigen types by reference.\n\nUsing %Eigen types with other third party libraries or even the STL can present the same problem.\n<code>boost::bind</code> for example uses pass-by-value to store arguments in the returned functor.\nThis will of course be a problem.\n\nThere are at least two ways around this:\n  - If the value you are passing is guaranteed to be around for the life of the functor, you can use boost::ref() to wrap the value as you pass it to boost::bind. Generally this is not a solution for values on the stack as if the functor ever gets passed to a lower or independent scope, the object may be gone by the time it's attempted to be used.\n  - The other option is to make your functions take a reference counted pointer like boost::shared_ptr as the argument. This avoids needing to worry about managing the lifetime of the object being passed.\n\n\n\\section TopicPitfalls_matrix_bool Matrices with boolean coefficients\n\nThe current behaviour of using \\c Matrix with boolean coefficients is inconsistent and likely to change in future versions of Eigen, so please use it carefully!\n\nA simple example for such an inconsistency is \n\n\\code\ntemplate<int Size>\nvoid foo() {\n  Eigen::Matrix<bool, Size, Size> A, B, C;\n  A.setOnes();\n  B.setOnes();\n\n  C = A * B - A * B;\n  std::cout << C << \"\\n\";\n}\n\\endcode\n\nsince calling \\c foo<3>() prints the zero matrix while calling \\c foo<10>() prints the identity matrix.\n\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/PreprocessorDirectives.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicPreprocessorDirectives Preprocessor directives\n\nYou can control some aspects of %Eigen by defining the preprocessor tokens using \\c \\#define. These macros\nshould be defined before any %Eigen headers are included. Often they are best set in the project options.\n\nThis page lists the preprocessor tokens recognized by %Eigen.\n\n\\eigenAutoToc\n\n\n\\section TopicPreprocessorDirectivesMajor Macros with major effects\n\nThese macros have a major effect and typically break the API (Application Programming Interface) and/or the\nABI (Application Binary Interface). This can be rather dangerous: if parts of your program are compiled with\none option, and other parts (or libraries that you use) are compiled with another option, your program may\nfail to link or exhibit subtle bugs. Nevertheless, these options can be useful for people who know what they\nare doing.\n\n - \\b EIGEN2_SUPPORT and \\b EIGEN2_SUPPORT_STAGEnn_xxx are disabled starting from the 3.3 release.\n   Defining one of these will raise a compile-error. If you need to compile Eigen2 code,\n   <a href=\"http://eigen.tuxfamily.org/index.php?title=Eigen2\">check this site</a>.\n - \\b EIGEN_DEFAULT_DENSE_INDEX_TYPE - the type for column and row indices in matrices, vectors and array\n   (DenseBase::Index). Set to \\c std::ptrdiff_t by default.\n - \\b EIGEN_DEFAULT_IO_FORMAT - the IOFormat to use when printing a matrix if no %IOFormat is specified.\n   Defaults to the %IOFormat constructed by the default constructor IOFormat::IOFormat().\n - \\b EIGEN_INITIALIZE_MATRICES_BY_ZERO - if defined, all entries of newly constructed matrices and arrays are\n   initialized to zero, as are new entries in matrices and arrays after resizing. Not defined by default.\n   \\warning The unary (resp. binary) constructor of \\c 1x1 (resp. \\c 2x1 or \\c 1x2) fixed size matrices is\n   always interpreted as an initialization constructor where the argument(s) are the coefficient values\n   and not the sizes. For instance, \\code Vector2d v(2,1); \\endcode will create a vector with coeficients [2,1],\n   and \\b not a \\c 2x1 vector initialized with zeros (i.e., [0,0]). If such cases might occur, then it is\n   recommended to use the default constructor with a explicit call to resize:\n   \\code\n   Matrix<?,SizeAtCompileTime,1> v;\n   v.resize(size);\n   Matrix<?,RowsAtCompileTime,ColsAtCompileTime> m;\n   m.resize(rows,cols);\n   \\endcode\n - \\b EIGEN_INITIALIZE_MATRICES_BY_NAN - if defined, all entries of newly constructed matrices and arrays are\n   initialized to NaN, as are new entries in matrices and arrays after resizing. This option is especially\n   useful for debugging purpose, though a memory tool like <a href=\"http://valgrind.org/\">valgrind</a> is\n   preferable. Not defined by default.\n   \\warning See the documentation of \\c EIGEN_INITIALIZE_MATRICES_BY_ZERO for a discussion on a limitations\n   of these macros when applied to \\c 1x1, \\c 1x2, and \\c 2x1 fixed-size matrices.\n - \\b EIGEN_NO_AUTOMATIC_RESIZING - if defined, the matrices (or arrays) on both sides of an assignment \n   <tt>a = b</tt> have to be of the same size; otherwise, %Eigen automatically resizes \\c a so that it is of\n   the correct size. Not defined by default.\n\n\n\\section TopicPreprocessorDirectivesCppVersion C++ standard features\n\nBy default, %Eigen strive to automatically detect and enable language features at compile-time based on\nthe information provided by the compiler.\n\n - \\b EIGEN_MAX_CPP_VER - disables usage of C++ features requiring a version greater than EIGEN_MAX_CPP_VER.\n   Possible values are: 03, 11, 14, 17, etc. If not defined (the default), %Eigen enables all features supported\n   by the compiler.\n\nIndividual features can be explicitly enabled or disabled by defining the following token to 0 or 1 respectively.\nFor instance, one might limit the C++ version to C++03 by defining EIGEN_MAX_CPP_VER=03, but still enable C99 math\nfunctions by defining EIGEN_HAS_C99_MATH=1.\n\n - \\b EIGEN_HAS_C99_MATH - controls the usage of C99 math functions such as erf, erfc, lgamma, etc.\n   Automatic detection disabled if EIGEN_MAX_CPP_VER<11.\n - \\b EIGEN_HAS_CXX11_MATH - controls the implementation of some functions such as round, logp1, isinf, isnan, etc.\n   Automatic detection disabled if EIGEN_MAX_CPP_VER<11.\n - \\b EIGEN_HAS_RVALUE_REFERENCES - defines whether rvalue references are supported\n   Automatic detection disabled if EIGEN_MAX_CPP_VER<11.\n - \\b EIGEN_HAS_STD_RESULT_OF - defines whether std::result_of is supported\n   Automatic detection disabled if EIGEN_MAX_CPP_VER<11.\n - \\b EIGEN_HAS_VARIADIC_TEMPLATES - defines whether variadic templates are supported\n   Automatic detection disabled if EIGEN_MAX_CPP_VER<11.\n - \\b EIGEN_HAS_CONSTEXPR - defines whether relaxed const expression are supported\n   Automatic detection disabled if EIGEN_MAX_CPP_VER<14.\n - \\b EIGEN_HAS_CXX11_CONTAINERS - defines whether STL's containers follows C++11 specifications\n   Automatic detection disabled if EIGEN_MAX_CPP_VER<11.\n - \\b EIGEN_HAS_CXX11_NOEXCEPT - defines whether noexcept is supported\n   Automatic detection disabled if EIGEN_MAX_CPP_VER<11.\n - \\b EIGEN_NO_IO - Disables any usage and support for `<iostreams>`.\n\n\\section TopicPreprocessorDirectivesAssertions Assertions\n\nThe %Eigen library contains many assertions to guard against programming errors, both at compile time and at\nrun time. However, these assertions do cost time and can thus be turned off.\n\n - \\b EIGEN_NO_DEBUG - disables %Eigen's assertions if defined. Not defined by default, unless the\n   \\c NDEBUG macro is defined (this is a standard C++ macro which disables all asserts). \n - \\b EIGEN_NO_STATIC_ASSERT - if defined, compile-time static assertions are replaced by runtime assertions; \n   this saves compilation time. Not defined by default.\n - \\b eigen_assert - macro with one argument that is used inside %Eigen for assertions. By default, it is\n   basically defined to be \\c assert, which aborts the program if the assertion is violated. Redefine this\n   macro if you want to do something else, like throwing an exception.\n - \\b EIGEN_MPL2_ONLY - disable non MPL2 compatible features, or in other words disable the features which\n   are still under the LGPL.\n\n\n\\section TopicPreprocessorDirectivesPerformance Alignment, vectorization and performance tweaking\n\n - \\b \\c EIGEN_MALLOC_ALREADY_ALIGNED - Can be set to 0 or 1 to tell whether default system \\c malloc already\n   returns aligned buffers. In not defined, then this information is automatically deduced from the compiler\n   and system preprocessor tokens.\n - \\b \\c EIGEN_MAX_ALIGN_BYTES - Must be a power of two, or 0. Defines an upper bound on the memory boundary in bytes on which dynamically and statically allocated data may be aligned by %Eigen. If not defined, a default value is automatically computed based on architecture, compiler, and OS.\n This option is typically used to enforce binary compatibility between code/libraries compiled with different SIMD options. For instance, one may compile AVX code and enforce ABI compatibility with existing SSE code by defining \\c EIGEN_MAX_ALIGN_BYTES=16. In the other way round, since by default AVX implies 32 bytes alignment for best performance, one can compile SSE code to be ABI compatible with AVX code by defining \\c EIGEN_MAX_ALIGN_BYTES=32.\n - \\b \\c EIGEN_MAX_STATIC_ALIGN_BYTES - Same as \\c EIGEN_MAX_ALIGN_BYTES but for statically allocated data only. By default, if only  \\c EIGEN_MAX_ALIGN_BYTES is defined, then \\c EIGEN_MAX_STATIC_ALIGN_BYTES == \\c EIGEN_MAX_ALIGN_BYTES, otherwise a default value is automatically computed based on architecture, compiler, and OS (can be smaller than the default value of EIGEN_MAX_ALIGN_BYTES on architectures that do not support stack alignment).\n Let us emphasize that \\c EIGEN_MAX_*_ALIGN_BYTES define only a diserable upper bound. In practice data is aligned to largest power-of-two common divisor of \\c EIGEN_MAX_STATIC_ALIGN_BYTES and the size of the data, such that memory is not wasted.\n - \\b \\c EIGEN_DONT_PARALLELIZE - if defined, this disables multi-threading. This is only relevant if you enabled OpenMP.\n   See \\ref TopicMultiThreading for details.\n - \\b \\c EIGEN_DONT_VECTORIZE - disables explicit vectorization when defined. Not defined by default, unless \n   alignment is disabled by %Eigen's platform test or the user defining \\c EIGEN_DONT_ALIGN.\n - \\b \\c EIGEN_UNALIGNED_VECTORIZE - disables/enables vectorization with unaligned stores. Default is 1 (enabled).\n   If set to 0 (disabled), then expression for which the destination cannot be aligned are not vectorized (e.g., unaligned\n   small fixed size vectors or matrices)\n - \\b \\c EIGEN_FAST_MATH - enables some optimizations which might affect the accuracy of the result. This currently\n   enables the SSE vectorization of sin() and cos(), and speedups sqrt() for single precision. Defined to 1 by default.\n   Define it to 0 to disable.\n - \\b \\c EIGEN_UNROLLING_LIMIT - defines the size of a loop to enable meta unrolling. Set it to zero to disable\n   unrolling. The size of a loop here is expressed in %Eigen's own notion of \"number of FLOPS\", it does not\n   correspond to the number of iterations or the number of instructions. The default is value 110.\n - \\b \\c EIGEN_STACK_ALLOCATION_LIMIT - defines the maximum bytes for a buffer to be allocated on the stack. For internal\n   temporary buffers, dynamic memory allocation is employed as a fall back. For fixed-size matrices or arrays, exceeding\n   this threshold raises a compile time assertion. Use 0 to set no limit. Default is 128 KB.\n - \\b \\c EIGEN_NO_CUDA - disables CUDA support when defined. Might be useful in .cu files for which Eigen is used on the host only,\n   and never called from device code.\n - \\b \\c EIGEN_STRONG_INLINE - This macro is used to qualify critical functions and methods that we expect the compiler to inline.\n   By default it is defined to \\c __forceinline for MSVC and ICC, and to \\c inline for other compilers. A tipical usage is to\n   define it to \\c inline for MSVC users wanting faster compilation times, at the risk of performance degradations in some rare\n   cases for which MSVC inliner fails to do a good job.\n - \\b \\c EIGEN_DEFAULT_L1_CACHE_SIZE - Sets the default L1 cache size that is used in Eigen's GEBP kernel when the correct cache size cannot be determined at runtime.\n - \\b \\c EIGEN_DEFAULT_L2_CACHE_SIZE - Sets the default L2 cache size that is used in Eigen's GEBP kernel when the correct cache size cannot be determined at runtime.\n - \\b \\c EIGEN_DEFAULT_L3_CACHE_SIZE - Sets the default L3 cache size that is used in Eigen's GEBP kernel when the correct cache size cannot be determined at runtime.\n\n - \\c EIGEN_DONT_ALIGN - Deprecated, it is a synonym for \\c EIGEN_MAX_ALIGN_BYTES=0. It disables alignment completely. %Eigen will not try to align its objects and does not expect that any objects passed to it are aligned. This will turn off vectorization if \\b \\c EIGEN_UNALIGNED_VECTORIZE=1. Not defined by default.\n - \\c EIGEN_DONT_ALIGN_STATICALLY - Deprecated, it is a synonym for \\c EIGEN_MAX_STATIC_ALIGN_BYTES=0. It disables alignment of arrays on the stack. Not defined by default, unless \\c EIGEN_DONT_ALIGN is defined.\n\n\n\\section TopicPreprocessorDirectivesPlugins Plugins\n\nIt is possible to add new methods to many fundamental classes in %Eigen by writing a plugin. As explained in\nthe section \\ref TopicCustomizing_Plugins, the plugin is specified by defining a \\c EIGEN_xxx_PLUGIN macro. The\nfollowing macros are supported; none of them are defined by default.\n\n - \\b EIGEN_ARRAY_PLUGIN - filename of plugin for extending the Array class.\n - \\b EIGEN_ARRAYBASE_PLUGIN - filename of plugin for extending the ArrayBase class.\n - \\b EIGEN_CWISE_PLUGIN - filename of plugin for extending the Cwise class.\n - \\b EIGEN_DENSEBASE_PLUGIN - filename of plugin for extending the DenseBase class.\n - \\b EIGEN_DYNAMICSPARSEMATRIX_PLUGIN - filename of plugin for extending the DynamicSparseMatrix class.\n - \\b EIGEN_FUNCTORS_PLUGIN - filename of plugin for adding new functors and specializations of functor_traits.\n - \\b EIGEN_MAPBASE_PLUGIN - filename of plugin for extending the MapBase class.\n - \\b EIGEN_MATRIX_PLUGIN - filename of plugin for extending the Matrix class.\n - \\b EIGEN_MATRIXBASE_PLUGIN - filename of plugin for extending the MatrixBase class.\n - \\b EIGEN_PLAINOBJECTBASE_PLUGIN - filename of plugin for extending the PlainObjectBase class.\n - \\b EIGEN_QUATERNION_PLUGIN - filename of plugin for extending the Quaternion class.\n - \\b EIGEN_QUATERNIONBASE_PLUGIN - filename of plugin for extending the QuaternionBase class.\n - \\b EIGEN_SPARSEMATRIX_PLUGIN - filename of plugin for extending the SparseMatrix class.\n - \\b EIGEN_SPARSEMATRIXBASE_PLUGIN - filename of plugin for extending the SparseMatrixBase class.\n - \\b EIGEN_SPARSEVECTOR_PLUGIN - filename of plugin for extending the SparseVector class.\n - \\b EIGEN_TRANSFORM_PLUGIN - filename of plugin for extending the Transform class.\n - \\b EIGEN_VECTORWISEOP_PLUGIN - filename of plugin for extending the VectorwiseOp class.\n\n\\section TopicPreprocessorDirectivesDevelopers Macros for Eigen developers\n\nThese macros are mainly meant for people developing %Eigen and for testing purposes. Even though, they might be useful for power users and the curious for debugging and testing purpose, they \\b should \\b not \\b be \\b used by real-word code.\n\n - \\b EIGEN_DEFAULT_TO_ROW_MAJOR - when defined, the default storage order for matrices becomes row-major\n   instead of column-major. Not defined by default.\n - \\b EIGEN_INTERNAL_DEBUGGING - if defined, enables assertions in %Eigen's internal routines. This is useful\n   for debugging %Eigen itself. Not defined by default.\n - \\b EIGEN_NO_MALLOC - if defined, any request from inside the %Eigen to allocate memory from the heap\n   results in an assertion failure. This is useful to check that some routine does not allocate memory\n   dynamically. Not defined by default.\n - \\b EIGEN_RUNTIME_NO_MALLOC - if defined, a new switch is introduced which can be turned on and off by\n   calling <tt>set_is_malloc_allowed(bool)</tt>. If malloc is not allowed and %Eigen tries to allocate memory\n   dynamically anyway, an assertion failure results. Not defined by default.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/QuickReference.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage QuickRefPage Quick reference guide\n\n\\eigenAutoToc\n\n<hr>\n\n<a href=\"#\" class=\"top\">top</a>\n\\section QuickRef_Headers Modules and Header files\n\nThe Eigen library is divided in a Core module and several additional modules. Each module has a corresponding header file which has to be included in order to use the module. The \\c %Dense and \\c Eigen header files are provided to conveniently gain access to several modules at once.\n\n<table class=\"manual\">\n<tr><th>Module</th><th>Header file</th><th>Contents</th></tr>\n<tr            ><td>\\link Core_Module Core \\endlink</td><td>\\code#include <Eigen/Core>\\endcode</td><td>Matrix and Array classes, basic linear algebra (including triangular and selfadjoint products), array manipulation</td></tr>\n<tr class=\"alt\"><td>\\link Geometry_Module Geometry \\endlink</td><td>\\code#include <Eigen/Geometry>\\endcode</td><td>Transform, Translation, Scaling, Rotation2D and 3D rotations (Quaternion, AngleAxis)</td></tr>\n<tr            ><td>\\link LU_Module LU \\endlink</td><td>\\code#include <Eigen/LU>\\endcode</td><td>Inverse, determinant, LU decompositions with solver (FullPivLU, PartialPivLU)</td></tr>\n<tr class=\"alt\"><td>\\link Cholesky_Module Cholesky \\endlink</td><td>\\code#include <Eigen/Cholesky>\\endcode</td><td>LLT and LDLT Cholesky factorization with solver</td></tr>\n<tr            ><td>\\link Householder_Module Householder \\endlink</td><td>\\code#include <Eigen/Householder>\\endcode</td><td>Householder transformations; this module is used by several linear algebra modules</td></tr>\n<tr class=\"alt\"><td>\\link SVD_Module SVD \\endlink</td><td>\\code#include <Eigen/SVD>\\endcode</td><td>SVD decompositions with least-squares solver (JacobiSVD, BDCSVD)</td></tr>\n<tr            ><td>\\link QR_Module QR \\endlink</td><td>\\code#include <Eigen/QR>\\endcode</td><td>QR decomposition with solver (HouseholderQR, ColPivHouseholderQR, FullPivHouseholderQR)</td></tr>\n<tr class=\"alt\"><td>\\link Eigenvalues_Module Eigenvalues \\endlink</td><td>\\code#include <Eigen/Eigenvalues>\\endcode</td><td>Eigenvalue, eigenvector decompositions (EigenSolver, SelfAdjointEigenSolver, ComplexEigenSolver)</td></tr>\n<tr            ><td>\\link Sparse_Module Sparse \\endlink</td><td>\\code#include <Eigen/Sparse>\\endcode</td><td>%Sparse matrix storage and related basic linear algebra (SparseMatrix, SparseVector) \\n (see \\ref SparseQuickRefPage for details on sparse modules)</td></tr>\n<tr class=\"alt\"><td></td><td>\\code#include <Eigen/Dense>\\endcode</td><td>Includes Core, Geometry, LU, Cholesky, SVD, QR, and Eigenvalues header files</td></tr>\n<tr            ><td></td><td>\\code#include <Eigen/Eigen>\\endcode</td><td>Includes %Dense and %Sparse header files (the whole Eigen library)</td></tr>\n</table>\n\n<a href=\"#\" class=\"top\">top</a>\n\\section QuickRef_Types Array, matrix and vector types\n\n\n\\b Recall: Eigen provides two kinds of dense objects: mathematical matrices and vectors which are both represented by the template class Matrix, and general 1D and 2D arrays represented by the template class Array:\n\\code\ntypedef Matrix<Scalar, RowsAtCompileTime, ColsAtCompileTime, Options> MyMatrixType;\ntypedef Array<Scalar, RowsAtCompileTime, ColsAtCompileTime, Options> MyArrayType;\n\\endcode\n\n\\li \\c Scalar is the scalar type of the coefficients (e.g., \\c float, \\c double, \\c bool, \\c int, etc.).\n\\li \\c RowsAtCompileTime and \\c ColsAtCompileTime are the number of rows and columns of the matrix as known at compile-time or \\c Dynamic.\n\\li \\c Options can be \\c ColMajor or \\c RowMajor, default is \\c ColMajor. (see class Matrix for more options)\n\nAll combinations are allowed: you can have a matrix with a fixed number of rows and a dynamic number of columns, etc. The following are all valid:\n\\code\nMatrix<double, 6, Dynamic>                  // Dynamic number of columns (heap allocation)\nMatrix<double, Dynamic, 2>                  // Dynamic number of rows (heap allocation)\nMatrix<double, Dynamic, Dynamic, RowMajor>  // Fully dynamic, row major (heap allocation)\nMatrix<double, 13, 3>                       // Fully fixed (usually allocated on stack)\n\\endcode\n\nIn most cases, you can simply use one of the convenience typedefs for \\ref matrixtypedefs \"matrices\" and \\ref arraytypedefs \"arrays\". Some examples:\n<table class=\"example\">\n<tr><th>Matrices</th><th>Arrays</th></tr>\n<tr><td>\\code\nMatrix<float,Dynamic,Dynamic>   <=>   MatrixXf\nMatrix<double,Dynamic,1>        <=>   VectorXd\nMatrix<int,1,Dynamic>           <=>   RowVectorXi\nMatrix<float,3,3>               <=>   Matrix3f\nMatrix<float,4,1>               <=>   Vector4f\n\\endcode</td><td>\\code\nArray<float,Dynamic,Dynamic>    <=>   ArrayXXf\nArray<double,Dynamic,1>         <=>   ArrayXd\nArray<int,1,Dynamic>            <=>   RowArrayXi\nArray<float,3,3>                <=>   Array33f\nArray<float,4,1>                <=>   Array4f\n\\endcode</td></tr>\n</table>\n\nConversion between the matrix and array worlds:\n\\code\nArray44f a1, a2;\nMatrix4f m1, m2;\nm1 = a1 * a2;                     // coeffwise product, implicit conversion from array to matrix.\na1 = m1 * m2;                     // matrix product, implicit conversion from matrix to array.\na2 = a1 + m1.array();             // mixing array and matrix is forbidden\nm2 = a1.matrix() + m1;            // and explicit conversion is required.\nArrayWrapper<Matrix4f> m1a(m1);   // m1a is an alias for m1.array(), they share the same coefficients\nMatrixWrapper<Array44f> a1m(a1);\n\\endcode\n\nIn the rest of this document we will use the following symbols to emphasize the features which are specifics to a given kind of object:\n\\li <a name=\"matrixonly\"></a>\\matrixworld linear algebra matrix and vector only\n\\li <a name=\"arrayonly\"></a>\\arrayworld array objects only\n\n\\subsection QuickRef_Basics Basic matrix manipulation\n\n<table class=\"manual\">\n<tr><th></th><th>1D objects</th><th>2D objects</th><th>Notes</th></tr>\n<tr><td>Constructors</td>\n<td>\\code\nVector4d  v4;\nVector2f  v1(x, y);\nArray3i   v2(x, y, z);\nVector4d  v3(x, y, z, w);\n\nVectorXf  v5; // empty object\nArrayXf   v6(size);\n\\endcode</td><td>\\code\nMatrix4f  m1;\n\n\n\n\nMatrixXf  m5; // empty object\nMatrixXf  m6(nb_rows, nb_columns);\n\\endcode</td><td class=\"note\">\nBy default, the coefficients \\n are left uninitialized</td></tr>\n<tr class=\"alt\"><td>Comma initializer</td>\n<td>\\code\nVector3f  v1;     v1 << x, y, z;\nArrayXf   v2(4);  v2 << 1, 2, 3, 4;\n\n\\endcode</td><td>\\code\nMatrix3f  m1;   m1 << 1, 2, 3,\n                      4, 5, 6,\n                      7, 8, 9;\n\\endcode</td><td></td></tr>\n\n<tr><td>Comma initializer (bis)</td>\n<td colspan=\"2\">\n\\include Tutorial_commainit_02.cpp\n</td>\n<td>\noutput:\n\\verbinclude Tutorial_commainit_02.out\n</td>\n</tr>\n\n<tr class=\"alt\"><td>Runtime info</td>\n<td>\\code\nvector.size();\n\nvector.innerStride();\nvector.data();\n\\endcode</td><td>\\code\nmatrix.rows();          matrix.cols();\nmatrix.innerSize();     matrix.outerSize();\nmatrix.innerStride();   matrix.outerStride();\nmatrix.data();\n\\endcode</td><td class=\"note\">Inner/Outer* are storage order dependent</td></tr>\n<tr><td>Compile-time info</td>\n<td colspan=\"2\">\\code\nObjectType::Scalar              ObjectType::RowsAtCompileTime\nObjectType::RealScalar          ObjectType::ColsAtCompileTime\nObjectType::Index               ObjectType::SizeAtCompileTime\n\\endcode</td><td></td></tr>\n<tr class=\"alt\"><td>Resizing</td>\n<td>\\code\nvector.resize(size);\n\n\nvector.resizeLike(other_vector);\nvector.conservativeResize(size);\n\\endcode</td><td>\\code\nmatrix.resize(nb_rows, nb_cols);\nmatrix.resize(Eigen::NoChange, nb_cols);\nmatrix.resize(nb_rows, Eigen::NoChange);\nmatrix.resizeLike(other_matrix);\nmatrix.conservativeResize(nb_rows, nb_cols);\n\\endcode</td><td class=\"note\">no-op if the new sizes match,<br/>otherwise data are lost<br/><br/>resizing with data preservation</td></tr>\n\n<tr><td>Coeff access with \\n range checking</td>\n<td>\\code\nvector(i)     vector.x()\nvector[i]     vector.y()\n              vector.z()\n              vector.w()\n\\endcode</td><td>\\code\nmatrix(i,j)\n\\endcode</td><td class=\"note\">Range checking is disabled if \\n NDEBUG or EIGEN_NO_DEBUG is defined</td></tr>\n\n<tr class=\"alt\"><td>Coeff access without \\n range checking</td>\n<td>\\code\nvector.coeff(i)\nvector.coeffRef(i)\n\\endcode</td><td>\\code\nmatrix.coeff(i,j)\nmatrix.coeffRef(i,j)\n\\endcode</td><td></td></tr>\n\n<tr><td>Assignment/copy</td>\n<td colspan=\"2\">\\code\nobject = expression;\nobject_of_float = expression_of_double.cast<float>();\n\\endcode</td><td class=\"note\">the destination is automatically resized (if possible)</td></tr>\n\n</table>\n\n\\subsection QuickRef_PredefMat Predefined Matrices\n\n<table class=\"manual\">\n<tr>\n  <th>Fixed-size matrix or vector</th>\n  <th>Dynamic-size matrix</th>\n  <th>Dynamic-size vector</th>\n</tr>\n<tr style=\"border-bottom-style: none;\">\n  <td>\n\\code\ntypedef {Matrix3f|Array33f} FixedXD;\nFixedXD x;\n\nx = FixedXD::Zero();\nx = FixedXD::Ones();\nx = FixedXD::Constant(value);\nx = FixedXD::Random();\nx = FixedXD::LinSpaced(size, low, high);\n\nx.setZero();\nx.setOnes();\nx.setConstant(value);\nx.setRandom();\nx.setLinSpaced(size, low, high);\n\\endcode\n  </td>\n  <td>\n\\code\ntypedef {MatrixXf|ArrayXXf} Dynamic2D;\nDynamic2D x;\n\nx = Dynamic2D::Zero(rows, cols);\nx = Dynamic2D::Ones(rows, cols);\nx = Dynamic2D::Constant(rows, cols, value);\nx = Dynamic2D::Random(rows, cols);\nN/A\n\nx.setZero(rows, cols);\nx.setOnes(rows, cols);\nx.setConstant(rows, cols, value);\nx.setRandom(rows, cols);\nN/A\n\\endcode\n  </td>\n  <td>\n\\code\ntypedef {VectorXf|ArrayXf} Dynamic1D;\nDynamic1D x;\n\nx = Dynamic1D::Zero(size);\nx = Dynamic1D::Ones(size);\nx = Dynamic1D::Constant(size, value);\nx = Dynamic1D::Random(size);\nx = Dynamic1D::LinSpaced(size, low, high);\n\nx.setZero(size);\nx.setOnes(size);\nx.setConstant(size, value);\nx.setRandom(size);\nx.setLinSpaced(size, low, high);\n\\endcode\n  </td>\n</tr>\n\n<tr><td colspan=\"3\">Identity and \\link MatrixBase::Unit basis vectors \\endlink \\matrixworld</td></tr>\n<tr style=\"border-bottom-style: none;\">\n  <td>\n\\code\nx = FixedXD::Identity();\nx.setIdentity();\n\nVector3f::UnitX() // 1 0 0\nVector3f::UnitY() // 0 1 0\nVector3f::UnitZ() // 0 0 1\nVector4f::Unit(i)\nx.setUnit(i);\n\\endcode\n  </td>\n  <td>\n\\code\nx = Dynamic2D::Identity(rows, cols);\nx.setIdentity(rows, cols);\n\n\n\nN/A\n\\endcode\n  </td>\n  <td>\\code\nN/A\n\n\nVectorXf::Unit(size,i)\nx.setUnit(size,i);\nVectorXf::Unit(4,1) == Vector4f(0,1,0,0)\n                    == Vector4f::UnitY()\n\\endcode\n  </td>\n</tr>\n</table>\n\nNote that it is allowed to call any of the \\c set* functions to a dynamic-sized vector or matrix without passing new sizes.\nFor instance:\n\\code\nMatrixXi M(3,3);\nM.setIdentity();\n\\endcode\n\n\\subsection QuickRef_Map Mapping external arrays\n\n<table class=\"manual\">\n<tr>\n<td>Contiguous \\n memory</td>\n<td>\\code\nfloat data[] = {1,2,3,4};\nMap<Vector3f> v1(data);       // uses v1 as a Vector3f object\nMap<ArrayXf>  v2(data,3);     // uses v2 as a ArrayXf object\nMap<Array22f> m1(data);       // uses m1 as a Array22f object\nMap<MatrixXf> m2(data,2,2);   // uses m2 as a MatrixXf object\n\\endcode</td>\n</tr>\n<tr>\n<td>Typical usage \\n of strides</td>\n<td>\\code\nfloat data[] = {1,2,3,4,5,6,7,8,9};\nMap<VectorXf,0,InnerStride<2> >  v1(data,3);                      // = [1,3,5]\nMap<VectorXf,0,InnerStride<> >   v2(data,3,InnerStride<>(3));     // = [1,4,7]\nMap<MatrixXf,0,OuterStride<3> >  m2(data,2,3);                    // both lines     |1,4,7|\nMap<MatrixXf,0,OuterStride<> >   m1(data,2,3,OuterStride<>(3));   // are equal to:  |2,5,8|\n\\endcode</td>\n</tr>\n</table>\n\n\n<a href=\"#\" class=\"top\">top</a>\n\\section QuickRef_ArithmeticOperators Arithmetic Operators\n\n<table class=\"manual\">\n<tr><td>\nadd \\n subtract</td><td>\\code\nmat3 = mat1 + mat2;           mat3 += mat1;\nmat3 = mat1 - mat2;           mat3 -= mat1;\\endcode\n</td></tr>\n<tr class=\"alt\"><td>\nscalar product</td><td>\\code\nmat3 = mat1 * s1;             mat3 *= s1;           mat3 = s1 * mat1;\nmat3 = mat1 / s1;             mat3 /= s1;\\endcode\n</td></tr>\n<tr><td>\nmatrix/vector \\n products \\matrixworld</td><td>\\code\ncol2 = mat1 * col1;\nrow2 = row1 * mat1;           row1 *= mat1;\nmat3 = mat1 * mat2;           mat3 *= mat1; \\endcode\n</td></tr>\n<tr class=\"alt\"><td>\ntransposition \\n adjoint \\matrixworld</td><td>\\code\nmat1 = mat2.transpose();      mat1.transposeInPlace();\nmat1 = mat2.adjoint();        mat1.adjointInPlace();\n\\endcode\n</td></tr>\n<tr><td>\n\\link MatrixBase::dot dot \\endlink product \\n inner product \\matrixworld</td><td>\\code\nscalar = vec1.dot(vec2);\nscalar = col1.adjoint() * col2;\nscalar = (col1.adjoint() * col2).value();\\endcode\n</td></tr>\n<tr class=\"alt\"><td>\nouter product \\matrixworld</td><td>\\code\nmat = col1 * col2.transpose();\\endcode\n</td></tr>\n\n<tr><td>\n\\link MatrixBase::norm() norm \\endlink \\n \\link MatrixBase::normalized() normalization \\endlink \\matrixworld</td><td>\\code\nscalar = vec1.norm();         scalar = vec1.squaredNorm()\nvec2 = vec1.normalized();     vec1.normalize(); // inplace \\endcode\n</td></tr>\n\n<tr class=\"alt\"><td>\n\\link MatrixBase::cross() cross product \\endlink \\matrixworld</td><td>\\code\n#include <Eigen/Geometry>\nvec3 = vec1.cross(vec2);\\endcode</td></tr>\n</table>\n\n<a href=\"#\" class=\"top\">top</a>\n\\section QuickRef_Coeffwise Coefficient-wise \\& Array operators\n\nIn addition to the aforementioned operators, Eigen supports numerous coefficient-wise operator and functions.\nMost of them unambiguously makes sense in array-world\\arrayworld. The following operators are readily available for arrays,\nor available through .array() for vectors and matrices:\n\n<table class=\"manual\">\n<tr><td>Arithmetic operators</td><td>\\code\narray1 * array2     array1 / array2     array1 *= array2    array1 /= array2\narray1 + scalar     array1 - scalar     array1 += scalar    array1 -= scalar\n\\endcode</td></tr>\n<tr><td>Comparisons</td><td>\\code\narray1 < array2     array1 > array2     array1 < scalar     array1 > scalar\narray1 <= array2    array1 >= array2    array1 <= scalar    array1 >= scalar\narray1 == array2    array1 != array2    array1 == scalar    array1 != scalar\narray1.min(array2)  array1.max(array2)  array1.min(scalar)  array1.max(scalar)\n\\endcode</td></tr>\n<tr><td>Trigo, power, and \\n misc functions \\n and the STL-like variants</td><td>\\code\narray1.abs2()\narray1.abs()                  abs(array1)\narray1.sqrt()                 sqrt(array1)\narray1.log()                  log(array1)\narray1.log10()                log10(array1)\narray1.exp()                  exp(array1)\narray1.pow(array2)            pow(array1,array2)\narray1.pow(scalar)            pow(array1,scalar)\n                              pow(scalar,array2)\narray1.square()\narray1.cube()\narray1.inverse()\n\narray1.sin()                  sin(array1)\narray1.cos()                  cos(array1)\narray1.tan()                  tan(array1)\narray1.asin()                 asin(array1)\narray1.acos()                 acos(array1)\narray1.atan()                 atan(array1)\narray1.sinh()                 sinh(array1)\narray1.cosh()                 cosh(array1)\narray1.tanh()                 tanh(array1)\narray1.arg()                  arg(array1)\n\narray1.floor()                floor(array1)\narray1.ceil()                 ceil(array1)\narray1.round()                round(aray1)\n\narray1.isFinite()             isfinite(array1)\narray1.isInf()                isinf(array1)\narray1.isNaN()                isnan(array1)\n\\endcode\n</td></tr>\n</table>\n\n\nThe following coefficient-wise operators are available for all kind of expressions (matrices, vectors, and arrays), and for both real or complex scalar types:\n\n<table class=\"manual\">\n<tr><th>Eigen's API</th><th>STL-like APIs\\arrayworld </th><th>Comments</th></tr>\n<tr><td>\\code\nmat1.real()\nmat1.imag()\nmat1.conjugate()\n\\endcode\n</td><td>\\code\nreal(array1)\nimag(array1)\nconj(array1)\n\\endcode\n</td><td>\n\\code\n // read-write, no-op for real expressions\n // read-only for real, read-write for complexes\n // no-op for real expressions\n\\endcode\n</td></tr>\n</table>\n\nSome coefficient-wise operators are readily available for for matrices and vectors through the following cwise* methods:\n<table class=\"manual\">\n<tr><th>Matrix API \\matrixworld</th><th>Via Array conversions</th></tr>\n<tr><td>\\code\nmat1.cwiseMin(mat2)         mat1.cwiseMin(scalar)\nmat1.cwiseMax(mat2)         mat1.cwiseMax(scalar)\nmat1.cwiseAbs2()\nmat1.cwiseAbs()\nmat1.cwiseSqrt()\nmat1.cwiseInverse()\nmat1.cwiseProduct(mat2)\nmat1.cwiseQuotient(mat2)\nmat1.cwiseEqual(mat2)       mat1.cwiseEqual(scalar)\nmat1.cwiseNotEqual(mat2)\n\\endcode\n</td><td>\\code\nmat1.array().min(mat2.array())    mat1.array().min(scalar)\nmat1.array().max(mat2.array())    mat1.array().max(scalar)\nmat1.array().abs2()\nmat1.array().abs()\nmat1.array().sqrt()\nmat1.array().inverse()\nmat1.array() * mat2.array()\nmat1.array() / mat2.array()\nmat1.array() == mat2.array()      mat1.array() == scalar\nmat1.array() != mat2.array()\n\\endcode</td></tr>\n</table>\nThe main difference between the two API is that the one based on cwise* methods returns an expression in the matrix world,\nwhile the second one (based on .array()) returns an array expression.\nRecall that .array() has no cost, it only changes the available API and interpretation of the data.\n\nIt is also very simple to apply any user defined function \\c foo using DenseBase::unaryExpr together with <a href=\"http://en.cppreference.com/w/cpp/utility/functional/ptr_fun\">std::ptr_fun</a> (c++03, deprecated or removed in newer C++ versions), <a href=\"http://en.cppreference.com/w/cpp/utility/functional/ref\">std::ref</a> (c++11), or <a href=\"http://en.cppreference.com/w/cpp/language/lambda\">lambdas</a> (c++11):\n\\code\nmat1.unaryExpr(std::ptr_fun(foo));\nmat1.unaryExpr(std::ref(foo));\nmat1.unaryExpr([](double x) { return foo(x); });\n\\endcode\n\nPlease note that it's not possible to pass a raw function pointer to \\c unaryExpr, so please warp it as shown above.\n\n<a href=\"#\" class=\"top\">top</a>\n\\section QuickRef_Reductions Reductions\n\nEigen provides several reduction methods such as:\n\\link DenseBase::minCoeff() minCoeff() \\endlink, \\link DenseBase::maxCoeff() maxCoeff() \\endlink,\n\\link DenseBase::sum() sum() \\endlink, \\link DenseBase::prod() prod() \\endlink,\n\\link MatrixBase::trace() trace() \\endlink \\matrixworld,\n\\link MatrixBase::norm() norm() \\endlink \\matrixworld, \\link MatrixBase::squaredNorm() squaredNorm() \\endlink \\matrixworld,\n\\link DenseBase::all() all() \\endlink, and \\link DenseBase::any() any() \\endlink.\nAll reduction operations can be done matrix-wise,\n\\link DenseBase::colwise() column-wise \\endlink or\n\\link DenseBase::rowwise() row-wise \\endlink. Usage example:\n<table class=\"manual\">\n<tr><td rowspan=\"3\" style=\"border-right-style:dashed;vertical-align:middle\">\\code\n      5 3 1\nmat = 2 7 8\n      9 4 6 \\endcode\n</td> <td>\\code mat.minCoeff(); \\endcode</td><td>\\code 1 \\endcode</td></tr>\n<tr class=\"alt\"><td>\\code mat.colwise().minCoeff(); \\endcode</td><td>\\code 2 3 1 \\endcode</td></tr>\n<tr style=\"vertical-align:middle\"><td>\\code mat.rowwise().minCoeff(); \\endcode</td><td>\\code\n1\n2\n4\n\\endcode</td></tr>\n</table>\n\nSpecial versions of \\link DenseBase::minCoeff(IndexType*,IndexType*) const minCoeff \\endlink and \\link DenseBase::maxCoeff(IndexType*,IndexType*) const maxCoeff \\endlink:\n\\code\nint i, j;\ns = vector.minCoeff(&i);        // s == vector[i]\ns = matrix.maxCoeff(&i, &j);    // s == matrix(i,j)\n\\endcode\nTypical use cases of all() and any():\n\\code\nif((array1 > 0).all()) ...      // if all coefficients of array1 are greater than 0 ...\nif((array1 < array2).any()) ... // if there exist a pair i,j such that array1(i,j) < array2(i,j) ...\n\\endcode\n\n\n<a href=\"#\" class=\"top\">top</a>\\section QuickRef_Blocks Sub-matrices\n\n<div class=\"warningbox\">\n<strong>PLEASE HELP US IMPROVING THIS SECTION.</strong>\n%Eigen 3.4 supports a much improved API for sub-matrices, including,\nslicing and indexing from arrays: \\ref TutorialSlicingIndexing\n</div>\n\nRead-write access to a \\link DenseBase::col(Index) column \\endlink\nor a \\link DenseBase::row(Index) row \\endlink of a matrix (or array):\n\\code\nmat1.row(i) = mat2.col(j);\nmat1.col(j1).swap(mat1.col(j2));\n\\endcode\n\nRead-write access to sub-vectors:\n<table class=\"manual\">\n<tr>\n<th>Default versions</th>\n<th>Optimized versions when the size \\n is known at compile time</th></tr>\n<th></th>\n\n<tr><td>\\code vec1.head(n)\\endcode</td><td>\\code vec1.head<n>()\\endcode</td><td>the first \\c n coeffs </td></tr>\n<tr><td>\\code vec1.tail(n)\\endcode</td><td>\\code vec1.tail<n>()\\endcode</td><td>the last \\c n coeffs </td></tr>\n<tr><td>\\code vec1.segment(pos,n)\\endcode</td><td>\\code vec1.segment<n>(pos)\\endcode</td>\n    <td>the \\c n coeffs in the \\n range [\\c pos : \\c pos + \\c n - 1]</td></tr>\n<tr class=\"alt\"><td colspan=\"3\">\n\nRead-write access to sub-matrices:</td></tr>\n<tr>\n  <td>\\code mat1.block(i,j,rows,cols)\\endcode\n      \\link DenseBase::block(Index,Index,Index,Index) (more) \\endlink</td>\n  <td>\\code mat1.block<rows,cols>(i,j)\\endcode\n      \\link DenseBase::block(Index,Index) (more) \\endlink</td>\n  <td>the \\c rows x \\c cols sub-matrix \\n starting from position (\\c i,\\c j)</td></tr>\n<tr><td>\\code\n mat1.topLeftCorner(rows,cols)\n mat1.topRightCorner(rows,cols)\n mat1.bottomLeftCorner(rows,cols)\n mat1.bottomRightCorner(rows,cols)\\endcode\n <td>\\code\n mat1.topLeftCorner<rows,cols>()\n mat1.topRightCorner<rows,cols>()\n mat1.bottomLeftCorner<rows,cols>()\n mat1.bottomRightCorner<rows,cols>()\\endcode\n <td>the \\c rows x \\c cols sub-matrix \\n taken in one of the four corners</td></tr>\n <tr><td>\\code\n mat1.topRows(rows)\n mat1.bottomRows(rows)\n mat1.leftCols(cols)\n mat1.rightCols(cols)\\endcode\n <td>\\code\n mat1.topRows<rows>()\n mat1.bottomRows<rows>()\n mat1.leftCols<cols>()\n mat1.rightCols<cols>()\\endcode\n <td>specialized versions of block() \\n when the block fit two corners</td></tr>\n</table>\n\n\n\n<a href=\"#\" class=\"top\">top</a>\\section QuickRef_Misc Miscellaneous operations\n\n<div class=\"warningbox\">\n<strong>PLEASE HELP US IMPROVING THIS SECTION.</strong>\n%Eigen 3.4 supports a new API for reshaping: \\ref TutorialReshape\n</div>\n\n\\subsection QuickRef_Reverse Reverse\nVectors, rows, and/or columns of a matrix can be reversed (see DenseBase::reverse(), DenseBase::reverseInPlace(), VectorwiseOp::reverse()).\n\\code\nvec.reverse()           mat.colwise().reverse()   mat.rowwise().reverse()\nvec.reverseInPlace()\n\\endcode\n\n\\subsection QuickRef_Replicate Replicate\nVectors, matrices, rows, and/or columns can be replicated in any direction (see DenseBase::replicate(), VectorwiseOp::replicate())\n\\code\nvec.replicate(times)                                          vec.replicate<Times>\nmat.replicate(vertical_times, horizontal_times)               mat.replicate<VerticalTimes, HorizontalTimes>()\nmat.colwise().replicate(vertical_times, horizontal_times)     mat.colwise().replicate<VerticalTimes, HorizontalTimes>()\nmat.rowwise().replicate(vertical_times, horizontal_times)     mat.rowwise().replicate<VerticalTimes, HorizontalTimes>()\n\\endcode\n\n\n<a href=\"#\" class=\"top\">top</a>\\section QuickRef_DiagTriSymm Diagonal, Triangular, and Self-adjoint matrices\n(matrix world \\matrixworld)\n\n\\subsection QuickRef_Diagonal Diagonal matrices\n\n<table class=\"example\">\n<tr><th>Operation</th><th>Code</th></tr>\n<tr><td>\nview a vector \\link MatrixBase::asDiagonal() as a diagonal matrix \\endlink \\n </td><td>\\code\nmat1 = vec1.asDiagonal();\\endcode\n</td></tr>\n<tr><td>\nDeclare a diagonal matrix</td><td>\\code\nDiagonalMatrix<Scalar,SizeAtCompileTime> diag1(size);\ndiag1.diagonal() = vector;\\endcode\n</td></tr>\n<tr><td>Access the \\link MatrixBase::diagonal() diagonal \\endlink and \\link MatrixBase::diagonal(Index) super/sub diagonals \\endlink of a matrix as a vector (read/write)</td>\n <td>\\code\nvec1 = mat1.diagonal();        mat1.diagonal() = vec1;      // main diagonal\nvec1 = mat1.diagonal(+n);      mat1.diagonal(+n) = vec1;    // n-th super diagonal\nvec1 = mat1.diagonal(-n);      mat1.diagonal(-n) = vec1;    // n-th sub diagonal\nvec1 = mat1.diagonal<1>();     mat1.diagonal<1>() = vec1;   // first super diagonal\nvec1 = mat1.diagonal<-2>();    mat1.diagonal<-2>() = vec1;  // second sub diagonal\n\\endcode</td>\n</tr>\n\n<tr><td>Optimized products and inverse</td>\n <td>\\code\nmat3  = scalar * diag1 * mat1;\nmat3 += scalar * mat1 * vec1.asDiagonal();\nmat3 = vec1.asDiagonal().inverse() * mat1\nmat3 = mat1 * diag1.inverse()\n\\endcode</td>\n</tr>\n\n</table>\n\n\\subsection QuickRef_TriangularView Triangular views\n\nTriangularView gives a view on a triangular part of a dense matrix and allows to perform optimized operations on it. The opposite triangular part is never referenced and can be used to store other information.\n\n\\note The .triangularView() template member function requires the \\c template keyword if it is used on an\nobject of a type that depends on a template parameter; see \\ref TopicTemplateKeyword for details.\n\n<table class=\"example\">\n<tr><th>Operation</th><th>Code</th></tr>\n<tr><td>\nReference to a triangular with optional \\n\nunit or null diagonal (read/write):\n</td><td>\\code\nm.triangularView<Xxx>()\n\\endcode \\n\n\\c Xxx = ::Upper, ::Lower, ::StrictlyUpper, ::StrictlyLower, ::UnitUpper, ::UnitLower\n</td></tr>\n<tr><td>\nWriting to a specific triangular part:\\n (only the referenced triangular part is evaluated)\n</td><td>\\code\nm1.triangularView<Eigen::Lower>() = m2 + m3 \\endcode\n</td></tr>\n<tr><td>\nConversion to a dense matrix setting the opposite triangular part to zero:\n</td><td>\\code\nm2 = m1.triangularView<Eigen::UnitUpper>()\\endcode\n</td></tr>\n<tr><td>\nProducts:\n</td><td>\\code\nm3 += s1 * m1.adjoint().triangularView<Eigen::UnitUpper>() * m2\nm3 -= s1 * m2.conjugate() * m1.adjoint().triangularView<Eigen::Lower>() \\endcode\n</td></tr>\n<tr><td>\nSolving linear equations:\\n\n\\f$ M_2 := L_1^{-1} M_2 \\f$ \\n\n\\f$ M_3 := {L_1^*}^{-1} M_3 \\f$ \\n\n\\f$ M_4 := M_4 U_1^{-1} \\f$\n</td><td>\\n \\code\nL1.triangularView<Eigen::UnitLower>().solveInPlace(M2)\nL1.triangularView<Eigen::Lower>().adjoint().solveInPlace(M3)\nU1.triangularView<Eigen::Upper>().solveInPlace<OnTheRight>(M4)\\endcode\n</td></tr>\n</table>\n\n\\subsection QuickRef_SelfadjointMatrix Symmetric/selfadjoint views\n\nJust as for triangular matrix, you can reference any triangular part of a square matrix to see it as a selfadjoint\nmatrix and perform special and optimized operations. Again the opposite triangular part is never referenced and can be\nused to store other information.\n\n\\note The .selfadjointView() template member function requires the \\c template keyword if it is used on an\nobject of a type that depends on a template parameter; see \\ref TopicTemplateKeyword for details.\n\n<table class=\"example\">\n<tr><th>Operation</th><th>Code</th></tr>\n<tr><td>\nConversion to a dense matrix:\n</td><td>\\code\nm2 = m.selfadjointView<Eigen::Lower>();\\endcode\n</td></tr>\n<tr><td>\nProduct with another general matrix or vector:\n</td><td>\\code\nm3  = s1 * m1.conjugate().selfadjointView<Eigen::Upper>() * m3;\nm3 -= s1 * m3.adjoint() * m1.selfadjointView<Eigen::Lower>();\\endcode\n</td></tr>\n<tr><td>\nRank 1 and rank K update: \\n\n\\f$ upper(M_1) \\mathrel{{+}{=}} s_1 M_2 M_2^* \\f$ \\n\n\\f$ lower(M_1) \\mathbin{{-}{=}} M_2^* M_2 \\f$\n</td><td>\\n \\code\nM1.selfadjointView<Eigen::Upper>().rankUpdate(M2,s1);\nM1.selfadjointView<Eigen::Lower>().rankUpdate(M2.adjoint(),-1); \\endcode\n</td></tr>\n<tr><td>\nRank 2 update: (\\f$ M \\mathrel{{+}{=}} s u v^* + s v u^* \\f$)\n</td><td>\\code\nM.selfadjointView<Eigen::Upper>().rankUpdate(u,v,s);\n\\endcode\n</td></tr>\n<tr><td>\nSolving linear equations:\\n(\\f$ M_2 := M_1^{-1} M_2 \\f$)\n</td><td>\\code\n// via a standard Cholesky factorization\nm2 = m1.selfadjointView<Eigen::Upper>().llt().solve(m2);\n// via a Cholesky factorization with pivoting\nm2 = m1.selfadjointView<Eigen::Lower>().ldlt().solve(m2);\n\\endcode\n</td></tr>\n</table>\n\n*/\n\n/*\n<table class=\"tutorial_code\">\n<tr><td>\n\\link MatrixBase::asDiagonal() make a diagonal matrix \\endlink \\n from a vector </td><td>\\code\nmat1 = vec1.asDiagonal();\\endcode\n</td></tr>\n<tr><td>\nDeclare a diagonal matrix</td><td>\\code\nDiagonalMatrix<Scalar,SizeAtCompileTime> diag1(size);\ndiag1.diagonal() = vector;\\endcode\n</td></tr>\n<tr><td>Access \\link MatrixBase::diagonal() the diagonal and super/sub diagonals of a matrix \\endlink as a vector (read/write)</td>\n <td>\\code\nvec1 = mat1.diagonal();            mat1.diagonal() = vec1;      // main diagonal\nvec1 = mat1.diagonal(+n);          mat1.diagonal(+n) = vec1;    // n-th super diagonal\nvec1 = mat1.diagonal(-n);          mat1.diagonal(-n) = vec1;    // n-th sub diagonal\nvec1 = mat1.diagonal<1>();         mat1.diagonal<1>() = vec1;   // first super diagonal\nvec1 = mat1.diagonal<-2>();        mat1.diagonal<-2>() = vec1;  // second sub diagonal\n\\endcode</td>\n</tr>\n\n<tr><td>View on a triangular part of a matrix (read/write)</td>\n <td>\\code\nmat2 = mat1.triangularView<Xxx>();\n// Xxx = Upper, Lower, StrictlyUpper, StrictlyLower, UnitUpper, UnitLower\nmat1.triangularView<Upper>() = mat2 + mat3; // only the upper part is evaluated and referenced\n\\endcode</td></tr>\n\n<tr><td>View a triangular part as a symmetric/self-adjoint matrix (read/write)</td>\n <td>\\code\nmat2 = mat1.selfadjointView<Xxx>();     // Xxx = Upper or Lower\nmat1.selfadjointView<Upper>() = mat2 + mat2.adjoint();  // evaluated and write to the upper triangular part only\n\\endcode</td></tr>\n\n</table>\n\nOptimized products:\n\\code\nmat3 += scalar * vec1.asDiagonal() * mat1\nmat3 += scalar * mat1 * vec1.asDiagonal()\nmat3.noalias() += scalar * mat1.triangularView<Xxx>() * mat2\nmat3.noalias() += scalar * mat2 * mat1.triangularView<Xxx>()\nmat3.noalias() += scalar * mat1.selfadjointView<Upper or Lower>() * mat2\nmat3.noalias() += scalar * mat2 * mat1.selfadjointView<Upper or Lower>()\nmat1.selfadjointView<Upper or Lower>().rankUpdate(mat2);\nmat1.selfadjointView<Upper or Lower>().rankUpdate(mat2.adjoint(), scalar);\n\\endcode\n\nInverse products: (all are optimized)\n\\code\nmat3 = vec1.asDiagonal().inverse() * mat1\nmat3 = mat1 * diag1.inverse()\nmat1.triangularView<Xxx>().solveInPlace(mat2)\nmat1.triangularView<Xxx>().solveInPlace<OnTheRight>(mat2)\nmat2 = mat1.selfadjointView<Upper or Lower>().llt().solve(mat2)\n\\endcode\n\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/QuickStartGuide.dox",
    "content": "namespace Eigen {\n\n/** \\page GettingStarted Getting started\n\n\\eigenAutoToc\n\nThis is a very short guide on how to get started with Eigen. It has a dual purpose. It serves as a minimal introduction to the Eigen library for people who want to start coding as soon as possible. You can also read this page as the first part of the Tutorial, which explains the library in more detail; in this case you will continue with \\ref TutorialMatrixClass.\n\n\\section GettingStartedInstallation How to \"install\" Eigen?\n\nIn order to use Eigen, you just need to download and extract Eigen's source code (see <a href=\"http://eigen.tuxfamily.org/index.php?title=Main_Page#Download\">the wiki</a> for download instructions). In fact, the header files in the \\c Eigen subdirectory are the only files required to compile programs using Eigen. The header files are the same for all platforms. It is not necessary to use CMake or install anything.\n\n\n\\section GettingStartedFirstProgram A simple first program\n\nHere is a rather simple program to get you started.\n\n\\include QuickStart_example.cpp\n\nWe will explain the program after telling you how to compile it.\n\n\n\\section GettingStartedCompiling Compiling and running your first program\n\nThere is no library to link to. The only thing that you need to keep in mind when compiling the above program is that the compiler must be able to find the Eigen header files. The directory in which you placed Eigen's source code must be in the include path. With GCC you use the \\c -I option to achieve this, so you can compile the program with a command like this:\n\n\\code g++ -I /path/to/eigen/ my_program.cpp -o my_program \\endcode\n\nOn Linux or Mac OS X, another option is to symlink or copy the Eigen folder into \\c /usr/local/include/. This way, you can compile the program with:\n\n\\code g++ my_program.cpp -o my_program \\endcode\n\nWhen you run the program, it produces the following output:\n\n\\include QuickStart_example.out\n\n\n\\section GettingStartedExplanation Explanation of the first program\n\nThe Eigen header files define many types, but for simple applications it may be enough to use only the \\c MatrixXd type. This represents a matrix of arbitrary size (hence the \\c X in \\c MatrixXd), in which every entry is a \\c double (hence the \\c d in \\c MatrixXd). See the \\ref QuickRef_Types \"quick reference guide\" for an overview of the different types you can use to represent a matrix.\n\nThe \\c Eigen/Dense header file defines all member functions for the MatrixXd type and related types (see also the \\ref QuickRef_Headers \"table of header files\"). All classes and functions defined in this header file (and other Eigen header files) are in the \\c Eigen namespace. \n\nThe first line of the \\c main function declares a variable of type \\c MatrixXd and specifies that it is a matrix with 2 rows and 2 columns (the entries are not initialized). The statement <tt>m(0,0) = 3</tt> sets the entry in the top-left corner to 3. You need to use round parentheses to refer to entries in the matrix. As usual in computer science, the index of the first index is 0, as opposed to the convention in mathematics that the first index is 1.\n\nThe following three statements sets the other three entries. The final line outputs the matrix \\c m to the standard output stream.\n\n\n\\section GettingStartedExample2 Example 2: Matrices and vectors\n\nHere is another example, which combines matrices with vectors. Concentrate on the left-hand program for now; we will talk about the right-hand program later.\n\n<table class=\"manual\">\n<tr><th>Size set at run time:</th><th>Size set at compile time:</th></tr>\n<tr><td>\n\\include QuickStart_example2_dynamic.cpp\n</td>\n<td>\n\\include QuickStart_example2_fixed.cpp\n</td></tr></table>\n\nThe output is as follows:\n\n\\include QuickStart_example2_dynamic.out\n\n\n\\section GettingStartedExplanation2 Explanation of the second example\n\nThe second example starts by declaring a 3-by-3 matrix \\c m which is initialized using the \\link DenseBase::Random(Index,Index) Random() \\endlink method with random values between -1 and 1. The next line applies a linear mapping such that the values are between 10 and 110. The function call \\link DenseBase::Constant(Index,Index,const Scalar&) MatrixXd::Constant\\endlink(3,3,1.2) returns a 3-by-3 matrix expression having all coefficients equal to 1.2. The rest is standard arithmetic.\n\nThe next line of the \\c main function introduces a new type: \\c VectorXd. This represents a (column) vector of arbitrary size. Here, the vector \\c v is created to contain \\c 3 coefficients which are left uninitialized. The one but last line uses the so-called comma-initializer, explained in \\ref TutorialAdvancedInitialization, to set all coefficients of the vector \\c v to be as follows:\n\n\\f[\nv =\n\\begin{bmatrix}\n  1 \\\\\n  2 \\\\\n  3\n\\end{bmatrix}.\n\\f]\n\nThe final line of the program multiplies the matrix \\c m with the vector \\c v and outputs the result.\n\nNow look back at the second example program. We presented two versions of it. In the version in the left column, the matrix is of type \\c MatrixXd which represents matrices of arbitrary size. The version in the right column is similar, except that the matrix is of type \\c Matrix3d, which represents matrices of a fixed size (here 3-by-3). Because the type already encodes the size of the matrix, it is not necessary to specify the size in the constructor; compare <tt>MatrixXd m(3,3)</tt> with <tt>Matrix3d m</tt>. Similarly, we have \\c VectorXd on the left (arbitrary size) versus \\c Vector3d on the right (fixed size). Note that here the coefficients of vector \\c v are directly set in the constructor, though the same syntax of the left example could be used too.\n\nThe use of fixed-size matrices and vectors has two advantages. The compiler emits better (faster) code because it knows the size of the matrices and vectors. Specifying the size in the type also allows for more rigorous checking at compile-time. For instance, the compiler will complain if you try to multiply a \\c Matrix4d (a 4-by-4 matrix) with a \\c Vector3d (a vector of size 3). However, the use of many types increases compilation time and the size of the executable. The size of the matrix may also not be known at compile-time. A rule of thumb is to use fixed-size matrices for size 4-by-4 and smaller.\n\n\n\\section GettingStartedConclusion Where to go from here?\n\nIt's worth taking the time to read the  \\ref TutorialMatrixClass \"long tutorial\".\n\nHowever if you think you don't need it, you can directly use the classes documentation and our \\ref QuickRefPage.\n\n\\li \\b Next: \\ref TutorialMatrixClass\n\n*/\n\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/SparseLinearSystems.dox",
    "content": "namespace Eigen {\n/** \\eigenManualPage TopicSparseSystems Solving Sparse Linear Systems\nIn Eigen, there are several methods available to solve linear systems when the coefficient matrix is sparse. Because of the special representation of this class of matrices, special care should be taken in order to get a good performance. See \\ref TutorialSparse for a detailed introduction about sparse matrices in Eigen. This page lists the sparse solvers available in Eigen. The main steps that are common to all these linear solvers are introduced as well. Depending on the properties of the matrix, the desired accuracy, the end-user is able to tune those steps in order to improve the performance of its code. Note that it is not required to know deeply what's hiding behind these steps: the last section presents a benchmark routine that can be easily used to get an insight on the performance of all the available solvers. \n\n\\eigenAutoToc\n\n\\section TutorialSparseSolverList List of sparse solvers\n\n%Eigen currently provides a wide set of built-in solvers, as well as wrappers to external solver libraries.\nThey are summarized in the following tables:\n\n\\subsection TutorialSparseSolverList_Direct Built-in direct solvers\n\n<table class=\"manual\">\n<tr><th>Class</th><th>Solver kind</th><th>Matrix kind</th><th>Features related to performance</th>\n    <th>License</th><th class=\"width20em\"><p>Notes</p></th></tr>\n\n<tr><td>SimplicialLLT \\n <tt>\\#include<Eigen/\\link SparseCholesky_Module SparseCholesky\\endlink></tt></td><td>Direct LLt factorization</td><td>SPD</td><td>Fill-in reducing</td>\n    <td>LGPL</td>\n    <td>SimplicialLDLT is often preferable</td></tr>\n\n<tr><td>SimplicialLDLT \\n <tt>\\#include<Eigen/\\link SparseCholesky_Module SparseCholesky\\endlink></tt></td><td>Direct LDLt factorization</td><td>SPD</td><td>Fill-in reducing</td>\n    <td>LGPL</td>\n    <td>Recommended for very sparse and not too large problems (e.g., 2D Poisson eq.)</td></tr>\n\n<tr><td>SparseLU \\n <tt>\\#include<Eigen/\\link SparseLU_Module SparseLU\\endlink></tt></td> <td>LU factorization </td>\n    <td>Square </td><td>Fill-in reducing, Leverage fast dense algebra</td>\n    <td>MPL2</td>\n    <td>optimized for small and large problems with irregular patterns </td></tr>\n\n<tr><td>SparseQR \\n <tt>\\#include<Eigen/\\link SparseQR_Module SparseQR\\endlink></tt></td> <td> QR factorization</td>\n    <td>Any, rectangular</td><td> Fill-in reducing</td>\n    <td>MPL2</td>\n    <td>recommended for least-square problems, has a basic rank-revealing feature</td></tr>\n </table>\n\n\\subsection TutorialSparseSolverList_Iterative Built-in iterative solvers\n\n<table class=\"manual\">\n<tr><th>Class</th><th>Solver kind</th><th>Matrix kind</th><th>Supported preconditioners, [default]</th>\n    <th>License</th><th class=\"width20em\"><p>Notes</p></th></tr>\n\n<tr><td>ConjugateGradient \\n <tt>\\#include<Eigen/\\link IterativeLinearSolvers_Module IterativeLinearSolvers\\endlink></tt></td> <td>Classic iterative CG</td><td>SPD</td>\n    <td>IdentityPreconditioner, [DiagonalPreconditioner], IncompleteCholesky</td>\n    <td>MPL2</td>\n    <td>Recommended for large symmetric problems (e.g., 3D Poisson eq.)</td></tr>\n\n<tr><td>LeastSquaresConjugateGradient \\n <tt>\\#include<Eigen/\\link IterativeLinearSolvers_Module IterativeLinearSolvers\\endlink></tt></td><td>CG for rectangular least-square problem</td><td>Rectangular</td>\n    <td>IdentityPreconditioner, [LeastSquareDiagonalPreconditioner]</td>\n    <td>MPL2</td>\n    <td>Solve for min |A'Ax-b|^2 without forming A'A</td></tr>\n\n<tr><td>BiCGSTAB \\n <tt>\\#include<Eigen/\\link IterativeLinearSolvers_Module IterativeLinearSolvers\\endlink></tt></td><td>Iterative stabilized bi-conjugate gradient</td><td>Square</td>\n    <td>IdentityPreconditioner, [DiagonalPreconditioner], IncompleteLUT</td>\n    <td>MPL2</td>\n    <td>To speedup the convergence, try it with the \\ref IncompleteLUT preconditioner.</td></tr>\n</table>\n\n\\subsection TutorialSparseSolverList_Wrapper Wrappers to external solvers\n\n<table class=\"manual\">\n<tr><th>Class</th><th>Module</th><th>Solver kind</th><th>Matrix kind</th><th>Features related to performance</th>\n    <th>Dependencies,License</th><th class=\"width20em\"><p>Notes</p></th></tr>\n<tr><td>PastixLLT \\n PastixLDLT \\n PastixLU</td><td>\\link PaStiXSupport_Module PaStiXSupport \\endlink</td><td>Direct LLt, LDLt, LU factorizations</td><td>SPD \\n SPD \\n Square</td><td>Fill-in reducing, Leverage fast dense algebra, Multithreading</td>\n    <td>Requires the <a href=\"http://pastix.gforge.inria.fr\">PaStiX</a> package, \\b CeCILL-C </td>\n    <td>optimized for tough problems and symmetric patterns</td></tr>\n<tr><td>CholmodSupernodalLLT</td><td>\\link CholmodSupport_Module CholmodSupport \\endlink</td><td>Direct LLt factorization</td><td>SPD</td><td>Fill-in reducing, Leverage fast dense algebra</td>\n    <td>Requires the <a href=\"http://www.suitesparse.com\">SuiteSparse</a> package, \\b GPL </td>\n    <td></td></tr>\n<tr><td>UmfPackLU</td><td>\\link UmfPackSupport_Module UmfPackSupport \\endlink</td><td>Direct LU factorization</td><td>Square</td><td>Fill-in reducing, Leverage fast dense algebra</td>\n    <td>Requires the <a href=\"http://www.suitesparse.com\">SuiteSparse</a> package, \\b GPL </td>\n    <td></td></tr>\n<tr><td>KLU</td><td>\\link KLUSupport_Module KLUSupport \\endlink</td><td>Direct LU factorization</td><td>Square</td><td>Fill-in reducing, suitted for circuit simulation</td>\n    <td>Requires the <a href=\"http://www.suitesparse.com\">SuiteSparse</a> package, \\b GPL </td>\n    <td></td></tr>\n<tr><td>SuperLU</td><td>\\link SuperLUSupport_Module SuperLUSupport \\endlink</td><td>Direct LU factorization</td><td>Square</td><td>Fill-in reducing, Leverage fast dense algebra</td>\n    <td>Requires the <a href=\"http://crd-legacy.lbl.gov/~xiaoye/SuperLU/\">SuperLU</a> library, (BSD-like)</td>\n    <td></td></tr>\n<tr><td>SPQR</td><td>\\link SPQRSupport_Module SPQRSupport \\endlink  </td> <td> QR factorization </td> \n    <td> Any, rectangular</td><td>fill-in reducing, multithreaded, fast dense algebra</td>\n    <td> requires the <a href=\"http://www.suitesparse.com\">SuiteSparse</a> package, \\b GPL </td><td>recommended for linear least-squares problems, has a rank-revealing feature</tr>\n<tr><td>PardisoLLT \\n PardisoLDLT \\n PardisoLU</td><td>\\link PardisoSupport_Module PardisoSupport \\endlink</td><td>Direct LLt, LDLt, LU factorizations</td><td>SPD \\n SPD \\n Square</td><td>Fill-in reducing, Leverage fast dense algebra, Multithreading</td>\n    <td>Requires the <a href=\"http://eigen.tuxfamily.org/Counter/redirect_to_mkl.php\">Intel MKL</a> package, \\b Proprietary </td>\n    <td>optimized for tough problems patterns, see also \\link TopicUsingIntelMKL using MKL with Eigen \\endlink</td></tr>\n</table>\n\nHere \\c SPD means symmetric positive definite.\n\n\\section TutorialSparseSolverConcept Sparse solver concept\n\nAll these solvers follow the same general concept.\nHere is a typical and general example:\n\\code\n#include <Eigen/RequiredModuleName>\n// ...\nSparseMatrix<double> A;\n// fill A\nVectorXd b, x;\n// fill b\n// solve Ax = b\nSolverClassName<SparseMatrix<double> > solver;\nsolver.compute(A);\nif(solver.info()!=Success) {\n  // decomposition failed\n  return;\n}\nx = solver.solve(b);\nif(solver.info()!=Success) {\n  // solving failed\n  return;\n}\n// solve for another right hand side:\nx1 = solver.solve(b1);\n\\endcode\n\nFor \\c SPD solvers, a second optional template argument allows to specify which triangular part have to be used, e.g.:\n\n\\code\n#include <Eigen/IterativeLinearSolvers>\n\nConjugateGradient<SparseMatrix<double>, Eigen::Upper> solver;\nx = solver.compute(A).solve(b);\n\\endcode\nIn the above example, only the upper triangular part of the input matrix A is considered for solving. The opposite triangle might either be empty or contain arbitrary values.\n\nIn the case where multiple problems with the same sparsity pattern have to be solved, then the \"compute\" step can be decomposed as follow:\n\\code\nSolverClassName<SparseMatrix<double> > solver;\nsolver.analyzePattern(A);   // for this step the numerical values of A are not used\nsolver.factorize(A);\nx1 = solver.solve(b1);\nx2 = solver.solve(b2);\n...\nA = ...;                    // modify the values of the nonzeros of A, the nonzeros pattern must stay unchanged\nsolver.factorize(A);\nx1 = solver.solve(b1);\nx2 = solver.solve(b2);\n...\n\\endcode\nThe `compute()` method is equivalent to calling both `analyzePattern()` and `factorize()`.\n\nEach solver provides some specific features, such as determinant, access to the factors, controls of the iterations, and so on.\nMore details are available in the documentations of the respective classes.\n\nFinally, most of the iterative solvers, can also be used in a \\b matrix-free context, see the following \\link MatrixfreeSolverExample example \\endlink.\n\n\\section TheSparseCompute The Compute Step\nIn the `compute()` function, the matrix is generally factorized: LLT for self-adjoint matrices, LDLT for general hermitian matrices, LU for non hermitian matrices and QR for rectangular matrices. These are the results of using direct solvers. For this class of solvers precisely, the compute step is further subdivided into `analyzePattern()` and `factorize()`. \n\nThe goal of `analyzePattern()` is to reorder the nonzero elements of the matrix, such that the factorization step creates less fill-in. This step exploits only the structure of the matrix. Hence, the results of this step can be used for other linear systems where the matrix has the same structure. Note however that sometimes, some external solvers (like SuperLU) require that the values of the matrix are set in this step, for instance to equilibrate the rows and columns of the matrix. In this situation, the results of this step should not be used with other matrices.\n\nEigen provides a limited set of methods to reorder the matrix in this step, either built-in (COLAMD, AMD) or external (METIS). These methods are set in template parameter list of the solver :\n\\code\nDirectSolverClassName<SparseMatrix<double>, OrderingMethod<IndexType> > solver;\n\\endcode \n\nSee the \\link OrderingMethods_Module OrderingMethods module \\endlink for the list of available methods and the associated options. \n\nIn `factorize()`, the factors of the coefficient matrix are computed. This step should be called each time the values of the matrix change. However, the structural pattern of the matrix should not change between multiple calls. \n\nFor iterative solvers, the compute step is used to eventually setup a preconditioner. For instance, with the ILUT preconditioner, the incomplete factors L and U are computed in this step. Remember that, basically, the goal of the preconditioner is to speedup the convergence of an iterative method by solving a modified linear system where the coefficient matrix has more clustered eigenvalues. For real problems, an iterative solver should always be used with a preconditioner. In Eigen, a preconditioner is  selected by simply adding it as a template parameter to the iterative solver object. \n\\code\nIterativeSolverClassName<SparseMatrix<double>, PreconditionerName<SparseMatrix<double> > solver; \n\\endcode\nThe member function `preconditioner()` returns a read-write reference to the preconditioner \n to directly interact with it. See the \\link IterativeLinearSolvers_Module Iterative solvers module \\endlink and the documentation of each class for the list of available methods.\n\n\\section TheSparseSolve The Solve step\nThe `solve()` function computes the solution of the linear systems with one or many right hand sides.\n\\code\nX = solver.solve(B);\n\\endcode \nHere, B  can be a vector or a matrix where the columns form the different right hand sides. `The solve()` function can be called several times as well, for instance when all the right hand sides are not available at once. \n\\code\nx1 = solver.solve(b1);\n// Get the second right hand side b2\nx2 = solver.solve(b2); \n//  ...\n\\endcode\nFor direct methods, the solution are computed at the machine precision. Sometimes, the solution need not be too accurate. In this case, the iterative methods are more suitable and the desired accuracy can be set before the solve step using \\b setTolerance(). For all the available functions, please, refer to the documentation of the \\link IterativeLinearSolvers_Module Iterative solvers module \\endlink. \n\n\\section BenchmarkRoutine\nMost of the time, all you need is to know how much time it will take to solve your system, and hopefully, what is the most suitable solver. In Eigen, we provide a benchmark routine that can be used for this purpose. It is very easy to use. In the build directory, navigate to `bench/spbench` and compile the routine by typing `make spbenchsolver`. Run it with `--help` option to get the list of all available options. Basically, the matrices to test should be in <a href=\"http://math.nist.gov/MatrixMarket/formats.html\">MatrixMarket Coordinate format</a>, and the routine returns the statistics from all available solvers in Eigen.\n\nTo export your matrices and right-hand-side vectors in the matrix-market format, you can the the unsupported SparseExtra module:\n\\code\n#include <unsupported/Eigen/SparseExtra>\n...\nEigen::saveMarket(A, \"filename.mtx\");\nEigen::saveMarket(A, \"filename_SPD.mtx\", Eigen::Symmetric); // if A is symmetric-positive-definite\nEigen::saveMarketVector(B, \"filename_b.mtx\");\n\\endcode\n\nThe following table gives an example of XML statistics from several Eigen built-in and external solvers. \n<TABLE border=\"1\">\n <TR><TH>Matrix <TH> N <TH> NNZ <TH>  <TH > UMFPACK <TH > SUPERLU <TH > PASTIX LU <TH >BiCGSTAB <TH > BiCGSTAB+ILUT <TH >GMRES+ILUT<TH > LDLT <TH> CHOLMOD LDLT <TH > PASTIX LDLT <TH > LLT <TH > CHOLMOD SP LLT <TH > CHOLMOD LLT <TH > PASTIX LLT <TH> CG</TR>\n<TR><TH rowspan=\"4\">vector_graphics <TD rowspan=\"4\"> 12855 <TD rowspan=\"4\"> 72069 <TH>Compute Time <TD>0.0254549<TD>0.0215677<TD>0.0701827<TD>0.000153388<TD>0.0140107<TD>0.0153709<TD>0.0101601<TD style=\"background-color:red\">0.00930502<TD>0.0649689\n<TR><TH>Solve Time <TD>0.00337835<TD>0.000951826<TD>0.00484373<TD>0.0374886<TD>0.0046445<TD>0.00847754<TD>0.000541813<TD style=\"background-color:red\">0.000293696<TD>0.00485376\n<TR><TH>Total Time <TD>0.0288333<TD>0.0225195<TD>0.0750265<TD>0.037642<TD>0.0186552<TD>0.0238484<TD>0.0107019<TD style=\"background-color:red\">0.00959871<TD>0.0698227\n<TR><TH>Error(Iter) <TD> 1.299e-16 <TD> 2.04207e-16 <TD> 4.83393e-15 <TD> 3.94856e-11 (80)  <TD> 1.03861e-12 (3)  <TD> 5.81088e-14 (6)  <TD> 1.97578e-16 <TD> 1.83927e-16 <TD> 4.24115e-15\n<TR><TH rowspan=\"4\">poisson_SPD <TD rowspan=\"4\"> 19788 <TD rowspan=\"4\"> 308232 <TH>Compute Time <TD>0.425026<TD>1.82378<TD>0.617367<TD>0.000478921<TD>1.34001<TD>1.33471<TD>0.796419<TD>0.857573<TD>0.473007<TD>0.814826<TD style=\"background-color:red\">0.184719<TD>0.861555<TD>0.470559<TD>0.000458188\n<TR><TH>Solve Time <TD>0.0280053<TD>0.0194402<TD>0.0268747<TD>0.249437<TD>0.0548444<TD>0.0926991<TD>0.00850204<TD>0.0053171<TD>0.0258932<TD>0.00874603<TD style=\"background-color:red\">0.00578155<TD>0.00530361<TD>0.0248942<TD>0.239093\n<TR><TH>Total Time <TD>0.453031<TD>1.84322<TD>0.644241<TD>0.249916<TD>1.39486<TD>1.42741<TD>0.804921<TD>0.862891<TD>0.4989<TD>0.823572<TD style=\"background-color:red\">0.190501<TD>0.866859<TD>0.495453<TD>0.239551\n<TR><TH>Error(Iter) <TD> 4.67146e-16 <TD> 1.068e-15 <TD> 1.3397e-15 <TD> 6.29233e-11 (201)  <TD> 3.68527e-11 (6)  <TD> 3.3168e-15 (16)  <TD> 1.86376e-15 <TD> 1.31518e-16 <TD> 1.42593e-15 <TD> 3.45361e-15 <TD> 3.14575e-16 <TD> 2.21723e-15 <TD> 7.21058e-16 <TD> 9.06435e-12 (261) \n<TR><TH rowspan=\"4\">sherman2 <TD rowspan=\"4\"> 1080 <TD rowspan=\"4\"> 23094 <TH>Compute Time <TD style=\"background-color:red\">0.00631754<TD>0.015052<TD>0.0247514 <TD> -<TD>0.0214425<TD>0.0217988\n<TR><TH>Solve Time <TD style=\"background-color:red\">0.000478424<TD>0.000337998<TD>0.0010291 <TD> -<TD>0.00243152<TD>0.00246152\n<TR><TH>Total Time <TD style=\"background-color:red\">0.00679597<TD>0.01539<TD>0.0257805 <TD> -<TD>0.023874<TD>0.0242603\n<TR><TH>Error(Iter) <TD> 1.83099e-15 <TD> 8.19351e-15 <TD> 2.625e-14 <TD> 1.3678e+69 (1080)  <TD> 4.1911e-12 (7)  <TD> 5.0299e-13 (12) \n<TR><TH rowspan=\"4\">bcsstk01_SPD <TD rowspan=\"4\"> 48 <TD rowspan=\"4\"> 400 <TH>Compute Time <TD>0.000169079<TD>0.00010789<TD>0.000572538<TD>1.425e-06<TD>9.1612e-05<TD>8.3985e-05<TD style=\"background-color:red\">5.6489e-05<TD>7.0913e-05<TD>0.000468251<TD>5.7389e-05<TD>8.0212e-05<TD>5.8394e-05<TD>0.000463017<TD>1.333e-06\n<TR><TH>Solve Time <TD>1.2288e-05<TD>1.1124e-05<TD>0.000286387<TD>8.5896e-05<TD>1.6381e-05<TD>1.6984e-05<TD style=\"background-color:red\">3.095e-06<TD>4.115e-06<TD>0.000325438<TD>3.504e-06<TD>7.369e-06<TD>3.454e-06<TD>0.000294095<TD>6.0516e-05\n<TR><TH>Total Time <TD>0.000181367<TD>0.000119014<TD>0.000858925<TD>8.7321e-05<TD>0.000107993<TD>0.000100969<TD style=\"background-color:red\">5.9584e-05<TD>7.5028e-05<TD>0.000793689<TD>6.0893e-05<TD>8.7581e-05<TD>6.1848e-05<TD>0.000757112<TD>6.1849e-05\n<TR><TH>Error(Iter) <TD> 1.03474e-16 <TD> 2.23046e-16 <TD> 2.01273e-16 <TD> 4.87455e-07 (48)  <TD> 1.03553e-16 (2)  <TD> 3.55965e-16 (2)  <TD> 2.48189e-16 <TD> 1.88808e-16 <TD> 1.97976e-16 <TD> 2.37248e-16 <TD> 1.82701e-16 <TD> 2.71474e-16 <TD> 2.11322e-16 <TD> 3.547e-09 (48) \n<TR><TH rowspan=\"4\">sherman1 <TD rowspan=\"4\"> 1000 <TD rowspan=\"4\"> 3750 <TH>Compute Time <TD>0.00228805<TD>0.00209231<TD>0.00528268<TD>9.846e-06<TD>0.00163522<TD>0.00162155<TD>0.000789259<TD style=\"background-color:red\">0.000804495<TD>0.00438269\n<TR><TH>Solve Time <TD>0.000213788<TD>9.7983e-05<TD>0.000938831<TD>0.00629835<TD>0.000361764<TD>0.00078794<TD>4.3989e-05<TD style=\"background-color:red\">2.5331e-05<TD>0.000917166\n<TR><TH>Total Time <TD>0.00250184<TD>0.00219029<TD>0.00622151<TD>0.0063082<TD>0.00199698<TD>0.00240949<TD>0.000833248<TD style=\"background-color:red\">0.000829826<TD>0.00529986\n<TR><TH>Error(Iter) <TD> 1.16839e-16 <TD> 2.25968e-16 <TD> 2.59116e-16 <TD> 3.76779e-11 (248)  <TD> 4.13343e-11 (4)  <TD> 2.22347e-14 (10)  <TD> 2.05861e-16 <TD> 1.83555e-16 <TD> 1.02917e-15\n<TR><TH rowspan=\"4\">young1c <TD rowspan=\"4\"> 841 <TD rowspan=\"4\"> 4089 <TH>Compute Time <TD>0.00235843<TD style=\"background-color:red\">0.00217228<TD>0.00568075<TD>1.2735e-05<TD>0.00264866<TD>0.00258236\n<TR><TH>Solve Time <TD>0.000329599<TD style=\"background-color:red\">0.000168634<TD>0.00080118<TD>0.0534738<TD>0.00187193<TD>0.00450211\n<TR><TH>Total Time <TD>0.00268803<TD style=\"background-color:red\">0.00234091<TD>0.00648193<TD>0.0534865<TD>0.00452059<TD>0.00708447\n<TR><TH>Error(Iter) <TD> 1.27029e-16 <TD> 2.81321e-16 <TD> 5.0492e-15 <TD> 8.0507e-11 (706)  <TD> 3.00447e-12 (8)  <TD> 1.46532e-12 (16) \n<TR><TH rowspan=\"4\">mhd1280b <TD rowspan=\"4\"> 1280 <TD rowspan=\"4\"> 22778 <TH>Compute Time <TD>0.00234898<TD>0.00207079<TD>0.00570918<TD>2.5976e-05<TD>0.00302563<TD>0.00298036<TD>0.00144525<TD style=\"background-color:red\">0.000919922<TD>0.00426444\n<TR><TH>Solve Time <TD>0.00103392<TD>0.000211911<TD>0.00105<TD>0.0110432<TD>0.000628287<TD>0.00392089<TD>0.000138303<TD style=\"background-color:red\">6.2446e-05<TD>0.00097564\n<TR><TH>Total Time <TD>0.0033829<TD>0.0022827<TD>0.00675918<TD>0.0110692<TD>0.00365392<TD>0.00690124<TD>0.00158355<TD style=\"background-color:red\">0.000982368<TD>0.00524008\n<TR><TH>Error(Iter) <TD> 1.32953e-16 <TD> 3.08646e-16 <TD> 6.734e-16 <TD> 8.83132e-11 (40)  <TD> 1.51153e-16 (1)  <TD> 6.08556e-16 (8)  <TD> 1.89264e-16 <TD> 1.97477e-16 <TD> 6.68126e-09\n<TR><TH rowspan=\"4\">crashbasis <TD rowspan=\"4\"> 160000 <TD rowspan=\"4\"> 1750416 <TH>Compute Time <TD>3.2019<TD>5.7892<TD>15.7573<TD style=\"background-color:red\">0.00383515<TD>3.1006<TD>3.09921\n<TR><TH>Solve Time <TD>0.261915<TD>0.106225<TD>0.402141<TD style=\"background-color:red\">1.49089<TD>0.24888<TD>0.443673\n<TR><TH>Total Time <TD>3.46381<TD>5.89542<TD>16.1594<TD style=\"background-color:red\">1.49473<TD>3.34948<TD>3.54288\n<TR><TH>Error(Iter) <TD> 1.76348e-16 <TD> 4.58395e-16 <TD> 1.67982e-14 <TD> 8.64144e-11 (61)  <TD> 8.5996e-12 (2)  <TD> 6.04042e-14 (5) \n\n</TABLE>\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/SparseQuickReference.dox",
    "content": "namespace Eigen {\n/** \\eigenManualPage SparseQuickRefPage Quick reference guide for sparse matrices\n\\eigenAutoToc\n\n<hr>\n\nIn this page, we give a quick summary of the main operations available for sparse matrices in the class SparseMatrix. First, it is recommended to read  the introductory tutorial at \\ref TutorialSparse. The important point to have in mind when working on sparse matrices is how they are stored : \ni.e either row major or column major. The default is column major. Most arithmetic operations on sparse matrices will assert that they have the same storage order. \n\n\\section SparseMatrixInit Sparse Matrix Initialization\n<table class=\"manual\">\n<tr><th> Category </th> <th> Operations</th> <th>Notes</th></tr>\n<tr><td>Constructor</td>\n<td>\n\\code\n  SparseMatrix<double> sm1(1000,1000); \n  SparseMatrix<std::complex<double>,RowMajor> sm2;\n\\endcode\n</td> <td> Default is ColMajor</td> </tr>\n<tr class=\"alt\">\n<td> Resize/Reserve</td>\n<td> \n \\code\n    sm1.resize(m,n);      // Change sm1 to a m x n matrix.\n    sm1.reserve(nnz);     // Allocate room for nnz nonzeros elements.   \n  \\endcode \n</td>\n<td> Note that when calling reserve(), it is not required that nnz is the exact number of nonzero elements in the final matrix. However, an exact estimation will avoid multiple reallocations during the insertion phase. </td>\n</tr>\n<tr> \n<td> Assignment </td>\n<td> \n\\code \n  SparseMatrix<double,Colmajor> sm1;\n // Initialize sm2 with sm1.\n  SparseMatrix<double,Rowmajor> sm2(sm1), sm3;        \n  // Assignment and evaluations modify the storage order.\n  sm3 = sm1; \n \\endcode\n</td>\n<td> The copy constructor can be used to convert from a storage order to another</td>\n</tr>\n<tr class=\"alt\">\n<td> Element-wise Insertion</td>\n<td>\n\\code \n// Insert a new element; \n sm1.insert(i, j) = v_ij;  \n\n// Update the value v_ij\n sm1.coeffRef(i,j) = v_ij;\n sm1.coeffRef(i,j) += v_ij;\n sm1.coeffRef(i,j) -= v_ij;\n\\endcode\n</td>\n<td> insert() assumes that the element does not already exist; otherwise, use coeffRef()</td>\n</tr>\n<tr> \n<td> Batch insertion</td>\n<td>\n\\code\n  std::vector< Eigen::Triplet<double> > tripletList;\n  tripletList.reserve(estimation_of_entries);\n  // -- Fill tripletList with nonzero elements...\n  sm1.setFromTriplets(TripletList.begin(), TripletList.end());\n\\endcode\n</td>\n<td>A complete example is available at \\link TutorialSparseFilling Triplet Insertion \\endlink.</td>\n</tr>\n<tr class=\"alt\"> \n<td> Constant or Random Insertion</td>\n<td>\n\\code\nsm1.setZero();\n\\endcode\n</td>\n<td>Remove all non-zero coefficients</td>\n</tr>\n</table>\n\n\n\\section SparseBasicInfos Matrix properties\nBeyond the basic functions rows() and cols(), there are some useful functions that are available to easily get some information from the matrix. \n<table class=\"manual\">\n<tr>\n  <td> \\code\n  sm1.rows();         // Number of rows\n  sm1.cols();         // Number of columns \n  sm1.nonZeros();     // Number of non zero values   \n  sm1.outerSize();    // Number of columns (resp. rows) for a column major (resp. row major )\n  sm1.innerSize();    // Number of rows (resp. columns) for a row major (resp. column major)\n  sm1.norm();         // Euclidian norm of the matrix\n  sm1.squaredNorm();  // Squared norm of the matrix\n  sm1.blueNorm();\n  sm1.isVector();     // Check if sm1 is a sparse vector or a sparse matrix\n  sm1.isCompressed(); // Check if sm1 is in compressed form\n  ...\n  \\endcode </td>\n</tr>\n</table>\n\n\\section SparseBasicOps Arithmetic operations\nIt is easy to perform arithmetic operations on sparse matrices provided that the dimensions are adequate and that the matrices have the same storage order. Note that the evaluation can always be done in a matrix with a different storage order. In the following, \\b sm denotes a sparse matrix, \\b dm a dense matrix and \\b dv a dense vector.\n<table class=\"manual\">\n<tr><th> Operations </th> <th> Code </th> <th> Notes </th></tr>\n\n<tr>\n  <td> add subtract </td> \n  <td> \\code\n  sm3 = sm1 + sm2; \n  sm3 = sm1 - sm2;\n  sm2 += sm1; \n  sm2 -= sm1; \\endcode\n  </td>\n  <td> \n  sm1 and sm2 should have the same storage order\n  </td> \n</tr>\n\n<tr class=\"alt\"><td>\n  scalar product</td><td>\\code\n  sm3 = sm1 * s1;   sm3 *= s1; \n  sm3 = s1 * sm1 + s2 * sm2; sm3 /= s1;\\endcode\n  </td>\n  <td>\n    Many combinations are possible if the dimensions and the storage order agree.\n</tr>\n\n<tr>\n  <td> %Sparse %Product </td>\n  <td> \\code\n  sm3 = sm1 * sm2;\n  dm2 = sm1 * dm1;\n  dv2 = sm1 * dv1;\n  \\endcode </td>\n  <td>\n  </td>\n</tr> \n\n<tr class='alt'>\n  <td> transposition, adjoint</td>\n  <td> \\code\n  sm2 = sm1.transpose();\n  sm2 = sm1.adjoint();\n  \\endcode </td>\n  <td>\n  Note that the transposition change the storage order. There is no support for transposeInPlace().\n  </td>\n</tr> \n<tr>\n<td> Permutation </td>\n<td> \n\\code \nperm.indices();      // Reference to the vector of indices\nsm1.twistedBy(perm); // Permute rows and columns\nsm2 = sm1 * perm;    // Permute the columns\nsm2 = perm * sm1;    // Permute the columns\n\\endcode \n</td>\n<td> \n\n</td>\n</tr>\n<tr>\n  <td>\n  Component-wise ops\n  </td>\n  <td>\\code \n  sm1.cwiseProduct(sm2);\n  sm1.cwiseQuotient(sm2);\n  sm1.cwiseMin(sm2);\n  sm1.cwiseMax(sm2);\n  sm1.cwiseAbs();\n  sm1.cwiseSqrt();\n  \\endcode</td>\n  <td>\n  sm1 and sm2 should have the same storage order\n  </td>\n</tr>\n</table>\n\n\\section sparseotherops Other supported operations\n<table class=\"manual\">\n<tr><th style=\"min-width:initial\"> Code </th> <th> Notes</th> </tr>\n<tr><td colspan=\"2\">Sub-matrices</td></tr>\n<tr>\n<td> \n\\code \n  sm1.block(startRow, startCol, rows, cols); \n  sm1.block(startRow, startCol); \n  sm1.topLeftCorner(rows, cols); \n  sm1.topRightCorner(rows, cols);\n  sm1.bottomLeftCorner( rows, cols);\n  sm1.bottomRightCorner( rows, cols);\n  \\endcode\n</td><td>\nContrary to dense matrices, here <strong>all these methods are read-only</strong>.\\n\nSee \\ref TutorialSparse_SubMatrices and below for read-write sub-matrices.\n</td>\n</tr>\n<tr class=\"alt\"><td colspan=\"2\"> Range </td></tr>\n<tr class=\"alt\">\n<td> \n\\code \n  sm1.innerVector(outer);           // RW\n  sm1.innerVectors(start, size);    // RW\n  sm1.leftCols(size);               // RW\n  sm2.rightCols(size);              // RO because sm2 is row-major\n  sm1.middleRows(start, numRows);   // RO because sm1 is column-major\n  sm1.middleCols(start, numCols);   // RW\n  sm1.col(j);                       // RW\n\\endcode\n</td>\n<td>\nA inner vector is either a row (for row-major) or a column (for column-major).\\n\nAs stated earlier, for a read-write sub-matrix (RW), the evaluation can be done in a matrix with different storage order.\n</td>\n</tr>\n<tr><td colspan=\"2\"> Triangular and selfadjoint views</td></tr>\n<tr>\n<td> \n\\code\n  sm2 = sm1.triangularview<Lower>();\n  sm2 = sm1.selfadjointview<Lower>();\n\\endcode\n</td>\n<td> Several combination between triangular views and blocks views are possible\n\\code \n  \\endcode </td>\n</tr>\n<tr class=\"alt\"><td colspan=\"2\">Triangular solve </td></tr>\n<tr class=\"alt\">\n<td> \n\\code \n dv2 = sm1.triangularView<Upper>().solve(dv1);\n dv2 = sm1.topLeftCorner(size, size)\n          .triangularView<Lower>().solve(dv1);\n\\endcode \n</td>\n<td> For general sparse solve, Use any suitable module described at \\ref TopicSparseSystems </td>\n</tr>\n<tr><td colspan=\"2\"> Low-level API</td></tr>\n<tr>\n<td>\n\\code\nsm1.valuePtr();      // Pointer to the values\nsm1.innerIndexPtr();  // Pointer to the indices.\nsm1.outerIndexPtr(); // Pointer to the beginning of each inner vector\n\\endcode\n</td>\n<td>\nIf the matrix is not in compressed form, `makeCompressed()` should be called before.\\n\nNote that these functions are mostly provided for interoperability purposes with external libraries.\\n\nA better access to the values of the matrix is done by using the InnerIterator class as described in \\link TutorialSparse the Tutorial Sparse \\endlink section</td>\n</tr>\n<tr class=\"alt\"><td colspan=\"2\">Mapping external buffers</td></tr>\n<tr class=\"alt\">\n<td>\n\\code\nint outerIndexPtr[cols+1];\nint innerIndices[nnz];\ndouble values[nnz];\nMap<SparseMatrix<double> > sm1(rows,cols,nnz,outerIndexPtr, // read-write\n                               innerIndices,values);\nMap<const SparseMatrix<double> > sm2(...);                  // read-only\n\\endcode\n</td>\n<td>As for dense matrices, class Map<SparseMatrixType> can be used to see external buffers as an %Eigen's SparseMatrix object. </td>\n</tr>\n</table>\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/StlContainers.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TopicStlContainers Using STL Containers with Eigen\n\n\\eigenAutoToc\n\n\\section StlContainers_summary Executive summary\n\nIf you're compiling in \\cpp17 mode only with a sufficiently recent compiler (e.g., GCC>=7, clang>=5, MSVC>=19.12), then everything is taken care by the compiler and you can stop reading.\n\nOtherwise, using STL containers on \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen types\", or classes having members of such types, requires the use of an over-aligned allocator.\nThat is, an allocator capable of allocating buffers with 16, 32, or even 64 bytes alignment.\n%Eigen does provide one ready for use: aligned_allocator.\n\nPrior to \\cpp11, if you want to use the `std::vector` container, then you also have to <code> \\#include <Eigen/StdVector> </code>.\n\nThese issues arise only with \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen types\" and \\ref TopicStructHavingEigenMembers \"structures having such Eigen objects as member\".\nFor other %Eigen types, such as Vector3f or MatrixXd, no special care is needed when using STL containers.\n\n\\section allocator Using an aligned allocator\n\nSTL containers take an optional template parameter, the allocator type. When using STL containers on \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen types\", you need tell the container to use an allocator that will always allocate memory at 16-byte-aligned (or more) locations. Fortunately, %Eigen does provide such an allocator: Eigen::aligned_allocator.\n\nFor example, instead of\n\\code\nstd::map<int, Eigen::Vector4d>\n\\endcode\nyou need to use\n\\code\nstd::map<int, Eigen::Vector4d, std::less<int>, \n         Eigen::aligned_allocator<std::pair<const int, Eigen::Vector4d> > >\n\\endcode\nNote that the third parameter `std::less<int>` is just the default value, but we have to include it because we want to specify the fourth parameter, which is the allocator type.\n\n\\section StlContainers_vector The case of std::vector\n\nThis section is for c++98/03 users only. \\cpp11 (or above) users can stop reading here.\n\nSo in c++98/03, the situation with `std::vector` is more complicated because of a bug in the standard (explanation below).\nTo workaround the issue, we had to specialize it for the Eigen::aligned_allocator type.\nIn practice you \\b must use the Eigen::aligned_allocator (not another aligned allocator), \\b and \\#include <Eigen/StdVector>.\n\nHere is an example:\n\\code\n#include<Eigen/StdVector>\n/* ... */\nstd::vector<Eigen::Vector4f,Eigen::aligned_allocator<Eigen::Vector4f> >\n\\endcode\n\n<span class=\"note\">\\b Explanation: The `resize()` method of `std::vector` takes a `value_type` argument (defaulting to `value_type()`). So with `std::vector<Eigen::Vector4d>`, some Eigen::Vector4d objects will be passed by value, which discards any alignment modifiers, so a Eigen::Vector4d can be created at an unaligned location.\nIn order to avoid that, the only solution we saw was to specialize `std::vector` to make it work on a slight modification of, here, Eigen::Vector4d, that is able to deal properly with this situation.\n</span>\n\n\\subsection vector_spec An alternative - specializing std::vector for Eigen types\n\nAs an alternative to the recommended approach described above, you have the option to specialize std::vector for Eigen types requiring alignment. \nThe advantage is that you won't need to declare std::vector all over with Eigen::aligned_allocator. One drawback on the other hand side is that\nthe specialization needs to be defined before all code pieces in which e.g. `std::vector<Vector2d>` is used. Otherwise, without knowing the specialization\nthe compiler will compile that particular instance with the default `std::allocator` and you program is most likely to crash.\n\nHere is an example:\n\\code\n#include<Eigen/StdVector>\n/* ... */\nEIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Matrix2d)\nstd::vector<Eigen::Vector2d>\n\\endcode\n\n\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/StorageOrders.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TopicStorageOrders Storage orders\n\nThere are two different storage orders for matrices and two-dimensional arrays: column-major and row-major.\nThis page explains these storage orders and how to specify which one should be used.\n\n\\eigenAutoToc\n\n\n\\section TopicStorageOrdersIntro Column-major and row-major storage\n\nThe entries of a matrix form a two-dimensional grid. However, when the matrix is stored in memory, the entries\nhave to somehow be laid out linearly. There are two main ways to do this, by row and by column.\n\nWe say that a matrix is stored in \\b row-major order if it is stored row by row. The entire first row is\nstored first, followed by the entire second row, and so on. Consider for example the matrix\n\n\\f[\nA = \\begin{bmatrix}\n8 & 2 & 2 & 9 \\\\\n9 & 1 & 4 & 4 \\\\\n3 & 5 & 4 & 5\n\\end{bmatrix}.\n\\f]\n\nIf this matrix is stored in row-major order, then the entries are laid out in memory as follows:\n\n\\code 8 2 2 9 9 1 4 4 3 5 4 5 \\endcode\n\nOn the other hand, a matrix is stored in \\b column-major order if it is stored column by column, starting with\nthe entire first column, followed by the entire second column, and so on. If the above matrix is stored in\ncolumn-major order, it is laid out as follows:\n\n\\code 8 9 3 2 1 5 2 4 4 9 4 5 \\endcode\n\nThis example is illustrated by the following Eigen code. It uses the PlainObjectBase::data() function, which\nreturns a pointer to the memory location of the first entry of the matrix.\n\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include TopicStorageOrders_example.cpp\n</td>\n<td>\n\\verbinclude TopicStorageOrders_example.out\n</td></tr></table>\n\n\n\\section TopicStorageOrdersInEigen Storage orders in Eigen\n\nThe storage order of a matrix or a two-dimensional array can be set by specifying the \\c Options template\nparameter for Matrix or Array. As \\ref TutorialMatrixClass explains, the %Matrix class template has six\ntemplate parameters, of which three are compulsory (\\c Scalar, \\c RowsAtCompileTime and \\c ColsAtCompileTime)\nand three are optional (\\c Options, \\c MaxRowsAtCompileTime and \\c MaxColsAtCompileTime). If the \\c Options\nparameter is set to \\c RowMajor, then the matrix or array is stored in row-major order; if it is set to \n\\c ColMajor, then it is stored in column-major order. This mechanism is used in the above Eigen program to\nspecify the storage order.\n\nIf the storage order is not specified, then Eigen defaults to storing the entry in column-major. This is also\nthe case if one of the convenience typedefs (\\c Matrix3f, \\c ArrayXXd, etc.) is used.\n\nMatrices and arrays using one storage order can be assigned to matrices and arrays using the other storage\norder, as happens in the above program when \\c Arowmajor is initialized using \\c Acolmajor. Eigen will reorder\nthe entries automatically. More generally, row-major and column-major matrices can be mixed in an expression\nas we want.\n\n\n\\section TopicStorageOrdersWhich Which storage order to choose?\n\nSo, which storage order should you use in your program? There is no simple answer to this question; it depends\non your application. Here are some points to keep in mind:\n\n  - Your users may expect you to use a specific storage order. Alternatively, you may use other libraries than\n    Eigen, and these other libraries may expect a certain storage order. In these cases it may be easiest and\n    fastest to use this storage order in your whole program.\n  - Algorithms that traverse a matrix row by row will go faster when the matrix is stored in row-major order\n    because of better data locality. Similarly, column-by-column traversal is faster for column-major\n    matrices. It may be worthwhile to experiment a bit to find out what is faster for your particular\n    application.\n  - The default in Eigen is column-major. Naturally, most of the development and testing of the Eigen library\n    is thus done with column-major matrices. This means that, even though we aim to support column-major and\n    row-major storage orders transparently, the Eigen library may well work best with column-major matrices.\n\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/StructHavingEigenMembers.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TopicStructHavingEigenMembers Structures Having Eigen Members\n\n\\eigenAutoToc\n\n\\section StructHavingEigenMembers_summary Executive Summary\n\n\nIf you define a structure having members of \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen types\", you must ensure that calling operator new on it allocates properly aligned buffers.\nIf you're compiling in \\cpp17 mode only with a sufficiently recent compiler (e.g., GCC>=7, clang>=5, MSVC>=19.12), then everything is taken care by the compiler and you can stop reading.\n\nOtherwise, you have to overload its `operator new` so that it generates properly aligned pointers (e.g., 32-bytes-aligned for Vector4d and AVX).\nFortunately, %Eigen provides you with a macro `EIGEN_MAKE_ALIGNED_OPERATOR_NEW` that does that for you.\n\n\\section StructHavingEigenMembers_what What kind of code needs to be changed?\n\nThe kind of code that needs to be changed is this:\n\n\\code\nclass Foo\n{\n  ...\n  Eigen::Vector2d v;\n  ...\n};\n\n...\n\nFoo *foo = new Foo;\n\\endcode\n\nIn other words: you have a class that has as a member a \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen object\", and then you dynamically create an object of that class.\n\n\\section StructHavingEigenMembers_how How should such code be modified?\n\nVery easy, you just need to put a `EIGEN_MAKE_ALIGNED_OPERATOR_NEW` macro in a public part of your class, like this:\n\n\\code\nclass Foo\n{\n  ...\n  Eigen::Vector4d v;\n  ...\npublic:\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n};\n\n...\n\nFoo *foo = new Foo;\n\\endcode\n\nThis macro makes `new Foo` always return an aligned pointer.\n\nIn \\cpp17, this macro is empty.\n\nIf this approach is too intrusive, see also the \\ref StructHavingEigenMembers_othersolutions \"other solutions\".\n\n\\section StructHavingEigenMembers_why Why is this needed?\n\nOK let's say that your code looks like this:\n\n\\code\nclass Foo\n{\n  ...\n  Eigen::Vector4d v;\n  ...\n};\n\n...\n\nFoo *foo = new Foo;\n\\endcode\n\nA Eigen::Vector4d consists of 4 doubles, which is 256 bits.\nThis is exactly the size of an AVX register, which makes it possible to use AVX for all sorts of operations on this vector.\nBut AVX instructions (at least the ones that %Eigen uses, which are the fast ones) require 256-bit alignment.\nOtherwise you get a segmentation fault.\n\nFor this reason, %Eigen takes care by itself to require 256-bit alignment for Eigen::Vector4d, by doing two things:\n\\li %Eigen requires 256-bit alignment for the Eigen::Vector4d's array (of 4 doubles). With \\cpp11 this is done with the <a href=\"https://en.cppreference.com/w/cpp/keyword/alignas\">alignas</a> keyword, or compiler's extensions for c++98/03.\n\\li %Eigen overloads the `operator new` of Eigen::Vector4d so it will always return 256-bit aligned pointers. (removed in \\cpp17)\n\nThus, normally, you don't have to worry about anything, %Eigen handles alignment of operator new for you...\n\n... except in one case. When you have a `class Foo` like above, and you dynamically allocate a new `Foo` as above, then, since `Foo` doesn't have aligned `operator new`, the returned pointer foo is not necessarily 256-bit aligned.\n\nThe alignment attribute of the member `v` is then relative to the start of the class `Foo`. If the `foo` pointer wasn't aligned, then `foo->v` won't be aligned either!\n\nThe solution is to let `class Foo` have an aligned `operator new`, as we showed in the previous section.\n\nThis explanation also holds for SSE/NEON/MSA/Altivec/VSX targets, which require 16-bytes alignment, and AVX512 which requires 64-bytes alignment for fixed-size objects multiple of 64 bytes (e.g., Eigen::Matrix4d).\n\n\\section StructHavingEigenMembers_movetotop Should I then put all the members of Eigen types at the beginning of my class?\n\nThat's not required. Since %Eigen takes care of declaring adequate alignment, all members that need it are automatically aligned relatively to the class. So code like this works fine:\n\n\\code\nclass Foo\n{\n  double x;\n  Eigen::Vector4d v;\npublic:\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n};\n\\endcode\n\nThat said, as usual, it is recommended to sort the members so that alignment does not waste memory.\nIn the above example, with AVX, the compiler will have to reserve 24 empty bytes between `x` and `v`.\n\n\n\\section StructHavingEigenMembers_dynamicsize What about dynamic-size matrices and vectors?\n\nDynamic-size matrices and vectors, such as Eigen::VectorXd, allocate dynamically their own array of coefficients, so they take care of requiring absolute alignment automatically. So they don't cause this issue. The issue discussed here is only with \\ref TopicFixedSizeVectorizable  \"fixed-size vectorizable matrices and vectors\".\n\n\n\\section StructHavingEigenMembers_bugineigen So is this a bug in Eigen?\n\nNo, it's not our bug. It's more like an inherent problem of the c++ language specification that has been solved in c++17 through the feature known as <a href=\"http://wg21.link/p0035r4\">dynamic memory allocation for over-aligned data</a>.\n\n\n\\section StructHavingEigenMembers_conditional What if I want to do this conditionally (depending on template parameters) ?\n\nFor this situation, we offer the macro `EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)`.\nIt will generate aligned operators like `EIGEN_MAKE_ALIGNED_OPERATOR_NEW` if `NeedsToAlign` is true.\nIt will generate operators with the default alignment if `NeedsToAlign` is false.\nIn \\cpp17, this macro is empty.\n\nExample:\n\n\\code\ntemplate<int n> class Foo\n{\n  typedef Eigen::Matrix<float,n,1> Vector;\n  enum { NeedsToAlign = (sizeof(Vector)%16)==0 };\n  ...\n  Vector v;\n  ...\npublic:\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)\n};\n\n...\n\nFoo<4> *foo4 = new Foo<4>; // foo4 is guaranteed to be 128bit-aligned\nFoo<3> *foo3 = new Foo<3>; // foo3 has only the system default alignment guarantee\n\\endcode\n\n\n\\section StructHavingEigenMembers_othersolutions Other solutions\n\nIn case putting the `EIGEN_MAKE_ALIGNED_OPERATOR_NEW` macro everywhere is too intrusive, there exists at least two other solutions.\n\n\\subsection othersolutions1 Disabling alignment\n\nThe first is to disable alignment requirement for the fixed size members:\n\\code\nclass Foo\n{\n  ...\n  Eigen::Matrix<double,4,1,Eigen::DontAlign> v;\n  ...\n};\n\\endcode\nThis `v` is fully compatible with aligned Eigen::Vector4d.\nThis has only for effect to make load/stores to `v` more expensive (usually slightly, but that's hardware dependent).\n\n\n\\subsection othersolutions2 Private structure\n\nThe second consist in storing the fixed-size objects into a private struct which will be dynamically allocated at the construction time of the main object:\n\n\\code\nstruct Foo_d\n{\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n  Vector4d v;\n  ...\n};\n\n\nstruct Foo {\n  Foo() { init_d(); }\n  ~Foo() { delete d; }\n  void bar()\n  {\n    // use d->v instead of v\n    ...\n  }\nprivate:\n  void init_d() { d = new Foo_d; }\n  Foo_d* d;\n};\n\\endcode\n\nThe clear advantage here is that the class `Foo` remains unchanged regarding alignment issues.\nThe drawback is that an additional heap allocation will be required whatsoever.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TemplateKeyword.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicTemplateKeyword The template and typename keywords in C++\n\nThere are two uses for the \\c template and \\c typename keywords in C++. One of them is fairly well known\namongst programmers: to define templates. The other use is more obscure: to specify that an expression refers\nto a template function or a type. This regularly trips up programmers that use the %Eigen library, often\nleading to error messages from the compiler that are difficult to understand, such as \"expected expression\" or\n\"no match for operator<\".\n\n\\eigenAutoToc\n\n\n\\section TopicTemplateKeywordToDefineTemplates Using the template and typename keywords to define templates\n\nThe \\c template and \\c typename keywords are routinely used to define templates. This is not the topic of this\npage as we assume that the reader is aware of this (otherwise consult a C++ book). The following example\nshould illustrate this use of the \\c template keyword.\n\n\\code\ntemplate <typename T>\nbool isPositive(T x)\n{\n    return x > 0;\n}\n\\endcode\n\nWe could just as well have written <tt>template &lt;class T&gt;</tt>; the keywords \\c typename and \\c class have the\nsame meaning in this context.\n\n\n\\section TopicTemplateKeywordExample An example showing the second use of the template keyword\n\nLet us illustrate the second use of the \\c template keyword with an example. Suppose we want to write a\nfunction which copies all entries in the upper triangular part of a matrix into another matrix, while keeping\nthe lower triangular part unchanged. A straightforward implementation would be as follows:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include TemplateKeyword_simple.cpp\n</td>\n<td>\n\\verbinclude TemplateKeyword_simple.out\n</td></tr></table>\n\nThat works fine, but it is not very flexible. First, it only works with dynamic-size matrices of\nsingle-precision floats; the function \\c copyUpperTriangularPart() does not accept static-size matrices or\nmatrices with double-precision numbers. Second, if you use an expression such as\n<tt>mat.topLeftCorner(3,3)</tt> as the parameter \\c src, then this is copied into a temporary variable of type\nMatrixXf; this copy can be avoided.\n\nAs explained in \\ref TopicFunctionTakingEigenTypes, both issues can be resolved by making \n\\c copyUpperTriangularPart() accept any object of type MatrixBase. This leads to the following code:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include TemplateKeyword_flexible.cpp\n</td>\n<td>\n\\verbinclude TemplateKeyword_flexible.out\n</td></tr></table>\n\nThe one line in the body of the function \\c copyUpperTriangularPart() shows the second, more obscure use of\nthe \\c template keyword in C++.  Even though it may look strange, the \\c template keywords are necessary\naccording to the standard. Without it, the compiler may reject the code with an error message like \"no match\nfor operator<\".\n\n\n\\section TopicTemplateKeywordExplanation Explanation\n\nThe reason that the \\c template keyword is necessary in the last example has to do with the rules for how\ntemplates are supposed to be compiled in C++. The compiler has to check the code for correct syntax at the\npoint where the template is defined, without knowing the actual value of the template arguments (\\c Derived1\nand \\c Derived2 in the example). That means that the compiler cannot know that <tt>dst.triangularView</tt> is\na member template and that the following &lt; symbol is part of the delimiter for the template\nparameter. Another possibility would be that <tt>dst.triangularView</tt> is a member variable with the &lt;\nsymbol referring to the <tt>operator&lt;()</tt> function. In fact, the compiler should choose the second\npossibility, according to the standard. If <tt>dst.triangularView</tt> is a member template (as in our case),\nthe programmer should specify this explicitly with the \\c template keyword and write <tt>dst.template\ntriangularView</tt>.\n\nThe precise rules are rather complicated, but ignoring some subtleties we can summarize them as follows:\n- A <em>dependent name</em> is name that depends (directly or indirectly) on a template parameter. In the\n  example, \\c dst is a dependent name because it is of type <tt>MatrixBase&lt;Derived1&gt;</tt> which depends\n  on the template parameter \\c Derived1.\n- If the code contains either one of the constructs <tt>xxx.yyy</tt> or <tt>xxx-&gt;yyy</tt> and \\c xxx is a\n  dependent name and \\c yyy refers to a member template, then the \\c template keyword must be used before \n  \\c yyy, leading to <tt>xxx.template yyy</tt> or <tt>xxx-&gt;template yyy</tt>.\n- If the code contains the construct <tt>xxx::yyy</tt> and \\c xxx is a dependent name and \\c yyy refers to a\n  member typedef, then the \\c typename keyword must be used before the whole construct, leading to\n  <tt>typename xxx::yyy</tt>.\n\nAs an example where the \\c typename keyword is required, consider the following code in \\ref TutorialSparse\nfor iterating over the non-zero entries of a sparse matrix type:\n\n\\code\nSparseMatrixType mat(rows,cols);\nfor (int k=0; k<mat.outerSize(); ++k)\n  for (SparseMatrixType::InnerIterator it(mat,k); it; ++it)\n  {\n    /* ... */\n  }\n\\endcode\n\nIf \\c SparseMatrixType depends on a template parameter, then the \\c typename keyword is required:\n\n\\code\ntemplate <typename T>\nvoid iterateOverSparseMatrix(const SparseMatrix<T>& mat;\n{\n  for (int k=0; k<m1.outerSize(); ++k)\n    for (typename SparseMatrix<T>::InnerIterator it(mat,k); it; ++it)\n    {\n      /* ... */\n    }\n}\n\\endcode\n\n\n\\section TopicTemplateKeywordResources Resources for further reading\n\nFor more information and a fuller explanation of this topic, the reader may consult the following sources:\n- The book \"C++ Template Metaprogramming\" by David Abrahams and Aleksey Gurtovoy contains a very good\n  explanation in Appendix B (\"The typename and template Keywords\") which formed the basis for this page.\n- http://pages.cs.wisc.edu/~driscoll/typename.html\n- http://www.parashift.com/c++-faq-lite/templates.html#faq-35.18\n- http://www.comeaucomputing.com/techtalk/templates/#templateprefix\n- http://www.comeaucomputing.com/techtalk/templates/#typename\n\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TopicAliasing.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TopicAliasing Aliasing\n\nIn %Eigen, aliasing refers to assignment statement in which the same matrix (or array or vector) appears on the\nleft and on the right of the assignment operators. Statements like <tt>mat = 2 * mat;</tt> or <tt>mat =\nmat.transpose();</tt> exhibit aliasing. The aliasing in the first example is harmless, but the aliasing in the\nsecond example leads to unexpected results. This page explains what aliasing is, when it is harmful, and what\nto do about it.\n\n\\eigenAutoToc\n\n\n\\section TopicAliasingExamples Examples\n\nHere is a simple example exhibiting aliasing:\n\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include TopicAliasing_block.cpp\n</td>\n<td>\n\\verbinclude TopicAliasing_block.out\n</td></tr></table>\n\nThe output is not what one would expect. The problem is the assignment\n\\code\nmat.bottomRightCorner(2,2) = mat.topLeftCorner(2,2);\n\\endcode\nThis assignment exhibits aliasing: the coefficient \\c mat(1,1) appears both in the block\n<tt>mat.bottomRightCorner(2,2)</tt> on the left-hand side of the assignment and the block\n<tt>mat.topLeftCorner(2,2)</tt> on the right-hand side. After the assignment, the (2,2) entry in the bottom\nright corner should have the value of \\c mat(1,1) before the assignment, which is 5. However, the output shows\nthat \\c mat(2,2) is actually 1. The problem is that %Eigen uses lazy evaluation (see \n\\ref TopicEigenExpressionTemplates) for <tt>mat.topLeftCorner(2,2)</tt>. The result is similar to\n\\code\nmat(1,1) = mat(0,0);\nmat(1,2) = mat(0,1);\nmat(2,1) = mat(1,0);\nmat(2,2) = mat(1,1);\n\\endcode\nThus, \\c mat(2,2) is assigned the \\e new value of \\c mat(1,1) instead of the old value. The next section\nexplains how to solve this problem by calling \\link DenseBase::eval() eval()\\endlink.\n\nAliasing occurs more naturally when trying to shrink a matrix. For example, the expressions <tt>vec =\nvec.head(n)</tt> and <tt>mat = mat.block(i,j,r,c)</tt> exhibit aliasing.\n\nIn general, aliasing cannot be detected at compile time: if \\c mat in the first example were a bit bigger,\nthen the blocks would not overlap, and there would be no aliasing problem. However, %Eigen does detect some\ninstances of aliasing, albeit at run time.  The following example exhibiting aliasing was mentioned in \\ref\nTutorialMatrixArithmetic :\n\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include tut_arithmetic_transpose_aliasing.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_transpose_aliasing.out\n</td></tr></table>\n\nAgain, the output shows the aliasing issue. However, by default %Eigen uses a run-time assertion to detect this\nand exits with a message like\n\n\\verbatim\nvoid Eigen::DenseBase<Derived>::checkTransposeAliasing(const OtherDerived&) const \n[with OtherDerived = Eigen::Transpose<Eigen::Matrix<int, 2, 2, 0, 2, 2> >, Derived = Eigen::Matrix<int, 2, 2, 0, 2, 2>]: \nAssertion `(!internal::check_transpose_aliasing_selector<Scalar,internal::blas_traits<Derived>::IsTransposed,OtherDerived>::run(internal::extract_data(derived()), other)) \n&& \"aliasing detected during transposition, use transposeInPlace() or evaluate the rhs into a temporary using .eval()\"' failed.\n\\endverbatim\n\nThe user can turn %Eigen's run-time assertions like the one to detect this aliasing problem off by defining the\nEIGEN_NO_DEBUG macro, and the above program was compiled with this macro turned off in order to illustrate the\naliasing problem. See \\ref TopicAssertions for more information about %Eigen's run-time assertions.\n\n\n\\section TopicAliasingSolution Resolving aliasing issues\n\nIf you understand the cause of the aliasing issue, then it is obvious what must happen to solve it: %Eigen has\nto evaluate the right-hand side fully into a temporary matrix/array and then assign it to the left-hand\nside. The function \\link DenseBase::eval() eval() \\endlink does precisely that.\n\nFor example, here is the corrected version of the first example above:\n\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include TopicAliasing_block_correct.cpp\n</td>\n<td>\n\\verbinclude TopicAliasing_block_correct.out\n</td></tr></table>\n\nNow, \\c mat(2,2) equals 5 after the assignment, as it should be.\n\nThe same solution also works for the second example, with the transpose: simply replace the line \n<tt>a = a.transpose();</tt> with <tt>a = a.transpose().eval();</tt>. However, in this common case there is a\nbetter solution. %Eigen provides the special-purpose function \n\\link DenseBase::transposeInPlace() transposeInPlace() \\endlink which replaces a matrix by its transpose. \nThis is shown below:\n\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include tut_arithmetic_transpose_inplace.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_transpose_inplace.out\n</td></tr></table>\n\nIf an xxxInPlace() function is available, then it is best to use it, because it indicates more clearly what you\nare doing. This may also allow %Eigen to optimize more aggressively. These are some of the xxxInPlace()\nfunctions provided: \n\n<table class=\"manual\">\n<tr><th>Original function</th><th>In-place function</th></tr>\n<tr> <td> MatrixBase::adjoint() </td> <td> MatrixBase::adjointInPlace() </td> </tr>\n<tr class=\"alt\"> <td> DenseBase::reverse() </td> <td> DenseBase::reverseInPlace() </td> </tr>\n<tr> <td> LDLT::solve() </td> <td> LDLT::solveInPlace() </td> </tr>\n<tr class=\"alt\"> <td> LLT::solve() </td> <td> LLT::solveInPlace() </td> </tr>\n<tr> <td> TriangularView::solve() </td> <td> TriangularView::solveInPlace() </td> </tr>\n<tr class=\"alt\"> <td> DenseBase::transpose() </td> <td> DenseBase::transposeInPlace() </td> </tr>\n</table>\n\nIn the special case where a matrix or vector is shrunk using an expression like <tt>vec = vec.head(n)</tt>,\nyou can use \\link PlainObjectBase::conservativeResize() conservativeResize() \\endlink.\n\n\n\\section TopicAliasingCwise Aliasing and component-wise operations\n\nAs explained above, it may be dangerous if the same matrix or array occurs on both the left-hand side and the\nright-hand side of an assignment operator, and it is then often necessary to evaluate the right-hand side\nexplicitly. However, applying component-wise operations (such as matrix addition, scalar multiplication and\narray multiplication) is safe. \n\nThe following example has only component-wise operations. Thus, there is no need for \\link DenseBase::eval()\neval() \\endlink even though the same matrix appears on both sides of the assignments.\n\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include TopicAliasing_cwise.cpp\n</td>\n<td>\n\\verbinclude TopicAliasing_cwise.out\n</td></tr></table>\n\nIn general, an assignment is safe if the (i,j) entry of the expression on the right-hand side depends only on\nthe (i,j) entry of the matrix or array on the left-hand side and not on any other entries. In that case it is\nnot necessary to evaluate the right-hand side explicitly.\n\n\n\\section TopicAliasingMatrixMult Aliasing and matrix multiplication\n\nMatrix multiplication is the only operation in %Eigen that assumes aliasing by default, <strong>under the\ncondition that the destination matrix is not resized</strong>.\nThus, if \\c matA is a \\b squared matrix, then the statement <tt>matA = matA * matA;</tt> is safe.\nAll other operations in %Eigen assume that there are no aliasing problems,\neither because the result is assigned to a different matrix or because it is a component-wise operation.\n\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include TopicAliasing_mult1.cpp\n</td>\n<td>\n\\verbinclude TopicAliasing_mult1.out\n</td></tr></table>\n\nHowever, this comes at a price. When executing the expression <tt>matA = matA * matA</tt>, %Eigen evaluates the\nproduct in a temporary matrix which is assigned to \\c matA after the computation. This is fine. But %Eigen does\nthe same when the product is assigned to a different matrix (e.g., <tt>matB = matA * matA</tt>). In that case,\nit is more efficient to evaluate the product directly into \\c matB instead of evaluating it first into a\ntemporary matrix and copying that matrix to \\c matB.\n\nThe user can indicate with the \\link MatrixBase::noalias() noalias()\\endlink function that there is no\naliasing, as follows: <tt>matB.noalias() = matA * matA</tt>. This allows %Eigen to evaluate the matrix product\n<tt>matA * matA</tt> directly into \\c matB.\n\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include TopicAliasing_mult2.cpp\n</td>\n<td>\n\\verbinclude TopicAliasing_mult2.out\n</td></tr></table>\n\nOf course, you should not use \\c noalias() when there is in fact aliasing taking place. If you do, then you\nmay get wrong results:\n\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include TopicAliasing_mult3.cpp\n</td>\n<td>\n\\verbinclude TopicAliasing_mult3.out\n</td></tr></table>\n\nMoreover, starting in Eigen 3.3, aliasing is \\b not assumed if the destination matrix is resized and the product is not directly assigned to the destination.\nTherefore, the following example is also wrong:\n\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include TopicAliasing_mult4.cpp\n</td>\n<td>\n\\verbinclude TopicAliasing_mult4.out\n</td></tr></table>\n\nAs for any aliasing issue, you can resolve it by explicitly evaluating the expression prior to assignment:\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include TopicAliasing_mult5.cpp\n</td>\n<td>\n\\verbinclude TopicAliasing_mult5.out\n</td></tr></table>\n\n\\section TopicAliasingSummary Summary\n\nAliasing occurs when the same matrix or array coefficients appear both on the left- and the right-hand side of\nan assignment operator.\n - Aliasing is harmless with coefficient-wise computations; this includes scalar multiplication and matrix or\n   array addition.\n - When you multiply two matrices, %Eigen assumes that aliasing occurs. If you know that there is no aliasing,\n   then you can use \\link MatrixBase::noalias() noalias()\\endlink.\n - In all other situations, %Eigen assumes that there is no aliasing issue and thus gives the wrong result if\n   aliasing does in fact occur. To prevent this, you have to use \\link DenseBase::eval() eval() \\endlink or\n   one of the xxxInPlace() functions.\n\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TopicAssertions.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicAssertions Assertions\n\n\\eigenAutoToc\n\n\\section PlainAssert Assertions\n\nThe macro eigen_assert is defined to be \\c eigen_plain_assert by default. We use eigen_plain_assert instead of \\c assert to work around a known bug for GCC <= 4.3. Basically, eigen_plain_assert \\a is \\c assert.\n\n\\subsection RedefineAssert Redefining assertions\n\nBoth eigen_assert and eigen_plain_assert are defined in Macros.h. Defining eigen_assert indirectly gives you a chance to change its behavior. You can redefine this macro if you want to do something else such as throwing an exception, and fall back to its default behavior with eigen_plain_assert. The code below tells Eigen to throw an std::runtime_error:\n\n\\code\n#include <stdexcept>\n#undef eigen_assert\n#define eigen_assert(x) \\\n  if (!(x)) { throw (std::runtime_error(\"Put your message here\")); }\n\\endcode\n\n\\subsection DisableAssert Disabling assertions\n\nAssertions cost run time and can be turned off. You can suppress eigen_assert by defining \\c EIGEN_NO_DEBUG \\b before including Eigen headers. \\c EIGEN_NO_DEBUG is undefined by default unless \\c NDEBUG is defined.\n\n\\section StaticAssert Static assertions\n\nStatic assertions are not standardized until C++11. However, in the Eigen library, there are many conditions can and should be detectedat compile time. For instance, we use static assertions to prevent the code below from compiling.\n\n\\code\nMatrix3d()  + Matrix4d();   // adding matrices of different sizes\nMatrix4cd() * Vector3cd();  // invalid product known at compile time\n\\endcode\n\nStatic assertions are defined in StaticAssert.h. If there is native static_assert, we use it. Otherwise, we have implemented an assertion macro that can show a limited range of messages.\n\nOne can easily come up with static assertions without messages, such as:\n\n\\code\n#define STATIC_ASSERT(x) \\\n  switch(0) { case 0: case x:; }\n\\endcode\n\nHowever, the example above obviously cannot tell why the assertion failed. Therefore, we define a \\c struct in namespace Eigen::internal to handle available messages.\n\n\\code\ntemplate<bool condition>\nstruct static_assertion {};\n\ntemplate<>\nstruct static_assertion<true>\n{\n  enum {\n    YOU_TRIED_CALLING_A_VECTOR_METHOD_ON_A_MATRIX,\n    YOU_MIXED_VECTORS_OF_DIFFERENT_SIZES,\n    // see StaticAssert.h for all enums.\n  };\n};\n\\endcode\n\nAnd then, we define EIGEN_STATIC_ASSERT(CONDITION,MSG) to access Eigen::internal::static_assertion<bool(CONDITION)>::MSG. If the condition evaluates into \\c false, your compiler displays a lot of messages explaining there is no MSG in static_assert<false>. Nevertheless, this is \\a not in what we are interested. As you can see, all members of static_assert<true> are ALL_CAPS_AND_THEY_ARE_SHOUTING.\n\n\\warning\nWhen using this macro, MSG should be a member of static_assertion<true>, or the static assertion \\b always fails.\nCurrently, it can only be used in function scope.\n\n\\subsection DerivedStaticAssert Derived static assertions\n\nThere are other macros derived from EIGEN_STATIC_ASSERT to enhance readability. Their names are self-explanatory.\n\n- \\b EIGEN_STATIC_ASSERT_FIXED_SIZE(TYPE) - passes if \\a TYPE is fixed size.\n- \\b EIGEN_STATIC_ASSERT_DYNAMIC_SIZE(TYPE) - passes if \\a TYPE is dynamic size.\n- \\b EIGEN_STATIC_ASSERT_LVALUE(Derived) - failes if \\a Derived is read-only.\n- \\b EIGEN_STATIC_ASSERT_ARRAYXPR(Derived) - passes if \\a Derived is an array expression.\n- <b>EIGEN_STATIC_ASSERT_SAME_XPR_KIND(Derived1, Derived2)</b> - failes if the two expressions are an array one and a matrix one.\n\nBecause Eigen handles both fixed-size and dynamic-size expressions, some conditions cannot be clearly determined at compile time. We classify them into strict assertions and permissive assertions.\n\n\\subsubsection StrictAssertions Strict assertions\n\nThese assertions fail if the condition <b>may not</b> be met. For example, MatrixXd may not be a vector, so it fails EIGEN_STATIC_ASSERT_VECTOR_ONLY.\n\n- \\b EIGEN_STATIC_ASSERT_VECTOR_ONLY(TYPE) - passes if \\a TYPE must be a vector type.\n- <b>EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(TYPE, SIZE)</b> - passes if \\a TYPE must be a vector of the given size.\n- <b>EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(TYPE, ROWS, COLS)</b> - passes if \\a TYPE must be a matrix with given rows and columns.\n\n\\subsubsection PermissiveAssertions Permissive assertions\n\nThese assertions fail if the condition \\b cannot be met. For example, MatrixXd and Matrix4d may have the same size, so they pass EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE.\n\n- \\b EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(TYPE0,TYPE1) - fails if the two vector expression types must have different sizes.\n- \\b EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(TYPE0,TYPE1) - fails if the two matrix expression types must have different sizes.\n- \\b EIGEN_STATIC_ASSERT_SIZE_1x1(TYPE) - fails if \\a TYPE cannot be an 1x1 expression.\n\nSee StaticAssert.h for details such as what messages they throw.\n\n\\subsection DisableStaticAssert Disabling static assertions\n\nIf \\c EIGEN_NO_STATIC_ASSERT is defined, static assertions turn into <tt>eigen_assert</tt>'s, working like:\n\n\\code\n#define EIGEN_STATIC_ASSERT(CONDITION,MSG) eigen_assert((CONDITION) && #MSG);\n\\endcode\n\nThis saves compile time but consumes more run time. \\c EIGEN_NO_STATIC_ASSERT is undefined by default.\n\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TopicCMakeGuide.dox",
    "content": "namespace Eigen {\n\n/**\n\n\\page TopicCMakeGuide Using %Eigen in CMake Projects\n\n%Eigen provides native CMake support which allows the library to be easily\nused in CMake projects.\n\n\\note %CMake 3.0 (or later) is required to enable this functionality.\n\n%Eigen exports a CMake target called `Eigen3::Eigen` which can be imported\nusing the `find_package` CMake command and used by calling\n`target_link_libraries` as in the following example:\n\\code{.cmake}\ncmake_minimum_required (VERSION 3.0)\nproject (myproject)\n\nfind_package (Eigen3 3.3 REQUIRED NO_MODULE)\n\nadd_executable (example example.cpp)\ntarget_link_libraries (example Eigen3::Eigen)\n\\endcode\n\nThe above code snippet must be placed in a file called `CMakeLists.txt` alongside\n`example.cpp`. After running\n\\code{.sh}\n$ cmake path-to-example-directory\n\\endcode\nCMake will produce project files that generate an executable called `example`\nwhich requires at least version 3.3 of %Eigen. Here, `path-to-example-directory`\nis the path to the directory that contains both `CMakeLists.txt` and\n`example.cpp`.\n\nDo not forget to set the <a href=\"https://cmake.org/cmake/help/v3.7/variable/CMAKE_PREFIX_PATH.html\">\\c CMAKE_PREFIX_PATH </a> variable if Eigen is not installed in a default location or if you want to pick a specific version. For instance:\n\\code{.sh}\n$ cmake path-to-example-directory -DCMAKE_PREFIX_PATH=$HOME/mypackages\n\\endcode\nAn alternative is to set the \\c Eigen3_DIR cmake's variable to the respective path containing the \\c Eigen3*.cmake files. For instance:\n\\code{.sh}\n$ cmake path-to-example-directory -DEigen3_DIR=$HOME/mypackages/share/eigen3/cmake/\n\\endcode\n\nIf the `REQUIRED` option is omitted when locating %Eigen using\n`find_package`, one can check whether the package was found as follows:\n\\code{.cmake}\nfind_package (Eigen3 3.3 NO_MODULE)\n\nif (TARGET Eigen3::Eigen)\n  # Use the imported target\nendif (TARGET Eigen3::Eigen)\n\\endcode\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TopicEigenExpressionTemplates.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicEigenExpressionTemplates Expression templates in Eigen\n\n\nTODO: write this dox page!\n\nIs linked from the tutorial on arithmetic ops.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TopicLazyEvaluation.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicLazyEvaluation Lazy Evaluation and Aliasing\n\nExecutive summary: %Eigen has intelligent compile-time mechanisms to enable lazy evaluation and removing temporaries where appropriate.\nIt will handle aliasing automatically in most cases, for example with matrix products. The automatic behavior can be overridden\nmanually by using the MatrixBase::eval() and MatrixBase::noalias() methods.\n\nWhen you write a line of code involving a complex expression such as\n\n\\code mat1 = mat2 + mat3 * (mat4 + mat5);\n\\endcode\n\n%Eigen determines automatically, for each sub-expression, whether to evaluate it into a temporary variable. Indeed, in certain cases it is better to evaluate a sub-expression into a temporary variable, while in other cases it is better to avoid that.\n\nA traditional math library without expression templates always evaluates all sub-expressions into temporaries. So with this code,\n\n\\code vec1 = vec2 + vec3;\n\\endcode\n\na traditional library would evaluate \\c vec2 + vec3 into a temporary \\c vec4 and then copy \\c vec4  into \\c vec1. This is of course inefficient: the arrays are traversed twice, so there are a lot of useless load/store operations.\n\nExpression-templates-based libraries can avoid evaluating sub-expressions into temporaries, which in many cases results in large speed improvements.\nThis is called <i>lazy evaluation</i> as an expression is getting evaluated as late as possible.\nIn %Eigen <b>all expressions are lazy-evaluated</b>.\nMore precisely, an expression starts to be evaluated once it is assigned to a matrix.\nUntil then nothing happens beyond constructing the abstract expression tree.\nIn contrast to most other expression-templates-based libraries, however, <b>%Eigen might choose to evaluate some sub-expressions into temporaries</b>.\nThere are two reasons for that: first, pure lazy evaluation is not always a good choice for performance; second, pure lazy evaluation can be very dangerous, for example with matrix products: doing <tt>mat = mat*mat</tt> gives a wrong result if the matrix product is directly evaluated within the destination matrix, because of the way matrix product works.\n\nFor these reasons, %Eigen has intelligent compile-time mechanisms to determine automatically which sub-expression should be evaluated into a temporary variable.\n\nSo in the basic example,\n\n\\code mat1 = mat2 + mat3;\n\\endcode\n\n%Eigen chooses not to introduce any temporary. Thus the arrays are traversed only once, producing optimized code.\nIf you really want to force immediate evaluation, use \\link MatrixBase::eval() eval()\\endlink:\n\n\\code mat1 = (mat2 + mat3).eval();\n\\endcode\n\nHere is now a more involved example:\n\n\\code mat1 = -mat2 + mat3 + 5 * mat4;\n\\endcode\n\nHere again %Eigen won't introduce any temporary, thus producing a single <b>fused</b> evaluation loop, which is clearly the correct choice.\n\n\\section TopicLazyEvaluationWhichExpr Which sub-expressions are evaluated into temporaries?\n\nThe default evaluation strategy is to fuse the operations in a single loop, and %Eigen will choose it except in a few circumstances.\n\n<b>The first circumstance</b> in which %Eigen chooses to evaluate a sub-expression is when it sees an assignment <tt>a = b;</tt> and the expression \\c b has the evaluate-before-assigning \\link flags flag\\endlink.\nThe most important example of such an expression is the \\link Product matrix product expression\\endlink. For example, when you do\n\n\\code mat = mat * mat;\n\\endcode\n\n%Eigen will evaluate <tt>mat * mat</tt> into a temporary matrix, and then copies it into the original \\c mat.\nThis guarantees a correct result as we saw above that lazy evaluation gives wrong results with matrix products.\nIt also doesn't cost much, as the cost of the matrix product itself is much higher.\nNote that this temporary is introduced at evaluation time only, that is, within operator= in this example.\nThe expression <tt>mat * mat</tt> still return a abstract product type.\n\nWhat if you know that the result does no alias the operand of the product and want to force lazy evaluation? Then use \\link MatrixBase::noalias() .noalias()\\endlink instead. Here is an example:\n\n\\code mat1.noalias() = mat2 * mat2;\n\\endcode\n\nHere, since we know that mat2 is not the same matrix as mat1, we know that lazy evaluation is not dangerous, so we may force lazy evaluation. Concretely, the effect of noalias() here is to bypass the evaluate-before-assigning \\link flags flag\\endlink.\n\n<b>The second circumstance</b> in which %Eigen chooses to evaluate a sub-expression, is when it sees a nested expression such as <tt>a + b</tt> where \\c b is already an expression having the evaluate-before-nesting \\link flags flag\\endlink.\nAgain, the most important example of such an expression is the \\link Product matrix product expression\\endlink.\nFor example, when you do\n\n\\code mat1 = mat2 * mat3 + mat4 * mat5;\n\\endcode\n\nthe products <tt>mat2 * mat3</tt> and <tt>mat4 * mat5</tt> gets evaluated separately into temporary matrices before being summed up in <tt>mat1</tt>.\nIndeed, to be efficient matrix products need to be evaluated within a destination matrix at hand, and not as simple \"dot products\".\nFor small matrices, however, you might want to enforce a \"dot-product\" based lazy evaluation with lazyProduct().\nAgain, it is important to understand that those temporaries are created at evaluation time only, that is in operator =.\nSee TopicPitfalls_auto_keyword for common pitfalls regarding this remark.\n\n<b>The third circumstance</b> in which %Eigen chooses to evaluate a sub-expression, is when its cost model shows that the total cost of an operation is reduced if a sub-expression gets evaluated into a temporary.\nIndeed, in certain cases, an intermediate result is sufficiently costly to compute and is reused sufficiently many times, that is worth \"caching\". Here is an example:\n\n\\code mat1 = mat2 * (mat3 + mat4);\n\\endcode\n\nHere, provided the matrices have at least 2 rows and 2 columns, each coefficient of the expression <tt>mat3 + mat4</tt> is going to be used several times in the matrix product. Instead of computing the sum every time, it is much better to compute it once and store it in a temporary variable. %Eigen understands this and evaluates <tt>mat3 + mat4</tt> into a temporary variable before evaluating the product.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TopicLinearAlgebraDecompositions.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TopicLinearAlgebraDecompositions Catalogue of dense decompositions\n\nThis page presents a catalogue of the dense matrix decompositions offered by Eigen.\nFor an introduction on linear solvers and decompositions, check this \\link TutorialLinearAlgebra page \\endlink.\nTo get an overview of the true relative speed of the different decompositions, check this \\link DenseDecompositionBenchmark benchmark \\endlink.\n\n\\section TopicLinAlgBigTable Catalogue of decompositions offered by Eigen\n\n<table class=\"manual-vl\">\n    <tr>\n        <th class=\"meta\"></th>\n        <th class=\"meta\" colspan=\"5\">Generic information, not Eigen-specific</th>\n        <th class=\"meta\" colspan=\"3\">Eigen-specific</th>\n    </tr>\n\n    <tr>\n        <th>Decomposition</th>\n        <th>Requirements on the matrix</th>\n        <th>Speed</th>\n        <th>Algorithm reliability and accuracy</th>\n        <th>Rank-revealing</th>\n        <th>Allows to compute (besides linear solving)</th>\n        <th>Linear solver provided by Eigen</th>\n        <th>Maturity of Eigen's implementation</th>\n        <th>Optimizations</th>\n    </tr>\n\n    <tr>\n        <td>PartialPivLU</td>\n        <td>Invertible</td>\n        <td>Fast</td>\n        <td>Depends on condition number</td>\n        <td>-</td>\n        <td>-</td>\n        <td>Yes</td>\n        <td>Excellent</td>\n        <td>Blocking, Implicit MT</td>\n    </tr>\n\n    <tr class=\"alt\">\n        <td>FullPivLU</td>\n        <td>-</td>\n        <td>Slow</td>\n        <td>Proven</td>\n        <td>Yes</td>\n        <td>-</td>\n        <td>Yes</td>\n        <td>Excellent</td>\n        <td>-</td>\n    </tr>\n\n    <tr>\n        <td>HouseholderQR</td>\n        <td>-</td>\n        <td>Fast</td>\n        <td>Depends on condition number</td>\n        <td>-</td>\n        <td>Orthogonalization</td>\n        <td>Yes</td>\n        <td>Excellent</td>\n        <td>Blocking</td>\n    </tr>\n\n    <tr class=\"alt\">\n        <td>ColPivHouseholderQR</td>\n        <td>-</td>\n        <td>Fast</td>\n        <td>Good</td>\n        <td>Yes</td>\n        <td>Orthogonalization</td>\n        <td>Yes</td>\n        <td>Excellent</td>\n        <td><em>-</em></td>\n    </tr>\n\n    <tr>\n        <td>FullPivHouseholderQR</td>\n        <td>-</td>\n        <td>Slow</td>\n        <td>Proven</td>\n        <td>Yes</td>\n        <td>Orthogonalization</td>\n        <td>Yes</td>\n        <td>Average</td>\n        <td>-</td>\n    </tr>\n\n    <tr class=\"alt\">\n        <td>CompleteOrthogonalDecomposition</td>\n        <td>-</td>\n        <td>Fast</td>\n        <td>Good</td>\n        <td>Yes</td>\n        <td>Orthogonalization</td>\n        <td>Yes</td>\n        <td>Excellent</td>\n        <td><em>-</em></td>\n    </tr>\n\n    <tr>\n        <td>LLT</td>\n        <td>Positive definite</td>\n        <td>Very fast</td>\n        <td>Depends on condition number</td>\n        <td>-</td>\n        <td>-</td>\n        <td>Yes</td>\n        <td>Excellent</td>\n        <td>Blocking</td>\n    </tr>\n\n    <tr class=\"alt\">\n        <td>LDLT</td>\n        <td>Positive or negative semidefinite<sup><a href=\"#note1\">1</a></sup></td>\n        <td>Very fast</td>\n        <td>Good</td>\n        <td>-</td>\n        <td>-</td>\n        <td>Yes</td>\n        <td>Excellent</td>\n        <td><em>Soon: blocking</em></td>\n    </tr>\n\n    <tr><th class=\"inter\" colspan=\"9\">\\n Singular values and eigenvalues decompositions</th></tr>\n\n    <tr>\n        <td>BDCSVD (divide \\& conquer)</td>\n        <td>-</td>\n        <td>One of the fastest SVD algorithms</td>\n        <td>Excellent</td>\n        <td>Yes</td>\n        <td>Singular values/vectors, least squares</td>\n        <td>Yes (and does least squares)</td>\n        <td>Excellent</td>\n        <td>Blocked bidiagonalization</td>\n    </tr>\n\n    <tr>\n        <td>JacobiSVD (two-sided)</td>\n        <td>-</td>\n        <td>Slow (but fast for small matrices)</td>\n        <td>Proven<sup><a href=\"#note3\">3</a></sup></td>\n        <td>Yes</td>\n        <td>Singular values/vectors, least squares</td>\n        <td>Yes (and does least squares)</td>\n        <td>Excellent</td>\n        <td>R-SVD</td>\n    </tr>\n\n    <tr class=\"alt\">\n        <td>SelfAdjointEigenSolver</td>\n        <td>Self-adjoint</td>\n        <td>Fast-average<sup><a href=\"#note2\">2</a></sup></td>\n        <td>Good</td>\n        <td>Yes</td>\n        <td>Eigenvalues/vectors</td>\n        <td>-</td>\n        <td>Excellent</td>\n        <td><em>Closed forms for 2x2 and 3x3</em></td>\n    </tr>\n\n    <tr>\n        <td>ComplexEigenSolver</td>\n        <td>Square</td>\n        <td>Slow-very slow<sup><a href=\"#note2\">2</a></sup></td>\n        <td>Depends on condition number</td>\n        <td>Yes</td>\n        <td>Eigenvalues/vectors</td>\n        <td>-</td>\n        <td>Average</td>\n        <td>-</td>\n    </tr>\n\n    <tr class=\"alt\">\n        <td>EigenSolver</td>\n        <td>Square and real</td>\n        <td>Average-slow<sup><a href=\"#note2\">2</a></sup></td>\n        <td>Depends on condition number</td>\n        <td>Yes</td>\n        <td>Eigenvalues/vectors</td>\n        <td>-</td>\n        <td>Average</td>\n        <td>-</td>\n    </tr>\n\n    <tr>\n        <td>GeneralizedSelfAdjointEigenSolver</td>\n        <td>Square</td>\n        <td>Fast-average<sup><a href=\"#note2\">2</a></sup></td>\n        <td>Depends on condition number</td>\n        <td>-</td>\n        <td>Generalized eigenvalues/vectors</td>\n        <td>-</td>\n        <td>Good</td>\n        <td>-</td>\n    </tr>\n\n    <tr><th class=\"inter\" colspan=\"9\">\\n Helper decompositions</th></tr>\n\n    <tr>\n        <td>RealSchur</td>\n        <td>Square and real</td>\n        <td>Average-slow<sup><a href=\"#note2\">2</a></sup></td>\n        <td>Depends on condition number</td>\n        <td>Yes</td>\n        <td>-</td>\n        <td>-</td>\n        <td>Average</td>\n        <td>-</td>\n    </tr>\n\n    <tr class=\"alt\">\n        <td>ComplexSchur</td>\n        <td>Square</td>\n        <td>Slow-very slow<sup><a href=\"#note2\">2</a></sup></td>\n        <td>Depends on condition number</td>\n        <td>Yes</td>\n        <td>-</td>\n        <td>-</td>\n        <td>Average</td>\n        <td>-</td>\n    </tr>\n\n    <tr class=\"alt\">\n        <td>Tridiagonalization</td>\n        <td>Self-adjoint</td>\n        <td>Fast</td>\n        <td>Good</td>\n        <td>-</td>\n        <td>-</td>\n        <td>-</td>\n        <td>Good</td>\n        <td><em>Soon: blocking</em></td>\n    </tr>\n\n    <tr>\n        <td>HessenbergDecomposition</td>\n        <td>Square</td>\n        <td>Average</td>\n        <td>Good</td>\n        <td>-</td>\n        <td>-</td>\n        <td>-</td>\n        <td>Good</td>\n        <td><em>Soon: blocking</em></td>\n    </tr>\n\n</table>\n\n\\b Notes:\n<ul>\n<li><a name=\"note1\">\\b 1: </a>There exist two variants of the LDLT algorithm. Eigen's one produces a pure diagonal D matrix, and therefore it cannot handle indefinite matrices, unlike Lapack's one which produces a block diagonal D matrix.</li>\n<li><a name=\"note2\">\\b 2: </a>Eigenvalues, SVD and Schur decompositions rely on iterative algorithms. Their convergence speed depends on how well the eigenvalues are separated.</li>\n<li><a name=\"note3\">\\b 3: </a>Our JacobiSVD is two-sided, making for proven and optimal precision for square matrices. For non-square matrices, we have to use a QR preconditioner first. The default choice, ColPivHouseholderQR, is already very reliable, but if you want it to be proven, use FullPivHouseholderQR instead.\n</ul>\n\n\\section TopicLinAlgTerminology Terminology\n\n<dl>\n  <dt><b>Selfadjoint</b></dt>\n    <dd>For a real matrix, selfadjoint is a synonym for symmetric. For a complex matrix, selfadjoint is a synonym for \\em hermitian.\n        More generally, a matrix \\f$ A \\f$ is selfadjoint if and only if it is equal to its adjoint \\f$ A^* \\f$. The adjoint is also called the \\em conjugate \\em transpose. </dd>\n  <dt><b>Positive/negative definite</b></dt>\n    <dd>A selfadjoint matrix \\f$ A \\f$ is positive definite if \\f$ v^* A v > 0 \\f$ for any non zero vector \\f$ v \\f$.\n        In the same vein, it is negative definite if \\f$ v^* A v < 0 \\f$ for any non zero vector \\f$ v \\f$ </dd>\n  <dt><b>Positive/negative semidefinite</b></dt>\n    <dd>A selfadjoint matrix \\f$ A \\f$ is positive semi-definite if \\f$ v^* A v \\ge 0 \\f$ for any non zero vector \\f$ v \\f$.\n        In the same vein, it is negative semi-definite if \\f$ v^* A v \\le 0 \\f$ for any non zero vector \\f$ v \\f$ </dd>\n\n  <dt><b>Blocking</b></dt>\n    <dd>Means the algorithm can work per block, whence guaranteeing a good scaling of the performance for large matrices.</dd>\n  <dt><b>Implicit Multi Threading (MT)</b></dt>\n    <dd>Means the algorithm can take advantage of multicore processors via OpenMP. \"Implicit\" means the algortihm itself is not parallelized, but that it relies on parallelized matrix-matrix product routines.</dd>\n  <dt><b>Explicit Multi Threading (MT)</b></dt>\n    <dd>Means the algorithm is explicitly parallelized to take advantage of multicore processors via OpenMP.</dd>\n  <dt><b>Meta-unroller</b></dt>\n    <dd>Means the algorithm is automatically and explicitly unrolled for very small fixed size matrices.</dd>\n  <dt><b></b></dt>\n    <dd></dd>\n</dl>\n\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TopicMultithreading.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicMultiThreading Eigen and multi-threading\n\n\\section TopicMultiThreading_MakingEigenMT Make Eigen run in parallel\n\nSome %Eigen's algorithms can exploit the multiple cores present in your hardware.\nTo this end, it is enough to enable OpenMP on your compiler, for instance:\n - GCC: \\c -fopenmp\n - ICC: \\c -openmp\n - MSVC: check the respective option in the build properties.\n\nYou can control the number of threads that will be used using either the OpenMP API or %Eigen's API using the following priority:\n\\code\n OMP_NUM_THREADS=n ./my_program\n omp_set_num_threads(n);\n Eigen::setNbThreads(n);\n\\endcode\nUnless `setNbThreads` has been called, %Eigen uses the number of threads specified by OpenMP.\nYou can restore this behavior by calling `setNbThreads(0);`.\nYou can query the number of threads that will be used with:\n\\code\nn = Eigen::nbThreads( );\n\\endcode\nYou can disable %Eigen's multi threading at compile time by defining the \\link TopicPreprocessorDirectivesPerformance EIGEN_DONT_PARALLELIZE \\endlink preprocessor token.\n\nCurrently, the following algorithms can make use of multi-threading:\n - general dense matrix - matrix products\n - PartialPivLU\n - row-major-sparse * dense vector/matrix products\n - ConjugateGradient with \\c Lower|Upper as the \\c UpLo template parameter.\n - BiCGSTAB with a row-major sparse matrix format.\n - LeastSquaresConjugateGradient\n\n\\warning On most OS it is <strong>very important</strong> to limit the number of threads to the number of physical cores, otherwise significant slowdowns are expected, especially for operations involving dense matrices.\n\nIndeed, the principle of hyper-threading is to run multiple threads (in most cases 2) on a single core in an interleaved manner.\nHowever, %Eigen's matrix-matrix product kernel is fully optimized and already exploits nearly 100% of the CPU capacity.\nConsequently, there is no room for running multiple such threads on a single core, and the performance would drops significantly because of cache pollution and other sources of overheads.\nAt this stage of reading you're probably wondering why %Eigen does not limit itself to the number of physical cores?\nThis is simply because OpenMP does not allow to know the number of physical cores, and thus %Eigen will launch as many threads as <i>cores</i> reported by OpenMP.\n\n\\section TopicMultiThreading_UsingEigenWithMT Using Eigen in a multi-threaded application\n\nIn the case your own application is multithreaded, and multiple threads make calls to %Eigen, then you have to initialize %Eigen by calling the following routine \\b before creating the threads:\n\\code\n#include <Eigen/Core>\n\nint main(int argc, char** argv)\n{\n  Eigen::initParallel();\n  \n  ...\n}\n\\endcode\n\n\\note With %Eigen 3.3, and a fully C++11 compliant compiler (i.e., <a href=\"http://en.cppreference.com/w/cpp/language/storage_duration#Static_local_variables\">thread-safe static local variable initialization</a>), then calling \\c initParallel() is optional.\n\n\\warning Note that all functions generating random matrices are \\b not re-entrant nor thread-safe. Those include DenseBase::Random(), and DenseBase::setRandom() despite a call to `Eigen::initParallel()`. This is because these functions are based on `std::rand` which is not re-entrant.\nFor thread-safe random generator, we recommend the use of c++11 random generators (\\link DenseBase::NullaryExpr(Index, const CustomNullaryOp&) example \\endlink) or `boost::random`.\n\nIn the case your application is parallelized with OpenMP, you might want to disable %Eigen's own parallelization as detailed in the previous section.\n\n\\warning Using OpenMP with custom scalar types that might throw exceptions can lead to unexpected behaviour in the event of throwing.\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TopicResizing.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicResizing Resizing\n\n\nTODO: write this dox page!\n\nIs linked from the tutorial on the Matrix class.\n\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TopicScalarTypes.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicScalarTypes Scalar types\n\n\nTODO: write this dox page!\n\nIs linked from the tutorial on the Matrix class.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TopicVectorization.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicVectorization Vectorization\n\n\nTODO: write this dox page!\n\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TutorialAdvancedInitialization.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialAdvancedInitialization Advanced initialization\n\nThis page discusses several advanced methods for initializing matrices. It gives more details on the\ncomma-initializer, which was introduced before. It also explains how to get special matrices such as the\nidentity matrix and the zero matrix.\n\n\\eigenAutoToc\n\n\\section TutorialAdvancedInitializationCommaInitializer The comma initializer\n\nEigen offers a comma initializer syntax which allows the user to easily set all the coefficients of a matrix,\nvector or array. Simply list the coefficients, starting at the top-left corner and moving from left to right\nand from the top to the bottom. The size of the object needs to be specified beforehand. If you list too few\nor too many coefficients, Eigen will complain.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_commainit_01.cpp\n</td>\n<td>\n\\verbinclude Tutorial_commainit_01.out\n</td></tr></table>\n\nMoreover, the elements of the initialization list may themselves be vectors or matrices. A common use is\nto join vectors or matrices together. For example, here is how to join two row vectors together. Remember\nthat you have to set the size before you can use the comma initializer.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_AdvancedInitialization_Join.cpp\n</td>\n<td>\n\\verbinclude Tutorial_AdvancedInitialization_Join.out\n</td></tr></table>\n\nWe can use the same technique to initialize matrices with a block structure.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_AdvancedInitialization_Block.cpp\n</td>\n<td>\n\\verbinclude Tutorial_AdvancedInitialization_Block.out\n</td></tr></table>\n\nThe comma initializer can also be used to fill block expressions such as <tt>m.row(i)</tt>. Here is a more\ncomplicated way to get the same result as in the first example above:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_commainit_01b.cpp\n</td>\n<td>\n\\verbinclude Tutorial_commainit_01b.out\n</td></tr></table>\n\n\n\\section TutorialAdvancedInitializationSpecialMatrices Special matrices and arrays\n\nThe Matrix and Array classes have static methods like \\link DenseBase::Zero() Zero()\\endlink, which can be\nused to initialize all coefficients to zero. There are three variants. The first variant takes no arguments\nand can only be used for fixed-size objects. If you want to initialize a dynamic-size object to zero, you need\nto specify the size. Thus, the second variant requires one argument and can be used for one-dimensional\ndynamic-size objects, while the third variant requires two arguments and can be used for two-dimensional\nobjects. All three variants are illustrated in the following example:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_AdvancedInitialization_Zero.cpp\n</td>\n<td>\n\\verbinclude Tutorial_AdvancedInitialization_Zero.out\n</td></tr></table>\n\nSimilarly, the static method \\link DenseBase::Constant() Constant\\endlink(value) sets all coefficients to \\c value.\nIf the size of the object needs to be specified, the additional arguments go before the \\c value\nargument, as in <tt>MatrixXd::Constant(rows, cols, value)</tt>. The method \\link DenseBase::Random() Random()\n\\endlink fills the matrix or array with random coefficients. The identity matrix can be obtained by calling\n\\link MatrixBase::Identity() Identity()\\endlink; this method is only available for Matrix, not for Array,\nbecause \"identity matrix\" is a linear algebra concept.  The method\n\\link DenseBase::LinSpaced LinSpaced\\endlink(size, low, high) is only available for vectors and\none-dimensional arrays; it yields a vector of the specified size whose coefficients are equally spaced between\n\\c low and \\c high. The method \\c LinSpaced() is illustrated in the following example, which prints a table\nwith angles in degrees, the corresponding angle in radians, and their sine and cosine.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_AdvancedInitialization_LinSpaced.cpp\n</td>\n<td>\n\\verbinclude Tutorial_AdvancedInitialization_LinSpaced.out\n</td></tr></table>\n\nThis example shows that objects like the ones returned by LinSpaced() can be assigned to variables (and\nexpressions). Eigen defines utility functions like \\link DenseBase::setZero() setZero()\\endlink, \n\\link MatrixBase::setIdentity() \\endlink and \\link DenseBase::setLinSpaced() \\endlink to do this\nconveniently. The following example contrasts three ways to construct the matrix\n\\f$ J = \\bigl[ \\begin{smallmatrix} O & I \\\\ I & O \\end{smallmatrix} \\bigr] \\f$: using static methods and\nassignment, using static methods and the comma-initializer, or using the setXxx() methods.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_AdvancedInitialization_ThreeWays.cpp\n</td>\n<td>\n\\verbinclude Tutorial_AdvancedInitialization_ThreeWays.out\n</td></tr></table>\n\nA summary of all pre-defined matrix, vector and array objects can be found in the \\ref QuickRefPage.\n\n\n\\section TutorialAdvancedInitializationTemporaryObjects Usage as temporary objects\n\nAs shown above, static methods as Zero() and Constant() can be used to initialize variables at the time of\ndeclaration or at the right-hand side of an assignment operator. You can think of these methods as returning a\nmatrix or array; in fact, they return so-called \\ref TopicEigenExpressionTemplates \"expression objects\" which\nevaluate to a matrix or array when needed, so that this syntax does not incur any overhead.\n\nThese expressions can also be used as a temporary object. The second example in\nthe \\ref GettingStarted guide, which we reproduce here, already illustrates this.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include QuickStart_example2_dynamic.cpp\n</td>\n<td>\n\\verbinclude QuickStart_example2_dynamic.out\n</td></tr></table>\n\nThe expression <tt>m + MatrixXf::Constant(3,3,1.2)</tt> constructs the 3-by-3 matrix expression with all its coefficients\nequal to 1.2 plus the corresponding coefficient of \\a m.\n\nThe comma-initializer, too, can also be used to construct temporary objects. The following example constructs a random\nmatrix of size 2-by-3, and then multiplies this matrix on the left with \n\\f$ \\bigl[ \\begin{smallmatrix} 0 & 1 \\\\ 1 & 0 \\end{smallmatrix} \\bigr] \\f$.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_AdvancedInitialization_CommaTemporary.cpp\n</td>\n<td>\n\\verbinclude Tutorial_AdvancedInitialization_CommaTemporary.out\n</td></tr></table>\n\nThe \\link CommaInitializer::finished() finished() \\endlink method is necessary here to get the actual matrix\nobject once the comma initialization of our temporary submatrix is done.\n\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TutorialArrayClass.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialArrayClass The Array class and coefficient-wise operations\n\nThis page aims to provide an overview and explanations on how to use\nEigen's Array class.\n\n\\eigenAutoToc\n  \n\\section TutorialArrayClassIntro What is the Array class?\n\nThe Array class provides general-purpose arrays, as opposed to the Matrix class which\nis intended for linear algebra. Furthermore, the Array class provides an easy way to\nperform coefficient-wise operations, which might not have a linear algebraic meaning,\nsuch as adding a constant to every coefficient in the array or multiplying two arrays coefficient-wise.\n\n\n\\section TutorialArrayClassTypes Array types\nArray is a class template taking the same template parameters as Matrix.\nAs with Matrix, the first three template parameters are mandatory:\n\\code\nArray<typename Scalar, int RowsAtCompileTime, int ColsAtCompileTime>\n\\endcode\nThe last three template parameters are optional. Since this is exactly the same as for Matrix,\nwe won't explain it again here and just refer to \\ref TutorialMatrixClass.\n\nEigen also provides typedefs for some common cases, in a way that is similar to the Matrix typedefs\nbut with some slight differences, as the word \"array\" is used for both 1-dimensional and 2-dimensional arrays.\nWe adopt the convention that typedefs of the form ArrayNt stand for 1-dimensional arrays, where N and t are\nthe size and the scalar type, as in the Matrix typedefs explained on \\ref TutorialMatrixClass \"this page\". For 2-dimensional arrays, we\nuse typedefs of the form ArrayNNt. Some examples are shown in the following table:\n\n<table class=\"manual\">\n  <tr>\n    <th>Type </th>\n    <th>Typedef </th>\n  </tr>\n  <tr>\n    <td> \\code Array<float,Dynamic,1> \\endcode </td>\n    <td> \\code ArrayXf \\endcode </td>\n  </tr>\n  <tr>\n    <td> \\code Array<float,3,1> \\endcode </td>\n    <td> \\code Array3f \\endcode </td>\n  </tr>\n  <tr>\n    <td> \\code Array<double,Dynamic,Dynamic> \\endcode </td>\n    <td> \\code ArrayXXd \\endcode </td>\n  </tr>\n  <tr>\n    <td> \\code Array<double,3,3> \\endcode </td>\n    <td> \\code Array33d \\endcode </td>\n  </tr>\n</table>\n\n\n\\section TutorialArrayClassAccess Accessing values inside an Array\n\nThe parenthesis operator is overloaded to provide write and read access to the coefficients of an array, just as with matrices.\nFurthermore, the \\c << operator can be used to initialize arrays (via the comma initializer) or to print them.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ArrayClass_accessors.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ArrayClass_accessors.out\n</td></tr></table>\n\nFor more information about the comma initializer, see \\ref TutorialAdvancedInitialization.\n\n\n\\section TutorialArrayClassAddSub Addition and subtraction\n\nAdding and subtracting two arrays is the same as for matrices.\nThe operation is valid if both arrays have the same size, and the addition or subtraction is done coefficient-wise.\n\nArrays also support expressions of the form <tt>array + scalar</tt> which add a scalar to each coefficient in the array.\nThis provides a functionality that is not directly available for Matrix objects.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ArrayClass_addition.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ArrayClass_addition.out\n</td></tr></table>\n\n\n\\section TutorialArrayClassMult Array multiplication\n\nFirst of all, of course you can multiply an array by a scalar, this works in the same way as matrices. Where arrays\nare fundamentally different from matrices, is when you multiply two together. Matrices interpret\nmultiplication as matrix product and arrays interpret multiplication as coefficient-wise product. Thus, two \narrays can be multiplied if and only if they have the same dimensions.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ArrayClass_mult.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ArrayClass_mult.out\n</td></tr></table>\n\n\n\\section TutorialArrayClassCwiseOther Other coefficient-wise operations\n\nThe Array class defines other coefficient-wise operations besides the addition, subtraction and multiplication\noperators described above. For example, the \\link ArrayBase::abs() .abs() \\endlink method takes the absolute\nvalue of each coefficient, while \\link ArrayBase::sqrt() .sqrt() \\endlink computes the square root of the\ncoefficients. If you have two arrays of the same size, you can call \\link ArrayBase::min(const Eigen::ArrayBase<OtherDerived>&) const .min(.) \\endlink to\nconstruct the array whose coefficients are the minimum of the corresponding coefficients of the two given\narrays. These operations are illustrated in the following example.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ArrayClass_cwise_other.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ArrayClass_cwise_other.out\n</td></tr></table>\n\nMore coefficient-wise operations can be found in the \\ref QuickRefPage.\n\n\n\\section TutorialArrayClassConvert Converting between array and matrix expressions\n\nWhen should you use objects of the Matrix class and when should you use objects of the Array class? You cannot\napply Matrix operations on arrays, or Array operations on matrices. Thus, if you need to do linear algebraic\noperations such as matrix multiplication, then you should use matrices; if you need to do coefficient-wise\noperations, then you should use arrays. However, sometimes it is not that simple, but you need to use both\nMatrix and Array operations. In that case, you need to convert a matrix to an array or reversely. This gives\naccess to all operations regardless of the choice of declaring objects as arrays or as matrices.\n\n\\link MatrixBase Matrix expressions \\endlink have an \\link MatrixBase::array() .array() \\endlink method that\n'converts' them into \\link ArrayBase array expressions\\endlink, so that coefficient-wise operations\ncan be applied easily. Conversely, \\link ArrayBase array expressions \\endlink\nhave a \\link ArrayBase::matrix() .matrix() \\endlink method. As with all Eigen expression abstractions,\nthis doesn't have any runtime cost (provided that you let your compiler optimize).\nBoth \\link MatrixBase::array() .array() \\endlink and \\link ArrayBase::matrix() .matrix() \\endlink \ncan be used as rvalues and as lvalues.\n\nMixing matrices and arrays in an expression is forbidden with Eigen. For instance, you cannot add a matrix and\narray directly; the operands of a \\c + operator should either both be matrices or both be arrays. However,\nit is easy to convert from one to the other with \\link MatrixBase::array() .array() \\endlink and \n\\link ArrayBase::matrix() .matrix()\\endlink. The exception to this rule is the assignment operator: it is\nallowed to assign a matrix expression to an array variable, or to assign an array expression to a matrix\nvariable.\n\nThe following example shows how to use array operations on a Matrix object by employing the \n\\link MatrixBase::array() .array() \\endlink method. For example, the statement \n<tt>result = m.array() * n.array()</tt> takes two matrices \\c m and \\c n, converts them both to an array, uses\n* to multiply them coefficient-wise and assigns the result to the matrix variable \\c result (this is legal\nbecause Eigen allows assigning array expressions to matrix variables). \n\nAs a matter of fact, this usage case is so common that Eigen provides a \\link MatrixBase::cwiseProduct const\n.cwiseProduct(.) \\endlink method for matrices to compute the coefficient-wise product. This is also shown in\nthe example program.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ArrayClass_interop_matrix.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ArrayClass_interop_matrix.out\n</td></tr></table>\n\nSimilarly, if \\c array1 and \\c array2 are arrays, then the expression <tt>array1.matrix() * array2.matrix()</tt>\ncomputes their matrix product.\n\nHere is a more advanced example. The expression <tt>(m.array() + 4).matrix() * m</tt> adds 4 to every\ncoefficient in the matrix \\c m and then computes the matrix product of the result with \\c m. Similarly, the\nexpression <tt>(m.array() * n.array()).matrix() * m</tt> computes the coefficient-wise product of the matrices\n\\c m and \\c n and then the matrix product of the result with \\c m.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ArrayClass_interop.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ArrayClass_interop.out\n</td></tr></table>\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TutorialBlockOperations.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialBlockOperations Block operations\n\nThis page explains the essentials of block operations.\nA block is a rectangular part of a matrix or array. Blocks expressions can be used both\nas rvalues and as lvalues. As usual with Eigen expressions, this abstraction has zero runtime cost\nprovided that you let your compiler optimize.\n\n\\eigenAutoToc\n\n\\section TutorialBlockOperationsUsing Using block operations\n\nThe most general block operation in Eigen is called \\link DenseBase::block() .block() \\endlink.\nThere are two versions, whose syntax is as follows:\n\n<table class=\"manual\">\n<tr><th>\\b %Block \\b operation</td>\n<th>Version constructing a \\n dynamic-size block expression</th>\n<th>Version constructing a \\n fixed-size block expression</th></tr>\n<tr><td>%Block of size <tt>(p,q)</tt>, starting at <tt>(i,j)</tt></td>\n    <td>\\code\nmatrix.block(i,j,p,q);\\endcode </td>\n    <td>\\code \nmatrix.block<p,q>(i,j);\\endcode </td>\n</tr>\n</table>\n\nAs always in Eigen, indices start at 0.\n\nBoth versions can be used on fixed-size and dynamic-size matrices and arrays.\nThese two expressions are semantically equivalent.\nThe only difference is that the fixed-size version will typically give you faster code if the block size is small,\nbut requires this size to be known at compile time.\n\nThe following program uses the dynamic-size and fixed-size versions to print the values of several blocks inside a\nmatrix.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_BlockOperations_print_block.cpp\n</td>\n<td>\n\\verbinclude Tutorial_BlockOperations_print_block.out\n</td></tr></table>\n\nIn the above example the \\link DenseBase::block() .block() \\endlink function was employed as a \\em rvalue, i.e.\nit was only read from. However, blocks can also be used as \\em lvalues, meaning that you can assign to a block.\n\nThis is illustrated in the following example. This example also demonstrates blocks in arrays, which works exactly like the above-demonstrated blocks in matrices.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_BlockOperations_block_assignment.cpp\n</td>\n<td>\n\\verbinclude Tutorial_BlockOperations_block_assignment.out\n</td></tr></table>\n\nWhile the \\link DenseBase::block() .block() \\endlink method can be used for any block operation, there are\nother methods for special cases, providing more specialized API and/or better performance. On the topic of performance, all what\nmatters is that you give Eigen as much information as possible at compile time. For example, if your block is a single whole column in a matrix,\nusing the specialized \\link DenseBase::col() .col() \\endlink function described below lets Eigen know that, which can give it optimization opportunities.\n\nThe rest of this page describes these specialized methods.\n\n\\section TutorialBlockOperationsSyntaxColumnRows Columns and rows\n\nIndividual columns and rows are special cases of blocks. Eigen provides methods to easily address them:\n\\link DenseBase::col() .col() \\endlink and \\link DenseBase::row() .row()\\endlink.\n\n<table class=\"manual\">\n<tr><th>%Block operation</th>\n<th>Method</th>\n<tr><td>i<sup>th</sup> row\n                    \\link DenseBase::row() * \\endlink</td>\n    <td>\\code\nmatrix.row(i);\\endcode </td>\n</tr>\n<tr><td>j<sup>th</sup> column\n                    \\link DenseBase::col() * \\endlink</td>\n    <td>\\code\nmatrix.col(j);\\endcode </td>\n</tr>\n</table>\n\nThe argument for \\p col() and \\p row() is the index of the column or row to be accessed. As always in Eigen, indices start at 0.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_BlockOperations_colrow.cpp\n</td>\n<td>\n\\verbinclude Tutorial_BlockOperations_colrow.out\n</td></tr></table>\n\nThat example also demonstrates that block expressions (here columns) can be used in arithmetic like any other expression.\n\n\n\\section TutorialBlockOperationsSyntaxCorners Corner-related operations\n\nEigen also provides special methods for blocks that are flushed against one of the corners or sides of a\nmatrix or array. For instance, \\link DenseBase::topLeftCorner() .topLeftCorner() \\endlink can be used to refer\nto a block in the top-left corner of a matrix.\n\nThe different possibilities are summarized in the following table:\n\n<table class=\"manual\">\n<tr><th>%Block \\b operation</td>\n<th>Version constructing a \\n dynamic-size block expression</th>\n<th>Version constructing a \\n fixed-size block expression</th></tr>\n<tr><td>Top-left p by q block \\link DenseBase::topLeftCorner() * \\endlink</td>\n    <td>\\code\nmatrix.topLeftCorner(p,q);\\endcode </td>\n    <td>\\code \nmatrix.topLeftCorner<p,q>();\\endcode </td>\n</tr>\n<tr><td>Bottom-left p by q block\n              \\link DenseBase::bottomLeftCorner() * \\endlink</td>\n    <td>\\code\nmatrix.bottomLeftCorner(p,q);\\endcode </td>\n    <td>\\code \nmatrix.bottomLeftCorner<p,q>();\\endcode </td>\n</tr>\n<tr><td>Top-right p by q block\n              \\link DenseBase::topRightCorner() * \\endlink</td>\n    <td>\\code\nmatrix.topRightCorner(p,q);\\endcode </td>\n    <td>\\code \nmatrix.topRightCorner<p,q>();\\endcode </td>\n</tr>\n<tr><td>Bottom-right p by q block\n               \\link DenseBase::bottomRightCorner() * \\endlink</td>\n    <td>\\code\nmatrix.bottomRightCorner(p,q);\\endcode </td>\n    <td>\\code \nmatrix.bottomRightCorner<p,q>();\\endcode </td>\n</tr>\n<tr><td>%Block containing the first q rows\n                   \\link DenseBase::topRows() * \\endlink</td>\n    <td>\\code\nmatrix.topRows(q);\\endcode </td>\n    <td>\\code \nmatrix.topRows<q>();\\endcode </td>\n</tr>\n<tr><td>%Block containing the last q rows\n                    \\link DenseBase::bottomRows() * \\endlink</td>\n    <td>\\code\nmatrix.bottomRows(q);\\endcode </td>\n    <td>\\code \nmatrix.bottomRows<q>();\\endcode </td>\n</tr>\n<tr><td>%Block containing the first p columns\n                    \\link DenseBase::leftCols() * \\endlink</td>\n    <td>\\code\nmatrix.leftCols(p);\\endcode </td>\n    <td>\\code \nmatrix.leftCols<p>();\\endcode </td>\n</tr>\n<tr><td>%Block containing the last q columns\n                    \\link DenseBase::rightCols() * \\endlink</td>\n    <td>\\code\nmatrix.rightCols(q);\\endcode </td>\n    <td>\\code \nmatrix.rightCols<q>();\\endcode </td>\n</tr>\n<tr><td>%Block containing the q columns starting from i\n                    \\link DenseBase::middleCols() * \\endlink</td>\n    <td>\\code\nmatrix.middleCols(i,q);\\endcode </td>\n    <td>\\code \nmatrix.middleCols<q>(i);\\endcode </td>\n</tr>\n<tr><td>%Block containing the q rows starting from i\n                    \\link DenseBase::middleRows() * \\endlink</td>\n    <td>\\code\nmatrix.middleRows(i,q);\\endcode </td>\n    <td>\\code \nmatrix.middleRows<q>(i);\\endcode </td>\n</tr>\n</table>\n\nHere is a simple example illustrating the use of the operations presented above:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_BlockOperations_corner.cpp\n</td>\n<td>\n\\verbinclude Tutorial_BlockOperations_corner.out\n</td></tr></table>\n\n\n\\section TutorialBlockOperationsSyntaxVectors Block operations for vectors\n\nEigen also provides a set of block operations designed specifically for the special case of vectors and one-dimensional arrays:\n\n<table class=\"manual\">\n<tr><th> %Block operation</th>\n<th>Version constructing a \\n dynamic-size block expression</th>\n<th>Version constructing a \\n fixed-size block expression</th></tr>\n<tr><td>%Block containing the first \\p n elements \n                    \\link DenseBase::head() * \\endlink</td>\n    <td>\\code\nvector.head(n);\\endcode </td>\n    <td>\\code \nvector.head<n>();\\endcode </td>\n</tr>\n<tr><td>%Block containing the last \\p n elements\n                    \\link DenseBase::tail() * \\endlink</td>\n    <td>\\code\nvector.tail(n);\\endcode </td>\n    <td>\\code \nvector.tail<n>();\\endcode </td>\n</tr>\n<tr><td>%Block containing \\p n elements, starting at position \\p i\n                    \\link DenseBase::segment() * \\endlink</td>\n    <td>\\code\nvector.segment(i,n);\\endcode </td>\n    <td>\\code \nvector.segment<n>(i);\\endcode </td>\n</tr>\n</table>\n\n\nAn example is presented below:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_BlockOperations_vector.cpp\n</td>\n<td>\n\\verbinclude Tutorial_BlockOperations_vector.out\n</td></tr></table>\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TutorialGeometry.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialGeometry Space transformations\n\nIn this page, we will introduce the many possibilities offered by the \\ref Geometry_Module \"geometry module\" to deal with 2D and 3D rotations and projective or affine transformations.\n\n\\eigenAutoToc\n\nEigen's Geometry module provides two different kinds of geometric transformations:\n  - Abstract transformations, such as rotations (represented by \\ref AngleAxis \"angle and axis\" or by a \\ref Quaternion \"quaternion\"), \\ref Translation \"translations\", \\ref Scaling \"scalings\". These transformations are NOT represented as matrices, but you can nevertheless mix them with matrices and vectors in expressions, and convert them to matrices if you wish.\n  - Projective or affine transformation matrices: see the Transform class. These are really matrices.\n\n\\note If you are working with OpenGL 4x4 matrices then Affine3f and Affine3d are what you want. Since Eigen defaults to column-major storage, you can directly use the Transform::data() method to pass your transformation matrix to OpenGL.\n\nYou can construct a Transform from an abstract transformation, like this:\n\\code\n  Transform t(AngleAxis(angle,axis));\n\\endcode\nor like this:\n\\code\n  Transform t;\n  t = AngleAxis(angle,axis);\n\\endcode\nBut note that unfortunately, because of how C++ works, you can \\b not do this:\n\\code\n  Transform t = AngleAxis(angle,axis);\n\\endcode\n<span class=\"note\">\\b Explanation: In the C++ language, this would require Transform to have a non-explicit conversion constructor from AngleAxis, but we really don't want to allow implicit casting here.\n</span>\n\n\\section TutorialGeoElementaryTransformations Transformation types\n\n<table class=\"manual\">\n<tr><th>Transformation type</th><th>Typical initialization code</th></tr>\n<tr><td>\n\\ref Rotation2D \"2D rotation\" from an angle</td><td>\\code\nRotation2D<float> rot2(angle_in_radian);\\endcode</td></tr>\n<tr class=\"alt\"><td>\n3D rotation as an \\ref AngleAxis \"angle + axis\"</td><td>\\code\nAngleAxis<float> aa(angle_in_radian, Vector3f(ax,ay,az));\\endcode\n<span class=\"note\">The axis vector must be normalized.</span></td></tr>\n<tr><td>\n3D rotation as a \\ref Quaternion \"quaternion\"</td><td>\\code\nQuaternion<float> q;  q = AngleAxis<float>(angle_in_radian, axis);\\endcode</td></tr>\n<tr class=\"alt\"><td>\nN-D Scaling</td><td>\\code\nScaling(sx, sy)\nScaling(sx, sy, sz)\nScaling(s)\nScaling(vecN)\\endcode</td></tr>\n<tr><td>\nN-D Translation</td><td>\\code\nTranslation<float,2>(tx, ty)\nTranslation<float,3>(tx, ty, tz)\nTranslation<float,N>(s)\nTranslation<float,N>(vecN)\\endcode</td></tr>\n<tr class=\"alt\"><td>\nN-D \\ref TutorialGeoTransform \"Affine transformation\"</td><td>\\code\nTransform<float,N,Affine> t = concatenation_of_any_transformations;\nTransform<float,3,Affine> t = Translation3f(p) * AngleAxisf(a,axis) * Scaling(s);\\endcode</td></tr>\n<tr><td>\nN-D Linear transformations \\n\n<em class=note>(pure rotations, \\n scaling, etc.)</em></td><td>\\code\nMatrix<float,N> t = concatenation_of_rotations_and_scalings;\nMatrix<float,2> t = Rotation2Df(a) * Scaling(s);\nMatrix<float,3> t = AngleAxisf(a,axis) * Scaling(s);\\endcode</td></tr>\n</table>\n\n<strong>Notes on rotations</strong>\\n To transform more than a single vector the preferred\nrepresentations are rotation matrices, while for other usages Quaternion is the\nrepresentation of choice as they are compact, fast and stable. Finally Rotation2D and\nAngleAxis are mainly convenient types to create other rotation objects.\n\n<strong>Notes on Translation and Scaling</strong>\\n Like AngleAxis, these classes were\ndesigned to simplify the creation/initialization of linear (Matrix) and affine (Transform)\ntransformations. Nevertheless, unlike AngleAxis which is inefficient to use, these classes\nmight still be interesting to write generic and efficient algorithms taking as input any\nkind of transformations.\n\nAny of the above transformation types can be converted to any other types of the same nature,\nor to a more generic type. Here are some additional examples:\n<table class=\"manual\">\n<tr><td>\\code\nRotation2Df r;  r  = Matrix2f(..);       // assumes a pure rotation matrix\nAngleAxisf aa;  aa = Quaternionf(..);\nAngleAxisf aa;  aa = Matrix3f(..);       // assumes a pure rotation matrix\nMatrix2f m;     m  = Rotation2Df(..);\nMatrix3f m;     m  = Quaternionf(..);       Matrix3f m;   m = Scaling(..);\nAffine3f m;     m  = AngleAxis3f(..);       Affine3f m;   m = Scaling(..);\nAffine3f m;     m  = Translation3f(..);     Affine3f m;   m = Matrix3f(..);\n\\endcode</td></tr>\n</table>\n\n\n<a href=\"#\" class=\"top\">top</a>\\section TutorialGeoCommontransformationAPI Common API across transformation types\n\nTo some extent, Eigen's \\ref Geometry_Module \"geometry module\" allows you to write\ngeneric algorithms working on any kind of transformation representations:\n<table class=\"manual\">\n<tr><td>\nConcatenation of two transformations</td><td>\\code\ngen1 * gen2;\\endcode</td></tr>\n<tr class=\"alt\"><td>Apply the transformation to a vector</td><td>\\code\nvec2 = gen1 * vec1;\\endcode</td></tr>\n<tr><td>Get the inverse of the transformation</td><td>\\code\ngen2 = gen1.inverse();\\endcode</td></tr>\n<tr class=\"alt\"><td>Spherical interpolation \\n (Rotation2D and Quaternion only)</td><td>\\code\nrot3 = rot1.slerp(alpha,rot2);\\endcode</td></tr>\n</table>\n\n\n\n<a href=\"#\" class=\"top\">top</a>\\section TutorialGeoTransform Affine transformations\nGeneric affine transformations are represented by the Transform class which internally\nis a (Dim+1)^2 matrix. In Eigen we have chosen to not distinghish between points and\nvectors such that all points are actually represented by displacement vectors from the\norigin ( \\f$ \\mathbf{p} \\equiv \\mathbf{p}-0 \\f$ ). With that in mind, real points and\nvector distinguish when the transformation is applied.\n<table class=\"manual\">\n<tr><td>\nApply the transformation to a \\b point </td><td>\\code\nVectorNf p1, p2;\np2 = t * p1;\\endcode</td></tr>\n<tr class=\"alt\"><td>\nApply the transformation to a \\b vector </td><td>\\code\nVectorNf vec1, vec2;\nvec2 = t.linear() * vec1;\\endcode</td></tr>\n<tr><td>\nApply a \\em general transformation \\n to a \\b normal \\b vector \\n\n</td><td>\\code\nVectorNf n1, n2;\nMatrixNf normalMatrix = t.linear().inverse().transpose();\nn2 = (normalMatrix * n1).normalized();\\endcode</td></tr>\n<tr><td colspan=\"2\">(See subject 5.27 of this <a href=\"http://www.faqs.org/faqs/graphics/algorithms-faq\">faq</a> for the explanations)</td></tr>\n<tr class=\"alt\"><td>\nApply a transformation with \\em pure \\em rotation \\n to a \\b normal \\b vector\n(no scaling, no shear)</td><td>\\code\nn2 = t.linear() * n1;\\endcode</td></tr>\n<tr><td>\nOpenGL compatibility \\b 3D </td><td>\\code\nglLoadMatrixf(t.data());\\endcode</td></tr>\n<tr class=\"alt\"><td>\nOpenGL compatibility \\b 2D </td><td>\\code\nAffine3f aux(Affine3f::Identity());\naux.linear().topLeftCorner<2,2>() = t.linear();\naux.translation().start<2>() = t.translation();\nglLoadMatrixf(aux.data());\\endcode</td></tr>\n</table>\n\n\\b Component \\b accessors\n<table class=\"manual\">\n<tr><td>\nfull read-write access to the internal matrix</td><td>\\code\nt.matrix() = matN1xN1;    // N1 means N+1\nmatN1xN1 = t.matrix();\n\\endcode</td></tr>\n<tr class=\"alt\"><td>\ncoefficient accessors</td><td>\\code\nt(i,j) = scalar;   <=>   t.matrix()(i,j) = scalar;\nscalar = t(i,j);   <=>   scalar = t.matrix()(i,j);\n\\endcode</td></tr>\n<tr><td>\ntranslation part</td><td>\\code\nt.translation() = vecN;\nvecN = t.translation();\n\\endcode</td></tr>\n<tr class=\"alt\"><td>\nlinear part</td><td>\\code\nt.linear() = matNxN;\nmatNxN = t.linear();\n\\endcode</td></tr>\n<tr><td>\nextract the rotation matrix</td><td>\\code\nmatNxN = t.rotation();\n\\endcode</td></tr>\n</table>\n\n\n\\b Transformation \\b creation \\n\nWhile transformation objects can be created and updated concatenating elementary transformations,\nthe Transform class also features a procedural API:\n<table class=\"manual\">\n<tr><th></th><th>procedural API</th><th>equivalent natural API </th></tr>\n<tr><td>Translation</td><td>\\code\nt.translate(Vector_(tx,ty,..));\nt.pretranslate(Vector_(tx,ty,..));\n\\endcode</td><td>\\code\nt *= Translation_(tx,ty,..);\nt = Translation_(tx,ty,..) * t;\n\\endcode</td></tr>\n<tr class=\"alt\"><td>\\b Rotation \\n <em class=\"note\">In 2D and for the procedural API, any_rotation can also \\n be an angle in radian</em></td><td>\\code\nt.rotate(any_rotation);\nt.prerotate(any_rotation);\n\\endcode</td><td>\\code\nt *= any_rotation;\nt = any_rotation * t;\n\\endcode</td></tr>\n<tr><td>Scaling</td><td>\\code\nt.scale(Vector_(sx,sy,..));\nt.scale(s);\nt.prescale(Vector_(sx,sy,..));\nt.prescale(s);\n\\endcode</td><td>\\code\nt *= Scaling(sx,sy,..);\nt *= Scaling(s);\nt = Scaling(sx,sy,..) * t;\nt = Scaling(s) * t;\n\\endcode</td></tr>\n<tr class=\"alt\"><td>Shear transformation \\n ( \\b 2D \\b only ! )</td><td>\\code\nt.shear(sx,sy);\nt.preshear(sx,sy);\n\\endcode</td><td></td></tr>\n</table>\n\nNote that in both API, any many transformations can be concatenated in a single expression as shown in the two following equivalent examples:\n<table class=\"manual\">\n<tr><td>\\code\nt.pretranslate(..).rotate(..).translate(..).scale(..);\n\\endcode</td></tr>\n<tr><td>\\code\nt = Translation_(..) * t * RotationType(..) * Translation_(..) * Scaling(..);\n\\endcode</td></tr>\n</table>\n\n\n\n<a href=\"#\" class=\"top\">top</a>\\section TutorialGeoEulerAngles Euler angles\n<table class=\"manual\">\n<tr><td style=\"max-width:30em;\">\nEuler angles might be convenient to create rotation objects.\nOn the other hand, since there exist 24 different conventions, they are pretty confusing to use. This example shows how\nto create a rotation matrix according to the 2-1-2 convention.</td><td>\\code\nMatrix3f m;\nm = AngleAxisf(angle1, Vector3f::UnitZ())\n *  * AngleAxisf(angle2, Vector3f::UnitY())\n *  * AngleAxisf(angle3, Vector3f::UnitZ());\n\\endcode</td></tr>\n</table>\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TutorialLinearAlgebra.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialLinearAlgebra Linear algebra and decompositions\n\nThis page explains how to solve linear systems, compute various decompositions such as LU,\nQR, %SVD, eigendecompositions... After reading this page, don't miss our\n\\link TopicLinearAlgebraDecompositions catalogue \\endlink of dense matrix decompositions.\n\n\\eigenAutoToc\n\n\\section TutorialLinAlgBasicSolve Basic linear solving\n\n\\b The \\b problem: You have a system of equations, that you have written as a single matrix equation\n    \\f[ Ax \\: = \\: b \\f]\nWhere \\a A and \\a b are matrices (\\a b could be a vector, as a special case). You want to find a solution \\a x.\n\n\\b The \\b solution: You can choose between various decompositions, depending on the properties of your matrix \\a A,\nand depending on whether you favor speed or accuracy. However, let's start with an example that works in all cases,\nand is a good compromise:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include TutorialLinAlgExSolveColPivHouseholderQR.cpp </td>\n  <td>\\verbinclude TutorialLinAlgExSolveColPivHouseholderQR.out </td>\n</tr>\n</table>\n\nIn this example, the colPivHouseholderQr() method returns an object of class ColPivHouseholderQR. Since here the\nmatrix is of type Matrix3f, this line could have been replaced by:\n\\code\nColPivHouseholderQR<Matrix3f> dec(A);\nVector3f x = dec.solve(b);\n\\endcode\n\nHere, ColPivHouseholderQR is a QR decomposition with column pivoting. It's a good compromise for this tutorial, as it\nworks for all matrices while being quite fast. Here is a table of some other decompositions that you can choose from,\ndepending on your matrix, the problem you are trying to solve, and the trade-off you want to make:\n\n<table class=\"manual\">\n    <tr>\n        <th>Decomposition</th>\n        <th>Method</th>\n        <th>Requirements<br/>on the matrix</th>\n        <th>Speed<br/> (small-to-medium)</th>\n        <th>Speed<br/> (large)</th>\n        <th>Accuracy</th>\n    </tr>\n    <tr>\n        <td>PartialPivLU</td>\n        <td>partialPivLu()</td>\n        <td>Invertible</td>\n        <td>++</td>\n        <td>++</td>\n        <td>+</td>\n    </tr>\n    <tr class=\"alt\">\n        <td>FullPivLU</td>\n        <td>fullPivLu()</td>\n        <td>None</td>\n        <td>-</td>\n        <td>- -</td>\n        <td>+++</td>\n    </tr>\n    <tr>\n        <td>HouseholderQR</td>\n        <td>householderQr()</td>\n        <td>None</td>\n        <td>++</td>\n        <td>++</td>\n        <td>+</td>\n    </tr>\n    <tr class=\"alt\">\n        <td>ColPivHouseholderQR</td>\n        <td>colPivHouseholderQr()</td>\n        <td>None</td>\n        <td>+</td>\n        <td>-</td>\n        <td>+++</td>\n    </tr>\n    <tr>\n        <td>FullPivHouseholderQR</td>\n        <td>fullPivHouseholderQr()</td>\n        <td>None</td>\n        <td>-</td>\n        <td>- -</td>\n        <td>+++</td>\n    </tr>\n    <tr class=\"alt\">\n        <td>CompleteOrthogonalDecomposition</td>\n        <td>completeOrthogonalDecomposition()</td>\n        <td>None</td>\n        <td>+</td>\n        <td>-</td>\n        <td>+++</td>\n    </tr>\n    <tr class=\"alt\">\n        <td>LLT</td>\n        <td>llt()</td>\n        <td>Positive definite</td>\n        <td>+++</td>\n        <td>+++</td>\n        <td>+</td>\n    </tr>\n    <tr>\n        <td>LDLT</td>\n        <td>ldlt()</td>\n        <td>Positive or negative<br/> semidefinite</td>\n        <td>+++</td>\n        <td>+</td>\n        <td>++</td>\n    </tr>\n    <tr class=\"alt\">\n        <td>BDCSVD</td>\n        <td>bdcSvd()</td>\n        <td>None</td>\n        <td>-</td>\n        <td>-</td>\n        <td>+++</td>\n    </tr>\n    <tr class=\"alt\">\n        <td>JacobiSVD</td>\n        <td>jacobiSvd()</td>\n        <td>None</td>\n        <td>-</td>\n        <td>- - -</td>\n        <td>+++</td>\n    </tr>\n</table>\nTo get an overview of the true relative speed of the different decompositions, check this \\link DenseDecompositionBenchmark benchmark \\endlink.\n\nAll of these decompositions offer a solve() method that works as in the above example. \n\nIf you know more about the properties of your matrix, you can use the above table to select the best method.\nFor example, a good choice for solving linear systems with a non-symmetric matrix of full rank is PartialPivLU.\nIf you know that your matrix is also symmetric and positive definite, the above table says that\na very good choice is the LLT or LDLT decomposition. Here's an example, also demonstrating that using a general\nmatrix (not a vector) as right hand side is possible:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include TutorialLinAlgExSolveLDLT.cpp </td>\n  <td>\\verbinclude TutorialLinAlgExSolveLDLT.out </td>\n</tr>\n</table>\n\nFor a \\ref TopicLinearAlgebraDecompositions \"much more complete table\" comparing all decompositions supported by Eigen (notice that Eigen\nsupports many other decompositions), see our special page on\n\\ref TopicLinearAlgebraDecompositions \"this topic\".\n\n\n\\section TutorialLinAlgLeastsquares Least squares solving\n\nThe most general and accurate method to solve under- or over-determined linear systems\nin the least squares sense, is the SVD decomposition. Eigen provides two implementations.\nThe recommended one is the BDCSVD class, which scales well for large problems\nand automatically falls back to the JacobiSVD class for smaller problems.\nFor both classes, their solve() method solved the linear system in the least-squares\nsense. \n\nHere is an example:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include TutorialLinAlgSVDSolve.cpp </td>\n  <td>\\verbinclude TutorialLinAlgSVDSolve.out </td>\n</tr>\n</table>\n\nAn alternative to the SVD, which is usually faster and about as accurate, is CompleteOrthogonalDecomposition. \n\nAgain, if you know more about the problem, the table above contains methods that are potentially faster.\nIf your matrix is full rank, HouseHolderQR is the method of choice. If your matrix is full rank and well conditioned,\nusing the Cholesky decomposition (LLT) on the matrix of the normal equations can be faster still.\nOur page on \\link LeastSquares least squares solving \\endlink has more details.\n\n\n\\section TutorialLinAlgSolutionExists Checking if a matrix is singular\n\nOnly you know what error margin you want to allow for a solution to be considered valid.\nSo Eigen lets you do this computation for yourself, if you want to, as in this example:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include TutorialLinAlgExComputeSolveError.cpp </td>\n  <td>\\verbinclude TutorialLinAlgExComputeSolveError.out </td>\n</tr>\n</table>\n\n\\section TutorialLinAlgEigensolving Computing eigenvalues and eigenvectors\n\nYou need an eigendecomposition here, see available such decompositions on \\ref TopicLinearAlgebraDecompositions \"this page\".\nMake sure to check if your matrix is self-adjoint, as is often the case in these problems. Here's an example using\nSelfAdjointEigenSolver, it could easily be adapted to general matrices using EigenSolver or ComplexEigenSolver.\n\nThe computation of eigenvalues and eigenvectors does not necessarily converge, but such failure to converge is\nvery rare. The call to info() is to check for this possibility.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include TutorialLinAlgSelfAdjointEigenSolver.cpp </td>\n  <td>\\verbinclude TutorialLinAlgSelfAdjointEigenSolver.out </td>\n</tr>\n</table>\n\n\\section TutorialLinAlgInverse Computing inverse and determinant\n\nFirst of all, make sure that you really want this. While inverse and determinant are fundamental mathematical concepts,\nin \\em numerical linear algebra they are not as useful as in pure mathematics. Inverse computations are often\nadvantageously replaced by solve() operations, and the determinant is often \\em not a good way of checking if a matrix\nis invertible.\n\nHowever, for \\em very \\em small matrices, the above may not be true, and inverse and determinant can be very useful.\n\nWhile certain decompositions, such as PartialPivLU and FullPivLU, offer inverse() and determinant() methods, you can also\ncall inverse() and determinant() directly on a matrix. If your matrix is of a very small fixed size (at most 4x4) this\nallows Eigen to avoid performing a LU decomposition, and instead use formulas that are more efficient on such small matrices.\n\nHere is an example:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include TutorialLinAlgInverseDeterminant.cpp </td>\n  <td>\\verbinclude TutorialLinAlgInverseDeterminant.out </td>\n</tr>\n</table>\n\n\\section TutorialLinAlgSeparateComputation Separating the computation from the construction\n\nIn the above examples, the decomposition was computed at the same time that the decomposition object was constructed.\nThere are however situations where you might want to separate these two things, for example if you don't know,\nat the time of the construction, the matrix that you will want to decompose; or if you want to reuse an existing\ndecomposition object.\n\nWhat makes this possible is that:\n\\li all decompositions have a default constructor,\n\\li all decompositions have a compute(matrix) method that does the computation, and that may be called again\n    on an already-computed decomposition, reinitializing it.\n\nFor example:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include TutorialLinAlgComputeTwice.cpp </td>\n  <td>\\verbinclude TutorialLinAlgComputeTwice.out </td>\n</tr>\n</table>\n\nFinally, you can tell the decomposition constructor to preallocate storage for decomposing matrices of a given size,\nso that when you subsequently decompose such matrices, no dynamic memory allocation is performed (of course, if you\nare using fixed-size matrices, no dynamic memory allocation happens at all). This is done by just\npassing the size to the decomposition constructor, as in this example:\n\\code\nHouseholderQR<MatrixXf> qr(50,50);\nMatrixXf A = MatrixXf::Random(50,50);\nqr.compute(A); // no dynamic memory allocation\n\\endcode\n\n\\section TutorialLinAlgRankRevealing Rank-revealing decompositions\n\nCertain decompositions are rank-revealing, i.e. are able to compute the rank of a matrix. These are typically\nalso the decompositions that behave best in the face of a non-full-rank matrix (which in the square case means a\nsingular matrix). On \\ref TopicLinearAlgebraDecompositions \"this table\" you can see for all our decompositions\nwhether they are rank-revealing or not.\n\nRank-revealing decompositions offer at least a rank() method. They can also offer convenience methods such as isInvertible(),\nand some are also providing methods to compute the kernel (null-space) and image (column-space) of the matrix, as is the\ncase with FullPivLU:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include TutorialLinAlgRankRevealing.cpp </td>\n  <td>\\verbinclude TutorialLinAlgRankRevealing.out </td>\n</tr>\n</table>\n\nOf course, any rank computation depends on the choice of an arbitrary threshold, since practically no\nfloating-point matrix is \\em exactly rank-deficient. Eigen picks a sensible default threshold, which depends\non the decomposition but is typically the diagonal size times machine epsilon. While this is the best default we\ncould pick, only you know what is the right threshold for your application. You can set this by calling setThreshold()\non your decomposition object before calling rank() or any other method that needs to use such a threshold.\nThe decomposition itself, i.e. the compute() method, is independent of the threshold. You don't need to recompute the\ndecomposition after you've changed the threshold.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include TutorialLinAlgSetThreshold.cpp </td>\n  <td>\\verbinclude TutorialLinAlgSetThreshold.out </td>\n</tr>\n</table>\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TutorialMapClass.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialMapClass Interfacing with raw buffers: the Map class\n\nThis page explains how to work with \"raw\" C/C++ arrays.\nThis can be useful in a variety of contexts, particularly when \"importing\" vectors and matrices from other libraries into %Eigen.\n\n\\eigenAutoToc\n\n\\section TutorialMapIntroduction Introduction\n\nOccasionally you may have a pre-defined array of numbers that you want to use within %Eigen as a vector or matrix. While one option is to make a copy of the data, most commonly you probably want to re-use this memory as an %Eigen type. Fortunately, this is very easy with the Map class.\n\n\\section TutorialMapTypes Map types and declaring Map variables\n\nA Map object has a type defined by its %Eigen equivalent:\n\\code\nMap<Matrix<typename Scalar, int RowsAtCompileTime, int ColsAtCompileTime> >\n\\endcode\nNote that, in this default case, a Map requires just a single template parameter.  \n\nTo construct a Map variable, you need two other pieces of information: a pointer to the region of memory defining the array of coefficients, and the desired shape of the matrix or vector.  For example, to define a matrix of \\c float with sizes determined at compile time, you might do the following:\n\\code\nMap<MatrixXf> mf(pf,rows,columns);\n\\endcode\nwhere \\c pf is a \\c float \\c * pointing to the array of memory.  A fixed-size read-only vector of integers might be declared as\n\\code\nMap<const Vector4i> mi(pi);\n\\endcode\nwhere \\c pi is an \\c int \\c *. In this case the size does not have to be passed to the constructor, because it is already specified by the Matrix/Array type.\n\nNote that Map does not have a default constructor; you \\em must pass a pointer to initialize the object. However, you can work around this requirement (see \\ref TutorialMapPlacementNew).\n\nMap is flexible enough to accommodate a variety of different data representations.  There are two other (optional) template parameters:\n\\code\nMap<typename MatrixType,\n    int MapOptions,\n    typename StrideType>\n\\endcode\n\\li \\c MapOptions specifies whether the pointer is \\c #Aligned, or \\c #Unaligned.  The default is \\c #Unaligned.\n\\li \\c StrideType allows you to specify a custom layout for the memory array, using the Stride class.  One example would be to specify that the data array is organized in row-major format:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n<td>\\include Tutorial_Map_rowmajor.cpp </td>\n<td>\\verbinclude Tutorial_Map_rowmajor.out </td>\n</table>\nHowever, Stride is even more flexible than this; for details, see the documentation for the Map and Stride classes.\n\n\\section TutorialMapUsing Using Map variables\n\nYou can use a Map object just like any other %Eigen type:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n<td>\\include Tutorial_Map_using.cpp </td>\n<td>\\verbinclude Tutorial_Map_using.out </td>\n</table>\n\nAll %Eigen functions are written to accept Map objects just like other %Eigen types. However, when writing your own functions taking %Eigen types, this does \\em not happen automatically: a Map type is not identical to its Dense equivalent.  See \\ref TopicFunctionTakingEigenTypes for details.\n\n\\section TutorialMapPlacementNew Changing the mapped array\n\nIt is possible to change the array of a Map object after declaration, using the C++ \"placement new\" syntax:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n<td>\\include Map_placement_new.cpp </td>\n<td>\\verbinclude Map_placement_new.out </td>\n</table>\nDespite appearances, this does not invoke the memory allocator, because the syntax specifies the location for storing the result.\n\nThis syntax makes it possible to declare a Map object without first knowing the mapped array's location in memory:\n\\code\nMap<Matrix3f> A(NULL);  // don't try to use this matrix yet!\nVectorXf b(n_matrices);\nfor (int i = 0; i < n_matrices; i++)\n{\n  new (&A) Map<Matrix3f>(get_matrix_pointer(i));\n  b(i) = A.trace();\n}\n\\endcode\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TutorialMatrixArithmetic.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialMatrixArithmetic Matrix and vector arithmetic\n\nThis page aims to provide an overview and some details on how to perform arithmetic\nbetween matrices, vectors and scalars with Eigen.\n\n\\eigenAutoToc\n\n\\section TutorialArithmeticIntroduction Introduction\n\nEigen offers matrix/vector arithmetic operations either through overloads of common C++ arithmetic operators such as +, -, *,\nor through special methods such as dot(), cross(), etc.\nFor the Matrix class (matrices and vectors), operators are only overloaded to support\nlinear-algebraic operations. For example, \\c matrix1 \\c * \\c matrix2 means matrix-matrix product,\nand \\c vector \\c + \\c scalar is just not allowed. If you want to perform all kinds of array operations,\nnot linear algebra, see the \\ref TutorialArrayClass \"next page\".\n\n\\section TutorialArithmeticAddSub Addition and subtraction\n\nThe left hand side and right hand side must, of course, have the same numbers of rows and of columns. They must\nalso have the same \\c Scalar type, as Eigen doesn't do automatic type promotion. The operators at hand here are:\n\\li binary operator + as in \\c a+b\n\\li binary operator - as in \\c a-b\n\\li unary operator - as in \\c -a\n\\li compound operator += as in \\c a+=b\n\\li compound operator -= as in \\c a-=b\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_arithmetic_add_sub.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_add_sub.out\n</td></tr></table>\n\n\\section TutorialArithmeticScalarMulDiv Scalar multiplication and division\n\nMultiplication and division by a scalar is very simple too. The operators at hand here are:\n\\li binary operator * as in \\c matrix*scalar\n\\li binary operator * as in \\c scalar*matrix\n\\li binary operator / as in \\c matrix/scalar\n\\li compound operator *= as in \\c matrix*=scalar\n\\li compound operator /= as in \\c matrix/=scalar\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_arithmetic_scalar_mul_div.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_scalar_mul_div.out\n</td></tr></table>\n\n\n\\section TutorialArithmeticMentionXprTemplates A note about expression templates\n\nThis is an advanced topic that we explain on \\ref TopicEigenExpressionTemplates \"this page\",\nbut it is useful to just mention it now. In Eigen, arithmetic operators such as \\c operator+ don't\nperform any computation by themselves, they just return an \"expression object\" describing the computation to be\nperformed. The actual computation happens later, when the whole expression is evaluated, typically in \\c operator=.\nWhile this might sound heavy, any modern optimizing compiler is able to optimize away that abstraction and\nthe result is perfectly optimized code. For example, when you do:\n\\code\nVectorXf a(50), b(50), c(50), d(50);\n...\na = 3*b + 4*c + 5*d;\n\\endcode\nEigen compiles it to just one for loop, so that the arrays are traversed only once. Simplifying (e.g. ignoring\nSIMD optimizations), this loop looks like this:\n\\code\nfor(int i = 0; i < 50; ++i)\n  a[i] = 3*b[i] + 4*c[i] + 5*d[i];\n\\endcode\nThus, you should not be afraid of using relatively large arithmetic expressions with Eigen: it only gives Eigen\nmore opportunities for optimization.\n\n\\section TutorialArithmeticTranspose Transposition and conjugation\n\nThe transpose \\f$ a^T \\f$, conjugate \\f$ \\bar{a} \\f$, and adjoint (i.e., conjugate transpose) \\f$ a^* \\f$ of a matrix or vector \\f$ a \\f$ are obtained by the member functions \\link DenseBase::transpose() transpose()\\endlink, \\link MatrixBase::conjugate() conjugate()\\endlink, and \\link MatrixBase::adjoint() adjoint()\\endlink, respectively.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_arithmetic_transpose_conjugate.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_transpose_conjugate.out\n</td></tr></table>\n\nFor real matrices, \\c conjugate() is a no-operation, and so \\c adjoint() is equivalent to \\c transpose().\n\nAs for basic arithmetic operators, \\c transpose() and \\c adjoint() simply return a proxy object without doing the actual transposition. If you do <tt>b = a.transpose()</tt>, then the transpose is evaluated at the same time as the result is written into \\c b. However, there is a complication here. If you do <tt>a = a.transpose()</tt>, then Eigen starts writing the result into \\c a before the evaluation of the transpose is finished. Therefore, the instruction <tt>a = a.transpose()</tt> does not replace \\c a with its transpose, as one would expect:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_arithmetic_transpose_aliasing.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_transpose_aliasing.out\n</td></tr></table>\nThis is the so-called \\ref TopicAliasing \"aliasing issue\". In \"debug mode\", i.e., when \\ref TopicAssertions \"assertions\" have not been disabled, such common pitfalls are automatically detected. \n\nFor \\em in-place transposition, as for instance in <tt>a = a.transpose()</tt>, simply use the \\link DenseBase::transposeInPlace() transposeInPlace()\\endlink  function:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_arithmetic_transpose_inplace.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_transpose_inplace.out\n</td></tr></table>\nThere is also the \\link MatrixBase::adjointInPlace() adjointInPlace()\\endlink function for complex matrices.\n\n\\section TutorialArithmeticMatrixMul Matrix-matrix and matrix-vector multiplication\n\nMatrix-matrix multiplication is again done with \\c operator*. Since vectors are a special\ncase of matrices, they are implicitly handled there too, so matrix-vector product is really just a special\ncase of matrix-matrix product, and so is vector-vector outer product. Thus, all these cases are handled by just\ntwo operators:\n\\li binary operator * as in \\c a*b\n\\li compound operator *= as in \\c a*=b (this multiplies on the right: \\c a*=b is equivalent to <tt>a = a*b</tt>)\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_arithmetic_matrix_mul.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_matrix_mul.out\n</td></tr></table>\n\nNote: if you read the above paragraph on expression templates and are worried that doing \\c m=m*m might cause\naliasing issues, be reassured for now: Eigen treats matrix multiplication as a special case and takes care of\nintroducing a temporary here, so it will compile \\c m=m*m as:\n\\code\ntmp = m*m;\nm = tmp;\n\\endcode\nIf you know your matrix product can be safely evaluated into the destination matrix without aliasing issue, then you can use the \\link MatrixBase::noalias() noalias()\\endlink function to avoid the temporary, e.g.:\n\\code\nc.noalias() += a * b;\n\\endcode\nFor more details on this topic, see the page on \\ref TopicAliasing \"aliasing\".\n\n\\b Note: for BLAS users worried about performance, expressions such as <tt>c.noalias() -= 2 * a.adjoint() * b;</tt> are fully optimized and trigger a single gemm-like function call.\n\n\\section TutorialArithmeticDotAndCross Dot product and cross product\n\nFor dot product and cross product, you need the \\link MatrixBase::dot() dot()\\endlink and \\link MatrixBase::cross() cross()\\endlink methods. Of course, the dot product can also be obtained as a 1x1 matrix as u.adjoint()*v.\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_arithmetic_dot_cross.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_dot_cross.out\n</td></tr></table>\n\nRemember that cross product is only for vectors of size 3. Dot product is for vectors of any sizes.\nWhen using complex numbers, Eigen's dot product is conjugate-linear in the first variable and linear in the\nsecond variable.\n\n\\section TutorialArithmeticRedux Basic arithmetic reduction operations\nEigen also provides some reduction operations to reduce a given matrix or vector to a single value such as the sum (computed by \\link DenseBase::sum() sum()\\endlink), product (\\link DenseBase::prod() prod()\\endlink), or the maximum (\\link DenseBase::maxCoeff() maxCoeff()\\endlink) and minimum (\\link DenseBase::minCoeff() minCoeff()\\endlink) of all its coefficients.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_arithmetic_redux_basic.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_redux_basic.out\n</td></tr></table>\n\nThe \\em trace of a matrix, as returned by the function \\link MatrixBase::trace() trace()\\endlink, is the sum of the diagonal coefficients and can also be computed as efficiently using <tt>a.diagonal().sum()</tt>, as we will see later on.\n\nThere also exist variants of the \\c minCoeff and \\c maxCoeff functions returning the coordinates of the respective coefficient via the arguments:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_arithmetic_redux_minmax.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_redux_minmax.out\n</td></tr></table>\n\n\n\\section TutorialArithmeticValidity Validity of operations\nEigen checks the validity of the operations that you perform. When possible,\nit checks them at compile time, producing compilation errors. These error messages can be long and ugly,\nbut Eigen writes the important message in UPPERCASE_LETTERS_SO_IT_STANDS_OUT. For example:\n\\code\n  Matrix3f m;\n  Vector4f v;\n  v = m*v;      // Compile-time error: YOU_MIXED_MATRICES_OF_DIFFERENT_SIZES\n\\endcode\n\nOf course, in many cases, for example when checking dynamic sizes, the check cannot be performed at compile time.\nEigen then uses runtime assertions. This means that the program will abort with an error message when executing an illegal operation if it is run in \"debug mode\", and it will probably crash if assertions are turned off.\n\n\\code\n  MatrixXf m(3,3);\n  VectorXf v(4);\n  v = m * v; // Run-time assertion failure here: \"invalid matrix product\"\n\\endcode\n\nFor more details on this topic, see \\ref TopicAssertions \"this page\".\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TutorialMatrixClass.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialMatrixClass The Matrix class\n\n\\eigenAutoToc\n\nIn Eigen, all matrices and vectors are objects of the Matrix template class.\nVectors are just a special case of matrices, with either 1 row or 1 column.\n\n\\section TutorialMatrixFirst3Params The first three template parameters of Matrix\n\nThe Matrix class takes six template parameters, but for now it's enough to\nlearn about the first three first parameters. The three remaining parameters have default\nvalues, which for now we will leave untouched, and which we\n\\ref TutorialMatrixOptTemplParams \"discuss below\".\n\nThe three mandatory template parameters of Matrix are:\n\\code\nMatrix<typename Scalar, int RowsAtCompileTime, int ColsAtCompileTime>\n\\endcode\n\\li \\c Scalar is the scalar type, i.e. the type of the coefficients.\n    That is, if you want a matrix of floats, choose \\c float here.\n    See \\ref TopicScalarTypes \"Scalar types\" for a list of all supported\n    scalar types and for how to extend support to new types.\n\\li \\c RowsAtCompileTime and \\c ColsAtCompileTime are the number of rows\n    and columns of the matrix as known at compile time (see \n    \\ref TutorialMatrixDynamic \"below\" for what to do if the number is not\n    known at compile time).\n\nWe offer a lot of convenience typedefs to cover the usual cases. For example, \\c Matrix4f is\na 4x4 matrix of floats. Here is how it is defined by Eigen:\n\\code\ntypedef Matrix<float, 4, 4> Matrix4f;\n\\endcode\nWe discuss \\ref TutorialMatrixTypedefs \"below\" these convenience typedefs.\n\n\\section TutorialMatrixVectors Vectors\n\nAs mentioned above, in Eigen, vectors are just a special case of\nmatrices, with either 1 row or 1 column. The case where they have 1 column is the most common;\nsuch vectors are called column-vectors, often abbreviated as just vectors. In the other case\nwhere they have 1 row, they are called row-vectors.\n\nFor example, the convenience typedef \\c Vector3f is a (column) vector of 3 floats. It is defined as follows by Eigen:\n\\code\ntypedef Matrix<float, 3, 1> Vector3f;\n\\endcode\nWe also offer convenience typedefs for row-vectors, for example:\n\\code\ntypedef Matrix<int, 1, 2> RowVector2i;\n\\endcode\n\n\\section TutorialMatrixDynamic The special value Dynamic\n\nOf course, Eigen is not limited to matrices whose dimensions are known at compile time.\nThe \\c RowsAtCompileTime and \\c ColsAtCompileTime template parameters can take the special\nvalue \\c Dynamic which indicates that the size is unknown at compile time, so must\nbe handled as a run-time variable. In Eigen terminology, such a size is referred to as a\n\\em dynamic \\em size; while a size that is known at compile time is called a\n\\em fixed \\em size. For example, the convenience typedef \\c MatrixXd, meaning\na matrix of doubles with dynamic size, is defined as follows:\n\\code\ntypedef Matrix<double, Dynamic, Dynamic> MatrixXd;\n\\endcode\nAnd similarly, we define a self-explanatory typedef \\c VectorXi as follows:\n\\code\ntypedef Matrix<int, Dynamic, 1> VectorXi;\n\\endcode\nYou can perfectly have e.g. a fixed number of rows with a dynamic number of columns, as in:\n\\code\nMatrix<float, 3, Dynamic>\n\\endcode\n\n\\section TutorialMatrixConstructors Constructors\n\nA default constructor is always available, never performs any dynamic memory allocation, and never initializes the matrix coefficients. You can do:\n\\code\nMatrix3f a;\nMatrixXf b;\n\\endcode\nHere,\n\\li \\c a is a 3-by-3 matrix, with a plain float[9] array of uninitialized coefficients,\n\\li \\c b is a dynamic-size matrix whose size is currently 0-by-0, and whose array of\ncoefficients hasn't yet been allocated at all.\n\nConstructors taking sizes are also available. For matrices, the number of rows is always passed first.\nFor vectors, just pass the vector size. They allocate the array of coefficients\nwith the given size, but don't initialize the coefficients themselves:\n\\code\nMatrixXf a(10,15);\nVectorXf b(30);\n\\endcode\nHere,\n\\li \\c a is a 10x15 dynamic-size matrix, with allocated but currently uninitialized coefficients.\n\\li \\c b is a dynamic-size vector of size 30, with allocated but currently uninitialized coefficients.\n\nIn order to offer a uniform API across fixed-size and dynamic-size matrices, it is legal to use these\nconstructors on fixed-size matrices, even if passing the sizes is useless in this case. So this is legal:\n\\code\nMatrix3f a(3,3);\n\\endcode\nand is a no-operation.\n\nMatrices and vectors can also be initialized from lists of coefficients.\nPrior to C++11, this feature is limited to small fixed-size column or vectors up to size 4:\n\\code\nVector2d a(5.0, 6.0);\nVector3d b(5.0, 6.0, 7.0);\nVector4d c(5.0, 6.0, 7.0, 8.0);\n\\endcode\n\nIf C++11 is enabled, fixed-size column or row vectors of arbitrary size can be initialized by passing an arbitrary number of coefficients:\n\\code\nVector2i a(1, 2);                      // A column vector containing the elements {1, 2}\nMatrix<int, 5, 1> b {1, 2, 3, 4, 5};   // A row-vector containing the elements {1, 2, 3, 4, 5}\nMatrix<int, 1, 5> c = {1, 2, 3, 4, 5}; // A column vector containing the elements {1, 2, 3, 4, 5}\n\\endcode\n\nIn the general case of matrices and vectors with either fixed or runtime sizes,\ncoefficients have to be grouped by rows and passed as an initializer list of initializer list (\\link Matrix::Matrix(const std::initializer_list<std::initializer_list<Scalar>>&) details \\endlink):\n\\code\nMatrixXi a {      // construct a 2x2 matrix\n      {1, 2},     // first row\n      {3, 4}      // second row\n};\nMatrix<double, 2, 3> b {\n      {2, 3, 4},\n      {5, 6, 7},\n};\n\\endcode\n\nFor column or row vectors, implicit transposition is allowed.\nThis means that a column vector can be initialized from a single row:\n\\code\nVectorXd a {{1.5, 2.5, 3.5}};             // A column-vector with 3 coefficients\nRowVectorXd b {{1.0, 2.0, 3.0, 4.0}};     // A row-vector with 4 coefficients\n\\endcode\n\n\\section TutorialMatrixCoeffAccessors Coefficient accessors\n\nThe primary coefficient accessors and mutators in Eigen are the overloaded parenthesis operators.\nFor matrices, the row index is always passed first. For vectors, just pass one index.\nThe numbering starts at 0. This example is self-explanatory:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_matrix_coefficient_accessors.cpp\n</td>\n<td>\n\\verbinclude tut_matrix_coefficient_accessors.out\n</td></tr></table>\n\nNote that the syntax `m(index)` \nis not restricted to vectors, it is also available for general matrices, meaning index-based access\nin the array of coefficients. This however depends on the matrix's storage order. All Eigen matrices default to\ncolumn-major storage order, but this can be changed to row-major, see \\ref TopicStorageOrders \"Storage orders\".\n\nThe `operator[]` is also overloaded for index-based access in vectors, but keep in mind that C++ doesn't allow `operator[]` to\ntake more than one argument. We restrict `operator[]` to vectors, because an awkwardness in the C++ language\nwould make `matrix[i,j]` compile to the same thing as `matrix[j]`!\n\n\\section TutorialMatrixCommaInitializer Comma-initialization\n\n%Matrix and vector coefficients can be conveniently set using the so-called \\em comma-initializer syntax.\nFor now, it is enough to know this example:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n<td>\\include Tutorial_commainit_01.cpp </td>\n<td>\\verbinclude Tutorial_commainit_01.out </td>\n</tr></table>\n\n\nThe right-hand side can also contain matrix expressions as discussed in \\ref TutorialAdvancedInitialization \"this page\".\n\n\\section TutorialMatrixSizesResizing Resizing\n\nThe current size of a matrix can be retrieved by \\link EigenBase::rows() rows()\\endlink, \\link EigenBase::cols() cols() \\endlink and \\link EigenBase::size() size()\\endlink. These methods return the number of rows, the number of columns and the number of coefficients, respectively. Resizing a dynamic-size matrix is done by the \\link PlainObjectBase::resize(Index,Index) resize() \\endlink method.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n<td>\\include tut_matrix_resize.cpp </td>\n<td>\\verbinclude tut_matrix_resize.out </td>\n</tr></table>\n\nThe `resize()` method is a no-operation if the actual matrix size doesn't change; otherwise it is destructive: the values of the coefficients may change.\nIf you want a conservative variant of `resize()` which does not change the coefficients, use \\link PlainObjectBase::conservativeResize() conservativeResize()\\endlink, see \\ref TopicResizing \"this page\" for more details.\n\nAll these methods are still available on fixed-size matrices, for the sake of API uniformity. Of course, you can't actually\nresize a fixed-size matrix. Trying to change a fixed size to an actually different value will trigger an assertion failure;\nbut the following code is legal:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n<td>\\include tut_matrix_resize_fixed_size.cpp </td>\n<td>\\verbinclude tut_matrix_resize_fixed_size.out </td>\n</tr></table>\n\n\n\\section TutorialMatrixAssignment Assignment and resizing\n\nAssignment is the action of copying a matrix into another, using \\c operator=. Eigen resizes the matrix on the left-hand side automatically so that it matches the size of the matrix on the right-hand size. For example:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n<td>\\include tut_matrix_assignment_resizing.cpp </td>\n<td>\\verbinclude tut_matrix_assignment_resizing.out </td>\n</tr></table>\n\nOf course, if the left-hand side is of fixed size, resizing it is not allowed.\n\nIf you do not want this automatic resizing to happen (for example for debugging purposes), you can disable it, see\n\\ref TopicResizing \"this page\".\n\n\n\\section TutorialMatrixFixedVsDynamic Fixed vs. Dynamic size\n\nWhen should one use fixed sizes (e.g. \\c Matrix4f), and when should one prefer dynamic sizes (e.g. \\c MatrixXf)?\nThe simple answer is: use fixed\nsizes for very small sizes where you can, and use dynamic sizes for larger sizes or where you have to. For small sizes,\nespecially for sizes smaller than (roughly) 16, using fixed sizes is hugely beneficial\nto performance, as it allows Eigen to avoid dynamic memory allocation and to unroll\nloops. Internally, a fixed-size Eigen matrix is just a plain array, i.e. doing\n\\code Matrix4f mymatrix; \\endcode\nreally amounts to just doing\n\\code float mymatrix[16]; \\endcode\nso this really has zero runtime cost. By contrast, the array of a dynamic-size matrix\nis always allocated on the heap, so doing\n\\code MatrixXf mymatrix(rows,columns); \\endcode\namounts to doing\n\\code float *mymatrix = new float[rows*columns]; \\endcode\nand in addition to that, the \\c MatrixXf object stores its number of rows and columns as\nmember variables.\n\nThe limitation of using fixed sizes, of course, is that this is only possible\nwhen you know the sizes at compile time. Also, for large enough sizes, say for sizes\ngreater than (roughly) 32, the performance benefit of using fixed sizes becomes negligible.\nWorse, trying to create a very large matrix using fixed sizes inside a function could result in a\nstack overflow, since Eigen will try to allocate the array automatically as a local variable, and\nthis is normally done on the stack.\nFinally, depending on circumstances, Eigen can also be more aggressive trying to vectorize\n(use SIMD instructions) when dynamic sizes are used, see \\ref TopicVectorization \"Vectorization\".\n\n\\section TutorialMatrixOptTemplParams Optional template parameters\n\nWe mentioned at the beginning of this page that the Matrix class takes six template parameters,\nbut so far we only discussed the first three. The remaining three parameters are optional. Here is\nthe complete list of template parameters:\n\\code\nMatrix<typename Scalar,\n       int RowsAtCompileTime,\n       int ColsAtCompileTime,\n       int Options = 0,\n       int MaxRowsAtCompileTime = RowsAtCompileTime,\n       int MaxColsAtCompileTime = ColsAtCompileTime>\n\\endcode\n\\li \\c Options is a bit field. Here, we discuss only one bit: \\c RowMajor. It specifies that the matrices\n      of this type use row-major storage order; by default, the storage order is column-major. See the page on\n      \\ref TopicStorageOrders \"storage orders\". For example, this type means row-major 3x3 matrices:\n      \\code\n      Matrix<float, 3, 3, RowMajor>\n      \\endcode\n\\li \\c MaxRowsAtCompileTime and \\c MaxColsAtCompileTime are useful when you want to specify that, even though\n      the exact sizes of your matrices are not known at compile time, a fixed upper bound is known at\n      compile time. The biggest reason why you might want to do that is to avoid dynamic memory allocation.\n      For example the following matrix type uses a plain array of 12 floats, without dynamic memory allocation:\n      \\code\n      Matrix<float, Dynamic, Dynamic, 0, 3, 4>\n      \\endcode\n\n\\section TutorialMatrixTypedefs Convenience typedefs\n\nEigen defines the following Matrix typedefs:\n\\li \\c MatrixNt for `Matrix<type, N, N>`. For example, \\c MatrixXi for `Matrix<int, Dynamic, Dynamic>`.\n\\li \\c VectorNt for `Matrix<type, N, 1>`. For example, \\c Vector2f for `Matrix<float, 2, 1>`.\n\\li \\c RowVectorNt for `Matrix<type, 1, N>`. For example, \\c RowVector3d for `Matrix<double, 1, 3>`.\n\nWhere:\n\\li \\c N can be any one of \\c 2, \\c 3, \\c 4, or \\c X (meaning \\c Dynamic).\n\\li \\c t can be any one of \\c i (meaning \\c int), \\c f (meaning \\c float), \\c d (meaning \\c double),\n      \\c cf (meaning `complex<float>`), or \\c cd (meaning `complex<double>`). The fact that `typedef`s are only\n    defined for these five types doesn't mean that they are the only supported scalar types. For example,\n    all standard integer types are supported, see \\ref TopicScalarTypes \"Scalar types\".\n\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TutorialReductionsVisitorsBroadcasting.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialReductionsVisitorsBroadcasting Reductions, visitors and broadcasting\n\nThis page explains Eigen's reductions, visitors and broadcasting and how they are used with\n\\link MatrixBase matrices \\endlink and \\link ArrayBase arrays \\endlink.\n\n\\eigenAutoToc\n\n\\section TutorialReductionsVisitorsBroadcastingReductions Reductions\nIn Eigen, a reduction is a function taking a matrix or array, and returning a single\nscalar value. One of the most used reductions is \\link DenseBase::sum() .sum() \\endlink,\nreturning the sum of all the coefficients inside a given matrix or array.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_arithmetic_redux_basic.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_redux_basic.out\n</td></tr></table>\n\nThe \\em trace of a matrix, as returned by the function \\c trace(), is the sum of the diagonal coefficients and can equivalently be computed <tt>a.diagonal().sum()</tt>.\n\n\n\\subsection TutorialReductionsVisitorsBroadcastingReductionsNorm Norm computations\n\nThe (Euclidean a.k.a. \\f$\\ell^2\\f$) squared norm of a vector can be obtained \\link MatrixBase::squaredNorm() squaredNorm() \\endlink. It is equal to the dot product of the vector by itself, and equivalently to the sum of squared absolute values of its coefficients.\n\nEigen also provides the \\link MatrixBase::norm() norm() \\endlink method, which returns the square root of \\link MatrixBase::squaredNorm() squaredNorm() \\endlink.\n\nThese operations can also operate on matrices; in that case, a n-by-p matrix is seen as a vector of size (n*p), so for example the \\link MatrixBase::norm() norm() \\endlink method returns the \"Frobenius\" or \"Hilbert-Schmidt\" norm. We refrain from speaking of the \\f$\\ell^2\\f$ norm of a matrix because that can mean different things.\n\nIf you want other coefficient-wise \\f$\\ell^p\\f$ norms, use the \\link MatrixBase::lpNorm lpNorm<p>() \\endlink method. The template parameter \\a p can take the special value \\a Infinity if you want the \\f$\\ell^\\infty\\f$ norm, which is the maximum of the absolute values of the coefficients.\n\nThe following example demonstrates these methods.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ReductionsVisitorsBroadcasting_reductions_norm.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ReductionsVisitorsBroadcasting_reductions_norm.out\n</td></tr></table>\n\n\\b Operator \\b norm: The 1-norm and \\f$\\infty\\f$-norm <a href=\"https://en.wikipedia.org/wiki/Operator_norm\">matrix operator norms</a> can easily be computed as follows:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ReductionsVisitorsBroadcasting_reductions_operatornorm.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ReductionsVisitorsBroadcasting_reductions_operatornorm.out\n</td></tr></table>\nSee below for more explanations on the syntax of these expressions.\n\n\\subsection TutorialReductionsVisitorsBroadcastingReductionsBool Boolean reductions\n\nThe following reductions operate on boolean values:\n  - \\link DenseBase::all() all() \\endlink returns \\b true if all of the coefficients in a given Matrix or Array evaluate to \\b true .\n  - \\link DenseBase::any() any() \\endlink returns \\b true if at least one of the coefficients in a given Matrix or Array evaluates to \\b true .\n  - \\link DenseBase::count() count() \\endlink returns the number of coefficients in a given Matrix or Array that evaluate to  \\b true.\n\nThese are typically used in conjunction with the coefficient-wise comparison and equality operators provided by Array. For instance, <tt>array > 0</tt> is an %Array of the same size as \\c array , with \\b true at those positions where the corresponding coefficient of \\c array is positive. Thus, <tt>(array > 0).all()</tt> tests whether all coefficients of \\c array are positive. This can be seen in the following example:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ReductionsVisitorsBroadcasting_reductions_bool.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ReductionsVisitorsBroadcasting_reductions_bool.out\n</td></tr></table>\n\n\\subsection TutorialReductionsVisitorsBroadcastingReductionsUserdefined User defined reductions\n\nTODO\n\nIn the meantime you can have a look at the DenseBase::redux() function.\n\n\\section TutorialReductionsVisitorsBroadcastingVisitors Visitors\nVisitors are useful when one wants to obtain the location of a coefficient inside \na Matrix or Array. The simplest examples are \n\\link MatrixBase::maxCoeff() maxCoeff(&x,&y) \\endlink and \n\\link MatrixBase::minCoeff() minCoeff(&x,&y)\\endlink, which can be used to find\nthe location of the greatest or smallest coefficient in a Matrix or \nArray.\n\nThe arguments passed to a visitor are pointers to the variables where the\nrow and column position are to be stored. These variables should be of type\n\\link Eigen::Index Index \\endlink, as shown below:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ReductionsVisitorsBroadcasting_visitors.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ReductionsVisitorsBroadcasting_visitors.out\n</td></tr></table>\n\nBoth functions also return the value of the minimum or maximum coefficient.\n\n\\section TutorialReductionsVisitorsBroadcastingPartialReductions Partial reductions\nPartial reductions are reductions that can operate column- or row-wise on a Matrix or \nArray, applying the reduction operation on each column or row and \nreturning a column or row vector with the corresponding values. Partial reductions are applied \nwith \\link DenseBase::colwise() colwise() \\endlink or \\link DenseBase::rowwise() rowwise() \\endlink.\n\nA simple example is obtaining the maximum of the elements \nin each column in a given matrix, storing the result in a row vector:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ReductionsVisitorsBroadcasting_colwise.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ReductionsVisitorsBroadcasting_colwise.out\n</td></tr></table>\n\nThe same operation can be performed row-wise:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ReductionsVisitorsBroadcasting_rowwise.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ReductionsVisitorsBroadcasting_rowwise.out\n</td></tr></table>\n\n<b>Note that column-wise operations return a row vector, while row-wise operations return a column vector.</b>\n\n\\subsection TutorialReductionsVisitorsBroadcastingPartialReductionsCombined Combining partial reductions with other operations\nIt is also possible to use the result of a partial reduction to do further processing.\nHere is another example that finds the column whose sum of elements is the maximum\n within a matrix. With column-wise partial reductions this can be coded as:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ReductionsVisitorsBroadcasting_maxnorm.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ReductionsVisitorsBroadcasting_maxnorm.out\n</td></tr></table>\n\nThe previous example applies the \\link DenseBase::sum() sum() \\endlink reduction on each column\nthough the \\link DenseBase::colwise() colwise() \\endlink visitor, obtaining a new matrix whose\nsize is 1x4.\n\nTherefore, if\n\\f[\n\\mbox{m} = \\begin{bmatrix} 1 & 2 & 6 & 9 \\\\\n                    3 & 1 & 7 & 2 \\end{bmatrix}\n\\f]\n\nthen\n\n\\f[\n\\mbox{m.colwise().sum()} = \\begin{bmatrix} 4 & 3 & 13 & 11 \\end{bmatrix}\n\\f]\n\nThe \\link DenseBase::maxCoeff() maxCoeff() \\endlink reduction is finally applied \nto obtain the column index where the maximum sum is found, \nwhich is the column index 2 (third column) in this case.\n\n\n\\section TutorialReductionsVisitorsBroadcastingBroadcasting Broadcasting\nThe concept behind broadcasting is similar to partial reductions, with the difference that broadcasting \nconstructs an expression where a vector (column or row) is interpreted as a matrix by replicating it in \none direction.\n\nA simple example is to add a certain column vector to each column in a matrix. \nThis can be accomplished with:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple.out\n</td></tr></table>\n\nWe can interpret the instruction <tt>mat.colwise() += v</tt> in two equivalent ways. It adds the vector \\c v\nto every column of the matrix. Alternatively, it can be interpreted as repeating the vector \\c v four times to\nform a four-by-two matrix which is then added to \\c mat:\n\\f[\n\\begin{bmatrix} 1 & 2 & 6 & 9 \\\\ 3 & 1 & 7 & 2 \\end{bmatrix}\n+ \\begin{bmatrix} 0 & 0 & 0 & 0 \\\\ 1 & 1 & 1 & 1 \\end{bmatrix}\n= \\begin{bmatrix} 1 & 2 & 6 & 9 \\\\ 4 & 2 & 8 & 3 \\end{bmatrix}.\n\\f]\nThe operators <tt>-=</tt>, <tt>+</tt> and <tt>-</tt> can also be used column-wise and row-wise. On arrays, we \ncan also use the operators <tt>*=</tt>, <tt>/=</tt>, <tt>*</tt> and <tt>/</tt> to perform coefficient-wise \nmultiplication and division column-wise or row-wise. These operators are not available on matrices because it\nis not clear what they would do. If you want multiply column 0 of a matrix \\c mat with \\c v(0), column 1 with \n\\c v(1), and so on, then use <tt>mat = mat * v.asDiagonal()</tt>.\n\nIt is important to point out that the vector to be added column-wise or row-wise must be of type Vector,\nand cannot be a Matrix. If this is not met then you will get compile-time error. This also means that\nbroadcasting operations can only be applied with an object of type Vector, when operating with Matrix.\nThe same applies for the Array class, where the equivalent for VectorXf is ArrayXf. As always, you should\nnot mix arrays and matrices in the same expression.\n\nTo perform the same operation row-wise we can do:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple_rowwise.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple_rowwise.out\n</td></tr></table>\n\n\\subsection TutorialReductionsVisitorsBroadcastingBroadcastingCombined Combining broadcasting with other operations\nBroadcasting can also be combined with other operations, such as Matrix or Array operations, \nreductions and partial reductions.\n\nNow that broadcasting, reductions and partial reductions have been introduced, we can dive into a more advanced example that finds\nthe nearest neighbour of a vector <tt>v</tt> within the columns of matrix <tt>m</tt>. The Euclidean distance will be used in this example,\ncomputing the squared Euclidean distance with the partial reduction named \\link MatrixBase::squaredNorm() squaredNorm() \\endlink:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ReductionsVisitorsBroadcasting_broadcast_1nn.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ReductionsVisitorsBroadcasting_broadcast_1nn.out\n</td></tr></table>\n\nThe line that does the job is \n\\code\n  (m.colwise() - v).colwise().squaredNorm().minCoeff(&index);\n\\endcode\n\nWe will go step by step to understand what is happening:\n\n  - <tt>m.colwise() - v</tt> is a broadcasting operation, subtracting <tt>v</tt> from each column in <tt>m</tt>. The result of this operation\nis a new matrix whose size is the same as matrix <tt>m</tt>: \\f[\n  \\mbox{m.colwise() - v} = \n  \\begin{bmatrix}\n    -1 & 21 & 4 & 7 \\\\\n     0 & 8  & 4 & -1\n  \\end{bmatrix}\n\\f]\n\n  - <tt>(m.colwise() - v).colwise().squaredNorm()</tt> is a partial reduction, computing the squared norm column-wise. The result of\nthis operation is a row vector where each coefficient is the squared Euclidean distance between each column in <tt>m</tt> and <tt>v</tt>: \\f[\n  \\mbox{(m.colwise() - v).colwise().squaredNorm()} =\n  \\begin{bmatrix}\n     1 & 505 & 32 & 50\n  \\end{bmatrix}\n\\f]\n\n  - Finally, <tt>minCoeff(&index)</tt> is used to obtain the index of the column in <tt>m</tt> that is closest to <tt>v</tt> in terms of Euclidean\ndistance.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TutorialReshape.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialReshape Reshape\n\nSince the version 3.4, %Eigen exposes convenient methods to reshape a matrix to another matrix of different sizes or vector.\nAll cases are handled via the `DenseBase::reshaped(NRowsType,NColsType)` and `DenseBase::reshaped()` functions.\nThose functions do not perform in-place reshaping, but instead return a <i> view </i> on the input expression.\n\n\\eigenAutoToc\n\n\\section TutorialReshapeMat2Mat Reshaped 2D views\n\nThe more general reshaping transformation is handled via: `reshaped(nrows,ncols)`.\nHere is an example reshaping a 4x4 matrix to a 2x8 one:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include MatrixBase_reshaped_int_int.cpp\n</td>\n<td>\n\\verbinclude MatrixBase_reshaped_int_int.out\n</td></tr></table>\n\nBy default, the input coefficients are always interpreted in column-major order regardless of the storage order of the input expression.\nFor more control on ordering, compile-time sizes, and automatic size deduction, please see de documentation of `DenseBase::reshaped(NRowsType,NColsType)` that contains all the details with many examples.\n\n\n\\section TutorialReshapeMat2Vec 1D linear views\n\nA very common usage of reshaping is to create a 1D linear view over a given 2D matrix or expression.\nIn this case, sizes can be deduced and thus omitted as in the following example:\n\n<table class=\"example\">\n<tr><th>Example:</th></tr>\n<tr><td>\n\\include MatrixBase_reshaped_to_vector.cpp\n</td></tr>\n<tr><th>Output:</th></tr>\n<tr><td>\n\\verbinclude MatrixBase_reshaped_to_vector.out\n</td></tr></table>\n\nThis shortcut always returns a column vector and by default input coefficients are always interpreted in column-major order.\nAgain, see the documentation of DenseBase::reshaped() for more control on the ordering.\n\n\\section TutorialReshapeInPlace\n\nThe above examples create reshaped views, but what about reshaping inplace a given matrix?\nOf course this task in only conceivable for matrix and arrays having runtime dimensions.\nIn many cases, this can be accomplished via PlainObjectBase::resize(Index,Index):\n\n<table class=\"example\">\n<tr><th>Example:</th></tr>\n<tr><td>\n\\include Tutorial_reshaped_vs_resize_1.cpp\n</td></tr>\n<tr><th>Output:</th></tr>\n<tr><td>\n\\verbinclude Tutorial_reshaped_vs_resize_1.out\n</td></tr></table>\n\nHowever beware that unlike \\c reshaped, the result of \\c resize depends on the input storage order.\nIt thus behaves similarly to `reshaped<AutoOrder>`:\n\n<table class=\"example\">\n<tr><th>Example:</th></tr>\n<tr><td>\n\\include Tutorial_reshaped_vs_resize_2.cpp\n</td></tr>\n<tr><th>Output:</th></tr>\n<tr><td>\n\\verbinclude Tutorial_reshaped_vs_resize_2.out\n</td></tr></table>\n\nFinally, assigning a reshaped matrix to itself is currently not supported and will result to undefined-behavior because of \\link TopicAliasing aliasing \\endlink.\nThe following is forbidden: \\code A = A.reshaped(2,8); \\endcode\nThis is OK: \\code A = A.reshaped(2,8).eval(); \\endcode\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TutorialSTL.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialSTL STL iterators and algorithms\n\nSince the version 3.4, %Eigen's dense matrices and arrays provide STL compatible iterators.\nAs demonstrated below, this makes them naturally compatible with range-for-loops and STL's algorithms.\n\n\\eigenAutoToc\n\n\\section TutorialSTLVectors Iterating over 1D arrays and vectors \n\nAny dense 1D expressions exposes the pair of `begin()/end()` methods to iterate over them.\n\nThis directly enables c++11 range for loops:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_range_for_loop_1d_cxx11.cpp\n</td>\n<td>\n\\verbinclude Tutorial_range_for_loop_1d_cxx11.out\n</td></tr></table>\n\nOne dimensional expressions can also easily be passed to STL algorithms:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_std_sort.cpp\n</td>\n<td>\n\\verbinclude Tutorial_std_sort.out\n</td></tr></table>\n\nSimilar to `std::vector`, 1D expressions also exposes the pair of `cbegin()/cend()` methods to conveniently get const iterators on non-const object.\n\n\\section TutorialSTLMatrices Iterating over coefficients of 2D arrays and matrices\n\nSTL iterators are intrinsically designed to iterate over 1D structures.\nThis is why `begin()/end()` methods are disabled for 2D expressions.\nIterating over all coefficients of a 2D expressions is still easily accomplished by creating a 1D linear view through `reshaped()`:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_range_for_loop_2d_cxx11.cpp\n</td>\n<td>\n\\verbinclude Tutorial_range_for_loop_2d_cxx11.out\n</td></tr></table>\n\n\\section TutorialSTLRowsColumns Iterating over rows or columns of 2D arrays and matrices\n\nIt is also possible to get iterators over rows or columns of 2D expressions.\nThose are available through the `rowwise()` and `colwise()` proxies.\nHere is an example sorting each row of a matrix:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_std_sort_rows_cxx11.cpp\n</td>\n<td>\n\\verbinclude Tutorial_std_sort_rows_cxx11.out\n</td></tr></table>\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TutorialSlicingIndexing.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialSlicingIndexing Slicing and Indexing\n\nThis page presents the numerous possibilities offered by `operator()` to index sub-set of rows and columns.\nThis API has been introduced in %Eigen 3.4.\nIt supports all the feature proposed by the \\link TutorialBlockOperations block API \\endlink, and much more.\nIn particular, it supports \\b slicing that consists in taking a set of rows, columns, or elements, uniformly spaced within a matrix or indexed from an array of indices.\n\n\\eigenAutoToc\n\n\\section TutorialSlicingOverview Overview\n\nAll the aforementioned operations are handled through the generic DenseBase::operator()(const RowIndices&, const ColIndices&) method.\nEach argument can be:\n  - An integer indexing a single row or column, including symbolic indices.\n  - The symbol Eigen::all representing the whole set of respective rows or columns in increasing order.\n  - An ArithmeticSequence as constructed by the Eigen::seq, Eigen::seqN, or Eigen::lastN functions.\n  - Any 1D vector/array of integers including %Eigen's vector/array, expressions, std::vector, std::array, as well as plain C arrays: `int[N]`.\n\nMore generally, it can accepts any object exposing the following two member functions:\n  \\code\n  <integral type> operator[](<integral type>) const;\n  <integral type> size() const;\n  \\endcode\nwhere `<integral type>` stands for any integer type compatible with Eigen::Index (i.e. `std::ptrdiff_t`).\n\n\\section TutorialSlicingBasic Basic slicing\n\nTaking a set of rows, columns, or elements, uniformly spaced within a matrix or vector is achieved through the Eigen::seq or Eigen::seqN functions where \"seq\" stands for arithmetic sequence. Their signatures are summarized below:\n\n<table class=\"manual\">\n<tr>\n  <th>function</th>\n  <th>description</th>\n  <th>example</th>\n</tr>\n<tr>\n  <td>\\code seq(firstIdx,lastIdx) \\endcode</td>\n  <td>represents the sequence of integers ranging from \\c firstIdx to \\c lastIdx</td>\n  <td>\\code seq(2,5) <=> {2,3,4,5} \\endcode</td>\n</tr>\n<tr>\n  <td>\\code seq(firstIdx,lastIdx,incr) \\endcode</td>\n  <td>same but using the increment \\c incr to advance from one index to the next</td>\n  <td>\\code seq(2,8,2) <=> {2,4,6,8} \\endcode</td>\n</tr>\n<tr>\n  <td>\\code seqN(firstIdx,size) \\endcode</td>\n  <td>represents the sequence of \\c size integers starting from \\c firstIdx</td>\n  <td>\\code seqN(2,5) <=> {2,3,4,5,6} \\endcode</td>\n</tr>\n<tr>\n  <td>\\code seqN(firstIdx,size,incr) \\endcode</td>\n  <td>same but using the increment \\c incr to advance from one index to the next</td>\n  <td>\\code seqN(2,3,3) <=> {2,5,8} \\endcode</td>\n</tr>\n</table>\n\nThe \\c firstIdx and \\c lastIdx parameters can also be defined with the help of the Eigen::last symbol representing the index of the last row, column or element of the underlying matrix/vector once the arithmetic sequence is passed to it through operator().\nHere are some examples for a 2D array/matrix \\c A and a 1D array/vector \\c v.\n<table class=\"manual\">\n<tr>\n  <th>Intent</th>\n  <th>Code</th>\n  <th>Block-API equivalence</th>\n</tr>\n<tr>\n  <td>Bottom-left corner starting at row \\c i with \\c n columns</td>\n  <td>\\code A(seq(i,last), seqN(0,n)) \\endcode</td>\n  <td>\\code A.bottomLeftCorner(A.rows()-i,n) \\endcode</td>\n</tr>\n<tr>\n  <td>%Block starting at \\c i,j having \\c m rows, and \\c n columns</td>\n  <td>\\code A(seqN(i,m), seqN(i,n) \\endcode</td>\n  <td>\\code A.block(i,j,m,n) \\endcode</td>\n</tr>\n<tr>\n  <td>%Block starting at \\c i0,j0 and ending at \\c i1,j1</td>\n  <td>\\code A(seq(i0,i1), seq(j0,j1) \\endcode</td>\n  <td>\\code A.block(i0,j0,i1-i0+1,j1-j0+1) \\endcode</td>\n</tr>\n<tr>\n  <td>Even columns of A</td>\n  <td>\\code A(all, seq(0,last,2)) \\endcode</td>\n  <td></td>\n</tr>\n<tr>\n  <td>First \\c n odd rows A</td>\n  <td>\\code A(seqN(1,n,2), all) \\endcode</td>\n  <td></td>\n</tr>\n<tr>\n  <td>The last past one column</td>\n  <td>\\code A(all, last-1) \\endcode</td>\n  <td>\\code A.col(A.cols()-2) \\endcode</td>\n</tr>\n<tr>\n  <td>The middle row</td>\n  <td>\\code A(last/2,all) \\endcode</td>\n  <td>\\code A.row((A.rows()-1)/2) \\endcode</td>\n</tr>\n<tr>\n  <td>Last elements of v starting at i</td>\n  <td>\\code v(seq(i,last)) \\endcode</td>\n  <td>\\code v.tail(v.size()-i) \\endcode</td>\n</tr>\n<tr>\n  <td>Last \\c n elements of v</td>\n  <td>\\code v(seq(last+1-n,last)) \\endcode</td>\n  <td>\\code v.tail(n) \\endcode</td>\n</tr>\n</table>\n\nAs seen in the last exemple, referencing the <i> last n </i> elements (or rows/columns) is a bit cumbersome to write.\nThis becomes even more tricky and error prone with a non-default increment.\nHere comes \\link Eigen::lastN(SizeType) Eigen::lastN(size) \\endlink, and \\link Eigen::lastN(SizeType,IncrType) Eigen::lastN(size,incr) \\endlink:\n\n<table class=\"manual\">\n<tr>\n  <th>Intent</th>\n  <th>Code</th>\n  <th>Block-API equivalence</th>\n</tr>\n<tr>\n  <td>Last \\c n elements of v</td>\n  <td>\\code v(lastN(n)) \\endcode</td>\n  <td>\\code v.tail(n) \\endcode</td>\n</tr>\n<tr>\n  <td>Bottom-right corner of A of size \\c m times \\c n</td>\n  <td>\\code v(lastN(m), lastN(n)) \\endcode</td>\n  <td>\\code A.bottomRightCorner(m,n) \\endcode</td>\n</tr>\n<tr>\n  <td>Bottom-right corner of A of size \\c m times \\c n</td>\n  <td>\\code v(lastN(m), lastN(n)) \\endcode</td>\n  <td>\\code A.bottomRightCorner(m,n) \\endcode</td>\n</tr>\n<tr>\n  <td>Last \\c n columns taking 1 column over 3</td>\n  <td>\\code A(all, lastN(n,3)) \\endcode</td>\n  <td></td>\n</tr>\n</table>\n\n\\section TutorialSlicingFixed Compile time size and increment\n\nIn terms of performance, %Eigen and the compiler can take advantage of compile-time size and increment.\nTo this end, you can enforce compile-time parameters using Eigen::fix<val>.\nSuch compile-time value can be combined with the Eigen::last symbol:\n\\code v(seq(last-fix<7>, last-fix<2>))\n\\endcode\nIn this example %Eigen knowns at compile-time that the returned expression has 6 elements.\nIt is equivalent to:\n\\code v(seqN(last-7, fix<6>))\n\\endcode\n\nWe can revisit the <i>even columns of A</i> example as follows:\n\\code A(all, seq(0,last,fix<2>))\n\\endcode\n\n\n\\section TutorialSlicingReverse Reverse order\n\nRow/column indices can also be enumerated in decreasing order using a negative increment.\nFor instance, one over two columns of A from the column 20 to 10:\n\\code A(all, seq(20, 10, fix<-2>))\n\\endcode\nThe last \\c n rows starting from the last one:\n\\code A(seqN(last, n, fix<-1>), all)\n\\endcode\nYou can also use the ArithmeticSequence::reverse() method to reverse its order.\nThe previous example can thus also be written as:\n\\code A(lastN(n).reverse(), all)\n\\endcode\n\n\n\\section TutorialSlicingArray Array of indices\n\nThe generic `operator()` can also takes as input an arbitrary list of row or column indices stored as either an `ArrayXi`, a `std::vector<int>`, `std::array<int,N>`, etc.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Slicing_stdvector_cxx11.cpp\n</td>\n<td>\n\\verbinclude Slicing_stdvector_cxx11.out\n</td></tr></table>\n\nYou can also directly pass a static array:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Slicing_rawarray_cxx11.cpp\n</td>\n<td>\n\\verbinclude Slicing_rawarray_cxx11.out\n</td></tr></table>\n\nor expressions:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Slicing_arrayexpr.cpp\n</td>\n<td>\n\\verbinclude Slicing_arrayexpr.out\n</td></tr></table>\n\nWhen passing an object with a compile-time size such as `Array4i`, `std::array<int,N>`, or a static array, then the returned expression also exhibit compile-time dimensions.\n\n\\section TutorialSlicingCustomArray Custom index list\n\nMore generally, `operator()` can accept as inputs any object \\c ind of type \\c T compatible with:\n\\code\nIndex s = ind.size(); or Index s = size(ind);\nIndex i;\ni = ind[i];\n\\endcode\n\nThis means you can easily build your own fancy sequence generator and pass it to `operator()`.\nHere is an exemple enlarging a given matrix while padding the additional first rows and columns through repetition:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Slicing_custom_padding_cxx11.cpp\n</td>\n<td>\n\\verbinclude Slicing_custom_padding_cxx11.out\n</td></tr></table>\n\n<br>\n\n*/\n\n/*\nTODO add:\nso_repeat_inner.cpp\nso_repeleme.cpp\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TutorialSparse.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialSparse Sparse matrix manipulations\n\n\\eigenAutoToc\n\nManipulating and solving sparse problems involves various modules which are summarized below:\n\n<table class=\"manual\">\n<tr><th>Module</th><th>Header file</th><th>Contents</th></tr>\n<tr><td>\\link SparseCore_Module SparseCore \\endlink</td><td>\\code#include <Eigen/SparseCore>\\endcode</td><td>SparseMatrix and SparseVector classes, matrix assembly, basic sparse linear algebra (including sparse triangular solvers)</td></tr>\n<tr><td>\\link SparseCholesky_Module SparseCholesky \\endlink</td><td>\\code#include <Eigen/SparseCholesky>\\endcode</td><td>Direct sparse LLT and LDLT Cholesky factorization to solve sparse self-adjoint positive definite problems</td></tr>\n<tr><td>\\link SparseLU_Module SparseLU \\endlink</td><td>\\code #include<Eigen/SparseLU> \\endcode</td>\n<td>%Sparse LU factorization to solve general square sparse systems</td></tr>\n<tr><td>\\link SparseQR_Module SparseQR \\endlink</td><td>\\code #include<Eigen/SparseQR>\\endcode </td><td>%Sparse QR factorization for solving sparse linear least-squares problems</td></tr>\n<tr><td>\\link IterativeLinearSolvers_Module IterativeLinearSolvers \\endlink</td><td>\\code#include <Eigen/IterativeLinearSolvers>\\endcode</td><td>Iterative solvers to solve large general linear square problems (including self-adjoint positive definite problems)</td></tr>\n<tr><td>\\link Sparse_Module Sparse \\endlink</td><td>\\code#include <Eigen/Sparse>\\endcode</td><td>Includes all the above modules</td></tr>\n</table>\n\n\\section TutorialSparseIntro Sparse matrix format\n\nIn many applications (e.g., finite element methods) it is common to deal with very large matrices where only a few coefficients are different from zero.  In such cases, memory consumption can be reduced and performance increased by using a specialized representation storing only the nonzero coefficients. Such a matrix is called a sparse matrix.\n\n\\b The \\b %SparseMatrix \\b class\n\nThe class SparseMatrix is the main sparse matrix representation of Eigen's sparse module; it offers high performance and low memory usage.\nIt implements a more versatile variant of the widely-used Compressed Column (or Row) Storage scheme.\nIt consists of four compact arrays:\n - \\c Values: stores the coefficient values of the non-zeros.\n - \\c InnerIndices: stores the row (resp. column) indices of the non-zeros.\n - \\c OuterStarts: stores for each column (resp. row) the index of the first non-zero in the previous two arrays.\n - \\c InnerNNZs: stores the number of non-zeros of each column (resp. row).\nThe word \\c inner refers to an \\em inner \\em vector that is a column for a column-major matrix, or a row for a row-major matrix.\nThe word \\c outer refers to the other direction.\n\nThis storage scheme is better explained on an example. The following matrix\n<table class=\"manual\">\n<tr><td> 0</td><td>3</td><td> 0</td><td>0</td><td> 0</td></tr>\n<tr><td>22</td><td>0</td><td> 0</td><td>0</td><td>17</td></tr>\n<tr><td> 7</td><td>5</td><td> 0</td><td>1</td><td> 0</td></tr>\n<tr><td> 0</td><td>0</td><td> 0</td><td>0</td><td> 0</td></tr>\n<tr><td> 0</td><td>0</td><td>14</td><td>0</td><td> 8</td></tr>\n</table>\n\nand one of its possible sparse, \\b column \\b major representation:\n<table class=\"manual\">\n<tr><td>Values:</td>        <td>22</td><td>7</td><td>_</td><td>3</td><td>5</td><td>14</td><td>_</td><td>_</td><td>1</td><td>_</td><td>17</td><td>8</td></tr>\n<tr><td>InnerIndices:</td>  <td> 1</td><td>2</td><td>_</td><td>0</td><td>2</td><td> 4</td><td>_</td><td>_</td><td>2</td><td>_</td><td> 1</td><td>4</td></tr>\n</table>\n<table class=\"manual\">\n<tr><td>OuterStarts:</td><td>0</td><td>3</td><td>5</td><td>8</td><td>10</td><td>\\em 12 </td></tr>\n<tr><td>InnerNNZs:</td>    <td>2</td><td>2</td><td>1</td><td>1</td><td> 2</td><td></td></tr>\n</table>\n\nCurrently the elements of a given inner vector are guaranteed to be always sorted by increasing inner indices.\nThe \\c \"_\" indicates available free space to quickly insert new elements.\nAssuming no reallocation is needed, the insertion of a random element is therefore in `O(nnz_j)` where `nnz_j` is the number of nonzeros of the respective inner vector.\nOn the other hand, inserting elements with increasing inner indices in a given inner vector is much more efficient since this only requires to increase the respective \\c InnerNNZs entry that is a `O(1)` operation.\n\nThe case where no empty space is available is a special case, and is referred as the \\em compressed mode.\nIt corresponds to the widely used Compressed Column (or Row) Storage schemes (CCS or CRS).\nAny SparseMatrix can be turned to this form by calling the SparseMatrix::makeCompressed() function.\nIn this case, one can remark that the \\c InnerNNZs array is redundant with \\c OuterStarts because we have the equality: `InnerNNZs[j] == OuterStarts[j+1] - OuterStarts[j]`.\nTherefore, in practice a call to SparseMatrix::makeCompressed() frees this buffer.\n\nIt is worth noting that most of our wrappers to external libraries requires compressed matrices as inputs.\n\nThe results of %Eigen's operations always produces \\b compressed sparse matrices.\nOn the other hand, the insertion of a new element into a SparseMatrix converts this later to the \\b uncompressed mode.\n\nHere is the previous matrix represented in compressed mode:\n<table class=\"manual\">\n<tr><td>Values:</td>        <td>22</td><td>7</td><td>3</td><td>5</td><td>14</td><td>1</td><td>17</td><td>8</td></tr>\n<tr><td>InnerIndices:</td>  <td> 1</td><td>2</td><td>0</td><td>2</td><td> 4</td><td>2</td><td> 1</td><td>4</td></tr>\n</table>\n<table class=\"manual\">\n<tr><td>OuterStarts:</td><td>0</td><td>2</td><td>4</td><td>5</td><td>6</td><td>\\em 8 </td></tr>\n</table>\n\nA SparseVector is a special case of a SparseMatrix where only the \\c Values and \\c InnerIndices arrays are stored.\nThere is no notion of compressed/uncompressed mode for a SparseVector.\n\n\n\\section TutorialSparseExample First example\n\nBefore describing each individual class, let's start with the following typical example: solving the Laplace equation \\f$ \\Delta u = 0 \\f$ on a regular 2D grid using a finite difference scheme and Dirichlet boundary conditions.\nSuch problem can be mathematically expressed as a linear problem of the form \\f$ Ax=b \\f$ where \\f$ x \\f$ is the vector of \\c m unknowns (in our case, the values of the pixels), \\f$ b \\f$ is the right hand side vector resulting from the boundary conditions, and \\f$ A \\f$ is an \\f$ m \\times m \\f$ matrix containing only a few non-zero elements resulting from the discretization of the Laplacian operator.\n\n<table class=\"manual\">\n<tr><td>\n\\include Tutorial_sparse_example.cpp\n</td>\n<td>\n\\image html Tutorial_sparse_example.jpeg\n</td></tr></table>\n\nIn this example, we start by defining a column-major sparse matrix type of double \\c SparseMatrix<double>, and a triplet list of the same scalar type \\c  Triplet<double>. A triplet is a simple object representing a non-zero entry as the triplet: \\c row index, \\c column index, \\c value.\n\nIn the main function, we declare a list \\c coefficients of triplets (as a std vector) and the right hand side vector \\f$ b \\f$ which are filled by the \\a buildProblem function.\nThe raw and flat list of non-zero entries is then converted to a true SparseMatrix object \\c A.\nNote that the elements of the list do not have to be sorted, and possible duplicate entries will be summed up.\n\nThe last step consists of effectively solving the assembled problem.\nSince the resulting matrix \\c A is symmetric by construction, we can perform a direct Cholesky factorization via the SimplicialLDLT class which behaves like its LDLT counterpart for dense objects.\n\nThe resulting vector \\c x contains the pixel values as a 1D array which is saved to a jpeg file shown on the right of the code above.\n\nDescribing the \\a buildProblem and \\a save functions is out of the scope of this tutorial. They are given \\ref TutorialSparse_example_details \"here\" for the curious and reproducibility purpose.\n\n\n\n\n\\section TutorialSparseSparseMatrix The SparseMatrix class\n\n\\b %Matrix \\b and \\b vector \\b properties \\n\n\nThe SparseMatrix and SparseVector classes take three template arguments:\n * the scalar type (e.g., double)\n * the storage order (ColMajor or RowMajor, the default is ColMajor)\n * the inner index type (default is \\c int).\n\nAs for dense Matrix objects, constructors takes the size of the object.\nHere are some examples:\n\n\\code\nSparseMatrix<std::complex<float> > mat(1000,2000);         // declares a 1000x2000 column-major compressed sparse matrix of complex<float>\nSparseMatrix<double,RowMajor> mat(1000,2000);              // declares a 1000x2000 row-major compressed sparse matrix of double\nSparseVector<std::complex<float> > vec(1000);              // declares a column sparse vector of complex<float> of size 1000\nSparseVector<double,RowMajor> vec(1000);                   // declares a row sparse vector of double of size 1000\n\\endcode\n\nIn the rest of the tutorial, \\c mat and \\c vec represent any sparse-matrix and sparse-vector objects, respectively.\n\nThe dimensions of a matrix can be queried using the following functions:\n<table class=\"manual\">\n<tr><td>Standard \\n dimensions</td><td>\\code\nmat.rows()\nmat.cols()\\endcode</td>\n<td>\\code\nvec.size() \\endcode</td>\n</tr>\n<tr><td>Sizes along the \\n inner/outer dimensions</td><td>\\code\nmat.innerSize()\nmat.outerSize()\\endcode</td>\n<td></td>\n</tr>\n<tr><td>Number of non \\n zero coefficients</td><td>\\code\nmat.nonZeros() \\endcode</td>\n<td>\\code\nvec.nonZeros() \\endcode</td></tr>\n</table>\n\n\n\\b Iterating \\b over \\b the \\b nonzero \\b coefficients \\n\n\nRandom access to the elements of a sparse object can be done through the \\c coeffRef(i,j) function.\nHowever, this function involves a quite expensive binary search.\nIn most cases, one only wants to iterate over the non-zeros elements. This is achieved by a standard loop over the outer dimension, and then by iterating over the non-zeros of the current inner vector via an InnerIterator. Thus, the non-zero entries have to be visited in the same order than the storage order.\nHere is an example:\n<table class=\"manual\">\n<tr><td>\n\\code\nSparseMatrix<double> mat(rows,cols);\nfor (int k=0; k<mat.outerSize(); ++k)\n  for (SparseMatrix<double>::InnerIterator it(mat,k); it; ++it)\n  {\n    it.value();\n    it.row();   // row index\n    it.col();   // col index (here it is equal to k)\n    it.index(); // inner index, here it is equal to it.row()\n  }\n\\endcode\n</td><td>\n\\code\nSparseVector<double> vec(size);\nfor (SparseVector<double>::InnerIterator it(vec); it; ++it)\n{\n  it.value(); // == vec[ it.index() ]\n  it.index();\n}\n\\endcode\n</td></tr>\n</table>\nFor a writable expression, the referenced value can be modified using the valueRef() function.\nIf the type of the sparse matrix or vector depends on a template parameter, then the \\c typename keyword is\nrequired to indicate that \\c InnerIterator denotes a type; see \\ref TopicTemplateKeyword for details.\n\n\n\\section TutorialSparseFilling Filling a sparse matrix\n\nBecause of the special storage scheme of a SparseMatrix, special care has to be taken when adding new nonzero entries.\nFor instance, the cost of a single purely random insertion into a SparseMatrix is \\c O(nnz), where \\c nnz is the current number of non-zero coefficients.\n\nThe simplest way to create a sparse matrix while guaranteeing good performance is thus to first build a list of so-called \\em triplets, and then convert it to a SparseMatrix.\n\nHere is a typical usage example:\n\\code\ntypedef Eigen::Triplet<double> T;\nstd::vector<T> tripletList;\ntripletList.reserve(estimation_of_entries);\nfor(...)\n{\n  // ...\n  tripletList.push_back(T(i,j,v_ij));\n}\nSparseMatrixType mat(rows,cols);\nmat.setFromTriplets(tripletList.begin(), tripletList.end());\n// mat is ready to go!\n\\endcode\nThe \\c std::vector of triplets might contain the elements in arbitrary order, and might even contain duplicated elements that will be summed up by setFromTriplets().\nSee the SparseMatrix::setFromTriplets() function and class Triplet for more details.\n\n\nIn some cases, however, slightly higher performance, and lower memory consumption can be reached by directly inserting the non-zeros into the destination matrix.\nA typical scenario of this approach is illustrated below:\n\\code\n1: SparseMatrix<double> mat(rows,cols);         // default is column major\n2: mat.reserve(VectorXi::Constant(cols,6));\n3: for each i,j such that v_ij != 0\n4:   mat.insert(i,j) = v_ij;                    // alternative: mat.coeffRef(i,j) += v_ij;\n5: mat.makeCompressed();                        // optional\n\\endcode\n\n- The key ingredient here is the line 2 where we reserve room for 6 non-zeros per column. In many cases, the number of non-zeros per column or row can easily be known in advance. If it varies significantly for each inner vector, then it is possible to specify a reserve size for each inner vector by providing a vector object with an `operator[](int j)` returning the reserve size of the \\c j-th inner vector (e.g., via a `VectorXi` or `std::vector<int>`). If only a rought estimate of the number of nonzeros per inner-vector can be obtained, it is highly recommended to overestimate it rather than the opposite. If this line is omitted, then the first insertion of a new element will reserve room for 2 elements per inner vector.\n- The line 4 performs a sorted insertion. In this example, the ideal case is when the \\c j-th column is not full and contains non-zeros whose inner-indices are smaller than \\c i. In this case, this operation boils down to trivial O(1) operation.\n- When calling `insert(i,j)` the element `i`, `j` must not already exists, otherwise use the `coeffRef(i,j)` method that will allow to, e.g., accumulate values. This method first performs a binary search and finally calls `insert(i,j)` if the element does not already exist. It is more flexible than `insert()` but also more costly.\n- The line 5 suppresses the remaining empty space and transforms the matrix into a compressed column storage.\n\n\n\n\\section TutorialSparseFeatureSet Supported operators and functions\n\nBecause of their special storage format, sparse matrices cannot offer the same level of flexibility than dense matrices.\nIn Eigen's sparse module we chose to expose only the subset of the dense matrix API which can be efficiently implemented.\nIn the following \\em sm denotes a sparse matrix, \\em sv a sparse vector, \\em dm a dense matrix, and \\em dv a dense vector.\n\n\\subsection TutorialSparse_BasicOps Basic operations\n\n%Sparse expressions support most of the unary and binary coefficient wise operations:\n\\code\nsm1.real()   sm1.imag()   -sm1                    0.5*sm1\nsm1+sm2      sm1-sm2      sm1.cwiseProduct(sm2)\n\\endcode\nHowever, <strong>a strong restriction is that the storage orders must match</strong>. For instance, in the following example:\n\\code\nsm4 = sm1 + sm2 + sm3;\n\\endcode\nsm1, sm2, and sm3 must all be row-major or all column-major.\nOn the other hand, there is no restriction on the target matrix sm4.\nFor instance, this means that for computing \\f$ A^T + A \\f$, the matrix \\f$ A^T \\f$ must be evaluated into a temporary matrix of compatible storage order:\n\\code\nSparseMatrix<double> A, B;\nB = SparseMatrix<double>(A.transpose()) + A;\n\\endcode\n\nBinary coefficient wise operators can also mix sparse and dense expressions:\n\\code\nsm2 = sm1.cwiseProduct(dm1);\ndm2 = sm1 + dm1;\ndm2 = dm1 - sm1;\n\\endcode\nPerformance-wise, the adding/subtracting sparse and dense matrices is better performed in two steps. For instance, instead of doing `dm2 = sm1 + dm1`, better write:\n\\code\ndm2 = dm1;\ndm2 += sm1;\n\\endcode\nThis version has the advantage to fully exploit the higher performance of dense storage (no indirection, SIMD, etc.), and to pay the cost of slow sparse evaluation on the few non-zeros of the sparse matrix only.\n\n\n%Sparse expressions also support transposition:\n\\code\nsm1 = sm2.transpose();\nsm1 = sm2.adjoint();\n\\endcode\nHowever, there is no `transposeInPlace()` method.\n\n\n\\subsection TutorialSparse_Products Matrix products\n\n%Eigen supports various kind of sparse matrix products which are summarize below:\n  - \\b sparse-dense:\n    \\code\ndv2 = sm1 * dv1;\ndm2 = dm1 * sm1.adjoint();\ndm2 = 2. * sm1 * dm1;\n    \\endcode\n  - \\b symmetric \\b sparse-dense. The product of a sparse symmetric matrix with a dense matrix (or vector) can also be optimized by specifying the symmetry with `selfadjointView()`:\n    \\code\ndm2 = sm1.selfadjointView<>() * dm1;          // if all coefficients of sm1 are stored\ndm2 = sm1.selfadjointView<Upper>() * dm1;     // if only the upper part of sm1 is stored\ndm2 = sm1.selfadjointView<Lower>() * dm1;     // if only the lower part of sm1 is stored\n    \\endcode\n  - \\b sparse-sparse. For sparse-sparse products, two different algorithms are available. The default one is conservative and preserve the explicit zeros that might appear:\n    \\code\nsm3 = sm1 * sm2;\nsm3 = 4 * sm1.adjoint() * sm2;\n    \\endcode\n    The second algorithm prunes on the fly the explicit zeros, or the values smaller than a given threshold. It is enabled and controlled through the `prune()` functions:\n    \\code\nsm3 = (sm1 * sm2).pruned();                  // removes numerical zeros\nsm3 = (sm1 * sm2).pruned(ref);               // removes elements much smaller than ref\nsm3 = (sm1 * sm2).pruned(ref,epsilon);       // removes elements smaller than ref*epsilon\n    \\endcode\n\n  - \\b permutations. Finally, permutations can be applied to sparse matrices too:\n    \\code\nPermutationMatrix<Dynamic,Dynamic> P = ...;\nsm2 = P * sm1;\nsm2 = sm1 * P.inverse();\nsm2 = sm1.transpose() * P;\n    \\endcode\n\n\n\\subsection TutorialSparse_SubMatrices Block operations\n\nRegarding read-access, sparse matrices expose the same API than for dense matrices to access to sub-matrices such as blocks, columns, and rows. See \\ref TutorialBlockOperations for a detailed introduction.\nHowever, for performance reasons, writing to a sub-sparse-matrix is much more limited, and currently only contiguous sets of columns (resp. rows) of a column-major (resp. row-major) SparseMatrix are writable. Moreover, this information has to be known at compile-time, leaving out methods such as `block(...)` and `corner*(...)`. The available API for write-access to a SparseMatrix are summarized below:\n\\code\nSparseMatrix<double,ColMajor> sm1;\nsm1.col(j) = ...;\nsm1.leftCols(ncols) = ...;\nsm1.middleCols(j,ncols) = ...;\nsm1.rightCols(ncols) = ...;\n\nSparseMatrix<double,RowMajor> sm2;\nsm2.row(i) = ...;\nsm2.topRows(nrows) = ...;\nsm2.middleRows(i,nrows) = ...;\nsm2.bottomRows(nrows) = ...;\n\\endcode\n\nIn addition, sparse matrices expose the `SparseMatrixBase::innerVector()` and `SparseMatrixBase::innerVectors()` methods, which are aliases to the `col`/`middleCols` methods for a column-major storage, and to the `row`/`middleRows` methods for a row-major storage.\n\n\\subsection TutorialSparse_TriangularSelfadjoint Triangular and selfadjoint views\n\nJust as with dense matrices, the `triangularView()` function can be used to address a triangular part of the matrix, and perform triangular solves with a dense right hand side:\n\\code\ndm2 = sm1.triangularView<Lower>(dm1);\ndv2 = sm1.transpose().triangularView<Upper>(dv1);\n\\endcode\n\nThe `selfadjointView()` function permits various operations:\n - optimized sparse-dense matrix products:\n    \\code\ndm2 = sm1.selfadjointView<>() * dm1;          // if all coefficients of sm1 are stored\ndm2 = sm1.selfadjointView<Upper>() * dm1;     // if only the upper part of sm1 is stored\ndm2 = sm1.selfadjointView<Lower>() * dm1;     // if only the lower part of sm1 is stored\n    \\endcode\n - copy of triangular parts:\n    \\code\nsm2 = sm1.selfadjointView<Upper>();                               // makes a full selfadjoint matrix from the upper triangular part\nsm2.selfadjointView<Lower>() = sm1.selfadjointView<Upper>();      // copies the upper triangular part to the lower triangular part\n    \\endcode\n - application of symmetric permutations:\n \\code\nPermutationMatrix<Dynamic,Dynamic> P = ...;\nsm2 = A.selfadjointView<Upper>().twistedBy(P);                                // compute P S P' from the upper triangular part of A, and make it a full matrix\nsm2.selfadjointView<Lower>() = A.selfadjointView<Lower>().twistedBy(P);       // compute P S P' from the lower triangular part of A, and then only compute the lower part\n \\endcode\n\nPlease, refer to the \\link SparseQuickRefPage Quick Reference \\endlink  guide for the list of supported operations. The list of linear solvers available is \\link TopicSparseSystems here. \\endlink\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/TutorialSparse_example_details.dox",
    "content": "/**\n\\page TutorialSparse_example_details\n\\include Tutorial_sparse_example_details.cpp\n*/\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/UnalignedArrayAssert.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TopicUnalignedArrayAssert Explanation of the assertion on unaligned arrays\n\nHello! You are seeing this webpage because your program terminated on an assertion failure like this one:\n<pre>\nmy_program: path/to/eigen/Eigen/src/Core/DenseStorage.h:44:\nEigen::internal::matrix_array<T, Size, MatrixOptions, Align>::internal::matrix_array()\n[with T = double, int Size = 2, int MatrixOptions = 2, bool Align = true]:\nAssertion `(reinterpret_cast<size_t>(array) & (sizemask)) == 0 && \"this assertion\nis explained here: http://eigen.tuxfamily.org/dox-devel/group__TopicUnalignedArrayAssert.html\n**** READ THIS WEB PAGE !!! ****\"' failed.\n</pre>\n\nThere are 4 known causes for this issue.\nIf you can target \\cpp17 only with a recent compiler (e.g., GCC>=7, clang>=5, MSVC>=19.12), then you're lucky: enabling c++17 should be enough (if not, please <a href=\"http://eigen.tuxfamily.org/bz/\">report</a> to us).\nOtherwise, please read on to understand those issues and learn how to fix them.\n\n\\eigenAutoToc\n\n\\section where Where in my own code is the cause of the problem?\n\nFirst of all, you need to find out where in your own code this assertion was triggered from. At first glance, the error message doesn't look helpful, as it refers to a file inside Eigen! However, since your program crashed, if you can reproduce the crash, you can get a backtrace using any debugger. For example, if you're using GCC, you can use the GDB debugger as follows:\n\\code\n$ gdb ./my_program          # Start GDB on your program\n> run                       # Start running your program\n...                         # Now reproduce the crash!\n> bt                        # Obtain the backtrace\n\\endcode\nNow that you know precisely where in your own code the problem is happening, read on to understand what you need to change.\n\n\\section c1 Cause 1: Structures having Eigen objects as members\n\nIf you have code like this,\n\n\\code\nclass Foo\n{\n  //...\n  Eigen::Vector4d v;\n  //...\n};\n//...\nFoo *foo = new Foo;\n\\endcode\n\nthen you need to read this separate page: \\ref TopicStructHavingEigenMembers \"Structures Having Eigen Members\".\n\nNote that here, Eigen::Vector4d is only used as an example, more generally the issue arises for all \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen types\".\n\n\\section c2 Cause 2: STL Containers or manual memory allocation\n\nIf you use STL Containers such as std::vector, std::map, ..., with %Eigen objects, or with classes containing %Eigen objects, like this,\n\n\\code\nstd::vector<Eigen::Matrix2d> my_vector;\nstruct my_class { ... Eigen::Matrix2d m; ... };\nstd::map<int, my_class> my_map;\n\\endcode\n\nthen you need to read this separate page: \\ref TopicStlContainers \"Using STL Containers with Eigen\".\n\nNote that here, Eigen::Matrix2d is only used as an example, more generally the issue arises for all \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen types\" and \\ref TopicStructHavingEigenMembers \"structures having such Eigen objects as member\".\n\nThe same issue will be exhibited by any classes/functions by-passing operator new to allocate memory, that is, by performing custom memory allocation followed by calls to the placement new operator. This is for instance typically the case of \\c `std::make_shared` or `std::allocate_shared` for which is the solution is to use an \\ref aligned_allocator \"aligned allocator\" as detailed in the \\ref TopicStlContainers \"solution for STL containers\".\n\n\\section c3 Cause 3: Passing Eigen objects by value\n\nIf some function in your code is getting an %Eigen object passed by value, like this,\n\n\\code\nvoid func(Eigen::Vector4d v);\n\\endcode\n\nthen you need to read this separate page: \\ref TopicPassingByValue \"Passing Eigen objects by value to functions\".\n\nNote that here, Eigen::Vector4d is only used as an example, more generally the issue arises for all \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen types\".\n\n\\section c4 Cause 4: Compiler making a wrong assumption on stack alignment (for instance GCC on Windows)\n\nThis is a must-read for people using GCC on Windows (like MinGW or TDM-GCC). If you have this assertion failure in an innocent function declaring a local variable like this:\n\n\\code\nvoid foo()\n{\n  Eigen::Quaternionf q;\n  //...\n}\n\\endcode\n\nthen you need to read this separate page: \\ref TopicWrongStackAlignment \"Compiler making a wrong assumption on stack alignment\".\n\nNote that here, Eigen::Quaternionf is only used as an example, more generally the issue arises for all \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen types\".\n\n\n\\section explanation General explanation of this assertion\n\n\\ref TopicFixedSizeVectorizable \"Fixed-size vectorizable Eigen objects\" must absolutely be created at properly aligned locations, otherwise SIMD instructions addressing them will crash.\nFor instance, SSE/NEON/MSA/Altivec/VSX targets will require 16-byte-alignment, whereas AVX and AVX512 targets may require up to 32 and 64 byte alignment respectively.\n\n%Eigen normally takes care of these alignment issues for you, by setting an alignment attribute on them and by overloading their `operator new`.\n\nHowever there are a few corner cases where these alignment settings get overridden: they are the possible causes for this assertion.\n\n\\section getrid I don't care about optimal vectorization, how do I get rid of that stuff?\n\nThree possibilities:\n<ul>\n  <li>Use the \\c DontAlign option to Matrix, Array, Quaternion, etc. objects that gives you trouble. This way %Eigen won't try to over-align them, and thus won\"t assume any special alignment. On the down side, you will pay the cost of unaligned loads/stores for them, but on modern CPUs, the overhead is either null or marginal. See \\link StructHavingEigenMembers_othersolutions here \\endlink for an example.</li>\n  <li>Define \\link TopicPreprocessorDirectivesPerformance EIGEN_MAX_STATIC_ALIGN_BYTES \\endlink to 0. That disables all 16-byte (and above) static alignment code, while keeping 16-byte (or above) heap alignment. This has the effect of\n      vectorizing fixed-size objects (like Matrix4d) through unaligned stores (as controlled by \\link TopicPreprocessorDirectivesPerformance EIGEN_UNALIGNED_VECTORIZE \\endlink), while keeping unchanged the vectorization of dynamic-size objects\n      (like MatrixXd). On 64 bytes systems, you might also define it 16 to disable only 32 and 64 bytes of over-alignment. But do note that this breaks ABI compatibility with the default behavior of static alignment.</li>\n  <li>Or define both \\link TopicPreprocessorDirectivesPerformance  EIGEN_DONT_VECTORIZE \\endlink and `EIGEN_DISABLE_UNALIGNED_ARRAY_ASSERT`. This keeps the\n      16-byte (or above) alignment code and thus preserves ABI compatibility, but completely disables vectorization.</li>\n</ul>\n\nIf you want to know why defining `EIGEN_DONT_VECTORIZE` does not by itself disable 16-byte (or above) alignment and the assertion, here's the explanation:\n\nIt doesn't disable the assertion, because otherwise code that runs fine without vectorization would suddenly crash when enabling vectorization.\nIt doesn't disable 16-byte (or above) alignment, because that would mean that vectorized and non-vectorized code are not mutually ABI-compatible. This ABI compatibility is very important, even for people who develop only an in-house application, as for instance one may want to have in the same application a vectorized path and a non-vectorized path.\n\n\\section checkmycode How can I check my code is safe regarding alignment issues?\n\nUnfortunately, there is no possibility in c++ to detect any of the aforementioned shortcoming at compile time (though static analyzers are becoming more and more powerful and could detect some of them).\nEven at runtime, all we can do is to catch invalid unaligned allocation and trigger the explicit assertion mentioned at the beginning of this page.\nTherefore, if your program runs fine on a given system with some given compilation flags, then this does not guarantee that your code is safe. For instance, on most 64 bits systems buffer are aligned on 16 bytes boundary and so, if you do not enable AVX instruction set, then your code will run fine. On the other hand, the same code may assert if moving to a more exotic platform, or enabling AVX instructions that required 32 bytes alignment by default.\n\nThe situation is not hopeless though. Assuming your code is well covered by unit test, then you can check its alignment safety by linking it to a custom malloc library returning 8 bytes aligned buffers only. This way all alignment shortcomings should pop-up. To this end, you must also compile your program with \\link TopicPreprocessorDirectivesPerformance EIGEN_MALLOC_ALREADY_ALIGNED=0 \\endlink.\n\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/UsingBlasLapackBackends.dox",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n Copyright (C) 2011-2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Documentation on the use of BLAS/LAPACK libraries through Eigen\n ********************************************************************************\n*/\n\nnamespace Eigen {\n\n/** \\page TopicUsingBlasLapack Using BLAS/LAPACK from %Eigen\n\n\nSince %Eigen version 3.3 and later, any F77 compatible BLAS or LAPACK libraries can be used as backends for dense matrix products and dense matrix decompositions.\nFor instance, one can use <a href=\"http://eigen.tuxfamily.org/Counter/redirect_to_mkl.php\">Intel® MKL</a>, Apple's Accelerate framework on OSX, <a href=\"http://www.openblas.net/\">OpenBLAS</a>, <a href=\"http://www.netlib.org/lapack\">Netlib LAPACK</a>, etc.\n\nDo not miss this \\link TopicUsingIntelMKL page \\endlink for further discussions on the specific use of Intel® MKL (also includes VML, PARDISO, etc.)\n\nIn order to use an external BLAS and/or LAPACK library, you must link you own application to the respective libraries and their dependencies.\nFor LAPACK, you must also link to the standard <a href=\"http://www.netlib.org/lapack/lapacke.html\">Lapacke</a> library, which is used as a convenient think layer between %Eigen's C++ code and LAPACK F77 interface. Then you must activate their usage by defining one or multiple of the following macros (\\b before including any %Eigen's header):\n\n\\note For Mac users, in order to use the lapack version shipped with the Accelerate framework, you also need the lapacke library.\nUsing <a href=\"https://www.macports.org/\">MacPorts</a>, this is as easy as:\n\\code\nsudo port install lapack\n\\endcode\nand then use the following link flags: \\c -framework \\c Accelerate \\c /opt/local/lib/lapack/liblapacke.dylib\n\n<table class=\"manual\">\n<tr><td>\\c EIGEN_USE_BLAS </td><td>Enables the use of external BLAS level 2 and 3 routines (compatible with any F77 BLAS interface)</td></tr>\n<tr class=\"alt\"><td>\\c EIGEN_USE_LAPACKE </td><td>Enables the use of external Lapack routines via the <a href=\"http://www.netlib.org/lapack/lapacke.html\">Lapacke</a> C interface to Lapack (compatible with any F77 LAPACK interface)</td></tr>\n<tr><td>\\c EIGEN_USE_LAPACKE_STRICT </td><td>Same as \\c EIGEN_USE_LAPACKE but algorithms of lower numerical robustness are disabled. \\n This currently concerns only JacobiSVD which otherwise would be replaced by \\c gesvd that is less robust than Jacobi rotations.</td></tr>\n</table>\n\nWhen doing so, a number of %Eigen's algorithms are silently substituted with calls to BLAS or LAPACK routines.\nThese substitutions apply only for \\b Dynamic \\b or \\b large enough objects with one of the following four standard scalar types: \\c float, \\c double, \\c complex<float>, and \\c complex<double>.\nOperations on other scalar types or mixing reals and complexes will continue to use the built-in algorithms.\n\nThe breadth of %Eigen functionality that can be substituted is listed in the table below.\n<table class=\"manual\">\n<tr><th>Functional domain</th><th>Code example</th><th>BLAS/LAPACK routines</th></tr>\n<tr><td>Matrix-matrix operations \\n \\c EIGEN_USE_BLAS </td><td>\\code\nm1*m2.transpose();\nm1.selfadjointView<Lower>()*m2;\nm1*m2.triangularView<Upper>();\nm1.selfadjointView<Lower>().rankUpdate(m2,1.0);\n\\endcode</td><td>\\code\n?gemm\n?symm/?hemm\n?trmm\ndsyrk/ssyrk\n\\endcode</td></tr>\n<tr class=\"alt\"><td>Matrix-vector operations \\n \\c EIGEN_USE_BLAS </td><td>\\code\nm1.adjoint()*b;\nm1.selfadjointView<Lower>()*b;\nm1.triangularView<Upper>()*b;\n\\endcode</td><td>\\code\n?gemv\n?symv/?hemv\n?trmv\n\\endcode</td></tr>\n<tr><td>LU decomposition \\n \\c EIGEN_USE_LAPACKE \\n \\c EIGEN_USE_LAPACKE_STRICT </td><td>\\code\nv1 = m1.lu().solve(v2);\n\\endcode</td><td>\\code\n?getrf\n\\endcode</td></tr>\n<tr class=\"alt\"><td>Cholesky decomposition \\n \\c EIGEN_USE_LAPACKE \\n \\c EIGEN_USE_LAPACKE_STRICT </td><td>\\code\nv1 = m2.selfadjointView<Upper>().llt().solve(v2);\n\\endcode</td><td>\\code\n?potrf\n\\endcode</td></tr>\n<tr><td>QR decomposition \\n \\c EIGEN_USE_LAPACKE \\n \\c EIGEN_USE_LAPACKE_STRICT </td><td>\\code\nm1.householderQr();\nm1.colPivHouseholderQr();\n\\endcode</td><td>\\code\n?geqrf\n?geqp3\n\\endcode</td></tr>\n<tr class=\"alt\"><td>Singular value decomposition \\n \\c EIGEN_USE_LAPACKE </td><td>\\code\nJacobiSVD<MatrixXd> svd;\nsvd.compute(m1, ComputeThinV);\n\\endcode</td><td>\\code\n?gesvd\n\\endcode</td></tr>\n<tr><td>Eigen-value decompositions \\n \\c EIGEN_USE_LAPACKE \\n \\c EIGEN_USE_LAPACKE_STRICT </td><td>\\code\nEigenSolver<MatrixXd> es(m1);\nComplexEigenSolver<MatrixXcd> ces(m1);\nSelfAdjointEigenSolver<MatrixXd> saes(m1+m1.transpose());\nGeneralizedSelfAdjointEigenSolver<MatrixXd>\n    gsaes(m1+m1.transpose(),m2+m2.transpose());\n\\endcode</td><td>\\code\n?gees\n?gees\n?syev/?heev\n?syev/?heev,\n?potrf\n\\endcode</td></tr>\n<tr class=\"alt\"><td>Schur decomposition \\n \\c EIGEN_USE_LAPACKE \\n \\c EIGEN_USE_LAPACKE_STRICT </td><td>\\code\nRealSchur<MatrixXd> schurR(m1);\nComplexSchur<MatrixXcd> schurC(m1);\n\\endcode</td><td>\\code\n?gees\n\\endcode</td></tr>\n</table>\nIn the examples, m1 and m2 are dense matrices and v1 and v2 are dense vectors.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/UsingIntelMKL.dox",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n Copyright (C) 2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Documentation on the use of Intel MKL through Eigen\n ********************************************************************************\n*/\n\nnamespace Eigen {\n\n/** \\page TopicUsingIntelMKL Using Intel® MKL from %Eigen\n\n<!-- \\section TopicUsingIntelMKL_Intro Eigen and Intel® Math Kernel Library (Intel® MKL) -->\n\nSince %Eigen version 3.1 and later, users can benefit from built-in Intel® Math Kernel Library (MKL) optimizations with an installed copy of Intel MKL 10.3 (or later).\n\n<a href=\"http://eigen.tuxfamily.org/Counter/redirect_to_mkl.php\"> Intel MKL </a> provides highly optimized multi-threaded mathematical routines for x86-compatible architectures.\nIntel MKL is available on Linux, Mac and Windows for both Intel64 and IA32 architectures.\n\n\\note\nIntel® MKL is a proprietary software and it is the responsibility of users to buy or register for community (free) Intel MKL licenses for their products. Moreover, the license of the user product has to allow linking to proprietary software that excludes any unmodified versions of the GPL.\n\nUsing Intel MKL through %Eigen is easy:\n-# define the \\c EIGEN_USE_MKL_ALL macro before including any %Eigen's header\n-# link your program to MKL libraries (see the <a href=\"http://software.intel.com/en-us/articles/intel-mkl-link-line-advisor/\">MKL linking advisor</a>)\n-# on a 64bits system, you must use the LP64 interface (not the ILP64 one)\n\nWhen doing so, a number of %Eigen's algorithms are silently substituted with calls to Intel MKL routines.\nThese substitutions apply only for \\b Dynamic \\b or \\b large enough objects with one of the following four standard scalar types: \\c float, \\c double, \\c complex<float>, and \\c complex<double>.\nOperations on other scalar types or mixing reals and complexes will continue to use the built-in algorithms.\n\nIn addition you can choose which parts will be substituted by defining one or multiple of the following macros:\n\n<table class=\"manual\">\n<tr><td>\\c EIGEN_USE_BLAS </td><td>Enables the use of external BLAS level 2 and 3 routines</td></tr>\n<tr class=\"alt\"><td>\\c EIGEN_USE_LAPACKE </td><td>Enables the use of external Lapack routines via the <a href=\"http://www.netlib.org/lapack/lapacke.html\">Lapacke</a> C interface to Lapack</td></tr>\n<tr><td>\\c EIGEN_USE_LAPACKE_STRICT </td><td>Same as \\c EIGEN_USE_LAPACKE but algorithm of lower robustness are disabled. \\n This currently concerns only JacobiSVD which otherwise would be replaced by \\c gesvd that is less robust than Jacobi rotations.</td></tr>\n<tr class=\"alt\"><td>\\c EIGEN_USE_MKL_VML </td><td>Enables the use of Intel VML (vector operations)</td></tr>\n<tr><td>\\c EIGEN_USE_MKL_ALL </td><td>Defines \\c EIGEN_USE_BLAS, \\c EIGEN_USE_LAPACKE, and \\c EIGEN_USE_MKL_VML </td></tr>\n</table>\n\nThe \\c EIGEN_USE_BLAS and \\c EIGEN_USE_LAPACKE* macros can be combined with \\c EIGEN_USE_MKL to explicitly tell Eigen that the underlying BLAS/Lapack implementation is Intel MKL.\nThe main effect is to enable MKL direct call feature (\\c MKL_DIRECT_CALL).\nThis may help to increase performance of some MKL BLAS (?GEMM, ?GEMV, ?TRSM, ?AXPY and ?DOT) and LAPACK (LU, Cholesky and QR) routines for very small matrices.\nMKL direct call can be disabled by defining \\c EIGEN_MKL_NO_DIRECT_CALL.\n\n\nNote that the BLAS and LAPACKE backends can be enabled for any F77 compatible BLAS and LAPACK libraries. See this \\link TopicUsingBlasLapack page \\endlink for the details.\n\nFinally, the PARDISO sparse solver shipped with Intel MKL can be used through the \\ref PardisoLU, \\ref PardisoLLT and \\ref PardisoLDLT classes of the \\ref PardisoSupport_Module.\n\nThe following table summarizes the list of functions covered by \\c EIGEN_USE_MKL_VML:\n<table class=\"manual\">\n<tr><th>Code example</th><th>MKL routines</th></tr>\n<tr><td>\\code\nv2=v1.array().sin();\nv2=v1.array().asin();\nv2=v1.array().cos();\nv2=v1.array().acos();\nv2=v1.array().tan();\nv2=v1.array().exp();\nv2=v1.array().log();\nv2=v1.array().sqrt();\nv2=v1.array().square();\nv2=v1.array().pow(1.5);\n\\endcode</td><td>\\code\nv?Sin\nv?Asin\nv?Cos\nv?Acos\nv?Tan\nv?Exp\nv?Ln\nv?Sqrt\nv?Sqr\nv?Powx\n\\endcode</td></tr>\n</table>\nIn the examples, v1 and v2 are dense vectors.\n\n\n\\section TopicUsingIntelMKL_Links Links\n- Intel MKL can be purchased and downloaded <a href=\"http://eigen.tuxfamily.org/Counter/redirect_to_mkl.php\">here</a>.\n- Intel MKL is also bundled with <a href=\"http://software.intel.com/en-us/articles/intel-composer-xe/\">Intel Composer XE</a>.\n\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/UsingNVCC.dox",
    "content": "\nnamespace Eigen {\n\n/** \\page TopicCUDA Using Eigen in CUDA kernels\n\nStaring from CUDA 5.5 and Eigen 3.3, it is possible to use Eigen's matrices, vectors, and arrays for fixed size within CUDA kernels. This is especially useful when working on numerous but small problems. By default, when Eigen's headers are included within a .cu file compiled by nvcc most Eigen's functions and methods are prefixed by the \\c __device__ \\c __host__ keywords making them callable from both host and device code.\nThis support can be disabled by defining \\c EIGEN_NO_CUDA before including any Eigen's header.\nThis might be useful to disable some warnings when a .cu file makes use of Eigen on the host side only.\nHowever, in both cases, host's SIMD vectorization has to be disabled in .cu files.\nIt is thus \\b strongly \\b recommended to properly move all costly host computation from your .cu files to regular .cpp files.\n\nKnown issues:\n\n - \\c nvcc with MS Visual Studio does not work (patch welcome)\n \n - \\c nvcc 5.5 with gcc-4.7 (or greater) has issues with the standard \\c \\<limits\\> header file. To workaround this, you can add the following before including any other files:\n   \\code\n    // workaround issue between gcc >= 4.7 and cuda 5.5\n    #if (defined __GNUC__) && (__GNUC__>4 || __GNUC_MINOR__>=7)\n      #undef _GLIBCXX_ATOMIC_BUILTINS\n      #undef _GLIBCXX_USE_INT128\n    #endif\n   \\endcode\n   \n - On 64bits system Eigen uses \\c long \\c int as the default type for indexes and sizes. On CUDA device, it would make sense to default to 32 bits \\c int.\n   However, to keep host and CUDA code compatible, this cannot be done automatically by %Eigen, and the user is thus required to define \\c EIGEN_DEFAULT_DENSE_INDEX_TYPE to \\c int throughout his code (or only for CUDA code if there is no interaction between host and CUDA code through %Eigen's object).\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/WrongStackAlignment.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TopicWrongStackAlignment Compiler making a wrong assumption on stack alignment\n\n<h4>It appears that this was a GCC bug that has been fixed in GCC 4.5.\nIf you hit this issue, please upgrade to GCC 4.5 and report to us, so we can update this page.</h4>\n\nThis is an issue that, so far, we met only with GCC on Windows: for instance, MinGW and TDM-GCC.\n\nBy default, in a function like this,\n\n\\code\nvoid foo()\n{\n  Eigen::Quaternionf q;\n  //...\n}\n\\endcode\n\nGCC assumes that the stack is already 16-byte-aligned so that the object \\a q will be created at a 16-byte-aligned location. For this reason, it doesn't take any special care to explicitly align the object \\a q, as Eigen requires.\n\nThe problem is that, in some particular cases, this assumption can be wrong on Windows, where the stack is only guaranteed to have 4-byte alignment. Indeed, even though GCC takes care of aligning the stack in the main function and does its best to keep it aligned, when a function is called from another thread or from a binary compiled with another compiler, the stack alignment can be corrupted. This results in the object 'q' being created at an unaligned location, making your program crash with the \\ref TopicUnalignedArrayAssert \"assertion on unaligned arrays\". So far we found the three following solutions.\n\n\n\\section sec_sol1 Local solution\n\nA local solution is to mark such a function with this attribute:\n\\code\n__attribute__((force_align_arg_pointer)) void foo()\n{\n  Eigen::Quaternionf q;\n  //...\n}\n\\endcode\nRead <a href=\"http://gcc.gnu.org/onlinedocs/gcc-4.4.0/gcc/Function-Attributes.html#Function-Attributes\">this GCC documentation</a> to understand what this does. Of course this should only be done on GCC on Windows, so for portability you'll have to encapsulate this in a macro which you leave empty on other platforms. The advantage of this solution is that you can finely select which function might have a corrupted stack alignment. Of course on the downside this has to be done for every such function, so you may prefer one of the following two global solutions.\n\n\n\\section sec_sol2 Global solutions\n\nA global solution is to edit your project so that when compiling with GCC on Windows, you pass this option to GCC:\n\\code\n-mincoming-stack-boundary=2\n\\endcode\nExplanation: this tells GCC that the stack is only required to be aligned to 2^2=4 bytes, so that GCC now knows that it really must take extra care to honor the 16 byte alignment of \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen types\" when needed.\n\nAnother global solution is to pass this option to gcc:\n\\code\n-mstackrealign\n\\endcode\nwhich has the same effect than adding the \\c force_align_arg_pointer attribute to all functions.\n\nThese global solutions are easy to use, but note that they may slowdown your program because they lead to extra prologue/epilogue instructions for every function.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/eigen_navtree_hacks.js",
    "content": "\n// generate a table of contents in the side-nav based on the h1/h2 tags of the current page.\nfunction generate_autotoc() {\n  var headers = $(\"h1, h2\");\n  if(headers.length > 1) {\n    var toc = $(\"#side-nav\").append('<div id=\"nav-toc\" class=\"toc\"><h3>Table of contents</h3></div>');\n    toc = $(\"#nav-toc\");\n    var footer  = $(\"#nav-path\");\n    var footerHeight = footer.height();\n    toc = toc.append('<ul></ul>');\n    toc = toc.find('ul');\n    var indices = new Array();\n    indices[0] = 0;\n    indices[1] = 0;\n\n    var h1counts = $(\"h1\").length;\n    headers.each(function(i) {\n      var current = $(this);\n      var levelTag = current[0].tagName.charAt(1);\n      if(h1counts==0)\n        levelTag--;\n      var cur_id = current.attr(\"id\");\n\n      indices[levelTag-1]+=1;  \n      var prefix = indices[0];\n      if (levelTag >1) {\n        prefix+=\".\"+indices[1];\n      }\n        \n      // Uncomment to add number prefixes\n      // current.html(prefix + \"   \" + current.html());\n      for(var l = levelTag; l < 2; ++l){\n          indices[l] = 0;\n      }\n\n      if(cur_id == undefined) {\n        current.attr('id', 'title' + i);\n        current.addClass('anchor');\n        toc.append(\"<li class='level\" + levelTag + \"'><a id='link\" + i + \"' href='#title\" +\n                    i + \"' title='\" + current.prop(\"tagName\") + \"'>\" + current.text() + \"</a></li>\");\n      } else {\n        toc.append(\"<li class='level\" + levelTag + \"'><a id='\" + cur_id + \"' href='#title\" +\n                    i + \"' title='\" + current.prop(\"tagName\") + \"'>\" + current.text() + \"</a></li>\");\n      }\n    });\n    resizeHeight();\n  }\n}\n\n\nvar global_navtree_object;\n\n// Overloaded to remove links to sections/subsections\nfunction getNode(o, po)\n{\n  po.childrenVisited = true;\n  var l = po.childrenData.length-1;\n  for (var i in po.childrenData) {\n    var nodeData = po.childrenData[i];\n    if((!nodeData[1]) ||  (nodeData[1].indexOf('#')==-1)) // <- we added this line\n      po.children[i] = newNode(o, po, nodeData[0], nodeData[1], nodeData[2], i==l);\n  }\n}\n\n// Overloaded to adjust the size of the navtree wrt the toc\nfunction resizeHeight() \n{\n  var header  = $(\"#top\");\n  var sidenav = $(\"#side-nav\");\n  var content = $(\"#doc-content\");\n  var navtree = $(\"#nav-tree\");\n  var footer  = $(\"#nav-path\");\n  var toc     = $(\"#nav-toc\");\n\n  var headerHeight = header.outerHeight();\n  var footerHeight = footer.outerHeight();\n  var tocHeight    = toc.height();\n  var windowHeight = $(window).height() - headerHeight - footerHeight;\n  content.css({height:windowHeight + \"px\"});\n  navtree.css({height:(windowHeight-tocHeight) + \"px\"});\n  sidenav.css({height:windowHeight + \"px\"});\n}\n\n// Overloaded to save the root node into global_navtree_object\nfunction initNavTree(toroot,relpath)\n{\n  var o = new Object();\n  global_navtree_object = o; // <- we added this line\n  o.toroot = toroot;\n  o.node = new Object();\n  o.node.li = document.getElementById(\"nav-tree-contents\");\n  o.node.childrenData = NAVTREE;\n  o.node.children = new Array();\n  o.node.childrenUL = document.createElement(\"ul\");\n  o.node.getChildrenUL = function() { return o.node.childrenUL; };\n  o.node.li.appendChild(o.node.childrenUL);\n  o.node.depth = 0;\n  o.node.relpath = relpath;\n  o.node.expanded = false;\n  o.node.isLast = true;\n  o.node.plus_img = document.createElement(\"img\");\n  o.node.plus_img.src = relpath+\"ftv2pnode.png\";\n  o.node.plus_img.width = 16;\n  o.node.plus_img.height = 22;\n\n  if (localStorageSupported()) {\n    var navSync = $('#nav-sync');\n    if (cachedLink()) {\n      showSyncOff(navSync,relpath);\n      navSync.removeClass('sync');\n    } else {\n      showSyncOn(navSync,relpath);\n    }\n    navSync.click(function(){ toggleSyncButton(relpath); });\n  }\n\n  navTo(o,toroot,window.location.hash,relpath);\n\n  $(window).bind('hashchange', function(){\n     if (window.location.hash && window.location.hash.length>1){\n       var a;\n       if ($(location).attr('hash')){\n         var clslink=stripPath($(location).attr('pathname'))+':'+\n                               $(location).attr('hash').substring(1);\n         a=$('.item a[class$=\"'+clslink+'\"]');\n       }\n       if (a==null || !$(a).parent().parent().hasClass('selected')){\n         $('.item').removeClass('selected');\n         $('.item').removeAttr('id');\n       }\n       var link=stripPath2($(location).attr('pathname'));\n       navTo(o,link,$(location).attr('hash'),relpath);\n     } else if (!animationInProgress) {\n       $('#doc-content').scrollTop(0);\n       $('.item').removeClass('selected');\n       $('.item').removeAttr('id');\n       navTo(o,toroot,window.location.hash,relpath);\n     }\n  })\n\n  $(window).on(\"load\", showRoot);\n}\n\n// return false if the the node has no children at all, or has only section/subsection children\nfunction checkChildrenData(node) {\n  if (!(typeof(node.childrenData)==='string')) {\n    for (var i in node.childrenData) {\n      var url = node.childrenData[i][1];\n      if(url.indexOf(\"#\")==-1)\n        return true;\n    }\n    return false;\n  }\n  return (node.childrenData);\n}\n\n// Modified to:\n// 1 - remove the root node \n// 2 - remove the section/subsection children\nfunction createIndent(o,domNode,node,level)\n{\n  var level=-2; // <- we replaced level=-1 by level=-2\n  var n = node;\n  while (n.parentNode) { level++; n=n.parentNode; }\n  if (checkChildrenData(node)) { // <- we modified this line to use checkChildrenData(node) instead of node.childrenData\n    var imgNode = document.createElement(\"span\");\n    imgNode.className = 'arrow';\n    imgNode.style.paddingLeft=(16*level).toString()+'px';\n    imgNode.innerHTML=arrowRight;\n    node.plus_img = imgNode;\n    node.expandToggle = document.createElement(\"a\");\n    node.expandToggle.href = \"javascript:void(0)\";\n    node.expandToggle.onclick = function() {\n      if (node.expanded) {\n        $(node.getChildrenUL()).slideUp(\"fast\");\n        node.plus_img.innerHTML=arrowRight;\n        node.expanded = false;\n      } else {\n        expandNode(o, node, false, false);\n      }\n    }\n    node.expandToggle.appendChild(imgNode);\n    domNode.appendChild(node.expandToggle);\n  } else {\n    var span = document.createElement(\"span\");\n    span.className = 'arrow';\n    span.style.width   = 16*(level+1)+'px';\n    span.innerHTML = '&#160;';\n    domNode.appendChild(span);\n  }\n}\n\n// Overloaded to automatically expand the selected node\nfunction selectAndHighlight(hash,n)\n{\n  var a;\n  if (hash) {\n    var link=stripPath($(location).attr('pathname'))+':'+hash.substring(1);\n    a=$('.item a[class$=\"'+link+'\"]');\n  }\n  if (a && a.length) {\n    a.parent().parent().addClass('selected');\n    a.parent().parent().attr('id','selected');\n    highlightAnchor();\n  } else if (n) {\n    $(n.itemDiv).addClass('selected');\n    $(n.itemDiv).attr('id','selected');\n  }\n  if ($('#nav-tree-contents .item:first').hasClass('selected')) {\n    $('#nav-sync').css('top','30px');\n  } else {\n    $('#nav-sync').css('top','5px');\n  }\n  expandNode(global_navtree_object, n, true, true); // <- we added this line\n  showRoot();\n}\n\n\n$(document).ready(function() {\n  \n  generate_autotoc();\n  \n  (function (){ // wait until the first \"selected\" element has been created\n    try {\n      \n      // this line will triger an exception if there is no #selected element, i.e., before the tree structure is complete.\n      document.getElementById(\"selected\").className = \"item selected\";\n      \n      // ok, the default tree has been created, we can keep going...\n      \n      // expand the \"Chapters\" node\n      if(window.location.href.indexOf('unsupported')==-1)\n        expandNode(global_navtree_object, global_navtree_object.node.children[0].children[2], true, true);\n      else\n        expandNode(global_navtree_object, global_navtree_object.node.children[0].children[1], true, true);\n      \n      // Hide the root node \"Eigen\"\n      $(document.getElementsByClassName('index.html')[0]).parent().parent().css({display:\"none\"});\n      \n    } catch (err) {\n      setTimeout(arguments.callee, 10);\n    }\n  })();\n\n  $(window).on(\"load\", resizeHeight);\n});\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/eigendoxy.css",
    "content": "\n/******** Eigen specific CSS code ************/\n\n/**** Styles removing elements ****/\n\n/* remove the \"modules|classes\" link for module pages (they are already in the TOC) */\ndiv.summary {\n  display:none;\n}\n\n/* remove */\ndiv.contents hr {\n  display:none;\n}\n\n/**** ****/\n\np, dl.warning, dl.attention, dl.note\n{\n  max-width:60em;\n  text-align:justify;\n}\n\nli {\n  max-width:55em;\n  text-align:justify;  \n}\n\nimg {\n  border: 0;\n}\n\ndiv.fragment {\n  display:table; /* this allows the element to be larger than its parent */\n  padding: 0pt;\n}\npre.fragment {\n  border: 1px solid #cccccc;\n\n  margin: 2px 0px 2px 0px;\n  padding: 3px 5px 3px 5px;\n}\n\n\n\n/* Common style for all Eigen's tables */\n\ntable.example, table.manual, table.manual-vl, table.manual-hl {\n    max-width:100%;\n    border-collapse: collapse;\n    border-style: solid;\n    border-width: 1px;\n    border-color: #cccccc;\n    font-size: 1em;\n    \n    box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15);\n    -moz-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15);\n    -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15);\n}\n\ntable.example th, table.manual th, table.manual-vl th, table.manual-hl th {\n  padding: 0.5em 0.5em 0.5em 0.5em;\n  text-align: left;\n  padding-right: 1em;\n  color: #555555;\n  background-color: #F4F4E5;\n  \n  background-image: -webkit-gradient(linear,center top,center bottom,from(#FFFFFF), color-stop(0.3,#FFFFFF), color-stop(0.30,#FFFFFF), color-stop(0.98,#F4F4E5), to(#ECECDE));\n  background-image: -moz-linear-gradient(center top, #FFFFFF 0%, #FFFFFF 30%, #F4F4E5 98%, #ECECDE);\n  filter: progid:DXImageTransform.Microsoft.gradient(startColorstr='#FFFFFF', endColorstr='#F4F4E5');\n}\n\ntable.example td, table.manual td, table.manual-vl td, table.manual-hl td {\n  vertical-align:top;\n  border-width: 1px;\n  border-color: #cccccc;\n}\n\n/* header of headers */\ntable th.meta {\n  text-align:center;\n  font-size: 1.2em;\n  background-color:#FFFFFF;\n}\n\n/* intermediate header */\ntable th.inter {\n  text-align:left;\n  background-color:#FFFFFF;\n  background-image:none;\n  border-style:solid solid solid solid;\n  border-width: 1px;\n\tborder-color: #cccccc;\n}\n\n/** class for example / output tables **/\n\ntable.example {\n}\n\ntable.example th {\n}\n\ntable.example td {\n  padding: 0.5em 0.5em 0.5em 0.5em;\n  vertical-align:top;\n}\n\n/* standard class for the manual */\n\ntable.manual, table.manual-vl, table.manual-hl {\n    padding: 0.2em 0em 0.5em 0em;\n}\n\ntable.manual th, table.manual-vl th, table.manual-hl th {\n  margin: 0em 0em 0.3em 0em;\n}\n\ntable.manual td, table.manual-vl td, table.manual-hl td {\n  padding: 0.3em 0.5em 0.3em 0.5em;\n  vertical-align:top;\n  border-width: 1px;\n}\n\ntable.manual td.alt, table.manual tr.alt, table.manual-vl td.alt, table.manual-vl tr.alt {\n  background-color: #F4F4E5;\n}\n\ntable.manual-vl th, table.manual-vl td, table.manual-vl td.alt {\n  border-color: #cccccc;\n  border-width: 1px;\n  border-style: none solid none solid;\n}\n\ntable.manual-vl th.inter {\n  border-style: solid solid solid solid;\n}\n\ntable.manual-hl td {\n  border-color: #cccccc;\n  border-width: 1px;\n  border-style: solid none solid none;\n}\n\ntable td.code {\n  font-family: monospace;\n}\n\nh2 {\n  margin-top:2em;\n  border-style: none none solid none;\n  border-width: 1px;\n  border-color: #cccccc;\n}\n\n/**** Table of content in the side-nav ****/\n\n\ndiv.toc {\n  margin:0;\n  padding: 0.3em 0 0 0;\n  width:100%;\n  float:none;\n  position:absolute;\n  bottom:0;\n  border-radius:0px;\n  border-style: solid none none none;\n  max-height:50%;\n  overflow-y: scroll;\n}\n\ndiv.toc h3 {\n  margin-left: 0.5em;\n  margin-bottom: 0.2em;\n}\n\ndiv.toc ul {\n  margin: 0.2em 0 0.4em 0.5em;\n}\n\nspan.cpp11,span.cpp14,span.cpp17 {\n  color: #119911;\n  font-weight: bold;\n}\n\n.newin3x {\n  color: #a37c1a;\n  font-weight: bold;\n}\n\ndiv.warningbox {\n  max-width:60em;\n  border-style: solid solid solid solid;\n  border-color: red;\n  border-width: 3px;\n}\n\n/**** old Eigen's styles ****/\n\n\ntable.tutorial_code td {\n  border-color: transparent; /* required for Firefox */\n  padding: 3pt 5pt 3pt 5pt;\n  vertical-align: top;\n}\n\n\n/* Whenever doxygen meets a '\\n' or a '<BR/>', it will put \n * the text containing the character into a <p class=\"starttd\">.\n * This little hack together with table.tutorial_code td.note\n * aims at fixing this issue. */\ntable.tutorial_code td.note p.starttd {\n  margin: 0px;\n  border: none;\n  padding: 0px;\n}\n\ndiv.eimainmenu {\n  text-align:     center;\n}\n\n/* center version number on main page */\nh3.version { \n  text-align:     center;\n}\n\n\ntd.width20em p.endtd {\n  width:  20em;\n}\n\n/* needed for huge screens */\n.ui-resizable-e {\n  background-repeat: repeat-y;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/eigendoxy_footer.html.in",
    "content": "<!-- start footer part -->\n<!--BEGIN GENERATE_TREEVIEW-->\n<div id=\"nav-path\" class=\"navpath\"><!-- id is needed for treeview function! -->\n  <ul>\n    $navpath\n    <li class=\"footer\">$generatedby\n    <a href=\"http://www.doxygen.org/index.html\">\n    <img class=\"footer\" src=\"$relpath^doxygen.png\" alt=\"doxygen\"/></a> $doxygenversion </li>\n  </ul>\n</div>\n<!--END GENERATE_TREEVIEW-->\n<!--BEGIN !GENERATE_TREEVIEW-->\n<hr class=\"footer\"/><address class=\"footer\"><small>\n$generatedby &#160;<a href=\"http://www.doxygen.org/index.html\">\n<img class=\"footer\" src=\"$relpath^doxygen.png\" alt=\"doxygen\"/>\n</a> $doxygenversion\n</small></address>\n<!--END !GENERATE_TREEVIEW-->\n\n</body>\n</html>\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/eigendoxy_header.html.in",
    "content": "<!DOCTYPE html PUBLIC \"-//W3C//DTD XHTML 1.0 Transitional//EN\" \"http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd\">\n<html xmlns=\"http://www.w3.org/1999/xhtml\">\n<head>\n<meta http-equiv=\"Content-Type\" content=\"text/xhtml;charset=UTF-8\"/>\n<meta http-equiv=\"X-UA-Compatible\" content=\"IE=9\"/>\n<meta name=\"generator\" content=\"Doxygen $doxygenversion\"/>\n<meta name=\"viewport\" content=\"width=device-width, initial-scale=1\"/>\n<!--BEGIN PROJECT_NAME--><title>$projectname: $title</title><!--END PROJECT_NAME-->\n<!--BEGIN !PROJECT_NAME--><title>$title</title><!--END !PROJECT_NAME-->\n<link href=\"$relpath^tabs.css\" rel=\"stylesheet\" type=\"text/css\"/>\n<script type=\"text/javascript\" src=\"$relpath^jquery.js\"></script>\n<script type=\"text/javascript\" src=\"$relpath^dynsections.js\"></script>\n$treeview\n$search\n$mathjax\n<link href=\"$relpath^$stylesheet\" rel=\"stylesheet\" type=\"text/css\" />\n<link href=\"$relpath$eigendoxy.css\" rel=\"stylesheet\" type=\"text/css\">\n<!-- $extrastylesheet -->\n<script type=\"text/javascript\" src=\"$relpath$eigen_navtree_hacks.js\"></script>\n\n</head>\n<body>\n\n<div style=\"background:#FFDDDD;font-size:120%;text-align:center;margin:0;padding:5px\">Please, help us to better know about our user community by answering the following short survey:  <a href=\"https://forms.gle/wpyrxWi18ox9Z5ae9\">https://forms.gle/wpyrxWi18ox9Z5ae9</a></div>\n\n<div id=\"top\"><!-- do not remove this div, it is closed by doxygen! -->\n\n<!--BEGIN TITLEAREA-->\n<div id=\"titlearea\">\n<table cellspacing=\"0\" cellpadding=\"0\">\n <tbody>\n <tr style=\"height: 56px;\">\n  <!--BEGIN PROJECT_LOGO-->\n  <td id=\"projectlogo\"><img alt=\"Logo\" src=\"$relpath^$projectlogo\"/></td>\n  <!--END PROJECT_LOGO-->\n  <!--BEGIN PROJECT_NAME-->\n  <td id=\"projectalign\" style=\"padding-left: 0.5em;\">\n   <div id=\"projectname\"><a href=\"http://eigen.tuxfamily.org\">$projectname</a>\n   <!--BEGIN PROJECT_NUMBER-->&#160;<span id=\"projectnumber\">$projectnumber</span><!--END PROJECT_NUMBER-->\n   </div>\n   <!--BEGIN PROJECT_BRIEF--><div id=\"projectbrief\">$projectbrief</div><!--END PROJECT_BRIEF-->\n  </td>\n  <!--END PROJECT_NAME-->\n  <!--BEGIN !PROJECT_NAME-->\n   <!--BEGIN PROJECT_BRIEF-->\n    <td id=\"projectalign\" style=\"padding-left: 0.5em;\">\n    <div id=\"projectbrief\">$projectbrief</div>\n    </td>\n   <!--END PROJECT_BRIEF-->\n  <!--END !PROJECT_NAME-->\n  <!--BEGIN DISABLE_INDEX-->\n   <!--BEGIN SEARCHENGINE-->\n   <td>$searchbox</td>\n   <!--END SEARCHENGINE-->\n  <!--END DISABLE_INDEX-->\n </tr>\n </tbody>\n</table>\n</div>\n<!--END TITLEAREA-->\n<!-- end header part -->\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/eigendoxy_layout.xml.in",
    "content": "<?xml version=\"1.0\"?>\n<doxygenlayout version=\"1.0\">\n  <!-- Navigation index tabs for HTML output -->\n  <navindex>\n    <tab type=\"user\" url=\"index.html\" title=\"Overview\" />\n    <tab type=\"user\" url=\"@ref GettingStarted\" title=\"Getting started\" />\n    <tab type=\"modules\" visible=\"yes\" title=\"Chapters\" intro=\"\"/>\n    <tab type=\"mainpage\" visible=\"yes\" title=\"\"/>\n    <tab type=\"classlist\" visible=\"yes\" title=\"\" intro=\"\"/>\n<!--     <tab type=\"classmembers\" visible=\"yes\" title=\"\" intro=\"\"/> -->\n  </navindex>\n\n  <!-- Layout definition for a class page -->\n  <class>\n    <briefdescription visible=\"no\"/>\n    <includes visible=\"$SHOW_INCLUDE_FILES\"/>\n    <detaileddescription title=\"\"/>\n    <inheritancegraph visible=\"$CLASS_GRAPH\"/>\n    <collaborationgraph visible=\"$COLLABORATION_GRAPH\"/>\n    <allmemberslink visible=\"yes\"/>\n    <memberdecl>\n      <nestedclasses visible=\"yes\" title=\"\"/>\n      <publictypes title=\"\"/>\n      <publicslots title=\"\"/>\n      <signals title=\"\"/>\n      <publicmethods title=\"\"/>\n      <publicstaticmethods title=\"\"/>\n      <publicattributes title=\"\"/>\n      <publicstaticattributes title=\"\"/>\n      <protectedtypes title=\"\"/>\n      <protectedslots title=\"\"/>\n      <protectedmethods title=\"\"/>\n      <protectedstaticmethods title=\"\"/>\n      <protectedattributes title=\"\"/>\n      <protectedstaticattributes title=\"\"/>\n      <packagetypes title=\"\"/>\n      <packagemethods title=\"\"/>\n      <packagestaticmethods title=\"\"/>\n      <packageattributes title=\"\"/>\n      <packagestaticattributes title=\"\"/>\n      <properties title=\"\"/>\n      <events title=\"\"/>\n      <privatetypes title=\"\"/>\n      <privateslots title=\"\"/>\n      <privatemethods title=\"\"/>\n      <privatestaticmethods title=\"\"/>\n      <privateattributes title=\"\"/>\n      <privatestaticattributes title=\"\"/>\n      <friends title=\"\"/>\n      <related title=\"\" subtitle=\"\"/>\n      <membergroups visible=\"yes\"/>\n    </memberdecl>\n    \n    <memberdef>\n      <inlineclasses title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <constructors title=\"\"/>\n      <functions title=\"\"/>\n      <related title=\"\"/>\n      <variables title=\"\"/>\n      <properties title=\"\"/>\n      <events title=\"\"/>\n    </memberdef>\n    <usedfiles visible=\"$SHOW_USED_FILES\"/>\n    <authorsection visible=\"yes\"/>\n  </class>\n\n  <!-- Layout definition for a namespace page -->\n  <namespace>\n    <briefdescription visible=\"yes\"/>\n    <memberdecl>\n      <nestednamespaces visible=\"yes\" title=\"\"/>\n      <classes visible=\"yes\" title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n      <membergroups visible=\"yes\"/>\n    </memberdecl>\n    <detaileddescription title=\"\"/>\n    <memberdef>\n      <inlineclasses title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n    </memberdef>\n    <authorsection visible=\"yes\"/>\n  </namespace>\n\n  <!-- Layout definition for a file page -->\n  <file>\n    <briefdescription visible=\"yes\"/>\n    <includes visible=\"$SHOW_INCLUDE_FILES\"/>\n    <includegraph visible=\"$INCLUDE_GRAPH\"/>\n    <includedbygraph visible=\"$INCLUDED_BY_GRAPH\"/>\n    <sourcelink visible=\"yes\"/>\n    <memberdecl>\n      <classes visible=\"yes\" title=\"\"/>\n      <namespaces visible=\"yes\" title=\"\"/>\n      <defines title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n      <membergroups visible=\"yes\"/>\n    </memberdecl>\n    <detaileddescription title=\"\"/>\n    <memberdef>\n      <inlineclasses title=\"\"/>\n      <defines title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n    </memberdef>\n    <authorsection/>\n  </file>\n\n  <!-- Layout definition for a group page -->\n  <group>\n    <briefdescription visible=\"no\"/>\n    <detaileddescription title=\"\"/>\n    <groupgraph visible=\"$GROUP_GRAPHS\"/>\n    <memberdecl>\n      <nestedgroups visible=\"yes\" title=\"\"/>\n      <dirs visible=\"yes\" title=\"\"/>\n      <files visible=\"yes\" title=\"\"/>\n      <namespaces visible=\"yes\" title=\"\"/>\n      <classes visible=\"yes\" title=\"\"/>\n      <defines title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <enumvalues title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n      <signals title=\"\"/>\n      <publicslots title=\"\"/>\n      <protectedslots title=\"\"/>\n      <privateslots title=\"\"/>\n      <events title=\"\"/>\n      <properties title=\"\"/>\n      <friends title=\"\"/>\n      <membergroups visible=\"yes\"/>\n    </memberdecl>\n    \n    <memberdef>\n      <pagedocs/>\n      <inlineclasses title=\"\"/>\n      <defines title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <enumvalues title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n      <signals title=\"\"/>\n      <publicslots title=\"\"/>\n      <protectedslots title=\"\"/>\n      <privateslots title=\"\"/>\n      <events title=\"\"/>\n      <properties title=\"\"/>\n      <friends title=\"\"/>\n    </memberdef>\n    <authorsection visible=\"yes\"/>\n  </group>\n\n  <!-- Layout definition for a directory page -->\n  <directory>\n    <briefdescription visible=\"yes\"/>\n    <directorygraph visible=\"yes\"/>\n    <memberdecl>\n      <dirs visible=\"yes\"/>\n      <files visible=\"yes\"/>\n    </memberdecl>\n    <detaileddescription title=\"\"/>\n  </directory>\n</doxygenlayout>\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/eigendoxy_tabs.css",
    "content": ".tabs, .tabs2, .tabs3 {\n    background-image: url('tab_b.png');\n    width: 100%;\n    z-index: 101;\n    font-size: 13px;\n}\n\n.tabs2 {\n    font-size: 10px;\n}\n.tabs3 {\n    font-size: 9px;\n}\n\n.tablist {\n    margin: 0;\n    padding: 0;\n    display: table;\n}\n\n.tablist li {\n    float: left;\n    display: table-cell;\n    background-image: url('tab_b.png');\n    line-height: 36px;\n    list-style: none;\n}\n\n.tablist a {\n    display: block;\n    padding: 0 20px;\n    font-weight: bold;\n    background-image:url('tab_s.png');\n    background-repeat:no-repeat;\n    background-position:right;\n    color: #283A5D;\n    text-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9);\n    text-decoration: none;\n    outline: none;\n}\n\n.tabs3 .tablist a {\n    padding: 0 10px;\n}\n\n.tablist a:hover {\n    background-image: url('tab_h.png');\n    background-repeat:repeat-x;\n    color: #fff;\n    text-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0);\n    text-decoration: none;\n}\n\n.tablist li.current a {\n    background-image: url('tab_a.png');\n    background-repeat:repeat-x;\n    color: #fff;\n    text-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/.krazy",
    "content": "EXCLUDE copyright\nEXCLUDE license\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/CMakeLists.txt",
    "content": "file(GLOB examples_SRCS \"*.cpp\")\n\nforeach(example_src ${examples_SRCS})\n  get_filename_component(example ${example_src} NAME_WE)\n  add_executable(${example} ${example_src})\n  if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO)\n    target_link_libraries(${example} ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO})\n  endif()\n  add_custom_command(\n    TARGET ${example}\n    POST_BUILD\n    COMMAND ${example}\n    ARGS >${CMAKE_CURRENT_BINARY_DIR}/${example}.out\n  )\n  add_dependencies(all_examples ${example})\nendforeach()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/CustomizingEigen_Inheritance.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\n\nclass MyVectorType : public Eigen::VectorXd\n{\npublic:\n    MyVectorType(void):Eigen::VectorXd() {}\n\n    // This constructor allows you to construct MyVectorType from Eigen expressions\n    template<typename OtherDerived>\n    MyVectorType(const Eigen::MatrixBase<OtherDerived>& other)\n        : Eigen::VectorXd(other)\n    { }\n\n    // This method allows you to assign Eigen expressions to MyVectorType\n    template<typename OtherDerived>\n    MyVectorType& operator=(const Eigen::MatrixBase <OtherDerived>& other)\n    {\n        this->Eigen::VectorXd::operator=(other);\n        return *this;\n    }\n};\n\nint main()\n{\n  MyVectorType v = MyVectorType::Ones(4);\n  v(2) += 10;\n  v = 2 * v;\n  std::cout << v.transpose() << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Cwise_erf.cpp",
    "content": "#include <Eigen/Core>\n#include <unsupported/Eigen/SpecialFunctions>\n#include <iostream>\nusing namespace Eigen;\nint main()\n{\n  Array4d v(-0.5,2,0,-7);\n  std::cout << v.erf() << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Cwise_erfc.cpp",
    "content": "#include <Eigen/Core>\n#include <unsupported/Eigen/SpecialFunctions>\n#include <iostream>\nusing namespace Eigen;\nint main()\n{\n  Array4d v(-0.5,2,0,-7);\n  std::cout << v.erfc() << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Cwise_lgamma.cpp",
    "content": "#include <Eigen/Core>\n#include <unsupported/Eigen/SpecialFunctions>\n#include <iostream>\nusing namespace Eigen;\nint main()\n{\n  Array4d v(0.5,10,0,-1);\n  std::cout << v.lgamma() << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/DenseBase_middleCols_int.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main(void)\n{\n    int const N = 5;\n    MatrixXi A(N,N);\n    A.setRandom();\n    cout << \"A =\\n\" << A << '\\n' << endl;\n    cout << \"A(1..3,:) =\\n\" << A.middleCols(1,3) << endl;\n    return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/DenseBase_middleRows_int.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main(void)\n{\n    int const N = 5;\n    MatrixXi A(N,N);\n    A.setRandom();\n    cout << \"A =\\n\" << A << '\\n' << endl;\n    cout << \"A(2..3,:) =\\n\" << A.middleRows(2,2) << endl;\n    return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/DenseBase_template_int_middleCols.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main(void)\n{\n    int const N = 5;\n    MatrixXi A(N,N);\n    A.setRandom();\n    cout << \"A =\\n\" << A << '\\n' << endl;\n    cout << \"A(:,1..3) =\\n\" << A.middleCols<3>(1) << endl;\n    return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/DenseBase_template_int_middleRows.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main(void)\n{\n    int const N = 5;\n    MatrixXi A(N,N);\n    A.setRandom();\n    cout << \"A =\\n\" << A << '\\n' << endl;\n    cout << \"A(1..3,:) =\\n\" << A.middleRows<3>(1) << endl;\n    return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/QuickStart_example.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing Eigen::MatrixXd;\n\nint main()\n{\n  MatrixXd m(2,2);\n  m(0,0) = 3;\n  m(1,0) = 2.5;\n  m(0,1) = -1;\n  m(1,1) = m(1,0) + m(0,1);\n  std::cout << m << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/QuickStart_example2_dynamic.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  MatrixXd m = MatrixXd::Random(3,3);\n  m = (m + MatrixXd::Constant(3,3,1.2)) * 50;\n  cout << \"m =\" << endl << m << endl;\n  VectorXd v(3);\n  v << 1, 2, 3;\n  cout << \"m * v =\" << endl << m * v << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/QuickStart_example2_fixed.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  Matrix3d m = Matrix3d::Random();\n  m = (m + Matrix3d::Constant(1.2)) * 50;\n  cout << \"m =\" << endl << m << endl;\n  Vector3d v(1,2,3);\n  \n  cout << \"m * v =\" << endl << m * v << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/TemplateKeyword_flexible.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace Eigen;\n\ntemplate <typename Derived1, typename Derived2>\nvoid copyUpperTriangularPart(MatrixBase<Derived1>& dst, const MatrixBase<Derived2>& src)\n{\n  /* Note the 'template' keywords in the following line! */\n  dst.template triangularView<Upper>() = src.template triangularView<Upper>();\n}\n\nint main()\n{\n  MatrixXi m1 = MatrixXi::Ones(5,5);\n  MatrixXi m2 = MatrixXi::Random(4,4);\n  std::cout << \"m2 before copy:\" << std::endl;\n  std::cout << m2 << std::endl << std::endl;\n  copyUpperTriangularPart(m2, m1.topLeftCorner(4,4));\n  std::cout << \"m2 after copy:\" << std::endl;\n  std::cout << m2 << std::endl << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/TemplateKeyword_simple.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace Eigen;\n\nvoid copyUpperTriangularPart(MatrixXf& dst, const MatrixXf& src)\n{\n  dst.triangularView<Upper>() = src.triangularView<Upper>();\n}\n\nint main()\n{\n  MatrixXf m1 = MatrixXf::Ones(4,4);\n  MatrixXf m2 = MatrixXf::Random(4,4);\n  std::cout << \"m2 before copy:\" << std::endl;\n  std::cout << m2 << std::endl << std::endl;\n  copyUpperTriangularPart(m2, m1);\n  std::cout << \"m2 after copy:\" << std::endl;\n  std::cout << m2 << std::endl << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/TutorialInplaceLU.cpp",
    "content": "#include <iostream>\nstruct init {\n  init() { std::cout << \"[\" << \"init\" << \"]\" << std::endl; }\n};\ninit init_obj;\n// [init]\n#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n  MatrixXd A(2,2);\n  A << 2, -1, 1, 3;\n  cout << \"Here is the input matrix A before decomposition:\\n\" << A << endl;\ncout << \"[init]\" << endl;\n\ncout << \"[declaration]\" << endl;\n  PartialPivLU<Ref<MatrixXd> > lu(A);\n  cout << \"Here is the input matrix A after decomposition:\\n\" << A << endl;\ncout << \"[declaration]\" << endl;\n\ncout << \"[matrixLU]\" << endl;\n  cout << \"Here is the matrix storing the L and U factors:\\n\" << lu.matrixLU() << endl;\ncout << \"[matrixLU]\" << endl;\n\ncout << \"[solve]\" << endl;\n  MatrixXd A0(2,2); A0 << 2, -1, 1, 3;\n  VectorXd b(2);    b << 1, 2;\n  VectorXd x = lu.solve(b);\n  cout << \"Residual: \" << (A0 * x - b).norm() << endl;\ncout << \"[solve]\" << endl;\n\ncout << \"[modifyA]\" << endl;\n  A << 3, 4, -2, 1;\n  x = lu.solve(b);\n  cout << \"Residual: \" << (A0 * x - b).norm() << endl;\ncout << \"[modifyA]\" << endl;\n\ncout << \"[recompute]\" << endl;\n  A0 = A; // save A\n  lu.compute(A);\n  x = lu.solve(b);\n  cout << \"Residual: \" << (A0 * x - b).norm() << endl;\ncout << \"[recompute]\" << endl;\n\ncout << \"[recompute_bis0]\" << endl;\n  MatrixXd A1(2,2);\n  A1 << 5,-2,3,4;\n  lu.compute(A1);\n  cout << \"Here is the input matrix A1 after decomposition:\\n\" << A1 << endl;\ncout << \"[recompute_bis0]\" << endl;\n\ncout << \"[recompute_bis1]\" << endl;\n  x = lu.solve(b);\n  cout << \"Residual: \" << (A1 * x - b).norm() << endl;\ncout << \"[recompute_bis1]\" << endl;\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/TutorialLinAlgComputeTwice.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n   Matrix2f A, b;\n   LLT<Matrix2f> llt;\n   A << 2, -1, -1, 3;\n   b << 1, 2, 3, 1;\n   cout << \"Here is the matrix A:\\n\" << A << endl;\n   cout << \"Here is the right hand side b:\\n\" << b << endl;\n   cout << \"Computing LLT decomposition...\" << endl;\n   llt.compute(A);\n   cout << \"The solution is:\\n\" << llt.solve(b) << endl;\n   A(1,1)++;\n   cout << \"The matrix A is now:\\n\" << A << endl;\n   cout << \"Computing LLT decomposition...\" << endl;\n   llt.compute(A);\n   cout << \"The solution is now:\\n\" << llt.solve(b) << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/TutorialLinAlgExComputeSolveError.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n   MatrixXd A = MatrixXd::Random(100,100);\n   MatrixXd b = MatrixXd::Random(100,50);\n   MatrixXd x = A.fullPivLu().solve(b);\n   double relative_error = (A*x - b).norm() / b.norm(); // norm() is L2 norm\n   cout << \"The relative error is:\\n\" << relative_error << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/TutorialLinAlgExSolveColPivHouseholderQR.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n   Matrix3f A;\n   Vector3f b;\n   A << 1,2,3,  4,5,6,  7,8,10;\n   b << 3, 3, 4;\n   cout << \"Here is the matrix A:\\n\" << A << endl;\n   cout << \"Here is the vector b:\\n\" << b << endl;\n   Vector3f x = A.colPivHouseholderQr().solve(b);\n   cout << \"The solution is:\\n\" << x << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/TutorialLinAlgExSolveLDLT.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n   Matrix2f A, b;\n   A << 2, -1, -1, 3;\n   b << 1, 2, 3, 1;\n   cout << \"Here is the matrix A:\\n\" << A << endl;\n   cout << \"Here is the right hand side b:\\n\" << b << endl;\n   Matrix2f x = A.ldlt().solve(b);\n   cout << \"The solution is:\\n\" << x << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/TutorialLinAlgInverseDeterminant.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n   Matrix3f A;\n   A << 1, 2, 1,\n        2, 1, 0,\n        -1, 1, 2;\n   cout << \"Here is the matrix A:\\n\" << A << endl;\n   cout << \"The determinant of A is \" << A.determinant() << endl;\n   cout << \"The inverse of A is:\\n\" << A.inverse() << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/TutorialLinAlgRankRevealing.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n   Matrix3f A;\n   A << 1, 2, 5,\n        2, 1, 4,\n        3, 0, 3;\n   cout << \"Here is the matrix A:\\n\" << A << endl;\n   FullPivLU<Matrix3f> lu_decomp(A);\n   cout << \"The rank of A is \" << lu_decomp.rank() << endl;\n   cout << \"Here is a matrix whose columns form a basis of the null-space of A:\\n\"\n        << lu_decomp.kernel() << endl;\n   cout << \"Here is a matrix whose columns form a basis of the column-space of A:\\n\"\n        << lu_decomp.image(A) << endl; // yes, have to pass the original A\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/TutorialLinAlgSVDSolve.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n   MatrixXf A = MatrixXf::Random(3, 2);\n   cout << \"Here is the matrix A:\\n\" << A << endl;\n   VectorXf b = VectorXf::Random(3);\n   cout << \"Here is the right hand side b:\\n\" << b << endl;\n   cout << \"The least-squares solution is:\\n\"\n        << A.bdcSvd(ComputeThinU | ComputeThinV).solve(b) << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/TutorialLinAlgSelfAdjointEigenSolver.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n   Matrix2f A;\n   A << 1, 2, 2, 3;\n   cout << \"Here is the matrix A:\\n\" << A << endl;\n   SelfAdjointEigenSolver<Matrix2f> eigensolver(A);\n   if (eigensolver.info() != Success) abort();\n   cout << \"The eigenvalues of A are:\\n\" << eigensolver.eigenvalues() << endl;\n   cout << \"Here's a matrix whose columns are eigenvectors of A \\n\"\n        << \"corresponding to these eigenvalues:\\n\"\n        << eigensolver.eigenvectors() << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/TutorialLinAlgSetThreshold.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n   Matrix2d A;\n   A << 2, 1,\n        2, 0.9999999999;\n   FullPivLU<Matrix2d> lu(A);\n   cout << \"By default, the rank of A is found to be \" << lu.rank() << endl;\n   lu.setThreshold(1e-5);\n   cout << \"With threshold 1e-5, the rank of A is found to be \" << lu.rank() << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_ArrayClass_accessors.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  ArrayXXf  m(2,2);\n  \n  // assign some values coefficient by coefficient\n  m(0,0) = 1.0; m(0,1) = 2.0;\n  m(1,0) = 3.0; m(1,1) = m(0,1) + m(1,0);\n  \n  // print values to standard output\n  cout << m << endl << endl;\n \n  // using the comma-initializer is also allowed\n  m << 1.0,2.0,\n       3.0,4.0;\n     \n  // print values to standard output\n  cout << m << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_ArrayClass_addition.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  ArrayXXf a(3,3);\n  ArrayXXf b(3,3);\n  a << 1,2,3,\n       4,5,6,\n       7,8,9;\n  b << 1,2,3,\n       1,2,3,\n       1,2,3;\n       \n  // Adding two arrays\n  cout << \"a + b = \" << endl << a + b << endl << endl;\n\n  // Subtracting a scalar from an array\n  cout << \"a - 2 = \" << endl << a - 2 << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_ArrayClass_cwise_other.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  ArrayXf a = ArrayXf::Random(5);\n  a *= 2;\n  cout << \"a =\" << endl \n       << a << endl;\n  cout << \"a.abs() =\" << endl \n       << a.abs() << endl;\n  cout << \"a.abs().sqrt() =\" << endl \n       << a.abs().sqrt() << endl;\n  cout << \"a.min(a.abs().sqrt()) =\" << endl \n       << a.min(a.abs().sqrt()) << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_ArrayClass_interop.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  MatrixXf m(2,2);\n  MatrixXf n(2,2);\n  MatrixXf result(2,2);\n\n  m << 1,2,\n       3,4;\n  n << 5,6,\n       7,8;\n  \n  result = (m.array() + 4).matrix() * m;\n  cout << \"-- Combination 1: --\" << endl << result << endl << endl;\n  result = (m.array() * n.array()).matrix() * m;\n  cout << \"-- Combination 2: --\" << endl << result << endl << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_ArrayClass_interop_matrix.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  MatrixXf m(2,2);\n  MatrixXf n(2,2);\n  MatrixXf result(2,2);\n\n  m << 1,2,\n       3,4;\n  n << 5,6,\n       7,8;\n\n  result = m * n;\n  cout << \"-- Matrix m*n: --\" << endl << result << endl << endl;\n  result = m.array() * n.array();\n  cout << \"-- Array m*n: --\" << endl << result << endl << endl;\n  result = m.cwiseProduct(n);\n  cout << \"-- With cwiseProduct: --\" << endl << result << endl << endl;\n  result = m.array() + 4;\n  cout << \"-- Array m + 4: --\" << endl << result << endl << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_ArrayClass_mult.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  ArrayXXf a(2,2);\n  ArrayXXf b(2,2);\n  a << 1,2,\n       3,4;\n  b << 5,6,\n       7,8;\n  cout << \"a * b = \" << endl << a * b << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_BlockOperations_block_assignment.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n  Array22f m;\n  m << 1,2,\n       3,4;\n  Array44f a = Array44f::Constant(0.6);\n  cout << \"Here is the array a:\" << endl << a << endl << endl;\n  a.block<2,2>(1,1) = m;\n  cout << \"Here is now a with m copied into its central 2x2 block:\" << endl << a << endl << endl;\n  a.block(0,0,2,3) = a.block(2,1,2,3);\n  cout << \"Here is now a with bottom-right 2x3 block copied into top-left 2x3 block:\" << endl << a << endl << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_BlockOperations_colrow.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace std;\n\nint main()\n{\n  Eigen::MatrixXf m(3,3);\n  m << 1,2,3,\n       4,5,6,\n       7,8,9;\n  cout << \"Here is the matrix m:\" << endl << m << endl;\n  cout << \"2nd Row: \" << m.row(1) << endl;\n  m.col(2) += 3 * m.col(0);\n  cout << \"After adding 3 times the first column into the third column, the matrix m is:\\n\";\n  cout << m << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_BlockOperations_corner.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace std;\n\nint main()\n{\n  Eigen::Matrix4f m;\n  m << 1, 2, 3, 4,\n       5, 6, 7, 8,\n       9, 10,11,12,\n       13,14,15,16;\n  cout << \"m.leftCols(2) =\" << endl << m.leftCols(2) << endl << endl;\n  cout << \"m.bottomRows<2>() =\" << endl << m.bottomRows<2>() << endl << endl;\n  m.topLeftCorner(1,3) = m.bottomRightCorner(3,1).transpose();\n  cout << \"After assignment, m = \" << endl << m << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_BlockOperations_print_block.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace std;\n\nint main()\n{\n  Eigen::MatrixXf m(4,4);\n  m <<  1, 2, 3, 4,\n        5, 6, 7, 8,\n        9,10,11,12,\n       13,14,15,16;\n  cout << \"Block in the middle\" << endl;\n  cout << m.block<2,2>(1,1) << endl << endl;\n  for (int i = 1; i <= 3; ++i)\n  {\n    cout << \"Block of size \" << i << \"x\" << i << endl;\n    cout << m.block(0,0,i,i) << endl << endl;\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_BlockOperations_vector.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace std;\n\nint main()\n{\n  Eigen::ArrayXf v(6);\n  v << 1, 2, 3, 4, 5, 6;\n  cout << \"v.head(3) =\" << endl << v.head(3) << endl << endl;\n  cout << \"v.tail<3>() = \" << endl << v.tail<3>() << endl << endl;\n  v.segment(1,4) *= 2;\n  cout << \"after 'v.segment(1,4) *= 2', v =\" << endl << v << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_PartialLU_solve.cpp",
    "content": "#include <Eigen/Core>\n#include <Eigen/LU>\n#include <iostream>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n   Matrix3f A;\n   Vector3f b;\n   A << 1,2,3,  4,5,6,  7,8,10;\n   b << 3, 3, 4;\n   cout << \"Here is the matrix A:\" << endl << A << endl;\n   cout << \"Here is the vector b:\" << endl << b << endl;\n   Vector3f x = A.lu().solve(b);\n   cout << \"The solution is:\" << endl << x << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_1nn.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n  Eigen::MatrixXf m(2,4);\n  Eigen::VectorXf v(2);\n  \n  m << 1, 23, 6, 9,\n       3, 11, 7, 2;\n       \n  v << 2,\n       3;\n\n  MatrixXf::Index index;\n  // find nearest neighbour\n  (m.colwise() - v).colwise().squaredNorm().minCoeff(&index);\n\n  cout << \"Nearest neighbour is column \" << index << \":\" << endl;\n  cout << m.col(index) << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nint main()\n{\n  Eigen::MatrixXf mat(2,4);\n  Eigen::VectorXf v(2);\n  \n  mat << 1, 2, 6, 9,\n         3, 1, 7, 2;\n         \n  v << 0,\n       1;\n       \n  //add v to each column of m\n  mat.colwise() += v;\n  \n  std::cout << \"Broadcasting result: \" << std::endl;\n  std::cout << mat << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple_rowwise.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nint main()\n{\n  Eigen::MatrixXf mat(2,4);\n  Eigen::VectorXf v(4);\n  \n  mat << 1, 2, 6, 9,\n         3, 1, 7, 2;\n         \n  v << 0,1,2,3;\n       \n  //add v to each row of m\n  mat.rowwise() += v.transpose();\n  \n  std::cout << \"Broadcasting result: \" << std::endl;\n  std::cout << mat << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_colwise.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nint main()\n{\n  Eigen::MatrixXf mat(2,4);\n  mat << 1, 2, 6, 9,\n         3, 1, 7, 2;\n  \n  std::cout << \"Column's maximum: \" << std::endl\n   << mat.colwise().maxCoeff() << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_maxnorm.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\nint main()\n{\n  MatrixXf mat(2,4);\n  mat << 1, 2, 6, 9,\n         3, 1, 7, 2;\n  \n  MatrixXf::Index   maxIndex;\n  float maxNorm = mat.colwise().sum().maxCoeff(&maxIndex);\n  \n  std::cout << \"Maximum sum at position \" << maxIndex << std::endl;\n\n  std::cout << \"The corresponding vector is: \" << std::endl;\n  std::cout << mat.col( maxIndex ) << std::endl;\n  std::cout << \"And its sum is is: \" << maxNorm << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_bool.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n  ArrayXXf a(2,2);\n  \n  a << 1,2,\n       3,4;\n\n  cout << \"(a > 0).all()   = \" << (a > 0).all() << endl;\n  cout << \"(a > 0).any()   = \" << (a > 0).any() << endl;\n  cout << \"(a > 0).count() = \" << (a > 0).count() << endl;\n  cout << endl;\n  cout << \"(a > 2).all()   = \" << (a > 2).all() << endl;\n  cout << \"(a > 2).any()   = \" << (a > 2).any() << endl;\n  cout << \"(a > 2).count() = \" << (a > 2).count() << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_norm.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n  VectorXf v(2);\n  MatrixXf m(2,2), n(2,2);\n  \n  v << -1,\n       2;\n  \n  m << 1,-2,\n       -3,4;\n\n  cout << \"v.squaredNorm() = \" << v.squaredNorm() << endl;\n  cout << \"v.norm() = \" << v.norm() << endl;\n  cout << \"v.lpNorm<1>() = \" << v.lpNorm<1>() << endl;\n  cout << \"v.lpNorm<Infinity>() = \" << v.lpNorm<Infinity>() << endl;\n\n  cout << endl;\n  cout << \"m.squaredNorm() = \" << m.squaredNorm() << endl;\n  cout << \"m.norm() = \" << m.norm() << endl;\n  cout << \"m.lpNorm<1>() = \" << m.lpNorm<1>() << endl;\n  cout << \"m.lpNorm<Infinity>() = \" << m.lpNorm<Infinity>() << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_operatornorm.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  MatrixXf m(2,2);\n  m << 1,-2,\n       -3,4;\n\n  cout << \"1-norm(m)     = \" << m.cwiseAbs().colwise().sum().maxCoeff()\n       << \" == \"             << m.colwise().lpNorm<1>().maxCoeff() << endl;\n\n  cout << \"infty-norm(m) = \" << m.cwiseAbs().rowwise().sum().maxCoeff()\n       << \" == \"             << m.rowwise().lpNorm<1>().maxCoeff() << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_rowwise.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nint main()\n{\n  Eigen::MatrixXf mat(2,4);\n  mat << 1, 2, 6, 9,\n         3, 1, 7, 2;\n  \n  std::cout << \"Row's maximum: \" << std::endl\n   << mat.rowwise().maxCoeff() << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_visitors.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n  Eigen::MatrixXf m(2,2);\n  \n  m << 1, 2,\n       3, 4;\n\n  //get location of maximum\n  MatrixXf::Index maxRow, maxCol;\n  float max = m.maxCoeff(&maxRow, &maxCol);\n\n  //get location of minimum\n  MatrixXf::Index minRow, minCol;\n  float min = m.minCoeff(&minRow, &minCol);\n\n  cout << \"Max: \" << max <<  \", at: \" <<\n     maxRow << \",\" << maxCol << endl;\n  cout << \"Min: \" << min << \", at: \" <<\n     minRow << \",\" << minCol << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_simple_example_dynamic_size.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\n\nusing namespace Eigen;\n\nint main()\n{\n  for (int size=1; size<=4; ++size)\n  {\n    MatrixXi m(size,size+1);         // a (size)x(size+1)-matrix of int's\n    for (int j=0; j<m.cols(); ++j)   // loop over columns\n      for (int i=0; i<m.rows(); ++i) // loop over rows\n        m(i,j) = i+j*size;           // to access matrix coefficients,\n                                     // use operator()(int,int)\n    std::cout << m << \"\\n\\n\";\n  }\n\n  VectorXf v(4); // a vector of 4 float's\n  // to access vector coefficients, use either operator () or operator []\n  v[0] = 1; v[1] = 2; v(2) = 3; v(3) = 4;\n  std::cout << \"\\nv:\\n\" << v << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/Tutorial_simple_example_fixed_size.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\n\nusing namespace Eigen;\n\nint main()\n{\n  Matrix3f m3;\n  m3 << 1, 2, 3, 4, 5, 6, 7, 8, 9;\n  Matrix4f m4 = Matrix4f::Identity();\n  Vector4i v4(1, 2, 3, 4);\n\n  std::cout << \"m3\\n\" << m3 << \"\\nm4:\\n\"\n    << m4 << \"\\nv4:\\n\" << v4 << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/class_Block.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\nusing namespace Eigen;\nusing namespace std;\n\ntemplate<typename Derived>\nEigen::Block<Derived>\ntopLeftCorner(MatrixBase<Derived>& m, int rows, int cols)\n{\n  return Eigen::Block<Derived>(m.derived(), 0, 0, rows, cols);\n}\n\ntemplate<typename Derived>\nconst Eigen::Block<const Derived>\ntopLeftCorner(const MatrixBase<Derived>& m, int rows, int cols)\n{\n  return Eigen::Block<const Derived>(m.derived(), 0, 0, rows, cols);\n}\n\nint main(int, char**)\n{\n  Matrix4d m = Matrix4d::Identity();\n  cout << topLeftCorner(4*m, 2, 3) << endl; // calls the const version\n  topLeftCorner(m, 2, 3) *= 5;              // calls the non-const version\n  cout << \"Now the matrix m is:\" << endl << m << endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/class_CwiseBinaryOp.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\nusing namespace Eigen;\nusing namespace std;\n\n// define a custom template binary functor\ntemplate<typename Scalar> struct MakeComplexOp {\n  EIGEN_EMPTY_STRUCT_CTOR(MakeComplexOp)\n  typedef complex<Scalar> result_type;\n  complex<Scalar> operator()(const Scalar& a, const Scalar& b) const { return complex<Scalar>(a,b); }\n};\n\nint main(int, char**)\n{\n  Matrix4d m1 = Matrix4d::Random(), m2 = Matrix4d::Random();\n  cout << m1.binaryExpr(m2, MakeComplexOp<double>()) << endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/class_CwiseUnaryOp.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\nusing namespace Eigen;\nusing namespace std;\n\n// define a custom template unary functor\ntemplate<typename Scalar>\nstruct CwiseClampOp {\n  CwiseClampOp(const Scalar& inf, const Scalar& sup) : m_inf(inf), m_sup(sup) {}\n  const Scalar operator()(const Scalar& x) const { return x<m_inf ? m_inf : (x>m_sup ? m_sup : x); }\n  Scalar m_inf, m_sup;\n};\n\nint main(int, char**)\n{\n  Matrix4d m1 = Matrix4d::Random();\n  cout << m1 << endl << \"becomes: \" << endl << m1.unaryExpr(CwiseClampOp<double>(-0.5,0.5)) << endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/class_CwiseUnaryOp_ptrfun.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\nusing namespace Eigen;\nusing namespace std;\n\n// define function to be applied coefficient-wise\ndouble ramp(double x)\n{\n  if (x > 0)\n    return x;\n  else \n    return 0;\n}\n\nint main(int, char**)\n{\n  Matrix4d m1 = Matrix4d::Random();\n  cout << m1 << endl << \"becomes: \" << endl << m1.unaryExpr(ptr_fun(ramp)) << endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/class_FixedBlock.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\nusing namespace Eigen;\nusing namespace std;\n\ntemplate<typename Derived>\nEigen::Block<Derived, 2, 2>\ntopLeft2x2Corner(MatrixBase<Derived>& m)\n{\n  return Eigen::Block<Derived, 2, 2>(m.derived(), 0, 0);\n}\n\ntemplate<typename Derived>\nconst Eigen::Block<const Derived, 2, 2>\ntopLeft2x2Corner(const MatrixBase<Derived>& m)\n{\n  return Eigen::Block<const Derived, 2, 2>(m.derived(), 0, 0);\n}\n\nint main(int, char**)\n{\n  Matrix3d m = Matrix3d::Identity();\n  cout << topLeft2x2Corner(4*m) << endl; // calls the const version\n  topLeft2x2Corner(m) *= 2;              // calls the non-const version\n  cout << \"Now the matrix m is:\" << endl << m << endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/class_FixedReshaped.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\nusing namespace Eigen;\nusing namespace std;\n\ntemplate<typename Derived>\nEigen::Reshaped<Derived, 4, 2>\nreshape_helper(MatrixBase<Derived>& m)\n{\n  return Eigen::Reshaped<Derived, 4, 2>(m.derived());\n}\n\nint main(int, char**)\n{\n  MatrixXd m(2, 4);\n  m << 1, 2, 3, 4,\n       5, 6, 7, 8;\n  MatrixXd n = reshape_helper(m);\n  cout << \"matrix m is:\" << endl << m << endl;\n  cout << \"matrix n is:\" << endl << n << endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/class_FixedVectorBlock.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\nusing namespace Eigen;\nusing namespace std;\n\ntemplate<typename Derived>\nEigen::VectorBlock<Derived, 2>\nfirstTwo(MatrixBase<Derived>& v)\n{\n  return Eigen::VectorBlock<Derived, 2>(v.derived(), 0);\n}\n\ntemplate<typename Derived>\nconst Eigen::VectorBlock<const Derived, 2>\nfirstTwo(const MatrixBase<Derived>& v)\n{\n  return Eigen::VectorBlock<const Derived, 2>(v.derived(), 0);\n}\n\nint main(int, char**)\n{\n  Matrix<int,1,6> v; v << 1,2,3,4,5,6;\n  cout << firstTwo(4*v) << endl; // calls the const version\n  firstTwo(v) *= 2;              // calls the non-const version\n  cout << \"Now the vector v is:\" << endl << v << endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/class_Reshaped.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\nusing namespace std;\nusing namespace Eigen;\n\ntemplate<typename Derived>\nconst Reshaped<const Derived>\nreshape_helper(const MatrixBase<Derived>& m, int rows, int cols)\n{\n  return Reshaped<const Derived>(m.derived(), rows, cols);\n}\n\nint main(int, char**)\n{\n  MatrixXd m(3, 4);\n  m << 1, 4, 7, 10,\n       2, 5, 8, 11,\n       3, 6, 9, 12;\n  cout << m << endl;\n  Ref<const MatrixXd> n = reshape_helper(m, 2, 6);\n  cout << \"Matrix m is:\" << endl << m << endl;\n  cout << \"Matrix n is:\" << endl << n << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/class_VectorBlock.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\nusing namespace Eigen;\nusing namespace std;\n\ntemplate<typename Derived>\nEigen::VectorBlock<Derived>\nsegmentFromRange(MatrixBase<Derived>& v, int start, int end)\n{\n  return Eigen::VectorBlock<Derived>(v.derived(), start, end-start);\n}\n\ntemplate<typename Derived>\nconst Eigen::VectorBlock<const Derived>\nsegmentFromRange(const MatrixBase<Derived>& v, int start, int end)\n{\n  return Eigen::VectorBlock<const Derived>(v.derived(), start, end-start);\n}\n\nint main(int, char**)\n{\n  Matrix<int,1,6> v; v << 1,2,3,4,5,6;\n  cout << segmentFromRange(2*v, 2, 4) << endl; // calls the const version\n  segmentFromRange(v, 1, 3) *= 5;              // calls the non-const version\n  cout << \"Now the vector v is:\" << endl << v << endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/function_taking_eigenbase.cpp",
    "content": "#include <iostream>\n#include <Eigen/Core>\nusing namespace Eigen;\n\ntemplate <typename Derived>\nvoid print_size(const EigenBase<Derived>& b)\n{\n  std::cout << \"size (rows, cols): \" << b.size() << \" (\" << b.rows()\n            << \", \" << b.cols() << \")\" << std::endl;\n}\n\nint main()\n{\n    Vector3f v;\n    print_size(v);\n    // v.asDiagonal() returns a 3x3 diagonal matrix pseudo-expression\n    print_size(v.asDiagonal());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/function_taking_ref.cpp",
    "content": "#include <iostream>\n#include <Eigen/SVD>\nusing namespace Eigen;\nusing namespace std;\n\nfloat inv_cond(const Ref<const MatrixXf>& a)\n{\n  const VectorXf sing_vals = a.jacobiSvd().singularValues();\n  return sing_vals(sing_vals.size()-1) / sing_vals(0);\n}\n\nint main()\n{\n  Matrix4f m = Matrix4f::Random();\n  cout << \"matrix m:\" << endl << m << endl << endl;\n  cout << \"inv_cond(m):          \" << inv_cond(m)                      << endl;\n  cout << \"inv_cond(m(1:3,1:3)): \" << inv_cond(m.topLeftCorner(3,3))   << endl;\n  cout << \"inv_cond(m+I):        \" << inv_cond(m+Matrix4f::Identity()) << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/make_circulant.cpp",
    "content": "/*\nThis program is presented in several fragments in the doc page.\nEvery fragment is in its own file; this file simply combines them.\n*/\n\n#include \"make_circulant.cpp.preamble\"\n#include \"make_circulant.cpp.traits\"\n#include \"make_circulant.cpp.expression\"\n#include \"make_circulant.cpp.evaluator\"\n#include \"make_circulant.cpp.entry\"\n#include \"make_circulant.cpp.main\"\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/make_circulant.cpp.entry",
    "content": "template <class ArgType>\nCirculant<ArgType> makeCirculant(const Eigen::MatrixBase<ArgType>& arg)\n{\n  return Circulant<ArgType>(arg.derived());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/make_circulant.cpp.evaluator",
    "content": "namespace Eigen {\n  namespace internal {\n    template<typename ArgType>\n    struct evaluator<Circulant<ArgType> >\n      : evaluator_base<Circulant<ArgType> >\n    {\n      typedef Circulant<ArgType> XprType;\n      typedef typename nested_eval<ArgType, XprType::ColsAtCompileTime>::type ArgTypeNested;\n      typedef typename remove_all<ArgTypeNested>::type ArgTypeNestedCleaned;\n      typedef typename XprType::CoeffReturnType CoeffReturnType;\n\n      enum { \n        CoeffReadCost = evaluator<ArgTypeNestedCleaned>::CoeffReadCost,\n        Flags = Eigen::ColMajor \n      };\n      \n      evaluator(const XprType& xpr)\n        : m_argImpl(xpr.m_arg), m_rows(xpr.rows())\n      { }\n\n      CoeffReturnType coeff(Index row, Index col) const\n      {\n        Index index = row - col;\n        if (index < 0) index += m_rows;\n        return m_argImpl.coeff(index);\n      }\n\n      evaluator<ArgTypeNestedCleaned> m_argImpl;\n      const Index m_rows;\n    };\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/make_circulant.cpp.expression",
    "content": "template <class ArgType>\nclass Circulant : public Eigen::MatrixBase<Circulant<ArgType> >\n{\npublic:\n  Circulant(const ArgType& arg)\n    : m_arg(arg)\n  { \n    EIGEN_STATIC_ASSERT(ArgType::ColsAtCompileTime == 1,\n                        YOU_TRIED_CALLING_A_VECTOR_METHOD_ON_A_MATRIX);\n  }\n\n  typedef typename Eigen::internal::ref_selector<Circulant>::type Nested; \n\n  typedef Eigen::Index Index;\n  Index rows() const { return m_arg.rows(); }\n  Index cols() const { return m_arg.rows(); }\n\n  typedef typename Eigen::internal::ref_selector<ArgType>::type ArgTypeNested;\n  ArgTypeNested m_arg;\n};\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/make_circulant.cpp.main",
    "content": "int main()\n{\n  Eigen::VectorXd vec(4);\n  vec << 1, 2, 4, 8;\n  Eigen::MatrixXd mat;\n  mat = makeCirculant(vec);\n  std::cout << mat << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/make_circulant.cpp.preamble",
    "content": "#include <Eigen/Core>\n#include <iostream>\n\ntemplate <class ArgType> class Circulant;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/make_circulant.cpp.traits",
    "content": "namespace Eigen {\n  namespace internal {\n    template <class ArgType>\n    struct traits<Circulant<ArgType> >\n    {\n      typedef Eigen::Dense StorageKind;\n      typedef Eigen::MatrixXpr XprKind;\n      typedef typename ArgType::StorageIndex StorageIndex;\n      typedef typename ArgType::Scalar Scalar;\n      enum { \n        Flags = Eigen::ColMajor,\n        RowsAtCompileTime = ArgType::RowsAtCompileTime,\n        ColsAtCompileTime = ArgType::RowsAtCompileTime,\n        MaxRowsAtCompileTime = ArgType::MaxRowsAtCompileTime,\n        MaxColsAtCompileTime = ArgType::MaxRowsAtCompileTime\n      };\n    };\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/make_circulant2.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\n\nusing namespace Eigen;\n\n// [circulant_func]\ntemplate<class ArgType>\nclass circulant_functor {\n  const ArgType &m_vec;\npublic:\n  circulant_functor(const ArgType& arg) : m_vec(arg) {}\n\n  const typename ArgType::Scalar& operator() (Index row, Index col) const {\n    Index index = row - col;\n    if (index < 0) index += m_vec.size();\n    return m_vec(index);\n  }\n};\n// [circulant_func]\n\n// [square]\ntemplate<class ArgType>\nstruct circulant_helper {\n  typedef Matrix<typename ArgType::Scalar,\n                 ArgType::SizeAtCompileTime,\n                 ArgType::SizeAtCompileTime,\n                 ColMajor,\n                 ArgType::MaxSizeAtCompileTime,\n                 ArgType::MaxSizeAtCompileTime> MatrixType;\n};\n// [square]\n\n// [makeCirculant]\ntemplate <class ArgType>\nCwiseNullaryOp<circulant_functor<ArgType>, typename circulant_helper<ArgType>::MatrixType>\nmakeCirculant(const Eigen::MatrixBase<ArgType>& arg)\n{\n  typedef typename circulant_helper<ArgType>::MatrixType MatrixType;\n  return MatrixType::NullaryExpr(arg.size(), arg.size(), circulant_functor<ArgType>(arg.derived()));\n}\n// [makeCirculant]\n\n// [main]\nint main()\n{\n  Eigen::VectorXd vec(4);\n  vec << 1, 2, 4, 8;\n  Eigen::MatrixXd mat;\n  mat = makeCirculant(vec);\n  std::cout << mat << std::endl;\n}\n// [main]\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/matrixfree_cg.cpp",
    "content": "#include <iostream>\n#include <Eigen/Core>\n#include <Eigen/Dense>\n#include <Eigen/IterativeLinearSolvers>\n#include <unsupported/Eigen/IterativeSolvers>\n\nclass MatrixReplacement;\nusing Eigen::SparseMatrix;\n\nnamespace Eigen {\nnamespace internal {\n  // MatrixReplacement looks-like a SparseMatrix, so let's inherits its traits:\n  template<>\n  struct traits<MatrixReplacement> :  public Eigen::internal::traits<Eigen::SparseMatrix<double> >\n  {};\n}\n}\n\n// Example of a matrix-free wrapper from a user type to Eigen's compatible type\n// For the sake of simplicity, this example simply wrap a Eigen::SparseMatrix.\nclass MatrixReplacement : public Eigen::EigenBase<MatrixReplacement> {\npublic:\n  // Required typedefs, constants, and method:\n  typedef double Scalar;\n  typedef double RealScalar;\n  typedef int StorageIndex;\n  enum {\n    ColsAtCompileTime = Eigen::Dynamic,\n    MaxColsAtCompileTime = Eigen::Dynamic,\n    IsRowMajor = false\n  };\n\n  Index rows() const { return mp_mat->rows(); }\n  Index cols() const { return mp_mat->cols(); }\n\n  template<typename Rhs>\n  Eigen::Product<MatrixReplacement,Rhs,Eigen::AliasFreeProduct> operator*(const Eigen::MatrixBase<Rhs>& x) const {\n    return Eigen::Product<MatrixReplacement,Rhs,Eigen::AliasFreeProduct>(*this, x.derived());\n  }\n\n  // Custom API:\n  MatrixReplacement() : mp_mat(0) {}\n\n  void attachMyMatrix(const SparseMatrix<double> &mat) {\n    mp_mat = &mat;\n  }\n  const SparseMatrix<double> my_matrix() const { return *mp_mat; }\n\nprivate:\n  const SparseMatrix<double> *mp_mat;\n};\n\n\n// Implementation of MatrixReplacement * Eigen::DenseVector though a specialization of internal::generic_product_impl:\nnamespace Eigen {\nnamespace internal {\n\n  template<typename Rhs>\n  struct generic_product_impl<MatrixReplacement, Rhs, SparseShape, DenseShape, GemvProduct> // GEMV stands for matrix-vector\n  : generic_product_impl_base<MatrixReplacement,Rhs,generic_product_impl<MatrixReplacement,Rhs> >\n  {\n    typedef typename Product<MatrixReplacement,Rhs>::Scalar Scalar;\n\n    template<typename Dest>\n    static void scaleAndAddTo(Dest& dst, const MatrixReplacement& lhs, const Rhs& rhs, const Scalar& alpha)\n    {\n      // This method should implement \"dst += alpha * lhs * rhs\" inplace,\n      // however, for iterative solvers, alpha is always equal to 1, so let's not bother about it.\n      assert(alpha==Scalar(1) && \"scaling is not implemented\");\n      EIGEN_ONLY_USED_FOR_DEBUG(alpha);\n\n      // Here we could simply call dst.noalias() += lhs.my_matrix() * rhs,\n      // but let's do something fancier (and less efficient):\n      for(Index i=0; i<lhs.cols(); ++i)\n        dst += rhs(i) * lhs.my_matrix().col(i);\n    }\n  };\n\n}\n}\n\nint main()\n{\n  int n = 10;\n  Eigen::SparseMatrix<double> S = Eigen::MatrixXd::Random(n,n).sparseView(0.5,1);\n  S = S.transpose()*S;\n\n  MatrixReplacement A;\n  A.attachMyMatrix(S);\n\n  Eigen::VectorXd b(n), x;\n  b.setRandom();\n\n  // Solve Ax = b using various iterative solver with matrix-free version:\n  {\n    Eigen::ConjugateGradient<MatrixReplacement, Eigen::Lower|Eigen::Upper, Eigen::IdentityPreconditioner> cg;\n    cg.compute(A);\n    x = cg.solve(b);\n    std::cout << \"CG:       #iterations: \" << cg.iterations() << \", estimated error: \" << cg.error() << std::endl;\n  }\n\n  {\n    Eigen::BiCGSTAB<MatrixReplacement, Eigen::IdentityPreconditioner> bicg;\n    bicg.compute(A);\n    x = bicg.solve(b);\n    std::cout << \"BiCGSTAB: #iterations: \" << bicg.iterations() << \", estimated error: \" << bicg.error() << std::endl;\n  }\n\n  {\n    Eigen::GMRES<MatrixReplacement, Eigen::IdentityPreconditioner> gmres;\n    gmres.compute(A);\n    x = gmres.solve(b);\n    std::cout << \"GMRES:    #iterations: \" << gmres.iterations() << \", estimated error: \" << gmres.error() << std::endl;\n  }\n\n  {\n    Eigen::DGMRES<MatrixReplacement, Eigen::IdentityPreconditioner> gmres;\n    gmres.compute(A);\n    x = gmres.solve(b);\n    std::cout << \"DGMRES:   #iterations: \" << gmres.iterations() << \", estimated error: \" << gmres.error() << std::endl;\n  }\n\n  {\n    Eigen::MINRES<MatrixReplacement, Eigen::Lower|Eigen::Upper, Eigen::IdentityPreconditioner> minres;\n    minres.compute(A);\n    x = minres.solve(b);\n    std::cout << \"MINRES:   #iterations: \" << minres.iterations() << \", estimated error: \" << minres.error() << std::endl;\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/nullary_indexing.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\n\nusing namespace Eigen;\n\n// [functor]\ntemplate<class ArgType, class RowIndexType, class ColIndexType>\nclass indexing_functor {\n  const ArgType &m_arg;\n  const RowIndexType &m_rowIndices;\n  const ColIndexType &m_colIndices;\npublic:\n  typedef Matrix<typename ArgType::Scalar,\n                 RowIndexType::SizeAtCompileTime,\n                 ColIndexType::SizeAtCompileTime,\n                 ArgType::Flags&RowMajorBit?RowMajor:ColMajor,\n                 RowIndexType::MaxSizeAtCompileTime,\n                 ColIndexType::MaxSizeAtCompileTime> MatrixType;\n\n  indexing_functor(const ArgType& arg, const RowIndexType& row_indices, const ColIndexType& col_indices)\n    : m_arg(arg), m_rowIndices(row_indices), m_colIndices(col_indices)\n  {}\n\n  const typename ArgType::Scalar& operator() (Index row, Index col) const {\n    return m_arg(m_rowIndices[row], m_colIndices[col]);\n  }\n};\n// [functor]\n\n// [function]\ntemplate <class ArgType, class RowIndexType, class ColIndexType>\nCwiseNullaryOp<indexing_functor<ArgType,RowIndexType,ColIndexType>, typename indexing_functor<ArgType,RowIndexType,ColIndexType>::MatrixType>\nmat_indexing(const Eigen::MatrixBase<ArgType>& arg, const RowIndexType& row_indices, const ColIndexType& col_indices)\n{\n  typedef indexing_functor<ArgType,RowIndexType,ColIndexType> Func;\n  typedef typename Func::MatrixType MatrixType;\n  return MatrixType::NullaryExpr(row_indices.size(), col_indices.size(), Func(arg.derived(), row_indices, col_indices));\n}\n// [function]\n\n\nint main()\n{\n  std::cout << \"[main1]\\n\";\n  Eigen::MatrixXi A = Eigen::MatrixXi::Random(4,4);\n  Array3i ri(1,2,1);\n  ArrayXi ci(6); ci << 3,2,1,0,0,2;\n  Eigen::MatrixXi B = mat_indexing(A, ri, ci);\n  std::cout << \"A =\" << std::endl;\n  std::cout << A << std::endl << std::endl;\n  std::cout << \"A([\" << ri.transpose() << \"], [\" << ci.transpose() << \"]) =\" << std::endl;\n  std::cout << B << std::endl;\n  std::cout << \"[main1]\\n\";\n\n  std::cout << \"[main2]\\n\";\n  B =  mat_indexing(A, ri+1, ci);\n  std::cout << \"A(ri+1,ci) =\" << std::endl;\n  std::cout << B << std::endl << std::endl;\n#if EIGEN_COMP_CXXVER >= 11\n  B =  mat_indexing(A, ArrayXi::LinSpaced(13,0,12).unaryExpr([](int x){return x%4;}), ArrayXi::LinSpaced(4,0,3));\n  std::cout << \"A(ArrayXi::LinSpaced(13,0,12).unaryExpr([](int x){return x%4;}), ArrayXi::LinSpaced(4,0,3)) =\" << std::endl;\n  std::cout << B << std::endl << std::endl;\n#endif\n  std::cout << \"[main2]\\n\";\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/tut_arithmetic_add_sub.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace Eigen;\n\nint main()\n{\n  Matrix2d a;\n  a << 1, 2,\n       3, 4;\n  MatrixXd b(2,2);\n  b << 2, 3,\n       1, 4;\n  std::cout << \"a + b =\\n\" << a + b << std::endl;\n  std::cout << \"a - b =\\n\" << a - b << std::endl;\n  std::cout << \"Doing a += b;\" << std::endl;\n  a += b;\n  std::cout << \"Now a =\\n\" << a << std::endl;\n  Vector3d v(1,2,3);\n  Vector3d w(1,0,0);\n  std::cout << \"-v + w - v =\\n\" << -v + w - v << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/tut_arithmetic_dot_cross.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace Eigen;\nusing namespace std;\nint main()\n{\n  Vector3d v(1,2,3);\n  Vector3d w(0,1,2);\n\n  cout << \"Dot product: \" << v.dot(w) << endl;\n  double dp = v.adjoint()*w; // automatic conversion of the inner product to a scalar\n  cout << \"Dot product via a matrix product: \" << dp << endl;\n  cout << \"Cross product:\\n\" << v.cross(w) << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/tut_arithmetic_matrix_mul.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace Eigen;\nint main()\n{\n  Matrix2d mat;\n  mat << 1, 2,\n         3, 4;\n  Vector2d u(-1,1), v(2,0);\n  std::cout << \"Here is mat*mat:\\n\" << mat*mat << std::endl;\n  std::cout << \"Here is mat*u:\\n\" << mat*u << std::endl;\n  std::cout << \"Here is u^T*mat:\\n\" << u.transpose()*mat << std::endl;\n  std::cout << \"Here is u^T*v:\\n\" << u.transpose()*v << std::endl;\n  std::cout << \"Here is u*v^T:\\n\" << u*v.transpose() << std::endl;\n  std::cout << \"Let's multiply mat by itself\" << std::endl;\n  mat = mat*mat;\n  std::cout << \"Now mat is mat:\\n\" << mat << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/tut_arithmetic_redux_basic.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nint main()\n{\n  Eigen::Matrix2d mat;\n  mat << 1, 2,\n         3, 4;\n  cout << \"Here is mat.sum():       \" << mat.sum()       << endl;\n  cout << \"Here is mat.prod():      \" << mat.prod()      << endl;\n  cout << \"Here is mat.mean():      \" << mat.mean()      << endl;\n  cout << \"Here is mat.minCoeff():  \" << mat.minCoeff()  << endl;\n  cout << \"Here is mat.maxCoeff():  \" << mat.maxCoeff()  << endl;\n  cout << \"Here is mat.trace():     \" << mat.trace()     << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/tut_arithmetic_scalar_mul_div.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace Eigen;\n\nint main()\n{\n  Matrix2d a;\n  a << 1, 2,\n       3, 4;\n  Vector3d v(1,2,3);\n  std::cout << \"a * 2.5 =\\n\" << a * 2.5 << std::endl;\n  std::cout << \"0.1 * v =\\n\" << 0.1 * v << std::endl;\n  std::cout << \"Doing v *= 2;\" << std::endl;\n  v *= 2;\n  std::cout << \"Now v =\\n\" << v << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/tut_matrix_coefficient_accessors.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace Eigen;\n\nint main()\n{\n  MatrixXd m(2,2);\n  m(0,0) = 3;\n  m(1,0) = 2.5;\n  m(0,1) = -1;\n  m(1,1) = m(1,0) + m(0,1);\n  std::cout << \"Here is the matrix m:\\n\" << m << std::endl;\n  VectorXd v(2);\n  v(0) = 4;\n  v(1) = v(0) - 1;\n  std::cout << \"Here is the vector v:\\n\" << v << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/tut_matrix_resize.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace Eigen;\n\nint main()\n{\n  MatrixXd m(2,5);\n  m.resize(4,3);\n  std::cout << \"The matrix m is of size \"\n            << m.rows() << \"x\" << m.cols() << std::endl;\n  std::cout << \"It has \" << m.size() << \" coefficients\" << std::endl;\n  VectorXd v(2);\n  v.resize(5);\n  std::cout << \"The vector v is of size \" << v.size() << std::endl;\n  std::cout << \"As a matrix, v is of size \"\n            << v.rows() << \"x\" << v.cols() << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/examples/tut_matrix_resize_fixed_size.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace Eigen;\n\nint main()\n{\n  Matrix4d m;\n  m.resize(4,4); // no operation\n  std::cout << \"The matrix m is of size \"\n            << m.rows() << \"x\" << m.cols() << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/.krazy",
    "content": "EXCLUDE copyright\nEXCLUDE license\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/AngleAxis_mimic_euler.cpp",
    "content": "Matrix3f m;\nm = AngleAxisf(0.25*M_PI, Vector3f::UnitX())\n  * AngleAxisf(0.5*M_PI,  Vector3f::UnitY())\n  * AngleAxisf(0.33*M_PI, Vector3f::UnitZ());\ncout << m << endl << \"is unitary: \" << m.isUnitary() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Array_initializer_list_23_cxx11.cpp",
    "content": "ArrayXXi a {\n  {1, 2, 3},\n  {3, 4, 5}\n};\ncout << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Array_initializer_list_vector_cxx11.cpp",
    "content": "Array<int, Dynamic, 1> v {{1, 2, 3, 4, 5}};\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Array_variadic_ctor_cxx11.cpp",
    "content": "Array<int, 1, 6> a(1, 2, 3, 4, 5, 6);\nArray<int, 3, 1> b {1, 2, 3};\ncout << a << \"\\n\\n\" << b << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/BiCGSTAB_simple.cpp",
    "content": "  int n = 10000;\n  VectorXd x(n), b(n);\n  SparseMatrix<double> A(n,n);\n  /* ... fill A and b ... */ \n  BiCGSTAB<SparseMatrix<double> > solver;\n  solver.compute(A);\n  x = solver.solve(b);\n  std::cout << \"#iterations:     \" << solver.iterations() << std::endl;\n  std::cout << \"estimated error: \" << solver.error()      << std::endl;\n  /* ... update b ... */\n  x = solver.solve(b); // solve again\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/BiCGSTAB_step_by_step.cpp",
    "content": "  int n = 10000;\n  VectorXd x(n), b(n);\n  SparseMatrix<double> A(n,n);\n  /* ... fill A and b ... */ \n  BiCGSTAB<SparseMatrix<double> > solver(A);\n  // start from a random solution\n  x = VectorXd::Random(n);\n  solver.setMaxIterations(1);\n  int i = 0;\n  do {\n    x = solver.solveWithGuess(b,x);\n    std::cout << i << \" : \" << solver.error() << std::endl;\n    ++i;\n  } while (solver.info()!=Success && i<100);\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/CMakeLists.txt",
    "content": "file(GLOB snippets_SRCS \"*.cpp\")\n\nadd_custom_target(all_snippets)\n\nforeach(snippet_src ${snippets_SRCS})\n  get_filename_component(snippet ${snippet_src} NAME_WE)\n  set(compile_snippet_target compile_${snippet})\n  set(compile_snippet_src ${compile_snippet_target}.cpp)\n  \n  file(READ ${snippet_src} snippet_source_code)\n  configure_file(${CMAKE_CURRENT_SOURCE_DIR}/compile_snippet.cpp.in\n                ${CMAKE_CURRENT_BINARY_DIR}/${compile_snippet_src})\n  add_executable(${compile_snippet_target}\n                ${CMAKE_CURRENT_BINARY_DIR}/${compile_snippet_src})\n  if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO)\n    target_link_libraries(${compile_snippet_target} ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO})\n  endif()\n\n  if(${snippet_src} MATCHES \"deprecated\")\n    set_target_properties(${compile_snippet_target} PROPERTIES COMPILE_FLAGS \"-DEIGEN_NO_DEPRECATED_WARNING\")\n  endif()\n  add_custom_command(\n    TARGET ${compile_snippet_target}\n    POST_BUILD\n    COMMAND ${compile_snippet_target}\n    ARGS >${CMAKE_CURRENT_BINARY_DIR}/${snippet}.out\n  )\n  add_dependencies(all_snippets ${compile_snippet_target})\n  set_source_files_properties(${CMAKE_CURRENT_BINARY_DIR}/${compile_snippet_src}\n                              PROPERTIES OBJECT_DEPENDS ${snippet_src})\nendforeach()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/ColPivHouseholderQR_solve.cpp",
    "content": "Matrix3f m = Matrix3f::Random();\nMatrix3f y = Matrix3f::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the matrix y:\" << endl << y << endl;\nMatrix3f x;\nx = m.colPivHouseholderQr().solve(y);\nassert(y.isApprox(m*x));\ncout << \"Here is a solution x to the equation mx=y:\" << endl << x << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/ComplexEigenSolver_compute.cpp",
    "content": "MatrixXcf A = MatrixXcf::Random(4,4);\ncout << \"Here is a random 4x4 matrix, A:\" << endl << A << endl << endl;\n\nComplexEigenSolver<MatrixXcf> ces;\nces.compute(A);\ncout << \"The eigenvalues of A are:\" << endl << ces.eigenvalues() << endl;\ncout << \"The matrix of eigenvectors, V, is:\" << endl << ces.eigenvectors() << endl << endl;\n\ncomplex<float> lambda = ces.eigenvalues()[0];\ncout << \"Consider the first eigenvalue, lambda = \" << lambda << endl;\nVectorXcf v = ces.eigenvectors().col(0);\ncout << \"If v is the corresponding eigenvector, then lambda * v = \" << endl << lambda * v << endl;\ncout << \"... and A * v = \" << endl << A * v << endl << endl;\n\ncout << \"Finally, V * D * V^(-1) = \" << endl\n     << ces.eigenvectors() * ces.eigenvalues().asDiagonal() * ces.eigenvectors().inverse() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/ComplexEigenSolver_eigenvalues.cpp",
    "content": "MatrixXcf ones = MatrixXcf::Ones(3,3);\nComplexEigenSolver<MatrixXcf> ces(ones, /* computeEigenvectors = */ false);\ncout << \"The eigenvalues of the 3x3 matrix of ones are:\" \n     << endl << ces.eigenvalues() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/ComplexEigenSolver_eigenvectors.cpp",
    "content": "MatrixXcf ones = MatrixXcf::Ones(3,3);\nComplexEigenSolver<MatrixXcf> ces(ones);\ncout << \"The first eigenvector of the 3x3 matrix of ones is:\" \n     << endl << ces.eigenvectors().col(0) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/ComplexSchur_compute.cpp",
    "content": "MatrixXcf A = MatrixXcf::Random(4,4);\nComplexSchur<MatrixXcf> schur(4);\nschur.compute(A);\ncout << \"The matrix T in the decomposition of A is:\" << endl << schur.matrixT() << endl;\nschur.compute(A.inverse());\ncout << \"The matrix T in the decomposition of A^(-1) is:\" << endl << schur.matrixT() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/ComplexSchur_matrixT.cpp",
    "content": "MatrixXcf A = MatrixXcf::Random(4,4);\ncout << \"Here is a random 4x4 matrix, A:\" << endl << A << endl << endl;\nComplexSchur<MatrixXcf> schurOfA(A, false); // false means do not compute U\ncout << \"The triangular matrix T is:\" << endl << schurOfA.matrixT() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/ComplexSchur_matrixU.cpp",
    "content": "MatrixXcf A = MatrixXcf::Random(4,4);\ncout << \"Here is a random 4x4 matrix, A:\" << endl << A << endl << endl;\nComplexSchur<MatrixXcf> schurOfA(A);\ncout << \"The unitary matrix U is:\" << endl << schurOfA.matrixU() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_abs.cpp",
    "content": "Array3d v(1,-2,-3);\ncout << v.abs() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_abs2.cpp",
    "content": "Array3d v(1,-2,-3);\ncout << v.abs2() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_acos.cpp",
    "content": "Array3d v(0, sqrt(2.)/2, 1);\ncout << v.acos() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_arg.cpp",
    "content": "ArrayXcf v = ArrayXcf::Random(3);\ncout << v << endl << endl;\ncout << arg(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_array_power_array.cpp",
    "content": "Array<double,1,3> x(8,25,3),\n                  e(1./3.,0.5,2.);\ncout << \"[\" << x << \"]^[\" << e << \"] = \" << x.pow(e) << endl; // using ArrayBase::pow\ncout << \"[\" << x << \"]^[\" << e << \"] = \" << pow(x,e) << endl; // using Eigen::pow\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_asin.cpp",
    "content": "Array3d v(0, sqrt(2.)/2, 1);\ncout << v.asin() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_atan.cpp",
    "content": "ArrayXd v = ArrayXd::LinSpaced(5,0,1);\ncout << v.atan() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_boolean_and.cpp",
    "content": "Array3d v(-1,2,1), w(-3,2,3);\ncout << ((v<w) && (v<0)) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_boolean_not.cpp",
    "content": "Array3d v(1,2,3);\nv(1) *= 0.0/0.0;\nv(2) /= 0.0;\ncout << v << endl << endl;\ncout << !isfinite(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_boolean_or.cpp",
    "content": "Array3d v(-1,2,1), w(-3,2,3);\ncout << ((v<w) || (v<0)) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_boolean_xor.cpp",
    "content": "Array3d v(-1,2,1), w(-3,2,3);\ncout << ((v<w) ^ (v<0)) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_ceil.cpp",
    "content": "ArrayXd v = ArrayXd::LinSpaced(7,-2,2);\ncout << v << endl << endl;\ncout << ceil(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_cos.cpp",
    "content": "Array3d v(M_PI, M_PI/2, M_PI/3);\ncout << v.cos() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_cosh.cpp",
    "content": "ArrayXd v = ArrayXd::LinSpaced(5,0,1);\ncout << cosh(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_cube.cpp",
    "content": "Array3d v(2,3,4);\ncout << v.cube() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_equal_equal.cpp",
    "content": "Array3d v(1,2,3), w(3,2,1);\ncout << (v==w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_exp.cpp",
    "content": "Array3d v(1,2,3);\ncout << v.exp() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_floor.cpp",
    "content": "ArrayXd v = ArrayXd::LinSpaced(7,-2,2);\ncout << v << endl << endl;\ncout << floor(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_greater.cpp",
    "content": "Array3d v(1,2,3), w(3,2,1);\ncout << (v>w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_greater_equal.cpp",
    "content": "Array3d v(1,2,3), w(3,2,1);\ncout << (v>=w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_inverse.cpp",
    "content": "Array3d v(2,3,4);\ncout << v.inverse() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_isFinite.cpp",
    "content": "Array3d v(1,2,3);\nv(1) *= 0.0/0.0;\nv(2) /= 0.0;\ncout << v << endl << endl;\ncout << isfinite(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_isInf.cpp",
    "content": "Array3d v(1,2,3);\nv(1) *= 0.0/0.0;\nv(2) /= 0.0;\ncout << v << endl << endl;\ncout << isinf(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_isNaN.cpp",
    "content": "Array3d v(1,2,3);\nv(1) *= 0.0/0.0;\nv(2) /= 0.0;\ncout << v << endl << endl;\ncout << isnan(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_less.cpp",
    "content": "Array3d v(1,2,3), w(3,2,1);\ncout << (v<w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_less_equal.cpp",
    "content": "Array3d v(1,2,3), w(3,2,1);\ncout << (v<=w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_log.cpp",
    "content": "Array3d v(1,2,3);\ncout << v.log() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_log10.cpp",
    "content": "Array4d v(-1,0,1,2);\ncout << log10(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_max.cpp",
    "content": "Array3d v(2,3,4), w(4,2,3);\ncout << v.max(w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_min.cpp",
    "content": "Array3d v(2,3,4), w(4,2,3);\ncout << v.min(w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_minus.cpp",
    "content": "Array3d v(1,2,3);\ncout << v-5 << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_minus_equal.cpp",
    "content": "Array3d v(1,2,3);\nv -= 5;\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_not_equal.cpp",
    "content": "Array3d v(1,2,3), w(3,2,1);\ncout << (v!=w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_plus.cpp",
    "content": "Array3d v(1,2,3);\ncout << v+5 << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_plus_equal.cpp",
    "content": "Array3d v(1,2,3);\nv += 5;\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_pow.cpp",
    "content": "Array3d v(8,27,64);\ncout << v.pow(0.333333) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_product.cpp",
    "content": "Array33i a = Array33i::Random(), b = Array33i::Random();\nArray33i c = a * b;\ncout << \"a:\\n\" << a << \"\\nb:\\n\" << b << \"\\nc:\\n\" << c << endl;\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_quotient.cpp",
    "content": "Array3d v(2,3,4), w(4,2,3);\ncout << v/w << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_rint.cpp",
    "content": "ArrayXd v = ArrayXd::LinSpaced(7,-2,2);\ncout << v << endl << endl;\ncout << rint(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_round.cpp",
    "content": "ArrayXd v = ArrayXd::LinSpaced(7,-2,2);\ncout << v << endl << endl;\ncout << round(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_scalar_power_array.cpp",
    "content": "Array<double,1,3> e(2,-3,1./3.);\ncout << \"10^[\" << e << \"] = \" << pow(10,e) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_sign.cpp",
    "content": "Array3d v(-3,5,0);\ncout << v.sign() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_sin.cpp",
    "content": "Array3d v(M_PI, M_PI/2, M_PI/3);\ncout << v.sin() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_sinh.cpp",
    "content": "ArrayXd v = ArrayXd::LinSpaced(5,0,1);\ncout << sinh(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_slash_equal.cpp",
    "content": "Array3d v(3,2,4), w(5,4,2);\nv /= w;\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_sqrt.cpp",
    "content": "Array3d v(1,2,4);\ncout << v.sqrt() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_square.cpp",
    "content": "Array3d v(2,3,4);\ncout << v.square() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_tan.cpp",
    "content": "Array3d v(M_PI, M_PI/2, M_PI/3);\ncout << v.tan() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_tanh.cpp",
    "content": "ArrayXd v = ArrayXd::LinSpaced(5,0,1);\ncout << tanh(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Cwise_times_equal.cpp",
    "content": "Array3d v(1,2,3), w(2,3,0);\nv *= w;\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/DenseBase_LinSpaced.cpp",
    "content": "cout << VectorXi::LinSpaced(4,7,10).transpose() << endl;\ncout << VectorXd::LinSpaced(5,0.0,1.0).transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/DenseBase_LinSpacedInt.cpp",
    "content": "cout << \"Even spacing inputs:\" << endl;\ncout << VectorXi::LinSpaced(8,1,4).transpose() << endl;\ncout << VectorXi::LinSpaced(8,1,8).transpose() << endl;\ncout << VectorXi::LinSpaced(8,1,15).transpose() << endl;\ncout << \"Uneven spacing inputs:\" << endl;\ncout << VectorXi::LinSpaced(8,1,7).transpose() << endl;\ncout << VectorXi::LinSpaced(8,1,9).transpose() << endl;\ncout << VectorXi::LinSpaced(8,1,16).transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/DenseBase_LinSpaced_seq_deprecated.cpp",
    "content": "cout << VectorXi::LinSpaced(Sequential,4,7,10).transpose() << endl;\ncout << VectorXd::LinSpaced(Sequential,5,0.0,1.0).transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/DenseBase_setLinSpaced.cpp",
    "content": "VectorXf v;\nv.setLinSpaced(5,0.5f,1.5f);\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/DirectionWise_hnormalized.cpp",
    "content": "Matrix4Xd M = Matrix4Xd::Random(4,5);\nProjective3d P(Matrix4d::Random());\ncout << \"The matrix M is:\" << endl << M << endl << endl;\ncout << \"M.colwise().hnormalized():\" << endl << M.colwise().hnormalized() << endl << endl;\ncout << \"P*M:\" << endl << P*M << endl << endl;\ncout << \"(P*M).colwise().hnormalized():\" << endl << (P*M).colwise().hnormalized() << endl << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/DirectionWise_replicate.cpp",
    "content": "MatrixXi m = MatrixXi::Random(2,3);\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"m.colwise().replicate<3>() = ...\" << endl;\ncout << m.colwise().replicate<3>() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/DirectionWise_replicate_int.cpp",
    "content": "Vector3i v = Vector3i::Random();\ncout << \"Here is the vector v:\" << endl << v << endl;\ncout << \"v.rowwise().replicate(5) = ...\" << endl;\ncout << v.rowwise().replicate(5) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/EigenSolver_EigenSolver_MatrixType.cpp",
    "content": "MatrixXd A = MatrixXd::Random(6,6);\ncout << \"Here is a random 6x6 matrix, A:\" << endl << A << endl << endl;\n\nEigenSolver<MatrixXd> es(A);\ncout << \"The eigenvalues of A are:\" << endl << es.eigenvalues() << endl;\ncout << \"The matrix of eigenvectors, V, is:\" << endl << es.eigenvectors() << endl << endl;\n\ncomplex<double> lambda = es.eigenvalues()[0];\ncout << \"Consider the first eigenvalue, lambda = \" << lambda << endl;\nVectorXcd v = es.eigenvectors().col(0);\ncout << \"If v is the corresponding eigenvector, then lambda * v = \" << endl << lambda * v << endl;\ncout << \"... and A * v = \" << endl << A.cast<complex<double> >() * v << endl << endl;\n\nMatrixXcd D = es.eigenvalues().asDiagonal();\nMatrixXcd V = es.eigenvectors();\ncout << \"Finally, V * D * V^(-1) = \" << endl << V * D * V.inverse() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/EigenSolver_compute.cpp",
    "content": "EigenSolver<MatrixXf> es;\nMatrixXf A = MatrixXf::Random(4,4);\nes.compute(A, /* computeEigenvectors = */ false);\ncout << \"The eigenvalues of A are: \" << es.eigenvalues().transpose() << endl;\nes.compute(A + MatrixXf::Identity(4,4), false); // re-use es to compute eigenvalues of A+I\ncout << \"The eigenvalues of A+I are: \" << es.eigenvalues().transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/EigenSolver_eigenvalues.cpp",
    "content": "MatrixXd ones = MatrixXd::Ones(3,3);\nEigenSolver<MatrixXd> es(ones, false);\ncout << \"The eigenvalues of the 3x3 matrix of ones are:\" \n     << endl << es.eigenvalues() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/EigenSolver_eigenvectors.cpp",
    "content": "MatrixXd ones = MatrixXd::Ones(3,3);\nEigenSolver<MatrixXd> es(ones);\ncout << \"The first eigenvector of the 3x3 matrix of ones is:\"\n     << endl << es.eigenvectors().col(0) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/EigenSolver_pseudoEigenvectors.cpp",
    "content": "MatrixXd A = MatrixXd::Random(6,6);\ncout << \"Here is a random 6x6 matrix, A:\" << endl << A << endl << endl;\n\nEigenSolver<MatrixXd> es(A);\nMatrixXd D = es.pseudoEigenvalueMatrix();\nMatrixXd V = es.pseudoEigenvectors();\ncout << \"The pseudo-eigenvalue matrix D is:\" << endl << D << endl;\ncout << \"The pseudo-eigenvector matrix V is:\" << endl << V << endl;\ncout << \"Finally, V * D * V^(-1) = \" << endl << V * D * V.inverse() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/FullPivHouseholderQR_solve.cpp",
    "content": "Matrix3f m = Matrix3f::Random();\nMatrix3f y = Matrix3f::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the matrix y:\" << endl << y << endl;\nMatrix3f x;\nx = m.fullPivHouseholderQr().solve(y);\nassert(y.isApprox(m*x));\ncout << \"Here is a solution x to the equation mx=y:\" << endl << x << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/FullPivLU_image.cpp",
    "content": "Matrix3d m;\nm << 1,1,0,\n     1,3,2,\n     0,1,1;\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Notice that the middle column is the sum of the two others, so the \"\n     << \"columns are linearly dependent.\" << endl;\ncout << \"Here is a matrix whose columns have the same span but are linearly independent:\"\n     << endl << m.fullPivLu().image(m) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/FullPivLU_kernel.cpp",
    "content": "MatrixXf m = MatrixXf::Random(3,5);\ncout << \"Here is the matrix m:\" << endl << m << endl;\nMatrixXf ker = m.fullPivLu().kernel();\ncout << \"Here is a matrix whose columns form a basis of the kernel of m:\"\n     << endl << ker << endl;\ncout << \"By definition of the kernel, m*ker is zero:\"\n     << endl << m*ker << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/FullPivLU_solve.cpp",
    "content": "Matrix<float,2,3> m = Matrix<float,2,3>::Random();\nMatrix2f y = Matrix2f::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the matrix y:\" << endl << y << endl;\nMatrix<float,3,2> x = m.fullPivLu().solve(y);\nif((m*x).isApprox(y))\n{\n  cout << \"Here is a solution x to the equation mx=y:\" << endl << x << endl;\n}\nelse\n  cout << \"The equation mx=y does not have any solution.\" << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/GeneralizedEigenSolver.cpp",
    "content": "GeneralizedEigenSolver<MatrixXf> ges;\nMatrixXf A = MatrixXf::Random(4,4);\nMatrixXf B = MatrixXf::Random(4,4);\nges.compute(A, B);\ncout << \"The (complex) numerators of the generalzied eigenvalues are: \" << ges.alphas().transpose() << endl;\ncout << \"The (real) denominatore of the generalzied eigenvalues are: \" << ges.betas().transpose() << endl;\ncout << \"The (complex) generalzied eigenvalues are (alphas./beta): \" << ges.eigenvalues().transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/HessenbergDecomposition_compute.cpp",
    "content": "MatrixXcf A = MatrixXcf::Random(4,4);\nHessenbergDecomposition<MatrixXcf> hd(4);\nhd.compute(A);\ncout << \"The matrix H in the decomposition of A is:\" << endl << hd.matrixH() << endl;\nhd.compute(2*A); // re-use hd to compute and store decomposition of 2A\ncout << \"The matrix H in the decomposition of 2A is:\" << endl << hd.matrixH() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/HessenbergDecomposition_matrixH.cpp",
    "content": "Matrix4f A = MatrixXf::Random(4,4);\ncout << \"Here is a random 4x4 matrix:\" << endl << A << endl;\nHessenbergDecomposition<MatrixXf> hessOfA(A);\nMatrixXf H = hessOfA.matrixH();\ncout << \"The Hessenberg matrix H is:\" << endl << H << endl;\nMatrixXf Q = hessOfA.matrixQ();\ncout << \"The orthogonal matrix Q is:\" << endl << Q << endl;\ncout << \"Q H Q^T is:\" << endl << Q * H * Q.transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/HessenbergDecomposition_packedMatrix.cpp",
    "content": "Matrix4d A = Matrix4d::Random(4,4);\ncout << \"Here is a random 4x4 matrix:\" << endl << A << endl;\nHessenbergDecomposition<Matrix4d> hessOfA(A);\nMatrix4d pm = hessOfA.packedMatrix();\ncout << \"The packed matrix M is:\" << endl << pm << endl;\ncout << \"The upper Hessenberg part corresponds to the matrix H, which is:\" \n     << endl << hessOfA.matrixH() << endl;\nVector3d hc = hessOfA.householderCoefficients();\ncout << \"The vector of Householder coefficients is:\" << endl << hc << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/HouseholderQR_householderQ.cpp",
    "content": "MatrixXf A(MatrixXf::Random(5,3)), thinQ(MatrixXf::Identity(5,3)), Q;\nA.setRandom();\nHouseholderQR<MatrixXf> qr(A);\nQ = qr.householderQ();\nthinQ = qr.householderQ() * thinQ;\nstd::cout << \"The complete unitary matrix Q is:\\n\" << Q << \"\\n\\n\";\nstd::cout << \"The thin matrix Q is:\\n\" << thinQ << \"\\n\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/HouseholderQR_solve.cpp",
    "content": "typedef Matrix<float,3,3> Matrix3x3;\nMatrix3x3 m = Matrix3x3::Random();\nMatrix3f y = Matrix3f::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the matrix y:\" << endl << y << endl;\nMatrix3f x;\nx = m.householderQr().solve(y);\nassert(y.isApprox(m*x));\ncout << \"Here is a solution x to the equation mx=y:\" << endl << x << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/HouseholderSequence_HouseholderSequence.cpp",
    "content": "Matrix3d v = Matrix3d::Random();\ncout << \"The matrix v is:\" << endl;\ncout << v << endl;\n\nVector3d v0(1, v(1,0), v(2,0));\ncout << \"The first Householder vector is: v_0 = \" << v0.transpose() << endl;\nVector3d v1(0, 1, v(2,1));\ncout << \"The second Householder vector is: v_1 = \" << v1.transpose()  << endl;\nVector3d v2(0, 0, 1);\ncout << \"The third Householder vector is: v_2 = \" << v2.transpose() << endl;\n\nVector3d h = Vector3d::Random();\ncout << \"The Householder coefficients are: h = \" << h.transpose() << endl;\n\nMatrix3d H0 = Matrix3d::Identity() - h(0) * v0 * v0.adjoint();\ncout << \"The first Householder reflection is represented by H_0 = \" << endl;\ncout << H0 << endl;\nMatrix3d H1 = Matrix3d::Identity() - h(1) * v1 * v1.adjoint();\ncout << \"The second Householder reflection is represented by H_1 = \" << endl;\ncout << H1 << endl;\nMatrix3d H2 = Matrix3d::Identity() - h(2) * v2 * v2.adjoint();\ncout << \"The third Householder reflection is represented by H_2 = \" << endl;\ncout << H2 << endl;\ncout << \"Their product is H_0 H_1 H_2 = \" << endl;\ncout << H0 * H1 * H2 << endl;\n\nHouseholderSequence<Matrix3d, Vector3d> hhSeq(v, h);\nMatrix3d hhSeqAsMatrix(hhSeq);\ncout << \"If we construct a HouseholderSequence from v and h\" << endl;\ncout << \"and convert it to a matrix, we get:\" << endl;\ncout << hhSeqAsMatrix << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/IOFormat.cpp",
    "content": "std::string sep = \"\\n----------------------------------------\\n\";\nMatrix3d m1;\nm1 << 1.111111, 2, 3.33333, 4, 5, 6, 7, 8.888888, 9;\n\nIOFormat CommaInitFmt(StreamPrecision, DontAlignCols, \", \", \", \", \"\", \"\", \" << \", \";\");\nIOFormat CleanFmt(4, 0, \", \", \"\\n\", \"[\", \"]\");\nIOFormat OctaveFmt(StreamPrecision, 0, \", \", \";\\n\", \"\", \"\", \"[\", \"]\");\nIOFormat HeavyFmt(FullPrecision, 0, \", \", \";\\n\", \"[\", \"]\", \"[\", \"]\");\n\nstd::cout << m1 << sep;\nstd::cout << m1.format(CommaInitFmt) << sep;\nstd::cout << m1.format(CleanFmt) << sep;\nstd::cout << m1.format(OctaveFmt) << sep;\nstd::cout << m1.format(HeavyFmt) << sep;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/JacobiSVD_basic.cpp",
    "content": "MatrixXf m = MatrixXf::Random(3,2);\ncout << \"Here is the matrix m:\" << endl << m << endl;\nJacobiSVD<MatrixXf> svd(m, ComputeThinU | ComputeThinV);\ncout << \"Its singular values are:\" << endl << svd.singularValues() << endl;\ncout << \"Its left singular vectors are the columns of the thin U matrix:\" << endl << svd.matrixU() << endl;\ncout << \"Its right singular vectors are the columns of the thin V matrix:\" << endl << svd.matrixV() << endl;\nVector3f rhs(1, 0, 0);\ncout << \"Now consider this rhs vector:\" << endl << rhs << endl;\ncout << \"A least-squares solution of m*x = rhs is:\" << endl << svd.solve(rhs) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Jacobi_makeGivens.cpp",
    "content": "Vector2f v = Vector2f::Random();\nJacobiRotation<float> G;\nG.makeGivens(v.x(), v.y());\ncout << \"Here is the vector v:\" << endl << v << endl;\nv.applyOnTheLeft(0, 1, G.adjoint());\ncout << \"Here is the vector J' * v:\" << endl << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Jacobi_makeJacobi.cpp",
    "content": "Matrix2f m = Matrix2f::Random();\nm = (m + m.adjoint()).eval();\nJacobiRotation<float> J;\nJ.makeJacobi(m, 0, 1);\ncout << \"Here is the matrix m:\" << endl << m << endl;\nm.applyOnTheLeft(0, 1, J.adjoint());\nm.applyOnTheRight(0, 1, J);\ncout << \"Here is the matrix J' * m * J:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/LLT_example.cpp",
    "content": "MatrixXd A(3,3);\nA << 4,-1,2, -1,6,0, 2,0,5;\ncout << \"The matrix A is\" << endl << A << endl;\n\nLLT<MatrixXd> lltOfA(A); // compute the Cholesky decomposition of A\nMatrixXd L = lltOfA.matrixL(); // retrieve factor L  in the decomposition\n// The previous two lines can also be written as \"L = A.llt().matrixL()\"\n\ncout << \"The Cholesky factor L is\" << endl << L << endl;\ncout << \"To check this, let us compute L * L.transpose()\" << endl;\ncout << L * L.transpose() << endl;\ncout << \"This should equal the matrix A\" << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/LLT_solve.cpp",
    "content": "typedef Matrix<float,Dynamic,2> DataMatrix;\n// let's generate some samples on the 3D plane of equation z = 2x+3y (with some noise)\nDataMatrix samples = DataMatrix::Random(12,2);\nVectorXf elevations = 2*samples.col(0) + 3*samples.col(1) + VectorXf::Random(12)*0.1;\n// and let's solve samples * [x y]^T = elevations in least square sense:\nMatrix<float,2,1> xy\n = (samples.adjoint() * samples).llt().solve((samples.adjoint()*elevations));\ncout << xy << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/LeastSquaresNormalEquations.cpp",
    "content": "MatrixXf A = MatrixXf::Random(3, 2);\nVectorXf b = VectorXf::Random(3);\ncout << \"The solution using normal equations is:\\n\"\n     << (A.transpose() * A).ldlt().solve(A.transpose() * b) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/LeastSquaresQR.cpp",
    "content": "MatrixXf A = MatrixXf::Random(3, 2);\nVectorXf b = VectorXf::Random(3);\ncout << \"The solution using the QR decomposition is:\\n\"\n     << A.colPivHouseholderQr().solve(b) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Map_general_stride.cpp",
    "content": "int array[24];\nfor(int i = 0; i < 24; ++i) array[i] = i;\ncout << Map<MatrixXi, 0, Stride<Dynamic,2> >\n         (array, 3, 3, Stride<Dynamic,2>(8, 2))\n     << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Map_inner_stride.cpp",
    "content": "int array[12];\nfor(int i = 0; i < 12; ++i) array[i] = i;\ncout << Map<VectorXi, 0, InnerStride<2> >\n         (array, 6) // the inner stride has already been passed as template parameter\n     << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Map_outer_stride.cpp",
    "content": "int array[12];\nfor(int i = 0; i < 12; ++i) array[i] = i;\ncout << Map<MatrixXi, 0, OuterStride<> >(array, 3, 3, OuterStride<>(4)) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Map_placement_new.cpp",
    "content": "int data[] = {1,2,3,4,5,6,7,8,9};\nMap<RowVectorXi> v(data,4);\ncout << \"The mapped vector v is: \" << v << \"\\n\";\nnew (&v) Map<RowVectorXi>(data+4,5);\ncout << \"Now v is: \" << v << \"\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Map_simple.cpp",
    "content": "int array[9];\nfor(int i = 0; i < 9; ++i) array[i] = i;\ncout << Map<Matrix3i>(array) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_adjoint.cpp",
    "content": "Matrix2cf m = Matrix2cf::Random();\ncout << \"Here is the 2x2 complex matrix m:\" << endl << m << endl;\ncout << \"Here is the adjoint of m:\" << endl << m.adjoint() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_all.cpp",
    "content": "Vector3f boxMin(Vector3f::Zero()), boxMax(Vector3f::Ones());\nVector3f p0 = Vector3f::Random(), p1 = Vector3f::Random().cwiseAbs();\n// let's check if p0 and p1 are inside the axis aligned box defined by the corners boxMin,boxMax:\ncout << \"Is (\" << p0.transpose() << \") inside the box: \"\n     << ((boxMin.array()<p0.array()).all() && (boxMax.array()>p0.array()).all()) << endl;\ncout << \"Is (\" << p1.transpose() << \") inside the box: \"\n     << ((boxMin.array()<p1.array()).all() && (boxMax.array()>p1.array()).all()) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_applyOnTheLeft.cpp",
    "content": "Matrix3f A = Matrix3f::Random(3,3), B;\nB << 0,1,0,  \n     0,0,1,  \n     1,0,0;\ncout << \"At start, A = \" << endl << A << endl;\nA.applyOnTheLeft(B); \ncout << \"After applyOnTheLeft, A = \" << endl << A << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_applyOnTheRight.cpp",
    "content": "Matrix3f A = Matrix3f::Random(3,3), B;\nB << 0,1,0,  \n     0,0,1,  \n     1,0,0;\ncout << \"At start, A = \" << endl << A << endl;\nA *= B;\ncout << \"After A *= B, A = \" << endl << A << endl;\nA.applyOnTheRight(B);  // equivalent to A *= B\ncout << \"After applyOnTheRight, A = \" << endl << A << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_array.cpp",
    "content": "Vector3d v(1,2,3);\nv.array() += 3;\nv.array() -= 2;\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_array_const.cpp",
    "content": "Vector3d v(-1,2,-3);\ncout << \"the absolute values:\" << endl << v.array().abs() << endl;\ncout << \"the absolute values plus one:\" << endl << v.array().abs()+1 << endl;\ncout << \"sum of the squares: \" << v.array().square().sum() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_asDiagonal.cpp",
    "content": "cout << Matrix3i(Vector3i(2,5,6).asDiagonal()) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_block_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.block<2,2>(1,1):\" << endl << m.block<2,2>(1,1) << endl;\nm.block<2,2>(1,1).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_block_int_int_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.block(1, 1, 2, 2):\" << endl << m.block(1, 1, 2, 2) << endl;\nm.block(1, 1, 2, 2).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_bottomLeftCorner_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.bottomLeftCorner(2, 2):\" << endl;\ncout << m.bottomLeftCorner(2, 2) << endl;\nm.bottomLeftCorner(2, 2).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_bottomRightCorner_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.bottomRightCorner(2, 2):\" << endl;\ncout << m.bottomRightCorner(2, 2) << endl;\nm.bottomRightCorner(2, 2).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_bottomRows_int.cpp",
    "content": "Array44i a = Array44i::Random();\ncout << \"Here is the array a:\" << endl << a << endl;\ncout << \"Here is a.bottomRows(2):\" << endl;\ncout << a.bottomRows(2) << endl;\na.bottomRows(2).setZero();\ncout << \"Now the array a is:\" << endl << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_cast.cpp",
    "content": "Matrix2d md = Matrix2d::Identity() * 0.45;\nMatrix2f mf = Matrix2f::Identity();\ncout << md + mf.cast<double>() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_col.cpp",
    "content": "Matrix3d m = Matrix3d::Identity();\nm.col(1) = Vector3d(4,5,6);\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_colwise.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the sum of each column:\" << endl << m.colwise().sum() << endl;\ncout << \"Here is the maximum absolute value of each column:\"\n     << endl << m.cwiseAbs().colwise().maxCoeff() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_colwise_iterator_cxx11.cpp",
    "content": "Matrix3i m = Matrix3i::Random();\ncout << \"Here is the initial matrix m:\" << endl << m << endl;\nint i = -1;\nfor(auto c: m.colwise()) {\n  c *= i;\n  ++i;\n}\ncout << \"Here is the matrix m after the for-range-loop:\" << endl << m << endl;\nauto cols = m.colwise();\nauto it = std::find_if(cols.cbegin(), cols.cend(),\n                       [](Matrix3i::ConstColXpr x) { return x.squaredNorm() == 0; });\ncout << \"The first empty column is: \" << distance(cols.cbegin(),it) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_computeInverseAndDetWithCheck.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\nMatrix3d inverse;\nbool invertible;\ndouble determinant;\nm.computeInverseAndDetWithCheck(inverse,determinant,invertible);\ncout << \"Its determinant is \" << determinant << endl;\nif(invertible) {\n  cout << \"It is invertible, and its inverse is:\" << endl << inverse << endl;\n}\nelse {\n  cout << \"It is not invertible.\" << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_computeInverseWithCheck.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\nMatrix3d inverse;\nbool invertible;\nm.computeInverseWithCheck(inverse,invertible);\nif(invertible) {\n  cout << \"It is invertible, and its inverse is:\" << endl << inverse << endl;\n}\nelse {\n  cout << \"It is not invertible.\" << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_cwiseAbs.cpp",
    "content": "MatrixXd m(2,3);\nm << 2, -4, 6,   \n     -5, 1, 0;\ncout << m.cwiseAbs() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_cwiseAbs2.cpp",
    "content": "MatrixXd m(2,3);\nm << 2, -4, 6,   \n     -5, 1, 0;\ncout << m.cwiseAbs2() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_cwiseArg.cpp",
    "content": "MatrixXcf v = MatrixXcf::Random(2, 3);\ncout << v << endl << endl;\ncout << v.cwiseArg() << endl;"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_cwiseEqual.cpp",
    "content": "MatrixXi m(2,2);\nm << 1, 0,\n     1, 1;\ncout << \"Comparing m with identity matrix:\" << endl;\ncout << m.cwiseEqual(MatrixXi::Identity(2,2)) << endl;\nIndex count = m.cwiseEqual(MatrixXi::Identity(2,2)).count();\ncout << \"Number of coefficients that are equal: \" << count << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_cwiseInverse.cpp",
    "content": "MatrixXd m(2,3);\nm << 2, 0.5, 1,   \n     3, 0.25, 1;\ncout << m.cwiseInverse() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_cwiseMax.cpp",
    "content": "Vector3d v(2,3,4), w(4,2,3);\ncout << v.cwiseMax(w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_cwiseMin.cpp",
    "content": "Vector3d v(2,3,4), w(4,2,3);\ncout << v.cwiseMin(w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_cwiseNotEqual.cpp",
    "content": "MatrixXi m(2,2);\nm << 1, 0,\n     1, 1;\ncout << \"Comparing m with identity matrix:\" << endl;\ncout << m.cwiseNotEqual(MatrixXi::Identity(2,2)) << endl;\nIndex count = m.cwiseNotEqual(MatrixXi::Identity(2,2)).count();\ncout << \"Number of coefficients that are not equal: \" << count << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_cwiseProduct.cpp",
    "content": "Matrix3i a = Matrix3i::Random(), b = Matrix3i::Random();\nMatrix3i c = a.cwiseProduct(b);\ncout << \"a:\\n\" << a << \"\\nb:\\n\" << b << \"\\nc:\\n\" << c << endl;\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_cwiseQuotient.cpp",
    "content": "Vector3d v(2,3,4), w(4,2,3);\ncout << v.cwiseQuotient(w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_cwiseSign.cpp",
    "content": "MatrixXd m(2,3);\nm <<  2, -4, 6,\n     -5,  1, 0;\ncout << m.cwiseSign() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_cwiseSqrt.cpp",
    "content": "Vector3d v(1,2,4);\ncout << v.cwiseSqrt() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_diagonal.cpp",
    "content": "Matrix3i m = Matrix3i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here are the coefficients on the main diagonal of m:\" << endl\n     << m.diagonal() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_diagonal_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here are the coefficients on the 1st super-diagonal and 2nd sub-diagonal of m:\" << endl\n     << m.diagonal(1).transpose() << endl\n     << m.diagonal(-2).transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_diagonal_template_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here are the coefficients on the 1st super-diagonal and 2nd sub-diagonal of m:\" << endl\n     << m.diagonal<1>().transpose() << endl\n     << m.diagonal<-2>().transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_eigenvalues.cpp",
    "content": "MatrixXd ones = MatrixXd::Ones(3,3);\nVectorXcd eivals = ones.eigenvalues();\ncout << \"The eigenvalues of the 3x3 matrix of ones are:\" << endl << eivals << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_end_int.cpp",
    "content": "RowVector4i v = RowVector4i::Random();\ncout << \"Here is the vector v:\" << endl << v << endl;\ncout << \"Here is v.tail(2):\" << endl << v.tail(2) << endl;\nv.tail(2).setZero();\ncout << \"Now the vector v is:\" << endl << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_eval.cpp",
    "content": "Matrix2f M = Matrix2f::Random();\nMatrix2f m;\nm = M;\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Now we want to copy a column into a row.\" << endl;\ncout << \"If we do m.col(1) = m.row(0), then m becomes:\" << endl;\nm.col(1) = m.row(0);\ncout << m << endl << \"which is wrong!\" << endl;\ncout << \"Now let us instead do m.col(1) = m.row(0).eval(). Then m becomes\" << endl;\nm = M;\nm.col(1) = m.row(0).eval();\ncout << m << endl << \"which is right.\" << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_fixedBlock_int_int.cpp",
    "content": "Matrix4d m = Vector4d(1,2,3,4).asDiagonal();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.fixed<2, 2>(2, 2):\" << endl << m.block<2, 2>(2, 2) << endl;\nm.block<2, 2>(2, 0) = m.block<2, 2>(2, 2);\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_hnormalized.cpp",
    "content": "Vector4d v = Vector4d::Random();\nProjective3d P(Matrix4d::Random());\ncout << \"v                   = \" << v.transpose() << \"]^T\" << endl;\ncout << \"v.hnormalized()     = \" << v.hnormalized().transpose() << \"]^T\" << endl;\ncout << \"P*v                 = \" << (P*v).transpose() << \"]^T\" << endl;\ncout << \"(P*v).hnormalized() = \" << (P*v).hnormalized().transpose() << \"]^T\" << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_homogeneous.cpp",
    "content": "Vector3d v = Vector3d::Random(), w;\nProjective3d P(Matrix4d::Random());\ncout << \"v                                   = [\" << v.transpose() << \"]^T\" << endl;\ncout << \"h.homogeneous()                     = [\" << v.homogeneous().transpose() << \"]^T\" << endl;\ncout << \"(P * v.homogeneous())               = [\" << (P * v.homogeneous()).transpose() << \"]^T\" << endl;\ncout << \"(P * v.homogeneous()).hnormalized() = [\" << (P * v.homogeneous()).eval().hnormalized().transpose() << \"]^T\" << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_identity.cpp",
    "content": "cout << Matrix<double, 3, 4>::Identity() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_identity_int_int.cpp",
    "content": "cout << MatrixXd::Identity(4, 3) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_inverse.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Its inverse is:\" << endl << m.inverse() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_isDiagonal.cpp",
    "content": "Matrix3d m = 10000 * Matrix3d::Identity();\nm(0,2) = 1;\ncout << \"Here's the matrix m:\" << endl << m << endl;\ncout << \"m.isDiagonal() returns: \" << m.isDiagonal() << endl;\ncout << \"m.isDiagonal(1e-3) returns: \" << m.isDiagonal(1e-3) << endl;\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_isIdentity.cpp",
    "content": "Matrix3d m = Matrix3d::Identity();\nm(0,2) = 1e-4;\ncout << \"Here's the matrix m:\" << endl << m << endl;\ncout << \"m.isIdentity() returns: \" << m.isIdentity() << endl;\ncout << \"m.isIdentity(1e-3) returns: \" << m.isIdentity(1e-3) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_isOnes.cpp",
    "content": "Matrix3d m = Matrix3d::Ones();\nm(0,2) += 1e-4;\ncout << \"Here's the matrix m:\" << endl << m << endl;\ncout << \"m.isOnes() returns: \" << m.isOnes() << endl;\ncout << \"m.isOnes(1e-3) returns: \" << m.isOnes(1e-3) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_isOrthogonal.cpp",
    "content": "Vector3d v(1,0,0);\nVector3d w(1e-4,0,1);\ncout << \"Here's the vector v:\" << endl << v << endl;\ncout << \"Here's the vector w:\" << endl << w << endl;\ncout << \"v.isOrthogonal(w) returns: \" << v.isOrthogonal(w) << endl;\ncout << \"v.isOrthogonal(w,1e-3) returns: \" << v.isOrthogonal(w,1e-3) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_isUnitary.cpp",
    "content": "Matrix3d m = Matrix3d::Identity();\nm(0,2) = 1e-4;\ncout << \"Here's the matrix m:\" << endl << m << endl;\ncout << \"m.isUnitary() returns: \" << m.isUnitary() << endl;\ncout << \"m.isUnitary(1e-3) returns: \" << m.isUnitary(1e-3) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_isZero.cpp",
    "content": "Matrix3d m = Matrix3d::Zero();\nm(0,2) = 1e-4;\ncout << \"Here's the matrix m:\" << endl << m << endl;\ncout << \"m.isZero() returns: \" << m.isZero() << endl;\ncout << \"m.isZero(1e-3) returns: \" << m.isZero(1e-3) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_leftCols_int.cpp",
    "content": "Array44i a = Array44i::Random();\ncout << \"Here is the array a:\" << endl << a << endl;\ncout << \"Here is a.leftCols(2):\" << endl;\ncout << a.leftCols(2) << endl;\na.leftCols(2).setZero();\ncout << \"Now the array a is:\" << endl << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_noalias.cpp",
    "content": "Matrix2d a, b, c; a << 1,2,3,4; b << 5,6,7,8;\nc.noalias() = a * b; // this computes the product directly to c\ncout << c << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_ones.cpp",
    "content": "cout << Matrix2d::Ones() << endl;\ncout << 6 * RowVector4i::Ones() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_ones_int.cpp",
    "content": "cout << 6 * RowVectorXi::Ones(4) << endl;\ncout << VectorXf::Ones(2) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_ones_int_int.cpp",
    "content": "cout << MatrixXi::Ones(2,3) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_operatorNorm.cpp",
    "content": "MatrixXd ones = MatrixXd::Ones(3,3);\ncout << \"The operator norm of the 3x3 matrix of ones is \"\n     << ones.operatorNorm() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_prod.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the product of all the coefficients:\" << endl << m.prod() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_random.cpp",
    "content": "cout << 100 * Matrix2i::Random() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_random_int.cpp",
    "content": "cout << VectorXi::Random(2) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_random_int_int.cpp",
    "content": "cout << MatrixXi::Random(2,3) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_replicate.cpp",
    "content": "MatrixXi m = MatrixXi::Random(2,3);\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"m.replicate<3,2>() = ...\" << endl;\ncout << m.replicate<3,2>() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_replicate_int_int.cpp",
    "content": "Vector3i v = Vector3i::Random();\ncout << \"Here is the vector v:\" << endl << v << endl;\ncout << \"v.replicate(2,5) = ...\" << endl;\ncout << v.replicate(2,5) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_reshaped_auto.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.reshaped(2, AutoSize):\" << endl << m.reshaped(2, AutoSize) << endl;\ncout << \"Here is m.reshaped<RowMajor>(AutoSize, fix<8>):\" << endl << m.reshaped<RowMajor>(AutoSize, fix<8>) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_reshaped_fixed.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.reshaped(fix<2>,fix<8>):\" << endl << m.reshaped(fix<2>,fix<8>) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_reshaped_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.reshaped(2, 8):\" << endl << m.reshaped(2, 8) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_reshaped_to_vector.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.reshaped().transpose():\" << endl << m.reshaped().transpose() << endl;\ncout << \"Here is m.reshaped<RowMajor>().transpose():  \" << endl << m.reshaped<RowMajor>().transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_reverse.cpp",
    "content": "MatrixXi m = MatrixXi::Random(3,4);\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the reverse of m:\" << endl << m.reverse() << endl;\ncout << \"Here is the coefficient (1,0) in the reverse of m:\" << endl\n     << m.reverse()(1,0) << endl;\ncout << \"Let us overwrite this coefficient with the value 4.\" << endl;\nm.reverse()(1,0) = 4;\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_rightCols_int.cpp",
    "content": "Array44i a = Array44i::Random();\ncout << \"Here is the array a:\" << endl << a << endl;\ncout << \"Here is a.rightCols(2):\" << endl;\ncout << a.rightCols(2) << endl;\na.rightCols(2).setZero();\ncout << \"Now the array a is:\" << endl << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_row.cpp",
    "content": "Matrix3d m = Matrix3d::Identity();\nm.row(1) = Vector3d(4,5,6);\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_rowwise.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the sum of each row:\" << endl << m.rowwise().sum() << endl;\ncout << \"Here is the maximum absolute value of each row:\"\n     << endl << m.cwiseAbs().rowwise().maxCoeff() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_segment_int_int.cpp",
    "content": "RowVector4i v = RowVector4i::Random();\ncout << \"Here is the vector v:\" << endl << v << endl;\ncout << \"Here is v.segment(1, 2):\" << endl << v.segment(1, 2) << endl;\nv.segment(1, 2).setZero();\ncout << \"Now the vector v is:\" << endl << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_select.cpp",
    "content": "MatrixXi m(3, 3);\nm << 1, 2, 3,\n     4, 5, 6,\n     7, 8, 9;\nm = (m.array() >= 5).select(-m, m);\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_selfadjointView.cpp",
    "content": "Matrix3i m = Matrix3i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the symmetric matrix extracted from the upper part of m:\" << endl\n     << Matrix3i(m.selfadjointView<Upper>()) << endl;\ncout << \"Here is the symmetric matrix extracted from the lower part of m:\" << endl\n     << Matrix3i(m.selfadjointView<Lower>()) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_set.cpp",
    "content": "Matrix3i m1;\nm1 << 1, 2, 3,\n      4, 5, 6,\n      7, 8, 9;\ncout << m1 << endl << endl;\nMatrix3i m2 = Matrix3i::Identity();\nm2.block(0,0, 2,2) << 10, 11, 12, 13;\ncout << m2 << endl << endl;\nVector2i v1;\nv1 << 14, 15;\nm2 << v1.transpose(), 16,\n      v1, m1.block(1,1,2,2);\ncout << m2 << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_setIdentity.cpp",
    "content": "Matrix4i m = Matrix4i::Zero();\nm.block<3,3>(1,0).setIdentity();\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_setOnes.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\nm.row(1).setOnes();\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_setRandom.cpp",
    "content": "Matrix4i m = Matrix4i::Zero();\nm.col(1).setRandom();\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_setZero.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\nm.row(1).setZero();\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_start_int.cpp",
    "content": "RowVector4i v = RowVector4i::Random();\ncout << \"Here is the vector v:\" << endl << v << endl;\ncout << \"Here is v.head(2):\" << endl << v.head(2) << endl;\nv.head(2).setZero();\ncout << \"Now the vector v is:\" << endl << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_template_int_bottomRows.cpp",
    "content": "Array44i a = Array44i::Random();\ncout << \"Here is the array a:\" << endl << a << endl;\ncout << \"Here is a.bottomRows<2>():\" << endl;\ncout << a.bottomRows<2>() << endl;\na.bottomRows<2>().setZero();\ncout << \"Now the array a is:\" << endl << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_template_int_end.cpp",
    "content": "RowVector4i v = RowVector4i::Random();\ncout << \"Here is the vector v:\" << endl << v << endl;\ncout << \"Here is v.tail(2):\" << endl << v.tail<2>() << endl;\nv.tail<2>().setZero();\ncout << \"Now the vector v is:\" << endl << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_template_int_int_block_int_int_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the block:\" << endl << m.block<2, Dynamic>(1, 1, 2, 3) << endl;\nm.block<2, Dynamic>(1, 1, 2, 3).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_template_int_int_bottomLeftCorner.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.bottomLeftCorner<2,2>():\" << endl;\ncout << m.bottomLeftCorner<2,2>() << endl;\nm.bottomLeftCorner<2,2>().setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_template_int_int_bottomLeftCorner_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.bottomLeftCorner<2,Dynamic>(2,2):\" << endl;\ncout << m.bottomLeftCorner<2,Dynamic>(2,2) << endl;\nm.bottomLeftCorner<2,Dynamic>(2,2).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_template_int_int_bottomRightCorner.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.bottomRightCorner<2,2>():\" << endl;\ncout << m.bottomRightCorner<2,2>() << endl;\nm.bottomRightCorner<2,2>().setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_template_int_int_bottomRightCorner_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.bottomRightCorner<2,Dynamic>(2,2):\" << endl;\ncout << m.bottomRightCorner<2,Dynamic>(2,2) << endl;\nm.bottomRightCorner<2,Dynamic>(2,2).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_template_int_int_topLeftCorner.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.topLeftCorner<2,2>():\" << endl;\ncout << m.topLeftCorner<2,2>() << endl;\nm.topLeftCorner<2,2>().setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_template_int_int_topLeftCorner_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.topLeftCorner<2,Dynamic>(2,2):\" << endl;\ncout << m.topLeftCorner<2,Dynamic>(2,2) << endl;\nm.topLeftCorner<2,Dynamic>(2,2).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_template_int_int_topRightCorner.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.topRightCorner<2,2>():\" << endl;\ncout << m.topRightCorner<2,2>() << endl;\nm.topRightCorner<2,2>().setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_template_int_int_topRightCorner_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.topRightCorner<2,Dynamic>(2,2):\" << endl;\ncout << m.topRightCorner<2,Dynamic>(2,2) << endl;\nm.topRightCorner<2,Dynamic>(2,2).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_template_int_leftCols.cpp",
    "content": "Array44i a = Array44i::Random();\ncout << \"Here is the array a:\" << endl << a << endl;\ncout << \"Here is a.leftCols<2>():\" << endl;\ncout << a.leftCols<2>() << endl;\na.leftCols<2>().setZero();\ncout << \"Now the array a is:\" << endl << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_template_int_rightCols.cpp",
    "content": "Array44i a = Array44i::Random();\ncout << \"Here is the array a:\" << endl << a << endl;\ncout << \"Here is a.rightCols<2>():\" << endl;\ncout << a.rightCols<2>() << endl;\na.rightCols<2>().setZero();\ncout << \"Now the array a is:\" << endl << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_template_int_segment.cpp",
    "content": "RowVector4i v = RowVector4i::Random();\ncout << \"Here is the vector v:\" << endl << v << endl;\ncout << \"Here is v.segment<2>(1):\" << endl << v.segment<2>(1) << endl;\nv.segment<2>(2).setZero();\ncout << \"Now the vector v is:\" << endl << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_template_int_start.cpp",
    "content": "RowVector4i v = RowVector4i::Random();\ncout << \"Here is the vector v:\" << endl << v << endl;\ncout << \"Here is v.head(2):\" << endl << v.head<2>() << endl;\nv.head<2>().setZero();\ncout << \"Now the vector v is:\" << endl << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_template_int_topRows.cpp",
    "content": "Array44i a = Array44i::Random();\ncout << \"Here is the array a:\" << endl << a << endl;\ncout << \"Here is a.topRows<2>():\" << endl;\ncout << a.topRows<2>() << endl;\na.topRows<2>().setZero();\ncout << \"Now the array a is:\" << endl << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_topLeftCorner_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.topLeftCorner(2, 2):\" << endl;\ncout << m.topLeftCorner(2, 2) << endl;\nm.topLeftCorner(2, 2).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_topRightCorner_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.topRightCorner(2, 2):\" << endl;\ncout << m.topRightCorner(2, 2) << endl;\nm.topRightCorner(2, 2).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_topRows_int.cpp",
    "content": "Array44i a = Array44i::Random();\ncout << \"Here is the array a:\" << endl << a << endl;\ncout << \"Here is a.topRows(2):\" << endl;\ncout << a.topRows(2) << endl;\na.topRows(2).setZero();\ncout << \"Now the array a is:\" << endl << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_transpose.cpp",
    "content": "Matrix2i m = Matrix2i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the transpose of m:\" << endl << m.transpose() << endl;\ncout << \"Here is the coefficient (1,0) in the transpose of m:\" << endl\n     << m.transpose()(1,0) << endl;\ncout << \"Let us overwrite this coefficient with the value 0.\" << endl;\nm.transpose()(1,0) = 0;\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_triangularView.cpp",
    "content": "Matrix3i m = Matrix3i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the upper-triangular matrix extracted from m:\" << endl\n     << Matrix3i(m.triangularView<Eigen::Upper>()) << endl;\ncout << \"Here is the strictly-upper-triangular matrix extracted from m:\" << endl\n     << Matrix3i(m.triangularView<Eigen::StrictlyUpper>()) << endl;\ncout << \"Here is the unit-lower-triangular matrix extracted from m:\" << endl\n     << Matrix3i(m.triangularView<Eigen::UnitLower>()) << endl;\n// FIXME need to implement output for triangularViews (Bug 885)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_zero.cpp",
    "content": "cout << Matrix2d::Zero() << endl;\ncout << RowVector4i::Zero() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_zero_int.cpp",
    "content": "cout << RowVectorXi::Zero(4) << endl;\ncout << VectorXf::Zero(2) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/MatrixBase_zero_int_int.cpp",
    "content": "cout << MatrixXi::Zero(2,3) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Matrix_Map_stride.cpp",
    "content": "Matrix4i A;\nA << 1,  2,  3,  4,\n     5,  6,  7,  8,\n     9, 10, 11, 12,\n    13, 14, 15, 16;\n\nstd::cout << Matrix2i::Map(&A(1,1),Stride<8,2>()) << std::endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Matrix_initializer_list_23_cxx11.cpp",
    "content": "MatrixXd m {\n  {1, 2, 3},\n  {4, 5, 6}\n};\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Matrix_initializer_list_vector_cxx11.cpp",
    "content": "VectorXi v {{1, 2}};\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Matrix_resize_NoChange_int.cpp",
    "content": "MatrixXd m(3,4);\nm.resize(NoChange, 5);\ncout << \"m: \" << m.rows() << \" rows, \" << m.cols() << \" cols\" << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Matrix_resize_int.cpp",
    "content": "VectorXd v(10);\nv.resize(3);\nRowVector3d w;\nw.resize(3); // this is legal, but has no effect\ncout << \"v: \" << v.rows() << \" rows, \" << v.cols() << \" cols\" << endl;\ncout << \"w: \" << w.rows() << \" rows, \" << w.cols() << \" cols\" << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Matrix_resize_int_NoChange.cpp",
    "content": "MatrixXd m(3,4);\nm.resize(5, NoChange);\ncout << \"m: \" << m.rows() << \" rows, \" << m.cols() << \" cols\" << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Matrix_resize_int_int.cpp",
    "content": "MatrixXd m(2,3);\nm << 1,2,3,4,5,6;\ncout << \"here's the 2x3 matrix m:\" << endl << m << endl;\ncout << \"let's resize m to 3x2. This is a conservative resizing because 2*3==3*2.\" << endl;\nm.resize(3,2);\ncout << \"here's the 3x2 matrix m:\" << endl << m << endl;\ncout << \"now let's resize m to size 2x2. This is NOT a conservative resizing, so it becomes uninitialized:\" << endl;\nm.resize(2,2);\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Matrix_setConstant_int.cpp",
    "content": "VectorXf v;\nv.setConstant(3, 5);\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Matrix_setConstant_int_int.cpp",
    "content": "MatrixXf m;\nm.setConstant(3, 3, 5);\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Matrix_setIdentity_int_int.cpp",
    "content": "MatrixXf m;\nm.setIdentity(3, 3);\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Matrix_setOnes_int.cpp",
    "content": "VectorXf v;\nv.setOnes(3);\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Matrix_setOnes_int_int.cpp",
    "content": "MatrixXf m;\nm.setOnes(3, 3);\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Matrix_setRandom_int.cpp",
    "content": "VectorXf v;\nv.setRandom(3);\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Matrix_setRandom_int_int.cpp",
    "content": "MatrixXf m;\nm.setRandom(3, 3);\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Matrix_setZero_int.cpp",
    "content": "VectorXf v;\nv.setZero(3);\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Matrix_setZero_int_int.cpp",
    "content": "MatrixXf m;\nm.setZero(3, 3);\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Matrix_variadic_ctor_cxx11.cpp",
    "content": "Matrix<int, 1, 6> a(1, 2, 3, 4, 5, 6);\nMatrix<int, 3, 1> b {1, 2, 3};\ncout << a << \"\\n\\n\" << b << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/PartialPivLU_solve.cpp",
    "content": "MatrixXd A = MatrixXd::Random(3,3);\nMatrixXd B = MatrixXd::Random(3,2);\ncout << \"Here is the invertible matrix A:\" << endl << A << endl;\ncout << \"Here is the matrix B:\" << endl << B << endl;\nMatrixXd X = A.lu().solve(B);\ncout << \"Here is the (unique) solution X to the equation AX=B:\" << endl << X << endl;\ncout << \"Relative error: \" << (A*X-B).norm() / B.norm() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/PartialRedux_count.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\nMatrix<ptrdiff_t, 3, 1> res = (m.array() >= 0.5).rowwise().count();\ncout << \"Here is the count of elements larger or equal than 0.5 of each row:\" << endl;\ncout << res << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/PartialRedux_maxCoeff.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the maximum of each column:\" << endl << m.colwise().maxCoeff() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/PartialRedux_minCoeff.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the minimum of each column:\" << endl << m.colwise().minCoeff() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/PartialRedux_norm.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the norm of each column:\" << endl << m.colwise().norm() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/PartialRedux_prod.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the product of each row:\" << endl << m.rowwise().prod() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/PartialRedux_squaredNorm.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the square norm of each row:\" << endl << m.rowwise().squaredNorm() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/PartialRedux_sum.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the sum of each row:\" << endl << m.rowwise().sum() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/RealQZ_compute.cpp",
    "content": "MatrixXf A = MatrixXf::Random(4,4);\nMatrixXf B = MatrixXf::Random(4,4);\nRealQZ<MatrixXf> qz(4); // preallocate space for 4x4 matrices\nqz.compute(A,B);  // A = Q S Z,  B = Q T Z\n\n// print original matrices and result of decomposition\ncout << \"A:\\n\" << A << \"\\n\" << \"B:\\n\" << B << \"\\n\";\ncout << \"S:\\n\" << qz.matrixS() << \"\\n\" << \"T:\\n\" << qz.matrixT() << \"\\n\";\ncout << \"Q:\\n\" << qz.matrixQ() << \"\\n\" << \"Z:\\n\" << qz.matrixZ() << \"\\n\";\n\n// verify precision\ncout << \"\\nErrors:\"\n  << \"\\n|A-QSZ|: \" << (A-qz.matrixQ()*qz.matrixS()*qz.matrixZ()).norm()\n  << \", |B-QTZ|: \" << (B-qz.matrixQ()*qz.matrixT()*qz.matrixZ()).norm()\n  << \"\\n|QQ* - I|: \" << (qz.matrixQ()*qz.matrixQ().adjoint() - MatrixXf::Identity(4,4)).norm()\n  << \", |ZZ* - I|: \" << (qz.matrixZ()*qz.matrixZ().adjoint() - MatrixXf::Identity(4,4)).norm()\n  << \"\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/RealSchur_RealSchur_MatrixType.cpp",
    "content": "MatrixXd A = MatrixXd::Random(6,6);\ncout << \"Here is a random 6x6 matrix, A:\" << endl << A << endl << endl;\n\nRealSchur<MatrixXd> schur(A);\ncout << \"The orthogonal matrix U is:\" << endl << schur.matrixU() << endl;\ncout << \"The quasi-triangular matrix T is:\" << endl << schur.matrixT() << endl << endl;\n\nMatrixXd U = schur.matrixU();\nMatrixXd T = schur.matrixT();\ncout << \"U * T * U^T = \" << endl << U * T * U.transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/RealSchur_compute.cpp",
    "content": "MatrixXf A = MatrixXf::Random(4,4);\nRealSchur<MatrixXf> schur(4);\nschur.compute(A, /* computeU = */ false);\ncout << \"The matrix T in the decomposition of A is:\" << endl << schur.matrixT() << endl;\nschur.compute(A.inverse(), /* computeU = */ false);\ncout << \"The matrix T in the decomposition of A^(-1) is:\" << endl << schur.matrixT() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/SelfAdjointEigenSolver_SelfAdjointEigenSolver.cpp",
    "content": "SelfAdjointEigenSolver<Matrix4f> es;\nMatrix4f X = Matrix4f::Random(4,4);\nMatrix4f A = X + X.transpose();\nes.compute(A);\ncout << \"The eigenvalues of A are: \" << es.eigenvalues().transpose() << endl;\nes.compute(A + Matrix4f::Identity(4,4)); // re-use es to compute eigenvalues of A+I\ncout << \"The eigenvalues of A+I are: \" << es.eigenvalues().transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/SelfAdjointEigenSolver_SelfAdjointEigenSolver_MatrixType.cpp",
    "content": "MatrixXd X = MatrixXd::Random(5,5);\nMatrixXd A = X + X.transpose();\ncout << \"Here is a random symmetric 5x5 matrix, A:\" << endl << A << endl << endl;\n\nSelfAdjointEigenSolver<MatrixXd> es(A);\ncout << \"The eigenvalues of A are:\" << endl << es.eigenvalues() << endl;\ncout << \"The matrix of eigenvectors, V, is:\" << endl << es.eigenvectors() << endl << endl;\n\ndouble lambda = es.eigenvalues()[0];\ncout << \"Consider the first eigenvalue, lambda = \" << lambda << endl;\nVectorXd v = es.eigenvectors().col(0);\ncout << \"If v is the corresponding eigenvector, then lambda * v = \" << endl << lambda * v << endl;\ncout << \"... and A * v = \" << endl << A * v << endl << endl;\n\nMatrixXd D = es.eigenvalues().asDiagonal();\nMatrixXd V = es.eigenvectors();\ncout << \"Finally, V * D * V^(-1) = \" << endl << V * D * V.inverse() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/SelfAdjointEigenSolver_SelfAdjointEigenSolver_MatrixType2.cpp",
    "content": "MatrixXd X = MatrixXd::Random(5,5);\nMatrixXd A = X + X.transpose();\ncout << \"Here is a random symmetric matrix, A:\" << endl << A << endl;\nX = MatrixXd::Random(5,5);\nMatrixXd B = X * X.transpose();\ncout << \"and a random postive-definite matrix, B:\" << endl << B << endl << endl;\n\nGeneralizedSelfAdjointEigenSolver<MatrixXd> es(A,B);\ncout << \"The eigenvalues of the pencil (A,B) are:\" << endl << es.eigenvalues() << endl;\ncout << \"The matrix of eigenvectors, V, is:\" << endl << es.eigenvectors() << endl << endl;\n\ndouble lambda = es.eigenvalues()[0];\ncout << \"Consider the first eigenvalue, lambda = \" << lambda << endl;\nVectorXd v = es.eigenvectors().col(0);\ncout << \"If v is the corresponding eigenvector, then A * v = \" << endl << A * v << endl;\ncout << \"... and lambda * B * v = \" << endl << lambda * B * v << endl << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/SelfAdjointEigenSolver_compute_MatrixType.cpp",
    "content": "SelfAdjointEigenSolver<MatrixXf> es(4);\nMatrixXf X = MatrixXf::Random(4,4);\nMatrixXf A = X + X.transpose();\nes.compute(A);\ncout << \"The eigenvalues of A are: \" << es.eigenvalues().transpose() << endl;\nes.compute(A + MatrixXf::Identity(4,4)); // re-use es to compute eigenvalues of A+I\ncout << \"The eigenvalues of A+I are: \" << es.eigenvalues().transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/SelfAdjointEigenSolver_compute_MatrixType2.cpp",
    "content": "MatrixXd X = MatrixXd::Random(5,5);\nMatrixXd A = X * X.transpose();\nX = MatrixXd::Random(5,5);\nMatrixXd B = X * X.transpose();\n\nGeneralizedSelfAdjointEigenSolver<MatrixXd> es(A,B,EigenvaluesOnly);\ncout << \"The eigenvalues of the pencil (A,B) are:\" << endl << es.eigenvalues() << endl;\nes.compute(B,A,false);\ncout << \"The eigenvalues of the pencil (B,A) are:\" << endl << es.eigenvalues() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/SelfAdjointEigenSolver_eigenvalues.cpp",
    "content": "MatrixXd ones = MatrixXd::Ones(3,3);\nSelfAdjointEigenSolver<MatrixXd> es(ones);\ncout << \"The eigenvalues of the 3x3 matrix of ones are:\" \n     << endl << es.eigenvalues() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/SelfAdjointEigenSolver_eigenvectors.cpp",
    "content": "MatrixXd ones = MatrixXd::Ones(3,3);\nSelfAdjointEigenSolver<MatrixXd> es(ones);\ncout << \"The first eigenvector of the 3x3 matrix of ones is:\" \n     << endl << es.eigenvectors().col(0) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/SelfAdjointEigenSolver_operatorInverseSqrt.cpp",
    "content": "MatrixXd X = MatrixXd::Random(4,4);\nMatrixXd A = X * X.transpose();\ncout << \"Here is a random positive-definite matrix, A:\" << endl << A << endl << endl;\n\nSelfAdjointEigenSolver<MatrixXd> es(A);\ncout << \"The inverse square root of A is: \" << endl;\ncout << es.operatorInverseSqrt() << endl;\ncout << \"We can also compute it with operatorSqrt() and inverse(). That yields: \" << endl;\ncout << es.operatorSqrt().inverse() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/SelfAdjointEigenSolver_operatorSqrt.cpp",
    "content": "MatrixXd X = MatrixXd::Random(4,4);\nMatrixXd A = X * X.transpose();\ncout << \"Here is a random positive-definite matrix, A:\" << endl << A << endl << endl;\n\nSelfAdjointEigenSolver<MatrixXd> es(A);\nMatrixXd sqrtA = es.operatorSqrt();\ncout << \"The square root of A is: \" << endl << sqrtA << endl;\ncout << \"If we square this, we get: \" << endl << sqrtA*sqrtA << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/SelfAdjointView_eigenvalues.cpp",
    "content": "MatrixXd ones = MatrixXd::Ones(3,3);\nVectorXd eivals = ones.selfadjointView<Lower>().eigenvalues();\ncout << \"The eigenvalues of the 3x3 matrix of ones are:\" << endl << eivals << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/SelfAdjointView_operatorNorm.cpp",
    "content": "MatrixXd ones = MatrixXd::Ones(3,3);\ncout << \"The operator norm of the 3x3 matrix of ones is \"\n     << ones.selfadjointView<Lower>().operatorNorm() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Slicing_arrayexpr.cpp",
    "content": "ArrayXi ind(5); ind<<4,2,5,5,3;\nMatrixXi A = MatrixXi::Random(4,6);\ncout << \"Initial matrix A:\\n\" << A << \"\\n\\n\";\ncout << \"A(all,ind-1):\\n\" << A(all,ind-1) << \"\\n\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Slicing_custom_padding_cxx11.cpp",
    "content": "struct pad {\n  Index size() const { return out_size; }\n  Index operator[] (Index i) const { return std::max<Index>(0,i-(out_size-in_size)); }\n  Index in_size, out_size;\n};\n\nMatrix3i A;\nA.reshaped() = VectorXi::LinSpaced(9,1,9);\ncout << \"Initial matrix A:\\n\" << A << \"\\n\\n\";\nMatrixXi B(5,5);\nB = A(pad{3,5}, pad{3,5});\ncout << \"A(pad{3,N}, pad{3,N}):\\n\" << B << \"\\n\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Slicing_rawarray_cxx11.cpp",
    "content": "#if EIGEN_HAS_STATIC_ARRAY_TEMPLATE\nMatrixXi A = MatrixXi::Random(4,6);\ncout << \"Initial matrix A:\\n\" << A << \"\\n\\n\";\ncout << \"A(all,{4,2,5,5,3}):\\n\" << A(all,{4,2,5,5,3}) << \"\\n\\n\";\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Slicing_stdvector_cxx11.cpp",
    "content": "std::vector<int> ind{4,2,5,5,3};\nMatrixXi A = MatrixXi::Random(4,6);\ncout << \"Initial matrix A:\\n\" << A << \"\\n\\n\";\ncout << \"A(all,ind):\\n\" << A(all,ind) << \"\\n\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/SparseMatrix_coeffs.cpp",
    "content": "SparseMatrix<double> A(3,3);\nA.insert(1,2) = 0;\nA.insert(0,1) = 1;\nA.insert(2,0) = 2;\nA.makeCompressed();\ncout << \"The matrix A is:\" << endl << MatrixXd(A) << endl;\ncout << \"it has \" << A.nonZeros() << \" stored non zero coefficients that are: \" << A.coeffs().transpose() << endl;\nA.coeffs() += 10;\ncout << \"After adding 10 to every stored non zero coefficient, the matrix A is:\" << endl << MatrixXd(A) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/TopicAliasing_block.cpp",
    "content": "MatrixXi mat(3,3); \nmat << 1, 2, 3,   4, 5, 6,   7, 8, 9;\ncout << \"Here is the matrix mat:\\n\" << mat << endl;\n\n// This assignment shows the aliasing problem\nmat.bottomRightCorner(2,2) = mat.topLeftCorner(2,2);\ncout << \"After the assignment, mat = \\n\" << mat << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/TopicAliasing_block_correct.cpp",
    "content": "MatrixXi mat(3,3); \nmat << 1, 2, 3,   4, 5, 6,   7, 8, 9;\ncout << \"Here is the matrix mat:\\n\" << mat << endl;\n\n// The eval() solves the aliasing problem\nmat.bottomRightCorner(2,2) = mat.topLeftCorner(2,2).eval();\ncout << \"After the assignment, mat = \\n\" << mat << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/TopicAliasing_cwise.cpp",
    "content": "MatrixXf mat(2,2); \nmat << 1, 2,  4, 7;\ncout << \"Here is the matrix mat:\\n\" << mat << endl << endl;\n\nmat = 2 * mat;\ncout << \"After 'mat = 2 * mat', mat = \\n\" << mat << endl << endl;\n\n\nmat = mat - MatrixXf::Identity(2,2);\ncout << \"After the subtraction, it becomes\\n\" << mat << endl << endl;\n\n\nArrayXXf arr = mat;\narr = arr.square();\ncout << \"After squaring, it becomes\\n\" << arr << endl << endl;\n\n// Combining all operations in one statement:\nmat << 1, 2,  4, 7;\nmat = (2 * mat - MatrixXf::Identity(2,2)).array().square();\ncout << \"Doing everything at once yields\\n\" << mat << endl << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/TopicAliasing_mult1.cpp",
    "content": "MatrixXf matA(2,2); \nmatA << 2, 0,  0, 2;\nmatA = matA * matA;\ncout << matA;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/TopicAliasing_mult2.cpp",
    "content": "MatrixXf matA(2,2), matB(2,2); \nmatA << 2, 0,  0, 2;\n\n// Simple but not quite as efficient\nmatB = matA * matA;\ncout << matB << endl << endl;\n\n// More complicated but also more efficient\nmatB.noalias() = matA * matA;\ncout << matB;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/TopicAliasing_mult3.cpp",
    "content": "MatrixXf matA(2,2); \nmatA << 2, 0,  0, 2;\nmatA.noalias() = matA * matA;\ncout << matA;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/TopicAliasing_mult4.cpp",
    "content": "MatrixXf A(2,2), B(3,2);\nB << 2, 0,  0, 3, 1, 1;\nA << 2, 0, 0, -2;\nA = (B * A).cwiseAbs();\ncout << A;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/TopicAliasing_mult5.cpp",
    "content": "MatrixXf A(2,2), B(3,2);\nB << 2, 0,  0, 3, 1, 1;\nA << 2, 0, 0, -2;\nA = (B * A).eval().cwiseAbs();\ncout << A;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/TopicStorageOrders_example.cpp",
    "content": "Matrix<int, 3, 4, ColMajor> Acolmajor;\nAcolmajor << 8, 2, 2, 9,\n             9, 1, 4, 4,\n\t     3, 5, 4, 5;\ncout << \"The matrix A:\" << endl;\ncout << Acolmajor << endl << endl; \n\ncout << \"In memory (column-major):\" << endl;\nfor (int i = 0; i < Acolmajor.size(); i++)\n  cout << *(Acolmajor.data() + i) << \"  \";\ncout << endl << endl;\n\nMatrix<int, 3, 4, RowMajor> Arowmajor = Acolmajor;\ncout << \"In memory (row-major):\" << endl;\nfor (int i = 0; i < Arowmajor.size(); i++)\n  cout << *(Arowmajor.data() + i) << \"  \";\ncout << endl;\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Triangular_solve.cpp",
    "content": "Matrix3d m = Matrix3d::Zero();\nm.triangularView<Eigen::Upper>().setOnes();\ncout << \"Here is the matrix m:\\n\" << m << endl;\nMatrix3d n = Matrix3d::Ones();\nn.triangularView<Eigen::Lower>() *= 2;\ncout << \"Here is the matrix n:\\n\" << n << endl;\ncout << \"And now here is m.inverse()*n, taking advantage of the fact that\"\n        \" m is upper-triangular:\\n\"\n     << m.triangularView<Eigen::Upper>().solve(n) << endl;\ncout << \"And this is n*m.inverse():\\n\"\n     << m.triangularView<Eigen::Upper>().solve<Eigen::OnTheRight>(n);\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tridiagonalization_Tridiagonalization_MatrixType.cpp",
    "content": "MatrixXd X = MatrixXd::Random(5,5);\nMatrixXd A = X + X.transpose();\ncout << \"Here is a random symmetric 5x5 matrix:\" << endl << A << endl << endl;\nTridiagonalization<MatrixXd> triOfA(A);\nMatrixXd Q = triOfA.matrixQ();\ncout << \"The orthogonal matrix Q is:\" << endl << Q << endl;\nMatrixXd T = triOfA.matrixT();\ncout << \"The tridiagonal matrix T is:\" << endl << T << endl << endl;\ncout << \"Q * T * Q^T = \" << endl << Q * T * Q.transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tridiagonalization_compute.cpp",
    "content": "Tridiagonalization<MatrixXf> tri;\nMatrixXf X = MatrixXf::Random(4,4);\nMatrixXf A = X + X.transpose();\ntri.compute(A);\ncout << \"The matrix T in the tridiagonal decomposition of A is: \" << endl;\ncout << tri.matrixT() << endl;\ntri.compute(2*A); // re-use tri to compute eigenvalues of 2A\ncout << \"The matrix T in the tridiagonal decomposition of 2A is: \" << endl;\ncout << tri.matrixT() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tridiagonalization_decomposeInPlace.cpp",
    "content": "MatrixXd X = MatrixXd::Random(5,5);\nMatrixXd A = X + X.transpose();\ncout << \"Here is a random symmetric 5x5 matrix:\" << endl << A << endl << endl;\n\nVectorXd diag(5);\nVectorXd subdiag(4);\nVectorXd hcoeffs(4);  // Scratch space for householder reflector.\ninternal::tridiagonalization_inplace(A, diag, subdiag, hcoeffs, true);\ncout << \"The orthogonal matrix Q is:\" << endl << A << endl;\ncout << \"The diagonal of the tridiagonal matrix T is:\" << endl << diag << endl;\ncout << \"The subdiagonal of the tridiagonal matrix T is:\" << endl << subdiag << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tridiagonalization_diagonal.cpp",
    "content": "MatrixXcd X = MatrixXcd::Random(4,4);\nMatrixXcd A = X + X.adjoint();\ncout << \"Here is a random self-adjoint 4x4 matrix:\" << endl << A << endl << endl;\n\nTridiagonalization<MatrixXcd> triOfA(A);\nMatrixXd T = triOfA.matrixT();\ncout << \"The tridiagonal matrix T is:\" << endl << T << endl << endl;\n\ncout << \"We can also extract the diagonals of T directly ...\" << endl;\nVectorXd diag = triOfA.diagonal();\ncout << \"The diagonal is:\" << endl << diag << endl; \nVectorXd subdiag = triOfA.subDiagonal();\ncout << \"The subdiagonal is:\" << endl << subdiag << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tridiagonalization_householderCoefficients.cpp",
    "content": "Matrix4d X = Matrix4d::Random(4,4);\nMatrix4d A = X + X.transpose();\ncout << \"Here is a random symmetric 4x4 matrix:\" << endl << A << endl;\nTridiagonalization<Matrix4d> triOfA(A);\nVector3d hc = triOfA.householderCoefficients();\ncout << \"The vector of Householder coefficients is:\" << endl << hc << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tridiagonalization_packedMatrix.cpp",
    "content": "Matrix4d X = Matrix4d::Random(4,4);\nMatrix4d A = X + X.transpose();\ncout << \"Here is a random symmetric 4x4 matrix:\" << endl << A << endl;\nTridiagonalization<Matrix4d> triOfA(A);\nMatrix4d pm = triOfA.packedMatrix();\ncout << \"The packed matrix M is:\" << endl << pm << endl;\ncout << \"The diagonal and subdiagonal corresponds to the matrix T, which is:\" \n     << endl << triOfA.matrixT() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_AdvancedInitialization_Block.cpp",
    "content": "MatrixXf matA(2, 2);\nmatA << 1, 2, 3, 4;\nMatrixXf matB(4, 4);\nmatB << matA, matA/10, matA/10, matA;\nstd::cout << matB << std::endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_AdvancedInitialization_CommaTemporary.cpp",
    "content": "MatrixXf mat = MatrixXf::Random(2, 3);\nstd::cout << mat << std::endl << std::endl;\nmat = (MatrixXf(2,2) << 0, 1, 1, 0).finished() * mat;\nstd::cout << mat << std::endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_AdvancedInitialization_Join.cpp",
    "content": "RowVectorXd vec1(3);\nvec1 << 1, 2, 3;\nstd::cout << \"vec1 = \" << vec1 << std::endl;\n\nRowVectorXd vec2(4);\nvec2 << 1, 4, 9, 16;\nstd::cout << \"vec2 = \" << vec2 << std::endl;\n\nRowVectorXd joined(7);\njoined << vec1, vec2;\nstd::cout << \"joined = \" << joined << std::endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_AdvancedInitialization_LinSpaced.cpp",
    "content": "ArrayXXf table(10, 4);\ntable.col(0) = ArrayXf::LinSpaced(10, 0, 90);\ntable.col(1) = M_PI / 180 * table.col(0);\ntable.col(2) = table.col(1).sin();\ntable.col(3) = table.col(1).cos();\nstd::cout << \"  Degrees   Radians      Sine    Cosine\\n\";\nstd::cout << table << std::endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_AdvancedInitialization_ThreeWays.cpp",
    "content": "const int size = 6;\nMatrixXd mat1(size, size);\nmat1.topLeftCorner(size/2, size/2)     = MatrixXd::Zero(size/2, size/2);\nmat1.topRightCorner(size/2, size/2)    = MatrixXd::Identity(size/2, size/2);\nmat1.bottomLeftCorner(size/2, size/2)  = MatrixXd::Identity(size/2, size/2);\nmat1.bottomRightCorner(size/2, size/2) = MatrixXd::Zero(size/2, size/2);\nstd::cout << mat1 << std::endl << std::endl;\n\nMatrixXd mat2(size, size);\nmat2.topLeftCorner(size/2, size/2).setZero();\nmat2.topRightCorner(size/2, size/2).setIdentity();\nmat2.bottomLeftCorner(size/2, size/2).setIdentity();\nmat2.bottomRightCorner(size/2, size/2).setZero();\nstd::cout << mat2 << std::endl << std::endl;\n\nMatrixXd mat3(size, size);\nmat3 << MatrixXd::Zero(size/2, size/2), MatrixXd::Identity(size/2, size/2),\n        MatrixXd::Identity(size/2, size/2), MatrixXd::Zero(size/2, size/2);\nstd::cout << mat3 << std::endl;\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_AdvancedInitialization_Zero.cpp",
    "content": "std::cout << \"A fixed-size array:\\n\";\nArray33f a1 = Array33f::Zero();\nstd::cout << a1 << \"\\n\\n\";\n\n\nstd::cout << \"A one-dimensional dynamic-size array:\\n\";\nArrayXf a2 = ArrayXf::Zero(3);\nstd::cout << a2 << \"\\n\\n\";\n\n\nstd::cout << \"A two-dimensional dynamic-size array:\\n\";\nArrayXXf a3 = ArrayXXf::Zero(3, 4);\nstd::cout << a3 << \"\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_Map_rowmajor.cpp",
    "content": "int array[8];\nfor(int i = 0; i < 8; ++i) array[i] = i;\ncout << \"Column-major:\\n\" << Map<Matrix<int,2,4> >(array) << endl;\ncout << \"Row-major:\\n\" << Map<Matrix<int,2,4,RowMajor> >(array) << endl;\ncout << \"Row-major using stride:\\n\" <<\n  Map<Matrix<int,2,4>, Unaligned, Stride<1,4> >(array) << endl;\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_Map_using.cpp",
    "content": "typedef Matrix<float,1,Dynamic> MatrixType;\ntypedef Map<MatrixType> MapType;\ntypedef Map<const MatrixType> MapTypeConst;   // a read-only map\nconst int n_dims = 5;\n  \nMatrixType m1(n_dims), m2(n_dims);\nm1.setRandom();\nm2.setRandom();\nfloat *p = &m2(0);  // get the address storing the data for m2\nMapType m2map(p,m2.size());   // m2map shares data with m2\nMapTypeConst m2mapconst(p,m2.size());  // a read-only accessor for m2\n\ncout << \"m1: \" << m1 << endl;\ncout << \"m2: \" << m2 << endl;\ncout << \"Squared euclidean distance: \" << (m1-m2).squaredNorm() << endl;\ncout << \"Squared euclidean distance, using map: \" <<\n  (m1-m2map).squaredNorm() << endl;\nm2map(3) = 7;   // this will change m2, since they share the same array\ncout << \"Updated m2: \" << m2 << endl;\ncout << \"m2 coefficient 2, constant accessor: \" << m2mapconst(2) << endl;\n/* m2mapconst(2) = 5; */   // this yields a compile-time error\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_ReshapeMat2Mat.cpp",
    "content": "MatrixXf M1(2,6);    // Column-major storage\nM1 << 1, 2, 3,  4,  5,  6,\n      7, 8, 9, 10, 11, 12;\n\nMap<MatrixXf> M2(M1.data(), 6,2);\ncout << \"M2:\" << endl << M2 << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_ReshapeMat2Vec.cpp",
    "content": "MatrixXf M1(3,3);    // Column-major storage\nM1 << 1, 2, 3,\n      4, 5, 6,\n      7, 8, 9;\n\nMap<RowVectorXf> v1(M1.data(), M1.size());\ncout << \"v1:\" << endl << v1 << endl;\n\nMatrix<float,Dynamic,Dynamic,RowMajor> M2(M1);\nMap<RowVectorXf> v2(M2.data(), M2.size());\ncout << \"v2:\" << endl << v2 << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_SlicingCol.cpp",
    "content": "MatrixXf M1 = MatrixXf::Random(3,8);\ncout << \"Column major input:\" << endl << M1 << \"\\n\";\nMap<MatrixXf,0,OuterStride<> > M2(M1.data(), M1.rows(), (M1.cols()+2)/3, OuterStride<>(M1.outerStride()*3));\ncout << \"1 column over 3:\" << endl << M2 << \"\\n\";\n\ntypedef Matrix<float,Dynamic,Dynamic,RowMajor> RowMajorMatrixXf;\nRowMajorMatrixXf M3(M1);\ncout << \"Row major input:\" << endl << M3 << \"\\n\";\nMap<RowMajorMatrixXf,0,Stride<Dynamic,3> > M4(M3.data(), M3.rows(), (M3.cols()+2)/3,\n                                              Stride<Dynamic,3>(M3.outerStride(),3));\ncout << \"1 column over 3:\" << endl << M4 << \"\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_SlicingVec.cpp",
    "content": "RowVectorXf v = RowVectorXf::LinSpaced(20,0,19);\ncout << \"Input:\" << endl << v << endl;\nMap<RowVectorXf,0,InnerStride<2> > v2(v.data(), v.size()/2);\ncout << \"Even:\" << v2 << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_commainit_01.cpp",
    "content": "Matrix3f m;\nm << 1, 2, 3,\n     4, 5, 6,\n     7, 8, 9;\nstd::cout << m;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_commainit_01b.cpp",
    "content": "Matrix3f m;\nm.row(0) << 1, 2, 3;\nm.block(1,0,2,2) << 4, 5, 7, 8;\nm.col(2).tail(2) << 6, 9;\t\t    \nstd::cout << m;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_commainit_02.cpp",
    "content": "int rows=5, cols=5;\nMatrixXf m(rows,cols);\nm << (Matrix3f() << 1, 2, 3, 4, 5, 6, 7, 8, 9).finished(),\n     MatrixXf::Zero(3,cols-3),\n     MatrixXf::Zero(rows-3,3),\n     MatrixXf::Identity(rows-3,cols-3);\ncout << m;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_range_for_loop_1d_cxx11.cpp",
    "content": "VectorXi v = VectorXi::Random(4);\ncout << \"Here is the vector v:\\n\";\nfor(auto x : v) cout << x << \" \";\ncout << \"\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_range_for_loop_2d_cxx11.cpp",
    "content": "Matrix2i A = Matrix2i::Random();\ncout << \"Here are the coeffs of the 2x2 matrix A:\\n\";\nfor(auto x : A.reshaped())\n  cout << x << \" \";\ncout << \"\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_reshaped_vs_resize_1.cpp",
    "content": "MatrixXi m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.reshaped(2, 8):\" << endl << m.reshaped(2, 8) << endl;\nm.resize(2,8);\ncout << \"Here is the matrix m after m.resize(2,8):\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_reshaped_vs_resize_2.cpp",
    "content": "Matrix<int,Dynamic,Dynamic,RowMajor> m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.reshaped(2, 8):\" << endl << m.reshaped(2, 8) << endl;\ncout << \"Here is m.reshaped<AutoOrder>(2, 8):\" << endl << m.reshaped<AutoOrder>(2, 8) << endl;\nm.resize(2,8);\ncout << \"Here is the matrix m after m.resize(2,8):\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_solve_matrix_inverse.cpp",
    "content": "Matrix3f A;\nVector3f b;\nA << 1,2,3,  4,5,6,  7,8,10;\nb << 3, 3, 4;\nVector3f x = A.inverse() * b;\ncout << \"The solution is:\" << endl << x << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_solve_multiple_rhs.cpp",
    "content": "Matrix3f A(3,3);\nA << 1,2,3,  4,5,6,  7,8,10;\nMatrix<float,3,2> B;\nB << 3,1, 3,1, 4,1;\nMatrix<float,3,2> X;\nX = A.fullPivLu().solve(B);\ncout << \"The solution with right-hand side (3,3,4) is:\" << endl;\ncout << X.col(0) << endl;\ncout << \"The solution with right-hand side (1,1,1) is:\" << endl;\ncout << X.col(1) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_solve_reuse_decomposition.cpp",
    "content": "Matrix3f A(3,3);\nA << 1,2,3,  4,5,6,  7,8,10;\nPartialPivLU<Matrix3f> luOfA(A); // compute LU decomposition of A\nVector3f b;\nb << 3,3,4;\nVector3f x;\nx = luOfA.solve(b);\ncout << \"The solution with right-hand side (3,3,4) is:\" << endl;\ncout << x << endl;\nb << 1,1,1;\nx = luOfA.solve(b);\ncout << \"The solution with right-hand side (1,1,1) is:\" << endl;\ncout << x << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_solve_singular.cpp",
    "content": "Matrix3f A;\nVector3f b;\nA << 1,2,3,  4,5,6,  7,8,9;\nb << 3, 3, 4;\ncout << \"Here is the matrix A:\" << endl << A << endl;\ncout << \"Here is the vector b:\" << endl << b << endl;\nVector3f x;\nx = A.lu().solve(b);\ncout << \"The solution is:\" << endl << x << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_solve_triangular.cpp",
    "content": "Matrix3f A;\nVector3f b;\nA << 1,2,3,  0,5,6,  0,0,10;\nb << 3, 3, 4;\ncout << \"Here is the matrix A:\" << endl << A << endl;\ncout << \"Here is the vector b:\" << endl << b << endl;\nVector3f x = A.triangularView<Upper>().solve(b);\ncout << \"The solution is:\" << endl << x << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_solve_triangular_inplace.cpp",
    "content": "Matrix3f A;\nVector3f b;\nA << 1,2,3,  0,5,6,  0,0,10;\nb << 3, 3, 4;\nA.triangularView<Upper>().solveInPlace(b);\ncout << \"The solution is:\" << endl << b << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_std_sort.cpp",
    "content": "Array4i v = Array4i::Random().abs();\ncout << \"Here is the initial vector v:\\n\" << v.transpose() << \"\\n\";\nstd::sort(v.begin(), v.end());\ncout << \"Here is the sorted vector v:\\n\" << v.transpose() << \"\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Tutorial_std_sort_rows_cxx11.cpp",
    "content": "ArrayXXi A = ArrayXXi::Random(4,4).abs();\ncout << \"Here is the initial matrix A:\\n\" << A << \"\\n\";\nfor(auto row : A.rowwise())\n  std::sort(row.begin(), row.end());\ncout << \"Here is the sorted matrix A:\\n\" << A << \"\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/VectorwiseOp_homogeneous.cpp",
    "content": "Matrix3Xd M = Matrix3Xd::Random(3,5);\nProjective3d P(Matrix4d::Random());\ncout << \"The matrix M is:\" << endl << M << endl << endl;\ncout << \"M.colwise().homogeneous():\" << endl << M.colwise().homogeneous() << endl << endl;\ncout << \"P * M.colwise().homogeneous():\" << endl << P * M.colwise().homogeneous() << endl << endl;\ncout << \"P * M.colwise().homogeneous().hnormalized(): \" << endl << (P * M.colwise().homogeneous()).colwise().hnormalized() << endl << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/Vectorwise_reverse.cpp",
    "content": "MatrixXi m = MatrixXi::Random(3,4);\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the rowwise reverse of m:\" << endl << m.rowwise().reverse() << endl;\ncout << \"Here is the colwise reverse of m:\" << endl << m.colwise().reverse() << endl;\n\ncout << \"Here is the coefficient (1,0) in the rowise reverse of m:\" << endl\n<< m.rowwise().reverse()(1,0) << endl;\ncout << \"Let us overwrite this coefficient with the value 4.\" << endl;\n//m.colwise().reverse()(1,0) = 4;\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/class_FullPivLU.cpp",
    "content": "typedef Matrix<double, 5, 3> Matrix5x3;\ntypedef Matrix<double, 5, 5> Matrix5x5;\nMatrix5x3 m = Matrix5x3::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\nEigen::FullPivLU<Matrix5x3> lu(m);\ncout << \"Here is, up to permutations, its LU decomposition matrix:\"\n     << endl << lu.matrixLU() << endl;\ncout << \"Here is the L part:\" << endl;\nMatrix5x5 l = Matrix5x5::Identity();\nl.block<5,3>(0,0).triangularView<StrictlyLower>() = lu.matrixLU();\ncout << l << endl;\ncout << \"Here is the U part:\" << endl;\nMatrix5x3 u = lu.matrixLU().triangularView<Upper>();\ncout << u << endl;\ncout << \"Let us now reconstruct the original matrix m:\" << endl;\ncout << lu.permutationP().inverse() * l * u * lu.permutationQ().inverse() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/compile_snippet.cpp.in",
    "content": "static bool eigen_did_assert = false;\n#define eigen_assert(X) if(!eigen_did_assert && !(X)){ std::cout << \"### Assertion raised in \" << __FILE__ << \":\" << __LINE__ << \":\\n\" #X << \"\\n### The following would happen without assertions:\\n\"; eigen_did_assert = true;}\n\n#include <iostream>\n#include <Eigen/Eigen>\n\n#ifndef M_PI\n#define M_PI 3.1415926535897932384626433832795\n#endif\n\n\nusing namespace Eigen;\nusing namespace std;\n\nint main(int, char**)\n{\n  cout.precision(3);\n// intentionally remove indentation of snippet\n{\n${snippet_source_code}\n}\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/tut_arithmetic_redux_minmax.cpp",
    "content": "  Matrix3f m = Matrix3f::Random();\n  std::ptrdiff_t i, j;\n  float minOfM = m.minCoeff(&i,&j);\n  cout << \"Here is the matrix m:\\n\" << m << endl;\n  cout << \"Its minimum coefficient (\" << minOfM \n       << \") is at position (\" << i << \",\" << j << \")\\n\\n\";\n\n  RowVector4i v = RowVector4i::Random();\n  int maxOfV = v.maxCoeff(&i);\n  cout << \"Here is the vector v: \" << v << endl;\n  cout << \"Its maximum coefficient (\" << maxOfV \n       << \") is at position \" << i << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/tut_arithmetic_transpose_aliasing.cpp",
    "content": "Matrix2i a; a << 1, 2, 3, 4;\ncout << \"Here is the matrix a:\\n\" << a << endl;\n\na = a.transpose(); // !!! do NOT do this !!!\ncout << \"and the result of the aliasing effect:\\n\" << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/tut_arithmetic_transpose_conjugate.cpp",
    "content": "MatrixXcf a = MatrixXcf::Random(2,2);\ncout << \"Here is the matrix a\\n\" << a << endl;\n\ncout << \"Here is the matrix a^T\\n\" << a.transpose() << endl;\n\n\ncout << \"Here is the conjugate of a\\n\" << a.conjugate() << endl;\n\n\ncout << \"Here is the matrix a^*\\n\" << a.adjoint() << endl;\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/tut_arithmetic_transpose_inplace.cpp",
    "content": "MatrixXf a(2,3); a << 1, 2, 3, 4, 5, 6;\ncout << \"Here is the initial matrix a:\\n\" << a << endl;\n\n\na.transposeInPlace();\ncout << \"and after being transposed:\\n\" << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/snippets/tut_matrix_assignment_resizing.cpp",
    "content": "MatrixXf a(2,2);\nstd::cout << \"a is of size \" << a.rows() << \"x\" << a.cols() << std::endl;\nMatrixXf b(3,3);\na = b;\nstd::cout << \"a is now of size \" << a.rows() << \"x\" << a.cols() << std::endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/special_examples/CMakeLists.txt",
    "content": "if(NOT EIGEN_TEST_NOQT)\n  find_package(Qt4)\n  if(QT4_FOUND)\n    include(${QT_USE_FILE})\n  endif()\nendif()\n\nif(QT4_FOUND)\n  add_executable(Tutorial_sparse_example Tutorial_sparse_example.cpp Tutorial_sparse_example_details.cpp)\n  target_link_libraries(Tutorial_sparse_example ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO} ${QT_QTCORE_LIBRARY} ${QT_QTGUI_LIBRARY})\n\n  add_custom_command(\n    TARGET Tutorial_sparse_example\n    POST_BUILD\n    COMMAND ${CMAKE_COMMAND} -E make_directory ${CMAKE_CURRENT_BINARY_DIR}/../html/\n    COMMAND Tutorial_sparse_example ARGS ${CMAKE_CURRENT_BINARY_DIR}/../html/Tutorial_sparse_example.jpeg\n  )\n\n  add_dependencies(all_examples Tutorial_sparse_example)\nendif()\n\nadd_executable(random_cpp11 random_cpp11.cpp)\ntarget_link_libraries(random_cpp11 ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO})\nadd_dependencies(all_examples random_cpp11)\n\nadd_custom_command(\n  TARGET random_cpp11\n  POST_BUILD\n  COMMAND random_cpp11\n  ARGS >${CMAKE_CURRENT_BINARY_DIR}/random_cpp11.out\n)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/special_examples/Tutorial_sparse_example.cpp",
    "content": "#include <Eigen/Sparse>\n#include <vector>\n#include <iostream>\n\ntypedef Eigen::SparseMatrix<double> SpMat; // declares a column-major sparse matrix type of double\ntypedef Eigen::Triplet<double> T;\n\nvoid buildProblem(std::vector<T>& coefficients, Eigen::VectorXd& b, int n);\nvoid saveAsBitmap(const Eigen::VectorXd& x, int n, const char* filename);\n\nint main(int argc, char** argv)\n{\n  if(argc!=2) {\n    std::cerr << \"Error: expected one and only one argument.\\n\";\n    return -1;\n  }\n  \n  int n = 300;  // size of the image\n  int m = n*n;  // number of unknowns (=number of pixels)\n\n  // Assembly:\n  std::vector<T> coefficients;            // list of non-zeros coefficients\n  Eigen::VectorXd b(m);                   // the right hand side-vector resulting from the constraints\n  buildProblem(coefficients, b, n);\n\n  SpMat A(m,m);\n  A.setFromTriplets(coefficients.begin(), coefficients.end());\n\n  // Solving:\n  Eigen::SimplicialCholesky<SpMat> chol(A);  // performs a Cholesky factorization of A\n  Eigen::VectorXd x = chol.solve(b);         // use the factorization to solve for the given right hand side\n\n  // Export the result to a file:\n  saveAsBitmap(x, n, argv[1]);\n\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/special_examples/Tutorial_sparse_example_details.cpp",
    "content": "#include <Eigen/Sparse>\n#include <vector>\n#include <QImage>\n\ntypedef Eigen::SparseMatrix<double> SpMat; // declares a column-major sparse matrix type of double\ntypedef Eigen::Triplet<double> T;\n\nvoid insertCoefficient(int id, int i, int j, double w, std::vector<T>& coeffs,\n                       Eigen::VectorXd& b, const Eigen::VectorXd& boundary)\n{\n  int n = int(boundary.size());\n  int id1 = i+j*n;\n\n        if(i==-1 || i==n) b(id) -= w * boundary(j); // constrained coefficient\n  else  if(j==-1 || j==n) b(id) -= w * boundary(i); // constrained coefficient\n  else  coeffs.push_back(T(id,id1,w));              // unknown coefficient\n}\n\nvoid buildProblem(std::vector<T>& coefficients, Eigen::VectorXd& b, int n)\n{\n  b.setZero();\n  Eigen::ArrayXd boundary = Eigen::ArrayXd::LinSpaced(n, 0,M_PI).sin().pow(2);\n  for(int j=0; j<n; ++j)\n  {\n    for(int i=0; i<n; ++i)\n    {\n      int id = i+j*n;\n      insertCoefficient(id, i-1,j, -1, coefficients, b, boundary);\n      insertCoefficient(id, i+1,j, -1, coefficients, b, boundary);\n      insertCoefficient(id, i,j-1, -1, coefficients, b, boundary);\n      insertCoefficient(id, i,j+1, -1, coefficients, b, boundary);\n      insertCoefficient(id, i,j,    4, coefficients, b, boundary);\n    }\n  }\n}\n\nvoid saveAsBitmap(const Eigen::VectorXd& x, int n, const char* filename)\n{\n  Eigen::Array<unsigned char,Eigen::Dynamic,Eigen::Dynamic> bits = (x*255).cast<unsigned char>();\n  QImage img(bits.data(), n,n,QImage::Format_Indexed8);\n  img.setColorCount(256);\n  for(int i=0;i<256;i++) img.setColor(i,qRgb(i,i,i));\n  img.save(filename);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/special_examples/random_cpp11.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\n#include <random>\n\nusing namespace Eigen;\n\nint main() {\n  std::default_random_engine generator;\n  std::poisson_distribution<int> distribution(4.1);\n  auto poisson = [&] () {return distribution(generator);};\n\n  RowVectorXi v = RowVectorXi::NullaryExpr(10, poisson );\n  std::cout << v << \"\\n\";\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/doc/tutorial.cpp",
    "content": "#include <Eigen/Array>\n\nint main(int argc, char *argv[])\n{\n  std::cout.precision(2);\n\n  // demo static functions\n  Eigen::Matrix3f m3 = Eigen::Matrix3f::Random();\n  Eigen::Matrix4f m4 = Eigen::Matrix4f::Identity();\n\n  std::cout << \"*** Step 1 ***\\nm3:\\n\" << m3 << \"\\nm4:\\n\" << m4 << std::endl;\n\n  // demo non-static set... functions\n  m4.setZero();\n  m3.diagonal().setOnes();\n  \n  std::cout << \"*** Step 2 ***\\nm3:\\n\" << m3 << \"\\nm4:\\n\" << m4 << std::endl;\n\n  // demo fixed-size block() expression as lvalue and as rvalue\n  m4.block<3,3>(0,1) = m3;\n  m3.row(2) = m4.block<1,3>(2,0);\n\n  std::cout << \"*** Step 3 ***\\nm3:\\n\" << m3 << \"\\nm4:\\n\" << m4 << std::endl;\n\n  // demo dynamic-size block()\n  {\n    int rows = 3, cols = 3;\n    m4.block(0,1,3,3).setIdentity();\n    std::cout << \"*** Step 4 ***\\nm4:\\n\" << m4 << std::endl;\n  }\n\n  // demo vector blocks\n  m4.diagonal().block(1,2).setOnes();\n  std::cout << \"*** Step 5 ***\\nm4.diagonal():\\n\" << m4.diagonal() << std::endl;\n  std::cout << \"m4.diagonal().start(3)\\n\" << m4.diagonal().start(3) << std::endl;\n\n  // demo coeff-wise operations\n  m4 = m4.cwise()*m4;\n  m3 = m3.cwise().cos();\n  std::cout << \"*** Step 6 ***\\nm3:\\n\" << m3 << \"\\nm4:\\n\" << m4 << std::endl;\n\n  // sums of coefficients\n  std::cout << \"*** Step 7 ***\\n m4.sum(): \" << m4.sum() << std::endl;\n  std::cout << \"m4.col(2).sum(): \" << m4.col(2).sum() << std::endl;\n  std::cout << \"m4.colwise().sum():\\n\" << m4.colwise().sum() << std::endl;\n  std::cout << \"m4.rowwise().sum():\\n\" << m4.rowwise().sum() << std::endl;\n\n  // demo intelligent auto-evaluation\n  m4 = m4 * m4; // auto-evaluates so no aliasing problem (performance penalty is low)\n  Eigen::Matrix4f other = (m4 * m4).lazy(); // forces lazy evaluation\n  m4 = m4 + m4; // here Eigen goes for lazy evaluation, as with most expressions\n  m4 = -m4 + m4 + 5 * m4; // same here, Eigen chooses lazy evaluation for all that.\n  m4 = m4 * (m4 + m4); // here Eigen chooses to first evaluate m4 + m4 into a temporary.\n                       // indeed, here it is an optimization to cache this intermediate result.\n  m3 = m3 * m4.block<3,3>(1,1); // here Eigen chooses NOT to evaluate block() into a temporary\n    // because accessing coefficients of that block expression is not more costly than accessing\n    // coefficients of a plain matrix.\n  m4 = m4 * m4.transpose(); // same here, lazy evaluation of the transpose.\n  m4 = m4 * m4.transpose().eval(); // forces immediate evaluation of the transpose\n\n  std::cout << \"*** Step 8 ***\\nm3:\\n\" << m3 << \"\\nm4:\\n\" << m4 << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/eigen3.pc.in",
    "content": "prefix=@CMAKE_INSTALL_PREFIX@\nexec_prefix=${prefix}\n\nName: Eigen3\nDescription: A C++ template library for linear algebra: vectors, matrices, and related algorithms\nRequires:\nVersion: @EIGEN_VERSION_NUMBER@\nLibs:\nCflags: -I${prefix}/@INCLUDE_INSTALL_DIR@\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/CMakeLists.txt",
    "content": "\nei_add_failtest(\"failtest_sanity_check\")\n\nei_add_failtest(\"block_nonconst_ctor_on_const_xpr_0\")\nei_add_failtest(\"block_nonconst_ctor_on_const_xpr_1\")\nei_add_failtest(\"block_nonconst_ctor_on_const_xpr_2\")\nei_add_failtest(\"transpose_nonconst_ctor_on_const_xpr\")\nei_add_failtest(\"diagonal_nonconst_ctor_on_const_xpr\")\nei_add_failtest(\"cwiseunaryview_nonconst_ctor_on_const_xpr\")\nei_add_failtest(\"triangularview_nonconst_ctor_on_const_xpr\")\nei_add_failtest(\"selfadjointview_nonconst_ctor_on_const_xpr\")\n\nei_add_failtest(\"const_qualified_block_method_retval_0\")\nei_add_failtest(\"const_qualified_block_method_retval_1\")\nei_add_failtest(\"const_qualified_transpose_method_retval\")\nei_add_failtest(\"const_qualified_diagonal_method_retval\")\n\nei_add_failtest(\"map_nonconst_ctor_on_const_ptr_0\")\nei_add_failtest(\"map_nonconst_ctor_on_const_ptr_1\")\nei_add_failtest(\"map_nonconst_ctor_on_const_ptr_2\")\nei_add_failtest(\"map_nonconst_ctor_on_const_ptr_3\")\nei_add_failtest(\"map_nonconst_ctor_on_const_ptr_4\")\n\nei_add_failtest(\"map_on_const_type_actually_const_0\")\nei_add_failtest(\"map_on_const_type_actually_const_1\")\nei_add_failtest(\"block_on_const_type_actually_const_0\")\nei_add_failtest(\"block_on_const_type_actually_const_1\")\nei_add_failtest(\"transpose_on_const_type_actually_const\")\nei_add_failtest(\"diagonal_on_const_type_actually_const\")\nei_add_failtest(\"cwiseunaryview_on_const_type_actually_const\")\nei_add_failtest(\"triangularview_on_const_type_actually_const\")\nei_add_failtest(\"selfadjointview_on_const_type_actually_const\")\n\nei_add_failtest(\"ref_1\")\nei_add_failtest(\"ref_2\")\nei_add_failtest(\"ref_3\")\nei_add_failtest(\"ref_4\")\nei_add_failtest(\"ref_5\")\n\nei_add_failtest(\"swap_1\")\nei_add_failtest(\"swap_2\")\n\nei_add_failtest(\"ternary_1\")\nei_add_failtest(\"ternary_2\")\n\nei_add_failtest(\"sparse_ref_1\")\nei_add_failtest(\"sparse_ref_2\")\nei_add_failtest(\"sparse_ref_3\")\nei_add_failtest(\"sparse_ref_4\")\nei_add_failtest(\"sparse_ref_5\")\n\nei_add_failtest(\"sparse_storage_mismatch\")\n\nei_add_failtest(\"partialpivlu_int\")\nei_add_failtest(\"fullpivlu_int\")\nei_add_failtest(\"llt_int\")\nei_add_failtest(\"ldlt_int\")\nei_add_failtest(\"qr_int\")\nei_add_failtest(\"colpivqr_int\")\nei_add_failtest(\"fullpivqr_int\")\nei_add_failtest(\"jacobisvd_int\")\nei_add_failtest(\"bdcsvd_int\")\nei_add_failtest(\"eigensolver_int\")\nei_add_failtest(\"eigensolver_cplx\")\nei_add_failtest(\"initializer_list_1\")\nei_add_failtest(\"initializer_list_2\")\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/bdcsvd_int.cpp",
    "content": "#include \"../Eigen/SVD\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR int\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  BDCSVD<Matrix<SCALAR,Dynamic,Dynamic> > qr(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/block_nonconst_ctor_on_const_xpr_0.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    Block<Matrix3d,3,3> b(m,0,0);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/block_nonconst_ctor_on_const_xpr_1.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    Block<Matrix3d> b(m,0,0,3,3);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/block_nonconst_ctor_on_const_xpr_2.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    // row/column constructor\n    Block<Matrix3d,3,1> b(m,0);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/block_on_const_type_actually_const_0.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(){\n    Matrix3f m;\n    Block<CV_QUALIFIER Matrix3f>(m, 0, 0, 3, 3).coeffRef(0, 0) = 1.0f;\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/block_on_const_type_actually_const_1.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(){\n    MatrixXf m;\n    Block<CV_QUALIFIER MatrixXf, 3, 3>(m, 0, 0).coeffRef(0, 0) = 1.0f;\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/colpivqr_int.cpp",
    "content": "#include \"../Eigen/QR\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR int\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  ColPivHouseholderQR<Matrix<SCALAR,Dynamic,Dynamic> > qr(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/const_qualified_block_method_retval_0.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    Block<Matrix3d,3,3> b(m.block<3,3>(0,0));\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/const_qualified_block_method_retval_1.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    Block<Matrix3d> b(m.block(0,0,3,3));\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/const_qualified_diagonal_method_retval.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    Diagonal<Matrix3d> b(m.diagonal());\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/const_qualified_transpose_method_retval.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    Transpose<Matrix3d> b(m.transpose());\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/cwiseunaryview_nonconst_ctor_on_const_xpr.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    CwiseUnaryView<internal::scalar_real_ref_op<double>,Matrix3d> t(m);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/cwiseunaryview_on_const_type_actually_const.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(){\n    MatrixXf m;\n    CwiseUnaryView<internal::scalar_real_ref_op<double>,CV_QUALIFIER MatrixXf>(m).coeffRef(0, 0) = 1.0f;\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/diagonal_nonconst_ctor_on_const_xpr.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    Diagonal<Matrix3d> d(m);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/diagonal_on_const_type_actually_const.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(){\n    MatrixXf m;\n    Diagonal<CV_QUALIFIER MatrixXf>(m).coeffRef(0) = 1.0f;\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/eigensolver_cplx.cpp",
    "content": "#include \"../Eigen/Eigenvalues\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR std::complex<double>\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  EigenSolver<Matrix<SCALAR,Dynamic,Dynamic> > eig(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/eigensolver_int.cpp",
    "content": "#include \"../Eigen/Eigenvalues\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR int\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  EigenSolver<Matrix<SCALAR,Dynamic,Dynamic> > eig(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/failtest_sanity_check.cpp",
    "content": "#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\nThis is just some text that won't compile as a C++ file, as a basic sanity check for failtest.\n#else\nint main() {}\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/fullpivlu_int.cpp",
    "content": "#include \"../Eigen/LU\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR int\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  FullPivLU<Matrix<SCALAR,Dynamic,Dynamic> > lu(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/fullpivqr_int.cpp",
    "content": "#include \"../Eigen/QR\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR int\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  FullPivHouseholderQR<Matrix<SCALAR,Dynamic,Dynamic> > qr(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/initializer_list_1.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define ROWS Dynamic\n#else\n#define ROWS 3\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  Matrix<int, ROWS, 1> {1, 2, 3};\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/initializer_list_2.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define ROWS Dynamic\n#define COLS Dynamic\n#else\n#define ROWS 3\n#define COLS 1\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  Matrix<int, ROWS, COLS> {1, 2, 3};\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/jacobisvd_int.cpp",
    "content": "#include \"../Eigen/SVD\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR int\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  JacobiSVD<Matrix<SCALAR,Dynamic,Dynamic> > qr(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/ldlt_int.cpp",
    "content": "#include \"../Eigen/Cholesky\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR int\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  LDLT<Matrix<SCALAR,Dynamic,Dynamic> > ldlt(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/llt_int.cpp",
    "content": "#include \"../Eigen/Cholesky\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR int\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  LLT<Matrix<SCALAR,Dynamic,Dynamic> > llt(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/map_nonconst_ctor_on_const_ptr_0.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER float *ptr){\n    Map<Matrix3f> m(ptr);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/map_nonconst_ctor_on_const_ptr_1.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER float *ptr, DenseIndex size){\n    Map<ArrayXf> m(ptr, size);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/map_nonconst_ctor_on_const_ptr_2.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER float *ptr, DenseIndex rows, DenseIndex cols){\n    Map<MatrixXf> m(ptr, rows, cols);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/map_nonconst_ctor_on_const_ptr_3.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER float *ptr, DenseIndex rows, DenseIndex cols){\n    Map<MatrixXf, Aligned, InnerStride<2> > m(ptr, rows, cols, InnerStride<2>());\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/map_nonconst_ctor_on_const_ptr_4.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER\n#else\n#define CV_QUALIFIER const\n#endif\n\nusing namespace Eigen;\n\nvoid foo(const float *ptr, DenseIndex rows, DenseIndex cols){\n    Map<CV_QUALIFIER MatrixXf, Unaligned, OuterStride<> > m(ptr, rows, cols, OuterStride<>(2));\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/map_on_const_type_actually_const_0.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(float *ptr){\n    Map<CV_QUALIFIER MatrixXf>(ptr, 1, 1).coeffRef(0,0) = 1.0f;\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/map_on_const_type_actually_const_1.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(float *ptr){\n    Map<CV_QUALIFIER Vector3f>(ptr).coeffRef(0) = 1.0f;\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/partialpivlu_int.cpp",
    "content": "#include \"../Eigen/LU\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR int\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  PartialPivLU<Matrix<SCALAR,Dynamic,Dynamic> > lu(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/qr_int.cpp",
    "content": "#include \"../Eigen/QR\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR int\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  HouseholderQR<Matrix<SCALAR,Dynamic,Dynamic> > qr(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/ref_1.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid call_ref(Ref<VectorXf> a) { }\n\nint main()\n{\n  VectorXf a(10);\n  CV_QUALIFIER VectorXf& ac(a);\n  call_ref(ac);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/ref_2.cpp",
    "content": "#include \"../Eigen/Core\"\n\nusing namespace Eigen;\n\nvoid call_ref(Ref<VectorXf> a) { }\n\nint main()\n{\n  MatrixXf A(10,10);\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n  call_ref(A.row(3));\n#else\n  call_ref(A.col(3));\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/ref_3.cpp",
    "content": "#include \"../Eigen/Core\"\n\nusing namespace Eigen;\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\nvoid call_ref(Ref<VectorXf> a) { }\n#else\nvoid call_ref(const Ref<const VectorXf> &a) { }\n#endif\n\nint main()\n{\n  VectorXf a(10);\n  call_ref(a+a);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/ref_4.cpp",
    "content": "#include \"../Eigen/Core\"\n\nusing namespace Eigen;\n\nvoid call_ref(Ref<MatrixXf,0,OuterStride<> > a) {}\n\nint main()\n{\n  MatrixXf A(10,10);\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n  call_ref(A.transpose());\n#else\n  call_ref(A);\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/ref_5.cpp",
    "content": "#include \"../Eigen/Core\"\n\nusing namespace Eigen;\n\nvoid call_ref(Ref<VectorXf> a) { }\n\nint main()\n{\n  VectorXf a(10);\n  DenseBase<VectorXf> &ac(a);\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n  call_ref(ac);\n#else\n  call_ref(ac.derived());\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/selfadjointview_nonconst_ctor_on_const_xpr.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    SelfAdjointView<Matrix3d,Upper> t(m);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/selfadjointview_on_const_type_actually_const.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(){\n    MatrixXf m;\n    SelfAdjointView<CV_QUALIFIER MatrixXf,Upper>(m).coeffRef(0, 0) = 1.0f;\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/sparse_ref_1.cpp",
    "content": "#include \"../Eigen/Sparse\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid call_ref(Ref<SparseMatrix<float> > a) { }\n\nint main()\n{\n  SparseMatrix<float> a(10,10);\n  CV_QUALIFIER SparseMatrix<float>& ac(a);\n  call_ref(ac);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/sparse_ref_2.cpp",
    "content": "#include \"../Eigen/Sparse\"\n\nusing namespace Eigen;\n\nvoid call_ref(Ref<SparseMatrix<float> > a) { }\n\nint main()\n{\n  SparseMatrix<float> A(10,10);\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n  call_ref(A.row(3));\n#else\n  call_ref(A.col(3));\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/sparse_ref_3.cpp",
    "content": "#include \"../Eigen/Sparse\"\n\nusing namespace Eigen;\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\nvoid call_ref(Ref<SparseMatrix<float> > a) { }\n#else\nvoid call_ref(const Ref<const SparseMatrix<float> > &a) { }\n#endif\n\nint main()\n{\n  SparseMatrix<float> a(10,10);\n  call_ref(a+a);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/sparse_ref_4.cpp",
    "content": "#include \"../Eigen/Sparse\"\n\nusing namespace Eigen;\n\nvoid call_ref(Ref<SparseMatrix<float> > a) {}\n\nint main()\n{\n  SparseMatrix<float> A(10,10);\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n  call_ref(A.transpose());\n#else\n  call_ref(A);\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/sparse_ref_5.cpp",
    "content": "#include \"../Eigen/Sparse\"\n\nusing namespace Eigen;\n\nvoid call_ref(Ref<SparseMatrix<float> > a) { }\n\nint main()\n{\n  SparseMatrix<float> a(10,10);\n  SparseMatrixBase<SparseMatrix<float> > &ac(a);\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n  call_ref(ac);\n#else\n  call_ref(ac.derived());\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/sparse_storage_mismatch.cpp",
    "content": "#include \"../Eigen/Sparse\"\nusing namespace Eigen;\n\ntypedef SparseMatrix<double,ColMajor> Mat1;\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\ntypedef SparseMatrix<double,RowMajor> Mat2;\n#else\ntypedef SparseMatrix<double,ColMajor> Mat2;\n#endif\n\nint main()\n{\n  Mat1 a(10,10);\n  Mat2 b(10,10);\n  a += b;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/swap_1.cpp",
    "content": "#include \"../Eigen/Core\"\n\nusing namespace Eigen;\n\nint main()\n{\n  VectorXf a(10), b(10);\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n  const DenseBase<VectorXf> &ac(a);\n#else\n  DenseBase<VectorXf> &ac(a);\n#endif\n  b.swap(ac);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/swap_2.cpp",
    "content": "#include \"../Eigen/Core\"\n\nusing namespace Eigen;\n\nint main()\n{\n  VectorXf a(10), b(10);\n  VectorXf const &ac(a);\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n  b.swap(ac);\n#else\n  b.swap(ac.const_cast_derived());\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/ternary_1.cpp",
    "content": "#include \"../Eigen/Core\"\n\nusing namespace Eigen;\n\nint main(int argc,char **)\n{\n  VectorXf a(10), b(10);\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n  b = argc>1 ? 2*a : -a;\n#else\n  b = argc>1 ? 2*a : VectorXf(-a);\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/ternary_2.cpp",
    "content": "#include \"../Eigen/Core\"\n\nusing namespace Eigen;\n\nint main(int argc,char **)\n{\n  VectorXf a(10), b(10);\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n  b = argc>1 ? 2*a : a+a;\n#else\n  b = argc>1 ? VectorXf(2*a) : VectorXf(a+a);\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/transpose_nonconst_ctor_on_const_xpr.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    Transpose<Matrix3d> t(m);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/transpose_on_const_type_actually_const.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(){\n    MatrixXf m;\n    Transpose<CV_QUALIFIER MatrixXf>(m).coeffRef(0, 0) = 1.0f;\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/triangularview_nonconst_ctor_on_const_xpr.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n  TriangularView<Matrix3d,Upper> t(m);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/failtest/triangularview_on_const_type_actually_const.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(){\n    MatrixXf m;\n    TriangularView<CV_QUALIFIER MatrixXf,Upper>(m).coeffRef(0, 0) = 1.0f;\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/CMakeLists.txt",
    "content": "project(EigenLapack CXX)\n\ninclude(CheckLanguage)\ncheck_language(Fortran)\nif(CMAKE_Fortran_COMPILER)\n  enable_language(Fortran)\n  if(\"${CMAKE_Fortran_COMPILER_ID}\" STREQUAL \"GNU\")\n    if (\"${CMAKE_Fortran_COMPILER_VERSION}\" VERSION_GREATER_EQUAL 10.0)\n      # We use an old version of LAPACK with argument type mismatches.\n      # Allow them to compile anyway with newer GNU versions.\n      set(CMAKE_Fortran_FLAGS  \"${CMAKE_Fortran_FLAGS} -fallow-argument-mismatch\")\n    endif()\n  endif()\n  set(EIGEN_Fortran_COMPILER_WORKS ON)\nelse()\n  set(EIGEN_Fortran_COMPILER_WORKS OFF)\nendif()\n\nadd_custom_target(lapack)\ninclude_directories(../blas)\n\nset(EigenLapack_SRCS\nsingle.cpp double.cpp complex_single.cpp complex_double.cpp ../blas/xerbla.cpp\n)\n\nif(EIGEN_Fortran_COMPILER_WORKS)\n\nset(EigenLapack_SRCS  ${EigenLapack_SRCS}\n  slarft.f  dlarft.f  clarft.f  zlarft.f\n  slarfb.f  dlarfb.f  clarfb.f  zlarfb.f\n  slarfg.f  dlarfg.f  clarfg.f  zlarfg.f\n  slarf.f   dlarf.f   clarf.f   zlarf.f\n  sladiv.f  dladiv.f  cladiv.f  zladiv.f\n  ilaslr.f  iladlr.f  ilaclr.f  ilazlr.f\n  ilaslc.f  iladlc.f  ilaclc.f  ilazlc.f\n  dlapy2.f  dlapy3.f  slapy2.f  slapy3.f\n  clacgv.f  zlacgv.f\n  slamch.f  dlamch.f\n  second_NONE.f dsecnd_NONE.f\n)\n\noption(EIGEN_ENABLE_LAPACK_TESTS OFF \"Enable the Lapack unit tests\")\n\nif(EIGEN_ENABLE_LAPACK_TESTS)\n\n  get_filename_component(eigen_full_path_to_reference_lapack \"./reference/\" ABSOLUTE)\n  if(NOT EXISTS ${eigen_full_path_to_reference_lapack})\n    # Download lapack and install sources and testing at the right place\n    message(STATUS \"Download lapack_addons_3.4.1.tgz...\")\n    \n    file(DOWNLOAD \"http://downloads.tuxfamily.org/eigen/lapack_addons_3.4.1.tgz\"\n                  \"${CMAKE_CURRENT_SOURCE_DIR}/lapack_addons_3.4.1.tgz\"\n                  INACTIVITY_TIMEOUT 15\n                  TIMEOUT 240\n                  STATUS download_status\n                  EXPECTED_MD5 ab5742640617e3221a873aba44bbdc93\n                  SHOW_PROGRESS)\n                  \n    message(STATUS ${download_status})\n    list(GET download_status 0 download_status_num)\n    set(download_status_num 0)\n    if(download_status_num EQUAL 0)\n      message(STATUS \"Setup lapack reference and lapack unit tests\")\n      execute_process(COMMAND tar xzf  \"lapack_addons_3.4.1.tgz\" WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR})\n    else()\n      message(STATUS \"Download of lapack_addons_3.4.1.tgz failed, LAPACK unit tests won't be enabled\")\n      set(EIGEN_ENABLE_LAPACK_TESTS false)\n    endif()\n                  \n  endif()\n  \n  get_filename_component(eigen_full_path_to_reference_lapack \"./reference/\" ABSOLUTE)\n  if(EXISTS ${eigen_full_path_to_reference_lapack})\n    set(EigenLapack_funcfilenames\n        ssyev.f   dsyev.f   csyev.f   zsyev.f\n        spotrf.f  dpotrf.f  cpotrf.f  zpotrf.f\n        spotrs.f  dpotrs.f  cpotrs.f  zpotrs.f\n        sgetrf.f  dgetrf.f  cgetrf.f  zgetrf.f\n        sgetrs.f  dgetrs.f  cgetrs.f  zgetrs.f)\n    \n    file(GLOB ReferenceLapack_SRCS0 RELATIVE ${CMAKE_CURRENT_SOURCE_DIR} \"reference/*.f\")\n    foreach(filename1 IN LISTS ReferenceLapack_SRCS0)\n      string(REPLACE \"reference/\" \"\" filename ${filename1})\n      list(FIND EigenLapack_SRCS ${filename} id1)\n      list(FIND EigenLapack_funcfilenames ${filename} id2)\n      if((id1 EQUAL -1) AND (id2 EQUAL -1))\n        set(ReferenceLapack_SRCS ${ReferenceLapack_SRCS} reference/${filename})\n      endif()\n    endforeach()\n  endif()\n  \n  \nendif()\n\nendif()\n\nset(EIGEN_LAPACK_TARGETS \"\")\n\nadd_library(eigen_lapack_static ${EigenLapack_SRCS} ${ReferenceLapack_SRCS})\nlist(APPEND EIGEN_LAPACK_TARGETS eigen_lapack_static)\n\nif (EIGEN_BUILD_SHARED_LIBS)\n  add_library(eigen_lapack SHARED ${EigenLapack_SRCS})\n  list(APPEND EIGEN_LAPACK_TARGETS eigen_lapack)\n  target_link_libraries(eigen_lapack  eigen_blas)\nendif()\n\nforeach(target IN LISTS EIGEN_LAPACK_TARGETS)\n  if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO)\n    target_link_libraries(${target} ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO})\n  endif()\n  add_dependencies(lapack ${target})\n  install(TARGETS ${target}\n          RUNTIME DESTINATION bin\n          LIBRARY DESTINATION lib\n          ARCHIVE DESTINATION lib)\nendforeach()\n\n\nget_filename_component(eigen_full_path_to_testing_lapack \"./testing/\" ABSOLUTE)\nif(EXISTS ${eigen_full_path_to_testing_lapack})\n  \n  # The following comes from lapack/TESTING/CMakeLists.txt\n  # Get Python\n  find_package(PythonInterp)\n  message(STATUS \"Looking for Python found - ${PYTHONINTERP_FOUND}\")\n  if (PYTHONINTERP_FOUND)\n    message(STATUS \"Using Python version ${PYTHON_VERSION_STRING}\")\n  endif()\n\n  set(LAPACK_SOURCE_DIR ${CMAKE_CURRENT_SOURCE_DIR})\n  set(LAPACK_BINARY_DIR ${CMAKE_CURRENT_BINARY_DIR})\n  set(BUILD_SINGLE      true)\n  set(BUILD_DOUBLE      true)\n  set(BUILD_COMPLEX     true)\n  set(BUILD_COMPLEX16E  true)\n  \n  if(MSVC_VERSION)\n#  string(REPLACE \"/STACK:10000000\" \"/STACK:900000000000000000\"\n#    CMAKE_EXE_LINKER_FLAGS \"${CMAKE_EXE_LINKER_FLAGS}\")\n  string(REGEX REPLACE \"(.*)/STACK:(.*) (.*)\" \"\\\\1/STACK:900000000000000000 \\\\3\"\n    CMAKE_EXE_LINKER_FLAGS \"${CMAKE_EXE_LINKER_FLAGS}\")\n  endif()\n  file(MAKE_DIRECTORY \"${LAPACK_BINARY_DIR}/TESTING\")\n  add_subdirectory(testing/MATGEN)\n  add_subdirectory(testing/LIN)\n  add_subdirectory(testing/EIG)\n  macro(add_lapack_test output input target)\n    set(TEST_INPUT \"${LAPACK_SOURCE_DIR}/testing/${input}\")\n    set(TEST_OUTPUT \"${LAPACK_BINARY_DIR}/TESTING/${output}\")\n    string(REPLACE \".\" \"_\" input_name ${input})\n    set(testName \"${target}_${input_name}\")\n    if(EXISTS \"${TEST_INPUT}\")\n      add_dependencies(buildtests ${target})\n      add_test(NAME LAPACK-${testName}\n        COMMAND \"${CMAKE_COMMAND}\"\n        -DTEST=$<TARGET_FILE:${target}>\n        -DINPUT=${TEST_INPUT} \n        -DOUTPUT=${TEST_OUTPUT} \n        -DINTDIR=${CMAKE_CFG_INTDIR}\n        -P \"${LAPACK_SOURCE_DIR}/testing/runtest.cmake\")\n    endif()\n  endmacro()\n\n  if (BUILD_SINGLE)\n  add_lapack_test(stest.out stest.in xlintsts)\n  #\n  # ======== SINGLE RFP LIN TESTS ========================\n  add_lapack_test(stest_rfp.out stest_rfp.in xlintstrfs)\n  #\n  #\n  # ======== SINGLE EIG TESTS ===========================\n  #\n\n  add_lapack_test(snep.out nep.in xeigtsts)\n\n\n  add_lapack_test(ssep.out sep.in xeigtsts)\n\n\n  add_lapack_test(ssvd.out svd.in xeigtsts)\n\n\n  add_lapack_test(sec.out sec.in xeigtsts)\n\n\n  add_lapack_test(sed.out sed.in xeigtsts)\n\n\n  add_lapack_test(sgg.out sgg.in xeigtsts)\n\n\n  add_lapack_test(sgd.out sgd.in xeigtsts)\n\n\n  add_lapack_test(ssb.out ssb.in xeigtsts)\n\n\n  add_lapack_test(ssg.out ssg.in xeigtsts)\n\n\n  add_lapack_test(sbal.out sbal.in xeigtsts)\n\n\n  add_lapack_test(sbak.out sbak.in xeigtsts)\n\n\n  add_lapack_test(sgbal.out sgbal.in xeigtsts)\n\n\n  add_lapack_test(sgbak.out sgbak.in xeigtsts)\n\n\n  add_lapack_test(sbb.out sbb.in xeigtsts)\n\n\n  add_lapack_test(sglm.out glm.in xeigtsts)\n\n\n  add_lapack_test(sgqr.out gqr.in xeigtsts)\n\n\n  add_lapack_test(sgsv.out gsv.in xeigtsts)\n\n\n  add_lapack_test(scsd.out csd.in xeigtsts)\n\n\n  add_lapack_test(slse.out lse.in xeigtsts)\n  endif()\n\n  if (BUILD_DOUBLE)\n  #\n  # ======== DOUBLE LIN TESTS ===========================\n  add_lapack_test(dtest.out dtest.in xlintstd)\n  #\n  # ======== DOUBLE RFP LIN TESTS ========================\n  add_lapack_test(dtest_rfp.out dtest_rfp.in xlintstrfd)\n  #\n  # ======== DOUBLE EIG TESTS ===========================\n\n  add_lapack_test(dnep.out nep.in xeigtstd)\n\n\n  add_lapack_test(dsep.out sep.in xeigtstd)\n\n\n  add_lapack_test(dsvd.out svd.in xeigtstd)\n\n\n  add_lapack_test(dec.out dec.in xeigtstd)\n\n\n  add_lapack_test(ded.out ded.in xeigtstd)\n\n\n  add_lapack_test(dgg.out dgg.in xeigtstd)\n\n\n  add_lapack_test(dgd.out dgd.in xeigtstd)\n\n\n  add_lapack_test(dsb.out dsb.in xeigtstd)\n\n\n  add_lapack_test(dsg.out dsg.in xeigtstd)\n\n\n  add_lapack_test(dbal.out dbal.in xeigtstd)\n\n\n  add_lapack_test(dbak.out dbak.in xeigtstd)\n\n\n  add_lapack_test(dgbal.out dgbal.in xeigtstd)\n\n\n  add_lapack_test(dgbak.out dgbak.in xeigtstd)\n\n\n  add_lapack_test(dbb.out dbb.in xeigtstd)\n\n\n  add_lapack_test(dglm.out glm.in xeigtstd)\n\n\n  add_lapack_test(dgqr.out gqr.in xeigtstd)\n\n\n  add_lapack_test(dgsv.out gsv.in xeigtstd)\n\n\n  add_lapack_test(dcsd.out csd.in xeigtstd)\n\n\n  add_lapack_test(dlse.out lse.in xeigtstd)\n  endif()\n\n  if (BUILD_COMPLEX)\n  add_lapack_test(ctest.out ctest.in xlintstc)\n  #\n  # ======== COMPLEX RFP LIN TESTS ========================\n  add_lapack_test(ctest_rfp.out ctest_rfp.in xlintstrfc)\n  #\n  # ======== COMPLEX EIG TESTS ===========================\n\n  add_lapack_test(cnep.out nep.in xeigtstc)\n\n\n  add_lapack_test(csep.out sep.in xeigtstc)\n\n\n  add_lapack_test(csvd.out svd.in xeigtstc)\n\n\n  add_lapack_test(cec.out cec.in xeigtstc)\n\n\n  add_lapack_test(ced.out ced.in xeigtstc)\n\n\n  add_lapack_test(cgg.out cgg.in xeigtstc)\n\n\n  add_lapack_test(cgd.out cgd.in xeigtstc)\n\n\n  add_lapack_test(csb.out csb.in xeigtstc)\n\n\n  add_lapack_test(csg.out csg.in xeigtstc)\n\n\n  add_lapack_test(cbal.out cbal.in xeigtstc)\n\n\n  add_lapack_test(cbak.out cbak.in xeigtstc)\n\n\n  add_lapack_test(cgbal.out cgbal.in xeigtstc)\n\n\n  add_lapack_test(cgbak.out cgbak.in xeigtstc)\n\n\n  add_lapack_test(cbb.out cbb.in xeigtstc)\n\n\n  add_lapack_test(cglm.out glm.in xeigtstc)\n\n\n  add_lapack_test(cgqr.out gqr.in xeigtstc)\n\n\n  add_lapack_test(cgsv.out gsv.in xeigtstc)\n\n\n  add_lapack_test(ccsd.out csd.in xeigtstc)\n\n\n  add_lapack_test(clse.out lse.in xeigtstc)\n  endif()\n\n  if (BUILD_COMPLEX16)\n  #\n  # ======== COMPLEX16 LIN TESTS ========================\n  add_lapack_test(ztest.out ztest.in xlintstz)\n  #\n  # ======== COMPLEX16 RFP LIN TESTS ========================\n  add_lapack_test(ztest_rfp.out ztest_rfp.in xlintstrfz)\n  #\n  # ======== COMPLEX16 EIG TESTS ===========================\n\n  add_lapack_test(znep.out nep.in xeigtstz)\n\n\n  add_lapack_test(zsep.out sep.in xeigtstz)\n\n\n  add_lapack_test(zsvd.out svd.in xeigtstz)\n\n\n  add_lapack_test(zec.out zec.in xeigtstz)\n\n\n  add_lapack_test(zed.out zed.in xeigtstz)\n\n\n  add_lapack_test(zgg.out zgg.in xeigtstz)\n\n\n  add_lapack_test(zgd.out zgd.in xeigtstz)\n\n\n  add_lapack_test(zsb.out zsb.in xeigtstz)\n\n\n  add_lapack_test(zsg.out zsg.in xeigtstz)\n\n\n  add_lapack_test(zbal.out zbal.in xeigtstz)\n\n\n  add_lapack_test(zbak.out zbak.in xeigtstz)\n\n\n  add_lapack_test(zgbal.out zgbal.in xeigtstz)\n\n\n  add_lapack_test(zgbak.out zgbak.in xeigtstz)\n\n\n  add_lapack_test(zbb.out zbb.in xeigtstz)\n\n\n  add_lapack_test(zglm.out glm.in xeigtstz)\n\n\n  add_lapack_test(zgqr.out gqr.in xeigtstz)\n\n\n  add_lapack_test(zgsv.out gsv.in xeigtstz)\n\n\n  add_lapack_test(zcsd.out csd.in xeigtstz)\n\n\n  add_lapack_test(zlse.out lse.in xeigtstz)\n  endif()\n\n\n  if (BUILD_SIMPLE)\n      if (BUILD_DOUBLE)\n  #\n  # ======== SINGLE-DOUBLE PROTO LIN TESTS ==============\n          add_lapack_test(dstest.out dstest.in xlintstds)\n      endif()\n  endif()\n\n\n  if (BUILD_COMPLEX)\n      if (BUILD_COMPLEX16)\n  #\n  # ======== COMPLEX-COMPLEX16 LIN TESTS ========================\n          add_lapack_test(zctest.out zctest.in xlintstzc)\n      endif()\n  endif()\n\n  # ==============================================================================\n\n  execute_process(COMMAND ${CMAKE_COMMAND} -E copy ${LAPACK_SOURCE_DIR}/testing/lapack_testing.py ${LAPACK_BINARY_DIR})\n  add_test(\n    NAME LAPACK_Test_Summary\n    WORKING_DIRECTORY ${LAPACK_BINARY_DIR}\n    COMMAND ${PYTHON_EXECUTABLE} \"lapack_testing.py\"\n  )\n\nendif()\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/cholesky.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010-2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"lapack_common.h\"\n#include <Eigen/Cholesky>\n\n// POTRF computes the Cholesky factorization of a real symmetric positive definite matrix A.\nEIGEN_LAPACK_FUNC(potrf,(char* uplo, int *n, RealScalar *pa, int *lda, int *info))\n{\n  *info = 0;\n        if(UPLO(*uplo)==INVALID) *info = -1;\n  else  if(*n<0)                 *info = -2;\n  else  if(*lda<std::max(1,*n))  *info = -4;\n  if(*info!=0)\n  {\n    int e = -*info;\n    return xerbla_(SCALAR_SUFFIX_UP\"POTRF\", &e, 6);\n  }\n\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  MatrixType A(a,*n,*n,*lda);\n  int ret;\n  if(UPLO(*uplo)==UP) ret = int(internal::llt_inplace<Scalar, Upper>::blocked(A));\n  else                ret = int(internal::llt_inplace<Scalar, Lower>::blocked(A));\n\n  if(ret>=0)\n    *info = ret+1;\n  \n  return 0;\n}\n\n// POTRS solves a system of linear equations A*X = B with a symmetric\n// positive definite matrix A using the Cholesky factorization\n// A = U**T*U or A = L*L**T computed by DPOTRF.\nEIGEN_LAPACK_FUNC(potrs,(char* uplo, int *n, int *nrhs, RealScalar *pa, int *lda, RealScalar *pb, int *ldb, int *info))\n{\n  *info = 0;\n        if(UPLO(*uplo)==INVALID) *info = -1;\n  else  if(*n<0)                 *info = -2;\n  else  if(*nrhs<0)              *info = -3;\n  else  if(*lda<std::max(1,*n))  *info = -5;\n  else  if(*ldb<std::max(1,*n))  *info = -7;\n  if(*info!=0)\n  {\n    int e = -*info;\n    return xerbla_(SCALAR_SUFFIX_UP\"POTRS\", &e, 6);\n  }\n\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  Scalar* b = reinterpret_cast<Scalar*>(pb);\n  MatrixType A(a,*n,*n,*lda);\n  MatrixType B(b,*n,*nrhs,*ldb);\n\n  if(UPLO(*uplo)==UP)\n  {\n    A.triangularView<Upper>().adjoint().solveInPlace(B);\n    A.triangularView<Upper>().solveInPlace(B);\n  }\n  else\n  {\n    A.triangularView<Lower>().solveInPlace(B);\n    A.triangularView<Lower>().adjoint().solveInPlace(B);\n  }\n\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/clacgv.f",
    "content": "*> \\brief \\b CLACGV\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download CLACGV + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/clacgv.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/clacgv.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/clacgv.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE CLACGV( N, X, INCX )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            INCX, N\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX            X( * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> CLACGV conjugates a complex vector of length N.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The length of the vector X.  N >= 0.\n*> \\endverbatim\n*>\n*> \\param[in,out] X\n*> \\verbatim\n*>          X is COMPLEX array, dimension\n*>                         (1+(N-1)*abs(INCX))\n*>          On entry, the vector of length N to be conjugated.\n*>          On exit, X is overwritten with conjg(X).\n*> \\endverbatim\n*>\n*> \\param[in] INCX\n*> \\verbatim\n*>          INCX is INTEGER\n*>          The spacing between successive elements of X.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complexOTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE CLACGV( N, X, INCX )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      INTEGER            INCX, N\n*     ..\n*     .. Array Arguments ..\n      COMPLEX            X( * )\n*     ..\n*\n* =====================================================================\n*\n*     .. Local Scalars ..\n      INTEGER            I, IOFF\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          CONJG\n*     ..\n*     .. Executable Statements ..\n*\n      IF( INCX.EQ.1 ) THEN\n         DO 10 I = 1, N\n            X( I ) = CONJG( X( I ) )\n   10    CONTINUE\n      ELSE\n         IOFF = 1\n         IF( INCX.LT.0 )\n     $      IOFF = 1 - ( N-1 )*INCX\n         DO 20 I = 1, N\n            X( IOFF ) = CONJG( X( IOFF ) )\n            IOFF = IOFF + INCX\n   20    CONTINUE\n      END IF\n      RETURN\n*\n*     End of CLACGV\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/cladiv.f",
    "content": "*> \\brief \\b CLADIV\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download CLADIV + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/cladiv.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/cladiv.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/cladiv.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       COMPLEX FUNCTION CLADIV( X, Y )\n* \n*       .. Scalar Arguments ..\n*       COMPLEX            X, Y\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> CLADIV := X / Y, where X and Y are complex.  The computation of X / Y\n*> will not overflow on an intermediary step unless the results\n*> overflows.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] X\n*> \\verbatim\n*>          X is COMPLEX\n*> \\endverbatim\n*>\n*> \\param[in] Y\n*> \\verbatim\n*>          Y is COMPLEX\n*>          The complex scalars X and Y.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complexOTHERauxiliary\n*\n*  =====================================================================\n      COMPLEX FUNCTION CLADIV( X, Y )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      COMPLEX            X, Y\n*     ..\n*\n*  =====================================================================\n*\n*     .. Local Scalars ..\n      REAL               ZI, ZR\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           SLADIV\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          AIMAG, CMPLX, REAL\n*     ..\n*     .. Executable Statements ..\n*\n      CALL SLADIV( REAL( X ), AIMAG( X ), REAL( Y ), AIMAG( Y ), ZR,\n     $             ZI )\n      CLADIV = CMPLX( ZR, ZI )\n*\n      RETURN\n*\n*     End of CLADIV\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/clarf.f",
    "content": "*> \\brief \\b CLARF\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download CLARF + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/clarf.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/clarf.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/clarf.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE CLARF( SIDE, M, N, V, INCV, TAU, C, LDC, WORK )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          SIDE\n*       INTEGER            INCV, LDC, M, N\n*       COMPLEX            TAU\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX            C( LDC, * ), V( * ), WORK( * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> CLARF applies a complex elementary reflector H to a complex M-by-N\n*> matrix C, from either the left or the right. H is represented in the\n*> form\n*>\n*>       H = I - tau * v * v**H\n*>\n*> where tau is a complex scalar and v is a complex vector.\n*>\n*> If tau = 0, then H is taken to be the unit matrix.\n*>\n*> To apply H**H (the conjugate transpose of H), supply conjg(tau) instead\n*> tau.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] SIDE\n*> \\verbatim\n*>          SIDE is CHARACTER*1\n*>          = 'L': form  H * C\n*>          = 'R': form  C * H\n*> \\endverbatim\n*>\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is COMPLEX array, dimension\n*>                     (1 + (M-1)*abs(INCV)) if SIDE = 'L'\n*>                  or (1 + (N-1)*abs(INCV)) if SIDE = 'R'\n*>          The vector v in the representation of H. V is not used if\n*>          TAU = 0.\n*> \\endverbatim\n*>\n*> \\param[in] INCV\n*> \\verbatim\n*>          INCV is INTEGER\n*>          The increment between elements of v. INCV <> 0.\n*> \\endverbatim\n*>\n*> \\param[in] TAU\n*> \\verbatim\n*>          TAU is COMPLEX\n*>          The value tau in the representation of H.\n*> \\endverbatim\n*>\n*> \\param[in,out] C\n*> \\verbatim\n*>          C is COMPLEX array, dimension (LDC,N)\n*>          On entry, the M-by-N matrix C.\n*>          On exit, C is overwritten by the matrix H * C if SIDE = 'L',\n*>          or C * H if SIDE = 'R'.\n*> \\endverbatim\n*>\n*> \\param[in] LDC\n*> \\verbatim\n*>          LDC is INTEGER\n*>          The leading dimension of the array C. LDC >= max(1,M).\n*> \\endverbatim\n*>\n*> \\param[out] WORK\n*> \\verbatim\n*>          WORK is COMPLEX array, dimension\n*>                         (N) if SIDE = 'L'\n*>                      or (M) if SIDE = 'R'\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complexOTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE CLARF( SIDE, M, N, V, INCV, TAU, C, LDC, WORK )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      CHARACTER          SIDE\n      INTEGER            INCV, LDC, M, N\n      COMPLEX            TAU\n*     ..\n*     .. Array Arguments ..\n      COMPLEX            C( LDC, * ), V( * ), WORK( * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      COMPLEX            ONE, ZERO\n      PARAMETER          ( ONE = ( 1.0E+0, 0.0E+0 ),\n     $                   ZERO = ( 0.0E+0, 0.0E+0 ) )\n*     ..\n*     .. Local Scalars ..\n      LOGICAL            APPLYLEFT\n      INTEGER            I, LASTV, LASTC\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           CGEMV, CGERC\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      INTEGER            ILACLR, ILACLC\n      EXTERNAL           LSAME, ILACLR, ILACLC\n*     ..\n*     .. Executable Statements ..\n*\n      APPLYLEFT = LSAME( SIDE, 'L' )\n      LASTV = 0\n      LASTC = 0\n      IF( TAU.NE.ZERO ) THEN\n!     Set up variables for scanning V.  LASTV begins pointing to the end\n!     of V.\n         IF( APPLYLEFT ) THEN\n            LASTV = M\n         ELSE\n            LASTV = N\n         END IF\n         IF( INCV.GT.0 ) THEN\n            I = 1 + (LASTV-1) * INCV\n         ELSE\n            I = 1\n         END IF\n!     Look for the last non-zero row in V.\n         DO WHILE( LASTV.GT.0 .AND. V( I ).EQ.ZERO )\n            LASTV = LASTV - 1\n            I = I - INCV\n         END DO\n         IF( APPLYLEFT ) THEN\n!     Scan for the last non-zero column in C(1:lastv,:).\n            LASTC = ILACLC(LASTV, N, C, LDC)\n         ELSE\n!     Scan for the last non-zero row in C(:,1:lastv).\n            LASTC = ILACLR(M, LASTV, C, LDC)\n         END IF\n      END IF\n!     Note that lastc.eq.0 renders the BLAS operations null; no special\n!     case is needed at this level.\n      IF( APPLYLEFT ) THEN\n*\n*        Form  H * C\n*\n         IF( LASTV.GT.0 ) THEN\n*\n*           w(1:lastc,1) := C(1:lastv,1:lastc)**H * v(1:lastv,1)\n*\n            CALL CGEMV( 'Conjugate transpose', LASTV, LASTC, ONE,\n     $           C, LDC, V, INCV, ZERO, WORK, 1 )\n*\n*           C(1:lastv,1:lastc) := C(...) - v(1:lastv,1) * w(1:lastc,1)**H\n*\n            CALL CGERC( LASTV, LASTC, -TAU, V, INCV, WORK, 1, C, LDC )\n         END IF\n      ELSE\n*\n*        Form  C * H\n*\n         IF( LASTV.GT.0 ) THEN\n*\n*           w(1:lastc,1) := C(1:lastc,1:lastv) * v(1:lastv,1)\n*\n            CALL CGEMV( 'No transpose', LASTC, LASTV, ONE, C, LDC,\n     $           V, INCV, ZERO, WORK, 1 )\n*\n*           C(1:lastc,1:lastv) := C(...) - w(1:lastc,1) * v(1:lastv,1)**H\n*\n            CALL CGERC( LASTC, LASTV, -TAU, WORK, 1, V, INCV, C, LDC )\n         END IF\n      END IF\n      RETURN\n*\n*     End of CLARF\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/clarfb.f",
    "content": "*> \\brief \\b CLARFB\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download CLARFB + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/clarfb.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/clarfb.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/clarfb.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE CLARFB( SIDE, TRANS, DIRECT, STOREV, M, N, K, V, LDV,\n*                          T, LDT, C, LDC, WORK, LDWORK )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          DIRECT, SIDE, STOREV, TRANS\n*       INTEGER            K, LDC, LDT, LDV, LDWORK, M, N\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX            C( LDC, * ), T( LDT, * ), V( LDV, * ),\n*      $                   WORK( LDWORK, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> CLARFB applies a complex block reflector H or its transpose H**H to a\n*> complex M-by-N matrix C, from either the left or the right.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] SIDE\n*> \\verbatim\n*>          SIDE is CHARACTER*1\n*>          = 'L': apply H or H**H from the Left\n*>          = 'R': apply H or H**H from the Right\n*> \\endverbatim\n*>\n*> \\param[in] TRANS\n*> \\verbatim\n*>          TRANS is CHARACTER*1\n*>          = 'N': apply H (No transpose)\n*>          = 'C': apply H**H (Conjugate transpose)\n*> \\endverbatim\n*>\n*> \\param[in] DIRECT\n*> \\verbatim\n*>          DIRECT is CHARACTER*1\n*>          Indicates how H is formed from a product of elementary\n*>          reflectors\n*>          = 'F': H = H(1) H(2) . . . H(k) (Forward)\n*>          = 'B': H = H(k) . . . H(2) H(1) (Backward)\n*> \\endverbatim\n*>\n*> \\param[in] STOREV\n*> \\verbatim\n*>          STOREV is CHARACTER*1\n*>          Indicates how the vectors which define the elementary\n*>          reflectors are stored:\n*>          = 'C': Columnwise\n*>          = 'R': Rowwise\n*> \\endverbatim\n*>\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] K\n*> \\verbatim\n*>          K is INTEGER\n*>          The order of the matrix T (= the number of elementary\n*>          reflectors whose product defines the block reflector).\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is COMPLEX array, dimension\n*>                                (LDV,K) if STOREV = 'C'\n*>                                (LDV,M) if STOREV = 'R' and SIDE = 'L'\n*>                                (LDV,N) if STOREV = 'R' and SIDE = 'R'\n*>          The matrix V. See Further Details.\n*> \\endverbatim\n*>\n*> \\param[in] LDV\n*> \\verbatim\n*>          LDV is INTEGER\n*>          The leading dimension of the array V.\n*>          If STOREV = 'C' and SIDE = 'L', LDV >= max(1,M);\n*>          if STOREV = 'C' and SIDE = 'R', LDV >= max(1,N);\n*>          if STOREV = 'R', LDV >= K.\n*> \\endverbatim\n*>\n*> \\param[in] T\n*> \\verbatim\n*>          T is COMPLEX array, dimension (LDT,K)\n*>          The triangular K-by-K matrix T in the representation of the\n*>          block reflector.\n*> \\endverbatim\n*>\n*> \\param[in] LDT\n*> \\verbatim\n*>          LDT is INTEGER\n*>          The leading dimension of the array T. LDT >= K.\n*> \\endverbatim\n*>\n*> \\param[in,out] C\n*> \\verbatim\n*>          C is COMPLEX array, dimension (LDC,N)\n*>          On entry, the M-by-N matrix C.\n*>          On exit, C is overwritten by H*C or H**H*C or C*H or C*H**H.\n*> \\endverbatim\n*>\n*> \\param[in] LDC\n*> \\verbatim\n*>          LDC is INTEGER\n*>          The leading dimension of the array C. LDC >= max(1,M).\n*> \\endverbatim\n*>\n*> \\param[out] WORK\n*> \\verbatim\n*>          WORK is COMPLEX array, dimension (LDWORK,K)\n*> \\endverbatim\n*>\n*> \\param[in] LDWORK\n*> \\verbatim\n*>          LDWORK is INTEGER\n*>          The leading dimension of the array WORK.\n*>          If SIDE = 'L', LDWORK >= max(1,N);\n*>          if SIDE = 'R', LDWORK >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complexOTHERauxiliary\n*\n*> \\par Further Details:\n*  =====================\n*>\n*> \\verbatim\n*>\n*>  The shape of the matrix V and the storage of the vectors which define\n*>  the H(i) is best illustrated by the following example with n = 5 and\n*>  k = 3. The elements equal to 1 are not stored; the corresponding\n*>  array elements are modified but restored on exit. The rest of the\n*>  array is not used.\n*>\n*>  DIRECT = 'F' and STOREV = 'C':         DIRECT = 'F' and STOREV = 'R':\n*>\n*>               V = (  1       )                 V = (  1 v1 v1 v1 v1 )\n*>                   ( v1  1    )                     (     1 v2 v2 v2 )\n*>                   ( v1 v2  1 )                     (        1 v3 v3 )\n*>                   ( v1 v2 v3 )\n*>                   ( v1 v2 v3 )\n*>\n*>  DIRECT = 'B' and STOREV = 'C':         DIRECT = 'B' and STOREV = 'R':\n*>\n*>               V = ( v1 v2 v3 )                 V = ( v1 v1  1       )\n*>                   ( v1 v2 v3 )                     ( v2 v2 v2  1    )\n*>                   (  1 v2 v3 )                     ( v3 v3 v3 v3  1 )\n*>                   (     1 v3 )\n*>                   (        1 )\n*> \\endverbatim\n*>\n*  =====================================================================\n      SUBROUTINE CLARFB( SIDE, TRANS, DIRECT, STOREV, M, N, K, V, LDV,\n     $                   T, LDT, C, LDC, WORK, LDWORK )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      CHARACTER          DIRECT, SIDE, STOREV, TRANS\n      INTEGER            K, LDC, LDT, LDV, LDWORK, M, N\n*     ..\n*     .. Array Arguments ..\n      COMPLEX            C( LDC, * ), T( LDT, * ), V( LDV, * ),\n     $                   WORK( LDWORK, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      COMPLEX            ONE\n      PARAMETER          ( ONE = ( 1.0E+0, 0.0E+0 ) )\n*     ..\n*     .. Local Scalars ..\n      CHARACTER          TRANST\n      INTEGER            I, J, LASTV, LASTC\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      INTEGER            ILACLR, ILACLC\n      EXTERNAL           LSAME, ILACLR, ILACLC\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           CCOPY, CGEMM, CLACGV, CTRMM\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          CONJG\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick return if possible\n*\n      IF( M.LE.0 .OR. N.LE.0 )\n     $   RETURN\n*\n      IF( LSAME( TRANS, 'N' ) ) THEN\n         TRANST = 'C'\n      ELSE\n         TRANST = 'N'\n      END IF\n*\n      IF( LSAME( STOREV, 'C' ) ) THEN\n*\n         IF( LSAME( DIRECT, 'F' ) ) THEN\n*\n*           Let  V =  ( V1 )    (first K rows)\n*                     ( V2 )\n*           where  V1  is unit lower triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**H * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILACLR( M, K, V, LDV ) )\n               LASTC = ILACLC( LASTV, N, C, LDC )\n*\n*              W := C**H * V  =  (C1**H * V1 + C2**H * V2)  (stored in WORK)\n*\n*              W := C1**H\n*\n               DO 10 J = 1, K\n                  CALL CCOPY( LASTC, C( J, 1 ), LDC, WORK( 1, J ), 1 )\n                  CALL CLACGV( LASTC, WORK( 1, J ), 1 )\n   10          CONTINUE\n*\n*              W := W * V1\n*\n               CALL CTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2**H *V2\n*\n                  CALL CGEMM( 'Conjugate transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K, ONE, C( K+1, 1 ), LDC,\n     $                 V( K+1, 1 ), LDV, ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**H  or  W * T\n*\n               CALL CTRMM( 'Right', 'Upper', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V * W**H\n*\n               IF( M.GT.K ) THEN\n*\n*                 C2 := C2 - V2 * W**H\n*\n                  CALL CGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTV-K, LASTC, K, -ONE, V( K+1, 1 ), LDV,\n     $                 WORK, LDWORK, ONE, C( K+1, 1 ), LDC )\n               END IF\n*\n*              W := W * V1**H\n*\n               CALL CTRMM( 'Right', 'Lower', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W**H\n*\n               DO 30 J = 1, K\n                  DO 20 I = 1, LASTC\n                     C( J, I ) = C( J, I ) - CONJG( WORK( I, J ) )\n   20             CONTINUE\n   30          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**H  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILACLR( N, K, V, LDV ) )\n               LASTC = ILACLR( M, LASTV, C, LDC )\n*\n*              W := C * V  =  (C1*V1 + C2*V2)  (stored in WORK)\n*\n*              W := C1\n*\n               DO 40 J = 1, K\n                  CALL CCOPY( LASTC, C( 1, J ), 1, WORK( 1, J ), 1 )\n   40          CONTINUE\n*\n*              W := W * V1\n*\n               CALL CTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2 * V2\n*\n                  CALL CGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C( 1, K+1 ), LDC, V( K+1, 1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**H\n*\n               CALL CTRMM( 'Right', 'Upper', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V**H\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - W * V2**H\n*\n                  CALL CGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTC, LASTV-K, K,\n     $                 -ONE, WORK, LDWORK, V( K+1, 1 ), LDV,\n     $                 ONE, C( 1, K+1 ), LDC )\n               END IF\n*\n*              W := W * V1**H\n*\n               CALL CTRMM( 'Right', 'Lower', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 60 J = 1, K\n                  DO 50 I = 1, LASTC\n                     C( I, J ) = C( I, J ) - WORK( I, J )\n   50             CONTINUE\n   60          CONTINUE\n            END IF\n*\n         ELSE\n*\n*           Let  V =  ( V1 )\n*                     ( V2 )    (last K rows)\n*           where  V2  is unit upper triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**H * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILACLR( M, K, V, LDV ) )\n               LASTC = ILACLC( LASTV, N, C, LDC )\n*\n*              W := C**H * V  =  (C1**H * V1 + C2**H * V2)  (stored in WORK)\n*\n*              W := C2**H\n*\n               DO 70 J = 1, K\n                  CALL CCOPY( LASTC, C( LASTV-K+J, 1 ), LDC,\n     $                 WORK( 1, J ), 1 )\n                  CALL CLACGV( LASTC, WORK( 1, J ), 1 )\n   70          CONTINUE\n*\n*              W := W * V2\n*\n               CALL CTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1**H*V1\n*\n                  CALL CGEMM( 'Conjugate transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**H  or  W * T\n*\n               CALL CTRMM( 'Right', 'Lower', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V * W**H\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - V1 * W**H\n*\n                  CALL CGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTV-K, LASTC, K, -ONE, V, LDV, WORK, LDWORK,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2**H\n*\n               CALL CTRMM( 'Right', 'Upper', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W**H\n*\n               DO 90 J = 1, K\n                  DO 80 I = 1, LASTC\n                     C( LASTV-K+J, I ) = C( LASTV-K+J, I ) -\n     $                               CONJG( WORK( I, J ) )\n   80             CONTINUE\n   90          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**H  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILACLR( N, K, V, LDV ) )\n               LASTC = ILACLR( M, LASTV, C, LDC )\n*\n*              W := C * V  =  (C1*V1 + C2*V2)  (stored in WORK)\n*\n*              W := C2\n*\n               DO 100 J = 1, K\n                  CALL CCOPY( LASTC, C( 1, LASTV-K+J ), 1,\n     $                 WORK( 1, J ), 1 )\n  100          CONTINUE\n*\n*              W := W * V2\n*\n               CALL CTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1 * V1\n*\n                  CALL CGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C, LDC, V, LDV, ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**H\n*\n               CALL CTRMM( 'Right', 'Lower', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V**H\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - W * V1**H\n*\n                  CALL CGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTC, LASTV-K, K, -ONE, WORK, LDWORK, V, LDV,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2**H\n*\n               CALL CTRMM( 'Right', 'Upper', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W\n*\n               DO 120 J = 1, K\n                  DO 110 I = 1, LASTC\n                     C( I, LASTV-K+J ) = C( I, LASTV-K+J )\n     $                    - WORK( I, J )\n  110             CONTINUE\n  120          CONTINUE\n            END IF\n         END IF\n*\n      ELSE IF( LSAME( STOREV, 'R' ) ) THEN\n*\n         IF( LSAME( DIRECT, 'F' ) ) THEN\n*\n*           Let  V =  ( V1  V2 )    (V1: first K columns)\n*           where  V1  is unit upper triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**H * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILACLC( K, M, V, LDV ) )\n               LASTC = ILACLC( LASTV, N, C, LDC )\n*\n*              W := C**H * V**H  =  (C1**H * V1**H + C2**H * V2**H) (stored in WORK)\n*\n*              W := C1**H\n*\n               DO 130 J = 1, K\n                  CALL CCOPY( LASTC, C( J, 1 ), LDC, WORK( 1, J ), 1 )\n                  CALL CLACGV( LASTC, WORK( 1, J ), 1 )\n  130          CONTINUE\n*\n*              W := W * V1**H\n*\n               CALL CTRMM( 'Right', 'Upper', 'Conjugate transpose',\n     $                     'Unit', LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2**H*V2**H\n*\n                  CALL CGEMM( 'Conjugate transpose',\n     $                 'Conjugate transpose', LASTC, K, LASTV-K,\n     $                 ONE, C( K+1, 1 ), LDC, V( 1, K+1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**H  or  W * T\n*\n               CALL CTRMM( 'Right', 'Upper', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V**H * W**H\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - V2**H * W**H\n*\n                  CALL CGEMM( 'Conjugate transpose',\n     $                 'Conjugate transpose', LASTV-K, LASTC, K,\n     $                 -ONE, V( 1, K+1 ), LDV, WORK, LDWORK,\n     $                 ONE, C( K+1, 1 ), LDC )\n               END IF\n*\n*              W := W * V1\n*\n               CALL CTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W**H\n*\n               DO 150 J = 1, K\n                  DO 140 I = 1, LASTC\n                     C( J, I ) = C( J, I ) - CONJG( WORK( I, J ) )\n  140             CONTINUE\n  150          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**H  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILACLC( K, N, V, LDV ) )\n               LASTC = ILACLR( M, LASTV, C, LDC )\n*\n*              W := C * V**H  =  (C1*V1**H + C2*V2**H)  (stored in WORK)\n*\n*              W := C1\n*\n               DO 160 J = 1, K\n                  CALL CCOPY( LASTC, C( 1, J ), 1, WORK( 1, J ), 1 )\n  160          CONTINUE\n*\n*              W := W * V1**H\n*\n               CALL CTRMM( 'Right', 'Upper', 'Conjugate transpose',\n     $                     'Unit', LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2 * V2**H\n*\n                  CALL CGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTC, K, LASTV-K, ONE, C( 1, K+1 ), LDC,\n     $                 V( 1, K+1 ), LDV, ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**H\n*\n               CALL CTRMM( 'Right', 'Upper', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - W * V2\n*\n                  CALL CGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, LASTV-K, K,\n     $                 -ONE, WORK, LDWORK, V( 1, K+1 ), LDV,\n     $                 ONE, C( 1, K+1 ), LDC )\n               END IF\n*\n*              W := W * V1\n*\n               CALL CTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 180 J = 1, K\n                  DO 170 I = 1, LASTC\n                     C( I, J ) = C( I, J ) - WORK( I, J )\n  170             CONTINUE\n  180          CONTINUE\n*\n            END IF\n*\n         ELSE\n*\n*           Let  V =  ( V1  V2 )    (V2: last K columns)\n*           where  V2  is unit lower triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**H * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILACLC( K, M, V, LDV ) )\n               LASTC = ILACLC( LASTV, N, C, LDC )\n*\n*              W := C**H * V**H  =  (C1**H * V1**H + C2**H * V2**H) (stored in WORK)\n*\n*              W := C2**H\n*\n               DO 190 J = 1, K\n                  CALL CCOPY( LASTC, C( LASTV-K+J, 1 ), LDC,\n     $                 WORK( 1, J ), 1 )\n                  CALL CLACGV( LASTC, WORK( 1, J ), 1 )\n  190          CONTINUE\n*\n*              W := W * V2**H\n*\n               CALL CTRMM( 'Right', 'Lower', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1**H * V1**H\n*\n                  CALL CGEMM( 'Conjugate transpose',\n     $                 'Conjugate transpose', LASTC, K, LASTV-K,\n     $                 ONE, C, LDC, V, LDV, ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**H  or  W * T\n*\n               CALL CTRMM( 'Right', 'Lower', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V**H * W**H\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - V1**H * W**H\n*\n                  CALL CGEMM( 'Conjugate transpose',\n     $                 'Conjugate transpose', LASTV-K, LASTC, K,\n     $                 -ONE, V, LDV, WORK, LDWORK, ONE, C, LDC )\n               END IF\n*\n*              W := W * V2\n*\n               CALL CTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W**H\n*\n               DO 210 J = 1, K\n                  DO 200 I = 1, LASTC\n                     C( LASTV-K+J, I ) = C( LASTV-K+J, I ) -\n     $                               CONJG( WORK( I, J ) )\n  200             CONTINUE\n  210          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**H  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILACLC( K, N, V, LDV ) )\n               LASTC = ILACLR( M, LASTV, C, LDC )\n*\n*              W := C * V**H  =  (C1*V1**H + C2*V2**H)  (stored in WORK)\n*\n*              W := C2\n*\n               DO 220 J = 1, K\n                  CALL CCOPY( LASTC, C( 1, LASTV-K+J ), 1,\n     $                 WORK( 1, J ), 1 )\n  220          CONTINUE\n*\n*              W := W * V2**H\n*\n               CALL CTRMM( 'Right', 'Lower', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1 * V1**H\n*\n                  CALL CGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV, ONE,\n     $                 WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**H\n*\n               CALL CTRMM( 'Right', 'Lower', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - W * V1\n*\n                  CALL CGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, LASTV-K, K, -ONE, WORK, LDWORK, V, LDV,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2\n*\n               CALL CTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 240 J = 1, K\n                  DO 230 I = 1, LASTC\n                     C( I, LASTV-K+J ) = C( I, LASTV-K+J )\n     $                    - WORK( I, J )\n  230             CONTINUE\n  240          CONTINUE\n*\n            END IF\n*\n         END IF\n      END IF\n*\n      RETURN\n*\n*     End of CLARFB\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/clarfg.f",
    "content": "*> \\brief \\b CLARFG\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download CLARFG + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/clarfg.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/clarfg.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/clarfg.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE CLARFG( N, ALPHA, X, INCX, TAU )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            INCX, N\n*       COMPLEX            ALPHA, TAU\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX            X( * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> CLARFG generates a complex elementary reflector H of order n, such\n*> that\n*>\n*>       H**H * ( alpha ) = ( beta ),   H**H * H = I.\n*>              (   x   )   (   0  )\n*>\n*> where alpha and beta are scalars, with beta real, and x is an\n*> (n-1)-element complex vector. H is represented in the form\n*>\n*>       H = I - tau * ( 1 ) * ( 1 v**H ) ,\n*>                     ( v )\n*>\n*> where tau is a complex scalar and v is a complex (n-1)-element\n*> vector. Note that H is not hermitian.\n*>\n*> If the elements of x are all zero and alpha is real, then tau = 0\n*> and H is taken to be the unit matrix.\n*>\n*> Otherwise  1 <= real(tau) <= 2  and  abs(tau-1) <= 1 .\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The order of the elementary reflector.\n*> \\endverbatim\n*>\n*> \\param[in,out] ALPHA\n*> \\verbatim\n*>          ALPHA is COMPLEX\n*>          On entry, the value alpha.\n*>          On exit, it is overwritten with the value beta.\n*> \\endverbatim\n*>\n*> \\param[in,out] X\n*> \\verbatim\n*>          X is COMPLEX array, dimension\n*>                         (1+(N-2)*abs(INCX))\n*>          On entry, the vector x.\n*>          On exit, it is overwritten with the vector v.\n*> \\endverbatim\n*>\n*> \\param[in] INCX\n*> \\verbatim\n*>          INCX is INTEGER\n*>          The increment between elements of X. INCX > 0.\n*> \\endverbatim\n*>\n*> \\param[out] TAU\n*> \\verbatim\n*>          TAU is COMPLEX\n*>          The value tau.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complexOTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE CLARFG( N, ALPHA, X, INCX, TAU )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      INTEGER            INCX, N\n      COMPLEX            ALPHA, TAU\n*     ..\n*     .. Array Arguments ..\n      COMPLEX            X( * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      REAL               ONE, ZERO\n      PARAMETER          ( ONE = 1.0E+0, ZERO = 0.0E+0 )\n*     ..\n*     .. Local Scalars ..\n      INTEGER            J, KNT\n      REAL               ALPHI, ALPHR, BETA, RSAFMN, SAFMIN, XNORM\n*     ..\n*     .. External Functions ..\n      REAL               SCNRM2, SLAMCH, SLAPY3\n      COMPLEX            CLADIV\n      EXTERNAL           SCNRM2, SLAMCH, SLAPY3, CLADIV\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, AIMAG, CMPLX, REAL, SIGN\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           CSCAL, CSSCAL\n*     ..\n*     .. Executable Statements ..\n*\n      IF( N.LE.0 ) THEN\n         TAU = ZERO\n         RETURN\n      END IF\n*\n      XNORM = SCNRM2( N-1, X, INCX )\n      ALPHR = REAL( ALPHA )\n      ALPHI = AIMAG( ALPHA )\n*\n      IF( XNORM.EQ.ZERO .AND. ALPHI.EQ.ZERO ) THEN\n*\n*        H  =  I\n*\n         TAU = ZERO\n      ELSE\n*\n*        general case\n*\n         BETA = -SIGN( SLAPY3( ALPHR, ALPHI, XNORM ), ALPHR )\n         SAFMIN = SLAMCH( 'S' ) / SLAMCH( 'E' )\n         RSAFMN = ONE / SAFMIN\n*\n         KNT = 0\n         IF( ABS( BETA ).LT.SAFMIN ) THEN\n*\n*           XNORM, BETA may be inaccurate; scale X and recompute them\n*\n   10       CONTINUE\n            KNT = KNT + 1\n            CALL CSSCAL( N-1, RSAFMN, X, INCX )\n            BETA = BETA*RSAFMN\n            ALPHI = ALPHI*RSAFMN\n            ALPHR = ALPHR*RSAFMN\n            IF( ABS( BETA ).LT.SAFMIN )\n     $         GO TO 10\n*\n*           New BETA is at most 1, at least SAFMIN\n*\n            XNORM = SCNRM2( N-1, X, INCX )\n            ALPHA = CMPLX( ALPHR, ALPHI )\n            BETA = -SIGN( SLAPY3( ALPHR, ALPHI, XNORM ), ALPHR )\n         END IF\n         TAU = CMPLX( ( BETA-ALPHR ) / BETA, -ALPHI / BETA )\n         ALPHA = CLADIV( CMPLX( ONE ), ALPHA-BETA )\n         CALL CSCAL( N-1, ALPHA, X, INCX )\n*\n*        If ALPHA is subnormal, it may lose relative accuracy\n*\n         DO 20 J = 1, KNT\n            BETA = BETA*SAFMIN\n 20      CONTINUE\n         ALPHA = BETA\n      END IF\n*\n      RETURN\n*\n*     End of CLARFG\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/clarft.f",
    "content": "*> \\brief \\b CLARFT\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download CLARFT + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/clarft.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/clarft.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/clarft.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE CLARFT( DIRECT, STOREV, N, K, V, LDV, TAU, T, LDT )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          DIRECT, STOREV\n*       INTEGER            K, LDT, LDV, N\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX            T( LDT, * ), TAU( * ), V( LDV, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> CLARFT forms the triangular factor T of a complex block reflector H\n*> of order n, which is defined as a product of k elementary reflectors.\n*>\n*> If DIRECT = 'F', H = H(1) H(2) . . . H(k) and T is upper triangular;\n*>\n*> If DIRECT = 'B', H = H(k) . . . H(2) H(1) and T is lower triangular.\n*>\n*> If STOREV = 'C', the vector which defines the elementary reflector\n*> H(i) is stored in the i-th column of the array V, and\n*>\n*>    H  =  I - V * T * V**H\n*>\n*> If STOREV = 'R', the vector which defines the elementary reflector\n*> H(i) is stored in the i-th row of the array V, and\n*>\n*>    H  =  I - V**H * T * V\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] DIRECT\n*> \\verbatim\n*>          DIRECT is CHARACTER*1\n*>          Specifies the order in which the elementary reflectors are\n*>          multiplied to form the block reflector:\n*>          = 'F': H = H(1) H(2) . . . H(k) (Forward)\n*>          = 'B': H = H(k) . . . H(2) H(1) (Backward)\n*> \\endverbatim\n*>\n*> \\param[in] STOREV\n*> \\verbatim\n*>          STOREV is CHARACTER*1\n*>          Specifies how the vectors which define the elementary\n*>          reflectors are stored (see also Further Details):\n*>          = 'C': columnwise\n*>          = 'R': rowwise\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The order of the block reflector H. N >= 0.\n*> \\endverbatim\n*>\n*> \\param[in] K\n*> \\verbatim\n*>          K is INTEGER\n*>          The order of the triangular factor T (= the number of\n*>          elementary reflectors). K >= 1.\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is COMPLEX array, dimension\n*>                               (LDV,K) if STOREV = 'C'\n*>                               (LDV,N) if STOREV = 'R'\n*>          The matrix V. See further details.\n*> \\endverbatim\n*>\n*> \\param[in] LDV\n*> \\verbatim\n*>          LDV is INTEGER\n*>          The leading dimension of the array V.\n*>          If STOREV = 'C', LDV >= max(1,N); if STOREV = 'R', LDV >= K.\n*> \\endverbatim\n*>\n*> \\param[in] TAU\n*> \\verbatim\n*>          TAU is COMPLEX array, dimension (K)\n*>          TAU(i) must contain the scalar factor of the elementary\n*>          reflector H(i).\n*> \\endverbatim\n*>\n*> \\param[out] T\n*> \\verbatim\n*>          T is COMPLEX array, dimension (LDT,K)\n*>          The k by k triangular factor T of the block reflector.\n*>          If DIRECT = 'F', T is upper triangular; if DIRECT = 'B', T is\n*>          lower triangular. The rest of the array is not used.\n*> \\endverbatim\n*>\n*> \\param[in] LDT\n*> \\verbatim\n*>          LDT is INTEGER\n*>          The leading dimension of the array T. LDT >= K.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup complexOTHERauxiliary\n*\n*> \\par Further Details:\n*  =====================\n*>\n*> \\verbatim\n*>\n*>  The shape of the matrix V and the storage of the vectors which define\n*>  the H(i) is best illustrated by the following example with n = 5 and\n*>  k = 3. The elements equal to 1 are not stored.\n*>\n*>  DIRECT = 'F' and STOREV = 'C':         DIRECT = 'F' and STOREV = 'R':\n*>\n*>               V = (  1       )                 V = (  1 v1 v1 v1 v1 )\n*>                   ( v1  1    )                     (     1 v2 v2 v2 )\n*>                   ( v1 v2  1 )                     (        1 v3 v3 )\n*>                   ( v1 v2 v3 )\n*>                   ( v1 v2 v3 )\n*>\n*>  DIRECT = 'B' and STOREV = 'C':         DIRECT = 'B' and STOREV = 'R':\n*>\n*>               V = ( v1 v2 v3 )                 V = ( v1 v1  1       )\n*>                   ( v1 v2 v3 )                     ( v2 v2 v2  1    )\n*>                   (  1 v2 v3 )                     ( v3 v3 v3 v3  1 )\n*>                   (     1 v3 )\n*>                   (        1 )\n*> \\endverbatim\n*>\n*  =====================================================================\n      SUBROUTINE CLARFT( DIRECT, STOREV, N, K, V, LDV, TAU, T, LDT )\n*\n*  -- LAPACK auxiliary routine (version 3.4.1) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*     .. Scalar Arguments ..\n      CHARACTER          DIRECT, STOREV\n      INTEGER            K, LDT, LDV, N\n*     ..\n*     .. Array Arguments ..\n      COMPLEX            T( LDT, * ), TAU( * ), V( LDV, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      COMPLEX            ONE, ZERO\n      PARAMETER          ( ONE = ( 1.0E+0, 0.0E+0 ),\n     $                   ZERO = ( 0.0E+0, 0.0E+0 ) )\n*     ..\n*     .. Local Scalars ..\n      INTEGER            I, J, PREVLASTV, LASTV\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           CGEMV, CLACGV, CTRMV\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      EXTERNAL           LSAME\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick return if possible\n*\n      IF( N.EQ.0 )\n     $   RETURN\n*\n      IF( LSAME( DIRECT, 'F' ) ) THEN\n         PREVLASTV = N\n         DO I = 1, K\n            PREVLASTV = MAX( PREVLASTV, I )\n            IF( TAU( I ).EQ.ZERO ) THEN\n*\n*              H(i)  =  I\n*\n               DO J = 1, I\n                  T( J, I ) = ZERO\n               END DO\n            ELSE\n*\n*              general case\n*\n               IF( LSAME( STOREV, 'C' ) ) THEN\n*                 Skip any trailing zeros.\n                  DO LASTV = N, I+1, -1\n                     IF( V( LASTV, I ).NE.ZERO ) EXIT\n                  END DO\n                  DO J = 1, I-1\n                     T( J, I ) = -TAU( I ) * CONJG( V( I , J ) )\n                  END DO                     \n                  J = MIN( LASTV, PREVLASTV )\n*\n*                 T(1:i-1,i) := - tau(i) * V(i:j,1:i-1)**H * V(i:j,i)\n*\n                  CALL CGEMV( 'Conjugate transpose', J-I, I-1,\n     $                        -TAU( I ), V( I+1, 1 ), LDV, \n     $                        V( I+1, I ), 1,\n     $                        ONE, T( 1, I ), 1 )\n               ELSE\n*                 Skip any trailing zeros.\n                  DO LASTV = N, I+1, -1\n                     IF( V( I, LASTV ).NE.ZERO ) EXIT\n                  END DO\n                  DO J = 1, I-1\n                     T( J, I ) = -TAU( I ) * V( J , I )\n                  END DO                     \n                  J = MIN( LASTV, PREVLASTV )\n*\n*                 T(1:i-1,i) := - tau(i) * V(1:i-1,i:j) * V(i,i:j)**H\n*\n                  CALL CGEMM( 'N', 'C', I-1, 1, J-I, -TAU( I ),\n     $                        V( 1, I+1 ), LDV, V( I, I+1 ), LDV,\n     $                        ONE, T( 1, I ), LDT )                  \n               END IF\n*\n*              T(1:i-1,i) := T(1:i-1,1:i-1) * T(1:i-1,i)\n*\n               CALL CTRMV( 'Upper', 'No transpose', 'Non-unit', I-1, T,\n     $                     LDT, T( 1, I ), 1 )\n               T( I, I ) = TAU( I )\n               IF( I.GT.1 ) THEN\n                  PREVLASTV = MAX( PREVLASTV, LASTV )\n               ELSE\n                  PREVLASTV = LASTV\n               END IF\n            END IF\n         END DO\n      ELSE\n         PREVLASTV = 1\n         DO I = K, 1, -1\n            IF( TAU( I ).EQ.ZERO ) THEN\n*\n*              H(i)  =  I\n*\n               DO J = I, K\n                  T( J, I ) = ZERO\n               END DO\n            ELSE\n*\n*              general case\n*\n               IF( I.LT.K ) THEN\n                  IF( LSAME( STOREV, 'C' ) ) THEN\n*                    Skip any leading zeros.\n                     DO LASTV = 1, I-1\n                        IF( V( LASTV, I ).NE.ZERO ) EXIT\n                     END DO\n                     DO J = I+1, K\n                        T( J, I ) = -TAU( I ) * CONJG( V( N-K+I , J ) )\n                     END DO                        \n                     J = MAX( LASTV, PREVLASTV )\n*\n*                    T(i+1:k,i) = -tau(i) * V(j:n-k+i,i+1:k)**H * V(j:n-k+i,i)\n*\n                     CALL CGEMV( 'Conjugate transpose', N-K+I-J, K-I,\n     $                           -TAU( I ), V( J, I+1 ), LDV, V( J, I ),\n     $                           1, ONE, T( I+1, I ), 1 )\n                  ELSE\n*                    Skip any leading zeros.\n                     DO LASTV = 1, I-1\n                        IF( V( I, LASTV ).NE.ZERO ) EXIT\n                     END DO\n                     DO J = I+1, K\n                        T( J, I ) = -TAU( I ) * V( J, N-K+I )\n                     END DO                      \n                     J = MAX( LASTV, PREVLASTV )\n*\n*                    T(i+1:k,i) = -tau(i) * V(i+1:k,j:n-k+i) * V(i,j:n-k+i)**H\n*\n                     CALL CGEMM( 'N', 'C', K-I, 1, N-K+I-J, -TAU( I ),\n     $                           V( I+1, J ), LDV, V( I, J ), LDV,\n     $                           ONE, T( I+1, I ), LDT )                     \n                  END IF\n*\n*                 T(i+1:k,i) := T(i+1:k,i+1:k) * T(i+1:k,i)\n*\n                  CALL CTRMV( 'Lower', 'No transpose', 'Non-unit', K-I,\n     $                        T( I+1, I+1 ), LDT, T( I+1, I ), 1 )\n                  IF( I.GT.1 ) THEN\n                     PREVLASTV = MIN( PREVLASTV, LASTV )\n                  ELSE\n                     PREVLASTV = LASTV\n                  END IF\n               END IF\n               T( I, I ) = TAU( I )\n            END IF\n         END DO\n      END IF\n      RETURN\n*\n*     End of CLARFT\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/complex_double.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define SCALAR        std::complex<double>\n#define SCALAR_SUFFIX z\n#define SCALAR_SUFFIX_UP \"Z\"\n#define REAL_SCALAR_SUFFIX d\n#define ISCOMPLEX     1\n\n#include \"cholesky.cpp\"\n#include \"lu.cpp\"\n#include \"svd.cpp\"\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/complex_single.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define SCALAR        std::complex<float>\n#define SCALAR_SUFFIX c\n#define SCALAR_SUFFIX_UP \"C\"\n#define REAL_SCALAR_SUFFIX s\n#define ISCOMPLEX     1\n\n#include \"cholesky.cpp\"\n#include \"lu.cpp\"\n#include \"svd.cpp\"\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/dladiv.f",
    "content": "*> \\brief \\b DLADIV\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download DLADIV + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/dladiv.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/dladiv.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/dladiv.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE DLADIV( A, B, C, D, P, Q )\n* \n*       .. Scalar Arguments ..\n*       DOUBLE PRECISION   A, B, C, D, P, Q\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> DLADIV performs complex division in  real arithmetic\n*>\n*>                       a + i*b\n*>            p + i*q = ---------\n*>                       c + i*d\n*>\n*> The algorithm is due to Robert L. Smith and can be found\n*> in D. Knuth, The art of Computer Programming, Vol.2, p.195\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] A\n*> \\verbatim\n*>          A is DOUBLE PRECISION\n*> \\endverbatim\n*>\n*> \\param[in] B\n*> \\verbatim\n*>          B is DOUBLE PRECISION\n*> \\endverbatim\n*>\n*> \\param[in] C\n*> \\verbatim\n*>          C is DOUBLE PRECISION\n*> \\endverbatim\n*>\n*> \\param[in] D\n*> \\verbatim\n*>          D is DOUBLE PRECISION\n*>          The scalars a, b, c, and d in the above expression.\n*> \\endverbatim\n*>\n*> \\param[out] P\n*> \\verbatim\n*>          P is DOUBLE PRECISION\n*> \\endverbatim\n*>\n*> \\param[out] Q\n*> \\verbatim\n*>          Q is DOUBLE PRECISION\n*>          The scalars p and q in the above expression.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE DLADIV( A, B, C, D, P, Q )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   A, B, C, D, P, Q\n*     ..\n*\n*  =====================================================================\n*\n*     .. Local Scalars ..\n      DOUBLE PRECISION   E, F\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS\n*     ..\n*     .. Executable Statements ..\n*\n      IF( ABS( D ).LT.ABS( C ) ) THEN\n         E = D / C\n         F = C + D*E\n         P = ( A+B*E ) / F\n         Q = ( B-A*E ) / F\n      ELSE\n         E = C / D\n         F = D + C*E\n         P = ( B+A*E ) / F\n         Q = ( -A+B*E ) / F\n      END IF\n*\n      RETURN\n*\n*     End of DLADIV\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/dlamch.f",
    "content": "*> \\brief \\b DLAMCH\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*      DOUBLE PRECISION FUNCTION DLAMCH( CMACH )\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> DLAMCH determines double precision machine parameters.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] CMACH\n*> \\verbatim\n*>          Specifies the value to be returned by DLAMCH:\n*>          = 'E' or 'e',   DLAMCH := eps\n*>          = 'S' or 's ,   DLAMCH := sfmin\n*>          = 'B' or 'b',   DLAMCH := base\n*>          = 'P' or 'p',   DLAMCH := eps*base\n*>          = 'N' or 'n',   DLAMCH := t\n*>          = 'R' or 'r',   DLAMCH := rnd\n*>          = 'M' or 'm',   DLAMCH := emin\n*>          = 'U' or 'u',   DLAMCH := rmin\n*>          = 'L' or 'l',   DLAMCH := emax\n*>          = 'O' or 'o',   DLAMCH := rmax\n*>          where\n*>          eps   = relative machine precision\n*>          sfmin = safe minimum, such that 1/sfmin does not overflow\n*>          base  = base of the machine\n*>          prec  = eps*base\n*>          t     = number of (base) digits in the mantissa\n*>          rnd   = 1.0 when rounding occurs in addition, 0.0 otherwise\n*>          emin  = minimum exponent before (gradual) underflow\n*>          rmin  = underflow threshold - base**(emin-1)\n*>          emax  = largest exponent before overflow\n*>          rmax  = overflow threshold  - (base**emax)*(1-eps)\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      DOUBLE PRECISION FUNCTION DLAMCH( CMACH )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      CHARACTER          CMACH\n*     ..\n*\n* =====================================================================\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ONE, ZERO\n      PARAMETER          ( ONE = 1.0D+0, ZERO = 0.0D+0 )\n*     ..\n*     .. Local Scalars ..\n      DOUBLE PRECISION   RND, EPS, SFMIN, SMALL, RMACH\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      EXTERNAL           LSAME\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          DIGITS, EPSILON, HUGE, MAXEXPONENT,\n     $                   MINEXPONENT, RADIX, TINY\n*     ..\n*     .. Executable Statements ..\n*\n*\n*     Assume rounding, not chopping. Always.\n*\n      RND = ONE\n*\n      IF( ONE.EQ.RND ) THEN\n         EPS = EPSILON(ZERO) * 0.5\n      ELSE\n         EPS = EPSILON(ZERO)\n      END IF\n*\n      IF( LSAME( CMACH, 'E' ) ) THEN\n         RMACH = EPS\n      ELSE IF( LSAME( CMACH, 'S' ) ) THEN\n         SFMIN = TINY(ZERO)\n         SMALL = ONE / HUGE(ZERO)\n         IF( SMALL.GE.SFMIN ) THEN\n*\n*           Use SMALL plus a bit, to avoid the possibility of rounding\n*           causing overflow when computing  1/sfmin.\n*\n            SFMIN = SMALL*( ONE+EPS )\n         END IF\n         RMACH = SFMIN\n      ELSE IF( LSAME( CMACH, 'B' ) ) THEN\n         RMACH = RADIX(ZERO)\n      ELSE IF( LSAME( CMACH, 'P' ) ) THEN\n         RMACH = EPS * RADIX(ZERO)\n      ELSE IF( LSAME( CMACH, 'N' ) ) THEN\n         RMACH = DIGITS(ZERO)\n      ELSE IF( LSAME( CMACH, 'R' ) ) THEN\n         RMACH = RND\n      ELSE IF( LSAME( CMACH, 'M' ) ) THEN\n         RMACH = MINEXPONENT(ZERO)\n      ELSE IF( LSAME( CMACH, 'U' ) ) THEN\n         RMACH = tiny(zero)\n      ELSE IF( LSAME( CMACH, 'L' ) ) THEN\n         RMACH = MAXEXPONENT(ZERO)\n      ELSE IF( LSAME( CMACH, 'O' ) ) THEN\n         RMACH = HUGE(ZERO)\n      ELSE\n         RMACH = ZERO\n      END IF\n*\n      DLAMCH = RMACH\n      RETURN\n*\n*     End of DLAMCH\n*\n      END\n************************************************************************\n*> \\brief \\b DLAMC3\n*> \\details\n*> \\b Purpose:\n*> \\verbatim\n*> DLAMC3  is intended to force  A  and  B  to be stored prior to doing\n*> the addition of  A  and  B ,  for use in situations where optimizers\n*> might hold one of these in a register.\n*> \\endverbatim\n*> \\author LAPACK is a software package provided by Univ. of Tennessee, Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..\n*> \\date November 2011\n*> \\ingroup auxOTHERauxiliary\n*>\n*> \\param[in] A\n*> \\verbatim\n*>          A is a DOUBLE PRECISION\n*> \\endverbatim\n*>\n*> \\param[in] B\n*> \\verbatim\n*>          B is a DOUBLE PRECISION\n*>          The values A and B.\n*> \\endverbatim\n*>\n      DOUBLE PRECISION FUNCTION DLAMC3( A, B )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*     Univ. of Tennessee, Univ. of California Berkeley and NAG Ltd..\n*     November 2010\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   A, B\n*     ..\n* =====================================================================\n*\n*     .. Executable Statements ..\n*\n      DLAMC3 = A + B\n*\n      RETURN\n*\n*     End of DLAMC3\n*\n      END\n*\n************************************************************************\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/dlapy2.f",
    "content": "*> \\brief \\b DLAPY2\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download DLAPY2 + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/dlapy2.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/dlapy2.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/dlapy2.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       DOUBLE PRECISION FUNCTION DLAPY2( X, Y )\n* \n*       .. Scalar Arguments ..\n*       DOUBLE PRECISION   X, Y\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> DLAPY2 returns sqrt(x**2+y**2), taking care not to cause unnecessary\n*> overflow.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] X\n*> \\verbatim\n*>          X is DOUBLE PRECISION\n*> \\endverbatim\n*>\n*> \\param[in] Y\n*> \\verbatim\n*>          Y is DOUBLE PRECISION\n*>          X and Y specify the values x and y.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      DOUBLE PRECISION FUNCTION DLAPY2( X, Y )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   X, Y\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO\n      PARAMETER          ( ZERO = 0.0D0 )\n      DOUBLE PRECISION   ONE\n      PARAMETER          ( ONE = 1.0D0 )\n*     ..\n*     .. Local Scalars ..\n      DOUBLE PRECISION   W, XABS, YABS, Z\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN, SQRT\n*     ..\n*     .. Executable Statements ..\n*\n      XABS = ABS( X )\n      YABS = ABS( Y )\n      W = MAX( XABS, YABS )\n      Z = MIN( XABS, YABS )\n      IF( Z.EQ.ZERO ) THEN\n         DLAPY2 = W\n      ELSE\n         DLAPY2 = W*SQRT( ONE+( Z / W )**2 )\n      END IF\n      RETURN\n*\n*     End of DLAPY2\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/dlapy3.f",
    "content": "*> \\brief \\b DLAPY3\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download DLAPY3 + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/dlapy3.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/dlapy3.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/dlapy3.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       DOUBLE PRECISION FUNCTION DLAPY3( X, Y, Z )\n* \n*       .. Scalar Arguments ..\n*       DOUBLE PRECISION   X, Y, Z\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> DLAPY3 returns sqrt(x**2+y**2+z**2), taking care not to cause\n*> unnecessary overflow.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] X\n*> \\verbatim\n*>          X is DOUBLE PRECISION\n*> \\endverbatim\n*>\n*> \\param[in] Y\n*> \\verbatim\n*>          Y is DOUBLE PRECISION\n*> \\endverbatim\n*>\n*> \\param[in] Z\n*> \\verbatim\n*>          Z is DOUBLE PRECISION\n*>          X, Y and Z specify the values x, y and z.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      DOUBLE PRECISION FUNCTION DLAPY3( X, Y, Z )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   X, Y, Z\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO\n      PARAMETER          ( ZERO = 0.0D0 )\n*     ..\n*     .. Local Scalars ..\n      DOUBLE PRECISION   W, XABS, YABS, ZABS\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, SQRT\n*     ..\n*     .. Executable Statements ..\n*\n      XABS = ABS( X )\n      YABS = ABS( Y )\n      ZABS = ABS( Z )\n      W = MAX( XABS, YABS, ZABS )\n      IF( W.EQ.ZERO ) THEN\n*     W can be zero for max(0,nan,0)\n*     adding all three entries together will make sure\n*     NaN will not disappear.\n         DLAPY3 =  XABS + YABS + ZABS\n      ELSE\n         DLAPY3 = W*SQRT( ( XABS / W )**2+( YABS / W )**2+\n     $            ( ZABS / W )**2 )\n      END IF\n      RETURN\n*\n*     End of DLAPY3\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/dlarf.f",
    "content": "*> \\brief \\b DLARF\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download DLARF + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/dlarf.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/dlarf.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/dlarf.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE DLARF( SIDE, M, N, V, INCV, TAU, C, LDC, WORK )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          SIDE\n*       INTEGER            INCV, LDC, M, N\n*       DOUBLE PRECISION   TAU\n*       ..\n*       .. Array Arguments ..\n*       DOUBLE PRECISION   C( LDC, * ), V( * ), WORK( * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> DLARF applies a real elementary reflector H to a real m by n matrix\n*> C, from either the left or the right. H is represented in the form\n*>\n*>       H = I - tau * v * v**T\n*>\n*> where tau is a real scalar and v is a real vector.\n*>\n*> If tau = 0, then H is taken to be the unit matrix.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] SIDE\n*> \\verbatim\n*>          SIDE is CHARACTER*1\n*>          = 'L': form  H * C\n*>          = 'R': form  C * H\n*> \\endverbatim\n*>\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is DOUBLE PRECISION array, dimension\n*>                     (1 + (M-1)*abs(INCV)) if SIDE = 'L'\n*>                  or (1 + (N-1)*abs(INCV)) if SIDE = 'R'\n*>          The vector v in the representation of H. V is not used if\n*>          TAU = 0.\n*> \\endverbatim\n*>\n*> \\param[in] INCV\n*> \\verbatim\n*>          INCV is INTEGER\n*>          The increment between elements of v. INCV <> 0.\n*> \\endverbatim\n*>\n*> \\param[in] TAU\n*> \\verbatim\n*>          TAU is DOUBLE PRECISION\n*>          The value tau in the representation of H.\n*> \\endverbatim\n*>\n*> \\param[in,out] C\n*> \\verbatim\n*>          C is DOUBLE PRECISION array, dimension (LDC,N)\n*>          On entry, the m by n matrix C.\n*>          On exit, C is overwritten by the matrix H * C if SIDE = 'L',\n*>          or C * H if SIDE = 'R'.\n*> \\endverbatim\n*>\n*> \\param[in] LDC\n*> \\verbatim\n*>          LDC is INTEGER\n*>          The leading dimension of the array C. LDC >= max(1,M).\n*> \\endverbatim\n*>\n*> \\param[out] WORK\n*> \\verbatim\n*>          WORK is DOUBLE PRECISION array, dimension\n*>                         (N) if SIDE = 'L'\n*>                      or (M) if SIDE = 'R'\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup doubleOTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE DLARF( SIDE, M, N, V, INCV, TAU, C, LDC, WORK )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      CHARACTER          SIDE\n      INTEGER            INCV, LDC, M, N\n      DOUBLE PRECISION   TAU\n*     ..\n*     .. Array Arguments ..\n      DOUBLE PRECISION   C( LDC, * ), V( * ), WORK( * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ONE, ZERO\n      PARAMETER          ( ONE = 1.0D+0, ZERO = 0.0D+0 )\n*     ..\n*     .. Local Scalars ..\n      LOGICAL            APPLYLEFT\n      INTEGER            I, LASTV, LASTC\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           DGEMV, DGER\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      INTEGER            ILADLR, ILADLC\n      EXTERNAL           LSAME, ILADLR, ILADLC\n*     ..\n*     .. Executable Statements ..\n*\n      APPLYLEFT = LSAME( SIDE, 'L' )\n      LASTV = 0\n      LASTC = 0\n      IF( TAU.NE.ZERO ) THEN\n!     Set up variables for scanning V.  LASTV begins pointing to the end\n!     of V.\n         IF( APPLYLEFT ) THEN\n            LASTV = M\n         ELSE\n            LASTV = N\n         END IF\n         IF( INCV.GT.0 ) THEN\n            I = 1 + (LASTV-1) * INCV\n         ELSE\n            I = 1\n         END IF\n!     Look for the last non-zero row in V.\n         DO WHILE( LASTV.GT.0 .AND. V( I ).EQ.ZERO )\n            LASTV = LASTV - 1\n            I = I - INCV\n         END DO\n         IF( APPLYLEFT ) THEN\n!     Scan for the last non-zero column in C(1:lastv,:).\n            LASTC = ILADLC(LASTV, N, C, LDC)\n         ELSE\n!     Scan for the last non-zero row in C(:,1:lastv).\n            LASTC = ILADLR(M, LASTV, C, LDC)\n         END IF\n      END IF\n!     Note that lastc.eq.0 renders the BLAS operations null; no special\n!     case is needed at this level.\n      IF( APPLYLEFT ) THEN\n*\n*        Form  H * C\n*\n         IF( LASTV.GT.0 ) THEN\n*\n*           w(1:lastc,1) := C(1:lastv,1:lastc)**T * v(1:lastv,1)\n*\n            CALL DGEMV( 'Transpose', LASTV, LASTC, ONE, C, LDC, V, INCV,\n     $           ZERO, WORK, 1 )\n*\n*           C(1:lastv,1:lastc) := C(...) - v(1:lastv,1) * w(1:lastc,1)**T\n*\n            CALL DGER( LASTV, LASTC, -TAU, V, INCV, WORK, 1, C, LDC )\n         END IF\n      ELSE\n*\n*        Form  C * H\n*\n         IF( LASTV.GT.0 ) THEN\n*\n*           w(1:lastc,1) := C(1:lastc,1:lastv) * v(1:lastv,1)\n*\n            CALL DGEMV( 'No transpose', LASTC, LASTV, ONE, C, LDC,\n     $           V, INCV, ZERO, WORK, 1 )\n*\n*           C(1:lastc,1:lastv) := C(...) - w(1:lastc,1) * v(1:lastv,1)**T\n*\n            CALL DGER( LASTC, LASTV, -TAU, WORK, 1, V, INCV, C, LDC )\n         END IF\n      END IF\n      RETURN\n*\n*     End of DLARF\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/dlarfb.f",
    "content": "*> \\brief \\b DLARFB\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download DLARFB + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/dlarfb.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/dlarfb.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/dlarfb.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE DLARFB( SIDE, TRANS, DIRECT, STOREV, M, N, K, V, LDV,\n*                          T, LDT, C, LDC, WORK, LDWORK )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          DIRECT, SIDE, STOREV, TRANS\n*       INTEGER            K, LDC, LDT, LDV, LDWORK, M, N\n*       ..\n*       .. Array Arguments ..\n*       DOUBLE PRECISION   C( LDC, * ), T( LDT, * ), V( LDV, * ),\n*      $                   WORK( LDWORK, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> DLARFB applies a real block reflector H or its transpose H**T to a\n*> real m by n matrix C, from either the left or the right.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] SIDE\n*> \\verbatim\n*>          SIDE is CHARACTER*1\n*>          = 'L': apply H or H**T from the Left\n*>          = 'R': apply H or H**T from the Right\n*> \\endverbatim\n*>\n*> \\param[in] TRANS\n*> \\verbatim\n*>          TRANS is CHARACTER*1\n*>          = 'N': apply H (No transpose)\n*>          = 'T': apply H**T (Transpose)\n*> \\endverbatim\n*>\n*> \\param[in] DIRECT\n*> \\verbatim\n*>          DIRECT is CHARACTER*1\n*>          Indicates how H is formed from a product of elementary\n*>          reflectors\n*>          = 'F': H = H(1) H(2) . . . H(k) (Forward)\n*>          = 'B': H = H(k) . . . H(2) H(1) (Backward)\n*> \\endverbatim\n*>\n*> \\param[in] STOREV\n*> \\verbatim\n*>          STOREV is CHARACTER*1\n*>          Indicates how the vectors which define the elementary\n*>          reflectors are stored:\n*>          = 'C': Columnwise\n*>          = 'R': Rowwise\n*> \\endverbatim\n*>\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] K\n*> \\verbatim\n*>          K is INTEGER\n*>          The order of the matrix T (= the number of elementary\n*>          reflectors whose product defines the block reflector).\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is DOUBLE PRECISION array, dimension\n*>                                (LDV,K) if STOREV = 'C'\n*>                                (LDV,M) if STOREV = 'R' and SIDE = 'L'\n*>                                (LDV,N) if STOREV = 'R' and SIDE = 'R'\n*>          The matrix V. See Further Details.\n*> \\endverbatim\n*>\n*> \\param[in] LDV\n*> \\verbatim\n*>          LDV is INTEGER\n*>          The leading dimension of the array V.\n*>          If STOREV = 'C' and SIDE = 'L', LDV >= max(1,M);\n*>          if STOREV = 'C' and SIDE = 'R', LDV >= max(1,N);\n*>          if STOREV = 'R', LDV >= K.\n*> \\endverbatim\n*>\n*> \\param[in] T\n*> \\verbatim\n*>          T is DOUBLE PRECISION array, dimension (LDT,K)\n*>          The triangular k by k matrix T in the representation of the\n*>          block reflector.\n*> \\endverbatim\n*>\n*> \\param[in] LDT\n*> \\verbatim\n*>          LDT is INTEGER\n*>          The leading dimension of the array T. LDT >= K.\n*> \\endverbatim\n*>\n*> \\param[in,out] C\n*> \\verbatim\n*>          C is DOUBLE PRECISION array, dimension (LDC,N)\n*>          On entry, the m by n matrix C.\n*>          On exit, C is overwritten by H*C or H**T*C or C*H or C*H**T.\n*> \\endverbatim\n*>\n*> \\param[in] LDC\n*> \\verbatim\n*>          LDC is INTEGER\n*>          The leading dimension of the array C. LDC >= max(1,M).\n*> \\endverbatim\n*>\n*> \\param[out] WORK\n*> \\verbatim\n*>          WORK is DOUBLE PRECISION array, dimension (LDWORK,K)\n*> \\endverbatim\n*>\n*> \\param[in] LDWORK\n*> \\verbatim\n*>          LDWORK is INTEGER\n*>          The leading dimension of the array WORK.\n*>          If SIDE = 'L', LDWORK >= max(1,N);\n*>          if SIDE = 'R', LDWORK >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup doubleOTHERauxiliary\n*\n*> \\par Further Details:\n*  =====================\n*>\n*> \\verbatim\n*>\n*>  The shape of the matrix V and the storage of the vectors which define\n*>  the H(i) is best illustrated by the following example with n = 5 and\n*>  k = 3. The elements equal to 1 are not stored; the corresponding\n*>  array elements are modified but restored on exit. The rest of the\n*>  array is not used.\n*>\n*>  DIRECT = 'F' and STOREV = 'C':         DIRECT = 'F' and STOREV = 'R':\n*>\n*>               V = (  1       )                 V = (  1 v1 v1 v1 v1 )\n*>                   ( v1  1    )                     (     1 v2 v2 v2 )\n*>                   ( v1 v2  1 )                     (        1 v3 v3 )\n*>                   ( v1 v2 v3 )\n*>                   ( v1 v2 v3 )\n*>\n*>  DIRECT = 'B' and STOREV = 'C':         DIRECT = 'B' and STOREV = 'R':\n*>\n*>               V = ( v1 v2 v3 )                 V = ( v1 v1  1       )\n*>                   ( v1 v2 v3 )                     ( v2 v2 v2  1    )\n*>                   (  1 v2 v3 )                     ( v3 v3 v3 v3  1 )\n*>                   (     1 v3 )\n*>                   (        1 )\n*> \\endverbatim\n*>\n*  =====================================================================\n      SUBROUTINE DLARFB( SIDE, TRANS, DIRECT, STOREV, M, N, K, V, LDV,\n     $                   T, LDT, C, LDC, WORK, LDWORK )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      CHARACTER          DIRECT, SIDE, STOREV, TRANS\n      INTEGER            K, LDC, LDT, LDV, LDWORK, M, N\n*     ..\n*     .. Array Arguments ..\n      DOUBLE PRECISION   C( LDC, * ), T( LDT, * ), V( LDV, * ),\n     $                   WORK( LDWORK, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ONE\n      PARAMETER          ( ONE = 1.0D+0 )\n*     ..\n*     .. Local Scalars ..\n      CHARACTER          TRANST\n      INTEGER            I, J, LASTV, LASTC\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      INTEGER            ILADLR, ILADLC\n      EXTERNAL           LSAME, ILADLR, ILADLC\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           DCOPY, DGEMM, DTRMM\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick return if possible\n*\n      IF( M.LE.0 .OR. N.LE.0 )\n     $   RETURN\n*\n      IF( LSAME( TRANS, 'N' ) ) THEN\n         TRANST = 'T'\n      ELSE\n         TRANST = 'N'\n      END IF\n*\n      IF( LSAME( STOREV, 'C' ) ) THEN\n*\n         IF( LSAME( DIRECT, 'F' ) ) THEN\n*\n*           Let  V =  ( V1 )    (first K rows)\n*                     ( V2 )\n*           where  V1  is unit lower triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**T * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILADLR( M, K, V, LDV ) )\n               LASTC = ILADLC( LASTV, N, C, LDC )\n*\n*              W := C**T * V  =  (C1**T * V1 + C2**T * V2)  (stored in WORK)\n*\n*              W := C1**T\n*\n               DO 10 J = 1, K\n                  CALL DCOPY( LASTC, C( J, 1 ), LDC, WORK( 1, J ), 1 )\n   10          CONTINUE\n*\n*              W := W * V1\n*\n               CALL DTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2**T *V2\n*\n                  CALL DGEMM( 'Transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C( K+1, 1 ), LDC, V( K+1, 1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**T  or  W * T\n*\n               CALL DTRMM( 'Right', 'Upper', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V * W**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - V2 * W**T\n*\n                  CALL DGEMM( 'No transpose', 'Transpose',\n     $                 LASTV-K, LASTC, K,\n     $                 -ONE, V( K+1, 1 ), LDV, WORK, LDWORK, ONE,\n     $                 C( K+1, 1 ), LDC )\n               END IF\n*\n*              W := W * V1**T\n*\n               CALL DTRMM( 'Right', 'Lower', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W**T\n*\n               DO 30 J = 1, K\n                  DO 20 I = 1, LASTC\n                     C( J, I ) = C( J, I ) - WORK( I, J )\n   20             CONTINUE\n   30          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**T  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILADLR( N, K, V, LDV ) )\n               LASTC = ILADLR( M, LASTV, C, LDC )\n*\n*              W := C * V  =  (C1*V1 + C2*V2)  (stored in WORK)\n*\n*              W := C1\n*\n               DO 40 J = 1, K\n                  CALL DCOPY( LASTC, C( 1, J ), 1, WORK( 1, J ), 1 )\n   40          CONTINUE\n*\n*              W := W * V1\n*\n               CALL DTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2 * V2\n*\n                  CALL DGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C( 1, K+1 ), LDC, V( K+1, 1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**T\n*\n               CALL DTRMM( 'Right', 'Upper', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - W * V2**T\n*\n                  CALL DGEMM( 'No transpose', 'Transpose',\n     $                 LASTC, LASTV-K, K,\n     $                 -ONE, WORK, LDWORK, V( K+1, 1 ), LDV, ONE,\n     $                 C( 1, K+1 ), LDC )\n               END IF\n*\n*              W := W * V1**T\n*\n               CALL DTRMM( 'Right', 'Lower', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 60 J = 1, K\n                  DO 50 I = 1, LASTC\n                     C( I, J ) = C( I, J ) - WORK( I, J )\n   50             CONTINUE\n   60          CONTINUE\n            END IF\n*\n         ELSE\n*\n*           Let  V =  ( V1 )\n*                     ( V2 )    (last K rows)\n*           where  V2  is unit upper triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**T * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILADLR( M, K, V, LDV ) )\n               LASTC = ILADLC( LASTV, N, C, LDC )\n*\n*              W := C**T * V  =  (C1**T * V1 + C2**T * V2)  (stored in WORK)\n*\n*              W := C2**T\n*\n               DO 70 J = 1, K\n                  CALL DCOPY( LASTC, C( LASTV-K+J, 1 ), LDC,\n     $                 WORK( 1, J ), 1 )\n   70          CONTINUE\n*\n*              W := W * V2\n*\n               CALL DTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1**T*V1\n*\n                  CALL DGEMM( 'Transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**T  or  W * T\n*\n               CALL DTRMM( 'Right', 'Lower', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V * W**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - V1 * W**T\n*\n                  CALL DGEMM( 'No transpose', 'Transpose',\n     $                 LASTV-K, LASTC, K, -ONE, V, LDV, WORK, LDWORK,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2**T\n*\n               CALL DTRMM( 'Right', 'Upper', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W**T\n*\n               DO 90 J = 1, K\n                  DO 80 I = 1, LASTC\n                     C( LASTV-K+J, I ) = C( LASTV-K+J, I ) - WORK(I, J)\n   80             CONTINUE\n   90          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**T  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILADLR( N, K, V, LDV ) )\n               LASTC = ILADLR( M, LASTV, C, LDC )\n*\n*              W := C * V  =  (C1*V1 + C2*V2)  (stored in WORK)\n*\n*              W := C2\n*\n               DO 100 J = 1, K\n                  CALL DCOPY( LASTC, C( 1, N-K+J ), 1, WORK( 1, J ), 1 )\n  100          CONTINUE\n*\n*              W := W * V2\n*\n               CALL DTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1 * V1\n*\n                  CALL DGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**T\n*\n               CALL DTRMM( 'Right', 'Lower', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - W * V1**T\n*\n                  CALL DGEMM( 'No transpose', 'Transpose',\n     $                 LASTC, LASTV-K, K, -ONE, WORK, LDWORK, V, LDV,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2**T\n*\n               CALL DTRMM( 'Right', 'Upper', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W\n*\n               DO 120 J = 1, K\n                  DO 110 I = 1, LASTC\n                     C( I, LASTV-K+J ) = C( I, LASTV-K+J ) - WORK(I, J)\n  110             CONTINUE\n  120          CONTINUE\n            END IF\n         END IF\n*\n      ELSE IF( LSAME( STOREV, 'R' ) ) THEN\n*\n         IF( LSAME( DIRECT, 'F' ) ) THEN\n*\n*           Let  V =  ( V1  V2 )    (V1: first K columns)\n*           where  V1  is unit upper triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**T * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILADLC( K, M, V, LDV ) )\n               LASTC = ILADLC( LASTV, N, C, LDC )\n*\n*              W := C**T * V**T  =  (C1**T * V1**T + C2**T * V2**T) (stored in WORK)\n*\n*              W := C1**T\n*\n               DO 130 J = 1, K\n                  CALL DCOPY( LASTC, C( J, 1 ), LDC, WORK( 1, J ), 1 )\n  130          CONTINUE\n*\n*              W := W * V1**T\n*\n               CALL DTRMM( 'Right', 'Upper', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2**T*V2**T\n*\n                  CALL DGEMM( 'Transpose', 'Transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C( K+1, 1 ), LDC, V( 1, K+1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**T  or  W * T\n*\n               CALL DTRMM( 'Right', 'Upper', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V**T * W**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - V2**T * W**T\n*\n                  CALL DGEMM( 'Transpose', 'Transpose',\n     $                 LASTV-K, LASTC, K,\n     $                 -ONE, V( 1, K+1 ), LDV, WORK, LDWORK,\n     $                 ONE, C( K+1, 1 ), LDC )\n               END IF\n*\n*              W := W * V1\n*\n               CALL DTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W**T\n*\n               DO 150 J = 1, K\n                  DO 140 I = 1, LASTC\n                     C( J, I ) = C( J, I ) - WORK( I, J )\n  140             CONTINUE\n  150          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**T  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILADLC( K, N, V, LDV ) )\n               LASTC = ILADLR( M, LASTV, C, LDC )\n*\n*              W := C * V**T  =  (C1*V1**T + C2*V2**T)  (stored in WORK)\n*\n*              W := C1\n*\n               DO 160 J = 1, K\n                  CALL DCOPY( LASTC, C( 1, J ), 1, WORK( 1, J ), 1 )\n  160          CONTINUE\n*\n*              W := W * V1**T\n*\n               CALL DTRMM( 'Right', 'Upper', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2 * V2**T\n*\n                  CALL DGEMM( 'No transpose', 'Transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C( 1, K+1 ), LDC, V( 1, K+1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**T\n*\n               CALL DTRMM( 'Right', 'Upper', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - W * V2\n*\n                  CALL DGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, LASTV-K, K,\n     $                 -ONE, WORK, LDWORK, V( 1, K+1 ), LDV,\n     $                 ONE, C( 1, K+1 ), LDC )\n               END IF\n*\n*              W := W * V1\n*\n               CALL DTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 180 J = 1, K\n                  DO 170 I = 1, LASTC\n                     C( I, J ) = C( I, J ) - WORK( I, J )\n  170             CONTINUE\n  180          CONTINUE\n*\n            END IF\n*\n         ELSE\n*\n*           Let  V =  ( V1  V2 )    (V2: last K columns)\n*           where  V2  is unit lower triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**T * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILADLC( K, M, V, LDV ) )\n               LASTC = ILADLC( LASTV, N, C, LDC )\n*\n*              W := C**T * V**T  =  (C1**T * V1**T + C2**T * V2**T) (stored in WORK)\n*\n*              W := C2**T\n*\n               DO 190 J = 1, K\n                  CALL DCOPY( LASTC, C( LASTV-K+J, 1 ), LDC,\n     $                 WORK( 1, J ), 1 )\n  190          CONTINUE\n*\n*              W := W * V2**T\n*\n               CALL DTRMM( 'Right', 'Lower', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1**T * V1**T\n*\n                  CALL DGEMM( 'Transpose', 'Transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**T  or  W * T\n*\n               CALL DTRMM( 'Right', 'Lower', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V**T * W**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - V1**T * W**T\n*\n                  CALL DGEMM( 'Transpose', 'Transpose',\n     $                 LASTV-K, LASTC, K, -ONE, V, LDV, WORK, LDWORK,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2\n*\n               CALL DTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W**T\n*\n               DO 210 J = 1, K\n                  DO 200 I = 1, LASTC\n                     C( LASTV-K+J, I ) = C( LASTV-K+J, I ) - WORK(I, J)\n  200             CONTINUE\n  210          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**T  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILADLC( K, N, V, LDV ) )\n               LASTC = ILADLR( M, LASTV, C, LDC )\n*\n*              W := C * V**T  =  (C1*V1**T + C2*V2**T)  (stored in WORK)\n*\n*              W := C2\n*\n               DO 220 J = 1, K\n                  CALL DCOPY( LASTC, C( 1, LASTV-K+J ), 1,\n     $                 WORK( 1, J ), 1 )\n  220          CONTINUE\n*\n*              W := W * V2**T\n*\n               CALL DTRMM( 'Right', 'Lower', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1 * V1**T\n*\n                  CALL DGEMM( 'No transpose', 'Transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**T\n*\n               CALL DTRMM( 'Right', 'Lower', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - W * V1\n*\n                  CALL DGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, LASTV-K, K, -ONE, WORK, LDWORK, V, LDV,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2\n*\n               CALL DTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 240 J = 1, K\n                  DO 230 I = 1, LASTC\n                     C( I, LASTV-K+J ) = C( I, LASTV-K+J ) - WORK(I, J)\n  230             CONTINUE\n  240          CONTINUE\n*\n            END IF\n*\n         END IF\n      END IF\n*\n      RETURN\n*\n*     End of DLARFB\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/dlarfg.f",
    "content": "*> \\brief \\b DLARFG\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download DLARFG + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/dlarfg.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/dlarfg.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/dlarfg.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE DLARFG( N, ALPHA, X, INCX, TAU )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            INCX, N\n*       DOUBLE PRECISION   ALPHA, TAU\n*       ..\n*       .. Array Arguments ..\n*       DOUBLE PRECISION   X( * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> DLARFG generates a real elementary reflector H of order n, such\n*> that\n*>\n*>       H * ( alpha ) = ( beta ),   H**T * H = I.\n*>           (   x   )   (   0  )\n*>\n*> where alpha and beta are scalars, and x is an (n-1)-element real\n*> vector. H is represented in the form\n*>\n*>       H = I - tau * ( 1 ) * ( 1 v**T ) ,\n*>                     ( v )\n*>\n*> where tau is a real scalar and v is a real (n-1)-element\n*> vector.\n*>\n*> If the elements of x are all zero, then tau = 0 and H is taken to be\n*> the unit matrix.\n*>\n*> Otherwise  1 <= tau <= 2.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The order of the elementary reflector.\n*> \\endverbatim\n*>\n*> \\param[in,out] ALPHA\n*> \\verbatim\n*>          ALPHA is DOUBLE PRECISION\n*>          On entry, the value alpha.\n*>          On exit, it is overwritten with the value beta.\n*> \\endverbatim\n*>\n*> \\param[in,out] X\n*> \\verbatim\n*>          X is DOUBLE PRECISION array, dimension\n*>                         (1+(N-2)*abs(INCX))\n*>          On entry, the vector x.\n*>          On exit, it is overwritten with the vector v.\n*> \\endverbatim\n*>\n*> \\param[in] INCX\n*> \\verbatim\n*>          INCX is INTEGER\n*>          The increment between elements of X. INCX > 0.\n*> \\endverbatim\n*>\n*> \\param[out] TAU\n*> \\verbatim\n*>          TAU is DOUBLE PRECISION\n*>          The value tau.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup doubleOTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE DLARFG( N, ALPHA, X, INCX, TAU )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      INTEGER            INCX, N\n      DOUBLE PRECISION   ALPHA, TAU\n*     ..\n*     .. Array Arguments ..\n      DOUBLE PRECISION   X( * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ONE, ZERO\n      PARAMETER          ( ONE = 1.0D+0, ZERO = 0.0D+0 )\n*     ..\n*     .. Local Scalars ..\n      INTEGER            J, KNT\n      DOUBLE PRECISION   BETA, RSAFMN, SAFMIN, XNORM\n*     ..\n*     .. External Functions ..\n      DOUBLE PRECISION   DLAMCH, DLAPY2, DNRM2\n      EXTERNAL           DLAMCH, DLAPY2, DNRM2\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, SIGN\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           DSCAL\n*     ..\n*     .. Executable Statements ..\n*\n      IF( N.LE.1 ) THEN\n         TAU = ZERO\n         RETURN\n      END IF\n*\n      XNORM = DNRM2( N-1, X, INCX )\n*\n      IF( XNORM.EQ.ZERO ) THEN\n*\n*        H  =  I\n*\n         TAU = ZERO\n      ELSE\n*\n*        general case\n*\n         BETA = -SIGN( DLAPY2( ALPHA, XNORM ), ALPHA )\n         SAFMIN = DLAMCH( 'S' ) / DLAMCH( 'E' )\n         KNT = 0\n         IF( ABS( BETA ).LT.SAFMIN ) THEN\n*\n*           XNORM, BETA may be inaccurate; scale X and recompute them\n*\n            RSAFMN = ONE / SAFMIN\n   10       CONTINUE\n            KNT = KNT + 1\n            CALL DSCAL( N-1, RSAFMN, X, INCX )\n            BETA = BETA*RSAFMN\n            ALPHA = ALPHA*RSAFMN\n            IF( ABS( BETA ).LT.SAFMIN )\n     $         GO TO 10\n*\n*           New BETA is at most 1, at least SAFMIN\n*\n            XNORM = DNRM2( N-1, X, INCX )\n            BETA = -SIGN( DLAPY2( ALPHA, XNORM ), ALPHA )\n         END IF\n         TAU = ( BETA-ALPHA ) / BETA\n         CALL DSCAL( N-1, ONE / ( ALPHA-BETA ), X, INCX )\n*\n*        If ALPHA is subnormal, it may lose relative accuracy\n*\n         DO 20 J = 1, KNT\n            BETA = BETA*SAFMIN\n 20      CONTINUE\n         ALPHA = BETA\n      END IF\n*\n      RETURN\n*\n*     End of DLARFG\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/dlarft.f",
    "content": "*> \\brief \\b DLARFT\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download DLARFT + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/dlarft.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/dlarft.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/dlarft.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE DLARFT( DIRECT, STOREV, N, K, V, LDV, TAU, T, LDT )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          DIRECT, STOREV\n*       INTEGER            K, LDT, LDV, N\n*       ..\n*       .. Array Arguments ..\n*       DOUBLE PRECISION   T( LDT, * ), TAU( * ), V( LDV, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> DLARFT forms the triangular factor T of a real block reflector H\n*> of order n, which is defined as a product of k elementary reflectors.\n*>\n*> If DIRECT = 'F', H = H(1) H(2) . . . H(k) and T is upper triangular;\n*>\n*> If DIRECT = 'B', H = H(k) . . . H(2) H(1) and T is lower triangular.\n*>\n*> If STOREV = 'C', the vector which defines the elementary reflector\n*> H(i) is stored in the i-th column of the array V, and\n*>\n*>    H  =  I - V * T * V**T\n*>\n*> If STOREV = 'R', the vector which defines the elementary reflector\n*> H(i) is stored in the i-th row of the array V, and\n*>\n*>    H  =  I - V**T * T * V\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] DIRECT\n*> \\verbatim\n*>          DIRECT is CHARACTER*1\n*>          Specifies the order in which the elementary reflectors are\n*>          multiplied to form the block reflector:\n*>          = 'F': H = H(1) H(2) . . . H(k) (Forward)\n*>          = 'B': H = H(k) . . . H(2) H(1) (Backward)\n*> \\endverbatim\n*>\n*> \\param[in] STOREV\n*> \\verbatim\n*>          STOREV is CHARACTER*1\n*>          Specifies how the vectors which define the elementary\n*>          reflectors are stored (see also Further Details):\n*>          = 'C': columnwise\n*>          = 'R': rowwise\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The order of the block reflector H. N >= 0.\n*> \\endverbatim\n*>\n*> \\param[in] K\n*> \\verbatim\n*>          K is INTEGER\n*>          The order of the triangular factor T (= the number of\n*>          elementary reflectors). K >= 1.\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is DOUBLE PRECISION array, dimension\n*>                               (LDV,K) if STOREV = 'C'\n*>                               (LDV,N) if STOREV = 'R'\n*>          The matrix V. See further details.\n*> \\endverbatim\n*>\n*> \\param[in] LDV\n*> \\verbatim\n*>          LDV is INTEGER\n*>          The leading dimension of the array V.\n*>          If STOREV = 'C', LDV >= max(1,N); if STOREV = 'R', LDV >= K.\n*> \\endverbatim\n*>\n*> \\param[in] TAU\n*> \\verbatim\n*>          TAU is DOUBLE PRECISION array, dimension (K)\n*>          TAU(i) must contain the scalar factor of the elementary\n*>          reflector H(i).\n*> \\endverbatim\n*>\n*> \\param[out] T\n*> \\verbatim\n*>          T is DOUBLE PRECISION array, dimension (LDT,K)\n*>          The k by k triangular factor T of the block reflector.\n*>          If DIRECT = 'F', T is upper triangular; if DIRECT = 'B', T is\n*>          lower triangular. The rest of the array is not used.\n*> \\endverbatim\n*>\n*> \\param[in] LDT\n*> \\verbatim\n*>          LDT is INTEGER\n*>          The leading dimension of the array T. LDT >= K.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup doubleOTHERauxiliary\n*\n*> \\par Further Details:\n*  =====================\n*>\n*> \\verbatim\n*>\n*>  The shape of the matrix V and the storage of the vectors which define\n*>  the H(i) is best illustrated by the following example with n = 5 and\n*>  k = 3. The elements equal to 1 are not stored.\n*>\n*>  DIRECT = 'F' and STOREV = 'C':         DIRECT = 'F' and STOREV = 'R':\n*>\n*>               V = (  1       )                 V = (  1 v1 v1 v1 v1 )\n*>                   ( v1  1    )                     (     1 v2 v2 v2 )\n*>                   ( v1 v2  1 )                     (        1 v3 v3 )\n*>                   ( v1 v2 v3 )\n*>                   ( v1 v2 v3 )\n*>\n*>  DIRECT = 'B' and STOREV = 'C':         DIRECT = 'B' and STOREV = 'R':\n*>\n*>               V = ( v1 v2 v3 )                 V = ( v1 v1  1       )\n*>                   ( v1 v2 v3 )                     ( v2 v2 v2  1    )\n*>                   (  1 v2 v3 )                     ( v3 v3 v3 v3  1 )\n*>                   (     1 v3 )\n*>                   (        1 )\n*> \\endverbatim\n*>\n*  =====================================================================\n      SUBROUTINE DLARFT( DIRECT, STOREV, N, K, V, LDV, TAU, T, LDT )\n*\n*  -- LAPACK auxiliary routine (version 3.4.1) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*     .. Scalar Arguments ..\n      CHARACTER          DIRECT, STOREV\n      INTEGER            K, LDT, LDV, N\n*     ..\n*     .. Array Arguments ..\n      DOUBLE PRECISION   T( LDT, * ), TAU( * ), V( LDV, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ONE, ZERO\n      PARAMETER          ( ONE = 1.0D+0, ZERO = 0.0D+0 )\n*     ..\n*     .. Local Scalars ..\n      INTEGER            I, J, PREVLASTV, LASTV\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           DGEMV, DTRMV\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      EXTERNAL           LSAME\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick return if possible\n*\n      IF( N.EQ.0 )\n     $   RETURN\n*\n      IF( LSAME( DIRECT, 'F' ) ) THEN\n         PREVLASTV = N\n         DO I = 1, K\n            PREVLASTV = MAX( I, PREVLASTV )\n            IF( TAU( I ).EQ.ZERO ) THEN\n*\n*              H(i)  =  I\n*\n               DO J = 1, I\n                  T( J, I ) = ZERO\n               END DO\n            ELSE\n*\n*              general case\n*\n               IF( LSAME( STOREV, 'C' ) ) THEN\n*                 Skip any trailing zeros.\n                  DO LASTV = N, I+1, -1\n                     IF( V( LASTV, I ).NE.ZERO ) EXIT\n                  END DO\n                  DO J = 1, I-1\n                     T( J, I ) = -TAU( I ) * V( I , J )\n                  END DO   \n                  J = MIN( LASTV, PREVLASTV )\n*\n*                 T(1:i-1,i) := - tau(i) * V(i:j,1:i-1)**T * V(i:j,i)\n*\n                  CALL DGEMV( 'Transpose', J-I, I-1, -TAU( I ), \n     $                        V( I+1, 1 ), LDV, V( I+1, I ), 1, ONE, \n     $                        T( 1, I ), 1 )\n               ELSE\n*                 Skip any trailing zeros.\n                  DO LASTV = N, I+1, -1\n                     IF( V( I, LASTV ).NE.ZERO ) EXIT\n                  END DO\n                  DO J = 1, I-1\n                     T( J, I ) = -TAU( I ) * V( J , I )\n                  END DO   \n                  J = MIN( LASTV, PREVLASTV )\n*\n*                 T(1:i-1,i) := - tau(i) * V(1:i-1,i:j) * V(i,i:j)**T\n*\n                  CALL DGEMV( 'No transpose', I-1, J-I, -TAU( I ),\n     $                        V( 1, I+1 ), LDV, V( I, I+1 ), LDV, ONE,\n     $                        T( 1, I ), 1 )\n               END IF\n*\n*              T(1:i-1,i) := T(1:i-1,1:i-1) * T(1:i-1,i)\n*\n               CALL DTRMV( 'Upper', 'No transpose', 'Non-unit', I-1, T,\n     $                     LDT, T( 1, I ), 1 )\n               T( I, I ) = TAU( I )\n               IF( I.GT.1 ) THEN\n                  PREVLASTV = MAX( PREVLASTV, LASTV )\n               ELSE\n                  PREVLASTV = LASTV\n               END IF\n            END IF\n         END DO\n      ELSE\n         PREVLASTV = 1\n         DO I = K, 1, -1\n            IF( TAU( I ).EQ.ZERO ) THEN\n*\n*              H(i)  =  I\n*\n               DO J = I, K\n                  T( J, I ) = ZERO\n               END DO\n            ELSE\n*\n*              general case\n*\n               IF( I.LT.K ) THEN\n                  IF( LSAME( STOREV, 'C' ) ) THEN\n*                    Skip any leading zeros.\n                     DO LASTV = 1, I-1\n                        IF( V( LASTV, I ).NE.ZERO ) EXIT\n                     END DO\n                     DO J = I+1, K\n                        T( J, I ) = -TAU( I ) * V( N-K+I , J )\n                     END DO   \n                     J = MAX( LASTV, PREVLASTV )\n*\n*                    T(i+1:k,i) = -tau(i) * V(j:n-k+i,i+1:k)**T * V(j:n-k+i,i)\n*\n                     CALL DGEMV( 'Transpose', N-K+I-J, K-I, -TAU( I ),\n     $                           V( J, I+1 ), LDV, V( J, I ), 1, ONE,\n     $                           T( I+1, I ), 1 )\n                  ELSE\n*                    Skip any leading zeros.\n                     DO LASTV = 1, I-1\n                        IF( V( I, LASTV ).NE.ZERO ) EXIT\n                     END DO\n                     DO J = I+1, K\n                        T( J, I ) = -TAU( I ) * V( J, N-K+I )\n                     END DO   \n                     J = MAX( LASTV, PREVLASTV )\n*\n*                    T(i+1:k,i) = -tau(i) * V(i+1:k,j:n-k+i) * V(i,j:n-k+i)**T\n*\n                     CALL DGEMV( 'No transpose', K-I, N-K+I-J,\n     $                    -TAU( I ), V( I+1, J ), LDV, V( I, J ), LDV,\n     $                    ONE, T( I+1, I ), 1 )\n                  END IF\n*\n*                 T(i+1:k,i) := T(i+1:k,i+1:k) * T(i+1:k,i)\n*\n                  CALL DTRMV( 'Lower', 'No transpose', 'Non-unit', K-I,\n     $                        T( I+1, I+1 ), LDT, T( I+1, I ), 1 )\n                  IF( I.GT.1 ) THEN\n                     PREVLASTV = MIN( PREVLASTV, LASTV )\n                  ELSE\n                     PREVLASTV = LASTV\n                  END IF\n               END IF\n               T( I, I ) = TAU( I )\n            END IF\n         END DO\n      END IF\n      RETURN\n*\n*     End of DLARFT\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/double.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define SCALAR        double\n#define SCALAR_SUFFIX d\n#define SCALAR_SUFFIX_UP \"D\"\n#define ISCOMPLEX     0\n\n#include \"cholesky.cpp\"\n#include \"lu.cpp\"\n#include \"eigenvalues.cpp\"\n#include \"svd.cpp\"\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/dsecnd_NONE.f",
    "content": "*> \\brief \\b DSECND returns nothing\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*      DOUBLE PRECISION FUNCTION DSECND( )\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*>  DSECND returns nothing instead of returning the user time for a process in seconds.\n*>  If you are using that routine, it means that neither EXTERNAL ETIME,\n*>  EXTERNAL ETIME_, INTERNAL ETIME, INTERNAL CPU_TIME is available  on\n*>  your machine.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      DOUBLE PRECISION FUNCTION DSECND( )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n* =====================================================================\n*\n      DSECND = 0.0D+0\n      RETURN\n*\n*     End of DSECND\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/eigenvalues.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"lapack_common.h\"\n#include <Eigen/Eigenvalues>\n\n// computes eigen values and vectors of a general N-by-N matrix A\nEIGEN_LAPACK_FUNC(syev,(char *jobz, char *uplo, int* n, Scalar* a, int *lda, Scalar* w, Scalar* /*work*/, int* lwork, int *info))\n{\n  // TODO exploit the work buffer\n  bool query_size = *lwork==-1;\n  \n  *info = 0;\n        if(*jobz!='N' && *jobz!='V')                    *info = -1;\n  else  if(UPLO(*uplo)==INVALID)                        *info = -2;\n  else  if(*n<0)                                        *info = -3;\n  else  if(*lda<std::max(1,*n))                         *info = -5;\n  else  if((!query_size) && *lwork<std::max(1,3**n-1))  *info = -8;\n    \n  if(*info!=0)\n  {\n    int e = -*info;\n    return xerbla_(SCALAR_SUFFIX_UP\"SYEV \", &e, 6);\n  }\n  \n  if(query_size)\n  {\n    *lwork = 0;\n    return 0;\n  }\n  \n  if(*n==0)\n    return 0;\n  \n  PlainMatrixType mat(*n,*n);\n  if(UPLO(*uplo)==UP) mat = matrix(a,*n,*n,*lda).adjoint();\n  else                mat = matrix(a,*n,*n,*lda);\n  \n  bool computeVectors = *jobz=='V' || *jobz=='v';\n  SelfAdjointEigenSolver<PlainMatrixType> eig(mat,computeVectors?ComputeEigenvectors:EigenvaluesOnly);\n  \n  if(eig.info()==NoConvergence)\n  {\n    make_vector(w,*n).setZero();\n    if(computeVectors)\n      matrix(a,*n,*n,*lda).setIdentity();\n    //*info = 1;\n    return 0;\n  }\n  \n  make_vector(w,*n) = eig.eigenvalues();\n  if(computeVectors)\n    matrix(a,*n,*n,*lda) = eig.eigenvectors();\n  \n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/ilaclc.f",
    "content": "*> \\brief \\b ILACLC\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ILACLC + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/ilaclc.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/ilaclc.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/ilaclc.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       INTEGER FUNCTION ILACLC( M, N, A, LDA )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            M, N, LDA\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX            A( LDA, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ILACLC scans A for its last non-zero column.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] A\n*> \\verbatim\n*>          A is COMPLEX array, dimension (LDA,N)\n*>          The m by n matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] LDA\n*> \\verbatim\n*>          LDA is INTEGER\n*>          The leading dimension of the array A. LDA >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complexOTHERauxiliary\n*\n*  =====================================================================\n      INTEGER FUNCTION ILACLC( M, N, A, LDA )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      INTEGER            M, N, LDA\n*     ..\n*     .. Array Arguments ..\n      COMPLEX            A( LDA, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      COMPLEX          ZERO\n      PARAMETER ( ZERO = (0.0E+0, 0.0E+0) )\n*     ..\n*     .. Local Scalars ..\n      INTEGER I\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick test for the common case where one corner is non-zero.\n      IF( N.EQ.0 ) THEN\n         ILACLC = N\n      ELSE IF( A(1, N).NE.ZERO .OR. A(M, N).NE.ZERO ) THEN\n         ILACLC = N\n      ELSE\n*     Now scan each column from the end, returning with the first non-zero.\n         DO ILACLC = N, 1, -1\n            DO I = 1, M\n               IF( A(I, ILACLC).NE.ZERO ) RETURN\n            END DO\n         END DO\n      END IF\n      RETURN\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/ilaclr.f",
    "content": "*> \\brief \\b ILACLR\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ILACLR + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/ilaclr.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/ilaclr.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/ilaclr.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       INTEGER FUNCTION ILACLR( M, N, A, LDA )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            M, N, LDA\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX            A( LDA, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ILACLR scans A for its last non-zero row.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] A\n*> \\verbatim\n*>          A is array, dimension (LDA,N)\n*>          The m by n matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] LDA\n*> \\verbatim\n*>          LDA is INTEGER\n*>          The leading dimension of the array A. LDA >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup complexOTHERauxiliary\n*\n*  =====================================================================\n      INTEGER FUNCTION ILACLR( M, N, A, LDA )\n*\n*  -- LAPACK auxiliary routine (version 3.4.1) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*     .. Scalar Arguments ..\n      INTEGER            M, N, LDA\n*     ..\n*     .. Array Arguments ..\n      COMPLEX            A( LDA, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      COMPLEX          ZERO\n      PARAMETER ( ZERO = (0.0E+0, 0.0E+0) )\n*     ..\n*     .. Local Scalars ..\n      INTEGER I, J\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick test for the common case where one corner is non-zero.\n      IF( M.EQ.0 ) THEN\n         ILACLR = M\n      ELSE IF( A(M, 1).NE.ZERO .OR. A(M, N).NE.ZERO ) THEN\n         ILACLR = M\n      ELSE\n*     Scan up each column tracking the last zero row seen.\n         ILACLR = 0\n         DO J = 1, N\n            I=M\n            DO WHILE((A(MAX(I,1),J).EQ.ZERO).AND.(I.GE.1))\n               I=I-1\n            ENDDO\n            ILACLR = MAX( ILACLR, I )\n         END DO\n      END IF\n      RETURN\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/iladlc.f",
    "content": "*> \\brief \\b ILADLC\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ILADLC + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/iladlc.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/iladlc.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/iladlc.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       INTEGER FUNCTION ILADLC( M, N, A, LDA )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            M, N, LDA\n*       ..\n*       .. Array Arguments ..\n*       DOUBLE PRECISION   A( LDA, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ILADLC scans A for its last non-zero column.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] A\n*> \\verbatim\n*>          A is DOUBLE PRECISION array, dimension (LDA,N)\n*>          The m by n matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] LDA\n*> \\verbatim\n*>          LDA is INTEGER\n*>          The leading dimension of the array A. LDA >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      INTEGER FUNCTION ILADLC( M, N, A, LDA )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      INTEGER            M, N, LDA\n*     ..\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( LDA, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      DOUBLE PRECISION ZERO\n      PARAMETER ( ZERO = 0.0D+0 )\n*     ..\n*     .. Local Scalars ..\n      INTEGER I\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick test for the common case where one corner is non-zero.\n      IF( N.EQ.0 ) THEN\n         ILADLC = N\n      ELSE IF( A(1, N).NE.ZERO .OR. A(M, N).NE.ZERO ) THEN\n         ILADLC = N\n      ELSE\n*     Now scan each column from the end, returning with the first non-zero.\n         DO ILADLC = N, 1, -1\n            DO I = 1, M\n               IF( A(I, ILADLC).NE.ZERO ) RETURN\n            END DO\n         END DO\n      END IF\n      RETURN\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/iladlr.f",
    "content": "*> \\brief \\b ILADLR\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ILADLR + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/iladlr.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/iladlr.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/iladlr.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       INTEGER FUNCTION ILADLR( M, N, A, LDA )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            M, N, LDA\n*       ..\n*       .. Array Arguments ..\n*       DOUBLE PRECISION   A( LDA, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ILADLR scans A for its last non-zero row.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] A\n*> \\verbatim\n*>          A is DOUBLE PRECISION array, dimension (LDA,N)\n*>          The m by n matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] LDA\n*> \\verbatim\n*>          LDA is INTEGER\n*>          The leading dimension of the array A. LDA >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      INTEGER FUNCTION ILADLR( M, N, A, LDA )\n*\n*  -- LAPACK auxiliary routine (version 3.4.1) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*     .. Scalar Arguments ..\n      INTEGER            M, N, LDA\n*     ..\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( LDA, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      DOUBLE PRECISION ZERO\n      PARAMETER ( ZERO = 0.0D+0 )\n*     ..\n*     .. Local Scalars ..\n      INTEGER I, J\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick test for the common case where one corner is non-zero.\n      IF( M.EQ.0 ) THEN\n         ILADLR = M\n      ELSE IF( A(M, 1).NE.ZERO .OR. A(M, N).NE.ZERO ) THEN\n         ILADLR = M\n      ELSE\n*     Scan up each column tracking the last zero row seen.\n         ILADLR = 0\n         DO J = 1, N\n            I=M\n            DO WHILE((A(MAX(I,1),J).EQ.ZERO).AND.(I.GE.1))\n               I=I-1\n            ENDDO\n            ILADLR = MAX( ILADLR, I )\n         END DO\n      END IF\n      RETURN\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/ilaslc.f",
    "content": "*> \\brief \\b ILASLC\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ILASLC + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/ilaslc.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/ilaslc.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/ilaslc.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       INTEGER FUNCTION ILASLC( M, N, A, LDA )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            M, N, LDA\n*       ..\n*       .. Array Arguments ..\n*       REAL               A( LDA, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ILASLC scans A for its last non-zero column.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] A\n*> \\verbatim\n*>          A is REAL array, dimension (LDA,N)\n*>          The m by n matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] LDA\n*> \\verbatim\n*>          LDA is INTEGER\n*>          The leading dimension of the array A. LDA >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup realOTHERauxiliary\n*\n*  =====================================================================\n      INTEGER FUNCTION ILASLC( M, N, A, LDA )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      INTEGER            M, N, LDA\n*     ..\n*     .. Array Arguments ..\n      REAL               A( LDA, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      REAL             ZERO\n      PARAMETER ( ZERO = 0.0D+0 )\n*     ..\n*     .. Local Scalars ..\n      INTEGER I\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick test for the common case where one corner is non-zero.\n      IF( N.EQ.0 ) THEN\n         ILASLC = N\n      ELSE IF( A(1, N).NE.ZERO .OR. A(M, N).NE.ZERO ) THEN\n         ILASLC = N\n      ELSE\n*     Now scan each column from the end, returning with the first non-zero.\n         DO ILASLC = N, 1, -1\n            DO I = 1, M\n               IF( A(I, ILASLC).NE.ZERO ) RETURN\n            END DO\n         END DO\n      END IF\n      RETURN\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/ilaslr.f",
    "content": "*> \\brief \\b ILASLR\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ILASLR + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/ilaslr.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/ilaslr.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/ilaslr.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       INTEGER FUNCTION ILASLR( M, N, A, LDA )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            M, N, LDA\n*       ..\n*       .. Array Arguments ..\n*       REAL               A( LDA, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ILASLR scans A for its last non-zero row.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] A\n*> \\verbatim\n*>          A is REAL array, dimension (LDA,N)\n*>          The m by n matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] LDA\n*> \\verbatim\n*>          LDA is INTEGER\n*>          The leading dimension of the array A. LDA >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup realOTHERauxiliary\n*\n*  =====================================================================\n      INTEGER FUNCTION ILASLR( M, N, A, LDA )\n*\n*  -- LAPACK auxiliary routine (version 3.4.1) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*     .. Scalar Arguments ..\n      INTEGER            M, N, LDA\n*     ..\n*     .. Array Arguments ..\n      REAL               A( LDA, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      REAL             ZERO\n      PARAMETER ( ZERO = 0.0E+0 )\n*     ..\n*     .. Local Scalars ..\n      INTEGER I, J\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick test for the common case where one corner is non-zero.\n      IF( M.EQ.0 ) THEN\n         ILASLR = M\n      ELSEIF( A(M, 1).NE.ZERO .OR. A(M, N).NE.ZERO ) THEN\n         ILASLR = M\n      ELSE\n*     Scan up each column tracking the last zero row seen.\n         ILASLR = 0\n         DO J = 1, N\n            I=M\n            DO WHILE((A(MAX(I,1),J).EQ.ZERO).AND.(I.GE.1))\n               I=I-1\n            ENDDO\n            ILASLR = MAX( ILASLR, I )\n         END DO\n      END IF\n      RETURN\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/ilazlc.f",
    "content": "*> \\brief \\b ILAZLC\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ILAZLC + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/ilazlc.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/ilazlc.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/ilazlc.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       INTEGER FUNCTION ILAZLC( M, N, A, LDA )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            M, N, LDA\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX*16         A( LDA, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ILAZLC scans A for its last non-zero column.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] A\n*> \\verbatim\n*>          A is COMPLEX*16 array, dimension (LDA,N)\n*>          The m by n matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] LDA\n*> \\verbatim\n*>          LDA is INTEGER\n*>          The leading dimension of the array A. LDA >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complex16OTHERauxiliary\n*\n*  =====================================================================\n      INTEGER FUNCTION ILAZLC( M, N, A, LDA )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      INTEGER            M, N, LDA\n*     ..\n*     .. Array Arguments ..\n      COMPLEX*16         A( LDA, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      COMPLEX*16       ZERO\n      PARAMETER ( ZERO = (0.0D+0, 0.0D+0) )\n*     ..\n*     .. Local Scalars ..\n      INTEGER I\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick test for the common case where one corner is non-zero.\n      IF( N.EQ.0 ) THEN\n         ILAZLC = N\n      ELSE IF( A(1, N).NE.ZERO .OR. A(M, N).NE.ZERO ) THEN\n         ILAZLC = N\n      ELSE\n*     Now scan each column from the end, returning with the first non-zero.\n         DO ILAZLC = N, 1, -1\n            DO I = 1, M\n               IF( A(I, ILAZLC).NE.ZERO ) RETURN\n            END DO\n         END DO\n      END IF\n      RETURN\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/ilazlr.f",
    "content": "*> \\brief \\b ILAZLR\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ILAZLR + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/ilazlr.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/ilazlr.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/ilazlr.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       INTEGER FUNCTION ILAZLR( M, N, A, LDA )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            M, N, LDA\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX*16         A( LDA, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ILAZLR scans A for its last non-zero row.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] A\n*> \\verbatim\n*>          A is COMPLEX*16 array, dimension (LDA,N)\n*>          The m by n matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] LDA\n*> \\verbatim\n*>          LDA is INTEGER\n*>          The leading dimension of the array A. LDA >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup complex16OTHERauxiliary\n*\n*  =====================================================================\n      INTEGER FUNCTION ILAZLR( M, N, A, LDA )\n*\n*  -- LAPACK auxiliary routine (version 3.4.1) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*     .. Scalar Arguments ..\n      INTEGER            M, N, LDA\n*     ..\n*     .. Array Arguments ..\n      COMPLEX*16         A( LDA, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      COMPLEX*16       ZERO\n      PARAMETER ( ZERO = (0.0D+0, 0.0D+0) )\n*     ..\n*     .. Local Scalars ..\n      INTEGER I, J\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick test for the common case where one corner is non-zero.\n      IF( M.EQ.0 ) THEN\n         ILAZLR = M\n      ELSE IF( A(M, 1).NE.ZERO .OR. A(M, N).NE.ZERO ) THEN\n         ILAZLR = M\n      ELSE\n*     Scan up each column tracking the last zero row seen.\n         ILAZLR = 0\n         DO J = 1, N\n            I=M\n            DO WHILE((A(MAX(I,1),J).EQ.ZERO).AND.(I.GE.1))\n               I=I-1\n            ENDDO\n            ILAZLR = MAX( ILAZLR, I )\n         END DO\n      END IF\n      RETURN\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/lapack_common.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_LAPACK_COMMON_H\n#define EIGEN_LAPACK_COMMON_H\n\n#include \"../blas/common.h\"\n#include \"../Eigen/src/misc/lapack.h\"\n\n#define EIGEN_LAPACK_FUNC(FUNC,ARGLIST)               \\\n  extern \"C\" { int EIGEN_BLAS_FUNC(FUNC) ARGLIST; }   \\\n  int EIGEN_BLAS_FUNC(FUNC) ARGLIST\n\ntypedef Eigen::Map<Eigen::Transpositions<Eigen::Dynamic,Eigen::Dynamic,int> > PivotsType;\n\n#if ISCOMPLEX\n#define EIGEN_LAPACK_ARG_IF_COMPLEX(X) X,\n#else\n#define EIGEN_LAPACK_ARG_IF_COMPLEX(X)\n#endif\n\n\n#endif // EIGEN_LAPACK_COMMON_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/lu.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010-2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"common.h\"\n#include <Eigen/LU>\n\n// computes an LU factorization of a general M-by-N matrix A using partial pivoting with row interchanges\nEIGEN_LAPACK_FUNC(getrf,(int *m, int *n, RealScalar *pa, int *lda, int *ipiv, int *info))\n{\n  *info = 0;\n        if(*m<0)                  *info = -1;\n  else  if(*n<0)                  *info = -2;\n  else  if(*lda<std::max(1,*m))   *info = -4;\n  if(*info!=0)\n  {\n    int e = -*info;\n    return xerbla_(SCALAR_SUFFIX_UP\"GETRF\", &e, 6);\n  }\n\n  if(*m==0 || *n==0)\n    return 0;\n\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  int nb_transpositions;\n  int ret = int(Eigen::internal::partial_lu_impl<Scalar,ColMajor,int>\n                     ::blocked_lu(*m, *n, a, *lda, ipiv, nb_transpositions));\n\n  for(int i=0; i<std::min(*m,*n); ++i)\n    ipiv[i]++;\n\n  if(ret>=0)\n    *info = ret+1;\n\n  return 0;\n}\n\n//GETRS solves a system of linear equations\n//    A * X = B  or  A' * X = B\n//  with a general N-by-N matrix A using the LU factorization computed  by GETRF\nEIGEN_LAPACK_FUNC(getrs,(char *trans, int *n, int *nrhs, RealScalar *pa, int *lda, int *ipiv, RealScalar *pb, int *ldb, int *info))\n{\n  *info = 0;\n        if(OP(*trans)==INVALID)  *info = -1;\n  else  if(*n<0)                 *info = -2;\n  else  if(*nrhs<0)              *info = -3;\n  else  if(*lda<std::max(1,*n))  *info = -5;\n  else  if(*ldb<std::max(1,*n))  *info = -8;\n  if(*info!=0)\n  {\n    int e = -*info;\n    return xerbla_(SCALAR_SUFFIX_UP\"GETRS\", &e, 6);\n  }\n\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  Scalar* b = reinterpret_cast<Scalar*>(pb);\n  MatrixType lu(a,*n,*n,*lda);\n  MatrixType B(b,*n,*nrhs,*ldb);\n\n  for(int i=0; i<*n; ++i)\n    ipiv[i]--;\n  if(OP(*trans)==NOTR)\n  {\n    B = PivotsType(ipiv,*n) * B;\n    lu.triangularView<UnitLower>().solveInPlace(B);\n    lu.triangularView<Upper>().solveInPlace(B);\n  }\n  else if(OP(*trans)==TR)\n  {\n    lu.triangularView<Upper>().transpose().solveInPlace(B);\n    lu.triangularView<UnitLower>().transpose().solveInPlace(B);\n    B = PivotsType(ipiv,*n).transpose() * B;\n  }\n  else if(OP(*trans)==ADJ)\n  {\n    lu.triangularView<Upper>().adjoint().solveInPlace(B);\n    lu.triangularView<UnitLower>().adjoint().solveInPlace(B);\n    B = PivotsType(ipiv,*n).transpose() * B;\n  }\n  for(int i=0; i<*n; ++i)\n    ipiv[i]++;\n\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/second_NONE.f",
    "content": "*> \\brief \\b SECOND returns nothing\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*      REAL FUNCTION SECOND( )\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*>  SECOND returns nothing instead of returning the user time for a process in seconds.\n*>  If you are using that routine, it means that neither EXTERNAL ETIME,\n*>  EXTERNAL ETIME_, INTERNAL ETIME, INTERNAL CPU_TIME is available  on\n*>  your machine.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      REAL FUNCTION SECOND( )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n* =====================================================================\n*\n      SECOND = 0.0E+0\n      RETURN\n*\n*     End of SECOND\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/single.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define SCALAR        float\n#define SCALAR_SUFFIX s\n#define SCALAR_SUFFIX_UP \"S\"\n#define ISCOMPLEX     0\n\n#include \"cholesky.cpp\"\n#include \"lu.cpp\"\n#include \"eigenvalues.cpp\"\n#include \"svd.cpp\"\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/sladiv.f",
    "content": "*> \\brief \\b SLADIV\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download SLADIV + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/sladiv.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/sladiv.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/sladiv.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE SLADIV( A, B, C, D, P, Q )\n* \n*       .. Scalar Arguments ..\n*       REAL               A, B, C, D, P, Q\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> SLADIV performs complex division in  real arithmetic\n*>\n*>                       a + i*b\n*>            p + i*q = ---------\n*>                       c + i*d\n*>\n*> The algorithm is due to Robert L. Smith and can be found\n*> in D. Knuth, The art of Computer Programming, Vol.2, p.195\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] A\n*> \\verbatim\n*>          A is REAL\n*> \\endverbatim\n*>\n*> \\param[in] B\n*> \\verbatim\n*>          B is REAL\n*> \\endverbatim\n*>\n*> \\param[in] C\n*> \\verbatim\n*>          C is REAL\n*> \\endverbatim\n*>\n*> \\param[in] D\n*> \\verbatim\n*>          D is REAL\n*>          The scalars a, b, c, and d in the above expression.\n*> \\endverbatim\n*>\n*> \\param[out] P\n*> \\verbatim\n*>          P is REAL\n*> \\endverbatim\n*>\n*> \\param[out] Q\n*> \\verbatim\n*>          Q is REAL\n*>          The scalars p and q in the above expression.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE SLADIV( A, B, C, D, P, Q )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      REAL               A, B, C, D, P, Q\n*     ..\n*\n*  =====================================================================\n*\n*     .. Local Scalars ..\n      REAL               E, F\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS\n*     ..\n*     .. Executable Statements ..\n*\n      IF( ABS( D ).LT.ABS( C ) ) THEN\n         E = D / C\n         F = C + D*E\n         P = ( A+B*E ) / F\n         Q = ( B-A*E ) / F\n      ELSE\n         E = C / D\n         F = D + C*E\n         P = ( B+A*E ) / F\n         Q = ( -A+B*E ) / F\n      END IF\n*\n      RETURN\n*\n*     End of SLADIV\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/slamch.f",
    "content": "*> \\brief \\b SLAMCH\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*      REAL             FUNCTION SLAMCH( CMACH )\n*\n*     .. Scalar Arguments ..\n*      CHARACTER          CMACH\n*     ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> SLAMCH determines single precision machine parameters.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] CMACH\n*> \\verbatim\n*>          Specifies the value to be returned by SLAMCH:\n*>          = 'E' or 'e',   SLAMCH := eps\n*>          = 'S' or 's ,   SLAMCH := sfmin\n*>          = 'B' or 'b',   SLAMCH := base\n*>          = 'P' or 'p',   SLAMCH := eps*base\n*>          = 'N' or 'n',   SLAMCH := t\n*>          = 'R' or 'r',   SLAMCH := rnd\n*>          = 'M' or 'm',   SLAMCH := emin\n*>          = 'U' or 'u',   SLAMCH := rmin\n*>          = 'L' or 'l',   SLAMCH := emax\n*>          = 'O' or 'o',   SLAMCH := rmax\n*>          where\n*>          eps   = relative machine precision\n*>          sfmin = safe minimum, such that 1/sfmin does not overflow\n*>          base  = base of the machine\n*>          prec  = eps*base\n*>          t     = number of (base) digits in the mantissa\n*>          rnd   = 1.0 when rounding occurs in addition, 0.0 otherwise\n*>          emin  = minimum exponent before (gradual) underflow\n*>          rmin  = underflow threshold - base**(emin-1)\n*>          emax  = largest exponent before overflow\n*>          rmax  = overflow threshold  - (base**emax)*(1-eps)\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      REAL             FUNCTION SLAMCH( CMACH )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      CHARACTER          CMACH\n*     ..\n*\n* =====================================================================\n*\n*     .. Parameters ..\n      REAL               ONE, ZERO\n      PARAMETER          ( ONE = 1.0E+0, ZERO = 0.0E+0 )\n*     ..\n*     .. Local Scalars ..\n      REAL               RND, EPS, SFMIN, SMALL, RMACH\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      EXTERNAL           LSAME\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          DIGITS, EPSILON, HUGE, MAXEXPONENT,\n     $                   MINEXPONENT, RADIX, TINY\n*     ..\n*     .. Executable Statements ..\n*\n*\n*     Assume rounding, not chopping. Always.\n*\n      RND = ONE\n*\n      IF( ONE.EQ.RND ) THEN\n         EPS = EPSILON(ZERO) * 0.5\n      ELSE\n         EPS = EPSILON(ZERO)\n      END IF\n*\n      IF( LSAME( CMACH, 'E' ) ) THEN\n         RMACH = EPS\n      ELSE IF( LSAME( CMACH, 'S' ) ) THEN\n         SFMIN = TINY(ZERO)\n         SMALL = ONE / HUGE(ZERO)\n         IF( SMALL.GE.SFMIN ) THEN\n*\n*           Use SMALL plus a bit, to avoid the possibility of rounding\n*           causing overflow when computing  1/sfmin.\n*\n            SFMIN = SMALL*( ONE+EPS )\n         END IF\n         RMACH = SFMIN\n      ELSE IF( LSAME( CMACH, 'B' ) ) THEN\n         RMACH = RADIX(ZERO)\n      ELSE IF( LSAME( CMACH, 'P' ) ) THEN\n         RMACH = EPS * RADIX(ZERO)\n      ELSE IF( LSAME( CMACH, 'N' ) ) THEN\n         RMACH = DIGITS(ZERO)\n      ELSE IF( LSAME( CMACH, 'R' ) ) THEN\n         RMACH = RND\n      ELSE IF( LSAME( CMACH, 'M' ) ) THEN\n         RMACH = MINEXPONENT(ZERO)\n      ELSE IF( LSAME( CMACH, 'U' ) ) THEN\n         RMACH = tiny(zero)\n      ELSE IF( LSAME( CMACH, 'L' ) ) THEN\n         RMACH = MAXEXPONENT(ZERO)\n      ELSE IF( LSAME( CMACH, 'O' ) ) THEN\n         RMACH = HUGE(ZERO)\n      ELSE\n         RMACH = ZERO\n      END IF\n*\n      SLAMCH = RMACH\n      RETURN\n*\n*     End of SLAMCH\n*\n      END\n************************************************************************\n*> \\brief \\b SLAMC3\n*> \\details\n*> \\b Purpose:\n*> \\verbatim\n*> SLAMC3  is intended to force  A  and  B  to be stored prior to doing\n*> the addition of  A  and  B ,  for use in situations where optimizers\n*> might hold one of these in a register.\n*> \\endverbatim\n*> \\author LAPACK is a software package provided by Univ. of Tennessee, Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..\n*> \\date November 2011\n*> \\ingroup auxOTHERauxiliary\n*>\n*> \\param[in] A\n*> \\verbatim\n*> \\endverbatim\n*>\n*> \\param[in] B\n*> \\verbatim\n*>          The values A and B.\n*> \\endverbatim\n*>\n*\n      REAL             FUNCTION SLAMC3( A, B )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*     Univ. of Tennessee, Univ. of California Berkeley and NAG Ltd..\n*     November 2010\n*\n*     .. Scalar Arguments ..\n      REAL               A, B\n*     ..\n* =====================================================================\n*\n*     .. Executable Statements ..\n*\n      SLAMC3 = A + B\n*\n      RETURN\n*\n*     End of SLAMC3\n*\n      END\n*\n************************************************************************\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/slapy2.f",
    "content": "*> \\brief \\b SLAPY2\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download SLAPY2 + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/slapy2.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/slapy2.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/slapy2.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       REAL             FUNCTION SLAPY2( X, Y )\n* \n*       .. Scalar Arguments ..\n*       REAL               X, Y\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> SLAPY2 returns sqrt(x**2+y**2), taking care not to cause unnecessary\n*> overflow.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] X\n*> \\verbatim\n*>          X is REAL\n*> \\endverbatim\n*>\n*> \\param[in] Y\n*> \\verbatim\n*>          Y is REAL\n*>          X and Y specify the values x and y.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      REAL             FUNCTION SLAPY2( X, Y )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      REAL               X, Y\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      REAL               ZERO\n      PARAMETER          ( ZERO = 0.0E0 )\n      REAL               ONE\n      PARAMETER          ( ONE = 1.0E0 )\n*     ..\n*     .. Local Scalars ..\n      REAL               W, XABS, YABS, Z\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN, SQRT\n*     ..\n*     .. Executable Statements ..\n*\n      XABS = ABS( X )\n      YABS = ABS( Y )\n      W = MAX( XABS, YABS )\n      Z = MIN( XABS, YABS )\n      IF( Z.EQ.ZERO ) THEN\n         SLAPY2 = W\n      ELSE\n         SLAPY2 = W*SQRT( ONE+( Z / W )**2 )\n      END IF\n      RETURN\n*\n*     End of SLAPY2\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/slapy3.f",
    "content": "*> \\brief \\b SLAPY3\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download SLAPY3 + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/slapy3.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/slapy3.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/slapy3.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       REAL             FUNCTION SLAPY3( X, Y, Z )\n* \n*       .. Scalar Arguments ..\n*       REAL               X, Y, Z\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> SLAPY3 returns sqrt(x**2+y**2+z**2), taking care not to cause\n*> unnecessary overflow.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] X\n*> \\verbatim\n*>          X is REAL\n*> \\endverbatim\n*>\n*> \\param[in] Y\n*> \\verbatim\n*>          Y is REAL\n*> \\endverbatim\n*>\n*> \\param[in] Z\n*> \\verbatim\n*>          Z is REAL\n*>          X, Y and Z specify the values x, y and z.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      REAL             FUNCTION SLAPY3( X, Y, Z )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      REAL               X, Y, Z\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      REAL               ZERO\n      PARAMETER          ( ZERO = 0.0E0 )\n*     ..\n*     .. Local Scalars ..\n      REAL               W, XABS, YABS, ZABS\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, SQRT\n*     ..\n*     .. Executable Statements ..\n*\n      XABS = ABS( X )\n      YABS = ABS( Y )\n      ZABS = ABS( Z )\n      W = MAX( XABS, YABS, ZABS )\n      IF( W.EQ.ZERO ) THEN\n*     W can be zero for max(0,nan,0)\n*     adding all three entries together will make sure\n*     NaN will not disappear.\n         SLAPY3 =  XABS + YABS + ZABS\n      ELSE\n         SLAPY3 = W*SQRT( ( XABS / W )**2+( YABS / W )**2+\n     $            ( ZABS / W )**2 )\n      END IF\n      RETURN\n*\n*     End of SLAPY3\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/slarf.f",
    "content": "*> \\brief \\b SLARF\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download SLARF + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/slarf.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/slarf.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/slarf.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE SLARF( SIDE, M, N, V, INCV, TAU, C, LDC, WORK )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          SIDE\n*       INTEGER            INCV, LDC, M, N\n*       REAL               TAU\n*       ..\n*       .. Array Arguments ..\n*       REAL               C( LDC, * ), V( * ), WORK( * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> SLARF applies a real elementary reflector H to a real m by n matrix\n*> C, from either the left or the right. H is represented in the form\n*>\n*>       H = I - tau * v * v**T\n*>\n*> where tau is a real scalar and v is a real vector.\n*>\n*> If tau = 0, then H is taken to be the unit matrix.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] SIDE\n*> \\verbatim\n*>          SIDE is CHARACTER*1\n*>          = 'L': form  H * C\n*>          = 'R': form  C * H\n*> \\endverbatim\n*>\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is REAL array, dimension\n*>                     (1 + (M-1)*abs(INCV)) if SIDE = 'L'\n*>                  or (1 + (N-1)*abs(INCV)) if SIDE = 'R'\n*>          The vector v in the representation of H. V is not used if\n*>          TAU = 0.\n*> \\endverbatim\n*>\n*> \\param[in] INCV\n*> \\verbatim\n*>          INCV is INTEGER\n*>          The increment between elements of v. INCV <> 0.\n*> \\endverbatim\n*>\n*> \\param[in] TAU\n*> \\verbatim\n*>          TAU is REAL\n*>          The value tau in the representation of H.\n*> \\endverbatim\n*>\n*> \\param[in,out] C\n*> \\verbatim\n*>          C is REAL array, dimension (LDC,N)\n*>          On entry, the m by n matrix C.\n*>          On exit, C is overwritten by the matrix H * C if SIDE = 'L',\n*>          or C * H if SIDE = 'R'.\n*> \\endverbatim\n*>\n*> \\param[in] LDC\n*> \\verbatim\n*>          LDC is INTEGER\n*>          The leading dimension of the array C. LDC >= max(1,M).\n*> \\endverbatim\n*>\n*> \\param[out] WORK\n*> \\verbatim\n*>          WORK is REAL array, dimension\n*>                         (N) if SIDE = 'L'\n*>                      or (M) if SIDE = 'R'\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup realOTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE SLARF( SIDE, M, N, V, INCV, TAU, C, LDC, WORK )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      CHARACTER          SIDE\n      INTEGER            INCV, LDC, M, N\n      REAL               TAU\n*     ..\n*     .. Array Arguments ..\n      REAL               C( LDC, * ), V( * ), WORK( * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      REAL               ONE, ZERO\n      PARAMETER          ( ONE = 1.0E+0, ZERO = 0.0E+0 )\n*     ..\n*     .. Local Scalars ..\n      LOGICAL            APPLYLEFT\n      INTEGER            I, LASTV, LASTC\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           SGEMV, SGER\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      INTEGER            ILASLR, ILASLC\n      EXTERNAL           LSAME, ILASLR, ILASLC\n*     ..\n*     .. Executable Statements ..\n*\n      APPLYLEFT = LSAME( SIDE, 'L' )\n      LASTV = 0\n      LASTC = 0\n      IF( TAU.NE.ZERO ) THEN\n!     Set up variables for scanning V.  LASTV begins pointing to the end\n!     of V.\n         IF( APPLYLEFT ) THEN\n            LASTV = M\n         ELSE\n            LASTV = N\n         END IF\n         IF( INCV.GT.0 ) THEN\n            I = 1 + (LASTV-1) * INCV\n         ELSE\n            I = 1\n         END IF\n!     Look for the last non-zero row in V.\n         DO WHILE( LASTV.GT.0 .AND. V( I ).EQ.ZERO )\n            LASTV = LASTV - 1\n            I = I - INCV\n         END DO\n         IF( APPLYLEFT ) THEN\n!     Scan for the last non-zero column in C(1:lastv,:).\n            LASTC = ILASLC(LASTV, N, C, LDC)\n         ELSE\n!     Scan for the last non-zero row in C(:,1:lastv).\n            LASTC = ILASLR(M, LASTV, C, LDC)\n         END IF\n      END IF\n!     Note that lastc.eq.0 renders the BLAS operations null; no special\n!     case is needed at this level.\n      IF( APPLYLEFT ) THEN\n*\n*        Form  H * C\n*\n         IF( LASTV.GT.0 ) THEN\n*\n*           w(1:lastc,1) := C(1:lastv,1:lastc)**T * v(1:lastv,1)\n*\n            CALL SGEMV( 'Transpose', LASTV, LASTC, ONE, C, LDC, V, INCV,\n     $           ZERO, WORK, 1 )\n*\n*           C(1:lastv,1:lastc) := C(...) - v(1:lastv,1) * w(1:lastc,1)**T\n*\n            CALL SGER( LASTV, LASTC, -TAU, V, INCV, WORK, 1, C, LDC )\n         END IF\n      ELSE\n*\n*        Form  C * H\n*\n         IF( LASTV.GT.0 ) THEN\n*\n*           w(1:lastc,1) := C(1:lastc,1:lastv) * v(1:lastv,1)\n*\n            CALL SGEMV( 'No transpose', LASTC, LASTV, ONE, C, LDC,\n     $           V, INCV, ZERO, WORK, 1 )\n*\n*           C(1:lastc,1:lastv) := C(...) - w(1:lastc,1) * v(1:lastv,1)**T\n*\n            CALL SGER( LASTC, LASTV, -TAU, WORK, 1, V, INCV, C, LDC )\n         END IF\n      END IF\n      RETURN\n*\n*     End of SLARF\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/slarfb.f",
    "content": "*> \\brief \\b SLARFB\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download SLARFB + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/slarfb.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/slarfb.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/slarfb.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE SLARFB( SIDE, TRANS, DIRECT, STOREV, M, N, K, V, LDV,\n*                          T, LDT, C, LDC, WORK, LDWORK )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          DIRECT, SIDE, STOREV, TRANS\n*       INTEGER            K, LDC, LDT, LDV, LDWORK, M, N\n*       ..\n*       .. Array Arguments ..\n*       REAL               C( LDC, * ), T( LDT, * ), V( LDV, * ),\n*      $                   WORK( LDWORK, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> SLARFB applies a real block reflector H or its transpose H**T to a\n*> real m by n matrix C, from either the left or the right.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] SIDE\n*> \\verbatim\n*>          SIDE is CHARACTER*1\n*>          = 'L': apply H or H**T from the Left\n*>          = 'R': apply H or H**T from the Right\n*> \\endverbatim\n*>\n*> \\param[in] TRANS\n*> \\verbatim\n*>          TRANS is CHARACTER*1\n*>          = 'N': apply H (No transpose)\n*>          = 'T': apply H**T (Transpose)\n*> \\endverbatim\n*>\n*> \\param[in] DIRECT\n*> \\verbatim\n*>          DIRECT is CHARACTER*1\n*>          Indicates how H is formed from a product of elementary\n*>          reflectors\n*>          = 'F': H = H(1) H(2) . . . H(k) (Forward)\n*>          = 'B': H = H(k) . . . H(2) H(1) (Backward)\n*> \\endverbatim\n*>\n*> \\param[in] STOREV\n*> \\verbatim\n*>          STOREV is CHARACTER*1\n*>          Indicates how the vectors which define the elementary\n*>          reflectors are stored:\n*>          = 'C': Columnwise\n*>          = 'R': Rowwise\n*> \\endverbatim\n*>\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] K\n*> \\verbatim\n*>          K is INTEGER\n*>          The order of the matrix T (= the number of elementary\n*>          reflectors whose product defines the block reflector).\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is REAL array, dimension\n*>                                (LDV,K) if STOREV = 'C'\n*>                                (LDV,M) if STOREV = 'R' and SIDE = 'L'\n*>                                (LDV,N) if STOREV = 'R' and SIDE = 'R'\n*>          The matrix V. See Further Details.\n*> \\endverbatim\n*>\n*> \\param[in] LDV\n*> \\verbatim\n*>          LDV is INTEGER\n*>          The leading dimension of the array V.\n*>          If STOREV = 'C' and SIDE = 'L', LDV >= max(1,M);\n*>          if STOREV = 'C' and SIDE = 'R', LDV >= max(1,N);\n*>          if STOREV = 'R', LDV >= K.\n*> \\endverbatim\n*>\n*> \\param[in] T\n*> \\verbatim\n*>          T is REAL array, dimension (LDT,K)\n*>          The triangular k by k matrix T in the representation of the\n*>          block reflector.\n*> \\endverbatim\n*>\n*> \\param[in] LDT\n*> \\verbatim\n*>          LDT is INTEGER\n*>          The leading dimension of the array T. LDT >= K.\n*> \\endverbatim\n*>\n*> \\param[in,out] C\n*> \\verbatim\n*>          C is REAL array, dimension (LDC,N)\n*>          On entry, the m by n matrix C.\n*>          On exit, C is overwritten by H*C or H**T*C or C*H or C*H**T.\n*> \\endverbatim\n*>\n*> \\param[in] LDC\n*> \\verbatim\n*>          LDC is INTEGER\n*>          The leading dimension of the array C. LDC >= max(1,M).\n*> \\endverbatim\n*>\n*> \\param[out] WORK\n*> \\verbatim\n*>          WORK is REAL array, dimension (LDWORK,K)\n*> \\endverbatim\n*>\n*> \\param[in] LDWORK\n*> \\verbatim\n*>          LDWORK is INTEGER\n*>          The leading dimension of the array WORK.\n*>          If SIDE = 'L', LDWORK >= max(1,N);\n*>          if SIDE = 'R', LDWORK >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup realOTHERauxiliary\n*\n*> \\par Further Details:\n*  =====================\n*>\n*> \\verbatim\n*>\n*>  The shape of the matrix V and the storage of the vectors which define\n*>  the H(i) is best illustrated by the following example with n = 5 and\n*>  k = 3. The elements equal to 1 are not stored; the corresponding\n*>  array elements are modified but restored on exit. The rest of the\n*>  array is not used.\n*>\n*>  DIRECT = 'F' and STOREV = 'C':         DIRECT = 'F' and STOREV = 'R':\n*>\n*>               V = (  1       )                 V = (  1 v1 v1 v1 v1 )\n*>                   ( v1  1    )                     (     1 v2 v2 v2 )\n*>                   ( v1 v2  1 )                     (        1 v3 v3 )\n*>                   ( v1 v2 v3 )\n*>                   ( v1 v2 v3 )\n*>\n*>  DIRECT = 'B' and STOREV = 'C':         DIRECT = 'B' and STOREV = 'R':\n*>\n*>               V = ( v1 v2 v3 )                 V = ( v1 v1  1       )\n*>                   ( v1 v2 v3 )                     ( v2 v2 v2  1    )\n*>                   (  1 v2 v3 )                     ( v3 v3 v3 v3  1 )\n*>                   (     1 v3 )\n*>                   (        1 )\n*> \\endverbatim\n*>\n*  =====================================================================\n      SUBROUTINE SLARFB( SIDE, TRANS, DIRECT, STOREV, M, N, K, V, LDV,\n     $                   T, LDT, C, LDC, WORK, LDWORK )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      CHARACTER          DIRECT, SIDE, STOREV, TRANS\n      INTEGER            K, LDC, LDT, LDV, LDWORK, M, N\n*     ..\n*     .. Array Arguments ..\n      REAL               C( LDC, * ), T( LDT, * ), V( LDV, * ),\n     $                   WORK( LDWORK, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      REAL               ONE\n      PARAMETER          ( ONE = 1.0E+0 )\n*     ..\n*     .. Local Scalars ..\n      CHARACTER          TRANST\n      INTEGER            I, J, LASTV, LASTC\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      INTEGER            ILASLR, ILASLC\n      EXTERNAL           LSAME, ILASLR, ILASLC\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           SCOPY, SGEMM, STRMM\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick return if possible\n*\n      IF( M.LE.0 .OR. N.LE.0 )\n     $   RETURN\n*\n      IF( LSAME( TRANS, 'N' ) ) THEN\n         TRANST = 'T'\n      ELSE\n         TRANST = 'N'\n      END IF\n*\n      IF( LSAME( STOREV, 'C' ) ) THEN\n*\n         IF( LSAME( DIRECT, 'F' ) ) THEN\n*\n*           Let  V =  ( V1 )    (first K rows)\n*                     ( V2 )\n*           where  V1  is unit lower triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**T * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILASLR( M, K, V, LDV ) )\n               LASTC = ILASLC( LASTV, N, C, LDC )\n*\n*              W := C**T * V  =  (C1**T * V1 + C2**T * V2)  (stored in WORK)\n*\n*              W := C1**T\n*\n               DO 10 J = 1, K\n                  CALL SCOPY( LASTC, C( J, 1 ), LDC, WORK( 1, J ), 1 )\n   10          CONTINUE\n*\n*              W := W * V1\n*\n               CALL STRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2**T *V2\n*\n                  CALL SGEMM( 'Transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C( K+1, 1 ), LDC, V( K+1, 1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**T  or  W * T\n*\n               CALL STRMM( 'Right', 'Upper', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V * W**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - V2 * W**T\n*\n                  CALL SGEMM( 'No transpose', 'Transpose',\n     $                 LASTV-K, LASTC, K,\n     $                 -ONE, V( K+1, 1 ), LDV, WORK, LDWORK, ONE,\n     $                 C( K+1, 1 ), LDC )\n               END IF\n*\n*              W := W * V1**T\n*\n               CALL STRMM( 'Right', 'Lower', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W**T\n*\n               DO 30 J = 1, K\n                  DO 20 I = 1, LASTC\n                     C( J, I ) = C( J, I ) - WORK( I, J )\n   20             CONTINUE\n   30          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**T  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILASLR( N, K, V, LDV ) )\n               LASTC = ILASLR( M, LASTV, C, LDC )\n*\n*              W := C * V  =  (C1*V1 + C2*V2)  (stored in WORK)\n*\n*              W := C1\n*\n               DO 40 J = 1, K\n                  CALL SCOPY( LASTC, C( 1, J ), 1, WORK( 1, J ), 1 )\n   40          CONTINUE\n*\n*              W := W * V1\n*\n               CALL STRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2 * V2\n*\n                  CALL SGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C( 1, K+1 ), LDC, V( K+1, 1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**T\n*\n               CALL STRMM( 'Right', 'Upper', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - W * V2**T\n*\n                  CALL SGEMM( 'No transpose', 'Transpose',\n     $                 LASTC, LASTV-K, K,\n     $                 -ONE, WORK, LDWORK, V( K+1, 1 ), LDV, ONE,\n     $                 C( 1, K+1 ), LDC )\n               END IF\n*\n*              W := W * V1**T\n*\n               CALL STRMM( 'Right', 'Lower', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 60 J = 1, K\n                  DO 50 I = 1, LASTC\n                     C( I, J ) = C( I, J ) - WORK( I, J )\n   50             CONTINUE\n   60          CONTINUE\n            END IF\n*\n         ELSE\n*\n*           Let  V =  ( V1 )\n*                     ( V2 )    (last K rows)\n*           where  V2  is unit upper triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**T * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILASLR( M, K, V, LDV ) )\n               LASTC = ILASLC( LASTV, N, C, LDC )\n*\n*              W := C**T * V  =  (C1**T * V1 + C2**T * V2)  (stored in WORK)\n*\n*              W := C2**T\n*\n               DO 70 J = 1, K\n                  CALL SCOPY( LASTC, C( LASTV-K+J, 1 ), LDC,\n     $                 WORK( 1, J ), 1 )\n   70          CONTINUE\n*\n*              W := W * V2\n*\n               CALL STRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1**T*V1\n*\n                  CALL SGEMM( 'Transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**T  or  W * T\n*\n               CALL STRMM( 'Right', 'Lower', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V * W**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - V1 * W**T\n*\n                  CALL SGEMM( 'No transpose', 'Transpose',\n     $                 LASTV-K, LASTC, K, -ONE, V, LDV, WORK, LDWORK,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2**T\n*\n               CALL STRMM( 'Right', 'Upper', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W**T\n*\n               DO 90 J = 1, K\n                  DO 80 I = 1, LASTC\n                     C( LASTV-K+J, I ) = C( LASTV-K+J, I ) - WORK(I, J)\n   80             CONTINUE\n   90          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**T  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILASLR( N, K, V, LDV ) )\n               LASTC = ILASLR( M, LASTV, C, LDC )\n*\n*              W := C * V  =  (C1*V1 + C2*V2)  (stored in WORK)\n*\n*              W := C2\n*\n               DO 100 J = 1, K\n                  CALL SCOPY( LASTC, C( 1, N-K+J ), 1, WORK( 1, J ), 1 )\n  100          CONTINUE\n*\n*              W := W * V2\n*\n               CALL STRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1 * V1\n*\n                  CALL SGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**T\n*\n               CALL STRMM( 'Right', 'Lower', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - W * V1**T\n*\n                  CALL SGEMM( 'No transpose', 'Transpose',\n     $                 LASTC, LASTV-K, K, -ONE, WORK, LDWORK, V, LDV,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2**T\n*\n               CALL STRMM( 'Right', 'Upper', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W\n*\n               DO 120 J = 1, K\n                  DO 110 I = 1, LASTC\n                     C( I, LASTV-K+J ) = C( I, LASTV-K+J ) - WORK(I, J)\n  110             CONTINUE\n  120          CONTINUE\n            END IF\n         END IF\n*\n      ELSE IF( LSAME( STOREV, 'R' ) ) THEN\n*\n         IF( LSAME( DIRECT, 'F' ) ) THEN\n*\n*           Let  V =  ( V1  V2 )    (V1: first K columns)\n*           where  V1  is unit upper triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**T * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILASLC( K, M, V, LDV ) )\n               LASTC = ILASLC( LASTV, N, C, LDC )\n*\n*              W := C**T * V**T  =  (C1**T * V1**T + C2**T * V2**T) (stored in WORK)\n*\n*              W := C1**T\n*\n               DO 130 J = 1, K\n                  CALL SCOPY( LASTC, C( J, 1 ), LDC, WORK( 1, J ), 1 )\n  130          CONTINUE\n*\n*              W := W * V1**T\n*\n               CALL STRMM( 'Right', 'Upper', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2**T*V2**T\n*\n                  CALL SGEMM( 'Transpose', 'Transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C( K+1, 1 ), LDC, V( 1, K+1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**T  or  W * T\n*\n               CALL STRMM( 'Right', 'Upper', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V**T * W**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - V2**T * W**T\n*\n                  CALL SGEMM( 'Transpose', 'Transpose',\n     $                 LASTV-K, LASTC, K,\n     $                 -ONE, V( 1, K+1 ), LDV, WORK, LDWORK,\n     $                 ONE, C( K+1, 1 ), LDC )\n               END IF\n*\n*              W := W * V1\n*\n               CALL STRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W**T\n*\n               DO 150 J = 1, K\n                  DO 140 I = 1, LASTC\n                     C( J, I ) = C( J, I ) - WORK( I, J )\n  140             CONTINUE\n  150          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**T  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILASLC( K, N, V, LDV ) )\n               LASTC = ILASLR( M, LASTV, C, LDC )\n*\n*              W := C * V**T  =  (C1*V1**T + C2*V2**T)  (stored in WORK)\n*\n*              W := C1\n*\n               DO 160 J = 1, K\n                  CALL SCOPY( LASTC, C( 1, J ), 1, WORK( 1, J ), 1 )\n  160          CONTINUE\n*\n*              W := W * V1**T\n*\n               CALL STRMM( 'Right', 'Upper', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2 * V2**T\n*\n                  CALL SGEMM( 'No transpose', 'Transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C( 1, K+1 ), LDC, V( 1, K+1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**T\n*\n               CALL STRMM( 'Right', 'Upper', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - W * V2\n*\n                  CALL SGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, LASTV-K, K,\n     $                 -ONE, WORK, LDWORK, V( 1, K+1 ), LDV,\n     $                 ONE, C( 1, K+1 ), LDC )\n               END IF\n*\n*              W := W * V1\n*\n               CALL STRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 180 J = 1, K\n                  DO 170 I = 1, LASTC\n                     C( I, J ) = C( I, J ) - WORK( I, J )\n  170             CONTINUE\n  180          CONTINUE\n*\n            END IF\n*\n         ELSE\n*\n*           Let  V =  ( V1  V2 )    (V2: last K columns)\n*           where  V2  is unit lower triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**T * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILASLC( K, M, V, LDV ) )\n               LASTC = ILASLC( LASTV, N, C, LDC )\n*\n*              W := C**T * V**T  =  (C1**T * V1**T + C2**T * V2**T) (stored in WORK)\n*\n*              W := C2**T\n*\n               DO 190 J = 1, K\n                  CALL SCOPY( LASTC, C( LASTV-K+J, 1 ), LDC,\n     $                 WORK( 1, J ), 1 )\n  190          CONTINUE\n*\n*              W := W * V2**T\n*\n               CALL STRMM( 'Right', 'Lower', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1**T * V1**T\n*\n                  CALL SGEMM( 'Transpose', 'Transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**T  or  W * T\n*\n               CALL STRMM( 'Right', 'Lower', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V**T * W**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - V1**T * W**T\n*\n                  CALL SGEMM( 'Transpose', 'Transpose',\n     $                 LASTV-K, LASTC, K, -ONE, V, LDV, WORK, LDWORK,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2\n*\n               CALL STRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W**T\n*\n               DO 210 J = 1, K\n                  DO 200 I = 1, LASTC\n                     C( LASTV-K+J, I ) = C( LASTV-K+J, I ) - WORK(I, J)\n  200             CONTINUE\n  210          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**T  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILASLC( K, N, V, LDV ) )\n               LASTC = ILASLR( M, LASTV, C, LDC )\n*\n*              W := C * V**T  =  (C1*V1**T + C2*V2**T)  (stored in WORK)\n*\n*              W := C2\n*\n               DO 220 J = 1, K\n                  CALL SCOPY( LASTC, C( 1, LASTV-K+J ), 1,\n     $                 WORK( 1, J ), 1 )\n  220          CONTINUE\n*\n*              W := W * V2**T\n*\n               CALL STRMM( 'Right', 'Lower', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1 * V1**T\n*\n                  CALL SGEMM( 'No transpose', 'Transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**T\n*\n               CALL STRMM( 'Right', 'Lower', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - W * V1\n*\n                  CALL SGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, LASTV-K, K, -ONE, WORK, LDWORK, V, LDV,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2\n*\n               CALL STRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 240 J = 1, K\n                  DO 230 I = 1, LASTC\n                     C( I, LASTV-K+J ) = C( I, LASTV-K+J )\n     $                    - WORK( I, J )\n  230             CONTINUE\n  240          CONTINUE\n*\n            END IF\n*\n         END IF\n      END IF\n*\n      RETURN\n*\n*     End of SLARFB\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/slarfg.f",
    "content": "*> \\brief \\b SLARFG\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download SLARFG + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/slarfg.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/slarfg.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/slarfg.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE SLARFG( N, ALPHA, X, INCX, TAU )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            INCX, N\n*       REAL               ALPHA, TAU\n*       ..\n*       .. Array Arguments ..\n*       REAL               X( * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> SLARFG generates a real elementary reflector H of order n, such\n*> that\n*>\n*>       H * ( alpha ) = ( beta ),   H**T * H = I.\n*>           (   x   )   (   0  )\n*>\n*> where alpha and beta are scalars, and x is an (n-1)-element real\n*> vector. H is represented in the form\n*>\n*>       H = I - tau * ( 1 ) * ( 1 v**T ) ,\n*>                     ( v )\n*>\n*> where tau is a real scalar and v is a real (n-1)-element\n*> vector.\n*>\n*> If the elements of x are all zero, then tau = 0 and H is taken to be\n*> the unit matrix.\n*>\n*> Otherwise  1 <= tau <= 2.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The order of the elementary reflector.\n*> \\endverbatim\n*>\n*> \\param[in,out] ALPHA\n*> \\verbatim\n*>          ALPHA is REAL\n*>          On entry, the value alpha.\n*>          On exit, it is overwritten with the value beta.\n*> \\endverbatim\n*>\n*> \\param[in,out] X\n*> \\verbatim\n*>          X is REAL array, dimension\n*>                         (1+(N-2)*abs(INCX))\n*>          On entry, the vector x.\n*>          On exit, it is overwritten with the vector v.\n*> \\endverbatim\n*>\n*> \\param[in] INCX\n*> \\verbatim\n*>          INCX is INTEGER\n*>          The increment between elements of X. INCX > 0.\n*> \\endverbatim\n*>\n*> \\param[out] TAU\n*> \\verbatim\n*>          TAU is REAL\n*>          The value tau.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup realOTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE SLARFG( N, ALPHA, X, INCX, TAU )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      INTEGER            INCX, N\n      REAL               ALPHA, TAU\n*     ..\n*     .. Array Arguments ..\n      REAL               X( * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      REAL               ONE, ZERO\n      PARAMETER          ( ONE = 1.0E+0, ZERO = 0.0E+0 )\n*     ..\n*     .. Local Scalars ..\n      INTEGER            J, KNT\n      REAL               BETA, RSAFMN, SAFMIN, XNORM\n*     ..\n*     .. External Functions ..\n      REAL               SLAMCH, SLAPY2, SNRM2\n      EXTERNAL           SLAMCH, SLAPY2, SNRM2\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, SIGN\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           SSCAL\n*     ..\n*     .. Executable Statements ..\n*\n      IF( N.LE.1 ) THEN\n         TAU = ZERO\n         RETURN\n      END IF\n*\n      XNORM = SNRM2( N-1, X, INCX )\n*\n      IF( XNORM.EQ.ZERO ) THEN\n*\n*        H  =  I\n*\n         TAU = ZERO\n      ELSE\n*\n*        general case\n*\n         BETA = -SIGN( SLAPY2( ALPHA, XNORM ), ALPHA )\n         SAFMIN = SLAMCH( 'S' ) / SLAMCH( 'E' )\n         KNT = 0\n         IF( ABS( BETA ).LT.SAFMIN ) THEN\n*\n*           XNORM, BETA may be inaccurate; scale X and recompute them\n*\n            RSAFMN = ONE / SAFMIN\n   10       CONTINUE\n            KNT = KNT + 1\n            CALL SSCAL( N-1, RSAFMN, X, INCX )\n            BETA = BETA*RSAFMN\n            ALPHA = ALPHA*RSAFMN\n            IF( ABS( BETA ).LT.SAFMIN )\n     $         GO TO 10\n*\n*           New BETA is at most 1, at least SAFMIN\n*\n            XNORM = SNRM2( N-1, X, INCX )\n            BETA = -SIGN( SLAPY2( ALPHA, XNORM ), ALPHA )\n         END IF\n         TAU = ( BETA-ALPHA ) / BETA\n         CALL SSCAL( N-1, ONE / ( ALPHA-BETA ), X, INCX )\n*\n*        If ALPHA is subnormal, it may lose relative accuracy\n*\n         DO 20 J = 1, KNT\n            BETA = BETA*SAFMIN\n 20      CONTINUE\n         ALPHA = BETA\n      END IF\n*\n      RETURN\n*\n*     End of SLARFG\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/slarft.f",
    "content": "*> \\brief \\b SLARFT\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download SLARFT + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/slarft.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/slarft.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/slarft.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE SLARFT( DIRECT, STOREV, N, K, V, LDV, TAU, T, LDT )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          DIRECT, STOREV\n*       INTEGER            K, LDT, LDV, N\n*       ..\n*       .. Array Arguments ..\n*       REAL               T( LDT, * ), TAU( * ), V( LDV, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> SLARFT forms the triangular factor T of a real block reflector H\n*> of order n, which is defined as a product of k elementary reflectors.\n*>\n*> If DIRECT = 'F', H = H(1) H(2) . . . H(k) and T is upper triangular;\n*>\n*> If DIRECT = 'B', H = H(k) . . . H(2) H(1) and T is lower triangular.\n*>\n*> If STOREV = 'C', the vector which defines the elementary reflector\n*> H(i) is stored in the i-th column of the array V, and\n*>\n*>    H  =  I - V * T * V**T\n*>\n*> If STOREV = 'R', the vector which defines the elementary reflector\n*> H(i) is stored in the i-th row of the array V, and\n*>\n*>    H  =  I - V**T * T * V\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] DIRECT\n*> \\verbatim\n*>          DIRECT is CHARACTER*1\n*>          Specifies the order in which the elementary reflectors are\n*>          multiplied to form the block reflector:\n*>          = 'F': H = H(1) H(2) . . . H(k) (Forward)\n*>          = 'B': H = H(k) . . . H(2) H(1) (Backward)\n*> \\endverbatim\n*>\n*> \\param[in] STOREV\n*> \\verbatim\n*>          STOREV is CHARACTER*1\n*>          Specifies how the vectors which define the elementary\n*>          reflectors are stored (see also Further Details):\n*>          = 'C': columnwise\n*>          = 'R': rowwise\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The order of the block reflector H. N >= 0.\n*> \\endverbatim\n*>\n*> \\param[in] K\n*> \\verbatim\n*>          K is INTEGER\n*>          The order of the triangular factor T (= the number of\n*>          elementary reflectors). K >= 1.\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is REAL array, dimension\n*>                               (LDV,K) if STOREV = 'C'\n*>                               (LDV,N) if STOREV = 'R'\n*>          The matrix V. See further details.\n*> \\endverbatim\n*>\n*> \\param[in] LDV\n*> \\verbatim\n*>          LDV is INTEGER\n*>          The leading dimension of the array V.\n*>          If STOREV = 'C', LDV >= max(1,N); if STOREV = 'R', LDV >= K.\n*> \\endverbatim\n*>\n*> \\param[in] TAU\n*> \\verbatim\n*>          TAU is REAL array, dimension (K)\n*>          TAU(i) must contain the scalar factor of the elementary\n*>          reflector H(i).\n*> \\endverbatim\n*>\n*> \\param[out] T\n*> \\verbatim\n*>          T is REAL array, dimension (LDT,K)\n*>          The k by k triangular factor T of the block reflector.\n*>          If DIRECT = 'F', T is upper triangular; if DIRECT = 'B', T is\n*>          lower triangular. The rest of the array is not used.\n*> \\endverbatim\n*>\n*> \\param[in] LDT\n*> \\verbatim\n*>          LDT is INTEGER\n*>          The leading dimension of the array T. LDT >= K.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup realOTHERauxiliary\n*\n*> \\par Further Details:\n*  =====================\n*>\n*> \\verbatim\n*>\n*>  The shape of the matrix V and the storage of the vectors which define\n*>  the H(i) is best illustrated by the following example with n = 5 and\n*>  k = 3. The elements equal to 1 are not stored.\n*>\n*>  DIRECT = 'F' and STOREV = 'C':         DIRECT = 'F' and STOREV = 'R':\n*>\n*>               V = (  1       )                 V = (  1 v1 v1 v1 v1 )\n*>                   ( v1  1    )                     (     1 v2 v2 v2 )\n*>                   ( v1 v2  1 )                     (        1 v3 v3 )\n*>                   ( v1 v2 v3 )\n*>                   ( v1 v2 v3 )\n*>\n*>  DIRECT = 'B' and STOREV = 'C':         DIRECT = 'B' and STOREV = 'R':\n*>\n*>               V = ( v1 v2 v3 )                 V = ( v1 v1  1       )\n*>                   ( v1 v2 v3 )                     ( v2 v2 v2  1    )\n*>                   (  1 v2 v3 )                     ( v3 v3 v3 v3  1 )\n*>                   (     1 v3 )\n*>                   (        1 )\n*> \\endverbatim\n*>\n*  =====================================================================\n      SUBROUTINE SLARFT( DIRECT, STOREV, N, K, V, LDV, TAU, T, LDT )\n*\n*  -- LAPACK auxiliary routine (version 3.4.1) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*     .. Scalar Arguments ..\n      CHARACTER          DIRECT, STOREV\n      INTEGER            K, LDT, LDV, N\n*     ..\n*     .. Array Arguments ..\n      REAL               T( LDT, * ), TAU( * ), V( LDV, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      REAL               ONE, ZERO\n      PARAMETER          ( ONE = 1.0E+0, ZERO = 0.0E+0 )\n*     ..\n*     .. Local Scalars ..\n      INTEGER            I, J, PREVLASTV, LASTV\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           SGEMV, STRMV\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      EXTERNAL           LSAME\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick return if possible\n*\n      IF( N.EQ.0 )\n     $   RETURN\n*\n      IF( LSAME( DIRECT, 'F' ) ) THEN\n         PREVLASTV = N\n         DO I = 1, K\n            PREVLASTV = MAX( I, PREVLASTV )\n            IF( TAU( I ).EQ.ZERO ) THEN\n*\n*              H(i)  =  I\n*\n               DO J = 1, I\n                  T( J, I ) = ZERO\n               END DO\n            ELSE\n*\n*              general case\n*\n               IF( LSAME( STOREV, 'C' ) ) THEN\n*                 Skip any trailing zeros.\n                  DO LASTV = N, I+1, -1\n                     IF( V( LASTV, I ).NE.ZERO ) EXIT\n                  END DO\n                  DO J = 1, I-1\n                     T( J, I ) = -TAU( I ) * V( I , J )\n                  END DO   \n                  J = MIN( LASTV, PREVLASTV )\n*\n*                 T(1:i-1,i) := - tau(i) * V(i:j,1:i-1)**T * V(i:j,i)\n*\n                  CALL SGEMV( 'Transpose', J-I, I-1, -TAU( I ),\n     $                        V( I+1, 1 ), LDV, V( I+1, I ), 1, ONE,\n     $                        T( 1, I ), 1 )\n               ELSE\n*                 Skip any trailing zeros.\n                  DO LASTV = N, I+1, -1\n                     IF( V( I, LASTV ).NE.ZERO ) EXIT\n                  END DO\n                  DO J = 1, I-1\n                     T( J, I ) = -TAU( I ) * V( J , I )\n                  END DO   \n                  J = MIN( LASTV, PREVLASTV )\n*\n*                 T(1:i-1,i) := - tau(i) * V(1:i-1,i:j) * V(i,i:j)**T\n*\n                  CALL SGEMV( 'No transpose', I-1, J-I, -TAU( I ),\n     $                        V( 1, I+1 ), LDV, V( I, I+1 ), LDV, \n     $                        ONE, T( 1, I ), 1 )\n               END IF\n*\n*              T(1:i-1,i) := T(1:i-1,1:i-1) * T(1:i-1,i)\n*\n               CALL STRMV( 'Upper', 'No transpose', 'Non-unit', I-1, T,\n     $                     LDT, T( 1, I ), 1 )\n               T( I, I ) = TAU( I )\n               IF( I.GT.1 ) THEN\n                  PREVLASTV = MAX( PREVLASTV, LASTV )\n               ELSE\n                  PREVLASTV = LASTV\n               END IF\n            END IF\n         END DO\n      ELSE\n         PREVLASTV = 1\n         DO I = K, 1, -1\n            IF( TAU( I ).EQ.ZERO ) THEN\n*\n*              H(i)  =  I\n*\n               DO J = I, K\n                  T( J, I ) = ZERO\n               END DO\n            ELSE\n*\n*              general case\n*\n               IF( I.LT.K ) THEN\n                  IF( LSAME( STOREV, 'C' ) ) THEN\n*                    Skip any leading zeros.\n                     DO LASTV = 1, I-1\n                        IF( V( LASTV, I ).NE.ZERO ) EXIT\n                     END DO\n                     DO J = I+1, K\n                        T( J, I ) = -TAU( I ) * V( N-K+I , J )\n                     END DO   \n                     J = MAX( LASTV, PREVLASTV )\n*\n*                    T(i+1:k,i) = -tau(i) * V(j:n-k+i,i+1:k)**T * V(j:n-k+i,i)\n*\n                     CALL SGEMV( 'Transpose', N-K+I-J, K-I, -TAU( I ),\n     $                           V( J, I+1 ), LDV, V( J, I ), 1, ONE,\n     $                           T( I+1, I ), 1 )\n                  ELSE\n*                    Skip any leading zeros.\n                     DO LASTV = 1, I-1\n                        IF( V( I, LASTV ).NE.ZERO ) EXIT\n                     END DO\n                     DO J = I+1, K\n                        T( J, I ) = -TAU( I ) * V( J, N-K+I )\n                     END DO   \n                     J = MAX( LASTV, PREVLASTV )\n*\n*                    T(i+1:k,i) = -tau(i) * V(i+1:k,j:n-k+i) * V(i,j:n-k+i)**T\n*\n                     CALL SGEMV( 'No transpose', K-I, N-K+I-J,\n     $                    -TAU( I ), V( I+1, J ), LDV, V( I, J ), LDV,\n     $                    ONE, T( I+1, I ), 1 )\n                  END IF\n*\n*                 T(i+1:k,i) := T(i+1:k,i+1:k) * T(i+1:k,i)\n*\n                  CALL STRMV( 'Lower', 'No transpose', 'Non-unit', K-I,\n     $                        T( I+1, I+1 ), LDT, T( I+1, I ), 1 )\n                  IF( I.GT.1 ) THEN\n                     PREVLASTV = MIN( PREVLASTV, LASTV )\n                  ELSE\n                     PREVLASTV = LASTV\n                  END IF\n               END IF\n               T( I, I ) = TAU( I )\n            END IF\n         END DO\n      END IF\n      RETURN\n*\n*     End of SLARFT\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/svd.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"lapack_common.h\"\n#include <Eigen/SVD>\n\n// computes the singular values/vectors a general M-by-N matrix A using divide-and-conquer\nEIGEN_LAPACK_FUNC(gesdd,(char *jobz, int *m, int* n, Scalar* a, int *lda, RealScalar *s, Scalar *u, int *ldu, Scalar *vt, int *ldvt, Scalar* /*work*/, int* lwork,\n                         EIGEN_LAPACK_ARG_IF_COMPLEX(RealScalar */*rwork*/) int * /*iwork*/, int *info))\n{\n  // TODO exploit the work buffer\n  bool query_size = *lwork==-1;\n  int diag_size = (std::min)(*m,*n);\n  \n  *info = 0;\n        if(*jobz!='A' && *jobz!='S' && *jobz!='O' && *jobz!='N')  *info = -1;\n  else  if(*m<0)                                                  *info = -2;\n  else  if(*n<0)                                                  *info = -3;\n  else  if(*lda<std::max(1,*m))                                   *info = -5;\n  else  if(*lda<std::max(1,*m))                                   *info = -8;\n  else  if(*ldu <1 || (*jobz=='A' && *ldu <*m)\n                   || (*jobz=='O' && *m<*n && *ldu<*m))           *info = -8;\n  else  if(*ldvt<1 || (*jobz=='A' && *ldvt<*n)\n                   || (*jobz=='S' && *ldvt<diag_size)\n                   || (*jobz=='O' && *m>=*n && *ldvt<*n))         *info = -10;\n  \n  if(*info!=0)\n  {\n    int e = -*info;\n    return xerbla_(SCALAR_SUFFIX_UP\"GESDD \", &e, 6);\n  }\n  \n  if(query_size)\n  {\n    *lwork = 0;\n    return 0;\n  }\n  \n  if(*n==0 || *m==0)\n    return 0;\n  \n  PlainMatrixType mat(*m,*n);\n  mat = matrix(a,*m,*n,*lda);\n  \n  int option = *jobz=='A' ? ComputeFullU|ComputeFullV\n             : *jobz=='S' ? ComputeThinU|ComputeThinV\n             : *jobz=='O' ? ComputeThinU|ComputeThinV\n             : 0;\n\n  BDCSVD<PlainMatrixType> svd(mat,option);\n  \n  make_vector(s,diag_size) = svd.singularValues().head(diag_size);\n\n  if(*jobz=='A')\n  {\n    matrix(u,*m,*m,*ldu)   = svd.matrixU();\n    matrix(vt,*n,*n,*ldvt) = svd.matrixV().adjoint();\n  }\n  else if(*jobz=='S')\n  {\n    matrix(u,*m,diag_size,*ldu)   = svd.matrixU();\n    matrix(vt,diag_size,*n,*ldvt) = svd.matrixV().adjoint();\n  }\n  else if(*jobz=='O' && *m>=*n)\n  {\n    matrix(a,*m,*n,*lda)   = svd.matrixU();\n    matrix(vt,*n,*n,*ldvt) = svd.matrixV().adjoint();\n  }\n  else if(*jobz=='O')\n  {\n    matrix(u,*m,*m,*ldu)        = svd.matrixU();\n    matrix(a,diag_size,*n,*lda) = svd.matrixV().adjoint();\n  }\n    \n  return 0;\n}\n\n// computes the singular values/vectors a general M-by-N matrix A using two sided jacobi algorithm\nEIGEN_LAPACK_FUNC(gesvd,(char *jobu, char *jobv, int *m, int* n, Scalar* a, int *lda, RealScalar *s, Scalar *u, int *ldu, Scalar *vt, int *ldvt, Scalar* /*work*/, int* lwork,\n                         EIGEN_LAPACK_ARG_IF_COMPLEX(RealScalar */*rwork*/) int *info))\n{\n  // TODO exploit the work buffer\n  bool query_size = *lwork==-1;\n  int diag_size = (std::min)(*m,*n);\n  \n  *info = 0;\n        if( *jobu!='A' && *jobu!='S' && *jobu!='O' && *jobu!='N') *info = -1;\n  else  if((*jobv!='A' && *jobv!='S' && *jobv!='O' && *jobv!='N')\n           || (*jobu=='O' && *jobv=='O'))                         *info = -2;\n  else  if(*m<0)                                                  *info = -3;\n  else  if(*n<0)                                                  *info = -4;\n  else  if(*lda<std::max(1,*m))                                   *info = -6;\n  else  if(*ldu <1 || ((*jobu=='A' || *jobu=='S') && *ldu<*m))    *info = -9;\n  else  if(*ldvt<1 || (*jobv=='A' && *ldvt<*n)\n                   || (*jobv=='S' && *ldvt<diag_size))            *info = -11;\n  \n  if(*info!=0)\n  {\n    int e = -*info;\n    return xerbla_(SCALAR_SUFFIX_UP\"GESVD \", &e, 6);\n  }\n  \n  if(query_size)\n  {\n    *lwork = 0;\n    return 0;\n  }\n  \n  if(*n==0 || *m==0)\n    return 0;\n  \n  PlainMatrixType mat(*m,*n);\n  mat = matrix(a,*m,*n,*lda);\n  \n  int option = (*jobu=='A' ? ComputeFullU : *jobu=='S' || *jobu=='O' ? ComputeThinU : 0)\n             | (*jobv=='A' ? ComputeFullV : *jobv=='S' || *jobv=='O' ? ComputeThinV : 0);\n  \n  JacobiSVD<PlainMatrixType> svd(mat,option);\n  \n  make_vector(s,diag_size) = svd.singularValues().head(diag_size);\n  {\n        if(*jobu=='A') matrix(u,*m,*m,*ldu)           = svd.matrixU();\n  else  if(*jobu=='S') matrix(u,*m,diag_size,*ldu)    = svd.matrixU();\n  else  if(*jobu=='O') matrix(a,*m,diag_size,*lda)    = svd.matrixU();\n  }\n  {\n        if(*jobv=='A') matrix(vt,*n,*n,*ldvt)         = svd.matrixV().adjoint();\n  else  if(*jobv=='S') matrix(vt,diag_size,*n,*ldvt)  = svd.matrixV().adjoint();\n  else  if(*jobv=='O') matrix(a,diag_size,*n,*lda)    = svd.matrixV().adjoint();\n  }\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/zlacgv.f",
    "content": "*> \\brief \\b ZLACGV\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ZLACGV + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/zlacgv.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/zlacgv.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/zlacgv.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE ZLACGV( N, X, INCX )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            INCX, N\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX*16         X( * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ZLACGV conjugates a complex vector of length N.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The length of the vector X.  N >= 0.\n*> \\endverbatim\n*>\n*> \\param[in,out] X\n*> \\verbatim\n*>          X is COMPLEX*16 array, dimension\n*>                         (1+(N-1)*abs(INCX))\n*>          On entry, the vector of length N to be conjugated.\n*>          On exit, X is overwritten with conjg(X).\n*> \\endverbatim\n*>\n*> \\param[in] INCX\n*> \\verbatim\n*>          INCX is INTEGER\n*>          The spacing between successive elements of X.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complex16OTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE ZLACGV( N, X, INCX )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      INTEGER            INCX, N\n*     ..\n*     .. Array Arguments ..\n      COMPLEX*16         X( * )\n*     ..\n*\n* =====================================================================\n*\n*     .. Local Scalars ..\n      INTEGER            I, IOFF\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          DCONJG\n*     ..\n*     .. Executable Statements ..\n*\n      IF( INCX.EQ.1 ) THEN\n         DO 10 I = 1, N\n            X( I ) = DCONJG( X( I ) )\n   10    CONTINUE\n      ELSE\n         IOFF = 1\n         IF( INCX.LT.0 )\n     $      IOFF = 1 - ( N-1 )*INCX\n         DO 20 I = 1, N\n            X( IOFF ) = DCONJG( X( IOFF ) )\n            IOFF = IOFF + INCX\n   20    CONTINUE\n      END IF\n      RETURN\n*\n*     End of ZLACGV\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/zladiv.f",
    "content": "*> \\brief \\b ZLADIV\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ZLADIV + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/zladiv.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/zladiv.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/zladiv.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       COMPLEX*16     FUNCTION ZLADIV( X, Y )\n* \n*       .. Scalar Arguments ..\n*       COMPLEX*16         X, Y\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ZLADIV := X / Y, where X and Y are complex.  The computation of X / Y\n*> will not overflow on an intermediary step unless the results\n*> overflows.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] X\n*> \\verbatim\n*>          X is COMPLEX*16\n*> \\endverbatim\n*>\n*> \\param[in] Y\n*> \\verbatim\n*>          Y is COMPLEX*16\n*>          The complex scalars X and Y.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complex16OTHERauxiliary\n*\n*  =====================================================================\n      COMPLEX*16     FUNCTION ZLADIV( X, Y )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      COMPLEX*16         X, Y\n*     ..\n*\n*  =====================================================================\n*\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ZI, ZR\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           DLADIV\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          DBLE, DCMPLX, DIMAG\n*     ..\n*     .. Executable Statements ..\n*\n      CALL DLADIV( DBLE( X ), DIMAG( X ), DBLE( Y ), DIMAG( Y ), ZR,\n     $             ZI )\n      ZLADIV = DCMPLX( ZR, ZI )\n*\n      RETURN\n*\n*     End of ZLADIV\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/zlarf.f",
    "content": "*> \\brief \\b ZLARF\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ZLARF + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/zlarf.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/zlarf.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/zlarf.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE ZLARF( SIDE, M, N, V, INCV, TAU, C, LDC, WORK )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          SIDE\n*       INTEGER            INCV, LDC, M, N\n*       COMPLEX*16         TAU\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX*16         C( LDC, * ), V( * ), WORK( * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ZLARF applies a complex elementary reflector H to a complex M-by-N\n*> matrix C, from either the left or the right. H is represented in the\n*> form\n*>\n*>       H = I - tau * v * v**H\n*>\n*> where tau is a complex scalar and v is a complex vector.\n*>\n*> If tau = 0, then H is taken to be the unit matrix.\n*>\n*> To apply H**H, supply conjg(tau) instead\n*> tau.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] SIDE\n*> \\verbatim\n*>          SIDE is CHARACTER*1\n*>          = 'L': form  H * C\n*>          = 'R': form  C * H\n*> \\endverbatim\n*>\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is COMPLEX*16 array, dimension\n*>                     (1 + (M-1)*abs(INCV)) if SIDE = 'L'\n*>                  or (1 + (N-1)*abs(INCV)) if SIDE = 'R'\n*>          The vector v in the representation of H. V is not used if\n*>          TAU = 0.\n*> \\endverbatim\n*>\n*> \\param[in] INCV\n*> \\verbatim\n*>          INCV is INTEGER\n*>          The increment between elements of v. INCV <> 0.\n*> \\endverbatim\n*>\n*> \\param[in] TAU\n*> \\verbatim\n*>          TAU is COMPLEX*16\n*>          The value tau in the representation of H.\n*> \\endverbatim\n*>\n*> \\param[in,out] C\n*> \\verbatim\n*>          C is COMPLEX*16 array, dimension (LDC,N)\n*>          On entry, the M-by-N matrix C.\n*>          On exit, C is overwritten by the matrix H * C if SIDE = 'L',\n*>          or C * H if SIDE = 'R'.\n*> \\endverbatim\n*>\n*> \\param[in] LDC\n*> \\verbatim\n*>          LDC is INTEGER\n*>          The leading dimension of the array C. LDC >= max(1,M).\n*> \\endverbatim\n*>\n*> \\param[out] WORK\n*> \\verbatim\n*>          WORK is COMPLEX*16 array, dimension\n*>                         (N) if SIDE = 'L'\n*>                      or (M) if SIDE = 'R'\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complex16OTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE ZLARF( SIDE, M, N, V, INCV, TAU, C, LDC, WORK )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      CHARACTER          SIDE\n      INTEGER            INCV, LDC, M, N\n      COMPLEX*16         TAU\n*     ..\n*     .. Array Arguments ..\n      COMPLEX*16         C( LDC, * ), V( * ), WORK( * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      COMPLEX*16         ONE, ZERO\n      PARAMETER          ( ONE = ( 1.0D+0, 0.0D+0 ),\n     $                   ZERO = ( 0.0D+0, 0.0D+0 ) )\n*     ..\n*     .. Local Scalars ..\n      LOGICAL            APPLYLEFT\n      INTEGER            I, LASTV, LASTC\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           ZGEMV, ZGERC\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      INTEGER            ILAZLR, ILAZLC\n      EXTERNAL           LSAME, ILAZLR, ILAZLC\n*     ..\n*     .. Executable Statements ..\n*\n      APPLYLEFT = LSAME( SIDE, 'L' )\n      LASTV = 0\n      LASTC = 0\n      IF( TAU.NE.ZERO ) THEN\n*     Set up variables for scanning V.  LASTV begins pointing to the end\n*     of V.\n         IF( APPLYLEFT ) THEN\n            LASTV = M\n         ELSE\n            LASTV = N\n         END IF\n         IF( INCV.GT.0 ) THEN\n            I = 1 + (LASTV-1) * INCV\n         ELSE\n            I = 1\n         END IF\n*     Look for the last non-zero row in V.\n         DO WHILE( LASTV.GT.0 .AND. V( I ).EQ.ZERO )\n            LASTV = LASTV - 1\n            I = I - INCV\n         END DO\n         IF( APPLYLEFT ) THEN\n*     Scan for the last non-zero column in C(1:lastv,:).\n            LASTC = ILAZLC(LASTV, N, C, LDC)\n         ELSE\n*     Scan for the last non-zero row in C(:,1:lastv).\n            LASTC = ILAZLR(M, LASTV, C, LDC)\n         END IF\n      END IF\n*     Note that lastc.eq.0 renders the BLAS operations null; no special\n*     case is needed at this level.\n      IF( APPLYLEFT ) THEN\n*\n*        Form  H * C\n*\n         IF( LASTV.GT.0 ) THEN\n*\n*           w(1:lastc,1) := C(1:lastv,1:lastc)**H * v(1:lastv,1)\n*\n            CALL ZGEMV( 'Conjugate transpose', LASTV, LASTC, ONE,\n     $           C, LDC, V, INCV, ZERO, WORK, 1 )\n*\n*           C(1:lastv,1:lastc) := C(...) - v(1:lastv,1) * w(1:lastc,1)**H\n*\n            CALL ZGERC( LASTV, LASTC, -TAU, V, INCV, WORK, 1, C, LDC )\n         END IF\n      ELSE\n*\n*        Form  C * H\n*\n         IF( LASTV.GT.0 ) THEN\n*\n*           w(1:lastc,1) := C(1:lastc,1:lastv) * v(1:lastv,1)\n*\n            CALL ZGEMV( 'No transpose', LASTC, LASTV, ONE, C, LDC,\n     $           V, INCV, ZERO, WORK, 1 )\n*\n*           C(1:lastc,1:lastv) := C(...) - w(1:lastc,1) * v(1:lastv,1)**H\n*\n            CALL ZGERC( LASTC, LASTV, -TAU, WORK, 1, V, INCV, C, LDC )\n         END IF\n      END IF\n      RETURN\n*\n*     End of ZLARF\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/zlarfb.f",
    "content": "*> \\brief \\b ZLARFB\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ZLARFB + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/zlarfb.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/zlarfb.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/zlarfb.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE ZLARFB( SIDE, TRANS, DIRECT, STOREV, M, N, K, V, LDV,\n*                          T, LDT, C, LDC, WORK, LDWORK )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          DIRECT, SIDE, STOREV, TRANS\n*       INTEGER            K, LDC, LDT, LDV, LDWORK, M, N\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX*16         C( LDC, * ), T( LDT, * ), V( LDV, * ),\n*      $                   WORK( LDWORK, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ZLARFB applies a complex block reflector H or its transpose H**H to a\n*> complex M-by-N matrix C, from either the left or the right.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] SIDE\n*> \\verbatim\n*>          SIDE is CHARACTER*1\n*>          = 'L': apply H or H**H from the Left\n*>          = 'R': apply H or H**H from the Right\n*> \\endverbatim\n*>\n*> \\param[in] TRANS\n*> \\verbatim\n*>          TRANS is CHARACTER*1\n*>          = 'N': apply H (No transpose)\n*>          = 'C': apply H**H (Conjugate transpose)\n*> \\endverbatim\n*>\n*> \\param[in] DIRECT\n*> \\verbatim\n*>          DIRECT is CHARACTER*1\n*>          Indicates how H is formed from a product of elementary\n*>          reflectors\n*>          = 'F': H = H(1) H(2) . . . H(k) (Forward)\n*>          = 'B': H = H(k) . . . H(2) H(1) (Backward)\n*> \\endverbatim\n*>\n*> \\param[in] STOREV\n*> \\verbatim\n*>          STOREV is CHARACTER*1\n*>          Indicates how the vectors which define the elementary\n*>          reflectors are stored:\n*>          = 'C': Columnwise\n*>          = 'R': Rowwise\n*> \\endverbatim\n*>\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] K\n*> \\verbatim\n*>          K is INTEGER\n*>          The order of the matrix T (= the number of elementary\n*>          reflectors whose product defines the block reflector).\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is COMPLEX*16 array, dimension\n*>                                (LDV,K) if STOREV = 'C'\n*>                                (LDV,M) if STOREV = 'R' and SIDE = 'L'\n*>                                (LDV,N) if STOREV = 'R' and SIDE = 'R'\n*>          See Further Details.\n*> \\endverbatim\n*>\n*> \\param[in] LDV\n*> \\verbatim\n*>          LDV is INTEGER\n*>          The leading dimension of the array V.\n*>          If STOREV = 'C' and SIDE = 'L', LDV >= max(1,M);\n*>          if STOREV = 'C' and SIDE = 'R', LDV >= max(1,N);\n*>          if STOREV = 'R', LDV >= K.\n*> \\endverbatim\n*>\n*> \\param[in] T\n*> \\verbatim\n*>          T is COMPLEX*16 array, dimension (LDT,K)\n*>          The triangular K-by-K matrix T in the representation of the\n*>          block reflector.\n*> \\endverbatim\n*>\n*> \\param[in] LDT\n*> \\verbatim\n*>          LDT is INTEGER\n*>          The leading dimension of the array T. LDT >= K.\n*> \\endverbatim\n*>\n*> \\param[in,out] C\n*> \\verbatim\n*>          C is COMPLEX*16 array, dimension (LDC,N)\n*>          On entry, the M-by-N matrix C.\n*>          On exit, C is overwritten by H*C or H**H*C or C*H or C*H**H.\n*> \\endverbatim\n*>\n*> \\param[in] LDC\n*> \\verbatim\n*>          LDC is INTEGER\n*>          The leading dimension of the array C. LDC >= max(1,M).\n*> \\endverbatim\n*>\n*> \\param[out] WORK\n*> \\verbatim\n*>          WORK is COMPLEX*16 array, dimension (LDWORK,K)\n*> \\endverbatim\n*>\n*> \\param[in] LDWORK\n*> \\verbatim\n*>          LDWORK is INTEGER\n*>          The leading dimension of the array WORK.\n*>          If SIDE = 'L', LDWORK >= max(1,N);\n*>          if SIDE = 'R', LDWORK >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complex16OTHERauxiliary\n*\n*> \\par Further Details:\n*  =====================\n*>\n*> \\verbatim\n*>\n*>  The shape of the matrix V and the storage of the vectors which define\n*>  the H(i) is best illustrated by the following example with n = 5 and\n*>  k = 3. The elements equal to 1 are not stored; the corresponding\n*>  array elements are modified but restored on exit. The rest of the\n*>  array is not used.\n*>\n*>  DIRECT = 'F' and STOREV = 'C':         DIRECT = 'F' and STOREV = 'R':\n*>\n*>               V = (  1       )                 V = (  1 v1 v1 v1 v1 )\n*>                   ( v1  1    )                     (     1 v2 v2 v2 )\n*>                   ( v1 v2  1 )                     (        1 v3 v3 )\n*>                   ( v1 v2 v3 )\n*>                   ( v1 v2 v3 )\n*>\n*>  DIRECT = 'B' and STOREV = 'C':         DIRECT = 'B' and STOREV = 'R':\n*>\n*>               V = ( v1 v2 v3 )                 V = ( v1 v1  1       )\n*>                   ( v1 v2 v3 )                     ( v2 v2 v2  1    )\n*>                   (  1 v2 v3 )                     ( v3 v3 v3 v3  1 )\n*>                   (     1 v3 )\n*>                   (        1 )\n*> \\endverbatim\n*>\n*  =====================================================================\n      SUBROUTINE ZLARFB( SIDE, TRANS, DIRECT, STOREV, M, N, K, V, LDV,\n     $                   T, LDT, C, LDC, WORK, LDWORK )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      CHARACTER          DIRECT, SIDE, STOREV, TRANS\n      INTEGER            K, LDC, LDT, LDV, LDWORK, M, N\n*     ..\n*     .. Array Arguments ..\n      COMPLEX*16         C( LDC, * ), T( LDT, * ), V( LDV, * ),\n     $                   WORK( LDWORK, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      COMPLEX*16         ONE\n      PARAMETER          ( ONE = ( 1.0D+0, 0.0D+0 ) )\n*     ..\n*     .. Local Scalars ..\n      CHARACTER          TRANST\n      INTEGER            I, J, LASTV, LASTC\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      INTEGER            ILAZLR, ILAZLC\n      EXTERNAL           LSAME, ILAZLR, ILAZLC\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           ZCOPY, ZGEMM, ZLACGV, ZTRMM\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          DCONJG\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick return if possible\n*\n      IF( M.LE.0 .OR. N.LE.0 )\n     $   RETURN\n*\n      IF( LSAME( TRANS, 'N' ) ) THEN\n         TRANST = 'C'\n      ELSE\n         TRANST = 'N'\n      END IF\n*\n      IF( LSAME( STOREV, 'C' ) ) THEN\n*\n         IF( LSAME( DIRECT, 'F' ) ) THEN\n*\n*           Let  V =  ( V1 )    (first K rows)\n*                     ( V2 )\n*           where  V1  is unit lower triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**H * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILAZLR( M, K, V, LDV ) )\n               LASTC = ILAZLC( LASTV, N, C, LDC )\n*\n*              W := C**H * V  =  (C1**H * V1 + C2**H * V2)  (stored in WORK)\n*\n*              W := C1**H\n*\n               DO 10 J = 1, K\n                  CALL ZCOPY( LASTC, C( J, 1 ), LDC, WORK( 1, J ), 1 )\n                  CALL ZLACGV( LASTC, WORK( 1, J ), 1 )\n   10          CONTINUE\n*\n*              W := W * V1\n*\n               CALL ZTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2**H *V2\n*\n                  CALL ZGEMM( 'Conjugate transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K, ONE, C( K+1, 1 ), LDC,\n     $                 V( K+1, 1 ), LDV, ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**H  or  W * T\n*\n               CALL ZTRMM( 'Right', 'Upper', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V * W**H\n*\n               IF( M.GT.K ) THEN\n*\n*                 C2 := C2 - V2 * W**H\n*\n                  CALL ZGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTV-K, LASTC, K,\n     $                 -ONE, V( K+1, 1 ), LDV, WORK, LDWORK,\n     $                 ONE, C( K+1, 1 ), LDC )\n               END IF\n*\n*              W := W * V1**H\n*\n               CALL ZTRMM( 'Right', 'Lower', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W**H\n*\n               DO 30 J = 1, K\n                  DO 20 I = 1, LASTC\n                     C( J, I ) = C( J, I ) - DCONJG( WORK( I, J ) )\n   20             CONTINUE\n   30          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**H  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILAZLR( N, K, V, LDV ) )\n               LASTC = ILAZLR( M, LASTV, C, LDC )\n*\n*              W := C * V  =  (C1*V1 + C2*V2)  (stored in WORK)\n*\n*              W := C1\n*\n               DO 40 J = 1, K\n                  CALL ZCOPY( LASTC, C( 1, J ), 1, WORK( 1, J ), 1 )\n   40          CONTINUE\n*\n*              W := W * V1\n*\n               CALL ZTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2 * V2\n*\n                  CALL ZGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C( 1, K+1 ), LDC, V( K+1, 1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**H\n*\n               CALL ZTRMM( 'Right', 'Upper', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V**H\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - W * V2**H\n*\n                  CALL ZGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTC, LASTV-K, K,\n     $                 -ONE, WORK, LDWORK, V( K+1, 1 ), LDV,\n     $                 ONE, C( 1, K+1 ), LDC )\n               END IF\n*\n*              W := W * V1**H\n*\n               CALL ZTRMM( 'Right', 'Lower', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 60 J = 1, K\n                  DO 50 I = 1, LASTC\n                     C( I, J ) = C( I, J ) - WORK( I, J )\n   50             CONTINUE\n   60          CONTINUE\n            END IF\n*\n         ELSE\n*\n*           Let  V =  ( V1 )\n*                     ( V2 )    (last K rows)\n*           where  V2  is unit upper triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**H * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILAZLR( M, K, V, LDV ) )\n               LASTC = ILAZLC( LASTV, N, C, LDC )\n*\n*              W := C**H * V  =  (C1**H * V1 + C2**H * V2)  (stored in WORK)\n*\n*              W := C2**H\n*\n               DO 70 J = 1, K\n                  CALL ZCOPY( LASTC, C( LASTV-K+J, 1 ), LDC,\n     $                 WORK( 1, J ), 1 )\n                  CALL ZLACGV( LASTC, WORK( 1, J ), 1 )\n   70          CONTINUE\n*\n*              W := W * V2\n*\n               CALL ZTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1**H*V1\n*\n                  CALL ZGEMM( 'Conjugate transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C, LDC, V, LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**H  or  W * T\n*\n               CALL ZTRMM( 'Right', 'Lower', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V * W**H\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - V1 * W**H\n*\n                  CALL ZGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTV-K, LASTC, K,\n     $                 -ONE, V, LDV, WORK, LDWORK,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2**H\n*\n               CALL ZTRMM( 'Right', 'Upper', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W**H\n*\n               DO 90 J = 1, K\n                  DO 80 I = 1, LASTC\n                     C( LASTV-K+J, I ) = C( LASTV-K+J, I ) -\n     $                               DCONJG( WORK( I, J ) )\n   80             CONTINUE\n   90          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**H  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILAZLR( N, K, V, LDV ) )\n               LASTC = ILAZLR( M, LASTV, C, LDC )\n*\n*              W := C * V  =  (C1*V1 + C2*V2)  (stored in WORK)\n*\n*              W := C2\n*\n               DO 100 J = 1, K\n                  CALL ZCOPY( LASTC, C( 1, LASTV-K+J ), 1,\n     $                 WORK( 1, J ), 1 )\n  100          CONTINUE\n*\n*              W := W * V2\n*\n               CALL ZTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1 * V1\n*\n                  CALL ZGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C, LDC, V, LDV, ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**H\n*\n               CALL ZTRMM( 'Right', 'Lower', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V**H\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - W * V1**H\n*\n                  CALL ZGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTC, LASTV-K, K, -ONE, WORK, LDWORK, V, LDV,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2**H\n*\n               CALL ZTRMM( 'Right', 'Upper', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W\n*\n               DO 120 J = 1, K\n                  DO 110 I = 1, LASTC\n                     C( I, LASTV-K+J ) = C( I, LASTV-K+J )\n     $                    - WORK( I, J )\n  110             CONTINUE\n  120          CONTINUE\n            END IF\n         END IF\n*\n      ELSE IF( LSAME( STOREV, 'R' ) ) THEN\n*\n         IF( LSAME( DIRECT, 'F' ) ) THEN\n*\n*           Let  V =  ( V1  V2 )    (V1: first K columns)\n*           where  V1  is unit upper triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**H * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILAZLC( K, M, V, LDV ) )\n               LASTC = ILAZLC( LASTV, N, C, LDC )\n*\n*              W := C**H * V**H  =  (C1**H * V1**H + C2**H * V2**H) (stored in WORK)\n*\n*              W := C1**H\n*\n               DO 130 J = 1, K\n                  CALL ZCOPY( LASTC, C( J, 1 ), LDC, WORK( 1, J ), 1 )\n                  CALL ZLACGV( LASTC, WORK( 1, J ), 1 )\n  130          CONTINUE\n*\n*              W := W * V1**H\n*\n               CALL ZTRMM( 'Right', 'Upper', 'Conjugate transpose',\n     $                     'Unit', LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2**H*V2**H\n*\n                  CALL ZGEMM( 'Conjugate transpose',\n     $                 'Conjugate transpose', LASTC, K, LASTV-K,\n     $                 ONE, C( K+1, 1 ), LDC, V( 1, K+1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**H  or  W * T\n*\n               CALL ZTRMM( 'Right', 'Upper', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V**H * W**H\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - V2**H * W**H\n*\n                  CALL ZGEMM( 'Conjugate transpose',\n     $                 'Conjugate transpose', LASTV-K, LASTC, K,\n     $                 -ONE, V( 1, K+1 ), LDV, WORK, LDWORK,\n     $                 ONE, C( K+1, 1 ), LDC )\n               END IF\n*\n*              W := W * V1\n*\n               CALL ZTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W**H\n*\n               DO 150 J = 1, K\n                  DO 140 I = 1, LASTC\n                     C( J, I ) = C( J, I ) - DCONJG( WORK( I, J ) )\n  140             CONTINUE\n  150          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**H  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILAZLC( K, N, V, LDV ) )\n               LASTC = ILAZLR( M, LASTV, C, LDC )\n*\n*              W := C * V**H  =  (C1*V1**H + C2*V2**H)  (stored in WORK)\n*\n*              W := C1\n*\n               DO 160 J = 1, K\n                  CALL ZCOPY( LASTC, C( 1, J ), 1, WORK( 1, J ), 1 )\n  160          CONTINUE\n*\n*              W := W * V1**H\n*\n               CALL ZTRMM( 'Right', 'Upper', 'Conjugate transpose',\n     $                     'Unit', LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2 * V2**H\n*\n                  CALL ZGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTC, K, LASTV-K, ONE, C( 1, K+1 ), LDC,\n     $                 V( 1, K+1 ), LDV, ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**H\n*\n               CALL ZTRMM( 'Right', 'Upper', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - W * V2\n*\n                  CALL ZGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, LASTV-K, K,\n     $                 -ONE, WORK, LDWORK, V( 1, K+1 ), LDV,\n     $                 ONE, C( 1, K+1 ), LDC )\n               END IF\n*\n*              W := W * V1\n*\n               CALL ZTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 180 J = 1, K\n                  DO 170 I = 1, LASTC\n                     C( I, J ) = C( I, J ) - WORK( I, J )\n  170             CONTINUE\n  180          CONTINUE\n*\n            END IF\n*\n         ELSE\n*\n*           Let  V =  ( V1  V2 )    (V2: last K columns)\n*           where  V2  is unit lower triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**H * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILAZLC( K, M, V, LDV ) )\n               LASTC = ILAZLC( LASTV, N, C, LDC )\n*\n*              W := C**H * V**H  =  (C1**H * V1**H + C2**H * V2**H) (stored in WORK)\n*\n*              W := C2**H\n*\n               DO 190 J = 1, K\n                  CALL ZCOPY( LASTC, C( LASTV-K+J, 1 ), LDC,\n     $                 WORK( 1, J ), 1 )\n                  CALL ZLACGV( LASTC, WORK( 1, J ), 1 )\n  190          CONTINUE\n*\n*              W := W * V2**H\n*\n               CALL ZTRMM( 'Right', 'Lower', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1**H * V1**H\n*\n                  CALL ZGEMM( 'Conjugate transpose',\n     $                 'Conjugate transpose', LASTC, K, LASTV-K,\n     $                 ONE, C, LDC, V, LDV, ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**H  or  W * T\n*\n               CALL ZTRMM( 'Right', 'Lower', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V**H * W**H\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - V1**H * W**H\n*\n                  CALL ZGEMM( 'Conjugate transpose',\n     $                 'Conjugate transpose', LASTV-K, LASTC, K,\n     $                 -ONE, V, LDV, WORK, LDWORK, ONE, C, LDC )\n               END IF\n*\n*              W := W * V2\n*\n               CALL ZTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W**H\n*\n               DO 210 J = 1, K\n                  DO 200 I = 1, LASTC\n                     C( LASTV-K+J, I ) = C( LASTV-K+J, I ) -\n     $                               DCONJG( WORK( I, J ) )\n  200             CONTINUE\n  210          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**H  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILAZLC( K, N, V, LDV ) )\n               LASTC = ILAZLR( M, LASTV, C, LDC )\n*\n*              W := C * V**H  =  (C1*V1**H + C2*V2**H)  (stored in WORK)\n*\n*              W := C2\n*\n               DO 220 J = 1, K\n                  CALL ZCOPY( LASTC, C( 1, LASTV-K+J ), 1,\n     $                 WORK( 1, J ), 1 )\n  220          CONTINUE\n*\n*              W := W * V2**H\n*\n               CALL ZTRMM( 'Right', 'Lower', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1 * V1**H\n*\n                  CALL ZGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV, ONE,\n     $                 WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**H\n*\n               CALL ZTRMM( 'Right', 'Lower', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - W * V1\n*\n                  CALL ZGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, LASTV-K, K, -ONE, WORK, LDWORK, V, LDV,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2\n*\n               CALL ZTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 240 J = 1, K\n                  DO 230 I = 1, LASTC\n                     C( I, LASTV-K+J ) = C( I, LASTV-K+J )\n     $                    - WORK( I, J )\n  230             CONTINUE\n  240          CONTINUE\n*\n            END IF\n*\n         END IF\n      END IF\n*\n      RETURN\n*\n*     End of ZLARFB\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/zlarfg.f",
    "content": "*> \\brief \\b ZLARFG\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ZLARFG + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/zlarfg.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/zlarfg.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/zlarfg.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE ZLARFG( N, ALPHA, X, INCX, TAU )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            INCX, N\n*       COMPLEX*16         ALPHA, TAU\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX*16         X( * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ZLARFG generates a complex elementary reflector H of order n, such\n*> that\n*>\n*>       H**H * ( alpha ) = ( beta ),   H**H * H = I.\n*>              (   x   )   (   0  )\n*>\n*> where alpha and beta are scalars, with beta real, and x is an\n*> (n-1)-element complex vector. H is represented in the form\n*>\n*>       H = I - tau * ( 1 ) * ( 1 v**H ) ,\n*>                     ( v )\n*>\n*> where tau is a complex scalar and v is a complex (n-1)-element\n*> vector. Note that H is not hermitian.\n*>\n*> If the elements of x are all zero and alpha is real, then tau = 0\n*> and H is taken to be the unit matrix.\n*>\n*> Otherwise  1 <= real(tau) <= 2  and  abs(tau-1) <= 1 .\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The order of the elementary reflector.\n*> \\endverbatim\n*>\n*> \\param[in,out] ALPHA\n*> \\verbatim\n*>          ALPHA is COMPLEX*16\n*>          On entry, the value alpha.\n*>          On exit, it is overwritten with the value beta.\n*> \\endverbatim\n*>\n*> \\param[in,out] X\n*> \\verbatim\n*>          X is COMPLEX*16 array, dimension\n*>                         (1+(N-2)*abs(INCX))\n*>          On entry, the vector x.\n*>          On exit, it is overwritten with the vector v.\n*> \\endverbatim\n*>\n*> \\param[in] INCX\n*> \\verbatim\n*>          INCX is INTEGER\n*>          The increment between elements of X. INCX > 0.\n*> \\endverbatim\n*>\n*> \\param[out] TAU\n*> \\verbatim\n*>          TAU is COMPLEX*16\n*>          The value tau.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complex16OTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE ZLARFG( N, ALPHA, X, INCX, TAU )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      INTEGER            INCX, N\n      COMPLEX*16         ALPHA, TAU\n*     ..\n*     .. Array Arguments ..\n      COMPLEX*16         X( * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ONE, ZERO\n      PARAMETER          ( ONE = 1.0D+0, ZERO = 0.0D+0 )\n*     ..\n*     .. Local Scalars ..\n      INTEGER            J, KNT\n      DOUBLE PRECISION   ALPHI, ALPHR, BETA, RSAFMN, SAFMIN, XNORM\n*     ..\n*     .. External Functions ..\n      DOUBLE PRECISION   DLAMCH, DLAPY3, DZNRM2\n      COMPLEX*16         ZLADIV\n      EXTERNAL           DLAMCH, DLAPY3, DZNRM2, ZLADIV\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, DBLE, DCMPLX, DIMAG, SIGN\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           ZDSCAL, ZSCAL\n*     ..\n*     .. Executable Statements ..\n*\n      IF( N.LE.0 ) THEN\n         TAU = ZERO\n         RETURN\n      END IF\n*\n      XNORM = DZNRM2( N-1, X, INCX )\n      ALPHR = DBLE( ALPHA )\n      ALPHI = DIMAG( ALPHA )\n*\n      IF( XNORM.EQ.ZERO .AND. ALPHI.EQ.ZERO ) THEN\n*\n*        H  =  I\n*\n         TAU = ZERO\n      ELSE\n*\n*        general case\n*\n         BETA = -SIGN( DLAPY3( ALPHR, ALPHI, XNORM ), ALPHR )\n         SAFMIN = DLAMCH( 'S' ) / DLAMCH( 'E' )\n         RSAFMN = ONE / SAFMIN\n*\n         KNT = 0\n         IF( ABS( BETA ).LT.SAFMIN ) THEN\n*\n*           XNORM, BETA may be inaccurate; scale X and recompute them\n*\n   10       CONTINUE\n            KNT = KNT + 1\n            CALL ZDSCAL( N-1, RSAFMN, X, INCX )\n            BETA = BETA*RSAFMN\n            ALPHI = ALPHI*RSAFMN\n            ALPHR = ALPHR*RSAFMN\n            IF( ABS( BETA ).LT.SAFMIN )\n     $         GO TO 10\n*\n*           New BETA is at most 1, at least SAFMIN\n*\n            XNORM = DZNRM2( N-1, X, INCX )\n            ALPHA = DCMPLX( ALPHR, ALPHI )\n            BETA = -SIGN( DLAPY3( ALPHR, ALPHI, XNORM ), ALPHR )\n         END IF\n         TAU = DCMPLX( ( BETA-ALPHR ) / BETA, -ALPHI / BETA )\n         ALPHA = ZLADIV( DCMPLX( ONE ), ALPHA-BETA )\n         CALL ZSCAL( N-1, ALPHA, X, INCX )\n*\n*        If ALPHA is subnormal, it may lose relative accuracy\n*\n         DO 20 J = 1, KNT\n            BETA = BETA*SAFMIN\n 20      CONTINUE\n         ALPHA = BETA\n      END IF\n*\n      RETURN\n*\n*     End of ZLARFG\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/lapack/zlarft.f",
    "content": "*> \\brief \\b ZLARFT\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ZLARFT + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/zlarft.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/zlarft.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/zlarft.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE ZLARFT( DIRECT, STOREV, N, K, V, LDV, TAU, T, LDT )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          DIRECT, STOREV\n*       INTEGER            K, LDT, LDV, N\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX*16         T( LDT, * ), TAU( * ), V( LDV, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ZLARFT forms the triangular factor T of a complex block reflector H\n*> of order n, which is defined as a product of k elementary reflectors.\n*>\n*> If DIRECT = 'F', H = H(1) H(2) . . . H(k) and T is upper triangular;\n*>\n*> If DIRECT = 'B', H = H(k) . . . H(2) H(1) and T is lower triangular.\n*>\n*> If STOREV = 'C', the vector which defines the elementary reflector\n*> H(i) is stored in the i-th column of the array V, and\n*>\n*>    H  =  I - V * T * V**H\n*>\n*> If STOREV = 'R', the vector which defines the elementary reflector\n*> H(i) is stored in the i-th row of the array V, and\n*>\n*>    H  =  I - V**H * T * V\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] DIRECT\n*> \\verbatim\n*>          DIRECT is CHARACTER*1\n*>          Specifies the order in which the elementary reflectors are\n*>          multiplied to form the block reflector:\n*>          = 'F': H = H(1) H(2) . . . H(k) (Forward)\n*>          = 'B': H = H(k) . . . H(2) H(1) (Backward)\n*> \\endverbatim\n*>\n*> \\param[in] STOREV\n*> \\verbatim\n*>          STOREV is CHARACTER*1\n*>          Specifies how the vectors which define the elementary\n*>          reflectors are stored (see also Further Details):\n*>          = 'C': columnwise\n*>          = 'R': rowwise\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The order of the block reflector H. N >= 0.\n*> \\endverbatim\n*>\n*> \\param[in] K\n*> \\verbatim\n*>          K is INTEGER\n*>          The order of the triangular factor T (= the number of\n*>          elementary reflectors). K >= 1.\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is COMPLEX*16 array, dimension\n*>                               (LDV,K) if STOREV = 'C'\n*>                               (LDV,N) if STOREV = 'R'\n*>          The matrix V. See further details.\n*> \\endverbatim\n*>\n*> \\param[in] LDV\n*> \\verbatim\n*>          LDV is INTEGER\n*>          The leading dimension of the array V.\n*>          If STOREV = 'C', LDV >= max(1,N); if STOREV = 'R', LDV >= K.\n*> \\endverbatim\n*>\n*> \\param[in] TAU\n*> \\verbatim\n*>          TAU is COMPLEX*16 array, dimension (K)\n*>          TAU(i) must contain the scalar factor of the elementary\n*>          reflector H(i).\n*> \\endverbatim\n*>\n*> \\param[out] T\n*> \\verbatim\n*>          T is COMPLEX*16 array, dimension (LDT,K)\n*>          The k by k triangular factor T of the block reflector.\n*>          If DIRECT = 'F', T is upper triangular; if DIRECT = 'B', T is\n*>          lower triangular. The rest of the array is not used.\n*> \\endverbatim\n*>\n*> \\param[in] LDT\n*> \\verbatim\n*>          LDT is INTEGER\n*>          The leading dimension of the array T. LDT >= K.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup complex16OTHERauxiliary\n*\n*> \\par Further Details:\n*  =====================\n*>\n*> \\verbatim\n*>\n*>  The shape of the matrix V and the storage of the vectors which define\n*>  the H(i) is best illustrated by the following example with n = 5 and\n*>  k = 3. The elements equal to 1 are not stored.\n*>\n*>  DIRECT = 'F' and STOREV = 'C':         DIRECT = 'F' and STOREV = 'R':\n*>\n*>               V = (  1       )                 V = (  1 v1 v1 v1 v1 )\n*>                   ( v1  1    )                     (     1 v2 v2 v2 )\n*>                   ( v1 v2  1 )                     (        1 v3 v3 )\n*>                   ( v1 v2 v3 )\n*>                   ( v1 v2 v3 )\n*>\n*>  DIRECT = 'B' and STOREV = 'C':         DIRECT = 'B' and STOREV = 'R':\n*>\n*>               V = ( v1 v2 v3 )                 V = ( v1 v1  1       )\n*>                   ( v1 v2 v3 )                     ( v2 v2 v2  1    )\n*>                   (  1 v2 v3 )                     ( v3 v3 v3 v3  1 )\n*>                   (     1 v3 )\n*>                   (        1 )\n*> \\endverbatim\n*>\n*  =====================================================================\n      SUBROUTINE ZLARFT( DIRECT, STOREV, N, K, V, LDV, TAU, T, LDT )\n*\n*  -- LAPACK auxiliary routine (version 3.4.1) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*     .. Scalar Arguments ..\n      CHARACTER          DIRECT, STOREV\n      INTEGER            K, LDT, LDV, N\n*     ..\n*     .. Array Arguments ..\n      COMPLEX*16         T( LDT, * ), TAU( * ), V( LDV, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      COMPLEX*16         ONE, ZERO\n      PARAMETER          ( ONE = ( 1.0D+0, 0.0D+0 ),\n     $                   ZERO = ( 0.0D+0, 0.0D+0 ) )\n*     ..\n*     .. Local Scalars ..\n      INTEGER            I, J, PREVLASTV, LASTV\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           ZGEMV, ZLACGV, ZTRMV\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      EXTERNAL           LSAME\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick return if possible\n*\n      IF( N.EQ.0 )\n     $   RETURN\n*\n      IF( LSAME( DIRECT, 'F' ) ) THEN\n         PREVLASTV = N\n         DO I = 1, K\n            PREVLASTV = MAX( PREVLASTV, I )\n            IF( TAU( I ).EQ.ZERO ) THEN\n*\n*              H(i)  =  I\n*\n               DO J = 1, I\n                  T( J, I ) = ZERO\n               END DO\n            ELSE\n*\n*              general case\n*\n               IF( LSAME( STOREV, 'C' ) ) THEN\n*                 Skip any trailing zeros.\n                  DO LASTV = N, I+1, -1\n                     IF( V( LASTV, I ).NE.ZERO ) EXIT\n                  END DO\n                  DO J = 1, I-1\n                     T( J, I ) = -TAU( I ) * CONJG( V( I , J ) )\n                  END DO                     \n                  J = MIN( LASTV, PREVLASTV )\n*\n*                 T(1:i-1,i) := - tau(i) * V(i:j,1:i-1)**H * V(i:j,i)\n*\n                  CALL ZGEMV( 'Conjugate transpose', J-I, I-1,\n     $                        -TAU( I ), V( I+1, 1 ), LDV, \n     $                        V( I+1, I ), 1, ONE, T( 1, I ), 1 )\n               ELSE\n*                 Skip any trailing zeros.\n                  DO LASTV = N, I+1, -1\n                     IF( V( I, LASTV ).NE.ZERO ) EXIT\n                  END DO\n                  DO J = 1, I-1\n                     T( J, I ) = -TAU( I ) * V( J , I )\n                  END DO                     \n                  J = MIN( LASTV, PREVLASTV )\n*\n*                 T(1:i-1,i) := - tau(i) * V(1:i-1,i:j) * V(i,i:j)**H\n*\n                  CALL ZGEMM( 'N', 'C', I-1, 1, J-I, -TAU( I ),\n     $                        V( 1, I+1 ), LDV, V( I, I+1 ), LDV,\n     $                        ONE, T( 1, I ), LDT )                  \n               END IF\n*\n*              T(1:i-1,i) := T(1:i-1,1:i-1) * T(1:i-1,i)\n*\n               CALL ZTRMV( 'Upper', 'No transpose', 'Non-unit', I-1, T,\n     $                     LDT, T( 1, I ), 1 )\n               T( I, I ) = TAU( I )\n               IF( I.GT.1 ) THEN\n                  PREVLASTV = MAX( PREVLASTV, LASTV )\n               ELSE\n                  PREVLASTV = LASTV\n               END IF\n             END IF\n         END DO\n      ELSE\n         PREVLASTV = 1\n         DO I = K, 1, -1\n            IF( TAU( I ).EQ.ZERO ) THEN\n*\n*              H(i)  =  I\n*\n               DO J = I, K\n                  T( J, I ) = ZERO\n               END DO\n            ELSE\n*\n*              general case\n*\n               IF( I.LT.K ) THEN\n                  IF( LSAME( STOREV, 'C' ) ) THEN\n*                    Skip any leading zeros.\n                     DO LASTV = 1, I-1\n                        IF( V( LASTV, I ).NE.ZERO ) EXIT\n                     END DO\n                     DO J = I+1, K\n                        T( J, I ) = -TAU( I ) * CONJG( V( N-K+I , J ) )\n                     END DO                        \n                     J = MAX( LASTV, PREVLASTV )\n*\n*                    T(i+1:k,i) = -tau(i) * V(j:n-k+i,i+1:k)**H * V(j:n-k+i,i)\n*\n                     CALL ZGEMV( 'Conjugate transpose', N-K+I-J, K-I,\n     $                           -TAU( I ), V( J, I+1 ), LDV, V( J, I ),\n     $                           1, ONE, T( I+1, I ), 1 )\n                  ELSE\n*                    Skip any leading zeros.\n                     DO LASTV = 1, I-1\n                        IF( V( I, LASTV ).NE.ZERO ) EXIT\n                     END DO\n                     DO J = I+1, K\n                        T( J, I ) = -TAU( I ) * V( J, N-K+I )\n                     END DO                                           \n                     J = MAX( LASTV, PREVLASTV )\n*\n*                    T(i+1:k,i) = -tau(i) * V(i+1:k,j:n-k+i) * V(i,j:n-k+i)**H\n*\n                     CALL ZGEMM( 'N', 'C', K-I, 1, N-K+I-J, -TAU( I ),\n     $                           V( I+1, J ), LDV, V( I, J ), LDV,\n     $                           ONE, T( I+1, I ), LDT )                     \n                  END IF\n*\n*                 T(i+1:k,i) := T(i+1:k,i+1:k) * T(i+1:k,i)\n*\n                  CALL ZTRMV( 'Lower', 'No transpose', 'Non-unit', K-I,\n     $                        T( I+1, I+1 ), LDT, T( I+1, I ), 1 )\n                  IF( I.GT.1 ) THEN\n                     PREVLASTV = MIN( PREVLASTV, LASTV )\n                  ELSE\n                     PREVLASTV = LASTV\n                  END IF\n               END IF\n               T( I, I ) = TAU( I )\n            END IF\n         END DO\n      END IF\n      RETURN\n*\n*     End of ZLARFT\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/scripts/CMakeLists.txt",
    "content": "get_property(EIGEN_TESTS_LIST GLOBAL PROPERTY EIGEN_TESTS_LIST)\nconfigure_file(buildtests.in ${CMAKE_BINARY_DIR}/buildtests.sh @ONLY)\n\nconfigure_file(check.in ${CMAKE_BINARY_DIR}/check.sh COPYONLY)\nconfigure_file(debug.in ${CMAKE_BINARY_DIR}/debug.sh COPYONLY)\nconfigure_file(release.in ${CMAKE_BINARY_DIR}/release.sh COPYONLY)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/scripts/cdashtesting.cmake.in",
    "content": "\nset(CTEST_SOURCE_DIRECTORY  \"@CMAKE_SOURCE_DIR@\")\nset(CTEST_BINARY_DIRECTORY  \"@CMAKE_BINARY_DIR@\")\nset(CTEST_CMAKE_GENERATOR   \"@CMAKE_GENERATOR@\")\nset(CTEST_BUILD_NAME        \"@BUILDNAME@\")\nset(CTEST_SITE              \"@SITE@\")\n\nset(MODEL Experimental)\nif(${CTEST_SCRIPT_ARG} MATCHES Nightly)\n  set(MODEL Nightly)\nelseif(${CTEST_SCRIPT_ARG} MATCHES Continuous)\n  set(MODEL Continuous)\nendif()\n\nfind_program(CTEST_GIT_COMMAND NAMES git)\nset(CTEST_UPDATE_COMMAND \"${CTEST_GIT_COMMAND}\")\n\nctest_start(${MODEL} ${CTEST_SOURCE_DIRECTORY} ${CTEST_BINARY_DIRECTORY})\n\nctest_update(SOURCE \"${CTEST_SOURCE_DIRECTORY}\")\nctest_submit(PARTS Update Notes)\n\n# to get CTEST_PROJECT_SUBPROJECTS definition:\ninclude(\"${CTEST_SOURCE_DIRECTORY}/CTestConfig.cmake\")\n\nforeach(subproject ${CTEST_PROJECT_SUBPROJECTS})\n  message(\"\")\n  message(\"Process ${subproject}\")\n  \n  set_property(GLOBAL PROPERTY SubProject ${subproject})\n  set_property(GLOBAL PROPERTY Label ${subproject})\n\n  ctest_configure(BUILD ${CTEST_BINARY_DIRECTORY} SOURCE ${CTEST_SOURCE_DIRECTORY} )\n  ctest_submit(PARTS Configure)\n\n  set(CTEST_BUILD_TARGET \"Build${subproject}\")\n  message(\"Build ${CTEST_BUILD_TARGET}\")\n  ctest_build(BUILD \"${CTEST_BINARY_DIRECTORY}\" APPEND)\n  # builds target ${CTEST_BUILD_TARGET}\n  ctest_submit(PARTS Build)\n\n  ctest_test(BUILD \"${CTEST_BINARY_DIRECTORY}\" INCLUDE_LABEL \"${subproject}\" )\n  # runs only tests that have a LABELS property matching \"${subproject}\"\n  \n  ctest_coverage(BUILD \"${CTEST_BINARY_DIRECTORY}\" LABELS \"${subproject}\" )\n  \n  ctest_submit(PARTS Test)\n  \nendforeach()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/scripts/check.in",
    "content": "#!/bin/bash\n# check : shorthand for make and ctest -R\n\nif [[ $# != 1 || $1 == *help ]]\nthen\n  echo \"usage: $0 regexp\"\n  echo \"  Builds and runs tests matching the regexp.\"\n  echo \"  The EIGEN_MAKE_ARGS environment variable allows to pass args to 'make'.\"\n  echo \"    For example, to launch 5 concurrent builds, use EIGEN_MAKE_ARGS='-j5'\"\n  echo \"  The EIGEN_CTEST_ARGS environment variable allows to pass args to 'ctest'.\"\n  echo \"    For example, with CTest 2.8, you can use EIGEN_CTEST_ARGS='-j5'.\"\n  exit 0\nfi\n\nif [ -n \"${EIGEN_CTEST_ARGS:+x}\" ]\nthen\n  ./buildtests.sh \"$1\" && ctest -R \"$1\" ${EIGEN_CTEST_ARGS}\nelse\n  ./buildtests.sh \"$1\" && ctest -R \"$1\"\nfi\nexit $?\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/scripts/debug.in",
    "content": "#!/bin/sh\n\ncmake -DCMAKE_BUILD_TYPE=Debug .\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/scripts/eigen_gen_credits.cpp",
    "content": "#include <string>\n#include <sstream>\n#include <iostream>\n#include <fstream>\n#include <iomanip>\n#include <map>\n#include <list>\n\nusing namespace std;\n\n// this function takes a line that may contain a name and/or email address,\n// and returns just the name, while fixing the \"bad cases\".\nstd::string contributor_name(const std::string& line)\n{\n  string result;\n\n  // let's first take care of the case of isolated email addresses, like\n  // \"user@localhost.localdomain\" entries\n  if(line.find(\"markb@localhost.localdomain\") != string::npos)\n  {\n    return \"Mark Borgerding\";\n  }\n\n  if(line.find(\"kayhman@contact.intra.cea.fr\") != string::npos)\n  {\n    return \"Guillaume Saupin\";\n  }\n\n  // from there on we assume that we have a entry of the form\n  // either:\n  //   Bla bli Blurp\n  // or:\n  //   Bla bli Blurp <bblurp@email.com>\n  \n  size_t position_of_email_address = line.find_first_of('<');\n  if(position_of_email_address != string::npos)\n  {\n    // there is an e-mail address in <...>.\n    \n    // Hauke once committed as \"John Smith\", fix that.\n    if(line.find(\"hauke.heibel\") != string::npos)\n      result = \"Hauke Heibel\";\n    else\n    {\n      // just remove the e-mail address\n      result = line.substr(0, position_of_email_address);\n    }\n  }\n  else\n  {\n    // there is no e-mail address in <...>.\n    \n    if(line.find(\"convert-repo\") != string::npos)\n      result = \"\";\n    else\n      result = line;\n  }\n\n  // remove trailing spaces\n  size_t length = result.length();\n  while(length >= 1 && result[length-1] == ' ') result.erase(--length);\n\n  return result;\n}\n\n// parses hg churn output to generate a contributors map.\nmap<string,int> contributors_map_from_churn_output(const char *filename)\n{\n  map<string,int> contributors_map;\n\n  string line;\n  ifstream churn_out;\n  churn_out.open(filename, ios::in);\n  while(!getline(churn_out,line).eof())\n  {\n    // remove the histograms \"******\" that hg churn may draw at the end of some lines\n    size_t first_star = line.find_first_of('*');\n    if(first_star != string::npos) line.erase(first_star);\n    \n    // remove trailing spaces\n    size_t length = line.length();\n    while(length >= 1 && line[length-1] == ' ') line.erase(--length);\n\n    // now the last space indicates where the number starts\n    size_t last_space = line.find_last_of(' ');\n    \n    // get the number (of changesets or of modified lines for each contributor)\n    int number;\n    istringstream(line.substr(last_space+1)) >> number;\n\n    // get the name of the contributor\n    line.erase(last_space);    \n    string name = contributor_name(line);\n    \n    map<string,int>::iterator it = contributors_map.find(name);\n    // if new contributor, insert\n    if(it == contributors_map.end())\n      contributors_map.insert(pair<string,int>(name, number));\n    // if duplicate, just add the number\n    else\n      it->second += number;\n  }\n  churn_out.close();\n\n  return contributors_map;\n}\n\n// find the last name, i.e. the last word.\n// for \"van den Schbling\" types of last names, that's not a problem, that's actually what we want.\nstring lastname(const string& name)\n{\n  size_t last_space = name.find_last_of(' ');\n  if(last_space >= name.length()-1) return name;\n  else return name.substr(last_space+1);\n}\n\nstruct contributor\n{\n  string name;\n  int changedlines;\n  int changesets;\n  string url;\n  string misc;\n  \n  contributor() : changedlines(0), changesets(0) {}\n  \n  bool operator < (const contributor& other)\n  {\n    return lastname(name).compare(lastname(other.name)) < 0;\n  }\n};\n\nvoid add_online_info_into_contributors_list(list<contributor>& contributors_list, const char *filename)\n{\n  string line;\n  ifstream online_info;\n  online_info.open(filename, ios::in);\n  while(!getline(online_info,line).eof())\n  {\n    string hgname, realname, url, misc;\n    \n    size_t last_bar = line.find_last_of('|');\n    if(last_bar == string::npos) continue;\n    if(last_bar < line.length())\n      misc = line.substr(last_bar+1);\n    line.erase(last_bar);\n    \n    last_bar = line.find_last_of('|');\n    if(last_bar == string::npos) continue;\n    if(last_bar < line.length())\n      url = line.substr(last_bar+1);\n    line.erase(last_bar);\n\n    last_bar = line.find_last_of('|');\n    if(last_bar == string::npos) continue;\n    if(last_bar < line.length())\n      realname = line.substr(last_bar+1);\n    line.erase(last_bar);\n\n    hgname = line;\n    \n    // remove the example line\n    if(hgname.find(\"MercurialName\") != string::npos) continue;\n    \n    list<contributor>::iterator it;\n    for(it=contributors_list.begin(); it != contributors_list.end() && it->name != hgname; ++it)\n    {}\n    \n    if(it == contributors_list.end())\n    {\n      contributor c;\n      c.name = realname;\n      c.url = url;\n      c.misc = misc;\n      contributors_list.push_back(c);\n    }\n    else\n    {\n      it->name = realname;\n      it->url = url;\n      it->misc = misc;\n    }\n  }\n}\n\nint main()\n{\n  // parse the hg churn output files\n  map<string,int> contributors_map_for_changedlines = contributors_map_from_churn_output(\"churn-changedlines.out\");\n  //map<string,int> contributors_map_for_changesets = contributors_map_from_churn_output(\"churn-changesets.out\");\n  \n  // merge into the contributors list\n  list<contributor> contributors_list;\n  map<string,int>::iterator it;\n  for(it=contributors_map_for_changedlines.begin(); it != contributors_map_for_changedlines.end(); ++it)\n  {\n    contributor c;\n    c.name = it->first;\n    c.changedlines = it->second;\n    c.changesets = 0; //contributors_map_for_changesets.find(it->first)->second;\n    contributors_list.push_back(c);\n  }\n  \n  add_online_info_into_contributors_list(contributors_list, \"online-info.out\");\n  \n  contributors_list.sort();\n  \n  cout << \"{| cellpadding=\\\"5\\\"\\n\";\n  cout << \"!\\n\";\n  cout << \"! Lines changed\\n\";\n  cout << \"!\\n\";\n\n  list<contributor>::iterator itc;\n  int i = 0;\n  for(itc=contributors_list.begin(); itc != contributors_list.end(); ++itc)\n  {\n    if(itc->name.length() == 0) continue;\n    if(i%2) cout << \"|-\\n\";\n    else cout << \"|- style=\\\"background:#FFFFD0\\\"\\n\";\n    if(itc->url.length())\n      cout << \"| [\" << itc->url << \" \" << itc->name << \"]\\n\";\n    else\n      cout << \"| \" << itc->name << \"\\n\";\n    if(itc->changedlines)\n      cout << \"| \" << itc->changedlines << \"\\n\";\n    else\n      cout << \"| (no information)\\n\";\n    cout << \"| \" << itc->misc << \"\\n\";\n    i++;\n  }\n  cout << \"|}\" << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/scripts/eigen_gen_docs",
    "content": "#!/bin/sh\n\n# configuration\n# You should call this script with USER set as you want, else some default\n# will be used\nUSER=${USER:-'orzel'}\nUPLOAD_DIR=dox-devel\n\n#ulimit -v 1024000\n\n# step 1 : build\nrm build/doc/html -Rf\nmkdir build -p\n(cd build && cmake .. && make doc) || { echo \"make failed\"; exit 1; }\n\n#step 2 : upload\n# (the '/' at the end of path is very important, see rsync documentation)\nrsync -az --no-p --delete build/doc/html/ $USER@ssh.tuxfamily.org:eigen/eigen.tuxfamily.org-web/htdocs/$UPLOAD_DIR/ || { echo \"upload failed\"; exit 1; }\n\n#step 3 : fix the perm\nssh $USER@ssh.tuxfamily.org \"chmod -R g+w /home/eigen/eigen.tuxfamily.org-web/htdocs/$UPLOAD_DIR\" || { echo \"perm failed\"; exit 1; }\n\necho \"Uploaded successfully\"\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/scripts/eigen_gen_split_test_help.cmake",
    "content": "#!cmake -P\nfile(WRITE split_test_helper.h \"\")\nforeach(i RANGE 1 999)\n  file(APPEND split_test_helper.h\n    \"#if defined(EIGEN_TEST_PART_${i}) || defined(EIGEN_TEST_PART_ALL)\\n\"\n    \"#define CALL_SUBTEST_${i}(FUNC) CALL_SUBTEST(FUNC)\\n\"\n    \"#else\\n\"\n    \"#define CALL_SUBTEST_${i}(FUNC)\\n\"\n    \"#endif\\n\\n\"\n  )\nendforeach()"
  },
  {
    "path": "VO_Module/thirdparty/eigen/scripts/eigen_monitor_perf.sh",
    "content": "#!/bin/bash\n\n# This is a script example to automatically update and upload performance unit tests.\n# The following five variables must be adjusted to match your settings.\n\nUSER='ggael'\nUPLOAD_DIR=perf_monitoring/ggaelmacbook26\nEIGEN_SOURCE_PATH=$HOME/Eigen/eigen\nexport PREFIX=\"haswell-fma\"\nexport CXX_FLAGS=\"-mfma -w\"\n\n####\n\nBENCH_PATH=$EIGEN_SOURCE_PATH/bench/perf_monitoring/$PREFIX\nPREVPATH=$(pwd)\ncd $EIGEN_SOURCE_PATH/bench/perf_monitoring && ./runall.sh \"Haswell 2.6GHz, FMA, Apple's clang\" \"$@\"\ncd $PREVPATH || exit 1\n\nALLFILES=\"$BENCH_PATH/*.png $BENCH_PATH/*.html $BENCH_PATH/index.html $BENCH_PATH/s1.js $BENCH_PATH/s2.js\"\n\n# (the '/' at the end of path is very important, see rsync documentation)\nrsync -az --no-p --delete $ALLFILES $USER@ssh.tuxfamily.org:eigen/eigen.tuxfamily.org-web/htdocs/$UPLOAD_DIR/ || { echo \"upload failed\"; exit 1; }\n\n# fix the perm\nssh $USER@ssh.tuxfamily.org \"chmod -R g+w /home/eigen/eigen.tuxfamily.org-web/htdocs/perf_monitoring\" || { echo \"perm failed\"; exit 1; }\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/scripts/release.in",
    "content": "#!/bin/sh\n\ncmake -DCMAKE_BUILD_TYPE=Release .\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/scripts/relicense.py",
    "content": "# This file is part of Eigen, a lightweight C++ template library\n# for linear algebra.\n#\n# Copyright (C) 2012 Keir Mierle <mierle@gmail.com>\n#\n# This Source Code Form is subject to the terms of the Mozilla\n# Public License v. 2.0. If a copy of the MPL was not distributed\n# with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n#\n# Author: mierle@gmail.com (Keir Mierle)\n#\n# Make the long-awaited conversion to MPL.\n\nlgpl3_header = '''\n// Eigen is free software; you can redistribute it and/or\n// modify it under the terms of the GNU Lesser General Public\n// License as published by the Free Software Foundation; either\n// version 3 of the License, or (at your option) any later version.\n//\n// Alternatively, you can redistribute it and/or\n// modify it under the terms of the GNU General Public License as\n// published by the Free Software Foundation; either version 2 of\n// the License, or (at your option) any later version.\n//\n// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY\n// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS\n// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU Lesser General Public\n// License and a copy of the GNU General Public License along with\n// Eigen. If not, see <http://www.gnu.org/licenses/>.\n'''\n\nmpl2_header = \"\"\"\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\"\"\"\n\nimport os\nimport sys\n\nexclusions = set(['relicense.py'])\n\ndef update(text):\n  if text.find(lgpl3_header) == -1:\n    return text, False\n  return text.replace(lgpl3_header, mpl2_header), True\n\nrootdir = sys.argv[1]\nfor root, sub_folders, files in os.walk(rootdir):\n    for basename in files:\n        if basename in exclusions:\n          print 'SKIPPED', filename\n          continue\n        filename = os.path.join(root, basename)\n        fo = file(filename)\n        text = fo.read()\n        fo.close()\n\n        text, updated = update(text)\n        if updated:\n          fo = file(filename, \"w\")\n          fo.write(text)\n          fo.close()\n          print 'UPDATED', filename\n        else:\n          print '       ', filename\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/signature_of_eigen3_matrix_library",
    "content": "This file is just there as a signature to help identify directories containing Eigen3. When writing a script looking for Eigen3, just look for this file. This is especially useful to help disambiguate with Eigen2...\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/AnnoyingScalar.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011-2018 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_TEST_ANNOYING_SCALAR_H\n#define EIGEN_TEST_ANNOYING_SCALAR_H\n\n#include <ostream>\n\n#if EIGEN_COMP_GNUC\n#pragma GCC diagnostic ignored \"-Wshadow\"\n#endif\n\n#ifndef EIGEN_TEST_ANNOYING_SCALAR_DONT_THROW\nstruct my_exception\n{\n  my_exception() {}\n  ~my_exception() {}\n};\n#endif\n\n// An AnnoyingScalar is a pseudo scalar type that:\n// - can randomly through an exception in operator +\n// - randomly allocate on the heap or initialize a reference to itself making it non trivially copyable, nor movable, nor relocatable.\n\nclass AnnoyingScalar\n{\n  public:\n    AnnoyingScalar()                { init(); *v = 0;  }\n    AnnoyingScalar(long double _v)  { init(); *v = _v; }\n    AnnoyingScalar(double _v)       { init(); *v = _v; }\n    AnnoyingScalar(float _v)        { init(); *v = _v; }\n    AnnoyingScalar(int _v)          { init(); *v = _v; }\n    AnnoyingScalar(long _v)         { init(); *v = _v; }\n    #if EIGEN_HAS_CXX11\n    AnnoyingScalar(long long _v)    { init(); *v = _v; }\n    #endif\n    AnnoyingScalar(const AnnoyingScalar& other) { init(); *v = *(other.v); }\n    ~AnnoyingScalar() {\n      if(v!=&data)\n        delete v;\n      instances--;\n    }\n\n    void init() {\n      if(internal::random<bool>())\n        v = new float;\n      else\n        v = &data;\n      instances++;\n    }\n\n    AnnoyingScalar operator+(const AnnoyingScalar& other) const\n    {\n      #ifndef EIGEN_TEST_ANNOYING_SCALAR_DONT_THROW\n      countdown--;\n      if(countdown<=0 && !dont_throw)\n        throw my_exception();\n      #endif\n      return AnnoyingScalar(*v+*other.v);\n    }\n\n    AnnoyingScalar operator-() const\n    { return AnnoyingScalar(-*v); }\n    \n    AnnoyingScalar operator-(const AnnoyingScalar& other) const\n    { return AnnoyingScalar(*v-*other.v); }\n    \n    AnnoyingScalar operator*(const AnnoyingScalar& other) const\n    { return AnnoyingScalar((*v)*(*other.v)); }\n\n    AnnoyingScalar operator/(const AnnoyingScalar& other) const\n    { return AnnoyingScalar((*v)/(*other.v)); }\n\n    AnnoyingScalar& operator+=(const AnnoyingScalar& other) { *v += *other.v; return *this; }\n    AnnoyingScalar& operator-=(const AnnoyingScalar& other) { *v -= *other.v; return *this; }\n    AnnoyingScalar& operator*=(const AnnoyingScalar& other) { *v *= *other.v; return *this; }\n    AnnoyingScalar& operator/=(const AnnoyingScalar& other) { *v /= *other.v; return *this; }\n    AnnoyingScalar& operator= (const AnnoyingScalar& other) { *v  = *other.v; return *this; }\n\n    bool operator==(const AnnoyingScalar& other) const { return *v == *other.v; }\n    bool operator!=(const AnnoyingScalar& other) const { return *v != *other.v; }\n    bool operator<=(const AnnoyingScalar& other) const { return *v <= *other.v; }\n    bool operator< (const AnnoyingScalar& other) const { return *v <  *other.v; }\n    bool operator>=(const AnnoyingScalar& other) const { return *v >= *other.v; }\n    bool operator> (const AnnoyingScalar& other) const { return *v >  *other.v; }\n  \n    float* v;\n    float data;\n    static int instances;\n#ifndef EIGEN_TEST_ANNOYING_SCALAR_DONT_THROW\n    static int countdown;\n    static bool dont_throw;\n#endif\n};\n\nAnnoyingScalar real(const AnnoyingScalar &x) { return x; }\nAnnoyingScalar imag(const AnnoyingScalar & ) { return 0; }\nAnnoyingScalar conj(const AnnoyingScalar &x) { return x; }\nAnnoyingScalar sqrt(const AnnoyingScalar &x) { return std::sqrt(*x.v); }\nAnnoyingScalar abs (const AnnoyingScalar &x) { return std::abs(*x.v); }\nAnnoyingScalar cos (const AnnoyingScalar &x) { return std::cos(*x.v); }\nAnnoyingScalar sin (const AnnoyingScalar &x) { return std::sin(*x.v); }\nAnnoyingScalar acos(const AnnoyingScalar &x) { return std::acos(*x.v); }\nAnnoyingScalar atan2(const AnnoyingScalar &y,const AnnoyingScalar &x) { return std::atan2(*y.v,*x.v); }\n\nstd::ostream& operator<<(std::ostream& stream,const AnnoyingScalar& x) {\n  stream << (*(x.v));\n  return stream;\n}\n\nint AnnoyingScalar::instances = 0;\n\n#ifndef EIGEN_TEST_ANNOYING_SCALAR_DONT_THROW\nint AnnoyingScalar::countdown = 0;\nbool AnnoyingScalar::dont_throw = false;\n#endif\n\nnamespace Eigen {\ntemplate<>\nstruct NumTraits<AnnoyingScalar> : NumTraits<float>\n{\n  enum {\n    RequireInitialization = 1,\n  };\n  typedef AnnoyingScalar Real;\n  typedef AnnoyingScalar Nested;\n  typedef AnnoyingScalar Literal;\n  typedef AnnoyingScalar NonInteger;\n};\n\ntemplate<> inline AnnoyingScalar test_precision<AnnoyingScalar>() { return test_precision<float>(); }\n\nnamespace numext {\ntemplate<>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nbool (isfinite)(const AnnoyingScalar& x) {\n  return (numext::isfinite)(*x.v);\n}\n}\n\nnamespace internal {\n  template<> EIGEN_STRONG_INLINE double cast(const AnnoyingScalar& x) { return double(*x.v); }\n  template<> EIGEN_STRONG_INLINE float  cast(const AnnoyingScalar& x) { return *x.v; }\n}\n}  // namespace Eigen\n\nAnnoyingScalar get_test_precision(const AnnoyingScalar&)\n{ return Eigen::test_precision<AnnoyingScalar>(); }\n\nAnnoyingScalar test_relative_error(const AnnoyingScalar &a, const AnnoyingScalar &b)\n{ return test_relative_error(*a.v, *b.v); }\n\ninline bool test_isApprox(const AnnoyingScalar &a, const AnnoyingScalar &b)\n{ return internal::isApprox(*a.v, *b.v, test_precision<float>()); }\n\ninline bool test_isMuchSmallerThan(const AnnoyingScalar &a, const AnnoyingScalar &b)\n{ return test_isMuchSmallerThan(*a.v, *b.v); }\n\n#endif // EIGEN_TEST_ANNOYING_SCALAR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/CMakeLists.txt",
    "content": "# The file split_test_helper.h was generated at first run,\n# it is now included in test/\nif(EXISTS ${CMAKE_CURRENT_BINARY_DIR}/split_test_helper.h)\n  file(REMOVE ${CMAKE_CURRENT_BINARY_DIR}/split_test_helper.h)\nendif()\n\n# check if we have a Fortran compiler\ninclude(CheckLanguage)\ncheck_language(Fortran)\nif(CMAKE_Fortran_COMPILER)\n  enable_language(Fortran)\n  set(EIGEN_Fortran_COMPILER_WORKS ON)\nelse()\n  set(EIGEN_Fortran_COMPILER_WORKS OFF)\n  # search for a default Lapack library to complete Eigen's one\n  find_package(LAPACK QUIET)\nendif()\n\n# TODO do the same for EXTERNAL_LAPACK\noption(EIGEN_TEST_EXTERNAL_BLAS \"Use external BLAS library for testsuite\" OFF)\nif(EIGEN_TEST_EXTERNAL_BLAS)\n  find_package(BLAS REQUIRED)\n  message(STATUS \"BLAS_COMPILER_FLAGS: ${BLAS_COMPILER_FLAGS}\")\n  add_definitions(\"-DEIGEN_USE_BLAS\") # is adding  ${BLAS_COMPILER_FLAGS} necessary?\n  list(APPEND EXTERNAL_LIBS \"${BLAS_LIBRARIES}\")\nendif()\n\n# configure blas/lapack (use Eigen's ones)\nset(EIGEN_BLAS_LIBRARIES eigen_blas)\nset(EIGEN_LAPACK_LIBRARIES eigen_lapack)\n\nset(EIGEN_TEST_MATRIX_DIR \"\" CACHE STRING \"Enable testing of realword sparse matrices contained in the specified path\")\nif(EIGEN_TEST_MATRIX_DIR)\n  if(NOT WIN32)\n    message(STATUS \"Test realworld sparse matrices: ${EIGEN_TEST_MATRIX_DIR}\")\n    add_definitions( -DTEST_REAL_CASES=\"${EIGEN_TEST_MATRIX_DIR}\" )\n  else()\n    message(STATUS \"REAL CASES CAN NOT BE CURRENTLY TESTED ON WIN32\")\n  endif()\nendif()\n\nset(SPARSE_LIBS \" \")\n\nfind_package(CHOLMOD)\nif(CHOLMOD_FOUND)\n  add_definitions(\"-DEIGEN_CHOLMOD_SUPPORT\")\n  include_directories(${CHOLMOD_INCLUDES})\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${CHOLMOD_LIBRARIES} ${EIGEN_BLAS_LIBRARIES} ${EIGEN_LAPACK_LIBRARIES})\n  set(CHOLMOD_ALL_LIBS  ${CHOLMOD_LIBRARIES} ${EIGEN_BLAS_LIBRARIES} ${EIGEN_LAPACK_LIBRARIES})\n  ei_add_property(EIGEN_TESTED_BACKENDS \"CHOLMOD, \")\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS \"CHOLMOD, \")\nendif()\n\nfind_package(UMFPACK)\nif(UMFPACK_FOUND)\n  add_definitions(\"-DEIGEN_UMFPACK_SUPPORT\")\n  include_directories(${UMFPACK_INCLUDES})\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${UMFPACK_LIBRARIES} ${EIGEN_BLAS_LIBRARIES})\n  set(UMFPACK_ALL_LIBS ${UMFPACK_LIBRARIES} ${EIGEN_BLAS_LIBRARIES})\n  ei_add_property(EIGEN_TESTED_BACKENDS \"UMFPACK, \")\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS \"UMFPACK, \")\nendif()\n\nfind_package(KLU)\nif(KLU_FOUND)\n  add_definitions(\"-DEIGEN_KLU_SUPPORT\")\n  include_directories(${KLU_INCLUDES})\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${KLU_LIBRARIES} ${EIGEN_BLAS_LIBRARIES})\n  set(KLU_ALL_LIBS ${KLU_LIBRARIES} ${EIGEN_BLAS_LIBRARIES})\n  ei_add_property(EIGEN_TESTED_BACKENDS \"KLU, \")\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS \"KLU, \")\nendif()\n\nfind_package(SuperLU 4.0)\nif(SuperLU_FOUND)\n  add_definitions(\"-DEIGEN_SUPERLU_SUPPORT\")\n  include_directories(${SUPERLU_INCLUDES})\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${SUPERLU_LIBRARIES} ${EIGEN_BLAS_LIBRARIES})\n  set(SUPERLU_ALL_LIBS ${SUPERLU_LIBRARIES} ${EIGEN_BLAS_LIBRARIES})\n  ei_add_property(EIGEN_TESTED_BACKENDS  \"SuperLU, \")\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS  \"SuperLU, \")\nendif()\n\n\nfind_package(PASTIX QUIET COMPONENTS METIS SEQ)\n# check that the PASTIX found is a version without MPI\nfind_path(PASTIX_pastix_nompi.h_INCLUDE_DIRS\n  NAMES pastix_nompi.h\n  HINTS ${PASTIX_INCLUDE_DIRS}\n)\nif (NOT PASTIX_pastix_nompi.h_INCLUDE_DIRS)\n  message(STATUS \"A version of Pastix has been found but pastix_nompi.h does not exist in the include directory.\"\n                 \" Because Eigen tests require a version without MPI, we disable the Pastix backend.\")\nendif()\nif(PASTIX_FOUND AND PASTIX_pastix_nompi.h_INCLUDE_DIRS)\n  add_definitions(\"-DEIGEN_PASTIX_SUPPORT\")\n  include_directories(${PASTIX_INCLUDE_DIRS_DEP})\n  if(SCOTCH_FOUND)\n    include_directories(${SCOTCH_INCLUDE_DIRS})\n    set(PASTIX_LIBRARIES ${PASTIX_LIBRARIES} ${SCOTCH_LIBRARIES})\n  elseif(METIS_FOUND)\n    include_directories(${METIS_INCLUDE_DIRS})\n    set(PASTIX_LIBRARIES ${PASTIX_LIBRARIES} ${METIS_LIBRARIES})\n  else()\n    ei_add_property(EIGEN_MISSING_BACKENDS  \"PaStiX, \")\n  endif()\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${PASTIX_LIBRARIES_DEP} ${ORDERING_LIBRARIES})\n  set(PASTIX_ALL_LIBS ${PASTIX_LIBRARIES_DEP})\n  ei_add_property(EIGEN_TESTED_BACKENDS  \"PaStiX, \")\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS  \"PaStiX, \")\nendif()\n\nif(METIS_FOUND)\n  add_definitions(\"-DEIGEN_METIS_SUPPORT\")\n  include_directories(${METIS_INCLUDE_DIRS})\n  ei_add_property(EIGEN_TESTED_BACKENDS \"METIS, \")\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS \"METIS, \")\nendif()\n\nfind_package(SPQR)\nif(SPQR_FOUND AND CHOLMOD_FOUND AND (EIGEN_Fortran_COMPILER_WORKS OR LAPACK_FOUND) )\n  add_definitions(\"-DEIGEN_SPQR_SUPPORT\")\n  include_directories(${SPQR_INCLUDES})\n  set(SPQR_ALL_LIBS ${SPQR_LIBRARIES} ${CHOLMOD_LIBRARIES} ${EIGEN_LAPACK_LIBRARIES} ${EIGEN_BLAS_LIBRARIES} ${LAPACK_LIBRARIES})\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${SPQR_ALL_LIBS})\n  ei_add_property(EIGEN_TESTED_BACKENDS \"SPQR, \")\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS \"SPQR, \")\nendif()\n\noption(EIGEN_TEST_NOQT \"Disable Qt support in unit tests\" OFF)\nif(NOT EIGEN_TEST_NOQT)\n  find_package(Qt4)\n  if(QT4_FOUND)\n    include(${QT_USE_FILE})\n    ei_add_property(EIGEN_TESTED_BACKENDS  \"Qt4 support, \")\n  else()\n    ei_add_property(EIGEN_MISSING_BACKENDS  \"Qt4 support, \")\n  endif()\nendif()\n\nif(TEST_LIB)\n  add_definitions(\"-DEIGEN_EXTERN_INSTANTIATIONS=1\")\nendif()\n\nset_property(GLOBAL PROPERTY EIGEN_CURRENT_SUBPROJECT \"Official\")\nadd_custom_target(BuildOfficial)\n\nei_add_test(rand)\nei_add_test(meta)\nei_add_test(numext)\nei_add_test(sizeof)\nei_add_test(dynalloc)\nei_add_test(nomalloc)\nei_add_test(first_aligned)\nei_add_test(type_alias)\nei_add_test(nullary)\nei_add_test(mixingtypes)\nei_add_test(io)\nei_add_test(packetmath \"-DEIGEN_FAST_MATH=1\")\nei_add_test(vectorization_logic)\nei_add_test(basicstuff)\nei_add_test(constructor)\nei_add_test(linearstructure)\nei_add_test(integer_types)\nei_add_test(unalignedcount)\nif(NOT EIGEN_TEST_NO_EXCEPTIONS AND NOT EIGEN_TEST_OPENMP)\n  ei_add_test(exceptions)\nendif()\nei_add_test(redux)\nei_add_test(visitor)\nei_add_test(block)\nei_add_test(corners)\nei_add_test(symbolic_index)\nei_add_test(indexed_view)\nei_add_test(reshape)\nei_add_test(swap)\nei_add_test(resize)\nei_add_test(conservative_resize)\nei_add_test(product_small)\nei_add_test(product_large)\nei_add_test(product_extra)\nei_add_test(diagonalmatrices)\nei_add_test(adjoint)\nei_add_test(diagonal)\nei_add_test(miscmatrices)\nei_add_test(commainitializer)\nei_add_test(smallvectors)\nei_add_test(mapped_matrix)\nei_add_test(mapstride)\nei_add_test(mapstaticmethods)\nei_add_test(array_cwise)\nei_add_test(array_for_matrix)\nei_add_test(array_replicate)\nei_add_test(array_reverse)\nei_add_test(ref)\nei_add_test(is_same_dense)\nei_add_test(triangular)\nei_add_test(selfadjoint)\nei_add_test(product_selfadjoint)\nei_add_test(product_symm)\nei_add_test(product_syrk)\nei_add_test(product_trmv)\nei_add_test(product_trmm)\nei_add_test(product_trsolve)\nei_add_test(product_mmtr)\nei_add_test(product_notemporary)\nei_add_test(stable_norm)\nei_add_test(permutationmatrices)\nei_add_test(bandmatrix)\nei_add_test(cholesky)\nei_add_test(lu)\nei_add_test(determinant)\nei_add_test(inverse)\nei_add_test(qr)\nei_add_test(qr_colpivoting)\nei_add_test(qr_fullpivoting)\nei_add_test(upperbidiagonalization)\nei_add_test(hessenberg)\nei_add_test(schur_real)\nei_add_test(schur_complex)\nei_add_test(eigensolver_selfadjoint)\nei_add_test(eigensolver_generic)\nei_add_test(eigensolver_complex)\nei_add_test(real_qz)\nei_add_test(eigensolver_generalized_real)\nei_add_test(jacobi)\nei_add_test(jacobisvd)\nei_add_test(bdcsvd)\nei_add_test(householder)\nei_add_test(geo_orthomethods)\nei_add_test(geo_quaternion)\nei_add_test(geo_eulerangles)\nei_add_test(geo_parametrizedline)\nei_add_test(geo_alignedbox)\nei_add_test(geo_hyperplane)\nei_add_test(geo_transformations)\nei_add_test(geo_homogeneous)\nei_add_test(stdvector)\nei_add_test(stdvector_overload)\nei_add_test(stdlist)\nei_add_test(stdlist_overload)\nei_add_test(stddeque)\nei_add_test(stddeque_overload)\nei_add_test(sparse_basic)\nei_add_test(sparse_block)\nei_add_test(sparse_vector)\nei_add_test(sparse_product)\nei_add_test(sparse_ref)\nei_add_test(sparse_solvers)\nei_add_test(sparse_permutations)\nei_add_test(simplicial_cholesky)\nei_add_test(conjugate_gradient)\nei_add_test(incomplete_cholesky)\nei_add_test(bicgstab)\nei_add_test(lscg)\nei_add_test(sparselu)\nei_add_test(sparseqr)\nei_add_test(umeyama)\nei_add_test(nesting_ops \"${CMAKE_CXX_FLAGS_DEBUG}\")\nei_add_test(nestbyvalue)\nei_add_test(zerosized)\nei_add_test(dontalign)\nei_add_test(evaluators)\nif(NOT EIGEN_TEST_NO_EXCEPTIONS)\n  ei_add_test(sizeoverflow)\nendif()\nei_add_test(prec_inverse_4x4)\nei_add_test(vectorwiseop)\nei_add_test(special_numbers)\nei_add_test(rvalue_types)\nei_add_test(dense_storage)\nei_add_test(ctorleak)\nei_add_test(mpl2only)\nei_add_test(inplace_decomposition)\nei_add_test(half_float)\nei_add_test(bfloat16_float)\nei_add_test(array_of_string)\nei_add_test(num_dimensions)\nei_add_test(stl_iterators)\nei_add_test(blasutil)\nei_add_test(random_matrix)\nei_add_test(initializer_list_construction)\nei_add_test(diagonal_matrix_variadic_ctor)\n\nadd_executable(bug1213 bug1213.cpp bug1213_main.cpp)\n\ncheck_cxx_compiler_flag(\"-ffast-math\" COMPILER_SUPPORT_FASTMATH)\nif(COMPILER_SUPPORT_FASTMATH)\n  set(EIGEN_FASTMATH_FLAGS \"-ffast-math\")\nelse()\n  check_cxx_compiler_flag(\"/fp:fast\" COMPILER_SUPPORT_FPFAST)\n  if(COMPILER_SUPPORT_FPFAST)\n    set(EIGEN_FASTMATH_FLAGS \"/fp:fast\")\n  endif()\nendif()\n\nei_add_test(fastmath \" ${EIGEN_FASTMATH_FLAGS} \")\n\n# # ei_add_test(denseLM)\n\nif(QT4_FOUND)\n  ei_add_test(qtvector \"\" \"${QT_QTCORE_LIBRARY}\")\nendif()\n\nif(UMFPACK_FOUND)\n  ei_add_test(umfpack_support \"\" \"${UMFPACK_ALL_LIBS}\")\nendif()\n\nif(KLU_FOUND OR SuiteSparse_FOUND)\n  ei_add_test(klu_support \"\" \"${KLU_ALL_LIBS}\")\nendif()\n\nif(SUPERLU_FOUND)\n  ei_add_test(superlu_support \"\" \"${SUPERLU_ALL_LIBS}\")\nendif()\n\nif(CHOLMOD_FOUND)\n  ei_add_test(cholmod_support \"\" \"${CHOLMOD_ALL_LIBS}\")\nendif()\n\nif(PARDISO_FOUND)\n  ei_add_test(pardiso_support \"\" \"${PARDISO_ALL_LIBS}\")\nendif()\n\nif(PASTIX_FOUND AND (SCOTCH_FOUND OR METIS_FOUND))\n  ei_add_test(pastix_support \"\" \"${PASTIX_ALL_LIBS}\")\nendif()\n\nif(SPQR_FOUND AND CHOLMOD_FOUND)\n  ei_add_test(spqr_support \"\" \"${SPQR_ALL_LIBS}\")\nendif()\n\nif(METIS_FOUND)\nei_add_test(metis_support \"\" \"${METIS_LIBRARIES}\")\nendif()\n\nstring(TOLOWER \"${CMAKE_CXX_COMPILER}\" cmake_cxx_compiler_tolower)\nif(cmake_cxx_compiler_tolower MATCHES \"qcc\")\n  set(CXX_IS_QCC \"ON\")\nendif()\n\nei_add_property(EIGEN_TESTING_SUMMARY \"CXX:               ${CMAKE_CXX_COMPILER}\\n\")\nif(CMAKE_COMPILER_IS_GNUCXX AND NOT CXX_IS_QCC)\n  execute_process(COMMAND ${CMAKE_CXX_COMPILER} --version COMMAND head -n 1 OUTPUT_VARIABLE EIGEN_CXX_VERSION_STRING OUTPUT_STRIP_TRAILING_WHITESPACE)\n  ei_add_property(EIGEN_TESTING_SUMMARY \"CXX_VERSION:       ${EIGEN_CXX_VERSION_STRING}\\n\")\nendif()\nei_add_property(EIGEN_TESTING_SUMMARY \"CXX_FLAGS:         ${CMAKE_CXX_FLAGS}\\n\")\nif (EIGEN_TEST_CUSTOM_CXX_FLAGS)\n  ei_add_property(EIGEN_TESTING_SUMMARY \"Custom CXX flags:  ${EIGEN_TEST_CUSTOM_CXX_FLAGS}\\n\")\nendif()\nei_add_property(EIGEN_TESTING_SUMMARY \"Sparse lib flags:  ${SPARSE_LIBS}\\n\")\n\noption(EIGEN_TEST_EIGEN2 \"Run whole Eigen2 test suite against EIGEN2_SUPPORT\" OFF)\nmark_as_advanced(EIGEN_TEST_EIGEN2)\nif(EIGEN_TEST_EIGEN2)\n  message(WARNING \"The Eigen2 test suite has been removed\")\nendif()\n\n# boost MP unit test\nfind_package(Boost 1.53.0)\nif(Boost_FOUND)\n  include_directories(${Boost_INCLUDE_DIRS})\n  ei_add_test(boostmultiprec \"\" \"${Boost_LIBRARIES}\")\n  ei_add_property(EIGEN_TESTED_BACKENDS \"Boost.Multiprecision, \")\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS \"Boost.Multiprecision, \")\nendif()\n\n\n# CUDA unit tests\noption(EIGEN_TEST_CUDA \"Enable CUDA support in unit tests\" OFF)\noption(EIGEN_TEST_CUDA_CLANG \"Use clang instead of nvcc to compile the CUDA tests\" OFF)\n\nif(EIGEN_TEST_CUDA_CLANG AND NOT CMAKE_CXX_COMPILER MATCHES \"clang\")\n  message(WARNING \"EIGEN_TEST_CUDA_CLANG is set, but CMAKE_CXX_COMPILER does not appear to be clang.\")\nendif()\n\nif(EIGEN_TEST_CUDA)\n\nfind_package(CUDA 5.0)\nif(CUDA_FOUND)\n  \n  set(CUDA_PROPAGATE_HOST_FLAGS OFF)\n  \n  set(EIGEN_CUDA_RELAXED_CONSTEXPR \"--expt-relaxed-constexpr\")\n  if (${CUDA_VERSION} STREQUAL \"7.0\")\n    set(EIGEN_CUDA_RELAXED_CONSTEXPR \"--relaxed-constexpr\")\n  endif()\n  \n  if(\"${CMAKE_CXX_COMPILER_ID}\" STREQUAL \"Clang\") \n    set(CUDA_NVCC_FLAGS \"-ccbin ${CMAKE_C_COMPILER}\" CACHE STRING \"nvcc flags\" FORCE)\n  endif()\n  if(EIGEN_TEST_CUDA_CLANG)\n    string(APPEND CMAKE_CXX_FLAGS \" --cuda-path=${CUDA_TOOLKIT_ROOT_DIR}\")\n    foreach(GPU IN LISTS EIGEN_CUDA_COMPUTE_ARCH)\n      string(APPEND CMAKE_CXX_FLAGS \" --cuda-gpu-arch=sm_${GPU}\")\n    endforeach()\n  else()\n    foreach(GPU IN LISTS EIGEN_CUDA_COMPUTE_ARCH)\n      string(APPEND CUDA_NVCC_FLAGS \" -gencode arch=compute_${GPU},code=sm_${GPU}\")\n    endforeach()\n  endif()\n  string(APPEND CUDA_NVCC_FLAGS \" ${EIGEN_CUDA_RELAXED_CONSTEXPR}\")\n  set(EIGEN_ADD_TEST_FILENAME_EXTENSION  \"cu\")\n  \n  ei_add_test(gpu_basic)\n  \n  unset(EIGEN_ADD_TEST_FILENAME_EXTENSION)\n\nendif()\n\nendif()\n\n\n# HIP unit tests\noption(EIGEN_TEST_HIP \"Add HIP support.\" OFF)\nif (EIGEN_TEST_HIP)\n\n  set(HIP_PATH \"/opt/rocm/hip\" CACHE STRING \"Path to the HIP installation.\")\n\n  if (EXISTS ${HIP_PATH})\n    \n    list(APPEND CMAKE_MODULE_PATH ${HIP_PATH}/cmake) \n\n    find_package(HIP REQUIRED)\n    if (HIP_FOUND)\n\n      execute_process(COMMAND ${HIP_PATH}/bin/hipconfig --platform OUTPUT_VARIABLE HIP_PLATFORM)\n\n      if ((${HIP_PLATFORM} STREQUAL \"hcc\") OR (${HIP_PLATFORM} STREQUAL \"amd\"))\n\n\tinclude_directories(${HIP_PATH}/include)\n\n\tset(EIGEN_ADD_TEST_FILENAME_EXTENSION  \"cu\")\n\tei_add_test(gpu_basic)\n\tunset(EIGEN_ADD_TEST_FILENAME_EXTENSION)\n\t\n      elseif ((${HIP_PLATFORM} STREQUAL \"nvcc\") OR (${HIP_PLATFORM} STREQUAL \"nvidia\"))\n\tmessage(FATAL_ERROR \"HIP_PLATFORM = nvcc is not supported within Eigen\")\n      else ()\n\tmessage(FATAL_ERROR \"Unknown HIP_PLATFORM = ${HIP_PLATFORM}\")\n      endif() \n    endif()\n  else ()\n    message(FATAL_ERROR \"EIGEN_TEST_HIP is ON, but the specified HIP_PATH (${HIP_PATH}) does not exist\")\n  endif()\nendif()\n\ncmake_dependent_option(EIGEN_TEST_BUILD_DOCUMENTATION \"Test building the doxygen documentation\" OFF \"EIGEN_BUILD_DOC\" OFF)\nif(EIGEN_TEST_BUILD_DOCUMENTATION)\n  add_dependencies(buildtests doc)\nendif()\n\n# Register all smoke tests\ninclude(\"EigenSmokeTestList\")\nei_add_smoke_tests(\"${ei_smoke_test_list}\")\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/MovableScalar.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2020 Sebastien Boisvert <seb@boisvert.info>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MISC_MOVABLE_SCALAR_H\n#define EIGEN_MISC_MOVABLE_SCALAR_H\n\n#include <vector>\n\nnamespace Eigen\n{\ntemplate <typename Scalar, typename Base = std::vector<Scalar>>\nstruct MovableScalar : public Base\n{\n  MovableScalar() = default;\n  ~MovableScalar() = default;\n  MovableScalar(const MovableScalar&) = default;\n  MovableScalar(MovableScalar&& other) = default;\n  MovableScalar& operator=(const MovableScalar&) = default;\n  MovableScalar& operator=(MovableScalar&& other) = default;\n  MovableScalar(Scalar scalar) : Base(100, scalar) {}\n\n  operator Scalar() const { return this->size() > 0 ? this->back() : Scalar(); }\n};\n\ntemplate<> struct NumTraits<MovableScalar<float>> : GenericNumTraits<float> {};\n}\n\n#endif\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/OffByOneScalar.h",
    "content": "\n// A Scalar with internal representation T+1 so that zero is internally\n// represented by T(1). This is used to test memory fill.\n// \ntemplate<typename T>\nclass OffByOneScalar {\n public:\n  OffByOneScalar() : val_(1) {}\n  OffByOneScalar(const OffByOneScalar& other) {\n    *this = other;\n  }\n  OffByOneScalar& operator=(const OffByOneScalar& other) {\n    val_ = other.val_;\n    return *this;\n  }\n  \n  OffByOneScalar(T val) : val_(val + 1) {}\n  OffByOneScalar& operator=(T val) {\n    val_ = val + 1;\n  }\n  \n  operator T() const {\n    return val_ - 1;\n  }\n \n private:\n  T val_;\n};\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/SafeScalar.h",
    "content": "\n// A Scalar that asserts for uninitialized access.\ntemplate<typename T>\nclass SafeScalar {\n public:\n  SafeScalar() : initialized_(false) {}\n  SafeScalar(const SafeScalar& other) {\n    *this = other;\n  }\n  SafeScalar& operator=(const SafeScalar& other) {\n    val_ = T(other);\n    initialized_ = true;\n    return *this;\n  }\n  \n  SafeScalar(T val) : val_(val), initialized_(true) {}\n  SafeScalar& operator=(T val) {\n    val_ = val;\n    initialized_ = true;\n  }\n  \n  operator T() const {\n    VERIFY(initialized_ && \"Uninitialized access.\");\n    return val_;\n  }\n \n private:\n  T val_;\n  bool initialized_;\n};\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/adjoint.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_STATIC_ASSERT\n\n#include \"main.h\"\n\ntemplate<bool IsInteger> struct adjoint_specific;\n\ntemplate<> struct adjoint_specific<true> {\n  template<typename Vec, typename Mat, typename Scalar>\n  static void run(const Vec& v1, const Vec& v2, Vec& v3, const Mat& square, Scalar s1, Scalar s2) {\n    VERIFY(test_isApproxWithRef((s1 * v1 + s2 * v2).dot(v3),     numext::conj(s1) * v1.dot(v3) + numext::conj(s2) * v2.dot(v3), 0));\n    VERIFY(test_isApproxWithRef(v3.dot(s1 * v1 + s2 * v2),       s1*v3.dot(v1)+s2*v3.dot(v2), 0));\n    \n    // check compatibility of dot and adjoint\n    VERIFY(test_isApproxWithRef(v1.dot(square * v2), (square.adjoint() * v1).dot(v2), 0));\n  }\n};\n\ntemplate<> struct adjoint_specific<false> {\n  template<typename Vec, typename Mat, typename Scalar>\n  static void run(const Vec& v1, const Vec& v2, Vec& v3, const Mat& square, Scalar s1, Scalar s2) {\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    using std::abs;\n    \n    RealScalar ref = NumTraits<Scalar>::IsInteger ? RealScalar(0) : (std::max)((s1 * v1 + s2 * v2).norm(),v3.norm());\n    VERIFY(test_isApproxWithRef((s1 * v1 + s2 * v2).dot(v3),     numext::conj(s1) * v1.dot(v3) + numext::conj(s2) * v2.dot(v3), ref));\n    VERIFY(test_isApproxWithRef(v3.dot(s1 * v1 + s2 * v2),       s1*v3.dot(v1)+s2*v3.dot(v2), ref));\n  \n    VERIFY_IS_APPROX(v1.squaredNorm(),                v1.norm() * v1.norm());\n    // check normalized() and normalize()\n    VERIFY_IS_APPROX(v1, v1.norm() * v1.normalized());\n    v3 = v1;\n    v3.normalize();\n    VERIFY_IS_APPROX(v1, v1.norm() * v3);\n    VERIFY_IS_APPROX(v3, v1.normalized());\n    VERIFY_IS_APPROX(v3.norm(), RealScalar(1));\n\n    // check null inputs\n    VERIFY_IS_APPROX((v1*0).normalized(), (v1*0));\n#if (!EIGEN_ARCH_i386) || defined(EIGEN_VECTORIZE)\n    RealScalar very_small = (std::numeric_limits<RealScalar>::min)();\n    VERIFY( (v1*very_small).norm() == 0 );\n    VERIFY_IS_APPROX((v1*very_small).normalized(), (v1*very_small));\n    v3 = v1*very_small;\n    v3.normalize();\n    VERIFY_IS_APPROX(v3, (v1*very_small));\n#endif\n    \n    // check compatibility of dot and adjoint\n    ref = NumTraits<Scalar>::IsInteger ? 0 : (std::max)((std::max)(v1.norm(),v2.norm()),(std::max)((square * v2).norm(),(square.adjoint() * v1).norm()));\n    VERIFY(internal::isMuchSmallerThan(abs(v1.dot(square * v2) - (square.adjoint() * v1).dot(v2)), ref, test_precision<Scalar>()));\n    \n    // check that Random().normalized() works: tricky as the random xpr must be evaluated by\n    // normalized() in order to produce a consistent result.\n    VERIFY_IS_APPROX(Vec::Random(v1.size()).normalized().norm(), RealScalar(1));\n  }\n};\n\ntemplate<typename MatrixType> void adjoint(const MatrixType& m)\n{\n  /* this test covers the following files:\n     Transpose.h Conjugate.h Dot.h\n  */\n  using std::abs;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> SquareMatrixType;\n  const Index PacketSize = internal::packet_traits<Scalar>::size;\n  \n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols),\n             square = SquareMatrixType::Random(rows, rows);\n  VectorType v1 = VectorType::Random(rows),\n             v2 = VectorType::Random(rows),\n             v3 = VectorType::Random(rows),\n             vzero = VectorType::Zero(rows);\n\n  Scalar s1 = internal::random<Scalar>(),\n         s2 = internal::random<Scalar>();\n\n  // check basic compatibility of adjoint, transpose, conjugate\n  VERIFY_IS_APPROX(m1.transpose().conjugate().adjoint(),    m1);\n  VERIFY_IS_APPROX(m1.adjoint().conjugate().transpose(),    m1);\n\n  // check multiplicative behavior\n  VERIFY_IS_APPROX((m1.adjoint() * m2).adjoint(),           m2.adjoint() * m1);\n  VERIFY_IS_APPROX((s1 * m1).adjoint(),                     numext::conj(s1) * m1.adjoint());\n\n  // check basic properties of dot, squaredNorm\n  VERIFY_IS_APPROX(numext::conj(v1.dot(v2)),               v2.dot(v1));\n  VERIFY_IS_APPROX(numext::real(v1.dot(v1)),               v1.squaredNorm());\n  \n  adjoint_specific<NumTraits<Scalar>::IsInteger>::run(v1, v2, v3, square, s1, s2);\n  \n  VERIFY_IS_MUCH_SMALLER_THAN(abs(vzero.dot(v1)),  static_cast<RealScalar>(1));\n  \n  // like in testBasicStuff, test operator() to check const-qualification\n  Index r = internal::random<Index>(0, rows-1),\n      c = internal::random<Index>(0, cols-1);\n  VERIFY_IS_APPROX(m1.conjugate()(r,c), numext::conj(m1(r,c)));\n  VERIFY_IS_APPROX(m1.adjoint()(c,r), numext::conj(m1(r,c)));\n\n  // check inplace transpose\n  m3 = m1;\n  m3.transposeInPlace();\n  VERIFY_IS_APPROX(m3,m1.transpose());\n  m3.transposeInPlace();\n  VERIFY_IS_APPROX(m3,m1);\n  \n  if(PacketSize<m3.rows() && PacketSize<m3.cols())\n  {\n    m3 = m1;\n    Index i = internal::random<Index>(0,m3.rows()-PacketSize);\n    Index j = internal::random<Index>(0,m3.cols()-PacketSize);\n    m3.template block<PacketSize,PacketSize>(i,j).transposeInPlace();\n    VERIFY_IS_APPROX( (m3.template block<PacketSize,PacketSize>(i,j)), (m1.template block<PacketSize,PacketSize>(i,j).transpose()) );\n    m3.template block<PacketSize,PacketSize>(i,j).transposeInPlace();\n    VERIFY_IS_APPROX(m3,m1);\n  }\n\n  // check inplace adjoint\n  m3 = m1;\n  m3.adjointInPlace();\n  VERIFY_IS_APPROX(m3,m1.adjoint());\n  m3.transposeInPlace();\n  VERIFY_IS_APPROX(m3,m1.conjugate());\n\n  // check mixed dot product\n  typedef Matrix<RealScalar, MatrixType::RowsAtCompileTime, 1> RealVectorType;\n  RealVectorType rv1 = RealVectorType::Random(rows);\n  VERIFY_IS_APPROX(v1.dot(rv1.template cast<Scalar>()), v1.dot(rv1));\n  VERIFY_IS_APPROX(rv1.template cast<Scalar>().dot(v1), rv1.dot(v1));\n\n  VERIFY( is_same_type(m1,m1.template conjugateIf<false>()) );\n  VERIFY( is_same_type(m1.conjugate(),m1.template conjugateIf<true>()) );\n}\n\ntemplate<int>\nvoid adjoint_extra()\n{\n  MatrixXcf a(10,10), b(10,10);\n  VERIFY_RAISES_ASSERT(a = a.transpose());\n  VERIFY_RAISES_ASSERT(a = a.transpose() + b);\n  VERIFY_RAISES_ASSERT(a = b + a.transpose());\n  VERIFY_RAISES_ASSERT(a = a.conjugate().transpose());\n  VERIFY_RAISES_ASSERT(a = a.adjoint());\n  VERIFY_RAISES_ASSERT(a = a.adjoint() + b);\n  VERIFY_RAISES_ASSERT(a = b + a.adjoint());\n\n  // no assertion should be triggered for these cases:\n  a.transpose() = a.transpose();\n  a.transpose() += a.transpose();\n  a.transpose() += a.transpose() + b;\n  a.transpose() = a.adjoint();\n  a.transpose() += a.adjoint();\n  a.transpose() += a.adjoint() + b;\n\n  // regression tests for check_for_aliasing\n  MatrixXd c(10,10);\n  c = 1.0 * MatrixXd::Ones(10,10) + c;\n  c = MatrixXd::Ones(10,10) * 1.0 + c;\n  c = c + MatrixXd::Ones(10,10) .cwiseProduct( MatrixXd::Zero(10,10) );\n  c = MatrixXd::Ones(10,10) * MatrixXd::Zero(10,10);\n\n  // regression for bug 1646\n  for (int j = 0; j < 10; ++j) {\n    c.col(j).head(j) = c.row(j).head(j);\n  }\n\n  for (int j = 0; j < 10; ++j) {\n    c.col(j) = c.row(j);\n  }\n\n  a.conservativeResize(1,1);\n  a = a.transpose();\n\n  a.conservativeResize(0,0);\n  a = a.transpose();\n}\n\nEIGEN_DECLARE_TEST(adjoint)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( adjoint(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( adjoint(Matrix3d()) );\n    CALL_SUBTEST_3( adjoint(Matrix4f()) );\n    \n    CALL_SUBTEST_4( adjoint(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2), internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))) );\n    CALL_SUBTEST_5( adjoint(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( adjoint(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    \n    // Complement for 128 bits vectorization:\n    CALL_SUBTEST_8( adjoint(Matrix2d()) );\n    CALL_SUBTEST_9( adjoint(Matrix<int,4,4>()) );\n    \n    // 256 bits vectorization:\n    CALL_SUBTEST_10( adjoint(Matrix<float,8,8>()) );\n    CALL_SUBTEST_11( adjoint(Matrix<double,4,4>()) );\n    CALL_SUBTEST_12( adjoint(Matrix<int,8,8>()) );\n  }\n  // test a large static matrix only once\n  CALL_SUBTEST_7( adjoint(Matrix<float, 100, 100>()) );\n\n  CALL_SUBTEST_13( adjoint_extra<0>() );\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/array_cwise.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n\n// Test the corner cases of pow(x, y) for real types.\ntemplate<typename Scalar>\nvoid pow_test() {\n  const Scalar zero = Scalar(0);\n  const Scalar eps = Eigen::NumTraits<Scalar>::epsilon();\n  const Scalar one = Scalar(1);\n  const Scalar two = Scalar(2);\n  const Scalar three = Scalar(3);\n  const Scalar sqrt_half = Scalar(std::sqrt(0.5));\n  const Scalar sqrt2 = Scalar(std::sqrt(2));\n  const Scalar inf = Eigen::NumTraits<Scalar>::infinity();\n  const Scalar nan = Eigen::NumTraits<Scalar>::quiet_NaN();\n  const Scalar denorm_min = std::numeric_limits<Scalar>::denorm_min();\n  const Scalar min = (std::numeric_limits<Scalar>::min)();\n  const Scalar max = (std::numeric_limits<Scalar>::max)();\n  const Scalar max_exp = (static_cast<Scalar>(int(Eigen::NumTraits<Scalar>::max_exponent())) * Scalar(EIGEN_LN2)) / eps;\n\n  const static Scalar abs_vals[] = {zero,\n                                    denorm_min,\n                                    min,\n                                    eps,\n                                    sqrt_half,\n                                    one,\n                                    sqrt2,\n                                    two,\n                                    three,\n                                    max_exp,\n                                    max,\n                                    inf,\n                                    nan};\n  const int abs_cases = 13;\n  const int num_cases = 2*abs_cases * 2*abs_cases;\n  // Repeat the same value to make sure we hit the vectorized path.\n  const int num_repeats = 32;\n  Array<Scalar, Dynamic, Dynamic> x(num_repeats, num_cases);\n  Array<Scalar, Dynamic, Dynamic> y(num_repeats, num_cases);\n  int count = 0;\n  for (int i = 0; i < abs_cases; ++i) {\n    const Scalar abs_x = abs_vals[i];\n    for (int sign_x = 0; sign_x < 2; ++sign_x) {\n      Scalar x_case = sign_x == 0 ? -abs_x : abs_x;\n      for (int j = 0; j < abs_cases; ++j) {\n        const Scalar abs_y = abs_vals[j];\n        for (int sign_y = 0; sign_y < 2; ++sign_y) {\n          Scalar y_case = sign_y == 0 ? -abs_y : abs_y;\n          for (int repeat = 0; repeat < num_repeats; ++repeat) {\n            x(repeat, count) = x_case;\n            y(repeat, count) = y_case;\n          }\n          ++count;\n        }\n      }\n    }\n  }\n\n  Array<Scalar, Dynamic, Dynamic> actual = x.pow(y);\n  const Scalar tol = test_precision<Scalar>();\n  bool all_pass = true;\n  for (int i = 0; i < 1; ++i) {\n    for (int j = 0; j < num_cases; ++j) {\n      Scalar e = static_cast<Scalar>(std::pow(x(i,j), y(i,j)));\n      Scalar a = actual(i, j);\n      bool fail = !(a==e) && !internal::isApprox(a, e, tol) && !((numext::isnan)(a) && (numext::isnan)(e));\n      all_pass &= !fail;\n      if (fail) {\n        std::cout << \"pow(\" << x(i,j) << \",\" << y(i,j) << \")   =   \" << a << \" !=  \" << e << std::endl;\n      }\n    }\n  }\n  VERIFY(all_pass);\n}\n\ntemplate<typename ArrayType> void array(const ArrayType& m)\n{\n  typedef typename ArrayType::Scalar Scalar;\n  typedef typename ArrayType::RealScalar RealScalar;\n  typedef Array<Scalar, ArrayType::RowsAtCompileTime, 1> ColVectorType;\n  typedef Array<Scalar, 1, ArrayType::ColsAtCompileTime> RowVectorType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  ArrayType m1 = ArrayType::Random(rows, cols),\n             m2 = ArrayType::Random(rows, cols),\n             m3(rows, cols);\n  ArrayType m4 = m1; // copy constructor\n  VERIFY_IS_APPROX(m1, m4);\n\n  ColVectorType cv1 = ColVectorType::Random(rows);\n  RowVectorType rv1 = RowVectorType::Random(cols);\n\n  Scalar  s1 = internal::random<Scalar>(),\n          s2 = internal::random<Scalar>();\n\n  // scalar addition\n  VERIFY_IS_APPROX(m1 + s1, s1 + m1);\n  VERIFY_IS_APPROX(m1 + s1, ArrayType::Constant(rows,cols,s1) + m1);\n  VERIFY_IS_APPROX(s1 - m1, (-m1)+s1 );\n  VERIFY_IS_APPROX(m1 - s1, m1 - ArrayType::Constant(rows,cols,s1));\n  VERIFY_IS_APPROX(s1 - m1, ArrayType::Constant(rows,cols,s1) - m1);\n  VERIFY_IS_APPROX((m1*Scalar(2)) - s2, (m1+m1) - ArrayType::Constant(rows,cols,s2) );\n  m3 = m1;\n  m3 += s2;\n  VERIFY_IS_APPROX(m3, m1 + s2);\n  m3 = m1;\n  m3 -= s1;\n  VERIFY_IS_APPROX(m3, m1 - s1);\n\n  // scalar operators via Maps\n  m3 = m1;\n  ArrayType::Map(m1.data(), m1.rows(), m1.cols()) -= ArrayType::Map(m2.data(), m2.rows(), m2.cols());\n  VERIFY_IS_APPROX(m1, m3 - m2);\n\n  m3 = m1;\n  ArrayType::Map(m1.data(), m1.rows(), m1.cols()) += ArrayType::Map(m2.data(), m2.rows(), m2.cols());\n  VERIFY_IS_APPROX(m1, m3 + m2);\n\n  m3 = m1;\n  ArrayType::Map(m1.data(), m1.rows(), m1.cols()) *= ArrayType::Map(m2.data(), m2.rows(), m2.cols());\n  VERIFY_IS_APPROX(m1, m3 * m2);\n\n  m3 = m1;\n  m2 = ArrayType::Random(rows,cols);\n  m2 = (m2==0).select(1,m2);\n  ArrayType::Map(m1.data(), m1.rows(), m1.cols()) /= ArrayType::Map(m2.data(), m2.rows(), m2.cols());\n  VERIFY_IS_APPROX(m1, m3 / m2);\n\n  // reductions\n  VERIFY_IS_APPROX(m1.abs().colwise().sum().sum(), m1.abs().sum());\n  VERIFY_IS_APPROX(m1.abs().rowwise().sum().sum(), m1.abs().sum());\n  using std::abs;\n  VERIFY_IS_MUCH_SMALLER_THAN(abs(m1.colwise().sum().sum() - m1.sum()), m1.abs().sum());\n  VERIFY_IS_MUCH_SMALLER_THAN(abs(m1.rowwise().sum().sum() - m1.sum()), m1.abs().sum());\n  if (!internal::isMuchSmallerThan(abs(m1.sum() - (m1+m2).sum()), m1.abs().sum(), test_precision<Scalar>()))\n      VERIFY_IS_NOT_APPROX(((m1+m2).rowwise().sum()).sum(), m1.sum());\n  VERIFY_IS_APPROX(m1.colwise().sum(), m1.colwise().redux(internal::scalar_sum_op<Scalar,Scalar>()));\n\n  // vector-wise ops\n  m3 = m1;\n  VERIFY_IS_APPROX(m3.colwise() += cv1, m1.colwise() + cv1);\n  m3 = m1;\n  VERIFY_IS_APPROX(m3.colwise() -= cv1, m1.colwise() - cv1);\n  m3 = m1;\n  VERIFY_IS_APPROX(m3.rowwise() += rv1, m1.rowwise() + rv1);\n  m3 = m1;\n  VERIFY_IS_APPROX(m3.rowwise() -= rv1, m1.rowwise() - rv1);\n\n  // Conversion from scalar\n  VERIFY_IS_APPROX((m3 = s1), ArrayType::Constant(rows,cols,s1));\n  VERIFY_IS_APPROX((m3 = 1),  ArrayType::Constant(rows,cols,1));\n  VERIFY_IS_APPROX((m3.topLeftCorner(rows,cols) = 1),  ArrayType::Constant(rows,cols,1));\n  typedef Array<Scalar,\n                ArrayType::RowsAtCompileTime==Dynamic?2:ArrayType::RowsAtCompileTime,\n                ArrayType::ColsAtCompileTime==Dynamic?2:ArrayType::ColsAtCompileTime,\n                ArrayType::Options> FixedArrayType;\n  {\n    FixedArrayType f1(s1);\n    VERIFY_IS_APPROX(f1, FixedArrayType::Constant(s1));\n    FixedArrayType f2(numext::real(s1));\n    VERIFY_IS_APPROX(f2, FixedArrayType::Constant(numext::real(s1)));\n    FixedArrayType f3((int)100*numext::real(s1));\n    VERIFY_IS_APPROX(f3, FixedArrayType::Constant((int)100*numext::real(s1)));\n    f1.setRandom();\n    FixedArrayType f4(f1.data());\n    VERIFY_IS_APPROX(f4, f1);\n  }\n  #if EIGEN_HAS_CXX11\n  {\n    FixedArrayType f1{s1};\n    VERIFY_IS_APPROX(f1, FixedArrayType::Constant(s1));\n    FixedArrayType f2{numext::real(s1)};\n    VERIFY_IS_APPROX(f2, FixedArrayType::Constant(numext::real(s1)));\n    FixedArrayType f3{(int)100*numext::real(s1)};\n    VERIFY_IS_APPROX(f3, FixedArrayType::Constant((int)100*numext::real(s1)));\n    f1.setRandom();\n    FixedArrayType f4{f1.data()};\n    VERIFY_IS_APPROX(f4, f1);\n  }\n  #endif\n\n  // pow\n  VERIFY_IS_APPROX(m1.pow(2), m1.square());\n  VERIFY_IS_APPROX(pow(m1,2), m1.square());\n  VERIFY_IS_APPROX(m1.pow(3), m1.cube());\n  VERIFY_IS_APPROX(pow(m1,3), m1.cube());\n  VERIFY_IS_APPROX((-m1).pow(3), -m1.cube());\n  VERIFY_IS_APPROX(pow(2*m1,3), 8*m1.cube());\n  ArrayType exponents = ArrayType::Constant(rows, cols, RealScalar(2));\n  VERIFY_IS_APPROX(Eigen::pow(m1,exponents), m1.square());\n  VERIFY_IS_APPROX(m1.pow(exponents), m1.square());\n  VERIFY_IS_APPROX(Eigen::pow(2*m1,exponents), 4*m1.square());\n  VERIFY_IS_APPROX((2*m1).pow(exponents), 4*m1.square());\n  VERIFY_IS_APPROX(Eigen::pow(m1,2*exponents), m1.square().square());\n  VERIFY_IS_APPROX(m1.pow(2*exponents), m1.square().square());\n  VERIFY_IS_APPROX(Eigen::pow(m1(0,0), exponents), ArrayType::Constant(rows,cols,m1(0,0)*m1(0,0)));\n\n  // Check possible conflicts with 1D ctor\n  typedef Array<Scalar, Dynamic, 1> OneDArrayType;\n  {\n    OneDArrayType o1(rows);\n    VERIFY(o1.size()==rows);\n    OneDArrayType o2(static_cast<int>(rows));\n    VERIFY(o2.size()==rows);\n  }\n  #if EIGEN_HAS_CXX11\n  {\n    OneDArrayType o1{rows};\n    VERIFY(o1.size()==rows);\n    OneDArrayType o4{int(rows)};\n    VERIFY(o4.size()==rows);\n  }\n  #endif\n  // Check possible conflicts with 2D ctor\n  typedef Array<Scalar, Dynamic, Dynamic> TwoDArrayType;\n  typedef Array<Scalar, 2, 1> ArrayType2;\n  {\n    TwoDArrayType o1(rows,cols);\n    VERIFY(o1.rows()==rows);\n    VERIFY(o1.cols()==cols);\n    TwoDArrayType o2(static_cast<int>(rows),static_cast<int>(cols));\n    VERIFY(o2.rows()==rows);\n    VERIFY(o2.cols()==cols);\n\n    ArrayType2 o3(rows,cols);\n    VERIFY(o3(0)==Scalar(rows) && o3(1)==Scalar(cols));\n    ArrayType2 o4(static_cast<int>(rows),static_cast<int>(cols));\n    VERIFY(o4(0)==Scalar(rows) && o4(1)==Scalar(cols));\n  }\n  #if EIGEN_HAS_CXX11\n  {\n    TwoDArrayType o1{rows,cols};\n    VERIFY(o1.rows()==rows);\n    VERIFY(o1.cols()==cols);\n    TwoDArrayType o2{int(rows),int(cols)};\n    VERIFY(o2.rows()==rows);\n    VERIFY(o2.cols()==cols);\n\n    ArrayType2 o3{rows,cols};\n    VERIFY(o3(0)==Scalar(rows) && o3(1)==Scalar(cols));\n    ArrayType2 o4{int(rows),int(cols)};\n    VERIFY(o4(0)==Scalar(rows) && o4(1)==Scalar(cols));\n  }\n  #endif\n}\n\ntemplate<typename ArrayType> void comparisons(const ArrayType& m)\n{\n  using std::abs;\n  typedef typename ArrayType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  Index r = internal::random<Index>(0, rows-1),\n        c = internal::random<Index>(0, cols-1);\n\n  ArrayType m1 = ArrayType::Random(rows, cols),\n            m2 = ArrayType::Random(rows, cols),\n            m3(rows, cols),\n            m4 = m1;\n\n  m4 = (m4.abs()==Scalar(0)).select(1,m4);\n\n  VERIFY(((m1 + Scalar(1)) > m1).all());\n  VERIFY(((m1 - Scalar(1)) < m1).all());\n  if (rows*cols>1)\n  {\n    m3 = m1;\n    m3(r,c) += 1;\n    VERIFY(! (m1 < m3).all() );\n    VERIFY(! (m1 > m3).all() );\n  }\n  VERIFY(!(m1 > m2 && m1 < m2).any());\n  VERIFY((m1 <= m2 || m1 >= m2).all());\n\n  // comparisons array to scalar\n  VERIFY( (m1 != (m1(r,c)+1) ).any() );\n  VERIFY( (m1 >  (m1(r,c)-1) ).any() );\n  VERIFY( (m1 <  (m1(r,c)+1) ).any() );\n  VERIFY( (m1 ==  m1(r,c)    ).any() );\n\n  // comparisons scalar to array\n  VERIFY( ( (m1(r,c)+1) != m1).any() );\n  VERIFY( ( (m1(r,c)-1) <  m1).any() );\n  VERIFY( ( (m1(r,c)+1) >  m1).any() );\n  VERIFY( (  m1(r,c)    == m1).any() );\n\n  // test Select\n  VERIFY_IS_APPROX( (m1<m2).select(m1,m2), m1.cwiseMin(m2) );\n  VERIFY_IS_APPROX( (m1>m2).select(m1,m2), m1.cwiseMax(m2) );\n  Scalar mid = (m1.cwiseAbs().minCoeff() + m1.cwiseAbs().maxCoeff())/Scalar(2);\n  for (int j=0; j<cols; ++j)\n  for (int i=0; i<rows; ++i)\n    m3(i,j) = abs(m1(i,j))<mid ? 0 : m1(i,j);\n  VERIFY_IS_APPROX( (m1.abs()<ArrayType::Constant(rows,cols,mid))\n                        .select(ArrayType::Zero(rows,cols),m1), m3);\n  // shorter versions:\n  VERIFY_IS_APPROX( (m1.abs()<ArrayType::Constant(rows,cols,mid))\n                        .select(0,m1), m3);\n  VERIFY_IS_APPROX( (m1.abs()>=ArrayType::Constant(rows,cols,mid))\n                        .select(m1,0), m3);\n  // even shorter version:\n  VERIFY_IS_APPROX( (m1.abs()<mid).select(0,m1), m3);\n\n  // count\n  VERIFY(((m1.abs()+1)>RealScalar(0.1)).count() == rows*cols);\n\n  // and/or\n  VERIFY( (m1<RealScalar(0) && m1>RealScalar(0)).count() == 0);\n  VERIFY( (m1<RealScalar(0) || m1>=RealScalar(0)).count() == rows*cols);\n  RealScalar a = m1.abs().mean();\n  VERIFY( (m1<-a || m1>a).count() == (m1.abs()>a).count());\n\n  typedef Array<Index, Dynamic, 1> ArrayOfIndices;\n\n  // TODO allows colwise/rowwise for array\n  VERIFY_IS_APPROX(((m1.abs()+1)>RealScalar(0.1)).colwise().count(), ArrayOfIndices::Constant(cols,rows).transpose());\n  VERIFY_IS_APPROX(((m1.abs()+1)>RealScalar(0.1)).rowwise().count(), ArrayOfIndices::Constant(rows, cols));\n}\n\ntemplate<typename ArrayType> void array_real(const ArrayType& m)\n{\n  using std::abs;\n  using std::sqrt;\n  typedef typename ArrayType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  ArrayType m1 = ArrayType::Random(rows, cols),\n            m2 = ArrayType::Random(rows, cols),\n            m3(rows, cols),\n            m4 = m1;\n\n  m4 = (m4.abs()==Scalar(0)).select(Scalar(1),m4);\n\n  Scalar  s1 = internal::random<Scalar>();\n\n  // these tests are mostly to check possible compilation issues with free-functions.\n  VERIFY_IS_APPROX(m1.sin(), sin(m1));\n  VERIFY_IS_APPROX(m1.cos(), cos(m1));\n  VERIFY_IS_APPROX(m1.tan(), tan(m1));\n  VERIFY_IS_APPROX(m1.asin(), asin(m1));\n  VERIFY_IS_APPROX(m1.acos(), acos(m1));\n  VERIFY_IS_APPROX(m1.atan(), atan(m1));\n  VERIFY_IS_APPROX(m1.sinh(), sinh(m1));\n  VERIFY_IS_APPROX(m1.cosh(), cosh(m1));\n  VERIFY_IS_APPROX(m1.tanh(), tanh(m1));\n#if EIGEN_HAS_CXX11_MATH\n  VERIFY_IS_APPROX(m1.tanh().atanh(), atanh(tanh(m1)));\n  VERIFY_IS_APPROX(m1.sinh().asinh(), asinh(sinh(m1)));\n  VERIFY_IS_APPROX(m1.cosh().acosh(), acosh(cosh(m1)));\n#endif\n  VERIFY_IS_APPROX(m1.logistic(), logistic(m1));\n\n  VERIFY_IS_APPROX(m1.arg(), arg(m1));\n  VERIFY_IS_APPROX(m1.round(), round(m1));\n  VERIFY_IS_APPROX(m1.rint(), rint(m1));\n  VERIFY_IS_APPROX(m1.floor(), floor(m1));\n  VERIFY_IS_APPROX(m1.ceil(), ceil(m1));\n  VERIFY((m1.isNaN() == (Eigen::isnan)(m1)).all());\n  VERIFY((m1.isInf() == (Eigen::isinf)(m1)).all());\n  VERIFY((m1.isFinite() == (Eigen::isfinite)(m1)).all());\n  VERIFY_IS_APPROX(m4.inverse(), inverse(m4));\n  VERIFY_IS_APPROX(m1.abs(), abs(m1));\n  VERIFY_IS_APPROX(m1.abs2(), abs2(m1));\n  VERIFY_IS_APPROX(m1.square(), square(m1));\n  VERIFY_IS_APPROX(m1.cube(), cube(m1));\n  VERIFY_IS_APPROX(cos(m1+RealScalar(3)*m2), cos((m1+RealScalar(3)*m2).eval()));\n  VERIFY_IS_APPROX(m1.sign(), sign(m1));\n  VERIFY((m1.sqrt().sign().isNaN() == (Eigen::isnan)(sign(sqrt(m1)))).all());\n\n  // avoid inf and NaNs so verification doesn't fail\n  m3 = m4.abs();\n  VERIFY_IS_APPROX(m3.sqrt(), sqrt(abs(m3)));\n  VERIFY_IS_APPROX(m3.rsqrt(), Scalar(1)/sqrt(abs(m3)));\n  VERIFY_IS_APPROX(rsqrt(m3), Scalar(1)/sqrt(abs(m3)));\n  VERIFY_IS_APPROX(m3.log(), log(m3));\n  VERIFY_IS_APPROX(m3.log1p(), log1p(m3));\n  VERIFY_IS_APPROX(m3.log10(), log10(m3));\n  VERIFY_IS_APPROX(m3.log2(), log2(m3));\n\n\n  VERIFY((!(m1>m2) == (m1<=m2)).all());\n\n  VERIFY_IS_APPROX(sin(m1.asin()), m1);\n  VERIFY_IS_APPROX(cos(m1.acos()), m1);\n  VERIFY_IS_APPROX(tan(m1.atan()), m1);\n  VERIFY_IS_APPROX(sinh(m1), Scalar(0.5)*(exp(m1)-exp(-m1)));\n  VERIFY_IS_APPROX(cosh(m1), Scalar(0.5)*(exp(m1)+exp(-m1)));\n  VERIFY_IS_APPROX(tanh(m1), (Scalar(0.5)*(exp(m1)-exp(-m1)))/(Scalar(0.5)*(exp(m1)+exp(-m1))));\n  VERIFY_IS_APPROX(logistic(m1), (Scalar(1)/(Scalar(1)+exp(-m1))));\n  VERIFY_IS_APPROX(arg(m1), ((m1<Scalar(0)).template cast<Scalar>())*Scalar(std::acos(Scalar(-1))));\n  VERIFY((round(m1) <= ceil(m1) && round(m1) >= floor(m1)).all());\n  VERIFY((rint(m1) <= ceil(m1) && rint(m1) >= floor(m1)).all());\n  VERIFY(((ceil(m1) - round(m1)) <= Scalar(0.5) || (round(m1) - floor(m1)) <= Scalar(0.5)).all());\n  VERIFY(((ceil(m1) - round(m1)) <= Scalar(1.0) && (round(m1) - floor(m1)) <= Scalar(1.0)).all());\n  VERIFY(((ceil(m1) - rint(m1)) <= Scalar(0.5) || (rint(m1) - floor(m1)) <= Scalar(0.5)).all());\n  VERIFY(((ceil(m1) - rint(m1)) <= Scalar(1.0) && (rint(m1) - floor(m1)) <= Scalar(1.0)).all());\n  VERIFY((Eigen::isnan)((m1*Scalar(0))/Scalar(0)).all());\n  VERIFY((Eigen::isinf)(m4/Scalar(0)).all());\n  VERIFY(((Eigen::isfinite)(m1) && (!(Eigen::isfinite)(m1*Scalar(0)/Scalar(0))) && (!(Eigen::isfinite)(m4/Scalar(0)))).all());\n  VERIFY_IS_APPROX(inverse(inverse(m4)),m4);\n  VERIFY((abs(m1) == m1 || abs(m1) == -m1).all());\n  VERIFY_IS_APPROX(m3, sqrt(abs2(m3)));\n  VERIFY_IS_APPROX(m1.absolute_difference(m2), (m1 > m2).select(m1 - m2, m2 - m1));\n  VERIFY_IS_APPROX( m1.sign(), -(-m1).sign() );\n  VERIFY_IS_APPROX( m1*m1.sign(),m1.abs());\n  VERIFY_IS_APPROX(m1.sign() * m1.abs(), m1);\n\n  VERIFY_IS_APPROX(numext::abs2(numext::real(m1)) + numext::abs2(numext::imag(m1)), numext::abs2(m1));\n  VERIFY_IS_APPROX(numext::abs2(Eigen::real(m1)) + numext::abs2(Eigen::imag(m1)), numext::abs2(m1));\n  if(!NumTraits<Scalar>::IsComplex)\n    VERIFY_IS_APPROX(numext::real(m1), m1);\n\n  // shift argument of logarithm so that it is not zero\n  Scalar smallNumber = NumTraits<Scalar>::dummy_precision();\n  VERIFY_IS_APPROX((m3 + smallNumber).log() , log(abs(m3) + smallNumber));\n  VERIFY_IS_APPROX((m3 + smallNumber + Scalar(1)).log() , log1p(abs(m3) + smallNumber));\n\n  VERIFY_IS_APPROX(m1.exp() * m2.exp(), exp(m1+m2));\n  VERIFY_IS_APPROX(m1.exp(), exp(m1));\n  VERIFY_IS_APPROX(m1.exp() / m2.exp(),(m1-m2).exp());\n\n  VERIFY_IS_APPROX(m1.expm1(), expm1(m1));\n  VERIFY_IS_APPROX((m3 + smallNumber).exp() - Scalar(1), expm1(abs(m3) + smallNumber));\n\n  VERIFY_IS_APPROX(m3.pow(RealScalar(0.5)), m3.sqrt());\n  VERIFY_IS_APPROX(pow(m3,RealScalar(0.5)), m3.sqrt());\n\n  VERIFY_IS_APPROX(m3.pow(RealScalar(-0.5)), m3.rsqrt());\n  VERIFY_IS_APPROX(pow(m3,RealScalar(-0.5)), m3.rsqrt());\n\n  // Avoid inf and NaN.\n  m3 = (m1.square()<NumTraits<Scalar>::epsilon()).select(Scalar(1),m3);\n  VERIFY_IS_APPROX(m3.pow(RealScalar(-2)), m3.square().inverse());\n  pow_test<Scalar>();\n\n  VERIFY_IS_APPROX(log10(m3), log(m3)/numext::log(Scalar(10)));\n  VERIFY_IS_APPROX(log2(m3), log(m3)/numext::log(Scalar(2)));\n\n  // scalar by array division\n  const RealScalar tiny = sqrt(std::numeric_limits<RealScalar>::epsilon());\n  s1 += Scalar(tiny);\n  m1 += ArrayType::Constant(rows,cols,Scalar(tiny));\n  VERIFY_IS_APPROX(s1/m1, s1 * m1.inverse());\n\n  // check inplace transpose\n  m3 = m1;\n  m3.transposeInPlace();\n  VERIFY_IS_APPROX(m3, m1.transpose());\n  m3.transposeInPlace();\n  VERIFY_IS_APPROX(m3, m1);\n}\n\ntemplate<typename ArrayType> void array_complex(const ArrayType& m)\n{\n  typedef typename ArrayType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  ArrayType m1 = ArrayType::Random(rows, cols),\n            m2(rows, cols),\n            m4 = m1;\n\n  m4.real() = (m4.real().abs()==RealScalar(0)).select(RealScalar(1),m4.real());\n  m4.imag() = (m4.imag().abs()==RealScalar(0)).select(RealScalar(1),m4.imag());\n\n  Array<RealScalar, -1, -1> m3(rows, cols);\n\n  for (Index i = 0; i < m.rows(); ++i)\n    for (Index j = 0; j < m.cols(); ++j)\n      m2(i,j) = sqrt(m1(i,j));\n\n  // these tests are mostly to check possible compilation issues with free-functions.\n  VERIFY_IS_APPROX(m1.sin(), sin(m1));\n  VERIFY_IS_APPROX(m1.cos(), cos(m1));\n  VERIFY_IS_APPROX(m1.tan(), tan(m1));\n  VERIFY_IS_APPROX(m1.sinh(), sinh(m1));\n  VERIFY_IS_APPROX(m1.cosh(), cosh(m1));\n  VERIFY_IS_APPROX(m1.tanh(), tanh(m1));\n  VERIFY_IS_APPROX(m1.logistic(), logistic(m1));\n  VERIFY_IS_APPROX(m1.arg(), arg(m1));\n  VERIFY((m1.isNaN() == (Eigen::isnan)(m1)).all());\n  VERIFY((m1.isInf() == (Eigen::isinf)(m1)).all());\n  VERIFY((m1.isFinite() == (Eigen::isfinite)(m1)).all());\n  VERIFY_IS_APPROX(m4.inverse(), inverse(m4));\n  VERIFY_IS_APPROX(m1.log(), log(m1));\n  VERIFY_IS_APPROX(m1.log10(), log10(m1));\n  VERIFY_IS_APPROX(m1.log2(), log2(m1));\n  VERIFY_IS_APPROX(m1.abs(), abs(m1));\n  VERIFY_IS_APPROX(m1.abs2(), abs2(m1));\n  VERIFY_IS_APPROX(m1.sqrt(), sqrt(m1));\n  VERIFY_IS_APPROX(m1.square(), square(m1));\n  VERIFY_IS_APPROX(m1.cube(), cube(m1));\n  VERIFY_IS_APPROX(cos(m1+RealScalar(3)*m2), cos((m1+RealScalar(3)*m2).eval()));\n  VERIFY_IS_APPROX(m1.sign(), sign(m1));\n\n\n  VERIFY_IS_APPROX(m1.exp() * m2.exp(), exp(m1+m2));\n  VERIFY_IS_APPROX(m1.exp(), exp(m1));\n  VERIFY_IS_APPROX(m1.exp() / m2.exp(),(m1-m2).exp());\n\n  VERIFY_IS_APPROX(m1.expm1(), expm1(m1));\n  VERIFY_IS_APPROX(expm1(m1), exp(m1) - 1.);\n  // Check for larger magnitude complex numbers that expm1 matches exp - 1.\n  VERIFY_IS_APPROX(expm1(10. * m1), exp(10. * m1) - 1.);\n\n  VERIFY_IS_APPROX(sinh(m1), 0.5*(exp(m1)-exp(-m1)));\n  VERIFY_IS_APPROX(cosh(m1), 0.5*(exp(m1)+exp(-m1)));\n  VERIFY_IS_APPROX(tanh(m1), (0.5*(exp(m1)-exp(-m1)))/(0.5*(exp(m1)+exp(-m1))));\n  VERIFY_IS_APPROX(logistic(m1), (1.0/(1.0 + exp(-m1))));\n\n  for (Index i = 0; i < m.rows(); ++i)\n    for (Index j = 0; j < m.cols(); ++j)\n      m3(i,j) = std::atan2(m1(i,j).imag(), m1(i,j).real());\n  VERIFY_IS_APPROX(arg(m1), m3);\n\n  std::complex<RealScalar> zero(0.0,0.0);\n  VERIFY((Eigen::isnan)(m1*zero/zero).all());\n#if EIGEN_COMP_MSVC\n  // msvc complex division is not robust\n  VERIFY((Eigen::isinf)(m4/RealScalar(0)).all());\n#else\n#if EIGEN_COMP_CLANG\n  // clang's complex division is notoriously broken too\n  if((numext::isinf)(m4(0,0)/RealScalar(0))) {\n#endif\n    VERIFY((Eigen::isinf)(m4/zero).all());\n#if EIGEN_COMP_CLANG\n  }\n  else\n  {\n    VERIFY((Eigen::isinf)(m4.real()/zero.real()).all());\n  }\n#endif\n#endif // MSVC\n\n  VERIFY(((Eigen::isfinite)(m1) && (!(Eigen::isfinite)(m1*zero/zero)) && (!(Eigen::isfinite)(m1/zero))).all());\n\n  VERIFY_IS_APPROX(inverse(inverse(m4)),m4);\n  VERIFY_IS_APPROX(conj(m1.conjugate()), m1);\n  VERIFY_IS_APPROX(abs(m1), sqrt(square(m1.real())+square(m1.imag())));\n  VERIFY_IS_APPROX(abs(m1), sqrt(abs2(m1)));\n  VERIFY_IS_APPROX(log10(m1), log(m1)/log(10));\n  VERIFY_IS_APPROX(log2(m1), log(m1)/log(2));\n\n  VERIFY_IS_APPROX( m1.sign(), -(-m1).sign() );\n  VERIFY_IS_APPROX( m1.sign() * m1.abs(), m1);\n\n  // scalar by array division\n  Scalar  s1 = internal::random<Scalar>();\n  const RealScalar tiny = std::sqrt(std::numeric_limits<RealScalar>::epsilon());\n  s1 += Scalar(tiny);\n  m1 += ArrayType::Constant(rows,cols,Scalar(tiny));\n  VERIFY_IS_APPROX(s1/m1, s1 * m1.inverse());\n\n  // check inplace transpose\n  m2 = m1;\n  m2.transposeInPlace();\n  VERIFY_IS_APPROX(m2, m1.transpose());\n  m2.transposeInPlace();\n  VERIFY_IS_APPROX(m2, m1);\n  // Check vectorized inplace transpose.\n  ArrayType m5 = ArrayType::Random(131, 131);\n  ArrayType m6 = m5;\n  m6.transposeInPlace();\n  VERIFY_IS_APPROX(m6, m5.transpose());\n}\n\ntemplate<typename ArrayType> void min_max(const ArrayType& m)\n{\n  typedef typename ArrayType::Scalar Scalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  ArrayType m1 = ArrayType::Random(rows, cols);\n\n  // min/max with array\n  Scalar maxM1 = m1.maxCoeff();\n  Scalar minM1 = m1.minCoeff();\n\n  VERIFY_IS_APPROX(ArrayType::Constant(rows,cols, minM1), (m1.min)(ArrayType::Constant(rows,cols, minM1)));\n  VERIFY_IS_APPROX(m1, (m1.min)(ArrayType::Constant(rows,cols, maxM1)));\n\n  VERIFY_IS_APPROX(ArrayType::Constant(rows,cols, maxM1), (m1.max)(ArrayType::Constant(rows,cols, maxM1)));\n  VERIFY_IS_APPROX(m1, (m1.max)(ArrayType::Constant(rows,cols, minM1)));\n\n  // min/max with scalar input\n  VERIFY_IS_APPROX(ArrayType::Constant(rows,cols, minM1), (m1.min)( minM1));\n  VERIFY_IS_APPROX(m1, (m1.min)( maxM1));\n\n  VERIFY_IS_APPROX(ArrayType::Constant(rows,cols, maxM1), (m1.max)( maxM1));\n  VERIFY_IS_APPROX(m1, (m1.max)( minM1));\n\n\n  // min/max with various NaN propagation options.\n  if (m1.size() > 1 && !NumTraits<Scalar>::IsInteger) {\n    m1(0,0) = NumTraits<Scalar>::quiet_NaN();\n    maxM1 = m1.template maxCoeff<PropagateNaN>();\n    minM1 = m1.template minCoeff<PropagateNaN>();\n    VERIFY((numext::isnan)(maxM1));\n    VERIFY((numext::isnan)(minM1));\n\n    maxM1 = m1.template maxCoeff<PropagateNumbers>();\n    minM1 = m1.template minCoeff<PropagateNumbers>();\n    VERIFY(!(numext::isnan)(maxM1));\n    VERIFY(!(numext::isnan)(minM1));\n  }\n}\n\ntemplate<int N>\nstruct shift_left {\n  template<typename Scalar>\n  Scalar operator()(const Scalar& v) const {\n    return v << N;\n  }\n};\n\ntemplate<int N>\nstruct arithmetic_shift_right {\n  template<typename Scalar>\n  Scalar operator()(const Scalar& v) const {\n    return v >> N;\n  }\n};\n\ntemplate<typename ArrayType> void array_integer(const ArrayType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  ArrayType m1 = ArrayType::Random(rows, cols),\n            m2(rows, cols);\n\n  m2 = m1.template shiftLeft<2>();\n  VERIFY( (m2 == m1.unaryExpr(shift_left<2>())).all() );\n  m2 = m1.template shiftLeft<9>();\n  VERIFY( (m2 == m1.unaryExpr(shift_left<9>())).all() );\n  \n  m2 = m1.template shiftRight<2>();\n  VERIFY( (m2 == m1.unaryExpr(arithmetic_shift_right<2>())).all() );\n  m2 = m1.template shiftRight<9>();\n  VERIFY( (m2 == m1.unaryExpr(arithmetic_shift_right<9>())).all() );\n}\n\nEIGEN_DECLARE_TEST(array_cwise)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( array(Array<float, 1, 1>()) );\n    CALL_SUBTEST_2( array(Array22f()) );\n    CALL_SUBTEST_3( array(Array44d()) );\n    CALL_SUBTEST_4( array(ArrayXXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_5( array(ArrayXXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( array(ArrayXXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( array(Array<Index,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( array_integer(ArrayXXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( array_integer(Array<Index,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( comparisons(Array<float, 1, 1>()) );\n    CALL_SUBTEST_2( comparisons(Array22f()) );\n    CALL_SUBTEST_3( comparisons(Array44d()) );\n    CALL_SUBTEST_5( comparisons(ArrayXXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( comparisons(ArrayXXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( min_max(Array<float, 1, 1>()) );\n    CALL_SUBTEST_2( min_max(Array22f()) );\n    CALL_SUBTEST_3( min_max(Array44d()) );\n    CALL_SUBTEST_5( min_max(ArrayXXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( min_max(ArrayXXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( array_real(Array<float, 1, 1>()) );\n    CALL_SUBTEST_2( array_real(Array22f()) );\n    CALL_SUBTEST_3( array_real(Array44d()) );\n    CALL_SUBTEST_5( array_real(ArrayXXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_7( array_real(Array<Eigen::half, 32, 32>()) );\n    CALL_SUBTEST_8( array_real(Array<Eigen::bfloat16, 32, 32>()) );\n  }\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_4( array_complex(ArrayXXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n\n  VERIFY((internal::is_same< internal::global_math_functions_filtering_base<int>::type, int >::value));\n  VERIFY((internal::is_same< internal::global_math_functions_filtering_base<float>::type, float >::value));\n  VERIFY((internal::is_same< internal::global_math_functions_filtering_base<Array2i>::type, ArrayBase<Array2i> >::value));\n  typedef CwiseUnaryOp<internal::scalar_abs_op<double>, ArrayXd > Xpr;\n  VERIFY((internal::is_same< internal::global_math_functions_filtering_base<Xpr>::type,\n                           ArrayBase<Xpr>\n                         >::value));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/array_for_matrix.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void array_for_matrix(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> ColVectorType;\n  typedef Matrix<Scalar, 1, MatrixType::ColsAtCompileTime> RowVectorType; \n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols);\n\n  ColVectorType cv1 = ColVectorType::Random(rows);\n  RowVectorType rv1 = RowVectorType::Random(cols);\n  \n  Scalar  s1 = internal::random<Scalar>(),\n          s2 = internal::random<Scalar>();\n          \n  // scalar addition\n  VERIFY_IS_APPROX(m1.array() + s1, s1 + m1.array());\n  VERIFY_IS_APPROX((m1.array() + s1).matrix(), MatrixType::Constant(rows,cols,s1) + m1);\n  VERIFY_IS_APPROX(((m1*Scalar(2)).array() - s2).matrix(), (m1+m1) - MatrixType::Constant(rows,cols,s2) );\n  m3 = m1;\n  m3.array() += s2;\n  VERIFY_IS_APPROX(m3, (m1.array() + s2).matrix());\n  m3 = m1;\n  m3.array() -= s1;\n  VERIFY_IS_APPROX(m3, (m1.array() - s1).matrix());\n\n  // reductions\n  VERIFY_IS_MUCH_SMALLER_THAN(m1.colwise().sum().sum() - m1.sum(), m1.squaredNorm());\n  VERIFY_IS_MUCH_SMALLER_THAN(m1.rowwise().sum().sum() - m1.sum(), m1.squaredNorm());\n  VERIFY_IS_MUCH_SMALLER_THAN(m1.colwise().sum() + m2.colwise().sum() - (m1+m2).colwise().sum(), (m1+m2).squaredNorm());\n  VERIFY_IS_MUCH_SMALLER_THAN(m1.rowwise().sum() - m2.rowwise().sum() - (m1-m2).rowwise().sum(), (m1-m2).squaredNorm());\n  VERIFY_IS_APPROX(m1.colwise().sum(), m1.colwise().redux(internal::scalar_sum_op<Scalar,Scalar>()));\n\n  // vector-wise ops\n  m3 = m1;\n  VERIFY_IS_APPROX(m3.colwise() += cv1, m1.colwise() + cv1);\n  m3 = m1;\n  VERIFY_IS_APPROX(m3.colwise() -= cv1, m1.colwise() - cv1);\n  m3 = m1;\n  VERIFY_IS_APPROX(m3.rowwise() += rv1, m1.rowwise() + rv1);\n  m3 = m1;\n  VERIFY_IS_APPROX(m3.rowwise() -= rv1, m1.rowwise() - rv1);\n  \n  // empty objects\n  VERIFY_IS_APPROX((m1.template block<0,Dynamic>(0,0,0,cols).colwise().sum()), RowVectorType::Zero(cols));\n  VERIFY_IS_APPROX((m1.template block<Dynamic,0>(0,0,rows,0).rowwise().sum()), ColVectorType::Zero(rows));\n  VERIFY_IS_APPROX((m1.template block<0,Dynamic>(0,0,0,cols).colwise().prod()), RowVectorType::Ones(cols));\n  VERIFY_IS_APPROX((m1.template block<Dynamic,0>(0,0,rows,0).rowwise().prod()), ColVectorType::Ones(rows));\n\n  VERIFY_IS_APPROX(m1.block(0,0,0,cols).colwise().sum(), RowVectorType::Zero(cols));\n  VERIFY_IS_APPROX(m1.block(0,0,rows,0).rowwise().sum(), ColVectorType::Zero(rows));\n  VERIFY_IS_APPROX(m1.block(0,0,0,cols).colwise().prod(), RowVectorType::Ones(cols));\n  VERIFY_IS_APPROX(m1.block(0,0,rows,0).rowwise().prod(), ColVectorType::Ones(rows));\n  \n  // verify the const accessors exist\n  const Scalar& ref_m1 = m.matrix().array().coeffRef(0);\n  const Scalar& ref_m2 = m.matrix().array().coeffRef(0,0);\n  const Scalar& ref_a1 = m.array().matrix().coeffRef(0);\n  const Scalar& ref_a2 = m.array().matrix().coeffRef(0,0);\n  VERIFY(&ref_a1 == &ref_m1);\n  VERIFY(&ref_a2 == &ref_m2);\n\n  // Check write accessors:\n  m1.array().coeffRef(0,0) = 1;\n  VERIFY_IS_APPROX(m1(0,0),Scalar(1));\n  m1.array()(0,0) = 2;\n  VERIFY_IS_APPROX(m1(0,0),Scalar(2));\n  m1.array().matrix().coeffRef(0,0) = 3;\n  VERIFY_IS_APPROX(m1(0,0),Scalar(3));\n  m1.array().matrix()(0,0) = 4;\n  VERIFY_IS_APPROX(m1(0,0),Scalar(4));\n}\n\ntemplate<typename MatrixType> void comparisons(const MatrixType& m)\n{\n  using std::abs;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  Index r = internal::random<Index>(0, rows-1),\n        c = internal::random<Index>(0, cols-1);\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols);\n\n  VERIFY(((m1.array() + Scalar(1)) > m1.array()).all());\n  VERIFY(((m1.array() - Scalar(1)) < m1.array()).all());\n  if (rows*cols>1)\n  {\n    m3 = m1;\n    m3(r,c) += 1;\n    VERIFY(! (m1.array() < m3.array()).all() );\n    VERIFY(! (m1.array() > m3.array()).all() );\n  }\n\n  // comparisons to scalar\n  VERIFY( (m1.array() != (m1(r,c)+1) ).any() );\n  VERIFY( (m1.array() > (m1(r,c)-1) ).any() );\n  VERIFY( (m1.array() < (m1(r,c)+1) ).any() );\n  VERIFY( (m1.array() == m1(r,c) ).any() );\n  VERIFY( m1.cwiseEqual(m1(r,c)).any() );\n\n  // test Select\n  VERIFY_IS_APPROX( (m1.array()<m2.array()).select(m1,m2), m1.cwiseMin(m2) );\n  VERIFY_IS_APPROX( (m1.array()>m2.array()).select(m1,m2), m1.cwiseMax(m2) );\n  Scalar mid = (m1.cwiseAbs().minCoeff() + m1.cwiseAbs().maxCoeff())/Scalar(2);\n  for (int j=0; j<cols; ++j)\n  for (int i=0; i<rows; ++i)\n    m3(i,j) = abs(m1(i,j))<mid ? 0 : m1(i,j);\n  VERIFY_IS_APPROX( (m1.array().abs()<MatrixType::Constant(rows,cols,mid).array())\n                        .select(MatrixType::Zero(rows,cols),m1), m3);\n  // shorter versions:\n  VERIFY_IS_APPROX( (m1.array().abs()<MatrixType::Constant(rows,cols,mid).array())\n                        .select(0,m1), m3);\n  VERIFY_IS_APPROX( (m1.array().abs()>=MatrixType::Constant(rows,cols,mid).array())\n                        .select(m1,0), m3);\n  // even shorter version:\n  VERIFY_IS_APPROX( (m1.array().abs()<mid).select(0,m1), m3);\n\n  // count\n  VERIFY(((m1.array().abs()+1)>RealScalar(0.1)).count() == rows*cols);\n\n  // and/or\n  VERIFY( ((m1.array()<RealScalar(0)).matrix() && (m1.array()>RealScalar(0)).matrix()).count() == 0);\n  VERIFY( ((m1.array()<RealScalar(0)).matrix() || (m1.array()>=RealScalar(0)).matrix()).count() == rows*cols);\n  RealScalar a = m1.cwiseAbs().mean();\n  VERIFY( ((m1.array()<-a).matrix() || (m1.array()>a).matrix()).count() == (m1.cwiseAbs().array()>a).count());\n\n  typedef Matrix<Index, Dynamic, 1> VectorOfIndices;\n\n  // TODO allows colwise/rowwise for array\n  VERIFY_IS_APPROX(((m1.array().abs()+1)>RealScalar(0.1)).matrix().colwise().count(), VectorOfIndices::Constant(cols,rows).transpose());\n  VERIFY_IS_APPROX(((m1.array().abs()+1)>RealScalar(0.1)).matrix().rowwise().count(), VectorOfIndices::Constant(rows, cols));\n}\n\ntemplate<typename VectorType> void lpNorm(const VectorType& v)\n{\n  using std::sqrt;\n  typedef typename VectorType::RealScalar RealScalar;\n  VectorType u = VectorType::Random(v.size());\n\n  if(v.size()==0)\n  {\n    VERIFY_IS_APPROX(u.template lpNorm<Infinity>(), RealScalar(0));\n    VERIFY_IS_APPROX(u.template lpNorm<1>(), RealScalar(0));\n    VERIFY_IS_APPROX(u.template lpNorm<2>(), RealScalar(0));\n    VERIFY_IS_APPROX(u.template lpNorm<5>(), RealScalar(0));\n  }\n  else\n  {\n    VERIFY_IS_APPROX(u.template lpNorm<Infinity>(), u.cwiseAbs().maxCoeff());\n  }\n\n  VERIFY_IS_APPROX(u.template lpNorm<1>(), u.cwiseAbs().sum());\n  VERIFY_IS_APPROX(u.template lpNorm<2>(), sqrt(u.array().abs().square().sum()));\n  VERIFY_IS_APPROX(numext::pow(u.template lpNorm<5>(), typename VectorType::RealScalar(5)), u.array().abs().pow(5).sum());\n}\n\ntemplate<typename MatrixType> void cwise_min_max(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols);\n\n  // min/max with array\n  Scalar maxM1 = m1.maxCoeff();\n  Scalar minM1 = m1.minCoeff();\n\n  VERIFY_IS_APPROX(MatrixType::Constant(rows,cols, minM1), m1.cwiseMin(MatrixType::Constant(rows,cols, minM1)));\n  VERIFY_IS_APPROX(m1, m1.cwiseMin(MatrixType::Constant(rows,cols, maxM1)));\n\n  VERIFY_IS_APPROX(MatrixType::Constant(rows,cols, maxM1), m1.cwiseMax(MatrixType::Constant(rows,cols, maxM1)));\n  VERIFY_IS_APPROX(m1, m1.cwiseMax(MatrixType::Constant(rows,cols, minM1)));\n\n  // min/max with scalar input\n  VERIFY_IS_APPROX(MatrixType::Constant(rows,cols, minM1), m1.cwiseMin( minM1));\n  VERIFY_IS_APPROX(m1, m1.cwiseMin(maxM1));\n  VERIFY_IS_APPROX(-m1, (-m1).cwiseMin(-minM1));\n  VERIFY_IS_APPROX(-m1.array(), ((-m1).array().min)( -minM1));\n\n  VERIFY_IS_APPROX(MatrixType::Constant(rows,cols, maxM1), m1.cwiseMax( maxM1));\n  VERIFY_IS_APPROX(m1, m1.cwiseMax(minM1));\n  VERIFY_IS_APPROX(-m1, (-m1).cwiseMax(-maxM1));\n  VERIFY_IS_APPROX(-m1.array(), ((-m1).array().max)(-maxM1));\n\n  VERIFY_IS_APPROX(MatrixType::Constant(rows,cols, minM1).array(), (m1.array().min)( minM1));\n  VERIFY_IS_APPROX(m1.array(), (m1.array().min)( maxM1));\n\n  VERIFY_IS_APPROX(MatrixType::Constant(rows,cols, maxM1).array(), (m1.array().max)( maxM1));\n  VERIFY_IS_APPROX(m1.array(), (m1.array().max)( minM1));\n\n}\n\ntemplate<typename MatrixTraits> void resize(const MatrixTraits& t)\n{\n  typedef typename MatrixTraits::Scalar Scalar;\n  typedef Matrix<Scalar,Dynamic,Dynamic> MatrixType;\n  typedef Array<Scalar,Dynamic,Dynamic> Array2DType;\n  typedef Matrix<Scalar,Dynamic,1> VectorType;\n  typedef Array<Scalar,Dynamic,1> Array1DType;\n\n  Index rows = t.rows(), cols = t.cols();\n\n  MatrixType m(rows,cols);\n  VectorType v(rows);\n  Array2DType a2(rows,cols);\n  Array1DType a1(rows);\n\n  m.array().resize(rows+1,cols+1);\n  VERIFY(m.rows()==rows+1 && m.cols()==cols+1);\n  a2.matrix().resize(rows+1,cols+1);\n  VERIFY(a2.rows()==rows+1 && a2.cols()==cols+1);\n  v.array().resize(cols);\n  VERIFY(v.size()==cols);\n  a1.matrix().resize(cols);\n  VERIFY(a1.size()==cols);\n}\n\ntemplate<int>\nvoid regression_bug_654()\n{\n  ArrayXf a = RowVectorXf(3);\n  VectorXf v = Array<float,1,Dynamic>(3);\n}\n\n// Check propagation of LvalueBit through Array/Matrix-Wrapper\ntemplate<int>\nvoid regrrssion_bug_1410()\n{\n  const Matrix4i M;\n  const Array4i A;\n  ArrayWrapper<const Matrix4i> MA = M.array();\n  MA.row(0);\n  MatrixWrapper<const Array4i> AM = A.matrix();\n  AM.row(0);\n\n  VERIFY((internal::traits<ArrayWrapper<const Matrix4i> >::Flags&LvalueBit)==0);\n  VERIFY((internal::traits<MatrixWrapper<const Array4i> >::Flags&LvalueBit)==0);\n\n  VERIFY((internal::traits<ArrayWrapper<Matrix4i> >::Flags&LvalueBit)==LvalueBit);\n  VERIFY((internal::traits<MatrixWrapper<Array4i> >::Flags&LvalueBit)==LvalueBit);\n}\n\nEIGEN_DECLARE_TEST(array_for_matrix)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( array_for_matrix(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( array_for_matrix(Matrix2f()) );\n    CALL_SUBTEST_3( array_for_matrix(Matrix4d()) );\n    CALL_SUBTEST_4( array_for_matrix(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_5( array_for_matrix(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( array_for_matrix(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( comparisons(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( comparisons(Matrix2f()) );\n    CALL_SUBTEST_3( comparisons(Matrix4d()) );\n    CALL_SUBTEST_5( comparisons(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( comparisons(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( cwise_min_max(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( cwise_min_max(Matrix2f()) );\n    CALL_SUBTEST_3( cwise_min_max(Matrix4d()) );\n    CALL_SUBTEST_5( cwise_min_max(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( cwise_min_max(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( lpNorm(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( lpNorm(Vector2f()) );\n    CALL_SUBTEST_7( lpNorm(Vector3d()) );\n    CALL_SUBTEST_8( lpNorm(Vector4f()) );\n    CALL_SUBTEST_5( lpNorm(VectorXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_4( lpNorm(VectorXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  CALL_SUBTEST_5( lpNorm(VectorXf(0)) );\n  CALL_SUBTEST_4( lpNorm(VectorXcf(0)) );\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_4( resize(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_5( resize(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( resize(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  CALL_SUBTEST_6( regression_bug_654<0>() );\n  CALL_SUBTEST_6( regrrssion_bug_1410<0>() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/array_of_string.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\nEIGEN_DECLARE_TEST(array_of_string)\n{\n  typedef Array<std::string,1,Dynamic> ArrayXs;\n  ArrayXs a1(3), a2(3), a3(3), a3ref(3);\n  a1 << \"one\", \"two\", \"three\";\n  a2 << \"1\", \"2\", \"3\";\n  a3ref << \"one (1)\", \"two (2)\", \"three (3)\";\n  std::stringstream s1;\n  s1 << a1;\n  VERIFY_IS_EQUAL(s1.str(), std::string(\"  one    two  three\"));\n  a3 = a1 + std::string(\" (\") + a2 + std::string(\")\");\n  VERIFY((a3==a3ref).all());\n\n  a3 = a1;\n  a3 += std::string(\" (\") + a2 + std::string(\")\");\n  VERIFY((a3==a3ref).all());\n\n  a1.swap(a3);\n  VERIFY((a1==a3ref).all());\n  VERIFY((a3!=a3ref).all());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/array_replicate.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void replicate(const MatrixType& m)\n{\n  /* this test covers the following files:\n     Replicate.cpp\n  */\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n  typedef Matrix<Scalar, Dynamic, Dynamic> MatrixX;\n  typedef Matrix<Scalar, Dynamic, 1> VectorX;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols);\n\n  VectorType v1 = VectorType::Random(rows);\n\n  MatrixX x1, x2;\n  VectorX vx1;\n\n  int  f1 = internal::random<int>(1,10),\n       f2 = internal::random<int>(1,10);\n\n  x1.resize(rows*f1,cols*f2);\n  for(int j=0; j<f2; j++)\n  for(int i=0; i<f1; i++)\n    x1.block(i*rows,j*cols,rows,cols) = m1;\n  VERIFY_IS_APPROX(x1, m1.replicate(f1,f2));\n\n  x2.resize(2*rows,3*cols);\n  x2 << m2, m2, m2,\n        m2, m2, m2;\n  VERIFY_IS_APPROX(x2, (m2.template replicate<2,3>()));\n  \n  x2.resize(rows,3*cols);\n  x2 << m2, m2, m2;\n  VERIFY_IS_APPROX(x2, (m2.template replicate<1,3>()));\n  \n  vx1.resize(3*rows,cols);\n  vx1 << m2, m2, m2;\n  VERIFY_IS_APPROX(vx1+vx1, vx1+(m2.template replicate<3,1>()));\n  \n  vx1=m2+(m2.colwise().replicate(1));\n  \n  if(m2.cols()==1)\n    VERIFY_IS_APPROX(m2.coeff(0), (m2.template replicate<3,1>().coeff(m2.rows())));\n\n  x2.resize(rows,f1);\n  for (int j=0; j<f1; ++j)\n    x2.col(j) = v1;\n  VERIFY_IS_APPROX(x2, v1.rowwise().replicate(f1));\n\n  vx1.resize(rows*f2);\n  for (int j=0; j<f2; ++j)\n    vx1.segment(j*rows,rows) = v1;\n  VERIFY_IS_APPROX(vx1, v1.colwise().replicate(f2));\n}\n\nEIGEN_DECLARE_TEST(array_replicate)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( replicate(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( replicate(Vector2f()) );\n    CALL_SUBTEST_3( replicate(Vector3d()) );\n    CALL_SUBTEST_4( replicate(Vector4f()) );\n    CALL_SUBTEST_5( replicate(VectorXf(16)) );\n    CALL_SUBTEST_6( replicate(VectorXcd(10)) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/array_reverse.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2009 Ricard Marxer <email@ricardmarxer.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <iostream>\n\nusing namespace std;\n\ntemplate<typename MatrixType> void reverse(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  // this test relies a lot on Random.h, and there's not much more that we can do\n  // to test it, hence I consider that we will have tested Random.h\n  MatrixType m1 = MatrixType::Random(rows, cols), m2;\n  VectorType v1 = VectorType::Random(rows);\n\n  MatrixType m1_r = m1.reverse();\n  // Verify that MatrixBase::reverse() works\n  for ( int i = 0; i < rows; i++ ) {\n    for ( int j = 0; j < cols; j++ ) {\n      VERIFY_IS_APPROX(m1_r(i, j), m1(rows - 1 - i, cols - 1 - j));\n    }\n  }\n\n  Reverse<MatrixType> m1_rd(m1);\n  // Verify that a Reverse default (in both directions) of an expression works\n  for ( int i = 0; i < rows; i++ ) {\n    for ( int j = 0; j < cols; j++ ) {\n      VERIFY_IS_APPROX(m1_rd(i, j), m1(rows - 1 - i, cols - 1 - j));\n    }\n  }\n\n  Reverse<MatrixType, BothDirections> m1_rb(m1);\n  // Verify that a Reverse in both directions of an expression works\n  for ( int i = 0; i < rows; i++ ) {\n    for ( int j = 0; j < cols; j++ ) {\n      VERIFY_IS_APPROX(m1_rb(i, j), m1(rows - 1 - i, cols - 1 - j));\n    }\n  }\n\n  Reverse<MatrixType, Vertical> m1_rv(m1);\n  // Verify that a Reverse in the vertical directions of an expression works\n  for ( int i = 0; i < rows; i++ ) {\n    for ( int j = 0; j < cols; j++ ) {\n      VERIFY_IS_APPROX(m1_rv(i, j), m1(rows - 1 - i, j));\n    }\n  }\n\n  Reverse<MatrixType, Horizontal> m1_rh(m1);\n  // Verify that a Reverse in the horizontal directions of an expression works\n  for ( int i = 0; i < rows; i++ ) {\n    for ( int j = 0; j < cols; j++ ) {\n      VERIFY_IS_APPROX(m1_rh(i, j), m1(i, cols - 1 - j));\n    }\n  }\n\n  VectorType v1_r = v1.reverse();\n  // Verify that a VectorType::reverse() of an expression works\n  for ( int i = 0; i < rows; i++ ) {\n    VERIFY_IS_APPROX(v1_r(i), v1(rows - 1 - i));\n  }\n\n  MatrixType m1_cr = m1.colwise().reverse();\n  // Verify that PartialRedux::reverse() works (for colwise())\n  for ( int i = 0; i < rows; i++ ) {\n    for ( int j = 0; j < cols; j++ ) {\n      VERIFY_IS_APPROX(m1_cr(i, j), m1(rows - 1 - i, j));\n    }\n  }\n\n  MatrixType m1_rr = m1.rowwise().reverse();\n  // Verify that PartialRedux::reverse() works (for rowwise())\n  for ( int i = 0; i < rows; i++ ) {\n    for ( int j = 0; j < cols; j++ ) {\n      VERIFY_IS_APPROX(m1_rr(i, j), m1(i, cols - 1 - j));\n    }\n  }\n\n  Scalar x = internal::random<Scalar>();\n\n  Index r = internal::random<Index>(0, rows-1),\n        c = internal::random<Index>(0, cols-1);\n\n  m1.reverse()(r, c) = x;\n  VERIFY_IS_APPROX(x, m1(rows - 1 - r, cols - 1 - c));\n  \n  m2 = m1;\n  m2.reverseInPlace();\n  VERIFY_IS_APPROX(m2,m1.reverse().eval());\n  \n  m2 = m1;\n  m2.col(0).reverseInPlace();\n  VERIFY_IS_APPROX(m2.col(0),m1.col(0).reverse().eval());\n  \n  m2 = m1;\n  m2.row(0).reverseInPlace();\n  VERIFY_IS_APPROX(m2.row(0),m1.row(0).reverse().eval());\n  \n  m2 = m1;\n  m2.rowwise().reverseInPlace();\n  VERIFY_IS_APPROX(m2,m1.rowwise().reverse().eval());\n  \n  m2 = m1;\n  m2.colwise().reverseInPlace();\n  VERIFY_IS_APPROX(m2,m1.colwise().reverse().eval());\n\n  m1.colwise().reverse()(r, c) = x;\n  VERIFY_IS_APPROX(x, m1(rows - 1 - r, c));\n\n  m1.rowwise().reverse()(r, c) = x;\n  VERIFY_IS_APPROX(x, m1(r, cols - 1 - c));\n}\n\ntemplate<int>\nvoid array_reverse_extra()\n{\n  Vector4f x; x << 1, 2, 3, 4;\n  Vector4f y; y << 4, 3, 2, 1;\n  VERIFY(x.reverse()[1] == 3);\n  VERIFY(x.reverse() == y);\n}\n\n// Simpler version of reverseInPlace leveraging a bug\n// in clang 6/7 with -O2 and AVX or AVX512 enabled.\n// This simpler version ensure that the clang bug is not simply hidden\n// through mis-inlining of reverseInPlace or other minor changes.\ntemplate<typename MatrixType>\nEIGEN_DONT_INLINE\nvoid bug1684_job1(MatrixType& m1, MatrixType& m2)\n{\n  m2 = m1;\n  m2.col(0).swap(m2.col(3));\n  m2.col(1).swap(m2.col(2));\n}\n\ntemplate<typename MatrixType>\nEIGEN_DONT_INLINE\nvoid bug1684_job2(MatrixType& m1, MatrixType& m2)\n{\n  m2 = m1; // load m1/m2 in AVX registers\n  m1.col(0) = m2.col(3); // perform 128 bits moves\n  m1.col(1) = m2.col(2);\n  m1.col(2) = m2.col(1);\n  m1.col(3) = m2.col(0);\n}\n\ntemplate<typename MatrixType>\nEIGEN_DONT_INLINE\nvoid bug1684_job3(MatrixType& m1, MatrixType& m2)\n{\n  m2 = m1;\n  Vector4f tmp;\n  tmp = m2.col(0);\n  m2.col(0) = m2.col(3);\n  m2.col(3) = tmp;\n  tmp = m2.col(1);\n  m2.col(1) = m2.col(2);\n  m2.col(2) = tmp;\n  \n}\n\ntemplate<int>\nvoid bug1684()\n{\n  Matrix4f m1 = Matrix4f::Random();\n  Matrix4f m2 = Matrix4f::Random();\n  bug1684_job1(m1,m2);\n  VERIFY_IS_APPROX(m2, m1.rowwise().reverse().eval());\n  bug1684_job2(m1,m2);\n  VERIFY_IS_APPROX(m2, m1.rowwise().reverse().eval());\n  // This one still fail after our swap's workaround,\n  // but I expect users not to implement their own swap.\n  // bug1684_job3(m1,m2);\n  // VERIFY_IS_APPROX(m2, m1.rowwise().reverse().eval());\n}\n\nEIGEN_DECLARE_TEST(array_reverse)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( reverse(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( reverse(Matrix2f()) );\n    CALL_SUBTEST_3( reverse(Matrix4f()) );\n    CALL_SUBTEST_4( reverse(Matrix4d()) );\n    CALL_SUBTEST_5( reverse(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( reverse(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_7( reverse(MatrixXcd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_8( reverse(Matrix<float, 100, 100>()) );\n    CALL_SUBTEST_9( reverse(Matrix<float,Dynamic,Dynamic,RowMajor>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_3( bug1684<0>() );\n  }\n  CALL_SUBTEST_3( array_reverse_extra<0>() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/bandmatrix.cpp",
    "content": "// This file is triangularView of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void bandmatrix(const MatrixType& _m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrixType;\n\n  Index rows = _m.rows();\n  Index cols = _m.cols();\n  Index supers = _m.supers();\n  Index subs = _m.subs();\n\n  MatrixType m(rows,cols,supers,subs);\n\n  DenseMatrixType dm1(rows,cols);\n  dm1.setZero();\n\n  m.diagonal().setConstant(123);\n  dm1.diagonal().setConstant(123);\n  for (int i=1; i<=m.supers();++i)\n  {\n    m.diagonal(i).setConstant(static_cast<RealScalar>(i));\n    dm1.diagonal(i).setConstant(static_cast<RealScalar>(i));\n  }\n  for (int i=1; i<=m.subs();++i)\n  {\n    m.diagonal(-i).setConstant(-static_cast<RealScalar>(i));\n    dm1.diagonal(-i).setConstant(-static_cast<RealScalar>(i));\n  }\n  //std::cerr << m.m_data << \"\\n\\n\" << m.toDense() << \"\\n\\n\" << dm1 << \"\\n\\n\\n\\n\";\n  VERIFY_IS_APPROX(dm1,m.toDenseMatrix());\n\n  for (int i=0; i<cols; ++i)\n  {\n    m.col(i).setConstant(static_cast<RealScalar>(i+1));\n    dm1.col(i).setConstant(static_cast<RealScalar>(i+1));\n  }\n  Index d = (std::min)(rows,cols);\n  Index a = std::max<Index>(0,cols-d-supers);\n  Index b = std::max<Index>(0,rows-d-subs);\n  if(a>0) dm1.block(0,d+supers,rows,a).setZero();\n  dm1.block(0,supers+1,cols-supers-1-a,cols-supers-1-a).template triangularView<Upper>().setZero();\n  dm1.block(subs+1,0,rows-subs-1-b,rows-subs-1-b).template triangularView<Lower>().setZero();\n  if(b>0) dm1.block(d+subs,0,b,cols).setZero();\n  //std::cerr << m.m_data << \"\\n\\n\" << m.toDense() << \"\\n\\n\" << dm1 << \"\\n\\n\";\n  VERIFY_IS_APPROX(dm1,m.toDenseMatrix());\n\n}\n\nusing Eigen::internal::BandMatrix;\n\nEIGEN_DECLARE_TEST(bandmatrix)\n{\n  for(int i = 0; i < 10*g_repeat ; i++) {\n    Index rows = internal::random<Index>(1,10);\n    Index cols = internal::random<Index>(1,10);\n    Index sups = internal::random<Index>(0,cols-1);\n    Index subs = internal::random<Index>(0,rows-1);\n    CALL_SUBTEST(bandmatrix(BandMatrix<float>(rows,cols,sups,subs)) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/basicstuff.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_STATIC_ASSERT\n\n#include \"main.h\"\n#include \"random_without_cast_overflow.h\"\n\ntemplate<typename MatrixType> void basicStuff(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> SquareMatrixType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  // this test relies a lot on Random.h, and there's not much more that we can do\n  // to test it, hence I consider that we will have tested Random.h\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols),\n             mzero = MatrixType::Zero(rows, cols),\n             square = Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime>::Random(rows, rows);\n  VectorType v1 = VectorType::Random(rows),\n             vzero = VectorType::Zero(rows);\n  SquareMatrixType sm1 = SquareMatrixType::Random(rows,rows), sm2(rows,rows);\n\n  Scalar x = 0;\n  while(x == Scalar(0)) x = internal::random<Scalar>();\n\n  Index r = internal::random<Index>(0, rows-1),\n        c = internal::random<Index>(0, cols-1);\n\n  m1.coeffRef(r,c) = x;\n  VERIFY_IS_APPROX(x, m1.coeff(r,c));\n  m1(r,c) = x;\n  VERIFY_IS_APPROX(x, m1(r,c));\n  v1.coeffRef(r) = x;\n  VERIFY_IS_APPROX(x, v1.coeff(r));\n  v1(r) = x;\n  VERIFY_IS_APPROX(x, v1(r));\n  v1[r] = x;\n  VERIFY_IS_APPROX(x, v1[r]);\n\n  // test fetching with various index types.\n  Index r1 = internal::random<Index>(0, numext::mini(Index(127),rows-1));\n  x = v1(static_cast<char>(r1));\n  x = v1(static_cast<signed char>(r1));\n  x = v1(static_cast<unsigned char>(r1));\n  x = v1(static_cast<signed short>(r1));\n  x = v1(static_cast<unsigned short>(r1));\n  x = v1(static_cast<signed int>(r1));\n  x = v1(static_cast<unsigned int>(r1));\n  x = v1(static_cast<signed long>(r1));\n  x = v1(static_cast<unsigned long>(r1));\n#if EIGEN_HAS_CXX11\n  x = v1(static_cast<long long int>(r1));\n  x = v1(static_cast<unsigned long long int>(r1));\n#endif\n\n  VERIFY_IS_APPROX(               v1,    v1);\n  VERIFY_IS_NOT_APPROX(           v1,    2*v1);\n  VERIFY_IS_MUCH_SMALLER_THAN(    vzero, v1);\n  VERIFY_IS_MUCH_SMALLER_THAN(  vzero, v1.squaredNorm());\n  VERIFY_IS_NOT_MUCH_SMALLER_THAN(v1,    v1);\n  VERIFY_IS_APPROX(               vzero, v1-v1);\n  VERIFY_IS_APPROX(               m1,    m1);\n  VERIFY_IS_NOT_APPROX(           m1,    2*m1);\n  VERIFY_IS_MUCH_SMALLER_THAN(    mzero, m1);\n  VERIFY_IS_NOT_MUCH_SMALLER_THAN(m1,    m1);\n  VERIFY_IS_APPROX(               mzero, m1-m1);\n\n  // always test operator() on each read-only expression class,\n  // in order to check const-qualifiers.\n  // indeed, if an expression class (here Zero) is meant to be read-only,\n  // hence has no _write() method, the corresponding MatrixBase method (here zero())\n  // should return a const-qualified object so that it is the const-qualified\n  // operator() that gets called, which in turn calls _read().\n  VERIFY_IS_MUCH_SMALLER_THAN(MatrixType::Zero(rows,cols)(r,c), static_cast<Scalar>(1));\n\n  // now test copying a row-vector into a (column-)vector and conversely.\n  square.col(r) = square.row(r).eval();\n  Matrix<Scalar, 1, MatrixType::RowsAtCompileTime> rv(rows);\n  Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> cv(rows);\n  rv = square.row(r);\n  cv = square.col(r);\n\n  VERIFY_IS_APPROX(rv, cv.transpose());\n\n  if(cols!=1 && rows!=1 && MatrixType::SizeAtCompileTime!=Dynamic)\n  {\n    VERIFY_RAISES_ASSERT(m1 = (m2.block(0,0, rows-1, cols-1)));\n  }\n\n  if(cols!=1 && rows!=1)\n  {\n    VERIFY_RAISES_ASSERT(m1[0]);\n    VERIFY_RAISES_ASSERT((m1+m1)[0]);\n  }\n\n  VERIFY_IS_APPROX(m3 = m1,m1);\n  MatrixType m4;\n  VERIFY_IS_APPROX(m4 = m1,m1);\n\n  m3.real() = m1.real();\n  VERIFY_IS_APPROX(static_cast<const MatrixType&>(m3).real(), static_cast<const MatrixType&>(m1).real());\n  VERIFY_IS_APPROX(static_cast<const MatrixType&>(m3).real(), m1.real());\n\n  // check == / != operators\n  VERIFY(m1==m1);\n  VERIFY(m1!=m2);\n  VERIFY(!(m1==m2));\n  VERIFY(!(m1!=m1));\n  m1 = m2;\n  VERIFY(m1==m2);\n  VERIFY(!(m1!=m2));\n\n  // check automatic transposition\n  sm2.setZero();\n  for(Index i=0;i<rows;++i)\n    sm2.col(i) = sm1.row(i);\n  VERIFY_IS_APPROX(sm2,sm1.transpose());\n\n  sm2.setZero();\n  for(Index i=0;i<rows;++i)\n    sm2.col(i).noalias() = sm1.row(i);\n  VERIFY_IS_APPROX(sm2,sm1.transpose());\n\n  sm2.setZero();\n  for(Index i=0;i<rows;++i)\n    sm2.col(i).noalias() += sm1.row(i);\n  VERIFY_IS_APPROX(sm2,sm1.transpose());\n\n  sm2.setZero();\n  for(Index i=0;i<rows;++i)\n    sm2.col(i).noalias() -= sm1.row(i);\n  VERIFY_IS_APPROX(sm2,-sm1.transpose());\n\n  // check ternary usage\n  {\n    bool b = internal::random<int>(0,10)>5;\n    m3 = b ? m1 : m2;\n    if(b) VERIFY_IS_APPROX(m3,m1);\n    else  VERIFY_IS_APPROX(m3,m2);\n    m3 = b ? -m1 : m2;\n    if(b) VERIFY_IS_APPROX(m3,-m1);\n    else  VERIFY_IS_APPROX(m3,m2);\n    m3 = b ? m1 : -m2;\n    if(b) VERIFY_IS_APPROX(m3,m1);\n    else  VERIFY_IS_APPROX(m3,-m2);\n  }\n}\n\ntemplate<typename MatrixType> void basicStuffComplex(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<RealScalar, MatrixType::RowsAtCompileTime, MatrixType::ColsAtCompileTime> RealMatrixType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  Scalar s1 = internal::random<Scalar>(),\n         s2 = internal::random<Scalar>();\n\n  VERIFY(numext::real(s1)==numext::real_ref(s1));\n  VERIFY(numext::imag(s1)==numext::imag_ref(s1));\n  numext::real_ref(s1) = numext::real(s2);\n  numext::imag_ref(s1) = numext::imag(s2);\n  VERIFY(internal::isApprox(s1, s2, NumTraits<RealScalar>::epsilon()));\n  // extended precision in Intel FPUs means that s1 == s2 in the line above is not guaranteed.\n\n  RealMatrixType rm1 = RealMatrixType::Random(rows,cols),\n                 rm2 = RealMatrixType::Random(rows,cols);\n  MatrixType cm(rows,cols);\n  cm.real() = rm1;\n  cm.imag() = rm2;\n  VERIFY_IS_APPROX(static_cast<const MatrixType&>(cm).real(), rm1);\n  VERIFY_IS_APPROX(static_cast<const MatrixType&>(cm).imag(), rm2);\n  rm1.setZero();\n  rm2.setZero();\n  rm1 = cm.real();\n  rm2 = cm.imag();\n  VERIFY_IS_APPROX(static_cast<const MatrixType&>(cm).real(), rm1);\n  VERIFY_IS_APPROX(static_cast<const MatrixType&>(cm).imag(), rm2);\n  cm.real().setZero();\n  VERIFY(static_cast<const MatrixType&>(cm).real().isZero());\n  VERIFY(!static_cast<const MatrixType&>(cm).imag().isZero());\n}\n\ntemplate<typename SrcScalar, typename TgtScalar>\nstruct casting_test {\n  static void run() {\n    Matrix<SrcScalar,4,4> m;\n    for (int i=0; i<m.rows(); ++i) {\n      for (int j=0; j<m.cols(); ++j) {\n        m(i, j) = internal::random_without_cast_overflow<SrcScalar,TgtScalar>::value();\n      }\n    }\n    Matrix<TgtScalar,4,4> n = m.template cast<TgtScalar>();\n    for (int i=0; i<m.rows(); ++i) {\n      for (int j=0; j<m.cols(); ++j) {\n        VERIFY_IS_APPROX(n(i, j), (internal::cast<SrcScalar,TgtScalar>(m(i, j))));\n      }\n    }\n  }\n};\n\ntemplate<typename SrcScalar, typename EnableIf = void>\nstruct casting_test_runner {\n  static void run() {\n    casting_test<SrcScalar, bool>::run();\n    casting_test<SrcScalar, int8_t>::run();\n    casting_test<SrcScalar, uint8_t>::run();\n    casting_test<SrcScalar, int16_t>::run();\n    casting_test<SrcScalar, uint16_t>::run();\n    casting_test<SrcScalar, int32_t>::run();\n    casting_test<SrcScalar, uint32_t>::run();\n#if EIGEN_HAS_CXX11\n    casting_test<SrcScalar, int64_t>::run();\n    casting_test<SrcScalar, uint64_t>::run();\n#endif\n    casting_test<SrcScalar, half>::run();\n    casting_test<SrcScalar, bfloat16>::run();\n    casting_test<SrcScalar, float>::run();\n    casting_test<SrcScalar, double>::run();\n    casting_test<SrcScalar, std::complex<float> >::run();\n    casting_test<SrcScalar, std::complex<double> >::run();\n  }\n};\n\ntemplate<typename SrcScalar>\nstruct casting_test_runner<SrcScalar, typename internal::enable_if<(NumTraits<SrcScalar>::IsComplex)>::type>\n{\n  static void run() {\n    // Only a few casts from std::complex<T> are defined.\n    casting_test<SrcScalar, half>::run();\n    casting_test<SrcScalar, bfloat16>::run();\n    casting_test<SrcScalar, std::complex<float> >::run();\n    casting_test<SrcScalar, std::complex<double> >::run();\n  }\n};\n\nvoid casting_all() {\n  casting_test_runner<bool>::run();\n  casting_test_runner<int8_t>::run();\n  casting_test_runner<uint8_t>::run();\n  casting_test_runner<int16_t>::run();\n  casting_test_runner<uint16_t>::run();\n  casting_test_runner<int32_t>::run();\n  casting_test_runner<uint32_t>::run();\n#if EIGEN_HAS_CXX11\n  casting_test_runner<int64_t>::run();\n  casting_test_runner<uint64_t>::run();\n#endif\n  casting_test_runner<half>::run();\n  casting_test_runner<bfloat16>::run();\n  casting_test_runner<float>::run();\n  casting_test_runner<double>::run();\n  casting_test_runner<std::complex<float> >::run();\n  casting_test_runner<std::complex<double> >::run();\n}\n\ntemplate <typename Scalar>\nvoid fixedSizeMatrixConstruction()\n{\n  Scalar raw[4];\n  for(int k=0; k<4; ++k)\n    raw[k] = internal::random<Scalar>();\n\n  {\n    Matrix<Scalar,4,1> m(raw);\n    Array<Scalar,4,1> a(raw);\n    for(int k=0; k<4; ++k) VERIFY(m(k) == raw[k]);\n    for(int k=0; k<4; ++k) VERIFY(a(k) == raw[k]);\n    VERIFY_IS_EQUAL(m,(Matrix<Scalar,4,1>(raw[0],raw[1],raw[2],raw[3])));\n    VERIFY((a==(Array<Scalar,4,1>(raw[0],raw[1],raw[2],raw[3]))).all());\n  }\n  {\n    Matrix<Scalar,3,1> m(raw);\n    Array<Scalar,3,1> a(raw);\n    for(int k=0; k<3; ++k) VERIFY(m(k) == raw[k]);\n    for(int k=0; k<3; ++k) VERIFY(a(k) == raw[k]);\n    VERIFY_IS_EQUAL(m,(Matrix<Scalar,3,1>(raw[0],raw[1],raw[2])));\n    VERIFY((a==Array<Scalar,3,1>(raw[0],raw[1],raw[2])).all());\n  }\n  {\n    Matrix<Scalar,2,1> m(raw), m2( (DenseIndex(raw[0])), (DenseIndex(raw[1])) );\n    Array<Scalar,2,1> a(raw),  a2( (DenseIndex(raw[0])), (DenseIndex(raw[1])) );\n    for(int k=0; k<2; ++k) VERIFY(m(k) == raw[k]);\n    for(int k=0; k<2; ++k) VERIFY(a(k) == raw[k]);\n    VERIFY_IS_EQUAL(m,(Matrix<Scalar,2,1>(raw[0],raw[1])));\n    VERIFY((a==Array<Scalar,2,1>(raw[0],raw[1])).all());\n    for(int k=0; k<2; ++k) VERIFY(m2(k) == DenseIndex(raw[k]));\n    for(int k=0; k<2; ++k) VERIFY(a2(k) == DenseIndex(raw[k]));\n  }\n  {\n    Matrix<Scalar,1,2> m(raw),\n                       m2( (DenseIndex(raw[0])), (DenseIndex(raw[1])) ),\n                       m3( (int(raw[0])), (int(raw[1])) ),\n                       m4( (float(raw[0])), (float(raw[1])) );\n    Array<Scalar,1,2> a(raw),  a2( (DenseIndex(raw[0])), (DenseIndex(raw[1])) );\n    for(int k=0; k<2; ++k) VERIFY(m(k) == raw[k]);\n    for(int k=0; k<2; ++k) VERIFY(a(k) == raw[k]);\n    VERIFY_IS_EQUAL(m,(Matrix<Scalar,1,2>(raw[0],raw[1])));\n    VERIFY((a==Array<Scalar,1,2>(raw[0],raw[1])).all());\n    for(int k=0; k<2; ++k) VERIFY(m2(k) == DenseIndex(raw[k]));\n    for(int k=0; k<2; ++k) VERIFY(a2(k) == DenseIndex(raw[k]));\n    for(int k=0; k<2; ++k) VERIFY(m3(k) == int(raw[k]));\n    for(int k=0; k<2; ++k) VERIFY((m4(k)) == Scalar(float(raw[k])));\n  }\n  {\n    Matrix<Scalar,1,1> m(raw), m1(raw[0]), m2( (DenseIndex(raw[0])) ), m3( (int(raw[0])) );\n    Array<Scalar,1,1> a(raw), a1(raw[0]), a2( (DenseIndex(raw[0])) );\n    VERIFY(m(0) == raw[0]);\n    VERIFY(a(0) == raw[0]);\n    VERIFY(m1(0) == raw[0]);\n    VERIFY(a1(0) == raw[0]);\n    VERIFY(m2(0) == DenseIndex(raw[0]));\n    VERIFY(a2(0) == DenseIndex(raw[0]));\n    VERIFY(m3(0) == int(raw[0]));\n    VERIFY_IS_EQUAL(m,(Matrix<Scalar,1,1>(raw[0])));\n    VERIFY((a==Array<Scalar,1,1>(raw[0])).all());\n  }\n}\n\nEIGEN_DECLARE_TEST(basicstuff)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( basicStuff(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( basicStuff(Matrix4d()) );\n    CALL_SUBTEST_3( basicStuff(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_4( basicStuff(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_5( basicStuff(MatrixXcd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( basicStuff(Matrix<float, 100, 100>()) );\n    CALL_SUBTEST_7( basicStuff(Matrix<long double,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE),internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_8( casting_all() );\n\n    CALL_SUBTEST_3( basicStuffComplex(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_5( basicStuffComplex(MatrixXcd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n\n  CALL_SUBTEST_1(fixedSizeMatrixConstruction<unsigned char>());\n  CALL_SUBTEST_1(fixedSizeMatrixConstruction<float>());\n  CALL_SUBTEST_1(fixedSizeMatrixConstruction<double>());\n  CALL_SUBTEST_1(fixedSizeMatrixConstruction<int>());\n  CALL_SUBTEST_1(fixedSizeMatrixConstruction<long int>());\n  CALL_SUBTEST_1(fixedSizeMatrixConstruction<std::ptrdiff_t>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/bdcsvd.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Gauthier Brun <brun.gauthier@gmail.com>\n// Copyright (C) 2013 Nicolas Carre <nicolas.carre@ensimag.fr>\n// Copyright (C) 2013 Jean Ceccato <jean.ceccato@ensimag.fr>\n// Copyright (C) 2013 Pierre Zoppitelli <pierre.zoppitelli@ensimag.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/\n\n// discard stack allocation as that too bypasses malloc\n#define EIGEN_STACK_ALLOCATION_LIMIT 0\n#define EIGEN_RUNTIME_NO_MALLOC\n\n#include \"main.h\"\n#include <Eigen/SVD>\n#include <iostream>\n#include <Eigen/LU>\n\n\n#define SVD_DEFAULT(M) BDCSVD<M>\n#define SVD_FOR_MIN_NORM(M) BDCSVD<M>\n#include \"svd_common.h\"\n\n// Check all variants of JacobiSVD\ntemplate<typename MatrixType>\nvoid bdcsvd(const MatrixType& a = MatrixType(), bool pickrandom = true)\n{\n  MatrixType m;\n  if(pickrandom) {\n    m.resizeLike(a);\n    svd_fill_random(m);\n  }\n  else\n    m = a;\n\n  CALL_SUBTEST(( svd_test_all_computation_options<BDCSVD<MatrixType> >(m, false)  ));\n}\n\ntemplate<typename MatrixType>\nvoid bdcsvd_method()\n{\n  enum { Size = MatrixType::RowsAtCompileTime };\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef Matrix<RealScalar, Size, 1> RealVecType;\n  MatrixType m = MatrixType::Identity();\n  VERIFY_IS_APPROX(m.bdcSvd().singularValues(), RealVecType::Ones());\n  VERIFY_RAISES_ASSERT(m.bdcSvd().matrixU());\n  VERIFY_RAISES_ASSERT(m.bdcSvd().matrixV());\n  VERIFY_IS_APPROX(m.bdcSvd(ComputeFullU|ComputeFullV).solve(m), m);\n  VERIFY_IS_APPROX(m.bdcSvd(ComputeFullU|ComputeFullV).transpose().solve(m), m);\n  VERIFY_IS_APPROX(m.bdcSvd(ComputeFullU|ComputeFullV).adjoint().solve(m), m);\n}\n\n// compare the Singular values returned with Jacobi and Bdc\ntemplate<typename MatrixType> \nvoid compare_bdc_jacobi(const MatrixType& a = MatrixType(), unsigned int computationOptions = 0)\n{\n  MatrixType m = MatrixType::Random(a.rows(), a.cols());\n  BDCSVD<MatrixType> bdc_svd(m);\n  JacobiSVD<MatrixType> jacobi_svd(m);\n  VERIFY_IS_APPROX(bdc_svd.singularValues(), jacobi_svd.singularValues());\n  if(computationOptions & ComputeFullU) VERIFY_IS_APPROX(bdc_svd.matrixU(), jacobi_svd.matrixU());\n  if(computationOptions & ComputeThinU) VERIFY_IS_APPROX(bdc_svd.matrixU(), jacobi_svd.matrixU());\n  if(computationOptions & ComputeFullV) VERIFY_IS_APPROX(bdc_svd.matrixV(), jacobi_svd.matrixV());\n  if(computationOptions & ComputeThinV) VERIFY_IS_APPROX(bdc_svd.matrixV(), jacobi_svd.matrixV());\n}\n\nEIGEN_DECLARE_TEST(bdcsvd)\n{\n  CALL_SUBTEST_3(( svd_verify_assert<BDCSVD<Matrix3f>  >(Matrix3f()) ));\n  CALL_SUBTEST_4(( svd_verify_assert<BDCSVD<Matrix4d>  >(Matrix4d()) ));\n  CALL_SUBTEST_7(( svd_verify_assert<BDCSVD<MatrixXf>  >(MatrixXf(10,12)) ));\n  CALL_SUBTEST_8(( svd_verify_assert<BDCSVD<MatrixXcd> >(MatrixXcd(7,5)) ));\n  \n  CALL_SUBTEST_101(( svd_all_trivial_2x2(bdcsvd<Matrix2cd>) ));\n  CALL_SUBTEST_102(( svd_all_trivial_2x2(bdcsvd<Matrix2d>) ));\n\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_3(( bdcsvd<Matrix3f>() ));\n    CALL_SUBTEST_4(( bdcsvd<Matrix4d>() ));\n    CALL_SUBTEST_5(( bdcsvd<Matrix<float,3,5> >() ));\n\n    int r = internal::random<int>(1, EIGEN_TEST_MAX_SIZE/2),\n        c = internal::random<int>(1, EIGEN_TEST_MAX_SIZE/2);\n    \n    TEST_SET_BUT_UNUSED_VARIABLE(r)\n    TEST_SET_BUT_UNUSED_VARIABLE(c)\n    \n    CALL_SUBTEST_6((  bdcsvd(Matrix<double,Dynamic,2>(r,2)) ));\n    CALL_SUBTEST_7((  bdcsvd(MatrixXf(r,c)) ));\n    CALL_SUBTEST_7((  compare_bdc_jacobi(MatrixXf(r,c)) ));\n    CALL_SUBTEST_10(( bdcsvd(MatrixXd(r,c)) ));\n    CALL_SUBTEST_10(( compare_bdc_jacobi(MatrixXd(r,c)) ));\n    CALL_SUBTEST_8((  bdcsvd(MatrixXcd(r,c)) ));\n    CALL_SUBTEST_8((  compare_bdc_jacobi(MatrixXcd(r,c)) ));\n\n    // Test on inf/nan matrix\n    CALL_SUBTEST_7(  (svd_inf_nan<BDCSVD<MatrixXf>, MatrixXf>()) );\n    CALL_SUBTEST_10( (svd_inf_nan<BDCSVD<MatrixXd>, MatrixXd>()) );\n  }\n\n  // test matrixbase method\n  CALL_SUBTEST_1(( bdcsvd_method<Matrix2cd>() ));\n  CALL_SUBTEST_3(( bdcsvd_method<Matrix3f>() ));\n\n  // Test problem size constructors\n  CALL_SUBTEST_7( BDCSVD<MatrixXf>(10,10) );\n\n  // Check that preallocation avoids subsequent mallocs\n  // Disabled because not supported by BDCSVD\n  // CALL_SUBTEST_9( svd_preallocate<void>() );\n\n  CALL_SUBTEST_2( svd_underoverflow<void>() );\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/bfloat16_float.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <sstream>\n#include <memory>\n#include <math.h>\n\n#include \"main.h\"\n\n#include <Eigen/src/Core/arch/Default/BFloat16.h>\n\n#define VERIFY_BFLOAT16_BITS_EQUAL(h, bits) \\\n  VERIFY_IS_EQUAL((numext::bit_cast<numext::uint16_t>(h)), (static_cast<numext::uint16_t>(bits)))\n\n// Make sure it's possible to forward declare Eigen::bfloat16\nnamespace Eigen {\nstruct bfloat16;\n}\n\nusing Eigen::bfloat16;\n\nfloat BinaryToFloat(uint32_t sign, uint32_t exponent, uint32_t high_mantissa,\n                    uint32_t low_mantissa) {\n  float dest;\n  uint32_t src = (sign << 31) + (exponent << 23) + (high_mantissa << 16) + low_mantissa;\n  memcpy(static_cast<void*>(&dest),\n         static_cast<const void*>(&src), sizeof(dest));\n  return dest;\n}\n\ntemplate<typename T>\n void test_roundtrip() {\n  // Representable T round trip via bfloat16\n  VERIFY_IS_EQUAL((internal::cast<bfloat16,T>(internal::cast<T,bfloat16>(-std::numeric_limits<T>::infinity()))), -std::numeric_limits<T>::infinity());\n  VERIFY_IS_EQUAL((internal::cast<bfloat16,T>(internal::cast<T,bfloat16>(std::numeric_limits<T>::infinity()))), std::numeric_limits<T>::infinity());\n  VERIFY_IS_EQUAL((internal::cast<bfloat16,T>(internal::cast<T,bfloat16>(T(-1.0)))), T(-1.0));\n  VERIFY_IS_EQUAL((internal::cast<bfloat16,T>(internal::cast<T,bfloat16>(T(-0.5)))), T(-0.5));\n  VERIFY_IS_EQUAL((internal::cast<bfloat16,T>(internal::cast<T,bfloat16>(T(-0.0)))), T(-0.0));\n  VERIFY_IS_EQUAL((internal::cast<bfloat16,T>(internal::cast<T,bfloat16>(T(1.0)))), T(1.0));\n  VERIFY_IS_EQUAL((internal::cast<bfloat16,T>(internal::cast<T,bfloat16>(T(0.5)))), T(0.5));\n  VERIFY_IS_EQUAL((internal::cast<bfloat16,T>(internal::cast<T,bfloat16>(T(0.0)))), T(0.0));\n}\n\nvoid test_conversion()\n{\n  using Eigen::bfloat16_impl::__bfloat16_raw;\n\n  // Round-trip casts\n  VERIFY_IS_EQUAL(\n    numext::bit_cast<bfloat16>(numext::bit_cast<numext::uint16_t>(bfloat16(1.0f))),\n    bfloat16(1.0f));\n  VERIFY_IS_EQUAL(\n    numext::bit_cast<bfloat16>(numext::bit_cast<numext::uint16_t>(bfloat16(0.5f))),\n    bfloat16(0.5f));\n  VERIFY_IS_EQUAL(\n    numext::bit_cast<bfloat16>(numext::bit_cast<numext::uint16_t>(bfloat16(-0.33333f))),\n    bfloat16(-0.33333f));\n   VERIFY_IS_EQUAL(\n    numext::bit_cast<bfloat16>(numext::bit_cast<numext::uint16_t>(bfloat16(0.0f))),\n    bfloat16(0.0f));\n\n  // Conversion from float.\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(1.0f), 0x3f80);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(0.5f), 0x3f00);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(0.33333f), 0x3eab);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(3.38e38f), 0x7f7e);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(3.40e38f), 0x7f80);  // Becomes infinity.\n\n  // Verify round-to-nearest-even behavior.\n  float val1 = static_cast<float>(bfloat16(__bfloat16_raw(0x3c00)));\n  float val2 = static_cast<float>(bfloat16(__bfloat16_raw(0x3c01)));\n  float val3 = static_cast<float>(bfloat16(__bfloat16_raw(0x3c02)));\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(0.5f * (val1 + val2)), 0x3c00);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(0.5f * (val2 + val3)), 0x3c02);\n\n  // Conversion from int.\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(-1), 0xbf80);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(0), 0x0000);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(1), 0x3f80);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(2), 0x4000);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(3), 0x4040);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(12), 0x4140);\n\n  // Conversion from bool.\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(false), 0x0000);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(true), 0x3f80);\n\n  // Conversion to bool\n  VERIFY_IS_EQUAL(static_cast<bool>(bfloat16(3)), true);\n  VERIFY_IS_EQUAL(static_cast<bool>(bfloat16(0.33333f)), true);\n  VERIFY_IS_EQUAL(bfloat16(-0.0), false);\n  VERIFY_IS_EQUAL(static_cast<bool>(bfloat16(0.0)), false);\n\n  // Explicit conversion to float.\n  VERIFY_IS_EQUAL(static_cast<float>(bfloat16(__bfloat16_raw(0x0000))), 0.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(bfloat16(__bfloat16_raw(0x3f80))), 1.0f);\n\n  // Implicit conversion to float\n  VERIFY_IS_EQUAL(bfloat16(__bfloat16_raw(0x0000)), 0.0f);\n  VERIFY_IS_EQUAL(bfloat16(__bfloat16_raw(0x3f80)), 1.0f);\n\n  // Zero representations\n  VERIFY_IS_EQUAL(bfloat16(0.0f), bfloat16(0.0f));\n  VERIFY_IS_EQUAL(bfloat16(-0.0f), bfloat16(0.0f));\n  VERIFY_IS_EQUAL(bfloat16(-0.0f), bfloat16(-0.0f));\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(0.0f), 0x0000);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(-0.0f), 0x8000);\n\n  // Default is zero\n  VERIFY_IS_EQUAL(static_cast<float>(bfloat16()), 0.0f);\n\n  // Representable floats round trip via bfloat16\n  test_roundtrip<float>();\n  test_roundtrip<double>();\n  test_roundtrip<std::complex<float> >();\n  test_roundtrip<std::complex<double> >();\n\n  // Conversion\n  Array<float,1,100> a;\n  for (int i = 0; i < 100; i++) a(i) = i + 1.25;\n  Array<bfloat16,1,100> b = a.cast<bfloat16>();\n  Array<float,1,100> c = b.cast<float>();\n  for (int i = 0; i < 100; ++i) {\n    VERIFY_LE(numext::abs(c(i) - a(i)), a(i) / 128);\n  }\n\n  // Epsilon\n  VERIFY_LE(1.0f, static_cast<float>((std::numeric_limits<bfloat16>::epsilon)() + bfloat16(1.0f)));\n  VERIFY_IS_EQUAL(1.0f, static_cast<float>((std::numeric_limits<bfloat16>::epsilon)() / bfloat16(2.0f) + bfloat16(1.0f)));\n\n  // Negate\n  VERIFY_IS_EQUAL(static_cast<float>(-bfloat16(3.0f)), -3.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(-bfloat16(-4.5f)), 4.5f);\n\n\n#if !EIGEN_COMP_MSVC\n  // Visual Studio errors out on divisions by 0\n  VERIFY((numext::isnan)(static_cast<float>(bfloat16(0.0 / 0.0))));\n  VERIFY((numext::isinf)(static_cast<float>(bfloat16(1.0 / 0.0))));\n  VERIFY((numext::isinf)(static_cast<float>(bfloat16(-1.0 / 0.0))));\n\n  // Visual Studio errors out on divisions by 0\n  VERIFY((numext::isnan)(bfloat16(0.0 / 0.0)));\n  VERIFY((numext::isinf)(bfloat16(1.0 / 0.0)));\n  VERIFY((numext::isinf)(bfloat16(-1.0 / 0.0)));\n#endif\n\n  // NaNs and infinities.\n  VERIFY(!(numext::isinf)(static_cast<float>(bfloat16(3.38e38f))));  // Largest finite number.\n  VERIFY(!(numext::isnan)(static_cast<float>(bfloat16(0.0f))));\n  VERIFY((numext::isinf)(static_cast<float>(bfloat16(__bfloat16_raw(0xff80)))));\n  VERIFY((numext::isnan)(static_cast<float>(bfloat16(__bfloat16_raw(0xffc0)))));\n  VERIFY((numext::isinf)(static_cast<float>(bfloat16(__bfloat16_raw(0x7f80)))));\n  VERIFY((numext::isnan)(static_cast<float>(bfloat16(__bfloat16_raw(0x7fc0)))));\n\n  // Exactly same checks as above, just directly on the bfloat16 representation.\n  VERIFY(!(numext::isinf)(bfloat16(__bfloat16_raw(0x7bff))));\n  VERIFY(!(numext::isnan)(bfloat16(__bfloat16_raw(0x0000))));\n  VERIFY((numext::isinf)(bfloat16(__bfloat16_raw(0xff80))));\n  VERIFY((numext::isnan)(bfloat16(__bfloat16_raw(0xffc0))));\n  VERIFY((numext::isinf)(bfloat16(__bfloat16_raw(0x7f80))));\n  VERIFY((numext::isnan)(bfloat16(__bfloat16_raw(0x7fc0))));\n\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(BinaryToFloat(0x0, 0xff, 0x40, 0x0)), 0x7fc0);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(BinaryToFloat(0x1, 0xff, 0x40, 0x0)), 0xffc0);\n}\n\nvoid test_numtraits()\n{\n  std::cout << \"epsilon       = \" << NumTraits<bfloat16>::epsilon() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(NumTraits<bfloat16>::epsilon()) << \")\" << std::endl;\n  std::cout << \"highest       = \" << NumTraits<bfloat16>::highest() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(NumTraits<bfloat16>::highest()) << \")\" << std::endl;\n  std::cout << \"lowest        = \" << NumTraits<bfloat16>::lowest() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(NumTraits<bfloat16>::lowest()) << \")\" << std::endl;\n  std::cout << \"min           = \" << (std::numeric_limits<bfloat16>::min)() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>((std::numeric_limits<bfloat16>::min)()) << \")\" << std::endl;\n  std::cout << \"denorm min    = \" << (std::numeric_limits<bfloat16>::denorm_min)() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>((std::numeric_limits<bfloat16>::denorm_min)()) << \")\" << std::endl;\n  std::cout << \"infinity      = \" << NumTraits<bfloat16>::infinity() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(NumTraits<bfloat16>::infinity()) << \")\" << std::endl;\n  std::cout << \"quiet nan     = \" << NumTraits<bfloat16>::quiet_NaN() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(NumTraits<bfloat16>::quiet_NaN()) << \")\" << std::endl;\n  std::cout << \"signaling nan = \" << std::numeric_limits<bfloat16>::signaling_NaN() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(std::numeric_limits<bfloat16>::signaling_NaN()) << \")\" << std::endl;\n\n  VERIFY(NumTraits<bfloat16>::IsSigned);\n\n  VERIFY_IS_EQUAL(\n    numext::bit_cast<numext::uint16_t>(std::numeric_limits<bfloat16>::infinity()),\n    numext::bit_cast<numext::uint16_t>(bfloat16(std::numeric_limits<float>::infinity())) );\n  // There is no guarantee that casting a 32-bit NaN to bfloat16 has a precise\n  // bit pattern.  We test that it is in fact a NaN, then test the signaling\n  // bit (msb of significand is 1 for quiet, 0 for signaling).\n  const numext::uint16_t BFLOAT16_QUIET_BIT = 0x0040;\n  VERIFY(\n    (numext::isnan)(std::numeric_limits<bfloat16>::quiet_NaN())\n    && (numext::isnan)(bfloat16(std::numeric_limits<float>::quiet_NaN()))\n    && ((numext::bit_cast<numext::uint16_t>(std::numeric_limits<bfloat16>::quiet_NaN()) & BFLOAT16_QUIET_BIT) > 0)\n    && ((numext::bit_cast<numext::uint16_t>(bfloat16(std::numeric_limits<float>::quiet_NaN())) & BFLOAT16_QUIET_BIT) > 0) );\n  // After a cast to bfloat16, a signaling NaN may become non-signaling. Thus,\n  // we check that both are NaN, and that only the `numeric_limits` version is\n  // signaling.\n  VERIFY(\n    (numext::isnan)(std::numeric_limits<bfloat16>::signaling_NaN())\n    && (numext::isnan)(bfloat16(std::numeric_limits<float>::signaling_NaN()))\n    && ((numext::bit_cast<numext::uint16_t>(std::numeric_limits<bfloat16>::signaling_NaN()) & BFLOAT16_QUIET_BIT) == 0) );\n\n  VERIFY( (std::numeric_limits<bfloat16>::min)() > bfloat16(0.f) );\n  VERIFY( (std::numeric_limits<bfloat16>::denorm_min)() > bfloat16(0.f) );\n  VERIFY_IS_EQUAL( (std::numeric_limits<bfloat16>::denorm_min)()/bfloat16(2), bfloat16(0.f) );\n}\n\nvoid test_arithmetic()\n{\n  VERIFY_IS_EQUAL(static_cast<float>(bfloat16(2) + bfloat16(2)), 4);\n  VERIFY_IS_EQUAL(static_cast<float>(bfloat16(2) + bfloat16(-2)), 0);\n  VERIFY_IS_APPROX(static_cast<float>(bfloat16(0.33333f) + bfloat16(0.66667f)), 1.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(bfloat16(2.0f) * bfloat16(-5.5f)), -11.0f);\n  VERIFY_IS_APPROX(static_cast<float>(bfloat16(1.0f) / bfloat16(3.0f)), 0.3339f);\n  VERIFY_IS_EQUAL(static_cast<float>(-bfloat16(4096.0f)), -4096.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(-bfloat16(-4096.0f)), 4096.0f);\n}\n\nvoid test_comparison()\n{\n  VERIFY(bfloat16(1.0f) > bfloat16(0.5f));\n  VERIFY(bfloat16(0.5f) < bfloat16(1.0f));\n  VERIFY(!(bfloat16(1.0f) < bfloat16(0.5f)));\n  VERIFY(!(bfloat16(0.5f) > bfloat16(1.0f)));\n\n  VERIFY(!(bfloat16(4.0f) > bfloat16(4.0f)));\n  VERIFY(!(bfloat16(4.0f) < bfloat16(4.0f)));\n\n  VERIFY(!(bfloat16(0.0f) < bfloat16(-0.0f)));\n  VERIFY(!(bfloat16(-0.0f) < bfloat16(0.0f)));\n  VERIFY(!(bfloat16(0.0f) > bfloat16(-0.0f)));\n  VERIFY(!(bfloat16(-0.0f) > bfloat16(0.0f)));\n\n  VERIFY(bfloat16(0.2f) > bfloat16(-1.0f));\n  VERIFY(bfloat16(-1.0f) < bfloat16(0.2f));\n  VERIFY(bfloat16(-16.0f) < bfloat16(-15.0f));\n\n  VERIFY(bfloat16(1.0f) == bfloat16(1.0f));\n  VERIFY(bfloat16(1.0f) != bfloat16(2.0f));\n\n  // Comparisons with NaNs and infinities.\n#if !EIGEN_COMP_MSVC\n  // Visual Studio errors out on divisions by 0\n  VERIFY(!(bfloat16(0.0 / 0.0) == bfloat16(0.0 / 0.0)));\n  VERIFY(bfloat16(0.0 / 0.0) != bfloat16(0.0 / 0.0));\n\n  VERIFY(!(bfloat16(1.0) == bfloat16(0.0 / 0.0)));\n  VERIFY(!(bfloat16(1.0) < bfloat16(0.0 / 0.0)));\n  VERIFY(!(bfloat16(1.0) > bfloat16(0.0 / 0.0)));\n  VERIFY(bfloat16(1.0) != bfloat16(0.0 / 0.0));\n\n  VERIFY(bfloat16(1.0) < bfloat16(1.0 / 0.0));\n  VERIFY(bfloat16(1.0) > bfloat16(-1.0 / 0.0));\n#endif\n}\n\nvoid test_basic_functions()\n{\n  VERIFY_IS_EQUAL(static_cast<float>(numext::abs(bfloat16(3.5f))), 3.5f);\n  VERIFY_IS_EQUAL(static_cast<float>(abs(bfloat16(3.5f))), 3.5f);\n  VERIFY_IS_EQUAL(static_cast<float>(numext::abs(bfloat16(-3.5f))), 3.5f);\n  VERIFY_IS_EQUAL(static_cast<float>(abs(bfloat16(-3.5f))), 3.5f);\n\n  VERIFY_IS_EQUAL(static_cast<float>(numext::floor(bfloat16(3.5f))), 3.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(floor(bfloat16(3.5f))), 3.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(numext::floor(bfloat16(-3.5f))), -4.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(floor(bfloat16(-3.5f))), -4.0f);\n\n  VERIFY_IS_EQUAL(static_cast<float>(numext::ceil(bfloat16(3.5f))), 4.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(ceil(bfloat16(3.5f))), 4.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(numext::ceil(bfloat16(-3.5f))), -3.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(ceil(bfloat16(-3.5f))), -3.0f);\n\n  VERIFY_IS_APPROX(static_cast<float>(numext::sqrt(bfloat16(0.0f))), 0.0f);\n  VERIFY_IS_APPROX(static_cast<float>(sqrt(bfloat16(0.0f))), 0.0f);\n  VERIFY_IS_APPROX(static_cast<float>(numext::sqrt(bfloat16(4.0f))), 2.0f);\n  VERIFY_IS_APPROX(static_cast<float>(sqrt(bfloat16(4.0f))), 2.0f);\n\n  VERIFY_IS_APPROX(static_cast<float>(numext::pow(bfloat16(0.0f), bfloat16(1.0f))), 0.0f);\n  VERIFY_IS_APPROX(static_cast<float>(pow(bfloat16(0.0f), bfloat16(1.0f))), 0.0f);\n  VERIFY_IS_APPROX(static_cast<float>(numext::pow(bfloat16(2.0f), bfloat16(2.0f))), 4.0f);\n  VERIFY_IS_APPROX(static_cast<float>(pow(bfloat16(2.0f), bfloat16(2.0f))), 4.0f);\n\n  VERIFY_IS_EQUAL(static_cast<float>(numext::exp(bfloat16(0.0f))), 1.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(exp(bfloat16(0.0f))), 1.0f);\n  VERIFY_IS_APPROX(static_cast<float>(numext::exp(bfloat16(EIGEN_PI))), 20.f + static_cast<float>(EIGEN_PI));\n  VERIFY_IS_APPROX(static_cast<float>(exp(bfloat16(EIGEN_PI))), 20.f + static_cast<float>(EIGEN_PI));\n\n  VERIFY_IS_EQUAL(static_cast<float>(numext::expm1(bfloat16(0.0f))), 0.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(expm1(bfloat16(0.0f))), 0.0f);\n  VERIFY_IS_APPROX(static_cast<float>(numext::expm1(bfloat16(2.0f))), 6.375f);\n  VERIFY_IS_APPROX(static_cast<float>(expm1(bfloat16(2.0f))), 6.375f);\n\n  VERIFY_IS_EQUAL(static_cast<float>(numext::log(bfloat16(1.0f))), 0.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(log(bfloat16(1.0f))), 0.0f);\n  VERIFY_IS_APPROX(static_cast<float>(numext::log(bfloat16(10.0f))), 2.296875f);\n  VERIFY_IS_APPROX(static_cast<float>(log(bfloat16(10.0f))), 2.296875f);\n\n  VERIFY_IS_EQUAL(static_cast<float>(numext::log1p(bfloat16(0.0f))), 0.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(log1p(bfloat16(0.0f))), 0.0f);\n  VERIFY_IS_APPROX(static_cast<float>(numext::log1p(bfloat16(10.0f))), 2.390625f);\n  VERIFY_IS_APPROX(static_cast<float>(log1p(bfloat16(10.0f))), 2.390625f);\n}\n\nvoid test_trigonometric_functions()\n{\n  VERIFY_IS_APPROX(numext::cos(bfloat16(0.0f)), bfloat16(cosf(0.0f)));\n  VERIFY_IS_APPROX(cos(bfloat16(0.0f)), bfloat16(cosf(0.0f)));\n  VERIFY_IS_APPROX(numext::cos(bfloat16(EIGEN_PI)), bfloat16(cosf(EIGEN_PI)));\n  // VERIFY_IS_APPROX(numext::cos(bfloat16(EIGEN_PI/2)), bfloat16(cosf(EIGEN_PI/2)));\n  // VERIFY_IS_APPROX(numext::cos(bfloat16(3*EIGEN_PI/2)), bfloat16(cosf(3*EIGEN_PI/2)));\n  VERIFY_IS_APPROX(numext::cos(bfloat16(3.5f)), bfloat16(cosf(3.5f)));\n\n  VERIFY_IS_APPROX(numext::sin(bfloat16(0.0f)), bfloat16(sinf(0.0f)));\n  VERIFY_IS_APPROX(sin(bfloat16(0.0f)), bfloat16(sinf(0.0f)));\n  // VERIFY_IS_APPROX(numext::sin(bfloat16(EIGEN_PI)), bfloat16(sinf(EIGEN_PI)));\n  VERIFY_IS_APPROX(numext::sin(bfloat16(EIGEN_PI/2)), bfloat16(sinf(EIGEN_PI/2)));\n  VERIFY_IS_APPROX(numext::sin(bfloat16(3*EIGEN_PI/2)), bfloat16(sinf(3*EIGEN_PI/2)));\n  VERIFY_IS_APPROX(numext::sin(bfloat16(3.5f)), bfloat16(sinf(3.5f)));\n\n  VERIFY_IS_APPROX(numext::tan(bfloat16(0.0f)), bfloat16(tanf(0.0f)));\n  VERIFY_IS_APPROX(tan(bfloat16(0.0f)), bfloat16(tanf(0.0f)));\n  // VERIFY_IS_APPROX(numext::tan(bfloat16(EIGEN_PI)), bfloat16(tanf(EIGEN_PI)));\n  // VERIFY_IS_APPROX(numext::tan(bfloat16(EIGEN_PI/2)), bfloat16(tanf(EIGEN_PI/2)));\n  // VERIFY_IS_APPROX(numext::tan(bfloat16(3*EIGEN_PI/2)), bfloat16(tanf(3*EIGEN_PI/2)));\n  VERIFY_IS_APPROX(numext::tan(bfloat16(3.5f)), bfloat16(tanf(3.5f)));\n}\n\nvoid test_array()\n{\n  typedef Array<bfloat16,1,Dynamic> ArrayXh;\n  Index size = internal::random<Index>(1,10);\n  Index i = internal::random<Index>(0,size-1);\n  ArrayXh a1 = ArrayXh::Random(size), a2 = ArrayXh::Random(size);\n  VERIFY_IS_APPROX( a1+a1, bfloat16(2)*a1 );\n  VERIFY( (a1.abs() >= bfloat16(0)).all() );\n  VERIFY_IS_APPROX( (a1*a1).sqrt(), a1.abs() );\n\n  VERIFY( ((a1.min)(a2) <= (a1.max)(a2)).all() );\n  a1(i) = bfloat16(-10.);\n  VERIFY_IS_EQUAL( a1.minCoeff(), bfloat16(-10.) );\n  a1(i) = bfloat16(10.);\n  VERIFY_IS_EQUAL( a1.maxCoeff(), bfloat16(10.) );\n\n  std::stringstream ss;\n  ss << a1;\n}\n\nvoid test_product()\n{\n  typedef Matrix<bfloat16,Dynamic,Dynamic> MatrixXh;\n  Index rows  = internal::random<Index>(1,EIGEN_TEST_MAX_SIZE);\n  Index cols  = internal::random<Index>(1,EIGEN_TEST_MAX_SIZE);\n  Index depth = internal::random<Index>(1,EIGEN_TEST_MAX_SIZE);\n  MatrixXh Ah = MatrixXh::Random(rows,depth);\n  MatrixXh Bh = MatrixXh::Random(depth,cols);\n  MatrixXh Ch = MatrixXh::Random(rows,cols);\n  MatrixXf Af = Ah.cast<float>();\n  MatrixXf Bf = Bh.cast<float>();\n  MatrixXf Cf = Ch.cast<float>();\n  VERIFY_IS_APPROX(Ch.noalias()+=Ah*Bh, (Cf.noalias()+=Af*Bf).cast<bfloat16>());\n}\n\nEIGEN_DECLARE_TEST(bfloat16_float)\n{\n  CALL_SUBTEST(test_numtraits());\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST(test_conversion());\n    CALL_SUBTEST(test_arithmetic());\n    CALL_SUBTEST(test_comparison());\n    CALL_SUBTEST(test_basic_functions());\n    CALL_SUBTEST(test_trigonometric_functions());\n    CALL_SUBTEST(test_array());\n    CALL_SUBTEST(test_product());\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/bicgstab.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"sparse_solver.h\"\n#include <Eigen/IterativeLinearSolvers>\n\ntemplate<typename T, typename I_> void test_bicgstab_T()\n{\n  BiCGSTAB<SparseMatrix<T,0,I_>, DiagonalPreconditioner<T> >     bicgstab_colmajor_diag;\n  BiCGSTAB<SparseMatrix<T,0,I_>, IdentityPreconditioner    >     bicgstab_colmajor_I;\n  BiCGSTAB<SparseMatrix<T,0,I_>, IncompleteLUT<T,I_> >              bicgstab_colmajor_ilut;\n  //BiCGSTAB<SparseMatrix<T>, SSORPreconditioner<T> >     bicgstab_colmajor_ssor;\n\n  bicgstab_colmajor_diag.setTolerance(NumTraits<T>::epsilon()*4);\n  bicgstab_colmajor_ilut.setTolerance(NumTraits<T>::epsilon()*4);\n  \n  CALL_SUBTEST( check_sparse_square_solving(bicgstab_colmajor_diag)  );\n//   CALL_SUBTEST( check_sparse_square_solving(bicgstab_colmajor_I)     );\n  CALL_SUBTEST( check_sparse_square_solving(bicgstab_colmajor_ilut)     );\n  //CALL_SUBTEST( check_sparse_square_solving(bicgstab_colmajor_ssor)     );\n}\n\nEIGEN_DECLARE_TEST(bicgstab)\n{\n  CALL_SUBTEST_1((test_bicgstab_T<double,int>()) );\n  CALL_SUBTEST_2((test_bicgstab_T<std::complex<double>, int>()));\n  CALL_SUBTEST_3((test_bicgstab_T<double,long int>()));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/blasutil.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2020 Everton Constantino <everton.constantino@ibm.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/\n\n#include \"main.h\"\n\n// Disable \"ignoring attributes on template argument\"\n// for packet_traits<Packet*>\n// => The only workaround would be to wrap _m128 and the likes\n//    within wrappers.\n#if EIGEN_GNUC_AT_LEAST(6,0)\n    #pragma GCC diagnostic ignored \"-Wignored-attributes\"\n#endif\n\n#define GET(i,j) (StorageOrder == RowMajor ? (i)*stride + (j) : (i) + (j)*stride)\n#define SCATTER(i,j,k) (StorageOrder == RowMajor ? ((i)+(k))*stride + (j) : (i) + ((j)+(k))*stride)\n\ntemplate<typename Scalar, typename Packet>\nvoid compare(const Packet& a, const Packet& b)\n{\n    int pktsz = internal::packet_traits<Scalar>::size;\n    Scalar *buffA = new Scalar[pktsz];\n    Scalar *buffB = new Scalar[pktsz];\n\n    internal::pstoreu<Scalar, Packet>(buffA, a);\n    internal::pstoreu<Scalar, Packet>(buffB, b);\n\n    for(int i = 0; i < pktsz; i++)\n    {\n        VERIFY_IS_EQUAL(buffA[i], buffB[i]);\n    }\n\n    delete[] buffA;\n    delete[] buffB;\n}\n\ntemplate<typename Scalar, int StorageOrder, int n>\nstruct PacketBlockSet\n{\n    typedef typename internal::packet_traits<Scalar>::type Packet;\n\n    void setPacketBlock(internal::PacketBlock<Packet,n>& block, Scalar value)\n    {\n        for(int idx = 0; idx < n; idx++)\n        {\n            block.packet[idx] = internal::pset1<Packet>(value);\n        }\n    }\n\n    void comparePacketBlock(Scalar *data, int i, int j, int stride, internal::PacketBlock<Packet, n>& block)\n    {\n        for(int idx = 0; idx < n; idx++)\n        {\n            Packet line = internal::ploadu<Packet>(data + SCATTER(i,j,idx));\n            compare<Scalar, Packet>(block.packet[idx], line);\n        }\n    }\n};\n\ntemplate<typename Scalar, int StorageOrder, int BlockSize>\nvoid run_bdmp_spec_1()\n{\n    typedef internal::blas_data_mapper<Scalar, int, StorageOrder> BlasDataMapper;\n    int packetSize = internal::packet_traits<Scalar>::size;\n    int minSize = std::max<int>(packetSize, BlockSize);\n    typedef typename internal::packet_traits<Scalar>::type Packet;\n\n    int szm = internal::random<int>(minSize,500), szn = internal::random<int>(minSize,500);\n    int stride = StorageOrder == RowMajor ? szn : szm;\n    Scalar *d = new Scalar[szn*szm];\n\n    // Initializing with random entries\n    for(int i = 0; i < szm*szn; i++)\n    {\n        d[i] = internal::random<Scalar>(static_cast<Scalar>(3), static_cast<Scalar>(10));\n    }\n\n    BlasDataMapper bdm(d, stride);\n\n    // Testing operator()\n    for(int i = 0; i < szm; i++)\n    {\n        for(int j = 0; j < szn; j++)\n        {\n            VERIFY_IS_EQUAL(d[GET(i,j)], bdm(i,j));\n        }\n    }\n\n    // Testing getSubMapper and getLinearMapper\n    int i0 = internal::random<int>(0,szm-2);\n    int j0 = internal::random<int>(0,szn-2);\n    for(int i = i0; i < szm; i++)\n    {\n        for(int j = j0; j < szn; j++)\n        {\n            const BlasDataMapper& bdmSM = bdm.getSubMapper(i0,j0);\n            const internal::BlasLinearMapper<Scalar, int, 0>& bdmLM = bdm.getLinearMapper(i0,j0);\n\n            Scalar v = bdmSM(i - i0, j - j0);\n            Scalar vd = d[GET(i,j)];\n            VERIFY_IS_EQUAL(vd, v);\n            VERIFY_IS_EQUAL(vd, bdmLM(GET(i-i0, j-j0)));\n        }\n    }\n\n    // Testing loadPacket\n    for(int i = 0; i < szm - minSize; i++)\n    {\n        for(int j = 0; j < szn - minSize; j++)\n        {\n            Packet pktBDM = bdm.template loadPacket<Packet>(i,j);\n            Packet pktD = internal::ploadu<Packet>(d + GET(i,j));\n\n            compare<Scalar, Packet>(pktBDM, pktD);\n        }\n    }\n\n    // Testing gatherPacket\n    Scalar *buff = new Scalar[packetSize];\n    for(int i = 0; i < szm - minSize; i++)\n    {\n        for(int j = 0; j < szn - minSize; j++)\n        {\n            Packet p = bdm.template gatherPacket<Packet>(i,j);\n            internal::pstoreu<Scalar, Packet>(buff, p);\n\n            for(int k = 0; k < packetSize; k++)\n            {\n                VERIFY_IS_EQUAL(d[SCATTER(i,j,k)], buff[k]);\n            }\n\n        }\n    }\n    delete[] buff;\n\n    // Testing scatterPacket\n    for(int i = 0; i < szm - minSize; i++)\n    {\n        for(int j = 0; j < szn - minSize; j++)\n        {\n            Packet p = internal::pset1<Packet>(static_cast<Scalar>(1));\n            bdm.template scatterPacket<Packet>(i,j,p);\n            for(int k = 0; k < packetSize; k++)\n            {\n                VERIFY_IS_EQUAL(d[SCATTER(i,j,k)], static_cast<Scalar>(1));\n            }\n        }\n    }\n\n    //Testing storePacketBlock\n    internal::PacketBlock<Packet, BlockSize> block;\n\n    PacketBlockSet<Scalar, StorageOrder, BlockSize> pbs;\n    pbs.setPacketBlock(block, static_cast<Scalar>(2));\n\n    for(int i = 0; i < szm - minSize; i++)\n    {\n        for(int j = 0; j < szn - minSize; j++)\n        {\n            bdm.template storePacketBlock<Packet, BlockSize>(i, j, block);\n\n            pbs.comparePacketBlock(d, i, j, stride, block);\n        }\n    }\n\n    delete[] d;\n}\n\ntemplate<typename Scalar>\nvoid run_test()\n{\n    run_bdmp_spec_1<Scalar, RowMajor, 1>();\n    run_bdmp_spec_1<Scalar, ColMajor, 1>();\n    run_bdmp_spec_1<Scalar, RowMajor, 2>();\n    run_bdmp_spec_1<Scalar, ColMajor, 2>();\n    run_bdmp_spec_1<Scalar, RowMajor, 4>();\n    run_bdmp_spec_1<Scalar, ColMajor, 4>();\n    run_bdmp_spec_1<Scalar, RowMajor, 8>();\n    run_bdmp_spec_1<Scalar, ColMajor, 8>();\n    run_bdmp_spec_1<Scalar, RowMajor, 16>();\n    run_bdmp_spec_1<Scalar, ColMajor, 16>();\n}\n\nEIGEN_DECLARE_TEST(blasutil)\n{\n    for(int i = 0; i < g_repeat; i++)\n    {\n        CALL_SUBTEST_1(run_test<numext::int8_t>());\n        CALL_SUBTEST_2(run_test<numext::int16_t>());\n        CALL_SUBTEST_3(run_test<numext::int32_t>());\n\n// TODO: Replace this by a call to numext::int64_t as soon as we have a way to\n// detect the typedef for int64_t on all platforms\n#if EIGEN_HAS_CXX11\n        CALL_SUBTEST_4(run_test<signed long long>());\n#else\n        CALL_SUBTEST_4(run_test<signed long>());\n#endif\n\n        CALL_SUBTEST_5(run_test<float_t>());\n        CALL_SUBTEST_6(run_test<double_t>());\n        CALL_SUBTEST_7(run_test<std::complex<float> >());\n        CALL_SUBTEST_8(run_test<std::complex<double> >());\n    }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/block.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_STATIC_ASSERT // otherwise we fail at compile time on unused paths\n#include \"main.h\"\n\ntemplate<typename MatrixType, typename Index, typename Scalar>\ntypename Eigen::internal::enable_if<!NumTraits<typename MatrixType::Scalar>::IsComplex,typename MatrixType::Scalar>::type\nblock_real_only(const MatrixType &m1, Index r1, Index r2, Index c1, Index c2, const Scalar& s1) {\n  // check cwise-Functions:\n  VERIFY_IS_APPROX(m1.row(r1).cwiseMax(s1), m1.cwiseMax(s1).row(r1));\n  VERIFY_IS_APPROX(m1.col(c1).cwiseMin(s1), m1.cwiseMin(s1).col(c1));\n\n  VERIFY_IS_APPROX(m1.block(r1,c1,r2-r1+1,c2-c1+1).cwiseMin(s1), m1.cwiseMin(s1).block(r1,c1,r2-r1+1,c2-c1+1));\n  VERIFY_IS_APPROX(m1.block(r1,c1,r2-r1+1,c2-c1+1).cwiseMax(s1), m1.cwiseMax(s1).block(r1,c1,r2-r1+1,c2-c1+1));\n  \n  return Scalar(0);\n}\n\ntemplate<typename MatrixType, typename Index, typename Scalar>\ntypename Eigen::internal::enable_if<NumTraits<typename MatrixType::Scalar>::IsComplex,typename MatrixType::Scalar>::type\nblock_real_only(const MatrixType &, Index, Index, Index, Index, const Scalar&) {\n  return Scalar(0);\n}\n\n// Check at compile-time that T1==T2, and at runtime-time that a==b\ntemplate<typename T1,typename T2>\ntypename internal::enable_if<internal::is_same<T1,T2>::value,bool>::type\nis_same_block(const T1& a, const T2& b)\n{\n  return a.isApprox(b);\n}\n\ntemplate<typename MatrixType> void block(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n  typedef Matrix<Scalar, 1, MatrixType::ColsAtCompileTime> RowVectorType;\n  typedef Matrix<Scalar, Dynamic, Dynamic, MatrixType::IsRowMajor?RowMajor:ColMajor> DynamicMatrixType;\n  typedef Matrix<Scalar, Dynamic, 1> DynamicVectorType;\n  \n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m1_copy = m1,\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols),\n             ones = MatrixType::Ones(rows, cols);\n  VectorType v1 = VectorType::Random(rows);\n\n  Scalar s1 = internal::random<Scalar>();\n\n  Index r1 = internal::random<Index>(0,rows-1);\n  Index r2 = internal::random<Index>(r1,rows-1);\n  Index c1 = internal::random<Index>(0,cols-1);\n  Index c2 = internal::random<Index>(c1,cols-1);\n\n  block_real_only(m1, r1, r2, c1, c1, s1);\n\n  //check row() and col()\n  VERIFY_IS_EQUAL(m1.col(c1).transpose(), m1.transpose().row(c1));\n  //check operator(), both constant and non-constant, on row() and col()\n  m1 = m1_copy;\n  m1.row(r1) += s1 * m1_copy.row(r2);\n  VERIFY_IS_APPROX(m1.row(r1), m1_copy.row(r1) + s1 * m1_copy.row(r2));\n  // check nested block xpr on lhs\n  m1.row(r1).row(0) += s1 * m1_copy.row(r2);\n  VERIFY_IS_APPROX(m1.row(r1), m1_copy.row(r1) + Scalar(2) * s1 * m1_copy.row(r2));\n  m1 = m1_copy;\n  m1.col(c1) += s1 * m1_copy.col(c2);\n  VERIFY_IS_APPROX(m1.col(c1), m1_copy.col(c1) + s1 * m1_copy.col(c2));\n  m1.col(c1).col(0) += s1 * m1_copy.col(c2);\n  VERIFY_IS_APPROX(m1.col(c1), m1_copy.col(c1) + Scalar(2) * s1 * m1_copy.col(c2));\n  \n  \n  //check block()\n  Matrix<Scalar,Dynamic,Dynamic> b1(1,1); b1(0,0) = m1(r1,c1);\n\n  RowVectorType br1(m1.block(r1,0,1,cols));\n  VectorType bc1(m1.block(0,c1,rows,1));\n  VERIFY_IS_EQUAL(b1, m1.block(r1,c1,1,1));\n  VERIFY_IS_EQUAL(m1.row(r1), br1);\n  VERIFY_IS_EQUAL(m1.col(c1), bc1);\n  //check operator(), both constant and non-constant, on block()\n  m1.block(r1,c1,r2-r1+1,c2-c1+1) = s1 * m2.block(0, 0, r2-r1+1,c2-c1+1);\n  m1.block(r1,c1,r2-r1+1,c2-c1+1)(r2-r1,c2-c1) = m2.block(0, 0, r2-r1+1,c2-c1+1)(0,0);\n\n  const Index BlockRows = 2;\n  const Index BlockCols = 5;\n\n  if (rows>=5 && cols>=8)\n  {\n    // test fixed block() as lvalue\n    m1.template block<BlockRows,BlockCols>(1,1) *= s1;\n    // test operator() on fixed block() both as constant and non-constant\n    m1.template block<BlockRows,BlockCols>(1,1)(0, 3) = m1.template block<2,5>(1,1)(1,2);\n    // check that fixed block() and block() agree\n    Matrix<Scalar,Dynamic,Dynamic> b = m1.template block<BlockRows,BlockCols>(3,3);\n    VERIFY_IS_EQUAL(b, m1.block(3,3,BlockRows,BlockCols));\n\n    // same tests with mixed fixed/dynamic size\n    m1.template block<BlockRows,Dynamic>(1,1,BlockRows,BlockCols) *= s1;\n    m1.template block<BlockRows,Dynamic>(1,1,BlockRows,BlockCols)(0,3) = m1.template block<2,5>(1,1)(1,2);\n    Matrix<Scalar,Dynamic,Dynamic> b2 = m1.template block<Dynamic,BlockCols>(3,3,2,5);\n    VERIFY_IS_EQUAL(b2, m1.block(3,3,BlockRows,BlockCols));\n\n    VERIFY(is_same_block(m1.block(3,3,BlockRows,BlockCols), m1.block(3,3,fix<Dynamic>(BlockRows),fix<Dynamic>(BlockCols))));\n    VERIFY(is_same_block(m1.template block<BlockRows,Dynamic>(1,1,BlockRows,BlockCols), m1.block(1,1,fix<BlockRows>,BlockCols)));\n    VERIFY(is_same_block(m1.template block<BlockRows,BlockCols>(1,1,BlockRows,BlockCols), m1.block(1,1,fix<BlockRows>(),fix<BlockCols>)));\n    VERIFY(is_same_block(m1.template block<BlockRows,BlockCols>(1,1,BlockRows,BlockCols), m1.block(1,1,fix<BlockRows>,fix<BlockCols>(BlockCols))));\n  }\n\n  if (rows>2)\n  {\n    // test sub vectors\n    VERIFY_IS_EQUAL(v1.template head<2>(), v1.block(0,0,2,1));\n    VERIFY_IS_EQUAL(v1.template head<2>(), v1.head(2));\n    VERIFY_IS_EQUAL(v1.template head<2>(), v1.segment(0,2));\n    VERIFY_IS_EQUAL(v1.template head<2>(), v1.template segment<2>(0));\n    Index i = rows-2;\n    VERIFY_IS_EQUAL(v1.template tail<2>(), v1.block(i,0,2,1));\n    VERIFY_IS_EQUAL(v1.template tail<2>(), v1.tail(2));\n    VERIFY_IS_EQUAL(v1.template tail<2>(), v1.segment(i,2));\n    VERIFY_IS_EQUAL(v1.template tail<2>(), v1.template segment<2>(i));\n    i = internal::random<Index>(0,rows-2);\n    VERIFY_IS_EQUAL(v1.segment(i,2), v1.template segment<2>(i));\n  }\n\n  // stress some basic stuffs with block matrices\n  VERIFY(numext::real(ones.col(c1).sum()) == RealScalar(rows));\n  VERIFY(numext::real(ones.row(r1).sum()) == RealScalar(cols));\n\n  VERIFY(numext::real(ones.col(c1).dot(ones.col(c2))) == RealScalar(rows));\n  VERIFY(numext::real(ones.row(r1).dot(ones.row(r2))) == RealScalar(cols));\n  \n  // check that linear acccessors works on blocks\n  m1 = m1_copy;\n  if((MatrixType::Flags&RowMajorBit)==0)\n    VERIFY_IS_EQUAL(m1.leftCols(c1).coeff(r1+c1*rows), m1(r1,c1));\n  else\n    VERIFY_IS_EQUAL(m1.topRows(r1).coeff(c1+r1*cols), m1(r1,c1));\n  \n\n  // now test some block-inside-of-block.\n  \n  // expressions with direct access\n  VERIFY_IS_EQUAL( (m1.block(r1,c1,rows-r1,cols-c1).block(r2-r1,c2-c1,rows-r2,cols-c2)) , (m1.block(r2,c2,rows-r2,cols-c2)) );\n  VERIFY_IS_EQUAL( (m1.block(r1,c1,r2-r1+1,c2-c1+1).row(0)) , (m1.row(r1).segment(c1,c2-c1+1)) );\n  VERIFY_IS_EQUAL( (m1.block(r1,c1,r2-r1+1,c2-c1+1).col(0)) , (m1.col(c1).segment(r1,r2-r1+1)) );\n  VERIFY_IS_EQUAL( (m1.block(r1,c1,r2-r1+1,c2-c1+1).transpose().col(0)) , (m1.row(r1).segment(c1,c2-c1+1)).transpose() );\n  VERIFY_IS_EQUAL( (m1.transpose().block(c1,r1,c2-c1+1,r2-r1+1).col(0)) , (m1.row(r1).segment(c1,c2-c1+1)).transpose() );\n\n  // expressions without direct access\n  VERIFY_IS_APPROX( ((m1+m2).block(r1,c1,rows-r1,cols-c1).block(r2-r1,c2-c1,rows-r2,cols-c2)) , ((m1+m2).block(r2,c2,rows-r2,cols-c2)) );\n  VERIFY_IS_APPROX( ((m1+m2).block(r1,c1,r2-r1+1,c2-c1+1).row(0)) , ((m1+m2).row(r1).segment(c1,c2-c1+1)) );\n  VERIFY_IS_APPROX( ((m1+m2).block(r1,c1,r2-r1+1,c2-c1+1).row(0)) , ((m1+m2).eval().row(r1).segment(c1,c2-c1+1)) );\n  VERIFY_IS_APPROX( ((m1+m2).block(r1,c1,r2-r1+1,c2-c1+1).col(0)) , ((m1+m2).col(c1).segment(r1,r2-r1+1)) );\n  VERIFY_IS_APPROX( ((m1+m2).block(r1,c1,r2-r1+1,c2-c1+1).transpose().col(0)) , ((m1+m2).row(r1).segment(c1,c2-c1+1)).transpose() );\n  VERIFY_IS_APPROX( ((m1+m2).transpose().block(c1,r1,c2-c1+1,r2-r1+1).col(0)) , ((m1+m2).row(r1).segment(c1,c2-c1+1)).transpose() );\n  VERIFY_IS_APPROX( ((m1+m2).template block<Dynamic,1>(r1,c1,r2-r1+1,1)) , ((m1+m2).eval().col(c1).eval().segment(r1,r2-r1+1)) );\n  VERIFY_IS_APPROX( ((m1+m2).template block<1,Dynamic>(r1,c1,1,c2-c1+1)) , ((m1+m2).eval().row(r1).eval().segment(c1,c2-c1+1)) );\n  VERIFY_IS_APPROX( ((m1+m2).transpose().template block<1,Dynamic>(c1,r1,1,r2-r1+1)) , ((m1+m2).eval().col(c1).eval().segment(r1,r2-r1+1)).transpose() );\n  VERIFY_IS_APPROX( (m1+m2).row(r1).eval(), (m1+m2).eval().row(r1) );\n  VERIFY_IS_APPROX( (m1+m2).adjoint().col(r1).eval(), (m1+m2).adjoint().eval().col(r1) );\n  VERIFY_IS_APPROX( (m1+m2).adjoint().row(c1).eval(), (m1+m2).adjoint().eval().row(c1) );\n  VERIFY_IS_APPROX( (m1*1).row(r1).segment(c1,c2-c1+1).eval(), m1.row(r1).eval().segment(c1,c2-c1+1).eval() );\n  VERIFY_IS_APPROX( m1.col(c1).reverse().segment(r1,r2-r1+1).eval(),m1.col(c1).reverse().eval().segment(r1,r2-r1+1).eval() );\n\n  VERIFY_IS_APPROX( (m1*1).topRows(r1),  m1.topRows(r1) );\n  VERIFY_IS_APPROX( (m1*1).leftCols(c1), m1.leftCols(c1) );\n  VERIFY_IS_APPROX( (m1*1).transpose().topRows(c1), m1.transpose().topRows(c1) );\n  VERIFY_IS_APPROX( (m1*1).transpose().leftCols(r1), m1.transpose().leftCols(r1) );\n  VERIFY_IS_APPROX( (m1*1).transpose().middleRows(c1,c2-c1+1), m1.transpose().middleRows(c1,c2-c1+1) );\n  VERIFY_IS_APPROX( (m1*1).transpose().middleCols(r1,r2-r1+1), m1.transpose().middleCols(r1,r2-r1+1) );\n\n  // evaluation into plain matrices from expressions with direct access (stress MapBase)\n  DynamicMatrixType dm;\n  DynamicVectorType dv;\n  dm.setZero();\n  dm = m1.block(r1,c1,rows-r1,cols-c1).block(r2-r1,c2-c1,rows-r2,cols-c2);\n  VERIFY_IS_EQUAL(dm, (m1.block(r2,c2,rows-r2,cols-c2)));\n  dm.setZero();\n  dv.setZero();\n  dm = m1.block(r1,c1,r2-r1+1,c2-c1+1).row(0).transpose();\n  dv = m1.row(r1).segment(c1,c2-c1+1);\n  VERIFY_IS_EQUAL(dv, dm);\n  dm.setZero();\n  dv.setZero();\n  dm = m1.col(c1).segment(r1,r2-r1+1);\n  dv = m1.block(r1,c1,r2-r1+1,c2-c1+1).col(0);\n  VERIFY_IS_EQUAL(dv, dm);\n  dm.setZero();\n  dv.setZero();\n  dm = m1.block(r1,c1,r2-r1+1,c2-c1+1).transpose().col(0);\n  dv = m1.row(r1).segment(c1,c2-c1+1);\n  VERIFY_IS_EQUAL(dv, dm);\n  dm.setZero();\n  dv.setZero();\n  dm = m1.row(r1).segment(c1,c2-c1+1).transpose();\n  dv = m1.transpose().block(c1,r1,c2-c1+1,r2-r1+1).col(0);\n  VERIFY_IS_EQUAL(dv, dm);\n\n  VERIFY_IS_EQUAL( (m1.template block<Dynamic,1>(1,0,0,1)), m1.block(1,0,0,1));\n  VERIFY_IS_EQUAL( (m1.template block<1,Dynamic>(0,1,1,0)), m1.block(0,1,1,0));\n  VERIFY_IS_EQUAL( ((m1*1).template block<Dynamic,1>(1,0,0,1)), m1.block(1,0,0,1));\n  VERIFY_IS_EQUAL( ((m1*1).template block<1,Dynamic>(0,1,1,0)), m1.block(0,1,1,0));\n\n  if (rows>=2 && cols>=2)\n  {\n    VERIFY_RAISES_ASSERT( m1 += m1.col(0) );\n    VERIFY_RAISES_ASSERT( m1 -= m1.col(0) );\n    VERIFY_RAISES_ASSERT( m1.array() *= m1.col(0).array() );\n    VERIFY_RAISES_ASSERT( m1.array() /= m1.col(0).array() );\n  }\n\n  VERIFY_IS_EQUAL( m1.template subVector<Horizontal>(r1), m1.row(r1) );\n  VERIFY_IS_APPROX( (m1+m1).template subVector<Horizontal>(r1), (m1+m1).row(r1) );\n  VERIFY_IS_EQUAL( m1.template subVector<Vertical>(c1), m1.col(c1) );\n  VERIFY_IS_APPROX( (m1+m1).template subVector<Vertical>(c1), (m1+m1).col(c1) );\n  VERIFY_IS_EQUAL( m1.template subVectors<Horizontal>(), m1.rows() );\n  VERIFY_IS_EQUAL( m1.template subVectors<Vertical>(), m1.cols() );\n\n  if (rows>=2 || cols>=2) {\n    VERIFY_IS_EQUAL( int(m1.middleCols(0,0).IsRowMajor), int(m1.IsRowMajor) );\n    VERIFY_IS_EQUAL( m1.middleCols(0,0).outerSize(), m1.IsRowMajor ? rows : 0);\n    VERIFY_IS_EQUAL( m1.middleCols(0,0).innerSize(), m1.IsRowMajor ? 0 : rows);\n\n    VERIFY_IS_EQUAL( int(m1.middleRows(0,0).IsRowMajor), int(m1.IsRowMajor) );\n    VERIFY_IS_EQUAL( m1.middleRows(0,0).outerSize(), m1.IsRowMajor ? 0 : cols);\n    VERIFY_IS_EQUAL( m1.middleRows(0,0).innerSize(), m1.IsRowMajor ? cols : 0);\n  }\n}\n\n\ntemplate<typename MatrixType>\nvoid compare_using_data_and_stride(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n  Index size = m.size();\n  Index innerStride = m.innerStride();\n  Index outerStride = m.outerStride();\n  Index rowStride = m.rowStride();\n  Index colStride = m.colStride();\n  const typename MatrixType::Scalar* data = m.data();\n\n  for(int j=0;j<cols;++j)\n    for(int i=0;i<rows;++i)\n      VERIFY(m.coeff(i,j) == data[i*rowStride + j*colStride]);\n\n  if(!MatrixType::IsVectorAtCompileTime)\n  {\n    for(int j=0;j<cols;++j)\n      for(int i=0;i<rows;++i)\n        VERIFY(m.coeff(i,j) == data[(MatrixType::Flags&RowMajorBit)\n                                     ? i*outerStride + j*innerStride\n                                     : j*outerStride + i*innerStride]);\n  }\n\n  if(MatrixType::IsVectorAtCompileTime)\n  {\n    VERIFY(innerStride == int((&m.coeff(1))-(&m.coeff(0))));\n    for (int i=0;i<size;++i)\n      VERIFY(m.coeff(i) == data[i*innerStride]);\n  }\n}\n\ntemplate<typename MatrixType>\nvoid data_and_stride(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  Index r1 = internal::random<Index>(0,rows-1);\n  Index r2 = internal::random<Index>(r1,rows-1);\n  Index c1 = internal::random<Index>(0,cols-1);\n  Index c2 = internal::random<Index>(c1,cols-1);\n\n  MatrixType m1 = MatrixType::Random(rows, cols);\n  compare_using_data_and_stride(m1.block(r1, c1, r2-r1+1, c2-c1+1));\n  compare_using_data_and_stride(m1.transpose().block(c1, r1, c2-c1+1, r2-r1+1));\n  compare_using_data_and_stride(m1.row(r1));\n  compare_using_data_and_stride(m1.col(c1));\n  compare_using_data_and_stride(m1.row(r1).transpose());\n  compare_using_data_and_stride(m1.col(c1).transpose());\n}\n\nEIGEN_DECLARE_TEST(block)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( block(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_1( block(Matrix<float, 1, Dynamic>(internal::random(2,50))) );\n    CALL_SUBTEST_1( block(Matrix<float, Dynamic, 1>(internal::random(2,50))) );\n    CALL_SUBTEST_2( block(Matrix4d()) );\n    CALL_SUBTEST_3( block(MatrixXcf(internal::random(2,50), internal::random(2,50))) );\n    CALL_SUBTEST_4( block(MatrixXi(internal::random(2,50), internal::random(2,50))) );\n    CALL_SUBTEST_5( block(MatrixXcd(internal::random(2,50), internal::random(2,50))) );\n    CALL_SUBTEST_6( block(MatrixXf(internal::random(2,50), internal::random(2,50))) );\n    CALL_SUBTEST_7( block(Matrix<int,Dynamic,Dynamic,RowMajor>(internal::random(2,50), internal::random(2,50))) );\n\n    CALL_SUBTEST_8( block(Matrix<float,Dynamic,4>(3, 4)) );\n\n#ifndef EIGEN_DEFAULT_TO_ROW_MAJOR\n    CALL_SUBTEST_6( data_and_stride(MatrixXf(internal::random(5,50), internal::random(5,50))) );\n    CALL_SUBTEST_7( data_and_stride(Matrix<int,Dynamic,Dynamic,RowMajor>(internal::random(5,50), internal::random(5,50))) );\n#endif\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/boostmultiprec.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <sstream>\n\n#ifdef EIGEN_TEST_MAX_SIZE\n#undef EIGEN_TEST_MAX_SIZE\n#endif\n\n#define EIGEN_TEST_MAX_SIZE 50\n\n#ifdef EIGEN_TEST_PART_1\n#include \"cholesky.cpp\"\n#endif\n\n#ifdef EIGEN_TEST_PART_2\n#include \"lu.cpp\"\n#endif\n\n#ifdef EIGEN_TEST_PART_3\n#include \"qr.cpp\"\n#endif\n\n#ifdef EIGEN_TEST_PART_4\n#include \"qr_colpivoting.cpp\"\n#endif\n\n#ifdef EIGEN_TEST_PART_5\n#include \"qr_fullpivoting.cpp\"\n#endif\n\n#ifdef EIGEN_TEST_PART_6\n#include \"eigensolver_selfadjoint.cpp\"\n#endif\n\n#ifdef EIGEN_TEST_PART_7\n#include \"eigensolver_generic.cpp\"\n#endif\n\n#ifdef EIGEN_TEST_PART_8\n#include \"eigensolver_generalized_real.cpp\"\n#endif\n\n#ifdef EIGEN_TEST_PART_9\n#include \"jacobisvd.cpp\"\n#endif\n\n#ifdef EIGEN_TEST_PART_10\n#include \"bdcsvd.cpp\"\n#endif\n\n#ifdef EIGEN_TEST_PART_11\n#include \"simplicial_cholesky.cpp\"\n#endif\n\n#include <Eigen/Dense>\n\n#undef min\n#undef max\n#undef isnan\n#undef isinf\n#undef isfinite\n#undef I\n\n#include <boost/serialization/nvp.hpp>\n#include <boost/multiprecision/cpp_dec_float.hpp>\n#include <boost/multiprecision/number.hpp>\n#include <boost/math/special_functions.hpp>\n#include <boost/math/complex.hpp>\n\nnamespace mp = boost::multiprecision;\ntypedef mp::number<mp::cpp_dec_float<100>, mp::et_on> Real;\n\nnamespace Eigen {\n  template<> struct NumTraits<Real> : GenericNumTraits<Real> {\n    static inline Real dummy_precision() { return 1e-50; }\n  };\n\n  template<typename T1,typename T2,typename T3,typename T4,typename T5>\n  struct NumTraits<boost::multiprecision::detail::expression<T1,T2,T3,T4,T5> > : NumTraits<Real> {};\n\n  template<>\n  Real test_precision<Real>() { return 1e-50; }\n\n  // needed in C++93 mode where number does not support explicit cast.\n  namespace internal {\n    template<typename NewType>\n    struct cast_impl<Real,NewType> {\n      static inline NewType run(const Real& x) {\n        return x.template convert_to<NewType>();\n      }\n    };\n\n    template<>\n    struct cast_impl<Real,std::complex<Real> > {\n      static inline std::complex<Real>  run(const Real& x) {\n        return std::complex<Real>(x);\n      }\n    };\n  }\n}\n\nnamespace boost {\nnamespace multiprecision {\n  // to make ADL works as expected:\n  using boost::math::isfinite;\n  using boost::math::isnan;\n  using boost::math::isinf;\n  using boost::math::copysign;\n  using boost::math::hypot;\n\n  // The following is needed for std::complex<Real>:\n  Real fabs(const Real& a) { return abs EIGEN_NOT_A_MACRO (a); }\n  Real fmax(const Real& a, const Real& b) { using std::max; return max(a,b); }\n\n  // some specialization for the unit tests:\n  inline bool test_isMuchSmallerThan(const Real& a, const Real& b) {\n    return internal::isMuchSmallerThan(a, b, test_precision<Real>());\n  }\n\n  inline bool test_isApprox(const Real& a, const Real& b) {\n    return internal::isApprox(a, b, test_precision<Real>());\n  }\n\n  inline bool test_isApproxOrLessThan(const Real& a, const Real& b) {\n    return internal::isApproxOrLessThan(a, b, test_precision<Real>());\n  }\n\n  Real get_test_precision(const Real&) {\n    return test_precision<Real>();\n  }\n\n  Real test_relative_error(const Real &a, const Real &b) {\n    using Eigen::numext::abs2;\n    return sqrt(abs2<Real>(a-b)/Eigen::numext::mini<Real>(abs2(a),abs2(b)));\n  }\n}\n}\n\nnamespace Eigen {\n\n}\n\nEIGEN_DECLARE_TEST(boostmultiprec)\n{\n  typedef Matrix<Real,Dynamic,Dynamic> Mat;\n  typedef Matrix<std::complex<Real>,Dynamic,Dynamic> MatC;\n\n  std::cout << \"NumTraits<Real>::epsilon()         = \" << NumTraits<Real>::epsilon() << std::endl;\n  std::cout << \"NumTraits<Real>::dummy_precision() = \" << NumTraits<Real>::dummy_precision() << std::endl;\n  std::cout << \"NumTraits<Real>::lowest()          = \" << NumTraits<Real>::lowest() << std::endl;\n  std::cout << \"NumTraits<Real>::highest()         = \" << NumTraits<Real>::highest() << std::endl;\n  std::cout << \"NumTraits<Real>::digits10()        = \" << NumTraits<Real>::digits10() << std::endl;\n\n  // check stream output\n  {\n    Mat A(10,10);\n    A.setRandom();\n    std::stringstream ss;\n    ss << A;\n  }\n  {\n    MatC A(10,10);\n    A.setRandom();\n    std::stringstream ss;\n    ss << A;\n  }\n\n  for(int i = 0; i < g_repeat; i++) {\n    int s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE);\n\n    CALL_SUBTEST_1( cholesky(Mat(s,s)) );\n\n    CALL_SUBTEST_2( lu_non_invertible<Mat>() );\n    CALL_SUBTEST_2( lu_invertible<Mat>() );\n    CALL_SUBTEST_2( lu_non_invertible<MatC>() );\n    CALL_SUBTEST_2( lu_invertible<MatC>() );\n\n    CALL_SUBTEST_3( qr(Mat(internal::random<int>(1,EIGEN_TEST_MAX_SIZE),internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_3( qr_invertible<Mat>() );\n\n    CALL_SUBTEST_4( qr<Mat>() );\n    CALL_SUBTEST_4( cod<Mat>() );\n    CALL_SUBTEST_4( qr_invertible<Mat>() );\n\n    CALL_SUBTEST_5( qr<Mat>() );\n    CALL_SUBTEST_5( qr_invertible<Mat>() );\n\n    CALL_SUBTEST_6( selfadjointeigensolver(Mat(s,s)) );\n\n    CALL_SUBTEST_7( eigensolver(Mat(s,s)) );\n\n    CALL_SUBTEST_8( generalized_eigensolver_real(Mat(s,s)) );\n\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n  }\n\n  CALL_SUBTEST_9(( jacobisvd(Mat(internal::random<int>(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE), internal::random<int>(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/2))) ));\n  CALL_SUBTEST_10(( bdcsvd(Mat(internal::random<int>(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE), internal::random<int>(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/2))) ));\n\n  CALL_SUBTEST_11(( test_simplicial_cholesky_T<Real,int,ColMajor>() ));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/bug1213.cpp",
    "content": "\n// This anonymous enum is essential to trigger the linking issue\nenum {\n  Foo\n};\n\n#include \"bug1213.h\"\n\nbool bug1213_1(const Eigen::Vector3f& x)\n{\n  return bug1213_2(x);\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/bug1213.h",
    "content": "\n#include <Eigen/Core>\n\ntemplate<typename T, int dim>\nbool bug1213_2(const Eigen::Matrix<T,dim,1>& x);\n\nbool bug1213_1(const Eigen::Vector3f& x);\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/bug1213_main.cpp",
    "content": "\n// This is a regression unit regarding a weird linking issue with gcc.\n\n#include \"bug1213.h\"\n\nint main()\n{\n  return 0;\n}\n\n\ntemplate<typename T, int dim>\nbool bug1213_2(const Eigen::Matrix<T,dim,1>& )\n{\n  return true;\n}\n\ntemplate bool bug1213_2<float,3>(const Eigen::Vector3f&);\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/cholesky.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define TEST_ENABLE_TEMPORARY_TRACKING\n\n#include \"main.h\"\n#include <Eigen/Cholesky>\n#include <Eigen/QR>\n#include \"solverbase.h\"\n\ntemplate<typename MatrixType, int UpLo>\ntypename MatrixType::RealScalar matrix_l1_norm(const MatrixType& m) {\n  if(m.cols()==0) return typename MatrixType::RealScalar(0);\n  MatrixType symm = m.template selfadjointView<UpLo>();\n  return symm.cwiseAbs().colwise().sum().maxCoeff();\n}\n\ntemplate<typename MatrixType,template <typename,int> class CholType> void test_chol_update(const MatrixType& symm)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n\n  MatrixType symmLo = symm.template triangularView<Lower>();\n  MatrixType symmUp = symm.template triangularView<Upper>();\n  MatrixType symmCpy = symm;\n\n  CholType<MatrixType,Lower> chollo(symmLo);\n  CholType<MatrixType,Upper> cholup(symmUp);\n\n  for (int k=0; k<10; ++k)\n  {\n    VectorType vec = VectorType::Random(symm.rows());\n    RealScalar sigma = internal::random<RealScalar>();\n    symmCpy += sigma * vec * vec.adjoint();\n\n    // we are doing some downdates, so it might be the case that the matrix is not SPD anymore\n    CholType<MatrixType,Lower> chol(symmCpy);\n    if(chol.info()!=Success)\n      break;\n\n    chollo.rankUpdate(vec, sigma);\n    VERIFY_IS_APPROX(symmCpy, chollo.reconstructedMatrix());\n\n    cholup.rankUpdate(vec, sigma);\n    VERIFY_IS_APPROX(symmCpy, cholup.reconstructedMatrix());\n  }\n}\n\ntemplate<typename MatrixType> void cholesky(const MatrixType& m)\n{\n  /* this test covers the following files:\n     LLT.h LDLT.h\n  */\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> SquareMatrixType;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n\n  MatrixType a0 = MatrixType::Random(rows,cols);\n  VectorType vecB = VectorType::Random(rows), vecX(rows);\n  MatrixType matB = MatrixType::Random(rows,cols), matX(rows,cols);\n  SquareMatrixType symm =  a0 * a0.adjoint();\n  // let's make sure the matrix is not singular or near singular\n  for (int k=0; k<3; ++k)\n  {\n    MatrixType a1 = MatrixType::Random(rows,cols);\n    symm += a1 * a1.adjoint();\n  }\n\n  {\n    STATIC_CHECK(( internal::is_same<typename LLT<MatrixType,Lower>::StorageIndex,int>::value ));\n    STATIC_CHECK(( internal::is_same<typename LLT<MatrixType,Upper>::StorageIndex,int>::value ));\n\n    SquareMatrixType symmUp = symm.template triangularView<Upper>();\n    SquareMatrixType symmLo = symm.template triangularView<Lower>();\n\n    LLT<SquareMatrixType,Lower> chollo(symmLo);\n    VERIFY_IS_APPROX(symm, chollo.reconstructedMatrix());\n\n    check_solverbase<VectorType, VectorType>(symm, chollo, rows, rows, 1);\n    check_solverbase<MatrixType, MatrixType>(symm, chollo, rows, cols, rows);\n\n    const MatrixType symmLo_inverse = chollo.solve(MatrixType::Identity(rows,cols));\n    RealScalar rcond = (RealScalar(1) / matrix_l1_norm<MatrixType, Lower>(symmLo)) /\n                             matrix_l1_norm<MatrixType, Lower>(symmLo_inverse);\n    RealScalar rcond_est = chollo.rcond();\n    // Verify that the estimated condition number is within a factor of 10 of the\n    // truth.\n    VERIFY(rcond_est >= rcond / 10 && rcond_est <= rcond * 10);\n\n    // test the upper mode\n    LLT<SquareMatrixType,Upper> cholup(symmUp);\n    VERIFY_IS_APPROX(symm, cholup.reconstructedMatrix());\n    vecX = cholup.solve(vecB);\n    VERIFY_IS_APPROX(symm * vecX, vecB);\n    matX = cholup.solve(matB);\n    VERIFY_IS_APPROX(symm * matX, matB);\n\n    // Verify that the estimated condition number is within a factor of 10 of the\n    // truth.\n    const MatrixType symmUp_inverse = cholup.solve(MatrixType::Identity(rows,cols));\n    rcond = (RealScalar(1) / matrix_l1_norm<MatrixType, Upper>(symmUp)) /\n                             matrix_l1_norm<MatrixType, Upper>(symmUp_inverse);\n    rcond_est = cholup.rcond();\n    VERIFY(rcond_est >= rcond / 10 && rcond_est <= rcond * 10);\n\n\n    MatrixType neg = -symmLo;\n    chollo.compute(neg);\n    VERIFY(neg.size()==0 || chollo.info()==NumericalIssue);\n\n    VERIFY_IS_APPROX(MatrixType(chollo.matrixL().transpose().conjugate()), MatrixType(chollo.matrixU()));\n    VERIFY_IS_APPROX(MatrixType(chollo.matrixU().transpose().conjugate()), MatrixType(chollo.matrixL()));\n    VERIFY_IS_APPROX(MatrixType(cholup.matrixL().transpose().conjugate()), MatrixType(cholup.matrixU()));\n    VERIFY_IS_APPROX(MatrixType(cholup.matrixU().transpose().conjugate()), MatrixType(cholup.matrixL()));\n\n    // test some special use cases of SelfCwiseBinaryOp:\n    MatrixType m1 = MatrixType::Random(rows,cols), m2(rows,cols);\n    m2 = m1;\n    m2 += symmLo.template selfadjointView<Lower>().llt().solve(matB);\n    VERIFY_IS_APPROX(m2, m1 + symmLo.template selfadjointView<Lower>().llt().solve(matB));\n    m2 = m1;\n    m2 -= symmLo.template selfadjointView<Lower>().llt().solve(matB);\n    VERIFY_IS_APPROX(m2, m1 - symmLo.template selfadjointView<Lower>().llt().solve(matB));\n    m2 = m1;\n    m2.noalias() += symmLo.template selfadjointView<Lower>().llt().solve(matB);\n    VERIFY_IS_APPROX(m2, m1 + symmLo.template selfadjointView<Lower>().llt().solve(matB));\n    m2 = m1;\n    m2.noalias() -= symmLo.template selfadjointView<Lower>().llt().solve(matB);\n    VERIFY_IS_APPROX(m2, m1 - symmLo.template selfadjointView<Lower>().llt().solve(matB));\n  }\n\n  // LDLT\n  {\n    STATIC_CHECK(( internal::is_same<typename LDLT<MatrixType,Lower>::StorageIndex,int>::value ));\n    STATIC_CHECK(( internal::is_same<typename LDLT<MatrixType,Upper>::StorageIndex,int>::value ));\n\n    int sign = internal::random<int>()%2 ? 1 : -1;\n\n    if(sign == -1)\n    {\n      symm = -symm; // test a negative matrix\n    }\n\n    SquareMatrixType symmUp = symm.template triangularView<Upper>();\n    SquareMatrixType symmLo = symm.template triangularView<Lower>();\n\n    LDLT<SquareMatrixType,Lower> ldltlo(symmLo);\n    VERIFY(ldltlo.info()==Success);\n    VERIFY_IS_APPROX(symm, ldltlo.reconstructedMatrix());\n\n    check_solverbase<VectorType, VectorType>(symm, ldltlo, rows, rows, 1);\n    check_solverbase<MatrixType, MatrixType>(symm, ldltlo, rows, cols, rows);\n\n    const MatrixType symmLo_inverse = ldltlo.solve(MatrixType::Identity(rows,cols));\n    RealScalar rcond = (RealScalar(1) / matrix_l1_norm<MatrixType, Lower>(symmLo)) /\n                             matrix_l1_norm<MatrixType, Lower>(symmLo_inverse);\n    RealScalar rcond_est = ldltlo.rcond();\n    // Verify that the estimated condition number is within a factor of 10 of the\n    // truth.\n    VERIFY(rcond_est >= rcond / 10 && rcond_est <= rcond * 10);\n\n\n    LDLT<SquareMatrixType,Upper> ldltup(symmUp);\n    VERIFY(ldltup.info()==Success);\n    VERIFY_IS_APPROX(symm, ldltup.reconstructedMatrix());\n    vecX = ldltup.solve(vecB);\n    VERIFY_IS_APPROX(symm * vecX, vecB);\n    matX = ldltup.solve(matB);\n    VERIFY_IS_APPROX(symm * matX, matB);\n\n    // Verify that the estimated condition number is within a factor of 10 of the\n    // truth.\n    const MatrixType symmUp_inverse = ldltup.solve(MatrixType::Identity(rows,cols));\n    rcond = (RealScalar(1) / matrix_l1_norm<MatrixType, Upper>(symmUp)) /\n                             matrix_l1_norm<MatrixType, Upper>(symmUp_inverse);\n    rcond_est = ldltup.rcond();\n    VERIFY(rcond_est >= rcond / 10 && rcond_est <= rcond * 10);\n\n    VERIFY_IS_APPROX(MatrixType(ldltlo.matrixL().transpose().conjugate()), MatrixType(ldltlo.matrixU()));\n    VERIFY_IS_APPROX(MatrixType(ldltlo.matrixU().transpose().conjugate()), MatrixType(ldltlo.matrixL()));\n    VERIFY_IS_APPROX(MatrixType(ldltup.matrixL().transpose().conjugate()), MatrixType(ldltup.matrixU()));\n    VERIFY_IS_APPROX(MatrixType(ldltup.matrixU().transpose().conjugate()), MatrixType(ldltup.matrixL()));\n\n    if(MatrixType::RowsAtCompileTime==Dynamic)\n    {\n      // note : each inplace permutation requires a small temporary vector (mask)\n\n      // check inplace solve\n      matX = matB;\n      VERIFY_EVALUATION_COUNT(matX = ldltlo.solve(matX), 0);\n      VERIFY_IS_APPROX(matX, ldltlo.solve(matB).eval());\n\n\n      matX = matB;\n      VERIFY_EVALUATION_COUNT(matX = ldltup.solve(matX), 0);\n      VERIFY_IS_APPROX(matX, ldltup.solve(matB).eval());\n    }\n\n    // restore\n    if(sign == -1)\n      symm = -symm;\n\n    // check matrices coming from linear constraints with Lagrange multipliers\n    if(rows>=3)\n    {\n      SquareMatrixType A = symm;\n      Index c = internal::random<Index>(0,rows-2);\n      A.bottomRightCorner(c,c).setZero();\n      // Make sure a solution exists:\n      vecX.setRandom();\n      vecB = A * vecX;\n      vecX.setZero();\n      ldltlo.compute(A);\n      VERIFY_IS_APPROX(A, ldltlo.reconstructedMatrix());\n      vecX = ldltlo.solve(vecB);\n      VERIFY_IS_APPROX(A * vecX, vecB);\n    }\n\n    // check non-full rank matrices\n    if(rows>=3)\n    {\n      Index r = internal::random<Index>(1,rows-1);\n      Matrix<Scalar,Dynamic,Dynamic> a = Matrix<Scalar,Dynamic,Dynamic>::Random(rows,r);\n      SquareMatrixType A = a * a.adjoint();\n      // Make sure a solution exists:\n      vecX.setRandom();\n      vecB = A * vecX;\n      vecX.setZero();\n      ldltlo.compute(A);\n      VERIFY_IS_APPROX(A, ldltlo.reconstructedMatrix());\n      vecX = ldltlo.solve(vecB);\n      VERIFY_IS_APPROX(A * vecX, vecB);\n    }\n\n    // check matrices with a wide spectrum\n    if(rows>=3)\n    {\n      using std::pow;\n      using std::sqrt;\n      RealScalar s = (std::min)(16,std::numeric_limits<RealScalar>::max_exponent10/8);\n      Matrix<Scalar,Dynamic,Dynamic> a = Matrix<Scalar,Dynamic,Dynamic>::Random(rows,rows);\n      Matrix<RealScalar,Dynamic,1> d =  Matrix<RealScalar,Dynamic,1>::Random(rows);\n      for(Index k=0; k<rows; ++k)\n        d(k) = d(k)*pow(RealScalar(10),internal::random<RealScalar>(-s,s));\n      SquareMatrixType A = a * d.asDiagonal() * a.adjoint();\n      // Make sure a solution exists:\n      vecX.setRandom();\n      vecB = A * vecX;\n      vecX.setZero();\n      ldltlo.compute(A);\n      VERIFY_IS_APPROX(A, ldltlo.reconstructedMatrix());\n      vecX = ldltlo.solve(vecB);\n\n      if(ldltlo.vectorD().real().cwiseAbs().minCoeff()>RealScalar(0))\n      {\n        VERIFY_IS_APPROX(A * vecX,vecB);\n      }\n      else\n      {\n        RealScalar large_tol =  sqrt(test_precision<RealScalar>());\n        VERIFY((A * vecX).isApprox(vecB, large_tol));\n\n        ++g_test_level;\n        VERIFY_IS_APPROX(A * vecX,vecB);\n        --g_test_level;\n      }\n    }\n  }\n\n  // update/downdate\n  CALL_SUBTEST(( test_chol_update<SquareMatrixType,LLT>(symm)  ));\n  CALL_SUBTEST(( test_chol_update<SquareMatrixType,LDLT>(symm) ));\n}\n\ntemplate<typename MatrixType> void cholesky_cplx(const MatrixType& m)\n{\n  // classic test\n  cholesky(m);\n\n  // test mixing real/scalar types\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<RealScalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> RealMatrixType;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n\n  RealMatrixType a0 = RealMatrixType::Random(rows,cols);\n  VectorType vecB = VectorType::Random(rows), vecX(rows);\n  MatrixType matB = MatrixType::Random(rows,cols), matX(rows,cols);\n  RealMatrixType symm =  a0 * a0.adjoint();\n  // let's make sure the matrix is not singular or near singular\n  for (int k=0; k<3; ++k)\n  {\n    RealMatrixType a1 = RealMatrixType::Random(rows,cols);\n    symm += a1 * a1.adjoint();\n  }\n\n  {\n    RealMatrixType symmLo = symm.template triangularView<Lower>();\n\n    LLT<RealMatrixType,Lower> chollo(symmLo);\n    VERIFY_IS_APPROX(symm, chollo.reconstructedMatrix());\n\n    check_solverbase<VectorType, VectorType>(symm, chollo, rows, rows, 1);\n    //check_solverbase<MatrixType, MatrixType>(symm, chollo, rows, cols, rows);\n  }\n\n  // LDLT\n  {\n    int sign = internal::random<int>()%2 ? 1 : -1;\n\n    if(sign == -1)\n    {\n      symm = -symm; // test a negative matrix\n    }\n\n    RealMatrixType symmLo = symm.template triangularView<Lower>();\n\n    LDLT<RealMatrixType,Lower> ldltlo(symmLo);\n    VERIFY(ldltlo.info()==Success);\n    VERIFY_IS_APPROX(symm, ldltlo.reconstructedMatrix());\n\n    check_solverbase<VectorType, VectorType>(symm, ldltlo, rows, rows, 1);\n    //check_solverbase<MatrixType, MatrixType>(symm, ldltlo, rows, cols, rows);\n  }\n}\n\n// regression test for bug 241\ntemplate<typename MatrixType> void cholesky_bug241(const MatrixType& m)\n{\n  eigen_assert(m.rows() == 2 && m.cols() == 2);\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n\n  MatrixType matA;\n  matA << 1, 1, 1, 1;\n  VectorType vecB;\n  vecB << 1, 1;\n  VectorType vecX = matA.ldlt().solve(vecB);\n  VERIFY_IS_APPROX(matA * vecX, vecB);\n}\n\n// LDLT is not guaranteed to work for indefinite matrices, but happens to work fine if matrix is diagonal.\n// This test checks that LDLT reports correctly that matrix is indefinite.\n// See http://forum.kde.org/viewtopic.php?f=74&t=106942 and bug 736\ntemplate<typename MatrixType> void cholesky_definiteness(const MatrixType& m)\n{\n  eigen_assert(m.rows() == 2 && m.cols() == 2);\n  MatrixType mat;\n  LDLT<MatrixType> ldlt(2);\n\n  {\n    mat << 1, 0, 0, -1;\n    ldlt.compute(mat);\n    VERIFY(ldlt.info()==Success);\n    VERIFY(!ldlt.isNegative());\n    VERIFY(!ldlt.isPositive());\n    VERIFY_IS_APPROX(mat,ldlt.reconstructedMatrix());\n  }\n  {\n    mat << 1, 2, 2, 1;\n    ldlt.compute(mat);\n    VERIFY(ldlt.info()==Success);\n    VERIFY(!ldlt.isNegative());\n    VERIFY(!ldlt.isPositive());\n    VERIFY_IS_APPROX(mat,ldlt.reconstructedMatrix());\n  }\n  {\n    mat << 0, 0, 0, 0;\n    ldlt.compute(mat);\n    VERIFY(ldlt.info()==Success);\n    VERIFY(ldlt.isNegative());\n    VERIFY(ldlt.isPositive());\n    VERIFY_IS_APPROX(mat,ldlt.reconstructedMatrix());\n  }\n  {\n    mat << 0, 0, 0, 1;\n    ldlt.compute(mat);\n    VERIFY(ldlt.info()==Success);\n    VERIFY(!ldlt.isNegative());\n    VERIFY(ldlt.isPositive());\n    VERIFY_IS_APPROX(mat,ldlt.reconstructedMatrix());\n  }\n  {\n    mat << -1, 0, 0, 0;\n    ldlt.compute(mat);\n    VERIFY(ldlt.info()==Success);\n    VERIFY(ldlt.isNegative());\n    VERIFY(!ldlt.isPositive());\n    VERIFY_IS_APPROX(mat,ldlt.reconstructedMatrix());\n  }\n}\n\ntemplate<typename>\nvoid cholesky_faillure_cases()\n{\n  MatrixXd mat;\n  LDLT<MatrixXd> ldlt;\n\n  {\n    mat.resize(2,2);\n    mat << 0, 1, 1, 0;\n    ldlt.compute(mat);\n    VERIFY_IS_NOT_APPROX(mat,ldlt.reconstructedMatrix());\n    VERIFY(ldlt.info()==NumericalIssue);\n  }\n#if (!EIGEN_ARCH_i386) || defined(EIGEN_VECTORIZE_SSE2)\n  {\n    mat.resize(3,3);\n    mat << -1, -3, 3,\n           -3, -8.9999999999999999999, 1,\n            3, 1, 0;\n    ldlt.compute(mat);\n    VERIFY(ldlt.info()==NumericalIssue);\n    VERIFY_IS_NOT_APPROX(mat,ldlt.reconstructedMatrix());\n  }\n#endif\n  {\n    mat.resize(3,3);\n    mat <<  1, 2, 3,\n            2, 4, 1,\n            3, 1, 0;\n    ldlt.compute(mat);\n    VERIFY(ldlt.info()==NumericalIssue);\n    VERIFY_IS_NOT_APPROX(mat,ldlt.reconstructedMatrix());\n  }\n\n  {\n    mat.resize(8,8);\n    mat <<  0.1, 0, -0.1, 0, 0, 0, 1, 0,\n            0, 4.24667, 0, 2.00333, 0, 0, 0, 0,\n            -0.1, 0, 0.2, 0, -0.1, 0, 0, 0,\n            0, 2.00333, 0, 8.49333, 0, 2.00333, 0, 0,\n            0, 0, -0.1, 0, 0.1, 0, 0, 1,\n            0, 0, 0, 2.00333, 0, 4.24667, 0, 0,\n            1, 0, 0, 0, 0, 0, 0, 0,\n            0, 0, 0, 0, 1, 0, 0, 0;\n    ldlt.compute(mat);\n    VERIFY(ldlt.info()==NumericalIssue);\n    VERIFY_IS_NOT_APPROX(mat,ldlt.reconstructedMatrix());\n  }\n\n  // bug 1479\n  {\n    mat.resize(4,4);\n    mat <<  1, 2, 0, 1,\n            2, 4, 0, 2,\n            0, 0, 0, 1,\n            1, 2, 1, 1;\n    ldlt.compute(mat);\n    VERIFY(ldlt.info()==NumericalIssue);\n    VERIFY_IS_NOT_APPROX(mat,ldlt.reconstructedMatrix());\n  }\n}\n\ntemplate<typename MatrixType> void cholesky_verify_assert()\n{\n  MatrixType tmp;\n\n  LLT<MatrixType> llt;\n  VERIFY_RAISES_ASSERT(llt.matrixL())\n  VERIFY_RAISES_ASSERT(llt.matrixU())\n  VERIFY_RAISES_ASSERT(llt.solve(tmp))\n  VERIFY_RAISES_ASSERT(llt.transpose().solve(tmp))\n  VERIFY_RAISES_ASSERT(llt.adjoint().solve(tmp))\n  VERIFY_RAISES_ASSERT(llt.solveInPlace(tmp))\n\n  LDLT<MatrixType> ldlt;\n  VERIFY_RAISES_ASSERT(ldlt.matrixL())\n  VERIFY_RAISES_ASSERT(ldlt.transpositionsP())\n  VERIFY_RAISES_ASSERT(ldlt.vectorD())\n  VERIFY_RAISES_ASSERT(ldlt.isPositive())\n  VERIFY_RAISES_ASSERT(ldlt.isNegative())\n  VERIFY_RAISES_ASSERT(ldlt.solve(tmp))\n  VERIFY_RAISES_ASSERT(ldlt.transpose().solve(tmp))\n  VERIFY_RAISES_ASSERT(ldlt.adjoint().solve(tmp))\n  VERIFY_RAISES_ASSERT(ldlt.solveInPlace(tmp))\n}\n\nEIGEN_DECLARE_TEST(cholesky)\n{\n  int s = 0;\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( cholesky(Matrix<double,1,1>()) );\n    CALL_SUBTEST_3( cholesky(Matrix2d()) );\n    CALL_SUBTEST_3( cholesky_bug241(Matrix2d()) );\n    CALL_SUBTEST_3( cholesky_definiteness(Matrix2d()) );\n    CALL_SUBTEST_4( cholesky(Matrix3f()) );\n    CALL_SUBTEST_5( cholesky(Matrix4d()) );\n\n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE);\n    CALL_SUBTEST_2( cholesky(MatrixXd(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n\n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2);\n    CALL_SUBTEST_6( cholesky_cplx(MatrixXcd(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n  }\n  // empty matrix, regression test for Bug 785:\n  CALL_SUBTEST_2( cholesky(MatrixXd(0,0)) );\n\n  // This does not work yet:\n  // CALL_SUBTEST_2( cholesky(Matrix<double,0,0>()) );\n\n  CALL_SUBTEST_4( cholesky_verify_assert<Matrix3f>() );\n  CALL_SUBTEST_7( cholesky_verify_assert<Matrix3d>() );\n  CALL_SUBTEST_8( cholesky_verify_assert<MatrixXf>() );\n  CALL_SUBTEST_2( cholesky_verify_assert<MatrixXd>() );\n\n  // Test problem size constructors\n  CALL_SUBTEST_9( LLT<MatrixXf>(10) );\n  CALL_SUBTEST_9( LDLT<MatrixXf>(10) );\n\n  CALL_SUBTEST_2( cholesky_faillure_cases<void>() );\n\n  TEST_SET_BUT_UNUSED_VARIABLE(nb_temporaries)\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/cholmod_support.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS\n#include \"sparse_solver.h\"\n\n#include <Eigen/CholmodSupport>\n\ntemplate<typename SparseType> void test_cholmod_ST()\n{\n  CholmodDecomposition<SparseType, Lower> g_chol_colmajor_lower; g_chol_colmajor_lower.setMode(CholmodSupernodalLLt);\n  CholmodDecomposition<SparseType, Upper> g_chol_colmajor_upper; g_chol_colmajor_upper.setMode(CholmodSupernodalLLt);\n  CholmodDecomposition<SparseType, Lower> g_llt_colmajor_lower;  g_llt_colmajor_lower.setMode(CholmodSimplicialLLt);\n  CholmodDecomposition<SparseType, Upper> g_llt_colmajor_upper;  g_llt_colmajor_upper.setMode(CholmodSimplicialLLt);\n  CholmodDecomposition<SparseType, Lower> g_ldlt_colmajor_lower; g_ldlt_colmajor_lower.setMode(CholmodLDLt);\n  CholmodDecomposition<SparseType, Upper> g_ldlt_colmajor_upper; g_ldlt_colmajor_upper.setMode(CholmodLDLt);\n  \n  CholmodSupernodalLLT<SparseType, Lower> chol_colmajor_lower;\n  CholmodSupernodalLLT<SparseType, Upper> chol_colmajor_upper;\n  CholmodSimplicialLLT<SparseType, Lower> llt_colmajor_lower;\n  CholmodSimplicialLLT<SparseType, Upper> llt_colmajor_upper;\n  CholmodSimplicialLDLT<SparseType, Lower> ldlt_colmajor_lower;\n  CholmodSimplicialLDLT<SparseType, Upper> ldlt_colmajor_upper;\n\n  check_sparse_spd_solving(g_chol_colmajor_lower);\n  check_sparse_spd_solving(g_chol_colmajor_upper);\n  check_sparse_spd_solving(g_llt_colmajor_lower);\n  check_sparse_spd_solving(g_llt_colmajor_upper);\n  check_sparse_spd_solving(g_ldlt_colmajor_lower);\n  check_sparse_spd_solving(g_ldlt_colmajor_upper);\n  \n  check_sparse_spd_solving(chol_colmajor_lower);\n  check_sparse_spd_solving(chol_colmajor_upper);\n  check_sparse_spd_solving(llt_colmajor_lower);\n  check_sparse_spd_solving(llt_colmajor_upper);\n  check_sparse_spd_solving(ldlt_colmajor_lower);\n  check_sparse_spd_solving(ldlt_colmajor_upper);\n\n  check_sparse_spd_determinant(chol_colmajor_lower);\n  check_sparse_spd_determinant(chol_colmajor_upper);\n  check_sparse_spd_determinant(llt_colmajor_lower);\n  check_sparse_spd_determinant(llt_colmajor_upper);\n  check_sparse_spd_determinant(ldlt_colmajor_lower);\n  check_sparse_spd_determinant(ldlt_colmajor_upper);\n}\n\ntemplate<typename T, int flags, typename IdxType> void test_cholmod_T()\n{\n    test_cholmod_ST<SparseMatrix<T, flags, IdxType> >();\n}\n\nEIGEN_DECLARE_TEST(cholmod_support)\n{\n  CALL_SUBTEST_11( (test_cholmod_T<double              , ColMajor, int >()) );\n  CALL_SUBTEST_12( (test_cholmod_T<double              , ColMajor, long>()) );\n  CALL_SUBTEST_13( (test_cholmod_T<double              , RowMajor, int >()) );\n  CALL_SUBTEST_14( (test_cholmod_T<double              , RowMajor, long>()) );\n  CALL_SUBTEST_21( (test_cholmod_T<std::complex<double>, ColMajor, int >()) );\n  CALL_SUBTEST_22( (test_cholmod_T<std::complex<double>, ColMajor, long>()) );\n  // TODO complex row-major matrices do not work at the moment:\n  // CALL_SUBTEST_23( (test_cholmod_T<std::complex<double>, RowMajor, int >()) );\n  // CALL_SUBTEST_24( (test_cholmod_T<std::complex<double>, RowMajor, long>()) );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/commainitializer.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n\ntemplate<int M1, int M2, int N1, int N2>\nvoid test_blocks()\n{\n  Matrix<int, M1+M2, N1+N2> m_fixed;\n  MatrixXi m_dynamic(M1+M2, N1+N2);\n\n  Matrix<int, M1, N1> mat11; mat11.setRandom();\n  Matrix<int, M1, N2> mat12; mat12.setRandom();\n  Matrix<int, M2, N1> mat21; mat21.setRandom();\n  Matrix<int, M2, N2> mat22; mat22.setRandom();\n\n  MatrixXi matx11 = mat11, matx12 = mat12, matx21 = mat21, matx22 = mat22;\n\n  {\n    VERIFY_IS_EQUAL((m_fixed << mat11, mat12, mat21, matx22).finished(), (m_dynamic << mat11, matx12, mat21, matx22).finished());\n    VERIFY_IS_EQUAL((m_fixed.template topLeftCorner<M1,N1>()), mat11);\n    VERIFY_IS_EQUAL((m_fixed.template topRightCorner<M1,N2>()), mat12);\n    VERIFY_IS_EQUAL((m_fixed.template bottomLeftCorner<M2,N1>()), mat21);\n    VERIFY_IS_EQUAL((m_fixed.template bottomRightCorner<M2,N2>()), mat22);\n    VERIFY_IS_EQUAL((m_fixed << mat12, mat11, matx21, mat22).finished(), (m_dynamic << mat12, matx11, matx21, mat22).finished());\n  }\n\n  if(N1 > 0)\n  {\n    if(M1 > 0)\n    {\n      VERIFY_RAISES_ASSERT((m_fixed << mat11, mat12, mat11, mat21, mat22));\n    }\n    if(M2 > 0)\n    {\n      VERIFY_RAISES_ASSERT((m_fixed << mat11, mat12, mat21, mat21, mat22));\n    }\n  }\n  else\n  {\n    // allow insertion of zero-column blocks:\n    VERIFY_IS_EQUAL((m_fixed << mat11, mat12, mat11, mat11, mat21, mat21, mat22).finished(), (m_dynamic << mat12, mat22).finished());\n  }\n  if(M1 != M2)\n  {\n    VERIFY_RAISES_ASSERT((m_fixed << mat11, mat21, mat12, mat22));\n  }\n}\n\n\ntemplate<int depth, int N=0>\nstruct test_block_recursion\n{\n  static void run()\n  {\n    test_block_recursion<depth-1, N>::run();\n    test_block_recursion<depth-1, N + (1 << (depth-1))>::run();\n  }\n};\n\ntemplate<int N>\nstruct test_block_recursion<0,N>\n{\n  static void run() {\n    test_blocks<(N>>6)&3, (N>>4)&3, (N>>2)&3, N & 3>();\n  }\n};\n\nvoid test_basics() {\n  Matrix3d m3;\n  Matrix4d m4;\n\n  VERIFY_RAISES_ASSERT( (m3 << 1, 2, 3, 4, 5, 6, 7, 8) );\n  \n  #ifndef _MSC_VER\n  VERIFY_RAISES_ASSERT( (m3 << 1, 2, 3, 4, 5, 6, 7, 8, 9, 10) );\n  #endif\n\n  double data[] = {1, 2, 3, 4, 5, 6, 7, 8, 9};\n  Matrix3d ref = Map<Matrix<double,3,3,RowMajor> >(data);\n\n  m3 = Matrix3d::Random();\n  m3 << 1, 2, 3, 4, 5, 6, 7, 8, 9;\n  VERIFY_IS_APPROX(m3, ref );\n\n  Vector3d vec[3];\n  vec[0] << 1, 4, 7;\n  vec[1] << 2, 5, 8;\n  vec[2] << 3, 6, 9;\n  m3 = Matrix3d::Random();\n  m3 << vec[0], vec[1], vec[2];\n  VERIFY_IS_APPROX(m3, ref);\n\n  vec[0] << 1, 2, 3;\n  vec[1] << 4, 5, 6;\n  vec[2] << 7, 8, 9;\n  m3 = Matrix3d::Random();\n  m3 << vec[0].transpose(),\n        4, 5, 6,\n        vec[2].transpose();\n  VERIFY_IS_APPROX(m3, ref);\n}\n\nEIGEN_DECLARE_TEST(commainitializer)\n{\n\n  CALL_SUBTEST_1(test_basics());\n\n  // recursively test all block-sizes from 0 to 3:\n  CALL_SUBTEST_2(test_block_recursion<8>::run());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/conjugate_gradient.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"sparse_solver.h\"\n#include <Eigen/IterativeLinearSolvers>\n\ntemplate<typename T, typename I_> void test_conjugate_gradient_T()\n{\n  typedef SparseMatrix<T,0,I_> SparseMatrixType;\n  ConjugateGradient<SparseMatrixType, Lower      > cg_colmajor_lower_diag;\n  ConjugateGradient<SparseMatrixType, Upper      > cg_colmajor_upper_diag;\n  ConjugateGradient<SparseMatrixType, Lower|Upper> cg_colmajor_loup_diag;\n  ConjugateGradient<SparseMatrixType, Lower, IdentityPreconditioner> cg_colmajor_lower_I;\n  ConjugateGradient<SparseMatrixType, Upper, IdentityPreconditioner> cg_colmajor_upper_I;\n\n  CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_lower_diag)  );\n  CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_upper_diag)  );\n  CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_loup_diag)   );\n  CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_lower_I)     );\n  CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_upper_I)     );\n}\n\nEIGEN_DECLARE_TEST(conjugate_gradient)\n{\n  CALL_SUBTEST_1(( test_conjugate_gradient_T<double,int>() ));\n  CALL_SUBTEST_2(( test_conjugate_gradient_T<std::complex<double>, int>() ));\n  CALL_SUBTEST_3(( test_conjugate_gradient_T<double,long int>() ));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/conservative_resize.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/Core>\n#include \"AnnoyingScalar.h\"\n\nusing namespace Eigen;\n\ntemplate <typename Scalar, int Storage>\nvoid run_matrix_tests()\n{\n  typedef Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Storage> MatrixType;\n\n  MatrixType m, n;\n\n  // boundary cases ...\n  m = n = MatrixType::Random(50,50);\n  m.conservativeResize(1,50);\n  VERIFY_IS_APPROX(m, n.block(0,0,1,50));\n\n  m = n = MatrixType::Random(50,50);\n  m.conservativeResize(50,1);\n  VERIFY_IS_APPROX(m, n.block(0,0,50,1));\n\n  m = n = MatrixType::Random(50,50);\n  m.conservativeResize(50,50);\n  VERIFY_IS_APPROX(m, n.block(0,0,50,50));\n\n  // random shrinking ...\n  for (int i=0; i<25; ++i)\n  {\n    const Index rows = internal::random<Index>(1,50);\n    const Index cols = internal::random<Index>(1,50);\n    m = n = MatrixType::Random(50,50);\n    m.conservativeResize(rows,cols);\n    VERIFY_IS_APPROX(m, n.block(0,0,rows,cols));\n  }\n\n  // random growing with zeroing ...\n  for (int i=0; i<25; ++i)\n  {\n    const Index rows = internal::random<Index>(50,75);\n    const Index cols = internal::random<Index>(50,75);\n    m = n = MatrixType::Random(50,50);\n    m.conservativeResizeLike(MatrixType::Zero(rows,cols));\n    VERIFY_IS_APPROX(m.block(0,0,n.rows(),n.cols()), n);\n    VERIFY( rows<=50 || m.block(50,0,rows-50,cols).sum() == Scalar(0) );\n    VERIFY( cols<=50 || m.block(0,50,rows,cols-50).sum() == Scalar(0) );\n  }\n}\n\ntemplate <typename Scalar>\nvoid run_vector_tests()\n{\n  typedef Matrix<Scalar, 1, Eigen::Dynamic> VectorType;\n\n  VectorType m, n;\n\n  // boundary cases ...\n  m = n = VectorType::Random(50);\n  m.conservativeResize(1);\n  VERIFY_IS_APPROX(m, n.segment(0,1));\n\n  m = n = VectorType::Random(50);\n  m.conservativeResize(50);\n  VERIFY_IS_APPROX(m, n.segment(0,50));\n  \n  m = n = VectorType::Random(50);\n  m.conservativeResize(m.rows(),1);\n  VERIFY_IS_APPROX(m, n.segment(0,1));\n\n  m = n = VectorType::Random(50);\n  m.conservativeResize(m.rows(),50);\n  VERIFY_IS_APPROX(m, n.segment(0,50));\n\n  // random shrinking ...\n  for (int i=0; i<50; ++i)\n  {\n    const int size = internal::random<int>(1,50);\n    m = n = VectorType::Random(50);\n    m.conservativeResize(size);\n    VERIFY_IS_APPROX(m, n.segment(0,size));\n    \n    m = n = VectorType::Random(50);\n    m.conservativeResize(m.rows(), size);\n    VERIFY_IS_APPROX(m, n.segment(0,size));\n  }\n\n  // random growing with zeroing ...\n  for (int i=0; i<50; ++i)\n  {\n    const int size = internal::random<int>(50,100);\n    m = n = VectorType::Random(50);\n    m.conservativeResizeLike(VectorType::Zero(size));\n    VERIFY_IS_APPROX(m.segment(0,50), n);\n    VERIFY( size<=50 || m.segment(50,size-50).sum() == Scalar(0) );\n    \n    m = n = VectorType::Random(50);\n    m.conservativeResizeLike(Matrix<Scalar,Dynamic,Dynamic>::Zero(1,size));\n    VERIFY_IS_APPROX(m.segment(0,50), n);\n    VERIFY( size<=50 || m.segment(50,size-50).sum() == Scalar(0) );\n  }\n}\n\n// Basic memory leak check with a non-copyable scalar type\ntemplate<int> void noncopyable()\n{\n  typedef Eigen::Matrix<AnnoyingScalar,Dynamic,1> VectorType;\n  typedef Eigen::Matrix<AnnoyingScalar,Dynamic,Dynamic> MatrixType;\n\n  {\n#ifndef EIGEN_TEST_ANNOYING_SCALAR_DONT_THROW\n    AnnoyingScalar::dont_throw = true;\n#endif\n    int n = 50;\n    VectorType v0(n), v1(n);\n    MatrixType m0(n,n), m1(n,n), m2(n,n);\n    v0.setOnes(); v1.setOnes();\n    m0.setOnes(); m1.setOnes(); m2.setOnes();\n    VERIFY(m0==m1);\n    m0.conservativeResize(2*n,2*n);\n    VERIFY(m0.topLeftCorner(n,n) == m1);\n    \n    VERIFY(v0.head(n) == v1);\n    v0.conservativeResize(2*n);\n    VERIFY(v0.head(n) == v1);\n  }\n  VERIFY(AnnoyingScalar::instances==0 && \"global memory leak detected in noncopyable\");\n}\n\nEIGEN_DECLARE_TEST(conservative_resize)\n{\n  for(int i=0; i<g_repeat; ++i)\n  {\n    CALL_SUBTEST_1((run_matrix_tests<int, Eigen::RowMajor>()));\n    CALL_SUBTEST_1((run_matrix_tests<int, Eigen::ColMajor>()));\n    CALL_SUBTEST_2((run_matrix_tests<float, Eigen::RowMajor>()));\n    CALL_SUBTEST_2((run_matrix_tests<float, Eigen::ColMajor>()));\n    CALL_SUBTEST_3((run_matrix_tests<double, Eigen::RowMajor>()));\n    CALL_SUBTEST_3((run_matrix_tests<double, Eigen::ColMajor>()));\n    CALL_SUBTEST_4((run_matrix_tests<std::complex<float>, Eigen::RowMajor>()));\n    CALL_SUBTEST_4((run_matrix_tests<std::complex<float>, Eigen::ColMajor>()));\n    CALL_SUBTEST_5((run_matrix_tests<std::complex<double>, Eigen::RowMajor>()));\n    CALL_SUBTEST_5((run_matrix_tests<std::complex<double>, Eigen::ColMajor>()));\n    CALL_SUBTEST_1((run_matrix_tests<int, Eigen::RowMajor | Eigen::DontAlign>()));\n\n    CALL_SUBTEST_1((run_vector_tests<int>()));\n    CALL_SUBTEST_2((run_vector_tests<float>()));\n    CALL_SUBTEST_3((run_vector_tests<double>()));\n    CALL_SUBTEST_4((run_vector_tests<std::complex<float> >()));\n    CALL_SUBTEST_5((run_vector_tests<std::complex<double> >()));\n\n#ifndef EIGEN_TEST_ANNOYING_SCALAR_DONT_THROW\n    AnnoyingScalar::dont_throw = true;\n#endif\n    CALL_SUBTEST_6(( run_vector_tests<AnnoyingScalar>() ));\n    CALL_SUBTEST_6(( noncopyable<0>() ));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/constructor.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2017 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#define TEST_ENABLE_TEMPORARY_TRACKING\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> struct Wrapper\n{\n  MatrixType m_mat;\n  inline Wrapper(const MatrixType &x) : m_mat(x) {}\n  inline operator const MatrixType& () const { return m_mat; }\n  inline operator MatrixType& () { return m_mat; }\n};\n\nenum my_sizes { M = 12, N = 7};\n\ntemplate<typename MatrixType> void ctor_init1(const MatrixType& m)\n{\n  // Check logic in PlainObjectBase::_init1\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m0 = MatrixType::Random(rows,cols);\n\n  VERIFY_EVALUATION_COUNT( MatrixType m1(m0), 1);\n  VERIFY_EVALUATION_COUNT( MatrixType m2(m0+m0), 1);\n  VERIFY_EVALUATION_COUNT( MatrixType m2(m0.block(0,0,rows,cols)) , 1);\n\n  Wrapper<MatrixType> wrapper(m0);\n  VERIFY_EVALUATION_COUNT( MatrixType m3(wrapper) , 1);\n}\n\n\nEIGEN_DECLARE_TEST(constructor)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( ctor_init1(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_1( ctor_init1(Matrix4d()) );\n    CALL_SUBTEST_1( ctor_init1(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_1( ctor_init1(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  {\n    Matrix<Index,1,1> a(123);\n    VERIFY_IS_EQUAL(a[0], 123);\n  }\n  {\n    Matrix<Index,1,1> a(123.0);\n    VERIFY_IS_EQUAL(a[0], 123);\n  }\n  {\n    Matrix<float,1,1> a(123);\n    VERIFY_IS_EQUAL(a[0], 123.f);\n  }\n  {\n    Array<Index,1,1> a(123);\n    VERIFY_IS_EQUAL(a[0], 123);\n  }\n  {\n    Array<Index,1,1> a(123.0);\n    VERIFY_IS_EQUAL(a[0], 123);\n  }\n  {\n    Array<float,1,1> a(123);\n    VERIFY_IS_EQUAL(a[0], 123.f);\n  }\n  {\n    Array<Index,3,3> a(123);\n    VERIFY_IS_EQUAL(a(4), 123);\n  }\n  {\n    Array<Index,3,3> a(123.0);\n    VERIFY_IS_EQUAL(a(4), 123);\n  }\n  {\n    Array<float,3,3> a(123);\n    VERIFY_IS_EQUAL(a(4), 123.f);\n  }\n  {\n    MatrixXi m1(M,N);\n    VERIFY_IS_EQUAL(m1.rows(),M);\n    VERIFY_IS_EQUAL(m1.cols(),N);\n    ArrayXXi a1(M,N);\n    VERIFY_IS_EQUAL(a1.rows(),M);\n    VERIFY_IS_EQUAL(a1.cols(),N);\n    VectorXi v1(M);\n    VERIFY_IS_EQUAL(v1.size(),M);\n    ArrayXi a2(M);\n    VERIFY_IS_EQUAL(a2.size(),M);\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/corners.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#define COMPARE_CORNER(A,B) \\\n  VERIFY_IS_EQUAL(matrix.A, matrix.B); \\\n  VERIFY_IS_EQUAL(const_matrix.A, const_matrix.B);\n\ntemplate<typename MatrixType> void corners(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  Index r = internal::random<Index>(1,rows);\n  Index c = internal::random<Index>(1,cols);\n\n  MatrixType matrix = MatrixType::Random(rows,cols);\n  const MatrixType const_matrix = MatrixType::Random(rows,cols);\n\n  COMPARE_CORNER(topLeftCorner(r,c), block(0,0,r,c));\n  COMPARE_CORNER(topRightCorner(r,c), block(0,cols-c,r,c));\n  COMPARE_CORNER(bottomLeftCorner(r,c), block(rows-r,0,r,c));\n  COMPARE_CORNER(bottomRightCorner(r,c), block(rows-r,cols-c,r,c));\n\n  Index sr = internal::random<Index>(1,rows) - 1;\n  Index nr = internal::random<Index>(1,rows-sr);\n  Index sc = internal::random<Index>(1,cols) - 1;\n  Index nc = internal::random<Index>(1,cols-sc);\n\n  COMPARE_CORNER(topRows(r), block(0,0,r,cols));\n  COMPARE_CORNER(middleRows(sr,nr), block(sr,0,nr,cols));\n  COMPARE_CORNER(bottomRows(r), block(rows-r,0,r,cols));\n  COMPARE_CORNER(leftCols(c), block(0,0,rows,c));\n  COMPARE_CORNER(middleCols(sc,nc), block(0,sc,rows,nc));\n  COMPARE_CORNER(rightCols(c), block(0,cols-c,rows,c));\n}\n\ntemplate<typename MatrixType, int CRows, int CCols, int SRows, int SCols> void corners_fixedsize()\n{\n  MatrixType matrix = MatrixType::Random();\n  const MatrixType const_matrix = MatrixType::Random();\n\n  enum {\n    rows = MatrixType::RowsAtCompileTime,\n    cols = MatrixType::ColsAtCompileTime,\n    r = CRows,\n    c = CCols,\n\tsr = SRows,\n\tsc = SCols\n  };\n\n  VERIFY_IS_EQUAL((matrix.template topLeftCorner<r,c>()), (matrix.template block<r,c>(0,0)));\n  VERIFY_IS_EQUAL((matrix.template topRightCorner<r,c>()), (matrix.template block<r,c>(0,cols-c)));\n  VERIFY_IS_EQUAL((matrix.template bottomLeftCorner<r,c>()), (matrix.template block<r,c>(rows-r,0)));\n  VERIFY_IS_EQUAL((matrix.template bottomRightCorner<r,c>()), (matrix.template block<r,c>(rows-r,cols-c)));\n\n  VERIFY_IS_EQUAL((matrix.template topLeftCorner<r,c>()), (matrix.template topLeftCorner<r,Dynamic>(r,c)));\n  VERIFY_IS_EQUAL((matrix.template topRightCorner<r,c>()), (matrix.template topRightCorner<r,Dynamic>(r,c)));\n  VERIFY_IS_EQUAL((matrix.template bottomLeftCorner<r,c>()), (matrix.template bottomLeftCorner<r,Dynamic>(r,c)));\n  VERIFY_IS_EQUAL((matrix.template bottomRightCorner<r,c>()), (matrix.template bottomRightCorner<r,Dynamic>(r,c)));\n\n  VERIFY_IS_EQUAL((matrix.template topLeftCorner<r,c>()), (matrix.template topLeftCorner<Dynamic,c>(r,c)));\n  VERIFY_IS_EQUAL((matrix.template topRightCorner<r,c>()), (matrix.template topRightCorner<Dynamic,c>(r,c)));\n  VERIFY_IS_EQUAL((matrix.template bottomLeftCorner<r,c>()), (matrix.template bottomLeftCorner<Dynamic,c>(r,c)));\n  VERIFY_IS_EQUAL((matrix.template bottomRightCorner<r,c>()), (matrix.template bottomRightCorner<Dynamic,c>(r,c)));\n\n  VERIFY_IS_EQUAL((matrix.template topRows<r>()), (matrix.template block<r,cols>(0,0)));\n  VERIFY_IS_EQUAL((matrix.template middleRows<r>(sr)), (matrix.template block<r,cols>(sr,0)));\n  VERIFY_IS_EQUAL((matrix.template bottomRows<r>()), (matrix.template block<r,cols>(rows-r,0)));\n  VERIFY_IS_EQUAL((matrix.template leftCols<c>()), (matrix.template block<rows,c>(0,0)));\n  VERIFY_IS_EQUAL((matrix.template middleCols<c>(sc)), (matrix.template block<rows,c>(0,sc)));\n  VERIFY_IS_EQUAL((matrix.template rightCols<c>()), (matrix.template block<rows,c>(0,cols-c)));\n\n  VERIFY_IS_EQUAL((const_matrix.template topLeftCorner<r,c>()), (const_matrix.template block<r,c>(0,0)));\n  VERIFY_IS_EQUAL((const_matrix.template topRightCorner<r,c>()), (const_matrix.template block<r,c>(0,cols-c)));\n  VERIFY_IS_EQUAL((const_matrix.template bottomLeftCorner<r,c>()), (const_matrix.template block<r,c>(rows-r,0)));\n  VERIFY_IS_EQUAL((const_matrix.template bottomRightCorner<r,c>()), (const_matrix.template block<r,c>(rows-r,cols-c)));\n\n  VERIFY_IS_EQUAL((const_matrix.template topLeftCorner<r,c>()), (const_matrix.template topLeftCorner<r,Dynamic>(r,c)));\n  VERIFY_IS_EQUAL((const_matrix.template topRightCorner<r,c>()), (const_matrix.template topRightCorner<r,Dynamic>(r,c)));\n  VERIFY_IS_EQUAL((const_matrix.template bottomLeftCorner<r,c>()), (const_matrix.template bottomLeftCorner<r,Dynamic>(r,c)));\n  VERIFY_IS_EQUAL((const_matrix.template bottomRightCorner<r,c>()), (const_matrix.template bottomRightCorner<r,Dynamic>(r,c)));\n\n  VERIFY_IS_EQUAL((const_matrix.template topLeftCorner<r,c>()), (const_matrix.template topLeftCorner<Dynamic,c>(r,c)));\n  VERIFY_IS_EQUAL((const_matrix.template topRightCorner<r,c>()), (const_matrix.template topRightCorner<Dynamic,c>(r,c)));\n  VERIFY_IS_EQUAL((const_matrix.template bottomLeftCorner<r,c>()), (const_matrix.template bottomLeftCorner<Dynamic,c>(r,c)));\n  VERIFY_IS_EQUAL((const_matrix.template bottomRightCorner<r,c>()), (const_matrix.template bottomRightCorner<Dynamic,c>(r,c)));\n\n  VERIFY_IS_EQUAL((const_matrix.template topRows<r>()), (const_matrix.template block<r,cols>(0,0)));\n  VERIFY_IS_EQUAL((const_matrix.template middleRows<r>(sr)), (const_matrix.template block<r,cols>(sr,0)));\n  VERIFY_IS_EQUAL((const_matrix.template bottomRows<r>()), (const_matrix.template block<r,cols>(rows-r,0)));\n  VERIFY_IS_EQUAL((const_matrix.template leftCols<c>()), (const_matrix.template block<rows,c>(0,0)));\n  VERIFY_IS_EQUAL((const_matrix.template middleCols<c>(sc)), (const_matrix.template block<rows,c>(0,sc)));\n  VERIFY_IS_EQUAL((const_matrix.template rightCols<c>()), (const_matrix.template block<rows,c>(0,cols-c)));\n}\n\nEIGEN_DECLARE_TEST(corners)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( corners(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( corners(Matrix4d()) );\n    CALL_SUBTEST_3( corners(Matrix<int,10,12>()) );\n    CALL_SUBTEST_4( corners(MatrixXcf(5, 7)) );\n    CALL_SUBTEST_5( corners(MatrixXf(21, 20)) );\n\n    CALL_SUBTEST_1(( corners_fixedsize<Matrix<float, 1, 1>, 1, 1, 0, 0>() ));\n    CALL_SUBTEST_2(( corners_fixedsize<Matrix4d,2,2,1,1>() ));\n    CALL_SUBTEST_3(( corners_fixedsize<Matrix<int,10,12>,4,7,5,2>() ));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/ctorleak.cpp",
    "content": "#include \"main.h\"\n\n#include <exception>  // std::exception\n\nstruct Foo\n{\n  static Index object_count;\n  static Index object_limit;\n  int dummy;\n\n  Foo() : dummy(0)\n  {\n#ifdef EIGEN_EXCEPTIONS\n    // TODO: Is this the correct way to handle this?\n    if (Foo::object_count > Foo::object_limit) { std::cout << \"\\nThrow!\\n\"; throw Foo::Fail(); }\n#endif\n\t  std::cout << '+';\n    ++Foo::object_count;\n  }\n\n  ~Foo()\n  {\n\t  std::cout << '-';\n    --Foo::object_count;\n  }\n\n  class Fail : public std::exception {};\n};\n\nIndex Foo::object_count = 0;\nIndex Foo::object_limit = 0;\n\n#undef EIGEN_TEST_MAX_SIZE\n#define EIGEN_TEST_MAX_SIZE 3\n\nEIGEN_DECLARE_TEST(ctorleak)\n{\n  typedef Matrix<Foo, Dynamic, Dynamic> MatrixX;\n  typedef Matrix<Foo, Dynamic, 1> VectorX;\n  \n  Foo::object_count = 0;\n  for(int i = 0; i < g_repeat; i++) {\n    Index rows = internal::random<Index>(2,EIGEN_TEST_MAX_SIZE), cols = internal::random<Index>(2,EIGEN_TEST_MAX_SIZE);\n    Foo::object_limit = rows*cols;\n    {\n    MatrixX r(rows, cols);\n    Foo::object_limit = r.size()+internal::random<Index>(0, rows*cols - 2);\n    std::cout << \"object_limit =\" << Foo::object_limit << std::endl;\n#ifdef EIGEN_EXCEPTIONS\n    try\n    {\n#endif\n      if(internal::random<bool>()) {\n        std::cout <<       \"\\nMatrixX m(\" << rows << \", \" << cols << \");\\n\";\n        MatrixX m(rows, cols);\n      }\n      else {\n        std::cout <<       \"\\nMatrixX m(r);\\n\";\n        MatrixX m(r);\n      }\n#ifdef EIGEN_EXCEPTIONS\n      VERIFY(false);  // not reached if exceptions are enabled\n    }\n    catch (const Foo::Fail&) { /* ignore */ }\n#endif\n    }\n    VERIFY_IS_EQUAL(Index(0), Foo::object_count);\n\n    {\n      Foo::object_limit = (rows+1)*(cols+1);\n      MatrixX A(rows, cols);\n      VERIFY_IS_EQUAL(Foo::object_count, rows*cols);\n      VectorX v=A.row(0);\n      VERIFY_IS_EQUAL(Foo::object_count, (rows+1)*cols);\n      v = A.col(0);\n      VERIFY_IS_EQUAL(Foo::object_count, rows*(cols+1));\n    }\n    VERIFY_IS_EQUAL(Index(0), Foo::object_count);\n  }\n  std::cout << \"\\n\";\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/denseLM.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Desire Nuentsa <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <iostream>\n#include <fstream>\n#include <iomanip>\n\n#include \"main.h\"\n#include <Eigen/LevenbergMarquardt>\nusing namespace std;\nusing namespace Eigen;\n\ntemplate<typename Scalar>\nstruct DenseLM : DenseFunctor<Scalar>\n{\n  typedef DenseFunctor<Scalar> Base;\n  typedef typename Base::JacobianType JacobianType;\n  typedef Matrix<Scalar,Dynamic,1> VectorType;\n  \n  DenseLM(int n, int m) : DenseFunctor<Scalar>(n,m) \n  { }\n \n  VectorType model(const VectorType& uv, VectorType& x)\n  {\n    VectorType y; // Should change to use expression template\n    int m = Base::values(); \n    int n = Base::inputs();\n    eigen_assert(uv.size()%2 == 0);\n    eigen_assert(uv.size() == n);\n    eigen_assert(x.size() == m);\n    y.setZero(m);\n    int half = n/2;\n    VectorBlock<const VectorType> u(uv, 0, half);\n    VectorBlock<const VectorType> v(uv, half, half);\n    for (int j = 0; j < m; j++)\n    {\n      for (int i = 0; i < half; i++)\n        y(j) += u(i)*std::exp(-(x(j)-i)*(x(j)-i)/(v(i)*v(i)));\n    }\n    return y;\n    \n  }\n  void initPoints(VectorType& uv_ref, VectorType& x)\n  {\n    m_x = x;\n    m_y = this->model(uv_ref, x);\n  }\n  \n  int operator()(const VectorType& uv, VectorType& fvec)\n  {\n    \n    int m = Base::values(); \n    int n = Base::inputs();\n    eigen_assert(uv.size()%2 == 0);\n    eigen_assert(uv.size() == n);\n    eigen_assert(fvec.size() == m);\n    int half = n/2;\n    VectorBlock<const VectorType> u(uv, 0, half);\n    VectorBlock<const VectorType> v(uv, half, half);\n    for (int j = 0; j < m; j++)\n    {\n      fvec(j) = m_y(j);\n      for (int i = 0; i < half; i++)\n      {\n        fvec(j) -= u(i) *std::exp(-(m_x(j)-i)*(m_x(j)-i)/(v(i)*v(i)));\n      }\n    }\n    \n    return 0;\n  }\n  int df(const VectorType& uv, JacobianType& fjac)\n  {\n    int m = Base::values(); \n    int n = Base::inputs();\n    eigen_assert(n == uv.size());\n    eigen_assert(fjac.rows() == m);\n    eigen_assert(fjac.cols() == n);\n    int half = n/2;\n    VectorBlock<const VectorType> u(uv, 0, half);\n    VectorBlock<const VectorType> v(uv, half, half);\n    for (int j = 0; j < m; j++)\n    {\n      for (int i = 0; i < half; i++)\n      {\n        fjac.coeffRef(j,i) = -std::exp(-(m_x(j)-i)*(m_x(j)-i)/(v(i)*v(i)));\n        fjac.coeffRef(j,i+half) = -2.*u(i)*(m_x(j)-i)*(m_x(j)-i)/(std::pow(v(i),3)) * std::exp(-(m_x(j)-i)*(m_x(j)-i)/(v(i)*v(i)));\n      }\n    }\n    return 0;\n  }\n  VectorType m_x, m_y; //Data Points\n};\n\ntemplate<typename FunctorType, typename VectorType>\nint test_minimizeLM(FunctorType& functor, VectorType& uv)\n{\n  LevenbergMarquardt<FunctorType> lm(functor);\n  LevenbergMarquardtSpace::Status info; \n  \n  info = lm.minimize(uv);\n  \n  VERIFY_IS_EQUAL(info, 1);\n  //FIXME Check other parameters\n  return info;\n}\n\ntemplate<typename FunctorType, typename VectorType>\nint test_lmder(FunctorType& functor, VectorType& uv)\n{\n  typedef typename VectorType::Scalar Scalar;\n  LevenbergMarquardtSpace::Status info; \n  LevenbergMarquardt<FunctorType> lm(functor);\n  info = lm.lmder1(uv);\n  \n  VERIFY_IS_EQUAL(info, 1);\n  //FIXME Check other parameters\n  return info;\n}\n\ntemplate<typename FunctorType, typename VectorType>\nint test_minimizeSteps(FunctorType& functor, VectorType& uv)\n{\n  LevenbergMarquardtSpace::Status info;   \n  LevenbergMarquardt<FunctorType> lm(functor);\n  info = lm.minimizeInit(uv);\n  if (info==LevenbergMarquardtSpace::ImproperInputParameters)\n      return info;\n  do \n  {\n    info = lm.minimizeOneStep(uv);\n  } while (info==LevenbergMarquardtSpace::Running);\n  \n  VERIFY_IS_EQUAL(info, 1);\n  //FIXME Check other parameters\n  return info;\n}\n\ntemplate<typename T>\nvoid test_denseLM_T()\n{\n  typedef Matrix<T,Dynamic,1> VectorType;\n  \n  int inputs = 10; \n  int values = 1000; \n  DenseLM<T> dense_gaussian(inputs, values);\n  VectorType uv(inputs),uv_ref(inputs);\n  VectorType x(values);\n  \n  // Generate the reference solution \n  uv_ref << -2, 1, 4 ,8, 6, 1.8, 1.2, 1.1, 1.9 , 3;\n  \n  //Generate the reference data points\n  x.setRandom();\n  x = 10*x;\n  x.array() += 10;\n  dense_gaussian.initPoints(uv_ref, x);\n  \n  // Generate the initial parameters \n  VectorBlock<VectorType> u(uv, 0, inputs/2); \n  VectorBlock<VectorType> v(uv, inputs/2, inputs/2);\n  \n  // Solve the optimization problem\n  \n  //Solve in one go\n  u.setOnes(); v.setOnes();\n  test_minimizeLM(dense_gaussian, uv);\n  \n  //Solve until the machine precision\n  u.setOnes(); v.setOnes();\n  test_lmder(dense_gaussian, uv); \n  \n  // Solve step by step\n  v.setOnes(); u.setOnes();\n  test_minimizeSteps(dense_gaussian, uv);\n  \n}\n\nEIGEN_DECLARE_TEST(denseLM)\n{\n  CALL_SUBTEST_2(test_denseLM_T<double>());\n  \n  // CALL_SUBTEST_2(test_sparseLM_T<std::complex<double>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/dense_storage.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include \"AnnoyingScalar.h\"\n#include \"SafeScalar.h\"\n\n#include <Eigen/Core>\n\n#if EIGEN_HAS_TYPE_TRAITS && EIGEN_HAS_CXX11\nusing DenseStorageD3x3 = Eigen::DenseStorage<double, 3, 3, 3, 3>;\nstatic_assert(std::is_trivially_move_constructible<DenseStorageD3x3>::value, \"DenseStorage not trivially_move_constructible\");\nstatic_assert(std::is_trivially_move_assignable<DenseStorageD3x3>::value, \"DenseStorage not trivially_move_assignable\");\n#if !defined(EIGEN_DENSE_STORAGE_CTOR_PLUGIN)\nstatic_assert(std::is_trivially_copy_constructible<DenseStorageD3x3>::value, \"DenseStorage not trivially_copy_constructible\");\nstatic_assert(std::is_trivially_copy_assignable<DenseStorageD3x3>::value, \"DenseStorage not trivially_copy_assignable\");\nstatic_assert(std::is_trivially_copyable<DenseStorageD3x3>::value, \"DenseStorage not trivially_copyable\");\n#endif\n#endif\n\ntemplate <typename T, int Size, int Rows, int Cols>\nvoid dense_storage_copy(int rows, int cols)\n{\n  typedef DenseStorage<T, Size, Rows, Cols, 0> DenseStorageType;\n  \n  const int size = rows*cols;\n  DenseStorageType reference(size, rows, cols);\n  T* raw_reference = reference.data();\n  for (int i=0; i<size; ++i)\n    raw_reference[i] = static_cast<T>(i);\n    \n  DenseStorageType copied_reference(reference);\n  const T* raw_copied_reference = copied_reference.data();\n  for (int i=0; i<size; ++i)\n    VERIFY_IS_EQUAL(raw_reference[i], raw_copied_reference[i]);\n}\n\ntemplate <typename T, int Size, int Rows, int Cols>\nvoid dense_storage_assignment(int rows, int cols)\n{\n  typedef DenseStorage<T, Size, Rows, Cols, 0> DenseStorageType;\n  \n  const int size = rows*cols;\n  DenseStorageType reference(size, rows, cols);\n  T* raw_reference = reference.data();\n  for (int i=0; i<size; ++i)\n    raw_reference[i] = static_cast<T>(i);\n    \n  DenseStorageType copied_reference;\n  copied_reference = reference;\n  const T* raw_copied_reference = copied_reference.data();\n  for (int i=0; i<size; ++i)\n    VERIFY_IS_EQUAL(raw_reference[i], raw_copied_reference[i]);\n}\n\ntemplate <typename T, int Size, int Rows, int Cols>\nvoid dense_storage_swap(int rows0, int cols0, int rows1, int cols1)\n{\n  typedef DenseStorage<T, Size, Rows, Cols, 0> DenseStorageType;\n  \n  const int size0 = rows0*cols0;\n  DenseStorageType a(size0, rows0, cols0);\n  for (int i=0; i<size0; ++i) {\n    a.data()[i] = static_cast<T>(i);\n  }\n  \n  const int size1 = rows1*cols1;\n  DenseStorageType b(size1, rows1, cols1);\n  for (int i=0; i<size1; ++i) {\n    b.data()[i] = static_cast<T>(-i);\n  }\n  \n  a.swap(b);\n  \n  for (int i=0; i<size0; ++i) {\n    VERIFY_IS_EQUAL(b.data()[i], static_cast<T>(i));\n  }\n  \n  for (int i=0; i<size1; ++i) {\n    VERIFY_IS_EQUAL(a.data()[i], static_cast<T>(-i));\n  }\n}\n\ntemplate<typename T, int Size, std::size_t Alignment>\nvoid dense_storage_alignment()\n{\n  #if EIGEN_HAS_ALIGNAS\n  \n  struct alignas(Alignment) Empty1 {};\n  VERIFY_IS_EQUAL(std::alignment_of<Empty1>::value, Alignment);\n\n  struct EIGEN_ALIGN_TO_BOUNDARY(Alignment) Empty2 {};\n  VERIFY_IS_EQUAL(std::alignment_of<Empty2>::value, Alignment);\n\n  struct Nested1 { EIGEN_ALIGN_TO_BOUNDARY(Alignment) T data[Size]; };\n  VERIFY_IS_EQUAL(std::alignment_of<Nested1>::value, Alignment);\n\n  VERIFY_IS_EQUAL( (std::alignment_of<internal::plain_array<T,Size,AutoAlign,Alignment> >::value), Alignment);\n\n  const std::size_t default_alignment = internal::compute_default_alignment<T,Size>::value;\n\n  VERIFY_IS_EQUAL( (std::alignment_of<DenseStorage<T,Size,1,1,AutoAlign> >::value), default_alignment);\n  VERIFY_IS_EQUAL( (std::alignment_of<Matrix<T,Size,1,AutoAlign> >::value), default_alignment);\n  struct Nested2 { Matrix<T,Size,1,AutoAlign> mat; };\n  VERIFY_IS_EQUAL(std::alignment_of<Nested2>::value, default_alignment);\n\n  #endif\n}\n\ntemplate<typename T>\nvoid dense_storage_tests() {\n  // Dynamic Storage.\n  dense_storage_copy<T,Dynamic,Dynamic,Dynamic>(4, 3);  \n  dense_storage_copy<T,Dynamic,Dynamic,3>(4, 3);\n  dense_storage_copy<T,Dynamic,4,Dynamic>(4, 3);\n  // Fixed Storage.\n  dense_storage_copy<T,12,4,3>(4, 3);\n  dense_storage_copy<T,12,Dynamic,Dynamic>(4, 3);\n  dense_storage_copy<T,12,4,Dynamic>(4, 3);\n  dense_storage_copy<T,12,Dynamic,3>(4, 3);\n  // Fixed Storage with Uninitialized Elements.\n  dense_storage_copy<T,18,Dynamic,Dynamic>(4, 3);\n  dense_storage_copy<T,18,4,Dynamic>(4, 3);\n  dense_storage_copy<T,18,Dynamic,3>(4, 3);\n  \n  // Dynamic Storage.\n  dense_storage_assignment<T,Dynamic,Dynamic,Dynamic>(4, 3);  \n  dense_storage_assignment<T,Dynamic,Dynamic,3>(4, 3);\n  dense_storage_assignment<T,Dynamic,4,Dynamic>(4, 3);\n  // Fixed Storage.\n  dense_storage_assignment<T,12,4,3>(4, 3);\n  dense_storage_assignment<T,12,Dynamic,Dynamic>(4, 3);\n  dense_storage_assignment<T,12,4,Dynamic>(4, 3);\n  dense_storage_assignment<T,12,Dynamic,3>(4, 3);\n  // Fixed Storage with Uninitialized Elements.\n  dense_storage_assignment<T,18,Dynamic,Dynamic>(4, 3);\n  dense_storage_assignment<T,18,4,Dynamic>(4, 3);\n  dense_storage_assignment<T,18,Dynamic,3>(4, 3);\n  \n  // Dynamic Storage.\n  dense_storage_swap<T,Dynamic,Dynamic,Dynamic>(4, 3, 4, 3); \n  dense_storage_swap<T,Dynamic,Dynamic,Dynamic>(4, 3, 2, 1);  \n  dense_storage_swap<T,Dynamic,Dynamic,Dynamic>(2, 1, 4, 3);\n  dense_storage_swap<T,Dynamic,Dynamic,3>(4, 3, 4, 3);\n  dense_storage_swap<T,Dynamic,Dynamic,3>(4, 3, 2, 3);\n  dense_storage_swap<T,Dynamic,Dynamic,3>(2, 3, 4, 3);\n  dense_storage_swap<T,Dynamic,4,Dynamic>(4, 3, 4, 3);\n  dense_storage_swap<T,Dynamic,4,Dynamic>(4, 3, 4, 1);\n  dense_storage_swap<T,Dynamic,4,Dynamic>(4, 1, 4, 3);\n  // Fixed Storage.\n  dense_storage_swap<T,12,4,3>(4, 3, 4, 3);\n  dense_storage_swap<T,12,Dynamic,Dynamic>(4, 3, 4, 3);\n  dense_storage_swap<T,12,Dynamic,Dynamic>(4, 3, 2, 1);\n  dense_storage_swap<T,12,Dynamic,Dynamic>(2, 1, 4, 3);\n  dense_storage_swap<T,12,4,Dynamic>(4, 3, 4, 3);\n  dense_storage_swap<T,12,4,Dynamic>(4, 3, 4, 1);\n  dense_storage_swap<T,12,4,Dynamic>(4, 1, 4, 3);\n  dense_storage_swap<T,12,Dynamic,3>(4, 3, 4, 3);\n  dense_storage_swap<T,12,Dynamic,3>(4, 3, 2, 3);\n  dense_storage_swap<T,12,Dynamic,3>(2, 3, 4, 3);\n  // Fixed Storage with Uninitialized Elements.\n  dense_storage_swap<T,18,Dynamic,Dynamic>(4, 3, 4, 3);\n  dense_storage_swap<T,18,Dynamic,Dynamic>(4, 3, 2, 1);\n  dense_storage_swap<T,18,Dynamic,Dynamic>(2, 1, 4, 3);\n  dense_storage_swap<T,18,4,Dynamic>(4, 3, 4, 3);\n  dense_storage_swap<T,18,4,Dynamic>(4, 3, 4, 1);\n  dense_storage_swap<T,18,4,Dynamic>(4, 1, 4, 3);\n  dense_storage_swap<T,18,Dynamic,3>(4, 3, 4, 3);\n  dense_storage_swap<T,18,Dynamic,3>(4, 3, 2, 3);\n  dense_storage_swap<T,18,Dynamic,3>(2, 3, 4, 3);\n  \n  dense_storage_alignment<T,16,8>();\n  dense_storage_alignment<T,16,16>();\n  dense_storage_alignment<T,16,32>();\n  dense_storage_alignment<T,16,64>();\n}\n\nEIGEN_DECLARE_TEST(dense_storage)\n{\n  dense_storage_tests<int>();\n  dense_storage_tests<float>();\n  dense_storage_tests<SafeScalar<float> >();\n  dense_storage_tests<AnnoyingScalar>();\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/determinant.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/LU>\n\ntemplate<typename MatrixType> void determinant(const MatrixType& m)\n{\n  /* this test covers the following files:\n     Determinant.h\n  */\n  Index size = m.rows();\n\n  MatrixType m1(size, size), m2(size, size);\n  m1.setRandom();\n  m2.setRandom();\n  typedef typename MatrixType::Scalar Scalar;\n  Scalar x = internal::random<Scalar>();\n  VERIFY_IS_APPROX(MatrixType::Identity(size, size).determinant(), Scalar(1));\n  VERIFY_IS_APPROX((m1*m2).eval().determinant(), m1.determinant() * m2.determinant());\n  if(size==1) return;\n  Index i = internal::random<Index>(0, size-1);\n  Index j;\n  do {\n    j = internal::random<Index>(0, size-1);\n  } while(j==i);\n  m2 = m1;\n  m2.row(i).swap(m2.row(j));\n  VERIFY_IS_APPROX(m2.determinant(), -m1.determinant());\n  m2 = m1;\n  m2.col(i).swap(m2.col(j));\n  VERIFY_IS_APPROX(m2.determinant(), -m1.determinant());\n  VERIFY_IS_APPROX(m2.determinant(), m2.transpose().determinant());\n  VERIFY_IS_APPROX(numext::conj(m2.determinant()), m2.adjoint().determinant());\n  m2 = m1;\n  m2.row(i) += x*m2.row(j);\n  VERIFY_IS_APPROX(m2.determinant(), m1.determinant());\n  m2 = m1;\n  m2.row(i) *= x;\n  VERIFY_IS_APPROX(m2.determinant(), m1.determinant() * x);\n  \n  // check empty matrix\n  VERIFY_IS_APPROX(m2.block(0,0,0,0).determinant(), Scalar(1));\n}\n\nEIGEN_DECLARE_TEST(determinant)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    int s = 0;\n    CALL_SUBTEST_1( determinant(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( determinant(Matrix<double, 2, 2>()) );\n    CALL_SUBTEST_3( determinant(Matrix<double, 3, 3>()) );\n    CALL_SUBTEST_4( determinant(Matrix<double, 4, 4>()) );\n    CALL_SUBTEST_5( determinant(Matrix<std::complex<double>, 10, 10>()) );\n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4);\n    CALL_SUBTEST_6( determinant(MatrixXd(s, s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/diagonal.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void diagonal(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols);\n\n  Scalar s1 = internal::random<Scalar>();\n\n  //check diagonal()\n  VERIFY_IS_APPROX(m1.diagonal(), m1.transpose().diagonal());\n  m2.diagonal() = 2 * m1.diagonal();\n  m2.diagonal()[0] *= 3;\n\n  if (rows>2)\n  {\n    enum {\n      N1 = MatrixType::RowsAtCompileTime>2 ?  2 : 0,\n      N2 = MatrixType::RowsAtCompileTime>1 ? -1 : 0\n    };\n\n    // check sub/super diagonal\n    if(MatrixType::SizeAtCompileTime!=Dynamic)\n    {\n      VERIFY(m1.template diagonal<N1>().RowsAtCompileTime == m1.diagonal(N1).size());\n      VERIFY(m1.template diagonal<N2>().RowsAtCompileTime == m1.diagonal(N2).size());\n    }\n\n    m2.template diagonal<N1>() = 2 * m1.template diagonal<N1>();\n    VERIFY_IS_APPROX(m2.template diagonal<N1>(), static_cast<Scalar>(2) * m1.diagonal(N1));\n    m2.template diagonal<N1>()[0] *= 3;\n    VERIFY_IS_APPROX(m2.template diagonal<N1>()[0], static_cast<Scalar>(6) * m1.template diagonal<N1>()[0]);\n\n\n    m2.template diagonal<N2>() = 2 * m1.template diagonal<N2>();\n    m2.template diagonal<N2>()[0] *= 3;\n    VERIFY_IS_APPROX(m2.template diagonal<N2>()[0], static_cast<Scalar>(6) * m1.template diagonal<N2>()[0]);\n\n    m2.diagonal(N1) = 2 * m1.diagonal(N1);\n    VERIFY_IS_APPROX(m2.template diagonal<N1>(), static_cast<Scalar>(2) * m1.diagonal(N1));\n    m2.diagonal(N1)[0] *= 3;\n    VERIFY_IS_APPROX(m2.diagonal(N1)[0], static_cast<Scalar>(6) * m1.diagonal(N1)[0]);\n\n    m2.diagonal(N2) = 2 * m1.diagonal(N2);\n    VERIFY_IS_APPROX(m2.template diagonal<N2>(), static_cast<Scalar>(2) * m1.diagonal(N2));\n    m2.diagonal(N2)[0] *= 3;\n    VERIFY_IS_APPROX(m2.diagonal(N2)[0], static_cast<Scalar>(6) * m1.diagonal(N2)[0]);\n\n    m2.diagonal(N2).x() = s1;\n    VERIFY_IS_APPROX(m2.diagonal(N2).x(), s1);\n    m2.diagonal(N2).coeffRef(0) = Scalar(2)*s1;\n    VERIFY_IS_APPROX(m2.diagonal(N2).coeff(0), Scalar(2)*s1);\n  }\n\n  VERIFY( m1.diagonal( cols).size()==0 );\n  VERIFY( m1.diagonal(-rows).size()==0 );\n}\n\ntemplate<typename MatrixType> void diagonal_assert(const MatrixType& m) {\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols);\n\n  if (rows>=2 && cols>=2)\n  {\n    VERIFY_RAISES_ASSERT( m1 += m1.diagonal() );\n    VERIFY_RAISES_ASSERT( m1 -= m1.diagonal() );\n    VERIFY_RAISES_ASSERT( m1.array() *= m1.diagonal().array() );\n    VERIFY_RAISES_ASSERT( m1.array() /= m1.diagonal().array() );\n  }\n\n  VERIFY_RAISES_ASSERT( m1.diagonal(cols+1) );\n  VERIFY_RAISES_ASSERT( m1.diagonal(-(rows+1)) );\n}\n\nEIGEN_DECLARE_TEST(diagonal)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( diagonal(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_1( diagonal(Matrix<float, 4, 9>()) );\n    CALL_SUBTEST_1( diagonal(Matrix<float, 7, 3>()) );\n    CALL_SUBTEST_2( diagonal(Matrix4d()) );\n    CALL_SUBTEST_2( diagonal(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_2( diagonal(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_2( diagonal(MatrixXcd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_1( diagonal(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_1( diagonal(Matrix<float,Dynamic,4>(3, 4)) );\n    CALL_SUBTEST_1( diagonal_assert(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/diagonal_matrix_variadic_ctor.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2019 David Tellenbach <david.tellenbach@tellnotes.org>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_STATIC_ASSERT\n\n#include \"main.h\"\n\ntemplate <typename Scalar>\nvoid assertionTest()\n{\n  typedef DiagonalMatrix<Scalar, 5> DiagMatrix5;\n  typedef DiagonalMatrix<Scalar, 7> DiagMatrix7;\n  typedef DiagonalMatrix<Scalar, Dynamic> DiagMatrixX;\n\n  Scalar raw[6];\n  for (int i = 0; i < 6; ++i) {\n    raw[i] = internal::random<Scalar>();\n  }\n\n  VERIFY_RAISES_ASSERT((DiagMatrix5{raw[0], raw[1], raw[2], raw[3]}));\n  VERIFY_RAISES_ASSERT((DiagMatrix5{raw[0], raw[1], raw[3]}));\n  VERIFY_RAISES_ASSERT((DiagMatrix7{raw[0], raw[1], raw[2], raw[3]}));\n\n  VERIFY_RAISES_ASSERT((DiagMatrixX {\n    {raw[0], raw[1], raw[2]},\n    {raw[3], raw[4], raw[5]}\n  }));\n}\n\n#define VERIFY_IMPLICIT_CONVERSION_3(DIAGTYPE, V0, V1, V2) \\\n  DIAGTYPE d(V0, V1, V2);                                  \\\n  DIAGTYPE::DenseMatrixType Dense = d.toDenseMatrix();     \\\n  VERIFY_IS_APPROX(Dense(0, 0), (Scalar)V0);               \\\n  VERIFY_IS_APPROX(Dense(1, 1), (Scalar)V1);               \\\n  VERIFY_IS_APPROX(Dense(2, 2), (Scalar)V2);\n\n#define VERIFY_IMPLICIT_CONVERSION_4(DIAGTYPE, V0, V1, V2, V3) \\\n  DIAGTYPE d(V0, V1, V2, V3);                                  \\\n  DIAGTYPE::DenseMatrixType Dense = d.toDenseMatrix();         \\\n  VERIFY_IS_APPROX(Dense(0, 0), (Scalar)V0);                   \\\n  VERIFY_IS_APPROX(Dense(1, 1), (Scalar)V1);                   \\\n  VERIFY_IS_APPROX(Dense(2, 2), (Scalar)V2);                   \\\n  VERIFY_IS_APPROX(Dense(3, 3), (Scalar)V3);\n\n#define VERIFY_IMPLICIT_CONVERSION_5(DIAGTYPE, V0, V1, V2, V3, V4) \\\n  DIAGTYPE d(V0, V1, V2, V3, V4);                                  \\\n  DIAGTYPE::DenseMatrixType Dense = d.toDenseMatrix();             \\\n  VERIFY_IS_APPROX(Dense(0, 0), (Scalar)V0);                       \\\n  VERIFY_IS_APPROX(Dense(1, 1), (Scalar)V1);                       \\\n  VERIFY_IS_APPROX(Dense(2, 2), (Scalar)V2);                       \\\n  VERIFY_IS_APPROX(Dense(3, 3), (Scalar)V3);                       \\\n  VERIFY_IS_APPROX(Dense(4, 4), (Scalar)V4);\n\ntemplate<typename Scalar>\nvoid constructorTest()\n{\n  typedef DiagonalMatrix<Scalar, 0> DiagonalMatrix0;\n  typedef DiagonalMatrix<Scalar, 3> DiagonalMatrix3;\n  typedef DiagonalMatrix<Scalar, 4> DiagonalMatrix4;\n  typedef DiagonalMatrix<Scalar, Dynamic> DiagonalMatrixX;\n\n  Scalar raw[7];\n  for (int k = 0; k < 7; ++k) raw[k] = internal::random<Scalar>();\n\n  // Fixed-sized matrices\n  {\n    DiagonalMatrix0 a {{}};\n    VERIFY(a.rows() == 0);\n    VERIFY(a.cols() == 0);\n    typename DiagonalMatrix0::DenseMatrixType m = a.toDenseMatrix();\n    for (Index k = 0; k < a.rows(); ++k) VERIFY(m(k, k) == raw[k]);\n  }\n  {\n    DiagonalMatrix3 a {{raw[0], raw[1], raw[2]}};\n    VERIFY(a.rows() == 3);\n    VERIFY(a.cols() == 3);\n    typename DiagonalMatrix3::DenseMatrixType m = a.toDenseMatrix();\n    for (Index k = 0; k < a.rows(); ++k) VERIFY(m(k, k) == raw[k]);\n  }\n  {\n    DiagonalMatrix4 a {{raw[0], raw[1], raw[2], raw[3]}};\n    VERIFY(a.rows() == 4);\n    VERIFY(a.cols() == 4);\n    typename DiagonalMatrix4::DenseMatrixType m = a.toDenseMatrix();\n    for (Index k = 0; k < a.rows(); ++k) VERIFY(m(k, k) == raw[k]);\n  }\n\n  // dynamically sized matrices\n  {\n    DiagonalMatrixX a{{}};\n    VERIFY(a.rows() == 0);\n    VERIFY(a.rows() == 0);\n    typename DiagonalMatrixX::DenseMatrixType m = a.toDenseMatrix();\n    for (Index k = 0; k < a.rows(); ++k) VERIFY(m(k, k) == raw[k]);\n  }\n  {\n    DiagonalMatrixX a{{raw[0], raw[1], raw[2], raw[3], raw[4], raw[5], raw[6]}};\n    VERIFY(a.rows() == 7);\n    VERIFY(a.rows() == 7);\n    typename DiagonalMatrixX::DenseMatrixType m = a.toDenseMatrix();\n    for (Index k = 0; k < a.rows(); ++k) VERIFY(m(k, k) == raw[k]);\n  }\n}\n\ntemplate<>\nvoid constructorTest<float>()\n{\n  typedef float Scalar;\n\n  typedef DiagonalMatrix<Scalar, 0> DiagonalMatrix0;\n  typedef DiagonalMatrix<Scalar, 3> DiagonalMatrix3;\n  typedef DiagonalMatrix<Scalar, 4> DiagonalMatrix4;\n  typedef DiagonalMatrix<Scalar, 5> DiagonalMatrix5;\n  typedef DiagonalMatrix<Scalar, Dynamic> DiagonalMatrixX;\n\n  Scalar raw[7];\n  for (int k = 0; k < 7; ++k) raw[k] = internal::random<Scalar>();\n\n  // Fixed-sized matrices\n  {\n    DiagonalMatrix0 a {{}};\n    VERIFY(a.rows() == 0);\n    VERIFY(a.cols() == 0);\n    typename DiagonalMatrix0::DenseMatrixType m = a.toDenseMatrix();\n    for (Index k = 0; k < a.rows(); ++k) VERIFY(m(k, k) == raw[k]);\n  }\n  {\n    DiagonalMatrix3 a {{raw[0], raw[1], raw[2]}};\n    VERIFY(a.rows() == 3);\n    VERIFY(a.cols() == 3);\n    typename DiagonalMatrix3::DenseMatrixType m = a.toDenseMatrix();\n    for (Index k = 0; k < a.rows(); ++k) VERIFY(m(k, k) == raw[k]);\n  }\n  {\n    DiagonalMatrix4 a {{raw[0], raw[1], raw[2], raw[3]}};\n    VERIFY(a.rows() == 4);\n    VERIFY(a.cols() == 4);\n    typename DiagonalMatrix4::DenseMatrixType m = a.toDenseMatrix();\n    for (Index k = 0; k < a.rows(); ++k) VERIFY(m(k, k) == raw[k]);\n  }\n\n  // dynamically sized matrices\n  {\n    DiagonalMatrixX a{{}};\n    VERIFY(a.rows() == 0);\n    VERIFY(a.rows() == 0);\n    typename DiagonalMatrixX::DenseMatrixType m = a.toDenseMatrix();\n    for (Index k = 0; k < a.rows(); ++k) VERIFY(m(k, k) == raw[k]);\n  }\n  {\n    DiagonalMatrixX a{{raw[0], raw[1], raw[2], raw[3], raw[4], raw[5], raw[6]}};\n    VERIFY(a.rows() == 7);\n    VERIFY(a.rows() == 7);\n    typename DiagonalMatrixX::DenseMatrixType m = a.toDenseMatrix();\n    for (Index k = 0; k < a.rows(); ++k) VERIFY(m(k, k) == raw[k]);\n  }\n  { VERIFY_IMPLICIT_CONVERSION_3(DiagonalMatrix3, 1.2647, 2.56f, -3); }\n  { VERIFY_IMPLICIT_CONVERSION_4(DiagonalMatrix4, 1.2647, 2.56f, -3, 3.23f); }\n  { VERIFY_IMPLICIT_CONVERSION_5(DiagonalMatrix5, 1.2647, 2.56f, -3, 3.23f, 2); }\n}\n\nEIGEN_DECLARE_TEST(diagonal_matrix_variadic_ctor)\n{\n  CALL_SUBTEST_1(assertionTest<unsigned char>());\n  CALL_SUBTEST_1(assertionTest<float>());\n  CALL_SUBTEST_1(assertionTest<Index>());\n  CALL_SUBTEST_1(assertionTest<int>());\n  CALL_SUBTEST_1(assertionTest<long int>());\n  CALL_SUBTEST_1(assertionTest<std::ptrdiff_t>());\n  CALL_SUBTEST_1(assertionTest<std::complex<double>>());\n\n  CALL_SUBTEST_2(constructorTest<unsigned char>());\n  CALL_SUBTEST_2(constructorTest<float>());\n  CALL_SUBTEST_2(constructorTest<Index>());\n  CALL_SUBTEST_2(constructorTest<int>());\n  CALL_SUBTEST_2(constructorTest<long int>());\n  CALL_SUBTEST_2(constructorTest<std::ptrdiff_t>());\n  CALL_SUBTEST_2(constructorTest<std::complex<double>>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/diagonalmatrices.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\nusing namespace std;\ntemplate<typename MatrixType> void diagonalmatrices(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  enum { Rows = MatrixType::RowsAtCompileTime, Cols = MatrixType::ColsAtCompileTime };\n  typedef Matrix<Scalar, Rows, 1> VectorType;\n  typedef Matrix<Scalar, 1, Cols> RowVectorType;\n  typedef Matrix<Scalar, Rows, Rows> SquareMatrixType;\n  typedef Matrix<Scalar, Dynamic, Dynamic> DynMatrixType;\n  typedef DiagonalMatrix<Scalar, Rows> LeftDiagonalMatrix;\n  typedef DiagonalMatrix<Scalar, Cols> RightDiagonalMatrix;\n  typedef Matrix<Scalar, Rows==Dynamic?Dynamic:2*Rows, Cols==Dynamic?Dynamic:2*Cols> BigMatrix;\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols);\n  VectorType v1 = VectorType::Random(rows),\n             v2 = VectorType::Random(rows);\n  RowVectorType rv1 = RowVectorType::Random(cols),\n             rv2 = RowVectorType::Random(cols);\n\n  LeftDiagonalMatrix ldm1(v1), ldm2(v2);\n  RightDiagonalMatrix rdm1(rv1), rdm2(rv2);\n  \n  Scalar s1 = internal::random<Scalar>();\n\n  SquareMatrixType sq_m1 (v1.asDiagonal());\n  VERIFY_IS_APPROX(sq_m1, v1.asDiagonal().toDenseMatrix());\n  sq_m1 = v1.asDiagonal();\n  VERIFY_IS_APPROX(sq_m1, v1.asDiagonal().toDenseMatrix());\n  SquareMatrixType sq_m2 = v1.asDiagonal();\n  VERIFY_IS_APPROX(sq_m1, sq_m2);\n  \n  ldm1 = v1.asDiagonal();\n  LeftDiagonalMatrix ldm3(v1);\n  VERIFY_IS_APPROX(ldm1.diagonal(), ldm3.diagonal());\n  LeftDiagonalMatrix ldm4 = v1.asDiagonal();\n  VERIFY_IS_APPROX(ldm1.diagonal(), ldm4.diagonal());\n  \n  sq_m1.block(0,0,rows,rows) = ldm1;\n  VERIFY_IS_APPROX(sq_m1, ldm1.toDenseMatrix());\n  sq_m1.transpose() = ldm1;\n  VERIFY_IS_APPROX(sq_m1, ldm1.toDenseMatrix());\n  \n  Index i = internal::random<Index>(0, rows-1);\n  Index j = internal::random<Index>(0, cols-1);\n  \n  VERIFY_IS_APPROX( ((ldm1 * m1)(i,j))  , ldm1.diagonal()(i) * m1(i,j) );\n  VERIFY_IS_APPROX( ((ldm1 * (m1+m2))(i,j))  , ldm1.diagonal()(i) * (m1+m2)(i,j) );\n  VERIFY_IS_APPROX( ((m1 * rdm1)(i,j))  , rdm1.diagonal()(j) * m1(i,j) );\n  VERIFY_IS_APPROX( ((v1.asDiagonal() * m1)(i,j))  , v1(i) * m1(i,j) );\n  VERIFY_IS_APPROX( ((m1 * rv1.asDiagonal())(i,j))  , rv1(j) * m1(i,j) );\n  VERIFY_IS_APPROX( (((v1+v2).asDiagonal() * m1)(i,j))  , (v1+v2)(i) * m1(i,j) );\n  VERIFY_IS_APPROX( (((v1+v2).asDiagonal() * (m1+m2))(i,j))  , (v1+v2)(i) * (m1+m2)(i,j) );\n  VERIFY_IS_APPROX( ((m1 * (rv1+rv2).asDiagonal())(i,j))  , (rv1+rv2)(j) * m1(i,j) );\n  VERIFY_IS_APPROX( (((m1+m2) * (rv1+rv2).asDiagonal())(i,j))  , (rv1+rv2)(j) * (m1+m2)(i,j) );\n  \n  if(rows>1)\n  {\n    DynMatrixType tmp = m1.topRows(rows/2), res;\n    VERIFY_IS_APPROX( (res = m1.topRows(rows/2) * rv1.asDiagonal()), tmp * rv1.asDiagonal() );\n    VERIFY_IS_APPROX( (res = v1.head(rows/2).asDiagonal()*m1.topRows(rows/2)), v1.head(rows/2).asDiagonal()*tmp );\n  }\n\n  BigMatrix big;\n  big.setZero(2*rows, 2*cols);\n  \n  big.block(i,j,rows,cols) = m1;\n  big.block(i,j,rows,cols) = v1.asDiagonal() * big.block(i,j,rows,cols);\n  \n  VERIFY_IS_APPROX((big.block(i,j,rows,cols)) , v1.asDiagonal() * m1 );\n  \n  big.block(i,j,rows,cols) = m1;\n  big.block(i,j,rows,cols) = big.block(i,j,rows,cols) * rv1.asDiagonal();\n  VERIFY_IS_APPROX((big.block(i,j,rows,cols)) , m1 * rv1.asDiagonal() );\n  \n  \n  // scalar multiple\n  VERIFY_IS_APPROX(LeftDiagonalMatrix(ldm1*s1).diagonal(), ldm1.diagonal() * s1);\n  VERIFY_IS_APPROX(LeftDiagonalMatrix(s1*ldm1).diagonal(), s1 * ldm1.diagonal());\n  \n  VERIFY_IS_APPROX(m1 * (rdm1 * s1), (m1 * rdm1) * s1);\n  VERIFY_IS_APPROX(m1 * (s1 * rdm1), (m1 * rdm1) * s1);\n  \n  // Diagonal to dense\n  sq_m1.setRandom();\n  sq_m2 = sq_m1;\n  VERIFY_IS_APPROX( (sq_m1 += (s1*v1).asDiagonal()), sq_m2 += (s1*v1).asDiagonal().toDenseMatrix() );\n  VERIFY_IS_APPROX( (sq_m1 -= (s1*v1).asDiagonal()), sq_m2 -= (s1*v1).asDiagonal().toDenseMatrix() );\n  VERIFY_IS_APPROX( (sq_m1 = (s1*v1).asDiagonal()), (s1*v1).asDiagonal().toDenseMatrix() );\n\n  sq_m1.setRandom();\n  sq_m2 = v1.asDiagonal();\n  sq_m2 = sq_m1 * sq_m2;\n  VERIFY_IS_APPROX( (sq_m1*v1.asDiagonal()).col(i), sq_m2.col(i) );\n  VERIFY_IS_APPROX( (sq_m1*v1.asDiagonal()).row(i), sq_m2.row(i) );\n\n  sq_m1 = v1.asDiagonal();\n  sq_m2 = v2.asDiagonal();\n  SquareMatrixType sq_m3 = v1.asDiagonal();\n  VERIFY_IS_APPROX( sq_m3 = v1.asDiagonal() + v2.asDiagonal(), sq_m1 + sq_m2);\n  VERIFY_IS_APPROX( sq_m3 = v1.asDiagonal() - v2.asDiagonal(), sq_m1 - sq_m2);\n  VERIFY_IS_APPROX( sq_m3 = v1.asDiagonal() - 2*v2.asDiagonal() + v1.asDiagonal(), sq_m1 - 2*sq_m2 + sq_m1);\n}\n\ntemplate<typename MatrixType> void as_scalar_product(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n  typedef Matrix<Scalar, Dynamic, Dynamic> DynMatrixType;\n  typedef Matrix<Scalar, Dynamic, 1> DynVectorType;\n  typedef Matrix<Scalar, 1, Dynamic> DynRowVectorType;\n\n  Index rows = m.rows();\n  Index depth = internal::random<Index>(1,EIGEN_TEST_MAX_SIZE);\n\n  VectorType v1 = VectorType::Random(rows);  \n  DynVectorType     dv1  = DynVectorType::Random(depth);\n  DynRowVectorType  drv1 = DynRowVectorType::Random(depth);\n  DynMatrixType     dm1  = dv1;\n  DynMatrixType     drm1 = drv1;\n  \n  Scalar s = v1(0);\n\n  VERIFY_IS_APPROX( v1.asDiagonal() * drv1, s*drv1 );\n  VERIFY_IS_APPROX( dv1 * v1.asDiagonal(), dv1*s );\n\n  VERIFY_IS_APPROX( v1.asDiagonal() * drm1, s*drm1 );\n  VERIFY_IS_APPROX( dm1 * v1.asDiagonal(), dm1*s );\n}\n\ntemplate<int>\nvoid bug987()\n{\n  Matrix3Xd points = Matrix3Xd::Random(3, 3);\n  Vector2d diag = Vector2d::Random();\n  Matrix2Xd tmp1 = points.topRows<2>(), res1, res2;\n  VERIFY_IS_APPROX( res1 = diag.asDiagonal() * points.topRows<2>(), res2 = diag.asDiagonal() * tmp1 );\n  Matrix2d tmp2 = points.topLeftCorner<2,2>();\n  VERIFY_IS_APPROX(( res1 = points.topLeftCorner<2,2>()*diag.asDiagonal()) , res2 = tmp2*diag.asDiagonal() );\n}\n\nEIGEN_DECLARE_TEST(diagonalmatrices)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( diagonalmatrices(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_1( as_scalar_product(Matrix<float, 1, 1>()) );\n\n    CALL_SUBTEST_2( diagonalmatrices(Matrix3f()) );\n    CALL_SUBTEST_3( diagonalmatrices(Matrix<double,3,3,RowMajor>()) );\n    CALL_SUBTEST_4( diagonalmatrices(Matrix4d()) );\n    CALL_SUBTEST_5( diagonalmatrices(Matrix<float,4,4,RowMajor>()) );\n    CALL_SUBTEST_6( diagonalmatrices(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( as_scalar_product(MatrixXcf(1,1)) );\n    CALL_SUBTEST_7( diagonalmatrices(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_8( diagonalmatrices(Matrix<double,Dynamic,Dynamic,RowMajor>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_9( diagonalmatrices(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_9( diagonalmatrices(MatrixXf(1,1)) );\n    CALL_SUBTEST_9( as_scalar_product(MatrixXf(1,1)) );\n  }\n  CALL_SUBTEST_10( bug987<0>() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/dontalign.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#if defined EIGEN_TEST_PART_1 || defined EIGEN_TEST_PART_2 || defined EIGEN_TEST_PART_3 || defined EIGEN_TEST_PART_4\n#define EIGEN_DONT_ALIGN\n#elif defined EIGEN_TEST_PART_5 || defined EIGEN_TEST_PART_6 || defined EIGEN_TEST_PART_7 || defined EIGEN_TEST_PART_8\n#define EIGEN_DONT_ALIGN_STATICALLY\n#endif\n\n#include \"main.h\"\n#include <Eigen/Dense>\n\ntemplate<typename MatrixType>\nvoid dontalign(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> SquareMatrixType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType a = MatrixType::Random(rows,cols);\n  SquareMatrixType square = SquareMatrixType::Random(rows,rows);\n  VectorType v = VectorType::Random(rows);\n\n  VERIFY_IS_APPROX(v, square * square.colPivHouseholderQr().solve(v));\n  square = square.inverse().eval();\n  a = square * a;\n  square = square*square;\n  v = square * v;\n  v = a.adjoint() * v;\n  VERIFY(square.determinant() != Scalar(0));\n\n  // bug 219: MapAligned() was giving an assert with EIGEN_DONT_ALIGN, because Map Flags were miscomputed\n  Scalar* array = internal::aligned_new<Scalar>(rows);\n  v = VectorType::MapAligned(array, rows);\n  internal::aligned_delete(array, rows);\n}\n\nEIGEN_DECLARE_TEST(dontalign)\n{\n#if defined EIGEN_TEST_PART_1 || defined EIGEN_TEST_PART_5\n  dontalign(Matrix3d());\n  dontalign(Matrix4f());\n#elif defined EIGEN_TEST_PART_2 || defined EIGEN_TEST_PART_6\n  dontalign(Matrix3cd());\n  dontalign(Matrix4cf());\n#elif defined EIGEN_TEST_PART_3 || defined EIGEN_TEST_PART_7\n  dontalign(Matrix<float, 32, 32>());\n  dontalign(Matrix<std::complex<float>, 32, 32>());\n#elif defined EIGEN_TEST_PART_4 || defined EIGEN_TEST_PART_8\n  dontalign(MatrixXd(32, 32));\n  dontalign(MatrixXcf(32, 32));\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/dynalloc.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#if EIGEN_MAX_ALIGN_BYTES>0\n#define ALIGNMENT EIGEN_MAX_ALIGN_BYTES\n#else\n#define ALIGNMENT 1\n#endif\n\ntypedef Matrix<float,16,1> Vector16f;\ntypedef Matrix<float,8,1> Vector8f;\n\nvoid check_handmade_aligned_malloc()\n{\n  for(int i = 1; i < 1000; i++)\n  {\n    char *p = (char*)internal::handmade_aligned_malloc(i);\n    VERIFY(internal::UIntPtr(p)%ALIGNMENT==0);\n    // if the buffer is wrongly allocated this will give a bad write --> check with valgrind\n    for(int j = 0; j < i; j++) p[j]=0;\n    internal::handmade_aligned_free(p);\n  }\n}\n\nvoid check_aligned_malloc()\n{\n  for(int i = ALIGNMENT; i < 1000; i++)\n  {\n    char *p = (char*)internal::aligned_malloc(i);\n    VERIFY(internal::UIntPtr(p)%ALIGNMENT==0);\n    // if the buffer is wrongly allocated this will give a bad write --> check with valgrind\n    for(int j = 0; j < i; j++) p[j]=0;\n    internal::aligned_free(p);\n  }\n}\n\nvoid check_aligned_new()\n{\n  for(int i = ALIGNMENT; i < 1000; i++)\n  {\n    float *p = internal::aligned_new<float>(i);\n    VERIFY(internal::UIntPtr(p)%ALIGNMENT==0);\n    // if the buffer is wrongly allocated this will give a bad write --> check with valgrind\n    for(int j = 0; j < i; j++) p[j]=0;\n    internal::aligned_delete(p,i);\n  }\n}\n\nvoid check_aligned_stack_alloc()\n{\n  for(int i = ALIGNMENT; i < 400; i++)\n  {\n    ei_declare_aligned_stack_constructed_variable(float,p,i,0);\n    VERIFY(internal::UIntPtr(p)%ALIGNMENT==0);\n    // if the buffer is wrongly allocated this will give a bad write --> check with valgrind\n    for(int j = 0; j < i; j++) p[j]=0;\n  }\n}\n\n\n// test compilation with both a struct and a class...\nstruct MyStruct\n{\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n  char dummychar;\n  Vector16f avec;\n};\n\nclass MyClassA\n{\n  public:\n    EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n    char dummychar;\n    Vector16f avec;\n};\n\ntemplate<typename T> void check_dynaligned()\n{\n  // TODO have to be updated once we support multiple alignment values\n  if(T::SizeAtCompileTime % ALIGNMENT == 0)\n  {\n    T* obj = new T;\n    VERIFY(T::NeedsToAlign==1);\n    VERIFY(internal::UIntPtr(obj)%ALIGNMENT==0);\n    delete obj;\n  }\n}\n\ntemplate<typename T> void check_custom_new_delete()\n{\n  {\n    T* t = new T;\n    delete t;\n  }\n  \n  {\n    std::size_t N = internal::random<std::size_t>(1,10);\n    T* t = new T[N];\n    delete[] t;\n  }\n  \n#if EIGEN_MAX_ALIGN_BYTES>0 && (!EIGEN_HAS_CXX17_OVERALIGN)\n  {\n    T* t = static_cast<T *>((T::operator new)(sizeof(T)));\n    (T::operator delete)(t, sizeof(T));\n  }\n  \n  {\n    T* t = static_cast<T *>((T::operator new)(sizeof(T)));\n    (T::operator delete)(t);\n  }\n#endif\n}\n\nEIGEN_DECLARE_TEST(dynalloc)\n{\n  // low level dynamic memory allocation\n  CALL_SUBTEST(check_handmade_aligned_malloc());\n  CALL_SUBTEST(check_aligned_malloc());\n  CALL_SUBTEST(check_aligned_new());\n  CALL_SUBTEST(check_aligned_stack_alloc());\n\n  for (int i=0; i<g_repeat*100; ++i)\n  {\n    CALL_SUBTEST( check_custom_new_delete<Vector4f>() );\n    CALL_SUBTEST( check_custom_new_delete<Vector2f>() );\n    CALL_SUBTEST( check_custom_new_delete<Matrix4f>() );\n    CALL_SUBTEST( check_custom_new_delete<MatrixXi>() );\n  }\n  \n  // check static allocation, who knows ?\n  #if EIGEN_MAX_STATIC_ALIGN_BYTES\n  for (int i=0; i<g_repeat*100; ++i)\n  {\n    CALL_SUBTEST(check_dynaligned<Vector4f>() );\n    CALL_SUBTEST(check_dynaligned<Vector2d>() );\n    CALL_SUBTEST(check_dynaligned<Matrix4f>() );\n    CALL_SUBTEST(check_dynaligned<Vector4d>() );\n    CALL_SUBTEST(check_dynaligned<Vector4i>() );\n    CALL_SUBTEST(check_dynaligned<Vector8f>() );\n    CALL_SUBTEST(check_dynaligned<Vector16f>() );\n  }\n\n  {\n    MyStruct foo0;  VERIFY(internal::UIntPtr(foo0.avec.data())%ALIGNMENT==0);\n    MyClassA fooA;  VERIFY(internal::UIntPtr(fooA.avec.data())%ALIGNMENT==0);\n  }\n  \n  // dynamic allocation, single object\n  for (int i=0; i<g_repeat*100; ++i)\n  {\n    MyStruct *foo0 = new MyStruct();  VERIFY(internal::UIntPtr(foo0->avec.data())%ALIGNMENT==0);\n    MyClassA *fooA = new MyClassA();  VERIFY(internal::UIntPtr(fooA->avec.data())%ALIGNMENT==0);\n    delete foo0;\n    delete fooA;\n  }\n\n  // dynamic allocation, array\n  const int N = 10;\n  for (int i=0; i<g_repeat*100; ++i)\n  {\n    MyStruct *foo0 = new MyStruct[N];  VERIFY(internal::UIntPtr(foo0->avec.data())%ALIGNMENT==0);\n    MyClassA *fooA = new MyClassA[N];  VERIFY(internal::UIntPtr(fooA->avec.data())%ALIGNMENT==0);\n    delete[] foo0;\n    delete[] fooA;\n  }\n  #endif\n  \n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/eigen2support.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN2_SUPPORT\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void eigen2support(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m3(rows, cols);\n\n  Scalar  s1 = internal::random<Scalar>(),\n          s2 = internal::random<Scalar>();\n\n  // scalar addition\n  VERIFY_IS_APPROX(m1.cwise() + s1, s1 + m1.cwise());\n  VERIFY_IS_APPROX(m1.cwise() + s1, MatrixType::Constant(rows,cols,s1) + m1);\n  VERIFY_IS_APPROX((m1*Scalar(2)).cwise() - s2, (m1+m1) - MatrixType::Constant(rows,cols,s2) );\n  m3 = m1;\n  m3.cwise() += s2;\n  VERIFY_IS_APPROX(m3, m1.cwise() + s2);\n  m3 = m1;\n  m3.cwise() -= s1;\n  VERIFY_IS_APPROX(m3, m1.cwise() - s1);\n\n  VERIFY_IS_EQUAL((m1.corner(TopLeft,1,1)), (m1.block(0,0,1,1)));\n  VERIFY_IS_EQUAL((m1.template corner<1,1>(TopLeft)), (m1.template block<1,1>(0,0)));\n  VERIFY_IS_EQUAL((m1.col(0).start(1)), (m1.col(0).segment(0,1)));\n  VERIFY_IS_EQUAL((m1.col(0).template start<1>()), (m1.col(0).segment(0,1)));\n  VERIFY_IS_EQUAL((m1.col(0).end(1)), (m1.col(0).segment(rows-1,1)));\n  VERIFY_IS_EQUAL((m1.col(0).template end<1>()), (m1.col(0).segment(rows-1,1)));\n  \n  using std::cos;\n  using numext::real;\n  using numext::abs2;\n  VERIFY_IS_EQUAL(ei_cos(s1), cos(s1));\n  VERIFY_IS_EQUAL(ei_real(s1), real(s1));\n  VERIFY_IS_EQUAL(ei_abs2(s1), abs2(s1));\n\n  m1.minor(0,0);\n}\n\nEIGEN_DECLARE_TEST(eigen2support)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( eigen2support(Matrix<double,1,1>()) );\n    CALL_SUBTEST_2( eigen2support(MatrixXd(1,1)) );\n    CALL_SUBTEST_4( eigen2support(Matrix3f()) );\n    CALL_SUBTEST_5( eigen2support(Matrix4d()) );\n    CALL_SUBTEST_2( eigen2support(MatrixXf(200,200)) );\n    CALL_SUBTEST_6( eigen2support(MatrixXcd(100,100)) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/eigensolver_complex.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <limits>\n#include <Eigen/Eigenvalues>\n#include <Eigen/LU>\n\ntemplate<typename MatrixType> bool find_pivot(typename MatrixType::Scalar tol, MatrixType &diffs, Index col=0)\n{\n  bool match = diffs.diagonal().sum() <= tol;\n  if(match || col==diffs.cols())\n  {\n    return match;\n  }\n  else\n  {\n    Index n = diffs.cols();\n    std::vector<std::pair<Index,Index> > transpositions;\n    for(Index i=col; i<n; ++i)\n    {\n      Index best_index(0);\n      if(diffs.col(col).segment(col,n-i).minCoeff(&best_index) > tol)\n        break;\n      \n      best_index += col;\n      \n      diffs.row(col).swap(diffs.row(best_index));\n      if(find_pivot(tol,diffs,col+1)) return true;\n      diffs.row(col).swap(diffs.row(best_index));\n      \n      // move current pivot to the end\n      diffs.row(n-(i-col)-1).swap(diffs.row(best_index));\n      transpositions.push_back(std::pair<Index,Index>(n-(i-col)-1,best_index));\n    }\n    // restore\n    for(Index k=transpositions.size()-1; k>=0; --k)\n      diffs.row(transpositions[k].first).swap(diffs.row(transpositions[k].second));\n  }\n  return false;\n}\n\n/* Check that two column vectors are approximately equal up to permutations.\n * Initially, this method checked that the k-th power sums are equal for all k = 1, ..., vec1.rows(),\n * however this strategy is numerically inacurate because of numerical cancellation issues.\n */\ntemplate<typename VectorType>\nvoid verify_is_approx_upto_permutation(const VectorType& vec1, const VectorType& vec2)\n{\n  typedef typename VectorType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  VERIFY(vec1.cols() == 1);\n  VERIFY(vec2.cols() == 1);\n  VERIFY(vec1.rows() == vec2.rows());\n  \n  Index n = vec1.rows();\n  RealScalar tol = test_precision<RealScalar>()*test_precision<RealScalar>()*numext::maxi(vec1.squaredNorm(),vec2.squaredNorm());\n  Matrix<RealScalar,Dynamic,Dynamic> diffs = (vec1.rowwise().replicate(n) - vec2.rowwise().replicate(n).transpose()).cwiseAbs2();\n  \n  VERIFY( find_pivot(tol, diffs) );\n}\n\n\ntemplate<typename MatrixType> void eigensolver(const MatrixType& m)\n{\n  /* this test covers the following files:\n     ComplexEigenSolver.h, and indirectly ComplexSchur.h\n  */\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  MatrixType a = MatrixType::Random(rows,cols);\n  MatrixType symmA =  a.adjoint() * a;\n\n  ComplexEigenSolver<MatrixType> ei0(symmA);\n  VERIFY_IS_EQUAL(ei0.info(), Success);\n  VERIFY_IS_APPROX(symmA * ei0.eigenvectors(), ei0.eigenvectors() * ei0.eigenvalues().asDiagonal());\n\n  ComplexEigenSolver<MatrixType> ei1(a);\n  VERIFY_IS_EQUAL(ei1.info(), Success);\n  VERIFY_IS_APPROX(a * ei1.eigenvectors(), ei1.eigenvectors() * ei1.eigenvalues().asDiagonal());\n  // Note: If MatrixType is real then a.eigenvalues() uses EigenSolver and thus\n  // another algorithm so results may differ slightly\n  verify_is_approx_upto_permutation(a.eigenvalues(), ei1.eigenvalues());\n\n  ComplexEigenSolver<MatrixType> ei2;\n  ei2.setMaxIterations(ComplexSchur<MatrixType>::m_maxIterationsPerRow * rows).compute(a);\n  VERIFY_IS_EQUAL(ei2.info(), Success);\n  VERIFY_IS_EQUAL(ei2.eigenvectors(), ei1.eigenvectors());\n  VERIFY_IS_EQUAL(ei2.eigenvalues(), ei1.eigenvalues());\n  if (rows > 2) {\n    ei2.setMaxIterations(1).compute(a);\n    VERIFY_IS_EQUAL(ei2.info(), NoConvergence);\n    VERIFY_IS_EQUAL(ei2.getMaxIterations(), 1);\n  }\n\n  ComplexEigenSolver<MatrixType> eiNoEivecs(a, false);\n  VERIFY_IS_EQUAL(eiNoEivecs.info(), Success);\n  VERIFY_IS_APPROX(ei1.eigenvalues(), eiNoEivecs.eigenvalues());\n\n  // Regression test for issue #66\n  MatrixType z = MatrixType::Zero(rows,cols);\n  ComplexEigenSolver<MatrixType> eiz(z);\n  VERIFY((eiz.eigenvalues().cwiseEqual(0)).all());\n\n  MatrixType id = MatrixType::Identity(rows, cols);\n  VERIFY_IS_APPROX(id.operatorNorm(), RealScalar(1));\n\n  if (rows > 1 && rows < 20)\n  {\n    // Test matrix with NaN\n    a(0,0) = std::numeric_limits<typename MatrixType::RealScalar>::quiet_NaN();\n    ComplexEigenSolver<MatrixType> eiNaN(a);\n    VERIFY_IS_EQUAL(eiNaN.info(), NoConvergence);\n  }\n\n  // regression test for bug 1098\n  {\n    ComplexEigenSolver<MatrixType> eig(a.adjoint() * a);\n    eig.compute(a.adjoint() * a);\n  }\n\n  // regression test for bug 478\n  {\n    a.setZero();\n    ComplexEigenSolver<MatrixType> ei3(a);\n    VERIFY_IS_EQUAL(ei3.info(), Success);\n    VERIFY_IS_MUCH_SMALLER_THAN(ei3.eigenvalues().norm(),RealScalar(1));\n    VERIFY((ei3.eigenvectors().transpose()*ei3.eigenvectors().transpose()).eval().isIdentity());\n  }\n}\n\ntemplate<typename MatrixType> void eigensolver_verify_assert(const MatrixType& m)\n{\n  ComplexEigenSolver<MatrixType> eig;\n  VERIFY_RAISES_ASSERT(eig.eigenvectors());\n  VERIFY_RAISES_ASSERT(eig.eigenvalues());\n\n  MatrixType a = MatrixType::Random(m.rows(),m.cols());\n  eig.compute(a, false);\n  VERIFY_RAISES_ASSERT(eig.eigenvectors());\n}\n\nEIGEN_DECLARE_TEST(eigensolver_complex)\n{\n  int s = 0;\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( eigensolver(Matrix4cf()) );\n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4);\n    CALL_SUBTEST_2( eigensolver(MatrixXcd(s,s)) );\n    CALL_SUBTEST_3( eigensolver(Matrix<std::complex<float>, 1, 1>()) );\n    CALL_SUBTEST_4( eigensolver(Matrix3f()) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n  }\n  CALL_SUBTEST_1( eigensolver_verify_assert(Matrix4cf()) );\n  s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4);\n  CALL_SUBTEST_2( eigensolver_verify_assert(MatrixXcd(s,s)) );\n  CALL_SUBTEST_3( eigensolver_verify_assert(Matrix<std::complex<float>, 1, 1>()) );\n  CALL_SUBTEST_4( eigensolver_verify_assert(Matrix3f()) );\n\n  // Test problem size constructors\n  CALL_SUBTEST_5(ComplexEigenSolver<MatrixXf> tmp(s));\n  \n  TEST_SET_BUT_UNUSED_VARIABLE(s)\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/eigensolver_generalized_real.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012-2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_RUNTIME_NO_MALLOC\n#include \"main.h\"\n#include <limits>\n#include <Eigen/Eigenvalues>\n#include <Eigen/LU>\n\ntemplate<typename MatrixType> void generalized_eigensolver_real(const MatrixType& m)\n{\n  /* this test covers the following files:\n     GeneralizedEigenSolver.h\n  */\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef std::complex<Scalar> ComplexScalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n\n  MatrixType a = MatrixType::Random(rows,cols);\n  MatrixType b = MatrixType::Random(rows,cols);\n  MatrixType a1 = MatrixType::Random(rows,cols);\n  MatrixType b1 = MatrixType::Random(rows,cols);\n  MatrixType spdA =  a.adjoint() * a + a1.adjoint() * a1;\n  MatrixType spdB =  b.adjoint() * b + b1.adjoint() * b1;\n\n  // lets compare to GeneralizedSelfAdjointEigenSolver\n  {\n    GeneralizedSelfAdjointEigenSolver<MatrixType> symmEig(spdA, spdB);\n    GeneralizedEigenSolver<MatrixType> eig(spdA, spdB);\n\n    VERIFY_IS_EQUAL(eig.eigenvalues().imag().cwiseAbs().maxCoeff(), 0);\n\n    VectorType realEigenvalues = eig.eigenvalues().real();\n    std::sort(realEigenvalues.data(), realEigenvalues.data()+realEigenvalues.size());\n    VERIFY_IS_APPROX(realEigenvalues, symmEig.eigenvalues());\n\n    // check eigenvectors\n    typename GeneralizedEigenSolver<MatrixType>::EigenvectorsType D = eig.eigenvalues().asDiagonal();\n    typename GeneralizedEigenSolver<MatrixType>::EigenvectorsType V = eig.eigenvectors();\n    VERIFY_IS_APPROX(spdA*V, spdB*V*D);\n  }\n\n  // non symmetric case:\n  {\n    GeneralizedEigenSolver<MatrixType> eig(rows);\n    // TODO enable full-prealocation of required memory, this probably requires an in-place mode for HessenbergDecomposition\n    //Eigen::internal::set_is_malloc_allowed(false);\n    eig.compute(a,b);\n    //Eigen::internal::set_is_malloc_allowed(true);\n    for(Index k=0; k<cols; ++k)\n    {\n      Matrix<ComplexScalar,Dynamic,Dynamic> tmp = (eig.betas()(k)*a).template cast<ComplexScalar>() - eig.alphas()(k)*b;\n      if(tmp.size()>1 && tmp.norm()>(std::numeric_limits<Scalar>::min)())\n        tmp /= tmp.norm();\n      VERIFY_IS_MUCH_SMALLER_THAN( std::abs(tmp.determinant()), Scalar(1) );\n    }\n    // check eigenvectors\n    typename GeneralizedEigenSolver<MatrixType>::EigenvectorsType D = eig.eigenvalues().asDiagonal();\n    typename GeneralizedEigenSolver<MatrixType>::EigenvectorsType V = eig.eigenvectors();\n    VERIFY_IS_APPROX(a*V, b*V*D);\n  }\n\n  // regression test for bug 1098\n  {\n    GeneralizedSelfAdjointEigenSolver<MatrixType> eig1(a.adjoint() * a,b.adjoint() * b);\n    eig1.compute(a.adjoint() * a,b.adjoint() * b);\n    GeneralizedEigenSolver<MatrixType> eig2(a.adjoint() * a,b.adjoint() * b);\n    eig2.compute(a.adjoint() * a,b.adjoint() * b);\n  }\n\n  // check without eigenvectors\n  {\n    GeneralizedEigenSolver<MatrixType> eig1(spdA, spdB, true);\n    GeneralizedEigenSolver<MatrixType> eig2(spdA, spdB, false);\n    VERIFY_IS_APPROX(eig1.eigenvalues(), eig2.eigenvalues());\n  }\n}\n\nEIGEN_DECLARE_TEST(eigensolver_generalized_real)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    int s = 0;\n    CALL_SUBTEST_1( generalized_eigensolver_real(Matrix4f()) );\n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4);\n    CALL_SUBTEST_2( generalized_eigensolver_real(MatrixXd(s,s)) );\n\n    // some trivial but implementation-wise special cases\n    CALL_SUBTEST_2( generalized_eigensolver_real(MatrixXd(1,1)) );\n    CALL_SUBTEST_2( generalized_eigensolver_real(MatrixXd(2,2)) );\n    CALL_SUBTEST_3( generalized_eigensolver_real(Matrix<double,1,1>()) );\n    CALL_SUBTEST_4( generalized_eigensolver_real(Matrix2d()) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/eigensolver_generic.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010,2012 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <limits>\n#include <Eigen/Eigenvalues>\n\ntemplate<typename EigType,typename MatType>\nvoid check_eigensolver_for_given_mat(const EigType &eig, const MatType& a)\n{\n  typedef typename NumTraits<typename MatType::Scalar>::Real RealScalar;\n  typedef Matrix<RealScalar, MatType::RowsAtCompileTime, 1> RealVectorType;\n  typedef typename std::complex<RealScalar> Complex;\n  Index n = a.rows();\n  VERIFY_IS_EQUAL(eig.info(), Success);\n  VERIFY_IS_APPROX(a * eig.pseudoEigenvectors(), eig.pseudoEigenvectors() * eig.pseudoEigenvalueMatrix());\n  VERIFY_IS_APPROX(a.template cast<Complex>() * eig.eigenvectors(),\n                   eig.eigenvectors() * eig.eigenvalues().asDiagonal());\n  VERIFY_IS_APPROX(eig.eigenvectors().colwise().norm(), RealVectorType::Ones(n).transpose());\n  VERIFY_IS_APPROX(a.eigenvalues(), eig.eigenvalues());\n}\n\ntemplate<typename MatrixType> void eigensolver(const MatrixType& m)\n{\n  /* this test covers the following files:\n     EigenSolver.h\n  */\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef typename std::complex<RealScalar> Complex;\n\n  MatrixType a = MatrixType::Random(rows,cols);\n  MatrixType a1 = MatrixType::Random(rows,cols);\n  MatrixType symmA =  a.adjoint() * a + a1.adjoint() * a1;\n\n  EigenSolver<MatrixType> ei0(symmA);\n  VERIFY_IS_EQUAL(ei0.info(), Success);\n  VERIFY_IS_APPROX(symmA * ei0.pseudoEigenvectors(), ei0.pseudoEigenvectors() * ei0.pseudoEigenvalueMatrix());\n  VERIFY_IS_APPROX((symmA.template cast<Complex>()) * (ei0.pseudoEigenvectors().template cast<Complex>()),\n    (ei0.pseudoEigenvectors().template cast<Complex>()) * (ei0.eigenvalues().asDiagonal()));\n\n  EigenSolver<MatrixType> ei1(a);\n  CALL_SUBTEST( check_eigensolver_for_given_mat(ei1,a) );\n\n  EigenSolver<MatrixType> ei2;\n  ei2.setMaxIterations(RealSchur<MatrixType>::m_maxIterationsPerRow * rows).compute(a);\n  VERIFY_IS_EQUAL(ei2.info(), Success);\n  VERIFY_IS_EQUAL(ei2.eigenvectors(), ei1.eigenvectors());\n  VERIFY_IS_EQUAL(ei2.eigenvalues(), ei1.eigenvalues());\n  if (rows > 2) {\n    ei2.setMaxIterations(1).compute(a);\n    VERIFY_IS_EQUAL(ei2.info(), NoConvergence);\n    VERIFY_IS_EQUAL(ei2.getMaxIterations(), 1);\n  }\n\n  EigenSolver<MatrixType> eiNoEivecs(a, false);\n  VERIFY_IS_EQUAL(eiNoEivecs.info(), Success);\n  VERIFY_IS_APPROX(ei1.eigenvalues(), eiNoEivecs.eigenvalues());\n  VERIFY_IS_APPROX(ei1.pseudoEigenvalueMatrix(), eiNoEivecs.pseudoEigenvalueMatrix());\n\n  MatrixType id = MatrixType::Identity(rows, cols);\n  VERIFY_IS_APPROX(id.operatorNorm(), RealScalar(1));\n\n  if (rows > 2 && rows < 20)\n  {\n    // Test matrix with NaN\n    a(0,0) = std::numeric_limits<typename MatrixType::RealScalar>::quiet_NaN();\n    EigenSolver<MatrixType> eiNaN(a);\n    VERIFY_IS_NOT_EQUAL(eiNaN.info(), Success);\n  }\n\n  // regression test for bug 1098\n  {\n    EigenSolver<MatrixType> eig(a.adjoint() * a);\n    eig.compute(a.adjoint() * a);\n  }\n\n  // regression test for bug 478\n  {\n    a.setZero();\n    EigenSolver<MatrixType> ei3(a);\n    VERIFY_IS_EQUAL(ei3.info(), Success);\n    VERIFY_IS_MUCH_SMALLER_THAN(ei3.eigenvalues().norm(),RealScalar(1));\n    VERIFY((ei3.eigenvectors().transpose()*ei3.eigenvectors().transpose()).eval().isIdentity());\n  }\n}\n\ntemplate<typename MatrixType> void eigensolver_verify_assert(const MatrixType& m)\n{\n  EigenSolver<MatrixType> eig;\n  VERIFY_RAISES_ASSERT(eig.eigenvectors());\n  VERIFY_RAISES_ASSERT(eig.pseudoEigenvectors());\n  VERIFY_RAISES_ASSERT(eig.pseudoEigenvalueMatrix());\n  VERIFY_RAISES_ASSERT(eig.eigenvalues());\n\n  MatrixType a = MatrixType::Random(m.rows(),m.cols());\n  eig.compute(a, false);\n  VERIFY_RAISES_ASSERT(eig.eigenvectors());\n  VERIFY_RAISES_ASSERT(eig.pseudoEigenvectors());\n}\n\n\ntemplate<typename CoeffType>\nMatrix<typename CoeffType::Scalar,Dynamic,Dynamic>\nmake_companion(const CoeffType& coeffs)\n{\n  Index n = coeffs.size()-1;\n  Matrix<typename CoeffType::Scalar,Dynamic,Dynamic> res(n,n);\n  res.setZero();\n\tres.row(0) = -coeffs.tail(n) / coeffs(0);\n\tres.diagonal(-1).setOnes();\n  return res;\n}\n\ntemplate<int>\nvoid eigensolver_generic_extra()\n{\n  {\n    // regression test for bug 793\n    MatrixXd a(3,3);\n    a << 0,  0,  1,\n        1,  1, 1,\n        1, 1e+200,  1;\n    Eigen::EigenSolver<MatrixXd> eig(a);\n    double scale = 1e-200; // scale to avoid overflow during the comparisons\n    VERIFY_IS_APPROX(a * eig.pseudoEigenvectors()*scale, eig.pseudoEigenvectors() * eig.pseudoEigenvalueMatrix()*scale);\n    VERIFY_IS_APPROX(a * eig.eigenvectors()*scale, eig.eigenvectors() * eig.eigenvalues().asDiagonal()*scale);\n  }\n  {\n    // check a case where all eigenvalues are null.\n    MatrixXd a(2,2);\n    a << 1,  1,\n        -1, -1;\n    Eigen::EigenSolver<MatrixXd> eig(a);\n    VERIFY_IS_APPROX(eig.pseudoEigenvectors().squaredNorm(), 2.);\n    VERIFY_IS_APPROX((a * eig.pseudoEigenvectors()).norm()+1., 1.);\n    VERIFY_IS_APPROX((eig.pseudoEigenvectors() * eig.pseudoEigenvalueMatrix()).norm()+1., 1.);\n    VERIFY_IS_APPROX((a * eig.eigenvectors()).norm()+1., 1.);\n    VERIFY_IS_APPROX((eig.eigenvectors() * eig.eigenvalues().asDiagonal()).norm()+1., 1.);\n  }\n\n  // regression test for bug 933\n  {\n    {\n      VectorXd coeffs(5); coeffs << 1, -3, -175, -225, 2250;\n      MatrixXd C = make_companion(coeffs);\n      EigenSolver<MatrixXd> eig(C);\n      CALL_SUBTEST( check_eigensolver_for_given_mat(eig,C) );\n    }\n    {\n      // this test is tricky because it requires high accuracy in smallest eigenvalues\n      VectorXd coeffs(5); coeffs << 6.154671e-15, -1.003870e-10, -9.819570e-01, 3.995715e+03, 2.211511e+08;\n      MatrixXd C = make_companion(coeffs);\n      EigenSolver<MatrixXd> eig(C);\n      CALL_SUBTEST( check_eigensolver_for_given_mat(eig,C) );\n      Index n = C.rows();\n      for(Index i=0;i<n;++i)\n      {\n        typedef std::complex<double> Complex;\n        MatrixXcd ac = C.cast<Complex>();\n        ac.diagonal().array() -= eig.eigenvalues()(i);\n        VectorXd sv = ac.jacobiSvd().singularValues();\n        // comparing to sv(0) is not enough here to catch the \"bug\",\n        // the hard-coded 1.0 is important!\n        VERIFY_IS_MUCH_SMALLER_THAN(sv(n-1), 1.0);\n      }\n    }\n  }\n  // regression test for bug 1557\n  {\n    // this test is interesting because it contains zeros on the diagonal.\n    MatrixXd A_bug1557(3,3);\n    A_bug1557 << 0, 0, 0, 1, 0, 0.5887907064808635127, 0, 1, 0;\n    EigenSolver<MatrixXd> eig(A_bug1557);\n    CALL_SUBTEST( check_eigensolver_for_given_mat(eig,A_bug1557) );\n  }\n\n  // regression test for bug 1174\n  {\n    Index n = 12;\n    MatrixXf A_bug1174(n,n);\n    A_bug1174 <<  262144, 0, 0, 262144, 786432, 0, 0, 0, 0, 0, 0, 786432,\n                  262144, 0, 0, 262144, 786432, 0, 0, 0, 0, 0, 0, 786432,\n                  262144, 0, 0, 262144, 786432, 0, 0, 0, 0, 0, 0, 786432,\n                  262144, 0, 0, 262144, 786432, 0, 0, 0, 0, 0, 0, 786432,\n                  0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,\n                  0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,\n                  0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,\n                  0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,\n                  0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,\n                  0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,\n                  0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,\n                  0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0;\n    EigenSolver<MatrixXf> eig(A_bug1174);\n    CALL_SUBTEST( check_eigensolver_for_given_mat(eig,A_bug1174) );\n  }\n}\n\nEIGEN_DECLARE_TEST(eigensolver_generic)\n{\n  int s = 0;\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( eigensolver(Matrix4f()) );\n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4);\n    CALL_SUBTEST_2( eigensolver(MatrixXd(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n\n    // some trivial but implementation-wise tricky cases\n    CALL_SUBTEST_2( eigensolver(MatrixXd(1,1)) );\n    CALL_SUBTEST_2( eigensolver(MatrixXd(2,2)) );\n    CALL_SUBTEST_3( eigensolver(Matrix<double,1,1>()) );\n    CALL_SUBTEST_4( eigensolver(Matrix2d()) );\n  }\n\n  CALL_SUBTEST_1( eigensolver_verify_assert(Matrix4f()) );\n  s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4);\n  CALL_SUBTEST_2( eigensolver_verify_assert(MatrixXd(s,s)) );\n  CALL_SUBTEST_3( eigensolver_verify_assert(Matrix<double,1,1>()) );\n  CALL_SUBTEST_4( eigensolver_verify_assert(Matrix2d()) );\n\n  // Test problem size constructors\n  CALL_SUBTEST_5(EigenSolver<MatrixXf> tmp(s));\n\n  // regression test for bug 410\n  CALL_SUBTEST_2(\n  {\n     MatrixXd A(1,1);\n     A(0,0) = std::sqrt(-1.); // is Not-a-Number\n     Eigen::EigenSolver<MatrixXd> solver(A);\n     VERIFY_IS_EQUAL(solver.info(), NumericalIssue);\n  }\n  );\n  \n  CALL_SUBTEST_2( eigensolver_generic_extra<0>() );\n  \n  TEST_SET_BUT_UNUSED_VARIABLE(s)\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/eigensolver_selfadjoint.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include \"svd_fill.h\"\n#include <limits>\n#include <Eigen/Eigenvalues>\n#include <Eigen/SparseCore>\n\n\ntemplate<typename MatrixType> void selfadjointeigensolver_essential_check(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  RealScalar eival_eps = numext::mini<RealScalar>(test_precision<RealScalar>(),  NumTraits<Scalar>::dummy_precision()*20000);\n  \n  SelfAdjointEigenSolver<MatrixType> eiSymm(m);\n  VERIFY_IS_EQUAL(eiSymm.info(), Success);\n\n  RealScalar scaling = m.cwiseAbs().maxCoeff();\n\n  if(scaling<(std::numeric_limits<RealScalar>::min)())\n  {\n    VERIFY(eiSymm.eigenvalues().cwiseAbs().maxCoeff() <= (std::numeric_limits<RealScalar>::min)());\n  }\n  else\n  {\n    VERIFY_IS_APPROX((m.template selfadjointView<Lower>() * eiSymm.eigenvectors())/scaling,\n                     (eiSymm.eigenvectors() * eiSymm.eigenvalues().asDiagonal())/scaling);\n  }\n  VERIFY_IS_APPROX(m.template selfadjointView<Lower>().eigenvalues(), eiSymm.eigenvalues());\n  VERIFY_IS_UNITARY(eiSymm.eigenvectors());\n\n  if(m.cols()<=4)\n  {\n    SelfAdjointEigenSolver<MatrixType> eiDirect;\n    eiDirect.computeDirect(m);  \n    VERIFY_IS_EQUAL(eiDirect.info(), Success);\n    if(! eiSymm.eigenvalues().isApprox(eiDirect.eigenvalues(), eival_eps) )\n    {\n      std::cerr << \"reference eigenvalues: \" << eiSymm.eigenvalues().transpose() << \"\\n\"\n                << \"obtained eigenvalues:  \" << eiDirect.eigenvalues().transpose() << \"\\n\"\n                << \"diff:                  \" << (eiSymm.eigenvalues()-eiDirect.eigenvalues()).transpose() << \"\\n\"\n                << \"error (eps):           \" << (eiSymm.eigenvalues()-eiDirect.eigenvalues()).norm() / eiSymm.eigenvalues().norm() << \"  (\" << eival_eps << \")\\n\";\n    }\n    if(scaling<(std::numeric_limits<RealScalar>::min)())\n    {\n      VERIFY(eiDirect.eigenvalues().cwiseAbs().maxCoeff() <= (std::numeric_limits<RealScalar>::min)());\n    }\n    else\n    {\n      VERIFY_IS_APPROX(eiSymm.eigenvalues()/scaling, eiDirect.eigenvalues()/scaling);\n      VERIFY_IS_APPROX((m.template selfadjointView<Lower>() * eiDirect.eigenvectors())/scaling,\n                       (eiDirect.eigenvectors() * eiDirect.eigenvalues().asDiagonal())/scaling);\n      VERIFY_IS_APPROX(m.template selfadjointView<Lower>().eigenvalues()/scaling, eiDirect.eigenvalues()/scaling);\n    }\n\n    VERIFY_IS_UNITARY(eiDirect.eigenvectors());\n  }\n}\n\ntemplate<typename MatrixType> void selfadjointeigensolver(const MatrixType& m)\n{\n  /* this test covers the following files:\n     EigenSolver.h, SelfAdjointEigenSolver.h (and indirectly: Tridiagonalization.h)\n  */\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  RealScalar largerEps = 10*test_precision<RealScalar>();\n\n  MatrixType a = MatrixType::Random(rows,cols);\n  MatrixType a1 = MatrixType::Random(rows,cols);\n  MatrixType symmA =  a.adjoint() * a + a1.adjoint() * a1;\n  MatrixType symmC = symmA;\n  \n  svd_fill_random(symmA,Symmetric);\n\n  symmA.template triangularView<StrictlyUpper>().setZero();\n  symmC.template triangularView<StrictlyUpper>().setZero();\n\n  MatrixType b = MatrixType::Random(rows,cols);\n  MatrixType b1 = MatrixType::Random(rows,cols);\n  MatrixType symmB = b.adjoint() * b + b1.adjoint() * b1;\n  symmB.template triangularView<StrictlyUpper>().setZero();\n  \n  CALL_SUBTEST( selfadjointeigensolver_essential_check(symmA) );\n\n  SelfAdjointEigenSolver<MatrixType> eiSymm(symmA);\n  // generalized eigen pb\n  GeneralizedSelfAdjointEigenSolver<MatrixType> eiSymmGen(symmC, symmB);\n\n  SelfAdjointEigenSolver<MatrixType> eiSymmNoEivecs(symmA, false);\n  VERIFY_IS_EQUAL(eiSymmNoEivecs.info(), Success);\n  VERIFY_IS_APPROX(eiSymm.eigenvalues(), eiSymmNoEivecs.eigenvalues());\n  \n  // generalized eigen problem Ax = lBx\n  eiSymmGen.compute(symmC, symmB,Ax_lBx);\n  VERIFY_IS_EQUAL(eiSymmGen.info(), Success);\n  VERIFY((symmC.template selfadjointView<Lower>() * eiSymmGen.eigenvectors()).isApprox(\n          symmB.template selfadjointView<Lower>() * (eiSymmGen.eigenvectors() * eiSymmGen.eigenvalues().asDiagonal()), largerEps));\n\n  // generalized eigen problem BAx = lx\n  eiSymmGen.compute(symmC, symmB,BAx_lx);\n  VERIFY_IS_EQUAL(eiSymmGen.info(), Success);\n  VERIFY((symmB.template selfadjointView<Lower>() * (symmC.template selfadjointView<Lower>() * eiSymmGen.eigenvectors())).isApprox(\n         (eiSymmGen.eigenvectors() * eiSymmGen.eigenvalues().asDiagonal()), largerEps));\n\n  // generalized eigen problem ABx = lx\n  eiSymmGen.compute(symmC, symmB,ABx_lx);\n  VERIFY_IS_EQUAL(eiSymmGen.info(), Success);\n  VERIFY((symmC.template selfadjointView<Lower>() * (symmB.template selfadjointView<Lower>() * eiSymmGen.eigenvectors())).isApprox(\n         (eiSymmGen.eigenvectors() * eiSymmGen.eigenvalues().asDiagonal()), largerEps));\n\n\n  eiSymm.compute(symmC);\n  MatrixType sqrtSymmA = eiSymm.operatorSqrt();\n  VERIFY_IS_APPROX(MatrixType(symmC.template selfadjointView<Lower>()), sqrtSymmA*sqrtSymmA);\n  VERIFY_IS_APPROX(sqrtSymmA, symmC.template selfadjointView<Lower>()*eiSymm.operatorInverseSqrt());\n\n  MatrixType id = MatrixType::Identity(rows, cols);\n  VERIFY_IS_APPROX(id.template selfadjointView<Lower>().operatorNorm(), RealScalar(1));\n\n  SelfAdjointEigenSolver<MatrixType> eiSymmUninitialized;\n  VERIFY_RAISES_ASSERT(eiSymmUninitialized.info());\n  VERIFY_RAISES_ASSERT(eiSymmUninitialized.eigenvalues());\n  VERIFY_RAISES_ASSERT(eiSymmUninitialized.eigenvectors());\n  VERIFY_RAISES_ASSERT(eiSymmUninitialized.operatorSqrt());\n  VERIFY_RAISES_ASSERT(eiSymmUninitialized.operatorInverseSqrt());\n\n  eiSymmUninitialized.compute(symmA, false);\n  VERIFY_RAISES_ASSERT(eiSymmUninitialized.eigenvectors());\n  VERIFY_RAISES_ASSERT(eiSymmUninitialized.operatorSqrt());\n  VERIFY_RAISES_ASSERT(eiSymmUninitialized.operatorInverseSqrt());\n\n  // test Tridiagonalization's methods\n  Tridiagonalization<MatrixType> tridiag(symmC);\n  VERIFY_IS_APPROX(tridiag.diagonal(), tridiag.matrixT().diagonal());\n  VERIFY_IS_APPROX(tridiag.subDiagonal(), tridiag.matrixT().template diagonal<-1>());\n  Matrix<RealScalar,Dynamic,Dynamic> T = tridiag.matrixT();\n  if(rows>1 && cols>1) {\n    // FIXME check that upper and lower part are 0:\n    //VERIFY(T.topRightCorner(rows-2, cols-2).template triangularView<Upper>().isZero());\n  }\n  VERIFY_IS_APPROX(tridiag.diagonal(), T.diagonal());\n  VERIFY_IS_APPROX(tridiag.subDiagonal(), T.template diagonal<1>());\n  VERIFY_IS_APPROX(MatrixType(symmC.template selfadjointView<Lower>()), tridiag.matrixQ() * tridiag.matrixT().eval() * MatrixType(tridiag.matrixQ()).adjoint());\n  VERIFY_IS_APPROX(MatrixType(symmC.template selfadjointView<Lower>()), tridiag.matrixQ() * tridiag.matrixT() * tridiag.matrixQ().adjoint());\n  \n  // Test computation of eigenvalues from tridiagonal matrix\n  if(rows > 1)\n  {\n    SelfAdjointEigenSolver<MatrixType> eiSymmTridiag;\n    eiSymmTridiag.computeFromTridiagonal(tridiag.matrixT().diagonal(), tridiag.matrixT().diagonal(-1), ComputeEigenvectors);\n    VERIFY_IS_APPROX(eiSymm.eigenvalues(), eiSymmTridiag.eigenvalues());\n    VERIFY_IS_APPROX(tridiag.matrixT(), eiSymmTridiag.eigenvectors().real() * eiSymmTridiag.eigenvalues().asDiagonal() * eiSymmTridiag.eigenvectors().real().transpose());\n  }\n\n  if (rows > 1 && rows < 20)\n  {\n    // Test matrix with NaN\n    symmC(0,0) = std::numeric_limits<typename MatrixType::RealScalar>::quiet_NaN();\n    SelfAdjointEigenSolver<MatrixType> eiSymmNaN(symmC);\n    VERIFY_IS_EQUAL(eiSymmNaN.info(), NoConvergence);\n  }\n\n  // regression test for bug 1098\n  {\n    SelfAdjointEigenSolver<MatrixType> eig(a.adjoint() * a);\n    eig.compute(a.adjoint() * a);\n  }\n\n  // regression test for bug 478\n  {\n    a.setZero();\n    SelfAdjointEigenSolver<MatrixType> ei3(a);\n    VERIFY_IS_EQUAL(ei3.info(), Success);\n    VERIFY_IS_MUCH_SMALLER_THAN(ei3.eigenvalues().norm(),RealScalar(1));\n    VERIFY((ei3.eigenvectors().transpose()*ei3.eigenvectors().transpose()).eval().isIdentity());\n  }\n}\n\ntemplate<int>\nvoid bug_854()\n{\n  Matrix3d m;\n  m << 850.961, 51.966, 0,\n       51.966, 254.841, 0,\n            0,       0, 0;\n  selfadjointeigensolver_essential_check(m);\n}\n\ntemplate<int>\nvoid bug_1014()\n{\n  Matrix3d m;\n  m <<        0.11111111111111114658, 0, 0,\n       0,     0.11111111111111109107, 0,\n       0, 0,  0.11111111111111107719;\n  selfadjointeigensolver_essential_check(m);\n}\n\ntemplate<int>\nvoid bug_1225()\n{\n  Matrix3d m1, m2;\n  m1.setRandom();\n  m1 = m1*m1.transpose();\n  m2 = m1.triangularView<Upper>();\n  SelfAdjointEigenSolver<Matrix3d> eig1(m1);\n  SelfAdjointEigenSolver<Matrix3d> eig2(m2.selfadjointView<Upper>());\n  VERIFY_IS_APPROX(eig1.eigenvalues(), eig2.eigenvalues());\n}\n\ntemplate<int>\nvoid bug_1204()\n{\n  SparseMatrix<double> A(2,2);\n  A.setIdentity();\n  SelfAdjointEigenSolver<Eigen::SparseMatrix<double> > eig(A);\n}\n\nEIGEN_DECLARE_TEST(eigensolver_selfadjoint)\n{\n  int s = 0;\n  for(int i = 0; i < g_repeat; i++) {\n\n    // trivial test for 1x1 matrices:\n    CALL_SUBTEST_1( selfadjointeigensolver(Matrix<float, 1, 1>()));\n    CALL_SUBTEST_1( selfadjointeigensolver(Matrix<double, 1, 1>()));\n    CALL_SUBTEST_1( selfadjointeigensolver(Matrix<std::complex<double>, 1, 1>()));\n\n    // very important to test 3x3 and 2x2 matrices since we provide special paths for them\n    CALL_SUBTEST_12( selfadjointeigensolver(Matrix2f()) );\n    CALL_SUBTEST_12( selfadjointeigensolver(Matrix2d()) );\n    CALL_SUBTEST_12( selfadjointeigensolver(Matrix2cd()) );\n    CALL_SUBTEST_13( selfadjointeigensolver(Matrix3f()) );\n    CALL_SUBTEST_13( selfadjointeigensolver(Matrix3d()) );\n    CALL_SUBTEST_13( selfadjointeigensolver(Matrix3cd()) );\n    CALL_SUBTEST_2( selfadjointeigensolver(Matrix4d()) );\n    CALL_SUBTEST_2( selfadjointeigensolver(Matrix4cd()) );\n    \n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4);\n    CALL_SUBTEST_3( selfadjointeigensolver(MatrixXf(s,s)) );\n    CALL_SUBTEST_4( selfadjointeigensolver(MatrixXd(s,s)) );\n    CALL_SUBTEST_5( selfadjointeigensolver(MatrixXcd(s,s)) );\n    CALL_SUBTEST_9( selfadjointeigensolver(Matrix<std::complex<double>,Dynamic,Dynamic,RowMajor>(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n\n    // some trivial but implementation-wise tricky cases\n    CALL_SUBTEST_4( selfadjointeigensolver(MatrixXd(1,1)) );\n    CALL_SUBTEST_4( selfadjointeigensolver(MatrixXd(2,2)) );\n    CALL_SUBTEST_5( selfadjointeigensolver(MatrixXcd(1,1)) );\n    CALL_SUBTEST_5( selfadjointeigensolver(MatrixXcd(2,2)) );\n    CALL_SUBTEST_6( selfadjointeigensolver(Matrix<double,1,1>()) );\n    CALL_SUBTEST_7( selfadjointeigensolver(Matrix<double,2,2>()) );\n  }\n  \n  CALL_SUBTEST_13( bug_854<0>() );\n  CALL_SUBTEST_13( bug_1014<0>() );\n  CALL_SUBTEST_13( bug_1204<0>() );\n  CALL_SUBTEST_13( bug_1225<0>() );\n\n  // Test problem size constructors\n  s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4);\n  CALL_SUBTEST_8(SelfAdjointEigenSolver<MatrixXf> tmp1(s));\n  CALL_SUBTEST_8(Tridiagonalization<MatrixXf> tmp2(s));\n  \n  TEST_SET_BUT_UNUSED_VARIABLE(s)\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/evaluator_common.h",
    "content": ""
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/evaluators.cpp",
    "content": "\n#include \"main.h\"\n\nnamespace Eigen {\n\n  template<typename Lhs,typename Rhs>\n  const Product<Lhs,Rhs>\n  prod(const Lhs& lhs, const Rhs& rhs)\n  {\n    return Product<Lhs,Rhs>(lhs,rhs);\n  }\n\n  template<typename Lhs,typename Rhs>\n  const Product<Lhs,Rhs,LazyProduct>\n  lazyprod(const Lhs& lhs, const Rhs& rhs)\n  {\n    return Product<Lhs,Rhs,LazyProduct>(lhs,rhs);\n  }\n  \n  template<typename DstXprType, typename SrcXprType>\n  EIGEN_STRONG_INLINE\n  DstXprType& copy_using_evaluator(const EigenBase<DstXprType> &dst, const SrcXprType &src)\n  {\n    call_assignment(dst.const_cast_derived(), src.derived(), internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar>());\n    return dst.const_cast_derived();\n  }\n  \n  template<typename DstXprType, template <typename> class StorageBase, typename SrcXprType>\n  EIGEN_STRONG_INLINE\n  const DstXprType& copy_using_evaluator(const NoAlias<DstXprType, StorageBase>& dst, const SrcXprType &src)\n  {\n    call_assignment(dst, src.derived(), internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar>());\n    return dst.expression();\n  }\n  \n  template<typename DstXprType, typename SrcXprType>\n  EIGEN_STRONG_INLINE\n  DstXprType& copy_using_evaluator(const PlainObjectBase<DstXprType> &dst, const SrcXprType &src)\n  {\n    #ifdef EIGEN_NO_AUTOMATIC_RESIZING\n    eigen_assert((dst.size()==0 || (IsVectorAtCompileTime ? (dst.size() == src.size())\n                                                          : (dst.rows() == src.rows() && dst.cols() == src.cols())))\n                && \"Size mismatch. Automatic resizing is disabled because EIGEN_NO_AUTOMATIC_RESIZING is defined\");\n  #else\n    dst.const_cast_derived().resizeLike(src.derived());\n  #endif\n    \n    call_assignment(dst.const_cast_derived(), src.derived(), internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar>());\n    return dst.const_cast_derived();\n  }\n\n  template<typename DstXprType, typename SrcXprType>\n  void add_assign_using_evaluator(const DstXprType& dst, const SrcXprType& src)\n  {\n    typedef typename DstXprType::Scalar Scalar;\n    call_assignment(const_cast<DstXprType&>(dst), src.derived(), internal::add_assign_op<Scalar,typename SrcXprType::Scalar>());\n  }\n\n  template<typename DstXprType, typename SrcXprType>\n  void subtract_assign_using_evaluator(const DstXprType& dst, const SrcXprType& src)\n  {\n    typedef typename DstXprType::Scalar Scalar;\n    call_assignment(const_cast<DstXprType&>(dst), src.derived(), internal::sub_assign_op<Scalar,typename SrcXprType::Scalar>());\n  }\n\n  template<typename DstXprType, typename SrcXprType>\n  void multiply_assign_using_evaluator(const DstXprType& dst, const SrcXprType& src)\n  {\n    typedef typename DstXprType::Scalar Scalar;\n    call_assignment(dst.const_cast_derived(), src.derived(), internal::mul_assign_op<Scalar,typename SrcXprType::Scalar>());\n  }\n\n  template<typename DstXprType, typename SrcXprType>\n  void divide_assign_using_evaluator(const DstXprType& dst, const SrcXprType& src)\n  {\n    typedef typename DstXprType::Scalar Scalar;\n    call_assignment(dst.const_cast_derived(), src.derived(), internal::div_assign_op<Scalar,typename SrcXprType::Scalar>());\n  }\n  \n  template<typename DstXprType, typename SrcXprType>\n  void swap_using_evaluator(const DstXprType& dst, const SrcXprType& src)\n  {\n    typedef typename DstXprType::Scalar Scalar;\n    call_assignment(dst.const_cast_derived(), src.const_cast_derived(), internal::swap_assign_op<Scalar>());\n  }\n\n  namespace internal {\n    template<typename Dst, template <typename> class StorageBase, typename Src, typename Func>\n    EIGEN_DEVICE_FUNC void call_assignment(const NoAlias<Dst,StorageBase>& dst, const Src& src, const Func& func)\n    {\n      call_assignment_no_alias(dst.expression(), src, func);\n    }\n\n    template<typename Dst, template <typename> class StorageBase, typename Src, typename Func>\n    EIGEN_DEVICE_FUNC void call_restricted_packet_assignment(const NoAlias<Dst,StorageBase>& dst, const Src& src, const Func& func)\n    {\n      call_restricted_packet_assignment_no_alias(dst.expression(), src, func);\n    }\n  }\n  \n}\n\ntemplate<typename XprType> long get_cost(const XprType& ) { return Eigen::internal::evaluator<XprType>::CoeffReadCost; }\n\nusing namespace std;\n\n#define VERIFY_IS_APPROX_EVALUATOR(DEST,EXPR) VERIFY_IS_APPROX(copy_using_evaluator(DEST,(EXPR)), (EXPR).eval());\n#define VERIFY_IS_APPROX_EVALUATOR2(DEST,EXPR,REF) VERIFY_IS_APPROX(copy_using_evaluator(DEST,(EXPR)), (REF).eval());\n\nEIGEN_DECLARE_TEST(evaluators)\n{\n  // Testing Matrix evaluator and Transpose\n  Vector2d v = Vector2d::Random();\n  const Vector2d v_const(v);\n  Vector2d v2;\n  RowVector2d w;\n\n  VERIFY_IS_APPROX_EVALUATOR(v2, v);\n  VERIFY_IS_APPROX_EVALUATOR(v2, v_const);\n\n  // Testing Transpose\n  VERIFY_IS_APPROX_EVALUATOR(w, v.transpose()); // Transpose as rvalue\n  VERIFY_IS_APPROX_EVALUATOR(w, v_const.transpose());\n\n  copy_using_evaluator(w.transpose(), v); // Transpose as lvalue\n  VERIFY_IS_APPROX(w,v.transpose().eval());\n\n  copy_using_evaluator(w.transpose(), v_const);\n  VERIFY_IS_APPROX(w,v_const.transpose().eval());\n\n  // Testing Array evaluator\n  {\n    ArrayXXf a(2,3);\n    ArrayXXf b(3,2);\n    a << 1,2,3, 4,5,6;\n    const ArrayXXf a_const(a);\n\n    VERIFY_IS_APPROX_EVALUATOR(b, a.transpose());\n\n    VERIFY_IS_APPROX_EVALUATOR(b, a_const.transpose());\n\n    // Testing CwiseNullaryOp evaluator\n    copy_using_evaluator(w, RowVector2d::Random());\n    VERIFY((w.array() >= -1).all() && (w.array() <= 1).all()); // not easy to test ...\n\n    VERIFY_IS_APPROX_EVALUATOR(w, RowVector2d::Zero());\n\n    VERIFY_IS_APPROX_EVALUATOR(w, RowVector2d::Constant(3));\n    \n    // mix CwiseNullaryOp and transpose\n    VERIFY_IS_APPROX_EVALUATOR(w, Vector2d::Zero().transpose());\n  }\n\n  {\n    // test product expressions\n    int s = internal::random<int>(1,100);\n    MatrixXf a(s,s), b(s,s), c(s,s), d(s,s);\n    a.setRandom();\n    b.setRandom();\n    c.setRandom();\n    d.setRandom();\n    VERIFY_IS_APPROX_EVALUATOR(d, (a + b));\n    VERIFY_IS_APPROX_EVALUATOR(d, (a + b).transpose());\n    VERIFY_IS_APPROX_EVALUATOR2(d, prod(a,b), a*b);\n    VERIFY_IS_APPROX_EVALUATOR2(d.noalias(), prod(a,b), a*b);\n    VERIFY_IS_APPROX_EVALUATOR2(d, prod(a,b) + c, a*b + c);\n    VERIFY_IS_APPROX_EVALUATOR2(d, s * prod(a,b), s * a*b);\n    VERIFY_IS_APPROX_EVALUATOR2(d, prod(a,b).transpose(), (a*b).transpose());\n    VERIFY_IS_APPROX_EVALUATOR2(d, prod(a,b) + prod(b,c), a*b + b*c);\n\n    // check that prod works even with aliasing present\n    c = a*a;\n    copy_using_evaluator(a, prod(a,a));\n    VERIFY_IS_APPROX(a,c);\n\n    // check compound assignment of products\n    d = c;\n    add_assign_using_evaluator(c.noalias(), prod(a,b));\n    d.noalias() += a*b;\n    VERIFY_IS_APPROX(c, d);\n\n    d = c;\n    subtract_assign_using_evaluator(c.noalias(), prod(a,b));\n    d.noalias() -= a*b;\n    VERIFY_IS_APPROX(c, d);\n  }\n\n  {\n    // test product with all possible sizes\n    int s = internal::random<int>(1,100);\n    Matrix<float,      1,      1> m11, res11;  m11.setRandom(1,1);\n    Matrix<float,      1,      4> m14, res14;  m14.setRandom(1,4);\n    Matrix<float,      1,Dynamic> m1X, res1X;  m1X.setRandom(1,s);\n    Matrix<float,      4,      1> m41, res41;  m41.setRandom(4,1);\n    Matrix<float,      4,      4> m44, res44;  m44.setRandom(4,4);\n    Matrix<float,      4,Dynamic> m4X, res4X;  m4X.setRandom(4,s);\n    Matrix<float,Dynamic,      1> mX1, resX1;  mX1.setRandom(s,1);\n    Matrix<float,Dynamic,      4> mX4, resX4;  mX4.setRandom(s,4);\n    Matrix<float,Dynamic,Dynamic> mXX, resXX;  mXX.setRandom(s,s);\n\n    VERIFY_IS_APPROX_EVALUATOR2(res11, prod(m11,m11), m11*m11);\n    VERIFY_IS_APPROX_EVALUATOR2(res11, prod(m14,m41), m14*m41);\n    VERIFY_IS_APPROX_EVALUATOR2(res11, prod(m1X,mX1), m1X*mX1);\n    VERIFY_IS_APPROX_EVALUATOR2(res14, prod(m11,m14), m11*m14);\n    VERIFY_IS_APPROX_EVALUATOR2(res14, prod(m14,m44), m14*m44);\n    VERIFY_IS_APPROX_EVALUATOR2(res14, prod(m1X,mX4), m1X*mX4);\n    VERIFY_IS_APPROX_EVALUATOR2(res1X, prod(m11,m1X), m11*m1X);\n    VERIFY_IS_APPROX_EVALUATOR2(res1X, prod(m14,m4X), m14*m4X);\n    VERIFY_IS_APPROX_EVALUATOR2(res1X, prod(m1X,mXX), m1X*mXX);\n    VERIFY_IS_APPROX_EVALUATOR2(res41, prod(m41,m11), m41*m11);\n    VERIFY_IS_APPROX_EVALUATOR2(res41, prod(m44,m41), m44*m41);\n    VERIFY_IS_APPROX_EVALUATOR2(res41, prod(m4X,mX1), m4X*mX1);\n    VERIFY_IS_APPROX_EVALUATOR2(res44, prod(m41,m14), m41*m14);\n    VERIFY_IS_APPROX_EVALUATOR2(res44, prod(m44,m44), m44*m44);\n    VERIFY_IS_APPROX_EVALUATOR2(res44, prod(m4X,mX4), m4X*mX4);\n    VERIFY_IS_APPROX_EVALUATOR2(res4X, prod(m41,m1X), m41*m1X);\n    VERIFY_IS_APPROX_EVALUATOR2(res4X, prod(m44,m4X), m44*m4X);\n    VERIFY_IS_APPROX_EVALUATOR2(res4X, prod(m4X,mXX), m4X*mXX);\n    VERIFY_IS_APPROX_EVALUATOR2(resX1, prod(mX1,m11), mX1*m11);\n    VERIFY_IS_APPROX_EVALUATOR2(resX1, prod(mX4,m41), mX4*m41);\n    VERIFY_IS_APPROX_EVALUATOR2(resX1, prod(mXX,mX1), mXX*mX1);\n    VERIFY_IS_APPROX_EVALUATOR2(resX4, prod(mX1,m14), mX1*m14);\n    VERIFY_IS_APPROX_EVALUATOR2(resX4, prod(mX4,m44), mX4*m44);\n    VERIFY_IS_APPROX_EVALUATOR2(resX4, prod(mXX,mX4), mXX*mX4);\n    VERIFY_IS_APPROX_EVALUATOR2(resXX, prod(mX1,m1X), mX1*m1X);\n    VERIFY_IS_APPROX_EVALUATOR2(resXX, prod(mX4,m4X), mX4*m4X);\n    VERIFY_IS_APPROX_EVALUATOR2(resXX, prod(mXX,mXX), mXX*mXX);\n  }\n\n  {\n    ArrayXXf a(2,3);\n    ArrayXXf b(3,2);\n    a << 1,2,3, 4,5,6;\n    const ArrayXXf a_const(a);\n    \n    // this does not work because Random is eval-before-nested: \n    // copy_using_evaluator(w, Vector2d::Random().transpose());\n\n    // test CwiseUnaryOp\n    VERIFY_IS_APPROX_EVALUATOR(v2, 3 * v);\n    VERIFY_IS_APPROX_EVALUATOR(w, (3 * v).transpose());\n    VERIFY_IS_APPROX_EVALUATOR(b, (a + 3).transpose());\n    VERIFY_IS_APPROX_EVALUATOR(b, (2 * a_const + 3).transpose());\n\n    // test CwiseBinaryOp\n    VERIFY_IS_APPROX_EVALUATOR(v2, v + Vector2d::Ones());\n    VERIFY_IS_APPROX_EVALUATOR(w, (v + Vector2d::Ones()).transpose().cwiseProduct(RowVector2d::Constant(3)));\n\n    // dynamic matrices and arrays\n    MatrixXd mat1(6,6), mat2(6,6);\n    VERIFY_IS_APPROX_EVALUATOR(mat1, MatrixXd::Identity(6,6));\n    VERIFY_IS_APPROX_EVALUATOR(mat2, mat1);\n    copy_using_evaluator(mat2.transpose(), mat1);\n    VERIFY_IS_APPROX(mat2.transpose(), mat1);\n\n    ArrayXXd arr1(6,6), arr2(6,6);\n    VERIFY_IS_APPROX_EVALUATOR(arr1, ArrayXXd::Constant(6,6, 3.0));\n    VERIFY_IS_APPROX_EVALUATOR(arr2, arr1);\n    \n    // test automatic resizing\n    mat2.resize(3,3);\n    VERIFY_IS_APPROX_EVALUATOR(mat2, mat1);\n    arr2.resize(9,9);\n    VERIFY_IS_APPROX_EVALUATOR(arr2, arr1);\n\n    // test direct traversal\n    Matrix3f m3;\n    Array33f a3;\n    VERIFY_IS_APPROX_EVALUATOR(m3, Matrix3f::Identity());  // matrix, nullary\n    // TODO: find a way to test direct traversal with array\n    VERIFY_IS_APPROX_EVALUATOR(m3.transpose(), Matrix3f::Identity().transpose());  // transpose\n    VERIFY_IS_APPROX_EVALUATOR(m3, 2 * Matrix3f::Identity());  // unary\n    VERIFY_IS_APPROX_EVALUATOR(m3, Matrix3f::Identity() + Matrix3f::Zero());  // binary\n    VERIFY_IS_APPROX_EVALUATOR(m3.block(0,0,2,2), Matrix3f::Identity().block(1,1,2,2));  // block\n\n    // test linear traversal\n    VERIFY_IS_APPROX_EVALUATOR(m3, Matrix3f::Zero());  // matrix, nullary\n    VERIFY_IS_APPROX_EVALUATOR(a3, Array33f::Zero());  // array\n    VERIFY_IS_APPROX_EVALUATOR(m3.transpose(), Matrix3f::Zero().transpose());  // transpose\n    VERIFY_IS_APPROX_EVALUATOR(m3, 2 * Matrix3f::Zero());  // unary\n    VERIFY_IS_APPROX_EVALUATOR(m3, Matrix3f::Zero() + m3);  // binary  \n\n    // test inner vectorization\n    Matrix4f m4, m4src = Matrix4f::Random();\n    Array44f a4, a4src = Matrix4f::Random();\n    VERIFY_IS_APPROX_EVALUATOR(m4, m4src);  // matrix\n    VERIFY_IS_APPROX_EVALUATOR(a4, a4src);  // array\n    VERIFY_IS_APPROX_EVALUATOR(m4.transpose(), m4src.transpose());  // transpose\n    // TODO: find out why Matrix4f::Zero() does not allow inner vectorization\n    VERIFY_IS_APPROX_EVALUATOR(m4, 2 * m4src);  // unary\n    VERIFY_IS_APPROX_EVALUATOR(m4, m4src + m4src);  // binary\n\n    // test linear vectorization\n    MatrixXf mX(6,6), mXsrc = MatrixXf::Random(6,6);\n    ArrayXXf aX(6,6), aXsrc = ArrayXXf::Random(6,6);\n    VERIFY_IS_APPROX_EVALUATOR(mX, mXsrc);  // matrix\n    VERIFY_IS_APPROX_EVALUATOR(aX, aXsrc);  // array\n    VERIFY_IS_APPROX_EVALUATOR(mX.transpose(), mXsrc.transpose());  // transpose\n    VERIFY_IS_APPROX_EVALUATOR(mX, MatrixXf::Zero(6,6));  // nullary\n    VERIFY_IS_APPROX_EVALUATOR(mX, 2 * mXsrc);  // unary\n    VERIFY_IS_APPROX_EVALUATOR(mX, mXsrc + mXsrc);  // binary\n\n    // test blocks and slice vectorization\n    VERIFY_IS_APPROX_EVALUATOR(m4, (mXsrc.block<4,4>(1,0)));\n    VERIFY_IS_APPROX_EVALUATOR(aX, ArrayXXf::Constant(10, 10, 3.0).block(2, 3, 6, 6));\n\n    Matrix4f m4ref = m4;\n    copy_using_evaluator(m4.block(1, 1, 2, 3), m3.bottomRows(2));\n    m4ref.block(1, 1, 2, 3) = m3.bottomRows(2);\n    VERIFY_IS_APPROX(m4, m4ref);\n\n    mX.setIdentity(20,20);\n    MatrixXf mXref = MatrixXf::Identity(20,20);\n    mXsrc = MatrixXf::Random(9,12);\n    copy_using_evaluator(mX.block(4, 4, 9, 12), mXsrc);\n    mXref.block(4, 4, 9, 12) = mXsrc;\n    VERIFY_IS_APPROX(mX, mXref);\n\n    // test Map\n    const float raw[3] = {1,2,3};\n    float buffer[3] = {0,0,0};\n    Vector3f v3;\n    Array3f a3f;\n    VERIFY_IS_APPROX_EVALUATOR(v3, Map<const Vector3f>(raw));\n    VERIFY_IS_APPROX_EVALUATOR(a3f, Map<const Array3f>(raw));\n    Vector3f::Map(buffer) = 2*v3;\n    VERIFY(buffer[0] == 2);\n    VERIFY(buffer[1] == 4);\n    VERIFY(buffer[2] == 6);\n\n    // test CwiseUnaryView\n    mat1.setRandom();\n    mat2.setIdentity();\n    MatrixXcd matXcd(6,6), matXcd_ref(6,6);\n    copy_using_evaluator(matXcd.real(), mat1);\n    copy_using_evaluator(matXcd.imag(), mat2);\n    matXcd_ref.real() = mat1;\n    matXcd_ref.imag() = mat2;\n    VERIFY_IS_APPROX(matXcd, matXcd_ref);\n\n    // test Select\n    VERIFY_IS_APPROX_EVALUATOR(aX, (aXsrc > 0).select(aXsrc, -aXsrc));\n\n    // test Replicate\n    mXsrc = MatrixXf::Random(6, 6);\n    VectorXf vX = VectorXf::Random(6);\n    mX.resize(6, 6);\n    VERIFY_IS_APPROX_EVALUATOR(mX, mXsrc.colwise() + vX);\n    matXcd.resize(12, 12);\n    VERIFY_IS_APPROX_EVALUATOR(matXcd, matXcd_ref.replicate(2,2));\n    VERIFY_IS_APPROX_EVALUATOR(matXcd, (matXcd_ref.replicate<2,2>()));\n\n    // test partial reductions\n    VectorXd vec1(6);\n    VERIFY_IS_APPROX_EVALUATOR(vec1, mat1.rowwise().sum());\n    VERIFY_IS_APPROX_EVALUATOR(vec1, mat1.colwise().sum().transpose());\n\n    // test MatrixWrapper and ArrayWrapper\n    mat1.setRandom(6,6);\n    arr1.setRandom(6,6);\n    VERIFY_IS_APPROX_EVALUATOR(mat2, arr1.matrix());\n    VERIFY_IS_APPROX_EVALUATOR(arr2, mat1.array());\n    VERIFY_IS_APPROX_EVALUATOR(mat2, (arr1 + 2).matrix());\n    VERIFY_IS_APPROX_EVALUATOR(arr2, mat1.array() + 2);\n    mat2.array() = arr1 * arr1;\n    VERIFY_IS_APPROX(mat2, (arr1 * arr1).matrix());\n    arr2.matrix() = MatrixXd::Identity(6,6);\n    VERIFY_IS_APPROX(arr2, MatrixXd::Identity(6,6).array());\n\n    // test Reverse\n    VERIFY_IS_APPROX_EVALUATOR(arr2, arr1.reverse());\n    VERIFY_IS_APPROX_EVALUATOR(arr2, arr1.colwise().reverse());\n    VERIFY_IS_APPROX_EVALUATOR(arr2, arr1.rowwise().reverse());\n    arr2.reverse() = arr1;\n    VERIFY_IS_APPROX(arr2, arr1.reverse());\n    mat2.array() = mat1.array().reverse();\n    VERIFY_IS_APPROX(mat2.array(), mat1.array().reverse());\n\n    // test Diagonal\n    VERIFY_IS_APPROX_EVALUATOR(vec1, mat1.diagonal());\n    vec1.resize(5);\n    VERIFY_IS_APPROX_EVALUATOR(vec1, mat1.diagonal(1));\n    VERIFY_IS_APPROX_EVALUATOR(vec1, mat1.diagonal<-1>());\n    vec1.setRandom();\n\n    mat2 = mat1;\n    copy_using_evaluator(mat1.diagonal(1), vec1);\n    mat2.diagonal(1) = vec1;\n    VERIFY_IS_APPROX(mat1, mat2);\n\n    copy_using_evaluator(mat1.diagonal<-1>(), mat1.diagonal(1));\n    mat2.diagonal<-1>() = mat2.diagonal(1);\n    VERIFY_IS_APPROX(mat1, mat2);\n  }\n  \n  {\n    // test swapping\n    MatrixXd mat1, mat2, mat1ref, mat2ref;\n    mat1ref = mat1 = MatrixXd::Random(6, 6);\n    mat2ref = mat2 = 2 * mat1 + MatrixXd::Identity(6, 6);\n    swap_using_evaluator(mat1, mat2);\n    mat1ref.swap(mat2ref);\n    VERIFY_IS_APPROX(mat1, mat1ref);\n    VERIFY_IS_APPROX(mat2, mat2ref);\n\n    swap_using_evaluator(mat1.block(0, 0, 3, 3), mat2.block(3, 3, 3, 3));\n    mat1ref.block(0, 0, 3, 3).swap(mat2ref.block(3, 3, 3, 3));\n    VERIFY_IS_APPROX(mat1, mat1ref);\n    VERIFY_IS_APPROX(mat2, mat2ref);\n\n    swap_using_evaluator(mat1.row(2), mat2.col(3).transpose());\n    mat1.row(2).swap(mat2.col(3).transpose());\n    VERIFY_IS_APPROX(mat1, mat1ref);\n    VERIFY_IS_APPROX(mat2, mat2ref);\n  }\n\n  {\n    // test compound assignment\n    const Matrix4d mat_const = Matrix4d::Random(); \n    Matrix4d mat, mat_ref;\n    mat = mat_ref = Matrix4d::Identity();\n    add_assign_using_evaluator(mat, mat_const);\n    mat_ref += mat_const;\n    VERIFY_IS_APPROX(mat, mat_ref);\n\n    subtract_assign_using_evaluator(mat.row(1), 2*mat.row(2));\n    mat_ref.row(1) -= 2*mat_ref.row(2);\n    VERIFY_IS_APPROX(mat, mat_ref);\n\n    const ArrayXXf arr_const = ArrayXXf::Random(5,3); \n    ArrayXXf arr, arr_ref;\n    arr = arr_ref = ArrayXXf::Constant(5, 3, 0.5);\n    multiply_assign_using_evaluator(arr, arr_const);\n    arr_ref *= arr_const;\n    VERIFY_IS_APPROX(arr, arr_ref);\n\n    divide_assign_using_evaluator(arr.row(1), arr.row(2) + 1);\n    arr_ref.row(1) /= (arr_ref.row(2) + 1);\n    VERIFY_IS_APPROX(arr, arr_ref);\n  }\n  \n  {\n    // test triangular shapes\n    MatrixXd A = MatrixXd::Random(6,6), B(6,6), C(6,6), D(6,6);\n    A.setRandom();B.setRandom();\n    VERIFY_IS_APPROX_EVALUATOR2(B, A.triangularView<Upper>(), MatrixXd(A.triangularView<Upper>()));\n    \n    A.setRandom();B.setRandom();\n    VERIFY_IS_APPROX_EVALUATOR2(B, A.triangularView<UnitLower>(), MatrixXd(A.triangularView<UnitLower>()));\n    \n    A.setRandom();B.setRandom();\n    VERIFY_IS_APPROX_EVALUATOR2(B, A.triangularView<UnitUpper>(), MatrixXd(A.triangularView<UnitUpper>()));\n    \n    A.setRandom();B.setRandom();\n    C = B; C.triangularView<Upper>() = A;\n    copy_using_evaluator(B.triangularView<Upper>(), A);\n    VERIFY(B.isApprox(C) && \"copy_using_evaluator(B.triangularView<Upper>(), A)\");\n    \n    A.setRandom();B.setRandom();\n    C = B; C.triangularView<Lower>() = A.triangularView<Lower>();\n    copy_using_evaluator(B.triangularView<Lower>(), A.triangularView<Lower>());\n    VERIFY(B.isApprox(C) && \"copy_using_evaluator(B.triangularView<Lower>(), A.triangularView<Lower>())\");\n    \n    \n    A.setRandom();B.setRandom();\n    C = B; C.triangularView<Lower>() = A.triangularView<Upper>().transpose();\n    copy_using_evaluator(B.triangularView<Lower>(), A.triangularView<Upper>().transpose());\n    VERIFY(B.isApprox(C) && \"copy_using_evaluator(B.triangularView<Lower>(), A.triangularView<Lower>().transpose())\");\n    \n    \n    A.setRandom();B.setRandom(); C = B; D = A;\n    C.triangularView<Upper>().swap(D.triangularView<Upper>());\n    swap_using_evaluator(B.triangularView<Upper>(), A.triangularView<Upper>());\n    VERIFY(B.isApprox(C) && \"swap_using_evaluator(B.triangularView<Upper>(), A.triangularView<Upper>())\");\n    \n    \n    VERIFY_IS_APPROX_EVALUATOR2(B, prod(A.triangularView<Upper>(),A), MatrixXd(A.triangularView<Upper>()*A));\n    \n    VERIFY_IS_APPROX_EVALUATOR2(B, prod(A.selfadjointView<Upper>(),A), MatrixXd(A.selfadjointView<Upper>()*A));\n  }\n\n  {\n    // test diagonal shapes\n    VectorXd d = VectorXd::Random(6);\n    MatrixXd A = MatrixXd::Random(6,6), B(6,6);\n    A.setRandom();B.setRandom();\n    \n    VERIFY_IS_APPROX_EVALUATOR2(B, lazyprod(d.asDiagonal(),A), MatrixXd(d.asDiagonal()*A));\n    VERIFY_IS_APPROX_EVALUATOR2(B, lazyprod(A,d.asDiagonal()), MatrixXd(A*d.asDiagonal()));\n  }\n\n  {\n    // test CoeffReadCost\n    Matrix4d a, b;\n    VERIFY_IS_EQUAL( get_cost(a), 1 );\n    VERIFY_IS_EQUAL( get_cost(a+b), 3);\n    VERIFY_IS_EQUAL( get_cost(2*a+b), 4);\n    VERIFY_IS_EQUAL( get_cost(a*b), 1);\n    VERIFY_IS_EQUAL( get_cost(a.lazyProduct(b)), 15);\n    VERIFY_IS_EQUAL( get_cost(a*(a*b)), 1);\n    VERIFY_IS_EQUAL( get_cost(a.lazyProduct(a*b)), 15);\n    VERIFY_IS_EQUAL( get_cost(a*(a+b)), 1);\n    VERIFY_IS_EQUAL( get_cost(a.lazyProduct(a+b)), 15);\n  }\n\n  // regression test for PR 544 and bug 1622 (introduced in #71609c4)\n  {\n    // test restricted_packet_assignment with an unaligned destination\n    const size_t M = 2;\n    const size_t K = 2;\n    const size_t N = 5;\n    float *destMem = new float[(M*N) + 1];\n    float *dest = (internal::UIntPtr(destMem)%EIGEN_MAX_ALIGN_BYTES) == 0 ? destMem+1 : destMem;\n\n    const Matrix<float, Dynamic, Dynamic, RowMajor> a = Matrix<float, Dynamic, Dynamic, RowMajor>::Random(M, K);\n    const Matrix<float, Dynamic, Dynamic, RowMajor> b = Matrix<float, Dynamic, Dynamic, RowMajor>::Random(K, N);\n    \n    Map<Matrix<float, Dynamic, Dynamic, RowMajor> > z(dest, M, N);;\n    Product<Matrix<float, Dynamic, Dynamic, RowMajor>, Matrix<float, Dynamic, Dynamic, RowMajor>, LazyProduct> tmp(a,b);\n    internal::call_restricted_packet_assignment(z.noalias(), tmp.derived(), internal::assign_op<float, float>());\n    \n    VERIFY_IS_APPROX(z, a*b);\n    delete[] destMem;\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/exceptions.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n// Various sanity tests with exceptions and non trivially copyable scalar type.\n//  - no memory leak when a custom scalar type trow an exceptions\n//  - todo: complete the list of tests!\n\n#define EIGEN_STACK_ALLOCATION_LIMIT 100000000\n\n#include \"main.h\"\n#include \"AnnoyingScalar.h\"\n\n#define CHECK_MEMLEAK(OP) {                                 \\\n    AnnoyingScalar::countdown = 100;                        \\\n    int before = AnnoyingScalar::instances;                 \\\n    bool exception_thrown = false;                          \\\n    try { OP; }                                             \\\n    catch (my_exception) {                                  \\\n      exception_thrown = true;                              \\\n      VERIFY(AnnoyingScalar::instances==before && \"memory leak detected in \" && EIGEN_MAKESTRING(OP)); \\\n    } \\\n    VERIFY( (AnnoyingScalar::dont_throw) || (exception_thrown && \" no exception thrown in \" && EIGEN_MAKESTRING(OP)) ); \\\n  }\n\nEIGEN_DECLARE_TEST(exceptions)\n{\n  typedef Eigen::Matrix<AnnoyingScalar,Dynamic,1> VectorType;\n  typedef Eigen::Matrix<AnnoyingScalar,Dynamic,Dynamic> MatrixType;\n  \n  {\n    AnnoyingScalar::dont_throw = false;\n    int n = 50;\n    VectorType v0(n), v1(n);\n    MatrixType m0(n,n), m1(n,n), m2(n,n);\n    v0.setOnes(); v1.setOnes();\n    m0.setOnes(); m1.setOnes(); m2.setOnes();\n    CHECK_MEMLEAK(v0 = m0 * m1 * v1);\n    CHECK_MEMLEAK(m2 = m0 * m1 * m2);\n    CHECK_MEMLEAK((v0+v1).dot(v0+v1));\n  }\n  VERIFY(AnnoyingScalar::instances==0 && \"global memory leak detected in \" && EIGEN_MAKESTRING(OP));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/fastmath.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\nvoid check(bool b, bool ref)\n{\n  std::cout << b;\n  if(b==ref)\n    std::cout << \" OK  \";\n  else\n    std::cout << \" BAD \";\n}\n\n#if EIGEN_COMP_MSVC && EIGEN_COMP_MSVC < 1800\nnamespace std {\n  template<typename T> bool (isfinite)(T x) { return _finite(x); }\n  template<typename T> bool (isnan)(T x) { return _isnan(x); }\n  template<typename T> bool (isinf)(T x) { return _fpclass(x)==_FPCLASS_NINF || _fpclass(x)==_FPCLASS_PINF; }\n}\n#endif\n\ntemplate<typename T>\nvoid check_inf_nan(bool dryrun) {\n  Matrix<T,Dynamic,1> m(10);\n  m.setRandom();\n  m(3) = std::numeric_limits<T>::quiet_NaN();\n\n  if(dryrun)\n  {\n    std::cout << \"std::isfinite(\" << m(3) << \") = \"; check((std::isfinite)(m(3)),false); std::cout << \"  ; numext::isfinite = \"; check((numext::isfinite)(m(3)), false); std::cout << \"\\n\";\n    std::cout << \"std::isinf(\" << m(3) << \")    = \"; check((std::isinf)(m(3)),false);    std::cout << \"  ; numext::isinf    = \"; check((numext::isinf)(m(3)), false); std::cout << \"\\n\";\n    std::cout << \"std::isnan(\" << m(3) << \")    = \"; check((std::isnan)(m(3)),true);     std::cout << \"  ; numext::isnan    = \"; check((numext::isnan)(m(3)), true); std::cout << \"\\n\";\n    std::cout << \"allFinite: \"; check(m.allFinite(), 0); std::cout << \"\\n\";\n    std::cout << \"hasNaN:    \"; check(m.hasNaN(), 1);    std::cout << \"\\n\";\n    std::cout << \"\\n\";\n  }\n  else\n  {\n    if( (std::isfinite)(m(3))) g_test_level=1;  VERIFY( !(numext::isfinite)(m(3)) ); g_test_level=0;\n    if( (std::isinf)   (m(3))) g_test_level=1;  VERIFY( !(numext::isinf)(m(3)) );    g_test_level=0;\n    if(!(std::isnan)   (m(3))) g_test_level=1;  VERIFY(  (numext::isnan)(m(3)) );    g_test_level=0;\n    if( (std::isfinite)(m(3))) g_test_level=1;  VERIFY( !m.allFinite() );            g_test_level=0;\n    if(!(std::isnan)   (m(3))) g_test_level=1;  VERIFY(  m.hasNaN() );               g_test_level=0;\n  }\n  T hidden_zero = (std::numeric_limits<T>::min)()*(std::numeric_limits<T>::min)();\n  m(4) /= hidden_zero;\n  if(dryrun)\n  {\n    std::cout << \"std::isfinite(\" << m(4) << \") = \"; check((std::isfinite)(m(4)),false); std::cout << \"  ; numext::isfinite = \"; check((numext::isfinite)(m(4)), false); std::cout << \"\\n\";\n    std::cout << \"std::isinf(\" << m(4) << \")    = \"; check((std::isinf)(m(4)),true);     std::cout << \"  ; numext::isinf    = \"; check((numext::isinf)(m(4)), true); std::cout << \"\\n\";\n    std::cout << \"std::isnan(\" << m(4) << \")    = \"; check((std::isnan)(m(4)),false);    std::cout << \"  ; numext::isnan    = \"; check((numext::isnan)(m(4)), false); std::cout << \"\\n\";\n    std::cout << \"allFinite: \"; check(m.allFinite(), 0); std::cout << \"\\n\";\n    std::cout << \"hasNaN:    \"; check(m.hasNaN(), 1);    std::cout << \"\\n\";\n    std::cout << \"\\n\";\n  }\n  else\n  {\n    if( (std::isfinite)(m(3))) g_test_level=1;  VERIFY( !(numext::isfinite)(m(4)) );  g_test_level=0;\n    if(!(std::isinf)   (m(3))) g_test_level=1;  VERIFY(  (numext::isinf)(m(4)) );     g_test_level=0;\n    if( (std::isnan)   (m(3))) g_test_level=1;  VERIFY( !(numext::isnan)(m(4)) );     g_test_level=0;\n    if( (std::isfinite)(m(3))) g_test_level=1;  VERIFY( !m.allFinite() );             g_test_level=0;\n    if(!(std::isnan)   (m(3))) g_test_level=1;  VERIFY(  m.hasNaN() );                g_test_level=0;\n  }\n  m(3) = 0;\n  if(dryrun)\n  {\n    std::cout << \"std::isfinite(\" << m(3) << \") = \"; check((std::isfinite)(m(3)),true); std::cout << \"  ; numext::isfinite = \"; check((numext::isfinite)(m(3)), true); std::cout << \"\\n\";\n    std::cout << \"std::isinf(\" << m(3) << \")    = \"; check((std::isinf)(m(3)),false);   std::cout << \"  ; numext::isinf    = \"; check((numext::isinf)(m(3)), false); std::cout << \"\\n\";\n    std::cout << \"std::isnan(\" << m(3) << \")    = \"; check((std::isnan)(m(3)),false);   std::cout << \"  ; numext::isnan    = \"; check((numext::isnan)(m(3)), false); std::cout << \"\\n\";\n    std::cout << \"allFinite: \"; check(m.allFinite(), 0); std::cout << \"\\n\";\n    std::cout << \"hasNaN:    \"; check(m.hasNaN(), 0);    std::cout << \"\\n\";\n    std::cout << \"\\n\\n\";\n  }\n  else\n  {\n    if(!(std::isfinite)(m(3))) g_test_level=1;  VERIFY(  (numext::isfinite)(m(3)) );  g_test_level=0;\n    if( (std::isinf)   (m(3))) g_test_level=1;  VERIFY( !(numext::isinf)(m(3)) );     g_test_level=0;\n    if( (std::isnan)   (m(3))) g_test_level=1;  VERIFY( !(numext::isnan)(m(3)) );     g_test_level=0;\n    if( (std::isfinite)(m(3))) g_test_level=1;  VERIFY( !m.allFinite() );             g_test_level=0;\n    if( (std::isnan)   (m(3))) g_test_level=1;  VERIFY( !m.hasNaN() );                g_test_level=0;\n  }\n}\n\nEIGEN_DECLARE_TEST(fastmath) {\n  std::cout << \"*** float *** \\n\\n\"; check_inf_nan<float>(true);\n  std::cout << \"*** double ***\\n\\n\"; check_inf_nan<double>(true);\n  std::cout << \"*** long double *** \\n\\n\"; check_inf_nan<long double>(true);\n\n  check_inf_nan<float>(false);\n  check_inf_nan<double>(false);\n  check_inf_nan<long double>(false);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/first_aligned.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename Scalar>\nvoid test_first_aligned_helper(Scalar *array, int size)\n{\n  const int packet_size = sizeof(Scalar) * internal::packet_traits<Scalar>::size;\n  VERIFY(((size_t(array) + sizeof(Scalar) * internal::first_default_aligned(array, size)) % packet_size) == 0);\n}\n\ntemplate<typename Scalar>\nvoid test_none_aligned_helper(Scalar *array, int size)\n{\n  EIGEN_UNUSED_VARIABLE(array);\n  EIGEN_UNUSED_VARIABLE(size);\n  VERIFY(internal::packet_traits<Scalar>::size == 1 || internal::first_default_aligned(array, size) == size);\n}\n\nstruct some_non_vectorizable_type { float x; };\n\nEIGEN_DECLARE_TEST(first_aligned)\n{\n  EIGEN_ALIGN16 float array_float[100];\n  test_first_aligned_helper(array_float, 50);\n  test_first_aligned_helper(array_float+1, 50);\n  test_first_aligned_helper(array_float+2, 50);\n  test_first_aligned_helper(array_float+3, 50);\n  test_first_aligned_helper(array_float+4, 50);\n  test_first_aligned_helper(array_float+5, 50);\n  \n  EIGEN_ALIGN16 double array_double[100];\n  test_first_aligned_helper(array_double, 50);\n  test_first_aligned_helper(array_double+1, 50);\n  test_first_aligned_helper(array_double+2, 50);\n  \n  double *array_double_plus_4_bytes = (double*)(internal::UIntPtr(array_double)+4);\n  test_none_aligned_helper(array_double_plus_4_bytes, 50);\n  test_none_aligned_helper(array_double_plus_4_bytes+1, 50);\n  \n  some_non_vectorizable_type array_nonvec[100];\n  test_first_aligned_helper(array_nonvec, 100);\n  test_none_aligned_helper(array_nonvec, 100);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/geo_alignedbox.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/Geometry>\n\nusing namespace std;\n\n// NOTE the following workaround was needed on some 32 bits builds to kill extra precision of x87 registers.\n// It seems that it is not needed anymore, but let's keep it here, just in case...\n\ntemplate<typename T> EIGEN_DONT_INLINE\nvoid kill_extra_precision(T& /* x */) {\n  // This one worked but triggered a warning:\n  /* eigen_assert((void*)(&x) != (void*)0); */\n  // An alternative could be:\n  /* volatile T tmp = x; */\n  /* x = tmp; */\n}\n\n\ntemplate<typename BoxType> void alignedbox(const BoxType& box)\n{\n  /* this test covers the following files:\n     AlignedBox.h\n  */\n  typedef typename BoxType::Scalar Scalar;\n  typedef NumTraits<Scalar> ScalarTraits;\n  typedef typename ScalarTraits::Real RealScalar;\n  typedef Matrix<Scalar, BoxType::AmbientDimAtCompileTime, 1> VectorType;\n\n  const Index dim = box.dim();\n\n  VectorType p0 = VectorType::Random(dim);\n  VectorType p1 = VectorType::Random(dim);\n  while( p1 == p0 ){\n      p1 =  VectorType::Random(dim); }\n  RealScalar s1 = internal::random<RealScalar>(0,1);\n\n  BoxType b0(dim);\n  BoxType b1(VectorType::Random(dim),VectorType::Random(dim));\n  BoxType b2;\n\n  kill_extra_precision(b1);\n  kill_extra_precision(p0);\n  kill_extra_precision(p1);\n\n  b0.extend(p0);\n  b0.extend(p1);\n  VERIFY(b0.contains(p0*s1+(Scalar(1)-s1)*p1));\n  VERIFY(b0.contains(b0.center()));\n  VERIFY_IS_APPROX(b0.center(),(p0+p1)/Scalar(2));\n\n  (b2 = b0).extend(b1);\n  VERIFY(b2.contains(b0));\n  VERIFY(b2.contains(b1));\n  VERIFY_IS_APPROX(b2.clamp(b0), b0);\n\n  // intersection\n  BoxType box1(VectorType::Random(dim));\n  box1.extend(VectorType::Random(dim));\n  BoxType box2(VectorType::Random(dim));\n  box2.extend(VectorType::Random(dim));\n\n  VERIFY(box1.intersects(box2) == !box1.intersection(box2).isEmpty());\n\n  // alignment -- make sure there is no memory alignment assertion\n  BoxType *bp0 = new BoxType(dim);\n  BoxType *bp1 = new BoxType(dim);\n  bp0->extend(*bp1);\n  delete bp0;\n  delete bp1;\n\n  // sampling\n  for( int i=0; i<10; ++i )\n  {\n      VectorType r = b0.sample();\n      VERIFY(b0.contains(r));\n  }\n\n}\n\ntemplate<typename BoxType> void alignedboxTranslatable(const BoxType& box)\n{\n  typedef typename BoxType::Scalar Scalar;\n  typedef Matrix<Scalar, BoxType::AmbientDimAtCompileTime, 1> VectorType;\n  typedef Transform<Scalar, BoxType::AmbientDimAtCompileTime, Isometry> IsometryTransform;\n  typedef Transform<Scalar, BoxType::AmbientDimAtCompileTime, Affine> AffineTransform;\n\n  alignedbox(box);\n\n  const VectorType Ones = VectorType::Ones();\n  const VectorType UnitX = VectorType::UnitX();\n  const Index dim = box.dim();\n\n  // box((-1, -1, -1), (1, 1, 1))\n  BoxType a(-Ones, Ones);\n\n  VERIFY_IS_APPROX(a.sizes(), Ones * Scalar(2));\n\n  BoxType b = a;\n  VectorType translate = Ones;\n  translate[0] = Scalar(2);\n  b.translate(translate);\n  // translate by (2, 1, 1) -> box((1, 0, 0), (3, 2, 2))\n\n  VERIFY_IS_APPROX(b.sizes(), Ones * Scalar(2));\n  VERIFY_IS_APPROX((b.min)(), UnitX);\n  VERIFY_IS_APPROX((b.max)(), Ones * Scalar(2) + UnitX);\n\n  // Test transform\n\n  IsometryTransform tf = IsometryTransform::Identity();\n  tf.translation() = -translate;\n\n  BoxType c = b.transformed(tf);\n  // translate by (-2, -1, -1) -> box((-1, -1, -1), (1, 1, 1))\n  VERIFY_IS_APPROX(c.sizes(), a.sizes());\n  VERIFY_IS_APPROX((c.min)(), (a.min)());\n  VERIFY_IS_APPROX((c.max)(), (a.max)());\n\n  c.transform(tf);\n  // translate by (-2, -1, -1) -> box((-3, -2, -2), (-1, 0, 0))\n  VERIFY_IS_APPROX(c.sizes(), a.sizes());\n  VERIFY_IS_APPROX((c.min)(), Ones * Scalar(-2) - UnitX);\n  VERIFY_IS_APPROX((c.max)(), -UnitX);\n\n  // Scaling\n\n  AffineTransform atf = AffineTransform::Identity();\n  atf.scale(Scalar(3));\n  c.transform(atf);\n  // scale by 3 -> box((-9, -6, -6), (-3, 0, 0))\n  VERIFY_IS_APPROX(c.sizes(), Scalar(3) * a.sizes());\n  VERIFY_IS_APPROX((c.min)(), Ones * Scalar(-6) - UnitX * Scalar(3));\n  VERIFY_IS_APPROX((c.max)(), UnitX * Scalar(-3));\n\n  atf = AffineTransform::Identity();\n  atf.scale(Scalar(-3));\n  c.transform(atf);\n  // scale by -3 -> box((27, 18, 18), (9, 0, 0))\n  VERIFY_IS_APPROX(c.sizes(), Scalar(9) * a.sizes());\n  VERIFY_IS_APPROX((c.min)(), UnitX * Scalar(9));\n  VERIFY_IS_APPROX((c.max)(), Ones * Scalar(18) + UnitX * Scalar(9));\n\n  // Check identity transform within numerical precision.\n  BoxType transformedC = c.transformed(IsometryTransform::Identity());\n  VERIFY_IS_APPROX(transformedC, c);\n\n  for (size_t i = 0; i < 10; ++i)\n  {\n    VectorType minCorner;\n    VectorType maxCorner;\n    for (Index d = 0; d < dim; ++d)\n    {\n      minCorner[d] = internal::random<Scalar>(-10,10);\n      maxCorner[d] = minCorner[d] + internal::random<Scalar>(0, 10);\n    }\n\n    c = BoxType(minCorner, maxCorner);\n\n    translate = VectorType::Random();\n    c.translate(translate);\n\n    VERIFY_IS_APPROX((c.min)(), minCorner + translate);\n    VERIFY_IS_APPROX((c.max)(), maxCorner + translate);\n  }\n}\n\ntemplate<typename Scalar, typename Rotation>\nRotation rotate2D(Scalar angle) {\n  return Rotation2D<Scalar>(angle);\n}\n\ntemplate<typename Scalar, typename Rotation>\nRotation rotate2DIntegral(typename NumTraits<Scalar>::NonInteger angle) {\n  typedef typename NumTraits<Scalar>::NonInteger NonInteger;\n  return Rotation2D<NonInteger>(angle).toRotationMatrix().\n      template cast<Scalar>();\n}\n\ntemplate<typename Scalar, typename Rotation>\nRotation rotate3DZAxis(Scalar angle) {\n  return AngleAxis<Scalar>(angle, Matrix<Scalar, 3, 1>(0, 0, 1));\n}\n\ntemplate<typename Scalar, typename Rotation>\nRotation rotate3DZAxisIntegral(typename NumTraits<Scalar>::NonInteger angle) {\n  typedef typename NumTraits<Scalar>::NonInteger NonInteger;\n  return AngleAxis<NonInteger>(angle, Matrix<NonInteger, 3, 1>(0, 0, 1)).\n      toRotationMatrix().template cast<Scalar>();\n}\n\ntemplate<typename Scalar, typename Rotation>\nRotation rotate4DZWAxis(Scalar angle) {\n  Rotation result = Matrix<Scalar, 4, 4>::Identity();\n  result.block(0, 0, 3, 3) = rotate3DZAxis<Scalar, AngleAxisd>(angle).toRotationMatrix();\n  return result;\n}\n\ntemplate <typename MatrixType>\nMatrixType randomRotationMatrix()\n{\n  // algorithm from\n  // https://www.isprs-ann-photogramm-remote-sens-spatial-inf-sci.net/III-7/103/2016/isprs-annals-III-7-103-2016.pdf\n  const MatrixType rand = MatrixType::Random();\n  const MatrixType q = rand.householderQr().householderQ();\n  const JacobiSVD<MatrixType> svd = q.jacobiSvd(ComputeFullU | ComputeFullV);\n  const typename MatrixType::Scalar det = (svd.matrixU() * svd.matrixV().transpose()).determinant();\n  MatrixType diag = rand.Identity();\n  diag(MatrixType::RowsAtCompileTime - 1, MatrixType::ColsAtCompileTime - 1) = det;\n  const MatrixType rotation = svd.matrixU() * diag * svd.matrixV().transpose();\n  return rotation;\n}\n\ntemplate <typename Scalar, int Dim>\nMatrix<Scalar, Dim, (1<<Dim)> boxGetCorners(const Matrix<Scalar, Dim, 1>& min_, const Matrix<Scalar, Dim, 1>& max_)\n{\n  Matrix<Scalar, Dim, (1<<Dim) > result;\n  for(Index i=0; i<(1<<Dim); ++i)\n  {\n    for(Index j=0; j<Dim; ++j)\n      result(j,i) = (i & (1<<j)) ? min_(j) : max_(j);\n  }\n  return result;\n}\n\ntemplate<typename BoxType, typename Rotation> void alignedboxRotatable(\n    const BoxType& box,\n    Rotation (*rotate)(typename NumTraits<typename BoxType::Scalar>::NonInteger /*_angle*/))\n{\n  alignedboxTranslatable(box);\n\n  typedef typename BoxType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::NonInteger NonInteger;\n  typedef Matrix<Scalar, BoxType::AmbientDimAtCompileTime, 1> VectorType;\n  typedef Transform<Scalar, BoxType::AmbientDimAtCompileTime, Isometry> IsometryTransform;\n  typedef Transform<Scalar, BoxType::AmbientDimAtCompileTime, Affine> AffineTransform;\n\n  const VectorType Zero = VectorType::Zero();\n  const VectorType Ones = VectorType::Ones();\n  const VectorType UnitX = VectorType::UnitX();\n  const VectorType UnitY = VectorType::UnitY();\n  // this is vector (0, 0, -1, -1, -1, ...), i.e. with zeros at first and second dimensions\n  const VectorType UnitZ = Ones - UnitX - UnitY;\n\n  // in this kind of comments the 3D case values will be illustrated\n  // box((-1, -1, -1), (1, 1, 1))\n  BoxType a(-Ones, Ones);\n\n  // to allow templating this test for both 2D and 3D cases, we always set all\n  // but the first coordinate to the same value; so basically 3D case works as\n  // if you were looking at the scene from top\n\n  VectorType minPoint = -2 * Ones;\n  minPoint[0] = -3;\n  VectorType maxPoint = Zero;\n  maxPoint[0] = -1;\n  BoxType c(minPoint, maxPoint);\n  // box((-3, -2, -2), (-1, 0, 0))\n\n  IsometryTransform tf2 = IsometryTransform::Identity();\n  // for some weird reason the following statement has to be put separate from\n  // the following rotate call, otherwise precision problems arise...\n  Rotation rot = rotate(NonInteger(EIGEN_PI));\n  tf2.rotate(rot);\n\n  c.transform(tf2);\n  // rotate by 180 deg around origin -> box((1, 0, -2), (3, 2, 0))\n\n  VERIFY_IS_APPROX(c.sizes(), a.sizes());\n  VERIFY_IS_APPROX((c.min)(), UnitX - UnitZ * Scalar(2));\n  VERIFY_IS_APPROX((c.max)(), UnitX * Scalar(3) + UnitY * Scalar(2));\n\n  rot = rotate(NonInteger(EIGEN_PI / 2));\n  tf2.setIdentity();\n  tf2.rotate(rot);\n\n  c.transform(tf2);\n  // rotate by 90 deg around origin ->  box((-2, 1, -2), (0, 3, 0))\n\n  VERIFY_IS_APPROX(c.sizes(), a.sizes());\n  VERIFY_IS_APPROX((c.min)(), Ones * Scalar(-2) + UnitY * Scalar(3));\n  VERIFY_IS_APPROX((c.max)(), UnitY * Scalar(3));\n\n  // box((-1, -1, -1), (1, 1, 1))\n  AffineTransform atf = AffineTransform::Identity();\n  atf.linearExt()(0, 1) = Scalar(1);\n  c = BoxType(-Ones, Ones);\n  c.transform(atf);\n  // 45 deg shear in x direction -> box((-2, -1, -1), (2, 1, 1))\n\n  VERIFY_IS_APPROX(c.sizes(), Ones * Scalar(2) + UnitX * Scalar(2));\n  VERIFY_IS_APPROX((c.min)(), -Ones - UnitX);\n  VERIFY_IS_APPROX((c.max)(), Ones + UnitX);\n}\n\ntemplate<typename BoxType, typename Rotation> void alignedboxNonIntegralRotatable(\n    const BoxType& box,\n    Rotation (*rotate)(typename NumTraits<typename BoxType::Scalar>::NonInteger /*_angle*/))\n{\n  alignedboxRotatable(box, rotate);\n\n  typedef typename BoxType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::NonInteger NonInteger;\n  enum { Dim = BoxType::AmbientDimAtCompileTime };\n  typedef Matrix<Scalar, Dim, 1> VectorType;\n  typedef Matrix<Scalar, Dim, (1 << Dim)> CornersType;\n  typedef Transform<Scalar, Dim, Isometry> IsometryTransform;\n  typedef Transform<Scalar, Dim, Affine> AffineTransform;\n\n  const Index dim = box.dim();\n  const VectorType Zero = VectorType::Zero();\n  const VectorType Ones = VectorType::Ones();\n\n  VectorType minPoint = -2 * Ones;\n  minPoint[1] = 1;\n  VectorType maxPoint = Zero;\n  maxPoint[1] = 3;\n  BoxType c(minPoint, maxPoint);\n  // ((-2, 1, -2), (0, 3, 0))\n\n  VectorType cornerBL = (c.min)();\n  VectorType cornerTR = (c.max)();\n  VectorType cornerBR = (c.min)(); cornerBR[0] = cornerTR[0];\n  VectorType cornerTL = (c.max)(); cornerTL[0] = cornerBL[0];\n\n  NonInteger angle = NonInteger(EIGEN_PI/3);\n  Rotation rot = rotate(angle);\n  IsometryTransform tf2;\n  tf2.setIdentity();\n  tf2.rotate(rot);\n\n  c.transform(tf2);\n  // rotate by 60 deg ->  box((-3.59, -1.23, -2), (-0.86, 1.5, 0))\n\n  cornerBL = tf2 * cornerBL;\n  cornerBR = tf2 * cornerBR;\n  cornerTL = tf2 * cornerTL;\n  cornerTR = tf2 * cornerTR;\n\n  VectorType minCorner = Ones * Scalar(-2);\n  VectorType maxCorner = Zero;\n  minCorner[0] = (min)((min)(cornerBL[0], cornerBR[0]), (min)(cornerTL[0], cornerTR[0]));\n  maxCorner[0] = (max)((max)(cornerBL[0], cornerBR[0]), (max)(cornerTL[0], cornerTR[0]));\n  minCorner[1] = (min)((min)(cornerBL[1], cornerBR[1]), (min)(cornerTL[1], cornerTR[1]));\n  maxCorner[1] = (max)((max)(cornerBL[1], cornerBR[1]), (max)(cornerTL[1], cornerTR[1]));\n\n  for (Index d = 2; d < dim; ++d)\n    VERIFY_IS_APPROX(c.sizes()[d], Scalar(2));\n\n  VERIFY_IS_APPROX((c.min)(), minCorner);\n  VERIFY_IS_APPROX((c.max)(), maxCorner);\n\n  VectorType minCornerValue = Ones * Scalar(-2);\n  VectorType maxCornerValue = Zero;\n  minCornerValue[0] = Scalar(Scalar(-sqrt(2*2 + 3*3)) * Scalar(cos(Scalar(atan(2.0/3.0)) - angle/2)));\n  minCornerValue[1] = Scalar(Scalar(-sqrt(1*1 + 2*2)) * Scalar(sin(Scalar(atan(2.0/1.0)) - angle/2)));\n  maxCornerValue[0] = Scalar(-sin(angle));\n  maxCornerValue[1] = Scalar(3 * cos(angle));\n  VERIFY_IS_APPROX((c.min)(), minCornerValue);\n  VERIFY_IS_APPROX((c.max)(), maxCornerValue);\n\n  // randomized test - translate and rotate the box and compare to a box made of transformed vertices\n  for (size_t i = 0; i < 10; ++i)\n  {\n    for (Index d = 0; d < dim; ++d)\n    {\n      minCorner[d] = internal::random<Scalar>(-10,10);\n      maxCorner[d] = minCorner[d] + internal::random<Scalar>(0, 10);\n    }\n\n    c = BoxType(minCorner, maxCorner);\n\n    CornersType corners = boxGetCorners(minCorner, maxCorner);\n\n    typename AffineTransform::LinearMatrixType rotation =\n        randomRotationMatrix<typename AffineTransform::LinearMatrixType>();\n\n    tf2.setIdentity();\n    tf2.rotate(rotation);\n    tf2.translate(VectorType::Random());\n\n    c.transform(tf2);\n    corners = tf2 * corners;\n\n    minCorner = corners.rowwise().minCoeff();\n    maxCorner = corners.rowwise().maxCoeff();\n\n    VERIFY_IS_APPROX((c.min)(), minCorner);\n    VERIFY_IS_APPROX((c.max)(), maxCorner);\n  }\n\n  // randomized test - transform the box with a random affine matrix and compare to a box made of transformed vertices\n  for (size_t i = 0; i < 10; ++i)\n  {\n    for (Index d = 0; d < dim; ++d)\n    {\n      minCorner[d] = internal::random<Scalar>(-10,10);\n      maxCorner[d] = minCorner[d] + internal::random<Scalar>(0, 10);\n    }\n\n    c = BoxType(minCorner, maxCorner);\n\n    CornersType corners = boxGetCorners(minCorner, maxCorner);\n\n    AffineTransform atf = AffineTransform::Identity();\n    atf.linearExt() = AffineTransform::LinearPart::Random();\n    atf.translate(VectorType::Random());\n\n    c.transform(atf);\n    corners = atf * corners;\n\n    minCorner = corners.rowwise().minCoeff();\n    maxCorner = corners.rowwise().maxCoeff();\n\n    VERIFY_IS_APPROX((c.min)(), minCorner);\n    VERIFY_IS_APPROX((c.max)(), maxCorner);\n  }\n}\n\ntemplate<typename BoxType>\nvoid alignedboxCastTests(const BoxType& box)\n{\n  // casting\n  typedef typename BoxType::Scalar Scalar;\n  typedef Matrix<Scalar, BoxType::AmbientDimAtCompileTime, 1> VectorType;\n\n  const Index dim = box.dim();\n\n  VectorType p0 = VectorType::Random(dim);\n  VectorType p1 = VectorType::Random(dim);\n\n  BoxType b0(dim);\n\n  b0.extend(p0);\n  b0.extend(p1);\n\n  const int Dim = BoxType::AmbientDimAtCompileTime;\n  typedef typename GetDifferentType<Scalar>::type OtherScalar;\n  AlignedBox<OtherScalar,Dim> hp1f = b0.template cast<OtherScalar>();\n  VERIFY_IS_APPROX(hp1f.template cast<Scalar>(),b0);\n  AlignedBox<Scalar,Dim> hp1d = b0.template cast<Scalar>();\n  VERIFY_IS_APPROX(hp1d.template cast<Scalar>(),b0);\n}\n\n\nvoid specificTest1()\n{\n    Vector2f m; m << -1.0f, -2.0f;\n    Vector2f M; M <<  1.0f,  5.0f;\n\n    typedef AlignedBox2f  BoxType;\n    BoxType box( m, M );\n\n    Vector2f sides = M-m;\n    VERIFY_IS_APPROX(sides, box.sizes() );\n    VERIFY_IS_APPROX(sides[1], box.sizes()[1] );\n    VERIFY_IS_APPROX(sides[1], box.sizes().maxCoeff() );\n    VERIFY_IS_APPROX(sides[0], box.sizes().minCoeff() );\n\n    VERIFY_IS_APPROX( 14.0f, box.volume() );\n    VERIFY_IS_APPROX( 53.0f, box.diagonal().squaredNorm() );\n    VERIFY_IS_APPROX( std::sqrt( 53.0f ), box.diagonal().norm() );\n\n    VERIFY_IS_APPROX( m, box.corner( BoxType::BottomLeft ) );\n    VERIFY_IS_APPROX( M, box.corner( BoxType::TopRight ) );\n    Vector2f bottomRight; bottomRight << M[0], m[1];\n    Vector2f topLeft; topLeft << m[0], M[1];\n    VERIFY_IS_APPROX( bottomRight, box.corner( BoxType::BottomRight ) );\n    VERIFY_IS_APPROX( topLeft, box.corner( BoxType::TopLeft ) );\n}\n\n\nvoid specificTest2()\n{\n    Vector3i m; m << -1, -2, 0;\n    Vector3i M; M <<  1,  5, 3;\n\n    typedef AlignedBox3i  BoxType;\n    BoxType box( m, M );\n\n    Vector3i sides = M-m;\n    VERIFY_IS_APPROX(sides, box.sizes() );\n    VERIFY_IS_APPROX(sides[1], box.sizes()[1] );\n    VERIFY_IS_APPROX(sides[1], box.sizes().maxCoeff() );\n    VERIFY_IS_APPROX(sides[0], box.sizes().minCoeff() );\n\n    VERIFY_IS_APPROX( 42, box.volume() );\n    VERIFY_IS_APPROX( 62, box.diagonal().squaredNorm() );\n\n    VERIFY_IS_APPROX( m, box.corner( BoxType::BottomLeftFloor ) );\n    VERIFY_IS_APPROX( M, box.corner( BoxType::TopRightCeil ) );\n    Vector3i bottomRightFloor; bottomRightFloor << M[0], m[1], m[2];\n    Vector3i topLeftFloor; topLeftFloor << m[0], M[1], m[2];\n    VERIFY_IS_APPROX( bottomRightFloor, box.corner( BoxType::BottomRightFloor ) );\n    VERIFY_IS_APPROX( topLeftFloor, box.corner( BoxType::TopLeftFloor ) );\n}\n\n\nEIGEN_DECLARE_TEST(geo_alignedbox)\n{\n  for(int i = 0; i < g_repeat; i++)\n  {\n    CALL_SUBTEST_1( (alignedboxNonIntegralRotatable<AlignedBox2f, Rotation2Df>(AlignedBox2f(), &rotate2D)) );\n    CALL_SUBTEST_2( alignedboxCastTests(AlignedBox2f()) );\n\n    CALL_SUBTEST_3( (alignedboxNonIntegralRotatable<AlignedBox3f, AngleAxisf>(AlignedBox3f(), &rotate3DZAxis)) );\n    CALL_SUBTEST_4( alignedboxCastTests(AlignedBox3f()) );\n\n    CALL_SUBTEST_5( (alignedboxNonIntegralRotatable<AlignedBox4d, Matrix4d>(AlignedBox4d(), &rotate4DZWAxis)) );\n    CALL_SUBTEST_6( alignedboxCastTests(AlignedBox4d()) );\n\n    CALL_SUBTEST_7( alignedboxTranslatable(AlignedBox1d()) );\n    CALL_SUBTEST_8( alignedboxCastTests(AlignedBox1d()) );\n\n    CALL_SUBTEST_9( alignedboxTranslatable(AlignedBox1i()) );\n    CALL_SUBTEST_10( (alignedboxRotatable<AlignedBox2i, Matrix2i>(AlignedBox2i(), &rotate2DIntegral<int, Matrix2i>)) );\n    CALL_SUBTEST_11( (alignedboxRotatable<AlignedBox3i, Matrix3i>(AlignedBox3i(), &rotate3DZAxisIntegral<int, Matrix3i>)) );\n\n    CALL_SUBTEST_14( alignedbox(AlignedBox<double,Dynamic>(4)) );\n  }\n  CALL_SUBTEST_12( specificTest1() );\n  CALL_SUBTEST_13( specificTest2() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/geo_eulerangles.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/Geometry>\n#include <Eigen/LU>\n#include <Eigen/SVD>\n\n\ntemplate<typename Scalar>\nvoid verify_euler(const Matrix<Scalar,3,1>& ea, int i, int j, int k)\n{\n  typedef Matrix<Scalar,3,3> Matrix3;\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef AngleAxis<Scalar> AngleAxisx;\n  using std::abs;\n  Matrix3 m(AngleAxisx(ea[0], Vector3::Unit(i)) * AngleAxisx(ea[1], Vector3::Unit(j)) * AngleAxisx(ea[2], Vector3::Unit(k)));\n  Vector3 eabis = m.eulerAngles(i, j, k);\n  Matrix3 mbis(AngleAxisx(eabis[0], Vector3::Unit(i)) * AngleAxisx(eabis[1], Vector3::Unit(j)) * AngleAxisx(eabis[2], Vector3::Unit(k))); \n  VERIFY_IS_APPROX(m,  mbis); \n  /* If I==K, and ea[1]==0, then there no unique solution. */ \n  /* The remark apply in the case where I!=K, and |ea[1]| is close to pi/2. */ \n  if( (i!=k || ea[1]!=0) && (i==k || !internal::isApprox(abs(ea[1]),Scalar(EIGEN_PI/2),test_precision<Scalar>())) ) \n    VERIFY((ea-eabis).norm() <= test_precision<Scalar>());\n  \n  // approx_or_less_than does not work for 0\n  VERIFY(0 < eabis[0] || test_isMuchSmallerThan(eabis[0], Scalar(1)));\n  VERIFY_IS_APPROX_OR_LESS_THAN(eabis[0], Scalar(EIGEN_PI));\n  VERIFY_IS_APPROX_OR_LESS_THAN(-Scalar(EIGEN_PI), eabis[1]);\n  VERIFY_IS_APPROX_OR_LESS_THAN(eabis[1], Scalar(EIGEN_PI));\n  VERIFY_IS_APPROX_OR_LESS_THAN(-Scalar(EIGEN_PI), eabis[2]);\n  VERIFY_IS_APPROX_OR_LESS_THAN(eabis[2], Scalar(EIGEN_PI));\n}\n\ntemplate<typename Scalar> void check_all_var(const Matrix<Scalar,3,1>& ea)\n{\n  verify_euler(ea, 0,1,2);\n  verify_euler(ea, 0,1,0);\n  verify_euler(ea, 0,2,1);\n  verify_euler(ea, 0,2,0);\n\n  verify_euler(ea, 1,2,0);\n  verify_euler(ea, 1,2,1);\n  verify_euler(ea, 1,0,2);\n  verify_euler(ea, 1,0,1);\n\n  verify_euler(ea, 2,0,1);\n  verify_euler(ea, 2,0,2);\n  verify_euler(ea, 2,1,0);\n  verify_euler(ea, 2,1,2);\n}\n\ntemplate<typename Scalar> void eulerangles()\n{\n  typedef Matrix<Scalar,3,3> Matrix3;\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef Array<Scalar,3,1> Array3;\n  typedef Quaternion<Scalar> Quaternionx;\n  typedef AngleAxis<Scalar> AngleAxisx;\n\n  Scalar a = internal::random<Scalar>(-Scalar(EIGEN_PI), Scalar(EIGEN_PI));\n  Quaternionx q1;\n  q1 = AngleAxisx(a, Vector3::Random().normalized());\n  Matrix3 m;\n  m = q1;\n  \n  Vector3 ea = m.eulerAngles(0,1,2);\n  check_all_var(ea);\n  ea = m.eulerAngles(0,1,0);\n  check_all_var(ea);\n  \n  // Check with purely random Quaternion:\n  q1.coeffs() = Quaternionx::Coefficients::Random().normalized();\n  m = q1;\n  ea = m.eulerAngles(0,1,2);\n  check_all_var(ea);\n  ea = m.eulerAngles(0,1,0);\n  check_all_var(ea);\n  \n  // Check with random angles in range [0:pi]x[-pi:pi]x[-pi:pi].\n  ea = (Array3::Random() + Array3(1,0,0))*Scalar(EIGEN_PI)*Array3(0.5,1,1);\n  check_all_var(ea);\n  \n  ea[2] = ea[0] = internal::random<Scalar>(0,Scalar(EIGEN_PI));\n  check_all_var(ea);\n  \n  ea[0] = ea[1] = internal::random<Scalar>(0,Scalar(EIGEN_PI));\n  check_all_var(ea);\n  \n  ea[1] = 0;\n  check_all_var(ea);\n  \n  ea.head(2).setZero();\n  check_all_var(ea);\n  \n  ea.setZero();\n  check_all_var(ea);\n}\n\nEIGEN_DECLARE_TEST(geo_eulerangles)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( eulerangles<float>() );\n    CALL_SUBTEST_2( eulerangles<double>() );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/geo_homogeneous.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/Geometry>\n\ntemplate<typename Scalar,int Size> void homogeneous(void)\n{\n  /* this test covers the following files:\n     Homogeneous.h\n  */\n\n  typedef Matrix<Scalar,Size,Size> MatrixType;\n  typedef Matrix<Scalar,Size,1, ColMajor> VectorType;\n\n  typedef Matrix<Scalar,Size+1,Size> HMatrixType;\n  typedef Matrix<Scalar,Size+1,1> HVectorType;\n\n  typedef Matrix<Scalar,Size,Size+1>   T1MatrixType;\n  typedef Matrix<Scalar,Size+1,Size+1> T2MatrixType;\n  typedef Matrix<Scalar,Size+1,Size> T3MatrixType;\n\n  VectorType v0 = VectorType::Random(),\n             ones = VectorType::Ones();\n\n  HVectorType hv0 = HVectorType::Random();\n\n  MatrixType m0 = MatrixType::Random();\n\n  HMatrixType hm0 = HMatrixType::Random();\n\n  hv0 << v0, 1;\n  VERIFY_IS_APPROX(v0.homogeneous(), hv0);\n  VERIFY_IS_APPROX(v0, hv0.hnormalized());\n  \n  VERIFY_IS_APPROX(v0.homogeneous().sum(), hv0.sum());\n  VERIFY_IS_APPROX(v0.homogeneous().minCoeff(), hv0.minCoeff());\n  VERIFY_IS_APPROX(v0.homogeneous().maxCoeff(), hv0.maxCoeff());\n\n  hm0 << m0, ones.transpose();\n  VERIFY_IS_APPROX(m0.colwise().homogeneous(), hm0);\n  VERIFY_IS_APPROX(m0, hm0.colwise().hnormalized());\n  hm0.row(Size-1).setRandom();\n  for(int j=0; j<Size; ++j)\n    m0.col(j) = hm0.col(j).head(Size) / hm0(Size,j);\n  VERIFY_IS_APPROX(m0, hm0.colwise().hnormalized());\n\n  T1MatrixType t1 = T1MatrixType::Random();\n  VERIFY_IS_APPROX(t1 * (v0.homogeneous().eval()), t1 * v0.homogeneous());\n  VERIFY_IS_APPROX(t1 * (m0.colwise().homogeneous().eval()), t1 * m0.colwise().homogeneous());\n\n  T2MatrixType t2 = T2MatrixType::Random();\n  VERIFY_IS_APPROX(t2 * (v0.homogeneous().eval()), t2 * v0.homogeneous());\n  VERIFY_IS_APPROX(t2 * (m0.colwise().homogeneous().eval()), t2 * m0.colwise().homogeneous());\n  VERIFY_IS_APPROX(t2 * (v0.homogeneous().asDiagonal()), t2 * hv0.asDiagonal());\n  VERIFY_IS_APPROX((v0.homogeneous().asDiagonal()) * t2, hv0.asDiagonal() * t2);\n\n  VERIFY_IS_APPROX((v0.transpose().rowwise().homogeneous().eval()) * t2,\n                    v0.transpose().rowwise().homogeneous() * t2);\n  VERIFY_IS_APPROX((m0.transpose().rowwise().homogeneous().eval()) * t2,\n                    m0.transpose().rowwise().homogeneous() * t2);\n\n  T3MatrixType t3 = T3MatrixType::Random();\n  VERIFY_IS_APPROX((v0.transpose().rowwise().homogeneous().eval()) * t3,\n                    v0.transpose().rowwise().homogeneous() * t3);\n  VERIFY_IS_APPROX((m0.transpose().rowwise().homogeneous().eval()) * t3,\n                    m0.transpose().rowwise().homogeneous() * t3);\n\n  // test product with a Transform object\n  Transform<Scalar, Size, Affine> aff;\n  Transform<Scalar, Size, AffineCompact> caff;\n  Transform<Scalar, Size, Projective> proj;\n  Matrix<Scalar, Size, Dynamic>   pts;\n  Matrix<Scalar, Size+1, Dynamic> pts1, pts2;\n\n  aff.affine().setRandom();\n  proj = caff = aff;\n  pts.setRandom(Size,internal::random<int>(1,20));\n  \n  pts1 = pts.colwise().homogeneous();\n  VERIFY_IS_APPROX(aff  * pts.colwise().homogeneous(), (aff  * pts1).colwise().hnormalized());\n  VERIFY_IS_APPROX(caff * pts.colwise().homogeneous(), (caff * pts1).colwise().hnormalized());\n  VERIFY_IS_APPROX(proj * pts.colwise().homogeneous(), (proj * pts1));\n\n  VERIFY_IS_APPROX((aff  * pts1).colwise().hnormalized(),  aff  * pts);\n  VERIFY_IS_APPROX((caff * pts1).colwise().hnormalized(), caff * pts);\n  \n  pts2 = pts1;\n  pts2.row(Size).setRandom();\n  VERIFY_IS_APPROX((aff  * pts2).colwise().hnormalized(), aff  * pts2.colwise().hnormalized());\n  VERIFY_IS_APPROX((caff * pts2).colwise().hnormalized(), caff * pts2.colwise().hnormalized());\n  VERIFY_IS_APPROX((proj * pts2).colwise().hnormalized(), (proj * pts2.colwise().hnormalized().colwise().homogeneous()).colwise().hnormalized());\n  \n  // Test combination of homogeneous\n  \n  VERIFY_IS_APPROX( (t2 * v0.homogeneous()).hnormalized(),\n                       (t2.template topLeftCorner<Size,Size>() * v0 + t2.template topRightCorner<Size,1>())\n                     / ((t2.template bottomLeftCorner<1,Size>()*v0).value() + t2(Size,Size)) );\n  \n  VERIFY_IS_APPROX( (t2 * pts.colwise().homogeneous()).colwise().hnormalized(),\n                    (Matrix<Scalar, Size+1, Dynamic>(t2 * pts1).colwise().hnormalized()) );\n  \n  VERIFY_IS_APPROX( (t2 .lazyProduct( v0.homogeneous() )).hnormalized(), (t2 * v0.homogeneous()).hnormalized() );\n  VERIFY_IS_APPROX( (t2 .lazyProduct  ( pts.colwise().homogeneous() )).colwise().hnormalized(), (t2 * pts1).colwise().hnormalized() );\n  \n  VERIFY_IS_APPROX( (v0.transpose().homogeneous() .lazyProduct( t2 )).hnormalized(), (v0.transpose().homogeneous()*t2).hnormalized() );\n  VERIFY_IS_APPROX( (pts.transpose().rowwise().homogeneous() .lazyProduct( t2 )).rowwise().hnormalized(), (pts1.transpose()*t2).rowwise().hnormalized() );\n\n  VERIFY_IS_APPROX( (t2.template triangularView<Lower>() * v0.homogeneous()).eval(), (t2.template triangularView<Lower>()*hv0) );\n}\n\nEIGEN_DECLARE_TEST(geo_homogeneous)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(( homogeneous<float,1>() ));\n    CALL_SUBTEST_2(( homogeneous<double,3>() ));\n    CALL_SUBTEST_3(( homogeneous<double,8>() ));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/geo_hyperplane.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/Geometry>\n#include <Eigen/LU>\n#include <Eigen/QR>\n\ntemplate<typename HyperplaneType> void hyperplane(const HyperplaneType& _plane)\n{\n  /* this test covers the following files:\n     Hyperplane.h\n  */\n  using std::abs;\n  const Index dim = _plane.dim();\n  enum { Options = HyperplaneType::Options };\n  typedef typename HyperplaneType::Scalar Scalar;\n  typedef typename HyperplaneType::RealScalar RealScalar;\n  typedef Matrix<Scalar, HyperplaneType::AmbientDimAtCompileTime, 1> VectorType;\n  typedef Matrix<Scalar, HyperplaneType::AmbientDimAtCompileTime,\n                         HyperplaneType::AmbientDimAtCompileTime> MatrixType;\n\n  VectorType p0 = VectorType::Random(dim);\n  VectorType p1 = VectorType::Random(dim);\n\n  VectorType n0 = VectorType::Random(dim).normalized();\n  VectorType n1 = VectorType::Random(dim).normalized();\n\n  HyperplaneType pl0(n0, p0);\n  HyperplaneType pl1(n1, p1);\n  HyperplaneType pl2 = pl1;\n\n  Scalar s0 = internal::random<Scalar>();\n  Scalar s1 = internal::random<Scalar>();\n\n  VERIFY_IS_APPROX( n1.dot(n1), Scalar(1) );\n\n  VERIFY_IS_MUCH_SMALLER_THAN( pl0.absDistance(p0), Scalar(1) );\n  if(numext::abs2(s0)>RealScalar(1e-6))\n    VERIFY_IS_APPROX( pl1.signedDistance(p1 + n1 * s0), s0);\n  else\n    VERIFY_IS_MUCH_SMALLER_THAN( abs(pl1.signedDistance(p1 + n1 * s0) - s0), Scalar(1) );\n  VERIFY_IS_MUCH_SMALLER_THAN( pl1.signedDistance(pl1.projection(p0)), Scalar(1) );\n  VERIFY_IS_MUCH_SMALLER_THAN( pl1.absDistance(p1 +  pl1.normal().unitOrthogonal() * s1), Scalar(1) );\n\n  // transform\n  if (!NumTraits<Scalar>::IsComplex)\n  {\n    MatrixType rot = MatrixType::Random(dim,dim).householderQr().householderQ();\n    DiagonalMatrix<Scalar,HyperplaneType::AmbientDimAtCompileTime> scaling(VectorType::Random());\n    Translation<Scalar,HyperplaneType::AmbientDimAtCompileTime> translation(VectorType::Random());\n    \n    while(scaling.diagonal().cwiseAbs().minCoeff()<RealScalar(1e-4)) scaling.diagonal() = VectorType::Random();\n\n    pl2 = pl1;\n    VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot).absDistance(rot * p1), Scalar(1) );\n    pl2 = pl1;\n    VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot,Isometry).absDistance(rot * p1), Scalar(1) );\n    pl2 = pl1;\n    VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot*scaling).absDistance((rot*scaling) * p1), Scalar(1) );\n    VERIFY_IS_APPROX( pl2.normal().norm(), RealScalar(1) );\n    pl2 = pl1;\n    VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot*scaling*translation)\n                                  .absDistance((rot*scaling*translation) * p1), Scalar(1) );\n    VERIFY_IS_APPROX( pl2.normal().norm(), RealScalar(1) );\n    pl2 = pl1;\n    VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot*translation,Isometry)\n                                 .absDistance((rot*translation) * p1), Scalar(1) );\n    VERIFY_IS_APPROX( pl2.normal().norm(), RealScalar(1) );\n  }\n\n  // casting\n  const int Dim = HyperplaneType::AmbientDimAtCompileTime;\n  typedef typename GetDifferentType<Scalar>::type OtherScalar;\n  Hyperplane<OtherScalar,Dim,Options> hp1f = pl1.template cast<OtherScalar>();\n  VERIFY_IS_APPROX(hp1f.template cast<Scalar>(),pl1);\n  Hyperplane<Scalar,Dim,Options> hp1d = pl1.template cast<Scalar>();\n  VERIFY_IS_APPROX(hp1d.template cast<Scalar>(),pl1);\n}\n\ntemplate<typename Scalar> void lines()\n{\n  using std::abs;\n  typedef Hyperplane<Scalar, 2> HLine;\n  typedef ParametrizedLine<Scalar, 2> PLine;\n  typedef Matrix<Scalar,2,1> Vector;\n  typedef Matrix<Scalar,3,1> CoeffsType;\n\n  for(int i = 0; i < 10; i++)\n  {\n    Vector center = Vector::Random();\n    Vector u = Vector::Random();\n    Vector v = Vector::Random();\n    Scalar a = internal::random<Scalar>();\n    while (abs(a-1) < Scalar(1e-4)) a = internal::random<Scalar>();\n    while (u.norm() < Scalar(1e-4)) u = Vector::Random();\n    while (v.norm() < Scalar(1e-4)) v = Vector::Random();\n\n    HLine line_u = HLine::Through(center + u, center + a*u);\n    HLine line_v = HLine::Through(center + v, center + a*v);\n\n    // the line equations should be normalized so that a^2+b^2=1\n    VERIFY_IS_APPROX(line_u.normal().norm(), Scalar(1));\n    VERIFY_IS_APPROX(line_v.normal().norm(), Scalar(1));\n\n    Vector result = line_u.intersection(line_v);\n\n    // the lines should intersect at the point we called \"center\"\n    if(abs(a-1) > Scalar(1e-2) && abs(v.normalized().dot(u.normalized()))<Scalar(0.9))\n      VERIFY_IS_APPROX(result, center);\n\n    // check conversions between two types of lines\n    PLine pl(line_u); // gcc 3.3 will crash if we don't name this variable.\n    HLine line_u2(pl);\n    CoeffsType converted_coeffs = line_u2.coeffs();\n    if(line_u2.normal().dot(line_u.normal())<Scalar(0))\n      converted_coeffs = -line_u2.coeffs();\n    VERIFY(line_u.coeffs().isApprox(converted_coeffs));\n  }\n}\n\ntemplate<typename Scalar> void planes()\n{\n  using std::abs;\n  typedef Hyperplane<Scalar, 3> Plane;\n  typedef Matrix<Scalar,3,1> Vector;\n\n  for(int i = 0; i < 10; i++)\n  {\n    Vector v0 = Vector::Random();\n    Vector v1(v0), v2(v0);\n    if(internal::random<double>(0,1)>0.25)\n      v1 += Vector::Random();\n    if(internal::random<double>(0,1)>0.25)\n      v2 += v1 * std::pow(internal::random<Scalar>(0,1),internal::random<int>(1,16));\n    if(internal::random<double>(0,1)>0.25)\n      v2 += Vector::Random() * std::pow(internal::random<Scalar>(0,1),internal::random<int>(1,16));\n\n    Plane p0 = Plane::Through(v0, v1, v2);\n\n    VERIFY_IS_APPROX(p0.normal().norm(), Scalar(1));\n    VERIFY_IS_MUCH_SMALLER_THAN(p0.absDistance(v0), Scalar(1));\n    VERIFY_IS_MUCH_SMALLER_THAN(p0.absDistance(v1), Scalar(1));\n    VERIFY_IS_MUCH_SMALLER_THAN(p0.absDistance(v2), Scalar(1));\n  }\n}\n\ntemplate<typename Scalar> void hyperplane_alignment()\n{\n  typedef Hyperplane<Scalar,3,AutoAlign> Plane3a;\n  typedef Hyperplane<Scalar,3,DontAlign> Plane3u;\n\n  EIGEN_ALIGN_MAX Scalar array1[4];\n  EIGEN_ALIGN_MAX Scalar array2[4];\n  EIGEN_ALIGN_MAX Scalar array3[4+1];\n  Scalar* array3u = array3+1;\n\n  Plane3a *p1 = ::new(reinterpret_cast<void*>(array1)) Plane3a;\n  Plane3u *p2 = ::new(reinterpret_cast<void*>(array2)) Plane3u;\n  Plane3u *p3 = ::new(reinterpret_cast<void*>(array3u)) Plane3u;\n  \n  p1->coeffs().setRandom();\n  *p2 = *p1;\n  *p3 = *p1;\n\n  VERIFY_IS_APPROX(p1->coeffs(), p2->coeffs());\n  VERIFY_IS_APPROX(p1->coeffs(), p3->coeffs());\n}\n\n\nEIGEN_DECLARE_TEST(geo_hyperplane)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( hyperplane(Hyperplane<float,2>()) );\n    CALL_SUBTEST_2( hyperplane(Hyperplane<float,3>()) );\n    CALL_SUBTEST_2( hyperplane(Hyperplane<float,3,DontAlign>()) );\n    CALL_SUBTEST_2( hyperplane_alignment<float>() );\n    CALL_SUBTEST_3( hyperplane(Hyperplane<double,4>()) );\n    CALL_SUBTEST_4( hyperplane(Hyperplane<std::complex<double>,5>()) );\n    CALL_SUBTEST_1( lines<float>() );\n    CALL_SUBTEST_3( lines<double>() );\n    CALL_SUBTEST_2( planes<float>() );\n    CALL_SUBTEST_5( planes<double>() );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/geo_orthomethods.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/Geometry>\n#include <Eigen/LU>\n#include <Eigen/SVD>\n\n/* this test covers the following files:\n   Geometry/OrthoMethods.h\n*/\n\ntemplate<typename Scalar> void orthomethods_3()\n{\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar,3,3> Matrix3;\n  typedef Matrix<Scalar,3,1> Vector3;\n\n  typedef Matrix<Scalar,4,1> Vector4;\n\n  Vector3 v0 = Vector3::Random(),\n          v1 = Vector3::Random(),\n          v2 = Vector3::Random();\n\n  // cross product\n  VERIFY_IS_MUCH_SMALLER_THAN(v1.cross(v2).dot(v1), Scalar(1));\n  VERIFY_IS_MUCH_SMALLER_THAN(v1.dot(v1.cross(v2)), Scalar(1));\n  VERIFY_IS_MUCH_SMALLER_THAN(v1.cross(v2).dot(v2), Scalar(1));\n  VERIFY_IS_MUCH_SMALLER_THAN(v2.dot(v1.cross(v2)), Scalar(1));\n  VERIFY_IS_MUCH_SMALLER_THAN(v1.cross(Vector3::Random()).dot(v1), Scalar(1));\n  Matrix3 mat3;\n  mat3 << v0.normalized(),\n         (v0.cross(v1)).normalized(),\n         (v0.cross(v1).cross(v0)).normalized();\n  VERIFY(mat3.isUnitary());\n  \n  mat3.setRandom();\n  VERIFY_IS_APPROX(v0.cross(mat3*v1), -(mat3*v1).cross(v0));\n  VERIFY_IS_APPROX(v0.cross(mat3.lazyProduct(v1)), -(mat3.lazyProduct(v1)).cross(v0));\n\n  // colwise/rowwise cross product\n  mat3.setRandom();\n  Vector3 vec3 = Vector3::Random();\n  Matrix3 mcross;\n  int i = internal::random<int>(0,2);\n  mcross = mat3.colwise().cross(vec3);\n  VERIFY_IS_APPROX(mcross.col(i), mat3.col(i).cross(vec3));\n  \n  VERIFY_IS_MUCH_SMALLER_THAN((mat3.adjoint() * mat3.colwise().cross(vec3)).diagonal().cwiseAbs().sum(), Scalar(1));\n  VERIFY_IS_MUCH_SMALLER_THAN((mat3.adjoint() * mat3.colwise().cross(Vector3::Random())).diagonal().cwiseAbs().sum(), Scalar(1));\n  \n  VERIFY_IS_MUCH_SMALLER_THAN((vec3.adjoint() * mat3.colwise().cross(vec3)).cwiseAbs().sum(), Scalar(1));\n  VERIFY_IS_MUCH_SMALLER_THAN((vec3.adjoint() * Matrix3::Random().colwise().cross(vec3)).cwiseAbs().sum(), Scalar(1));\n  \n  mcross = mat3.rowwise().cross(vec3);\n  VERIFY_IS_APPROX(mcross.row(i), mat3.row(i).cross(vec3));\n\n  // cross3\n  Vector4 v40 = Vector4::Random(),\n          v41 = Vector4::Random(),\n          v42 = Vector4::Random();\n  v40.w() = v41.w() = v42.w() = 0;\n  v42.template head<3>() = v40.template head<3>().cross(v41.template head<3>());\n  VERIFY_IS_APPROX(v40.cross3(v41), v42);\n  VERIFY_IS_MUCH_SMALLER_THAN(v40.cross3(Vector4::Random()).dot(v40), Scalar(1));\n  \n  // check mixed product\n  typedef Matrix<RealScalar, 3, 1> RealVector3;\n  RealVector3 rv1 = RealVector3::Random();\n  VERIFY_IS_APPROX(v1.cross(rv1.template cast<Scalar>()), v1.cross(rv1));\n  VERIFY_IS_APPROX(rv1.template cast<Scalar>().cross(v1), rv1.cross(v1));\n}\n\ntemplate<typename Scalar, int Size> void orthomethods(int size=Size)\n{\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar,Size,1> VectorType;\n  typedef Matrix<Scalar,3,Size> Matrix3N;\n  typedef Matrix<Scalar,Size,3> MatrixN3;\n  typedef Matrix<Scalar,3,1> Vector3;\n\n  VectorType v0 = VectorType::Random(size);\n\n  // unitOrthogonal\n  VERIFY_IS_MUCH_SMALLER_THAN(v0.unitOrthogonal().dot(v0), Scalar(1));\n  VERIFY_IS_APPROX(v0.unitOrthogonal().norm(), RealScalar(1));\n\n  if (size>=3)\n  {\n    v0.template head<2>().setZero();\n    v0.tail(size-2).setRandom();\n\n    VERIFY_IS_MUCH_SMALLER_THAN(v0.unitOrthogonal().dot(v0), Scalar(1));\n    VERIFY_IS_APPROX(v0.unitOrthogonal().norm(), RealScalar(1));\n  }\n\n  // colwise/rowwise cross product\n  Vector3 vec3 = Vector3::Random();\n  int i = internal::random<int>(0,size-1);\n\n  Matrix3N mat3N(3,size), mcross3N(3,size);\n  mat3N.setRandom();\n  mcross3N = mat3N.colwise().cross(vec3);\n  VERIFY_IS_APPROX(mcross3N.col(i), mat3N.col(i).cross(vec3));\n\n  MatrixN3 matN3(size,3), mcrossN3(size,3);\n  matN3.setRandom();\n  mcrossN3 = matN3.rowwise().cross(vec3);\n  VERIFY_IS_APPROX(mcrossN3.row(i), matN3.row(i).cross(vec3));\n}\n\nEIGEN_DECLARE_TEST(geo_orthomethods)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( orthomethods_3<float>() );\n    CALL_SUBTEST_2( orthomethods_3<double>() );\n    CALL_SUBTEST_4( orthomethods_3<std::complex<double> >() );\n    CALL_SUBTEST_1( (orthomethods<float,2>()) );\n    CALL_SUBTEST_2( (orthomethods<double,2>()) );\n    CALL_SUBTEST_1( (orthomethods<float,3>()) );\n    CALL_SUBTEST_2( (orthomethods<double,3>()) );\n    CALL_SUBTEST_3( (orthomethods<float,7>()) );\n    CALL_SUBTEST_4( (orthomethods<std::complex<double>,8>()) );\n    CALL_SUBTEST_5( (orthomethods<float,Dynamic>(36)) );\n    CALL_SUBTEST_6( (orthomethods<double,Dynamic>(35)) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/geo_parametrizedline.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/Geometry>\n#include <Eigen/LU>\n#include <Eigen/QR>\n\ntemplate<typename LineType> void parametrizedline(const LineType& _line)\n{\n  /* this test covers the following files:\n     ParametrizedLine.h\n  */\n  using std::abs;\n  const Index dim = _line.dim();\n  typedef typename LineType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar, LineType::AmbientDimAtCompileTime, 1> VectorType;\n  typedef Hyperplane<Scalar,LineType::AmbientDimAtCompileTime> HyperplaneType;\n  typedef Matrix<Scalar, HyperplaneType::AmbientDimAtCompileTime,\n                         HyperplaneType::AmbientDimAtCompileTime> MatrixType;\n\n  VectorType p0 = VectorType::Random(dim);\n  VectorType p1 = VectorType::Random(dim);\n\n  VectorType d0 = VectorType::Random(dim).normalized();\n\n  LineType l0(p0, d0);\n\n  Scalar s0 = internal::random<Scalar>();\n  Scalar s1 = abs(internal::random<Scalar>());\n\n  VERIFY_IS_MUCH_SMALLER_THAN( l0.distance(p0), RealScalar(1) );\n  VERIFY_IS_MUCH_SMALLER_THAN( l0.distance(p0+s0*d0), RealScalar(1) );\n  VERIFY_IS_APPROX( (l0.projection(p1)-p1).norm(), l0.distance(p1) );\n  VERIFY_IS_MUCH_SMALLER_THAN( l0.distance(l0.projection(p1)), RealScalar(1) );\n  VERIFY_IS_APPROX( Scalar(l0.distance((p0+s0*d0) + d0.unitOrthogonal() * s1)), s1 );\n\n  // casting\n  const int Dim = LineType::AmbientDimAtCompileTime;\n  typedef typename GetDifferentType<Scalar>::type OtherScalar;\n  ParametrizedLine<OtherScalar,Dim> hp1f = l0.template cast<OtherScalar>();\n  VERIFY_IS_APPROX(hp1f.template cast<Scalar>(),l0);\n  ParametrizedLine<Scalar,Dim> hp1d = l0.template cast<Scalar>();\n  VERIFY_IS_APPROX(hp1d.template cast<Scalar>(),l0);\n\n  // intersections\n  VectorType p2 = VectorType::Random(dim);\n  VectorType n2 = VectorType::Random(dim).normalized();\n  HyperplaneType hp(p2,n2);\n  Scalar t = l0.intersectionParameter(hp);\n  VectorType pi = l0.pointAt(t);\n  VERIFY_IS_MUCH_SMALLER_THAN(hp.signedDistance(pi), RealScalar(1));\n  VERIFY_IS_MUCH_SMALLER_THAN(l0.distance(pi), RealScalar(1));\n  VERIFY_IS_APPROX(l0.intersectionPoint(hp), pi);\n\n  // transform\n  if (!NumTraits<Scalar>::IsComplex)\n  {\n    MatrixType rot = MatrixType::Random(dim,dim).householderQr().householderQ();\n    DiagonalMatrix<Scalar,LineType::AmbientDimAtCompileTime> scaling(VectorType::Random());\n    Translation<Scalar,LineType::AmbientDimAtCompileTime> translation(VectorType::Random());\n\n    while(scaling.diagonal().cwiseAbs().minCoeff()<RealScalar(1e-4)) scaling.diagonal() = VectorType::Random();\n\n    LineType l1 = l0;\n    VectorType p3 = l0.pointAt(Scalar(1));\n    VERIFY_IS_MUCH_SMALLER_THAN( l1.transform(rot).distance(rot * p3), Scalar(1) );\n    l1 = l0;\n    VERIFY_IS_MUCH_SMALLER_THAN( l1.transform(rot,Isometry).distance(rot * p3), Scalar(1) );\n    l1 = l0;\n    VERIFY_IS_MUCH_SMALLER_THAN( l1.transform(rot*scaling).distance((rot*scaling) * p3), Scalar(1) );\n    l1 = l0;\n    VERIFY_IS_MUCH_SMALLER_THAN( l1.transform(rot*scaling*translation)\n                                   .distance((rot*scaling*translation) * p3), Scalar(1) );\n    l1 = l0;\n    VERIFY_IS_MUCH_SMALLER_THAN( l1.transform(rot*translation,Isometry)\n                                   .distance((rot*translation) * p3), Scalar(1) );\n  }\n\n}\n\ntemplate<typename Scalar> void parametrizedline_alignment()\n{\n  typedef ParametrizedLine<Scalar,4,AutoAlign> Line4a;\n  typedef ParametrizedLine<Scalar,4,DontAlign> Line4u;\n\n  EIGEN_ALIGN_MAX Scalar array1[16];\n  EIGEN_ALIGN_MAX Scalar array2[16];\n  EIGEN_ALIGN_MAX Scalar array3[16+1];\n  Scalar* array3u = array3+1;\n\n  Line4a *p1 = ::new(reinterpret_cast<void*>(array1)) Line4a;\n  Line4u *p2 = ::new(reinterpret_cast<void*>(array2)) Line4u;\n  Line4u *p3 = ::new(reinterpret_cast<void*>(array3u)) Line4u;\n  \n  p1->origin().setRandom();\n  p1->direction().setRandom();\n  *p2 = *p1;\n  *p3 = *p1;\n\n  VERIFY_IS_APPROX(p1->origin(), p2->origin());\n  VERIFY_IS_APPROX(p1->origin(), p3->origin());\n  VERIFY_IS_APPROX(p1->direction(), p2->direction());\n  VERIFY_IS_APPROX(p1->direction(), p3->direction());\n}\n\nEIGEN_DECLARE_TEST(geo_parametrizedline)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( parametrizedline(ParametrizedLine<float,2>()) );\n    CALL_SUBTEST_2( parametrizedline(ParametrizedLine<float,3>()) );\n    CALL_SUBTEST_2( parametrizedline_alignment<float>() );\n    CALL_SUBTEST_3( parametrizedline(ParametrizedLine<double,4>()) );\n    CALL_SUBTEST_3( parametrizedline_alignment<double>() );\n    CALL_SUBTEST_4( parametrizedline(ParametrizedLine<std::complex<double>,5>()) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/geo_quaternion.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Mathieu Gautier <mathieu.gautier@cea.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/Geometry>\n#include <Eigen/LU>\n#include <Eigen/SVD>\n#include \"AnnoyingScalar.h\"\n\ntemplate<typename T> T bounded_acos(T v)\n{\n  using std::acos;\n  using std::min;\n  using std::max;\n  return acos((max)(T(-1),(min)(v,T(1))));\n}\n\ntemplate<typename QuatType> void check_slerp(const QuatType& q0, const QuatType& q1)\n{\n  using std::abs;\n  typedef typename QuatType::Scalar Scalar;\n  typedef AngleAxis<Scalar> AA;\n\n  Scalar largeEps = test_precision<Scalar>();\n\n  Scalar theta_tot = AA(q1*q0.inverse()).angle();\n  if(theta_tot>Scalar(EIGEN_PI))\n    theta_tot = Scalar(2.)*Scalar(EIGEN_PI)-theta_tot;\n  for(Scalar t=0; t<=Scalar(1.001); t+=Scalar(0.1))\n  {\n    QuatType q = q0.slerp(t,q1);\n    Scalar theta = AA(q*q0.inverse()).angle();\n    VERIFY(abs(q.norm() - 1) < largeEps);\n    if(theta_tot==0)  VERIFY(theta_tot==0);\n    else              VERIFY(abs(theta - t * theta_tot) < largeEps);\n  }\n}\n\ntemplate<typename Scalar, int Options> void quaternion(void)\n{\n  /* this test covers the following files:\n     Quaternion.h\n  */\n  using std::abs;\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef Matrix<Scalar,3,3> Matrix3;\n  typedef Quaternion<Scalar,Options> Quaternionx;\n  typedef AngleAxis<Scalar> AngleAxisx;\n\n  Scalar largeEps = test_precision<Scalar>();\n  if (internal::is_same<Scalar,float>::value)\n    largeEps = Scalar(1e-3);\n\n  Scalar eps = internal::random<Scalar>() * Scalar(1e-2);\n\n  Vector3 v0 = Vector3::Random(),\n          v1 = Vector3::Random(),\n          v2 = Vector3::Random(),\n          v3 = Vector3::Random();\n\n  Scalar  a = internal::random<Scalar>(-Scalar(EIGEN_PI), Scalar(EIGEN_PI)),\n          b = internal::random<Scalar>(-Scalar(EIGEN_PI), Scalar(EIGEN_PI));\n\n  // Quaternion: Identity(), setIdentity();\n  Quaternionx q1, q2;\n  q2.setIdentity();\n  VERIFY_IS_APPROX(Quaternionx(Quaternionx::Identity()).coeffs(), q2.coeffs());\n  q1.coeffs().setRandom();\n  VERIFY_IS_APPROX(q1.coeffs(), (q1*q2).coeffs());\n\n#ifndef EIGEN_NO_IO\n  // Printing\n  std::ostringstream ss;\n  ss << q2;\n  VERIFY(ss.str() == \"0i + 0j + 0k + 1\");\n#endif\n\n  // concatenation\n  q1 *= q2;\n\n  q1 = AngleAxisx(a, v0.normalized());\n  q2 = AngleAxisx(a, v1.normalized());\n\n  // angular distance\n  Scalar refangle = abs(AngleAxisx(q1.inverse()*q2).angle());\n  if (refangle>Scalar(EIGEN_PI))\n    refangle = Scalar(2)*Scalar(EIGEN_PI) - refangle;\n\n  if((q1.coeffs()-q2.coeffs()).norm() > Scalar(10)*largeEps)\n  {\n    VERIFY_IS_MUCH_SMALLER_THAN(abs(q1.angularDistance(q2) - refangle), Scalar(1));\n  }\n\n  // rotation matrix conversion\n  VERIFY_IS_APPROX(q1 * v2, q1.toRotationMatrix() * v2);\n  VERIFY_IS_APPROX(q1 * q2 * v2,\n    q1.toRotationMatrix() * q2.toRotationMatrix() * v2);\n\n  VERIFY(  (q2*q1).isApprox(q1*q2, largeEps)\n        || !(q2 * q1 * v2).isApprox(q1.toRotationMatrix() * q2.toRotationMatrix() * v2));\n\n  q2 = q1.toRotationMatrix();\n  VERIFY_IS_APPROX(q1*v1,q2*v1);\n\n  Matrix3 rot1(q1);\n  VERIFY_IS_APPROX(q1*v1,rot1*v1);\n  Quaternionx q3(rot1.transpose()*rot1);\n  VERIFY_IS_APPROX(q3*v1,v1);\n\n\n  // angle-axis conversion\n  AngleAxisx aa = AngleAxisx(q1);\n  VERIFY_IS_APPROX(q1 * v1, Quaternionx(aa) * v1);\n\n  // Do not execute the test if the rotation angle is almost zero, or\n  // the rotation axis and v1 are almost parallel.\n  if (abs(aa.angle()) > Scalar(5)*test_precision<Scalar>()\n      && (aa.axis() - v1.normalized()).norm() < Scalar(1.99)\n      && (aa.axis() + v1.normalized()).norm() < Scalar(1.99))\n  {\n    VERIFY_IS_NOT_APPROX(q1 * v1, Quaternionx(AngleAxisx(aa.angle()*2,aa.axis())) * v1);\n  }\n\n  // from two vector creation\n  VERIFY_IS_APPROX( v2.normalized(),(q2.setFromTwoVectors(v1, v2)*v1).normalized());\n  VERIFY_IS_APPROX( v1.normalized(),(q2.setFromTwoVectors(v1, v1)*v1).normalized());\n  VERIFY_IS_APPROX(-v1.normalized(),(q2.setFromTwoVectors(v1,-v1)*v1).normalized());\n  if (internal::is_same<Scalar,double>::value)\n  {\n    v3 = (v1.array()+eps).matrix();\n    VERIFY_IS_APPROX( v3.normalized(),(q2.setFromTwoVectors(v1, v3)*v1).normalized());\n    VERIFY_IS_APPROX(-v3.normalized(),(q2.setFromTwoVectors(v1,-v3)*v1).normalized());\n  }\n\n  // from two vector creation static function\n  VERIFY_IS_APPROX( v2.normalized(),(Quaternionx::FromTwoVectors(v1, v2)*v1).normalized());\n  VERIFY_IS_APPROX( v1.normalized(),(Quaternionx::FromTwoVectors(v1, v1)*v1).normalized());\n  VERIFY_IS_APPROX(-v1.normalized(),(Quaternionx::FromTwoVectors(v1,-v1)*v1).normalized());\n  if (internal::is_same<Scalar,double>::value)\n  {\n    v3 = (v1.array()+eps).matrix();\n    VERIFY_IS_APPROX( v3.normalized(),(Quaternionx::FromTwoVectors(v1, v3)*v1).normalized());\n    VERIFY_IS_APPROX(-v3.normalized(),(Quaternionx::FromTwoVectors(v1,-v3)*v1).normalized());\n  }\n\n  // inverse and conjugate\n  VERIFY_IS_APPROX(q1 * (q1.inverse() * v1), v1);\n  VERIFY_IS_APPROX(q1 * (q1.conjugate() * v1), v1);\n\n  // test casting\n  Quaternion<float> q1f = q1.template cast<float>();\n  VERIFY_IS_APPROX(q1f.template cast<Scalar>(),q1);\n  Quaternion<double> q1d = q1.template cast<double>();\n  VERIFY_IS_APPROX(q1d.template cast<Scalar>(),q1);\n\n  // test bug 369 - improper alignment.\n  Quaternionx *q = new Quaternionx;\n  delete q;\n\n  q1 = Quaternionx::UnitRandom();\n  q2 = Quaternionx::UnitRandom();\n  check_slerp(q1,q2);\n\n  q1 = AngleAxisx(b, v1.normalized());\n  q2 = AngleAxisx(b+Scalar(EIGEN_PI), v1.normalized());\n  check_slerp(q1,q2);\n\n  q1 = AngleAxisx(b,  v1.normalized());\n  q2 = AngleAxisx(-b, -v1.normalized());\n  check_slerp(q1,q2);\n\n  q1 = Quaternionx::UnitRandom();\n  q2.coeffs() = -q1.coeffs();\n  check_slerp(q1,q2);\n}\n\ntemplate<typename Scalar> void mapQuaternion(void){\n  typedef Map<Quaternion<Scalar>, Aligned> MQuaternionA;\n  typedef Map<const Quaternion<Scalar>, Aligned> MCQuaternionA;\n  typedef Map<Quaternion<Scalar> > MQuaternionUA;\n  typedef Map<const Quaternion<Scalar> > MCQuaternionUA;\n  typedef Quaternion<Scalar> Quaternionx;\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef AngleAxis<Scalar> AngleAxisx;\n  \n  Vector3 v0 = Vector3::Random(),\n          v1 = Vector3::Random();\n  Scalar  a = internal::random<Scalar>(-Scalar(EIGEN_PI), Scalar(EIGEN_PI));\n\n  EIGEN_ALIGN_MAX Scalar array1[4];\n  EIGEN_ALIGN_MAX Scalar array2[4];\n  EIGEN_ALIGN_MAX Scalar array3[4+1];\n  Scalar* array3unaligned = array3+1;\n  \n  MQuaternionA    mq1(array1);\n  MCQuaternionA   mcq1(array1);\n  MQuaternionA    mq2(array2);\n  MQuaternionUA   mq3(array3unaligned);\n  MCQuaternionUA  mcq3(array3unaligned);\n\n//  std::cerr << array1 << \" \" << array2 << \" \" << array3 << \"\\n\";\n  mq1 = AngleAxisx(a, v0.normalized());\n  mq2 = mq1;\n  mq3 = mq1;\n\n  Quaternionx q1 = mq1;\n  Quaternionx q2 = mq2;\n  Quaternionx q3 = mq3;\n  Quaternionx q4 = MCQuaternionUA(array3unaligned);\n\n  VERIFY_IS_APPROX(q1.coeffs(), q2.coeffs());\n  VERIFY_IS_APPROX(q1.coeffs(), q3.coeffs());\n  VERIFY_IS_APPROX(q4.coeffs(), q3.coeffs());\n    \n  VERIFY_IS_APPROX(mq1 * (mq1.inverse() * v1), v1);\n  VERIFY_IS_APPROX(mq1 * (mq1.conjugate() * v1), v1);\n  \n  VERIFY_IS_APPROX(mcq1 * (mcq1.inverse() * v1), v1);\n  VERIFY_IS_APPROX(mcq1 * (mcq1.conjugate() * v1), v1);\n  \n  VERIFY_IS_APPROX(mq3 * (mq3.inverse() * v1), v1);\n  VERIFY_IS_APPROX(mq3 * (mq3.conjugate() * v1), v1);\n  \n  VERIFY_IS_APPROX(mcq3 * (mcq3.inverse() * v1), v1);\n  VERIFY_IS_APPROX(mcq3 * (mcq3.conjugate() * v1), v1);\n  \n  VERIFY_IS_APPROX(mq1*mq2, q1*q2);\n  VERIFY_IS_APPROX(mq3*mq2, q3*q2);\n  VERIFY_IS_APPROX(mcq1*mq2, q1*q2);\n  VERIFY_IS_APPROX(mcq3*mq2, q3*q2);\n\n  // Bug 1461, compilation issue with Map<const Quat>::w(), and other reference/constness checks:\n  VERIFY_IS_APPROX(mcq3.coeffs().x() + mcq3.coeffs().y() + mcq3.coeffs().z() + mcq3.coeffs().w(), mcq3.coeffs().sum());\n  VERIFY_IS_APPROX(mcq3.x() + mcq3.y() + mcq3.z() + mcq3.w(), mcq3.coeffs().sum());\n  mq3.w() = 1;\n  const Quaternionx& cq3(q3);\n  VERIFY( &cq3.x() == &q3.x() );\n  const MQuaternionUA& cmq3(mq3);\n  VERIFY( &cmq3.x() == &mq3.x() );\n  // FIXME the following should be ok. The problem is that currently the LValueBit flag\n  // is used to determine whether we can return a coeff by reference or not, which is not enough for Map<const ...>.\n  //const MCQuaternionUA& cmcq3(mcq3);\n  //VERIFY( &cmcq3.x() == &mcq3.x() );\n\n  // test cast\n  {\n    Quaternion<float> q1f = mq1.template cast<float>();\n    VERIFY_IS_APPROX(q1f.template cast<Scalar>(),mq1);\n    Quaternion<double> q1d = mq1.template cast<double>();\n    VERIFY_IS_APPROX(q1d.template cast<Scalar>(),mq1);\n  }\n}\n\ntemplate<typename Scalar> void quaternionAlignment(void){\n  typedef Quaternion<Scalar,AutoAlign> QuaternionA;\n  typedef Quaternion<Scalar,DontAlign> QuaternionUA;\n\n  EIGEN_ALIGN_MAX Scalar array1[4];\n  EIGEN_ALIGN_MAX Scalar array2[4];\n  EIGEN_ALIGN_MAX Scalar array3[4+1];\n  Scalar* arrayunaligned = array3+1;\n\n  QuaternionA *q1 = ::new(reinterpret_cast<void*>(array1)) QuaternionA;\n  QuaternionUA *q2 = ::new(reinterpret_cast<void*>(array2)) QuaternionUA;\n  QuaternionUA *q3 = ::new(reinterpret_cast<void*>(arrayunaligned)) QuaternionUA;\n\n  q1->coeffs().setRandom();\n  *q2 = *q1;\n  *q3 = *q1;\n\n  VERIFY_IS_APPROX(q1->coeffs(), q2->coeffs());\n  VERIFY_IS_APPROX(q1->coeffs(), q3->coeffs());\n}\n\ntemplate<typename PlainObjectType> void check_const_correctness(const PlainObjectType&)\n{\n  // there's a lot that we can't test here while still having this test compile!\n  // the only possible approach would be to run a script trying to compile stuff and checking that it fails.\n  // CMake can help with that.\n\n  // verify that map-to-const don't have LvalueBit\n  typedef typename internal::add_const<PlainObjectType>::type ConstPlainObjectType;\n  VERIFY( !(internal::traits<Map<ConstPlainObjectType> >::Flags & LvalueBit) );\n  VERIFY( !(internal::traits<Map<ConstPlainObjectType, Aligned> >::Flags & LvalueBit) );\n  VERIFY( !(Map<ConstPlainObjectType>::Flags & LvalueBit) );\n  VERIFY( !(Map<ConstPlainObjectType, Aligned>::Flags & LvalueBit) );\n}\n\n#if EIGEN_HAS_RVALUE_REFERENCES\n\n// Regression for bug 1573\nstruct MovableClass {\n  // The following line is a workaround for gcc 4.7 and 4.8 (see bug 1573 comments).\n  static_assert(std::is_nothrow_move_constructible<Quaternionf>::value,\"\");\n  MovableClass() = default;\n  MovableClass(const MovableClass&) = default;\n  MovableClass(MovableClass&&) noexcept = default;\n  MovableClass& operator=(const MovableClass&) = default;\n  MovableClass& operator=(MovableClass&&) = default;\n  Quaternionf m_quat;\n};\n\n#endif\n\nEIGEN_DECLARE_TEST(geo_quaternion)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(( quaternion<float,AutoAlign>() ));\n    CALL_SUBTEST_1( check_const_correctness(Quaternionf()) );\n    CALL_SUBTEST_1(( quaternion<float,DontAlign>() ));\n    CALL_SUBTEST_1(( quaternionAlignment<float>() ));\n    CALL_SUBTEST_1( mapQuaternion<float>() );\n\n    CALL_SUBTEST_2(( quaternion<double,AutoAlign>() ));\n    CALL_SUBTEST_2( check_const_correctness(Quaterniond()) );\n    CALL_SUBTEST_2(( quaternion<double,DontAlign>() ));\n    CALL_SUBTEST_2(( quaternionAlignment<double>() ));\n    CALL_SUBTEST_2( mapQuaternion<double>() );\n\n#ifndef EIGEN_TEST_ANNOYING_SCALAR_DONT_THROW\n    AnnoyingScalar::dont_throw = true;\n#endif\n    CALL_SUBTEST_3(( quaternion<AnnoyingScalar,AutoAlign>() ));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/geo_transformations.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/Geometry>\n#include <Eigen/LU>\n#include <Eigen/SVD>\n\ntemplate<typename T>\nMatrix<T,2,1> angleToVec(T a)\n{\n  return Matrix<T,2,1>(std::cos(a), std::sin(a));\n}\n\n// This permits to workaround a bug in clang/llvm code generation.\ntemplate<typename T>\nEIGEN_DONT_INLINE\nvoid dont_over_optimize(T& x) { volatile typename T::Scalar tmp = x(0); x(0) = tmp; }\n\ntemplate<typename Scalar, int Mode, int Options> void non_projective_only()\n{\n    /* this test covers the following files:\n     Cross.h Quaternion.h, Transform.cpp\n  */\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef Quaternion<Scalar> Quaternionx;\n  typedef AngleAxis<Scalar> AngleAxisx;\n  typedef Transform<Scalar,3,Mode,Options> Transform3;\n  typedef DiagonalMatrix<Scalar,3> AlignedScaling3;\n  typedef Translation<Scalar,3> Translation3;\n\n  Vector3 v0 = Vector3::Random(),\n          v1 = Vector3::Random();\n\n  Transform3 t0, t1, t2;\n\n  Scalar a = internal::random<Scalar>(-Scalar(EIGEN_PI), Scalar(EIGEN_PI));\n\n  Quaternionx q1, q2;\n\n  q1 = AngleAxisx(a, v0.normalized());\n\n  t0 = Transform3::Identity();\n  VERIFY_IS_APPROX(t0.matrix(), Transform3::MatrixType::Identity());\n\n  t0.linear() = q1.toRotationMatrix();\n\n  v0 << 50, 2, 1;\n  t0.scale(v0);\n\n  VERIFY_IS_APPROX( (t0 * Vector3(1,0,0)).template head<3>().norm(), v0.x());\n\n  t0.setIdentity();\n  t1.setIdentity();\n  v1 << 1, 2, 3;\n  t0.linear() = q1.toRotationMatrix();\n  t0.pretranslate(v0);\n  t0.scale(v1);\n  t1.linear() = q1.conjugate().toRotationMatrix();\n  t1.prescale(v1.cwiseInverse());\n  t1.translate(-v0);\n\n  VERIFY((t0 * t1).matrix().isIdentity(test_precision<Scalar>()));\n\n  t1.fromPositionOrientationScale(v0, q1, v1);\n  VERIFY_IS_APPROX(t1.matrix(), t0.matrix());\n  VERIFY_IS_APPROX(t1*v1, t0*v1);\n\n  // translation * vector\n  t0.setIdentity();\n  t0.translate(v0);\n  VERIFY_IS_APPROX((t0 * v1).template head<3>(), Translation3(v0) * v1);\n\n  // AlignedScaling * vector\n  t0.setIdentity();\n  t0.scale(v0);\n  VERIFY_IS_APPROX((t0 * v1).template head<3>(), AlignedScaling3(v0) * v1);\n}\n\ntemplate<typename Scalar, int Mode, int Options> void transformations()\n{\n  /* this test covers the following files:\n     Cross.h Quaternion.h, Transform.cpp\n  */\n  using std::cos;\n  using std::abs;\n  typedef Matrix<Scalar,3,3> Matrix3;\n  typedef Matrix<Scalar,4,4> Matrix4;\n  typedef Matrix<Scalar,2,1> Vector2;\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef Matrix<Scalar,4,1> Vector4;\n  typedef Quaternion<Scalar> Quaternionx;\n  typedef AngleAxis<Scalar> AngleAxisx;\n  typedef Transform<Scalar,2,Mode,Options> Transform2;\n  typedef Transform<Scalar,3,Mode,Options> Transform3;\n  typedef typename Transform3::MatrixType MatrixType;\n  typedef DiagonalMatrix<Scalar,3> AlignedScaling3;\n  typedef Translation<Scalar,2> Translation2;\n  typedef Translation<Scalar,3> Translation3;\n\n  Vector3 v0 = Vector3::Random(),\n          v1 = Vector3::Random();\n  Matrix3 matrot1, m;\n\n  Scalar a = internal::random<Scalar>(-Scalar(EIGEN_PI), Scalar(EIGEN_PI));\n  Scalar s0 = internal::random<Scalar>(), s1 = internal::random<Scalar>();\n  \n  while(v0.norm() < test_precision<Scalar>()) v0 = Vector3::Random();\n  while(v1.norm() < test_precision<Scalar>()) v1 = Vector3::Random();\n\n  VERIFY_IS_APPROX(v0, AngleAxisx(a, v0.normalized()) * v0);\n  VERIFY_IS_APPROX(-v0, AngleAxisx(Scalar(EIGEN_PI), v0.unitOrthogonal()) * v0);\n  if(abs(cos(a)) > test_precision<Scalar>())\n  {\n    VERIFY_IS_APPROX(cos(a)*v0.squaredNorm(), v0.dot(AngleAxisx(a, v0.unitOrthogonal()) * v0));\n  }\n  m = AngleAxisx(a, v0.normalized()).toRotationMatrix().adjoint();\n  VERIFY_IS_APPROX(Matrix3::Identity(), m * AngleAxisx(a, v0.normalized()));\n  VERIFY_IS_APPROX(Matrix3::Identity(), AngleAxisx(a, v0.normalized()) * m);\n\n  Quaternionx q1, q2;\n  q1 = AngleAxisx(a, v0.normalized());\n  q2 = AngleAxisx(a, v1.normalized());\n\n  // rotation matrix conversion\n  matrot1 = AngleAxisx(Scalar(0.1), Vector3::UnitX())\n          * AngleAxisx(Scalar(0.2), Vector3::UnitY())\n          * AngleAxisx(Scalar(0.3), Vector3::UnitZ());\n  VERIFY_IS_APPROX(matrot1 * v1,\n       AngleAxisx(Scalar(0.1), Vector3(1,0,0)).toRotationMatrix()\n    * (AngleAxisx(Scalar(0.2), Vector3(0,1,0)).toRotationMatrix()\n    * (AngleAxisx(Scalar(0.3), Vector3(0,0,1)).toRotationMatrix() * v1)));\n\n  // angle-axis conversion\n  AngleAxisx aa = AngleAxisx(q1);\n  VERIFY_IS_APPROX(q1 * v1, Quaternionx(aa) * v1);\n  \n  // The following test is stable only if 2*angle != angle and v1 is not colinear with axis\n  if( (abs(aa.angle()) > test_precision<Scalar>()) && (abs(aa.axis().dot(v1.normalized()))<(Scalar(1)-Scalar(4)*test_precision<Scalar>())) )\n  {\n    VERIFY( !(q1 * v1).isApprox(Quaternionx(AngleAxisx(aa.angle()*2,aa.axis())) * v1) );\n  }\n\n  aa.fromRotationMatrix(aa.toRotationMatrix());\n  VERIFY_IS_APPROX(q1 * v1, Quaternionx(aa) * v1);\n  // The following test is stable only if 2*angle != angle and v1 is not colinear with axis\n  if( (abs(aa.angle()) > test_precision<Scalar>()) && (abs(aa.axis().dot(v1.normalized()))<(Scalar(1)-Scalar(4)*test_precision<Scalar>())) )\n  {\n    VERIFY( !(q1 * v1).isApprox(Quaternionx(AngleAxisx(aa.angle()*2,aa.axis())) * v1) );\n  }\n\n  // AngleAxis\n  VERIFY_IS_APPROX(AngleAxisx(a,v1.normalized()).toRotationMatrix(),\n    Quaternionx(AngleAxisx(a,v1.normalized())).toRotationMatrix());\n\n  AngleAxisx aa1;\n  m = q1.toRotationMatrix();\n  aa1 = m;\n  VERIFY_IS_APPROX(AngleAxisx(m).toRotationMatrix(),\n    Quaternionx(m).toRotationMatrix());\n\n  // Transform\n  // TODO complete the tests !\n  a = 0;\n  while (abs(a)<Scalar(0.1))\n    a = internal::random<Scalar>(-Scalar(0.4)*Scalar(EIGEN_PI), Scalar(0.4)*Scalar(EIGEN_PI));\n  q1 = AngleAxisx(a, v0.normalized());\n  Transform3 t0, t1, t2;\n\n  // first test setIdentity() and Identity()\n  t0.setIdentity();\n  VERIFY_IS_APPROX(t0.matrix(), Transform3::MatrixType::Identity());\n  t0.matrix().setZero();\n  t0 = Transform3::Identity();\n  VERIFY_IS_APPROX(t0.matrix(), Transform3::MatrixType::Identity());\n\n  t0.setIdentity();\n  t1.setIdentity();\n  v1 << 1, 2, 3;\n  t0.linear() = q1.toRotationMatrix();\n  t0.pretranslate(v0);\n  t0.scale(v1);\n  t1.linear() = q1.conjugate().toRotationMatrix();\n  t1.prescale(v1.cwiseInverse());\n  t1.translate(-v0);\n\n  VERIFY((t0 * t1).matrix().isIdentity(test_precision<Scalar>()));\n\n  t1.fromPositionOrientationScale(v0, q1, v1);\n  VERIFY_IS_APPROX(t1.matrix(), t0.matrix());\n\n  t0.setIdentity(); t0.scale(v0).rotate(q1.toRotationMatrix());\n  t1.setIdentity(); t1.scale(v0).rotate(q1);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  t0.setIdentity(); t0.scale(v0).rotate(AngleAxisx(q1));\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  VERIFY_IS_APPROX(t0.scale(a).matrix(), t1.scale(Vector3::Constant(a)).matrix());\n  VERIFY_IS_APPROX(t0.prescale(a).matrix(), t1.prescale(Vector3::Constant(a)).matrix());\n\n  // More transform constructors, operator=, operator*=\n\n  Matrix3 mat3 = Matrix3::Random();\n  Matrix4 mat4;\n  mat4 << mat3 , Vector3::Zero() , Vector4::Zero().transpose();\n  Transform3 tmat3(mat3), tmat4(mat4);\n  if(Mode!=int(AffineCompact))\n    tmat4.matrix()(3,3) = Scalar(1);\n  VERIFY_IS_APPROX(tmat3.matrix(), tmat4.matrix());\n\n  Scalar a3 = internal::random<Scalar>(-Scalar(EIGEN_PI), Scalar(EIGEN_PI));\n  Vector3 v3 = Vector3::Random().normalized();\n  AngleAxisx aa3(a3, v3);\n  Transform3 t3(aa3);\n  Transform3 t4;\n  t4 = aa3;\n  VERIFY_IS_APPROX(t3.matrix(), t4.matrix());\n  t4.rotate(AngleAxisx(-a3,v3));\n  VERIFY_IS_APPROX(t4.matrix(), MatrixType::Identity());\n  t4 *= aa3;\n  VERIFY_IS_APPROX(t3.matrix(), t4.matrix());\n\n  do {\n    v3 = Vector3::Random();\n    dont_over_optimize(v3);\n  } while (v3.cwiseAbs().minCoeff()<NumTraits<Scalar>::epsilon());\n  Translation3 tv3(v3);\n  Transform3 t5(tv3);\n  t4 = tv3;\n  VERIFY_IS_APPROX(t5.matrix(), t4.matrix());\n  t4.translate((-v3).eval());\n  VERIFY_IS_APPROX(t4.matrix(), MatrixType::Identity());\n  t4 *= tv3;\n  VERIFY_IS_APPROX(t5.matrix(), t4.matrix());\n\n  AlignedScaling3 sv3(v3);\n  Transform3 t6(sv3);\n  t4 = sv3;\n  VERIFY_IS_APPROX(t6.matrix(), t4.matrix());\n  t4.scale(v3.cwiseInverse());\n  VERIFY_IS_APPROX(t4.matrix(), MatrixType::Identity());\n  t4 *= sv3;\n  VERIFY_IS_APPROX(t6.matrix(), t4.matrix());\n\n  // matrix * transform\n  VERIFY_IS_APPROX((t3.matrix()*t4).matrix(), (t3*t4).matrix());\n\n  // chained Transform product\n  VERIFY_IS_APPROX(((t3*t4)*t5).matrix(), (t3*(t4*t5)).matrix());\n\n  // check that Transform product doesn't have aliasing problems\n  t5 = t4;\n  t5 = t5*t5;\n  VERIFY_IS_APPROX(t5, t4*t4);\n\n  // 2D transformation\n  Transform2 t20, t21;\n  Vector2 v20 = Vector2::Random();\n  Vector2 v21 = Vector2::Random();\n  for (int k=0; k<2; ++k)\n    if (abs(v21[k])<Scalar(1e-3)) v21[k] = Scalar(1e-3);\n  t21.setIdentity();\n  t21.linear() = Rotation2D<Scalar>(a).toRotationMatrix();\n  VERIFY_IS_APPROX(t20.fromPositionOrientationScale(v20,a,v21).matrix(),\n    t21.pretranslate(v20).scale(v21).matrix());\n\n  t21.setIdentity();\n  t21.linear() = Rotation2D<Scalar>(-a).toRotationMatrix();\n  VERIFY( (t20.fromPositionOrientationScale(v20,a,v21)\n        * (t21.prescale(v21.cwiseInverse()).translate(-v20))).matrix().isIdentity(test_precision<Scalar>()) );\n\n  // Transform - new API\n  // 3D\n  t0.setIdentity();\n  t0.rotate(q1).scale(v0).translate(v0);\n  // mat * aligned scaling and mat * translation\n  t1 = (Matrix3(q1) * AlignedScaling3(v0)) * Translation3(v0);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  t1 = (Matrix3(q1) * Eigen::Scaling(v0)) * Translation3(v0);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  t1 = (q1 * Eigen::Scaling(v0)) * Translation3(v0);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  // mat * transformation and aligned scaling * translation\n  t1 = Matrix3(q1) * (AlignedScaling3(v0) * Translation3(v0));\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n\n  t0.setIdentity();\n  t0.scale(s0).translate(v0);\n  t1 = Eigen::Scaling(s0) * Translation3(v0);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  t0.prescale(s0);\n  t1 = Eigen::Scaling(s0) * t1;\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  \n  t0 = t3;\n  t0.scale(s0);\n  t1 = t3 * Eigen::Scaling(s0,s0,s0);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  t0.prescale(s0);\n  t1 = Eigen::Scaling(s0,s0,s0) * t1;\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  t0 = t3;\n  t0.scale(s0);\n  t1 = t3 * Eigen::Scaling(s0);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  t0.prescale(s0);\n  t1 = Eigen::Scaling(s0) * t1;\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  t0.setIdentity();\n  t0.prerotate(q1).prescale(v0).pretranslate(v0);\n  // translation * aligned scaling and transformation * mat\n  t1 = (Translation3(v0) * AlignedScaling3(v0)) * Transform3(q1);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  // scaling * mat and translation * mat\n  t1 = Translation3(v0) * (AlignedScaling3(v0) * Transform3(q1));\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  t0.setIdentity();\n  t0.scale(v0).translate(v0).rotate(q1);\n  // translation * mat and aligned scaling * transformation\n  t1 = AlignedScaling3(v0) * (Translation3(v0) * Transform3(q1));\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  // transformation * aligned scaling\n  t0.scale(v0);\n  t1 *= AlignedScaling3(v0);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  t1 = AlignedScaling3(v0) * (Translation3(v0) * Transform3(q1));\n  t1 = t1 * v0.asDiagonal();\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  // transformation * translation\n  t0.translate(v0);\n  t1 = t1 * Translation3(v0);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  // translation * transformation\n  t0.pretranslate(v0);\n  t1 = Translation3(v0) * t1;\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  // transform * quaternion\n  t0.rotate(q1);\n  t1 = t1 * q1;\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  // translation * quaternion\n  t0.translate(v1).rotate(q1);\n  t1 = t1 * (Translation3(v1) * q1);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  // aligned scaling * quaternion\n  t0.scale(v1).rotate(q1);\n  t1 = t1 * (AlignedScaling3(v1) * q1);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  // quaternion * transform\n  t0.prerotate(q1);\n  t1 = q1 * t1;\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  // quaternion * translation\n  t0.rotate(q1).translate(v1);\n  t1 = t1 * (q1 * Translation3(v1));\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  // quaternion * aligned scaling\n  t0.rotate(q1).scale(v1);\n  t1 = t1 * (q1 * AlignedScaling3(v1));\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  // test transform inversion\n  t0.setIdentity();\n  t0.translate(v0);\n  do {\n    t0.linear().setRandom();\n  } while(t0.linear().jacobiSvd().singularValues()(2)<test_precision<Scalar>());\n  Matrix4 t044 = Matrix4::Zero();\n  t044(3,3) = 1;\n  t044.block(0,0,t0.matrix().rows(),4) = t0.matrix();\n  VERIFY_IS_APPROX(t0.inverse(Affine).matrix(), t044.inverse().block(0,0,t0.matrix().rows(),4));\n  t0.setIdentity();\n  t0.translate(v0).rotate(q1);\n  t044 = Matrix4::Zero();\n  t044(3,3) = 1;\n  t044.block(0,0,t0.matrix().rows(),4) = t0.matrix();\n  VERIFY_IS_APPROX(t0.inverse(Isometry).matrix(), t044.inverse().block(0,0,t0.matrix().rows(),4));\n\n  Matrix3 mat_rotation, mat_scaling;\n  t0.setIdentity();\n  t0.translate(v0).rotate(q1).scale(v1);\n  t0.computeRotationScaling(&mat_rotation, &mat_scaling);\n  VERIFY_IS_APPROX(t0.linear(), mat_rotation * mat_scaling);\n  VERIFY_IS_APPROX(mat_rotation*mat_rotation.adjoint(), Matrix3::Identity());\n  VERIFY_IS_APPROX(mat_rotation.determinant(), Scalar(1));\n  t0.computeScalingRotation(&mat_scaling, &mat_rotation);\n  VERIFY_IS_APPROX(t0.linear(), mat_scaling * mat_rotation);\n  VERIFY_IS_APPROX(mat_rotation*mat_rotation.adjoint(), Matrix3::Identity());\n  VERIFY_IS_APPROX(mat_rotation.determinant(), Scalar(1));\n\n  // test casting\n  Transform<float,3,Mode> t1f = t1.template cast<float>();\n  VERIFY_IS_APPROX(t1f.template cast<Scalar>(),t1);\n  Transform<double,3,Mode> t1d = t1.template cast<double>();\n  VERIFY_IS_APPROX(t1d.template cast<Scalar>(),t1);\n\n  Translation3 tr1(v0);\n  Translation<float,3> tr1f = tr1.template cast<float>();\n  VERIFY_IS_APPROX(tr1f.template cast<Scalar>(),tr1);\n  Translation<double,3> tr1d = tr1.template cast<double>();\n  VERIFY_IS_APPROX(tr1d.template cast<Scalar>(),tr1);\n\n  AngleAxis<float> aa1f = aa1.template cast<float>();\n  VERIFY_IS_APPROX(aa1f.template cast<Scalar>(),aa1);\n  AngleAxis<double> aa1d = aa1.template cast<double>();\n  VERIFY_IS_APPROX(aa1d.template cast<Scalar>(),aa1);\n\n  Rotation2D<Scalar> r2d1(internal::random<Scalar>());\n  Rotation2D<float> r2d1f = r2d1.template cast<float>();\n  VERIFY_IS_APPROX(r2d1f.template cast<Scalar>(),r2d1);\n  Rotation2D<double> r2d1d = r2d1.template cast<double>();\n  VERIFY_IS_APPROX(r2d1d.template cast<Scalar>(),r2d1);\n  \n  for(int k=0; k<100; ++k)\n  {\n    Scalar angle = internal::random<Scalar>(-100,100);\n    Rotation2D<Scalar> rot2(angle);\n    VERIFY( rot2.smallestPositiveAngle() >= 0 );\n    VERIFY( rot2.smallestPositiveAngle() <= Scalar(2)*Scalar(EIGEN_PI) );\n    VERIFY_IS_APPROX( angleToVec(rot2.smallestPositiveAngle()), angleToVec(rot2.angle()) );\n    \n    VERIFY( rot2.smallestAngle() >= -Scalar(EIGEN_PI) );\n    VERIFY( rot2.smallestAngle() <=  Scalar(EIGEN_PI) );\n    VERIFY_IS_APPROX( angleToVec(rot2.smallestAngle()), angleToVec(rot2.angle()) );\n\n    Matrix<Scalar,2,2> rot2_as_mat(rot2);\n    Rotation2D<Scalar> rot3(rot2_as_mat);\n    VERIFY_IS_APPROX( angleToVec(rot2.smallestAngle()),  angleToVec(rot3.angle()) );\n  }\n\n  s0 = internal::random<Scalar>(-100,100);\n  s1 = internal::random<Scalar>(-100,100);\n  Rotation2D<Scalar> R0(s0), R1(s1);\n  \n  t20 = Translation2(v20) * (R0 * Eigen::Scaling(s0));\n  t21 = Translation2(v20) * R0 * Eigen::Scaling(s0);\n  VERIFY_IS_APPROX(t20,t21);\n  \n  t20 = Translation2(v20) * (R0 * R0.inverse() * Eigen::Scaling(s0));\n  t21 = Translation2(v20) * Eigen::Scaling(s0);\n  VERIFY_IS_APPROX(t20,t21);\n  \n  VERIFY_IS_APPROX(s0, (R0.slerp(0, R1)).angle());\n  VERIFY_IS_APPROX( angleToVec(R1.smallestPositiveAngle()), angleToVec((R0.slerp(1, R1)).smallestPositiveAngle()) );\n  VERIFY_IS_APPROX(R0.smallestPositiveAngle(), (R0.slerp(0.5, R0)).smallestPositiveAngle());\n\n  if(std::cos(s0)>0)\n    VERIFY_IS_MUCH_SMALLER_THAN((R0.slerp(0.5, R0.inverse())).smallestAngle(), Scalar(1));\n  else\n    VERIFY_IS_APPROX(Scalar(EIGEN_PI), (R0.slerp(0.5, R0.inverse())).smallestPositiveAngle());\n  \n  // Check path length\n  Scalar l = 0;\n  int path_steps = 100;\n  for(int k=0; k<path_steps; ++k)\n  {\n    Scalar a1 = R0.slerp(Scalar(k)/Scalar(path_steps), R1).angle();\n    Scalar a2 = R0.slerp(Scalar(k+1)/Scalar(path_steps), R1).angle();\n    l += std::abs(a2-a1);\n  }\n  VERIFY(l<=Scalar(EIGEN_PI)*(Scalar(1)+NumTraits<Scalar>::epsilon()*Scalar(path_steps/2)));\n  \n  // check basic features\n  {\n    Rotation2D<Scalar> r1;           // default ctor\n    r1 = Rotation2D<Scalar>(s0);     // copy assignment\n    VERIFY_IS_APPROX(r1.angle(),s0);\n    Rotation2D<Scalar> r2(r1);       // copy ctor\n    VERIFY_IS_APPROX(r2.angle(),s0);\n  }\n\n  {\n    Transform3 t32(Matrix4::Random()), t33, t34;\n    t34 = t33 = t32;\n    t32.scale(v0);\n    t33*=AlignedScaling3(v0);\n    VERIFY_IS_APPROX(t32.matrix(), t33.matrix());\n    t33 = t34 * AlignedScaling3(v0);\n    VERIFY_IS_APPROX(t32.matrix(), t33.matrix());\n  }\n\n}\n\ntemplate<typename A1, typename A2, typename P, typename Q, typename V, typename H>\nvoid transform_associativity_left(const A1& a1, const A2& a2, const P& p, const Q& q, const V& v, const H& h)\n{\n  VERIFY_IS_APPROX( q*(a1*v), (q*a1)*v );\n  VERIFY_IS_APPROX( q*(a2*v), (q*a2)*v );\n  VERIFY_IS_APPROX( q*(p*h).hnormalized(),  ((q*p)*h).hnormalized() );\n}\n\ntemplate<typename A1, typename A2, typename P, typename Q, typename V, typename H>\nvoid transform_associativity2(const A1& a1, const A2& a2, const P& p, const Q& q, const V& v, const H& h)\n{\n  VERIFY_IS_APPROX( a1*(q*v), (a1*q)*v );\n  VERIFY_IS_APPROX( a2*(q*v), (a2*q)*v );\n  VERIFY_IS_APPROX( p *(q*v).homogeneous(), (p *q)*v.homogeneous() );\n\n  transform_associativity_left(a1, a2,p, q, v, h);\n}\n\ntemplate<typename Scalar, int Dim, int Options,typename RotationType>\nvoid transform_associativity(const RotationType& R)\n{\n  typedef Matrix<Scalar,Dim,1> VectorType;\n  typedef Matrix<Scalar,Dim+1,1> HVectorType;\n  typedef Matrix<Scalar,Dim,Dim> LinearType;\n  typedef Matrix<Scalar,Dim+1,Dim+1> MatrixType;\n  typedef Transform<Scalar,Dim,AffineCompact,Options> AffineCompactType;\n  typedef Transform<Scalar,Dim,Affine,Options> AffineType;\n  typedef Transform<Scalar,Dim,Projective,Options> ProjectiveType;\n  typedef DiagonalMatrix<Scalar,Dim> ScalingType;\n  typedef Translation<Scalar,Dim> TranslationType;\n\n  AffineCompactType A1c; A1c.matrix().setRandom();\n  AffineCompactType A2c; A2c.matrix().setRandom();\n  AffineType A1(A1c);\n  AffineType A2(A2c);\n  ProjectiveType P1; P1.matrix().setRandom();\n  VectorType v1 = VectorType::Random();\n  VectorType v2 = VectorType::Random();\n  HVectorType h1 = HVectorType::Random();\n  Scalar s1 = internal::random<Scalar>();\n  LinearType L = LinearType::Random();\n  MatrixType M = MatrixType::Random();\n\n  CALL_SUBTEST( transform_associativity2(A1c, A1, P1, A2, v2, h1) );\n  CALL_SUBTEST( transform_associativity2(A1c, A1, P1, A2c, v2, h1) );\n  CALL_SUBTEST( transform_associativity2(A1c, A1, P1, v1.asDiagonal(), v2, h1) );\n  CALL_SUBTEST( transform_associativity2(A1c, A1, P1, ScalingType(v1), v2, h1) );\n  CALL_SUBTEST( transform_associativity2(A1c, A1, P1, Scaling(v1), v2, h1) );\n  CALL_SUBTEST( transform_associativity2(A1c, A1, P1, Scaling(s1), v2, h1) );\n  CALL_SUBTEST( transform_associativity2(A1c, A1, P1, TranslationType(v1), v2, h1) );\n  CALL_SUBTEST( transform_associativity_left(A1c, A1, P1, L, v2, h1) );\n  CALL_SUBTEST( transform_associativity2(A1c, A1, P1, R, v2, h1) );\n\n  VERIFY_IS_APPROX( A1*(M*h1), (A1*M)*h1 );\n  VERIFY_IS_APPROX( A1c*(M*h1), (A1c*M)*h1 );\n  VERIFY_IS_APPROX( P1*(M*h1), (P1*M)*h1 );\n\n  VERIFY_IS_APPROX( M*(A1*h1), (M*A1)*h1 );\n  VERIFY_IS_APPROX( M*(A1c*h1), (M*A1c)*h1 );\n  VERIFY_IS_APPROX( M*(P1*h1),  ((M*P1)*h1) );\n}\n\ntemplate<typename Scalar> void transform_alignment()\n{\n  typedef Transform<Scalar,3,Projective,AutoAlign> Projective3a;\n  typedef Transform<Scalar,3,Projective,DontAlign> Projective3u;\n\n  EIGEN_ALIGN_MAX Scalar array1[16];\n  EIGEN_ALIGN_MAX Scalar array2[16];\n  EIGEN_ALIGN_MAX Scalar array3[16+1];\n  Scalar* array3u = array3+1;\n\n  Projective3a *p1 = ::new(reinterpret_cast<void*>(array1)) Projective3a;\n  Projective3u *p2 = ::new(reinterpret_cast<void*>(array2)) Projective3u;\n  Projective3u *p3 = ::new(reinterpret_cast<void*>(array3u)) Projective3u;\n  \n  p1->matrix().setRandom();\n  *p2 = *p1;\n  *p3 = *p1;\n\n  VERIFY_IS_APPROX(p1->matrix(), p2->matrix());\n  VERIFY_IS_APPROX(p1->matrix(), p3->matrix());\n  \n  VERIFY_IS_APPROX( (*p1) * (*p1), (*p2)*(*p3));\n}\n\ntemplate<typename Scalar, int Dim, int Options> void transform_products()\n{\n  typedef Matrix<Scalar,Dim+1,Dim+1> Mat;\n  typedef Transform<Scalar,Dim,Projective,Options> Proj;\n  typedef Transform<Scalar,Dim,Affine,Options> Aff;\n  typedef Transform<Scalar,Dim,AffineCompact,Options> AffC;\n\n  Proj p; p.matrix().setRandom();\n  Aff a; a.linear().setRandom(); a.translation().setRandom();\n  AffC ac = a;\n\n  Mat p_m(p.matrix()), a_m(a.matrix());\n\n  VERIFY_IS_APPROX((p*p).matrix(), p_m*p_m);\n  VERIFY_IS_APPROX((a*a).matrix(), a_m*a_m);\n  VERIFY_IS_APPROX((p*a).matrix(), p_m*a_m);\n  VERIFY_IS_APPROX((a*p).matrix(), a_m*p_m);\n  VERIFY_IS_APPROX((ac*a).matrix(), a_m*a_m);\n  VERIFY_IS_APPROX((a*ac).matrix(), a_m*a_m);\n  VERIFY_IS_APPROX((p*ac).matrix(), p_m*a_m);\n  VERIFY_IS_APPROX((ac*p).matrix(), a_m*p_m);\n}\n\ntemplate<typename Scalar, int Mode, int Options> void transformations_no_scale()\n{\n     /* this test covers the following files:\n     Cross.h Quaternion.h, Transform.h\n  */\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef Matrix<Scalar,4,1> Vector4;\n  typedef Quaternion<Scalar> Quaternionx;\n  typedef AngleAxis<Scalar> AngleAxisx;\n  typedef Transform<Scalar,3,Mode,Options> Transform3;\n  typedef Translation<Scalar,3> Translation3;\n  typedef Matrix<Scalar,4,4> Matrix4;\n\n  Vector3 v0 = Vector3::Random(),\n          v1 = Vector3::Random();\n\n  Transform3 t0, t1, t2;\n\n  Scalar a = internal::random<Scalar>(-Scalar(EIGEN_PI), Scalar(EIGEN_PI));\n\n  Quaternionx q1, q2;\n\n  q1 = AngleAxisx(a, v0.normalized());\n\n  t0 = Transform3::Identity();\n  VERIFY_IS_APPROX(t0.matrix(), Transform3::MatrixType::Identity());\n\n  t0.setIdentity();\n  t1.setIdentity();\n  v1 = Vector3::Ones();\n  t0.linear() = q1.toRotationMatrix();\n  t0.pretranslate(v0);\n  t1.linear() = q1.conjugate().toRotationMatrix();\n  t1.translate(-v0);\n\n  VERIFY((t0 * t1).matrix().isIdentity(test_precision<Scalar>()));\n\n  t1.fromPositionOrientationScale(v0, q1, v1);\n  VERIFY_IS_APPROX(t1.matrix(), t0.matrix());\n  VERIFY_IS_APPROX(t1*v1, t0*v1);\n\n  // translation * vector\n  t0.setIdentity();\n  t0.translate(v0);\n  VERIFY_IS_APPROX((t0 * v1).template head<3>(), Translation3(v0) * v1);\n\n  // Conversion to matrix.\n  Transform3 t3;\n  t3.linear() = q1.toRotationMatrix();\n  t3.translation() = v1;\n  Matrix4 m3 = t3.matrix();\n  VERIFY((m3 * m3.inverse()).isIdentity(test_precision<Scalar>()));\n  // Verify implicit last row is initialized.\n  VERIFY_IS_APPROX(Vector4(m3.row(3)), Vector4(0.0, 0.0, 0.0, 1.0));\n\n  VERIFY_IS_APPROX(t3.rotation(), t3.linear());\n  if(Mode==Isometry)\n    VERIFY(t3.rotation().data()==t3.linear().data());\n}\n\ntemplate<typename Scalar, int Mode, int Options> void transformations_computed_scaling_continuity()\n{\n  typedef Matrix<Scalar, 3, 1> Vector3;\n  typedef Transform<Scalar, 3, Mode, Options> Transform3;\n  typedef Matrix<Scalar, 3, 3> Matrix3;\n\n  // Given: two transforms that differ by '2*eps'.\n  Scalar eps(1e-3);\n  Vector3 v0 = Vector3::Random().normalized(),\n    v1 = Vector3::Random().normalized(),\n    v3 = Vector3::Random().normalized();\n  Transform3 t0, t1;\n  // The interesting case is when their determinants have different signs.\n  Matrix3 rank2 = 50 * v0 * v0.adjoint() + 20 * v1 * v1.adjoint();\n  t0.linear() = rank2 + eps * v3 * v3.adjoint();\n  t1.linear() = rank2 - eps * v3 * v3.adjoint();\n\n  // When: computing the rotation-scaling parts\n  Matrix3 r0, s0, r1, s1;\n  t0.computeRotationScaling(&r0, &s0);\n  t1.computeRotationScaling(&r1, &s1);\n\n  // Then: the scaling parts should differ by no more than '2*eps'.\n  const Scalar c(2.1); // 2 + room for rounding errors\n  VERIFY((s0 - s1).norm() < c * eps);\n}\n\nEIGEN_DECLARE_TEST(geo_transformations)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(( transformations<double,Affine,AutoAlign>() ));\n    CALL_SUBTEST_1(( non_projective_only<double,Affine,AutoAlign>() ));\n    CALL_SUBTEST_1(( transformations_computed_scaling_continuity<double,Affine,AutoAlign>() ));   \n    \n    CALL_SUBTEST_2(( transformations<float,AffineCompact,AutoAlign>() ));\n    CALL_SUBTEST_2(( non_projective_only<float,AffineCompact,AutoAlign>() ));\n    CALL_SUBTEST_2(( transform_alignment<float>() ));\n    \n    CALL_SUBTEST_3(( transformations<double,Projective,AutoAlign>() ));\n    CALL_SUBTEST_3(( transformations<double,Projective,DontAlign>() ));\n    CALL_SUBTEST_3(( transform_alignment<double>() ));\n\n    CALL_SUBTEST_4(( transformations<float,Affine,RowMajor|AutoAlign>() ));\n    CALL_SUBTEST_4(( non_projective_only<float,Affine,RowMajor>() ));\n    \n    CALL_SUBTEST_5(( transformations<double,AffineCompact,RowMajor|AutoAlign>() ));\n    CALL_SUBTEST_5(( non_projective_only<double,AffineCompact,RowMajor>() ));\n\n    CALL_SUBTEST_6(( transformations<double,Projective,RowMajor|AutoAlign>() ));\n    CALL_SUBTEST_6(( transformations<double,Projective,RowMajor|DontAlign>() ));\n\n\n    CALL_SUBTEST_7(( transform_products<double,3,RowMajor|AutoAlign>() ));\n    CALL_SUBTEST_7(( transform_products<float,2,AutoAlign>() ));\n\n    CALL_SUBTEST_8(( transform_associativity<double,2,ColMajor>(Rotation2D<double>(internal::random<double>()*double(EIGEN_PI))) ));\n    CALL_SUBTEST_8(( transform_associativity<double,3,ColMajor>(Quaterniond::UnitRandom()) ));\n\n    CALL_SUBTEST_9(( transformations_no_scale<double,Affine,AutoAlign>() ));\n    CALL_SUBTEST_9(( transformations_no_scale<double,Isometry,AutoAlign>() ));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/gpu_basic.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015-2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// workaround issue between gcc >= 4.7 and cuda 5.5\n#if (defined __GNUC__) && (__GNUC__>4 || __GNUC_MINOR__>=7)\n  #undef _GLIBCXX_ATOMIC_BUILTINS\n  #undef _GLIBCXX_USE_INT128\n#endif\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int\n\n#include \"main.h\"\n#include \"gpu_common.h\"\n\n// Check that dense modules can be properly parsed by nvcc\n#include <Eigen/Dense>\n\n// struct Foo{\n//   EIGEN_DEVICE_FUNC\n//   void operator()(int i, const float* mats, float* vecs) const {\n//     using namespace Eigen;\n//   //   Matrix3f M(data);\n//   //   Vector3f x(data+9);\n//   //   Map<Vector3f>(data+9) = M.inverse() * x;\n//     Matrix3f M(mats+i/16);\n//     Vector3f x(vecs+i*3);\n//   //   using std::min;\n//   //   using std::sqrt;\n//     Map<Vector3f>(vecs+i*3) << x.minCoeff(), 1, 2;// / x.dot(x);//(M.inverse() *  x) / x.x();\n//     //x = x*2 + x.y() * x + x * x.maxCoeff() - x / x.sum();\n//   }\n// };\n\ntemplate<typename T>\nstruct coeff_wise {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const\n  {\n    using namespace Eigen;\n    T x1(in+i);\n    T x2(in+i+1);\n    T x3(in+i+2);\n    Map<T> res(out+i*T::MaxSizeAtCompileTime);\n    \n    res.array() += (in[0] * x1 + x2).array() * x3.array();\n  }\n};\n\ntemplate<typename T>\nstruct complex_sqrt {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const\n  {\n    using namespace Eigen;\n    typedef typename T::Scalar ComplexType;\n    typedef typename T::Scalar::value_type ValueType;\n    const int num_special_inputs = 18;\n    \n    if (i == 0) {\n      const ValueType nan = std::numeric_limits<ValueType>::quiet_NaN();\n      typedef Eigen::Vector<ComplexType, num_special_inputs> SpecialInputs;\n      SpecialInputs special_in;\n      special_in.setZero();\n      int idx = 0;\n      special_in[idx++] = ComplexType(0, 0);\n      special_in[idx++] = ComplexType(-0, 0);\n      special_in[idx++] = ComplexType(0, -0);\n      special_in[idx++] = ComplexType(-0, -0);\n      // GCC's fallback sqrt implementation fails for inf inputs.\n      // It is called when _GLIBCXX_USE_C99_COMPLEX is false or if\n      // clang includes the GCC header (which temporarily disables\n      // _GLIBCXX_USE_C99_COMPLEX)\n      #if !defined(_GLIBCXX_COMPLEX) || \\\n        (_GLIBCXX_USE_C99_COMPLEX && !defined(__CLANG_CUDA_WRAPPERS_COMPLEX))\n      const ValueType inf = std::numeric_limits<ValueType>::infinity();\n      special_in[idx++] = ComplexType(1.0, inf);\n      special_in[idx++] = ComplexType(nan, inf);\n      special_in[idx++] = ComplexType(1.0, -inf);\n      special_in[idx++] = ComplexType(nan, -inf);\n      special_in[idx++] = ComplexType(-inf, 1.0);\n      special_in[idx++] = ComplexType(inf, 1.0);\n      special_in[idx++] = ComplexType(-inf, -1.0);\n      special_in[idx++] = ComplexType(inf, -1.0);\n      special_in[idx++] = ComplexType(-inf, nan);\n      special_in[idx++] = ComplexType(inf, nan);\n      #endif\n      special_in[idx++] = ComplexType(1.0, nan);\n      special_in[idx++] = ComplexType(nan, 1.0);\n      special_in[idx++] = ComplexType(nan, -1.0);\n      special_in[idx++] = ComplexType(nan, nan);\n      \n      Map<SpecialInputs> special_out(out);\n      special_out = special_in.cwiseSqrt();\n    }\n    \n    T x1(in + i);\n    Map<T> res(out + num_special_inputs + i*T::MaxSizeAtCompileTime);\n    res = x1.cwiseSqrt();\n  }\n};\n\ntemplate<typename T>\nstruct complex_operators {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const\n  {\n    using namespace Eigen;\n    typedef typename T::Scalar ComplexType;\n    typedef typename T::Scalar::value_type ValueType;\n    const int num_scalar_operators = 24;\n    const int num_vector_operators = 23;  // no unary + operator.\n    int out_idx = i * (num_scalar_operators + num_vector_operators * T::MaxSizeAtCompileTime);\n    \n    // Scalar operators.\n    const ComplexType a = in[i];\n    const ComplexType b = in[i + 1];\n    \n    out[out_idx++] = +a;\n    out[out_idx++] = -a;\n    \n    out[out_idx++] = a + b;\n    out[out_idx++] = a + numext::real(b);\n    out[out_idx++] = numext::real(a) + b;\n    out[out_idx++] = a - b;\n    out[out_idx++] = a - numext::real(b);\n    out[out_idx++] = numext::real(a) - b;\n    out[out_idx++] = a * b;\n    out[out_idx++] = a * numext::real(b);\n    out[out_idx++] = numext::real(a) * b;\n    out[out_idx++] = a / b;\n    out[out_idx++] = a / numext::real(b);\n    out[out_idx++] = numext::real(a) / b;\n    \n    out[out_idx] = a; out[out_idx++] += b;\n    out[out_idx] = a; out[out_idx++] -= b;\n    out[out_idx] = a; out[out_idx++] *= b;\n    out[out_idx] = a; out[out_idx++] /= b;\n    \n    const ComplexType true_value = ComplexType(ValueType(1), ValueType(0));\n    const ComplexType false_value = ComplexType(ValueType(0), ValueType(0));\n    out[out_idx++] = (a == b ? true_value : false_value);\n    out[out_idx++] = (a == numext::real(b) ? true_value : false_value);\n    out[out_idx++] = (numext::real(a) == b ? true_value : false_value);\n    out[out_idx++] = (a != b ? true_value : false_value);\n    out[out_idx++] = (a != numext::real(b) ? true_value : false_value);\n    out[out_idx++] = (numext::real(a) != b ? true_value : false_value);\n    \n    // Vector versions.\n    T x1(in + i);\n    T x2(in + i + 1);\n    const int res_size = T::MaxSizeAtCompileTime * num_scalar_operators;\n    const int size = T::MaxSizeAtCompileTime;\n    int block_idx = 0;\n    \n    Map<VectorX<ComplexType>> res(out + out_idx, res_size);\n    res.segment(block_idx, size) = -x1;\n    block_idx += size;\n    \n    res.segment(block_idx, size) = x1 + x2;\n    block_idx += size;\n    res.segment(block_idx, size) = x1 + x2.real();\n    block_idx += size;\n    res.segment(block_idx, size) = x1.real() + x2;\n    block_idx += size;\n    res.segment(block_idx, size) = x1 - x2;\n    block_idx += size;\n    res.segment(block_idx, size) = x1 - x2.real();\n    block_idx += size;\n    res.segment(block_idx, size) = x1.real() - x2;\n    block_idx += size;\n    res.segment(block_idx, size) = x1.array() * x2.array();\n    block_idx += size;\n    res.segment(block_idx, size) = x1.array() * x2.real().array();\n    block_idx += size;\n    res.segment(block_idx, size) = x1.real().array() * x2.array();\n    block_idx += size;\n    res.segment(block_idx, size) = x1.array() / x2.array();\n    block_idx += size;\n    res.segment(block_idx, size) = x1.array() / x2.real().array();\n    block_idx += size;\n    res.segment(block_idx, size) = x1.real().array() / x2.array();\n    block_idx += size;\n    \n    res.segment(block_idx, size) = x1; res.segment(block_idx, size) += x2;\n    block_idx += size;\n    res.segment(block_idx, size) = x1; res.segment(block_idx, size) -= x2;\n    block_idx += size;\n    res.segment(block_idx, size) = x1; res.segment(block_idx, size).array() *= x2.array();\n    block_idx += size;\n    res.segment(block_idx, size) = x1; res.segment(block_idx, size).array() /= x2.array();\n    block_idx += size;\n\n    const T true_vector = T::Constant(true_value);\n    const T false_vector = T::Constant(false_value);\n    res.segment(block_idx, size) = (x1 == x2 ? true_vector : false_vector);\n    block_idx += size;\n    // Mixing types in equality comparison does not work.\n    // res.segment(block_idx, size) = (x1 == x2.real() ? true_vector : false_vector);\n    // block_idx += size;\n    // res.segment(block_idx, size) = (x1.real() == x2 ? true_vector : false_vector);\n    // block_idx += size;\n    res.segment(block_idx, size) = (x1 != x2 ? true_vector : false_vector);\n    block_idx += size;\n    // res.segment(block_idx, size) = (x1 != x2.real() ? true_vector : false_vector);\n    // block_idx += size;\n    // res.segment(block_idx, size) = (x1.real() != x2 ? true_vector : false_vector);\n    // block_idx += size;\n  }\n};\n\ntemplate<typename T>\nstruct replicate {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const\n  {\n    using namespace Eigen;\n    T x1(in+i);\n    int step   = x1.size() * 4;\n    int stride = 3 * step;\n    \n    typedef Map<Array<typename T::Scalar,Dynamic,Dynamic> > MapType;\n    MapType(out+i*stride+0*step, x1.rows()*2, x1.cols()*2) = x1.replicate(2,2);\n    MapType(out+i*stride+1*step, x1.rows()*3, x1.cols()) = in[i] * x1.colwise().replicate(3);\n    MapType(out+i*stride+2*step, x1.rows(), x1.cols()*3) = in[i] * x1.rowwise().replicate(3);\n  }\n};\n\ntemplate<typename T>\nstruct alloc_new_delete {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const\n  {\n    int offset = 2*i*T::MaxSizeAtCompileTime;\n    T* x = new T(in + offset);\n    Eigen::Map<T> u(out + offset);\n    u = *x;\n    delete x;\n    \n    offset += T::MaxSizeAtCompileTime;\n    T* y = new T[1];\n    y[0] = T(in + offset);\n    Eigen::Map<T> v(out + offset);\n    v = y[0];    \n    delete[] y;\n  }\n};\n\ntemplate<typename T>\nstruct redux {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const\n  {\n    using namespace Eigen;\n    int N = 10;\n    T x1(in+i);\n    out[i*N+0] = x1.minCoeff();\n    out[i*N+1] = x1.maxCoeff();\n    out[i*N+2] = x1.sum();\n    out[i*N+3] = x1.prod();\n    out[i*N+4] = x1.matrix().squaredNorm();\n    out[i*N+5] = x1.matrix().norm();\n    out[i*N+6] = x1.colwise().sum().maxCoeff();\n    out[i*N+7] = x1.rowwise().maxCoeff().sum();\n    out[i*N+8] = x1.matrix().colwise().squaredNorm().sum();\n  }\n};\n\ntemplate<typename T1, typename T2>\nstruct prod_test {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T1::Scalar* in, typename T1::Scalar* out) const\n  {\n    using namespace Eigen;\n    typedef Matrix<typename T1::Scalar, T1::RowsAtCompileTime, T2::ColsAtCompileTime> T3;\n    T1 x1(in+i);\n    T2 x2(in+i+1);\n    Map<T3> res(out+i*T3::MaxSizeAtCompileTime);\n    res += in[i] * x1 * x2;\n  }\n};\n\ntemplate<typename T1, typename T2>\nstruct diagonal {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T1::Scalar* in, typename T1::Scalar* out) const\n  {\n    using namespace Eigen;\n    T1 x1(in+i);\n    Map<T2> res(out+i*T2::MaxSizeAtCompileTime);\n    res += x1.diagonal();\n  }\n};\n\ntemplate<typename T>\nstruct eigenvalues_direct {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const\n  {\n    using namespace Eigen;\n    typedef Matrix<typename T::Scalar, T::RowsAtCompileTime, 1> Vec;\n    T M(in+i);\n    Map<Vec> res(out+i*Vec::MaxSizeAtCompileTime);\n    T A = M*M.adjoint();\n    SelfAdjointEigenSolver<T> eig;\n    eig.computeDirect(A);\n    res = eig.eigenvalues();\n  }\n};\n\ntemplate<typename T>\nstruct eigenvalues {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const\n  {\n    using namespace Eigen;\n    typedef Matrix<typename T::Scalar, T::RowsAtCompileTime, 1> Vec;\n    T M(in+i);\n    Map<Vec> res(out+i*Vec::MaxSizeAtCompileTime);\n    T A = M*M.adjoint();\n    SelfAdjointEigenSolver<T> eig;\n    eig.compute(A);\n    res = eig.eigenvalues();\n  }\n};\n\ntemplate<typename T>\nstruct matrix_inverse {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const\n  {\n    using namespace Eigen;\n    T M(in+i);\n    Map<T> res(out+i*T::MaxSizeAtCompileTime);\n    res = M.inverse();\n  }\n};\n\ntemplate<typename T>\nstruct numeric_limits_test {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const\n  {\n    EIGEN_UNUSED_VARIABLE(in)\n    int out_idx = i * 5;\n    out[out_idx++] = numext::numeric_limits<float>::epsilon();\n    out[out_idx++] = (numext::numeric_limits<float>::max)();\n    out[out_idx++] = (numext::numeric_limits<float>::min)();\n    out[out_idx++] = numext::numeric_limits<float>::infinity();\n    out[out_idx++] = numext::numeric_limits<float>::quiet_NaN();\n  }\n};\n\ntemplate<typename Type1, typename Type2>\nbool verifyIsApproxWithInfsNans(const Type1& a, const Type2& b, typename Type1::Scalar* = 0) // Enabled for Eigen's type only\n{\n  if (a.rows() != b.rows()) {\n    return false;\n  }\n  if (a.cols() != b.cols()) {\n    return false;\n  }\n  for (Index r = 0; r < a.rows(); ++r) {\n    for (Index c = 0; c < a.cols(); ++c) {\n      if (a(r, c) != b(r, c)\n          && !((numext::isnan)(a(r, c)) && (numext::isnan)(b(r, c))) \n          && !test_isApprox(a(r, c), b(r, c))) {\n        return false;\n      }\n    }\n  }\n  return true;\n}\n\ntemplate<typename Kernel, typename Input, typename Output>\nvoid test_with_infs_nans(const Kernel& ker, int n, const Input& in, Output& out)\n{\n  Output out_ref, out_gpu;\n  #if !defined(EIGEN_GPU_COMPILE_PHASE)\n  out_ref = out_gpu = out;\n  #else\n  EIGEN_UNUSED_VARIABLE(in);\n  EIGEN_UNUSED_VARIABLE(out);\n  #endif\n  run_on_cpu (ker, n, in,  out_ref);\n  run_on_gpu(ker, n, in, out_gpu);\n  #if !defined(EIGEN_GPU_COMPILE_PHASE)\n  verifyIsApproxWithInfsNans(out_ref, out_gpu);\n  #endif\n}\n\nEIGEN_DECLARE_TEST(gpu_basic)\n{\n  ei_test_init_gpu();\n  \n  int nthreads = 100;\n  Eigen::VectorXf in, out;\n  Eigen::VectorXcf cfin, cfout;\n  \n  #if !defined(EIGEN_GPU_COMPILE_PHASE)\n  int data_size = nthreads * 512;\n  in.setRandom(data_size);\n  out.setConstant(data_size, -1);\n  cfin.setRandom(data_size);\n  cfout.setConstant(data_size, -1);\n  #endif\n  \n  CALL_SUBTEST( run_and_compare_to_gpu(coeff_wise<Vector3f>(), nthreads, in, out) );\n  CALL_SUBTEST( run_and_compare_to_gpu(coeff_wise<Array44f>(), nthreads, in, out) );\n\n#if !defined(EIGEN_USE_HIP)\n  // FIXME\n  // These subtests result in a compile failure on the HIP platform\n  //\n  //  eigen-upstream/Eigen/src/Core/Replicate.h:61:65: error:\n  //           base class 'internal::dense_xpr_base<Replicate<Array<float, 4, 1, 0, 4, 1>, -1, -1> >::type'\n  //           (aka 'ArrayBase<Eigen::Replicate<Eigen::Array<float, 4, 1, 0, 4, 1>, -1, -1> >') has protected default constructor\n  CALL_SUBTEST( run_and_compare_to_gpu(replicate<Array4f>(), nthreads, in, out) );\n  CALL_SUBTEST( run_and_compare_to_gpu(replicate<Array33f>(), nthreads, in, out) );\n\n  // HIP does not support new/delete on device.\n  CALL_SUBTEST( run_and_compare_to_gpu(alloc_new_delete<Vector3f>(), nthreads, in, out) );\n#endif\n  \n  CALL_SUBTEST( run_and_compare_to_gpu(redux<Array4f>(), nthreads, in, out) );\n  CALL_SUBTEST( run_and_compare_to_gpu(redux<Matrix3f>(), nthreads, in, out) );\n  \n  CALL_SUBTEST( run_and_compare_to_gpu(prod_test<Matrix3f,Matrix3f>(), nthreads, in, out) );\n  CALL_SUBTEST( run_and_compare_to_gpu(prod_test<Matrix4f,Vector4f>(), nthreads, in, out) );\n  \n  CALL_SUBTEST( run_and_compare_to_gpu(diagonal<Matrix3f,Vector3f>(), nthreads, in, out) );\n  CALL_SUBTEST( run_and_compare_to_gpu(diagonal<Matrix4f,Vector4f>(), nthreads, in, out) );\n\n  CALL_SUBTEST( run_and_compare_to_gpu(matrix_inverse<Matrix2f>(), nthreads, in, out) );\n  CALL_SUBTEST( run_and_compare_to_gpu(matrix_inverse<Matrix3f>(), nthreads, in, out) );\n  CALL_SUBTEST( run_and_compare_to_gpu(matrix_inverse<Matrix4f>(), nthreads, in, out) );\n  \n  CALL_SUBTEST( run_and_compare_to_gpu(eigenvalues_direct<Matrix3f>(), nthreads, in, out) );\n  CALL_SUBTEST( run_and_compare_to_gpu(eigenvalues_direct<Matrix2f>(), nthreads, in, out) );\n\n  // Test std::complex.\n  CALL_SUBTEST( run_and_compare_to_gpu(complex_operators<Vector3cf>(), nthreads, cfin, cfout) );\n  CALL_SUBTEST( test_with_infs_nans(complex_sqrt<Vector3cf>(), nthreads, cfin, cfout) );\n\n  // numeric_limits\n  CALL_SUBTEST( test_with_infs_nans(numeric_limits_test<Vector3f>(), 1, in, out) );\n\n#if defined(__NVCC__)\n  // FIXME\n  // These subtests compiles only with nvcc and fail with HIPCC and clang-cuda\n  CALL_SUBTEST( run_and_compare_to_gpu(eigenvalues<Matrix4f>(), nthreads, in, out) );\n  typedef Matrix<float,6,6> Matrix6f;\n  CALL_SUBTEST( run_and_compare_to_gpu(eigenvalues<Matrix6f>(), nthreads, in, out) );\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/gpu_common.h",
    "content": "#ifndef EIGEN_TEST_GPU_COMMON_H\n#define EIGEN_TEST_GPU_COMMON_H\n\n#ifdef EIGEN_USE_HIP\n  #include <hip/hip_runtime.h>\n  #include <hip/hip_runtime_api.h>\n#else\n  #include <cuda.h>\n  #include <cuda_runtime.h>\n  #include <cuda_runtime_api.h>\n#endif\n\n#include <iostream>\n\n#define EIGEN_USE_GPU\n#include <unsupported/Eigen/CXX11/src/Tensor/TensorGpuHipCudaDefines.h>\n\n#if !defined(__CUDACC__) && !defined(__HIPCC__)\ndim3 threadIdx, blockDim, blockIdx;\n#endif\n\ntemplate<typename Kernel, typename Input, typename Output>\nvoid run_on_cpu(const Kernel& ker, int n, const Input& in, Output& out)\n{\n  for(int i=0; i<n; i++)\n    ker(i, in.data(), out.data());\n}\n\n\ntemplate<typename Kernel, typename Input, typename Output>\n__global__\nEIGEN_HIP_LAUNCH_BOUNDS_1024\nvoid run_on_gpu_meta_kernel(const Kernel ker, int n, const Input* in, Output* out)\n{\n  int i = threadIdx.x + blockIdx.x*blockDim.x;\n  if(i<n) {\n    ker(i, in, out);\n  }\n}\n\n\ntemplate<typename Kernel, typename Input, typename Output>\nvoid run_on_gpu(const Kernel& ker, int n, const Input& in, Output& out)\n{\n  typename Input::Scalar*  d_in;\n  typename Output::Scalar* d_out;\n  std::ptrdiff_t in_bytes  = in.size()  * sizeof(typename Input::Scalar);\n  std::ptrdiff_t out_bytes = out.size() * sizeof(typename Output::Scalar);\n  \n  gpuMalloc((void**)(&d_in),  in_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n  \n  gpuMemcpy(d_in,  in.data(),  in_bytes,  gpuMemcpyHostToDevice);\n  gpuMemcpy(d_out, out.data(), out_bytes, gpuMemcpyHostToDevice);\n  \n  // Simple and non-optimal 1D mapping assuming n is not too large\n  // That's only for unit testing!\n  dim3 Blocks(128);\n  dim3 Grids( (n+int(Blocks.x)-1)/int(Blocks.x) );\n\n  gpuDeviceSynchronize();\n  \n#ifdef EIGEN_USE_HIP\n  hipLaunchKernelGGL(HIP_KERNEL_NAME(run_on_gpu_meta_kernel<Kernel,\n\t\t\t\t     typename std::decay<decltype(*d_in)>::type,\n\t\t\t\t     typename std::decay<decltype(*d_out)>::type>), \n\t\t     dim3(Grids), dim3(Blocks), 0, 0, ker, n, d_in, d_out);\n#else\n  run_on_gpu_meta_kernel<<<Grids,Blocks>>>(ker, n, d_in, d_out);\n#endif\n  // Pre-launch errors.\n  gpuError_t err = gpuGetLastError();\n  if (err != gpuSuccess) {\n    printf(\"%s: %s\\n\", gpuGetErrorName(err), gpuGetErrorString(err));\n    gpu_assert(false);\n  }\n  \n  // Kernel execution errors.\n  err = gpuDeviceSynchronize();\n  if (err != gpuSuccess) {\n    printf(\"%s: %s\\n\", gpuGetErrorName(err), gpuGetErrorString(err));\n    gpu_assert(false);\n  }\n  \n  \n  // check inputs have not been modified\n  gpuMemcpy(const_cast<typename Input::Scalar*>(in.data()),  d_in,  in_bytes,  gpuMemcpyDeviceToHost);\n  gpuMemcpy(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost);\n  \n  gpuFree(d_in);\n  gpuFree(d_out);\n}\n\n\ntemplate<typename Kernel, typename Input, typename Output>\nvoid run_and_compare_to_gpu(const Kernel& ker, int n, const Input& in, Output& out)\n{\n  Input  in_ref,  in_gpu;\n  Output out_ref, out_gpu;\n  #if !defined(EIGEN_GPU_COMPILE_PHASE)\n  in_ref = in_gpu = in;\n  out_ref = out_gpu = out;\n  #else\n  EIGEN_UNUSED_VARIABLE(in);\n  EIGEN_UNUSED_VARIABLE(out);\n  #endif\n  run_on_cpu (ker, n, in_ref,  out_ref);\n  run_on_gpu(ker, n, in_gpu, out_gpu);\n  #if !defined(EIGEN_GPU_COMPILE_PHASE)\n  VERIFY_IS_APPROX(in_ref, in_gpu);\n  VERIFY_IS_APPROX(out_ref, out_gpu);\n  #endif\n}\n\nstruct compile_time_device_info {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const int* /*in*/, int* info) const\n  {\n    if (i == 0) {\n      EIGEN_UNUSED_VARIABLE(info)\n      #if defined(__CUDA_ARCH__)\n      info[0] = int(__CUDA_ARCH__ +0);\n      #endif\n      #if defined(EIGEN_HIP_DEVICE_COMPILE)\n      info[1] = int(EIGEN_HIP_DEVICE_COMPILE +0);\n      #endif\n    }\n  }\n};\n\nvoid ei_test_init_gpu()\n{\n  int device = 0;\n  gpuDeviceProp_t deviceProp;\n  gpuGetDeviceProperties(&deviceProp, device);\n\n  ArrayXi dummy(1), info(10);\n  info = -1;\n  run_on_gpu(compile_time_device_info(),10,dummy,info);\n\n\n  std::cout << \"GPU compile-time info:\\n\";\n  \n  #ifdef EIGEN_CUDACC\n  std::cout << \"  EIGEN_CUDACC:                 \" << int(EIGEN_CUDACC) << \"\\n\";\n  #endif\n  \n  #ifdef EIGEN_CUDA_SDK_VER\n  std::cout << \"  EIGEN_CUDA_SDK_VER:             \" << int(EIGEN_CUDA_SDK_VER) << \"\\n\";\n  #endif\n\n  #ifdef EIGEN_COMP_NVCC\n  std::cout << \"  EIGEN_COMP_NVCC:             \" << int(EIGEN_COMP_NVCC) << \"\\n\";\n  #endif\n  \n  #ifdef EIGEN_HIPCC\n  std::cout << \"  EIGEN_HIPCC:                 \" << int(EIGEN_HIPCC) << \"\\n\";\n  #endif\n\n  std::cout << \"  EIGEN_CUDA_ARCH:             \" << info[0] << \"\\n\";  \n  std::cout << \"  EIGEN_HIP_DEVICE_COMPILE:    \" << info[1] << \"\\n\";\n\n  std::cout << \"GPU device info:\\n\";\n  std::cout << \"  name:                        \" << deviceProp.name << \"\\n\";\n  std::cout << \"  capability:                  \" << deviceProp.major << \".\" << deviceProp.minor << \"\\n\";\n  std::cout << \"  multiProcessorCount:         \" << deviceProp.multiProcessorCount << \"\\n\";\n  std::cout << \"  maxThreadsPerMultiProcessor: \" << deviceProp.maxThreadsPerMultiProcessor << \"\\n\";\n  std::cout << \"  warpSize:                    \" << deviceProp.warpSize << \"\\n\";\n  std::cout << \"  regsPerBlock:                \" << deviceProp.regsPerBlock << \"\\n\";\n  std::cout << \"  concurrentKernels:           \" << deviceProp.concurrentKernels << \"\\n\";\n  std::cout << \"  clockRate:                   \" << deviceProp.clockRate << \"\\n\";\n  std::cout << \"  canMapHostMemory:            \" << deviceProp.canMapHostMemory << \"\\n\";\n  std::cout << \"  computeMode:                 \" << deviceProp.computeMode << \"\\n\";\n}\n\n#endif // EIGEN_TEST_GPU_COMMON_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/half_float.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <sstream>\n\n#include \"main.h\"\n\n#include <Eigen/src/Core/arch/Default/Half.h>\n\n#define VERIFY_HALF_BITS_EQUAL(h, bits) \\\n  VERIFY_IS_EQUAL((numext::bit_cast<numext::uint16_t>(h)), (static_cast<numext::uint16_t>(bits)))\n\n// Make sure it's possible to forward declare Eigen::half\nnamespace Eigen {\nstruct half;\n}\n\nusing Eigen::half;\n\nvoid test_conversion()\n{\n  using Eigen::half_impl::__half_raw;\n\n  // Round-trip bit-cast with uint16.\n  VERIFY_IS_EQUAL(\n    numext::bit_cast<half>(numext::bit_cast<numext::uint16_t>(half(1.0f))),\n    half(1.0f));\n  VERIFY_IS_EQUAL(\n    numext::bit_cast<half>(numext::bit_cast<numext::uint16_t>(half(0.5f))),\n    half(0.5f));\n  VERIFY_IS_EQUAL(\n    numext::bit_cast<half>(numext::bit_cast<numext::uint16_t>(half(-0.33333f))),\n    half(-0.33333f));\n   VERIFY_IS_EQUAL(\n    numext::bit_cast<half>(numext::bit_cast<numext::uint16_t>(half(0.0f))),\n    half(0.0f));\n\n  // Conversion from float.\n  VERIFY_HALF_BITS_EQUAL(half(1.0f), 0x3c00);\n  VERIFY_HALF_BITS_EQUAL(half(0.5f), 0x3800);\n  VERIFY_HALF_BITS_EQUAL(half(0.33333f), 0x3555);\n  VERIFY_HALF_BITS_EQUAL(half(0.0f), 0x0000);\n  VERIFY_HALF_BITS_EQUAL(half(-0.0f), 0x8000);\n  VERIFY_HALF_BITS_EQUAL(half(65504.0f), 0x7bff);\n  VERIFY_HALF_BITS_EQUAL(half(65536.0f), 0x7c00);  // Becomes infinity.\n\n  // Denormals.\n  VERIFY_HALF_BITS_EQUAL(half(-5.96046e-08f), 0x8001);\n  VERIFY_HALF_BITS_EQUAL(half(5.96046e-08f), 0x0001);\n  VERIFY_HALF_BITS_EQUAL(half(1.19209e-07f), 0x0002);\n\n  // Verify round-to-nearest-even behavior.\n  float val1 = float(half(__half_raw(0x3c00)));\n  float val2 = float(half(__half_raw(0x3c01)));\n  float val3 = float(half(__half_raw(0x3c02)));\n  VERIFY_HALF_BITS_EQUAL(half(0.5f * (val1 + val2)), 0x3c00);\n  VERIFY_HALF_BITS_EQUAL(half(0.5f * (val2 + val3)), 0x3c02);\n\n  // Conversion from int.\n  VERIFY_HALF_BITS_EQUAL(half(-1), 0xbc00);\n  VERIFY_HALF_BITS_EQUAL(half(0), 0x0000);\n  VERIFY_HALF_BITS_EQUAL(half(1), 0x3c00);\n  VERIFY_HALF_BITS_EQUAL(half(2), 0x4000);\n  VERIFY_HALF_BITS_EQUAL(half(3), 0x4200);\n\n  // Conversion from bool.\n  VERIFY_HALF_BITS_EQUAL(half(false), 0x0000);\n  VERIFY_HALF_BITS_EQUAL(half(true), 0x3c00);\n\n  // Conversion to float.\n  VERIFY_IS_EQUAL(float(half(__half_raw(0x0000))), 0.0f);\n  VERIFY_IS_EQUAL(float(half(__half_raw(0x3c00))), 1.0f);\n\n  // Denormals.\n  VERIFY_IS_APPROX(float(half(__half_raw(0x8001))), -5.96046e-08f);\n  VERIFY_IS_APPROX(float(half(__half_raw(0x0001))), 5.96046e-08f);\n  VERIFY_IS_APPROX(float(half(__half_raw(0x0002))), 1.19209e-07f);\n\n  // NaNs and infinities.\n  VERIFY(!(numext::isinf)(float(half(65504.0f))));  // Largest finite number.\n  VERIFY(!(numext::isnan)(float(half(0.0f))));\n  VERIFY((numext::isinf)(float(half(__half_raw(0xfc00)))));\n  VERIFY((numext::isnan)(float(half(__half_raw(0xfc01)))));\n  VERIFY((numext::isinf)(float(half(__half_raw(0x7c00)))));\n  VERIFY((numext::isnan)(float(half(__half_raw(0x7c01)))));\n\n#if !EIGEN_COMP_MSVC\n  // Visual Studio errors out on divisions by 0\n  VERIFY((numext::isnan)(float(half(0.0 / 0.0))));\n  VERIFY((numext::isinf)(float(half(1.0 / 0.0))));\n  VERIFY((numext::isinf)(float(half(-1.0 / 0.0))));\n#endif\n\n  // Exactly same checks as above, just directly on the half representation.\n  VERIFY(!(numext::isinf)(half(__half_raw(0x7bff))));\n  VERIFY(!(numext::isnan)(half(__half_raw(0x0000))));\n  VERIFY((numext::isinf)(half(__half_raw(0xfc00))));\n  VERIFY((numext::isnan)(half(__half_raw(0xfc01))));\n  VERIFY((numext::isinf)(half(__half_raw(0x7c00))));\n  VERIFY((numext::isnan)(half(__half_raw(0x7c01))));\n\n#if !EIGEN_COMP_MSVC\n  // Visual Studio errors out on divisions by 0\n  VERIFY((numext::isnan)(half(0.0 / 0.0)));\n  VERIFY((numext::isinf)(half(1.0 / 0.0)));\n  VERIFY((numext::isinf)(half(-1.0 / 0.0)));\n#endif\n\n  // Conversion to bool\n  VERIFY(!static_cast<bool>(half(0.0)));\n  VERIFY(!static_cast<bool>(half(-0.0)));\n  VERIFY(static_cast<bool>(half(__half_raw(0x7bff))));\n  VERIFY(static_cast<bool>(half(-0.33333)));\n  VERIFY(static_cast<bool>(half(1.0)));\n  VERIFY(static_cast<bool>(half(-1.0)));\n  VERIFY(static_cast<bool>(half(-5.96046e-08f)));\n}\n\nvoid test_numtraits()\n{\n  std::cout << \"epsilon       = \" << NumTraits<half>::epsilon() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(NumTraits<half>::epsilon()) << \")\" << std::endl;\n  std::cout << \"highest       = \" << NumTraits<half>::highest() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(NumTraits<half>::highest()) << \")\" << std::endl;\n  std::cout << \"lowest        = \" << NumTraits<half>::lowest() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(NumTraits<half>::lowest()) << \")\" << std::endl;\n  std::cout << \"min           = \" << (std::numeric_limits<half>::min)() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(half((std::numeric_limits<half>::min)())) << \")\" << std::endl;\n  std::cout << \"denorm min    = \" << (std::numeric_limits<half>::denorm_min)() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(half((std::numeric_limits<half>::denorm_min)())) << \")\" << std::endl;\n  std::cout << \"infinity      = \" << NumTraits<half>::infinity() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(NumTraits<half>::infinity()) << \")\" << std::endl;\n  std::cout << \"quiet nan     = \" << NumTraits<half>::quiet_NaN() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(NumTraits<half>::quiet_NaN()) << \")\" << std::endl;\n  std::cout << \"signaling nan = \" << std::numeric_limits<half>::signaling_NaN() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(std::numeric_limits<half>::signaling_NaN()) << \")\" << std::endl;\n\n  VERIFY(NumTraits<half>::IsSigned);\n\n  VERIFY_IS_EQUAL(\n    numext::bit_cast<numext::uint16_t>(std::numeric_limits<half>::infinity()),\n    numext::bit_cast<numext::uint16_t>(half(std::numeric_limits<float>::infinity())) );\n  // There is no guarantee that casting a 32-bit NaN to 16-bit has a precise\n  // bit pattern.  We test that it is in fact a NaN, then test the signaling\n  // bit (msb of significand is 1 for quiet, 0 for signaling).\n  const numext::uint16_t HALF_QUIET_BIT = 0x0200;\n  VERIFY(\n    (numext::isnan)(std::numeric_limits<half>::quiet_NaN())\n    && (numext::isnan)(half(std::numeric_limits<float>::quiet_NaN()))\n    && ((numext::bit_cast<numext::uint16_t>(std::numeric_limits<half>::quiet_NaN()) & HALF_QUIET_BIT) > 0)\n    && ((numext::bit_cast<numext::uint16_t>(half(std::numeric_limits<float>::quiet_NaN())) & HALF_QUIET_BIT) > 0) );\n  // After a cast to half, a signaling NaN may become non-signaling\n  // (e.g. in the case of casting float to native __fp16). Thus, we check that\n  // both are NaN, and that only the `numeric_limits` version is signaling.\n  VERIFY(\n    (numext::isnan)(std::numeric_limits<half>::signaling_NaN())\n    && (numext::isnan)(half(std::numeric_limits<float>::signaling_NaN()))\n    && ((numext::bit_cast<numext::uint16_t>(std::numeric_limits<half>::signaling_NaN()) & HALF_QUIET_BIT) == 0) );\n\n  VERIFY( (std::numeric_limits<half>::min)() > half(0.f) );\n  VERIFY( (std::numeric_limits<half>::denorm_min)() > half(0.f) );\n  VERIFY( (std::numeric_limits<half>::min)()/half(2) > half(0.f) );\n  VERIFY_IS_EQUAL( (std::numeric_limits<half>::denorm_min)()/half(2), half(0.f) );\n}\n\nvoid test_arithmetic()\n{\n  VERIFY_IS_EQUAL(float(half(2) + half(2)), 4);\n  VERIFY_IS_EQUAL(float(half(2) + half(-2)), 0);\n  VERIFY_IS_APPROX(float(half(0.33333f) + half(0.66667f)), 1.0f);\n  VERIFY_IS_EQUAL(float(half(2.0f) * half(-5.5f)), -11.0f);\n  VERIFY_IS_APPROX(float(half(1.0f) / half(3.0f)), 0.33333f);\n  VERIFY_IS_EQUAL(float(-half(4096.0f)), -4096.0f);\n  VERIFY_IS_EQUAL(float(-half(-4096.0f)), 4096.0f);\n  \n  half x(3);\n  half y = ++x;\n  VERIFY_IS_EQUAL(x, half(4));\n  VERIFY_IS_EQUAL(y, half(4));\n  y = --x;\n  VERIFY_IS_EQUAL(x, half(3));\n  VERIFY_IS_EQUAL(y, half(3));\n  y = x++;\n  VERIFY_IS_EQUAL(x, half(4));\n  VERIFY_IS_EQUAL(y, half(3));\n  y = x--;\n  VERIFY_IS_EQUAL(x, half(3));\n  VERIFY_IS_EQUAL(y, half(4));\n}\n\nvoid test_comparison()\n{\n  VERIFY(half(1.0f) > half(0.5f));\n  VERIFY(half(0.5f) < half(1.0f));\n  VERIFY(!(half(1.0f) < half(0.5f)));\n  VERIFY(!(half(0.5f) > half(1.0f)));\n\n  VERIFY(!(half(4.0f) > half(4.0f)));\n  VERIFY(!(half(4.0f) < half(4.0f)));\n\n  VERIFY(!(half(0.0f) < half(-0.0f)));\n  VERIFY(!(half(-0.0f) < half(0.0f)));\n  VERIFY(!(half(0.0f) > half(-0.0f)));\n  VERIFY(!(half(-0.0f) > half(0.0f)));\n\n  VERIFY(half(0.2f) > half(-1.0f));\n  VERIFY(half(-1.0f) < half(0.2f));\n  VERIFY(half(-16.0f) < half(-15.0f));\n\n  VERIFY(half(1.0f) == half(1.0f));\n  VERIFY(half(1.0f) != half(2.0f));\n\n  // Comparisons with NaNs and infinities.\n#if !EIGEN_COMP_MSVC\n  // Visual Studio errors out on divisions by 0\n  VERIFY(!(half(0.0 / 0.0) == half(0.0 / 0.0)));\n  VERIFY(half(0.0 / 0.0) != half(0.0 / 0.0));\n\n  VERIFY(!(half(1.0) == half(0.0 / 0.0)));\n  VERIFY(!(half(1.0) < half(0.0 / 0.0)));\n  VERIFY(!(half(1.0) > half(0.0 / 0.0)));\n  VERIFY(half(1.0) != half(0.0 / 0.0));\n\n  VERIFY(half(1.0) < half(1.0 / 0.0));\n  VERIFY(half(1.0) > half(-1.0 / 0.0));\n#endif\n}\n\nvoid test_basic_functions()\n{\n  VERIFY_IS_EQUAL(float(numext::abs(half(3.5f))), 3.5f);\n  VERIFY_IS_EQUAL(float(abs(half(3.5f))), 3.5f);\n  VERIFY_IS_EQUAL(float(numext::abs(half(-3.5f))), 3.5f);\n  VERIFY_IS_EQUAL(float(abs(half(-3.5f))), 3.5f);\n\n  VERIFY_IS_EQUAL(float(numext::floor(half(3.5f))), 3.0f);\n  VERIFY_IS_EQUAL(float(floor(half(3.5f))), 3.0f);\n  VERIFY_IS_EQUAL(float(numext::floor(half(-3.5f))), -4.0f);\n  VERIFY_IS_EQUAL(float(floor(half(-3.5f))), -4.0f);\n\n  VERIFY_IS_EQUAL(float(numext::ceil(half(3.5f))), 4.0f);\n  VERIFY_IS_EQUAL(float(ceil(half(3.5f))), 4.0f);\n  VERIFY_IS_EQUAL(float(numext::ceil(half(-3.5f))), -3.0f);\n  VERIFY_IS_EQUAL(float(ceil(half(-3.5f))), -3.0f);\n\n  VERIFY_IS_APPROX(float(numext::sqrt(half(0.0f))), 0.0f);\n  VERIFY_IS_APPROX(float(sqrt(half(0.0f))), 0.0f);\n  VERIFY_IS_APPROX(float(numext::sqrt(half(4.0f))), 2.0f);\n  VERIFY_IS_APPROX(float(sqrt(half(4.0f))), 2.0f);\n\n  VERIFY_IS_APPROX(float(numext::pow(half(0.0f), half(1.0f))), 0.0f);\n  VERIFY_IS_APPROX(float(pow(half(0.0f), half(1.0f))), 0.0f);\n  VERIFY_IS_APPROX(float(numext::pow(half(2.0f), half(2.0f))), 4.0f);\n  VERIFY_IS_APPROX(float(pow(half(2.0f), half(2.0f))), 4.0f);\n\n  VERIFY_IS_EQUAL(float(numext::exp(half(0.0f))), 1.0f);\n  VERIFY_IS_EQUAL(float(exp(half(0.0f))), 1.0f);\n  VERIFY_IS_APPROX(float(numext::exp(half(EIGEN_PI))), 20.f + float(EIGEN_PI));\n  VERIFY_IS_APPROX(float(exp(half(EIGEN_PI))), 20.f + float(EIGEN_PI));\n\n  VERIFY_IS_EQUAL(float(numext::expm1(half(0.0f))), 0.0f);\n  VERIFY_IS_EQUAL(float(expm1(half(0.0f))), 0.0f);\n  VERIFY_IS_APPROX(float(numext::expm1(half(2.0f))), 6.3890561f);\n  VERIFY_IS_APPROX(float(expm1(half(2.0f))), 6.3890561f);\n\n  VERIFY_IS_EQUAL(float(numext::log(half(1.0f))), 0.0f);\n  VERIFY_IS_EQUAL(float(log(half(1.0f))), 0.0f);\n  VERIFY_IS_APPROX(float(numext::log(half(10.0f))), 2.30273f);\n  VERIFY_IS_APPROX(float(log(half(10.0f))), 2.30273f);\n\n  VERIFY_IS_EQUAL(float(numext::log1p(half(0.0f))), 0.0f);\n  VERIFY_IS_EQUAL(float(log1p(half(0.0f))), 0.0f);\n  VERIFY_IS_APPROX(float(numext::log1p(half(10.0f))), 2.3978953f);\n  VERIFY_IS_APPROX(float(log1p(half(10.0f))), 2.3978953f);\n  \n  VERIFY_IS_APPROX(numext::fmod(half(5.3f), half(2.0f)), half(1.3f));\n  VERIFY_IS_APPROX(fmod(half(5.3f), half(2.0f)), half(1.3f));\n  VERIFY_IS_APPROX(numext::fmod(half(-18.5f), half(-4.2f)), half(-1.7f));\n  VERIFY_IS_APPROX(fmod(half(-18.5f), half(-4.2f)), half(-1.7f));\n}\n\nvoid test_trigonometric_functions()\n{\n  VERIFY_IS_APPROX(numext::cos(half(0.0f)), half(cosf(0.0f)));\n  VERIFY_IS_APPROX(cos(half(0.0f)), half(cosf(0.0f)));\n  VERIFY_IS_APPROX(numext::cos(half(EIGEN_PI)), half(cosf(EIGEN_PI)));\n  // VERIFY_IS_APPROX(numext::cos(half(EIGEN_PI/2)), half(cosf(EIGEN_PI/2)));\n  // VERIFY_IS_APPROX(numext::cos(half(3*EIGEN_PI/2)), half(cosf(3*EIGEN_PI/2)));\n  VERIFY_IS_APPROX(numext::cos(half(3.5f)), half(cosf(3.5f)));\n\n  VERIFY_IS_APPROX(numext::sin(half(0.0f)), half(sinf(0.0f)));\n  VERIFY_IS_APPROX(sin(half(0.0f)), half(sinf(0.0f)));\n  //  VERIFY_IS_APPROX(numext::sin(half(EIGEN_PI)), half(sinf(EIGEN_PI)));\n  VERIFY_IS_APPROX(numext::sin(half(EIGEN_PI/2)), half(sinf(EIGEN_PI/2)));\n  VERIFY_IS_APPROX(numext::sin(half(3*EIGEN_PI/2)), half(sinf(3*EIGEN_PI/2)));\n  VERIFY_IS_APPROX(numext::sin(half(3.5f)), half(sinf(3.5f)));\n\n  VERIFY_IS_APPROX(numext::tan(half(0.0f)), half(tanf(0.0f)));\n  VERIFY_IS_APPROX(tan(half(0.0f)), half(tanf(0.0f)));\n  //  VERIFY_IS_APPROX(numext::tan(half(EIGEN_PI)), half(tanf(EIGEN_PI)));\n  //  VERIFY_IS_APPROX(numext::tan(half(EIGEN_PI/2)), half(tanf(EIGEN_PI/2)));\n  //VERIFY_IS_APPROX(numext::tan(half(3*EIGEN_PI/2)), half(tanf(3*EIGEN_PI/2)));\n  VERIFY_IS_APPROX(numext::tan(half(3.5f)), half(tanf(3.5f)));\n}\n\nvoid test_array()\n{\n  typedef Array<half,1,Dynamic> ArrayXh;\n  Index size = internal::random<Index>(1,10);\n  Index i = internal::random<Index>(0,size-1);\n  ArrayXh a1 = ArrayXh::Random(size), a2 = ArrayXh::Random(size);\n  VERIFY_IS_APPROX( a1+a1, half(2)*a1 );\n  VERIFY( (a1.abs() >= half(0)).all() );\n  VERIFY_IS_APPROX( (a1*a1).sqrt(), a1.abs() );\n\n  VERIFY( ((a1.min)(a2) <= (a1.max)(a2)).all() );\n  a1(i) = half(-10.);\n  VERIFY_IS_EQUAL( a1.minCoeff(), half(-10.) );\n  a1(i) = half(10.);\n  VERIFY_IS_EQUAL( a1.maxCoeff(), half(10.) );\n\n  std::stringstream ss;\n  ss << a1;\n}\n\nvoid test_product()\n{\n  typedef Matrix<half,Dynamic,Dynamic> MatrixXh;\n  Index rows  = internal::random<Index>(1,EIGEN_TEST_MAX_SIZE);\n  Index cols  = internal::random<Index>(1,EIGEN_TEST_MAX_SIZE);\n  Index depth = internal::random<Index>(1,EIGEN_TEST_MAX_SIZE);\n  MatrixXh Ah = MatrixXh::Random(rows,depth);\n  MatrixXh Bh = MatrixXh::Random(depth,cols);\n  MatrixXh Ch = MatrixXh::Random(rows,cols);\n  MatrixXf Af = Ah.cast<float>();\n  MatrixXf Bf = Bh.cast<float>();\n  MatrixXf Cf = Ch.cast<float>();\n  VERIFY_IS_APPROX(Ch.noalias()+=Ah*Bh, (Cf.noalias()+=Af*Bf).cast<half>());\n}\n\nEIGEN_DECLARE_TEST(half_float)\n{\n  CALL_SUBTEST(test_numtraits());\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST(test_conversion());\n    CALL_SUBTEST(test_arithmetic());\n    CALL_SUBTEST(test_comparison());\n    CALL_SUBTEST(test_basic_functions());\n    CALL_SUBTEST(test_trigonometric_functions());\n    CALL_SUBTEST(test_array());\n    CALL_SUBTEST(test_product());\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/hessenberg.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/Eigenvalues>\n\ntemplate<typename Scalar,int Size> void hessenberg(int size = Size)\n{\n  typedef Matrix<Scalar,Size,Size> MatrixType;\n\n  // Test basic functionality: A = U H U* and H is Hessenberg\n  for(int counter = 0; counter < g_repeat; ++counter) {\n    MatrixType m = MatrixType::Random(size,size);\n    HessenbergDecomposition<MatrixType> hess(m);\n    MatrixType Q = hess.matrixQ();\n    MatrixType H = hess.matrixH();\n    VERIFY_IS_APPROX(m, Q * H * Q.adjoint());\n    for(int row = 2; row < size; ++row) {\n      for(int col = 0; col < row-1; ++col) {\n\tVERIFY(H(row,col) == (typename MatrixType::Scalar)0);\n      }\n    }\n  }\n\n  // Test whether compute() and constructor returns same result\n  MatrixType A = MatrixType::Random(size, size);\n  HessenbergDecomposition<MatrixType> cs1;\n  cs1.compute(A);\n  HessenbergDecomposition<MatrixType> cs2(A);\n  VERIFY_IS_EQUAL(cs1.matrixH().eval(), cs2.matrixH().eval());\n  MatrixType cs1Q = cs1.matrixQ();\n  MatrixType cs2Q = cs2.matrixQ();  \n  VERIFY_IS_EQUAL(cs1Q, cs2Q);\n\n  // Test assertions for when used uninitialized\n  HessenbergDecomposition<MatrixType> hessUninitialized;\n  VERIFY_RAISES_ASSERT( hessUninitialized.matrixH() );\n  VERIFY_RAISES_ASSERT( hessUninitialized.matrixQ() );\n  VERIFY_RAISES_ASSERT( hessUninitialized.householderCoefficients() );\n  VERIFY_RAISES_ASSERT( hessUninitialized.packedMatrix() );\n\n  // TODO: Add tests for packedMatrix() and householderCoefficients()\n}\n\nEIGEN_DECLARE_TEST(hessenberg)\n{\n  CALL_SUBTEST_1(( hessenberg<std::complex<double>,1>() ));\n  CALL_SUBTEST_2(( hessenberg<std::complex<double>,2>() ));\n  CALL_SUBTEST_3(( hessenberg<std::complex<float>,4>() ));\n  CALL_SUBTEST_4(( hessenberg<float,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)) ));\n  CALL_SUBTEST_5(( hessenberg<std::complex<double>,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)) ));\n\n  // Test problem size constructors\n  CALL_SUBTEST_6(HessenbergDecomposition<MatrixXf>(10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/householder.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/QR>\n\ntemplate<typename MatrixType> void householder(const MatrixType& m)\n{\n  static bool even = true;\n  even = !even;\n  /* this test covers the following files:\n     Householder.h\n  */\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n  typedef Matrix<Scalar, internal::decrement_size<MatrixType::RowsAtCompileTime>::ret, 1> EssentialVectorType;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> SquareMatrixType;\n  typedef Matrix<Scalar, Dynamic, MatrixType::ColsAtCompileTime> HBlockMatrixType;\n  typedef Matrix<Scalar, Dynamic, 1> HCoeffsVectorType;\n\n  typedef Matrix<Scalar, MatrixType::ColsAtCompileTime, MatrixType::RowsAtCompileTime> TMatrixType;\n  \n  Matrix<Scalar, EIGEN_SIZE_MAX(MatrixType::RowsAtCompileTime,MatrixType::ColsAtCompileTime), 1> _tmp((std::max)(rows,cols));\n  Scalar* tmp = &_tmp.coeffRef(0,0);\n\n  Scalar beta;\n  RealScalar alpha;\n  EssentialVectorType essential;\n\n  VectorType v1 = VectorType::Random(rows), v2;\n  v2 = v1;\n  v1.makeHouseholder(essential, beta, alpha);\n  v1.applyHouseholderOnTheLeft(essential,beta,tmp);\n  VERIFY_IS_APPROX(v1.norm(), v2.norm());\n  if(rows>=2) VERIFY_IS_MUCH_SMALLER_THAN(v1.tail(rows-1).norm(), v1.norm());\n  v1 = VectorType::Random(rows);\n  v2 = v1;\n  v1.applyHouseholderOnTheLeft(essential,beta,tmp);\n  VERIFY_IS_APPROX(v1.norm(), v2.norm());\n\n  // reconstruct householder matrix:\n  SquareMatrixType id, H1, H2;\n  id.setIdentity(rows, rows);\n  H1 = H2 = id;\n  VectorType vv(rows);\n  vv << Scalar(1), essential;\n  H1.applyHouseholderOnTheLeft(essential, beta, tmp);\n  H2.applyHouseholderOnTheRight(essential, beta, tmp);\n  VERIFY_IS_APPROX(H1, H2);\n  VERIFY_IS_APPROX(H1, id - beta * vv*vv.adjoint());\n\n  MatrixType m1(rows, cols),\n             m2(rows, cols);\n\n  v1 = VectorType::Random(rows);\n  if(even) v1.tail(rows-1).setZero();\n  m1.colwise() = v1;\n  m2 = m1;\n  m1.col(0).makeHouseholder(essential, beta, alpha);\n  m1.applyHouseholderOnTheLeft(essential,beta,tmp);\n  VERIFY_IS_APPROX(m1.norm(), m2.norm());\n  if(rows>=2) VERIFY_IS_MUCH_SMALLER_THAN(m1.block(1,0,rows-1,cols).norm(), m1.norm());\n  VERIFY_IS_MUCH_SMALLER_THAN(numext::imag(m1(0,0)), numext::real(m1(0,0)));\n  VERIFY_IS_APPROX(numext::real(m1(0,0)), alpha);\n\n  v1 = VectorType::Random(rows);\n  if(even) v1.tail(rows-1).setZero();\n  SquareMatrixType m3(rows,rows), m4(rows,rows);\n  m3.rowwise() = v1.transpose();\n  m4 = m3;\n  m3.row(0).makeHouseholder(essential, beta, alpha);\n  m3.applyHouseholderOnTheRight(essential.conjugate(),beta,tmp);\n  VERIFY_IS_APPROX(m3.norm(), m4.norm());\n  if(rows>=2) VERIFY_IS_MUCH_SMALLER_THAN(m3.block(0,1,rows,rows-1).norm(), m3.norm());\n  VERIFY_IS_MUCH_SMALLER_THAN(numext::imag(m3(0,0)), numext::real(m3(0,0)));\n  VERIFY_IS_APPROX(numext::real(m3(0,0)), alpha);\n\n  // test householder sequence on the left with a shift\n\n  Index shift = internal::random<Index>(0, std::max<Index>(rows-2,0));\n  Index brows = rows - shift;\n  m1.setRandom(rows, cols);\n  HBlockMatrixType hbm = m1.block(shift,0,brows,cols);\n  HouseholderQR<HBlockMatrixType> qr(hbm);\n  m2 = m1;\n  m2.block(shift,0,brows,cols) = qr.matrixQR();\n  HCoeffsVectorType hc = qr.hCoeffs().conjugate();\n  HouseholderSequence<MatrixType, HCoeffsVectorType> hseq(m2, hc);\n  hseq.setLength(hc.size()).setShift(shift);\n  VERIFY(hseq.length() == hc.size());\n  VERIFY(hseq.shift() == shift);\n  \n  MatrixType m5 = m2;\n  m5.block(shift,0,brows,cols).template triangularView<StrictlyLower>().setZero();\n  VERIFY_IS_APPROX(hseq * m5, m1); // test applying hseq directly\n  m3 = hseq;\n  VERIFY_IS_APPROX(m3 * m5, m1); // test evaluating hseq to a dense matrix, then applying\n  \n  SquareMatrixType hseq_mat = hseq;\n  SquareMatrixType hseq_mat_conj = hseq.conjugate();\n  SquareMatrixType hseq_mat_adj = hseq.adjoint();\n  SquareMatrixType hseq_mat_trans = hseq.transpose();\n  SquareMatrixType m6 = SquareMatrixType::Random(rows, rows);\n  VERIFY_IS_APPROX(hseq_mat.adjoint(),    hseq_mat_adj);\n  VERIFY_IS_APPROX(hseq_mat.conjugate(),  hseq_mat_conj);\n  VERIFY_IS_APPROX(hseq_mat.transpose(),  hseq_mat_trans);\n  VERIFY_IS_APPROX(hseq * m6,             hseq_mat * m6);\n  VERIFY_IS_APPROX(hseq.adjoint() * m6,   hseq_mat_adj * m6);\n  VERIFY_IS_APPROX(hseq.conjugate() * m6, hseq_mat_conj * m6);\n  VERIFY_IS_APPROX(hseq.transpose() * m6, hseq_mat_trans * m6);\n  VERIFY_IS_APPROX(m6 * hseq,             m6 * hseq_mat);\n  VERIFY_IS_APPROX(m6 * hseq.adjoint(),   m6 * hseq_mat_adj);\n  VERIFY_IS_APPROX(m6 * hseq.conjugate(), m6 * hseq_mat_conj);\n  VERIFY_IS_APPROX(m6 * hseq.transpose(), m6 * hseq_mat_trans);\n\n  // test householder sequence on the right with a shift\n\n  TMatrixType tm2 = m2.transpose();\n  HouseholderSequence<TMatrixType, HCoeffsVectorType, OnTheRight> rhseq(tm2, hc);\n  rhseq.setLength(hc.size()).setShift(shift);\n  VERIFY_IS_APPROX(rhseq * m5, m1); // test applying rhseq directly\n  m3 = rhseq;\n  VERIFY_IS_APPROX(m3 * m5, m1); // test evaluating rhseq to a dense matrix, then applying\n}\n\nEIGEN_DECLARE_TEST(householder)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( householder(Matrix<double,2,2>()) );\n    CALL_SUBTEST_2( householder(Matrix<float,2,3>()) );\n    CALL_SUBTEST_3( householder(Matrix<double,3,5>()) );\n    CALL_SUBTEST_4( householder(Matrix<float,4,4>()) );\n    CALL_SUBTEST_5( householder(MatrixXd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE),internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( householder(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE),internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_7( householder(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE),internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_8( householder(Matrix<double,1,1>()) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/incomplete_cholesky.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015-2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n// #define EIGEN_DONT_VECTORIZE\n// #define EIGEN_MAX_ALIGN_BYTES 0\n#include \"sparse_solver.h\"\n#include <Eigen/IterativeLinearSolvers>\n#include <unsupported/Eigen/IterativeSolvers>\n\ntemplate<typename T, typename I_> void test_incomplete_cholesky_T()\n{\n  typedef SparseMatrix<T,0,I_> SparseMatrixType;\n  ConjugateGradient<SparseMatrixType, Lower, IncompleteCholesky<T, Lower, AMDOrdering<I_> > >        cg_illt_lower_amd;\n  ConjugateGradient<SparseMatrixType, Lower, IncompleteCholesky<T, Lower, NaturalOrdering<I_> > >    cg_illt_lower_nat;\n  ConjugateGradient<SparseMatrixType, Upper, IncompleteCholesky<T, Upper, AMDOrdering<I_> > >        cg_illt_upper_amd;\n  ConjugateGradient<SparseMatrixType, Upper, IncompleteCholesky<T, Upper, NaturalOrdering<I_> > >    cg_illt_upper_nat;\n  ConjugateGradient<SparseMatrixType, Upper|Lower, IncompleteCholesky<T, Lower, AMDOrdering<I_> > >  cg_illt_uplo_amd;\n  \n\n  CALL_SUBTEST( check_sparse_spd_solving(cg_illt_lower_amd) );\n  CALL_SUBTEST( check_sparse_spd_solving(cg_illt_lower_nat) );\n  CALL_SUBTEST( check_sparse_spd_solving(cg_illt_upper_amd) );\n  CALL_SUBTEST( check_sparse_spd_solving(cg_illt_upper_nat) );\n  CALL_SUBTEST( check_sparse_spd_solving(cg_illt_uplo_amd) );\n}\n\ntemplate<int>\nvoid bug1150()\n{\n  // regression for bug 1150\n  for(int N = 1; N<20; ++N)\n  {\n    Eigen::MatrixXd b( N, N );\n    b.setOnes();\n\n    Eigen::SparseMatrix<double> m( N, N );\n    m.reserve(Eigen::VectorXi::Constant(N,4));\n    for( int i = 0; i < N; ++i )\n    {\n        m.insert( i, i ) = 1;\n        m.coeffRef( i, i / 2 ) = 2;\n        m.coeffRef( i, i / 3 ) = 2;\n        m.coeffRef( i, i / 4 ) = 2;\n    }\n\n    Eigen::SparseMatrix<double> A;\n    A = m * m.transpose();\n\n    Eigen::ConjugateGradient<Eigen::SparseMatrix<double>,\n        Eigen::Lower | Eigen::Upper,\n        Eigen::IncompleteCholesky<double> > solver( A );\n    VERIFY(solver.preconditioner().info() == Eigen::Success);\n    VERIFY(solver.info() == Eigen::Success);\n  }\n}\n\nEIGEN_DECLARE_TEST(incomplete_cholesky)\n{\n  CALL_SUBTEST_1(( test_incomplete_cholesky_T<double,int>() ));\n  CALL_SUBTEST_2(( test_incomplete_cholesky_T<std::complex<double>, int>() ));\n  CALL_SUBTEST_3(( test_incomplete_cholesky_T<double,long int>() ));\n\n  CALL_SUBTEST_1(( bug1150<0>() ));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/indexed_view.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2017 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifdef EIGEN_TEST_PART_2\n// Make sure we also check c++11 max implementation\n#define EIGEN_MAX_CPP_VER 11\n#endif\n\n#ifdef EIGEN_TEST_PART_3\n// Make sure we also check c++98 max implementation\n#define EIGEN_MAX_CPP_VER 03\n\n// We need to disable this warning when compiling with c++11 while limiting Eigen to c++98\n// Ideally we would rather configure the compiler to build in c++98 mode but this needs\n// to be done at the CMakeLists.txt level.\n#if defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8))\n  #pragma GCC diagnostic ignored \"-Wdeprecated\"\n#endif\n\n#if defined(__GNUC__) && (__GNUC__ >=9)\n  #pragma GCC diagnostic ignored \"-Wdeprecated-copy\"\n#endif\n#if defined(__clang__) && (__clang_major__ >= 10)\n  #pragma clang diagnostic ignored \"-Wdeprecated-copy\"\n#endif\n\n#endif\n\n#include <valarray>\n#include <vector>\n#include \"main.h\"\n\n#if EIGEN_HAS_CXX11\n#include <array>\n#endif\n\ntypedef std::pair<Index,Index> IndexPair;\n\nint encode(Index i, Index j) {\n  return int(i*100 + j);\n}\n\nIndexPair decode(Index ij) {\n  return IndexPair(ij / 100, ij % 100);\n}\n\ntemplate<typename T>\nbool match(const T& xpr, std::string ref, std::string str_xpr = \"\") {\n  EIGEN_UNUSED_VARIABLE(str_xpr);\n  std::stringstream str;\n  str << xpr;\n  if(!(str.str() == ref))\n    std::cout << str_xpr << \"\\n\" << xpr << \"\\n\\n\";\n  return str.str() == ref;\n}\n\n#define MATCH(X,R) match(X, R, #X)\n\ntemplate<typename T1,typename T2>\ntypename internal::enable_if<internal::is_same<T1,T2>::value,bool>::type\nis_same_eq(const T1& a, const T2& b)\n{\n  return (a == b).all();\n}\n\ntemplate<typename T1,typename T2>\nbool is_same_seq(const T1& a, const T2& b)\n{\n  bool ok = a.first()==b.first() && a.size() == b.size() && Index(a.incrObject())==Index(b.incrObject());;\n  if(!ok)\n  {\n    std::cerr << \"seqN(\" << a.first() << \", \" << a.size() << \", \" << Index(a.incrObject()) << \") != \";\n    std::cerr << \"seqN(\" << b.first() << \", \" << b.size() << \", \" << Index(b.incrObject()) << \")\\n\";\n  }\n  return ok;\n}\n\ntemplate<typename T1,typename T2>\ntypename internal::enable_if<internal::is_same<T1,T2>::value,bool>::type\nis_same_seq_type(const T1& a, const T2& b)\n{\n  return is_same_seq(a,b);\n}\n\n\n\n#define VERIFY_EQ_INT(A,B) VERIFY_IS_APPROX(int(A),int(B))\n\n// C++03 does not allow local or unnamed enums as index\nenum DummyEnum { XX=0, YY=1 };\n\nvoid check_indexed_view()\n{\n  Index n = 10;\n\n  ArrayXd a = ArrayXd::LinSpaced(n,0,n-1);\n  Array<double,1,Dynamic> b = a.transpose();\n\n  #if EIGEN_COMP_CXXVER>=14\n  ArrayXXi A = ArrayXXi::NullaryExpr(n,n, std::ref(encode));\n  #else\n  ArrayXXi A = ArrayXXi::NullaryExpr(n,n, std::ptr_fun(&encode));\n  #endif\n\n  for(Index i=0; i<n; ++i)\n    for(Index j=0; j<n; ++j)\n      VERIFY( decode(A(i,j)) == IndexPair(i,j) );\n\n  Array4i eii(4); eii << 3, 1, 6, 5;\n  std::valarray<int> vali(4); Map<ArrayXi>(&vali[0],4) = eii;\n  std::vector<int> veci(4); Map<ArrayXi>(veci.data(),4) = eii;\n\n  VERIFY( MATCH( A(3, seq(9,3,-1)),\n    \"309  308  307  306  305  304  303\")\n  );\n\n  VERIFY( MATCH( A(seqN(2,5), seq(9,3,-1)),\n    \"209  208  207  206  205  204  203\\n\"\n    \"309  308  307  306  305  304  303\\n\"\n    \"409  408  407  406  405  404  403\\n\"\n    \"509  508  507  506  505  504  503\\n\"\n    \"609  608  607  606  605  604  603\")\n  );\n\n  VERIFY( MATCH( A(seqN(2,5), 5),\n    \"205\\n\"\n    \"305\\n\"\n    \"405\\n\"\n    \"505\\n\"\n    \"605\")\n  );\n\n  VERIFY( MATCH( A(seqN(last,5,-1), seq(2,last)),\n    \"902  903  904  905  906  907  908  909\\n\"\n    \"802  803  804  805  806  807  808  809\\n\"\n    \"702  703  704  705  706  707  708  709\\n\"\n    \"602  603  604  605  606  607  608  609\\n\"\n    \"502  503  504  505  506  507  508  509\")\n  );\n\n  VERIFY( MATCH( A(eii, veci),\n    \"303  301  306  305\\n\"\n    \"103  101  106  105\\n\"\n    \"603  601  606  605\\n\"\n    \"503  501  506  505\")\n  );\n\n  VERIFY( MATCH( A(eii, all),\n    \"300  301  302  303  304  305  306  307  308  309\\n\"\n    \"100  101  102  103  104  105  106  107  108  109\\n\"\n    \"600  601  602  603  604  605  606  607  608  609\\n\"\n    \"500  501  502  503  504  505  506  507  508  509\")\n  );\n\n  // take row number 3, and repeat it 5 times\n  VERIFY( MATCH( A(seqN(3,5,0), all),\n    \"300  301  302  303  304  305  306  307  308  309\\n\"\n    \"300  301  302  303  304  305  306  307  308  309\\n\"\n    \"300  301  302  303  304  305  306  307  308  309\\n\"\n    \"300  301  302  303  304  305  306  307  308  309\\n\"\n    \"300  301  302  303  304  305  306  307  308  309\")\n  );\n\n  VERIFY( MATCH( a(seqN(3,3),0), \"3\\n4\\n5\" ) );\n  VERIFY( MATCH( a(seq(3,5)), \"3\\n4\\n5\" ) );\n  VERIFY( MATCH( a(seqN(3,3,1)), \"3\\n4\\n5\" ) );\n  VERIFY( MATCH( a(seqN(5,3,-1)), \"5\\n4\\n3\" ) );\n\n  VERIFY( MATCH( b(0,seqN(3,3)), \"3  4  5\" ) );\n  VERIFY( MATCH( b(seq(3,5)), \"3  4  5\" ) );\n  VERIFY( MATCH( b(seqN(3,3,1)), \"3  4  5\" ) );\n  VERIFY( MATCH( b(seqN(5,3,-1)), \"5  4  3\" ) );\n\n  VERIFY( MATCH( b(all), \"0  1  2  3  4  5  6  7  8  9\" ) );\n  VERIFY( MATCH( b(eii), \"3  1  6  5\" ) );\n\n  Array44i B;\n  B.setRandom();\n  VERIFY( (A(seqN(2,5), 5)).ColsAtCompileTime == 1);\n  VERIFY( (A(seqN(2,5), 5)).RowsAtCompileTime == Dynamic);\n  VERIFY_EQ_INT( (A(seqN(2,5), 5)).InnerStrideAtCompileTime , A.InnerStrideAtCompileTime);\n  VERIFY_EQ_INT( (A(seqN(2,5), 5)).OuterStrideAtCompileTime , A.col(5).OuterStrideAtCompileTime);\n\n  VERIFY_EQ_INT( (A(5,seqN(2,5))).InnerStrideAtCompileTime , A.row(5).InnerStrideAtCompileTime);\n  VERIFY_EQ_INT( (A(5,seqN(2,5))).OuterStrideAtCompileTime , A.row(5).OuterStrideAtCompileTime);\n  VERIFY_EQ_INT( (B(1,seqN(1,2))).InnerStrideAtCompileTime , B.row(1).InnerStrideAtCompileTime);\n  VERIFY_EQ_INT( (B(1,seqN(1,2))).OuterStrideAtCompileTime , B.row(1).OuterStrideAtCompileTime);\n\n  VERIFY_EQ_INT( (A(seqN(2,5), seq(1,3))).InnerStrideAtCompileTime , A.InnerStrideAtCompileTime);\n  VERIFY_EQ_INT( (A(seqN(2,5), seq(1,3))).OuterStrideAtCompileTime , A.OuterStrideAtCompileTime);\n  VERIFY_EQ_INT( (B(seqN(1,2), seq(1,3))).InnerStrideAtCompileTime , B.InnerStrideAtCompileTime);\n  VERIFY_EQ_INT( (B(seqN(1,2), seq(1,3))).OuterStrideAtCompileTime , B.OuterStrideAtCompileTime);\n  VERIFY_EQ_INT( (A(seqN(2,5,2), seq(1,3,2))).InnerStrideAtCompileTime , Dynamic);\n  VERIFY_EQ_INT( (A(seqN(2,5,2), seq(1,3,2))).OuterStrideAtCompileTime , Dynamic);\n  VERIFY_EQ_INT( (A(seqN(2,5,fix<2>), seq(1,3,fix<3>))).InnerStrideAtCompileTime , 2);\n  VERIFY_EQ_INT( (A(seqN(2,5,fix<2>), seq(1,3,fix<3>))).OuterStrideAtCompileTime , Dynamic);\n  VERIFY_EQ_INT( (B(seqN(1,2,fix<2>), seq(1,3,fix<3>))).InnerStrideAtCompileTime , 2);\n  VERIFY_EQ_INT( (B(seqN(1,2,fix<2>), seq(1,3,fix<3>))).OuterStrideAtCompileTime , 3*4);\n\n  VERIFY_EQ_INT( (A(seqN(2,fix<5>), seqN(1,fix<3>))).RowsAtCompileTime, 5);\n  VERIFY_EQ_INT( (A(seqN(2,fix<5>), seqN(1,fix<3>))).ColsAtCompileTime, 3);\n  VERIFY_EQ_INT( (A(seqN(2,fix<5>(5)), seqN(1,fix<3>(3)))).RowsAtCompileTime, 5);\n  VERIFY_EQ_INT( (A(seqN(2,fix<5>(5)), seqN(1,fix<3>(3)))).ColsAtCompileTime, 3);\n  VERIFY_EQ_INT( (A(seqN(2,fix<Dynamic>(5)), seqN(1,fix<Dynamic>(3)))).RowsAtCompileTime, Dynamic);\n  VERIFY_EQ_INT( (A(seqN(2,fix<Dynamic>(5)), seqN(1,fix<Dynamic>(3)))).ColsAtCompileTime, Dynamic);\n  VERIFY_EQ_INT( (A(seqN(2,fix<Dynamic>(5)), seqN(1,fix<Dynamic>(3)))).rows(), 5);\n  VERIFY_EQ_INT( (A(seqN(2,fix<Dynamic>(5)), seqN(1,fix<Dynamic>(3)))).cols(), 3);\n\n  VERIFY( is_same_seq_type( seqN(2,5,fix<-1>), seqN(2,5,fix<-1>(-1)) ) );\n  VERIFY( is_same_seq_type( seqN(2,5), seqN(2,5,fix<1>(1)) ) );\n  VERIFY( is_same_seq_type( seqN(2,5,3), seqN(2,5,fix<DynamicIndex>(3)) ) );\n  VERIFY( is_same_seq_type( seq(2,7,fix<3>), seqN(2,2,fix<3>) ) );\n  VERIFY( is_same_seq_type( seqN(2,fix<Dynamic>(5),3), seqN(2,5,fix<DynamicIndex>(3)) ) );\n  VERIFY( is_same_seq_type( seqN(2,fix<5>(5),fix<-2>), seqN(2,fix<5>,fix<-2>()) ) );\n\n  VERIFY( is_same_seq_type( seq(2,fix<5>), seqN(2,4) ) );\n#if EIGEN_HAS_CXX11\n  VERIFY( is_same_seq_type( seq(fix<2>,fix<5>), seqN(fix<2>,fix<4>) ) );\n  VERIFY( is_same_seq( seqN(2,std::integral_constant<int,5>(),std::integral_constant<int,-2>()), seqN(2,fix<5>,fix<-2>()) ) );\n  VERIFY( is_same_seq( seq(std::integral_constant<int,1>(),std::integral_constant<int,5>(),std::integral_constant<int,2>()),\n                       seq(fix<1>,fix<5>,fix<2>()) ) );\n  VERIFY( is_same_seq_type( seqN(2,std::integral_constant<int,5>(),std::integral_constant<int,-2>()), seqN(2,fix<5>,fix<-2>()) ) );\n  VERIFY( is_same_seq_type( seq(std::integral_constant<int,1>(),std::integral_constant<int,5>(),std::integral_constant<int,2>()),\n                            seq(fix<1>,fix<5>,fix<2>()) ) );\n\n  VERIFY( is_same_seq_type( seqN(2,std::integral_constant<int,5>()), seqN(2,fix<5>) ) );\n  VERIFY( is_same_seq_type( seq(std::integral_constant<int,1>(),std::integral_constant<int,5>()), seq(fix<1>,fix<5>) ) );\n#else\n  // sorry, no compile-time size recovery in c++98/03\n  VERIFY( is_same_seq( seq(fix<2>,fix<5>), seqN(fix<2>,fix<4>) ) );\n#endif\n\n  VERIFY( (A(seqN(2,fix<5>), 5)).RowsAtCompileTime == 5);\n  VERIFY( (A(4, all)).ColsAtCompileTime == Dynamic);\n  VERIFY( (A(4, all)).RowsAtCompileTime == 1);\n  VERIFY( (B(1, all)).ColsAtCompileTime == 4);\n  VERIFY( (B(1, all)).RowsAtCompileTime == 1);\n  VERIFY( (B(all,1)).ColsAtCompileTime == 1);\n  VERIFY( (B(all,1)).RowsAtCompileTime == 4);\n\n  VERIFY(int( (A(all, eii)).ColsAtCompileTime) == int(eii.SizeAtCompileTime));\n  VERIFY_EQ_INT( (A(eii, eii)).Flags&DirectAccessBit, (unsigned int)(0));\n  VERIFY_EQ_INT( (A(eii, eii)).InnerStrideAtCompileTime, 0);\n  VERIFY_EQ_INT( (A(eii, eii)).OuterStrideAtCompileTime, 0);\n\n  VERIFY_IS_APPROX( A(seq(n-1,2,-2), seqN(n-1-6,3,-1)), A(seq(last,2,fix<-2>), seqN(last-6,3,fix<-1>)) );\n\n  VERIFY_IS_APPROX( A(seq(n-1,2,-2), seqN(n-1-6,4)), A(seq(last,2,-2), seqN(last-6,4)) );\n  VERIFY_IS_APPROX( A(seq(n-1-6,n-1-2), seqN(n-1-6,4)), A(seq(last-6,last-2), seqN(6+last-6-6,4)) );\n  VERIFY_IS_APPROX( A(seq((n-1)/2,(n)/2+3), seqN(2,4)), A(seq(last/2,(last+1)/2+3), seqN(last+2-last,4)) );\n  VERIFY_IS_APPROX( A(seq(n-2,2,-2), seqN(n-8,4)), A(seq(lastp1-2,2,-2), seqN(lastp1-8,4)) );\n\n  // Check all combinations of seq:\n  VERIFY_IS_APPROX( A(seq(1,n-1-2,2), seq(1,n-1-2,2)), A(seq(1,last-2,2), seq(1,last-2,fix<2>)) );\n  VERIFY_IS_APPROX( A(seq(n-1-5,n-1-2,2), seq(n-1-5,n-1-2,2)), A(seq(last-5,last-2,2), seq(last-5,last-2,fix<2>)) );\n  VERIFY_IS_APPROX( A(seq(n-1-5,7,2), seq(n-1-5,7,2)), A(seq(last-5,7,2), seq(last-5,7,fix<2>)) );\n  VERIFY_IS_APPROX( A(seq(1,n-1-2), seq(n-1-5,7)), A(seq(1,last-2), seq(last-5,7)) );\n  VERIFY_IS_APPROX( A(seq(n-1-5,n-1-2), seq(n-1-5,n-1-2)), A(seq(last-5,last-2), seq(last-5,last-2)) );\n\n  VERIFY_IS_APPROX( A.col(A.cols()-1), A(all,last) );\n  VERIFY_IS_APPROX( A(A.rows()-2, A.cols()/2), A(last-1, lastp1/2) );\n  VERIFY_IS_APPROX( a(a.size()-2), a(last-1) );\n  VERIFY_IS_APPROX( a(a.size()/2), a((last+1)/2) );\n\n  // Check fall-back to Block\n  {\n    VERIFY( is_same_eq(A.col(0), A(all,0)) );\n    VERIFY( is_same_eq(A.row(0), A(0,all)) );\n    VERIFY( is_same_eq(A.block(0,0,2,2), A(seqN(0,2),seq(0,1))) );\n    VERIFY( is_same_eq(A.middleRows(2,4), A(seqN(2,4),all)) );\n    VERIFY( is_same_eq(A.middleCols(2,4), A(all,seqN(2,4))) );\n\n    VERIFY( is_same_eq(A.col(A.cols()-1), A(all,last)) );\n\n    const ArrayXXi& cA(A);\n    VERIFY( is_same_eq(cA.col(0), cA(all,0)) );\n    VERIFY( is_same_eq(cA.row(0), cA(0,all)) );\n    VERIFY( is_same_eq(cA.block(0,0,2,2), cA(seqN(0,2),seq(0,1))) );\n    VERIFY( is_same_eq(cA.middleRows(2,4), cA(seqN(2,4),all)) );\n    VERIFY( is_same_eq(cA.middleCols(2,4), cA(all,seqN(2,4))) );\n\n    VERIFY( is_same_eq(a.head(4), a(seq(0,3))) );\n    VERIFY( is_same_eq(a.tail(4), a(seqN(last-3,4))) );\n    VERIFY( is_same_eq(a.tail(4), a(seq(lastp1-4,last))) );\n    VERIFY( is_same_eq(a.segment<4>(3), a(seqN(3,fix<4>))) );\n  }\n\n  ArrayXXi A1=A, A2 = ArrayXXi::Random(4,4);\n  ArrayXi range25(4); range25 << 3,2,4,5;\n  A1(seqN(3,4),seq(2,5)) = A2;\n  VERIFY_IS_APPROX( A1.block(3,2,4,4), A2 );\n  A1 = A;\n  A2.setOnes();\n  A1(seq(6,3,-1),range25) = A2;\n  VERIFY_IS_APPROX( A1.block(3,2,4,4), A2 );\n\n  // check reverse\n  {\n    VERIFY( is_same_seq_type( seq(3,7).reverse(), seqN(7,5,fix<-1>)  ) );\n    VERIFY( is_same_seq_type( seq(7,3,fix<-2>).reverse(), seqN(3,3,fix<2>)  ) );\n    VERIFY_IS_APPROX( a(seqN(2,last/2).reverse()), a(seqN(2+(last/2-1)*1,last/2,fix<-1>)) );\n    VERIFY_IS_APPROX( a(seqN(last/2,fix<4>).reverse()),a(seqN(last/2,fix<4>)).reverse() );\n    VERIFY_IS_APPROX( A(seq(last-5,last-1,2).reverse(), seqN(last-3,3,fix<-2>).reverse()),\n                      A(seq(last-5,last-1,2), seqN(last-3,3,fix<-2>)).reverse() );\n  }\n\n#if EIGEN_HAS_CXX11\n  // check lastN\n  VERIFY_IS_APPROX( a(lastN(3)), a.tail(3) );\n  VERIFY( MATCH( a(lastN(3)), \"7\\n8\\n9\" ) );\n  VERIFY_IS_APPROX( a(lastN(fix<3>())), a.tail<3>() );\n  VERIFY( MATCH( a(lastN(3,2)), \"5\\n7\\n9\" ) );\n  VERIFY( MATCH( a(lastN(3,fix<2>())), \"5\\n7\\n9\" ) );\n  VERIFY( a(lastN(fix<3>())).SizeAtCompileTime == 3 );\n\n  VERIFY( (A(all, std::array<int,4>{{1,3,2,4}})).ColsAtCompileTime == 4);\n\n  VERIFY_IS_APPROX( (A(std::array<int,3>{{1,3,5}}, std::array<int,4>{{9,6,3,0}})), A(seqN(1,3,2), seqN(9,4,-3)) );\n\n#if EIGEN_HAS_STATIC_ARRAY_TEMPLATE\n  VERIFY_IS_APPROX( A({3, 1, 6, 5}, all), A(std::array<int,4>{{3, 1, 6, 5}}, all) );\n  VERIFY_IS_APPROX( A(all,{3, 1, 6, 5}), A(all,std::array<int,4>{{3, 1, 6, 5}}) );\n  VERIFY_IS_APPROX( A({1,3,5},{3, 1, 6, 5}), A(std::array<int,3>{{1,3,5}},std::array<int,4>{{3, 1, 6, 5}}) );\n\n  VERIFY_IS_EQUAL( A({1,3,5},{3, 1, 6, 5}).RowsAtCompileTime, 3 );\n  VERIFY_IS_EQUAL( A({1,3,5},{3, 1, 6, 5}).ColsAtCompileTime, 4 );\n\n  VERIFY_IS_APPROX( a({3, 1, 6, 5}), a(std::array<int,4>{{3, 1, 6, 5}}) );\n  VERIFY_IS_EQUAL( a({1,3,5}).SizeAtCompileTime, 3 );\n\n  VERIFY_IS_APPROX( b({3, 1, 6, 5}), b(std::array<int,4>{{3, 1, 6, 5}}) );\n  VERIFY_IS_EQUAL( b({1,3,5}).SizeAtCompileTime, 3 );\n#endif\n\n#endif\n\n  // check mat(i,j) with weird types for i and j\n  {\n    VERIFY_IS_APPROX( A(B.RowsAtCompileTime-1, 1), A(3,1) );\n    VERIFY_IS_APPROX( A(B.RowsAtCompileTime, 1), A(4,1) );\n    VERIFY_IS_APPROX( A(B.RowsAtCompileTime-1, B.ColsAtCompileTime-1), A(3,3) );\n    VERIFY_IS_APPROX( A(B.RowsAtCompileTime, B.ColsAtCompileTime), A(4,4) );\n    const Index I_ = 3, J_ = 4;\n    VERIFY_IS_APPROX( A(I_,J_), A(3,4) );\n  }\n\n  // check extended block API\n  {\n    VERIFY( is_same_eq( A.block<3,4>(1,1), A.block(1,1,fix<3>,fix<4>)) );\n    VERIFY( is_same_eq( A.block<3,4>(1,1,3,4), A.block(1,1,fix<3>(),fix<4>(4))) );\n    VERIFY( is_same_eq( A.block<3,Dynamic>(1,1,3,4), A.block(1,1,fix<3>,4)) );\n    VERIFY( is_same_eq( A.block<Dynamic,4>(1,1,3,4), A.block(1,1,fix<Dynamic>(3),fix<4>)) );\n    VERIFY( is_same_eq( A.block(1,1,3,4), A.block(1,1,fix<Dynamic>(3),fix<Dynamic>(4))) );\n\n    VERIFY( is_same_eq( A.topLeftCorner<3,4>(), A.topLeftCorner(fix<3>,fix<4>)) );\n    VERIFY( is_same_eq( A.bottomLeftCorner<3,4>(), A.bottomLeftCorner(fix<3>,fix<4>)) );\n    VERIFY( is_same_eq( A.bottomRightCorner<3,4>(), A.bottomRightCorner(fix<3>,fix<4>)) );\n    VERIFY( is_same_eq( A.topRightCorner<3,4>(), A.topRightCorner(fix<3>,fix<4>)) );\n\n    VERIFY( is_same_eq( A.leftCols<3>(), A.leftCols(fix<3>)) );\n    VERIFY( is_same_eq( A.rightCols<3>(), A.rightCols(fix<3>)) );\n    VERIFY( is_same_eq( A.middleCols<3>(1), A.middleCols(1,fix<3>)) );\n\n    VERIFY( is_same_eq( A.topRows<3>(), A.topRows(fix<3>)) );\n    VERIFY( is_same_eq( A.bottomRows<3>(), A.bottomRows(fix<3>)) );\n    VERIFY( is_same_eq( A.middleRows<3>(1), A.middleRows(1,fix<3>)) );\n\n    VERIFY( is_same_eq( a.segment<3>(1), a.segment(1,fix<3>)) );\n    VERIFY( is_same_eq( a.head<3>(), a.head(fix<3>)) );\n    VERIFY( is_same_eq( a.tail<3>(), a.tail(fix<3>)) );\n\n    const ArrayXXi& cA(A);\n    VERIFY( is_same_eq( cA.block<Dynamic,4>(1,1,3,4), cA.block(1,1,fix<Dynamic>(3),fix<4>)) );\n\n    VERIFY( is_same_eq( cA.topLeftCorner<3,4>(), cA.topLeftCorner(fix<3>,fix<4>)) );\n    VERIFY( is_same_eq( cA.bottomLeftCorner<3,4>(), cA.bottomLeftCorner(fix<3>,fix<4>)) );\n    VERIFY( is_same_eq( cA.bottomRightCorner<3,4>(), cA.bottomRightCorner(fix<3>,fix<4>)) );\n    VERIFY( is_same_eq( cA.topRightCorner<3,4>(), cA.topRightCorner(fix<3>,fix<4>)) );\n\n    VERIFY( is_same_eq( cA.leftCols<3>(), cA.leftCols(fix<3>)) );\n    VERIFY( is_same_eq( cA.rightCols<3>(), cA.rightCols(fix<3>)) );\n    VERIFY( is_same_eq( cA.middleCols<3>(1), cA.middleCols(1,fix<3>)) );\n\n    VERIFY( is_same_eq( cA.topRows<3>(), cA.topRows(fix<3>)) );\n    VERIFY( is_same_eq( cA.bottomRows<3>(), cA.bottomRows(fix<3>)) );\n    VERIFY( is_same_eq( cA.middleRows<3>(1), cA.middleRows(1,fix<3>)) );\n  }\n\n  // Check compilation of enums as index type:\n  a(XX) = 1;\n  A(XX,YY) = 1;\n  // Anonymous enums only work with C++11\n#if EIGEN_HAS_CXX11\n  enum { X=0, Y=1 };\n  a(X) = 1;\n  A(X,Y) = 1;\n  A(XX,Y) = 1;\n  A(X,YY) = 1;\n#endif\n\n  // Check compilation of varying integer types as index types:\n  Index i = n/2;\n  short i_short(i);\n  std::size_t i_sizet(i);\n  VERIFY_IS_EQUAL( a(i), a.coeff(i_short) );\n  VERIFY_IS_EQUAL( a(i), a.coeff(i_sizet) );\n\n  VERIFY_IS_EQUAL( A(i,i), A.coeff(i_short, i_short) );\n  VERIFY_IS_EQUAL( A(i,i), A.coeff(i_short, i) );\n  VERIFY_IS_EQUAL( A(i,i), A.coeff(i, i_short) );\n  VERIFY_IS_EQUAL( A(i,i), A.coeff(i, i_sizet) );\n  VERIFY_IS_EQUAL( A(i,i), A.coeff(i_sizet, i) );\n  VERIFY_IS_EQUAL( A(i,i), A.coeff(i_sizet, i_short) );\n  VERIFY_IS_EQUAL( A(i,i), A.coeff(5, i_sizet) );\n\n  // Regression test for Max{Rows,Cols}AtCompileTime\n  {\n    Matrix3i A3 = Matrix3i::Random();\n    ArrayXi ind(5); ind << 1,1,1,1,1;\n    VERIFY_IS_EQUAL( A3(ind,ind).eval(), MatrixXi::Constant(5,5,A3(1,1)) );\n  }\n\n  // Regression for bug 1736\n  {\n    VERIFY_IS_APPROX(A(all, eii).col(0).eval(), A.col(eii(0)));\n    A(all, eii).col(0) = A.col(eii(0));\n  }\n\n  // bug 1815: IndexedView should allow linear access\n  {\n    VERIFY( MATCH( b(eii)(0), \"3\" ) );\n    VERIFY( MATCH( a(eii)(0), \"3\" ) );\n    VERIFY( MATCH( A(1,eii)(0), \"103\"));\n    VERIFY( MATCH( A(eii,1)(0), \"301\"));\n    VERIFY( MATCH( A(1,all)(1), \"101\"));\n    VERIFY( MATCH( A(all,1)(1), \"101\"));\n  }\n\n#if EIGEN_HAS_CXX11\n  //Bug IndexView with a single static row should be RowMajor:\n  {\n    // A(1, seq(0,2,1)).cwiseAbs().colwise().replicate(2).eval();\n    STATIC_CHECK(( (internal::evaluator<decltype( A(1,seq(0,2,1)) )>::Flags & RowMajorBit) == RowMajorBit ));\n  }\n#endif\n\n}\n\nEIGEN_DECLARE_TEST(indexed_view)\n{\n//   for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( check_indexed_view() );\n    CALL_SUBTEST_2( check_indexed_view() );\n    CALL_SUBTEST_3( check_indexed_view() );\n//   }\n\n  // static checks of some internals:\n  STATIC_CHECK(( internal::is_valid_index_type<int>::value ));\n  STATIC_CHECK(( internal::is_valid_index_type<unsigned int>::value ));\n  STATIC_CHECK(( internal::is_valid_index_type<short>::value ));\n  STATIC_CHECK(( internal::is_valid_index_type<std::ptrdiff_t>::value ));\n  STATIC_CHECK(( internal::is_valid_index_type<std::size_t>::value ));\n  STATIC_CHECK(( !internal::valid_indexed_view_overload<int,int>::value ));\n  STATIC_CHECK(( !internal::valid_indexed_view_overload<int,std::ptrdiff_t>::value ));\n  STATIC_CHECK(( !internal::valid_indexed_view_overload<std::ptrdiff_t,int>::value ));\n  STATIC_CHECK(( !internal::valid_indexed_view_overload<std::size_t,int>::value ));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/initializer_list_construction.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2019 David Tellenbach <david.tellenbach@tellnotes.org>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_STATIC_ASSERT\n\n#include \"main.h\"\n\ntemplate<typename Scalar, bool is_integer = NumTraits<Scalar>::IsInteger>\nstruct TestMethodDispatching {\n  static void run() {}\n};\n\ntemplate<typename Scalar>\nstruct TestMethodDispatching<Scalar, 1> {\n  static void run()\n  {\n    {\n      Matrix<Scalar, Dynamic, Dynamic> m {3, 4};\n      Array<Scalar, Dynamic, Dynamic> a {3, 4};\n      VERIFY(m.rows() == 3);\n      VERIFY(m.cols() == 4);\n      VERIFY(a.rows() == 3);\n      VERIFY(a.cols() == 4);\n    }\n    {\n      Matrix<Scalar, 1, 2> m {3, 4};\n      Array<Scalar, 1, 2> a {3, 4};\n      VERIFY(m(0) == 3);\n      VERIFY(m(1) == 4);\n      VERIFY(a(0) == 3);\n      VERIFY(a(1) == 4);\n    }\n    {\n      Matrix<Scalar, 2, 1> m {3, 4};\n      Array<Scalar, 2, 1> a {3, 4};\n      VERIFY(m(0) == 3);\n      VERIFY(m(1) == 4);\n      VERIFY(a(0) == 3);\n      VERIFY(a(1) == 4);\n    }\n  }\n};\n\ntemplate<typename Vec4, typename Vec5> void fixedsizeVariadicVectorConstruction2()\n{\n  {\n    Vec4 ref = Vec4::Random();\n    Vec4 v{ ref[0], ref[1], ref[2], ref[3] };\n    VERIFY_IS_APPROX(v, ref);\n    VERIFY_IS_APPROX(v, (Vec4( ref[0], ref[1], ref[2], ref[3] )));\n    VERIFY_IS_APPROX(v, (Vec4({ref[0], ref[1], ref[2], ref[3]})));\n\n    Vec4 v2 = { ref[0], ref[1], ref[2], ref[3] };\n    VERIFY_IS_APPROX(v2, ref);\n  }\n  {\n    Vec5 ref = Vec5::Random();\n    Vec5 v{ ref[0], ref[1], ref[2], ref[3], ref[4] };\n    VERIFY_IS_APPROX(v, ref);\n    VERIFY_IS_APPROX(v, (Vec5( ref[0], ref[1], ref[2], ref[3], ref[4] )));\n    VERIFY_IS_APPROX(v, (Vec5({ref[0], ref[1], ref[2], ref[3], ref[4]})));\n\n    Vec5 v2 = { ref[0], ref[1], ref[2], ref[3], ref[4] };\n    VERIFY_IS_APPROX(v2, ref);\n  }\n}\n\n#define CHECK_MIXSCALAR_V5_APPROX(V, A0, A1, A2, A3, A4) { \\\n  VERIFY_IS_APPROX(V[0], Scalar(A0) ); \\\n  VERIFY_IS_APPROX(V[1], Scalar(A1) ); \\\n  VERIFY_IS_APPROX(V[2], Scalar(A2) ); \\\n  VERIFY_IS_APPROX(V[3], Scalar(A3) ); \\\n  VERIFY_IS_APPROX(V[4], Scalar(A4) ); \\\n}\n\n#define CHECK_MIXSCALAR_V5(VEC5, A0, A1, A2, A3, A4) { \\\n  typedef VEC5::Scalar Scalar; \\\n  VEC5 v = { A0 , A1 , A2 , A3 , A4 }; \\\n  CHECK_MIXSCALAR_V5_APPROX(v, A0 , A1 , A2 , A3 , A4); \\\n}\n\ntemplate<int> void fixedsizeVariadicVectorConstruction3()\n{\n  typedef Matrix<double,5,1> Vec5;\n  typedef Array<float,5,1> Arr5;\n  CHECK_MIXSCALAR_V5(Vec5, 1, 2., -3, 4.121, 5.53252);\n  CHECK_MIXSCALAR_V5(Arr5, 1, 2., 3.12f, 4.121, 5.53252);\n}\n\ntemplate<typename Scalar> void fixedsizeVariadicVectorConstruction()\n{\n  CALL_SUBTEST(( fixedsizeVariadicVectorConstruction2<Matrix<Scalar,4,1>, Matrix<Scalar,5,1> >() ));\n  CALL_SUBTEST(( fixedsizeVariadicVectorConstruction2<Matrix<Scalar,1,4>, Matrix<Scalar,1,5> >() ));\n  CALL_SUBTEST(( fixedsizeVariadicVectorConstruction2<Array<Scalar,4,1>,  Array<Scalar,5,1>  >() ));\n  CALL_SUBTEST(( fixedsizeVariadicVectorConstruction2<Array<Scalar,1,4>,  Array<Scalar,1,5>  >() ));\n}\n\n\ntemplate<typename Scalar> void initializerListVectorConstruction()\n{\n  Scalar raw[4];\n  for(int k = 0; k < 4; ++k) {\n    raw[k] = internal::random<Scalar>();\n  }\n  {\n    Matrix<Scalar, 4, 1> m { {raw[0]}, {raw[1]},{raw[2]},{raw[3]} };\n    Array<Scalar, 4, 1> a { {raw[0]}, {raw[1]}, {raw[2]}, {raw[3]} };\n    for(int k = 0; k < 4; ++k) {\n      VERIFY(m(k) == raw[k]);\n    }\n    for(int k = 0; k < 4; ++k) {\n      VERIFY(a(k) == raw[k]);\n    }\n    VERIFY_IS_EQUAL(m, (Matrix<Scalar,4,1>({ {raw[0]}, {raw[1]}, {raw[2]}, {raw[3]} })));\n    VERIFY((a == (Array<Scalar,4,1>({ {raw[0]}, {raw[1]}, {raw[2]}, {raw[3]} }))).all());\n  }\n  {\n    Matrix<Scalar, 1, 4> m { {raw[0], raw[1], raw[2], raw[3]} };\n    Array<Scalar, 1, 4> a { {raw[0], raw[1], raw[2], raw[3]} };\n    for(int k = 0; k < 4; ++k) {\n      VERIFY(m(k) == raw[k]);\n    }\n    for(int k = 0; k < 4; ++k) {\n      VERIFY(a(k) == raw[k]);\n    }\n    VERIFY_IS_EQUAL(m, (Matrix<Scalar, 1, 4>({{raw[0],raw[1],raw[2],raw[3]}})));\n    VERIFY((a == (Array<Scalar, 1, 4>({{raw[0],raw[1],raw[2],raw[3]}}))).all());\n  }\n  {\n    Matrix<Scalar, 4, Dynamic> m { {raw[0]}, {raw[1]}, {raw[2]}, {raw[3]} };\n    Array<Scalar, 4, Dynamic> a { {raw[0]}, {raw[1]}, {raw[2]}, {raw[3]} };\n    for(int k=0; k < 4; ++k) {\n      VERIFY(m(k) == raw[k]);\n    }\n    for(int k=0; k < 4; ++k) {\n      VERIFY(a(k) == raw[k]);\n    }\n    VERIFY_IS_EQUAL(m, (Matrix<Scalar, 4, Dynamic>({ {raw[0]}, {raw[1]}, {raw[2]}, {raw[3]} })));\n    VERIFY((a == (Array<Scalar, 4, Dynamic>({ {raw[0]}, {raw[1]}, {raw[2]}, {raw[3]} }))).all());\n  }\n  {\n    Matrix<Scalar, Dynamic, 4> m {{raw[0],raw[1],raw[2],raw[3]}};\n    Array<Scalar, Dynamic, 4> a {{raw[0],raw[1],raw[2],raw[3]}};\n    for(int k=0; k < 4; ++k) {\n      VERIFY(m(k) == raw[k]);\n    }\n    for(int k=0; k < 4; ++k) {\n      VERIFY(a(k) == raw[k]);\n    }\n    VERIFY_IS_EQUAL(m, (Matrix<Scalar, Dynamic, 4>({{raw[0],raw[1],raw[2],raw[3]}})));\n    VERIFY((a == (Array<Scalar, Dynamic, 4>({{raw[0],raw[1],raw[2],raw[3]}}))).all());\n  }\n}\n\ntemplate<typename Scalar> void initializerListMatrixConstruction()\n{\n  const Index RowsAtCompileTime = 5;\n  const Index ColsAtCompileTime = 4;\n  const Index SizeAtCompileTime = RowsAtCompileTime * ColsAtCompileTime;\n\n  Scalar raw[SizeAtCompileTime];\n  for (int i = 0; i < SizeAtCompileTime; ++i) {\n    raw[i] = internal::random<Scalar>();\n  }\n  {\n    Matrix<Scalar, Dynamic, Dynamic> m {};\n    VERIFY(m.cols() == 0);\n    VERIFY(m.rows() == 0);\n    VERIFY_IS_EQUAL(m, (Matrix<Scalar, Dynamic, Dynamic>()));\n  }\n  {\n    Matrix<Scalar, 5, 4> m {\n      {raw[0], raw[1], raw[2], raw[3]},\n      {raw[4], raw[5], raw[6], raw[7]},\n      {raw[8], raw[9], raw[10], raw[11]},\n      {raw[12], raw[13], raw[14], raw[15]},\n      {raw[16], raw[17], raw[18], raw[19]}\n    };\n\n    Matrix<Scalar, 5, 4> m2;\n    m2 << raw[0], raw[1], raw[2], raw[3],\n          raw[4], raw[5], raw[6], raw[7],\n          raw[8], raw[9], raw[10], raw[11],\n          raw[12], raw[13], raw[14], raw[15],\n          raw[16], raw[17], raw[18], raw[19];\n\n    int k = 0;\n    for(int i = 0; i < RowsAtCompileTime; ++i) {\n      for (int j = 0; j < ColsAtCompileTime; ++j) {\n        VERIFY(m(i, j) == raw[k]);\n        ++k;\n      }\n    }\n    VERIFY_IS_EQUAL(m, m2);\n  }\n  {\n    Matrix<Scalar, Dynamic, Dynamic> m{\n      {raw[0], raw[1], raw[2], raw[3]},\n      {raw[4], raw[5], raw[6], raw[7]},\n      {raw[8], raw[9], raw[10], raw[11]},\n      {raw[12], raw[13], raw[14], raw[15]},\n      {raw[16], raw[17], raw[18], raw[19]}\n    };\n\n    VERIFY(m.cols() == 4);\n    VERIFY(m.rows() == 5);\n    int k = 0;\n    for(int i = 0; i < RowsAtCompileTime; ++i) {\n      for (int j = 0; j < ColsAtCompileTime; ++j) {\n        VERIFY(m(i, j) == raw[k]);\n        ++k;\n      }\n    }\n\n    Matrix<Scalar, Dynamic, Dynamic> m2(RowsAtCompileTime, ColsAtCompileTime);\n    k = 0;\n    for(int i = 0; i < RowsAtCompileTime; ++i) {\n      for (int j = 0; j < ColsAtCompileTime; ++j) {\n        m2(i, j) = raw[k];\n        ++k;\n      }\n    }\n    VERIFY_IS_EQUAL(m, m2);\n  }\n}\n\ntemplate<typename Scalar> void initializerListArrayConstruction()\n{\n  const Index RowsAtCompileTime = 5;\n  const Index ColsAtCompileTime = 4;\n  const Index SizeAtCompileTime = RowsAtCompileTime * ColsAtCompileTime;\n\n  Scalar raw[SizeAtCompileTime];\n  for (int i = 0; i < SizeAtCompileTime; ++i) {\n    raw[i] = internal::random<Scalar>();\n  }\n  {\n    Array<Scalar, Dynamic, Dynamic> a {};\n    VERIFY(a.cols() == 0);\n    VERIFY(a.rows() == 0);\n  }\n  {\n    Array<Scalar, 5, 4> m {\n      {raw[0], raw[1], raw[2], raw[3]},\n      {raw[4], raw[5], raw[6], raw[7]},\n      {raw[8], raw[9], raw[10], raw[11]},\n      {raw[12], raw[13], raw[14], raw[15]},\n      {raw[16], raw[17], raw[18], raw[19]}\n    };\n\n    Array<Scalar, 5, 4> m2;\n    m2 << raw[0], raw[1], raw[2], raw[3],\n          raw[4], raw[5], raw[6], raw[7],\n          raw[8], raw[9], raw[10], raw[11],\n          raw[12], raw[13], raw[14], raw[15],\n          raw[16], raw[17], raw[18], raw[19];\n\n    int k = 0;\n    for(int i = 0; i < RowsAtCompileTime; ++i) {\n      for (int j = 0; j < ColsAtCompileTime; ++j) {\n        VERIFY(m(i, j) == raw[k]);\n        ++k;\n      }\n    }\n    VERIFY_IS_APPROX(m, m2);\n  }\n  {\n    Array<Scalar, Dynamic, Dynamic> m {\n      {raw[0], raw[1], raw[2], raw[3]},\n      {raw[4], raw[5], raw[6], raw[7]},\n      {raw[8], raw[9], raw[10], raw[11]},\n      {raw[12], raw[13], raw[14], raw[15]},\n      {raw[16], raw[17], raw[18], raw[19]}\n    };\n\n    VERIFY(m.cols() == 4);\n    VERIFY(m.rows() == 5);\n    int k = 0;\n    for(int i = 0; i < RowsAtCompileTime; ++i) {\n      for (int j = 0; j < ColsAtCompileTime; ++j) {\n        VERIFY(m(i, j) == raw[k]);\n        ++k;\n      }\n    }\n\n    Array<Scalar, Dynamic, Dynamic> m2(RowsAtCompileTime, ColsAtCompileTime);\n    k = 0;\n    for(int i = 0; i < RowsAtCompileTime; ++i) {\n      for (int j = 0; j < ColsAtCompileTime; ++j) {\n        m2(i, j) = raw[k];\n        ++k;\n      }\n    }\n    VERIFY_IS_APPROX(m, m2);\n  }\n}\n\ntemplate<typename Scalar> void dynamicVectorConstruction()\n{\n  const Index size = 4;\n  Scalar raw[size];\n  for (int i = 0; i < size; ++i) {\n    raw[i] = internal::random<Scalar>();\n  }\n\n  typedef Matrix<Scalar, Dynamic, 1>  VectorX;\n\n  {\n    VectorX v {{raw[0], raw[1], raw[2], raw[3]}};\n    for (int i = 0; i < size; ++i) {\n      VERIFY(v(i) == raw[i]);\n    }\n    VERIFY(v.rows() == size);\n    VERIFY(v.cols() == 1);\n    VERIFY_IS_EQUAL(v, (VectorX {{raw[0], raw[1], raw[2], raw[3]}}));\n  }\n\n  {\n    VERIFY_RAISES_ASSERT((VectorX {raw[0], raw[1], raw[2], raw[3]}));\n  }\n  {\n    VERIFY_RAISES_ASSERT((VectorX  {\n      {raw[0], raw[1], raw[2], raw[3]},\n      {raw[0], raw[1], raw[2], raw[3]},\n    }));\n  }\n}\n\nEIGEN_DECLARE_TEST(initializer_list_construction)\n{\n  CALL_SUBTEST_1(initializerListVectorConstruction<unsigned char>());\n  CALL_SUBTEST_1(initializerListVectorConstruction<float>());\n  CALL_SUBTEST_1(initializerListVectorConstruction<double>());\n  CALL_SUBTEST_1(initializerListVectorConstruction<int>());\n  CALL_SUBTEST_1(initializerListVectorConstruction<long int>());\n  CALL_SUBTEST_1(initializerListVectorConstruction<std::ptrdiff_t>());\n  CALL_SUBTEST_1(initializerListVectorConstruction<std::complex<double>>());\n  CALL_SUBTEST_1(initializerListVectorConstruction<std::complex<float>>());\n\n  CALL_SUBTEST_2(initializerListMatrixConstruction<unsigned char>());\n  CALL_SUBTEST_2(initializerListMatrixConstruction<float>());\n  CALL_SUBTEST_2(initializerListMatrixConstruction<double>());\n  CALL_SUBTEST_2(initializerListMatrixConstruction<int>());\n  CALL_SUBTEST_2(initializerListMatrixConstruction<long int>());\n  CALL_SUBTEST_2(initializerListMatrixConstruction<std::ptrdiff_t>());\n  CALL_SUBTEST_2(initializerListMatrixConstruction<std::complex<double>>());\n  CALL_SUBTEST_2(initializerListMatrixConstruction<std::complex<float>>());\n\n  CALL_SUBTEST_3(initializerListArrayConstruction<unsigned char>());\n  CALL_SUBTEST_3(initializerListArrayConstruction<float>());\n  CALL_SUBTEST_3(initializerListArrayConstruction<double>());\n  CALL_SUBTEST_3(initializerListArrayConstruction<int>());\n  CALL_SUBTEST_3(initializerListArrayConstruction<long int>());\n  CALL_SUBTEST_3(initializerListArrayConstruction<std::ptrdiff_t>());\n  CALL_SUBTEST_3(initializerListArrayConstruction<std::complex<double>>());\n  CALL_SUBTEST_3(initializerListArrayConstruction<std::complex<float>>());\n\n  CALL_SUBTEST_4(fixedsizeVariadicVectorConstruction<unsigned char>());\n  CALL_SUBTEST_4(fixedsizeVariadicVectorConstruction<float>());\n  CALL_SUBTEST_4(fixedsizeVariadicVectorConstruction<double>());\n  CALL_SUBTEST_4(fixedsizeVariadicVectorConstruction<int>());\n  CALL_SUBTEST_4(fixedsizeVariadicVectorConstruction<long int>());\n  CALL_SUBTEST_4(fixedsizeVariadicVectorConstruction<std::ptrdiff_t>());\n  CALL_SUBTEST_4(fixedsizeVariadicVectorConstruction<std::complex<double>>());\n  CALL_SUBTEST_4(fixedsizeVariadicVectorConstruction<std::complex<float>>());\n  CALL_SUBTEST_4(fixedsizeVariadicVectorConstruction3<0>());\n\n  CALL_SUBTEST_5(TestMethodDispatching<int>::run());\n  CALL_SUBTEST_5(TestMethodDispatching<long int>::run());\n\n  CALL_SUBTEST_6(dynamicVectorConstruction<unsigned char>());\n  CALL_SUBTEST_6(dynamicVectorConstruction<float>());\n  CALL_SUBTEST_6(dynamicVectorConstruction<double>());\n  CALL_SUBTEST_6(dynamicVectorConstruction<int>());\n  CALL_SUBTEST_6(dynamicVectorConstruction<long int>());\n  CALL_SUBTEST_6(dynamicVectorConstruction<std::ptrdiff_t>());\n  CALL_SUBTEST_6(dynamicVectorConstruction<std::complex<double>>());\n  CALL_SUBTEST_6(dynamicVectorConstruction<std::complex<float>>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/inplace_decomposition.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/LU>\n#include <Eigen/Cholesky>\n#include <Eigen/QR>\n\n// This file test inplace decomposition through Ref<>, as supported by Cholesky, LU, and QR decompositions.\n\ntemplate<typename DecType,typename MatrixType> void inplace(bool square = false, bool SPD = false)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> RhsType;\n  typedef Matrix<Scalar, MatrixType::ColsAtCompileTime, 1> ResType;\n\n  Index rows = MatrixType::RowsAtCompileTime==Dynamic ? internal::random<Index>(2,EIGEN_TEST_MAX_SIZE/2) : Index(MatrixType::RowsAtCompileTime);\n  Index cols = MatrixType::ColsAtCompileTime==Dynamic ? (square?rows:internal::random<Index>(2,rows))    : Index(MatrixType::ColsAtCompileTime);\n\n  MatrixType A = MatrixType::Random(rows,cols);\n  RhsType b = RhsType::Random(rows);\n  ResType x(cols);\n\n  if(SPD)\n  {\n    assert(square);\n    A.topRows(cols) = A.topRows(cols).adjoint() * A.topRows(cols);\n    A.diagonal().array() += 1e-3;\n  }\n\n  MatrixType A0 = A;\n  MatrixType A1 = A;\n\n  DecType dec(A);\n\n  // Check that the content of A has been modified\n  VERIFY_IS_NOT_APPROX( A, A0 );\n\n  // Check that the decomposition is correct:\n  if(rows==cols)\n  {\n    VERIFY_IS_APPROX( A0 * (x = dec.solve(b)), b );\n  }\n  else\n  {\n    VERIFY_IS_APPROX( A0.transpose() * A0 * (x = dec.solve(b)), A0.transpose() * b );\n  }\n\n  // Check that modifying A breaks the current dec:\n  A.setRandom();\n  if(rows==cols)\n  {\n    VERIFY_IS_NOT_APPROX( A0 * (x = dec.solve(b)), b );\n  }\n  else\n  {\n    VERIFY_IS_NOT_APPROX( A0.transpose() * A0 * (x = dec.solve(b)), A0.transpose() * b );\n  }\n\n  // Check that calling compute(A1) does not modify A1:\n  A = A0;\n  dec.compute(A1);\n  VERIFY_IS_EQUAL(A0,A1);\n  VERIFY_IS_NOT_APPROX( A, A0 );\n  if(rows==cols)\n  {\n    VERIFY_IS_APPROX( A0 * (x = dec.solve(b)), b );\n  }\n  else\n  {\n    VERIFY_IS_APPROX( A0.transpose() * A0 * (x = dec.solve(b)), A0.transpose() * b );\n  }\n}\n\n\nEIGEN_DECLARE_TEST(inplace_decomposition)\n{\n  EIGEN_UNUSED typedef Matrix<double,4,3> Matrix43d;\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(( inplace<LLT<Ref<MatrixXd> >, MatrixXd>(true,true) ));\n    CALL_SUBTEST_1(( inplace<LLT<Ref<Matrix4d> >, Matrix4d>(true,true) ));\n\n    CALL_SUBTEST_2(( inplace<LDLT<Ref<MatrixXd> >, MatrixXd>(true,true) ));\n    CALL_SUBTEST_2(( inplace<LDLT<Ref<Matrix4d> >, Matrix4d>(true,true) ));\n\n    CALL_SUBTEST_3(( inplace<PartialPivLU<Ref<MatrixXd> >, MatrixXd>(true,false) ));\n    CALL_SUBTEST_3(( inplace<PartialPivLU<Ref<Matrix4d> >, Matrix4d>(true,false) ));\n\n    CALL_SUBTEST_4(( inplace<FullPivLU<Ref<MatrixXd> >, MatrixXd>(true,false) ));\n    CALL_SUBTEST_4(( inplace<FullPivLU<Ref<Matrix4d> >, Matrix4d>(true,false) ));\n\n    CALL_SUBTEST_5(( inplace<HouseholderQR<Ref<MatrixXd> >, MatrixXd>(false,false) ));\n    CALL_SUBTEST_5(( inplace<HouseholderQR<Ref<Matrix43d> >, Matrix43d>(false,false) ));\n\n    CALL_SUBTEST_6(( inplace<ColPivHouseholderQR<Ref<MatrixXd> >, MatrixXd>(false,false) ));\n    CALL_SUBTEST_6(( inplace<ColPivHouseholderQR<Ref<Matrix43d> >, Matrix43d>(false,false) ));\n\n    CALL_SUBTEST_7(( inplace<FullPivHouseholderQR<Ref<MatrixXd> >, MatrixXd>(false,false) ));\n    CALL_SUBTEST_7(( inplace<FullPivHouseholderQR<Ref<Matrix43d> >, Matrix43d>(false,false) ));\n\n    CALL_SUBTEST_8(( inplace<CompleteOrthogonalDecomposition<Ref<MatrixXd> >, MatrixXd>(false,false) ));\n    CALL_SUBTEST_8(( inplace<CompleteOrthogonalDecomposition<Ref<Matrix43d> >, Matrix43d>(false,false) ));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/integer_types.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_STATIC_ASSERT\n\n#include \"main.h\"\n\n#undef VERIFY_IS_APPROX\n#define VERIFY_IS_APPROX(a, b) VERIFY((a)==(b));\n#undef VERIFY_IS_NOT_APPROX\n#define VERIFY_IS_NOT_APPROX(a, b) VERIFY((a)!=(b));\n\ntemplate<typename MatrixType> void signed_integer_type_tests(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  enum { is_signed = (Scalar(-1) > Scalar(0)) ? 0 : 1 };\n  VERIFY(is_signed == 1);\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             mzero = MatrixType::Zero(rows, cols);\n\n  do {\n    m1 = MatrixType::Random(rows, cols);\n  } while(m1 == mzero || m1 == m2);\n\n  // check linear structure\n\n  Scalar s1;\n  do {\n    s1 = internal::random<Scalar>();\n  } while(s1 == 0);\n\n  VERIFY_IS_EQUAL(-(-m1),                  m1);\n  VERIFY_IS_EQUAL(-m2+m1+m2,               m1);\n  VERIFY_IS_EQUAL((-m1+m2)*s1,             -s1*m1+s1*m2);\n}\n\ntemplate<typename MatrixType> void integer_type_tests(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  VERIFY(NumTraits<Scalar>::IsInteger);\n  enum { is_signed = (Scalar(-1) > Scalar(0)) ? 0 : 1 };\n  VERIFY(int(NumTraits<Scalar>::IsSigned) == is_signed);\n\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  // this test relies a lot on Random.h, and there's not much more that we can do\n  // to test it, hence I consider that we will have tested Random.h\n  MatrixType m1(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols),\n             mzero = MatrixType::Zero(rows, cols);\n\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> SquareMatrixType;\n  SquareMatrixType identity = SquareMatrixType::Identity(rows, rows),\n                   square = SquareMatrixType::Random(rows, rows);\n  VectorType v1(rows),\n             v2 = VectorType::Random(rows),\n             vzero = VectorType::Zero(rows);\n\n  do {\n    m1 = MatrixType::Random(rows, cols);\n  } while(m1 == mzero || m1 == m2);\n\n  do {\n    v1 = VectorType::Random(rows);\n  } while(v1 == vzero || v1 == v2);\n\n  VERIFY_IS_APPROX(               v1,    v1);\n  VERIFY_IS_NOT_APPROX(           v1,    2*v1);\n  VERIFY_IS_APPROX(               vzero, v1-v1);\n  VERIFY_IS_APPROX(               m1,    m1);\n  VERIFY_IS_NOT_APPROX(           m1,    2*m1);\n  VERIFY_IS_APPROX(               mzero, m1-m1);\n\n  VERIFY_IS_APPROX(m3 = m1,m1);\n  MatrixType m4;\n  VERIFY_IS_APPROX(m4 = m1,m1);\n\n  m3.real() = m1.real();\n  VERIFY_IS_APPROX(static_cast<const MatrixType&>(m3).real(), static_cast<const MatrixType&>(m1).real());\n  VERIFY_IS_APPROX(static_cast<const MatrixType&>(m3).real(), m1.real());\n\n  // check == / != operators\n  VERIFY(m1==m1);\n  VERIFY(m1!=m2);\n  VERIFY(!(m1==m2));\n  VERIFY(!(m1!=m1));\n  m1 = m2;\n  VERIFY(m1==m2);\n  VERIFY(!(m1!=m2));\n\n  // check linear structure\n\n  Scalar s1;\n  do {\n    s1 = internal::random<Scalar>();\n  } while(s1 == 0);\n\n  VERIFY_IS_EQUAL(m1+m1,                   2*m1);\n  VERIFY_IS_EQUAL(m1+m2-m1,                m2);\n  VERIFY_IS_EQUAL(m1*s1,                   s1*m1);\n  VERIFY_IS_EQUAL((m1+m2)*s1,              s1*m1+s1*m2);\n  m3 = m2; m3 += m1;\n  VERIFY_IS_EQUAL(m3,                      m1+m2);\n  m3 = m2; m3 -= m1;\n  VERIFY_IS_EQUAL(m3,                      m2-m1);\n  m3 = m2; m3 *= s1;\n  VERIFY_IS_EQUAL(m3,                      s1*m2);\n\n  // check matrix product.\n\n  VERIFY_IS_APPROX(identity * m1, m1);\n  VERIFY_IS_APPROX(square * (m1 + m2), square * m1 + square * m2);\n  VERIFY_IS_APPROX((m1 + m2).transpose() * square, m1.transpose() * square + m2.transpose() * square);\n  VERIFY_IS_APPROX((m1 * m2.transpose()) * m1, m1 * (m2.transpose() * m1));\n}\n\ntemplate<int>\nvoid integer_types_extra()\n{\n  VERIFY_IS_EQUAL(int(internal::scalar_div_cost<int>::value), 8);\n  VERIFY_IS_EQUAL(int(internal::scalar_div_cost<unsigned int>::value), 8);\n  if(sizeof(long)>sizeof(int)) {\n    VERIFY(int(internal::scalar_div_cost<long>::value) > int(internal::scalar_div_cost<int>::value));\n    VERIFY(int(internal::scalar_div_cost<unsigned long>::value) > int(internal::scalar_div_cost<int>::value));\n  }\n}\n\nEIGEN_DECLARE_TEST(integer_types)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( integer_type_tests(Matrix<unsigned int, 1, 1>()) );\n    CALL_SUBTEST_1( integer_type_tests(Matrix<unsigned long, 3, 4>()) );\n\n    CALL_SUBTEST_2( integer_type_tests(Matrix<long, 2, 2>()) );\n    CALL_SUBTEST_2( signed_integer_type_tests(Matrix<long, 2, 2>()) );\n\n    CALL_SUBTEST_3( integer_type_tests(Matrix<char, 2, Dynamic>(2, 10)) );\n    CALL_SUBTEST_3( signed_integer_type_tests(Matrix<signed char, 2, Dynamic>(2, 10)) );\n\n    CALL_SUBTEST_4( integer_type_tests(Matrix<unsigned char, 3, 3>()) );\n    CALL_SUBTEST_4( integer_type_tests(Matrix<unsigned char, Dynamic, Dynamic>(20, 20)) );\n\n    CALL_SUBTEST_5( integer_type_tests(Matrix<short, Dynamic, 4>(7, 4)) );\n    CALL_SUBTEST_5( signed_integer_type_tests(Matrix<short, Dynamic, 4>(7, 4)) );\n\n    CALL_SUBTEST_6( integer_type_tests(Matrix<unsigned short, 4, 4>()) );\n\n#if EIGEN_HAS_CXX11\n    CALL_SUBTEST_7( integer_type_tests(Matrix<long long, 11, 13>()) );\n    CALL_SUBTEST_7( signed_integer_type_tests(Matrix<long long, 11, 13>()) );\n\n    CALL_SUBTEST_8( integer_type_tests(Matrix<unsigned long long, Dynamic, 5>(1, 5)) );\n#endif\n  }\n  CALL_SUBTEST_9( integer_types_extra<0>() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/inverse.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/LU>\n\ntemplate<typename MatrixType>\nvoid inverse_for_fixed_size(const MatrixType&, typename internal::enable_if<MatrixType::SizeAtCompileTime==Dynamic>::type* = 0)\n{\n}\n\ntemplate<typename MatrixType>\nvoid inverse_for_fixed_size(const MatrixType& m1, typename internal::enable_if<MatrixType::SizeAtCompileTime!=Dynamic>::type* = 0)\n{\n  using std::abs;\n\n  MatrixType m2, identity = MatrixType::Identity();\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar, MatrixType::ColsAtCompileTime, 1> VectorType;\n  \n  //computeInverseAndDetWithCheck tests\n  //First: an invertible matrix\n  bool invertible;\n  Scalar det;\n\n  m2.setZero();\n  m1.computeInverseAndDetWithCheck(m2, det, invertible);\n  VERIFY(invertible);\n  VERIFY_IS_APPROX(identity, m1*m2);\n  VERIFY_IS_APPROX(det, m1.determinant());\n\n  m2.setZero();\n  m1.computeInverseWithCheck(m2, invertible);\n  VERIFY(invertible);\n  VERIFY_IS_APPROX(identity, m1*m2);\n\n  //Second: a rank one matrix (not invertible, except for 1x1 matrices)\n  VectorType v3 = VectorType::Random();\n  MatrixType m3 = v3*v3.transpose(), m4;\n  m3.computeInverseAndDetWithCheck(m4, det, invertible);\n  VERIFY( m1.rows()==1 ? invertible : !invertible );\n  VERIFY_IS_MUCH_SMALLER_THAN(abs(det-m3.determinant()), RealScalar(1));\n  m3.computeInverseWithCheck(m4, invertible);\n  VERIFY( m1.rows()==1 ? invertible : !invertible );\n  \n  // check with submatrices\n  {\n    Matrix<Scalar, MatrixType::RowsAtCompileTime+1, MatrixType::RowsAtCompileTime+1, MatrixType::Options> m5;\n    m5.setRandom();\n    m5.topLeftCorner(m1.rows(),m1.rows()) = m1;\n    m2 = m5.template topLeftCorner<MatrixType::RowsAtCompileTime,MatrixType::ColsAtCompileTime>().inverse();\n    VERIFY_IS_APPROX( (m5.template topLeftCorner<MatrixType::RowsAtCompileTime,MatrixType::ColsAtCompileTime>()), m2.inverse() );\n  }\n}\n\ntemplate<typename MatrixType> void inverse(const MatrixType& m)\n{\n  /* this test covers the following files:\n     Inverse.h\n  */\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  typedef typename MatrixType::Scalar Scalar;\n\n  MatrixType m1(rows, cols),\n             m2(rows, cols),\n             identity = MatrixType::Identity(rows, rows);\n  createRandomPIMatrixOfRank(rows,rows,rows,m1);\n  m2 = m1.inverse();\n  VERIFY_IS_APPROX(m1, m2.inverse() );\n\n  VERIFY_IS_APPROX((Scalar(2)*m2).inverse(), m2.inverse()*Scalar(0.5));\n\n  VERIFY_IS_APPROX(identity, m1.inverse() * m1 );\n  VERIFY_IS_APPROX(identity, m1 * m1.inverse() );\n\n  VERIFY_IS_APPROX(m1, m1.inverse().inverse() );\n\n  // since for the general case we implement separately row-major and col-major, test that\n  VERIFY_IS_APPROX(MatrixType(m1.transpose().inverse()), MatrixType(m1.inverse().transpose()));\n\n  inverse_for_fixed_size(m1);\n\n  // check in-place inversion\n  if(MatrixType::RowsAtCompileTime>=2 && MatrixType::RowsAtCompileTime<=4)\n  {\n    // in-place is forbidden\n    VERIFY_RAISES_ASSERT(m1 = m1.inverse());\n  }\n  else\n  {\n    m2 = m1.inverse();\n    m1 = m1.inverse();\n    VERIFY_IS_APPROX(m1,m2);\n  }\n}\n\ntemplate<typename Scalar>\nvoid inverse_zerosized()\n{\n  Matrix<Scalar,Dynamic,Dynamic> A(0,0);\n  {\n    Matrix<Scalar,0,1> b, x;\n    x = A.inverse() * b;\n  }\n  {\n    Matrix<Scalar,Dynamic,Dynamic> b(0,1), x;\n    x = A.inverse() * b;\n    VERIFY_IS_EQUAL(x.rows(), 0);\n    VERIFY_IS_EQUAL(x.cols(), 1);\n  }\n}\n\nEIGEN_DECLARE_TEST(inverse)\n{\n  int s = 0;\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( inverse(Matrix<double,1,1>()) );\n    CALL_SUBTEST_2( inverse(Matrix2d()) );\n    CALL_SUBTEST_3( inverse(Matrix3f()) );\n    CALL_SUBTEST_4( inverse(Matrix4f()) );\n    CALL_SUBTEST_4( inverse(Matrix<float,4,4,DontAlign>()) );\n    \n    s = internal::random<int>(50,320); \n    CALL_SUBTEST_5( inverse(MatrixXf(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n    CALL_SUBTEST_5( inverse_zerosized<float>() );\n    CALL_SUBTEST_5( inverse(MatrixXf(0, 0)) );\n    CALL_SUBTEST_5( inverse(MatrixXf(1, 1)) );\n    \n    s = internal::random<int>(25,100);\n    CALL_SUBTEST_6( inverse(MatrixXcd(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n    \n    CALL_SUBTEST_7( inverse(Matrix4d()) );\n    CALL_SUBTEST_7( inverse(Matrix<double,4,4,DontAlign>()) );\n\n    CALL_SUBTEST_8( inverse(Matrix4cd()) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/io.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2019 Joel Holdsworth <joel.holdsworth@vcatechnology.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <sstream>\n\n#include \"main.h\"\n\ntemplate<typename Scalar>\nstruct check_ostream_impl\n{\n  static void run()\n  {\n    const Array<Scalar,1,1> array(123);\n    std::ostringstream ss;\n    ss << array;\n    VERIFY(ss.str() == \"123\");\n\n    check_ostream_impl< std::complex<Scalar> >::run();\n  };\n};\n\ntemplate<>\nstruct check_ostream_impl<bool>\n{\n  static void run()\n  {\n    const Array<bool,1,2> array(1, 0);\n    std::ostringstream ss;\n    ss << array;\n    VERIFY(ss.str() == \"1  0\");\n  };\n};\n\ntemplate<typename Scalar>\nstruct check_ostream_impl< std::complex<Scalar> >\n{\n  static void run()\n  {\n    const Array<std::complex<Scalar>,1,1> array(std::complex<Scalar>(12, 34));\n    std::ostringstream ss;\n    ss << array;\n    VERIFY(ss.str() == \"(12,34)\");\n  };\n};\n\ntemplate<typename Scalar>\nstatic void check_ostream()\n{\n  check_ostream_impl<Scalar>::run();\n}\n\nEIGEN_DECLARE_TEST(rand)\n{\n  CALL_SUBTEST(check_ostream<bool>());\n  CALL_SUBTEST(check_ostream<float>());\n  CALL_SUBTEST(check_ostream<double>());\n  CALL_SUBTEST(check_ostream<Eigen::numext::int8_t>());\n  CALL_SUBTEST(check_ostream<Eigen::numext::uint8_t>());\n  CALL_SUBTEST(check_ostream<Eigen::numext::int16_t>());\n  CALL_SUBTEST(check_ostream<Eigen::numext::uint16_t>());\n  CALL_SUBTEST(check_ostream<Eigen::numext::int32_t>());\n  CALL_SUBTEST(check_ostream<Eigen::numext::uint32_t>());\n  CALL_SUBTEST(check_ostream<Eigen::numext::int64_t>());\n  CALL_SUBTEST(check_ostream<Eigen::numext::uint64_t>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/is_same_dense.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\nusing internal::is_same_dense;\n\nEIGEN_DECLARE_TEST(is_same_dense)\n{\n  typedef Matrix<double,Dynamic,Dynamic,ColMajor> ColMatrixXd;\n  typedef Matrix<std::complex<double>,Dynamic,Dynamic,ColMajor> ColMatrixXcd;\n  ColMatrixXd m1(10,10);\n  ColMatrixXcd m2(10,10);\n  Ref<ColMatrixXd> ref_m1(m1);\n  Ref<ColMatrixXd,0, Stride<Dynamic,Dynamic> >  ref_m2_real(m2.real());\n  Ref<const ColMatrixXd> const_ref_m1(m1);\n\n  VERIFY(is_same_dense(m1,m1));\n  VERIFY(is_same_dense(m1,ref_m1));\n  VERIFY(is_same_dense(const_ref_m1,m1));\n  VERIFY(is_same_dense(const_ref_m1,ref_m1));\n  \n  VERIFY(is_same_dense(m1.block(0,0,m1.rows(),m1.cols()),m1));\n  VERIFY(!is_same_dense(m1.row(0),m1.col(0)));\n  \n  Ref<const ColMatrixXd> const_ref_m1_row(m1.row(1));\n  VERIFY(!is_same_dense(m1.row(1),const_ref_m1_row));\n  \n  Ref<const ColMatrixXd> const_ref_m1_col(m1.col(1));\n  VERIFY(is_same_dense(m1.col(1),const_ref_m1_col));\n\n\n  VERIFY(!is_same_dense(m1, ref_m2_real));\n  VERIFY(!is_same_dense(m2, ref_m2_real));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/jacobi.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/SVD>\n\ntemplate<typename MatrixType, typename JacobiScalar>\nvoid jacobi(const MatrixType& m = MatrixType())\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  enum {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime\n  };\n\n  typedef Matrix<JacobiScalar, 2, 1> JacobiVector;\n\n  const MatrixType a(MatrixType::Random(rows, cols));\n\n  JacobiVector v = JacobiVector::Random().normalized();\n  JacobiScalar c = v.x(), s = v.y();\n  JacobiRotation<JacobiScalar> rot(c, s);\n\n  {\n    Index p = internal::random<Index>(0, rows-1);\n    Index q;\n    do {\n      q = internal::random<Index>(0, rows-1);\n    } while (q == p);\n\n    MatrixType b = a;\n    b.applyOnTheLeft(p, q, rot);\n    VERIFY_IS_APPROX(b.row(p), c * a.row(p) + numext::conj(s) * a.row(q));\n    VERIFY_IS_APPROX(b.row(q), -s * a.row(p) + numext::conj(c) * a.row(q));\n  }\n\n  {\n    Index p = internal::random<Index>(0, cols-1);\n    Index q;\n    do {\n      q = internal::random<Index>(0, cols-1);\n    } while (q == p);\n\n    MatrixType b = a;\n    b.applyOnTheRight(p, q, rot);\n    VERIFY_IS_APPROX(b.col(p), c * a.col(p) - s * a.col(q));\n    VERIFY_IS_APPROX(b.col(q), numext::conj(s) * a.col(p) + numext::conj(c) * a.col(q));\n  }\n}\n\nEIGEN_DECLARE_TEST(jacobi)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(( jacobi<Matrix3f, float>() ));\n    CALL_SUBTEST_2(( jacobi<Matrix4d, double>() ));\n    CALL_SUBTEST_3(( jacobi<Matrix4cf, float>() ));\n    CALL_SUBTEST_3(( jacobi<Matrix4cf, std::complex<float> >() ));\n\n    int r = internal::random<int>(2, internal::random<int>(1,EIGEN_TEST_MAX_SIZE)/2),\n        c = internal::random<int>(2, internal::random<int>(1,EIGEN_TEST_MAX_SIZE)/2);\n    CALL_SUBTEST_4(( jacobi<MatrixXf, float>(MatrixXf(r,c)) ));\n    CALL_SUBTEST_5(( jacobi<MatrixXcd, double>(MatrixXcd(r,c)) ));\n    CALL_SUBTEST_5(( jacobi<MatrixXcd, std::complex<double> >(MatrixXcd(r,c)) ));\n    // complex<float> is really important to test as it is the only way to cover conjugation issues in certain unaligned paths\n    CALL_SUBTEST_6(( jacobi<MatrixXcf, float>(MatrixXcf(r,c)) ));\n    CALL_SUBTEST_6(( jacobi<MatrixXcf, std::complex<float> >(MatrixXcf(r,c)) ));\n    \n    TEST_SET_BUT_UNUSED_VARIABLE(r);\n    TEST_SET_BUT_UNUSED_VARIABLE(c);\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/jacobisvd.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// discard stack allocation as that too bypasses malloc\n#define EIGEN_STACK_ALLOCATION_LIMIT 0\n#define EIGEN_RUNTIME_NO_MALLOC\n#include \"main.h\"\n#include <Eigen/SVD>\n\n#define SVD_DEFAULT(M) JacobiSVD<M>\n#define SVD_FOR_MIN_NORM(M) JacobiSVD<M,ColPivHouseholderQRPreconditioner>\n#include \"svd_common.h\"\n\n// Check all variants of JacobiSVD\ntemplate<typename MatrixType>\nvoid jacobisvd(const MatrixType& a = MatrixType(), bool pickrandom = true)\n{\n  MatrixType m = a;\n  if(pickrandom)\n    svd_fill_random(m);\n\n  CALL_SUBTEST(( svd_test_all_computation_options<JacobiSVD<MatrixType, FullPivHouseholderQRPreconditioner> >(m, true)  )); // check full only\n  CALL_SUBTEST(( svd_test_all_computation_options<JacobiSVD<MatrixType, ColPivHouseholderQRPreconditioner>  >(m, false) ));\n  CALL_SUBTEST(( svd_test_all_computation_options<JacobiSVD<MatrixType, HouseholderQRPreconditioner>        >(m, false) ));\n  if(m.rows()==m.cols())\n    CALL_SUBTEST(( svd_test_all_computation_options<JacobiSVD<MatrixType, NoQRPreconditioner>               >(m, false) ));\n}\n\ntemplate<typename MatrixType> void jacobisvd_verify_assert(const MatrixType& m)\n{\n  svd_verify_assert<JacobiSVD<MatrixType> >(m);\n  svd_verify_assert<JacobiSVD<MatrixType, FullPivHouseholderQRPreconditioner> >(m, true);\n  svd_verify_assert<JacobiSVD<MatrixType, ColPivHouseholderQRPreconditioner> >(m);\n  svd_verify_assert<JacobiSVD<MatrixType, HouseholderQRPreconditioner> >(m);\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  enum {\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime\n  };\n\n\n  MatrixType a = MatrixType::Zero(rows, cols);\n  a.setZero();\n\n  if (ColsAtCompileTime == Dynamic)\n  {\n    JacobiSVD<MatrixType, FullPivHouseholderQRPreconditioner> svd_fullqr;\n    VERIFY_RAISES_ASSERT(svd_fullqr.compute(a, ComputeFullU|ComputeThinV))\n    VERIFY_RAISES_ASSERT(svd_fullqr.compute(a, ComputeThinU|ComputeThinV))\n    VERIFY_RAISES_ASSERT(svd_fullqr.compute(a, ComputeThinU|ComputeFullV))\n  }\n}\n\ntemplate<typename MatrixType>\nvoid jacobisvd_method()\n{\n  enum { Size = MatrixType::RowsAtCompileTime };\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef Matrix<RealScalar, Size, 1> RealVecType;\n  MatrixType m = MatrixType::Identity();\n  VERIFY_IS_APPROX(m.jacobiSvd().singularValues(), RealVecType::Ones());\n  VERIFY_RAISES_ASSERT(m.jacobiSvd().matrixU());\n  VERIFY_RAISES_ASSERT(m.jacobiSvd().matrixV());\n  VERIFY_IS_APPROX(m.jacobiSvd(ComputeFullU|ComputeFullV).solve(m), m);\n  VERIFY_IS_APPROX(m.jacobiSvd(ComputeFullU|ComputeFullV).transpose().solve(m), m);\n  VERIFY_IS_APPROX(m.jacobiSvd(ComputeFullU|ComputeFullV).adjoint().solve(m), m);\n}\n\nnamespace Foo {\n// older compiler require a default constructor for Bar\n// cf: https://stackoverflow.com/questions/7411515/\nclass Bar {public: Bar() {}};\nbool operator<(const Bar&, const Bar&) { return true; }\n}\n// regression test for a very strange MSVC issue for which simply\n// including SVDBase.h messes up with std::max and custom scalar type\nvoid msvc_workaround()\n{\n  const Foo::Bar a;\n  const Foo::Bar b;\n  std::max EIGEN_NOT_A_MACRO (a,b);\n}\n\nEIGEN_DECLARE_TEST(jacobisvd)\n{\n  CALL_SUBTEST_3(( jacobisvd_verify_assert(Matrix3f()) ));\n  CALL_SUBTEST_4(( jacobisvd_verify_assert(Matrix4d()) ));\n  CALL_SUBTEST_7(( jacobisvd_verify_assert(MatrixXf(10,12)) ));\n  CALL_SUBTEST_8(( jacobisvd_verify_assert(MatrixXcd(7,5)) ));\n  \n  CALL_SUBTEST_11(svd_all_trivial_2x2(jacobisvd<Matrix2cd>));\n  CALL_SUBTEST_12(svd_all_trivial_2x2(jacobisvd<Matrix2d>));\n\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_3(( jacobisvd<Matrix3f>() ));\n    CALL_SUBTEST_4(( jacobisvd<Matrix4d>() ));\n    CALL_SUBTEST_5(( jacobisvd<Matrix<float,3,5> >() ));\n    CALL_SUBTEST_6(( jacobisvd<Matrix<double,Dynamic,2> >(Matrix<double,Dynamic,2>(10,2)) ));\n\n    int r = internal::random<int>(1, 30),\n        c = internal::random<int>(1, 30);\n    \n    TEST_SET_BUT_UNUSED_VARIABLE(r)\n    TEST_SET_BUT_UNUSED_VARIABLE(c)\n    \n    CALL_SUBTEST_10(( jacobisvd<MatrixXd>(MatrixXd(r,c)) ));\n    CALL_SUBTEST_7(( jacobisvd<MatrixXf>(MatrixXf(r,c)) ));\n    CALL_SUBTEST_8(( jacobisvd<MatrixXcd>(MatrixXcd(r,c)) ));\n    (void) r;\n    (void) c;\n\n    // Test on inf/nan matrix\n    CALL_SUBTEST_7(  (svd_inf_nan<JacobiSVD<MatrixXf>, MatrixXf>()) );\n    CALL_SUBTEST_10( (svd_inf_nan<JacobiSVD<MatrixXd>, MatrixXd>()) );\n\n    // bug1395 test compile-time vectors as input\n    CALL_SUBTEST_13(( jacobisvd_verify_assert(Matrix<double,6,1>()) ));\n    CALL_SUBTEST_13(( jacobisvd_verify_assert(Matrix<double,1,6>()) ));\n    CALL_SUBTEST_13(( jacobisvd_verify_assert(Matrix<double,Dynamic,1>(r)) ));\n    CALL_SUBTEST_13(( jacobisvd_verify_assert(Matrix<double,1,Dynamic>(c)) ));\n  }\n\n  CALL_SUBTEST_7(( jacobisvd<MatrixXf>(MatrixXf(internal::random<int>(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/2), internal::random<int>(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/2))) ));\n  CALL_SUBTEST_8(( jacobisvd<MatrixXcd>(MatrixXcd(internal::random<int>(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/3), internal::random<int>(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/3))) ));\n\n  // test matrixbase method\n  CALL_SUBTEST_1(( jacobisvd_method<Matrix2cd>() ));\n  CALL_SUBTEST_3(( jacobisvd_method<Matrix3f>() ));\n\n  // Test problem size constructors\n  CALL_SUBTEST_7( JacobiSVD<MatrixXf>(10,10) );\n\n  // Check that preallocation avoids subsequent mallocs\n  CALL_SUBTEST_9( svd_preallocate<void>() );\n\n  CALL_SUBTEST_2( svd_underoverflow<void>() );\n\n  msvc_workaround();\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/klu_support.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS\n#include \"sparse_solver.h\"\n\n#include <Eigen/KLUSupport>\n\ntemplate<typename T> void test_klu_support_T()\n{\n  KLU<SparseMatrix<T, ColMajor> > klu_colmajor;\n  KLU<SparseMatrix<T, RowMajor> > klu_rowmajor;\n  \n  check_sparse_square_solving(klu_colmajor);\n  check_sparse_square_solving(klu_rowmajor);\n  \n  //check_sparse_square_determinant(umfpack_colmajor);\n  //check_sparse_square_determinant(umfpack_rowmajor);\n}\n\nEIGEN_DECLARE_TEST(klu_support)\n{\n  CALL_SUBTEST_1(test_klu_support_T<double>());\n  CALL_SUBTEST_2(test_klu_support_T<std::complex<double> >());\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/linearstructure.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\nstatic bool g_called;\n#define EIGEN_SCALAR_BINARY_OP_PLUGIN { g_called |= (!internal::is_same<LhsScalar,RhsScalar>::value); }\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void linearStructure(const MatrixType& m)\n{\n  using std::abs;\n  /* this test covers the following files:\n     CwiseUnaryOp.h, CwiseBinaryOp.h, SelfCwiseBinaryOp.h \n  */\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  // this test relies a lot on Random.h, and there's not much more that we can do\n  // to test it, hence I consider that we will have tested Random.h\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols);\n\n  Scalar s1 = internal::random<Scalar>();\n  while (abs(s1)<RealScalar(1e-3)) s1 = internal::random<Scalar>();\n\n  Index r = internal::random<Index>(0, rows-1),\n        c = internal::random<Index>(0, cols-1);\n\n  VERIFY_IS_APPROX(-(-m1),                  m1);\n  VERIFY_IS_APPROX(m1+m1,                   2*m1);\n  VERIFY_IS_APPROX(m1+m2-m1,                m2);\n  VERIFY_IS_APPROX(-m2+m1+m2,               m1);\n  VERIFY_IS_APPROX(m1*s1,                   s1*m1);\n  VERIFY_IS_APPROX((m1+m2)*s1,              s1*m1+s1*m2);\n  VERIFY_IS_APPROX((-m1+m2)*s1,             -s1*m1+s1*m2);\n  m3 = m2; m3 += m1;\n  VERIFY_IS_APPROX(m3,                      m1+m2);\n  m3 = m2; m3 -= m1;\n  VERIFY_IS_APPROX(m3,                      m2-m1);\n  m3 = m2; m3 *= s1;\n  VERIFY_IS_APPROX(m3,                      s1*m2);\n  if(!NumTraits<Scalar>::IsInteger)\n  {\n    m3 = m2; m3 /= s1;\n    VERIFY_IS_APPROX(m3,                    m2/s1);\n  }\n\n  // again, test operator() to check const-qualification\n  VERIFY_IS_APPROX((-m1)(r,c), -(m1(r,c)));\n  VERIFY_IS_APPROX((m1-m2)(r,c), (m1(r,c))-(m2(r,c)));\n  VERIFY_IS_APPROX((m1+m2)(r,c), (m1(r,c))+(m2(r,c)));\n  VERIFY_IS_APPROX((s1*m1)(r,c), s1*(m1(r,c)));\n  VERIFY_IS_APPROX((m1*s1)(r,c), (m1(r,c))*s1);\n  if(!NumTraits<Scalar>::IsInteger)\n    VERIFY_IS_APPROX((m1/s1)(r,c), (m1(r,c))/s1);\n\n  // use .block to disable vectorization and compare to the vectorized version\n  VERIFY_IS_APPROX(m1+m1.block(0,0,rows,cols), m1+m1);\n  VERIFY_IS_APPROX(m1.cwiseProduct(m1.block(0,0,rows,cols)), m1.cwiseProduct(m1));\n  VERIFY_IS_APPROX(m1 - m1.block(0,0,rows,cols), m1 - m1);\n  VERIFY_IS_APPROX(m1.block(0,0,rows,cols) * s1, m1 * s1);\n}\n\n// Make sure that complex * real and real * complex are properly optimized\ntemplate<typename MatrixType> void real_complex(DenseIndex rows = MatrixType::RowsAtCompileTime, DenseIndex cols = MatrixType::ColsAtCompileTime)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  \n  RealScalar s = internal::random<RealScalar>();\n  MatrixType m1 = MatrixType::Random(rows, cols);\n  \n  g_called = false;\n  VERIFY_IS_APPROX(s*m1, Scalar(s)*m1);\n  VERIFY(g_called && \"real * matrix<complex> not properly optimized\");\n  \n  g_called = false;\n  VERIFY_IS_APPROX(m1*s, m1*Scalar(s));\n  VERIFY(g_called && \"matrix<complex> * real not properly optimized\");\n  \n  g_called = false;\n  VERIFY_IS_APPROX(m1/s, m1/Scalar(s));\n  VERIFY(g_called && \"matrix<complex> / real not properly optimized\");\n\n  g_called = false;\n  VERIFY_IS_APPROX(s+m1.array(), Scalar(s)+m1.array());\n  VERIFY(g_called && \"real + matrix<complex> not properly optimized\");\n\n  g_called = false;\n  VERIFY_IS_APPROX(m1.array()+s, m1.array()+Scalar(s));\n  VERIFY(g_called && \"matrix<complex> + real not properly optimized\");\n\n  g_called = false;\n  VERIFY_IS_APPROX(s-m1.array(), Scalar(s)-m1.array());\n  VERIFY(g_called && \"real - matrix<complex> not properly optimized\");\n\n  g_called = false;\n  VERIFY_IS_APPROX(m1.array()-s, m1.array()-Scalar(s));\n  VERIFY(g_called && \"matrix<complex> - real not properly optimized\");\n}\n\ntemplate<int>\nvoid linearstructure_overflow()\n{\n  // make sure that /=scalar and /scalar do not overflow\n  // rational: 1.0/4.94e-320 overflow, but m/4.94e-320 should not\n  Matrix4d m2, m3;\n  m3 = m2 =  Matrix4d::Random()*1e-20;\n  m2 = m2 / 4.9e-320;\n  VERIFY_IS_APPROX(m2.cwiseQuotient(m2), Matrix4d::Ones());\n  m3 /= 4.9e-320;\n  VERIFY_IS_APPROX(m3.cwiseQuotient(m3), Matrix4d::Ones());\n}\n\nEIGEN_DECLARE_TEST(linearstructure)\n{\n  g_called = true;\n  VERIFY(g_called); // avoid `unneeded-internal-declaration` warning.\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( linearStructure(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( linearStructure(Matrix2f()) );\n    CALL_SUBTEST_3( linearStructure(Vector3d()) );\n    CALL_SUBTEST_4( linearStructure(Matrix4d()) );\n    CALL_SUBTEST_5( linearStructure(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2), internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))) );\n    CALL_SUBTEST_6( linearStructure(MatrixXf (internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_7( linearStructure(MatrixXi (internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_8( linearStructure(MatrixXcd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2), internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))) );\n    CALL_SUBTEST_9( linearStructure(ArrayXXf (internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_10( linearStructure(ArrayXXcf (internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    \n    CALL_SUBTEST_11( real_complex<Matrix4cd>() );\n    CALL_SUBTEST_11( real_complex<MatrixXcf>(10,10) );\n    CALL_SUBTEST_11( real_complex<ArrayXXcf>(10,10) );\n  }\n  CALL_SUBTEST_4( linearstructure_overflow<0>() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/lscg.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"sparse_solver.h\"\n#include <Eigen/IterativeLinearSolvers>\n\ntemplate<typename T> void test_lscg_T()\n{\n  LeastSquaresConjugateGradient<SparseMatrix<T> > lscg_colmajor_diag;\n  LeastSquaresConjugateGradient<SparseMatrix<T>, IdentityPreconditioner> lscg_colmajor_I;\n  LeastSquaresConjugateGradient<SparseMatrix<T,RowMajor> > lscg_rowmajor_diag;\n  LeastSquaresConjugateGradient<SparseMatrix<T,RowMajor>, IdentityPreconditioner> lscg_rowmajor_I;\n\n  CALL_SUBTEST( check_sparse_square_solving(lscg_colmajor_diag)  );\n  CALL_SUBTEST( check_sparse_square_solving(lscg_colmajor_I)     );\n  \n  CALL_SUBTEST( check_sparse_leastsquare_solving(lscg_colmajor_diag)  );\n  CALL_SUBTEST( check_sparse_leastsquare_solving(lscg_colmajor_I)     );\n\n  CALL_SUBTEST( check_sparse_square_solving(lscg_rowmajor_diag)  );\n  CALL_SUBTEST( check_sparse_square_solving(lscg_rowmajor_I)     );\n\n  CALL_SUBTEST( check_sparse_leastsquare_solving(lscg_rowmajor_diag)  );\n  CALL_SUBTEST( check_sparse_leastsquare_solving(lscg_rowmajor_I)     );\n}\n\nEIGEN_DECLARE_TEST(lscg)\n{\n  CALL_SUBTEST_1(test_lscg_T<double>());\n  CALL_SUBTEST_2(test_lscg_T<std::complex<double> >());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/lu.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/LU>\n#include \"solverbase.h\"\nusing namespace std;\n\ntemplate<typename MatrixType>\ntypename MatrixType::RealScalar matrix_l1_norm(const MatrixType& m) {\n  return m.cwiseAbs().colwise().sum().maxCoeff();\n}\n\ntemplate<typename MatrixType> void lu_non_invertible()\n{\n  STATIC_CHECK(( internal::is_same<typename FullPivLU<MatrixType>::StorageIndex,int>::value ));\n\n  typedef typename MatrixType::RealScalar RealScalar;\n  /* this test covers the following files:\n     LU.h\n  */\n  Index rows, cols, cols2;\n  if(MatrixType::RowsAtCompileTime==Dynamic)\n  {\n    rows = internal::random<Index>(2,EIGEN_TEST_MAX_SIZE);\n  }\n  else\n  {\n    rows = MatrixType::RowsAtCompileTime;\n  }\n  if(MatrixType::ColsAtCompileTime==Dynamic)\n  {\n    cols = internal::random<Index>(2,EIGEN_TEST_MAX_SIZE);\n    cols2 = internal::random<int>(2,EIGEN_TEST_MAX_SIZE);\n  }\n  else\n  {\n    cols2 = cols = MatrixType::ColsAtCompileTime;\n  }\n\n  enum {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime\n  };\n  typedef typename internal::kernel_retval_base<FullPivLU<MatrixType> >::ReturnType KernelMatrixType;\n  typedef typename internal::image_retval_base<FullPivLU<MatrixType> >::ReturnType ImageMatrixType;\n  typedef Matrix<typename MatrixType::Scalar, ColsAtCompileTime, ColsAtCompileTime>\n          CMatrixType;\n  typedef Matrix<typename MatrixType::Scalar, RowsAtCompileTime, RowsAtCompileTime>\n          RMatrixType;\n\n  Index rank = internal::random<Index>(1, (std::min)(rows, cols)-1);\n\n  // The image of the zero matrix should consist of a single (zero) column vector\n  VERIFY((MatrixType::Zero(rows,cols).fullPivLu().image(MatrixType::Zero(rows,cols)).cols() == 1));\n\n  // The kernel of the zero matrix is the entire space, and thus is an invertible matrix of dimensions cols.\n  KernelMatrixType kernel = MatrixType::Zero(rows,cols).fullPivLu().kernel();\n  VERIFY((kernel.fullPivLu().isInvertible()));\n\n  MatrixType m1(rows, cols), m3(rows, cols2);\n  CMatrixType m2(cols, cols2);\n  createRandomPIMatrixOfRank(rank, rows, cols, m1);\n\n  FullPivLU<MatrixType> lu;\n\n  // The special value 0.01 below works well in tests. Keep in mind that we're only computing the rank\n  // of singular values are either 0 or 1.\n  // So it's not clear at all that the epsilon should play any role there.\n  lu.setThreshold(RealScalar(0.01));\n  lu.compute(m1);\n\n  MatrixType u(rows,cols);\n  u = lu.matrixLU().template triangularView<Upper>();\n  RMatrixType l = RMatrixType::Identity(rows,rows);\n  l.block(0,0,rows,(std::min)(rows,cols)).template triangularView<StrictlyLower>()\n    = lu.matrixLU().block(0,0,rows,(std::min)(rows,cols));\n\n  VERIFY_IS_APPROX(lu.permutationP() * m1 * lu.permutationQ(), l*u);\n\n  KernelMatrixType m1kernel = lu.kernel();\n  ImageMatrixType m1image = lu.image(m1);\n\n  VERIFY_IS_APPROX(m1, lu.reconstructedMatrix());\n  VERIFY(rank == lu.rank());\n  VERIFY(cols - lu.rank() == lu.dimensionOfKernel());\n  VERIFY(!lu.isInjective());\n  VERIFY(!lu.isInvertible());\n  VERIFY(!lu.isSurjective());\n  VERIFY_IS_MUCH_SMALLER_THAN((m1 * m1kernel), m1);\n  VERIFY(m1image.fullPivLu().rank() == rank);\n  VERIFY_IS_APPROX(m1 * m1.adjoint() * m1image, m1image);\n\n  check_solverbase<CMatrixType, MatrixType>(m1, lu, rows, cols, cols2);\n\n  m2 = CMatrixType::Random(cols,cols2);\n  m3 = m1*m2;\n  m2 = CMatrixType::Random(cols,cols2);\n  // test that the code, which does resize(), may be applied to an xpr\n  m2.block(0,0,m2.rows(),m2.cols()) = lu.solve(m3);\n  VERIFY_IS_APPROX(m3, m1*m2);\n}\n\ntemplate<typename MatrixType> void lu_invertible()\n{\n  /* this test covers the following files:\n     FullPivLU.h\n  */\n  typedef typename NumTraits<typename MatrixType::Scalar>::Real RealScalar;\n  Index size = MatrixType::RowsAtCompileTime;\n  if( size==Dynamic)\n    size = internal::random<Index>(1,EIGEN_TEST_MAX_SIZE);\n\n  MatrixType m1(size, size), m2(size, size), m3(size, size);\n  FullPivLU<MatrixType> lu;\n  lu.setThreshold(RealScalar(0.01));\n  do {\n    m1 = MatrixType::Random(size,size);\n    lu.compute(m1);\n  } while(!lu.isInvertible());\n\n  VERIFY_IS_APPROX(m1, lu.reconstructedMatrix());\n  VERIFY(0 == lu.dimensionOfKernel());\n  VERIFY(lu.kernel().cols() == 1); // the kernel() should consist of a single (zero) column vector\n  VERIFY(size == lu.rank());\n  VERIFY(lu.isInjective());\n  VERIFY(lu.isSurjective());\n  VERIFY(lu.isInvertible());\n  VERIFY(lu.image(m1).fullPivLu().isInvertible());\n\n  check_solverbase<MatrixType, MatrixType>(m1, lu, size, size, size);\n\n  MatrixType m1_inverse = lu.inverse();\n  m3 = MatrixType::Random(size,size);\n  m2 = lu.solve(m3);\n  VERIFY_IS_APPROX(m2, m1_inverse*m3);\n\n  RealScalar rcond = (RealScalar(1) / matrix_l1_norm(m1)) / matrix_l1_norm(m1_inverse);\n  const RealScalar rcond_est = lu.rcond();\n  // Verify that the estimated condition number is within a factor of 10 of the\n  // truth.\n  VERIFY(rcond_est > rcond / 10 && rcond_est < rcond * 10);\n\n  // Regression test for Bug 302\n  MatrixType m4 = MatrixType::Random(size,size);\n  VERIFY_IS_APPROX(lu.solve(m3*m4), lu.solve(m3)*m4);\n}\n\ntemplate<typename MatrixType> void lu_partial_piv(Index size = MatrixType::ColsAtCompileTime)\n{\n  /* this test covers the following files:\n     PartialPivLU.h\n  */\n  typedef typename NumTraits<typename MatrixType::Scalar>::Real RealScalar;\n\n  MatrixType m1(size, size), m2(size, size), m3(size, size);\n  m1.setRandom();\n  PartialPivLU<MatrixType> plu(m1);\n\n  STATIC_CHECK(( internal::is_same<typename PartialPivLU<MatrixType>::StorageIndex,int>::value ));\n\n  VERIFY_IS_APPROX(m1, plu.reconstructedMatrix());\n\n  check_solverbase<MatrixType, MatrixType>(m1, plu, size, size, size);\n\n  MatrixType m1_inverse = plu.inverse();\n  m3 = MatrixType::Random(size,size);\n  m2 = plu.solve(m3);\n  VERIFY_IS_APPROX(m2, m1_inverse*m3);\n\n  RealScalar rcond = (RealScalar(1) / matrix_l1_norm(m1)) / matrix_l1_norm(m1_inverse);\n  const RealScalar rcond_est = plu.rcond();\n  // Verify that the estimate is within a factor of 10 of the truth.\n  VERIFY(rcond_est > rcond / 10 && rcond_est < rcond * 10);\n}\n\ntemplate<typename MatrixType> void lu_verify_assert()\n{\n  MatrixType tmp;\n\n  FullPivLU<MatrixType> lu;\n  VERIFY_RAISES_ASSERT(lu.matrixLU())\n  VERIFY_RAISES_ASSERT(lu.permutationP())\n  VERIFY_RAISES_ASSERT(lu.permutationQ())\n  VERIFY_RAISES_ASSERT(lu.kernel())\n  VERIFY_RAISES_ASSERT(lu.image(tmp))\n  VERIFY_RAISES_ASSERT(lu.solve(tmp))\n  VERIFY_RAISES_ASSERT(lu.transpose().solve(tmp))\n  VERIFY_RAISES_ASSERT(lu.adjoint().solve(tmp))\n  VERIFY_RAISES_ASSERT(lu.determinant())\n  VERIFY_RAISES_ASSERT(lu.rank())\n  VERIFY_RAISES_ASSERT(lu.dimensionOfKernel())\n  VERIFY_RAISES_ASSERT(lu.isInjective())\n  VERIFY_RAISES_ASSERT(lu.isSurjective())\n  VERIFY_RAISES_ASSERT(lu.isInvertible())\n  VERIFY_RAISES_ASSERT(lu.inverse())\n\n  PartialPivLU<MatrixType> plu;\n  VERIFY_RAISES_ASSERT(plu.matrixLU())\n  VERIFY_RAISES_ASSERT(plu.permutationP())\n  VERIFY_RAISES_ASSERT(plu.solve(tmp))\n  VERIFY_RAISES_ASSERT(plu.transpose().solve(tmp))\n  VERIFY_RAISES_ASSERT(plu.adjoint().solve(tmp))\n  VERIFY_RAISES_ASSERT(plu.determinant())\n  VERIFY_RAISES_ASSERT(plu.inverse())\n}\n\nEIGEN_DECLARE_TEST(lu)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( lu_non_invertible<Matrix3f>() );\n    CALL_SUBTEST_1( lu_invertible<Matrix3f>() );\n    CALL_SUBTEST_1( lu_verify_assert<Matrix3f>() );\n    CALL_SUBTEST_1( lu_partial_piv<Matrix3f>() );\n\n    CALL_SUBTEST_2( (lu_non_invertible<Matrix<double, 4, 6> >()) );\n    CALL_SUBTEST_2( (lu_verify_assert<Matrix<double, 4, 6> >()) );\n    CALL_SUBTEST_2( lu_partial_piv<Matrix2d>() );\n    CALL_SUBTEST_2( lu_partial_piv<Matrix4d>() );\n    CALL_SUBTEST_2( (lu_partial_piv<Matrix<double,6,6> >()) );\n\n    CALL_SUBTEST_3( lu_non_invertible<MatrixXf>() );\n    CALL_SUBTEST_3( lu_invertible<MatrixXf>() );\n    CALL_SUBTEST_3( lu_verify_assert<MatrixXf>() );\n\n    CALL_SUBTEST_4( lu_non_invertible<MatrixXd>() );\n    CALL_SUBTEST_4( lu_invertible<MatrixXd>() );\n    CALL_SUBTEST_4( lu_partial_piv<MatrixXd>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)) );\n    CALL_SUBTEST_4( lu_verify_assert<MatrixXd>() );\n\n    CALL_SUBTEST_5( lu_non_invertible<MatrixXcf>() );\n    CALL_SUBTEST_5( lu_invertible<MatrixXcf>() );\n    CALL_SUBTEST_5( lu_verify_assert<MatrixXcf>() );\n\n    CALL_SUBTEST_6( lu_non_invertible<MatrixXcd>() );\n    CALL_SUBTEST_6( lu_invertible<MatrixXcd>() );\n    CALL_SUBTEST_6( lu_partial_piv<MatrixXcd>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)) );\n    CALL_SUBTEST_6( lu_verify_assert<MatrixXcd>() );\n\n    CALL_SUBTEST_7(( lu_non_invertible<Matrix<float,Dynamic,16> >() ));\n\n    // Test problem size constructors\n    CALL_SUBTEST_9( PartialPivLU<MatrixXf>(10) );\n    CALL_SUBTEST_9( FullPivLU<MatrixXf>(10, 20); );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/main.h",
    "content": "\n// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <cstdlib>\n#include <cerrno>\n#include <ctime>\n#include <iostream>\n#include <fstream>\n#include <string>\n#include <sstream>\n#include <vector>\n#include <typeinfo>\n#include <functional>\n\n// The following includes of STL headers have to be done _before_ the\n// definition of macros min() and max().  The reason is that many STL\n// implementations will not work properly as the min and max symbols collide\n// with the STL functions std:min() and std::max().  The STL headers may check\n// for the macro definition of min/max and issue a warning or undefine the\n// macros.\n//\n// Still, Windows defines min() and max() in windef.h as part of the regular\n// Windows system interfaces and many other Windows APIs depend on these\n// macros being available.  To prevent the macro expansion of min/max and to\n// make Eigen compatible with the Windows environment all function calls of\n// std::min() and std::max() have to be written with parenthesis around the\n// function name.\n//\n// All STL headers used by Eigen should be included here.  Because main.h is\n// included before any Eigen header and because the STL headers are guarded\n// against multiple inclusions, no STL header will see our own min/max macro\n// definitions.\n#include <limits>\n#include <algorithm>\n// Disable ICC's std::complex operator specializations so we can use our own.\n#define _OVERRIDE_COMPLEX_SPECIALIZATION_ 1\n#include <complex>\n#include <deque>\n#include <queue>\n#include <cassert>\n#include <list>\n#if __cplusplus >= 201103L || (defined(_MSVC_LANG) && _MSVC_LANG >= 201103L)\n#include <random>\n#include <chrono>\n#ifdef EIGEN_USE_THREADS\n#include <future>\n#endif\n#endif\n\n// Same for cuda_fp16.h\n#if defined(__CUDACC__) && !defined(EIGEN_NO_CUDA)\n  // Means the compiler is either nvcc or clang with CUDA enabled\n  #define EIGEN_CUDACC __CUDACC__\n#endif\n#if defined(EIGEN_CUDACC)\n#include <cuda.h>\n  #define EIGEN_CUDA_SDK_VER (CUDA_VERSION * 10)\n#else\n  #define EIGEN_CUDA_SDK_VER 0\n#endif\n#if EIGEN_CUDA_SDK_VER >= 70500\n#include <cuda_fp16.h>\n#endif\n\n// To test that all calls from Eigen code to std::min() and std::max() are\n// protected by parenthesis against macro expansion, the min()/max() macros\n// are defined here and any not-parenthesized min/max call will cause a\n// compiler error.\n#if !defined(__HIPCC__) && !defined(EIGEN_USE_SYCL)\n  //\n  // HIP header files include the following files\n  //  <thread>\n  //  <regex>\n  //  <unordered_map>\n  // which seem to contain not-parenthesized calls to \"max\"/\"min\", triggering the following check and causing the compile to fail\n  //\n  // Including those header files before the following macro definition for \"min\" / \"max\", only partially resolves the issue\n  // This is because other HIP header files also define \"isnan\" / \"isinf\" / \"isfinite\" functions, which are needed in other\n  // headers.\n  //\n  // So instead choosing to simply disable this check for HIP\n  //\n  #define min(A,B) please_protect_your_min_with_parentheses\n  #define max(A,B) please_protect_your_max_with_parentheses\n  #define isnan(X) please_protect_your_isnan_with_parentheses\n  #define isinf(X) please_protect_your_isinf_with_parentheses\n  #define isfinite(X) please_protect_your_isfinite_with_parentheses\n#endif\n\n\n// test possible conflicts\nstruct real {};\nstruct imag {};\n\n#ifdef M_PI\n#undef M_PI\n#endif\n#define M_PI please_use_EIGEN_PI_instead_of_M_PI\n\n#define FORBIDDEN_IDENTIFIER (this_identifier_is_forbidden_to_avoid_clashes) this_identifier_is_forbidden_to_avoid_clashes\n// B0 is defined in POSIX header termios.h\n#define B0 FORBIDDEN_IDENTIFIER\n// `I` may be defined by complex.h:\n#define I  FORBIDDEN_IDENTIFIER\n\n// Unit tests calling Eigen's blas library must preserve the default blocking size\n// to avoid troubles.\n#ifndef EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS\n#define EIGEN_DEBUG_SMALL_PRODUCT_BLOCKS\n#endif\n\n// shuts down ICC's remark #593: variable \"XXX\" was set but never used\n#define TEST_SET_BUT_UNUSED_VARIABLE(X) EIGEN_UNUSED_VARIABLE(X)\n\n#ifdef TEST_ENABLE_TEMPORARY_TRACKING\n\nstatic long int nb_temporaries;\nstatic long int nb_temporaries_on_assert = -1;\n\ninline void on_temporary_creation(long int size) {\n  // here's a great place to set a breakpoint when debugging failures in this test!\n  if(size!=0) nb_temporaries++;\n  if(nb_temporaries_on_assert>0) assert(nb_temporaries<nb_temporaries_on_assert);\n}\n\n#define EIGEN_DENSE_STORAGE_CTOR_PLUGIN { on_temporary_creation(size); }\n\n#define VERIFY_EVALUATION_COUNT(XPR,N) {\\\n    nb_temporaries = 0; \\\n    XPR; \\\n    if(nb_temporaries!=(N)) { std::cerr << \"nb_temporaries == \" << nb_temporaries << \"\\n\"; }\\\n    VERIFY( (#XPR) && nb_temporaries==(N) ); \\\n  }\n\n#endif\n\n#include \"split_test_helper.h\"\n\n#ifdef NDEBUG\n#undef NDEBUG\n#endif\n\n// On windows CE, NDEBUG is automatically defined <assert.h> if NDEBUG is not defined.\n#ifndef DEBUG\n#define DEBUG\n#endif\n\n// bounds integer values for AltiVec\n#if defined(__ALTIVEC__) || defined(__VSX__)\n#define EIGEN_MAKING_DOCS\n#endif\n\n#define DEFAULT_REPEAT 10\n\nnamespace Eigen\n{\n  static std::vector<std::string> g_test_stack;\n  // level == 0 <=> abort if test fail\n  // level >= 1 <=> warning message to std::cerr if test fail\n  static int g_test_level = 0;\n  static int g_repeat = 1;\n  static unsigned int g_seed = 0;\n  static bool g_has_set_repeat = false, g_has_set_seed = false;\n\n  class EigenTest\n  {\n  public:\n    EigenTest() : m_func(0) {}\n    EigenTest(const char* a_name, void (*func)(void))\n      : m_name(a_name), m_func(func)\n    {\n      get_registered_tests().push_back(this);\n    }\n    const std::string& name() const { return m_name; }\n    void operator()() const { m_func(); }\n\n    static const std::vector<EigenTest*>& all() { return get_registered_tests(); }\n  protected:\n    static std::vector<EigenTest*>& get_registered_tests()\n    {\n      static std::vector<EigenTest*>* ms_registered_tests = new std::vector<EigenTest*>();\n      return *ms_registered_tests;\n    }\n    std::string m_name;\n    void (*m_func)(void);\n  };\n\n  // Declare and register a test, e.g.:\n  //    EIGEN_DECLARE_TEST(mytest) { ... }\n  // will create a function:\n  //    void test_mytest() { ... }\n  // that will be automatically called.\n  #define EIGEN_DECLARE_TEST(X) \\\n    void EIGEN_CAT(test_,X) (); \\\n    static EigenTest EIGEN_CAT(test_handler_,X) (EIGEN_MAKESTRING(X), & EIGEN_CAT(test_,X)); \\\n    void EIGEN_CAT(test_,X) ()\n}\n\n#define TRACK std::cerr << __FILE__ << \" \" << __LINE__ << std::endl\n// #define TRACK while()\n\n#define EIGEN_DEFAULT_IO_FORMAT IOFormat(4, 0, \"  \", \"\\n\", \"\", \"\", \"\", \"\")\n\n#if (defined(_CPPUNWIND) || defined(__EXCEPTIONS)) && !defined(__CUDA_ARCH__) && !defined(__HIP_DEVICE_COMPILE__) && !defined(__SYCL_DEVICE_ONLY__)\n  #define EIGEN_EXCEPTIONS\n#endif\n\n#ifndef EIGEN_NO_ASSERTION_CHECKING\n\n  namespace Eigen\n  {\n    static const bool should_raise_an_assert = false;\n\n    // Used to avoid to raise two exceptions at a time in which\n    // case the exception is not properly caught.\n    // This may happen when a second exceptions is triggered in a destructor.\n    static bool no_more_assert = false;\n    static bool report_on_cerr_on_assert_failure = true;\n\n    struct eigen_assert_exception\n    {\n      eigen_assert_exception(void) {}\n      ~eigen_assert_exception() { Eigen::no_more_assert = false; }\n    };\n\n    struct eigen_static_assert_exception\n    {\n      eigen_static_assert_exception(void) {}\n      ~eigen_static_assert_exception() { Eigen::no_more_assert = false; }\n    };\n  }\n  // If EIGEN_DEBUG_ASSERTS is defined and if no assertion is triggered while\n  // one should have been, then the list of executed assertions is printed out.\n  //\n  // EIGEN_DEBUG_ASSERTS is not enabled by default as it\n  // significantly increases the compilation time\n  // and might even introduce side effects that would hide\n  // some memory errors.\n  #ifdef EIGEN_DEBUG_ASSERTS\n\n    namespace Eigen\n    {\n      namespace internal\n      {\n        static bool push_assert = false;\n      }\n      static std::vector<std::string> eigen_assert_list;\n    }\n    #define eigen_assert(a)                       \\\n      if( (!(a)) && (!no_more_assert) )     \\\n      { \\\n        if(report_on_cerr_on_assert_failure) \\\n          std::cerr <<  #a << \" \" __FILE__ << \"(\" << __LINE__ << \")\\n\"; \\\n        Eigen::no_more_assert = true;       \\\n        EIGEN_THROW_X(Eigen::eigen_assert_exception()); \\\n      }                                     \\\n      else if (Eigen::internal::push_assert)       \\\n      {                                     \\\n        eigen_assert_list.push_back(std::string(EIGEN_MAKESTRING(__FILE__) \" (\" EIGEN_MAKESTRING(__LINE__) \") : \" #a) ); \\\n      }\n\n    #ifdef EIGEN_EXCEPTIONS\n    #define VERIFY_RAISES_ASSERT(a)                                                   \\\n      {                                                                               \\\n        Eigen::no_more_assert = false;                                                \\\n        Eigen::eigen_assert_list.clear();                                             \\\n        Eigen::internal::push_assert = true;                                          \\\n        Eigen::report_on_cerr_on_assert_failure = false;                              \\\n        try {                                                                         \\\n          a;                                                                          \\\n          std::cerr << \"One of the following asserts should have been triggered:\\n\";  \\\n          for (uint ai=0 ; ai<eigen_assert_list.size() ; ++ai)                        \\\n            std::cerr << \"  \" << eigen_assert_list[ai] << \"\\n\";                       \\\n          VERIFY(Eigen::should_raise_an_assert && # a);                               \\\n        } catch (Eigen::eigen_assert_exception) {                                     \\\n          Eigen::internal::push_assert = false; VERIFY(true);                         \\\n        }                                                                             \\\n        Eigen::report_on_cerr_on_assert_failure = true;                               \\\n        Eigen::internal::push_assert = false;                                         \\\n      }\n    #endif //EIGEN_EXCEPTIONS\n\n  #elif !defined(__CUDACC__) && !defined(__HIPCC__) && !defined(SYCL_DEVICE_ONLY) // EIGEN_DEBUG_ASSERTS\n    // see bug 89. The copy_bool here is working around a bug in gcc <= 4.3\n    #define eigen_assert(a) \\\n      if( (!Eigen::internal::copy_bool(a)) && (!no_more_assert) )\\\n      {                                       \\\n        Eigen::no_more_assert = true;         \\\n        if(report_on_cerr_on_assert_failure)  \\\n          eigen_plain_assert(a);              \\\n        else                                  \\\n          EIGEN_THROW_X(Eigen::eigen_assert_exception()); \\\n      }\n\n    #ifdef EIGEN_EXCEPTIONS\n      #define VERIFY_RAISES_ASSERT(a) {                           \\\n        Eigen::no_more_assert = false;                            \\\n        Eigen::report_on_cerr_on_assert_failure = false;          \\\n        try {                                                     \\\n          a;                                                      \\\n          VERIFY(Eigen::should_raise_an_assert && # a);           \\\n        }                                                         \\\n        catch (Eigen::eigen_assert_exception&) { VERIFY(true); }  \\\n        Eigen::report_on_cerr_on_assert_failure = true;           \\\n      }\n    #endif // EIGEN_EXCEPTIONS\n  #endif // EIGEN_DEBUG_ASSERTS\n\n  #if defined(TEST_CHECK_STATIC_ASSERTIONS) && defined(EIGEN_EXCEPTIONS)\n    #define EIGEN_STATIC_ASSERT(a,MSG) \\\n      if( (!Eigen::internal::copy_bool(a)) && (!no_more_assert) )\\\n      {                                       \\\n        Eigen::no_more_assert = true;         \\\n        if(report_on_cerr_on_assert_failure)  \\\n          eigen_plain_assert((a) && #MSG);      \\\n        else                                  \\\n          EIGEN_THROW_X(Eigen::eigen_static_assert_exception()); \\\n      }\n    #define VERIFY_RAISES_STATIC_ASSERT(a) {                    \\\n      Eigen::no_more_assert = false;                            \\\n      Eigen::report_on_cerr_on_assert_failure = false;          \\\n      try {                                                     \\\n        a;                                                      \\\n        VERIFY(Eigen::should_raise_an_assert && # a);           \\\n      }                                                         \\\n      catch (Eigen::eigen_static_assert_exception&) { VERIFY(true); }  \\\n      Eigen::report_on_cerr_on_assert_failure = true;           \\\n    }\n  #endif // TEST_CHECK_STATIC_ASSERTIONS\n\n#ifndef VERIFY_RAISES_ASSERT\n  #define VERIFY_RAISES_ASSERT(a) \\\n    std::cout << \"Can't VERIFY_RAISES_ASSERT( \" #a \" ) with exceptions disabled\\n\";\n#endif\n#ifndef VERIFY_RAISES_STATIC_ASSERT\n  #define VERIFY_RAISES_STATIC_ASSERT(a) \\\n    std::cout << \"Can't VERIFY_RAISES_STATIC_ASSERT( \" #a \" ) with exceptions disabled\\n\";\n#endif\n\n  #if !defined(__CUDACC__) && !defined(__HIPCC__) && !defined(SYCL_DEVICE_ONLY)\n  #define EIGEN_USE_CUSTOM_ASSERT\n  #endif\n\n#else // EIGEN_NO_ASSERTION_CHECKING\n\n  #define VERIFY_RAISES_ASSERT(a) {}\n  #define VERIFY_RAISES_STATIC_ASSERT(a) {}\n\n#endif // EIGEN_NO_ASSERTION_CHECKING\n\n#define EIGEN_INTERNAL_DEBUGGING\n#include <Eigen/QR> // required for createRandomPIMatrixOfRank and generateRandomMatrixSvs\n\ninline void verify_impl(bool condition, const char *testname, const char *file, int line, const char *condition_as_string)\n{\n  if (!condition)\n  {\n    if(Eigen::g_test_level>0)\n      std::cerr << \"WARNING: \";\n    std::cerr << \"Test \" << testname << \" failed in \" << file << \" (\" << line << \")\"\n      << std::endl << \"    \" << condition_as_string << std::endl;\n    std::cerr << \"Stack:\\n\";\n    const int test_stack_size = static_cast<int>(Eigen::g_test_stack.size());\n    for(int i=test_stack_size-1; i>=0; --i)\n      std::cerr << \"  - \" << Eigen::g_test_stack[i] << \"\\n\";\n    std::cerr << \"\\n\";\n    if(Eigen::g_test_level==0)\n      abort();\n  }\n}\n\n#define VERIFY(a) ::verify_impl(a, g_test_stack.back().c_str(), __FILE__, __LINE__, EIGEN_MAKESTRING(a))\n\n#define VERIFY_GE(a, b) ::verify_impl(a >= b, g_test_stack.back().c_str(), __FILE__, __LINE__, EIGEN_MAKESTRING(a >= b))\n#define VERIFY_LE(a, b) ::verify_impl(a <= b, g_test_stack.back().c_str(), __FILE__, __LINE__, EIGEN_MAKESTRING(a <= b))\n\n\n#define VERIFY_IS_EQUAL(a, b) VERIFY(test_is_equal(a, b, true))\n#define VERIFY_IS_NOT_EQUAL(a, b) VERIFY(test_is_equal(a, b, false))\n#define VERIFY_IS_APPROX(a, b) VERIFY(verifyIsApprox(a, b))\n#define VERIFY_IS_NOT_APPROX(a, b) VERIFY(!test_isApprox(a, b))\n#define VERIFY_IS_MUCH_SMALLER_THAN(a, b) VERIFY(test_isMuchSmallerThan(a, b))\n#define VERIFY_IS_NOT_MUCH_SMALLER_THAN(a, b) VERIFY(!test_isMuchSmallerThan(a, b))\n#define VERIFY_IS_APPROX_OR_LESS_THAN(a, b) VERIFY(test_isApproxOrLessThan(a, b))\n#define VERIFY_IS_NOT_APPROX_OR_LESS_THAN(a, b) VERIFY(!test_isApproxOrLessThan(a, b))\n\n#define VERIFY_IS_UNITARY(a) VERIFY(test_isUnitary(a))\n\n#define STATIC_CHECK(COND) EIGEN_STATIC_ASSERT( (COND) , EIGEN_INTERNAL_ERROR_PLEASE_FILE_A_BUG_REPORT )\n\n#define CALL_SUBTEST(FUNC) do { \\\n    g_test_stack.push_back(EIGEN_MAKESTRING(FUNC)); \\\n    FUNC; \\\n    g_test_stack.pop_back(); \\\n  } while (0)\n\n\n  namespace Eigen {\n\n// Forward declarations to avoid ICC warnings\ntemplate<typename T, typename U>\nbool test_is_equal(const T& actual, const U& expected, bool expect_equal=true);\n\ntemplate<typename MatrixType>\nvoid createRandomPIMatrixOfRank(Index desired_rank, Index rows, Index cols, MatrixType& m);\n\ntemplate<typename PermutationVectorType>\nvoid randomPermutationVector(PermutationVectorType& v, Index size);\n\ntemplate<typename MatrixType>\nMatrixType generateRandomUnitaryMatrix(const Index dim);\n\ntemplate<typename MatrixType, typename RealScalarVectorType>\nvoid generateRandomMatrixSvs(const RealScalarVectorType &svs, const Index rows, const Index cols, MatrixType& M);\n\ntemplate<typename VectorType, typename RealScalar>\nVectorType setupRandomSvs(const Index dim, const RealScalar max);\n\ntemplate<typename VectorType, typename RealScalar>\nVectorType setupRangeSvs(const Index dim, const RealScalar min, const RealScalar max);\n\n} // end namespace Eigen\n\n// Forward declaration to avoid ICC warnings\ntemplate<typename T> std::string type_name();\n\n\nnamespace Eigen {\n\ntemplate<typename T1,typename T2>\ntypename internal::enable_if<internal::is_same<T1,T2>::value,bool>::type\nis_same_type(const T1&, const T2&)\n{\n  return true;\n}\n\ntemplate<typename T> inline typename NumTraits<T>::Real test_precision() { return NumTraits<T>::dummy_precision(); }\ntemplate<> inline float test_precision<float>() { return 1e-3f; }\ntemplate<> inline double test_precision<double>() { return 1e-6; }\ntemplate<> inline long double test_precision<long double>() { return 1e-6l; }\ntemplate<> inline float test_precision<std::complex<float> >() { return test_precision<float>(); }\ntemplate<> inline double test_precision<std::complex<double> >() { return test_precision<double>(); }\ntemplate<> inline long double test_precision<std::complex<long double> >() { return test_precision<long double>(); }\n\n#define EIGEN_TEST_SCALAR_TEST_OVERLOAD(TYPE)                             \\\n  inline bool test_isApprox(TYPE a, TYPE b)                               \\\n  { return internal::isApprox(a, b, test_precision<TYPE>()); }            \\\n  inline bool test_isMuchSmallerThan(TYPE a, TYPE b)                      \\\n  { return internal::isMuchSmallerThan(a, b, test_precision<TYPE>()); }   \\\n  inline bool test_isApproxOrLessThan(TYPE a, TYPE b)                     \\\n  { return internal::isApproxOrLessThan(a, b, test_precision<TYPE>()); }\n\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(short)\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(unsigned short)\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(int)\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(unsigned int)\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(long)\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(unsigned long)\n#if EIGEN_HAS_CXX11\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(long long)\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(unsigned long long)\n#endif\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(float)\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(double)\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(half)\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(bfloat16)\n\n#undef EIGEN_TEST_SCALAR_TEST_OVERLOAD\n\n#ifndef EIGEN_TEST_NO_COMPLEX\ninline bool test_isApprox(const std::complex<float>& a, const std::complex<float>& b)\n{ return internal::isApprox(a, b, test_precision<std::complex<float> >()); }\ninline bool test_isMuchSmallerThan(const std::complex<float>& a, const std::complex<float>& b)\n{ return internal::isMuchSmallerThan(a, b, test_precision<std::complex<float> >()); }\n\ninline bool test_isApprox(const std::complex<double>& a, const std::complex<double>& b)\n{ return internal::isApprox(a, b, test_precision<std::complex<double> >()); }\ninline bool test_isMuchSmallerThan(const std::complex<double>& a, const std::complex<double>& b)\n{ return internal::isMuchSmallerThan(a, b, test_precision<std::complex<double> >()); }\n\n#ifndef EIGEN_TEST_NO_LONGDOUBLE\ninline bool test_isApprox(const std::complex<long double>& a, const std::complex<long double>& b)\n{ return internal::isApprox(a, b, test_precision<std::complex<long double> >()); }\ninline bool test_isMuchSmallerThan(const std::complex<long double>& a, const std::complex<long double>& b)\n{ return internal::isMuchSmallerThan(a, b, test_precision<std::complex<long double> >()); }\n#endif\n#endif\n\n#ifndef EIGEN_TEST_NO_LONGDOUBLE\ninline bool test_isApprox(const long double& a, const long double& b)\n{\n    bool ret = internal::isApprox(a, b, test_precision<long double>());\n    if (!ret) std::cerr\n        << std::endl << \"    actual   = \" << a\n        << std::endl << \"    expected = \" << b << std::endl << std::endl;\n    return ret;\n}\n\ninline bool test_isMuchSmallerThan(const long double& a, const long double& b)\n{ return internal::isMuchSmallerThan(a, b, test_precision<long double>()); }\ninline bool test_isApproxOrLessThan(const long double& a, const long double& b)\n{ return internal::isApproxOrLessThan(a, b, test_precision<long double>()); }\n#endif // EIGEN_TEST_NO_LONGDOUBLE\n\n// test_relative_error returns the relative difference between a and b as a real scalar as used in isApprox.\ntemplate<typename T1,typename T2>\ntypename NumTraits<typename T1::RealScalar>::NonInteger test_relative_error(const EigenBase<T1> &a, const EigenBase<T2> &b)\n{\n  using std::sqrt;\n  typedef typename NumTraits<typename T1::RealScalar>::NonInteger RealScalar;\n  typename internal::nested_eval<T1,2>::type ea(a.derived());\n  typename internal::nested_eval<T2,2>::type eb(b.derived());\n  return sqrt(RealScalar((ea-eb).cwiseAbs2().sum()) / RealScalar((std::min)(eb.cwiseAbs2().sum(),ea.cwiseAbs2().sum())));\n}\n\ntemplate<typename T1,typename T2>\ntypename T1::RealScalar test_relative_error(const T1 &a, const T2 &b, const typename T1::Coefficients* = 0)\n{\n  return test_relative_error(a.coeffs(), b.coeffs());\n}\n\ntemplate<typename T1,typename T2>\ntypename T1::Scalar test_relative_error(const T1 &a, const T2 &b, const typename T1::MatrixType* = 0)\n{\n  return test_relative_error(a.matrix(), b.matrix());\n}\n\ntemplate<typename S, int D>\nS test_relative_error(const Translation<S,D> &a, const Translation<S,D> &b)\n{\n  return test_relative_error(a.vector(), b.vector());\n}\n\ntemplate <typename S, int D, int O>\nS test_relative_error(const ParametrizedLine<S,D,O> &a, const ParametrizedLine<S,D,O> &b)\n{\n  return (std::max)(test_relative_error(a.origin(), b.origin()), test_relative_error(a.origin(), b.origin()));\n}\n\ntemplate <typename S, int D>\nS test_relative_error(const AlignedBox<S,D> &a, const AlignedBox<S,D> &b)\n{\n  return (std::max)(test_relative_error((a.min)(), (b.min)()), test_relative_error((a.max)(), (b.max)()));\n}\n\ntemplate<typename Derived> class SparseMatrixBase;\ntemplate<typename T1,typename T2>\ntypename T1::RealScalar test_relative_error(const MatrixBase<T1> &a, const SparseMatrixBase<T2> &b)\n{\n  return test_relative_error(a,b.toDense());\n}\n\ntemplate<typename Derived> class SparseMatrixBase;\ntemplate<typename T1,typename T2>\ntypename T1::RealScalar test_relative_error(const SparseMatrixBase<T1> &a, const MatrixBase<T2> &b)\n{\n  return test_relative_error(a.toDense(),b);\n}\n\ntemplate<typename Derived> class SparseMatrixBase;\ntemplate<typename T1,typename T2>\ntypename T1::RealScalar test_relative_error(const SparseMatrixBase<T1> &a, const SparseMatrixBase<T2> &b)\n{\n  return test_relative_error(a.toDense(),b.toDense());\n}\n\ntemplate<typename T1,typename T2>\ntypename NumTraits<typename NumTraits<T1>::Real>::NonInteger test_relative_error(const T1 &a, const T2 &b, typename internal::enable_if<internal::is_arithmetic<typename NumTraits<T1>::Real>::value, T1>::type* = 0)\n{\n  typedef typename NumTraits<typename NumTraits<T1>::Real>::NonInteger RealScalar;\n  return numext::sqrt(RealScalar(numext::abs2(a-b))/(numext::mini)(RealScalar(numext::abs2(a)),RealScalar(numext::abs2(b))));\n}\n\ntemplate<typename T>\nT test_relative_error(const Rotation2D<T> &a, const Rotation2D<T> &b)\n{\n  return test_relative_error(a.angle(), b.angle());\n}\n\ntemplate<typename T>\nT test_relative_error(const AngleAxis<T> &a, const AngleAxis<T> &b)\n{\n  return (std::max)(test_relative_error(a.angle(), b.angle()), test_relative_error(a.axis(), b.axis()));\n}\n\ntemplate<typename Type1, typename Type2>\ninline bool test_isApprox(const Type1& a, const Type2& b, typename Type1::Scalar* = 0) // Enabled for Eigen's type only\n{\n  return a.isApprox(b, test_precision<typename Type1::Scalar>());\n}\n\n// get_test_precision is a small wrapper to test_precision allowing to return the scalar precision for either scalars or expressions\ntemplate<typename T>\ntypename NumTraits<typename T::Scalar>::Real get_test_precision(const T&, const typename T::Scalar* = 0)\n{\n  return test_precision<typename NumTraits<typename T::Scalar>::Real>();\n}\n\ntemplate<typename T>\ntypename NumTraits<T>::Real get_test_precision(const T&,typename internal::enable_if<internal::is_arithmetic<typename NumTraits<T>::Real>::value, T>::type* = 0)\n{\n  return test_precision<typename NumTraits<T>::Real>();\n}\n\n// verifyIsApprox is a wrapper to test_isApprox that outputs the relative difference magnitude if the test fails.\ntemplate<typename Type1, typename Type2>\ninline bool verifyIsApprox(const Type1& a, const Type2& b)\n{\n  bool ret = test_isApprox(a,b);\n  if(!ret)\n  {\n    std::cerr << \"Difference too large wrt tolerance \" << get_test_precision(a)  << \", relative error is: \" << test_relative_error(a,b) << std::endl;\n  }\n  return ret;\n}\n\n// The idea behind this function is to compare the two scalars a and b where\n// the scalar ref is a hint about the expected order of magnitude of a and b.\n// WARNING: the scalar a and b must be positive\n// Therefore, if for some reason a and b are very small compared to ref,\n// we won't issue a false negative.\n// This test could be: abs(a-b) <= eps * ref\n// However, it seems that simply comparing a+ref and b+ref is more sensitive to true error.\ntemplate<typename Scalar,typename ScalarRef>\ninline bool test_isApproxWithRef(const Scalar& a, const Scalar& b, const ScalarRef& ref)\n{\n  return test_isApprox(a+ref, b+ref);\n}\n\ntemplate<typename Derived1, typename Derived2>\ninline bool test_isMuchSmallerThan(const MatrixBase<Derived1>& m1,\n                                   const MatrixBase<Derived2>& m2)\n{\n  return m1.isMuchSmallerThan(m2, test_precision<typename internal::traits<Derived1>::Scalar>());\n}\n\ntemplate<typename Derived>\ninline bool test_isMuchSmallerThan(const MatrixBase<Derived>& m,\n                                   const typename NumTraits<typename internal::traits<Derived>::Scalar>::Real& s)\n{\n  return m.isMuchSmallerThan(s, test_precision<typename internal::traits<Derived>::Scalar>());\n}\n\ntemplate<typename Derived>\ninline bool test_isUnitary(const MatrixBase<Derived>& m)\n{\n  return m.isUnitary(test_precision<typename internal::traits<Derived>::Scalar>());\n}\n\ntemplate<typename T, typename U>\nbool test_is_equal(const T& actual, const U& expected, bool expect_equal)\n{\n    if ((actual==expected) == expect_equal)\n        return true;\n    // false:\n    std::cerr\n        << \"\\n    actual   = \" << actual\n        << \"\\n    expected \" << (expect_equal ? \"= \" : \"!=\") << expected << \"\\n\\n\";\n    return false;\n}\n\n// Forward declaration to avoid ICC warning\ntemplate<typename MatrixType>\nvoid createRandomPIMatrixOfRank(Index desired_rank, Index rows, Index cols, MatrixType& m);\n/**\n * Creates a random partial isometry matrix of given rank.\n *\n * A partial isometry is a matrix all of whose singular values are either 0 or 1.\n * This is very useful to test rank-revealing algorithms.\n *\n * @tparam MatrixType type of random partial isometry matrix\n * @param desired_rank rank requested for the random partial isometry matrix\n * @param rows row dimension of requested random partial isometry matrix\n * @param cols column dimension of requested random partial isometry matrix\n * @param m random partial isometry matrix\n */\ntemplate<typename MatrixType>\nvoid createRandomPIMatrixOfRank(Index desired_rank, Index rows, Index cols, MatrixType& m)\n{\n  typedef typename internal::traits<MatrixType>::Scalar Scalar;\n  enum { Rows = MatrixType::RowsAtCompileTime, Cols = MatrixType::ColsAtCompileTime };\n\n  typedef Matrix<Scalar, Dynamic, 1> VectorType;\n  typedef Matrix<Scalar, Rows, Rows> MatrixAType;\n  typedef Matrix<Scalar, Cols, Cols> MatrixBType;\n\n  if(desired_rank == 0)\n  {\n    m.setZero(rows,cols);\n    return;\n  }\n\n  if(desired_rank == 1)\n  {\n    // here we normalize the vectors to get a partial isometry\n    m = VectorType::Random(rows).normalized() * VectorType::Random(cols).normalized().transpose();\n    return;\n  }\n\n  MatrixAType a = MatrixAType::Random(rows,rows);\n  MatrixType d = MatrixType::Identity(rows,cols);\n  MatrixBType  b = MatrixBType::Random(cols,cols);\n\n  // set the diagonal such that only desired_rank non-zero entries remain\n  const Index diag_size = (std::min)(d.rows(),d.cols());\n  if(diag_size != desired_rank)\n    d.diagonal().segment(desired_rank, diag_size-desired_rank) = VectorType::Zero(diag_size-desired_rank);\n\n  HouseholderQR<MatrixAType> qra(a);\n  HouseholderQR<MatrixBType> qrb(b);\n  m = qra.householderQ() * d * qrb.householderQ();\n}\n\n// Forward declaration to avoid ICC warning\ntemplate<typename PermutationVectorType>\nvoid randomPermutationVector(PermutationVectorType& v, Index size);\n/**\n * Generate random permutation vector.\n *\n * @tparam PermutationVectorType type of vector used to store permutation\n * @param v permutation vector\n * @param size length of permutation vector\n */\ntemplate<typename PermutationVectorType>\nvoid randomPermutationVector(PermutationVectorType& v, Index size)\n{\n  typedef typename PermutationVectorType::Scalar Scalar;\n  v.resize(size);\n  for(Index i = 0; i < size; ++i) v(i) = Scalar(i);\n  if(size == 1) return;\n  for(Index n = 0; n < 3 * size; ++n)\n  {\n    Index i = internal::random<Index>(0, size-1);\n    Index j;\n    do j = internal::random<Index>(0, size-1); while(j==i);\n    std::swap(v(i), v(j));\n  }\n}\n\n/**\n * Generate a random unitary matrix of prescribed dimension.\n *\n * The algorithm is using a random Householder sequence to produce\n * a random unitary matrix.\n *\n * @tparam MatrixType type of matrix to generate\n * @param dim row and column dimension of the requested square matrix\n * @return random unitary matrix\n */\ntemplate<typename MatrixType>\nMatrixType generateRandomUnitaryMatrix(const Index dim)\n{\n  typedef typename internal::traits<MatrixType>::Scalar Scalar;\n  typedef Matrix<Scalar, Dynamic, 1> VectorType;\n\n  MatrixType v = MatrixType::Identity(dim, dim);\n  VectorType h = VectorType::Zero(dim);\n  for (Index i = 0; i < dim; ++i)\n  {\n    v.col(i).tail(dim - i - 1) = VectorType::Random(dim - i - 1);\n    h(i) = 2 / v.col(i).tail(dim - i).squaredNorm();\n  }\n\n  const Eigen::HouseholderSequence<MatrixType, VectorType> HSeq(v, h);\n  return MatrixType(HSeq);\n}\n\n/**\n * Generation of random matrix with prescribed singular values.\n *\n * We generate random matrices with given singular values by setting up\n * a singular value decomposition. By choosing the number of zeros as\n * singular values we can specify the rank of the matrix.\n * Moreover, we also control its spectral norm, which is the largest\n * singular value, as well as its condition number with respect to the\n * l2-norm, which is the quotient of the largest and smallest singular\n * value.\n *\n * Reference: For details on the method see e.g. Section 8.1 (pp. 62 f) in\n *\n *   C. C. Paige, M. A. Saunders,\n *   LSQR: An algorithm for sparse linear equations and sparse least squares.\n *   ACM Transactions on Mathematical Software 8(1), pp. 43-71, 1982.\n *   https://web.stanford.edu/group/SOL/software/lsqr/lsqr-toms82a.pdf\n *\n * and also the LSQR webpage https://web.stanford.edu/group/SOL/software/lsqr/.\n *\n * @tparam MatrixType matrix type to generate\n * @tparam RealScalarVectorType vector type with real entries used for singular values\n * @param svs vector of desired singular values\n * @param rows row dimension of requested random matrix\n * @param cols column dimension of requested random matrix\n * @param M generated matrix with prescribed singular values\n */\ntemplate<typename MatrixType, typename RealScalarVectorType>\nvoid generateRandomMatrixSvs(const RealScalarVectorType &svs, const Index rows, const Index cols, MatrixType& M)\n{\n  enum { Rows = MatrixType::RowsAtCompileTime, Cols = MatrixType::ColsAtCompileTime };\n  typedef typename internal::traits<MatrixType>::Scalar Scalar;\n  typedef Matrix<Scalar, Rows, Rows> MatrixAType;\n  typedef Matrix<Scalar, Cols, Cols> MatrixBType;\n\n  const Index min_dim = (std::min)(rows, cols);\n\n  const MatrixAType U = generateRandomUnitaryMatrix<MatrixAType>(rows);\n  const MatrixBType V = generateRandomUnitaryMatrix<MatrixBType>(cols);\n\n  M = U.block(0, 0, rows, min_dim) * svs.asDiagonal() * V.block(0, 0, cols, min_dim).transpose();\n}\n\n/**\n * Setup a vector of random singular values with prescribed upper limit.\n * For use with generateRandomMatrixSvs().\n *\n * Singular values are non-negative real values. By convention (to be consistent with\n * singular value decomposition) we sort them in decreasing order.\n *\n * This strategy produces random singular values in the range [0, max], in particular\n * the singular values can be zero or arbitrarily close to zero.\n *\n * @tparam VectorType vector type with real entries used for singular values\n * @tparam RealScalar data type used for real entry\n * @param dim number of singular values to generate\n * @param max upper bound for singular values\n * @return vector of singular values\n */\ntemplate<typename VectorType, typename RealScalar>\nVectorType setupRandomSvs(const Index dim, const RealScalar max)\n{\n  VectorType svs = max / RealScalar(2) * (VectorType::Random(dim) + VectorType::Ones(dim));\n  std::sort(svs.begin(), svs.end(), std::greater<RealScalar>());\n  return svs;\n}\n\n/**\n * Setup a vector of random singular values with prescribed range.\n * For use with generateRandomMatrixSvs().\n *\n * Singular values are non-negative real values. By convention (to be consistent with\n * singular value decomposition) we sort them in decreasing order.\n *\n * For dim > 1 this strategy generates a vector with largest entry max, smallest entry\n * min, and remaining entries in the range [min, max]. For dim == 1 the only entry is\n * min.\n *\n * @tparam VectorType vector type with real entries used for singular values\n * @tparam RealScalar data type used for real entry\n * @param dim number of singular values to generate\n * @param min smallest singular value to use\n * @param max largest singular value to use\n * @return vector of singular values\n */\ntemplate<typename VectorType, typename RealScalar>\nVectorType setupRangeSvs(const Index dim, const RealScalar min, const RealScalar max)\n{\n  VectorType svs = VectorType::Random(dim);\n  if(dim == 0)\n    return svs;\n  if(dim == 1)\n  {\n    svs(0) = min;\n    return svs;\n  }\n  std::sort(svs.begin(), svs.end(), std::greater<RealScalar>());\n\n  // scale to range [min, max]\n  const RealScalar c_min = svs(dim - 1), c_max = svs(0);\n  svs = (svs - VectorType::Constant(dim, c_min)) / (c_max - c_min);\n  return min * (VectorType::Ones(dim) - svs) + max * svs;\n}\n\n/**\n * Check if number is \"not a number\" (NaN).\n *\n * @tparam T input type\n * @param x input value\n * @return true, if input value is \"not a number\" (NaN)\n */\ntemplate<typename T> bool isNotNaN(const T& x)\n{\n  return x==x;\n}\n\n/**\n * Check if number is plus infinity.\n *\n * @tparam T input type\n * @param x input value\n * @return true, if input value is plus infinity\n */\ntemplate<typename T> bool isPlusInf(const T& x)\n{\n  return x > NumTraits<T>::highest();\n}\n\n/**\n * Check if number is minus infinity.\n *\n * @tparam T input type\n * @param x input value\n * @return true, if input value is minus infinity\n */\ntemplate<typename T> bool isMinusInf(const T& x)\n{\n  return x < NumTraits<T>::lowest();\n}\n\n} // end namespace Eigen\n\ntemplate<typename T> struct GetDifferentType;\n\ntemplate<> struct GetDifferentType<float> { typedef double type; };\ntemplate<> struct GetDifferentType<double> { typedef float type; };\ntemplate<typename T> struct GetDifferentType<std::complex<T> >\n{ typedef std::complex<typename GetDifferentType<T>::type> type; };\n\ntemplate<typename T> std::string type_name()                    { return \"other\"; }\ntemplate<> std::string type_name<float>()                       { return \"float\"; }\ntemplate<> std::string type_name<double>()                      { return \"double\"; }\ntemplate<> std::string type_name<long double>()                 { return \"long double\"; }\ntemplate<> std::string type_name<int>()                         { return \"int\"; }\ntemplate<> std::string type_name<std::complex<float> >()        { return \"complex<float>\"; }\ntemplate<> std::string type_name<std::complex<double> >()       { return \"complex<double>\"; }\ntemplate<> std::string type_name<std::complex<long double> >()  { return \"complex<long double>\"; }\ntemplate<> std::string type_name<std::complex<int> >()          { return \"complex<int>\"; }\n\nusing namespace Eigen;\n\n/**\n * Set number of repetitions for unit test from input string.\n *\n * @param str input string\n */\ninline void set_repeat_from_string(const char *str)\n{\n  errno = 0;\n  g_repeat = int(strtoul(str, 0, 10));\n  if(errno || g_repeat <= 0)\n  {\n    std::cout << \"Invalid repeat value \" << str << std::endl;\n    exit(EXIT_FAILURE);\n  }\n  g_has_set_repeat = true;\n}\n\n/**\n * Set seed for randomized unit tests from input string.\n *\n * @param str input string\n */\ninline void set_seed_from_string(const char *str)\n{\n  errno = 0;\n  g_seed = int(strtoul(str, 0, 10));\n  if(errno || g_seed == 0)\n  {\n    std::cout << \"Invalid seed value \" << str << std::endl;\n    exit(EXIT_FAILURE);\n  }\n  g_has_set_seed = true;\n}\n\nint main(int argc, char *argv[])\n{\n    g_has_set_repeat = false;\n    g_has_set_seed = false;\n    bool need_help = false;\n\n    for(int i = 1; i < argc; i++)\n    {\n      if(argv[i][0] == 'r')\n      {\n        if(g_has_set_repeat)\n        {\n          std::cout << \"Argument \" << argv[i] << \" conflicting with a former argument\" << std::endl;\n          return 1;\n        }\n        set_repeat_from_string(argv[i]+1);\n      }\n      else if(argv[i][0] == 's')\n      {\n        if(g_has_set_seed)\n        {\n          std::cout << \"Argument \" << argv[i] << \" conflicting with a former argument\" << std::endl;\n          return 1;\n        }\n         set_seed_from_string(argv[i]+1);\n      }\n      else\n      {\n        need_help = true;\n      }\n    }\n\n    if(need_help)\n    {\n      std::cout << \"This test application takes the following optional arguments:\" << std::endl;\n      std::cout << \"  rN     Repeat each test N times (default: \" << DEFAULT_REPEAT << \")\" << std::endl;\n      std::cout << \"  sN     Use N as seed for random numbers (default: based on current time)\" << std::endl;\n      std::cout << std::endl;\n      std::cout << \"If defined, the environment variables EIGEN_REPEAT and EIGEN_SEED\" << std::endl;\n      std::cout << \"will be used as default values for these parameters.\" << std::endl;\n      return 1;\n    }\n\n    char *env_EIGEN_REPEAT = getenv(\"EIGEN_REPEAT\");\n    if(!g_has_set_repeat && env_EIGEN_REPEAT)\n      set_repeat_from_string(env_EIGEN_REPEAT);\n    char *env_EIGEN_SEED = getenv(\"EIGEN_SEED\");\n    if(!g_has_set_seed && env_EIGEN_SEED)\n      set_seed_from_string(env_EIGEN_SEED);\n\n    if(!g_has_set_seed) g_seed = (unsigned int) time(NULL);\n    if(!g_has_set_repeat) g_repeat = DEFAULT_REPEAT;\n\n    std::cout << \"Initializing random number generator with seed \" << g_seed << std::endl;\n    std::stringstream ss;\n    ss << \"Seed: \" << g_seed;\n    g_test_stack.push_back(ss.str());\n    srand(g_seed);\n    std::cout << \"Repeating each test \" << g_repeat << \" times\" << std::endl;\n\n    VERIFY(EigenTest::all().size()>0);\n\n    for(std::size_t i=0; i<EigenTest::all().size(); ++i)\n    {\n      const EigenTest& current_test = *EigenTest::all()[i];\n      Eigen::g_test_stack.push_back(current_test.name());\n      current_test();\n      Eigen::g_test_stack.pop_back();\n    }\n\n    return 0;\n}\n\n// These warning are disabled here such that they are still ON when parsing Eigen's header files.\n#if defined __INTEL_COMPILER\n  // remark #383: value copied to temporary, reference to temporary used\n  //  -> this warning is raised even for legal usage as: g_test_stack.push_back(\"foo\"); where g_test_stack is a std::vector<std::string>\n  // remark #1418: external function definition with no prior declaration\n  //  -> this warning is raised for all our test functions. Declaring them static would fix the issue.\n  // warning #279: controlling expression is constant\n  // remark #1572: floating-point equality and inequality comparisons are unreliable\n  #pragma warning disable 279 383 1418 1572\n#endif\n\n#ifdef _MSC_VER\n  // 4503 - decorated name length exceeded, name was truncated\n  #pragma warning( disable : 4503)\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/mapped_matrix.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_NO_STATIC_ASSERT\n#define EIGEN_NO_STATIC_ASSERT // turn static asserts into runtime asserts in order to check them\n#endif\n\n#include \"main.h\"\n\n#define EIGEN_TESTMAP_MAX_SIZE 256\n\ntemplate<typename VectorType> void map_class_vector(const VectorType& m)\n{\n  typedef typename VectorType::Scalar Scalar;\n\n  Index size = m.size();\n\n  Scalar* array1 = internal::aligned_new<Scalar>(size);\n  Scalar* array2 = internal::aligned_new<Scalar>(size);\n  Scalar* array3 = new Scalar[size+1];\n  Scalar* array3unaligned = (internal::UIntPtr(array3)%EIGEN_MAX_ALIGN_BYTES) == 0 ? array3+1 : array3;\n  Scalar  array4[EIGEN_TESTMAP_MAX_SIZE];\n\n  Map<VectorType, AlignedMax>(array1, size) = VectorType::Random(size);\n  Map<VectorType, AlignedMax>(array2, size) = Map<VectorType,AlignedMax>(array1, size);\n  Map<VectorType>(array3unaligned, size) = Map<VectorType>(array1, size);\n  Map<VectorType>(array4, size)          = Map<VectorType,AlignedMax>(array1, size);\n  VectorType ma1 = Map<VectorType, AlignedMax>(array1, size);\n  VectorType ma2 = Map<VectorType, AlignedMax>(array2, size);\n  VectorType ma3 = Map<VectorType>(array3unaligned, size);\n  VectorType ma4 = Map<VectorType>(array4, size);\n  VERIFY_IS_EQUAL(ma1, ma2);\n  VERIFY_IS_EQUAL(ma1, ma3);\n  VERIFY_IS_EQUAL(ma1, ma4);\n  #ifdef EIGEN_VECTORIZE\n  if(internal::packet_traits<Scalar>::Vectorizable && size>=AlignedMax)\n    VERIFY_RAISES_ASSERT((Map<VectorType,AlignedMax>(array3unaligned, size)))\n  #endif\n\n  internal::aligned_delete(array1, size);\n  internal::aligned_delete(array2, size);\n  delete[] array3;\n}\n\ntemplate<typename MatrixType> void map_class_matrix(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index rows = m.rows(), cols = m.cols(), size = rows*cols;\n  Scalar s1 = internal::random<Scalar>();\n\n  // array1 and array2 -> aligned heap allocation\n  Scalar* array1 = internal::aligned_new<Scalar>(size);\n  for(int i = 0; i < size; i++) array1[i] = Scalar(1);\n  Scalar* array2 = internal::aligned_new<Scalar>(size);\n  for(int i = 0; i < size; i++) array2[i] = Scalar(1);\n  // array3unaligned -> unaligned pointer to heap\n  Scalar* array3 = new Scalar[size+1];\n  Index sizep1 = size + 1; // <- without this temporary MSVC 2103 generates bad code\n  for(Index i = 0; i < sizep1; i++) array3[i] = Scalar(1);\n  Scalar* array3unaligned = (internal::UIntPtr(array3)%EIGEN_MAX_ALIGN_BYTES) == 0 ? array3+1 : array3;\n  Scalar array4[256];\n  if(size<=256)\n    for(int i = 0; i < size; i++) array4[i] = Scalar(1);\n  \n  Map<MatrixType> map1(array1, rows, cols);\n  Map<MatrixType, AlignedMax> map2(array2, rows, cols);\n  Map<MatrixType> map3(array3unaligned, rows, cols);\n  Map<MatrixType> map4(array4, rows, cols);\n  \n  VERIFY_IS_EQUAL(map1, MatrixType::Ones(rows,cols));\n  VERIFY_IS_EQUAL(map2, MatrixType::Ones(rows,cols));\n  VERIFY_IS_EQUAL(map3, MatrixType::Ones(rows,cols));\n  map1 = MatrixType::Random(rows,cols);\n  map2 = map1;\n  map3 = map1;\n  MatrixType ma1 = map1;\n  MatrixType ma2 = map2;\n  MatrixType ma3 = map3;\n  VERIFY_IS_EQUAL(map1, map2);\n  VERIFY_IS_EQUAL(map1, map3);\n  VERIFY_IS_EQUAL(ma1, ma2);\n  VERIFY_IS_EQUAL(ma1, ma3);\n  VERIFY_IS_EQUAL(ma1, map3);\n  \n  VERIFY_IS_APPROX(s1*map1, s1*map2);\n  VERIFY_IS_APPROX(s1*ma1, s1*ma2);\n  VERIFY_IS_EQUAL(s1*ma1, s1*ma3);\n  VERIFY_IS_APPROX(s1*map1, s1*map3);\n  \n  map2 *= s1;\n  map3 *= s1;\n  VERIFY_IS_APPROX(s1*map1, map2);\n  VERIFY_IS_APPROX(s1*map1, map3);\n  \n  if(size<=256)\n  {\n    VERIFY_IS_EQUAL(map4, MatrixType::Ones(rows,cols));\n    map4 = map1;\n    MatrixType ma4 = map4;\n    VERIFY_IS_EQUAL(map1, map4);\n    VERIFY_IS_EQUAL(ma1, map4);\n    VERIFY_IS_EQUAL(ma1, ma4);\n    VERIFY_IS_APPROX(s1*map1, s1*map4);\n    \n    map4 *= s1;\n    VERIFY_IS_APPROX(s1*map1, map4);\n  }\n\n  internal::aligned_delete(array1, size);\n  internal::aligned_delete(array2, size);\n  delete[] array3;\n}\n\ntemplate<typename VectorType> void map_static_methods(const VectorType& m)\n{\n  typedef typename VectorType::Scalar Scalar;\n\n  Index size = m.size();\n\n  Scalar* array1 = internal::aligned_new<Scalar>(size);\n  Scalar* array2 = internal::aligned_new<Scalar>(size);\n  Scalar* array3 = new Scalar[size+1];\n  Scalar* array3unaligned = internal::UIntPtr(array3)%EIGEN_MAX_ALIGN_BYTES == 0 ? array3+1 : array3;\n\n  VectorType::MapAligned(array1, size) = VectorType::Random(size);\n  VectorType::Map(array2, size) = VectorType::Map(array1, size);\n  VectorType::Map(array3unaligned, size) = VectorType::Map(array1, size);\n  VectorType ma1 = VectorType::Map(array1, size);\n  VectorType ma2 = VectorType::MapAligned(array2, size);\n  VectorType ma3 = VectorType::Map(array3unaligned, size);\n  VERIFY_IS_EQUAL(ma1, ma2);\n  VERIFY_IS_EQUAL(ma1, ma3);\n\n  internal::aligned_delete(array1, size);\n  internal::aligned_delete(array2, size);\n  delete[] array3;\n}\n\ntemplate<typename PlainObjectType> void check_const_correctness(const PlainObjectType&)\n{\n  // there's a lot that we can't test here while still having this test compile!\n  // the only possible approach would be to run a script trying to compile stuff and checking that it fails.\n  // CMake can help with that.\n\n  // verify that map-to-const don't have LvalueBit\n  typedef typename internal::add_const<PlainObjectType>::type ConstPlainObjectType;\n  VERIFY( !(internal::traits<Map<ConstPlainObjectType> >::Flags & LvalueBit) );\n  VERIFY( !(internal::traits<Map<ConstPlainObjectType, AlignedMax> >::Flags & LvalueBit) );\n  VERIFY( !(Map<ConstPlainObjectType>::Flags & LvalueBit) );\n  VERIFY( !(Map<ConstPlainObjectType, AlignedMax>::Flags & LvalueBit) );\n}\n\ntemplate<typename Scalar>\nvoid map_not_aligned_on_scalar()\n{\n  typedef Matrix<Scalar,Dynamic,Dynamic> MatrixType;\n  Index size = 11;\n  Scalar* array1 = internal::aligned_new<Scalar>((size+1)*(size+1)+1);\n  Scalar* array2 = reinterpret_cast<Scalar*>(sizeof(Scalar)/2+std::size_t(array1));\n  Map<MatrixType,0,OuterStride<> > map2(array2, size, size, OuterStride<>(size+1));\n  MatrixType m2 = MatrixType::Random(size,size);\n  map2 = m2;\n  VERIFY_IS_EQUAL(m2, map2);\n  \n  typedef Matrix<Scalar,Dynamic,1> VectorType;\n  Map<VectorType> map3(array2, size);\n  MatrixType v3 = VectorType::Random(size);\n  map3 = v3;\n  VERIFY_IS_EQUAL(v3, map3);\n  \n  internal::aligned_delete(array1, (size+1)*(size+1)+1);\n}\n\nEIGEN_DECLARE_TEST(mapped_matrix)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( map_class_vector(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_1( check_const_correctness(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( map_class_vector(Vector4d()) );\n    CALL_SUBTEST_2( map_class_vector(VectorXd(13)) );\n    CALL_SUBTEST_2( check_const_correctness(Matrix4d()) );\n    CALL_SUBTEST_3( map_class_vector(RowVector4f()) );\n    CALL_SUBTEST_4( map_class_vector(VectorXcf(8)) );\n    CALL_SUBTEST_5( map_class_vector(VectorXi(12)) );\n    CALL_SUBTEST_5( check_const_correctness(VectorXi(12)) );\n\n    CALL_SUBTEST_1( map_class_matrix(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( map_class_matrix(Matrix4d()) );\n    CALL_SUBTEST_11( map_class_matrix(Matrix<float,3,5>()) );\n    CALL_SUBTEST_4( map_class_matrix(MatrixXcf(internal::random<int>(1,10),internal::random<int>(1,10))) );\n    CALL_SUBTEST_5( map_class_matrix(MatrixXi(internal::random<int>(1,10),internal::random<int>(1,10))) );\n\n    CALL_SUBTEST_6( map_static_methods(Matrix<double, 1, 1>()) );\n    CALL_SUBTEST_7( map_static_methods(Vector3f()) );\n    CALL_SUBTEST_8( map_static_methods(RowVector3d()) );\n    CALL_SUBTEST_9( map_static_methods(VectorXcd(8)) );\n    CALL_SUBTEST_10( map_static_methods(VectorXf(12)) );\n    CALL_SUBTEST_11( map_not_aligned_on_scalar<double>() );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/mapstaticmethods.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n// GCC<=4.8 has spurious shadow warnings, because `ptr` re-appears inside template instantiations\n// workaround: put these in an anonymous namespace\nnamespace {\nfloat *ptr;\nconst float *const_ptr;\n}\n\ntemplate<typename PlainObjectType,\n         bool IsDynamicSize = PlainObjectType::SizeAtCompileTime == Dynamic,\n         bool IsVector = PlainObjectType::IsVectorAtCompileTime\n>\nstruct mapstaticmethods_impl {};\n\ntemplate<typename PlainObjectType, bool IsVector>\nstruct mapstaticmethods_impl<PlainObjectType, false, IsVector>\n{\n  static void run(const PlainObjectType& m)\n  {\n    mapstaticmethods_impl<PlainObjectType, true, IsVector>::run(m);\n\n    int i = internal::random<int>(2,5), j = internal::random<int>(2,5);\n\n    PlainObjectType::Map(ptr).setZero();\n    PlainObjectType::MapAligned(ptr).setZero();\n    PlainObjectType::Map(const_ptr).sum();\n    PlainObjectType::MapAligned(const_ptr).sum();\n\n    PlainObjectType::Map(ptr, InnerStride<>(i)).setZero();\n    PlainObjectType::MapAligned(ptr, InnerStride<>(i)).setZero();\n    PlainObjectType::Map(const_ptr, InnerStride<>(i)).sum();\n    PlainObjectType::MapAligned(const_ptr, InnerStride<>(i)).sum();\n\n    PlainObjectType::Map(ptr, InnerStride<2>()).setZero();\n    PlainObjectType::MapAligned(ptr, InnerStride<3>()).setZero();\n    PlainObjectType::Map(const_ptr, InnerStride<4>()).sum();\n    PlainObjectType::MapAligned(const_ptr, InnerStride<5>()).sum();\n\n    PlainObjectType::Map(ptr, OuterStride<>(i)).setZero();\n    PlainObjectType::MapAligned(ptr, OuterStride<>(i)).setZero();\n    PlainObjectType::Map(const_ptr, OuterStride<>(i)).sum();\n    PlainObjectType::MapAligned(const_ptr, OuterStride<>(i)).sum();\n\n    PlainObjectType::Map(ptr, OuterStride<2>()).setZero();\n    PlainObjectType::MapAligned(ptr, OuterStride<3>()).setZero();\n    PlainObjectType::Map(const_ptr, OuterStride<4>()).sum();\n    PlainObjectType::MapAligned(const_ptr, OuterStride<5>()).sum();\n\n    PlainObjectType::Map(ptr, Stride<Dynamic, Dynamic>(i,j)).setZero();\n    PlainObjectType::MapAligned(ptr, Stride<2,Dynamic>(2,i)).setZero();\n    PlainObjectType::Map(const_ptr, Stride<Dynamic,3>(i,3)).sum();\n    PlainObjectType::MapAligned(const_ptr, Stride<Dynamic, Dynamic>(i,j)).sum();\n\n    PlainObjectType::Map(ptr, Stride<2,3>()).setZero();\n    PlainObjectType::MapAligned(ptr, Stride<3,4>()).setZero();\n    PlainObjectType::Map(const_ptr, Stride<2,4>()).sum();\n    PlainObjectType::MapAligned(const_ptr, Stride<5,3>()).sum();\n  }\n};\n\ntemplate<typename PlainObjectType>\nstruct mapstaticmethods_impl<PlainObjectType, true, false>\n{\n  static void run(const PlainObjectType& m)\n  {\n    Index rows = m.rows(), cols = m.cols();\n\n    int i = internal::random<int>(2,5), j = internal::random<int>(2,5);\n\n    PlainObjectType::Map(ptr, rows, cols).setZero();\n    PlainObjectType::MapAligned(ptr, rows, cols).setZero();\n    PlainObjectType::Map(const_ptr, rows, cols).sum();\n    PlainObjectType::MapAligned(const_ptr, rows, cols).sum();\n\n    PlainObjectType::Map(ptr, rows, cols, InnerStride<>(i)).setZero();\n    PlainObjectType::MapAligned(ptr, rows, cols, InnerStride<>(i)).setZero();\n    PlainObjectType::Map(const_ptr, rows, cols, InnerStride<>(i)).sum();\n    PlainObjectType::MapAligned(const_ptr, rows, cols, InnerStride<>(i)).sum();\n\n    PlainObjectType::Map(ptr, rows, cols, InnerStride<2>()).setZero();\n    PlainObjectType::MapAligned(ptr, rows, cols, InnerStride<3>()).setZero();\n    PlainObjectType::Map(const_ptr, rows, cols, InnerStride<4>()).sum();\n    PlainObjectType::MapAligned(const_ptr, rows, cols, InnerStride<5>()).sum();\n\n    PlainObjectType::Map(ptr, rows, cols, OuterStride<>(i)).setZero();\n    PlainObjectType::MapAligned(ptr, rows, cols, OuterStride<>(i)).setZero();\n    PlainObjectType::Map(const_ptr, rows, cols, OuterStride<>(i)).sum();\n    PlainObjectType::MapAligned(const_ptr, rows, cols, OuterStride<>(i)).sum();\n\n    PlainObjectType::Map(ptr, rows, cols, OuterStride<2>()).setZero();\n    PlainObjectType::MapAligned(ptr, rows, cols, OuterStride<3>()).setZero();\n    PlainObjectType::Map(const_ptr, rows, cols, OuterStride<4>()).sum();\n    PlainObjectType::MapAligned(const_ptr, rows, cols, OuterStride<5>()).sum();\n\n    PlainObjectType::Map(ptr, rows, cols, Stride<Dynamic, Dynamic>(i,j)).setZero();\n    PlainObjectType::MapAligned(ptr, rows, cols, Stride<2,Dynamic>(2,i)).setZero();\n    PlainObjectType::Map(const_ptr, rows, cols, Stride<Dynamic,3>(i,3)).sum();\n    PlainObjectType::MapAligned(const_ptr, rows, cols, Stride<Dynamic, Dynamic>(i,j)).sum();\n\n    PlainObjectType::Map(ptr, rows, cols, Stride<2,3>()).setZero();\n    PlainObjectType::MapAligned(ptr, rows, cols, Stride<3,4>()).setZero();\n    PlainObjectType::Map(const_ptr, rows, cols, Stride<2,4>()).sum();\n    PlainObjectType::MapAligned(const_ptr, rows, cols, Stride<5,3>()).sum();\n  }\n};\n\ntemplate<typename PlainObjectType>\nstruct mapstaticmethods_impl<PlainObjectType, true, true>\n{\n  static void run(const PlainObjectType& v)\n  {\n    Index size = v.size();\n\n    int i = internal::random<int>(2,5);\n\n    PlainObjectType::Map(ptr, size).setZero();\n    PlainObjectType::MapAligned(ptr, size).setZero();\n    PlainObjectType::Map(const_ptr, size).sum();\n    PlainObjectType::MapAligned(const_ptr, size).sum();\n\n    PlainObjectType::Map(ptr, size, InnerStride<>(i)).setZero();\n    PlainObjectType::MapAligned(ptr, size, InnerStride<>(i)).setZero();\n    PlainObjectType::Map(const_ptr, size, InnerStride<>(i)).sum();\n    PlainObjectType::MapAligned(const_ptr, size, InnerStride<>(i)).sum();\n\n    PlainObjectType::Map(ptr, size, InnerStride<2>()).setZero();\n    PlainObjectType::MapAligned(ptr, size, InnerStride<3>()).setZero();\n    PlainObjectType::Map(const_ptr, size, InnerStride<4>()).sum();\n    PlainObjectType::MapAligned(const_ptr, size, InnerStride<5>()).sum();\n  }\n};\n\ntemplate<typename PlainObjectType>\nvoid mapstaticmethods(const PlainObjectType& m)\n{\n  mapstaticmethods_impl<PlainObjectType>::run(m);\n  VERIFY(true); // just to avoid 'unused function' warning\n}\n\nEIGEN_DECLARE_TEST(mapstaticmethods)\n{\n  ptr = internal::aligned_new<float>(1000);\n  for(int i = 0; i < 1000; i++) ptr[i] = float(i);\n\n  const_ptr = ptr;\n\n  CALL_SUBTEST_1(( mapstaticmethods(Matrix<float, 1, 1>()) ));\n  CALL_SUBTEST_1(( mapstaticmethods(Vector2f()) ));\n  CALL_SUBTEST_2(( mapstaticmethods(Vector3f()) ));\n  CALL_SUBTEST_2(( mapstaticmethods(Matrix2f()) ));\n  CALL_SUBTEST_3(( mapstaticmethods(Matrix4f()) ));\n  CALL_SUBTEST_3(( mapstaticmethods(Array4f()) ));\n  CALL_SUBTEST_4(( mapstaticmethods(Array3f()) ));\n  CALL_SUBTEST_4(( mapstaticmethods(Array33f()) ));\n  CALL_SUBTEST_5(( mapstaticmethods(Array44f()) ));\n  CALL_SUBTEST_5(( mapstaticmethods(VectorXf(1)) ));\n  CALL_SUBTEST_5(( mapstaticmethods(VectorXf(8)) ));\n  CALL_SUBTEST_6(( mapstaticmethods(MatrixXf(1,1)) ));\n  CALL_SUBTEST_6(( mapstaticmethods(MatrixXf(5,7)) ));\n  CALL_SUBTEST_7(( mapstaticmethods(ArrayXf(1)) ));\n  CALL_SUBTEST_7(( mapstaticmethods(ArrayXf(5)) ));\n  CALL_SUBTEST_8(( mapstaticmethods(ArrayXXf(1,1)) ));\n  CALL_SUBTEST_8(( mapstaticmethods(ArrayXXf(8,6)) ));\n\n  internal::aligned_delete(ptr, 1000);\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/mapstride.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<int Alignment,typename VectorType> void map_class_vector(const VectorType& m)\n{\n  typedef typename VectorType::Scalar Scalar;\n\n  Index size = m.size();\n\n  VectorType v = VectorType::Random(size);\n\n  Index arraysize = 3*size;\n  \n  Scalar* a_array = internal::aligned_new<Scalar>(arraysize+1);\n  Scalar* array = a_array;\n  if(Alignment!=Aligned)\n    array = (Scalar*)(internal::IntPtr(a_array) + (internal::packet_traits<Scalar>::AlignedOnScalar?sizeof(Scalar):sizeof(typename NumTraits<Scalar>::Real)));\n\n  {\n    Map<VectorType, Alignment, InnerStride<3> > map(array, size);\n    map = v;\n    for(int i = 0; i < size; ++i)\n    {\n      VERIFY(array[3*i] == v[i]);\n      VERIFY(map[i] == v[i]);\n    }\n  }\n\n  {\n    Map<VectorType, Unaligned, InnerStride<Dynamic> > map(array, size, InnerStride<Dynamic>(2));\n    map = v;\n    for(int i = 0; i < size; ++i)\n    {\n      VERIFY(array[2*i] == v[i]);\n      VERIFY(map[i] == v[i]);\n    }\n  }\n\n  internal::aligned_delete(a_array, arraysize+1);\n}\n\ntemplate<int Alignment,typename MatrixType> void map_class_matrix(const MatrixType& _m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index rows = _m.rows(), cols = _m.cols();\n\n  MatrixType m = MatrixType::Random(rows,cols);\n  Scalar s1 = internal::random<Scalar>();\n\n  Index arraysize = 4*(rows+4)*(cols+4);\n\n  Scalar* a_array1 = internal::aligned_new<Scalar>(arraysize+1);\n  Scalar* array1 = a_array1;\n  if(Alignment!=Aligned)\n    array1 = (Scalar*)(internal::IntPtr(a_array1) + (internal::packet_traits<Scalar>::AlignedOnScalar?sizeof(Scalar):sizeof(typename NumTraits<Scalar>::Real)));\n\n  Scalar a_array2[256];\n  Scalar* array2 = a_array2;\n  if(Alignment!=Aligned)\n    array2 = (Scalar*)(internal::IntPtr(a_array2) + (internal::packet_traits<Scalar>::AlignedOnScalar?sizeof(Scalar):sizeof(typename NumTraits<Scalar>::Real)));\n  else\n    array2 = (Scalar*)(((internal::UIntPtr(a_array2)+EIGEN_MAX_ALIGN_BYTES-1)/EIGEN_MAX_ALIGN_BYTES)*EIGEN_MAX_ALIGN_BYTES);\n  Index maxsize2 = a_array2 - array2 + 256;\n  \n  // test no inner stride and some dynamic outer stride\n  for(int k=0; k<2; ++k)\n  {\n    if(k==1 && (m.innerSize()+1)*m.outerSize() > maxsize2)\n      break;\n    Scalar* array = (k==0 ? array1 : array2);\n    \n    Map<MatrixType, Alignment, OuterStride<Dynamic> > map(array, rows, cols, OuterStride<Dynamic>(m.innerSize()+1));\n    map = m;\n    VERIFY(map.outerStride() == map.innerSize()+1);\n    for(int i = 0; i < m.outerSize(); ++i)\n      for(int j = 0; j < m.innerSize(); ++j)\n      {\n        VERIFY(array[map.outerStride()*i+j] == m.coeffByOuterInner(i,j));\n        VERIFY(map.coeffByOuterInner(i,j) == m.coeffByOuterInner(i,j));\n      }\n    VERIFY_IS_APPROX(s1*map,s1*m);\n    map *= s1;\n    VERIFY_IS_APPROX(map,s1*m);\n  }\n\n  // test no inner stride and an outer stride of +4. This is quite important as for fixed-size matrices,\n  // this allows to hit the special case where it's vectorizable.\n  for(int k=0; k<2; ++k)\n  {\n    if(k==1 && (m.innerSize()+4)*m.outerSize() > maxsize2)\n      break;\n    Scalar* array = (k==0 ? array1 : array2);\n    \n    enum {\n      InnerSize = MatrixType::InnerSizeAtCompileTime,\n      OuterStrideAtCompileTime = InnerSize==Dynamic ? Dynamic : InnerSize+4\n    };\n    Map<MatrixType, Alignment, OuterStride<OuterStrideAtCompileTime> >\n      map(array, rows, cols, OuterStride<OuterStrideAtCompileTime>(m.innerSize()+4));\n    map = m;\n    VERIFY(map.outerStride() == map.innerSize()+4);\n    for(int i = 0; i < m.outerSize(); ++i)\n      for(int j = 0; j < m.innerSize(); ++j)\n      {\n        VERIFY(array[map.outerStride()*i+j] == m.coeffByOuterInner(i,j));\n        VERIFY(map.coeffByOuterInner(i,j) == m.coeffByOuterInner(i,j));\n      }\n    VERIFY_IS_APPROX(s1*map,s1*m);\n    map *= s1;\n    VERIFY_IS_APPROX(map,s1*m);\n  }\n\n  // test both inner stride and outer stride\n  for(int k=0; k<2; ++k)\n  {\n    if(k==1 && (2*m.innerSize()+1)*(m.outerSize()*2) > maxsize2)\n      break;\n    Scalar* array = (k==0 ? array1 : array2);\n    \n    Map<MatrixType, Alignment, Stride<Dynamic,Dynamic> > map(array, rows, cols, Stride<Dynamic,Dynamic>(2*m.innerSize()+1, 2));\n    map = m;\n    VERIFY(map.outerStride() == 2*map.innerSize()+1);\n    VERIFY(map.innerStride() == 2);\n    for(int i = 0; i < m.outerSize(); ++i)\n      for(int j = 0; j < m.innerSize(); ++j)\n      {\n        VERIFY(array[map.outerStride()*i+map.innerStride()*j] == m.coeffByOuterInner(i,j));\n        VERIFY(map.coeffByOuterInner(i,j) == m.coeffByOuterInner(i,j));\n      }\n    VERIFY_IS_APPROX(s1*map,s1*m);\n    map *= s1;\n    VERIFY_IS_APPROX(map,s1*m);\n  }\n\n  // test inner stride and no outer stride\n  for(int k=0; k<2; ++k)\n  {\n    if(k==1 && (m.innerSize()*2)*m.outerSize() > maxsize2)\n      break;\n    Scalar* array = (k==0 ? array1 : array2);\n\n    Map<MatrixType, Alignment, InnerStride<Dynamic> > map(array, rows, cols, InnerStride<Dynamic>(2));\n    map = m;\n    VERIFY(map.outerStride() == map.innerSize()*2);\n    for(int i = 0; i < m.outerSize(); ++i)\n      for(int j = 0; j < m.innerSize(); ++j)\n      {\n        VERIFY(array[map.innerSize()*i*2+j*2] == m.coeffByOuterInner(i,j));\n        VERIFY(map.coeffByOuterInner(i,j) == m.coeffByOuterInner(i,j));\n      }\n    VERIFY_IS_APPROX(s1*map,s1*m);\n    map *= s1;\n    VERIFY_IS_APPROX(map,s1*m);\n  }\n\n  // test negative strides\n  {\n    Matrix<Scalar,Dynamic,1>::Map(a_array1, arraysize+1).setRandom();\n    Index outerstride = m.innerSize()+4;\n    Scalar* array = array1;\n\n    {\n      Map<MatrixType, Alignment, OuterStride<> > map1(array, rows, cols, OuterStride<>( outerstride));\n      Map<MatrixType, Unaligned, OuterStride<> > map2(array+(m.outerSize()-1)*outerstride, rows, cols, OuterStride<>(-outerstride));\n      if(MatrixType::IsRowMajor)  VERIFY_IS_APPROX(map1.colwise().reverse(), map2);\n      else                        VERIFY_IS_APPROX(map1.rowwise().reverse(), map2);\n    }\n\n    {\n      Map<MatrixType, Alignment, OuterStride<> > map1(array, rows, cols, OuterStride<>( outerstride));\n      Map<MatrixType, Unaligned, Stride<Dynamic,Dynamic> > map2(array+(m.outerSize()-1)*outerstride+m.innerSize()-1, rows, cols, Stride<Dynamic,Dynamic>(-outerstride,-1));\n      VERIFY_IS_APPROX(map1.reverse(), map2);\n    }\n\n    {\n      Map<MatrixType, Alignment, OuterStride<> > map1(array, rows, cols, OuterStride<>( outerstride));\n      Map<MatrixType, Unaligned, Stride<Dynamic,-1> > map2(array+(m.outerSize()-1)*outerstride+m.innerSize()-1, rows, cols, Stride<Dynamic,-1>(-outerstride,-1));\n      VERIFY_IS_APPROX(map1.reverse(), map2);\n    }\n  }\n\n  internal::aligned_delete(a_array1, arraysize+1);\n}\n\n// Additional tests for inner-stride but no outer-stride\ntemplate<int>\nvoid bug1453()\n{\n  const int data[] = {0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31};\n  typedef Matrix<int,Dynamic,Dynamic,RowMajor> RowMatrixXi;\n  typedef Matrix<int,2,3,ColMajor> ColMatrix23i;\n  typedef Matrix<int,3,2,ColMajor> ColMatrix32i;\n  typedef Matrix<int,2,3,RowMajor> RowMatrix23i;\n  typedef Matrix<int,3,2,RowMajor> RowMatrix32i;\n\n  VERIFY_IS_APPROX(MatrixXi::Map(data, 2, 3, InnerStride<2>()), MatrixXi::Map(data, 2, 3, Stride<4,2>()));\n  VERIFY_IS_APPROX(MatrixXi::Map(data, 2, 3, InnerStride<>(2)), MatrixXi::Map(data, 2, 3, Stride<4,2>()));\n  VERIFY_IS_APPROX(MatrixXi::Map(data, 3, 2, InnerStride<2>()), MatrixXi::Map(data, 3, 2, Stride<6,2>()));\n  VERIFY_IS_APPROX(MatrixXi::Map(data, 3, 2, InnerStride<>(2)), MatrixXi::Map(data, 3, 2, Stride<6,2>()));\n\n  VERIFY_IS_APPROX(RowMatrixXi::Map(data, 2, 3, InnerStride<2>()), RowMatrixXi::Map(data, 2, 3, Stride<6,2>()));\n  VERIFY_IS_APPROX(RowMatrixXi::Map(data, 2, 3, InnerStride<>(2)), RowMatrixXi::Map(data, 2, 3, Stride<6,2>()));\n  VERIFY_IS_APPROX(RowMatrixXi::Map(data, 3, 2, InnerStride<2>()), RowMatrixXi::Map(data, 3, 2, Stride<4,2>()));\n  VERIFY_IS_APPROX(RowMatrixXi::Map(data, 3, 2, InnerStride<>(2)), RowMatrixXi::Map(data, 3, 2, Stride<4,2>()));\n\n  VERIFY_IS_APPROX(ColMatrix23i::Map(data, InnerStride<2>()), MatrixXi::Map(data, 2, 3, Stride<4,2>()));\n  VERIFY_IS_APPROX(ColMatrix23i::Map(data, InnerStride<>(2)), MatrixXi::Map(data, 2, 3, Stride<4,2>()));\n  VERIFY_IS_APPROX(ColMatrix32i::Map(data, InnerStride<2>()), MatrixXi::Map(data, 3, 2, Stride<6,2>()));\n  VERIFY_IS_APPROX(ColMatrix32i::Map(data, InnerStride<>(2)), MatrixXi::Map(data, 3, 2, Stride<6,2>()));\n\n  VERIFY_IS_APPROX(RowMatrix23i::Map(data, InnerStride<2>()), RowMatrixXi::Map(data, 2, 3, Stride<6,2>()));\n  VERIFY_IS_APPROX(RowMatrix23i::Map(data, InnerStride<>(2)), RowMatrixXi::Map(data, 2, 3, Stride<6,2>()));\n  VERIFY_IS_APPROX(RowMatrix32i::Map(data, InnerStride<2>()), RowMatrixXi::Map(data, 3, 2, Stride<4,2>()));\n  VERIFY_IS_APPROX(RowMatrix32i::Map(data, InnerStride<>(2)), RowMatrixXi::Map(data, 3, 2, Stride<4,2>()));\n}\n\nEIGEN_DECLARE_TEST(mapstride)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    int maxn = 3;\n    CALL_SUBTEST_1( map_class_vector<Aligned>(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_1( map_class_vector<Unaligned>(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( map_class_vector<Aligned>(Vector4d()) );\n    CALL_SUBTEST_2( map_class_vector<Unaligned>(Vector4d()) );\n    CALL_SUBTEST_3( map_class_vector<Aligned>(RowVector4f()) );\n    CALL_SUBTEST_3( map_class_vector<Unaligned>(RowVector4f()) );\n    CALL_SUBTEST_4( map_class_vector<Aligned>(VectorXcf(internal::random<int>(1,maxn))) );\n    CALL_SUBTEST_4( map_class_vector<Unaligned>(VectorXcf(internal::random<int>(1,maxn))) );\n    CALL_SUBTEST_5( map_class_vector<Aligned>(VectorXi(internal::random<int>(1,maxn))) );\n    CALL_SUBTEST_5( map_class_vector<Unaligned>(VectorXi(internal::random<int>(1,maxn))) );\n\n    CALL_SUBTEST_1( map_class_matrix<Aligned>(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_1( map_class_matrix<Unaligned>(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( map_class_matrix<Aligned>(Matrix4d()) );\n    CALL_SUBTEST_2( map_class_matrix<Unaligned>(Matrix4d()) );\n    CALL_SUBTEST_3( map_class_matrix<Aligned>(Matrix<float,3,5>()) );\n    CALL_SUBTEST_3( map_class_matrix<Unaligned>(Matrix<float,3,5>()) );\n    CALL_SUBTEST_3( map_class_matrix<Aligned>(Matrix<float,4,8>()) );\n    CALL_SUBTEST_3( map_class_matrix<Unaligned>(Matrix<float,4,8>()) );\n    CALL_SUBTEST_4( map_class_matrix<Aligned>(MatrixXcf(internal::random<int>(1,maxn),internal::random<int>(1,maxn))) );\n    CALL_SUBTEST_4( map_class_matrix<Unaligned>(MatrixXcf(internal::random<int>(1,maxn),internal::random<int>(1,maxn))) );\n    CALL_SUBTEST_5( map_class_matrix<Aligned>(MatrixXi(internal::random<int>(1,maxn),internal::random<int>(1,maxn))) );\n    CALL_SUBTEST_5( map_class_matrix<Unaligned>(MatrixXi(internal::random<int>(1,maxn),internal::random<int>(1,maxn))) );\n    CALL_SUBTEST_6( map_class_matrix<Aligned>(MatrixXcd(internal::random<int>(1,maxn),internal::random<int>(1,maxn))) );\n    CALL_SUBTEST_6( map_class_matrix<Unaligned>(MatrixXcd(internal::random<int>(1,maxn),internal::random<int>(1,maxn))) );\n\n    CALL_SUBTEST_5( bug1453<0>() );\n    \n    TEST_SET_BUT_UNUSED_VARIABLE(maxn);\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/meta.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename From, typename To>\nbool check_is_convertible(const From&, const To&)\n{\n  return internal::is_convertible<From,To>::value;\n}\n\nstruct FooReturnType {\n  typedef int ReturnType;\n};\n\nstruct MyInterface {\n  virtual void func() = 0;\n  virtual ~MyInterface() {}\n};\nstruct MyImpl : public MyInterface {\n  void func() {}\n};\n\nEIGEN_DECLARE_TEST(meta)\n{\n  VERIFY((internal::conditional<(3<4),internal::true_type, internal::false_type>::type::value));\n  VERIFY(( internal::is_same<float,float>::value));\n  VERIFY((!internal::is_same<float,double>::value));\n  VERIFY((!internal::is_same<float,float&>::value));\n  VERIFY((!internal::is_same<float,const float&>::value));\n\n  VERIFY(( internal::is_same<float,internal::remove_all<const float&>::type >::value));\n  VERIFY(( internal::is_same<float,internal::remove_all<const float*>::type >::value));\n  VERIFY(( internal::is_same<float,internal::remove_all<const float*&>::type >::value));\n  VERIFY(( internal::is_same<float,internal::remove_all<float**>::type >::value));\n  VERIFY(( internal::is_same<float,internal::remove_all<float**&>::type >::value));\n  VERIFY(( internal::is_same<float,internal::remove_all<float* const *&>::type >::value));\n  VERIFY(( internal::is_same<float,internal::remove_all<float* const>::type >::value));\n\n  // test add_const\n  VERIFY(( internal::is_same< internal::add_const<float>::type, const float >::value));\n  VERIFY(( internal::is_same< internal::add_const<float*>::type, float* const>::value));\n  VERIFY(( internal::is_same< internal::add_const<float const*>::type, float const* const>::value));\n  VERIFY(( internal::is_same< internal::add_const<float&>::type, float& >::value));\n\n  // test remove_const\n  VERIFY(( internal::is_same< internal::remove_const<float const* const>::type, float const* >::value));\n  VERIFY(( internal::is_same< internal::remove_const<float const*>::type, float const* >::value));\n  VERIFY(( internal::is_same< internal::remove_const<float* const>::type, float* >::value));\n\n  // test add_const_on_value_type\n  VERIFY(( internal::is_same< internal::add_const_on_value_type<float&>::type, float const& >::value));\n  VERIFY(( internal::is_same< internal::add_const_on_value_type<float*>::type, float const* >::value));\n\n  VERIFY(( internal::is_same< internal::add_const_on_value_type<float>::type, const float >::value));\n  VERIFY(( internal::is_same< internal::add_const_on_value_type<const float>::type, const float >::value));\n\n  VERIFY(( internal::is_same< internal::add_const_on_value_type<const float* const>::type, const float* const>::value));\n  VERIFY(( internal::is_same< internal::add_const_on_value_type<float* const>::type, const float* const>::value));\n\n  VERIFY(( internal::is_same<float,internal::remove_reference<float&>::type >::value));\n  VERIFY(( internal::is_same<const float,internal::remove_reference<const float&>::type >::value));\n  VERIFY(( internal::is_same<float,internal::remove_pointer<float*>::type >::value));\n  VERIFY(( internal::is_same<const float,internal::remove_pointer<const float*>::type >::value));\n  VERIFY(( internal::is_same<float,internal::remove_pointer<float* const >::type >::value));\n\n\n  // is_convertible\n  STATIC_CHECK(( internal::is_convertible<float,double>::value ));\n  STATIC_CHECK(( internal::is_convertible<int,double>::value ));\n  STATIC_CHECK(( internal::is_convertible<int, short>::value ));\n  STATIC_CHECK(( internal::is_convertible<short, int>::value ));\n  STATIC_CHECK(( internal::is_convertible<double,int>::value ));\n  STATIC_CHECK(( internal::is_convertible<double,std::complex<double> >::value ));\n  STATIC_CHECK((!internal::is_convertible<std::complex<double>,double>::value ));\n  STATIC_CHECK(( internal::is_convertible<Array33f,Matrix3f>::value ));\n  STATIC_CHECK(( internal::is_convertible<Matrix3f&,Matrix3f>::value ));\n  STATIC_CHECK(( internal::is_convertible<Matrix3f&,Matrix3f&>::value ));\n  STATIC_CHECK(( internal::is_convertible<Matrix3f&,const Matrix3f&>::value ));\n  STATIC_CHECK(( internal::is_convertible<const Matrix3f&,Matrix3f>::value ));\n  STATIC_CHECK(( internal::is_convertible<const Matrix3f&,const Matrix3f&>::value ));\n  STATIC_CHECK((!internal::is_convertible<const Matrix3f&,Matrix3f&>::value ));\n  STATIC_CHECK((!internal::is_convertible<const Matrix3f,Matrix3f&>::value ));\n  STATIC_CHECK(!( internal::is_convertible<Matrix3f,Matrix3f&>::value ));\n\n  STATIC_CHECK(!( internal::is_convertible<int,int&>::value ));\n  STATIC_CHECK(( internal::is_convertible<const int,const int& >::value ));\n\n  //STATIC_CHECK((!internal::is_convertible<Matrix3f,Matrix3d>::value )); //does not even compile because the conversion is prevented by a static assertion\n  STATIC_CHECK((!internal::is_convertible<Array33f,int>::value ));\n  STATIC_CHECK((!internal::is_convertible<MatrixXf,float>::value ));\n  {\n    float f = 0.0f;\n    MatrixXf A, B;\n    VectorXf a, b;\n    VERIFY(( check_is_convertible(a.dot(b), f) ));\n    VERIFY(( check_is_convertible(a.transpose()*b, f) ));\n    VERIFY((!check_is_convertible(A*B, f) ));\n    VERIFY(( check_is_convertible(A*B, A) ));\n  }\n\n  #if (EIGEN_COMP_GNUC  && EIGEN_COMP_GNUC  <=  99) \\\n   || (EIGEN_COMP_CLANG && EIGEN_COMP_CLANG <= 909) \\\n   || (EIGEN_COMP_MSVC  && EIGEN_COMP_MSVC  <=1914)\n  // See http://eigen.tuxfamily.org/bz/show_bug.cgi?id=1752,\n  // basically, a fix in the c++ standard breaks our c++98 implementation\n  // of is_convertible for abstract classes.\n  // So the following tests are expected to fail with recent compilers.\n\n  STATIC_CHECK(( !internal::is_convertible<MyInterface, MyImpl>::value ));\n  #if (!EIGEN_COMP_GNUC_STRICT) || (EIGEN_GNUC_AT_LEAST(4,8))\n  // GCC prior to 4.8 fails to compile this test:\n  // error: cannot allocate an object of abstract type 'MyInterface'\n  // In other word, it does not obey SFINAE.\n  // Nevertheless, we don't really care about supporting abstract type as scalar type!\n  STATIC_CHECK(( !internal::is_convertible<MyImpl, MyInterface>::value ));\n  #endif\n  STATIC_CHECK((  internal::is_convertible<MyImpl, const MyInterface&>::value ));\n\n  #endif\n\n  {\n    int i = 0;\n    VERIFY(( check_is_convertible(fix<3>(), i) ));\n    VERIFY((!check_is_convertible(i, fix<DynamicIndex>()) ));\n  }\n\n\n  VERIFY((  internal::has_ReturnType<FooReturnType>::value ));\n  VERIFY((  internal::has_ReturnType<ScalarBinaryOpTraits<int,int> >::value ));\n  VERIFY(( !internal::has_ReturnType<MatrixXf>::value ));\n  VERIFY(( !internal::has_ReturnType<int>::value ));\n\n  VERIFY(internal::meta_sqrt<1>::ret == 1);\n  #define VERIFY_META_SQRT(X) VERIFY(internal::meta_sqrt<X>::ret == int(std::sqrt(double(X))))\n  VERIFY_META_SQRT(2);\n  VERIFY_META_SQRT(3);\n  VERIFY_META_SQRT(4);\n  VERIFY_META_SQRT(5);\n  VERIFY_META_SQRT(6);\n  VERIFY_META_SQRT(8);\n  VERIFY_META_SQRT(9);\n  VERIFY_META_SQRT(15);\n  VERIFY_META_SQRT(16);\n  VERIFY_META_SQRT(17);\n  VERIFY_META_SQRT(255);\n  VERIFY_META_SQRT(256);\n  VERIFY_META_SQRT(257);\n  VERIFY_META_SQRT(1023);\n  VERIFY_META_SQRT(1024);\n  VERIFY_META_SQRT(1025);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/metis_support.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"sparse_solver.h\"\n#include <Eigen/SparseLU>\n#include <Eigen/MetisSupport>\n#include <unsupported/Eigen/SparseExtra>\n\ntemplate<typename T> void test_metis_T()\n{\n  SparseLU<SparseMatrix<T, ColMajor>, MetisOrdering<int> > sparselu_metis;\n  \n  check_sparse_square_solving(sparselu_metis); \n}\n\nEIGEN_DECLARE_TEST(metis_support)\n{\n  CALL_SUBTEST_1(test_metis_T<double>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/miscmatrices.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void miscMatrices(const MatrixType& m)\n{\n  /* this test covers the following files:\n     DiagonalMatrix.h Ones.h\n  */\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  Index r = internal::random<Index>(0, rows-1), r2 = internal::random<Index>(0, rows-1), c = internal::random<Index>(0, cols-1);\n  VERIFY_IS_APPROX(MatrixType::Ones(rows,cols)(r,c), static_cast<Scalar>(1));\n  MatrixType m1 = MatrixType::Ones(rows,cols);\n  VERIFY_IS_APPROX(m1(r,c), static_cast<Scalar>(1));\n  VectorType v1 = VectorType::Random(rows);\n  v1[0];\n  Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime>\n  square(v1.asDiagonal());\n  if(r==r2) VERIFY_IS_APPROX(square(r,r2), v1[r]);\n  else VERIFY_IS_MUCH_SMALLER_THAN(square(r,r2), static_cast<Scalar>(1));\n  square = MatrixType::Zero(rows, rows);\n  square.diagonal() = VectorType::Ones(rows);\n  VERIFY_IS_APPROX(square, MatrixType::Identity(rows, rows));\n}\n\nEIGEN_DECLARE_TEST(miscmatrices)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( miscMatrices(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( miscMatrices(Matrix4d()) );\n    CALL_SUBTEST_3( miscMatrices(MatrixXcf(3, 3)) );\n    CALL_SUBTEST_4( miscMatrices(MatrixXi(8, 12)) );\n    CALL_SUBTEST_5( miscMatrices(MatrixXcd(20, 20)) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/mixingtypes.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#if defined(EIGEN_TEST_PART_7)\n\n#ifndef EIGEN_NO_STATIC_ASSERT\n#define EIGEN_NO_STATIC_ASSERT // turn static asserts into runtime asserts in order to check them\n#endif\n\n// ignore double-promotion diagnostic for clang and gcc, if we check for static assertion anyway:\n// TODO do the same for MSVC?\n#if defined(__clang__)\n#  if (__clang_major__ * 100 + __clang_minor__) >= 308\n#    pragma clang diagnostic ignored \"-Wdouble-promotion\"\n#  endif\n#elif defined(__GNUC__)\n  // TODO is there a minimal GCC version for this? At least g++-4.7 seems to be fine with this.\n#  pragma GCC diagnostic ignored \"-Wdouble-promotion\"\n#endif\n\n#endif\n\n\n\n#if defined(EIGEN_TEST_PART_1) || defined(EIGEN_TEST_PART_2) || defined(EIGEN_TEST_PART_3)\n\n#ifndef EIGEN_DONT_VECTORIZE\n#define EIGEN_DONT_VECTORIZE\n#endif\n\n#endif\n\nstatic bool g_called;\n#define EIGEN_SCALAR_BINARY_OP_PLUGIN { g_called |= (!internal::is_same<LhsScalar,RhsScalar>::value); }\n\n#include \"main.h\"\n\nusing namespace std;\n\n#define VERIFY_MIX_SCALAR(XPR,REF) \\\n  g_called = false; \\\n  VERIFY_IS_APPROX(XPR,REF); \\\n  VERIFY( g_called && #XPR\" not properly optimized\");\n\ntemplate<int SizeAtCompileType>\nvoid raise_assertion(Index size = SizeAtCompileType)\n{\n  // VERIFY_RAISES_ASSERT(mf+md); // does not even compile\n  Matrix<float, SizeAtCompileType, 1> vf; vf.setRandom(size);\n  Matrix<double, SizeAtCompileType, 1> vd; vd.setRandom(size);\n  VERIFY_RAISES_ASSERT(vf=vd);\n  VERIFY_RAISES_ASSERT(vf+=vd);\n  VERIFY_RAISES_ASSERT(vf-=vd);\n  VERIFY_RAISES_ASSERT(vd=vf);\n  VERIFY_RAISES_ASSERT(vd+=vf);\n  VERIFY_RAISES_ASSERT(vd-=vf);\n\n  //   vd.asDiagonal() * mf;    // does not even compile\n  //   vcd.asDiagonal() * mf;   // does not even compile\n\n#if 0 // we get other compilation errors here than just static asserts\n  VERIFY_RAISES_ASSERT(vd.dot(vf));\n#endif\n}\n\n\ntemplate<int SizeAtCompileType> void mixingtypes(int size = SizeAtCompileType)\n{\n  typedef std::complex<float>   CF;\n  typedef std::complex<double>  CD;\n  typedef Matrix<float, SizeAtCompileType, SizeAtCompileType> Mat_f;\n  typedef Matrix<double, SizeAtCompileType, SizeAtCompileType> Mat_d;\n  typedef Matrix<std::complex<float>, SizeAtCompileType, SizeAtCompileType> Mat_cf;\n  typedef Matrix<std::complex<double>, SizeAtCompileType, SizeAtCompileType> Mat_cd;\n  typedef Matrix<float, SizeAtCompileType, 1> Vec_f;\n  typedef Matrix<double, SizeAtCompileType, 1> Vec_d;\n  typedef Matrix<std::complex<float>, SizeAtCompileType, 1> Vec_cf;\n  typedef Matrix<std::complex<double>, SizeAtCompileType, 1> Vec_cd;\n\n  Mat_f mf    = Mat_f::Random(size,size);\n  Mat_d md    = mf.template cast<double>();\n  //Mat_d rd    = md;\n  Mat_cf mcf  = Mat_cf::Random(size,size);\n  Mat_cd mcd  = mcf.template cast<complex<double> >();\n  Mat_cd rcd = mcd;\n  Vec_f vf    = Vec_f::Random(size,1);\n  Vec_d vd    = vf.template cast<double>();\n  Vec_cf vcf  = Vec_cf::Random(size,1);\n  Vec_cd vcd  = vcf.template cast<complex<double> >();\n  float           sf  = internal::random<float>();\n  double          sd  = internal::random<double>();\n  complex<float>  scf = internal::random<complex<float> >();\n  complex<double> scd = internal::random<complex<double> >();\n\n  mf+mf;\n\n  float  epsf = std::sqrt(std::numeric_limits<float> ::min EIGEN_EMPTY ());\n  double epsd = std::sqrt(std::numeric_limits<double>::min EIGEN_EMPTY ());\n\n  while(std::abs(sf )<epsf) sf  = internal::random<float>();\n  while(std::abs(sd )<epsd) sd  = internal::random<double>();\n  while(std::abs(scf)<epsf) scf = internal::random<CF>();\n  while(std::abs(scd)<epsd) scd = internal::random<CD>();\n\n  // check scalar products\n  VERIFY_MIX_SCALAR(vcf * sf , vcf * complex<float>(sf));\n  VERIFY_MIX_SCALAR(sd * vcd , complex<double>(sd) * vcd);\n  VERIFY_MIX_SCALAR(vf * scf , vf.template cast<complex<float> >() * scf);\n  VERIFY_MIX_SCALAR(scd * vd , scd * vd.template cast<complex<double> >());\n\n  VERIFY_MIX_SCALAR(vcf * 2 , vcf * complex<float>(2));\n  VERIFY_MIX_SCALAR(vcf * 2.1 , vcf * complex<float>(2.1));\n  VERIFY_MIX_SCALAR(2 * vcf, vcf * complex<float>(2));\n  VERIFY_MIX_SCALAR(2.1 * vcf , vcf * complex<float>(2.1));\n\n  // check scalar quotients\n  VERIFY_MIX_SCALAR(vcf / sf , vcf / complex<float>(sf));\n  VERIFY_MIX_SCALAR(vf / scf , vf.template cast<complex<float> >() / scf);\n  VERIFY_MIX_SCALAR(vf.array()  / scf, vf.template cast<complex<float> >().array() / scf);\n  VERIFY_MIX_SCALAR(scd / vd.array() , scd / vd.template cast<complex<double> >().array());\n\n  // check scalar increment\n  VERIFY_MIX_SCALAR(vcf.array() + sf , vcf.array() + complex<float>(sf));\n  VERIFY_MIX_SCALAR(sd  + vcd.array(), complex<double>(sd) + vcd.array());\n  VERIFY_MIX_SCALAR(vf.array()  + scf, vf.template cast<complex<float> >().array() + scf);\n  VERIFY_MIX_SCALAR(scd + vd.array() , scd + vd.template cast<complex<double> >().array());\n\n  // check scalar subtractions\n  VERIFY_MIX_SCALAR(vcf.array() - sf , vcf.array() - complex<float>(sf));\n  VERIFY_MIX_SCALAR(sd  - vcd.array(), complex<double>(sd) - vcd.array());\n  VERIFY_MIX_SCALAR(vf.array()  - scf, vf.template cast<complex<float> >().array() - scf);\n  VERIFY_MIX_SCALAR(scd - vd.array() , scd - vd.template cast<complex<double> >().array());\n\n  // check scalar powers\n  VERIFY_MIX_SCALAR( pow(vcf.array(), sf),        Eigen::pow(vcf.array(), complex<float>(sf)) );\n  VERIFY_MIX_SCALAR( vcf.array().pow(sf) ,        Eigen::pow(vcf.array(), complex<float>(sf)) );\n  VERIFY_MIX_SCALAR( pow(sd, vcd.array()),        Eigen::pow(complex<double>(sd), vcd.array()) );\n  VERIFY_MIX_SCALAR( Eigen::pow(vf.array(), scf), Eigen::pow(vf.template cast<complex<float> >().array(), scf) );\n  VERIFY_MIX_SCALAR( vf.array().pow(scf) ,        Eigen::pow(vf.template cast<complex<float> >().array(), scf) );\n  VERIFY_MIX_SCALAR( Eigen::pow(scd, vd.array()), Eigen::pow(scd, vd.template cast<complex<double> >().array()) );\n\n  // check dot product\n  vf.dot(vf);\n  VERIFY_IS_APPROX(vcf.dot(vf), vcf.dot(vf.template cast<complex<float> >()));\n\n  // check diagonal product\n  VERIFY_IS_APPROX(vf.asDiagonal() * mcf, vf.template cast<complex<float> >().asDiagonal() * mcf);\n  VERIFY_IS_APPROX(vcd.asDiagonal() * md, vcd.asDiagonal() * md.template cast<complex<double> >());\n  VERIFY_IS_APPROX(mcf * vf.asDiagonal(), mcf * vf.template cast<complex<float> >().asDiagonal());\n  VERIFY_IS_APPROX(md * vcd.asDiagonal(), md.template cast<complex<double> >() * vcd.asDiagonal());\n\n  // check inner product\n  VERIFY_IS_APPROX((vf.transpose() * vcf).value(), (vf.template cast<complex<float> >().transpose() * vcf).value());\n\n  // check outer product\n  VERIFY_IS_APPROX((vf * vcf.transpose()).eval(), (vf.template cast<complex<float> >() * vcf.transpose()).eval());\n\n  // coeff wise product\n\n  VERIFY_IS_APPROX((vf * vcf.transpose()).eval(), (vf.template cast<complex<float> >() * vcf.transpose()).eval());\n\n  Mat_cd mcd2 = mcd;\n  VERIFY_IS_APPROX(mcd.array() *= md.array(), mcd2.array() *= md.array().template cast<std::complex<double> >());\n  \n  // check matrix-matrix products\n  VERIFY_IS_APPROX(sd*md*mcd, (sd*md).template cast<CD>().eval()*mcd);\n  VERIFY_IS_APPROX(sd*mcd*md, sd*mcd*md.template cast<CD>());\n  VERIFY_IS_APPROX(scd*md*mcd, scd*md.template cast<CD>().eval()*mcd);\n  VERIFY_IS_APPROX(scd*mcd*md, scd*mcd*md.template cast<CD>());\n\n  VERIFY_IS_APPROX(sf*mf*mcf, sf*mf.template cast<CF>()*mcf);\n  VERIFY_IS_APPROX(sf*mcf*mf, sf*mcf*mf.template cast<CF>());\n  VERIFY_IS_APPROX(scf*mf*mcf, scf*mf.template cast<CF>()*mcf);\n  VERIFY_IS_APPROX(scf*mcf*mf, scf*mcf*mf.template cast<CF>());\n\n  VERIFY_IS_APPROX(sd*md.adjoint()*mcd, (sd*md).template cast<CD>().eval().adjoint()*mcd);\n  VERIFY_IS_APPROX(sd*mcd.adjoint()*md, sd*mcd.adjoint()*md.template cast<CD>());\n  VERIFY_IS_APPROX(sd*md.adjoint()*mcd.adjoint(), (sd*md).template cast<CD>().eval().adjoint()*mcd.adjoint());\n  VERIFY_IS_APPROX(sd*mcd.adjoint()*md.adjoint(), sd*mcd.adjoint()*md.template cast<CD>().adjoint());\n  VERIFY_IS_APPROX(sd*md*mcd.adjoint(), (sd*md).template cast<CD>().eval()*mcd.adjoint());\n  VERIFY_IS_APPROX(sd*mcd*md.adjoint(), sd*mcd*md.template cast<CD>().adjoint());\n\n  VERIFY_IS_APPROX(sf*mf.adjoint()*mcf, (sf*mf).template cast<CF>().eval().adjoint()*mcf);\n  VERIFY_IS_APPROX(sf*mcf.adjoint()*mf, sf*mcf.adjoint()*mf.template cast<CF>());\n  VERIFY_IS_APPROX(sf*mf.adjoint()*mcf.adjoint(), (sf*mf).template cast<CF>().eval().adjoint()*mcf.adjoint());\n  VERIFY_IS_APPROX(sf*mcf.adjoint()*mf.adjoint(), sf*mcf.adjoint()*mf.template cast<CF>().adjoint());\n  VERIFY_IS_APPROX(sf*mf*mcf.adjoint(), (sf*mf).template cast<CF>().eval()*mcf.adjoint());\n  VERIFY_IS_APPROX(sf*mcf*mf.adjoint(), sf*mcf*mf.template cast<CF>().adjoint());\n\n  VERIFY_IS_APPROX(sf*mf*vcf, (sf*mf).template cast<CF>().eval()*vcf);\n  VERIFY_IS_APPROX(scf*mf*vcf,(scf*mf.template cast<CF>()).eval()*vcf);\n  VERIFY_IS_APPROX(sf*mcf*vf, sf*mcf*vf.template cast<CF>());\n  VERIFY_IS_APPROX(scf*mcf*vf,scf*mcf*vf.template cast<CF>());\n\n  VERIFY_IS_APPROX(sf*vcf.adjoint()*mf,  sf*vcf.adjoint()*mf.template cast<CF>().eval());\n  VERIFY_IS_APPROX(scf*vcf.adjoint()*mf, scf*vcf.adjoint()*mf.template cast<CF>().eval());\n  VERIFY_IS_APPROX(sf*vf.adjoint()*mcf,  sf*vf.adjoint().template cast<CF>().eval()*mcf);\n  VERIFY_IS_APPROX(scf*vf.adjoint()*mcf, scf*vf.adjoint().template cast<CF>().eval()*mcf);\n\n  VERIFY_IS_APPROX(sd*md*vcd, (sd*md).template cast<CD>().eval()*vcd);\n  VERIFY_IS_APPROX(scd*md*vcd,(scd*md.template cast<CD>()).eval()*vcd);\n  VERIFY_IS_APPROX(sd*mcd*vd, sd*mcd*vd.template cast<CD>().eval());\n  VERIFY_IS_APPROX(scd*mcd*vd,scd*mcd*vd.template cast<CD>().eval());\n\n  VERIFY_IS_APPROX(sd*vcd.adjoint()*md,  sd*vcd.adjoint()*md.template cast<CD>().eval());\n  VERIFY_IS_APPROX(scd*vcd.adjoint()*md, scd*vcd.adjoint()*md.template cast<CD>().eval());\n  VERIFY_IS_APPROX(sd*vd.adjoint()*mcd,  sd*vd.adjoint().template cast<CD>().eval()*mcd);\n  VERIFY_IS_APPROX(scd*vd.adjoint()*mcd, scd*vd.adjoint().template cast<CD>().eval()*mcd);\n\n  VERIFY_IS_APPROX( sd*vcd.adjoint()*md.template triangularView<Upper>(),  sd*vcd.adjoint()*md.template cast<CD>().eval().template triangularView<Upper>());\n  VERIFY_IS_APPROX(scd*vcd.adjoint()*md.template triangularView<Lower>(), scd*vcd.adjoint()*md.template cast<CD>().eval().template triangularView<Lower>());\n  VERIFY_IS_APPROX( sd*vcd.adjoint()*md.transpose().template triangularView<Upper>(),  sd*vcd.adjoint()*md.transpose().template cast<CD>().eval().template triangularView<Upper>());\n  VERIFY_IS_APPROX(scd*vcd.adjoint()*md.transpose().template triangularView<Lower>(), scd*vcd.adjoint()*md.transpose().template cast<CD>().eval().template triangularView<Lower>());\n  VERIFY_IS_APPROX( sd*vd.adjoint()*mcd.template triangularView<Lower>(),  sd*vd.adjoint().template cast<CD>().eval()*mcd.template triangularView<Lower>());\n  VERIFY_IS_APPROX(scd*vd.adjoint()*mcd.template triangularView<Upper>(), scd*vd.adjoint().template cast<CD>().eval()*mcd.template triangularView<Upper>());\n  VERIFY_IS_APPROX( sd*vd.adjoint()*mcd.transpose().template triangularView<Lower>(),  sd*vd.adjoint().template cast<CD>().eval()*mcd.transpose().template triangularView<Lower>());\n  VERIFY_IS_APPROX(scd*vd.adjoint()*mcd.transpose().template triangularView<Upper>(), scd*vd.adjoint().template cast<CD>().eval()*mcd.transpose().template triangularView<Upper>());\n\n  // Not supported yet: trmm\n//   VERIFY_IS_APPROX(sd*mcd*md.template triangularView<Lower>(),  sd*mcd*md.template cast<CD>().eval().template triangularView<Lower>());\n//   VERIFY_IS_APPROX(scd*mcd*md.template triangularView<Upper>(), scd*mcd*md.template cast<CD>().eval().template triangularView<Upper>());\n//   VERIFY_IS_APPROX(sd*md*mcd.template triangularView<Lower>(),  sd*md.template cast<CD>().eval()*mcd.template triangularView<Lower>());\n//   VERIFY_IS_APPROX(scd*md*mcd.template triangularView<Upper>(), scd*md.template cast<CD>().eval()*mcd.template triangularView<Upper>());\n\n  // Not supported yet: symv\n//   VERIFY_IS_APPROX(sd*vcd.adjoint()*md.template selfadjointView<Upper>(),  sd*vcd.adjoint()*md.template cast<CD>().eval().template selfadjointView<Upper>());\n//   VERIFY_IS_APPROX(scd*vcd.adjoint()*md.template selfadjointView<Lower>(), scd*vcd.adjoint()*md.template cast<CD>().eval().template selfadjointView<Lower>());\n//   VERIFY_IS_APPROX(sd*vd.adjoint()*mcd.template selfadjointView<Lower>(),  sd*vd.adjoint().template cast<CD>().eval()*mcd.template selfadjointView<Lower>());\n//   VERIFY_IS_APPROX(scd*vd.adjoint()*mcd.template selfadjointView<Upper>(), scd*vd.adjoint().template cast<CD>().eval()*mcd.template selfadjointView<Upper>());\n\n  // Not supported yet: symm\n//   VERIFY_IS_APPROX(sd*vcd.adjoint()*md.template selfadjointView<Upper>(),  sd*vcd.adjoint()*md.template cast<CD>().eval().template selfadjointView<Upper>());\n//   VERIFY_IS_APPROX(scd*vcd.adjoint()*md.template selfadjointView<Upper>(), scd*vcd.adjoint()*md.template cast<CD>().eval().template selfadjointView<Upper>());\n//   VERIFY_IS_APPROX(sd*vd.adjoint()*mcd.template selfadjointView<Upper>(),  sd*vd.adjoint().template cast<CD>().eval()*mcd.template selfadjointView<Upper>());\n//   VERIFY_IS_APPROX(scd*vd.adjoint()*mcd.template selfadjointView<Upper>(), scd*vd.adjoint().template cast<CD>().eval()*mcd.template selfadjointView<Upper>());\n\n  rcd.setZero();\n  VERIFY_IS_APPROX(Mat_cd(rcd.template triangularView<Upper>() = sd * mcd * md),\n                   Mat_cd((sd * mcd * md.template cast<CD>().eval()).template triangularView<Upper>()));\n  VERIFY_IS_APPROX(Mat_cd(rcd.template triangularView<Upper>() = sd * md * mcd),\n                   Mat_cd((sd * md.template cast<CD>().eval() * mcd).template triangularView<Upper>()));\n  VERIFY_IS_APPROX(Mat_cd(rcd.template triangularView<Upper>() = scd * mcd * md),\n                   Mat_cd((scd * mcd * md.template cast<CD>().eval()).template triangularView<Upper>()));\n  VERIFY_IS_APPROX(Mat_cd(rcd.template triangularView<Upper>() = scd * md * mcd),\n                   Mat_cd((scd * md.template cast<CD>().eval() * mcd).template triangularView<Upper>()));\n\n\n  VERIFY_IS_APPROX( md.array()  * mcd.array(), md.template cast<CD>().eval().array() * mcd.array() );\n  VERIFY_IS_APPROX( mcd.array() * md.array(),  mcd.array() * md.template cast<CD>().eval().array() );\n\n  VERIFY_IS_APPROX( md.array()  + mcd.array(), md.template cast<CD>().eval().array() + mcd.array() );\n  VERIFY_IS_APPROX( mcd.array() + md.array(),  mcd.array() + md.template cast<CD>().eval().array() );\n\n  VERIFY_IS_APPROX( md.array()  - mcd.array(), md.template cast<CD>().eval().array() - mcd.array() );\n  VERIFY_IS_APPROX( mcd.array() - md.array(),  mcd.array() - md.template cast<CD>().eval().array() );\n\n  if(mcd.array().abs().minCoeff()>epsd)\n  {\n    VERIFY_IS_APPROX( md.array() / mcd.array(), md.template cast<CD>().eval().array() / mcd.array() );\n  }\n  if(md.array().abs().minCoeff()>epsd)\n  {\n    VERIFY_IS_APPROX( mcd.array() / md.array(), mcd.array() / md.template cast<CD>().eval().array() );\n  }\n\n  if(md.array().abs().minCoeff()>epsd || mcd.array().abs().minCoeff()>epsd)\n  {\n    VERIFY_IS_APPROX( md.array().pow(mcd.array()), md.template cast<CD>().eval().array().pow(mcd.array()) );\n    VERIFY_IS_APPROX( mcd.array().pow(md.array()),  mcd.array().pow(md.template cast<CD>().eval().array()) );\n\n    VERIFY_IS_APPROX( pow(md.array(),mcd.array()), md.template cast<CD>().eval().array().pow(mcd.array()) );\n    VERIFY_IS_APPROX( pow(mcd.array(),md.array()),  mcd.array().pow(md.template cast<CD>().eval().array()) );\n  }\n\n  rcd = mcd;\n  VERIFY_IS_APPROX( rcd = md, md.template cast<CD>().eval() );\n  rcd = mcd;\n  VERIFY_IS_APPROX( rcd += md, mcd + md.template cast<CD>().eval() );\n  rcd = mcd;\n  VERIFY_IS_APPROX( rcd -= md, mcd - md.template cast<CD>().eval() );\n  rcd = mcd;\n  VERIFY_IS_APPROX( rcd.array() *= md.array(), mcd.array() * md.template cast<CD>().eval().array() );\n  rcd = mcd;\n  if(md.array().abs().minCoeff()>epsd)\n  {\n    VERIFY_IS_APPROX( rcd.array() /= md.array(), mcd.array() / md.template cast<CD>().eval().array() );\n  }\n\n  rcd = mcd;\n  VERIFY_IS_APPROX( rcd.noalias() += md + mcd*md, mcd + (md.template cast<CD>().eval()) + mcd*(md.template cast<CD>().eval()));\n\n  VERIFY_IS_APPROX( rcd.noalias()  = md*md,       ((md*md).eval().template cast<CD>()) );\n  rcd = mcd;\n  VERIFY_IS_APPROX( rcd.noalias() += md*md, mcd + ((md*md).eval().template cast<CD>()) );\n  rcd = mcd;\n  VERIFY_IS_APPROX( rcd.noalias() -= md*md, mcd - ((md*md).eval().template cast<CD>()) );\n\n  VERIFY_IS_APPROX( rcd.noalias()  = mcd + md*md,       mcd + ((md*md).eval().template cast<CD>()) );\n  rcd = mcd;\n  VERIFY_IS_APPROX( rcd.noalias() += mcd + md*md, mcd + mcd + ((md*md).eval().template cast<CD>()) );\n  rcd = mcd;\n  VERIFY_IS_APPROX( rcd.noalias() -= mcd + md*md,           - ((md*md).eval().template cast<CD>()) );\n}\n\nEIGEN_DECLARE_TEST(mixingtypes)\n{\n  g_called = false; // Silence -Wunneeded-internal-declaration.\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(mixingtypes<3>());\n    CALL_SUBTEST_2(mixingtypes<4>());\n    CALL_SUBTEST_3(mixingtypes<Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)));\n\n    CALL_SUBTEST_4(mixingtypes<3>());\n    CALL_SUBTEST_5(mixingtypes<4>());\n    CALL_SUBTEST_6(mixingtypes<Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)));\n    CALL_SUBTEST_7(raise_assertion<Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)));\n  }\n  CALL_SUBTEST_7(raise_assertion<0>());\n  CALL_SUBTEST_7(raise_assertion<3>());\n  CALL_SUBTEST_7(raise_assertion<4>());\n  CALL_SUBTEST_7(raise_assertion<Dynamic>(0));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/mpl2only.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MPL2_ONLY\n#define EIGEN_MPL2_ONLY\n#endif\n#include <Eigen/Dense>\n#include <Eigen/SparseCore>\n#include <Eigen/SparseLU>\n#include <Eigen/SparseQR>\n#include <Eigen/Sparse>\n#include <Eigen/IterativeLinearSolvers>\n#include <Eigen/Eigen>\n\nint main()\n{\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/nestbyvalue.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2019 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define TEST_ENABLE_TEMPORARY_TRACKING\n\n#include \"main.h\"\n\ntypedef NestByValue<MatrixXd> CpyMatrixXd;\ntypedef CwiseBinaryOp<internal::scalar_sum_op<double,double>,const CpyMatrixXd,const CpyMatrixXd> XprType;\n\nXprType get_xpr_with_temps(const MatrixXd& a)\n{\n  MatrixXd t1 = a.rowwise().reverse();\n  MatrixXd t2 = a+a;\n  return t1.nestByValue() + t2.nestByValue();\n}\n\nEIGEN_DECLARE_TEST(nestbyvalue)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    Index rows = internal::random<Index>(1,EIGEN_TEST_MAX_SIZE);\n    Index cols = internal::random<Index>(1,EIGEN_TEST_MAX_SIZE);\n    MatrixXd a = MatrixXd(rows,cols);\n    nb_temporaries = 0;\n    XprType x = get_xpr_with_temps(a);\n    VERIFY_IS_EQUAL(nb_temporaries,6);\n    MatrixXd b = x;\n    VERIFY_IS_EQUAL(nb_temporaries,6+1);\n    VERIFY_IS_APPROX(b, a.rowwise().reverse().eval() + (a+a).eval());\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/nesting_ops.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Hauke Heibel <hauke.heibel@gmail.com>\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define TEST_ENABLE_TEMPORARY_TRACKING\n\n#include \"main.h\"\n\ntemplate <int N, typename XprType>\nvoid use_n_times(const XprType &xpr)\n{\n  typename internal::nested_eval<XprType,N>::type mat(xpr);\n  typename XprType::PlainObject res(mat.rows(), mat.cols());\n  nb_temporaries--; // remove res\n  res.setZero();\n  for(int i=0; i<N; ++i)\n    res += mat;\n}\n\ntemplate <int N, typename ReferenceType, typename XprType>\nbool verify_eval_type(const XprType &, const ReferenceType&)\n{\n  typedef typename internal::nested_eval<XprType,N>::type EvalType;\n  return internal::is_same<typename internal::remove_all<EvalType>::type, typename internal::remove_all<ReferenceType>::type>::value;\n}\n\ntemplate <typename MatrixType> void run_nesting_ops_1(const MatrixType& _m)\n{\n  typename internal::nested_eval<MatrixType,2>::type m(_m);\n\n  // Make really sure that we are in debug mode!\n  VERIFY_RAISES_ASSERT(eigen_assert(false));\n\n  // The only intention of these tests is to ensure that this code does\n  // not trigger any asserts or segmentation faults... more to come.\n  VERIFY_IS_APPROX( (m.transpose() * m).diagonal().sum(), (m.transpose() * m).diagonal().sum() );\n  VERIFY_IS_APPROX( (m.transpose() * m).diagonal().array().abs().sum(), (m.transpose() * m).diagonal().array().abs().sum() );\n\n  VERIFY_IS_APPROX( (m.transpose() * m).array().abs().sum(), (m.transpose() * m).array().abs().sum() );\n}\n\ntemplate <typename MatrixType> void run_nesting_ops_2(const MatrixType& _m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  Index rows = _m.rows();\n  Index cols = _m.cols();\n  MatrixType m1 = MatrixType::Random(rows,cols);\n  Matrix<Scalar,MatrixType::RowsAtCompileTime,MatrixType::ColsAtCompileTime,ColMajor> m2;\n\n  if((MatrixType::SizeAtCompileTime==Dynamic))\n  {\n    VERIFY_EVALUATION_COUNT( use_n_times<1>(m1 + m1*m1), 1 );\n    VERIFY_EVALUATION_COUNT( use_n_times<10>(m1 + m1*m1), 1 );\n\n    VERIFY_EVALUATION_COUNT( use_n_times<1>(m1.template triangularView<Lower>().solve(m1.col(0))), 1 );\n    VERIFY_EVALUATION_COUNT( use_n_times<10>(m1.template triangularView<Lower>().solve(m1.col(0))), 1 );\n\n    VERIFY_EVALUATION_COUNT( use_n_times<1>(Scalar(2)*m1.template triangularView<Lower>().solve(m1.col(0))), 2 ); // FIXME could be one by applying the scaling in-place on the solve result\n    VERIFY_EVALUATION_COUNT( use_n_times<1>(m1.col(0)+m1.template triangularView<Lower>().solve(m1.col(0))), 2 ); // FIXME could be one by adding m1.col() inplace\n    VERIFY_EVALUATION_COUNT( use_n_times<10>(m1.col(0)+m1.template triangularView<Lower>().solve(m1.col(0))), 2 );\n  }\n\n  {\n    VERIFY( verify_eval_type<10>(m1, m1) );\n    if(!NumTraits<Scalar>::IsComplex)\n    {\n      VERIFY( verify_eval_type<3>(2*m1, 2*m1) );\n      VERIFY( verify_eval_type<4>(2*m1, m1) );\n    }\n    else\n    {\n      VERIFY( verify_eval_type<2>(2*m1, 2*m1) );\n      VERIFY( verify_eval_type<3>(2*m1, m1) );\n    }\n    VERIFY( verify_eval_type<2>(m1+m1, m1+m1) );\n    VERIFY( verify_eval_type<3>(m1+m1, m1) );\n    VERIFY( verify_eval_type<1>(m1*m1.transpose(), m2) );\n    VERIFY( verify_eval_type<1>(m1*(m1+m1).transpose(), m2) );\n    VERIFY( verify_eval_type<2>(m1*m1.transpose(), m2) );\n    VERIFY( verify_eval_type<1>(m1+m1*m1, m1) );\n\n    VERIFY( verify_eval_type<1>(m1.template triangularView<Lower>().solve(m1), m1) );\n    VERIFY( verify_eval_type<1>(m1+m1.template triangularView<Lower>().solve(m1), m1) );\n  }\n}\n\n\nEIGEN_DECLARE_TEST(nesting_ops)\n{\n  CALL_SUBTEST_1(run_nesting_ops_1(MatrixXf::Random(25,25)));\n  CALL_SUBTEST_2(run_nesting_ops_1(MatrixXcd::Random(25,25)));\n  CALL_SUBTEST_3(run_nesting_ops_1(Matrix4f::Random()));\n  CALL_SUBTEST_4(run_nesting_ops_1(Matrix2d::Random()));\n\n  Index s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE);\n  CALL_SUBTEST_1( run_nesting_ops_2(MatrixXf(s,s)) );\n  CALL_SUBTEST_2( run_nesting_ops_2(MatrixXcd(s,s)) );\n  CALL_SUBTEST_3( run_nesting_ops_2(Matrix4f()) );\n  CALL_SUBTEST_4( run_nesting_ops_2(Matrix2d()) );\n  TEST_SET_BUT_UNUSED_VARIABLE(s)\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/nomalloc.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// discard stack allocation as that too bypasses malloc\n#define EIGEN_STACK_ALLOCATION_LIMIT 0\n// heap allocation will raise an assert if enabled at runtime\n#define EIGEN_RUNTIME_NO_MALLOC\n\n#include \"main.h\"\n#include <Eigen/Cholesky>\n#include <Eigen/Eigenvalues>\n#include <Eigen/LU>\n#include <Eigen/QR>\n#include <Eigen/SVD>\n\ntemplate<typename MatrixType> void nomalloc(const MatrixType& m)\n{\n  /* this test check no dynamic memory allocation are issued with fixed-size matrices\n  */\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols);\n\n  Scalar s1 = internal::random<Scalar>();\n\n  Index r = internal::random<Index>(0, rows-1),\n        c = internal::random<Index>(0, cols-1);\n\n  VERIFY_IS_APPROX((m1+m2)*s1,              s1*m1+s1*m2);\n  VERIFY_IS_APPROX((m1+m2)(r,c), (m1(r,c))+(m2(r,c)));\n  VERIFY_IS_APPROX(m1.cwiseProduct(m1.block(0,0,rows,cols)), (m1.array()*m1.array()).matrix());\n  VERIFY_IS_APPROX((m1*m1.transpose())*m2,  m1*(m1.transpose()*m2));\n  \n  m2.col(0).noalias() = m1 * m1.col(0);\n  m2.col(0).noalias() -= m1.adjoint() * m1.col(0);\n  m2.col(0).noalias() -= m1 * m1.row(0).adjoint();\n  m2.col(0).noalias() -= m1.adjoint() * m1.row(0).adjoint();\n\n  m2.row(0).noalias() = m1.row(0) * m1;\n  m2.row(0).noalias() -= m1.row(0) * m1.adjoint();\n  m2.row(0).noalias() -= m1.col(0).adjoint() * m1;\n  m2.row(0).noalias() -= m1.col(0).adjoint() * m1.adjoint();\n  VERIFY_IS_APPROX(m2,m2);\n  \n  m2.col(0).noalias() = m1.template triangularView<Upper>() * m1.col(0);\n  m2.col(0).noalias() -= m1.adjoint().template triangularView<Upper>() * m1.col(0);\n  m2.col(0).noalias() -= m1.template triangularView<Upper>() * m1.row(0).adjoint();\n  m2.col(0).noalias() -= m1.adjoint().template triangularView<Upper>() * m1.row(0).adjoint();\n\n  m2.row(0).noalias() = m1.row(0) * m1.template triangularView<Upper>();\n  m2.row(0).noalias() -= m1.row(0) * m1.adjoint().template triangularView<Upper>();\n  m2.row(0).noalias() -= m1.col(0).adjoint() * m1.template triangularView<Upper>();\n  m2.row(0).noalias() -= m1.col(0).adjoint() * m1.adjoint().template triangularView<Upper>();\n  VERIFY_IS_APPROX(m2,m2);\n  \n  m2.col(0).noalias() = m1.template selfadjointView<Upper>() * m1.col(0);\n  m2.col(0).noalias() -= m1.adjoint().template selfadjointView<Upper>() * m1.col(0);\n  m2.col(0).noalias() -= m1.template selfadjointView<Upper>() * m1.row(0).adjoint();\n  m2.col(0).noalias() -= m1.adjoint().template selfadjointView<Upper>() * m1.row(0).adjoint();\n\n  m2.row(0).noalias() = m1.row(0) * m1.template selfadjointView<Upper>();\n  m2.row(0).noalias() -= m1.row(0) * m1.adjoint().template selfadjointView<Upper>();\n  m2.row(0).noalias() -= m1.col(0).adjoint() * m1.template selfadjointView<Upper>();\n  m2.row(0).noalias() -= m1.col(0).adjoint() * m1.adjoint().template selfadjointView<Upper>();\n  VERIFY_IS_APPROX(m2,m2);\n  \n  m2.template selfadjointView<Lower>().rankUpdate(m1.col(0),-1);\n  m2.template selfadjointView<Upper>().rankUpdate(m1.row(0),-1);\n  m2.template selfadjointView<Lower>().rankUpdate(m1.col(0), m1.col(0)); // rank-2\n\n  // The following fancy matrix-matrix products are not safe yet regarding static allocation\n  m2.template selfadjointView<Lower>().rankUpdate(m1);\n  m2 += m2.template triangularView<Upper>() * m1;\n  m2.template triangularView<Upper>() = m2 * m2;\n  m1 += m1.template selfadjointView<Lower>() * m2;\n  VERIFY_IS_APPROX(m2,m2);\n}\n\ntemplate<typename Scalar>\nvoid ctms_decompositions()\n{\n  const int maxSize = 16;\n  const int size    = 12;\n\n  typedef Eigen::Matrix<Scalar,\n                        Eigen::Dynamic, Eigen::Dynamic,\n                        0,\n                        maxSize, maxSize> Matrix;\n\n  typedef Eigen::Matrix<Scalar,\n                        Eigen::Dynamic, 1,\n                        0,\n                        maxSize, 1> Vector;\n\n  typedef Eigen::Matrix<std::complex<Scalar>,\n                        Eigen::Dynamic, Eigen::Dynamic,\n                        0,\n                        maxSize, maxSize> ComplexMatrix;\n\n  const Matrix A(Matrix::Random(size, size)), B(Matrix::Random(size, size));\n  Matrix X(size,size);\n  const ComplexMatrix complexA(ComplexMatrix::Random(size, size));\n  const Matrix saA = A.adjoint() * A;\n  const Vector b(Vector::Random(size));\n  Vector x(size);\n\n  // Cholesky module\n  Eigen::LLT<Matrix>  LLT;  LLT.compute(A);\n  X = LLT.solve(B);\n  x = LLT.solve(b);\n  Eigen::LDLT<Matrix> LDLT; LDLT.compute(A);\n  X = LDLT.solve(B);\n  x = LDLT.solve(b);\n\n  // Eigenvalues module\n  Eigen::HessenbergDecomposition<ComplexMatrix> hessDecomp;        hessDecomp.compute(complexA);\n  Eigen::ComplexSchur<ComplexMatrix>            cSchur(size);      cSchur.compute(complexA);\n  Eigen::ComplexEigenSolver<ComplexMatrix>      cEigSolver;        cEigSolver.compute(complexA);\n  Eigen::EigenSolver<Matrix>                    eigSolver;         eigSolver.compute(A);\n  Eigen::SelfAdjointEigenSolver<Matrix>         saEigSolver(size); saEigSolver.compute(saA);\n  Eigen::Tridiagonalization<Matrix>             tridiag;           tridiag.compute(saA);\n\n  // LU module\n  Eigen::PartialPivLU<Matrix> ppLU; ppLU.compute(A);\n  X = ppLU.solve(B);\n  x = ppLU.solve(b);\n  Eigen::FullPivLU<Matrix>    fpLU; fpLU.compute(A);\n  X = fpLU.solve(B);\n  x = fpLU.solve(b);\n\n  // QR module\n  Eigen::HouseholderQR<Matrix>        hQR;  hQR.compute(A);\n  X = hQR.solve(B);\n  x = hQR.solve(b);\n  Eigen::ColPivHouseholderQR<Matrix>  cpQR; cpQR.compute(A);\n  X = cpQR.solve(B);\n  x = cpQR.solve(b);\n  Eigen::FullPivHouseholderQR<Matrix> fpQR; fpQR.compute(A);\n  // FIXME X = fpQR.solve(B);\n  x = fpQR.solve(b);\n\n  // SVD module\n  Eigen::JacobiSVD<Matrix> jSVD; jSVD.compute(A, ComputeFullU | ComputeFullV);\n}\n\nvoid test_zerosized() {\n  // default constructors:\n  Eigen::MatrixXd A;\n  Eigen::VectorXd v;\n  // explicit zero-sized:\n  Eigen::ArrayXXd A0(0,0);\n  Eigen::ArrayXd v0(0);\n\n  // assigning empty objects to each other:\n  A=A0;\n  v=v0;\n}\n\ntemplate<typename MatrixType> void test_reference(const MatrixType& m) {\n  typedef typename MatrixType::Scalar Scalar;\n  enum { Flag          =  MatrixType::IsRowMajor ? Eigen::RowMajor : Eigen::ColMajor};\n  enum { TransposeFlag = !MatrixType::IsRowMajor ? Eigen::RowMajor : Eigen::ColMajor};\n  Index rows = m.rows(), cols=m.cols();\n  typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Flag         > MatrixX;\n  typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, TransposeFlag> MatrixXT;\n  // Dynamic reference:\n  typedef Eigen::Ref<const MatrixX  > Ref;\n  typedef Eigen::Ref<const MatrixXT > RefT;\n\n  Ref r1(m);\n  Ref r2(m.block(rows/3, cols/4, rows/2, cols/2));\n  RefT r3(m.transpose());\n  RefT r4(m.topLeftCorner(rows/2, cols/2).transpose());\n\n  VERIFY_RAISES_ASSERT(RefT r5(m));\n  VERIFY_RAISES_ASSERT(Ref r6(m.transpose()));\n  VERIFY_RAISES_ASSERT(Ref r7(Scalar(2) * m));\n\n  // Copy constructors shall also never malloc\n  Ref r8 = r1;\n  RefT r9 = r3;\n\n  // Initializing from a compatible Ref shall also never malloc\n  Eigen::Ref<const MatrixX, Unaligned, Stride<Dynamic, Dynamic> > r10=r8, r11=m;\n\n  // Initializing from an incompatible Ref will malloc:\n  typedef Eigen::Ref<const MatrixX, Aligned> RefAligned;\n  VERIFY_RAISES_ASSERT(RefAligned r12=r10);\n  VERIFY_RAISES_ASSERT(Ref r13=r10); // r10 has more dynamic strides\n\n}\n\nEIGEN_DECLARE_TEST(nomalloc)\n{\n  // create some dynamic objects\n  Eigen::MatrixXd M1 = MatrixXd::Random(3,3);\n  Ref<const MatrixXd> R1 = 2.0*M1; // Ref requires temporary\n\n  // from here on prohibit malloc:\n  Eigen::internal::set_is_malloc_allowed(false);\n\n  // check that our operator new is indeed called:\n  VERIFY_RAISES_ASSERT(MatrixXd dummy(MatrixXd::Random(3,3)));\n  CALL_SUBTEST_1(nomalloc(Matrix<float, 1, 1>()) );\n  CALL_SUBTEST_2(nomalloc(Matrix4d()) );\n  CALL_SUBTEST_3(nomalloc(Matrix<float,32,32>()) );\n  \n  // Check decomposition modules with dynamic matrices that have a known compile-time max size (ctms)\n  CALL_SUBTEST_4(ctms_decompositions<float>());\n\n  CALL_SUBTEST_5(test_zerosized());\n\n  CALL_SUBTEST_6(test_reference(Matrix<float,32,32>()));\n  CALL_SUBTEST_7(test_reference(R1));\n  CALL_SUBTEST_8(Ref<MatrixXd> R2 = M1.topRows<2>(); test_reference(R2));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/nullary.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010-2011 Jitse Niesen <jitse@maths.leeds.ac.uk>\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType>\nbool equalsIdentity(const MatrixType& A)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  Scalar zero = static_cast<Scalar>(0);\n\n  bool offDiagOK = true;\n  for (Index i = 0; i < A.rows(); ++i) {\n    for (Index j = i+1; j < A.cols(); ++j) {\n      offDiagOK = offDiagOK && (A(i,j) == zero);\n    }\n  }\n  for (Index i = 0; i < A.rows(); ++i) {\n    for (Index j = 0; j < (std::min)(i, A.cols()); ++j) {\n      offDiagOK = offDiagOK && (A(i,j) == zero);\n    }\n  }\n\n  bool diagOK = (A.diagonal().array() == 1).all();\n  return offDiagOK && diagOK;\n\n}\n\ntemplate<typename VectorType>\nvoid check_extremity_accuracy(const VectorType &v, const typename VectorType::Scalar &low, const typename VectorType::Scalar &high)\n{\n  typedef typename VectorType::Scalar Scalar;\n  typedef typename VectorType::RealScalar RealScalar;\n\n  RealScalar prec = internal::is_same<RealScalar,float>::value ? NumTraits<RealScalar>::dummy_precision()*10 : NumTraits<RealScalar>::dummy_precision()/10;\n  Index size = v.size();\n\n  if(size<20)\n    return;\n\n  for (int i=0; i<size; ++i)\n  {\n    if(i<5 || i>size-6)\n    {\n      Scalar ref = (low*RealScalar(size-i-1))/RealScalar(size-1) + (high*RealScalar(i))/RealScalar(size-1);\n      if(std::abs(ref)>1)\n      {\n        if(!internal::isApprox(v(i), ref, prec))\n          std::cout << v(i) << \" != \" << ref << \"  ; relative error: \" << std::abs((v(i)-ref)/ref) << \"  ; required precision: \" << prec << \"  ; range: \" << low << \",\" << high << \"  ; i: \" << i << \"\\n\";\n        VERIFY(internal::isApprox(v(i), (low*RealScalar(size-i-1))/RealScalar(size-1) + (high*RealScalar(i))/RealScalar(size-1), prec));\n      }\n    }\n  }\n}\n\ntemplate<typename VectorType>\nvoid testVectorType(const VectorType& base)\n{\n  typedef typename VectorType::Scalar Scalar;\n  typedef typename VectorType::RealScalar RealScalar;\n\n  const Index size = base.size();\n  \n  Scalar high = internal::random<Scalar>(-500,500);\n  Scalar low = (size == 1 ? high : internal::random<Scalar>(-500,500));\n  if (numext::real(low)>numext::real(high)) std::swap(low,high);\n\n  // check low==high\n  if(internal::random<float>(0.f,1.f)<0.05f)\n    low = high;\n  // check abs(low) >> abs(high)\n  else if(size>2 && std::numeric_limits<RealScalar>::max_exponent10>0 && internal::random<float>(0.f,1.f)<0.1f)\n    low = -internal::random<Scalar>(1,2) * RealScalar(std::pow(RealScalar(10),std::numeric_limits<RealScalar>::max_exponent10/2));\n\n  const Scalar step = ((size == 1) ? 1 : (high-low)/RealScalar(size-1));\n\n  // check whether the result yields what we expect it to do\n  VectorType m(base);\n  m.setLinSpaced(size,low,high);\n\n  if(!NumTraits<Scalar>::IsInteger)\n  {\n    VectorType n(size);\n    for (int i=0; i<size; ++i)\n      n(i) = low+RealScalar(i)*step;\n    VERIFY_IS_APPROX(m,n);\n\n    CALL_SUBTEST( check_extremity_accuracy(m, low, high) );\n  }\n\n  RealScalar range_length = numext::real(high-low);\n  if((!NumTraits<Scalar>::IsInteger) || (range_length>=size && (Index(range_length)%(size-1))==0) || (Index(range_length+1)<size && (size%Index(range_length+1))==0))\n  {\n    VectorType n(size);\n    if((!NumTraits<Scalar>::IsInteger) || (range_length>=size))\n      for (int i=0; i<size; ++i)\n        n(i) = size==1 ? low : (low + ((high-low)*Scalar(i))/RealScalar(size-1));\n    else\n      for (int i=0; i<size; ++i)\n        n(i) = size==1 ? low : low + Scalar((double(range_length+1)*double(i))/double(size));\n    VERIFY_IS_APPROX(m,n);\n\n    // random access version\n    m = VectorType::LinSpaced(size,low,high);\n    VERIFY_IS_APPROX(m,n);\n    VERIFY( internal::isApprox(m(m.size()-1),high) );\n    VERIFY( size==1 || internal::isApprox(m(0),low) );\n    VERIFY_IS_EQUAL(m(m.size()-1) , high);\n    if(!NumTraits<Scalar>::IsInteger)\n      CALL_SUBTEST( check_extremity_accuracy(m, low, high) );\n  }\n\n  VERIFY( numext::real(m(m.size()-1)) <= numext::real(high) );\n  VERIFY( (m.array().real() <= numext::real(high)).all() );\n  VERIFY( (m.array().real() >= numext::real(low)).all() );\n\n\n  VERIFY( numext::real(m(m.size()-1)) >= numext::real(low) );\n  if(size>=1)\n  {\n    VERIFY( internal::isApprox(m(0),low) );\n    VERIFY_IS_EQUAL(m(0) , low);\n  }\n\n  // check whether everything works with row and col major vectors\n  Matrix<Scalar,Dynamic,1> row_vector(size);\n  Matrix<Scalar,1,Dynamic> col_vector(size);\n  row_vector.setLinSpaced(size,low,high);\n  col_vector.setLinSpaced(size,low,high);\n  // when using the extended precision (e.g., FPU) the relative error might exceed 1 bit\n  // when computing the squared sum in isApprox, thus the 2x factor.\n  VERIFY( row_vector.isApprox(col_vector.transpose(), RealScalar(2)*NumTraits<Scalar>::epsilon()));\n\n  Matrix<Scalar,Dynamic,1> size_changer(size+50);\n  size_changer.setLinSpaced(size,low,high);\n  VERIFY( size_changer.size() == size );\n\n  typedef Matrix<Scalar,1,1> ScalarMatrix;\n  ScalarMatrix scalar;\n  scalar.setLinSpaced(1,low,high);\n  VERIFY_IS_APPROX( scalar, ScalarMatrix::Constant(high) );\n  VERIFY_IS_APPROX( ScalarMatrix::LinSpaced(1,low,high), ScalarMatrix::Constant(high) );\n\n  // regression test for bug 526 (linear vectorized transversal)\n  if (size > 1 && (!NumTraits<Scalar>::IsInteger)) {\n    m.tail(size-1).setLinSpaced(low, high);\n    VERIFY_IS_APPROX(m(size-1), high);\n  }\n\n  // regression test for bug 1383 (LinSpaced with empty size/range)\n  {\n    Index n0 = VectorType::SizeAtCompileTime==Dynamic ? 0 : VectorType::SizeAtCompileTime;\n    low = internal::random<Scalar>();\n    m = VectorType::LinSpaced(n0,low,low-RealScalar(1));\n    VERIFY(m.size()==n0);\n\n    if(VectorType::SizeAtCompileTime==Dynamic)\n    {\n      VERIFY_IS_EQUAL(VectorType::LinSpaced(n0,0,Scalar(n0-1)).sum(),Scalar(0));\n      VERIFY_IS_EQUAL(VectorType::LinSpaced(n0,low,low-RealScalar(1)).sum(),Scalar(0));\n    }\n\n    m.setLinSpaced(n0,0,Scalar(n0-1));\n    VERIFY(m.size()==n0);\n    m.setLinSpaced(n0,low,low-RealScalar(1));\n    VERIFY(m.size()==n0);\n\n    // empty range only:\n    VERIFY_IS_APPROX(VectorType::LinSpaced(size,low,low),VectorType::Constant(size,low));\n    m.setLinSpaced(size,low,low);\n    VERIFY_IS_APPROX(m,VectorType::Constant(size,low));\n\n    if(NumTraits<Scalar>::IsInteger)\n    {\n      VERIFY_IS_APPROX( VectorType::LinSpaced(size,low,low+Scalar(size-1)), VectorType::LinSpaced(size,low+Scalar(size-1),low).reverse() );\n\n      if(VectorType::SizeAtCompileTime==Dynamic)\n      {\n        // Check negative multiplicator path:\n        for(Index k=1; k<5; ++k)\n          VERIFY_IS_APPROX( VectorType::LinSpaced(size,low,low+Scalar((size-1)*k)), VectorType::LinSpaced(size,low+Scalar((size-1)*k),low).reverse() );\n        // Check negative divisor path:\n        for(Index k=1; k<5; ++k)\n          VERIFY_IS_APPROX( VectorType::LinSpaced(size*k,low,low+Scalar(size-1)), VectorType::LinSpaced(size*k,low+Scalar(size-1),low).reverse() );\n      }\n    }\n  }\n\n  // test setUnit()\n  if(m.size()>0)\n  {\n    for(Index k=0; k<10; ++k)\n    {\n      Index i = internal::random<Index>(0,m.size()-1);\n      m.setUnit(i);\n      VERIFY_IS_APPROX( m, VectorType::Unit(m.size(), i) );\n    }\n    if(VectorType::SizeAtCompileTime==Dynamic)\n    {\n      Index i = internal::random<Index>(0,2*m.size()-1);\n      m.setUnit(2*m.size(),i);\n      VERIFY_IS_APPROX( m, VectorType::Unit(m.size(),i) );\n    }\n  }\n\n}\n\ntemplate<typename MatrixType>\nvoid testMatrixType(const MatrixType& m)\n{\n  using std::abs;\n  const Index rows = m.rows();\n  const Index cols = m.cols();\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n\n  Scalar s1;\n  do {\n    s1 = internal::random<Scalar>();\n  } while(abs(s1)<RealScalar(1e-5) && (!NumTraits<Scalar>::IsInteger));\n\n  MatrixType A;\n  A.setIdentity(rows, cols);\n  VERIFY(equalsIdentity(A));\n  VERIFY(equalsIdentity(MatrixType::Identity(rows, cols)));\n\n\n  A = MatrixType::Constant(rows,cols,s1);\n  Index i = internal::random<Index>(0,rows-1);\n  Index j = internal::random<Index>(0,cols-1);\n  VERIFY_IS_APPROX( MatrixType::Constant(rows,cols,s1)(i,j), s1 );\n  VERIFY_IS_APPROX( MatrixType::Constant(rows,cols,s1).coeff(i,j), s1 );\n  VERIFY_IS_APPROX( A(i,j), s1 );\n}\n\ntemplate<int>\nvoid bug79()\n{\n  // Assignment of a RowVectorXd to a MatrixXd (regression test for bug #79).\n  VERIFY( (MatrixXd(RowVectorXd::LinSpaced(3, 0, 1)) - RowVector3d(0, 0.5, 1)).norm() < std::numeric_limits<double>::epsilon() );\n}\n\ntemplate<int>\nvoid bug1630()\n{\n  Array4d x4 = Array4d::LinSpaced(0.0, 1.0);\n  Array3d x3(Array4d::LinSpaced(0.0, 1.0).head(3));\n  VERIFY_IS_APPROX(x4.head(3), x3);\n}\n\ntemplate<int>\nvoid nullary_overflow()\n{\n  // Check possible overflow issue\n  int n = 60000;\n  ArrayXi a1(n), a2(n);\n  a1.setLinSpaced(n, 0, n-1);\n  for(int i=0; i<n; ++i)\n    a2(i) = i;\n  VERIFY_IS_APPROX(a1,a2);\n}\n\ntemplate<int>\nvoid nullary_internal_logic()\n{\n  // check some internal logic\n  VERIFY((  internal::has_nullary_operator<internal::scalar_constant_op<double> >::value ));\n  VERIFY(( !internal::has_unary_operator<internal::scalar_constant_op<double> >::value ));\n  VERIFY(( !internal::has_binary_operator<internal::scalar_constant_op<double> >::value ));\n  VERIFY((  internal::functor_has_linear_access<internal::scalar_constant_op<double> >::ret ));\n\n  VERIFY(( !internal::has_nullary_operator<internal::scalar_identity_op<double> >::value ));\n  VERIFY(( !internal::has_unary_operator<internal::scalar_identity_op<double> >::value ));\n  VERIFY((  internal::has_binary_operator<internal::scalar_identity_op<double> >::value ));\n  VERIFY(( !internal::functor_has_linear_access<internal::scalar_identity_op<double> >::ret ));\n\n  VERIFY(( !internal::has_nullary_operator<internal::linspaced_op<float> >::value ));\n  VERIFY((  internal::has_unary_operator<internal::linspaced_op<float> >::value ));\n  VERIFY(( !internal::has_binary_operator<internal::linspaced_op<float> >::value ));\n  VERIFY((  internal::functor_has_linear_access<internal::linspaced_op<float> >::ret ));\n\n  // Regression unit test for a weird MSVC bug.\n  // Search \"nullary_wrapper_workaround_msvc\" in CoreEvaluators.h for the details.\n  // See also traits<Ref>::match.\n  {\n    MatrixXf A = MatrixXf::Random(3,3);\n    Ref<const MatrixXf> R = 2.0*A;\n    VERIFY_IS_APPROX(R, A+A);\n\n    Ref<const MatrixXf> R1 = MatrixXf::Random(3,3)+A;\n\n    VectorXi V = VectorXi::Random(3);\n    Ref<const VectorXi> R2 = VectorXi::LinSpaced(3,1,3)+V;\n    VERIFY_IS_APPROX(R2, V+Vector3i(1,2,3));\n\n    VERIFY((  internal::has_nullary_operator<internal::scalar_constant_op<float> >::value ));\n    VERIFY(( !internal::has_unary_operator<internal::scalar_constant_op<float> >::value ));\n    VERIFY(( !internal::has_binary_operator<internal::scalar_constant_op<float> >::value ));\n    VERIFY((  internal::functor_has_linear_access<internal::scalar_constant_op<float> >::ret ));\n\n    VERIFY(( !internal::has_nullary_operator<internal::linspaced_op<int> >::value ));\n    VERIFY((  internal::has_unary_operator<internal::linspaced_op<int> >::value ));\n    VERIFY(( !internal::has_binary_operator<internal::linspaced_op<int> >::value ));\n    VERIFY((  internal::functor_has_linear_access<internal::linspaced_op<int> >::ret ));\n  }\n}\n\nEIGEN_DECLARE_TEST(nullary)\n{\n  CALL_SUBTEST_1( testMatrixType(Matrix2d()) );\n  CALL_SUBTEST_2( testMatrixType(MatrixXcf(internal::random<int>(1,300),internal::random<int>(1,300))) );\n  CALL_SUBTEST_3( testMatrixType(MatrixXf(internal::random<int>(1,300),internal::random<int>(1,300))) );\n  \n  for(int i = 0; i < g_repeat*10; i++) {\n    CALL_SUBTEST_3( testVectorType(VectorXcd(internal::random<int>(1,30000))) );\n    CALL_SUBTEST_4( testVectorType(VectorXd(internal::random<int>(1,30000))) );\n    CALL_SUBTEST_5( testVectorType(Vector4d()) );  // regression test for bug 232\n    CALL_SUBTEST_6( testVectorType(Vector3d()) );\n    CALL_SUBTEST_7( testVectorType(VectorXf(internal::random<int>(1,30000))) );\n    CALL_SUBTEST_8( testVectorType(Vector3f()) );\n    CALL_SUBTEST_8( testVectorType(Vector4f()) );\n    CALL_SUBTEST_8( testVectorType(Matrix<float,8,1>()) );\n    CALL_SUBTEST_8( testVectorType(Matrix<float,1,1>()) );\n\n    CALL_SUBTEST_9( testVectorType(VectorXi(internal::random<int>(1,10))) );\n    CALL_SUBTEST_9( testVectorType(VectorXi(internal::random<int>(9,300))) );\n    CALL_SUBTEST_9( testVectorType(Matrix<int,1,1>()) );\n  }\n\n  CALL_SUBTEST_6( bug79<0>() );\n  CALL_SUBTEST_6( bug1630<0>() );\n  CALL_SUBTEST_9( nullary_overflow<0>() );\n  CALL_SUBTEST_10( nullary_internal_logic<0>() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/num_dimensions.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2018 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/SparseCore>\n\ntemplate<int ExpectedDim,typename Xpr>\nvoid check_dim(const Xpr& ) {\n  STATIC_CHECK( Xpr::NumDimensions == ExpectedDim );\n}\n\n#if EIGEN_HAS_CXX11\ntemplate<template <typename,int,int> class Object>\nvoid map_num_dimensions()\n{\n  typedef Object<double, 1, 1> ArrayScalarType;\n  typedef Object<double, 2, 1> ArrayVectorType;\n  typedef Object<double, 1, 2> TransposeArrayVectorType;\n  typedef Object<double, 2, 2> ArrayType;\n  typedef Object<double, Eigen::Dynamic, 1> DynamicArrayVectorType;\n  typedef Object<double, 1, Eigen::Dynamic> DynamicTransposeArrayVectorType;\n  typedef Object<double, Eigen::Dynamic, Eigen::Dynamic> DynamicArrayType;\n\n  STATIC_CHECK(ArrayScalarType::NumDimensions == 0);\n  STATIC_CHECK(ArrayVectorType::NumDimensions == 1);\n  STATIC_CHECK(TransposeArrayVectorType::NumDimensions == 1);\n  STATIC_CHECK(ArrayType::NumDimensions == 2);\n  STATIC_CHECK(DynamicArrayVectorType::NumDimensions == 1);\n  STATIC_CHECK(DynamicTransposeArrayVectorType::NumDimensions == 1);\n  STATIC_CHECK(DynamicArrayType::NumDimensions == 2);\n\n  typedef Eigen::Map<ArrayScalarType> ArrayScalarMap;\n  typedef Eigen::Map<ArrayVectorType> ArrayVectorMap;\n  typedef Eigen::Map<TransposeArrayVectorType> TransposeArrayVectorMap;\n  typedef Eigen::Map<ArrayType> ArrayMap;\n  typedef Eigen::Map<DynamicArrayVectorType> DynamicArrayVectorMap;\n  typedef Eigen::Map<DynamicTransposeArrayVectorType> DynamicTransposeArrayVectorMap;\n  typedef Eigen::Map<DynamicArrayType> DynamicArrayMap;\n\n  STATIC_CHECK(ArrayScalarMap::NumDimensions == 0);\n  STATIC_CHECK(ArrayVectorMap::NumDimensions == 1);\n  STATIC_CHECK(TransposeArrayVectorMap::NumDimensions == 1);\n  STATIC_CHECK(ArrayMap::NumDimensions == 2);\n  STATIC_CHECK(DynamicArrayVectorMap::NumDimensions == 1);\n  STATIC_CHECK(DynamicTransposeArrayVectorMap::NumDimensions == 1);\n  STATIC_CHECK(DynamicArrayMap::NumDimensions == 2);\n}\n\ntemplate<typename Scalar, int Rows, int Cols>\nusing TArray = Array<Scalar,Rows,Cols>;\n\ntemplate<typename Scalar, int Rows, int Cols>\nusing TMatrix = Matrix<Scalar,Rows,Cols>;\n\n#endif\n\nEIGEN_DECLARE_TEST(num_dimensions)\n{\n  int n = 10;\n  ArrayXXd A(n,n);\n  CALL_SUBTEST( check_dim<2>(A) );\n  CALL_SUBTEST( check_dim<2>(A.block(1,1,2,2)) );\n  CALL_SUBTEST( check_dim<1>(A.col(1)) );\n  CALL_SUBTEST( check_dim<1>(A.row(1)) );\n\n  MatrixXd M(n,n);\n  CALL_SUBTEST( check_dim<0>(M.row(1)*M.col(1)) );\n\n  SparseMatrix<double> S(n,n);\n  CALL_SUBTEST( check_dim<2>(S) );\n  CALL_SUBTEST( check_dim<2>(S.block(1,1,2,2)) );\n  CALL_SUBTEST( check_dim<1>(S.col(1)) );\n  CALL_SUBTEST( check_dim<1>(S.row(1)) );\n\n  SparseVector<double> s(n);\n  CALL_SUBTEST( check_dim<1>(s) );\n  CALL_SUBTEST( check_dim<1>(s.head(2)) );\n  \n\n  #if EIGEN_HAS_CXX11\n  CALL_SUBTEST( map_num_dimensions<TArray>() );\n  CALL_SUBTEST( map_num_dimensions<TMatrix>() );\n  #endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/numext.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2017 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename T, typename U>\nbool check_if_equal_or_nans(const T& actual, const U& expected) {\n  return ((actual == expected) || ((numext::isnan)(actual) && (numext::isnan)(expected)));\n}\n\ntemplate<typename T, typename U>\nbool check_if_equal_or_nans(const std::complex<T>& actual, const std::complex<U>& expected) {\n  return check_if_equal_or_nans(numext::real(actual), numext::real(expected))\n         && check_if_equal_or_nans(numext::imag(actual), numext::imag(expected));\n}\n\ntemplate<typename T, typename U>\nbool test_is_equal_or_nans(const T& actual, const U& expected)\n{\n    if (check_if_equal_or_nans(actual, expected)) {\n      return true;\n    }\n\n    // false:\n    std::cerr\n        << \"\\n    actual   = \" << actual\n        << \"\\n    expected = \" << expected << \"\\n\\n\";\n    return false;\n}\n\n#define VERIFY_IS_EQUAL_OR_NANS(a, b) VERIFY(test_is_equal_or_nans(a, b))\n\ntemplate<typename T>\nvoid check_abs() {\n  typedef typename NumTraits<T>::Real Real;\n  Real zero(0);\n\n  if(NumTraits<T>::IsSigned)\n    VERIFY_IS_EQUAL(numext::abs(-T(1)), T(1));\n  VERIFY_IS_EQUAL(numext::abs(T(0)), T(0));\n  VERIFY_IS_EQUAL(numext::abs(T(1)), T(1));\n\n  for(int k=0; k<100; ++k)\n  {\n    T x = internal::random<T>();\n    if(!internal::is_same<T,bool>::value)\n      x = x/Real(2);\n    if(NumTraits<T>::IsSigned)\n    {\n      VERIFY_IS_EQUAL(numext::abs(x), numext::abs(-x));\n      VERIFY( numext::abs(-x) >= zero );\n    }\n    VERIFY( numext::abs(x) >= zero );\n    VERIFY_IS_APPROX( numext::abs2(x), numext::abs2(numext::abs(x)) );\n  }\n}\n\ntemplate<typename T>\nvoid check_arg() {\n  typedef typename NumTraits<T>::Real Real;\n  VERIFY_IS_EQUAL(numext::abs(T(0)), T(0));\n  VERIFY_IS_EQUAL(numext::abs(T(1)), T(1));\n\n  for(int k=0; k<100; ++k)\n  {\n    T x = internal::random<T>();\n    Real y = numext::arg(x);\n    VERIFY_IS_APPROX( y, std::arg(x) );\n  }\n}\n\ntemplate<typename T>\nstruct check_sqrt_impl {\n  static void run() {\n    for (int i=0; i<1000; ++i) {\n      const T x = numext::abs(internal::random<T>());\n      const T sqrtx = numext::sqrt(x);\n      VERIFY_IS_APPROX(sqrtx*sqrtx, x);\n    }\n\n    // Corner cases.\n    const T zero = T(0);\n    const T one = T(1);\n    const T inf = std::numeric_limits<T>::infinity();\n    const T nan = std::numeric_limits<T>::quiet_NaN();\n    VERIFY_IS_EQUAL(numext::sqrt(zero), zero);\n    VERIFY_IS_EQUAL(numext::sqrt(inf), inf);\n    VERIFY((numext::isnan)(numext::sqrt(nan)));\n    VERIFY((numext::isnan)(numext::sqrt(-one)));\n  }\n};\n\ntemplate<typename T>\nstruct check_sqrt_impl<std::complex<T>  > {\n  static void run() {\n    typedef typename std::complex<T> ComplexT;\n\n    for (int i=0; i<1000; ++i) {\n      const ComplexT x = internal::random<ComplexT>();\n      const ComplexT sqrtx = numext::sqrt(x);\n      VERIFY_IS_APPROX(sqrtx*sqrtx, x);\n    }\n\n    // Corner cases.\n    const T zero = T(0);\n    const T one = T(1);\n    const T inf = std::numeric_limits<T>::infinity();\n    const T nan = std::numeric_limits<T>::quiet_NaN();\n\n    // Set of corner cases from https://en.cppreference.com/w/cpp/numeric/complex/sqrt\n    const int kNumCorners = 20;\n    const ComplexT corners[kNumCorners][2] = {\n      {ComplexT(zero, zero), ComplexT(zero, zero)},\n      {ComplexT(-zero, zero), ComplexT(zero, zero)},\n      {ComplexT(zero, -zero), ComplexT(zero, zero)},\n      {ComplexT(-zero, -zero), ComplexT(zero, zero)},\n      {ComplexT(one, inf), ComplexT(inf, inf)},\n      {ComplexT(nan, inf), ComplexT(inf, inf)},\n      {ComplexT(one, -inf), ComplexT(inf, -inf)},\n      {ComplexT(nan, -inf), ComplexT(inf, -inf)},\n      {ComplexT(-inf, one), ComplexT(zero, inf)},\n      {ComplexT(inf, one), ComplexT(inf, zero)},\n      {ComplexT(-inf, -one), ComplexT(zero, -inf)},\n      {ComplexT(inf, -one), ComplexT(inf, -zero)},\n      {ComplexT(-inf, nan), ComplexT(nan, inf)},\n      {ComplexT(inf, nan), ComplexT(inf, nan)},\n      {ComplexT(zero, nan), ComplexT(nan, nan)},\n      {ComplexT(one, nan), ComplexT(nan, nan)},\n      {ComplexT(nan, zero), ComplexT(nan, nan)},\n      {ComplexT(nan, one), ComplexT(nan, nan)},\n      {ComplexT(nan, -one), ComplexT(nan, nan)},\n      {ComplexT(nan, nan), ComplexT(nan, nan)},\n    };\n\n    for (int i=0; i<kNumCorners; ++i) {\n      const ComplexT& x = corners[i][0];\n      const ComplexT sqrtx = corners[i][1];\n      VERIFY_IS_EQUAL_OR_NANS(numext::sqrt(x), sqrtx);\n    }\n  }\n};\n\ntemplate<typename T>\nvoid check_sqrt() {\n  check_sqrt_impl<T>::run();\n}\n\ntemplate<typename T>\nstruct check_rsqrt_impl {\n  static void run() {\n    const T zero = T(0);\n    const T one = T(1);\n    const T inf = std::numeric_limits<T>::infinity();\n    const T nan = std::numeric_limits<T>::quiet_NaN();\n\n    for (int i=0; i<1000; ++i) {\n      const T x = numext::abs(internal::random<T>());\n      const T rsqrtx = numext::rsqrt(x);\n      const T invx = one / x;\n      VERIFY_IS_APPROX(rsqrtx*rsqrtx, invx);\n    }\n\n    // Corner cases.\n    VERIFY_IS_EQUAL(numext::rsqrt(zero), inf);\n    VERIFY_IS_EQUAL(numext::rsqrt(inf), zero);\n    VERIFY((numext::isnan)(numext::rsqrt(nan)));\n    VERIFY((numext::isnan)(numext::rsqrt(-one)));\n  }\n};\n\ntemplate<typename T>\nstruct check_rsqrt_impl<std::complex<T> > {\n  static void run() {\n    typedef typename std::complex<T> ComplexT;\n    const T zero = T(0);\n    const T one = T(1);\n    const T inf = std::numeric_limits<T>::infinity();\n    const T nan = std::numeric_limits<T>::quiet_NaN();\n\n    for (int i=0; i<1000; ++i) {\n      const ComplexT x = internal::random<ComplexT>();\n      const ComplexT invx = ComplexT(one, zero) / x;\n      const ComplexT rsqrtx = numext::rsqrt(x);\n      VERIFY_IS_APPROX(rsqrtx*rsqrtx, invx);\n    }\n\n    // GCC and MSVC differ in their treatment of 1/(0 + 0i)\n    //   GCC/clang = (inf, nan)\n    //   MSVC = (nan, nan)\n    // and 1 / (x + inf i)\n    //   GCC/clang = (0, 0)\n    //   MSVC = (nan, nan)\n    #if (EIGEN_COMP_GNUC)\n    {\n      const int kNumCorners = 20;\n      const ComplexT corners[kNumCorners][2] = {\n        // Only consistent across GCC, clang\n        {ComplexT(zero, zero), ComplexT(zero, zero)},\n        {ComplexT(-zero, zero), ComplexT(zero, zero)},\n        {ComplexT(zero, -zero), ComplexT(zero, zero)},\n        {ComplexT(-zero, -zero), ComplexT(zero, zero)},\n        {ComplexT(one, inf), ComplexT(inf, inf)},\n        {ComplexT(nan, inf), ComplexT(inf, inf)},\n        {ComplexT(one, -inf), ComplexT(inf, -inf)},\n        {ComplexT(nan, -inf), ComplexT(inf, -inf)},\n        // Consistent across GCC, clang, MSVC\n        {ComplexT(-inf, one), ComplexT(zero, inf)},\n        {ComplexT(inf, one), ComplexT(inf, zero)},\n        {ComplexT(-inf, -one), ComplexT(zero, -inf)},\n        {ComplexT(inf, -one), ComplexT(inf, -zero)},\n        {ComplexT(-inf, nan), ComplexT(nan, inf)},\n        {ComplexT(inf, nan), ComplexT(inf, nan)},\n        {ComplexT(zero, nan), ComplexT(nan, nan)},\n        {ComplexT(one, nan), ComplexT(nan, nan)},\n        {ComplexT(nan, zero), ComplexT(nan, nan)},\n        {ComplexT(nan, one), ComplexT(nan, nan)},\n        {ComplexT(nan, -one), ComplexT(nan, nan)},\n        {ComplexT(nan, nan), ComplexT(nan, nan)},\n      };\n\n      for (int i=0; i<kNumCorners; ++i) {\n        const ComplexT& x = corners[i][0];\n        const ComplexT rsqrtx = ComplexT(one, zero) / corners[i][1];\n        VERIFY_IS_EQUAL_OR_NANS(numext::rsqrt(x), rsqrtx);\n      }\n    }\n    #endif\n  }\n};\n\ntemplate<typename T>\nvoid check_rsqrt() {\n  check_rsqrt_impl<T>::run();\n}\n\nEIGEN_DECLARE_TEST(numext) {\n  for(int k=0; k<g_repeat; ++k)\n  {\n    CALL_SUBTEST( check_abs<bool>() );\n    CALL_SUBTEST( check_abs<signed char>() );\n    CALL_SUBTEST( check_abs<unsigned char>() );\n    CALL_SUBTEST( check_abs<short>() );\n    CALL_SUBTEST( check_abs<unsigned short>() );\n    CALL_SUBTEST( check_abs<int>() );\n    CALL_SUBTEST( check_abs<unsigned int>() );\n    CALL_SUBTEST( check_abs<long>() );\n    CALL_SUBTEST( check_abs<unsigned long>() );\n    CALL_SUBTEST( check_abs<half>() );\n    CALL_SUBTEST( check_abs<bfloat16>() );\n    CALL_SUBTEST( check_abs<float>() );\n    CALL_SUBTEST( check_abs<double>() );\n    CALL_SUBTEST( check_abs<long double>() );\n    CALL_SUBTEST( check_abs<std::complex<float> >() );\n    CALL_SUBTEST( check_abs<std::complex<double> >() );\n\n    CALL_SUBTEST( check_arg<std::complex<float> >() );\n    CALL_SUBTEST( check_arg<std::complex<double> >() );\n\n    CALL_SUBTEST( check_sqrt<float>() );\n    CALL_SUBTEST( check_sqrt<double>() );\n    CALL_SUBTEST( check_sqrt<std::complex<float> >() );\n    CALL_SUBTEST( check_sqrt<std::complex<double> >() );\n    \n    CALL_SUBTEST( check_rsqrt<float>() );\n    CALL_SUBTEST( check_rsqrt<double>() );\n    CALL_SUBTEST( check_rsqrt<std::complex<float> >() );\n    CALL_SUBTEST( check_rsqrt<std::complex<double> >() );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/packetmath.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"packetmath_test_shared.h\"\n#include \"random_without_cast_overflow.h\"\n\ntemplate <typename T>\ninline T REF_ADD(const T& a, const T& b) {\n  return a + b;\n}\ntemplate <typename T>\ninline T REF_SUB(const T& a, const T& b) {\n  return a - b;\n}\ntemplate <typename T>\ninline T REF_MUL(const T& a, const T& b) {\n  return a * b;\n}\ntemplate <typename T>\ninline T REF_DIV(const T& a, const T& b) {\n  return a / b;\n}\ntemplate <typename T>\ninline T REF_ABS_DIFF(const T& a, const T& b) {\n  return a > b ? a - b : b - a;\n}\n\n// Specializations for bool.\ntemplate <>\ninline bool REF_ADD(const bool& a, const bool& b) {\n  return a || b;\n}\ntemplate <>\ninline bool REF_SUB(const bool& a, const bool& b) {\n  return a ^ b;\n}\ntemplate <>\ninline bool REF_MUL(const bool& a, const bool& b) {\n  return a && b;\n}\n\ntemplate <typename T>\ninline T REF_FREXP(const T& x, T& exp) {\n  int iexp;\n  EIGEN_USING_STD(frexp)\n  const T out = static_cast<T>(frexp(x, &iexp));\n  exp = static_cast<T>(iexp);\n  return out;\n}\n\ntemplate <typename T>\ninline T REF_LDEXP(const T& x, const T& exp) {\n  EIGEN_USING_STD(ldexp)\n  return static_cast<T>(ldexp(x, static_cast<int>(exp)));\n}\n\n// Uses pcast to cast from one array to another.\ntemplate <typename SrcPacket, typename TgtPacket, int SrcCoeffRatio, int TgtCoeffRatio>\nstruct pcast_array;\n\ntemplate <typename SrcPacket, typename TgtPacket, int TgtCoeffRatio>\nstruct pcast_array<SrcPacket, TgtPacket, 1, TgtCoeffRatio> {\n  typedef typename internal::unpacket_traits<SrcPacket>::type SrcScalar;\n  typedef typename internal::unpacket_traits<TgtPacket>::type TgtScalar;\n  static void cast(const SrcScalar* src, size_t size, TgtScalar* dst) {\n    static const int SrcPacketSize = internal::unpacket_traits<SrcPacket>::size;\n    static const int TgtPacketSize = internal::unpacket_traits<TgtPacket>::size;\n    size_t i;\n    for (i = 0; i < size && i + SrcPacketSize <= size; i += TgtPacketSize) {\n      internal::pstoreu(dst + i, internal::pcast<SrcPacket, TgtPacket>(internal::ploadu<SrcPacket>(src + i)));\n    }\n    // Leftovers that cannot be loaded into a packet.\n    for (; i < size; ++i) {\n      dst[i] = static_cast<TgtScalar>(src[i]);\n    }\n  }\n};\n\ntemplate <typename SrcPacket, typename TgtPacket>\nstruct pcast_array<SrcPacket, TgtPacket, 2, 1> {\n  static void cast(const typename internal::unpacket_traits<SrcPacket>::type* src, size_t size,\n                   typename internal::unpacket_traits<TgtPacket>::type* dst) {\n    static const int SrcPacketSize = internal::unpacket_traits<SrcPacket>::size;\n    static const int TgtPacketSize = internal::unpacket_traits<TgtPacket>::size;\n    for (size_t i = 0; i < size; i += TgtPacketSize) {\n      SrcPacket a = internal::ploadu<SrcPacket>(src + i);\n      SrcPacket b = internal::ploadu<SrcPacket>(src + i + SrcPacketSize);\n      internal::pstoreu(dst + i, internal::pcast<SrcPacket, TgtPacket>(a, b));\n    }\n  }\n};\n\ntemplate <typename SrcPacket, typename TgtPacket>\nstruct pcast_array<SrcPacket, TgtPacket, 4, 1> {\n  static void cast(const typename internal::unpacket_traits<SrcPacket>::type* src, size_t size,\n                   typename internal::unpacket_traits<TgtPacket>::type* dst) {\n    static const int SrcPacketSize = internal::unpacket_traits<SrcPacket>::size;\n    static const int TgtPacketSize = internal::unpacket_traits<TgtPacket>::size;\n    for (size_t i = 0; i < size; i += TgtPacketSize) {\n      SrcPacket a = internal::ploadu<SrcPacket>(src + i);\n      SrcPacket b = internal::ploadu<SrcPacket>(src + i + SrcPacketSize);\n      SrcPacket c = internal::ploadu<SrcPacket>(src + i + 2 * SrcPacketSize);\n      SrcPacket d = internal::ploadu<SrcPacket>(src + i + 3 * SrcPacketSize);\n      internal::pstoreu(dst + i, internal::pcast<SrcPacket, TgtPacket>(a, b, c, d));\n    }\n  }\n};\n\ntemplate <typename SrcPacket, typename TgtPacket>\nstruct pcast_array<SrcPacket, TgtPacket, 8, 1> {\n  static void cast(const typename internal::unpacket_traits<SrcPacket>::type* src, size_t size,\n                   typename internal::unpacket_traits<TgtPacket>::type* dst) {\n    static const int SrcPacketSize = internal::unpacket_traits<SrcPacket>::size;\n    static const int TgtPacketSize = internal::unpacket_traits<TgtPacket>::size;\n    for (size_t i = 0; i < size; i += TgtPacketSize) {\n      SrcPacket a = internal::ploadu<SrcPacket>(src + i);\n      SrcPacket b = internal::ploadu<SrcPacket>(src + i + SrcPacketSize);\n      SrcPacket c = internal::ploadu<SrcPacket>(src + i + 2 * SrcPacketSize);\n      SrcPacket d = internal::ploadu<SrcPacket>(src + i + 3 * SrcPacketSize);\n      SrcPacket e = internal::ploadu<SrcPacket>(src + i + 4 * SrcPacketSize);\n      SrcPacket f = internal::ploadu<SrcPacket>(src + i + 5 * SrcPacketSize);\n      SrcPacket g = internal::ploadu<SrcPacket>(src + i + 6 * SrcPacketSize);\n      SrcPacket h = internal::ploadu<SrcPacket>(src + i + 7 * SrcPacketSize);\n      internal::pstoreu(dst + i, internal::pcast<SrcPacket, TgtPacket>(a, b, c, d, e, f, g, h));\n    }\n  }\n};\n\ntemplate <typename SrcPacket, typename TgtPacket, int SrcCoeffRatio, int TgtCoeffRatio, bool CanCast = false>\nstruct test_cast_helper;\n\ntemplate <typename SrcPacket, typename TgtPacket, int SrcCoeffRatio, int TgtCoeffRatio>\nstruct test_cast_helper<SrcPacket, TgtPacket, SrcCoeffRatio, TgtCoeffRatio, false> {\n  static void run() {}\n};\n\ntemplate <typename SrcPacket, typename TgtPacket, int SrcCoeffRatio, int TgtCoeffRatio>\nstruct test_cast_helper<SrcPacket, TgtPacket, SrcCoeffRatio, TgtCoeffRatio, true> {\n  static void run() {\n    typedef typename internal::unpacket_traits<SrcPacket>::type SrcScalar;\n    typedef typename internal::unpacket_traits<TgtPacket>::type TgtScalar;\n    static const int SrcPacketSize = internal::unpacket_traits<SrcPacket>::size;\n    static const int TgtPacketSize = internal::unpacket_traits<TgtPacket>::size;\n    static const int BlockSize = SrcPacketSize * SrcCoeffRatio;\n    eigen_assert(BlockSize == TgtPacketSize * TgtCoeffRatio && \"Packet sizes and cast ratios are mismatched.\");\n\n    static const int DataSize = 10 * BlockSize;\n    EIGEN_ALIGN_MAX SrcScalar data1[DataSize];\n    EIGEN_ALIGN_MAX TgtScalar data2[DataSize];\n    EIGEN_ALIGN_MAX TgtScalar ref[DataSize];\n\n    // Construct a packet of scalars that will not overflow when casting\n    for (int i = 0; i < DataSize; ++i) {\n      data1[i] = internal::random_without_cast_overflow<SrcScalar, TgtScalar>::value();\n    }\n\n    for (int i = 0; i < DataSize; ++i) {\n      ref[i] = static_cast<const TgtScalar>(data1[i]);\n    }\n\n    pcast_array<SrcPacket, TgtPacket, SrcCoeffRatio, TgtCoeffRatio>::cast(data1, DataSize, data2);\n\n    VERIFY(test::areApprox(ref, data2, DataSize) && \"internal::pcast<>\");\n  }\n};\n\ntemplate <typename SrcPacket, typename TgtPacket>\nstruct test_cast {\n  static void run() {\n    typedef typename internal::unpacket_traits<SrcPacket>::type SrcScalar;\n    typedef typename internal::unpacket_traits<TgtPacket>::type TgtScalar;\n    typedef typename internal::type_casting_traits<SrcScalar, TgtScalar> TypeCastingTraits;\n    static const int SrcCoeffRatio = TypeCastingTraits::SrcCoeffRatio;\n    static const int TgtCoeffRatio = TypeCastingTraits::TgtCoeffRatio;\n    static const int SrcPacketSize = internal::unpacket_traits<SrcPacket>::size;\n    static const int TgtPacketSize = internal::unpacket_traits<TgtPacket>::size;\n    static const bool HasCast =\n        internal::unpacket_traits<SrcPacket>::vectorizable && internal::unpacket_traits<TgtPacket>::vectorizable &&\n        TypeCastingTraits::VectorizedCast && (SrcPacketSize * SrcCoeffRatio == TgtPacketSize * TgtCoeffRatio);\n    test_cast_helper<SrcPacket, TgtPacket, SrcCoeffRatio, TgtCoeffRatio, HasCast>::run();\n  }\n};\n\ntemplate <typename SrcPacket, typename TgtScalar,\n          typename TgtPacket = typename internal::packet_traits<TgtScalar>::type,\n          bool Vectorized = internal::packet_traits<TgtScalar>::Vectorizable,\n          bool HasHalf = !internal::is_same<typename internal::unpacket_traits<TgtPacket>::half, TgtPacket>::value>\nstruct test_cast_runner;\n\ntemplate <typename SrcPacket, typename TgtScalar, typename TgtPacket>\nstruct test_cast_runner<SrcPacket, TgtScalar, TgtPacket, true, false> {\n  static void run() { test_cast<SrcPacket, TgtPacket>::run(); }\n};\n\ntemplate <typename SrcPacket, typename TgtScalar, typename TgtPacket>\nstruct test_cast_runner<SrcPacket, TgtScalar, TgtPacket, true, true> {\n  static void run() {\n    test_cast<SrcPacket, TgtPacket>::run();\n    test_cast_runner<SrcPacket, TgtScalar, typename internal::unpacket_traits<TgtPacket>::half>::run();\n  }\n};\n\ntemplate <typename SrcPacket, typename TgtScalar, typename TgtPacket>\nstruct test_cast_runner<SrcPacket, TgtScalar, TgtPacket, false, false> {\n  static void run() {}\n};\n\ntemplate <typename Scalar, typename Packet, typename EnableIf = void>\nstruct packetmath_pcast_ops_runner {\n  static void run() {\n    test_cast_runner<Packet, float>::run();\n    test_cast_runner<Packet, double>::run();\n    test_cast_runner<Packet, int8_t>::run();\n    test_cast_runner<Packet, uint8_t>::run();\n    test_cast_runner<Packet, int16_t>::run();\n    test_cast_runner<Packet, uint16_t>::run();\n    test_cast_runner<Packet, int32_t>::run();\n    test_cast_runner<Packet, uint32_t>::run();\n    test_cast_runner<Packet, int64_t>::run();\n    test_cast_runner<Packet, uint64_t>::run();\n    test_cast_runner<Packet, bool>::run();\n    test_cast_runner<Packet, std::complex<float> >::run();\n    test_cast_runner<Packet, std::complex<double> >::run();\n    test_cast_runner<Packet, half>::run();\n    test_cast_runner<Packet, bfloat16>::run();\n  }\n};\n\n// Only some types support cast from std::complex<>.\ntemplate <typename Scalar, typename Packet>\nstruct packetmath_pcast_ops_runner<Scalar, Packet, typename internal::enable_if<NumTraits<Scalar>::IsComplex>::type> {\n  static void run() {\n    test_cast_runner<Packet, std::complex<float> >::run();\n    test_cast_runner<Packet, std::complex<double> >::run();\n    test_cast_runner<Packet, half>::run();\n    test_cast_runner<Packet, bfloat16>::run();\n  }\n};\n\ntemplate <typename Scalar, typename Packet>\nvoid packetmath_boolean_mask_ops() {\n  const int PacketSize = internal::unpacket_traits<Packet>::size;\n  const int size = 2 * PacketSize;\n  EIGEN_ALIGN_MAX Scalar data1[size];\n  EIGEN_ALIGN_MAX Scalar data2[size];\n  EIGEN_ALIGN_MAX Scalar ref[size];\n\n  for (int i = 0; i < size; ++i) {\n    data1[i] = internal::random<Scalar>();\n  }\n  CHECK_CWISE1(internal::ptrue, internal::ptrue);\n  CHECK_CWISE2_IF(true, internal::pandnot, internal::pandnot);\n  for (int i = 0; i < PacketSize; ++i) {\n    data1[i] = Scalar(i);\n    data1[i + PacketSize] = internal::random<bool>() ? data1[i] : Scalar(0);\n  }\n\n  CHECK_CWISE2_IF(true, internal::pcmp_eq, internal::pcmp_eq);\n\n  //Test (-0) == (0) for signed operations\n  for (int i = 0; i < PacketSize; ++i) {\n    data1[i] = Scalar(-0.0);\n    data1[i + PacketSize] = internal::random<bool>() ? data1[i] : Scalar(0);\n  }\n  CHECK_CWISE2_IF(true, internal::pcmp_eq, internal::pcmp_eq);\n\n  //Test NaN\n  for (int i = 0; i < PacketSize; ++i) {\n    data1[i] = NumTraits<Scalar>::quiet_NaN();\n    data1[i + PacketSize] = internal::random<bool>() ? data1[i] : Scalar(0);\n  }\n  CHECK_CWISE2_IF(true, internal::pcmp_eq, internal::pcmp_eq);\n}\n\ntemplate <typename Scalar, typename Packet>\nvoid packetmath_boolean_mask_ops_real() {\n  const int PacketSize = internal::unpacket_traits<Packet>::size;\n  const int size = 2 * PacketSize;\n  EIGEN_ALIGN_MAX Scalar data1[size];\n  EIGEN_ALIGN_MAX Scalar data2[size];\n  EIGEN_ALIGN_MAX Scalar ref[size];\n\n  for (int i = 0; i < PacketSize; ++i) {\n    data1[i] = internal::random<Scalar>();\n    data1[i + PacketSize] = internal::random<bool>() ? data1[i] : Scalar(0);\n  }\n\n  CHECK_CWISE2_IF(true, internal::pcmp_lt_or_nan, internal::pcmp_lt_or_nan);\n\n  //Test (-0) <=/< (0) for signed operations\n  for (int i = 0; i < PacketSize; ++i) {\n    data1[i] = Scalar(-0.0);\n    data1[i + PacketSize] = internal::random<bool>() ? data1[i] : Scalar(0);\n  }\n  CHECK_CWISE2_IF(true, internal::pcmp_lt_or_nan, internal::pcmp_lt_or_nan);\n\n  //Test NaN\n  for (int i = 0; i < PacketSize; ++i) {\n    data1[i] = NumTraits<Scalar>::quiet_NaN();\n    data1[i + PacketSize] = internal::random<bool>() ? data1[i] : Scalar(0);\n  }\n  CHECK_CWISE2_IF(true, internal::pcmp_lt_or_nan, internal::pcmp_lt_or_nan);\n}\n\ntemplate <typename Scalar, typename Packet>\nvoid packetmath_boolean_mask_ops_notcomplex() {\n  const int PacketSize = internal::unpacket_traits<Packet>::size;\n  const int size = 2 * PacketSize;\n  EIGEN_ALIGN_MAX Scalar data1[size];\n  EIGEN_ALIGN_MAX Scalar data2[size];\n  EIGEN_ALIGN_MAX Scalar ref[size];\n\n  for (int i = 0; i < PacketSize; ++i) {\n    data1[i] = internal::random<Scalar>();\n    data1[i + PacketSize] = internal::random<bool>() ? data1[i] : Scalar(0);\n  }\n\n  CHECK_CWISE2_IF(true, internal::pcmp_le, internal::pcmp_le);\n  CHECK_CWISE2_IF(true, internal::pcmp_lt, internal::pcmp_lt);\n\n  //Test (-0) <=/< (0) for signed operations\n  for (int i = 0; i < PacketSize; ++i) {\n    data1[i] = Scalar(-0.0);\n    data1[i + PacketSize] = internal::random<bool>() ? data1[i] : Scalar(0);\n  }\n  CHECK_CWISE2_IF(true, internal::pcmp_le, internal::pcmp_le);\n  CHECK_CWISE2_IF(true, internal::pcmp_lt, internal::pcmp_lt);\n\n  //Test NaN\n  for (int i = 0; i < PacketSize; ++i) {\n    data1[i] = NumTraits<Scalar>::quiet_NaN();\n    data1[i + PacketSize] = internal::random<bool>() ? data1[i] : Scalar(0);\n  }\n  CHECK_CWISE2_IF(true, internal::pcmp_le, internal::pcmp_le);\n  CHECK_CWISE2_IF(true, internal::pcmp_lt, internal::pcmp_lt);\n}\n\n// Packet16b representing bool does not support ptrue, pandnot or pcmp_eq, since the scalar path\n// (for some compilers) compute the bitwise and with 0x1 of the results to keep the value in [0,1].\ntemplate<>\nvoid packetmath_boolean_mask_ops<bool, internal::packet_traits<bool>::type>() {}\ntemplate<>\nvoid packetmath_boolean_mask_ops_notcomplex<bool, internal::packet_traits<bool>::type>() {}\n\ntemplate <typename Scalar, typename Packet>\nvoid packetmath_minus_zero_add() {\n  const int PacketSize = internal::unpacket_traits<Packet>::size;\n  const int size = 2 * PacketSize;\n  EIGEN_ALIGN_MAX Scalar data1[size];\n  EIGEN_ALIGN_MAX Scalar data2[size];\n  EIGEN_ALIGN_MAX Scalar ref[size];\n\n  for (int i = 0; i < PacketSize; ++i) {\n    data1[i] = Scalar(-0.0);\n    data1[i + PacketSize] = Scalar(-0.0);\n  }\n  CHECK_CWISE2_IF(internal::packet_traits<Scalar>::HasAdd, REF_ADD, internal::padd);\n}\n\n// Ensure optimization barrier compiles and doesn't modify contents.\n// Only applies to raw types, so will not work for std::complex, Eigen::half\n// or Eigen::bfloat16. For those you would need to refer to an underlying\n// storage element.\ntemplate<typename Packet, typename EnableIf = void>\nstruct eigen_optimization_barrier_test {\n  static void run() {}\n};\n\ntemplate<typename Packet>\nstruct eigen_optimization_barrier_test<Packet, typename internal::enable_if<\n    !NumTraits<Packet>::IsComplex &&\n    !internal::is_same<Packet, Eigen::half>::value &&\n    !internal::is_same<Packet, Eigen::bfloat16>::value\n  >::type> {\n  static void run() {\n    typedef typename internal::unpacket_traits<Packet>::type Scalar;\n    Scalar s = internal::random<Scalar>();\n    Packet barrier = internal::pset1<Packet>(s);\n    EIGEN_OPTIMIZATION_BARRIER(barrier);\n    eigen_assert(s == internal::pfirst(barrier) && \"EIGEN_OPTIMIZATION_BARRIER\");\n  }\n};\n\ntemplate <typename Scalar, typename Packet>\nvoid packetmath() {\n  typedef internal::packet_traits<Scalar> PacketTraits;\n  const int PacketSize = internal::unpacket_traits<Packet>::size;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  if (g_first_pass)\n    std::cerr << \"=== Testing packet of type '\" << typeid(Packet).name() << \"' and scalar type '\"\n              << typeid(Scalar).name() << \"' and size '\" << PacketSize << \"' ===\\n\";\n\n  const int max_size = PacketSize > 4 ? PacketSize : 4;\n  const int size = PacketSize * max_size;\n  EIGEN_ALIGN_MAX Scalar data1[size];\n  EIGEN_ALIGN_MAX Scalar data2[size];\n  EIGEN_ALIGN_MAX Scalar data3[size];\n  EIGEN_ALIGN_MAX Scalar ref[size];\n  RealScalar refvalue = RealScalar(0);\n\n  eigen_optimization_barrier_test<Packet>::run();\n  eigen_optimization_barrier_test<Scalar>::run();\n\n  for (int i = 0; i < size; ++i) {\n    data1[i] = internal::random<Scalar>() / RealScalar(PacketSize);\n    data2[i] = internal::random<Scalar>() / RealScalar(PacketSize);\n    refvalue = (std::max)(refvalue, numext::abs(data1[i]));\n  }\n\n  internal::pstore(data2, internal::pload<Packet>(data1));\n  VERIFY(test::areApprox(data1, data2, PacketSize) && \"aligned load/store\");\n\n  for (int offset = 0; offset < PacketSize; ++offset) {\n    internal::pstore(data2, internal::ploadu<Packet>(data1 + offset));\n    VERIFY(test::areApprox(data1 + offset, data2, PacketSize) && \"internal::ploadu\");\n  }\n\n  for (int offset = 0; offset < PacketSize; ++offset) {\n    internal::pstoreu(data2 + offset, internal::pload<Packet>(data1));\n    VERIFY(test::areApprox(data1, data2 + offset, PacketSize) && \"internal::pstoreu\");\n  }\n\n  if (internal::unpacket_traits<Packet>::masked_load_available) {\n    test::packet_helper<internal::unpacket_traits<Packet>::masked_load_available, Packet> h;\n    unsigned long long max_umask = (0x1ull << PacketSize);\n\n    for (int offset = 0; offset < PacketSize; ++offset) {\n      for (unsigned long long umask = 0; umask < max_umask; ++umask) {\n        h.store(data2, h.load(data1 + offset, umask));\n        for (int k = 0; k < PacketSize; ++k) data3[k] = ((umask & (0x1ull << k)) >> k) ? data1[k + offset] : Scalar(0);\n        VERIFY(test::areApprox(data3, data2, PacketSize) && \"internal::ploadu masked\");\n      }\n    }\n  }\n\n  if (internal::unpacket_traits<Packet>::masked_store_available) {\n    test::packet_helper<internal::unpacket_traits<Packet>::masked_store_available, Packet> h;\n    unsigned long long max_umask = (0x1ull << PacketSize);\n\n    for (int offset = 0; offset < PacketSize; ++offset) {\n      for (unsigned long long umask = 0; umask < max_umask; ++umask) {\n        internal::pstore(data2, internal::pset1<Packet>(Scalar(0)));\n        h.store(data2, h.loadu(data1 + offset), umask);\n        for (int k = 0; k < PacketSize; ++k) data3[k] = ((umask & (0x1ull << k)) >> k) ? data1[k + offset] : Scalar(0);\n        VERIFY(test::areApprox(data3, data2, PacketSize) && \"internal::pstoreu masked\");\n      }\n    }\n  }\n\n  VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasAdd);\n  VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasSub);\n  VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasMul);\n\n  CHECK_CWISE2_IF(PacketTraits::HasAdd, REF_ADD, internal::padd);\n  CHECK_CWISE2_IF(PacketTraits::HasSub, REF_SUB, internal::psub);\n  CHECK_CWISE2_IF(PacketTraits::HasMul, REF_MUL, internal::pmul);\n  CHECK_CWISE2_IF(PacketTraits::HasDiv, REF_DIV, internal::pdiv);\n\n  if (PacketTraits::HasNegate) CHECK_CWISE1(internal::negate, internal::pnegate);\n  CHECK_CWISE1(numext::conj, internal::pconj);\n\n  for (int offset = 0; offset < 3; ++offset) {\n    for (int i = 0; i < PacketSize; ++i) ref[i] = data1[offset];\n    internal::pstore(data2, internal::pset1<Packet>(data1[offset]));\n    VERIFY(test::areApprox(ref, data2, PacketSize) && \"internal::pset1\");\n  }\n\n  {\n    for (int i = 0; i < PacketSize * 4; ++i) ref[i] = data1[i / PacketSize];\n    Packet A0, A1, A2, A3;\n    internal::pbroadcast4<Packet>(data1, A0, A1, A2, A3);\n    internal::pstore(data2 + 0 * PacketSize, A0);\n    internal::pstore(data2 + 1 * PacketSize, A1);\n    internal::pstore(data2 + 2 * PacketSize, A2);\n    internal::pstore(data2 + 3 * PacketSize, A3);\n    VERIFY(test::areApprox(ref, data2, 4 * PacketSize) && \"internal::pbroadcast4\");\n  }\n\n  {\n    for (int i = 0; i < PacketSize * 2; ++i) ref[i] = data1[i / PacketSize];\n    Packet A0, A1;\n    internal::pbroadcast2<Packet>(data1, A0, A1);\n    internal::pstore(data2 + 0 * PacketSize, A0);\n    internal::pstore(data2 + 1 * PacketSize, A1);\n    VERIFY(test::areApprox(ref, data2, 2 * PacketSize) && \"internal::pbroadcast2\");\n  }\n\n  VERIFY(internal::isApprox(data1[0], internal::pfirst(internal::pload<Packet>(data1))) && \"internal::pfirst\");\n\n  if (PacketSize > 1) {\n    // apply different offsets to check that ploaddup is robust to unaligned inputs\n    for (int offset = 0; offset < 4; ++offset) {\n      for (int i = 0; i < PacketSize / 2; ++i) ref[2 * i + 0] = ref[2 * i + 1] = data1[offset + i];\n      internal::pstore(data2, internal::ploaddup<Packet>(data1 + offset));\n      VERIFY(test::areApprox(ref, data2, PacketSize) && \"ploaddup\");\n    }\n  }\n\n  if (PacketSize > 2) {\n    // apply different offsets to check that ploadquad is robust to unaligned inputs\n    for (int offset = 0; offset < 4; ++offset) {\n      for (int i = 0; i < PacketSize / 4; ++i)\n        ref[4 * i + 0] = ref[4 * i + 1] = ref[4 * i + 2] = ref[4 * i + 3] = data1[offset + i];\n      internal::pstore(data2, internal::ploadquad<Packet>(data1 + offset));\n      VERIFY(test::areApprox(ref, data2, PacketSize) && \"ploadquad\");\n    }\n  }\n\n  ref[0] = Scalar(0);\n  for (int i = 0; i < PacketSize; ++i) ref[0] += data1[i];\n  VERIFY(test::isApproxAbs(ref[0], internal::predux(internal::pload<Packet>(data1)), refvalue) && \"internal::predux\");\n\n  if (!internal::is_same<Packet, typename internal::unpacket_traits<Packet>::half>::value) {\n    int HalfPacketSize = PacketSize > 4 ? PacketSize / 2 : PacketSize;\n    for (int i = 0; i < HalfPacketSize; ++i) ref[i] = Scalar(0);\n    for (int i = 0; i < PacketSize; ++i) ref[i % HalfPacketSize] += data1[i];\n    internal::pstore(data2, internal::predux_half_dowto4(internal::pload<Packet>(data1)));\n    VERIFY(test::areApprox(ref, data2, HalfPacketSize) && \"internal::predux_half_dowto4\");\n  }\n\n  ref[0] = Scalar(1);\n  for (int i = 0; i < PacketSize; ++i) ref[0] = REF_MUL(ref[0], data1[i]);\n  VERIFY(internal::isApprox(ref[0], internal::predux_mul(internal::pload<Packet>(data1))) && \"internal::predux_mul\");\n\n  for (int i = 0; i < PacketSize; ++i) ref[i] = data1[PacketSize - i - 1];\n  internal::pstore(data2, internal::preverse(internal::pload<Packet>(data1)));\n  VERIFY(test::areApprox(ref, data2, PacketSize) && \"internal::preverse\");\n\n  internal::PacketBlock<Packet> kernel;\n  for (int i = 0; i < PacketSize; ++i) {\n    kernel.packet[i] = internal::pload<Packet>(data1 + i * PacketSize);\n  }\n  ptranspose(kernel);\n  for (int i = 0; i < PacketSize; ++i) {\n    internal::pstore(data2, kernel.packet[i]);\n    for (int j = 0; j < PacketSize; ++j) {\n      VERIFY(test::isApproxAbs(data2[j], data1[i + j * PacketSize], refvalue) && \"ptranspose\");\n    }\n  }\n\n  // GeneralBlockPanelKernel also checks PacketBlock<Packet,(PacketSize%4)==0?4:PacketSize>;\n  if (PacketSize > 4 && PacketSize % 4 == 0) {\n    internal::PacketBlock<Packet, PacketSize%4==0?4:PacketSize> kernel2;\n    for (int i = 0; i < 4; ++i) {\n      kernel2.packet[i] = internal::pload<Packet>(data1 + i * PacketSize);\n    }\n    ptranspose(kernel2);\n    int data_counter = 0;\n    for (int i = 0; i < PacketSize; ++i) {\n      for (int j = 0; j < 4; ++j) {\n        data2[data_counter++] = data1[j*PacketSize + i];\n      }\n    }\n    for (int i = 0; i < 4; ++i) {\n      internal::pstore(data3, kernel2.packet[i]);\n      for (int j = 0; j < PacketSize; ++j) {\n        VERIFY(test::isApproxAbs(data3[j], data2[i*PacketSize + j], refvalue) && \"ptranspose\");\n      }\n    }\n  }\n\n  if (PacketTraits::HasBlend) {\n    Packet thenPacket = internal::pload<Packet>(data1);\n    Packet elsePacket = internal::pload<Packet>(data2);\n    EIGEN_ALIGN_MAX internal::Selector<PacketSize> selector;\n    for (int i = 0; i < PacketSize; ++i) {\n      selector.select[i] = i;\n    }\n\n    Packet blend = internal::pblend(selector, thenPacket, elsePacket);\n    EIGEN_ALIGN_MAX Scalar result[size];\n    internal::pstore(result, blend);\n    for (int i = 0; i < PacketSize; ++i) {\n      VERIFY(test::isApproxAbs(result[i], (selector.select[i] ? data1[i] : data2[i]), refvalue));\n    }\n  }\n\n  {\n    for (int i = 0; i < PacketSize; ++i) {\n      // \"if\" mask\n      unsigned char v = internal::random<bool>() ? 0xff : 0;\n      char* bytes = (char*)(data1 + i);\n      for (int k = 0; k < int(sizeof(Scalar)); ++k) {\n        bytes[k] = v;\n      }\n      // \"then\" packet\n      data1[i + PacketSize] = internal::random<Scalar>();\n      // \"else\" packet\n      data1[i + 2 * PacketSize] = internal::random<Scalar>();\n    }\n    CHECK_CWISE3_IF(true, internal::pselect, internal::pselect);\n  }\n\n  for (int i = 0; i < size; ++i) {\n    data1[i] = internal::random<Scalar>();\n  }\n  CHECK_CWISE1(internal::pzero, internal::pzero);\n  CHECK_CWISE2_IF(true, internal::por, internal::por);\n  CHECK_CWISE2_IF(true, internal::pxor, internal::pxor);\n  CHECK_CWISE2_IF(true, internal::pand, internal::pand);\n\n  packetmath_boolean_mask_ops<Scalar, Packet>();\n  packetmath_pcast_ops_runner<Scalar, Packet>::run();\n  packetmath_minus_zero_add<Scalar, Packet>();\n\n  for (int i = 0; i < size; ++i) {\n    data1[i] = numext::abs(internal::random<Scalar>());\n  }\n  CHECK_CWISE1_IF(PacketTraits::HasSqrt, numext::sqrt, internal::psqrt);\n  CHECK_CWISE1_IF(PacketTraits::HasRsqrt, numext::rsqrt, internal::prsqrt);\n}\n\n// Notice that this definition works for complex types as well.\n// c++11 has std::log2 for real, but not for complex types.\ntemplate <typename Scalar>\nScalar log2(Scalar x) {\n  return Scalar(EIGEN_LOG2E) * std::log(x);\n}\n\ntemplate <typename Scalar, typename Packet>\nvoid packetmath_real() {\n  typedef internal::packet_traits<Scalar> PacketTraits;\n  const int PacketSize = internal::unpacket_traits<Packet>::size;\n\n  const int size = PacketSize * 4;\n  EIGEN_ALIGN_MAX Scalar data1[PacketSize * 4];\n  EIGEN_ALIGN_MAX Scalar data2[PacketSize * 4];\n  EIGEN_ALIGN_MAX Scalar ref[PacketSize * 4];\n\n  for (int i = 0; i < size; ++i) {\n    data1[i] = Scalar(internal::random<double>(0, 1) * std::pow(10., internal::random<double>(-6, 6)));\n    data2[i] = Scalar(internal::random<double>(0, 1) * std::pow(10., internal::random<double>(-6, 6)));\n  }\n\n  if (internal::random<float>(0, 1) < 0.1f) data1[internal::random<int>(0, PacketSize)] = Scalar(0);\n\n  CHECK_CWISE1_IF(PacketTraits::HasLog, std::log, internal::plog);\n  CHECK_CWISE1_IF(PacketTraits::HasLog, log2, internal::plog2);\n  CHECK_CWISE1_IF(PacketTraits::HasRsqrt, numext::rsqrt, internal::prsqrt);\n\n  for (int i = 0; i < size; ++i) {\n    data1[i] = Scalar(internal::random<double>(-1, 1) * std::pow(10., internal::random<double>(-3, 3)));\n    data2[i] = Scalar(internal::random<double>(-1, 1) * std::pow(10., internal::random<double>(-3, 3)));\n  }\n  CHECK_CWISE1_IF(PacketTraits::HasSin, std::sin, internal::psin);\n  CHECK_CWISE1_IF(PacketTraits::HasCos, std::cos, internal::pcos);\n  CHECK_CWISE1_IF(PacketTraits::HasTan, std::tan, internal::ptan);\n\n  CHECK_CWISE1_EXACT_IF(PacketTraits::HasRound, numext::round, internal::pround);\n  CHECK_CWISE1_EXACT_IF(PacketTraits::HasCeil, numext::ceil, internal::pceil);\n  CHECK_CWISE1_EXACT_IF(PacketTraits::HasFloor, numext::floor, internal::pfloor);\n  CHECK_CWISE1_EXACT_IF(PacketTraits::HasRint, numext::rint, internal::print);\n\n  packetmath_boolean_mask_ops_real<Scalar,Packet>();\n  \n  // Rounding edge cases.\n  if (PacketTraits::HasRound || PacketTraits::HasCeil || PacketTraits::HasFloor || PacketTraits::HasRint) {\n    typedef typename internal::make_integer<Scalar>::type IntType;\n    // Start with values that cannot fit inside an integer, work down to less than one.\n    Scalar val = numext::mini(\n        Scalar(2) * static_cast<Scalar>(NumTraits<IntType>::highest()),\n        NumTraits<Scalar>::highest());\n    std::vector<Scalar> values;\n    while (val > Scalar(0.25)) {\n      // Cover both even and odd, positive and negative cases.\n      values.push_back(val);\n      values.push_back(val + Scalar(0.3));\n      values.push_back(val + Scalar(0.5));\n      values.push_back(val + Scalar(0.8));\n      values.push_back(val + Scalar(1));\n      values.push_back(val + Scalar(1.3));\n      values.push_back(val + Scalar(1.5));\n      values.push_back(val + Scalar(1.8));\n      values.push_back(-val);\n      values.push_back(-val - Scalar(0.3));\n      values.push_back(-val - Scalar(0.5));\n      values.push_back(-val - Scalar(0.8));\n      values.push_back(-val - Scalar(1));\n      values.push_back(-val - Scalar(1.3));\n      values.push_back(-val - Scalar(1.5));\n      values.push_back(-val - Scalar(1.8));\n      values.push_back(Scalar(-1.5) + val);  // Bug 1785.\n      val = val / Scalar(2);\n    }\n    values.push_back(NumTraits<Scalar>::infinity());\n    values.push_back(-NumTraits<Scalar>::infinity());\n    values.push_back(NumTraits<Scalar>::quiet_NaN());\n    \n    for (size_t k=0; k<values.size(); ++k) {\n      data1[0] = values[k];\n      CHECK_CWISE1_EXACT_IF(PacketTraits::HasRound, numext::round, internal::pround);\n      CHECK_CWISE1_EXACT_IF(PacketTraits::HasCeil, numext::ceil, internal::pceil);\n      CHECK_CWISE1_EXACT_IF(PacketTraits::HasFloor, numext::floor, internal::pfloor);\n      CHECK_CWISE1_EXACT_IF(PacketTraits::HasRint, numext::rint, internal::print);\n    }\n  }\n\n  for (int i = 0; i < size; ++i) {\n    data1[i] = Scalar(internal::random<double>(-1, 1));\n    data2[i] = Scalar(internal::random<double>(-1, 1));\n  }\n  CHECK_CWISE1_IF(PacketTraits::HasASin, std::asin, internal::pasin);\n  CHECK_CWISE1_IF(PacketTraits::HasACos, std::acos, internal::pacos);\n\n  for (int i = 0; i < size; ++i) {\n    data1[i] = Scalar(internal::random<double>(-87, 88));\n    data2[i] = Scalar(internal::random<double>(-87, 88));\n  }\n  CHECK_CWISE1_IF(PacketTraits::HasExp, std::exp, internal::pexp);\n  \n  CHECK_CWISE1_BYREF1_IF(PacketTraits::HasExp, REF_FREXP, internal::pfrexp);\n  if (PacketTraits::HasExp) {\n    // Check denormals:\n    for (int j=0; j<3; ++j) {\n      data1[0] = Scalar(std::ldexp(1, NumTraits<Scalar>::min_exponent()-j));\n      CHECK_CWISE1_BYREF1_IF(PacketTraits::HasExp, REF_FREXP, internal::pfrexp);\n      data1[0] = -data1[0];\n      CHECK_CWISE1_BYREF1_IF(PacketTraits::HasExp, REF_FREXP, internal::pfrexp);\n    }\n    \n    // zero\n    data1[0] = Scalar(0);\n    CHECK_CWISE1_BYREF1_IF(PacketTraits::HasExp, REF_FREXP, internal::pfrexp);\n    \n    // inf and NaN only compare output fraction, not exponent.\n    test::packet_helper<PacketTraits::HasExp,Packet> h;\n    Packet pout;\n    Scalar sout;\n    Scalar special[] = { NumTraits<Scalar>::infinity(), \n                        -NumTraits<Scalar>::infinity(),\n                         NumTraits<Scalar>::quiet_NaN()};\n    for (int i=0; i<3; ++i) {\n      data1[0] = special[i];\n      ref[0] = Scalar(REF_FREXP(data1[0], ref[PacketSize]));\n      h.store(data2, internal::pfrexp(h.load(data1), h.forward_reference(pout, sout)));\n      VERIFY(test::areApprox(ref, data2, 1) && \"internal::pfrexp\");\n    }\n  }\n  \n  for (int i = 0; i < PacketSize; ++i) {\n    data1[i] = Scalar(internal::random<double>(-1, 1));\n    data2[i] = Scalar(internal::random<double>(-1, 1));\n  }\n  for (int i = 0; i < PacketSize; ++i) {\n    data1[i+PacketSize] = Scalar(internal::random<int>(-4, 4));\n    data2[i+PacketSize] = Scalar(internal::random<double>(-4, 4));\n  }\n  CHECK_CWISE2_IF(PacketTraits::HasExp, REF_LDEXP, internal::pldexp);\n  if (PacketTraits::HasExp) {\n    data1[0] = Scalar(-1);\n    // underflow to zero\n    data1[PacketSize] = Scalar(NumTraits<Scalar>::min_exponent()-55);\n    CHECK_CWISE2_IF(PacketTraits::HasExp, REF_LDEXP, internal::pldexp);\n    // overflow to inf\n    data1[PacketSize] = Scalar(NumTraits<Scalar>::max_exponent()+10);\n    CHECK_CWISE2_IF(PacketTraits::HasExp, REF_LDEXP, internal::pldexp);\n    // NaN stays NaN\n    data1[0] = NumTraits<Scalar>::quiet_NaN();\n    CHECK_CWISE2_IF(PacketTraits::HasExp, REF_LDEXP, internal::pldexp);\n    VERIFY((numext::isnan)(data2[0]));\n    // inf stays inf\n    data1[0] = NumTraits<Scalar>::infinity();\n    data1[PacketSize] = Scalar(NumTraits<Scalar>::min_exponent()-10);\n    CHECK_CWISE2_IF(PacketTraits::HasExp, REF_LDEXP, internal::pldexp);\n    // zero stays zero\n    data1[0] = Scalar(0);\n    data1[PacketSize] = Scalar(NumTraits<Scalar>::max_exponent()+10);\n    CHECK_CWISE2_IF(PacketTraits::HasExp, REF_LDEXP, internal::pldexp);\n    // Small number big exponent.\n    data1[0] = Scalar(std::ldexp(Scalar(1.0), NumTraits<Scalar>::min_exponent()-1));\n    data1[PacketSize] = Scalar(-NumTraits<Scalar>::min_exponent()\n                               +NumTraits<Scalar>::max_exponent());\n    CHECK_CWISE2_IF(PacketTraits::HasExp, REF_LDEXP, internal::pldexp);\n    // Big number small exponent.\n    data1[0] = Scalar(std::ldexp(Scalar(1.0), NumTraits<Scalar>::max_exponent()-1));\n    data1[PacketSize] = Scalar(+NumTraits<Scalar>::min_exponent()\n                               -NumTraits<Scalar>::max_exponent());\n    CHECK_CWISE2_IF(PacketTraits::HasExp, REF_LDEXP, internal::pldexp);\n  }\n\n  for (int i = 0; i < size; ++i) {\n    data1[i] = Scalar(internal::random<double>(-1, 1) * std::pow(10., internal::random<double>(-6, 6)));\n    data2[i] = Scalar(internal::random<double>(-1, 1) * std::pow(10., internal::random<double>(-6, 6)));\n  }\n  data1[0] = Scalar(1e-20);\n  CHECK_CWISE1_IF(PacketTraits::HasTanh, std::tanh, internal::ptanh);\n  if (PacketTraits::HasExp && PacketSize >= 2) {\n    const Scalar small = NumTraits<Scalar>::epsilon();\n    data1[0] = NumTraits<Scalar>::quiet_NaN();\n    data1[1] = small;\n    test::packet_helper<PacketTraits::HasExp, Packet> h;\n    h.store(data2, internal::pexp(h.load(data1)));\n    VERIFY((numext::isnan)(data2[0]));\n    // TODO(rmlarsen): Re-enable for bfloat16.\n    if (!internal::is_same<Scalar, bfloat16>::value) {\n      VERIFY_IS_APPROX(std::exp(small), data2[1]);\n    }\n\n    data1[0] = -small;\n    data1[1] = Scalar(0);\n    h.store(data2, internal::pexp(h.load(data1)));\n    // TODO(rmlarsen): Re-enable for bfloat16.\n    if (!internal::is_same<Scalar, bfloat16>::value) {\n      VERIFY_IS_APPROX(std::exp(-small), data2[0]);\n    }\n    VERIFY_IS_EQUAL(std::exp(Scalar(0)), data2[1]);\n\n    data1[0] = (std::numeric_limits<Scalar>::min)();\n    data1[1] = -(std::numeric_limits<Scalar>::min)();\n    h.store(data2, internal::pexp(h.load(data1)));\n    VERIFY_IS_APPROX(std::exp((std::numeric_limits<Scalar>::min)()), data2[0]);\n    VERIFY_IS_APPROX(std::exp(-(std::numeric_limits<Scalar>::min)()), data2[1]);\n\n    data1[0] = std::numeric_limits<Scalar>::denorm_min();\n    data1[1] = -std::numeric_limits<Scalar>::denorm_min();\n    h.store(data2, internal::pexp(h.load(data1)));\n    VERIFY_IS_APPROX(std::exp(std::numeric_limits<Scalar>::denorm_min()), data2[0]);\n    VERIFY_IS_APPROX(std::exp(-std::numeric_limits<Scalar>::denorm_min()), data2[1]);\n  }\n\n  if (PacketTraits::HasTanh) {\n    // NOTE this test migh fail with GCC prior to 6.3, see MathFunctionsImpl.h for details.\n    data1[0] = NumTraits<Scalar>::quiet_NaN();\n    test::packet_helper<internal::packet_traits<Scalar>::HasTanh, Packet> h;\n    h.store(data2, internal::ptanh(h.load(data1)));\n    VERIFY((numext::isnan)(data2[0]));\n  }\n\n  if (PacketTraits::HasExp) {\n    internal::scalar_logistic_op<Scalar> logistic;\n    for (int i = 0; i < size; ++i) {\n      data1[i] = Scalar(internal::random<double>(-20, 20));\n    }\n\n    test::packet_helper<PacketTraits::HasExp, Packet> h;\n    h.store(data2, logistic.packetOp(h.load(data1)));\n    for (int i = 0; i < PacketSize; ++i) {\n      VERIFY_IS_APPROX(data2[i], logistic(data1[i]));\n    }\n  }\n\n#if EIGEN_HAS_C99_MATH && (EIGEN_COMP_CXXVER >= 11)\n  data1[0] = NumTraits<Scalar>::infinity();\n  data1[1] = Scalar(-1);\n  CHECK_CWISE1_IF(PacketTraits::HasLog1p, std::log1p, internal::plog1p);\n  data1[0] = NumTraits<Scalar>::infinity();\n  data1[1] = -NumTraits<Scalar>::infinity();\n  CHECK_CWISE1_IF(PacketTraits::HasExpm1, std::expm1, internal::pexpm1);\n#endif\n\n  if (PacketSize >= 2) {\n    data1[0] = NumTraits<Scalar>::quiet_NaN();\n    data1[1] = NumTraits<Scalar>::epsilon();\n    if (PacketTraits::HasLog) {\n      test::packet_helper<PacketTraits::HasLog, Packet> h;\n      h.store(data2, internal::plog(h.load(data1)));\n      VERIFY((numext::isnan)(data2[0]));\n      // TODO(cantonios): Re-enable for bfloat16.\n      if (!internal::is_same<Scalar, bfloat16>::value) {\n        VERIFY_IS_APPROX(std::log(data1[1]), data2[1]);\n      }\n\n      data1[0] = -NumTraits<Scalar>::epsilon();\n      data1[1] = Scalar(0);\n      h.store(data2, internal::plog(h.load(data1)));\n      VERIFY((numext::isnan)(data2[0]));\n      VERIFY_IS_EQUAL(std::log(Scalar(0)), data2[1]);\n\n      data1[0] = (std::numeric_limits<Scalar>::min)();\n      data1[1] = -(std::numeric_limits<Scalar>::min)();\n      h.store(data2, internal::plog(h.load(data1)));\n      // TODO(cantonios): Re-enable for bfloat16.\n      if (!internal::is_same<Scalar, bfloat16>::value) {\n        VERIFY_IS_APPROX(std::log((std::numeric_limits<Scalar>::min)()), data2[0]);\n      }\n      VERIFY((numext::isnan)(data2[1]));\n\n      // Note: 32-bit arm always flushes denorms to zero.\n#if !EIGEN_ARCH_ARM\n      if (std::numeric_limits<Scalar>::has_denorm == std::denorm_present) {\n        data1[0] = std::numeric_limits<Scalar>::denorm_min();\n        data1[1] = -std::numeric_limits<Scalar>::denorm_min();\n        h.store(data2, internal::plog(h.load(data1)));\n        // TODO(rmlarsen): Reenable.\n        //        VERIFY_IS_EQUAL(std::log(std::numeric_limits<Scalar>::denorm_min()), data2[0]);\n        VERIFY((numext::isnan)(data2[1]));\n      }\n#endif\n\n      data1[0] = Scalar(-1.0f);\n      h.store(data2, internal::plog(h.load(data1)));\n      VERIFY((numext::isnan)(data2[0]));\n\n      data1[0] = NumTraits<Scalar>::infinity();\n      h.store(data2, internal::plog(h.load(data1)));\n      VERIFY((numext::isinf)(data2[0]));\n    }\n    if (PacketTraits::HasLog1p) {\n      test::packet_helper<PacketTraits::HasLog1p, Packet> h;\n      data1[0] = Scalar(-2);\n      data1[1] = -NumTraits<Scalar>::infinity();\n      h.store(data2, internal::plog1p(h.load(data1)));\n      VERIFY((numext::isnan)(data2[0]));\n      VERIFY((numext::isnan)(data2[1]));\n    }\n    if (PacketTraits::HasSqrt) {\n      test::packet_helper<PacketTraits::HasSqrt, Packet> h;\n      data1[0] = Scalar(-1.0f);\n      if (std::numeric_limits<Scalar>::has_denorm == std::denorm_present) {\n        data1[1] = -std::numeric_limits<Scalar>::denorm_min();\n      } else {\n        data1[1] = -NumTraits<Scalar>::epsilon();\n      }\n      h.store(data2, internal::psqrt(h.load(data1)));\n      VERIFY((numext::isnan)(data2[0]));\n      VERIFY((numext::isnan)(data2[1]));\n    }\n    // TODO(rmlarsen): Re-enable for half and bfloat16.\n    if (PacketTraits::HasCos\n        && !internal::is_same<Scalar, half>::value\n        && !internal::is_same<Scalar, bfloat16>::value) {\n      test::packet_helper<PacketTraits::HasCos, Packet> h;\n      for (Scalar k = Scalar(1); k < Scalar(10000) / NumTraits<Scalar>::epsilon(); k *= Scalar(2)) {\n        for (int k1 = 0; k1 <= 1; ++k1) {\n          data1[0] = Scalar((2 * double(k) + k1) * double(EIGEN_PI) / 2 * internal::random<double>(0.8, 1.2));\n          data1[1] = Scalar((2 * double(k) + 2 + k1) * double(EIGEN_PI) / 2 * internal::random<double>(0.8, 1.2));\n          h.store(data2, internal::pcos(h.load(data1)));\n          h.store(data2 + PacketSize, internal::psin(h.load(data1)));\n          VERIFY(data2[0] <= Scalar(1.) && data2[0] >= Scalar(-1.));\n          VERIFY(data2[1] <= Scalar(1.) && data2[1] >= Scalar(-1.));\n          VERIFY(data2[PacketSize + 0] <= Scalar(1.) && data2[PacketSize + 0] >= Scalar(-1.));\n          VERIFY(data2[PacketSize + 1] <= Scalar(1.) && data2[PacketSize + 1] >= Scalar(-1.));\n\n          VERIFY_IS_APPROX(data2[0], std::cos(data1[0]));\n          VERIFY_IS_APPROX(data2[1], std::cos(data1[1]));\n          VERIFY_IS_APPROX(data2[PacketSize + 0], std::sin(data1[0]));\n          VERIFY_IS_APPROX(data2[PacketSize + 1], std::sin(data1[1]));\n\n          VERIFY_IS_APPROX(numext::abs2(data2[0]) + numext::abs2(data2[PacketSize + 0]), Scalar(1));\n          VERIFY_IS_APPROX(numext::abs2(data2[1]) + numext::abs2(data2[PacketSize + 1]), Scalar(1));\n        }\n      }\n\n      data1[0] = NumTraits<Scalar>::infinity();\n      data1[1] = -NumTraits<Scalar>::infinity();\n      h.store(data2, internal::psin(h.load(data1)));\n      VERIFY((numext::isnan)(data2[0]));\n      VERIFY((numext::isnan)(data2[1]));\n\n      h.store(data2, internal::pcos(h.load(data1)));\n      VERIFY((numext::isnan)(data2[0]));\n      VERIFY((numext::isnan)(data2[1]));\n\n      data1[0] = NumTraits<Scalar>::quiet_NaN();\n      h.store(data2, internal::psin(h.load(data1)));\n      VERIFY((numext::isnan)(data2[0]));\n      h.store(data2, internal::pcos(h.load(data1)));\n      VERIFY((numext::isnan)(data2[0]));\n\n      data1[0] = -Scalar(0.);\n      h.store(data2, internal::psin(h.load(data1)));\n      VERIFY(internal::biteq(data2[0], data1[0]));\n      h.store(data2, internal::pcos(h.load(data1)));\n      VERIFY_IS_EQUAL(data2[0], Scalar(1));\n    }\n  }\n}\n\n#define CAST_CHECK_CWISE1_IF(COND, REFOP, POP, SCALAR, REFTYPE) if(COND) { \\\n  test::packet_helper<COND,Packet> h; \\\n  for (int i=0; i<PacketSize; ++i) \\\n    ref[i] = SCALAR(REFOP(static_cast<REFTYPE>(data1[i]))); \\\n  h.store(data2, POP(h.load(data1))); \\\n  VERIFY(test::areApprox(ref, data2, PacketSize) && #POP); \\\n}\n\ntemplate <typename Scalar>\nScalar propagate_nan_max(const Scalar& a, const Scalar& b) {\n  if ((numext::isnan)(a)) return a;\n  if ((numext::isnan)(b)) return b;\n  return (numext::maxi)(a,b);\n}\n\ntemplate <typename Scalar>\nScalar propagate_nan_min(const Scalar& a, const Scalar& b) {\n  if ((numext::isnan)(a)) return a;\n  if ((numext::isnan)(b)) return b;\n  return (numext::mini)(a,b);\n}\n\ntemplate <typename Scalar>\nScalar propagate_number_max(const Scalar& a, const Scalar& b) {\n  if ((numext::isnan)(a)) return b;\n  if ((numext::isnan)(b)) return a;\n  return (numext::maxi)(a,b);\n}\n\ntemplate <typename Scalar>\nScalar propagate_number_min(const Scalar& a, const Scalar& b) {\n  if ((numext::isnan)(a)) return b;\n  if ((numext::isnan)(b)) return a;\n  return (numext::mini)(a,b);\n}\n\ntemplate <typename Scalar, typename Packet>\nvoid packetmath_notcomplex() {\n  typedef internal::packet_traits<Scalar> PacketTraits;\n  const int PacketSize = internal::unpacket_traits<Packet>::size;\n\n  EIGEN_ALIGN_MAX Scalar data1[PacketSize * 4];\n  EIGEN_ALIGN_MAX Scalar data2[PacketSize * 4];\n  EIGEN_ALIGN_MAX Scalar ref[PacketSize * 4];\n\n  Array<Scalar, Dynamic, 1>::Map(data1, PacketSize * 4).setRandom();\n\n  VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasMin);\n  VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasMax);\n\n  CHECK_CWISE2_IF(PacketTraits::HasMin, (std::min), internal::pmin);\n  CHECK_CWISE2_IF(PacketTraits::HasMax, (std::max), internal::pmax);\n\n  CHECK_CWISE2_IF(PacketTraits::HasMin, propagate_number_min, internal::pmin<PropagateNumbers>);\n  CHECK_CWISE2_IF(PacketTraits::HasMax, propagate_number_max, internal::pmax<PropagateNumbers>);\n  CHECK_CWISE1(numext::abs, internal::pabs);\n  CHECK_CWISE2_IF(PacketTraits::HasAbsDiff, REF_ABS_DIFF, internal::pabsdiff);\n\n  ref[0] = data1[0];\n  for (int i = 0; i < PacketSize; ++i) ref[0] = internal::pmin(ref[0], data1[i]);\n  VERIFY(internal::isApprox(ref[0], internal::predux_min(internal::pload<Packet>(data1))) && \"internal::predux_min\");\n  ref[0] = data1[0];\n  for (int i = 0; i < PacketSize; ++i) ref[0] = internal::pmax(ref[0], data1[i]);\n  VERIFY(internal::isApprox(ref[0], internal::predux_max(internal::pload<Packet>(data1))) && \"internal::predux_max\");\n\n  for (int i = 0; i < PacketSize; ++i) ref[i] = data1[0] + Scalar(i);\n  internal::pstore(data2, internal::plset<Packet>(data1[0]));\n  VERIFY(test::areApprox(ref, data2, PacketSize) && \"internal::plset\");\n\n  {\n    unsigned char* data1_bits = reinterpret_cast<unsigned char*>(data1);\n    // predux_all - not needed yet\n    // for (unsigned int i=0; i<PacketSize*sizeof(Scalar); ++i) data1_bits[i] = 0xff;\n    // VERIFY(internal::predux_all(internal::pload<Packet>(data1)) && \"internal::predux_all(1111)\");\n    // for(int k=0; k<PacketSize; ++k)\n    // {\n    //   for (unsigned int i=0; i<sizeof(Scalar); ++i) data1_bits[k*sizeof(Scalar)+i] = 0x0;\n    //   VERIFY( (!internal::predux_all(internal::pload<Packet>(data1))) && \"internal::predux_all(0101)\");\n    //   for (unsigned int i=0; i<sizeof(Scalar); ++i) data1_bits[k*sizeof(Scalar)+i] = 0xff;\n    // }\n\n    // predux_any\n    for (unsigned int i = 0; i < PacketSize * sizeof(Scalar); ++i) data1_bits[i] = 0x0;\n    VERIFY((!internal::predux_any(internal::pload<Packet>(data1))) && \"internal::predux_any(0000)\");\n    for (int k = 0; k < PacketSize; ++k) {\n      for (unsigned int i = 0; i < sizeof(Scalar); ++i) data1_bits[k * sizeof(Scalar) + i] = 0xff;\n      VERIFY(internal::predux_any(internal::pload<Packet>(data1)) && \"internal::predux_any(0101)\");\n      for (unsigned int i = 0; i < sizeof(Scalar); ++i) data1_bits[k * sizeof(Scalar) + i] = 0x00;\n    }\n  }\n\n\n  // Test NaN propagation.\n  if (!NumTraits<Scalar>::IsInteger) {\n    // Test reductions with no NaNs.\n    ref[0] = data1[0];\n    for (int i = 0; i < PacketSize; ++i) ref[0] = internal::pmin<PropagateNumbers>(ref[0], data1[i]);\n    VERIFY(internal::isApprox(ref[0], internal::predux_min<PropagateNumbers>(internal::pload<Packet>(data1))) && \"internal::predux_min<PropagateNumbers>\");\n    ref[0] = data1[0];\n    for (int i = 0; i < PacketSize; ++i) ref[0] = internal::pmin<PropagateNaN>(ref[0], data1[i]);\n    VERIFY(internal::isApprox(ref[0], internal::predux_min<PropagateNaN>(internal::pload<Packet>(data1))) && \"internal::predux_min<PropagateNaN>\");\n    ref[0] = data1[0];\n    for (int i = 0; i < PacketSize; ++i) ref[0] = internal::pmax<PropagateNumbers>(ref[0], data1[i]);\n    VERIFY(internal::isApprox(ref[0], internal::predux_max<PropagateNumbers>(internal::pload<Packet>(data1))) && \"internal::predux_max<PropagateNumbers>\");\n    ref[0] = data1[0];\n    for (int i = 0; i < PacketSize; ++i) ref[0] = internal::pmax<PropagateNaN>(ref[0], data1[i]);\n    VERIFY(internal::isApprox(ref[0], internal::predux_max<PropagateNaN>(internal::pload<Packet>(data1))) && \"internal::predux_max<PropagateNumbers>\");\n    // A single NaN.\n    const size_t index = std::numeric_limits<size_t>::quiet_NaN() % PacketSize;\n    data1[index] = NumTraits<Scalar>::quiet_NaN();\n    VERIFY(PacketSize==1 || !(numext::isnan)(internal::predux_min<PropagateNumbers>(internal::pload<Packet>(data1))));\n    VERIFY((numext::isnan)(internal::predux_min<PropagateNaN>(internal::pload<Packet>(data1))));\n    VERIFY(PacketSize==1 || !(numext::isnan)(internal::predux_max<PropagateNumbers>(internal::pload<Packet>(data1))));\n    VERIFY((numext::isnan)(internal::predux_max<PropagateNaN>(internal::pload<Packet>(data1))));\n    // All NaNs.\n    for (int i = 0; i < 4 * PacketSize; ++i) data1[i] = NumTraits<Scalar>::quiet_NaN();\n    VERIFY((numext::isnan)(internal::predux_min<PropagateNumbers>(internal::pload<Packet>(data1))));\n    VERIFY((numext::isnan)(internal::predux_min<PropagateNaN>(internal::pload<Packet>(data1))));\n    VERIFY((numext::isnan)(internal::predux_max<PropagateNumbers>(internal::pload<Packet>(data1))));\n    VERIFY((numext::isnan)(internal::predux_max<PropagateNaN>(internal::pload<Packet>(data1))));\n\n    // Test NaN propagation for coefficient-wise min and max.\n    for (int i = 0; i < PacketSize; ++i) {\n      data1[i] = internal::random<bool>() ? NumTraits<Scalar>::quiet_NaN() : Scalar(0);\n      data1[i + PacketSize] = internal::random<bool>() ? NumTraits<Scalar>::quiet_NaN() : Scalar(0);\n    }\n    // Note: NaN propagation is implementation defined for pmin/pmax, so we do not test it here.\n    CHECK_CWISE2_IF(PacketTraits::HasMin, propagate_number_min, (internal::pmin<PropagateNumbers>));\n    CHECK_CWISE2_IF(PacketTraits::HasMax, propagate_number_max, internal::pmax<PropagateNumbers>);\n    CHECK_CWISE2_IF(PacketTraits::HasMin, propagate_nan_min, (internal::pmin<PropagateNaN>));\n    CHECK_CWISE2_IF(PacketTraits::HasMax, propagate_nan_max, internal::pmax<PropagateNaN>);\n  }\n\n  packetmath_boolean_mask_ops_notcomplex<Scalar, Packet>();\n}\n\ntemplate <typename Scalar, typename Packet, bool ConjLhs, bool ConjRhs>\nvoid test_conj_helper(Scalar* data1, Scalar* data2, Scalar* ref, Scalar* pval) {\n  const int PacketSize = internal::unpacket_traits<Packet>::size;\n\n  internal::conj_if<ConjLhs> cj0;\n  internal::conj_if<ConjRhs> cj1;\n  internal::conj_helper<Scalar, Scalar, ConjLhs, ConjRhs> cj;\n  internal::conj_helper<Packet, Packet, ConjLhs, ConjRhs> pcj;\n\n  for (int i = 0; i < PacketSize; ++i) {\n    ref[i] = cj0(data1[i]) * cj1(data2[i]);\n    VERIFY(internal::isApprox(ref[i], cj.pmul(data1[i], data2[i])) && \"conj_helper pmul\");\n  }\n  internal::pstore(pval, pcj.pmul(internal::pload<Packet>(data1), internal::pload<Packet>(data2)));\n  VERIFY(test::areApprox(ref, pval, PacketSize) && \"conj_helper pmul\");\n\n  for (int i = 0; i < PacketSize; ++i) {\n    Scalar tmp = ref[i];\n    ref[i] += cj0(data1[i]) * cj1(data2[i]);\n    VERIFY(internal::isApprox(ref[i], cj.pmadd(data1[i], data2[i], tmp)) && \"conj_helper pmadd\");\n  }\n  internal::pstore(\n      pval, pcj.pmadd(internal::pload<Packet>(data1), internal::pload<Packet>(data2), internal::pload<Packet>(pval)));\n  VERIFY(test::areApprox(ref, pval, PacketSize) && \"conj_helper pmadd\");\n}\n\ntemplate <typename Scalar, typename Packet>\nvoid packetmath_complex() {\n  typedef internal::packet_traits<Scalar> PacketTraits;\n  typedef typename Scalar::value_type RealScalar;\n  const int PacketSize = internal::unpacket_traits<Packet>::size;\n\n  const int size = PacketSize * 4;\n  EIGEN_ALIGN_MAX Scalar data1[PacketSize * 4];\n  EIGEN_ALIGN_MAX Scalar data2[PacketSize * 4];\n  EIGEN_ALIGN_MAX Scalar ref[PacketSize * 4];\n  EIGEN_ALIGN_MAX Scalar pval[PacketSize * 4];\n\n  for (int i = 0; i < size; ++i) {\n    data1[i] = internal::random<Scalar>() * Scalar(1e2);\n    data2[i] = internal::random<Scalar>() * Scalar(1e2);\n  }\n\n  test_conj_helper<Scalar, Packet, false, false>(data1, data2, ref, pval);\n  test_conj_helper<Scalar, Packet, false, true>(data1, data2, ref, pval);\n  test_conj_helper<Scalar, Packet, true, false>(data1, data2, ref, pval);\n  test_conj_helper<Scalar, Packet, true, true>(data1, data2, ref, pval);\n\n  // Test pcplxflip.\n  {\n    for (int i = 0; i < PacketSize; ++i) ref[i] = Scalar(std::imag(data1[i]), std::real(data1[i]));\n    internal::pstore(pval, internal::pcplxflip(internal::pload<Packet>(data1)));\n    VERIFY(test::areApprox(ref, pval, PacketSize) && \"pcplxflip\");\n  }\n\n  if (PacketTraits::HasSqrt) {\n    for (int i = 0; i < size; ++i) {\n      data1[i] = Scalar(internal::random<RealScalar>(), internal::random<RealScalar>());\n    }\n    CHECK_CWISE1_N(numext::sqrt, internal::psqrt, size);\n\n    // Test misc. corner cases.\n    const RealScalar zero = RealScalar(0);\n    const RealScalar one = RealScalar(1);\n    const RealScalar inf = std::numeric_limits<RealScalar>::infinity();\n    const RealScalar nan = std::numeric_limits<RealScalar>::quiet_NaN();\n    data1[0] = Scalar(zero, zero);\n    data1[1] = Scalar(-zero, zero);\n    data1[2] = Scalar(one, zero);\n    data1[3] = Scalar(zero, one);\n    CHECK_CWISE1_N(numext::sqrt, internal::psqrt, 4);\n    data1[0] = Scalar(-one, zero);\n    data1[1] = Scalar(zero, -one);\n    data1[2] = Scalar(one, one);\n    data1[3] = Scalar(-one, -one);\n    CHECK_CWISE1_N(numext::sqrt, internal::psqrt, 4);\n    data1[0] = Scalar(inf, zero);\n    data1[1] = Scalar(zero, inf);\n    data1[2] = Scalar(-inf, zero);\n    data1[3] = Scalar(zero, -inf);\n    CHECK_CWISE1_N(numext::sqrt, internal::psqrt, 4);\n    data1[0] = Scalar(inf, inf);\n    data1[1] = Scalar(-inf, inf);\n    data1[2] = Scalar(inf, -inf);\n    data1[3] = Scalar(-inf, -inf);\n    CHECK_CWISE1_N(numext::sqrt, internal::psqrt, 4);\n    data1[0] = Scalar(nan, zero);\n    data1[1] = Scalar(zero, nan);\n    data1[2] = Scalar(nan, one);\n    data1[3] = Scalar(one, nan);\n    CHECK_CWISE1_N(numext::sqrt, internal::psqrt, 4);\n    data1[0] = Scalar(nan, nan);\n    data1[1] = Scalar(inf, nan);\n    data1[2] = Scalar(nan, inf);\n    data1[3] = Scalar(-inf, nan);\n    CHECK_CWISE1_N(numext::sqrt, internal::psqrt, 4);\n  }\n}\n\ntemplate <typename Scalar, typename Packet>\nvoid packetmath_scatter_gather() {\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  const int PacketSize = internal::unpacket_traits<Packet>::size;\n  EIGEN_ALIGN_MAX Scalar data1[PacketSize];\n  RealScalar refvalue = RealScalar(0);\n  for (int i = 0; i < PacketSize; ++i) {\n    data1[i] = internal::random<Scalar>() / RealScalar(PacketSize);\n  }\n\n  int stride = internal::random<int>(1, 20);\n\n  // Buffer of zeros.\n  EIGEN_ALIGN_MAX Scalar buffer[PacketSize * 20] = {};\n\n  Packet packet = internal::pload<Packet>(data1);\n  internal::pscatter<Scalar, Packet>(buffer, packet, stride);\n\n  for (int i = 0; i < PacketSize * 20; ++i) {\n    if ((i % stride) == 0 && i < stride * PacketSize) {\n      VERIFY(test::isApproxAbs(buffer[i], data1[i / stride], refvalue) && \"pscatter\");\n    } else {\n      VERIFY(test::isApproxAbs(buffer[i], Scalar(0), refvalue) && \"pscatter\");\n    }\n  }\n\n  for (int i = 0; i < PacketSize * 7; ++i) {\n    buffer[i] = internal::random<Scalar>() / RealScalar(PacketSize);\n  }\n  packet = internal::pgather<Scalar, Packet>(buffer, 7);\n  internal::pstore(data1, packet);\n  for (int i = 0; i < PacketSize; ++i) {\n    VERIFY(test::isApproxAbs(data1[i], buffer[i * 7], refvalue) && \"pgather\");\n  }\n}\n\nnamespace Eigen {\nnamespace test {\n\ntemplate <typename Scalar, typename PacketType>\nstruct runall<Scalar, PacketType, false, false> {  // i.e. float or double\n  static void run() {\n    packetmath<Scalar, PacketType>();\n    packetmath_scatter_gather<Scalar, PacketType>();\n    packetmath_notcomplex<Scalar, PacketType>();\n    packetmath_real<Scalar, PacketType>();\n  }\n};\n\ntemplate <typename Scalar, typename PacketType>\nstruct runall<Scalar, PacketType, false, true> {  // i.e. int\n  static void run() {\n    packetmath<Scalar, PacketType>();\n    packetmath_scatter_gather<Scalar, PacketType>();\n    packetmath_notcomplex<Scalar, PacketType>();\n  }\n};\n\ntemplate <typename Scalar, typename PacketType>\nstruct runall<Scalar, PacketType, true, false> {  // i.e. complex\n  static void run() {\n    packetmath<Scalar, PacketType>();\n    packetmath_scatter_gather<Scalar, PacketType>();\n    packetmath_complex<Scalar, PacketType>();\n  }\n};\n\n}  // namespace test\n}  // namespace Eigen\n\nEIGEN_DECLARE_TEST(packetmath) {\n  g_first_pass = true;\n  for (int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(test::runner<float>::run());\n    CALL_SUBTEST_2(test::runner<double>::run());\n    CALL_SUBTEST_3(test::runner<int8_t>::run());\n    CALL_SUBTEST_4(test::runner<uint8_t>::run());\n    CALL_SUBTEST_5(test::runner<int16_t>::run());\n    CALL_SUBTEST_6(test::runner<uint16_t>::run());\n    CALL_SUBTEST_7(test::runner<int32_t>::run());\n    CALL_SUBTEST_8(test::runner<uint32_t>::run());\n    CALL_SUBTEST_9(test::runner<int64_t>::run());\n    CALL_SUBTEST_10(test::runner<uint64_t>::run());\n    CALL_SUBTEST_11(test::runner<std::complex<float> >::run());\n    CALL_SUBTEST_12(test::runner<std::complex<double> >::run());\n    CALL_SUBTEST_13(test::runner<half>::run());\n    CALL_SUBTEST_14((packetmath<bool, internal::packet_traits<bool>::type>()));\n    CALL_SUBTEST_15(test::runner<bfloat16>::run());\n    g_first_pass = false;\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/packetmath_test_shared.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <typeinfo>\n\n#if defined __GNUC__ && __GNUC__>=6\n  #pragma GCC diagnostic ignored \"-Wignored-attributes\"\n#endif\n// using namespace Eigen;\n\nbool g_first_pass = true;\n\nnamespace Eigen {\nnamespace internal {\n\ntemplate<typename T> T negate(const T& x) { return -x; }\n\ntemplate<typename T>\nMap<const Array<unsigned char,sizeof(T),1> >\nbits(const T& x) {\n  return Map<const Array<unsigned char,sizeof(T),1> >(reinterpret_cast<const unsigned char *>(&x));\n}\n\n// The following implement bitwise operations on floating point types\ntemplate<typename T,typename Bits,typename Func>\nT apply_bit_op(Bits a, Bits b, Func f) {\n  Array<unsigned char,sizeof(T),1> data;\n  T res;\n  for(Index i = 0; i < data.size(); ++i)\n    data[i] = f(a[i], b[i]);\n  // Note: The reinterpret_cast works around GCC's class-memaccess warnings:\n  std::memcpy(reinterpret_cast<unsigned char*>(&res), data.data(), sizeof(T));\n  return res;\n}\n\n#define EIGEN_TEST_MAKE_BITWISE2(OP,FUNC,T)             \\\n  template<> T EIGEN_CAT(p,OP)(const T& a,const T& b) { \\\n    return apply_bit_op<T>(bits(a),bits(b),FUNC);     \\\n  }\n\n#define EIGEN_TEST_MAKE_BITWISE(OP,FUNC)                  \\\n  EIGEN_TEST_MAKE_BITWISE2(OP,FUNC,float)                 \\\n  EIGEN_TEST_MAKE_BITWISE2(OP,FUNC,double)                \\\n  EIGEN_TEST_MAKE_BITWISE2(OP,FUNC,half)                  \\\n  EIGEN_TEST_MAKE_BITWISE2(OP,FUNC,bfloat16)              \\\n  EIGEN_TEST_MAKE_BITWISE2(OP,FUNC,std::complex<float>)   \\\n  EIGEN_TEST_MAKE_BITWISE2(OP,FUNC,std::complex<double>)\n\nEIGEN_TEST_MAKE_BITWISE(xor,std::bit_xor<unsigned char>())\nEIGEN_TEST_MAKE_BITWISE(and,std::bit_and<unsigned char>())\nEIGEN_TEST_MAKE_BITWISE(or, std::bit_or<unsigned char>())\nstruct bit_andnot{\n  template<typename T> T\n  operator()(T a, T b) const { return a & (~b); }\n};\nEIGEN_TEST_MAKE_BITWISE(andnot, bit_andnot())\ntemplate<typename T>\nbool biteq(T a, T b) {\n  return (bits(a) == bits(b)).all();\n}\n\n}\n\nnamespace test {\n\n// NOTE: we disable inlining for this function to workaround a GCC issue when using -O3 and the i387 FPU.\ntemplate<typename Scalar> EIGEN_DONT_INLINE\nbool isApproxAbs(const Scalar& a, const Scalar& b, const typename NumTraits<Scalar>::Real& refvalue)\n{\n  return internal::isMuchSmallerThan(a-b, refvalue);\n}\n\ntemplate<typename Scalar>\ninline void print_mismatch(const Scalar* ref, const Scalar* vec, int size) {\n  std::cout << \"ref: [\" << Map<const Matrix<Scalar,1,Dynamic> >(ref,size) << \"]\" << \" != vec: [\" << Map<const Matrix<Scalar,1,Dynamic> >(vec,size) << \"]\\n\";\n}\n\ntemplate<typename Scalar> bool areApproxAbs(const Scalar* a, const Scalar* b, int size, const typename NumTraits<Scalar>::Real& refvalue)\n{\n  for (int i=0; i<size; ++i)\n  {\n    if (!isApproxAbs(a[i],b[i],refvalue))\n    {\n      print_mismatch(a, b, size);\n      return false;\n    }\n  }\n  return true;\n}\n\ntemplate<typename Scalar> bool areApprox(const Scalar* a, const Scalar* b, int size)\n{\n  for (int i=0; i<size; ++i)\n  {\n    if ( a[i]!=b[i] && !internal::isApprox(a[i],b[i]) \n         && !((numext::isnan)(a[i]) && (numext::isnan)(b[i])) )\n    {\n      print_mismatch(a, b, size);\n      return false;\n    }\n  }\n  return true;\n}\n\ntemplate<typename Scalar> bool areEqual(const Scalar* a, const Scalar* b, int size)\n{\n  for (int i=0; i<size; ++i)\n  {\n    if ( (a[i] != b[i]) && !((numext::isnan)(a[i]) && (numext::isnan)(b[i])) )\n    {\n      print_mismatch(a, b, size);\n      return false;\n    }\n  }\n  return true;\n}\n\n#define CHECK_CWISE1(REFOP, POP) { \\\n  for (int i=0; i<PacketSize; ++i) \\\n    ref[i] = REFOP(data1[i]); \\\n  internal::pstore(data2, POP(internal::pload<Packet>(data1))); \\\n  VERIFY(test::areApprox(ref, data2, PacketSize) && #POP); \\\n}\n\n// Checks component-wise for input of size N. All of data1, data2, and ref\n// should have size at least ceil(N/PacketSize)*PacketSize to avoid memory\n// access errors.\n#define CHECK_CWISE1_N(REFOP, POP, N) { \\\n  for (int i=0; i<N; ++i) \\\n    ref[i] = REFOP(data1[i]); \\\n  for (int j=0; j<N; j+=PacketSize) \\\n    internal::pstore(data2 + j, POP(internal::pload<Packet>(data1 + j))); \\\n  VERIFY(test::areApprox(ref, data2, N) && #POP); \\\n}\n\ntemplate<bool Cond,typename Packet>\nstruct packet_helper\n{\n  template<typename T>\n  inline Packet load(const T* from) const { return internal::pload<Packet>(from); }\n\n  template<typename T>\n  inline Packet loadu(const T* from) const { return internal::ploadu<Packet>(from); }\n\n  template<typename T>\n  inline Packet load(const T* from, unsigned long long umask) const { return internal::ploadu<Packet>(from, umask); }\n\n  template<typename T>\n  inline void store(T* to, const Packet& x) const { internal::pstore(to,x); }\n\n  template<typename T>\n  inline void store(T* to, const Packet& x, unsigned long long umask) const { internal::pstoreu(to, x, umask); }\n\n  template<typename T>\n  inline Packet& forward_reference(Packet& packet, T& /*scalar*/) const { return packet; }\n};\n\ntemplate<typename Packet>\nstruct packet_helper<false,Packet>\n{\n  template<typename T>\n  inline T load(const T* from) const { return *from; }\n\n  template<typename T>\n  inline T loadu(const T* from) const { return *from; }\n\n  template<typename T>\n  inline T load(const T* from, unsigned long long) const { return *from; }\n\n  template<typename T>\n  inline void store(T* to, const T& x) const { *to = x; }\n\n  template<typename T>\n  inline void store(T* to, const T& x, unsigned long long) const { *to = x; }\n\n  template<typename T>\n  inline T& forward_reference(Packet& /*packet*/, T& scalar) const { return scalar; }\n};\n\n#define CHECK_CWISE1_IF(COND, REFOP, POP) if(COND) { \\\n  test::packet_helper<COND,Packet> h; \\\n  for (int i=0; i<PacketSize; ++i) \\\n    ref[i] = Scalar(REFOP(data1[i])); \\\n  h.store(data2, POP(h.load(data1))); \\\n  VERIFY(test::areApprox(ref, data2, PacketSize) && #POP); \\\n}\n\n#define CHECK_CWISE1_EXACT_IF(COND, REFOP, POP) if(COND) { \\\n  test::packet_helper<COND,Packet> h; \\\n  for (int i=0; i<PacketSize; ++i) \\\n    ref[i] = Scalar(REFOP(data1[i])); \\\n  h.store(data2, POP(h.load(data1))); \\\n  VERIFY(test::areEqual(ref, data2, PacketSize) && #POP); \\\n}\n\n#define CHECK_CWISE2_IF(COND, REFOP, POP) if(COND) { \\\n  test::packet_helper<COND,Packet> h; \\\n  for (int i=0; i<PacketSize; ++i) \\\n    ref[i] = Scalar(REFOP(data1[i], data1[i+PacketSize]));     \\\n  h.store(data2, POP(h.load(data1),h.load(data1+PacketSize))); \\\n  VERIFY(test::areApprox(ref, data2, PacketSize) && #POP); \\\n}\n\n// One input, one output by reference.\n#define CHECK_CWISE1_BYREF1_IF(COND, REFOP, POP) if(COND) { \\\n  test::packet_helper<COND,Packet> h; \\\n  for (int i=0; i<PacketSize; ++i) \\\n    ref[i] = Scalar(REFOP(data1[i], ref[i+PacketSize]));     \\\n  Packet pout; \\\n  Scalar sout; \\\n  h.store(data2, POP(h.load(data1), h.forward_reference(pout, sout))); \\\n  h.store(data2+PacketSize, h.forward_reference(pout, sout)); \\\n  VERIFY(test::areApprox(ref, data2, 2 * PacketSize) && #POP); \\\n}\n\n#define CHECK_CWISE3_IF(COND, REFOP, POP) if (COND) {                      \\\n  test::packet_helper<COND, Packet> h;                                     \\\n  for (int i = 0; i < PacketSize; ++i)                                     \\\n    ref[i] = Scalar(REFOP(data1[i], data1[i + PacketSize],                 \\\n                          data1[i + 2 * PacketSize]));                     \\\n  h.store(data2, POP(h.load(data1), h.load(data1 + PacketSize),            \\\n                     h.load(data1 + 2 * PacketSize)));                     \\\n  VERIFY(test::areApprox(ref, data2, PacketSize) && #POP);                 \\\n}\n\n// Specialize the runall struct in your test file by defining run().\ntemplate<\n  typename Scalar,\n  typename PacketType,\n  bool IsComplex = NumTraits<Scalar>::IsComplex,\n  bool IsInteger = NumTraits<Scalar>::IsInteger>\nstruct runall;\n\ntemplate<\n  typename Scalar,\n  typename PacketType = typename internal::packet_traits<Scalar>::type,\n  bool Vectorized = internal::packet_traits<Scalar>::Vectorizable,\n  bool HasHalf = !internal::is_same<typename internal::unpacket_traits<PacketType>::half,PacketType>::value >\nstruct runner;\n\ntemplate<typename Scalar,typename PacketType>\nstruct runner<Scalar,PacketType,true,true>\n{\n  static void run() {\n    runall<Scalar,PacketType>::run();\n    runner<Scalar,typename internal::unpacket_traits<PacketType>::half>::run();\n  }\n};\n\ntemplate<typename Scalar,typename PacketType>\nstruct runner<Scalar,PacketType,true,false>\n{\n  static void run() {\n    runall<Scalar,PacketType>::run();\n  }\n};\n\ntemplate<typename Scalar,typename PacketType>\nstruct runner<Scalar,PacketType,false,false>\n{\n  static void run() {\n    runall<Scalar,PacketType>::run();\n  }\n};\n\n}\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/pardiso_support.cpp",
    "content": "/* \n   Intel Copyright (C) ....\n*/\n\n#include \"sparse_solver.h\"\n#include <Eigen/PardisoSupport>\n\ntemplate<typename T> void test_pardiso_T()\n{\n  PardisoLLT < SparseMatrix<T, RowMajor>, Lower> pardiso_llt_lower;\n  PardisoLLT < SparseMatrix<T, RowMajor>, Upper> pardiso_llt_upper;\n  PardisoLDLT < SparseMatrix<T, RowMajor>, Lower> pardiso_ldlt_lower;\n  PardisoLDLT < SparseMatrix<T, RowMajor>, Upper> pardiso_ldlt_upper;\n  PardisoLU  < SparseMatrix<T, RowMajor> > pardiso_lu;\n\n  check_sparse_spd_solving(pardiso_llt_lower);\n  check_sparse_spd_solving(pardiso_llt_upper);\n  check_sparse_spd_solving(pardiso_ldlt_lower);\n  check_sparse_spd_solving(pardiso_ldlt_upper);\n  check_sparse_square_solving(pardiso_lu);\n}\n\nEIGEN_DECLARE_TEST(pardiso_support)\n{\n  CALL_SUBTEST_1(test_pardiso_T<float>());\n  CALL_SUBTEST_2(test_pardiso_T<double>());\n  CALL_SUBTEST_3(test_pardiso_T< std::complex<float> >());\n  CALL_SUBTEST_4(test_pardiso_T< std::complex<double> >());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/pastix_support.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS\n#include \"sparse_solver.h\"\n#include <Eigen/PaStiXSupport>\n#include <unsupported/Eigen/SparseExtra>\n\n\ntemplate<typename T> void test_pastix_T()\n{\n  PastixLLT< SparseMatrix<T, ColMajor>, Eigen::Lower > pastix_llt_lower;\n  PastixLDLT< SparseMatrix<T, ColMajor>, Eigen::Lower > pastix_ldlt_lower;\n  PastixLLT< SparseMatrix<T, ColMajor>, Eigen::Upper > pastix_llt_upper;\n  PastixLDLT< SparseMatrix<T, ColMajor>, Eigen::Upper > pastix_ldlt_upper;\n  PastixLU< SparseMatrix<T, ColMajor> > pastix_lu;\n\n  check_sparse_spd_solving(pastix_llt_lower);\n  check_sparse_spd_solving(pastix_ldlt_lower);\n  check_sparse_spd_solving(pastix_llt_upper);\n  check_sparse_spd_solving(pastix_ldlt_upper);\n  check_sparse_square_solving(pastix_lu);\n\n  // Some compilation check:\n  pastix_llt_lower.iparm();\n  pastix_llt_lower.dparm();\n  pastix_ldlt_lower.iparm();\n  pastix_ldlt_lower.dparm();\n  pastix_lu.iparm();\n  pastix_lu.dparm();\n}\n\n// There is no support for selfadjoint matrices with PaStiX. \n// Complex symmetric matrices should pass though\ntemplate<typename T> void test_pastix_T_LU()\n{\n  PastixLU< SparseMatrix<T, ColMajor> > pastix_lu;\n  check_sparse_square_solving(pastix_lu);\n}\n\nEIGEN_DECLARE_TEST(pastix_support)\n{\n  CALL_SUBTEST_1(test_pastix_T<float>());\n  CALL_SUBTEST_2(test_pastix_T<double>());\n  CALL_SUBTEST_3( (test_pastix_T_LU<std::complex<float> >()) );\n  CALL_SUBTEST_4(test_pastix_T_LU<std::complex<double> >());\n} \n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/permutationmatrices.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define TEST_ENABLE_TEMPORARY_TRACKING\n  \n#include \"main.h\"\n\nusing namespace std;\ntemplate<typename MatrixType> void permutationmatrices(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  enum { Rows = MatrixType::RowsAtCompileTime, Cols = MatrixType::ColsAtCompileTime,\n         Options = MatrixType::Options };\n  typedef PermutationMatrix<Rows> LeftPermutationType;\n  typedef Transpositions<Rows> LeftTranspositionsType;\n  typedef Matrix<int, Rows, 1> LeftPermutationVectorType;\n  typedef Map<LeftPermutationType> MapLeftPerm;\n  typedef PermutationMatrix<Cols> RightPermutationType;\n  typedef Transpositions<Cols> RightTranspositionsType;\n  typedef Matrix<int, Cols, 1> RightPermutationVectorType;\n  typedef Map<RightPermutationType> MapRightPerm;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m_original = MatrixType::Random(rows,cols);\n  LeftPermutationVectorType lv;\n  randomPermutationVector(lv, rows);\n  LeftPermutationType lp(lv);\n  RightPermutationVectorType rv;\n  randomPermutationVector(rv, cols);\n  RightPermutationType rp(rv);\n  LeftTranspositionsType lt(lv);\n  RightTranspositionsType rt(rv);\n  MatrixType m_permuted = MatrixType::Random(rows,cols);\n  \n  VERIFY_EVALUATION_COUNT(m_permuted = lp * m_original * rp, 1); // 1 temp for sub expression \"lp * m_original\"\n\n  for (int i=0; i<rows; i++)\n    for (int j=0; j<cols; j++)\n        VERIFY_IS_APPROX(m_permuted(lv(i),j), m_original(i,rv(j)));\n\n  Matrix<Scalar,Rows,Rows> lm(lp);\n  Matrix<Scalar,Cols,Cols> rm(rp);\n\n  VERIFY_IS_APPROX(m_permuted, lm*m_original*rm);\n  \n  m_permuted = m_original;\n  VERIFY_EVALUATION_COUNT(m_permuted = lp * m_permuted * rp, 1);\n  VERIFY_IS_APPROX(m_permuted, lm*m_original*rm);\n\n  LeftPermutationType lpi;\n  lpi = lp.inverse();\n  VERIFY_IS_APPROX(lpi*m_permuted,lp.inverse()*m_permuted);\n\n  VERIFY_IS_APPROX(lp.inverse()*m_permuted*rp.inverse(), m_original);\n  VERIFY_IS_APPROX(lv.asPermutation().inverse()*m_permuted*rv.asPermutation().inverse(), m_original);\n  VERIFY_IS_APPROX(MapLeftPerm(lv.data(),lv.size()).inverse()*m_permuted*MapRightPerm(rv.data(),rv.size()).inverse(), m_original);\n  \n  VERIFY((lp*lp.inverse()).toDenseMatrix().isIdentity());\n  VERIFY((lv.asPermutation()*lv.asPermutation().inverse()).toDenseMatrix().isIdentity());\n  VERIFY((MapLeftPerm(lv.data(),lv.size())*MapLeftPerm(lv.data(),lv.size()).inverse()).toDenseMatrix().isIdentity());\n\n  LeftPermutationVectorType lv2;\n  randomPermutationVector(lv2, rows);\n  LeftPermutationType lp2(lv2);\n  Matrix<Scalar,Rows,Rows> lm2(lp2);\n  VERIFY_IS_APPROX((lp*lp2).toDenseMatrix().template cast<Scalar>(), lm*lm2);\n  VERIFY_IS_APPROX((lv.asPermutation()*lv2.asPermutation()).toDenseMatrix().template cast<Scalar>(), lm*lm2);\n  VERIFY_IS_APPROX((MapLeftPerm(lv.data(),lv.size())*MapLeftPerm(lv2.data(),lv2.size())).toDenseMatrix().template cast<Scalar>(), lm*lm2);\n\n  LeftPermutationType identityp;\n  identityp.setIdentity(rows);\n  VERIFY_IS_APPROX(m_original, identityp*m_original);\n  \n  // check inplace permutations\n  m_permuted = m_original;\n  VERIFY_EVALUATION_COUNT(m_permuted.noalias()= lp.inverse() * m_permuted, 1); // 1 temp to allocate the mask\n  VERIFY_IS_APPROX(m_permuted, lp.inverse()*m_original);\n  \n  m_permuted = m_original;\n  VERIFY_EVALUATION_COUNT(m_permuted.noalias() = m_permuted * rp.inverse(), 1); // 1 temp to allocate the mask\n  VERIFY_IS_APPROX(m_permuted, m_original*rp.inverse());\n  \n  m_permuted = m_original;\n  VERIFY_EVALUATION_COUNT(m_permuted.noalias() = lp * m_permuted, 1); // 1 temp to allocate the mask\n  VERIFY_IS_APPROX(m_permuted, lp*m_original);\n  \n  m_permuted = m_original;\n  VERIFY_EVALUATION_COUNT(m_permuted.noalias() = m_permuted * rp, 1); // 1 temp to allocate the mask\n  VERIFY_IS_APPROX(m_permuted, m_original*rp);\n\n  if(rows>1 && cols>1)\n  {\n    lp2 = lp;\n    Index i = internal::random<Index>(0, rows-1);\n    Index j;\n    do j = internal::random<Index>(0, rows-1); while(j==i);\n    lp2.applyTranspositionOnTheLeft(i, j);\n    lm = lp;\n    lm.row(i).swap(lm.row(j));\n    VERIFY_IS_APPROX(lm, lp2.toDenseMatrix().template cast<Scalar>());\n\n    RightPermutationType rp2 = rp;\n    i = internal::random<Index>(0, cols-1);\n    do j = internal::random<Index>(0, cols-1); while(j==i);\n    rp2.applyTranspositionOnTheRight(i, j);\n    rm = rp;\n    rm.col(i).swap(rm.col(j));\n    VERIFY_IS_APPROX(rm, rp2.toDenseMatrix().template cast<Scalar>());\n  }\n\n  {\n    // simple compilation check\n    Matrix<Scalar, Cols, Cols> A = rp;\n    Matrix<Scalar, Cols, Cols> B = rp.transpose();\n    VERIFY_IS_APPROX(A, B.transpose());\n  }\n\n  m_permuted = m_original;\n  lp = lt;\n  rp = rt;\n  VERIFY_EVALUATION_COUNT(m_permuted = lt * m_permuted * rt, 1);\n  VERIFY_IS_APPROX(m_permuted, lp*m_original*rp.transpose());\n  \n  VERIFY_IS_APPROX(lt.inverse()*m_permuted*rt.inverse(), m_original);\n\n  // Check inplace transpositions\n  m_permuted = m_original;\n  VERIFY_IS_APPROX(m_permuted = lt * m_permuted, lp * m_original);\n  m_permuted = m_original;\n  VERIFY_IS_APPROX(m_permuted = lt.inverse() * m_permuted, lp.inverse() * m_original);\n  m_permuted = m_original;\n  VERIFY_IS_APPROX(m_permuted = m_permuted * rt, m_original * rt);\n  m_permuted = m_original;\n  VERIFY_IS_APPROX(m_permuted = m_permuted * rt.inverse(), m_original * rt.inverse());\n}\n\ntemplate<typename T>\nvoid bug890()\n{\n  typedef Matrix<T, Dynamic, Dynamic> MatrixType;\n  typedef Matrix<T, Dynamic, 1> VectorType;\n  typedef Stride<Dynamic,Dynamic> S;\n  typedef Map<MatrixType, Aligned, S> MapType;\n  typedef PermutationMatrix<Dynamic> Perm;\n  \n  VectorType v1(2), v2(2), op(4), rhs(2);\n  v1 << 666,667;\n  op << 1,0,0,1;\n  rhs << 42,42;\n  \n  Perm P(2);\n  P.indices() << 1, 0;\n\n  MapType(v1.data(),2,1,S(1,1)) = P * MapType(rhs.data(),2,1,S(1,1));\n  VERIFY_IS_APPROX(v1, (P * rhs).eval());\n\n  MapType(v1.data(),2,1,S(1,1)) = P.inverse() * MapType(rhs.data(),2,1,S(1,1));\n  VERIFY_IS_APPROX(v1, (P.inverse() * rhs).eval());\n}\n\nEIGEN_DECLARE_TEST(permutationmatrices)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( permutationmatrices(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( permutationmatrices(Matrix3f()) );\n    CALL_SUBTEST_3( permutationmatrices(Matrix<double,3,3,RowMajor>()) );\n    CALL_SUBTEST_4( permutationmatrices(Matrix4d()) );\n    CALL_SUBTEST_5( permutationmatrices(Matrix<double,40,60>()) );\n    CALL_SUBTEST_6( permutationmatrices(Matrix<double,Dynamic,Dynamic,RowMajor>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_7( permutationmatrices(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  CALL_SUBTEST_5( bug890<double>() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/prec_inverse_4x4.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/LU>\n#include <algorithm>\n\ntemplate<typename MatrixType> void inverse_permutation_4x4()\n{\n  typedef typename MatrixType::Scalar Scalar;\n  Vector4i indices(0,1,2,3);\n  for(int i = 0; i < 24; ++i)\n  {\n    MatrixType m = PermutationMatrix<4>(indices);\n    MatrixType inv = m.inverse();\n    double error = double( (m*inv-MatrixType::Identity()).norm() / NumTraits<Scalar>::epsilon() );\n    EIGEN_DEBUG_VAR(error)\n    VERIFY(error == 0.0);\n    std::next_permutation(indices.data(),indices.data()+4);\n  }\n}\n\ntemplate<typename MatrixType> void inverse_general_4x4(int repeat)\n{\n  using std::abs;\n  typedef typename MatrixType::Scalar Scalar;\n  double error_sum = 0., error_max = 0.;\n  for(int i = 0; i < repeat; ++i)\n  {\n    MatrixType m;\n    bool is_invertible;\n    do {\n      m = MatrixType::Random();\n      is_invertible = Eigen::FullPivLU<MatrixType>(m).isInvertible();\n    } while(!is_invertible);\n    MatrixType inv = m.inverse();\n    double error = double( (m*inv-MatrixType::Identity()).norm());\n    error_sum += error;\n    error_max = (std::max)(error_max, error);\n  }\n  std::cerr << \"inverse_general_4x4, Scalar = \" << type_name<Scalar>() << std::endl;\n  double error_avg = error_sum / repeat;\n  EIGEN_DEBUG_VAR(error_avg);\n  EIGEN_DEBUG_VAR(error_max);\n   // FIXME that 1.25 used to be a 1.0 until the NumTraits changes on 28 April 2010, what's going wrong??\n   // FIXME that 1.25 used to be 1.2 until we tested gcc 4.1 on 30 June 2010 and got 1.21.\n  VERIFY(error_avg < (NumTraits<Scalar>::IsComplex ? 8.0 : 1.25));\n  VERIFY(error_max < (NumTraits<Scalar>::IsComplex ? 64.0 : 20.0));\n\n  {\n    int s = 5;//internal::random<int>(4,10);\n    int i = 0;//internal::random<int>(0,s-4);\n    int j = 0;//internal::random<int>(0,s-4);\n    Matrix<Scalar,5,5> mat(s,s);\n    mat.setRandom();\n    MatrixType submat = mat.template block<4,4>(i,j);\n    MatrixType mat_inv = mat.template block<4,4>(i,j).inverse();\n    VERIFY_IS_APPROX(mat_inv, submat.inverse());\n    mat.template block<4,4>(i,j) = submat.inverse();\n    VERIFY_IS_APPROX(mat_inv, (mat.template block<4,4>(i,j)));\n  }\n}\n\nEIGEN_DECLARE_TEST(prec_inverse_4x4)\n{\n  CALL_SUBTEST_1((inverse_permutation_4x4<Matrix4f>()));\n  CALL_SUBTEST_1(( inverse_general_4x4<Matrix4f>(200000 * g_repeat) ));\n  CALL_SUBTEST_1(( inverse_general_4x4<Matrix<float,4,4,RowMajor> >(200000 * g_repeat) ));\n\n  CALL_SUBTEST_2((inverse_permutation_4x4<Matrix<double,4,4,RowMajor> >()));\n  CALL_SUBTEST_2(( inverse_general_4x4<Matrix<double,4,4,ColMajor> >(200000 * g_repeat) ));\n  CALL_SUBTEST_2(( inverse_general_4x4<Matrix<double,4,4,RowMajor> >(200000 * g_repeat) ));\n\n  CALL_SUBTEST_3((inverse_permutation_4x4<Matrix4cf>()));\n  CALL_SUBTEST_3((inverse_general_4x4<Matrix4cf>(50000 * g_repeat)));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/product.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/QR>\n\ntemplate<typename Derived1, typename Derived2>\nbool areNotApprox(const MatrixBase<Derived1>& m1, const MatrixBase<Derived2>& m2, typename Derived1::RealScalar epsilon = NumTraits<typename Derived1::RealScalar>::dummy_precision())\n{\n  return !((m1-m2).cwiseAbs2().maxCoeff() < epsilon * epsilon\n                          * (std::max)(m1.cwiseAbs2().maxCoeff(), m2.cwiseAbs2().maxCoeff()));\n}\n\ntemplate<typename MatrixType> void product(const MatrixType& m)\n{\n  /* this test covers the following files:\n     Identity.h Product.h\n  */\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> RowVectorType;\n  typedef Matrix<Scalar, MatrixType::ColsAtCompileTime, 1> ColVectorType;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> RowSquareMatrixType;\n  typedef Matrix<Scalar, MatrixType::ColsAtCompileTime, MatrixType::ColsAtCompileTime> ColSquareMatrixType;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::ColsAtCompileTime,\n                         MatrixType::Flags&RowMajorBit?ColMajor:RowMajor> OtherMajorMatrixType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  // this test relies a lot on Random.h, and there's not much more that we can do\n  // to test it, hence I consider that we will have tested Random.h\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols);\n  RowSquareMatrixType\n             identity = RowSquareMatrixType::Identity(rows, rows),\n             square = RowSquareMatrixType::Random(rows, rows),\n             res = RowSquareMatrixType::Random(rows, rows);\n  ColSquareMatrixType\n             square2 = ColSquareMatrixType::Random(cols, cols),\n             res2 = ColSquareMatrixType::Random(cols, cols);\n  RowVectorType v1 = RowVectorType::Random(rows);\n  ColVectorType vc2 = ColVectorType::Random(cols), vcres(cols);\n  OtherMajorMatrixType tm1 = m1;\n\n  Scalar s1 = internal::random<Scalar>();\n\n  Index r  = internal::random<Index>(0, rows-1),\n        c  = internal::random<Index>(0, cols-1),\n        c2 = internal::random<Index>(0, cols-1);\n\n  // begin testing Product.h: only associativity for now\n  // (we use Transpose.h but this doesn't count as a test for it)\n  VERIFY_IS_APPROX((m1*m1.transpose())*m2,  m1*(m1.transpose()*m2));\n  m3 = m1;\n  m3 *= m1.transpose() * m2;\n  VERIFY_IS_APPROX(m3,                      m1 * (m1.transpose()*m2));\n  VERIFY_IS_APPROX(m3,                      m1 * (m1.transpose()*m2));\n\n  // continue testing Product.h: distributivity\n  VERIFY_IS_APPROX(square*(m1 + m2),        square*m1+square*m2);\n  VERIFY_IS_APPROX(square*(m1 - m2),        square*m1-square*m2);\n\n  // continue testing Product.h: compatibility with ScalarMultiple.h\n  VERIFY_IS_APPROX(s1*(square*m1),          (s1*square)*m1);\n  VERIFY_IS_APPROX(s1*(square*m1),          square*(m1*s1));\n\n  // test Product.h together with Identity.h\n  VERIFY_IS_APPROX(v1,                      identity*v1);\n  VERIFY_IS_APPROX(v1.transpose(),          v1.transpose() * identity);\n  // again, test operator() to check const-qualification\n  VERIFY_IS_APPROX(MatrixType::Identity(rows, cols)(r,c), static_cast<Scalar>(r==c));\n\n  if (rows!=cols)\n     VERIFY_RAISES_ASSERT(m3 = m1*m1);\n\n  // test the previous tests were not screwed up because operator* returns 0\n  // (we use the more accurate default epsilon)\n  if (!NumTraits<Scalar>::IsInteger && (std::min)(rows,cols)>1)\n  {\n    VERIFY(areNotApprox(m1.transpose()*m2,m2.transpose()*m1));\n  }\n\n  // test optimized operator+= path\n  res = square;\n  res.noalias() += m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, square + m1 * m2.transpose());\n  if (!NumTraits<Scalar>::IsInteger && (std::min)(rows,cols)>1)\n  {\n    VERIFY(areNotApprox(res,square + m2 * m1.transpose()));\n  }\n  vcres = vc2;\n  vcres.noalias() += m1.transpose() * v1;\n  VERIFY_IS_APPROX(vcres, vc2 + m1.transpose() * v1);\n\n  // test optimized operator-= path\n  res = square;\n  res.noalias() -= m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, square - (m1 * m2.transpose()));\n  if (!NumTraits<Scalar>::IsInteger && (std::min)(rows,cols)>1)\n  {\n    VERIFY(areNotApprox(res,square - m2 * m1.transpose()));\n  }\n  vcres = vc2;\n  vcres.noalias() -= m1.transpose() * v1;\n  VERIFY_IS_APPROX(vcres, vc2 - m1.transpose() * v1);\n\n  // test scaled products\n  res = square;\n  res.noalias() = s1 * m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, ((s1*m1).eval() * m2.transpose()));\n  res = square;\n  res.noalias() += s1 * m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, square + ((s1*m1).eval() * m2.transpose()));\n  res = square;\n  res.noalias() -= s1 * m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, square - ((s1*m1).eval() * m2.transpose()));\n\n  // test d ?= a+b*c rules\n  res.noalias() = square + m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, square + m1 * m2.transpose());\n  res.noalias() += square + m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, 2*(square + m1 * m2.transpose()));\n  res.noalias() -= square + m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, square + m1 * m2.transpose());\n\n  // test d ?= a-b*c rules\n  res.noalias() = square - m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, square - m1 * m2.transpose());\n  res.noalias() += square - m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, 2*(square - m1 * m2.transpose()));\n  res.noalias() -= square - m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, square - m1 * m2.transpose());\n\n\n  tm1 = m1;\n  VERIFY_IS_APPROX(tm1.transpose() * v1, m1.transpose() * v1);\n  VERIFY_IS_APPROX(v1.transpose() * tm1, v1.transpose() * m1);\n\n  // test submatrix and matrix/vector product\n  for (int i=0; i<rows; ++i)\n    res.row(i) = m1.row(i) * m2.transpose();\n  VERIFY_IS_APPROX(res, m1 * m2.transpose());\n  // the other way round:\n  for (int i=0; i<rows; ++i)\n    res.col(i) = m1 * m2.transpose().col(i);\n  VERIFY_IS_APPROX(res, m1 * m2.transpose());\n\n  res2 = square2;\n  res2.noalias() += m1.transpose() * m2;\n  VERIFY_IS_APPROX(res2, square2 + m1.transpose() * m2);\n  if (!NumTraits<Scalar>::IsInteger && (std::min)(rows,cols)>1)\n  {\n    VERIFY(areNotApprox(res2,square2 + m2.transpose() * m1));\n  }\n\n  VERIFY_IS_APPROX(res.col(r).noalias() = square.adjoint() * square.col(r), (square.adjoint() * square.col(r)).eval());\n  VERIFY_IS_APPROX(res.col(r).noalias() = square * square.col(r), (square * square.col(r)).eval());\n\n  // vector at runtime (see bug 1166)\n  {\n    RowSquareMatrixType ref(square);\n    ColSquareMatrixType ref2(square2);\n    ref = res = square;\n    VERIFY_IS_APPROX(res.block(0,0,1,rows).noalias() = m1.col(0).transpose() * square.transpose(),            (ref.row(0) = m1.col(0).transpose() * square.transpose()));\n    VERIFY_IS_APPROX(res.block(0,0,1,rows).noalias() = m1.block(0,0,rows,1).transpose() * square.transpose(), (ref.row(0) = m1.col(0).transpose() * square.transpose()));\n    VERIFY_IS_APPROX(res.block(0,0,1,rows).noalias() = m1.col(0).transpose() * square,                        (ref.row(0) = m1.col(0).transpose() * square));\n    VERIFY_IS_APPROX(res.block(0,0,1,rows).noalias() = m1.block(0,0,rows,1).transpose() * square,             (ref.row(0) = m1.col(0).transpose() * square));\n    ref2 = res2 = square2;\n    VERIFY_IS_APPROX(res2.block(0,0,1,cols).noalias() = m1.row(0) * square2.transpose(),                      (ref2.row(0) = m1.row(0) * square2.transpose()));\n    VERIFY_IS_APPROX(res2.block(0,0,1,cols).noalias() = m1.block(0,0,1,cols) * square2.transpose(),           (ref2.row(0) = m1.row(0) * square2.transpose()));\n    VERIFY_IS_APPROX(res2.block(0,0,1,cols).noalias() = m1.row(0) * square2,                                  (ref2.row(0) = m1.row(0) * square2));\n    VERIFY_IS_APPROX(res2.block(0,0,1,cols).noalias() = m1.block(0,0,1,cols) * square2,                       (ref2.row(0) = m1.row(0) * square2));\n  }\n\n  // vector.block() (see bug 1283)\n  {\n    RowVectorType w1(rows);\n    VERIFY_IS_APPROX(square * v1.block(0,0,rows,1), square * v1);\n    VERIFY_IS_APPROX(w1.noalias() = square * v1.block(0,0,rows,1), square * v1);\n    VERIFY_IS_APPROX(w1.block(0,0,rows,1).noalias() = square * v1.block(0,0,rows,1), square * v1);\n\n    Matrix<Scalar,1,MatrixType::ColsAtCompileTime> w2(cols);\n    VERIFY_IS_APPROX(vc2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2);\n    VERIFY_IS_APPROX(w2.noalias() = vc2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2);\n    VERIFY_IS_APPROX(w2.block(0,0,1,cols).noalias() = vc2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2);\n\n    vc2 = square2.block(0,0,1,cols).transpose();\n    VERIFY_IS_APPROX(square2.block(0,0,1,cols) * square2, vc2.transpose() * square2);\n    VERIFY_IS_APPROX(w2.noalias() = square2.block(0,0,1,cols) * square2, vc2.transpose() * square2);\n    VERIFY_IS_APPROX(w2.block(0,0,1,cols).noalias() = square2.block(0,0,1,cols) * square2, vc2.transpose() * square2);\n\n    vc2 = square2.block(0,0,cols,1);\n    VERIFY_IS_APPROX(square2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2);\n    VERIFY_IS_APPROX(w2.noalias() = square2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2);\n    VERIFY_IS_APPROX(w2.block(0,0,1,cols).noalias() = square2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2);\n  }\n\n  // inner product\n  {\n    Scalar x = square2.row(c) * square2.col(c2);\n    VERIFY_IS_APPROX(x, square2.row(c).transpose().cwiseProduct(square2.col(c2)).sum());\n  }\n\n  // outer product\n  {\n    VERIFY_IS_APPROX(m1.col(c) * m1.row(r), m1.block(0,c,rows,1) * m1.block(r,0,1,cols));\n    VERIFY_IS_APPROX(m1.row(r).transpose() * m1.col(c).transpose(), m1.block(r,0,1,cols).transpose() * m1.block(0,c,rows,1).transpose());\n    VERIFY_IS_APPROX(m1.block(0,c,rows,1) * m1.row(r), m1.block(0,c,rows,1) * m1.block(r,0,1,cols));\n    VERIFY_IS_APPROX(m1.col(c) * m1.block(r,0,1,cols), m1.block(0,c,rows,1) * m1.block(r,0,1,cols));\n    VERIFY_IS_APPROX(m1.leftCols(1) * m1.row(r), m1.block(0,0,rows,1) * m1.block(r,0,1,cols));\n    VERIFY_IS_APPROX(m1.col(c) * m1.topRows(1), m1.block(0,c,rows,1) * m1.block(0,0,1,cols));\n  }\n\n  // Aliasing\n  {\n    ColVectorType x(cols); x.setRandom();\n    ColVectorType z(x);\n    ColVectorType y(cols); y.setZero();\n    ColSquareMatrixType A(cols,cols); A.setRandom();\n    // CwiseBinaryOp\n    VERIFY_IS_APPROX(x = y + A*x, A*z);\n    x = z;\n    VERIFY_IS_APPROX(x = y - A*x, A*(-z));\n    x = z;\n    // CwiseUnaryOp\n    VERIFY_IS_APPROX(x = Scalar(1.)*(A*x), A*z);\n  }\n\n  // regression for blas_trais\n  {\n    VERIFY_IS_APPROX(square * (square*square).transpose(), square * square.transpose() * square.transpose());\n    VERIFY_IS_APPROX(square * (-(square*square)), -square * square * square);\n    VERIFY_IS_APPROX(square * (s1*(square*square)), s1 * square * square * square);\n    VERIFY_IS_APPROX(square * (square*square).conjugate(), square * square.conjugate() * square.conjugate());\n  }\n\n  // destination with a non-default inner-stride\n  // see bug 1741\n  if(!MatrixType::IsRowMajor)\n  {\n    typedef Matrix<Scalar,Dynamic,Dynamic> MatrixX;\n    MatrixX buffer(2*rows,2*rows);\n    Map<RowSquareMatrixType,0,Stride<Dynamic,2> > map1(buffer.data(),rows,rows,Stride<Dynamic,2>(2*rows,2));\n    buffer.setZero();\n    VERIFY_IS_APPROX(map1 = m1 * m2.transpose(), (m1 * m2.transpose()).eval());\n    buffer.setZero();\n    VERIFY_IS_APPROX(map1.noalias() = m1 * m2.transpose(), (m1 * m2.transpose()).eval());\n    buffer.setZero();\n    VERIFY_IS_APPROX(map1.noalias() += m1 * m2.transpose(), (m1 * m2.transpose()).eval());\n  }\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/product_extra.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void product_extra(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, 1, Dynamic> RowVectorType;\n  typedef Matrix<Scalar, Dynamic, 1> ColVectorType;\n  typedef Matrix<Scalar, Dynamic, Dynamic,\n                         MatrixType::Flags&RowMajorBit> OtherMajorMatrixType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols),\n             mzero = MatrixType::Zero(rows, cols),\n             identity = MatrixType::Identity(rows, rows),\n             square = MatrixType::Random(rows, rows),\n             res = MatrixType::Random(rows, rows),\n             square2 = MatrixType::Random(cols, cols),\n             res2 = MatrixType::Random(cols, cols);\n  RowVectorType v1 = RowVectorType::Random(rows), vrres(rows);\n  ColVectorType vc2 = ColVectorType::Random(cols), vcres(cols);\n  OtherMajorMatrixType tm1 = m1;\n\n  Scalar s1 = internal::random<Scalar>(),\n         s2 = internal::random<Scalar>(),\n         s3 = internal::random<Scalar>();\n\n  VERIFY_IS_APPROX(m3.noalias() = m1 * m2.adjoint(),                 m1 * m2.adjoint().eval());\n  VERIFY_IS_APPROX(m3.noalias() = m1.adjoint() * square.adjoint(),   m1.adjoint().eval() * square.adjoint().eval());\n  VERIFY_IS_APPROX(m3.noalias() = m1.adjoint() * m2,                 m1.adjoint().eval() * m2);\n  VERIFY_IS_APPROX(m3.noalias() = (s1 * m1.adjoint()) * m2,          (s1 * m1.adjoint()).eval() * m2);\n  VERIFY_IS_APPROX(m3.noalias() = ((s1 * m1).adjoint()) * m2,        (numext::conj(s1) * m1.adjoint()).eval() * m2);\n  VERIFY_IS_APPROX(m3.noalias() = (- m1.adjoint() * s1) * (s3 * m2), (- m1.adjoint()  * s1).eval() * (s3 * m2).eval());\n  VERIFY_IS_APPROX(m3.noalias() = (s2 * m1.adjoint() * s1) * m2,     (s2 * m1.adjoint()  * s1).eval() * m2);\n  VERIFY_IS_APPROX(m3.noalias() = (-m1*s2) * s1*m2.adjoint(),        (-m1*s2).eval() * (s1*m2.adjoint()).eval());\n\n  // a very tricky case where a scale factor has to be automatically conjugated:\n  VERIFY_IS_APPROX( m1.adjoint() * (s1*m2).conjugate(), (m1.adjoint()).eval() * ((s1*m2).conjugate()).eval());\n\n\n  // test all possible conjugate combinations for the four matrix-vector product cases:\n\n  VERIFY_IS_APPROX((-m1.conjugate() * s2) * (s1 * vc2),\n                   (-m1.conjugate()*s2).eval() * (s1 * vc2).eval());\n  VERIFY_IS_APPROX((-m1 * s2) * (s1 * vc2.conjugate()),\n                   (-m1*s2).eval() * (s1 * vc2.conjugate()).eval());\n  VERIFY_IS_APPROX((-m1.conjugate() * s2) * (s1 * vc2.conjugate()),\n                   (-m1.conjugate()*s2).eval() * (s1 * vc2.conjugate()).eval());\n\n  VERIFY_IS_APPROX((s1 * vc2.transpose()) * (-m1.adjoint() * s2),\n                   (s1 * vc2.transpose()).eval() * (-m1.adjoint()*s2).eval());\n  VERIFY_IS_APPROX((s1 * vc2.adjoint()) * (-m1.transpose() * s2),\n                   (s1 * vc2.adjoint()).eval() * (-m1.transpose()*s2).eval());\n  VERIFY_IS_APPROX((s1 * vc2.adjoint()) * (-m1.adjoint() * s2),\n                   (s1 * vc2.adjoint()).eval() * (-m1.adjoint()*s2).eval());\n\n  VERIFY_IS_APPROX((-m1.adjoint() * s2) * (s1 * v1.transpose()),\n                   (-m1.adjoint()*s2).eval() * (s1 * v1.transpose()).eval());\n  VERIFY_IS_APPROX((-m1.transpose() * s2) * (s1 * v1.adjoint()),\n                   (-m1.transpose()*s2).eval() * (s1 * v1.adjoint()).eval());\n  VERIFY_IS_APPROX((-m1.adjoint() * s2) * (s1 * v1.adjoint()),\n                   (-m1.adjoint()*s2).eval() * (s1 * v1.adjoint()).eval());\n\n  VERIFY_IS_APPROX((s1 * v1) * (-m1.conjugate() * s2),\n                   (s1 * v1).eval() * (-m1.conjugate()*s2).eval());\n  VERIFY_IS_APPROX((s1 * v1.conjugate()) * (-m1 * s2),\n                   (s1 * v1.conjugate()).eval() * (-m1*s2).eval());\n  VERIFY_IS_APPROX((s1 * v1.conjugate()) * (-m1.conjugate() * s2),\n                   (s1 * v1.conjugate()).eval() * (-m1.conjugate()*s2).eval());\n\n  VERIFY_IS_APPROX((-m1.adjoint() * s2) * (s1 * v1.adjoint()),\n                   (-m1.adjoint()*s2).eval() * (s1 * v1.adjoint()).eval());\n\n  // test the vector-matrix product with non aligned starts\n  Index i = internal::random<Index>(0,m1.rows()-2);\n  Index j = internal::random<Index>(0,m1.cols()-2);\n  Index r = internal::random<Index>(1,m1.rows()-i);\n  Index c = internal::random<Index>(1,m1.cols()-j);\n  Index i2 = internal::random<Index>(0,m1.rows()-1);\n  Index j2 = internal::random<Index>(0,m1.cols()-1);\n\n  VERIFY_IS_APPROX(m1.col(j2).adjoint() * m1.block(0,j,m1.rows(),c), m1.col(j2).adjoint().eval() * m1.block(0,j,m1.rows(),c).eval());\n  VERIFY_IS_APPROX(m1.block(i,0,r,m1.cols()) * m1.row(i2).adjoint(), m1.block(i,0,r,m1.cols()).eval() * m1.row(i2).adjoint().eval());\n\n  // test negative strides\n  {\n    Map<MatrixType,Unaligned,Stride<Dynamic,Dynamic> > map1(&m1(rows-1,cols-1), rows, cols, Stride<Dynamic,Dynamic>(-m1.outerStride(),-1));\n    Map<MatrixType,Unaligned,Stride<Dynamic,Dynamic> > map2(&m2(rows-1,cols-1), rows, cols, Stride<Dynamic,Dynamic>(-m2.outerStride(),-1));\n    Map<RowVectorType,Unaligned,InnerStride<-1> > mapv1(&v1(v1.size()-1), v1.size(), InnerStride<-1>(-1));\n    Map<ColVectorType,Unaligned,InnerStride<-1> > mapvc2(&vc2(vc2.size()-1), vc2.size(), InnerStride<-1>(-1));\n    VERIFY_IS_APPROX(MatrixType(map1), m1.reverse());\n    VERIFY_IS_APPROX(MatrixType(map2), m2.reverse());\n    VERIFY_IS_APPROX(m3.noalias() = MatrixType(map1) * MatrixType(map2).adjoint(), m1.reverse() * m2.reverse().adjoint());\n    VERIFY_IS_APPROX(m3.noalias() = map1 * map2.adjoint(), m1.reverse() * m2.reverse().adjoint());\n    VERIFY_IS_APPROX(map1 * vc2, m1.reverse() * vc2);\n    VERIFY_IS_APPROX(m1 * mapvc2, m1 * mapvc2);\n    VERIFY_IS_APPROX(map1.adjoint() * v1.transpose(), m1.adjoint().reverse() * v1.transpose());\n    VERIFY_IS_APPROX(m1.adjoint() * mapv1.transpose(), m1.adjoint() * v1.reverse().transpose());\n  }\n  \n  // regression test\n  MatrixType tmp = m1 * m1.adjoint() * s1;\n  VERIFY_IS_APPROX(tmp, m1 * m1.adjoint() * s1);\n\n  // regression test for bug 1343, assignment to arrays\n  Array<Scalar,Dynamic,1> a1 = m1 * vc2;\n  VERIFY_IS_APPROX(a1.matrix(),m1*vc2);\n  Array<Scalar,Dynamic,1> a2 = s1 * (m1 * vc2);\n  VERIFY_IS_APPROX(a2.matrix(),s1*m1*vc2);\n  Array<Scalar,1,Dynamic> a3 = v1 * m1;\n  VERIFY_IS_APPROX(a3.matrix(),v1*m1);\n  Array<Scalar,Dynamic,Dynamic> a4 = m1 * m2.adjoint();\n  VERIFY_IS_APPROX(a4.matrix(),m1*m2.adjoint());\n}\n\n// Regression test for bug reported at http://forum.kde.org/viewtopic.php?f=74&t=96947\nvoid mat_mat_scalar_scalar_product()\n{\n  Eigen::Matrix2Xd dNdxy(2, 3);\n  dNdxy << -0.5, 0.5, 0,\n           -0.3, 0, 0.3;\n  double det = 6.0, wt = 0.5;\n  VERIFY_IS_APPROX(dNdxy.transpose()*dNdxy*det*wt, det*wt*dNdxy.transpose()*dNdxy);\n}\n\ntemplate <typename MatrixType> \nvoid zero_sized_objects(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  const int PacketSize  = internal::packet_traits<Scalar>::size;\n  const int PacketSize1 = PacketSize>1 ?  PacketSize-1 : 1;\n  Index rows = m.rows();\n  Index cols = m.cols();\n  \n  {\n    MatrixType res, a(rows,0), b(0,cols);\n    VERIFY_IS_APPROX( (res=a*b), MatrixType::Zero(rows,cols) );\n    VERIFY_IS_APPROX( (res=a*a.transpose()), MatrixType::Zero(rows,rows) );\n    VERIFY_IS_APPROX( (res=b.transpose()*b), MatrixType::Zero(cols,cols) );\n    VERIFY_IS_APPROX( (res=b.transpose()*a.transpose()), MatrixType::Zero(cols,rows) );\n  }\n  \n  {\n    MatrixType res, a(rows,cols), b(cols,0);\n    res = a*b;\n    VERIFY(res.rows()==rows && res.cols()==0);\n    b.resize(0,rows);\n    res = b*a;\n    VERIFY(res.rows()==0 && res.cols()==cols);\n  }\n  \n  {\n    Matrix<Scalar,PacketSize,0> a;\n    Matrix<Scalar,0,1> b;\n    Matrix<Scalar,PacketSize,1> res;\n    VERIFY_IS_APPROX( (res=a*b), MatrixType::Zero(PacketSize,1) );\n    VERIFY_IS_APPROX( (res=a.lazyProduct(b)), MatrixType::Zero(PacketSize,1) );\n  }\n  \n  {\n    Matrix<Scalar,PacketSize1,0> a;\n    Matrix<Scalar,0,1> b;\n    Matrix<Scalar,PacketSize1,1> res;\n    VERIFY_IS_APPROX( (res=a*b), MatrixType::Zero(PacketSize1,1) );\n    VERIFY_IS_APPROX( (res=a.lazyProduct(b)), MatrixType::Zero(PacketSize1,1) );\n  }\n  \n  {\n    Matrix<Scalar,PacketSize,Dynamic> a(PacketSize,0);\n    Matrix<Scalar,Dynamic,1> b(0,1);\n    Matrix<Scalar,PacketSize,1> res;\n    VERIFY_IS_APPROX( (res=a*b), MatrixType::Zero(PacketSize,1) );\n    VERIFY_IS_APPROX( (res=a.lazyProduct(b)), MatrixType::Zero(PacketSize,1) );\n  }\n  \n  {\n    Matrix<Scalar,PacketSize1,Dynamic> a(PacketSize1,0);\n    Matrix<Scalar,Dynamic,1> b(0,1);\n    Matrix<Scalar,PacketSize1,1> res;\n    VERIFY_IS_APPROX( (res=a*b), MatrixType::Zero(PacketSize1,1) );\n    VERIFY_IS_APPROX( (res=a.lazyProduct(b)), MatrixType::Zero(PacketSize1,1) );\n  }\n}\n\ntemplate<int>\nvoid bug_127()\n{\n  // Bug 127\n  //\n  // a product of the form lhs*rhs with\n  //\n  // lhs:\n  // rows = 1, cols = 4\n  // RowsAtCompileTime = 1, ColsAtCompileTime = -1\n  // MaxRowsAtCompileTime = 1, MaxColsAtCompileTime = 5\n  //\n  // rhs:\n  // rows = 4, cols = 0\n  // RowsAtCompileTime = -1, ColsAtCompileTime = -1\n  // MaxRowsAtCompileTime = 5, MaxColsAtCompileTime = 1\n  //\n  // was failing on a runtime assertion, because it had been mis-compiled as a dot product because Product.h was using the\n  // max-sizes to detect size 1 indicating vectors, and that didn't account for 0-sized object with max-size 1.\n\n  Matrix<float,1,Dynamic,RowMajor,1,5> a(1,4);\n  Matrix<float,Dynamic,Dynamic,ColMajor,5,1> b(4,0);\n  a*b;\n}\n\ntemplate<int> void bug_817()\n{\n  ArrayXXf B = ArrayXXf::Random(10,10), C;\n  VectorXf x = VectorXf::Random(10);\n  C = (x.transpose()*B.matrix());\n  B = (x.transpose()*B.matrix());\n  VERIFY_IS_APPROX(B,C);\n}\n\ntemplate<int>\nvoid unaligned_objects()\n{\n  // Regression test for the bug reported here:\n  // http://forum.kde.org/viewtopic.php?f=74&t=107541\n  // Recall the matrix*vector kernel avoid unaligned loads by loading two packets and then reassemble then.\n  // There was a mistake in the computation of the valid range for fully unaligned objects: in some rare cases,\n  // memory was read outside the allocated matrix memory. Though the values were not used, this might raise segfault.\n  for(int m=450;m<460;++m)\n  {\n    for(int n=8;n<12;++n)\n    {\n      MatrixXf M(m, n);\n      VectorXf v1(n), r1(500);\n      RowVectorXf v2(m), r2(16);\n\n      M.setRandom();\n      v1.setRandom();\n      v2.setRandom();\n      for(int o=0; o<4; ++o)\n      {\n        r1.segment(o,m).noalias() = M * v1;\n        VERIFY_IS_APPROX(r1.segment(o,m), M * MatrixXf(v1));\n        r2.segment(o,n).noalias() = v2 * M;\n        VERIFY_IS_APPROX(r2.segment(o,n), MatrixXf(v2) * M);\n      }\n    }\n  }\n}\n\ntemplate<typename T>\nEIGEN_DONT_INLINE\nIndex test_compute_block_size(Index m, Index n, Index k)\n{\n  Index mc(m), nc(n), kc(k);\n  internal::computeProductBlockingSizes<T,T>(kc, mc, nc);\n  return kc+mc+nc;\n}\n\ntemplate<typename T>\nIndex compute_block_size()\n{\n  Index ret = 0;\n  ret += test_compute_block_size<T>(0,1,1);\n  ret += test_compute_block_size<T>(1,0,1);\n  ret += test_compute_block_size<T>(1,1,0);\n  ret += test_compute_block_size<T>(0,0,1);\n  ret += test_compute_block_size<T>(0,1,0);\n  ret += test_compute_block_size<T>(1,0,0);\n  ret += test_compute_block_size<T>(0,0,0);\n  return ret;\n}\n\ntemplate<typename>\nvoid aliasing_with_resize()\n{\n  Index m = internal::random<Index>(10,50);\n  Index n = internal::random<Index>(10,50);\n  MatrixXd A, B, C(m,n), D(m,m);\n  VectorXd a, b, c(n);\n  C.setRandom();\n  D.setRandom();\n  c.setRandom();\n  double s = internal::random<double>(1,10);\n\n  A = C;\n  B = A * A.transpose();\n  A = A * A.transpose();\n  VERIFY_IS_APPROX(A,B);\n\n  A = C;\n  B = (A * A.transpose())/s;\n  A = (A * A.transpose())/s;\n  VERIFY_IS_APPROX(A,B);\n\n  A = C;\n  B = (A * A.transpose()) + D;\n  A = (A * A.transpose()) + D;\n  VERIFY_IS_APPROX(A,B);\n\n  A = C;\n  B = D + (A * A.transpose());\n  A = D + (A * A.transpose());\n  VERIFY_IS_APPROX(A,B);\n\n  A = C;\n  B = s * (A * A.transpose());\n  A = s * (A * A.transpose());\n  VERIFY_IS_APPROX(A,B);\n\n  A = C;\n  a = c;\n  b = (A * a)/s;\n  a = (A * a)/s;\n  VERIFY_IS_APPROX(a,b);\n}\n\ntemplate<int>\nvoid bug_1308()\n{\n  int n = 10;\n  MatrixXd r(n,n);\n  VectorXd v = VectorXd::Random(n);\n  r = v * RowVectorXd::Ones(n);\n  VERIFY_IS_APPROX(r, v.rowwise().replicate(n));\n  r = VectorXd::Ones(n) * v.transpose();\n  VERIFY_IS_APPROX(r, v.rowwise().replicate(n).transpose());\n\n  Matrix4d ones44 = Matrix4d::Ones();\n  Matrix4d m44 = Matrix4d::Ones() * Matrix4d::Ones();\n  VERIFY_IS_APPROX(m44,Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(m44.noalias()=ones44*Matrix4d::Ones(), Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(m44.noalias()=ones44.transpose()*Matrix4d::Ones(), Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(m44.noalias()=Matrix4d::Ones()*ones44, Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(m44.noalias()=Matrix4d::Ones()*ones44.transpose(), Matrix4d::Constant(4));\n\n  typedef Matrix<double,4,4,RowMajor> RMatrix4d;\n  RMatrix4d r44 = Matrix4d::Ones() * Matrix4d::Ones();\n  VERIFY_IS_APPROX(r44,Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(r44.noalias()=ones44*Matrix4d::Ones(), Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(r44.noalias()=ones44.transpose()*Matrix4d::Ones(), Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(r44.noalias()=Matrix4d::Ones()*ones44, Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(r44.noalias()=Matrix4d::Ones()*ones44.transpose(), Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(r44.noalias()=ones44*RMatrix4d::Ones(), Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(r44.noalias()=ones44.transpose()*RMatrix4d::Ones(), Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(r44.noalias()=RMatrix4d::Ones()*ones44, Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(r44.noalias()=RMatrix4d::Ones()*ones44.transpose(), Matrix4d::Constant(4));\n\n//   RowVector4d r4;\n  m44.setOnes();\n  r44.setZero();\n  VERIFY_IS_APPROX(r44.noalias() += m44.row(0).transpose() * RowVector4d::Ones(), ones44);\n  r44.setZero();\n  VERIFY_IS_APPROX(r44.noalias() += m44.col(0) * RowVector4d::Ones(), ones44);\n  r44.setZero();\n  VERIFY_IS_APPROX(r44.noalias() += Vector4d::Ones() * m44.row(0), ones44);\n  r44.setZero();\n  VERIFY_IS_APPROX(r44.noalias() += Vector4d::Ones() * m44.col(0).transpose(), ones44);\n}\n\nEIGEN_DECLARE_TEST(product_extra)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( product_extra(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_2( product_extra(MatrixXd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_2( mat_mat_scalar_scalar_product() );\n    CALL_SUBTEST_3( product_extra(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2), internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))) );\n    CALL_SUBTEST_4( product_extra(MatrixXcd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2), internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))) );\n    CALL_SUBTEST_1( zero_sized_objects(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  CALL_SUBTEST_5( bug_127<0>() );\n  CALL_SUBTEST_5( bug_817<0>() );\n  CALL_SUBTEST_5( bug_1308<0>() );\n  CALL_SUBTEST_6( unaligned_objects<0>() );\n  CALL_SUBTEST_7( compute_block_size<float>() );\n  CALL_SUBTEST_7( compute_block_size<double>() );\n  CALL_SUBTEST_7( compute_block_size<std::complex<double> >() );\n  CALL_SUBTEST_8( aliasing_with_resize<void>() );\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/product_large.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"product.h\"\n#include <Eigen/LU>\n\ntemplate<typename T>\nvoid test_aliasing()\n{\n  int rows = internal::random<int>(1,12);\n  int cols = internal::random<int>(1,12);\n  typedef Matrix<T,Dynamic,Dynamic> MatrixType;\n  typedef Matrix<T,Dynamic,1> VectorType;\n  VectorType x(cols); x.setRandom();\n  VectorType z(x);\n  VectorType y(rows); y.setZero();\n  MatrixType A(rows,cols); A.setRandom();\n  // CwiseBinaryOp\n  VERIFY_IS_APPROX(x = y + A*x, A*z);     // OK because \"y + A*x\" is marked as \"assume-aliasing\"\n  x = z;\n  // CwiseUnaryOp\n  VERIFY_IS_APPROX(x = T(1.)*(A*x), A*z); // OK because 1*(A*x) is replaced by (1*A*x) which is a Product<> expression\n  x = z;\n  // VERIFY_IS_APPROX(x = y-A*x, -A*z);   // Not OK in 3.3 because x is resized before A*x gets evaluated\n  x = z;\n}\n\ntemplate<int>\nvoid product_large_regressions()\n{\n  {\n    // test a specific issue in DiagonalProduct\n    int N = 1000000;\n    VectorXf v = VectorXf::Ones(N);\n    MatrixXf m = MatrixXf::Ones(N,3);\n    m = (v+v).asDiagonal() * m;\n    VERIFY_IS_APPROX(m, MatrixXf::Constant(N,3,2));\n  }\n\n  {\n    // test deferred resizing in Matrix::operator=\n    MatrixXf a = MatrixXf::Random(10,4), b = MatrixXf::Random(4,10), c = a;\n    VERIFY_IS_APPROX((a = a * b), (c * b).eval());\n  }\n\n  {\n    // check the functions to setup blocking sizes compile and do not segfault\n    // FIXME check they do what they are supposed to do !!\n    std::ptrdiff_t l1 = internal::random<int>(10000,20000);\n    std::ptrdiff_t l2 = internal::random<int>(100000,200000);\n    std::ptrdiff_t l3 = internal::random<int>(1000000,2000000);\n    setCpuCacheSizes(l1,l2,l3);\n    VERIFY(l1==l1CacheSize());\n    VERIFY(l2==l2CacheSize());\n    std::ptrdiff_t k1 = internal::random<int>(10,100)*16;\n    std::ptrdiff_t m1 = internal::random<int>(10,100)*16;\n    std::ptrdiff_t n1 = internal::random<int>(10,100)*16;\n    // only makes sure it compiles fine\n    internal::computeProductBlockingSizes<float,float,std::ptrdiff_t>(k1,m1,n1,1);\n  }\n\n  {\n    // test regression in row-vector by matrix (bad Map type)\n    MatrixXf mat1(10,32); mat1.setRandom();\n    MatrixXf mat2(32,32); mat2.setRandom();\n    MatrixXf r1 = mat1.row(2)*mat2.transpose();\n    VERIFY_IS_APPROX(r1, (mat1.row(2)*mat2.transpose()).eval());\n\n    MatrixXf r2 = mat1.row(2)*mat2;\n    VERIFY_IS_APPROX(r2, (mat1.row(2)*mat2).eval());\n  }\n\n  {\n    Eigen::MatrixXd A(10,10), B, C;\n    A.setRandom();\n    C = A;\n    for(int k=0; k<79; ++k)\n      C = C * A;\n    B.noalias() = (((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)) * ((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)))\n                * (((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)) * ((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)));\n    VERIFY_IS_APPROX(B,C);\n  }\n}\n\ntemplate<int>\nvoid bug_1622() {\n  typedef Matrix<double, 2, -1, 0, 2, -1> Mat2X;\n  Mat2X x(2,2); x.setRandom();\n  MatrixXd y(2,2); y.setRandom();\n  const Mat2X K1 = x * y.inverse();\n  const Matrix2d K2 = x * y.inverse();\n  VERIFY_IS_APPROX(K1,K2);\n}\n\nEIGEN_DECLARE_TEST(product_large)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( product(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_2( product(MatrixXd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_2( product(MatrixXd(internal::random<int>(1,10), internal::random<int>(1,10))) );\n\n    CALL_SUBTEST_3( product(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_4( product(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2), internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))) );\n    CALL_SUBTEST_5( product(Matrix<float,Dynamic,Dynamic,RowMajor>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n\n    CALL_SUBTEST_1( test_aliasing<float>() );\n\n    CALL_SUBTEST_6( bug_1622<1>() );\n\n    CALL_SUBTEST_7( product(MatrixXcd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2), internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))) );\n    CALL_SUBTEST_8( product(Matrix<double,Dynamic,Dynamic,RowMajor>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_9( product(Matrix<std::complex<float>,Dynamic,Dynamic,RowMajor>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_10( product(Matrix<std::complex<double>,Dynamic,Dynamic,RowMajor>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n\n  CALL_SUBTEST_6( product_large_regressions<0>() );\n\n  // Regression test for bug 714:\n#if defined EIGEN_HAS_OPENMP\n  omp_set_dynamic(1);\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_6( product(Matrix<float,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/product_mmtr.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010-2017 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#define CHECK_MMTR(DEST, TRI, OP) {                   \\\n    ref3 = DEST;                                      \\\n    ref2 = ref1 = DEST;                               \\\n    DEST.template triangularView<TRI>() OP;           \\\n    ref1 OP;                                          \\\n    ref2.template triangularView<TRI>()               \\\n      = ref1.template triangularView<TRI>();          \\\n    VERIFY_IS_APPROX(DEST,ref2);                      \\\n    \\\n    DEST = ref3;                                      \\\n    ref3 = ref2;                                      \\\n    ref3.diagonal() = DEST.diagonal();                \\\n    DEST.template triangularView<TRI|ZeroDiag>() OP;  \\\n    VERIFY_IS_APPROX(DEST,ref3);                      \\\n  }\n\ntemplate<typename Scalar> void mmtr(int size)\n{\n  typedef Matrix<Scalar,Dynamic,Dynamic,ColMajor> MatrixColMaj;\n  typedef Matrix<Scalar,Dynamic,Dynamic,RowMajor> MatrixRowMaj;\n\n  DenseIndex othersize = internal::random<DenseIndex>(1,200);\n  \n  MatrixColMaj matc = MatrixColMaj::Zero(size, size);\n  MatrixRowMaj matr = MatrixRowMaj::Zero(size, size);\n  MatrixColMaj ref1(size, size), ref2(size, size), ref3(size,size);\n  \n  MatrixColMaj soc(size,othersize); soc.setRandom();\n  MatrixColMaj osc(othersize,size); osc.setRandom();\n  MatrixRowMaj sor(size,othersize); sor.setRandom();\n  MatrixRowMaj osr(othersize,size); osr.setRandom();\n  MatrixColMaj sqc(size,size); sqc.setRandom();\n  MatrixRowMaj sqr(size,size); sqr.setRandom();\n  \n  Scalar s = internal::random<Scalar>();\n  \n  CHECK_MMTR(matc, Lower, = s*soc*sor.adjoint());\n  CHECK_MMTR(matc, Upper, = s*(soc*soc.adjoint()));\n  CHECK_MMTR(matr, Lower, = s*soc*soc.adjoint());\n  CHECK_MMTR(matr, Upper, = soc*(s*sor.adjoint()));\n  \n  CHECK_MMTR(matc, Lower, += s*soc*soc.adjoint());\n  CHECK_MMTR(matc, Upper, += s*(soc*sor.transpose()));\n  CHECK_MMTR(matr, Lower, += s*sor*soc.adjoint());\n  CHECK_MMTR(matr, Upper, += soc*(s*soc.adjoint()));\n  \n  CHECK_MMTR(matc, Lower, -= s*soc*soc.adjoint());\n  CHECK_MMTR(matc, Upper, -= s*(osc.transpose()*osc.conjugate()));\n  CHECK_MMTR(matr, Lower, -= s*soc*soc.adjoint());\n  CHECK_MMTR(matr, Upper, -= soc*(s*soc.adjoint()));\n  \n  CHECK_MMTR(matc, Lower, -= s*sqr*sqc.template triangularView<Upper>());\n  CHECK_MMTR(matc, Upper, = s*sqc*sqr.template triangularView<Upper>());\n  CHECK_MMTR(matc, Lower, += s*sqr*sqc.template triangularView<Lower>());\n  CHECK_MMTR(matc, Upper, = s*sqc*sqc.template triangularView<Lower>());\n  \n  CHECK_MMTR(matc, Lower, = (s*sqr).template triangularView<Upper>()*sqc);\n  CHECK_MMTR(matc, Upper, -= (s*sqc).template triangularView<Upper>()*sqc);\n  CHECK_MMTR(matc, Lower, = (s*sqr).template triangularView<Lower>()*sqc);\n  CHECK_MMTR(matc, Upper, += (s*sqc).template triangularView<Lower>()*sqc);\n\n  // check aliasing\n  ref2 = ref1 = matc;\n  ref1 = sqc.adjoint() * matc * sqc;\n  ref2.template triangularView<Upper>() = ref1.template triangularView<Upper>();\n  matc.template triangularView<Upper>() = sqc.adjoint() * matc * sqc;\n  VERIFY_IS_APPROX(matc, ref2);\n\n  ref2 = ref1 = matc;\n  ref1 = sqc * matc * sqc.adjoint();\n  ref2.template triangularView<Lower>() = ref1.template triangularView<Lower>();\n  matc.template triangularView<Lower>() = sqc * matc * sqc.adjoint();\n  VERIFY_IS_APPROX(matc, ref2);\n\n  // destination with a non-default inner-stride\n  // see bug 1741\n  {\n    typedef Matrix<Scalar,Dynamic,Dynamic> MatrixX;\n    MatrixX buffer(2*size,2*size);\n    Map<MatrixColMaj,0,Stride<Dynamic,Dynamic> > map1(buffer.data(),size,size,Stride<Dynamic,Dynamic>(2*size,2));\n    buffer.setZero();\n    CHECK_MMTR(map1, Lower, = s*soc*sor.adjoint());\n  }\n}\n\nEIGEN_DECLARE_TEST(product_mmtr)\n{\n  for(int i = 0; i < g_repeat ; i++)\n  {\n    CALL_SUBTEST_1((mmtr<float>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_2((mmtr<double>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_3((mmtr<std::complex<float> >(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))));\n    CALL_SUBTEST_4((mmtr<std::complex<double> >(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/product_notemporary.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define TEST_ENABLE_TEMPORARY_TRACKING\n\n#include \"main.h\"\n\ntemplate<typename Dst, typename Lhs, typename Rhs>\nvoid check_scalar_multiple3(Dst &dst, const Lhs& A, const Rhs& B)\n{\n  VERIFY_EVALUATION_COUNT( (dst.noalias()  = A * B), 0);\n  VERIFY_IS_APPROX( dst, (A.eval() * B.eval()).eval() );\n  VERIFY_EVALUATION_COUNT( (dst.noalias() += A * B), 0);\n  VERIFY_IS_APPROX( dst, 2*(A.eval() * B.eval()).eval() );\n  VERIFY_EVALUATION_COUNT( (dst.noalias() -= A * B), 0);\n  VERIFY_IS_APPROX( dst, (A.eval() * B.eval()).eval() );\n}\n\ntemplate<typename Dst, typename Lhs, typename Rhs, typename S2>\nvoid check_scalar_multiple2(Dst &dst, const Lhs& A, const Rhs& B, S2 s2)\n{\n  CALL_SUBTEST( check_scalar_multiple3(dst, A,    B) );\n  CALL_SUBTEST( check_scalar_multiple3(dst, A,   -B) );\n  CALL_SUBTEST( check_scalar_multiple3(dst, A, s2*B) );\n  CALL_SUBTEST( check_scalar_multiple3(dst, A, B*s2) );\n  CALL_SUBTEST( check_scalar_multiple3(dst, A, (B*s2).conjugate()) );\n}\n\ntemplate<typename Dst, typename Lhs, typename Rhs, typename S1, typename S2>\nvoid check_scalar_multiple1(Dst &dst, const Lhs& A, const Rhs& B, S1 s1, S2 s2)\n{\n  CALL_SUBTEST( check_scalar_multiple2(dst,    A, B, s2) );\n  CALL_SUBTEST( check_scalar_multiple2(dst,   -A, B, s2) );\n  CALL_SUBTEST( check_scalar_multiple2(dst, s1*A, B, s2) );\n  CALL_SUBTEST( check_scalar_multiple2(dst, A*s1, B, s2) );\n  CALL_SUBTEST( check_scalar_multiple2(dst, (A*s1).conjugate(), B, s2) );\n}\n\ntemplate<typename MatrixType> void product_notemporary(const MatrixType& m)\n{\n  /* This test checks the number of temporaries created\n   * during the evaluation of a complex expression */\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef Matrix<Scalar, 1, Dynamic> RowVectorType;\n  typedef Matrix<Scalar, Dynamic, 1> ColVectorType;\n  typedef Matrix<Scalar, Dynamic, Dynamic, ColMajor> ColMajorMatrixType;\n  typedef Matrix<Scalar, Dynamic, Dynamic, RowMajor> RowMajorMatrixType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  ColMajorMatrixType m1 = MatrixType::Random(rows, cols),\n                     m2 = MatrixType::Random(rows, cols),\n                     m3(rows, cols);\n  RowVectorType rv1 = RowVectorType::Random(rows), rvres(rows);\n  ColVectorType cv1 = ColVectorType::Random(cols), cvres(cols);\n  RowMajorMatrixType rm3(rows, cols);\n\n  Scalar s1 = internal::random<Scalar>(),\n         s2 = internal::random<Scalar>(),\n         s3 = internal::random<Scalar>();\n\n  Index c0 = internal::random<Index>(4,cols-8),\n        c1 = internal::random<Index>(8,cols-c0),\n        r0 = internal::random<Index>(4,cols-8),\n        r1 = internal::random<Index>(8,rows-r0);\n\n  VERIFY_EVALUATION_COUNT( m3 = (m1 * m2.adjoint()), 1);\n  VERIFY_EVALUATION_COUNT( m3 = (m1 * m2.adjoint()).transpose(), 1);\n  VERIFY_EVALUATION_COUNT( m3.noalias() = m1 * m2.adjoint(), 0);\n\n  VERIFY_EVALUATION_COUNT( m3 = s1 * (m1 * m2.transpose()), 1);\n//   VERIFY_EVALUATION_COUNT( m3 = m3 + s1 * (m1 * m2.transpose()), 1);\n  VERIFY_EVALUATION_COUNT( m3.noalias() = s1 * (m1 * m2.transpose()), 0);\n\n  VERIFY_EVALUATION_COUNT( m3 = m3 + (m1 * m2.adjoint()), 1);\n  VERIFY_EVALUATION_COUNT( m3 = m3 - (m1 * m2.adjoint()), 1);\n\n  VERIFY_EVALUATION_COUNT( m3 = m3 + (m1 * m2.adjoint()).transpose(), 1);\n  VERIFY_EVALUATION_COUNT( m3.noalias() = m3 + m1 * m2.transpose(), 0);\n  VERIFY_EVALUATION_COUNT( m3.noalias() += m3 + m1 * m2.transpose(), 0);\n  VERIFY_EVALUATION_COUNT( m3.noalias() -= m3 + m1 * m2.transpose(), 0);\n  VERIFY_EVALUATION_COUNT( m3.noalias() =  m3 - m1 * m2.transpose(), 0);\n  VERIFY_EVALUATION_COUNT( m3.noalias() += m3 - m1 * m2.transpose(), 0);\n  VERIFY_EVALUATION_COUNT( m3.noalias() -= m3 - m1 * m2.transpose(), 0);\n\n  VERIFY_EVALUATION_COUNT( m3.noalias() = s1 * m1 * s2 * m2.adjoint(), 0);\n  VERIFY_EVALUATION_COUNT( m3.noalias() = s1 * m1 * s2 * (m1*s3+m2*s2).adjoint(), 1);\n  VERIFY_EVALUATION_COUNT( m3.noalias() = (s1 * m1).adjoint() * s2 * m2, 0);\n  VERIFY_EVALUATION_COUNT( m3.noalias() += s1 * (-m1*s3).adjoint() * (s2 * m2 * s3), 0);\n  VERIFY_EVALUATION_COUNT( m3.noalias() -= s1 * (m1.transpose() * m2), 0);\n\n  VERIFY_EVALUATION_COUNT(( m3.block(r0,r0,r1,r1).noalias() += -m1.block(r0,c0,r1,c1) * (s2*m2.block(r0,c0,r1,c1)).adjoint() ), 0);\n  VERIFY_EVALUATION_COUNT(( m3.block(r0,r0,r1,r1).noalias() -= s1 * m1.block(r0,c0,r1,c1) * m2.block(c0,r0,c1,r1) ), 0);\n\n  // NOTE this is because the Block expression is not handled yet by our expression analyser\n  VERIFY_EVALUATION_COUNT(( m3.block(r0,r0,r1,r1).noalias() = s1 * m1.block(r0,c0,r1,c1) * (s1*m2).block(c0,r0,c1,r1) ), 1);\n\n  VERIFY_EVALUATION_COUNT( m3.noalias() -= (s1 * m1).template triangularView<Lower>() * m2, 0);\n  VERIFY_EVALUATION_COUNT( rm3.noalias() = (s1 * m1.adjoint()).template triangularView<Upper>() * (m2+m2), 1);\n  VERIFY_EVALUATION_COUNT( rm3.noalias() = (s1 * m1.adjoint()).template triangularView<UnitUpper>() * m2.adjoint(), 0);\n\n  VERIFY_EVALUATION_COUNT( m3.template triangularView<Upper>() = (m1 * m2.adjoint()), 0);\n  VERIFY_EVALUATION_COUNT( m3.template triangularView<Upper>() -= (m1 * m2.adjoint()), 0);\n\n  // NOTE this is because the blas_traits require innerstride==1 to avoid a temporary, but that doesn't seem to be actually needed for the triangular products\n  VERIFY_EVALUATION_COUNT( rm3.col(c0).noalias() = (s1 * m1.adjoint()).template triangularView<UnitUpper>() * (s2*m2.row(c0)).adjoint(), 1);\n\n  VERIFY_EVALUATION_COUNT( m1.template triangularView<Lower>().solveInPlace(m3), 0);\n  VERIFY_EVALUATION_COUNT( m1.adjoint().template triangularView<Lower>().solveInPlace(m3.transpose()), 0);\n\n  VERIFY_EVALUATION_COUNT( m3.noalias() -= (s1 * m1).adjoint().template selfadjointView<Lower>() * (-m2*s3).adjoint(), 0);\n  VERIFY_EVALUATION_COUNT( m3.noalias() = s2 * m2.adjoint() * (s1 * m1.adjoint()).template selfadjointView<Upper>(), 0);\n  VERIFY_EVALUATION_COUNT( rm3.noalias() = (s1 * m1.adjoint()).template selfadjointView<Lower>() * m2.adjoint(), 0);\n\n  // NOTE this is because the blas_traits require innerstride==1 to avoid a temporary, but that doesn't seem to be actually needed for the triangular products\n  VERIFY_EVALUATION_COUNT( m3.col(c0).noalias() = (s1 * m1).adjoint().template selfadjointView<Lower>() * (-m2.row(c0)*s3).adjoint(), 1);\n  VERIFY_EVALUATION_COUNT( m3.col(c0).noalias() -= (s1 * m1).adjoint().template selfadjointView<Upper>() * (-m2.row(c0)*s3).adjoint(), 1);\n\n  VERIFY_EVALUATION_COUNT( m3.block(r0,c0,r1,c1).noalias() += m1.block(r0,r0,r1,r1).template selfadjointView<Upper>() * (s1*m2.block(r0,c0,r1,c1)), 0);\n  VERIFY_EVALUATION_COUNT( m3.block(r0,c0,r1,c1).noalias() = m1.block(r0,r0,r1,r1).template selfadjointView<Upper>() * m2.block(r0,c0,r1,c1), 0);\n\n  VERIFY_EVALUATION_COUNT( m3.template selfadjointView<Lower>().rankUpdate(m2.adjoint()), 0);\n\n  // Here we will get 1 temporary for each resize operation of the lhs operator; resize(r1,c1) would lead to zero temporaries\n  m3.resize(1,1);\n  VERIFY_EVALUATION_COUNT( m3.noalias() = m1.block(r0,r0,r1,r1).template selfadjointView<Lower>() * m2.block(r0,c0,r1,c1), 1);\n  m3.resize(1,1);\n  VERIFY_EVALUATION_COUNT( m3.noalias() = m1.block(r0,r0,r1,r1).template triangularView<UnitUpper>()  * m2.block(r0,c0,r1,c1), 1);\n\n  // Zero temporaries for lazy products ...\n  m3.setRandom(rows,cols);\n  VERIFY_EVALUATION_COUNT( Scalar tmp = 0; tmp += Scalar(RealScalar(1)) /  (m3.transpose().lazyProduct(m3)).diagonal().sum(), 0 );\n  VERIFY_EVALUATION_COUNT( m3.noalias() = m1.conjugate().lazyProduct(m2.conjugate()), 0);\n\n  // ... and even no temporary for even deeply (>=2) nested products\n  VERIFY_EVALUATION_COUNT( Scalar tmp = 0; tmp += Scalar(RealScalar(1)) /  (m3.transpose() * m3).diagonal().sum(), 0 );\n  VERIFY_EVALUATION_COUNT( Scalar tmp = 0; tmp += Scalar(RealScalar(1)) /  (m3.transpose() * m3).diagonal().array().abs().sum(), 0 );\n\n  // Zero temporaries for ... CoeffBasedProductMode\n  VERIFY_EVALUATION_COUNT( m3.col(0).template head<5>() * m3.col(0).transpose() + m3.col(0).template head<5>() * m3.col(0).transpose(), 0 );\n\n  // Check matrix * vectors\n  VERIFY_EVALUATION_COUNT( cvres.noalias() = m1 * cv1, 0 );\n  VERIFY_EVALUATION_COUNT( cvres.noalias() -= m1 * cv1, 0 );\n  VERIFY_EVALUATION_COUNT( cvres.noalias() -= m1 * m2.col(0), 0 );\n  VERIFY_EVALUATION_COUNT( cvres.noalias() -= m1 * rv1.adjoint(), 0 );\n  VERIFY_EVALUATION_COUNT( cvres.noalias() -= m1 * m2.row(0).transpose(), 0 );\n\n  VERIFY_EVALUATION_COUNT( cvres.noalias() = (m1+m1) * cv1, 0 );\n  VERIFY_EVALUATION_COUNT( cvres.noalias() = (rm3+rm3) * cv1, 0 );\n  VERIFY_EVALUATION_COUNT( cvres.noalias() = (m1+m1) * (m1*cv1), 1 );\n  VERIFY_EVALUATION_COUNT( cvres.noalias() = (rm3+rm3) * (m1*cv1), 1 );\n\n  // Check outer products\n  #ifdef EIGEN_ALLOCA\n  bool temp_via_alloca = m3.rows()*sizeof(Scalar) <= EIGEN_STACK_ALLOCATION_LIMIT;\n  #else\n  bool temp_via_alloca = false;\n  #endif\n  m3 = cv1 * rv1;\n  VERIFY_EVALUATION_COUNT( m3.noalias() = cv1 * rv1, 0 );\n  VERIFY_EVALUATION_COUNT( m3.noalias() = (cv1+cv1) * (rv1+rv1), temp_via_alloca ? 0 : 1 );\n  VERIFY_EVALUATION_COUNT( m3.noalias() = (m1*cv1) * (rv1), 1 );\n  VERIFY_EVALUATION_COUNT( m3.noalias() += (m1*cv1) * (rv1), 1 );\n  rm3 = cv1 * rv1;\n  VERIFY_EVALUATION_COUNT( rm3.noalias() = cv1 * rv1, 0 );\n  VERIFY_EVALUATION_COUNT( rm3.noalias() = (cv1+cv1) * (rv1+rv1), temp_via_alloca ? 0 : 1 );\n  VERIFY_EVALUATION_COUNT( rm3.noalias() = (cv1) * (rv1 * m1), 1 );\n  VERIFY_EVALUATION_COUNT( rm3.noalias() -= (cv1) * (rv1 * m1), 1 );\n  VERIFY_EVALUATION_COUNT( rm3.noalias() = (m1*cv1) * (rv1 * m1), 2 );\n  VERIFY_EVALUATION_COUNT( rm3.noalias() += (m1*cv1) * (rv1 * m1), 2 );\n\n  // Check nested products\n  VERIFY_EVALUATION_COUNT( cvres.noalias() = m1.adjoint() * m1 * cv1, 1 );\n  VERIFY_EVALUATION_COUNT( rvres.noalias() = rv1 * (m1 * m2.adjoint()), 1 );\n\n  // exhaustively check all scalar multiple combinations:\n  {\n    // Generic path:\n    check_scalar_multiple1(m3, m1, m2, s1, s2);\n    // Force fall back to coeff-based:\n    typename ColMajorMatrixType::BlockXpr m3_blck = m3.block(r0,r0,1,1);\n    check_scalar_multiple1(m3_blck, m1.block(r0,c0,1,1), m2.block(c0,r0,1,1), s1, s2);\n  }\n}\n\nEIGEN_DECLARE_TEST(product_notemporary)\n{\n  int s;\n  for(int i = 0; i < g_repeat; i++) {\n    s = internal::random<int>(16,EIGEN_TEST_MAX_SIZE);\n    CALL_SUBTEST_1( product_notemporary(MatrixXf(s, s)) );\n    CALL_SUBTEST_2( product_notemporary(MatrixXd(s, s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n    \n    s = internal::random<int>(16,EIGEN_TEST_MAX_SIZE/2);\n    CALL_SUBTEST_3( product_notemporary(MatrixXcf(s,s)) );\n    CALL_SUBTEST_4( product_notemporary(MatrixXcd(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/product_selfadjoint.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void product_selfadjoint(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n  typedef Matrix<Scalar, 1, MatrixType::RowsAtCompileTime> RowVectorType;\n\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, Dynamic, RowMajor> RhsMatrixType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3;\n  VectorType v1 = VectorType::Random(rows),\n             v2 = VectorType::Random(rows),\n             v3(rows);\n  RowVectorType r1 = RowVectorType::Random(rows),\n                r2 = RowVectorType::Random(rows);\n  RhsMatrixType m4 = RhsMatrixType::Random(rows,10);\n\n  Scalar s1 = internal::random<Scalar>(),\n         s2 = internal::random<Scalar>(),\n         s3 = internal::random<Scalar>();\n\n  m1 = (m1.adjoint() + m1).eval();\n\n  // rank2 update\n  m2 = m1.template triangularView<Lower>();\n  m2.template selfadjointView<Lower>().rankUpdate(v1,v2);\n  VERIFY_IS_APPROX(m2, (m1 + v1 * v2.adjoint()+ v2 * v1.adjoint()).template triangularView<Lower>().toDenseMatrix());\n\n  m2 = m1.template triangularView<Upper>();\n  m2.template selfadjointView<Upper>().rankUpdate(-v1,s2*v2,s3);\n  VERIFY_IS_APPROX(m2, (m1 + (s3*(-v1)*(s2*v2).adjoint()+numext::conj(s3)*(s2*v2)*(-v1).adjoint())).template triangularView<Upper>().toDenseMatrix());\n\n  m2 = m1.template triangularView<Upper>();\n  m2.template selfadjointView<Upper>().rankUpdate(-s2*r1.adjoint(),r2.adjoint()*s3,s1);\n  VERIFY_IS_APPROX(m2, (m1 + s1*(-s2*r1.adjoint())*(r2.adjoint()*s3).adjoint() + numext::conj(s1)*(r2.adjoint()*s3) * (-s2*r1.adjoint()).adjoint()).template triangularView<Upper>().toDenseMatrix());\n\n  if (rows>1)\n  {\n    m2 = m1.template triangularView<Lower>();\n    m2.block(1,1,rows-1,cols-1).template selfadjointView<Lower>().rankUpdate(v1.tail(rows-1),v2.head(cols-1));\n    m3 = m1;\n    m3.block(1,1,rows-1,cols-1) += v1.tail(rows-1) * v2.head(cols-1).adjoint()+ v2.head(cols-1) * v1.tail(rows-1).adjoint();\n    VERIFY_IS_APPROX(m2, m3.template triangularView<Lower>().toDenseMatrix());\n  }\n}\n\nEIGEN_DECLARE_TEST(product_selfadjoint)\n{\n  int s = 0;\n  for(int i = 0; i < g_repeat ; i++) {\n    CALL_SUBTEST_1( product_selfadjoint(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( product_selfadjoint(Matrix<float, 2, 2>()) );\n    CALL_SUBTEST_3( product_selfadjoint(Matrix3d()) );\n    \n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2);\n    CALL_SUBTEST_4( product_selfadjoint(MatrixXcf(s, s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n    \n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2);\n    CALL_SUBTEST_5( product_selfadjoint(MatrixXcd(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n    \n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE);\n    CALL_SUBTEST_6( product_selfadjoint(MatrixXd(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n    \n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE);\n    CALL_SUBTEST_7( product_selfadjoint(Matrix<float,Dynamic,Dynamic,RowMajor>(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/product_small.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_STATIC_ASSERT\n#include \"product.h\"\n#include <Eigen/LU>\n\n// regression test for bug 447\ntemplate<int>\nvoid product1x1()\n{\n  Matrix<float,1,3> matAstatic;\n  Matrix<float,3,1> matBstatic;\n  matAstatic.setRandom();\n  matBstatic.setRandom();\n  VERIFY_IS_APPROX( (matAstatic * matBstatic).coeff(0,0), \n                    matAstatic.cwiseProduct(matBstatic.transpose()).sum() );\n\n  MatrixXf matAdynamic(1,3);\n  MatrixXf matBdynamic(3,1);\n  matAdynamic.setRandom();\n  matBdynamic.setRandom();\n  VERIFY_IS_APPROX( (matAdynamic * matBdynamic).coeff(0,0), \n                    matAdynamic.cwiseProduct(matBdynamic.transpose()).sum() );\n}\n\ntemplate<typename TC, typename TA, typename TB>\nconst TC& ref_prod(TC &C, const TA &A, const TB &B)\n{\n  for(Index i=0;i<C.rows();++i)\n    for(Index j=0;j<C.cols();++j)\n      for(Index k=0;k<A.cols();++k)\n        C.coeffRef(i,j) += A.coeff(i,k) * B.coeff(k,j);\n  return C;\n}\n\ntemplate<typename T, int Rows, int Cols, int Depth, int OC, int OA, int OB>\ntypename internal::enable_if<! ( (Rows ==1&&Depth!=1&&OA==ColMajor)\n                              || (Depth==1&&Rows !=1&&OA==RowMajor)\n                              || (Cols ==1&&Depth!=1&&OB==RowMajor)\n                              || (Depth==1&&Cols !=1&&OB==ColMajor)\n                              || (Rows ==1&&Cols !=1&&OC==ColMajor)\n                              || (Cols ==1&&Rows !=1&&OC==RowMajor)),void>::type\ntest_lazy_single(int rows, int cols, int depth)\n{\n  Matrix<T,Rows,Depth,OA> A(rows,depth); A.setRandom();\n  Matrix<T,Depth,Cols,OB> B(depth,cols); B.setRandom();\n  Matrix<T,Rows,Cols,OC>  C(rows,cols);  C.setRandom();\n  Matrix<T,Rows,Cols,OC>  D(C);\n  VERIFY_IS_APPROX(C+=A.lazyProduct(B), ref_prod(D,A,B));\n}\n\nvoid test_dynamic_bool()\n{\n  int rows = internal::random<int>(1,64);\n  int cols = internal::random<int>(1,64);\n  int depth = internal::random<int>(1,65);\n\n  typedef Matrix<bool,Dynamic,Dynamic> MatrixX;\n  MatrixX A(rows,depth); A.setRandom();\n  MatrixX B(depth,cols); B.setRandom();\n  MatrixX C(rows,cols);  C.setRandom();\n  MatrixX D(C);\n  for(Index i=0;i<C.rows();++i)\n    for(Index j=0;j<C.cols();++j)\n      for(Index k=0;k<A.cols();++k)\n       D.coeffRef(i,j) |= A.coeff(i,k) & B.coeff(k,j);\n  C += A * B;\n  VERIFY_IS_EQUAL(C, D);\n\n  MatrixX E = B.transpose();\n  for(Index i=0;i<B.rows();++i)\n    for(Index j=0;j<B.cols();++j)\n      VERIFY_IS_EQUAL(B(i,j), E(j,i));\n}\n\ntemplate<typename T, int Rows, int Cols, int Depth, int OC, int OA, int OB>\ntypename internal::enable_if<  ( (Rows ==1&&Depth!=1&&OA==ColMajor)\n                              || (Depth==1&&Rows !=1&&OA==RowMajor)\n                              || (Cols ==1&&Depth!=1&&OB==RowMajor)\n                              || (Depth==1&&Cols !=1&&OB==ColMajor)\n                              || (Rows ==1&&Cols !=1&&OC==ColMajor)\n                              || (Cols ==1&&Rows !=1&&OC==RowMajor)),void>::type\ntest_lazy_single(int, int, int)\n{\n}\n\ntemplate<typename T, int Rows, int Cols, int Depth>\nvoid test_lazy_all_layout(int rows=Rows, int cols=Cols, int depth=Depth)\n{\n  CALL_SUBTEST(( test_lazy_single<T,Rows,Cols,Depth,ColMajor,ColMajor,ColMajor>(rows,cols,depth) ));\n  CALL_SUBTEST(( test_lazy_single<T,Rows,Cols,Depth,RowMajor,ColMajor,ColMajor>(rows,cols,depth) ));\n  CALL_SUBTEST(( test_lazy_single<T,Rows,Cols,Depth,ColMajor,RowMajor,ColMajor>(rows,cols,depth) ));\n  CALL_SUBTEST(( test_lazy_single<T,Rows,Cols,Depth,RowMajor,RowMajor,ColMajor>(rows,cols,depth) ));\n  CALL_SUBTEST(( test_lazy_single<T,Rows,Cols,Depth,ColMajor,ColMajor,RowMajor>(rows,cols,depth) ));\n  CALL_SUBTEST(( test_lazy_single<T,Rows,Cols,Depth,RowMajor,ColMajor,RowMajor>(rows,cols,depth) ));\n  CALL_SUBTEST(( test_lazy_single<T,Rows,Cols,Depth,ColMajor,RowMajor,RowMajor>(rows,cols,depth) ));\n  CALL_SUBTEST(( test_lazy_single<T,Rows,Cols,Depth,RowMajor,RowMajor,RowMajor>(rows,cols,depth) ));\n}  \n\ntemplate<typename T>\nvoid test_lazy_l1()\n{\n  int rows = internal::random<int>(1,12);\n  int cols = internal::random<int>(1,12);\n  int depth = internal::random<int>(1,12);\n\n  // Inner\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,1,1>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,1,2>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,1,3>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,1,8>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,1,9>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,1,-1>(1,1,depth) ));\n\n  // Outer\n  CALL_SUBTEST(( test_lazy_all_layout<T,2,1,1>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,2,1>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,2,2,1>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,3,3,1>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,4,1>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,8,1>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,-1,1>(4,cols) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,7,-1,1>(7,cols) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,-1,8,1>(rows) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,-1,3,1>(rows) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,-1,-1,1>(rows,cols) ));\n}\n\ntemplate<typename T>\nvoid test_lazy_l2()\n{\n  int rows = internal::random<int>(1,12);\n  int cols = internal::random<int>(1,12);\n  int depth = internal::random<int>(1,12);\n\n  // mat-vec\n  CALL_SUBTEST(( test_lazy_all_layout<T,2,1,2>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,2,1,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,1,2>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,1,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,5,1,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,1,5>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,1,6>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,6,1,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,8,1,8>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,-1,1,4>(rows) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,1,-1>(4,1,depth) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,-1,1,-1>(rows,1,depth) ));\n\n  // vec-mat\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,2,2>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,2,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,4,2>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,4,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,5,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,4,5>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,4,6>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,6,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,8,8>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,-1, 4>(1,cols) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1, 4,-1>(1,4,depth) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,-1,-1>(1,cols,depth) ));\n}\n\ntemplate<typename T>\nvoid test_lazy_l3()\n{\n  int rows = internal::random<int>(1,12);\n  int cols = internal::random<int>(1,12);\n  int depth = internal::random<int>(1,12);\n  // mat-mat\n  CALL_SUBTEST(( test_lazy_all_layout<T,2,4,2>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,2,6,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,3,2>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,8,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,5,6,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,2,5>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,7,6>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,6,8,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,8,3,8>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,-1,6,4>(rows) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,3,-1>(4,3,depth) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,-1,6,-1>(rows,6,depth) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,8,2,2>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,5,2,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,4,2>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,8,4,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,6,5,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,4,5>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,3,4,6>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,2,6,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,7,8,8>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,8,-1, 4>(8,cols) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,3, 4,-1>(3,4,depth) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,-1,-1>(4,cols,depth) ));\n}\n\ntemplate<typename T,int N,int M,int K>\nvoid test_linear_but_not_vectorizable()\n{\n  // Check tricky cases for which the result of the product is a vector and thus must exhibit the LinearBit flag,\n  // but is not vectorizable along the linear dimension.\n  Index n = N==Dynamic ? internal::random<Index>(1,32) : N;\n  Index m = M==Dynamic ? internal::random<Index>(1,32) : M;\n  Index k = K==Dynamic ? internal::random<Index>(1,32) : K;\n\n  {\n    Matrix<T,N,M+1> A; A.setRandom(n,m+1);\n    Matrix<T,M*2,K> B; B.setRandom(m*2,k);\n    Matrix<T,1,K> C;\n    Matrix<T,1,K> R;\n\n    C.noalias() = A.template topLeftCorner<1,M>() * (B.template topRows<M>()+B.template bottomRows<M>());\n    R.noalias() = A.template topLeftCorner<1,M>() * (B.template topRows<M>()+B.template bottomRows<M>()).eval();\n    VERIFY_IS_APPROX(C,R);\n  }\n\n  {\n    Matrix<T,M+1,N,RowMajor> A; A.setRandom(m+1,n);\n    Matrix<T,K,M*2,RowMajor> B; B.setRandom(k,m*2);\n    Matrix<T,K,1> C;\n    Matrix<T,K,1> R;\n\n    C.noalias() = (B.template leftCols<M>()+B.template rightCols<M>())        * A.template topLeftCorner<M,1>();\n    R.noalias() = (B.template leftCols<M>()+B.template rightCols<M>()).eval() * A.template topLeftCorner<M,1>();\n    VERIFY_IS_APPROX(C,R);\n  }\n}\n\ntemplate<int Rows>\nvoid bug_1311()\n{\n  Matrix< double, Rows, 2 > A;  A.setRandom();\n  Vector2d b = Vector2d::Random() ;\n  Matrix<double,Rows,1> res;\n  res.noalias() = 1. * (A * b);\n  VERIFY_IS_APPROX(res, A*b);\n  res.noalias() = 1.*A * b;\n  VERIFY_IS_APPROX(res, A*b);\n  res.noalias() = (1.*A).lazyProduct(b);\n  VERIFY_IS_APPROX(res, A*b);\n  res.noalias() = (1.*A).lazyProduct(1.*b);\n  VERIFY_IS_APPROX(res, A*b);\n  res.noalias() = (A).lazyProduct(1.*b);\n  VERIFY_IS_APPROX(res, A*b);\n}\n\ntemplate<int>\nvoid product_small_regressions()\n{\n  {\n    // test compilation of (outer_product) * vector\n    Vector3f v = Vector3f::Random();\n    VERIFY_IS_APPROX( (v * v.transpose()) * v, (v * v.transpose()).eval() * v);\n  }\n  \n  {\n    // regression test for pull-request #93\n    Eigen::Matrix<double, 1, 1> A;  A.setRandom();\n    Eigen::Matrix<double, 18, 1> B; B.setRandom();\n    Eigen::Matrix<double, 1, 18> C; C.setRandom();\n    VERIFY_IS_APPROX(B * A.inverse(), B * A.inverse()[0]);\n    VERIFY_IS_APPROX(A.inverse() * C, A.inverse()[0] * C);\n  }\n\n  {\n    Eigen::Matrix<double, 10, 10> A, B, C;\n    A.setRandom();\n    C = A;\n    for(int k=0; k<79; ++k)\n      C = C * A;\n    B.noalias() = (((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)) * ((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)))\n                * (((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)) * ((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)));\n    VERIFY_IS_APPROX(B,C);\n  }\n}\n\nEIGEN_DECLARE_TEST(product_small)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( product(Matrix<float, 3, 2>()) );\n    CALL_SUBTEST_2( product(Matrix<int, 3, 17>()) );\n    CALL_SUBTEST_8( product(Matrix<double, 3, 17>()) );\n    CALL_SUBTEST_3( product(Matrix3d()) );\n    CALL_SUBTEST_4( product(Matrix4d()) );\n    CALL_SUBTEST_5( product(Matrix4f()) );\n    CALL_SUBTEST_6( product1x1<0>() );\n\n    CALL_SUBTEST_11( test_lazy_l1<float>() );\n    CALL_SUBTEST_12( test_lazy_l2<float>() );\n    CALL_SUBTEST_13( test_lazy_l3<float>() );\n\n    CALL_SUBTEST_21( test_lazy_l1<double>() );\n    CALL_SUBTEST_22( test_lazy_l2<double>() );\n    CALL_SUBTEST_23( test_lazy_l3<double>() );\n\n    CALL_SUBTEST_31( test_lazy_l1<std::complex<float> >() );\n    CALL_SUBTEST_32( test_lazy_l2<std::complex<float> >() );\n    CALL_SUBTEST_33( test_lazy_l3<std::complex<float> >() );\n\n    CALL_SUBTEST_41( test_lazy_l1<std::complex<double> >() );\n    CALL_SUBTEST_42( test_lazy_l2<std::complex<double> >() );\n    CALL_SUBTEST_43( test_lazy_l3<std::complex<double> >() );\n\n    CALL_SUBTEST_7(( test_linear_but_not_vectorizable<float,2,1,Dynamic>() ));\n    CALL_SUBTEST_7(( test_linear_but_not_vectorizable<float,3,1,Dynamic>() ));\n    CALL_SUBTEST_7(( test_linear_but_not_vectorizable<float,2,1,16>() ));\n\n    CALL_SUBTEST_6( bug_1311<3>() );\n    CALL_SUBTEST_6( bug_1311<5>() );\n\n    CALL_SUBTEST_9( test_dynamic_bool() );\n  }\n\n  CALL_SUBTEST_6( product_small_regressions<0>() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/product_symm.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename Scalar, int Size, int OtherSize> void symm(int size = Size, int othersize = OtherSize)\n{\n  typedef Matrix<Scalar, Size, Size> MatrixType;\n  typedef Matrix<Scalar, Size, OtherSize> Rhs1;\n  typedef Matrix<Scalar, OtherSize, Size> Rhs2;\n  enum { order = OtherSize==1 ? 0 : RowMajor };\n  typedef Matrix<Scalar, Size, OtherSize,order> Rhs3;\n\n  Index rows = size;\n  Index cols = size;\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols), m3;\n\n  m1 = (m1+m1.adjoint()).eval();\n\n  Rhs1 rhs1 = Rhs1::Random(cols, othersize), rhs12(cols, othersize), rhs13(cols, othersize);\n  Rhs2 rhs2 = Rhs2::Random(othersize, rows), rhs22(othersize, rows), rhs23(othersize, rows);\n  Rhs3 rhs3 = Rhs3::Random(cols, othersize), rhs32(cols, othersize), rhs33(cols, othersize);\n\n  Scalar s1 = internal::random<Scalar>(),\n         s2 = internal::random<Scalar>();\n\n  m2 = m1.template triangularView<Lower>();\n  m3 = m2.template selfadjointView<Lower>();\n  VERIFY_IS_EQUAL(m1, m3);\n  VERIFY_IS_APPROX(rhs12 = (s1*m2).template selfadjointView<Lower>() * (s2*rhs1),\n                   rhs13 = (s1*m1) * (s2*rhs1));\n\n  VERIFY_IS_APPROX(rhs12 = (s1*m2).transpose().template selfadjointView<Upper>() * (s2*rhs1),\n                   rhs13 = (s1*m1.transpose()) * (s2*rhs1));\n\n  VERIFY_IS_APPROX(rhs12 = (s1*m2).template selfadjointView<Lower>().transpose() * (s2*rhs1),\n                   rhs13 = (s1*m1.transpose()) * (s2*rhs1));\n\n  VERIFY_IS_APPROX(rhs12 = (s1*m2).conjugate().template selfadjointView<Lower>() * (s2*rhs1),\n                   rhs13 = (s1*m1).conjugate() * (s2*rhs1));\n\n  VERIFY_IS_APPROX(rhs12 = (s1*m2).template selfadjointView<Lower>().conjugate() * (s2*rhs1),\n                   rhs13 = (s1*m1).conjugate() * (s2*rhs1));\n\n  VERIFY_IS_APPROX(rhs12 = (s1*m2).adjoint().template selfadjointView<Upper>() * (s2*rhs1),\n                   rhs13 = (s1*m1).adjoint() * (s2*rhs1));\n\n  VERIFY_IS_APPROX(rhs12 = (s1*m2).template selfadjointView<Lower>().adjoint() * (s2*rhs1),\n                   rhs13 = (s1*m1).adjoint() * (s2*rhs1));\n\n  m2 = m1.template triangularView<Upper>(); rhs12.setRandom(); rhs13 = rhs12;\n  m3 = m2.template selfadjointView<Upper>();\n  VERIFY_IS_EQUAL(m1, m3);\n  VERIFY_IS_APPROX(rhs12 += (s1*m2).template selfadjointView<Upper>() * (s2*rhs1),\n                   rhs13 += (s1*m1) * (s2*rhs1));\n\n  m2 = m1.template triangularView<Lower>();\n  VERIFY_IS_APPROX(rhs12 = (s1*m2).template selfadjointView<Lower>() * (s2*rhs2.adjoint()),\n                   rhs13 = (s1*m1) * (s2*rhs2.adjoint()));\n\n  m2 = m1.template triangularView<Upper>();\n  VERIFY_IS_APPROX(rhs12 = (s1*m2).template selfadjointView<Upper>() * (s2*rhs2.adjoint()),\n                   rhs13 = (s1*m1) * (s2*rhs2.adjoint()));\n\n  m2 = m1.template triangularView<Upper>();\n  VERIFY_IS_APPROX(rhs12 = (s1*m2.adjoint()).template selfadjointView<Lower>() * (s2*rhs2.adjoint()),\n                   rhs13 = (s1*m1.adjoint()) * (s2*rhs2.adjoint()));\n\n  // test row major = <...>\n  m2 = m1.template triangularView<Lower>(); rhs32.setRandom(); rhs13 = rhs32;\n  VERIFY_IS_APPROX(rhs32.noalias() -= (s1*m2).template selfadjointView<Lower>() * (s2*rhs3),\n                   rhs13 -= (s1*m1) * (s2 * rhs3));\n\n  m2 = m1.template triangularView<Upper>();\n  VERIFY_IS_APPROX(rhs32.noalias() = (s1*m2.adjoint()).template selfadjointView<Lower>() * (s2*rhs3).conjugate(),\n                   rhs13 = (s1*m1.adjoint()) * (s2*rhs3).conjugate());\n\n\n  m2 = m1.template triangularView<Upper>(); rhs13 = rhs12;\n  VERIFY_IS_APPROX(rhs12.noalias() += s1 * ((m2.adjoint()).template selfadjointView<Lower>() * (s2*rhs3).conjugate()),\n                   rhs13 += (s1*m1.adjoint()) * (s2*rhs3).conjugate());\n\n  m2 = m1.template triangularView<Lower>();\n  VERIFY_IS_APPROX(rhs22 = (rhs2) * (m2).template selfadjointView<Lower>(), rhs23 = (rhs2) * (m1));\n  VERIFY_IS_APPROX(rhs22 = (s2*rhs2) * (s1*m2).template selfadjointView<Lower>(), rhs23 = (s2*rhs2) * (s1*m1));\n\n  // destination with a non-default inner-stride\n  // see bug 1741\n  {\n    typedef Matrix<Scalar,Dynamic,Dynamic> MatrixX;\n    MatrixX buffer(2*cols,2*othersize);\n    Map<Rhs1,0,Stride<Dynamic,2> > map1(buffer.data(),cols,othersize,Stride<Dynamic,2>(2*rows,2));\n    buffer.setZero();\n    VERIFY_IS_APPROX( map1.noalias()  = (s1*m2).template selfadjointView<Lower>() * (s2*rhs1),\n                      rhs13 = (s1*m1) * (s2*rhs1));\n\n    Map<Rhs2,0,Stride<Dynamic,2> > map2(buffer.data(),rhs22.rows(),rhs22.cols(),Stride<Dynamic,2>(2*rhs22.outerStride(),2));\n    buffer.setZero();\n    VERIFY_IS_APPROX(map2 = (rhs2) * (m2).template selfadjointView<Lower>(), rhs23 = (rhs2) * (m1));\n  }\n}\n\nEIGEN_DECLARE_TEST(product_symm)\n{\n  for(int i = 0; i < g_repeat ; i++)\n  {\n    CALL_SUBTEST_1(( symm<float,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE),internal::random<int>(1,EIGEN_TEST_MAX_SIZE)) ));\n    CALL_SUBTEST_2(( symm<double,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE),internal::random<int>(1,EIGEN_TEST_MAX_SIZE)) ));\n    CALL_SUBTEST_3(( symm<std::complex<float>,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2),internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2)) ));\n    CALL_SUBTEST_4(( symm<std::complex<double>,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2),internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2)) ));\n\n    CALL_SUBTEST_5(( symm<float,Dynamic,1>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)) ));\n    CALL_SUBTEST_6(( symm<double,Dynamic,1>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)) ));\n    CALL_SUBTEST_7(( symm<std::complex<float>,Dynamic,1>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)) ));\n    CALL_SUBTEST_8(( symm<std::complex<double>,Dynamic,1>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)) ));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/product_syrk.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void syrk(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::ColsAtCompileTime, RowMajor> RMatrixType;\n  typedef Matrix<Scalar, MatrixType::ColsAtCompileTime, Dynamic> Rhs1;\n  typedef Matrix<Scalar, Dynamic, MatrixType::RowsAtCompileTime> Rhs2;\n  typedef Matrix<Scalar, MatrixType::ColsAtCompileTime, Dynamic,RowMajor> Rhs3;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3 = MatrixType::Random(rows, cols);\n  RMatrixType rm2 = MatrixType::Random(rows, cols);\n\n  Rhs1 rhs1 = Rhs1::Random(internal::random<int>(1,320), cols); Rhs1 rhs11 = Rhs1::Random(rhs1.rows(), cols);\n  Rhs2 rhs2 = Rhs2::Random(rows, internal::random<int>(1,320)); Rhs2 rhs22 = Rhs2::Random(rows, rhs2.cols());\n  Rhs3 rhs3 = Rhs3::Random(internal::random<int>(1,320), rows);\n\n  Scalar s1 = internal::random<Scalar>();\n  \n  Index c = internal::random<Index>(0,cols-1);\n\n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template selfadjointView<Lower>().rankUpdate(rhs2,s1)._expression()),\n                   ((s1 * rhs2 * rhs2.adjoint()).eval().template triangularView<Lower>().toDenseMatrix()));\n  m2.setZero();\n  VERIFY_IS_APPROX(((m2.template triangularView<Lower>() += s1 * rhs2  * rhs22.adjoint()).nestedExpression()),\n                   ((s1 * rhs2 * rhs22.adjoint()).eval().template triangularView<Lower>().toDenseMatrix()));\n\n  \n  m2.setZero();\n  VERIFY_IS_APPROX(m2.template selfadjointView<Upper>().rankUpdate(rhs2,s1)._expression(),\n                   (s1 * rhs2 * rhs2.adjoint()).eval().template triangularView<Upper>().toDenseMatrix());\n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template triangularView<Upper>() += s1 * rhs22 * rhs2.adjoint()).nestedExpression(),\n                   (s1 * rhs22 * rhs2.adjoint()).eval().template triangularView<Upper>().toDenseMatrix());\n\n  \n  m2.setZero();\n  VERIFY_IS_APPROX(m2.template selfadjointView<Lower>().rankUpdate(rhs1.adjoint(),s1)._expression(),\n                   (s1 * rhs1.adjoint() * rhs1).eval().template triangularView<Lower>().toDenseMatrix());\n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template triangularView<Lower>() += s1 * rhs11.adjoint() * rhs1).nestedExpression(),\n                   (s1 * rhs11.adjoint() * rhs1).eval().template triangularView<Lower>().toDenseMatrix());\n  \n  \n  m2.setZero();\n  VERIFY_IS_APPROX(m2.template selfadjointView<Upper>().rankUpdate(rhs1.adjoint(),s1)._expression(),\n                   (s1 * rhs1.adjoint() * rhs1).eval().template triangularView<Upper>().toDenseMatrix());\n  VERIFY_IS_APPROX((m2.template triangularView<Upper>() = s1 * rhs1.adjoint() * rhs11).nestedExpression(),\n                   (s1 * rhs1.adjoint() * rhs11).eval().template triangularView<Upper>().toDenseMatrix());\n\n  \n  m2.setZero();\n  VERIFY_IS_APPROX(m2.template selfadjointView<Lower>().rankUpdate(rhs3.adjoint(),s1)._expression(),\n                   (s1 * rhs3.adjoint() * rhs3).eval().template triangularView<Lower>().toDenseMatrix());\n\n  m2.setZero();\n  VERIFY_IS_APPROX(m2.template selfadjointView<Upper>().rankUpdate(rhs3.adjoint(),s1)._expression(),\n                   (s1 * rhs3.adjoint() * rhs3).eval().template triangularView<Upper>().toDenseMatrix());\n                   \n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template selfadjointView<Lower>().rankUpdate(m1.col(c),s1)._expression()),\n                   ((s1 * m1.col(c) * m1.col(c).adjoint()).eval().template triangularView<Lower>().toDenseMatrix()));\n                   \n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template selfadjointView<Upper>().rankUpdate(m1.col(c),s1)._expression()),\n                   ((s1 * m1.col(c) * m1.col(c).adjoint()).eval().template triangularView<Upper>().toDenseMatrix()));\n  rm2.setZero();\n  VERIFY_IS_APPROX((rm2.template selfadjointView<Upper>().rankUpdate(m1.col(c),s1)._expression()),\n                   ((s1 * m1.col(c) * m1.col(c).adjoint()).eval().template triangularView<Upper>().toDenseMatrix()));\n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template triangularView<Upper>() += s1 * m3.col(c) * m1.col(c).adjoint()).nestedExpression(),\n                   ((s1 * m3.col(c) * m1.col(c).adjoint()).eval().template triangularView<Upper>().toDenseMatrix()));\n  rm2.setZero();\n  VERIFY_IS_APPROX((rm2.template triangularView<Upper>() += s1 * m1.col(c) * m3.col(c).adjoint()).nestedExpression(),\n                   ((s1 * m1.col(c) * m3.col(c).adjoint()).eval().template triangularView<Upper>().toDenseMatrix()));\n  \n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template selfadjointView<Lower>().rankUpdate(m1.col(c).conjugate(),s1)._expression()),\n                   ((s1 * m1.col(c).conjugate() * m1.col(c).conjugate().adjoint()).eval().template triangularView<Lower>().toDenseMatrix()));\n                   \n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template selfadjointView<Upper>().rankUpdate(m1.col(c).conjugate(),s1)._expression()),\n                   ((s1 * m1.col(c).conjugate() * m1.col(c).conjugate().adjoint()).eval().template triangularView<Upper>().toDenseMatrix()));\n  \n  \n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template selfadjointView<Lower>().rankUpdate(m1.row(c),s1)._expression()),\n                   ((s1 * m1.row(c).transpose() * m1.row(c).transpose().adjoint()).eval().template triangularView<Lower>().toDenseMatrix()));\n  rm2.setZero();\n  VERIFY_IS_APPROX((rm2.template selfadjointView<Lower>().rankUpdate(m1.row(c),s1)._expression()),\n                   ((s1 * m1.row(c).transpose() * m1.row(c).transpose().adjoint()).eval().template triangularView<Lower>().toDenseMatrix()));\n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template triangularView<Lower>() += s1 * m3.row(c).transpose() * m1.row(c).transpose().adjoint()).nestedExpression(),\n                   ((s1 * m3.row(c).transpose() * m1.row(c).transpose().adjoint()).eval().template triangularView<Lower>().toDenseMatrix()));\n  rm2.setZero();\n  VERIFY_IS_APPROX((rm2.template triangularView<Lower>() += s1 * m3.row(c).transpose() * m1.row(c).transpose().adjoint()).nestedExpression(),\n                   ((s1 * m3.row(c).transpose() * m1.row(c).transpose().adjoint()).eval().template triangularView<Lower>().toDenseMatrix()));\n  \n  \n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template selfadjointView<Upper>().rankUpdate(m1.row(c).adjoint(),s1)._expression()),\n                   ((s1 * m1.row(c).adjoint() * m1.row(c).adjoint().adjoint()).eval().template triangularView<Upper>().toDenseMatrix()));\n\n  // destination with a non-default inner-stride\n  // see bug 1741\n  {\n    typedef Matrix<Scalar,Dynamic,Dynamic> MatrixX;\n    MatrixX buffer(2*rows,2*cols);\n    Map<MatrixType,0,Stride<Dynamic,2> > map1(buffer.data(),rows,cols,Stride<Dynamic,2>(2*rows,2));\n    buffer.setZero();\n    VERIFY_IS_APPROX((map1.template selfadjointView<Lower>().rankUpdate(rhs2,s1)._expression()),\n                      ((s1 * rhs2 * rhs2.adjoint()).eval().template triangularView<Lower>().toDenseMatrix()));\n  }\n}\n\nEIGEN_DECLARE_TEST(product_syrk)\n{\n  for(int i = 0; i < g_repeat ; i++)\n  {\n    int s;\n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE);\n    CALL_SUBTEST_1( syrk(MatrixXf(s, s)) );\n    CALL_SUBTEST_2( syrk(MatrixXd(s, s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n    \n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2);\n    CALL_SUBTEST_3( syrk(MatrixXcf(s, s)) );\n    CALL_SUBTEST_4( syrk(MatrixXcd(s, s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/product_trmm.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename T>\nint get_random_size()\n{\n  const int factor = NumTraits<T>::ReadCost;\n  const int max_test_size = EIGEN_TEST_MAX_SIZE>2*factor ? EIGEN_TEST_MAX_SIZE/factor : EIGEN_TEST_MAX_SIZE;\n  return internal::random<int>(1,max_test_size);\n}\n\ntemplate<typename Scalar, int Mode, int TriOrder, int OtherOrder, int ResOrder, int OtherCols>\nvoid trmm(int rows=get_random_size<Scalar>(),\n          int cols=get_random_size<Scalar>(),\n          int otherCols = OtherCols==Dynamic?get_random_size<Scalar>():OtherCols)\n{\n  typedef Matrix<Scalar,Dynamic,Dynamic,TriOrder> TriMatrix;\n  typedef Matrix<Scalar,Dynamic,OtherCols,OtherCols==1?ColMajor:OtherOrder> OnTheRight;\n  typedef Matrix<Scalar,OtherCols,Dynamic,OtherCols==1?RowMajor:OtherOrder> OnTheLeft;\n  \n  typedef Matrix<Scalar,Dynamic,OtherCols,OtherCols==1?ColMajor:ResOrder> ResXS;\n  typedef Matrix<Scalar,OtherCols,Dynamic,OtherCols==1?RowMajor:ResOrder> ResSX;\n\n  TriMatrix  mat(rows,cols), tri(rows,cols), triTr(cols,rows), s1tri(rows,cols), s1triTr(cols,rows);\n  \n  OnTheRight  ge_right(cols,otherCols);\n  OnTheLeft   ge_left(otherCols,rows);\n  ResSX       ge_sx, ge_sx_save;\n  ResXS       ge_xs, ge_xs_save;\n\n  Scalar s1 = internal::random<Scalar>(),\n         s2 = internal::random<Scalar>();\n\n  mat.setRandom();\n  tri = mat.template triangularView<Mode>();\n  triTr = mat.transpose().template triangularView<Mode>();\n  s1tri = (s1*mat).template triangularView<Mode>();\n  s1triTr = (s1*mat).transpose().template triangularView<Mode>();\n  ge_right.setRandom();\n  ge_left.setRandom();\n\n  VERIFY_IS_APPROX( ge_xs = mat.template triangularView<Mode>() * ge_right, tri * ge_right);\n  VERIFY_IS_APPROX( ge_sx = ge_left * mat.template triangularView<Mode>(), ge_left * tri);\n  \n  VERIFY_IS_APPROX( ge_xs.noalias() = mat.template triangularView<Mode>() * ge_right, tri * ge_right);\n  VERIFY_IS_APPROX( ge_sx.noalias() = ge_left * mat.template triangularView<Mode>(), ge_left * tri);\n\n  if((Mode&UnitDiag)==0)\n    VERIFY_IS_APPROX( ge_xs.noalias() = (s1*mat.adjoint()).template triangularView<Mode>() * (s2*ge_left.transpose()), s1*triTr.conjugate() * (s2*ge_left.transpose()));\n  \n  VERIFY_IS_APPROX( ge_xs.noalias() = (s1*mat.transpose()).template triangularView<Mode>() * (s2*ge_left.transpose()), s1triTr * (s2*ge_left.transpose()));\n  VERIFY_IS_APPROX( ge_sx.noalias() = (s2*ge_left) * (s1*mat).template triangularView<Mode>(), (s2*ge_left)*s1tri);\n\n  VERIFY_IS_APPROX( ge_sx.noalias() = ge_right.transpose() * mat.adjoint().template triangularView<Mode>(), ge_right.transpose() * triTr.conjugate());\n  VERIFY_IS_APPROX( ge_sx.noalias() = ge_right.adjoint() * mat.adjoint().template triangularView<Mode>(), ge_right.adjoint() * triTr.conjugate());\n  \n  ge_xs_save = ge_xs;\n  if((Mode&UnitDiag)==0)\n    VERIFY_IS_APPROX( (ge_xs_save + s1*triTr.conjugate() * (s2*ge_left.adjoint())).eval(), ge_xs.noalias() += (s1*mat.adjoint()).template triangularView<Mode>() * (s2*ge_left.adjoint()) );\n  ge_xs_save = ge_xs;\n  VERIFY_IS_APPROX( (ge_xs_save + s1triTr * (s2*ge_left.adjoint())).eval(), ge_xs.noalias() += (s1*mat.transpose()).template triangularView<Mode>() * (s2*ge_left.adjoint()) );\n  ge_sx.setRandom();\n  ge_sx_save = ge_sx;\n  if((Mode&UnitDiag)==0)\n    VERIFY_IS_APPROX( ge_sx_save - (ge_right.adjoint() * (-s1 * triTr).conjugate()).eval(), ge_sx.noalias() -= (ge_right.adjoint() * (-s1 * mat).adjoint().template triangularView<Mode>()).eval());\n  \n  if((Mode&UnitDiag)==0)\n    VERIFY_IS_APPROX( ge_xs = (s1*mat).adjoint().template triangularView<Mode>() * ge_left.adjoint(), numext::conj(s1) * triTr.conjugate() * ge_left.adjoint());\n  VERIFY_IS_APPROX( ge_xs = (s1*mat).transpose().template triangularView<Mode>() * ge_left.adjoint(), s1triTr * ge_left.adjoint());\n\n  // TODO check with sub-matrix expressions ?\n\n  // destination with a non-default inner-stride\n  // see bug 1741\n  {\n    VERIFY_IS_APPROX( ge_xs.noalias() = mat.template triangularView<Mode>() * ge_right, tri * ge_right);\n    typedef Matrix<Scalar,Dynamic,Dynamic> MatrixX;\n    MatrixX buffer(2*ge_xs.rows(),2*ge_xs.cols());\n    Map<ResXS,0,Stride<Dynamic,2> > map1(buffer.data(),ge_xs.rows(),ge_xs.cols(),Stride<Dynamic,2>(2*ge_xs.outerStride(),2));\n    buffer.setZero();\n    VERIFY_IS_APPROX( map1.noalias() = mat.template triangularView<Mode>() * ge_right, tri * ge_right);\n  }\n}\n\ntemplate<typename Scalar, int Mode, int TriOrder>\nvoid trmv(int rows=get_random_size<Scalar>(), int cols=get_random_size<Scalar>())\n{\n  trmm<Scalar,Mode,TriOrder,ColMajor,ColMajor,1>(rows,cols,1);\n}\n\ntemplate<typename Scalar, int Mode, int TriOrder, int OtherOrder, int ResOrder>\nvoid trmm(int rows=get_random_size<Scalar>(), int cols=get_random_size<Scalar>(), int otherCols = get_random_size<Scalar>())\n{\n  trmm<Scalar,Mode,TriOrder,OtherOrder,ResOrder,Dynamic>(rows,cols,otherCols);\n}\n\n#define CALL_ALL_ORDERS(NB,SCALAR,MODE)                                             \\\n  EIGEN_CAT(CALL_SUBTEST_,NB)((trmm<SCALAR, MODE, ColMajor,ColMajor,ColMajor>()));  \\\n  EIGEN_CAT(CALL_SUBTEST_,NB)((trmm<SCALAR, MODE, ColMajor,ColMajor,RowMajor>()));  \\\n  EIGEN_CAT(CALL_SUBTEST_,NB)((trmm<SCALAR, MODE, ColMajor,RowMajor,ColMajor>()));  \\\n  EIGEN_CAT(CALL_SUBTEST_,NB)((trmm<SCALAR, MODE, ColMajor,RowMajor,RowMajor>()));  \\\n  EIGEN_CAT(CALL_SUBTEST_,NB)((trmm<SCALAR, MODE, RowMajor,ColMajor,ColMajor>()));  \\\n  EIGEN_CAT(CALL_SUBTEST_,NB)((trmm<SCALAR, MODE, RowMajor,ColMajor,RowMajor>()));  \\\n  EIGEN_CAT(CALL_SUBTEST_,NB)((trmm<SCALAR, MODE, RowMajor,RowMajor,ColMajor>()));  \\\n  EIGEN_CAT(CALL_SUBTEST_,NB)((trmm<SCALAR, MODE, RowMajor,RowMajor,RowMajor>()));  \\\n  \\\n  EIGEN_CAT(CALL_SUBTEST_1,NB)((trmv<SCALAR, MODE, ColMajor>()));                   \\\n  EIGEN_CAT(CALL_SUBTEST_1,NB)((trmv<SCALAR, MODE, RowMajor>()));\n\n  \n#define CALL_ALL(NB,SCALAR)                 \\\n  CALL_ALL_ORDERS(EIGEN_CAT(1,NB),SCALAR,Upper)          \\\n  CALL_ALL_ORDERS(EIGEN_CAT(2,NB),SCALAR,UnitUpper)      \\\n  CALL_ALL_ORDERS(EIGEN_CAT(3,NB),SCALAR,StrictlyUpper)  \\\n  CALL_ALL_ORDERS(EIGEN_CAT(1,NB),SCALAR,Lower)          \\\n  CALL_ALL_ORDERS(EIGEN_CAT(2,NB),SCALAR,UnitLower)      \\\n  CALL_ALL_ORDERS(EIGEN_CAT(3,NB),SCALAR,StrictlyLower)\n  \n\nEIGEN_DECLARE_TEST(product_trmm)\n{\n  for(int i = 0; i < g_repeat ; i++)\n  {\n    CALL_ALL(1,float);                //  EIGEN_SUFFIXES;11;111;21;121;31;131\n    CALL_ALL(2,double);               //  EIGEN_SUFFIXES;12;112;22;122;32;132\n    CALL_ALL(3,std::complex<float>);  //  EIGEN_SUFFIXES;13;113;23;123;33;133\n    CALL_ALL(4,std::complex<double>); //  EIGEN_SUFFIXES;14;114;24;124;34;134\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/product_trmv.cpp",
    "content": "// This file is triangularView of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void trmv(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n\n  RealScalar largerEps = 10*test_precision<RealScalar>();\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m3(rows, cols);\n  VectorType v1 = VectorType::Random(rows);\n\n  Scalar s1 = internal::random<Scalar>();\n\n  m1 = MatrixType::Random(rows, cols);\n\n  // check with a column-major matrix\n  m3 = m1.template triangularView<Eigen::Lower>();\n  VERIFY((m3 * v1).isApprox(m1.template triangularView<Eigen::Lower>() * v1, largerEps));\n  m3 = m1.template triangularView<Eigen::Upper>();\n  VERIFY((m3 * v1).isApprox(m1.template triangularView<Eigen::Upper>() * v1, largerEps));\n  m3 = m1.template triangularView<Eigen::UnitLower>();\n  VERIFY((m3 * v1).isApprox(m1.template triangularView<Eigen::UnitLower>() * v1, largerEps));\n  m3 = m1.template triangularView<Eigen::UnitUpper>();\n  VERIFY((m3 * v1).isApprox(m1.template triangularView<Eigen::UnitUpper>() * v1, largerEps));\n\n  // check conjugated and scalar multiple expressions (col-major)\n  m3 = m1.template triangularView<Eigen::Lower>();\n  VERIFY(((s1*m3).conjugate() * v1).isApprox((s1*m1).conjugate().template triangularView<Eigen::Lower>() * v1, largerEps));\n  m3 = m1.template triangularView<Eigen::Upper>();\n  VERIFY((m3.conjugate() * v1.conjugate()).isApprox(m1.conjugate().template triangularView<Eigen::Upper>() * v1.conjugate(), largerEps));\n\n  // check with a row-major matrix\n  m3 = m1.template triangularView<Eigen::Upper>();\n  VERIFY((m3.transpose() * v1).isApprox(m1.transpose().template triangularView<Eigen::Lower>() * v1, largerEps));\n  m3 = m1.template triangularView<Eigen::Lower>();\n  VERIFY((m3.transpose() * v1).isApprox(m1.transpose().template triangularView<Eigen::Upper>() * v1, largerEps));\n  m3 = m1.template triangularView<Eigen::UnitUpper>();\n  VERIFY((m3.transpose() * v1).isApprox(m1.transpose().template triangularView<Eigen::UnitLower>() * v1, largerEps));\n  m3 = m1.template triangularView<Eigen::UnitLower>();\n  VERIFY((m3.transpose() * v1).isApprox(m1.transpose().template triangularView<Eigen::UnitUpper>() * v1, largerEps));\n\n  // check conjugated and scalar multiple expressions (row-major)\n  m3 = m1.template triangularView<Eigen::Upper>();\n  VERIFY((m3.adjoint() * v1).isApprox(m1.adjoint().template triangularView<Eigen::Lower>() * v1, largerEps));\n  m3 = m1.template triangularView<Eigen::Lower>();\n  VERIFY((m3.adjoint() * (s1*v1.conjugate())).isApprox(m1.adjoint().template triangularView<Eigen::Upper>() * (s1*v1.conjugate()), largerEps));\n  m3 = m1.template triangularView<Eigen::UnitUpper>();\n\n  // check transposed cases:\n  m3 = m1.template triangularView<Eigen::Lower>();\n  VERIFY((v1.transpose() * m3).isApprox(v1.transpose() * m1.template triangularView<Eigen::Lower>(), largerEps));\n  VERIFY((v1.adjoint() * m3).isApprox(v1.adjoint() * m1.template triangularView<Eigen::Lower>(), largerEps));\n  VERIFY((v1.adjoint() * m3.adjoint()).isApprox(v1.adjoint() * m1.template triangularView<Eigen::Lower>().adjoint(), largerEps));\n\n  // TODO check with sub-matrices\n}\n\nEIGEN_DECLARE_TEST(product_trmv)\n{\n  int s = 0;\n  for(int i = 0; i < g_repeat ; i++) {\n    CALL_SUBTEST_1( trmv(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( trmv(Matrix<float, 2, 2>()) );\n    CALL_SUBTEST_3( trmv(Matrix3d()) );\n    \n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2);\n    CALL_SUBTEST_4( trmv(MatrixXcf(s,s)) );\n    CALL_SUBTEST_5( trmv(MatrixXcd(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n    \n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE);\n    CALL_SUBTEST_6( trmv(Matrix<float,Dynamic,Dynamic,RowMajor>(s, s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/product_trsolve.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#define VERIFY_TRSM(TRI,XB) { \\\n    (XB).setRandom(); ref = (XB); \\\n    (TRI).solveInPlace(XB); \\\n    VERIFY_IS_APPROX((TRI).toDenseMatrix() * (XB), ref); \\\n    (XB).setRandom(); ref = (XB); \\\n    (XB) = (TRI).solve(XB); \\\n    VERIFY_IS_APPROX((TRI).toDenseMatrix() * (XB), ref); \\\n  }\n\n#define VERIFY_TRSM_ONTHERIGHT(TRI,XB) { \\\n    (XB).setRandom(); ref = (XB); \\\n    (TRI).transpose().template solveInPlace<OnTheRight>(XB.transpose()); \\\n    VERIFY_IS_APPROX((XB).transpose() * (TRI).transpose().toDenseMatrix(), ref.transpose()); \\\n    (XB).setRandom(); ref = (XB); \\\n    (XB).transpose() = (TRI).transpose().template solve<OnTheRight>(XB.transpose()); \\\n    VERIFY_IS_APPROX((XB).transpose() * (TRI).transpose().toDenseMatrix(), ref.transpose()); \\\n  }\n\ntemplate<typename Scalar,int Size, int Cols> void trsolve(int size=Size,int cols=Cols)\n{\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  Matrix<Scalar,Size,Size,ColMajor> cmLhs(size,size);\n  Matrix<Scalar,Size,Size,RowMajor> rmLhs(size,size);\n\n  enum {  colmajor = Size==1 ? RowMajor : ColMajor,\n          rowmajor = Cols==1 ? ColMajor : RowMajor };\n  Matrix<Scalar,Size,Cols,colmajor> cmRhs(size,cols);\n  Matrix<Scalar,Size,Cols,rowmajor> rmRhs(size,cols);\n  Matrix<Scalar,Dynamic,Dynamic,colmajor> ref(size,cols);\n\n  cmLhs.setRandom(); cmLhs *= static_cast<RealScalar>(0.1); cmLhs.diagonal().array() += static_cast<RealScalar>(1);\n  rmLhs.setRandom(); rmLhs *= static_cast<RealScalar>(0.1); rmLhs.diagonal().array() += static_cast<RealScalar>(1);\n\n  VERIFY_TRSM(cmLhs.conjugate().template triangularView<Lower>(), cmRhs);\n  VERIFY_TRSM(cmLhs.adjoint()  .template triangularView<Lower>(), cmRhs);\n  VERIFY_TRSM(cmLhs            .template triangularView<Upper>(), cmRhs);\n  VERIFY_TRSM(cmLhs            .template triangularView<Lower>(), rmRhs);\n  VERIFY_TRSM(cmLhs.conjugate().template triangularView<Upper>(), rmRhs);\n  VERIFY_TRSM(cmLhs.adjoint()  .template triangularView<Upper>(), rmRhs);\n\n  VERIFY_TRSM(cmLhs.conjugate().template triangularView<UnitLower>(), cmRhs);\n  VERIFY_TRSM(cmLhs            .template triangularView<UnitUpper>(), rmRhs);\n\n  VERIFY_TRSM(rmLhs            .template triangularView<Lower>(), cmRhs);\n  VERIFY_TRSM(rmLhs.conjugate().template triangularView<UnitUpper>(), rmRhs);\n\n\n  VERIFY_TRSM_ONTHERIGHT(cmLhs.conjugate().template triangularView<Lower>(), cmRhs);\n  VERIFY_TRSM_ONTHERIGHT(cmLhs            .template triangularView<Upper>(), cmRhs);\n  VERIFY_TRSM_ONTHERIGHT(cmLhs            .template triangularView<Lower>(), rmRhs);\n  VERIFY_TRSM_ONTHERIGHT(cmLhs.conjugate().template triangularView<Upper>(), rmRhs);\n\n  VERIFY_TRSM_ONTHERIGHT(cmLhs.conjugate().template triangularView<UnitLower>(), cmRhs);\n  VERIFY_TRSM_ONTHERIGHT(cmLhs            .template triangularView<UnitUpper>(), rmRhs);\n\n  VERIFY_TRSM_ONTHERIGHT(rmLhs            .template triangularView<Lower>(), cmRhs);\n  VERIFY_TRSM_ONTHERIGHT(rmLhs.conjugate().template triangularView<UnitUpper>(), rmRhs);\n\n  int c = internal::random<int>(0,cols-1);\n  VERIFY_TRSM(rmLhs.template triangularView<Lower>(), rmRhs.col(c));\n  VERIFY_TRSM(cmLhs.template triangularView<Lower>(), rmRhs.col(c));\n\n  // destination with a non-default inner-stride\n  // see bug 1741\n  {\n    typedef Matrix<Scalar,Dynamic,Dynamic> MatrixX;\n    MatrixX buffer(2*cmRhs.rows(),2*cmRhs.cols());\n    Map<Matrix<Scalar,Size,Cols,colmajor>,0,Stride<Dynamic,2> > map1(buffer.data(),cmRhs.rows(),cmRhs.cols(),Stride<Dynamic,2>(2*cmRhs.outerStride(),2));\n    Map<Matrix<Scalar,Size,Cols,rowmajor>,0,Stride<Dynamic,2> > map2(buffer.data(),rmRhs.rows(),rmRhs.cols(),Stride<Dynamic,2>(2*rmRhs.outerStride(),2));\n    buffer.setZero();\n    VERIFY_TRSM(cmLhs.conjugate().template triangularView<Lower>(), map1);\n    buffer.setZero();\n    VERIFY_TRSM(cmLhs            .template triangularView<Lower>(), map2);\n  }\n\n  if(Size==Dynamic)\n  {\n    cmLhs.resize(0,0);\n    cmRhs.resize(0,cmRhs.cols());\n    Matrix<Scalar,Size,Cols,colmajor> res = cmLhs.template triangularView<Lower>().solve(cmRhs);\n    VERIFY_IS_EQUAL(res.rows(),0);\n    VERIFY_IS_EQUAL(res.cols(),cmRhs.cols());\n    res = cmRhs;\n    cmLhs.template triangularView<Lower>().solveInPlace(res);\n    VERIFY_IS_EQUAL(res.rows(),0);\n    VERIFY_IS_EQUAL(res.cols(),cmRhs.cols());\n  }\n}\n\nEIGEN_DECLARE_TEST(product_trsolve)\n{\n  for(int i = 0; i < g_repeat ; i++)\n  {\n    // matrices\n    CALL_SUBTEST_1((trsolve<float,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE),internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_2((trsolve<double,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE),internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_3((trsolve<std::complex<float>,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2),internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))));\n    CALL_SUBTEST_4((trsolve<std::complex<double>,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2),internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))));\n\n    // vectors\n    CALL_SUBTEST_5((trsolve<float,Dynamic,1>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_6((trsolve<double,Dynamic,1>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_7((trsolve<std::complex<float>,Dynamic,1>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_8((trsolve<std::complex<double>,Dynamic,1>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    \n    // meta-unrollers\n    CALL_SUBTEST_9((trsolve<float,4,1>()));\n    CALL_SUBTEST_10((trsolve<double,4,1>()));\n    CALL_SUBTEST_11((trsolve<std::complex<float>,4,1>()));\n    CALL_SUBTEST_12((trsolve<float,1,1>()));\n    CALL_SUBTEST_13((trsolve<float,1,2>()));\n    CALL_SUBTEST_14((trsolve<float,3,1>()));\n    \n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/qr.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/QR>\n#include \"solverbase.h\"\n\ntemplate<typename MatrixType> void qr(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> MatrixQType;\n\n  MatrixType a = MatrixType::Random(rows,cols);\n  HouseholderQR<MatrixType> qrOfA(a);\n\n  MatrixQType q = qrOfA.householderQ();\n  VERIFY_IS_UNITARY(q);\n\n  MatrixType r = qrOfA.matrixQR().template triangularView<Upper>();\n  VERIFY_IS_APPROX(a, qrOfA.householderQ() * r);\n}\n\ntemplate<typename MatrixType, int Cols2> void qr_fixedsize()\n{\n  enum { Rows = MatrixType::RowsAtCompileTime, Cols = MatrixType::ColsAtCompileTime };\n  typedef typename MatrixType::Scalar Scalar;\n  Matrix<Scalar,Rows,Cols> m1 = Matrix<Scalar,Rows,Cols>::Random();\n  HouseholderQR<Matrix<Scalar,Rows,Cols> > qr(m1);\n\n  Matrix<Scalar,Rows,Cols> r = qr.matrixQR();\n  // FIXME need better way to construct trapezoid\n  for(int i = 0; i < Rows; i++) for(int j = 0; j < Cols; j++) if(i>j) r(i,j) = Scalar(0);\n\n  VERIFY_IS_APPROX(m1, qr.householderQ() * r);\n\n  check_solverbase<Matrix<Scalar,Cols,Cols2>, Matrix<Scalar,Rows,Cols2> >(m1, qr, Rows, Cols, Cols2);\n}\n\ntemplate<typename MatrixType> void qr_invertible()\n{\n  using std::log;\n  using std::abs;\n  using std::pow;\n  using std::max;\n  typedef typename NumTraits<typename MatrixType::Scalar>::Real RealScalar;\n  typedef typename MatrixType::Scalar Scalar;\n\n  STATIC_CHECK(( internal::is_same<typename HouseholderQR<MatrixType>::StorageIndex,int>::value ));\n\n  int size = internal::random<int>(10,50);\n\n  MatrixType m1(size, size), m2(size, size), m3(size, size);\n  m1 = MatrixType::Random(size,size);\n\n  if (internal::is_same<RealScalar,float>::value)\n  {\n    // let's build a matrix more stable to inverse\n    MatrixType a = MatrixType::Random(size,size*4);\n    m1 += a * a.adjoint();\n  }\n\n  HouseholderQR<MatrixType> qr(m1);\n\n  check_solverbase<MatrixType, MatrixType>(m1, qr, size, size, size);\n\n  // now construct a matrix with prescribed determinant\n  m1.setZero();\n  for(int i = 0; i < size; i++) m1(i,i) = internal::random<Scalar>();\n  RealScalar absdet = abs(m1.diagonal().prod());\n  m3 = qr.householderQ(); // get a unitary\n  m1 = m3 * m1 * m3;\n  qr.compute(m1);\n  VERIFY_IS_APPROX(log(absdet), qr.logAbsDeterminant());\n  // This test is tricky if the determinant becomes too small.\n  // Since we generate random numbers with magnitude range [0,1], the average determinant is 0.5^size\n  VERIFY_IS_MUCH_SMALLER_THAN( abs(absdet-qr.absDeterminant()), numext::maxi(RealScalar(pow(0.5,size)),numext::maxi<RealScalar>(abs(absdet),abs(qr.absDeterminant()))) );\n  \n}\n\ntemplate<typename MatrixType> void qr_verify_assert()\n{\n  MatrixType tmp;\n\n  HouseholderQR<MatrixType> qr;\n  VERIFY_RAISES_ASSERT(qr.matrixQR())\n  VERIFY_RAISES_ASSERT(qr.solve(tmp))\n  VERIFY_RAISES_ASSERT(qr.transpose().solve(tmp))\n  VERIFY_RAISES_ASSERT(qr.adjoint().solve(tmp))\n  VERIFY_RAISES_ASSERT(qr.householderQ())\n  VERIFY_RAISES_ASSERT(qr.absDeterminant())\n  VERIFY_RAISES_ASSERT(qr.logAbsDeterminant())\n}\n\nEIGEN_DECLARE_TEST(qr)\n{\n  for(int i = 0; i < g_repeat; i++) {\n   CALL_SUBTEST_1( qr(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE),internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n   CALL_SUBTEST_2( qr(MatrixXcd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2),internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))) );\n   CALL_SUBTEST_3(( qr_fixedsize<Matrix<float,3,4>, 2 >() ));\n   CALL_SUBTEST_4(( qr_fixedsize<Matrix<double,6,2>, 4 >() ));\n   CALL_SUBTEST_5(( qr_fixedsize<Matrix<double,2,5>, 7 >() ));\n   CALL_SUBTEST_11( qr(Matrix<float,1,1>()) );\n  }\n\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( qr_invertible<MatrixXf>() );\n    CALL_SUBTEST_6( qr_invertible<MatrixXd>() );\n    CALL_SUBTEST_7( qr_invertible<MatrixXcf>() );\n    CALL_SUBTEST_8( qr_invertible<MatrixXcd>() );\n  }\n\n  CALL_SUBTEST_9(qr_verify_assert<Matrix3f>());\n  CALL_SUBTEST_10(qr_verify_assert<Matrix3d>());\n  CALL_SUBTEST_1(qr_verify_assert<MatrixXf>());\n  CALL_SUBTEST_6(qr_verify_assert<MatrixXd>());\n  CALL_SUBTEST_7(qr_verify_assert<MatrixXcf>());\n  CALL_SUBTEST_8(qr_verify_assert<MatrixXcd>());\n\n  // Test problem size constructors\n  CALL_SUBTEST_12(HouseholderQR<MatrixXf>(10, 20));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/qr_colpivoting.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/QR>\n#include <Eigen/SVD>\n#include \"solverbase.h\"\n\ntemplate <typename MatrixType>\nvoid cod() {\n  STATIC_CHECK(( internal::is_same<typename CompleteOrthogonalDecomposition<MatrixType>::StorageIndex,int>::value ));\n\n  Index rows = internal::random<Index>(2, EIGEN_TEST_MAX_SIZE);\n  Index cols = internal::random<Index>(2, EIGEN_TEST_MAX_SIZE);\n  Index cols2 = internal::random<Index>(2, EIGEN_TEST_MAX_SIZE);\n  Index rank = internal::random<Index>(1, (std::min)(rows, cols) - 1);\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime,\n                 MatrixType::RowsAtCompileTime>\n      MatrixQType;\n  MatrixType matrix;\n  createRandomPIMatrixOfRank(rank, rows, cols, matrix);\n  CompleteOrthogonalDecomposition<MatrixType> cod(matrix);\n  VERIFY(rank == cod.rank());\n  VERIFY(cols - cod.rank() == cod.dimensionOfKernel());\n  VERIFY(!cod.isInjective());\n  VERIFY(!cod.isInvertible());\n  VERIFY(!cod.isSurjective());\n\n  MatrixQType q = cod.householderQ();\n  VERIFY_IS_UNITARY(q);\n\n  MatrixType z = cod.matrixZ();\n  VERIFY_IS_UNITARY(z);\n\n  MatrixType t;\n  t.setZero(rows, cols);\n  t.topLeftCorner(rank, rank) =\n      cod.matrixT().topLeftCorner(rank, rank).template triangularView<Upper>();\n\n  MatrixType c = q * t * z * cod.colsPermutation().inverse();\n  VERIFY_IS_APPROX(matrix, c);\n\n  check_solverbase<MatrixType, MatrixType>(matrix, cod, rows, cols, cols2);\n\n  // Verify that we get the same minimum-norm solution as the SVD.\n  MatrixType exact_solution = MatrixType::Random(cols, cols2);\n  MatrixType rhs = matrix * exact_solution;\n  MatrixType cod_solution = cod.solve(rhs);\n  JacobiSVD<MatrixType> svd(matrix, ComputeThinU | ComputeThinV);\n  MatrixType svd_solution = svd.solve(rhs);\n  VERIFY_IS_APPROX(cod_solution, svd_solution);\n\n  MatrixType pinv = cod.pseudoInverse();\n  VERIFY_IS_APPROX(cod_solution, pinv * rhs);\n}\n\ntemplate <typename MatrixType, int Cols2>\nvoid cod_fixedsize() {\n  enum {\n    Rows = MatrixType::RowsAtCompileTime,\n    Cols = MatrixType::ColsAtCompileTime\n  };\n  typedef typename MatrixType::Scalar Scalar;\n  typedef CompleteOrthogonalDecomposition<Matrix<Scalar, Rows, Cols> > COD;\n  int rank = internal::random<int>(1, (std::min)(int(Rows), int(Cols)) - 1);\n  Matrix<Scalar, Rows, Cols> matrix;\n  createRandomPIMatrixOfRank(rank, Rows, Cols, matrix);\n  COD cod(matrix);\n  VERIFY(rank == cod.rank());\n  VERIFY(Cols - cod.rank() == cod.dimensionOfKernel());\n  VERIFY(cod.isInjective() == (rank == Rows));\n  VERIFY(cod.isSurjective() == (rank == Cols));\n  VERIFY(cod.isInvertible() == (cod.isInjective() && cod.isSurjective()));\n\n  check_solverbase<Matrix<Scalar, Cols, Cols2>, Matrix<Scalar, Rows, Cols2> >(matrix, cod, Rows, Cols, Cols2);\n\n  // Verify that we get the same minimum-norm solution as the SVD.\n  Matrix<Scalar, Cols, Cols2> exact_solution;\n  exact_solution.setRandom(Cols, Cols2);\n  Matrix<Scalar, Rows, Cols2> rhs = matrix * exact_solution;\n  Matrix<Scalar, Cols, Cols2> cod_solution = cod.solve(rhs);\n  JacobiSVD<MatrixType> svd(matrix, ComputeFullU | ComputeFullV);\n  Matrix<Scalar, Cols, Cols2> svd_solution = svd.solve(rhs);\n  VERIFY_IS_APPROX(cod_solution, svd_solution);\n\n  typename Inverse<COD>::PlainObject pinv = cod.pseudoInverse();\n  VERIFY_IS_APPROX(cod_solution, pinv * rhs);\n}\n\ntemplate<typename MatrixType> void qr()\n{\n  using std::sqrt;\n\n  STATIC_CHECK(( internal::is_same<typename ColPivHouseholderQR<MatrixType>::StorageIndex,int>::value ));\n\n  Index rows = internal::random<Index>(2,EIGEN_TEST_MAX_SIZE), cols = internal::random<Index>(2,EIGEN_TEST_MAX_SIZE), cols2 = internal::random<Index>(2,EIGEN_TEST_MAX_SIZE);\n  Index rank = internal::random<Index>(1, (std::min)(rows, cols)-1);\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> MatrixQType;\n  MatrixType m1;\n  createRandomPIMatrixOfRank(rank,rows,cols,m1);\n  ColPivHouseholderQR<MatrixType> qr(m1);\n  VERIFY_IS_EQUAL(rank, qr.rank());\n  VERIFY_IS_EQUAL(cols - qr.rank(), qr.dimensionOfKernel());\n  VERIFY(!qr.isInjective());\n  VERIFY(!qr.isInvertible());\n  VERIFY(!qr.isSurjective());\n\n  MatrixQType q = qr.householderQ();\n  VERIFY_IS_UNITARY(q);\n\n  MatrixType r = qr.matrixQR().template triangularView<Upper>();\n  MatrixType c = q * r * qr.colsPermutation().inverse();\n  VERIFY_IS_APPROX(m1, c);\n\n  // Verify that the absolute value of the diagonal elements in R are\n  // non-increasing until they reach the singularity threshold.\n  RealScalar threshold =\n      sqrt(RealScalar(rows)) * numext::abs(r(0, 0)) * NumTraits<Scalar>::epsilon();\n  for (Index i = 0; i < (std::min)(rows, cols) - 1; ++i) {\n    RealScalar x = numext::abs(r(i, i));\n    RealScalar y = numext::abs(r(i + 1, i + 1));\n    if (x < threshold && y < threshold) continue;\n    if (!test_isApproxOrLessThan(y, x)) {\n      for (Index j = 0; j < (std::min)(rows, cols); ++j) {\n        std::cout << \"i = \" << j << \", |r_ii| = \" << numext::abs(r(j, j)) << std::endl;\n      }\n      std::cout << \"Failure at i=\" << i << \", rank=\" << rank\n                << \", threshold=\" << threshold << std::endl;\n    }\n    VERIFY_IS_APPROX_OR_LESS_THAN(y, x);\n  }\n\n  check_solverbase<MatrixType, MatrixType>(m1, qr, rows, cols, cols2);\n\n  {\n    MatrixType m2, m3;\n    Index size = rows;\n    do {\n      m1 = MatrixType::Random(size,size);\n      qr.compute(m1);\n    } while(!qr.isInvertible());\n    MatrixType m1_inv = qr.inverse();\n    m3 = m1 * MatrixType::Random(size,cols2);\n    m2 = qr.solve(m3);\n    VERIFY_IS_APPROX(m2, m1_inv*m3);\n  }\n}\n\ntemplate<typename MatrixType, int Cols2> void qr_fixedsize()\n{\n  using std::sqrt;\n  using std::abs;\n  enum { Rows = MatrixType::RowsAtCompileTime, Cols = MatrixType::ColsAtCompileTime };\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  int rank = internal::random<int>(1, (std::min)(int(Rows), int(Cols))-1);\n  Matrix<Scalar,Rows,Cols> m1;\n  createRandomPIMatrixOfRank(rank,Rows,Cols,m1);\n  ColPivHouseholderQR<Matrix<Scalar,Rows,Cols> > qr(m1);\n  VERIFY_IS_EQUAL(rank, qr.rank());\n  VERIFY_IS_EQUAL(Cols - qr.rank(), qr.dimensionOfKernel());\n  VERIFY_IS_EQUAL(qr.isInjective(), (rank == Rows));\n  VERIFY_IS_EQUAL(qr.isSurjective(), (rank == Cols));\n  VERIFY_IS_EQUAL(qr.isInvertible(), (qr.isInjective() && qr.isSurjective()));\n\n  Matrix<Scalar,Rows,Cols> r = qr.matrixQR().template triangularView<Upper>();\n  Matrix<Scalar,Rows,Cols> c = qr.householderQ() * r * qr.colsPermutation().inverse();\n  VERIFY_IS_APPROX(m1, c);\n\n  check_solverbase<Matrix<Scalar,Cols,Cols2>, Matrix<Scalar,Rows,Cols2> >(m1, qr, Rows, Cols, Cols2);\n\n  // Verify that the absolute value of the diagonal elements in R are\n  // non-increasing until they reache the singularity threshold.\n  RealScalar threshold =\n      sqrt(RealScalar(Rows)) * (std::abs)(r(0, 0)) * NumTraits<Scalar>::epsilon();\n  for (Index i = 0; i < (std::min)(int(Rows), int(Cols)) - 1; ++i) {\n    RealScalar x = numext::abs(r(i, i));\n    RealScalar y = numext::abs(r(i + 1, i + 1));\n    if (x < threshold && y < threshold) continue;\n    if (!test_isApproxOrLessThan(y, x)) {\n      for (Index j = 0; j < (std::min)(int(Rows), int(Cols)); ++j) {\n        std::cout << \"i = \" << j << \", |r_ii| = \" << numext::abs(r(j, j)) << std::endl;\n      }\n      std::cout << \"Failure at i=\" << i << \", rank=\" << rank\n                << \", threshold=\" << threshold << std::endl;\n    }\n    VERIFY_IS_APPROX_OR_LESS_THAN(y, x);\n  }\n}\n\n// This test is meant to verify that pivots are chosen such that\n// even for a graded matrix, the diagonal of R falls of roughly\n// monotonically until it reaches the threshold for singularity.\n// We use the so-called Kahan matrix, which is a famous counter-example\n// for rank-revealing QR. See\n// http://www.netlib.org/lapack/lawnspdf/lawn176.pdf\n// page 3 for more detail.\ntemplate<typename MatrixType> void qr_kahan_matrix()\n{\n  using std::sqrt;\n  using std::abs;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n\n  Index rows = 300, cols = rows;\n\n  MatrixType m1;\n  m1.setZero(rows,cols);\n  RealScalar s = std::pow(NumTraits<RealScalar>::epsilon(), 1.0 / rows);\n  RealScalar c = std::sqrt(1 - s*s);\n  RealScalar pow_s_i(1.0); // pow(s,i)\n  for (Index i = 0; i < rows; ++i) {\n    m1(i, i) = pow_s_i;\n    m1.row(i).tail(rows - i - 1) = -pow_s_i * c * MatrixType::Ones(1, rows - i - 1);\n    pow_s_i *= s;\n  }\n  m1 = (m1 + m1.transpose()).eval();\n  ColPivHouseholderQR<MatrixType> qr(m1);\n  MatrixType r = qr.matrixQR().template triangularView<Upper>();\n\n  RealScalar threshold =\n      std::sqrt(RealScalar(rows)) * numext::abs(r(0, 0)) * NumTraits<Scalar>::epsilon();\n  for (Index i = 0; i < (std::min)(rows, cols) - 1; ++i) {\n    RealScalar x = numext::abs(r(i, i));\n    RealScalar y = numext::abs(r(i + 1, i + 1));\n    if (x < threshold && y < threshold) continue;\n    if (!test_isApproxOrLessThan(y, x)) {\n      for (Index j = 0; j < (std::min)(rows, cols); ++j) {\n        std::cout << \"i = \" << j << \", |r_ii| = \" << numext::abs(r(j, j)) << std::endl;\n      }\n      std::cout << \"Failure at i=\" << i << \", rank=\" << qr.rank()\n                << \", threshold=\" << threshold << std::endl;\n    }\n    VERIFY_IS_APPROX_OR_LESS_THAN(y, x);\n  }\n}\n\ntemplate<typename MatrixType> void qr_invertible()\n{\n  using std::log;\n  using std::abs;\n  typedef typename NumTraits<typename MatrixType::Scalar>::Real RealScalar;\n  typedef typename MatrixType::Scalar Scalar;\n\n  int size = internal::random<int>(10,50);\n\n  MatrixType m1(size, size), m2(size, size), m3(size, size);\n  m1 = MatrixType::Random(size,size);\n\n  if (internal::is_same<RealScalar,float>::value)\n  {\n    // let's build a matrix more stable to inverse\n    MatrixType a = MatrixType::Random(size,size*2);\n    m1 += a * a.adjoint();\n  }\n\n  ColPivHouseholderQR<MatrixType> qr(m1);\n\n  check_solverbase<MatrixType, MatrixType>(m1, qr, size, size, size);\n\n  // now construct a matrix with prescribed determinant\n  m1.setZero();\n  for(int i = 0; i < size; i++) m1(i,i) = internal::random<Scalar>();\n  RealScalar absdet = abs(m1.diagonal().prod());\n  m3 = qr.householderQ(); // get a unitary\n  m1 = m3 * m1 * m3;\n  qr.compute(m1);\n  VERIFY_IS_APPROX(absdet, qr.absDeterminant());\n  VERIFY_IS_APPROX(log(absdet), qr.logAbsDeterminant());\n}\n\ntemplate<typename MatrixType> void qr_verify_assert()\n{\n  MatrixType tmp;\n\n  ColPivHouseholderQR<MatrixType> qr;\n  VERIFY_RAISES_ASSERT(qr.matrixQR())\n  VERIFY_RAISES_ASSERT(qr.solve(tmp))\n  VERIFY_RAISES_ASSERT(qr.transpose().solve(tmp))\n  VERIFY_RAISES_ASSERT(qr.adjoint().solve(tmp))\n  VERIFY_RAISES_ASSERT(qr.householderQ())\n  VERIFY_RAISES_ASSERT(qr.dimensionOfKernel())\n  VERIFY_RAISES_ASSERT(qr.isInjective())\n  VERIFY_RAISES_ASSERT(qr.isSurjective())\n  VERIFY_RAISES_ASSERT(qr.isInvertible())\n  VERIFY_RAISES_ASSERT(qr.inverse())\n  VERIFY_RAISES_ASSERT(qr.absDeterminant())\n  VERIFY_RAISES_ASSERT(qr.logAbsDeterminant())\n}\n\ntemplate<typename MatrixType> void cod_verify_assert()\n{\n  MatrixType tmp;\n\n  CompleteOrthogonalDecomposition<MatrixType> cod;\n  VERIFY_RAISES_ASSERT(cod.matrixQTZ())\n  VERIFY_RAISES_ASSERT(cod.solve(tmp))\n  VERIFY_RAISES_ASSERT(cod.transpose().solve(tmp))\n  VERIFY_RAISES_ASSERT(cod.adjoint().solve(tmp))\n  VERIFY_RAISES_ASSERT(cod.householderQ())\n  VERIFY_RAISES_ASSERT(cod.dimensionOfKernel())\n  VERIFY_RAISES_ASSERT(cod.isInjective())\n  VERIFY_RAISES_ASSERT(cod.isSurjective())\n  VERIFY_RAISES_ASSERT(cod.isInvertible())\n  VERIFY_RAISES_ASSERT(cod.pseudoInverse())\n  VERIFY_RAISES_ASSERT(cod.absDeterminant())\n  VERIFY_RAISES_ASSERT(cod.logAbsDeterminant())\n}\n\nEIGEN_DECLARE_TEST(qr_colpivoting)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( qr<MatrixXf>() );\n    CALL_SUBTEST_2( qr<MatrixXd>() );\n    CALL_SUBTEST_3( qr<MatrixXcd>() );\n    CALL_SUBTEST_4(( qr_fixedsize<Matrix<float,3,5>, 4 >() ));\n    CALL_SUBTEST_5(( qr_fixedsize<Matrix<double,6,2>, 3 >() ));\n    CALL_SUBTEST_5(( qr_fixedsize<Matrix<double,1,1>, 1 >() ));\n  }\n\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( cod<MatrixXf>() );\n    CALL_SUBTEST_2( cod<MatrixXd>() );\n    CALL_SUBTEST_3( cod<MatrixXcd>() );\n    CALL_SUBTEST_4(( cod_fixedsize<Matrix<float,3,5>, 4 >() ));\n    CALL_SUBTEST_5(( cod_fixedsize<Matrix<double,6,2>, 3 >() ));\n    CALL_SUBTEST_5(( cod_fixedsize<Matrix<double,1,1>, 1 >() ));\n  }\n\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( qr_invertible<MatrixXf>() );\n    CALL_SUBTEST_2( qr_invertible<MatrixXd>() );\n    CALL_SUBTEST_6( qr_invertible<MatrixXcf>() );\n    CALL_SUBTEST_3( qr_invertible<MatrixXcd>() );\n  }\n\n  CALL_SUBTEST_7(qr_verify_assert<Matrix3f>());\n  CALL_SUBTEST_8(qr_verify_assert<Matrix3d>());\n  CALL_SUBTEST_1(qr_verify_assert<MatrixXf>());\n  CALL_SUBTEST_2(qr_verify_assert<MatrixXd>());\n  CALL_SUBTEST_6(qr_verify_assert<MatrixXcf>());\n  CALL_SUBTEST_3(qr_verify_assert<MatrixXcd>());\n\n  CALL_SUBTEST_7(cod_verify_assert<Matrix3f>());\n  CALL_SUBTEST_8(cod_verify_assert<Matrix3d>());\n  CALL_SUBTEST_1(cod_verify_assert<MatrixXf>());\n  CALL_SUBTEST_2(cod_verify_assert<MatrixXd>());\n  CALL_SUBTEST_6(cod_verify_assert<MatrixXcf>());\n  CALL_SUBTEST_3(cod_verify_assert<MatrixXcd>());\n\n  // Test problem size constructors\n  CALL_SUBTEST_9(ColPivHouseholderQR<MatrixXf>(10, 20));\n\n  CALL_SUBTEST_1( qr_kahan_matrix<MatrixXf>() );\n  CALL_SUBTEST_2( qr_kahan_matrix<MatrixXd>() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/qr_fullpivoting.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/QR>\n#include \"solverbase.h\"\n\ntemplate<typename MatrixType> void qr()\n{\n  STATIC_CHECK(( internal::is_same<typename FullPivHouseholderQR<MatrixType>::StorageIndex,int>::value ));\n\n  static const int Rows = MatrixType::RowsAtCompileTime, Cols = MatrixType::ColsAtCompileTime;\n  Index max_size = EIGEN_TEST_MAX_SIZE;\n  Index min_size = numext::maxi(1,EIGEN_TEST_MAX_SIZE/10);\n  Index rows  = Rows == Dynamic ? internal::random<Index>(min_size,max_size) : Rows,\n        cols  = Cols == Dynamic ? internal::random<Index>(min_size,max_size) : Cols,\n        cols2 = Cols == Dynamic ? internal::random<Index>(min_size,max_size) : Cols,\n        rank  = internal::random<Index>(1, (std::min)(rows, cols)-1);\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> MatrixQType;\n  MatrixType m1;\n  createRandomPIMatrixOfRank(rank,rows,cols,m1);\n  FullPivHouseholderQR<MatrixType> qr(m1);\n  VERIFY_IS_EQUAL(rank, qr.rank());\n  VERIFY_IS_EQUAL(cols - qr.rank(), qr.dimensionOfKernel());\n  VERIFY(!qr.isInjective());\n  VERIFY(!qr.isInvertible());\n  VERIFY(!qr.isSurjective());\n\n  MatrixType r = qr.matrixQR();\n  \n  MatrixQType q = qr.matrixQ();\n  VERIFY_IS_UNITARY(q);\n  \n  // FIXME need better way to construct trapezoid\n  for(int i = 0; i < rows; i++) for(int j = 0; j < cols; j++) if(i>j) r(i,j) = Scalar(0);\n\n  MatrixType c = qr.matrixQ() * r * qr.colsPermutation().inverse();\n\n  VERIFY_IS_APPROX(m1, c);\n  \n  // stress the ReturnByValue mechanism\n  MatrixType tmp;\n  VERIFY_IS_APPROX(tmp.noalias() = qr.matrixQ() * r, (qr.matrixQ() * r).eval());\n  \n  check_solverbase<MatrixType, MatrixType>(m1, qr, rows, cols, cols2);\n\n  {\n    MatrixType m2, m3;\n    Index size = rows;\n    do {\n      m1 = MatrixType::Random(size,size);\n      qr.compute(m1);\n    } while(!qr.isInvertible());\n    MatrixType m1_inv = qr.inverse();\n    m3 = m1 * MatrixType::Random(size,cols2);\n    m2 = qr.solve(m3);\n    VERIFY_IS_APPROX(m2, m1_inv*m3);\n  }\n}\n\ntemplate<typename MatrixType> void qr_invertible()\n{\n  using std::log;\n  using std::abs;\n  typedef typename NumTraits<typename MatrixType::Scalar>::Real RealScalar;\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index max_size = numext::mini(50,EIGEN_TEST_MAX_SIZE);\n  Index min_size = numext::maxi(1,EIGEN_TEST_MAX_SIZE/10);\n  Index size = internal::random<Index>(min_size,max_size);\n\n  MatrixType m1(size, size), m2(size, size), m3(size, size);\n  m1 = MatrixType::Random(size,size);\n\n  if (internal::is_same<RealScalar,float>::value)\n  {\n    // let's build a matrix more stable to inverse\n    MatrixType a = MatrixType::Random(size,size*2);\n    m1 += a * a.adjoint();\n  }\n\n  FullPivHouseholderQR<MatrixType> qr(m1);\n  VERIFY(qr.isInjective());\n  VERIFY(qr.isInvertible());\n  VERIFY(qr.isSurjective());\n\n  check_solverbase<MatrixType, MatrixType>(m1, qr, size, size, size);\n\n  // now construct a matrix with prescribed determinant\n  m1.setZero();\n  for(int i = 0; i < size; i++) m1(i,i) = internal::random<Scalar>();\n  RealScalar absdet = abs(m1.diagonal().prod());\n  m3 = qr.matrixQ(); // get a unitary\n  m1 = m3 * m1 * m3;\n  qr.compute(m1);\n  VERIFY_IS_APPROX(absdet, qr.absDeterminant());\n  VERIFY_IS_APPROX(log(absdet), qr.logAbsDeterminant());\n}\n\ntemplate<typename MatrixType> void qr_verify_assert()\n{\n  MatrixType tmp;\n\n  FullPivHouseholderQR<MatrixType> qr;\n  VERIFY_RAISES_ASSERT(qr.matrixQR())\n  VERIFY_RAISES_ASSERT(qr.solve(tmp))\n  VERIFY_RAISES_ASSERT(qr.transpose().solve(tmp))\n  VERIFY_RAISES_ASSERT(qr.adjoint().solve(tmp))\n  VERIFY_RAISES_ASSERT(qr.matrixQ())\n  VERIFY_RAISES_ASSERT(qr.dimensionOfKernel())\n  VERIFY_RAISES_ASSERT(qr.isInjective())\n  VERIFY_RAISES_ASSERT(qr.isSurjective())\n  VERIFY_RAISES_ASSERT(qr.isInvertible())\n  VERIFY_RAISES_ASSERT(qr.inverse())\n  VERIFY_RAISES_ASSERT(qr.absDeterminant())\n  VERIFY_RAISES_ASSERT(qr.logAbsDeterminant())\n}\n\nEIGEN_DECLARE_TEST(qr_fullpivoting)\n{\n  for(int i = 0; i < 1; i++) {\n    CALL_SUBTEST_5( qr<Matrix3f>() );\n    CALL_SUBTEST_6( qr<Matrix3d>() );\n    CALL_SUBTEST_8( qr<Matrix2f>() );\n    CALL_SUBTEST_1( qr<MatrixXf>() );\n    CALL_SUBTEST_2( qr<MatrixXd>() );\n    CALL_SUBTEST_3( qr<MatrixXcd>() );\n  }\n\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( qr_invertible<MatrixXf>() );\n    CALL_SUBTEST_2( qr_invertible<MatrixXd>() );\n    CALL_SUBTEST_4( qr_invertible<MatrixXcf>() );\n    CALL_SUBTEST_3( qr_invertible<MatrixXcd>() );\n  }\n\n  CALL_SUBTEST_5(qr_verify_assert<Matrix3f>());\n  CALL_SUBTEST_6(qr_verify_assert<Matrix3d>());\n  CALL_SUBTEST_1(qr_verify_assert<MatrixXf>());\n  CALL_SUBTEST_2(qr_verify_assert<MatrixXd>());\n  CALL_SUBTEST_4(qr_verify_assert<MatrixXcf>());\n  CALL_SUBTEST_3(qr_verify_assert<MatrixXcd>());\n\n  // Test problem size constructors\n  CALL_SUBTEST_7(FullPivHouseholderQR<MatrixXf>(10, 20));\n  CALL_SUBTEST_7((FullPivHouseholderQR<Matrix<float,10,20> >(10,20)));\n  CALL_SUBTEST_7((FullPivHouseholderQR<Matrix<float,10,20> >(Matrix<float,10,20>::Random())));\n  CALL_SUBTEST_7((FullPivHouseholderQR<Matrix<float,20,10> >(20,10)));\n  CALL_SUBTEST_7((FullPivHouseholderQR<Matrix<float,20,10> >(Matrix<float,20,10>::Random())));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/qtvector.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_WORK_AROUND_QT_BUG_CALLING_WRONG_OPERATOR_NEW_FIXED_IN_QT_4_5\n\n#include \"main.h\"\n#include <QtCore/QVector>\n#include <Eigen/Geometry>\n#include <Eigen/QtAlignedMalloc>\n\ntemplate<typename MatrixType>\nvoid check_qtvector_matrix(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n  MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols);\n  QVector<MatrixType> v(10, MatrixType(rows,cols)), w(20, y);\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], y);\n  }\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.fill(y,22);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n  VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(MatrixType));\n\n  // do a lot of push_back such that the vector gets internally resized\n  // (with memory reallocation)\n  MatrixType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(int i=23; i<v.size(); ++i)\n  {\n    VERIFY(v[i]==w[(i-23)%w.size()]);\n  }\n}\n\ntemplate<typename TransformType>\nvoid check_qtvector_transform(const TransformType&)\n{\n  typedef typename TransformType::MatrixType MatrixType;\n  TransformType x(MatrixType::Random()), y(MatrixType::Random());\n  QVector<TransformType> v(10), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.fill(y,22);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n  VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(TransformType));\n\n  // do a lot of push_back such that the vector gets internally resized\n  // (with memory reallocation)\n  TransformType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; int(i)<v.size(); ++i)\n  {\n    VERIFY(v[i].matrix()==w[(i-23)%w.size()].matrix());\n  }\n}\n\ntemplate<typename QuaternionType>\nvoid check_qtvector_quaternion(const QuaternionType&)\n{\n  typedef typename QuaternionType::Coefficients Coefficients;\n  QuaternionType x(Coefficients::Random()), y(Coefficients::Random());\n  QVector<QuaternionType> v(10), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.fill(y,22);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n  VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(QuaternionType));\n\n  // do a lot of push_back such that the vector gets internally resized\n  // (with memory reallocation)\n  QuaternionType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; int(i)<v.size(); ++i)\n  {\n    VERIFY(v[i].coeffs()==w[(i-23)%w.size()].coeffs());\n  }\n}\n\nEIGEN_DECLARE_TEST(qtvector)\n{\n  // some non vectorizable fixed sizes\n  CALL_SUBTEST(check_qtvector_matrix(Vector2f()));\n  CALL_SUBTEST(check_qtvector_matrix(Matrix3f()));\n  CALL_SUBTEST(check_qtvector_matrix(Matrix3d()));\n\n  // some vectorizable fixed sizes\n  CALL_SUBTEST(check_qtvector_matrix(Matrix2f()));\n  CALL_SUBTEST(check_qtvector_matrix(Vector4f()));\n  CALL_SUBTEST(check_qtvector_matrix(Matrix4f()));\n  CALL_SUBTEST(check_qtvector_matrix(Matrix4d()));\n\n  // some dynamic sizes\n  CALL_SUBTEST(check_qtvector_matrix(MatrixXd(1,1)));\n  CALL_SUBTEST(check_qtvector_matrix(VectorXd(20)));\n  CALL_SUBTEST(check_qtvector_matrix(RowVectorXf(20)));\n  CALL_SUBTEST(check_qtvector_matrix(MatrixXcf(10,10)));\n\n  // some Transform\n  CALL_SUBTEST(check_qtvector_transform(Affine2f()));\n  CALL_SUBTEST(check_qtvector_transform(Affine3f()));\n  CALL_SUBTEST(check_qtvector_transform(Affine3d()));\n  //CALL_SUBTEST(check_qtvector_transform(Transform4d()));\n\n  // some Quaternion\n  CALL_SUBTEST(check_qtvector_quaternion(Quaternionf()));\n  CALL_SUBTEST(check_qtvector_quaternion(Quaternionf()));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/rand.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntypedef long long int64;\n\ntemplate<typename Scalar> Scalar check_in_range(Scalar x, Scalar y)\n{\n  Scalar r = internal::random<Scalar>(x,y);\n  VERIFY(r>=x);\n  if(y>=x)\n  {\n    VERIFY(r<=y);\n  }\n  return r;\n}\n\ntemplate<typename Scalar> void check_all_in_range(Scalar x, Scalar y)\n{\n  Array<int,1,Dynamic> mask(y-x+1);\n  mask.fill(0);\n  long n = (y-x+1)*32;\n  for(long k=0; k<n; ++k)\n  {\n    mask( check_in_range(x,y)-x )++;\n  }\n  for(Index i=0; i<mask.size(); ++i)\n    if(mask(i)==0)\n      std::cout << \"WARNING: value \" << x+i << \" not reached.\" << std::endl;\n  VERIFY( (mask>0).all() );\n}\n\ntemplate<typename Scalar> void check_histogram(Scalar x, Scalar y, int bins)\n{\n  Array<int,1,Dynamic> hist(bins);\n  hist.fill(0);\n  int f = 100000;\n  int n = bins*f;\n  int64 range = int64(y)-int64(x);\n  int divisor = int((range+1)/bins);\n  assert(((range+1)%bins)==0);\n  for(int k=0; k<n; ++k)\n  {\n    Scalar r = check_in_range(x,y);\n    hist( int((int64(r)-int64(x))/divisor) )++;\n  }\n  VERIFY( (((hist.cast<double>()/double(f))-1.0).abs()<0.03).all() );\n}\n\nEIGEN_DECLARE_TEST(rand)\n{\n  long long_ref = NumTraits<long>::highest()/10;\n  signed char char_offset = (std::min)(g_repeat,64);\n  signed char short_offset = (std::min)(g_repeat,16000);\n\n  for(int i = 0; i < g_repeat*10000; i++) {\n    CALL_SUBTEST(check_in_range<float>(10,11));\n    CALL_SUBTEST(check_in_range<float>(1.24234523,1.24234523));\n    CALL_SUBTEST(check_in_range<float>(-1,1));\n    CALL_SUBTEST(check_in_range<float>(-1432.2352,-1432.2352));\n\n    CALL_SUBTEST(check_in_range<double>(10,11));\n    CALL_SUBTEST(check_in_range<double>(1.24234523,1.24234523));\n    CALL_SUBTEST(check_in_range<double>(-1,1));\n    CALL_SUBTEST(check_in_range<double>(-1432.2352,-1432.2352));\n\n    CALL_SUBTEST(check_in_range<int>(0,-1));\n    CALL_SUBTEST(check_in_range<short>(0,-1));\n    CALL_SUBTEST(check_in_range<long>(0,-1));\n    CALL_SUBTEST(check_in_range<int>(-673456,673456));\n    CALL_SUBTEST(check_in_range<int>(-RAND_MAX+10,RAND_MAX-10));\n    CALL_SUBTEST(check_in_range<short>(-24345,24345));\n    CALL_SUBTEST(check_in_range<long>(-long_ref,long_ref));\n  }\n\n  CALL_SUBTEST(check_all_in_range<signed char>(11,11));\n  CALL_SUBTEST(check_all_in_range<signed char>(11,11+char_offset));\n  CALL_SUBTEST(check_all_in_range<signed char>(-5,5));\n  CALL_SUBTEST(check_all_in_range<signed char>(-11-char_offset,-11));\n  CALL_SUBTEST(check_all_in_range<signed char>(-126,-126+char_offset));\n  CALL_SUBTEST(check_all_in_range<signed char>(126-char_offset,126));\n  CALL_SUBTEST(check_all_in_range<signed char>(-126,126));\n\n  CALL_SUBTEST(check_all_in_range<short>(11,11));\n  CALL_SUBTEST(check_all_in_range<short>(11,11+short_offset));\n  CALL_SUBTEST(check_all_in_range<short>(-5,5));\n  CALL_SUBTEST(check_all_in_range<short>(-11-short_offset,-11));\n  CALL_SUBTEST(check_all_in_range<short>(-24345,-24345+short_offset));\n  CALL_SUBTEST(check_all_in_range<short>(24345,24345+short_offset));\n\n  CALL_SUBTEST(check_all_in_range<int>(11,11));\n  CALL_SUBTEST(check_all_in_range<int>(11,11+g_repeat));\n  CALL_SUBTEST(check_all_in_range<int>(-5,5));\n  CALL_SUBTEST(check_all_in_range<int>(-11-g_repeat,-11));\n  CALL_SUBTEST(check_all_in_range<int>(-673456,-673456+g_repeat));\n  CALL_SUBTEST(check_all_in_range<int>(673456,673456+g_repeat));\n\n  CALL_SUBTEST(check_all_in_range<long>(11,11));\n  CALL_SUBTEST(check_all_in_range<long>(11,11+g_repeat));\n  CALL_SUBTEST(check_all_in_range<long>(-5,5));\n  CALL_SUBTEST(check_all_in_range<long>(-11-g_repeat,-11));\n  CALL_SUBTEST(check_all_in_range<long>(-long_ref,-long_ref+g_repeat));\n  CALL_SUBTEST(check_all_in_range<long>( long_ref, long_ref+g_repeat));\n\n  CALL_SUBTEST(check_histogram<int>(-5,5,11));\n  int bins = 100;\n  CALL_SUBTEST(check_histogram<int>(-3333,-3333+bins*(3333/bins)-1,bins));\n  bins = 1000;\n  CALL_SUBTEST(check_histogram<int>(-RAND_MAX+10,-RAND_MAX+10+bins*(RAND_MAX/bins)-1,bins));\n  CALL_SUBTEST(check_histogram<int>(-RAND_MAX+10,-int64(RAND_MAX)+10+bins*(2*int64(RAND_MAX)/bins)-1,bins));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/random_matrix.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2021 Kolja Brix <kolja.brix@rwth-aachen.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/SVD>\n\n\ntemplate<typename MatrixType>\nvoid check_generateRandomUnitaryMatrix(const Index dim)\n{\n    const MatrixType Q = generateRandomUnitaryMatrix<MatrixType>(dim);\n\n    // validate dimensions\n    VERIFY_IS_EQUAL(Q.rows(), dim);\n    VERIFY_IS_EQUAL(Q.cols(), dim);\n\n    VERIFY_IS_UNITARY(Q);\n}\n\ntemplate<typename VectorType, typename RealScalarType>\nvoid check_setupRandomSvs(const Index dim, const RealScalarType max)\n{\n    const VectorType v = setupRandomSvs<VectorType, RealScalarType>(dim, max);\n\n    // validate dimensions\n    VERIFY_IS_EQUAL(v.size(), dim);\n\n    // check entries\n    for(Index i = 0; i < v.size(); ++i)\n        VERIFY_GE(v(i), 0);\n    for(Index i = 0; i < v.size()-1; ++i)\n        VERIFY_GE(v(i), v(i+1));\n}\n\ntemplate<typename VectorType, typename RealScalarType>\nvoid check_setupRangeSvs(const Index dim, const RealScalarType min, const RealScalarType max)\n{\n    const VectorType v = setupRangeSvs<VectorType, RealScalarType>(dim, min, max);\n\n    // validate dimensions\n    VERIFY_IS_EQUAL(v.size(), dim);\n\n    // check entries\n    if(dim == 1) {\n        VERIFY_IS_APPROX(v(0), min);\n    } else {\n        VERIFY_IS_APPROX(v(0), max);\n        VERIFY_IS_APPROX(v(dim-1), min);\n    }\n    for(Index i = 0; i < v.size()-1; ++i)\n        VERIFY_GE(v(i), v(i+1));\n}\n\ntemplate<typename MatrixType, typename RealScalar, typename RealVectorType>\nvoid check_generateRandomMatrixSvs(const Index rows, const Index cols, const Index diag_size,\n                                   const RealScalar min_svs, const RealScalar max_svs)\n{\n    RealVectorType svs = setupRangeSvs<RealVectorType, RealScalar>(diag_size, min_svs, max_svs);\n\n    MatrixType M;\n    generateRandomMatrixSvs(svs, rows, cols, M);\n\n    // validate dimensions\n    VERIFY_IS_EQUAL(M.rows(), rows);\n    VERIFY_IS_EQUAL(M.cols(), cols);\n    VERIFY_IS_EQUAL(svs.size(), diag_size);\n\n    // validate singular values\n    Eigen::JacobiSVD<MatrixType> SVD(M);\n    VERIFY_IS_APPROX(svs, SVD.singularValues());\n}\n\ntemplate<typename MatrixType>\nvoid check_random_matrix(const MatrixType &m)\n{\n    enum {\n        Rows = MatrixType::RowsAtCompileTime,\n        Cols = MatrixType::ColsAtCompileTime,\n        DiagSize = EIGEN_SIZE_MIN_PREFER_DYNAMIC(Rows, Cols)\n    };\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef Matrix<RealScalar, DiagSize, 1> RealVectorType;\n\n    const Index rows = m.rows(), cols = m.cols();\n    const Index diag_size = (std::min)(rows, cols);\n    const RealScalar min_svs = 1.0, max_svs = 1000.0;\n\n    // check generation of unitary random matrices\n    typedef Matrix<Scalar, Rows, Rows> MatrixAType;\n    typedef Matrix<Scalar, Cols, Cols> MatrixBType;\n    check_generateRandomUnitaryMatrix<MatrixAType>(rows);\n    check_generateRandomUnitaryMatrix<MatrixBType>(cols);\n\n    // test generators for singular values\n    check_setupRandomSvs<RealVectorType, RealScalar>(diag_size, max_svs);\n    check_setupRangeSvs<RealVectorType, RealScalar>(diag_size, min_svs, max_svs);\n\n    // check generation of random matrices\n    check_generateRandomMatrixSvs<MatrixType, RealScalar, RealVectorType>(rows, cols, diag_size, min_svs, max_svs);\n}\n\nEIGEN_DECLARE_TEST(random_matrix)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(check_random_matrix(Matrix<float, 1, 1>()));\n    CALL_SUBTEST_2(check_random_matrix(Matrix<float, 4, 4>()));\n    CALL_SUBTEST_3(check_random_matrix(Matrix<float, 2, 3>()));\n    CALL_SUBTEST_4(check_random_matrix(Matrix<float, 7, 4>()));\n\n    CALL_SUBTEST_5(check_random_matrix(Matrix<double, 1, 1>()));\n    CALL_SUBTEST_6(check_random_matrix(Matrix<double, 6, 6>()));\n    CALL_SUBTEST_7(check_random_matrix(Matrix<double, 5, 3>()));\n    CALL_SUBTEST_8(check_random_matrix(Matrix<double, 4, 9>()));\n\n    CALL_SUBTEST_9(check_random_matrix(Matrix<std::complex<float>, 12, 12>()));\n    CALL_SUBTEST_10(check_random_matrix(Matrix<std::complex<float>, 7, 14>()));\n    CALL_SUBTEST_11(check_random_matrix(Matrix<std::complex<double>, 15, 11>()));\n    CALL_SUBTEST_12(check_random_matrix(Matrix<std::complex<double>, 6, 9>()));\n\n    CALL_SUBTEST_13(check_random_matrix(\n        MatrixXf(internal::random<int>(1, EIGEN_TEST_MAX_SIZE), internal::random<int>(1, EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_14(check_random_matrix(\n        MatrixXd(internal::random<int>(1, EIGEN_TEST_MAX_SIZE), internal::random<int>(1, EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_15(check_random_matrix(\n        MatrixXcf(internal::random<int>(1, EIGEN_TEST_MAX_SIZE), internal::random<int>(1, EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_16(check_random_matrix(\n        MatrixXcd(internal::random<int>(1, EIGEN_TEST_MAX_SIZE), internal::random<int>(1, EIGEN_TEST_MAX_SIZE))));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/random_without_cast_overflow.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2020 C. Antonio Sanchez <cantonios@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// Utilities for generating random numbers without overflows, which might\n// otherwise result in undefined behavior.\n\nnamespace Eigen {\nnamespace internal {\n\n// Default implementation assuming SrcScalar fits into TgtScalar.\ntemplate <typename SrcScalar, typename TgtScalar, typename EnableIf = void>\nstruct random_without_cast_overflow {\n  static SrcScalar value() { return internal::random<SrcScalar>(); }\n};\n\n// Signed to unsigned integer widening cast.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<NumTraits<SrcScalar>::IsInteger && NumTraits<TgtScalar>::IsInteger &&\n                                 !NumTraits<TgtScalar>::IsSigned &&\n                                 (std::numeric_limits<SrcScalar>::digits < std::numeric_limits<TgtScalar>::digits ||\n                                  (std::numeric_limits<SrcScalar>::digits == std::numeric_limits<TgtScalar>::digits &&\n                                   NumTraits<SrcScalar>::IsSigned))>::type> {\n  static SrcScalar value() {\n    SrcScalar a = internal::random<SrcScalar>();\n    return a < SrcScalar(0) ? -(a + 1) : a;\n  }\n};\n\n// Integer to unsigned narrowing cast.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<\n        NumTraits<SrcScalar>::IsInteger && NumTraits<TgtScalar>::IsInteger && !NumTraits<SrcScalar>::IsSigned &&\n        (std::numeric_limits<SrcScalar>::digits > std::numeric_limits<TgtScalar>::digits)>::type> {\n  static SrcScalar value() {\n    TgtScalar b = internal::random<TgtScalar>();\n    return static_cast<SrcScalar>(b < TgtScalar(0) ? -(b + 1) : b);\n  }\n};\n\n// Integer to signed narrowing cast.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<\n        NumTraits<SrcScalar>::IsInteger && NumTraits<TgtScalar>::IsInteger && NumTraits<SrcScalar>::IsSigned &&\n        (std::numeric_limits<SrcScalar>::digits > std::numeric_limits<TgtScalar>::digits)>::type> {\n  static SrcScalar value() { return static_cast<SrcScalar>(internal::random<TgtScalar>()); }\n};\n\n// Unsigned to signed integer narrowing cast.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<NumTraits<SrcScalar>::IsInteger && NumTraits<TgtScalar>::IsInteger &&\n                                 !NumTraits<SrcScalar>::IsSigned && NumTraits<TgtScalar>::IsSigned &&\n                                 (std::numeric_limits<SrcScalar>::digits ==\n                                  std::numeric_limits<TgtScalar>::digits)>::type> {\n  static SrcScalar value() { return internal::random<SrcScalar>() / 2; }\n};\n\n// Floating-point to integer, full precision.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<\n        !NumTraits<SrcScalar>::IsInteger && !NumTraits<SrcScalar>::IsComplex && NumTraits<TgtScalar>::IsInteger &&\n        (std::numeric_limits<TgtScalar>::digits <= std::numeric_limits<SrcScalar>::digits)>::type> {\n  static SrcScalar value() { return static_cast<SrcScalar>(internal::random<TgtScalar>()); }\n};\n\n// Floating-point to integer, narrowing precision.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<\n        !NumTraits<SrcScalar>::IsInteger && !NumTraits<SrcScalar>::IsComplex && NumTraits<TgtScalar>::IsInteger &&\n        (std::numeric_limits<TgtScalar>::digits > std::numeric_limits<SrcScalar>::digits)>::type> {\n  static SrcScalar value() {\n    // NOTE: internal::random<T>() is limited by RAND_MAX, so random<int64_t> is always within that range.\n    // This prevents us from simply shifting bits, which would result in only 0 or -1.\n    // Instead, keep least-significant K bits and sign.\n    static const TgtScalar KeepMask = (static_cast<TgtScalar>(1) << std::numeric_limits<SrcScalar>::digits) - 1;\n    const TgtScalar a = internal::random<TgtScalar>();\n    return static_cast<SrcScalar>(a > TgtScalar(0) ? (a & KeepMask) : -(a & KeepMask));\n  }\n};\n\n// Integer to floating-point, re-use above logic.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<NumTraits<SrcScalar>::IsInteger && !NumTraits<TgtScalar>::IsInteger &&\n                                 !NumTraits<TgtScalar>::IsComplex>::type> {\n  static SrcScalar value() {\n    return static_cast<SrcScalar>(random_without_cast_overflow<TgtScalar, SrcScalar>::value());\n  }\n};\n\n// Floating-point narrowing conversion.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<!NumTraits<SrcScalar>::IsInteger && !NumTraits<SrcScalar>::IsComplex &&\n                                 !NumTraits<TgtScalar>::IsInteger && !NumTraits<TgtScalar>::IsComplex &&\n                                 (std::numeric_limits<SrcScalar>::digits >\n                                  std::numeric_limits<TgtScalar>::digits)>::type> {\n  static SrcScalar value() { return static_cast<SrcScalar>(internal::random<TgtScalar>()); }\n};\n\n// Complex to non-complex.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<NumTraits<SrcScalar>::IsComplex && !NumTraits<TgtScalar>::IsComplex>::type> {\n  typedef typename NumTraits<SrcScalar>::Real SrcReal;\n  static SrcScalar value() { return SrcScalar(random_without_cast_overflow<SrcReal, TgtScalar>::value(), 0); }\n};\n\n// Non-complex to complex.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<!NumTraits<SrcScalar>::IsComplex && NumTraits<TgtScalar>::IsComplex>::type> {\n  typedef typename NumTraits<TgtScalar>::Real TgtReal;\n  static SrcScalar value() { return random_without_cast_overflow<SrcScalar, TgtReal>::value(); }\n};\n\n// Complex to complex.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<NumTraits<SrcScalar>::IsComplex && NumTraits<TgtScalar>::IsComplex>::type> {\n  typedef typename NumTraits<SrcScalar>::Real SrcReal;\n  typedef typename NumTraits<TgtScalar>::Real TgtReal;\n  static SrcScalar value() {\n    return SrcScalar(random_without_cast_overflow<SrcReal, TgtReal>::value(),\n                     random_without_cast_overflow<SrcReal, TgtReal>::value());\n  }\n};\n\n}  // namespace internal\n}  // namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/real_qz.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Alexey Korepanov <kaikaikai@yandex.ru>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_RUNTIME_NO_MALLOC\n#include \"main.h\"\n#include <limits>\n#include <Eigen/Eigenvalues>\n\ntemplate<typename MatrixType> void real_qz(const MatrixType& m)\n{\n  /* this test covers the following files:\n     RealQZ.h\n  */\n  using std::abs;\n  typedef typename MatrixType::Scalar Scalar;\n  \n  Index dim = m.cols();\n  \n  MatrixType A = MatrixType::Random(dim,dim),\n             B = MatrixType::Random(dim,dim);\n\n\n  // Regression test for bug 985: Randomly set rows or columns to zero\n  Index k=internal::random<Index>(0, dim-1);\n  switch(internal::random<int>(0,10)) {\n  case 0:\n    A.row(k).setZero(); break;\n  case 1:\n    A.col(k).setZero(); break;\n  case 2:\n    B.row(k).setZero(); break;\n  case 3:\n    B.col(k).setZero(); break;\n  default:\n    break;\n  }\n\n  RealQZ<MatrixType> qz(dim);\n  // TODO enable full-prealocation of required memory, this probably requires an in-place mode for HessenbergDecomposition\n  //Eigen::internal::set_is_malloc_allowed(false);\n  qz.compute(A,B);\n  //Eigen::internal::set_is_malloc_allowed(true);\n  \n  VERIFY_IS_EQUAL(qz.info(), Success);\n  // check for zeros\n  bool all_zeros = true;\n  for (Index i=0; i<A.cols(); i++)\n    for (Index j=0; j<i; j++) {\n      if (abs(qz.matrixT()(i,j))!=Scalar(0.0))\n      {\n        std::cerr << \"Error: T(\" << i << \",\" << j << \") = \" << qz.matrixT()(i,j) << std::endl;\n        all_zeros = false;\n      }\n      if (j<i-1 && abs(qz.matrixS()(i,j))!=Scalar(0.0))\n      {\n        std::cerr << \"Error: S(\" << i << \",\" << j << \") = \" << qz.matrixS()(i,j) << std::endl;\n        all_zeros = false;\n      }\n      if (j==i-1 && j>0 && abs(qz.matrixS()(i,j))!=Scalar(0.0) && abs(qz.matrixS()(i-1,j-1))!=Scalar(0.0))\n      {\n        std::cerr << \"Error: S(\" << i << \",\" << j << \") = \" << qz.matrixS()(i,j)  << \" && S(\" << i-1 << \",\" << j-1 << \") = \" << qz.matrixS()(i-1,j-1) << std::endl;\n        all_zeros = false;\n      }\n    }\n  VERIFY_IS_EQUAL(all_zeros, true);\n  VERIFY_IS_APPROX(qz.matrixQ()*qz.matrixS()*qz.matrixZ(), A);\n  VERIFY_IS_APPROX(qz.matrixQ()*qz.matrixT()*qz.matrixZ(), B);\n  VERIFY_IS_APPROX(qz.matrixQ()*qz.matrixQ().adjoint(), MatrixType::Identity(dim,dim));\n  VERIFY_IS_APPROX(qz.matrixZ()*qz.matrixZ().adjoint(), MatrixType::Identity(dim,dim));\n}\n\nEIGEN_DECLARE_TEST(real_qz)\n{\n  int s = 0;\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( real_qz(Matrix4f()) );\n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4);\n    CALL_SUBTEST_2( real_qz(MatrixXd(s,s)) );\n\n    // some trivial but implementation-wise tricky cases\n    CALL_SUBTEST_2( real_qz(MatrixXd(1,1)) );\n    CALL_SUBTEST_2( real_qz(MatrixXd(2,2)) );\n    CALL_SUBTEST_3( real_qz(Matrix<double,1,1>()) );\n    CALL_SUBTEST_4( real_qz(Matrix2d()) );\n  }\n  \n  TEST_SET_BUT_UNUSED_VARIABLE(s)\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/redux.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define TEST_ENABLE_TEMPORARY_TRACKING\n#define EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD 8\n// ^^ see bug 1449\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void matrixRedux(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols);\n\n  // The entries of m1 are uniformly distributed in [0,1], so m1.prod() is very small. This may lead to test\n  // failures if we underflow into denormals. Thus, we scale so that entries are close to 1.\n  MatrixType m1_for_prod = MatrixType::Ones(rows, cols) + RealScalar(0.2) * m1;\n\n  Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> m2(rows,rows);\n  m2.setRandom();\n\n  VERIFY_IS_MUCH_SMALLER_THAN(MatrixType::Zero(rows, cols).sum(), Scalar(1));\n  VERIFY_IS_APPROX(MatrixType::Ones(rows, cols).sum(), Scalar(float(rows*cols))); // the float() here to shut up excessive MSVC warning about int->complex conversion being lossy\n  Scalar s(0), p(1), minc(numext::real(m1.coeff(0))), maxc(numext::real(m1.coeff(0)));\n  for(int j = 0; j < cols; j++)\n  for(int i = 0; i < rows; i++)\n  {\n    s += m1(i,j);\n    p *= m1_for_prod(i,j);\n    minc = (std::min)(numext::real(minc), numext::real(m1(i,j)));\n    maxc = (std::max)(numext::real(maxc), numext::real(m1(i,j)));\n  }\n  const Scalar mean = s/Scalar(RealScalar(rows*cols));\n\n  VERIFY_IS_APPROX(m1.sum(), s);\n  VERIFY_IS_APPROX(m1.mean(), mean);\n  VERIFY_IS_APPROX(m1_for_prod.prod(), p);\n  VERIFY_IS_APPROX(m1.real().minCoeff(), numext::real(minc));\n  VERIFY_IS_APPROX(m1.real().maxCoeff(), numext::real(maxc));\n  \n  // test that partial reduction works if nested expressions is forced to evaluate early\n  VERIFY_IS_APPROX((m1.matrix() * m1.matrix().transpose())       .cwiseProduct(m2.matrix()).rowwise().sum().sum(), \n                   (m1.matrix() * m1.matrix().transpose()).eval().cwiseProduct(m2.matrix()).rowwise().sum().sum());\n\n  // test slice vectorization assuming assign is ok\n  Index r0 = internal::random<Index>(0,rows-1);\n  Index c0 = internal::random<Index>(0,cols-1);\n  Index r1 = internal::random<Index>(r0+1,rows)-r0;\n  Index c1 = internal::random<Index>(c0+1,cols)-c0;\n  VERIFY_IS_APPROX(m1.block(r0,c0,r1,c1).sum(), m1.block(r0,c0,r1,c1).eval().sum());\n  VERIFY_IS_APPROX(m1.block(r0,c0,r1,c1).mean(), m1.block(r0,c0,r1,c1).eval().mean());\n  VERIFY_IS_APPROX(m1_for_prod.block(r0,c0,r1,c1).prod(), m1_for_prod.block(r0,c0,r1,c1).eval().prod());\n  VERIFY_IS_APPROX(m1.block(r0,c0,r1,c1).real().minCoeff(), m1.block(r0,c0,r1,c1).real().eval().minCoeff());\n  VERIFY_IS_APPROX(m1.block(r0,c0,r1,c1).real().maxCoeff(), m1.block(r0,c0,r1,c1).real().eval().maxCoeff());\n\n  // regression for bug 1090\n  const int R1 = MatrixType::RowsAtCompileTime>=2 ? MatrixType::RowsAtCompileTime/2 : 6;\n  const int C1 = MatrixType::ColsAtCompileTime>=2 ? MatrixType::ColsAtCompileTime/2 : 6;\n  if(R1<=rows-r0 && C1<=cols-c0)\n  {\n    VERIFY_IS_APPROX( (m1.template block<R1,C1>(r0,c0).sum()), m1.block(r0,c0,R1,C1).sum() );\n  }\n  \n  // test empty objects\n  VERIFY_IS_APPROX(m1.block(r0,c0,0,0).sum(),   Scalar(0));\n  VERIFY_IS_APPROX(m1.block(r0,c0,0,0).prod(),  Scalar(1));\n\n  // test nesting complex expression\n  VERIFY_EVALUATION_COUNT( (m1.matrix()*m1.matrix().transpose()).sum(), (MatrixType::IsVectorAtCompileTime && MatrixType::SizeAtCompileTime!=1 ? 0 : 1) );\n  VERIFY_EVALUATION_COUNT( ((m1.matrix()*m1.matrix().transpose())+m2).sum(),(MatrixType::IsVectorAtCompileTime && MatrixType::SizeAtCompileTime!=1 ? 0 : 1));\n}\n\ntemplate<typename VectorType> void vectorRedux(const VectorType& w)\n{\n  using std::abs;\n  typedef typename VectorType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  Index size = w.size();\n\n  VectorType v = VectorType::Random(size);\n  VectorType v_for_prod = VectorType::Ones(size) + Scalar(0.2) * v; // see comment above declaration of m1_for_prod\n\n  for(int i = 1; i < size; i++)\n  {\n    Scalar s(0), p(1);\n    RealScalar minc(numext::real(v.coeff(0))), maxc(numext::real(v.coeff(0)));\n    for(int j = 0; j < i; j++)\n    {\n      s += v[j];\n      p *= v_for_prod[j];\n      minc = (std::min)(minc, numext::real(v[j]));\n      maxc = (std::max)(maxc, numext::real(v[j]));\n    }\n    VERIFY_IS_MUCH_SMALLER_THAN(abs(s - v.head(i).sum()), Scalar(1));\n    VERIFY_IS_APPROX(p, v_for_prod.head(i).prod());\n    VERIFY_IS_APPROX(minc, v.real().head(i).minCoeff());\n    VERIFY_IS_APPROX(maxc, v.real().head(i).maxCoeff());\n  }\n\n  for(int i = 0; i < size-1; i++)\n  {\n    Scalar s(0), p(1);\n    RealScalar minc(numext::real(v.coeff(i))), maxc(numext::real(v.coeff(i)));\n    for(int j = i; j < size; j++)\n    {\n      s += v[j];\n      p *= v_for_prod[j];\n      minc = (std::min)(minc, numext::real(v[j]));\n      maxc = (std::max)(maxc, numext::real(v[j]));\n    }\n    VERIFY_IS_MUCH_SMALLER_THAN(abs(s - v.tail(size-i).sum()), Scalar(1));\n    VERIFY_IS_APPROX(p, v_for_prod.tail(size-i).prod());\n    VERIFY_IS_APPROX(minc, v.real().tail(size-i).minCoeff());\n    VERIFY_IS_APPROX(maxc, v.real().tail(size-i).maxCoeff());\n  }\n\n  for(int i = 0; i < size/2; i++)\n  {\n    Scalar s(0), p(1);\n    RealScalar minc(numext::real(v.coeff(i))), maxc(numext::real(v.coeff(i)));\n    for(int j = i; j < size-i; j++)\n    {\n      s += v[j];\n      p *= v_for_prod[j];\n      minc = (std::min)(minc, numext::real(v[j]));\n      maxc = (std::max)(maxc, numext::real(v[j]));\n    }\n    VERIFY_IS_MUCH_SMALLER_THAN(abs(s - v.segment(i, size-2*i).sum()), Scalar(1));\n    VERIFY_IS_APPROX(p, v_for_prod.segment(i, size-2*i).prod());\n    VERIFY_IS_APPROX(minc, v.real().segment(i, size-2*i).minCoeff());\n    VERIFY_IS_APPROX(maxc, v.real().segment(i, size-2*i).maxCoeff());\n  }\n  \n  // test empty objects\n  VERIFY_IS_APPROX(v.head(0).sum(),   Scalar(0));\n  VERIFY_IS_APPROX(v.tail(0).prod(),  Scalar(1));\n  VERIFY_RAISES_ASSERT(v.head(0).mean());\n  VERIFY_RAISES_ASSERT(v.head(0).minCoeff());\n  VERIFY_RAISES_ASSERT(v.head(0).maxCoeff());\n}\n\nEIGEN_DECLARE_TEST(redux)\n{\n  // the max size cannot be too large, otherwise reduxion operations obviously generate large errors.\n  int maxsize = (std::min)(100,EIGEN_TEST_MAX_SIZE);\n  TEST_SET_BUT_UNUSED_VARIABLE(maxsize);\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( matrixRedux(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_1( matrixRedux(Array<float, 1, 1>()) );\n    CALL_SUBTEST_2( matrixRedux(Matrix2f()) );\n    CALL_SUBTEST_2( matrixRedux(Array2f()) );\n    CALL_SUBTEST_2( matrixRedux(Array22f()) );\n    CALL_SUBTEST_3( matrixRedux(Matrix4d()) );\n    CALL_SUBTEST_3( matrixRedux(Array4d()) );\n    CALL_SUBTEST_3( matrixRedux(Array44d()) );\n    CALL_SUBTEST_4( matrixRedux(MatrixXcf(internal::random<int>(1,maxsize), internal::random<int>(1,maxsize))) );\n    CALL_SUBTEST_4( matrixRedux(ArrayXXcf(internal::random<int>(1,maxsize), internal::random<int>(1,maxsize))) );\n    CALL_SUBTEST_5( matrixRedux(MatrixXd (internal::random<int>(1,maxsize), internal::random<int>(1,maxsize))) );\n    CALL_SUBTEST_5( matrixRedux(ArrayXXd (internal::random<int>(1,maxsize), internal::random<int>(1,maxsize))) );\n    CALL_SUBTEST_6( matrixRedux(MatrixXi (internal::random<int>(1,maxsize), internal::random<int>(1,maxsize))) );\n    CALL_SUBTEST_6( matrixRedux(ArrayXXi (internal::random<int>(1,maxsize), internal::random<int>(1,maxsize))) );\n  }\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_7( vectorRedux(Vector4f()) );\n    CALL_SUBTEST_7( vectorRedux(Array4f()) );\n    CALL_SUBTEST_5( vectorRedux(VectorXd(internal::random<int>(1,maxsize))) );\n    CALL_SUBTEST_5( vectorRedux(ArrayXd(internal::random<int>(1,maxsize))) );\n    CALL_SUBTEST_8( vectorRedux(VectorXf(internal::random<int>(1,maxsize))) );\n    CALL_SUBTEST_8( vectorRedux(ArrayXf(internal::random<int>(1,maxsize))) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/ref.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 20013 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// This unit test cannot be easily written to work with EIGEN_DEFAULT_TO_ROW_MAJOR\n#ifdef EIGEN_DEFAULT_TO_ROW_MAJOR\n#undef EIGEN_DEFAULT_TO_ROW_MAJOR\n#endif\n\n#define TEST_ENABLE_TEMPORARY_TRACKING\n#define TEST_CHECK_STATIC_ASSERTIONS\n#include \"main.h\"\n\n// test Ref.h\n\n// Deal with i387 extended precision\n#if EIGEN_ARCH_i386 && !(EIGEN_ARCH_x86_64)\n\n#if EIGEN_COMP_GNUC_STRICT && EIGEN_GNUC_AT_LEAST(4,4)\n#pragma GCC optimize (\"-ffloat-store\")\n#else\n#undef VERIFY_IS_EQUAL\n#define VERIFY_IS_EQUAL(X,Y) VERIFY_IS_APPROX(X,Y)\n#endif\n\n#endif\n\ntemplate<typename MatrixType> void ref_matrix(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef Matrix<Scalar,Dynamic,Dynamic,MatrixType::Options> DynMatrixType;\n  typedef Matrix<RealScalar,Dynamic,Dynamic,MatrixType::Options> RealDynMatrixType;\n  \n  typedef Ref<MatrixType> RefMat;\n  typedef Ref<DynMatrixType> RefDynMat;\n  typedef Ref<const DynMatrixType> ConstRefDynMat;\n  typedef Ref<RealDynMatrixType , 0, Stride<Dynamic,Dynamic> > RefRealMatWithStride;\n\n  Index rows = m.rows(), cols = m.cols();\n  \n  MatrixType  m1 = MatrixType::Random(rows, cols),\n              m2 = m1;\n  \n  Index i = internal::random<Index>(0,rows-1);\n  Index j = internal::random<Index>(0,cols-1);\n  Index brows = internal::random<Index>(1,rows-i);\n  Index bcols = internal::random<Index>(1,cols-j);\n  \n  RefMat rm0 = m1;\n  VERIFY_IS_EQUAL(rm0, m1);\n  RefDynMat rm1 = m1;\n  VERIFY_IS_EQUAL(rm1, m1);\n  RefDynMat rm2 = m1.block(i,j,brows,bcols);\n  VERIFY_IS_EQUAL(rm2, m1.block(i,j,brows,bcols));\n  rm2.setOnes();\n  m2.block(i,j,brows,bcols).setOnes();\n  VERIFY_IS_EQUAL(m1, m2);\n  \n  m2.block(i,j,brows,bcols).setRandom();\n  rm2 = m2.block(i,j,brows,bcols);\n  VERIFY_IS_EQUAL(m1, m2);\n  \n  ConstRefDynMat rm3 = m1.block(i,j,brows,bcols);\n  m1.block(i,j,brows,bcols) *= 2;\n  m2.block(i,j,brows,bcols) *= 2;\n  VERIFY_IS_EQUAL(rm3, m2.block(i,j,brows,bcols));\n  RefRealMatWithStride rm4 = m1.real();\n  VERIFY_IS_EQUAL(rm4, m2.real());\n  rm4.array() += 1;\n  m2.real().array() += 1;\n  VERIFY_IS_EQUAL(m1, m2);\n}\n\ntemplate<typename VectorType> void ref_vector(const VectorType& m)\n{\n  typedef typename VectorType::Scalar Scalar;\n  typedef typename VectorType::RealScalar RealScalar;\n  typedef Matrix<Scalar,Dynamic,1,VectorType::Options> DynMatrixType;\n  typedef Matrix<Scalar,Dynamic,Dynamic,ColMajor> MatrixType;\n  typedef Matrix<RealScalar,Dynamic,1,VectorType::Options> RealDynMatrixType;\n  \n  typedef Ref<VectorType> RefMat;\n  typedef Ref<DynMatrixType> RefDynMat;\n  typedef Ref<const DynMatrixType> ConstRefDynMat;\n  typedef Ref<RealDynMatrixType , 0, InnerStride<> > RefRealMatWithStride;\n  typedef Ref<DynMatrixType , 0, InnerStride<> > RefMatWithStride;\n\n  Index size = m.size();\n  \n  VectorType  v1 = VectorType::Random(size),\n              v2 = v1;\n  MatrixType mat1 = MatrixType::Random(size,size),\n             mat2 = mat1,\n             mat3 = MatrixType::Random(size,size);\n  \n  Index i = internal::random<Index>(0,size-1);\n  Index bsize = internal::random<Index>(1,size-i);\n  \n  { RefMat    rm0 = v1;                   VERIFY_IS_EQUAL(rm0, v1); }\n  { RefMat    rm0 = v1.block(0,0,size,1); VERIFY_IS_EQUAL(rm0, v1); }\n  { RefDynMat rv1 = v1;                   VERIFY_IS_EQUAL(rv1, v1); }\n  { RefDynMat rv1 = v1.block(0,0,size,1); VERIFY_IS_EQUAL(rv1, v1); }\n  { VERIFY_RAISES_ASSERT( RefMat    rm0 = v1.block(0, 0, size, 0); EIGEN_UNUSED_VARIABLE(rm0); ); }\n  if(VectorType::SizeAtCompileTime!=1)\n  { VERIFY_RAISES_ASSERT( RefDynMat rv1 = v1.block(0, 0, size, 0); EIGEN_UNUSED_VARIABLE(rv1); ); }\n\n  RefDynMat rv2 = v1.segment(i,bsize);\n  VERIFY_IS_EQUAL(rv2, v1.segment(i,bsize));\n  rv2.setOnes();\n  v2.segment(i,bsize).setOnes();\n  VERIFY_IS_EQUAL(v1, v2);\n  \n  v2.segment(i,bsize).setRandom();\n  rv2 = v2.segment(i,bsize);\n  VERIFY_IS_EQUAL(v1, v2);\n  \n  ConstRefDynMat rm3 = v1.segment(i,bsize);\n  v1.segment(i,bsize) *= 2;\n  v2.segment(i,bsize) *= 2;\n  VERIFY_IS_EQUAL(rm3, v2.segment(i,bsize));\n  \n  RefRealMatWithStride rm4 = v1.real();\n  VERIFY_IS_EQUAL(rm4, v2.real());\n  rm4.array() += 1;\n  v2.real().array() += 1;\n  VERIFY_IS_EQUAL(v1, v2);\n  \n  RefMatWithStride rm5 = mat1.row(i).transpose();\n  VERIFY_IS_EQUAL(rm5, mat1.row(i).transpose());\n  rm5.array() += 1;\n  mat2.row(i).array() += 1;\n  VERIFY_IS_EQUAL(mat1, mat2);\n  rm5.noalias() = rm4.transpose() * mat3;\n  mat2.row(i) = v2.real().transpose() * mat3;\n  VERIFY_IS_APPROX(mat1, mat2);\n}\n\ntemplate<typename Scalar, int Rows, int Cols>\nvoid ref_vector_fixed_sizes()\n{\n  typedef Matrix<Scalar,Rows,Cols,RowMajor> RowMajorMatrixType;\n  typedef Matrix<Scalar,Rows,Cols,ColMajor> ColMajorMatrixType;\n  typedef Matrix<Scalar,1,Cols> RowVectorType;\n  typedef Matrix<Scalar,Rows,1> ColVectorType;\n  typedef Matrix<Scalar,Cols,1> RowVectorTransposeType;\n  typedef Matrix<Scalar,1,Rows> ColVectorTransposeType;\n  typedef Stride<Dynamic, Dynamic> DynamicStride;\n\n  RowMajorMatrixType mr = RowMajorMatrixType::Random();\n  ColMajorMatrixType mc = ColMajorMatrixType::Random();\n\n  Index i = internal::random<Index>(0,Rows-1);\n  Index j = internal::random<Index>(0,Cols-1);\n\n  // Reference ith row.\n  Ref<RowVectorType, 0, DynamicStride> mr_ri = mr.row(i);\n  VERIFY_IS_EQUAL(mr_ri, mr.row(i));\n  Ref<RowVectorType, 0, DynamicStride> mc_ri = mc.row(i);\n  VERIFY_IS_EQUAL(mc_ri, mc.row(i));\n\n  // Reference jth col.\n  Ref<ColVectorType, 0, DynamicStride> mr_cj = mr.col(j);\n  VERIFY_IS_EQUAL(mr_cj, mr.col(j));\n  Ref<ColVectorType, 0, DynamicStride> mc_cj = mc.col(j);\n  VERIFY_IS_EQUAL(mc_cj, mc.col(j));\n\n  // Reference the transpose of row i.\n  Ref<RowVectorTransposeType, 0, DynamicStride> mr_rit = mr.row(i);\n  VERIFY_IS_EQUAL(mr_rit, mr.row(i).transpose());\n  Ref<RowVectorTransposeType, 0, DynamicStride> mc_rit = mc.row(i);\n  VERIFY_IS_EQUAL(mc_rit, mc.row(i).transpose());\n\n  // Reference the transpose of col j.\n  Ref<ColVectorTransposeType, 0, DynamicStride> mr_cjt = mr.col(j);\n  VERIFY_IS_EQUAL(mr_cjt, mr.col(j).transpose());\n  Ref<ColVectorTransposeType, 0, DynamicStride> mc_cjt = mc.col(j);\n  VERIFY_IS_EQUAL(mc_cjt, mc.col(j).transpose());\n  \n  // Const references without strides.\n  Ref<const RowVectorType> cmr_ri = mr.row(i);\n  VERIFY_IS_EQUAL(cmr_ri, mr.row(i));\n  Ref<const RowVectorType> cmc_ri = mc.row(i);\n  VERIFY_IS_EQUAL(cmc_ri, mc.row(i));\n\n  Ref<const ColVectorType> cmr_cj = mr.col(j);\n  VERIFY_IS_EQUAL(cmr_cj, mr.col(j));\n  Ref<const ColVectorType> cmc_cj = mc.col(j);\n  VERIFY_IS_EQUAL(cmc_cj, mc.col(j));\n\n  Ref<const RowVectorTransposeType> cmr_rit = mr.row(i);\n  VERIFY_IS_EQUAL(cmr_rit, mr.row(i).transpose());\n  Ref<const RowVectorTransposeType> cmc_rit = mc.row(i);\n  VERIFY_IS_EQUAL(cmc_rit, mc.row(i).transpose());\n\n  Ref<const ColVectorTransposeType> cmr_cjt = mr.col(j);\n  VERIFY_IS_EQUAL(cmr_cjt, mr.col(j).transpose());\n  Ref<const ColVectorTransposeType> cmc_cjt = mc.col(j);\n  VERIFY_IS_EQUAL(cmc_cjt, mc.col(j).transpose());\n}\n\ntemplate<typename PlainObjectType> void check_const_correctness(const PlainObjectType&)\n{\n  // verify that ref-to-const don't have LvalueBit\n  typedef typename internal::add_const<PlainObjectType>::type ConstPlainObjectType;\n  VERIFY( !(internal::traits<Ref<ConstPlainObjectType> >::Flags & LvalueBit) );\n  VERIFY( !(internal::traits<Ref<ConstPlainObjectType, Aligned> >::Flags & LvalueBit) );\n  VERIFY( !(Ref<ConstPlainObjectType>::Flags & LvalueBit) );\n  VERIFY( !(Ref<ConstPlainObjectType, Aligned>::Flags & LvalueBit) );\n}\n\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_1(Ref<VectorXf> a, const B &b) { VERIFY_IS_EQUAL(a,b); }\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_2(const Ref<const VectorXf>& a, const B &b) { VERIFY_IS_EQUAL(a,b); }\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_3(Ref<VectorXf,0,InnerStride<> > a, const B &b) { VERIFY_IS_EQUAL(a,b); }\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_4(const Ref<const VectorXf,0,InnerStride<> >& a, const B &b) { VERIFY_IS_EQUAL(a,b); }\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_5(Ref<MatrixXf,0,OuterStride<> > a, const B &b) { VERIFY_IS_EQUAL(a,b); }\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_6(const Ref<const MatrixXf,0,OuterStride<> >& a, const B &b) { VERIFY_IS_EQUAL(a,b); }\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_7(Ref<Matrix<float,Dynamic,3> > a, const B &b) { VERIFY_IS_EQUAL(a,b); }\n\nvoid call_ref()\n{\n  VectorXcf ca  = VectorXcf::Random(10);\n  VectorXf a    = VectorXf::Random(10);\n  RowVectorXf b = RowVectorXf::Random(10);\n  MatrixXf A    = MatrixXf::Random(10,10);\n  RowVector3f c = RowVector3f::Random();\n  const VectorXf& ac(a);\n  VectorBlock<VectorXf> ab(a,0,3);\n  const VectorBlock<VectorXf> abc(a,0,3);\n  \n\n  VERIFY_EVALUATION_COUNT( call_ref_1(a,a), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_1(b,b.transpose()), 0);\n//   call_ref_1(ac,a<c);           // does not compile because ac is const\n  VERIFY_EVALUATION_COUNT( call_ref_1(ab,ab), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_1(a.head(4),a.head(4)), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_1(abc,abc), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_1(A.col(3),A.col(3)), 0);\n//   call_ref_1(A.row(3),A.row(3));    // does not compile because innerstride!=1\n  VERIFY_EVALUATION_COUNT( call_ref_3(A.row(3),A.row(3).transpose()), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_4(A.row(3),A.row(3).transpose()), 0);\n//   call_ref_1(a+a, a+a);          // does not compile for obvious reason\n\n  MatrixXf tmp = A*A.col(1);\n  VERIFY_EVALUATION_COUNT( call_ref_2(A*A.col(1), tmp), 1);     // evaluated into a temp\n  VERIFY_EVALUATION_COUNT( call_ref_2(ac.head(5),ac.head(5)), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(ac,ac), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(a,a), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(ab,ab), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(a.head(4),a.head(4)), 0);\n  tmp = a+a;\n  VERIFY_EVALUATION_COUNT( call_ref_2(a+a,tmp), 1);            // evaluated into a temp\n  VERIFY_EVALUATION_COUNT( call_ref_2(ca.imag(),ca.imag()), 1);      // evaluated into a temp\n\n  VERIFY_EVALUATION_COUNT( call_ref_4(ac.head(5),ac.head(5)), 0);\n  tmp = a+a;\n  VERIFY_EVALUATION_COUNT( call_ref_4(a+a,tmp), 1);           // evaluated into a temp\n  VERIFY_EVALUATION_COUNT( call_ref_4(ca.imag(),ca.imag()), 0);\n\n  VERIFY_EVALUATION_COUNT( call_ref_5(a,a), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_5(a.head(3),a.head(3)), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_5(A,A), 0);\n//   call_ref_5(A.transpose(),A.transpose());   // does not compile because storage order does not match\n  VERIFY_EVALUATION_COUNT( call_ref_5(A.block(1,1,2,2),A.block(1,1,2,2)), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_5(b,b), 0);             // storage order do not match, but this is a degenerate case that should work\n  VERIFY_EVALUATION_COUNT( call_ref_5(a.row(3),a.row(3)), 0);\n\n  VERIFY_EVALUATION_COUNT( call_ref_6(a,a), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_6(a.head(3),a.head(3)), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_6(A.row(3),A.row(3)), 1);           // evaluated into a temp thouth it could be avoided by viewing it as a 1xn matrix\n  tmp = A+A;\n  VERIFY_EVALUATION_COUNT( call_ref_6(A+A,tmp), 1);                // evaluated into a temp\n  VERIFY_EVALUATION_COUNT( call_ref_6(A,A), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_6(A.transpose(),A.transpose()), 1);      // evaluated into a temp because the storage orders do not match\n  VERIFY_EVALUATION_COUNT( call_ref_6(A.block(1,1,2,2),A.block(1,1,2,2)), 0);\n  \n  VERIFY_EVALUATION_COUNT( call_ref_7(c,c), 0);\n}\n\ntypedef Matrix<double,Dynamic,Dynamic,RowMajor> RowMatrixXd;\nint test_ref_overload_fun1(Ref<MatrixXd> )       { return 1; }\nint test_ref_overload_fun1(Ref<RowMatrixXd> )    { return 2; }\nint test_ref_overload_fun1(Ref<MatrixXf> )       { return 3; }\n\nint test_ref_overload_fun2(Ref<const MatrixXd> ) { return 4; }\nint test_ref_overload_fun2(Ref<const MatrixXf> ) { return 5; }\n\nvoid test_ref_ambiguous(const Ref<const ArrayXd> &A, Ref<ArrayXd> B)\n{\n  B = A;\n  B = A - A;\n}\n\n// See also bug 969\nvoid test_ref_overloads()\n{\n  MatrixXd Ad, Bd;\n  RowMatrixXd rAd, rBd;\n  VERIFY( test_ref_overload_fun1(Ad)==1 );\n  VERIFY( test_ref_overload_fun1(rAd)==2 );\n  \n  MatrixXf Af, Bf;\n  VERIFY( test_ref_overload_fun2(Ad)==4 );\n  VERIFY( test_ref_overload_fun2(Ad+Bd)==4 );\n  VERIFY( test_ref_overload_fun2(Af+Bf)==5 );\n  \n  ArrayXd A, B;\n  test_ref_ambiguous(A, B);\n}\n\nvoid test_ref_fixed_size_assert()\n{\n  Vector4f v4 = Vector4f::Random();\n  VectorXf vx = VectorXf::Random(10);\n  VERIFY_RAISES_STATIC_ASSERT( Ref<Vector3f> y = v4; (void)y; );\n  VERIFY_RAISES_STATIC_ASSERT( Ref<Vector3f> y = vx.head<4>(); (void)y; );\n  VERIFY_RAISES_STATIC_ASSERT( Ref<const Vector3f> y = v4; (void)y; );\n  VERIFY_RAISES_STATIC_ASSERT( Ref<const Vector3f> y = vx.head<4>(); (void)y; );\n  VERIFY_RAISES_STATIC_ASSERT( Ref<const Vector3f> y = 2*v4; (void)y; );\n}\n\nEIGEN_DECLARE_TEST(ref)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( ref_vector(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_1( check_const_correctness(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( ref_vector(Vector4d()) );\n    CALL_SUBTEST_2( check_const_correctness(Matrix4d()) );\n    CALL_SUBTEST_3( ref_vector(Vector4cf()) );\n    CALL_SUBTEST_4( ref_vector(VectorXcf(8)) );\n    CALL_SUBTEST_5( ref_vector(VectorXi(12)) );\n    CALL_SUBTEST_5( check_const_correctness(VectorXi(12)) );\n\n    CALL_SUBTEST_1( ref_matrix(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( ref_matrix(Matrix4d()) );\n    CALL_SUBTEST_1( ref_matrix(Matrix<float,3,5>()) );\n    CALL_SUBTEST_4( ref_matrix(MatrixXcf(internal::random<int>(1,10),internal::random<int>(1,10))) );\n    CALL_SUBTEST_4( ref_matrix(Matrix<std::complex<double>,10,15>()) );\n    CALL_SUBTEST_5( ref_matrix(MatrixXi(internal::random<int>(1,10),internal::random<int>(1,10))) );\n    CALL_SUBTEST_6( call_ref() );\n\n    CALL_SUBTEST_8( (ref_vector_fixed_sizes<float,3,5>()) );\n    CALL_SUBTEST_8( (ref_vector_fixed_sizes<float,15,10>()) );\n  }\n  \n  CALL_SUBTEST_7( test_ref_overloads() );\n  CALL_SUBTEST_7( test_ref_fixed_size_assert() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/reshape.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2017 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2014 yoco <peter.xiau@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename T1,typename T2>\ntypename internal::enable_if<internal::is_same<T1,T2>::value,bool>::type\nis_same_eq(const T1& a, const T2& b)\n{\n  return (a.array() == b.array()).all();\n}\n\ntemplate <int Order,typename MatType>\nvoid check_auto_reshape4x4(MatType m)\n{\n  internal::VariableAndFixedInt<MatType::SizeAtCompileTime==Dynamic?-1: 1>  v1( 1);\n  internal::VariableAndFixedInt<MatType::SizeAtCompileTime==Dynamic?-1: 2>  v2( 2);\n  internal::VariableAndFixedInt<MatType::SizeAtCompileTime==Dynamic?-1: 4>  v4( 4);\n  internal::VariableAndFixedInt<MatType::SizeAtCompileTime==Dynamic?-1: 8>  v8( 8);\n  internal::VariableAndFixedInt<MatType::SizeAtCompileTime==Dynamic?-1:16> v16(16);\n\n  VERIFY(is_same_eq(m.template reshaped<Order>( 1,       AutoSize), m.template reshaped<Order>( 1, 16)));\n  VERIFY(is_same_eq(m.template reshaped<Order>(AutoSize, 16      ), m.template reshaped<Order>( 1, 16)));\n  VERIFY(is_same_eq(m.template reshaped<Order>( 2,       AutoSize), m.template reshaped<Order>( 2,  8)));\n  VERIFY(is_same_eq(m.template reshaped<Order>(AutoSize, 8       ), m.template reshaped<Order>( 2,  8)));\n  VERIFY(is_same_eq(m.template reshaped<Order>( 4,       AutoSize), m.template reshaped<Order>( 4,  4)));\n  VERIFY(is_same_eq(m.template reshaped<Order>(AutoSize, 4       ), m.template reshaped<Order>( 4,  4)));\n  VERIFY(is_same_eq(m.template reshaped<Order>( 8,       AutoSize), m.template reshaped<Order>( 8,  2)));\n  VERIFY(is_same_eq(m.template reshaped<Order>(AutoSize, 2       ), m.template reshaped<Order>( 8,  2)));\n  VERIFY(is_same_eq(m.template reshaped<Order>(16,       AutoSize), m.template reshaped<Order>(16,  1)));\n  VERIFY(is_same_eq(m.template reshaped<Order>(AutoSize, 1       ), m.template reshaped<Order>(16,  1)));\n\n  VERIFY(is_same_eq(m.template reshaped<Order>(fix< 1>,   AutoSize),  m.template reshaped<Order>(fix< 1>, v16    )));\n  VERIFY(is_same_eq(m.template reshaped<Order>(AutoSize,  fix<16> ),  m.template reshaped<Order>( v1,     fix<16>)));\n  VERIFY(is_same_eq(m.template reshaped<Order>(fix< 2>,   AutoSize),  m.template reshaped<Order>(fix< 2>, v8     )));\n  VERIFY(is_same_eq(m.template reshaped<Order>(AutoSize,  fix< 8> ),  m.template reshaped<Order>( v2,     fix< 8>)));\n  VERIFY(is_same_eq(m.template reshaped<Order>(fix< 4>,   AutoSize),  m.template reshaped<Order>(fix< 4>, v4     )));\n  VERIFY(is_same_eq(m.template reshaped<Order>(AutoSize,  fix< 4> ),  m.template reshaped<Order>( v4,     fix< 4>)));\n  VERIFY(is_same_eq(m.template reshaped<Order>(fix< 8>,   AutoSize),  m.template reshaped<Order>(fix< 8>, v2     )));\n  VERIFY(is_same_eq(m.template reshaped<Order>(AutoSize,  fix< 2> ),  m.template reshaped<Order>( v8,     fix< 2>)));\n  VERIFY(is_same_eq(m.template reshaped<Order>(fix<16>,   AutoSize),  m.template reshaped<Order>(fix<16>, v1     )));\n  VERIFY(is_same_eq(m.template reshaped<Order>(AutoSize,  fix< 1> ),  m.template reshaped<Order>(v16,     fix< 1>)));\n}\n\ntemplate <typename MatType>\nvoid check_direct_access_reshape4x4(MatType , internal::FixedInt<RowMajorBit>) {}\n\ntemplate <typename MatType>\nvoid check_direct_access_reshape4x4(MatType m, internal::FixedInt<0>) {\n  VERIFY_IS_EQUAL(m.reshaped( 1, 16).data(), m.data());\n  VERIFY_IS_EQUAL(m.reshaped( 1, 16).innerStride(), 1);\n\n  VERIFY_IS_EQUAL(m.reshaped( 2, 8).data(), m.data());\n  VERIFY_IS_EQUAL(m.reshaped( 2, 8).innerStride(), 1);\n  VERIFY_IS_EQUAL(m.reshaped( 2, 8).outerStride(), 2);\n}\n\n// just test a 4x4 matrix, enumerate all combination manually\ntemplate <typename MatType>\nvoid reshape4x4(MatType m)\n{\n  typedef typename MatType::Scalar Scalar;\n\n  internal::VariableAndFixedInt<MatType::SizeAtCompileTime==Dynamic?-1: 1>  v1( 1);\n  internal::VariableAndFixedInt<MatType::SizeAtCompileTime==Dynamic?-1: 2>  v2( 2);\n  internal::VariableAndFixedInt<MatType::SizeAtCompileTime==Dynamic?-1: 4>  v4( 4);\n  internal::VariableAndFixedInt<MatType::SizeAtCompileTime==Dynamic?-1: 8>  v8( 8);\n  internal::VariableAndFixedInt<MatType::SizeAtCompileTime==Dynamic?-1:16> v16(16);\n\n  if((MatType::Flags&RowMajorBit)==0)\n  {\n    typedef Map<MatrixXi> MapMat;\n    // dynamic\n    VERIFY_IS_EQUAL((m.reshaped( 1, 16)), MapMat(m.data(),  1, 16));\n    VERIFY_IS_EQUAL((m.reshaped( 2,  8)), MapMat(m.data(),  2,  8));\n    VERIFY_IS_EQUAL((m.reshaped( 4,  4)), MapMat(m.data(),  4,  4));\n    VERIFY_IS_EQUAL((m.reshaped( 8,  2)), MapMat(m.data(),  8,  2));\n    VERIFY_IS_EQUAL((m.reshaped(16,  1)), MapMat(m.data(), 16,  1));\n\n    // static\n    VERIFY_IS_EQUAL(m.reshaped(fix< 1>, fix<16>), MapMat(m.data(),  1, 16));\n    VERIFY_IS_EQUAL(m.reshaped(fix< 2>, fix< 8>), MapMat(m.data(),  2,  8));\n    VERIFY_IS_EQUAL(m.reshaped(fix< 4>, fix< 4>), MapMat(m.data(),  4,  4));\n    VERIFY_IS_EQUAL(m.reshaped(fix< 8>, fix< 2>), MapMat(m.data(),  8,  2));\n    VERIFY_IS_EQUAL(m.reshaped(fix<16>, fix< 1>), MapMat(m.data(), 16,  1));\n\n\n    // reshape chain\n    VERIFY_IS_EQUAL(\n      (m\n      .reshaped( 1, 16)\n      .reshaped(fix< 2>,fix< 8>)\n      .reshaped(16,  1)\n      .reshaped(fix< 8>,fix< 2>)\n      .reshaped( 2,  8)\n      .reshaped(fix< 1>,fix<16>)\n      .reshaped( 4,  4)\n      .reshaped(fix<16>,fix< 1>)\n      .reshaped( 8,  2)\n      .reshaped(fix< 4>,fix< 4>)\n      ),\n      MapMat(m.data(), 4,  4)\n    );\n  }\n\n  VERIFY(is_same_eq(m.reshaped( 1,       AutoSize), m.reshaped( 1, 16)));\n  VERIFY(is_same_eq(m.reshaped(AutoSize, 16),       m.reshaped( 1, 16)));\n  VERIFY(is_same_eq(m.reshaped( 2,       AutoSize), m.reshaped( 2,  8)));\n  VERIFY(is_same_eq(m.reshaped(AutoSize, 8),        m.reshaped( 2,  8)));\n  VERIFY(is_same_eq(m.reshaped( 4,       AutoSize), m.reshaped( 4,  4)));\n  VERIFY(is_same_eq(m.reshaped(AutoSize, 4),        m.reshaped( 4,  4)));\n  VERIFY(is_same_eq(m.reshaped( 8,       AutoSize), m.reshaped( 8,  2)));\n  VERIFY(is_same_eq(m.reshaped(AutoSize, 2),        m.reshaped( 8,  2)));\n  VERIFY(is_same_eq(m.reshaped(16,       AutoSize), m.reshaped(16,  1)));\n  VERIFY(is_same_eq(m.reshaped(AutoSize,  1),       m.reshaped(16,  1)));\n\n  VERIFY(is_same_eq(m.reshaped(fix< 1>,   AutoSize),  m.reshaped(fix< 1>, v16)));\n  VERIFY(is_same_eq(m.reshaped(AutoSize,  fix<16>),   m.reshaped( v1,     fix<16>)));\n  VERIFY(is_same_eq(m.reshaped(fix< 2>,   AutoSize),  m.reshaped(fix< 2>, v8)));\n  VERIFY(is_same_eq(m.reshaped(AutoSize,  fix< 8>),   m.reshaped( v2,     fix< 8>)));\n  VERIFY(is_same_eq(m.reshaped(fix< 4>,   AutoSize),  m.reshaped(fix< 4>, v4)));\n  VERIFY(is_same_eq(m.reshaped(AutoSize,  fix< 4>),   m.reshaped( v4,     fix< 4>)));\n  VERIFY(is_same_eq(m.reshaped(fix< 8>,   AutoSize),  m.reshaped(fix< 8>, v2)));\n  VERIFY(is_same_eq(m.reshaped(AutoSize,  fix< 2>),   m.reshaped( v8,     fix< 2>)));\n  VERIFY(is_same_eq(m.reshaped(fix<16>,   AutoSize),  m.reshaped(fix<16>, v1)));\n  VERIFY(is_same_eq(m.reshaped(AutoSize,  fix< 1>),   m.reshaped(v16,     fix< 1>)));\n\n  check_auto_reshape4x4<ColMajor> (m);\n  check_auto_reshape4x4<RowMajor> (m);\n  check_auto_reshape4x4<AutoOrder>(m);\n  check_auto_reshape4x4<ColMajor> (m.transpose());\n  check_auto_reshape4x4<ColMajor> (m.transpose());\n  check_auto_reshape4x4<AutoOrder>(m.transpose());\n\n  check_direct_access_reshape4x4(m,fix<MatType::Flags&RowMajorBit>);\n\n  if((MatType::Flags&RowMajorBit)==0)\n  {\n    VERIFY_IS_EQUAL(m.template reshaped<ColMajor>(2,8),m.reshaped(2,8));\n    VERIFY_IS_EQUAL(m.template reshaped<ColMajor>(2,8),m.template reshaped<AutoOrder>(2,8));\n    VERIFY_IS_EQUAL(m.transpose().template reshaped<RowMajor>(2,8),m.transpose().template reshaped<AutoOrder>(2,8));\n  }\n  else\n  {\n    VERIFY_IS_EQUAL(m.template reshaped<ColMajor>(2,8),m.reshaped(2,8));\n    VERIFY_IS_EQUAL(m.template reshaped<RowMajor>(2,8),m.template reshaped<AutoOrder>(2,8));\n    VERIFY_IS_EQUAL(m.transpose().template reshaped<ColMajor>(2,8),m.transpose().template reshaped<AutoOrder>(2,8));\n    VERIFY_IS_EQUAL(m.transpose().reshaped(2,8),m.transpose().template reshaped<AutoOrder>(2,8));\n  }\n\n  MatrixXi m28r1 = m.template reshaped<RowMajor>(2,8);\n  MatrixXi m28r2 = m.transpose().template reshaped<ColMajor>(8,2).transpose();\n  VERIFY_IS_EQUAL( m28r1, m28r2);\n\n  VERIFY(is_same_eq(m.reshaped(v16,fix<1>), m.reshaped()));\n  VERIFY_IS_EQUAL(m.reshaped(16,1).eval(), m.reshaped().eval());\n  VERIFY_IS_EQUAL(m.reshaped(1,16).eval(), m.reshaped().transpose().eval());\n  VERIFY_IS_EQUAL(m.reshaped().reshaped(2,8), m.reshaped(2,8));\n  VERIFY_IS_EQUAL(m.reshaped().reshaped(4,4), m.reshaped(4,4));\n  VERIFY_IS_EQUAL(m.reshaped().reshaped(8,2), m.reshaped(8,2));\n\n  VERIFY_IS_EQUAL(m.reshaped(), m.template reshaped<ColMajor>());\n  VERIFY_IS_EQUAL(m.transpose().reshaped(), m.template reshaped<RowMajor>());\n  VERIFY_IS_EQUAL(m.template reshaped<RowMajor>(AutoSize,fix<1>), m.template reshaped<RowMajor>());\n  VERIFY_IS_EQUAL(m.template reshaped<AutoOrder>(AutoSize,fix<1>), m.template reshaped<AutoOrder>());\n\n  VERIFY(is_same_eq(m.reshaped(AutoSize,fix<1>), m.reshaped()));\n  VERIFY_IS_EQUAL(m.template reshaped<RowMajor>(fix<1>,AutoSize), m.transpose().reshaped().transpose());\n\n  // check assignment\n  {\n    Matrix<Scalar,Dynamic,1> m1x(m.size()); m1x.setRandom();\n    VERIFY_IS_APPROX(m.reshaped() = m1x, m1x);\n    VERIFY_IS_APPROX(m, m1x.reshaped(4,4));\n    \n    Matrix<Scalar,Dynamic,Dynamic> m28(2,8); m28.setRandom();\n    VERIFY_IS_APPROX(m.reshaped(2,8) = m28, m28);\n    VERIFY_IS_APPROX(m, m28.reshaped(4,4));\n    VERIFY_IS_APPROX(m.template reshaped<RowMajor>(2,8) = m28, m28);\n\n    Matrix<Scalar,Dynamic,Dynamic> m24(2,4); m24.setRandom();\n    VERIFY_IS_APPROX(m(seq(0,last,2),all).reshaped(2,4) = m24, m24);\n\n    // check constness:\n    m.reshaped(2,8).nestedExpression() = m;\n  }\n}\n\nEIGEN_DECLARE_TEST(reshape)\n{\n  typedef Matrix<int,Dynamic,Dynamic,RowMajor> RowMatrixXi;\n  typedef Matrix<int,4,4,RowMajor> RowMatrix4i;\n  MatrixXi mx = MatrixXi::Random(4, 4);\n  Matrix4i m4 = Matrix4i::Random(4, 4);\n  RowMatrixXi rmx = RowMatrixXi::Random(4, 4);\n  RowMatrix4i rm4 = RowMatrix4i::Random(4, 4);\n\n  // test dynamic-size matrix\n  CALL_SUBTEST(reshape4x4(mx));\n  // test static-size matrix\n  CALL_SUBTEST(reshape4x4(m4));\n  // test dynamic-size const matrix\n  CALL_SUBTEST(reshape4x4(static_cast<const MatrixXi>(mx)));\n  // test static-size const matrix\n  CALL_SUBTEST(reshape4x4(static_cast<const Matrix4i>(m4)));\n\n  CALL_SUBTEST(reshape4x4(rmx));\n  CALL_SUBTEST(reshape4x4(rm4));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/resize.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Keir Mierle <mierle@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<DenseIndex rows, DenseIndex cols>\nvoid resizeLikeTest()\n{\n  MatrixXf A(rows, cols);\n  MatrixXf B;\n  Matrix<double, rows, cols> C;\n  B.resizeLike(A);\n  C.resizeLike(B);  // Shouldn't crash.\n  VERIFY(B.rows() == rows && B.cols() == cols);\n\n  VectorXf x(rows);\n  RowVectorXf y;\n  y.resizeLike(x);\n  VERIFY(y.rows() == 1 && y.cols() == rows);\n\n  y.resize(cols);\n  x.resizeLike(y);\n  VERIFY(x.rows() == cols && x.cols() == 1);\n}\n\nvoid resizeLikeTest12() { resizeLikeTest<1,2>(); }\nvoid resizeLikeTest1020() { resizeLikeTest<10,20>(); }\nvoid resizeLikeTest31() { resizeLikeTest<3,1>(); }\n\nEIGEN_DECLARE_TEST(resize)\n{\n  CALL_SUBTEST(resizeLikeTest12() );\n  CALL_SUBTEST(resizeLikeTest1020() );\n  CALL_SUBTEST(resizeLikeTest31() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/rvalue_types.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_RUNTIME_NO_MALLOC\n\n#include \"main.h\"\n#if EIGEN_HAS_CXX11\n#include \"MovableScalar.h\"\n#endif\n#include \"SafeScalar.h\"\n\n#include <Eigen/Core>\n\nusing internal::UIntPtr;\n\n#if EIGEN_HAS_RVALUE_REFERENCES\ntemplate <typename MatrixType>\nvoid rvalue_copyassign(const MatrixType& m)\n{\n\n  typedef typename internal::traits<MatrixType>::Scalar Scalar;\n  \n  // create a temporary which we are about to destroy by moving\n  MatrixType tmp = m;\n  UIntPtr src_address = reinterpret_cast<UIntPtr>(tmp.data());\n  \n  Eigen::internal::set_is_malloc_allowed(false); // moving from an rvalue reference shall never allocate\n  // move the temporary to n\n  MatrixType n = std::move(tmp);\n  UIntPtr dst_address = reinterpret_cast<UIntPtr>(n.data());\n  if (MatrixType::RowsAtCompileTime==Dynamic|| MatrixType::ColsAtCompileTime==Dynamic)\n  {\n    // verify that we actually moved the guts\n    VERIFY_IS_EQUAL(src_address, dst_address);\n    VERIFY_IS_EQUAL(tmp.size(), 0);\n    VERIFY_IS_EQUAL(reinterpret_cast<UIntPtr>(tmp.data()), UIntPtr(0));\n  }\n\n  // verify that the content did not change\n  Scalar abs_diff = (m-n).array().abs().sum();\n  VERIFY_IS_EQUAL(abs_diff, Scalar(0));\n  Eigen::internal::set_is_malloc_allowed(true);\n}\ntemplate<typename TranspositionsType>\nvoid rvalue_transpositions(Index rows)\n{\n  typedef typename TranspositionsType::IndicesType PermutationVectorType;\n\n  PermutationVectorType vec;\n  randomPermutationVector(vec, rows);\n  TranspositionsType t0(vec);\n\n  Eigen::internal::set_is_malloc_allowed(false); // moving from an rvalue reference shall never allocate\n\n  UIntPtr t0_address = reinterpret_cast<UIntPtr>(t0.indices().data());\n\n  // Move constructors:\n  TranspositionsType t1 = std::move(t0);\n  UIntPtr t1_address = reinterpret_cast<UIntPtr>(t1.indices().data());\n  VERIFY_IS_EQUAL(t0_address, t1_address);\n  // t0 must be de-allocated:\n  VERIFY_IS_EQUAL(t0.size(), 0);\n  VERIFY_IS_EQUAL(reinterpret_cast<UIntPtr>(t0.indices().data()), UIntPtr(0));\n\n\n  // Move assignment:\n  t0 = std::move(t1);\n  t0_address = reinterpret_cast<UIntPtr>(t0.indices().data());\n  VERIFY_IS_EQUAL(t0_address, t1_address);\n  // t1 must be de-allocated:\n  VERIFY_IS_EQUAL(t1.size(), 0);\n  VERIFY_IS_EQUAL(reinterpret_cast<UIntPtr>(t1.indices().data()), UIntPtr(0));\n\n  Eigen::internal::set_is_malloc_allowed(true);\n}\n\ntemplate <typename MatrixType>\nvoid rvalue_move(const MatrixType& m)\n{\n    // lvalue reference is copied\n    MatrixType b(m);\n    VERIFY_IS_EQUAL(b, m);\n\n    // lvalue reference is copied\n    MatrixType c{m};\n    VERIFY_IS_EQUAL(c, m);\n\n    // lvalue reference is copied\n    MatrixType d = m;\n    VERIFY_IS_EQUAL(d, m);\n\n    // rvalue reference is moved - copy constructor.\n    MatrixType e_src(m);\n    VERIFY_IS_EQUAL(e_src, m);\n    MatrixType e_dst(std::move(e_src));\n    VERIFY_IS_EQUAL(e_dst, m);\n\n    // rvalue reference is moved - copy constructor.\n    MatrixType f_src(m);\n    VERIFY_IS_EQUAL(f_src, m);\n    MatrixType f_dst = std::move(f_src);\n    VERIFY_IS_EQUAL(f_dst, m);\n    \n    // rvalue reference is moved - copy assignment.\n    MatrixType g_src(m);\n    VERIFY_IS_EQUAL(g_src, m);\n    MatrixType g_dst;\n    g_dst = std::move(g_src);\n    VERIFY_IS_EQUAL(g_dst, m);\n}\n#else\ntemplate <typename MatrixType>\nvoid rvalue_copyassign(const MatrixType&) {}\ntemplate<typename TranspositionsType>\nvoid rvalue_transpositions(Index) {}\ntemplate <typename MatrixType>\nvoid rvalue_move(const MatrixType&) {}\n#endif\n\nEIGEN_DECLARE_TEST(rvalue_types)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(rvalue_copyassign( MatrixXf::Random(50,50).eval() ));\n    CALL_SUBTEST_1(rvalue_copyassign( ArrayXXf::Random(50,50).eval() ));\n\n    CALL_SUBTEST_1(rvalue_copyassign( Matrix<float,1,Dynamic>::Random(50).eval() ));\n    CALL_SUBTEST_1(rvalue_copyassign( Array<float,1,Dynamic>::Random(50).eval() ));\n\n    CALL_SUBTEST_1(rvalue_copyassign( Matrix<float,Dynamic,1>::Random(50).eval() ));\n    CALL_SUBTEST_1(rvalue_copyassign( Array<float,Dynamic,1>::Random(50).eval() ));\n\n    CALL_SUBTEST_2(rvalue_copyassign( Array<float,2,1>::Random().eval() ));\n    CALL_SUBTEST_2(rvalue_copyassign( Array<float,3,1>::Random().eval() ));\n    CALL_SUBTEST_2(rvalue_copyassign( Array<float,4,1>::Random().eval() ));\n\n    CALL_SUBTEST_2(rvalue_copyassign( Array<float,2,2>::Random().eval() ));\n    CALL_SUBTEST_2(rvalue_copyassign( Array<float,3,3>::Random().eval() ));\n    CALL_SUBTEST_2(rvalue_copyassign( Array<float,4,4>::Random().eval() ));\n  \n    CALL_SUBTEST_3((rvalue_transpositions<PermutationMatrix<Dynamic, Dynamic, int> >(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_3((rvalue_transpositions<PermutationMatrix<Dynamic, Dynamic, Index> >(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_4((rvalue_transpositions<Transpositions<Dynamic, Dynamic, int> >(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_4((rvalue_transpositions<Transpositions<Dynamic, Dynamic, Index> >(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n\n#if EIGEN_HAS_CXX11\n    CALL_SUBTEST_5(rvalue_move(Eigen::Matrix<MovableScalar<float>,1,3>::Random().eval()));\n    CALL_SUBTEST_5(rvalue_move(Eigen::Matrix<SafeScalar<float>,1,3>::Random().eval()));\n    CALL_SUBTEST_5(rvalue_move(Eigen::Matrix<SafeScalar<float>,Eigen::Dynamic,Eigen::Dynamic>::Random(1,3).eval()));\n#endif\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/schur_complex.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010,2012 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <limits>\n#include <Eigen/Eigenvalues>\n\ntemplate<typename MatrixType> void schur(int size = MatrixType::ColsAtCompileTime)\n{\n  typedef typename ComplexSchur<MatrixType>::ComplexScalar ComplexScalar;\n  typedef typename ComplexSchur<MatrixType>::ComplexMatrixType ComplexMatrixType;\n\n  // Test basic functionality: T is triangular and A = U T U*\n  for(int counter = 0; counter < g_repeat; ++counter) {\n    MatrixType A = MatrixType::Random(size, size);\n    ComplexSchur<MatrixType> schurOfA(A);\n    VERIFY_IS_EQUAL(schurOfA.info(), Success);\n    ComplexMatrixType U = schurOfA.matrixU();\n    ComplexMatrixType T = schurOfA.matrixT();\n    for(int row = 1; row < size; ++row) {\n      for(int col = 0; col < row; ++col) {\n        VERIFY(T(row,col) == (typename MatrixType::Scalar)0);\n      }\n    }\n    VERIFY_IS_APPROX(A.template cast<ComplexScalar>(), U * T * U.adjoint());\n  }\n\n  // Test asserts when not initialized\n  ComplexSchur<MatrixType> csUninitialized;\n  VERIFY_RAISES_ASSERT(csUninitialized.matrixT());\n  VERIFY_RAISES_ASSERT(csUninitialized.matrixU());\n  VERIFY_RAISES_ASSERT(csUninitialized.info());\n  \n  // Test whether compute() and constructor returns same result\n  MatrixType A = MatrixType::Random(size, size);\n  ComplexSchur<MatrixType> cs1;\n  cs1.compute(A);\n  ComplexSchur<MatrixType> cs2(A);\n  VERIFY_IS_EQUAL(cs1.info(), Success);\n  VERIFY_IS_EQUAL(cs2.info(), Success);\n  VERIFY_IS_EQUAL(cs1.matrixT(), cs2.matrixT());\n  VERIFY_IS_EQUAL(cs1.matrixU(), cs2.matrixU());\n\n  // Test maximum number of iterations\n  ComplexSchur<MatrixType> cs3;\n  cs3.setMaxIterations(ComplexSchur<MatrixType>::m_maxIterationsPerRow * size).compute(A);\n  VERIFY_IS_EQUAL(cs3.info(), Success);\n  VERIFY_IS_EQUAL(cs3.matrixT(), cs1.matrixT());\n  VERIFY_IS_EQUAL(cs3.matrixU(), cs1.matrixU());\n  cs3.setMaxIterations(1).compute(A);\n  VERIFY_IS_EQUAL(cs3.info(), size > 1 ? NoConvergence : Success);\n  VERIFY_IS_EQUAL(cs3.getMaxIterations(), 1);\n\n  MatrixType Atriangular = A;\n  Atriangular.template triangularView<StrictlyLower>().setZero(); \n  cs3.setMaxIterations(1).compute(Atriangular); // triangular matrices do not need any iterations\n  VERIFY_IS_EQUAL(cs3.info(), Success);\n  VERIFY_IS_EQUAL(cs3.matrixT(), Atriangular.template cast<ComplexScalar>());\n  VERIFY_IS_EQUAL(cs3.matrixU(), ComplexMatrixType::Identity(size, size));\n\n  // Test computation of only T, not U\n  ComplexSchur<MatrixType> csOnlyT(A, false);\n  VERIFY_IS_EQUAL(csOnlyT.info(), Success);\n  VERIFY_IS_EQUAL(cs1.matrixT(), csOnlyT.matrixT());\n  VERIFY_RAISES_ASSERT(csOnlyT.matrixU());\n\n  if (size > 1 && size < 20)\n  {\n    // Test matrix with NaN\n    A(0,0) = std::numeric_limits<typename MatrixType::RealScalar>::quiet_NaN();\n    ComplexSchur<MatrixType> csNaN(A);\n    VERIFY_IS_EQUAL(csNaN.info(), NoConvergence);\n  }\n}\n\nEIGEN_DECLARE_TEST(schur_complex)\n{\n  CALL_SUBTEST_1(( schur<Matrix4cd>() ));\n  CALL_SUBTEST_2(( schur<MatrixXcf>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4)) ));\n  CALL_SUBTEST_3(( schur<Matrix<std::complex<float>, 1, 1> >() ));\n  CALL_SUBTEST_4(( schur<Matrix<float, 3, 3, Eigen::RowMajor> >() ));\n\n  // Test problem size constructors\n  CALL_SUBTEST_5(ComplexSchur<MatrixXf>(10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/schur_real.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010,2012 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <limits>\n#include <Eigen/Eigenvalues>\n\ntemplate<typename MatrixType> void verifyIsQuasiTriangular(const MatrixType& T)\n{\n  const Index size = T.cols();\n  typedef typename MatrixType::Scalar Scalar;\n\n  // Check T is lower Hessenberg\n  for(int row = 2; row < size; ++row) {\n    for(int col = 0; col < row - 1; ++col) {\n      VERIFY(T(row,col) == Scalar(0));\n    }\n  }\n\n  // Check that any non-zero on the subdiagonal is followed by a zero and is\n  // part of a 2x2 diagonal block with imaginary eigenvalues.\n  for(int row = 1; row < size; ++row) {\n    if (T(row,row-1) != Scalar(0)) {\n      VERIFY(row == size-1 || T(row+1,row) == 0);\n      Scalar tr = T(row-1,row-1) + T(row,row);\n      Scalar det = T(row-1,row-1) * T(row,row) - T(row-1,row) * T(row,row-1);\n      VERIFY(4 * det > tr * tr);\n    }\n  }\n}\n\ntemplate<typename MatrixType> void schur(int size = MatrixType::ColsAtCompileTime)\n{\n  // Test basic functionality: T is quasi-triangular and A = U T U*\n  for(int counter = 0; counter < g_repeat; ++counter) {\n    MatrixType A = MatrixType::Random(size, size);\n    RealSchur<MatrixType> schurOfA(A);\n    VERIFY_IS_EQUAL(schurOfA.info(), Success);\n    MatrixType U = schurOfA.matrixU();\n    MatrixType T = schurOfA.matrixT();\n    verifyIsQuasiTriangular(T);\n    VERIFY_IS_APPROX(A, U * T * U.transpose());\n  }\n\n  // Test asserts when not initialized\n  RealSchur<MatrixType> rsUninitialized;\n  VERIFY_RAISES_ASSERT(rsUninitialized.matrixT());\n  VERIFY_RAISES_ASSERT(rsUninitialized.matrixU());\n  VERIFY_RAISES_ASSERT(rsUninitialized.info());\n  \n  // Test whether compute() and constructor returns same result\n  MatrixType A = MatrixType::Random(size, size);\n  RealSchur<MatrixType> rs1;\n  rs1.compute(A);\n  RealSchur<MatrixType> rs2(A);\n  VERIFY_IS_EQUAL(rs1.info(), Success);\n  VERIFY_IS_EQUAL(rs2.info(), Success);\n  VERIFY_IS_EQUAL(rs1.matrixT(), rs2.matrixT());\n  VERIFY_IS_EQUAL(rs1.matrixU(), rs2.matrixU());\n\n  // Test maximum number of iterations\n  RealSchur<MatrixType> rs3;\n  rs3.setMaxIterations(RealSchur<MatrixType>::m_maxIterationsPerRow * size).compute(A);\n  VERIFY_IS_EQUAL(rs3.info(), Success);\n  VERIFY_IS_EQUAL(rs3.matrixT(), rs1.matrixT());\n  VERIFY_IS_EQUAL(rs3.matrixU(), rs1.matrixU());\n  if (size > 2) {\n    rs3.setMaxIterations(1).compute(A);\n    VERIFY_IS_EQUAL(rs3.info(), NoConvergence);\n    VERIFY_IS_EQUAL(rs3.getMaxIterations(), 1);\n  }\n\n  MatrixType Atriangular = A;\n  Atriangular.template triangularView<StrictlyLower>().setZero(); \n  rs3.setMaxIterations(1).compute(Atriangular); // triangular matrices do not need any iterations\n  VERIFY_IS_EQUAL(rs3.info(), Success);\n  VERIFY_IS_APPROX(rs3.matrixT(), Atriangular); // approx because of scaling...\n  VERIFY_IS_EQUAL(rs3.matrixU(), MatrixType::Identity(size, size));\n\n  // Test computation of only T, not U\n  RealSchur<MatrixType> rsOnlyT(A, false);\n  VERIFY_IS_EQUAL(rsOnlyT.info(), Success);\n  VERIFY_IS_EQUAL(rs1.matrixT(), rsOnlyT.matrixT());\n  VERIFY_RAISES_ASSERT(rsOnlyT.matrixU());\n\n  if (size > 2 && size < 20)\n  {\n    // Test matrix with NaN\n    A(0,0) = std::numeric_limits<typename MatrixType::Scalar>::quiet_NaN();\n    RealSchur<MatrixType> rsNaN(A);\n    VERIFY_IS_EQUAL(rsNaN.info(), NoConvergence);\n  }\n}\n\nEIGEN_DECLARE_TEST(schur_real)\n{\n  CALL_SUBTEST_1(( schur<Matrix4f>() ));\n  CALL_SUBTEST_2(( schur<MatrixXd>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4)) ));\n  CALL_SUBTEST_3(( schur<Matrix<float, 1, 1> >() ));\n  CALL_SUBTEST_4(( schur<Matrix<double, 3, 3, Eigen::RowMajor> >() ));\n\n  // Test problem size constructors\n  CALL_SUBTEST_5(RealSchur<MatrixXf>(10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/selfadjoint.cpp",
    "content": "// This file is triangularView of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define TEST_CHECK_STATIC_ASSERTIONS\n#include \"main.h\"\n\n// This file tests the basic selfadjointView API,\n// the related products and decompositions are tested in specific files.\n\ntemplate<typename MatrixType> void selfadjoint(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols),\n             m4(rows, cols);\n\n  m1.diagonal() = m1.diagonal().real().template cast<Scalar>();\n\n  // check selfadjoint to dense\n  m3 = m1.template selfadjointView<Upper>();\n  VERIFY_IS_APPROX(MatrixType(m3.template triangularView<Upper>()), MatrixType(m1.template triangularView<Upper>()));\n  VERIFY_IS_APPROX(m3, m3.adjoint());\n\n  m3 = m1.template selfadjointView<Lower>();\n  VERIFY_IS_APPROX(MatrixType(m3.template triangularView<Lower>()), MatrixType(m1.template triangularView<Lower>()));\n  VERIFY_IS_APPROX(m3, m3.adjoint());\n\n  m3 = m1.template selfadjointView<Upper>();\n  m4 = m2;\n  m4 += m1.template selfadjointView<Upper>();\n  VERIFY_IS_APPROX(m4, m2+m3);\n\n  m3 = m1.template selfadjointView<Lower>();\n  m4 = m2;\n  m4 -= m1.template selfadjointView<Lower>();\n  VERIFY_IS_APPROX(m4, m2-m3);\n\n  VERIFY_RAISES_STATIC_ASSERT(m2.template selfadjointView<StrictlyUpper>());\n  VERIFY_RAISES_STATIC_ASSERT(m2.template selfadjointView<UnitLower>());\n}\n\nvoid bug_159()\n{\n  Matrix3d m = Matrix3d::Random().selfadjointView<Lower>();\n  EIGEN_UNUSED_VARIABLE(m)\n}\n\nEIGEN_DECLARE_TEST(selfadjoint)\n{\n  for(int i = 0; i < g_repeat ; i++)\n  {\n    int s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE);\n\n    CALL_SUBTEST_1( selfadjoint(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( selfadjoint(Matrix<float, 2, 2>()) );\n    CALL_SUBTEST_3( selfadjoint(Matrix3cf()) );\n    CALL_SUBTEST_4( selfadjoint(MatrixXcd(s,s)) );\n    CALL_SUBTEST_5( selfadjoint(Matrix<float,Dynamic,Dynamic,RowMajor>(s, s)) );\n    \n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n  }\n  \n  CALL_SUBTEST_1( bug_159() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/simplicial_cholesky.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"sparse_solver.h\"\n\ntemplate<typename T, typename I_, int flag> void test_simplicial_cholesky_T()\n{\n  typedef SparseMatrix<T,flag,I_> SparseMatrixType;\n  SimplicialCholesky<SparseMatrixType, Lower> chol_colmajor_lower_amd;\n  SimplicialCholesky<SparseMatrixType, Upper> chol_colmajor_upper_amd;\n  SimplicialLLT<     SparseMatrixType, Lower> llt_colmajor_lower_amd;\n  SimplicialLLT<     SparseMatrixType, Upper> llt_colmajor_upper_amd;\n  SimplicialLDLT<    SparseMatrixType, Lower> ldlt_colmajor_lower_amd;\n  SimplicialLDLT<    SparseMatrixType, Upper> ldlt_colmajor_upper_amd;\n  SimplicialLDLT<    SparseMatrixType, Lower, NaturalOrdering<I_> > ldlt_colmajor_lower_nat;\n  SimplicialLDLT<    SparseMatrixType, Upper, NaturalOrdering<I_> > ldlt_colmajor_upper_nat;\n\n  check_sparse_spd_solving(chol_colmajor_lower_amd);\n  check_sparse_spd_solving(chol_colmajor_upper_amd);\n  check_sparse_spd_solving(llt_colmajor_lower_amd);\n  check_sparse_spd_solving(llt_colmajor_upper_amd);\n  check_sparse_spd_solving(ldlt_colmajor_lower_amd);\n  check_sparse_spd_solving(ldlt_colmajor_upper_amd);\n  \n  check_sparse_spd_determinant(chol_colmajor_lower_amd);\n  check_sparse_spd_determinant(chol_colmajor_upper_amd);\n  check_sparse_spd_determinant(llt_colmajor_lower_amd);\n  check_sparse_spd_determinant(llt_colmajor_upper_amd);\n  check_sparse_spd_determinant(ldlt_colmajor_lower_amd);\n  check_sparse_spd_determinant(ldlt_colmajor_upper_amd);\n  \n  check_sparse_spd_solving(ldlt_colmajor_lower_nat, (std::min)(300,EIGEN_TEST_MAX_SIZE), 1000);\n  check_sparse_spd_solving(ldlt_colmajor_upper_nat, (std::min)(300,EIGEN_TEST_MAX_SIZE), 1000);\n}\n\nEIGEN_DECLARE_TEST(simplicial_cholesky)\n{\n  CALL_SUBTEST_11(( test_simplicial_cholesky_T<double,               int, ColMajor>() ));\n  CALL_SUBTEST_12(( test_simplicial_cholesky_T<std::complex<double>, int, ColMajor>() ));\n  CALL_SUBTEST_13(( test_simplicial_cholesky_T<double,          long int, ColMajor>() ));\n  CALL_SUBTEST_21(( test_simplicial_cholesky_T<double,               int, RowMajor>() ));\n  CALL_SUBTEST_22(( test_simplicial_cholesky_T<std::complex<double>, int, RowMajor>() ));\n  CALL_SUBTEST_23(( test_simplicial_cholesky_T<double,          long int, RowMajor>() ));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/sizeof.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void verifySizeOf(const MatrixType&)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  if (MatrixType::RowsAtCompileTime!=Dynamic && MatrixType::ColsAtCompileTime!=Dynamic)\n    VERIFY_IS_EQUAL(std::ptrdiff_t(sizeof(MatrixType)),std::ptrdiff_t(sizeof(Scalar))*std::ptrdiff_t(MatrixType::SizeAtCompileTime));\n  else\n    VERIFY_IS_EQUAL(sizeof(MatrixType),sizeof(Scalar*) + 2 * sizeof(Index));\n}\n\nEIGEN_DECLARE_TEST(sizeof)\n{\n  CALL_SUBTEST(verifySizeOf(Matrix<float, 1, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 2, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 3, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 4, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 5, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 6, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 7, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 8, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 9, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 10, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 11, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 12, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Vector2d()) );\n  CALL_SUBTEST(verifySizeOf(Vector4f()) );\n  CALL_SUBTEST(verifySizeOf(Matrix4d()) );\n  CALL_SUBTEST(verifySizeOf(Matrix<double, 4, 2>()) );\n  CALL_SUBTEST(verifySizeOf(Matrix<bool, 7, 5>()) );\n  CALL_SUBTEST(verifySizeOf(MatrixXcf(3, 3)) );\n  CALL_SUBTEST(verifySizeOf(MatrixXi(8, 12)) );\n  CALL_SUBTEST(verifySizeOf(MatrixXcd(20, 20)) );\n  CALL_SUBTEST(verifySizeOf(Matrix<float, 100, 100>()) );\n  \n  VERIFY(sizeof(std::complex<float>) == 2*sizeof(float));\n  VERIFY(sizeof(std::complex<double>) == 2*sizeof(double));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/sizeoverflow.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#define VERIFY_THROWS_BADALLOC(a) {                           \\\n    bool threw = false;                                       \\\n    try {                                                     \\\n      a;                                                      \\\n    }                                                         \\\n    catch (std::bad_alloc&) { threw = true; }                 \\\n    VERIFY(threw && \"should have thrown bad_alloc: \" #a);     \\\n  }\n\ntemplate<typename MatrixType>\nvoid triggerMatrixBadAlloc(Index rows, Index cols)\n{\n  VERIFY_THROWS_BADALLOC( MatrixType m(rows, cols) );\n  VERIFY_THROWS_BADALLOC( MatrixType m; m.resize(rows, cols) );\n  VERIFY_THROWS_BADALLOC( MatrixType m; m.conservativeResize(rows, cols) );\n}\n\ntemplate<typename VectorType>\nvoid triggerVectorBadAlloc(Index size)\n{\n  VERIFY_THROWS_BADALLOC( VectorType v(size) );\n  VERIFY_THROWS_BADALLOC( VectorType v; v.resize(size) );\n  VERIFY_THROWS_BADALLOC( VectorType v; v.conservativeResize(size) );\n}\n\nEIGEN_DECLARE_TEST(sizeoverflow)\n{\n  // there are 2 levels of overflow checking. first in PlainObjectBase.h we check for overflow in rows*cols computations.\n  // this is tested in tests of the form times_itself_gives_0 * times_itself_gives_0\n  // Then in Memory.h we check for overflow in size * sizeof(T) computations.\n  // this is tested in tests of the form times_4_gives_0 * sizeof(float)\n  \n  size_t times_itself_gives_0 = size_t(1) << (8 * sizeof(Index) / 2);\n  VERIFY(times_itself_gives_0 * times_itself_gives_0 == 0);\n\n  size_t times_4_gives_0 = size_t(1) << (8 * sizeof(Index) - 2);\n  VERIFY(times_4_gives_0 * 4 == 0);\n\n  size_t times_8_gives_0 = size_t(1) << (8 * sizeof(Index) - 3);\n  VERIFY(times_8_gives_0 * 8 == 0);\n\n  triggerMatrixBadAlloc<MatrixXf>(times_itself_gives_0, times_itself_gives_0);\n  triggerMatrixBadAlloc<MatrixXf>(times_itself_gives_0 / 4, times_itself_gives_0);\n  triggerMatrixBadAlloc<MatrixXf>(times_4_gives_0, 1);\n\n  triggerMatrixBadAlloc<MatrixXd>(times_itself_gives_0, times_itself_gives_0);\n  triggerMatrixBadAlloc<MatrixXd>(times_itself_gives_0 / 8, times_itself_gives_0);\n  triggerMatrixBadAlloc<MatrixXd>(times_8_gives_0, 1);\n  \n  triggerVectorBadAlloc<VectorXf>(times_4_gives_0);\n  \n  triggerVectorBadAlloc<VectorXd>(times_8_gives_0);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/smallvectors.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_STATIC_ASSERT\n#include \"main.h\"\n\ntemplate<typename Scalar> void smallVectors()\n{\n  typedef Matrix<Scalar, 1, 2> V2;\n  typedef Matrix<Scalar, 3, 1> V3;\n  typedef Matrix<Scalar, 1, 4> V4;\n  typedef Matrix<Scalar, Dynamic, 1> VX;\n  Scalar x1 = internal::random<Scalar>(),\n         x2 = internal::random<Scalar>(),\n         x3 = internal::random<Scalar>(),\n         x4 = internal::random<Scalar>();\n  V2 v2(x1, x2);\n  V3 v3(x1, x2, x3);\n  V4 v4(x1, x2, x3, x4);\n  VERIFY_IS_APPROX(x1, v2.x());\n  VERIFY_IS_APPROX(x1, v3.x());\n  VERIFY_IS_APPROX(x1, v4.x());\n  VERIFY_IS_APPROX(x2, v2.y());\n  VERIFY_IS_APPROX(x2, v3.y());\n  VERIFY_IS_APPROX(x2, v4.y());\n  VERIFY_IS_APPROX(x3, v3.z());\n  VERIFY_IS_APPROX(x3, v4.z());\n  VERIFY_IS_APPROX(x4, v4.w());\n\n  if (!NumTraits<Scalar>::IsInteger)\n  {\n    VERIFY_RAISES_ASSERT(V3(2, 1))\n    VERIFY_RAISES_ASSERT(V3(3, 2))\n    VERIFY_RAISES_ASSERT(V3(Scalar(3), 1))\n    VERIFY_RAISES_ASSERT(V3(3, Scalar(1)))\n    VERIFY_RAISES_ASSERT(V3(Scalar(3), Scalar(1)))\n    VERIFY_RAISES_ASSERT(V3(Scalar(123), Scalar(123)))\n\n    VERIFY_RAISES_ASSERT(V4(1, 3))\n    VERIFY_RAISES_ASSERT(V4(2, 4))\n    VERIFY_RAISES_ASSERT(V4(1, Scalar(4)))\n    VERIFY_RAISES_ASSERT(V4(Scalar(1), 4))\n    VERIFY_RAISES_ASSERT(V4(Scalar(1), Scalar(4)))\n    VERIFY_RAISES_ASSERT(V4(Scalar(123), Scalar(123)))\n\n    VERIFY_RAISES_ASSERT(VX(3, 2))\n    VERIFY_RAISES_ASSERT(VX(Scalar(3), 1))\n    VERIFY_RAISES_ASSERT(VX(3, Scalar(1)))\n    VERIFY_RAISES_ASSERT(VX(Scalar(3), Scalar(1)))\n    VERIFY_RAISES_ASSERT(VX(Scalar(123), Scalar(123)))\n  }\n}\n\nEIGEN_DECLARE_TEST(smallvectors)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST(smallVectors<int>() );\n    CALL_SUBTEST(smallVectors<float>() );\n    CALL_SUBTEST(smallVectors<double>() );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/solverbase.h",
    "content": "#ifndef TEST_SOLVERBASE_H\n#define TEST_SOLVERBASE_H\n\ntemplate<typename DstType, typename RhsType, typename MatrixType, typename SolverType>\nvoid check_solverbase(const MatrixType& matrix, const SolverType& solver, Index rows, Index cols, Index cols2)\n{\n  // solve\n  DstType m2               = DstType::Random(cols,cols2);\n  RhsType m3               = matrix*m2;\n  DstType solver_solution  = DstType::Random(cols,cols2);\n  solver._solve_impl(m3, solver_solution);\n  VERIFY_IS_APPROX(m3, matrix*solver_solution);\n  solver_solution          = DstType::Random(cols,cols2);\n  solver_solution          = solver.solve(m3);\n  VERIFY_IS_APPROX(m3, matrix*solver_solution);\n  // test solve with transposed\n  m3                       = RhsType::Random(rows,cols2);\n  m2                       = matrix.transpose()*m3;\n  RhsType solver_solution2 = RhsType::Random(rows,cols2);\n  solver.template _solve_impl_transposed<false>(m2, solver_solution2);\n  VERIFY_IS_APPROX(m2, matrix.transpose()*solver_solution2);\n  solver_solution2         = RhsType::Random(rows,cols2);\n  solver_solution2         = solver.transpose().solve(m2);\n  VERIFY_IS_APPROX(m2, matrix.transpose()*solver_solution2);\n  // test solve with conjugate transposed\n  m3                       = RhsType::Random(rows,cols2);\n  m2                       = matrix.adjoint()*m3;\n  solver_solution2         = RhsType::Random(rows,cols2);\n  solver.template _solve_impl_transposed<true>(m2, solver_solution2);\n  VERIFY_IS_APPROX(m2, matrix.adjoint()*solver_solution2);\n  solver_solution2         = RhsType::Random(rows,cols2);\n  solver_solution2         = solver.adjoint().solve(m2);\n  VERIFY_IS_APPROX(m2, matrix.adjoint()*solver_solution2);\n  // test with temporary expression as rhs\n  m2 = DstType::Random(cols,cols2);\n  solver_solution = solver.solve(matrix*m2);\n  VERIFY_IS_APPROX(matrix*m2, matrix*solver_solution);\n}\n\n#endif // TEST_SOLVERBASE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/sparse.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_TESTSPARSE_H\n#define EIGEN_TESTSPARSE_H\n\n#define EIGEN_YES_I_KNOW_SPARSE_MODULE_IS_NOT_STABLE_YET\n\n#include \"main.h\"\n\n#if EIGEN_HAS_CXX11\n\n#ifdef min\n#undef min\n#endif\n\n#ifdef max\n#undef max\n#endif\n\n#include <unordered_map>\n#define EIGEN_UNORDERED_MAP_SUPPORT\n\n#endif\n\n#include <Eigen/Cholesky>\n#include <Eigen/LU>\n#include <Eigen/Sparse>\n\nenum {\n  ForceNonZeroDiag = 1,\n  MakeLowerTriangular = 2,\n  MakeUpperTriangular = 4,\n  ForceRealDiag = 8\n};\n\n/* Initializes both a sparse and dense matrix with same random values,\n * and a ratio of \\a density non zero entries.\n * \\param flags is a union of ForceNonZeroDiag, MakeLowerTriangular and MakeUpperTriangular\n *        allowing to control the shape of the matrix.\n * \\param zeroCoords and nonzeroCoords allows to get the coordinate lists of the non zero,\n *        and zero coefficients respectively.\n */\ntemplate<typename Scalar,int Opt1,int Opt2,typename StorageIndex> void\ninitSparse(double density,\n           Matrix<Scalar,Dynamic,Dynamic,Opt1>& refMat,\n           SparseMatrix<Scalar,Opt2,StorageIndex>& sparseMat,\n           int flags = 0,\n           std::vector<Matrix<StorageIndex,2,1> >* zeroCoords = 0,\n           std::vector<Matrix<StorageIndex,2,1> >* nonzeroCoords = 0)\n{\n  enum { IsRowMajor = SparseMatrix<Scalar,Opt2,StorageIndex>::IsRowMajor };\n  sparseMat.setZero();\n  //sparseMat.reserve(int(refMat.rows()*refMat.cols()*density));\n  sparseMat.reserve(VectorXi::Constant(IsRowMajor ? refMat.rows() : refMat.cols(), int((1.5*density)*(IsRowMajor?refMat.cols():refMat.rows()))));\n  \n  for(Index j=0; j<sparseMat.outerSize(); j++)\n  {\n    //sparseMat.startVec(j);\n    for(Index i=0; i<sparseMat.innerSize(); i++)\n    {\n      Index ai(i), aj(j);\n      if(IsRowMajor)\n        std::swap(ai,aj);\n      Scalar v = (internal::random<double>(0,1) < density) ? internal::random<Scalar>() : Scalar(0);\n      if ((flags&ForceNonZeroDiag) && (i==j))\n      {\n        // FIXME: the following is too conservative\n        v = internal::random<Scalar>()*Scalar(3.);\n        v = v*v;\n        if(numext::real(v)>0) v += Scalar(5);\n        else                  v -= Scalar(5);\n      }\n      if ((flags & MakeLowerTriangular) && aj>ai)\n        v = Scalar(0);\n      else if ((flags & MakeUpperTriangular) && aj<ai)\n        v = Scalar(0);\n\n      if ((flags&ForceRealDiag) && (i==j))\n        v = numext::real(v);\n\n      if (v!=Scalar(0))\n      {\n        //sparseMat.insertBackByOuterInner(j,i) = v;\n        sparseMat.insertByOuterInner(j,i) = v;\n        if (nonzeroCoords)\n          nonzeroCoords->push_back(Matrix<StorageIndex,2,1> (ai,aj));\n      }\n      else if (zeroCoords)\n      {\n        zeroCoords->push_back(Matrix<StorageIndex,2,1> (ai,aj));\n      }\n      refMat(ai,aj) = v;\n    }\n  }\n  //sparseMat.finalize();\n}\n\ntemplate<typename Scalar,int Opt1,int Opt2,typename Index> void\ninitSparse(double density,\n           Matrix<Scalar,Dynamic,Dynamic, Opt1>& refMat,\n           DynamicSparseMatrix<Scalar, Opt2, Index>& sparseMat,\n           int flags = 0,\n           std::vector<Matrix<Index,2,1> >* zeroCoords = 0,\n           std::vector<Matrix<Index,2,1> >* nonzeroCoords = 0)\n{\n  enum { IsRowMajor = DynamicSparseMatrix<Scalar,Opt2,Index>::IsRowMajor };\n  sparseMat.setZero();\n  sparseMat.reserve(int(refMat.rows()*refMat.cols()*density));\n  for(int j=0; j<sparseMat.outerSize(); j++)\n  {\n    sparseMat.startVec(j); // not needed for DynamicSparseMatrix\n    for(int i=0; i<sparseMat.innerSize(); i++)\n    {\n      int ai(i), aj(j);\n      if(IsRowMajor)\n        std::swap(ai,aj);\n      Scalar v = (internal::random<double>(0,1) < density) ? internal::random<Scalar>() : Scalar(0);\n      if ((flags&ForceNonZeroDiag) && (i==j))\n      {\n        v = internal::random<Scalar>()*Scalar(3.);\n        v = v*v + Scalar(5.);\n      }\n      if ((flags & MakeLowerTriangular) && aj>ai)\n        v = Scalar(0);\n      else if ((flags & MakeUpperTriangular) && aj<ai)\n        v = Scalar(0);\n\n      if ((flags&ForceRealDiag) && (i==j))\n        v = numext::real(v);\n\n      if (v!=Scalar(0))\n      {\n        sparseMat.insertBackByOuterInner(j,i) = v;\n        if (nonzeroCoords)\n          nonzeroCoords->push_back(Matrix<Index,2,1> (ai,aj));\n      }\n      else if (zeroCoords)\n      {\n        zeroCoords->push_back(Matrix<Index,2,1> (ai,aj));\n      }\n      refMat(ai,aj) = v;\n    }\n  }\n  sparseMat.finalize();\n}\n\ntemplate<typename Scalar,int Options,typename Index> void\ninitSparse(double density,\n           Matrix<Scalar,Dynamic,1>& refVec,\n           SparseVector<Scalar,Options,Index>& sparseVec,\n           std::vector<int>* zeroCoords = 0,\n           std::vector<int>* nonzeroCoords = 0)\n{\n  sparseVec.reserve(int(refVec.size()*density));\n  sparseVec.setZero();\n  for(int i=0; i<refVec.size(); i++)\n  {\n    Scalar v = (internal::random<double>(0,1) < density) ? internal::random<Scalar>() : Scalar(0);\n    if (v!=Scalar(0))\n    {\n      sparseVec.insertBack(i) = v;\n      if (nonzeroCoords)\n        nonzeroCoords->push_back(i);\n    }\n    else if (zeroCoords)\n        zeroCoords->push_back(i);\n    refVec[i] = v;\n  }\n}\n\ntemplate<typename Scalar,int Options,typename Index> void\ninitSparse(double density,\n           Matrix<Scalar,1,Dynamic>& refVec,\n           SparseVector<Scalar,Options,Index>& sparseVec,\n           std::vector<int>* zeroCoords = 0,\n           std::vector<int>* nonzeroCoords = 0)\n{\n  sparseVec.reserve(int(refVec.size()*density));\n  sparseVec.setZero();\n  for(int i=0; i<refVec.size(); i++)\n  {\n    Scalar v = (internal::random<double>(0,1) < density) ? internal::random<Scalar>() : Scalar(0);\n    if (v!=Scalar(0))\n    {\n      sparseVec.insertBack(i) = v;\n      if (nonzeroCoords)\n        nonzeroCoords->push_back(i);\n    }\n    else if (zeroCoords)\n        zeroCoords->push_back(i);\n    refVec[i] = v;\n  }\n}\n\n\n#include <unsupported/Eigen/SparseExtra>\n#endif // EIGEN_TESTSPARSE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/sparseLM.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Desire Nuentsa <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n#include <iostream>\n#include <fstream>\n#include <iomanip>\n\n#include \"main.h\"\n#include <Eigen/LevenbergMarquardt>\n\nusing namespace std;\nusing namespace Eigen;\n\ntemplate <typename Scalar>\nstruct sparseGaussianTest : SparseFunctor<Scalar, int>\n{\n  typedef Matrix<Scalar,Dynamic,1> VectorType;\n  typedef SparseFunctor<Scalar,int> Base;\n  typedef typename Base::JacobianType JacobianType;\n  sparseGaussianTest(int inputs, int values) : SparseFunctor<Scalar,int>(inputs,values)\n  { }\n  \n  VectorType model(const VectorType& uv, VectorType& x)\n  {\n    VectorType y; //Change this to use expression template\n    int m = Base::values(); \n    int n = Base::inputs();\n    eigen_assert(uv.size()%2 == 0);\n    eigen_assert(uv.size() == n);\n    eigen_assert(x.size() == m);\n    y.setZero(m);\n    int half = n/2;\n    VectorBlock<const VectorType> u(uv, 0, half);\n    VectorBlock<const VectorType> v(uv, half, half);\n    Scalar coeff;\n    for (int j = 0; j < m; j++)\n    {\n      for (int i = 0; i < half; i++) \n      {\n        coeff = (x(j)-i)/v(i);\n        coeff *= coeff;\n        if (coeff < 1. && coeff > 0.)\n          y(j) += u(i)*std::pow((1-coeff), 2);\n      }\n    }\n    return y;\n  }\n  void initPoints(VectorType& uv_ref, VectorType& x)\n  {\n    m_x = x;\n    m_y = this->model(uv_ref,x);\n  }\n  int operator()(const VectorType& uv, VectorType& fvec)\n  {\n    int m = Base::values(); \n    int n = Base::inputs();\n    eigen_assert(uv.size()%2 == 0);\n    eigen_assert(uv.size() == n);\n    int half = n/2;\n    VectorBlock<const VectorType> u(uv, 0, half);\n    VectorBlock<const VectorType> v(uv, half, half);\n    fvec = m_y;\n    Scalar coeff;\n    for (int j = 0; j < m; j++)\n    {\n      for (int i = 0; i < half; i++)\n      {\n        coeff = (m_x(j)-i)/v(i);\n        coeff *= coeff;\n        if (coeff < 1. && coeff > 0.)\n          fvec(j) -= u(i)*std::pow((1-coeff), 2);\n      }\n    }\n    return 0;\n  }\n  \n  int df(const VectorType& uv, JacobianType& fjac)\n  {\n    int m = Base::values(); \n    int n = Base::inputs();\n    eigen_assert(n == uv.size());\n    eigen_assert(fjac.rows() == m);\n    eigen_assert(fjac.cols() == n);\n    int half = n/2;\n    VectorBlock<const VectorType> u(uv, 0, half);\n    VectorBlock<const VectorType> v(uv, half, half);\n    Scalar coeff;\n    \n    //Derivatives with respect to u\n    for (int col = 0; col < half; col++)\n    {\n      for (int row = 0; row < m; row++)\n      {\n        coeff = (m_x(row)-col)/v(col);\n          coeff = coeff*coeff;\n        if(coeff < 1. && coeff > 0.)\n        {\n          fjac.coeffRef(row,col) = -(1-coeff)*(1-coeff);\n        }\n      }\n    }\n    //Derivatives with respect to v\n    for (int col = 0; col < half; col++)\n    {\n      for (int row = 0; row < m; row++)\n      {\n        coeff = (m_x(row)-col)/v(col);\n        coeff = coeff*coeff;\n        if(coeff < 1. && coeff > 0.)\n        {\n          fjac.coeffRef(row,col+half) = -4 * (u(col)/v(col))*coeff*(1-coeff);\n        }\n      }\n    }\n    return 0;\n  }\n  \n  VectorType m_x, m_y; //Data points\n};\n\n\ntemplate<typename T>\nvoid test_sparseLM_T()\n{\n  typedef Matrix<T,Dynamic,1> VectorType;\n  \n  int inputs = 10;\n  int values = 2000;\n  sparseGaussianTest<T> sparse_gaussian(inputs, values);\n  VectorType uv(inputs),uv_ref(inputs);\n  VectorType x(values);\n  // Generate the reference solution \n  uv_ref << -2, 1, 4 ,8, 6, 1.8, 1.2, 1.1, 1.9 , 3;\n  //Generate the reference data points\n  x.setRandom();\n  x = 10*x;\n  x.array() += 10;\n  sparse_gaussian.initPoints(uv_ref, x);\n  \n  \n  // Generate the initial parameters \n  VectorBlock<VectorType> u(uv, 0, inputs/2); \n  VectorBlock<VectorType> v(uv, inputs/2, inputs/2);\n  v.setOnes();\n  //Generate u or Solve for u from v\n  u.setOnes();\n  \n  // Solve the optimization problem\n  LevenbergMarquardt<sparseGaussianTest<T> > lm(sparse_gaussian);\n  int info;\n//   info = lm.minimize(uv);\n  \n  VERIFY_IS_EQUAL(info,1);\n    // Do a step by step solution and save the residual \n  int maxiter = 200;\n  int iter = 0;\n  MatrixXd Err(values, maxiter);\n  MatrixXd Mod(values, maxiter);\n  LevenbergMarquardtSpace::Status status; \n  status = lm.minimizeInit(uv);\n  if (status==LevenbergMarquardtSpace::ImproperInputParameters)\n      return ;\n\n}\nEIGEN_DECLARE_TEST(sparseLM)\n{\n  CALL_SUBTEST_1(test_sparseLM_T<double>());\n  \n  // CALL_SUBTEST_2(test_sparseLM_T<std::complex<double>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/sparse_basic.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2008 Daniel Gomez Ferro <dgomezferro@gmail.com>\n// Copyright (C) 2013 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_TEST_INCLUDED_FROM_SPARSE_EXTRA\nstatic long g_realloc_count = 0;\n#define EIGEN_SPARSE_COMPRESSED_STORAGE_REALLOCATE_PLUGIN g_realloc_count++;\n\nstatic long g_dense_op_sparse_count = 0;\n#define EIGEN_SPARSE_ASSIGNMENT_FROM_DENSE_OP_SPARSE_PLUGIN g_dense_op_sparse_count++;\n#define EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_ADD_DENSE_PLUGIN g_dense_op_sparse_count+=10;\n#define EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_SUB_DENSE_PLUGIN g_dense_op_sparse_count+=20;\n#endif\n\n#include \"sparse.h\"\n\ntemplate<typename SparseMatrixType> void sparse_basic(const SparseMatrixType& ref)\n{\n  typedef typename SparseMatrixType::StorageIndex StorageIndex;\n  typedef Matrix<StorageIndex,2,1> Vector2;\n  \n  const Index rows = ref.rows();\n  const Index cols = ref.cols();\n  //const Index inner = ref.innerSize();\n  //const Index outer = ref.outerSize();\n\n  typedef typename SparseMatrixType::Scalar Scalar;\n  typedef typename SparseMatrixType::RealScalar RealScalar;\n  enum { Flags = SparseMatrixType::Flags };\n\n  double density = (std::max)(8./(rows*cols), 0.01);\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n  Scalar eps = 1e-6;\n\n  Scalar s1 = internal::random<Scalar>();\n  {\n    SparseMatrixType m(rows, cols);\n    DenseMatrix refMat = DenseMatrix::Zero(rows, cols);\n    DenseVector vec1 = DenseVector::Random(rows);\n\n    std::vector<Vector2> zeroCoords;\n    std::vector<Vector2> nonzeroCoords;\n    initSparse<Scalar>(density, refMat, m, 0, &zeroCoords, &nonzeroCoords);\n\n    // test coeff and coeffRef\n    for (std::size_t i=0; i<zeroCoords.size(); ++i)\n    {\n      VERIFY_IS_MUCH_SMALLER_THAN( m.coeff(zeroCoords[i].x(),zeroCoords[i].y()), eps );\n      if(internal::is_same<SparseMatrixType,SparseMatrix<Scalar,Flags> >::value)\n        VERIFY_RAISES_ASSERT( m.coeffRef(zeroCoords[i].x(),zeroCoords[i].y()) = 5 );\n    }\n    VERIFY_IS_APPROX(m, refMat);\n\n    if(!nonzeroCoords.empty()) {\n      m.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5);\n      refMat.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5);\n    }\n\n    VERIFY_IS_APPROX(m, refMat);\n\n      // test assertion\n      VERIFY_RAISES_ASSERT( m.coeffRef(-1,1) = 0 );\n      VERIFY_RAISES_ASSERT( m.coeffRef(0,m.cols()) = 0 );\n    }\n\n    // test insert (inner random)\n    {\n      DenseMatrix m1(rows,cols);\n      m1.setZero();\n      SparseMatrixType m2(rows,cols);\n      bool call_reserve = internal::random<int>()%2;\n      Index nnz = internal::random<int>(1,int(rows)/2);\n      if(call_reserve)\n      {\n        if(internal::random<int>()%2)\n          m2.reserve(VectorXi::Constant(m2.outerSize(), int(nnz)));\n        else\n          m2.reserve(m2.outerSize() * nnz);\n      }\n      g_realloc_count = 0;\n      for (Index j=0; j<cols; ++j)\n      {\n        for (Index k=0; k<nnz; ++k)\n        {\n          Index i = internal::random<Index>(0,rows-1);\n          if (m1.coeff(i,j)==Scalar(0))\n            m2.insert(i,j) = m1(i,j) = internal::random<Scalar>();\n        }\n      }\n      \n      if(call_reserve && !SparseMatrixType::IsRowMajor)\n      {\n        VERIFY(g_realloc_count==0);\n      }\n      \n      m2.finalize();\n      VERIFY_IS_APPROX(m2,m1);\n    }\n\n    // test insert (fully random)\n    {\n      DenseMatrix m1(rows,cols);\n      m1.setZero();\n      SparseMatrixType m2(rows,cols);\n      if(internal::random<int>()%2)\n        m2.reserve(VectorXi::Constant(m2.outerSize(), 2));\n      for (int k=0; k<rows*cols; ++k)\n      {\n        Index i = internal::random<Index>(0,rows-1);\n        Index j = internal::random<Index>(0,cols-1);\n        if ((m1.coeff(i,j)==Scalar(0)) && (internal::random<int>()%2))\n          m2.insert(i,j) = m1(i,j) = internal::random<Scalar>();\n        else\n        {\n          Scalar v = internal::random<Scalar>();\n          m2.coeffRef(i,j) += v;\n          m1(i,j) += v;\n        }\n      }\n      VERIFY_IS_APPROX(m2,m1);\n    }\n    \n    // test insert (un-compressed)\n    for(int mode=0;mode<4;++mode)\n    {\n      DenseMatrix m1(rows,cols);\n      m1.setZero();\n      SparseMatrixType m2(rows,cols);\n      VectorXi r(VectorXi::Constant(m2.outerSize(), ((mode%2)==0) ? int(m2.innerSize()) : std::max<int>(1,int(m2.innerSize())/8)));\n      m2.reserve(r);\n      for (Index k=0; k<rows*cols; ++k)\n      {\n        Index i = internal::random<Index>(0,rows-1);\n        Index j = internal::random<Index>(0,cols-1);\n        if (m1.coeff(i,j)==Scalar(0))\n          m2.insert(i,j) = m1(i,j) = internal::random<Scalar>();\n        if(mode==3)\n          m2.reserve(r);\n      }\n      if(internal::random<int>()%2)\n        m2.makeCompressed();\n      VERIFY_IS_APPROX(m2,m1);\n    }\n\n  // test basic computations\n  {\n    DenseMatrix refM1 = DenseMatrix::Zero(rows, cols);\n    DenseMatrix refM2 = DenseMatrix::Zero(rows, cols);\n    DenseMatrix refM3 = DenseMatrix::Zero(rows, cols);\n    DenseMatrix refM4 = DenseMatrix::Zero(rows, cols);\n    SparseMatrixType m1(rows, cols);\n    SparseMatrixType m2(rows, cols);\n    SparseMatrixType m3(rows, cols);\n    SparseMatrixType m4(rows, cols);\n    initSparse<Scalar>(density, refM1, m1);\n    initSparse<Scalar>(density, refM2, m2);\n    initSparse<Scalar>(density, refM3, m3);\n    initSparse<Scalar>(density, refM4, m4);\n\n    if(internal::random<bool>())\n      m1.makeCompressed();\n\n    Index m1_nnz = m1.nonZeros();\n\n    VERIFY_IS_APPROX(m1*s1, refM1*s1);\n    VERIFY_IS_APPROX(m1+m2, refM1+refM2);\n    VERIFY_IS_APPROX(m1+m2+m3, refM1+refM2+refM3);\n    VERIFY_IS_APPROX(m3.cwiseProduct(m1+m2), refM3.cwiseProduct(refM1+refM2));\n    VERIFY_IS_APPROX(m1*s1-m2, refM1*s1-refM2);\n    VERIFY_IS_APPROX(m4=m1/s1, refM1/s1);\n    VERIFY_IS_EQUAL(m4.nonZeros(), m1_nnz);\n\n    if(SparseMatrixType::IsRowMajor)\n      VERIFY_IS_APPROX(m1.innerVector(0).dot(refM2.row(0)), refM1.row(0).dot(refM2.row(0)));\n    else\n      VERIFY_IS_APPROX(m1.innerVector(0).dot(refM2.col(0)), refM1.col(0).dot(refM2.col(0)));\n\n    DenseVector rv = DenseVector::Random(m1.cols());\n    DenseVector cv = DenseVector::Random(m1.rows());\n    Index r = internal::random<Index>(0,m1.rows()-2);\n    Index c = internal::random<Index>(0,m1.cols()-1);\n    VERIFY_IS_APPROX(( m1.template block<1,Dynamic>(r,0,1,m1.cols()).dot(rv)) , refM1.row(r).dot(rv));\n    VERIFY_IS_APPROX(m1.row(r).dot(rv), refM1.row(r).dot(rv));\n    VERIFY_IS_APPROX(m1.col(c).dot(cv), refM1.col(c).dot(cv));\n\n    VERIFY_IS_APPROX(m1.conjugate(), refM1.conjugate());\n    VERIFY_IS_APPROX(m1.real(), refM1.real());\n\n    refM4.setRandom();\n    // sparse cwise* dense\n    VERIFY_IS_APPROX(m3.cwiseProduct(refM4), refM3.cwiseProduct(refM4));\n    // dense cwise* sparse\n    VERIFY_IS_APPROX(refM4.cwiseProduct(m3), refM4.cwiseProduct(refM3));\n//     VERIFY_IS_APPROX(m3.cwise()/refM4, refM3.cwise()/refM4);\n\n    // mixed sparse-dense\n    VERIFY_IS_APPROX(refM4 + m3, refM4 + refM3);\n    VERIFY_IS_APPROX(m3 + refM4, refM3 + refM4);\n    VERIFY_IS_APPROX(refM4 - m3, refM4 - refM3);\n    VERIFY_IS_APPROX(m3 - refM4, refM3 - refM4);\n    VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + RealScalar(0.5)*m3).eval(), RealScalar(0.5)*refM4 + RealScalar(0.5)*refM3);\n    VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + m3*RealScalar(0.5)).eval(), RealScalar(0.5)*refM4 + RealScalar(0.5)*refM3);\n    VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + m3.cwiseProduct(m3)).eval(), RealScalar(0.5)*refM4 + refM3.cwiseProduct(refM3));\n\n    VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + RealScalar(0.5)*m3).eval(), RealScalar(0.5)*refM4 + RealScalar(0.5)*refM3);\n    VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + m3*RealScalar(0.5)).eval(), RealScalar(0.5)*refM4 + RealScalar(0.5)*refM3);\n    VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + (m3+m3)).eval(), RealScalar(0.5)*refM4 + (refM3+refM3));\n    VERIFY_IS_APPROX(((refM3+m3)+RealScalar(0.5)*m3).eval(), RealScalar(0.5)*refM3 + (refM3+refM3));\n    VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + (refM3+m3)).eval(), RealScalar(0.5)*refM4 + (refM3+refM3));\n    VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + (m3+refM3)).eval(), RealScalar(0.5)*refM4 + (refM3+refM3));\n\n\n    VERIFY_IS_APPROX(m1.sum(), refM1.sum());\n\n    m4 = m1; refM4 = m4;\n\n    VERIFY_IS_APPROX(m1*=s1, refM1*=s1);\n    VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz);\n    VERIFY_IS_APPROX(m1/=s1, refM1/=s1);\n    VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz);\n\n    VERIFY_IS_APPROX(m1+=m2, refM1+=refM2);\n    VERIFY_IS_APPROX(m1-=m2, refM1-=refM2);\n\n    refM3 = refM1;\n    \n    VERIFY_IS_APPROX(refM1+=m2, refM3+=refM2);\n    VERIFY_IS_APPROX(refM1-=m2, refM3-=refM2);\n\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1 =m2+refM4, refM3 =refM2+refM4);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,10);\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1+=m2+refM4, refM3+=refM2+refM4);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,1);\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1-=m2+refM4, refM3-=refM2+refM4);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,1);\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1 =refM4+m2, refM3 =refM2+refM4);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,1);\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1+=refM4+m2, refM3+=refM2+refM4);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,1);\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1-=refM4+m2, refM3-=refM2+refM4);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,1);\n\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1 =m2-refM4, refM3 =refM2-refM4);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,20);\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1+=m2-refM4, refM3+=refM2-refM4);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,1);\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1-=m2-refM4, refM3-=refM2-refM4);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,1);\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1 =refM4-m2, refM3 =refM4-refM2);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,1);\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1+=refM4-m2, refM3+=refM4-refM2);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,1);\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1-=refM4-m2, refM3-=refM4-refM2);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,1);\n    refM3 = m3;\n\n    if (rows>=2 && cols>=2)\n    {\n      VERIFY_RAISES_ASSERT( m1 += m1.innerVector(0) );\n      VERIFY_RAISES_ASSERT( m1 -= m1.innerVector(0) );\n      VERIFY_RAISES_ASSERT( refM1 -= m1.innerVector(0) );\n      VERIFY_RAISES_ASSERT( refM1 += m1.innerVector(0) );\n    }\n    m1 = m4; refM1 = refM4;\n\n    // test aliasing\n    VERIFY_IS_APPROX((m1 = -m1), (refM1 = -refM1));\n    VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz);\n    m1 = m4; refM1 = refM4;\n    VERIFY_IS_APPROX((m1 = m1.transpose()), (refM1 = refM1.transpose().eval()));\n    VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz);\n    m1 = m4; refM1 = refM4;\n    VERIFY_IS_APPROX((m1 = -m1.transpose()), (refM1 = -refM1.transpose().eval()));\n    VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz);\n    m1 = m4; refM1 = refM4;\n    VERIFY_IS_APPROX((m1 += -m1), (refM1 += -refM1));\n    VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz);\n    m1 = m4; refM1 = refM4;\n\n    if(m1.isCompressed())\n    {\n      VERIFY_IS_APPROX(m1.coeffs().sum(), m1.sum());\n      m1.coeffs() += s1;\n      for(Index j = 0; j<m1.outerSize(); ++j)\n        for(typename SparseMatrixType::InnerIterator it(m1,j); it; ++it)\n          refM1(it.row(), it.col()) += s1;\n      VERIFY_IS_APPROX(m1, refM1);\n    }\n\n    // and/or\n    {\n      typedef SparseMatrix<bool, SparseMatrixType::Options, typename SparseMatrixType::StorageIndex> SpBool;\n      SpBool mb1 = m1.real().template cast<bool>();\n      SpBool mb2 = m2.real().template cast<bool>();\n      VERIFY_IS_EQUAL(mb1.template cast<int>().sum(), refM1.real().template cast<bool>().count());\n      VERIFY_IS_EQUAL((mb1 && mb2).template cast<int>().sum(), (refM1.real().template cast<bool>() && refM2.real().template cast<bool>()).count());\n      VERIFY_IS_EQUAL((mb1 || mb2).template cast<int>().sum(), (refM1.real().template cast<bool>() || refM2.real().template cast<bool>()).count());\n      SpBool mb3 = mb1 && mb2;\n      if(mb1.coeffs().all() && mb2.coeffs().all())\n      {\n        VERIFY_IS_EQUAL(mb3.nonZeros(), (refM1.real().template cast<bool>() && refM2.real().template cast<bool>()).count());\n      }\n    }\n  }\n\n  // test reverse iterators\n  {\n    DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols);\n    SparseMatrixType m2(rows, cols);\n    initSparse<Scalar>(density, refMat2, m2);\n    std::vector<Scalar> ref_value(m2.innerSize());\n    std::vector<Index> ref_index(m2.innerSize());\n    if(internal::random<bool>())\n      m2.makeCompressed();\n    for(Index j = 0; j<m2.outerSize(); ++j)\n    {\n      Index count_forward = 0;\n\n      for(typename SparseMatrixType::InnerIterator it(m2,j); it; ++it)\n      {\n        ref_value[ref_value.size()-1-count_forward] = it.value();\n        ref_index[ref_index.size()-1-count_forward] = it.index();\n        count_forward++;\n      }\n      Index count_reverse = 0;\n      for(typename SparseMatrixType::ReverseInnerIterator it(m2,j); it; --it)\n      {\n        VERIFY_IS_APPROX( std::abs(ref_value[ref_value.size()-count_forward+count_reverse])+1, std::abs(it.value())+1);\n        VERIFY_IS_EQUAL( ref_index[ref_index.size()-count_forward+count_reverse] , it.index());\n        count_reverse++;\n      }\n      VERIFY_IS_EQUAL(count_forward, count_reverse);\n    }\n  }\n\n  // test transpose\n  {\n    DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols);\n    SparseMatrixType m2(rows, cols);\n    initSparse<Scalar>(density, refMat2, m2);\n    VERIFY_IS_APPROX(m2.transpose().eval(), refMat2.transpose().eval());\n    VERIFY_IS_APPROX(m2.transpose(), refMat2.transpose());\n\n    VERIFY_IS_APPROX(SparseMatrixType(m2.adjoint()), refMat2.adjoint());\n    \n    // check isApprox handles opposite storage order\n    typename Transpose<SparseMatrixType>::PlainObject m3(m2);\n    VERIFY(m2.isApprox(m3));\n  }\n\n  // test prune\n  {\n    SparseMatrixType m2(rows, cols);\n    DenseMatrix refM2(rows, cols);\n    refM2.setZero();\n    int countFalseNonZero = 0;\n    int countTrueNonZero = 0;\n    m2.reserve(VectorXi::Constant(m2.outerSize(), int(m2.innerSize())));\n    for (Index j=0; j<m2.cols(); ++j)\n    {\n      for (Index i=0; i<m2.rows(); ++i)\n      {\n        float x = internal::random<float>(0,1);\n        if (x<0.1f)\n        {\n          // do nothing\n        }\n        else if (x<0.5f)\n        {\n          countFalseNonZero++;\n          m2.insert(i,j) = Scalar(0);\n        }\n        else\n        {\n          countTrueNonZero++;\n          m2.insert(i,j) = Scalar(1);\n          refM2(i,j) = Scalar(1);\n        }\n      }\n    }\n    if(internal::random<bool>())\n      m2.makeCompressed();\n    VERIFY(countFalseNonZero+countTrueNonZero == m2.nonZeros());\n    if(countTrueNonZero>0)\n      VERIFY_IS_APPROX(m2, refM2);\n    m2.prune(Scalar(1));\n    VERIFY(countTrueNonZero==m2.nonZeros());\n    VERIFY_IS_APPROX(m2, refM2);\n  }\n\n  // test setFromTriplets\n  {\n    typedef Triplet<Scalar,StorageIndex> TripletType;\n    std::vector<TripletType> triplets;\n    Index ntriplets = rows*cols;\n    triplets.reserve(ntriplets);\n    DenseMatrix refMat_sum  = DenseMatrix::Zero(rows,cols);\n    DenseMatrix refMat_prod = DenseMatrix::Zero(rows,cols);\n    DenseMatrix refMat_last = DenseMatrix::Zero(rows,cols);\n\n    for(Index i=0;i<ntriplets;++i)\n    {\n      StorageIndex r = internal::random<StorageIndex>(0,StorageIndex(rows-1));\n      StorageIndex c = internal::random<StorageIndex>(0,StorageIndex(cols-1));\n      Scalar v = internal::random<Scalar>();\n      triplets.push_back(TripletType(r,c,v));\n      refMat_sum(r,c) += v;\n      if(std::abs(refMat_prod(r,c))==0)\n        refMat_prod(r,c) = v;\n      else\n        refMat_prod(r,c) *= v;\n      refMat_last(r,c) = v;\n    }\n    SparseMatrixType m(rows,cols);\n    m.setFromTriplets(triplets.begin(), triplets.end());\n    VERIFY_IS_APPROX(m, refMat_sum);\n\n    m.setFromTriplets(triplets.begin(), triplets.end(), std::multiplies<Scalar>());\n    VERIFY_IS_APPROX(m, refMat_prod);\n#if (EIGEN_COMP_CXXVER >= 11)\n    m.setFromTriplets(triplets.begin(), triplets.end(), [] (Scalar,Scalar b) { return b; });\n    VERIFY_IS_APPROX(m, refMat_last);\n#endif\n  }\n  \n  // test Map\n  {\n    DenseMatrix refMat2(rows, cols), refMat3(rows, cols);\n    SparseMatrixType m2(rows, cols), m3(rows, cols);\n    initSparse<Scalar>(density, refMat2, m2);\n    initSparse<Scalar>(density, refMat3, m3);\n    {\n      Map<SparseMatrixType> mapMat2(m2.rows(), m2.cols(), m2.nonZeros(), m2.outerIndexPtr(), m2.innerIndexPtr(), m2.valuePtr(), m2.innerNonZeroPtr());\n      Map<SparseMatrixType> mapMat3(m3.rows(), m3.cols(), m3.nonZeros(), m3.outerIndexPtr(), m3.innerIndexPtr(), m3.valuePtr(), m3.innerNonZeroPtr());\n      VERIFY_IS_APPROX(mapMat2+mapMat3, refMat2+refMat3);\n      VERIFY_IS_APPROX(mapMat2+mapMat3, refMat2+refMat3);\n    }\n    {\n      MappedSparseMatrix<Scalar,SparseMatrixType::Options,StorageIndex> mapMat2(m2.rows(), m2.cols(), m2.nonZeros(), m2.outerIndexPtr(), m2.innerIndexPtr(), m2.valuePtr(), m2.innerNonZeroPtr());\n      MappedSparseMatrix<Scalar,SparseMatrixType::Options,StorageIndex> mapMat3(m3.rows(), m3.cols(), m3.nonZeros(), m3.outerIndexPtr(), m3.innerIndexPtr(), m3.valuePtr(), m3.innerNonZeroPtr());\n      VERIFY_IS_APPROX(mapMat2+mapMat3, refMat2+refMat3);\n      VERIFY_IS_APPROX(mapMat2+mapMat3, refMat2+refMat3);\n    }\n\n    Index i = internal::random<Index>(0,rows-1);\n    Index j = internal::random<Index>(0,cols-1);\n    m2.coeffRef(i,j) = 123;\n    if(internal::random<bool>())\n      m2.makeCompressed();\n    Map<SparseMatrixType> mapMat2(rows, cols, m2.nonZeros(), m2.outerIndexPtr(), m2.innerIndexPtr(), m2.valuePtr(),  m2.innerNonZeroPtr());\n    VERIFY_IS_EQUAL(m2.coeff(i,j),Scalar(123));\n    VERIFY_IS_EQUAL(mapMat2.coeff(i,j),Scalar(123));\n    mapMat2.coeffRef(i,j) = -123;\n    VERIFY_IS_EQUAL(m2.coeff(i,j),Scalar(-123));\n  }\n\n  // test triangularView\n  {\n    DenseMatrix refMat2(rows, cols), refMat3(rows, cols);\n    SparseMatrixType m2(rows, cols), m3(rows, cols);\n    initSparse<Scalar>(density, refMat2, m2);\n    refMat3 = refMat2.template triangularView<Lower>();\n    m3 = m2.template triangularView<Lower>();\n    VERIFY_IS_APPROX(m3, refMat3);\n\n    refMat3 = refMat2.template triangularView<Upper>();\n    m3 = m2.template triangularView<Upper>();\n    VERIFY_IS_APPROX(m3, refMat3);\n\n    {\n      refMat3 = refMat2.template triangularView<UnitUpper>();\n      m3 = m2.template triangularView<UnitUpper>();\n      VERIFY_IS_APPROX(m3, refMat3);\n\n      refMat3 = refMat2.template triangularView<UnitLower>();\n      m3 = m2.template triangularView<UnitLower>();\n      VERIFY_IS_APPROX(m3, refMat3);\n    }\n\n    refMat3 = refMat2.template triangularView<StrictlyUpper>();\n    m3 = m2.template triangularView<StrictlyUpper>();\n    VERIFY_IS_APPROX(m3, refMat3);\n\n    refMat3 = refMat2.template triangularView<StrictlyLower>();\n    m3 = m2.template triangularView<StrictlyLower>();\n    VERIFY_IS_APPROX(m3, refMat3);\n\n    // check sparse-triangular to dense\n    refMat3 = m2.template triangularView<StrictlyUpper>();\n    VERIFY_IS_APPROX(refMat3, DenseMatrix(refMat2.template triangularView<StrictlyUpper>()));\n  }\n  \n  // test selfadjointView\n  if(!SparseMatrixType::IsRowMajor)\n  {\n    DenseMatrix refMat2(rows, rows), refMat3(rows, rows);\n    SparseMatrixType m2(rows, rows), m3(rows, rows);\n    initSparse<Scalar>(density, refMat2, m2);\n    refMat3 = refMat2.template selfadjointView<Lower>();\n    m3 = m2.template selfadjointView<Lower>();\n    VERIFY_IS_APPROX(m3, refMat3);\n\n    refMat3 += refMat2.template selfadjointView<Lower>();\n    m3 += m2.template selfadjointView<Lower>();\n    VERIFY_IS_APPROX(m3, refMat3);\n\n    refMat3 -= refMat2.template selfadjointView<Lower>();\n    m3 -= m2.template selfadjointView<Lower>();\n    VERIFY_IS_APPROX(m3, refMat3);\n\n    // selfadjointView only works for square matrices:\n    SparseMatrixType m4(rows, rows+1);\n    VERIFY_RAISES_ASSERT(m4.template selfadjointView<Lower>());\n    VERIFY_RAISES_ASSERT(m4.template selfadjointView<Upper>());\n  }\n  \n  // test sparseView\n  {\n    DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows);\n    SparseMatrixType m2(rows, rows);\n    initSparse<Scalar>(density, refMat2, m2);\n    VERIFY_IS_APPROX(m2.eval(), refMat2.sparseView().eval());\n\n    // sparse view on expressions:\n    VERIFY_IS_APPROX((s1*m2).eval(), (s1*refMat2).sparseView().eval());\n    VERIFY_IS_APPROX((m2+m2).eval(), (refMat2+refMat2).sparseView().eval());\n    VERIFY_IS_APPROX((m2*m2).eval(), (refMat2.lazyProduct(refMat2)).sparseView().eval());\n    VERIFY_IS_APPROX((m2*m2).eval(), (refMat2*refMat2).sparseView().eval());\n  }\n\n  // test diagonal\n  {\n    DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols);\n    SparseMatrixType m2(rows, cols);\n    initSparse<Scalar>(density, refMat2, m2);\n    VERIFY_IS_APPROX(m2.diagonal(), refMat2.diagonal().eval());\n    DenseVector d = m2.diagonal();\n    VERIFY_IS_APPROX(d, refMat2.diagonal().eval());\n    d = m2.diagonal().array();\n    VERIFY_IS_APPROX(d, refMat2.diagonal().eval());\n    VERIFY_IS_APPROX(const_cast<const SparseMatrixType&>(m2).diagonal(), refMat2.diagonal().eval());\n    \n    initSparse<Scalar>(density, refMat2, m2, ForceNonZeroDiag);\n    m2.diagonal()      += refMat2.diagonal();\n    refMat2.diagonal() += refMat2.diagonal();\n    VERIFY_IS_APPROX(m2, refMat2);\n  }\n  \n  // test diagonal to sparse\n  {\n    DenseVector d = DenseVector::Random(rows);\n    DenseMatrix refMat2 = d.asDiagonal();\n    SparseMatrixType m2;\n    m2 = d.asDiagonal();\n    VERIFY_IS_APPROX(m2, refMat2);\n    SparseMatrixType m3(d.asDiagonal());\n    VERIFY_IS_APPROX(m3, refMat2);\n    refMat2 += d.asDiagonal();\n    m2 += d.asDiagonal();\n    VERIFY_IS_APPROX(m2, refMat2);\n    m2.setZero();       m2 += d.asDiagonal();\n    refMat2.setZero();  refMat2 += d.asDiagonal();\n    VERIFY_IS_APPROX(m2, refMat2);\n    m2.setZero();       m2 -= d.asDiagonal();\n    refMat2.setZero();  refMat2 -= d.asDiagonal();\n    VERIFY_IS_APPROX(m2, refMat2);\n\n    initSparse<Scalar>(density, refMat2, m2);\n    m2.makeCompressed();\n    m2 += d.asDiagonal();\n    refMat2 += d.asDiagonal();\n    VERIFY_IS_APPROX(m2, refMat2);\n\n    initSparse<Scalar>(density, refMat2, m2);\n    m2.makeCompressed();\n    VectorXi res(rows);\n    for(Index i=0; i<rows; ++i)\n      res(i) = internal::random<int>(0,3);\n    m2.reserve(res);\n    m2 -= d.asDiagonal();\n    refMat2 -= d.asDiagonal();\n    VERIFY_IS_APPROX(m2, refMat2);\n  }\n  \n  // test conservative resize\n  {\n      std::vector< std::pair<StorageIndex,StorageIndex> > inc;\n      if(rows > 3 && cols > 2)\n        inc.push_back(std::pair<StorageIndex,StorageIndex>(-3,-2));\n      inc.push_back(std::pair<StorageIndex,StorageIndex>(0,0));\n      inc.push_back(std::pair<StorageIndex,StorageIndex>(3,2));\n      inc.push_back(std::pair<StorageIndex,StorageIndex>(3,0));\n      inc.push_back(std::pair<StorageIndex,StorageIndex>(0,3));\n      inc.push_back(std::pair<StorageIndex,StorageIndex>(0,-1));\n      inc.push_back(std::pair<StorageIndex,StorageIndex>(-1,0));\n      inc.push_back(std::pair<StorageIndex,StorageIndex>(-1,-1));\n\n      for(size_t i = 0; i< inc.size(); i++) {\n        StorageIndex incRows = inc[i].first;\n        StorageIndex incCols = inc[i].second;\n        SparseMatrixType m1(rows, cols);\n        DenseMatrix refMat1 = DenseMatrix::Zero(rows, cols);\n        initSparse<Scalar>(density, refMat1, m1);\n\n        SparseMatrixType m2 = m1;\n        m2.makeCompressed();\n\n        m1.conservativeResize(rows+incRows, cols+incCols);\n        m2.conservativeResize(rows+incRows, cols+incCols);\n        refMat1.conservativeResize(rows+incRows, cols+incCols);\n        if (incRows > 0) refMat1.bottomRows(incRows).setZero();\n        if (incCols > 0) refMat1.rightCols(incCols).setZero();\n\n        VERIFY_IS_APPROX(m1, refMat1);\n        VERIFY_IS_APPROX(m2, refMat1);\n\n        // Insert new values\n        if (incRows > 0) \n          m1.insert(m1.rows()-1, 0) = refMat1(refMat1.rows()-1, 0) = 1;\n        if (incCols > 0) \n          m1.insert(0, m1.cols()-1) = refMat1(0, refMat1.cols()-1) = 1;\n\n        VERIFY_IS_APPROX(m1, refMat1);\n\n\n      }\n  }\n\n  // test Identity matrix\n  {\n    DenseMatrix refMat1 = DenseMatrix::Identity(rows, rows);\n    SparseMatrixType m1(rows, rows);\n    m1.setIdentity();\n    VERIFY_IS_APPROX(m1, refMat1);\n    for(int k=0; k<rows*rows/4; ++k)\n    {\n      Index i = internal::random<Index>(0,rows-1);\n      Index j = internal::random<Index>(0,rows-1);\n      Scalar v = internal::random<Scalar>();\n      m1.coeffRef(i,j) = v;\n      refMat1.coeffRef(i,j) = v;\n      VERIFY_IS_APPROX(m1, refMat1);\n      if(internal::random<Index>(0,10)<2)\n        m1.makeCompressed();\n    }\n    m1.setIdentity();\n    refMat1.setIdentity();\n    VERIFY_IS_APPROX(m1, refMat1);\n  }\n\n  // test array/vector of InnerIterator\n  {\n    typedef typename SparseMatrixType::InnerIterator IteratorType;\n\n    DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols);\n    SparseMatrixType m2(rows, cols);\n    initSparse<Scalar>(density, refMat2, m2);\n    IteratorType static_array[2];\n    static_array[0] = IteratorType(m2,0);\n    static_array[1] = IteratorType(m2,m2.outerSize()-1);\n    VERIFY( static_array[0] || m2.innerVector(static_array[0].outer()).nonZeros() == 0 );\n    VERIFY( static_array[1] || m2.innerVector(static_array[1].outer()).nonZeros() == 0 );\n    if(static_array[0] && static_array[1])\n    {\n      ++(static_array[1]);\n      static_array[1] = IteratorType(m2,0);\n      VERIFY( static_array[1] );\n      VERIFY( static_array[1].index() == static_array[0].index() );\n      VERIFY( static_array[1].outer() == static_array[0].outer() );\n      VERIFY( static_array[1].value() == static_array[0].value() );\n    }\n\n    std::vector<IteratorType> iters(2);\n    iters[0] = IteratorType(m2,0);\n    iters[1] = IteratorType(m2,m2.outerSize()-1);\n  }\n\n  // test reserve with empty rows/columns\n  {\n    SparseMatrixType m1(0,cols);\n    m1.reserve(ArrayXi::Constant(m1.outerSize(),1));\n    SparseMatrixType m2(rows,0);\n    m2.reserve(ArrayXi::Constant(m2.outerSize(),1));\n  }\n}\n\n\ntemplate<typename SparseMatrixType>\nvoid big_sparse_triplet(Index rows, Index cols, double density) {\n  typedef typename SparseMatrixType::StorageIndex StorageIndex;\n  typedef typename SparseMatrixType::Scalar Scalar;\n  typedef Triplet<Scalar,Index> TripletType;\n  std::vector<TripletType> triplets;\n  double nelements = density * rows*cols;\n  VERIFY(nelements>=0 && nelements < static_cast<double>(NumTraits<StorageIndex>::highest()));\n  Index ntriplets = Index(nelements);\n  triplets.reserve(ntriplets);\n  Scalar sum = Scalar(0);\n  for(Index i=0;i<ntriplets;++i)\n  {\n    Index r = internal::random<Index>(0,rows-1);\n    Index c = internal::random<Index>(0,cols-1);\n    // use positive values to prevent numerical cancellation errors in sum\n    Scalar v = numext::abs(internal::random<Scalar>());\n    triplets.push_back(TripletType(r,c,v));\n    sum += v;\n  }\n  SparseMatrixType m(rows,cols);\n  m.setFromTriplets(triplets.begin(), triplets.end());\n  VERIFY(m.nonZeros() <= ntriplets);\n  VERIFY_IS_APPROX(sum, m.sum());\n}\n\ntemplate<int>\nvoid bug1105()\n{\n  // Regression test for bug 1105\n  int n = Eigen::internal::random<int>(200,600);\n  SparseMatrix<std::complex<double>,0, long> mat(n, n);\n  std::complex<double> val;\n\n  for(int i=0; i<n; ++i)\n  {\n    mat.coeffRef(i, i%(n/10)) = val;\n    VERIFY(mat.data().allocatedSize()<20*n);\n  }\n}\n\n#ifndef EIGEN_SPARSE_TEST_INCLUDED_FROM_SPARSE_EXTRA\n\nEIGEN_DECLARE_TEST(sparse_basic)\n{\n  g_dense_op_sparse_count = 0;  // Suppresses compiler warning.\n  for(int i = 0; i < g_repeat; i++) {\n    int r = Eigen::internal::random<int>(1,200), c = Eigen::internal::random<int>(1,200);\n    if(Eigen::internal::random<int>(0,4) == 0) {\n      r = c; // check square matrices in 25% of tries\n    }\n    EIGEN_UNUSED_VARIABLE(r+c);\n    CALL_SUBTEST_1(( sparse_basic(SparseMatrix<double>(1, 1)) ));\n    CALL_SUBTEST_1(( sparse_basic(SparseMatrix<double>(8, 8)) ));\n    CALL_SUBTEST_2(( sparse_basic(SparseMatrix<std::complex<double>, ColMajor>(r, c)) ));\n    CALL_SUBTEST_2(( sparse_basic(SparseMatrix<std::complex<double>, RowMajor>(r, c)) ));\n    CALL_SUBTEST_1(( sparse_basic(SparseMatrix<double>(r, c)) ));\n    CALL_SUBTEST_5(( sparse_basic(SparseMatrix<double,ColMajor,long int>(r, c)) ));\n    CALL_SUBTEST_5(( sparse_basic(SparseMatrix<double,RowMajor,long int>(r, c)) ));\n    \n    r = Eigen::internal::random<int>(1,100);\n    c = Eigen::internal::random<int>(1,100);\n    if(Eigen::internal::random<int>(0,4) == 0) {\n      r = c; // check square matrices in 25% of tries\n    }\n    \n    CALL_SUBTEST_6(( sparse_basic(SparseMatrix<double,ColMajor,short int>(short(r), short(c))) ));\n    CALL_SUBTEST_6(( sparse_basic(SparseMatrix<double,RowMajor,short int>(short(r), short(c))) ));\n  }\n\n  // Regression test for bug 900: (manually insert higher values here, if you have enough RAM):\n  CALL_SUBTEST_3((big_sparse_triplet<SparseMatrix<float, RowMajor, int> >(10000, 10000, 0.125)));\n  CALL_SUBTEST_4((big_sparse_triplet<SparseMatrix<double, ColMajor, long int> >(10000, 10000, 0.125)));\n\n  CALL_SUBTEST_7( bug1105<0>() );\n}\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/sparse_block.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"sparse.h\"\n#include \"AnnoyingScalar.h\"\n\ntemplate<typename T>\ntypename Eigen::internal::enable_if<(T::Flags&RowMajorBit)==RowMajorBit, typename T::RowXpr>::type\ninnervec(T& A, Index i)\n{\n  return A.row(i);\n}\n\ntemplate<typename T>\ntypename Eigen::internal::enable_if<(T::Flags&RowMajorBit)==0, typename T::ColXpr>::type\ninnervec(T& A, Index i)\n{\n  return A.col(i);\n}\n\ntemplate<typename SparseMatrixType> void sparse_block(const SparseMatrixType& ref)\n{\n  const Index rows = ref.rows();\n  const Index cols = ref.cols();\n  const Index inner = ref.innerSize();\n  const Index outer = ref.outerSize();\n\n  typedef typename SparseMatrixType::Scalar Scalar;\n  typedef typename SparseMatrixType::RealScalar RealScalar;\n  typedef typename SparseMatrixType::StorageIndex StorageIndex;\n\n  double density = (std::max)(8./(rows*cols), 0.01);\n  typedef Matrix<Scalar,Dynamic,Dynamic,SparseMatrixType::IsRowMajor?RowMajor:ColMajor> DenseMatrix;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n  typedef Matrix<Scalar,1,Dynamic> RowDenseVector;\n  typedef SparseVector<Scalar> SparseVectorType;\n\n  Scalar s1 = internal::random<Scalar>();\n  {\n    SparseMatrixType m(rows, cols);\n    DenseMatrix refMat = DenseMatrix::Zero(rows, cols);\n    initSparse<Scalar>(density, refMat, m);\n\n    VERIFY_IS_APPROX(m, refMat);\n\n    // test InnerIterators and Block expressions\n    for (int t=0; t<10; ++t)\n    {\n      Index j = internal::random<Index>(0,cols-2);\n      Index i = internal::random<Index>(0,rows-2);\n      Index w = internal::random<Index>(1,cols-j);\n      Index h = internal::random<Index>(1,rows-i);\n\n      VERIFY_IS_APPROX(m.block(i,j,h,w), refMat.block(i,j,h,w));\n      for(Index c=0; c<w; c++)\n      {\n        VERIFY_IS_APPROX(m.block(i,j,h,w).col(c), refMat.block(i,j,h,w).col(c));\n        for(Index r=0; r<h; r++)\n        {\n          VERIFY_IS_APPROX(m.block(i,j,h,w).col(c).coeff(r), refMat.block(i,j,h,w).col(c).coeff(r));\n          VERIFY_IS_APPROX(m.block(i,j,h,w).coeff(r,c), refMat.block(i,j,h,w).coeff(r,c));\n        }\n      }\n      for(Index r=0; r<h; r++)\n      {\n        VERIFY_IS_APPROX(m.block(i,j,h,w).row(r), refMat.block(i,j,h,w).row(r));\n        for(Index c=0; c<w; c++)\n        {\n          VERIFY_IS_APPROX(m.block(i,j,h,w).row(r).coeff(c), refMat.block(i,j,h,w).row(r).coeff(c));\n          VERIFY_IS_APPROX(m.block(i,j,h,w).coeff(r,c), refMat.block(i,j,h,w).coeff(r,c));\n        }\n      }\n      \n      VERIFY_IS_APPROX(m.middleCols(j,w), refMat.middleCols(j,w));\n      VERIFY_IS_APPROX(m.middleRows(i,h), refMat.middleRows(i,h));\n      for(Index r=0; r<h; r++)\n      {\n        VERIFY_IS_APPROX(m.middleCols(j,w).row(r), refMat.middleCols(j,w).row(r));\n        VERIFY_IS_APPROX(m.middleRows(i,h).row(r), refMat.middleRows(i,h).row(r));\n        for(Index c=0; c<w; c++)\n        {\n          VERIFY_IS_APPROX(m.col(c).coeff(r), refMat.col(c).coeff(r));\n          VERIFY_IS_APPROX(m.row(r).coeff(c), refMat.row(r).coeff(c));\n          \n          VERIFY_IS_APPROX(m.middleCols(j,w).coeff(r,c), refMat.middleCols(j,w).coeff(r,c));\n          VERIFY_IS_APPROX(m.middleRows(i,h).coeff(r,c), refMat.middleRows(i,h).coeff(r,c));\n          if(m.middleCols(j,w).coeff(r,c) != Scalar(0))\n          {\n            VERIFY_IS_APPROX(m.middleCols(j,w).coeffRef(r,c), refMat.middleCols(j,w).coeff(r,c));\n          }\n          if(m.middleRows(i,h).coeff(r,c) != Scalar(0))\n          {\n            VERIFY_IS_APPROX(m.middleRows(i,h).coeff(r,c), refMat.middleRows(i,h).coeff(r,c));\n          }\n        }\n      }\n      for(Index c=0; c<w; c++)\n      {\n        VERIFY_IS_APPROX(m.middleCols(j,w).col(c), refMat.middleCols(j,w).col(c));\n        VERIFY_IS_APPROX(m.middleRows(i,h).col(c), refMat.middleRows(i,h).col(c));\n      }\n    }\n\n    for(Index c=0; c<cols; c++)\n    {\n      VERIFY_IS_APPROX(m.col(c) + m.col(c), (m + m).col(c));\n      VERIFY_IS_APPROX(m.col(c) + m.col(c), refMat.col(c) + refMat.col(c));\n    }\n\n    for(Index r=0; r<rows; r++)\n    {\n      VERIFY_IS_APPROX(m.row(r) + m.row(r), (m + m).row(r));\n      VERIFY_IS_APPROX(m.row(r) + m.row(r), refMat.row(r) + refMat.row(r));\n    }\n  }\n\n  // test innerVector()\n  {\n    DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols);\n    SparseMatrixType m2(rows, cols);\n    initSparse<Scalar>(density, refMat2, m2);\n    Index j0 = internal::random<Index>(0,outer-1);\n    Index j1 = internal::random<Index>(0,outer-1);\n    Index r0 = internal::random<Index>(0,rows-1);\n    Index c0 = internal::random<Index>(0,cols-1);\n\n    VERIFY_IS_APPROX(m2.innerVector(j0), innervec(refMat2,j0));\n    VERIFY_IS_APPROX(m2.innerVector(j0)+m2.innerVector(j1), innervec(refMat2,j0)+innervec(refMat2,j1));\n\n    m2.innerVector(j0) *= Scalar(2);\n    innervec(refMat2,j0) *= Scalar(2);\n    VERIFY_IS_APPROX(m2, refMat2);\n\n    m2.row(r0) *= Scalar(3);\n    refMat2.row(r0) *= Scalar(3);\n    VERIFY_IS_APPROX(m2, refMat2);\n\n    m2.col(c0) *= Scalar(4);\n    refMat2.col(c0) *= Scalar(4);\n    VERIFY_IS_APPROX(m2, refMat2);\n\n    m2.row(r0) /= Scalar(3);\n    refMat2.row(r0) /= Scalar(3);\n    VERIFY_IS_APPROX(m2, refMat2);\n\n    m2.col(c0) /= Scalar(4);\n    refMat2.col(c0) /= Scalar(4);\n    VERIFY_IS_APPROX(m2, refMat2);\n\n    SparseVectorType v1;\n    VERIFY_IS_APPROX(v1 = m2.col(c0) * 4, refMat2.col(c0)*4);\n    VERIFY_IS_APPROX(v1 = m2.row(r0) * 4, refMat2.row(r0).transpose()*4);\n\n    SparseMatrixType m3(rows,cols);\n    m3.reserve(VectorXi::Constant(outer,int(inner/2)));\n    for(Index j=0; j<outer; ++j)\n      for(Index k=0; k<(std::min)(j,inner); ++k)\n        m3.insertByOuterInner(j,k) = internal::convert_index<StorageIndex>(k+1);\n    for(Index j=0; j<(std::min)(outer, inner); ++j)\n    {\n      VERIFY(j==numext::real(m3.innerVector(j).nonZeros()));\n      if(j>0)\n        VERIFY(RealScalar(j)==numext::real(m3.innerVector(j).lastCoeff()));\n    }\n    m3.makeCompressed();\n    for(Index j=0; j<(std::min)(outer, inner); ++j)\n    {\n      VERIFY(j==numext::real(m3.innerVector(j).nonZeros()));\n      if(j>0)\n        VERIFY(RealScalar(j)==numext::real(m3.innerVector(j).lastCoeff()));\n    }\n\n    VERIFY(m3.innerVector(j0).nonZeros() == m3.transpose().innerVector(j0).nonZeros());\n\n//     m2.innerVector(j0) = 2*m2.innerVector(j1);\n//     refMat2.col(j0) = 2*refMat2.col(j1);\n//     VERIFY_IS_APPROX(m2, refMat2);\n  }\n\n  // test innerVectors()\n  {\n    DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols);\n    SparseMatrixType m2(rows, cols);\n    initSparse<Scalar>(density, refMat2, m2);\n    if(internal::random<float>(0,1)>0.5f) m2.makeCompressed();\n    Index j0 = internal::random<Index>(0,outer-2);\n    Index j1 = internal::random<Index>(0,outer-2);\n    Index n0 = internal::random<Index>(1,outer-(std::max)(j0,j1));\n    if(SparseMatrixType::IsRowMajor)\n      VERIFY_IS_APPROX(m2.innerVectors(j0,n0), refMat2.block(j0,0,n0,cols));\n    else\n      VERIFY_IS_APPROX(m2.innerVectors(j0,n0), refMat2.block(0,j0,rows,n0));\n    if(SparseMatrixType::IsRowMajor)\n      VERIFY_IS_APPROX(m2.innerVectors(j0,n0)+m2.innerVectors(j1,n0),\n                       refMat2.middleRows(j0,n0)+refMat2.middleRows(j1,n0));\n    else\n      VERIFY_IS_APPROX(m2.innerVectors(j0,n0)+m2.innerVectors(j1,n0),\n                      refMat2.block(0,j0,rows,n0)+refMat2.block(0,j1,rows,n0));\n    \n    VERIFY_IS_APPROX(m2, refMat2);\n    \n    VERIFY(m2.innerVectors(j0,n0).nonZeros() == m2.transpose().innerVectors(j0,n0).nonZeros());\n    \n    m2.innerVectors(j0,n0) = m2.innerVectors(j0,n0) + m2.innerVectors(j1,n0);\n    if(SparseMatrixType::IsRowMajor)\n      refMat2.middleRows(j0,n0) = (refMat2.middleRows(j0,n0) + refMat2.middleRows(j1,n0)).eval();\n    else\n      refMat2.middleCols(j0,n0) = (refMat2.middleCols(j0,n0) + refMat2.middleCols(j1,n0)).eval();\n    \n    VERIFY_IS_APPROX(m2, refMat2);\n  }\n\n  // test generic blocks\n  {\n    DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols);\n    SparseMatrixType m2(rows, cols);\n    initSparse<Scalar>(density, refMat2, m2);\n    Index j0 = internal::random<Index>(0,outer-2);\n    Index j1 = internal::random<Index>(0,outer-2);\n    Index n0 = internal::random<Index>(1,outer-(std::max)(j0,j1));\n    if(SparseMatrixType::IsRowMajor)\n      VERIFY_IS_APPROX(m2.block(j0,0,n0,cols), refMat2.block(j0,0,n0,cols));\n    else\n      VERIFY_IS_APPROX(m2.block(0,j0,rows,n0), refMat2.block(0,j0,rows,n0));\n    \n    if(SparseMatrixType::IsRowMajor)\n      VERIFY_IS_APPROX(m2.block(j0,0,n0,cols)+m2.block(j1,0,n0,cols),\n                      refMat2.block(j0,0,n0,cols)+refMat2.block(j1,0,n0,cols));\n    else\n      VERIFY_IS_APPROX(m2.block(0,j0,rows,n0)+m2.block(0,j1,rows,n0),\n                      refMat2.block(0,j0,rows,n0)+refMat2.block(0,j1,rows,n0));\n      \n    Index i = internal::random<Index>(0,m2.outerSize()-1);\n    if(SparseMatrixType::IsRowMajor) {\n      m2.innerVector(i) = m2.innerVector(i) * s1;\n      refMat2.row(i) = refMat2.row(i) * s1;\n      VERIFY_IS_APPROX(m2,refMat2);\n    } else {\n      m2.innerVector(i) = m2.innerVector(i) * s1;\n      refMat2.col(i) = refMat2.col(i) * s1;\n      VERIFY_IS_APPROX(m2,refMat2);\n    }\n    \n    Index r0 = internal::random<Index>(0,rows-2);\n    Index c0 = internal::random<Index>(0,cols-2);\n    Index r1 = internal::random<Index>(1,rows-r0);\n    Index c1 = internal::random<Index>(1,cols-c0);\n    \n    VERIFY_IS_APPROX(DenseVector(m2.col(c0)), refMat2.col(c0));\n    VERIFY_IS_APPROX(m2.col(c0), refMat2.col(c0));\n    \n    VERIFY_IS_APPROX(RowDenseVector(m2.row(r0)), refMat2.row(r0));\n    VERIFY_IS_APPROX(m2.row(r0), refMat2.row(r0));\n\n    VERIFY_IS_APPROX(m2.block(r0,c0,r1,c1), refMat2.block(r0,c0,r1,c1));\n    VERIFY_IS_APPROX((2*m2).block(r0,c0,r1,c1), (2*refMat2).block(r0,c0,r1,c1));\n\n    if(m2.nonZeros()>0)\n    {\n      VERIFY_IS_APPROX(m2, refMat2);\n      SparseMatrixType m3(rows, cols);\n      DenseMatrix refMat3(rows, cols); refMat3.setZero();\n      Index n = internal::random<Index>(1,10);\n      for(Index k=0; k<n; ++k)\n      {\n        Index o1 = internal::random<Index>(0,outer-1);\n        Index o2 = internal::random<Index>(0,outer-1);\n        if(SparseMatrixType::IsRowMajor)\n        {\n          m3.innerVector(o1) = m2.row(o2);\n          refMat3.row(o1) = refMat2.row(o2);\n        }\n        else\n        {\n          m3.innerVector(o1) = m2.col(o2);\n          refMat3.col(o1) = refMat2.col(o2);\n        }\n        if(internal::random<bool>())\n          m3.makeCompressed();\n      }\n      if(m3.nonZeros()>0)\n      VERIFY_IS_APPROX(m3, refMat3);\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(sparse_block)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    int r = Eigen::internal::random<int>(1,200), c = Eigen::internal::random<int>(1,200);\n    if(Eigen::internal::random<int>(0,4) == 0) {\n      r = c; // check square matrices in 25% of tries\n    }\n    EIGEN_UNUSED_VARIABLE(r+c);\n    CALL_SUBTEST_1(( sparse_block(SparseMatrix<double>(1, 1)) ));\n    CALL_SUBTEST_1(( sparse_block(SparseMatrix<double>(8, 8)) ));\n    CALL_SUBTEST_1(( sparse_block(SparseMatrix<double>(r, c)) ));\n    CALL_SUBTEST_2(( sparse_block(SparseMatrix<std::complex<double>, ColMajor>(r, c)) ));\n    CALL_SUBTEST_2(( sparse_block(SparseMatrix<std::complex<double>, RowMajor>(r, c)) ));\n    \n    CALL_SUBTEST_3(( sparse_block(SparseMatrix<double,ColMajor,long int>(r, c)) ));\n    CALL_SUBTEST_3(( sparse_block(SparseMatrix<double,RowMajor,long int>(r, c)) ));\n    \n    r = Eigen::internal::random<int>(1,100);\n    c = Eigen::internal::random<int>(1,100);\n    if(Eigen::internal::random<int>(0,4) == 0) {\n      r = c; // check square matrices in 25% of tries\n    }\n    \n    CALL_SUBTEST_4(( sparse_block(SparseMatrix<double,ColMajor,short int>(short(r), short(c))) ));\n    CALL_SUBTEST_4(( sparse_block(SparseMatrix<double,RowMajor,short int>(short(r), short(c))) ));\n#ifndef EIGEN_TEST_ANNOYING_SCALAR_DONT_THROW\n    AnnoyingScalar::dont_throw = true;\n#endif\n    CALL_SUBTEST_5((  sparse_block(SparseMatrix<AnnoyingScalar>(r,c)) ));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/sparse_permutations.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\nstatic long int nb_transposed_copies;\n#define EIGEN_SPARSE_TRANSPOSED_COPY_PLUGIN {nb_transposed_copies++;}\n#define VERIFY_TRANSPOSITION_COUNT(XPR,N) {\\\n    nb_transposed_copies = 0; \\\n    XPR; \\\n    if(nb_transposed_copies!=N) std::cerr << \"nb_transposed_copies == \" << nb_transposed_copies << \"\\n\"; \\\n    VERIFY( (#XPR) && nb_transposed_copies==N ); \\\n  }\n\n#include \"sparse.h\"\n\ntemplate<typename T>\nbool is_sorted(const T& mat) {\n  for(Index k = 0; k<mat.outerSize(); ++k)\n  {\n    Index prev = -1;\n    for(typename T::InnerIterator it(mat,k); it; ++it)\n    {\n      if(prev>=it.index())\n        return false;\n      prev = it.index();\n    }\n  }\n  return true;\n}\n\ntemplate<typename T>\ntypename internal::nested_eval<T,1>::type eval(const T &xpr)\n{\n  VERIFY( int(internal::nested_eval<T,1>::type::Flags&RowMajorBit) == int(internal::evaluator<T>::Flags&RowMajorBit) );\n  return xpr;\n}\n\ntemplate<int OtherStorage, typename SparseMatrixType> void sparse_permutations(const SparseMatrixType& ref)\n{\n  const Index rows = ref.rows();\n  const Index cols = ref.cols();\n  typedef typename SparseMatrixType::Scalar Scalar;\n  typedef typename SparseMatrixType::StorageIndex StorageIndex;\n  typedef SparseMatrix<Scalar, OtherStorage, StorageIndex> OtherSparseMatrixType;\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  typedef Matrix<StorageIndex,Dynamic,1> VectorI;\n//   bool IsRowMajor1 = SparseMatrixType::IsRowMajor;\n//   bool IsRowMajor2 = OtherSparseMatrixType::IsRowMajor;\n  \n  double density = (std::max)(8./(rows*cols), 0.01);\n  \n  SparseMatrixType mat(rows, cols), up(rows,cols), lo(rows,cols);\n  OtherSparseMatrixType res;\n  DenseMatrix mat_d = DenseMatrix::Zero(rows, cols), up_sym_d, lo_sym_d, res_d;\n  \n  initSparse<Scalar>(density, mat_d, mat, 0);\n\n  up = mat.template triangularView<Upper>();\n  lo = mat.template triangularView<Lower>();\n  \n  up_sym_d = mat_d.template selfadjointView<Upper>();\n  lo_sym_d = mat_d.template selfadjointView<Lower>();\n  \n  VERIFY_IS_APPROX(mat, mat_d);\n  VERIFY_IS_APPROX(up, DenseMatrix(mat_d.template triangularView<Upper>()));\n  VERIFY_IS_APPROX(lo, DenseMatrix(mat_d.template triangularView<Lower>()));\n  \n  PermutationMatrix<Dynamic> p, p_null;\n  VectorI pi;\n  randomPermutationVector(pi, cols);\n  p.indices() = pi;\n\n  VERIFY( is_sorted( ::eval(mat*p) ));\n  VERIFY( is_sorted( res = mat*p ));\n  VERIFY_TRANSPOSITION_COUNT( ::eval(mat*p), 0);\n  //VERIFY_TRANSPOSITION_COUNT( res = mat*p, IsRowMajor ? 1 : 0 );\n  res_d = mat_d*p;\n  VERIFY(res.isApprox(res_d) && \"mat*p\");\n\n  VERIFY( is_sorted( ::eval(p*mat) ));\n  VERIFY( is_sorted( res = p*mat ));\n  VERIFY_TRANSPOSITION_COUNT( ::eval(p*mat), 0);\n  res_d = p*mat_d;\n  VERIFY(res.isApprox(res_d) && \"p*mat\");\n\n  VERIFY( is_sorted( (mat*p).eval() ));\n  VERIFY( is_sorted( res = mat*p.inverse() ));\n  VERIFY_TRANSPOSITION_COUNT( ::eval(mat*p.inverse()), 0);\n  res_d = mat*p.inverse();\n  VERIFY(res.isApprox(res_d) && \"mat*inv(p)\");\n\n  VERIFY( is_sorted( (p*mat+p*mat).eval() ));\n  VERIFY( is_sorted( res = p.inverse()*mat ));\n  VERIFY_TRANSPOSITION_COUNT( ::eval(p.inverse()*mat), 0);\n  res_d = p.inverse()*mat_d;\n  VERIFY(res.isApprox(res_d) && \"inv(p)*mat\");\n\n  VERIFY( is_sorted( (p * mat * p.inverse()).eval() ));\n  VERIFY( is_sorted( res = mat.twistedBy(p) ));\n  VERIFY_TRANSPOSITION_COUNT( ::eval(p * mat * p.inverse()), 0);\n  res_d = (p * mat_d) * p.inverse();\n  VERIFY(res.isApprox(res_d) && \"p*mat*inv(p)\");\n\n  \n  VERIFY( is_sorted( res = mat.template selfadjointView<Upper>().twistedBy(p_null) ));\n  res_d = up_sym_d;\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint upper to full\");\n  \n  VERIFY( is_sorted( res = mat.template selfadjointView<Lower>().twistedBy(p_null) ));\n  res_d = lo_sym_d;\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint lower to full\");\n  \n  \n  VERIFY( is_sorted( res = up.template selfadjointView<Upper>().twistedBy(p_null) ));\n  res_d = up_sym_d;\n  VERIFY(res.isApprox(res_d) && \"upper selfadjoint to full\");\n  \n  VERIFY( is_sorted( res = lo.template selfadjointView<Lower>().twistedBy(p_null) ));\n  res_d = lo_sym_d;\n  VERIFY(res.isApprox(res_d) && \"lower selfadjoint full\");\n\n\n  VERIFY( is_sorted( res = mat.template selfadjointView<Upper>() ));\n  res_d = up_sym_d;\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint upper to full\");\n\n  VERIFY( is_sorted( res = mat.template selfadjointView<Lower>() ));\n  res_d = lo_sym_d;\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint lower to full\");\n\n  VERIFY( is_sorted( res = up.template selfadjointView<Upper>() ));\n  res_d = up_sym_d;\n  VERIFY(res.isApprox(res_d) && \"upper selfadjoint to full\");\n\n  VERIFY( is_sorted( res = lo.template selfadjointView<Lower>() ));\n  res_d = lo_sym_d;\n  VERIFY(res.isApprox(res_d) && \"lower selfadjoint full\");\n\n\n  res.template selfadjointView<Upper>() = mat.template selfadjointView<Upper>();\n  res_d = up_sym_d.template triangularView<Upper>();\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint upper to upper\");\n\n  res.template selfadjointView<Lower>() = mat.template selfadjointView<Upper>();\n  res_d = up_sym_d.template triangularView<Lower>();\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint upper to lower\");\n\n  res.template selfadjointView<Upper>() = mat.template selfadjointView<Lower>();\n  res_d = lo_sym_d.template triangularView<Upper>();\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint lower to upper\");\n\n  res.template selfadjointView<Lower>() = mat.template selfadjointView<Lower>();\n  res_d = lo_sym_d.template triangularView<Lower>();\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint lower to lower\");\n\n  \n  \n  res.template selfadjointView<Upper>() = mat.template selfadjointView<Upper>().twistedBy(p);\n  res_d = ((p * up_sym_d) * p.inverse()).eval().template triangularView<Upper>();\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint upper twisted to upper\");\n  \n  res.template selfadjointView<Upper>() = mat.template selfadjointView<Lower>().twistedBy(p);\n  res_d = ((p * lo_sym_d) * p.inverse()).eval().template triangularView<Upper>();\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint lower twisted to upper\");\n  \n  res.template selfadjointView<Lower>() = mat.template selfadjointView<Lower>().twistedBy(p);\n  res_d = ((p * lo_sym_d) * p.inverse()).eval().template triangularView<Lower>();\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint lower twisted to lower\");\n  \n  res.template selfadjointView<Lower>() = mat.template selfadjointView<Upper>().twistedBy(p);\n  res_d = ((p * up_sym_d) * p.inverse()).eval().template triangularView<Lower>();\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint upper twisted to lower\");\n  \n  \n  res.template selfadjointView<Upper>() = up.template selfadjointView<Upper>().twistedBy(p);\n  res_d = ((p * up_sym_d) * p.inverse()).eval().template triangularView<Upper>();\n  VERIFY(res.isApprox(res_d) && \"upper selfadjoint twisted to upper\");\n  \n  res.template selfadjointView<Upper>() = lo.template selfadjointView<Lower>().twistedBy(p);\n  res_d = ((p * lo_sym_d) * p.inverse()).eval().template triangularView<Upper>();\n  VERIFY(res.isApprox(res_d) && \"lower selfadjoint twisted to upper\");\n  \n  res.template selfadjointView<Lower>() = lo.template selfadjointView<Lower>().twistedBy(p);\n  res_d = ((p * lo_sym_d) * p.inverse()).eval().template triangularView<Lower>();\n  VERIFY(res.isApprox(res_d) && \"lower selfadjoint twisted to lower\");\n  \n  res.template selfadjointView<Lower>() = up.template selfadjointView<Upper>().twistedBy(p);\n  res_d = ((p * up_sym_d) * p.inverse()).eval().template triangularView<Lower>();\n  VERIFY(res.isApprox(res_d) && \"upper selfadjoint twisted to lower\");\n\n  \n  VERIFY( is_sorted( res = mat.template selfadjointView<Upper>().twistedBy(p) ));\n  res_d = (p * up_sym_d) * p.inverse();\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint upper twisted to full\");\n  \n  VERIFY( is_sorted( res = mat.template selfadjointView<Lower>().twistedBy(p) ));\n  res_d = (p * lo_sym_d) * p.inverse();\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint lower twisted to full\");\n  \n  VERIFY( is_sorted( res = up.template selfadjointView<Upper>().twistedBy(p) ));\n  res_d = (p * up_sym_d) * p.inverse();\n  VERIFY(res.isApprox(res_d) && \"upper selfadjoint twisted to full\");\n  \n  VERIFY( is_sorted( res = lo.template selfadjointView<Lower>().twistedBy(p) ));\n  res_d = (p * lo_sym_d) * p.inverse();\n  VERIFY(res.isApprox(res_d) && \"lower selfadjoint twisted to full\");\n}\n\ntemplate<typename Scalar> void sparse_permutations_all(int size)\n{\n  CALL_SUBTEST(( sparse_permutations<ColMajor>(SparseMatrix<Scalar, ColMajor>(size,size)) ));\n  CALL_SUBTEST(( sparse_permutations<ColMajor>(SparseMatrix<Scalar, RowMajor>(size,size)) ));\n  CALL_SUBTEST(( sparse_permutations<RowMajor>(SparseMatrix<Scalar, ColMajor>(size,size)) ));\n  CALL_SUBTEST(( sparse_permutations<RowMajor>(SparseMatrix<Scalar, RowMajor>(size,size)) ));\n}\n\nEIGEN_DECLARE_TEST(sparse_permutations)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    int s = Eigen::internal::random<int>(1,50);\n    CALL_SUBTEST_1((  sparse_permutations_all<double>(s) ));\n    CALL_SUBTEST_2((  sparse_permutations_all<std::complex<double> >(s) ));\n  }\n\n  VERIFY((internal::is_same<internal::permutation_matrix_product<SparseMatrix<double>,OnTheRight,false,SparseShape>::ReturnType,\n                            internal::nested_eval<Product<SparseMatrix<double>,PermutationMatrix<Dynamic,Dynamic>,AliasFreeProduct>,1>::type>::value));\n\n  VERIFY((internal::is_same<internal::permutation_matrix_product<SparseMatrix<double>,OnTheLeft,false,SparseShape>::ReturnType,\n                            internal::nested_eval<Product<PermutationMatrix<Dynamic,Dynamic>,SparseMatrix<double>,AliasFreeProduct>,1>::type>::value));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/sparse_product.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#if defined(_MSC_VER) && (_MSC_VER==1800)\n// This unit test takes forever to compile in Release mode with MSVC 2013,\n// multiple hours. So let's switch off optimization for this one.\n#pragma optimize(\"\",off)\n#endif\n\nstatic long int nb_temporaries;\n\ninline void on_temporary_creation() {\n  // here's a great place to set a breakpoint when debugging failures in this test!\n  nb_temporaries++;\n}\n\n#define EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN { on_temporary_creation(); }\n\n#include \"sparse.h\"\n\n#define VERIFY_EVALUATION_COUNT(XPR,N) {\\\n    nb_temporaries = 0; \\\n    CALL_SUBTEST( XPR ); \\\n    if(nb_temporaries!=N) std::cerr << \"nb_temporaries == \" << nb_temporaries << \"\\n\"; \\\n    VERIFY( (#XPR) && nb_temporaries==N ); \\\n  }\n\n\n\ntemplate<typename SparseMatrixType> void sparse_product()\n{\n  typedef typename SparseMatrixType::StorageIndex StorageIndex;\n  Index n = 100;\n  const Index rows  = internal::random<Index>(1,n);\n  const Index cols  = internal::random<Index>(1,n);\n  const Index depth = internal::random<Index>(1,n);\n  typedef typename SparseMatrixType::Scalar Scalar;\n  enum { Flags = SparseMatrixType::Flags };\n\n  double density = (std::max)(8./(rows*cols), 0.2);\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n  typedef Matrix<Scalar,1,Dynamic> RowDenseVector;\n  typedef SparseVector<Scalar,0,StorageIndex> ColSpVector;\n  typedef SparseVector<Scalar,RowMajor,StorageIndex> RowSpVector;\n\n  Scalar s1 = internal::random<Scalar>();\n  Scalar s2 = internal::random<Scalar>();\n\n  // test matrix-matrix product\n  {\n    DenseMatrix refMat2  = DenseMatrix::Zero(rows, depth);\n    DenseMatrix refMat2t = DenseMatrix::Zero(depth, rows);\n    DenseMatrix refMat3  = DenseMatrix::Zero(depth, cols);\n    DenseMatrix refMat3t = DenseMatrix::Zero(cols, depth);\n    DenseMatrix refMat4  = DenseMatrix::Zero(rows, cols);\n    DenseMatrix refMat4t = DenseMatrix::Zero(cols, rows);\n    DenseMatrix refMat5  = DenseMatrix::Random(depth, cols);\n    DenseMatrix refMat6  = DenseMatrix::Random(rows, rows);\n    DenseMatrix dm4 = DenseMatrix::Zero(rows, rows);\n//     DenseVector dv1 = DenseVector::Random(rows);\n    SparseMatrixType m2 (rows, depth);\n    SparseMatrixType m2t(depth, rows);\n    SparseMatrixType m3 (depth, cols);\n    SparseMatrixType m3t(cols, depth);\n    SparseMatrixType m4 (rows, cols);\n    SparseMatrixType m4t(cols, rows);\n    SparseMatrixType m6(rows, rows);\n    initSparse(density, refMat2,  m2);\n    initSparse(density, refMat2t, m2t);\n    initSparse(density, refMat3,  m3);\n    initSparse(density, refMat3t, m3t);\n    initSparse(density, refMat4,  m4);\n    initSparse(density, refMat4t, m4t);\n    initSparse(density, refMat6, m6);\n\n//     int c = internal::random<int>(0,depth-1);\n\n    // sparse * sparse\n    VERIFY_IS_APPROX(m4=m2*m3, refMat4=refMat2*refMat3);\n    VERIFY_IS_APPROX(m4=m2t.transpose()*m3, refMat4=refMat2t.transpose()*refMat3);\n    VERIFY_IS_APPROX(m4=m2t.transpose()*m3t.transpose(), refMat4=refMat2t.transpose()*refMat3t.transpose());\n    VERIFY_IS_APPROX(m4=m2*m3t.transpose(), refMat4=refMat2*refMat3t.transpose());\n\n    VERIFY_IS_APPROX(m4 = m2*m3/s1, refMat4 = refMat2*refMat3/s1);\n    VERIFY_IS_APPROX(m4 = m2*m3*s1, refMat4 = refMat2*refMat3*s1);\n    VERIFY_IS_APPROX(m4 = s2*m2*m3*s1, refMat4 = s2*refMat2*refMat3*s1);\n    VERIFY_IS_APPROX(m4 = (m2+m2)*m3, refMat4 = (refMat2+refMat2)*refMat3);\n    VERIFY_IS_APPROX(m4 = m2*m3.leftCols(cols/2), refMat4 = refMat2*refMat3.leftCols(cols/2));\n    VERIFY_IS_APPROX(m4 = m2*(m3+m3).leftCols(cols/2), refMat4 = refMat2*(refMat3+refMat3).leftCols(cols/2));\n\n    VERIFY_IS_APPROX(m4=(m2*m3).pruned(0), refMat4=refMat2*refMat3);\n    VERIFY_IS_APPROX(m4=(m2t.transpose()*m3).pruned(0), refMat4=refMat2t.transpose()*refMat3);\n    VERIFY_IS_APPROX(m4=(m2t.transpose()*m3t.transpose()).pruned(0), refMat4=refMat2t.transpose()*refMat3t.transpose());\n    VERIFY_IS_APPROX(m4=(m2*m3t.transpose()).pruned(0), refMat4=refMat2*refMat3t.transpose());\n\n#ifndef EIGEN_SPARSE_PRODUCT_IGNORE_TEMPORARY_COUNT\n    // make sure the right product implementation is called:\n    if((!SparseMatrixType::IsRowMajor) && m2.rows()<=m3.cols())\n    {\n      VERIFY_EVALUATION_COUNT(m4 = m2*m3, 2); // 2 for transposing and get a sorted result.\n      VERIFY_EVALUATION_COUNT(m4 = (m2*m3).pruned(0), 1);\n      VERIFY_EVALUATION_COUNT(m4 = (m2*m3).eval().pruned(0), 4);\n    }\n#endif\n\n    // and that pruning is effective:\n    {\n      DenseMatrix Ad(2,2);\n      Ad << -1, 1, 1, 1;\n      SparseMatrixType As(Ad.sparseView()), B(2,2);\n      VERIFY_IS_EQUAL( (As*As.transpose()).eval().nonZeros(), 4);\n      VERIFY_IS_EQUAL( (Ad*Ad.transpose()).eval().sparseView().eval().nonZeros(), 2);\n      VERIFY_IS_EQUAL( (As*As.transpose()).pruned(1e-6).eval().nonZeros(), 2);\n    }\n\n    // dense ?= sparse * sparse\n    VERIFY_IS_APPROX(dm4 =m2*m3, refMat4 =refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4+=m2*m3, refMat4+=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4-=m2*m3, refMat4-=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4 =m2t.transpose()*m3, refMat4 =refMat2t.transpose()*refMat3);\n    VERIFY_IS_APPROX(dm4+=m2t.transpose()*m3, refMat4+=refMat2t.transpose()*refMat3);\n    VERIFY_IS_APPROX(dm4-=m2t.transpose()*m3, refMat4-=refMat2t.transpose()*refMat3);\n    VERIFY_IS_APPROX(dm4 =m2t.transpose()*m3t.transpose(), refMat4 =refMat2t.transpose()*refMat3t.transpose());\n    VERIFY_IS_APPROX(dm4+=m2t.transpose()*m3t.transpose(), refMat4+=refMat2t.transpose()*refMat3t.transpose());\n    VERIFY_IS_APPROX(dm4-=m2t.transpose()*m3t.transpose(), refMat4-=refMat2t.transpose()*refMat3t.transpose());\n    VERIFY_IS_APPROX(dm4 =m2*m3t.transpose(), refMat4 =refMat2*refMat3t.transpose());\n    VERIFY_IS_APPROX(dm4+=m2*m3t.transpose(), refMat4+=refMat2*refMat3t.transpose());\n    VERIFY_IS_APPROX(dm4-=m2*m3t.transpose(), refMat4-=refMat2*refMat3t.transpose());\n    VERIFY_IS_APPROX(dm4 = m2*m3*s1, refMat4 = refMat2*refMat3*s1);\n\n    // test aliasing\n    m4 = m2; refMat4 = refMat2;\n    VERIFY_IS_APPROX(m4=m4*m3, refMat4=refMat4*refMat3);\n\n    // sparse * dense matrix\n    VERIFY_IS_APPROX(dm4=m2*refMat3, refMat4=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4=m2*refMat3t.transpose(), refMat4=refMat2*refMat3t.transpose());\n    VERIFY_IS_APPROX(dm4=m2t.transpose()*refMat3, refMat4=refMat2t.transpose()*refMat3);\n    VERIFY_IS_APPROX(dm4=m2t.transpose()*refMat3t.transpose(), refMat4=refMat2t.transpose()*refMat3t.transpose());\n\n    VERIFY_IS_APPROX(dm4=m2*refMat3, refMat4=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4=dm4+m2*refMat3, refMat4=refMat4+refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4+=m2*refMat3, refMat4+=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4-=m2*refMat3, refMat4-=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4.noalias()+=m2*refMat3, refMat4+=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4.noalias()-=m2*refMat3, refMat4-=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4=m2*(refMat3+refMat3), refMat4=refMat2*(refMat3+refMat3));\n    VERIFY_IS_APPROX(dm4=m2t.transpose()*(refMat3+refMat5)*0.5, refMat4=refMat2t.transpose()*(refMat3+refMat5)*0.5);\n\n    // sparse * dense vector\n    VERIFY_IS_APPROX(dm4.col(0)=m2*refMat3.col(0), refMat4.col(0)=refMat2*refMat3.col(0));\n    VERIFY_IS_APPROX(dm4.col(0)=m2*refMat3t.transpose().col(0), refMat4.col(0)=refMat2*refMat3t.transpose().col(0));\n    VERIFY_IS_APPROX(dm4.col(0)=m2t.transpose()*refMat3.col(0), refMat4.col(0)=refMat2t.transpose()*refMat3.col(0));\n    VERIFY_IS_APPROX(dm4.col(0)=m2t.transpose()*refMat3t.transpose().col(0), refMat4.col(0)=refMat2t.transpose()*refMat3t.transpose().col(0));\n\n    // dense * sparse\n    VERIFY_IS_APPROX(dm4=refMat2*m3, refMat4=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4=dm4+refMat2*m3, refMat4=refMat4+refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4+=refMat2*m3, refMat4+=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4-=refMat2*m3, refMat4-=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4.noalias()+=refMat2*m3, refMat4+=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4.noalias()-=refMat2*m3, refMat4-=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4=refMat2*m3t.transpose(), refMat4=refMat2*refMat3t.transpose());\n    VERIFY_IS_APPROX(dm4=refMat2t.transpose()*m3, refMat4=refMat2t.transpose()*refMat3);\n    VERIFY_IS_APPROX(dm4=refMat2t.transpose()*m3t.transpose(), refMat4=refMat2t.transpose()*refMat3t.transpose());\n\n    // sparse * dense and dense * sparse outer product\n    {\n      Index c  = internal::random<Index>(0,depth-1);\n      Index r  = internal::random<Index>(0,rows-1);\n      Index c1 = internal::random<Index>(0,cols-1);\n      Index r1 = internal::random<Index>(0,depth-1);\n      DenseMatrix dm5  = DenseMatrix::Random(depth, cols);\n\n      VERIFY_IS_APPROX( m4=m2.col(c)*dm5.col(c1).transpose(), refMat4=refMat2.col(c)*dm5.col(c1).transpose());\n      VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count());\n      VERIFY_IS_APPROX( m4=m2.middleCols(c,1)*dm5.col(c1).transpose(), refMat4=refMat2.col(c)*dm5.col(c1).transpose());\n      VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count());\n      VERIFY_IS_APPROX(dm4=m2.col(c)*dm5.col(c1).transpose(), refMat4=refMat2.col(c)*dm5.col(c1).transpose());\n\n      VERIFY_IS_APPROX(m4=dm5.col(c1)*m2.col(c).transpose(), refMat4=dm5.col(c1)*refMat2.col(c).transpose());\n      VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count());\n      VERIFY_IS_APPROX(m4=dm5.col(c1)*m2.middleCols(c,1).transpose(), refMat4=dm5.col(c1)*refMat2.col(c).transpose());\n      VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count());\n      VERIFY_IS_APPROX(dm4=dm5.col(c1)*m2.col(c).transpose(), refMat4=dm5.col(c1)*refMat2.col(c).transpose());\n\n      VERIFY_IS_APPROX( m4=dm5.row(r1).transpose()*m2.col(c).transpose(), refMat4=dm5.row(r1).transpose()*refMat2.col(c).transpose());\n      VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count());\n      VERIFY_IS_APPROX(dm4=dm5.row(r1).transpose()*m2.col(c).transpose(), refMat4=dm5.row(r1).transpose()*refMat2.col(c).transpose());\n\n      VERIFY_IS_APPROX( m4=m2.row(r).transpose()*dm5.col(c1).transpose(), refMat4=refMat2.row(r).transpose()*dm5.col(c1).transpose());\n      VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count());\n      VERIFY_IS_APPROX( m4=m2.middleRows(r,1).transpose()*dm5.col(c1).transpose(), refMat4=refMat2.row(r).transpose()*dm5.col(c1).transpose());\n      VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count());\n      VERIFY_IS_APPROX(dm4=m2.row(r).transpose()*dm5.col(c1).transpose(), refMat4=refMat2.row(r).transpose()*dm5.col(c1).transpose());\n\n      VERIFY_IS_APPROX( m4=dm5.col(c1)*m2.row(r), refMat4=dm5.col(c1)*refMat2.row(r));\n      VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count());\n      VERIFY_IS_APPROX( m4=dm5.col(c1)*m2.middleRows(r,1), refMat4=dm5.col(c1)*refMat2.row(r));\n      VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count());\n      VERIFY_IS_APPROX(dm4=dm5.col(c1)*m2.row(r), refMat4=dm5.col(c1)*refMat2.row(r));\n\n      VERIFY_IS_APPROX( m4=dm5.row(r1).transpose()*m2.row(r), refMat4=dm5.row(r1).transpose()*refMat2.row(r));\n      VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count());\n      VERIFY_IS_APPROX(dm4=dm5.row(r1).transpose()*m2.row(r), refMat4=dm5.row(r1).transpose()*refMat2.row(r));\n    }\n\n    VERIFY_IS_APPROX(m6=m6*m6, refMat6=refMat6*refMat6);\n\n    // sparse matrix * sparse vector\n    ColSpVector cv0(cols), cv1;\n    DenseVector dcv0(cols), dcv1;\n    initSparse(2*density,dcv0, cv0);\n\n    RowSpVector rv0(depth), rv1;\n    RowDenseVector drv0(depth), drv1(rv1);\n    initSparse(2*density,drv0, rv0);\n\n    VERIFY_IS_APPROX(cv1=m3*cv0, dcv1=refMat3*dcv0);\n    VERIFY_IS_APPROX(rv1=rv0*m3, drv1=drv0*refMat3);\n    VERIFY_IS_APPROX(cv1=m3t.adjoint()*cv0, dcv1=refMat3t.adjoint()*dcv0);\n    VERIFY_IS_APPROX(cv1=rv0*m3, dcv1=drv0*refMat3);\n    VERIFY_IS_APPROX(rv1=m3*cv0, drv1=refMat3*dcv0);\n  }\n\n  // test matrix - diagonal product\n  {\n    DenseMatrix refM2 = DenseMatrix::Zero(rows, cols);\n    DenseMatrix refM3 = DenseMatrix::Zero(rows, cols);\n    DenseMatrix d3 = DenseMatrix::Zero(rows, cols);\n    DiagonalMatrix<Scalar,Dynamic> d1(DenseVector::Random(cols));\n    DiagonalMatrix<Scalar,Dynamic> d2(DenseVector::Random(rows));\n    SparseMatrixType m2(rows, cols);\n    SparseMatrixType m3(rows, cols);\n    initSparse<Scalar>(density, refM2, m2);\n    initSparse<Scalar>(density, refM3, m3);\n    VERIFY_IS_APPROX(m3=m2*d1, refM3=refM2*d1);\n    VERIFY_IS_APPROX(m3=m2.transpose()*d2, refM3=refM2.transpose()*d2);\n    VERIFY_IS_APPROX(m3=d2*m2, refM3=d2*refM2);\n    VERIFY_IS_APPROX(m3=d1*m2.transpose(), refM3=d1*refM2.transpose());\n\n    // also check with a SparseWrapper:\n    DenseVector v1 = DenseVector::Random(cols);\n    DenseVector v2 = DenseVector::Random(rows);\n    DenseVector v3 = DenseVector::Random(rows);\n    VERIFY_IS_APPROX(m3=m2*v1.asDiagonal(), refM3=refM2*v1.asDiagonal());\n    VERIFY_IS_APPROX(m3=m2.transpose()*v2.asDiagonal(), refM3=refM2.transpose()*v2.asDiagonal());\n    VERIFY_IS_APPROX(m3=v2.asDiagonal()*m2, refM3=v2.asDiagonal()*refM2);\n    VERIFY_IS_APPROX(m3=v1.asDiagonal()*m2.transpose(), refM3=v1.asDiagonal()*refM2.transpose());\n\n    VERIFY_IS_APPROX(m3=v2.asDiagonal()*m2*v1.asDiagonal(), refM3=v2.asDiagonal()*refM2*v1.asDiagonal());\n\n    VERIFY_IS_APPROX(v2=m2*v1.asDiagonal()*v1, refM2*v1.asDiagonal()*v1);\n    VERIFY_IS_APPROX(v3=v2.asDiagonal()*m2*v1, v2.asDiagonal()*refM2*v1);\n\n    // evaluate to a dense matrix to check the .row() and .col() iterator functions\n    VERIFY_IS_APPROX(d3=m2*d1, refM3=refM2*d1);\n    VERIFY_IS_APPROX(d3=m2.transpose()*d2, refM3=refM2.transpose()*d2);\n    VERIFY_IS_APPROX(d3=d2*m2, refM3=d2*refM2);\n    VERIFY_IS_APPROX(d3=d1*m2.transpose(), refM3=d1*refM2.transpose());\n  }\n\n  // test self-adjoint and triangular-view products\n  {\n    DenseMatrix b = DenseMatrix::Random(rows, rows);\n    DenseMatrix x = DenseMatrix::Random(rows, rows);\n    DenseMatrix refX = DenseMatrix::Random(rows, rows);\n    DenseMatrix refUp = DenseMatrix::Zero(rows, rows);\n    DenseMatrix refLo = DenseMatrix::Zero(rows, rows);\n    DenseMatrix refS = DenseMatrix::Zero(rows, rows);\n    DenseMatrix refA = DenseMatrix::Zero(rows, rows);\n    SparseMatrixType mUp(rows, rows);\n    SparseMatrixType mLo(rows, rows);\n    SparseMatrixType mS(rows, rows);\n    SparseMatrixType mA(rows, rows);\n    initSparse<Scalar>(density, refA, mA);\n    do {\n      initSparse<Scalar>(density, refUp, mUp, ForceRealDiag|/*ForceNonZeroDiag|*/MakeUpperTriangular);\n    } while (refUp.isZero());\n    refLo = refUp.adjoint();\n    mLo = mUp.adjoint();\n    refS = refUp + refLo;\n    refS.diagonal() *= 0.5;\n    mS = mUp + mLo;\n    // TODO be able to address the diagonal....\n    for (int k=0; k<mS.outerSize(); ++k)\n      for (typename SparseMatrixType::InnerIterator it(mS,k); it; ++it)\n        if (it.index() == k)\n          it.valueRef() *= Scalar(0.5);\n\n    VERIFY_IS_APPROX(refS.adjoint(), refS);\n    VERIFY_IS_APPROX(mS.adjoint(), mS);\n    VERIFY_IS_APPROX(mS, refS);\n    VERIFY_IS_APPROX(x=mS*b, refX=refS*b);\n\n    // sparse selfadjointView with dense matrices\n    VERIFY_IS_APPROX(x=mUp.template selfadjointView<Upper>()*b, refX=refS*b);\n    VERIFY_IS_APPROX(x=mLo.template selfadjointView<Lower>()*b, refX=refS*b);\n    VERIFY_IS_APPROX(x=mS.template selfadjointView<Upper|Lower>()*b, refX=refS*b);\n\n    VERIFY_IS_APPROX(x=b * mUp.template selfadjointView<Upper>(),       refX=b*refS);\n    VERIFY_IS_APPROX(x=b * mLo.template selfadjointView<Lower>(),       refX=b*refS);\n    VERIFY_IS_APPROX(x=b * mS.template selfadjointView<Upper|Lower>(),  refX=b*refS);\n\n    VERIFY_IS_APPROX(x.noalias()+=mUp.template selfadjointView<Upper>()*b, refX+=refS*b);\n    VERIFY_IS_APPROX(x.noalias()-=mLo.template selfadjointView<Lower>()*b, refX-=refS*b);\n    VERIFY_IS_APPROX(x.noalias()+=mS.template selfadjointView<Upper|Lower>()*b, refX+=refS*b);\n\n    // sparse selfadjointView with sparse matrices\n    SparseMatrixType mSres(rows,rows);\n    VERIFY_IS_APPROX(mSres = mLo.template selfadjointView<Lower>()*mS,\n                     refX = refLo.template selfadjointView<Lower>()*refS);\n    VERIFY_IS_APPROX(mSres = mS * mLo.template selfadjointView<Lower>(),\n                     refX = refS * refLo.template selfadjointView<Lower>());\n\n    // sparse triangularView with dense matrices\n    VERIFY_IS_APPROX(x=mA.template triangularView<Upper>()*b, refX=refA.template triangularView<Upper>()*b);\n    VERIFY_IS_APPROX(x=mA.template triangularView<Lower>()*b, refX=refA.template triangularView<Lower>()*b);\n    VERIFY_IS_APPROX(x=b*mA.template triangularView<Upper>(), refX=b*refA.template triangularView<Upper>());\n    VERIFY_IS_APPROX(x=b*mA.template triangularView<Lower>(), refX=b*refA.template triangularView<Lower>());\n\n    // sparse triangularView with sparse matrices\n    VERIFY_IS_APPROX(mSres = mA.template triangularView<Lower>()*mS,   refX = refA.template triangularView<Lower>()*refS);\n    VERIFY_IS_APPROX(mSres = mS * mA.template triangularView<Lower>(), refX = refS * refA.template triangularView<Lower>());\n    VERIFY_IS_APPROX(mSres = mA.template triangularView<Upper>()*mS,   refX = refA.template triangularView<Upper>()*refS);\n    VERIFY_IS_APPROX(mSres = mS * mA.template triangularView<Upper>(), refX = refS * refA.template triangularView<Upper>());\n  }\n}\n\n// New test for Bug in SparseTimeDenseProduct\ntemplate<typename SparseMatrixType, typename DenseMatrixType> void sparse_product_regression_test()\n{\n  // This code does not compile with afflicted versions of the bug\n  SparseMatrixType sm1(3,2);\n  DenseMatrixType m2(2,2);\n  sm1.setZero();\n  m2.setZero();\n\n  DenseMatrixType m3 = sm1*m2;\n\n\n  // This code produces a segfault with afflicted versions of another SparseTimeDenseProduct\n  // bug\n\n  SparseMatrixType sm2(20000,2);\n  sm2.setZero();\n  DenseMatrixType m4(sm2*m2);\n\n  VERIFY_IS_APPROX( m4(0,0), 0.0 );\n}\n\ntemplate<typename Scalar>\nvoid bug_942()\n{\n  typedef Matrix<Scalar, Dynamic, 1>     Vector;\n  typedef SparseMatrix<Scalar, ColMajor> ColSpMat;\n  typedef SparseMatrix<Scalar, RowMajor> RowSpMat;\n  ColSpMat cmA(1,1);\n  cmA.insert(0,0) = 1;\n\n  RowSpMat rmA(1,1);\n  rmA.insert(0,0) = 1;\n\n  Vector d(1);\n  d[0] = 2;\n\n  double res = 2;\n\n  VERIFY_IS_APPROX( ( cmA*d.asDiagonal() ).eval().coeff(0,0), res );\n  VERIFY_IS_APPROX( ( d.asDiagonal()*rmA ).eval().coeff(0,0), res );\n  VERIFY_IS_APPROX( ( rmA*d.asDiagonal() ).eval().coeff(0,0), res );\n  VERIFY_IS_APPROX( ( d.asDiagonal()*cmA ).eval().coeff(0,0), res );\n}\n\ntemplate<typename Real>\nvoid test_mixing_types()\n{\n  typedef std::complex<Real> Cplx;\n  typedef SparseMatrix<Real> SpMatReal;\n  typedef SparseMatrix<Cplx> SpMatCplx;\n  typedef SparseMatrix<Cplx,RowMajor> SpRowMatCplx;\n  typedef Matrix<Real,Dynamic,Dynamic> DenseMatReal;\n  typedef Matrix<Cplx,Dynamic,Dynamic> DenseMatCplx;\n\n  Index n = internal::random<Index>(1,100);\n  double density = (std::max)(8./(n*n), 0.2);\n\n  SpMatReal sR1(n,n);\n  SpMatCplx sC1(n,n), sC2(n,n), sC3(n,n);\n  SpRowMatCplx sCR(n,n);\n  DenseMatReal dR1(n,n);\n  DenseMatCplx dC1(n,n), dC2(n,n), dC3(n,n);\n\n  initSparse<Real>(density, dR1, sR1);\n  initSparse<Cplx>(density, dC1, sC1);\n  initSparse<Cplx>(density, dC2, sC2);\n\n  VERIFY_IS_APPROX( sC2 = (sR1 * sC1),                         dC3 = dR1.template cast<Cplx>() * dC1 );\n  VERIFY_IS_APPROX( sC2 = (sC1 * sR1),                         dC3 = dC1 * dR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( sC2 = (sR1.transpose() * sC1),             dC3 = dR1.template cast<Cplx>().transpose() * dC1 );\n  VERIFY_IS_APPROX( sC2 = (sC1.transpose() * sR1),             dC3 = dC1.transpose() * dR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( sC2 = (sR1 * sC1.transpose()),             dC3 = dR1.template cast<Cplx>() * dC1.transpose() );\n  VERIFY_IS_APPROX( sC2 = (sC1 * sR1.transpose()),             dC3 = dC1 * dR1.template cast<Cplx>().transpose() );\n  VERIFY_IS_APPROX( sC2 = (sR1.transpose() * sC1.transpose()), dC3 = dR1.template cast<Cplx>().transpose() * dC1.transpose() );\n  VERIFY_IS_APPROX( sC2 = (sC1.transpose() * sR1.transpose()), dC3 = dC1.transpose() * dR1.template cast<Cplx>().transpose() );\n\n  VERIFY_IS_APPROX( sCR = (sR1 * sC1),                         dC3 = dR1.template cast<Cplx>() * dC1 );\n  VERIFY_IS_APPROX( sCR = (sC1 * sR1),                         dC3 = dC1 * dR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( sCR = (sR1.transpose() * sC1),             dC3 = dR1.template cast<Cplx>().transpose() * dC1 );\n  VERIFY_IS_APPROX( sCR = (sC1.transpose() * sR1),             dC3 = dC1.transpose() * dR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( sCR = (sR1 * sC1.transpose()),             dC3 = dR1.template cast<Cplx>() * dC1.transpose() );\n  VERIFY_IS_APPROX( sCR = (sC1 * sR1.transpose()),             dC3 = dC1 * dR1.template cast<Cplx>().transpose() );\n  VERIFY_IS_APPROX( sCR = (sR1.transpose() * sC1.transpose()), dC3 = dR1.template cast<Cplx>().transpose() * dC1.transpose() );\n  VERIFY_IS_APPROX( sCR = (sC1.transpose() * sR1.transpose()), dC3 = dC1.transpose() * dR1.template cast<Cplx>().transpose() );\n\n\n  VERIFY_IS_APPROX( sC2 = (sR1 * sC1).pruned(),                         dC3 = dR1.template cast<Cplx>() * dC1 );\n  VERIFY_IS_APPROX( sC2 = (sC1 * sR1).pruned(),                         dC3 = dC1 * dR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( sC2 = (sR1.transpose() * sC1).pruned(),             dC3 = dR1.template cast<Cplx>().transpose() * dC1 );\n  VERIFY_IS_APPROX( sC2 = (sC1.transpose() * sR1).pruned(),             dC3 = dC1.transpose() * dR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( sC2 = (sR1 * sC1.transpose()).pruned(),             dC3 = dR1.template cast<Cplx>() * dC1.transpose() );\n  VERIFY_IS_APPROX( sC2 = (sC1 * sR1.transpose()).pruned(),             dC3 = dC1 * dR1.template cast<Cplx>().transpose() );\n  VERIFY_IS_APPROX( sC2 = (sR1.transpose() * sC1.transpose()).pruned(), dC3 = dR1.template cast<Cplx>().transpose() * dC1.transpose() );\n  VERIFY_IS_APPROX( sC2 = (sC1.transpose() * sR1.transpose()).pruned(), dC3 = dC1.transpose() * dR1.template cast<Cplx>().transpose() );\n\n  VERIFY_IS_APPROX( sCR = (sR1 * sC1).pruned(),                         dC3 = dR1.template cast<Cplx>() * dC1 );\n  VERIFY_IS_APPROX( sCR = (sC1 * sR1).pruned(),                         dC3 = dC1 * dR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( sCR = (sR1.transpose() * sC1).pruned(),             dC3 = dR1.template cast<Cplx>().transpose() * dC1 );\n  VERIFY_IS_APPROX( sCR = (sC1.transpose() * sR1).pruned(),             dC3 = dC1.transpose() * dR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( sCR = (sR1 * sC1.transpose()).pruned(),             dC3 = dR1.template cast<Cplx>() * dC1.transpose() );\n  VERIFY_IS_APPROX( sCR = (sC1 * sR1.transpose()).pruned(),             dC3 = dC1 * dR1.template cast<Cplx>().transpose() );\n  VERIFY_IS_APPROX( sCR = (sR1.transpose() * sC1.transpose()).pruned(), dC3 = dR1.template cast<Cplx>().transpose() * dC1.transpose() );\n  VERIFY_IS_APPROX( sCR = (sC1.transpose() * sR1.transpose()).pruned(), dC3 = dC1.transpose() * dR1.template cast<Cplx>().transpose() );\n\n\n  VERIFY_IS_APPROX( dC2 = (sR1 * sC1),                         dC3 = dR1.template cast<Cplx>() * dC1 );\n  VERIFY_IS_APPROX( dC2 = (sC1 * sR1),                         dC3 = dC1 * dR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( dC2 = (sR1.transpose() * sC1),             dC3 = dR1.template cast<Cplx>().transpose() * dC1 );\n  VERIFY_IS_APPROX( dC2 = (sC1.transpose() * sR1),             dC3 = dC1.transpose() * dR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( dC2 = (sR1 * sC1.transpose()),             dC3 = dR1.template cast<Cplx>() * dC1.transpose() );\n  VERIFY_IS_APPROX( dC2 = (sC1 * sR1.transpose()),             dC3 = dC1 * dR1.template cast<Cplx>().transpose() );\n  VERIFY_IS_APPROX( dC2 = (sR1.transpose() * sC1.transpose()), dC3 = dR1.template cast<Cplx>().transpose() * dC1.transpose() );\n  VERIFY_IS_APPROX( dC2 = (sC1.transpose() * sR1.transpose()), dC3 = dC1.transpose() * dR1.template cast<Cplx>().transpose() );\n\n\n  VERIFY_IS_APPROX( dC2 = dR1 * sC1, dC3 = dR1.template cast<Cplx>() * sC1 );\n  VERIFY_IS_APPROX( dC2 = sR1 * dC1, dC3 = sR1.template cast<Cplx>() * dC1 );\n  VERIFY_IS_APPROX( dC2 = dC1 * sR1, dC3 = dC1 * sR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( dC2 = sC1 * dR1, dC3 = sC1 * dR1.template cast<Cplx>() );\n\n  VERIFY_IS_APPROX( dC2 = dR1.row(0) * sC1, dC3 = dR1.template cast<Cplx>().row(0) * sC1 );\n  VERIFY_IS_APPROX( dC2 = sR1 * dC1.col(0), dC3 = sR1.template cast<Cplx>() * dC1.col(0) );\n  VERIFY_IS_APPROX( dC2 = dC1.row(0) * sR1, dC3 = dC1.row(0) * sR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( dC2 = sC1 * dR1.col(0), dC3 = sC1 * dR1.template cast<Cplx>().col(0) );\n}\n\nEIGEN_DECLARE_TEST(sparse_product)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( (sparse_product<SparseMatrix<double,ColMajor> >()) );\n    CALL_SUBTEST_1( (sparse_product<SparseMatrix<double,RowMajor> >()) );\n    CALL_SUBTEST_1( (bug_942<double>()) );\n    CALL_SUBTEST_2( (sparse_product<SparseMatrix<std::complex<double>, ColMajor > >()) );\n    CALL_SUBTEST_2( (sparse_product<SparseMatrix<std::complex<double>, RowMajor > >()) );\n    CALL_SUBTEST_3( (sparse_product<SparseMatrix<float,ColMajor,long int> >()) );\n    CALL_SUBTEST_4( (sparse_product_regression_test<SparseMatrix<double,RowMajor>, Matrix<double, Dynamic, Dynamic, RowMajor> >()) );\n\n    CALL_SUBTEST_5( (test_mixing_types<float>()) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/sparse_ref.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 20015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// This unit test cannot be easily written to work with EIGEN_DEFAULT_TO_ROW_MAJOR\n#ifdef EIGEN_DEFAULT_TO_ROW_MAJOR\n#undef EIGEN_DEFAULT_TO_ROW_MAJOR\n#endif\n\nstatic long int nb_temporaries;\n\ninline void on_temporary_creation() {\n  // here's a great place to set a breakpoint when debugging failures in this test!\n  nb_temporaries++;\n}\n\n#define EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN { on_temporary_creation(); }\n\n#include \"main.h\"\n#include <Eigen/SparseCore>\n\n#define VERIFY_EVALUATION_COUNT(XPR,N) {\\\n    nb_temporaries = 0; \\\n    CALL_SUBTEST( XPR ); \\\n    if(nb_temporaries!=N) std::cerr << \"nb_temporaries == \" << nb_temporaries << \"\\n\"; \\\n    VERIFY( (#XPR) && nb_temporaries==N ); \\\n  }\n\ntemplate<typename PlainObjectType> void check_const_correctness(const PlainObjectType&)\n{\n  // verify that ref-to-const don't have LvalueBit\n  typedef typename internal::add_const<PlainObjectType>::type ConstPlainObjectType;\n  VERIFY( !(internal::traits<Ref<ConstPlainObjectType> >::Flags & LvalueBit) );\n  VERIFY( !(internal::traits<Ref<ConstPlainObjectType, Aligned> >::Flags & LvalueBit) );\n  VERIFY( !(Ref<ConstPlainObjectType>::Flags & LvalueBit) );\n  VERIFY( !(Ref<ConstPlainObjectType, Aligned>::Flags & LvalueBit) );\n}\n\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_1(Ref<SparseMatrix<float> > a, const B &b) { VERIFY_IS_EQUAL(a.toDense(),b.toDense()); }\n\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_2(const Ref<const SparseMatrix<float> >& a, const B &b) { VERIFY_IS_EQUAL(a.toDense(),b.toDense()); }\n\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_3(const Ref<const SparseMatrix<float>, StandardCompressedFormat>& a, const B &b) {\n  VERIFY(a.isCompressed());\n  VERIFY_IS_EQUAL(a.toDense(),b.toDense());\n}\n\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_4(Ref<SparseVector<float> > a, const B &b) { VERIFY_IS_EQUAL(a.toDense(),b.toDense()); }\n\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_5(const Ref<const SparseVector<float> >& a, const B &b) { VERIFY_IS_EQUAL(a.toDense(),b.toDense()); }\n\nvoid call_ref()\n{\n  SparseMatrix<float>               A = MatrixXf::Random(10,10).sparseView(0.5,1);\n  SparseMatrix<float,RowMajor>      B = MatrixXf::Random(10,10).sparseView(0.5,1);\n  SparseMatrix<float>               C = MatrixXf::Random(10,10).sparseView(0.5,1);\n  C.reserve(VectorXi::Constant(C.outerSize(), 2));\n  const SparseMatrix<float>&        Ac(A);\n  Block<SparseMatrix<float> >       Ab(A,0,1, 3,3);\n  const Block<SparseMatrix<float> > Abc(A,0,1,3,3);\n  SparseVector<float>               vc =  VectorXf::Random(10).sparseView(0.5,1);\n  SparseVector<float,RowMajor>      vr =  VectorXf::Random(10).sparseView(0.5,1);\n  SparseMatrix<float> AA = A*A;\n  \n\n  VERIFY_EVALUATION_COUNT( call_ref_1(A, A),  0);\n//   VERIFY_EVALUATION_COUNT( call_ref_1(Ac, Ac),  0); // does not compile on purpose\n  VERIFY_EVALUATION_COUNT( call_ref_2(A, A),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_3(A, A),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(A.transpose(), A.transpose()),  1);\n  VERIFY_EVALUATION_COUNT( call_ref_3(A.transpose(), A.transpose()),  1);\n  VERIFY_EVALUATION_COUNT( call_ref_2(Ac,Ac), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_3(Ac,Ac), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(A+A,2*Ac), 1);\n  VERIFY_EVALUATION_COUNT( call_ref_3(A+A,2*Ac), 1);\n  VERIFY_EVALUATION_COUNT( call_ref_2(B, B),  1);\n  VERIFY_EVALUATION_COUNT( call_ref_3(B, B),  1);\n  VERIFY_EVALUATION_COUNT( call_ref_2(B.transpose(), B.transpose()),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_3(B.transpose(), B.transpose()),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(A*A, AA),  3);\n  VERIFY_EVALUATION_COUNT( call_ref_3(A*A, AA),  3);\n  \n  VERIFY(!C.isCompressed());\n  VERIFY_EVALUATION_COUNT( call_ref_3(C, C),  1);\n  \n  Ref<SparseMatrix<float> > Ar(A);\n  VERIFY_IS_APPROX(Ar+Ar, A+A);\n  VERIFY_EVALUATION_COUNT( call_ref_1(Ar, A),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(Ar, A),  0);\n  \n  Ref<SparseMatrix<float,RowMajor> > Br(B);\n  VERIFY_EVALUATION_COUNT( call_ref_1(Br.transpose(), Br.transpose()),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(Br, Br),  1);\n  VERIFY_EVALUATION_COUNT( call_ref_2(Br.transpose(), Br.transpose()),  0);\n  \n  Ref<const SparseMatrix<float> > Arc(A);\n//   VERIFY_EVALUATION_COUNT( call_ref_1(Arc, Arc),  0); // does not compile on purpose\n  VERIFY_EVALUATION_COUNT( call_ref_2(Arc, Arc),  0);\n  \n  VERIFY_EVALUATION_COUNT( call_ref_2(A.middleCols(1,3), A.middleCols(1,3)),  0);\n  \n  VERIFY_EVALUATION_COUNT( call_ref_2(A.col(2), A.col(2)),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(vc, vc),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(vr.transpose(), vr.transpose()),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(vr, vr.transpose()),  0);\n  \n  VERIFY_EVALUATION_COUNT( call_ref_2(A.block(1,1,3,3), A.block(1,1,3,3)),  1); // should be 0 (allocate starts/nnz only)\n\n  VERIFY_EVALUATION_COUNT( call_ref_4(vc, vc),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_4(vr, vr.transpose()),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_5(vc, vc),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_5(vr, vr.transpose()),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_4(A.col(2), A.col(2)),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_5(A.col(2), A.col(2)),  0);\n  // VERIFY_EVALUATION_COUNT( call_ref_4(A.row(2), A.row(2).transpose()),  1); // does not compile on purpose\n  VERIFY_EVALUATION_COUNT( call_ref_5(A.row(2), A.row(2).transpose()),  1);\n}\n\nEIGEN_DECLARE_TEST(sparse_ref)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( check_const_correctness(SparseMatrix<float>()) );\n    CALL_SUBTEST_1( check_const_correctness(SparseMatrix<double,RowMajor>()) );\n    CALL_SUBTEST_2( call_ref() );\n\n    CALL_SUBTEST_3( check_const_correctness(SparseVector<float>()) );\n    CALL_SUBTEST_3( check_const_correctness(SparseVector<double,RowMajor>()) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/sparse_solver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"sparse.h\"\n#include <Eigen/SparseCore>\n#include <Eigen/SparseLU>\n#include <sstream>\n\ntemplate<typename Solver, typename Rhs, typename Guess,typename Result>\nvoid solve_with_guess(IterativeSolverBase<Solver>& solver, const MatrixBase<Rhs>& b, const Guess& g, Result &x) {\n  if(internal::random<bool>())\n  {\n    // With a temporary through evaluator<SolveWithGuess>\n    x = solver.derived().solveWithGuess(b,g) + Result::Zero(x.rows(), x.cols());\n  }\n  else\n  {\n    // direct evaluation within x through Assignment<Result,SolveWithGuess>\n    x = solver.derived().solveWithGuess(b.derived(),g);\n  }\n}\n\ntemplate<typename Solver, typename Rhs, typename Guess,typename Result>\nvoid solve_with_guess(SparseSolverBase<Solver>& solver, const MatrixBase<Rhs>& b, const Guess& , Result& x) {\n  if(internal::random<bool>())\n    x = solver.derived().solve(b) + Result::Zero(x.rows(), x.cols());\n  else\n    x = solver.derived().solve(b);\n}\n\ntemplate<typename Solver, typename Rhs, typename Guess,typename Result>\nvoid solve_with_guess(SparseSolverBase<Solver>& solver, const SparseMatrixBase<Rhs>& b, const Guess& , Result& x) {\n  x = solver.derived().solve(b);\n}\n\ntemplate<typename Solver, typename Rhs, typename DenseMat, typename DenseRhs>\nvoid check_sparse_solving(Solver& solver, const typename Solver::MatrixType& A, const Rhs& b, const DenseMat& dA, const DenseRhs& db)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  typedef typename Mat::StorageIndex StorageIndex;\n\n  DenseRhs refX = dA.householderQr().solve(db);\n  {\n    Rhs x(A.cols(), b.cols());\n    Rhs oldb = b;\n\n    solver.compute(A);\n    if (solver.info() != Success)\n    {\n      std::cerr << \"ERROR | sparse solver testing, factorization failed (\" << typeid(Solver).name() << \")\\n\";\n      VERIFY(solver.info() == Success);\n    }\n    x = solver.solve(b);\n    if (solver.info() != Success)\n    {\n      std::cerr << \"WARNING: sparse solver testing: solving failed (\" << typeid(Solver).name() << \")\\n\";\n      // dump call stack:\n      g_test_level++; \n      VERIFY(solver.info() == Success);\n      g_test_level--;\n      return;\n    }\n    VERIFY(oldb.isApprox(b) && \"sparse solver testing: the rhs should not be modified!\");\n    VERIFY(x.isApprox(refX,test_precision<Scalar>()));\n\n    x.setZero();\n    solve_with_guess(solver, b, x, x);\n    VERIFY(solver.info() == Success && \"solving failed when using solve_with_guess API\");\n    VERIFY(oldb.isApprox(b) && \"sparse solver testing: the rhs should not be modified!\");\n    VERIFY(x.isApprox(refX,test_precision<Scalar>()));\n    \n    x.setZero();\n    // test the analyze/factorize API\n    solver.analyzePattern(A);\n    solver.factorize(A);\n    VERIFY(solver.info() == Success && \"factorization failed when using analyzePattern/factorize API\");\n    x = solver.solve(b);\n    VERIFY(solver.info() == Success && \"solving failed when using analyzePattern/factorize API\");\n    VERIFY(oldb.isApprox(b) && \"sparse solver testing: the rhs should not be modified!\");\n    VERIFY(x.isApprox(refX,test_precision<Scalar>()));\n    \n    x.setZero();\n    // test with Map\n    MappedSparseMatrix<Scalar,Mat::Options,StorageIndex> Am(A.rows(), A.cols(), A.nonZeros(), const_cast<StorageIndex*>(A.outerIndexPtr()), const_cast<StorageIndex*>(A.innerIndexPtr()), const_cast<Scalar*>(A.valuePtr()));\n    solver.compute(Am);\n    VERIFY(solver.info() == Success && \"factorization failed when using Map\");\n    DenseRhs dx(refX);\n    dx.setZero();\n    Map<DenseRhs> xm(dx.data(), dx.rows(), dx.cols());\n    Map<const DenseRhs> bm(db.data(), db.rows(), db.cols());\n    xm = solver.solve(bm);\n    VERIFY(solver.info() == Success && \"solving failed when using Map\");\n    VERIFY(oldb.isApprox(bm) && \"sparse solver testing: the rhs should not be modified!\");\n    VERIFY(xm.isApprox(refX,test_precision<Scalar>()));\n  }\n  \n  // if not too large, do some extra check:\n  if(A.rows()<2000)\n  {\n    // test initialization ctor\n    {\n      Rhs x(b.rows(), b.cols());\n      Solver solver2(A);\n      VERIFY(solver2.info() == Success);\n      x = solver2.solve(b);\n      VERIFY(x.isApprox(refX,test_precision<Scalar>()));\n    }\n\n    // test dense Block as the result and rhs:\n    {\n      DenseRhs x(refX.rows(), refX.cols());\n      DenseRhs oldb(db);\n      x.setZero();\n      x.block(0,0,x.rows(),x.cols()) = solver.solve(db.block(0,0,db.rows(),db.cols()));\n      VERIFY(oldb.isApprox(db) && \"sparse solver testing: the rhs should not be modified!\");\n      VERIFY(x.isApprox(refX,test_precision<Scalar>()));\n    }\n\n    // test uncompressed inputs\n    {\n      Mat A2 = A;\n      A2.reserve((ArrayXf::Random(A.outerSize())+2).template cast<typename Mat::StorageIndex>().eval());\n      solver.compute(A2);\n      Rhs x = solver.solve(b);\n      VERIFY(x.isApprox(refX,test_precision<Scalar>()));\n    }\n\n    // test expression as input\n    {\n      solver.compute(0.5*(A+A));\n      Rhs x = solver.solve(b);\n      VERIFY(x.isApprox(refX,test_precision<Scalar>()));\n\n      Solver solver2(0.5*(A+A));\n      Rhs x2 = solver2.solve(b);\n      VERIFY(x2.isApprox(refX,test_precision<Scalar>()));\n    }\n  }\n}\n\n// specialization of generic check_sparse_solving for SuperLU in order to also test adjoint and transpose solves\ntemplate<typename Scalar, typename Rhs, typename DenseMat, typename DenseRhs>\nvoid check_sparse_solving(Eigen::SparseLU<Eigen::SparseMatrix<Scalar> >& solver, const typename Eigen::SparseMatrix<Scalar>& A, const Rhs& b, const DenseMat& dA, const DenseRhs& db)\n{\n  typedef typename Eigen::SparseMatrix<Scalar> Mat;\n  typedef typename Mat::StorageIndex StorageIndex;\n  typedef typename Eigen::SparseLU<Eigen::SparseMatrix<Scalar> > Solver;\n\n  // reference solutions computed by dense QR solver\n  DenseRhs refX1 = dA.householderQr().solve(db); // solution of A x = db\n  DenseRhs refX2 = dA.transpose().householderQr().solve(db); // solution of A^T * x = db (use transposed matrix A^T)\n  DenseRhs refX3 = dA.adjoint().householderQr().solve(db);  // solution of A^* * x = db (use adjoint matrix A^*)\n\n\n  {\n    Rhs x1(A.cols(), b.cols());\n    Rhs x2(A.cols(), b.cols());\n    Rhs x3(A.cols(), b.cols());\n    Rhs oldb = b;\n\n    solver.compute(A);\n    if (solver.info() != Success)\n    {\n      std::cerr << \"ERROR | sparse solver testing, factorization failed (\" << typeid(Solver).name() << \")\\n\";\n      VERIFY(solver.info() == Success);\n    }\n    x1 = solver.solve(b);\n    if (solver.info() != Success)\n    {\n      std::cerr << \"WARNING | sparse solver testing: solving failed (\" << typeid(Solver).name() << \")\\n\";\n      return;\n    }\n    VERIFY(oldb.isApprox(b,0.0) && \"sparse solver testing: the rhs should not be modified!\");\n    VERIFY(x1.isApprox(refX1,test_precision<Scalar>()));\n\n    // test solve with transposed\n    x2 = solver.transpose().solve(b);\n    VERIFY(oldb.isApprox(b) && \"sparse solver testing: the rhs should not be modified!\");\n    VERIFY(x2.isApprox(refX2,test_precision<Scalar>()));\n\n\n    // test solve with adjoint\n    //solver.template _solve_impl_transposed<true>(b, x3);\n    x3 = solver.adjoint().solve(b);\n    VERIFY(oldb.isApprox(b,0.0) && \"sparse solver testing: the rhs should not be modified!\");\n    VERIFY(x3.isApprox(refX3,test_precision<Scalar>()));\n\n    x1.setZero();\n    solve_with_guess(solver, b, x1, x1);\n    VERIFY(solver.info() == Success && \"solving failed when using analyzePattern/factorize API\");\n    VERIFY(oldb.isApprox(b,0.0) && \"sparse solver testing: the rhs should not be modified!\");\n    VERIFY(x1.isApprox(refX1,test_precision<Scalar>()));\n\n    x1.setZero();\n    x2.setZero();\n    x3.setZero();\n    // test the analyze/factorize API\n    solver.analyzePattern(A);\n    solver.factorize(A);\n    VERIFY(solver.info() == Success && \"factorization failed when using analyzePattern/factorize API\");\n    x1 = solver.solve(b);\n    x2 = solver.transpose().solve(b);\n    x3 = solver.adjoint().solve(b);\n\n    VERIFY(solver.info() == Success && \"solving failed when using analyzePattern/factorize API\");\n    VERIFY(oldb.isApprox(b,0.0) && \"sparse solver testing: the rhs should not be modified!\");\n    VERIFY(x1.isApprox(refX1,test_precision<Scalar>()));\n    VERIFY(x2.isApprox(refX2,test_precision<Scalar>()));\n    VERIFY(x3.isApprox(refX3,test_precision<Scalar>()));\n\n    x1.setZero();\n    // test with Map\n    MappedSparseMatrix<Scalar,Mat::Options,StorageIndex> Am(A.rows(), A.cols(), A.nonZeros(), const_cast<StorageIndex*>(A.outerIndexPtr()), const_cast<StorageIndex*>(A.innerIndexPtr()), const_cast<Scalar*>(A.valuePtr()));\n    solver.compute(Am);\n    VERIFY(solver.info() == Success && \"factorization failed when using Map\");\n    DenseRhs dx(refX1);\n    dx.setZero();\n    Map<DenseRhs> xm(dx.data(), dx.rows(), dx.cols());\n    Map<const DenseRhs> bm(db.data(), db.rows(), db.cols());\n    xm = solver.solve(bm);\n    VERIFY(solver.info() == Success && \"solving failed when using Map\");\n    VERIFY(oldb.isApprox(bm,0.0) && \"sparse solver testing: the rhs should not be modified!\");\n    VERIFY(xm.isApprox(refX1,test_precision<Scalar>()));\n  }\n\n  // if not too large, do some extra check:\n  if(A.rows()<2000)\n  {\n    // test initialization ctor\n    {\n      Rhs x(b.rows(), b.cols());\n      Solver solver2(A);\n      VERIFY(solver2.info() == Success);\n      x = solver2.solve(b);\n      VERIFY(x.isApprox(refX1,test_precision<Scalar>()));\n    }\n\n    // test dense Block as the result and rhs:\n    {\n      DenseRhs x(refX1.rows(), refX1.cols());\n      DenseRhs oldb(db);\n      x.setZero();\n      x.block(0,0,x.rows(),x.cols()) = solver.solve(db.block(0,0,db.rows(),db.cols()));\n      VERIFY(oldb.isApprox(db,0.0) && \"sparse solver testing: the rhs should not be modified!\");\n      VERIFY(x.isApprox(refX1,test_precision<Scalar>()));\n    }\n\n    // test uncompressed inputs\n    {\n      Mat A2 = A;\n      A2.reserve((ArrayXf::Random(A.outerSize())+2).template cast<typename Mat::StorageIndex>().eval());\n      solver.compute(A2);\n      Rhs x = solver.solve(b);\n      VERIFY(x.isApprox(refX1,test_precision<Scalar>()));\n    }\n\n    // test expression as input\n    {\n      solver.compute(0.5*(A+A));\n      Rhs x = solver.solve(b);\n      VERIFY(x.isApprox(refX1,test_precision<Scalar>()));\n\n      Solver solver2(0.5*(A+A));\n      Rhs x2 = solver2.solve(b);\n      VERIFY(x2.isApprox(refX1,test_precision<Scalar>()));\n    }\n  }\n}\n\n\ntemplate<typename Solver, typename Rhs>\nvoid check_sparse_solving_real_cases(Solver& solver, const typename Solver::MatrixType& A, const Rhs& b, const typename Solver::MatrixType& fullA, const Rhs& refX)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  typedef typename Mat::RealScalar RealScalar;\n  \n  Rhs x(A.cols(), b.cols());\n\n  solver.compute(A);\n  if (solver.info() != Success)\n  {\n    std::cerr << \"ERROR | sparse solver testing, factorization failed (\" << typeid(Solver).name() << \")\\n\";\n    VERIFY(solver.info() == Success);\n  }\n  x = solver.solve(b);\n  \n  if (solver.info() != Success)\n  {\n    std::cerr << \"WARNING | sparse solver testing, solving failed (\" << typeid(Solver).name() << \")\\n\";\n    return;\n  }\n  \n  RealScalar res_error = (fullA*x-b).norm()/b.norm();  \n  VERIFY( (res_error <= test_precision<Scalar>() ) && \"sparse solver failed without noticing it\"); \n\n  \n  if(refX.size() != 0 && (refX - x).norm()/refX.norm() > test_precision<Scalar>())\n  {\n    std::cerr << \"WARNING | found solution is different from the provided reference one\\n\";\n  }\n  \n}\ntemplate<typename Solver, typename DenseMat>\nvoid check_sparse_determinant(Solver& solver, const typename Solver::MatrixType& A, const DenseMat& dA)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  \n  solver.compute(A);\n  if (solver.info() != Success)\n  {\n    std::cerr << \"WARNING | sparse solver testing: factorization failed (check_sparse_determinant)\\n\";\n    return;\n  }\n\n  Scalar refDet = dA.determinant();\n  VERIFY_IS_APPROX(refDet,solver.determinant());\n}\ntemplate<typename Solver, typename DenseMat>\nvoid check_sparse_abs_determinant(Solver& solver, const typename Solver::MatrixType& A, const DenseMat& dA)\n{\n  using std::abs;\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  \n  solver.compute(A);\n  if (solver.info() != Success)\n  {\n    std::cerr << \"WARNING | sparse solver testing: factorization failed (check_sparse_abs_determinant)\\n\";\n    return;\n  }\n\n  Scalar refDet = abs(dA.determinant());\n  VERIFY_IS_APPROX(refDet,solver.absDeterminant());\n}\n\ntemplate<typename Solver, typename DenseMat>\nint generate_sparse_spd_problem(Solver& , typename Solver::MatrixType& A, typename Solver::MatrixType& halfA, DenseMat& dA, int maxSize = 300)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n\n  int size = internal::random<int>(1,maxSize);\n  double density = (std::max)(8./(size*size), 0.01);\n\n  Mat M(size, size);\n  DenseMatrix dM(size, size);\n\n  initSparse<Scalar>(density, dM, M, ForceNonZeroDiag);\n\n  A = M * M.adjoint();\n  dA = dM * dM.adjoint();\n  \n  halfA.resize(size,size);\n  if(Solver::UpLo==(Lower|Upper))\n    halfA = A;\n  else\n    halfA.template selfadjointView<Solver::UpLo>().rankUpdate(M);\n  \n  return size;\n}\n\n\n#ifdef TEST_REAL_CASES\ntemplate<typename Scalar>\ninline std::string get_matrixfolder()\n{\n  std::string mat_folder = TEST_REAL_CASES; \n  if( internal::is_same<Scalar, std::complex<float> >::value || internal::is_same<Scalar, std::complex<double> >::value )\n    mat_folder  = mat_folder + static_cast<std::string>(\"/complex/\");\n  else\n    mat_folder = mat_folder + static_cast<std::string>(\"/real/\");\n  return mat_folder;\n}\nstd::string sym_to_string(int sym)\n{\n  if(sym==Symmetric) return \"Symmetric \";\n  if(sym==SPD)       return \"SPD \";\n  return \"\";\n}\ntemplate<typename Derived>\nstd::string solver_stats(const IterativeSolverBase<Derived> &solver)\n{\n  std::stringstream ss;\n  ss << solver.iterations() << \" iters, error: \" << solver.error();\n  return ss.str();\n}\ntemplate<typename Derived>\nstd::string solver_stats(const SparseSolverBase<Derived> &/*solver*/)\n{\n  return \"\";\n}\n#endif\n\ntemplate<typename Solver> void check_sparse_spd_solving(Solver& solver, int maxSize = (std::min)(300,EIGEN_TEST_MAX_SIZE), int maxRealWorldSize = 100000)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  typedef typename Mat::StorageIndex StorageIndex;\n  typedef SparseMatrix<Scalar,ColMajor, StorageIndex> SpMat;\n  typedef SparseVector<Scalar, 0, StorageIndex> SpVec;\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n\n  // generate the problem\n  Mat A, halfA;\n  DenseMatrix dA;\n  for (int i = 0; i < g_repeat; i++) {\n    int size = generate_sparse_spd_problem(solver, A, halfA, dA, maxSize);\n\n    // generate the right hand sides\n    int rhsCols = internal::random<int>(1,16);\n    double density = (std::max)(8./(size*rhsCols), 0.1);\n    SpMat B(size,rhsCols);\n    DenseVector b = DenseVector::Random(size);\n    DenseMatrix dB(size,rhsCols);\n    initSparse<Scalar>(density, dB, B, ForceNonZeroDiag);\n    SpVec c = B.col(0);\n    DenseVector dc = dB.col(0);\n  \n    CALL_SUBTEST( check_sparse_solving(solver, A,     b,  dA, b)  );\n    CALL_SUBTEST( check_sparse_solving(solver, halfA, b,  dA, b)  );\n    CALL_SUBTEST( check_sparse_solving(solver, A,     dB, dA, dB) );\n    CALL_SUBTEST( check_sparse_solving(solver, halfA, dB, dA, dB) );\n    CALL_SUBTEST( check_sparse_solving(solver, A,     B,  dA, dB) );\n    CALL_SUBTEST( check_sparse_solving(solver, halfA, B,  dA, dB) );\n    CALL_SUBTEST( check_sparse_solving(solver, A,     c,  dA, dc) );\n    CALL_SUBTEST( check_sparse_solving(solver, halfA, c,  dA, dc) );\n    \n    // check only once\n    if(i==0)\n    {\n      b = DenseVector::Zero(size);\n      check_sparse_solving(solver, A, b, dA, b);\n    }\n  }\n  \n  // First, get the folder \n#ifdef TEST_REAL_CASES\n  // Test real problems with double precision only\n  if (internal::is_same<typename NumTraits<Scalar>::Real, double>::value)\n  {\n    std::string mat_folder = get_matrixfolder<Scalar>();\n    MatrixMarketIterator<Scalar> it(mat_folder);\n    for (; it; ++it)\n    {\n      if (it.sym() == SPD){\n        A = it.matrix();\n        if(A.diagonal().size() <= maxRealWorldSize)\n        {\n          DenseVector b = it.rhs();\n          DenseVector refX = it.refX();\n          PermutationMatrix<Dynamic, Dynamic, StorageIndex> pnull;\n          halfA.resize(A.rows(), A.cols());\n          if(Solver::UpLo == (Lower|Upper))\n            halfA = A;\n          else\n            halfA.template selfadjointView<Solver::UpLo>() = A.template triangularView<Eigen::Lower>().twistedBy(pnull);\n          \n          std::cout << \"INFO | Testing \" << sym_to_string(it.sym()) << \"sparse problem \" << it.matname()\n                  << \" (\" << A.rows() << \"x\" << A.cols() << \") using \" << typeid(Solver).name() << \"...\" << std::endl;\n          CALL_SUBTEST( check_sparse_solving_real_cases(solver, A,     b, A, refX) );\n          std::string stats = solver_stats(solver);\n          if(stats.size()>0)\n            std::cout << \"INFO |  \" << stats << std::endl;\n          CALL_SUBTEST( check_sparse_solving_real_cases(solver, halfA, b, A, refX) );\n        }\n        else\n        {\n          std::cout << \"INFO | Skip sparse problem \\\"\" << it.matname() << \"\\\" (too large)\" << std::endl;\n        }\n      }\n    }\n  }\n#else\n  EIGEN_UNUSED_VARIABLE(maxRealWorldSize);\n#endif\n}\n\ntemplate<typename Solver> void check_sparse_spd_determinant(Solver& solver)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n\n  // generate the problem\n  Mat A, halfA;\n  DenseMatrix dA;\n  generate_sparse_spd_problem(solver, A, halfA, dA, 30);\n  \n  for (int i = 0; i < g_repeat; i++) {\n    check_sparse_determinant(solver, A,     dA);\n    check_sparse_determinant(solver, halfA, dA );\n  }\n}\n\ntemplate<typename Solver, typename DenseMat>\nIndex generate_sparse_square_problem(Solver&, typename Solver::MatrixType& A, DenseMat& dA, int maxSize = 300, int options = ForceNonZeroDiag)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n\n  Index size = internal::random<int>(1,maxSize);\n  double density = (std::max)(8./(size*size), 0.01);\n  \n  A.resize(size,size);\n  dA.resize(size,size);\n\n  initSparse<Scalar>(density, dA, A, options);\n  \n  return size;\n}\n\n\nstruct prune_column {\n  Index m_col;\n  prune_column(Index col) : m_col(col) {}\n  template<class Scalar>\n  bool operator()(Index, Index col, const Scalar&) const {\n    return col != m_col;\n  }\n};\n\n\ntemplate<typename Solver> void check_sparse_square_solving(Solver& solver, int maxSize = 300, int maxRealWorldSize = 100000, bool checkDeficient = false)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  typedef SparseMatrix<Scalar,ColMajor, typename Mat::StorageIndex> SpMat;\n  typedef SparseVector<Scalar, 0, typename Mat::StorageIndex> SpVec;\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n\n  int rhsCols = internal::random<int>(1,16);\n\n  Mat A;\n  DenseMatrix dA;\n  for (int i = 0; i < g_repeat; i++) {\n    Index size = generate_sparse_square_problem(solver, A, dA, maxSize);\n\n    A.makeCompressed();\n    DenseVector b = DenseVector::Random(size);\n    DenseMatrix dB(size,rhsCols);\n    SpMat B(size,rhsCols);\n    double density = (std::max)(8./(size*rhsCols), 0.1);\n    initSparse<Scalar>(density, dB, B, ForceNonZeroDiag);\n    B.makeCompressed();\n    SpVec c = B.col(0);\n    DenseVector dc = dB.col(0);\n    CALL_SUBTEST(check_sparse_solving(solver, A, b,  dA, b));\n    CALL_SUBTEST(check_sparse_solving(solver, A, dB, dA, dB));\n    CALL_SUBTEST(check_sparse_solving(solver, A, B,  dA, dB));\n    CALL_SUBTEST(check_sparse_solving(solver, A, c,  dA, dc));\n    \n    // check only once\n    if(i==0)\n    {\n      CALL_SUBTEST(b = DenseVector::Zero(size); check_sparse_solving(solver, A, b, dA, b));\n    }\n    // regression test for Bug 792 (structurally rank deficient matrices):\n    if(checkDeficient && size>1) {\n      Index col = internal::random<int>(0,int(size-1));\n      A.prune(prune_column(col));\n      solver.compute(A);\n      VERIFY_IS_EQUAL(solver.info(), NumericalIssue);\n    }\n  }\n  \n  // First, get the folder \n#ifdef TEST_REAL_CASES\n  // Test real problems with double precision only\n  if (internal::is_same<typename NumTraits<Scalar>::Real, double>::value)\n  {\n    std::string mat_folder = get_matrixfolder<Scalar>();\n    MatrixMarketIterator<Scalar> it(mat_folder);\n    for (; it; ++it)\n    {\n      A = it.matrix();\n      if(A.diagonal().size() <= maxRealWorldSize)\n      {\n        DenseVector b = it.rhs();\n        DenseVector refX = it.refX();\n        std::cout << \"INFO | Testing \" << sym_to_string(it.sym()) << \"sparse problem \" << it.matname()\n                  << \" (\" << A.rows() << \"x\" << A.cols() << \") using \" << typeid(Solver).name() << \"...\" << std::endl;\n        CALL_SUBTEST(check_sparse_solving_real_cases(solver, A, b, A, refX));\n        std::string stats = solver_stats(solver);\n        if(stats.size()>0)\n          std::cout << \"INFO |  \" << stats << std::endl;\n      }\n      else\n      {\n        std::cout << \"INFO | SKIP sparse problem \\\"\" << it.matname() << \"\\\" (too large)\" << std::endl;\n      }\n    }\n  }\n#else\n  EIGEN_UNUSED_VARIABLE(maxRealWorldSize);\n#endif\n\n}\n\ntemplate<typename Solver> void check_sparse_square_determinant(Solver& solver)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  \n  for (int i = 0; i < g_repeat; i++) {\n    // generate the problem\n    Mat A;\n    DenseMatrix dA;\n    \n    int size = internal::random<int>(1,30);\n    dA.setRandom(size,size);\n    \n    dA = (dA.array().abs()<0.3).select(0,dA);\n    dA.diagonal() = (dA.diagonal().array()==0).select(1,dA.diagonal());\n    A = dA.sparseView();\n    A.makeCompressed();\n  \n    check_sparse_determinant(solver, A, dA);\n  }\n}\n\ntemplate<typename Solver> void check_sparse_square_abs_determinant(Solver& solver)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n\n  for (int i = 0; i < g_repeat; i++) {\n    // generate the problem\n    Mat A;\n    DenseMatrix dA;\n    generate_sparse_square_problem(solver, A, dA, 30);\n    A.makeCompressed();\n    check_sparse_abs_determinant(solver, A, dA);\n  }\n}\n\ntemplate<typename Solver, typename DenseMat>\nvoid generate_sparse_leastsquare_problem(Solver&, typename Solver::MatrixType& A, DenseMat& dA, int maxSize = 300, int options = ForceNonZeroDiag)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n\n  int rows = internal::random<int>(1,maxSize);\n  int cols = internal::random<int>(1,rows);\n  double density = (std::max)(8./(rows*cols), 0.01);\n  \n  A.resize(rows,cols);\n  dA.resize(rows,cols);\n\n  initSparse<Scalar>(density, dA, A, options);\n}\n\ntemplate<typename Solver> void check_sparse_leastsquare_solving(Solver& solver)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  typedef SparseMatrix<Scalar,ColMajor, typename Mat::StorageIndex> SpMat;\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n\n  int rhsCols = internal::random<int>(1,16);\n\n  Mat A;\n  DenseMatrix dA;\n  for (int i = 0; i < g_repeat; i++) {\n    generate_sparse_leastsquare_problem(solver, A, dA);\n\n    A.makeCompressed();\n    DenseVector b = DenseVector::Random(A.rows());\n    DenseMatrix dB(A.rows(),rhsCols);\n    SpMat B(A.rows(),rhsCols);\n    double density = (std::max)(8./(A.rows()*rhsCols), 0.1);\n    initSparse<Scalar>(density, dB, B, ForceNonZeroDiag);\n    B.makeCompressed();\n    check_sparse_solving(solver, A, b,  dA, b);\n    check_sparse_solving(solver, A, dB, dA, dB);\n    check_sparse_solving(solver, A, B,  dA, dB);\n    \n    // check only once\n    if(i==0)\n    {\n      b = DenseVector::Zero(A.rows());\n      check_sparse_solving(solver, A, b, dA, b);\n    }\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/sparse_solvers.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"sparse.h\"\n\ntemplate<typename Scalar> void\ninitSPD(double density,\n        Matrix<Scalar,Dynamic,Dynamic>& refMat,\n        SparseMatrix<Scalar>& sparseMat)\n{\n  Matrix<Scalar,Dynamic,Dynamic> aux(refMat.rows(),refMat.cols());\n  initSparse(density,refMat,sparseMat);\n  refMat = refMat * refMat.adjoint();\n  for (int k=0; k<2; ++k)\n  {\n    initSparse(density,aux,sparseMat,ForceNonZeroDiag);\n    refMat += aux * aux.adjoint();\n  }\n  sparseMat.setZero();\n  for (int j=0 ; j<sparseMat.cols(); ++j)\n    for (int i=j ; i<sparseMat.rows(); ++i)\n      if (refMat(i,j)!=Scalar(0))\n        sparseMat.insert(i,j) = refMat(i,j);\n  sparseMat.finalize();\n}\n\ntemplate<typename Scalar> void sparse_solvers(int rows, int cols)\n{\n  double density = (std::max)(8./(rows*cols), 0.01);\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n  // Scalar eps = 1e-6;\n\n  DenseVector vec1 = DenseVector::Random(rows);\n\n  std::vector<Vector2i> zeroCoords;\n  std::vector<Vector2i> nonzeroCoords;\n\n  // test triangular solver\n  {\n    DenseVector vec2 = vec1, vec3 = vec1;\n    SparseMatrix<Scalar> m2(rows, cols);\n    DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols);\n\n    // lower - dense\n    initSparse<Scalar>(density, refMat2, m2, ForceNonZeroDiag|MakeLowerTriangular, &zeroCoords, &nonzeroCoords);\n    VERIFY_IS_APPROX(refMat2.template triangularView<Lower>().solve(vec2),\n                     m2.template triangularView<Lower>().solve(vec3));\n\n    // upper - dense\n    initSparse<Scalar>(density, refMat2, m2, ForceNonZeroDiag|MakeUpperTriangular, &zeroCoords, &nonzeroCoords);\n    VERIFY_IS_APPROX(refMat2.template triangularView<Upper>().solve(vec2),\n                     m2.template triangularView<Upper>().solve(vec3));\n    VERIFY_IS_APPROX(refMat2.conjugate().template triangularView<Upper>().solve(vec2),\n                     m2.conjugate().template triangularView<Upper>().solve(vec3));\n    {\n      SparseMatrix<Scalar> cm2(m2);\n      //Index rows, Index cols, Index nnz, Index* outerIndexPtr, Index* innerIndexPtr, Scalar* valuePtr\n      MappedSparseMatrix<Scalar> mm2(rows, cols, cm2.nonZeros(), cm2.outerIndexPtr(), cm2.innerIndexPtr(), cm2.valuePtr());\n      VERIFY_IS_APPROX(refMat2.conjugate().template triangularView<Upper>().solve(vec2),\n                       mm2.conjugate().template triangularView<Upper>().solve(vec3));\n    }\n\n    // lower - transpose\n    initSparse<Scalar>(density, refMat2, m2, ForceNonZeroDiag|MakeLowerTriangular, &zeroCoords, &nonzeroCoords);\n    VERIFY_IS_APPROX(refMat2.transpose().template triangularView<Upper>().solve(vec2),\n                     m2.transpose().template triangularView<Upper>().solve(vec3));\n\n    // upper - transpose\n    initSparse<Scalar>(density, refMat2, m2, ForceNonZeroDiag|MakeUpperTriangular, &zeroCoords, &nonzeroCoords);\n    VERIFY_IS_APPROX(refMat2.transpose().template triangularView<Lower>().solve(vec2),\n                     m2.transpose().template triangularView<Lower>().solve(vec3));\n\n    SparseMatrix<Scalar> matB(rows, rows);\n    DenseMatrix refMatB = DenseMatrix::Zero(rows, rows);\n\n    // lower - sparse\n    initSparse<Scalar>(density, refMat2, m2, ForceNonZeroDiag|MakeLowerTriangular);\n    initSparse<Scalar>(density, refMatB, matB);\n    refMat2.template triangularView<Lower>().solveInPlace(refMatB);\n    m2.template triangularView<Lower>().solveInPlace(matB);\n    VERIFY_IS_APPROX(matB.toDense(), refMatB);\n\n    // upper - sparse\n    initSparse<Scalar>(density, refMat2, m2, ForceNonZeroDiag|MakeUpperTriangular);\n    initSparse<Scalar>(density, refMatB, matB);\n    refMat2.template triangularView<Upper>().solveInPlace(refMatB);\n    m2.template triangularView<Upper>().solveInPlace(matB);\n    VERIFY_IS_APPROX(matB, refMatB);\n\n    // test deprecated API\n    initSparse<Scalar>(density, refMat2, m2, ForceNonZeroDiag|MakeLowerTriangular, &zeroCoords, &nonzeroCoords);\n    VERIFY_IS_APPROX(refMat2.template triangularView<Lower>().solve(vec2),\n                     m2.template triangularView<Lower>().solve(vec3));\n\n    // test empty triangular matrix\n    {\n      m2.resize(0,0);\n      refMatB.resize(0,refMatB.cols());\n      DenseMatrix res = m2.template triangularView<Lower>().solve(refMatB);\n      VERIFY_IS_EQUAL(res.rows(),0);\n      VERIFY_IS_EQUAL(res.cols(),refMatB.cols());\n      res = refMatB;\n      m2.template triangularView<Lower>().solveInPlace(res);\n      VERIFY_IS_EQUAL(res.rows(),0);\n      VERIFY_IS_EQUAL(res.cols(),refMatB.cols());\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(sparse_solvers)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(sparse_solvers<double>(8, 8) );\n    int s = internal::random<int>(1,300);\n    CALL_SUBTEST_2(sparse_solvers<std::complex<double> >(s,s) );\n    CALL_SUBTEST_1(sparse_solvers<double>(s,s) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/sparse_vector.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"sparse.h\"\n\ntemplate<typename Scalar,typename StorageIndex> void sparse_vector(int rows, int cols)\n{\n  double densityMat = (std::max)(8./(rows*cols), 0.01);\n  double densityVec = (std::max)(8./(rows), 0.1);\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n  typedef SparseVector<Scalar,0,StorageIndex> SparseVectorType;\n  typedef SparseMatrix<Scalar,0,StorageIndex> SparseMatrixType;\n  Scalar eps = 1e-6;\n\n  SparseMatrixType m1(rows,rows);\n  SparseVectorType v1(rows), v2(rows), v3(rows);\n  DenseMatrix refM1 = DenseMatrix::Zero(rows, rows);\n  DenseVector refV1 = DenseVector::Random(rows),\n              refV2 = DenseVector::Random(rows),\n              refV3 = DenseVector::Random(rows);\n\n  std::vector<int> zerocoords, nonzerocoords;\n  initSparse<Scalar>(densityVec, refV1, v1, &zerocoords, &nonzerocoords);\n  initSparse<Scalar>(densityMat, refM1, m1);\n\n  initSparse<Scalar>(densityVec, refV2, v2);\n  initSparse<Scalar>(densityVec, refV3, v3);\n\n  Scalar s1 = internal::random<Scalar>();\n\n  // test coeff and coeffRef\n  for (unsigned int i=0; i<zerocoords.size(); ++i)\n  {\n    VERIFY_IS_MUCH_SMALLER_THAN( v1.coeff(zerocoords[i]), eps );\n    //VERIFY_RAISES_ASSERT( v1.coeffRef(zerocoords[i]) = 5 );\n  }\n  {\n    VERIFY(int(nonzerocoords.size()) == v1.nonZeros());\n    int j=0;\n    for (typename SparseVectorType::InnerIterator it(v1); it; ++it,++j)\n    {\n      VERIFY(nonzerocoords[j]==it.index());\n      VERIFY(it.value()==v1.coeff(it.index()));\n      VERIFY(it.value()==refV1.coeff(it.index()));\n    }\n  }\n  VERIFY_IS_APPROX(v1, refV1);\n  \n  // test coeffRef with reallocation\n  {\n    SparseVectorType v4(rows);\n    DenseVector v5 = DenseVector::Zero(rows);\n    for(int k=0; k<rows; ++k)\n    {\n      int i = internal::random<int>(0,rows-1);\n      Scalar v = internal::random<Scalar>();\n      v4.coeffRef(i) += v;\n      v5.coeffRef(i) += v;\n    }\n    VERIFY_IS_APPROX(v4,v5);\n  }\n\n  v1.coeffRef(nonzerocoords[0]) = Scalar(5);\n  refV1.coeffRef(nonzerocoords[0]) = Scalar(5);\n  VERIFY_IS_APPROX(v1, refV1);\n\n  VERIFY_IS_APPROX(v1+v2, refV1+refV2);\n  VERIFY_IS_APPROX(v1+v2+v3, refV1+refV2+refV3);\n\n  VERIFY_IS_APPROX(v1*s1-v2, refV1*s1-refV2);\n\n  VERIFY_IS_APPROX(v1*=s1, refV1*=s1);\n  VERIFY_IS_APPROX(v1/=s1, refV1/=s1);\n\n  VERIFY_IS_APPROX(v1+=v2, refV1+=refV2);\n  VERIFY_IS_APPROX(v1-=v2, refV1-=refV2);\n\n  VERIFY_IS_APPROX(v1.dot(v2), refV1.dot(refV2));\n  VERIFY_IS_APPROX(v1.dot(refV2), refV1.dot(refV2));\n\n  VERIFY_IS_APPROX(m1*v2, refM1*refV2);\n  VERIFY_IS_APPROX(v1.dot(m1*v2), refV1.dot(refM1*refV2));\n  {\n    int i = internal::random<int>(0,rows-1);\n    VERIFY_IS_APPROX(v1.dot(m1.col(i)), refV1.dot(refM1.col(i)));\n  }\n\n\n  VERIFY_IS_APPROX(v1.squaredNorm(), refV1.squaredNorm());\n  \n  VERIFY_IS_APPROX(v1.blueNorm(), refV1.blueNorm());\n\n  // test aliasing\n  VERIFY_IS_APPROX((v1 = -v1), (refV1 = -refV1));\n  VERIFY_IS_APPROX((v1 = v1.transpose()), (refV1 = refV1.transpose().eval()));\n  VERIFY_IS_APPROX((v1 += -v1), (refV1 += -refV1));\n  \n  // sparse matrix to sparse vector\n  SparseMatrixType mv1;\n  VERIFY_IS_APPROX((mv1=v1),v1);\n  VERIFY_IS_APPROX(mv1,(v1=mv1));\n  VERIFY_IS_APPROX(mv1,(v1=mv1.transpose()));\n  \n  // check copy to dense vector with transpose\n  refV3.resize(0);\n  VERIFY_IS_APPROX(refV3 = v1.transpose(),v1.toDense()); \n  VERIFY_IS_APPROX(DenseVector(v1),v1.toDense()); \n\n  // test conservative resize\n  {\n    std::vector<StorageIndex> inc;\n    if(rows > 3)\n      inc.push_back(-3);\n    inc.push_back(0);\n    inc.push_back(3);\n    inc.push_back(1);\n    inc.push_back(10);\n\n    for(std::size_t i = 0; i< inc.size(); i++) {\n      StorageIndex incRows = inc[i];\n      SparseVectorType vec1(rows);\n      DenseVector refVec1 = DenseVector::Zero(rows);\n      initSparse<Scalar>(densityVec, refVec1, vec1);\n\n      vec1.conservativeResize(rows+incRows);\n      refVec1.conservativeResize(rows+incRows);\n      if (incRows > 0) refVec1.tail(incRows).setZero();\n\n      VERIFY_IS_APPROX(vec1, refVec1);\n\n      // Insert new values\n      if (incRows > 0)\n        vec1.insert(vec1.rows()-1) = refVec1(refVec1.rows()-1) = 1;\n\n      VERIFY_IS_APPROX(vec1, refVec1);\n    }\n  }\n\n}\n\nEIGEN_DECLARE_TEST(sparse_vector)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    int r = Eigen::internal::random<int>(1,500), c = Eigen::internal::random<int>(1,500);\n    if(Eigen::internal::random<int>(0,4) == 0) {\n      r = c; // check square matrices in 25% of tries\n    }\n    EIGEN_UNUSED_VARIABLE(r+c);\n\n    CALL_SUBTEST_1(( sparse_vector<double,int>(8, 8) ));\n    CALL_SUBTEST_2(( sparse_vector<std::complex<double>, int>(r, c) ));\n    CALL_SUBTEST_1(( sparse_vector<double,long int>(r, c) ));\n    CALL_SUBTEST_1(( sparse_vector<double,short>(r, c) ));\n  }\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/sparselu.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// SparseLU solve does not accept column major matrices for the destination.\n// However, as expected, the generic check_sparse_square_solving routines produces row-major\n// rhs and destination matrices when compiled with EIGEN_DEFAULT_TO_ROW_MAJOR\n\n#ifdef EIGEN_DEFAULT_TO_ROW_MAJOR\n#undef EIGEN_DEFAULT_TO_ROW_MAJOR\n#endif\n\n#include \"sparse_solver.h\"\n#include <Eigen/SparseLU>\n#include <unsupported/Eigen/SparseExtra>\n\ntemplate<typename T> void test_sparselu_T()\n{\n  SparseLU<SparseMatrix<T, ColMajor> /*, COLAMDOrdering<int>*/ > sparselu_colamd; // COLAMDOrdering is the default\n  SparseLU<SparseMatrix<T, ColMajor>, AMDOrdering<int> > sparselu_amd; \n  SparseLU<SparseMatrix<T, ColMajor, long int>, NaturalOrdering<long int> > sparselu_natural;\n  \n  check_sparse_square_solving(sparselu_colamd,  300, 100000, true); \n  check_sparse_square_solving(sparselu_amd,     300,  10000, true);\n  check_sparse_square_solving(sparselu_natural, 300,   2000, true);\n  \n  check_sparse_square_abs_determinant(sparselu_colamd);\n  check_sparse_square_abs_determinant(sparselu_amd);\n  \n  check_sparse_square_determinant(sparselu_colamd);\n  check_sparse_square_determinant(sparselu_amd);\n}\n\nEIGEN_DECLARE_TEST(sparselu)\n{\n  CALL_SUBTEST_1(test_sparselu_T<float>()); \n  CALL_SUBTEST_2(test_sparselu_T<double>());\n  CALL_SUBTEST_3(test_sparselu_T<std::complex<float> >()); \n  CALL_SUBTEST_4(test_sparselu_T<std::complex<double> >());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/sparseqr.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Desire Nuentsa Wakam <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n#include \"sparse.h\"\n#include <Eigen/SparseQR>\n\ntemplate<typename MatrixType,typename DenseMat>\nint generate_sparse_rectangular_problem(MatrixType& A, DenseMat& dA, int maxRows = 300, int maxCols = 150)\n{\n  eigen_assert(maxRows >= maxCols);\n  typedef typename MatrixType::Scalar Scalar;\n  int rows = internal::random<int>(1,maxRows);\n  int cols = internal::random<int>(1,maxCols);\n  double density = (std::max)(8./(rows*cols), 0.01);\n  \n  A.resize(rows,cols);\n  dA.resize(rows,cols);\n  initSparse<Scalar>(density, dA, A,ForceNonZeroDiag);\n  A.makeCompressed();\n  int nop = internal::random<int>(0, internal::random<double>(0,1) > 0.5 ? cols/2 : 0);\n  for(int k=0; k<nop; ++k)\n  {\n    int j0 = internal::random<int>(0,cols-1);\n    int j1 = internal::random<int>(0,cols-1);\n    Scalar s = internal::random<Scalar>();\n    A.col(j0)  = s * A.col(j1);\n    dA.col(j0) = s * dA.col(j1);\n  }\n  \n//   if(rows<cols) {\n//     A.conservativeResize(cols,cols);\n//     dA.conservativeResize(cols,cols);\n//     dA.bottomRows(cols-rows).setZero();\n//   }\n  \n  return rows;\n}\n\ntemplate<typename Scalar> void test_sparseqr_scalar()\n{\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef SparseMatrix<Scalar,ColMajor> MatrixType; \n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMat;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n  MatrixType A;\n  DenseMat dA;\n  DenseVector refX,x,b; \n  SparseQR<MatrixType, COLAMDOrdering<int> > solver; \n  generate_sparse_rectangular_problem(A,dA);\n  \n  b = dA * DenseVector::Random(A.cols());\n  solver.compute(A);\n\n  // Q should be MxM\n  VERIFY_IS_EQUAL(solver.matrixQ().rows(), A.rows());\n  VERIFY_IS_EQUAL(solver.matrixQ().cols(), A.rows());\n\n  // R should be MxN\n  VERIFY_IS_EQUAL(solver.matrixR().rows(), A.rows());\n  VERIFY_IS_EQUAL(solver.matrixR().cols(), A.cols());\n\n  // Q and R can be multiplied\n  DenseMat recoveredA = solver.matrixQ()\n                      * DenseMat(solver.matrixR().template triangularView<Upper>())\n                      * solver.colsPermutation().transpose();\n  VERIFY_IS_EQUAL(recoveredA.rows(), A.rows());\n  VERIFY_IS_EQUAL(recoveredA.cols(), A.cols());\n\n  // and in the full rank case the original matrix is recovered\n  if (solver.rank() == A.cols())\n  {\n      VERIFY_IS_APPROX(A, recoveredA);\n  }\n\n  if(internal::random<float>(0,1)>0.5f)\n    solver.factorize(A);  // this checks that calling analyzePattern is not needed if the pattern do not change.\n  if (solver.info() != Success)\n  {\n    std::cerr << \"sparse QR factorization failed\\n\";\n    exit(0);\n    return;\n  }\n  x = solver.solve(b);\n  if (solver.info() != Success)\n  {\n    std::cerr << \"sparse QR factorization failed\\n\";\n    exit(0);\n    return;\n  }\n\n  // Compare with a dense QR solver\n  ColPivHouseholderQR<DenseMat> dqr(dA);\n  refX = dqr.solve(b);\n  \n  bool rank_deficient = A.cols()>A.rows() || dqr.rank()<A.cols();\n  if(rank_deficient)\n  {\n    // rank deficient problem -> we might have to increase the threshold\n    // to get a correct solution.\n    RealScalar th = RealScalar(20)*dA.colwise().norm().maxCoeff()*(A.rows()+A.cols()) * NumTraits<RealScalar>::epsilon();\n    for(Index k=0; (k<16) && !test_isApprox(A*x,b); ++k)\n    {\n      th *= RealScalar(10);\n      solver.setPivotThreshold(th);\n      solver.compute(A);\n      x = solver.solve(b);\n    }\n  }\n\n  VERIFY_IS_APPROX(A * x, b);\n  \n  // For rank deficient problem, the estimated rank might\n  // be slightly off, so let's only raise a warning in such cases.\n  if(rank_deficient) ++g_test_level;\n  VERIFY_IS_EQUAL(solver.rank(), dqr.rank());\n  if(rank_deficient) --g_test_level;\n\n  if(solver.rank()==A.cols()) // full rank\n    VERIFY_IS_APPROX(x, refX);\n//   else\n//     VERIFY((dA * refX - b).norm() * 2 > (A * x - b).norm() );\n\n  // Compute explicitly the matrix Q\n  MatrixType Q, QtQ, idM;\n  Q = solver.matrixQ();\n  //Check  ||Q' * Q - I ||\n  QtQ = Q * Q.adjoint();\n  idM.resize(Q.rows(), Q.rows()); idM.setIdentity();\n  VERIFY(idM.isApprox(QtQ));\n  \n  // Q to dense\n  DenseMat dQ;\n  dQ = solver.matrixQ();\n  VERIFY_IS_APPROX(Q, dQ);\n}\nEIGEN_DECLARE_TEST(sparseqr)\n{\n  for(int i=0; i<g_repeat; ++i)\n  {\n    CALL_SUBTEST_1(test_sparseqr_scalar<double>());\n    CALL_SUBTEST_2(test_sparseqr_scalar<std::complex<double> >());\n  }\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/special_numbers.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename Scalar> void special_numbers()\n{\n  typedef Matrix<Scalar, Dynamic,Dynamic> MatType;\n  int rows = internal::random<int>(1,300);\n  int cols = internal::random<int>(1,300);\n  \n  Scalar nan = std::numeric_limits<Scalar>::quiet_NaN();\n  Scalar inf = std::numeric_limits<Scalar>::infinity();\n  Scalar s1 = internal::random<Scalar>();\n  \n  MatType m1    = MatType::Random(rows,cols),\n          mnan  = MatType::Random(rows,cols),\n          minf  = MatType::Random(rows,cols),\n          mboth = MatType::Random(rows,cols);\n          \n  int n = internal::random<int>(1,10);\n  for(int k=0; k<n; ++k)\n  {\n    mnan(internal::random<int>(0,rows-1), internal::random<int>(0,cols-1)) = nan;\n    minf(internal::random<int>(0,rows-1), internal::random<int>(0,cols-1)) = inf;\n  }\n  mboth = mnan + minf;\n  \n  VERIFY(!m1.hasNaN());\n  VERIFY(m1.allFinite());\n  \n  VERIFY(mnan.hasNaN());\n  VERIFY((s1*mnan).hasNaN());\n  VERIFY(!minf.hasNaN());\n  VERIFY(!(2*minf).hasNaN());\n  VERIFY(mboth.hasNaN());\n  VERIFY(mboth.array().hasNaN());\n  \n  VERIFY(!mnan.allFinite());\n  VERIFY(!minf.allFinite());\n  VERIFY(!(minf-mboth).allFinite());\n  VERIFY(!mboth.allFinite());\n  VERIFY(!mboth.array().allFinite());\n}\n\nEIGEN_DECLARE_TEST(special_numbers)\n{\n  for(int i = 0; i < 10*g_repeat; i++) {\n    CALL_SUBTEST_1( special_numbers<float>() );\n    CALL_SUBTEST_1( special_numbers<double>() );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/split_test_helper.h",
    "content": "#if defined(EIGEN_TEST_PART_1) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_1(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_1(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_2) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_2(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_2(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_3) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_3(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_3(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_4) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_4(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_4(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_5) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_5(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_5(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_6) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_6(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_6(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_7) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_7(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_7(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_8) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_8(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_8(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_9) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_9(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_9(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_10) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_10(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_10(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_11) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_11(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_11(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_12) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_12(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_12(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_13) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_13(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_13(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_14) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_14(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_14(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_15) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_15(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_15(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_16) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_16(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_16(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_17) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_17(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_17(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_18) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_18(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_18(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_19) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_19(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_19(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_20) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_20(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_20(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_21) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_21(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_21(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_22) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_22(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_22(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_23) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_23(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_23(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_24) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_24(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_24(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_25) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_25(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_25(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_26) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_26(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_26(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_27) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_27(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_27(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_28) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_28(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_28(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_29) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_29(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_29(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_30) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_30(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_30(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_31) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_31(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_31(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_32) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_32(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_32(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_33) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_33(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_33(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_34) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_34(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_34(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_35) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_35(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_35(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_36) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_36(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_36(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_37) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_37(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_37(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_38) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_38(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_38(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_39) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_39(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_39(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_40) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_40(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_40(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_41) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_41(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_41(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_42) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_42(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_42(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_43) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_43(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_43(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_44) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_44(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_44(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_45) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_45(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_45(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_46) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_46(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_46(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_47) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_47(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_47(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_48) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_48(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_48(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_49) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_49(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_49(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_50) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_50(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_50(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_51) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_51(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_51(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_52) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_52(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_52(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_53) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_53(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_53(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_54) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_54(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_54(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_55) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_55(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_55(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_56) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_56(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_56(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_57) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_57(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_57(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_58) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_58(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_58(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_59) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_59(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_59(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_60) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_60(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_60(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_61) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_61(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_61(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_62) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_62(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_62(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_63) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_63(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_63(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_64) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_64(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_64(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_65) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_65(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_65(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_66) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_66(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_66(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_67) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_67(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_67(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_68) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_68(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_68(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_69) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_69(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_69(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_70) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_70(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_70(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_71) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_71(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_71(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_72) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_72(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_72(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_73) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_73(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_73(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_74) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_74(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_74(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_75) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_75(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_75(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_76) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_76(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_76(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_77) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_77(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_77(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_78) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_78(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_78(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_79) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_79(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_79(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_80) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_80(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_80(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_81) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_81(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_81(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_82) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_82(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_82(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_83) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_83(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_83(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_84) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_84(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_84(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_85) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_85(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_85(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_86) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_86(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_86(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_87) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_87(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_87(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_88) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_88(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_88(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_89) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_89(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_89(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_90) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_90(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_90(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_91) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_91(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_91(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_92) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_92(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_92(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_93) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_93(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_93(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_94) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_94(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_94(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_95) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_95(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_95(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_96) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_96(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_96(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_97) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_97(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_97(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_98) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_98(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_98(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_99) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_99(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_99(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_100) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_100(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_100(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_101) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_101(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_101(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_102) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_102(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_102(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_103) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_103(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_103(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_104) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_104(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_104(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_105) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_105(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_105(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_106) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_106(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_106(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_107) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_107(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_107(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_108) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_108(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_108(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_109) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_109(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_109(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_110) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_110(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_110(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_111) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_111(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_111(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_112) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_112(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_112(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_113) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_113(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_113(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_114) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_114(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_114(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_115) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_115(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_115(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_116) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_116(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_116(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_117) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_117(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_117(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_118) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_118(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_118(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_119) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_119(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_119(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_120) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_120(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_120(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_121) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_121(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_121(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_122) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_122(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_122(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_123) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_123(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_123(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_124) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_124(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_124(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_125) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_125(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_125(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_126) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_126(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_126(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_127) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_127(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_127(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_128) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_128(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_128(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_129) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_129(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_129(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_130) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_130(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_130(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_131) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_131(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_131(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_132) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_132(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_132(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_133) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_133(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_133(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_134) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_134(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_134(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_135) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_135(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_135(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_136) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_136(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_136(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_137) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_137(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_137(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_138) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_138(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_138(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_139) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_139(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_139(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_140) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_140(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_140(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_141) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_141(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_141(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_142) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_142(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_142(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_143) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_143(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_143(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_144) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_144(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_144(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_145) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_145(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_145(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_146) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_146(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_146(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_147) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_147(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_147(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_148) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_148(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_148(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_149) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_149(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_149(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_150) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_150(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_150(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_151) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_151(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_151(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_152) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_152(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_152(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_153) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_153(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_153(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_154) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_154(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_154(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_155) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_155(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_155(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_156) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_156(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_156(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_157) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_157(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_157(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_158) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_158(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_158(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_159) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_159(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_159(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_160) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_160(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_160(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_161) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_161(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_161(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_162) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_162(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_162(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_163) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_163(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_163(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_164) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_164(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_164(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_165) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_165(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_165(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_166) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_166(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_166(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_167) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_167(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_167(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_168) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_168(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_168(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_169) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_169(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_169(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_170) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_170(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_170(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_171) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_171(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_171(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_172) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_172(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_172(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_173) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_173(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_173(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_174) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_174(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_174(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_175) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_175(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_175(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_176) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_176(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_176(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_177) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_177(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_177(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_178) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_178(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_178(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_179) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_179(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_179(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_180) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_180(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_180(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_181) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_181(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_181(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_182) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_182(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_182(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_183) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_183(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_183(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_184) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_184(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_184(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_185) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_185(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_185(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_186) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_186(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_186(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_187) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_187(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_187(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_188) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_188(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_188(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_189) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_189(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_189(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_190) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_190(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_190(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_191) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_191(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_191(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_192) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_192(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_192(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_193) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_193(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_193(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_194) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_194(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_194(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_195) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_195(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_195(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_196) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_196(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_196(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_197) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_197(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_197(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_198) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_198(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_198(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_199) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_199(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_199(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_200) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_200(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_200(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_201) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_201(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_201(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_202) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_202(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_202(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_203) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_203(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_203(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_204) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_204(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_204(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_205) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_205(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_205(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_206) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_206(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_206(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_207) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_207(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_207(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_208) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_208(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_208(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_209) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_209(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_209(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_210) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_210(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_210(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_211) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_211(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_211(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_212) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_212(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_212(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_213) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_213(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_213(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_214) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_214(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_214(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_215) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_215(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_215(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_216) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_216(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_216(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_217) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_217(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_217(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_218) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_218(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_218(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_219) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_219(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_219(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_220) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_220(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_220(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_221) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_221(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_221(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_222) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_222(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_222(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_223) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_223(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_223(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_224) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_224(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_224(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_225) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_225(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_225(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_226) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_226(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_226(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_227) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_227(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_227(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_228) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_228(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_228(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_229) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_229(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_229(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_230) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_230(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_230(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_231) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_231(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_231(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_232) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_232(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_232(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_233) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_233(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_233(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_234) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_234(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_234(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_235) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_235(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_235(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_236) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_236(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_236(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_237) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_237(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_237(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_238) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_238(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_238(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_239) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_239(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_239(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_240) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_240(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_240(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_241) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_241(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_241(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_242) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_242(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_242(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_243) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_243(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_243(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_244) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_244(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_244(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_245) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_245(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_245(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_246) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_246(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_246(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_247) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_247(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_247(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_248) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_248(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_248(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_249) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_249(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_249(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_250) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_250(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_250(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_251) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_251(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_251(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_252) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_252(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_252(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_253) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_253(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_253(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_254) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_254(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_254(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_255) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_255(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_255(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_256) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_256(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_256(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_257) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_257(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_257(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_258) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_258(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_258(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_259) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_259(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_259(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_260) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_260(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_260(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_261) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_261(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_261(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_262) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_262(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_262(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_263) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_263(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_263(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_264) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_264(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_264(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_265) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_265(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_265(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_266) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_266(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_266(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_267) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_267(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_267(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_268) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_268(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_268(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_269) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_269(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_269(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_270) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_270(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_270(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_271) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_271(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_271(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_272) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_272(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_272(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_273) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_273(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_273(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_274) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_274(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_274(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_275) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_275(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_275(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_276) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_276(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_276(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_277) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_277(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_277(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_278) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_278(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_278(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_279) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_279(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_279(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_280) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_280(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_280(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_281) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_281(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_281(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_282) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_282(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_282(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_283) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_283(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_283(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_284) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_284(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_284(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_285) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_285(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_285(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_286) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_286(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_286(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_287) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_287(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_287(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_288) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_288(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_288(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_289) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_289(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_289(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_290) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_290(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_290(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_291) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_291(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_291(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_292) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_292(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_292(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_293) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_293(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_293(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_294) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_294(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_294(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_295) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_295(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_295(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_296) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_296(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_296(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_297) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_297(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_297(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_298) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_298(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_298(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_299) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_299(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_299(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_300) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_300(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_300(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_301) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_301(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_301(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_302) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_302(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_302(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_303) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_303(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_303(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_304) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_304(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_304(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_305) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_305(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_305(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_306) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_306(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_306(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_307) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_307(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_307(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_308) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_308(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_308(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_309) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_309(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_309(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_310) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_310(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_310(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_311) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_311(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_311(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_312) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_312(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_312(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_313) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_313(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_313(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_314) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_314(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_314(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_315) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_315(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_315(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_316) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_316(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_316(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_317) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_317(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_317(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_318) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_318(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_318(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_319) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_319(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_319(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_320) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_320(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_320(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_321) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_321(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_321(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_322) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_322(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_322(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_323) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_323(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_323(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_324) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_324(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_324(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_325) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_325(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_325(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_326) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_326(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_326(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_327) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_327(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_327(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_328) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_328(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_328(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_329) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_329(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_329(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_330) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_330(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_330(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_331) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_331(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_331(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_332) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_332(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_332(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_333) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_333(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_333(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_334) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_334(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_334(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_335) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_335(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_335(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_336) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_336(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_336(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_337) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_337(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_337(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_338) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_338(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_338(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_339) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_339(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_339(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_340) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_340(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_340(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_341) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_341(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_341(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_342) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_342(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_342(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_343) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_343(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_343(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_344) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_344(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_344(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_345) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_345(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_345(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_346) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_346(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_346(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_347) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_347(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_347(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_348) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_348(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_348(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_349) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_349(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_349(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_350) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_350(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_350(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_351) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_351(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_351(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_352) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_352(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_352(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_353) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_353(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_353(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_354) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_354(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_354(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_355) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_355(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_355(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_356) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_356(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_356(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_357) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_357(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_357(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_358) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_358(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_358(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_359) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_359(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_359(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_360) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_360(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_360(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_361) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_361(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_361(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_362) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_362(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_362(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_363) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_363(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_363(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_364) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_364(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_364(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_365) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_365(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_365(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_366) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_366(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_366(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_367) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_367(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_367(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_368) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_368(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_368(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_369) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_369(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_369(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_370) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_370(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_370(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_371) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_371(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_371(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_372) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_372(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_372(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_373) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_373(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_373(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_374) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_374(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_374(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_375) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_375(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_375(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_376) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_376(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_376(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_377) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_377(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_377(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_378) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_378(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_378(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_379) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_379(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_379(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_380) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_380(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_380(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_381) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_381(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_381(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_382) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_382(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_382(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_383) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_383(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_383(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_384) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_384(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_384(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_385) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_385(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_385(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_386) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_386(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_386(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_387) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_387(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_387(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_388) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_388(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_388(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_389) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_389(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_389(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_390) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_390(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_390(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_391) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_391(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_391(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_392) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_392(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_392(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_393) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_393(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_393(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_394) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_394(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_394(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_395) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_395(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_395(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_396) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_396(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_396(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_397) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_397(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_397(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_398) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_398(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_398(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_399) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_399(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_399(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_400) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_400(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_400(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_401) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_401(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_401(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_402) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_402(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_402(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_403) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_403(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_403(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_404) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_404(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_404(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_405) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_405(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_405(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_406) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_406(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_406(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_407) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_407(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_407(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_408) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_408(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_408(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_409) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_409(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_409(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_410) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_410(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_410(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_411) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_411(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_411(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_412) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_412(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_412(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_413) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_413(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_413(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_414) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_414(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_414(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_415) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_415(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_415(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_416) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_416(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_416(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_417) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_417(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_417(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_418) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_418(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_418(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_419) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_419(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_419(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_420) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_420(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_420(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_421) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_421(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_421(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_422) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_422(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_422(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_423) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_423(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_423(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_424) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_424(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_424(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_425) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_425(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_425(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_426) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_426(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_426(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_427) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_427(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_427(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_428) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_428(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_428(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_429) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_429(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_429(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_430) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_430(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_430(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_431) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_431(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_431(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_432) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_432(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_432(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_433) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_433(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_433(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_434) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_434(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_434(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_435) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_435(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_435(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_436) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_436(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_436(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_437) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_437(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_437(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_438) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_438(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_438(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_439) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_439(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_439(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_440) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_440(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_440(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_441) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_441(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_441(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_442) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_442(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_442(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_443) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_443(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_443(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_444) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_444(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_444(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_445) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_445(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_445(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_446) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_446(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_446(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_447) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_447(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_447(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_448) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_448(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_448(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_449) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_449(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_449(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_450) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_450(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_450(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_451) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_451(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_451(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_452) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_452(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_452(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_453) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_453(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_453(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_454) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_454(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_454(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_455) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_455(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_455(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_456) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_456(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_456(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_457) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_457(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_457(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_458) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_458(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_458(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_459) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_459(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_459(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_460) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_460(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_460(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_461) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_461(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_461(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_462) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_462(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_462(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_463) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_463(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_463(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_464) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_464(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_464(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_465) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_465(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_465(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_466) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_466(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_466(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_467) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_467(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_467(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_468) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_468(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_468(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_469) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_469(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_469(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_470) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_470(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_470(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_471) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_471(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_471(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_472) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_472(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_472(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_473) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_473(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_473(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_474) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_474(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_474(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_475) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_475(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_475(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_476) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_476(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_476(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_477) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_477(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_477(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_478) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_478(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_478(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_479) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_479(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_479(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_480) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_480(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_480(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_481) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_481(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_481(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_482) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_482(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_482(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_483) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_483(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_483(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_484) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_484(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_484(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_485) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_485(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_485(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_486) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_486(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_486(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_487) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_487(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_487(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_488) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_488(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_488(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_489) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_489(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_489(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_490) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_490(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_490(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_491) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_491(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_491(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_492) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_492(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_492(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_493) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_493(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_493(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_494) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_494(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_494(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_495) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_495(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_495(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_496) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_496(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_496(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_497) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_497(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_497(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_498) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_498(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_498(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_499) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_499(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_499(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_500) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_500(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_500(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_501) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_501(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_501(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_502) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_502(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_502(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_503) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_503(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_503(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_504) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_504(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_504(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_505) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_505(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_505(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_506) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_506(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_506(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_507) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_507(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_507(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_508) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_508(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_508(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_509) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_509(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_509(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_510) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_510(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_510(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_511) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_511(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_511(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_512) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_512(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_512(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_513) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_513(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_513(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_514) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_514(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_514(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_515) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_515(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_515(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_516) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_516(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_516(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_517) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_517(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_517(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_518) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_518(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_518(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_519) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_519(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_519(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_520) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_520(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_520(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_521) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_521(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_521(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_522) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_522(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_522(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_523) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_523(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_523(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_524) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_524(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_524(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_525) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_525(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_525(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_526) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_526(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_526(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_527) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_527(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_527(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_528) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_528(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_528(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_529) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_529(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_529(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_530) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_530(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_530(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_531) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_531(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_531(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_532) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_532(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_532(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_533) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_533(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_533(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_534) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_534(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_534(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_535) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_535(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_535(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_536) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_536(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_536(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_537) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_537(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_537(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_538) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_538(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_538(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_539) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_539(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_539(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_540) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_540(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_540(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_541) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_541(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_541(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_542) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_542(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_542(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_543) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_543(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_543(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_544) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_544(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_544(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_545) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_545(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_545(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_546) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_546(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_546(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_547) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_547(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_547(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_548) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_548(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_548(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_549) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_549(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_549(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_550) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_550(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_550(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_551) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_551(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_551(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_552) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_552(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_552(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_553) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_553(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_553(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_554) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_554(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_554(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_555) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_555(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_555(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_556) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_556(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_556(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_557) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_557(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_557(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_558) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_558(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_558(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_559) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_559(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_559(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_560) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_560(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_560(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_561) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_561(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_561(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_562) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_562(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_562(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_563) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_563(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_563(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_564) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_564(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_564(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_565) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_565(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_565(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_566) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_566(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_566(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_567) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_567(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_567(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_568) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_568(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_568(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_569) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_569(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_569(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_570) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_570(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_570(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_571) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_571(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_571(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_572) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_572(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_572(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_573) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_573(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_573(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_574) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_574(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_574(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_575) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_575(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_575(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_576) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_576(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_576(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_577) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_577(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_577(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_578) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_578(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_578(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_579) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_579(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_579(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_580) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_580(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_580(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_581) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_581(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_581(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_582) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_582(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_582(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_583) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_583(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_583(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_584) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_584(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_584(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_585) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_585(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_585(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_586) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_586(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_586(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_587) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_587(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_587(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_588) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_588(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_588(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_589) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_589(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_589(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_590) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_590(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_590(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_591) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_591(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_591(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_592) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_592(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_592(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_593) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_593(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_593(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_594) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_594(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_594(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_595) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_595(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_595(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_596) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_596(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_596(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_597) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_597(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_597(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_598) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_598(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_598(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_599) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_599(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_599(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_600) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_600(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_600(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_601) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_601(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_601(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_602) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_602(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_602(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_603) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_603(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_603(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_604) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_604(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_604(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_605) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_605(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_605(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_606) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_606(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_606(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_607) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_607(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_607(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_608) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_608(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_608(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_609) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_609(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_609(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_610) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_610(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_610(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_611) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_611(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_611(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_612) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_612(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_612(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_613) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_613(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_613(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_614) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_614(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_614(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_615) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_615(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_615(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_616) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_616(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_616(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_617) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_617(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_617(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_618) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_618(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_618(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_619) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_619(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_619(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_620) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_620(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_620(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_621) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_621(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_621(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_622) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_622(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_622(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_623) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_623(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_623(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_624) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_624(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_624(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_625) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_625(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_625(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_626) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_626(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_626(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_627) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_627(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_627(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_628) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_628(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_628(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_629) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_629(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_629(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_630) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_630(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_630(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_631) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_631(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_631(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_632) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_632(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_632(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_633) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_633(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_633(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_634) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_634(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_634(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_635) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_635(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_635(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_636) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_636(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_636(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_637) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_637(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_637(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_638) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_638(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_638(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_639) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_639(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_639(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_640) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_640(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_640(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_641) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_641(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_641(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_642) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_642(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_642(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_643) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_643(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_643(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_644) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_644(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_644(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_645) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_645(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_645(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_646) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_646(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_646(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_647) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_647(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_647(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_648) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_648(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_648(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_649) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_649(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_649(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_650) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_650(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_650(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_651) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_651(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_651(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_652) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_652(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_652(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_653) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_653(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_653(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_654) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_654(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_654(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_655) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_655(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_655(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_656) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_656(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_656(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_657) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_657(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_657(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_658) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_658(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_658(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_659) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_659(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_659(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_660) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_660(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_660(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_661) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_661(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_661(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_662) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_662(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_662(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_663) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_663(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_663(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_664) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_664(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_664(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_665) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_665(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_665(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_666) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_666(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_666(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_667) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_667(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_667(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_668) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_668(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_668(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_669) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_669(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_669(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_670) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_670(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_670(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_671) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_671(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_671(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_672) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_672(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_672(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_673) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_673(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_673(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_674) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_674(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_674(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_675) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_675(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_675(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_676) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_676(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_676(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_677) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_677(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_677(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_678) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_678(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_678(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_679) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_679(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_679(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_680) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_680(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_680(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_681) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_681(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_681(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_682) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_682(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_682(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_683) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_683(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_683(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_684) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_684(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_684(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_685) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_685(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_685(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_686) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_686(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_686(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_687) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_687(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_687(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_688) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_688(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_688(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_689) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_689(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_689(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_690) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_690(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_690(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_691) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_691(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_691(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_692) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_692(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_692(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_693) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_693(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_693(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_694) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_694(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_694(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_695) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_695(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_695(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_696) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_696(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_696(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_697) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_697(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_697(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_698) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_698(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_698(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_699) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_699(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_699(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_700) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_700(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_700(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_701) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_701(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_701(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_702) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_702(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_702(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_703) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_703(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_703(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_704) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_704(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_704(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_705) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_705(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_705(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_706) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_706(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_706(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_707) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_707(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_707(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_708) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_708(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_708(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_709) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_709(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_709(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_710) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_710(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_710(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_711) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_711(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_711(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_712) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_712(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_712(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_713) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_713(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_713(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_714) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_714(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_714(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_715) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_715(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_715(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_716) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_716(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_716(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_717) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_717(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_717(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_718) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_718(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_718(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_719) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_719(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_719(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_720) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_720(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_720(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_721) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_721(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_721(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_722) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_722(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_722(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_723) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_723(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_723(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_724) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_724(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_724(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_725) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_725(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_725(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_726) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_726(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_726(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_727) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_727(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_727(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_728) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_728(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_728(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_729) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_729(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_729(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_730) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_730(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_730(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_731) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_731(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_731(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_732) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_732(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_732(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_733) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_733(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_733(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_734) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_734(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_734(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_735) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_735(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_735(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_736) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_736(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_736(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_737) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_737(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_737(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_738) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_738(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_738(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_739) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_739(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_739(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_740) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_740(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_740(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_741) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_741(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_741(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_742) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_742(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_742(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_743) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_743(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_743(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_744) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_744(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_744(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_745) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_745(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_745(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_746) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_746(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_746(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_747) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_747(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_747(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_748) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_748(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_748(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_749) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_749(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_749(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_750) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_750(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_750(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_751) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_751(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_751(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_752) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_752(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_752(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_753) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_753(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_753(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_754) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_754(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_754(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_755) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_755(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_755(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_756) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_756(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_756(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_757) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_757(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_757(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_758) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_758(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_758(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_759) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_759(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_759(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_760) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_760(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_760(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_761) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_761(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_761(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_762) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_762(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_762(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_763) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_763(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_763(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_764) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_764(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_764(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_765) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_765(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_765(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_766) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_766(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_766(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_767) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_767(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_767(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_768) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_768(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_768(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_769) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_769(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_769(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_770) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_770(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_770(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_771) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_771(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_771(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_772) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_772(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_772(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_773) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_773(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_773(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_774) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_774(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_774(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_775) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_775(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_775(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_776) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_776(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_776(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_777) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_777(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_777(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_778) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_778(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_778(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_779) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_779(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_779(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_780) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_780(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_780(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_781) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_781(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_781(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_782) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_782(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_782(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_783) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_783(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_783(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_784) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_784(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_784(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_785) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_785(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_785(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_786) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_786(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_786(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_787) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_787(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_787(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_788) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_788(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_788(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_789) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_789(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_789(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_790) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_790(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_790(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_791) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_791(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_791(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_792) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_792(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_792(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_793) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_793(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_793(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_794) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_794(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_794(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_795) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_795(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_795(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_796) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_796(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_796(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_797) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_797(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_797(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_798) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_798(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_798(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_799) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_799(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_799(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_800) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_800(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_800(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_801) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_801(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_801(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_802) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_802(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_802(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_803) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_803(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_803(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_804) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_804(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_804(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_805) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_805(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_805(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_806) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_806(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_806(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_807) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_807(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_807(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_808) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_808(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_808(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_809) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_809(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_809(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_810) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_810(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_810(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_811) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_811(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_811(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_812) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_812(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_812(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_813) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_813(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_813(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_814) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_814(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_814(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_815) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_815(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_815(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_816) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_816(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_816(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_817) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_817(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_817(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_818) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_818(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_818(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_819) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_819(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_819(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_820) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_820(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_820(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_821) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_821(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_821(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_822) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_822(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_822(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_823) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_823(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_823(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_824) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_824(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_824(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_825) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_825(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_825(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_826) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_826(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_826(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_827) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_827(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_827(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_828) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_828(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_828(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_829) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_829(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_829(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_830) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_830(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_830(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_831) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_831(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_831(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_832) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_832(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_832(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_833) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_833(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_833(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_834) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_834(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_834(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_835) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_835(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_835(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_836) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_836(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_836(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_837) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_837(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_837(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_838) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_838(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_838(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_839) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_839(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_839(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_840) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_840(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_840(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_841) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_841(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_841(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_842) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_842(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_842(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_843) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_843(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_843(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_844) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_844(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_844(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_845) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_845(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_845(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_846) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_846(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_846(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_847) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_847(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_847(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_848) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_848(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_848(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_849) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_849(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_849(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_850) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_850(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_850(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_851) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_851(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_851(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_852) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_852(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_852(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_853) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_853(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_853(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_854) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_854(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_854(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_855) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_855(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_855(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_856) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_856(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_856(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_857) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_857(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_857(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_858) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_858(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_858(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_859) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_859(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_859(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_860) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_860(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_860(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_861) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_861(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_861(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_862) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_862(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_862(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_863) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_863(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_863(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_864) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_864(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_864(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_865) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_865(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_865(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_866) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_866(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_866(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_867) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_867(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_867(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_868) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_868(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_868(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_869) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_869(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_869(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_870) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_870(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_870(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_871) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_871(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_871(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_872) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_872(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_872(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_873) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_873(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_873(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_874) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_874(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_874(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_875) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_875(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_875(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_876) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_876(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_876(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_877) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_877(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_877(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_878) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_878(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_878(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_879) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_879(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_879(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_880) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_880(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_880(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_881) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_881(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_881(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_882) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_882(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_882(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_883) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_883(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_883(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_884) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_884(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_884(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_885) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_885(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_885(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_886) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_886(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_886(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_887) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_887(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_887(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_888) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_888(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_888(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_889) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_889(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_889(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_890) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_890(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_890(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_891) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_891(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_891(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_892) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_892(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_892(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_893) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_893(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_893(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_894) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_894(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_894(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_895) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_895(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_895(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_896) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_896(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_896(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_897) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_897(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_897(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_898) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_898(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_898(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_899) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_899(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_899(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_900) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_900(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_900(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_901) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_901(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_901(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_902) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_902(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_902(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_903) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_903(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_903(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_904) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_904(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_904(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_905) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_905(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_905(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_906) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_906(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_906(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_907) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_907(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_907(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_908) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_908(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_908(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_909) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_909(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_909(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_910) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_910(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_910(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_911) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_911(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_911(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_912) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_912(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_912(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_913) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_913(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_913(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_914) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_914(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_914(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_915) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_915(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_915(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_916) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_916(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_916(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_917) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_917(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_917(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_918) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_918(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_918(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_919) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_919(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_919(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_920) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_920(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_920(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_921) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_921(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_921(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_922) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_922(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_922(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_923) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_923(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_923(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_924) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_924(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_924(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_925) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_925(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_925(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_926) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_926(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_926(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_927) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_927(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_927(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_928) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_928(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_928(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_929) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_929(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_929(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_930) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_930(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_930(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_931) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_931(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_931(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_932) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_932(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_932(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_933) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_933(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_933(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_934) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_934(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_934(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_935) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_935(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_935(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_936) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_936(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_936(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_937) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_937(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_937(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_938) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_938(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_938(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_939) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_939(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_939(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_940) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_940(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_940(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_941) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_941(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_941(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_942) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_942(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_942(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_943) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_943(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_943(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_944) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_944(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_944(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_945) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_945(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_945(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_946) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_946(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_946(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_947) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_947(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_947(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_948) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_948(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_948(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_949) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_949(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_949(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_950) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_950(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_950(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_951) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_951(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_951(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_952) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_952(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_952(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_953) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_953(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_953(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_954) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_954(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_954(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_955) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_955(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_955(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_956) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_956(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_956(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_957) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_957(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_957(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_958) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_958(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_958(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_959) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_959(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_959(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_960) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_960(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_960(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_961) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_961(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_961(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_962) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_962(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_962(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_963) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_963(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_963(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_964) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_964(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_964(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_965) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_965(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_965(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_966) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_966(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_966(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_967) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_967(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_967(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_968) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_968(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_968(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_969) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_969(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_969(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_970) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_970(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_970(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_971) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_971(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_971(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_972) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_972(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_972(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_973) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_973(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_973(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_974) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_974(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_974(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_975) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_975(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_975(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_976) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_976(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_976(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_977) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_977(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_977(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_978) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_978(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_978(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_979) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_979(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_979(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_980) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_980(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_980(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_981) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_981(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_981(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_982) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_982(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_982(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_983) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_983(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_983(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_984) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_984(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_984(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_985) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_985(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_985(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_986) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_986(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_986(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_987) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_987(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_987(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_988) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_988(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_988(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_989) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_989(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_989(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_990) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_990(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_990(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_991) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_991(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_991(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_992) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_992(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_992(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_993) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_993(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_993(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_994) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_994(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_994(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_995) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_995(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_995(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_996) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_996(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_996(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_997) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_997(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_997(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_998) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_998(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_998(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_999) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_999(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_999(FUNC)\n#endif\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/spqr_support.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Desire Nuentsa Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n\n#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS\n#include \"sparse.h\"\n#include <Eigen/SPQRSupport>\n\n\ntemplate<typename MatrixType,typename DenseMat>\nint generate_sparse_rectangular_problem(MatrixType& A, DenseMat& dA, int maxRows = 300, int maxCols = 300)\n{\n  eigen_assert(maxRows >= maxCols);\n  typedef typename MatrixType::Scalar Scalar;\n  int rows = internal::random<int>(1,maxRows);\n  int cols = internal::random<int>(1,rows);\n  double density = (std::max)(8./(rows*cols), 0.01);\n  \n  A.resize(rows,cols);\n  dA.resize(rows,cols);\n  initSparse<Scalar>(density, dA, A,ForceNonZeroDiag);\n  A.makeCompressed();\n  return rows;\n}\n\ntemplate<typename Scalar> void test_spqr_scalar()\n{\n  typedef SparseMatrix<Scalar,ColMajor> MatrixType; \n  MatrixType A;\n  Matrix<Scalar,Dynamic,Dynamic> dA;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n  DenseVector refX,x,b; \n  SPQR<MatrixType> solver; \n  generate_sparse_rectangular_problem(A,dA);\n  \n  Index m = A.rows();\n  b = DenseVector::Random(m);\n  solver.compute(A);\n  if (solver.info() != Success)\n  {\n    std::cerr << \"sparse QR factorization failed\\n\";\n    exit(0);\n    return;\n  }\n  x = solver.solve(b);\n  if (solver.info() != Success)\n  {\n    std::cerr << \"sparse QR factorization failed\\n\";\n    exit(0);\n    return;\n  }  \n  //Compare with a dense solver\n  refX = dA.colPivHouseholderQr().solve(b);\n  VERIFY(x.isApprox(refX,test_precision<Scalar>()));\n}\nEIGEN_DECLARE_TEST(spqr_support)\n{\n  CALL_SUBTEST_1(test_spqr_scalar<double>());\n  CALL_SUBTEST_2(test_spqr_scalar<std::complex<double> >());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/stable_norm.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename T> EIGEN_DONT_INLINE T copy(const T& x)\n{\n  return x;\n}\n\ntemplate<typename MatrixType> void stable_norm(const MatrixType& m)\n{\n  /* this test covers the following files:\n     StableNorm.h\n  */\n  using std::sqrt;\n  using std::abs;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  \n  bool complex_real_product_ok = true;\n\n  // Check the basic machine-dependent constants.\n  {\n    int ibeta, it, iemin, iemax;\n\n    ibeta = std::numeric_limits<RealScalar>::radix;         // base for floating-point numbers\n    it    = std::numeric_limits<RealScalar>::digits;        // number of base-beta digits in mantissa\n    iemin = std::numeric_limits<RealScalar>::min_exponent;  // minimum exponent\n    iemax = std::numeric_limits<RealScalar>::max_exponent;  // maximum exponent\n\n    VERIFY( (!(iemin > 1 - 2*it || 1+it>iemax || (it==2 && ibeta<5) || (it<=4 && ibeta <= 3 ) || it<2))\n           && \"the stable norm algorithm cannot be guaranteed on this computer\");\n    \n    Scalar inf = std::numeric_limits<RealScalar>::infinity();\n    if(NumTraits<Scalar>::IsComplex && (numext::isnan)(inf*RealScalar(1)) )\n    {\n      complex_real_product_ok = false;\n      static bool first = true;\n      if(first)\n        std::cerr << \"WARNING: compiler mess up complex*real product, \" << inf << \" * \" << 1.0 << \" = \" << inf*RealScalar(1) << std::endl;\n      first = false;\n    }\n  }\n\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  // get a non-zero random factor\n  Scalar factor = internal::random<Scalar>();\n  while(numext::abs2(factor)<RealScalar(1e-4))\n    factor = internal::random<Scalar>();\n  Scalar big = factor * ((std::numeric_limits<RealScalar>::max)() * RealScalar(1e-4));\n  \n  factor = internal::random<Scalar>();\n  while(numext::abs2(factor)<RealScalar(1e-4))\n    factor = internal::random<Scalar>();\n  Scalar small = factor * ((std::numeric_limits<RealScalar>::min)() * RealScalar(1e4));\n\n  Scalar one(1);\n\n  MatrixType  vzero = MatrixType::Zero(rows, cols),\n              vrand = MatrixType::Random(rows, cols),\n              vbig(rows, cols),\n              vsmall(rows,cols);\n\n  vbig.fill(big);\n  vsmall.fill(small);\n\n  VERIFY_IS_MUCH_SMALLER_THAN(vzero.norm(), static_cast<RealScalar>(1));\n  VERIFY_IS_APPROX(vrand.stableNorm(),      vrand.norm());\n  VERIFY_IS_APPROX(vrand.blueNorm(),        vrand.norm());\n  VERIFY_IS_APPROX(vrand.hypotNorm(),       vrand.norm());\n\n  // test with expressions as input\n  VERIFY_IS_APPROX((one*vrand).stableNorm(),      vrand.norm());\n  VERIFY_IS_APPROX((one*vrand).blueNorm(),        vrand.norm());\n  VERIFY_IS_APPROX((one*vrand).hypotNorm(),       vrand.norm());\n  VERIFY_IS_APPROX((one*vrand+one*vrand-one*vrand).stableNorm(),      vrand.norm());\n  VERIFY_IS_APPROX((one*vrand+one*vrand-one*vrand).blueNorm(),        vrand.norm());\n  VERIFY_IS_APPROX((one*vrand+one*vrand-one*vrand).hypotNorm(),       vrand.norm());\n\n  RealScalar size = static_cast<RealScalar>(m.size());\n\n  // test numext::isfinite\n  VERIFY(!(numext::isfinite)( std::numeric_limits<RealScalar>::infinity()));\n  VERIFY(!(numext::isfinite)(sqrt(-abs(big))));\n\n  // test overflow\n  VERIFY((numext::isfinite)(sqrt(size)*abs(big)));\n  VERIFY_IS_NOT_APPROX(sqrt(copy(vbig.squaredNorm())), abs(sqrt(size)*big)); // here the default norm must fail\n  VERIFY_IS_APPROX(vbig.stableNorm(), sqrt(size)*abs(big));\n  VERIFY_IS_APPROX(vbig.blueNorm(),   sqrt(size)*abs(big));\n  VERIFY_IS_APPROX(vbig.hypotNorm(),  sqrt(size)*abs(big));\n\n  // test underflow\n  VERIFY((numext::isfinite)(sqrt(size)*abs(small)));\n  VERIFY_IS_NOT_APPROX(sqrt(copy(vsmall.squaredNorm())),   abs(sqrt(size)*small)); // here the default norm must fail\n  VERIFY_IS_APPROX(vsmall.stableNorm(), sqrt(size)*abs(small));\n  VERIFY_IS_APPROX(vsmall.blueNorm(),   sqrt(size)*abs(small));\n  VERIFY_IS_APPROX(vsmall.hypotNorm(),  sqrt(size)*abs(small));\n\n  // Test compilation of cwise() version\n  VERIFY_IS_APPROX(vrand.colwise().stableNorm(),      vrand.colwise().norm());\n  VERIFY_IS_APPROX(vrand.colwise().blueNorm(),        vrand.colwise().norm());\n  VERIFY_IS_APPROX(vrand.colwise().hypotNorm(),       vrand.colwise().norm());\n  VERIFY_IS_APPROX(vrand.rowwise().stableNorm(),      vrand.rowwise().norm());\n  VERIFY_IS_APPROX(vrand.rowwise().blueNorm(),        vrand.rowwise().norm());\n  VERIFY_IS_APPROX(vrand.rowwise().hypotNorm(),       vrand.rowwise().norm());\n  \n  // test NaN, +inf, -inf \n  MatrixType v;\n  Index i = internal::random<Index>(0,rows-1);\n  Index j = internal::random<Index>(0,cols-1);\n\n  // NaN\n  {\n    v = vrand;\n    v(i,j) = std::numeric_limits<RealScalar>::quiet_NaN();\n    VERIFY(!(numext::isfinite)(v.squaredNorm()));   VERIFY((numext::isnan)(v.squaredNorm()));\n    VERIFY(!(numext::isfinite)(v.norm()));          VERIFY((numext::isnan)(v.norm()));\n    VERIFY(!(numext::isfinite)(v.stableNorm()));    VERIFY((numext::isnan)(v.stableNorm()));\n    VERIFY(!(numext::isfinite)(v.blueNorm()));      VERIFY((numext::isnan)(v.blueNorm()));\n    VERIFY(!(numext::isfinite)(v.hypotNorm()));     VERIFY((numext::isnan)(v.hypotNorm()));\n  }\n  \n  // +inf\n  {\n    v = vrand;\n    v(i,j) = std::numeric_limits<RealScalar>::infinity();\n    VERIFY(!(numext::isfinite)(v.squaredNorm()));   VERIFY(isPlusInf(v.squaredNorm()));\n    VERIFY(!(numext::isfinite)(v.norm()));          VERIFY(isPlusInf(v.norm()));\n    VERIFY(!(numext::isfinite)(v.stableNorm()));\n    if(complex_real_product_ok){\n      VERIFY(isPlusInf(v.stableNorm()));\n    }\n    VERIFY(!(numext::isfinite)(v.blueNorm()));      VERIFY(isPlusInf(v.blueNorm()));\n    VERIFY(!(numext::isfinite)(v.hypotNorm()));     VERIFY(isPlusInf(v.hypotNorm()));\n  }\n  \n  // -inf\n  {\n    v = vrand;\n    v(i,j) = -std::numeric_limits<RealScalar>::infinity();\n    VERIFY(!(numext::isfinite)(v.squaredNorm()));   VERIFY(isPlusInf(v.squaredNorm()));\n    VERIFY(!(numext::isfinite)(v.norm()));          VERIFY(isPlusInf(v.norm()));\n    VERIFY(!(numext::isfinite)(v.stableNorm()));\n    if(complex_real_product_ok) {\n      VERIFY(isPlusInf(v.stableNorm()));\n    }\n    VERIFY(!(numext::isfinite)(v.blueNorm()));      VERIFY(isPlusInf(v.blueNorm()));\n    VERIFY(!(numext::isfinite)(v.hypotNorm()));     VERIFY(isPlusInf(v.hypotNorm()));\n  }\n  \n  // mix\n  {\n    Index i2 = internal::random<Index>(0,rows-1);\n    Index j2 = internal::random<Index>(0,cols-1);\n    v = vrand;\n    v(i,j) = -std::numeric_limits<RealScalar>::infinity();\n    v(i2,j2) = std::numeric_limits<RealScalar>::quiet_NaN();\n    VERIFY(!(numext::isfinite)(v.squaredNorm()));   VERIFY((numext::isnan)(v.squaredNorm()));\n    VERIFY(!(numext::isfinite)(v.norm()));          VERIFY((numext::isnan)(v.norm()));\n    VERIFY(!(numext::isfinite)(v.stableNorm()));    VERIFY((numext::isnan)(v.stableNorm()));\n    VERIFY(!(numext::isfinite)(v.blueNorm()));      VERIFY((numext::isnan)(v.blueNorm()));\n    if (i2 != i || j2 != j) {\n      // hypot propagates inf over NaN.\n      VERIFY(!(numext::isfinite)(v.hypotNorm()));     VERIFY((numext::isinf)(v.hypotNorm()));\n    } else {\n      // inf is overwritten by NaN, expect norm to be NaN.\n      VERIFY(!(numext::isfinite)(v.hypotNorm()));     VERIFY((numext::isnan)(v.hypotNorm()));\n    }\n  }\n\n  // stableNormalize[d]\n  {\n    VERIFY_IS_APPROX(vrand.stableNormalized(), vrand.normalized());\n    MatrixType vcopy(vrand);\n    vcopy.stableNormalize();\n    VERIFY_IS_APPROX(vcopy, vrand.normalized());\n    VERIFY_IS_APPROX((vrand.stableNormalized()).norm(), RealScalar(1));\n    VERIFY_IS_APPROX(vcopy.norm(), RealScalar(1));\n    VERIFY_IS_APPROX((vbig.stableNormalized()).norm(), RealScalar(1));\n    VERIFY_IS_APPROX((vsmall.stableNormalized()).norm(), RealScalar(1));\n    RealScalar big_scaling = ((std::numeric_limits<RealScalar>::max)() * RealScalar(1e-4));\n    VERIFY_IS_APPROX(vbig/big_scaling, (vbig.stableNorm() * vbig.stableNormalized()).eval()/big_scaling);\n    VERIFY_IS_APPROX(vsmall, vsmall.stableNorm() * vsmall.stableNormalized());\n  }\n}\n\ntemplate<typename Scalar>\nvoid test_hypot()\n{\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  Scalar factor = internal::random<Scalar>();\n  while(numext::abs2(factor)<RealScalar(1e-4))\n    factor = internal::random<Scalar>();\n  Scalar big = factor * ((std::numeric_limits<RealScalar>::max)() * RealScalar(1e-4));\n  \n  factor = internal::random<Scalar>();\n  while(numext::abs2(factor)<RealScalar(1e-4))\n    factor = internal::random<Scalar>();\n  Scalar small = factor * ((std::numeric_limits<RealScalar>::min)() * RealScalar(1e4));\n\n  Scalar  one   (1),\n          zero  (0),\n          sqrt2 (std::sqrt(2)),\n          nan   (std::numeric_limits<RealScalar>::quiet_NaN());\n\n  Scalar a = internal::random<Scalar>(-1,1);\n  Scalar b = internal::random<Scalar>(-1,1);\n  VERIFY_IS_APPROX(numext::hypot(a,b),std::sqrt(numext::abs2(a)+numext::abs2(b)));\n  VERIFY_IS_EQUAL(numext::hypot(zero,zero), zero);\n  VERIFY_IS_APPROX(numext::hypot(one, one), sqrt2);\n  VERIFY_IS_APPROX(numext::hypot(big,big), sqrt2*numext::abs(big));\n  VERIFY_IS_APPROX(numext::hypot(small,small), sqrt2*numext::abs(small));\n  VERIFY_IS_APPROX(numext::hypot(small,big), numext::abs(big));\n  VERIFY((numext::isnan)(numext::hypot(nan,a)));\n  VERIFY((numext::isnan)(numext::hypot(a,nan)));\n}\n\nEIGEN_DECLARE_TEST(stable_norm)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_3( test_hypot<double>() );\n    CALL_SUBTEST_4( test_hypot<float>() );\n    CALL_SUBTEST_5( test_hypot<std::complex<double> >() );\n    CALL_SUBTEST_6( test_hypot<std::complex<float> >() );\n\n    CALL_SUBTEST_1( stable_norm(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( stable_norm(Vector4d()) );\n    CALL_SUBTEST_3( stable_norm(VectorXd(internal::random<int>(10,2000))) );\n    CALL_SUBTEST_3( stable_norm(MatrixXd(internal::random<int>(10,200), internal::random<int>(10,200))) );\n    CALL_SUBTEST_4( stable_norm(VectorXf(internal::random<int>(10,2000))) );\n    CALL_SUBTEST_5( stable_norm(VectorXcd(internal::random<int>(10,2000))) );\n    CALL_SUBTEST_6( stable_norm(VectorXcf(internal::random<int>(10,2000))) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/stddeque.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2010 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/StdDeque>\n#include <Eigen/Geometry>\n\ntemplate<typename MatrixType>\nvoid check_stddeque_matrix(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n  MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols);\n  std::deque<MatrixType,Eigen::aligned_allocator<MatrixType> > v(10, MatrixType::Zero(rows,cols)), w(20, y);\n  v.front() = x;\n  w.front() = w.back();\n  VERIFY_IS_APPROX(w.front(), w.back());\n  v = w;\n\n  typename std::deque<MatrixType,Eigen::aligned_allocator<MatrixType> >::iterator vi = v.begin();\n  typename std::deque<MatrixType,Eigen::aligned_allocator<MatrixType> >::iterator wi = w.begin();\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(*vi, *wi);\n    ++vi;\n    ++wi;\n  }\n\n  v.resize(21,MatrixType::Zero(rows,cols));  \n  v.back() = x;\n  VERIFY_IS_APPROX(v.back(), x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v.back(), y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v.back(), x);\n}\n\ntemplate<typename TransformType>\nvoid check_stddeque_transform(const TransformType&)\n{\n  typedef typename TransformType::MatrixType MatrixType;\n  TransformType x(MatrixType::Random()), y(MatrixType::Random()), ti=TransformType::Identity();\n  std::deque<TransformType,Eigen::aligned_allocator<TransformType> > v(10,ti), w(20, y);\n  v.front() = x;\n  w.front() = w.back();\n  VERIFY_IS_APPROX(w.front(), w.back());\n  v = w;\n\n  typename std::deque<TransformType,Eigen::aligned_allocator<TransformType> >::iterator vi = v.begin();\n  typename std::deque<TransformType,Eigen::aligned_allocator<TransformType> >::iterator wi = w.begin();\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(*vi, *wi);\n    ++vi;\n    ++wi;\n  }\n\n  v.resize(21,ti);\n  v.back() = x;\n  VERIFY_IS_APPROX(v.back(), x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v.back(), y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v.back(), x);\n}\n\ntemplate<typename QuaternionType>\nvoid check_stddeque_quaternion(const QuaternionType&)\n{\n  typedef typename QuaternionType::Coefficients Coefficients;\n  QuaternionType x(Coefficients::Random()), y(Coefficients::Random()), qi=QuaternionType::Identity();\n  std::deque<QuaternionType,Eigen::aligned_allocator<QuaternionType> > v(10,qi), w(20, y);\n  v.front() = x;\n  w.front() = w.back();\n  VERIFY_IS_APPROX(w.front(), w.back());\n  v = w;\n\n  typename std::deque<QuaternionType,Eigen::aligned_allocator<QuaternionType> >::iterator vi = v.begin();\n  typename std::deque<QuaternionType,Eigen::aligned_allocator<QuaternionType> >::iterator wi = w.begin();\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(*vi, *wi);\n    ++vi;\n    ++wi;\n  }\n\n  v.resize(21,qi);\n  v.back() = x;\n  VERIFY_IS_APPROX(v.back(), x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v.back(), y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v.back(), x);\n}\n\nEIGEN_DECLARE_TEST(stddeque)\n{\n  // some non vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stddeque_matrix(Vector2f()));\n  CALL_SUBTEST_1(check_stddeque_matrix(Matrix3f()));\n  CALL_SUBTEST_2(check_stddeque_matrix(Matrix3d()));\n\n  // some vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stddeque_matrix(Matrix2f()));\n  CALL_SUBTEST_1(check_stddeque_matrix(Vector4f()));\n  CALL_SUBTEST_1(check_stddeque_matrix(Matrix4f()));\n  CALL_SUBTEST_2(check_stddeque_matrix(Matrix4d()));\n\n  // some dynamic sizes\n  CALL_SUBTEST_3(check_stddeque_matrix(MatrixXd(1,1)));\n  CALL_SUBTEST_3(check_stddeque_matrix(VectorXd(20)));\n  CALL_SUBTEST_3(check_stddeque_matrix(RowVectorXf(20)));\n  CALL_SUBTEST_3(check_stddeque_matrix(MatrixXcf(10,10)));\n\n  // some Transform\n  CALL_SUBTEST_4(check_stddeque_transform(Affine2f()));\n  CALL_SUBTEST_4(check_stddeque_transform(Affine3f()));\n  CALL_SUBTEST_4(check_stddeque_transform(Affine3d()));\n\n  // some Quaternion\n  CALL_SUBTEST_5(check_stddeque_quaternion(Quaternionf()));\n  CALL_SUBTEST_5(check_stddeque_quaternion(Quaterniond()));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/stddeque_overload.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2010 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/StdDeque>\n#include <Eigen/Geometry>\n\nEIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Vector4f)\n\nEIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Matrix2f)\nEIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Matrix4f)\nEIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Matrix4d)\n\nEIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Affine3f)\nEIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Affine3d)\n\nEIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Quaternionf)\nEIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Quaterniond)\n\ntemplate<typename MatrixType>\nvoid check_stddeque_matrix(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n  MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols);\n  std::deque<MatrixType> v(10, MatrixType::Zero(rows,cols)), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n\n  // do a lot of push_back such that the deque gets internally resized\n  // (with memory reallocation)\n  MatrixType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(v[i]==w[(i-23)%w.size()]);\n  }\n}\n\ntemplate<typename TransformType>\nvoid check_stddeque_transform(const TransformType&)\n{\n  typedef typename TransformType::MatrixType MatrixType;\n  TransformType x(MatrixType::Random()), y(MatrixType::Random()), ti=TransformType::Identity();\n  std::deque<TransformType> v(10,ti), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21,ti);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n\n  // do a lot of push_back such that the deque gets internally resized\n  // (with memory reallocation)\n  TransformType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(v[i].matrix()==w[(i-23)%w.size()].matrix());\n  }\n}\n\ntemplate<typename QuaternionType>\nvoid check_stddeque_quaternion(const QuaternionType&)\n{\n  typedef typename QuaternionType::Coefficients Coefficients;\n  QuaternionType x(Coefficients::Random()), y(Coefficients::Random()), qi=QuaternionType::Identity();\n  std::deque<QuaternionType> v(10,qi), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21,qi);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n\n  // do a lot of push_back such that the deque gets internally resized\n  // (with memory reallocation)\n  QuaternionType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(v[i].coeffs()==w[(i-23)%w.size()].coeffs());\n  }\n}\n\nEIGEN_DECLARE_TEST(stddeque_overload)\n{\n  // some non vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stddeque_matrix(Vector2f()));\n  CALL_SUBTEST_1(check_stddeque_matrix(Matrix3f()));\n  CALL_SUBTEST_2(check_stddeque_matrix(Matrix3d()));\n\n  // some vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stddeque_matrix(Matrix2f()));\n  CALL_SUBTEST_1(check_stddeque_matrix(Vector4f()));\n  CALL_SUBTEST_1(check_stddeque_matrix(Matrix4f()));\n  CALL_SUBTEST_2(check_stddeque_matrix(Matrix4d()));\n\n  // some dynamic sizes\n  CALL_SUBTEST_3(check_stddeque_matrix(MatrixXd(1,1)));\n  CALL_SUBTEST_3(check_stddeque_matrix(VectorXd(20)));\n  CALL_SUBTEST_3(check_stddeque_matrix(RowVectorXf(20)));\n  CALL_SUBTEST_3(check_stddeque_matrix(MatrixXcf(10,10)));\n\n  // some Transform\n  CALL_SUBTEST_4(check_stddeque_transform(Affine2f())); // does not need the specialization (2+1)^2 = 9\n  CALL_SUBTEST_4(check_stddeque_transform(Affine3f()));\n  CALL_SUBTEST_4(check_stddeque_transform(Affine3d()));\n\n  // some Quaternion\n  CALL_SUBTEST_5(check_stddeque_quaternion(Quaternionf()));\n  CALL_SUBTEST_5(check_stddeque_quaternion(Quaterniond()));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/stdlist.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2010 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/StdList>\n#include <Eigen/Geometry>\n\ntemplate<typename MatrixType>\nvoid check_stdlist_matrix(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n  MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols);\n  std::list<MatrixType,Eigen::aligned_allocator<MatrixType> > v(10, MatrixType::Zero(rows,cols)), w(20, y);\n  v.front() = x;\n  w.front() = w.back();\n  VERIFY_IS_APPROX(w.front(), w.back());\n  v = w;\n\n  typename std::list<MatrixType,Eigen::aligned_allocator<MatrixType> >::iterator vi = v.begin();\n  typename std::list<MatrixType,Eigen::aligned_allocator<MatrixType> >::iterator wi = w.begin();\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(*vi, *wi);\n    ++vi;\n    ++wi;\n  }\n\n  v.resize(21, MatrixType::Zero(rows,cols));  \n  v.back() = x;\n  VERIFY_IS_APPROX(v.back(), x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v.back(), y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v.back(), x);\n}\n\ntemplate<typename TransformType>\nvoid check_stdlist_transform(const TransformType&)\n{\n  typedef typename TransformType::MatrixType MatrixType;\n  TransformType x(MatrixType::Random()), y(MatrixType::Random()), ti=TransformType::Identity();\n  std::list<TransformType,Eigen::aligned_allocator<TransformType> > v(10,ti), w(20, y);\n  v.front() = x;\n  w.front() = w.back();\n  VERIFY_IS_APPROX(w.front(), w.back());\n  v = w;\n\n  typename std::list<TransformType,Eigen::aligned_allocator<TransformType> >::iterator vi = v.begin();\n  typename std::list<TransformType,Eigen::aligned_allocator<TransformType> >::iterator wi = w.begin();\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(*vi, *wi);\n    ++vi;\n    ++wi;\n  }\n\n  v.resize(21, ti);\n  v.back() = x;\n  VERIFY_IS_APPROX(v.back(), x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v.back(), y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v.back(), x);\n}\n\ntemplate<typename QuaternionType>\nvoid check_stdlist_quaternion(const QuaternionType&)\n{\n  typedef typename QuaternionType::Coefficients Coefficients;\n  QuaternionType x(Coefficients::Random()), y(Coefficients::Random()), qi=QuaternionType::Identity();\n  std::list<QuaternionType,Eigen::aligned_allocator<QuaternionType> > v(10,qi), w(20, y);\n  v.front() = x;\n  w.front() = w.back();\n  VERIFY_IS_APPROX(w.front(), w.back());\n  v = w;\n\n  typename std::list<QuaternionType,Eigen::aligned_allocator<QuaternionType> >::iterator vi = v.begin();\n  typename std::list<QuaternionType,Eigen::aligned_allocator<QuaternionType> >::iterator wi = w.begin();\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(*vi, *wi);\n    ++vi;\n    ++wi;\n  }\n\n  v.resize(21,qi);\n  v.back() = x;\n  VERIFY_IS_APPROX(v.back(), x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v.back(), y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v.back(), x);\n}\n\nEIGEN_DECLARE_TEST(stdlist)\n{\n  // some non vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stdlist_matrix(Vector2f()));\n  CALL_SUBTEST_1(check_stdlist_matrix(Matrix3f()));\n  CALL_SUBTEST_2(check_stdlist_matrix(Matrix3d()));\n\n  // some vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stdlist_matrix(Matrix2f()));\n  CALL_SUBTEST_1(check_stdlist_matrix(Vector4f()));\n  CALL_SUBTEST_1(check_stdlist_matrix(Matrix4f()));\n  CALL_SUBTEST_2(check_stdlist_matrix(Matrix4d()));\n\n  // some dynamic sizes\n  CALL_SUBTEST_3(check_stdlist_matrix(MatrixXd(1,1)));\n  CALL_SUBTEST_3(check_stdlist_matrix(VectorXd(20)));\n  CALL_SUBTEST_3(check_stdlist_matrix(RowVectorXf(20)));\n  CALL_SUBTEST_3(check_stdlist_matrix(MatrixXcf(10,10)));\n\n  // some Transform\n  CALL_SUBTEST_4(check_stdlist_transform(Affine2f()));\n  CALL_SUBTEST_4(check_stdlist_transform(Affine3f()));\n  CALL_SUBTEST_4(check_stdlist_transform(Affine3d()));\n\n  // some Quaternion\n  CALL_SUBTEST_5(check_stdlist_quaternion(Quaternionf()));\n  CALL_SUBTEST_5(check_stdlist_quaternion(Quaterniond()));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/stdlist_overload.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2010 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/StdList>\n#include <Eigen/Geometry>\n\nEIGEN_DEFINE_STL_LIST_SPECIALIZATION(Vector4f)\n\nEIGEN_DEFINE_STL_LIST_SPECIALIZATION(Matrix2f)\nEIGEN_DEFINE_STL_LIST_SPECIALIZATION(Matrix4f)\nEIGEN_DEFINE_STL_LIST_SPECIALIZATION(Matrix4d)\n\nEIGEN_DEFINE_STL_LIST_SPECIALIZATION(Affine3f)\nEIGEN_DEFINE_STL_LIST_SPECIALIZATION(Affine3d)\n\nEIGEN_DEFINE_STL_LIST_SPECIALIZATION(Quaternionf)\nEIGEN_DEFINE_STL_LIST_SPECIALIZATION(Quaterniond)\n\ntemplate <class Container, class Position>\ntypename Container::iterator get(Container & c, Position position)\n{\n  typename Container::iterator it = c.begin();\n  std::advance(it, position);\n  return it;\n}\n\ntemplate <class Container, class Position, class Value>\nvoid set(Container & c, Position position, const Value & value)\n{\n  typename Container::iterator it = c.begin();\n  std::advance(it, position);\n  *it = value;\n}\n\ntemplate<typename MatrixType>\nvoid check_stdlist_matrix(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n  MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols);\n  std::list<MatrixType> v(10, MatrixType::Zero(rows,cols)), w(20, y);\n  typename std::list<MatrixType>::iterator itv = get(v, 5);\n  typename std::list<MatrixType>::iterator itw = get(w, 6);\n  *itv = x;\n  *itw = *itv;\n  VERIFY_IS_APPROX(*itw, *itv);\n  v = w;\n  itv = v.begin();\n  itw = w.begin();\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(*itw, *itv);\n    ++itv;\n    ++itw;\n  }\n\n  v.resize(21);\n  set(v, 20, x);\n  VERIFY_IS_APPROX(*get(v, 20), x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(*get(v, 21), y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(*get(v, 22), x);\n\n  // do a lot of push_back such that the list gets internally resized\n  // (with memory reallocation)\n  MatrixType* ref = &(*get(w, 0));\n  for(int i=0; i<30 || ((ref==&(*get(w, 0))) && i<300); ++i)\n    v.push_back(*get(w, i%w.size()));\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY((*get(v, i))==(*get(w, (i-23)%w.size())));\n  }\n}\n\ntemplate<typename TransformType>\nvoid check_stdlist_transform(const TransformType&)\n{\n  typedef typename TransformType::MatrixType MatrixType;\n  TransformType x(MatrixType::Random()), y(MatrixType::Random()), ti=TransformType::Identity();\n  std::list<TransformType> v(10,ti), w(20, y);\n  typename std::list<TransformType>::iterator itv = get(v, 5);\n  typename std::list<TransformType>::iterator itw = get(w, 6);\n  *itv = x;\n  *itw = *itv;\n  VERIFY_IS_APPROX(*itw, *itv);\n  v = w;\n  itv = v.begin();\n  itw = w.begin();\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(*itw, *itv);\n    ++itv;\n    ++itw;\n  }\n\n  v.resize(21, ti);\n  set(v, 20, x);\n  VERIFY_IS_APPROX(*get(v, 20), x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(*get(v, 21), y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(*get(v, 22), x);\n\n  // do a lot of push_back such that the list gets internally resized\n  // (with memory reallocation)\n  TransformType* ref = &(*get(w, 0));\n  for(int i=0; i<30 || ((ref==&(*get(w, 0))) && i<300); ++i)\n    v.push_back(*get(w, i%w.size()));\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(get(v, i)->matrix()==get(w, (i-23)%w.size())->matrix());\n  }\n}\n\ntemplate<typename QuaternionType>\nvoid check_stdlist_quaternion(const QuaternionType&)\n{\n  typedef typename QuaternionType::Coefficients Coefficients;\n  QuaternionType x(Coefficients::Random()), y(Coefficients::Random()), qi=QuaternionType::Identity();\n  std::list<QuaternionType> v(10,qi), w(20, y);\n  typename std::list<QuaternionType>::iterator itv = get(v, 5);\n  typename std::list<QuaternionType>::iterator itw = get(w, 6);\n  *itv = x;\n  *itw = *itv;\n  VERIFY_IS_APPROX(*itw, *itv);\n  v = w;\n  itv = v.begin();\n  itw = w.begin();\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(*itw, *itv);\n    ++itv;\n    ++itw;\n  }\n\n  v.resize(21,qi);\n  set(v, 20, x);\n  VERIFY_IS_APPROX(*get(v, 20), x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(*get(v, 21), y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(*get(v, 22), x);\n\n  // do a lot of push_back such that the list gets internally resized\n  // (with memory reallocation)\n  QuaternionType* ref = &(*get(w, 0));\n  for(int i=0; i<30 || ((ref==&(*get(w, 0))) && i<300); ++i)\n    v.push_back(*get(w, i%w.size()));\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(get(v, i)->coeffs()==get(w, (i-23)%w.size())->coeffs());\n  }\n}\n\nEIGEN_DECLARE_TEST(stdlist_overload)\n{\n  // some non vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stdlist_matrix(Vector2f()));\n  CALL_SUBTEST_1(check_stdlist_matrix(Matrix3f()));\n  CALL_SUBTEST_2(check_stdlist_matrix(Matrix3d()));\n\n  // some vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stdlist_matrix(Matrix2f()));\n  CALL_SUBTEST_1(check_stdlist_matrix(Vector4f()));\n  CALL_SUBTEST_1(check_stdlist_matrix(Matrix4f()));\n  CALL_SUBTEST_2(check_stdlist_matrix(Matrix4d()));\n\n  // some dynamic sizes\n  CALL_SUBTEST_3(check_stdlist_matrix(MatrixXd(1,1)));\n  CALL_SUBTEST_3(check_stdlist_matrix(VectorXd(20)));\n  CALL_SUBTEST_3(check_stdlist_matrix(RowVectorXf(20)));\n  CALL_SUBTEST_3(check_stdlist_matrix(MatrixXcf(10,10)));\n\n  // some Transform\n  CALL_SUBTEST_4(check_stdlist_transform(Affine2f())); // does not need the specialization (2+1)^2 = 9\n  CALL_SUBTEST_4(check_stdlist_transform(Affine3f()));\n  CALL_SUBTEST_4(check_stdlist_transform(Affine3d()));\n\n  // some Quaternion\n  CALL_SUBTEST_5(check_stdlist_quaternion(Quaternionf()));\n  CALL_SUBTEST_5(check_stdlist_quaternion(Quaterniond()));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/stdvector.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/StdVector>\n#include <Eigen/Geometry>\n\ntemplate<typename MatrixType>\nvoid check_stdvector_matrix(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n  MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols);\n  std::vector<MatrixType,Eigen::aligned_allocator<MatrixType> > v(10, MatrixType::Zero(rows,cols)), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n  VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(MatrixType));\n\n  // do a lot of push_back such that the vector gets internally resized\n  // (with memory reallocation)\n  MatrixType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(v[i]==w[(i-23)%w.size()]);\n  }\n}\n\ntemplate<typename TransformType>\nvoid check_stdvector_transform(const TransformType&)\n{\n  typedef typename TransformType::MatrixType MatrixType;\n  TransformType x(MatrixType::Random()), y(MatrixType::Random());\n  std::vector<TransformType,Eigen::aligned_allocator<TransformType> > v(10), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n  VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(TransformType));\n\n  // do a lot of push_back such that the vector gets internally resized\n  // (with memory reallocation)\n  TransformType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(v[i].matrix()==w[(i-23)%w.size()].matrix());\n  }\n}\n\ntemplate<typename QuaternionType>\nvoid check_stdvector_quaternion(const QuaternionType&)\n{\n  typedef typename QuaternionType::Coefficients Coefficients;\n  QuaternionType x(Coefficients::Random()), y(Coefficients::Random()), qi=QuaternionType::Identity();\n  std::vector<QuaternionType,Eigen::aligned_allocator<QuaternionType> > v(10,qi), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n  VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(QuaternionType));\n\n  // do a lot of push_back such that the vector gets internally resized\n  // (with memory reallocation)\n  QuaternionType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(v[i].coeffs()==w[(i-23)%w.size()].coeffs());\n  }\n}\n\n// the code below triggered an invalid warning with gcc >= 7\n// eigen/Eigen/src/Core/util/Memory.h:189:12: warning: argument 1 value '18446744073709551612' exceeds maximum object size 9223372036854775807\n// This has been reported to gcc there: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=87544\nvoid std_vector_gcc_warning()\n{\n  typedef Eigen::Vector3f T;\n  std::vector<T, Eigen::aligned_allocator<T> > v;\n  v.push_back(T());\n}\n\nEIGEN_DECLARE_TEST(stdvector)\n{\n  // some non vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stdvector_matrix(Vector2f()));\n  CALL_SUBTEST_1(check_stdvector_matrix(Matrix3f()));\n  CALL_SUBTEST_2(check_stdvector_matrix(Matrix3d()));\n\n  // some vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stdvector_matrix(Matrix2f()));\n  CALL_SUBTEST_1(check_stdvector_matrix(Vector4f()));\n  CALL_SUBTEST_1(check_stdvector_matrix(Matrix4f()));\n  CALL_SUBTEST_2(check_stdvector_matrix(Matrix4d()));\n\n  // some dynamic sizes\n  CALL_SUBTEST_3(check_stdvector_matrix(MatrixXd(1,1)));\n  CALL_SUBTEST_3(check_stdvector_matrix(VectorXd(20)));\n  CALL_SUBTEST_3(check_stdvector_matrix(RowVectorXf(20)));\n  CALL_SUBTEST_3(check_stdvector_matrix(MatrixXcf(10,10)));\n\n  // some Transform\n  CALL_SUBTEST_4(check_stdvector_transform(Projective2f()));\n  CALL_SUBTEST_4(check_stdvector_transform(Projective3f()));\n  CALL_SUBTEST_4(check_stdvector_transform(Projective3d()));\n  //CALL_SUBTEST(heck_stdvector_transform(Projective4d()));\n\n  // some Quaternion\n  CALL_SUBTEST_5(check_stdvector_quaternion(Quaternionf()));\n  CALL_SUBTEST_5(check_stdvector_quaternion(Quaterniond()));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/stdvector_overload.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2010 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/StdVector>\n#include <Eigen/Geometry>\n\nEIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Vector4f)\n\nEIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Matrix2f)\nEIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Matrix4f)\nEIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Matrix4d)\n\nEIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Affine3f)\nEIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Affine3d)\n\nEIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Quaternionf)\nEIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Quaterniond)\n\ntemplate<typename MatrixType>\nvoid check_stdvector_matrix(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n  MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols);\n  std::vector<MatrixType> v(10, MatrixType::Zero(rows,cols)), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n  VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(MatrixType));\n\n  // do a lot of push_back such that the vector gets internally resized\n  // (with memory reallocation)\n  MatrixType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(v[i]==w[(i-23)%w.size()]);\n  }\n}\n\ntemplate<typename TransformType>\nvoid check_stdvector_transform(const TransformType&)\n{\n  typedef typename TransformType::MatrixType MatrixType;\n  TransformType x(MatrixType::Random()), y(MatrixType::Random());\n  std::vector<TransformType> v(10), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n  VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(TransformType));\n\n  // do a lot of push_back such that the vector gets internally resized\n  // (with memory reallocation)\n  TransformType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(v[i].matrix()==w[(i-23)%w.size()].matrix());\n  }\n}\n\ntemplate<typename QuaternionType>\nvoid check_stdvector_quaternion(const QuaternionType&)\n{\n  typedef typename QuaternionType::Coefficients Coefficients;\n  QuaternionType x(Coefficients::Random()), y(Coefficients::Random()), qi=QuaternionType::Identity();\n  std::vector<QuaternionType> v(10,qi), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n  VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(QuaternionType));\n\n  // do a lot of push_back such that the vector gets internally resized\n  // (with memory reallocation)\n  QuaternionType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(v[i].coeffs()==w[(i-23)%w.size()].coeffs());\n  }\n}\n\nEIGEN_DECLARE_TEST(stdvector_overload)\n{\n  // some non vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stdvector_matrix(Vector2f()));\n  CALL_SUBTEST_1(check_stdvector_matrix(Matrix3f()));\n  CALL_SUBTEST_2(check_stdvector_matrix(Matrix3d()));\n\n  // some vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stdvector_matrix(Matrix2f()));\n  CALL_SUBTEST_1(check_stdvector_matrix(Vector4f()));\n  CALL_SUBTEST_1(check_stdvector_matrix(Matrix4f()));\n  CALL_SUBTEST_2(check_stdvector_matrix(Matrix4d()));\n\n  // some dynamic sizes\n  CALL_SUBTEST_3(check_stdvector_matrix(MatrixXd(1,1)));\n  CALL_SUBTEST_3(check_stdvector_matrix(VectorXd(20)));\n  CALL_SUBTEST_3(check_stdvector_matrix(RowVectorXf(20)));\n  CALL_SUBTEST_3(check_stdvector_matrix(MatrixXcf(10,10)));\n\n  // some Transform\n  CALL_SUBTEST_4(check_stdvector_transform(Affine2f())); // does not need the specialization (2+1)^2 = 9\n  CALL_SUBTEST_4(check_stdvector_transform(Affine3f()));\n  CALL_SUBTEST_4(check_stdvector_transform(Affine3d()));\n\n  // some Quaternion\n  CALL_SUBTEST_5(check_stdvector_quaternion(Quaternionf()));\n  CALL_SUBTEST_5(check_stdvector_quaternion(Quaterniond()));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/stl_iterators.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2018-2019 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <iterator>\n#include <numeric>\n\ntemplate< class Iterator >\nstd::reverse_iterator<Iterator>\nmake_reverse_iterator( Iterator i )\n{\n  return std::reverse_iterator<Iterator>(i);\n}\n\n#if !EIGEN_HAS_CXX11\ntemplate<class ForwardIt>\nForwardIt is_sorted_until(ForwardIt firstIt, ForwardIt lastIt)\n{\n    if (firstIt != lastIt) {\n        ForwardIt next = firstIt;\n        while (++next != lastIt) {\n            if (*next < *firstIt)\n                return next;\n            firstIt = next;\n        }\n    }\n    return lastIt;\n}\ntemplate<class ForwardIt>\nbool is_sorted(ForwardIt firstIt, ForwardIt lastIt)\n{\n    return ::is_sorted_until(firstIt, lastIt) == lastIt;\n}\n#else\nusing std::is_sorted;\n#endif\n\ntemplate<typename XprType>\nbool is_pointer_based_stl_iterator(const internal::pointer_based_stl_iterator<XprType> &) { return true; }\n\ntemplate<typename XprType>\nbool is_generic_randaccess_stl_iterator(const internal::generic_randaccess_stl_iterator<XprType> &) { return true; }\n\ntemplate<typename Iter>\nbool is_default_constructible_and_assignable(const Iter& it)\n{\n#if EIGEN_HAS_CXX11\n  VERIFY(std::is_default_constructible<Iter>::value);\n  VERIFY(std::is_nothrow_default_constructible<Iter>::value);\n#endif\n  Iter it2;\n  it2 = it;\n  return (it==it2);\n}\n\ntemplate<typename Xpr>\nvoid check_begin_end_for_loop(Xpr xpr)\n{\n  const Xpr& cxpr(xpr);\n  Index i = 0;\n\n  i = 0;\n  for(typename Xpr::iterator it = xpr.begin(); it!=xpr.end(); ++it) { VERIFY_IS_EQUAL(*it,xpr[i++]); }\n\n  i = 0;\n  for(typename Xpr::const_iterator it = xpr.cbegin(); it!=xpr.cend(); ++it) { VERIFY_IS_EQUAL(*it,xpr[i++]); }\n\n  i = 0;\n  for(typename Xpr::const_iterator it = cxpr.begin(); it!=cxpr.end(); ++it) { VERIFY_IS_EQUAL(*it,xpr[i++]); }\n\n  i = 0;\n  for(typename Xpr::const_iterator it = xpr.begin(); it!=xpr.end(); ++it) { VERIFY_IS_EQUAL(*it,xpr[i++]); }\n\n  {\n    // simple API check\n    typename Xpr::const_iterator cit = xpr.begin();\n    cit = xpr.cbegin();\n\n    #if EIGEN_HAS_CXX11\n    auto tmp1 = xpr.begin();\n    VERIFY(tmp1==xpr.begin());\n    auto tmp2 = xpr.cbegin();\n    VERIFY(tmp2==xpr.cbegin());\n    #endif\n  }\n\n  VERIFY( xpr.end() -xpr.begin()  == xpr.size() );\n  VERIFY( xpr.cend()-xpr.begin()  == xpr.size() );\n  VERIFY( xpr.end() -xpr.cbegin() == xpr.size() );\n  VERIFY( xpr.cend()-xpr.cbegin() == xpr.size() );\n\n  if(xpr.size()>0) {\n    VERIFY(xpr.begin() != xpr.end());\n    VERIFY(xpr.begin() < xpr.end());\n    VERIFY(xpr.begin() <= xpr.end());\n    VERIFY(!(xpr.begin() == xpr.end()));\n    VERIFY(!(xpr.begin() > xpr.end()));\n    VERIFY(!(xpr.begin() >= xpr.end()));\n    \n    VERIFY(xpr.cbegin() != xpr.end());\n    VERIFY(xpr.cbegin() < xpr.end());\n    VERIFY(xpr.cbegin() <= xpr.end());\n    VERIFY(!(xpr.cbegin() == xpr.end()));\n    VERIFY(!(xpr.cbegin() > xpr.end()));\n    VERIFY(!(xpr.cbegin() >= xpr.end()));\n\n    VERIFY(xpr.begin() != xpr.cend());\n    VERIFY(xpr.begin() < xpr.cend());\n    VERIFY(xpr.begin() <= xpr.cend());\n    VERIFY(!(xpr.begin() == xpr.cend()));\n    VERIFY(!(xpr.begin() > xpr.cend()));\n    VERIFY(!(xpr.begin() >= xpr.cend()));\n  }\n}\n\ntemplate<typename Scalar, int Rows, int Cols>\nvoid test_stl_iterators(int rows=Rows, int cols=Cols)\n{\n  typedef Matrix<Scalar,Rows,1> VectorType;\n  #if EIGEN_HAS_CXX11\n  typedef Matrix<Scalar,1,Cols> RowVectorType;\n  #endif\n  typedef Matrix<Scalar,Rows,Cols,ColMajor> ColMatrixType;\n  typedef Matrix<Scalar,Rows,Cols,RowMajor> RowMatrixType;\n  VectorType v = VectorType::Random(rows);\n  const VectorType& cv(v);\n  ColMatrixType A = ColMatrixType::Random(rows,cols);\n  const ColMatrixType& cA(A);\n  RowMatrixType B = RowMatrixType::Random(rows,cols);\n  \n  Index i, j;\n\n  // Verify that iterators are default constructible (See bug #1900)\n  {\n    VERIFY( is_default_constructible_and_assignable(v.begin()));\n    VERIFY( is_default_constructible_and_assignable(v.end()));\n    VERIFY( is_default_constructible_and_assignable(cv.begin()));\n    VERIFY( is_default_constructible_and_assignable(cv.end()));\n\n    VERIFY( is_default_constructible_and_assignable(A.row(0).begin()));\n    VERIFY( is_default_constructible_and_assignable(A.row(0).end()));\n    VERIFY( is_default_constructible_and_assignable(cA.row(0).begin()));\n    VERIFY( is_default_constructible_and_assignable(cA.row(0).end()));\n\n    VERIFY( is_default_constructible_and_assignable(B.row(0).begin()));\n    VERIFY( is_default_constructible_and_assignable(B.row(0).end()));\n  }\n\n  // Check we got a fast pointer-based iterator when expected\n  {\n    VERIFY( is_pointer_based_stl_iterator(v.begin()) );\n    VERIFY( is_pointer_based_stl_iterator(v.end()) );\n    VERIFY( is_pointer_based_stl_iterator(cv.begin()) );\n    VERIFY( is_pointer_based_stl_iterator(cv.end()) );\n\n    j = internal::random<Index>(0,A.cols()-1);\n    VERIFY( is_pointer_based_stl_iterator(A.col(j).begin()) );\n    VERIFY( is_pointer_based_stl_iterator(A.col(j).end()) );\n    VERIFY( is_pointer_based_stl_iterator(cA.col(j).begin()) );\n    VERIFY( is_pointer_based_stl_iterator(cA.col(j).end()) );\n\n    i = internal::random<Index>(0,A.rows()-1);\n    VERIFY( is_pointer_based_stl_iterator(A.row(i).begin()) );\n    VERIFY( is_pointer_based_stl_iterator(A.row(i).end()) );\n    VERIFY( is_pointer_based_stl_iterator(cA.row(i).begin()) );\n    VERIFY( is_pointer_based_stl_iterator(cA.row(i).end()) );\n\n    VERIFY( is_pointer_based_stl_iterator(A.reshaped().begin()) );\n    VERIFY( is_pointer_based_stl_iterator(A.reshaped().end()) );\n    VERIFY( is_pointer_based_stl_iterator(cA.reshaped().begin()) );\n    VERIFY( is_pointer_based_stl_iterator(cA.reshaped().end()) );\n\n    VERIFY( is_pointer_based_stl_iterator(B.template reshaped<AutoOrder>().begin()) );\n    VERIFY( is_pointer_based_stl_iterator(B.template reshaped<AutoOrder>().end()) );\n\n    VERIFY( is_generic_randaccess_stl_iterator(A.template reshaped<RowMajor>().begin()) );\n    VERIFY( is_generic_randaccess_stl_iterator(A.template reshaped<RowMajor>().end()) );\n  }\n\n  {\n    check_begin_end_for_loop(v);\n    check_begin_end_for_loop(A.col(internal::random<Index>(0,A.cols()-1)));\n    check_begin_end_for_loop(A.row(internal::random<Index>(0,A.rows()-1)));\n    check_begin_end_for_loop(v+v);\n  }\n\n#if EIGEN_HAS_CXX11\n  // check swappable\n  {\n    using std::swap;\n    // pointer-based\n    {\n      VectorType v_copy = v;\n      auto a = v.begin();\n      auto b = v.end()-1;\n      swap(a,b);\n      VERIFY_IS_EQUAL(v,v_copy);\n      VERIFY_IS_EQUAL(*b,*v.begin());\n      VERIFY_IS_EQUAL(*b,v(0));\n      VERIFY_IS_EQUAL(*a,v.end()[-1]);\n      VERIFY_IS_EQUAL(*a,v(last));\n    }\n\n    // generic\n    {\n      RowMatrixType B_copy = B;\n      auto Br = B.reshaped();\n      auto a = Br.begin();\n      auto b = Br.end()-1;\n      swap(a,b);\n      VERIFY_IS_EQUAL(B,B_copy);\n      VERIFY_IS_EQUAL(*b,*Br.begin());\n      VERIFY_IS_EQUAL(*b,Br(0));\n      VERIFY_IS_EQUAL(*a,Br.end()[-1]);\n      VERIFY_IS_EQUAL(*a,Br(last));\n    }\n  }\n\n  // check non-const iterator with for-range loops\n  {\n    i = 0;\n    for(auto x : v) { VERIFY_IS_EQUAL(x,v[i++]); }\n\n    j = internal::random<Index>(0,A.cols()-1);\n    i = 0;\n    for(auto x : A.col(j)) { VERIFY_IS_EQUAL(x,A(i++,j)); }\n\n    i = 0;\n    for(auto x : (v+A.col(j))) { VERIFY_IS_APPROX(x,v(i)+A(i,j)); ++i; }\n\n    j = 0;\n    i = internal::random<Index>(0,A.rows()-1);\n    for(auto x : A.row(i)) { VERIFY_IS_EQUAL(x,A(i,j++)); }\n\n    i = 0;\n    for(auto x : A.reshaped()) { VERIFY_IS_EQUAL(x,A(i++)); }\n  }\n\n  // same for const_iterator\n  {\n    i = 0;\n    for(auto x : cv) { VERIFY_IS_EQUAL(x,v[i++]); }\n\n    i = 0;\n    for(auto x : cA.reshaped()) { VERIFY_IS_EQUAL(x,A(i++)); }\n\n    j = 0;\n    i = internal::random<Index>(0,A.rows()-1);\n    for(auto x : cA.row(i)) { VERIFY_IS_EQUAL(x,A(i,j++)); }\n  }\n\n  // check reshaped() on row-major\n  {\n    i = 0;\n    Matrix<Scalar,Dynamic,Dynamic,ColMajor> Bc = B;\n    for(auto x : B.reshaped()) { VERIFY_IS_EQUAL(x,Bc(i++)); }\n  }\n\n  // check write access\n  {\n    VectorType w(v.size());\n    i = 0;\n    for(auto& x : w) { x = v(i++); }\n    VERIFY_IS_EQUAL(v,w);\n  }\n\n  // check for dangling pointers\n  {\n    // no dangling because pointer-based\n    {\n      j = internal::random<Index>(0,A.cols()-1);\n      auto it = A.col(j).begin();\n      for(i=0;i<rows;++i) {\n        VERIFY_IS_EQUAL(it[i],A(i,j));\n      }\n    }\n\n    // no dangling because pointer-based\n    {\n      i = internal::random<Index>(0,A.rows()-1);\n      auto it = A.row(i).begin();\n      for(j=0;j<cols;++j) { VERIFY_IS_EQUAL(it[j],A(i,j)); }\n    }\n\n    {\n      j = internal::random<Index>(0,A.cols()-1);\n      // this would produce a dangling pointer:\n      // auto it = (A+2*A).col(j).begin(); \n      // we need to name the temporary expression:\n      auto tmp = (A+2*A).col(j);\n      auto it = tmp.begin();\n      for(i=0;i<rows;++i) {\n        VERIFY_IS_APPROX(it[i],3*A(i,j));\n      }\n    }\n  }\n\n  {\n    // check basic for loop on vector-wise iterators\n    j=0;\n    for (auto it = A.colwise().cbegin(); it != A.colwise().cend(); ++it, ++j) {\n      VERIFY_IS_APPROX( it->coeff(0), A(0,j) );\n      VERIFY_IS_APPROX( (*it).coeff(0), A(0,j) );\n    }\n    j=0;\n    for (auto it = A.colwise().begin(); it != A.colwise().end(); ++it, ++j) {\n      (*it).coeffRef(0) = (*it).coeff(0); // compilation check\n      it->coeffRef(0) = it->coeff(0);     // compilation check\n      VERIFY_IS_APPROX( it->coeff(0), A(0,j) );\n      VERIFY_IS_APPROX( (*it).coeff(0), A(0,j) );\n    }\n\n    // check valuetype gives us a copy\n    j=0;\n    for (auto it = A.colwise().cbegin(); it != A.colwise().cend(); ++it, ++j) {\n      typename decltype(it)::value_type tmp = *it;\n      VERIFY_IS_NOT_EQUAL( tmp.data() , it->data() );\n      VERIFY_IS_APPROX( tmp, A.col(j) );\n    }\n  }\n\n#endif\n\n  if(rows>=3) {\n    VERIFY_IS_EQUAL((v.begin()+rows/2)[1], v(rows/2+1));\n\n    VERIFY_IS_EQUAL((A.rowwise().begin()+rows/2)[1], A.row(rows/2+1));\n  }\n\n  if(cols>=3) {\n    VERIFY_IS_EQUAL((A.colwise().begin()+cols/2)[1], A.col(cols/2+1));\n  }\n\n  // check std::sort\n  {\n    // first check that is_sorted returns false when required\n    if(rows>=2)\n    {\n      v(1) = v(0)-Scalar(1);\n      #if EIGEN_HAS_CXX11\n      VERIFY(!is_sorted(std::begin(v),std::end(v)));\n      #else\n      VERIFY(!is_sorted(v.cbegin(),v.cend()));\n      #endif\n    }\n\n    // on a vector\n    {\n      std::sort(v.begin(),v.end());\n      VERIFY(is_sorted(v.begin(),v.end()));\n      VERIFY(!::is_sorted(make_reverse_iterator(v.end()),make_reverse_iterator(v.begin())));\n    }\n\n    // on a column of a column-major matrix -> pointer-based iterator and default increment\n    {\n      j = internal::random<Index>(0,A.cols()-1);\n      // std::sort(begin(A.col(j)),end(A.col(j))); // does not compile because this returns const iterators\n      typename ColMatrixType::ColXpr Acol = A.col(j);\n      std::sort(Acol.begin(),Acol.end());\n      VERIFY(is_sorted(Acol.cbegin(),Acol.cend()));\n      A.setRandom();\n\n      std::sort(A.col(j).begin(),A.col(j).end());\n      VERIFY(is_sorted(A.col(j).cbegin(),A.col(j).cend()));\n      A.setRandom();\n    }\n\n    // on a row of a rowmajor matrix -> pointer-based iterator and runtime increment\n    {\n      i = internal::random<Index>(0,A.rows()-1);\n      typename ColMatrixType::RowXpr Arow = A.row(i);\n      VERIFY_IS_EQUAL( std::distance(Arow.begin(),Arow.end()), cols);\n      std::sort(Arow.begin(),Arow.end());\n      VERIFY(is_sorted(Arow.cbegin(),Arow.cend()));\n      A.setRandom();\n\n      std::sort(A.row(i).begin(),A.row(i).end());\n      VERIFY(is_sorted(A.row(i).cbegin(),A.row(i).cend()));\n      A.setRandom();\n    }\n\n    // with a generic iterator\n    {\n      Reshaped<RowMatrixType,RowMatrixType::SizeAtCompileTime,1> B1 = B.reshaped();\n      std::sort(B1.begin(),B1.end());\n      VERIFY(is_sorted(B1.cbegin(),B1.cend()));\n      B.setRandom();\n\n      // assertion because nested expressions are different\n      // std::sort(B.reshaped().begin(),B.reshaped().end());\n      // VERIFY(is_sorted(B.reshaped().cbegin(),B.reshaped().cend()));\n      // B.setRandom();\n    }\n  }\n\n  // check with partial_sum\n  {\n    j = internal::random<Index>(0,A.cols()-1);\n    typename ColMatrixType::ColXpr Acol = A.col(j);\n    std::partial_sum(Acol.begin(), Acol.end(), v.begin());\n    VERIFY_IS_APPROX(v(seq(1,last)), v(seq(0,last-1))+Acol(seq(1,last)));\n\n    // inplace\n    std::partial_sum(Acol.begin(), Acol.end(), Acol.begin());\n    VERIFY_IS_APPROX(v, Acol);\n  }\n\n  // stress random access as required by std::nth_element\n  if(rows>=3)\n  {\n    v.setRandom();\n    VectorType v1 = v;\n    std::sort(v1.begin(),v1.end());\n    std::nth_element(v.begin(), v.begin()+rows/2, v.end());\n    VERIFY_IS_APPROX(v1(rows/2), v(rows/2));\n\n    v.setRandom();\n    v1 = v;\n    std::sort(v1.begin()+rows/2,v1.end());\n    std::nth_element(v.begin()+rows/2, v.begin()+rows/4, v.end());\n    VERIFY_IS_APPROX(v1(rows/4), v(rows/4));\n  }\n\n#if EIGEN_HAS_CXX11\n  // check rows/cols iterators with range-for loops\n  {\n    j = 0;\n    for(auto c : A.colwise()) { VERIFY_IS_APPROX(c.sum(), A.col(j).sum()); ++j; }\n    j = 0;\n    for(auto c : B.colwise()) { VERIFY_IS_APPROX(c.sum(), B.col(j).sum()); ++j; }\n\n    j = 0;\n    for(auto c : B.colwise()) {\n      i = 0;\n      for(auto& x : c) {\n        VERIFY_IS_EQUAL(x, B(i,j));\n        x = A(i,j);\n        ++i;\n      }\n      ++j;\n    }\n    VERIFY_IS_APPROX(A,B);\n    B.setRandom();\n    \n    i = 0;\n    for(auto r : A.rowwise()) { VERIFY_IS_APPROX(r.sum(), A.row(i).sum()); ++i; }\n    i = 0;\n    for(auto r : B.rowwise()) { VERIFY_IS_APPROX(r.sum(), B.row(i).sum()); ++i; }\n  }\n\n\n  // check rows/cols iterators with STL algorithms\n  {\n    RowVectorType row = RowVectorType::Random(cols);\n    A.rowwise() = row;\n    VERIFY( std::all_of(A.rowwise().begin(),  A.rowwise().end(),  [&row](typename ColMatrixType::RowXpr x) { return internal::isApprox(x.squaredNorm(),row.squaredNorm()); }) );\n    VERIFY( std::all_of(A.rowwise().rbegin(), A.rowwise().rend(), [&row](typename ColMatrixType::RowXpr x) { return internal::isApprox(x.squaredNorm(),row.squaredNorm()); }) );\n\n    VectorType col = VectorType::Random(rows);\n    A.colwise() = col;\n    VERIFY( std::all_of(A.colwise().begin(),   A.colwise().end(),   [&col](typename ColMatrixType::ColXpr x) { return internal::isApprox(x.squaredNorm(),col.squaredNorm()); }) );\n    VERIFY( std::all_of(A.colwise().rbegin(),  A.colwise().rend(),  [&col](typename ColMatrixType::ColXpr x) { return internal::isApprox(x.squaredNorm(),col.squaredNorm()); }) );\n    VERIFY( std::all_of(A.colwise().cbegin(),  A.colwise().cend(),  [&col](typename ColMatrixType::ConstColXpr x) { return internal::isApprox(x.squaredNorm(),col.squaredNorm()); }) );\n    VERIFY( std::all_of(A.colwise().crbegin(), A.colwise().crend(), [&col](typename ColMatrixType::ConstColXpr x) { return internal::isApprox(x.squaredNorm(),col.squaredNorm()); }) );\n\n    i = internal::random<Index>(0,A.rows()-1);\n    A.setRandom();\n    A.row(i).setZero();\n    VERIFY_IS_EQUAL( std::find_if(A.rowwise().begin(),  A.rowwise().end(),  [](typename ColMatrixType::RowXpr x) { return x.squaredNorm() == Scalar(0); })-A.rowwise().begin(),  i );\n    VERIFY_IS_EQUAL( std::find_if(A.rowwise().rbegin(), A.rowwise().rend(), [](typename ColMatrixType::RowXpr x) { return x.squaredNorm() == Scalar(0); })-A.rowwise().rbegin(), (A.rows()-1) - i );\n\n    j = internal::random<Index>(0,A.cols()-1);\n    A.setRandom();\n    A.col(j).setZero();\n    VERIFY_IS_EQUAL( std::find_if(A.colwise().begin(),  A.colwise().end(),  [](typename ColMatrixType::ColXpr x) { return x.squaredNorm() == Scalar(0); })-A.colwise().begin(),  j );\n    VERIFY_IS_EQUAL( std::find_if(A.colwise().rbegin(), A.colwise().rend(), [](typename ColMatrixType::ColXpr x) { return x.squaredNorm() == Scalar(0); })-A.colwise().rbegin(), (A.cols()-1) - j );\n  }\n\n  {\n    using VecOp = VectorwiseOp<ArrayXXi, 0>;\n    STATIC_CHECK(( internal::is_same<VecOp::const_iterator, decltype(std::declval<const VecOp&>().cbegin())>::value ));\n    STATIC_CHECK(( internal::is_same<VecOp::const_iterator, decltype(std::declval<const VecOp&>().cend  ())>::value ));\n    #if EIGEN_COMP_CXXVER>=14\n      STATIC_CHECK(( internal::is_same<VecOp::const_iterator, decltype(std::cbegin(std::declval<const VecOp&>()))>::value ));\n      STATIC_CHECK(( internal::is_same<VecOp::const_iterator, decltype(std::cend  (std::declval<const VecOp&>()))>::value ));\n    #endif\n  }\n\n#endif\n}\n\n\n#if EIGEN_HAS_CXX11\n// When the compiler sees expression IsContainerTest<C>(0), if C is an\n// STL-style container class, the first overload of IsContainerTest\n// will be viable (since both C::iterator* and C::const_iterator* are\n// valid types and NULL can be implicitly converted to them).  It will\n// be picked over the second overload as 'int' is a perfect match for\n// the type of argument 0.  If C::iterator or C::const_iterator is not\n// a valid type, the first overload is not viable, and the second\n// overload will be picked.\ntemplate <class C,\n          class Iterator = decltype(::std::declval<const C&>().begin()),\n          class = decltype(::std::declval<const C&>().end()),\n          class = decltype(++::std::declval<Iterator&>()),\n          class = decltype(*::std::declval<Iterator>()),\n          class = typename C::const_iterator>\nbool IsContainerType(int /* dummy */) { return true; }\n\ntemplate <class C>\nbool IsContainerType(long /* dummy */) { return false; }\n\ntemplate <typename Scalar, int Rows, int Cols>\nvoid test_stl_container_detection(int rows=Rows, int cols=Cols)\n{\n  typedef Matrix<Scalar,Rows,1> VectorType;\n  typedef Matrix<Scalar,Rows,Cols,ColMajor> ColMatrixType;\n  typedef Matrix<Scalar,Rows,Cols,RowMajor> RowMatrixType;\n\n  ColMatrixType A = ColMatrixType::Random(rows, cols);\n  RowMatrixType B = RowMatrixType::Random(rows, cols);\n\n  Index i = 1;\n\n  using ColMatrixColType = decltype(A.col(i));\n  using ColMatrixRowType = decltype(A.row(i));\n  using RowMatrixColType = decltype(B.col(i));\n  using RowMatrixRowType = decltype(B.row(i));\n\n  // Vector and matrix col/row are valid Stl-style container.\n  VERIFY_IS_EQUAL(IsContainerType<VectorType>(0), true);\n  VERIFY_IS_EQUAL(IsContainerType<ColMatrixColType>(0), true);\n  VERIFY_IS_EQUAL(IsContainerType<ColMatrixRowType>(0), true);\n  VERIFY_IS_EQUAL(IsContainerType<RowMatrixColType>(0), true);\n  VERIFY_IS_EQUAL(IsContainerType<RowMatrixRowType>(0), true);\n\n  // But the matrix itself is not a valid Stl-style container.\n  VERIFY_IS_EQUAL(IsContainerType<ColMatrixType>(0), rows == 1 || cols == 1);\n  VERIFY_IS_EQUAL(IsContainerType<RowMatrixType>(0), rows == 1 || cols == 1);\n}\n#endif\n\nEIGEN_DECLARE_TEST(stl_iterators)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(( test_stl_iterators<double,2,3>() ));\n    CALL_SUBTEST_1(( test_stl_iterators<float,7,5>() ));\n    CALL_SUBTEST_1(( test_stl_iterators<int,Dynamic,Dynamic>(internal::random<int>(5,10), internal::random<int>(5,10)) ));\n    CALL_SUBTEST_1(( test_stl_iterators<int,Dynamic,Dynamic>(internal::random<int>(10,200), internal::random<int>(10,200)) ));\n  }\n  \n#if EIGEN_HAS_CXX11\n  CALL_SUBTEST_1(( test_stl_container_detection<float,1,1>() ));\n  CALL_SUBTEST_1(( test_stl_container_detection<float,5,5>() ));\n#endif  \n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/superlu_support.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS\n#include \"sparse_solver.h\"\n\n#include <Eigen/SuperLUSupport>\n\nEIGEN_DECLARE_TEST(superlu_support)\n{\n  SuperLU<SparseMatrix<double> > superlu_double_colmajor;\n  SuperLU<SparseMatrix<std::complex<double> > > superlu_cplxdouble_colmajor;\n  CALL_SUBTEST_1( check_sparse_square_solving(superlu_double_colmajor)      );\n  CALL_SUBTEST_2( check_sparse_square_solving(superlu_cplxdouble_colmajor)  );\n  CALL_SUBTEST_1( check_sparse_square_determinant(superlu_double_colmajor)      );\n  CALL_SUBTEST_2( check_sparse_square_determinant(superlu_cplxdouble_colmajor)  );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/svd_common.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef SVD_DEFAULT\n#error a macro SVD_DEFAULT(MatrixType) must be defined prior to including svd_common.h\n#endif\n\n#ifndef SVD_FOR_MIN_NORM\n#error a macro SVD_FOR_MIN_NORM(MatrixType) must be defined prior to including svd_common.h\n#endif\n\n#include \"svd_fill.h\"\n#include \"solverbase.h\"\n\n// Check that the matrix m is properly reconstructed and that the U and V factors are unitary\n// The SVD must have already been computed.\ntemplate<typename SvdType, typename MatrixType>\nvoid svd_check_full(const MatrixType& m, const SvdType& svd)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  enum {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime\n  };\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef Matrix<Scalar, RowsAtCompileTime, RowsAtCompileTime> MatrixUType;\n  typedef Matrix<Scalar, ColsAtCompileTime, ColsAtCompileTime> MatrixVType;\n\n  MatrixType sigma = MatrixType::Zero(rows,cols);\n  sigma.diagonal() = svd.singularValues().template cast<Scalar>();\n  MatrixUType u = svd.matrixU();\n  MatrixVType v = svd.matrixV();\n  RealScalar scaling = m.cwiseAbs().maxCoeff();\n  if(scaling<(std::numeric_limits<RealScalar>::min)())\n  {\n    VERIFY(sigma.cwiseAbs().maxCoeff() <= (std::numeric_limits<RealScalar>::min)());\n  }\n  else\n  {\n    VERIFY_IS_APPROX(m/scaling, u * (sigma/scaling) * v.adjoint());\n  }\n  VERIFY_IS_UNITARY(u);\n  VERIFY_IS_UNITARY(v);\n}\n\n// Compare partial SVD defined by computationOptions to a full SVD referenceSvd\ntemplate<typename SvdType, typename MatrixType>\nvoid svd_compare_to_full(const MatrixType& m,\n                         unsigned int computationOptions,\n                         const SvdType& referenceSvd)\n{\n  typedef typename MatrixType::RealScalar RealScalar;\n  Index rows = m.rows();\n  Index cols = m.cols();\n  Index diagSize = (std::min)(rows, cols);\n  RealScalar prec = test_precision<RealScalar>();\n\n  SvdType svd(m, computationOptions);\n\n  VERIFY_IS_APPROX(svd.singularValues(), referenceSvd.singularValues());\n  \n  if(computationOptions & (ComputeFullV|ComputeThinV))\n  {\n    VERIFY( (svd.matrixV().adjoint()*svd.matrixV()).isIdentity(prec) );\n    VERIFY_IS_APPROX( svd.matrixV().leftCols(diagSize) * svd.singularValues().asDiagonal() * svd.matrixV().leftCols(diagSize).adjoint(),\n                      referenceSvd.matrixV().leftCols(diagSize) * referenceSvd.singularValues().asDiagonal() * referenceSvd.matrixV().leftCols(diagSize).adjoint());\n  }\n  \n  if(computationOptions & (ComputeFullU|ComputeThinU))\n  {\n    VERIFY( (svd.matrixU().adjoint()*svd.matrixU()).isIdentity(prec) );\n    VERIFY_IS_APPROX( svd.matrixU().leftCols(diagSize) * svd.singularValues().cwiseAbs2().asDiagonal() * svd.matrixU().leftCols(diagSize).adjoint(),\n                      referenceSvd.matrixU().leftCols(diagSize) * referenceSvd.singularValues().cwiseAbs2().asDiagonal() * referenceSvd.matrixU().leftCols(diagSize).adjoint());\n  }\n  \n  // The following checks are not critical.\n  // For instance, with Dived&Conquer SVD, if only the factor 'V' is computedt then different matrix-matrix product implementation will be used\n  // and the resulting 'V' factor might be significantly different when the SVD decomposition is not unique, especially with single precision float.\n  ++g_test_level;\n  if(computationOptions & ComputeFullU)  VERIFY_IS_APPROX(svd.matrixU(), referenceSvd.matrixU());\n  if(computationOptions & ComputeThinU)  VERIFY_IS_APPROX(svd.matrixU(), referenceSvd.matrixU().leftCols(diagSize));\n  if(computationOptions & ComputeFullV)  VERIFY_IS_APPROX(svd.matrixV().cwiseAbs(), referenceSvd.matrixV().cwiseAbs());\n  if(computationOptions & ComputeThinV)  VERIFY_IS_APPROX(svd.matrixV(), referenceSvd.matrixV().leftCols(diagSize));\n  --g_test_level;\n}\n\n//\ntemplate<typename SvdType, typename MatrixType>\nvoid svd_least_square(const MatrixType& m, unsigned int computationOptions)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  enum {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime\n  };\n\n  typedef Matrix<Scalar, RowsAtCompileTime, Dynamic> RhsType;\n  typedef Matrix<Scalar, ColsAtCompileTime, Dynamic> SolutionType;\n\n  RhsType rhs = RhsType::Random(rows, internal::random<Index>(1, cols));\n  SvdType svd(m, computationOptions);\n\n       if(internal::is_same<RealScalar,double>::value) svd.setThreshold(1e-8);\n  else if(internal::is_same<RealScalar,float>::value)  svd.setThreshold(2e-4);\n\n  SolutionType x = svd.solve(rhs);\n   \n  RealScalar residual = (m*x-rhs).norm();\n  RealScalar rhs_norm = rhs.norm();\n  if(!test_isMuchSmallerThan(residual,rhs.norm()))\n  {\n    // ^^^ If the residual is very small, then we have an exact solution, so we are already good.\n    \n    // evaluate normal equation which works also for least-squares solutions\n    if(internal::is_same<RealScalar,double>::value || svd.rank()==m.diagonal().size())\n    {\n      using std::sqrt;\n      // This test is not stable with single precision.\n      // This is probably because squaring m signicantly affects the precision.      \n      if(internal::is_same<RealScalar,float>::value) ++g_test_level;\n      \n      VERIFY_IS_APPROX(m.adjoint()*(m*x),m.adjoint()*rhs);\n      \n      if(internal::is_same<RealScalar,float>::value) --g_test_level;\n    }\n    \n    // Check that there is no significantly better solution in the neighborhood of x\n    for(Index k=0;k<x.rows();++k)\n    {\n      using std::abs;\n      \n      SolutionType y(x);\n      y.row(k) = (RealScalar(1)+2*NumTraits<RealScalar>::epsilon())*x.row(k);\n      RealScalar residual_y = (m*y-rhs).norm();\n      VERIFY( test_isMuchSmallerThan(abs(residual_y-residual), rhs_norm) || residual < residual_y );\n      if(internal::is_same<RealScalar,float>::value) ++g_test_level;\n      VERIFY( test_isApprox(residual_y,residual) || residual < residual_y );\n      if(internal::is_same<RealScalar,float>::value) --g_test_level;\n      \n      y.row(k) = (RealScalar(1)-2*NumTraits<RealScalar>::epsilon())*x.row(k);\n      residual_y = (m*y-rhs).norm();\n      VERIFY( test_isMuchSmallerThan(abs(residual_y-residual), rhs_norm) || residual < residual_y );\n      if(internal::is_same<RealScalar,float>::value) ++g_test_level;\n      VERIFY( test_isApprox(residual_y,residual) || residual < residual_y );\n      if(internal::is_same<RealScalar,float>::value) --g_test_level;\n    }\n  }\n}\n\n// check minimal norm solutions, the inoput matrix m is only used to recover problem size\ntemplate<typename MatrixType>\nvoid svd_min_norm(const MatrixType& m, unsigned int computationOptions)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  Index cols = m.cols();\n\n  enum {\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime\n  };\n\n  typedef Matrix<Scalar, ColsAtCompileTime, Dynamic> SolutionType;\n\n  // generate a full-rank m x n problem with m<n\n  enum {\n    RankAtCompileTime2 = ColsAtCompileTime==Dynamic ? Dynamic : (ColsAtCompileTime)/2+1,\n    RowsAtCompileTime3 = ColsAtCompileTime==Dynamic ? Dynamic : ColsAtCompileTime+1\n  };\n  typedef Matrix<Scalar, RankAtCompileTime2, ColsAtCompileTime> MatrixType2;\n  typedef Matrix<Scalar, RankAtCompileTime2, 1> RhsType2;\n  typedef Matrix<Scalar, ColsAtCompileTime, RankAtCompileTime2> MatrixType2T;\n  Index rank = RankAtCompileTime2==Dynamic ? internal::random<Index>(1,cols) : Index(RankAtCompileTime2);\n  MatrixType2 m2(rank,cols);\n  int guard = 0;\n  do {\n    m2.setRandom();\n  } while(SVD_FOR_MIN_NORM(MatrixType2)(m2).setThreshold(test_precision<Scalar>()).rank()!=rank && (++guard)<10);\n  VERIFY(guard<10);\n\n  RhsType2 rhs2 = RhsType2::Random(rank);\n  // use QR to find a reference minimal norm solution\n  HouseholderQR<MatrixType2T> qr(m2.adjoint());\n  Matrix<Scalar,Dynamic,1> tmp = qr.matrixQR().topLeftCorner(rank,rank).template triangularView<Upper>().adjoint().solve(rhs2);\n  tmp.conservativeResize(cols);\n  tmp.tail(cols-rank).setZero();\n  SolutionType x21 = qr.householderQ() * tmp;\n  // now check with SVD\n  SVD_FOR_MIN_NORM(MatrixType2) svd2(m2, computationOptions);\n  SolutionType x22 = svd2.solve(rhs2);\n  VERIFY_IS_APPROX(m2*x21, rhs2);\n  VERIFY_IS_APPROX(m2*x22, rhs2);\n  VERIFY_IS_APPROX(x21, x22);\n\n  // Now check with a rank deficient matrix\n  typedef Matrix<Scalar, RowsAtCompileTime3, ColsAtCompileTime> MatrixType3;\n  typedef Matrix<Scalar, RowsAtCompileTime3, 1> RhsType3;\n  Index rows3 = RowsAtCompileTime3==Dynamic ? internal::random<Index>(rank+1,2*cols) : Index(RowsAtCompileTime3);\n  Matrix<Scalar,RowsAtCompileTime3,Dynamic> C = Matrix<Scalar,RowsAtCompileTime3,Dynamic>::Random(rows3,rank);\n  MatrixType3 m3 = C * m2;\n  RhsType3 rhs3 = C * rhs2;\n  SVD_FOR_MIN_NORM(MatrixType3) svd3(m3, computationOptions);\n  SolutionType x3 = svd3.solve(rhs3);\n  VERIFY_IS_APPROX(m3*x3, rhs3);\n  VERIFY_IS_APPROX(m3*x21, rhs3);\n  VERIFY_IS_APPROX(m2*x3, rhs2);\n  VERIFY_IS_APPROX(x21, x3);\n}\n\ntemplate<typename MatrixType, typename SolverType>\nvoid svd_test_solvers(const MatrixType& m, const SolverType& solver) {\n    Index rows, cols, cols2;\n\n    rows = m.rows();\n    cols = m.cols();\n\n    if(MatrixType::ColsAtCompileTime==Dynamic)\n    {\n      cols2 = internal::random<int>(2,EIGEN_TEST_MAX_SIZE);\n    }\n    else\n    {\n      cols2 = cols;\n    }\n    typedef Matrix<typename MatrixType::Scalar, MatrixType::ColsAtCompileTime, MatrixType::ColsAtCompileTime> CMatrixType;\n    check_solverbase<CMatrixType, MatrixType>(m, solver, rows, cols, cols2);\n}\n\n// Check full, compare_to_full, least_square, and min_norm for all possible compute-options\ntemplate<typename SvdType, typename MatrixType>\nvoid svd_test_all_computation_options(const MatrixType& m, bool full_only)\n{\n//   if (QRPreconditioner == NoQRPreconditioner && m.rows() != m.cols())\n//     return;\n  STATIC_CHECK(( internal::is_same<typename SvdType::StorageIndex,int>::value ));\n\n  SvdType fullSvd(m, ComputeFullU|ComputeFullV);\n  CALL_SUBTEST(( svd_check_full(m, fullSvd) ));\n  CALL_SUBTEST(( svd_least_square<SvdType>(m, ComputeFullU | ComputeFullV) ));\n  CALL_SUBTEST(( svd_min_norm(m, ComputeFullU | ComputeFullV) ));\n  \n  #if defined __INTEL_COMPILER\n  // remark #111: statement is unreachable\n  #pragma warning disable 111\n  #endif\n\n  svd_test_solvers(m, fullSvd);\n\n  if(full_only)\n    return;\n\n  CALL_SUBTEST(( svd_compare_to_full(m, ComputeFullU, fullSvd) ));\n  CALL_SUBTEST(( svd_compare_to_full(m, ComputeFullV, fullSvd) ));\n  CALL_SUBTEST(( svd_compare_to_full(m, 0, fullSvd) ));\n\n  if (MatrixType::ColsAtCompileTime == Dynamic) {\n    // thin U/V are only available with dynamic number of columns\n    CALL_SUBTEST(( svd_compare_to_full(m, ComputeFullU|ComputeThinV, fullSvd) ));\n    CALL_SUBTEST(( svd_compare_to_full(m,              ComputeThinV, fullSvd) ));\n    CALL_SUBTEST(( svd_compare_to_full(m, ComputeThinU|ComputeFullV, fullSvd) ));\n    CALL_SUBTEST(( svd_compare_to_full(m, ComputeThinU             , fullSvd) ));\n    CALL_SUBTEST(( svd_compare_to_full(m, ComputeThinU|ComputeThinV, fullSvd) ));\n    \n    CALL_SUBTEST(( svd_least_square<SvdType>(m, ComputeFullU | ComputeThinV) ));\n    CALL_SUBTEST(( svd_least_square<SvdType>(m, ComputeThinU | ComputeFullV) ));\n    CALL_SUBTEST(( svd_least_square<SvdType>(m, ComputeThinU | ComputeThinV) ));\n\n    CALL_SUBTEST(( svd_min_norm(m, ComputeFullU | ComputeThinV) ));\n    CALL_SUBTEST(( svd_min_norm(m, ComputeThinU | ComputeFullV) ));\n    CALL_SUBTEST(( svd_min_norm(m, ComputeThinU | ComputeThinV) ));\n\n    // test reconstruction\n    Index diagSize = (std::min)(m.rows(), m.cols());\n    SvdType svd(m, ComputeThinU | ComputeThinV);\n    VERIFY_IS_APPROX(m, svd.matrixU().leftCols(diagSize) * svd.singularValues().asDiagonal() * svd.matrixV().leftCols(diagSize).adjoint());\n  }\n}\n\n\n// work around stupid msvc error when constructing at compile time an expression that involves\n// a division by zero, even if the numeric type has floating point\ntemplate<typename Scalar>\nEIGEN_DONT_INLINE Scalar zero() { return Scalar(0); }\n\n// workaround aggressive optimization in ICC\ntemplate<typename T> EIGEN_DONT_INLINE  T sub(T a, T b) { return a - b; }\n\n// This function verifies we don't iterate infinitely on nan/inf values,\n// and that info() returns InvalidInput.\ntemplate<typename SvdType, typename MatrixType>\nvoid svd_inf_nan()\n{\n  SvdType svd;\n  typedef typename MatrixType::Scalar Scalar;\n  Scalar some_inf = Scalar(1) / zero<Scalar>();\n  VERIFY(sub(some_inf, some_inf) != sub(some_inf, some_inf));\n  svd.compute(MatrixType::Constant(10,10,some_inf), ComputeFullU | ComputeFullV);\n  VERIFY(svd.info() == InvalidInput);\n\n  Scalar nan = std::numeric_limits<Scalar>::quiet_NaN();\n  VERIFY(nan != nan);\n  svd.compute(MatrixType::Constant(10,10,nan), ComputeFullU | ComputeFullV);\n  VERIFY(svd.info() == InvalidInput);  \n\n  MatrixType m = MatrixType::Zero(10,10);\n  m(internal::random<int>(0,9), internal::random<int>(0,9)) = some_inf;\n  svd.compute(m, ComputeFullU | ComputeFullV);\n  VERIFY(svd.info() == InvalidInput);\n\n  m = MatrixType::Zero(10,10);\n  m(internal::random<int>(0,9), internal::random<int>(0,9)) = nan;\n  svd.compute(m, ComputeFullU | ComputeFullV);\n  VERIFY(svd.info() == InvalidInput);\n  \n  // regression test for bug 791\n  m.resize(3,3);\n  m << 0,    2*NumTraits<Scalar>::epsilon(),  0.5,\n       0,   -0.5,                             0,\n       nan,  0,                               0;\n  svd.compute(m, ComputeFullU | ComputeFullV);\n  VERIFY(svd.info() == InvalidInput);\n  \n  m.resize(4,4);\n  m <<  1, 0, 0, 0,\n        0, 3, 1, 2e-308,\n        1, 0, 1, nan,\n        0, nan, nan, 0;\n  svd.compute(m, ComputeFullU | ComputeFullV);\n  VERIFY(svd.info() == InvalidInput);\n}\n\n// Regression test for bug 286: JacobiSVD loops indefinitely with some\n// matrices containing denormal numbers.\ntemplate<typename>\nvoid svd_underoverflow()\n{\n#if defined __INTEL_COMPILER\n// shut up warning #239: floating point underflow\n#pragma warning push\n#pragma warning disable 239\n#endif\n  Matrix2d M;\n  M << -7.90884e-313, -4.94e-324,\n                 0, 5.60844e-313;\n  SVD_DEFAULT(Matrix2d) svd;\n  svd.compute(M,ComputeFullU|ComputeFullV);\n  CALL_SUBTEST( svd_check_full(M,svd) );\n  \n  // Check all 2x2 matrices made with the following coefficients:\n  VectorXd value_set(9);\n  value_set << 0, 1, -1, 5.60844e-313, -5.60844e-313, 4.94e-324, -4.94e-324, -4.94e-223, 4.94e-223;\n  Array4i id(0,0,0,0);\n  int k = 0;\n  do\n  {\n    M << value_set(id(0)), value_set(id(1)), value_set(id(2)), value_set(id(3));\n    svd.compute(M,ComputeFullU|ComputeFullV);\n    CALL_SUBTEST( svd_check_full(M,svd) );\n\n    id(k)++;\n    if(id(k)>=value_set.size())\n    {\n      while(k<3 && id(k)>=value_set.size()) id(++k)++;\n      id.head(k).setZero();\n      k=0;\n    }\n\n  } while((id<int(value_set.size())).all());\n  \n#if defined __INTEL_COMPILER\n#pragma warning pop\n#endif\n  \n  // Check for overflow:\n  Matrix3d M3;\n  M3 << 4.4331978442502944e+307, -5.8585363752028680e+307,  6.4527017443412964e+307,\n        3.7841695601406358e+307,  2.4331702789740617e+306, -3.5235707140272905e+307,\n       -8.7190887618028355e+307, -7.3453213709232193e+307, -2.4367363684472105e+307;\n\n  SVD_DEFAULT(Matrix3d) svd3;\n  svd3.compute(M3,ComputeFullU|ComputeFullV); // just check we don't loop indefinitely\n  CALL_SUBTEST( svd_check_full(M3,svd3) );\n}\n\n// void jacobisvd(const MatrixType& a = MatrixType(), bool pickrandom = true)\n\ntemplate<typename MatrixType>\nvoid svd_all_trivial_2x2( void (*cb)(const MatrixType&,bool) )\n{\n  MatrixType M;\n  VectorXd value_set(3);\n  value_set << 0, 1, -1;\n  Array4i id(0,0,0,0);\n  int k = 0;\n  do\n  {\n    M << value_set(id(0)), value_set(id(1)), value_set(id(2)), value_set(id(3));\n    \n    cb(M,false);\n    \n    id(k)++;\n    if(id(k)>=value_set.size())\n    {\n      while(k<3 && id(k)>=value_set.size()) id(++k)++;\n      id.head(k).setZero();\n      k=0;\n    }\n    \n  } while((id<int(value_set.size())).all());\n}\n\ntemplate<typename>\nvoid svd_preallocate()\n{\n  Vector3f v(3.f, 2.f, 1.f);\n  MatrixXf m = v.asDiagonal();\n\n  internal::set_is_malloc_allowed(false);\n  VERIFY_RAISES_ASSERT(VectorXf tmp(10);)\n  SVD_DEFAULT(MatrixXf) svd;\n  internal::set_is_malloc_allowed(true);\n  svd.compute(m);\n  VERIFY_IS_APPROX(svd.singularValues(), v);\n\n  SVD_DEFAULT(MatrixXf) svd2(3,3);\n  internal::set_is_malloc_allowed(false);\n  svd2.compute(m);\n  internal::set_is_malloc_allowed(true);\n  VERIFY_IS_APPROX(svd2.singularValues(), v);\n  VERIFY_RAISES_ASSERT(svd2.matrixU());\n  VERIFY_RAISES_ASSERT(svd2.matrixV());\n  svd2.compute(m, ComputeFullU | ComputeFullV);\n  VERIFY_IS_APPROX(svd2.matrixU(), Matrix3f::Identity());\n  VERIFY_IS_APPROX(svd2.matrixV(), Matrix3f::Identity());\n  internal::set_is_malloc_allowed(false);\n  svd2.compute(m);\n  internal::set_is_malloc_allowed(true);\n\n  SVD_DEFAULT(MatrixXf) svd3(3,3,ComputeFullU|ComputeFullV);\n  internal::set_is_malloc_allowed(false);\n  svd2.compute(m);\n  internal::set_is_malloc_allowed(true);\n  VERIFY_IS_APPROX(svd2.singularValues(), v);\n  VERIFY_IS_APPROX(svd2.matrixU(), Matrix3f::Identity());\n  VERIFY_IS_APPROX(svd2.matrixV(), Matrix3f::Identity());\n  internal::set_is_malloc_allowed(false);\n  svd2.compute(m, ComputeFullU|ComputeFullV);\n  internal::set_is_malloc_allowed(true);\n}\n\ntemplate<typename SvdType,typename MatrixType> \nvoid svd_verify_assert(const MatrixType& m, bool fullOnly = false)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  enum {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime\n  };\n\n  typedef Matrix<Scalar, RowsAtCompileTime, 1> RhsType;\n  RhsType rhs(rows);\n  SvdType svd;\n  VERIFY_RAISES_ASSERT(svd.matrixU())\n  VERIFY_RAISES_ASSERT(svd.singularValues())\n  VERIFY_RAISES_ASSERT(svd.matrixV())\n  VERIFY_RAISES_ASSERT(svd.solve(rhs))\n  VERIFY_RAISES_ASSERT(svd.transpose().solve(rhs))\n  VERIFY_RAISES_ASSERT(svd.adjoint().solve(rhs))\n  MatrixType a = MatrixType::Zero(rows, cols);\n  a.setZero();\n  svd.compute(a, 0);\n  VERIFY_RAISES_ASSERT(svd.matrixU())\n  VERIFY_RAISES_ASSERT(svd.matrixV())\n  svd.singularValues();\n  VERIFY_RAISES_ASSERT(svd.solve(rhs))\n\n  svd.compute(a, ComputeFullU);\n  svd.matrixU();\n  VERIFY_RAISES_ASSERT(svd.matrixV())\n  VERIFY_RAISES_ASSERT(svd.solve(rhs))\n  svd.compute(a, ComputeFullV);\n  svd.matrixV();\n  VERIFY_RAISES_ASSERT(svd.matrixU())\n  VERIFY_RAISES_ASSERT(svd.solve(rhs))\n\n  if (!fullOnly && ColsAtCompileTime == Dynamic)\n  {\n    svd.compute(a, ComputeThinU);\n    svd.matrixU();\n    VERIFY_RAISES_ASSERT(svd.matrixV())\n    VERIFY_RAISES_ASSERT(svd.solve(rhs))\n    svd.compute(a, ComputeThinV);\n    svd.matrixV();\n    VERIFY_RAISES_ASSERT(svd.matrixU())\n    VERIFY_RAISES_ASSERT(svd.solve(rhs))\n  }\n  else\n  {\n    VERIFY_RAISES_ASSERT(svd.compute(a, ComputeThinU))\n    VERIFY_RAISES_ASSERT(svd.compute(a, ComputeThinV))\n  }\n}\n\n#undef SVD_DEFAULT\n#undef SVD_FOR_MIN_NORM\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/svd_fill.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\ntemplate<typename T>\nArray<T,4,1> four_denorms();\n\ntemplate<>\nArray4f four_denorms() { return Array4f(5.60844e-39f, -5.60844e-39f, 4.94e-44f, -4.94e-44f); }\ntemplate<>\nArray4d four_denorms() { return Array4d(5.60844e-313, -5.60844e-313, 4.94e-324, -4.94e-324); }\ntemplate<typename T>\nArray<T,4,1> four_denorms() { return four_denorms<double>().cast<T>(); }\n\ntemplate<typename MatrixType>\nvoid svd_fill_random(MatrixType &m, int Option = 0)\n{\n  using std::pow;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  Index diagSize = (std::min)(m.rows(), m.cols());\n  RealScalar s = std::numeric_limits<RealScalar>::max_exponent10/4;\n  s = internal::random<RealScalar>(1,s);\n  Matrix<RealScalar,Dynamic,1> d =  Matrix<RealScalar,Dynamic,1>::Random(diagSize);\n  for(Index k=0; k<diagSize; ++k)\n    d(k) = d(k)*pow(RealScalar(10),internal::random<RealScalar>(-s,s));\n\n  bool dup     = internal::random<int>(0,10) < 3;\n  bool unit_uv = internal::random<int>(0,10) < (dup?7:3); // if we duplicate some diagonal entries, then increase the chance to preserve them using unitary U and V factors\n  \n  // duplicate some singular values\n  if(dup)\n  {\n    Index n = internal::random<Index>(0,d.size()-1);\n    for(Index i=0; i<n; ++i)\n      d(internal::random<Index>(0,d.size()-1)) = d(internal::random<Index>(0,d.size()-1));\n  }\n  \n  Matrix<Scalar,Dynamic,Dynamic> U(m.rows(),diagSize);\n  Matrix<Scalar,Dynamic,Dynamic> VT(diagSize,m.cols());\n  if(unit_uv)\n  {\n    // in very rare cases let's try with a pure diagonal matrix\n    if(internal::random<int>(0,10) < 1)\n    {\n      U.setIdentity();\n      VT.setIdentity();\n    }\n    else\n    {\n      createRandomPIMatrixOfRank(diagSize,U.rows(), U.cols(), U);\n      createRandomPIMatrixOfRank(diagSize,VT.rows(), VT.cols(), VT);\n    }\n  }\n  else\n  {\n    U.setRandom();\n    VT.setRandom();\n  }\n  \n  Matrix<Scalar,Dynamic,1> samples(9);\n  samples << 0, four_denorms<RealScalar>(),\n            -RealScalar(1)/NumTraits<RealScalar>::highest(), RealScalar(1)/NumTraits<RealScalar>::highest(), (std::numeric_limits<RealScalar>::min)(), pow((std::numeric_limits<RealScalar>::min)(),0.8);\n  \n  if(Option==Symmetric)\n  {\n    m = U * d.asDiagonal() * U.transpose();\n    \n    // randomly nullify some rows/columns\n    {\n      Index count = internal::random<Index>(-diagSize,diagSize);\n      for(Index k=0; k<count; ++k)\n      {\n        Index i = internal::random<Index>(0,diagSize-1);\n        m.row(i).setZero();\n        m.col(i).setZero();\n      }\n      if(count<0)\n      // (partly) cancel some coeffs\n      if(!(dup && unit_uv))\n      {\n        \n        Index n = internal::random<Index>(0,m.size()-1);\n        for(Index k=0; k<n; ++k)\n        {\n          Index i = internal::random<Index>(0,m.rows()-1);\n          Index j = internal::random<Index>(0,m.cols()-1);\n          m(j,i) = m(i,j) = samples(internal::random<Index>(0,samples.size()-1));\n          if(NumTraits<Scalar>::IsComplex)\n            *(&numext::real_ref(m(j,i))+1) = *(&numext::real_ref(m(i,j))+1) = samples.real()(internal::random<Index>(0,samples.size()-1));\n        }\n      }\n    }\n  }\n  else\n  {\n    m = U * d.asDiagonal() * VT;\n    // (partly) cancel some coeffs\n    if(!(dup && unit_uv))\n    {\n      Index n = internal::random<Index>(0,m.size()-1);\n      for(Index k=0; k<n; ++k)\n      {\n        Index i = internal::random<Index>(0,m.rows()-1);\n        Index j = internal::random<Index>(0,m.cols()-1);\n        m(i,j) = samples(internal::random<Index>(0,samples.size()-1));\n        if(NumTraits<Scalar>::IsComplex)\n          *(&numext::real_ref(m(i,j))+1) = samples.real()(internal::random<Index>(0,samples.size()-1));\n      }\n    }\n  }\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/swap.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_STATIC_ASSERT\n#include \"main.h\"\n\ntemplate<typename T>\nstruct other_matrix_type\n{\n  typedef int type;\n};\n\ntemplate<typename Scalar_, int Rows_, int Cols_, int Options_, int MaxRows_, int MaxCols_>\nstruct other_matrix_type<Matrix<Scalar_, Rows_, Cols_, Options_, MaxRows_, MaxCols_> >\n{\n  typedef Matrix<Scalar_, Rows_, Cols_, Options_^RowMajor, MaxRows_, MaxCols_> type;\n};\n\ntemplate<typename MatrixType> void swap(const MatrixType& m)\n{\n  typedef typename other_matrix_type<MatrixType>::type OtherMatrixType;\n  typedef typename MatrixType::Scalar Scalar;\n\n  eigen_assert((!internal::is_same<MatrixType,OtherMatrixType>::value));\n  Index rows = m.rows();\n  Index cols = m.cols();\n  \n  // construct 3 matrix guaranteed to be distinct\n  MatrixType m1 = MatrixType::Random(rows,cols);\n  MatrixType m2 = MatrixType::Random(rows,cols) + Scalar(100) * MatrixType::Identity(rows,cols);\n  OtherMatrixType m3 = OtherMatrixType::Random(rows,cols) + Scalar(200) * OtherMatrixType::Identity(rows,cols);\n  \n  MatrixType m1_copy = m1;\n  MatrixType m2_copy = m2;\n  OtherMatrixType m3_copy = m3;\n  \n  // test swapping 2 matrices of same type\n  Scalar *d1=m1.data(), *d2=m2.data();\n  m1.swap(m2);\n  VERIFY_IS_APPROX(m1,m2_copy);\n  VERIFY_IS_APPROX(m2,m1_copy);\n  if(MatrixType::SizeAtCompileTime==Dynamic)\n  {\n    VERIFY(m1.data()==d2);\n    VERIFY(m2.data()==d1);\n  }\n  m1 = m1_copy;\n  m2 = m2_copy;\n  \n  // test swapping 2 matrices of different types\n  m1.swap(m3);\n  VERIFY_IS_APPROX(m1,m3_copy);\n  VERIFY_IS_APPROX(m3,m1_copy);\n  m1 = m1_copy;\n  m3 = m3_copy;\n  \n  // test swapping matrix with expression\n  m1.swap(m2.block(0,0,rows,cols));\n  VERIFY_IS_APPROX(m1,m2_copy);\n  VERIFY_IS_APPROX(m2,m1_copy);\n  m1 = m1_copy;\n  m2 = m2_copy;\n\n  // test swapping two expressions of different types\n  m1.transpose().swap(m3.transpose());\n  VERIFY_IS_APPROX(m1,m3_copy);\n  VERIFY_IS_APPROX(m3,m1_copy);\n  m1 = m1_copy;\n  m3 = m3_copy;\n  \n  if(m1.rows()>1)\n  {\n    // test assertion on mismatching size -- matrix case\n    VERIFY_RAISES_ASSERT(m1.swap(m1.row(0)));\n    // test assertion on mismatching size -- xpr case\n    VERIFY_RAISES_ASSERT(m1.row(0).swap(m1));\n  }\n}\n\nEIGEN_DECLARE_TEST(swap)\n{\n  int s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE);\n  CALL_SUBTEST_1( swap(Matrix3f()) ); // fixed size, no vectorization \n  CALL_SUBTEST_2( swap(Matrix4d()) ); // fixed size, possible vectorization \n  CALL_SUBTEST_3( swap(MatrixXd(s,s)) ); // dyn size, no vectorization \n  CALL_SUBTEST_4( swap(MatrixXf(s,s)) ); // dyn size, possible vectorization \n  TEST_SET_BUT_UNUSED_VARIABLE(s)\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/symbolic_index.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2017 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifdef EIGEN_TEST_PART_2\n#define EIGEN_MAX_CPP_VER 03\n\n// see indexed_view.cpp\n#if defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8))\n  #pragma GCC diagnostic ignored \"-Wdeprecated\"\n#endif\n\n#endif\n\n#include \"main.h\"\n\ntemplate<typename T1,typename T2>\nbool is_same_symb(const T1& a, const T2& b, Index size)\n{\n  return a.eval(last=size-1) == b.eval(last=size-1);\n}\n\ntemplate<typename T>\nvoid check_is_symbolic(const T&) {\n  STATIC_CHECK(( symbolic::is_symbolic<T>::value ))\n}\n\ntemplate<typename T>\nvoid check_isnot_symbolic(const T&) {\n  STATIC_CHECK(( !symbolic::is_symbolic<T>::value ))\n}\n\n#define VERIFY_EQ_INT(A,B) VERIFY_IS_APPROX(int(A),int(B))\n\nvoid check_symbolic_index()\n{\n  check_is_symbolic(last);\n  check_is_symbolic(lastp1);\n  check_is_symbolic(last+1);\n  check_is_symbolic(last-lastp1);\n  check_is_symbolic(2*last-lastp1/2);\n  check_isnot_symbolic(fix<3>());\n\n  Index size=100;\n\n  // First, let's check FixedInt arithmetic:\n  VERIFY( is_same_type( (fix<5>()-fix<3>())*fix<9>()/(-fix<3>()), fix<-(5-3)*9/3>() ) );\n  VERIFY( is_same_type( (fix<5>()-fix<3>())*fix<9>()/fix<2>(), fix<(5-3)*9/2>() ) );\n  VERIFY( is_same_type( fix<9>()/fix<2>(), fix<9/2>() ) );\n  VERIFY( is_same_type( fix<9>()%fix<2>(), fix<9%2>() ) );\n  VERIFY( is_same_type( fix<9>()&fix<2>(), fix<9&2>() ) );\n  VERIFY( is_same_type( fix<9>()|fix<2>(), fix<9|2>() ) );\n  VERIFY( is_same_type( fix<9>()/2, int(9/2) ) );\n\n  VERIFY( is_same_symb( lastp1-1, last, size) );\n  VERIFY( is_same_symb( lastp1-fix<1>(), last, size) );\n\n  VERIFY_IS_EQUAL( ( (last*5-2)/3 ).eval(last=size-1), ((size-1)*5-2)/3 );\n  VERIFY_IS_EQUAL( ( (last*fix<5>()-fix<2>())/fix<3>() ).eval(last=size-1), ((size-1)*5-2)/3 );\n  VERIFY_IS_EQUAL( ( -last*lastp1  ).eval(last=size-1), -(size-1)*size );\n  VERIFY_IS_EQUAL( ( lastp1-3*last  ).eval(last=size-1), size- 3*(size-1) );\n  VERIFY_IS_EQUAL( ( (lastp1-3*last)/lastp1  ).eval(last=size-1), (size- 3*(size-1))/size );\n\n#if EIGEN_HAS_CXX14_VARIABLE_TEMPLATES\n  {\n    struct x_tag {};  static const symbolic::SymbolExpr<x_tag> x;\n    struct y_tag {};  static const symbolic::SymbolExpr<y_tag> y;\n    struct z_tag {};  static const symbolic::SymbolExpr<z_tag> z;\n\n    VERIFY_IS_APPROX( int(((x+3)/y+z).eval(x=6,y=3,z=-13)), (6+3)/3+(-13) );\n  }\n#endif\n}\n\nEIGEN_DECLARE_TEST(symbolic_index)\n{\n  CALL_SUBTEST_1( check_symbolic_index() );\n  CALL_SUBTEST_2( check_symbolic_index() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/triangular.cpp",
    "content": "// This file is triangularView of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifdef EIGEN_TEST_PART_100\n#  define EIGEN_NO_DEPRECATED_WARNING\n#endif\n\n#include \"main.h\"\n\n\ntemplate<typename MatrixType> void triangular_deprecated(const MatrixType &m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n  MatrixType m1, m2, m3, m4;\n  m1.setRandom(rows,cols);\n  m2.setRandom(rows,cols);\n  m3 = m1; m4 = m2;\n  // deprecated method:\n  m1.template triangularView<Eigen::Upper>().swap(m2);\n  // use this method instead:\n  m3.template triangularView<Eigen::Upper>().swap(m4.template triangularView<Eigen::Upper>());\n  VERIFY_IS_APPROX(m1,m3);\n  VERIFY_IS_APPROX(m2,m4);\n  // deprecated method:\n  m1.template triangularView<Eigen::Lower>().swap(m4);\n  // use this method instead:\n  m3.template triangularView<Eigen::Lower>().swap(m2.template triangularView<Eigen::Lower>());\n  VERIFY_IS_APPROX(m1,m3);\n  VERIFY_IS_APPROX(m2,m4);\n}\n\n\ntemplate<typename MatrixType> void triangular_square(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n\n  RealScalar largerEps = 10*test_precision<RealScalar>();\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols),\n             m4(rows, cols),\n             r1(rows, cols),\n             r2(rows, cols);\n  VectorType v2 = VectorType::Random(rows);\n\n  MatrixType m1up = m1.template triangularView<Upper>();\n  MatrixType m2up = m2.template triangularView<Upper>();\n\n  if (rows*cols>1)\n  {\n    VERIFY(m1up.isUpperTriangular());\n    VERIFY(m2up.transpose().isLowerTriangular());\n    VERIFY(!m2.isLowerTriangular());\n  }\n\n//   VERIFY_IS_APPROX(m1up.transpose() * m2, m1.upper().transpose().lower() * m2);\n\n  // test overloaded operator+=\n  r1.setZero();\n  r2.setZero();\n  r1.template triangularView<Upper>() +=  m1;\n  r2 += m1up;\n  VERIFY_IS_APPROX(r1,r2);\n\n  // test overloaded operator=\n  m1.setZero();\n  m1.template triangularView<Upper>() = m2.transpose() + m2;\n  m3 = m2.transpose() + m2;\n  VERIFY_IS_APPROX(m3.template triangularView<Lower>().transpose().toDenseMatrix(), m1);\n\n  // test overloaded operator=\n  m1.setZero();\n  m1.template triangularView<Lower>() = m2.transpose() + m2;\n  VERIFY_IS_APPROX(m3.template triangularView<Lower>().toDenseMatrix(), m1);\n\n  VERIFY_IS_APPROX(m3.template triangularView<Lower>().conjugate().toDenseMatrix(),\n                   m3.conjugate().template triangularView<Lower>().toDenseMatrix());\n\n  m1 = MatrixType::Random(rows, cols);\n  for (int i=0; i<rows; ++i)\n    while (numext::abs2(m1(i,i))<RealScalar(1e-1)) m1(i,i) = internal::random<Scalar>();\n\n  Transpose<MatrixType> trm4(m4);\n  // test back and forward substitution with a vector as the rhs\n  m3 = m1.template triangularView<Upper>();\n  VERIFY(v2.isApprox(m3.adjoint() * (m1.adjoint().template triangularView<Lower>().solve(v2)), largerEps));\n  m3 = m1.template triangularView<Lower>();\n  VERIFY(v2.isApprox(m3.transpose() * (m1.transpose().template triangularView<Upper>().solve(v2)), largerEps));\n  m3 = m1.template triangularView<Upper>();\n  VERIFY(v2.isApprox(m3 * (m1.template triangularView<Upper>().solve(v2)), largerEps));\n  m3 = m1.template triangularView<Lower>();\n  VERIFY(v2.isApprox(m3.conjugate() * (m1.conjugate().template triangularView<Lower>().solve(v2)), largerEps));\n\n  // test back and forward substitution with a matrix as the rhs\n  m3 = m1.template triangularView<Upper>();\n  VERIFY(m2.isApprox(m3.adjoint() * (m1.adjoint().template triangularView<Lower>().solve(m2)), largerEps));\n  m3 = m1.template triangularView<Lower>();\n  VERIFY(m2.isApprox(m3.transpose() * (m1.transpose().template triangularView<Upper>().solve(m2)), largerEps));\n  m3 = m1.template triangularView<Upper>();\n  VERIFY(m2.isApprox(m3 * (m1.template triangularView<Upper>().solve(m2)), largerEps));\n  m3 = m1.template triangularView<Lower>();\n  VERIFY(m2.isApprox(m3.conjugate() * (m1.conjugate().template triangularView<Lower>().solve(m2)), largerEps));\n\n  // check M * inv(L) using in place API\n  m4 = m3;\n  m1.transpose().template triangularView<Eigen::Upper>().solveInPlace(trm4);\n  VERIFY_IS_APPROX(m4 * m1.template triangularView<Eigen::Lower>(), m3);\n\n  // check M * inv(U) using in place API\n  m3 = m1.template triangularView<Upper>();\n  m4 = m3;\n  m3.transpose().template triangularView<Eigen::Lower>().solveInPlace(trm4);\n  VERIFY_IS_APPROX(m4 * m1.template triangularView<Eigen::Upper>(), m3);\n\n  // check solve with unit diagonal\n  m3 = m1.template triangularView<UnitUpper>();\n  VERIFY(m2.isApprox(m3 * (m1.template triangularView<UnitUpper>().solve(m2)), largerEps));\n\n//   VERIFY((  m1.template triangularView<Upper>()\n//           * m2.template triangularView<Upper>()).isUpperTriangular());\n\n  // test swap\n  m1.setOnes();\n  m2.setZero();\n  m2.template triangularView<Upper>().swap(m1.template triangularView<Eigen::Upper>());\n  m3.setZero();\n  m3.template triangularView<Upper>().setOnes();\n  VERIFY_IS_APPROX(m2,m3);\n  VERIFY_RAISES_STATIC_ASSERT(m1.template triangularView<Eigen::Lower>().swap(m2.template triangularView<Eigen::Upper>()));\n\n  m1.setRandom();\n  m3 = m1.template triangularView<Upper>();\n  Matrix<Scalar, MatrixType::ColsAtCompileTime, Dynamic> m5(cols, internal::random<int>(1,20));  m5.setRandom();\n  Matrix<Scalar, Dynamic, MatrixType::RowsAtCompileTime> m6(internal::random<int>(1,20), rows);  m6.setRandom();\n  VERIFY_IS_APPROX(m1.template triangularView<Upper>() * m5, m3*m5);\n  VERIFY_IS_APPROX(m6*m1.template triangularView<Upper>(), m6*m3);\n\n  m1up = m1.template triangularView<Upper>();\n  VERIFY_IS_APPROX(m1.template selfadjointView<Upper>().template triangularView<Upper>().toDenseMatrix(), m1up);\n  VERIFY_IS_APPROX(m1up.template selfadjointView<Upper>().template triangularView<Upper>().toDenseMatrix(), m1up);\n  VERIFY_IS_APPROX(m1.template selfadjointView<Upper>().template triangularView<Lower>().toDenseMatrix(), m1up.adjoint());\n  VERIFY_IS_APPROX(m1up.template selfadjointView<Upper>().template triangularView<Lower>().toDenseMatrix(), m1up.adjoint());\n\n  VERIFY_IS_APPROX(m1.template selfadjointView<Upper>().diagonal(), m1.diagonal());\n\n  m3.setRandom();\n  const MatrixType& m3c(m3);\n  VERIFY( is_same_type(m3c.template triangularView<Lower>(),m3.template triangularView<Lower>().template conjugateIf<false>()) );\n  VERIFY( is_same_type(m3c.template triangularView<Lower>().conjugate(),m3.template triangularView<Lower>().template conjugateIf<true>()) );\n  VERIFY_IS_APPROX(m3.template triangularView<Lower>().template conjugateIf<true>().toDenseMatrix(),\n                   m3.conjugate().template triangularView<Lower>().toDenseMatrix());\n  VERIFY_IS_APPROX(m3.template triangularView<Lower>().template conjugateIf<false>().toDenseMatrix(),\n                   m3.template triangularView<Lower>().toDenseMatrix());\n\n  VERIFY( is_same_type(m3c.template selfadjointView<Lower>(),m3.template selfadjointView<Lower>().template conjugateIf<false>()) );\n  VERIFY( is_same_type(m3c.template selfadjointView<Lower>().conjugate(),m3.template selfadjointView<Lower>().template conjugateIf<true>()) );\n  VERIFY_IS_APPROX(m3.template selfadjointView<Lower>().template conjugateIf<true>().toDenseMatrix(),\n                   m3.conjugate().template selfadjointView<Lower>().toDenseMatrix());\n  VERIFY_IS_APPROX(m3.template selfadjointView<Lower>().template conjugateIf<false>().toDenseMatrix(),\n                   m3.template selfadjointView<Lower>().toDenseMatrix());\n\n}\n\n\ntemplate<typename MatrixType> void triangular_rect(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  enum { Rows =  MatrixType::RowsAtCompileTime, Cols =  MatrixType::ColsAtCompileTime };\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols),\n             m4(rows, cols),\n             r1(rows, cols),\n             r2(rows, cols);\n\n  MatrixType m1up = m1.template triangularView<Upper>();\n  MatrixType m2up = m2.template triangularView<Upper>();\n\n  if (rows>1 && cols>1)\n  {\n    VERIFY(m1up.isUpperTriangular());\n    VERIFY(m2up.transpose().isLowerTriangular());\n    VERIFY(!m2.isLowerTriangular());\n  }\n\n  // test overloaded operator+=\n  r1.setZero();\n  r2.setZero();\n  r1.template triangularView<Upper>() +=  m1;\n  r2 += m1up;\n  VERIFY_IS_APPROX(r1,r2);\n\n  // test overloaded operator=\n  m1.setZero();\n  m1.template triangularView<Upper>() = 3 * m2;\n  m3 = 3 * m2;\n  VERIFY_IS_APPROX(m3.template triangularView<Upper>().toDenseMatrix(), m1);\n\n\n  m1.setZero();\n  m1.template triangularView<Lower>() = 3 * m2;\n  VERIFY_IS_APPROX(m3.template triangularView<Lower>().toDenseMatrix(), m1);\n\n  m1.setZero();\n  m1.template triangularView<StrictlyUpper>() = 3 * m2;\n  VERIFY_IS_APPROX(m3.template triangularView<StrictlyUpper>().toDenseMatrix(), m1);\n\n\n  m1.setZero();\n  m1.template triangularView<StrictlyLower>() = 3 * m2;\n  VERIFY_IS_APPROX(m3.template triangularView<StrictlyLower>().toDenseMatrix(), m1);\n  m1.setRandom();\n  m2 = m1.template triangularView<Upper>();\n  VERIFY(m2.isUpperTriangular());\n  VERIFY(!m2.isLowerTriangular());\n  m2 = m1.template triangularView<StrictlyUpper>();\n  VERIFY(m2.isUpperTriangular());\n  VERIFY(m2.diagonal().isMuchSmallerThan(RealScalar(1)));\n  m2 = m1.template triangularView<UnitUpper>();\n  VERIFY(m2.isUpperTriangular());\n  m2.diagonal().array() -= Scalar(1);\n  VERIFY(m2.diagonal().isMuchSmallerThan(RealScalar(1)));\n  m2 = m1.template triangularView<Lower>();\n  VERIFY(m2.isLowerTriangular());\n  VERIFY(!m2.isUpperTriangular());\n  m2 = m1.template triangularView<StrictlyLower>();\n  VERIFY(m2.isLowerTriangular());\n  VERIFY(m2.diagonal().isMuchSmallerThan(RealScalar(1)));\n  m2 = m1.template triangularView<UnitLower>();\n  VERIFY(m2.isLowerTriangular());\n  m2.diagonal().array() -= Scalar(1);\n  VERIFY(m2.diagonal().isMuchSmallerThan(RealScalar(1)));\n  // test swap\n  m1.setOnes();\n  m2.setZero();\n  m2.template triangularView<Upper>().swap(m1.template triangularView<Eigen::Upper>());\n  m3.setZero();\n  m3.template triangularView<Upper>().setOnes();\n  VERIFY_IS_APPROX(m2,m3);\n}\n\nvoid bug_159()\n{\n  Matrix3d m = Matrix3d::Random().triangularView<Lower>();\n  EIGEN_UNUSED_VARIABLE(m)\n}\n\nEIGEN_DECLARE_TEST(triangular)\n{\n  int maxsize = (std::min)(EIGEN_TEST_MAX_SIZE,20);\n  for(int i = 0; i < g_repeat ; i++)\n  {\n    int r = internal::random<int>(2,maxsize); TEST_SET_BUT_UNUSED_VARIABLE(r)\n    int c = internal::random<int>(2,maxsize); TEST_SET_BUT_UNUSED_VARIABLE(c)\n\n    CALL_SUBTEST_1( triangular_square(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( triangular_square(Matrix<float, 2, 2>()) );\n    CALL_SUBTEST_3( triangular_square(Matrix3d()) );\n    CALL_SUBTEST_4( triangular_square(Matrix<std::complex<float>,8, 8>()) );\n    CALL_SUBTEST_5( triangular_square(MatrixXcd(r,r)) );\n    CALL_SUBTEST_6( triangular_square(Matrix<float,Dynamic,Dynamic,RowMajor>(r, r)) );\n\n    CALL_SUBTEST_7( triangular_rect(Matrix<float, 4, 5>()) );\n    CALL_SUBTEST_8( triangular_rect(Matrix<double, 6, 2>()) );\n    CALL_SUBTEST_9( triangular_rect(MatrixXcf(r, c)) );\n    CALL_SUBTEST_5( triangular_rect(MatrixXcd(r, c)) );\n    CALL_SUBTEST_6( triangular_rect(Matrix<float,Dynamic,Dynamic,RowMajor>(r, c)) );\n\n    CALL_SUBTEST_100( triangular_deprecated(Matrix<float, 5, 7>()) );\n    CALL_SUBTEST_100( triangular_deprecated(MatrixXd(r,c)) );\n  }\n  \n  CALL_SUBTEST_1( bug_159() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/type_alias.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2019 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\nEIGEN_DECLARE_TEST(type_alias)\n{\n  using namespace internal;\n\n  // To warm up, some basic checks:\n  STATIC_CHECK((is_same<MatrixXd,Matrix<double,Dynamic,Dynamic> >::value));\n  STATIC_CHECK((is_same<Matrix2f,Matrix<float,2,2> >::value));\n  STATIC_CHECK((is_same<Array33i,Array<int,3,3> >::value));\n\n#if EIGEN_HAS_CXX11\n  \n  STATIC_CHECK((is_same<MatrixX<double>,    MatrixXd>::value));\n  STATIC_CHECK((is_same<MatrixX<int>,       MatrixXi>::value));\n  STATIC_CHECK((is_same<Matrix2<int>,       Matrix2i>::value));\n  STATIC_CHECK((is_same<Matrix2X<float>,    Matrix2Xf>::value));\n  STATIC_CHECK((is_same<MatrixX4<double>,   MatrixX4d>::value));\n  STATIC_CHECK((is_same<VectorX<int>,       VectorXi>::value));\n  STATIC_CHECK((is_same<Vector2<float>,     Vector2f>::value));\n  STATIC_CHECK((is_same<RowVectorX<int>,    RowVectorXi>::value));\n  STATIC_CHECK((is_same<RowVector2<float>,  RowVector2f>::value));\n\n  STATIC_CHECK((is_same<ArrayXX<float>,     ArrayXXf>::value));\n  STATIC_CHECK((is_same<Array33<int>,       Array33i>::value));\n  STATIC_CHECK((is_same<Array2X<float>,     Array2Xf>::value));\n  STATIC_CHECK((is_same<ArrayX4<double>,    ArrayX4d>::value));\n  STATIC_CHECK((is_same<ArrayX<double>,     ArrayXd>::value));\n  STATIC_CHECK((is_same<Array4<double>,     Array4d>::value));\n\n  STATIC_CHECK((is_same<Vector<float,3>,        Vector3f>::value));\n  STATIC_CHECK((is_same<Vector<int,Dynamic>,    VectorXi>::value));\n  STATIC_CHECK((is_same<RowVector<float,3>,     RowVector3f>::value));\n  STATIC_CHECK((is_same<RowVector<int,Dynamic>, RowVectorXi>::value));\n\n#else\n  std::cerr << \"WARNING: c++11 type aliases not tested.\\n\";\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/umeyama.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/Core>\n#include <Eigen/Geometry>\n\n#include <Eigen/LU> // required for MatrixBase::determinant\n#include <Eigen/SVD> // required for SVD\n\nusing namespace Eigen;\n\n//  Constructs a random matrix from the unitary group U(size).\ntemplate <typename T>\nEigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> randMatrixUnitary(int size)\n{\n  typedef T Scalar;\n  typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> MatrixType;\n\n  MatrixType Q;\n\n  int max_tries = 40;\n  bool is_unitary = false;\n\n  while (!is_unitary && max_tries > 0)\n  {\n    // initialize random matrix\n    Q = MatrixType::Random(size, size);\n\n    // orthogonalize columns using the Gram-Schmidt algorithm\n    for (int col = 0; col < size; ++col)\n    {\n      typename MatrixType::ColXpr colVec = Q.col(col);\n      for (int prevCol = 0; prevCol < col; ++prevCol)\n      {\n        typename MatrixType::ColXpr prevColVec = Q.col(prevCol);\n        colVec -= colVec.dot(prevColVec)*prevColVec;\n      }\n      Q.col(col) = colVec.normalized();\n    }\n\n    // this additional orthogonalization is not necessary in theory but should enhance\n    // the numerical orthogonality of the matrix\n    for (int row = 0; row < size; ++row)\n    {\n      typename MatrixType::RowXpr rowVec = Q.row(row);\n      for (int prevRow = 0; prevRow < row; ++prevRow)\n      {\n        typename MatrixType::RowXpr prevRowVec = Q.row(prevRow);\n        rowVec -= rowVec.dot(prevRowVec)*prevRowVec;\n      }\n      Q.row(row) = rowVec.normalized();\n    }\n\n    // final check\n    is_unitary = Q.isUnitary();\n    --max_tries;\n  }\n\n  if (max_tries == 0)\n    eigen_assert(false && \"randMatrixUnitary: Could not construct unitary matrix!\");\n\n  return Q;\n}\n\n//  Constructs a random matrix from the special unitary group SU(size).\ntemplate <typename T>\nEigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> randMatrixSpecialUnitary(int size)\n{\n  typedef T Scalar;\n\n  typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> MatrixType;\n\n  // initialize unitary matrix\n  MatrixType Q = randMatrixUnitary<Scalar>(size);\n\n  // tweak the first column to make the determinant be 1\n  Q.col(0) *= numext::conj(Q.determinant());\n\n  return Q;\n}\n\ntemplate <typename MatrixType>\nvoid run_test(int dim, int num_elements)\n{\n  using std::abs;\n  typedef typename internal::traits<MatrixType>::Scalar Scalar;\n  typedef Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> MatrixX;\n  typedef Matrix<Scalar, Eigen::Dynamic, 1> VectorX;\n\n  // MUST be positive because in any other case det(cR_t) may become negative for\n  // odd dimensions!\n  const Scalar c = abs(internal::random<Scalar>());\n\n  MatrixX R = randMatrixSpecialUnitary<Scalar>(dim);\n  VectorX t = Scalar(50)*VectorX::Random(dim,1);\n\n  MatrixX cR_t = MatrixX::Identity(dim+1,dim+1);\n  cR_t.block(0,0,dim,dim) = c*R;\n  cR_t.block(0,dim,dim,1) = t;\n\n  MatrixX src = MatrixX::Random(dim+1, num_elements);\n  src.row(dim) = Matrix<Scalar, 1, Dynamic>::Constant(num_elements, Scalar(1));\n\n  MatrixX dst = cR_t*src;\n\n  MatrixX cR_t_umeyama = umeyama(src.block(0,0,dim,num_elements), dst.block(0,0,dim,num_elements));\n\n  const Scalar error = ( cR_t_umeyama*src - dst ).norm() / dst.norm();\n  VERIFY(error < Scalar(40)*std::numeric_limits<Scalar>::epsilon());\n}\n\ntemplate<typename Scalar, int Dimension>\nvoid run_fixed_size_test(int num_elements)\n{\n  using std::abs;\n  typedef Matrix<Scalar, Dimension+1, Dynamic> MatrixX;\n  typedef Matrix<Scalar, Dimension+1, Dimension+1> HomMatrix;\n  typedef Matrix<Scalar, Dimension, Dimension> FixedMatrix;\n  typedef Matrix<Scalar, Dimension, 1> FixedVector;\n\n  const int dim = Dimension;\n\n  // MUST be positive because in any other case det(cR_t) may become negative for\n  // odd dimensions!\n  // Also if c is to small compared to t.norm(), problem is ill-posed (cf. Bug 744)\n  const Scalar c = internal::random<Scalar>(0.5, 2.0);\n\n  FixedMatrix R = randMatrixSpecialUnitary<Scalar>(dim);\n  FixedVector t = Scalar(32)*FixedVector::Random(dim,1);\n\n  HomMatrix cR_t = HomMatrix::Identity(dim+1,dim+1);\n  cR_t.block(0,0,dim,dim) = c*R;\n  cR_t.block(0,dim,dim,1) = t;\n\n  MatrixX src = MatrixX::Random(dim+1, num_elements);\n  src.row(dim) = Matrix<Scalar, 1, Dynamic>::Constant(num_elements, Scalar(1));\n\n  MatrixX dst = cR_t*src;\n\n  Block<MatrixX, Dimension, Dynamic> src_block(src,0,0,dim,num_elements);\n  Block<MatrixX, Dimension, Dynamic> dst_block(dst,0,0,dim,num_elements);\n\n  HomMatrix cR_t_umeyama = umeyama(src_block, dst_block);\n\n  const Scalar error = ( cR_t_umeyama*src - dst ).squaredNorm();\n\n  VERIFY(error < Scalar(16)*std::numeric_limits<Scalar>::epsilon());\n}\n\nEIGEN_DECLARE_TEST(umeyama)\n{\n  for (int i=0; i<g_repeat; ++i)\n  {\n    const int num_elements = internal::random<int>(40,500);\n\n    // works also for dimensions bigger than 3...\n    for (int dim=2; dim<8; ++dim)\n    {\n      CALL_SUBTEST_1(run_test<MatrixXd>(dim, num_elements));\n      CALL_SUBTEST_2(run_test<MatrixXf>(dim, num_elements));\n    }\n\n    CALL_SUBTEST_3((run_fixed_size_test<float, 2>(num_elements)));\n    CALL_SUBTEST_4((run_fixed_size_test<float, 3>(num_elements)));\n    CALL_SUBTEST_5((run_fixed_size_test<float, 4>(num_elements)));\n\n    CALL_SUBTEST_6((run_fixed_size_test<double, 2>(num_elements)));\n    CALL_SUBTEST_7((run_fixed_size_test<double, 3>(num_elements)));\n    CALL_SUBTEST_8((run_fixed_size_test<double, 4>(num_elements)));\n  }\n\n  // Those two calls don't compile and result in meaningful error messages!\n  // umeyama(MatrixXcf(),MatrixXcf());\n  // umeyama(MatrixXcd(),MatrixXcd());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/umfpack_support.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS\n#include \"sparse_solver.h\"\n\n#include <Eigen/UmfPackSupport>\n\ntemplate<typename T1, typename T2> void test_umfpack_support_T()\n{\n  UmfPackLU<SparseMatrix<T1, ColMajor, T2> > umfpack_colmajor;\n  UmfPackLU<SparseMatrix<T1, RowMajor, T2> > umfpack_rowmajor;\n  \n  check_sparse_square_solving(umfpack_colmajor);\n  check_sparse_square_solving(umfpack_rowmajor);\n  \n  check_sparse_square_determinant(umfpack_colmajor);\n  check_sparse_square_determinant(umfpack_rowmajor);\n}\n\nEIGEN_DECLARE_TEST(umfpack_support)\n{\n  CALL_SUBTEST_1((test_umfpack_support_T<double, int>()));\n  CALL_SUBTEST_2((test_umfpack_support_T<std::complex<double>, int>()));\n  CALL_SUBTEST_3((test_umfpack_support_T<double, long >()));\n  CALL_SUBTEST_4((test_umfpack_support_T<std::complex<double>, long>()));\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/unalignedcount.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\nstatic int nb_load;\nstatic int nb_loadu;\nstatic int nb_store;\nstatic int nb_storeu;\n\n#define EIGEN_DEBUG_ALIGNED_LOAD    { nb_load++;    }\n#define EIGEN_DEBUG_UNALIGNED_LOAD  { nb_loadu++;   }\n#define EIGEN_DEBUG_ALIGNED_STORE   { nb_store++;   }\n#define EIGEN_DEBUG_UNALIGNED_STORE { nb_storeu++;  }\n\n#define VERIFY_ALIGNED_UNALIGNED_COUNT(XPR,AL,UL,AS,US) {\\\n    nb_load = nb_loadu = nb_store = nb_storeu = 0; \\\n    XPR; \\\n    if(!(nb_load==AL && nb_loadu==UL && nb_store==AS && nb_storeu==US)) \\\n      std::cerr << \" >> \" << nb_load << \", \" << nb_loadu << \", \" << nb_store << \", \" << nb_storeu << \"\\n\"; \\\n    VERIFY( (#XPR) && nb_load==AL && nb_loadu==UL && nb_store==AS && nb_storeu==US ); \\\n  }\n\n\n#include \"main.h\"\n\nEIGEN_DECLARE_TEST(unalignedcount)\n{\n  #if defined(EIGEN_VECTORIZE_AVX512)\n  VectorXf a(48), b(48);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a += b, 6, 0, 3, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,48) += b.segment(0,48), 3, 3, 3, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,48) -= b.segment(0,48), 3, 3, 3, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,48) *= 3.5, 3, 0, 3, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,48) /= 3.5, 3, 0, 3, 0);\n  #elif defined(EIGEN_VECTORIZE_AVX)\n  VectorXf a(40), b(40);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a += b, 10, 0, 5, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) += b.segment(0,40), 5, 5, 5, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) -= b.segment(0,40), 5, 5, 5, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) *= 3.5, 5, 0, 5, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) /= 3.5, 5, 0, 5, 0);\n  #elif defined(EIGEN_VECTORIZE_SSE)\n  VectorXf a(40), b(40);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a += b, 20, 0, 10, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) += b.segment(0,40), 10, 10, 10, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) -= b.segment(0,40), 10, 10, 10, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) *= 3.5, 10, 0, 10, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) /= 3.5, 10, 0, 10, 0);\n  #else\n  // The following line is to eliminate \"variable not used\" warnings\n  nb_load = nb_loadu = nb_store = nb_storeu = 0;\n  int a(0), b(0);\n  VERIFY(a==b);\n  #endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/upperbidiagonalization.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/SVD>\n\ntemplate<typename MatrixType> void upperbidiag(const MatrixType& m)\n{\n  const Index rows = m.rows();\n  const Index cols = m.cols();\n\n  typedef Matrix<typename MatrixType::RealScalar, MatrixType::RowsAtCompileTime,  MatrixType::ColsAtCompileTime> RealMatrixType;\n  typedef Matrix<typename MatrixType::Scalar, MatrixType::ColsAtCompileTime,  MatrixType::RowsAtCompileTime> TransposeMatrixType;\n\n  MatrixType a = MatrixType::Random(rows,cols);\n  internal::UpperBidiagonalization<MatrixType> ubd(a);\n  RealMatrixType b(rows, cols);\n  b.setZero();\n  b.block(0,0,cols,cols) = ubd.bidiagonal();\n  MatrixType c = ubd.householderU() * b * ubd.householderV().adjoint();\n  VERIFY_IS_APPROX(a,c);\n  TransposeMatrixType d = ubd.householderV() * b.adjoint() * ubd.householderU().adjoint();\n  VERIFY_IS_APPROX(a.adjoint(),d);\n}\n\nEIGEN_DECLARE_TEST(upperbidiagonalization)\n{\n  for(int i = 0; i < g_repeat; i++) {\n   CALL_SUBTEST_1( upperbidiag(MatrixXf(3,3)) );\n   CALL_SUBTEST_2( upperbidiag(MatrixXd(17,12)) );\n   CALL_SUBTEST_3( upperbidiag(MatrixXcf(20,20)) );\n   CALL_SUBTEST_4( upperbidiag(Matrix<std::complex<double>,Dynamic,Dynamic,RowMajor>(16,15)) );\n   CALL_SUBTEST_5( upperbidiag(Matrix<float,6,4>()) );\n   CALL_SUBTEST_6( upperbidiag(Matrix<float,5,5>()) );\n   CALL_SUBTEST_7( upperbidiag(Matrix<double,4,3>()) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/vectorization_logic.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifdef EIGEN_TEST_PART_1\n#define EIGEN_UNALIGNED_VECTORIZE 1\n#endif\n\n#ifdef EIGEN_TEST_PART_2\n#define EIGEN_UNALIGNED_VECTORIZE 0\n#endif\n\n#ifdef EIGEN_DEFAULT_TO_ROW_MAJOR\n#undef EIGEN_DEFAULT_TO_ROW_MAJOR\n#endif\n#define EIGEN_DEBUG_ASSIGN\n#include \"main.h\"\n#include <typeinfo>\n\n// Disable \"ignoring attributes on template argument\"\n// for packet_traits<Packet*>\n// => The only workaround would be to wrap _m128 and the likes\n//    within wrappers.\n#if EIGEN_GNUC_AT_LEAST(6,0)\n    #pragma GCC diagnostic ignored \"-Wignored-attributes\"\n#endif\n\nusing internal::demangle_flags;\nusing internal::demangle_traversal;\nusing internal::demangle_unrolling;\n\ntemplate<typename Dst, typename Src>\nbool test_assign(const Dst&, const Src&, int traversal, int unrolling)\n{\n  EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Dst,Src);\n  typedef internal::copy_using_evaluator_traits<internal::evaluator<Dst>,internal::evaluator<Src>, internal::assign_op<typename Dst::Scalar,typename Src::Scalar> > traits;\n  bool res = traits::Traversal==traversal;\n  if(unrolling==InnerUnrolling+CompleteUnrolling)\n    res = res && (int(traits::Unrolling)==InnerUnrolling || int(traits::Unrolling)==CompleteUnrolling);\n  else\n    res = res && int(traits::Unrolling)==unrolling;\n  if(!res)\n  {\n    std::cerr << \"Src: \" << demangle_flags(Src::Flags) << std::endl;\n    std::cerr << \"     \" << demangle_flags(internal::evaluator<Src>::Flags) << std::endl;\n    std::cerr << \"Dst: \" << demangle_flags(Dst::Flags) << std::endl;\n    std::cerr << \"     \" << demangle_flags(internal::evaluator<Dst>::Flags) << std::endl;\n    traits::debug();\n    std::cerr << \" Expected Traversal == \" << demangle_traversal(traversal)\n              << \" got \" << demangle_traversal(traits::Traversal) << \"\\n\";\n    std::cerr << \" Expected Unrolling == \" << demangle_unrolling(unrolling)\n              << \" got \" << demangle_unrolling(traits::Unrolling) << \"\\n\";\n  }\n  return res;\n}\n\ntemplate<typename Dst, typename Src>\nbool test_assign(int traversal, int unrolling)\n{\n  EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Dst,Src);\n  typedef internal::copy_using_evaluator_traits<internal::evaluator<Dst>,internal::evaluator<Src>, internal::assign_op<typename Dst::Scalar,typename Src::Scalar> > traits;\n  bool res = traits::Traversal==traversal && traits::Unrolling==unrolling;\n  if(!res)\n  {\n    std::cerr << \"Src: \" << demangle_flags(Src::Flags) << std::endl;\n    std::cerr << \"     \" << demangle_flags(internal::evaluator<Src>::Flags) << std::endl;\n    std::cerr << \"Dst: \" << demangle_flags(Dst::Flags) << std::endl;\n    std::cerr << \"     \" << demangle_flags(internal::evaluator<Dst>::Flags) << std::endl;\n    traits::debug();\n    std::cerr << \" Expected Traversal == \" << demangle_traversal(traversal)\n              << \" got \" << demangle_traversal(traits::Traversal) << \"\\n\";\n    std::cerr << \" Expected Unrolling == \" << demangle_unrolling(unrolling)\n              << \" got \" << demangle_unrolling(traits::Unrolling) << \"\\n\";\n  }\n  return res;\n}\n\ntemplate<typename Xpr>\nbool test_redux(const Xpr&, int traversal, int unrolling)\n{\n  typedef typename Xpr::Scalar Scalar;\n  typedef internal::redux_traits<internal::scalar_sum_op<Scalar,Scalar>,internal::redux_evaluator<Xpr> > traits;\n  \n  bool res = traits::Traversal==traversal && traits::Unrolling==unrolling;\n  if(!res)\n  {\n    std::cerr << demangle_flags(Xpr::Flags) << std::endl;\n    std::cerr << demangle_flags(internal::evaluator<Xpr>::Flags) << std::endl;\n    traits::debug();\n    \n    std::cerr << \" Expected Traversal == \" << demangle_traversal(traversal)\n              << \" got \" << demangle_traversal(traits::Traversal) << \"\\n\";\n    std::cerr << \" Expected Unrolling == \" << demangle_unrolling(unrolling)\n              << \" got \" << demangle_unrolling(traits::Unrolling) << \"\\n\";\n  }\n  return res;\n}\n\ntemplate<typename Scalar, bool Enable = internal::packet_traits<Scalar>::Vectorizable>\nstruct vectorization_logic\n{\n  typedef internal::packet_traits<Scalar> PacketTraits;\n  \n  typedef typename internal::packet_traits<Scalar>::type PacketType;\n  typedef typename internal::unpacket_traits<PacketType>::half HalfPacketType;\n  enum {\n    PacketSize = internal::unpacket_traits<PacketType>::size,\n    HalfPacketSize = internal::unpacket_traits<HalfPacketType>::size\n  };\n  static void run()\n  {\n    \n    typedef Matrix<Scalar,PacketSize,1> Vector1;\n    typedef Matrix<Scalar,Dynamic,1> VectorX;\n    typedef Matrix<Scalar,Dynamic,Dynamic> MatrixXX;\n    typedef Matrix<Scalar,PacketSize,PacketSize> Matrix11;\n    typedef Matrix<Scalar,(Matrix11::Flags&RowMajorBit)?8:2*PacketSize,(Matrix11::Flags&RowMajorBit)?2*PacketSize:8>   Matrix22;\n    typedef Matrix<Scalar,(Matrix11::Flags&RowMajorBit)?16:4*PacketSize,(Matrix11::Flags&RowMajorBit)?4*PacketSize:16> Matrix44;\n    typedef Matrix<Scalar,(Matrix11::Flags&RowMajorBit)?16:4*PacketSize,(Matrix11::Flags&RowMajorBit)?4*PacketSize:16,DontAlign|EIGEN_DEFAULT_MATRIX_STORAGE_ORDER_OPTION> Matrix44u;\n    typedef Matrix<Scalar,4*PacketSize,4*PacketSize,ColMajor> Matrix44c;\n    typedef Matrix<Scalar,4*PacketSize,4*PacketSize,RowMajor> Matrix44r;\n\n    typedef Matrix<Scalar,\n        (PacketSize==16 ? 8 : PacketSize==8 ? 4 : PacketSize==4 ? 2 : PacketSize==2 ? 1 : /*PacketSize==1 ?*/ 1),\n        (PacketSize==16 ? 2 : PacketSize==8 ? 2 : PacketSize==4 ? 2 : PacketSize==2 ? 2 : /*PacketSize==1 ?*/ 1)\n      > Matrix1;\n\n    typedef Matrix<Scalar,\n        (PacketSize==16 ? 8 : PacketSize==8 ? 4 : PacketSize==4 ? 2 : PacketSize==2 ? 1 : /*PacketSize==1 ?*/ 1),\n        (PacketSize==16 ? 2 : PacketSize==8 ? 2 : PacketSize==4 ? 2 : PacketSize==2 ? 2 : /*PacketSize==1 ?*/ 1),\n      DontAlign|((Matrix1::Flags&RowMajorBit)?RowMajor:ColMajor)> Matrix1u;\n\n    // this type is made such that it can only be vectorized when viewed as a linear 1D vector\n    typedef Matrix<Scalar,\n        (PacketSize==16 ?  4 : PacketSize==8 ? 4 : PacketSize==4 ? 6 : PacketSize==2 ? ((Matrix11::Flags&RowMajorBit)?2:3) : /*PacketSize==1 ?*/ 1),\n        (PacketSize==16 ? 12 : PacketSize==8 ? 6 : PacketSize==4 ? 2 : PacketSize==2 ? ((Matrix11::Flags&RowMajorBit)?3:2) : /*PacketSize==1 ?*/ 3)\n      > Matrix3;\n    \n    #if !EIGEN_GCC_AND_ARCH_DOESNT_WANT_STACK_ALIGNMENT\n    VERIFY(test_assign(Vector1(),Vector1(),\n      InnerVectorizedTraversal,CompleteUnrolling));\n    VERIFY(test_assign(Vector1(),Vector1()+Vector1(),\n      InnerVectorizedTraversal,CompleteUnrolling));\n    VERIFY(test_assign(Vector1(),Vector1().cwiseProduct(Vector1()),\n      InnerVectorizedTraversal,CompleteUnrolling));\n    VERIFY(test_assign(Vector1(),Vector1().template cast<Scalar>(),\n      InnerVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_assign(Matrix44(),Matrix44()+Matrix44(),\n      InnerVectorizedTraversal,InnerUnrolling));\n\n    VERIFY(test_assign(Matrix44u(),Matrix44()+Matrix44(),\n      EIGEN_UNALIGNED_VECTORIZE ? InnerVectorizedTraversal : LinearTraversal,\n      EIGEN_UNALIGNED_VECTORIZE ? InnerUnrolling : NoUnrolling));\n\n    VERIFY(test_assign(Matrix1(),Matrix1()+Matrix1(),\n      (int(Matrix1::InnerSizeAtCompileTime) % int(PacketSize))==0 ? InnerVectorizedTraversal : LinearVectorizedTraversal,\n      CompleteUnrolling));\n\n    VERIFY(test_assign(Matrix1u(),Matrix1()+Matrix1(),\n      EIGEN_UNALIGNED_VECTORIZE ? ((int(Matrix1::InnerSizeAtCompileTime) % int(PacketSize))==0 ? InnerVectorizedTraversal : LinearVectorizedTraversal)\n                                : LinearTraversal, CompleteUnrolling));\n\n    VERIFY(test_assign(Matrix44c().col(1),Matrix44c().col(2)+Matrix44c().col(3),\n      InnerVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_assign(Matrix44r().row(2),Matrix44r().row(1)+Matrix44r().row(1),\n      InnerVectorizedTraversal,CompleteUnrolling));\n\n    if(PacketSize>1)\n    {\n      typedef Matrix<Scalar,3,3,ColMajor> Matrix33c;\n      typedef Matrix<Scalar,3,1,ColMajor> Vector3;\n      VERIFY(test_assign(Matrix33c().row(2),Matrix33c().row(1)+Matrix33c().row(1),\n        LinearTraversal,CompleteUnrolling));\n      VERIFY(test_assign(Vector3(),Vector3()+Vector3(),\n        sizeof(Scalar)==16 ? InnerVectorizedTraversal : (EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : LinearTraversal), CompleteUnrolling));\n      VERIFY(test_assign(Matrix33c().col(0),Matrix33c().col(1)+Matrix33c().col(1),\n        EIGEN_UNALIGNED_VECTORIZE ? (sizeof(Scalar)==16 ? InnerVectorizedTraversal : LinearVectorizedTraversal)\n                                  : (sizeof(Scalar)==16 ? SliceVectorizedTraversal : LinearTraversal),\n        ((!EIGEN_UNALIGNED_VECTORIZE) && (sizeof(Scalar)==16)) ? NoUnrolling : CompleteUnrolling));\n\n      VERIFY(test_assign(Matrix3(),Matrix3().cwiseProduct(Matrix3()),\n        LinearVectorizedTraversal,CompleteUnrolling));\n\n      VERIFY(test_assign(Matrix<Scalar,17,17>(),Matrix<Scalar,17,17>()+Matrix<Scalar,17,17>(),\n        sizeof(Scalar)==16        ? InnerVectorizedTraversal  :\n        EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal :\n                                    LinearTraversal,\n        NoUnrolling));\n\n      VERIFY(test_assign(Matrix11(), Matrix11()+Matrix11(),InnerVectorizedTraversal,CompleteUnrolling));\n\n\n      VERIFY(test_assign(Matrix11(),Matrix<Scalar,21,21>().template block<PacketSize,PacketSize>(2,3)+Matrix<Scalar,21,21>().template block<PacketSize,PacketSize>(3,2),\n        (EIGEN_UNALIGNED_VECTORIZE) ? InnerVectorizedTraversal : DefaultTraversal, CompleteUnrolling|InnerUnrolling));\n\n      VERIFY(test_assign(Vector1(),Matrix11()*Vector1(),\n                         InnerVectorizedTraversal,CompleteUnrolling));\n\n      VERIFY(test_assign(Matrix11(),Matrix11().lazyProduct(Matrix11()),\n                         InnerVectorizedTraversal,InnerUnrolling+CompleteUnrolling));\n    }\n\n    VERIFY(test_redux(Vector1(),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_redux(Vector1().array()*Vector1().array(),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_redux((Vector1().array()*Vector1().array()).col(0),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_redux(Matrix<Scalar,PacketSize,3>(),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_redux(Matrix3(),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_redux(Matrix44(),\n      LinearVectorizedTraversal,NoUnrolling));\n\n    if(PacketSize>1) {\n      VERIFY(test_redux(Matrix44().template block<(Matrix1::Flags&RowMajorBit)?4:PacketSize,(Matrix1::Flags&RowMajorBit)?PacketSize:4>(1,2),\n        SliceVectorizedTraversal,CompleteUnrolling));\n\n      VERIFY(test_redux(Matrix44().template block<(Matrix1::Flags&RowMajorBit)?2:PacketSize,(Matrix1::Flags&RowMajorBit)?PacketSize:2>(1,2),\n        DefaultTraversal,CompleteUnrolling));\n    }\n\n    VERIFY(test_redux(Matrix44c().template block<2*PacketSize,1>(1,2),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_redux(Matrix44r().template block<1,2*PacketSize>(2,1),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY((test_assign<\n            Map<Matrix22, AlignedMax, OuterStride<3*PacketSize> >,\n            Matrix22\n            >(InnerVectorizedTraversal,CompleteUnrolling)));\n\n    VERIFY((test_assign<\n            Map<Matrix<Scalar,EIGEN_PLAIN_ENUM_MAX(2,PacketSize),EIGEN_PLAIN_ENUM_MAX(2,PacketSize)>, AlignedMax, InnerStride<3*PacketSize> >,\n            Matrix<Scalar,EIGEN_PLAIN_ENUM_MAX(2,PacketSize),EIGEN_PLAIN_ENUM_MAX(2,PacketSize)>\n            >(DefaultTraversal,PacketSize>=8?InnerUnrolling:CompleteUnrolling)));\n\n    VERIFY((test_assign(Matrix11(), Matrix<Scalar,PacketSize,EIGEN_PLAIN_ENUM_MIN(2,PacketSize)>()*Matrix<Scalar,EIGEN_PLAIN_ENUM_MIN(2,PacketSize),PacketSize>(),\n                        InnerVectorizedTraversal, CompleteUnrolling)));\n    #endif\n\n    VERIFY(test_assign(MatrixXX(10,10),MatrixXX(20,20).block(10,10,2,3),\n      SliceVectorizedTraversal,NoUnrolling));\n\n    VERIFY(test_redux(VectorX(10),\n      LinearVectorizedTraversal,NoUnrolling));\n  }\n};\n\ntemplate<typename Scalar> struct vectorization_logic<Scalar,false>\n{\n  static void run() {}\n};\n\ntemplate<typename Scalar, bool Enable = !internal::is_same<typename internal::unpacket_traits<typename internal::packet_traits<Scalar>::type>::half,\n                                                           typename internal::packet_traits<Scalar>::type>::value >\nstruct vectorization_logic_half\n{\n  typedef internal::packet_traits<Scalar> PacketTraits;\n  typedef typename internal::unpacket_traits<typename internal::packet_traits<Scalar>::type>::half PacketType;\n  enum {\n    PacketSize = internal::unpacket_traits<PacketType>::size\n  };\n  static void run()\n  {\n    \n    typedef Matrix<Scalar,PacketSize,1> Vector1;\n    typedef Matrix<Scalar,PacketSize,PacketSize> Matrix11;\n    typedef Matrix<Scalar,5*PacketSize,7,ColMajor> Matrix57;\n    typedef Matrix<Scalar,3*PacketSize,5,ColMajor> Matrix35;\n    typedef Matrix<Scalar,5*PacketSize,7,DontAlign|ColMajor> Matrix57u;\n\n    typedef Matrix<Scalar,\n        (PacketSize==16 ? 8 : PacketSize==8 ? 4 : PacketSize==4 ? 2 : PacketSize==2 ? 1 : /*PacketSize==1 ?*/ 1),\n        (PacketSize==16 ? 2 : PacketSize==8 ? 2 : PacketSize==4 ? 2 : PacketSize==2 ? 2 : /*PacketSize==1 ?*/ 1)\n      > Matrix1;\n\n    typedef Matrix<Scalar,\n        (PacketSize==16 ? 8 : PacketSize==8 ? 4 : PacketSize==4 ? 2 : PacketSize==2 ? 1 : /*PacketSize==1 ?*/ 1),\n        (PacketSize==16 ? 2 : PacketSize==8 ? 2 : PacketSize==4 ? 2 : PacketSize==2 ? 2 : /*PacketSize==1 ?*/ 1),\n      DontAlign|((Matrix1::Flags&RowMajorBit)?RowMajor:ColMajor)> Matrix1u;\n\n    // this type is made such that it can only be vectorized when viewed as a linear 1D vector\n    typedef Matrix<Scalar,\n        (PacketSize==16 ?  4 : PacketSize==8 ? 4 : PacketSize==4 ? 6 : PacketSize==2 ? ((Matrix11::Flags&RowMajorBit)?2:3) : /*PacketSize==1 ?*/ 1),\n        (PacketSize==16 ? 12 : PacketSize==8 ? 6 : PacketSize==4 ? 2 : PacketSize==2 ? ((Matrix11::Flags&RowMajorBit)?3:2) : /*PacketSize==1 ?*/ 3)\n      > Matrix3;\n    \n    #if !EIGEN_GCC_AND_ARCH_DOESNT_WANT_STACK_ALIGNMENT\n    VERIFY(test_assign(Vector1(),Vector1(),\n      InnerVectorizedTraversal,CompleteUnrolling));\n    VERIFY(test_assign(Vector1(),Vector1()+Vector1(),\n      InnerVectorizedTraversal,CompleteUnrolling));\n    VERIFY(test_assign(Vector1(),Vector1().template segment<PacketSize>(0).derived(),\n      EIGEN_UNALIGNED_VECTORIZE ? InnerVectorizedTraversal : LinearVectorizedTraversal,CompleteUnrolling));\n    VERIFY(test_assign(Vector1(),Scalar(2.1)*Vector1()-Vector1(),\n      InnerVectorizedTraversal,CompleteUnrolling));\n    VERIFY(test_assign(Vector1(),(Scalar(2.1)*Vector1().template segment<PacketSize>(0)-Vector1().template segment<PacketSize>(0)).derived(),\n      EIGEN_UNALIGNED_VECTORIZE ? InnerVectorizedTraversal : LinearVectorizedTraversal,CompleteUnrolling));\n    VERIFY(test_assign(Vector1(),Vector1().cwiseProduct(Vector1()),\n      InnerVectorizedTraversal,CompleteUnrolling));\n    VERIFY(test_assign(Vector1(),Vector1().template cast<Scalar>(),\n      InnerVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_assign(Matrix57(),Matrix57()+Matrix57(),\n      InnerVectorizedTraversal,InnerUnrolling));\n\n    VERIFY(test_assign(Matrix57u(),Matrix57()+Matrix57(),\n      EIGEN_UNALIGNED_VECTORIZE ? InnerVectorizedTraversal : LinearTraversal,\n      EIGEN_UNALIGNED_VECTORIZE ? InnerUnrolling : NoUnrolling));\n\n    VERIFY(test_assign(Matrix1u(),Matrix1()+Matrix1(),\n      EIGEN_UNALIGNED_VECTORIZE ? ((int(Matrix1::InnerSizeAtCompileTime) % int(PacketSize))==0 ? InnerVectorizedTraversal : LinearVectorizedTraversal) : LinearTraversal,CompleteUnrolling));\n        \n    if(PacketSize>1)\n    {\n      typedef Matrix<Scalar,3,3,ColMajor> Matrix33c;\n      VERIFY(test_assign(Matrix33c().row(2),Matrix33c().row(1)+Matrix33c().row(1),\n        LinearTraversal,CompleteUnrolling));\n      VERIFY(test_assign(Matrix33c().col(0),Matrix33c().col(1)+Matrix33c().col(1),\n        EIGEN_UNALIGNED_VECTORIZE ? (sizeof(Scalar)==16 ? InnerVectorizedTraversal : LinearVectorizedTraversal)\n                                  : (sizeof(Scalar)==16 ? SliceVectorizedTraversal : LinearTraversal),\n        ((!EIGEN_UNALIGNED_VECTORIZE) && (sizeof(Scalar)==16)) ? NoUnrolling : CompleteUnrolling));\n              \n      VERIFY(test_assign(Matrix3(),Matrix3().cwiseQuotient(Matrix3()),\n        PacketTraits::HasDiv ? LinearVectorizedTraversal : LinearTraversal,\n        PacketTraits::HasDiv ? CompleteUnrolling : NoUnrolling));\n        \n      VERIFY(test_assign(Matrix<Scalar,17,17>(),Matrix<Scalar,17,17>()+Matrix<Scalar,17,17>(),\n        sizeof(Scalar)==16 ? InnerVectorizedTraversal : (EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : LinearTraversal),\n        NoUnrolling));\n        \n      VERIFY(test_assign(Matrix11(),Matrix<Scalar,17,17>().template block<PacketSize,PacketSize>(2,3)+Matrix<Scalar,17,17>().template block<PacketSize,PacketSize>(8,4),\n        EIGEN_UNALIGNED_VECTORIZE ? InnerVectorizedTraversal : DefaultTraversal,InnerUnrolling+CompleteUnrolling));\n  \n\n      VERIFY(test_assign(Vector1(),Matrix11()*Vector1(),\n                         InnerVectorizedTraversal,CompleteUnrolling));\n\n      VERIFY(test_assign(Matrix11(),Matrix11().lazyProduct(Matrix11()),\n                         InnerVectorizedTraversal,InnerUnrolling+CompleteUnrolling));\n    }\n    \n    VERIFY(test_redux(Vector1(),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_redux(Matrix<Scalar,PacketSize,3>(),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_redux(Matrix3(),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_redux(Matrix35(),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_redux(Matrix57().template block<PacketSize==1?2:PacketSize,3>(1,0),\n      SliceVectorizedTraversal,CompleteUnrolling));\n\n    if(PacketSize>1) {\n      VERIFY(test_redux(Matrix57().template block<PacketSize,2>(1,0),\n        DefaultTraversal,CompleteUnrolling));\n    }\n\n    VERIFY((test_assign<\n            Map<Matrix<Scalar,EIGEN_PLAIN_ENUM_MAX(2,PacketSize),EIGEN_PLAIN_ENUM_MAX(2,PacketSize)>, AlignedMax, InnerStride<3*PacketSize> >,\n            Matrix<Scalar,EIGEN_PLAIN_ENUM_MAX(2,PacketSize),EIGEN_PLAIN_ENUM_MAX(2,PacketSize)>\n            >(DefaultTraversal,PacketSize>4?InnerUnrolling:CompleteUnrolling)));\n\n    VERIFY((test_assign(Matrix57(), Matrix<Scalar,5*PacketSize,3>()*Matrix<Scalar,3,7>(),\n                        InnerVectorizedTraversal, InnerUnrolling+CompleteUnrolling)));\n    #endif\n  }\n};\n\ntemplate<typename Scalar> struct vectorization_logic_half<Scalar,false>\n{\n  static void run() {}\n};\n\nEIGEN_DECLARE_TEST(vectorization_logic)\n{\n\n#ifdef EIGEN_VECTORIZE\n\n  CALL_SUBTEST( vectorization_logic<int>::run() );\n  CALL_SUBTEST( vectorization_logic<float>::run() );\n  CALL_SUBTEST( vectorization_logic<double>::run() );\n  CALL_SUBTEST( vectorization_logic<std::complex<float> >::run() );\n  CALL_SUBTEST( vectorization_logic<std::complex<double> >::run() );\n  \n  CALL_SUBTEST( vectorization_logic_half<int>::run() );\n  CALL_SUBTEST( vectorization_logic_half<float>::run() );\n  CALL_SUBTEST( vectorization_logic_half<double>::run() );\n  CALL_SUBTEST( vectorization_logic_half<std::complex<float> >::run() );\n  CALL_SUBTEST( vectorization_logic_half<std::complex<double> >::run() );\n  \n  if(internal::packet_traits<float>::Vectorizable)\n  {\n    VERIFY(test_assign(Matrix<float,3,3>(),Matrix<float,3,3>()+Matrix<float,3,3>(),\n      EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : LinearTraversal,CompleteUnrolling));\n      \n    VERIFY(test_redux(Matrix<float,5,2>(),\n      EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : DefaultTraversal,CompleteUnrolling));\n  }\n  \n  if(internal::packet_traits<double>::Vectorizable)\n  {\n    VERIFY(test_assign(Matrix<double,3,3>(),Matrix<double,3,3>()+Matrix<double,3,3>(),\n      EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : LinearTraversal,CompleteUnrolling));\n    \n    VERIFY(test_redux(Matrix<double,7,3>(),\n      EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : DefaultTraversal,CompleteUnrolling));\n  }\n#endif // EIGEN_VECTORIZE\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/vectorwiseop.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define TEST_ENABLE_TEMPORARY_TRACKING\n#define EIGEN_NO_STATIC_ASSERT\n\n#include \"main.h\"\n\ntemplate<typename ArrayType> void vectorwiseop_array(const ArrayType& m)\n{\n  typedef typename ArrayType::Scalar Scalar;\n  typedef Array<Scalar, ArrayType::RowsAtCompileTime, 1> ColVectorType;\n  typedef Array<Scalar, 1, ArrayType::ColsAtCompileTime> RowVectorType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n  Index r = internal::random<Index>(0, rows-1),\n        c = internal::random<Index>(0, cols-1);\n\n  ArrayType m1 = ArrayType::Random(rows, cols),\n            m2(rows, cols),\n            m3(rows, cols);\n\n  ColVectorType colvec = ColVectorType::Random(rows);\n  RowVectorType rowvec = RowVectorType::Random(cols);\n\n  // test addition\n\n  m2 = m1;\n  m2.colwise() += colvec;\n  VERIFY_IS_APPROX(m2, m1.colwise() + colvec);\n  VERIFY_IS_APPROX(m2.col(c), m1.col(c) + colvec);\n\n  VERIFY_RAISES_ASSERT(m2.colwise() += colvec.transpose());\n  VERIFY_RAISES_ASSERT(m1.colwise() + colvec.transpose());\n\n  m2 = m1;\n  m2.rowwise() += rowvec;\n  VERIFY_IS_APPROX(m2, m1.rowwise() + rowvec);\n  VERIFY_IS_APPROX(m2.row(r), m1.row(r) + rowvec);\n\n  VERIFY_RAISES_ASSERT(m2.rowwise() += rowvec.transpose());\n  VERIFY_RAISES_ASSERT(m1.rowwise() + rowvec.transpose());\n\n  // test substraction\n\n  m2 = m1;\n  m2.colwise() -= colvec;\n  VERIFY_IS_APPROX(m2, m1.colwise() - colvec);\n  VERIFY_IS_APPROX(m2.col(c), m1.col(c) - colvec);\n\n  VERIFY_RAISES_ASSERT(m2.colwise() -= colvec.transpose());\n  VERIFY_RAISES_ASSERT(m1.colwise() - colvec.transpose());\n\n  m2 = m1;\n  m2.rowwise() -= rowvec;\n  VERIFY_IS_APPROX(m2, m1.rowwise() - rowvec);\n  VERIFY_IS_APPROX(m2.row(r), m1.row(r) - rowvec);\n\n  VERIFY_RAISES_ASSERT(m2.rowwise() -= rowvec.transpose());\n  VERIFY_RAISES_ASSERT(m1.rowwise() - rowvec.transpose());\n\n  // test multiplication\n\n  m2 = m1;\n  m2.colwise() *= colvec;\n  VERIFY_IS_APPROX(m2, m1.colwise() * colvec);\n  VERIFY_IS_APPROX(m2.col(c), m1.col(c) * colvec);\n\n  VERIFY_RAISES_ASSERT(m2.colwise() *= colvec.transpose());\n  VERIFY_RAISES_ASSERT(m1.colwise() * colvec.transpose());\n\n  m2 = m1;\n  m2.rowwise() *= rowvec;\n  VERIFY_IS_APPROX(m2, m1.rowwise() * rowvec);\n  VERIFY_IS_APPROX(m2.row(r), m1.row(r) * rowvec);\n\n  VERIFY_RAISES_ASSERT(m2.rowwise() *= rowvec.transpose());\n  VERIFY_RAISES_ASSERT(m1.rowwise() * rowvec.transpose());\n\n  // test quotient\n\n  m2 = m1;\n  m2.colwise() /= colvec;\n  VERIFY_IS_APPROX(m2, m1.colwise() / colvec);\n  VERIFY_IS_APPROX(m2.col(c), m1.col(c) / colvec);\n\n  VERIFY_RAISES_ASSERT(m2.colwise() /= colvec.transpose());\n  VERIFY_RAISES_ASSERT(m1.colwise() / colvec.transpose());\n\n  m2 = m1;\n  m2.rowwise() /= rowvec;\n  VERIFY_IS_APPROX(m2, m1.rowwise() / rowvec);\n  VERIFY_IS_APPROX(m2.row(r), m1.row(r) / rowvec);\n\n  VERIFY_RAISES_ASSERT(m2.rowwise() /= rowvec.transpose());\n  VERIFY_RAISES_ASSERT(m1.rowwise() / rowvec.transpose());\n\n  m2 = m1;\n  // yes, there might be an aliasing issue there but \".rowwise() /=\"\n  // is supposed to evaluate \" m2.colwise().sum()\" into a temporary to avoid\n  // evaluating the reduction multiple times\n  if(ArrayType::RowsAtCompileTime>2 || ArrayType::RowsAtCompileTime==Dynamic)\n  {\n    m2.rowwise() /= m2.colwise().sum();\n    VERIFY_IS_APPROX(m2, m1.rowwise() / m1.colwise().sum());\n  }\n\n  // all/any\n  Array<bool,Dynamic,Dynamic> mb(rows,cols);\n  mb = (m1.real()<=0.7).colwise().all();\n  VERIFY( (mb.col(c) == (m1.real().col(c)<=0.7).all()).all() );\n  mb = (m1.real()<=0.7).rowwise().all();\n  VERIFY( (mb.row(r) == (m1.real().row(r)<=0.7).all()).all() );\n\n  mb = (m1.real()>=0.7).colwise().any();\n  VERIFY( (mb.col(c) == (m1.real().col(c)>=0.7).any()).all() );\n  mb = (m1.real()>=0.7).rowwise().any();\n  VERIFY( (mb.row(r) == (m1.real().row(r)>=0.7).any()).all() );\n}\n\ntemplate<typename MatrixType> void vectorwiseop_matrix(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> ColVectorType;\n  typedef Matrix<Scalar, 1, MatrixType::ColsAtCompileTime> RowVectorType;\n  typedef Matrix<RealScalar, MatrixType::RowsAtCompileTime, 1> RealColVectorType;\n  typedef Matrix<RealScalar, 1, MatrixType::ColsAtCompileTime> RealRowVectorType;\n  typedef Matrix<Scalar,Dynamic,Dynamic> MatrixX;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n  Index r = internal::random<Index>(0, rows-1),\n        c = internal::random<Index>(0, cols-1);\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n            m2(rows, cols),\n            m3(rows, cols);\n\n  ColVectorType colvec = ColVectorType::Random(rows);\n  RowVectorType rowvec = RowVectorType::Random(cols);\n  RealColVectorType rcres;\n  RealRowVectorType rrres;\n\n  // test broadcast assignment\n  m2 = m1;\n  m2.colwise() = colvec;\n  for(Index j=0; j<cols; ++j)\n    VERIFY_IS_APPROX(m2.col(j), colvec);\n  m2.rowwise() = rowvec;\n  for(Index i=0; i<rows; ++i)\n    VERIFY_IS_APPROX(m2.row(i), rowvec);\n  if(rows>1)\n    VERIFY_RAISES_ASSERT(m2.colwise() = colvec.transpose());\n  if(cols>1)\n    VERIFY_RAISES_ASSERT(m2.rowwise() = rowvec.transpose());\n\n  // test addition\n\n  m2 = m1;\n  m2.colwise() += colvec;\n  VERIFY_IS_APPROX(m2, m1.colwise() + colvec);\n  VERIFY_IS_APPROX(m2.col(c), m1.col(c) + colvec);\n\n  if(rows>1)\n  {\n    VERIFY_RAISES_ASSERT(m2.colwise() += colvec.transpose());\n    VERIFY_RAISES_ASSERT(m1.colwise() + colvec.transpose());\n  }\n\n  m2 = m1;\n  m2.rowwise() += rowvec;\n  VERIFY_IS_APPROX(m2, m1.rowwise() + rowvec);\n  VERIFY_IS_APPROX(m2.row(r), m1.row(r) + rowvec);\n\n  if(cols>1)\n  {\n    VERIFY_RAISES_ASSERT(m2.rowwise() += rowvec.transpose());\n    VERIFY_RAISES_ASSERT(m1.rowwise() + rowvec.transpose());\n  }\n\n  // test substraction\n\n  m2 = m1;\n  m2.colwise() -= colvec;\n  VERIFY_IS_APPROX(m2, m1.colwise() - colvec);\n  VERIFY_IS_APPROX(m2.col(c), m1.col(c) - colvec);\n\n  if(rows>1)\n  {\n    VERIFY_RAISES_ASSERT(m2.colwise() -= colvec.transpose());\n    VERIFY_RAISES_ASSERT(m1.colwise() - colvec.transpose());\n  }\n\n  m2 = m1;\n  m2.rowwise() -= rowvec;\n  VERIFY_IS_APPROX(m2, m1.rowwise() - rowvec);\n  VERIFY_IS_APPROX(m2.row(r), m1.row(r) - rowvec);\n\n  if(cols>1)\n  {\n    VERIFY_RAISES_ASSERT(m2.rowwise() -= rowvec.transpose());\n    VERIFY_RAISES_ASSERT(m1.rowwise() - rowvec.transpose());\n  }\n\n  // ------ partial reductions ------\n\n  #define TEST_PARTIAL_REDUX_BASIC(FUNC,ROW,COL,PREPROCESS) {                          \\\n    ROW = m1 PREPROCESS .colwise().FUNC ;                                              \\\n    for(Index k=0; k<cols; ++k) VERIFY_IS_APPROX(ROW(k), m1.col(k) PREPROCESS .FUNC ); \\\n    COL = m1 PREPROCESS .rowwise().FUNC ;                                              \\\n    for(Index k=0; k<rows; ++k) VERIFY_IS_APPROX(COL(k), m1.row(k) PREPROCESS .FUNC ); \\\n  }\n\n  TEST_PARTIAL_REDUX_BASIC(sum(),        rowvec,colvec,EIGEN_EMPTY);\n  TEST_PARTIAL_REDUX_BASIC(prod(),       rowvec,colvec,EIGEN_EMPTY);\n  TEST_PARTIAL_REDUX_BASIC(mean(),       rowvec,colvec,EIGEN_EMPTY);\n  TEST_PARTIAL_REDUX_BASIC(minCoeff(),   rrres, rcres, .real());\n  TEST_PARTIAL_REDUX_BASIC(maxCoeff(),   rrres, rcres, .real());\n  TEST_PARTIAL_REDUX_BASIC(norm(),       rrres, rcres, EIGEN_EMPTY);\n  TEST_PARTIAL_REDUX_BASIC(squaredNorm(),rrres, rcres, EIGEN_EMPTY);\n  TEST_PARTIAL_REDUX_BASIC(redux(internal::scalar_sum_op<Scalar,Scalar>()),rowvec,colvec,EIGEN_EMPTY);\n\n  VERIFY_IS_APPROX(m1.cwiseAbs().colwise().sum(), m1.colwise().template lpNorm<1>());\n  VERIFY_IS_APPROX(m1.cwiseAbs().rowwise().sum(), m1.rowwise().template lpNorm<1>());\n  VERIFY_IS_APPROX(m1.cwiseAbs().colwise().maxCoeff(), m1.colwise().template lpNorm<Infinity>());\n  VERIFY_IS_APPROX(m1.cwiseAbs().rowwise().maxCoeff(), m1.rowwise().template lpNorm<Infinity>());\n\n  // regression for bug 1158\n  VERIFY_IS_APPROX(m1.cwiseAbs().colwise().sum().x(), m1.col(0).cwiseAbs().sum());\n\n  // test normalized\n  m2 = m1.colwise().normalized();\n  VERIFY_IS_APPROX(m2.col(c), m1.col(c).normalized());\n  m2 = m1.rowwise().normalized();\n  VERIFY_IS_APPROX(m2.row(r), m1.row(r).normalized());\n\n  // test normalize\n  m2 = m1;\n  m2.colwise().normalize();\n  VERIFY_IS_APPROX(m2.col(c), m1.col(c).normalized());\n  m2 = m1;\n  m2.rowwise().normalize();\n  VERIFY_IS_APPROX(m2.row(r), m1.row(r).normalized());\n\n  // test with partial reduction of products\n  Matrix<Scalar,MatrixType::RowsAtCompileTime,MatrixType::RowsAtCompileTime> m1m1 = m1 * m1.transpose();\n  VERIFY_IS_APPROX( (m1 * m1.transpose()).colwise().sum(), m1m1.colwise().sum());\n  Matrix<Scalar,1,MatrixType::RowsAtCompileTime> tmp(rows);\n  VERIFY_EVALUATION_COUNT( tmp = (m1 * m1.transpose()).colwise().sum(), 1);\n\n  m2 = m1.rowwise() - (m1.colwise().sum()/RealScalar(m1.rows())).eval();\n  m1 = m1.rowwise() - (m1.colwise().sum()/RealScalar(m1.rows()));\n  VERIFY_IS_APPROX( m1, m2 );\n  VERIFY_EVALUATION_COUNT( m2 = (m1.rowwise() - m1.colwise().sum()/RealScalar(m1.rows())), (MatrixType::RowsAtCompileTime!=1 ? 1 : 0) );\n\n  // test empty expressions\n  VERIFY_IS_APPROX(m1.matrix().middleCols(0,0).rowwise().sum().eval(), MatrixX::Zero(rows,1));\n  VERIFY_IS_APPROX(m1.matrix().middleRows(0,0).colwise().sum().eval(), MatrixX::Zero(1,cols));\n  VERIFY_IS_APPROX(m1.matrix().middleCols(0,fix<0>).rowwise().sum().eval(), MatrixX::Zero(rows,1));\n  VERIFY_IS_APPROX(m1.matrix().middleRows(0,fix<0>).colwise().sum().eval(), MatrixX::Zero(1,cols));\n\n  VERIFY_IS_APPROX(m1.matrix().middleCols(0,0).rowwise().prod().eval(), MatrixX::Ones(rows,1));\n  VERIFY_IS_APPROX(m1.matrix().middleRows(0,0).colwise().prod().eval(), MatrixX::Ones(1,cols));\n  VERIFY_IS_APPROX(m1.matrix().middleCols(0,fix<0>).rowwise().prod().eval(), MatrixX::Ones(rows,1));\n  VERIFY_IS_APPROX(m1.matrix().middleRows(0,fix<0>).colwise().prod().eval(), MatrixX::Ones(1,cols));\n  \n  VERIFY_IS_APPROX(m1.matrix().middleCols(0,0).rowwise().squaredNorm().eval(), MatrixX::Zero(rows,1));\n\n  VERIFY_RAISES_ASSERT(m1.real().middleCols(0,0).rowwise().minCoeff().eval());\n  VERIFY_RAISES_ASSERT(m1.real().middleRows(0,0).colwise().maxCoeff().eval());\n  VERIFY_IS_EQUAL(m1.real().middleRows(0,0).rowwise().maxCoeff().eval().rows(),0);\n  VERIFY_IS_EQUAL(m1.real().middleCols(0,0).colwise().maxCoeff().eval().cols(),0);\n  VERIFY_IS_EQUAL(m1.real().middleRows(0,fix<0>).rowwise().maxCoeff().eval().rows(),0);\n  VERIFY_IS_EQUAL(m1.real().middleCols(0,fix<0>).colwise().maxCoeff().eval().cols(),0);\n}\n\nEIGEN_DECLARE_TEST(vectorwiseop)\n{\n  CALL_SUBTEST_1( vectorwiseop_array(Array22cd()) );\n  CALL_SUBTEST_2( vectorwiseop_array(Array<double, 3, 2>()) );\n  CALL_SUBTEST_3( vectorwiseop_array(ArrayXXf(3, 4)) );\n  CALL_SUBTEST_4( vectorwiseop_matrix(Matrix4cf()) );\n  CALL_SUBTEST_5( vectorwiseop_matrix(Matrix4f()) );\n  CALL_SUBTEST_5( vectorwiseop_matrix(Vector4f()) );\n  CALL_SUBTEST_5( vectorwiseop_matrix(Matrix<float,4,5>()) );\n  CALL_SUBTEST_6( vectorwiseop_matrix(MatrixXd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  CALL_SUBTEST_7( vectorwiseop_matrix(VectorXd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  CALL_SUBTEST_7( vectorwiseop_matrix(RowVectorXd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/visitor.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void matrixVisitor(const MatrixType& p)\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index rows = p.rows();\n  Index cols = p.cols();\n\n  // construct a random matrix where all coefficients are different\n  MatrixType m;\n  m = MatrixType::Random(rows, cols);\n  for(Index i = 0; i < m.size(); i++)\n    for(Index i2 = 0; i2 < i; i2++)\n      while(m(i) == m(i2)) // yes, ==\n        m(i) = internal::random<Scalar>();\n  \n  Scalar minc = Scalar(1000), maxc = Scalar(-1000);\n  Index minrow=0,mincol=0,maxrow=0,maxcol=0;\n  for(Index j = 0; j < cols; j++)\n  for(Index i = 0; i < rows; i++)\n  {\n    if(m(i,j) < minc)\n    {\n      minc = m(i,j);\n      minrow = i;\n      mincol = j;\n    }\n    if(m(i,j) > maxc)\n    {\n      maxc = m(i,j);\n      maxrow = i;\n      maxcol = j;\n    }\n  }\n  Index eigen_minrow, eigen_mincol, eigen_maxrow, eigen_maxcol;\n  Scalar eigen_minc, eigen_maxc;\n  eigen_minc = m.minCoeff(&eigen_minrow,&eigen_mincol);\n  eigen_maxc = m.maxCoeff(&eigen_maxrow,&eigen_maxcol);\n  VERIFY(minrow == eigen_minrow);\n  VERIFY(maxrow == eigen_maxrow);\n  VERIFY(mincol == eigen_mincol);\n  VERIFY(maxcol == eigen_maxcol);\n  VERIFY_IS_APPROX(minc, eigen_minc);\n  VERIFY_IS_APPROX(maxc, eigen_maxc);\n  VERIFY_IS_APPROX(minc, m.minCoeff());\n  VERIFY_IS_APPROX(maxc, m.maxCoeff());\n\n  eigen_maxc = (m.adjoint()*m).maxCoeff(&eigen_maxrow,&eigen_maxcol);\n  Index maxrow2=0,maxcol2=0;\n  eigen_maxc = (m.adjoint()*m).eval().maxCoeff(&maxrow2,&maxcol2);\n  VERIFY(maxrow2 == eigen_maxrow);\n  VERIFY(maxcol2 == eigen_maxcol);\n\n  if (!NumTraits<Scalar>::IsInteger && m.size() > 2) {\n    // Test NaN propagation by replacing an element with NaN.\n    bool stop = false;\n    for (Index j = 0; j < cols && !stop; ++j) {\n      for (Index i = 0; i < rows && !stop; ++i) {\n        if (!(j == mincol && i == minrow) &&\n            !(j == maxcol && i == maxrow)) {\n          m(i,j) = NumTraits<Scalar>::quiet_NaN();\n          stop = true;\n          break;\n        }\n      }\n    }\n\n    eigen_minc = m.template minCoeff<PropagateNumbers>(&eigen_minrow, &eigen_mincol);\n    eigen_maxc = m.template maxCoeff<PropagateNumbers>(&eigen_maxrow, &eigen_maxcol);\n    VERIFY(minrow == eigen_minrow);\n    VERIFY(maxrow == eigen_maxrow);\n    VERIFY(mincol == eigen_mincol);\n    VERIFY(maxcol == eigen_maxcol);\n    VERIFY_IS_APPROX(minc, eigen_minc);\n    VERIFY_IS_APPROX(maxc, eigen_maxc);\n    VERIFY_IS_APPROX(minc, m.template minCoeff<PropagateNumbers>());\n    VERIFY_IS_APPROX(maxc, m.template maxCoeff<PropagateNumbers>());\n\n    eigen_minc = m.template minCoeff<PropagateNaN>(&eigen_minrow, &eigen_mincol);\n    eigen_maxc = m.template maxCoeff<PropagateNaN>(&eigen_maxrow, &eigen_maxcol);\n    VERIFY(minrow != eigen_minrow || mincol != eigen_mincol);\n    VERIFY(maxrow != eigen_maxrow || maxcol != eigen_maxcol);\n    VERIFY((numext::isnan)(eigen_minc));\n    VERIFY((numext::isnan)(eigen_maxc));\n  }\n\n}\n\ntemplate<typename VectorType> void vectorVisitor(const VectorType& w)\n{\n  typedef typename VectorType::Scalar Scalar;\n\n  Index size = w.size();\n\n  // construct a random vector where all coefficients are different\n  VectorType v;\n  v = VectorType::Random(size);\n  for(Index i = 0; i < size; i++)\n    for(Index i2 = 0; i2 < i; i2++)\n      while(v(i) == v(i2)) // yes, ==\n        v(i) = internal::random<Scalar>();\n  \n  Scalar minc = v(0), maxc = v(0);\n  Index minidx=0, maxidx=0;\n  for(Index i = 0; i < size; i++)\n  {\n    if(v(i) < minc)\n    {\n      minc = v(i);\n      minidx = i;\n    }\n    if(v(i) > maxc)\n    {\n      maxc = v(i);\n      maxidx = i;\n    }\n  }\n  Index eigen_minidx, eigen_maxidx;\n  Scalar eigen_minc, eigen_maxc;\n  eigen_minc = v.minCoeff(&eigen_minidx);\n  eigen_maxc = v.maxCoeff(&eigen_maxidx);\n  VERIFY(minidx == eigen_minidx);\n  VERIFY(maxidx == eigen_maxidx);\n  VERIFY_IS_APPROX(minc, eigen_minc);\n  VERIFY_IS_APPROX(maxc, eigen_maxc);\n  VERIFY_IS_APPROX(minc, v.minCoeff());\n  VERIFY_IS_APPROX(maxc, v.maxCoeff());\n  \n  Index idx0 = internal::random<Index>(0,size-1);\n  Index idx1 = eigen_minidx;\n  Index idx2 = eigen_maxidx;\n  VectorType v1(v), v2(v);\n  v1(idx0) = v1(idx1);\n  v2(idx0) = v2(idx2);\n  v1.minCoeff(&eigen_minidx);\n  v2.maxCoeff(&eigen_maxidx);\n  VERIFY(eigen_minidx == (std::min)(idx0,idx1));\n  VERIFY(eigen_maxidx == (std::min)(idx0,idx2));\n\n  if (!NumTraits<Scalar>::IsInteger && size > 2) {\n    // Test NaN propagation by replacing an element with NaN.\n    for (Index i = 0; i < size; ++i) {\n      if (i != minidx && i != maxidx) {\n        v(i) = NumTraits<Scalar>::quiet_NaN();\n        break;\n      }\n    }\n    eigen_minc = v.template minCoeff<PropagateNumbers>(&eigen_minidx);\n    eigen_maxc = v.template maxCoeff<PropagateNumbers>(&eigen_maxidx);\n    VERIFY(minidx == eigen_minidx);\n    VERIFY(maxidx == eigen_maxidx);\n    VERIFY_IS_APPROX(minc, eigen_minc);\n    VERIFY_IS_APPROX(maxc, eigen_maxc);\n    VERIFY_IS_APPROX(minc, v.template minCoeff<PropagateNumbers>());\n    VERIFY_IS_APPROX(maxc, v.template maxCoeff<PropagateNumbers>());\n\n    eigen_minc = v.template minCoeff<PropagateNaN>(&eigen_minidx);\n    eigen_maxc = v.template maxCoeff<PropagateNaN>(&eigen_maxidx);\n    VERIFY(minidx != eigen_minidx);\n    VERIFY(maxidx != eigen_maxidx);\n    VERIFY((numext::isnan)(eigen_minc));\n    VERIFY((numext::isnan)(eigen_maxc));\n  }\n}\n\nEIGEN_DECLARE_TEST(visitor)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( matrixVisitor(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( matrixVisitor(Matrix2f()) );\n    CALL_SUBTEST_3( matrixVisitor(Matrix4d()) );\n    CALL_SUBTEST_4( matrixVisitor(MatrixXd(8, 12)) );\n    CALL_SUBTEST_5( matrixVisitor(Matrix<double,Dynamic,Dynamic,RowMajor>(20, 20)) );\n    CALL_SUBTEST_6( matrixVisitor(MatrixXi(8, 12)) );\n  }\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_7( vectorVisitor(Vector4f()) );\n    CALL_SUBTEST_7( vectorVisitor(Matrix<int,12,1>()) );\n    CALL_SUBTEST_8( vectorVisitor(VectorXd(10)) );\n    CALL_SUBTEST_9( vectorVisitor(RowVectorXd(10)) );\n    CALL_SUBTEST_10( vectorVisitor(VectorXf(33)) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/test/zerosized.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n\ntemplate<typename MatrixType> void zeroReduction(const MatrixType& m) {\n  // Reductions that must hold for zero sized objects\n  VERIFY(m.all());\n  VERIFY(!m.any());\n  VERIFY(m.prod()==1);\n  VERIFY(m.sum()==0);\n  VERIFY(m.norm()==0);\n  VERIFY(m.squaredNorm()==0);\n  VERIFY(m.count()==0);\n  VERIFY(m.allFinite());\n  VERIFY(!m.hasNaN());\n  VERIFY_RAISES_ASSERT( m.minCoeff() );\n  VERIFY_RAISES_ASSERT( m.maxCoeff() );\n  Index i,j;\n  VERIFY_RAISES_ASSERT( m.minCoeff(&i,&j) );\n  VERIFY_RAISES_ASSERT( m.maxCoeff(&i,&j) );\n  VERIFY_RAISES_ASSERT( m.reshaped().minCoeff(&i) );\n  VERIFY_RAISES_ASSERT( m.reshaped().maxCoeff(&i) );\n}\n\n\ntemplate<typename MatrixType> void zeroSizedMatrix()\n{\n  MatrixType t1;\n  typedef typename MatrixType::Scalar Scalar;\n\n  if (MatrixType::SizeAtCompileTime == Dynamic || MatrixType::SizeAtCompileTime == 0)\n  {\n    zeroReduction(t1);\n    if (MatrixType::RowsAtCompileTime == Dynamic)\n      VERIFY(t1.rows() == 0);\n    if (MatrixType::ColsAtCompileTime == Dynamic)\n      VERIFY(t1.cols() == 0);\n\n    if (MatrixType::RowsAtCompileTime == Dynamic && MatrixType::ColsAtCompileTime == Dynamic)\n    {\n\n      MatrixType t2(0, 0), t3(t1);\n      VERIFY(t2.rows() == 0);\n      VERIFY(t2.cols() == 0);\n\n      zeroReduction(t2);\n      VERIFY(t1==t2);\n    }\n  }\n\n  if(MatrixType::MaxColsAtCompileTime!=0 && MatrixType::MaxRowsAtCompileTime!=0)\n  {\n    Index rows = MatrixType::RowsAtCompileTime==Dynamic ? internal::random<Index>(1,10) : Index(MatrixType::RowsAtCompileTime);\n    Index cols = MatrixType::ColsAtCompileTime==Dynamic ? internal::random<Index>(1,10) : Index(MatrixType::ColsAtCompileTime);\n    MatrixType m(rows,cols);\n    zeroReduction(m.template block<0,MatrixType::ColsAtCompileTime>(0,0,0,cols));\n    zeroReduction(m.template block<MatrixType::RowsAtCompileTime,0>(0,0,rows,0));\n    zeroReduction(m.template block<0,1>(0,0));\n    zeroReduction(m.template block<1,0>(0,0));\n    Matrix<Scalar,Dynamic,Dynamic> prod = m.template block<MatrixType::RowsAtCompileTime,0>(0,0,rows,0) * m.template block<0,MatrixType::ColsAtCompileTime>(0,0,0,cols);\n    VERIFY(prod.rows()==rows && prod.cols()==cols);\n    VERIFY(prod.isZero());\n    prod = m.template block<1,0>(0,0) * m.template block<0,1>(0,0);\n    VERIFY(prod.size()==1);\n    VERIFY(prod.isZero());\n  }\n}\n\ntemplate<typename VectorType> void zeroSizedVector()\n{\n  VectorType t1;\n\n  if (VectorType::SizeAtCompileTime == Dynamic || VectorType::SizeAtCompileTime==0)\n  {\n    zeroReduction(t1);\n    VERIFY(t1.size() == 0);\n    VectorType t2(DenseIndex(0)); // DenseIndex disambiguates with 0-the-null-pointer (error with gcc 4.4 and MSVC8)\n    VERIFY(t2.size() == 0);\n    zeroReduction(t2);\n\n    VERIFY(t1==t2);\n  }\n}\n\nEIGEN_DECLARE_TEST(zerosized)\n{\n  zeroSizedMatrix<Matrix2d>();\n  zeroSizedMatrix<Matrix3i>();\n  zeroSizedMatrix<Matrix<float, 2, Dynamic> >();\n  zeroSizedMatrix<MatrixXf>();\n  zeroSizedMatrix<Matrix<float, 0, 0> >();\n  zeroSizedMatrix<Matrix<float, Dynamic, 0, 0, 0, 0> >();\n  zeroSizedMatrix<Matrix<float, 0, Dynamic, 0, 0, 0> >();\n  zeroSizedMatrix<Matrix<float, Dynamic, Dynamic, 0, 0, 0> >();\n  zeroSizedMatrix<Matrix<float, 0, 4> >();\n  zeroSizedMatrix<Matrix<float, 4, 0> >();\n\n  zeroSizedVector<Vector2d>();\n  zeroSizedVector<Vector3i>();\n  zeroSizedVector<VectorXf>();\n  zeroSizedVector<Matrix<float, 0, 1> >();\n  zeroSizedVector<Matrix<float, 1, 0> >();\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/CMakeLists.txt",
    "content": "add_subdirectory(Eigen)\nif(EIGEN_BUILD_DOC)\n  add_subdirectory(doc EXCLUDE_FROM_ALL)\nendif()\nif(BUILD_TESTING)\n  if(EIGEN_LEAVE_TEST_IN_ALL_TARGET)\n    add_subdirectory(test) # can't do EXCLUDE_FROM_ALL here, breaks CTest\n  else()\n    add_subdirectory(test EXCLUDE_FROM_ALL)\n  endif()\nendif()\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/AdolcForward",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ADLOC_FORWARD\n#define EIGEN_ADLOC_FORWARD\n\n//--------------------------------------------------------------------------------\n//\n// This file provides support for adolc's adouble type in forward mode.\n// ADOL-C is a C++ automatic differentiation library,\n// see https://projects.coin-or.org/ADOL-C for more information.\n//\n// Note that the maximal number of directions is controlled by\n// the preprocessor token NUMBER_DIRECTIONS. The default is 2.\n//\n//--------------------------------------------------------------------------------\n\n#define ADOLC_TAPELESS\n#ifndef NUMBER_DIRECTIONS\n# define NUMBER_DIRECTIONS 2\n#endif\n#include <adolc/adtl.h>\n\n// adolc defines some very stupid macros:\n#if defined(malloc)\n# undef malloc\n#endif\n\n#if defined(calloc)\n# undef calloc\n#endif\n\n#if defined(realloc)\n# undef realloc\n#endif\n\n#include \"../../Eigen/Core\"\n\nnamespace Eigen {\n\n/**\n  * \\defgroup AdolcForward_Module Adolc forward module\n  * This module provides support for adolc's adouble type in forward mode.\n  * ADOL-C is a C++ automatic differentiation library,\n  * see https://projects.coin-or.org/ADOL-C for more information.\n  * It mainly consists in:\n  *  - a struct Eigen::NumTraits<adtl::adouble> specialization\n  *  - overloads of internal::* math function for adtl::adouble type.\n  *\n  * Note that the maximal number of directions is controlled by\n  * the preprocessor token NUMBER_DIRECTIONS. The default is 2.\n  *\n  * \\code\n  * #include <unsupported/Eigen/AdolcSupport>\n  * \\endcode\n  */\n  //@{\n\n} // namespace Eigen\n\n// Eigen's require a few additional functions which must be defined in the same namespace\n// than the custom scalar type own namespace\nnamespace adtl {\n\ninline const adouble& conj(const adouble& x)  { return x; }\ninline const adouble& real(const adouble& x)  { return x; }\ninline adouble imag(const adouble&)    { return 0.; }\ninline adouble abs(const adouble&  x)  { return fabs(x); }\ninline adouble abs2(const adouble& x)  { return x*x; }\n\ninline bool (isinf)(const adouble& x) { return (Eigen::numext::isinf)(x.getValue()); }\ninline bool (isnan)(const adouble& x) { return (Eigen::numext::isnan)(x.getValue()); }\n\n}\n\nnamespace Eigen {\n\ntemplate<> struct NumTraits<adtl::adouble>\n    : NumTraits<double>\n{\n  typedef adtl::adouble Real;\n  typedef adtl::adouble NonInteger;\n  typedef adtl::adouble Nested;\n  enum {\n    IsComplex = 0,\n    IsInteger = 0,\n    IsSigned = 1,\n    RequireInitialization = 1,\n    ReadCost = 1,\n    AddCost = 1,\n    MulCost = 1\n  };\n};\n\ntemplate<typename Functor> class AdolcForwardJacobian : public Functor\n{\n  typedef adtl::adouble ActiveScalar;\npublic:\n\n  AdolcForwardJacobian() : Functor() {}\n  AdolcForwardJacobian(const Functor& f) : Functor(f) {}\n\n  // forward constructors\n  template<typename T0>\n  AdolcForwardJacobian(const T0& a0) : Functor(a0) {}\n  template<typename T0, typename T1>\n  AdolcForwardJacobian(const T0& a0, const T1& a1) : Functor(a0, a1) {}\n  template<typename T0, typename T1, typename T2>\n  AdolcForwardJacobian(const T0& a0, const T1& a1, const T1& a2) : Functor(a0, a1, a2) {}\n\n  typedef typename Functor::InputType InputType;\n  typedef typename Functor::ValueType ValueType;\n  typedef typename Functor::JacobianType JacobianType;\n\n  typedef Matrix<ActiveScalar, InputType::SizeAtCompileTime, 1> ActiveInput;\n  typedef Matrix<ActiveScalar, ValueType::SizeAtCompileTime, 1> ActiveValue;\n\n  void operator() (const InputType& x, ValueType* v, JacobianType* _jac) const\n  {\n    eigen_assert(v!=0);\n    if (!_jac)\n    {\n      Functor::operator()(x, v);\n      return;\n    }\n\n    JacobianType& jac = *_jac;\n\n    ActiveInput ax = x.template cast<ActiveScalar>();\n    ActiveValue av(jac.rows());\n\n    for (int j=0; j<jac.cols(); j++)\n      for (int i=0; i<jac.cols(); i++)\n        ax[i].setADValue(j, i==j ? 1 : 0);\n\n    Functor::operator()(ax, &av);\n\n    for (int i=0; i<jac.rows(); i++)\n    {\n      (*v)[i] = av[i].getValue();\n      for (int j=0; j<jac.cols(); j++)\n        jac.coeffRef(i,j) = av[i].getADValue(j);\n    }\n  }\nprotected:\n\n};\n\n//@}\n\n}\n\n#endif // EIGEN_ADLOC_FORWARD\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/AlignedVector3",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ALIGNED_VECTOR3\n#define EIGEN_ALIGNED_VECTOR3\n\n#include \"../../Eigen/Geometry\"\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\nnamespace Eigen {\n\n/**\n  * \\defgroup AlignedVector3_Module Aligned vector3 module\n  *\n  * \\code\n  * #include <unsupported/Eigen/AlignedVector3>\n  * \\endcode\n  */\n  //@{\n\n\n/** \\class AlignedVector3\n  *\n  * \\brief A vectorization friendly 3D vector\n  *\n  * This class represents a 3D vector internally using a 4D vector\n  * such that vectorization can be seamlessly enabled. Of course,\n  * the same result can be achieved by directly using a 4D vector.\n  * This class makes this process simpler.\n  *\n  */\n// TODO specialize Cwise\ntemplate<typename Scalar_> class AlignedVector3;\n\nnamespace internal {\ntemplate<typename Scalar_> struct traits<AlignedVector3<Scalar_> >\n  : traits<Matrix<Scalar_,3,1,0,4,1> >\n{\n};\n}\n\ntemplate<typename Scalar_> class AlignedVector3\n  : public MatrixBase<AlignedVector3<Scalar_> >\n{\n    typedef Matrix<Scalar_,4,1> CoeffType;\n    CoeffType m_coeffs;\n  public:\n\n    typedef MatrixBase<AlignedVector3<Scalar_> > Base;\n    EIGEN_DENSE_PUBLIC_INTERFACE(AlignedVector3)\n    using Base::operator*;\n\n    inline Index rows() const { return 3; }\n    inline Index cols() const { return 1; }\n    \n    Scalar* data() { return m_coeffs.data(); }\n    const Scalar* data() const { return m_coeffs.data(); }\n    Index innerStride() const { return 1; }\n    Index outerStride() const { return 3; }\n\n    inline const Scalar& coeff(Index row, Index col) const\n    { return m_coeffs.coeff(row, col); }\n\n    inline Scalar& coeffRef(Index row, Index col)\n    { return m_coeffs.coeffRef(row, col); }\n\n    inline const Scalar& coeff(Index index) const\n    { return m_coeffs.coeff(index); }\n\n    inline Scalar& coeffRef(Index index)\n    { return m_coeffs.coeffRef(index);}\n\n\n    inline AlignedVector3()\n    {}\n\n    inline AlignedVector3(const Scalar& x, const Scalar& y, const Scalar& z)\n      : m_coeffs(x, y, z, Scalar(0))\n    {}\n\n    inline AlignedVector3(const AlignedVector3& other)\n      : Base(), m_coeffs(other.m_coeffs)\n    {}\n\n    template<typename XprType, int Size=XprType::SizeAtCompileTime>\n    struct generic_assign_selector {};\n\n    template<typename XprType> struct generic_assign_selector<XprType,4>\n    {\n      inline static void run(AlignedVector3& dest, const XprType& src)\n      {\n        dest.m_coeffs = src;\n      }\n    };\n\n    template<typename XprType> struct generic_assign_selector<XprType,3>\n    {\n      inline static void run(AlignedVector3& dest, const XprType& src)\n      {\n        dest.m_coeffs.template head<3>() = src;\n        dest.m_coeffs.w() = Scalar(0);\n      }\n    };\n\n    template<typename Derived>\n    inline AlignedVector3(const MatrixBase<Derived>& other)\n    {\n      generic_assign_selector<Derived>::run(*this,other.derived());\n    }\n\n    inline AlignedVector3& operator=(const AlignedVector3& other)\n    { m_coeffs = other.m_coeffs; return *this; }\n\n    template <typename Derived>\n    inline AlignedVector3& operator=(const MatrixBase<Derived>& other)\n    {\n      generic_assign_selector<Derived>::run(*this,other.derived());\n      return *this;\n    }\n\n    inline AlignedVector3 operator+(const AlignedVector3& other) const\n    { return AlignedVector3(m_coeffs + other.m_coeffs); }\n\n    inline AlignedVector3& operator+=(const AlignedVector3& other)\n    { m_coeffs += other.m_coeffs; return *this; }\n\n    inline AlignedVector3 operator-(const AlignedVector3& other) const\n    { return AlignedVector3(m_coeffs - other.m_coeffs); }\n\n    inline AlignedVector3 operator-() const\n    { return AlignedVector3(-m_coeffs); }\n\n    inline AlignedVector3 operator-=(const AlignedVector3& other)\n    { m_coeffs -= other.m_coeffs; return *this; }\n\n    inline AlignedVector3 operator*(const Scalar& s) const\n    { return AlignedVector3(m_coeffs * s); }\n\n    inline friend AlignedVector3 operator*(const Scalar& s,const AlignedVector3& vec)\n    { return AlignedVector3(s * vec.m_coeffs); }\n\n    inline AlignedVector3& operator*=(const Scalar& s)\n    { m_coeffs *= s; return *this; }\n\n    inline AlignedVector3 operator/(const Scalar& s) const\n    { return AlignedVector3(m_coeffs / s); }\n\n    inline AlignedVector3& operator/=(const Scalar& s)\n    { m_coeffs /= s; return *this; }\n\n    inline Scalar dot(const AlignedVector3& other) const\n    {\n      eigen_assert(m_coeffs.w()==Scalar(0));\n      eigen_assert(other.m_coeffs.w()==Scalar(0));\n      return m_coeffs.dot(other.m_coeffs);\n    }\n\n    inline void normalize()\n    {\n      m_coeffs /= norm();\n    }\n\n    inline AlignedVector3 normalized() const\n    {\n      return AlignedVector3(m_coeffs / norm());\n    }\n\n    inline Scalar sum() const\n    {\n      eigen_assert(m_coeffs.w()==Scalar(0));\n      return m_coeffs.sum();\n    }\n\n    inline Scalar squaredNorm() const\n    {\n      eigen_assert(m_coeffs.w()==Scalar(0));\n      return m_coeffs.squaredNorm();\n    }\n\n    inline Scalar norm() const\n    {\n      using std::sqrt;\n      return sqrt(squaredNorm());\n    }\n\n    inline AlignedVector3 cross(const AlignedVector3& other) const\n    {\n      return AlignedVector3(m_coeffs.cross3(other.m_coeffs));\n    }\n\n    template<typename Derived>\n    inline bool isApprox(const MatrixBase<Derived>& other, const RealScalar& eps=NumTraits<Scalar>::dummy_precision()) const\n    {\n      return m_coeffs.template head<3>().isApprox(other,eps);\n    }\n    \n    CoeffType& coeffs() { return m_coeffs; }\n    const CoeffType& coeffs() const { return m_coeffs; }\n};\n\nnamespace internal {\n\ntemplate<typename Scalar_>\nstruct eval<AlignedVector3<Scalar_>, Dense>\n{\n typedef const AlignedVector3<Scalar_>& type;\n};\n\ntemplate<typename Scalar>\nstruct evaluator<AlignedVector3<Scalar> >\n  : evaluator<Matrix<Scalar,4,1> >\n{\n  typedef AlignedVector3<Scalar> XprType;\n  typedef evaluator<Matrix<Scalar,4,1> > Base;\n  \n  evaluator(const XprType &m) : Base(m.coeffs()) {}  \n};\n\n}\n\n//@}\n\n}\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_ALIGNED_VECTOR3\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/ArpackSupport",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ARPACKSUPPORT_MODULE_H\n#define EIGEN_ARPACKSUPPORT_MODULE_H\n\n#include \"../../Eigen/Core\"\n\n/** \\defgroup ArpackSupport_Module Arpack support module\n  *\n  * This module provides a wrapper to Arpack, a library for sparse eigenvalue decomposition.\n  *\n  * \\code\n  * #include <Eigen/ArpackSupport>\n  * \\endcode\n  */\n\n#include \"../../Eigen/SparseCholesky\"\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n#include \"src/Eigenvalues/ArpackSelfAdjointEigenSolver.h\"\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_ARPACKSUPPORT_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/AutoDiff",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_AUTODIFF_MODULE\n#define EIGEN_AUTODIFF_MODULE\n\nnamespace Eigen {\n\n/**\n  * \\defgroup AutoDiff_Module Auto Diff module\n  *\n  * This module features forward automatic differentation via a simple\n  * templated scalar type wrapper AutoDiffScalar.\n  *\n  * Warning : this should NOT be confused with numerical differentiation, which\n  * is a different method and has its own module in Eigen : \\ref NumericalDiff_Module.\n  *\n  * \\code\n  * #include <unsupported/Eigen/AutoDiff>\n  * \\endcode\n  */\n//@{\n\n}\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n\n#include \"src/AutoDiff/AutoDiffScalar.h\"\n// #include \"src/AutoDiff/AutoDiffVector.h\"\n#include \"src/AutoDiff/AutoDiffJacobian.h\"\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n\n\nnamespace Eigen {\n//@}\n}\n\n#endif // EIGEN_AUTODIFF_MODULE\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/BVH",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Ilya Baran <ibaran@mit.edu>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BVH_MODULE_H\n#define EIGEN_BVH_MODULE_H\n\n#include \"../../Eigen/Core\"\n#include \"../../Eigen/Geometry\"\n#include \"../../Eigen/StdVector\"\n#include <algorithm>\n#include <queue>\n\nnamespace Eigen {\n\n/**\n  * \\defgroup BVH_Module BVH module\n  * \\brief This module provides generic bounding volume hierarchy algorithms\n  * and reference tree implementations.\n  *\n  *\n  * \\code\n  * #include <unsupported/Eigen/BVH>\n  * \\endcode\n  *\n  * A bounding volume hierarchy (BVH) can accelerate many geometric queries.  This module provides a generic implementation\n  * of the two basic algorithms over a BVH: intersection of a query object against all objects in the hierarchy and minimization\n  * of a function over the objects in the hierarchy.  It also provides intersection and minimization over a cartesian product of\n  * two BVH's.  A BVH accelerates intersection by using the fact that if a query object does not intersect a volume, then it cannot\n  * intersect any object contained in that volume.  Similarly, a BVH accelerates minimization because the minimum of a function\n  * over a volume is no greater than the minimum of a function over any object contained in it.\n  *\n  * Some sample queries that can be written in terms of intersection are:\n  *   - Determine all points where a ray intersects a triangle mesh\n  *   - Given a set of points, determine which are contained in a query sphere\n  *   - Given a set of spheres, determine which contain the query point\n  *   - Given a set of disks, determine if any is completely contained in a query rectangle (represent each 2D disk as a point \\f$(x,y,r)\\f$\n  *     in 3D and represent the rectangle as a pyramid based on the original rectangle and shrinking in the \\f$r\\f$ direction)\n  *   - Given a set of points, count how many pairs are \\f$d\\pm\\epsilon\\f$ apart (done by looking at the cartesian product of the set\n  *     of points with itself)\n  *\n  * Some sample queries that can be written in terms of function minimization over a set of objects are:\n  *   - Find the intersection between a ray and a triangle mesh closest to the ray origin (function is infinite off the ray)\n  *   - Given a polyline and a query point, determine the closest point on the polyline to the query\n  *   - Find the diameter of a point cloud (done by looking at the cartesian product and using negative distance as the function)\n  *   - Determine how far two meshes are from colliding (this is also a cartesian product query)\n  *\n  * This implementation decouples the basic algorithms both from the type of hierarchy (and the types of the bounding volumes) and\n  * from the particulars of the query.  To enable abstraction from the BVH, the BVH is required to implement a generic mechanism\n  * for traversal.  To abstract from the query, the query is responsible for keeping track of results.\n  *\n  * To be used in the algorithms, a hierarchy must implement the following traversal mechanism (see KdBVH for a sample implementation): \\code\n      typedef Volume  //the type of bounding volume\n      typedef Object  //the type of object in the hierarchy\n      typedef Index   //a reference to a node in the hierarchy--typically an int or a pointer\n      typedef VolumeIterator //an iterator type over node children--returns Index\n      typedef ObjectIterator //an iterator over object (leaf) children--returns const Object &\n      Index getRootIndex() const //returns the index of the hierarchy root\n      const Volume &getVolume(Index index) const //returns the bounding volume of the node at given index\n      void getChildren(Index index, VolumeIterator &outVBegin, VolumeIterator &outVEnd,\n                      ObjectIterator &outOBegin, ObjectIterator &outOEnd) const\n      //getChildren takes a node index and makes [outVBegin, outVEnd) range over its node children\n      //and [outOBegin, outOEnd) range over its object children\n    \\endcode\n  *\n  * To use the hierarchy, call BVIntersect or BVMinimize, passing it a BVH (or two, for cartesian product) and a minimizer or intersector.\n  * For an intersection query on a single BVH, the intersector encapsulates the query and must provide two functions:\n  * \\code\n      bool intersectVolume(const Volume &volume) //returns true if the query intersects the volume\n      bool intersectObject(const Object &object) //returns true if the intersection search should terminate immediately\n    \\endcode\n  * The guarantee that BVIntersect provides is that intersectObject will be called on every object whose bounding volume\n  * intersects the query (but possibly on other objects too) unless the search is terminated prematurely.  It is the\n  * responsibility of the intersectObject function to keep track of the results in whatever manner is appropriate.\n  * The cartesian product intersection and the BVMinimize queries are similar--see their individual documentation.\n  *\n  * The following is a simple but complete example for how to use the BVH to accelerate the search for a closest red-blue point pair:\n  * \\include BVH_Example.cpp\n  * Output: \\verbinclude BVH_Example.out\n  */\n}\n\n//@{\n\n#include \"src/BVH/BVAlgorithms.h\"\n#include \"src/BVH/KdBVH.h\"\n\n//@}\n\n#endif // EIGEN_BVH_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CMakeLists.txt",
    "content": "set(Eigen_HEADERS \n  AdolcForward\n  AlignedVector3\n  ArpackSupport\n  AutoDiff\n  BVH\n  EulerAngles\n  FFT\n  IterativeSolvers \n  KroneckerProduct\n  LevenbergMarquardt\n  MatrixFunctions \n  MoreVectorization\n  MPRealSupport\n  NonLinearOptimization\n  NumericalDiff\n  OpenGLSupport\n  Polynomials\n  Skyline \n  SparseExtra\n  SpecialFunctions\n  Splines\n  )\n\ninstall(FILES\n  ${Eigen_HEADERS}\n  DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen COMPONENT Devel\n  )\n\ninstall(DIRECTORY src DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen COMPONENT Devel FILES_MATCHING PATTERN \"*.h\")\n\nadd_subdirectory(CXX11)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/CMakeLists.txt",
    "content": "set(Eigen_CXX11_HEADERS Tensor TensorSymmetry ThreadPool)\n\ninstall(FILES\n  ${Eigen_CXX11_HEADERS}\n  DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen/CXX11 COMPONENT Devel\n  )\n\ninstall(DIRECTORY src DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen/CXX11 COMPONENT Devel FILES_MATCHING PATTERN \"*.h\")\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/Tensor",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n//#ifndef EIGEN_CXX11_TENSOR_MODULE\n//#define EIGEN_CXX11_TENSOR_MODULE\n\n#include \"../../../Eigen/Core\"\n\n#if EIGEN_HAS_CXX11\n\n#include \"../SpecialFunctions\"\n\n#include \"../../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n#include \"src/util/CXX11Meta.h\"\n#include \"src/util/MaxSizeVector.h\"\n\n/** \\defgroup CXX11_Tensor_Module Tensor Module\n  *\n  * This module provides a Tensor class for storing arbitrarily indexed\n  * objects.\n  *\n  * \\code\n  * #include <Eigen/CXX11/Tensor>\n  * \\endcode\n  *\n  * Much of the documentation can be found \\ref eigen_tensors \"here\".\n  */\n\n#include <atomic>\n#include <chrono>\n#include <cmath>\n#include <cstddef>\n#include <cstring>\n#include <random>\n#include <thread>\n\n#if defined(EIGEN_USE_THREADS) || defined(EIGEN_USE_SYCL)\n#include \"ThreadPool\"\n#endif\n\n#ifdef EIGEN_USE_GPU\n  #include <iostream>\n  #if defined(EIGEN_USE_HIP)\n    #include <hip/hip_runtime.h>\n  #else\n    #include <cuda_runtime.h>\n  #endif\n#endif\n\n#include \"src/Tensor/TensorMacros.h\"\n#include \"src/Tensor/TensorForwardDeclarations.h\"\n#include \"src/Tensor/TensorMeta.h\"\n#include \"src/Tensor/TensorFunctors.h\"\n#include \"src/Tensor/TensorCostModel.h\"\n#include \"src/Tensor/TensorDeviceDefault.h\"\n#include \"src/Tensor/TensorDeviceThreadPool.h\"\n#include \"src/Tensor/TensorDeviceGpu.h\"\n#ifndef gpu_assert\n#define gpu_assert(x)\n#endif\n#include \"src/Tensor/TensorDeviceSycl.h\"\n#include \"src/Tensor/TensorIndexList.h\"\n#include \"src/Tensor/TensorDimensionList.h\"\n#include \"src/Tensor/TensorDimensions.h\"\n#include \"src/Tensor/TensorInitializer.h\"\n#include \"src/Tensor/TensorTraits.h\"\n#include \"src/Tensor/TensorRandom.h\"\n#include \"src/Tensor/TensorUInt128.h\"\n#include \"src/Tensor/TensorIntDiv.h\"\n#include \"src/Tensor/TensorGlobalFunctions.h\"\n\n#include \"src/Tensor/TensorBase.h\"\n#include \"src/Tensor/TensorBlock.h\"\n\n#include \"src/Tensor/TensorEvaluator.h\"\n#include \"src/Tensor/TensorExpr.h\"\n#include \"src/Tensor/TensorReduction.h\"\n#include \"src/Tensor/TensorReductionGpu.h\"\n#include \"src/Tensor/TensorArgMax.h\"\n#include \"src/Tensor/TensorConcatenation.h\"\n#include \"src/Tensor/TensorContractionMapper.h\"\n#include \"src/Tensor/TensorContractionBlocking.h\"\n#include \"src/Tensor/TensorContraction.h\"\n#include \"src/Tensor/TensorContractionThreadPool.h\"\n#include \"src/Tensor/TensorContractionGpu.h\"\n#include \"src/Tensor/TensorConversion.h\"\n#include \"src/Tensor/TensorConvolution.h\"\n#include \"src/Tensor/TensorFFT.h\"\n#include \"src/Tensor/TensorPatch.h\"\n#include \"src/Tensor/TensorImagePatch.h\"\n#include \"src/Tensor/TensorVolumePatch.h\"\n#include \"src/Tensor/TensorBroadcasting.h\"\n#include \"src/Tensor/TensorChipping.h\"\n#include \"src/Tensor/TensorInflation.h\"\n#include \"src/Tensor/TensorLayoutSwap.h\"\n#include \"src/Tensor/TensorMorphing.h\"\n#include \"src/Tensor/TensorPadding.h\"\n#include \"src/Tensor/TensorReverse.h\"\n#include \"src/Tensor/TensorShuffling.h\"\n#include \"src/Tensor/TensorStriding.h\"\n#include \"src/Tensor/TensorCustomOp.h\"\n#include \"src/Tensor/TensorEvalTo.h\"\n#include \"src/Tensor/TensorForcedEval.h\"\n#include \"src/Tensor/TensorGenerator.h\"\n#include \"src/Tensor/TensorAssign.h\"\n#include \"src/Tensor/TensorScan.h\"\n#include \"src/Tensor/TensorTrace.h\"\n\n#ifdef EIGEN_USE_SYCL\n#include \"src/Tensor/TensorReductionSycl.h\"\n#include \"src/Tensor/TensorConvolutionSycl.h\"\n#include \"src/Tensor/TensorContractionSycl.h\"\n#include \"src/Tensor/TensorScanSycl.h\"\n#endif\n\n#include \"src/Tensor/TensorExecutor.h\"\n#include \"src/Tensor/TensorDevice.h\"\n\n#include \"src/Tensor/TensorStorage.h\"\n#include \"src/Tensor/Tensor.h\"\n#include \"src/Tensor/TensorFixedSize.h\"\n#include \"src/Tensor/TensorMap.h\"\n#include \"src/Tensor/TensorRef.h\"\n\n#include \"src/Tensor/TensorIO.h\"\n\n#include \"../../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif  // EIGEN_HAS_CXX11\n//#endif // EIGEN_CXX11_TENSOR_MODULE\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/TensorSymmetry",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSORSYMMETRY_MODULE\n#define EIGEN_CXX11_TENSORSYMMETRY_MODULE\n\n#include \"Tensor\"\n\n#include \"../../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n#include \"src/util/CXX11Meta.h\"\n\n/** \\defgroup CXX11_TensorSymmetry_Module Tensor Symmetry Module\n  *\n  * This module provides a classes that allow for the definition of\n  * symmetries w.r.t. tensor indices.\n  *\n  * Including this module will implicitly include the Tensor module.\n  *\n  * \\code\n  * #include <Eigen/TensorSymmetry>\n  * \\endcode\n  */\n\n#include \"src/TensorSymmetry/util/TemplateGroupTheory.h\"\n#include \"src/TensorSymmetry/Symmetry.h\"\n#include \"src/TensorSymmetry/StaticSymmetry.h\"\n#include \"src/TensorSymmetry/DynamicSymmetry.h\"\n\n#include \"../../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_CXX11_TENSORSYMMETRY_MODULE\n\n/*\n * kate: space-indent on; indent-width 2; mixedindent off; indent-mode cstyle;\n */\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/ThreadPool",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_THREADPOOL_MODULE\n#define EIGEN_CXX11_THREADPOOL_MODULE\n\n#include \"../../../Eigen/Core\"\n\n#include \"../../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n/** \\defgroup CXX11_ThreadPool_Module C++11 ThreadPool Module\n  *\n  * This module provides 2 threadpool implementations\n  *  - a simple reference implementation\n  *  - a faster non blocking implementation\n  *\n  * This module requires C++11.\n  *\n  * \\code\n  * #include <Eigen/CXX11/ThreadPool>\n  * \\endcode\n  */\n\n\n// The code depends on CXX11, so only include the module if the\n// compiler supports it.\n#if (EIGEN_COMP_CXXVER >= 11)\n#include <cstddef>\n#include <cstring>\n#include <time.h>\n\n#include <vector>\n#include <atomic>\n#include <condition_variable>\n#include <deque>\n#include <mutex>\n#include <thread>\n#include <functional>\n#include <memory>\n#include <utility>\n\n// There are non-parenthesized calls to \"max\" in the  <unordered_map> header,\n// which trigger a check in test/main.h causing compilation to fail.\n// We work around the check here by removing the check for max in\n// the case where we have to emulate thread_local.\n#ifdef max\n#undef max\n#endif\n#include <unordered_map>\n\n#include \"src/util/CXX11Meta.h\"\n#include \"src/util/MaxSizeVector.h\"\n\n#include \"src/ThreadPool/ThreadLocal.h\"\n#include \"src/ThreadPool/ThreadYield.h\"\n#include \"src/ThreadPool/ThreadCancel.h\"\n#include \"src/ThreadPool/EventCount.h\"\n#include \"src/ThreadPool/RunQueue.h\"\n#include \"src/ThreadPool/ThreadPoolInterface.h\"\n#include \"src/ThreadPool/ThreadEnvironment.h\"\n#include \"src/ThreadPool/Barrier.h\"\n#include \"src/ThreadPool/NonBlockingThreadPool.h\"\n\n#endif\n\n#include \"../../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_CXX11_THREADPOOL_MODULE\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/README.md",
    "content": "# Eigen Tensors {#eigen_tensors}\n\nTensors are multidimensional arrays of elements. Elements are typically scalars,\nbut more complex types such as strings are also supported.\n\n## Tensor Classes\n\nYou can manipulate a tensor with one of the following classes.  They all are in\nthe namespace `::Eigen.`\n\n\n### Class Tensor<data_type, rank>\n\nThis is the class to use to create a tensor and allocate memory for it.  The\nclass is templatized with the tensor datatype, such as float or int, and the\ntensor rank.  The rank is the number of dimensions, for example rank 2 is a\nmatrix.\n\nTensors of this class are resizable.  For example, if you assign a tensor of a\ndifferent size to a Tensor, that tensor is resized to match its new value.\n\n#### Constructor Tensor<data_type, rank>(size0, size1, ...)\n\nConstructor for a Tensor.  The constructor must be passed `rank` integers\nindicating the sizes of the instance along each of the the `rank`\ndimensions.\n\n    // Create a tensor of rank 3 of sizes 2, 3, 4.  This tensor owns\n    // memory to hold 24 floating point values (24 = 2 x 3 x 4).\n    Tensor<float, 3> t_3d(2, 3, 4);\n\n    // Resize t_3d by assigning a tensor of different sizes, but same rank.\n    t_3d = Tensor<float, 3>(3, 4, 3);\n\n#### Constructor Tensor<data_type, rank>(size_array)\n\nConstructor where the sizes for the constructor are specified as an array of\nvalues instead of an explicitly list of parameters.  The array type to use is\n`Eigen::array<Eigen::Index>`.  The array can be constructed automatically\nfrom an initializer list.\n\n    // Create a tensor of strings of rank 2 with sizes 5, 7.\n    Tensor<string, 2> t_2d({5, 7});\n\n\n### Class TensorFixedSize<data_type, Sizes<size0, size1, ...>>\n\nClass to use for tensors of fixed size, where the size is known at compile\ntime.  Fixed sized tensors can provide very fast computations because all their\ndimensions are known by the compiler.  FixedSize tensors are not resizable.\n\nIf the total number of elements in a fixed size tensor is small enough the\ntensor data is held onto the stack and does not cause heap allocation and free.\n\n    // Create a 4 x 3 tensor of floats.\n    TensorFixedSize<float, Sizes<4, 3>> t_4x3;\n\n### Class TensorMap<Tensor<data_type, rank>>\n\nThis is the class to use to create a tensor on top of memory allocated and\nowned by another part of your code.  It allows to view any piece of allocated\nmemory as a Tensor.  Instances of this class do not own the memory where the\ndata are stored.\n\nA TensorMap is not resizable because it does not own the memory where its data\nare stored.\n\n#### Constructor TensorMap<Tensor<data_type, rank>>(data, size0, size1, ...)\n\nConstructor for a Tensor.  The constructor must be passed a pointer to the\nstorage for the data, and \"rank\" size attributes.  The storage has to be\nlarge enough to hold all the data.\n\n    // Map a tensor of ints on top of stack-allocated storage.\n    int storage[128];  // 2 x 4 x 2 x 8 = 128\n    TensorMap<Tensor<int, 4>> t_4d(storage, 2, 4, 2, 8);\n\n    // The same storage can be viewed as a different tensor.\n    // You can also pass the sizes as an array.\n    TensorMap<Tensor<int, 2>> t_2d(storage, 16, 8);\n\n    // You can also map fixed-size tensors.  Here we get a 1d view of\n    // the 2d fixed-size tensor.\n    TensorFixedSize<float, Sizes<4, 3>> t_4x3;\n    TensorMap<Tensor<float, 1>> t_12(t_4x3.data(), 12);\n\n\n#### Class TensorRef\n\nSee Assigning to a TensorRef below.\n\n## Accessing Tensor Elements\n\n#### <data_type> tensor(index0, index1...)\n\nReturn the element at position `(index0, index1...)` in tensor\n`tensor`.  You must pass as many parameters as the rank of `tensor`.\nThe expression can be used as an l-value to set the value of the element at the\nspecified position.  The value returned is of the datatype of the tensor.\n\n    // Set the value of the element at position (0, 1, 0);\n    Tensor<float, 3> t_3d(2, 3, 4);\n    t_3d(0, 1, 0) = 12.0f;\n\n    // Initialize all elements to random values.\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 3; ++j) {\n        for (int k = 0; k < 4; ++k) {\n          t_3d(i, j, k) = ...some random value...;\n        }\n      }\n    }\n\n    // Print elements of a tensor.\n    for (int i = 0; i < 2; ++i) {\n      LOG(INFO) << t_3d(i, 0, 0);\n    }\n\n\n## TensorLayout\n\nThe tensor library supports 2 layouts: `ColMajor` (the default) and\n`RowMajor`.  Only the default column major layout is currently fully\nsupported, and it is therefore not recommended to attempt to use the row major\nlayout at the moment.\n\nThe layout of a tensor is optionally specified as part of its type. If not\nspecified explicitly column major is assumed.\n\n    Tensor<float, 3, ColMajor> col_major;  // equivalent to Tensor<float, 3>\n    TensorMap<Tensor<float, 3, RowMajor> > row_major(data, ...);\n\nAll the arguments to an expression must use the same layout. Attempting to mix\ndifferent layouts will result in a compilation error.\n\nIt is possible to change the layout of a tensor or an expression using the\n`swap_layout()` method.  Note that this will also reverse the order of the\ndimensions.\n\n    Tensor<float, 2, ColMajor> col_major(2, 4);\n    Tensor<float, 2, RowMajor> row_major(2, 4);\n\n    Tensor<float, 2> col_major_result = col_major;  // ok, layouts match\n    Tensor<float, 2> col_major_result = row_major;  // will not compile\n\n    // Simple layout swap\n    col_major_result = row_major.swap_layout();\n    eigen_assert(col_major_result.dimension(0) == 4);\n    eigen_assert(col_major_result.dimension(1) == 2);\n\n    // Swap the layout and preserve the order of the dimensions\n    array<int, 2> shuffle(1, 0);\n    col_major_result = row_major.swap_layout().shuffle(shuffle);\n    eigen_assert(col_major_result.dimension(0) == 2);\n    eigen_assert(col_major_result.dimension(1) == 4);\n\n\n## Tensor Operations\n\nThe Eigen Tensor library provides a vast library of operations on Tensors:\nnumerical operations such as addition and multiplication, geometry operations\nsuch as slicing and shuffling, etc.  These operations are available as methods\nof the Tensor classes, and in some cases as operator overloads.  For example\nthe following code computes the elementwise addition of two tensors:\n\n    Tensor<float, 3> t1(2, 3, 4);\n    ...set some values in t1...\n    Tensor<float, 3> t2(2, 3, 4);\n    ...set some values in t2...\n    // Set t3 to the element wise sum of t1 and t2\n    Tensor<float, 3> t3 = t1 + t2;\n\nWhile the code above looks easy enough, it is important to understand that the\nexpression `t1 + t2` is not actually adding the values of the tensors.  The\nexpression instead constructs a \"tensor operator\" object of the class\nTensorCwiseBinaryOp<scalar_sum>, which has references to the tensors\n`t1` and `t2`.  This is a small C++ object that knows how to add\n`t1` and `t2`.  It is only when the value of the expression is assigned\nto the tensor `t3` that the addition is actually performed.  Technically,\nthis happens through the overloading of `operator=()` in the Tensor class.\n\nThis mechanism for computing tensor expressions allows for lazy evaluation and\noptimizations which are what make the tensor library very fast.\n\nOf course, the tensor operators do nest, and the expression `t1 + t2 * 0.3f`\nis actually represented with the (approximate) tree of operators:\n\n    TensorCwiseBinaryOp<scalar_sum>(t1, TensorCwiseUnaryOp<scalar_mul>(t2, 0.3f))\n\n\n### Tensor Operations and C++ \"auto\"\n\nBecause Tensor operations create tensor operators, the C++ `auto` keyword\ndoes not have its intuitive meaning.  Consider these 2 lines of code:\n\n    Tensor<float, 3> t3 = t1 + t2;\n    auto t4 = t1 + t2;\n\nIn the first line we allocate the tensor `t3` and it will contain the\nresult of the addition of `t1` and `t2`.  In the second line, `t4`\nis actually the tree of tensor operators that will compute the addition of\n`t1` and `t2`.  In fact, `t4` is *not* a tensor and you cannot get\nthe values of its elements:\n\n    Tensor<float, 3> t3 = t1 + t2;\n    cout << t3(0, 0, 0);  // OK prints the value of t1(0, 0, 0) + t2(0, 0, 0)\n\n    auto t4 = t1 + t2;\n    cout << t4(0, 0, 0);  // Compilation error!\n\nWhen you use `auto` you do not get a Tensor as a result but instead a\nnon-evaluated expression.  So only use `auto` to delay evaluation.\n\nUnfortunately, there is no single underlying concrete type for holding\nnon-evaluated expressions, hence you have to use auto in the case when you do\nwant to hold non-evaluated expressions.\n\nWhen you need the results of set of tensor computations you have to assign the\nresult to a Tensor that will be capable of holding onto them.  This can be\neither a normal Tensor, a fixed size Tensor, or a TensorMap on an existing\npiece of memory.  All the following will work:\n\n    auto t4 = t1 + t2;\n\n    Tensor<float, 3> result = t4;  // Could also be: result(t4);\n    cout << result(0, 0, 0);\n\n    TensorMap<float, 4> result(<a float* with enough space>, <size0>, ...) = t4;\n    cout << result(0, 0, 0);\n\n    TensorFixedSize<float, Sizes<size0, ...>> result = t4;\n    cout << result(0, 0, 0);\n\nUntil you need the results, you can keep the operation around, and even reuse\nit for additional operations.  As long as you keep the expression as an\noperation, no computation is performed.\n\n    // One way to compute exp((t1 + t2) * 0.2f);\n    auto t3 = t1 + t2;\n    auto t4 = t3 * 0.2f;\n    auto t5 = t4.exp();\n    Tensor<float, 3> result = t5;\n\n    // Another way, exactly as efficient as the previous one:\n    Tensor<float, 3> result = ((t1 + t2) * 0.2f).exp();\n\n### Controlling When Expression are Evaluated\n\nThere are several ways to control when expressions are evaluated:\n\n*   Assignment to a Tensor, TensorFixedSize, or TensorMap.\n*   Use of the eval() method.\n*   Assignment to a TensorRef.\n\n#### Assigning to a Tensor, TensorFixedSize, or TensorMap.\n\nThe most common way to evaluate an expression is to assign it to a Tensor.  In\nthe example below, the `auto` declarations make the intermediate values\n\"Operations\", not Tensors, and do not cause the expressions to be evaluated.\nThe assignment to the Tensor `result` causes the evaluation of all the\noperations.\n\n    auto t3 = t1 + t2;             // t3 is an Operation.\n    auto t4 = t3 * 0.2f;           // t4 is an Operation.\n    auto t5 = t4.exp();            // t5 is an Operation.\n    Tensor<float, 3> result = t5;  // The operations are evaluated.\n\nIf you know the ranks and sizes of the Operation value you can assign the\nOperation to a TensorFixedSize instead of a Tensor, which is a bit more\nefficient.\n\n    // We know that the result is a 4x4x2 tensor!\n    TensorFixedSize<float, Sizes<4, 4, 2>> result = t5;\n\nSimiarly, assigning an expression to a TensorMap causes its evaluation.  Like\ntensors of type TensorFixedSize, TensorMaps cannot be resized so they have to\nhave the rank and sizes of the expression that are assigned to them.\n\n#### Calling eval().\n\nWhen you compute large composite expressions, you sometimes want to tell Eigen\nthat an intermediate value in the expression tree is worth evaluating ahead of\ntime.  This is done by inserting a call to the `eval()` method of the\nexpression Operation.\n\n    // The previous example could have been written:\n    Tensor<float, 3> result = ((t1 + t2) * 0.2f).exp();\n\n    // If you want to compute (t1 + t2) once ahead of time you can write:\n    Tensor<float, 3> result = ((t1 + t2).eval() * 0.2f).exp();\n\nSemantically, calling `eval()` is equivalent to materializing the value of\nthe expression in a temporary Tensor of the right size.  The code above in\neffect does:\n\n    // .eval() knows the size!\n    TensorFixedSize<float, Sizes<4, 4, 2>> tmp = t1 + t2;\n    Tensor<float, 3> result = (tmp * 0.2f).exp();\n\nNote that the return value of `eval()` is itself an Operation, so the\nfollowing code does not do what you may think:\n\n    // Here t3 is an evaluation Operation.  t3 has not been evaluated yet.\n    auto t3 = (t1 + t2).eval();\n\n    // You can use t3 in another expression.  Still no evaluation.\n    auto t4 = (t3 * 0.2f).exp();\n\n    // The value is evaluated when you assign the Operation to a Tensor, using\n    // an intermediate tensor to represent t3.x\n    Tensor<float, 3> result = t4;\n\nWhile in the examples above calling `eval()` does not make a difference in\nperformance, in other cases it can make a huge difference.  In the expression\nbelow the `broadcast()` expression causes the `X.maximum()` expression\nto be evaluated many times:\n\n    Tensor<...> X ...;\n    Tensor<...> Y = ((X - X.maximum(depth_dim).reshape(dims2d).broadcast(bcast))\n                     * beta).exp();\n\nInserting a call to `eval()` between the `maximum()` and\n`reshape()` calls guarantees that maximum() is only computed once and\ngreatly speeds-up execution:\n\n    Tensor<...> Y =\n      ((X - X.maximum(depth_dim).eval().reshape(dims2d).broadcast(bcast))\n        * beta).exp();\n\nIn the other example below, the tensor `Y` is both used in the expression\nand its assignment.  This is an aliasing problem and if the evaluation is not\ndone in the right order Y will be updated incrementally during the evaluation\nresulting in bogus results:\n\n     Tensor<...> Y ...;\n     Y = Y / (Y.sum(depth_dim).reshape(dims2d).broadcast(bcast));\n\nInserting a call to `eval()` between the `sum()` and `reshape()`\nexpressions ensures that the sum is computed before any updates to `Y` are\ndone.\n\n     Y = Y / (Y.sum(depth_dim).eval().reshape(dims2d).broadcast(bcast));\n\nNote that an eval around the full right hand side expression is not needed\nbecause the generated has to compute the i-th value of the right hand side\nbefore assigning it to the left hand side.\n\nHowever, if you were assigning the expression value to a shuffle of `Y`\nthen you would need to force an eval for correctness by adding an `eval()`\ncall for the right hand side:\n\n     Y.shuffle(...) =\n        (Y / (Y.sum(depth_dim).eval().reshape(dims2d).broadcast(bcast))).eval();\n\n\n#### Assigning to a TensorRef.\n\nIf you need to access only a few elements from the value of an expression you\ncan avoid materializing the value in a full tensor by using a TensorRef.\n\nA TensorRef is a small wrapper class for any Eigen Operation.  It provides\noverloads for the `()` operator that let you access individual values in\nthe expression.  TensorRef is convenient, because the Operation themselves do\nnot provide a way to access individual elements.\n\n    // Create a TensorRef for the expression.  The expression is not\n    // evaluated yet.\n    TensorRef<Tensor<float, 3> > ref = ((t1 + t2) * 0.2f).exp();\n\n    // Use \"ref\" to access individual elements.  The expression is evaluated\n    // on the fly.\n    float at_0 = ref(0, 0, 0);\n    cout << ref(0, 1, 0);\n\nOnly use TensorRef when you need a subset of the values of the expression.\nTensorRef only computes the values you access.  However note that if you are\ngoing to access all the values it will be much faster to materialize the\nresults in a Tensor first.\n\nIn some cases, if the full Tensor result would be very large, you may save\nmemory by accessing it as a TensorRef.  But not always.  So don't count on it.\n\n\n### Controlling How Expressions Are Evaluated\n\nThe tensor library provides several implementations of the various operations\nsuch as contractions and convolutions.  The implementations are optimized for\ndifferent environments: single threaded on CPU, multi threaded on CPU, or on a\nGPU using cuda.  Additional implementations may be added later.\n\nYou can choose which implementation to use with the `device()` call.  If\nyou do not choose an implementation explicitly the default implementation that\nuses a single thread on the CPU is used.\n\nThe default implementation has been optimized for recent Intel CPUs, taking\nadvantage of SSE, AVX, and FMA instructions.  Work is ongoing to tune the\nlibrary on ARM CPUs.  Note that you need to pass compiler-dependent flags\nto enable the use of SSE, AVX, and other instructions.\n\nFor example, the following code adds two tensors using the default\nsingle-threaded CPU implementation:\n\n    Tensor<float, 2> a(30, 40);\n    Tensor<float, 2> b(30, 40);\n    Tensor<float, 2> c = a + b;\n\nTo choose a different implementation you have to insert a `device()` call\nbefore the assignment of the result.  For technical C++ reasons this requires\nthat the Tensor for the result be declared on its own.  This means that you\nhave to know the size of the result.\n\n    Eigen::Tensor<float, 2> c(30, 40);\n    c.device(...) = a + b;\n\nThe call to `device()` must be the last call on the left of the operator=.\n\nYou must pass to the `device()` call an Eigen device object.  There are\npresently three devices you can use: DefaultDevice, ThreadPoolDevice and\nGpuDevice.\n\n\n#### Evaluating With the DefaultDevice\n\nThis is exactly the same as not inserting a `device()` call.\n\n    DefaultDevice my_device;\n    c.device(my_device) = a + b;\n\n#### Evaluating with a Thread Pool\n\n    // Create the Eigen ThreadPool\n    Eigen::ThreadPool pool(8 /* number of threads in pool */)\n\n    // Create the Eigen ThreadPoolDevice.\n    Eigen::ThreadPoolDevice my_device(&pool, 4 /* number of threads to use */);\n\n    // Now just use the device when evaluating expressions.\n    Eigen::Tensor<float, 2> c(30, 50);\n    c.device(my_device) = a.contract(b, dot_product_dims);\n\n\n#### Evaluating On GPU\n\nThis is presently a bit more complicated than just using a thread pool device.\nYou need to create a GPU device but you also need to explicitly allocate the\nmemory for tensors with cuda.\n\n\n## API Reference\n\n### Datatypes\n\nIn the documentation of the tensor methods and Operation we mention datatypes\nthat are tensor-type specific:\n\n#### <Tensor-Type>::Dimensions\n\nActs like an array of ints.  Has an `int size` attribute, and can be\nindexed like an array to access individual values.  Used to represent the\ndimensions of a tensor.  See `dimensions()`.\n\n#### <Tensor-Type>::Index\n\nActs like an `int`.  Used for indexing tensors along their dimensions.  See\n`operator()`, `dimension()`, and `size()`.\n\n#### <Tensor-Type>::Scalar\n\nRepresents the datatype of individual tensor elements.  For example, for a\n`Tensor<float>`, `Scalar` is the type `float`.  See\n`setConstant()`.\n\n#### <Operation>\n\nWe use this pseudo type to indicate that a tensor Operation is returned by a\nmethod.  We indicate in the text the type and dimensions of the tensor that the\nOperation returns after evaluation.\n\nThe Operation will have to be evaluated, for example by assigning it to a\ntensor, before you can access the values of the resulting tensor.  You can also\naccess the values through a TensorRef.\n\n\n## Built-in Tensor Methods\n\nThese are usual C++ methods that act on tensors immediately.  They are not\nOperations which provide delayed evaluation of their results.  Unless specified\notherwise, all the methods listed below are available on all tensor classes:\nTensor, TensorFixedSize, and TensorMap.\n\n## Metadata\n\n### int NumDimensions\n\nConstant value indicating the number of dimensions of a Tensor.  This is also\nknown as the tensor \"rank\".\n\n      Eigen::Tensor<float, 2> a(3, 4);\n      cout << \"Dims \" << a.NumDimensions;\n      => Dims 2\n\n### Dimensions dimensions()\n\nReturns an array-like object representing the dimensions of the tensor.\nThe actual type of the `dimensions()` result is `<Tensor-Type>::``Dimensions`.\n\n    Eigen::Tensor<float, 2> a(3, 4);\n    const Eigen::Tensor<float, 2>::Dimensions& d = a.dimensions();\n    cout << \"Dim size: \" << d.size << \", dim 0: \" << d[0]\n         << \", dim 1: \" << d[1];\n    => Dim size: 2, dim 0: 3, dim 1: 4\n\nIf you use a C++11 compiler, you can use `auto` to simplify the code:\n\n    const auto& d = a.dimensions();\n    cout << \"Dim size: \" << d.size << \", dim 0: \" << d[0]\n         << \", dim 1: \" << d[1];\n    => Dim size: 2, dim 0: 3, dim 1: 4\n\n### Index dimension(Index n)\n\nReturns the n-th dimension of the tensor.  The actual type of the\n`dimension()` result is `<Tensor-Type>::``Index`, but you can\nalways use it like an int.\n\n      Eigen::Tensor<float, 2> a(3, 4);\n      int dim1 = a.dimension(1);\n      cout << \"Dim 1: \" << dim1;\n      => Dim 1: 4\n\n### Index size()\n\nReturns the total number of elements in the tensor.  This is the product of all\nthe tensor dimensions.  The actual type of the `size()` result is\n`<Tensor-Type>::``Index`, but you can always use it like an int.\n\n    Eigen::Tensor<float, 2> a(3, 4);\n    cout << \"Size: \" << a.size();\n    => Size: 12\n\n\n### Getting Dimensions From An Operation\n\nA few operations provide `dimensions()` directly,\ne.g. `TensorReslicingOp`.  Most operations defer calculating dimensions\nuntil the operation is being evaluated.  If you need access to the dimensions\nof a deferred operation, you can wrap it in a TensorRef (see Assigning to a\nTensorRef above), which provides `dimensions()` and `dimension()` as\nabove.\n\nTensorRef can also wrap the plain Tensor types, so this is a useful idiom in\ntemplated contexts where the underlying object could be either a raw Tensor\nor some deferred operation (e.g. a slice of a Tensor).  In this case, the\ntemplate code can wrap the object in a TensorRef and reason about its\ndimensionality while remaining agnostic to the underlying type.\n\n\n## Constructors\n\n### Tensor\n\nCreates a tensor of the specified size. The number of arguments must be equal\nto the rank of the tensor. The content of the tensor is not initialized.\n\n    Eigen::Tensor<float, 2> a(3, 4);\n    cout << \"NumRows: \" << a.dimension(0) << \" NumCols: \" << a.dimension(1) << endl;\n    => NumRows: 3 NumCols: 4\n\n### TensorFixedSize\n\nCreates a tensor of the specified size. The number of arguments in the Sizes<>\ntemplate parameter determines the rank of the tensor. The content of the tensor\nis not initialized.\n\n    Eigen::TensorFixedSize<float, Sizes<3, 4>> a;\n    cout << \"Rank: \" << a.rank() << endl;\n    => Rank: 2\n    cout << \"NumRows: \" << a.dimension(0) << \" NumCols: \" << a.dimension(1) << endl;\n    => NumRows: 3 NumCols: 4\n\n### TensorMap\n\nCreates a tensor mapping an existing array of data. The data must not be freed\nuntil the TensorMap is discarded, and the size of the data must be large enough\nto accommodate the coefficients of the tensor.\n\n    float data[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11};\n    Eigen::TensorMap<Tensor<float, 2>> a(data, 3, 4);\n    cout << \"NumRows: \" << a.dimension(0) << \" NumCols: \" << a.dimension(1) << endl;\n    => NumRows: 3 NumCols: 4\n    cout << \"a(1, 2): \" << a(1, 2) << endl;\n    => a(1, 2): 7\n\n\n## Contents Initialization\n\nWhen a new Tensor or a new TensorFixedSize are created, memory is allocated to\nhold all the tensor elements, but the memory is not initialized.  Similarly,\nwhen a new TensorMap is created on top of non-initialized memory the memory its\ncontents are not initialized.\n\nYou can use one of the methods below to initialize the tensor memory.  These\nhave an immediate effect on the tensor and return the tensor itself as a\nresult.  These are not tensor Operations which delay evaluation.\n\n### <Tensor-Type> setConstant(const Scalar& val)\n\nSets all elements of the tensor to the constant value `val`.  `Scalar`\nis the type of data stored in the tensor.  You can pass any value that is\nconvertible to that type.\n\nReturns the tensor itself in case you want to chain another call.\n\n    a.setConstant(12.3f);\n    cout << \"Constant: \" << endl << a << endl << endl;\n    =>\n    Constant:\n    12.3 12.3 12.3 12.3\n    12.3 12.3 12.3 12.3\n    12.3 12.3 12.3 12.3\n\nNote that `setConstant()` can be used on any tensor where the element type\nhas a copy constructor and an `operator=()`:\n\n    Eigen::Tensor<string, 2> a(2, 3);\n    a.setConstant(\"yolo\");\n    cout << \"String tensor: \" << endl << a << endl << endl;\n    =>\n    String tensor:\n    yolo yolo yolo\n    yolo yolo yolo\n\n\n### <Tensor-Type> setZero()\n\nFills the tensor with zeros.  Equivalent to `setConstant(Scalar(0))`.\nReturns the tensor itself in case you want to chain another call.\n\n    a.setZero();\n    cout << \"Zeros: \" << endl << a << endl << endl;\n    =>\n    Zeros:\n    0 0 0 0\n    0 0 0 0\n    0 0 0 0\n\n\n### <Tensor-Type> setValues({..initializer_list})\n\nFills the tensor with explicit values specified in a std::initializer_list.\nThe type of the initializer list depends on the type and rank of the tensor.\n\nIf the tensor has rank N, the initializer list must be nested N times.  The\nmost deeply nested lists must contains P scalars of the Tensor type where P is\nthe size of the last dimension of the Tensor.\n\nFor example, for a `TensorFixedSize<float, 2, 3>` the initializer list must\ncontains 2 lists of 3 floats each.\n\n`setValues()` returns the tensor itself in case you want to chain another\ncall.\n\n    Eigen::Tensor<float, 2> a(2, 3);\n    a.setValues({{0.0f, 1.0f, 2.0f}, {3.0f, 4.0f, 5.0f}});\n    cout << \"a\" << endl << a << endl << endl;\n    =>\n    a\n    0 1 2\n    3 4 5\n\nIf a list is too short, the corresponding elements of the tensor will not be\nchanged.  This is valid at each level of nesting.  For example the following\ncode only sets the values of the first row of the tensor.\n\n    Eigen::Tensor<int, 2> a(2, 3);\n    a.setConstant(1000);\n    a.setValues({{10, 20, 30}});\n    cout << \"a\" << endl << a << endl << endl;\n    =>\n    a\n    10   20   30\n    1000 1000 1000\n\n### <Tensor-Type> setRandom()\n\nFills the tensor with random values.  Returns the tensor itself in case you\nwant to chain another call.\n\n    a.setRandom();\n    cout << \"Random: \" << endl << a << endl << endl;\n    =>\n    Random:\n      0.680375    0.59688  -0.329554    0.10794\n     -0.211234   0.823295   0.536459 -0.0452059\n      0.566198  -0.604897  -0.444451   0.257742\n\nYou can customize `setRandom()` by providing your own random number\ngenerator as a template argument:\n\n    a.setRandom<MyRandomGenerator>();\n\nHere, `MyRandomGenerator` must be a struct with the following member\nfunctions, where Scalar and Index are the same as `<Tensor-Type>::``Scalar`\nand `<Tensor-Type>::``Index`.\n\nSee `struct UniformRandomGenerator` in TensorFunctors.h for an example.\n\n    // Custom number generator for use with setRandom().\n    struct MyRandomGenerator {\n      // Default and copy constructors. Both are needed\n      MyRandomGenerator() { }\n      MyRandomGenerator(const MyRandomGenerator& ) { }\n\n      // Return a random value to be used.  \"element_location\" is the\n      // location of the entry to set in the tensor, it can typically\n      // be ignored.\n      Scalar operator()(Eigen::DenseIndex element_location,\n                        Eigen::DenseIndex /*unused*/ = 0) const {\n        return <randomly generated value of type T>;\n      }\n\n      // Same as above but generates several numbers at a time.\n      typename internal::packet_traits<Scalar>::type packetOp(\n          Eigen::DenseIndex packet_location, Eigen::DenseIndex /*unused*/ = 0) const {\n        return <a packet of randomly generated values>;\n      }\n    };\n\nYou can also use one of the 2 random number generators that are part of the\ntensor library:\n*   UniformRandomGenerator\n*   NormalRandomGenerator\n\n\n## Data Access\n\nThe Tensor, TensorFixedSize, and TensorRef classes provide the following\naccessors to access the tensor coefficients:\n\n    const Scalar& operator()(const array<Index, NumIndices>& indices)\n    const Scalar& operator()(Index firstIndex, IndexTypes... otherIndices)\n    Scalar& operator()(const array<Index, NumIndices>& indices)\n    Scalar& operator()(Index firstIndex, IndexTypes... otherIndices)\n\nThe number of indices must be equal to the rank of the tensor. Moreover, these\naccessors are not available on tensor expressions. In order to access the\nvalues of a tensor expression, the expression must either be evaluated or\nwrapped in a TensorRef.\n\n\n### Scalar* data() and const Scalar* data() const\n\nReturns a pointer to the storage for the tensor.  The pointer is const if the\ntensor was const.  This allows direct access to the data.  The layout of the\ndata depends on the tensor layout: RowMajor or ColMajor.\n\nThis access is usually only needed for special cases, for example when mixing\nEigen Tensor code with other libraries.\n\nScalar is the type of data stored in the tensor.\n\n    Eigen::Tensor<float, 2> a(3, 4);\n    float* a_data = a.data();\n    a_data[0] = 123.45f;\n    cout << \"a(0, 0): \" << a(0, 0);\n    => a(0, 0): 123.45\n\n\n## Tensor Operations\n\nAll the methods documented below return non evaluated tensor `Operations`.\nThese can be chained: you can apply another Tensor Operation to the value\nreturned by the method.\n\nThe chain of Operation is evaluated lazily, typically when it is assigned to a\ntensor.  See \"Controlling when Expression are Evaluated\" for more details about\ntheir evaluation.\n\n### <Operation> constant(const Scalar& val)\n\nReturns a tensor of the same type and dimensions as the original tensor but\nwhere all elements have the value `val`.\n\nThis is useful, for example, when you want to add or subtract a constant from a\ntensor, or multiply every element of a tensor by a scalar.\n\n    Eigen::Tensor<float, 2> a(2, 3);\n    a.setConstant(1.0f);\n    Eigen::Tensor<float, 2> b = a + a.constant(2.0f);\n    Eigen::Tensor<float, 2> c = b * b.constant(0.2f);\n    cout << \"a\" << endl << a << endl << endl;\n    cout << \"b\" << endl << b << endl << endl;\n    cout << \"c\" << endl << c << endl << endl;\n    =>\n    a\n    1 1 1\n    1 1 1\n\n    b\n    3 3 3\n    3 3 3\n\n    c\n    0.6 0.6 0.6\n    0.6 0.6 0.6\n\n### <Operation> random()\n\nReturns a tensor of the same type and dimensions as the current tensor\nbut where all elements have random values.\n\nThis is for example useful to add random values to an existing tensor.\nThe generation of random values can be customized in the same manner\nas for `setRandom()`.\n\n    Eigen::Tensor<float, 2> a(2, 3);\n    a.setConstant(1.0f);\n    Eigen::Tensor<float, 2> b = a + a.random();\n    cout << \"a\" << endl << a << endl << endl;\n    cout << \"b\" << endl << b << endl << endl;\n    =>\n    a\n    1 1 1\n    1 1 1\n\n    b\n    1.68038   1.5662  1.82329\n    0.788766  1.59688 0.395103\n\n\n## Unary Element Wise Operations\n\nAll these operations take a single input tensor as argument and return a tensor\nof the same type and dimensions as the tensor to which they are applied.  The\nrequested operations are applied to each element independently.\n\n### <Operation> operator-()\n\nReturns a tensor of the same type and dimensions as the original tensor\ncontaining the opposite values of the original tensor.\n\n    Eigen::Tensor<float, 2> a(2, 3);\n    a.setConstant(1.0f);\n    Eigen::Tensor<float, 2> b = -a;\n    cout << \"a\" << endl << a << endl << endl;\n    cout << \"b\" << endl << b << endl << endl;\n    =>\n    a\n    1 1 1\n    1 1 1\n\n    b\n    -1 -1 -1\n    -1 -1 -1\n\n### <Operation> sqrt()\n\nReturns a tensor of the same type and dimensions as the original tensor\ncontaining the square roots of the original tensor.\n\n### <Operation> rsqrt()\n\nReturns a tensor of the same type and dimensions as the original tensor\ncontaining the inverse square roots of the original tensor.\n\n### <Operation> square()\n\nReturns a tensor of the same type and dimensions as the original tensor\ncontaining the squares of the original tensor values.\n\n### <Operation> inverse()\n\nReturns a tensor of the same type and dimensions as the original tensor\ncontaining the inverse of the original tensor values.\n\n### <Operation> exp()\n\nReturns a tensor of the same type and dimensions as the original tensor\ncontaining the exponential of the original tensor.\n\n### <Operation> log()\n\nReturns a tensor of the same type and dimensions as the original tensor\ncontaining the natural logarithms of the original tensor.\n\n### <Operation> abs()\n\nReturns a tensor of the same type and dimensions as the original tensor\ncontaining the absolute values of the original tensor.\n\n### <Operation> pow(Scalar exponent)\n\nReturns a tensor of the same type and dimensions as the original tensor\ncontaining the coefficients of the original tensor to the power of the\nexponent.\n\nThe type of the exponent, Scalar, is always the same as the type of the\ntensor coefficients.  For example, only integer exponents can be used in\nconjuntion with tensors of integer values.\n\nYou can use cast() to lift this restriction.  For example this computes\ncubic roots of an int Tensor:\n\n    Eigen::Tensor<int, 2> a(2, 3);\n    a.setValues({{0, 1, 8}, {27, 64, 125}});\n    Eigen::Tensor<double, 2> b = a.cast<double>().pow(1.0 / 3.0);\n    cout << \"a\" << endl << a << endl << endl;\n    cout << \"b\" << endl << b << endl << endl;\n    =>\n    a\n    0   1   8\n    27  64 125\n\n    b\n    0 1 2\n    3 4 5\n\n### <Operation>  operator * (Scalar scale)\n\nMultiplies all the coefficients of the input tensor by the provided scale.\n\n### <Operation>  cwiseMax(Scalar threshold)\nTODO\n\n### <Operation>  cwiseMin(Scalar threshold)\nTODO\n\n### <Operation>  unaryExpr(const CustomUnaryOp& func)\nTODO\n\n\n## Binary Element Wise Operations\n\nThese operations take two input tensors as arguments. The 2 input tensors should\nbe of the same type and dimensions. The result is a tensor of the same\ndimensions as the tensors to which they are applied, and unless otherwise\nspecified it is also of the same type. The requested operations are applied to\neach pair of elements independently.\n\n### <Operation> operator+(const OtherDerived& other)\n\nReturns a tensor of the same type and dimensions as the input tensors\ncontaining the coefficient wise sums of the inputs.\n\n### <Operation> operator-(const OtherDerived& other)\n\nReturns a tensor of the same type and dimensions as the input tensors\ncontaining the coefficient wise differences of the inputs.\n\n### <Operation> operator*(const OtherDerived& other)\n\nReturns a tensor of the same type and dimensions as the input tensors\ncontaining the coefficient wise products of the inputs.\n\n### <Operation> operator/(const OtherDerived& other)\n\nReturns a tensor of the same type and dimensions as the input tensors\ncontaining the coefficient wise quotients of the inputs.\n\nThis operator is not supported for integer types.\n\n### <Operation> cwiseMax(const OtherDerived& other)\n\nReturns a tensor of the same type and dimensions as the input tensors\ncontaining the coefficient wise maximums of the inputs.\n\n### <Operation> cwiseMin(const OtherDerived& other)\n\nReturns a tensor of the same type and dimensions as the input tensors\ncontaining the coefficient wise mimimums of the inputs.\n\n### <Operation> Logical operators\n\nThe following logical operators are supported as well:\n\n*   operator&&(const OtherDerived& other)\n*   operator||(const OtherDerived& other)\n*   operator<(const OtherDerived& other)\n*   operator<=(const OtherDerived& other)\n*   operator>(const OtherDerived& other)\n*   operator>=(const OtherDerived& other)\n*   operator==(const OtherDerived& other)\n*   operator!=(const OtherDerived& other)\n\nThey all return a tensor of boolean values.\n\n\n## Selection (select(const ThenDerived& thenTensor, const ElseDerived& elseTensor)\n\nSelection is a coefficient-wise ternary operator that is the tensor equivalent\nto the if-then-else operation.\n\n    Tensor<bool, 3> if = ...;\n    Tensor<float, 3> then = ...;\n    Tensor<float, 3> else = ...;\n    Tensor<float, 3> result = if.select(then, else);\n\nThe 3 arguments must be of the same dimensions, which will also be the dimension\nof the result.  The 'if' tensor must be of type boolean, the 'then' and the\n'else' tensor must be of the same type, which will also be the type of the\nresult.\n\nEach coefficient in the result is equal to the corresponding coefficient in the\n'then' tensor if the corresponding value in the 'if' tensor is true. If not, the\nresulting coefficient will come from the 'else' tensor.\n\n\n## Contraction\n\nTensor *contractions* are a generalization of the matrix product to the\nmultidimensional case.\n\n    // Create 2 matrices using tensors of rank 2\n    Eigen::Tensor<int, 2> a(2, 3);\n    a.setValues({{1, 2, 3}, {6, 5, 4}});\n    Eigen::Tensor<int, 2> b(3, 2);\n    b.setValues({{1, 2}, {4, 5}, {5, 6}});\n\n    // Compute the traditional matrix product\n    Eigen::array<Eigen::IndexPair<int>, 1> product_dims = { Eigen::IndexPair<int>(1, 0) };\n    Eigen::Tensor<int, 2> AB = a.contract(b, product_dims);\n\n    // Compute the product of the transpose of the matrices\n    Eigen::array<Eigen::IndexPair<int>, 1> transposed_product_dims = { Eigen::IndexPair<int>(0, 1) };\n    Eigen::Tensor<int, 2> AtBt = a.contract(b, transposed_product_dims);\n\n    // Contraction to scalar value using a double contraction.\n    // First coordinate of both tensors are contracted as well as both second coordinates, i.e., this computes the sum of the squares of the elements.\n    Eigen::array<Eigen::IndexPair<int>, 2> double_contraction_product_dims = { Eigen::IndexPair<int>(0, 0), Eigen::IndexPair<int>(1, 1) };\n    Eigen::Tensor<int, 0> AdoubleContractedA = a.contract(a, double_contraction_product_dims);\n\n    // Extracting the scalar value of the tensor contraction for further usage\n    int value = AdoubleContractedA(0);\n\n## Reduction Operations\n\nA *Reduction* operation returns a tensor with fewer dimensions than the\noriginal tensor.  The values in the returned tensor are computed by applying a\n*reduction operator* to slices of values from the original tensor.  You specify\nthe dimensions along which the slices are made.\n\nThe Eigen Tensor library provides a set of predefined reduction operators such\nas `maximum()` and `sum()` and lets you define additional operators by\nimplementing a few methods from a reductor template.\n\n### Reduction Dimensions\n\nAll reduction operations take a single parameter of type\n`<TensorType>::``Dimensions` which can always be specified as an array of\nints.  These are called the \"reduction dimensions.\"  The values are the indices\nof the dimensions of the input tensor over which the reduction is done.  The\nparameter can have at most as many element as the rank of the input tensor;\neach element must be less than the tensor rank, as it indicates one of the\ndimensions to reduce.\n\nEach dimension of the input tensor should occur at most once in the reduction\ndimensions as the implementation does not remove duplicates.\n\nThe order of the values in the reduction dimensions does not affect the\nresults, but the code may execute faster if you list the dimensions in\nincreasing order.\n\nExample: Reduction along one dimension.\n\n    // Create a tensor of 2 dimensions\n    Eigen::Tensor<int, 2> a(2, 3);\n    a.setValues({{1, 2, 3}, {6, 5, 4}});\n    // Reduce it along the second dimension (1)...\n    Eigen::array<int, 1> dims({1 /* dimension to reduce */});\n    // ...using the \"maximum\" operator.\n    // The result is a tensor with one dimension.  The size of\n    // that dimension is the same as the first (non-reduced) dimension of a.\n    Eigen::Tensor<int, 1> b = a.maximum(dims);\n    cout << \"a\" << endl << a << endl << endl;\n    cout << \"b\" << endl << b << endl << endl;\n    =>\n    a\n    1 2 3\n    6 5 4\n\n    b\n    3\n    6\n\nExample: Reduction along two dimensions.\n\n    Eigen::Tensor<float, 3, Eigen::ColMajor> a(2, 3, 4);\n    a.setValues({{{0.0f, 1.0f, 2.0f, 3.0f},\n                  {7.0f, 6.0f, 5.0f, 4.0f},\n                  {8.0f, 9.0f, 10.0f, 11.0f}},\n                 {{12.0f, 13.0f, 14.0f, 15.0f},\n                  {19.0f, 18.0f, 17.0f, 16.0f},\n                  {20.0f, 21.0f, 22.0f, 23.0f}}});\n    // The tensor a has 3 dimensions.  We reduce along the\n    // first 2, resulting in a tensor with a single dimension\n    // of size 4 (the last dimension of a.)\n    // Note that we pass the array of reduction dimensions\n    // directly to the maximum() call.\n    Eigen::Tensor<float, 1, Eigen::ColMajor> b =\n        a.maximum(Eigen::array<int, 2>({0, 1}));\n    cout << \"b\" << endl << b << endl << endl;\n    =>\n    b\n    20\n    21\n    22\n    23\n\n#### Reduction along all dimensions\n\nAs a special case, if you pass no parameter to a reduction operation the\noriginal tensor is reduced along *all* its dimensions.  The result is a\nscalar, represented as a zero-dimension tensor.\n\n    Eigen::Tensor<float, 3> a(2, 3, 4);\n    a.setValues({{{0.0f, 1.0f, 2.0f, 3.0f},\n                  {7.0f, 6.0f, 5.0f, 4.0f},\n                  {8.0f, 9.0f, 10.0f, 11.0f}},\n                 {{12.0f, 13.0f, 14.0f, 15.0f},\n                  {19.0f, 18.0f, 17.0f, 16.0f},\n                  {20.0f, 21.0f, 22.0f, 23.0f}}});\n    // Reduce along all dimensions using the sum() operator.\n    Eigen::Tensor<float, 0> b = a.sum();\n    cout << \"b\" << endl << b << endl << endl;\n    =>\n    b\n    276\n\n\n### <Operation> sum(const Dimensions& new_dims)\n### <Operation> sum()\n\nReduce a tensor using the sum() operator.  The resulting values\nare the sum of the reduced values.\n\n### <Operation> mean(const Dimensions& new_dims)\n### <Operation> mean()\n\nReduce a tensor using the mean() operator.  The resulting values\nare the mean of the reduced values.\n\n### <Operation> maximum(const Dimensions& new_dims)\n### <Operation> maximum()\n\nReduce a tensor using the maximum() operator.  The resulting values are the\nlargest of the reduced values.\n\n### <Operation> minimum(const Dimensions& new_dims)\n### <Operation> minimum()\n\nReduce a tensor using the minimum() operator.  The resulting values\nare the smallest of the reduced values.\n\n### <Operation> prod(const Dimensions& new_dims)\n### <Operation> prod()\n\nReduce a tensor using the prod() operator.  The resulting values\nare the product of the reduced values.\n\n### <Operation> all(const Dimensions& new_dims)\n### <Operation> all()\nReduce a tensor using the all() operator.  Casts tensor to bool and then checks\nwhether all elements are true.  Runs through all elements rather than\nshort-circuiting, so may be significantly inefficient.\n\n### <Operation> any(const Dimensions& new_dims)\n### <Operation> any()\nReduce a tensor using the any() operator.  Casts tensor to bool and then checks\nwhether any element is true.  Runs through all elements rather than\nshort-circuiting, so may be significantly inefficient.\n\n\n### <Operation> reduce(const Dimensions& new_dims, const Reducer& reducer)\n\nReduce a tensor using a user-defined reduction operator.  See `SumReducer`\nin TensorFunctors.h for information on how to implement a reduction operator.\n\n\n## Trace\n\nA *Trace* operation returns a tensor with fewer dimensions than the original\ntensor. It returns a tensor whose elements are the sum of the elements of the\noriginal tensor along the main diagonal for a list of specified dimensions, the\n\"trace dimensions\". Similar to the `Reduction Dimensions`, the trace dimensions\nare passed as an input parameter to the operation, are of type `<TensorType>::``Dimensions`\n, and have the same requirements when passed as an input parameter. In addition,\nthe trace dimensions must have the same size.\n\nExample: Trace along 2 dimensions.\n\n    // Create a tensor of 3 dimensions\n    Eigen::Tensor<int, 3> a(2, 2, 3);\n    a.setValues({{{1, 2, 3}, {4, 5, 6}}, {{7, 8, 9}, {10, 11, 12}}});\n    // Specify the dimensions along which the trace will be computed.\n    // In this example, the trace can only be computed along the dimensions\n    // with indices 0 and 1\n    Eigen::array<int, 2> dims({0, 1});\n    // The output tensor contains all but the trace dimensions.\n    Tensor<int, 1> a_trace = a.trace(dims);\n    cout << \"a_trace:\" << endl;\n    cout << a_trace << endl;\n    =>\n    a_trace:\n    11\n    13\n    15\n\n\n### <Operation> trace(const Dimensions& new_dims)\n### <Operation> trace()\n\nAs a special case, if no parameter is passed to the operation, trace is computed\nalong *all* dimensions of the input tensor.\n\nExample: Trace along all dimensions.\n\n    // Create a tensor of 3 dimensions, with all dimensions having the same size.\n    Eigen::Tensor<int, 3> a(3, 3, 3);\n    a.setValues({{{1, 2, 3}, {4, 5, 6}, {7, 8, 9}},\n                {{10, 11, 12}, {13, 14, 15}, {16, 17, 18}},\n                {{19, 20, 21}, {22, 23, 24}, {25, 26, 27}}});\n    // Result is a zero dimension tensor\n    Tensor<int, 0> a_trace = a.trace();\n    cout<<\"a_trace:\"<<endl;\n    cout<<a_trace<<endl;\n    =>\n    a_trace:\n    42\n\n\n## Scan Operations\n\nA *Scan* operation returns a tensor with the same dimensions as the original\ntensor. The operation performs an inclusive scan along the specified\naxis, which means it computes a running total along the axis for a given\nreduction operation.\nIf the reduction operation corresponds to summation, then this computes the\nprefix sum of the tensor along the given axis.\n\nExample:\ndd a comment to this line\n\n    // Create a tensor of 2 dimensions\n    Eigen::Tensor<int, 2> a(2, 3);\n    a.setValues({{1, 2, 3}, {4, 5, 6}});\n    // Scan it along the second dimension (1) using summation\n    Eigen::Tensor<int, 2> b = a.cumsum(1);\n    // The result is a tensor with the same size as the input\n    cout << \"a\" << endl << a << endl << endl;\n    cout << \"b\" << endl << b << endl << endl;\n    =>\n    a\n    1 2 3\n    4 5 6\n\n    b\n    1  3  6\n    4  9 15\n\n### <Operation> cumsum(const Index& axis)\n\nPerform a scan by summing consecutive entries.\n\n### <Operation> cumprod(const Index& axis)\n\nPerform a scan by multiplying consecutive entries.\n\n\n## Convolutions\n\n### <Operation> convolve(const Kernel& kernel, const Dimensions& dims)\n\nReturns a tensor that is the output of the convolution of the input tensor with the kernel,\nalong the specified dimensions of the input tensor. The dimension size for dimensions of the output tensor\nwhich were part of the convolution will be reduced by the formula:\noutput_dim_size = input_dim_size - kernel_dim_size + 1 (requires: input_dim_size >= kernel_dim_size).\nThe dimension sizes for dimensions that were not part of the convolution will remain the same.\nPerformance of the convolution can depend on the length of the stride(s) of the input tensor dimension(s) along which the\nconvolution is computed (the first dimension has the shortest stride for ColMajor, whereas RowMajor's shortest stride is\nfor the last dimension).\n\n    // Compute convolution along the second and third dimension.\n    Tensor<float, 4, DataLayout> input(3, 3, 7, 11);\n    Tensor<float, 2, DataLayout> kernel(2, 2);\n    Tensor<float, 4, DataLayout> output(3, 2, 6, 11);\n    input.setRandom();\n    kernel.setRandom();\n\n    Eigen::array<ptrdiff_t, 2> dims({1, 2});  // Specify second and third dimension for convolution.\n    output = input.convolve(kernel, dims);\n\n    for (int i = 0; i < 3; ++i) {\n      for (int j = 0; j < 2; ++j) {\n        for (int k = 0; k < 6; ++k) {\n          for (int l = 0; l < 11; ++l) {\n            const float result = output(i,j,k,l);\n            const float expected = input(i,j+0,k+0,l) * kernel(0,0) +\n                                   input(i,j+1,k+0,l) * kernel(1,0) +\n                                   input(i,j+0,k+1,l) * kernel(0,1) +\n                                   input(i,j+1,k+1,l) * kernel(1,1);\n            VERIFY_IS_APPROX(result, expected);\n          }\n        }\n      }\n    }\n\n\n## Geometrical Operations\n\nThese operations return a Tensor with different dimensions than the original\nTensor.  They can be used to access slices of tensors, see them with different\ndimensions, or pad tensors with additional data.\n\n### <Operation> reshape(const Dimensions& new_dims)\n\nReturns a view of the input tensor that has been reshaped to the specified\nnew dimensions.  The argument new_dims is an array of Index values.  The\nrank of the resulting tensor is equal to the number of elements in new_dims.\n\nThe product of all the sizes in the new dimension array must be equal to\nthe number of elements in the input tensor.\n\n    // Increase the rank of the input tensor by introducing a new dimension\n    // of size 1.\n    Tensor<float, 2> input(7, 11);\n    array<int, 3> three_dims{{7, 11, 1}};\n    Tensor<float, 3> result = input.reshape(three_dims);\n\n    // Decrease the rank of the input tensor by merging 2 dimensions;\n    array<int, 1> one_dim{{7 * 11}};\n    Tensor<float, 1> result = input.reshape(one_dim);\n\nThis operation does not move any data in the input tensor, so the resulting\ncontents of a reshaped Tensor depend on the data layout of the original Tensor.\n\nFor example this is what happens when you `reshape()` a 2D ColMajor tensor\nto one dimension:\n\n    Eigen::Tensor<float, 2, Eigen::ColMajor> a(2, 3);\n    a.setValues({{0.0f, 100.0f, 200.0f}, {300.0f, 400.0f, 500.0f}});\n    Eigen::array<Eigen::DenseIndex, 1> one_dim({3 * 2});\n    Eigen::Tensor<float, 1, Eigen::ColMajor> b = a.reshape(one_dim);\n    cout << \"b\" << endl << b << endl;\n    =>\n    b\n      0\n    300\n    100\n    400\n    200\n    500\n\nThis is what happens when the 2D Tensor is RowMajor:\n\n    Eigen::Tensor<float, 2, Eigen::RowMajor> a(2, 3);\n    a.setValues({{0.0f, 100.0f, 200.0f}, {300.0f, 400.0f, 500.0f}});\n    Eigen::array<Eigen::DenseIndex, 1> one_dim({3 * 2});\n    Eigen::Tensor<float, 1, Eigen::RowMajor> b = a.reshape(one_dim);\n    cout << \"b\" << endl << b << endl;\n    =>\n    b\n      0\n    100\n    200\n    300\n    400\n    500\n\nThe reshape operation is a lvalue. In other words, it can be used on the left\nside of the assignment operator.\n\nThe previous example can be rewritten as follow:\n\n    Eigen::Tensor<float, 2, Eigen::ColMajor> a(2, 3);\n    a.setValues({{0.0f, 100.0f, 200.0f}, {300.0f, 400.0f, 500.0f}});\n    Eigen::array<Eigen::DenseIndex, 2> two_dim({2, 3});\n    Eigen::Tensor<float, 1, Eigen::ColMajor> b(6);\n    b.reshape(two_dim) = a;\n    cout << \"b\" << endl << b << endl;\n    =>\n    b\n      0\n    300\n    100\n    400\n    200\n    500\n\nNote that \"b\" itself was not reshaped but that instead the assignment is done to\nthe reshape view of b.\n\n\n### <Operation> shuffle(const Shuffle& shuffle)\n\nReturns a copy of the input tensor whose dimensions have been\nreordered according to the specified permutation. The argument shuffle\nis an array of Index values. Its size is the rank of the input\ntensor. It must contain a permutation of 0, 1, ..., rank - 1. The i-th\ndimension of the output tensor equals to the size of the shuffle[i]-th\ndimension of the input tensor. For example:\n\n    // Shuffle all dimensions to the left by 1.\n    Tensor<float, 3> input(20, 30, 50);\n    // ... set some values in input.\n    Tensor<float, 3> output = input.shuffle({1, 2, 0})\n\n    eigen_assert(output.dimension(0) == 30);\n    eigen_assert(output.dimension(1) == 50);\n    eigen_assert(output.dimension(2) == 20);\n\nIndices into the output tensor are shuffled accordingly to formulate\nindices into the input tensor. For example, one can assert in the above\ncode snippet that:\n\n    eigen_assert(output(3, 7, 11) == input(11, 3, 7));\n\nIn general, one can assert that\n\n    eigen_assert(output(..., indices[shuffle[i]], ...) ==\n                 input(..., indices[i], ...))\n\nThe shuffle operation results in a lvalue, which means that it can be assigned\nto. In other words, it can be used on the left side of the assignment operator.\n\nLet's rewrite the previous example to take advantage of this feature:\n\n    // Shuffle all dimensions to the left by 1.\n    Tensor<float, 3> input(20, 30, 50);\n    // ... set some values in input.\n    Tensor<float, 3> output(30, 50, 20);\n    output.shuffle({2, 0, 1}) = input;\n\n\n### <Operation> stride(const Strides& strides)\n\nReturns a view of the input tensor that strides (skips stride-1\nelements) along each of the dimensions.  The argument strides is an\narray of Index values.  The dimensions of the resulting tensor are\nceil(input_dimensions[i] / strides[i]).\n\nFor example this is what happens when you `stride()` a 2D tensor:\n\n    Eigen::Tensor<int, 2> a(4, 3);\n    a.setValues({{0, 100, 200}, {300, 400, 500}, {600, 700, 800}, {900, 1000, 1100}});\n    Eigen::array<Eigen::DenseIndex, 2> strides({3, 2});\n    Eigen::Tensor<int, 2> b = a.stride(strides);\n    cout << \"b\" << endl << b << endl;\n    =>\n    b\n       0   200\n     900  1100\n\nIt is possible to assign a tensor to a stride:\n    Tensor<float, 3> input(20, 30, 50);\n    // ... set some values in input.\n    Tensor<float, 3> output(40, 90, 200);\n    output.stride({2, 3, 4}) = input;\n\n\n### <Operation> slice(const StartIndices& offsets, const Sizes& extents)\n\nReturns a sub-tensor of the given tensor. For each dimension i, the slice is\nmade of the coefficients stored between offset[i] and offset[i] + extents[i] in\nthe input tensor.\n\n    Eigen::Tensor<int, 2> a(4, 3);\n    a.setValues({{0, 100, 200}, {300, 400, 500},\n                 {600, 700, 800}, {900, 1000, 1100}});\n    Eigen::array<Eigen::Index, 2> offsets = {1, 0};\n    Eigen::array<Eigen::Index, 2> extents = {2, 2};\n    Eigen::Tensor<int, 2> slice = a.slice(offsets, extents);\n    cout << \"a\" << endl << a << endl;\n    =>\n    a\n       0   100   200\n     300   400   500\n     600   700   800\n     900  1000  1100\n    cout << \"slice\" << endl << slice << endl;\n    =>\n    slice\n     300   400\n     600   700\n\n\n### <Operation> chip(const Index offset, const Index dim)\n\nA chip is a special kind of slice. It is the subtensor at the given offset in\nthe dimension dim. The returned tensor has one fewer dimension than the input\ntensor: the dimension dim is removed.\n\nFor example, a matrix chip would be either a row or a column of the input\nmatrix.\n\n    Eigen::Tensor<int, 2> a(4, 3);\n    a.setValues({{0, 100, 200}, {300, 400, 500},\n                 {600, 700, 800}, {900, 1000, 1100}});\n    Eigen::Tensor<int, 1> row_3 = a.chip(2, 0);\n    Eigen::Tensor<int, 1> col_2 = a.chip(1, 1);\n    cout << \"a\" << endl << a << endl;\n    =>\n    a\n       0   100   200\n     300   400   500\n     600   700   800\n     900  1000  1100\n    cout << \"row_3\" << endl << row_3 << endl;\n    =>\n    row_3\n       600   700   800\n    cout << \"col_2\" << endl << col_2 << endl;\n    =>\n    col_2\n       100   400   700    1000\n\nIt is possible to assign values to a tensor chip since the chip operation is a\nlvalue. For example:\n\n    Eigen::Tensor<int, 1> a(3);\n    a.setValues({{100, 200, 300}});\n    Eigen::Tensor<int, 2> b(2, 3);\n    b.setZero();\n    b.chip(0, 0) = a;\n    cout << \"a\" << endl << a << endl;\n    =>\n    a\n     100\n     200\n     300\n    cout << \"b\" << endl << b << endl;\n    =>\n    b\n       100   200   300\n         0     0     0\n\n\n### <Operation> reverse(const ReverseDimensions& reverse)\n\nReturns a view of the input tensor that reverses the order of the coefficients\nalong a subset of the dimensions.  The argument reverse is an array of boolean\nvalues that indicates whether or not the order of the coefficients should be\nreversed along each of the dimensions.  This operation preserves the dimensions\nof the input tensor.\n\nFor example this is what happens when you `reverse()` the first dimension\nof a 2D tensor:\n\n    Eigen::Tensor<int, 2> a(4, 3);\n    a.setValues({{0, 100, 200}, {300, 400, 500},\n                {600, 700, 800}, {900, 1000, 1100}});\n    Eigen::array<bool, 2> reverse({true, false});\n    Eigen::Tensor<int, 2> b = a.reverse(reverse);\n    cout << \"a\" << endl << a << endl << \"b\" << endl << b << endl;\n    =>\n    a\n       0   100   200\n     300   400   500\n     600   700   800\n     900  1000  1100\n    b\n     900  1000  1100\n     600   700   800\n     300   400   500\n       0   100   200\n\n\n### <Operation> broadcast(const Broadcast& broadcast)\n\nReturns a view of the input tensor in which the input is replicated one to many\ntimes.\nThe broadcast argument specifies how many copies of the input tensor need to be\nmade in each of the dimensions.\n\n    Eigen::Tensor<int, 2> a(2, 3);\n    a.setValues({{0, 100, 200}, {300, 400, 500}});\n    Eigen::array<int, 2> bcast({3, 2});\n    Eigen::Tensor<int, 2> b = a.broadcast(bcast);\n    cout << \"a\" << endl << a << endl << \"b\" << endl << b << endl;\n    =>\n    a\n       0   100   200\n     300   400   500\n    b\n       0   100   200    0   100   200\n     300   400   500  300   400   500\n       0   100   200    0   100   200\n     300   400   500  300   400   500\n       0   100   200    0   100   200\n     300   400   500  300   400   500\n\n### <Operation> concatenate(const OtherDerived& other, Axis axis)\n\nTODO\n\n### <Operation>  pad(const PaddingDimensions& padding)\n\nReturns a view of the input tensor in which the input is padded with zeros.\n\n    Eigen::Tensor<int, 2> a(2, 3);\n    a.setValues({{0, 100, 200}, {300, 400, 500}});\n    Eigen::array<pair<int, int>, 2> paddings;\n    paddings[0] = make_pair(0, 1);\n    paddings[1] = make_pair(2, 3);\n    Eigen::Tensor<int, 2> b = a.pad(paddings);\n    cout << \"a\" << endl << a << endl << \"b\" << endl << b << endl;\n    =>\n    a\n       0   100   200\n     300   400   500\n    b\n       0     0     0    0\n       0     0     0    0\n       0   100   200    0\n     300   400   500    0\n       0     0     0    0\n       0     0     0    0\n       0     0     0    0\n\n\n### <Operation>  extract_patches(const PatchDims& patch_dims)\n\nReturns a tensor of coefficient patches extracted from the input tensor, where\neach patch is of dimension specified by 'patch_dims'. The returned tensor has\none greater dimension than the input tensor, which is used to index each patch.\nThe patch index in the output tensor depends on the data layout of the input\ntensor: the patch index is the last dimension ColMajor layout, and the first\ndimension in RowMajor layout.\n\nFor example, given the following input tensor:\n\n    Eigen::Tensor<float, 2, DataLayout> tensor(3,4);\n    tensor.setValues({{0.0f, 1.0f, 2.0f, 3.0f},\n                      {4.0f, 5.0f, 6.0f, 7.0f},\n                      {8.0f, 9.0f, 10.0f, 11.0f}});\n\n    cout << \"tensor: \" << endl << tensor << endl;\n    =>\n    tensor:\n     0   1   2   3\n     4   5   6   7\n     8   9  10  11\n\nSix 2x2 patches can be extracted and indexed using the following code:\n\n    Eigen::Tensor<float, 3, DataLayout> patch;\n    Eigen::array<ptrdiff_t, 2> patch_dims;\n    patch_dims[0] = 2;\n    patch_dims[1] = 2;\n    patch = tensor.extract_patches(patch_dims);\n    for (int k = 0; k < 6; ++k) {\n      cout << \"patch index: \" << k << endl;\n      for (int i = 0; i < 2; ++i) {\n    \tfor (int j = 0; j < 2; ++j) {\n    \t  if (DataLayout == ColMajor) {\n    \t\tcout << patch(i, j, k) << \" \";\n    \t  } else {\n    \t\tcout << patch(k, i, j) << \" \";\n    \t  }\n    \t}\n    \tcout << endl;\n      }\n    }\n\nThis code results in the following output when the data layout is ColMajor:\n\n    patch index: 0\n    0 1\n    4 5\n    patch index: 1\n    4 5\n    8 9\n    patch index: 2\n    1 2\n    5 6\n    patch index: 3\n    5 6\n    9 10\n    patch index: 4\n    2 3\n    6 7\n    patch index: 5\n    6 7\n    10 11\n\nThis code results in the following output when the data layout is RowMajor:\n(NOTE: the set of patches is the same as in ColMajor, but are indexed differently).\n\n    patch index: 0\n    0 1\n    4 5\n    patch index: 1\n    1 2\n    5 6\n    patch index: 2\n    2 3\n    6 7\n    patch index: 3\n    4 5\n    8 9\n    patch index: 4\n    5 6\n    9 10\n    patch index: 5\n    6 7\n    10 11\n\n### <Operation>  extract_image_patches(const Index patch_rows, const Index patch_cols, const Index row_stride, const Index col_stride, const PaddingType padding_type)\n\nReturns a tensor of coefficient image patches extracted from the input tensor,\nwhich is expected to have dimensions ordered as follows (depending on the data\nlayout of the input tensor, and the number of additional dimensions 'N'):\n\n*) ColMajor\n1st dimension: channels (of size d)\n2nd dimension: rows (of size r)\n3rd dimension: columns (of size c)\n4th-Nth dimension: time (for video) or batch (for bulk processing).\n\n*) RowMajor (reverse order of ColMajor)\n1st-Nth dimension: time (for video) or batch (for bulk processing).\nN+1'th dimension: columns (of size c)\nN+2'th dimension: rows (of size r)\nN+3'th dimension: channels (of size d)\n\nThe returned tensor has one greater dimension than the input tensor, which is\nused to index each patch. The patch index in the output tensor depends on the\ndata layout of the input tensor: the patch index is the 4'th dimension in\nColMajor layout, and the 4'th from the last dimension in RowMajor layout.\n\nFor example, given the following input tensor with the following dimension\nsizes:\n *) depth:   2\n *) rows:    3\n *) columns: 5\n *) batch:   7\n\n    Tensor<float, 4> tensor(2,3,5,7);\n    Tensor<float, 4, RowMajor> tensor_row_major = tensor.swap_layout();\n\n2x2 image patches can be extracted and indexed using the following code:\n\n*) 2D patch: ColMajor (patch indexed by second-to-last dimension)\n\n    Tensor<float, 5> twod_patch;\n    twod_patch = tensor.extract_image_patches<2, 2>();\n    // twod_patch.dimension(0) == 2\n    // twod_patch.dimension(1) == 2\n    // twod_patch.dimension(2) == 2\n    // twod_patch.dimension(3) == 3*5\n    // twod_patch.dimension(4) == 7\n\n*) 2D patch: RowMajor (patch indexed by the second dimension)\n\n    Tensor<float, 5, RowMajor> twod_patch_row_major;\n    twod_patch_row_major = tensor_row_major.extract_image_patches<2, 2>();\n    // twod_patch_row_major.dimension(0) == 7\n    // twod_patch_row_major.dimension(1) == 3*5\n    // twod_patch_row_major.dimension(2) == 2\n    // twod_patch_row_major.dimension(3) == 2\n    // twod_patch_row_major.dimension(4) == 2\n\n## Special Operations\n\n### <Operation> cast<T>()\n\nReturns a tensor of type T with the same dimensions as the original tensor.\nThe returned tensor contains the values of the original tensor converted to\ntype T.\n\n    Eigen::Tensor<float, 2> a(2, 3);\n    Eigen::Tensor<int, 2> b = a.cast<int>();\n\nThis can be useful for example if you need to do element-wise division of\nTensors of integers.  This is not currently supported by the Tensor library\nbut you can easily cast the tensors to floats to do the division:\n\n    Eigen::Tensor<int, 2> a(2, 3);\n    a.setValues({{0, 1, 2}, {3, 4, 5}});\n    Eigen::Tensor<int, 2> b =\n        (a.cast<float>() / a.constant(2).cast<float>()).cast<int>();\n    cout << \"a\" << endl << a << endl << endl;\n    cout << \"b\" << endl << b << endl << endl;\n    =>\n    a\n    0 1 2\n    3 4 5\n\n    b\n    0 0 1\n    1 2 2\n\n\n### <Operation>     eval()\n\nTODO\n\n\n## Representation of scalar values\n\nScalar values are often represented by tensors of size 1 and rank 0.For example\nTensor<T, N>::maximum() currently returns a Tensor<T, 0>. Similarly, the inner\nproduct of 2 1d tensors (through contractions) returns a 0d tensor.\n\n## Limitations\n\n*   The number of tensor dimensions is currently limited to 250 when using a\n    compiler that supports cxx11. It is limited to only 5 for older compilers.\n*   The IndexList class requires a cxx11 compliant compiler. You can use an\n    array of indices instead if you don't have access to a modern compiler.\n*   On GPUs only floating point values are properly tested and optimized for.\n*   Complex and integer values are known to be broken on GPUs. If you try to use\n    them you'll most likely end up triggering a static assertion failure such as\n    EIGEN_STATIC_ASSERT(packetSize > 1, YOU_MADE_A_PROGRAMMING_MISTAKE)\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/Tensor.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_H\n#define EIGEN_CXX11_TENSOR_TENSOR_H\n\nnamespace Eigen {\n\n/** \\class Tensor\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief The tensor class.\n  *\n  * The %Tensor class is the work-horse for all \\em dense tensors within Eigen.\n  *\n  * The %Tensor class encompasses only dynamic-size objects so far.\n  *\n  * The first two template parameters are required:\n  * \\tparam Scalar_  Numeric type, e.g. float, double, int or `std::complex<float>`.\n  *                 User defined scalar types are supported as well (see \\ref user_defined_scalars \"here\").\n  * \\tparam NumIndices_ Number of indices (i.e. rank of the tensor)\n  *\n  * The remaining template parameters are optional -- in most cases you don't have to worry about them.\n  * \\tparam Options_  A combination of either \\b #RowMajor or \\b #ColMajor, and of either\n  *                 \\b #AutoAlign or \\b #DontAlign.\n  *                 The former controls \\ref TopicStorageOrders \"storage order\", and defaults to column-major. The latter controls alignment, which is required\n  *                 for vectorization. It defaults to aligning tensors. Note that tensors currently do not support any operations that profit from vectorization.\n  *                 Support for such operations (i.e. adding two tensors etc.) is planned.\n  *\n  * You can access elements of tensors using normal subscripting:\n  *\n  * \\code\n  * Eigen::Tensor<double, 4> t(10, 10, 10, 10);\n  * t(0, 1, 2, 3) = 42.0;\n  * \\endcode\n  *\n  * This class can be extended with the help of the plugin mechanism described on the page\n  * \\ref TopicCustomizing_Plugins by defining the preprocessor symbol \\c EIGEN_TENSOR_PLUGIN,\n  * \\c EIGEN_TENSORBASE_PLUGIN, and \\c EIGEN_READONLY_TENSORBASE_PLUGIN.\n  *\n  * <i><b>Some notes:</b></i>\n  *\n  * <dl>\n  * <dt><b>Relation to other parts of Eigen:</b></dt>\n  * <dd>The midterm development goal for this class is to have a similar hierarchy as Eigen uses for matrices, so that\n  * taking blocks or using tensors in expressions is easily possible, including an interface with the vector/matrix code\n  * by providing .asMatrix() and .asVector() (or similar) methods for rank 2 and 1 tensors. However, currently, the %Tensor\n  * class does not provide any of these features and is only available as a stand-alone class that just allows for\n  * coefficient access. Also, when fixed-size tensors are implemented, the number of template arguments is likely to\n  * change dramatically.</dd>\n  * </dl>\n  *\n  * \\ref TopicStorageOrders\n  */\n\ntemplate<typename Scalar_, int NumIndices_, int Options_, typename IndexType_>\nclass Tensor : public TensorBase<Tensor<Scalar_, NumIndices_, Options_, IndexType_> >\n{\n  public:\n    typedef Tensor<Scalar_, NumIndices_, Options_, IndexType_> Self;\n    typedef TensorBase<Tensor<Scalar_, NumIndices_, Options_, IndexType_> > Base;\n    typedef typename Eigen::internal::nested<Self>::type Nested;\n    typedef typename internal::traits<Self>::StorageKind StorageKind;\n    typedef typename internal::traits<Self>::Index Index;\n    typedef Scalar_ Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef typename Base::CoeffReturnType CoeffReturnType;\n\n    enum {\n      IsAligned = bool(EIGEN_MAX_ALIGN_BYTES>0) & !(Options_&DontAlign),\n      Layout = Options_ & RowMajor ? RowMajor : ColMajor,\n      CoordAccess = true,\n      RawAccess = true\n    };\n\n    static const int Options = Options_;\n    static const int NumIndices = NumIndices_;\n    typedef DSizes<Index, NumIndices_> Dimensions;\n\n  protected:\n    TensorStorage<Scalar, Dimensions, Options> m_storage;\n\n#ifdef EIGEN_HAS_SFINAE\n    template<typename CustomIndices>\n    struct isOfNormalIndex{\n      static const bool is_array = internal::is_base_of<array<Index, NumIndices>, CustomIndices>::value;\n      static const bool is_int = NumTraits<CustomIndices>::IsInteger;\n      static const bool value = is_array | is_int;\n    };\n#endif\n\n  public:\n    // Metadata\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index                         rank()                   const { return NumIndices; }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index                         dimension(std::size_t n) const { return m_storage.dimensions()[n]; }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions&             dimensions()             const { return m_storage.dimensions(); }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index                         size()                   const { return m_storage.size(); }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar                        *data()                        { return m_storage.data(); }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar                  *data()                  const { return m_storage.data(); }\n\n    // This makes EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED\n    // work, because that uses base().coeffRef() - and we don't yet\n    // implement a similar class hierarchy\n    inline Self& base()             { return *this; }\n    inline const Self& base() const { return *this; }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(Index firstIndex, Index secondIndex, IndexTypes... otherIndices) const\n    {\n      // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return coeff(array<Index, NumIndices>{{firstIndex, secondIndex, otherIndices...}});\n    }\n#endif\n\n    // normal indices\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(const array<Index, NumIndices>& indices) const\n    {\n      eigen_internal_assert(checkIndexRange(indices));\n      return m_storage.data()[linearizedIndex(indices)];\n    }\n\n    // custom indices\n#ifdef EIGEN_HAS_SFINAE\n    template<typename CustomIndices,\n             EIGEN_SFINAE_ENABLE_IF( !(isOfNormalIndex<CustomIndices>::value) )\n    >\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(CustomIndices& indices) const\n    {\n        return coeff(internal::customIndices2Array<Index,NumIndices>(indices));\n    }\n#endif\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff() const\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return m_storage.data()[0];\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(Index index) const\n    {\n      eigen_internal_assert(index >= 0 && index < size());\n      return m_storage.data()[index];\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes>\n    inline Scalar& coeffRef(Index firstIndex, Index secondIndex, IndexTypes... otherIndices)\n    {\n      // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return coeffRef(array<Index, NumIndices>{{firstIndex, secondIndex, otherIndices...}});\n    }\n#endif\n\n    // normal indices\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(const array<Index, NumIndices>& indices)\n    {\n      eigen_internal_assert(checkIndexRange(indices));\n      return m_storage.data()[linearizedIndex(indices)];\n    }\n\n    // custom indices\n#ifdef EIGEN_HAS_SFINAE\n    template<typename CustomIndices,\n             EIGEN_SFINAE_ENABLE_IF( !(isOfNormalIndex<CustomIndices>::value) )\n             >\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(CustomIndices& indices)\n    {\n        return coeffRef(internal::customIndices2Array<Index,NumIndices>(indices));\n    }\n#endif\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef()\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return m_storage.data()[0];\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index index)\n    {\n      eigen_internal_assert(index >= 0 && index < size());\n      return m_storage.data()[index];\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes>\n    inline const Scalar& operator()(Index firstIndex, Index secondIndex, IndexTypes... otherIndices) const\n    {\n      // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return this->operator()(array<Index, NumIndices>{{firstIndex, secondIndex, otherIndices...}});\n    }\n#else\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1) const\n    {\n      return coeff(array<Index, 2>(i0, i1));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2) const\n    {\n      return coeff(array<Index, 3>(i0, i1, i2));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2, Index i3) const\n    {\n      return coeff(array<Index, 4>(i0, i1, i2, i3));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2, Index i3, Index i4) const\n    {\n      return coeff(array<Index, 5>(i0, i1, i2, i3, i4));\n    }\n#endif\n\n    // custom indices\n#ifdef EIGEN_HAS_SFINAE\n    template<typename CustomIndices,\n             EIGEN_SFINAE_ENABLE_IF( !(isOfNormalIndex<CustomIndices>::value) )\n    >\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator()(CustomIndices& indices) const\n    {\n        return coeff(internal::customIndices2Array<Index,NumIndices>(indices));\n    }\n#endif\n\n    // normal indices\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator()(const array<Index, NumIndices>& indices) const\n    {\n      return coeff(indices);\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator()(Index index) const\n    {\n      eigen_internal_assert(index >= 0 && index < size());\n      return coeff(index);\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator()() const\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return coeff();\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator[](Index index) const\n    {\n      // The bracket operator is only for vectors, use the parenthesis operator instead.\n      EIGEN_STATIC_ASSERT(NumIndices == 1, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return coeff(index);\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes>\n    inline Scalar& operator()(Index firstIndex, Index secondIndex, IndexTypes... otherIndices)\n    {\n      // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return operator()(array<Index, NumIndices>{{firstIndex, secondIndex, otherIndices...}});\n    }\n#else\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1)\n    {\n      return coeffRef(array<Index, 2>(i0, i1));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2)\n    {\n      return coeffRef(array<Index, 3>(i0, i1, i2));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3)\n    {\n      return coeffRef(array<Index, 4>(i0, i1, i2, i3));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3, Index i4)\n    {\n      return coeffRef(array<Index, 5>(i0, i1, i2, i3, i4));\n    }\n#endif\n\n    // normal indices\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator()(const array<Index, NumIndices>& indices)\n    {\n      return coeffRef(indices);\n    }\n\n    // custom indices\n#ifdef EIGEN_HAS_SFINAE\n    template<typename CustomIndices,\n             EIGEN_SFINAE_ENABLE_IF( !(isOfNormalIndex<CustomIndices>::value) )\n    >\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator()(CustomIndices& indices)\n    {\n      return coeffRef(internal::customIndices2Array<Index,NumIndices>(indices));\n    }\n#endif\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator()(Index index)\n    {\n      eigen_assert(index >= 0 && index < size());\n      return coeffRef(index);\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator()()\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return coeffRef();\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator[](Index index)\n    {\n      // The bracket operator is only for vectors, use the parenthesis operator instead\n      EIGEN_STATIC_ASSERT(NumIndices == 1, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return coeffRef(index);\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Tensor()\n      : m_storage()\n    {\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Tensor(const Self& other)\n      : m_storage(other.m_storage)\n    {\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Tensor(Index firstDimension, IndexTypes... otherDimensions)\n        : m_storage(firstDimension, otherDimensions...)\n    {\n      // The number of dimensions used to construct a tensor must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT(sizeof...(otherDimensions) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n#else\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE explicit Tensor(Index dim1)\n      : m_storage(dim1, array<Index, 1>(dim1))\n    {\n      EIGEN_STATIC_ASSERT(1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Tensor(Index dim1, Index dim2)\n      : m_storage(dim1*dim2, array<Index, 2>(dim1, dim2))\n    {\n      EIGEN_STATIC_ASSERT(2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Tensor(Index dim1, Index dim2, Index dim3)\n      : m_storage(dim1*dim2*dim3, array<Index, 3>(dim1, dim2, dim3))\n    {\n      EIGEN_STATIC_ASSERT(3 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Tensor(Index dim1, Index dim2, Index dim3, Index dim4)\n      : m_storage(dim1*dim2*dim3*dim4, array<Index, 4>(dim1, dim2, dim3, dim4))\n    {\n      EIGEN_STATIC_ASSERT(4 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Tensor(Index dim1, Index dim2, Index dim3, Index dim4, Index dim5)\n      : m_storage(dim1*dim2*dim3*dim4*dim5, array<Index, 5>(dim1, dim2, dim3, dim4, dim5))\n    {\n      EIGEN_STATIC_ASSERT(5 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n#endif\n\n    /** Normal Dimension */\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE explicit Tensor(const array<Index, NumIndices>& dimensions)\n        : m_storage(internal::array_prod(dimensions), dimensions)\n    {\n      EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED\n    }\n\n    template<typename OtherDerived>\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Tensor(const TensorBase<OtherDerived, ReadOnlyAccessors>& other)\n    {\n      typedef TensorAssignOp<Tensor, const OtherDerived> Assign;\n      Assign assign(*this, other.derived());\n      resize(TensorEvaluator<const Assign, DefaultDevice>(assign, DefaultDevice()).dimensions());\n      internal::TensorExecutor<const Assign, DefaultDevice>::run(assign, DefaultDevice());\n    }\n\n    template<typename OtherDerived>\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Tensor(const TensorBase<OtherDerived, WriteAccessors>& other)\n    {\n      typedef TensorAssignOp<Tensor, const OtherDerived> Assign;\n      Assign assign(*this, other.derived());\n      resize(TensorEvaluator<const Assign, DefaultDevice>(assign, DefaultDevice()).dimensions());\n      internal::TensorExecutor<const Assign, DefaultDevice>::run(assign, DefaultDevice());\n    }\n\n    #if EIGEN_HAS_RVALUE_REFERENCES\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Tensor(Self&& other)\n      : m_storage(std::move(other.m_storage))\n    {\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Tensor& operator=(Self&& other)\n    {\n      m_storage = std::move(other.m_storage);\n      return *this;\n    }\n    #endif\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Tensor& operator=(const Tensor& other)\n    {\n      typedef TensorAssignOp<Tensor, const Tensor> Assign;\n      Assign assign(*this, other);\n      resize(TensorEvaluator<const Assign, DefaultDevice>(assign, DefaultDevice()).dimensions());\n      internal::TensorExecutor<const Assign, DefaultDevice>::run(assign, DefaultDevice());\n      return *this;\n    }\n    template<typename OtherDerived>\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Tensor& operator=(const OtherDerived& other)\n    {\n      typedef TensorAssignOp<Tensor, const OtherDerived> Assign;\n      Assign assign(*this, other);\n      resize(TensorEvaluator<const Assign, DefaultDevice>(assign, DefaultDevice()).dimensions());\n      internal::TensorExecutor<const Assign, DefaultDevice>::run(assign, DefaultDevice());\n      return *this;\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes> EIGEN_DEVICE_FUNC\n    void resize(Index firstDimension, IndexTypes... otherDimensions)\n    {\n      // The number of dimensions used to resize a tensor must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT(sizeof...(otherDimensions) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      resize(array<Index, NumIndices>{{firstDimension, otherDimensions...}});\n    }\n#endif\n\n    /** Normal Dimension */\n    EIGEN_DEVICE_FUNC void resize(const array<Index, NumIndices>& dimensions)\n    {\n      int i;\n      Index size = Index(1);\n      for (i = 0; i < NumIndices; i++) {\n        internal::check_rows_cols_for_overflow<Dynamic>::run(size, dimensions[i]);\n        size *= dimensions[i];\n      }\n      #ifdef EIGEN_INITIALIZE_COEFFS\n        bool size_changed = size != this->size();\n        m_storage.resize(size, dimensions);\n        if(size_changed) EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED\n      #else\n        m_storage.resize(size, dimensions);\n      #endif\n    }\n\n    // Why this overload, DSizes is derived from array ??? //\n    EIGEN_DEVICE_FUNC void resize(const DSizes<Index, NumIndices>& dimensions) {\n      array<Index, NumIndices> dims;\n      for (int i = 0; i < NumIndices; ++i) {\n        dims[i] = dimensions[i];\n      }\n      resize(dims);\n    }\n\n    EIGEN_DEVICE_FUNC\n    void resize()\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      // Nothing to do: rank 0 tensors have fixed size\n    }\n\n#ifdef EIGEN_HAS_INDEX_LIST\n    template <typename FirstType, typename... OtherTypes>\n    EIGEN_DEVICE_FUNC\n    void resize(const Eigen::IndexList<FirstType, OtherTypes...>& dimensions) {\n      array<Index, NumIndices> dims;\n      for (int i = 0; i < NumIndices; ++i) {\n        dims[i] = static_cast<Index>(dimensions[i]);\n      }\n      resize(dims);\n    }\n#endif\n\n    /** Custom Dimension */\n#ifdef EIGEN_HAS_SFINAE\n    template<typename CustomDimension,\n             EIGEN_SFINAE_ENABLE_IF( !(isOfNormalIndex<CustomDimension>::value) )\n    >\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(CustomDimension& dimensions)\n    {\n      resize(internal::customIndices2Array<Index,NumIndices>(dimensions));\n    }\n#endif\n\n#ifndef EIGEN_EMULATE_CXX11_META_H\n    template <typename std::ptrdiff_t... Indices>\n    EIGEN_DEVICE_FUNC\n    void resize(const Sizes<Indices...>& dimensions) {\n      array<Index, NumIndices> dims;\n      for (int i = 0; i < NumIndices; ++i) {\n        dims[i] = static_cast<Index>(dimensions[i]);\n      }\n      resize(dims);\n    }\n#else\n    template <std::size_t V1, std::size_t V2, std::size_t V3, std::size_t V4, std::size_t V5>\n    EIGEN_DEVICE_FUNC\n    void resize(const Sizes<V1, V2, V3, V4, V5>& dimensions) {\n      array<Index, NumIndices> dims;\n      for (int i = 0; i < NumIndices; ++i) {\n        dims[i] = static_cast<Index>(dimensions[i]);\n      }\n      resize(dims);\n    }\n#endif\n\n    #ifdef EIGEN_TENSOR_PLUGIN\n    #include EIGEN_TENSOR_PLUGIN\n    #endif\n\n  protected:\n\n    bool checkIndexRange(const array<Index, NumIndices>& indices) const\n    {\n      using internal::array_apply_and_reduce;\n      using internal::array_zip_and_reduce;\n      using internal::greater_equal_zero_op;\n      using internal::logical_and_op;\n      using internal::lesser_op;\n\n      return\n        // check whether the indices are all >= 0\n        array_apply_and_reduce<logical_and_op, greater_equal_zero_op>(indices) &&\n        // check whether the indices fit in the dimensions\n        array_zip_and_reduce<logical_and_op, lesser_op>(indices, m_storage.dimensions());\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index linearizedIndex(const array<Index, NumIndices>& indices) const\n    {\n      if (Options&RowMajor) {\n        return m_storage.dimensions().IndexOfRowMajor(indices);\n      } else {\n        return m_storage.dimensions().IndexOfColMajor(indices);\n      }\n    }\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorArgMax.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Eugene Brevdo <ebrevdo@gmail.com>\n//                    Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_ARG_MAX_H\n#define EIGEN_CXX11_TENSOR_TENSOR_ARG_MAX_H\n\nnamespace Eigen {\nnamespace internal {\n\n/** \\class TensorIndexTuple\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor + Index Tuple class.\n  *\n  *\n  */\ntemplate<typename XprType>\nstruct traits<TensorIndexTupleOp<XprType> > : public traits<XprType>\n{\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef Tuple<Index, typename XprTraits::Scalar> Scalar;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n};\n\ntemplate<typename XprType>\nstruct eval<TensorIndexTupleOp<XprType>, Eigen::Dense>\n{\n  typedef const TensorIndexTupleOp<XprType>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename XprType>\nstruct nested<TensorIndexTupleOp<XprType>, 1,\n              typename eval<TensorIndexTupleOp<XprType> >::type>\n{\n  typedef TensorIndexTupleOp<XprType> type;\n};\n\n}  // end namespace internal\n\ntemplate<typename XprType>\nclass TensorIndexTupleOp : public TensorBase<TensorIndexTupleOp<XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorIndexTupleOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename Eigen::internal::nested<TensorIndexTupleOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorIndexTupleOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorIndexTupleOp>::Index Index;\n  typedef Tuple<Index, typename XprType::CoeffReturnType> CoeffReturnType;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorIndexTupleOp(const XprType& expr)\n      : m_xpr(expr) {}\n\n  EIGEN_DEVICE_FUNC\n  const typename internal::remove_all<typename XprType::Nested>::type&\n  expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n};\n\n// Eval as rvalue\ntemplate<typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorIndexTupleOp<ArgType>, Device>\n{\n  typedef TensorIndexTupleOp<ArgType> XprType;\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n\n  typedef typename TensorEvaluator<ArgType, Device>::Dimensions Dimensions;\n  static const int NumDims = internal::array_size<Dimensions>::value;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = /*TensorEvaluator<ArgType, Device>::IsAligned*/ false,\n    PacketAccess = /*TensorEvaluator<ArgType, Device>::PacketAccess*/ false,\n    BlockAccess = false,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device) { }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const {\n    return m_impl.dimensions();\n  }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType /*data*/) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    return CoeffReturnType(index, m_impl.coeff(index));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    return m_impl.costPerCoeff(vectorized) + TensorOpCost(0, 0, 1);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n\n protected:\n  TensorEvaluator<ArgType, Device> m_impl;\n};\n\nnamespace internal {\n\n/** \\class TensorTupleIndex\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Converts to Tensor<Tuple<Index, Scalar> > and reduces to Tensor<Index>.\n  *\n  */\ntemplate<typename ReduceOp, typename Dims, typename XprType>\nstruct traits<TensorTupleReducerOp<ReduceOp, Dims, XprType> > : public traits<XprType>\n{\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef Index Scalar;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions - array_size<Dims>::value;\n  static const int Layout = XprTraits::Layout;\n};\n\ntemplate<typename ReduceOp, typename Dims, typename XprType>\nstruct eval<TensorTupleReducerOp<ReduceOp, Dims, XprType>, Eigen::Dense>\n{\n  typedef const TensorTupleReducerOp<ReduceOp, Dims, XprType>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename ReduceOp, typename Dims, typename XprType>\nstruct nested<TensorTupleReducerOp<ReduceOp, Dims, XprType>, 1,\n              typename eval<TensorTupleReducerOp<ReduceOp, Dims, XprType> >::type>\n{\n  typedef TensorTupleReducerOp<ReduceOp, Dims, XprType> type;\n};\n\n}  // end namespace internal\n\ntemplate<typename ReduceOp, typename Dims, typename XprType>\nclass TensorTupleReducerOp : public TensorBase<TensorTupleReducerOp<ReduceOp, Dims, XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorTupleReducerOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename Eigen::internal::nested<TensorTupleReducerOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorTupleReducerOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorTupleReducerOp>::Index Index;\n  typedef Index CoeffReturnType;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorTupleReducerOp(const XprType& expr,\n                                                          const ReduceOp& reduce_op,\n                                                          const Index return_dim,\n                                                          const Dims& reduce_dims)\n      : m_xpr(expr), m_reduce_op(reduce_op), m_return_dim(return_dim), m_reduce_dims(reduce_dims) {}\n\n  EIGEN_DEVICE_FUNC\n  const typename internal::remove_all<typename XprType::Nested>::type&\n  expression() const { return m_xpr; }\n\n  EIGEN_DEVICE_FUNC\n  const ReduceOp& reduce_op() const { return m_reduce_op; }\n\n  EIGEN_DEVICE_FUNC\n  const Dims& reduce_dims() const { return m_reduce_dims; }\n\n  EIGEN_DEVICE_FUNC\n  Index return_dim() const { return m_return_dim; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const ReduceOp m_reduce_op;\n    const Index m_return_dim;\n    const Dims m_reduce_dims;\n};\n\n// Eval as rvalue\ntemplate<typename ReduceOp, typename Dims, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorTupleReducerOp<ReduceOp, Dims, ArgType>, Device>\n{\n  typedef TensorTupleReducerOp<ReduceOp, Dims, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename TensorIndexTupleOp<ArgType>::CoeffReturnType TupleType;\n  typedef typename TensorEvaluator<const TensorReductionOp<ReduceOp, Dims, const TensorIndexTupleOp<ArgType> >, Device>::Dimensions Dimensions;\n  typedef typename TensorEvaluator<const TensorIndexTupleOp<ArgType> , Device>::Dimensions InputDimensions;\n  static const int NumDims = internal::array_size<InputDimensions>::value;\n  typedef array<Index, NumDims> StrideDims;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n  typedef StorageMemory<TupleType, Device> TupleStorageMem;\n\n  enum {\n    IsAligned         = /*TensorEvaluator<ArgType, Device>::IsAligned*/ false,\n    PacketAccess      = /*TensorEvaluator<ArgType, Device>::PacketAccess*/ false,\n    BlockAccess       = false,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout            = TensorEvaluator<const TensorReductionOp<ReduceOp, Dims, const TensorIndexTupleOp<ArgType> >, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_orig_impl(op.expression(), device),\n        m_impl(op.expression().index_tuples().reduce(op.reduce_dims(), op.reduce_op()), device),\n        m_return_dim(op.return_dim())\n  {\n    gen_strides(m_orig_impl.dimensions(), m_strides);\n    if (Layout == static_cast<int>(ColMajor)) {\n      const Index total_size = internal::array_prod(m_orig_impl.dimensions());\n      m_stride_mod = (m_return_dim < NumDims - 1) ? m_strides[m_return_dim + 1] : total_size;\n    } else {\n      const Index total_size = internal::array_prod(m_orig_impl.dimensions());\n      m_stride_mod = (m_return_dim > 0) ? m_strides[m_return_dim - 1] : total_size;\n    }    \n    // If m_return_dim is not a valid index, returns 1 or this can crash on Windows.\n    m_stride_div = ((m_return_dim >= 0) &&\n                    (m_return_dim < static_cast<Index>(m_strides.size())))\n                   ? m_strides[m_return_dim] : 1;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const {\n    return m_impl.dimensions();\n  }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType /*data*/) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const {\n    const TupleType v = m_impl.coeff(index);\n    return (m_return_dim < 0) ? v.first : (v.first % m_stride_mod) / m_stride_div;\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n#ifdef EIGEN_USE_SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n    m_orig_impl.bind(cgh);\n  }\n#endif\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    const double compute_cost = 1.0 +\n        (m_return_dim < 0 ? 0.0 : (TensorOpCost::ModCost<Index>() + TensorOpCost::DivCost<Index>()));\n    return m_orig_impl.costPerCoeff(vectorized) +\n           m_impl.costPerCoeff(vectorized) + TensorOpCost(0, 0, compute_cost);\n  }\n\n private:\n  EIGEN_DEVICE_FUNC void gen_strides(const InputDimensions& dims, StrideDims& strides) {\n    if (m_return_dim < 0) {\n      return;  // Won't be using the strides.\n    }\n    eigen_assert(m_return_dim < NumDims &&\n                 \"Asking to convert index to a dimension outside of the rank\");\n\n    // Calculate m_stride_div and m_stride_mod, which are used to\n    // calculate the value of an index w.r.t. the m_return_dim.\n    if (Layout == static_cast<int>(ColMajor)) {\n      strides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        strides[i] = strides[i-1] * dims[i-1];\n      }\n    } else {\n      strides[NumDims-1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        strides[i] = strides[i+1] * dims[i+1];\n      }\n    }\n  }\n\n protected:\n  TensorEvaluator<const TensorIndexTupleOp<ArgType>, Device> m_orig_impl;\n  TensorEvaluator<const TensorReductionOp<ReduceOp, Dims, const TensorIndexTupleOp<ArgType> >, Device> m_impl;\n  const Index m_return_dim;\n  StrideDims m_strides;\n  Index m_stride_mod;\n  Index m_stride_div;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_ARG_MAX_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorAssign.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_ASSIGN_H\n#define EIGEN_CXX11_TENSOR_TENSOR_ASSIGN_H\n\nnamespace Eigen {\n\n/** \\class TensorAssign\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief The tensor assignment class.\n  *\n  * This class is represents the assignment of the values resulting from the evaluation of\n  * the rhs expression to the memory locations denoted by the lhs expression.\n  */\nnamespace internal {\ntemplate<typename LhsXprType, typename RhsXprType>\nstruct traits<TensorAssignOp<LhsXprType, RhsXprType> >\n{\n  typedef typename LhsXprType::Scalar Scalar;\n  typedef typename traits<LhsXprType>::StorageKind StorageKind;\n  typedef typename promote_index_type<typename traits<LhsXprType>::Index,\n                                      typename traits<RhsXprType>::Index>::type Index;\n  typedef typename LhsXprType::Nested LhsNested;\n  typedef typename RhsXprType::Nested RhsNested;\n  typedef typename remove_reference<LhsNested>::type _LhsNested;\n  typedef typename remove_reference<RhsNested>::type _RhsNested;\n  static const std::size_t NumDimensions = internal::traits<LhsXprType>::NumDimensions;\n  static const int Layout = internal::traits<LhsXprType>::Layout;\n  typedef typename traits<LhsXprType>::PointerType PointerType;\n\n  enum {\n    Flags = 0\n  };\n};\n\ntemplate<typename LhsXprType, typename RhsXprType>\nstruct eval<TensorAssignOp<LhsXprType, RhsXprType>, Eigen::Dense>\n{\n  typedef const TensorAssignOp<LhsXprType, RhsXprType>& type;\n};\n\ntemplate<typename LhsXprType, typename RhsXprType>\nstruct nested<TensorAssignOp<LhsXprType, RhsXprType>, 1, typename eval<TensorAssignOp<LhsXprType, RhsXprType> >::type>\n{\n  typedef TensorAssignOp<LhsXprType, RhsXprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename LhsXprType, typename RhsXprType>\nclass TensorAssignOp : public TensorBase<TensorAssignOp<LhsXprType, RhsXprType> >\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorAssignOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename LhsXprType::CoeffReturnType CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorAssignOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorAssignOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorAssignOp>::Index Index;\n\n  static const int NumDims = Eigen::internal::traits<TensorAssignOp>::NumDimensions;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorAssignOp(LhsXprType& lhs, const RhsXprType& rhs)\n      : m_lhs_xpr(lhs), m_rhs_xpr(rhs) {}\n\n    /** \\returns the nested expressions */\n    EIGEN_DEVICE_FUNC\n    typename internal::remove_all<typename LhsXprType::Nested>::type&\n    lhsExpression() const { return *((typename internal::remove_all<typename LhsXprType::Nested>::type*)&m_lhs_xpr); }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename RhsXprType::Nested>::type&\n    rhsExpression() const { return m_rhs_xpr; }\n\n  protected:\n    typename internal::remove_all<typename LhsXprType::Nested>::type& m_lhs_xpr;\n    const typename internal::remove_all<typename RhsXprType::Nested>::type& m_rhs_xpr;\n};\n\n\ntemplate<typename LeftArgType, typename RightArgType, typename Device>\nstruct TensorEvaluator<const TensorAssignOp<LeftArgType, RightArgType>, Device>\n{\n  typedef TensorAssignOp<LeftArgType, RightArgType> XprType;\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef typename TensorEvaluator<RightArgType, Device>::Dimensions Dimensions;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  static const int NumDims = XprType::NumDims;\n\n  enum {\n    IsAligned         = int(TensorEvaluator<LeftArgType, Device>::IsAligned) &\n                        int(TensorEvaluator<RightArgType, Device>::IsAligned),\n    PacketAccess      = int(TensorEvaluator<LeftArgType, Device>::PacketAccess) &\n                        int(TensorEvaluator<RightArgType, Device>::PacketAccess),\n    BlockAccess       = int(TensorEvaluator<LeftArgType, Device>::BlockAccess) &\n                        int(TensorEvaluator<RightArgType, Device>::BlockAccess),\n    PreferBlockAccess = int(TensorEvaluator<LeftArgType, Device>::PreferBlockAccess) |\n                        int(TensorEvaluator<RightArgType, Device>::PreferBlockAccess),\n    Layout            = TensorEvaluator<LeftArgType, Device>::Layout,\n    RawAccess         = TensorEvaluator<LeftArgType, Device>::RawAccess\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename TensorEvaluator<const RightArgType, Device>::TensorBlock\n      RightTensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  TensorEvaluator(const XprType& op, const Device& device) :\n      m_leftImpl(op.lhsExpression(), device),\n      m_rightImpl(op.rhsExpression(), device)\n  {\n    EIGEN_STATIC_ASSERT(\n        (static_cast<int>(TensorEvaluator<LeftArgType, Device>::Layout) ==\n         static_cast<int>(TensorEvaluator<RightArgType, Device>::Layout)),\n        YOU_MADE_A_PROGRAMMING_MISTAKE);\n  }\n\n  EIGEN_DEVICE_FUNC const Dimensions& dimensions() const\n  {\n    // The dimensions of the lhs and the rhs tensors should be equal to prevent\n    // overflows and ensure the result is fully initialized.\n    // TODO: use left impl instead if right impl dimensions are known at compile time.\n    return m_rightImpl.dimensions();\n  }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    eigen_assert(dimensions_match(m_leftImpl.dimensions(), m_rightImpl.dimensions()));\n    m_leftImpl.evalSubExprsIfNeeded(NULL);\n    // If the lhs provides raw access to its storage area (i.e. if m_leftImpl.data() returns a non\n    // null value), attempt to evaluate the rhs expression in place. Returns true iff in place\n    // evaluation isn't supported and the caller still needs to manually assign the values generated\n    // by the rhs to the lhs.\n    return m_rightImpl.evalSubExprsIfNeeded(m_leftImpl.data());\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    m_leftImpl.evalSubExprsIfNeededAsync(nullptr, [this, done](bool) {\n      m_rightImpl.evalSubExprsIfNeededAsync(\n          m_leftImpl.data(), [done](bool need_assign) { done(need_assign); });\n    });\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_leftImpl.cleanup();\n    m_rightImpl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalScalar(Index i) {\n    m_leftImpl.coeffRef(i) = m_rightImpl.coeff(i);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalPacket(Index i) {\n\n    const int LhsStoreMode = TensorEvaluator<LeftArgType, Device>::IsAligned ? Aligned : Unaligned;\n    const int RhsLoadMode = TensorEvaluator<RightArgType, Device>::IsAligned ? Aligned : Unaligned;\n    m_leftImpl.template writePacket<LhsStoreMode>(i, m_rightImpl.template packet<RhsLoadMode>(i));\n  }\n  EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const\n  {\n    return m_leftImpl.coeff(index);\n  }\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC PacketReturnType packet(Index index) const\n  {\n    return m_leftImpl.template packet<LoadMode>(index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    // We assume that evalPacket or evalScalar is called to perform the\n    // assignment and account for the cost of the write here, but reduce left\n    // cost by one load because we are using m_leftImpl.coeffRef.\n    TensorOpCost left = m_leftImpl.costPerCoeff(vectorized);\n    return m_rightImpl.costPerCoeff(vectorized) +\n           TensorOpCost(\n               numext::maxi(0.0, left.bytes_loaded() - sizeof(CoeffReturnType)),\n               left.bytes_stored(), left.compute_cycles()) +\n           TensorOpCost(0, sizeof(CoeffReturnType), 0, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    return internal::TensorBlockResourceRequirements::merge(\n        m_leftImpl.getResourceRequirements(),\n        m_rightImpl.getResourceRequirements());\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalBlock(\n      TensorBlockDesc& desc, TensorBlockScratch& scratch) {\n    if (TensorEvaluator<LeftArgType, Device>::RawAccess &&\n        m_leftImpl.data() != NULL) {\n      // If destination has raw data access, we pass it as a potential\n      // destination for a block descriptor evaluation.\n      desc.template AddDestinationBuffer<Layout>(\n          /*dst_base=*/m_leftImpl.data() + desc.offset(),\n          /*dst_strides=*/internal::strides<Layout>(m_leftImpl.dimensions()));\n    }\n\n    RightTensorBlock block = m_rightImpl.block(desc, scratch, /*root_of_expr_ast=*/true);\n    // If block was evaluated into a destination, there is no need to do assignment.\n    if (block.kind() != internal::TensorBlockKind::kMaterializedInOutput) {\n      m_leftImpl.writeBlock(desc, block);\n    }\n    block.cleanup();\n  }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_leftImpl.bind(cgh);\n    m_rightImpl.bind(cgh);\n  }\n#endif\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return m_leftImpl.data(); }\n\n private:\n  TensorEvaluator<LeftArgType, Device> m_leftImpl;\n  TensorEvaluator<RightArgType, Device> m_rightImpl;\n};\n\n}\n\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_ASSIGN_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBase.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_BASE_H\n#define EIGEN_CXX11_TENSOR_TENSOR_BASE_H\n\n// clang-format off\n\nnamespace Eigen {\n\n/** \\class TensorBase\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief The tensor base class.\n  *\n  * This class is the common parent of the Tensor and TensorMap class, thus\n  * making it possible to use either class interchangeably in expressions.\n  */\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n// FIXME Doxygen does not like the inheritance with different template parameters\n// Since there is no doxygen documentation inside, we disable it for now\ntemplate<typename Derived>\nclass TensorBase<Derived, ReadOnlyAccessors>\n{\n  public:\n    typedef internal::traits<Derived> DerivedTraits;\n    typedef typename DerivedTraits::Scalar Scalar;\n    typedef typename DerivedTraits::Index Index;\n    typedef typename internal::remove_const<Scalar>::type CoeffReturnType;\n    static const int NumDimensions = DerivedTraits::NumDimensions;\n\n    // Generic nullary operation support.\n    template <typename CustomNullaryOp> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseNullaryOp<CustomNullaryOp, const Derived>\n    nullaryExpr(const CustomNullaryOp& func) const {\n      return TensorCwiseNullaryOp<CustomNullaryOp, const Derived>(derived(), func);\n    }\n\n    // Coefficient-wise nullary operators\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseNullaryOp<internal::scalar_constant_op<Scalar>, const Derived>\n    constant(const Scalar& value) const {\n      return nullaryExpr(internal::scalar_constant_op<Scalar>(value));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseNullaryOp<internal::UniformRandomGenerator<Scalar>, const Derived>\n    random() const {\n      return nullaryExpr(internal::UniformRandomGenerator<Scalar>());\n    }\n    template <typename RandomGenerator> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseNullaryOp<RandomGenerator, const Derived>\n    random(const RandomGenerator& gen = RandomGenerator()) const {\n      return nullaryExpr(gen);\n    }\n\n    // Tensor generation\n    template <typename Generator> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorGeneratorOp<Generator, const Derived>\n    generate(const Generator& generator) const {\n      return TensorGeneratorOp<Generator, const Derived>(derived(), generator);\n    }\n\n    // Generic unary operation support.\n    template <typename CustomUnaryOp> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<CustomUnaryOp, const Derived>\n    unaryExpr(const CustomUnaryOp& func) const {\n      return TensorCwiseUnaryOp<CustomUnaryOp, const Derived>(derived(), func);\n    }\n\n    // Coefficient-wise unary operators\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_opposite_op<Scalar>, const Derived>\n    operator-() const {\n      return unaryExpr(internal::scalar_opposite_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_sqrt_op<Scalar>, const Derived>\n    sqrt() const {\n      return unaryExpr(internal::scalar_sqrt_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_sign_op<Scalar>, const Derived>\n    sign() const {\n      return unaryExpr(internal::scalar_sign_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_rsqrt_op<Scalar>, const Derived>\n    rsqrt() const {\n      return unaryExpr(internal::scalar_rsqrt_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_square_op<Scalar>, const Derived>\n    square() const {\n      return unaryExpr(internal::scalar_square_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_cube_op<Scalar>, const Derived>\n    cube() const {\n      return unaryExpr(internal::scalar_cube_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_inverse_op<Scalar>, const Derived>\n    inverse() const {\n      return unaryExpr(internal::scalar_inverse_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_tanh_op<Scalar>, const Derived>\n    tanh() const {\n      return unaryExpr(internal::scalar_tanh_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_lgamma_op<Scalar>, const Derived>\n    lgamma() const {\n      return unaryExpr(internal::scalar_lgamma_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_digamma_op<Scalar>, const Derived>\n    digamma() const {\n      return unaryExpr(internal::scalar_digamma_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_i0_op<Scalar>, const Derived>\n    bessel_i0() const {\n      return unaryExpr(internal::scalar_bessel_i0_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_i0e_op<Scalar>, const Derived>\n    bessel_i0e() const {\n      return unaryExpr(internal::scalar_bessel_i0e_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_i1_op<Scalar>, const Derived>\n    bessel_i1() const {\n      return unaryExpr(internal::scalar_bessel_i1_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_i1e_op<Scalar>, const Derived>\n    bessel_i1e() const {\n      return unaryExpr(internal::scalar_bessel_i1e_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_j0_op<Scalar>, const Derived>\n    bessel_j0() const {\n      return unaryExpr(internal::scalar_bessel_j0_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_y0_op<Scalar>, const Derived>\n    bessel_y0() const {\n      return unaryExpr(internal::scalar_bessel_y0_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_j1_op<Scalar>, const Derived>\n    bessel_j1() const {\n      return unaryExpr(internal::scalar_bessel_j1_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_y1_op<Scalar>, const Derived>\n    bessel_y1() const {\n      return unaryExpr(internal::scalar_bessel_y1_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_k0_op<Scalar>, const Derived>\n    bessel_k0() const {\n      return unaryExpr(internal::scalar_bessel_k0_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_k0e_op<Scalar>, const Derived>\n    bessel_k0e() const {\n      return unaryExpr(internal::scalar_bessel_k0e_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_k1_op<Scalar>, const Derived>\n    bessel_k1() const {\n      return unaryExpr(internal::scalar_bessel_k1_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_k1e_op<Scalar>, const Derived>\n    bessel_k1e() const {\n      return unaryExpr(internal::scalar_bessel_k1e_op<Scalar>());\n    }\n\n    // igamma(a = this, x = other)\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_igamma_op<Scalar>, const Derived, const OtherDerived>\n    igamma(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_igamma_op<Scalar>());\n    }\n\n    // igamma_der_a(a = this, x = other)\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_igamma_der_a_op<Scalar>, const Derived, const OtherDerived>\n    igamma_der_a(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_igamma_der_a_op<Scalar>());\n    }\n\n    // gamma_sample_der_alpha(alpha = this, sample = other)\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_gamma_sample_der_alpha_op<Scalar>, const Derived, const OtherDerived>\n    gamma_sample_der_alpha(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_gamma_sample_der_alpha_op<Scalar>());\n    }\n\n    // igammac(a = this, x = other)\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_igammac_op<Scalar>, const Derived, const OtherDerived>\n    igammac(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_igammac_op<Scalar>());\n    }\n\n    // zeta(x = this, q = other)\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_zeta_op<Scalar>, const Derived, const OtherDerived>\n    zeta(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_zeta_op<Scalar>());\n    }\n\n    // polygamma(n = this, x = other)\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_polygamma_op<Scalar>, const Derived, const OtherDerived>\n    polygamma(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_polygamma_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_erf_op<Scalar>, const Derived>\n    erf() const {\n      return unaryExpr(internal::scalar_erf_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_erfc_op<Scalar>, const Derived>\n    erfc() const {\n      return unaryExpr(internal::scalar_erfc_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_ndtri_op<Scalar>, const Derived>\n    ndtri() const {\n      return unaryExpr(internal::scalar_ndtri_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_logistic_op<Scalar>, const Derived>\n    sigmoid() const {\n      return unaryExpr(internal::scalar_logistic_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_exp_op<Scalar>, const Derived>\n    exp() const {\n      return unaryExpr(internal::scalar_exp_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_expm1_op<Scalar>, const Derived>\n    expm1() const {\n      return unaryExpr(internal::scalar_expm1_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_log_op<Scalar>, const Derived>\n    log() const {\n      return unaryExpr(internal::scalar_log_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_log1p_op<Scalar>, const Derived>\n    log1p() const {\n      return unaryExpr(internal::scalar_log1p_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_log2_op<Scalar>, const Derived>\n    log2() const {\n      return unaryExpr(internal::scalar_log2_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_abs_op<Scalar>, const Derived>\n    abs() const {\n      return unaryExpr(internal::scalar_abs_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_clamp_op<Scalar>, const Derived>\n    clip(Scalar min, Scalar max) const {\n      return unaryExpr(internal::scalar_clamp_op<Scalar>(min, max));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const typename internal::conditional<NumTraits<CoeffReturnType>::IsComplex,\n                                                             TensorCwiseUnaryOp<internal::scalar_conjugate_op<Scalar>, const Derived>,\n                                                             Derived>::type\n    conjugate() const {\n      return choose(Cond<NumTraits<CoeffReturnType>::IsComplex>(), unaryExpr(internal::scalar_conjugate_op<Scalar>()), derived());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::bind2nd_op<internal::scalar_pow_op<Scalar,Scalar> >, const Derived>\n    pow(Scalar exponent) const {\n      return unaryExpr(internal::bind2nd_op<internal::scalar_pow_op<Scalar,Scalar> >(exponent));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_real_op<Scalar>, const Derived>\n    real() const {\n      return unaryExpr(internal::scalar_real_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_imag_op<Scalar>, const Derived>\n    imag() const {\n      return unaryExpr(internal::scalar_imag_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::bind2nd_op<internal::scalar_sum_op<Scalar,Scalar> >, const Derived>\n    operator+ (Scalar rhs) const {\n      return unaryExpr(internal::bind2nd_op<internal::scalar_sum_op<Scalar,Scalar> >(rhs));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE friend\n    const TensorCwiseUnaryOp<internal::bind1st_op<internal::scalar_sum_op<Scalar> >, const Derived>\n    operator+ (Scalar lhs, const Derived& rhs) {\n      return rhs.unaryExpr(internal::bind1st_op<internal::scalar_sum_op<Scalar> >(lhs));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::bind2nd_op<internal::scalar_difference_op<Scalar,Scalar> >, const Derived>\n    operator- (Scalar rhs) const {\n      EIGEN_STATIC_ASSERT((NumTraits<Scalar>::IsSigned || internal::is_same<Scalar, const std::complex<float> >::value), YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return unaryExpr(internal::bind2nd_op<internal::scalar_difference_op<Scalar,Scalar> >(rhs));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE friend\n    const TensorCwiseUnaryOp<internal::bind1st_op<internal::scalar_difference_op<Scalar> >, const Derived>\n    operator- (Scalar lhs, const Derived& rhs) {\n      return rhs.unaryExpr(internal::bind1st_op<internal::scalar_difference_op<Scalar> >(lhs));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::bind2nd_op<internal::scalar_product_op<Scalar,Scalar> >, const Derived>\n    operator* (Scalar rhs) const {\n      return unaryExpr(internal::bind2nd_op<internal::scalar_product_op<Scalar,Scalar> >(rhs));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE friend\n    const TensorCwiseUnaryOp<internal::bind1st_op<internal::scalar_product_op<Scalar> >, const Derived>\n    operator* (Scalar lhs, const Derived& rhs) {\n      return rhs.unaryExpr(internal::bind1st_op<internal::scalar_product_op<Scalar> >(lhs));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::bind2nd_op<internal::scalar_quotient_op<Scalar,Scalar> >, const Derived>\n    operator/ (Scalar rhs) const {\n      return unaryExpr(internal::bind2nd_op<internal::scalar_quotient_op<Scalar,Scalar> >(rhs));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE friend\n    const TensorCwiseUnaryOp<internal::bind1st_op<internal::scalar_quotient_op<Scalar> >, const Derived>\n    operator/ (Scalar lhs, const Derived& rhs) {\n      return rhs.unaryExpr(internal::bind1st_op<internal::scalar_quotient_op<Scalar> >(lhs));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_mod_op<Scalar>, const Derived>\n    operator% (Scalar rhs) const {\n      EIGEN_STATIC_ASSERT(NumTraits<Scalar>::IsInteger, YOU_MADE_A_PROGRAMMING_MISTAKE_TRY_MOD);\n      return unaryExpr(internal::scalar_mod_op<Scalar>(rhs));\n    }\n\n    template <int NanPropagation=PropagateFast>\n    EIGEN_DEVICE_FUNC\n        EIGEN_STRONG_INLINE const TensorCwiseBinaryOp<internal::scalar_max_op<Scalar,Scalar,NanPropagation>, const Derived, const TensorCwiseNullaryOp<internal::scalar_constant_op<Scalar>, const Derived> >\n    cwiseMax(Scalar threshold) const {\n      return cwiseMax<NanPropagation>(constant(threshold));\n    }\n\n    template <int NanPropagation=PropagateFast>\n    EIGEN_DEVICE_FUNC\n        EIGEN_STRONG_INLINE const TensorCwiseBinaryOp<internal::scalar_min_op<Scalar,Scalar,NanPropagation>, const Derived, const TensorCwiseNullaryOp<internal::scalar_constant_op<Scalar>, const Derived> >\n    cwiseMin(Scalar threshold) const {\n      return cwiseMin<NanPropagation>(constant(threshold));\n    }\n\n    template<typename NewType>\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const typename internal::conditional<internal::is_same<NewType, CoeffReturnType>::value,\n                                                             Derived,\n                                                             TensorConversionOp<NewType, const Derived> >::type\n    cast() const {\n      return choose(Cond<internal::is_same<NewType, CoeffReturnType>::value>(), derived(), TensorConversionOp<NewType, const Derived>(derived()));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_round_op<Scalar>, const Derived>\n    round() const {\n      return unaryExpr(internal::scalar_round_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_rint_op<Scalar>, const Derived>\n    rint() const {\n      return unaryExpr(internal::scalar_rint_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_ceil_op<Scalar>, const Derived>\n    ceil() const {\n      return unaryExpr(internal::scalar_ceil_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_floor_op<Scalar>, const Derived>\n    floor() const {\n      return unaryExpr(internal::scalar_floor_op<Scalar>());\n    }\n\n    // Generic binary operation support.\n    template <typename CustomBinaryOp, typename OtherDerived> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseBinaryOp<CustomBinaryOp, const Derived, const OtherDerived>\n    binaryExpr(const OtherDerived& other, const CustomBinaryOp& func) const {\n      return TensorCwiseBinaryOp<CustomBinaryOp, const Derived, const OtherDerived>(derived(), other, func);\n    }\n\n    // Coefficient-wise binary operators.\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_sum_op<Scalar>, const Derived, const OtherDerived>\n    operator+(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_sum_op<Scalar>());\n    }\n\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_difference_op<Scalar>, const Derived, const OtherDerived>\n    operator-(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_difference_op<Scalar>());\n    }\n\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_product_op<Scalar>, const Derived, const OtherDerived>\n    operator*(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_product_op<Scalar>());\n    }\n\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_quotient_op<Scalar>, const Derived, const OtherDerived>\n    operator/(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_quotient_op<Scalar>());\n    }\n\n  template<int NaNPropagation=PropagateFast, typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n      const TensorCwiseBinaryOp<internal::scalar_max_op<Scalar,Scalar, NaNPropagation>, const Derived, const OtherDerived>\n    cwiseMax(const OtherDerived& other) const {\n    return binaryExpr(other.derived(), internal::scalar_max_op<Scalar,Scalar, NaNPropagation>());\n    }\n\n  template<int NaNPropagation=PropagateFast, typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_min_op<Scalar,Scalar, NaNPropagation>, const Derived, const OtherDerived>\n    cwiseMin(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_min_op<Scalar,Scalar, NaNPropagation>());\n    }\n\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_boolean_and_op, const Derived, const OtherDerived>\n    operator&&(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_boolean_and_op());\n    }\n\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_boolean_or_op, const Derived, const OtherDerived>\n    operator||(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_boolean_or_op());\n    }\n\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_boolean_xor_op, const Derived, const OtherDerived>\n    operator^(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_boolean_xor_op());\n    }\n\n    // Comparisons and tests.\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_LT>, const Derived, const OtherDerived>\n    operator<(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_LT>());\n    }\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_LE>, const Derived, const OtherDerived>\n    operator<=(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_LE>());\n    }\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_GT>, const Derived, const OtherDerived>\n    operator>(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_GT>());\n    }\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_GE>, const Derived, const OtherDerived>\n    operator>=(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_GE>());\n    }\n\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_EQ>, const Derived, const OtherDerived>\n    operator==(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_EQ>());\n    }\n\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_NEQ>, const Derived, const OtherDerived>\n    operator!=(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_NEQ>());\n    }\n\n    // comparisons and tests for Scalars\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_LT>, const Derived, const TensorCwiseNullaryOp<internal::scalar_constant_op<Scalar>, const Derived> >\n    operator<(Scalar threshold) const {\n      return operator<(constant(threshold));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_LE>, const Derived, const TensorCwiseNullaryOp<internal::scalar_constant_op<Scalar>, const Derived> >\n    operator<=(Scalar threshold) const {\n      return operator<=(constant(threshold));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_GT>, const Derived, const TensorCwiseNullaryOp<internal::scalar_constant_op<Scalar>, const Derived> >\n    operator>(Scalar threshold) const {\n      return operator>(constant(threshold));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_GE>, const Derived, const TensorCwiseNullaryOp<internal::scalar_constant_op<Scalar>, const Derived> >\n    operator>=(Scalar threshold) const {\n      return operator>=(constant(threshold));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_EQ>, const Derived, const TensorCwiseNullaryOp<internal::scalar_constant_op<Scalar>, const Derived> >\n    operator==(Scalar threshold) const {\n      return operator==(constant(threshold));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_NEQ>, const Derived, const TensorCwiseNullaryOp<internal::scalar_constant_op<Scalar>, const Derived> >\n    operator!=(Scalar threshold) const {\n      return operator!=(constant(threshold));\n    }\n\n    // Checks\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_isnan_op<Scalar>, const Derived>\n    (isnan)() const {\n      return unaryExpr(internal::scalar_isnan_op<Scalar>());\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_isinf_op<Scalar>, const Derived>\n    (isinf)() const {\n      return unaryExpr(internal::scalar_isinf_op<Scalar>());\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_isfinite_op<Scalar>, const Derived>\n    (isfinite)() const {\n      return unaryExpr(internal::scalar_isfinite_op<Scalar>());\n    }\n\n    // Coefficient-wise ternary operators.\n    template<typename ThenDerived, typename ElseDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorSelectOp<const Derived, const ThenDerived, const ElseDerived>\n    select(const ThenDerived& thenTensor, const ElseDerived& elseTensor) const {\n      return TensorSelectOp<const Derived, const ThenDerived, const ElseDerived>(derived(), thenTensor.derived(), elseTensor.derived());\n    }\n\n    // Contractions.\n    typedef Eigen::IndexPair<Index> DimensionPair;\n\n    template<typename OtherDerived, typename Dimensions> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorContractionOp<const Dimensions, const Derived, const OtherDerived, const NoOpOutputKernel>\n    contract(const OtherDerived& other, const Dimensions& dims) const {\n      return TensorContractionOp<const Dimensions, const Derived, const OtherDerived, const NoOpOutputKernel>(derived(), other.derived(), dims);\n    }\n\n    template<typename OtherDerived, typename Dimensions, typename OutputKernel> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorContractionOp<const Dimensions, const Derived, const OtherDerived, const OutputKernel>\n    contract(const OtherDerived& other, const Dimensions& dims, const OutputKernel& output_kernel) const {\n      return TensorContractionOp<const Dimensions, const Derived, const OtherDerived, const OutputKernel>(derived(), other.derived(), dims, output_kernel);\n    }\n\n    // Convolutions.\n    template<typename KernelDerived, typename Dimensions> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorConvolutionOp<const Dimensions, const Derived, const KernelDerived>\n    convolve(const KernelDerived& kernel, const Dimensions& dims) const {\n      return TensorConvolutionOp<const Dimensions, const Derived, const KernelDerived>(derived(), kernel.derived(), dims);\n    }\n\n    // Fourier transforms\n    template <int FFTDataType, int FFTDirection, typename FFT> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorFFTOp<const FFT, const Derived, FFTDataType, FFTDirection>\n    fft(const FFT& dims) const {\n      return TensorFFTOp<const FFT, const Derived, FFTDataType, FFTDirection>(derived(), dims);\n    }\n\n    // Scan.\n    typedef TensorScanOp<internal::SumReducer<CoeffReturnType>, const Derived> TensorScanSumOp;\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorScanSumOp\n    cumsum(const Index& axis, bool exclusive = false) const {\n      return TensorScanSumOp(derived(), axis, exclusive);\n    }\n\n    typedef TensorScanOp<internal::ProdReducer<CoeffReturnType>, const Derived> TensorScanProdOp;\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorScanProdOp\n    cumprod(const Index& axis, bool exclusive = false) const {\n      return TensorScanProdOp(derived(), axis, exclusive);\n    }\n\n    template <typename Reducer>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorScanOp<Reducer, const Derived>\n    scan(const Index& axis, const Reducer& reducer, bool exclusive = false) const {\n      return TensorScanOp<Reducer, const Derived>(derived(), axis, exclusive, reducer);\n    }\n\n    // Reductions.\n    template <typename Dims> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReductionOp<internal::SumReducer<CoeffReturnType>, const Dims, const Derived>\n    sum(const Dims& dims) const {\n      return TensorReductionOp<internal::SumReducer<CoeffReturnType>, const Dims, const Derived>(derived(), dims, internal::SumReducer<CoeffReturnType>());\n    }\n\n    const TensorReductionOp<internal::SumReducer<CoeffReturnType>, const DimensionList<Index, NumDimensions>, const Derived>\n    sum() const {\n      DimensionList<Index, NumDimensions> in_dims;\n      return TensorReductionOp<internal::SumReducer<CoeffReturnType>, const DimensionList<Index, NumDimensions>, const Derived>(derived(), in_dims, internal::SumReducer<CoeffReturnType>());\n    }\n\n    template <typename Dims> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReductionOp<internal::MeanReducer<CoeffReturnType>, const Dims, const Derived>\n    mean(const Dims& dims) const {\n      return TensorReductionOp<internal::MeanReducer<CoeffReturnType>, const Dims, const Derived>(derived(), dims, internal::MeanReducer<CoeffReturnType>());\n    }\n\n    const TensorReductionOp<internal::MeanReducer<CoeffReturnType>, const DimensionList<Index, NumDimensions>, const Derived>\n    mean() const {\n      DimensionList<Index, NumDimensions> in_dims;\n      return TensorReductionOp<internal::MeanReducer<CoeffReturnType>, const DimensionList<Index, NumDimensions>, const Derived>(derived(), in_dims, internal::MeanReducer<CoeffReturnType>());\n    }\n\n    template <typename Dims> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReductionOp<internal::ProdReducer<CoeffReturnType>, const Dims, const Derived>\n    prod(const Dims& dims) const {\n      return TensorReductionOp<internal::ProdReducer<CoeffReturnType>, const Dims, const Derived>(derived(), dims, internal::ProdReducer<CoeffReturnType>());\n    }\n\n    const TensorReductionOp<internal::ProdReducer<CoeffReturnType>, const DimensionList<Index, NumDimensions>, const Derived>\n    prod() const {\n      DimensionList<Index, NumDimensions> in_dims;\n      return TensorReductionOp<internal::ProdReducer<CoeffReturnType>, const DimensionList<Index, NumDimensions>, const Derived>(derived(), in_dims, internal::ProdReducer<CoeffReturnType>());\n    }\n\n    template <typename Dims,int NanPropagation=PropagateFast> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReductionOp<internal::MaxReducer<CoeffReturnType,NanPropagation>, const Dims, const Derived>\n    maximum(const Dims& dims) const {\n      return TensorReductionOp<internal::MaxReducer<CoeffReturnType,NanPropagation>, const Dims, const Derived>(derived(), dims, internal::MaxReducer<CoeffReturnType,NanPropagation>());\n    }\n\n    template <int NanPropagation=PropagateFast>\n    const TensorReductionOp<internal::MaxReducer<CoeffReturnType,NanPropagation>, const DimensionList<Index, NumDimensions>, const Derived>\n    maximum() const {\n      DimensionList<Index, NumDimensions> in_dims;\n      return TensorReductionOp<internal::MaxReducer<CoeffReturnType,NanPropagation>, const DimensionList<Index, NumDimensions>, const Derived>(derived(), in_dims, internal::MaxReducer<CoeffReturnType,NanPropagation>());\n    }\n\n    template <typename Dims,int NanPropagation=PropagateFast> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReductionOp<internal::MinReducer<CoeffReturnType,NanPropagation>, const Dims, const Derived>\n    minimum(const Dims& dims) const {\n      return TensorReductionOp<internal::MinReducer<CoeffReturnType,NanPropagation>, const Dims, const Derived>(derived(), dims, internal::MinReducer<CoeffReturnType,NanPropagation>());\n    }\n\n    template <int NanPropagation=PropagateFast>\n    const TensorReductionOp<internal::MinReducer<CoeffReturnType,NanPropagation>, const DimensionList<Index, NumDimensions>, const Derived>\n    minimum() const {\n      DimensionList<Index, NumDimensions> in_dims;\n      return TensorReductionOp<internal::MinReducer<CoeffReturnType,NanPropagation>, const DimensionList<Index, NumDimensions>, const Derived>(derived(), in_dims, internal::MinReducer<CoeffReturnType,NanPropagation>());\n    }\n\n    template <typename Dims> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReductionOp<internal::AndReducer, const Dims, const typename internal::conditional<internal::is_same<bool, CoeffReturnType>::value, Derived, TensorConversionOp<bool, const Derived> >::type >\n    all(const Dims& dims) const {\n      return cast<bool>().reduce(dims, internal::AndReducer());\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReductionOp<internal::AndReducer, const DimensionList<Index, NumDimensions>, const typename internal::conditional<internal::is_same<bool, CoeffReturnType>::value, Derived, TensorConversionOp<bool, const Derived> >::type >\n    all() const {\n      DimensionList<Index, NumDimensions> in_dims;\n      return cast<bool>().reduce(in_dims, internal::AndReducer());\n    }\n\n    template <typename Dims> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReductionOp<internal::OrReducer, const Dims, const typename internal::conditional<internal::is_same<bool, CoeffReturnType>::value, Derived, TensorConversionOp<bool, const Derived> >::type >\n    any(const Dims& dims) const {\n      return cast<bool>().reduce(dims, internal::OrReducer());\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReductionOp<internal::OrReducer, const DimensionList<Index, NumDimensions>, const typename internal::conditional<internal::is_same<bool, CoeffReturnType>::value, Derived, TensorConversionOp<bool, const Derived> >::type >\n    any() const {\n      DimensionList<Index, NumDimensions> in_dims;\n      return cast<bool>().reduce(in_dims, internal::OrReducer());\n    }\n\n   EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorTupleReducerOp<\n      internal::ArgMaxTupleReducer<Tuple<Index, CoeffReturnType> >,\n      const array<Index, NumDimensions>, const Derived>\n    argmax() const {\n      array<Index, NumDimensions> in_dims;\n      for (Index d = 0; d < NumDimensions; ++d) in_dims[d] = d;\n      return TensorTupleReducerOp<\n        internal::ArgMaxTupleReducer<Tuple<Index, CoeffReturnType> >,\n        const array<Index, NumDimensions>,\n        const Derived>(derived(), internal::ArgMaxTupleReducer<Tuple<Index, CoeffReturnType> >(), -1, in_dims);\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorTupleReducerOp<\n      internal::ArgMinTupleReducer<Tuple<Index, CoeffReturnType> >,\n      const array<Index, NumDimensions>, const Derived>\n    argmin() const {\n      array<Index, NumDimensions> in_dims;\n      for (Index d = 0; d < NumDimensions; ++d) in_dims[d] = d;\n      return TensorTupleReducerOp<\n        internal::ArgMinTupleReducer<Tuple<Index, CoeffReturnType> >,\n        const array<Index, NumDimensions>,\n        const Derived>(derived(), internal::ArgMinTupleReducer<Tuple<Index, CoeffReturnType> >(), -1, in_dims);\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorTupleReducerOp<\n      internal::ArgMaxTupleReducer<Tuple<Index, CoeffReturnType> >,\n      const array<Index, 1>, const Derived>\n    argmax(const Index return_dim) const {\n      array<Index, 1> in_dims;\n      in_dims[0] = return_dim;\n      return TensorTupleReducerOp<\n        internal::ArgMaxTupleReducer<Tuple<Index, CoeffReturnType> >,\n        const array<Index, 1>,\n        const Derived>(derived(), internal::ArgMaxTupleReducer<Tuple<Index, CoeffReturnType> >(), return_dim, in_dims);\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorTupleReducerOp<\n      internal::ArgMinTupleReducer<Tuple<Index, CoeffReturnType> >,\n      const array<Index, 1>, const Derived>\n    argmin(const Index return_dim) const {\n      array<Index, 1> in_dims;\n      in_dims[0] = return_dim;\n      return TensorTupleReducerOp<\n        internal::ArgMinTupleReducer<Tuple<Index, CoeffReturnType> >,\n        const array<Index, 1>,\n        const Derived>(derived(), internal::ArgMinTupleReducer<Tuple<Index, CoeffReturnType> >(), return_dim, in_dims);\n    }\n\n    template <typename Reducer, typename Dims> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReductionOp<Reducer, const Dims, const Derived>\n    reduce(const Dims& dims, const Reducer& reducer) const {\n      return TensorReductionOp<Reducer, const Dims, const Derived>(derived(), dims, reducer);\n    }\n\n    template <typename Dims> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorTraceOp<const Dims, const Derived>\n    trace(const Dims& dims) const {\n      return TensorTraceOp<const Dims, const Derived>(derived(), dims);\n    }\n\n    const TensorTraceOp<const DimensionList<Index, NumDimensions>, const Derived>\n    trace() const {\n      DimensionList<Index, NumDimensions> in_dims;\n      return TensorTraceOp<const DimensionList<Index, NumDimensions>, const Derived>(derived(), in_dims);\n    }\n\n    template <typename Broadcast> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorBroadcastingOp<const Broadcast, const Derived>\n    broadcast(const Broadcast& bcast) const {\n      return TensorBroadcastingOp<const Broadcast, const Derived>(derived(), bcast);\n    }\n\n    template <typename Axis, typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorConcatenationOp<Axis, const Derived, const OtherDerived>\n    concatenate(const OtherDerived& other, Axis axis) const {\n      return TensorConcatenationOp<Axis, const Derived, const OtherDerived>(derived(), other.derived(), axis);\n    }\n\n    template <typename PatchDims> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorPatchOp<const PatchDims, const Derived>\n    extract_patches(const PatchDims& patch_dims) const {\n      return TensorPatchOp<const PatchDims, const Derived>(derived(), patch_dims);\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorImagePatchOp<Dynamic, Dynamic, const Derived>\n    extract_image_patches(const Index patch_rows = 1, const Index patch_cols = 1,\n                          const Index row_stride = 1, const Index col_stride = 1,\n                          const Index in_row_stride = 1, const Index in_col_stride = 1,\n                          const PaddingType padding_type = PADDING_SAME, const Scalar padding_value = Scalar(0)) const {\n      return TensorImagePatchOp<Dynamic, Dynamic, const Derived>(derived(), patch_rows, patch_cols, row_stride, col_stride,\n                                                                 in_row_stride, in_col_stride, 1, 1, padding_type, padding_value);\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorImagePatchOp<Dynamic, Dynamic, const Derived>\n    extract_image_patches(const Index patch_rows, const Index patch_cols,\n                          const Index row_stride, const Index col_stride,\n                          const Index in_row_stride, const Index in_col_stride,\n                          const Index row_inflate_stride, const Index col_inflate_stride,\n                          const Index padding_top, const Index padding_bottom,\n                          const Index padding_left,const Index padding_right,\n                          const Scalar padding_value) const {\n      return TensorImagePatchOp<Dynamic, Dynamic, const Derived>(derived(), patch_rows, patch_cols, row_stride, col_stride,\n                                                                 in_row_stride, in_col_stride, row_inflate_stride, col_inflate_stride,\n                                                                 padding_top, padding_bottom, padding_left, padding_right, padding_value);\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorVolumePatchOp<Dynamic, Dynamic, Dynamic, const Derived>\n    extract_volume_patches(const Index patch_planes, const Index patch_rows, const Index patch_cols,\n                           const Index plane_stride = 1, const Index row_stride = 1, const Index col_stride = 1,\n                           const PaddingType padding_type = PADDING_SAME, const Scalar padding_value = Scalar(0)) const {\n      return TensorVolumePatchOp<Dynamic, Dynamic, Dynamic, const Derived>(derived(), patch_planes, patch_rows, patch_cols, plane_stride, row_stride, col_stride, 1, 1, 1, 1, 1, 1, padding_type, padding_value);\n    }\n\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorVolumePatchOp<Dynamic, Dynamic, Dynamic, const Derived>\n    extract_volume_patches(const Index patch_planes, const Index patch_rows, const Index patch_cols,\n                           const Index plane_stride, const Index row_stride, const Index col_stride,\n                           const Index plane_inflate_stride, const Index row_inflate_stride, const Index col_inflate_stride,\n                           const Index padding_top_z, const Index padding_bottom_z,\n                           const Index padding_top, const Index padding_bottom,\n                           const Index padding_left, const Index padding_right, const Scalar padding_value = Scalar(0)) const {\n      return TensorVolumePatchOp<Dynamic, Dynamic, Dynamic, const Derived>(derived(), patch_planes, patch_rows, patch_cols, plane_stride, row_stride, col_stride, 1, 1, 1, plane_inflate_stride, row_inflate_stride, col_inflate_stride, padding_top_z, padding_bottom_z, padding_top, padding_bottom, padding_left, padding_right, padding_value);\n    }\n\n    // Morphing operators.\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorLayoutSwapOp<const Derived>\n    swap_layout() const {\n      return TensorLayoutSwapOp<const Derived>(derived());\n    }\n    template <typename NewDimensions> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReshapingOp<const NewDimensions, const Derived>\n    reshape(const NewDimensions& newDimensions) const {\n      return TensorReshapingOp<const NewDimensions, const Derived>(derived(), newDimensions);\n    }\n    template <typename StartIndices, typename Sizes> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorSlicingOp<const StartIndices, const Sizes, const Derived>\n    slice(const StartIndices& startIndices, const Sizes& sizes) const {\n      return TensorSlicingOp<const StartIndices, const Sizes, const Derived>(derived(), startIndices, sizes);\n    }\n    template <typename StartIndices, typename StopIndices, typename Strides> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorStridingSlicingOp<const StartIndices, const StopIndices, const Strides, const Derived>\n    stridedSlice(const StartIndices& startIndices, const StopIndices& stopIndices, const Strides& strides) const {\n      return TensorStridingSlicingOp<const StartIndices, const StopIndices, const Strides,\n                                const Derived>(derived(), startIndices, stopIndices, strides);\n    }\n    template <Index DimId> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorChippingOp<DimId, const Derived>\n    chip(const Index offset) const {\n      return TensorChippingOp<DimId, const Derived>(derived(), offset, DimId);\n    }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorChippingOp<Dynamic, const Derived>\n    chip(const Index offset, const Index dim) const {\n      return TensorChippingOp<Dynamic, const Derived>(derived(), offset, dim);\n    }\n    template <typename ReverseDimensions> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReverseOp<const ReverseDimensions, const Derived>\n    reverse(const ReverseDimensions& rev) const {\n      return TensorReverseOp<const ReverseDimensions, const Derived>(derived(), rev);\n    }\n    template <typename PaddingDimensions> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorPaddingOp<const PaddingDimensions, const Derived>\n    pad(const PaddingDimensions& padding) const {\n      return TensorPaddingOp<const PaddingDimensions, const Derived>(derived(), padding, internal::scalar_cast_op<int, Scalar>()(0));\n    }\n    template <typename PaddingDimensions> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorPaddingOp<const PaddingDimensions, const Derived>\n    pad(const PaddingDimensions& padding, const Scalar padding_value) const {\n      return TensorPaddingOp<const PaddingDimensions, const Derived>(derived(), padding, padding_value);\n    }\n    template <typename Shuffle> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorShufflingOp<const Shuffle, const Derived>\n    shuffle(const Shuffle& shfl) const {\n      return TensorShufflingOp<const Shuffle, const Derived>(derived(), shfl);\n    }\n    template <typename Strides> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorStridingOp<const Strides, const Derived>\n    stride(const Strides& strides) const {\n      return TensorStridingOp<const Strides, const Derived>(derived(), strides);\n    }\n    template <typename Strides> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorInflationOp<const Strides, const Derived>\n    inflate(const Strides& strides) const {\n      return TensorInflationOp<const Strides, const Derived>(derived(), strides);\n    }\n\n    // Returns a tensor containing index/value tuples\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorIndexTupleOp<const Derived>\n    index_tuples() const {\n      return TensorIndexTupleOp<const Derived>(derived());\n    }\n\n    // Support for custom unary and binary operations\n    template <typename CustomUnaryFunc>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCustomUnaryOp<const CustomUnaryFunc, const Derived> customOp(const CustomUnaryFunc& op) const {\n      return TensorCustomUnaryOp<const CustomUnaryFunc, const Derived>(derived(), op);\n    }\n    template <typename OtherDerived, typename CustomBinaryFunc>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCustomBinaryOp<const CustomBinaryFunc, const Derived, const OtherDerived> customOp(const OtherDerived& other, const CustomBinaryFunc& op) const {\n      return TensorCustomBinaryOp<const CustomBinaryFunc, const Derived, const OtherDerived>(derived(), other, op);\n    }\n\n    // Force the evaluation of the expression.\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorForcedEvalOp<const Derived> eval() const {\n      return TensorForcedEvalOp<const Derived>(derived());\n    }\n\n    #ifdef EIGEN_READONLY_TENSORBASE_PLUGIN\n    #include EIGEN_READONLY_TENSORBASE_PLUGIN\n    #endif\n\n  protected:\n    template <typename Scalar, int NumIndices, int Options, typename IndexType> friend class Tensor;\n    template <typename Scalar, typename Dimensions, int Option, typename IndexTypes> friend class TensorFixedSize;\n    // the Eigen:: prefix is required to workaround a compilation issue with nvcc 9.0\n    template <typename OtherDerived, int AccessLevel> friend class Eigen::TensorBase;\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Derived& derived() const { return *static_cast<const Derived*>(this); }\n};\n\ntemplate<typename Derived, int AccessLevel = internal::accessors_level<Derived>::value>\nclass TensorBase : public TensorBase<Derived, ReadOnlyAccessors> {\n public:\n    typedef TensorBase<Derived, ReadOnlyAccessors> Base;\n    typedef internal::traits<Derived> DerivedTraits;\n    typedef typename DerivedTraits::Scalar Scalar;\n    typedef typename DerivedTraits::Index Index;\n    typedef Scalar CoeffReturnType;\n    static const int NumDimensions = DerivedTraits::NumDimensions;\n\n    template <typename Scalar, int NumIndices, int Options, typename IndexType> friend class Tensor;\n    template <typename Scalar, typename Dimensions, int Option, typename IndexTypes> friend class TensorFixedSize;\n    // the Eigen:: prefix is required to workaround a compilation issue with nvcc 9.0\n    template <typename OtherDerived, int OtherAccessLevel> friend class Eigen::TensorBase;\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Derived& setZero() {\n      return setConstant(Scalar(0));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Derived& setConstant(const Scalar& val) {\n      return derived() = this->constant(val);\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Derived& setRandom() {\n      return derived() = this->random();\n    }\n    template <typename RandomGenerator> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Derived& setRandom() {\n      return derived() = this->template random<RandomGenerator>();\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Derived& setValues(\n        const typename internal::Initializer<Derived, NumDimensions>::InitList& vals) {\n      TensorEvaluator<Derived, DefaultDevice> eval(derived(), DefaultDevice());\n      internal::initialize_tensor<Derived, NumDimensions>(eval, vals);\n      return derived();\n    }\n#endif  // EIGEN_HAS_VARIADIC_TEMPLATES\n\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    Derived& operator+=(const OtherDerived& other) {\n      return derived() = derived() + other.derived();\n    }\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    Derived& operator-=(const OtherDerived& other) {\n      return derived() = derived() - other.derived();\n    }\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    Derived& operator*=(const OtherDerived& other) {\n      return derived() = derived() * other.derived();\n    }\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    Derived& operator/=(const OtherDerived& other) {\n      return derived() = derived() / other.derived();\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorLayoutSwapOp<const Derived>\n    swap_layout() const {\n      return TensorLayoutSwapOp<const Derived>(derived());\n    }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorLayoutSwapOp<Derived>\n    swap_layout() {\n      return TensorLayoutSwapOp<Derived>(derived());\n    }\n\n    template <typename Axis, typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorConcatenationOp<const Axis, const Derived, const OtherDerived>\n    concatenate(const OtherDerived& other, const Axis& axis) const {\n      return TensorConcatenationOp<const Axis, const Derived, const OtherDerived>(derived(), other, axis);\n    }\n    template <typename Axis, typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorConcatenationOp<const Axis, Derived, OtherDerived>\n    concatenate(const OtherDerived& other, const Axis& axis) {\n      return TensorConcatenationOp<const Axis, Derived, OtherDerived>(derived(), other, axis);\n    }\n\n    template <typename NewDimensions> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReshapingOp<const NewDimensions, const Derived>\n    reshape(const NewDimensions& newDimensions) const {\n      return TensorReshapingOp<const NewDimensions, const Derived>(derived(), newDimensions);\n    }\n    template <typename NewDimensions> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorReshapingOp<const NewDimensions, Derived>\n    reshape(const NewDimensions& newDimensions) {\n      return TensorReshapingOp<const NewDimensions, Derived>(derived(), newDimensions);\n    }\n\n    template <typename StartIndices, typename Sizes> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorSlicingOp<const StartIndices, const Sizes, const Derived>\n    slice(const StartIndices& startIndices, const Sizes& sizes) const {\n      return TensorSlicingOp<const StartIndices, const Sizes, const Derived>(derived(), startIndices, sizes);\n    }\n    template <typename StartIndices, typename Sizes> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorSlicingOp<const StartIndices, const Sizes, Derived>\n    slice(const StartIndices& startIndices, const Sizes& sizes) {\n      return TensorSlicingOp<const StartIndices, const Sizes, Derived>(derived(), startIndices, sizes);\n    }\n\n    template <typename StartIndices, typename StopIndices, typename Strides> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorStridingSlicingOp<const StartIndices, const StopIndices, const Strides, const Derived>\n    stridedSlice(const StartIndices& startIndices, const StopIndices& stopIndices, const Strides& strides) const {\n      return TensorStridingSlicingOp<const StartIndices, const StopIndices, const Strides,\n                                const Derived>(derived(), startIndices, stopIndices, strides);\n    }\n    template <typename StartIndices, typename StopIndices, typename Strides> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorStridingSlicingOp<const StartIndices, const StopIndices, const Strides, Derived>\n    stridedSlice(const StartIndices& startIndices, const StopIndices& stopIndices, const Strides& strides) {\n      return TensorStridingSlicingOp<const StartIndices, const StopIndices, const Strides,\n                                Derived>(derived(), startIndices, stopIndices, strides);\n    }\n\n    template <DenseIndex DimId> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorChippingOp<DimId, const Derived>\n    chip(const Index offset) const {\n      return TensorChippingOp<DimId, const Derived>(derived(), offset, DimId);\n    }\n    template <Index DimId> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorChippingOp<DimId, Derived>\n    chip(const Index offset) {\n      return TensorChippingOp<DimId, Derived>(derived(), offset, DimId);\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorChippingOp<Dynamic, const Derived>\n    chip(const Index offset, const Index dim) const {\n      return TensorChippingOp<Dynamic, const Derived>(derived(), offset, dim);\n    }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorChippingOp<Dynamic, Derived>\n    chip(const Index offset, const Index dim) {\n      return TensorChippingOp<Dynamic, Derived>(derived(), offset, dim);\n    }\n\n    template <typename ReverseDimensions> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReverseOp<const ReverseDimensions, const Derived>\n    reverse(const ReverseDimensions& rev) const {\n      return TensorReverseOp<const ReverseDimensions, const Derived>(derived(), rev);\n    }\n    template <typename ReverseDimensions> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorReverseOp<const ReverseDimensions, Derived>\n    reverse(const ReverseDimensions& rev) {\n      return TensorReverseOp<const ReverseDimensions, Derived>(derived(), rev);\n    }\n\n    template <typename Shuffle> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorShufflingOp<const Shuffle, const Derived>\n    shuffle(const Shuffle& shfl) const {\n      return TensorShufflingOp<const Shuffle, const Derived>(derived(), shfl);\n    }\n    template <typename Shuffle> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorShufflingOp<const Shuffle, Derived>\n    shuffle(const Shuffle& shfl) {\n      return TensorShufflingOp<const Shuffle, Derived>(derived(), shfl);\n    }\n\n    template <typename Strides> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorStridingOp<const Strides, const Derived>\n    stride(const Strides& strides) const {\n      return TensorStridingOp<const Strides, const Derived>(derived(), strides);\n    }\n    template <typename Strides> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorStridingOp<const Strides, Derived>\n    stride(const Strides& strides) {\n      return TensorStridingOp<const Strides, Derived>(derived(), strides);\n    }\n\n    // Select the device on which to evaluate the expression.\n    template <typename DeviceType>\n    TensorDevice<Derived, DeviceType> device(const DeviceType& dev) {\n      return TensorDevice<Derived, DeviceType>(dev, derived());\n    }\n\n    // Select the async device on which to evaluate the expression.\n    template <typename DeviceType, typename DoneCallback>\n    TensorAsyncDevice<Derived, DeviceType, DoneCallback> device(const DeviceType& dev, DoneCallback done) {\n      return TensorAsyncDevice<Derived, DeviceType, DoneCallback>(dev, derived(), std::move(done));\n    }\n\n    #ifdef EIGEN_TENSORBASE_PLUGIN\n    #include EIGEN_TENSORBASE_PLUGIN\n    #endif\n\n protected:\n    EIGEN_DEFAULT_EMPTY_CONSTRUCTOR_AND_DESTRUCTOR(TensorBase)\n    EIGEN_DEFAULT_COPY_CONSTRUCTOR(TensorBase)\n\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Derived& operator=(const OtherDerived& other)\n    {\n      typedef TensorAssignOp<Derived, const OtherDerived> Assign;\n      Assign assign(derived(), other.derived());\n      internal::TensorExecutor<const Assign, DefaultDevice>::run(assign, DefaultDevice());\n      return derived();\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Derived& derived() { return *static_cast<Derived*>(this); }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Derived& derived() const { return *static_cast<const Derived*>(this); }\n};\n#endif // EIGEN_PARSED_BY_DOXYGEN\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_BASE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBlock.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_BLOCK_H\n#define EIGEN_CXX11_TENSOR_TENSOR_BLOCK_H\n\nnamespace Eigen {\nnamespace internal {\n\n// -------------------------------------------------------------------------- //\n// Forward declarations for templates defined below.\ntemplate <typename Scalar, typename IndexType, int NumDims, int Layout>\nclass TensorBlockIO;\n\n// -------------------------------------------------------------------------- //\n// Helper function to compute strides for densely stored buffer of given\n// dimensions.\n\n// TODO(ezhulenev): We compute strides 1000 times in different evaluators, use\n// this function instead everywhere.\ntemplate <int Layout, typename IndexType, int NumDims>\nEIGEN_ALWAYS_INLINE DSizes<IndexType, NumDims> strides(\n    const DSizes<IndexType, NumDims>& dimensions) {\n  DSizes<IndexType, NumDims> strides;\n  if (NumDims == 0) return strides;\n\n  // TODO(ezhulenev): Use templates to unroll this loop (similar to\n  // h_array_reduce in CXX11meta.h)? Benchmark it.\n  if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n    strides[0] = 1;\n    for (int i = 1; i < NumDims; ++i) {\n      strides[i] = strides[i - 1] * dimensions[i - 1];\n    }\n  } else {\n    strides[NumDims - 1] = 1;\n    for (int i = NumDims - 2; i >= 0; --i) {\n      strides[i] = strides[i + 1] * dimensions[i + 1];\n    }\n  }\n\n  return strides;\n}\n\ntemplate <int Layout, typename IndexType, size_t NumDims>\nEIGEN_ALWAYS_INLINE DSizes<IndexType, NumDims> strides(\n    const Eigen::array<IndexType, NumDims>& dimensions) {\n  return strides<Layout>(DSizes<IndexType, NumDims>(dimensions));\n}\n\ntemplate <int Layout, std::ptrdiff_t... Indices>\nEIGEN_STRONG_INLINE DSizes<std::ptrdiff_t, sizeof...(Indices)> strides(\n    const Sizes<Indices...>& sizes) {\n  return strides<Layout>(DSizes<std::ptrdiff_t, sizeof...(Indices)>(sizes));\n}\n\n// -------------------------------------------------------------------------- //\n\n// Tensor block shape type defines what are the shape preference for the blocks\n// extracted from the larger tensor.\n//\n// Example: blocks of 100 elements from the large 100x100 tensor:\n// - tensor: 100x100\n// - target_block_size: 100\n//\n// TensorBlockShapeType:\n//  - kUniformAllDims: 100 blocks of size 10x10\n//  - kSkewedInnerDims: 100 blocks of size 100x1 (or 1x100 depending on a column\n//                      or row major layout)\nenum class TensorBlockShapeType { kUniformAllDims, kSkewedInnerDims };\n\nstruct TensorBlockResourceRequirements {\n  TensorBlockShapeType shape_type;  // target block shape\n  size_t size;                      // target block size\n  TensorOpCost cost_per_coeff;      // cost of computing a single block element\n\n#ifdef EIGEN_HIPCC\n  // For HIPCC, we need to explicitly declare as a \"device fun\", the constructor\n  // which is implicitly invoked in the \"merge\" / \"any\" routines. else HIPCC\n  // errors out complaining about the lack of a matching constructor\n  EIGEN_DEVICE_FUNC\n  TensorBlockResourceRequirements(TensorBlockShapeType shape_type_, size_t size_,\n\t\t\t\t  TensorOpCost cost_)\n    : shape_type(shape_type_), size(size_), cost_per_coeff(cost_)\n  {}\n#endif\n\n  template <typename Scalar>\n  EIGEN_DEVICE_FUNC static TensorBlockResourceRequirements withShapeAndSize(\n      TensorBlockShapeType shape_type, size_t size_in_bytes,\n      TensorOpCost cost) {\n    const size_t size = numext::maxi(size_t(1), size_in_bytes / sizeof(Scalar));\n    return {shape_type, size, cost};\n  }\n\n  template <typename Scalar>\n  EIGEN_DEVICE_FUNC static TensorBlockResourceRequirements withShapeAndSize(\n      TensorBlockShapeType shape_type, size_t size_in_bytes) {\n    // This default cost per coefficient is valid for most materialized tensor\n    // block evaluation implementations, because they typically just read\n    // coefficients from the underlying tensor storage, and write to the tensor\n    // block buffer (scratch or destination memory, reads and writes have linear\n    // access pattern). We ignore the fixed cost of block evaluation, because in\n    // practice it should negligible.\n    //\n    // Lazy block evaluation adds the cost of calling a functor for each\n    // coefficient.\n    //\n    // All non-trivial block evaluation implementations must provide their own\n    // cost approximation (e.g. shuffling inner dimension has a much higher cost\n    // because it reads memory randomly, although the total number of moved\n    // bytes is the same).\n    return withShapeAndSize<Scalar>(shape_type, size_in_bytes,\n                                    {/*bytes_loaded=*/sizeof(Scalar),\n                                     /*bytes_stored=*/sizeof(Scalar),\n                                     /*compute_cycles=*/0});\n  }\n\n  template <typename Scalar>\n  EIGEN_DEVICE_FUNC static TensorBlockResourceRequirements skewed(\n      size_t size_in_bytes) {\n    return withShapeAndSize<Scalar>(TensorBlockShapeType::kSkewedInnerDims,\n                                    size_in_bytes);\n  }\n\n  template <typename Scalar>\n  EIGEN_DEVICE_FUNC static TensorBlockResourceRequirements uniform(\n      size_t size_in_bytes) {\n    return withShapeAndSize<Scalar>(TensorBlockShapeType::kUniformAllDims,\n                                    size_in_bytes);\n  }\n\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE TensorBlockResourceRequirements\n  merge(const TensorBlockResourceRequirements& lhs,\n        const TensorBlockResourceRequirements& rhs) {\n    return {merge(lhs.shape_type, rhs.shape_type),           // shape_type\n            merge(lhs.size, rhs.size),                       // size\n            merge(lhs.cost_per_coeff, rhs.cost_per_coeff)};  // cost_per_coeff\n  }\n\n  EIGEN_DEVICE_FUNC TensorBlockResourceRequirements& addCostPerCoeff(\n      TensorOpCost cost) {\n    cost_per_coeff += cost;\n    return *this;\n  }\n\n  // This is a resource requirement that should be returned from expressions\n  // that do not have any block evaluation preference (e.g. default tensor\n  // expression with raw buffer access).\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE TensorBlockResourceRequirements any() {\n    return {TensorBlockShapeType::kUniformAllDims, 1, {0, 0, 0}};\n  }\n\n private:\n  using Requirements = TensorBlockResourceRequirements;\n\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE size_t merge(size_t lhs_size, size_t rhs_size) {\n    return numext::maxi(lhs_size, rhs_size);\n  }\n\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE TensorBlockShapeType\n  merge(TensorBlockShapeType lhs, TensorBlockShapeType rhs) {\n    return (lhs == TensorBlockShapeType::kSkewedInnerDims ||\n            rhs == TensorBlockShapeType::kSkewedInnerDims)\n               ? TensorBlockShapeType::kSkewedInnerDims\n               : TensorBlockShapeType::kUniformAllDims;\n  }\n\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE TensorOpCost merge(TensorOpCost lhs_cost,\n                                                TensorOpCost rhs_cost) {\n    return lhs_cost + rhs_cost;\n  }\n};\n\n// -------------------------------------------------------------------------- //\n// TensorBlockDescriptor specifies a block offset within a tensor and the block\n// sizes along each of the tensor dimensions.\n\ntemplate <int NumDims, typename IndexType = Eigen::Index>\nclass TensorBlockDescriptor {\n public:\n  typedef DSizes<IndexType, NumDims> Dimensions;\n\n  // If we evaluate a Tensor assignment, and expression on the left, already has\n  // a memory buffer, then we might do performance optimization, and evaluate\n  // the root expression directly into the final output memory. Some time it's\n  // possible to reuse it for materializing subexpressions inside an expression\n  // tree, to to avoid dynamic memory allocation.\n  //\n  // The pointer type of the underlying storage is erased, because passing\n  // Scalar type through all the expression evaluation layers is way too many\n  // templates. In practice destination buffer type should always match the\n  // evaluated expression scalar type.\n  class DestinationBuffer {\n   public:\n    enum DestinationBufferKind : int {\n      // The above explicit specification of \"int\" as the enum basetype is\n      // needed to get around a HIPCC link error (\"the field type is not\n      // amp-compatible\")\n      // which is issued for class members with the enum type.\n      // TODO(rocm):\n      // remove the \"int\" basetype once HIPCC has been fixed to not error out\n      // in the above scenario.\n\n      // Destination buffer is not defined (`m_data` == nullptr).\n      kEmpty,\n\n      // Tensor block defined by an owning tensor block descriptor can fit\n      // contiguously into the destination buffer. In this case it's safe to\n      // materialize tensor block in the destination buffer, wrap it in a\n      // TensorMap, and use to build Eigen expression on top of it.\n      kContiguous,\n\n      // Destination buffer strides do not match strides of the contiguously\n      // stored block, and it's impossible to define a TensorMap over this\n      // buffer. However if we are evaluating a root of an expression tree, we\n      // still can materialize an output into this destination, because we can\n      // guarantee that no one will ever access it through block API.\n      //\n      // In theory it is possible to build valid TensorStriding<TensorMap>\n      // expression on top of this destination buffer, however it has\n      // inefficient coeff/packet access, and defeats the purpose of fast block\n      // evaluation API.\n      kStrided\n    };\n\n    template <typename Scalar>\n    Scalar* data() const {\n      eigen_assert(m_data_type_size == sizeof(Scalar));\n      return static_cast<Scalar*>(m_data);\n    }\n\n    const Dimensions& strides() const { return m_strides; }\n    const DestinationBufferKind& kind() const { return m_kind; }\n\n   private:\n    friend class TensorBlockDescriptor;\n\n    DestinationBuffer() : m_data(NULL), m_data_type_size(0), m_kind(kEmpty) {}\n\n    template <typename Scalar>\n    DestinationBuffer(Scalar* data, const Dimensions& strides,\n                      DestinationBufferKind kind)\n        : m_data(static_cast<void*>(data)),\n          m_data_type_size(sizeof(Scalar)),\n          m_strides(strides),\n          m_kind(kind) {}\n\n    template <int Layout, typename Scalar>\n    static DestinationBuffer make(const TensorBlockDescriptor& desc,\n                                  Scalar* data, const Dimensions& strides) {\n      return DestinationBuffer(data, strides, kind<Layout>(desc, strides));\n    }\n\n    template <int Layout>\n    static DestinationBufferKind kind(const TensorBlockDescriptor& desc,\n                                      const Dimensions& strides) {\n      const Dimensions& desc_dims = desc.dimensions();\n      const Dimensions& desc_strides = internal::strides<Layout>(desc_dims);\n      for (int i = 0; i < NumDims; ++i) {\n        if (desc_dims[i] == 1) continue;\n        if (desc_strides[i] != strides[i]) return kStrided;\n      }\n      return kContiguous;\n    }\n\n    // Storage pointer is type erased, to reduce template bloat, but we still\n    // keep the size of the underlying element type for error checking.\n    void* m_data;\n    size_t m_data_type_size;\n\n    // Destination buffer dimensions always match the dimensions of a tensor\n    // block descriptor it belongs to, however strides might be different.\n    Dimensions m_strides;\n\n    DestinationBufferKind m_kind;\n  };\n\n  TensorBlockDescriptor(const IndexType offset, const Dimensions& dimensions,\n                        const DestinationBuffer& destination)\n      : m_offset(offset),\n        m_dimensions(dimensions),\n        m_destination(destination) {}\n\n  TensorBlockDescriptor(const IndexType offset, const Dimensions& dimensions)\n      : m_offset(offset),\n        m_dimensions(dimensions),\n        m_destination(DestinationBuffer()) {}\n\n  IndexType offset() const { return m_offset; }\n  const Dimensions& dimensions() const { return m_dimensions; }\n  IndexType dimension(int index) const { return m_dimensions[index]; }\n  IndexType size() const { return array_prod<IndexType>(m_dimensions); }\n\n  const DestinationBuffer& destination() const { return m_destination; }\n\n  template <int Layout, typename Scalar>\n  void AddDestinationBuffer(Scalar* dst_base, const Dimensions& dst_strides) {\n    eigen_assert(dst_base != NULL);\n    m_destination =\n        DestinationBuffer::template make<Layout>(*this, dst_base, dst_strides);\n  }\n\n  template <int Layout, typename Scalar, typename DstStridesIndexType>\n  void AddDestinationBuffer(\n      Scalar* dst_base,\n      const DSizes<DstStridesIndexType, NumDims>& dst_strides) {\n    // DSizes constructor will do index type promotion if it's safe.\n    AddDestinationBuffer<Layout>(dst_base, Dimensions(dst_strides));\n  }\n\n  TensorBlockDescriptor& DropDestinationBuffer() {\n    m_destination.m_data = NULL;\n    m_destination.m_kind = DestinationBuffer::kEmpty;\n    return *this;\n  }\n\n  bool HasDestinationBuffer() const {\n    return m_destination.kind() != DestinationBuffer::kEmpty;\n  }\n\n  // Returns a copy of `*this` with updated offset.\n  TensorBlockDescriptor WithOffset(IndexType offset) const {\n    return TensorBlockDescriptor(offset, m_dimensions, m_destination);\n  }\n\n private:\n  // Offset and dimensions are immutable after construction. Block descriptor\n  // can only be mutated by adding or dropping destination.\n  const IndexType m_offset;\n  const Dimensions m_dimensions;\n  DestinationBuffer m_destination;\n};\n\n// -------------------------------------------------------------------------- //\n// TensorBlockMapper is responsible for iterating over the blocks of a tensor.\n\ntemplate <int NumDims, int Layout, typename IndexType = Eigen::Index>\nclass TensorBlockMapper {\n  typedef TensorBlockDescriptor<NumDims, IndexType> BlockDescriptor;\n\n public:\n  typedef DSizes<IndexType, NumDims> Dimensions;\n\n  TensorBlockMapper() = default;\n  TensorBlockMapper(const DSizes<IndexType, NumDims>& dimensions,\n                    const TensorBlockResourceRequirements& requirements)\n      : m_tensor_dimensions(dimensions), m_requirements(requirements) {\n    // Compute block dimensions and the total number of blocks.\n    InitializeBlockDimensions();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE IndexType blockCount() const {\n    return m_total_block_count;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE IndexType blockTotalSize() const {\n    return m_block_dimensions.TotalSize();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const DSizes<IndexType, NumDims>&\n  blockDimensions() const {\n    return m_block_dimensions;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE BlockDescriptor\n  blockDescriptor(IndexType block_index) const {\n    static const bool isColMajor = Layout == static_cast<int>(ColMajor);\n\n    IndexType offset = 0;\n    DSizes<IndexType, NumDims> dimensions;\n\n    if (NumDims == 0) return BlockDescriptor(offset, dimensions);\n\n    // Iterate outer -> inner dimensions.\n    for (int i = NumDims - 1; i >= 0; --i) {\n      const int dim = isColMajor ? i : NumDims - i - 1;\n\n      const IndexType idx = block_index / m_block_strides[dim];\n      block_index -= idx * m_block_strides[dim];\n\n      const IndexType coord = idx * m_block_dimensions[dim];\n      dimensions[dim] = numext::mini(m_tensor_dimensions[dim] - coord,\n                                     m_block_dimensions[dim]);\n      offset += coord * m_tensor_strides[dim];\n    }\n\n    return {offset, dimensions};\n  }\n\n private:\n  void InitializeBlockDimensions() {\n    // Requested block shape and size.\n    const TensorBlockShapeType shape_type = m_requirements.shape_type;\n    IndexType target_block_size =\n        numext::maxi<IndexType>(1, static_cast<IndexType>(m_requirements.size));\n\n    IndexType tensor_size = m_tensor_dimensions.TotalSize();\n\n    // Corner case: one of the dimensions is zero. Logic below is too complex\n    // to handle this case on a general basis, just use unit block size.\n    // Note: we must not yield blocks with zero dimensions (recipe for\n    // overflows/underflows, divisions by zero and NaNs later).\n    if (tensor_size == 0) {\n      for (int i = 0; i < NumDims; ++i) {\n        m_block_dimensions[i] = 1;\n      }\n      m_total_block_count = 0;\n      return;\n    }\n\n    // If tensor fits into a target block size, evaluate it as a single block.\n    if (tensor_size <= target_block_size) {\n      m_block_dimensions = m_tensor_dimensions;\n      m_total_block_count = 1;\n      // The only valid block index is `0`, and in this case we do not need\n      // to compute real strides for tensor or blocks (see blockDescriptor).\n      for (int i = 0; i < NumDims; ++i) {\n        m_tensor_strides[i] = 0;\n        m_block_strides[i] = 1;\n      }\n      return;\n    }\n\n    static const bool isColMajor = Layout == static_cast<int>(ColMajor);\n\n    // Block shape skewed towards inner dimension.\n    if (shape_type == TensorBlockShapeType::kSkewedInnerDims) {\n      IndexType coeff_to_allocate = target_block_size;\n\n      for (int i = 0; i < NumDims; ++i) {\n        const int dim = isColMajor ? i : NumDims - i - 1;\n        m_block_dimensions[dim] =\n            numext::mini(coeff_to_allocate, m_tensor_dimensions[dim]);\n        coeff_to_allocate = divup(\n            coeff_to_allocate,\n            numext::maxi(static_cast<IndexType>(1), m_block_dimensions[dim]));\n      }\n      eigen_assert(coeff_to_allocate == 1);\n\n    } else if (shape_type == TensorBlockShapeType::kUniformAllDims) {\n      // Tensor will not fit within 'target_block_size' budget: calculate tensor\n      // block dimension sizes based on \"square\" dimension size target.\n      const IndexType dim_size_target = convert_index<IndexType>(\n          std::pow(static_cast<float>(target_block_size),\n                   1.0f / static_cast<float>(m_block_dimensions.rank())));\n\n      for (int i = 0; i < NumDims; ++i) {\n        // TODO(andydavis) Adjust the inner most 'block_dim_size' to make it\n        // a multiple of the packet size. Note that reducing\n        // 'block_dim_size' in this manner can increase the number of\n        // blocks, and so will amplify any per-block overhead.\n        m_block_dimensions[i] =\n            numext::mini(dim_size_target, m_tensor_dimensions[i]);\n      }\n\n      // Add any un-allocated coefficients to inner dimension(s).\n      IndexType total_size = m_block_dimensions.TotalSize();\n      for (int i = 0; i < NumDims; ++i) {\n        const int dim = isColMajor ? i : NumDims - i - 1;\n\n        if (m_block_dimensions[dim] < m_tensor_dimensions[dim]) {\n          const IndexType total_size_other_dims =\n              total_size / m_block_dimensions[dim];\n          const IndexType alloc_avail =\n              divup<IndexType>(target_block_size, total_size_other_dims);\n          if (alloc_avail == m_block_dimensions[dim]) {\n            // Insufficient excess coefficients to allocate.\n            break;\n          }\n          m_block_dimensions[dim] =\n              numext::mini(m_tensor_dimensions[dim], alloc_avail);\n          total_size = total_size_other_dims * m_block_dimensions[dim];\n        }\n      }\n\n    } else {\n      eigen_assert(false);  // unknown block shape\n    }\n\n    eigen_assert(m_block_dimensions.TotalSize() >=\n                 numext::mini<IndexType>(target_block_size,\n                                         m_tensor_dimensions.TotalSize()));\n\n    // Calculate block counts by dimension and total block count.\n    DSizes<IndexType, NumDims> block_count;\n    for (int i = 0; i < NumDims; ++i) {\n      block_count[i] = divup(m_tensor_dimensions[i], m_block_dimensions[i]);\n    }\n    m_total_block_count = array_prod(block_count);\n\n    // Calculate block strides (used for enumerating blocks).\n    m_tensor_strides = strides<Layout>(m_tensor_dimensions);\n    m_block_strides = strides<Layout>(block_count);\n  }\n\n  DSizes<IndexType, NumDims> m_tensor_dimensions;\n  TensorBlockResourceRequirements m_requirements;\n\n  DSizes<IndexType, NumDims> m_block_dimensions;\n  IndexType m_total_block_count;\n\n  DSizes<IndexType, NumDims> m_tensor_strides;\n  DSizes<IndexType, NumDims> m_block_strides;\n};\n\n// -------------------------------------------------------------------------- //\n// TensorBlockScratchAllocator is responsible for allocating temporary buffers\n// for block evaluation (output or input block materialization). Given that\n// Eigen expression traversal order is deterministic, all temporary allocations\n// are happening in the same order, and usually have exactly the same size.\n// Scratch allocator keeps a trace of all dynamic allocations, and after the\n// first block evaluation is completed, we should be able to reuse all the\n// temporary buffers for the next block evaluation.\n\ntemplate <typename Device>\nclass TensorBlockScratchAllocator {\n public:\n  explicit TensorBlockScratchAllocator(const Device& device)\n      : m_device(device), m_allocation_index(0) {}\n\n  ~TensorBlockScratchAllocator() {\n    for (size_t i = 0; i < m_allocations.size(); ++i) {\n      m_device.deallocate(m_allocations[i].ptr);\n    }\n  }\n\n  void* allocate(size_t size) {\n    // TODO(ezhulenev): Remove when replaced with inlined vector.\n    if (m_allocations.capacity() == 0) m_allocations.reserve(8);\n\n    // Check if we already have an existing allocation att current index.\n    const int num_allocations = static_cast<int>(m_allocations.size());\n    const bool has_allocation = m_allocation_index < num_allocations;\n\n    // Allocation index can't be larger than the number of allocations.\n    eigen_assert(m_allocation_index <= num_allocations);\n\n    // If we have existing allocation, and its size is larger or equal to\n    // requested size, we do nothing.\n\n    // If current allocation can't fit requested size, we deallocate it, and\n    // replace with a larger allocation.\n    if (has_allocation && m_allocations[m_allocation_index].size < size) {\n      m_device.deallocate(m_allocations[m_allocation_index].ptr);\n      m_allocations[m_allocation_index].ptr = m_device.allocate(size);\n      m_allocations[m_allocation_index].size = size;\n    }\n\n    // Make a new allocation if we don't have and existing one.\n    if (!has_allocation) {\n      Allocation allocation;\n      allocation.ptr = m_device.allocate(size);\n      allocation.size = size;\n      m_allocations.push_back(allocation);\n    }\n\n    eigen_assert(m_allocations[m_allocation_index].ptr != NULL);\n    eigen_assert(m_allocations[m_allocation_index].size >= size);\n\n    return m_allocations[m_allocation_index++].ptr;\n  }\n\n  void reset() { m_allocation_index = 0; }\n\n private:\n  struct Allocation {\n    void* ptr;\n    size_t size;\n  };\n\n  const Device& m_device;\n  int m_allocation_index;\n  // TODO(ezhulenev): This should be an inlined vector.\n  std::vector<Allocation> m_allocations;\n};\n\n// -------------------------------------------------------------------------- //\n// TensorBlockKind represents all possible block kinds, that can be produced by\n// TensorEvaluator::evalBlock function.\nenum TensorBlockKind {\n  // Tensor block that is a lazy expression that must be assigned to a\n  // destination using TensorBlockAssign.\n  kExpr,\n\n  // Tensor block that is a view into a memory buffer owned by an underlying\n  // Tensor expression (e.g. it can be a view into a Tensor buffer).\n  kView,\n\n  // Tensor block that was materialized in a scratch memory buffer, allocated\n  // with TensorBlockScratchAllocator. This block must be copied to a\n  // destination, similar to a block of `kExpr` type.\n  kMaterializedInScratch,\n\n  // Tensor block that was materialized directly into the final output memory\n  // buffer. For example if the left side of an assignment is a Tensor, we can\n  // directly materialize the block in the destination memory.\n  //\n  // If strides in the output buffer do not match tensor block strides, the\n  // Tensor expression will be invalid, and should not be used by\n  // TensorBlockAssign or for constructing another block expression.\n  kMaterializedInOutput\n};\n\n// -------------------------------------------------------------------------- //\n// TensorBlockNotImplemented should be used to defined TensorBlock typedef in\n// TensorEvaluators that do not support block evaluation.\n\nclass TensorBlockNotImplemented {\n public:\n  typedef void XprType;\n};\n\n// -------------------------------------------------------------------------- //\n// XprScalar extracts Scalar type from the Eigen expressions (if expression type\n// is not void). It's required to be able to define lazy block expression for\n// argument types, that do not support block evaluation.\n\ntemplate <typename XprType>\nstruct XprScalar {\n  typedef typename XprType::Scalar type;\n};\ntemplate <>\nstruct XprScalar<void> {\n  typedef void type;\n};\n\n// -------------------------------------------------------------------------- //\n// TensorMaterializedBlock is a fully evaluated block of the original tensor,\n// and XprType is just a TensorMap over the data. This block type is typically\n// used to materialize blocks of tensor expressions, that can't be efficiently\n// represented as lazy Tensor expressions with fast coeff/packet operations,\n// e.g. we materialize all broadcasts into evaluated blocks.\n//\n// TensorMaterializedBlock does not own its memory buffer, it's either a memory\n// buffer that backs the original expression (e.g. block is just a view into a\n// Tensor), or a memory buffer allocated with scratch allocator, and in this\n// case the scratch allocator will deallocate it at the end of block based\n// expression execution.\n//\n// If the block was evaluated directly into the output buffer, and strides in\n// the output buffer do not match block strides, the TensorMap expression will\n// be invalid, and should never be used in block assignment or any other tensor\n// expression.\n\ntemplate <typename Scalar, int NumDims, int Layout,\n          typename IndexType = Eigen::Index>\nclass TensorMaterializedBlock {\n public:\n  typedef DSizes<IndexType, NumDims> Dimensions;\n  typedef TensorMap<const Tensor<Scalar, NumDims, Layout> > XprType;\n\n  TensorMaterializedBlock(TensorBlockKind kind, const Scalar* data,\n                          const Dimensions& dimensions, bool valid_expr = true)\n      : m_kind(kind),\n        m_data(data),\n        m_dimensions(dimensions),\n        m_expr(m_data, m_dimensions),\n        m_valid_expr(valid_expr) {\n    eigen_assert(m_kind == internal::TensorBlockKind::kView ||\n                 m_kind == internal::TensorBlockKind::kMaterializedInScratch ||\n                 m_kind == internal::TensorBlockKind::kMaterializedInOutput);\n  }\n\n  TensorBlockKind kind() const { return m_kind; }\n  // NOTE(ezhulenev): Returning XprType by value like in other block types\n  // causes asan failures. The theory is that XprType::Nested doesn't work\n  // properly for TensorMap.\n  const XprType& expr() const {\n    eigen_assert(m_valid_expr);\n    return m_expr;\n  }\n  const Scalar* data() const { return m_data; }\n  void cleanup() {}\n\n  typedef internal::TensorBlockDescriptor<NumDims, IndexType> TensorBlockDesc;\n\n  // TensorMaterializedBlock can be backed by different types of storage:\n  //\n  //   (1) Contiguous block of memory allocated with scratch allocator.\n  //   (2) Contiguous block of memory reused from tensor block descriptor\n  //       destination buffer.\n  //   (3) Strided block of memory reused from tensor block descriptor\n  //       destination buffer.\n  //\n  class Storage {\n   public:\n    Scalar* data() const { return m_data; }\n    const Dimensions& dimensions() const { return m_dimensions; }\n    const Dimensions& strides() const { return m_strides; }\n\n    TensorMaterializedBlock AsTensorMaterializedBlock() const {\n      return TensorMaterializedBlock(\n          m_materialized_in_output\n              ? internal::TensorBlockKind::kMaterializedInOutput\n              : internal::TensorBlockKind::kMaterializedInScratch,\n          m_data, m_dimensions, !m_strided_storage);\n    }\n\n   private:\n    friend class TensorMaterializedBlock;\n\n    Storage(Scalar* data, const Dimensions& dimensions,\n            const Dimensions& strides, bool materialized_in_output,\n            bool strided_storage)\n        : m_data(data),\n          m_dimensions(dimensions),\n          m_strides(strides),\n          m_materialized_in_output(materialized_in_output),\n          m_strided_storage(strided_storage) {}\n\n    Scalar* m_data;\n    Dimensions m_dimensions;\n    Dimensions m_strides;\n    bool m_materialized_in_output;\n    bool m_strided_storage;\n  };\n\n  // Creates a storage for materialized block either from the block descriptor\n  // destination buffer, or allocates a new buffer with scratch allocator.\n  template <typename TensorBlockScratch>\n  EIGEN_STRONG_INLINE static Storage prepareStorage(\n      TensorBlockDesc& desc, TensorBlockScratch& scratch,\n      bool allow_strided_storage = false) {\n    // Try to reuse destination as an output block buffer.\n    typedef typename TensorBlockDesc::DestinationBuffer DestinationBuffer;\n\n    if (desc.destination().kind() == DestinationBuffer::kContiguous) {\n      Scalar* buffer = desc.destination().template data<Scalar>();\n      desc.DropDestinationBuffer();\n      return Storage(buffer, desc.dimensions(),\n                     internal::strides<Layout>(desc.dimensions()),\n                     /*materialized_in_output=*/true,\n                     /*strided_storage=*/false);\n\n    } else if (desc.destination().kind() == DestinationBuffer::kStrided &&\n               allow_strided_storage) {\n      Scalar* buffer = desc.destination().template data<Scalar>();\n      desc.DropDestinationBuffer();\n      return Storage(buffer, desc.dimensions(), desc.destination().strides(),\n                     /*materialized_in_output=*/true, /*strided_storage=*/true);\n\n    } else {\n      void* mem = scratch.allocate(desc.size() * sizeof(Scalar));\n      return Storage(static_cast<Scalar*>(mem), desc.dimensions(),\n                     internal::strides<Layout>(desc.dimensions()),\n                     /*materialized_in_output=*/false,\n                     /*strided_storage=*/false);\n    }\n  }\n\n  // Creates a materialized block for the given descriptor from a memory buffer.\n  template <typename DataDimensions, typename TensorBlockScratch>\n  EIGEN_STRONG_INLINE static TensorMaterializedBlock materialize(\n      const Scalar* data, const DataDimensions& data_dims,\n      TensorBlockDesc& desc, TensorBlockScratch& scratch) {\n    eigen_assert(array_size<DataDimensions>::value == desc.dimensions().size());\n\n    // If a tensor block dimensions covers a contiguous block of the underlying\n    // memory, we can skip block buffer memory allocation, and construct a block\n    // from existing `data` memory buffer.\n    //\n    // Example: (RowMajor layout)\n    //   data_dims:          [11, 12, 13, 14]\n    //   desc.dimensions():  [1,   1,  3, 14]\n    //\n    // In this case we can construct a TensorBlock starting at\n    // `data + desc.offset()`, with a `desc.dimensions()` block sizes.\n    static const bool is_col_major = Layout == ColMajor;\n\n    // Find out how many inner dimensions have a matching size.\n    int num_matching_inner_dims = 0;\n    for (int i = 0; i < NumDims; ++i) {\n      int dim = is_col_major ? i : NumDims - i - 1;\n      if (data_dims[dim] != desc.dimensions()[dim]) break;\n      ++num_matching_inner_dims;\n    }\n\n    // All the outer dimensions must be of size `1`, except a single dimension\n    // before the matching inner dimension (`3` in the example above).\n    bool can_use_direct_access = true;\n    for (int i = num_matching_inner_dims + 1; i < NumDims; ++i) {\n      int dim = is_col_major ? i : NumDims - i - 1;\n      if (desc.dimension(dim) != 1) {\n        can_use_direct_access = false;\n        break;\n      }\n    }\n\n    if (can_use_direct_access) {\n      const Scalar* block_start = data + desc.offset();\n      return TensorMaterializedBlock(internal::TensorBlockKind::kView,\n                                     block_start, desc.dimensions());\n\n    } else {\n      // Reuse destination buffer or allocate new buffer with scratch allocator.\n      const Storage storage = prepareStorage(desc, scratch);\n\n      typedef internal::TensorBlockIO<Scalar, IndexType, NumDims, Layout>\n          TensorBlockIO;\n      typedef typename TensorBlockIO::Dst TensorBlockIODst;\n      typedef typename TensorBlockIO::Src TensorBlockIOSrc;\n\n      TensorBlockIOSrc src(internal::strides<Layout>(Dimensions(data_dims)),\n                           data, desc.offset());\n      TensorBlockIODst dst(storage.dimensions(), storage.strides(),\n                           storage.data());\n\n      TensorBlockIO::Copy(dst, src);\n      return storage.AsTensorMaterializedBlock();\n    }\n  }\n\n private:\n  TensorBlockKind m_kind;\n  const Scalar* m_data;\n  Dimensions m_dimensions;\n  XprType m_expr;\n  bool m_valid_expr;\n};\n\n// -------------------------------------------------------------------------- //\n// TensorCwiseUnaryBlock is a lazy tensor expression block that applies UnaryOp\n// functor to the blocks produced by the underlying Tensor expression.\n\ntemplate <typename UnaryOp, typename ArgTensorBlock>\nclass TensorCwiseUnaryBlock {\n  static const bool NoArgBlockAccess =\n      internal::is_void<typename ArgTensorBlock::XprType>::value;\n\n public:\n  typedef typename conditional<\n      NoArgBlockAccess, void,\n      TensorCwiseUnaryOp<UnaryOp, const typename ArgTensorBlock::XprType> >::\n      type XprType;\n\n  typedef typename XprScalar<XprType>::type Scalar;\n\n  TensorCwiseUnaryBlock(const ArgTensorBlock& arg_block, const UnaryOp& functor)\n      : m_arg_block(arg_block), m_functor(functor) {}\n\n  TensorBlockKind kind() const { return internal::TensorBlockKind::kExpr; }\n\n  XprType expr() const { return XprType(m_arg_block.expr(), m_functor); }\n  const Scalar* data() const { return NULL; }\n  void cleanup() { m_arg_block.cleanup(); }\n\n private:\n  ArgTensorBlock m_arg_block;\n  UnaryOp m_functor;\n};\n\n// -------------------------------------------------------------------------- //\n// TensorCwiseUnaryBlock is a lazy tensor expression block that applies BinaryOp\n// functor to the blocks produced by the underlying Tensor expression.\n\ntemplate <typename BinaryOp, typename LhsTensorBlock, typename RhsTensorBlock>\nclass TensorCwiseBinaryBlock {\n  static const bool NoArgBlockAccess =\n      internal::is_void<typename LhsTensorBlock::XprType>::value ||\n      internal::is_void<typename RhsTensorBlock::XprType>::value;\n\n public:\n  typedef typename conditional<\n      NoArgBlockAccess, void,\n      TensorCwiseBinaryOp<BinaryOp, const typename LhsTensorBlock::XprType,\n                          const typename RhsTensorBlock::XprType> >::type\n      XprType;\n\n  typedef typename XprScalar<XprType>::type Scalar;\n\n  TensorCwiseBinaryBlock(const LhsTensorBlock& left_block,\n                         const RhsTensorBlock& right_block,\n                         const BinaryOp& functor)\n      : m_left_block(left_block),\n        m_right_block(right_block),\n        m_functor(functor) {}\n\n  TensorBlockKind kind() const { return internal::TensorBlockKind::kExpr; }\n\n  XprType expr() const {\n    return XprType(m_left_block.expr(), m_right_block.expr(), m_functor);\n  }\n\n  const Scalar* data() const { return NULL; }\n\n  void cleanup() {\n    m_left_block.cleanup();\n    m_right_block.cleanup();\n  }\n\n private:\n  LhsTensorBlock m_left_block;\n  RhsTensorBlock m_right_block;\n  BinaryOp m_functor;\n};\n\n// -------------------------------------------------------------------------- //\n// TensorUnaryExprBlock is a lazy tensor expression block that can construct\n// an arbitrary tensor expression from a block of the underlying type (this is a\n// generalization of the TensorCwiseUnaryBlock for arbitrary expressions).\n\ntemplate <typename BlockFactory, typename ArgTensorBlock>\nclass TensorUnaryExprBlock {\n  typedef typename ArgTensorBlock::XprType ArgXprType;\n  static const bool NoArgBlockAccess = internal::is_void<ArgXprType>::value;\n\n public:\n  typedef typename conditional<\n      NoArgBlockAccess, void,\n      typename BlockFactory::template XprType<ArgXprType>::type>::type XprType;\n\n  typedef typename XprScalar<XprType>::type Scalar;\n\n  TensorUnaryExprBlock(const ArgTensorBlock& arg_block,\n                       const BlockFactory& factory)\n      : m_arg_block(arg_block), m_factory(factory) {}\n\n  TensorBlockKind kind() const { return internal::TensorBlockKind::kExpr; }\n  XprType expr() const { return m_factory.expr(m_arg_block.expr()); }\n  const Scalar* data() const { return NULL; }\n  void cleanup() { m_arg_block.cleanup(); }\n\n private:\n  ArgTensorBlock m_arg_block;\n  BlockFactory m_factory;\n};\n\n// -------------------------------------------------------------------------- //\n// TensorTernaryExprBlock is a lazy tensor expression block that can construct\n// an arbitrary tensor expression from three blocks of the underlying type.\n\ntemplate <typename BlockFactory, typename Arg1TensorBlock,\n          typename Arg2TensorBlock, typename Arg3TensorBlock>\nclass TensorTernaryExprBlock {\n  typedef typename Arg1TensorBlock::XprType Arg1XprType;\n  typedef typename Arg2TensorBlock::XprType Arg2XprType;\n  typedef typename Arg3TensorBlock::XprType Arg3XprType;\n\n  static const bool NoArgBlockAccess = internal::is_void<Arg1XprType>::value ||\n                                       internal::is_void<Arg2XprType>::value ||\n                                       internal::is_void<Arg3XprType>::value;\n\n public:\n  typedef typename conditional<\n      NoArgBlockAccess, void,\n      typename BlockFactory::template XprType<Arg1XprType, Arg2XprType,\n                                              Arg3XprType>::type>::type XprType;\n\n  typedef typename XprScalar<XprType>::type Scalar;\n\n  TensorTernaryExprBlock(const Arg1TensorBlock& arg1_block,\n                         const Arg2TensorBlock& arg2_block,\n                         const Arg3TensorBlock& arg3_block,\n                         const BlockFactory& factory)\n      : m_arg1_block(arg1_block),\n        m_arg2_block(arg2_block),\n        m_arg3_block(arg3_block),\n        m_factory(factory) {}\n\n  TensorBlockKind kind() const { return internal::TensorBlockKind::kExpr; }\n  XprType expr() const {\n    return m_factory.expr(m_arg1_block.expr(), m_arg2_block.expr(),\n                          m_arg3_block.expr());\n  }\n  const Scalar* data() const { return NULL; }\n  void cleanup() {\n    m_arg1_block.cleanup();\n    m_arg2_block.cleanup();\n    m_arg3_block.cleanup();\n  }\n\n private:\n  Arg1TensorBlock m_arg1_block;\n  Arg2TensorBlock m_arg2_block;\n  Arg3TensorBlock m_arg3_block;\n  BlockFactory m_factory;\n};\n\n// -------------------------------------------------------------------------- //\n// StridedLinearBufferCopy provides a method to copy data between two linear\n// buffers with different strides, with optimized paths for scatter/gather.\n\ntemplate <typename Scalar, typename IndexType>\nclass StridedLinearBufferCopy {\n  typedef typename packet_traits<Scalar>::type Packet;\n  enum {\n    Vectorizable = packet_traits<Scalar>::Vectorizable,\n    PacketSize = packet_traits<Scalar>::size\n  };\n\n public:\n  // Specifying linear copy kind statically gives ~30% speedup for small sizes.\n  enum class Kind {\n    Linear = 0,       // src_stride == 1 && dst_stride == 1\n    Scatter = 1,      // src_stride == 1 && dst_stride != 1\n    FillLinear = 2,   // src_stride == 0 && dst_stride == 1\n    FillScatter = 3,  // src_stride == 0 && dst_stride != 1\n    Gather = 4,       // dst_stride == 1\n    Random = 5        // everything else\n  };\n\n  struct Dst {\n    Dst(IndexType o, IndexType s, Scalar* d) : offset(o), stride(s), data(d) {}\n\n    IndexType offset;\n    IndexType stride;\n    Scalar* data;\n  };\n\n  struct Src {\n    Src(IndexType o, IndexType s, const Scalar* d)\n        : offset(o), stride(s), data(d) {}\n\n    IndexType offset;\n    IndexType stride;\n    const Scalar* data;\n  };\n\n  template <typename StridedLinearBufferCopy::Kind kind>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void Run(const Dst& dst,\n                                                        const Src& src,\n                                                        const size_t count) {\n    Run<kind>(count, dst.offset, dst.stride, dst.data, src.offset, src.stride,\n              src.data);\n  }\n\n private:\n  template <typename StridedLinearBufferCopy::Kind kind>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void Run(\n      const IndexType count, const IndexType dst_offset,\n      const IndexType dst_stride, Scalar* EIGEN_RESTRICT dst_data,\n      const IndexType src_offset, const IndexType src_stride,\n      const Scalar* EIGEN_RESTRICT src_data) {\n    const Scalar* src = &src_data[src_offset];\n    Scalar* dst = &dst_data[dst_offset];\n\n    if (!Vectorizable) {\n      for (Index i = 0; i < count; ++i) {\n        dst[i * dst_stride] = src[i * src_stride];\n      }\n      return;\n    }\n\n    const IndexType vectorized_size = count - PacketSize;\n    IndexType i = 0;\n\n    if (kind == StridedLinearBufferCopy::Kind::Linear) {\n      // ******************************************************************** //\n      // Linear copy from `src` to `dst`.\n      const IndexType unrolled_size = count - 4 * PacketSize;\n      eigen_assert(src_stride == 1 && dst_stride == 1);\n      for (; i <= unrolled_size; i += 4 * PacketSize) {\n        for (int j = 0; j < 4; ++j) {\n          Packet p = ploadu<Packet>(src + i + j * PacketSize);\n          pstoreu<Scalar, Packet>(dst + i + j * PacketSize, p);\n        }\n      }\n      for (; i <= vectorized_size; i += PacketSize) {\n        Packet p = ploadu<Packet>(src + i);\n        pstoreu<Scalar, Packet>(dst + i, p);\n      }\n      for (; i < count; ++i) {\n        dst[i] = src[i];\n      }\n      // ******************************************************************** //\n    } else if (kind == StridedLinearBufferCopy::Kind::Scatter) {\n      // Scatter from `src` to `dst`.\n      eigen_assert(src_stride == 1 && dst_stride != 1);\n      for (; i <= vectorized_size; i += PacketSize) {\n        Packet p = ploadu<Packet>(src + i);\n        pscatter<Scalar, Packet>(dst + i * dst_stride, p, dst_stride);\n      }\n      for (; i < count; ++i) {\n        dst[i * dst_stride] = src[i];\n      }\n      // ******************************************************************** //\n    } else if (kind == StridedLinearBufferCopy::Kind::FillLinear) {\n      // Fill `dst` with value at `*src`.\n      eigen_assert(src_stride == 0 && dst_stride == 1);\n      const IndexType unrolled_size = count - 4 * PacketSize;\n      Packet p = pload1<Packet>(src);\n      for (; i <= unrolled_size; i += 4 * PacketSize) {\n        for (int j = 0; j < 4; ++j) {\n          pstoreu<Scalar, Packet>(dst + i + j * PacketSize, p);\n        }\n      }\n      for (; i <= vectorized_size; i += PacketSize) {\n        pstoreu<Scalar, Packet>(dst + i, p);\n      }\n      for (; i < count; ++i) {\n        dst[i] = *src;\n      }\n      // ******************************************************************** //\n    } else if (kind == StridedLinearBufferCopy::Kind::FillScatter) {\n      // Scatter `*src` into `dst`.\n      eigen_assert(src_stride == 0 && dst_stride != 1);\n      Packet p = pload1<Packet>(src);\n      for (; i <= vectorized_size; i += PacketSize) {\n        pscatter<Scalar, Packet>(dst + i * dst_stride, p, dst_stride);\n      }\n      for (; i < count; ++i) {\n        dst[i * dst_stride] = *src;\n      }\n      // ******************************************************************** //\n    } else if (kind == StridedLinearBufferCopy::Kind::Gather) {\n      // Gather from `src` into `dst`.\n      eigen_assert(dst_stride == 1);\n      for (; i <= vectorized_size; i += PacketSize) {\n        Packet p = pgather<Scalar, Packet>(src + i * src_stride, src_stride);\n        pstoreu<Scalar, Packet>(dst + i, p);\n      }\n      for (; i < count; ++i) {\n        dst[i] = src[i * src_stride];\n      }\n      // ******************************************************************** //\n    } else if (kind == StridedLinearBufferCopy::Kind::Random) {\n      // Random.\n      for (; i < count; ++i) {\n        dst[i * dst_stride] = src[i * src_stride];\n      }\n    } else {\n      eigen_assert(false);\n    }\n  }\n};\n\n// -------------------------------------------------------------------------- //\n// TensorBlockIO copies data from `src` tensor block, to the `dst` tensor block.\n// It's possible to specify src->dst dimension mapping for the copy operation.\n// Dimensions of `dst` specify how many elements have to be copied, for the\n// `src` we need to know only stride to navigate through source memory buffer.\n\ntemplate <typename Scalar, typename IndexType, int NumDims, int Layout>\nclass TensorBlockIO {\n  static const bool IsColMajor = (Layout == ColMajor);\n\n  typedef StridedLinearBufferCopy<Scalar, IndexType> LinCopy;\n\n public:\n  typedef DSizes<IndexType, NumDims> Dimensions;\n  typedef DSizes<int, NumDims> DimensionsMap;\n\n  struct Dst {\n    Dst(const Dimensions& dst_dims, const Dimensions& dst_strides, Scalar* dst,\n        IndexType dst_offset = 0)\n        : dims(dst_dims), strides(dst_strides), data(dst), offset(dst_offset) {}\n\n    Dimensions dims;\n    Dimensions strides;\n    Scalar* data;\n    IndexType offset;\n  };\n\n  struct Src {\n    Src(const Dimensions& src_strides, const Scalar* src,\n        IndexType src_offset = 0)\n        : strides(src_strides), data(src), offset(src_offset) {}\n\n    Dimensions strides;\n    const Scalar* data;\n    IndexType offset;\n  };\n\n  // Copies data to `dst` from `src`, using provided dimensions mapping:\n  //\n  //   src_dimension_index = dst_to_src_dim_map[dst_dimension_index]\n  //\n  // Returns the number of copied elements.\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE IndexType Copy(\n      const Dst& dst, const Src& src, const DimensionsMap& dst_to_src_dim_map) {\n    // Copy single scalar value from `src` to `dst`.\n    if (NumDims == 0) {\n      *(dst.data + dst.offset) = *(src.data + src.offset);\n      return 1;\n    }\n\n    // Both `dst` and `src` must have contiguous innermost dimension. We also\n    // accept the special case with stride '0', because it's used as a trick to\n    // implement broadcasting.\n    {\n      int inner_dim = IsColMajor ? 0 : NumDims - 1;\n      EIGEN_UNUSED_VARIABLE(inner_dim);\n      eigen_assert(dst.strides[inner_dim] == 1 || dst.strides[inner_dim] == 0);\n      eigen_assert(src.strides[inner_dim] == 1 || src.strides[inner_dim] == 0);\n    }\n\n    // Give a shorter name to `dst_to_src_dim_map`.\n    const DimensionsMap& dim_map = dst_to_src_dim_map;\n\n    // Do not squeeze reordered inner dimensions.\n    int num_squeezable_dims = NumSqueezableInnerDims(dim_map);\n\n    // NOTE: We find the innermost dimension (contiguous in memory) in the dst\n    // block, and we write data linearly into that dimension, reading it from\n    // the src. If dimensions are reordered, we might end up reading data from\n    // the src with `stride != 1`.\n    //\n    // NOTE: Random-Read/Linear-Write can be up to ~2X faster than\n    // Linear-Read/Random-Write: https://stackoverflow.com/a/54935680\n\n    // Find the innermost dimension in the dst whose size is not 1. This is the\n    // effective inner dim.\n    int num_size_one_inner_dims = 0;\n    for (int i = 0; i < num_squeezable_dims; ++i) {\n      const int dst_dim = IsColMajor ? i : NumDims - i - 1;\n      if (dst.dims[dst_dim] != 1) break;\n      num_size_one_inner_dims++;\n    }\n\n    // If all dimensions are of size 1, just copy a scalar from `src` to `dst`.\n    if (num_size_one_inner_dims == NumDims) {\n      *(dst.data + dst.offset) = *(src.data + src.offset);\n      return 1;\n    }\n\n    // Outermost dimension in the dst with `stride == 1` (contiguous in memory).\n    const int dst_stride1_dim = IsColMajor\n                                    ? num_size_one_inner_dims\n                                    : NumDims - num_size_one_inner_dims - 1;\n\n    // Dimension in the src that corresponds to the dst innermost dimension.\n    const int src_dim_for_dst_stride1_dim =\n        NumDims == 0 ? 1 : dim_map[dst_stride1_dim];\n\n    // Size of the innermost dimension (length of contiguous blocks of memory).\n    IndexType dst_inner_dim_size = NumDims == 0 ? 1 : dst.dims[dst_stride1_dim];\n\n    // Squeeze multiple inner dims into one if they are contiguous in `dst` and\n    // `src` memory, so we can do less linear copy calls.\n    for (int i = num_size_one_inner_dims + 1; i < num_squeezable_dims; ++i) {\n      const int dst_dim = IsColMajor ? i : NumDims - i - 1;\n      const IndexType dst_stride = dst.strides[dst_dim];\n      const IndexType src_stride = src.strides[dim_map[dst_dim]];\n      if (dst_inner_dim_size == dst_stride && dst_stride == src_stride) {\n        dst_inner_dim_size *= dst.dims[dst_dim];\n        ++num_size_one_inner_dims;\n      } else {\n        break;\n      }\n    }\n\n    // Setup strides to read data from `src` and write to `dst`.\n    IndexType input_offset = src.offset;\n    IndexType output_offset = dst.offset;\n    IndexType input_stride =\n        NumDims == 0 ? 1 : src.strides[src_dim_for_dst_stride1_dim];\n    IndexType output_stride = NumDims == 0 ? 1 : dst.strides[dst_stride1_dim];\n\n    const int at_least_1_dim = NumDims <= 1 ? 1 : NumDims - 1;\n    array<BlockIteratorState, at_least_1_dim> it;\n\n    // Initialize block iterator state. Squeeze away any dimension of size 1.\n    int idx = 0;  // currently initialized iterator state index\n    for (int i = num_size_one_inner_dims; i < NumDims - 1; ++i) {\n      const int dst_dim = IsColMajor ? i + 1 : NumDims - i - 2;\n      if (dst.dims[dst_dim] == 1) continue;\n\n      it[idx].size = dst.dims[dst_dim];\n      it[idx].input_stride = src.strides[dim_map[dst_dim]];\n      it[idx].output_stride = dst.strides[dst_dim];\n\n      it[idx].input_span = it[idx].input_stride * (it[idx].size - 1);\n      it[idx].output_span = it[idx].output_stride * (it[idx].size - 1);\n\n      idx++;\n    }\n\n    // Iterate copying data from src to dst.\n    const IndexType block_total_size = NumDims == 0 ? 1 : dst.dims.TotalSize();\n\n#define COPY_INNER_DIM(KIND)                                           \\\n  IndexType num_copied = 0;                                            \\\n  for (num_copied = 0; num_copied < block_total_size;                  \\\n       num_copied += dst_inner_dim_size) {                             \\\n    LinCopy::template Run<KIND>(                                       \\\n        typename LinCopy::Dst(output_offset, output_stride, dst.data), \\\n        typename LinCopy::Src(input_offset, input_stride, src.data),   \\\n        dst_inner_dim_size);                                           \\\n                                                                       \\\n    for (int j = 0; j < idx; ++j) {                                    \\\n      if (++it[j].count < it[j].size) {                                \\\n        input_offset += it[j].input_stride;                            \\\n        output_offset += it[j].output_stride;                          \\\n        break;                                                         \\\n      }                                                                \\\n      it[j].count = 0;                                                 \\\n      input_offset -= it[j].input_span;                                \\\n      output_offset -= it[j].output_span;                              \\\n    }                                                                  \\\n  }                                                                    \\\n  return num_copied;\n\n    if (input_stride == 1 && output_stride == 1) {\n      COPY_INNER_DIM(LinCopy::Kind::Linear);\n    } else if (input_stride == 1 && output_stride != 1) {\n      COPY_INNER_DIM(LinCopy::Kind::Scatter);\n    } else if (input_stride == 0 && output_stride == 1) {\n      COPY_INNER_DIM(LinCopy::Kind::FillLinear);\n    } else if (input_stride == 0 && output_stride != 1) {\n      COPY_INNER_DIM(LinCopy::Kind::FillScatter);\n    } else if (output_stride == 1) {\n      COPY_INNER_DIM(LinCopy::Kind::Gather);\n    } else {\n      COPY_INNER_DIM(LinCopy::Kind::Random);\n    }\n\n#undef COPY_INNER_DIM\n  }\n\n  // Copy from `src` to `dst` with an identity src->dst dimension map. Returns\n  // the number of copied elements.\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE IndexType Copy(const Dst& dst,\n                                                              const Src& src) {\n    DimensionsMap dst_to_src_map;\n    for (int i = 0; i < NumDims; ++i) dst_to_src_map[i] = i;\n    return Copy(dst, src, dst_to_src_map);\n  }\n\n private:\n  struct BlockIteratorState {\n    BlockIteratorState()\n        : size(0),\n          count(0),\n          input_stride(0),\n          output_stride(0),\n          input_span(0),\n          output_span(0) {}\n\n    IndexType size;\n    IndexType count;\n    IndexType input_stride;\n    IndexType output_stride;\n    IndexType input_span;\n    IndexType output_span;\n  };\n\n  // Compute how many inner dimensions it's allowed to squeeze when doing IO\n  // between two tensor blocks. It's safe to squeeze inner dimensions, only\n  // if they are not reordered.\n  static int NumSqueezableInnerDims(const DimensionsMap& dim_map) {\n    int num_squeezable_dims = 0;\n    for (int i = 0; i < NumDims; ++i) {\n      const int dim = IsColMajor ? i : NumDims - i - 1;\n      if (dim_map[dim] != dim) break;\n      num_squeezable_dims++;\n    }\n    return num_squeezable_dims;\n  }\n};\n\n// -------------------------------------------------------------------------- //\n// TensorBlockAssignment assigns a block expression of type `TensorBlockExpr` to\n// a Tensor block defined by `desc`, backed by a memory buffer at `target`.\n//\n// Currently there is no way to write from a Tensor expression to a block of\n// memory, if dimensions are reordered. If you need to do that, you should\n// materialize a Tensor block expression into a memory buffer, and then use\n// TensorBlockIO to copy data between two memory buffers with a custom\n// `target->src` dimension map (see definition above).\n//\n// Also currently the innermost dimension of `target` must have a stride '1'\n// (contiguous in memory). This restriction could be lifted with a `pscatter`,\n// but in practice it's never needed, and there is a similar TensorBlockIO\n// workaround for that.\n//\n// TODO(ezhulenev): TensorBlockAssignment is a special case of TensorBlockIO\n// where `src` is a tensor expression. Explore if it is possible to rewrite IO\n// to use expressions instead of pointers, and after that TensorBlockAssignment\n// will become an alias to IO.\ntemplate <typename Scalar, int NumDims, typename TensorBlockExpr,\n          typename IndexType = Eigen::Index>\nclass TensorBlockAssignment {\n  // We will use coeff/packet path to evaluate block expressions.\n  typedef TensorEvaluator<const TensorBlockExpr, DefaultDevice>\n      TensorBlockEvaluator;\n\n  typedef DSizes<IndexType, NumDims> Dimensions;\n\n  enum {\n    Vectorizable = packet_traits<Scalar>::Vectorizable,\n    PacketSize = packet_traits<Scalar>::size\n  };\n\n  template <bool Vectorizable, typename Evaluator>\n  struct InnerDimAssign {\n    EIGEN_ALWAYS_INLINE static void Run(Scalar* target, IndexType count,\n                                        const Evaluator& eval,\n                                        IndexType eval_offset) {\n      for (IndexType i = 0; i < count; ++i) {\n        target[i] = eval.coeff(eval_offset + i);\n      }\n    }\n  };\n\n  template <typename Evaluator>\n  struct InnerDimAssign<true, Evaluator> {\n    EIGEN_ALWAYS_INLINE static void Run(Scalar* target, IndexType count,\n                                        const Evaluator& eval,\n                                        IndexType eval_offset) {\n      typedef typename packet_traits<Scalar>::type Packet;\n\n      const IndexType unrolled_size = count - 4 * PacketSize;\n      const IndexType vectorized_size = count - PacketSize;\n      IndexType i = 0;\n\n      for (; i <= unrolled_size; i += 4 * PacketSize) {\n        for (int j = 0; j < 4; ++j) {\n          const IndexType idx = eval_offset + i + j * PacketSize;\n          Packet p = eval.template packet<Unaligned>(idx);\n          pstoreu<Scalar>(target + i + j * PacketSize, p);\n        }\n      }\n\n      for (; i <= vectorized_size; i += PacketSize) {\n        Packet p = eval.template packet<Unaligned>(eval_offset + i);\n        pstoreu<Scalar>(target + i, p);\n      }\n\n      for (; i < count; ++i) {\n        target[i] = eval.coeff(eval_offset + i);\n      }\n    }\n  };\n\n public:\n  struct Target {\n    Target(const Dimensions& target_dims, const Dimensions& target_strides,\n           Scalar* target_data, IndexType target_offset = 0)\n        : dims(target_dims),\n          strides(target_strides),\n          data(target_data),\n          offset(target_offset) {}\n\n    Dimensions dims;\n    Dimensions strides;\n    Scalar* data;\n    IndexType offset;\n  };\n\n  static Target target(const Dimensions& target_dims,\n                       const Dimensions& target_strides, Scalar* target_data,\n                       IndexType target_offset = 0) {\n    return Target(target_dims, target_strides, target_data, target_offset);\n  }\n\n  template <typename TargetDimsIndexType, typename TargetStridesIndexType>\n  static Target target(\n      const DSizes<TargetDimsIndexType, NumDims>& target_dims,\n      const DSizes<TargetStridesIndexType, NumDims>& target_strides,\n      Scalar* target_data, IndexType target_offset = 0) {\n    // DSizes constructor will do index type promotion if it's safe.\n    return Target(Dimensions(target_dims), Dimensions(target_strides),\n                  target_data, target_offset);\n  }\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void Run(\n      const Target& target, const TensorBlockExpr& expr) {\n    // Prepare evaluator for block expression.\n    DefaultDevice default_device;\n    TensorBlockEvaluator eval(expr, default_device);\n\n    // Tensor block expression dimension should match destination dimensions.\n    eigen_assert(dimensions_match(target.dims, eval.dimensions()));\n\n    static const int Layout = TensorBlockEvaluator::Layout;\n    static const bool is_col_major = Layout == ColMajor;\n\n    // Initialize output inner dimension size based on a layout.\n    const IndexType output_size = NumDims == 0 ? 1 : target.dims.TotalSize();\n    const int inner_dim_idx = is_col_major ? 0 : NumDims - 1;\n    IndexType output_inner_dim_size = target.dims[inner_dim_idx];\n\n    // Target inner dimension stride must be '1'.\n    eigen_assert(target.strides[inner_dim_idx] == 1);\n\n    // Squeeze multiple inner dims into one if they are contiguous in `target`.\n    IndexType num_squeezed_dims = 0;\n    for (Index i = 1; i < NumDims; ++i) {\n      const Index dim = is_col_major ? i : NumDims - i - 1;\n      const IndexType target_stride = target.strides[dim];\n\n      if (output_inner_dim_size == target_stride) {\n        output_inner_dim_size *= target.dims[dim];\n        num_squeezed_dims++;\n      } else {\n        break;\n      }\n    }\n\n    // Initialize output block iterator state. Dimension in this array are\n    // always in inner_most -> outer_most order (col major layout).\n    array<BlockIteratorState, NumDims> it;\n\n    int idx = 0;  // currently initialized iterator state index\n    for (Index i = num_squeezed_dims; i < NumDims - 1; ++i) {\n      const Index dim = is_col_major ? i + 1 : NumDims - i - 2;\n\n      it[idx].count = 0;\n      it[idx].size = target.dims[dim];\n      it[idx].output_stride = target.strides[dim];\n      it[idx].output_span = it[idx].output_stride * (it[idx].size - 1);\n      idx++;\n    }\n\n    // We read block expression from the beginning, and start writing data to\n    // `target` at given offset.\n    IndexType input_offset = 0;\n    IndexType output_offset = target.offset;\n\n    // Iterate copying data from `eval` to `target`.\n    for (IndexType i = 0; i < output_size; i += output_inner_dim_size) {\n      // Assign to `target` at current offset.\n      InnerDimAssign<Vectorizable && TensorBlockEvaluator::PacketAccess,\n                     TensorBlockEvaluator>::Run(target.data + output_offset,\n                                                output_inner_dim_size, eval,\n                                                input_offset);\n\n      // Move input offset forward by the number of assigned coefficients.\n      input_offset += output_inner_dim_size;\n\n      // Update index.\n      for (int j = 0; j < idx; ++j) {\n        if (++it[j].count < it[j].size) {\n          output_offset += it[j].output_stride;\n          break;\n        }\n        it[j].count = 0;\n        output_offset -= it[j].output_span;\n      }\n    }\n  }\n\n private:\n  struct BlockIteratorState {\n    BlockIteratorState()\n        : count(0), size(0), output_stride(0), output_span(0) {}\n\n    IndexType count;\n    IndexType size;\n    IndexType output_stride;\n    IndexType output_span;\n  };\n};\n\n// -------------------------------------------------------------------------- //\n\n}  // namespace internal\n}  // namespace Eigen\n\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_BLOCK_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBroadcasting.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_BROADCASTING_H\n#define EIGEN_CXX11_TENSOR_TENSOR_BROADCASTING_H\n\nnamespace Eigen {\n\n/** \\class TensorBroadcasting\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor broadcasting class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename Broadcast, typename XprType>\nstruct traits<TensorBroadcastingOp<Broadcast, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename Broadcast, typename XprType>\nstruct eval<TensorBroadcastingOp<Broadcast, XprType>, Eigen::Dense>\n{\n  typedef const TensorBroadcastingOp<Broadcast, XprType> EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename Broadcast, typename XprType>\nstruct nested<TensorBroadcastingOp<Broadcast, XprType>, 1, typename eval<TensorBroadcastingOp<Broadcast, XprType> >::type>\n{\n  typedef TensorBroadcastingOp<Broadcast, XprType> type;\n};\n\ntemplate <typename Dims>\nstruct is_input_scalar {\n  static const bool value = false;\n};\ntemplate <>\nstruct is_input_scalar<Sizes<> > {\n  static const bool value = true;\n};\n#ifndef EIGEN_EMULATE_CXX11_META_H\ntemplate <typename std::ptrdiff_t... Indices>\nstruct is_input_scalar<Sizes<Indices...> > {\n  static const bool value = (Sizes<Indices...>::total_size == 1);\n};\n#endif\n\n}  // end namespace internal\n\n\n\ntemplate<typename Broadcast, typename XprType>\nclass TensorBroadcastingOp : public TensorBase<TensorBroadcastingOp<Broadcast, XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorBroadcastingOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorBroadcastingOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorBroadcastingOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorBroadcastingOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBroadcastingOp(const XprType& expr, const Broadcast& broadcast)\n      : m_xpr(expr), m_broadcast(broadcast) {}\n\n    EIGEN_DEVICE_FUNC\n    const Broadcast& broadcast() const { return m_broadcast; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const Broadcast m_broadcast;\n};\n\n\n// Eval as rvalue\ntemplate<typename Broadcast, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorBroadcastingOp<Broadcast, ArgType>, Device>\n{\n  typedef TensorBroadcastingOp<Broadcast, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename TensorEvaluator<ArgType, Device>::Dimensions InputDimensions;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  protected: //  all the non-static fields must have the same access control, otherwise the TensorEvaluator wont be standard layout;\n  bool isCopy, nByOne, oneByN;\n  public:\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned         = TensorEvaluator<ArgType, Device>::IsAligned,\n    PacketAccess      = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess       = TensorEvaluator<ArgType, Device>::BlockAccess,\n    PreferBlockAccess = true,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    RawAccess         = false\n  };\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  // We do block based broadcasting using a trick with 2x tensor rank and 0\n  // strides. See block method implementation for details.\n  typedef DSizes<Index, 2 * NumDims> BroadcastDimensions;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename TensorEvaluator<const ArgType, Device>::TensorBlock\n      ArgTensorBlock;\n\n  typedef typename internal::TensorMaterializedBlock<ScalarNoConst, NumDims,\n                                                     Layout, Index>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : isCopy(false), nByOne(false), oneByN(false),\n        m_device(device), m_broadcast(op.broadcast()), m_impl(op.expression(), device)\n  {\n\n    // The broadcasting op doesn't change the rank of the tensor. One can't broadcast a scalar\n    // and store the result in a scalar. Instead one should reshape the scalar into a a N-D\n    // tensor with N >= 1 of 1 element first and then broadcast.\n    EIGEN_STATIC_ASSERT((NumDims > 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    const InputDimensions& input_dims = m_impl.dimensions();\n    isCopy = true;\n    for (int i = 0; i < NumDims; ++i) {\n      eigen_assert(input_dims[i] > 0);\n      m_dimensions[i] = input_dims[i] * m_broadcast[i];\n      if (m_broadcast[i] != 1) {\n        isCopy = false;\n      }\n    }\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_inputStrides[0] = 1;\n      m_outputStrides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1];\n        m_outputStrides[i] = m_outputStrides[i-1] * m_dimensions[i-1];\n      }\n    } else {\n      m_inputStrides[NumDims-1] = 1;\n      m_outputStrides[NumDims-1] = 1;\n      for (int i = NumDims-2; i >= 0; --i) {\n        m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1];\n        m_outputStrides[i] = m_outputStrides[i+1] * m_dimensions[i+1];\n      }\n    }\n\n    if (input_dims[0] == 1) {\n      oneByN = true;\n      for (int i = 1; i < NumDims; ++i) {\n        if (m_broadcast[i] != 1) {\n          oneByN = false;\n          break;\n        }\n      }\n    } else if (input_dims[NumDims-1] == 1) {\n      nByOne = true;\n      for (int i = 0; i < NumDims-1; ++i) {\n        if (m_broadcast[i] != 1) {\n          nByOne = false;\n          break;\n        }\n      }\n    }\n\n    // Handle special format like NCHW, its input shape is '[1, N..., 1]' and\n    // broadcast shape is '[N, 1..., N]'\n    if (!oneByN && !nByOne) {\n      if (input_dims[0] == 1 && input_dims[NumDims-1] == 1 && NumDims > 2) {\n        nByOne = true;\n        oneByN = true;\n        for (int i = 1; i < NumDims-1; ++i) {\n          if (m_broadcast[i] != 1) {\n            nByOne = false;\n            oneByN = false;\n            break;\n          }\n        }\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    m_impl.evalSubExprsIfNeededAsync(nullptr, [done](bool) { done(true); });\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE CoeffReturnType coeff(Index index) const\n  {\n    if (internal::is_input_scalar<typename internal::remove_all<InputDimensions>::type>::value) {\n      return m_impl.coeff(0);\n    }\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      if (isCopy) {\n        return m_impl.coeff(index);\n      } else {\n        return coeffColMajor(index);\n      }\n    } else {\n      if (isCopy) {\n        return m_impl.coeff(index);\n      } else {\n        return coeffRowMajor(index);\n      }\n    }\n  }\n\n  // TODO: attempt to speed this up. The integer divisions and modulo are slow\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index indexColMajor(Index index) const {\n    Index inputIndex = 0;\n    EIGEN_UNROLL_LOOP\n    for (int i = NumDims - 1; i > 0; --i) {\n      const Index idx = index / m_outputStrides[i];\n      if (internal::index_statically_eq<Broadcast>(i, 1)) {\n        eigen_assert(idx < m_impl.dimensions()[i]);\n        inputIndex += idx * m_inputStrides[i];\n      } else {\n        if (internal::index_statically_eq<InputDimensions>(i, 1)) {\n          eigen_assert(idx % m_impl.dimensions()[i] == 0);\n        } else {\n          inputIndex += (idx % m_impl.dimensions()[i]) * m_inputStrides[i];\n        }\n      }\n      index -= idx * m_outputStrides[i];\n    }\n    if (internal::index_statically_eq<Broadcast>(0, 1)) {\n      eigen_assert(index < m_impl.dimensions()[0]);\n      inputIndex += index;\n    } else {\n      if (internal::index_statically_eq<InputDimensions>(0, 1)) {\n        eigen_assert(index % m_impl.dimensions()[0] == 0);\n      } else {\n        inputIndex += (index % m_impl.dimensions()[0]);\n      }\n    }\n    return inputIndex;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeffColMajor(Index index) const\n  {\n    return m_impl.coeff(indexColMajor(index));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index indexRowMajor(Index index) const {\n    Index inputIndex = 0;\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < NumDims - 1; ++i) {\n      const Index idx = index / m_outputStrides[i];\n      if (internal::index_statically_eq<Broadcast>(i, 1)) {\n        eigen_assert(idx < m_impl.dimensions()[i]);\n        inputIndex += idx * m_inputStrides[i];\n      } else {\n        if (internal::index_statically_eq<InputDimensions>(i, 1)) {\n          eigen_assert(idx % m_impl.dimensions()[i] == 0);\n        } else {\n          inputIndex += (idx % m_impl.dimensions()[i]) * m_inputStrides[i];\n        }\n      }\n      index -= idx * m_outputStrides[i];\n    }\n    if (internal::index_statically_eq<Broadcast>(NumDims - 1, 1)) {\n      eigen_assert(index < m_impl.dimensions()[NumDims - 1]);\n      inputIndex += index;\n    } else {\n      if (internal::index_statically_eq<InputDimensions>(NumDims - 1, 1)) {\n        eigen_assert(index % m_impl.dimensions()[NumDims - 1] == 0);\n      } else {\n        inputIndex += (index % m_impl.dimensions()[NumDims - 1]);\n      }\n    }\n    return inputIndex;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeffRowMajor(Index index) const\n  {\n    return m_impl.coeff(indexRowMajor(index));\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketReturnType packet(Index index) const\n  {\n    if (internal::is_input_scalar<typename internal::remove_all<InputDimensions>::type>::value) {\n      return internal::pset1<PacketReturnType>(m_impl.coeff(0));\n    }\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      if (isCopy) {\n        #ifdef EIGEN_GPU_COMPILE_PHASE\n        // See PR 437: on NVIDIA P100 and K20m we observed a x3-4 speed up by enforcing\n        // unaligned loads here. The reason is unclear though.\n        return m_impl.template packet<Unaligned>(index);\n        #else\n        return m_impl.template packet<LoadMode>(index);\n        #endif\n      } else if (oneByN && !nByOne) {\n        return packetNByOne<LoadMode>(index);\n      } else if (!oneByN && nByOne) {\n        return packetOneByN<LoadMode>(index);\n      } else if (oneByN && nByOne) {\n        return packetOneByNByOne<LoadMode>(index);\n      } else {\n        return packetColMajor<LoadMode>(index);\n      }\n    } else {\n      if (isCopy) {\n        #ifdef EIGEN_GPU_COMPILE_PHASE\n        // See above.\n        return m_impl.template packet<Unaligned>(index);\n        #else\n        return m_impl.template packet<LoadMode>(index);\n        #endif\n      } else if (oneByN && !nByOne) {\n        return packetOneByN<LoadMode>(index);\n      } else if (!oneByN && nByOne) {\n        return packetNByOne<LoadMode>(index);\n      } else if (oneByN && nByOne) {\n        return packetOneByNByOne<LoadMode>(index);\n      } else {\n        return packetRowMajor<LoadMode>(index);\n      }\n    }\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetOneByNByOne\n  (Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n    Index startDim, endDim;\n    Index inputIndex, outputOffset, batchedIndex;\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      startDim = NumDims - 1;\n      endDim = 1;\n    } else {\n      startDim = 0;\n      endDim = NumDims - 2;\n    }\n\n    batchedIndex = index % m_outputStrides[startDim];\n    inputIndex   = batchedIndex / m_outputStrides[endDim];\n    outputOffset = batchedIndex % m_outputStrides[endDim];\n\n    if (outputOffset + PacketSize <= m_outputStrides[endDim]) {\n      values[0] = m_impl.coeff(inputIndex);\n      return internal::pload1<PacketReturnType>(values);\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0, cur = 0; i < PacketSize; ++i, ++cur) {\n        if (outputOffset + cur < m_outputStrides[endDim]) {\n          values[i] = m_impl.coeff(inputIndex);\n        } else {\n          ++inputIndex;\n          inputIndex = (inputIndex == m_inputStrides[startDim] ? 0 : inputIndex);\n          values[i] = m_impl.coeff(inputIndex);\n          outputOffset = 0;\n          cur = 0;\n        }\n      }\n      return internal::pload<PacketReturnType>(values);\n    }\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetOneByN(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    Index dim, inputIndex;\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      dim = NumDims - 1;\n    } else {\n      dim = 0;\n    }\n\n    inputIndex = index % m_inputStrides[dim];\n    if (inputIndex + PacketSize <= m_inputStrides[dim]) {\n      return m_impl.template packet<Unaligned>(inputIndex);\n    } else {\n      EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < PacketSize; ++i) {\n        if (inputIndex > m_inputStrides[dim]-1) {\n          inputIndex = 0;\n        }\n        values[i] = m_impl.coeff(inputIndex++);\n      }\n      return internal::pload<PacketReturnType>(values);\n    }\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetNByOne(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n    Index dim, inputIndex, outputOffset;\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      dim = 1;\n    } else {\n      dim = NumDims - 2;\n    }\n\n    inputIndex   = index / m_outputStrides[dim];\n    outputOffset = index % m_outputStrides[dim];\n    if (outputOffset + PacketSize <= m_outputStrides[dim]) {\n      values[0] = m_impl.coeff(inputIndex);\n      return internal::pload1<PacketReturnType>(values);\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0, cur = 0; i < PacketSize; ++i, ++cur) {\n        if (outputOffset + cur < m_outputStrides[dim]) {\n          values[i] = m_impl.coeff(inputIndex);\n        } else {\n          values[i] = m_impl.coeff(++inputIndex);\n          outputOffset = 0;\n          cur = 0;\n        }\n      }\n      return internal::pload<PacketReturnType>(values);\n    }\n  }\n\n  // Ignore the LoadMode and always use unaligned loads since we can't guarantee\n  // the alignment at compile time.\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetColMajor(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    const Index originalIndex = index;\n\n    Index inputIndex = 0;\n    EIGEN_UNROLL_LOOP\n    for (int i = NumDims - 1; i > 0; --i) {\n      const Index idx = index / m_outputStrides[i];\n      if (internal::index_statically_eq<Broadcast>(i, 1)) {\n        eigen_assert(idx < m_impl.dimensions()[i]);\n        inputIndex += idx * m_inputStrides[i];\n      } else {\n        if (internal::index_statically_eq<InputDimensions>(i, 1)) {\n          eigen_assert(idx % m_impl.dimensions()[i] == 0);\n        } else {\n          inputIndex += (idx % m_impl.dimensions()[i]) * m_inputStrides[i];\n        }\n      }\n      index -= idx * m_outputStrides[i];\n    }\n    Index innermostLoc;\n    if (internal::index_statically_eq<Broadcast>(0, 1)) {\n      eigen_assert(index < m_impl.dimensions()[0]);\n      innermostLoc = index;\n    } else {\n      if (internal::index_statically_eq<InputDimensions>(0, 1)) {\n        eigen_assert(index % m_impl.dimensions()[0] == 0);\n        innermostLoc = 0;\n      } else {\n        innermostLoc = index % m_impl.dimensions()[0];\n      }\n    }\n    inputIndex += innermostLoc;\n\n    // Todo: this could be extended to the second dimension if we're not\n    // broadcasting alongside the first dimension, and so on.\n    if (innermostLoc + PacketSize <= m_impl.dimensions()[0]) {\n      return m_impl.template packet<Unaligned>(inputIndex);\n    } else {\n      EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n      values[0] = m_impl.coeff(inputIndex);\n      EIGEN_UNROLL_LOOP\n      for (int i = 1; i < PacketSize; ++i) {\n        if (innermostLoc + i < m_impl.dimensions()[0]) {\n          values[i] = m_impl.coeff(inputIndex+i);\n        } else {\n          values[i] = coeffColMajor(originalIndex+i);\n        }\n      }\n      PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n      return rslt;\n    }\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetRowMajor(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    const Index originalIndex = index;\n\n    Index inputIndex = 0;\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < NumDims - 1; ++i) {\n      const Index idx = index / m_outputStrides[i];\n      if (internal::index_statically_eq<Broadcast>(i, 1)) {\n        eigen_assert(idx < m_impl.dimensions()[i]);\n        inputIndex += idx * m_inputStrides[i];\n      } else {\n        if (internal::index_statically_eq<InputDimensions>(i, 1)) {\n          eigen_assert(idx % m_impl.dimensions()[i] == 0);\n        } else {\n          inputIndex += (idx % m_impl.dimensions()[i]) * m_inputStrides[i];\n        }\n      }\n      index -= idx * m_outputStrides[i];\n    }\n    Index innermostLoc;\n    if (internal::index_statically_eq<Broadcast>(NumDims-1, 1)) {\n      eigen_assert(index < m_impl.dimensions()[NumDims-1]);\n      innermostLoc = index;\n    } else {\n      if (internal::index_statically_eq<InputDimensions>(NumDims-1, 1)) {\n        eigen_assert(index % m_impl.dimensions()[NumDims-1] == 0);\n        innermostLoc = 0;\n      } else {\n        innermostLoc = index % m_impl.dimensions()[NumDims-1];\n      }\n    }\n    inputIndex += innermostLoc;\n\n    // Todo: this could be extended to the second dimension if we're not\n    // broadcasting alongside the first dimension, and so on.\n    if (innermostLoc + PacketSize <= m_impl.dimensions()[NumDims-1]) {\n      return m_impl.template packet<Unaligned>(inputIndex);\n    } else {\n      EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n      values[0] = m_impl.coeff(inputIndex);\n      EIGEN_UNROLL_LOOP\n      for (int i = 1; i < PacketSize; ++i) {\n        if (innermostLoc + i < m_impl.dimensions()[NumDims-1]) {\n          values[i] = m_impl.coeff(inputIndex+i);\n        } else {\n          values[i] = coeffRowMajor(originalIndex+i);\n        }\n      }\n      PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n      return rslt;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    double compute_cost = TensorOpCost::AddCost<Index>();\n    if (!isCopy && NumDims > 0) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i > 0; --i) {\n        compute_cost += TensorOpCost::DivCost<Index>();\n        if (internal::index_statically_eq<Broadcast>(i, 1)) {\n          compute_cost +=\n              TensorOpCost::MulCost<Index>() + TensorOpCost::AddCost<Index>();\n        } else {\n          if (!internal::index_statically_eq<InputDimensions>(i, 1)) {\n            compute_cost += TensorOpCost::MulCost<Index>() +\n                            TensorOpCost::ModCost<Index>() +\n                            TensorOpCost::AddCost<Index>();\n          }\n        }\n        compute_cost +=\n            TensorOpCost::MulCost<Index>() + TensorOpCost::AddCost<Index>();\n      }\n    }\n    return m_impl.costPerCoeff(vectorized) +\n           TensorOpCost(0, 0, compute_cost, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    // TODO(wuke): Targeting L1 size is 30% faster than targeting L{-1} on large\n    // tensors. But this might need further tuning.\n    const size_t target_size = m_device.firstLevelCacheSize();\n    return internal::TensorBlockResourceRequirements::merge(\n        m_impl.getResourceRequirements(),\n        internal::TensorBlockResourceRequirements::skewed<Scalar>(target_size));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    BlockBroadcastingParams params = blockBroadcastingParams(desc);\n\n    if (params.inner_dim_size == 0 || params.bcast_dim_size == 0) {\n      return emptyBlock();\n    }\n\n    // Prepare storage for the materialized broadcasting result.\n    const typename TensorBlock::Storage block_storage =\n        TensorBlock::prepareStorage(desc, scratch);\n    ScalarNoConst* materialized_output = block_storage.data();\n\n    // We potentially will need to materialize input blocks.\n    size_t materialized_input_size = 0;\n    ScalarNoConst* materialized_input = NULL;\n\n    // Initialize block broadcating iterator state for outer dimensions (outer\n    // with regard to bcast dimension). Dimension in this array are always in\n    // inner_most -> outer_most order (col major layout).\n    array<BlockBroadcastingIteratorState, NumDims> it;\n    int idx = 0;\n\n    for (int i = params.inner_dim_count + 1; i < NumDims; ++i) {\n      const Index dim = IsColMajor ? i : NumDims - 1 - i;\n      it[idx].size = params.output_dims[dim];\n      it[idx].count = 0;\n      it[idx].output_stride = m_outputStrides[dim];\n      it[idx].output_span = it[idx].output_stride * (it[idx].size - 1);\n      idx++;\n    }\n\n    // Write output into the beginning of `materialized_output`.\n    Index output_offset = 0;\n\n    // We will fill output block by broadcasting along the bcast dim, and\n    // iterating over outer dimension.\n    const Index output_size = NumDims == 0 ? 1 : params.output_dims.TotalSize();\n\n    for (Index num_output_coeffs = 0; num_output_coeffs < output_size;) {\n      ScalarNoConst* bcast_output = materialized_output + num_output_coeffs;\n      Index bcast_offset = desc.offset() + output_offset;\n\n      // Broadcast along the bcast dimension.\n      num_output_coeffs += BroadcastBlockAlongBcastDim(\n          params, bcast_offset, scratch, bcast_output, &materialized_input,\n          &materialized_input_size);\n\n      // Switch to the next outer dimension.\n      for (int j = 0; j < idx; ++j) {\n        if (++it[j].count < it[j].size) {\n          output_offset += it[j].output_stride;\n          break;\n        }\n        it[j].count = 0;\n        output_offset -= it[j].output_span;\n      }\n    }\n\n    return block_storage.AsTensorMaterializedBlock();\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n  const TensorEvaluator<ArgType, Device>& impl() const { return m_impl; }\n\n  Broadcast functor() const { return m_broadcast; }\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(\n      cl::sycl::handler& cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n private:\n  static const bool IsColMajor =\n      static_cast<int>(Layout) == static_cast<int>(ColMajor);\n\n  // We will build a general case block broadcasting on top of broadcasting\n  // primitive that will do broadcasting only for the inner dimension(s) along\n  // the first dimension smaller than the input size (it's called `bcast_dim`).\n  //\n  // Example:\n  //           dim:  0  1  2   (ColMajor)\n  //    input size: [9, 3, 6]\n  //    block size: [9, 2, 6]\n  //\n  // We will compute broadcasted block by iterating over the outer dimensions\n  // before `bcast_dim` (only dimension `2` in this example) and computing\n  // broadcasts along the `bcast_dim` (dimension `1` in this example).\n\n  // BlockBroadcastingParams holds precomputed parameters for broadcasting a\n  // single block along the broadcasting dimension. Sizes and strides along the\n  // `bcast_dim` might be invalid, they will be adjusted later in\n  // `BroadcastBlockAlongBcastDim`.\n  struct BlockBroadcastingParams {\n    Dimensions input_dims;      // input expression dimensions\n    Dimensions output_dims;     // output block sizes\n    Dimensions output_strides;  // output block strides\n\n    int inner_dim_count;   // count inner dimensions matching in size\n    int bcast_dim;         // broadcasting dimension index\n    Index bcast_dim_size;  // broadcasting dimension size\n    Index inner_dim_size;  // inner dimensions size\n\n    // Block sizes and strides for the input block where all dimensions before\n    // `bcast_dim` are equal to `1`.\n    Dimensions input_block_sizes;\n    Dimensions input_block_strides;\n\n    // Block sizes and strides for blocks with extra dimensions and strides `0`.\n    BroadcastDimensions bcast_block_sizes;\n    BroadcastDimensions bcast_block_strides;\n    BroadcastDimensions bcast_input_strides;\n  };\n\n  struct BlockBroadcastingIteratorState {\n    Index size;\n    Index count;\n    Index output_stride;\n    Index output_span;\n  };\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE BlockBroadcastingParams\n  blockBroadcastingParams(TensorBlockDesc& desc) const {\n    BlockBroadcastingParams params;\n\n    params.input_dims = Dimensions(m_impl.dimensions());\n\n    // Output block sizes and strides.\n    params.output_dims = desc.dimensions();\n    params.output_strides = internal::strides<Layout>(params.output_dims);\n\n    // Find the broadcasting dimension (first dimension with output size smaller\n    // that the input size).\n    params.bcast_dim = 0;\n    params.bcast_dim_size = 1;\n    params.inner_dim_size = 1;\n\n    // Count the number of inner dimensions that have the same size in the block\n    // and in the broadcast expression.\n    params.inner_dim_count = 0;\n\n    for (int i = 0; i < NumDims; ++i) {\n      const int dim = IsColMajor ? i : NumDims - i - 1;\n\n      if (params.output_dims[dim] == m_dimensions[dim]) {\n        params.inner_dim_size *= params.output_dims[dim];\n        ++params.inner_dim_count;\n        continue;\n      }\n\n      // First non-matching dimension is the broadcasting dimension.\n      eigen_assert(params.output_dims[dim] < m_dimensions[dim]);\n      params.bcast_dim = dim;\n      params.bcast_dim_size = params.output_dims[dim];\n      break;\n    }\n\n    // Calculate the input block size for looking into the input.\n    for (int i = 0; i < params.inner_dim_count; ++i) {\n      const int dim = IsColMajor ? i : NumDims - i - 1;\n      params.input_block_sizes[dim] = params.input_dims[dim];\n    }\n    for (int i = params.inner_dim_count; i < NumDims; ++i) {\n      const int dim = IsColMajor ? i : NumDims - i - 1;\n      params.input_block_sizes[dim] = 1;\n    }\n    params.input_block_strides =\n        internal::strides<Layout>(params.input_block_sizes);\n\n    // Broadcast with the 0-stride trick: Create 1 extra dim for each\n    // broadcast, set the input stride to 0.\n    //\n    // When ColMajor:\n    //\n    // - bcast_block_sizes:\n    //   [d_0, b_0, d_1, b_1, ...]\n    //\n    // - bcast_block_strides:\n    //   [output_block_strides[0], output_block_strides[0] * d_0,\n    //    output_block_strides[1], output_block_strides[1] * d_1,\n    //   ...]\n    //\n    // - bcast_input_strides:\n    //   [input_block_strides[0], 0,\n    //    input_block_strides[1], 0,\n    //   ...].\n    //\n    for (int i = 0; i < params.inner_dim_count; ++i) {\n      const int dim = IsColMajor ? i : NumDims - i - 1;\n\n      const int copy_dim = IsColMajor ? 2 * i : 2 * NumDims - 2 * i - 1;\n      const int broadcast_dim = IsColMajor ? copy_dim + 1 : copy_dim - 1;\n\n      params.bcast_block_sizes[copy_dim] = params.input_dims[dim];\n      params.bcast_block_sizes[broadcast_dim] = m_broadcast[dim];\n      params.bcast_block_strides[copy_dim] = params.output_strides[dim];\n      params.bcast_block_strides[broadcast_dim] =\n          params.output_strides[dim] * params.input_dims[dim];\n      params.bcast_input_strides[copy_dim] = params.input_block_strides[dim];\n      params.bcast_input_strides[broadcast_dim] = 0;\n    }\n\n    for (int i = 2 * params.inner_dim_count; i < 2 * NumDims; ++i) {\n      const int dim = IsColMajor ? i : 2 * NumDims - i - 1;\n      params.bcast_block_sizes[dim] = 1;\n      params.bcast_block_strides[dim] = 0;\n      params.bcast_input_strides[dim] = 0;\n    }\n\n    return params;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock emptyBlock() const {\n    DSizes<Index, NumDims> dimensions;\n    for (int i = 0; i < NumDims; ++i) dimensions[i] = 0;\n    return TensorBlock(internal::TensorBlockKind::kView, NULL, dimensions);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index BroadcastBlockAlongBcastDim(\n      BlockBroadcastingParams params, Index bcast_offset,\n      TensorBlockScratch& scratch, ScalarNoConst* materialized_output,\n      ScalarNoConst** materialized_input,\n      size_t* materialized_input_size) const {\n    if (params.bcast_dim_size == 1) {\n      // We just need one block read using the ready-set values above.\n      return BroadcastBlock(\n          params.input_block_sizes, params.input_block_strides,\n          params.bcast_block_sizes, params.bcast_block_strides,\n          params.bcast_input_strides, bcast_offset, 0, scratch,\n          materialized_output, materialized_input, materialized_input_size);\n\n    } else if (params.input_dims[params.bcast_dim] == 1) {\n      // Broadcast bcast dimension (< NumDims) by bcast_dim_size.\n      const int broadcast_bcast_dim =\n          IsColMajor ? 2 * params.inner_dim_count + 1\n                     : 2 * NumDims - 2 * params.inner_dim_count - 2;\n\n      params.bcast_block_sizes[broadcast_bcast_dim] = params.bcast_dim_size;\n      params.bcast_input_strides[broadcast_bcast_dim] = 0;\n      params.bcast_block_strides[broadcast_bcast_dim] =\n          params.output_strides[params.bcast_dim];\n\n      return BroadcastBlock(\n          params.input_block_sizes, params.input_block_strides,\n          params.bcast_block_sizes, params.bcast_block_strides,\n          params.bcast_input_strides, bcast_offset, 0, scratch,\n          materialized_output, materialized_input, materialized_input_size);\n\n    } else {\n      // Keep track of the total number of the coefficients written to the\n      // output block.\n      Index num_output_coeffs = 0;\n\n      // The general case. Let's denote the output block as\n      //\n      //   x[..., a:a+bcast_dim_size, :, ..., :]\n      //\n      // where a:a+bcast_dim_size is a slice on the bcast_dim dimension\n      // (< NumDims). We need to split the a:a+bcast_dim_size into possibly 3\n      // sub-blocks:\n      //\n      // (1) a:b, where b is the smallest multiple of\n      //     input_dims[bcast_dim_start] in [a, a+bcast_dim_size].\n      //\n      // (2) b:c, where c is the largest multiple of input_dims[bcast_dim_start]\n      //     in [a, a+bcast_dim_size].\n      //\n      // (3) c:a+bcast_dim_size .\n      //\n      // Or, when b and c do not exist, we just need to process the whole block\n      // together.\n\n      // Find a.\n      const Index bcast_dim_left_index =\n          bcast_offset / m_outputStrides[params.bcast_dim];\n\n      // Find b and c.\n      const Index input_bcast_dim_size = params.input_dims[params.bcast_dim];\n\n      // First multiple after a. This is b when <= bcast_dim_left_index +\n      // bcast_dim_size.\n      const Index first_multiple =\n          divup<Index>(bcast_dim_left_index, input_bcast_dim_size) *\n          input_bcast_dim_size;\n\n      if (first_multiple <= bcast_dim_left_index + params.bcast_dim_size) {\n        // b exists, so does c. Find it.\n        const Index last_multiple =\n            (bcast_dim_left_index + params.bcast_dim_size) /\n            input_bcast_dim_size * input_bcast_dim_size;\n        const int copy_bcast_dim =\n            IsColMajor ? 2 * params.inner_dim_count\n                       : 2 * NumDims - 2 * params.inner_dim_count - 1;\n        const int broadcast_bcast_dim =\n            IsColMajor ? 2 * params.inner_dim_count + 1\n                       : 2 * NumDims - 2 * params.inner_dim_count - 2;\n\n        if (first_multiple > bcast_dim_left_index) {\n          const Index head_size = first_multiple - bcast_dim_left_index;\n          params.input_block_sizes[params.bcast_dim] = head_size;\n          params.bcast_block_sizes[copy_bcast_dim] = head_size;\n          params.bcast_input_strides[copy_bcast_dim] =\n              params.input_block_strides[params.bcast_dim];\n          params.bcast_block_strides[copy_bcast_dim] =\n              params.output_strides[params.bcast_dim];\n          params.bcast_block_sizes[broadcast_bcast_dim] = 1;\n          params.bcast_input_strides[broadcast_bcast_dim] = 0;\n          params.bcast_block_strides[broadcast_bcast_dim] =\n              params.output_strides[params.bcast_dim] *\n              params.input_dims[params.bcast_dim];\n\n          num_output_coeffs += BroadcastBlock(\n              params.input_block_sizes, params.input_block_strides,\n              params.bcast_block_sizes, params.bcast_block_strides,\n              params.bcast_input_strides, bcast_offset, 0, scratch,\n              materialized_output, materialized_input, materialized_input_size);\n        }\n        if (first_multiple < last_multiple) {\n          params.input_block_sizes[params.bcast_dim] = input_bcast_dim_size;\n          params.bcast_block_sizes[copy_bcast_dim] = input_bcast_dim_size;\n          params.bcast_input_strides[copy_bcast_dim] =\n              params.input_block_strides[params.bcast_dim];\n          params.bcast_block_strides[copy_bcast_dim] =\n              params.output_strides[params.bcast_dim];\n          params.bcast_block_sizes[broadcast_bcast_dim] =\n              (last_multiple - first_multiple) / input_bcast_dim_size;\n          params.bcast_input_strides[broadcast_bcast_dim] = 0;\n          params.bcast_block_strides[broadcast_bcast_dim] =\n              params.output_strides[params.bcast_dim] *\n              params.input_dims[params.bcast_dim];\n          const Index offset = (first_multiple - bcast_dim_left_index) *\n                               m_outputStrides[params.bcast_dim];\n\n          num_output_coeffs += BroadcastBlock(\n              params.input_block_sizes, params.input_block_strides,\n              params.bcast_block_sizes, params.bcast_block_strides,\n              params.bcast_input_strides, bcast_offset, offset, scratch,\n              materialized_output, materialized_input, materialized_input_size);\n        }\n        if (last_multiple < bcast_dim_left_index + params.bcast_dim_size) {\n          const Index tail_size =\n              bcast_dim_left_index + params.bcast_dim_size - last_multiple;\n          params.input_block_sizes[params.bcast_dim] = tail_size;\n          params.bcast_block_sizes[copy_bcast_dim] = tail_size;\n          params.bcast_input_strides[copy_bcast_dim] =\n              params.input_block_strides[params.bcast_dim];\n          params.bcast_block_strides[copy_bcast_dim] =\n              params.output_strides[params.bcast_dim];\n          params.bcast_block_sizes[broadcast_bcast_dim] = 1;\n          params.bcast_input_strides[broadcast_bcast_dim] = 0;\n          params.bcast_block_strides[broadcast_bcast_dim] =\n              params.output_strides[params.bcast_dim] *\n              params.input_dims[params.bcast_dim];\n          const Index offset = (last_multiple - bcast_dim_left_index) *\n                               m_outputStrides[params.bcast_dim];\n\n          num_output_coeffs += BroadcastBlock(\n              params.input_block_sizes, params.input_block_strides,\n              params.bcast_block_sizes, params.bcast_block_strides,\n              params.bcast_input_strides, bcast_offset, offset, scratch,\n              materialized_output, materialized_input, materialized_input_size);\n        }\n      } else {\n        // b and c do not exist.\n        const int copy_bcast_dim =\n            IsColMajor ? 2 * params.inner_dim_count\n                       : 2 * NumDims - 2 * params.inner_dim_count - 1;\n        params.input_block_sizes[params.bcast_dim] = params.bcast_dim_size;\n        params.bcast_block_sizes[copy_bcast_dim] = params.bcast_dim_size;\n        params.bcast_input_strides[copy_bcast_dim] =\n            params.input_block_strides[params.bcast_dim];\n        params.bcast_block_strides[copy_bcast_dim] =\n            params.output_strides[params.bcast_dim];\n\n        num_output_coeffs += BroadcastBlock(\n            params.input_block_sizes, params.input_block_strides,\n            params.bcast_block_sizes, params.bcast_block_strides,\n            params.bcast_input_strides, bcast_offset, 0, scratch,\n            materialized_output, materialized_input, materialized_input_size);\n      }\n\n      return num_output_coeffs;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index BroadcastBlock(\n      const Dimensions& input_block_sizes,\n      const Dimensions& input_block_strides,\n      const BroadcastDimensions& bcast_block_sizes,\n      const BroadcastDimensions& bcast_block_strides,\n      const BroadcastDimensions& bcast_input_strides, Index bcast_offset,\n      Index offset, TensorBlockScratch& scratch,\n      ScalarNoConst* materialized_output, ScalarNoConst** materialized_input,\n      size_t* materialized_input_size) const {\n    // ---------------------------------------------------------------------- //\n    // Tensor block descriptor for reading block from the input.\n    const Index input_offset = bcast_offset + offset;\n    TensorBlockDesc input_desc(\n        IsColMajor ? indexColMajor(input_offset) : indexRowMajor(input_offset),\n        input_block_sizes);\n\n    ArgTensorBlock input_block = m_impl.block(input_desc, scratch);\n\n    // ---------------------------------------------------------------------- //\n    // Materialize input block into a temporary memory buffer only if it's not\n    // already available in the arg block.\n    const ScalarNoConst* input_buffer = NULL;\n\n    if (input_block.data() != NULL) {\n      // Input block already has raw data, there is no need to materialize it.\n      input_buffer = input_block.data();\n\n    } else {\n      // Otherwise we have to do block assignment into a temporary buffer.\n\n      // Maybe reuse previously allocated buffer, or allocate a new one with a\n      // scratch allocator.\n      const size_t input_total_size = input_block_sizes.TotalSize();\n      if (*materialized_input == NULL ||\n          *materialized_input_size < input_total_size) {\n        *materialized_input_size = input_total_size;\n        void* mem = scratch.allocate(*materialized_input_size * sizeof(Scalar));\n        *materialized_input = static_cast<ScalarNoConst*>(mem);\n      }\n\n      typedef internal::TensorBlockAssignment<\n          ScalarNoConst, NumDims, typename ArgTensorBlock::XprType, Index>\n          TensorBlockAssignment;\n\n      TensorBlockAssignment::Run(\n          TensorBlockAssignment::target(input_block_sizes, input_block_strides,\n                                        *materialized_input),\n          input_block.expr());\n\n      input_buffer = *materialized_input;\n    }\n\n    // ---------------------------------------------------------------------- //\n    // Copy data from materialized input block to the materialized output, using\n    // given broadcast strides (strides with zeroes).\n    typedef internal::TensorBlockIO<ScalarNoConst, Index, 2 * NumDims, Layout>\n        TensorBlockIO;\n\n    typename TensorBlockIO::Src src(bcast_input_strides, input_buffer);\n    typename TensorBlockIO::Dst dst(bcast_block_sizes, bcast_block_strides,\n                                      materialized_output + offset);\n\n    return TensorBlockIO::Copy(dst, src);\n  }\n\nprotected:\n  const Device EIGEN_DEVICE_REF m_device;\n  const typename internal::remove_reference<Broadcast>::type m_broadcast;\n  Dimensions m_dimensions;\n  array<Index, NumDims> m_outputStrides;\n  array<Index, NumDims> m_inputStrides;\n  TensorEvaluator<ArgType, Device> m_impl;\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_BROADCASTING_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorChipping.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CHIPPING_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CHIPPING_H\n\nnamespace Eigen {\n\n/** \\class TensorKChippingReshaping\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief A chip is a thin slice, corresponding to a column or a row in a 2-d tensor.\n  *\n  *\n  */\n\nnamespace internal {\ntemplate<DenseIndex DimId, typename XprType>\nstruct traits<TensorChippingOp<DimId, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions - 1;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<DenseIndex DimId, typename XprType>\nstruct eval<TensorChippingOp<DimId, XprType>, Eigen::Dense>\n{\n  typedef const TensorChippingOp<DimId, XprType> EIGEN_DEVICE_REF type;\n};\n\ntemplate<DenseIndex DimId, typename XprType>\nstruct nested<TensorChippingOp<DimId, XprType>, 1, typename eval<TensorChippingOp<DimId, XprType> >::type>\n{\n  typedef TensorChippingOp<DimId, XprType> type;\n};\n\ntemplate <DenseIndex DimId>\nstruct DimensionId\n{\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DimensionId(DenseIndex dim) {\n    EIGEN_UNUSED_VARIABLE(dim);\n    eigen_assert(dim == DimId);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex actualDim() const {\n    return DimId;\n  }\n};\ntemplate <>\nstruct DimensionId<Dynamic>\n{\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DimensionId(DenseIndex dim) : actual_dim(dim) {\n    eigen_assert(dim >= 0);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex actualDim() const {\n    return actual_dim;\n  }\n private:\n  const DenseIndex actual_dim;\n};\n\n\n}  // end namespace internal\n\n\n\ntemplate<DenseIndex DimId, typename XprType>\nclass TensorChippingOp : public TensorBase<TensorChippingOp<DimId, XprType> >\n{\n  public:\n    typedef TensorBase<TensorChippingOp<DimId, XprType> > Base;\n    typedef typename Eigen::internal::traits<TensorChippingOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef typename XprType::CoeffReturnType CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorChippingOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorChippingOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorChippingOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorChippingOp(const XprType& expr, const Index offset, const Index dim)\n        : m_xpr(expr), m_offset(offset), m_dim(dim) {\n    }\n\n    EIGEN_DEVICE_FUNC\n    const Index offset() const { return m_offset; }\n    EIGEN_DEVICE_FUNC\n    const Index dim() const { return m_dim.actualDim(); }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(TensorChippingOp)\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const Index m_offset;\n    const internal::DimensionId<DimId> m_dim;\n};\n\n\n// Eval as rvalue\ntemplate<DenseIndex DimId, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorChippingOp<DimId, ArgType>, Device>\n{\n  typedef TensorChippingOp<DimId, ArgType> XprType;\n  static const int NumInputDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  static const int NumDims = NumInputDims-1;\n  typedef typename XprType::Index Index;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    // Alignment can't be guaranteed at compile time since it depends on the\n    // slice offsets.\n    IsAligned         = false,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    PacketAccess      = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess       = TensorEvaluator<ArgType, Device>::BlockAccess,\n    // Chipping of outer-most dimension is a trivial operation, because we can\n    // read and write directly from the underlying tensor using single offset.\n    IsOuterChipping   = (static_cast<int>(Layout) == ColMajor && DimId == NumInputDims - 1) ||\n                        (static_cast<int>(Layout) == RowMajor && DimId == 0),\n    // Chipping inner-most dimension.\n    IsInnerChipping   = (static_cast<int>(Layout) == ColMajor && DimId == 0) ||\n                        (static_cast<int>(Layout) == RowMajor && DimId == NumInputDims - 1),\n    // Prefer block access if the underlying expression prefers it, otherwise\n    // only if chipping is not trivial.\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess ||\n                        !IsOuterChipping,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = false\n  };\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef internal::TensorBlockDescriptor<NumInputDims, Index>\n      ArgTensorBlockDesc;\n  typedef typename TensorEvaluator<const ArgType, Device>::TensorBlock\n      ArgTensorBlock;\n\n  typedef typename internal::TensorMaterializedBlock<ScalarNoConst, NumDims,\n                                                     Layout, Index>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device), m_dim(op.dim()), m_device(device)\n  {\n    EIGEN_STATIC_ASSERT((NumInputDims >= 1), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    eigen_assert(NumInputDims > m_dim.actualDim());\n\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n    eigen_assert(op.offset() < input_dims[m_dim.actualDim()]);\n\n    int j = 0;\n    for (int i = 0; i < NumInputDims; ++i) {\n      if (i != m_dim.actualDim()) {\n        m_dimensions[j] = input_dims[i];\n        ++j;\n      }\n    }\n\n    m_stride = 1;\n    m_inputStride = 1;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = 0; i < m_dim.actualDim(); ++i) {\n        m_stride *= input_dims[i];\n        m_inputStride *= input_dims[i];\n      }\n    } else {\n      for (int i = NumInputDims-1; i > m_dim.actualDim(); --i) {\n        m_stride *= input_dims[i];\n        m_inputStride *= input_dims[i];\n      }\n    }\n    m_inputStride *= input_dims[m_dim.actualDim()];\n    m_inputOffset = m_stride * op.offset();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    return m_impl.coeff(srcCoeff(index));\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    if (isInnerChipping()) {\n      // m_stride is equal to 1, so let's avoid the integer division.\n      eigen_assert(m_stride == 1);\n      Index inputIndex = index * m_inputStride + m_inputOffset;\n      EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < PacketSize; ++i) {\n        values[i] = m_impl.coeff(inputIndex);\n        inputIndex += m_inputStride;\n      }\n      PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n      return rslt;\n    } else if (isOuterChipping()) {\n      // m_stride is always greater than index, so let's avoid the integer division.\n      eigen_assert(m_stride > index);\n      return m_impl.template packet<LoadMode>(index + m_inputOffset);\n    } else {\n      const Index idx = index / m_stride;\n      const Index rem = index - idx * m_stride;\n      if (rem + PacketSize <= m_stride) {\n        Index inputIndex = idx * m_inputStride + m_inputOffset + rem;\n        return m_impl.template packet<LoadMode>(inputIndex);\n      } else {\n        // Cross the stride boundary. Fallback to slow path.\n        EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n       EIGEN_UNROLL_LOOP\n        for (int i = 0; i < PacketSize; ++i) {\n          values[i] = coeff(index);\n          ++index;\n        }\n        PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n        return rslt;\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    double cost = 0;\n    if ((static_cast<int>(Layout) == static_cast<int>(ColMajor) &&\n         m_dim.actualDim() == 0) ||\n        (static_cast<int>(Layout) == static_cast<int>(RowMajor) &&\n         m_dim.actualDim() == NumInputDims - 1)) {\n      cost += TensorOpCost::MulCost<Index>() + TensorOpCost::AddCost<Index>();\n    } else if ((static_cast<int>(Layout) == static_cast<int>(ColMajor) &&\n                m_dim.actualDim() == NumInputDims - 1) ||\n               (static_cast<int>(Layout) == static_cast<int>(RowMajor) &&\n                m_dim.actualDim() == 0)) {\n      cost += TensorOpCost::AddCost<Index>();\n    } else {\n      cost += 3 * TensorOpCost::MulCost<Index>() + TensorOpCost::DivCost<Index>() +\n              3 * TensorOpCost::AddCost<Index>();\n    }\n\n    return m_impl.costPerCoeff(vectorized) +\n           TensorOpCost(0, 0, cost, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    const size_t target_size = m_device.lastLevelCacheSize();\n    return internal::TensorBlockResourceRequirements::merge(\n        internal::TensorBlockResourceRequirements::skewed<Scalar>(target_size),\n        m_impl.getResourceRequirements());\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool root_of_expr_ast = false) const {\n    const Index chip_dim = m_dim.actualDim();\n\n    DSizes<Index, NumInputDims> input_block_dims;\n    for (int i = 0; i < NumInputDims; ++i) {\n      input_block_dims[i]\n            = i < chip_dim ? desc.dimension(i)\n            : i > chip_dim ? desc.dimension(i - 1)\n            : 1;\n    }\n\n    ArgTensorBlockDesc arg_desc(srcCoeff(desc.offset()), input_block_dims);\n\n    // Try to reuse destination buffer for materializing argument block.\n    if (desc.HasDestinationBuffer()) {\n      DSizes<Index, NumInputDims> arg_destination_strides;\n      for (int i = 0; i < NumInputDims; ++i) {\n      arg_destination_strides[i]\n            = i < chip_dim ? desc.destination().strides()[i]\n            : i > chip_dim ? desc.destination().strides()[i - 1]\n            : 0; // for dimensions of size `1` stride should never be used.\n      }\n\n      arg_desc.template AddDestinationBuffer<Layout>(\n          desc.destination().template data<ScalarNoConst>(),\n          arg_destination_strides);\n    }\n\n    ArgTensorBlock arg_block = m_impl.block(arg_desc, scratch, root_of_expr_ast);\n    if (!arg_desc.HasDestinationBuffer()) desc.DropDestinationBuffer();\n\n    if (arg_block.data() != NULL) {\n      // Forward argument block buffer if possible.\n      return TensorBlock(arg_block.kind(), arg_block.data(),\n                           desc.dimensions());\n\n    } else {\n      // Assign argument block expression to a buffer.\n\n      // Prepare storage for the materialized chipping result.\n      const typename TensorBlock::Storage block_storage =\n          TensorBlock::prepareStorage(desc, scratch);\n\n      typedef internal::TensorBlockAssignment<\n          ScalarNoConst, NumInputDims, typename ArgTensorBlock::XprType, Index>\n          TensorBlockAssignment;\n\n      TensorBlockAssignment::Run(\n          TensorBlockAssignment::target(\n              arg_desc.dimensions(),\n              internal::strides<Layout>(arg_desc.dimensions()),\n              block_storage.data()),\n          arg_block.expr());\n\n      return block_storage.AsTensorMaterializedBlock();\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Storage::Type data() const {\n    typename Storage::Type result = constCast(m_impl.data());\n    if (isOuterChipping() && result) {\n      return result + m_inputOffset;\n    } else {\n      return NULL;\n    }\n  }\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n\n protected:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index srcCoeff(Index index) const\n  {\n    Index inputIndex;\n    if (isInnerChipping()) {\n      // m_stride is equal to 1, so let's avoid the integer division.\n      eigen_assert(m_stride == 1);\n      inputIndex = index * m_inputStride + m_inputOffset;\n    } else if (isOuterChipping()) {\n      // m_stride is always greater than index, so let's avoid the integer\n      // division.\n      eigen_assert(m_stride > index);\n      inputIndex = index + m_inputOffset;\n    } else {\n      const Index idx = index / m_stride;\n      inputIndex = idx * m_inputStride + m_inputOffset;\n      index -= idx * m_stride;\n      inputIndex += index;\n    }\n    return inputIndex;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool isInnerChipping() const {\n    return IsInnerChipping ||\n           (static_cast<int>(Layout) == ColMajor && m_dim.actualDim() == 0) ||\n           (static_cast<int>(Layout) == RowMajor && m_dim.actualDim() == NumInputDims - 1);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool isOuterChipping() const {\n    return IsOuterChipping ||\n           (static_cast<int>(Layout) == ColMajor && m_dim.actualDim() == NumInputDims-1) ||\n           (static_cast<int>(Layout) == RowMajor && m_dim.actualDim() == 0);\n  }\n\n  Dimensions m_dimensions;\n  Index m_stride;\n  Index m_inputOffset;\n  Index m_inputStride;\n  TensorEvaluator<ArgType, Device> m_impl;\n  const internal::DimensionId<DimId> m_dim;\n  const Device EIGEN_DEVICE_REF m_device;\n};\n\n\n// Eval as lvalue\ntemplate<DenseIndex DimId, typename ArgType, typename Device>\nstruct TensorEvaluator<TensorChippingOp<DimId, ArgType>, Device>\n  : public TensorEvaluator<const TensorChippingOp<DimId, ArgType>, Device>\n{\n  typedef TensorEvaluator<const TensorChippingOp<DimId, ArgType>, Device> Base;\n  typedef TensorChippingOp<DimId, ArgType> XprType;\n  static const int NumInputDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  static const int NumDims = NumInputDims-1;\n  typedef typename XprType::Index Index;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n\n  enum {\n    IsAligned     = false,\n    PacketAccess  = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess   = TensorEvaluator<ArgType, Device>::RawAccess,\n    Layout        = TensorEvaluator<ArgType, Device>::Layout,\n    RawAccess     = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n    : Base(op, device)\n    { }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index)\n  {\n    return this->m_impl.coeffRef(this->srcCoeff(index));\n  }\n\n  template <int StoreMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void writePacket(Index index, const PacketReturnType& x)\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n\n    if (this->isInnerChipping()) {\n      // m_stride is equal to 1, so let's avoid the integer division.\n      eigen_assert(this->m_stride == 1);\n      EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n      internal::pstore<CoeffReturnType, PacketReturnType>(values, x);\n      Index inputIndex = index * this->m_inputStride + this->m_inputOffset;\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < PacketSize; ++i) {\n        this->m_impl.coeffRef(inputIndex) = values[i];\n        inputIndex += this->m_inputStride;\n      }\n    } else if (this->isOuterChipping()) {\n      // m_stride is always greater than index, so let's avoid the integer division.\n      eigen_assert(this->m_stride > index);\n      this->m_impl.template writePacket<StoreMode>(index + this->m_inputOffset, x);\n    } else {\n      const Index idx = index / this->m_stride;\n      const Index rem = index - idx * this->m_stride;\n      if (rem + PacketSize <= this->m_stride) {\n        const Index inputIndex = idx * this->m_inputStride + this->m_inputOffset + rem;\n        this->m_impl.template writePacket<StoreMode>(inputIndex, x);\n      } else {\n        // Cross stride boundary. Fallback to slow path.\n        EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n        internal::pstore<CoeffReturnType, PacketReturnType>(values, x);\n        EIGEN_UNROLL_LOOP\n        for (int i = 0; i < PacketSize; ++i) {\n          this->coeffRef(index) = values[i];\n          ++index;\n        }\n      }\n    }\n  }\n\n  template <typename TensorBlock>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void writeBlock(\n      const TensorBlockDesc& desc, const TensorBlock& block) {\n    assert(this->m_impl.data() != NULL);\n\n    const Index chip_dim = this->m_dim.actualDim();\n\n    DSizes<Index, NumInputDims> input_block_dims;\n    for (int i = 0; i < NumInputDims; ++i) {\n      input_block_dims[i] = i < chip_dim ? desc.dimension(i)\n                          : i > chip_dim ? desc.dimension(i - 1)\n                          : 1;\n    }\n\n    typedef TensorReshapingOp<const DSizes<Index, NumInputDims>,\n                              const typename TensorBlock::XprType>\n        TensorBlockExpr;\n\n    typedef internal::TensorBlockAssignment<Scalar, NumInputDims,\n                                            TensorBlockExpr, Index>\n        TensorBlockAssign;\n\n    TensorBlockAssign::Run(\n        TensorBlockAssign::target(\n            input_block_dims,\n            internal::strides<Layout>(this->m_impl.dimensions()),\n            this->m_impl.data(), this->srcCoeff(desc.offset())),\n        block.expr().reshape(input_block_dims));\n  }\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_CHIPPING_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConcatenation.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONCATENATION_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CONCATENATION_H\n\nnamespace Eigen {\n\n/** \\class TensorConcatenationOp\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor concatenation class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename Axis, typename LhsXprType, typename RhsXprType>\nstruct traits<TensorConcatenationOp<Axis, LhsXprType, RhsXprType> >\n{\n  // Type promotion to handle the case where the types of the lhs and the rhs are different.\n  typedef typename promote_storage_type<typename LhsXprType::Scalar,\n                                        typename RhsXprType::Scalar>::ret Scalar;\n  typedef typename promote_storage_type<typename traits<LhsXprType>::StorageKind,\n                                        typename traits<RhsXprType>::StorageKind>::ret StorageKind;\n  typedef typename promote_index_type<typename traits<LhsXprType>::Index,\n                                      typename traits<RhsXprType>::Index>::type Index;\n  typedef typename LhsXprType::Nested LhsNested;\n  typedef typename RhsXprType::Nested RhsNested;\n  typedef typename remove_reference<LhsNested>::type _LhsNested;\n  typedef typename remove_reference<RhsNested>::type _RhsNested;\n  static const int NumDimensions = traits<LhsXprType>::NumDimensions;\n  static const int Layout = traits<LhsXprType>::Layout;\n  enum { Flags = 0 };\n  typedef typename conditional<Pointer_type_promotion<typename LhsXprType::Scalar, Scalar>::val,\n                               typename traits<LhsXprType>::PointerType, typename traits<RhsXprType>::PointerType>::type PointerType;\n};\n\ntemplate<typename Axis, typename LhsXprType, typename RhsXprType>\nstruct eval<TensorConcatenationOp<Axis, LhsXprType, RhsXprType>, Eigen::Dense>\n{\n  typedef const TensorConcatenationOp<Axis, LhsXprType, RhsXprType>& type;\n};\n\ntemplate<typename Axis, typename LhsXprType, typename RhsXprType>\nstruct nested<TensorConcatenationOp<Axis, LhsXprType, RhsXprType>, 1, typename eval<TensorConcatenationOp<Axis, LhsXprType, RhsXprType> >::type>\n{\n  typedef TensorConcatenationOp<Axis, LhsXprType, RhsXprType> type;\n};\n\n}  // end namespace internal\n\n\ntemplate<typename Axis, typename LhsXprType, typename RhsXprType>\nclass TensorConcatenationOp : public TensorBase<TensorConcatenationOp<Axis, LhsXprType, RhsXprType>, WriteAccessors>\n{\n  public:\n    typedef TensorBase<TensorConcatenationOp<Axis, LhsXprType, RhsXprType>, WriteAccessors> Base;\n    typedef typename internal::traits<TensorConcatenationOp>::Scalar Scalar;\n    typedef typename internal::traits<TensorConcatenationOp>::StorageKind StorageKind;\n    typedef typename internal::traits<TensorConcatenationOp>::Index Index;\n    typedef typename internal::nested<TensorConcatenationOp>::type Nested;\n    typedef typename internal::promote_storage_type<typename LhsXprType::CoeffReturnType,\n                                                    typename RhsXprType::CoeffReturnType>::ret CoeffReturnType;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorConcatenationOp(const LhsXprType& lhs, const RhsXprType& rhs, Axis axis)\n        : m_lhs_xpr(lhs), m_rhs_xpr(rhs), m_axis(axis) {}\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename LhsXprType::Nested>::type&\n    lhsExpression() const { return m_lhs_xpr; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename RhsXprType::Nested>::type&\n    rhsExpression() const { return m_rhs_xpr; }\n\n    EIGEN_DEVICE_FUNC const Axis& axis() const { return m_axis; }\n\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(TensorConcatenationOp)\n  protected:\n    typename LhsXprType::Nested m_lhs_xpr;\n    typename RhsXprType::Nested m_rhs_xpr;\n    const Axis m_axis;\n};\n\n\n// Eval as rvalue\ntemplate<typename Axis, typename LeftArgType, typename RightArgType, typename Device>\nstruct TensorEvaluator<const TensorConcatenationOp<Axis, LeftArgType, RightArgType>, Device>\n{\n  typedef TensorConcatenationOp<Axis, LeftArgType, RightArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<LeftArgType, Device>::Dimensions>::value;\n  static const int RightNumDims = internal::array_size<typename TensorEvaluator<RightArgType, Device>::Dimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n  enum {\n    IsAligned         = false,\n    PacketAccess      = TensorEvaluator<LeftArgType, Device>::PacketAccess &&\n                        TensorEvaluator<RightArgType, Device>::PacketAccess,\n    BlockAccess       = false,\n    PreferBlockAccess = TensorEvaluator<LeftArgType, Device>::PreferBlockAccess ||\n                        TensorEvaluator<RightArgType, Device>::PreferBlockAccess,\n    Layout            = TensorEvaluator<LeftArgType, Device>::Layout,\n    RawAccess         = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n    : m_leftImpl(op.lhsExpression(), device), m_rightImpl(op.rhsExpression(), device), m_axis(op.axis())\n  {\n    EIGEN_STATIC_ASSERT((static_cast<int>(TensorEvaluator<LeftArgType, Device>::Layout) == static_cast<int>(TensorEvaluator<RightArgType, Device>::Layout) || NumDims == 1), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    EIGEN_STATIC_ASSERT((NumDims == RightNumDims), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    EIGEN_STATIC_ASSERT((NumDims > 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    eigen_assert(0 <= m_axis && m_axis < NumDims);\n    const Dimensions& lhs_dims = m_leftImpl.dimensions();\n    const Dimensions& rhs_dims = m_rightImpl.dimensions();\n    {\n      int i = 0;\n      for (; i < m_axis; ++i) {\n        eigen_assert(lhs_dims[i] > 0);\n        eigen_assert(lhs_dims[i] == rhs_dims[i]);\n        m_dimensions[i] = lhs_dims[i];\n      }\n      eigen_assert(lhs_dims[i] > 0);  // Now i == m_axis.\n      eigen_assert(rhs_dims[i] > 0);\n      m_dimensions[i] = lhs_dims[i] + rhs_dims[i];\n      for (++i; i < NumDims; ++i) {\n        eigen_assert(lhs_dims[i] > 0);\n        eigen_assert(lhs_dims[i] == rhs_dims[i]);\n        m_dimensions[i] = lhs_dims[i];\n      }\n    }\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_leftStrides[0] = 1;\n      m_rightStrides[0] = 1;\n      m_outputStrides[0] = 1;\n\n      for (int j = 1; j < NumDims; ++j) {\n        m_leftStrides[j] = m_leftStrides[j-1] * lhs_dims[j-1];\n        m_rightStrides[j] = m_rightStrides[j-1] * rhs_dims[j-1];\n        m_outputStrides[j] = m_outputStrides[j-1] * m_dimensions[j-1];\n      }\n    } else {\n      m_leftStrides[NumDims - 1] = 1;\n      m_rightStrides[NumDims - 1] = 1;\n      m_outputStrides[NumDims - 1] = 1;\n\n      for (int j = NumDims - 2; j >= 0; --j) {\n        m_leftStrides[j] = m_leftStrides[j+1] * lhs_dims[j+1];\n        m_rightStrides[j] = m_rightStrides[j+1] * rhs_dims[j+1];\n        m_outputStrides[j] = m_outputStrides[j+1] * m_dimensions[j+1];\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  // TODO(phli): Add short-circuit memcpy evaluation if underlying data are linear?\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType)\n  {\n    m_leftImpl.evalSubExprsIfNeeded(NULL);\n    m_rightImpl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n  EIGEN_STRONG_INLINE void cleanup()\n  {\n    m_leftImpl.cleanup();\n    m_rightImpl.cleanup();\n  }\n\n  // TODO(phli): attempt to speed this up. The integer divisions and modulo are slow.\n  // See CL/76180724 comments for more ideas.\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    // Collect dimension-wise indices (subs).\n    array<Index, NumDims> subs;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = NumDims - 1; i > 0; --i) {\n        subs[i] = index / m_outputStrides[i];\n        index -= subs[i] * m_outputStrides[i];\n      }\n      subs[0] = index;\n    } else {\n      for (int i = 0; i < NumDims - 1; ++i) {\n        subs[i] = index / m_outputStrides[i];\n        index -= subs[i] * m_outputStrides[i];\n      }\n      subs[NumDims - 1] = index;\n    }\n\n    const Dimensions& left_dims = m_leftImpl.dimensions();\n    if (subs[m_axis] < left_dims[m_axis]) {\n      Index left_index;\n      if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n        left_index = subs[0];\n        EIGEN_UNROLL_LOOP\n        for (int i = 1; i < NumDims; ++i) {\n          left_index += (subs[i] % left_dims[i]) * m_leftStrides[i];\n        }\n      } else {\n        left_index = subs[NumDims - 1];\n        EIGEN_UNROLL_LOOP\n        for (int i = NumDims - 2; i >= 0; --i) {\n          left_index += (subs[i] % left_dims[i]) * m_leftStrides[i];\n        }\n      }\n      return m_leftImpl.coeff(left_index);\n    } else {\n      subs[m_axis] -= left_dims[m_axis];\n      const Dimensions& right_dims = m_rightImpl.dimensions();\n      Index right_index;\n      if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n        right_index = subs[0];\n        EIGEN_UNROLL_LOOP\n        for (int i = 1; i < NumDims; ++i) {\n          right_index += (subs[i] % right_dims[i]) * m_rightStrides[i];\n        }\n      } else {\n        right_index = subs[NumDims - 1];\n        EIGEN_UNROLL_LOOP\n        for (int i = NumDims - 2; i >= 0; --i) {\n          right_index += (subs[i] % right_dims[i]) * m_rightStrides[i];\n        }\n      }\n      return m_rightImpl.coeff(right_index);\n    }\n  }\n\n  // TODO(phli): Add a real vectorization.\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    const int packetSize = PacketType<CoeffReturnType, Device>::size;\n    EIGEN_STATIC_ASSERT((packetSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index + packetSize - 1 < dimensions().TotalSize());\n\n    EIGEN_ALIGN_MAX CoeffReturnType values[packetSize];\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < packetSize; ++i) {\n      values[i] = coeff(index+i);\n    }\n    PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n    return rslt;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    const double compute_cost = NumDims * (2 * TensorOpCost::AddCost<Index>() +\n                                           2 * TensorOpCost::MulCost<Index>() +\n                                           TensorOpCost::DivCost<Index>() +\n                                           TensorOpCost::ModCost<Index>());\n    const double lhs_size = m_leftImpl.dimensions().TotalSize();\n    const double rhs_size = m_rightImpl.dimensions().TotalSize();\n    return (lhs_size / (lhs_size + rhs_size)) *\n               m_leftImpl.costPerCoeff(vectorized) +\n           (rhs_size / (lhs_size + rhs_size)) *\n               m_rightImpl.costPerCoeff(vectorized) +\n           TensorOpCost(0, 0, compute_cost);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n  #ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_leftImpl.bind(cgh);\n    m_rightImpl.bind(cgh);\n  }\n  #endif\n\n  protected:\n    Dimensions m_dimensions;\n    array<Index, NumDims> m_outputStrides;\n    array<Index, NumDims> m_leftStrides;\n    array<Index, NumDims> m_rightStrides;\n    TensorEvaluator<LeftArgType, Device> m_leftImpl;\n    TensorEvaluator<RightArgType, Device> m_rightImpl;\n    const Axis m_axis;\n};\n\n// Eval as lvalue\ntemplate<typename Axis, typename LeftArgType, typename RightArgType, typename Device>\n  struct TensorEvaluator<TensorConcatenationOp<Axis, LeftArgType, RightArgType>, Device>\n  : public TensorEvaluator<const TensorConcatenationOp<Axis, LeftArgType, RightArgType>, Device>\n{\n  typedef TensorEvaluator<const TensorConcatenationOp<Axis, LeftArgType, RightArgType>, Device> Base;\n  typedef TensorConcatenationOp<Axis, LeftArgType, RightArgType> XprType;\n  typedef typename Base::Dimensions Dimensions;\n  enum {\n    IsAligned         = false,\n    PacketAccess      = TensorEvaluator<LeftArgType, Device>::PacketAccess &&\n                        TensorEvaluator<RightArgType, Device>::PacketAccess,\n    BlockAccess       = false,\n    PreferBlockAccess = TensorEvaluator<LeftArgType, Device>::PreferBlockAccess ||\n                        TensorEvaluator<RightArgType, Device>::PreferBlockAccess,\n    Layout            = TensorEvaluator<LeftArgType, Device>::Layout,\n    RawAccess         = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(XprType& op, const Device& device)\n    : Base(op, device)\n  {\n    EIGEN_STATIC_ASSERT((static_cast<int>(Layout) == static_cast<int>(ColMajor)), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  }\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index)\n  {\n    // Collect dimension-wise indices (subs).\n    array<Index, Base::NumDims> subs;\n    for (int i = Base::NumDims - 1; i > 0; --i) {\n      subs[i] = index / this->m_outputStrides[i];\n      index -= subs[i] * this->m_outputStrides[i];\n    }\n    subs[0] = index;\n\n    const Dimensions& left_dims = this->m_leftImpl.dimensions();\n    if (subs[this->m_axis] < left_dims[this->m_axis]) {\n      Index left_index = subs[0];\n      for (int i = 1; i < Base::NumDims; ++i) {\n        left_index += (subs[i] % left_dims[i]) * this->m_leftStrides[i];\n      }\n      return this->m_leftImpl.coeffRef(left_index);\n    } else {\n      subs[this->m_axis] -= left_dims[this->m_axis];\n      const Dimensions& right_dims = this->m_rightImpl.dimensions();\n      Index right_index = subs[0];\n      for (int i = 1; i < Base::NumDims; ++i) {\n        right_index += (subs[i] % right_dims[i]) * this->m_rightStrides[i];\n      }\n      return this->m_rightImpl.coeffRef(right_index);\n    }\n  }\n\n  template <int StoreMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void writePacket(Index index, const PacketReturnType& x)\n  {\n    const int packetSize = PacketType<CoeffReturnType, Device>::size;\n    EIGEN_STATIC_ASSERT((packetSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index + packetSize - 1 < this->dimensions().TotalSize());\n\n    EIGEN_ALIGN_MAX CoeffReturnType values[packetSize];\n    internal::pstore<CoeffReturnType, PacketReturnType>(values, x);\n    for (int i = 0; i < packetSize; ++i) {\n      coeffRef(index+i) = values[i];\n    }\n  }\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_CONCATENATION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContraction.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_H\n\nnamespace Eigen {\n\n/** \\class TensorContraction\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor contraction class.\n  *\n  *\n  */\nnamespace internal {\n\ntemplate<typename Dimensions, typename LhsXprType, typename RhsXprType, typename OutputKernelType>\nstruct traits<TensorContractionOp<Dimensions, LhsXprType, RhsXprType, OutputKernelType> >\n{\n  // Type promotion to handle the case where the types of the lhs and the rhs are different.\n  typedef typename gebp_traits<typename remove_const<typename LhsXprType::Scalar>::type,\n                               typename remove_const<typename RhsXprType::Scalar>::type>::ResScalar Scalar;\n\n  typedef typename promote_storage_type<typename traits<LhsXprType>::StorageKind,\n                                        typename traits<RhsXprType>::StorageKind>::ret StorageKind;\n  typedef typename promote_index_type<typename traits<LhsXprType>::Index,\n                                      typename traits<RhsXprType>::Index>::type Index;\n  typedef typename LhsXprType::Nested LhsNested;\n  typedef typename RhsXprType::Nested RhsNested;\n  typedef typename remove_reference<LhsNested>::type _LhsNested;\n  typedef typename remove_reference<RhsNested>::type _RhsNested;\n\n  // From NumDims below.\n  static const int NumDimensions = traits<LhsXprType>::NumDimensions + traits<RhsXprType>::NumDimensions - 2 * array_size<Dimensions>::value;\n  static const int Layout = traits<LhsXprType>::Layout;\n  typedef typename conditional<Pointer_type_promotion<typename LhsXprType::Scalar, Scalar>::val,\n                               typename traits<LhsXprType>::PointerType,\n                               typename traits<RhsXprType>::PointerType>::type\n      PointerType;\n\n  enum {\n    Flags = 0\n  };\n};\n\ntemplate<typename Dimensions, typename LhsXprType, typename RhsXprType, typename OutputKernelType>\nstruct eval<TensorContractionOp<Dimensions, LhsXprType, RhsXprType, OutputKernelType>, Eigen::Dense>\n{\n  typedef const TensorContractionOp<Dimensions, LhsXprType, RhsXprType, OutputKernelType>& type;\n};\n\ntemplate<typename Dimensions, typename LhsXprType, typename RhsXprType, typename OutputKernelType>\nstruct nested<TensorContractionOp<Dimensions, LhsXprType, RhsXprType, OutputKernelType>, 1, typename eval<TensorContractionOp<Dimensions, LhsXprType, RhsXprType, OutputKernelType> >::type>\n{\n  typedef TensorContractionOp<Dimensions, LhsXprType, RhsXprType, OutputKernelType> type;\n};\n\ntemplate<typename Indices_, typename LeftArgType_, typename RightArgType_, typename OutputKernelType_, typename Device_>\nstruct traits<TensorEvaluator<const TensorContractionOp<Indices_, LeftArgType_, RightArgType_, OutputKernelType_>, Device_> > {\n  typedef Indices_ Indices;\n  typedef LeftArgType_ LeftArgType;\n  typedef RightArgType_ RightArgType;\n  typedef OutputKernelType_ OutputKernelType;\n  typedef Device_ Device;\n\n  // From NumDims below.\n  static const int NumDimensions = traits<LeftArgType_>::NumDimensions + traits<RightArgType_>::NumDimensions - 2 * array_size<Indices_>::value;\n};\n\n// Helper class to allocate and deallocate temporary memory for packed buffers.\ntemplate <typename LhsScalar, typename RhsScalar>\nstruct TensorContractionBlockMemAllocator {\n  typedef void* BlockMemHandle;\n\n  template <typename Device>\n  EIGEN_DEVICE_FUNC static BlockMemHandle allocate(Device& d, const Index bm,\n                                                   const Index bk,\n                                                   const Index bn,\n                                                   LhsScalar** lhs_block,\n                                                   RhsScalar** rhs_block) {\n    eigen_assert(lhs_block);\n    eigen_assert(rhs_block);\n    BlockSizes sz = ComputeLhsRhsBlockSizes(bm, bk, bn);\n    char* block_mem = static_cast<char*>(d.allocate(sz.lhs_size + sz.rhs_size));\n    eigen_assert(block_mem);\n    *lhs_block = reinterpret_cast<LhsScalar*>(block_mem);\n    *rhs_block = reinterpret_cast<RhsScalar*>(block_mem + sz.lhs_size);\n    return block_mem;\n  }\n\n  template <typename Device>\n  EIGEN_DEVICE_FUNC static BlockMemHandle allocateSlices(\n      Device& d, const Index bm, const Index bk, const Index bn,\n      const Index num_lhs, const Index num_rhs, const Index num_slices,\n      std::vector<LhsScalar*>* lhs_blocks,\n      std::vector<RhsScalar*>* rhs_blocks) {\n    eigen_assert(num_slices > 0);\n    eigen_assert(num_lhs >= 0 && num_rhs >= 0);\n    eigen_assert(num_lhs == 0 || lhs_blocks);\n    eigen_assert(num_rhs == 0 || rhs_blocks);\n    BlockSizes sz = ComputeLhsRhsBlockSizes(bm, bk, bn);\n    void* block_mem = d.allocate(\n        (num_lhs * sz.lhs_size + num_rhs * sz.rhs_size) * num_slices);\n    eigen_assert(block_mem);\n    char* mem = static_cast<char*>(block_mem);\n\n    for (Index x = 0; x < num_slices; x++) {\n      if (num_lhs > 0) lhs_blocks[x].resize(num_lhs);\n      for (Index m = 0; m < num_lhs; m++) {\n        lhs_blocks[x][m] = reinterpret_cast<LhsScalar*>(mem);\n        mem += sz.lhs_size;\n      }\n      if (num_rhs > 0) rhs_blocks[x].resize(num_rhs);\n      for (Index n = 0; n < num_rhs; n++) {\n        rhs_blocks[x][n] = reinterpret_cast<RhsScalar*>(mem);\n        mem += sz.rhs_size;\n      }\n    }\n\n    return block_mem;\n  }\n\n  template <typename Device>\n  EIGEN_DEVICE_FUNC static void deallocate(Device& d, BlockMemHandle handle) {\n    d.deallocate(handle);\n  }\n\n private:\n  struct BlockSizes {\n    Index lhs_size;\n    Index rhs_size;\n  };\n  EIGEN_DEVICE_FUNC static BlockSizes ComputeLhsRhsBlockSizes(const Index bm,\n                                                              const Index bk,\n                                                              const Index bn) {\n    Index align = numext::maxi(EIGEN_MAX_ALIGN_BYTES, 1);\n    BlockSizes sz;\n    sz.lhs_size = divup<Index>(bm * bk * sizeof(LhsScalar), align) * align;\n    sz.rhs_size = divup<Index>(bn * bk * sizeof(RhsScalar), align) * align;\n    return sz;\n  }\n};\n\n// WARNING: In this code we assume that Lhs and Rhs tensor expressions are in\n// ColMajor storage order. This property is guaranteed by the\n// TensorContractionOp evaluator. TensorContractionKernel specifies how we pack\n// blocks of Lhs and Rhs tensor expressions, and how we invoke matrix\n// multiplication for these blocks. Default tensor contraction uses\n// gemm_pack_rhs, gemm_pack_lhs and gebp_kernel from Eigen Core (see\n// GeneralBlocPanelKernel.h for details).\n//\n// By specializing contraction kernels we can use other low level libraries to\n// perform matrix multiplication, and still rely on Eigen contraction evaluator.\n// This also includes full support in TensorContractionThreadPool, assuming that\n// underlying gemm do not use it's own threading.\n//\n// - ResScalar/LhsScalar/RhsScalar - scalar type for the result of\n//   multiplication, lhs tensor and rhs tensor respectively.\n//\n// - StorageIndex - index type for the tensor expressions. In practice almost\n//   always is Eigen::Index.\n//\n// - OutputMapper provides access to the memory of the output matrix. In\n//   practice it's always column major blas_data_mapper (it must be of ResScalar\n//   type).\n//\n// - LhsMapper/RhsMapper similarly to blas_data_mapper provide a two dimensional\n//   view into the Lhs/Rhs tensor expressions. In practice it's\n//   TensorContractionInputMapper, or some specialization of it based on the\n//   type of tensor expression (e.g. TensorImagePatchOp has optimized input\n//   mapper).\ntemplate <typename ResScalar, typename LhsScalar, typename RhsScalar,\n    typename StorageIndex, typename OutputMapper, typename LhsMapper,\n    typename RhsMapper>\nstruct TensorContractionKernel {\n  // True if `invoke()` supports `beta` in `C <- alpha * A * B + beta * C`\n  // (otherwise beta should be always equal to 1).\n  enum { HasBeta = false };\n\n  EIGEN_DEVICE_FUNC\n  TensorContractionKernel(StorageIndex m_, StorageIndex k_, StorageIndex n_,\n                          StorageIndex bm_, StorageIndex bk_, StorageIndex bn_)\n      : m(m_), k(k_), n(n_), bm(bm_), bk(bk_), bn(bn_) {}\n\n  // Pack blocks of Lhs and Rhs into contiguous blocks in memory.\n  typedef LhsScalar* LhsBlock;\n  typedef RhsScalar* RhsBlock;\n\n  // Packed Lhs/Rhs block memory allocator.\n  typedef TensorContractionBlockMemAllocator<LhsScalar, RhsScalar>\n      BlockMemAllocator;\n  typedef typename BlockMemAllocator::BlockMemHandle BlockMemHandle;\n\n  typedef typename internal::gebp_traits<LhsScalar, RhsScalar> Traits;\n\n  typedef internal::gemm_pack_lhs<\n      LhsScalar, StorageIndex, typename LhsMapper::SubMapper, Traits::mr,\n      Traits::LhsProgress, typename Traits::LhsPacket4Packing, ColMajor>\n      LhsPacker;\n\n  typedef internal::gemm_pack_rhs<RhsScalar, StorageIndex,\n                                  typename RhsMapper::SubMapper, Traits::nr,\n                                  ColMajor>\n      RhsPacker;\n\n  typedef internal::gebp_kernel<LhsScalar, RhsScalar, StorageIndex,\n                                OutputMapper, Traits::mr, Traits::nr,\n      /*ConjugateLhs*/ false, /*ConjugateRhs*/ false>\n      GebpKernel;\n\n  template <typename Device>\n  EIGEN_DEVICE_FUNC BlockMemHandle allocate(Device& d, LhsBlock* lhs_block,\n                                            RhsBlock* rhs_block) {\n    return BlockMemAllocator::allocate(d, bm, bk, bn, lhs_block, rhs_block);\n  }\n\n  template <typename Device>\n  EIGEN_DEVICE_FUNC BlockMemHandle allocateSlices(\n      Device& d, const StorageIndex num_lhs, const StorageIndex num_rhs,\n      const StorageIndex num_slices, std::vector<LhsBlock>* lhs_blocks,\n      std::vector<RhsBlock>* rhs_blocks) {\n    return BlockMemAllocator::allocateSlices(\n        d, bm, bk, bn, num_lhs, num_rhs, num_slices, lhs_blocks, rhs_blocks);\n  }\n\n  template <typename Device>\n  EIGEN_DEVICE_FUNC static void deallocate(Device& d, BlockMemHandle handle) {\n    BlockMemAllocator::deallocate(d, handle);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_DONT_INLINE void packLhs(\n      LhsBlock* lhsBlock, const typename LhsMapper::SubMapper& data_mapper,\n      const StorageIndex depth, const StorageIndex rows) {\n    LhsPacker()(*lhsBlock, data_mapper, depth, rows, /*stride*/ 0,\n        /*offset*/ 0);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_DONT_INLINE void packRhs(\n      RhsBlock* rhsBlock, const typename RhsMapper::SubMapper& data_mapper,\n      const StorageIndex depth, const StorageIndex cols) {\n    RhsPacker()(*rhsBlock, data_mapper, depth, cols);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_DONT_INLINE void invoke(\n      const OutputMapper& output_mapper, const LhsBlock& lhsBlock,\n      const RhsBlock& rhsBlock, const StorageIndex rows,\n      const StorageIndex depth, const StorageIndex cols,\n      const ResScalar alpha, const ResScalar beta) {\n    // Default GEBP kernel does not support beta.\n    eigen_assert(beta == ResScalar(1));\n    static const int kComputeStrideFromBlockDimensions = -1;\n    GebpKernel()(output_mapper, lhsBlock, rhsBlock, rows, depth, cols, alpha,\n        /*strideA*/ kComputeStrideFromBlockDimensions,\n        /*strideB*/ kComputeStrideFromBlockDimensions,\n        /*offsetA*/ 0, /*offsetB*/ 0);\n  }\n\n private:\n  // These are dimensions of the original Tensors, and selected block sizes. The\n  // actual block sizes passed to all function above might be smaller because of\n  // the partial blocks at the end.\n  const StorageIndex m;\n  const StorageIndex k;\n  const StorageIndex n;\n  const StorageIndex bm;\n  const StorageIndex bk;\n  const StorageIndex bn;\n};\n\n}  // end namespace internal\n\n// Tensor contraction params that should enable to get from output matrix\n// 2-dimensional coordinates to the output tensor dimensions.\nstruct TensorContractionParams {\n  // TensorContraction evaluator assumes that both tensors are in ColMajor\n  // layout, if tensors are in RowMajor evaluator swap lhs with rhs.\n  bool swapped_arguments;\n};\n\n// Output kernel allows to fuse operations into the tensor contraction.\n//\n// Examples:\n//   1. Elementwise Relu transformation following Conv2D.\n//   2. AddBias to the Conv2D output channels dimension.\n//\n// The NoOpOutputKernel implements an output kernel that does absolutely nothing.\nstruct NoOpOutputKernel {\n  /**\n   * Tensor contraction evaluator calls this kernel after finishing each block\n   * of output matrix. Output blocks belong to the 2-dimensional output tensor.\n   *\n   * TensorContractionParams contains contraction dimensions information\n   * required to map output 2-d space into the expected output tensor space\n   * (potentially higher dimensional).\n   *\n   * \\param[in] output_mapper Access to output tensor memory\n   * \\param[in] params   Tensor contraction parameters\n   * \\param[in] i        Index of a first row available through output_mapper\n   * \\param[in] j        Index of a first column available through output_mapper\n   * \\param[in] num_rows Number of available rows\n   * \\param[in] num_cols Number of available columns\n   */\n  template <typename Index, typename Scalar>\n  EIGEN_ALWAYS_INLINE void operator()(\n      const internal::blas_data_mapper<Scalar, Index, ColMajor>& output_mapper,\n      const TensorContractionParams& params, Index i,\n      Index j, Index num_rows, Index num_cols) const {\n    EIGEN_UNUSED_VARIABLE(output_mapper);\n    EIGEN_UNUSED_VARIABLE(params);\n    EIGEN_UNUSED_VARIABLE(i);\n    EIGEN_UNUSED_VARIABLE(j);\n    EIGEN_UNUSED_VARIABLE(num_rows);\n    EIGEN_UNUSED_VARIABLE(num_cols);\n  }\n};\n\ntemplate<typename Indices, typename LhsXprType, typename RhsXprType, typename OutputKernelType = const NoOpOutputKernel>\nclass TensorContractionOp : public TensorBase<TensorContractionOp<Indices, LhsXprType, RhsXprType, OutputKernelType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorContractionOp>::Scalar Scalar;\n  typedef typename internal::gebp_traits<typename LhsXprType::CoeffReturnType,\n                                         typename RhsXprType::CoeffReturnType>::ResScalar CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorContractionOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorContractionOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorContractionOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorContractionOp(\n      const LhsXprType& lhs, const RhsXprType& rhs, const Indices& dims,\n      const OutputKernelType& output_kernel = OutputKernelType())\n      : m_lhs_xpr(lhs), m_rhs_xpr(rhs), m_indices(dims),\n        m_output_kernel(output_kernel) {}\n\n  EIGEN_DEVICE_FUNC\n  const Indices& indices() const { return m_indices; }\n\n  /** \\returns the nested expressions */\n  EIGEN_DEVICE_FUNC\n  const typename internal::remove_all<typename LhsXprType::Nested>::type&\n  lhsExpression() const { return m_lhs_xpr; }\n\n  EIGEN_DEVICE_FUNC\n  const typename internal::remove_all<typename RhsXprType::Nested>::type&\n  rhsExpression() const { return m_rhs_xpr; }\n\n  EIGEN_DEVICE_FUNC\n  const OutputKernelType& outputKernel() const { return m_output_kernel; }\n\n  protected:\n    typename LhsXprType::Nested m_lhs_xpr;\n    typename RhsXprType::Nested m_rhs_xpr;\n    const Indices m_indices;\n    const OutputKernelType m_output_kernel;\n};\n\n\ntemplate<typename Derived>\nstruct TensorContractionEvaluatorBase : internal::no_assignment_operator\n{\n  typedef typename internal::traits<Derived>::Indices Indices;\n  typedef typename internal::traits<Derived>::LeftArgType LeftArgType;\n  typedef typename internal::traits<Derived>::RightArgType RightArgType;\n  typedef typename internal::traits<Derived>::OutputKernelType OutputKernelType;\n  typedef typename internal::traits<Derived>::Device Device;\n\n  typedef TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType> XprType;\n  typedef typename internal::remove_const<typename XprType::Scalar>::type Scalar;\n  typedef typename XprType::Index Index;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef StorageMemory<Scalar, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned         = true,\n    PacketAccess      = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess       = false,\n    PreferBlockAccess = false,\n    Layout            = TensorEvaluator<LeftArgType, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = true\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  // Most of the code is assuming that both input tensors are ColMajor. If the\n  // inputs are RowMajor, we will \"cheat\" by swapping the LHS and RHS:\n  // If we want to compute A * B = C, where A is LHS and B is RHS, the code\n  // will pretend B is LHS and A is RHS.\n  typedef typename internal::conditional<\n    static_cast<int>(Layout) == static_cast<int>(ColMajor), LeftArgType, RightArgType>::type EvalLeftArgType;\n  typedef typename internal::conditional<\n    static_cast<int>(Layout) == static_cast<int>(ColMajor), RightArgType, LeftArgType>::type EvalRightArgType;\n\n  typedef TensorEvaluator<EvalLeftArgType, Device> LeftEvaluatorType;\n  typedef TensorEvaluator<EvalRightArgType, Device> RightEvaluatorType;\n\n  static const int LDims =\n      internal::array_size<typename TensorEvaluator<EvalLeftArgType, Device>::Dimensions>::value;\n  static const int RDims =\n      internal::array_size<typename TensorEvaluator<EvalRightArgType, Device>::Dimensions>::value;\n  static const int ContractDims = internal::array_size<Indices>::value;\n  static const int NumDims = LDims + RDims - 2 * ContractDims;\n\n  typedef array<Index, ContractDims> contract_t;\n  typedef array<Index, LDims - ContractDims> left_nocontract_t;\n  typedef array<Index, RDims - ContractDims> right_nocontract_t;\n\n  typedef DSizes<Index, NumDims> Dimensions;\n\n  EIGEN_STRONG_INLINE\n  TensorContractionEvaluatorBase(const XprType& op, const Device& device)\n      : m_leftImpl(choose(Cond<static_cast<int>(Layout) == static_cast<int>(ColMajor)>(),\n                          op.lhsExpression(), op.rhsExpression()), device),\n        m_rightImpl(choose(Cond<static_cast<int>(Layout) == static_cast<int>(ColMajor)>(),\n                           op.rhsExpression(), op.lhsExpression()), device),\n        m_device(device),\n        m_output_kernel(op.outputKernel()),\n        m_result(NULL) {\n    EIGEN_STATIC_ASSERT((static_cast<int>(TensorEvaluator<LeftArgType, Device>::Layout) ==\n         static_cast<int>(TensorEvaluator<RightArgType, Device>::Layout)),\n                        YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n\n    DSizes<Index, LDims> eval_left_dims;\n    DSizes<Index, RDims> eval_right_dims;\n    array<IndexPair<Index>, ContractDims> eval_op_indices;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      // For ColMajor, we keep using the existing dimensions\n      for (int i = 0; i < LDims; i++) {\n        eval_left_dims[i] = m_leftImpl.dimensions()[i];\n      }\n      for (int i = 0; i < RDims; i++) {\n        eval_right_dims[i] = m_rightImpl.dimensions()[i];\n      }\n      // We keep the pairs of contracting indices.\n      for (int i = 0; i < ContractDims; i++) {\n        eval_op_indices[i].first = op.indices()[i].first;\n        eval_op_indices[i].second = op.indices()[i].second;\n      }\n    } else {\n      // For RowMajor, we need to reverse the existing dimensions\n      for (int i = 0; i < LDims; i++) {\n        eval_left_dims[i] = m_leftImpl.dimensions()[LDims - i - 1];\n      }\n      for (int i = 0; i < RDims; i++) {\n        eval_right_dims[i] = m_rightImpl.dimensions()[RDims - i - 1];\n      }\n      // We need to flip all the pairs of contracting indices as well as\n      // reversing the dimensions.\n      for (int i = 0; i < ContractDims; i++) {\n        eval_op_indices[i].first = LDims - 1 - op.indices()[ContractDims - 1 - i].second;\n        eval_op_indices[i].second = RDims - 1 - op.indices()[ContractDims - 1 - i].first;\n      }\n    }\n\n    // Check for duplicate axes and make sure the first index in eval_op_indices\n    // is increasing. Using O(n^2) sorting is OK since ContractDims is small\n    for (int i = 0; i < ContractDims; i++) {\n      for (int j = i + 1; j < ContractDims; j++) {\n        eigen_assert(eval_op_indices[j].first != eval_op_indices[i].first &&\n                     eval_op_indices[j].second != eval_op_indices[i].second &&\n                     \"contraction axes should be unique\");\n        if (eval_op_indices[j].first < eval_op_indices[i].first) {\n          numext::swap(eval_op_indices[j], eval_op_indices[i]);\n        }\n      }\n    }\n\n    array<Index, LDims> lhs_strides;\n    lhs_strides[0] = 1;\n    for (int i = 0; i < LDims-1; ++i) {\n      lhs_strides[i+1] = lhs_strides[i] * eval_left_dims[i];\n    }\n\n    array<Index, RDims> rhs_strides;\n    rhs_strides[0] = 1;\n    for (int i = 0; i < RDims-1; ++i) {\n      rhs_strides[i+1] = rhs_strides[i] * eval_right_dims[i];\n    }\n\n    if (m_i_strides.size() > 0) m_i_strides[0] = 1;\n    if (m_j_strides.size() > 0) m_j_strides[0] = 1;\n    if (m_k_strides.size() > 0) m_k_strides[0] = 1;\n\n    m_i_size = 1;\n    m_j_size = 1;\n    m_k_size = 1;\n\n    // To compute the dimension, we simply concatenate the non-contracting\n    // dimensions of the left and then the right tensor. Additionally, we also\n    // compute the strides corresponding to the left non-contracting\n    // dimensions and right non-contracting dimensions.\n    m_lhs_inner_dim_contiguous = true;\n    int dim_idx = 0;\n    Index nocontract_idx = 0;\n\n    for (int i = 0; i < LDims; i++) {\n      // find if we are contracting on index i of left tensor\n      bool contracting = false;\n      for (int j = 0; j < ContractDims; j++) {\n        if (eval_op_indices[j].first == i) {\n          contracting = true;\n          break;\n        }\n      }\n      if (!contracting) {\n        // add dimension size to output dimensions\n        m_dimensions[dim_idx] = eval_left_dims[i];\n        m_left_nocontract_strides[nocontract_idx] = lhs_strides[i];\n        if (dim_idx != i) {\n          m_lhs_inner_dim_contiguous = false;\n        }\n        if (nocontract_idx+1 < internal::array_size<left_nocontract_t>::value) {\n          m_i_strides[nocontract_idx+1] =\n              m_i_strides[nocontract_idx] * eval_left_dims[i];\n        } else {\n          m_i_size = m_i_strides[nocontract_idx] * eval_left_dims[i];\n        }\n        dim_idx++;\n        nocontract_idx++;\n      }\n    }\n\n    nocontract_idx = 0;\n    for (int i = 0; i < RDims; i++) {\n      bool contracting = false;\n      // find if we are contracting on index i of right tensor\n      for (int j = 0; j < ContractDims; j++) {\n        if (eval_op_indices[j].second == i) {\n          contracting = true;\n          break;\n        }\n      }\n      if (!contracting) {\n        m_dimensions[dim_idx] = eval_right_dims[i];\n        if (nocontract_idx+1 < internal::array_size<right_nocontract_t>::value) {\n          m_j_strides[nocontract_idx+1] =\n              m_j_strides[nocontract_idx] * eval_right_dims[i];\n        } else {\n          m_j_size = m_j_strides[nocontract_idx] * eval_right_dims[i];\n        }\n        m_right_nocontract_strides[nocontract_idx] = rhs_strides[i];\n        dim_idx++;\n        nocontract_idx++;\n      }\n    }\n\n    // Now compute the strides corresponding to the contracting dimensions. We\n    // assumed above that non-contracting axes are represented in the same order\n    // in the matrix as they are in the tensor. This is not the case for\n    // contracting axes. As the contracting axes must be of the same size in\n    // each tensor, we'll only look at the first tensor here.\n    m_rhs_inner_dim_contiguous = true;\n    m_rhs_inner_dim_reordered = false;\n    for (int i = 0; i < ContractDims; i++) {\n      Index left = eval_op_indices[i].first;\n      Index right = eval_op_indices[i].second;\n\n      Index size = eval_left_dims[left];\n      eigen_assert(size == eval_right_dims[right] &&\n                   \"Contraction axes must be same size\");\n\n      if (i+1 < static_cast<int>(internal::array_size<contract_t>::value)) {\n        m_k_strides[i+1] = m_k_strides[i] * size;\n      } else {\n        m_k_size = m_k_strides[i] * size;\n      }\n      m_left_contracting_strides[i] = lhs_strides[left];\n      m_right_contracting_strides[i] = rhs_strides[right];\n\n      if (i > 0 && right < eval_op_indices[i-1].second) {\n        m_rhs_inner_dim_reordered = true;\n      }\n      if (right != i) {\n        m_rhs_inner_dim_contiguous = false;\n      }\n    }\n\n    // If the layout is RowMajor, we need to reverse the m_dimensions\n    if (static_cast<int>(Layout) == static_cast<int>(RowMajor)) {\n      for (int i = 0, j = NumDims - 1; i < j; i++, j--) {\n        numext::swap(m_dimensions[i], m_dimensions[j]);\n      }\n    }\n\n    // A set of parameters that will allow output kernel to get from output\n    // tensor dimensions (i, j) into the original tensor dimensions.\n    // TODO(ezhulenev): Add parameters required to infer output tensor index for\n    // more complex contractions than 2x2 on internal dimension.\n    m_tensor_contraction_params.swapped_arguments = static_cast<int>(Layout) == RowMajor;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    m_leftImpl.evalSubExprsIfNeeded(NULL);\n    m_rightImpl.evalSubExprsIfNeeded(NULL);\n    if (data) {\n      evalTo(data);\n      return false;\n    } else {\n      m_result = static_cast<EvaluatorPointerType>(m_device.allocate(dimensions().TotalSize() * sizeof(Scalar)));\n      evalTo(m_result);\n      return true;\n    }\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType dest, EvalSubExprsCallback done) {\n    m_leftImpl.evalSubExprsIfNeededAsync(nullptr, [this, done, dest](bool) {\n      m_rightImpl.evalSubExprsIfNeededAsync(nullptr, [this, done, dest](bool) {\n        if (dest) {\n          evalToAsync(dest, [done]() { done(false); });\n        } else {\n          m_result = static_cast<EvaluatorPointerType>(\n              m_device.allocate(dimensions().TotalSize() * sizeof(Scalar)));\n          evalToAsync(m_result, [done]() { done(true); });\n        }\n      });\n    });\n  }\n#endif  // EIGEN_USE_THREADS\n\n#ifndef TENSOR_CONTRACTION_DISPATCH\n#define TENSOR_CONTRACTION_DISPATCH(METHOD, ALIGNMENT, ARGS) \\\n  if (this->m_lhs_inner_dim_contiguous) {                    \\\n    if (this->m_rhs_inner_dim_contiguous) {                  \\\n      if (this->m_rhs_inner_dim_reordered) {                 \\\n        METHOD<true, true, true, ALIGNMENT> ARGS;            \\\n      } else {                                               \\\n        METHOD<true, true, false, ALIGNMENT> ARGS;           \\\n      }                                                      \\\n    } else {                                                 \\\n      if (this->m_rhs_inner_dim_reordered) {                 \\\n        METHOD<true, false, true, ALIGNMENT> ARGS;           \\\n      } else {                                               \\\n        METHOD<true, false, false, ALIGNMENT> ARGS;          \\\n      }                                                      \\\n    }                                                        \\\n  } else {                                                   \\\n    if (this->m_rhs_inner_dim_contiguous) {                  \\\n      if (this->m_rhs_inner_dim_reordered) {                 \\\n        METHOD<false, true, true, ALIGNMENT> ARGS;           \\\n      } else {                                               \\\n        METHOD<false, true, false, ALIGNMENT> ARGS;          \\\n      }                                                      \\\n    } else {                                                 \\\n      if (this->m_rhs_inner_dim_reordered) {                 \\\n        METHOD<false, false, true, ALIGNMENT> ARGS;          \\\n      } else {                                               \\\n        METHOD<false, false, false, ALIGNMENT> ARGS;         \\\n      }                                                      \\\n    }                                                        \\\n  }\n#endif\n\n#ifndef TENSOR_CONTRACTION_ASYNC_DISPATCH\n#define TENSOR_CONTRACTION_ASYNC_DISPATCH(METHOD, DONE, ALIGNMENT, ARGS, FN) \\\n  if (this->m_lhs_inner_dim_contiguous) {                                    \\\n    if (this->m_rhs_inner_dim_contiguous) {                                  \\\n      if (this->m_rhs_inner_dim_reordered) {                                 \\\n        (new METHOD<DONE, true, true, true, ALIGNMENT> ARGS)->FN;            \\\n      } else {                                                               \\\n        (new METHOD<DONE, true, true, false, ALIGNMENT> ARGS)->FN;           \\\n      }                                                                      \\\n    } else {                                                                 \\\n      if (this->m_rhs_inner_dim_reordered) {                                 \\\n        (new METHOD<DONE, true, false, true, ALIGNMENT> ARGS)->FN;           \\\n      } else {                                                               \\\n        (new METHOD<DONE, true, false, false, ALIGNMENT> ARGS)->FN;          \\\n      }                                                                      \\\n    }                                                                        \\\n  } else {                                                                   \\\n    if (this->m_rhs_inner_dim_contiguous) {                                  \\\n      if (this->m_rhs_inner_dim_reordered) {                                 \\\n        (new METHOD<DONE, false, true, true, ALIGNMENT> ARGS)->FN;           \\\n      } else {                                                               \\\n        (new METHOD<DONE, false, true, false, ALIGNMENT> ARGS)->FN;          \\\n      }                                                                      \\\n    } else {                                                                 \\\n      if (this->m_rhs_inner_dim_reordered) {                                 \\\n        (new METHOD<DONE, false, false, true, ALIGNMENT> ARGS)->FN;          \\\n      } else {                                                               \\\n        (new METHOD<DONE, false, false, false, ALIGNMENT> ARGS)->FN;         \\\n      }                                                                      \\\n    }                                                                        \\\n  }\n#endif\n\n  EIGEN_DEVICE_FUNC void evalTo(Scalar* buffer) const {\n   static_cast<const Derived*>(this)->template evalProduct<Unaligned>(buffer);\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalToCallback>\n  void evalToAsync(Scalar* buffer, EvalToCallback done) const {\n    static_cast<const Derived*>(this)\n        ->template evalProductAsync<EvalToCallback, Unaligned>(buffer,\n                                                               std::move(done));\n  }\n#endif  // EIGEN_USE_THREADS\n\n  template <bool lhs_inner_dim_contiguous, bool rhs_inner_dim_contiguous,\n            bool rhs_inner_dim_reordered, int Alignment>\n  void evalProductSequential(Scalar* buffer) const {\n    if (this->m_j_size == 1) {\n      this->template evalGemv<lhs_inner_dim_contiguous,\n                              rhs_inner_dim_contiguous, rhs_inner_dim_reordered,\n                              Alignment>(buffer);\n    } else {\n      this->template evalGemm<lhs_inner_dim_contiguous, rhs_inner_dim_contiguous,\n                              rhs_inner_dim_reordered, Alignment>(buffer);\n    }\n  }\n\n  template <bool lhs_inner_dim_contiguous, bool rhs_inner_dim_contiguous, bool rhs_inner_dim_reordered, int Alignment>\n  #if !defined(EIGEN_HIPCC)\n  EIGEN_DEVICE_FUNC\n  #endif\n  void evalGemv(Scalar* buffer) const {\n    const Index rows = m_i_size;\n    const Index cols = m_k_size;\n\n    typedef typename internal::remove_const<typename EvalLeftArgType::Scalar>::type LhsScalar;\n    typedef typename internal::remove_const<typename EvalRightArgType::Scalar>::type RhsScalar;\n    typedef TensorEvaluator<EvalLeftArgType, Device> LeftEvaluator;\n    typedef TensorEvaluator<EvalRightArgType, Device> RightEvaluator;\n    const Index lhs_packet_size = internal::unpacket_traits<typename LeftEvaluator::PacketReturnType>::size;\n    const Index rhs_packet_size = internal::unpacket_traits<typename RightEvaluator::PacketReturnType>::size;\n    const int lhs_alignment = LeftEvaluator::IsAligned ? Aligned : Unaligned;\n    const int rhs_alignment = RightEvaluator::IsAligned ? Aligned : Unaligned;\n    typedef internal::TensorContractionInputMapper<LhsScalar, Index, internal::Lhs,\n                                                   LeftEvaluator, left_nocontract_t,\n                                                   contract_t, lhs_packet_size,\n                                                   lhs_inner_dim_contiguous,\n                                                   false, lhs_alignment> LhsMapper;\n\n    typedef internal::TensorContractionInputMapper<RhsScalar, Index, internal::Rhs,\n                                                   RightEvaluator, right_nocontract_t,\n                                                   contract_t, rhs_packet_size,\n                                                   rhs_inner_dim_contiguous,\n                                                   rhs_inner_dim_reordered, rhs_alignment> RhsMapper;\n\n    LhsMapper lhs(m_leftImpl, m_left_nocontract_strides, m_i_strides,\n                  m_left_contracting_strides, m_k_strides);\n    RhsMapper rhs(m_rightImpl, m_right_nocontract_strides, m_j_strides,\n                  m_right_contracting_strides, m_k_strides);\n\n    const Scalar alpha(1);\n    const Index resIncr(1);\n\n    // zero out the result buffer (which must be of size at least rows * sizeof(Scalar)\n    m_device.fill(buffer, buffer + rows, Scalar(0));\n\n    internal::general_matrix_vector_product<Index,LhsScalar,LhsMapper,ColMajor,false,RhsScalar,RhsMapper,false>::run(\n        rows, cols, lhs, rhs,\n        buffer, resIncr, alpha);\n\n    typedef internal::blas_data_mapper<Scalar, Index, ColMajor> OutputMapper;\n    m_output_kernel(OutputMapper(buffer, rows), m_tensor_contraction_params,\n                    static_cast<Index>(0), static_cast<Index>(0), rows,\n                    static_cast<Index>(1));\n  }\n\n  template <bool lhs_inner_dim_contiguous, bool rhs_inner_dim_contiguous, bool rhs_inner_dim_reordered, int Alignment>\n  #if !defined(EIGEN_HIPCC)\n  EIGEN_DEVICE_FUNC\n  #endif\n  void evalGemm(Scalar* buffer) const {\n    // columns in left side, rows in right side\n    const Index k = this->m_k_size;\n    this->template evalGemmPartial<lhs_inner_dim_contiguous,\n                                   rhs_inner_dim_contiguous,\n                                   rhs_inner_dim_reordered,\n                                   Alignment, true>(buffer, 0, k, 1);\n  }\n\n  template <bool lhs_inner_dim_contiguous, bool rhs_inner_dim_contiguous,\n      bool rhs_inner_dim_reordered, int Alignment>\n  EIGEN_DEVICE_FUNC void evalGemmPartialWithoutOutputKernel(\n      Scalar* buffer, Index k_start, Index k_end, int num_threads) const {\n    evalGemmPartial<lhs_inner_dim_contiguous, rhs_inner_dim_contiguous,\n                    rhs_inner_dim_reordered, Alignment,\n        /*use_output_kernel*/ false>(buffer, k_start, k_end,\n                                     num_threads);\n  }\n\n  template <bool lhs_inner_dim_contiguous, bool rhs_inner_dim_contiguous, bool rhs_inner_dim_reordered, int Alignment, bool use_output_kernel>\n  EIGEN_DEVICE_FUNC void evalGemmPartial(Scalar* buffer, Index k_start, Index k_end, int num_threads) const {\n    eigen_assert(k_end >= k_start && k_start >= 0 && k_end <= this->m_k_size);\n    // columns in slice on left side, rows on right side\n    const Index k_slice = k_end - k_start;\n\n    // rows in left side\n    const Index m = this->m_i_size;\n\n    // columns in right side\n    const Index n = this->m_j_size;\n\n    // define data mappers for Lhs and Rhs\n    typedef typename internal::remove_const<typename EvalLeftArgType::Scalar>::type LhsScalar;\n    typedef typename internal::remove_const<typename EvalRightArgType::Scalar>::type RhsScalar;\n\n    typedef TensorEvaluator<EvalLeftArgType, Device> LeftEvaluator;\n    typedef TensorEvaluator<EvalRightArgType, Device> RightEvaluator;\n\n    const Index lhs_packet_size = internal::unpacket_traits<typename LeftEvaluator::PacketReturnType>::size;\n    const Index rhs_packet_size = internal::unpacket_traits<typename RightEvaluator::PacketReturnType>::size;\n\n    typedef internal::TensorContractionInputMapper<LhsScalar, Index, internal::Lhs,\n                                                   LeftEvaluator, left_nocontract_t,\n                                                   contract_t, lhs_packet_size,\n                                                   lhs_inner_dim_contiguous,\n                                                   false, Unaligned> LhsMapper;\n\n    typedef internal::TensorContractionInputMapper<RhsScalar, Index, internal::Rhs,\n                                                   RightEvaluator, right_nocontract_t,\n                                                   contract_t, rhs_packet_size,\n                                                   rhs_inner_dim_contiguous,\n                                                   rhs_inner_dim_reordered, Unaligned> RhsMapper;\n\n    typedef internal::blas_data_mapper<Scalar, Index, ColMajor> OutputMapper;\n\n    typedef internal::TensorContractionKernel<\n        Scalar, LhsScalar, RhsScalar, Index, OutputMapper, LhsMapper, RhsMapper>\n        TensorContractionKernel;\n\n    // initialize data mappers\n    LhsMapper lhs(this->m_leftImpl, this->m_left_nocontract_strides, this->m_i_strides,\n                  this->m_left_contracting_strides, this->m_k_strides);\n\n    RhsMapper rhs(this->m_rightImpl, this->m_right_nocontract_strides, this->m_j_strides,\n                  this->m_right_contracting_strides, this->m_k_strides);\n\n    OutputMapper output(buffer, m);\n\n    // Sizes of the blocks to load in cache. See the Goto paper for details.\n    internal::TensorContractionBlocking<Scalar, LhsScalar, RhsScalar,\n                                        Index, internal::ShardByCol>\n        blocking(k_slice, m, n, num_threads);\n    const Index kc = blocking.kc();\n    const Index mc = numext::mini(m, blocking.mc());\n    const Index nc = numext::mini(n, blocking.nc());\n\n    typedef typename TensorContractionKernel::LhsBlock LhsBlock;\n    typedef typename TensorContractionKernel::RhsBlock RhsBlock;\n\n    LhsBlock blockA;\n    RhsBlock blockB;\n\n    TensorContractionKernel kernel(m, k_slice, n, mc, kc, nc);\n\n    typedef typename TensorContractionKernel::BlockMemHandle BlockMemHandle;\n    const BlockMemHandle packed_mem =\n        kernel.allocate(this->m_device, &blockA, &blockB);\n\n    // If a contraction kernel does not support beta, explicitly initialize\n    // output buffer with zeroes.\n    if (!TensorContractionKernel::HasBeta) {\n      this->m_device.fill(buffer, buffer + m * n, Scalar(0));\n    }\n\n    for(Index i2=0; i2<m; i2+=mc)\n    {\n      const Index actual_mc = numext::mini(i2+mc,m)-i2;\n      for (Index k2 = k_start; k2 < k_end; k2 += kc) {\n        // make sure we don't overshoot right edge of left matrix, then pack vertical panel\n        const Index actual_kc = numext::mini(k2 + kc, k_end) - k2;\n        kernel.packLhs(&blockA, lhs.getSubMapper(i2, k2), actual_kc, actual_mc);\n\n        // If kernel supports beta, there is no need to initialize output\n        // buffer with zeroes.\n        const Scalar alpha = Scalar(1);\n        const Scalar beta = (TensorContractionKernel::HasBeta && k2 == k_start)\n                                ? Scalar(0)\n                                : Scalar(1);\n\n        // series of horizontal blocks\n        for (Index j2 = 0; j2 < n; j2 += nc) {\n          // make sure we don't overshoot right edge of right matrix, then pack block\n          const Index actual_nc = numext::mini(j2 + nc, n) - j2;\n          kernel.packRhs(&blockB, rhs.getSubMapper(k2, j2), actual_kc,\n                         actual_nc);\n\n          // call gebp (matrix kernel)\n          // The parameters here are copied from Eigen's GEMM implementation\n          const OutputMapper output_mapper = output.getSubMapper(i2, j2);\n          kernel.invoke(output_mapper, blockA, blockB, actual_mc, actual_kc,\n                        actual_nc, alpha, beta);\n\n          // We are done with this [i2, j2] output block.\n          if (use_output_kernel && k2 + kc >= k_end) {\n            m_output_kernel(output_mapper, m_tensor_contraction_params, i2, j2,\n                            actual_mc, actual_nc);\n          }\n        }\n      }\n    }\n\n    kernel.deallocate(this->m_device, packed_mem);\n  }\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_leftImpl.cleanup();\n    m_rightImpl.cleanup();\n\n    if (m_result != NULL) {\n      m_device.deallocate(m_result);\n      m_result = NULL;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const {\n    return m_result[index];\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool) const {\n    return TensorOpCost(sizeof(CoeffReturnType), 0, 0);\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const {\n    return internal::ploadt<PacketReturnType, LoadMode>(m_result + index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EvaluatorPointerType data() const { return m_result; }\n\nprotected:\n  Dimensions m_dimensions;\n\n  contract_t m_k_strides;\n  contract_t m_left_contracting_strides;\n  contract_t m_right_contracting_strides;\n\n  bool m_lhs_inner_dim_contiguous;\n  bool m_rhs_inner_dim_contiguous;\n  bool m_rhs_inner_dim_reordered;\n\n  left_nocontract_t m_i_strides;\n  right_nocontract_t m_j_strides;\n  left_nocontract_t m_left_nocontract_strides;\n  right_nocontract_t m_right_nocontract_strides;\n\n  Index m_i_size;\n  Index m_j_size;\n  Index m_k_size;\n\n  TensorContractionParams m_tensor_contraction_params;\n\n  TensorEvaluator<EvalLeftArgType, Device> m_leftImpl;\n  TensorEvaluator<EvalRightArgType, Device> m_rightImpl;\n  const Device EIGEN_DEVICE_REF m_device;\n  OutputKernelType m_output_kernel;\n  EvaluatorPointerType m_result;\n};\n\n\n// evaluator for default device\ntemplate<typename Indices, typename LeftArgType, typename RightArgType, typename OutputKernelType, typename Device>\nstruct TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, Device> :\n    public TensorContractionEvaluatorBase<\n      TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, Device> > {\n  typedef TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, Device> Self;\n  typedef TensorContractionEvaluatorBase<Self> Base;\n\n  typedef TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType> XprType;\n  typedef typename internal::remove_const<typename XprType::Scalar>::type Scalar;\n  typedef typename XprType::Index Index;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n\n  enum {\n    Layout = TensorEvaluator<LeftArgType, Device>::Layout\n  };\n\n  // Most of the code is assuming that both input tensors are ColMajor. If the\n  // inputs are RowMajor, we will \"cheat\" by swapping the LHS and RHS:\n  // If we want to compute A * B = C, where A is LHS and B is RHS, the code\n  // will pretend B is LHS and A is RHS.\n  typedef typename internal::conditional<\n    static_cast<int>(Layout) == static_cast<int>(ColMajor), LeftArgType, RightArgType>::type EvalLeftArgType;\n  typedef typename internal::conditional<\n    static_cast<int>(Layout) == static_cast<int>(ColMajor), RightArgType, LeftArgType>::type EvalRightArgType;\n\n  static const int LDims =\n      internal::array_size<typename TensorEvaluator<EvalLeftArgType, Device>::Dimensions>::value;\n  static const int RDims =\n      internal::array_size<typename TensorEvaluator<EvalRightArgType, Device>::Dimensions>::value;\n  static const int ContractDims = internal::array_size<Indices>::value;\n\n  typedef array<Index, ContractDims> contract_t;\n  typedef array<Index, LDims - ContractDims> left_nocontract_t;\n  typedef array<Index, RDims - ContractDims> right_nocontract_t;\n\n  static const int NumDims = LDims + RDims - 2 * ContractDims;\n\n  // Could we use NumDimensions here?\n  typedef DSizes<Index, NumDims> Dimensions;\n\n  TensorEvaluator(const XprType& op, const Device& device) :\n      Base(op, device) { }\n\n  template <int Alignment>\n  void evalProduct(Scalar* buffer) const {\n    TENSOR_CONTRACTION_DISPATCH(this->template evalProductSequential, Alignment, (buffer));\n  }\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionBlocking.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_BLOCKING_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_BLOCKING_H\n\n\nnamespace Eigen {\nnamespace internal {\n\nenum {\n  ShardByRow = 0,\n  ShardByCol = 1\n};\n\n\n// Default Blocking Strategy\ntemplate<typename ResScalar, typename LhsScalar, typename RhsScalar, typename StorageIndex, int ShardingType = ShardByCol>\nclass TensorContractionBlocking {\n public:\n\n /*\n   adding EIGEN_DEVICE_FUNC unconditionally to 'TensorContractionBlocking' constructor in `TensorContractionBlocking.h`\n     requires adding EIGEN_DEVICE_FUNC to `computeProductBlockingSizes` in `GeneralBlockPanelKernel.h`\n     which in turn, requires adding EIGEN_DEVICE_FUNC to `evaluateProductBlockingSizesHeuristic` in `GeneralBlockPanelKernel.h`\n     which in turn, requires adding EIGEN_DEVICE_FUNC to `manage_caching_sizes` in `GeneralBlockPanelKernel.h`\n     (else HIPCC will error out)\n\n   However adding EIGEN_DEVICE_FUNC to `manage_caching_sizes` in `GeneralBlockPanelKernel.h`\n   results in NVCC erroring out with the following error\n\n   ../Eigen/src/Core/products/GeneralBlockPanelKernel.h(57): error #2901:\n      dynamic initialization is not supported for function-scope static variables within a __device__/__global__ function\n */\n\n  #if !defined(EIGEN_HIPCC)\n  EIGEN_DEVICE_FUNC\n  #endif\n TensorContractionBlocking(StorageIndex k, StorageIndex m, StorageIndex n, StorageIndex num_threads = 1) :\n      kc_(k), mc_(m), nc_(n)\n  {\n    if (ShardingType == ShardByCol) {\n      computeProductBlockingSizes<LhsScalar, RhsScalar, 1>(kc_, mc_, nc_, num_threads);\n    }\n    else {\n      computeProductBlockingSizes<LhsScalar, RhsScalar, 1>(kc_, nc_, mc_, num_threads);\n    }\n\n    const int rhs_packet_size = internal::packet_traits<RhsScalar>::size;\n    kc_ = (rhs_packet_size <= 8 || kc_ <= rhs_packet_size) ?\n      kc_ : (kc_ / rhs_packet_size) * rhs_packet_size;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE StorageIndex kc() const { return kc_; }\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE StorageIndex mc() const { return mc_; }\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE StorageIndex nc() const { return nc_; }\n\n private:\n  StorageIndex kc_;\n  StorageIndex mc_;\n  StorageIndex nc_;\n};\n\n} // end namespace internal\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_BLOCKING_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionCuda.h",
    "content": "\n#if defined(__clang__) || defined(__GNUC__)\n#warning \"Deprecated header file, please either include the main Eigen/CXX11/Tensor header or the respective TensorContractionGpu.h file\"\n#endif\n\n#include \"TensorContractionGpu.h\"\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionGpu.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014-2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n// Copyright (C) 2015 Navdeep Jaitly <ndjaitly@google.com>\n// Copyright (C) 2014 Eric Martin <eric@ericmart.in>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_GPU_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_GPU_H\n\n#if defined(EIGEN_USE_GPU) && defined(EIGEN_GPUCC)\n\nnamespace Eigen {\n\ntemplate<typename Scalar, typename Index, typename LhsMapper,\n         typename RhsMapper, typename OutputMapper, bool needs_edge_check>\n__device__ EIGEN_STRONG_INLINE void\nEigenContractionKernelInternal(const LhsMapper lhs, const RhsMapper rhs,\n                               const OutputMapper output, Scalar* lhs_shmem, Scalar* rhs_shmem,\n                       const Index m_size, const Index n_size, const Index k_size) {\n\n  const Index m_block_idx = blockIdx.x;\n  const Index n_block_idx = blockIdx.y;\n\n  const Index base_m = 64 * m_block_idx;\n  const Index base_n = 64 * n_block_idx;\n\n  // declare and initialize 64 registers for output 8x8 block\n\n  // prefetch registers\n  Scalar lhs_pf0;\n  Scalar lhs_pf1;\n  Scalar lhs_pf2;\n  Scalar lhs_pf3;\n  Scalar lhs_pf4;\n  Scalar lhs_pf5;\n  Scalar lhs_pf6;\n  Scalar lhs_pf7;\n\n  Scalar rhs_pf0;\n  Scalar rhs_pf1;\n  Scalar rhs_pf2;\n  Scalar rhs_pf3;\n  Scalar rhs_pf4;\n  Scalar rhs_pf5;\n  Scalar rhs_pf6;\n  Scalar rhs_pf7;\n\n  // shared memory is formatted\n  // (contract idx in block, nocontract idx in block, block idx)\n  // where block idx is column major. This transposition limits the number of\n  // bank conflicts when reading the LHS. The core idea is that since the contracting\n  // index is shared by both sides, then the contracting index should be in threadIdx.x.\n\n  // On the LHS, we pad each row inside of each block with an extra element. This makes\n  // each block 8 rows of 9 elements, which is 72 elements. This gives no bank conflicts\n  // on writes and very few 2-way conflicts on reads. There is an 8x8 grid of these blocks.\n\n  // On the RHS we just add 8 padding elements to the end of each block. This gives no bank\n  // conflicts on writes and also none on reads.\n\n  // storage indices\n  const Index lhs_store_idx_base = threadIdx.y * 72 + threadIdx.x * 9 + threadIdx.z;\n  const Index rhs_store_idx_base = threadIdx.y * 72 + threadIdx.z * 8 + threadIdx.x;\n\n  const Index lhs_store_idx_0 = lhs_store_idx_base + 576 * 0;\n  const Index lhs_store_idx_1 = lhs_store_idx_base + 576 * 1;\n  const Index lhs_store_idx_2 = lhs_store_idx_base + 576 * 2;\n  const Index lhs_store_idx_3 = lhs_store_idx_base + 576 * 3;\n  const Index lhs_store_idx_4 = lhs_store_idx_base + 576 * 4;\n  const Index lhs_store_idx_5 = lhs_store_idx_base + 576 * 5;\n  const Index lhs_store_idx_6 = lhs_store_idx_base + 576 * 6;\n  const Index lhs_store_idx_7 = lhs_store_idx_base + 576 * 7;\n\n  const Index rhs_store_idx_0 = rhs_store_idx_base + 576 * 0;\n  const Index rhs_store_idx_1 = rhs_store_idx_base + 576 * 1;\n  const Index rhs_store_idx_2 = rhs_store_idx_base + 576 * 2;\n  const Index rhs_store_idx_3 = rhs_store_idx_base + 576 * 3;\n  const Index rhs_store_idx_4 = rhs_store_idx_base + 576 * 4;\n  const Index rhs_store_idx_5 = rhs_store_idx_base + 576 * 5;\n  const Index rhs_store_idx_6 = rhs_store_idx_base + 576 * 6;\n  const Index rhs_store_idx_7 = rhs_store_idx_base + 576 * 7;\n\n  // in the loading code, the following variables are important:\n  // threadIdx.x: the vertical position in an 8x8 block\n  // threadIdx.y: the vertical index of the 8x8 block in the grid\n  // threadIdx.z: the horizontal position in an 8x8 block\n  // k: the horizontal index of the 8x8 block in the grid\n  //\n  // The k parameter is implicit (it was the loop counter for a loop that went\n  // from 0 to <8, but now that loop is unrolled in the below code.\n\n  const Index load_idx_vert = threadIdx.x + 8 * threadIdx.y;\n  const Index lhs_vert = base_m + load_idx_vert;\n\n#define prefetchIntoRegisters(base_k)                           \\\n  {                                                             \\\n    lhs_pf0 = conv(0);                                          \\\n    lhs_pf1 = conv(0);                                          \\\n    lhs_pf2 = conv(0);                                          \\\n    lhs_pf3 = conv(0);                                          \\\n    lhs_pf4 = conv(0);                                          \\\n    lhs_pf5 = conv(0);                                          \\\n    lhs_pf6 = conv(0);                                          \\\n    lhs_pf7 = conv(0);                                          \\\n                                                                \\\n    rhs_pf0 = conv(0);                                          \\\n    rhs_pf1 = conv(0);                                          \\\n    rhs_pf2 = conv(0);                                          \\\n    rhs_pf3 = conv(0);                                          \\\n    rhs_pf4 = conv(0);                                          \\\n    rhs_pf5 = conv(0);                                          \\\n    rhs_pf6 = conv(0);                                          \\\n    rhs_pf7 = conv(0);                                          \\\n                                                                \\\n    if (!needs_edge_check || lhs_vert < m_size) {               \\\n      const Index lhs_horiz_0 = base_k + threadIdx.z + 0 * 8;   \\\n      const Index lhs_horiz_1 = base_k + threadIdx.z + 1 * 8;   \\\n      const Index lhs_horiz_2 = base_k + threadIdx.z + 2 * 8;   \\\n      const Index lhs_horiz_3 = base_k + threadIdx.z + 3 * 8;   \\\n      const Index lhs_horiz_4 = base_k + threadIdx.z + 4 * 8;   \\\n      const Index lhs_horiz_5 = base_k + threadIdx.z + 5 * 8;   \\\n      const Index lhs_horiz_6 = base_k + threadIdx.z + 6 * 8;   \\\n      const Index lhs_horiz_7 = base_k + threadIdx.z + 7 * 8;   \\\n                                                                \\\n      if (!needs_edge_check || lhs_horiz_7 < k_size) {          \\\n        lhs_pf0 = lhs(lhs_vert, lhs_horiz_0);                   \\\n        lhs_pf1 = lhs(lhs_vert, lhs_horiz_1);                   \\\n        lhs_pf2 = lhs(lhs_vert, lhs_horiz_2);                   \\\n        lhs_pf3 = lhs(lhs_vert, lhs_horiz_3);                   \\\n        lhs_pf4 = lhs(lhs_vert, lhs_horiz_4);                   \\\n        lhs_pf5 = lhs(lhs_vert, lhs_horiz_5);                   \\\n        lhs_pf6 = lhs(lhs_vert, lhs_horiz_6);                   \\\n        lhs_pf7 = lhs(lhs_vert, lhs_horiz_7);                   \\\n      } else if (lhs_horiz_6 < k_size) {                        \\\n        lhs_pf0 = lhs(lhs_vert, lhs_horiz_0);                   \\\n        lhs_pf1 = lhs(lhs_vert, lhs_horiz_1);                   \\\n        lhs_pf2 = lhs(lhs_vert, lhs_horiz_2);                   \\\n        lhs_pf3 = lhs(lhs_vert, lhs_horiz_3);                   \\\n        lhs_pf4 = lhs(lhs_vert, lhs_horiz_4);                   \\\n        lhs_pf5 = lhs(lhs_vert, lhs_horiz_5);                   \\\n        lhs_pf6 = lhs(lhs_vert, lhs_horiz_6);                   \\\n      } else if (lhs_horiz_5 < k_size) {                        \\\n        lhs_pf0 = lhs(lhs_vert, lhs_horiz_0);                   \\\n        lhs_pf1 = lhs(lhs_vert, lhs_horiz_1);                   \\\n        lhs_pf2 = lhs(lhs_vert, lhs_horiz_2);                   \\\n        lhs_pf3 = lhs(lhs_vert, lhs_horiz_3);                   \\\n        lhs_pf4 = lhs(lhs_vert, lhs_horiz_4);                   \\\n        lhs_pf5 = lhs(lhs_vert, lhs_horiz_5);                   \\\n      } else if (lhs_horiz_4 < k_size) {                        \\\n        lhs_pf0 = lhs(lhs_vert, lhs_horiz_0);                   \\\n        lhs_pf1 = lhs(lhs_vert, lhs_horiz_1);                   \\\n        lhs_pf2 = lhs(lhs_vert, lhs_horiz_2);                   \\\n        lhs_pf3 = lhs(lhs_vert, lhs_horiz_3);                   \\\n        lhs_pf4 = lhs(lhs_vert, lhs_horiz_4);                   \\\n      } else if (lhs_horiz_3 < k_size) {                        \\\n        lhs_pf0 = lhs(lhs_vert, lhs_horiz_0);                   \\\n        lhs_pf1 = lhs(lhs_vert, lhs_horiz_1);                   \\\n        lhs_pf2 = lhs(lhs_vert, lhs_horiz_2);                   \\\n        lhs_pf3 = lhs(lhs_vert, lhs_horiz_3);                   \\\n      } else if (lhs_horiz_2 < k_size) {                        \\\n        lhs_pf0 = lhs(lhs_vert, lhs_horiz_0);                   \\\n        lhs_pf1 = lhs(lhs_vert, lhs_horiz_1);                   \\\n        lhs_pf2 = lhs(lhs_vert, lhs_horiz_2);                   \\\n      } else if (lhs_horiz_1 < k_size) {                        \\\n        lhs_pf0 = lhs(lhs_vert, lhs_horiz_0);                   \\\n        lhs_pf1 = lhs(lhs_vert, lhs_horiz_1);                   \\\n      } else if (lhs_horiz_0 < k_size) {                        \\\n        lhs_pf0 = lhs(lhs_vert, lhs_horiz_0);                   \\\n      }                                                         \\\n    }                                                           \\\n                                                                \\\n    const Index rhs_vert = base_k + load_idx_vert;              \\\n    if (!needs_edge_check || rhs_vert < k_size) {               \\\n      const Index rhs_horiz_0 = base_n + threadIdx.z + 0 * 8;   \\\n      const Index rhs_horiz_1 = base_n + threadIdx.z + 1 * 8;   \\\n      const Index rhs_horiz_2 = base_n + threadIdx.z + 2 * 8;   \\\n      const Index rhs_horiz_3 = base_n + threadIdx.z + 3 * 8;   \\\n      const Index rhs_horiz_4 = base_n + threadIdx.z + 4 * 8;   \\\n      const Index rhs_horiz_5 = base_n + threadIdx.z + 5 * 8;   \\\n      const Index rhs_horiz_6 = base_n + threadIdx.z + 6 * 8;   \\\n      const Index rhs_horiz_7 = base_n + threadIdx.z + 7 * 8;   \\\n                                                                \\\n      if (rhs_horiz_7 < n_size) {                               \\\n        rhs_pf0 = rhs(rhs_vert, rhs_horiz_0);                   \\\n        rhs_pf1 = rhs(rhs_vert, rhs_horiz_1);                   \\\n        rhs_pf2 = rhs(rhs_vert, rhs_horiz_2);                   \\\n        rhs_pf3 = rhs(rhs_vert, rhs_horiz_3);                   \\\n        rhs_pf4 = rhs(rhs_vert, rhs_horiz_4);                   \\\n        rhs_pf5 = rhs(rhs_vert, rhs_horiz_5);                   \\\n        rhs_pf6 = rhs(rhs_vert, rhs_horiz_6);                   \\\n        rhs_pf7 = rhs(rhs_vert, rhs_horiz_7);                   \\\n      } else if (rhs_horiz_6 < n_size) {                        \\\n        rhs_pf0 = rhs(rhs_vert, rhs_horiz_0);                   \\\n        rhs_pf1 = rhs(rhs_vert, rhs_horiz_1);                   \\\n        rhs_pf2 = rhs(rhs_vert, rhs_horiz_2);                   \\\n        rhs_pf3 = rhs(rhs_vert, rhs_horiz_3);                   \\\n        rhs_pf4 = rhs(rhs_vert, rhs_horiz_4);                   \\\n        rhs_pf5 = rhs(rhs_vert, rhs_horiz_5);                   \\\n        rhs_pf6 = rhs(rhs_vert, rhs_horiz_6);                   \\\n      } else if (rhs_horiz_5 < n_size) {                        \\\n        rhs_pf0 = rhs(rhs_vert, rhs_horiz_0);                   \\\n        rhs_pf1 = rhs(rhs_vert, rhs_horiz_1);                   \\\n        rhs_pf2 = rhs(rhs_vert, rhs_horiz_2);                   \\\n        rhs_pf3 = rhs(rhs_vert, rhs_horiz_3);                   \\\n        rhs_pf4 = rhs(rhs_vert, rhs_horiz_4);                   \\\n        rhs_pf5 = rhs(rhs_vert, rhs_horiz_5);                   \\\n      } else if (rhs_horiz_4 < n_size) {                        \\\n        rhs_pf0 = rhs(rhs_vert, rhs_horiz_0);                   \\\n        rhs_pf1 = rhs(rhs_vert, rhs_horiz_1);                   \\\n        rhs_pf2 = rhs(rhs_vert, rhs_horiz_2);                   \\\n        rhs_pf3 = rhs(rhs_vert, rhs_horiz_3);                   \\\n        rhs_pf4 = rhs(rhs_vert, rhs_horiz_4);                   \\\n      } else if (rhs_horiz_3 < n_size) {                        \\\n        rhs_pf0 = rhs(rhs_vert, rhs_horiz_0);                   \\\n        rhs_pf1 = rhs(rhs_vert, rhs_horiz_1);                   \\\n        rhs_pf2 = rhs(rhs_vert, rhs_horiz_2);                   \\\n        rhs_pf3 = rhs(rhs_vert, rhs_horiz_3);                   \\\n      } else if (rhs_horiz_2 < n_size) {                        \\\n        rhs_pf0 = rhs(rhs_vert, rhs_horiz_0);                   \\\n        rhs_pf1 = rhs(rhs_vert, rhs_horiz_1);                   \\\n        rhs_pf2 = rhs(rhs_vert, rhs_horiz_2);                   \\\n      } else if (rhs_horiz_1 < n_size) {                        \\\n        rhs_pf0 = rhs(rhs_vert, rhs_horiz_0);                   \\\n        rhs_pf1 = rhs(rhs_vert, rhs_horiz_1);                   \\\n      } else if (rhs_horiz_0 < n_size) {                        \\\n        rhs_pf0 = rhs(rhs_vert, rhs_horiz_0);                   \\\n      }                                                         \\\n    }                                                           \\\n  }                                                             \\\n\n#define writeRegToShmem(_)                      \\\n  lhs_shmem[lhs_store_idx_0] = lhs_pf0;         \\\n  rhs_shmem[rhs_store_idx_0] = rhs_pf0;         \\\n                                                \\\n  lhs_shmem[lhs_store_idx_1] = lhs_pf1;         \\\n  rhs_shmem[rhs_store_idx_1] = rhs_pf1;         \\\n                                                \\\n  lhs_shmem[lhs_store_idx_2] = lhs_pf2;         \\\n  rhs_shmem[rhs_store_idx_2] = rhs_pf2;         \\\n                                                \\\n  lhs_shmem[lhs_store_idx_3] = lhs_pf3;         \\\n  rhs_shmem[rhs_store_idx_3] = rhs_pf3;         \\\n                                                \\\n  lhs_shmem[lhs_store_idx_4] = lhs_pf4;         \\\n  rhs_shmem[rhs_store_idx_4] = rhs_pf4;         \\\n                                                \\\n  lhs_shmem[lhs_store_idx_5] = lhs_pf5;         \\\n  rhs_shmem[rhs_store_idx_5] = rhs_pf5;         \\\n                                                \\\n  lhs_shmem[lhs_store_idx_6] = lhs_pf6;         \\\n  rhs_shmem[rhs_store_idx_6] = rhs_pf6;         \\\n                                                \\\n  lhs_shmem[lhs_store_idx_7] = lhs_pf7;         \\\n  rhs_shmem[rhs_store_idx_7] = rhs_pf7;         \\\n\n  // declare and initialize result array\n#define res(i, j) _res_##i##j\n#define initResultRow(i)                        \\\n  Scalar res(i, 0) = conv(0);                   \\\n  Scalar res(i, 1) = conv(0);                   \\\n  Scalar res(i, 2) = conv(0);                   \\\n  Scalar res(i, 3) = conv(0);                   \\\n  Scalar res(i, 4) = conv(0);                   \\\n  Scalar res(i, 5) = conv(0);                   \\\n  Scalar res(i, 6) = conv(0);                   \\\n  Scalar res(i, 7) = conv(0);                   \\\n\n  internal::scalar_cast_op<int, Scalar> conv;\n  initResultRow(0);\n  initResultRow(1);\n  initResultRow(2);\n  initResultRow(3);\n  initResultRow(4);\n  initResultRow(5);\n  initResultRow(6);\n  initResultRow(7);\n#undef initResultRow\n\n  for (Index base_k = 0; base_k < k_size; base_k += 64) {\n    // wait for previous iteration to finish with shmem. Despite common sense,\n    // the code is a bit faster with this here then at bottom of loop\n    __syncthreads();\n\n    prefetchIntoRegisters(base_k);\n    writeRegToShmem();\n\n    #undef prefetchIntoRegisters\n    #undef writeRegToShmem\n\n    // wait for shared mem packing to be done before starting computation\n    __syncthreads();\n\n    // compute 8x8 matrix product by outer product. This involves packing one column\n    // of LHS and one row of RHS into registers (takes 16 registers).\n\n#define lcol(i) _lcol##i\n    Scalar lcol(0);\n    Scalar lcol(1);\n    Scalar lcol(2);\n    Scalar lcol(3);\n    Scalar lcol(4);\n    Scalar lcol(5);\n    Scalar lcol(6);\n    Scalar lcol(7);\n\n#define rrow(j) _rrow##j\n    Scalar rrow(0);\n    Scalar rrow(1);\n    Scalar rrow(2);\n    Scalar rrow(3);\n    Scalar rrow(4);\n    Scalar rrow(5);\n    Scalar rrow(6);\n    Scalar rrow(7);\n\n    // Now x corresponds to k, y to m, and z to n\n    const Scalar* lhs_block = &lhs_shmem[threadIdx.x + 9 * threadIdx.y];\n    const Scalar* rhs_block = &rhs_shmem[threadIdx.x + 8 * threadIdx.z];\n\n#define lhs_element(i, j) lhs_block[72 * ((i) + 8 * (j))]\n#define rhs_element(i, j) rhs_block[72 * ((i) + 8 * (j))]\n\n#define loadData(i, j)                          \\\n    lcol(0) = lhs_element(0, j);               \\\n    rrow(0) = rhs_element(i, 0);               \\\n    lcol(1) = lhs_element(1, j);               \\\n    rrow(1) = rhs_element(i, 1);               \\\n    lcol(2) = lhs_element(2, j);               \\\n    rrow(2) = rhs_element(i, 2);               \\\n    lcol(3) = lhs_element(3, j);               \\\n    rrow(3) = rhs_element(i, 3);               \\\n    lcol(4) = lhs_element(4, j);               \\\n    rrow(4) = rhs_element(i, 4);               \\\n    lcol(5) = lhs_element(5, j);               \\\n    rrow(5) = rhs_element(i, 5);               \\\n    lcol(6) = lhs_element(6, j);               \\\n    rrow(6) = rhs_element(i, 6);               \\\n    lcol(7) = lhs_element(7, j);               \\\n    rrow(7) = rhs_element(i, 7);               \\\n\n#define computeCol(j)                           \\\n    res(0, j) += lcol(0) * rrow(j);             \\\n    res(1, j) += lcol(1) * rrow(j);             \\\n    res(2, j) += lcol(2) * rrow(j);             \\\n    res(3, j) += lcol(3) * rrow(j);             \\\n    res(4, j) += lcol(4) * rrow(j);             \\\n    res(5, j) += lcol(5) * rrow(j);             \\\n    res(6, j) += lcol(6) * rrow(j);             \\\n    res(7, j) += lcol(7) * rrow(j);             \\\n\n#define computePass(i)                          \\\n    loadData(i, i);                             \\\n                                                \\\n    computeCol(0);                              \\\n    computeCol(1);                              \\\n    computeCol(2);                              \\\n    computeCol(3);                              \\\n    computeCol(4);                              \\\n    computeCol(5);                              \\\n    computeCol(6);                              \\\n    computeCol(7);                              \\\n\n    computePass(0);\n    computePass(1);\n    computePass(2);\n    computePass(3);\n    computePass(4);\n    computePass(5);\n    computePass(6);\n    computePass(7);\n\n#undef lcol\n#undef rrow\n#undef lhs_element\n#undef rhs_element\n#undef loadData\n#undef computeCol\n#undef computePass\n  } // end loop over k\n\n  // we've now iterated over all of the large (ie width 64) k blocks and\n  // accumulated results in registers. At this point thread (x, y, z) contains\n  // the sum across all big k blocks of the product of little k block of index (x, y)\n  // with block of index (y, z). To compute the final output, we need to reduce\n  // the 8 threads over y by summation.\n#if defined(EIGEN_HIPCC) || (defined(EIGEN_CUDA_SDK_VER) && EIGEN_CUDA_SDK_VER < 90000)\n#define shuffleInc(i, j, mask) res(i, j) += __shfl_xor(res(i, j), mask)\n#else\n#define shuffleInc(i, j, mask) res(i, j) += __shfl_xor_sync(0xFFFFFFFF, res(i, j), mask)\n#endif\n\n#define reduceRow(i, mask)                      \\\n  shuffleInc(i, 0, mask);                       \\\n  shuffleInc(i, 1, mask);                       \\\n  shuffleInc(i, 2, mask);                       \\\n  shuffleInc(i, 3, mask);                       \\\n  shuffleInc(i, 4, mask);                       \\\n  shuffleInc(i, 5, mask);                       \\\n  shuffleInc(i, 6, mask);                       \\\n  shuffleInc(i, 7, mask);                       \\\n\n#define reduceMatrix(mask)                      \\\n  reduceRow(0, mask);                           \\\n  reduceRow(1, mask);                           \\\n  reduceRow(2, mask);                           \\\n  reduceRow(3, mask);                           \\\n  reduceRow(4, mask);                           \\\n  reduceRow(5, mask);                           \\\n  reduceRow(6, mask);                           \\\n  reduceRow(7, mask);                           \\\n\n  // actually perform the reduction, now each thread of index (_, y, z)\n  // contains the correct values in its registers that belong in the output\n  // block\n  reduceMatrix(1);\n  reduceMatrix(2);\n  reduceMatrix(4);\n\n#undef shuffleInc\n#undef reduceRow\n#undef reduceMatrix\n\n  // now we need to copy the 64 values into main memory. We can't split work\n  // among threads because all variables are in registers. There's 2 ways\n  // to do this:\n  // (1) have 1 thread do 64 writes from registers into global memory\n  // (2) have 1 thread do 64 writes into shared memory, and then 8 threads\n  //     each do 8 writes into global memory. We can just overwrite the shared\n  //     memory from the problem we just solved.\n  // (2) is slightly faster than (1) due to less branching and more ILP\n\n  // TODO: won't yield much gain, but could just use currently unused shared mem\n  //       and then we won't have to sync\n  // wait for shared mem to be out of use\n  __syncthreads();\n\n#define writeResultShmem(i, j)                                          \\\n  lhs_shmem[i + 8 * threadIdx.y + 64 * threadIdx.z + 512 * j] = res(i, j); \\\n\n#define writeRow(i)                             \\\n  writeResultShmem(i, 0);                       \\\n  writeResultShmem(i, 1);                       \\\n  writeResultShmem(i, 2);                       \\\n  writeResultShmem(i, 3);                       \\\n  writeResultShmem(i, 4);                       \\\n  writeResultShmem(i, 5);                       \\\n  writeResultShmem(i, 6);                       \\\n  writeResultShmem(i, 7);                       \\\n\n  if (threadIdx.x == 0) {\n    writeRow(0);\n    writeRow(1);\n    writeRow(2);\n    writeRow(3);\n    writeRow(4);\n    writeRow(5);\n    writeRow(6);\n    writeRow(7);\n  }\n#undef writeResultShmem\n#undef writeRow\n\n  const int max_i_write = numext::mini((int)((m_size - base_m - threadIdx.y + 7) / 8), 8);\n  const int max_j_write = numext::mini((int)((n_size - base_n - threadIdx.z + 7) / 8), 8);\n\n  if (threadIdx.x < max_i_write) {\n    if (max_j_write == 8) {\n      // TODO: can i trade bank conflicts for coalesced writes?\n      Scalar val0 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 0];\n      Scalar val1 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 1];\n      Scalar val2 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 2];\n      Scalar val3 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 3];\n      Scalar val4 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 4];\n      Scalar val5 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 5];\n      Scalar val6 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 6];\n      Scalar val7 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 7];\n\n      output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 0) = val0;\n      output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 1) = val1;\n      output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 2) = val2;\n      output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 3) = val3;\n      output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 4) = val4;\n      output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 5) = val5;\n      output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 6) = val6;\n      output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 7) = val7;\n    } else {\n#pragma unroll 7\n      for (int j = 0; j < max_j_write; j++) {\n        Scalar val = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * j];\n        output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * j) = val;\n      }\n    }\n  }\n#undef res\n}\n\n\ntemplate<typename Scalar, typename Index, typename LhsMapper,\n         typename RhsMapper, typename OutputMapper>\n__global__ void\n#if defined(EIGEN_HIPCC)\n__launch_bounds__(512, 1)\n#else\n__launch_bounds__(512)\n#endif\nEigenContractionKernel(const LhsMapper lhs, const RhsMapper rhs,\n                       const OutputMapper output,\n                       const Index m_size, const Index n_size, const Index k_size) {\n  __shared__ Scalar lhs_shmem[72 * 64];\n  __shared__ Scalar rhs_shmem[72 * 64];\n\n  const Index m_block_idx = blockIdx.x;\n  const Index n_block_idx = blockIdx.y;\n\n  const Index base_m = 64 * m_block_idx;\n  const Index base_n = 64 * n_block_idx;\n\n  if (base_m + 63 < m_size && base_n + 63 < n_size) {\n    EigenContractionKernelInternal<Scalar, Index, LhsMapper, RhsMapper, OutputMapper, false>(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size);\n  } else {\n    EigenContractionKernelInternal<Scalar, Index, LhsMapper, RhsMapper, OutputMapper, true>(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size);\n  }\n}\n\n\ntemplate<typename Index, typename LhsMapper,\n         typename RhsMapper, typename OutputMapper, bool CHECK_LHS_BOUNDARY,\n         bool CHECK_RHS_BOUNDARY>\n__device__ __forceinline__ void\nEigenFloatContractionKernelInternal16x16(const LhsMapper lhs, const RhsMapper rhs,\n                       const OutputMapper output, float2 lhs_shmem2[][16],\n                       float2 rhs_shmem2[][8], const Index m_size,\n                       const Index n_size, const Index k_size,\n                       const Index base_m, const Index base_n) {\n\n  // prefetch registers\n  float4 lhs_pf0, rhs_pf0;\n\n  float4 results[4];\n  for (int i=0; i < 4; i++) {\n    results[i].x = results[i].y = results[i].z = results[i].w = 0;\n  }\n\n#define prefetch_lhs(reg, row, col)                            \\\n    if (!CHECK_LHS_BOUNDARY) {                                 \\\n      if (col < k_size) {                                      \\\n        reg =lhs.template loadPacket<float4,Unaligned>(row, col);     \\\n      }                                                        \\\n    } else {                                                   \\\n      if (col < k_size) {                                      \\\n        if (row + 3 < m_size) {                                \\\n          reg =lhs.template loadPacket<float4,Unaligned>(row, col);   \\\n        } else if (row + 2 < m_size) {                         \\\n          reg.x =lhs(row + 0, col);                            \\\n          reg.y =lhs(row + 1, col);                            \\\n          reg.z =lhs(row + 2, col);                            \\\n        } else if (row + 1 < m_size) {                         \\\n          reg.x =lhs(row + 0, col);                            \\\n          reg.y =lhs(row + 1, col);                            \\\n        } else if (row  < m_size) {                            \\\n          reg.x =lhs(row + 0, col);                            \\\n        }                                                      \\\n      }                                                        \\\n    }\t\t\t\t\t\t\t       \\\n\n  Index lhs_vert = base_m+threadIdx.x*4;\n\n  for (Index k = 0; k < k_size; k += 16) {\n\n    lhs_pf0 = internal::pset1<float4>(0);\n    rhs_pf0 = internal::pset1<float4>(0);\n\n    Index lhs_horiz = threadIdx.y+k;\n    prefetch_lhs(lhs_pf0, lhs_vert, lhs_horiz)\n\n    Index rhs_vert = k+(threadIdx.x%4)*4;\n    Index rhs_horiz0 = (threadIdx.x>>2)+threadIdx.y*4+base_n;\n\n    if (!CHECK_RHS_BOUNDARY) {\n      if ((rhs_vert + 3) < k_size) {\n        // just CHECK_RHS_BOUNDARY\n        rhs_pf0 = rhs.template loadPacket<float4,Unaligned>(rhs_vert, rhs_horiz0);\n      } else if (rhs_vert + 2 < k_size) {\n        // just CHECK_RHS_BOUNDARY\n        rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n        rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0);\n        rhs_pf0.z = rhs(rhs_vert + 2, rhs_horiz0);\n      } else if (rhs_vert + 1 < k_size) {\n        rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n        rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0);\n      } else if (rhs_vert  < k_size) {\n        rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n      }\n    } else {\n      if (rhs_horiz0 < n_size) {\n        if ((rhs_vert + 3) < k_size) {\n          rhs_pf0 = rhs.template loadPacket<float4,Unaligned>(rhs_vert, rhs_horiz0);\n        } else if ((rhs_vert + 2) < k_size) {\n          rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n          rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0);\n          rhs_pf0.z = rhs(rhs_vert + 2, rhs_horiz0);\n        } else if ((rhs_vert + 1) < k_size) {\n          rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n          rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0);\n        } else if (rhs_vert  < k_size) {\n          rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n        }\n      }\n    }\n    float x1, x2 ;\n    // the following can be a bitwise operation..... some day.\n    if((threadIdx.x%8) < 4) {\n      x1 = rhs_pf0.y;\n      x2 = rhs_pf0.w;\n    } else {\n      x1 = rhs_pf0.x;\n      x2 = rhs_pf0.z;\n    }\n    #if defined(EIGEN_HIPCC) || (defined(EIGEN_CUDA_SDK_VER) && EIGEN_CUDA_SDK_VER < 90000)\n    x1 = __shfl_xor(x1, 4);\n    x2 = __shfl_xor(x2, 4);\n    #else\n    x1 = __shfl_xor_sync(0xFFFFFFFF, x1, 4);\n    x2 = __shfl_xor_sync(0xFFFFFFFF, x2, 4);\n    #endif\n    if((threadIdx.x%8) < 4) {\n      rhs_pf0.y = x1;\n      rhs_pf0.w = x2;\n    } else {\n      rhs_pf0.x = x1;\n      rhs_pf0.z = x2;\n    }\n\n    // We have 64 features.\n    // Row 0 -> times (0, 4, 8, 12, 1, 5, 9, 13) for features 0, 1.\n    // Row 1 -> times (0, 4, 8, 12, 1, 5, 9, 13) for features 2, 3.\n    // ...\n    // Row 31 -> times (0, 4, 8, 12, 1, 5, 9, 13) for features 62, 63\n    // Row 32 -> times (2, 6, 10, 14, 3, 7, 11, 15) for features 0, 1\n    // ...\n    rhs_shmem2[(threadIdx.x>>3)+ threadIdx.y*2][threadIdx.x%8] = make_float2(rhs_pf0.x, rhs_pf0.y);\n    rhs_shmem2[(threadIdx.x>>3)+ threadIdx.y*2+32][threadIdx.x%8] = make_float2(rhs_pf0.z, rhs_pf0.w);\n\n    // Row 0 (time 0) -> features (0, 1), (4, 5), .. (28, 29), (32, 33), ..  (60, 61)\n    // Row 1 (time 1) -> features (0, 1), (4, 5), .. (28, 29), (32, 33), ..  (60, 61)\n    // ...\n    // Row 15 (time 15) -> features (0, 1), (4, 5), .. (28, 29), (32, 33), ..  (60, 61)\n    // Row 16 (time 0) -> features (2, 3), (6, 7), .. (30, 31), (34, 35), ..  (62, 63)\n    // ...\n\n    lhs_shmem2[threadIdx.y][threadIdx.x] = make_float2(lhs_pf0.x, lhs_pf0.y);\n    lhs_shmem2[threadIdx.y+16][threadIdx.x] = make_float2(lhs_pf0.z, lhs_pf0.w);\n\n\n#define add_vals(fl1, fl2, fr1, fr2)\\\n    results[0].x += fl1.x * fr1.x;\\\n    results[0].y += fl1.y * fr1.x;\\\n    results[0].z += fl2.x * fr1.x;\\\n    results[0].w += fl2.y * fr1.x;\\\n\\\n    results[1].x += fl1.x * fr1.y;\\\n    results[1].y += fl1.y * fr1.y;\\\n    results[1].z += fl2.x * fr1.y;\\\n    results[1].w += fl2.y * fr1.y;\\\n\\\n    results[2].x += fl1.x * fr2.x;\\\n    results[2].y += fl1.y * fr2.x;\\\n    results[2].z += fl2.x * fr2.x;\\\n    results[2].w += fl2.y * fr2.x;\\\n\\\n    results[3].x += fl1.x * fr2.y;\\\n    results[3].y += fl1.y * fr2.y;\\\n    results[3].z += fl2.x * fr2.y;\\\n    results[3].w += fl2.y * fr2.y;\\\n\n    __syncthreads();\n\n    // Do the multiplies.\n    #pragma unroll\n    for (int koff = 0; koff < 16; koff ++) {\n      // 32 x threads.\n      float2 fl1 = lhs_shmem2[koff][threadIdx.x];\n      float2 fl2 = lhs_shmem2[koff + 16][threadIdx.x];\n\n      int start_feature = threadIdx.y * 4;\n      float2 fr1 = rhs_shmem2[(start_feature>>1) + 32*((koff%4)/2)][koff/4 + (koff%2)*4];\n      float2 fr2 = rhs_shmem2[(start_feature>>1) + 1 + 32*((koff%4)/2)][koff/4 + (koff%2)*4];\n\n      add_vals(fl1, fl2, fr1, fr2)\n    }\n    __syncthreads();\n  }\n\n#undef prefetch_lhs\n#undef add_vals\n\n  Index horiz_base = threadIdx.y*4+base_n;\n  if (!CHECK_LHS_BOUNDARY && !CHECK_RHS_BOUNDARY) {\n    for (int i = 0; i < 4; i++) {\n      output(lhs_vert, horiz_base + i) = results[i].x;\n      output(lhs_vert + 1, horiz_base + i) = results[i].y;\n      output(lhs_vert + 2, horiz_base + i) = results[i].z;\n      output(lhs_vert + 3, horiz_base + i) = results[i].w;\n    }\n  } else if (!CHECK_RHS_BOUNDARY) {\n    // CHECK LHS\n    if (lhs_vert + 3 < m_size) {\n      for (int i = 0; i < 4; i++) {\n        output(lhs_vert, horiz_base + i) = results[i].x;\n        output(lhs_vert + 1, horiz_base + i) = results[i].y;\n        output(lhs_vert + 2, horiz_base + i) = results[i].z;\n        output(lhs_vert + 3, horiz_base + i) = results[i].w;\n      }\n    } else if (lhs_vert + 2 < m_size) {\n      for (int i = 0; i < 4; i++) {\n        output(lhs_vert, horiz_base + i) = results[i].x;\n        output(lhs_vert + 1, horiz_base + i) = results[i].y;\n        output(lhs_vert + 2, horiz_base + i) = results[i].z;\n      }\n    } else if (lhs_vert + 1 < m_size) {\n      for (int i = 0; i < 4; i++) {\n        output(lhs_vert, horiz_base + i) = results[i].x;\n        output(lhs_vert + 1, horiz_base + i) = results[i].y;\n      }\n    } else if (lhs_vert  < m_size) {\n      for (int i = 0; i < 4; i++) {\n        output(lhs_vert, horiz_base + i) = results[i].x;\n      }\n    }\n  } else if (!CHECK_LHS_BOUNDARY) {\n    // CHECK RHS\n    /*\n    int ncols_rem = fminf(n_size- horiz_base, 4);\n    for (int i = 0; i < ncols_rem; i++) {\n      output(lhs_vert, horiz_base + i) = results[i].x;\n      output(lhs_vert + 1, horiz_base + i) = results[i].y;\n      output(lhs_vert + 2, horiz_base + i) = results[i].z;\n      output(lhs_vert + 3, horiz_base + i) = results[i].w;\n    }*/\n    for (int i = 0; i < 4; i++) {\n      if (horiz_base+i < n_size) {\n        output(lhs_vert, horiz_base + i) = results[i].x;\n        output(lhs_vert + 1, horiz_base + i) = results[i].y;\n        output(lhs_vert + 2, horiz_base + i) = results[i].z;\n        output(lhs_vert + 3, horiz_base + i) = results[i].w;\n       }\n    }\n  } else {\n    // CHECK both boundaries.\n    for (int i = 0; i < 4; i++) {\n      if (horiz_base+i < n_size) {\n        if (lhs_vert < m_size)\n          output(lhs_vert, horiz_base + i) = results[i].x;\n        if (lhs_vert + 1 < m_size)\n          output(lhs_vert + 1, horiz_base + i) = results[i].y;\n        if (lhs_vert + 2 < m_size)\n          output(lhs_vert + 2, horiz_base + i) = results[i].z;\n        if (lhs_vert + 3 < m_size)\n          output(lhs_vert + 3, horiz_base + i) = results[i].w;\n      }\n    }\n  }\n}\n\n\ntemplate<typename Index, typename LhsMapper,\n         typename RhsMapper, typename OutputMapper, bool CHECK_LHS_BOUNDARY,\n         bool CHECK_RHS_BOUNDARY>\n__device__ __forceinline__ void\nEigenFloatContractionKernelInternal(const LhsMapper lhs, const RhsMapper rhs,\n                       const OutputMapper output, float2 lhs_shmem2[][32],\n                       float2 rhs_shmem2[][8], const Index m_size,\n                       const Index n_size, const Index k_size,\n                       const Index base_m, const Index base_n) {\n\n  // prefetch registers\n  float4 lhs_pf0, lhs_pf1, lhs_pf2, lhs_pf3;\n  float4 rhs_pf0, rhs_pf1;\n\n  float4 results[8];\n  for (int i=0; i < 8; i++) {\n    results[i].x = results[i].y = results[i].z = results[i].w = 0;\n  }\n\n  Index lhs_vert = base_m+threadIdx.x*4+(threadIdx.y%4)*32;\n  for (Index k = 0; k < k_size; k += 32) {\n    lhs_pf0 = internal::pset1<float4>(0);\n    lhs_pf1 = internal::pset1<float4>(0);\n    lhs_pf2 = internal::pset1<float4>(0);\n    lhs_pf3 = internal::pset1<float4>(0);\n\n    rhs_pf0 = internal::pset1<float4>(0);\n    rhs_pf1 = internal::pset1<float4>(0);\n\n     if (!CHECK_LHS_BOUNDARY) {\n      if ((threadIdx.y/4+k+24) < k_size) {\n        lhs_pf0 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k));\n        lhs_pf1 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+8));\n        lhs_pf2 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+16));\n        lhs_pf3 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+24));\n      } else if ((threadIdx.y/4+k+16) < k_size) {\n        lhs_pf0 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k));\n        lhs_pf1 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+8));\n        lhs_pf2 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+16));\n      } else if ((threadIdx.y/4+k+8) < k_size) {\n        lhs_pf0 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k));\n        lhs_pf1 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+8));\n      } else if ((threadIdx.y/4+k) < k_size) {\n        lhs_pf0 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k));\n      }\n    } else {\n      // just CHECK_LHS_BOUNDARY\n      if (lhs_vert + 3 < m_size) {\n        if ((threadIdx.y/4+k+24) < k_size) {\n          lhs_pf0 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k));\n          lhs_pf1 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+8));\n          lhs_pf2 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+16));\n          lhs_pf3 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+24));\n        } else if ((threadIdx.y/4+k+16) < k_size) {\n          lhs_pf0 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k));\n          lhs_pf1 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+8));\n          lhs_pf2 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+16));\n        } else if ((threadIdx.y/4+k+8) < k_size) {\n          lhs_pf0 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k));\n          lhs_pf1 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+8));\n        } else if ((threadIdx.y/4+k) < k_size) {\n          lhs_pf0 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k));\n        }\n      } else if (lhs_vert + 2 < m_size) {\n        if ((threadIdx.y/4+k+24) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k));\n          lhs_pf0.z =lhs(lhs_vert + 2, (threadIdx.y/4+k));\n          lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8));\n          lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8));\n          lhs_pf1.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+8));\n          lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16));\n          lhs_pf2.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+16));\n          lhs_pf2.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+16));\n          lhs_pf3.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+24));\n          lhs_pf3.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+24));\n          lhs_pf3.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+24));\n        } else if ((threadIdx.y/4+k+16) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k));\n          lhs_pf0.z =lhs(lhs_vert + 2, (threadIdx.y/4+k));\n          lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8));\n          lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8));\n          lhs_pf1.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+8));\n          lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16));\n          lhs_pf2.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+16));\n          lhs_pf2.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+16));\n        } else if ((threadIdx.y/4+k+8) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k));\n          lhs_pf0.z =lhs(lhs_vert + 2, (threadIdx.y/4+k));\n          lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8));\n          lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8));\n          lhs_pf1.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+8));\n        } else if ((threadIdx.y/4+k) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k));\n          lhs_pf0.z =lhs(lhs_vert + 2, (threadIdx.y/4+k));\n        }\n      } else if (lhs_vert + 1 < m_size) {\n        if ((threadIdx.y/4+k+24) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k));\n          lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8));\n          lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8));\n          lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16));\n          lhs_pf2.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+16));\n          lhs_pf3.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+24));\n          lhs_pf3.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+24));\n        } else if ((threadIdx.y/4+k+16) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k));\n          lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8));\n          lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8));\n          lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16));\n          lhs_pf2.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+16));\n        } else if ((threadIdx.y/4+k+8) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k));\n          lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8));\n          lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8));\n        } else if ((threadIdx.y/4+k) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k));\n        }\n      } else if (lhs_vert < m_size) {\n        if ((threadIdx.y/4+k+24) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8));\n          lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16));\n          lhs_pf3.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+24));\n        } else if ((threadIdx.y/4+k+16) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8));\n          lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16));\n        } else if ((threadIdx.y/4+k+8) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8));\n        } else if ((threadIdx.y/4+k) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n        }\n      }\n    }\n    __syncthreads();\n    Index rhs_vert = k+threadIdx.x*4;\n    Index rhs_horiz0 = threadIdx.y*2+base_n;\n    Index rhs_horiz1 = threadIdx.y*2+1+base_n;\n    if (!CHECK_RHS_BOUNDARY) {\n      if ((rhs_vert + 3) < k_size) {\n        // just CHECK_RHS_BOUNDARY\n        rhs_pf0 = rhs.template loadPacket<float4,Unaligned>(rhs_vert, rhs_horiz0);\n        rhs_pf1 = rhs.template loadPacket<float4,Unaligned>(rhs_vert, rhs_horiz1);\n      } else if (rhs_vert + 2 < k_size) {\n        // just CHECK_RHS_BOUNDARY\n        rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n        rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0);\n        rhs_pf0.z = rhs(rhs_vert + 2, rhs_horiz0);\n        rhs_pf1.x = rhs(rhs_vert, rhs_horiz1);\n        rhs_pf1.y = rhs(rhs_vert + 1, rhs_horiz1);\n        rhs_pf1.z = rhs(rhs_vert + 2, rhs_horiz1);\n      } else if (rhs_vert + 1 < k_size) {\n        rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n        rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0);\n        rhs_pf1.x = rhs(rhs_vert, rhs_horiz1);\n        rhs_pf1.y = rhs(rhs_vert + 1, rhs_horiz1);\n      } else if (rhs_vert  < k_size) {\n        rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n        rhs_pf1.x = rhs(rhs_vert, rhs_horiz1);\n      }\n    } else {\n      if (rhs_horiz1 < n_size) {\n        if ((rhs_vert + 3) < k_size) {\n          // just CHECK_RHS_BOUNDARY\n          rhs_pf0 = rhs.template loadPacket<float4,Unaligned>(rhs_vert, rhs_horiz0);\n          rhs_pf1 = rhs.template loadPacket<float4,Unaligned>(rhs_vert, rhs_horiz1);\n        } else if (rhs_vert + 2 < k_size) {\n          // just CHECK_RHS_BOUNDARY\n          rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n          rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0);\n          rhs_pf0.z = rhs(rhs_vert + 2, rhs_horiz0);\n          rhs_pf1.x = rhs(rhs_vert, rhs_horiz1);\n          rhs_pf1.y = rhs(rhs_vert + 1, rhs_horiz1);\n          rhs_pf1.z = rhs(rhs_vert + 2, rhs_horiz1);\n        } else if (k+threadIdx.x*4 + 1 < k_size) {\n          rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n          rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0);\n          rhs_pf1.x = rhs(rhs_vert, rhs_horiz1);\n          rhs_pf1.y = rhs(rhs_vert + 1, rhs_horiz1);\n        } else if (k+threadIdx.x*4  < k_size) {\n          rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n          rhs_pf1.x = rhs(rhs_vert, rhs_horiz1);\n        }\n      } else if (rhs_horiz0 < n_size) {\n        if ((rhs_vert + 3) < k_size) {\n          // just CHECK_RHS_BOUNDARY\n          rhs_pf0 = rhs.template loadPacket<float4,Unaligned>(rhs_vert, rhs_horiz0);\n        } else if ((rhs_vert + 2) < k_size) {\n          // just CHECK_RHS_BOUNDARY\n          rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n          rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0);\n          rhs_pf0.z = rhs(rhs_vert + 2, rhs_horiz0);\n        } else if ((rhs_vert + 1) < k_size) {\n          rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n          rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0);\n        } else if (rhs_vert  < k_size) {\n          rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n        }\n      }\n    }\n    __syncthreads();\n    // Loaded. Do computation\n    // Row 0 -> times (0, 4, 8, .. 28) for features 0, 1.\n    // Row 1 -> times (0, 4, 8, .. 28) for features 2, 3.\n    // ..\n    // Row 31 -> times (0, 4, 8, .. 28) for features 62, 63\n    rhs_shmem2[threadIdx.y][threadIdx.x] = make_float2(rhs_pf0.x, rhs_pf1.x);\n    // Row 32 -> times (1, 5, 9, .. 29) for features 0, 1.\n    // Row 33 -> times (1, 5, 9, .. 29) for features 2, 3.\n    // ..\n    rhs_shmem2[threadIdx.y+32][threadIdx.x] = make_float2(rhs_pf0.y, rhs_pf1.y);\n    // Row 64 -> times (2, 6, 10, .. 30) for features 0, 1.\n    // Row 65 -> times (2, 6, 10, .. 30) for features 2, 3.\n    rhs_shmem2[threadIdx.y+64][threadIdx.x] = make_float2(rhs_pf0.z, rhs_pf1.z);\n    // Row 96 -> times (3, 7, 11, .. 31) for features 0, 1.\n    // Row 97 -> times (3, 7, 11, .. 31) for features 2, 3.\n    rhs_shmem2[threadIdx.y+96][threadIdx.x] = make_float2(rhs_pf0.w, rhs_pf1.w);\n\n    // LHS.\n    // Row 0 (time 0) -> features (0, 1), (4, 5), .. (28, 29), (32, 33), ..  (60, 61) .. (124, 125)\n    // Row 1 (time 1) -> features (0, 1), (4, 5), .. (28, 29), (32, 33), ..  (60, 61) .. (124, 125)\n    // ...\n    // Row 8 (time 0) -> features (2, 3), (6, 7), .. (30, 31), (34, 35), ..  (62, 63) .. (126, 127)\n    // Row 15 (time 7) -> features (2, 3), (6, 7), .. (30, 31), (34, 35), ..  (62, 63) .. (126, 127)\n\n\n#define add_vals(a_feat1, a_feat2, f1, f2, f3, f4)\\\n      results[0].x += a_feat1.x * f1.x;\\\n      results[1].x += a_feat1.x * f1.y;\\\n      results[2].x += a_feat1.x * f2.x;\\\n      results[3].x += a_feat1.x * f2.y;\\\n      results[4].x += a_feat1.x * f3.x;\\\n      results[5].x += a_feat1.x * f3.y;\\\n      results[6].x += a_feat1.x * f4.x;\\\n      results[7].x += a_feat1.x * f4.y;\\\n\\\n      results[0].y += a_feat1.y * f1.x;\\\n      results[1].y += a_feat1.y * f1.y;\\\n      results[2].y += a_feat1.y * f2.x;\\\n      results[3].y += a_feat1.y * f2.y;\\\n      results[4].y += a_feat1.y * f3.x;\\\n      results[5].y += a_feat1.y * f3.y;\\\n      results[6].y += a_feat1.y * f4.x;\\\n      results[7].y += a_feat1.y * f4.y;\\\n\\\n      results[0].z += a_feat2.x * f1.x;\\\n      results[1].z += a_feat2.x * f1.y;\\\n      results[2].z += a_feat2.x * f2.x;\\\n      results[3].z += a_feat2.x * f2.y;\\\n      results[4].z += a_feat2.x * f3.x;\\\n      results[5].z += a_feat2.x * f3.y;\\\n      results[6].z += a_feat2.x * f4.x;\\\n      results[7].z += a_feat2.x * f4.y;\\\n\\\n      results[0].w += a_feat2.y * f1.x;\\\n      results[1].w += a_feat2.y * f1.y;\\\n      results[2].w += a_feat2.y * f2.x;\\\n      results[3].w += a_feat2.y * f2.y;\\\n      results[4].w += a_feat2.y * f3.x;\\\n      results[5].w += a_feat2.y * f3.y;\\\n      results[6].w += a_feat2.y * f4.x;\\\n      results[7].w += a_feat2.y * f4.y;\\\n\n    lhs_shmem2[threadIdx.y/4][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf0.x, lhs_pf0.y);\n    lhs_shmem2[threadIdx.y/4+8][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf1.x, lhs_pf1.y);\n    lhs_shmem2[threadIdx.y/4+16][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf2.x, lhs_pf2.y);\n    lhs_shmem2[threadIdx.y/4+24][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf3.x, lhs_pf3.y);\n\n    lhs_shmem2[threadIdx.y/4 + 32][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf0.z, lhs_pf0.w);\n    lhs_shmem2[threadIdx.y/4 + 40][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf1.z, lhs_pf1.w);\n    lhs_shmem2[threadIdx.y/4 + 48][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf2.z, lhs_pf2.w);\n    lhs_shmem2[threadIdx.y/4 + 56][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf3.z, lhs_pf3.w);\n\n    __syncthreads();\n\n    // Do the multiplies.\n    #pragma unroll\n    for (int koff = 0; koff < 32; koff ++) {\n      float2 a3 = lhs_shmem2[koff][threadIdx.x + (threadIdx.y % 4) * 8];\n      float2 a4 = lhs_shmem2[koff + 32][threadIdx.x + (threadIdx.y % 4) * 8];\n\n      // first feature is at (threadIdx.y/4) * 8 last is at start + 8.\n      int start_feature = (threadIdx.y / 4) * 8;\n\n      float2 br1 = rhs_shmem2[start_feature/2 +     (koff % 4) * 32][koff/4];\n      float2 br2 = rhs_shmem2[start_feature/2 + 1 + (koff % 4) * 32][koff/4];\n      float2 br3 = rhs_shmem2[start_feature/2 + 2 + (koff % 4) * 32][koff/4];\n      float2 br4 = rhs_shmem2[start_feature/2 + 3 + (koff % 4) * 32][koff/4];\n\n      add_vals(a3, a4, br1, br2, br3, br4)\n    }\n    __syncthreads();\n  } // end loop over k\n\n  __syncthreads();\n  Index horiz_base = (threadIdx.y/4)*8+base_n;\n  if (!CHECK_LHS_BOUNDARY && !CHECK_RHS_BOUNDARY) {\n    for (int i = 0; i < 8; i++) {\n      output(lhs_vert, horiz_base + i) = results[i].x;\n      output(lhs_vert + 1, horiz_base + i) = results[i].y;\n      output(lhs_vert + 2, horiz_base + i) = results[i].z;\n      output(lhs_vert + 3, horiz_base + i) = results[i].w;\n    }\n  } else if (!CHECK_RHS_BOUNDARY) {\n    if (lhs_vert + 3 < m_size) {\n      for (int i = 0; i < 8; i++) {\n        output(lhs_vert, horiz_base + i) = results[i].x;\n        output(lhs_vert + 1, horiz_base + i) = results[i].y;\n        output(lhs_vert + 2, horiz_base + i) = results[i].z;\n        output(lhs_vert + 3, horiz_base + i) = results[i].w;\n      }\n    } else if (lhs_vert + 2 < m_size) {\n      for (int i = 0; i < 8; i++) {\n        output(lhs_vert, horiz_base + i) = results[i].x;\n        output(lhs_vert + 1, horiz_base + i) = results[i].y;\n        output(lhs_vert + 2, horiz_base + i) = results[i].z;\n      }\n    } else if (lhs_vert + 1 < m_size) {\n      for (int i = 0; i < 8; i++) {\n        output(lhs_vert, horiz_base + i) = results[i].x;\n        output(lhs_vert + 1, horiz_base + i) = results[i].y;\n      }\n    } else if (lhs_vert  < m_size) {\n      for (int i = 0; i < 8; i++) {\n        output(lhs_vert, horiz_base + i) = results[i].x;\n      }\n    }\n  } else if (!CHECK_LHS_BOUNDARY) {\n    // CHECK BOUNDARY_B\n    for (int i = 0; i < 8; i++) {\n      if (horiz_base + i < n_size) {\n        output(lhs_vert, horiz_base + i) = results[i].x;\n        output(lhs_vert + 1, horiz_base + i) = results[i].y;\n        output(lhs_vert + 2, horiz_base + i) = results[i].z;\n        output(lhs_vert + 3, horiz_base + i) = results[i].w;\n      }\n    }\n  } else {\n    // CHECK both boundaries.\n    for (int i = 0; i < 8; i++) {\n      if (horiz_base + i < n_size) {\n        if (lhs_vert < m_size)\n          output(lhs_vert, horiz_base + i) = results[i].x;\n        if (lhs_vert + 1 < m_size)\n          output(lhs_vert + 1, horiz_base + i) = results[i].y;\n        if (lhs_vert + 2 < m_size)\n          output(lhs_vert + 2, horiz_base + i) = results[i].z;\n        if (lhs_vert + 3 < m_size)\n          output(lhs_vert + 3, horiz_base + i) = results[i].w;\n      }\n    }\n  }\n}\n\n\ntemplate<typename Index, typename LhsMapper,\n         typename RhsMapper, typename OutputMapper>\n__global__ void\n#if defined(EIGEN_HIPCC)\n__launch_bounds__(256, 1)\n#else\n__launch_bounds__(256)\n#endif\nEigenFloatContractionKernel(const LhsMapper lhs, const RhsMapper rhs,\n                       const OutputMapper output,\n                       const Index m_size, const Index n_size, const Index k_size) {\n  __shared__ float2 lhs_shmem[64*32];\n  __shared__ float2 rhs_shmem[128*8];\n\n  typedef float2 LHS_MEM[64][32];\n  typedef float2 RHS_MEM[128][8];\n\n  const Index m_block_idx = blockIdx.x;\n  const Index n_block_idx = blockIdx.y;\n\n  const Index base_m = 128 * m_block_idx;\n  const Index base_n = 64 * n_block_idx;\n\n  bool check_rhs = (base_n + 63) >= n_size;\n  bool check_lhs128 = (base_m + 127) >= m_size;\n\n  if (!check_rhs) {\n    if (!check_lhs128) {\n      // >= 128 rows left\n      EigenFloatContractionKernelInternal<Index, LhsMapper, RhsMapper, OutputMapper, false, false>(\n                     lhs, rhs, output, *((LHS_MEM *) lhs_shmem), *((RHS_MEM *) rhs_shmem), m_size, n_size, k_size, base_m, base_n);\n    } else {\n      EigenFloatContractionKernelInternal<Index, LhsMapper, RhsMapper, OutputMapper, true, false>(\n                     lhs, rhs, output, *((LHS_MEM *) lhs_shmem), *((RHS_MEM *) rhs_shmem), m_size, n_size, k_size, base_m, base_n);\n    }\n  } else {\n    if (!check_lhs128) {\n      // >= 128 rows left\n      EigenFloatContractionKernelInternal<Index, LhsMapper, RhsMapper, OutputMapper, false, true>(\n                     lhs, rhs, output, *((LHS_MEM *) lhs_shmem), *((RHS_MEM *) rhs_shmem), m_size, n_size, k_size, base_m, base_n);\n    } else {\n      EigenFloatContractionKernelInternal<Index, LhsMapper, RhsMapper, OutputMapper, true, true>(\n                     lhs, rhs, output, *((LHS_MEM *) lhs_shmem), *((RHS_MEM *) rhs_shmem), m_size, n_size, k_size, base_m, base_n);\n    }\n  }\n}\n\ntemplate<typename Index, typename LhsMapper,\n         typename RhsMapper, typename OutputMapper>\n__global__ void\n#if defined(EIGEN_HIPCC)\n__launch_bounds__(256, 1)\n#else\n__launch_bounds__(256)\n#endif\nEigenFloatContractionKernel16x16(const LhsMapper lhs, const RhsMapper rhs,\n                       const OutputMapper output,\n                       const Index m_size, const Index n_size, const Index k_size) {\n  __shared__ float2 lhs_shmem[32][16];\n  __shared__ float2 rhs_shmem[64][8];\n\n  const Index m_block_idx = blockIdx.x;\n  const Index n_block_idx = blockIdx.y;\n\n  const Index base_m = 64 * m_block_idx;\n  const Index base_n = 64 * n_block_idx;\n\n  if (base_m + 63 < m_size) {\n    if (base_n + 63 < n_size) {\n      EigenFloatContractionKernelInternal16x16<Index, LhsMapper, RhsMapper, OutputMapper, false, false>(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size, base_m, base_n);\n    } else {\n      EigenFloatContractionKernelInternal16x16<Index, LhsMapper, RhsMapper, OutputMapper, false, true>(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size, base_m, base_n);\n    }\n  } else {\n    if (base_n + 63 < n_size) {\n      EigenFloatContractionKernelInternal16x16<Index, LhsMapper, RhsMapper, OutputMapper, true, false>(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size, base_m, base_n);\n    } else {\n      EigenFloatContractionKernelInternal16x16<Index, LhsMapper, RhsMapper, OutputMapper, true, true>(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size, base_m, base_n);\n    }\n  }\n}\n\n\ntemplate<typename Indices, typename LeftArgType, typename RightArgType, typename OutputKernelType>\nstruct TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, GpuDevice> :\n    public TensorContractionEvaluatorBase<TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, GpuDevice> > {\n\n  typedef GpuDevice Device;\n\n  typedef TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, Device> Self;\n  typedef TensorContractionEvaluatorBase<Self> Base;\n\n  typedef TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType> XprType;\n  typedef typename internal::remove_const<typename XprType::Scalar>::type Scalar;\n  typedef typename XprType::Index Index;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, GpuDevice>::type PacketReturnType;\n\n  enum {\n    Layout = TensorEvaluator<LeftArgType, Device>::Layout,\n  };\n\n  // Most of the code is assuming that both input tensors are ColMajor. If the\n  // inputs are RowMajor, we will \"cheat\" by swapping the LHS and RHS:\n  // If we want to compute A * B = C, where A is LHS and B is RHS, the code\n  // will pretend B is LHS and A is RHS.\n  typedef typename internal::conditional<\n    static_cast<int>(Layout) == static_cast<int>(ColMajor), LeftArgType, RightArgType>::type EvalLeftArgType;\n  typedef typename internal::conditional<\n    static_cast<int>(Layout) == static_cast<int>(ColMajor), RightArgType, LeftArgType>::type EvalRightArgType;\n\n  static const int LDims =\n      internal::array_size<typename TensorEvaluator<EvalLeftArgType, Device>::Dimensions>::value;\n  static const int RDims =\n      internal::array_size<typename TensorEvaluator<EvalRightArgType, Device>::Dimensions>::value;\n  static const int ContractDims = internal::array_size<Indices>::value;\n\n  typedef array<Index, LDims> left_dim_mapper_t;\n  typedef array<Index, RDims> right_dim_mapper_t;\n\n  typedef array<Index, ContractDims> contract_t;\n  typedef array<Index, LDims - ContractDims> left_nocontract_t;\n  typedef array<Index, RDims - ContractDims> right_nocontract_t;\n\n  static const int NumDims = LDims + RDims - 2 * ContractDims;\n\n  typedef DSizes<Index, NumDims> Dimensions;\n\n  // typedefs needed in evalTo\n  typedef typename internal::remove_const<typename EvalLeftArgType::Scalar>::type LhsScalar;\n  typedef typename internal::remove_const<typename EvalRightArgType::Scalar>::type RhsScalar;\n\n  typedef TensorEvaluator<EvalLeftArgType, Device> LeftEvaluator;\n  typedef TensorEvaluator<EvalRightArgType, Device> RightEvaluator;\n\n  typedef typename LeftEvaluator::Dimensions LeftDimensions;\n  typedef typename RightEvaluator::Dimensions RightDimensions;\n\n  TensorEvaluator(const XprType& op, const Device& device) :\n      Base(op, device)\n  {\n    EIGEN_STATIC_ASSERT( (internal::is_same<OutputKernelType, const NoOpOutputKernel>::value),\n                          GPU_TENSOR_CONTRACTION_DOES_NOT_SUPPORT_OUTPUT_KERNELS);\n  }\n\n  // We need to redefine this method to make nvcc happy\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* data) {\n    this->m_leftImpl.evalSubExprsIfNeeded(NULL);\n    this->m_rightImpl.evalSubExprsIfNeeded(NULL);\n    if (data) {\n      evalTo(data);\n      return false;\n    } else {\n      this->m_result = static_cast<Scalar *>(this->m_device.allocate(this->dimensions().TotalSize() * sizeof(Scalar)));\n      evalTo(this->m_result);\n      return true;\n    }\n  }\n\n  void evalTo(Scalar* buffer) const {\n    if (this->m_lhs_inner_dim_contiguous) {\n      if (this->m_rhs_inner_dim_contiguous) {\n        if (this->m_rhs_inner_dim_reordered) {\n          evalTyped<true, true, true, Unaligned>(buffer);\n        }\n        else {\n          evalTyped<true, true, false, Unaligned>(buffer);\n        }\n      }\n      else {\n       if (this->m_rhs_inner_dim_reordered) {\n          evalTyped<true, false, true, Unaligned>(buffer);\n        }\n        else {\n          evalTyped<true, false, false, Unaligned>(buffer);\n        }\n      }\n    }\n    else {\n      if (this->m_rhs_inner_dim_contiguous) {\n        if (this->m_rhs_inner_dim_reordered) {\n          evalTyped<false, true, true, Unaligned>(buffer);\n        }\n        else {\n          evalTyped<false, true, false, Unaligned>(buffer);\n        }\n      }\n      else {\n       if (this->m_rhs_inner_dim_reordered) {\n          evalTyped<false, false, true, Unaligned>(buffer);\n        }\n        else {\n          evalTyped<false, false, false, Unaligned>(buffer);\n        }\n      }\n    }\n  }\n\n  template <typename LhsScalar, typename RhsScalar, typename Index, typename LhsMapper, typename RhsMapper, typename OutputMapper> struct LaunchKernels {\n    static void Run(const LhsMapper& lhs, const RhsMapper& rhs, const OutputMapper& output, Index m, Index n, Index k, const GpuDevice& device) {\n    const Index m_blocks = (m + 63) / 64;\n    const Index n_blocks = (n + 63) / 64;\n    const dim3 num_blocks(m_blocks, n_blocks, 1);\n    const dim3 block_size(8, 8, 8);\n    LAUNCH_GPU_KERNEL((EigenContractionKernel<Scalar, Index, LhsMapper, RhsMapper, OutputMapper>), num_blocks, block_size, 0, device, lhs, rhs, output, m, n, k);\n    }\n  };\n\n  template <typename Index, typename LhsMapper, typename RhsMapper, typename OutputMapper> struct LaunchKernels<float, float, Index, LhsMapper, RhsMapper, OutputMapper> {\n    static void Run(const LhsMapper& lhs, const RhsMapper& rhs, const OutputMapper& output, Index m, Index n, Index k, const GpuDevice& device) {\n      if (m < 768 || n < 768) {\n        const Index m_blocks = (m + 63) / 64;\n        const Index n_blocks = (n + 63) / 64;\n        const dim3 num_blocks(m_blocks, n_blocks, 1);\n        const dim3 block_size(16, 16, 1);\n        LAUNCH_GPU_KERNEL((EigenFloatContractionKernel16x16<Index, LhsMapper, RhsMapper, OutputMapper>), num_blocks, block_size, 0, device, lhs, rhs, output, m, n, k);\n      } else {\n        const Index m_blocks = (m + 127) / 128;\n        const Index n_blocks = (n + 63) / 64;\n        const dim3 num_blocks(m_blocks, n_blocks, 1);\n        const dim3 block_size(8, 32, 1);\n        LAUNCH_GPU_KERNEL((EigenFloatContractionKernel<Index, LhsMapper, RhsMapper, OutputMapper>), num_blocks, block_size, 0, device, lhs, rhs, output, m, n, k);\n      }\n    }\n  };\n\n  template <bool lhs_inner_dim_contiguous, bool rhs_inner_dim_contiguous, bool rhs_inner_dim_reordered, int Alignment>\n  void evalTyped(Scalar* buffer) const {\n    // columns in left side, rows in right side\n    const Index k = this->m_k_size;\n    EIGEN_UNUSED_VARIABLE(k)\n\n    // rows in left side\n    const Index m = this->m_i_size;\n\n    // columns in right side\n    const Index n = this->m_j_size;\n\n    // zero out the result buffer (which must be of size at least m * n * sizeof(Scalar))\n    this->m_device.fill(buffer, buffer + m * n, Scalar(0));\n\n    typedef internal::TensorContractionInputMapper<LhsScalar, Index, internal::Lhs,\n                                                   LeftEvaluator, left_nocontract_t,\n                                                   contract_t, 4,\n                                                   lhs_inner_dim_contiguous,\n                                                   false, Unaligned> LhsMapper;\n\n    typedef internal::TensorContractionInputMapper<RhsScalar, Index, internal::Rhs,\n                                                   RightEvaluator, right_nocontract_t,\n                                                   contract_t, 4,\n                                                   rhs_inner_dim_contiguous,\n                                                   rhs_inner_dim_reordered, Unaligned> RhsMapper;\n\n    typedef internal::blas_data_mapper<Scalar, Index, ColMajor> OutputMapper;\n\n\n    // initialize data mappers\n    LhsMapper lhs(this->m_leftImpl, this->m_left_nocontract_strides, this->m_i_strides,\n                  this->m_left_contracting_strides, this->m_k_strides);\n\n    RhsMapper rhs(this->m_rightImpl, this->m_right_nocontract_strides, this->m_j_strides,\n                  this->m_right_contracting_strides, this->m_k_strides);\n\n    OutputMapper output(buffer, m);\n\n#if defined(EIGEN_USE_HIP)\n    setGpuSharedMemConfig(hipSharedMemBankSizeEightByte);\n#else\n    setGpuSharedMemConfig(cudaSharedMemBankSizeEightByte);\n#endif\n\n    LaunchKernels<LhsScalar, RhsScalar, Index, LhsMapper, RhsMapper, OutputMapper>::Run(lhs, rhs, output,  m, n, k, this->m_device);\n  }\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_USE_GPU and EIGEN_GPUCC\n#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_GPU_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionMapper.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_MAPPER_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_MAPPER_H\n\nnamespace Eigen {\n\nnamespace internal {\n\nenum {\n  Rhs = 0,\n  Lhs = 1\n};\n\n/*\n * Implementation of the Eigen blas_data_mapper class for tensors.\n */\n/// The make pointer class is used by sycl in order to build the mapper class on the device. For other platform the default make pointer is used which\n/// is scalar * for CoeffLoader.\ntemplate <typename Tensor, bool HasRawAccess, template <class> class MakePointer_ = MakePointer>\nstruct CoeffLoader;\n\ntemplate <typename Scalar, typename Index, int side, typename Tensor,\n          typename nocontract_t, typename contract_t, int packet_size,\n          bool inner_dim_contiguous, bool inner_dim_reordered, int Alignment,\n          template <class> class MakePointer_ = MakePointer>\nclass BaseTensorContractionMapper;\n\ntemplate <typename Tensor, bool HasRawAccess, template <class> class MakePointer_>\nstruct CoeffLoader {\n  enum {\n    DirectOffsets = false\n  };\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE CoeffLoader(const Tensor& tensor) : m_tensor(tensor) { }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void offsetBuffer(typename Tensor::Index) {\n    eigen_assert(false && \"unsupported\");\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE const typename MakePointer_<const typename Tensor::Scalar>::Type\n  data() const {\n    eigen_assert(false && \"unsupported\");\n    return NULL;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE typename Tensor::Scalar coeff(typename Tensor::Index index) const { return m_tensor.coeff(index); }\n\n template<int LoadMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n typename Tensor::PacketReturnType packet(typename Tensor::Index index) const\n  {\n    return m_tensor.template packet<LoadMode>(index);\n  }\n\n  #ifdef EIGEN_USE_SYCL\n  // The placeholder accessors require to be bound to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_tensor.bind(cgh);\n  }\n  #endif\n\n private:\n  const Tensor m_tensor;\n};\n\ntemplate <typename Tensor, template <class> class MakePointer_>\nstruct CoeffLoader<Tensor, true, MakePointer_> {\n  enum {\n    DirectOffsets = true\n  };\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE CoeffLoader(const Tensor& tensor) : m_data(tensor.data()) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void offsetBuffer(typename Tensor::Index offset) {\n    m_data += offset;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE const typename MakePointer_<const typename Tensor::Scalar>::Type\n  data() const {\n    return m_data;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE typename Tensor::Scalar coeff(typename Tensor::Index index) const { return loadConstant(m_data+index); }\n\n template<int LoadMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n typename Tensor::PacketReturnType packet(typename Tensor::Index index) const\n  {\n    return internal::ploadt_ro<typename Tensor::PacketReturnType, LoadMode>(m_data + index);\n  }\n\n  #ifdef EIGEN_USE_SYCL\n  // The placeholder accessors require to be bound to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_data.bind(cgh);\n  }\n  #endif\n private:\n  typedef typename Tensor::Scalar Scalar;\n\n  typename MakePointer_<const Scalar>::Type m_data;\n};\n\ntemplate<typename Scalar, typename Index, int side,\n         typename Tensor,\n         typename nocontract_t, typename contract_t,\n         int packet_size, bool inner_dim_contiguous, int Alignment, template <class> class MakePointer_ = MakePointer>\nclass SimpleTensorContractionMapper {\n  public:\n  EIGEN_DEVICE_FUNC\n  SimpleTensorContractionMapper(const Tensor& tensor,\n                                const nocontract_t& nocontract_strides,\n                                const nocontract_t& ij_strides,\n                                const contract_t& contract_strides,\n                                const contract_t& k_strides) :\n      m_tensor(tensor),\n      m_nocontract_strides(nocontract_strides),\n      m_ij_strides(ij_strides),\n      m_contract_strides(contract_strides),\n      m_k_strides(k_strides) { }\n\n  enum {\n    DirectOffsets = CoeffLoader<Tensor, Tensor::RawAccess, MakePointer_>::DirectOffsets\n  };\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void offsetBuffer(typename Tensor::Index offset) {\n    m_tensor.offsetBuffer(offset);\n  }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE void prefetch(Index /*i*/) { }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE Scalar operator()(Index row) const {\n    // column major assumption\n    return operator()(row, 0);\n  }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE Scalar operator()(Index row, Index col) const {\n    return m_tensor.coeff(computeIndex(row, col));\n  }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE Index computeIndex(Index row, Index col) const {\n    const bool left = (side == Lhs);\n    EIGEN_UNUSED_VARIABLE(left); // annoying bug in g++8.1: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=85963\n    Index nocontract_val = left ? row : col;\n    Index linidx = 0;\n    EIGEN_UNROLL_LOOP\n    for (int i = static_cast<int>(array_size<nocontract_t>::value) - 1; i > 0; i--) {\n      const Index idx = nocontract_val / m_ij_strides[i];\n      linidx += idx * m_nocontract_strides[i];\n      nocontract_val -= idx * m_ij_strides[i];\n    }\n    if (array_size<typename Tensor::Dimensions>::value > array_size<contract_t>::value) {\n      if (side == Lhs && inner_dim_contiguous) {\n        eigen_assert(m_nocontract_strides[0] == 1);\n        linidx += nocontract_val;\n      } else {\n        linidx += nocontract_val * m_nocontract_strides[0];\n      }\n    }\n\n    Index contract_val = left ? col : row;\n    if(array_size<contract_t>::value > 0) {\n      EIGEN_UNROLL_LOOP\n      for (int i = static_cast<int>(array_size<contract_t>::value) - 1; i > 0; i--) {\n        const Index idx = contract_val / m_k_strides[i];\n        linidx += idx * m_contract_strides[i];\n        contract_val -= idx * m_k_strides[i];\n      }\n\n      if (side == Rhs && inner_dim_contiguous) {\n        eigen_assert(m_contract_strides[0] == 1);\n        linidx += contract_val;\n      } else {\n        linidx += contract_val * m_contract_strides[0];\n      }\n    }\n\n    return linidx;\n  }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE IndexPair<Index> computeIndexPair(Index row, Index col, const Index distance) const {\n    const bool left = (side == Lhs);\n    EIGEN_UNUSED_VARIABLE(left); // annoying bug in g++8.1: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=85963\n    Index nocontract_val[2] = {left ? row : col, left ? row + distance : col};\n    Index linidx[2] = {0, 0};\n    if (array_size<typename Tensor::Dimensions>::value > array_size<contract_t>::value) {\n      EIGEN_UNROLL_LOOP\n      for (int i = static_cast<int>(array_size<nocontract_t>::value) - 1; i > 0; i--) {\n        const Index idx0 = nocontract_val[0] / m_ij_strides[i];\n        const Index idx1 = nocontract_val[1] / m_ij_strides[i];\n        linidx[0] += idx0 * m_nocontract_strides[i];\n        linidx[1] += idx1 * m_nocontract_strides[i];\n        nocontract_val[0] -= idx0 * m_ij_strides[i];\n        nocontract_val[1] -= idx1 * m_ij_strides[i];\n      }\n      if (side == Lhs && inner_dim_contiguous) {\n        eigen_assert(m_nocontract_strides[0] == 1);\n        linidx[0] += nocontract_val[0];\n        linidx[1] += nocontract_val[1];\n      } else {\n        linidx[0] += nocontract_val[0] * m_nocontract_strides[0];\n        linidx[1] += nocontract_val[1] * m_nocontract_strides[0];\n      }\n    }\n\n    Index contract_val[2] = {left ? col : row, left ? col : row + distance};\n    if (array_size<contract_t>::value> 0) {\n      EIGEN_UNROLL_LOOP\n      for (int i = static_cast<int>(array_size<contract_t>::value) - 1; i > 0; i--) {\n        const Index idx0 = contract_val[0] / m_k_strides[i];\n        const Index idx1 = contract_val[1] / m_k_strides[i];\n        linidx[0] += idx0 * m_contract_strides[i];\n        linidx[1] += idx1 * m_contract_strides[i];\n        contract_val[0] -= idx0 * m_k_strides[i];\n        contract_val[1] -= idx1 * m_k_strides[i];\n      }\n\n      if (side == Rhs && inner_dim_contiguous) {\n        eigen_assert(m_contract_strides[0] == 1);\n        linidx[0] += contract_val[0];\n        linidx[1] += contract_val[1];\n      } else {\n        linidx[0] += contract_val[0] * m_contract_strides[0];\n        linidx[1] += contract_val[1] * m_contract_strides[0];\n      }\n    }\n    return IndexPair<Index>(linidx[0], linidx[1]);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Index firstAligned(Index size) const {\n    // Only claim alignment when we can compute the actual stride (ie when we're\n    // dealing with the lhs with inner_dim_contiguous. This is because the\n    // matrix-vector product relies on the stride when dealing with aligned inputs.\n    return (Alignment == Aligned) && (side == Lhs) && inner_dim_contiguous ? 0 : size;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Index stride() const {\n    return ((side == Lhs) && inner_dim_contiguous && array_size<contract_t>::value > 0) ? m_contract_strides[0] : 1;\n  }\n\n  #ifdef EIGEN_USE_SYCL\n  // The placeholder accessors require to be bound to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_tensor.bind(cgh);\n  }\n  #endif\n\n  const CoeffLoader<Tensor, Tensor::RawAccess, MakePointer_>& tensor() const {\n    return m_tensor;\n  }\n\n  const nocontract_t& nocontract_strides() const {\n    return m_nocontract_strides;\n  }\n  const nocontract_t& ij_strides() const { return m_ij_strides; }\n  const contract_t& contract_strides() const { return m_contract_strides; }\n  const contract_t& k_strides() const { return m_k_strides; }\n\n protected:\n  CoeffLoader<Tensor, Tensor::RawAccess, MakePointer_> m_tensor;\n  const nocontract_t m_nocontract_strides;\n  const nocontract_t m_ij_strides;\n  const contract_t m_contract_strides;\n  const contract_t m_k_strides;\n};\n\ntemplate<typename Scalar, typename Index, int side,\n         typename Tensor,\n         typename nocontract_t, typename contract_t,\n         int packet_size, bool inner_dim_contiguous,\n         bool inner_dim_reordered, int Alignment, template <class> class MakePointer_>\nclass BaseTensorContractionMapper : public SimpleTensorContractionMapper<Scalar, Index, side, Tensor, nocontract_t, contract_t, packet_size, inner_dim_contiguous, Alignment, MakePointer_>\n{\n public:\n  typedef SimpleTensorContractionMapper<Scalar, Index, side, Tensor, nocontract_t, contract_t, packet_size, inner_dim_contiguous, Alignment, MakePointer_> ParentMapper;\n\n  EIGEN_DEVICE_FUNC\n  BaseTensorContractionMapper(const Tensor& tensor,\n                              const nocontract_t& nocontract_strides,\n                              const nocontract_t& ij_strides,\n                              const contract_t& contract_strides,\n                              const contract_t& k_strides) :\n  ParentMapper(tensor, nocontract_strides, ij_strides, contract_strides, k_strides) { }\n\n  template <typename PacketT,int AlignmentType>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  typename internal::enable_if<internal::unpacket_traits<PacketT>::size==packet_size,PacketT>::type\n  load(Index i, Index j) const\n  {\n    // whole method makes column major assumption\n\n    // don't need to add offsets for now (because operator handles that)\n    // current code assumes packet size must be a multiple of 2\n    EIGEN_STATIC_ASSERT(packet_size % 2 == 0, YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    if (Tensor::PacketAccess && inner_dim_contiguous && !inner_dim_reordered) {\n      const Index index = this->computeIndex(i, j);\n      eigen_assert(this->computeIndex(i+packet_size-1, j) == index + packet_size-1);\n      return this->m_tensor.template packet<AlignmentType>(index);\n    }\n\n    const IndexPair<Index> indexPair = this->computeIndexPair(i, j, packet_size - 1);\n    const Index first = indexPair.first;\n    const Index lastIdx = indexPair.second;\n\n    // We can always do optimized packet reads from left hand side right now, because\n    // the vertical matrix dimension on the left hand side is never contracting.\n    // On the right hand side we need to check if the contracting dimensions may have\n    // been shuffled first.\n    if (Tensor::PacketAccess &&\n        (side == Lhs || internal::array_size<contract_t>::value <= 1 || !inner_dim_reordered) &&\n        (lastIdx - first) == (packet_size - 1)) {\n\n      return this->m_tensor.template packet<AlignmentType>(first);\n    }\n\n    EIGEN_ALIGN_MAX Scalar data[packet_size];\n\n    data[0] = this->m_tensor.coeff(first);\n    EIGEN_UNROLL_LOOP\n    for (Index k = 1; k < packet_size - 1; k += 2) {\n      const IndexPair<Index> internal_pair = this->computeIndexPair(i + k, j, 1);\n      data[k] = this->m_tensor.coeff(internal_pair.first);\n      data[k + 1] = this->m_tensor.coeff(internal_pair.second);\n    }\n    data[packet_size - 1] = this->m_tensor.coeff(lastIdx);\n\n    return pload<PacketT>(data);\n  }\n\n  template <typename PacketT,int AlignmentType>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  typename internal::enable_if<internal::unpacket_traits<PacketT>::size!=packet_size,PacketT>::type\n  load(Index i, Index j) const\n  {\n    const Index requested_packet_size = internal::unpacket_traits<PacketT>::size;\n    EIGEN_ALIGN_MAX Scalar data[requested_packet_size];\n\n    const IndexPair<Index> indexPair = this->computeIndexPair(i, j, requested_packet_size - 1);\n    const Index first = indexPair.first;\n    const Index lastIdx = indexPair.second;\n\n    data[0] = this->m_tensor.coeff(first);\n    for (Index k = 1; k < requested_packet_size - 1; k += 2) {\n      const IndexPair<Index> internal_pair = this->computeIndexPair(i + k, j, 1);\n      data[k] = this->m_tensor.coeff(internal_pair.first);\n      data[k + 1] = this->m_tensor.coeff(internal_pair.second);\n    }\n    data[requested_packet_size - 1] = this->m_tensor.coeff(lastIdx);\n\n    return pload<PacketT>(data);\n  }\n\n  template <typename PacketT,int AlignmentType>\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE PacketT loadPacket(Index i, Index j) const {\n    return this->load<PacketT,AlignmentType>(i,j);\n  }\n};\n\n\ntemplate<typename Scalar, typename Index, int side,\n         typename Tensor,\n         typename nocontract_t, typename contract_t,\n         bool inner_dim_contiguous,\n         bool inner_dim_reordered, int Alignment, template <class> class MakePointer_>\nclass BaseTensorContractionMapper<Scalar, Index, side, Tensor, nocontract_t, contract_t, 1, inner_dim_contiguous, inner_dim_reordered, Alignment, MakePointer_>\n  : public SimpleTensorContractionMapper<Scalar, Index, side, Tensor, nocontract_t, contract_t, 1, inner_dim_contiguous, Alignment, MakePointer_>\n{\n public:\n  typedef SimpleTensorContractionMapper<Scalar, Index, side, Tensor, nocontract_t, contract_t, 1, inner_dim_contiguous, Alignment, MakePointer_> ParentMapper;\n\n  EIGEN_DEVICE_FUNC\n  BaseTensorContractionMapper(const Tensor& tensor,\n                              const nocontract_t& nocontract_strides,\n                              const nocontract_t& ij_strides,\n                              const contract_t& contract_strides,\n                              const contract_t& k_strides) :\n  ParentMapper(tensor, nocontract_strides, ij_strides, contract_strides, k_strides) { }\n\n  template <typename PacketT,int> EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE PacketT loadPacket(Index i, Index j) const {\n    EIGEN_ALIGN_MAX Scalar data[1];\n    data[0] = this->m_tensor.coeff(this->computeIndex(i, j));\n    return pload<PacketT>(data);\n  }\n  template <typename PacketT,int> EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE PacketT load(Index i, Index j) const {\n    EIGEN_ALIGN_MAX Scalar data[1];\n    data[0] = this->m_tensor.coeff(this->computeIndex(i, j));\n    return pload<PacketT>(data);\n  }\n};\n\n\ntemplate<typename Scalar, typename Index, int side,\n         typename Tensor,\n         typename nocontract_t, typename contract_t,\n         int packet_size,\n         bool inner_dim_contiguous, bool inner_dim_reordered, int Alignment, template <class> class MakePointer_=MakePointer>\nclass TensorContractionSubMapper {\n public:\n\n  typedef BaseTensorContractionMapper<Scalar, Index, side, Tensor, nocontract_t, contract_t, packet_size, inner_dim_contiguous, inner_dim_reordered, Alignment, MakePointer_> ParentMapper;\n  typedef TensorContractionSubMapper<Scalar, Index, side, Tensor, nocontract_t, contract_t, packet_size, inner_dim_contiguous, inner_dim_reordered, Alignment, MakePointer_> Self;\n  typedef Self LinearMapper;\n\n  enum {\n    // We can use direct offsets iff the parent mapper supports then and we can compute the strides.\n    // TODO: we should also enable direct offsets for the Rhs case.\n    UseDirectOffsets = ParentMapper::DirectOffsets && (side == Lhs) && inner_dim_contiguous && (array_size<contract_t>::value > 0)\n  };\n\n  EIGEN_DEVICE_FUNC TensorContractionSubMapper(const ParentMapper& base_mapper, Index vert_offset, Index horiz_offset)\n      : m_base_mapper(base_mapper), m_vert_offset(vert_offset), m_horiz_offset(horiz_offset) {\n    // Bake the offsets into the buffer used by the base mapper whenever possible. This avoids the need to recompute\n    // this offset every time we attempt to access a coefficient.\n    if (UseDirectOffsets) {\n      Index stride = m_base_mapper.stride();\n      m_base_mapper.offsetBuffer(vert_offset + horiz_offset * stride);\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Scalar operator()(Index i) const {\n    if (UseDirectOffsets) {\n      return m_base_mapper(i, 0);\n    }\n    return m_base_mapper(i + m_vert_offset, m_horiz_offset);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Scalar operator()(Index i, Index j) const {\n    if (UseDirectOffsets) {\n      return m_base_mapper(i, j);\n    }\n    return m_base_mapper(i + m_vert_offset, j + m_horiz_offset);\n  }\n\n  template <typename PacketT>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketT loadPacket(Index i) const {\n    if (UseDirectOffsets) {\n      return m_base_mapper.template loadPacket<PacketT,Alignment>(i, 0);\n    }\n    return m_base_mapper.template loadPacket<PacketT,Alignment>(i + m_vert_offset, m_horiz_offset);\n  }\n\n  template <typename PacketT>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketT loadPacket(Index i, Index j) const {\n    if (UseDirectOffsets) {\n      return m_base_mapper.template loadPacket<PacketT,Alignment>(i, j);\n    }\n    return m_base_mapper.template loadPacket<PacketT,Alignment>(i + m_vert_offset, j + m_horiz_offset);\n  }\n\n  template <typename PacketT, int AlignmentType>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketT loadPacket(Index i, Index j) const {\n    if (UseDirectOffsets) {\n      return m_base_mapper.template load<PacketT,AlignmentType>(i, j);\n    }\n    return m_base_mapper.template loadPacket<PacketT,AlignmentType>(i + m_vert_offset, j + m_horiz_offset);\n  }\n\n  template <typename PacketT>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void storePacket(Index i, const PacketT& p) const {\n    if (UseDirectOffsets) {\n      m_base_mapper.storePacket(i, 0, p);\n    }\n    m_base_mapper.storePacket(i + m_vert_offset, m_horiz_offset, p);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE LinearMapper getLinearMapper(Index i, Index j) const {\n    if (UseDirectOffsets) {\n      return LinearMapper(m_base_mapper, i, j);\n    }\n    return LinearMapper(m_base_mapper, i + m_vert_offset, j + m_horiz_offset);\n  }\n\n  template <typename PacketT, int AlignmentType>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketT load(Index i) const {\n    EIGEN_STATIC_ASSERT((internal::is_same<PacketT, PacketT>::value), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    const int ActualAlignment = (AlignmentType == Aligned) && (Alignment == Aligned) ? Aligned : Unaligned;\n    if (UseDirectOffsets) {\n     return m_base_mapper.template loadPacket<PacketT,ActualAlignment>(i, 0);\n    }\n    return m_base_mapper.template loadPacket<PacketT,ActualAlignment>(i + m_vert_offset, m_horiz_offset);\n  }\n\n  template <typename PacketT>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool aligned(Index) const {\n    return false;\n  }\n\n  #ifdef EIGEN_USE_SYCL\n  // The placeholder accessors require to be bound to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_base_mapper.bind(cgh);\n  }\n  #endif\n\n  const ParentMapper& base_mapper() const { return m_base_mapper; }\n  Index vert_offset() const { return m_vert_offset; }\n  Index horiz_offset() const { return m_horiz_offset; }\n\n private:\n  ParentMapper m_base_mapper;\n  const Index m_vert_offset;\n  const Index m_horiz_offset;\n};\n\n\ntemplate<typename Scalar_, typename Index, int side,\n         typename Tensor,\n         typename nocontract_t, typename contract_t,\n         int packet_size,\n         bool inner_dim_contiguous, bool inner_dim_reordered, int Alignment,  template <class> class MakePointer_=MakePointer>\nclass TensorContractionInputMapper\n  : public BaseTensorContractionMapper<Scalar_, Index, side, Tensor, nocontract_t, contract_t, packet_size, inner_dim_contiguous, inner_dim_reordered, Alignment, MakePointer_> {\n\n public:\n  typedef Scalar_ Scalar;\n  typedef BaseTensorContractionMapper<Scalar, Index, side, Tensor, nocontract_t, contract_t, packet_size, inner_dim_contiguous, inner_dim_reordered, Alignment, MakePointer_> Base;\n  typedef TensorContractionSubMapper<Scalar, Index, side, Tensor, nocontract_t, contract_t, packet_size, inner_dim_contiguous, inner_dim_reordered, Alignment, MakePointer_> SubMapper;\n  typedef SubMapper VectorMapper;\n\n  EIGEN_DEVICE_FUNC TensorContractionInputMapper(const Tensor& tensor,\n                               const nocontract_t& nocontract_strides,\n                               const nocontract_t& ij_strides,\n                               const contract_t& contract_strides,\n                               const contract_t& k_strides)\n      : Base(tensor, nocontract_strides, ij_strides, contract_strides, k_strides) { }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE SubMapper getSubMapper(Index i, Index j) const {\n    return SubMapper(*this, i, j);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE VectorMapper getVectorMapper(Index i, Index j) const {\n    return VectorMapper(*this, i, j);\n  }\n  \n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE const CoeffLoader<Tensor, Tensor::RawAccess, MakePointer_>& get_tensor() const {\n    return Base::m_tensor;\n  }\n};\n\n\ntemplate <typename T> struct TensorContractionInputMapperTrait;\n\ntemplate<typename Scalar_, typename Index_, int side_,\n         typename Tensor_,\n         typename nocontract_t_, typename contract_t_,\n         int packet_size_,\n         bool inner_dim_contiguous_, bool inner_dim_reordered_, int Alignment_,  template <class> class MakePointer_>\nstruct TensorContractionInputMapperTrait<TensorContractionInputMapper<Scalar_, Index_, side_, Tensor_, \n                                                    nocontract_t_, contract_t_, packet_size_, inner_dim_contiguous_, \n                                                    inner_dim_reordered_, Alignment_, MakePointer_> > {\n\n      typedef Tensor_ XprType;\n      static const bool  inner_dim_contiguous = inner_dim_contiguous_;\n      static const bool  inner_dim_reordered = inner_dim_reordered_;\n  };  \n\n\n}  // end namespace internal\n}  // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_MAPPER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionSycl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library for linear algebra.\n//\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla Public License v. 2.0. If a copy of the MPL was not\n// distributed with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/*****************************************************************\n * TensorContractionSycl.h\n *\n * \\brief:\n *  TensorContractionSycl.h, provides various tensor contraction kernel for SYCL backend\n *\n *****************************************************************/\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_SYCL_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_SYCL_H\n\nnamespace Eigen {\n\nnamespace TensorSycl {\nnamespace internal {\n\n#ifndef EIGEN_SYCL_DISABLE_GEMV\n/*!\n * \\brief TVPanelSize, a template class used for setting the panel size required for launching General TensorVector\n * contraction kernel on various hardware devices.\n *\n * \\tparam Scalar: determines the element type of the tensor/vector\n *\n * \\tparam StorageIndex  determines the Index type.\n *\n * \\tparam NCWindow: determines the number of non-contracting element to be process by each work-group\n *\n * \\tparam CFactor: determines the number of contracting element to be process by each thread\n *\n * \\tparam NCFactor: determines the number of non-contracting element to be process by each thread\n */\ntemplate <typename Scalar, typename StorageIndex, StorageIndex NCWindow, StorageIndex CFactor, StorageIndex NCFactor>\nstruct TVPanelSize {\n  // LocalThreadSizeC: determines total number of thread per workgroup for the contracting dimension\n  static EIGEN_CONSTEXPR StorageIndex LocalThreadSizeC = EIGEN_SYCL_LOCAL_THREAD_DIM0;\n  // LocalThreadSizeNC: determines total number of thread per workgroup for the non-contracting dimension\n  static EIGEN_CONSTEXPR StorageIndex LocalThreadSizeNC = EIGEN_SYCL_LOCAL_THREAD_DIM1;\n  // TileSizeDimNC: determines the tile size for the non-contracting dimension\n  static EIGEN_CONSTEXPR StorageIndex TileSizeDimNC = NCWindow / NCFactor;\n  // TileSizeDimC: determines the tile size for the contracting dimension\n  static EIGEN_CONSTEXPR StorageIndex TileSizeDimC = CFactor * LocalThreadSizeNC * LocalThreadSizeC;\n  // WorkLoadPerThreadNC : determines workload per thread for loading the non-contracting dimension\n  static EIGEN_CONSTEXPR StorageIndex WorkLoadPerThreadNC = TileSizeDimNC / LocalThreadSizeNC;\n  // WorkLoadPerThreadC: determines workload per thread for loading the non-contracting dimension\n  static EIGEN_CONSTEXPR StorageIndex WorkLoadPerThreadC = TileSizeDimC / LocalThreadSizeC;\n  // BC : determines if supporting bank conflict is required\n  static EIGEN_CONSTEXPR bool BC = false;\n};\n#endif\n\n/*!\n * \\brief TTPanelSize, a template class used for setting the panel size required for launching General Tensor Tensor\n contraction kernel on various hardware devices.\n *\n * \\tparam Scalar: determines the element type of the tensor\n *\n * \\tparam StorageIndex: determines the Index type.\n *\n * \\tparam REG_SIZE_M: determines workload per thread for loading the M dimension This can be varied based on the\n available register on a chosen device(can be controlled by EIGEN_SYCL_REG_M macro).\n *\n * \\tparam REG_SIZE_N: determines workload per thread for loading the N dimension This can be varied based on the\n available register on a chosen device(can be controlled by EIGEN_SYCL_REG_N macro).\n *\n * \\tparam TSDK: determines Tile size for dimension K. The packet size is assumed to be considered\n */\n\ntemplate <typename Scalar, typename StorageIndex, StorageIndex REG_SIZE_M, StorageIndex REG_SIZE_N, StorageIndex TSDK>\nstruct TTPanelSize {\n  // TileSizeDimK: determines Tile size for dimension K. The packet size is assumed to be considered\n  static EIGEN_CONSTEXPR StorageIndex TileSizeDimK = TSDK;\n  // WorkLoadPerThreadM : determines workload per thread for loading the M dimension This can be varied based on the\n  // available register on a chosen device(can be controlled by EIGEN_SYCL_REG_M macro//\n#ifndef EIGEN_SYCL_REG_M\n  static EIGEN_CONSTEXPR StorageIndex WorkLoadPerThreadM = REG_SIZE_M;\n#else\n  static EIGEN_CONSTEXPR StorageIndex WorkLoadPerThreadM = EIGEN_SYCL_REG_M;\n#endif\n// WorkLoadPerThreadN : determines workload per thread for loading the N dimension This can be varied based on the\n// available register on a chosen device(can be controlled by EIGEN_SYCL_REG_N macro\n#ifndef EIGEN_SYCL_REG_N\n  static EIGEN_CONSTEXPR StorageIndex WorkLoadPerThreadN = REG_SIZE_N;\n#else\n  static EIGEN_CONSTEXPR StorageIndex WorkLoadPerThreadN = EIGEN_SYCL_REG_N;\n#endif\n  // LocalThreadSizeM: determines total number of thread per workgroup for the m dimension\n  static EIGEN_CONSTEXPR StorageIndex LocalThreadSizeM = EIGEN_SYCL_LOCAL_THREAD_DIM0;\n  // LocalThreadSizeN: determines total number of thread per workgroup for the n dimension\n  static EIGEN_CONSTEXPR StorageIndex LocalThreadSizeN = EIGEN_SYCL_LOCAL_THREAD_DIM1;\n  // TileSizeDimM: determines the tile size for the m dimension\n  static EIGEN_CONSTEXPR StorageIndex TileSizeDimM = LocalThreadSizeM * WorkLoadPerThreadM;\n  // TileSizeDimN: determines the tile size for the n dimension\n  static EIGEN_CONSTEXPR StorageIndex TileSizeDimN = LocalThreadSizeN * WorkLoadPerThreadN;\n  // LoadPerThreadLhs: determines workload per thread for loading Lhs Tensor. This must be divisable by packetsize\n  static EIGEN_CONSTEXPR StorageIndex LoadPerThreadLhs =\n      ((TileSizeDimK * WorkLoadPerThreadM * WorkLoadPerThreadN) / (TileSizeDimN));\n  // LoadPerThreadRhs: determines workload per thread for loading Rhs Tensor. This must be divisable by packetsize\n  static EIGEN_CONSTEXPR StorageIndex LoadPerThreadRhs =\n      ((TileSizeDimK * WorkLoadPerThreadM * WorkLoadPerThreadN) / (TileSizeDimM));\n  // BC : determines if supporting bank conflict is required\n  static EIGEN_CONSTEXPR bool BC = true;\n  // DoubleBuffer: determines if double buffering technique should be used (This can be disabled by\n  // EIGEN_SYCL_DISABLE_DOUBLE_BUFFER macro when the device doesnot have sufficient  local memory)\n  static EIGEN_CONSTEXPR bool DoubleBuffer =\n#ifdef EIGEN_SYCL_DISABLE_DOUBLE_BUFFER\n      false;\n#else\n      true;\n#endif\n};\n\n/* !\n * \\brief contraction_type: an enum class representing the Tensor Contraction implementation algorithm. This is used to\n * specialize the contraction algorithm based on device support for dedicated local memory.\n */\nenum class contraction_type { local, no_local };\n/* !\n * \\brief data_source an enum class determining the location of the data in a memory hierarchy (global, local, private).\n */\nenum class data_source { global_mem, local_mem, private_mem };\n\n/*!\n * \\brief read, a template function used for loading the data from global\n memory. This function is used to guarantee coalesced and vectorized load whenever possible\n *\n * \\tparam PacketLoad: determines if the each element of this tensor block should be loaded in a packet mode\n *\n * \\param is_coalesced_layout: determines whether or not the Tensor data in a memory can be access coalesced and\n vectorized when possible. Coalesced memory access is a key factor in Kernel performance. When a tensor is 2d and the\n contracting dimension is 1, it is always possible to accessed tensor data coalesced and vectorized. This is the case\n when RHS(right hand side) Tensor is transposed or when LHS(left hand side) Tensor is not transposed.\n *\n * \\tparam PacketType:  determines the type of packet\n *\n * \\tparam TensorMapper: determines the input tensor mapper type\n *\n * \\tparam StorageIndex: determines the Index type\n\n * \\param tensorMapper: is the input tensor\n *\n * \\param NCIndex: is the non-contracting dim index\n *\n * \\param CIndex is the contracting dim index\n *\n * \\param ld: is the leading dimension of the flattened tensor\n */\ntemplate <bool PacketLoad, bool is_coalesced_layout, bool, typename PacketType, typename TensorMapper,\n          typename StorageIndex>\nstatic EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename ::Eigen::internal::enable_if<PacketLoad, PacketType>::type read(\n    const TensorMapper &tensorMapper, const StorageIndex &NCIndex, const StorageIndex &CIndex, const StorageIndex &ld) {\n  const StorageIndex row = (is_coalesced_layout) ? NCIndex : CIndex;\n  const StorageIndex col = (is_coalesced_layout) ? CIndex : NCIndex;\n  return tensorMapper.get_tensor().template packet<Unaligned>(row + (col * ld));\n}\n\n/*!\n * \\brief read, special overload of read function, when the read access is not vectorized\n *\n * \\tparam PacketLoad: determines if the each element of this tensor block should be loaded in a packet mode\n *\n * \\param is_coalesced_layout: determines whether or not the Tensor data in a memory can be access coalesced and\n  vectorized when possible. Coalesced memory access is a key factor in Kernel performance. When a tensor is 2d and the\n  contracting dimension is 1, it is always possible to accessed tensor data coalesced and vectorized. This is the case\n  when RHS(right hand side) Tensor is transposed or when LHS(left hand side) Tensor is not transposed.\n *\n * \\tparam PacketType: determines the type of packet\n *\n * \\tparam TensorMapper: determines the input tensor mapper type\n *\n * \\tparam StorageIndex: determines the Index type\n\n * \\param tensorMapper: is the input tensor\n *\n * \\param NCIndex: is the non-contracting dim index\n *\n * \\param CIndex: is the contracting dim index\n */\ntemplate <bool PacketLoad, bool, bool IsRhs, typename PacketType, typename TensorMapper, typename StorageIndex>\nstatic EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename ::Eigen::internal::enable_if<!PacketLoad, PacketType>::type read(\n    const TensorMapper &tensorMapper, const StorageIndex &NCIndex, const StorageIndex &CIndex, const StorageIndex &) {\n  const StorageIndex row = (IsRhs) ? CIndex : NCIndex;\n  const StorageIndex col = (IsRhs) ? NCIndex : CIndex;\n  return tensorMapper(row, col);\n}\n\n/*!\n * \\brief write, a template function used for storing the data to local memory. This function is used to guarantee\n * coalesced and vectorized store whenever possible.\n *\n * \\tparam StorageIndex: determines the Index type\n *\n * \\param ld is the leading dimension of the local memory. ld is a compile time value for the local memory\n *\n * \\tparam data_source: an enum value representing if the location of the data in a memory hierarchy.\n *\n * \\tparam PacketType:  determines the type of packet\n *\n * \\tparam DataScalar: determines the output data type\n *\n * \\param packet_data: the data to be written in the local memory\n *\n * \\param ptr: a pointer to the local memory\n *\n * \\param CIndex is the contracting dim index\n */\n\ntemplate <typename StorageIndex, StorageIndex ld, data_source dt, typename PacketType, typename DataScalar>\nstatic EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    typename ::Eigen::internal::enable_if<dt != data_source::global_mem, void>::type\n    write(PacketType &packet_data, DataScalar ptr) {\n  EIGEN_CONSTEXPR int PacketSize = Eigen::internal::unpacket_traits<PacketType>::size;\n  EIGEN_UNROLL_LOOP\n  for (int i = 0; i < PacketSize; i++) {\n    *ptr = PacketWrapper<PacketType, PacketSize>::scalarize(i, packet_data);\n    ptr += ld;\n  }\n}\n\n/*!\n * \\brief Overloading the write function for storing the data to global memory, when vectorization enabled This function\n * is used to guarantee coalesced and vectorized store whenever possible.\n *\n * \\tparam data_source: an enum value representing if the location of the data in a memory hierarchy.\n *\n * \\tparam PacketType:  determines the type of packet\n *\n * \\tparam DataScalar: determines the output data type\n *\n * \\param packet_data: the data to be written in the local memory\n *\n * \\param ptr: a pointer to the local memory\n */\n\ntemplate <data_source dt, typename PacketType, typename DataScalar>\nstatic EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename ::Eigen::internal::enable_if<\n    Eigen::internal::unpacket_traits<PacketType>::size != 1 && dt == data_source::global_mem, void>::type\nwrite(PacketType &packet_data, DataScalar *ptr) {\n  ::Eigen::internal::pstoreu<DataScalar, PacketType>(ptr, packet_data);\n}\n\n/*!\n * \\brief Overloading the write function for storing the data to global memory, when vectorization is disabled.\n *\n * \\tparam data_source: an enum value representing if the location of the data in a memory hierarchy.\n *\n * \\tparam PacketType:  determines the type of packet\n *\n * \\tparam DataScalar: determines the output data type\n *\n * \\param packet_data: the data to be written in the local memory\n *\n * \\param ptr: a pointer to the local memory\n */\ntemplate <data_source dt, typename PacketType, typename DataScalar>\nstatic EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename ::Eigen::internal::enable_if<\n    Eigen::internal::unpacket_traits<PacketType>::size == 1 && dt == data_source::global_mem, void>::type\nwrite(PacketType &packet_data, DataScalar *ptr) {\n  *ptr = packet_data;\n}\n\n/*!\n * \\brief check_boundary: is used to check the edge condition for non-internal blocks.\n *\n * \\tparam is_internal: determines if the block is internal\n */\ntemplate <bool is_internal>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool check_boundary(bool) {\n  return true;\n}\n\n/*!\n * \\brief check_boundary: specialization of the check_boundary for non-internal blocks.\n *\n * \\param cond: true when the data is in range. Otherwise false\n */\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool check_boundary<false>(bool cond) {\n  return cond;\n}\n\n/*!\n * \\brief BlockProperties is a template class that provides different characteristic of a block of each Tensor processed\n * by each workgroup.\n *\n * \\tparam is_transposed: iff true, determines whether or not the block of the Tensor is transposed\n *\n * \\tparam packet_load_: determines if the each element of this tensor block should be loaded in a packet mode\n *\n * \\tparam PacketType:  determines the type of packet\n *\n * \\tparam OutType: determines the type of each element for this block of tensor. If packet load is true, it will be\n * packetType; Otherwise it will be scalar Type\n *\n * \\param elements_per_access determines the size of each element based on OutType\n *\n * \\param is_coalesced_layout  determines whether or not the Tensor data in a memory can be access coalesced and\n * vectorized when possible. Coalesced memory access is a key factor in Kernel performance. When a tensor is 2d and the\n * contracting dimension is 1, it is always possible to accessed tensor data coalesced and vectorized. This is the case\n * when RHS(right hand side) Tensor is transposed or when LHS(left hand side) Tensor is not transposed.\n *\n * \\param nc_stride determines the stride of non-contracting dimension to access the next adjustment element within the\n * Tensor Block for each workgroup\n *\n * \\param c_stride  determines the stride of contracting dimension to access the next adjustment element within the\n * Tensor Block for each workgroup\n */\ntemplate <bool is_transposed, bool is_rhs_, bool packet_load_, typename PacketType>\nstruct BlockProperties {\n  static EIGEN_CONSTEXPR bool packet_load = packet_load_;\n  typedef typename Eigen::internal::unpacket_traits<PacketType>::type OutScalar;\n  static EIGEN_CONSTEXPR bool is_rhs = is_rhs_;\n  typedef typename Eigen::internal::conditional<packet_load, PacketType, OutScalar>::type OutType;\n  static EIGEN_CONSTEXPR int elements_per_access = Eigen::internal::unpacket_traits<OutType>::size;\n  static EIGEN_CONSTEXPR bool is_coalesced_layout = !(is_transposed ^ is_rhs);\n  static EIGEN_CONSTEXPR int nc_stride = (is_coalesced_layout ? elements_per_access : 1);\n  static EIGEN_CONSTEXPR int c_stride = (is_coalesced_layout ? 1 : elements_per_access);\n};\n\n/*!\n * \\brief ThreadProperties is a template class that provides each thread's properties within a workgroup.  Please see\n * the sycl-1.2.1 specification (https://www.khronos.org/registry/SYCL/specs/sycl-1.2.1.pdf) for the workgroup,\n * work-items\n *\n * \\tparam StorageIndex: determines the StorageIndex Type\n *\n * \\param linearLocalThreadId: determines the linearized location of a thread within a work-group\n *\n * \\param kGroupId: determines the logical group id in a k dimension of the flattened tensor. It will be > 1 when\n * tall/skinny algorithm is used\n *\n * \\param mGroupOffset: determines the logical start position of all thread within a workgroup for the m dimension of\n * the flattened tensor.\n *\n * \\param kGroupOffset determines the logical start position of all thread within a workgroup for the k dimension of the\n * flattened tensor. It will be > 1 when tall/skinny algorithm is used.\n *\n * \\param mLocalOffset: determines the logical start position of each thread within a workgroup for the m dimension of a\n * flattened tensor. The position determines the distance of each thread within the workgroup from each other\n * independent from their global position.\n *\n * \\param nLocalOffset: determines the logical start position of each thread within a workgroup for the n dimension of a\n * flattened tensor. The position determines the distance of each thread within the workgroup from each other\n * independent from their global position.\n *\n * \\param mGlobalOffset: determines the logical start position of each thread a thread for the m dimension on a\n * flattened tensor\n *\n * \\param nGlobalOffset: determines the logical start position of each thread a thread for the n dimension on a\n * flattened tensor\n *\n * \\param kSize : determine the number of the k elements of the flattened Tensor to be processed by each thread for the\n * given tensor block. This is !=K dimension of Flattened Tensor when Tall/Skinny matrix is used.\n *\n * \\param is_internal : this will determined if the thread within the work-group computes an internal block of tensor or\n * the edge blocks. When it is internal, there is no need to check the boundaries and all the if stantement can be\n * resolve by compiler.\n */\ntemplate <typename StorageIndex>\nstruct ThreadProperties {\n  const StorageIndex linearLocalThreadId;\n  const StorageIndex kGroupId;\n  const StorageIndex mGroupOffset;\n  const StorageIndex nGroupOffset;\n  const StorageIndex kGroupOffset;\n  const StorageIndex mLocalOffset;\n  const StorageIndex nLocalOffset;\n  const StorageIndex mGlobalOffset;\n  const StorageIndex nGlobalOffset;\n  StorageIndex kSize;\n  const bool is_internal;\n  // this is used to adjust the last block\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ThreadProperties(\n      const StorageIndex linearLocalThreadId_, const StorageIndex kGroupId_, const StorageIndex mGroupOffset_,\n      const StorageIndex nGroupOffset_, const StorageIndex kGroupOffset_, const StorageIndex mLocalOffset_,\n      const StorageIndex nLocalOffset_, const StorageIndex mGlobalOffset_, const StorageIndex nGlobalOffset_,\n      StorageIndex kSize_, const bool is_internal_)\n      : linearLocalThreadId(linearLocalThreadId_),\n        kGroupId(kGroupId_),\n        mGroupOffset(mGroupOffset_),\n        nGroupOffset(nGroupOffset_),\n        kGroupOffset(kGroupOffset_),\n        mLocalOffset(mLocalOffset_),\n        nLocalOffset(nLocalOffset_),\n        mGlobalOffset(mGlobalOffset_),\n        nGlobalOffset(nGlobalOffset_),\n        kSize(kSize_),\n        is_internal(is_internal_) {}\n};\n\n/*!\n * \\brief TensorContractionKernel is a template class that provides Tensor -Tensor contraction operation.\n *\n * \\tparam OutScalar: determines the output scalar type\n *\n * \\tparam LhsScalar: determines the left-hand-side scalar type\n *\n * \\tparam RhsScalar: determines the right-hand-side scalar type\n *\n * \\tparam OutAccessor: determines the sycl accessor type for out put (please see the sycl-1.2.1 specification\n (https://www.khronos.org/registry/SYCL/specs/sycl-1.2.1.pdf) for accessor definition)\n *\n * \\tparam LhsMapper determines the tensor contraction mapper type for left-hand-side matrix\n *\n * \\tparam RhsMapper determines the tensor contraction mapper type for right-hand-side matrix\n *\n * \\tparam StorageIndex: determines the StorageIndex Type\n *\n * \\tparam Properties: determines the Contraction Panel properties\n *\n * \\tparam TripleDim: determines the M, K, N dimensions for the flatten tensors in order to treat them as a matrix\n *\n * \\tparam Vectorizable: determines whether or not the vectorization is enabled for the Eigen expression.\n *\n * \\tparam input_mapper_properties : determine if the input tensors are matrix. If they are matrix, special memory\n access is used to guarantee that always the memory access are coalesced.\n *\n * \\tptaram IsFinal : determine if this is the final kernel. If so, the result will be written in a final output.\n Otherwise, the result of contraction will be written iin a temporary buffer. This is the case when Tall/Skinny\n contraction is used. So in this case, a final reduction step is required to compute final output.\n\n * \\tparam contraction_tp: it is an enum value representing whether the local memroy/no local memory implementation of\n the algorithm to be used\n *\n * \\param scratch: local memory containing tiles of LHS and RHS tensors for each work-group\n *\n * \\param lhs: determines the left-hand-side flattened tensor (tensor mapper)\n *\n * \\param rhs: determines the right-hand-side flattened tensor (tensor mapper)\n *\n * \\param out_res: determines the output tensor containing the contraction result\n *\n * \\param groupSizeM: a logical number determining the number of work-group for m dimension\n *\n * \\param groupSizeN: a logical number determining the number of work-group for n dimension\n *\n * \\param numTiles: determines total number of tiles on the k dimension\n *\n * \\param TripleDim: determines the M, K, N dimensions for the flatten tensors in order to treat them as a matrix\n */\ntemplate <typename OutScalar, typename LhsScalar, typename RhsScalar, typename OutAccessor, typename LhsMapper,\n          typename RhsMapper, typename StorageIndex, typename Properties, typename TripleDim, bool Vectorizable,\n          typename input_mapper_properties, bool IsFinal, contraction_type contraction_tp>\nclass TensorContractionKernel {\n public:\n  typedef typename Eigen::TensorSycl::internal::Vectorise<OutScalar, Eigen::SyclDevice, Vectorizable>::PacketReturnType\n      PacketReturnType;\n  static EIGEN_CONSTEXPR int PacketSize =\n      Eigen::TensorSycl::internal::Vectorise<OutScalar, Eigen::SyclDevice, Vectorizable>::PacketSize;\n  static EIGEN_CONSTEXPR bool is_lhs_transposed =\n      !::Eigen::internal::TensorContractionInputMapperTrait<LhsMapper>::inner_dim_contiguous;\n  static EIGEN_CONSTEXPR bool is_rhs_transposed =\n      !::Eigen::internal::TensorContractionInputMapperTrait<RhsMapper>::inner_dim_contiguous;\n\n  typedef BlockProperties<is_lhs_transposed, false, input_mapper_properties::is_lhs_matrix && Vectorizable,\n                          PacketReturnType>\n      LHSBlockProperties;\n\n  typedef BlockProperties<is_rhs_transposed, true, input_mapper_properties::is_rhs_matrix && Vectorizable,\n                          PacketReturnType>\n      RHSBlockProperties;\n\n  static EIGEN_CONSTEXPR StorageIndex NStride =\n      contraction_tp == contraction_type::local ? Properties::WorkLoadPerThreadN : RHSBlockProperties::nc_stride;\n\n  typedef cl::sycl::accessor<OutScalar, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local> Scratch;\n  typedef cl::sycl::multi_ptr<OutScalar, cl::sycl::access::address_space::local_space> local_ptr;\n  typedef OutScalar * /*cl::sycl::multi_ptr<OutScalar, cl::sycl::access::address_space::private_space>*/ private_ptr;\n  typedef\n      typename ::Eigen::internal::conditional<contraction_tp == contraction_type::local, local_ptr, private_ptr>::type\n          tile_ptr;\n  static EIGEN_CONSTEXPR StorageIndex LSDL = contraction_tp == contraction_type::local\n                                                 ? Properties::TileSizeDimM + Properties::BC\n                                                 : Properties::WorkLoadPerThreadM;\n  static EIGEN_CONSTEXPR StorageIndex LSDR = contraction_tp == contraction_type::local\n                                                 ? Properties::TileSizeDimN + Properties::BC\n                                                 : Properties::WorkLoadPerThreadN;\n  static EIGEN_CONSTEXPR StorageIndex LocalOffset = Properties::LocalThreadSizeM * Properties::LocalThreadSizeN;\n\n  /**\n   * \\brief MemHolder this is a place holder struct for creating memory hierarchy in SYCL. Inside SYCL kernel it is not\n   * allowed to have dynamic memory allocation. While the local memory is created outside of the kernel and passed to\n   * the kernel as an accessor, the private memory can only allowed to be allocated statically. Since we are abstracting\n   * the TiledMemory for both local and private memory, the MemHolder structs is used as a helper to abstract out\n   * different type of memory needed when local/no_local memory computation is called.\n   *\n   * \\tparam contraction_type: it is an enum value representing whether the local memroy/no local memory implementation\n   of the algorithm to be used\n   * \\tparam the private memory size\n   * \\param ptr the tile memory pointer type\n   */\n  template <contraction_type, StorageIndex>\n  struct MemHolder {\n    tile_ptr ptr;\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE MemHolder(local_ptr block_start_ptr) : ptr(block_start_ptr) {}\n  };\n  /**\n   * \\brief specialization of memHolder class when no local memory kernel is used.\n   */\n  template <StorageIndex MemSize>\n  struct MemHolder<contraction_type::no_local, MemSize> {\n    OutScalar ptr[MemSize] = {OutScalar{0}};\n  };\n  /**\n   * \\brief TiledMemory: contains required memory pointer for loading  each tile of the TensorContraction panel from\n   * global memory to local/private memory when local/no_local algorithm used.\n   *\n   * \\param lhs_scratch_extract : determines the LHS tile memory. It is either private or local memory based on the\n   * selected contraction_type.\n   *\n   * \\param rhs_scratch_extract : determines the RHS tile memory. It is either private or local memory based on the\n   * selected contraction_type.\n   *\n   * \\param lhs_extract_index: determins the position of each thread on a local memory for lhs input. When private\n   * memory is used this is set to zero as this is not applicable in case of private memory.\n   *\n   * \\param rhs_extract_index: determins the position of each thread on a local memory for rhs input. When private\n   * memory is used this is set to zero as this is not applicable in case of private memory.\n   *\n   * \\param lhs_scratch_compute : determines the  location to load for computation for lhs_local memory. This is the\n   * same as lhs_scratch_extract for private memory.\n   *\n   * \\param rhs_scratch_compute : determines the  location to load for computation for rhs_local memory. This is the\n   * same as rhs_scratch_extract for private memory.\n   */\n  struct TiledMemory {\n    MemHolder<contraction_tp, Properties::WorkLoadPerThreadM * Properties::TileSizeDimK> lhs_scratch_extract;\n    MemHolder<contraction_tp, Properties::WorkLoadPerThreadN * Properties::TileSizeDimK> rhs_scratch_extract;\n    tile_ptr lhs_scratch_ptr_compute;\n    tile_ptr rhs_scratch_ptr_compute;\n    const std::pair<StorageIndex, StorageIndex> lhs_extract_index;\n    const std::pair<StorageIndex, StorageIndex> rhs_extract_index;\n    template <contraction_type tp = contraction_tp>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TiledMemory(const ThreadProperties<StorageIndex> &, local_ptr,\n                typename ::Eigen::internal::enable_if<tp == contraction_type::no_local>::type * = 0)\n        : lhs_scratch_extract{},\n          rhs_scratch_extract{},\n          lhs_scratch_ptr_compute(lhs_scratch_extract.ptr),\n          rhs_scratch_ptr_compute(rhs_scratch_extract.ptr),\n          lhs_extract_index(std::pair<StorageIndex, StorageIndex>(StorageIndex{0}, StorageIndex{0})),\n          rhs_extract_index(std::pair<StorageIndex, StorageIndex>(StorageIndex{0}, StorageIndex{0})) {}\n\n    template <contraction_type tp = contraction_tp>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TiledMemory(const ThreadProperties<StorageIndex> &thread_properties, local_ptr block_start_ptr,\n                typename ::Eigen::internal::enable_if<tp == contraction_type::local>::type * = 0)\n        : lhs_scratch_extract{block_start_ptr},\n          rhs_scratch_extract{lhs_scratch_extract.ptr +\n                              ((Properties::DoubleBuffer + 1) * LSDL * Properties::TileSizeDimK)},\n          lhs_scratch_ptr_compute(lhs_scratch_extract.ptr + thread_properties.mLocalOffset),\n          rhs_scratch_ptr_compute(rhs_scratch_extract.ptr + thread_properties.nLocalOffset),\n          lhs_extract_index(\n              local_id_extract<LHSBlockProperties, Properties::TileSizeDimM>(thread_properties.linearLocalThreadId)),\n          rhs_extract_index(\n              local_id_extract<RHSBlockProperties, Properties::TileSizeDimN>(thread_properties.linearLocalThreadId)) {}\n  };\n\n  Scratch scratch;\n  const LhsMapper lhs;\n  const RhsMapper rhs;\n  OutAccessor out_res;\n  const StorageIndex groupSizeM;\n  const StorageIndex groupSizeN;\n  const StorageIndex numTiles;\n  const TripleDim triple_dim;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorContractionKernel(Scratch scratch_, const LhsMapper lhs_,\n                                                                const RhsMapper rhs_, OutAccessor out_res_,\n                                                                const StorageIndex groupSizeM_,\n                                                                const StorageIndex groupSizeN_,\n                                                                const StorageIndex numTiles_,\n                                                                const TripleDim triple_dim_)\n      : scratch(scratch_),\n        lhs(lhs_),\n        rhs(rhs_),\n        out_res(out_res_),\n        groupSizeM(groupSizeM_),\n        groupSizeN(groupSizeN_),\n        numTiles(numTiles_),\n        triple_dim(triple_dim_) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorContractionKernel(Scratch scratch_, const LhsMapper lhs_,\n                                                                const RhsMapper rhs_, OutAccessor out_res_,\n                                                                const StorageIndex groupSizeM_,\n                                                                const StorageIndex numTiles_,\n                                                                const TripleDim triple_dim_)\n      : TensorContractionKernel(scratch_, lhs_, rhs_, out_res_, groupSizeM_, 1, numTiles_, triple_dim_) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void operator()(cl::sycl::nd_item<1> itemID) {\n    const StorageIndex linearLocalThreadId = itemID.get_local_id(0);\n    const StorageIndex nLocalThreadId = linearLocalThreadId / Properties::LocalThreadSizeM;\n    const StorageIndex mLocalThreadId = linearLocalThreadId % Properties::LocalThreadSizeM;\n    const StorageIndex mGroupId = itemID.get_group(0) % groupSizeM;\n    const StorageIndex tmp = itemID.get_group(0) / groupSizeM;\n    const StorageIndex nGroupId = IsFinal ? tmp : tmp % groupSizeN;\n    const StorageIndex kGroupId = IsFinal ? 0 : tmp / groupSizeN;\n    const StorageIndex mGroupOffset = mGroupId * Properties::TileSizeDimM;\n    const StorageIndex nGroupOffset = nGroupId * Properties::TileSizeDimN;\n    const StorageIndex mLocalOffset = PacketSize * mLocalThreadId;\n    const StorageIndex nLocalOffset = NStride * nLocalThreadId;\n    const StorageIndex mGlobalOffset = mGroupOffset + mLocalOffset;\n    const StorageIndex nGlobalOffset = nGroupOffset + nLocalOffset;\n\n    const StorageIndex kSizePerWG = IsFinal ? triple_dim.K : numTiles * Properties::TileSizeDimK;\n    StorageIndex kGroupOffset = kGroupId * kSizePerWG;\n    const bool is_internal = triple_dim.M - mGroupOffset >= Properties::TileSizeDimM &&\n                             triple_dim.N - nGroupOffset >= Properties::TileSizeDimN &&\n                             triple_dim.K - kGroupOffset >= kSizePerWG;\n    // this is used to adjust the last block\n    StorageIndex kSize = IsFinal ? triple_dim.K : std::min(kSizePerWG, triple_dim.K - kGroupOffset);\n    // This is used to find out the lats K offset so that kGroupOffset -kSize can compute the coffset for loading to\n    // tile\n    kGroupOffset += kSize;\n\n    auto thread_properties =\n        ThreadProperties<StorageIndex>(linearLocalThreadId, kGroupId, mGroupOffset, nGroupOffset, kGroupOffset,\n                                       mLocalOffset, nLocalOffset, mGlobalOffset, nGlobalOffset, kSize, is_internal);\n\n    auto out_ptr = out_res.get_pointer() + (IsFinal ? 0 : thread_properties.kGroupId * triple_dim.M * triple_dim.N);\n\n    (thread_properties.is_internal) ? compute_panel<true>(itemID, thread_properties, out_ptr)\n                                    : compute_panel<false>(itemID, thread_properties, out_ptr);\n  }\n  // The compute block computes the contraction operation private block for each thread and store the resutl in the\n  // privateRes memory of Each computation the compute block function is independent of local and no local concepts as\n  // it only compute the block on each thread's private memory space\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void compute_block_per_tile(OutScalar *lhs_block_ptr, OutScalar *rhs_block_ptr,\n                                                                    PacketReturnType *privateRes) {\n    StorageIndex idx = 0;\n    EIGEN_CONSTEXPR StorageIndex lhs_stride =\n        contraction_tp == contraction_type::local ? (PacketSize * Properties::LocalThreadSizeM) : 1;\n    EIGEN_UNROLL_LOOP\n    for (StorageIndex wLPTN = 0; wLPTN < Properties::WorkLoadPerThreadN; wLPTN++) {\n      auto rhsPacket = PacketReturnType{*(rhs_block_ptr + wLPTN)};\n      StorageIndex lhs_index = 0;\n      EIGEN_UNROLL_LOOP\n      for (StorageIndex wLPTM = 0; wLPTM < Properties::WorkLoadPerThreadM / PacketSize; wLPTM++) {\n        PacketReturnType lhsPack{};\n        Eigen::TensorSycl::internal::PacketWrapper<PacketReturnType, PacketSize>::set_packet(lhsPack,\n                                                                                             lhs_block_ptr + lhs_index);\n        privateRes[idx] = ::Eigen::internal::pmadd(lhsPack, rhsPacket, privateRes[idx]);\n\n        lhs_index += lhs_stride;\n        idx++;\n      }\n    }\n  }\n  // The store function write the computed contraction operation in the private memory of each thread to the global\n  // memory. The store function is independent of local and no local concepts s that it can be abstract out in the base\n  // class.\n  template <bool is_internal_block, StorageIndex PrivateNStride, typename OutPtr>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void store(OutPtr *out_ptr, PacketReturnType *privateRes,\n                                                   StorageIndex mGlobalOffset, StorageIndex nGlobalOffset) {\n    auto chk_bound = [&](const StorageIndex &mIndex, const StorageIndex &nIndex) EIGEN_DEVICE_FUNC {\n      return (mIndex + PacketSize - 1 < triple_dim.M && nGlobalOffset + nIndex < triple_dim.N);\n    };\n    // when local memory is not used M and N are both accessed in a coalesced way. However, when local memory is\n    // available the k*N is transposed in the local to N*K therefore, each blocks operates on blockId*\n    // WorkLoadPerThreadN slice of N\n    EIGEN_CONSTEXPR StorageIndex GlobalNStride =\n        contraction_tp == contraction_type::local ? 1 : Properties::LocalThreadSizeN;\n    EIGEN_UNROLL_LOOP\n    for (StorageIndex wLPTN = 0; wLPTN < Properties::WorkLoadPerThreadN / PrivateNStride; wLPTN++) {\n      // output leading dimension\n      StorageIndex outputLD = 0;\n      // When local memory is used the PrivateNstride is always 1 because the coalesed access on N is loaded into Local\n      // memory and extracting from local to global is the same as no transposed version. However, when local memory is\n      // not used and RHS is transposed we packetize the load for RHS.\n      EIGEN_UNROLL_LOOP\n      for (StorageIndex nId = 0; nId < PrivateNStride; nId++) {\n        StorageIndex globalRow = mGlobalOffset;\n        EIGEN_UNROLL_LOOP\n        for (StorageIndex wLPTM = 0; wLPTM < Properties::WorkLoadPerThreadM / PacketSize; wLPTM++) {\n          PacketReturnType privetOut = privateRes[wLPTM];\n          if (check_boundary<is_internal_block>(chk_bound(globalRow, nId))) {\n            // Store the final results in C. The C matrix has always M as a first StorageIndex and N as a second\n            // StorageIndex Therefore it is always coalesced layout\n            write<data_source::global_mem>(privetOut, out_ptr + outputLD + globalRow);\n          } else {\n            EIGEN_UNROLL_LOOP\n            for (StorageIndex mId = 0; mId < PacketSize; mId++) {\n              StorageIndex mOffset = globalRow + mId;\n              if (mOffset < triple_dim.M && (nGlobalOffset + nId < triple_dim.N)) {\n                out_ptr[mOffset + outputLD] =\n                    Eigen::TensorSycl::internal::PacketWrapper<PacketReturnType, PacketSize>::scalarize(mId, privetOut);\n              }\n            }\n          }\n          globalRow += (PacketSize * Properties::LocalThreadSizeM);\n        }\n        outputLD += triple_dim.M;\n        privateRes += Properties::WorkLoadPerThreadM / PacketSize;\n      }\n      out_ptr += (GlobalNStride * outputLD);\n\n      nGlobalOffset += (PrivateNStride * GlobalNStride);\n    }\n  }\n  // when no local memory is used the following extract_block will be enabled\n  template <typename InputBlockProperties, bool is_internal_block, typename Input, typename PrivateReg,\n            contraction_type contract_tp = contraction_tp>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n      typename ::Eigen::internal::enable_if<contract_tp == contraction_type::no_local>::type\n      extract_block(const Input &inpt, PrivateReg private_ptr, const std::pair<StorageIndex, StorageIndex> &,\n                    const StorageIndex &ncOffset, const StorageIndex cOffset) {\n    EIGEN_CONSTEXPR StorageIndex LocalThreadSizeNC =\n        InputBlockProperties::is_rhs ? Properties::LocalThreadSizeN : Properties::LocalThreadSizeM;\n    EIGEN_CONSTEXPR StorageIndex WorkLoadPerThreadNC =\n        InputBlockProperties::is_rhs ? Properties::WorkLoadPerThreadN : Properties::WorkLoadPerThreadM;\n    const StorageIndex &NC = InputBlockProperties::is_rhs ? triple_dim.N : triple_dim.M;\n\n    auto chk_bound = [&](const StorageIndex &CIndex, const StorageIndex &NCIndex) EIGEN_DEVICE_FUNC {\n      return ((CIndex + InputBlockProperties::c_stride - 1 < triple_dim.K) &&\n              (NCIndex + InputBlockProperties::nc_stride - 1 < NC));\n    };\n    const StorageIndex ld = InputBlockProperties::is_coalesced_layout ? NC : triple_dim.K;\n    StorageIndex cIndex = cOffset;\n\n    EIGEN_UNROLL_LOOP\n    for (StorageIndex cId = 0; cId < Properties::TileSizeDimK / InputBlockProperties::c_stride; cId++) {\n      StorageIndex ncIndex = ncOffset;\n      EIGEN_UNROLL_LOOP\n      for (StorageIndex ncId = 0; ncId < WorkLoadPerThreadNC / InputBlockProperties::nc_stride; ncId++) {\n        if (check_boundary<is_internal_block>(chk_bound(cIndex, ncIndex))) {\n          auto val =\n              read<InputBlockProperties::packet_load, InputBlockProperties::is_coalesced_layout,\n                   InputBlockProperties::is_rhs, typename InputBlockProperties::OutType>(inpt, ncIndex, cIndex, ld);\n\n          write<StorageIndex, (InputBlockProperties::is_coalesced_layout ? 1 : WorkLoadPerThreadNC),\n                data_source::private_mem>(val, private_ptr);\n        } else {\n          EIGEN_UNROLL_LOOP\n          for (StorageIndex i = 0; i < InputBlockProperties::elements_per_access; i++) {\n            const StorageIndex ncInd = ncIndex + (InputBlockProperties::is_coalesced_layout ? i : 0);\n            const StorageIndex cInd = cIndex + (InputBlockProperties::is_coalesced_layout ? 0 : i);\n            OutScalar val =\n                (ncInd < NC && cInd < triple_dim.K)\n                    ? read<false, InputBlockProperties::is_coalesced_layout, InputBlockProperties::is_rhs, OutScalar>(\n                          inpt, ncInd, cInd, ld)\n                    : OutScalar(0);\n            write<StorageIndex, (InputBlockProperties::is_coalesced_layout ? 1 : WorkLoadPerThreadNC),\n                  data_source::private_mem>(\n                val, private_ptr + (InputBlockProperties::is_coalesced_layout ? i : 0) +\n                         ((InputBlockProperties::is_coalesced_layout ? 0 : i) * WorkLoadPerThreadNC));\n          }\n        }\n\n        // if it is lhs we have to load it packetised when the packet size is > 1, because the output is coalesced. So\n        // even if M is not accessed in a coalesced mode, we have to load packet_size number of m per thread.\n        ncIndex = (!InputBlockProperties::is_rhs && InputBlockProperties::nc_stride == 1 && PacketSize != 1)\n                      ? ncOffset + (ncId + 1) % PacketSize + ((ncId + 1) / PacketSize) * LocalThreadSizeNC\n                      : (ncIndex + InputBlockProperties::nc_stride * LocalThreadSizeNC);\n        private_ptr += InputBlockProperties::nc_stride;\n      }\n      // the previous for loop ( private_ptr += (ncId * nc_stride)) has already moved ptr with one WorkLoadPerThreadNC\n      private_ptr += (InputBlockProperties::c_stride - 1) * WorkLoadPerThreadNC;\n      cIndex += InputBlockProperties::c_stride;\n    }\n  }\n  template <typename InputBlockProperties, StorageIndex TileSizeDimNC>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::pair<StorageIndex, StorageIndex> local_id_extract(\n      const StorageIndex &linearLocalThreadId) {\n    const StorageIndex localThreadNC =\n        (InputBlockProperties::is_coalesced_layout)\n            ? linearLocalThreadId % (TileSizeDimNC / InputBlockProperties::nc_stride)\n            : linearLocalThreadId / (Properties::TileSizeDimK / InputBlockProperties::c_stride);\n    const StorageIndex localThreadC =\n        (InputBlockProperties::is_coalesced_layout)\n            ? linearLocalThreadId / (TileSizeDimNC / InputBlockProperties::nc_stride)\n            : linearLocalThreadId % (Properties::TileSizeDimK / InputBlockProperties::c_stride);\n    return std::pair<StorageIndex, StorageIndex>(localThreadNC, localThreadC);\n  }\n\n  template <bool db = Properties::DoubleBuffer, contraction_type ctp = contraction_tp>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n      typename ::Eigen::internal::enable_if<db && ctp == contraction_type::local>::type\n      sync_mem(const cl::sycl::nd_item<1> &, bool &db_offset) noexcept {\n    db_offset = !db_offset;\n  }\n\n  template <bool db = Properties::DoubleBuffer, contraction_type ctp = contraction_tp>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n      typename ::Eigen::internal::enable_if<!db && ctp == contraction_type::local>::type\n      sync_mem(const cl::sycl::nd_item<1> &itemID, bool &) noexcept {\n    itemID.barrier(cl::sycl::access::fence_space::local_space);\n  }\n\n  template <contraction_type ctp = contraction_tp>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n      typename ::Eigen::internal::enable_if<ctp == contraction_type::no_local>::type\n      sync_mem(const cl::sycl::nd_item<1> &, bool &) noexcept {\n    return;\n  }\n\n  template <bool need_sync, contraction_type ctp = contraction_tp>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n      typename ::Eigen::internal::enable_if<need_sync && ctp == contraction_type::no_local>::type\n      sync_thread(const cl::sycl::nd_item<1> &\n#ifdef EIGEN_SYCL_ARM_GPU_CACHE_OPTIMISATION\n                      itemID\n#endif\n                  ) noexcept {\n#ifdef EIGEN_SYCL_ARM_GPU_CACHE_OPTIMISATION\n    itemID.barrier(cl::sycl::access::fence_spacce::local_space);\n#else\n    return;\n#endif\n  }\n  template <bool need_sync, contraction_type ctp = contraction_tp>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n      typename ::Eigen::internal::enable_if<need_sync && ctp == contraction_type::local>::type\n      sync_thread(const cl::sycl::nd_item<1> &itemID) {\n    itemID.barrier(cl::sycl::access::fence_space::local_space);\n  }\n  template <bool need_sync>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename ::Eigen::internal::enable_if<!need_sync>::type sync_thread(\n      const cl::sycl::nd_item<1> &) {\n    return;\n  }\n\n  template <bool is_internal_block>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void compute_tile_per_panel(const cl::sycl::nd_item<1> &itemID,\n                                                                    ThreadProperties<StorageIndex> &thread_properties,\n                                                                    TiledMemory &tiled_input_block,\n                                                                    PacketReturnType *privateRes, bool &db_offset) {\n    // Tiling the Rhs block from global to local memory\n    extract_block<RHSBlockProperties, is_internal_block>(\n        rhs, tiled_input_block.rhs_scratch_extract.ptr + (db_offset * Properties::TileSizeDimK * LSDR),\n        tiled_input_block.rhs_extract_index,\n        contraction_tp == contraction_type::local ? thread_properties.nGroupOffset : thread_properties.nGlobalOffset,\n        thread_properties.kGroupOffset - thread_properties.kSize);\n\n    sync_thread<contraction_tp == contraction_type::no_local>(itemID);\n\n    // Tiling the Lhs block from global to local memory\n    extract_block<LHSBlockProperties, is_internal_block>(\n        lhs, tiled_input_block.lhs_scratch_extract.ptr + (db_offset * LSDL * Properties::TileSizeDimK),\n        tiled_input_block.lhs_extract_index,\n        contraction_tp == contraction_type::local ? thread_properties.mGroupOffset : thread_properties.mGlobalOffset,\n        thread_properties.kGroupOffset - thread_properties.kSize);\n\n    // itemID.barrier(cl::sycl::access::fence_space::local_space);\n    sync_thread<contraction_tp == contraction_type::local>(itemID);\n    // switch to compute mede\n    StorageIndex lhs_offset = (db_offset * LSDL * Properties::TileSizeDimK);\n    StorageIndex rhs_offset = (db_offset * Properties::TileSizeDimK * LSDR);\n    // Loop over the values of a single tile\n    for (StorageIndex k = 0; k < Properties::TileSizeDimK; k++) {\n      compute_block_per_tile(tiled_input_block.lhs_scratch_ptr_compute + lhs_offset,\n                             tiled_input_block.rhs_scratch_ptr_compute + rhs_offset, privateRes);\n      lhs_offset += LSDL;\n      rhs_offset += LSDR;\n    }\n    // computing the K index for the next tile\n    thread_properties.kSize -= Properties::TileSizeDimK;\n    sync_mem(itemID, db_offset);\n  }\n\n  // when local memory is available the following compute_panel will be enabled\n  template <bool is_internal_block, typename OutPtr>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void compute_panel(const cl::sycl::nd_item<1> &itemID,\n                                                           ThreadProperties<StorageIndex> &thread_properties,\n                                                           OutPtr out_ptr) {\n    auto tiled_input_block = TiledMemory{thread_properties, scratch.get_pointer()};\n    // Allocate register space\n    PacketReturnType privateRes[Properties::WorkLoadPerThreadM * Properties::WorkLoadPerThreadN / PacketSize] = {\n        PacketReturnType{0}};\n    bool db_offset = 0;\n\n    while (thread_properties.kSize >= Properties::TileSizeDimK) {\n      compute_tile_per_panel<is_internal_block>(itemID, thread_properties, tiled_input_block, privateRes, db_offset);\n    }\n    if (thread_properties.kSize > 0) {\n      compute_tile_per_panel<false>(itemID, thread_properties, tiled_input_block, privateRes, db_offset);\n    }\n\n    // Storing the final results in the output\n    store<is_internal_block,\n          contraction_tp == contraction_type::local ? static_cast<StorageIndex>(1) : RHSBlockProperties::nc_stride>(\n        out_ptr + thread_properties.nGlobalOffset * triple_dim.M, privateRes, thread_properties.mGlobalOffset,\n        thread_properties.nGlobalOffset);\n  }\n  // When local memory is available the following extract_block will be enabled\n  template <typename InputBlockProperties, bool is_internal_block, typename Input, typename Local,\n            contraction_type contract_tp = contraction_tp>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n      typename ::Eigen::internal::enable_if<contract_tp == contraction_type::local>::type\n      extract_block(const Input &inpt, Local local_ptr, const std::pair<StorageIndex, StorageIndex>& local_index,\n                    const StorageIndex &ncOffset, const StorageIndex cOffset) {\n    EIGEN_CONSTEXPR StorageIndex TileSizeDimNC =\n        InputBlockProperties::is_rhs ? Properties::TileSizeDimN : Properties::TileSizeDimM;\n    EIGEN_CONSTEXPR StorageIndex LoadPerThread =\n        InputBlockProperties::is_rhs ? Properties::LoadPerThreadRhs : Properties::LoadPerThreadLhs;\n    EIGEN_CONSTEXPR StorageIndex LSD = InputBlockProperties::is_rhs ? LSDR : LSDL;\n    static_assert(((LocalOffset % (TileSizeDimNC / InputBlockProperties::nc_stride) == 0) &&\n                   (LocalOffset % (Properties::TileSizeDimK / InputBlockProperties::c_stride) == 0)),\n                  \" LocalOffset must be divisable by stride\");\n    const StorageIndex &NC = InputBlockProperties::is_rhs ? triple_dim.N : triple_dim.M;\n    StorageIndex localThreadNC = local_index.first;\n    StorageIndex localThreadC = local_index.second;\n    auto chk_bound = [&](const StorageIndex &CIndex, const StorageIndex &NCIndex) EIGEN_DEVICE_FUNC {\n      return ((CIndex + InputBlockProperties::c_stride - 1 < triple_dim.K) &&\n              (NCIndex + InputBlockProperties::nc_stride - 1 < NC));\n    };\n    EIGEN_UNROLL_LOOP\n    for (StorageIndex lPT = 0; lPT < LoadPerThread / InputBlockProperties::elements_per_access; lPT++) {\n      const StorageIndex CIndex = cOffset + (InputBlockProperties::c_stride * localThreadC);\n      const StorageIndex NCIndex = ncOffset + (InputBlockProperties::nc_stride * localThreadNC);\n      const StorageIndex ld = InputBlockProperties::is_coalesced_layout ? NC : triple_dim.K;\n      if (check_boundary<is_internal_block>(chk_bound(CIndex, NCIndex))) {\n        auto val =\n            read<InputBlockProperties::packet_load, InputBlockProperties::is_coalesced_layout,\n                 InputBlockProperties::is_rhs, typename InputBlockProperties::OutType>(inpt, NCIndex, CIndex, ld);\n        write<StorageIndex, (InputBlockProperties::is_coalesced_layout ? 1 : LSD), data_source::local_mem>(\n            val, local_ptr + (InputBlockProperties::nc_stride * localThreadNC) +\n                     (InputBlockProperties::c_stride * localThreadC * LSD));\n      } else {\n        EIGEN_UNROLL_LOOP\n        for (StorageIndex i = 0; i < InputBlockProperties::elements_per_access; i++) {\n          const StorageIndex nCInd = NCIndex + (InputBlockProperties::is_coalesced_layout ? i : 0);\n          const StorageIndex cInd = CIndex + (InputBlockProperties::is_coalesced_layout ? 0 : i);\n          OutScalar val =\n              (nCInd < NC && cInd < triple_dim.K)\n                  ? read<false, InputBlockProperties::is_coalesced_layout, InputBlockProperties::is_rhs, OutScalar>(\n                        inpt, nCInd, cInd, ld)\n                  : OutScalar(0);\n\n          write<StorageIndex, (InputBlockProperties::is_coalesced_layout ? 1 : LSD), data_source::local_mem>(\n              val, local_ptr + (InputBlockProperties::nc_stride * localThreadNC) +\n                       (InputBlockProperties::is_coalesced_layout ? i : 0) +\n                       ((InputBlockProperties::c_stride * localThreadC +\n                         (InputBlockProperties::is_coalesced_layout ? 0 : i)) *\n                        LSD));\n        }\n      }\n      localThreadNC += (InputBlockProperties::is_coalesced_layout)\n                           ? LocalOffset % (TileSizeDimNC / InputBlockProperties::nc_stride)\n                           : LocalOffset / (Properties::TileSizeDimK / InputBlockProperties::c_stride);\n      localThreadC += (InputBlockProperties::is_coalesced_layout)\n                          ? LocalOffset / (TileSizeDimNC / InputBlockProperties::nc_stride)\n                          : LocalOffset % (Properties::TileSizeDimK / InputBlockProperties::c_stride);\n    }\n  }\n};\n\n#ifndef EIGEN_SYCL_DISABLE_GEMV\n\n/*!\n * \\brief GeneralVectorTensor is a template class that provides Tensor -vector contraction operation, which is a special\n * case of Tensor Tensor contraction.\n *\n * \\tparam OutScalar: determines the output scalar type\n *\n * \\tparam OutAccessor: determines the sycl accessor type for out put (please see the sycl-1.2.1 specification\n * (https://www.khronos.org/registry/SYCL/specs/sycl-1.2.1.pdf) for accessor definition)\n *\n * \\tparam VectorMapper: determines the tensor contraction mapper for the vector input (can be lhs or rhs)\n *\n * \\tparam TensorMapper: determines the tensor contraction mapper for the tensor input (can be lhs or rhs)\n *\n * \\tparam StorageIndex: determines the StorageIndex Type\n *\n * \\tparam Properties: determines the Contraction Panel properties\n *\n * \\tparam KFactor: determines the number of elements in K dimension in a Tile\n *\n * \\tparam Vectorizable: determines whether or not the vectorization is enabled for the Eigen expression.\n *\n * \\tparam is_lhs_vec: determines whether lhs is a vector or rhs is a vector\n *\n * \\tparam IsFinal: determine if this is the final kernel. If so, the result will be written in a final output.\n * Otherwise, the result of contraction will be written iin a temporary buffer.\n *\n * \\param scratch: determines the local memory containing the vector block for each work-group\n *\n * \\param vec: determines the vector input (tensor mapper)\n *\n * \\param mat: determines the tensor input (tensor mapper)\n *\n * \\param out_res: determines the output vector containing the contraction result\n *\n * \\param nonContractGroupSize: a logical number determining the number of work-group for non-contracting dimension\n *\n * \\param nonContractDim: determines the size of non contracting dimension for the flattened tensor\n *\n * \\param contractDim: determines the size of non contracting dimension for the flattened tensor\n *\n */\ntemplate <typename OutScalar, typename OutAccessor, typename VectorMapper, typename TensorMapper, typename StorageIndex,\n          typename Properties, StorageIndex KFactor, bool Vectorizable, bool is_lhs_vec, bool IsFinal>\nstruct GeneralVectorTensor {\n  typedef typename Eigen::TensorSycl::internal::Vectorise<OutScalar, Eigen::SyclDevice, Vectorizable>::PacketReturnType\n      PacketReturnType;\n  static EIGEN_CONSTEXPR int PacketSize =\n      Eigen::TensorSycl::internal::Vectorise<OutScalar, Eigen::SyclDevice, Vectorizable>::PacketSize;\n  typedef cl::sycl::accessor<OutScalar, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local> Scratch;\n\n  static EIGEN_CONSTEXPR StorageIndex OutScratchOffset =\n      KFactor * Properties::LocalThreadSizeC * Properties::LocalThreadSizeNC;\n\n  // Since the access layout for a vector can always be coalesced, when LHS is a vector, we pass false and false to make\n  // sure that the !^ is true When RHS is a vector, we pass true and true to make sure that the !^ is true.\n  typedef BlockProperties<is_lhs_vec ? false : true, is_lhs_vec ? false : true, Vectorizable, PacketReturnType>\n      VecBlockProperties;\n\n  Scratch scratch;\n  const VectorMapper vec;\n  const TensorMapper mat;\n  OutAccessor out_res;\n  const StorageIndex nonContractGroupSize;\n  const StorageIndex nonContractDim;\n  const StorageIndex contractDim;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE GeneralVectorTensor(Scratch scratch_, const VectorMapper vec_,\n                                                            const TensorMapper mat_, OutAccessor out_res_,\n                                                            const StorageIndex nonContractGroupSize_,\n                                                            const StorageIndex nonContractDim_,\n                                                            const StorageIndex contractDim_)\n      : scratch(scratch_),\n        vec(vec_),\n        mat(mat_),\n        out_res(out_res_),\n        nonContractGroupSize(nonContractGroupSize_),\n        nonContractDim(nonContractDim_),\n        contractDim(contractDim_) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void operator()(cl::sycl::nd_item<1> itemID) {\n    auto scratch_ptr = scratch.get_pointer();\n    const StorageIndex linearLocalThreadId = itemID.get_local_id(0);\n    StorageIndex nonContractId = is_lhs_vec ? linearLocalThreadId / Properties::LocalThreadSizeC\n                                            : linearLocalThreadId % Properties::LocalThreadSizeNC;\n    StorageIndex contractId = is_lhs_vec ? linearLocalThreadId % Properties::LocalThreadSizeC\n                                         : linearLocalThreadId / Properties::LocalThreadSizeNC;\n    const StorageIndex cGroupSize = itemID.get_group_range(0) / nonContractGroupSize;\n    const StorageIndex nonContractGroupId =\n        is_lhs_vec ? itemID.get_group(0) / cGroupSize : itemID.get_group(0) % nonContractGroupSize;\n    const StorageIndex contractGroupId =\n        is_lhs_vec ? itemID.get_group(0) % cGroupSize : itemID.get_group(0) / nonContractGroupSize;\n    auto out_ptr = out_res.get_pointer() + (IsFinal ? 0 : contractGroupId * nonContractDim);\n\n    const StorageIndex nonContractGroupOffset = nonContractGroupId * Properties::TileSizeDimNC;\n    const StorageIndex contractGroupOffset = contractGroupId * Properties::TileSizeDimC;\n    auto outScratchIndex = nonContractId + contractId * Properties::LocalThreadSizeNC;\n    const StorageIndex globalNonContractDimOffset = nonContractGroupOffset + nonContractId;\n    const StorageIndex globalContractDimOffset = contractGroupOffset + contractId;\n    auto local_output = scratch_ptr + OutScratchOffset;\n    const bool is_internal = nonContractDim - nonContractGroupOffset >= Properties::TileSizeDimNC &&\n                             contractDim - contractGroupOffset >= Properties::TileSizeDimC;\n    is_internal\n        ? compute_panel<true>(itemID, vec, mat, local_output, out_ptr,\n#ifdef EIGEN_SYCL_LOCAL_MEM_UNSET_OR_ON\n                              scratch_ptr, contractGroupOffset,\n#endif\n                              nonContractGroupOffset, linearLocalThreadId, contractDim, nonContractDim, contractId,\n                              nonContractId, globalContractDimOffset, globalNonContractDimOffset, outScratchIndex)\n        : compute_panel<false>(itemID, vec, mat, local_output, out_ptr,\n#ifdef EIGEN_SYCL_LOCAL_MEM_UNSET_OR_ON\n                               scratch_ptr, contractGroupOffset,\n#endif\n                               nonContractGroupOffset, linearLocalThreadId, contractDim, nonContractDim, contractId,\n                               nonContractId, globalContractDimOffset, globalNonContractDimOffset, outScratchIndex);\n  }\n  template <bool is_internal_block, typename OutPtr>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void compute_panel(\n      const cl::sycl::nd_item<1> &itemID, const VectorMapper &vec, const TensorMapper &mat, OutScalar *local_output,\n      OutPtr out_ptr,\n#ifdef EIGEN_SYCL_LOCAL_MEM_UNSET_OR_ON\n      OutScalar *scratch_ptr, const StorageIndex contractGroupOffset,\n#endif\n      const StorageIndex nonContractGroupOffset, const StorageIndex linearLocalThreadId, StorageIndex contractDim,\n      StorageIndex nonContractDim, StorageIndex contractId, StorageIndex nonContractId,\n      StorageIndex globalContractDimOffset, StorageIndex globalNonContractDimOffset, StorageIndex outScratchIndex) {\n    OutScalar outScalar[Properties::WorkLoadPerThreadNC] = {OutScalar(0)};\n    // Reading the vector\n#ifdef EIGEN_SYCL_LOCAL_MEM_UNSET_OR_ON\n    const StorageIndex vectorOffset = contractGroupOffset + linearLocalThreadId;\n    extract_block<VecBlockProperties, is_internal_block, KFactor,\n                  Properties::LocalThreadSizeNC * Properties::LocalThreadSizeC>(vec, scratch_ptr, linearLocalThreadId,\n                                                                                vectorOffset, contractDim);\n\n    itemID.barrier(cl::sycl::access::fence_space::local_space);\n    auto in_scratch_ptr = scratch_ptr + contractId;\n#endif\n\n    StorageIndex privateOffsetC = 0;\n    EIGEN_UNROLL_LOOP\n    for (StorageIndex i = 0; i < Properties::WorkLoadPerThreadC; i++) {\n      StorageIndex privateOffsetNC = 0;\n      bool contract_conds = ((globalContractDimOffset + privateOffsetC) < contractDim);\n#ifdef EIGEN_SYCL_LOCAL_MEM_UNSET_OR_ON\n      auto vecScalar = *in_scratch_ptr;\n#else\n      auto vecScalar = (check_boundary<is_internal_block>(contract_conds))\n                           ? vec(is_lhs_vec ? StorageIndex(0) : globalContractDimOffset + privateOffsetC,\n                                 is_lhs_vec ? globalContractDimOffset + privateOffsetC : StorageIndex(0))\n                           : OutScalar(0);\n#endif\n      EIGEN_UNROLL_LOOP\n      for (StorageIndex j = 0; j < Properties::WorkLoadPerThreadNC; j++) {\n        auto matScalar = (check_boundary<is_internal_block>(\n                             contract_conds && ((globalNonContractDimOffset + privateOffsetNC) < nonContractDim)))\n                             ? mat(is_lhs_vec ? globalContractDimOffset + privateOffsetC\n                                              : globalNonContractDimOffset + privateOffsetNC,\n                                   is_lhs_vec ? globalNonContractDimOffset + privateOffsetNC\n                                              : globalContractDimOffset + privateOffsetC)\n                             : OutScalar(0);\n\n        outScalar[j] = cl::sycl::mad(matScalar, vecScalar, outScalar[j]);\n        privateOffsetNC += Properties::LocalThreadSizeNC;\n      }\n      privateOffsetC += Properties::LocalThreadSizeC;\n#ifdef EIGEN_SYCL_LOCAL_MEM_UNSET_OR_ON\n      in_scratch_ptr += Properties::LocalThreadSizeC;\n#endif\n    }\n\n    auto out_scratch_ptr = local_output + outScratchIndex;\n    // Each block of 16*16 element in shared memory should reduce to 16*1\n    EIGEN_UNROLL_LOOP\n    for (StorageIndex j = 0; j < Properties::WorkLoadPerThreadNC; j++) {\n      *out_scratch_ptr = outScalar[j];\n\n      out_scratch_ptr += (Properties::LocalThreadSizeNC * Properties::LocalThreadSizeC);\n    }\n    if (is_lhs_vec) {\n      nonContractId = linearLocalThreadId % Properties::LocalThreadSizeNC;\n      contractId = linearLocalThreadId / Properties::LocalThreadSizeNC;\n      outScratchIndex = nonContractId + contractId * Properties::LocalThreadSizeNC;\n    }\n\n    out_scratch_ptr = local_output + outScratchIndex;\n    EIGEN_UNROLL_LOOP\n    for (StorageIndex j = 0; j < Properties::WorkLoadPerThreadNC; j++) {\n      EIGEN_UNROLL_LOOP\n      for (StorageIndex offset = Properties::LocalThreadSizeC >> 1; offset > 0; offset >>= 1) {\n        itemID.barrier(cl::sycl::access::fence_space::local_space);\n        if (contractId < offset) {\n          StorageIndex myNeigbourId = (Properties::LocalThreadSizeNC * offset);\n          *out_scratch_ptr += out_scratch_ptr[myNeigbourId];\n        }\n      }\n      // moving to next 16 by 16 block\n      out_scratch_ptr += (Properties::LocalThreadSizeNC * Properties::LocalThreadSizeC);\n    }\n\n    if (contractId == 0) {\n      out_scratch_ptr = local_output + nonContractId;\n      StorageIndex global_final_offset = nonContractGroupOffset + nonContractId;\n      out_ptr += global_final_offset;\n      EIGEN_UNROLL_LOOP\n      for (StorageIndex j = 0; j < Properties::WorkLoadPerThreadNC; j++) {\n        if (check_boundary<is_internal_block>(global_final_offset < nonContractDim)) {\n          auto res = *out_scratch_ptr;\n\n          *out_ptr = res;\n          out_ptr += Properties::LocalThreadSizeNC;\n        }\n        // moving to next 16 by 16 block to ge the next 16 reduced elements\n        out_scratch_ptr += (Properties::LocalThreadSizeNC * Properties::LocalThreadSizeC);\n        if (!(is_internal_block)) global_final_offset += Properties::LocalThreadSizeNC;\n      }\n    }\n  }\n\n  template <typename InputBlockProperties, bool is_internal_block, int CFactor, int GroupSize, typename Input,\n            typename Local>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void extract_block(const Input &inpt, Local *local_ptr,\n                                                                  const StorageIndex &linearLocalThreadId,\n                                                                  const StorageIndex &cOffset, const StorageIndex &C) {\n    local_ptr += InputBlockProperties::c_stride * linearLocalThreadId;\n    StorageIndex cIndex = cOffset;\n    for (StorageIndex cId = 0; cId < CFactor / InputBlockProperties::c_stride; cId++) {\n      if (check_boundary<is_internal_block>(cIndex + InputBlockProperties::c_stride - 1 < C)) {\n        auto val = read<InputBlockProperties::packet_load, InputBlockProperties::is_coalesced_layout,\n                        InputBlockProperties::is_rhs, typename InputBlockProperties::OutType>(inpt, StorageIndex(0),\n                                                                                              cIndex, StorageIndex(1));\n        write<StorageIndex, 1, data_source::local_mem>(val, local_ptr);\n      } else {\n        EIGEN_UNROLL_LOOP\n        for (StorageIndex i = 0; i < InputBlockProperties::elements_per_access; i++) {\n          OutScalar val =\n              (cIndex + i < C)\n                  ? read<false, InputBlockProperties::is_coalesced_layout, InputBlockProperties::is_rhs, OutScalar>(\n                        inpt, StorageIndex(0), cIndex + i, StorageIndex(1))\n                  : OutScalar(0);\n          write<StorageIndex, 1, data_source::local_mem>(val, local_ptr + i);\n        }\n      }\n      local_ptr += InputBlockProperties::c_stride * GroupSize;\n      cIndex += InputBlockProperties::c_stride * GroupSize;\n    }\n  }\n};\n#endif\n\n#ifndef EIGEN_SYCL_DISABLE_SCALAR\n\n/*!\n * \\brief GeneralScalarContraction is a template class that provides the scalar value of Tensor -Tensor contraction\n * operation, when all the dimensions are contracting dimensions. This Kernel reduces two tensors to an scalar\n *\n * \\tparam OutScalar: determines the output scalar type\n *\n * \\tparam LhsScalar: determines the left-hand-side scalar type\n *\n * \\tparam RhsScalar: determines the right-hand-side scalar type\n *\n * \\tparam OutAccessor: determines the sycl accessor type for out put (please see the sycl-1.2.1 specification\n * (https://www.khronos.org/registry/SYCL/specs/sycl-1.2.1.pdf) for accessor definition)\n *\n * \\tparam LhsMapper: determines the tensor contraction mapper type for left-hand-side matrix\n *\n * \\tparam RhsMapper: determines the tensor contraction mapper type for right-hand-side matrix\n *\n * \\tparam StorageIndex: determines the StorageIndex Type\n *\n * \\tparam Vectorizable: determines whether or not the vectorization is enabled for the Eigen expression.\n *\n * \\param scratch: local memory containing tiles of LHS and RHS tensors for each work-group\n *\n * \\param lhs: determines the left-hand-side flattened tensor (tensor mapper)\n *\n * \\param rhs: determines the right-hand-side flattened tensor (tensor mapper)\n *\n * \\param out_res: determines the output tensor containing the contraction result\n *\n * \\param rng: determins the total input data size\n */\ntemplate <typename OutScalar, typename LhsScalar, typename RhsScalar, typename OutAccessor, typename LhsMapper,\n          typename RhsMapper, typename StorageIndex, bool Vectorizable>\nstruct GeneralScalarContraction {\n  typedef cl::sycl::accessor<OutScalar, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local> Scratch;\n  Scratch scratch;\n  const LhsMapper lhs;\n  const RhsMapper rhs;\n  OutAccessor out_res;\n  const StorageIndex rng;\n\n  EIGEN_DEVICE_FUNC\n  GeneralScalarContraction(Scratch scratch_, const LhsMapper lhs_, const RhsMapper rhs_, OutAccessor out_res_,\n                           const StorageIndex rng_)\n      : scratch(scratch_), lhs(lhs_), rhs(rhs_), out_res(out_res_), rng(rng_) {}\n\n  EIGEN_DEVICE_FUNC void operator()(cl::sycl::nd_item<1> itemID) {\n    auto out_ptr = out_res.get_pointer();\n    auto scratch_ptr = scratch.get_pointer().get();\n\n    StorageIndex globalid = itemID.get_global_id(0);\n    StorageIndex localid = itemID.get_local_id(0);\n    OutScalar accumulator = OutScalar(0);\n    for (StorageIndex i = globalid; i < rng; i += itemID.get_global_range(0)) {\n      accumulator = cl::sycl::mad(lhs(0, i), rhs(i, 0), accumulator);\n    }\n    auto out_scratch_ptr = scratch_ptr + localid;\n    *out_scratch_ptr = accumulator;\n    for (StorageIndex offset = itemID.get_local_range(0) >> 1; offset > 0; offset >>= 1) {\n      itemID.barrier(cl::sycl::access::fence_space::local_space);\n      if (localid < offset) {\n        *out_scratch_ptr = (accumulator += out_scratch_ptr[offset]);\n      }\n    }\n    if (localid == 0) {\n      out_ptr[itemID.get_group(0)] = accumulator;\n    }\n  }\n};\n#endif\n\n}  // namespace internal\n}  // namespace TensorSycl\n\ntemplate <typename Indices, typename LeftArgType, typename RightArgType, typename OutputKernelType>\nstruct TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>,\n                       Eigen::SyclDevice>\n    : public TensorContractionEvaluatorBase<TensorEvaluator<\n          const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, Eigen::SyclDevice>> {\n  static_assert(std::is_same<OutputKernelType, const NoOpOutputKernel>::value,\n                \"SYCL tensor contraction does not support output kernels.\");\n\n  typedef Eigen::SyclDevice Device;\n\n  typedef TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, Device> Self;\n  typedef TensorContractionEvaluatorBase<Self> Base;\n  typedef TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType> XprType;\n  typedef typename internal::remove_const<typename XprType::Scalar>::type Scalar;\n  typedef typename XprType::Index StorageIndex;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef typename Base::Storage Storage;\n  typedef typename Base::EvaluatorPointerType EvaluatorPointerType;\n  struct TripleDim {\n    const StorageIndex M;\n    const StorageIndex N;\n    const StorageIndex K;\n    TripleDim(const StorageIndex M_, const StorageIndex N_, const StorageIndex K_) : M(M_), N(N_), K(K_) {}\n  };\n  enum {\n    Layout = TensorEvaluator<LeftArgType, Device>::Layout,\n    PacketAccess = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess = false,\n  };\n\n  static EIGEN_CONSTEXPR int LDims = Base::LDims;\n  static EIGEN_CONSTEXPR int RDims = Base::RDims;\n  static EIGEN_CONSTEXPR int ContractDims = Base::ContractDims;\n\n  typedef array<StorageIndex, LDims> left_dim_mapper_t;\n  typedef array<StorageIndex, RDims> right_dim_mapper_t;\n\n  typedef array<StorageIndex, ContractDims> contract_t;\n  typedef array<StorageIndex, LDims - ContractDims> left_nocontract_t;\n  typedef array<StorageIndex, RDims - ContractDims> right_nocontract_t;\n\n  static const int NumDims = LDims + RDims - 2 * ContractDims;\n\n  typedef DSizes<StorageIndex, NumDims> Dimensions;\n\n  typedef TensorEvaluator<typename Base::EvalLeftArgType, Device> LeftEvaluator;\n  typedef TensorEvaluator<typename Base::EvalRightArgType, Device> RightEvaluator;\n  typedef typename Eigen::internal::remove_const<typename LeftEvaluator::CoeffReturnType>::type LhsScalar;\n  typedef typename Eigen::internal::remove_const<typename RightEvaluator::CoeffReturnType>::type RhsScalar;\n\n  typedef typename LeftEvaluator::Dimensions LeftDimensions;\n  typedef typename RightEvaluator::Dimensions RightDimensions;\n\n  template <bool lhs_inner_dim_contiguous, bool rhs_inner_dim_contiguous, bool rhs_inner_dim_reordered>\n  struct input_mapper_propertis {\n    static EIGEN_CONSTEXPR bool is_lhs_matrix = (LDims == 2 && ContractDims == 1) || lhs_inner_dim_contiguous;\n    static EIGEN_CONSTEXPR bool is_rhs_matrix =\n        (RDims == 2 && ContractDims == 1) || (rhs_inner_dim_contiguous && !rhs_inner_dim_reordered);\n  };\n\n  TensorEvaluator(const XprType &op, const Device &device) : Base(op, device) {}\n\n  // We need to redefine this method to make nvcc happy\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(typename Base::EvaluatorPointerType data) {\n    this->m_leftImpl.evalSubExprsIfNeeded(NULL);\n    this->m_rightImpl.evalSubExprsIfNeeded(NULL);\n    if (!data) {\n      this->m_result = this->m_device.get(\n          static_cast<Scalar *>(this->m_device.allocate_temp(this->dimensions().TotalSize() * sizeof(Scalar))));\n      data = this->m_result;\n    }\n    evalToSycl(data);\n    return (this->m_result != NULL);\n  }\n  const Eigen::SyclDevice &device() const { return this->m_device; }\n  void evalToSycl(typename Base::EvaluatorPointerType buffer) const {\n    if (this->m_lhs_inner_dim_contiguous) {\n      if (this->m_rhs_inner_dim_contiguous) {\n        if (this->m_rhs_inner_dim_reordered) {\n          evalTyped<true, true, true, Unaligned>(buffer);\n        } else {\n          evalTyped<true, true, false, Unaligned>(buffer);\n        }\n      } else {\n        if (this->m_rhs_inner_dim_reordered) {\n          evalTyped<true, false, true, Unaligned>(buffer);\n        } else {\n          evalTyped<true, false, false, Unaligned>(buffer);\n        }\n      }\n    } else {\n      if (this->m_rhs_inner_dim_contiguous) {\n        if (this->m_rhs_inner_dim_reordered) {\n          evalTyped<false, true, true, Unaligned>(buffer);\n        } else {\n          evalTyped<false, true, false, Unaligned>(buffer);\n        }\n      } else {\n        if (this->m_rhs_inner_dim_reordered) {\n          evalTyped<false, false, true, Unaligned>(buffer);\n        } else {\n          evalTyped<false, false, false, Unaligned>(buffer);\n        }\n      }\n    }\n  }\n\n  template <bool lhs_inner_dim_contiguous, bool rhs_inner_dim_contiguous, bool rhs_inner_dim_reordered, int Alignment>\n  void evalTyped(typename Base::EvaluatorPointerType buffer) const {\n    const auto triple_dim = TripleDim{this->m_i_size, this->m_j_size, this->m_k_size};\n    typedef internal::TensorContractionInputMapper<\n        LhsScalar, StorageIndex, internal::Lhs, LeftEvaluator, left_nocontract_t, contract_t,\n        PacketType<CoeffReturnType, Device>::size, lhs_inner_dim_contiguous, false, Unaligned, MakeSYCLPointer>\n        LhsMapper;\n\n    typedef internal::TensorContractionInputMapper<RhsScalar, StorageIndex, internal::Rhs, RightEvaluator,\n                                                   right_nocontract_t, contract_t,\n                                                   PacketType<CoeffReturnType, Device>::size, rhs_inner_dim_contiguous,\n                                                   rhs_inner_dim_reordered, Unaligned, MakeSYCLPointer>\n        RhsMapper;\n\n    // initialize data mappers\n    LhsMapper lhs(this->m_leftImpl, this->m_left_nocontract_strides, this->m_i_strides,\n                  this->m_left_contracting_strides, this->m_k_strides);\n\n    RhsMapper rhs(this->m_rightImpl, this->m_right_nocontract_strides, this->m_j_strides,\n                  this->m_right_contracting_strides, this->m_k_strides);\n\n#ifndef EIGEN_SYCL_DISABLE_SCALAR\n    if (triple_dim.M == 1 && triple_dim.N == 1) {\n      launchSC(buffer, lhs, rhs, triple_dim.K);\n    } else\n#endif\n#ifndef EIGEN_SYCL_DISABLE_GEMV\n        if (triple_dim.M != 1 && triple_dim.N == 1) {\n      LaunchVT<false>(buffer, rhs, lhs, triple_dim.M, triple_dim.K);\n    } else if (triple_dim.M == 1 && triple_dim.N != 1) {\n      LaunchVT<true>(buffer, lhs, rhs, triple_dim.N, triple_dim.K);\n    } else  // This is equivalent of if (m!=1 && n!=1)\n#endif\n    {\n      typedef input_mapper_propertis<lhs_inner_dim_contiguous, rhs_inner_dim_contiguous, rhs_inner_dim_reordered>\n          inpt_mapper_properties;\n#ifndef EIGEN_SYCL_DISABLE_SKINNY\n      bool skinny = false;\n      auto platform_name = this->device().getPlatformName();\n      // This is based on empirical calculation for AMD r9-nano and Fiji\n      if (platform_name.find(\"AMD\") == 0) {\n        skinny = (triple_dim.M < triple_dim.K || triple_dim.N < triple_dim.K) &&\n                 ((triple_dim.M < 1024 && triple_dim.N < 1024) ||\n                  (uint64_t(triple_dim.M * triple_dim.N) < uint64_t(triple_dim.K)));\n      } else {\n        skinny = (((std::max(triple_dim.K, triple_dim.N) / std::min(triple_dim.K, triple_dim.N)) > 100) ||\n                  ((std::max(triple_dim.K, triple_dim.M) / std::min(triple_dim.K, triple_dim.M)) > 100) ||\n                  ((std::max(triple_dim.N, triple_dim.M) / std::min(triple_dim.N, triple_dim.M)) > 100));\n      }\n      if (skinny)\n        adjustTT<true, inpt_mapper_properties>(buffer, lhs, rhs, triple_dim);\n      else\n#endif  // EIGEN_SYCL_DISABLE_SKINNY\n        adjustTT<false, inpt_mapper_properties>(buffer, lhs, rhs, triple_dim);\n    }\n  }\n\n  template <bool skinny, typename input_mapper_properties, typename LhsMapper, typename RhsMapper>\n  void EIGEN_ALWAYS_INLINE adjustTT(EvaluatorPointerType buffer, const LhsMapper &lhs, const RhsMapper &rhs,\n                                    const TripleDim &triple_dim) const {\n#ifdef EIGEN_SYCL_LOCAL_MEM_UNSET_OR_ON\n    if (device().has_local_memory()) {\n      typedef TensorSycl::internal::TTPanelSize<CoeffReturnType, StorageIndex, 4, 4, 16> PanelParameters;\n      launchTT<TensorSycl::internal::contraction_type::local, skinny, input_mapper_properties, PanelParameters>(\n          buffer, lhs, rhs, triple_dim);\n    }\n#endif\n#ifdef EIGEN_SYCL_LOCAL_MEM_UNSET_OR_OFF\n    if (!(device().has_local_memory())) {\n      typedef TensorSycl::internal::TTPanelSize<CoeffReturnType, StorageIndex, 4, 4, 4> PanelParameters;\n      launchTT<TensorSycl::internal::contraction_type::no_local, skinny, input_mapper_properties, PanelParameters>(\n          buffer, lhs, rhs, triple_dim);\n    }\n#endif\n  }\n\n  template <TensorSycl::internal::contraction_type ct, bool skinny, typename input_mapper_properties,\n            typename Properties, typename LhsMapper, typename RhsMapper>\n  void launchTT(EvaluatorPointerType buffer, const LhsMapper &lhs, const RhsMapper &rhs,\n                const TripleDim &triple_dim) const {\n    const StorageIndex roundUpM = Eigen::TensorSycl::internal::roundUp(triple_dim.M, Properties::TileSizeDimM);\n    const StorageIndex roundUpN = Eigen::TensorSycl::internal::roundUp(triple_dim.N, Properties::TileSizeDimN);\n    const StorageIndex groupSizeM = roundUpM / Properties::TileSizeDimM;\n    const StorageIndex groupSizeN = roundUpN / Properties::TileSizeDimN;\n\n    const StorageIndex roundUpK = Eigen::TensorSycl::internal::roundUp(triple_dim.K, Properties::TileSizeDimK);\n    StorageIndex totalTilesK = roundUpK / Properties::TileSizeDimK;\n    StorageIndex groupSizeK =\n        skinny\n            ? std::max(std::min(totalTilesK,\n                                (StorageIndex)(device().getPowerOfTwo(device().getNumSyclMultiProcessors(), true) * 4) /\n                                    (groupSizeM * groupSizeN)),\n                       StorageIndex(1))\n            : StorageIndex(1);\n\n    const StorageIndex numTilesPerGroup = Eigen::TensorSycl::internal::roundUp(totalTilesK, groupSizeK) / groupSizeK;\n\n    const StorageIndex totalGroupSize = groupSizeM * groupSizeN * groupSizeK;\n\n    const StorageIndex localRange = Properties::LocalThreadSizeM * Properties::LocalThreadSizeN;\n    const StorageIndex globalRange = totalGroupSize * localRange;\n\n    const StorageIndex scratchSize = (ct == TensorSycl::internal::contraction_type::local)\n                                         ? ((Properties::DoubleBuffer + 1) *\n                                            (Properties::TileSizeDimM + Properties::BC) * (Properties::TileSizeDimK)) +\n                                               ((Properties::DoubleBuffer + 1) * (Properties::TileSizeDimK) *\n                                                (Properties::TileSizeDimN + Properties::BC))\n                                         : StorageIndex(1);\n\n    auto thread_range = cl::sycl::nd_range<1>(cl::sycl::range<1>(globalRange), cl::sycl::range<1>(localRange));\n    if (groupSizeK == 1) {\n      typedef TensorSycl::internal::TensorContractionKernel<CoeffReturnType, LhsScalar, RhsScalar, EvaluatorPointerType,\n                                                            LhsMapper, RhsMapper, StorageIndex, Properties, TripleDim,\n                                                            PacketAccess, input_mapper_properties, true, ct>\n          ContractKernelName;\n      device().template binary_kernel_launcher<CoeffReturnType, ContractKernelName>(\n          lhs, rhs, buffer, thread_range, scratchSize, groupSizeM, groupSizeN, numTilesPerGroup, triple_dim);\n    } else {\n      typedef TensorSycl::internal::TensorContractionKernel<CoeffReturnType, LhsScalar, RhsScalar, EvaluatorPointerType,\n                                                            LhsMapper, RhsMapper, StorageIndex, Properties, TripleDim,\n                                                            PacketAccess, input_mapper_properties, false, ct>\n          ContractKernelName;\n      CoeffReturnType *temp_pointer = static_cast<CoeffReturnType *>(\n          device().allocate_temp(triple_dim.M * triple_dim.N * groupSizeK * sizeof(CoeffReturnType)));\n      EvaluatorPointerType tmp_global_accessor = device().get(temp_pointer);\n\n      device().template binary_kernel_launcher<CoeffReturnType, ContractKernelName>(\n          lhs, rhs, tmp_global_accessor, thread_range, scratchSize, groupSizeM, groupSizeN, numTilesPerGroup,\n          triple_dim);\n\n      typedef Eigen::internal::SumReducer<CoeffReturnType> Op;\n      auto op = Op();\n      typedef TensorSycl::internal::SecondStepPartialReduction<CoeffReturnType, StorageIndex, EvaluatorPointerType,\n                                                               EvaluatorPointerType, Op>\n          ReductionKernel;\n\n      device().template unary_kernel_launcher<CoeffReturnType, ReductionKernel>(\n          tmp_global_accessor, buffer,\n          cl::sycl::nd_range<1>(cl::sycl::range<1>(StorageIndex(\n                                    Eigen::TensorSycl::internal::roundUp(triple_dim.M * triple_dim.N, localRange))),\n                                cl::sycl::range<1>(localRange)),\n          StorageIndex(1), op, StorageIndex(triple_dim.M * triple_dim.N), groupSizeK);\n\n      device().deallocate_temp(temp_pointer);\n    }\n  }\n\n#ifndef EIGEN_SYCL_DISABLE_GEMV\n  template <bool is_lhs_vec, typename VectorMapper, typename TensorMapper, typename StorageIndex>\n  void EIGEN_ALWAYS_INLINE LaunchVT(EvaluatorPointerType buffer, const VectorMapper &vec, const TensorMapper &mat,\n                                    StorageIndex NC, StorageIndex C) const {\n    const StorageIndex nonContractDim = NC;\n    EIGEN_CONSTEXPR StorageIndex NCFactor = 1;\n    EIGEN_CONSTEXPR StorageIndex CFactor = 1;\n    EIGEN_CONSTEXPR StorageIndex NCWindow = 16;\n    typedef Eigen::TensorSycl::internal::TVPanelSize<CoeffReturnType, StorageIndex, NCWindow, CFactor, NCFactor>\n        Properties;\n    const StorageIndex roundUpC = Eigen::TensorSycl::internal::roundUp(C, Properties::TileSizeDimC);\n    const StorageIndex cNumGroups = roundUpC / (Properties::LocalThreadSizeC * Properties::WorkLoadPerThreadC);\n    const StorageIndex roundUpNC = Eigen::TensorSycl::internal::roundUp(nonContractDim, Properties::TileSizeDimNC);\n    const StorageIndex nCNumGroups = roundUpNC / (Properties::LocalThreadSizeNC * Properties::WorkLoadPerThreadNC);\n    const StorageIndex globalRange =\n        (roundUpNC / (Properties::WorkLoadPerThreadNC)) * (roundUpC / (Properties::WorkLoadPerThreadC));\n    const StorageIndex localRange = Properties::LocalThreadSizeNC * Properties::LocalThreadSizeC;\n    const StorageIndex scratchSize =\n        (Properties::WorkLoadPerThreadNC + CFactor) * Properties::LocalThreadSizeC * Properties::LocalThreadSizeNC;\n    auto thread_range = cl::sycl::nd_range<1>(cl::sycl::range<1>(globalRange), cl::sycl::range<1>(localRange));\n    if (cNumGroups > 1) {\n      typedef Eigen::TensorSycl::internal::GeneralVectorTensor<CoeffReturnType, EvaluatorPointerType, VectorMapper,\n                                                               TensorMapper, StorageIndex, Properties, CFactor, false,\n                                                               is_lhs_vec, false>\n          ContractKernelName;\n      CoeffReturnType *temp_pointer =\n          static_cast<CoeffReturnType *>(device().allocate_temp(nonContractDim * cNumGroups * sizeof(CoeffReturnType)));\n      EvaluatorPointerType tmp_global_accessor = device().get(temp_pointer);\n\n      device().template binary_kernel_launcher<CoeffReturnType, ContractKernelName>(\n          vec, mat, tmp_global_accessor, thread_range, scratchSize, nCNumGroups, nonContractDim, C);\n\n      typedef Eigen::internal::SumReducer<CoeffReturnType> Op;\n      typedef TensorSycl::internal::SecondStepPartialReduction<CoeffReturnType, StorageIndex, EvaluatorPointerType,\n                                                               EvaluatorPointerType, Op>\n          ReductionKernel;\n\n      device().template unary_kernel_launcher<CoeffReturnType, ReductionKernel>(\n          tmp_global_accessor, buffer,\n          cl::sycl::nd_range<1>(cl::sycl::range<1>(Eigen::TensorSycl::internal::roundUp(nonContractDim, localRange)),\n                                cl::sycl::range<1>(localRange)),\n          StorageIndex(1), Op(), nonContractDim, cNumGroups);\n\n      device().deallocate_temp(temp_pointer);\n    } else {\n      typedef Eigen::TensorSycl::internal::GeneralVectorTensor<CoeffReturnType, EvaluatorPointerType, VectorMapper,\n                                                               TensorMapper, StorageIndex, Properties, CFactor, false,\n                                                               is_lhs_vec, true>\n          ContractKernelName;\n      device().template binary_kernel_launcher<CoeffReturnType, ContractKernelName>(\n          vec, mat, buffer, thread_range, scratchSize, nCNumGroups, nonContractDim, C);\n    }\n  }\n#endif\n\n#ifndef EIGEN_SYCL_DISABLE_SCALAR\n  template <typename LhsMapper, typename RhsMapper>\n  EIGEN_ALWAYS_INLINE void launchSC(EvaluatorPointerType buffer, const LhsMapper &lhs, const RhsMapper &rhs,\n                                    StorageIndex K) const {\n    EIGEN_STATIC_ASSERT(!((EIGEN_SYCL_LOCAL_THREAD_DIM0 * EIGEN_SYCL_LOCAL_THREAD_DIM1) &\n                          (EIGEN_SYCL_LOCAL_THREAD_DIM0 * EIGEN_SYCL_LOCAL_THREAD_DIM1 - 1)),\n                        \"The Local thread size must be a power of 2 for the reduction \"\n                        \"operation\");\n    EIGEN_CONSTEXPR StorageIndex local_range = EIGEN_SYCL_LOCAL_THREAD_DIM0 * EIGEN_SYCL_LOCAL_THREAD_DIM1;\n\n    // Here we force the code not to be more than 2-step reduction: Our empirical research shows that if each thread\n    // reduces at least 512 elementss individually, we get better performance.\n    const StorageIndex num_work_group = ((K + (512 * local_range - 1)) / (512 * local_range) > 1 ? local_range : 1);\n    const StorageIndex global_range = num_work_group * local_range;\n\n    typedef Eigen::TensorSycl::internal::GeneralScalarContraction<\n        CoeffReturnType, LhsScalar, RhsScalar, EvaluatorPointerType, LhsMapper, RhsMapper, StorageIndex, false>\n        ContractKernelName;\n    auto thread_range = cl::sycl::nd_range<1>(cl::sycl::range<1>(global_range), cl::sycl::range<1>(local_range));\n    if (num_work_group > 1) {\n      CoeffReturnType *temp_pointer =\n          static_cast<CoeffReturnType *>(device().allocate_temp(num_work_group * sizeof(CoeffReturnType)));\n      EvaluatorPointerType tmp_global_accessor = device().get(temp_pointer);\n      device().template binary_kernel_launcher<CoeffReturnType, ContractKernelName>(lhs, rhs, tmp_global_accessor,\n                                                                                    thread_range, local_range, K);\n      typedef Eigen::internal::SumReducer<CoeffReturnType> Op;\n      typedef TensorSycl::internal::SecondStepFullReducer<CoeffReturnType, Op, EvaluatorPointerType,\n                                                          EvaluatorPointerType, StorageIndex, local_range>\n          GenericRKernel;\n      device().template unary_kernel_launcher<CoeffReturnType, GenericRKernel>(\n          tmp_global_accessor, buffer,\n          cl::sycl::nd_range<1>(cl::sycl::range<1>(local_range), cl::sycl::range<1>(local_range)), local_range, Op());\n\n      device().deallocate_temp(temp_pointer);\n    } else {\n      device().template binary_kernel_launcher<CoeffReturnType, ContractKernelName>(lhs, rhs, buffer, thread_range,\n                                                                                    local_range, K);\n    }\n  }\n#endif\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    this->m_leftImpl.cleanup();\n    this->m_rightImpl.cleanup();\n\n    if (this->m_result) {\n      this->m_device.deallocate_temp(this->m_result);\n      this->m_result = NULL;\n    }\n  }\n  // The placeholder accessors must bound to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    this->m_leftImpl.bind(cgh);\n    this->m_rightImpl.bind(cgh);\n    this->m_result.bind(cgh);\n  }\n};\n}  // namespace Eigen\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_SYCL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionThreadPool.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_THREAD_POOL_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_THREAD_POOL_H\n\n// evaluator for thread pool device\n#ifdef EIGEN_USE_THREADS\n\nnamespace Eigen {\n\ntemplate<typename Indices, typename LeftArgType, typename RightArgType, typename OutputKernelType>\nstruct TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, ThreadPoolDevice> :\n    public TensorContractionEvaluatorBase<TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, ThreadPoolDevice> > {\n\n  typedef ThreadPoolDevice Device;\n\n  typedef TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, Device> Self;\n  typedef TensorContractionEvaluatorBase<Self> Base;\n\n  typedef TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType> XprType;\n  typedef typename internal::remove_const<typename XprType::Scalar>::type Scalar;\n  typedef typename XprType::Index Index;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n\n  enum {\n    Layout = TensorEvaluator<LeftArgType, Device>::Layout,\n  };\n\n  // Most of the code is assuming that both input tensors are ColMajor. If the\n  // inputs are RowMajor, we will \"cheat\" by swapping the LHS and RHS:\n  // If we want to compute A * B = C, where A is LHS and B is RHS, the code\n  // will pretend B is LHS and A is RHS.\n  typedef typename internal::conditional<\n    static_cast<int>(Layout) == static_cast<int>(ColMajor), LeftArgType, RightArgType>::type EvalLeftArgType;\n  typedef typename internal::conditional<\n    static_cast<int>(Layout) == static_cast<int>(ColMajor), RightArgType, LeftArgType>::type EvalRightArgType;\n\n  static const int LDims =\n      internal::array_size<typename TensorEvaluator<EvalLeftArgType, Device>::Dimensions>::value;\n  static const int RDims =\n      internal::array_size<typename TensorEvaluator<EvalRightArgType, Device>::Dimensions>::value;\n  static const int ContractDims = internal::array_size<Indices>::value;\n\n  typedef array<Index, LDims> left_dim_mapper_t;\n  typedef array<Index, RDims> right_dim_mapper_t;\n\n  typedef array<Index, ContractDims> contract_t;\n  typedef array<Index, LDims - ContractDims> left_nocontract_t;\n  typedef array<Index, RDims - ContractDims> right_nocontract_t;\n\n  static const int NumDims = LDims + RDims - 2 * ContractDims;\n\n  typedef DSizes<Index, NumDims> Dimensions;\n\n  // typedefs needed in evalTo\n  typedef typename internal::remove_const<typename EvalLeftArgType::Scalar>::type LhsScalar;\n  typedef typename internal::remove_const<typename EvalRightArgType::Scalar>::type RhsScalar;\n  typedef typename internal::gebp_traits<LhsScalar, RhsScalar> Traits;\n\n  typedef TensorEvaluator<EvalLeftArgType, Device> LeftEvaluator;\n  typedef TensorEvaluator<EvalRightArgType, Device> RightEvaluator;\n\n  TensorEvaluator(const XprType& op, const Device& device) :\n      Base(op, device) {}\n\n  template <int Alignment>\n  void evalProduct(Scalar* buffer) const {\n    evalProductImpl<NoCallback, Alignment>(buffer, NoCallback());\n  }\n\n  template <typename EvalToCallback, int Alignment>\n  void evalProductAsync(Scalar* buffer, EvalToCallback done) const {\n    evalProductImpl<EvalToCallback, Alignment>(buffer, std::move(done));\n  }\n\n  template <typename DoneCallback, int Alignment>\n  void evalProductImpl(Scalar* buffer, DoneCallback done) const {\n    // This function computes a lot of heuristics in multiple steps, and it\n    // also has multiple exit points. To keep it sane, readable and all in one\n    // place, sync/async execution decision is made at runtime at the very end.\n    //\n    // (1) In sync mode we allocate Context on the stack, submit computations\n    //     to the device thread pool, and block on a barrier until it is\n    //     completed.\n    //\n    // (2) In async mode we allocate Context on the heap, and after all tasks\n    //     are finished, we call provided the done callback, and delete a\n    //     context from the heap.\n    //\n    // (*) EvalParallelContext & EvalShardedByInnerDimContext owns all the state\n    // and temporary buffers, requried for executing the tensor contraction.\n    // They are responsible for cleaning it up after contraction is done.\n    static const bool IsEvalInSyncMode =\n        std::is_same<DoneCallback, NoCallback>::value;\n\n    const Index m = this->m_i_size;\n    const Index n = this->m_j_size;\n    const Index k = this->m_k_size;\n    if (m == 0 || n == 0 || k == 0) return;\n\n    // Compute a set of algorithm parameters:\n    // - kernel block sizes (bm, bn, bk)\n    // - task grain sizes (number of kernels executed per task: gm, gn)\n    // - number of threads\n    // - sharding by row/column\n    // - parallel packing or first lhs then rhs\n    // and some derived parameters:\n    // - number of tasks (nm, nn, nk)\n    // - number of kernels (nm0, nn0)\n    // Unfortunately, all these parameters are tightly interdependent.\n    // So in some cases we first compute approximate values, then compute other\n    // values based on these approximations and then refine the approximations.\n\n    // There are lots of heuristics here. There is some reasoning behind them,\n    // but ultimately they are just tuned on contraction benchmarks for\n    // different input configurations, thread counts and instruction sets.\n    // So feel free to question any of them.\n\n    // Compute whether we want to shard by row or by column.\n    // This is a first approximation, it will be refined later. Since we don't\n    // know number of threads yet we use 2, because what's we are most\n    // interested in at this point is whether it makes sense to use\n    // parallelization at all or not.\n    bool shard_by_col = shardByCol(m, n, 2);\n\n    // First approximation of kernel blocking sizes.\n    // Again, we don't know number of threads yet, so we use 2.\n    Index bm, bn, bk;\n    if (shard_by_col) {\n      internal::TensorContractionBlocking<Scalar, LhsScalar, RhsScalar, Index,\n                                          internal::ShardByCol>\n          blocking(k, m, n, 2);\n      bm = blocking.mc();\n      bn = blocking.nc();\n      bk = blocking.kc();\n    } else {\n      internal::TensorContractionBlocking<Scalar, LhsScalar, RhsScalar, Index,\n                                          internal::ShardByRow>\n          blocking(k, m, n, 2);\n      bm = blocking.mc();\n      bn = blocking.nc();\n      bk = blocking.kc();\n    }\n\n    // Compute optimal number of threads.\n    // Note: we use bk instead of k here because we are interested in amount of\n    // _parallelizable_ computations, and computations are not parallelizable\n    // across k dimension.\n    const TensorOpCost cost =\n        contractionCost(m, n, bm, bn, bk, shard_by_col, false);\n    int num_threads = TensorCostModel<ThreadPoolDevice>::numThreads(\n        static_cast<double>(n) * m, cost, this->m_device.numThreads());\n    int num_threads_by_k = numThreadsInnerDim(m, n, k);\n    if (shardByInnerDim(m, n, k, num_threads, num_threads_by_k)) {\n      // We are in the scenario where it is more effective to shard by the\n      // inner dimension.\n      if (IsEvalInSyncMode) {\n        EvalShardedByInnerDimContext<DoneCallback> ctx(\n            this, num_threads_by_k, buffer, m, n, k, std::move(done));\n        ctx.template run<Alignment>();\n      } else {\n        auto* ctx = new EvalShardedByInnerDimContext<DoneCallback>(\n            this, num_threads_by_k, buffer, m, n, k, std::move(done));\n        ctx->template runAsync<Alignment>();\n      }\n\n      return;\n    }\n\n    // TODO(dvyukov): this is a stop-gap to prevent regressions while the cost\n    // model is not tuned. Remove this when the cost model is tuned.\n    if (n == 1) num_threads = 1;\n\n    if (num_threads == 1) {\n      TENSOR_CONTRACTION_DISPATCH(this->template evalProductSequential,\n                                  Unaligned, (buffer));\n      if (!IsEvalInSyncMode) done();\n      return;\n    }\n\n    // Now that we know number of threads, recalculate sharding and blocking.\n    shard_by_col = shardByCol(m, n, num_threads);\n    if (shard_by_col) {\n      internal::TensorContractionBlocking<Scalar, LhsScalar, RhsScalar, Index,\n                                          internal::ShardByCol>\n          blocking(k, m, n, num_threads);\n      bm = blocking.mc();\n      bn = blocking.nc();\n      bk = blocking.kc();\n    } else {\n      internal::TensorContractionBlocking<Scalar, LhsScalar, RhsScalar, Index,\n                                          internal::ShardByRow>\n          blocking(k, m, n, num_threads);\n      bm = blocking.mc();\n      bn = blocking.nc();\n      bk = blocking.kc();\n    }\n\n    // Number of kernels for each dimension.\n    Index nm0 = divup(m, bm);\n    Index nn0 = divup(n, bn);\n    Index nk = divup(k, bk);\n\n    // Calculate task grain size (number of kernels executed per task).\n    // This task size coarsening serves two purposes:\n    // 1. It reduces per-task overheads including synchronization overheads.\n    // 2. It allows to use caches better (reuse the same packed rhs in several\n    // consecutive kernels).\n    Index gm = 1;\n    Index gn = 1;\n    // If we are sharding by column, then we prefer to reduce rows first.\n    if (shard_by_col) {\n      gm = coarsenM(m, n, bm, bn, bk, gn, num_threads, shard_by_col);\n      gn = coarsenN(m, n, bm, bn, bk, gm, num_threads, shard_by_col);\n    } else {\n      gn = coarsenN(m, n, bm, bn, bk, gm, num_threads, shard_by_col);\n      gm = coarsenM(m, n, bm, bn, bk, gn, num_threads, shard_by_col);\n    }\n    // Number of tasks in each dimension.\n    Index nm = divup(nm0, gm);\n    Index nn = divup(nn0, gn);\n\n    // If there is enough concurrency in the sharding dimension, we choose not\n    // to paralellize by the other dimension, and execute all kernels in sync\n    // mode. This reduces parallelism from the nm x nn down to nn\n    // (shard_by_col==true) or nm (shard_by_col==false).\n    const Index sharding_dim_tasks = shard_by_col ? nn : nm;\n    const int num_worker_threads = this->m_device.numThreadsInPool();\n\n    // With small number of threads we want to make sure that we do not reduce\n    // parallelism too much. With large number of threads we trade maximum\n    // parallelism for better memory locality.\n    const float oversharding_factor =\n        num_worker_threads <= 4  ? 8.0 :\n        num_worker_threads <= 8  ? 4.0 :\n        num_worker_threads <= 16 ? 2.0 :\n        num_worker_threads <= 32 ? 1.0 :\n        num_worker_threads <= 64 ? 0.8 : /* num_worker_threads > 64 */ 0.6;\n\n    const bool parallelize_by_sharding_dim_only =\n        sharding_dim_tasks >= oversharding_factor * num_worker_threads;\n\n    // Last by not least, decide whether we want to issue both lhs and rhs\n    // packing in parallel; or issue lhs packing first, and then issue rhs\n    // packing when lhs packing completes (for !shard_by_col lhs and rhs are\n    // swapped). Parallel packing allows more parallelism (for both packing and\n    // kernels), while sequential packing provides better locality (once\n    // a thread finishes rhs packing it proceed to kernels with that rhs).\n    // First, we are interested in parallel packing if there are few tasks.\n    bool parallel_pack = num_threads >= nm * nn;\n    // Also do parallel packing if all data fits into L2$.\n    if (m * bk * Index(sizeof(LhsScalar)) + n * bk * Index(sizeof(RhsScalar)) <=\n        l2CacheSize() * num_threads)\n      parallel_pack = true;\n    // But don't do it if we will use each rhs only once. Locality seems to be\n    // more important in this case.\n    if ((shard_by_col ? nm : nn) == 1) parallel_pack = false;\n    // Also don't get in the way of parallelize_by_sharding_dim_only\n    // optimization.\n    if (parallelize_by_sharding_dim_only) parallel_pack = false;\n\n    // TODO(ezhulnev): With if contexpr we don't need SyncEvalParallelContext.\n    if (IsEvalInSyncMode) {\n#define CONTEXT_ARGS                                                        \\\n  (this, num_threads, buffer, m, n, k, bm, bn, bk, nm, nn, nk, gm, gn, nm0, \\\n   nn0, shard_by_col, parallel_pack, parallelize_by_sharding_dim_only,      \\\n   NoCallback())                                                            \\\n      .run()\n      TENSOR_CONTRACTION_DISPATCH(SyncEvalParallelContext, Alignment,\n                                  CONTEXT_ARGS);\n#undef CONTEXT_ARGS\n\n    } else {\n#define CONTEXT_ARGS                                                        \\\n  (this, num_threads, buffer, m, n, k, bm, bn, bk, nm, nn, nk, gm, gn, nm0, \\\n   nn0, shard_by_col, parallel_pack, parallelize_by_sharding_dim_only,      \\\n   std::move(done))\n      TENSOR_CONTRACTION_ASYNC_DISPATCH(EvalParallelContext, DoneCallback,\n                                        Alignment, CONTEXT_ARGS, run());\n#undef CONTEXT_ARGS\n    }\n  }\n\n  // ------------------------------------------------------------------------ //\n\n  // Dummy struct to represent an empty DoneCallback.\n\n  struct NoCallback {\n    void operator()() {\n      eigen_assert(false && \"NoCallback should never be called\");\n    }\n  };\n\n  // ------------------------------------------------------------------------ //\n\n  template <typename DoneCallback, typename Context>\n  class EvalParallelNotification;\n\n  // Synchronous evaluation notification that blocks caller thread in Wait().\n  template <typename Context>\n  class EvalParallelNotification<NoCallback, Context> {\n   public:\n    EvalParallelNotification(Context*, NoCallback) {}\n    void Notify() { done_.Notify(); }\n    void Wait() { done_.Wait(); }\n   private:\n    Eigen::Notification done_;\n  };\n\n  // Asynchronous evaluation notification that does not block in Wait().\n  template <typename DoneCallback, typename Context>\n  class EvalParallelNotification {\n   public:\n    EvalParallelNotification(Context* ctx, DoneCallback done)\n        : ctx_(ctx), done_(std::move(done)) {}\n\n    void Notify() {\n      // Make a copy of done callback, because it will be destructed when we\n      // will delete context in the next line (EvalParallelNotification is a\n      // data member of EvalParallelContext class).\n      DoneCallback done_copy = std::move(done_);\n\n      // Delete parallel evaluation context.\n      delete ctx_;\n\n      // Now safely call the done callback.\n      done_copy();\n    }\n\n    void Wait() {}\n\n   private:\n    Context* ctx_;\n    DoneCallback done_;\n  };\n\n  // Context orchestrates sync/async parallel contraction evaluation. When it is\n  // executed in asynchronous mode, it owns all the shared state that might be\n  // accessible by block packing and kernel tasks.\n\n  template <typename DoneCallback, bool lhs_inner_dim_contiguous,\n            bool rhs_inner_dim_contiguous, bool rhs_inner_dim_reordered,\n            int Alignment>\n  class EvalParallelContext {\n   public:\n    typedef internal::TensorContractionInputMapper<\n        LhsScalar, Index, internal::Lhs, LeftEvaluator, left_nocontract_t,\n        contract_t, internal::packet_traits<LhsScalar>::size,\n        lhs_inner_dim_contiguous, false, Unaligned>\n        LhsMapper;\n    typedef internal::TensorContractionInputMapper<\n        RhsScalar, Index, internal::Rhs, RightEvaluator, right_nocontract_t,\n        contract_t, internal::packet_traits<RhsScalar>::size,\n        rhs_inner_dim_contiguous, rhs_inner_dim_reordered, Unaligned>\n        RhsMapper;\n\n    typedef internal::blas_data_mapper<Scalar, Index, ColMajor> OutputMapper;\n\n    typedef internal::TensorContractionKernel<\n        Scalar, LhsScalar, RhsScalar, Index, OutputMapper, LhsMapper, RhsMapper>\n        TensorContractionKernel;\n\n    typedef typename TensorContractionKernel::LhsBlock LhsBlock;\n    typedef typename TensorContractionKernel::RhsBlock RhsBlock;\n    typedef typename TensorContractionKernel::BlockMemHandle BlockMemHandle;\n\n    EvalParallelContext(const Self* self, int num_threads, Scalar* buffer,\n                        Index tm, Index tn, Index tk, Index bm, Index bn,\n                        Index bk, Index nm, Index nn, Index nk, Index gm,\n                        Index gn, Index nm0, Index nn0, bool shard_by_col,\n                        bool parallel_pack,\n                        bool parallelize_by_sharding_dim_only,\n                        DoneCallback done)\n        : created_by_thread_id_(std::this_thread::get_id()),\n          done_(this, std::move(done)),\n          device_(self->m_device),\n          lhs_(self->m_leftImpl, self->m_left_nocontract_strides,\n               self->m_i_strides, self->m_left_contracting_strides,\n               self->m_k_strides),\n          rhs_(self->m_rightImpl, self->m_right_nocontract_strides,\n               self->m_j_strides, self->m_right_contracting_strides,\n               self->m_k_strides),\n          buffer_(buffer),\n          output_(buffer, tm),\n          output_kernel_(self->m_output_kernel),\n          tensor_contraction_params_(self->m_tensor_contraction_params),\n          num_threads_(num_threads),\n          shard_by_col_(shard_by_col),\n          parallel_pack_(parallel_pack),\n          parallelize_by_sharding_dim_only_(parallelize_by_sharding_dim_only),\n          m_(tm),\n          n_(tn),\n          k_(tk),\n          bm_(bm),\n          bn_(bn),\n          bk_(bk),\n          nm_(nm),\n          nn_(nn),\n          nk_(nk),\n          gm_(gm),\n          gn_(gn),\n          nm0_(nm0),\n          nn0_(nn0),\n          kernel_(m_, k_, n_, bm_, bk_, bn_),\n          num_thread_local_allocations_(0),\n          // We reserve 2X more capacity for a thread local values, than the\n          // number of threads in the pool to efficiently handle task stealing\n          // by threads that are not managed by the pool.\n          thread_local_capacity(2 * (parallelize_by_sharding_dim_only_\n                                         ? device_.numThreadsInPool()\n                                         : 0)),\n          // We will use only one of the Lhs/Rhs thread local storage depending\n          // on the shard_by_col value and we parallelize by sharding dim ONLY.\n          lhs_thread_local_blocks_(shard_by_col_ ? 0 : thread_local_capacity,\n                                   {*this}, {*this}),\n          rhs_thread_local_blocks_(shard_by_col_ ? thread_local_capacity : 0,\n                                   {*this}, {*this}) {\n      // These two options are mutually exclusive.\n      eigen_assert(!(parallel_pack && parallelize_by_sharding_dim_only));\n\n      for (Index x = 0; x < P; x++) {\n        // Normal number of notifications for k slice switch is\n        // nm_ + nn_ + nm_ * nn_. However, first P - 1 slices will receive only\n        // nm_ + nn_ notifications, because they will not receive notifications\n        // from preceding kernels.\n        state_switch_[x] =\n            x == 0\n                ? 1\n                : (parallel_pack_ ? nn_ + nm_ : (shard_by_col_ ? nn_ : nm_)) +\n                      (x == P - 1 ? nm_ * nn_ : 0);\n        state_packing_ready_[x] =\n            parallel_pack_ ? 0 : (shard_by_col_ ? nm_ : nn_);\n        state_kernel_[x] = new std::atomic<uint8_t>*[nm_];\n        for (Index m = 0; m < nm_; m++) {\n          state_kernel_[x][m] = new std::atomic<uint8_t>[nn_];\n          // Kernels generally receive 3 notifications (previous kernel + 2\n          // packing), but the first slice won't get notifications from previous\n          // kernels.\n          for (Index n = 0; n < nn_; n++)\n            state_kernel_[x][m][n].store(\n                (x == 0 ? 0 : 1) + (parallel_pack_ ? 2 : 1),\n                std::memory_order_relaxed);\n        }\n      }\n\n      // Allocate memory for packed rhs/lhs matrices.\n      packed_mem_ = kernel_.allocateSlices(            //\n          device_,                                     //\n          /*num_lhs=*/nm0_,                            //\n          /*num_rhs=*/nn0_,                            //\n          /*num_slices=*/std::min<Index>(nk_, P - 1),  //\n          packed_lhs_, packed_rhs_);\n\n      if (parallelize_by_sharding_dim_only_) {\n        const int num_worker_threads = device_.numThreadsInPool();\n\n        if (shard_by_col) {\n          can_use_thread_local_packed_ = new std::atomic<bool>[nn_];\n          for (int i = 0; i < nn_; ++i)\n            can_use_thread_local_packed_[i].store(true,\n                                                  std::memory_order_relaxed);\n\n          Index num_blocks = num_worker_threads * gn_;\n          thread_local_pre_alocated_mem_ = kernel_.allocateSlices(  //\n              device_,                                              //\n              /*num_lhs=*/0,                                        //\n              /*num_rhs=*/num_blocks,                               //\n              /*num_slices=*/1,                                     //\n              /*lhs_blocks=*/nullptr, &rhs_thread_local_pre_allocated_);\n\n        } else {\n          can_use_thread_local_packed_ = new std::atomic<bool>[nm_];\n          for (int i = 0; i < nm_; ++i)\n            can_use_thread_local_packed_[i].store(true,\n                                                  std::memory_order_relaxed);\n\n          Index num_blocks = num_worker_threads * gm_;\n          thread_local_pre_alocated_mem_ = kernel_.allocateSlices(  //\n              device_,                                              //\n              /*num_lhs=*/num_blocks,                               //\n              /*num_rhs=*/0,                                        //\n              /*num_slices=*/1, &lhs_thread_local_pre_allocated_,   //\n              /*rhs_blocks=*/nullptr);\n        }\n      }\n    }\n\n    ~EvalParallelContext() {\n      for (Index x = 0; x < P; x++) {\n        for (Index m = 0; m < nm_; m++) delete[] state_kernel_[x][m];\n        delete[] state_kernel_[x];\n      }\n      kernel_.deallocate(device_, packed_mem_);\n      if (parallelize_by_sharding_dim_only_) {\n        kernel_.deallocate(device_, thread_local_pre_alocated_mem_);\n        delete[] can_use_thread_local_packed_;\n      }\n    }\n\n    void run() {\n      // Kick off packing of the first slice.\n      signal_switch(0, 1);\n\n      // Wait for overall completion.\n      //\n      // If parallel evaluation is executed in async mode, this is a no-op, and\n      // Wait() will return immediately. In synchronous mode it will block the\n      // caller thread until it will receive notification from last task.\n      //\n      // In async mode, last task when completed will call done callback from\n      // the same thread, and will delete this context.\n      //\n      // TODO(dvyukov): This wait can lead to deadlock if contraction is\n      // evaluated in synchronous mode. If nthreads contractions are\n      // concurrently submitted from worker threads, this wait will block all\n      // worker threads and the system will deadlock.\n      done_.Wait();\n    }\n\n   private:\n    std::thread::id created_by_thread_id_;\n\n    // This notification is specialized on the type of DoneCallback and can be\n    // blocking or non-blocking.\n    EvalParallelNotification<DoneCallback, EvalParallelContext> done_;\n\n    const Device& device_;\n    LhsMapper lhs_;\n    RhsMapper rhs_;\n    Scalar* const buffer_;\n    OutputMapper output_;\n    OutputKernelType output_kernel_;\n    TensorContractionParams tensor_contraction_params_;\n    const int num_threads_;\n    const bool shard_by_col_;\n    const bool parallel_pack_;\n    const bool parallelize_by_sharding_dim_only_;\n    // Matrix sizes.\n    const Index m_;\n    const Index n_;\n    const Index k_;\n    // Block sizes.\n    const Index bm_;\n    const Index bn_;\n    const Index bk_;\n    // Number of tasks.\n    const Index nm_;\n    const Index nn_;\n    const Index nk_;\n    // Task grain sizes (number of kernels executed per task).\n    const Index gm_;\n    const Index gn_;\n    // Number of blocks (this is different from ni_/nn_ because of task size\n    // coarsening).\n    const Index nm0_;\n    const Index nn0_;\n    // Tensor contraction kernel.\n    TensorContractionKernel kernel_;\n\n    // Parallelization strategy.\n    //\n    // Blocks related to the same k block can run in parallel because they write\n    // to different output blocks. So we parallelize within k slices, this\n    // gives us parallelism level of m x n. Before we can start any kernels\n    // related to k-th slice, we need to issue m lhs packing tasks and n rhs\n    // packing tasks.\n    //\n    // However, there is a bottleneck when we are finishing kernels for k-th\n    // slice (at the very end there is only 1 runnable kernel). To mitigate this\n    // bottleneck we allow kernels from k-th and k+1-th slices to run in\n    // parallel. Note that (m, n, k) and (m, n, k+1) kernels write to the same\n    // output block, so they must not run in parallel.\n    //\n    // This gives us the following dependency graph.\n    // On each k slice we have m x n kernel tasks, m lhs paking tasks and n rhs\n    // packing tasks.\n    // Kernel (m, n, k) can start when:\n    //  - kernel (m, n, k-1) has finished\n    //  - lhs packing (m, k) has finished\n    //  - rhs packing (n, k) has finished\n    // Lhs/rhs packing can start when:\n    //  - all k-1 packing has finished (artificially imposed to limit amount of\n    //  parallel packing)\n    //\n    // On top of that we limit runnable tasks to two consecutive k slices.\n    // This is done to limit amount of memory we need for packed lhs/rhs\n    // (for each k slice we need m*bk + n*bk memory in packed_lhs_/packed_rhs_).\n    //\n    // state_switch_ tracks when we are ready to switch to the next k slice.\n    // state_kernel_[m][n] tracks when we are ready to kick off kernel (m, n).\n    // These variable are rolling over 3 consecutive k slices: first two we are\n    // actively executing + one to track completion of kernels in the second\n    // slice.\n    static const Index P = 3;\n\n    // Handle to the allocated temporary storage for Lhs/Rhs blocks.\n    BlockMemHandle packed_mem_;\n    std::vector<LhsBlock> packed_lhs_[P - 1];\n    std::vector<RhsBlock> packed_rhs_[P - 1];\n\n    // If we choose to parallelize only by the sharding dimension, each thread\n    // will have it's own \"thead local\" (not a c++ thread local storage) memory\n    // for packed_lhs or packed_rhs (shard_by_col = false of true). This memory\n    // can't be passed to a kernel that might execute on a different thread.\n    //\n    // In practice when we are ready to pack memory for the sharding dimension\n    // (rhs if shard_by_col==true) of the K-th slice, all kernels for K-1 slice\n    // already computed (99% of the time), and we can pack data into the thread\n    // local storage, and guarantee that all the kernels will be executed\n    // immediately in the same thread. This significantly increases L1 cache hit\n    // ratio and reduces pressure on the memory bus.\n    //\n    // It's still possible that kernel for the K-th slice will be ready before\n    // completion of the K-1 kernel, so we have to allocate \"global\" packed_lhs_\n    // and packed_rhs_ to allow kernels to be executed later on a thread\n    // different from the thread that was used for packing.\n\n    // Handle for pre-allocated thread local memory buffers.\n    BlockMemHandle thread_local_pre_alocated_mem_;\n\n    // Only one of these will be initialized depending on shard_by_col value\n    // (the size will be `num_worker_threads * num_grains_in_the_sharding_dim`).\n    std::vector<LhsBlock> lhs_thread_local_pre_allocated_;\n    std::vector<RhsBlock> rhs_thread_local_pre_allocated_;\n\n    // How many thread local blocks were already allocated.\n    std::atomic<int> num_thread_local_allocations_;\n    const int thread_local_capacity;\n\n    // We will use pre-allocated Lhs/Rhs blocks defined above, if the number of\n    // unique threads in a system is below or equal to the number of threads in\n    // a thread pool. We will fallback on dynamic memory allocation after that.\n\n    // ThreadLocalBlocks is a container for Lhs or Rhs thread local buffers. Its\n    // size is equal to the grain size in Lhs/Rhs sharding dimension.\n    template <typename BlockType>\n    class ThreadLocalBlocks {\n     public:\n      ThreadLocalBlocks() = default;\n\n      ThreadLocalBlocks(BlockType* base, size_t grain_size)\n          : is_pre_allocated_(true),\n            thread_local_pre_allocated_base_(base),\n            grain_size_(grain_size) {}\n\n      ThreadLocalBlocks(BlockMemHandle mem_handle,\n                        std::vector<BlockType> blocks)\n          : is_pre_allocated_(false),\n            mem_handle_(std::move(mem_handle)),\n            blocks_(std::move(blocks)) {}\n\n      BlockType& block(int grain_index) {\n        eigen_assert(grain_index >= 0);\n        eigen_assert(static_cast<size_t>(grain_index) < size());\n        return is_pre_allocated_ ? thread_local_pre_allocated_base_[grain_index]\n                                 : blocks_[grain_index];\n      }\n\n      void Release(EvalParallelContext& ctx) const {\n        if (!is_pre_allocated_) {\n          ctx.kernel_.deallocate(ctx.device_, mem_handle_);\n        }\n      }\n\n      size_t size() const {\n        return is_pre_allocated_ ? grain_size_ : blocks_.size();\n      }\n\n     private:\n      bool is_pre_allocated_;\n\n      // Reuse pre-allocated thread local buffers.\n      BlockType* thread_local_pre_allocated_base_ = nullptr;\n      size_t grain_size_ = 0;\n\n      // These will be initialized only if `is_pre_allocated == false`.\n      BlockMemHandle mem_handle_{};\n      std::vector<BlockType> blocks_;\n    };\n\n    // ThreadLocalBlocksInitialize callable does custom thread local blocks\n    // initialization, and will reuse pre-allocated buffers if possible, or will\n    // dynamically allocate new memory.\n    //\n    // Lhs/Rhs blocks might be of the same type, so we have to pass explicitly\n    // for what side do we plan to do block allocation.\n    template <typename BlockType, bool is_rhs>\n    class ThreadLocalBlocksInitialize {\n      static constexpr bool kIsLhs =\n          !is_rhs && std::is_same<BlockType, LhsBlock>::value;\n      static const bool kIsRhs =\n          is_rhs && std::is_same<BlockType, RhsBlock>::value;\n      static_assert(kIsLhs || kIsRhs, \"Unkown block type\");\n\n      using Blocks = ThreadLocalBlocks<BlockType>;\n\n     public:\n      ThreadLocalBlocksInitialize(EvalParallelContext& ctx)\n          : ctx_(ctx),\n            num_worker_threads_(ctx_.device_.numThreadsInPool()) {}\n\n      void operator()(Blocks& blocks) {\n        const int n = ctx_.num_thread_local_allocations_.fetch_add(\n            1, std::memory_order_relaxed);\n\n        if (n >= num_worker_threads_) {\n          ThreadLocalBlocksAllocator<is_rhs>::allocate(ctx_, blocks);\n        } else {\n          ThreadLocalBlocksAllocator<is_rhs>::reuse(ctx_, n, blocks);\n        }\n      }\n\n     private:\n      // NOTE(ezhulenev): Without 'if constexpr' we have to put calls to\n      // TensorContractionKernel::allocateSlices into template specializations.\n      // Also explicit specializations are not allowed at class scope in C++03,\n      // EvalCtx type parameter is just a workaround for that limitation.\n      template <bool pack_rhs, typename EvalCtx = EvalParallelContext>\n      struct ThreadLocalBlocksAllocator;\n\n      template <typename EvalCtx>\n      struct ThreadLocalBlocksAllocator</*pack_rhs=*/true, EvalCtx> {\n        static void allocate(EvalCtx& ctx, Blocks& blocks) {\n          std::vector<RhsBlock> rhs_blocks;\n          BlockMemHandle mem_handle = ctx.kernel_.allocateSlices(\n              ctx.device_,\n              /*num_lhs=*/0,\n              /*num_rhs=*/ctx.gn_,\n              /*num_slices=*/1,\n              /*lhs_blocks=*/nullptr, /*rhs_blocks=*/&rhs_blocks);\n\n          blocks = ThreadLocalBlocks<RhsBlock>(std::move(mem_handle),\n                                               std::move(rhs_blocks));\n        }\n\n        static void reuse(EvalCtx& ctx, int index, Blocks& blocks) {\n          RhsBlock* ptr = &ctx.rhs_thread_local_pre_allocated_[ctx.gn_ * index];\n          blocks = ThreadLocalBlocks<RhsBlock>(ptr, ctx.gn_);\n        }\n      };\n\n      template <typename EvalCtx>\n      struct ThreadLocalBlocksAllocator</*pack_rhs=*/false, EvalCtx> {\n        static void allocate(EvalCtx& ctx, Blocks& blocks) {\n          std::vector<LhsBlock> lhs_blocks;\n          BlockMemHandle mem_handle = ctx.kernel_.allocateSlices(\n              ctx.device_,\n              /*num_lhs=*/ctx.gm_,\n              /*num_rhs=*/0,\n              /*num_slices=*/1,\n              /*lhs_blocks=*/&lhs_blocks, /*rhs_blocks=*/nullptr);\n\n          blocks = ThreadLocalBlocks<LhsBlock>(std::move(mem_handle),\n                                               std::move(lhs_blocks));\n        }\n\n        static void reuse(EvalCtx& ctx, int index, Blocks& blocks) {\n          LhsBlock* ptr = &ctx.lhs_thread_local_pre_allocated_[ctx.gm_ * index];\n          blocks = ThreadLocalBlocks<LhsBlock>(ptr, ctx.gm_);\n        }\n      };\n\n      EvalParallelContext& ctx_;\n      const int num_worker_threads_;\n    };\n\n    template <typename BlockType>\n    class ThreadLocalBlocksRelease {\n     public:\n      using Blocks = ThreadLocalBlocks<BlockType>;\n      ThreadLocalBlocksRelease(EvalParallelContext& ctx) : ctx_(ctx) {}\n      void operator()(Blocks& blocks) { blocks.Release(ctx_); }\n\n     private:\n      EvalParallelContext& ctx_;\n    };\n\n    // ThreadLocalBlocks initialization callables.\n    using ThreadLocalLhsInit =\n        ThreadLocalBlocksInitialize<LhsBlock, /*is_rhs=*/false>;\n    using ThreadLocalRhsInit =\n        ThreadLocalBlocksInitialize<RhsBlock, /*is_rhs=*/true>;\n\n    // ThreadLocalBlocks release callables.\n    using ThreadLocalLhsRelease = ThreadLocalBlocksRelease<LhsBlock>;\n    using ThreadLocalRhsRelease = ThreadLocalBlocksRelease<RhsBlock>;\n\n    // Thread local containers for Lhs/Rhs block packs. In practice only one of\n    // them will be used, depending on the shard_by_col value.\n    Eigen::ThreadLocal<ThreadLocalBlocks<LhsBlock>, ThreadLocalLhsInit,\n                       ThreadLocalLhsRelease>\n        lhs_thread_local_blocks_;\n    Eigen::ThreadLocal<ThreadLocalBlocks<RhsBlock>, ThreadLocalRhsInit,\n                       ThreadLocalRhsRelease>\n        rhs_thread_local_blocks_;\n\n    // After a particular shard for Kth slice missed thread local execution\n    // opportunity (K-1 slice didn't complete kernels execution), we can no\n    // longer schedule K+1 and following slices in thread local mode, because\n    // there is no more guarantee that previous kernels were executed\n    // sequentially in the same thread (size is nn_ or nm_).\n    std::atomic<bool>* can_use_thread_local_packed_;\n\n    std::atomic<uint8_t>** state_kernel_[P];\n    // state_switch_ is frequently modified by worker threads, while other\n    // fields are read-only after constructor. Let's move it to a separate cache\n    // line to reduce cache-coherency traffic.\n    char pad_[128];\n    std::atomic<Index> state_packing_ready_[P];\n    std::atomic<Index> state_switch_[P];\n\n    LhsBlock& packed_lhs(Index m, Index k, Index m1, bool use_thread_local) {\n      if (use_thread_local) {\n        eigen_assert(!shard_by_col_);\n        ThreadLocalBlocks<LhsBlock>& blocks = lhs_thread_local_blocks_.local();\n\n        Index grain_index = m1 - m * gm_;\n        return blocks.block(internal::convert_index<int>(grain_index)); // FIXME better make ThreadLocalBlocks use Eigen::Index?\n      } else {\n        return packed_lhs_[k % (P - 1)][m1];\n      }\n    }\n\n    RhsBlock& packed_rhs(Index n, Index k, Index n1, bool use_thread_local) {\n      if (use_thread_local) {\n        eigen_assert(shard_by_col_);\n        ThreadLocalBlocks<RhsBlock>& blocks = rhs_thread_local_blocks_.local();\n\n        Index grain_index = n1 - n * gn_;\n        return blocks.block(internal::convert_index<int>(grain_index)); // FIXME better make ThreadLocalBlocks use Eigen::Index?\n      } else {\n        return packed_rhs_[k % (P - 1)][n1];\n      }\n    }\n\n    // In following two methods (pack_lhs and pack_rhs), if we know for sure\n    // that we'll be able to immediately call a kernel with packed data, and do\n    // not submit it to the thread pool, we can use thread local memory for\n    // packed data.\n    //\n    // We can only reliably check it if we are running all kernels in sync mode\n    // (parallelize only by sharding dim). If kernel for m==0 (n==0) is ready to\n    // run, it's guaranteed that all kernels with larger values of m (n) are\n    // also ready, because we execute them in the same order for all K slices.\n\n    void pack_lhs(Index m, Index k) {\n      bool use_thread_local = false;\n\n      if (parallelize_by_sharding_dim_only_ && !shard_by_col_ &&\n          can_use_thread_local_packed_[m].load(std::memory_order_relaxed)) {\n        if (state_kernel_[k % P][m][0].load(std::memory_order_relaxed) == 1) {\n          use_thread_local = true;\n        } else {\n          // If we can't guarantee that all kernels in `k` slice will be\n          // executed sequentially in current thread, it's no longer safe to use\n          // thread local memory in following slices along the k dimensions.\n          eigen_assert(k > 0);\n          can_use_thread_local_packed_[m].store(false,\n                                                std::memory_order_relaxed);\n        }\n      }\n\n      const Index mend = m * gm_ + gm(m);\n      for (Index m1 = m * gm_; m1 < mend; m1++)\n        kernel_.packLhs(&packed_lhs(m, k, m1, use_thread_local),\n                        lhs_.getSubMapper(m1 * bm_, k * bk_), bk(k), bm(m1));\n\n      if (!parallel_pack_ && shard_by_col_) {\n        assert(!use_thread_local);\n        signal_packing(k);\n      } else {\n        signal_switch(k + 1);\n        for (Index n = nn_ - 1; n >= 0; n--) {\n          bool sync = parallelize_by_sharding_dim_only_ || n == 0;\n          signal_kernel(m, n, k, sync, use_thread_local);\n        }\n      }\n    }\n\n    void pack_rhs(Index n, Index k) {\n      bool use_thread_local = false;\n\n      if (parallelize_by_sharding_dim_only_ && shard_by_col_ &&\n          can_use_thread_local_packed_[n].load(std::memory_order_relaxed)) {\n        if (state_kernel_[k % P][0][n].load(std::memory_order_relaxed) == 1) {\n          use_thread_local = true;\n        } else {\n          // If we can't guarantee that all kernels in `k` slice will be\n          // executed sequentially in current thread, it's no longer safe to use\n          // thread local memory in followig slices along the k dimensions.\n          eigen_assert(k > 0);\n          can_use_thread_local_packed_[n].store(false,\n                                                std::memory_order_relaxed);\n        }\n      }\n\n      const Index nend = n * gn_ + gn(n);\n      for (Index n1 = n * gn_; n1 < nend; n1++) {\n        if (!TensorContractionKernel::HasBeta && k == 0) {\n          // Zero the output memory in parallel, only if contraction kernel does\n          // not support `beta`. Otherwise we will pass beta 0.0 to the first\n          // call to the `TensorContractionKernel::invoke()`.\n          //\n          // On 10000x2x10000 mm zeroing can easily take half of time. Zero (bn\n          // x m) row. Safe to do here because all kernels that will write to\n          // this memory depend on completion of this task. Note: don't call\n          // device_.fill() here. device_.fill() blocks on thread pool\n          // worker thread, which can lead to underutilization and deadlocks.\n          std::fill_n(buffer_ + n1 * bn_ * m_, bn(n1) * m_, Scalar(0));\n        }\n        kernel_.packRhs(&packed_rhs(n, k, n1, use_thread_local),\n                        rhs_.getSubMapper(k * bk_, n1 * bn_), bk(k), bn(n1));\n      }\n\n      if (parallel_pack_ || shard_by_col_) {\n        signal_switch(k + 1);\n        for (Index m = nm_ - 1; m >= 0; m--) {\n          bool sync = parallelize_by_sharding_dim_only_ || m == 0;\n          signal_kernel(m, n, k, sync, use_thread_local);\n        }\n      } else {\n        assert(!use_thread_local);\n        signal_packing(k);\n      }\n    }\n\n    void kernel(Index m, Index n, Index k, bool use_thread_local) {\n      // Note: order of iteration matters here. Iteration over m is innermost\n      // because we want to reuse the same packed rhs in consecutive tasks\n      // (rhs fits into L2$ while lhs only into L3$).\n      const Index nend = n * gn_ + gn(n);\n      const Index mend = m * gm_ + gm(m);\n\n      // NOTE: output = alpha * LHS * RHS + beta * output.\n      const Scalar alpha = Scalar(1);\n      const Scalar beta =\n          (TensorContractionKernel::HasBeta && k == 0) ? Scalar(0) : Scalar(1);\n\n      if (shard_by_col_) {\n        for (Index n1 = n * gn_; n1 < nend; n1++) {\n          for (Index m1 = m * gm_; m1 < mend; m1++) {\n            const auto output_mapper = output_.getSubMapper(m1 * bm_, n1 * bn_);\n            kernel_.invoke(\n                output_mapper,\n                packed_lhs(m, k, m1, !shard_by_col_ && use_thread_local),\n                packed_rhs(n, k, n1, shard_by_col_ && use_thread_local), bm(m1),\n                bk(k), bn(n1), alpha, beta);\n\n            // We are done with the last task for the [m1, n1] block.\n            if (k + 1 == nk_) {\n              output_kernel_(output_mapper, tensor_contraction_params_,\n                             m1 * bm_, n1 * bn_, bm(m1), bn(n1));\n            }\n          }\n        }\n      } else {\n        for (Index m1 = m * gm_; m1 < mend; m1++)\n          for (Index n1 = n * gn_; n1 < nend; n1++) {\n            const auto output_mapper = output_.getSubMapper(m1 * bm_, n1 * bn_);\n            kernel_.invoke(\n                output_mapper,\n                packed_lhs(m, k, m1, !shard_by_col_ && use_thread_local),\n                packed_rhs(n, k, n1, shard_by_col_ && use_thread_local), bm(m1),\n                bk(k), bn(n1), alpha, beta);\n\n            // We are done with the last task for the [m1, n1] block.\n            if (k + 1 == nk_) {\n              output_kernel_(output_mapper, tensor_contraction_params_,\n                             m1 * bm_, n1 * bn_, bm(m1), bn(n1));\n            }\n          }\n      }\n      signal_kernel(m, n, k + 1, /*sync=*/false, /*use_thread_local=*/false);\n      signal_switch(k + 2);\n    }\n\n    void signal_packing(Index k) {\n      eigen_assert(!parallel_pack_);\n      Index s = state_packing_ready_[k % P].fetch_sub(1);\n      eigen_assert(s > 0);\n      if (s != 1) return;\n      state_packing_ready_[k % P] = shard_by_col_ ? nm_ : nn_;\n      enqueue_packing(k, shard_by_col_);\n    }\n\n    void signal_kernel(Index m, Index n, Index k, bool sync,\n                       bool use_thread_local) {\n      std::atomic<uint8_t>* state = &state_kernel_[k % P][m][n];\n      Index s = state->load();\n      eigen_assert(s > 0);\n      if (s != 1 && state->fetch_sub(1) != 1) {\n        eigen_assert(!use_thread_local);\n        return;\n      }\n      state->store(parallel_pack_ ? 3 : 2, std::memory_order_relaxed);\n      if (sync) {\n        kernel(m, n, k, use_thread_local);\n      } else {\n        eigen_assert(!use_thread_local);\n        device_.enqueueNoNotification(\n            [=]() { kernel(m, n, k, use_thread_local); });\n      }\n    }\n\n    void signal_switch(Index k, Index v = 1) {\n      Index s = state_switch_[k % P].fetch_sub(v);\n      eigen_assert(s >= v);\n      if (s != v) return;\n\n      // Ready to switch to the next k slice.\n      // Reset counter for the next iteration.\n      state_switch_[k % P] =\n          (parallel_pack_ ? nm_ + nn_ : (shard_by_col_ ? nn_ : nm_)) +\n          nm_ * nn_;\n      if (k < nk_) {\n        // Issue lhs/rhs packing. Their completion will in turn kick off\n        // kernels.\n        if (parallel_pack_) {\n          enqueue_packing(k, !shard_by_col_);\n          enqueue_packing(k, shard_by_col_);\n        } else if (shard_by_col_) {\n          enqueue_packing(k, false);\n        } else {\n          enqueue_packing(k, true);\n        }\n\n        // Termination handling.\n        // Because kernel completion signals k + 2 switch, we need to finish nk\n        // + 2 slices without issuing any tasks on nk + 1 slice. So here we\n        // pretend that all nk + 1 packing tasks just finish instantly; so that\n        // nk + 2 switch only waits for completion of nk kernels.\n      } else if (k == nk_) {\n        signal_switch(k + 1,\n                      parallel_pack_ ? nm_ + nn_ : (shard_by_col_ ? nn_ : nm_));\n      } else {\n        done_.Notify();\n      }\n    }\n\n    // Enqueue all rhs/lhs packing for k-th slice.\n    void enqueue_packing(Index k, bool rhs) {\n      enqueue_packing_helper(0, rhs ? nn_ : nm_, k, rhs);\n    }\n\n    void enqueue_packing_helper(Index start, Index end, Index k, bool rhs) {\n      if (end - start == 1) {\n        if (rhs)\n          pack_rhs(start, k);\n        else\n          pack_lhs(start, k);\n      } else {\n        while (end - start > 1) {\n          Index mid = (start + end) / 2;\n          device_.enqueueNoNotification(\n              [=]() { enqueue_packing_helper(mid, end, k, rhs); });\n          end = mid;\n        }\n\n        // Decide if we want to run first packing task (start == 0) in\n        // async mode if we parallelize only by sharding dim:\n        // (1) pack_lhs and pack_rhs call signal_switch before completing\n        //     all calls to signal_kernel, which in sync mode might lead\n        //     to the execution of the first kernel of the k+1 slice, before\n        //     completing a call to the last kernel of the k slice.\n        // (2) all pack tasks for sharded dim must be executed in a thread\n        //     pool to get pre-allocated thead local buffers.\n        bool pack_async =\n          (start == 0) &&\n          (parallelize_by_sharding_dim_only_&& shard_by_col_ == rhs) &&\n          (k > 0 || std::this_thread::get_id() == created_by_thread_id_);\n\n        if (pack_async) {\n          device_.enqueueNoNotification(\n              [=]() { enqueue_packing_helper(start, end, k, rhs); });\n        } else {\n          enqueue_packing_helper(start, end, k, rhs);\n        }\n      }\n    }\n\n    // Block sizes with accounting for potentially incomplete last block.\n    Index bm(Index m) const { return m + 1 < nm0_ ? bm_ : m_ + bm_ - bm_ * nm0_; }\n    Index bn(Index n) const { return n + 1 < nn0_ ? bn_ : n_ + bn_ - bn_ * nn0_; }\n    Index bk(Index k) const { return k + 1 < nk_ ? bk_ : k_ + bk_ - bk_ * nk_; }\n    // Task grain sizes accounting for potentially incomplete last task.\n    Index gm(Index m) const { return m + 1 < nm_ ? gm_ : nm0_ + gm_ - gm_ * nm_; }\n    Index gn(Index n) const { return n + 1 < nn_ ? gn_ : nn0_ + gn_ - gn_ * nn_; }\n\n    EvalParallelContext(const EvalParallelContext&) = delete;\n    void operator=(const EvalParallelContext&) = delete;\n  };\n\n  template <bool lhs_inner_dim_contiguous, bool rhs_inner_dim_contiguous,\n            bool rhs_inner_dim_reordered, int Alignment>\n  using SyncEvalParallelContext =\n      EvalParallelContext<NoCallback, lhs_inner_dim_contiguous,\n                          rhs_inner_dim_contiguous, rhs_inner_dim_reordered,\n                          Alignment>;\n\n  // ------------------------------------------------------------------------ //\n\n  // EvalShardedByInnerDimContext orchestrates sync/async contraction\n  // evaluation, when we shard by inner dimension. When it is executed in\n  // asynchronous mode, it owns all the shared state that might be accessible by\n  // block processing tasks.\n\n  template <typename DoneCallback>\n  struct EvalShardedByInnerDimContext {\n    EvalShardedByInnerDimContext(const Self* self, int num_threads,\n                                 Scalar* result_buffer,\n                                 Index m_size, Index n_size, Index k_size,\n                                 DoneCallback done_callback)\n        : evaluator(self),\n          m_lhs_inner_dim_contiguous(evaluator->m_lhs_inner_dim_contiguous),\n          m_rhs_inner_dim_contiguous(evaluator->m_rhs_inner_dim_contiguous),\n          m_rhs_inner_dim_reordered(evaluator->m_rhs_inner_dim_reordered),\n          result(result_buffer),\n          m(m_size),\n          n(n_size),\n          k(k_size),\n          done(std::move(done_callback)),\n          buffer_size_bytes(m * n * sizeof(Scalar)),\n          block_size(blockSize(k, num_threads)),\n          num_blocks(divup<Index>(k, block_size)),\n          num_pending_blocks(internal::convert_index<int>(num_blocks)),\n          l0_ranges(divup<Index>(num_blocks, l0_size)),\n          l0_state(l0_ranges),\n          block_buffers(num_blocks) {\n      // Keep count of pending gemm tasks for each l0 range.\n      for (int i = 0; i < l0_ranges; ++i) {\n        const Index num_pending_tasks = actualRangeSize(l0_ranges, l0_size, i);\n        l0_state.emplace_back(internal::convert_index<int>(num_pending_tasks));\n      }\n\n      // Allocate temporary buffers for each block.\n      for (Index block_idx = 0; block_idx < num_blocks; ++block_idx) {\n        Scalar* buf = block_idx == 0\n                          ? result\n                          : static_cast<Scalar*>(evaluator->m_device.allocate(\n                                buffer_size_bytes));\n        block_buffers.emplace_back(buf);\n      }\n    }\n\n    ~EvalShardedByInnerDimContext() {\n      for (Index i = 1; i < num_blocks; ++i) {\n        evaluator->m_device.deallocate(block_buffers[i]);\n      }\n    }\n\n    template <int Alignment>\n    void run() {\n      Barrier barrier(internal::convert_index<int>(num_blocks));\n      eval<Alignment>(barrier, 0, num_blocks);\n      barrier.Wait();\n\n      // Aggregate partial sums from l0 ranges.\n      aggregateL0Blocks<Alignment>();\n\n      // Apply output kernel.\n      applyOutputKernel();\n    }\n\n    template <int Alignment>\n    void runAsync() {\n      evalAsync<Alignment>(0, num_blocks);\n    }\n\n   private:\n    // The underlying GEMM kernel assumes that k is a multiple of\n    // the packet size and subtle breakage occurs if this is violated.\n    static const Index packet_size = internal::packet_traits<RhsScalar>::size;\n\n    const Self* evaluator;  // TensorContraction evaluator\n\n    // These fields required fromTENSOR_CONTRACTION_DISPATCH macro.\n    bool m_lhs_inner_dim_contiguous;\n    bool m_rhs_inner_dim_contiguous;\n    bool m_rhs_inner_dim_reordered;\n\n    Scalar* result;\n\n    Index m;\n    Index n;\n    Index k;\n\n    DoneCallback done;\n\n    // ----------------------------------------------------------------------//\n    // Algorithm parameters.\n\n    // We will compute partial results into the buffers of this size.\n    Index buffer_size_bytes;\n\n    Index block_size;\n    Index num_blocks;\n\n    // Keep track of pending tasks when evaluate in async mode.\n    std::atomic<int> num_pending_blocks;\n\n    // We compute partial gemm results in parallel, and to get the final result\n    // we need to add them all together. For the large number of threads (>= 48)\n    // this adds a very expensive sequential step at the end.\n    //\n    // We split the [0, num_blocks) into small ranges, and when a task for the\n    // block finishes its partial gemm computation, it checks if it was the last\n    // gemm in the range, and if so, it will add all blocks of the range.\n    //\n    // After all tasks done, we need to add only these pre-aggregated blocks.\n\n    // For now we use just a single level of ranges to compute pre-aggregated\n    // partial sums, but in general we can use more layers to compute tree\n    // aggregation in parallel and reduce the size of the sequential step.\n    //\n    // TODO(ezhulenev): Add multilevel tree aggregation? Probably will make\n    // sense only if number of threads >= ~128?\n    static const Index l0_size = 4;\n    Index l0_ranges;\n\n    // Keep count of pending gemm tasks for each l0 range.\n    MaxSizeVector<std::atomic<int>> l0_state;  // [0, l0_ranges)\n\n    // Buffers allocated for each temporary block computation.\n    MaxSizeVector<Scalar*> block_buffers;  // [0, num_blocks)\n\n    template <int Alignment>\n    void processBlock(Index block_idx, Index begin, Index end) {\n      Scalar* buf = block_buffers[block_idx];\n\n      TENSOR_CONTRACTION_DISPATCH(\n          evaluator->template evalGemmPartialWithoutOutputKernel, Alignment,\n          (buf, begin, end,\n           /*num_threads=*/internal::convert_index<int>(num_blocks)));\n\n      // Check if it was the last task in l0 range.\n      const Index l0_index = block_idx / l0_size;\n      const int v = l0_state[l0_index].fetch_sub(1);\n      eigen_assert(v >= 1);\n\n      // If we processed the last block of the range, we can aggregate all\n      // partial results into the first block of the range.\n      if (v == 1) {\n        const Index rng_size = actualRangeSize(l0_ranges, l0_size, l0_index);\n        const Index dst_block_idx = l0_index * l0_size;\n\n        if (rng_size == l0_size) {\n          addAllToBuffer<Alignment>(\n              m * n,\n              /*src_buf0=*/block_buffers[dst_block_idx + 1],\n              /*src_buf1=*/block_buffers[dst_block_idx + 2],\n              /*src_buf2=*/block_buffers[dst_block_idx + 3],\n              /*dst_buf= */ block_buffers[dst_block_idx]);\n        } else {\n          // Aggregate blocks of potentially incomplete last range.\n          for (int i = 1; i < rng_size; ++i) {\n            addToBuffer<Alignment>(m * n,\n                                   /*src_buf=*/block_buffers[dst_block_idx + i],\n                                   /*dst_buf=*/block_buffers[dst_block_idx]);\n          }\n        }\n      }\n    }\n\n    // Aggregate partial sums from l0 ranges.\n    template <int Alignment>\n    void aggregateL0Blocks() const {\n      Index l0_index = 1;\n\n      for (; l0_index + 2 < l0_ranges; l0_index += 3) {\n        addAllToBuffer<Alignment>(\n            m * n,\n            /*src_buf0=*/block_buffers[(l0_index + 0) * l0_size],\n            /*src_buf1=*/block_buffers[(l0_index + 1) * l0_size],\n            /*src_buf2=*/block_buffers[(l0_index + 2) * l0_size],\n            /*dst_buf= */ block_buffers[0]);\n      }\n\n      for (; l0_index < l0_ranges; ++l0_index) {\n        addToBuffer<Alignment>(m * n, block_buffers[l0_index * l0_size],\n                               block_buffers[0]);\n      }\n    }\n\n    void applyOutputKernel() const {\n      typedef internal::blas_data_mapper<Scalar, Index, ColMajor> OutputMapper;\n      evaluator->m_output_kernel(\n          OutputMapper(result, m), evaluator->m_tensor_contraction_params,\n          static_cast<Eigen::Index>(0), static_cast<Eigen::Index>(0), m, n);\n    }\n\n    // Compute block size with accounting for potentially incomplete last block.\n    Index actualBlockSize(Index block_idx) const {\n      return block_idx + 1 < num_blocks\n                 ? block_size\n                 : k + block_size - block_size * num_blocks;\n    };\n\n    // Compute range size with accounting for potentially incomplete last range.\n    Index actualRangeSize(Index num_ranges, Index range_size,\n                          Index range_idx) const {\n      eigen_assert(range_idx < num_ranges);\n      return range_idx + 1 < num_ranges\n                 ? range_size\n                 : num_blocks + range_size - range_size * num_ranges;\n    };\n\n    template <int Alignment>\n    EIGEN_STRONG_INLINE static void addToBuffer(size_t n, const Scalar* src_buf,\n                                                Scalar* tgt_buf) {\n      const int output_packet_size =\n          internal::unpacket_traits<PacketReturnType>::size;\n      size_t i = 0;\n      const size_t num_packets = n / output_packet_size;\n      for (; i < output_packet_size * num_packets; i += output_packet_size) {\n        const PacketReturnType src_val =\n            internal::pload<PacketReturnType>(src_buf + i);\n        const PacketReturnType tgt_val =\n            internal::ploadt<PacketReturnType, Alignment>(tgt_buf + i);\n        const PacketReturnType sum = internal::padd(src_val, tgt_val);\n        internal::pstoret<Scalar, PacketReturnType, Alignment>(tgt_buf + i,\n                                                               sum);\n      }\n      for (; i < n; ++i) {\n        tgt_buf[i] += src_buf[i];\n      }\n    }\n\n    template <int Alignment>\n    EIGEN_STRONG_INLINE static void addAllToBuffer(size_t n,\n                                                   const Scalar* src_buf0,\n                                                   const Scalar* src_buf1,\n                                                   const Scalar* src_buf2,\n                                                   Scalar* dst_buf) {\n      using ::Eigen::internal::padd;\n      using ::Eigen::internal::pload;\n      using ::Eigen::internal::ploadt;\n      using ::Eigen::internal::pstoret;\n\n      const int output_packet_size =\n          internal::unpacket_traits<PacketReturnType>::size;\n\n      size_t i = 0;\n      const size_t num_packets = n / output_packet_size;\n      for (; i < output_packet_size * num_packets; i += output_packet_size) {\n        const auto src_val0 = pload<PacketReturnType>(src_buf0 + i);\n        const auto src_val1 = pload<PacketReturnType>(src_buf1 + i);\n        const auto src_val2 = pload<PacketReturnType>(src_buf2 + i);\n\n        const auto dst_val = ploadt<PacketReturnType, Alignment>(dst_buf + i);\n        const auto sum =\n            padd(padd(dst_val, src_val0), padd(src_val1, src_val2));\n\n        pstoret<Scalar, PacketReturnType, Alignment>(dst_buf + i, sum);\n      }\n      for (; i < n; ++i) {\n        dst_buf[i] += src_buf0[i] + src_buf1[i] + src_buf2[i];\n      }\n    }\n\n    template <int Alignment>\n    void eval(Barrier& barrier, Index start_block_idx, Index end_block_idx) {\n      while (end_block_idx - start_block_idx > 1) {\n        Index mid_block_idx = (start_block_idx + end_block_idx) / 2;\n        evaluator->m_device.enqueueNoNotification(\n            [this, &barrier, mid_block_idx, end_block_idx]() {\n              eval<Alignment>(barrier, mid_block_idx, end_block_idx);\n            });\n        end_block_idx = mid_block_idx;\n      }\n\n      Index block_idx = start_block_idx;\n      Index block_start = block_idx * block_size;\n      Index block_end = block_start + actualBlockSize(block_idx);\n\n      processBlock<Alignment>(block_idx, block_start, block_end);\n      barrier.Notify();\n    }\n\n    template <int Alignment>\n    void evalAsync(Index start_block_idx, Index end_block_idx) {\n      while (end_block_idx - start_block_idx > 1) {\n        Index mid_block_idx = (start_block_idx + end_block_idx) / 2;\n        evaluator->m_device.enqueueNoNotification(\n            [this, mid_block_idx, end_block_idx]() {\n              evalAsync<Alignment>(mid_block_idx, end_block_idx);\n            });\n        end_block_idx = mid_block_idx;\n      }\n\n      Index block_idx = start_block_idx;\n\n      Index block_start = block_idx * block_size;\n      Index block_end = block_start + actualBlockSize(block_idx);\n\n      processBlock<Alignment>(block_idx, block_start, block_end);\n\n      int v = num_pending_blocks.fetch_sub(1);\n      eigen_assert(v >= 1);\n\n      if (v == 1) {\n        // Aggregate partial sums from l0 ranges.\n        aggregateL0Blocks<Alignment>();\n\n        // Apply output kernel.\n        applyOutputKernel();\n\n        // NOTE: If we call `done` callback before deleting this (context),\n        // it might deallocate Self* pointer captured by context, and we'll\n        // fail in destructor trying to deallocate temporary buffers.\n\n        // Move done call back from context before it will be destructed.\n        DoneCallback done_copy = std::move(done);\n\n        // We are confident that we are the last one who touches context.\n        delete this;\n\n        // Now safely call the done callback.\n        done_copy();\n      }\n    }\n\n    // Cost model doesn't capture well the cost associated with constructing\n    // tensor contraction mappers and computing loop bounds in gemm_pack_lhs\n    // and gemm_pack_rhs, so we specify minimum desired block size.\n    static Index blockSize(Index k, int num_threads) {\n      const auto round_up = [=](Index index) -> Index {\n        const Index kmultiple = packet_size <= 8 ? 8 : packet_size;\n        return divup<Index>(index, kmultiple) * kmultiple;\n      };\n\n      const Index target_block_size = round_up(divup<Index>(k, num_threads));\n      const Index desired_min_block_size = 12 * packet_size;\n\n      return numext::mini<Index>(\n          k, numext::maxi<Index>(desired_min_block_size, target_block_size));\n    }\n\n    EvalShardedByInnerDimContext(const EvalShardedByInnerDimContext&) = delete;\n    void operator=(const EvalShardedByInnerDimContext&) = delete;\n  };\n\n  // ------------------------------------------------------------------------ //\n\n  // Below are the function used by evalProductImpl heuristics, trying to select\n  // optimcal parameters for parallelization algorithm.\n\n  // Decide whether we want to shard m x n contraction by columns or by rows.\n  static bool shardByCol(Index m, Index n, Index num_threads) {\n    // Note: we are comparing both n and m against Traits::nr, it is not\n    // a mistake. We are trying to figure out how both n and m will fit into\n    // the main sharding dimension.\n\n    // Sharding by column is the default\n    // ... unless there is enough data for vectorization over rows\n    if (m / num_threads >= Traits::nr &&\n        // and not enough data for vectorization over columns\n        (n / num_threads < Traits::nr ||\n         // ... or barely enough data for vectorization over columns,\n         // but it is not evenly dividable across threads\n         (n / num_threads < 4 * Traits::nr &&\n          (n % (num_threads * Traits::nr)) != 0 &&\n          // ... and it is evenly dividable across threads for rows\n          ((m % (num_threads * Traits::nr)) == 0 ||\n           // .. or it is not evenly dividable for both dimensions but\n           // there is much more data over rows so that corner effects are\n           // mitigated.\n           (m / n >= 6)))))\n      return false;\n    // Wait, or if matrices are just substantially prolonged over the other\n    // dimension.\n    if (n / num_threads < 16 * Traits::nr && m > n * 32) return false;\n    return true;\n  }\n\n  Index coarsenM(Index m, Index n, Index bm, Index bn, Index bk, Index gn,\n                 int num_threads, bool shard_by_col) const {\n    Index gm = 1;\n    Index gm1 = 1;\n    Index nm0 = divup(m, bm);\n    Index nm1 = nm0;\n    for (;;) {\n      // Find the next candidate for m grain size. It needs to result in\n      // different number of blocks. E.g. if we have 10 kernels, we want to try\n      // 5 and 10, but not 6, 7, 8 and 9.\n      while (gm1 <= nm0 && nm1 == divup(nm0, gm1)) gm1++;\n      if (gm1 > nm0) break;\n      // Check the candidate.\n      int res = checkGrain(m, n, bm, bn, bk, gm1, gn, gm, gn, num_threads,\n                           shard_by_col);\n      if (res < 0) break;\n      nm1 = divup(nm0, gm1);\n      if (res == 0) continue;\n      // Commit new grain size.\n      gm = gm1;\n    }\n    return gm;\n  }\n\n  Index coarsenN(Index m, Index n, Index bm, Index bn, Index bk, Index gm,\n                 int num_threads, bool shard_by_col) const {\n    Index gn = 1;\n    Index gn1 = 1;\n    Index nn0 = divup(n, bn);\n    Index nn1 = nn0;\n    for (;;) {\n      while (gn1 <= nn0 && nn1 == divup(nn0, gn1)) gn1++;\n      if (gn1 > nn0) break;\n      int res = checkGrain(m, n, bm, bn, bk, gm, gn1, gm, gn, num_threads,\n                           shard_by_col);\n      if (res < 0) break;\n      nn1 = divup(nn0, gn1);\n      if (res == 0) continue;\n      gn = gn1;\n    }\n    return gn;\n  }\n\n  // checkGrain checks whether grain (gm, gn) is suitable and is better than\n  // (oldgm, oldgn).\n  int checkGrain(Index m, Index n, Index bm, Index bn, Index bk, Index gm,\n                 Index gn, Index oldgm, Index oldgn, int num_threads,\n                 bool shard_by_col) const {\n    const TensorOpCost cost =\n        contractionCost(bm * gm, bn * gn, bm, bn, bk, shard_by_col, true);\n    double taskSize = TensorCostModel<ThreadPoolDevice>::taskSize(\n        static_cast<double>(bm) * gm * bn * gn, cost);\n    // If the task is too small, then we agree on it regardless of anything\n    // else. Otherwise synchronization overheads will dominate.\n    if (taskSize < 1) return 1;\n    // If it is too large, then we reject it and all larger tasks.\n    if (taskSize > 2) return -1;\n    // Now we are in presumably good task size range.\n    // The main deciding factor here is parallelism. Consider that we have 12\n    // kernels and 4 threads. Grains of 2, 3 and 4 all yield good task sizes.\n    // But 2/4 yield 6/3 tasks, which gives us parallelism of 0.75 (at most 3/4\n    // of cores will be busy). While grain size 3 gives us 4 tasks, which gives\n    // us parallelism of 1 (we can load all cores).\n    Index nm0 = divup(m, bm);\n    Index nn0 = divup(n, bn);\n    Index new_tasks = divup(nm0, gm) * divup(nn0, gn);\n    double new_parallelism = static_cast<double>(new_tasks) /\n                             (divup<int>(new_tasks, num_threads) * num_threads);\n    Index old_tasks = divup(nm0, oldgm) * divup(nn0, oldgn);\n    double old_parallelism = static_cast<double>(old_tasks) /\n                             (divup<int>(old_tasks, num_threads) * num_threads);\n    if (new_parallelism > old_parallelism || new_parallelism == 1) return 1;\n    return 0;\n  }\n\n  TensorOpCost contractionCost(Index m, Index n, Index bm, Index bn, Index bk,\n                               bool shard_by_col, bool prepacked) const {\n    const int packed_size = std::min<int>(PacketType<LhsScalar, Device>::size,\n                                          PacketType<RhsScalar, Device>::size);\n    const int output_packet_size = internal::unpacket_traits<PacketReturnType>::size;\n    const double kd = static_cast<double>(bk);\n    double compute_bandwidth = computeBandwidth(false, bm, bn, bk);\n    // Computations.\n    TensorOpCost cost = TensorOpCost(0, 0, kd * compute_bandwidth, true, packed_size);\n    // Output stores.\n    cost += TensorOpCost(0, sizeof(CoeffReturnType), 0, true, output_packet_size);\n    if (prepacked) {\n      // Packing and kernels are executed in different tasks. When we calculate\n      // task grain size we look only at kernel cost assuming that kernel\n      // is more expensive than packing.\n      return cost;\n    }\n    // Lhs/rhs loads + computations.\n    TensorOpCost lhsCost = this->m_leftImpl.costPerCoeff(true) * (kd / n);\n    TensorOpCost rhsCost = this->m_rightImpl.costPerCoeff(true) * (kd / m);\n    // Lhs packing memory cost does not contribute considerably to overall\n    // execution time because lhs is prefetched early and accessed sequentially.\n    if (shard_by_col)\n      lhsCost.dropMemoryCost();\n    else\n      rhsCost.dropMemoryCost();\n    return cost + lhsCost + rhsCost;\n  }\n\n  // Decide whether we want to shard m x k x n contraction over the inner\n  // (contraction) dimension (k).\n  static bool shardByInnerDim(Index m, Index n, Index k, int num_threads,\n                              int num_threads_by_k) {\n    std::ptrdiff_t bufsize = m * n * sizeof(Scalar);\n    bool shard_by_k = false;\n    if (n == 1 ||                // If mat*vec or...\n        num_threads_by_k < 2 ||  // running single threaded or...\n        num_threads_by_k <\n            num_threads ||  // sharding by k gives less parallelism or...\n        bufsize > l3CacheSize() / num_threads_by_k ||  // need more buffer space\n        // than L3 cache or...\n        k / num_threads_by_k < 2 * Traits::nr) {  // k per thread is tiny.\n      shard_by_k = false;\n    } else if (numext::maxi(m, n) / num_threads <\n                   Traits::nr ||  // both other dimensions are tiny or...\n               // k per thread is not small and...\n               (k / num_threads_by_k > 8 * Traits::nr &&\n                // one of the outer dimensions is tiny or sharding by k offers\n                // more parallelism.\n                (numext::mini(m, n) < 2 * Traits::nr ||\n                 num_threads_by_k > num_threads))) {\n      shard_by_k = true;\n    }\n    return shard_by_k;\n  }\n\n  TensorOpCost contractionCostPerInnerDim(Index m, Index n, Index k) const {\n    // Compute cost.\n    const int output_packet_size = internal::unpacket_traits<PacketReturnType>::size;\n    TensorOpCost cost(0, 0, (computeBandwidth(true, m, n, k) * m) * n, true, output_packet_size);\n    // Output stores.\n    cost += TensorOpCost(0, sizeof(CoeffReturnType), 0, true, output_packet_size);\n    TensorOpCost lhsCost = this->m_leftImpl.costPerCoeff(true) * m;\n    TensorOpCost rhsCost = this->m_rightImpl.costPerCoeff(true) * n;\n    // Since the inner gemm kernel is always sharded by column, the lhs\n    // load cost is negligible.\n    lhsCost.dropMemoryCost();\n    return cost + lhsCost + rhsCost;\n  }\n\n  int numThreadsInnerDim(Index m, Index n, Index k) const {\n    const int output_packet_size = internal::unpacket_traits<PacketReturnType>::size;\n    TensorOpCost cost = contractionCostPerInnerDim(m, n, k);\n    double total_parallel_cost =\n        TensorCostModel<ThreadPoolDevice>::totalCost(k, cost);\n    // Cost of reduction step accumulating the m*n per-thread buffers into the\n    // result.\n    double reduction_cost = TensorCostModel<ThreadPoolDevice>::totalCost(\n        m * n, TensorOpCost(2, 1, 1, true, output_packet_size));\n    int num_threads = 1;\n    double min_cost = total_parallel_cost;\n    double kPerThreadOverHead = 3000;\n    double kFixedOverHead = 100000;\n    for (int nt = 2; nt <= this->m_device.numThreads(); nt += 2) {\n      double sequential_cost =\n          kFixedOverHead + nt * (reduction_cost + kPerThreadOverHead);\n      double parallel_cost = total_parallel_cost / nt + sequential_cost;\n      if (parallel_cost < min_cost) {\n        num_threads = nt;\n        min_cost = parallel_cost;\n      }\n    }\n    return num_threads;\n  }\n\n  double computeBandwidth(bool shard_by_col, Index bm, Index bn,\n                          Index bk) const {\n    // Peak VFMA bandwidth is 0.5. However if we have not enough data for\n    // vectorization bandwidth drops. The 4.0 and 2.0 bandwidth is determined\n    // experimentally.\n    double computeBandwidth =\n        bk == 1 ? 4.0\n                : (shard_by_col ? bn : bm) < Traits::nr ||\n                          (shard_by_col ? bm : bn) < Traits::mr\n                      ? 2.0\n                      : 0.5;\n#ifndef EIGEN_VECTORIZE_FMA\n    // Bandwidth of all of VFMA/MULPS/ADDPS is 0.5 on latest Intel processors.\n    // However for MULPS/ADDPS we have dependent sequence of 2 such\n    // instructions,\n    // so overall bandwidth is 1.0.\n    if (computeBandwidth == 0.5) computeBandwidth = 1.0;\n#endif\n    return computeBandwidth;\n  }\n\n};\n\n} // end namespace Eigen\n\n#endif  // EIGEN_USE_THREADS\n#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_THREAD_POOL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConversion.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONVERSION_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CONVERSION_H\n\nnamespace Eigen {\n\n/** \\class TensorConversionOp\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor conversion class. This class makes it possible to vectorize\n  * type casting operations when the number of scalars per packet in the source\n  * and the destination type differ\n  */\nnamespace internal {\ntemplate<typename TargetType, typename XprType>\nstruct traits<TensorConversionOp<TargetType, XprType> >\n{\n  // Type promotion to handle the case where the types of the lhs and the rhs are different.\n  typedef TargetType Scalar;\n  typedef typename traits<XprType>::StorageKind StorageKind;\n  typedef typename traits<XprType>::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = traits<XprType>::NumDimensions;\n  static const int Layout = traits<XprType>::Layout;\n  enum { Flags = 0 };\n  typedef typename TypeConversion<Scalar, typename traits<XprType>::PointerType>::type PointerType;\n};\n\ntemplate<typename TargetType, typename XprType>\nstruct eval<TensorConversionOp<TargetType, XprType>, Eigen::Dense>\n{\n  typedef const TensorConversionOp<TargetType, XprType>& type;\n};\n\ntemplate<typename TargetType, typename XprType>\nstruct nested<TensorConversionOp<TargetType, XprType>, 1, typename eval<TensorConversionOp<TargetType, XprType> >::type>\n{\n  typedef TensorConversionOp<TargetType, XprType> type;\n};\n\n}  // end namespace internal\n\n\ntemplate <typename TensorEvaluator, typename SrcPacket, typename TgtPacket, int SrcCoeffRatio, int TgtCoeffRatio>\nstruct PacketConverter;\n\ntemplate <typename TensorEvaluator, typename SrcPacket, typename TgtPacket>\nstruct PacketConverter<TensorEvaluator, SrcPacket, TgtPacket, 1, 1> {\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  PacketConverter(const TensorEvaluator& impl)\n      : m_impl(impl) {}\n\n  template<int LoadMode, typename Index>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TgtPacket packet(Index index) const {\n    return internal::pcast<SrcPacket, TgtPacket>(m_impl.template packet<LoadMode>(index));\n  }\n\n private:\n  const TensorEvaluator& m_impl;\n};\n\n\ntemplate <typename TensorEvaluator, typename SrcPacket, typename TgtPacket>\nstruct PacketConverter<TensorEvaluator, SrcPacket, TgtPacket, 2, 1> {\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  PacketConverter(const TensorEvaluator& impl)\n      : m_impl(impl) {}\n\n  template<int LoadMode, typename Index>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TgtPacket packet(Index index) const {\n    const int SrcPacketSize = internal::unpacket_traits<SrcPacket>::size;\n\n    SrcPacket src1 = m_impl.template packet<LoadMode>(index);\n    SrcPacket src2 = m_impl.template packet<LoadMode>(index + SrcPacketSize);\n    TgtPacket result = internal::pcast<SrcPacket, TgtPacket>(src1, src2);\n    return result;\n  }\n\n private:\n  const TensorEvaluator& m_impl;\n};\n\ntemplate <typename TensorEvaluator, typename SrcPacket, typename TgtPacket>\nstruct PacketConverter<TensorEvaluator, SrcPacket, TgtPacket, 4, 1> {\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  PacketConverter(const TensorEvaluator& impl)\n      : m_impl(impl) {}\n\n  template<int LoadMode, typename Index>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TgtPacket packet(Index index) const {\n    const int SrcPacketSize = internal::unpacket_traits<SrcPacket>::size;\n\n    SrcPacket src1 = m_impl.template packet<LoadMode>(index);\n    SrcPacket src2 = m_impl.template packet<LoadMode>(index + SrcPacketSize);\n    SrcPacket src3 = m_impl.template packet<LoadMode>(index + 2 * SrcPacketSize);\n    SrcPacket src4 = m_impl.template packet<LoadMode>(index + 3 * SrcPacketSize);\n    TgtPacket result = internal::pcast<SrcPacket, TgtPacket>(src1, src2, src3, src4);\n    return result;\n  }\n\n private:\n  const TensorEvaluator& m_impl;\n};\n\ntemplate <typename TensorEvaluator, typename SrcPacket, typename TgtPacket>\nstruct PacketConverter<TensorEvaluator, SrcPacket, TgtPacket, 8, 1> {\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  PacketConverter(const TensorEvaluator& impl)\n      : m_impl(impl) {}\n\n  template<int LoadMode, typename Index>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TgtPacket packet(Index index) const {\n    const int SrcPacketSize = internal::unpacket_traits<SrcPacket>::size;\n\n    SrcPacket src1 = m_impl.template packet<LoadMode>(index);\n    SrcPacket src2 = m_impl.template packet<LoadMode>(index + 1 * SrcPacketSize);\n    SrcPacket src3 = m_impl.template packet<LoadMode>(index + 2 * SrcPacketSize);\n    SrcPacket src4 = m_impl.template packet<LoadMode>(index + 3 * SrcPacketSize);\n    SrcPacket src5 = m_impl.template packet<LoadMode>(index + 4 * SrcPacketSize);\n    SrcPacket src6 = m_impl.template packet<LoadMode>(index + 5 * SrcPacketSize);\n    SrcPacket src7 = m_impl.template packet<LoadMode>(index + 6 * SrcPacketSize);\n    SrcPacket src8 = m_impl.template packet<LoadMode>(index + 7 * SrcPacketSize);\n    TgtPacket result = internal::pcast<SrcPacket, TgtPacket>(src1, src2, src3, src4, src5, src6, src7, src8);\n    return result;\n  }\n\n private:\n  const TensorEvaluator& m_impl;\n};\n\ntemplate <typename TensorEvaluator, typename SrcPacket, typename TgtPacket, int TgtCoeffRatio>\nstruct PacketConverter<TensorEvaluator, SrcPacket, TgtPacket, 1, TgtCoeffRatio> {\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  PacketConverter(const TensorEvaluator& impl)\n      : m_impl(impl), m_maxIndex(impl.dimensions().TotalSize()) {}\n\n  template<int LoadMode, typename Index>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TgtPacket packet(Index index) const {\n    const int SrcPacketSize = internal::unpacket_traits<SrcPacket>::size;\n    // Only call m_impl.packet() when we have direct access to the underlying data. This\n    // ensures that we don't compute the subexpression twice. We may however load some\n    // coefficients twice, but in practice this doesn't negatively impact performance.\n    if (m_impl.data() && (index + SrcPacketSize < m_maxIndex)) {\n      // Force unaligned memory loads since we can't ensure alignment anymore\n      return internal::pcast<SrcPacket, TgtPacket>(m_impl.template packet<Unaligned>(index));\n    } else {\n      const int TgtPacketSize = internal::unpacket_traits<TgtPacket>::size;\n      typedef typename internal::unpacket_traits<SrcPacket>::type SrcType;\n      typedef typename internal::unpacket_traits<TgtPacket>::type TgtType;\n      internal::scalar_cast_op<SrcType, TgtType> converter;\n      EIGEN_ALIGN_MAX typename internal::unpacket_traits<TgtPacket>::type values[TgtPacketSize];\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < TgtPacketSize; ++i) {\n        values[i] = converter(m_impl.coeff(index+i));\n      }\n      TgtPacket rslt = internal::pload<TgtPacket>(values);\n      return rslt;\n    }\n  }\n\n private:\n  const TensorEvaluator& m_impl;\n  const typename TensorEvaluator::Index m_maxIndex;\n};\n\ntemplate<typename TargetType, typename XprType>\nclass TensorConversionOp : public TensorBase<TensorConversionOp<TargetType, XprType>, ReadOnlyAccessors>\n{\n  public:\n    typedef typename internal::traits<TensorConversionOp>::Scalar Scalar;\n    typedef typename internal::traits<TensorConversionOp>::StorageKind StorageKind;\n    typedef typename internal::traits<TensorConversionOp>::Index Index;\n    typedef typename internal::nested<TensorConversionOp>::type Nested;\n    typedef Scalar CoeffReturnType;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorConversionOp(const XprType& xpr)\n        : m_xpr(xpr) {}\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n};\n\ntemplate <bool SameType, typename Eval, typename EvalPointerType> struct ConversionSubExprEval {\n  static EIGEN_STRONG_INLINE bool run(Eval& impl, EvalPointerType) {\n    impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n};\n\ntemplate <typename Eval, typename EvalPointerType> struct ConversionSubExprEval<true, Eval, EvalPointerType> {\n  static EIGEN_STRONG_INLINE bool run(Eval& impl, EvalPointerType data) {\n    return impl.evalSubExprsIfNeeded(data);\n  }\n};\n\n#ifdef EIGEN_USE_THREADS\ntemplate <bool SameType, typename Eval, typename EvalPointerType,\n          typename EvalSubExprsCallback>\nstruct ConversionSubExprEvalAsync {\n  static EIGEN_STRONG_INLINE void run(Eval& impl, EvalPointerType, EvalSubExprsCallback done) {\n    impl.evalSubExprsIfNeededAsync(nullptr, std::move(done));\n  }\n};\n\ntemplate <typename Eval, typename EvalPointerType,\n          typename EvalSubExprsCallback>\nstruct ConversionSubExprEvalAsync<true, Eval, EvalPointerType,\n                                  EvalSubExprsCallback> {\n  static EIGEN_STRONG_INLINE void run(Eval& impl, EvalPointerType data, EvalSubExprsCallback done) {\n    impl.evalSubExprsIfNeededAsync(data, std::move(done));\n  }\n};\n#endif\n\nnamespace internal {\n\ntemplate <typename SrcType, typename TargetType, bool IsSameT>\nstruct CoeffConv {\n  template <typename ArgType, typename Device>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TargetType run(const TensorEvaluator<ArgType, Device>& impl, Index index) {\n    internal::scalar_cast_op<SrcType, TargetType> converter;\n    return converter(impl.coeff(index));\n  }\n};\n\ntemplate <typename SrcType, typename TargetType>\nstruct CoeffConv<SrcType, TargetType, true> {\n  template <typename ArgType, typename Device>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TargetType run(const TensorEvaluator<ArgType, Device>& impl, Index index) {\n    return impl.coeff(index);\n  }\n};\n\ntemplate <typename SrcPacket, typename TargetPacket, int LoadMode, bool ActuallyVectorize, bool IsSameT>\nstruct PacketConv {\n  typedef typename internal::unpacket_traits<SrcPacket>::type SrcType;\n  typedef typename internal::unpacket_traits<TargetPacket>::type TargetType;\n\n  static const int PacketSize = internal::unpacket_traits<TargetPacket>::size;\n\n  template <typename ArgType, typename Device>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TargetPacket run(const TensorEvaluator<ArgType, Device>& impl, Index index) {\n    internal::scalar_cast_op<SrcType, TargetType> converter;\n    EIGEN_ALIGN_MAX typename internal::remove_const<TargetType>::type values[PacketSize];\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < PacketSize; ++i) {\n      values[i] = converter(impl.coeff(index+i));\n    }\n    TargetPacket rslt = internal::pload<TargetPacket>(values);\n    return rslt;\n  }\n};\n\ntemplate <typename SrcPacket, typename TargetPacket, int LoadMode, bool IsSameT>\nstruct PacketConv<SrcPacket, TargetPacket, LoadMode, true, IsSameT> {\n  typedef typename internal::unpacket_traits<SrcPacket>::type SrcType;\n  typedef typename internal::unpacket_traits<TargetPacket>::type TargetType;\n\n  template <typename ArgType, typename Device>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TargetPacket run(const TensorEvaluator<ArgType, Device>& impl, Index index) {\n    const int SrcCoeffRatio = internal::type_casting_traits<SrcType, TargetType>::SrcCoeffRatio;\n    const int TgtCoeffRatio = internal::type_casting_traits<SrcType, TargetType>::TgtCoeffRatio;\n    PacketConverter<TensorEvaluator<ArgType, Device>, SrcPacket, TargetPacket,\n                    SrcCoeffRatio, TgtCoeffRatio> converter(impl);\n    return converter.template packet<LoadMode>(index);\n  }\n};\n\ntemplate <typename SrcPacket, typename TargetPacket, int LoadMode>\nstruct PacketConv<SrcPacket, TargetPacket, LoadMode, /*ActuallyVectorize=*/false, /*IsSameT=*/true> {\n  typedef typename internal::unpacket_traits<TargetPacket>::type TargetType;\n  static const int PacketSize = internal::unpacket_traits<TargetPacket>::size;\n\n  template <typename ArgType, typename Device>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TargetPacket run(const TensorEvaluator<ArgType, Device>& impl, Index index) {\n    EIGEN_ALIGN_MAX typename internal::remove_const<TargetType>::type values[PacketSize];\n    for (int i = 0; i < PacketSize; ++i) values[i] = impl.coeff(index+i);\n    return internal::pload<TargetPacket>(values);\n  }\n};\n\ntemplate <typename SrcPacket, typename TargetPacket, int LoadMode>\nstruct PacketConv<SrcPacket, TargetPacket, LoadMode, /*ActuallyVectorize=*/true, /*IsSameT=*/true> {\n  template <typename ArgType, typename Device>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TargetPacket run(const TensorEvaluator<ArgType, Device>& impl, Index index) {\n    return impl.template packet<LoadMode>(index);\n  }\n};\n\n}  // namespace internal\n\n// Eval as rvalue\ntemplate<typename TargetType, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorConversionOp<TargetType, ArgType>, Device>\n{\n  typedef TensorConversionOp<TargetType, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  typedef typename TensorEvaluator<ArgType, Device>::Dimensions Dimensions;\n  typedef TargetType Scalar;\n  typedef TargetType CoeffReturnType;\n  typedef typename internal::remove_all<typename internal::traits<ArgType>::Scalar>::type SrcType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef typename PacketType<SrcType, Device>::type PacketSourceType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  static const bool IsSameType = internal::is_same<TargetType, SrcType>::value;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned         = false,\n    PacketAccess      =\n    #ifndef EIGEN_USE_SYCL\n                        true,\n    #else\n                        TensorEvaluator<ArgType, Device>::PacketAccess &\n                        internal::type_casting_traits<SrcType, TargetType>::VectorizedCast,\n    #endif\n    BlockAccess       = TensorEvaluator<ArgType, Device>::BlockAccess,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    RawAccess         = false\n  };\n\n  static const int NumDims = internal::array_size<Dimensions>::value;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename TensorEvaluator<const ArgType, Device>::TensorBlock\n      ArgTensorBlock;\n\n  struct TensorConversionOpBlockFactory {\n    template <typename ArgXprType>\n    struct XprType {\n      typedef TensorConversionOp<TargetType, const ArgXprType> type;\n    };\n\n    template <typename ArgXprType>\n    typename XprType<ArgXprType>::type expr(const ArgXprType& expr) const {\n      return typename XprType<ArgXprType>::type(expr);\n    }\n  };\n\n  typedef internal::TensorUnaryExprBlock<TensorConversionOpBlockFactory,\n                                         ArgTensorBlock>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n    : m_impl(op.expression(), device)\n  {\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_impl.dimensions(); }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data)\n  {\n    return ConversionSubExprEval<IsSameType, TensorEvaluator<ArgType, Device>, EvaluatorPointerType>::run(m_impl, data);\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType data, EvalSubExprsCallback done) {\n    ConversionSubExprEvalAsync<IsSameType, TensorEvaluator<ArgType, Device>,\n                               EvaluatorPointerType,\n        EvalSubExprsCallback>::run(m_impl, data, std::move(done));\n  }\n#endif\n\n  EIGEN_STRONG_INLINE void cleanup()\n  {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    return internal::CoeffConv<SrcType, TargetType, IsSameType>::run(m_impl,index);\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType\n  packet(Index index) const {\n    // If we are not going to do the cast, we just need to check that base\n    // TensorEvaluator has packet access. Otherwise we also need to make sure,\n    // that we have an implementation of vectorized cast.\n    const bool Vectorizable =\n        IsSameType\n        ? TensorEvaluator<ArgType, Device>::PacketAccess\n        : int(TensorEvaluator<ArgType, Device>::PacketAccess) &\n          int(internal::type_casting_traits<SrcType, TargetType>::VectorizedCast);\n\n    return internal::PacketConv<PacketSourceType, PacketReturnType, LoadMode,\n                                Vectorizable, IsSameType>::run(m_impl, index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    const double cast_cost = TensorOpCost::CastCost<SrcType, TargetType>();\n    if (vectorized) {\n      const double SrcCoeffRatio =\n          internal::type_casting_traits<SrcType, TargetType>::SrcCoeffRatio;\n      const double TgtCoeffRatio =\n          internal::type_casting_traits<SrcType, TargetType>::TgtCoeffRatio;\n      return m_impl.costPerCoeff(vectorized) * (SrcCoeffRatio / PacketSize) +\n          TensorOpCost(0, 0, TgtCoeffRatio * (cast_cost / PacketSize));\n    } else {\n      return m_impl.costPerCoeff(vectorized) + TensorOpCost(0, 0, cast_cost);\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    return m_impl.getResourceRequirements();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    return TensorBlock(m_impl.block(desc, scratch),\n                         TensorConversionOpBlockFactory());\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n  /// required by sycl in order to extract the sycl accessor\n  const TensorEvaluator<ArgType, Device>& impl() const { return m_impl; }\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n\n protected:\n  TensorEvaluator<ArgType, Device> m_impl;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_CONVERSION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConvolution.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_H\n\nnamespace Eigen {\n\n/** \\class TensorConvolution\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor convolution class.\n  *\n  *\n  */\nnamespace internal {\n\ntemplate <typename Index, typename InputDims, int NumKernelDims, int Layout>\nclass IndexMapper {\n public:\n  IndexMapper(const InputDims& input_dims, const array<Index, NumKernelDims>& kernel_dims,\n              const array<Index, NumKernelDims>& indices) {\n\n    array<Index, NumDims> dimensions = input_dims;\n    for (int i = 0; i < NumKernelDims; ++i) {\n      const Index index = indices[i];\n      const Index input_dim = input_dims[index];\n      const Index kernel_dim = kernel_dims[i];\n      const Index result_dim = input_dim - kernel_dim + 1;\n      dimensions[index] = result_dim;\n    }\n\n    array<Index, NumDims> inputStrides;\n    array<Index, NumDims> outputStrides;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      inputStrides[0] = 1;\n      outputStrides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        inputStrides[i] = inputStrides[i-1] * input_dims[i-1];\n        outputStrides[i] = outputStrides[i-1] * dimensions[i-1];\n      }\n    } else {\n      inputStrides[NumDims - 1] = 1;\n      outputStrides[NumDims - 1] = 1;\n      for (int i = static_cast<int>(NumDims) - 2; i >= 0; --i) {\n        inputStrides[i] = inputStrides[i + 1] * input_dims[i + 1];\n        outputStrides[i] = outputStrides[i + 1] * dimensions[i + 1];\n      }\n    }\n\n    array<Index, NumDims> gpuInputDimensions;\n    array<Index, NumDims> gpuOutputDimensions;\n    array<Index, NumDims> tmp = dimensions;\n    array<Index, NumDims> ordering;\n    const size_t offset = static_cast<int>(Layout) == static_cast<int>(ColMajor)\n                              ? 0\n                              : NumDims - NumKernelDims;\n    for (int i = 0; i < NumKernelDims; ++i) {\n      const Index index = i + offset;\n      ordering[index] = indices[i];\n      tmp[indices[i]] = -1;\n      gpuInputDimensions[index] = input_dims[indices[i]];\n      gpuOutputDimensions[index] = dimensions[indices[i]];\n    }\n\n    int written = static_cast<int>(Layout) == static_cast<int>(ColMajor)\n                      ? NumKernelDims\n                      : 0;\n    for (int i = 0; i < NumDims; ++i) {\n      if (tmp[i] >= 0) {\n        ordering[written] = i;\n        gpuInputDimensions[written] = input_dims[i];\n        gpuOutputDimensions[written] = dimensions[i];\n        ++written;\n      }\n    }\n\n    for (int i = 0; i < NumDims; ++i) {\n      m_inputStrides[i] = inputStrides[ordering[i]];\n      m_outputStrides[i] = outputStrides[ordering[i]];\n    }\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = 0; i < NumDims; ++i) {\n        if (i > NumKernelDims) {\n          m_gpuInputStrides[i] =\n              m_gpuInputStrides[i - 1] * gpuInputDimensions[i - 1];\n          m_gpuOutputStrides[i] =\n              m_gpuOutputStrides[i - 1] * gpuOutputDimensions[i - 1];\n        } else {\n          m_gpuInputStrides[i] = 1;\n          m_gpuOutputStrides[i] = 1;\n        }\n      }\n    } else {\n      for (int i = NumDims - 1; i >= 0; --i) {\n        if (static_cast<size_t>(i + 1) < offset) {\n          m_gpuInputStrides[i] =\n              m_gpuInputStrides[i + 1] * gpuInputDimensions[i + 1];\n          m_gpuOutputStrides[i] =\n              m_gpuOutputStrides[i + 1] * gpuOutputDimensions[i + 1];\n        } else {\n          m_gpuInputStrides[i] = 1;\n          m_gpuOutputStrides[i] = 1;\n        }\n      }\n    }\n  }\n\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapGpuInputPlaneToTensorInputOffset(Index p) const {\n    Index inputIndex = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int d = NumDims - 1; d > NumKernelDims; --d) {\n        const Index idx = p / m_gpuInputStrides[d];\n        inputIndex += idx * m_inputStrides[d];\n        p -= idx * m_gpuInputStrides[d];\n      }\n      inputIndex += p * m_inputStrides[NumKernelDims];\n    } else {\n      std::ptrdiff_t limit = 0;\n      if (NumKernelDims < NumDims) {\n        limit = NumDims - NumKernelDims - 1;\n      }\n      for (int d = 0; d < limit; ++d) {\n        const Index idx = p / m_gpuInputStrides[d];\n        inputIndex += idx * m_inputStrides[d];\n        p -= idx * m_gpuInputStrides[d];\n      }\n      inputIndex += p * m_inputStrides[limit];\n    }\n    return inputIndex;\n  }\n\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapGpuOutputPlaneToTensorOutputOffset(Index p) const {\n    Index outputIndex = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int d = NumDims - 1; d > NumKernelDims; --d) {\n        const Index idx = p / m_gpuOutputStrides[d];\n        outputIndex += idx * m_outputStrides[d];\n        p -= idx * m_gpuOutputStrides[d];\n      }\n      outputIndex += p * m_outputStrides[NumKernelDims];\n    } else {\n      std::ptrdiff_t limit = 0;\n      if (NumKernelDims < NumDims) {\n        limit = NumDims - NumKernelDims - 1;\n      }\n      for (int d = 0; d < limit; ++d) {\n        const Index idx = p / m_gpuOutputStrides[d];\n        outputIndex += idx * m_outputStrides[d];\n        p -= idx * m_gpuOutputStrides[d];\n      }\n      outputIndex += p * m_outputStrides[limit];\n    }\n    return outputIndex;\n  }\n\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapGpuInputKernelToTensorInputOffset(Index i) const {\n    const size_t offset = static_cast<int>(Layout) == static_cast<int>(ColMajor)\n                              ? 0\n                              : NumDims - NumKernelDims;\n    return i * m_inputStrides[offset];\n  }\n\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapGpuOutputKernelToTensorOutputOffset(Index i) const {\n    const size_t offset = static_cast<int>(Layout) == static_cast<int>(ColMajor)\n                              ? 0\n                              : NumDims - NumKernelDims;\n    return i * m_outputStrides[offset];\n  }\n\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapGpuInputKernelToTensorInputOffset(Index i, Index j) const {\n    const size_t offset = static_cast<int>(Layout) == static_cast<int>(ColMajor)\n                              ? 0\n                              : NumDims - NumKernelDims;\n    return i * m_inputStrides[offset] + j * m_inputStrides[offset + 1];\n  }\n\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapGpuOutputKernelToTensorOutputOffset(Index i, Index j) const {\n    const size_t offset = static_cast<int>(Layout) == static_cast<int>(ColMajor)\n                              ? 0\n                              : NumDims - NumKernelDims;\n    return i * m_outputStrides[offset] + j * m_outputStrides[offset + 1];\n  }\n\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapGpuInputKernelToTensorInputOffset(Index i, Index j, Index k) const {\n    const size_t offset = static_cast<int>(Layout) == static_cast<int>(ColMajor)\n                              ? 0\n                              : NumDims - NumKernelDims;\n    return i * m_inputStrides[offset] + j * m_inputStrides[offset + 1] +\n           k * m_inputStrides[offset + 2];\n  }\n\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapGpuOutputKernelToTensorOutputOffset(Index i, Index j, Index k) const {\n    const size_t offset = static_cast<int>(Layout) == static_cast<int>(ColMajor)\n                              ? 0\n                              : NumDims - NumKernelDims;\n    return i * m_outputStrides[offset] + j * m_outputStrides[offset + 1] +\n           k * m_outputStrides[offset + 2];\n  }\n\n private:\n  static const int NumDims = internal::array_size<InputDims>::value;\n  array<Index, NumDims> m_inputStrides;\n  array<Index, NumDims> m_outputStrides;\n  array<Index, NumDims> m_gpuInputStrides;\n  array<Index, NumDims> m_gpuOutputStrides;\n};\n\n\n\ntemplate<typename Dimensions, typename InputXprType, typename KernelXprType>\nstruct traits<TensorConvolutionOp<Dimensions, InputXprType, KernelXprType> >\n{\n  // Type promotion to handle the case where the types of the lhs and the rhs are different.\n  typedef typename promote_storage_type<typename InputXprType::Scalar,\n                                        typename KernelXprType::Scalar>::ret Scalar;\n  typedef typename promote_storage_type<typename traits<InputXprType>::StorageKind,\n                                        typename traits<KernelXprType>::StorageKind>::ret StorageKind;\n  typedef typename promote_index_type<typename traits<InputXprType>::Index,\n                                      typename traits<KernelXprType>::Index>::type Index;\n  typedef typename InputXprType::Nested LhsNested;\n  typedef typename KernelXprType::Nested RhsNested;\n  typedef typename remove_reference<LhsNested>::type _LhsNested;\n  typedef typename remove_reference<RhsNested>::type _RhsNested;\n  static const int NumDimensions = traits<InputXprType>::NumDimensions;\n  static const int Layout = traits<InputXprType>::Layout;\n  typedef typename conditional<Pointer_type_promotion<typename InputXprType::Scalar, Scalar>::val,\n  typename traits<InputXprType>::PointerType, typename traits<KernelXprType>::PointerType>::type PointerType;\n\n  enum {\n    Flags = 0\n  };\n};\n\ntemplate<typename Dimensions, typename InputXprType, typename KernelXprType>\nstruct eval<TensorConvolutionOp<Dimensions, InputXprType, KernelXprType>, Eigen::Dense>\n{\n  typedef const TensorConvolutionOp<Dimensions, InputXprType, KernelXprType>& type;\n};\n\ntemplate<typename Dimensions, typename InputXprType, typename KernelXprType>\nstruct nested<TensorConvolutionOp<Dimensions, InputXprType, KernelXprType>, 1, typename eval<TensorConvolutionOp<Dimensions, InputXprType, KernelXprType> >::type>\n{\n  typedef TensorConvolutionOp<Dimensions, InputXprType, KernelXprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename Indices, typename InputXprType, typename KernelXprType>\nclass TensorConvolutionOp : public TensorBase<TensorConvolutionOp<Indices, InputXprType, KernelXprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorConvolutionOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename internal::promote_storage_type<typename InputXprType::CoeffReturnType,\n                                                  typename KernelXprType::CoeffReturnType>::ret CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorConvolutionOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorConvolutionOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorConvolutionOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorConvolutionOp(const InputXprType& input, const KernelXprType& kernel, const Indices& dims)\n      : m_input_xpr(input), m_kernel_xpr(kernel), m_indices(dims) {}\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const Indices& indices() const { return m_indices; }\n\n    /** \\returns the nested expressions */\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const typename internal::remove_all<typename InputXprType::Nested>::type&\n    inputExpression() const { return m_input_xpr; }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const typename internal::remove_all<typename KernelXprType::Nested>::type&\n    kernelExpression() const { return m_kernel_xpr; }\n\n  protected:\n    typename InputXprType::Nested m_input_xpr;\n    typename KernelXprType::Nested m_kernel_xpr;\n    const Indices m_indices;\n};\n\n\ntemplate<typename Indices, typename InputArgType, typename KernelArgType, typename Device>\nstruct TensorEvaluator<const TensorConvolutionOp<Indices, InputArgType, KernelArgType>, Device>\n{\n  typedef TensorConvolutionOp<Indices, InputArgType, KernelArgType> XprType;\n\n  static const int NumDims = internal::array_size<typename TensorEvaluator<InputArgType, Device>::Dimensions>::value;\n  static const int NumKernelDims = internal::array_size<Indices>::value;\n  typedef typename XprType::Index Index;\n  typedef DSizes<Index, NumDims> Dimensions;\n\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<Scalar, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = int(TensorEvaluator<InputArgType, Device>::IsAligned) & int(TensorEvaluator<KernelArgType, Device>::IsAligned),\n    PacketAccess = int(TensorEvaluator<InputArgType, Device>::PacketAccess) & int(TensorEvaluator<KernelArgType, Device>::PacketAccess),\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<InputArgType, Device>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_inputImpl(op.inputExpression(), device), m_kernelImpl(op.kernelExpression(), device), m_kernelArg(op.kernelExpression()), m_kernel(NULL), m_local_kernel(false), m_device(device)\n  {\n    EIGEN_STATIC_ASSERT((static_cast<int>(TensorEvaluator<InputArgType, Device>::Layout) == static_cast<int>(TensorEvaluator<KernelArgType, Device>::Layout)), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    const typename TensorEvaluator<InputArgType, Device>::Dimensions& input_dims = m_inputImpl.dimensions();\n    const typename TensorEvaluator<KernelArgType, Device>::Dimensions& kernel_dims = m_kernelImpl.dimensions();\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_inputStride[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_inputStride[i] = m_inputStride[i - 1] * input_dims[i - 1];\n      }\n    } else {\n      m_inputStride[NumDims - 1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_inputStride[i] = m_inputStride[i + 1] * input_dims[i + 1];\n      }\n    }\n\n    m_dimensions = m_inputImpl.dimensions();\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = 0; i < NumKernelDims; ++i) {\n        const Index index = op.indices()[i];\n        const Index input_dim = input_dims[index];\n        const Index kernel_dim = kernel_dims[i];\n        const Index result_dim = input_dim - kernel_dim + 1;\n        m_dimensions[index] = result_dim;\n        if (i > 0) {\n          m_kernelStride[i] = m_kernelStride[i - 1] * kernel_dims[i - 1];\n        } else {\n          m_kernelStride[0] = 1;\n        }\n        m_indexStride[i] = m_inputStride[index];\n      }\n\n      m_outputStride[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_outputStride[i] = m_outputStride[i - 1] * m_dimensions[i - 1];\n      }\n    } else {\n      for (int i = NumKernelDims - 1; i >= 0; --i) {\n        const Index index = op.indices()[i];\n        const Index input_dim = input_dims[index];\n        const Index kernel_dim = kernel_dims[i];\n        const Index result_dim = input_dim - kernel_dim + 1;\n        m_dimensions[index] = result_dim;\n        if (i < NumKernelDims - 1) {\n          m_kernelStride[i] = m_kernelStride[i + 1] * kernel_dims[i + 1];\n        } else {\n          m_kernelStride[NumKernelDims - 1] = 1;\n        }\n        m_indexStride[i] = m_inputStride[index];\n      }\n\n      m_outputStride[NumDims - 1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_outputStride[i] = m_outputStride[i + 1] * m_dimensions[i + 1];\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar*) {\n    m_inputImpl.evalSubExprsIfNeeded(NULL);\n    preloadKernel();\n    return true;\n  }\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_inputImpl.cleanup();\n    if (m_local_kernel) {\n      m_device.deallocate((void*)m_kernel);\n      m_local_kernel = false;\n    }\n    m_kernel = NULL;\n  }\n\n  void evalTo(typename XprType::Scalar* buffer) {\n    evalSubExprsIfNeeded(NULL);\n    for (int i = 0; i < dimensions().TotalSize(); ++i) {\n      buffer[i] += coeff(i);\n    }\n    cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    CoeffReturnType result = CoeffReturnType(0);\n    convolve(firstInput(index), 0, NumKernelDims-1, result);\n    return result;\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC PacketReturnType packet(const Index index) const\n  {\n    Index indices[2] = {index, index+PacketSize-1};\n    Index startInputs[2] = {0, 0};\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx0 = indices[0] / m_outputStride[i];\n        const Index idx1 = indices[1] / m_outputStride[i];\n        startInputs[0] += idx0 * m_inputStride[i];\n        startInputs[1] += idx1 * m_inputStride[i];\n        indices[0] -= idx0 * m_outputStride[i];\n        indices[1] -= idx1 * m_outputStride[i];\n      }\n    } else {\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx0 = indices[0] / m_outputStride[i];\n        const Index idx1 = indices[1] / m_outputStride[i];\n        startInputs[0] += idx0 * m_inputStride[i];\n        startInputs[1] += idx1 * m_inputStride[i];\n        indices[0] -= idx0 * m_outputStride[i];\n        indices[1] -= idx1 * m_outputStride[i];\n      }\n    }\n    startInputs[0] += indices[0];\n    startInputs[1] += indices[1];\n\n    if (startInputs[1]-startInputs[0] == PacketSize-1) {\n      PacketReturnType result = internal::pset1<PacketReturnType>(0);\n      convolvePacket(startInputs[0], 0, NumKernelDims-1, result);\n      return result;\n    } else {\n      EIGEN_ALIGN_MAX Scalar data[PacketSize];\n      data[0] = Scalar(0);\n      convolve(startInputs[0], 0, NumKernelDims-1, data[0]);\n      for (int i = 1; i < PacketSize-1; ++i) {\n        data[i] = Scalar(0);\n        convolve(firstInput(index+i), 0, NumKernelDims-1, data[i]);\n      }\n      data[PacketSize-1] = Scalar(0);\n      convolve(startInputs[1], 0, NumKernelDims-1, data[PacketSize-1]);\n      return internal::pload<PacketReturnType>(data);\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    const double kernel_size = m_kernelImpl.dimensions().TotalSize();\n    // We ignore the use of fused multiply-add.\n    const double convolve_compute_cost =\n        TensorOpCost::AddCost<Scalar>() + TensorOpCost::MulCost<Scalar>();\n    const double firstIndex_compute_cost =\n        NumDims *\n        (2 * TensorOpCost::AddCost<Index>() + 2 * TensorOpCost::MulCost<Index>() +\n         TensorOpCost::DivCost<Index>());\n    return TensorOpCost(0, 0, firstIndex_compute_cost, vectorized, PacketSize) +\n           kernel_size * (m_inputImpl.costPerCoeff(vectorized) +\n                          m_kernelImpl.costPerCoeff(vectorized) +\n                          TensorOpCost(0, 0, convolve_compute_cost, vectorized,\n                                       PacketSize));\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n private:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index firstInput(Index index) const {\n    Index startInput = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx = index / m_outputStride[i];\n        startInput += idx * m_inputStride[i];\n        index -= idx * m_outputStride[i];\n      }\n    } else {\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx = index / m_outputStride[i];\n        startInput += idx * m_inputStride[i];\n        index -= idx * m_outputStride[i];\n      }\n    }\n    startInput += index;\n    return startInput;\n  }\n\n  EIGEN_DEVICE_FUNC void convolve(Index firstIndex, Index firstKernel, int DimIndex, CoeffReturnType& accum) const {\n    for (int j = 0; j < m_kernelImpl.dimensions()[DimIndex]; ++j) {\n      const Index input = firstIndex + j * m_indexStride[DimIndex];\n      const Index kernel = firstKernel + j * m_kernelStride[DimIndex];\n      if (DimIndex > 0) {\n        convolve(input, kernel, DimIndex-1, accum);\n      } else {\n        accum += m_inputImpl.coeff(input) * m_kernel[kernel];\n      }\n    }\n  }\n\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC void convolvePacket(Index firstIndex, Index firstKernel, int DimIndex, Packet& accum) const {\n    for (int j = 0; j < m_kernelImpl.dimensions()[DimIndex]; ++j) {\n      const Index input = firstIndex + j * m_indexStride[DimIndex];\n      const Index kernel = firstKernel + j * m_kernelStride[DimIndex];\n      if (DimIndex > 0) {\n        convolvePacket(input, kernel, DimIndex-1, accum);\n      } else {\n        accum = internal::pmadd<Packet>(m_inputImpl.template packet<Unaligned>(input), internal::pset1<Packet>(m_kernel[kernel]), accum);\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void preloadKernel() {\n    // Don't make a local copy of the kernel unless we have to (i.e. it's an\n    // expression that needs to be evaluated)\n    const Scalar* in_place = m_kernelImpl.data();\n    if (in_place) {\n      m_kernel = in_place;\n      m_local_kernel = false;\n    } else {\n      size_t kernel_sz = m_kernelImpl.dimensions().TotalSize() * sizeof(Scalar);\n      Scalar* local = (Scalar*)m_device.allocate_temp(kernel_sz);\n      typedef TensorEvalToOp<const KernelArgType> EvalTo;\n      EvalTo evalToTmp(local, m_kernelArg);\n      const bool Vectorize = internal::IsVectorizable<Device, KernelArgType>::value;\n      internal::TensorExecutor<const EvalTo, Device, Vectorize>::run(evalToTmp, m_device);\n\n      m_kernel = local;\n      m_local_kernel = true;\n    }\n  }\n\n  array<Index, NumDims> m_inputStride;\n  array<Index, NumDims> m_outputStride;\n\n  array<Index, NumKernelDims> m_indexStride;\n  array<Index, NumKernelDims> m_kernelStride;\n  TensorEvaluator<InputArgType, Device> m_inputImpl;\n  TensorEvaluator<KernelArgType, Device> m_kernelImpl;\n  Dimensions m_dimensions;\n\n  KernelArgType m_kernelArg;\n  const Scalar* m_kernel;\n  bool m_local_kernel;\n  const Device EIGEN_DEVICE_REF m_device;\n};\n\n\n\n\n// Use an optimized implementation of the evaluation code for GPUs whenever possible.\n#if defined(EIGEN_USE_GPU) && defined(EIGEN_GPUCC)\n\ntemplate <int StaticKernelSize>\nstruct GetKernelSize {\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int operator() (const int /*kernelSize*/) const {\n    return StaticKernelSize;\n  }\n};\ntemplate <>\nstruct GetKernelSize<Dynamic> {\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int operator() (const int kernelSize) const {\n    return kernelSize;\n  }\n};\n\ntemplate <typename InputEvaluator, typename Index, typename InputDims,\n          int StaticKernelSize>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void EigenConvolutionKernel1D(\n    InputEvaluator eval,\n    const internal::IndexMapper<Index, InputDims, 1, InputEvaluator::Layout>\n        indexMapper,\n    const float* __restrict kernel, const int numPlanes, const int numX,\n    const int maxX, const int kernelSize, float* buffer) {\n#if defined(EIGEN_HIPCC)\n  HIP_DYNAMIC_SHARED(float, s)\n#else\n  extern __shared__ float s[];\n#endif\n\n  const int first_x = blockIdx.x * maxX;\n  const int last_x = (first_x + maxX < numX ? first_x + maxX : numX) - 1;\n  const int num_x_input = last_x - first_x + GetKernelSize<StaticKernelSize>()(kernelSize);\n  const int num_x_output = last_x - first_x + 1;\n\n  const int first_plane = blockIdx.y * blockDim.y;\n  const int plane_stride = blockDim.y * gridDim.y;\n\n  for (int p = first_plane + threadIdx.y; p < numPlanes; p += plane_stride) {\n    // Load inputs to shared memory\n    const int plane_input_offset = indexMapper.mapGpuInputPlaneToTensorInputOffset(p);\n    const int plane_kernel_offset = threadIdx.y * num_x_input;\n    #pragma unroll\n    for (int i = threadIdx.x; i < num_x_input; i += blockDim.x) {\n      const int tensor_index = plane_input_offset + indexMapper.mapGpuInputKernelToTensorInputOffset(i+first_x);\n      s[i + plane_kernel_offset] = eval.coeff(tensor_index);\n    }\n\n    __syncthreads();\n\n    // Compute the convolution\n    const int plane_output_offset = indexMapper.mapGpuOutputPlaneToTensorOutputOffset(p);\n\n    #pragma unroll\n    for (int i = threadIdx.x; i < num_x_output; i += blockDim.x) {\n      const int kernel_offset = plane_kernel_offset + i;\n      float result = 0.0f;\n      #pragma unroll\n      for (int k = 0; k < GetKernelSize<StaticKernelSize>()(kernelSize); ++k) {\n        result += s[k + kernel_offset] * kernel[k];\n      }\n      const int tensor_index = plane_output_offset + indexMapper.mapGpuOutputKernelToTensorOutputOffset(i+first_x);\n      buffer[tensor_index] = result;\n    }\n    __syncthreads();\n  }\n};\n\ntemplate <typename InputEvaluator, typename Index, typename InputDims,\n          int StaticKernelSizeX, int StaticKernelSizeY>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void EigenConvolutionKernel2D(\n    InputEvaluator eval,\n    const internal::IndexMapper<Index, InputDims, 2, InputEvaluator::Layout>\n        indexMapper,\n    const float* __restrict kernel, const int numPlanes, const int numX,\n    const int maxX, const int numY, const int maxY, const int kernelSizeX,\n    const int kernelSizeY, float* buffer) {\n#if defined(EIGEN_HIPCC)\n  HIP_DYNAMIC_SHARED(float, s)\n#else\n  extern __shared__ float s[];\n#endif\n\n  const int first_x = blockIdx.x * maxX;\n  const int last_x = (first_x + maxX < numX ? first_x + maxX : numX) - 1;\n  const int num_x_input = last_x - first_x + GetKernelSize<StaticKernelSizeX>()(kernelSizeX);\n  const int num_x_output = last_x - first_x + 1;\n\n  const int first_y = blockIdx.y * maxY;\n  const int last_y = (first_y + maxY < numY ? first_y + maxY : numY) - 1;\n  const int num_y_input = last_y - first_y + GetKernelSize<StaticKernelSizeY>()(kernelSizeY);\n  const int num_y_output = last_y - first_y + 1;\n\n  const int first_plane = blockIdx.z * blockDim.z;\n  const int plane_stride = blockDim.z * gridDim.z;\n\n  for (int p = first_plane + threadIdx.z; p < numPlanes; p += plane_stride) {\n\n    const int plane_input_offset = indexMapper.mapGpuInputPlaneToTensorInputOffset(p);\n    const int plane_kernel_offset = threadIdx.z * num_y_input;\n\n    // Load inputs to shared memory\n    #pragma unroll\n    for (int j = threadIdx.y; j < num_y_input; j += blockDim.y) {\n      const int input_offset = num_x_input * (j + plane_kernel_offset);\n      #pragma unroll\n      for (int i = threadIdx.x; i < num_x_input; i += blockDim.x) {\n        const int tensor_index = plane_input_offset + indexMapper.mapGpuInputKernelToTensorInputOffset(i+first_x, j+first_y);\n        s[i + input_offset] = eval.coeff(tensor_index);\n      }\n    }\n\n    __syncthreads();\n\n    // Convolution\n    const int plane_output_offset = indexMapper.mapGpuOutputPlaneToTensorOutputOffset(p);\n\n    #pragma unroll\n    for (int j = threadIdx.y; j < num_y_output; j += blockDim.y) {\n      #pragma unroll\n      for (int i = threadIdx.x; i < num_x_output; i += blockDim.x) {\n        float result = 0.0f;\n        #pragma unroll\n        for (int l = 0; l < GetKernelSize<StaticKernelSizeY>()(kernelSizeY); ++l) {\n          const int kernel_offset = kernelSizeX * l;\n          const int input_offset = i + num_x_input * (j + l + plane_kernel_offset);\n          #pragma unroll\n          for (int k = 0; k < GetKernelSize<StaticKernelSizeX>()(kernelSizeX); ++k) {\n            result += s[k + input_offset] * kernel[k + kernel_offset];\n          }\n        }\n        const int tensor_index = plane_output_offset + indexMapper.mapGpuOutputKernelToTensorOutputOffset(i+first_x, j+first_y);\n        buffer[tensor_index] = result;\n      }\n    }\n\n    __syncthreads();\n  }\n};\n\ntemplate <typename InputEvaluator, typename Index, typename InputDims>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void EigenConvolutionKernel3D(\n    InputEvaluator eval,\n    const internal::IndexMapper<Index, InputDims, 3, InputEvaluator::Layout>\n        indexMapper,\n    const float* __restrict kernel, const size_t numPlanes, const size_t numX,\n    const size_t maxX, const size_t numY, const size_t maxY, const size_t numZ,\n    const size_t maxZ, const size_t kernelSizeX, const size_t kernelSizeY,\n    const size_t kernelSizeZ, float* buffer) {\n#if defined(EIGEN_HIPCC)\n  HIP_DYNAMIC_SHARED(float, s)\n#else\n  extern __shared__ float s[];\n#endif\n\n  // Load inputs to shared memory\n  const int first_x = blockIdx.x * maxX;\n  const int last_x = (first_x + maxX < numX ? first_x + maxX : numX) - 1;\n  const int num_x_input = last_x - first_x + kernelSizeX;\n\n  const int first_y = blockIdx.y * maxY;\n  const int last_y = (first_y + maxY < numY ? first_y + maxY : numY) - 1;\n  const int num_y_input = last_y - first_y + kernelSizeY;\n\n  const int first_z = blockIdx.z * maxZ;\n  const int last_z = (first_z + maxZ < numZ ? first_z + maxZ : numZ) - 1;\n  const int num_z_input = last_z - first_z + kernelSizeZ;\n\n  for (int p = 0; p < numPlanes; ++p) {\n\n    const int plane_input_offset = indexMapper.mapGpuInputPlaneToTensorInputOffset(p);\n    const int plane_kernel_offset = 0;\n\n    for (int k = threadIdx.z; k < num_z_input; k += blockDim.z) {\n      for (int j = threadIdx.y; j < num_y_input; j += blockDim.y) {\n        for (int i = threadIdx.x; i < num_x_input; i += blockDim.x) {\n          const int tensor_index = plane_input_offset + indexMapper.mapGpuInputKernelToTensorInputOffset(i+first_x, j+first_y, k+first_z);\n          s[i + num_x_input * (j + num_y_input * (k + plane_kernel_offset))] = eval.coeff(tensor_index);\n        }\n      }\n    }\n\n    __syncthreads();\n\n    // Convolution\n    const int num_z_output = last_z - first_z + 1;\n    const int num_y_output = last_y - first_y + 1;\n    const int num_x_output = last_x - first_x + 1;\n    const int plane_output_offset = indexMapper.mapGpuOutputPlaneToTensorOutputOffset(p);\n\n    for (int k = threadIdx.z; k < num_z_output; k += blockDim.z) {\n      for (int j = threadIdx.y; j < num_y_output; j += blockDim.y) {\n        for (int i = threadIdx.x; i < num_x_output; i += blockDim.x) {\n          float result = 0.0f;\n          for (int n = 0; n < kernelSizeZ; ++n) {\n            for (int m = 0; m < kernelSizeY; ++m) {\n              for (int l = 0; l < kernelSizeX; ++l) {\n                result += s[i + l + num_x_input * (j + m + num_y_input * (k + n + plane_kernel_offset))] * kernel[l + kernelSizeX * (m + kernelSizeY * n)];\n              }\n            }\n          }\n          const int tensor_index = plane_output_offset + indexMapper.mapGpuOutputKernelToTensorOutputOffset(i+first_x, j+first_y, k+first_z);\n          buffer[tensor_index] = result;\n        }\n      }\n    }\n    __syncthreads();\n  }\n};\n\n\n\ntemplate<typename Indices, typename InputArgType, typename KernelArgType>\nstruct TensorEvaluator<const TensorConvolutionOp<Indices, InputArgType, KernelArgType>, GpuDevice>\n{\n  typedef TensorConvolutionOp<Indices, InputArgType, KernelArgType> XprType;\n\n  static const int NumDims =  internal::array_size<typename TensorEvaluator<InputArgType, GpuDevice>::Dimensions>::value;\n  static const int NumKernelDims = internal::array_size<Indices>::value;\n  typedef typename XprType::Index Index;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename TensorEvaluator<KernelArgType, GpuDevice>::Dimensions KernelDimensions;\n\n  enum {\n    IsAligned = TensorEvaluator<InputArgType, GpuDevice>::IsAligned & TensorEvaluator<KernelArgType, GpuDevice>::IsAligned,\n    PacketAccess = false,\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<InputArgType, GpuDevice>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  TensorEvaluator(const XprType& op, const GpuDevice& device)\n      : m_inputImpl(op.inputExpression(), device), m_kernelImpl(op.kernelExpression(), device), m_kernelArg(op.kernelExpression()), m_indices(op.indices()), m_buf(NULL), m_kernel(NULL), m_local_kernel(false), m_device(device)\n  {\n    EIGEN_STATIC_ASSERT((static_cast<int>(TensorEvaluator<InputArgType, GpuDevice>::Layout) == static_cast<int>(TensorEvaluator<KernelArgType, GpuDevice>::Layout)), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    const typename TensorEvaluator<InputArgType, GpuDevice>::Dimensions& input_dims = m_inputImpl.dimensions();\n    const typename TensorEvaluator<KernelArgType, GpuDevice>::Dimensions& kernel_dims = m_kernelImpl.dimensions();\n\n    m_dimensions = m_inputImpl.dimensions();\n    for (int i = 0; i < NumKernelDims; ++i) {\n      const Index index = op.indices()[i];\n      const Index input_dim = input_dims[index];\n      const Index kernel_dim = kernel_dims[i];\n      const Index result_dim = input_dim - kernel_dim + 1;\n      m_dimensions[index] = result_dim;\n    }\n  }\n\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, GpuDevice>::type PacketReturnType;\n  typedef typename InputArgType::Scalar Scalar;\n  static const int PacketSize = internal::unpacket_traits<PacketReturnType>::size;\n\n  EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* data) {\n    preloadKernel();\n    m_inputImpl.evalSubExprsIfNeeded(NULL);\n    if (data) {\n      executeEval(data);\n      return false;\n    } else {\n      m_buf = (Scalar*)m_device.allocate(dimensions().TotalSize() * sizeof(Scalar));\n      executeEval(m_buf);\n      return true;\n    }\n  }\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_inputImpl.cleanup();\n    if (m_buf) {\n      m_device.deallocate(m_buf);\n      m_buf = NULL;\n    }\n    if (m_local_kernel) {\n      m_device.deallocate((void*)m_kernel);\n      m_local_kernel = false;\n    }\n    m_kernel = NULL;\n  }\n\n  EIGEN_STRONG_INLINE void preloadKernel() {\n    // Don't make a local copy of the kernel unless we have to (i.e. it's an\n    // expression that needs to be evaluated)\n    const Scalar* in_place = m_kernelImpl.data();\n    if (in_place) {\n      m_kernel = in_place;\n      m_local_kernel = false;\n    } else {\n      size_t kernel_sz = m_kernelImpl.dimensions().TotalSize() * sizeof(Scalar);\n      Scalar* local = (Scalar*)m_device.allocate(kernel_sz);\n      typedef TensorEvalToOp<const KernelArgType> EvalTo;\n      EvalTo evalToTmp(local, m_kernelArg);\n      const bool PacketAccess = internal::IsVectorizable<GpuDevice, KernelArgType>::value;\n      internal::TensorExecutor<const EvalTo, GpuDevice, PacketAccess>::run(evalToTmp, m_device);\n\n      m_kernel = local;\n      m_local_kernel = true;\n    }\n  }\n\n  static unsigned int ceil(unsigned int num, unsigned int denom) {\n    const unsigned int rounded_toward_zero = num / denom;\n    if (num > rounded_toward_zero * denom) {\n      return rounded_toward_zero + 1;\n    }\n    return rounded_toward_zero;\n  }\n\n  void executeEval(Scalar* data) const {\n    typedef typename TensorEvaluator<InputArgType, GpuDevice>::Dimensions InputDims;\n\n    const int maxSharedMem = m_device.sharedMemPerBlock();\n    const int maxThreadsPerBlock = m_device.maxGpuThreadsPerBlock();\n    const int maxBlocksPerProcessor = m_device.maxGpuThreadsPerMultiProcessor() / maxThreadsPerBlock;\n    const int numMultiProcessors = m_device.getNumGpuMultiProcessors();\n    const int warpSize = 32;\n\n    switch (NumKernelDims) {\n      case 1: {\n        const int kernel_size = m_kernelImpl.dimensions().TotalSize();\n\n        const int numX = dimensions()[m_indices[0]];\n        const int numP = dimensions().TotalSize() / numX;\n        int maxX;\n        dim3 block_size;\n\n        const int single_stride_dim =\n            static_cast<int>(Layout) == static_cast<int>(ColMajor)\n                ? 0\n                : m_inputImpl.dimensions().rank() - 1;\n        if (m_indices[0] == single_stride_dim) {\n          // Maximum the reuse\n          const int inner_dim = ((maxSharedMem / (sizeof(Scalar)) - kernel_size + 1 + 31) / 32) * 32;\n          maxX = numext::mini<int>(inner_dim, numX);\n          const int maxP = numext::mini<int>(maxSharedMem / ((kernel_size - 1 + maxX) * sizeof(Scalar)), numP);\n          block_size.x = numext::mini(maxThreadsPerBlock, maxX);\n          block_size.y = numext::mini<int>(maxThreadsPerBlock / block_size.x, maxP);\n        }\n        else {\n          // Read as much as possible alongside the inner most dimension, that is the plane\n          const int inner_dim = maxSharedMem / ((warpSize + kernel_size) * sizeof(Scalar));\n          const int maxP = numext::mini<int>(inner_dim, numP);\n          maxX = numext::mini<int>(maxSharedMem / (inner_dim * sizeof(Scalar)) - kernel_size + 1, numX);\n\n          block_size.x = numext::mini(warpSize, maxX);\n          block_size.y = numext::mini<int>(maxThreadsPerBlock/block_size.x, maxP);\n        }\n\n        const int shared_mem = block_size.y * (maxX + kernel_size - 1) * sizeof(Scalar);\n        gpu_assert(shared_mem <= maxSharedMem);\n\n        const int num_x_blocks = ceil(numX, maxX);\n        const int blocksPerProcessor = numext::mini(maxBlocksPerProcessor, maxSharedMem / shared_mem);\n        const int num_y_blocks = ceil(numMultiProcessors * blocksPerProcessor, num_x_blocks);\n\n        dim3 num_blocks(num_x_blocks, numext::mini<int>(num_y_blocks, ceil(numP, block_size.y)));\n\n\n        //cout << \"launching 1D kernel with block_size.x: \" << block_size.x << \" block_size.y: \" << block_size.y << \" num_blocks.x: \" << num_blocks.x << \" num_blocks.y: \" << num_blocks.y << \" maxX: \" << maxX << \" shared_mem: \" << shared_mem << \" in stream \" << m_device.stream() << endl;\n\n        const array<Index, 1> indices(m_indices[0]);\n        const array<Index, 1> kernel_dims(m_kernelImpl.dimensions()[0]);\n        internal::IndexMapper<Index, InputDims, 1, Layout> indexMapper(\n            m_inputImpl.dimensions(), kernel_dims, indices);\n        switch(kernel_size) {\n          case 4: {\n            LAUNCH_GPU_KERNEL((EigenConvolutionKernel1D<TensorEvaluator<InputArgType, GpuDevice>, Index, InputDims, 4>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, 4, data);\n            break;\n          }\n          case 7: {\n            LAUNCH_GPU_KERNEL((EigenConvolutionKernel1D<TensorEvaluator<InputArgType, GpuDevice>, Index, InputDims, 7>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, 7, data);\n            break;\n          }\n          default: {\n            LAUNCH_GPU_KERNEL((EigenConvolutionKernel1D<TensorEvaluator<InputArgType, GpuDevice>, Index, InputDims, Dynamic>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, kernel_size, data);\n          }\n        }\n        break;\n      }\n\n      case 2: {\n        const int idxX =\n            static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 0 : 1;\n        const int idxY =\n            static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 1 : 0;\n        const int kernel_size_x = m_kernelImpl.dimensions()[idxX];\n        const int kernel_size_y = m_kernelImpl.dimensions()[idxY];\n\n        const int numX = dimensions()[m_indices[idxX]];\n        const int numY = dimensions()[m_indices[idxY]];\n        const int numP = dimensions().TotalSize() / (numX*numY);\n\n        const float scaling_factor = sqrtf(static_cast<float>(maxSharedMem) / (sizeof(Scalar) * kernel_size_y * kernel_size_x));\n\n        // Snap maxX to warp size\n        int inner_dim = ((static_cast<int>(scaling_factor * kernel_size_x) - kernel_size_x + 1 + 32) / 32) * 32;\n        const int maxX = numext::mini<int>(inner_dim, numX);\n        const int maxY = numext::mini<int>(maxSharedMem / (sizeof(Scalar) * (maxX + kernel_size_x - 1)) - kernel_size_y + 1, numY);\n        const int maxP = numext::mini<int>(maxSharedMem / ((kernel_size_x - 1 + maxX) * (kernel_size_y - 1 + maxY) * sizeof(Scalar)), numP);\n\n        dim3 block_size;\n        block_size.x = numext::mini(1024, maxX);\n        block_size.y = numext::mini<int>(1024/block_size.x, maxY);\n        block_size.z = numext::mini<int>(1024/(block_size.x*block_size.y), maxP);\n\n        const int shared_mem = block_size.z * (maxX + kernel_size_x - 1) * (maxY + kernel_size_y - 1) * sizeof(Scalar);\n        gpu_assert(shared_mem <= maxSharedMem);\n\n        const int num_x_blocks = ceil(numX, maxX);\n        const int num_y_blocks = ceil(numY, maxY);\n        const int blocksPerProcessor = numext::mini(maxBlocksPerProcessor, maxSharedMem / shared_mem);\n        const int num_z_blocks = ceil(numMultiProcessors * blocksPerProcessor, num_x_blocks * num_y_blocks);\n\n        dim3 num_blocks(num_x_blocks, num_y_blocks, numext::mini<int>(num_z_blocks, ceil(numP, block_size.z)));\n\n\n        //cout << \"launching 2D kernel with block_size.x: \" << block_size.x << \" block_size.y: \" << block_size.y  << \" block_size.z: \" << block_size.z << \" num_blocks.x: \" << num_blocks.x << \" num_blocks.y: \" << num_blocks.y << \" num_blocks.z: \" << num_blocks.z << \" maxX: \" << maxX << \" maxY: \" << maxY << \" maxP: \" << maxP << \" shared_mem: \" << shared_mem << \" in stream \" << m_device.stream() << endl;\n\n        const array<Index, 2> indices(m_indices[idxX], m_indices[idxY]);\n        const array<Index, 2> kernel_dims(m_kernelImpl.dimensions()[idxX],\n                                          m_kernelImpl.dimensions()[idxY]);\n        internal::IndexMapper<Index, InputDims, 2, Layout> indexMapper(\n            m_inputImpl.dimensions(), kernel_dims, indices);\n        switch (kernel_size_x) {\n          case 4: {\n            switch (kernel_size_y) {\n              case 7: {\n                LAUNCH_GPU_KERNEL((EigenConvolutionKernel2D<TensorEvaluator<InputArgType, GpuDevice>, Index, InputDims, 4, 7>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, 4, 7, data);\n                break;\n              }\n              default: {\n                LAUNCH_GPU_KERNEL((EigenConvolutionKernel2D<TensorEvaluator<InputArgType, GpuDevice>, Index, InputDims, 4, Dynamic>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, 4, kernel_size_y, data);\n                break;\n              }\n            }\n            break;\n          }\n          case 7: {\n            switch (kernel_size_y) {\n              case 4: {\n                LAUNCH_GPU_KERNEL((EigenConvolutionKernel2D<TensorEvaluator<InputArgType, GpuDevice>, Index, InputDims, 7, 4>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, 7, 4, data);\n                break;\n              }\n              default: {\n                LAUNCH_GPU_KERNEL((EigenConvolutionKernel2D<TensorEvaluator<InputArgType, GpuDevice>, Index, InputDims, 7, Dynamic>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, 7, kernel_size_y, data);\n                break;\n              }\n            }\n            break;\n          }\n          default: {\n            LAUNCH_GPU_KERNEL((EigenConvolutionKernel2D<TensorEvaluator<InputArgType, GpuDevice>, Index, InputDims, Dynamic, Dynamic>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, kernel_size_x, kernel_size_y, data);\n            break;\n          }\n        }\n        break;\n      }\n\n      case 3: {\n        const int idxX =\n            static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 0 : 2;\n        const int idxY =\n            static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 1 : 1;\n        const int idxZ =\n            static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 2 : 0;\n\n        const int kernel_size_x = m_kernelImpl.dimensions()[idxX];\n        const int kernel_size_y = m_kernelImpl.dimensions()[idxY];\n        const int kernel_size_z = m_kernelImpl.dimensions()[idxZ];\n\n        const int numX = dimensions()[m_indices[idxX]];\n        const int numY = dimensions()[m_indices[idxY]];\n        const int numZ = dimensions()[m_indices[idxZ]];\n        const int numP = dimensions().TotalSize() / (numX*numY*numZ);\n\n        const int maxX = numext::mini<int>(128, numext::mini<int>(maxSharedMem / (sizeof(Scalar) * kernel_size_y * kernel_size_z) - kernel_size_x + 1, numX));\n        const int maxY = numext::mini<int>(128, numext::mini<int>(maxSharedMem / (sizeof(Scalar) * (maxX + kernel_size_x - 1) * kernel_size_z) - kernel_size_y + 1, numY));\n        const int maxZ = numext::mini<int>(128, numext::mini<int>(maxSharedMem / (sizeof(Scalar) * (maxX + kernel_size_x - 1) * (maxY + kernel_size_y - 1)) - kernel_size_z + 1, numZ));\n\n        dim3 block_size;\n        block_size.x = numext::mini(32, maxX);\n        block_size.y = numext::mini(32, maxY);\n        block_size.z = numext::mini<int>(1024/(block_size.x*block_size.y), maxZ);\n        dim3 num_blocks(ceil(numX, maxX), ceil(numY, maxY), ceil(numZ, maxZ));\n\n        const int shared_mem = (maxX + kernel_size_x - 1) * (maxY + kernel_size_y - 1) * (maxZ + kernel_size_z - 1) * sizeof(Scalar);\n        gpu_assert(shared_mem <= maxSharedMem);\n\n        //cout << \"launching 3D kernel with block_size.x: \" << block_size.x << \" block_size.y: \" << block_size.y  << \" block_size.z: \" << block_size.z << \" num_blocks.x: \" << num_blocks.x << \" num_blocks.y: \" << num_blocks.y << \" num_blocks.z: \" << num_blocks.z  << \" shared_mem: \" << shared_mem << \" in stream \" << m_device.stream() << endl;\n        const array<Index, 3> indices(m_indices[idxX], m_indices[idxY],\n                                      m_indices[idxZ]);\n        const array<Index, 3> kernel_dims(m_kernelImpl.dimensions()[idxX],\n                                          m_kernelImpl.dimensions()[idxY],\n                                          m_kernelImpl.dimensions()[idxZ]);\n        internal::IndexMapper<Index, InputDims, 3, Layout> indexMapper(\n            m_inputImpl.dimensions(), kernel_dims, indices);\n\n        LAUNCH_GPU_KERNEL((EigenConvolutionKernel3D<TensorEvaluator<InputArgType, GpuDevice>, Index, InputDims>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, numZ, maxZ, kernel_size_x, kernel_size_y, kernel_size_z, data);\n        break;\n      }\n\n      default: {\n        EIGEN_STATIC_ASSERT((NumKernelDims >= 1 && NumKernelDims <= 3), THIS_METHOD_IS_ONLY_FOR_OBJECTS_OF_A_SPECIFIC_SIZE);\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    eigen_assert(m_buf);\n    eigen_assert(index < m_dimensions.TotalSize());\n    return m_buf[index];\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(const Index index) const\n  {\n    eigen_assert(m_buf);\n    eigen_assert(index < m_dimensions.TotalSize());\n    return internal::ploadt<PacketReturnType, LoadMode>(m_buf+index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    // TODO(rmlarsen): FIXME: For now, this is just a copy of the CPU cost\n    // model.\n    const double kernel_size = m_kernelImpl.dimensions().TotalSize();\n    // We ignore the use of fused multiply-add.\n    const double convolve_compute_cost =\n        TensorOpCost::AddCost<Scalar>() + TensorOpCost::MulCost<Scalar>();\n    const double firstIndex_compute_cost =\n        NumDims *\n        (2 * TensorOpCost::AddCost<Index>() + 2 * TensorOpCost::MulCost<Index>() +\n         TensorOpCost::DivCost<Index>());\n    return TensorOpCost(0, 0, firstIndex_compute_cost, vectorized, PacketSize) +\n           kernel_size * (m_inputImpl.costPerCoeff(vectorized) +\n                          m_kernelImpl.costPerCoeff(vectorized) +\n                          TensorOpCost(0, 0, convolve_compute_cost, vectorized,\n                                       PacketSize));\n  }\n\n private:\n  // No assignment (copies are needed by the kernels)\n  TensorEvaluator& operator = (const TensorEvaluator&);\n\n  TensorEvaluator<InputArgType, GpuDevice> m_inputImpl;\n  TensorEvaluator<KernelArgType, GpuDevice> m_kernelImpl;\n  KernelArgType m_kernelArg;\n  Indices m_indices;\n  Dimensions m_dimensions;\n  Scalar* m_buf;\n  const Scalar* m_kernel;\n  bool m_local_kernel;\n\n  const GpuDevice& m_device;\n};\n#endif\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConvolutionSycl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_SYCL_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_SYCL_H\n\nnamespace Eigen {\n\n/** \\class TensorConvolution\n * \\ingroup CXX11_Tensor_Module\n *\n * \\brief Tensor convolution class.\n *\n *\n */\n\nenum class convolution_type { CONV1D, CONV2D, CONV3D };\ntemplate <typename Evaluator, typename CoeffReturnType, typename KernelType, typename Index, typename InputDims,\n          typename Kernel_accessor, typename Buffer_accessor, convolution_type Conv_Dim>\nstruct EigenConvolutionKernel;\ntemplate <typename Evaluator, typename CoeffReturnType, typename KernelType, typename Index, typename InputDims,\n          typename Kernel_accessor, typename Buffer_accessor>\nstruct EigenConvolutionKernel<Evaluator, CoeffReturnType, KernelType, Index, InputDims, Kernel_accessor,\n                              Buffer_accessor, convolution_type::CONV1D> {\n  typedef cl::sycl::accessor<CoeffReturnType, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local>\n      Local_accessor;\n  Local_accessor local_acc;\n  Evaluator device_evaluator;\n  Kernel_accessor kernel_filter;\n  Buffer_accessor buffer_acc;\n  internal::IndexMapper<Index, InputDims, 1, Evaluator::Layout> indexMapper;\n  const size_t kernelSize;\n  const cl::sycl::range<2> input_range;\n  EigenConvolutionKernel(Local_accessor local_acc_, Evaluator device_evaluator_, Kernel_accessor kernel_filter_,\n                         Buffer_accessor buffer_acc_,\n                         internal::IndexMapper<Index, InputDims, 1, Evaluator::Layout> indexMapper_,\n                         const size_t kernelSize_, const cl::sycl::range<2> input_range_)\n      : local_acc(local_acc_),\n        device_evaluator(device_evaluator_),\n        kernel_filter(kernel_filter_),\n        buffer_acc(buffer_acc_),\n        indexMapper(indexMapper_),\n        kernelSize(kernelSize_),\n        input_range(input_range_) {}\n\n  template <typename BooleanDim2>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool boundary_check(const BooleanDim2 boolean_check) {\n    return (boolean_check[0] && boolean_check[1]);\n  }\n  void operator()(cl::sycl::nd_item<2> itemID) {\n    auto buffer_ptr = buffer_acc.get_pointer();\n    auto kernel_ptr = kernel_filter.get_pointer();\n    // the required row to be calculated for the for each plane in shered memory\n    const size_t num_input = (itemID.get_local_range()[0] + kernelSize - 1);\n    const size_t plane_kernel_offset = itemID.get_local_id(1) * num_input;\n    const size_t input_offset = itemID.get_group(0) * itemID.get_local_range()[0];\n    const size_t plane_tensor_offset = indexMapper.mapGpuInputPlaneToTensorInputOffset(itemID.get_global_id(1));\n    /// fill the shared memory\n    for (size_t i = itemID.get_local_id(0); i < num_input; i += itemID.get_local_range()[0]) {\n      const size_t local_index = i + plane_kernel_offset;\n      const size_t tensor_index =\n          plane_tensor_offset + indexMapper.mapGpuInputKernelToTensorInputOffset(i + input_offset);\n\n      local_acc[local_index] =\n          (((i + input_offset) < (input_range[0] + kernelSize - 1)) && itemID.get_global_id(1) < input_range[1])\n              ? device_evaluator.coeff(tensor_index)\n              : CoeffReturnType(0);\n    }\n\n    itemID.barrier(cl::sycl::access::fence_space::local_space);\n\n    // calculate the convolution // output start x\n    const size_t first_output_start = itemID.get_group(0) * (itemID.get_local_range()[0]);\n    if (boundary_check(itemID.get_global_id() < input_range)) {\n      CoeffReturnType result = static_cast<CoeffReturnType>(0);\n      const size_t index = plane_kernel_offset + itemID.get_local_id(0);\n      for (size_t k = 0; k < kernelSize; ++k) {\n        result += (local_acc[k + index] * kernel_ptr[k]);\n      }\n      const size_t tensor_index =\n          indexMapper.mapGpuOutputPlaneToTensorOutputOffset(itemID.get_global_id(1)) +\n          indexMapper.mapGpuOutputKernelToTensorOutputOffset(itemID.get_local_id(0) + first_output_start);\n      buffer_ptr[tensor_index] = result;\n    }\n  }\n};\n\ntemplate <typename Evaluator, typename CoeffReturnType, typename KernelType, typename Index, typename InputDims,\n          typename Kernel_accessor, typename Buffer_accessor>\nstruct EigenConvolutionKernel<Evaluator, CoeffReturnType, KernelType, Index, InputDims, Kernel_accessor,\n                              Buffer_accessor, convolution_type::CONV2D> {\n  typedef cl::sycl::accessor<CoeffReturnType, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local>\n      Local_accessor;\n  Local_accessor local_acc;\n  Evaluator device_evaluator;\n  Kernel_accessor kernel_filter;\n  Buffer_accessor buffer_acc;\n  internal::IndexMapper<Index, InputDims, 2, Evaluator::Layout> indexMapper;\n  const cl::sycl::range<2> kernel_size;\n  const cl::sycl::range<3> input_range;\n  EigenConvolutionKernel(Local_accessor local_acc_, Evaluator device_evaluator_, Kernel_accessor kernel_filter_,\n                         Buffer_accessor buffer_acc_,\n                         internal::IndexMapper<Index, InputDims, 2, Evaluator::Layout> indexMapper_,\n                         const cl::sycl::range<2> kernel_size_, const cl::sycl::range<3> input_range_)\n      : local_acc(local_acc_),\n        device_evaluator(device_evaluator_),\n        kernel_filter(kernel_filter_),\n        buffer_acc(buffer_acc_),\n        indexMapper(indexMapper_),\n        kernel_size(kernel_size_),\n        input_range(input_range_) {}\n  template <typename BooleanDim3>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool boundary_check(const BooleanDim3 boolean_check) {\n    return (boolean_check[0] && boolean_check[1] && boolean_check[2]);\n  }\n\n  void operator()(cl::sycl::nd_item<3> itemID) {\n    auto buffer_ptr = buffer_acc.get_pointer();\n    auto kernel_ptr = kernel_filter.get_pointer();\n    // the required row to be calculated for the for each plane in shered memory\n    const auto num_input = cl::sycl::range<2>{\n        (cl::sycl::range<2>(itemID.get_local_range()[0], itemID.get_local_range()[1]) + kernel_size - 1)};\n\n    const size_t plane_input_offset = indexMapper.mapGpuInputPlaneToTensorInputOffset(itemID.get_global_id(2));\n    const size_t plane_kernel_offset = itemID.get_local_id(2) * num_input[1];\n\n    const auto input_offset = cl::sycl::range<2>{itemID.get_group(0) * itemID.get_local_range()[0],\n                                                 itemID.get_group(1) * itemID.get_local_range()[1]};\n      \n    // fill the local memory\n    bool in_range_dim2 = itemID.get_global_id(2) < input_range[2];\n    for (size_t j = itemID.get_local_id(1); j < num_input[1]; j += itemID.get_local_range()[1]) {\n      const size_t local_input_offset = num_input[0] * (j + plane_kernel_offset);\n      bool in_range_dim1 = ((j + input_offset[1]) < (input_range[1] + kernel_size[1] - 1)); \n      for (size_t i = itemID.get_local_id(0); i < num_input[0]; i += itemID.get_local_range()[0]) {\n        const size_t local_index = i + local_input_offset;\n        const size_t tensor_index = plane_input_offset + indexMapper.mapGpuInputKernelToTensorInputOffset(\n                                                             i + input_offset[0], j + input_offset[1]);\n        local_acc[local_index] = (((i + input_offset[0]) < (input_range[0] + kernel_size[0] - 1)) &&\n                                  in_range_dim1 && in_range_dim2)\n                                     ? device_evaluator.coeff(tensor_index)\n                                     : CoeffReturnType(0);\n      }\n    }\n\n    itemID.barrier(cl::sycl::access::fence_space::local_space);\n\n    // output offset start for each thread\n    const auto output_offset = cl::sycl::range<2>{itemID.get_group(0) * itemID.get_local_range()[0],\n                                                  itemID.get_group(1) * itemID.get_local_range()[1]};\n\n    if (boundary_check(itemID.get_global_id() < input_range)) {\n      CoeffReturnType result = static_cast<CoeffReturnType>(0);\n\n      for (size_t j = 0; j < kernel_size[1]; j++) {\n        size_t kernel_offset = kernel_size[0] * j;\n        const size_t index =\n            (num_input[0] * (plane_kernel_offset + j + itemID.get_local_id(1))) + itemID.get_local_id(0);\n        for (size_t i = 0; i < kernel_size[0]; i++) {\n          result += (local_acc[i + index] * kernel_ptr[i + kernel_offset]);\n        }\n      }\n      const size_t tensor_index =\n          indexMapper.mapGpuOutputPlaneToTensorOutputOffset(itemID.get_global_id(2)) +\n          indexMapper.mapGpuOutputKernelToTensorOutputOffset(itemID.get_local_id(0) + output_offset[0],\n                                                             itemID.get_local_id(1) + output_offset[1]);\n\n      buffer_ptr[tensor_index] = result;\n    }\n  }\n};\n\ntemplate <typename Evaluator, typename CoeffReturnType, typename KernelType, typename Index, typename InputDims,\n          typename Kernel_accessor, typename Buffer_accessor>\nstruct EigenConvolutionKernel<Evaluator, CoeffReturnType, KernelType, Index, InputDims, Kernel_accessor,\n                              Buffer_accessor, convolution_type::CONV3D> {\n  typedef cl::sycl::accessor<CoeffReturnType, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local>\n      Local_accessor;\n  Local_accessor local_acc;\n  Evaluator device_evaluator;\n  Kernel_accessor kernel_filter;\n  Buffer_accessor buffer_acc;\n  internal::IndexMapper<Index, InputDims, 3, Evaluator::Layout> indexMapper;\n  const cl::sycl::range<3> kernel_size;\n  const cl::sycl::range<3> input_range;\n  const size_t numP;\n\n  EigenConvolutionKernel(Local_accessor local_acc_, Evaluator device_evaluator_, Kernel_accessor kernel_filter_,\n                         Buffer_accessor buffer_acc_,\n                         internal::IndexMapper<Index, InputDims, 3, Evaluator::Layout> indexMapper_,\n                         const cl::sycl::range<3> kernel_size_, const cl::sycl::range<3> input_range_,\n                         const size_t numP_)\n      : local_acc(local_acc_),\n        device_evaluator(device_evaluator_),\n        kernel_filter(kernel_filter_),\n        buffer_acc(buffer_acc_),\n        indexMapper(indexMapper_),\n        kernel_size(kernel_size_),\n        input_range(input_range_),\n        numP(numP_) {}\n  template <typename BooleanDim3>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool boundary_check(const BooleanDim3 boolean_check) {\n    return (boolean_check[0] && boolean_check[1] && boolean_check[2]);\n  }\n  void operator()(cl::sycl::nd_item<3> itemID) {\n    auto buffer_ptr = buffer_acc.get_pointer();\n    auto kernel_ptr = kernel_filter.get_pointer();\n    const auto num_input = cl::sycl::range<3>{itemID.get_local_range() + kernel_size - 1};\n\n    const auto input_offset = cl::sycl::range<3>{itemID.get_group().get_id() * itemID.get_local_range()};\n\n    const auto output_offset =\n          cl::sycl::range<3>{itemID.get_group().get_id() * itemID.get_local_range() + itemID.get_local_id()};\n\n    for (size_t p = 0; p < numP; p++) {\n      /// fill the shared memory\n      const size_t plane_input_offset = indexMapper.mapGpuInputPlaneToTensorInputOffset(p);\n      for (size_t k = itemID.get_local_id(2); k < num_input[2]; k += itemID.get_local_range()[2]) {\n        size_t local_index_dim2 = num_input[0] * num_input[1] * k;\n        bool cond_k_dim = (k + input_offset[2] < (input_range[2] + kernel_size[2] - 1));\n        for (size_t j = itemID.get_local_id(1); j < num_input[1]; j += itemID.get_local_range()[1]) {\n          bool cond_j_dim = cond_k_dim && (j + input_offset[1] < (input_range[1] + kernel_size[1] - 1));\n          size_t local_index_dim1 = (num_input[0] * j)  + local_index_dim2;\n          for (size_t i = itemID.get_local_id(0); i < num_input[0]; i += itemID.get_local_range()[0]) {\n            bool conds = cond_j_dim && (i + input_offset[0] < (input_range[0] + kernel_size[0] - 1));\n            const size_t local_index = local_index_dim1 + i;\n            const size_t tensor_index =\n                plane_input_offset + indexMapper.mapGpuInputKernelToTensorInputOffset(\n                                         i + input_offset[0], j + input_offset[1], k + input_offset[2]);\n            local_acc[local_index] = conds ? device_evaluator.coeff(tensor_index) : CoeffReturnType(0);\n          }\n        }\n      }\n      itemID.barrier(cl::sycl::access::fence_space::local_space);\n\n      // calculate the convolution\n\n      if (boundary_check(itemID.get_global_id() < input_range)) {\n        CoeffReturnType result = static_cast<CoeffReturnType>(0);\n        for (size_t k = 0; k < kernel_size[2]; k++) {\n          for (size_t j = 0; j < kernel_size[1]; j++) {\n            for (size_t i = 0; i < kernel_size[0]; i++) {\n              const size_t kernel_index = i + kernel_size[0] * (j + kernel_size[1] * k);\n              const size_t local_index =\n                  ((i + itemID.get_local_id(0)) +\n                   num_input[0] * ((j + itemID.get_local_id(1)) + num_input[1] * (k + itemID.get_local_id(2))));\n\n              result += (local_acc[local_index] * kernel_ptr[kernel_index]);\n            }\n          }\n        }\n        const size_t tensor_index =\n            indexMapper.mapGpuOutputPlaneToTensorOutputOffset(p) +\n            indexMapper.mapGpuOutputKernelToTensorOutputOffset(output_offset[0], output_offset[1], output_offset[2]);\n        buffer_ptr[tensor_index] = result;\n      }\n\n      itemID.barrier(cl::sycl::access::fence_space::local_space);\n    }\n  }\n};\n\ntemplate <typename Indices, typename InputArgType, typename KernelArgType>\nstruct TensorEvaluator<const TensorConvolutionOp<Indices, InputArgType, KernelArgType>, Eigen::SyclDevice> {\n  typedef TensorConvolutionOp<Indices, InputArgType, KernelArgType> XprType;\n\n  static const int NumDims =\n      internal::array_size<typename TensorEvaluator<InputArgType, Eigen::SyclDevice>::Dimensions>::value;\n  static const int NumKernelDims = internal::array_size<Indices>::value;\n  typedef typename XprType::Index Index;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename TensorEvaluator<KernelArgType, Eigen::SyclDevice>::Dimensions KernelDimensions;\n  typedef const Eigen::SyclDevice Device;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Eigen::SyclDevice>::type PacketReturnType;\n  typedef typename InputArgType::Scalar Scalar;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<CoeffReturnType, Eigen::SyclDevice> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n  typedef StorageMemory<const CoeffReturnType, Eigen::SyclDevice> KernelStorage;\n\n  enum {\n    IsAligned = TensorEvaluator<InputArgType, Eigen::SyclDevice>::IsAligned &\n                TensorEvaluator<KernelArgType, Eigen::SyclDevice>::IsAligned,\n    PacketAccess = false,\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<InputArgType, Eigen::SyclDevice>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  TensorEvaluator(const XprType &op, const Eigen::SyclDevice &device)\n      : m_inputImpl(op.inputExpression(), device),\n        m_kernelArg(op.kernelExpression()),\n        m_kernelImpl(op.kernelExpression(), device),\n        m_indices(op.indices()),\n        m_buf(NULL),\n        m_kernel(NULL),\n        m_local_kernel(false),\n        m_device(device) {\n    EIGEN_STATIC_ASSERT((static_cast<int>(TensorEvaluator<InputArgType, Eigen::SyclDevice>::Layout) ==\n                         static_cast<int>(TensorEvaluator<KernelArgType, Eigen::SyclDevice>::Layout)),\n                        YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    const typename TensorEvaluator<InputArgType, Eigen::SyclDevice>::Dimensions &input_dims = m_inputImpl.dimensions();\n    const typename TensorEvaluator<KernelArgType, Eigen::SyclDevice>::Dimensions &kernel_dims =\n        m_kernelImpl.dimensions();\n\n    m_dimensions = m_inputImpl.dimensions();\n    for (int i = 0; i < NumKernelDims; ++i) {\n      const Index index = op.indices()[i];\n      const Index input_dim = input_dims[index];\n      const Index kernel_dim = kernel_dims[i];\n      const Index result_dim = input_dim - kernel_dim + 1;\n      m_dimensions[index] = result_dim;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC const Dimensions &dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    preloadKernel();\n    m_inputImpl.evalSubExprsIfNeeded(NULL);\n    if (data) {\n      executeEval(data);\n      return false;\n    } else {\n      m_buf = (EvaluatorPointerType)m_device.get(\n          (Scalar *)m_device.allocate_temp(dimensions().TotalSize() * sizeof(Scalar)));\n      executeEval(m_buf);\n      return true;\n    }\n  }\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_inputImpl.cleanup();\n    if (m_buf) {\n      m_device.deallocate_temp(m_buf);\n      m_buf = NULL;\n    }\n    if (m_local_kernel) {\n      m_device.deallocate_temp(m_kernel);\n      m_local_kernel = false;\n    }\n    m_kernel = NULL;\n  }\n  /// used by sycl in order to build the sycl buffer\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Device &device() const { return m_device; }\n  /// used by sycl in order to build the sycl buffer\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EvaluatorPointerType data() const { return m_buf; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void preloadKernel() {\n    // Don't make a local copy of the kernel unless we have to (i.e. it's an\n    // expression that needs to be evaluated)\n    typename KernelStorage::Type in_place = m_kernelImpl.data();\n    if (in_place) {\n      m_kernel = in_place;\n      m_local_kernel = false;\n    } else {\n      ptrdiff_t kernel_sz = m_kernelImpl.dimensions().TotalSize() * sizeof(Scalar);\n      EvaluatorPointerType local = (EvaluatorPointerType)m_device.get((Scalar *)m_device.allocate_temp(kernel_sz));\n      typedef TensorEvalToOp<const KernelArgType> EvalTo;\n      EvalTo evalToTmp(m_device.get(local), m_kernelArg);\n      const bool PacketAccess = internal::IsVectorizable<Eigen::SyclDevice, KernelArgType>::value;\n      internal::TensorExecutor<const EvalTo, Eigen::SyclDevice, PacketAccess>::run(evalToTmp, m_device);\n      m_kernel = local;\n      m_local_kernel = true;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void executeEval(EvaluatorPointerType data) const {\n    typedef TensorEvaluator<InputArgType, Eigen::SyclDevice> InputEvaluator;\n    typedef typename InputEvaluator::Dimensions InputDims;\n    switch (NumKernelDims) {\n      case 1: {\n        const size_t numX = dimensions()[m_indices[0]];\n        const size_t numP = dimensions().TotalSize() / numX;\n        const auto input_dim = std::array<size_t, 2>{numX, numP};\n        auto global_range = cl::sycl::range<2>{};\n        auto local_range = cl::sycl::range<2>{};\n        const size_t kernel_size = m_kernelImpl.dimensions().TotalSize();\n\n        m_device.parallel_for_setup(input_dim, global_range, local_range);\n        const size_t local_memory_size = (local_range[0] + kernel_size - 1) * (local_range[1]);\n        gpu_assert(static_cast<unsigned long>(local_memory_size) <= m_device.sharedMemPerBlock());\n        const array<Index, 1> indices{{m_indices[0]}};\n        const array<Index, 1> kernel_dims{{m_kernelImpl.dimensions()[0]}};\n        internal::IndexMapper<Index, InputDims, 1, Layout> indexMapper(m_inputImpl.dimensions(), kernel_dims, indices);\n\n        typedef EigenConvolutionKernel<InputEvaluator, CoeffReturnType, Scalar, Index, InputDims,\n                                       typename KernelStorage::Type, EvaluatorPointerType, convolution_type::CONV1D>\n            ConvKernel;\n\n        m_device.template binary_kernel_launcher<CoeffReturnType, ConvKernel>(\n            m_inputImpl, m_kernel, data, cl::sycl::nd_range<2>(global_range, local_range), local_memory_size,\n            indexMapper, kernel_size, cl::sycl::range<2>(input_dim[0], input_dim[1]));\n        break;\n      }\n\n      case 2: {\n        auto kernel_index = std::array<size_t, 2>{static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 0 : 1,\n                                                  static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 1 : 0};\n        auto kernel_size = cl::sycl::range<2>{(size_t)m_kernelImpl.dimensions()[kernel_index[0]],\n                                              (size_t)m_kernelImpl.dimensions()[kernel_index[1]]};\n        const size_t numX = dimensions()[m_indices[kernel_index[0]]];\n        const size_t numY = dimensions()[m_indices[kernel_index[1]]];\n        const size_t numP = dimensions().TotalSize() / (numX * numY);\n        auto input_dim = std::array<size_t, 3>{numX, numY, numP};\n\n        auto global_range = cl::sycl::range<3>{};\n        auto local_range = cl::sycl::range<3>{};\n\n        m_device.parallel_for_setup(input_dim, global_range, local_range);\n\n        const size_t local_memory_size =\n            (local_range[0] + kernel_size[0] - 1) * (local_range[1] + kernel_size[1] - 1) * local_range[2];\n        gpu_assert(static_cast<unsigned long>(local_memory_size) <= m_device.sharedMemPerBlock());\n        const array<Index, 2> indices{{m_indices[kernel_index[0]], m_indices[kernel_index[1]]}};\n        const array<Index, 2> kernel_dims{\n            {m_kernelImpl.dimensions()[kernel_index[0]], m_kernelImpl.dimensions()[kernel_index[1]]}};\n        internal::IndexMapper<Index, InputDims, 2, Layout> indexMapper(m_inputImpl.dimensions(), kernel_dims, indices);\n        typedef EigenConvolutionKernel<InputEvaluator, CoeffReturnType, Scalar, Index, InputDims,\n                                       typename KernelStorage::Type, EvaluatorPointerType, convolution_type::CONV2D>\n            ConvKernel;\n        m_device.template binary_kernel_launcher<CoeffReturnType, ConvKernel>(\n            m_inputImpl, m_kernel, data, cl::sycl::nd_range<3>(global_range, local_range), local_memory_size,\n            indexMapper, kernel_size, cl::sycl::range<3>{input_dim[0], input_dim[1], input_dim[2]});\n        break;\n      }\n\n      case 3: {\n        auto kernel_index = std::array<size_t, 3>{static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 0 : 2,\n                                                  static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 1 : 1,\n                                                  static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 2 : 0};\n\n        auto kernel_size = cl::sycl::range<3>{(size_t)m_kernelImpl.dimensions()[kernel_index[0]],\n                                              (size_t)m_kernelImpl.dimensions()[kernel_index[1]],\n                                              (size_t)m_kernelImpl.dimensions()[kernel_index[2]]};\n\n        const size_t numX = dimensions()[m_indices[kernel_index[0]]];\n        const size_t numY = dimensions()[m_indices[kernel_index[1]]];\n        const size_t numZ = dimensions()[m_indices[kernel_index[2]]];\n        auto input_dim = std::array<size_t, 3>{numX, numY, numZ};\n        const size_t numP = dimensions().TotalSize() / (numX * numY * numZ);\n\n        const array<Index, 3> indices{\n            {m_indices[kernel_index[0]], m_indices[kernel_index[1]], m_indices[kernel_index[2]]}};\n        const array<Index, 3> kernel_dims{{m_kernelImpl.dimensions()[kernel_index[0]],\n                                           m_kernelImpl.dimensions()[kernel_index[1]],\n                                           m_kernelImpl.dimensions()[kernel_index[2]]}};\n\n        internal::IndexMapper<Index, InputDims, 3, Layout> indexMapper(m_inputImpl.dimensions(), kernel_dims, indices);\n\n        auto global_range = cl::sycl::range<3>{};\n        auto local_range = cl::sycl::range<3>{};\n\n        m_device.parallel_for_setup(input_dim, global_range, local_range);\n        auto local_memory_range = (local_range + kernel_size - 1);\n        const size_t local_memory_size = local_memory_range[0] * local_memory_range[1] * local_memory_range[2];\n\n        gpu_assert(static_cast<unsigned long>(local_memory_size) <= m_device.sharedMemPerBlock());\n        typedef EigenConvolutionKernel<InputEvaluator, CoeffReturnType, Scalar, Index, InputDims,\n                                       typename KernelStorage::Type, EvaluatorPointerType, convolution_type::CONV3D>\n            ConvKernel;\n        m_device.template binary_kernel_launcher<CoeffReturnType, ConvKernel>(\n            m_inputImpl, m_kernel, data, cl::sycl::nd_range<3>(global_range, local_range), local_memory_size,\n            indexMapper, kernel_size, cl::sycl::range<3>(input_dim[0], input_dim[1], input_dim[2]), numP);\n        break;\n      }\n\n      default: {\n        EIGEN_STATIC_ASSERT((NumKernelDims >= 1 && NumKernelDims <= 3),\n                            THIS_METHOD_IS_ONLY_FOR_OBJECTS_OF_A_SPECIFIC_SIZE);\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const {\n    eigen_assert(m_buf != NULL);\n    eigen_assert(index < m_dimensions.TotalSize());\n    return m_buf[index];\n  }\n\n  template <int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(const Index index) const {\n    eigen_assert(m_buf != NULL);\n    eigen_assert(index < m_dimensions.TotalSize());\n    return internal::ploadt<PacketReturnType, LoadMode>(m_buf + index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    // TODO(rmlarsen): FIXME: For now, this is just a copy of the CPU cost\n    // model.\n    const double kernel_size = m_kernelImpl.dimensions().TotalSize();\n    // We ignore the use of fused multiply-add.\n    const double convolve_compute_cost = TensorOpCost::AddCost<Scalar>() + TensorOpCost::MulCost<Scalar>();\n    const double firstIndex_compute_cost =\n        NumDims *\n        (2 * TensorOpCost::AddCost<Index>() + 2 * TensorOpCost::MulCost<Index>() + TensorOpCost::DivCost<Index>());\n    return TensorOpCost(0, 0, firstIndex_compute_cost, vectorized, PacketSize) +\n           kernel_size * (m_inputImpl.costPerCoeff(vectorized) + m_kernelImpl.costPerCoeff(vectorized) +\n                          TensorOpCost(0, 0, convolve_compute_cost, vectorized, PacketSize));\n  }\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_kernelImpl.bind(cgh);\n    m_inputImpl.bind(cgh);\n    m_buf.bind(cgh);\n    m_kernel.bind(cgh);\n  }\n\n private:\n  // No assignment (copies are needed by the kernels)\n  TensorEvaluator &operator=(const TensorEvaluator &);\n  TensorEvaluator<InputArgType, Eigen::SyclDevice> m_inputImpl;\n  KernelArgType m_kernelArg;\n  TensorEvaluator<KernelArgType, Eigen::SyclDevice> m_kernelImpl;\n  Indices m_indices;\n  Dimensions m_dimensions;\n  EvaluatorPointerType m_buf;\n  typename KernelStorage::Type m_kernel;\n  bool m_local_kernel;\n  const Eigen::SyclDevice EIGEN_DEVICE_REF m_device;\n};  // namespace Eigen\n\n}  // end namespace Eigen\n\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorCostModel.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Rasmus Munk Larsen <rmlarsen@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_COST_MODEL_H\n#define EIGEN_CXX11_TENSOR_TENSOR_COST_MODEL_H\n\nnamespace Eigen {\n\n/** \\class TensorEvaluator\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief A cost model used to limit the number of threads used for evaluating\n  * tensor expression.\n  *\n  */\n\n// Class storing the cost of evaluating a tensor expression in terms of the\n// estimated number of operand bytes loads, bytes stored, and compute cycles.\nclass TensorOpCost {\n public:\n  // TODO(rmlarsen): Fix the scalar op costs in Eigen proper. Even a simple\n  // model based on minimal reciprocal throughput numbers from Intel or\n  // Agner Fog's tables would be better than what is there now.\n  template <typename ArgType>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int MulCost() {\n    return internal::functor_traits<\n        internal::scalar_product_op<ArgType, ArgType> >::Cost;\n  }\n  template <typename ArgType>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int AddCost() {\n    return internal::functor_traits<internal::scalar_sum_op<ArgType> >::Cost;\n  }\n  template <typename ArgType>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int DivCost() {\n    return internal::functor_traits<\n        internal::scalar_quotient_op<ArgType, ArgType> >::Cost;\n  }\n  template <typename ArgType>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int ModCost() {\n    return internal::functor_traits<internal::scalar_mod_op<ArgType> >::Cost;\n  }\n  template <typename SrcType, typename TargetType>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int CastCost() {\n    return internal::functor_traits<\n        internal::scalar_cast_op<SrcType, TargetType> >::Cost;\n  }\n\n  EIGEN_DEVICE_FUNC\n  TensorOpCost() : bytes_loaded_(0), bytes_stored_(0), compute_cycles_(0) {}\n  EIGEN_DEVICE_FUNC\n  TensorOpCost(double bytes_loaded, double bytes_stored, double compute_cycles)\n      : bytes_loaded_(bytes_loaded),\n        bytes_stored_(bytes_stored),\n        compute_cycles_(compute_cycles) {}\n\n  EIGEN_DEVICE_FUNC\n  TensorOpCost(double bytes_loaded, double bytes_stored, double compute_cycles,\n               bool vectorized, double packet_size)\n      : bytes_loaded_(bytes_loaded),\n        bytes_stored_(bytes_stored),\n        compute_cycles_(vectorized ? compute_cycles / packet_size\n                                   : compute_cycles) {\n    eigen_assert(bytes_loaded >= 0 && (numext::isfinite)(bytes_loaded));\n    eigen_assert(bytes_stored >= 0 && (numext::isfinite)(bytes_stored));\n    eigen_assert(compute_cycles >= 0 && (numext::isfinite)(compute_cycles));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double bytes_loaded() const {\n    return bytes_loaded_;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double bytes_stored() const {\n    return bytes_stored_;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double compute_cycles() const {\n    return compute_cycles_;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double total_cost(\n      double load_cost, double store_cost, double compute_cost) const {\n    return load_cost * bytes_loaded_ + store_cost * bytes_stored_ +\n           compute_cost * compute_cycles_;\n  }\n\n  // Drop memory access component. Intended for cases when memory accesses are\n  // sequential or are completely masked by computations.\n  EIGEN_DEVICE_FUNC void dropMemoryCost() {\n    bytes_loaded_ = 0;\n    bytes_stored_ = 0;\n  }\n\n  // TODO(rmlarsen): Define min in terms of total cost, not elementwise.\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost cwiseMin(\n      const TensorOpCost& rhs) const {\n    double bytes_loaded = numext::mini(bytes_loaded_, rhs.bytes_loaded());\n    double bytes_stored = numext::mini(bytes_stored_, rhs.bytes_stored());\n    double compute_cycles = numext::mini(compute_cycles_, rhs.compute_cycles());\n    return TensorOpCost(bytes_loaded, bytes_stored, compute_cycles);\n  }\n\n  // TODO(rmlarsen): Define max in terms of total cost, not elementwise.\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost cwiseMax(\n      const TensorOpCost& rhs) const {\n    double bytes_loaded = numext::maxi(bytes_loaded_, rhs.bytes_loaded());\n    double bytes_stored = numext::maxi(bytes_stored_, rhs.bytes_stored());\n    double compute_cycles = numext::maxi(compute_cycles_, rhs.compute_cycles());\n    return TensorOpCost(bytes_loaded, bytes_stored, compute_cycles);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost& operator+=(\n      const TensorOpCost& rhs) {\n    bytes_loaded_ += rhs.bytes_loaded();\n    bytes_stored_ += rhs.bytes_stored();\n    compute_cycles_ += rhs.compute_cycles();\n    return *this;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost& operator*=(double rhs) {\n    bytes_loaded_ *= rhs;\n    bytes_stored_ *= rhs;\n    compute_cycles_ *= rhs;\n    return *this;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE friend TensorOpCost operator+(\n      TensorOpCost lhs, const TensorOpCost& rhs) {\n    lhs += rhs;\n    return lhs;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE friend TensorOpCost operator*(\n      TensorOpCost lhs, double rhs) {\n    lhs *= rhs;\n    return lhs;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE friend TensorOpCost operator*(\n      double lhs, TensorOpCost rhs) {\n    rhs *= lhs;\n    return rhs;\n  }\n\n  friend std::ostream& operator<<(std::ostream& os, const TensorOpCost& tc) {\n    return os << \"[bytes_loaded = \" << tc.bytes_loaded()\n              << \", bytes_stored = \" << tc.bytes_stored()\n              << \", compute_cycles = \" << tc.compute_cycles() << \"]\";\n  }\n\n private:\n  double bytes_loaded_;\n  double bytes_stored_;\n  double compute_cycles_;\n};\n\n// TODO(rmlarsen): Implement a policy that chooses an \"optimal\" number of theads\n// in [1:max_threads] instead of just switching multi-threading off for small\n// work units.\ntemplate <typename Device>\nclass TensorCostModel {\n public:\n  // Scaling from Eigen compute cost to device cycles.\n  static const int kDeviceCyclesPerComputeCycle = 1;\n\n // Costs in device cycles.\n  static const int kStartupCycles = 100000;\n  static const int kPerThreadCycles = 100000;\n  static const int kTaskSize = 40000;\n\n  // Returns the number of threads in [1:max_threads] to use for\n  // evaluating an expression with the given output size and cost per\n  // coefficient.\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int numThreads(\n      double output_size, const TensorOpCost& cost_per_coeff, int max_threads) {\n    double cost = totalCost(output_size, cost_per_coeff);\n    double threads = (cost - kStartupCycles) / kPerThreadCycles + 0.9;\n    // Make sure we don't invoke undefined behavior when we convert to an int.\n    threads = numext::mini<double>(threads, GenericNumTraits<int>::highest());\n    return numext::mini(max_threads,\n                        numext::maxi<int>(1, static_cast<int>(threads)));\n  }\n\n  // taskSize assesses parallel task size.\n  // Value of 1.0 means ideal parallel task size. Values < 1.0 mean that task\n  // granularity needs to be increased to mitigate parallelization overheads.\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double taskSize(\n      double output_size, const TensorOpCost& cost_per_coeff) {\n    return totalCost(output_size, cost_per_coeff) / kTaskSize;\n  }\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double totalCost(\n      double output_size, const TensorOpCost& cost_per_coeff) {\n    // Cost of memory fetches from L2 cache. 64 is typical cache line size.\n    // 11 is L2 cache latency on Haswell.\n    // We don't know whether data is in L1, L2 or L3. But we are most interested\n    // in single-threaded computational time around 100us-10ms (smaller time\n    // is too small for parallelization, larger time is not interesting\n    // either because we are probably using all available threads already).\n    // And for the target time range, L2 seems to be what matters. Data set\n    // fitting into L1 is too small to take noticeable time. Data set fitting\n    // only into L3 presumably will take more than 10ms to load and process.\n    const double kLoadCycles = 1.0 / 64 * 11;\n    const double kStoreCycles = 1.0 / 64 * 11;\n    // Scaling from Eigen compute cost to device cycles.\n    return output_size *\n        cost_per_coeff.total_cost(kLoadCycles, kStoreCycles,\n                                  kDeviceCyclesPerComputeCycle);\n  }\n};\n\n}  // namespace Eigen\n\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_COST_MODEL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorCustomOp.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CUSTOM_OP_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CUSTOM_OP_H\n\nnamespace Eigen {\n\n/** \\class TensorCustomUnaryOp\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor custom class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename CustomUnaryFunc, typename XprType>\nstruct traits<TensorCustomUnaryOp<CustomUnaryFunc, XprType> >\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::StorageKind StorageKind;\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = traits<XprType>::NumDimensions;\n  static const int Layout = traits<XprType>::Layout;\n  typedef typename traits<XprType>::PointerType PointerType;\n};\n\ntemplate<typename CustomUnaryFunc, typename XprType>\nstruct eval<TensorCustomUnaryOp<CustomUnaryFunc, XprType>, Eigen::Dense>\n{\n  typedef const TensorCustomUnaryOp<CustomUnaryFunc, XprType>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename CustomUnaryFunc, typename XprType>\nstruct nested<TensorCustomUnaryOp<CustomUnaryFunc, XprType> >\n{\n  typedef TensorCustomUnaryOp<CustomUnaryFunc, XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename CustomUnaryFunc, typename XprType>\nclass TensorCustomUnaryOp : public TensorBase<TensorCustomUnaryOp<CustomUnaryFunc, XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename internal::traits<TensorCustomUnaryOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename internal::nested<TensorCustomUnaryOp>::type Nested;\n  typedef typename internal::traits<TensorCustomUnaryOp>::StorageKind StorageKind;\n  typedef typename internal::traits<TensorCustomUnaryOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCustomUnaryOp(const XprType& expr, const CustomUnaryFunc& func)\n      : m_expr(expr), m_func(func) {}\n\n  EIGEN_DEVICE_FUNC\n  const CustomUnaryFunc& func() const { return m_func; }\n\n  EIGEN_DEVICE_FUNC\n  const typename internal::remove_all<typename XprType::Nested>::type&\n  expression() const { return m_expr; }\n\n  protected:\n    typename XprType::Nested m_expr;\n    const CustomUnaryFunc m_func;\n};\n\n\n// Eval as rvalue\ntemplate<typename CustomUnaryFunc, typename XprType, typename Device>\nstruct TensorEvaluator<const TensorCustomUnaryOp<CustomUnaryFunc, XprType>, Device>\n{\n  typedef TensorCustomUnaryOp<CustomUnaryFunc, XprType> ArgType;\n  typedef typename internal::traits<ArgType>::Index Index;\n  static const int NumDims = internal::traits<ArgType>::NumDimensions;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename internal::remove_const<typename ArgType::Scalar>::type Scalar;\n  typedef typename internal::remove_const<typename XprType::CoeffReturnType>::type CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef typename Eigen::internal::traits<XprType>::PointerType TensorPointerType;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<XprType, Device>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const ArgType& op, const Device& device)\n      : m_op(op), m_device(device), m_result(NULL)\n  {\n    m_dimensions = op.func().dimensions(op.expression());\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    if (data) {\n      evalTo(data);\n      return false;\n    } else {\n      m_result = static_cast<EvaluatorPointerType>(m_device.get( (CoeffReturnType*)\n          m_device.allocate_temp(dimensions().TotalSize() * sizeof(Scalar))));\n      evalTo(m_result);\n      return true;\n    }\n  }\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    if (m_result) {\n      m_device.deallocate_temp(m_result);\n      m_result = NULL;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const {\n    return m_result[index];\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC PacketReturnType packet(Index index) const {\n    return internal::ploadt<PacketReturnType, LoadMode>(m_result + index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    // TODO(rmlarsen): Extend CustomOp API to return its cost estimate.\n    return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return m_result; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_result.bind(cgh);\n  }\n#endif\n\n protected:\n  void evalTo(EvaluatorPointerType data) {\n    TensorMap<Tensor<CoeffReturnType, NumDims, Layout, Index> > result(m_device.get(data), m_dimensions);\n    m_op.func().eval(m_op.expression(), result, m_device);\n  }\n\n  Dimensions m_dimensions;\n  const ArgType m_op;\n  const Device EIGEN_DEVICE_REF m_device;\n  EvaluatorPointerType m_result;\n};\n\n\n\n/** \\class TensorCustomBinaryOp\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor custom class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename CustomBinaryFunc, typename LhsXprType, typename RhsXprType>\nstruct traits<TensorCustomBinaryOp<CustomBinaryFunc, LhsXprType, RhsXprType> >\n{\n  typedef typename internal::promote_storage_type<typename LhsXprType::Scalar,\n                                                  typename RhsXprType::Scalar>::ret Scalar;\n  typedef typename internal::promote_storage_type<typename LhsXprType::CoeffReturnType,\n                                                  typename RhsXprType::CoeffReturnType>::ret CoeffReturnType;\n  typedef typename promote_storage_type<typename traits<LhsXprType>::StorageKind,\n                                        typename traits<RhsXprType>::StorageKind>::ret StorageKind;\n  typedef typename promote_index_type<typename traits<LhsXprType>::Index,\n                                      typename traits<RhsXprType>::Index>::type Index;\n  typedef typename LhsXprType::Nested LhsNested;\n  typedef typename RhsXprType::Nested RhsNested;\n  typedef typename remove_reference<LhsNested>::type _LhsNested;\n  typedef typename remove_reference<RhsNested>::type _RhsNested;\n  static const int NumDimensions = traits<LhsXprType>::NumDimensions;\n  static const int Layout = traits<LhsXprType>::Layout;\n  typedef typename conditional<Pointer_type_promotion<typename LhsXprType::Scalar, Scalar>::val,\n                                typename traits<LhsXprType>::PointerType, typename traits<RhsXprType>::PointerType>::type PointerType;\n};\n\ntemplate<typename CustomBinaryFunc, typename LhsXprType, typename RhsXprType>\nstruct eval<TensorCustomBinaryOp<CustomBinaryFunc, LhsXprType, RhsXprType>, Eigen::Dense>\n{\n  typedef const TensorCustomBinaryOp<CustomBinaryFunc, LhsXprType, RhsXprType>& type;\n};\n\ntemplate<typename CustomBinaryFunc, typename LhsXprType, typename RhsXprType>\nstruct nested<TensorCustomBinaryOp<CustomBinaryFunc, LhsXprType, RhsXprType> >\n{\n  typedef TensorCustomBinaryOp<CustomBinaryFunc, LhsXprType, RhsXprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename CustomBinaryFunc, typename LhsXprType, typename RhsXprType>\nclass TensorCustomBinaryOp : public TensorBase<TensorCustomBinaryOp<CustomBinaryFunc, LhsXprType, RhsXprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename internal::traits<TensorCustomBinaryOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename internal::traits<TensorCustomBinaryOp>::CoeffReturnType CoeffReturnType;\n  typedef typename internal::nested<TensorCustomBinaryOp>::type Nested;\n  typedef typename internal::traits<TensorCustomBinaryOp>::StorageKind StorageKind;\n  typedef typename internal::traits<TensorCustomBinaryOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCustomBinaryOp(const LhsXprType& lhs, const RhsXprType& rhs, const CustomBinaryFunc& func)\n\n      : m_lhs_xpr(lhs), m_rhs_xpr(rhs), m_func(func) {}\n\n  EIGEN_DEVICE_FUNC\n  const CustomBinaryFunc& func() const { return m_func; }\n\n  EIGEN_DEVICE_FUNC\n  const typename internal::remove_all<typename LhsXprType::Nested>::type&\n  lhsExpression() const { return m_lhs_xpr; }\n\n  EIGEN_DEVICE_FUNC\n  const typename internal::remove_all<typename RhsXprType::Nested>::type&\n  rhsExpression() const { return m_rhs_xpr; }\n\n  protected:\n    typename LhsXprType::Nested m_lhs_xpr;\n    typename RhsXprType::Nested m_rhs_xpr;\n    const CustomBinaryFunc m_func;\n};\n\n\n// Eval as rvalue\ntemplate<typename CustomBinaryFunc, typename LhsXprType, typename RhsXprType, typename Device>\nstruct TensorEvaluator<const TensorCustomBinaryOp<CustomBinaryFunc, LhsXprType, RhsXprType>, Device>\n{\n  typedef TensorCustomBinaryOp<CustomBinaryFunc, LhsXprType, RhsXprType> XprType;\n  typedef typename internal::traits<XprType>::Index Index;\n  static const int NumDims = internal::traits<XprType>::NumDimensions;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename internal::remove_const<typename XprType::CoeffReturnType>::type CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n\n  typedef typename Eigen::internal::traits<XprType>::PointerType TensorPointerType;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<LhsXprType, Device>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_op(op), m_device(device), m_result(NULL)\n  {\n    m_dimensions = op.func().dimensions(op.lhsExpression(), op.rhsExpression());\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    if (data) {\n      evalTo(data);\n      return false;\n    } else {\n      m_result = static_cast<EvaluatorPointerType>(m_device.get( (CoeffReturnType*)\n        m_device.allocate_temp(dimensions().TotalSize() * sizeof(CoeffReturnType))));\n      evalTo(m_result);\n      return true;\n    }\n  }\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    if (m_result != NULL) {\n      m_device.deallocate_temp(m_result);\n      m_result = NULL;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const {\n    return m_result[index];\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC PacketReturnType packet(Index index) const {\n    return internal::ploadt<PacketReturnType, LoadMode>(m_result + index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    // TODO(rmlarsen): Extend CustomOp API to return its cost estimate.\n    return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return m_result; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_result.bind(cgh);\n  }\n#endif\n\n protected:\n  void evalTo(EvaluatorPointerType data) {\n    TensorMap<Tensor<CoeffReturnType, NumDims, Layout> > result(m_device.get(data), m_dimensions);\n    m_op.func().eval(m_op.lhsExpression(), m_op.rhsExpression(), result, m_device);\n  }\n\n  Dimensions m_dimensions;\n  const XprType m_op;\n  const Device EIGEN_DEVICE_REF m_device;\n  EvaluatorPointerType m_result;\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_CUSTOM_OP_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDevice.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_DEVICE_H\n#define EIGEN_CXX11_TENSOR_TENSOR_DEVICE_H\n\nnamespace Eigen {\n\n/** \\class TensorDevice\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Pseudo expression providing an operator = that will evaluate its argument\n  * on the specified computing 'device' (GPU, thread pool, ...)\n  *\n  * Example:\n  *    C.device(EIGEN_GPU) = A + B;\n  *\n  * Todo: operator *= and /=.\n  */\n\ntemplate <typename ExpressionType, typename DeviceType> class TensorDevice {\n  public:\n    TensorDevice(const DeviceType& device, ExpressionType& expression) : m_device(device), m_expression(expression) {}\n\n    EIGEN_DEFAULT_COPY_CONSTRUCTOR(TensorDevice)\n\n    template<typename OtherDerived>\n    EIGEN_STRONG_INLINE TensorDevice& operator=(const OtherDerived& other) {\n      typedef TensorAssignOp<ExpressionType, const OtherDerived> Assign;\n      Assign assign(m_expression, other);\n      internal::TensorExecutor<const Assign, DeviceType>::run(assign, m_device);\n      return *this;\n    }\n\n    template<typename OtherDerived>\n    EIGEN_STRONG_INLINE TensorDevice& operator+=(const OtherDerived& other) {\n      typedef typename OtherDerived::Scalar Scalar;\n      typedef TensorCwiseBinaryOp<internal::scalar_sum_op<Scalar>, const ExpressionType, const OtherDerived> Sum;\n      Sum sum(m_expression, other);\n      typedef TensorAssignOp<ExpressionType, const Sum> Assign;\n      Assign assign(m_expression, sum);\n      internal::TensorExecutor<const Assign, DeviceType>::run(assign, m_device);\n      return *this;\n    }\n\n    template<typename OtherDerived>\n    EIGEN_STRONG_INLINE TensorDevice& operator-=(const OtherDerived& other) {\n      typedef typename OtherDerived::Scalar Scalar;\n      typedef TensorCwiseBinaryOp<internal::scalar_difference_op<Scalar>, const ExpressionType, const OtherDerived> Difference;\n      Difference difference(m_expression, other);\n      typedef TensorAssignOp<ExpressionType, const Difference> Assign;\n      Assign assign(m_expression, difference);\n      internal::TensorExecutor<const Assign, DeviceType>::run(assign, m_device);\n      return *this;\n    }\n\n  protected:\n    const DeviceType& m_device;\n    ExpressionType& m_expression;\n};\n\n/** \\class TensorAsyncDevice\n * \\ingroup CXX11_Tensor_Module\n *\n * \\brief Pseudo expression providing an operator = that will evaluate its\n * argument asynchronously on the specified device. Currently only\n * ThreadPoolDevice implements proper asynchronous execution, while the default\n * and GPU devices just run the expression synchronously and call m_done() on\n * completion..\n *\n * Example:\n *    auto done = []() { ... expression evaluation done ... };\n *    C.device(thread_pool_device, std::move(done)) = A + B;\n */\n\ntemplate <typename ExpressionType, typename DeviceType, typename DoneCallback>\nclass TensorAsyncDevice {\n public:\n  TensorAsyncDevice(const DeviceType& device, ExpressionType& expression,\n                    DoneCallback done)\n      : m_device(device), m_expression(expression), m_done(std::move(done)) {}\n\n  template <typename OtherDerived>\n  EIGEN_STRONG_INLINE TensorAsyncDevice& operator=(const OtherDerived& other) {\n    typedef TensorAssignOp<ExpressionType, const OtherDerived> Assign;\n    typedef internal::TensorExecutor<const Assign, DeviceType> Executor;\n\n    Assign assign(m_expression, other);\n    Executor::run(assign, m_device);\n    m_done();\n\n    return *this;\n  }\n\n protected:\n  const DeviceType& m_device;\n  ExpressionType& m_expression;\n  DoneCallback m_done;\n};\n\n\n#ifdef EIGEN_USE_THREADS\ntemplate <typename ExpressionType, typename DoneCallback>\nclass TensorAsyncDevice<ExpressionType, ThreadPoolDevice, DoneCallback> {\n public:\n  TensorAsyncDevice(const ThreadPoolDevice& device, ExpressionType& expression,\n                    DoneCallback done)\n      : m_device(device), m_expression(expression), m_done(std::move(done)) {}\n\n  template <typename OtherDerived>\n  EIGEN_STRONG_INLINE TensorAsyncDevice& operator=(const OtherDerived& other) {\n    typedef TensorAssignOp<ExpressionType, const OtherDerived> Assign;\n    typedef internal::TensorAsyncExecutor<const Assign, ThreadPoolDevice, DoneCallback> Executor;\n\n    // WARNING: After assignment 'm_done' callback will be in undefined state.\n    Assign assign(m_expression, other);\n    Executor::runAsync(assign, m_device, std::move(m_done));\n\n    return *this;\n  }\n\n protected:\n  const ThreadPoolDevice& m_device;\n  ExpressionType& m_expression;\n  DoneCallback m_done;\n};\n#endif\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_DEVICE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceCuda.h",
    "content": "\n#if defined(__clang__) || defined(__GNUC__)\n#warning \"Deprecated header file, please either include the main Eigen/CXX11/Tensor header or the respective TensorDeviceGpu.h file\"\n#endif\n\n#include \"TensorDeviceGpu.h\"\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceDefault.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_DEVICE_DEFAULT_H\n#define EIGEN_CXX11_TENSOR_TENSOR_DEVICE_DEFAULT_H\n\n\nnamespace Eigen {\n\n// Default device for the machine (typically a single cpu core)\nstruct DefaultDevice {\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void* allocate(size_t num_bytes) const {\n    return internal::aligned_malloc(num_bytes);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void deallocate(void* buffer) const {\n    internal::aligned_free(buffer);\n  }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void* allocate_temp(size_t num_bytes) const {\n    return allocate(num_bytes);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void deallocate_temp(void* buffer) const {\n    deallocate(buffer);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memcpy(void* dst, const void* src, size_t n) const {\n    ::memcpy(dst, src, n);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memcpyHostToDevice(void* dst, const void* src, size_t n) const {\n    memcpy(dst, src, n);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memcpyDeviceToHost(void* dst, const void* src, size_t n) const {\n    memcpy(dst, src, n);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memset(void* buffer, int c, size_t n) const {\n    ::memset(buffer, c, n);\n  }\n  template<typename T>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void fill(T* begin, T* end, const T& value) const {\n#ifdef EIGEN_GPU_COMPILE_PHASE\n    // std::fill is not a device function, so resort to simple loop.\n    for (T* it = begin; it != end; ++it) {\n      *it = value;\n    }\n#else\n    std::fill(begin, end, value);\n#endif\n  }\n  template<typename Type>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Type get(Type data) const { \n    return data;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE size_t numThreads() const {\n#if !defined(EIGEN_GPU_COMPILE_PHASE)\n    // Running on the host CPU\n    return 1;\n#elif defined(EIGEN_HIP_DEVICE_COMPILE)\n    // Running on a HIP device\n    return 64;\n#else\n    // Running on a CUDA device\n    return 32;\n#endif\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE size_t firstLevelCacheSize() const {\n#if !defined(EIGEN_GPU_COMPILE_PHASE) && !defined(SYCL_DEVICE_ONLY)\n    // Running on the host CPU\n    return l1CacheSize();\n#elif defined(EIGEN_HIP_DEVICE_COMPILE)\n    // Running on a HIP device\n    return 48*1024; // FIXME : update this number for HIP\n#else\n    // Running on a CUDA device, return the amount of shared memory available.\n    return 48*1024;\n#endif\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE size_t lastLevelCacheSize() const {\n#if !defined(EIGEN_GPU_COMPILE_PHASE) && !defined(SYCL_DEVICE_ONLY)\n    // Running single threaded on the host CPU\n    return l3CacheSize();\n#elif defined(EIGEN_HIP_DEVICE_COMPILE)\n    // Running on a HIP device\n    return firstLevelCacheSize(); // FIXME : update this number for HIP\n#else\n    // Running on a CUDA device\n    return firstLevelCacheSize();\n#endif\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int majorDeviceVersion() const {\n#if !defined(EIGEN_GPU_COMPILE_PHASE)\n    // Running single threaded on the host CPU\n    // Should return an enum that encodes the ISA supported by the CPU\n    return 1;\n#elif defined(EIGEN_HIP_DEVICE_COMPILE)\n    // Running on a HIP device\n    // return 1 as major for HIP\n    return 1;\n#else\n    // Running on a CUDA device\n    return EIGEN_CUDA_ARCH / 100;\n#endif\n  }\n};\n\n}  // namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_DEVICE_DEFAULT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceGpu.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#if defined(EIGEN_USE_GPU) && !defined(EIGEN_CXX11_TENSOR_TENSOR_DEVICE_GPU_H)\n#define EIGEN_CXX11_TENSOR_TENSOR_DEVICE_GPU_H\n\n// This header file container defines fo gpu* macros which will resolve to\n// their equivalent hip* or cuda* versions depending on the compiler in use\n// A separate header (included at the end of this file) will undefine all \n#include \"TensorGpuHipCudaDefines.h\"\n\nnamespace Eigen {\n\nstatic const int kGpuScratchSize = 1024;\n\n// This defines an interface that GPUDevice can take to use\n// HIP / CUDA streams underneath.\nclass StreamInterface {\n public:\n  virtual ~StreamInterface() {}\n\n  virtual const gpuStream_t& stream() const = 0;\n  virtual const gpuDeviceProp_t& deviceProperties() const = 0;\n\n  // Allocate memory on the actual device where the computation will run\n  virtual void* allocate(size_t num_bytes) const = 0;\n  virtual void deallocate(void* buffer) const = 0;\n\n  // Return a scratchpad buffer of size 1k\n  virtual void* scratchpad() const = 0;\n\n  // Return a semaphore. The semaphore is initially initialized to 0, and\n  // each kernel using it is responsible for resetting to 0 upon completion\n  // to maintain the invariant that the semaphore is always equal to 0 upon\n  // each kernel start.\n  virtual unsigned int* semaphore() const = 0;\n};\n\nclass GpuDeviceProperties {\n public:\n  GpuDeviceProperties() : \n      initialized_(false), first_(true), device_properties_(nullptr) {}\n \n  ~GpuDeviceProperties() {\n    if (device_properties_) {\n      delete[] device_properties_;\n    }\n  }\n  \n  EIGEN_STRONG_INLINE const gpuDeviceProp_t& get(int device) const {\n    return device_properties_[device];\n  }\n\n  EIGEN_STRONG_INLINE bool isInitialized() const {\n    return initialized_;\n  }\n\n  void initialize() {\n    if (!initialized_) {\n      // Attempts to ensure proper behavior in the case of multiple threads\n      // calling this function simultaneously. This would be trivial to\n      // implement if we could use std::mutex, but unfortunately mutex don't\n      // compile with nvcc, so we resort to atomics and thread fences instead.\n      // Note that if the caller uses a compiler that doesn't support c++11 we\n      // can't ensure that the initialization is thread safe.\n      if (first_.exchange(false)) {\n        // We're the first thread to reach this point.\n        int num_devices;\n        gpuError_t status = gpuGetDeviceCount(&num_devices);\n        if (status != gpuSuccess) {\n          std::cerr << \"Failed to get the number of GPU devices: \"\n                    << gpuGetErrorString(status)\n                    << std::endl;\n          gpu_assert(status == gpuSuccess);\n        }\n        device_properties_ = new gpuDeviceProp_t[num_devices];\n        for (int i = 0; i < num_devices; ++i) {\n          status = gpuGetDeviceProperties(&device_properties_[i], i);\n          if (status != gpuSuccess) {\n            std::cerr << \"Failed to initialize GPU device #\"\n                      << i\n                      << \": \"\n                      << gpuGetErrorString(status)\n                      << std::endl;\n            gpu_assert(status == gpuSuccess);\n          }\n        }\n\n        std::atomic_thread_fence(std::memory_order_release);\n        initialized_ = true;\n      } else {\n        // Wait for the other thread to inititialize the properties.\n        while (!initialized_) {\n          std::atomic_thread_fence(std::memory_order_acquire);\n          std::this_thread::sleep_for(std::chrono::milliseconds(1000));\n        }\n      }\n    }\n  }\n\n private:\n  volatile bool initialized_;\n  std::atomic<bool> first_;\n  gpuDeviceProp_t* device_properties_;\n};\n\nEIGEN_ALWAYS_INLINE const GpuDeviceProperties& GetGpuDeviceProperties() {\n  static GpuDeviceProperties* deviceProperties = new GpuDeviceProperties();\n  if (!deviceProperties->isInitialized()) {\n    deviceProperties->initialize();\n  }\n  return *deviceProperties;\n}\n\nEIGEN_ALWAYS_INLINE const gpuDeviceProp_t& GetGpuDeviceProperties(int device) {\n  return GetGpuDeviceProperties().get(device);\n}\n\nstatic const gpuStream_t default_stream = gpuStreamDefault;\n\nclass GpuStreamDevice : public StreamInterface {\n public:\n  // Use the default stream on the current device\n  GpuStreamDevice() : stream_(&default_stream), scratch_(NULL), semaphore_(NULL) {\n    gpuGetDevice(&device_);\n  }\n  // Use the default stream on the specified device\n  GpuStreamDevice(int device) : stream_(&default_stream), device_(device), scratch_(NULL), semaphore_(NULL) {}\n  // Use the specified stream. Note that it's the\n  // caller responsibility to ensure that the stream can run on\n  // the specified device. If no device is specified the code\n  // assumes that the stream is associated to the current gpu device.\n  GpuStreamDevice(const gpuStream_t* stream, int device = -1)\n      : stream_(stream), device_(device), scratch_(NULL), semaphore_(NULL) {\n    if (device < 0) {\n      gpuGetDevice(&device_);\n    } else {\n      int num_devices;\n      gpuError_t err = gpuGetDeviceCount(&num_devices);\n      EIGEN_UNUSED_VARIABLE(err)\n      gpu_assert(err == gpuSuccess);\n      gpu_assert(device < num_devices);\n      device_ = device;\n    }\n  }\n\n  virtual ~GpuStreamDevice() {\n    if (scratch_) {\n      deallocate(scratch_);\n    }\n  }\n\n  const gpuStream_t& stream() const { return *stream_; }\n  const gpuDeviceProp_t& deviceProperties() const {\n    return GetGpuDeviceProperties(device_);\n  }\n  virtual void* allocate(size_t num_bytes) const {\n    gpuError_t err = gpuSetDevice(device_);\n    EIGEN_UNUSED_VARIABLE(err)\n    gpu_assert(err == gpuSuccess);\n    void* result;\n    err = gpuMalloc(&result, num_bytes);\n    gpu_assert(err == gpuSuccess);\n    gpu_assert(result != NULL);\n    return result;\n  }\n  virtual void deallocate(void* buffer) const {\n    gpuError_t err = gpuSetDevice(device_);\n    EIGEN_UNUSED_VARIABLE(err)\n    gpu_assert(err == gpuSuccess);\n    gpu_assert(buffer != NULL);\n    err = gpuFree(buffer);\n    gpu_assert(err == gpuSuccess);\n  }\n\n  virtual void* scratchpad() const {\n    if (scratch_ == NULL) {\n      scratch_ = allocate(kGpuScratchSize + sizeof(unsigned int));\n    }\n    return scratch_;\n  }\n\n  virtual unsigned int* semaphore() const {\n    if (semaphore_ == NULL) {\n      char* scratch = static_cast<char*>(scratchpad()) + kGpuScratchSize;\n      semaphore_ = reinterpret_cast<unsigned int*>(scratch);\n      gpuError_t err = gpuMemsetAsync(semaphore_, 0, sizeof(unsigned int), *stream_);\n      EIGEN_UNUSED_VARIABLE(err)\n      gpu_assert(err == gpuSuccess);\n    }\n    return semaphore_;\n  }\n\n private:\n  const gpuStream_t* stream_;\n  int device_;\n  mutable void* scratch_;\n  mutable unsigned int* semaphore_;\n};\n\nstruct GpuDevice {\n  // The StreamInterface is not owned: the caller is\n  // responsible for its initialization and eventual destruction.\n  explicit GpuDevice(const StreamInterface* stream) : stream_(stream), max_blocks_(INT_MAX) {\n    eigen_assert(stream);\n  }\n  explicit GpuDevice(const StreamInterface* stream, int num_blocks) : stream_(stream), max_blocks_(num_blocks) {\n    eigen_assert(stream);\n  }\n  // TODO(bsteiner): This is an internal API, we should not expose it.\n  EIGEN_STRONG_INLINE const gpuStream_t& stream() const {\n    return stream_->stream();\n  }\n\n  EIGEN_STRONG_INLINE void* allocate(size_t num_bytes) const {\n    return stream_->allocate(num_bytes);\n  }\n\n  EIGEN_STRONG_INLINE void deallocate(void* buffer) const {\n    stream_->deallocate(buffer);\n  }\n\n  EIGEN_STRONG_INLINE void* allocate_temp(size_t num_bytes) const {\n    return stream_->allocate(num_bytes);\n  }\n\n  EIGEN_STRONG_INLINE void deallocate_temp(void* buffer) const {\n    stream_->deallocate(buffer);\n  }\n\n  template<typename Type>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Type get(Type data) const { \n    return data;\n  }\n\n  EIGEN_STRONG_INLINE void* scratchpad() const {\n    return stream_->scratchpad();\n  }\n\n  EIGEN_STRONG_INLINE unsigned int* semaphore() const {\n    return stream_->semaphore();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memcpy(void* dst, const void* src, size_t n) const {\n#ifndef EIGEN_GPU_COMPILE_PHASE\n    gpuError_t err = gpuMemcpyAsync(dst, src, n, gpuMemcpyDeviceToDevice,\n                                      stream_->stream());\n    EIGEN_UNUSED_VARIABLE(err)\n    gpu_assert(err == gpuSuccess);\n#else\n    EIGEN_UNUSED_VARIABLE(dst);\n    EIGEN_UNUSED_VARIABLE(src);\n    EIGEN_UNUSED_VARIABLE(n);\n    eigen_assert(false && \"The default device should be used instead to generate kernel code\");\n#endif\n  }\n\n  EIGEN_STRONG_INLINE void memcpyHostToDevice(void* dst, const void* src, size_t n) const {\n    gpuError_t err =\n        gpuMemcpyAsync(dst, src, n, gpuMemcpyHostToDevice, stream_->stream());\n    EIGEN_UNUSED_VARIABLE(err)\n    gpu_assert(err == gpuSuccess);\n  }\n\n  EIGEN_STRONG_INLINE void memcpyDeviceToHost(void* dst, const void* src, size_t n) const {\n    gpuError_t err =\n        gpuMemcpyAsync(dst, src, n, gpuMemcpyDeviceToHost, stream_->stream());\n    EIGEN_UNUSED_VARIABLE(err)\n    gpu_assert(err == gpuSuccess);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memset(void* buffer, int c, size_t n) const {\n#ifndef EIGEN_GPU_COMPILE_PHASE\n    gpuError_t err = gpuMemsetAsync(buffer, c, n, stream_->stream());\n    EIGEN_UNUSED_VARIABLE(err)\n    gpu_assert(err == gpuSuccess);\n#else\n  EIGEN_UNUSED_VARIABLE(buffer)\n  EIGEN_UNUSED_VARIABLE(c)\n  EIGEN_UNUSED_VARIABLE(n)\n  eigen_assert(false && \"The default device should be used instead to generate kernel code\");\n#endif\n  }\n\n  template<typename T>\n  EIGEN_STRONG_INLINE void fill(T* begin, T* end, const T& value) const {\n#ifndef EIGEN_GPU_COMPILE_PHASE\n    const size_t count = end - begin;\n    // Split value into bytes and run memset with stride.\n    const int value_size = sizeof(value);\n    char* buffer = (char*)begin;\n    char* value_bytes = (char*)(&value);\n    gpuError_t err;\n    EIGEN_UNUSED_VARIABLE(err)\n    \n    // If all value bytes are equal, then a single memset can be much faster.\n    bool use_single_memset = true;\n    for (int i=1; i<value_size; ++i) {\n      if (value_bytes[i] != value_bytes[0]) {\n        use_single_memset = false;\n      } \n    }\n    \n    if (use_single_memset) {\n      err = gpuMemsetAsync(buffer, value_bytes[0], count * sizeof(T), stream_->stream());\n      gpu_assert(err == gpuSuccess);\n    } else {\n      for (int b=0; b<value_size; ++b) {\n        err = gpuMemset2DAsync(buffer+b, value_size, value_bytes[b], 1, count, stream_->stream());\n        gpu_assert(err == gpuSuccess);\n      }\n    }\n#else\n    EIGEN_UNUSED_VARIABLE(begin)\n    EIGEN_UNUSED_VARIABLE(end)\n    EIGEN_UNUSED_VARIABLE(value)\n    eigen_assert(false && \"The default device should be used instead to generate kernel code\");\n#endif\n  }\n\n  EIGEN_STRONG_INLINE size_t numThreads() const {\n    // FIXME\n    return 32;\n  }\n\n  EIGEN_STRONG_INLINE size_t firstLevelCacheSize() const {\n    // FIXME\n    return 48*1024;\n  }\n\n  EIGEN_STRONG_INLINE size_t lastLevelCacheSize() const {\n    // We won't try to take advantage of the l2 cache for the time being, and\n    // there is no l3 cache on hip/cuda devices.\n    return firstLevelCacheSize();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void synchronize() const {\n#ifndef EIGEN_GPU_COMPILE_PHASE\n    gpuError_t err = gpuStreamSynchronize(stream_->stream());\n    if (err != gpuSuccess) {\n      std::cerr << \"Error detected in GPU stream: \"\n                << gpuGetErrorString(err)\n                << std::endl;\n      gpu_assert(err == gpuSuccess);\n    }\n#else\n    gpu_assert(false && \"The default device should be used instead to generate kernel code\");\n#endif\n  }\n\n  EIGEN_STRONG_INLINE int getNumGpuMultiProcessors() const {\n    return stream_->deviceProperties().multiProcessorCount;\n  }\n  EIGEN_STRONG_INLINE int maxGpuThreadsPerBlock() const {\n    return stream_->deviceProperties().maxThreadsPerBlock;\n  }\n  EIGEN_STRONG_INLINE int maxGpuThreadsPerMultiProcessor() const {\n    return stream_->deviceProperties().maxThreadsPerMultiProcessor;\n  }\n  EIGEN_STRONG_INLINE int sharedMemPerBlock() const {\n    return stream_->deviceProperties().sharedMemPerBlock;\n  }\n  EIGEN_STRONG_INLINE int majorDeviceVersion() const {\n    return stream_->deviceProperties().major;\n  }\n  EIGEN_STRONG_INLINE int minorDeviceVersion() const {\n    return stream_->deviceProperties().minor;\n  }\n\n  EIGEN_STRONG_INLINE int maxBlocks() const {\n    return max_blocks_;\n  }\n\n  // This function checks if the GPU runtime recorded an error for the\n  // underlying stream device.\n  inline bool ok() const {\n#ifdef EIGEN_GPUCC\n    gpuError_t error = gpuStreamQuery(stream_->stream());\n    return (error == gpuSuccess) || (error == gpuErrorNotReady);\n#else\n    return false;\n#endif\n  }\n\n private:\n  const StreamInterface* stream_;\n  int max_blocks_;\n};\n\n#if defined(EIGEN_HIPCC)\n\n#define LAUNCH_GPU_KERNEL(kernel, gridsize, blocksize, sharedmem, device, ...)             \\\n  hipLaunchKernelGGL(kernel, dim3(gridsize), dim3(blocksize), (sharedmem), (device).stream(), __VA_ARGS__); \\\n  gpu_assert(hipGetLastError() == hipSuccess);\n\n#else\n \n#define LAUNCH_GPU_KERNEL(kernel, gridsize, blocksize, sharedmem, device, ...)             \\\n  (kernel) <<< (gridsize), (blocksize), (sharedmem), (device).stream() >>> (__VA_ARGS__);   \\\n  gpu_assert(cudaGetLastError() == cudaSuccess);\n\n#endif\n \n// FIXME: Should be device and kernel specific.\n#ifdef EIGEN_GPUCC\nstatic EIGEN_DEVICE_FUNC inline void setGpuSharedMemConfig(gpuSharedMemConfig config) {\n#ifndef EIGEN_GPU_COMPILE_PHASE\n  gpuError_t status = gpuDeviceSetSharedMemConfig(config);\n  EIGEN_UNUSED_VARIABLE(status)\n  gpu_assert(status == gpuSuccess);\n#else\n  EIGEN_UNUSED_VARIABLE(config)\n#endif\n}\n#endif\n\n}  // end namespace Eigen\n\n// undefine all the gpu* macros we defined at the beginning of the file\n#include \"TensorGpuHipCudaUndefines.h\"\n\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_DEVICE_GPU_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceSycl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#if defined(EIGEN_USE_SYCL) && !defined(EIGEN_CXX11_TENSOR_TENSOR_DEVICE_SYCL_H)\n#define EIGEN_CXX11_TENSOR_TENSOR_DEVICE_SYCL_H\n#include <unordered_set>\n\nnamespace Eigen {\n\nnamespace TensorSycl {\nnamespace internal {\n\n/// Cache all the device information needed\nstruct SyclDeviceInfo {\n  SyclDeviceInfo(cl::sycl::queue queue)\n      : local_mem_type(\n            queue.get_device()\n                .template get_info<cl::sycl::info::device::local_mem_type>()),\n        max_work_item_sizes(\n            queue.get_device()\n                .template get_info<\n                    cl::sycl::info::device::max_work_item_sizes>()),\n        max_mem_alloc_size(\n            queue.get_device()\n                .template get_info<\n                    cl::sycl::info::device::max_mem_alloc_size>()),\n        max_compute_units(queue.get_device()\n                              .template get_info<\n                                  cl::sycl::info::device::max_compute_units>()),\n        max_work_group_size(\n            queue.get_device()\n                .template get_info<\n                    cl::sycl::info::device::max_work_group_size>()),\n        local_mem_size(\n            queue.get_device()\n                .template get_info<cl::sycl::info::device::local_mem_size>()),\n        platform_name(queue.get_device()\n                          .get_platform()\n                          .template get_info<cl::sycl::info::platform::name>()),\n        device_name(queue.get_device()\n                        .template get_info<cl::sycl::info::device::name>()),\n        device_vendor(\n            queue.get_device()\n                .template get_info<cl::sycl::info::device::vendor>()) {}\n\n  cl::sycl::info::local_mem_type local_mem_type;\n  cl::sycl::id<3> max_work_item_sizes;\n  unsigned long max_mem_alloc_size;\n  unsigned long max_compute_units;\n  unsigned long max_work_group_size;\n  size_t local_mem_size;\n  std::string platform_name;\n  std::string device_name;\n  std::string device_vendor;\n};\n\n}  // end namespace internal\n}  // end namespace TensorSycl\n\ntypedef TensorSycl::internal::buffer_data_type_t buffer_scalar_t;\n// All devices (even AMD CPU with intel OpenCL runtime) that support OpenCL and\n// can consume SPIR or SPIRV can use the Eigen SYCL backend and consequently\n// TensorFlow via the Eigen SYCL Backend.\nEIGEN_STRONG_INLINE auto get_sycl_supported_devices()\n    -> decltype(cl::sycl::device::get_devices()) {\n#ifdef EIGEN_SYCL_USE_DEFAULT_SELECTOR\n  return {cl::sycl::device(cl::sycl::default_selector())};\n#else\n  std::vector<cl::sycl::device> supported_devices;\n  auto platform_list = cl::sycl::platform::get_platforms();\n  for (const auto &platform : platform_list) {\n    auto device_list = platform.get_devices();\n    auto platform_name =\n        platform.template get_info<cl::sycl::info::platform::name>();\n    std::transform(platform_name.begin(), platform_name.end(),\n                   platform_name.begin(), ::tolower);\n    for (const auto &device : device_list) {\n      auto vendor = device.template get_info<cl::sycl::info::device::vendor>();\n      std::transform(vendor.begin(), vendor.end(), vendor.begin(), ::tolower);\n      bool unsupported_condition =\n          (device.is_cpu() && platform_name.find(\"amd\") != std::string::npos &&\n           vendor.find(\"apu\") == std::string::npos) ||\n          (platform_name.find(\"experimental\") != std::string::npos) ||\n          device.is_host();\n      if (!unsupported_condition) {\n        supported_devices.push_back(device);\n      }\n    }\n  }\n  return supported_devices;\n#endif\n}\n\nclass QueueInterface {\n public:\n  /// Creating device by using cl::sycl::selector or cl::sycl::device.\n  template <typename DeviceOrSelector>\n  explicit QueueInterface(\n      const DeviceOrSelector &dev_or_sel, cl::sycl::async_handler handler,\n      unsigned num_threads = std::thread::hardware_concurrency())\n      : m_queue(dev_or_sel, handler),\n#ifdef EIGEN_SYCL_USE_PROGRAM_CLASS\n        m_prog(m_queue.get_context(), get_sycl_supported_devices()),\n#endif\n        m_thread_pool(num_threads),\n        m_device_info(m_queue) {\n#ifdef EIGEN_SYCL_USE_PROGRAM_CLASS\n    m_prog.build_with_kernel_type<DeviceOrSelector>();\n    auto f = [&](cl::sycl::handler &cgh) {\n      cgh.single_task<DeviceOrSelector>(m_prog.get_kernel<DeviceOrSelector>(),\n                                        [=]() {})\n    };\n    EIGEN_SYCL_TRY_CATCH(m_queue.submit(f));\n#endif\n  }\n\n  template <typename DeviceOrSelector>\n  explicit QueueInterface(\n      const DeviceOrSelector &dev_or_sel,\n      unsigned num_threads = std::thread::hardware_concurrency())\n      : QueueInterface(dev_or_sel,\n                       [this](cl::sycl::exception_list l) {\n                         this->exception_caught_ = this->sycl_async_handler(l);\n                       },\n                       num_threads) {}\n\n#ifdef EIGEN_SYCL_USE_PROGRAM_CLASS\n  EIGEN_STRONG_INLINE cl::sycl::program &program() const { return m_prog; }\n#endif\n\n  /// Attach an existing buffer to the pointer map, Eigen will not reuse it\n  EIGEN_STRONG_INLINE void *attach_buffer(\n      cl::sycl::buffer<buffer_scalar_t, 1> &buf) const {\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n    return static_cast<void *>(pMapper.add_pointer(buf));\n  }\n\n  /// Detach previously attached buffer\n  EIGEN_STRONG_INLINE void detach_buffer(void *p) const {\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n    TensorSycl::internal::SYCLfree<false>(p, pMapper);\n  }\n\n  /// Allocating device pointer. This pointer is actually an 8 bytes host\n  /// pointer used as key to access the sycl device buffer. The reason is that\n  /// we cannot use device buffer as a pointer as a m_data in Eigen leafNode\n  /// expressions. So we create a key pointer to be used in Eigen expression\n  /// construction. When we convert the Eigen construction into the sycl\n  /// construction we use this pointer as a key in our buffer_map and we make\n  /// sure that we dedicate only one buffer only for this pointer. The device\n  /// pointer would be deleted by calling deallocate function.\n  EIGEN_STRONG_INLINE void *allocate(size_t num_bytes) const {\n#if EIGEN_MAX_ALIGN_BYTES > 0\n    size_t align = num_bytes % EIGEN_MAX_ALIGN_BYTES;\n    if (align > 0) {\n      num_bytes += EIGEN_MAX_ALIGN_BYTES - align;\n    }\n#endif\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n    return TensorSycl::internal::SYCLmalloc(num_bytes, pMapper);\n  }\n\n  EIGEN_STRONG_INLINE void *allocate_temp(size_t num_bytes) const {\n#if EIGEN_MAX_ALIGN_BYTES > 0\n    size_t align = num_bytes % EIGEN_MAX_ALIGN_BYTES;\n    if (align > 0) {\n      num_bytes += EIGEN_MAX_ALIGN_BYTES - align;\n    }\n#endif\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n#ifndef EIGEN_SYCL_NO_REUSE_BUFFERS\n    if (scratch_buffers.empty()) {\n      return TensorSycl::internal::SYCLmalloc(num_bytes, pMapper);\n      ;\n    } else {\n      for (auto it = scratch_buffers.begin(); it != scratch_buffers.end();) {\n        auto buff = pMapper.get_buffer(*it);\n        if (buff.get_size() >= num_bytes) {\n          auto ptr = *it;\n          scratch_buffers.erase(it);\n          return ptr;\n        } else {\n          ++it;\n        }\n      }\n      return TensorSycl::internal::SYCLmalloc(num_bytes, pMapper);\n    }\n#else\n    return TensorSycl::internal::SYCLmalloc(num_bytes, pMapper);\n#endif\n  }\n  template <typename data_t>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorSycl::internal::RangeAccess<\n      cl::sycl::access::mode::read_write, data_t>\n  get(data_t *data) const {\n    return get_range_accessor<cl::sycl::access::mode::read_write, data_t>(data);\n  }\n  template <typename data_t>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE data_t *get(\n      TensorSycl::internal::RangeAccess<cl::sycl::access::mode::read_write,\n                                        data_t>\n          data) const {\n    return static_cast<data_t *>(data.get_virtual_pointer());\n  }\n\n  EIGEN_STRONG_INLINE void deallocate_temp(void *p) const {\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n#ifndef EIGEN_SYCL_NO_REUSE_BUFFERS\n    scratch_buffers.insert(p);\n#else\n    TensorSycl::internal::SYCLfree(p, pMapper);\n#endif\n  }\n  template <cl::sycl::access::mode AcMd, typename T>\n  EIGEN_STRONG_INLINE void deallocate_temp(\n      const TensorSycl::internal::RangeAccess<AcMd, T> &p) const {\n    deallocate_temp(p.get_virtual_pointer());\n  }\n\n  /// This is used to deallocate the device pointer. p is used as a key inside\n  /// the map to find the device buffer and delete it.\n  EIGEN_STRONG_INLINE void deallocate(void *p) const {\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n    TensorSycl::internal::SYCLfree(p, pMapper);\n  }\n\n  EIGEN_STRONG_INLINE void deallocate_all() const {\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n    TensorSycl::internal::SYCLfreeAll(pMapper);\n#ifndef EIGEN_SYCL_NO_REUSE_BUFFERS\n    scratch_buffers.clear();\n#endif\n  }\n\n  /// The memcpyHostToDevice is used to copy the data from host to device\n  /// The destination pointer could be deleted before the copy happend which is\n  /// why a callback function is needed. By default if none is provided, the\n  /// function is blocking.\n  EIGEN_STRONG_INLINE void memcpyHostToDevice(\n      void *dst, const void *src, size_t n,\n      std::function<void()> callback) const {\n    static const auto write_mode = cl::sycl::access::mode::discard_write;\n    static const auto global_access = cl::sycl::access::target::global_buffer;\n    typedef cl::sycl::accessor<buffer_scalar_t, 1, write_mode, global_access>\n        write_accessor;\n    if (n == 0) {\n      if (callback) callback();\n      return;\n    }\n    n /= sizeof(buffer_scalar_t);\n    auto f = [&](cl::sycl::handler &cgh) {\n      write_accessor dst_acc = get_range_accessor<write_mode>(cgh, dst, n);\n      buffer_scalar_t const *ptr = static_cast<buffer_scalar_t const *>(src);\n      auto non_deleter = [](buffer_scalar_t const *) {};\n      std::shared_ptr<const buffer_scalar_t> s_ptr(ptr, non_deleter);\n      cgh.copy(s_ptr, dst_acc);\n    };\n    cl::sycl::event e;\n    EIGEN_SYCL_TRY_CATCH(e = m_queue.submit(f));\n    synchronize_and_callback(e, callback);\n  }\n\n  /// The memcpyDeviceToHost is used to copy the data from device to host.\n  /// The source pointer could be deleted before the copy happend which is\n  /// why a callback function is needed. By default if none is provided, the\n  /// function is blocking.\n  EIGEN_STRONG_INLINE void memcpyDeviceToHost(\n      void *dst, const void *src, size_t n,\n      std::function<void()> callback) const {\n    static const auto read_mode = cl::sycl::access::mode::read;\n    static const auto global_access = cl::sycl::access::target::global_buffer;\n    typedef cl::sycl::accessor<buffer_scalar_t, 1, read_mode, global_access>\n        read_accessor;\n    if (n == 0) {\n      if (callback) callback();\n      return;\n    }\n    n /= sizeof(buffer_scalar_t);\n    auto f = [&](cl::sycl::handler &cgh) {\n      read_accessor src_acc = get_range_accessor<read_mode>(cgh, src, n);\n      buffer_scalar_t *ptr = static_cast<buffer_scalar_t *>(dst);\n      auto non_deleter = [](buffer_scalar_t *) {};\n      std::shared_ptr<buffer_scalar_t> s_ptr(ptr, non_deleter);\n      cgh.copy(src_acc, s_ptr);\n    };\n    cl::sycl::event e;\n    EIGEN_SYCL_TRY_CATCH(e = m_queue.submit(f));\n    synchronize_and_callback(e, callback);\n  }\n\n  /// The memcpy function.\n  /// No callback is required here as both arguments are on the device\n  /// and SYCL can handle the dependency.\n  EIGEN_STRONG_INLINE void memcpy(void *dst, const void *src, size_t n) const {\n    static const auto read_mode = cl::sycl::access::mode::read;\n    static const auto write_mode = cl::sycl::access::mode::discard_write;\n    if (n == 0) {\n      return;\n    }\n    n /= sizeof(buffer_scalar_t);\n    auto f = [&](cl::sycl::handler &cgh) {\n      auto src_acc = get_range_accessor<read_mode>(cgh, src, n);\n      auto dst_acc = get_range_accessor<write_mode>(cgh, dst, n);\n      cgh.copy(src_acc, dst_acc);\n    };\n    cl::sycl::event e;\n    EIGEN_SYCL_TRY_CATCH(e = m_queue.submit(f));\n    async_synchronize(e);\n  }\n\n  /// the memset function.\n  /// No callback is required here as both arguments are on the device\n  /// and SYCL can handle the dependency.\n  EIGEN_STRONG_INLINE void memset(void *data, int c, size_t n) const {\n    static const auto write_mode = cl::sycl::access::mode::discard_write;\n    if (n == 0) {\n      return;\n    }\n    auto f = [&](cl::sycl::handler &cgh) {\n      // Get a typed range accesser to ensure we fill each byte, in case\n      // `buffer_scalar_t` is not (u)int8_t.\n      auto dst_acc = get_typed_range_accessor<write_mode, uint8_t>(cgh, data, n);\n      cgh.fill(dst_acc, static_cast<uint8_t>(c));\n    };\n    cl::sycl::event e;\n    EIGEN_SYCL_TRY_CATCH(e = m_queue.submit(f));\n    async_synchronize(e);\n  }\n\n  template<typename T>\n  EIGEN_STRONG_INLINE void fill(T* begin, T* end, const T& value) const {\n    static const auto write_mode = cl::sycl::access::mode::discard_write;\n    if (begin == end) {\n      return;\n    }\n    const ptrdiff_t count = end - begin;\n    auto f = [&](cl::sycl::handler &cgh) {\n      auto dst_acc = get_typed_range_accessor<write_mode, T>(cgh, begin, count);\n      cgh.fill(dst_acc, value);\n    };\n    cl::sycl::event e;\n    EIGEN_SYCL_TRY_CATCH(e = m_queue.submit(f));\n    async_synchronize(e);\n  }\n\n  /// Get a range accessor to the virtual pointer's device memory. This range\n  /// accessor will allow access to the memory from the pointer to the end of\n  /// the buffer.\n  ///\n  /// NOTE: Inside a kernel the range accessor will always be indexed from the\n  /// start of the buffer, so the offset in the accessor is only used by\n  /// methods like handler::copy and will not be available inside a kernel.\n  template <cl::sycl::access::mode AcMd, typename T>\n  EIGEN_STRONG_INLINE TensorSycl::internal::RangeAccess<AcMd, T>\n  get_range_accessor(const void *ptr) const {\n    static const auto global_access = cl::sycl::access::target::global_buffer;\n    static const auto is_place_holder = cl::sycl::access::placeholder::true_t;\n    typedef TensorSycl::internal::RangeAccess<AcMd, T> ret_type;\n    typedef const TensorSycl::internal::buffer_data_type_t *internal_ptr_t;\n\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n\n    auto original_buffer = pMapper.get_buffer(ptr);\n    const ptrdiff_t offset = pMapper.get_offset(ptr);\n    eigen_assert(offset % sizeof(T) == 0 && \"The offset must be a multiple of sizeof(T)\");\n    eigen_assert(original_buffer.get_size() % sizeof(T) == 0 && \"The buffer size must be a multiple of sizeof(T)\");\n    const ptrdiff_t typed_offset = offset / sizeof(T);\n    eigen_assert(typed_offset >= 0);\n    const auto typed_size = original_buffer.get_size() / sizeof(T);\n    auto buffer = original_buffer.template reinterpret<\n        typename Eigen::internal::remove_const<T>::type>(\n        cl::sycl::range<1>(typed_size));\n    const ptrdiff_t size = buffer.get_count() - typed_offset;\n    eigen_assert(size >= 0);\n    typedef cl::sycl::accessor<typename Eigen::internal::remove_const<T>::type,\n                               1, AcMd, global_access, is_place_holder>\n        placeholder_accessor_t;\n    const auto start_ptr = static_cast<internal_ptr_t>(ptr) - offset;\n    return ret_type(placeholder_accessor_t(buffer, cl::sycl::range<1>(size),\n                                           cl::sycl::id<1>(typed_offset)),\n                    static_cast<size_t>(typed_offset),\n                    reinterpret_cast<std::intptr_t>(start_ptr));\n  }\n\n  /// Get a range accessor to the virtual pointer's device memory with a\n  /// specified size.\n  template <cl::sycl::access::mode AcMd, typename Index>\n  EIGEN_STRONG_INLINE cl::sycl::accessor<\n      buffer_scalar_t, 1, AcMd, cl::sycl::access::target::global_buffer>\n  get_range_accessor(cl::sycl::handler &cgh, const void *ptr,\n                     const Index n_bytes) const {\n    static const auto global_access = cl::sycl::access::target::global_buffer;\n    eigen_assert(n_bytes >= 0);\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n    auto buffer = pMapper.get_buffer(ptr);\n    const ptrdiff_t offset = pMapper.get_offset(ptr);\n    eigen_assert(offset >= 0);\n    eigen_assert(offset + n_bytes <= buffer.get_size());\n    return buffer.template get_access<AcMd, global_access>(\n        cgh, cl::sycl::range<1>(n_bytes), cl::sycl::id<1>(offset));\n  }\n\n  /// Get a range accessor to the virtual pointer's device memory with a\n  /// specified type and count.\n  template <cl::sycl::access::mode AcMd, typename T, typename Index>\n  EIGEN_STRONG_INLINE cl::sycl::accessor<\n      T, 1, AcMd, cl::sycl::access::target::global_buffer>\n  get_typed_range_accessor(cl::sycl::handler &cgh, const void *ptr,\n                     const Index count) const {\n    static const auto global_access = cl::sycl::access::target::global_buffer;\n    eigen_assert(count >= 0);\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n    auto buffer = pMapper.get_buffer(ptr);\n    const ptrdiff_t offset = pMapper.get_offset(ptr);\n    eigen_assert(offset >= 0);\n\n    // Technically we should create a subbuffer for the desired range,\n    // then reinterpret that.  However, I was not able to get changes to reflect\n    // in the original buffer (only the subbuffer and reinterpretted buffer).\n    // This current implementation now has the restriction that the buffer\n    // offset and original buffer size must be a multiple of sizeof(T).\n    // Note that get_range_accessor(void*) currently has the same restriction.\n    //\n    // auto subbuffer = cl::sycl::buffer<buffer_scalar_t, 1>(buffer, \n    //     cl::sycl::id<1>(offset), cl::sycl::range<1>(n_bytes));\n    eigen_assert(offset % sizeof(T) == 0 && \"The offset must be a multiple of sizeof(T)\");\n    eigen_assert(buffer.get_size() % sizeof(T) == 0 && \"The buffer size must be a multiple of sizeof(T)\");\n    const ptrdiff_t typed_offset = offset / sizeof(T);\n    const size_t typed_size = buffer.get_size() / sizeof(T);\n    auto reint = buffer.template reinterpret<\n        typename Eigen::internal::remove_const<T>::type>(\n        cl::sycl::range<1>(typed_size));\n    return reint.template get_access<AcMd, global_access>(\n        cgh, cl::sycl::range<1>(count), cl::sycl::id<1>(typed_offset));\n  }\n\n  /// Creation of sycl accessor for a buffer. This function first tries to find\n  /// the buffer in the buffer_map. If found it gets the accessor from it, if\n  /// not, the function then adds an entry by creating a sycl buffer for that\n  /// particular pointer.\n  template <cl::sycl::access::mode AcMd>\n  EIGEN_STRONG_INLINE cl::sycl::accessor<\n      buffer_scalar_t, 1, AcMd, cl::sycl::access::target::global_buffer>\n  get_sycl_accessor(cl::sycl::handler &cgh, const void *ptr) const {\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n    return pMapper.get_buffer(ptr)\n        .template get_access<AcMd, cl::sycl::access::target::global_buffer>(\n            cgh);\n  }\n\n  EIGEN_STRONG_INLINE cl::sycl::buffer<buffer_scalar_t, 1> get_sycl_buffer(\n      const void *ptr) const {\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n    return pMapper.get_buffer(ptr);\n  }\n\n  EIGEN_STRONG_INLINE ptrdiff_t get_offset(const void *ptr) const {\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n    return pMapper.get_offset(ptr);\n  }\n\n  template <typename OutScalar, typename sycl_kernel, typename Lhs,\n            typename Rhs, typename OutPtr, typename Range, typename Index,\n            typename... T>\n  EIGEN_ALWAYS_INLINE void binary_kernel_launcher(const Lhs &lhs,\n                                                  const Rhs &rhs, OutPtr outptr,\n                                                  Range thread_range,\n                                                  Index scratchSize,\n                                                  T... var) const {\n    auto kernel_functor = [=](cl::sycl::handler &cgh) {\n      // binding the placeholder accessors to a commandgroup handler\n      lhs.bind(cgh);\n      rhs.bind(cgh);\n      outptr.bind(cgh);\n      typedef cl::sycl::accessor<OutScalar, 1,\n                                 cl::sycl::access::mode::read_write,\n                                 cl::sycl::access::target::local>\n          LocalAccessor;\n\n      LocalAccessor scratch(cl::sycl::range<1>(scratchSize), cgh);\n      cgh.parallel_for(\n#ifdef EIGEN_SYCL_USE_PROGRAM_CLASS\n          program().template get_kernel<sycl_kernel>(),\n#endif\n          thread_range, sycl_kernel(scratch, lhs, rhs, outptr, var...));\n    };\n    cl::sycl::event e;\n    EIGEN_SYCL_TRY_CATCH(e = m_queue.submit(kernel_functor));\n    async_synchronize(e);\n  }\n\n  template <typename OutScalar, typename sycl_kernel, typename InPtr,\n            typename OutPtr, typename Range, typename Index, typename... T>\n  EIGEN_ALWAYS_INLINE void unary_kernel_launcher(const InPtr &inptr,\n                                                 OutPtr &outptr,\n                                                 Range thread_range,\n                                                 Index scratchSize,\n                                                 T... var) const {\n    auto kernel_functor = [=](cl::sycl::handler &cgh) {\n      // binding the placeholder accessors to a commandgroup handler\n      inptr.bind(cgh);\n      outptr.bind(cgh);\n      typedef cl::sycl::accessor<OutScalar, 1,\n                                 cl::sycl::access::mode::read_write,\n                                 cl::sycl::access::target::local>\n          LocalAccessor;\n\n      LocalAccessor scratch(cl::sycl::range<1>(scratchSize), cgh);\n      cgh.parallel_for(\n#ifdef EIGEN_SYCL_USE_PROGRAM_CLASS\n          program().template get_kernel<sycl_kernel>(),\n#endif\n          thread_range, sycl_kernel(scratch, inptr, outptr, var...));\n    };\n    cl::sycl::event e;\n    EIGEN_SYCL_TRY_CATCH(e = m_queue.submit(kernel_functor));\n    async_synchronize(e);\n  }\n\n    template <typename OutScalar, typename sycl_kernel, typename InPtr,\n           typename Range, typename Index, typename... T>\n  EIGEN_ALWAYS_INLINE void nullary_kernel_launcher(const InPtr &inptr,\n                                                 Range thread_range,\n                                                 Index scratchSize,\n                                                 T... var) const {\n    auto kernel_functor = [=](cl::sycl::handler &cgh) {\n      // binding the placeholder accessors to a commandgroup handler\n      inptr.bind(cgh);\n      typedef cl::sycl::accessor<OutScalar, 1,\n                                 cl::sycl::access::mode::read_write,\n                                 cl::sycl::access::target::local>\n          LocalAccessor;\n\n      LocalAccessor scratch(cl::sycl::range<1>(scratchSize), cgh);\n      cgh.parallel_for(\n#ifdef EIGEN_SYCL_USE_PROGRAM_CLASS\n          program().template get_kernel<sycl_kernel>(),\n#endif\n          thread_range, sycl_kernel(scratch, inptr, var...));\n    };\n    cl::sycl::event e;\n    EIGEN_SYCL_TRY_CATCH(e = m_queue.submit(kernel_functor));\n    async_synchronize(e);\n  }\n\n\n  EIGEN_STRONG_INLINE void synchronize() const {\n#ifdef EIGEN_EXCEPTIONS\n    m_queue.wait_and_throw();\n#else\n    m_queue.wait();\n#endif\n  }\n\n\n  EIGEN_STRONG_INLINE void async_synchronize(cl::sycl::event e) const {\n    set_latest_event(e);\n#ifndef EIGEN_SYCL_ASYNC_EXECUTION\n    synchronize();\n#endif\n  }\n\n  template <typename Index>\n  EIGEN_STRONG_INLINE void parallel_for_setup(Index n, Index &tileSize,\n                                              Index &rng, Index &GRange) const {\n    tileSize = static_cast<Index>(getNearestPowerOfTwoWorkGroupSize());\n    tileSize = std::min(static_cast<Index>(EIGEN_SYCL_LOCAL_THREAD_DIM0 *\n                                           EIGEN_SYCL_LOCAL_THREAD_DIM1),\n                        static_cast<Index>(tileSize));\n    rng = n;\n    if (rng == 0) rng = static_cast<Index>(1);\n    GRange = rng;\n    if (tileSize > GRange)\n      tileSize = GRange;\n    else if (GRange > tileSize) {\n      Index xMode = static_cast<Index>(GRange % tileSize);\n      if (xMode != 0) GRange += static_cast<Index>(tileSize - xMode);\n    }\n  }\n\n  /// This is used to prepare the number of threads and also the number of\n  /// threads per block for sycl kernels\n  template <typename Index>\n  EIGEN_STRONG_INLINE void parallel_for_setup(\n      const std::array<Index, 2> &input_dim, cl::sycl::range<2> &global_range,\n      cl::sycl::range<2> &local_range) const {\n    std::array<Index, 2> input_range = input_dim;\n    Index max_workgroup_Size =\n        static_cast<Index>(getNearestPowerOfTwoWorkGroupSize());\n    max_workgroup_Size =\n        std::min(static_cast<Index>(EIGEN_SYCL_LOCAL_THREAD_DIM0 *\n                                    EIGEN_SYCL_LOCAL_THREAD_DIM1),\n                 static_cast<Index>(max_workgroup_Size));\n    Index pow_of_2 = static_cast<Index>(std::log2(max_workgroup_Size));\n    local_range[1] =\n        static_cast<Index>(std::pow(2, static_cast<Index>(pow_of_2 / 2)));\n    input_range[1] = input_dim[1];\n    if (input_range[1] == 0) input_range[1] = static_cast<Index>(1);\n    global_range[1] = input_range[1];\n    if (local_range[1] > global_range[1])\n      local_range[1] = global_range[1];\n    else if (global_range[1] > local_range[1]) {\n      Index xMode = static_cast<Index>(global_range[1] % local_range[1]);\n      if (xMode != 0)\n        global_range[1] += static_cast<Index>(local_range[1] - xMode);\n    }\n    local_range[0] = static_cast<Index>(max_workgroup_Size / local_range[1]);\n    input_range[0] = input_dim[0];\n    if (input_range[0] == 0) input_range[0] = static_cast<Index>(1);\n    global_range[0] = input_range[0];\n    if (local_range[0] > global_range[0])\n      local_range[0] = global_range[0];\n    else if (global_range[0] > local_range[0]) {\n      Index xMode = static_cast<Index>(global_range[0] % local_range[0]);\n      if (xMode != 0)\n        global_range[0] += static_cast<Index>(local_range[0] - xMode);\n    }\n  }\n\n  /// This is used to prepare the number of threads and also the number of\n  /// threads per block for sycl kernels\n  template <typename Index>\n  EIGEN_STRONG_INLINE void parallel_for_setup(\n      const std::array<Index, 3> &input_dim, cl::sycl::range<3> &global_range,\n      cl::sycl::range<3> &local_range) const {\n    std::array<Index, 3> input_range = input_dim;\n    Index max_workgroup_Size =\n        static_cast<Index>(getNearestPowerOfTwoWorkGroupSize());\n    max_workgroup_Size =\n        std::min(static_cast<Index>(EIGEN_SYCL_LOCAL_THREAD_DIM0 *\n                                    EIGEN_SYCL_LOCAL_THREAD_DIM1),\n                 static_cast<Index>(max_workgroup_Size));\n    Index pow_of_2 = static_cast<Index>(std::log2(max_workgroup_Size));\n    local_range[2] =\n        static_cast<Index>(std::pow(2, static_cast<Index>(pow_of_2 / 3)));\n    input_range[2] = input_dim[2];\n    if (input_range[2] == 0) input_range[1] = static_cast<Index>(1);\n    global_range[2] = input_range[2];\n    if (local_range[2] > global_range[2])\n      local_range[2] = global_range[2];\n    else if (global_range[2] > local_range[2]) {\n      Index xMode = static_cast<Index>(global_range[2] % local_range[2]);\n      if (xMode != 0)\n        global_range[2] += static_cast<Index>(local_range[2] - xMode);\n    }\n    pow_of_2 = static_cast<Index>(\n        std::log2(static_cast<Index>(max_workgroup_Size / local_range[2])));\n    local_range[1] =\n        static_cast<Index>(std::pow(2, static_cast<Index>(pow_of_2 / 2)));\n    input_range[1] = input_dim[1];\n    if (input_range[1] == 0) input_range[1] = static_cast<Index>(1);\n    global_range[1] = input_range[1];\n    if (local_range[1] > global_range[1])\n      local_range[1] = global_range[1];\n    else if (global_range[1] > local_range[1]) {\n      Index xMode = static_cast<Index>(global_range[1] % local_range[1]);\n      if (xMode != 0)\n        global_range[1] += static_cast<Index>(local_range[1] - xMode);\n    }\n    local_range[0] = static_cast<Index>(max_workgroup_Size /\n                                        (local_range[1] * local_range[2]));\n    input_range[0] = input_dim[0];\n    if (input_range[0] == 0) input_range[0] = static_cast<Index>(1);\n    global_range[0] = input_range[0];\n    if (local_range[0] > global_range[0])\n      local_range[0] = global_range[0];\n    else if (global_range[0] > local_range[0]) {\n      Index xMode = static_cast<Index>(global_range[0] % local_range[0]);\n      if (xMode != 0)\n        global_range[0] += static_cast<Index>(local_range[0] - xMode);\n    }\n  }\n\n  EIGEN_STRONG_INLINE bool has_local_memory() const {\n#if !defined(EIGEN_SYCL_LOCAL_MEM) && defined(EIGEN_SYCL_NO_LOCAL_MEM)\n    return false;\n#elif defined(EIGEN_SYCL_LOCAL_MEM) && !defined(EIGEN_SYCL_NO_LOCAL_MEM)\n    return true;\n#else\n    return m_device_info.local_mem_type ==\n           cl::sycl::info::local_mem_type::local;\n#endif\n  }\n\n  EIGEN_STRONG_INLINE unsigned long max_buffer_size() const {\n    return m_device_info.max_mem_alloc_size;\n  }\n\n  EIGEN_STRONG_INLINE unsigned long getNumSyclMultiProcessors() const {\n    return m_device_info.max_compute_units;\n  }\n\n  EIGEN_STRONG_INLINE unsigned long maxSyclThreadsPerBlock() const {\n    return m_device_info.max_work_group_size;\n  }\n\n  EIGEN_STRONG_INLINE cl::sycl::id<3> maxWorkItemSizes() const {\n    return m_device_info.max_work_item_sizes;\n  }\n\n  /// No need for sycl it should act the same as CPU version\n  EIGEN_STRONG_INLINE int majorDeviceVersion() const { return 1; }\n\n  EIGEN_STRONG_INLINE unsigned long maxSyclThreadsPerMultiProcessor() const {\n    // OpenCL doesnot have such concept\n    return 2;\n  }\n\n  EIGEN_STRONG_INLINE size_t sharedMemPerBlock() const {\n    return m_device_info.local_mem_size;\n  }\n\n  // This function returns the nearest power of 2 Work-group size which is <=\n  // maximum device workgroup size.\n  EIGEN_STRONG_INLINE size_t getNearestPowerOfTwoWorkGroupSize() const {\n    return getPowerOfTwo(m_device_info.max_work_group_size, false);\n  }\n\n  EIGEN_STRONG_INLINE std::string getPlatformName() const {\n    return m_device_info.platform_name;\n  }\n\n  EIGEN_STRONG_INLINE std::string getDeviceName() const {\n    return m_device_info.device_name;\n  }\n\n  EIGEN_STRONG_INLINE std::string getDeviceVendor() const {\n    return m_device_info.device_vendor;\n  }\n\n  // This function returns the nearest power of 2\n  // if roundup is true returns result>=wgsize\n  // else it return result <= wgsize\n  EIGEN_STRONG_INLINE size_t getPowerOfTwo(size_t wGSize, bool roundUp) const {\n    if (roundUp) --wGSize;\n    wGSize |= (wGSize >> 1);\n    wGSize |= (wGSize >> 2);\n    wGSize |= (wGSize >> 4);\n    wGSize |= (wGSize >> 8);\n    wGSize |= (wGSize >> 16);\n#if EIGEN_ARCH_x86_64 || EIGEN_ARCH_ARM64 || EIGEN_OS_WIN64\n    wGSize |= (wGSize >> 32);\n#endif\n    return ((!roundUp) ? (wGSize - (wGSize >> 1)) : ++wGSize);\n  }\n\n  EIGEN_STRONG_INLINE cl::sycl::queue &sycl_queue() const { return m_queue; }\n\n  // This function checks if the runtime recorded an error for the\n  // underlying stream device.\n  EIGEN_STRONG_INLINE bool ok() const {\n    if (!exception_caught_) {\n      synchronize();\n    }\n    return !exception_caught_;\n  }\n\n  EIGEN_STRONG_INLINE cl::sycl::event get_latest_event() const {\n#ifdef EIGEN_SYCL_STORE_LATEST_EVENT\n    std::lock_guard<std::mutex> lock(event_mutex_);\n    return latest_events_[std::this_thread::get_id()];\n#else\n    eigen_assert(false);\n    return cl::sycl::event();\n#endif\n  }\n\n  // destructor\n  ~QueueInterface() {\n    pMapper.clear();\n#ifndef EIGEN_SYCL_NO_REUSE_BUFFERS\n    scratch_buffers.clear();\n#endif\n  }\n\n protected:\n  EIGEN_STRONG_INLINE void set_latest_event(cl::sycl::event e) const {\n#ifdef EIGEN_SYCL_STORE_LATEST_EVENT\n    std::lock_guard<std::mutex> lock(event_mutex_);\n    latest_events_[std::this_thread::get_id()] = e;\n#else\n    EIGEN_UNUSED_VARIABLE(e);\n#endif\n  }\n\n  void synchronize_and_callback(cl::sycl::event e,\n                                const std::function<void()> &callback) const {\n    set_latest_event(e);\n    if (callback) {\n      auto callback_ = [=]() {\n#ifdef EIGEN_EXCEPTIONS\n        cl::sycl::event(e).wait_and_throw();\n#else\n        cl::sycl::event(e).wait();\n#endif\n        callback();\n      };\n      m_thread_pool.Schedule(std::move(callback_));\n    } else {\n#ifdef EIGEN_EXCEPTIONS\n      m_queue.wait_and_throw();\n#else\n      m_queue.wait();\n#endif\n    }\n  }\n\n  bool sycl_async_handler(cl::sycl::exception_list exceptions) const {\n    bool exception_caught = false;\n    for (const auto &e : exceptions) {\n      if (e) {\n        exception_caught = true;\n        EIGEN_THROW_X(e);\n      }\n    }\n    return exception_caught;\n  }\n\n  /// class members:\n  bool exception_caught_ = false;\n\n  mutable std::mutex pmapper_mutex_;\n\n#ifdef EIGEN_SYCL_STORE_LATEST_EVENT\n  mutable std::mutex event_mutex_;\n  mutable std::unordered_map<std::thread::id, cl::sycl::event> latest_events_;\n#endif\n\n  /// std::map is the container used to make sure that we create only one buffer\n  /// per pointer. The lifespan of the buffer now depends on the lifespan of\n  /// SyclDevice. If a non-read-only pointer is needed to be accessed on the\n  /// host we should manually deallocate it.\n  mutable TensorSycl::internal::PointerMapper pMapper;\n#ifndef EIGEN_SYCL_NO_REUSE_BUFFERS\n  mutable std::unordered_set<void *> scratch_buffers;\n#endif\n  /// sycl queue\n  mutable cl::sycl::queue m_queue;\n#ifdef EIGEN_SYCL_USE_PROGRAM_CLASS\n  mutable cl::sycl::program m_prog;\n#endif\n\n  /// The thread pool is used to wait on events and call callbacks\n  /// asynchronously\n  mutable Eigen::ThreadPool m_thread_pool;\n\n  const TensorSycl::internal::SyclDeviceInfo m_device_info;\n};\n\nstruct SyclDeviceBase {\n  /// QueueInterface is not owned. it is the caller's responsibility to destroy\n  /// it\n  const QueueInterface *m_queue_stream;\n  explicit SyclDeviceBase(const QueueInterface *queue_stream)\n      : m_queue_stream(queue_stream) {}\n  EIGEN_STRONG_INLINE const QueueInterface *queue_stream() const {\n    return m_queue_stream;\n  }\n};\n\n// Here is a sycl device struct which accept the sycl queue interface\n// as an input\nstruct SyclDevice : public SyclDeviceBase {\n  explicit SyclDevice(const QueueInterface *queue_stream)\n      : SyclDeviceBase(queue_stream) {}\n\n  // this is the accessor used to construct the evaluator\n  template <cl::sycl::access::mode AcMd, typename T>\n  EIGEN_STRONG_INLINE TensorSycl::internal::RangeAccess<AcMd, T>\n  get_range_accessor(const void *ptr) const {\n    return queue_stream()->template get_range_accessor<AcMd, T>(ptr);\n  }\n\n  // get sycl accessor\n  template <cl::sycl::access::mode AcMd>\n  EIGEN_STRONG_INLINE cl::sycl::accessor<\n      buffer_scalar_t, 1, AcMd, cl::sycl::access::target::global_buffer>\n  get_sycl_accessor(cl::sycl::handler &cgh, const void *ptr) const {\n    return queue_stream()->template get_sycl_accessor<AcMd>(cgh, ptr);\n  }\n\n  /// Accessing the created sycl device buffer for the device pointer\n  EIGEN_STRONG_INLINE cl::sycl::buffer<buffer_scalar_t, 1> get_sycl_buffer(\n      const void *ptr) const {\n    return queue_stream()->get_sycl_buffer(ptr);\n  }\n\n  /// This is used to prepare the number of threads and also the number of\n  /// threads per block for sycl kernels\n  template <typename Index>\n  EIGEN_STRONG_INLINE void parallel_for_setup(Index n, Index &tileSize,\n                                              Index &rng, Index &GRange) const {\n    queue_stream()->parallel_for_setup(n, tileSize, rng, GRange);\n  }\n\n  /// This is used to prepare the number of threads and also the number of\n  /// threads per block for sycl kernels\n  template <typename Index>\n  EIGEN_STRONG_INLINE void parallel_for_setup(\n      const std::array<Index, 2> &input_dim, cl::sycl::range<2> &global_range,\n      cl::sycl::range<2> &local_range) const {\n    queue_stream()->parallel_for_setup(input_dim, global_range, local_range);\n  }\n\n  /// This is used to prepare the number of threads and also the number of\n  /// threads per block for sycl kernels\n  template <typename Index>\n  EIGEN_STRONG_INLINE void parallel_for_setup(\n      const std::array<Index, 3> &input_dim, cl::sycl::range<3> &global_range,\n      cl::sycl::range<3> &local_range) const {\n    queue_stream()->parallel_for_setup(input_dim, global_range, local_range);\n  }\n\n  /// allocate device memory\n  EIGEN_STRONG_INLINE void *allocate(size_t num_bytes) const {\n    return queue_stream()->allocate(num_bytes);\n  }\n\n  EIGEN_STRONG_INLINE void *allocate_temp(size_t num_bytes) const {\n    return queue_stream()->allocate_temp(num_bytes);\n  }\n\n  /// deallocate device memory\n  EIGEN_STRONG_INLINE void deallocate(void *p) const {\n    queue_stream()->deallocate(p);\n  }\n\n  EIGEN_STRONG_INLINE void deallocate_temp(void *buffer) const {\n    queue_stream()->deallocate_temp(buffer);\n  }\n  template <cl::sycl::access::mode AcMd, typename T>\n  EIGEN_STRONG_INLINE void deallocate_temp(\n      const TensorSycl::internal::RangeAccess<AcMd, T> &buffer) const {\n    queue_stream()->deallocate_temp(buffer);\n  }\n  EIGEN_STRONG_INLINE void deallocate_all() const {\n    queue_stream()->deallocate_all();\n  }\n\n  template <typename data_t>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorSycl::internal::RangeAccess<\n      cl::sycl::access::mode::read_write, data_t>\n  get(data_t *data) const {\n    return queue_stream()->get(data);\n  }\n  template <typename data_t>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE data_t *get(\n      TensorSycl::internal::RangeAccess<cl::sycl::access::mode::read_write,\n                                        data_t>\n          data) const {\n    return queue_stream()->get(data);\n  }\n\n  /// attach existing buffer\n  EIGEN_STRONG_INLINE void *attach_buffer(\n      cl::sycl::buffer<buffer_scalar_t, 1> &buf) const {\n    return queue_stream()->attach_buffer(buf);\n  }\n  /// detach buffer\n  EIGEN_STRONG_INLINE void detach_buffer(void *p) const {\n    queue_stream()->detach_buffer(p);\n  }\n  EIGEN_STRONG_INLINE ptrdiff_t get_offset(const void *ptr) const {\n    return queue_stream()->get_offset(ptr);\n  }\n\n  // some runtime conditions that can be applied here\n  EIGEN_STRONG_INLINE bool isDeviceSuitable() const { return true; }\n\n  /// memcpyHostToDevice\n  template <typename Index>\n  EIGEN_STRONG_INLINE void memcpyHostToDevice(\n      Index *dst, const Index *src, size_t n,\n      std::function<void()> callback = {}) const {\n    queue_stream()->memcpyHostToDevice(dst, src, n, callback);\n  }\n  /// memcpyDeviceToHost\n  template <typename Index>\n  EIGEN_STRONG_INLINE void memcpyDeviceToHost(\n      void *dst, const Index *src, size_t n,\n      std::function<void()> callback = {}) const {\n    queue_stream()->memcpyDeviceToHost(dst, src, n, callback);\n  }\n  /// the memcpy function\n  template <typename Index>\n  EIGEN_STRONG_INLINE void memcpy(void *dst, const Index *src, size_t n) const {\n    queue_stream()->memcpy(dst, src, n);\n  }\n  /// the memset function\n  EIGEN_STRONG_INLINE void memset(void *data, int c, size_t n) const {\n    queue_stream()->memset(data, c, n);\n  }\n  /// the fill function\n  template<typename T>\n  EIGEN_STRONG_INLINE void fill(T* begin, T* end, const T& value) const {\n    queue_stream()->fill(begin, end, value);\n  }\n  /// returning the sycl queue\n  EIGEN_STRONG_INLINE cl::sycl::queue &sycl_queue() const {\n    return queue_stream()->sycl_queue();\n  }\n#ifdef EIGEN_SYCL_USE_PROGRAM_CLASS\n  EIGEN_STRONG_INLINE cl::sycl::program &program() const {\n    return queue_stream()->program();\n  }\n#endif\n\n  EIGEN_STRONG_INLINE size_t firstLevelCacheSize() const { return 48 * 1024; }\n\n  EIGEN_STRONG_INLINE size_t lastLevelCacheSize() const {\n    // We won't try to take advantage of the l2 cache for the time being, and\n    // there is no l3 cache on sycl devices.\n    return firstLevelCacheSize();\n  }\n  EIGEN_STRONG_INLINE unsigned long getNumSyclMultiProcessors() const {\n    return queue_stream()->getNumSyclMultiProcessors();\n  }\n  EIGEN_STRONG_INLINE unsigned long maxSyclThreadsPerBlock() const {\n    return queue_stream()->maxSyclThreadsPerBlock();\n  }\n  EIGEN_STRONG_INLINE cl::sycl::id<3> maxWorkItemSizes() const {\n    return queue_stream()->maxWorkItemSizes();\n  }\n  EIGEN_STRONG_INLINE unsigned long maxSyclThreadsPerMultiProcessor() const {\n    // OpenCL doesnot have such concept\n    return queue_stream()->maxSyclThreadsPerMultiProcessor();\n  }\n  EIGEN_STRONG_INLINE size_t sharedMemPerBlock() const {\n    return queue_stream()->sharedMemPerBlock();\n  }\n  EIGEN_STRONG_INLINE size_t getNearestPowerOfTwoWorkGroupSize() const {\n    return queue_stream()->getNearestPowerOfTwoWorkGroupSize();\n  }\n\n  EIGEN_STRONG_INLINE size_t getPowerOfTwo(size_t val, bool roundUp) const {\n    return queue_stream()->getPowerOfTwo(val, roundUp);\n  }\n  /// No need for sycl it should act the same as CPU version\n  EIGEN_STRONG_INLINE int majorDeviceVersion() const {\n    return queue_stream()->majorDeviceVersion();\n  }\n\n  EIGEN_STRONG_INLINE void synchronize() const {\n    queue_stream()->synchronize();\n  }\n  EIGEN_STRONG_INLINE void async_synchronize(\n      cl::sycl::event e = cl::sycl::event()) const {\n    queue_stream()->async_synchronize(e);\n  }\n  EIGEN_STRONG_INLINE cl::sycl::event get_latest_event() const {\n    return queue_stream()->get_latest_event();\n  }\n\n  // This function checks if the runtime recorded an error for the\n  // underlying stream device.\n  EIGEN_STRONG_INLINE bool ok() const { return queue_stream()->ok(); }\n\n  EIGEN_STRONG_INLINE bool has_local_memory() const {\n    return queue_stream()->has_local_memory();\n  }\n  EIGEN_STRONG_INLINE long max_buffer_size() const {\n    return queue_stream()->max_buffer_size();\n  }\n  EIGEN_STRONG_INLINE std::string getPlatformName() const {\n    return queue_stream()->getPlatformName();\n  }\n  EIGEN_STRONG_INLINE std::string getDeviceName() const {\n    return queue_stream()->getDeviceName();\n  }\n  EIGEN_STRONG_INLINE std::string getDeviceVendor() const {\n    return queue_stream()->getDeviceVendor();\n  }\n  template <typename OutScalar, typename KernelType, typename... T>\n  EIGEN_ALWAYS_INLINE void binary_kernel_launcher(T... var) const {\n    queue_stream()->template binary_kernel_launcher<OutScalar, KernelType>(\n        var...);\n  }\n  template <typename OutScalar, typename KernelType, typename... T>\n  EIGEN_ALWAYS_INLINE void unary_kernel_launcher(T... var) const {\n    queue_stream()->template unary_kernel_launcher<OutScalar, KernelType>(\n        var...);\n  }\n\n  template <typename OutScalar, typename KernelType, typename... T>\n  EIGEN_ALWAYS_INLINE void nullary_kernel_launcher(T... var) const {\n    queue_stream()->template nullary_kernel_launcher<OutScalar, KernelType>(\n        var...);\n  }\n};\n}  // end namespace Eigen\n\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_DEVICE_SYCL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceThreadPool.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#if defined(EIGEN_USE_THREADS) && !defined(EIGEN_CXX11_TENSOR_TENSOR_DEVICE_THREAD_POOL_H)\n#define EIGEN_CXX11_TENSOR_TENSOR_DEVICE_THREAD_POOL_H\n\nnamespace Eigen {\n\n// Runs an arbitrary function and then calls Notify() on the passed in\n// Notification.\ntemplate <typename Function, typename... Args> struct FunctionWrapperWithNotification\n{\n  static void run(Notification* n, Function f, Args... args) {\n    f(args...);\n    if (n) {\n      n->Notify();\n    }\n  }\n};\n\ntemplate <typename Function, typename... Args> struct FunctionWrapperWithBarrier\n{\n  static void run(Barrier* b, Function f, Args... args) {\n    f(args...);\n    if (b) {\n      b->Notify();\n    }\n  }\n};\n\ntemplate <typename SyncType>\nstatic EIGEN_STRONG_INLINE void wait_until_ready(SyncType* n) {\n  if (n) {\n    n->Wait();\n  }\n}\n\n// An abstract interface to a device specific memory allocator.\nclass Allocator {\n public:\n  virtual ~Allocator() {}\n  virtual void* allocate(size_t num_bytes) const = 0;\n  virtual void deallocate(void* buffer) const = 0;\n};\n\n// Build a thread pool device on top the an existing pool of threads.\nstruct ThreadPoolDevice {\n  // The ownership of the thread pool remains with the caller.\n  ThreadPoolDevice(ThreadPoolInterface* pool, int num_cores, Allocator* allocator = nullptr)\n      : pool_(pool), num_threads_(num_cores), allocator_(allocator) { }\n\n  EIGEN_STRONG_INLINE void* allocate(size_t num_bytes) const {\n    return allocator_ ? allocator_->allocate(num_bytes)\n        : internal::aligned_malloc(num_bytes);\n  }\n\n  EIGEN_STRONG_INLINE void deallocate(void* buffer) const {\n    if (allocator_) {\n      allocator_->deallocate(buffer);\n    } else {\n      internal::aligned_free(buffer);\n    }\n  }\n\n    EIGEN_STRONG_INLINE void* allocate_temp(size_t num_bytes) const {\n    return allocate(num_bytes);\n  }\n\n  EIGEN_STRONG_INLINE void deallocate_temp(void* buffer) const {\n    deallocate(buffer);\n  }\n\n  template<typename Type>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Type get(Type data) const {\n    return data;\n  }\n\n  EIGEN_STRONG_INLINE void memcpy(void* dst, const void* src, size_t n) const {\n#ifdef __ANDROID__\n    ::memcpy(dst, src, n);\n#else\n    // TODO(rmlarsen): Align blocks on cache lines.\n    // We have observed that going beyond 4 threads usually just wastes\n    // CPU cycles due to the threads competing for memory bandwidth, so we\n    // statically schedule at most 4 block copies here.\n    const size_t kMinBlockSize = 32768;\n    const size_t num_threads = CostModel::numThreads(n, TensorOpCost(1.0, 1.0, 0), 4);\n    if (n <= kMinBlockSize || num_threads < 2) {\n      ::memcpy(dst, src, n);\n    } else {\n      const char* src_ptr = static_cast<const char*>(src);\n      char* dst_ptr = static_cast<char*>(dst);\n      const size_t blocksize = (n + (num_threads - 1)) / num_threads;\n      Barrier barrier(static_cast<int>(num_threads - 1));\n      // Launch the last 3 blocks on worker threads.\n      for (size_t i = 1; i < num_threads; ++i) {\n        enqueue_with_barrier(&barrier, [n, i, src_ptr, dst_ptr, blocksize] {\n          ::memcpy(dst_ptr + i * blocksize, src_ptr + i * blocksize,\n                   numext::mini(blocksize, n - (i * blocksize)));\n        });\n      }\n      // Launch the first block on the main thread.\n      ::memcpy(dst_ptr, src_ptr, blocksize);\n      barrier.Wait();\n    }\n#endif\n  }\n  EIGEN_STRONG_INLINE void memcpyHostToDevice(void* dst, const void* src, size_t n) const {\n    memcpy(dst, src, n);\n  }\n  EIGEN_STRONG_INLINE void memcpyDeviceToHost(void* dst, const void* src, size_t n) const {\n    memcpy(dst, src, n);\n  }\n\n  EIGEN_STRONG_INLINE void memset(void* buffer, int c, size_t n) const {\n    ::memset(buffer, c, n);\n  }\n\n  template<typename T>\n  EIGEN_STRONG_INLINE void fill(T* begin, T* end, const T& value) const {\n    std::fill(begin, end, value);\n  }\n\n  EIGEN_STRONG_INLINE int numThreads() const {\n    return num_threads_;\n  }\n\n  // Number of theads available in the underlying thread pool. This number can\n  // be different from the value returned by numThreads().\n  EIGEN_STRONG_INLINE int numThreadsInPool() const {\n    return pool_->NumThreads();\n  }\n\n  EIGEN_STRONG_INLINE size_t firstLevelCacheSize() const {\n    return l1CacheSize();\n  }\n\n  EIGEN_STRONG_INLINE size_t lastLevelCacheSize() const {\n    // The l3 cache size is shared between all the cores.\n    return l3CacheSize() / num_threads_;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int majorDeviceVersion() const {\n    // Should return an enum that encodes the ISA supported by the CPU\n    return 1;\n  }\n\n  template <class Function, class... Args>\n  EIGEN_STRONG_INLINE Notification* enqueue(Function&& f,\n                                            Args&&... args) const {\n    Notification* n = new Notification();\n    pool_->Schedule(\n        std::bind(&FunctionWrapperWithNotification<Function, Args...>::run, n,\n                  std::move(f), args...));\n    return n;\n  }\n\n  template <class Function, class... Args>\n  EIGEN_STRONG_INLINE void enqueue_with_barrier(Barrier* b, Function&& f,\n                                                Args&&... args) const {\n    pool_->Schedule(\n        std::bind(&FunctionWrapperWithBarrier<Function, Args...>::run, b,\n                  std::move(f), args...));\n  }\n\n  template <class Function, class... Args>\n  EIGEN_STRONG_INLINE void enqueueNoNotification(Function&& f,\n                                                 Args&&... args) const {\n    if (sizeof...(args) > 0) {\n      pool_->Schedule(std::bind(std::move(f), args...));\n    } else {\n      pool_->Schedule(std::move(f));\n    }\n  }\n\n  // Returns a logical thread index between 0 and pool_->NumThreads() - 1 if\n  // called from one of the threads in pool_. Returns -1 otherwise.\n  EIGEN_STRONG_INLINE int currentThreadId() const {\n    return pool_->CurrentThreadId();\n  }\n\n  // WARNING: This function is synchronous and will block the calling thread.\n  //\n  // Synchronous parallelFor executes f with [0, n) arguments in parallel and\n  // waits for completion. F accepts a half-open interval [first, last). Block\n  // size is chosen based on the iteration cost and resulting parallel\n  // efficiency. If block_align is not nullptr, it is called to round up the\n  // block size.\n  void parallelFor(Index n, const TensorOpCost& cost,\n                   std::function<Index(Index)> block_align,\n                   std::function<void(Index, Index)> f) const {\n    if (EIGEN_PREDICT_FALSE(n <= 0)){\n      return;\n    // Compute small problems directly in the caller thread.\n    } else if (n == 1 || numThreads() == 1 ||\n               CostModel::numThreads(n, cost, static_cast<int>(numThreads())) == 1) {\n      f(0, n);\n      return;\n    }\n\n    // Compute block size and total count of blocks.\n    ParallelForBlock block = CalculateParallelForBlock(n, cost, block_align);\n\n    // Recursively divide size into halves until we reach block_size.\n    // Division code rounds mid to block_size, so we are guaranteed to get\n    // block_count leaves that do actual computations.\n    Barrier barrier(static_cast<unsigned int>(block.count));\n    std::function<void(Index, Index)> handleRange;\n    handleRange = [=, &handleRange, &barrier, &f](Index firstIdx,\n                                                  Index lastIdx) {\n      while (lastIdx - firstIdx > block.size) {\n        // Split into halves and schedule the second half on a different thread.\n        const Index midIdx = firstIdx + divup((lastIdx - firstIdx) / 2, block.size) * block.size;\n        pool_->Schedule([=, &handleRange]() { handleRange(midIdx, lastIdx); });\n        lastIdx = midIdx;\n      }\n      // Single block or less, execute directly.\n      f(firstIdx, lastIdx);\n      barrier.Notify();\n    };\n\n    if (block.count <= numThreads()) {\n      // Avoid a thread hop by running the root of the tree and one block on the\n      // main thread.\n      handleRange(0, n);\n    } else {\n      // Execute the root in the thread pool to avoid running work on more than\n      // numThreads() threads.\n      pool_->Schedule([=, &handleRange]() { handleRange(0, n); });\n    }\n\n    barrier.Wait();\n  }\n\n  // Convenience wrapper for parallelFor that does not align blocks.\n  void parallelFor(Index n, const TensorOpCost& cost,\n                   std::function<void(Index, Index)> f) const {\n    parallelFor(n, cost, nullptr, std::move(f));\n  }\n\n  // WARNING: This function is asynchronous and will not block the calling thread.\n  //\n  // Asynchronous parallelFor executes f with [0, n) arguments in parallel\n  // without waiting for completion. When the last block finished, it will call\n  // 'done' callback. F accepts a half-open interval [first, last). Block size\n  // is chosen based on the iteration cost and resulting parallel efficiency. If\n  // block_align is not nullptr, it is called to round up the block size.\n  void parallelForAsync(Index n, const TensorOpCost& cost,\n                        std::function<Index(Index)> block_align,\n                        std::function<void(Index, Index)> f,\n                        std::function<void()> done) const {\n    // Compute small problems directly in the caller thread.\n    if (n <= 1 || numThreads() == 1 ||\n        CostModel::numThreads(n, cost, static_cast<int>(numThreads())) == 1) {\n      f(0, n);\n      done();\n      return;\n    }\n\n    // Compute block size and total count of blocks.\n    ParallelForBlock block = CalculateParallelForBlock(n, cost, block_align);\n\n    ParallelForAsyncContext* const ctx =\n        new ParallelForAsyncContext(block.count, std::move(f), std::move(done));\n\n    // Recursively divide size into halves until we reach block_size.\n    // Division code rounds mid to block_size, so we are guaranteed to get\n    // block_count leaves that do actual computations.\n    ctx->handle_range = [this, ctx, block](Index firstIdx, Index lastIdx) {\n      while (lastIdx - firstIdx > block.size) {\n        // Split into halves and schedule the second half on a different thread.\n        const Index midIdx = firstIdx + divup((lastIdx - firstIdx) / 2, block.size) * block.size;\n        pool_->Schedule(\n            [ctx, midIdx, lastIdx]() { ctx->handle_range(midIdx, lastIdx); });\n        lastIdx = midIdx;\n      }\n\n      // Single block or less, execute directly.\n      ctx->f(firstIdx, lastIdx);\n\n      // Delete async context if it was the last block.\n      if (ctx->count.fetch_sub(1) == 1) delete ctx;\n    };\n\n    if (block.count <= numThreads()) {\n      // Avoid a thread hop by running the root of the tree and one block on the\n      // main thread.\n      ctx->handle_range(0, n);\n    } else {\n      // Execute the root in the thread pool to avoid running work on more than\n      // numThreads() threads.\n      pool_->Schedule([ctx, n]() { ctx->handle_range(0, n); });\n    }\n  }\n\n  // Convenience wrapper for parallelForAsync that does not align blocks.\n  void parallelForAsync(Index n, const TensorOpCost& cost,\n                        std::function<void(Index, Index)> f,\n                        std::function<void()> done) const {\n    parallelForAsync(n, cost, nullptr, std::move(f), std::move(done));\n  }\n\n  // Thread pool accessor.\n  ThreadPoolInterface* getPool() const { return pool_; }\n\n  // Allocator accessor.\n  Allocator* allocator() const { return allocator_; }\n\n private:\n  typedef TensorCostModel<ThreadPoolDevice> CostModel;\n\n  // For parallelForAsync we must keep passed in closures on the heap, and\n  // delete them only after `done` callback finished.\n  struct ParallelForAsyncContext {\n    ParallelForAsyncContext(Index block_count,\n                            std::function<void(Index, Index)> block_f,\n                            std::function<void()> done_callback)\n        : count(block_count),\n          f(std::move(block_f)),\n          done(std::move(done_callback)) {}\n    ~ParallelForAsyncContext() { done(); }\n\n    std::atomic<Index> count;\n    std::function<void(Index, Index)> f;\n    std::function<void()> done;\n\n    std::function<void(Index, Index)> handle_range;\n  };\n\n  struct ParallelForBlock {\n    Index size;   // block size\n    Index count;  // number of blocks\n  };\n\n  // Calculates block size based on (1) the iteration cost and (2) parallel\n  // efficiency. We want blocks to be not too small to mitigate parallelization\n  // overheads; not too large to mitigate tail effect and potential load\n  // imbalance and we also want number of blocks to be evenly dividable across\n  // threads.\n  ParallelForBlock CalculateParallelForBlock(\n      const Index n, const TensorOpCost& cost,\n      std::function<Index(Index)> block_align) const {\n    const double block_size_f = 1.0 / CostModel::taskSize(1, cost);\n    const Index max_oversharding_factor = 4;\n    Index block_size = numext::mini(\n        n, numext::maxi<Index>(\n               divup<Index>(n, max_oversharding_factor * numThreads()),\n               block_size_f));\n    const Index max_block_size = numext::mini(n, 2 * block_size);\n\n    if (block_align) {\n      Index new_block_size = block_align(block_size);\n      eigen_assert(new_block_size >= block_size);\n      block_size = numext::mini(n, new_block_size);\n    }\n\n    Index block_count = divup(n, block_size);\n\n    // Calculate parallel efficiency as fraction of total CPU time used for\n    // computations:\n    double max_efficiency =\n        static_cast<double>(block_count) /\n        (divup<int>(block_count, numThreads()) * numThreads());\n\n    // Now try to increase block size up to max_block_size as long as it\n    // doesn't decrease parallel efficiency.\n    for (Index prev_block_count = block_count;\n         max_efficiency < 1.0 && prev_block_count > 1;) {\n      // This is the next block size that divides size into a smaller number\n      // of blocks than the current block_size.\n      Index coarser_block_size = divup(n, prev_block_count - 1);\n      if (block_align) {\n        Index new_block_size = block_align(coarser_block_size);\n        eigen_assert(new_block_size >= coarser_block_size);\n        coarser_block_size = numext::mini(n, new_block_size);\n      }\n      if (coarser_block_size > max_block_size) {\n        break;  // Reached max block size. Stop.\n      }\n      // Recalculate parallel efficiency.\n      const Index coarser_block_count = divup(n, coarser_block_size);\n      eigen_assert(coarser_block_count < prev_block_count);\n      prev_block_count = coarser_block_count;\n      const double coarser_efficiency =\n          static_cast<double>(coarser_block_count) /\n          (divup<int>(coarser_block_count, numThreads()) * numThreads());\n      if (coarser_efficiency + 0.01 >= max_efficiency) {\n        // Taking it.\n        block_size = coarser_block_size;\n        block_count = coarser_block_count;\n        if (max_efficiency < coarser_efficiency) {\n          max_efficiency = coarser_efficiency;\n        }\n      }\n    }\n\n    return {block_size, block_count};\n  }\n\n  ThreadPoolInterface* pool_;\n  int num_threads_;\n  Allocator* allocator_;\n};\n\n\n}  // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_DEVICE_THREAD_POOL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDimensionList.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_DIMENSION_LIST_H\n#define EIGEN_CXX11_TENSOR_TENSOR_DIMENSION_LIST_H\n\nnamespace Eigen {\n\n/** \\internal\n  *\n  * \\class TensorDimensionList\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Special case of tensor index list used to list all the dimensions of a tensor of rank n.\n  *\n  * \\sa Tensor\n  */\n\ntemplate <typename Index, std::size_t Rank> struct DimensionList {\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  const Index operator[] (const Index i) const { return i; }\n};\n\nnamespace internal {\n\ntemplate<typename Index, std::size_t Rank> struct array_size<DimensionList<Index, Rank> > {\n  static const size_t value = Rank;\n};\ntemplate<typename Index, std::size_t Rank> struct array_size<const DimensionList<Index, Rank> > {\n  static const size_t value = Rank;\n};\n\ntemplate<DenseIndex n, typename Index, std::size_t Rank> const Index array_get(DimensionList<Index, Rank>&) {\n  return n;\n}\ntemplate<DenseIndex n, typename Index, std::size_t Rank> const Index array_get(const DimensionList<Index, Rank>&) {\n  return n;\n}\n\n\n#if EIGEN_HAS_CONSTEXPR\ntemplate <typename Index, std::size_t Rank>\nstruct index_known_statically_impl<DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex) {\n    return true;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct index_known_statically_impl<const DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex) {\n    return true;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct all_indices_known_statically_impl<DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run() {\n    return true;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct all_indices_known_statically_impl<const DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run() {\n    return true;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct indices_statically_known_to_increase_impl<DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run() {\n    return true;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct indices_statically_known_to_increase_impl<const DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run() {\n    return true;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_eq_impl<DimensionList<Index, Rank> > {\n  static constexpr bool run(const DenseIndex i, const DenseIndex value) {\n    return i == value;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_eq_impl<const DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) {\n    return i == value;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_ne_impl<DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) {\n    return i != value;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_ne_impl<const DimensionList<Index, Rank> > {\n  static constexpr bool run(const DenseIndex i, const DenseIndex value) {\n    return i != value;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_gt_impl<DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) {\n    return i > value;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_gt_impl<const DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) {\n    return i > value;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_lt_impl<DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) {\n    return i < value;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_lt_impl<const DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) {\n    return i < value;\n  }\n};\n\n#else\ntemplate <typename Index, std::size_t Rank>\nstruct index_known_statically_impl<DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static EIGEN_ALWAYS_INLINE bool run(const DenseIndex) {\n    return true;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct index_known_statically_impl<const DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static EIGEN_ALWAYS_INLINE bool run(const DenseIndex) {\n    return true;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct all_indices_known_statically_impl<DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static EIGEN_ALWAYS_INLINE bool run() {\n    return true;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct all_indices_known_statically_impl<const DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static EIGEN_ALWAYS_INLINE bool run() {\n    return true;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct indices_statically_known_to_increase_impl<DimensionList<Index, Rank> > {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run() {\n    return true;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct indices_statically_known_to_increase_impl<const DimensionList<Index, Rank> > {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run() {\n    return true;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_eq_impl<DimensionList<Index, Rank> > {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) {\n    return false;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_eq_impl<const DimensionList<Index, Rank> > {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) {\n    return false;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_ne_impl<DimensionList<Index, Rank> > {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex){\n    return false;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_ne_impl<const DimensionList<Index, Rank> > {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) {\n    return false;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_gt_impl<DimensionList<Index, Rank> > {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) {\n    return false;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_gt_impl<const DimensionList<Index, Rank> > {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) {\n    return false;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_lt_impl<DimensionList<Index, Rank> > {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) {\n    return false;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_lt_impl<const DimensionList<Index, Rank> > {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) {\n    return false;\n  }\n};\n#endif\n\n}  // end namespace internal\n}  // end namespace Eigen\n\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_DIMENSION_LIST_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDimensions.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_DIMENSIONS_H\n#define EIGEN_CXX11_TENSOR_TENSOR_DIMENSIONS_H\n\n\nnamespace Eigen {\n\n/** \\internal\n  *\n  * \\class TensorDimensions\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Set of classes used to encode and store the dimensions of a Tensor.\n  *\n  * The Sizes class encodes as part of the type the number of dimensions and the\n  * sizes corresponding to each dimension. It uses no storage space since it is\n  * entirely known at compile time.\n  * The DSizes class is its dynamic sibling: the number of dimensions is known\n  * at compile time but the sizes are set during execution.\n  *\n  * \\sa Tensor\n  */\n\n// Boilerplate code\nnamespace internal {\n\ntemplate<std::ptrdiff_t n, typename Dimension> struct dget {\n  static const std::ptrdiff_t value = get<n, Dimension>::value;\n};\n\n\ntemplate<typename Index, std::ptrdiff_t NumIndices, std::ptrdiff_t n, bool RowMajor>\nstruct fixed_size_tensor_index_linearization_helper\n{\n  template <typename Dimensions> EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Index run(array<Index, NumIndices> const& indices,\n                          const Dimensions& dimensions)\n  {\n    return array_get<RowMajor ? n - 1 : (NumIndices - n)>(indices) +\n        dget<RowMajor ? n - 1 : (NumIndices - n), Dimensions>::value *\n        fixed_size_tensor_index_linearization_helper<Index, NumIndices, n - 1, RowMajor>::run(indices, dimensions);\n  }\n};\n\ntemplate<typename Index, std::ptrdiff_t NumIndices, bool RowMajor>\nstruct fixed_size_tensor_index_linearization_helper<Index, NumIndices, 0, RowMajor>\n{\n  template <typename Dimensions> EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Index run(array<Index, NumIndices> const&, const Dimensions&)\n  {\n    return 0;\n  }\n};\n\ntemplate<typename Index, std::ptrdiff_t n>\nstruct fixed_size_tensor_index_extraction_helper\n{\n  template <typename Dimensions> EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Index run(const Index index,\n                          const Dimensions& dimensions)\n  {\n    const Index mult = (index == n-1) ? 1 : 0;\n    return array_get<n-1>(dimensions) * mult +\n        fixed_size_tensor_index_extraction_helper<Index, n - 1>::run(index, dimensions);\n  }\n};\n\ntemplate<typename Index>\nstruct fixed_size_tensor_index_extraction_helper<Index, 0>\n{\n  template <typename Dimensions> EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Index run(const Index,\n                          const Dimensions&)\n  {\n    return 0;\n  }\n  };\n\n}  // end namespace internal\n\n\n// Fixed size\n#ifndef EIGEN_EMULATE_CXX11_META_H\ntemplate <typename std::ptrdiff_t... Indices>\nstruct Sizes {\n  typedef internal::numeric_list<std::ptrdiff_t, Indices...> Base;\n  const Base t = Base();\n  static const std::ptrdiff_t total_size = internal::arg_prod(Indices...);\n  static const ptrdiff_t count = Base::count;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t rank() const {\n    return Base::count;\n  }\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t TotalSize() {\n    return internal::arg_prod(Indices...);\n  }\n\n  EIGEN_DEVICE_FUNC Sizes() { }\n  template <typename DenseIndex>\n  explicit EIGEN_DEVICE_FUNC Sizes(const array<DenseIndex, Base::count>& /*indices*/) {\n    // todo: add assertion\n  }\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  template <typename... DenseIndex> EIGEN_DEVICE_FUNC Sizes(DenseIndex...) { }\n  explicit EIGEN_DEVICE_FUNC Sizes(std::initializer_list<std::ptrdiff_t> /*l*/) {\n    // todo: add assertion\n  }\n#endif\n\n  template <typename T> Sizes& operator = (const T& /*other*/) {\n    // add assertion failure if the size of other is different\n    return *this;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t operator[] (const std::ptrdiff_t index) const {\n    return internal::fixed_size_tensor_index_extraction_helper<std::ptrdiff_t, Base::count>::run(index, t);\n  }\n\n  template <typename DenseIndex> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  ptrdiff_t IndexOfColMajor(const array<DenseIndex, Base::count>& indices) const {\n    return internal::fixed_size_tensor_index_linearization_helper<DenseIndex, Base::count, Base::count, false>::run(indices, t);\n  }\n  template <typename DenseIndex> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  ptrdiff_t IndexOfRowMajor(const array<DenseIndex, Base::count>& indices) const {\n    return internal::fixed_size_tensor_index_linearization_helper<DenseIndex, Base::count, Base::count, true>::run(indices, t);\n  }\n};\n\nnamespace internal {\ntemplate <typename std::ptrdiff_t... Indices>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t array_prod(const Sizes<Indices...>&) {\n  return Sizes<Indices...>::total_size;\n}\n}\n\n#else\n\ntemplate <std::ptrdiff_t n>\nstruct non_zero_size {\n  typedef internal::type2val<std::ptrdiff_t, n> type;\n};\ntemplate <>\nstruct non_zero_size<0> {\n  typedef internal::null_type type;\n};\n\ntemplate <std::ptrdiff_t V1=0, std::ptrdiff_t V2=0, std::ptrdiff_t V3=0, std::ptrdiff_t V4=0, std::ptrdiff_t V5=0> struct Sizes {\n  typedef typename internal::make_type_list<typename non_zero_size<V1>::type, typename non_zero_size<V2>::type, typename non_zero_size<V3>::type, typename non_zero_size<V4>::type, typename non_zero_size<V5>::type >::type Base;\n  static const std::ptrdiff_t count = Base::count;\n  static const std::ptrdiff_t total_size = internal::arg_prod<Base>::value;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ptrdiff_t rank() const {\n    return count;\n  }\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ptrdiff_t TotalSize() {\n    return internal::arg_prod<Base>::value;\n  }\n\n  Sizes() { }\n  template <typename DenseIndex>\n  explicit Sizes(const array<DenseIndex, Base::count>& /*indices*/) {\n    // todo: add assertion\n  }\n  template <typename T> Sizes& operator = (const T& /*other*/) {\n    // add assertion failure if the size of other is different\n    return *this;\n  }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  template <typename... DenseIndex> Sizes(DenseIndex... /*indices*/) { }\n  explicit Sizes(std::initializer_list<std::ptrdiff_t>) {\n    // todo: add assertion\n  }\n#else\n  EIGEN_DEVICE_FUNC explicit Sizes(const DenseIndex) {\n  }\n  EIGEN_DEVICE_FUNC Sizes(const DenseIndex, const DenseIndex) {\n  }\n  EIGEN_DEVICE_FUNC Sizes(const DenseIndex, const DenseIndex, const DenseIndex) {\n  }\n  EIGEN_DEVICE_FUNC Sizes(const DenseIndex, const DenseIndex, const DenseIndex, const DenseIndex) {\n  }\n  EIGEN_DEVICE_FUNC Sizes(const DenseIndex, const DenseIndex, const DenseIndex, const DenseIndex, const DenseIndex) {\n  }\n#endif\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index operator[] (const Index index) const {\n    switch (index) {\n      case 0:\n        return internal::get<0, Base>::value;\n      case 1:\n        return internal::get<1, Base>::value;\n      case 2:\n        return internal::get<2, Base>::value;\n      case 3:\n        return internal::get<3, Base>::value;\n      case 4:\n        return internal::get<4, Base>::value;\n      default:\n        eigen_assert(false && \"index overflow\");\n        return static_cast<Index>(-1);\n    }\n  }\n\n  template <typename DenseIndex> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  ptrdiff_t IndexOfColMajor(const array<DenseIndex, Base::count>& indices) const {\n    return internal::fixed_size_tensor_index_linearization_helper<DenseIndex, Base::count, Base::count, false>::run(indices, *reinterpret_cast<const Base*>(this));\n  }\n  template <typename DenseIndex> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  ptrdiff_t IndexOfRowMajor(const array<DenseIndex, Base::count>& indices) const {\n    return internal::fixed_size_tensor_index_linearization_helper<DenseIndex, Base::count, Base::count, true>::run(indices, *reinterpret_cast<const Base*>(this));\n  }\n};\n\nnamespace internal {\ntemplate <std::ptrdiff_t V1, std::ptrdiff_t V2, std::ptrdiff_t V3, std::ptrdiff_t V4, std::ptrdiff_t V5>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t array_prod(const Sizes<V1, V2, V3, V4, V5>&) {\n  return Sizes<V1, V2, V3, V4, V5>::total_size;\n}\n}\n\n#endif\n\n// Boilerplate\nnamespace internal {\ntemplate<typename Index, std::ptrdiff_t NumIndices, std::ptrdiff_t n, bool RowMajor>\nstruct tensor_index_linearization_helper\n{\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  Index run(array<Index, NumIndices> const& indices, array<Index, NumIndices> const& dimensions)\n  {\n    return array_get<RowMajor ? n : (NumIndices - n - 1)>(indices) +\n      array_get<RowMajor ? n : (NumIndices - n - 1)>(dimensions) *\n        tensor_index_linearization_helper<Index, NumIndices, n - 1, RowMajor>::run(indices, dimensions);\n  }\n};\n\ntemplate<typename Index, std::ptrdiff_t NumIndices, bool RowMajor>\nstruct tensor_index_linearization_helper<Index, NumIndices, 0, RowMajor>\n{\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  Index run(array<Index, NumIndices> const& indices, array<Index, NumIndices> const&)\n  {\n    return array_get<RowMajor ? 0 : NumIndices - 1>(indices);\n  }\n};\n}  // end namespace internal\n\n\n\n// Dynamic size\ntemplate <typename DenseIndex, int NumDims>\nstruct DSizes : array<DenseIndex, NumDims> {\n  typedef array<DenseIndex, NumDims> Base;\n  static const int count = NumDims;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rank() const {\n    return NumDims;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex TotalSize() const {\n    return (NumDims == 0) ? 1 : internal::array_prod(*static_cast<const Base*>(this));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DSizes() {\n    for (int i = 0 ; i < NumDims; ++i) {\n      (*this)[i] = 0;\n    }\n  }\n  EIGEN_DEVICE_FUNC explicit DSizes(const array<DenseIndex, NumDims>& a) : Base(a) { }\n\n  EIGEN_DEVICE_FUNC explicit DSizes(const DenseIndex i0) {\n    eigen_assert(NumDims == 1);\n    (*this)[0] = i0;\n  }\n\n  EIGEN_DEVICE_FUNC DSizes(const DimensionList<DenseIndex, NumDims>& a) {\n    for (int i = 0 ; i < NumDims; ++i) {\n      (*this)[i] = a[i];\n    }\n  }\n\n  // Enable DSizes index type promotion only if we are promoting to the\n  // larger type, e.g. allow to promote dimensions of type int to long.\n  template<typename OtherIndex>\n  EIGEN_DEVICE_FUNC\n  explicit DSizes(const array<OtherIndex, NumDims>& other,\n                  // Default template parameters require c++11.\n                  typename internal::enable_if<\n                     internal::is_same<\n                         DenseIndex,\n                         typename internal::promote_index_type<\n                             DenseIndex,\n                             OtherIndex\n                         >::type\n                     >::value, void*>::type = 0) {\n    for (int i = 0; i < NumDims; ++i) {\n      (*this)[i] = static_cast<DenseIndex>(other[i]);\n    }\n  }\n\n#ifdef EIGEN_HAS_INDEX_LIST\n  template <typename FirstType, typename... OtherTypes>\n  EIGEN_DEVICE_FUNC\n  explicit DSizes(const Eigen::IndexList<FirstType, OtherTypes...>& dimensions) {\n    for (int i = 0; i < dimensions.count; ++i) {\n      (*this)[i] = dimensions[i];\n    }\n  }\n#endif\n\n#ifndef EIGEN_EMULATE_CXX11_META_H\n  template <typename std::ptrdiff_t... Indices>\n  EIGEN_DEVICE_FUNC DSizes(const Sizes<Indices...>& a) {\n    for (int i = 0 ; i < NumDims; ++i) {\n      (*this)[i] = a[i];\n    }\n  }\n#else\n  template <std::ptrdiff_t V1, std::ptrdiff_t V2, std::ptrdiff_t V3, std::ptrdiff_t V4, std::ptrdiff_t V5>\n  EIGEN_DEVICE_FUNC DSizes(const Sizes<V1, V2, V3, V4, V5>& a) {\n    for (int i = 0 ; i < NumDims; ++i) {\n      (*this)[i] = a[i];\n    }\n  }\n#endif\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  template<typename... IndexTypes> EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE explicit DSizes(DenseIndex firstDimension, DenseIndex secondDimension, IndexTypes... otherDimensions) : Base({{firstDimension, secondDimension, otherDimensions...}}) {\n    EIGEN_STATIC_ASSERT(sizeof...(otherDimensions) + 2 == NumDims, YOU_MADE_A_PROGRAMMING_MISTAKE)\n  }\n#else\n  EIGEN_DEVICE_FUNC DSizes(const DenseIndex i0, const DenseIndex i1) {\n    eigen_assert(NumDims == 2);\n    (*this)[0] = i0;\n    (*this)[1] = i1;\n  }\n  EIGEN_DEVICE_FUNC DSizes(const DenseIndex i0, const DenseIndex i1, const DenseIndex i2) {\n    eigen_assert(NumDims == 3);\n    (*this)[0] = i0;\n    (*this)[1] = i1;\n    (*this)[2] = i2;\n  }\n  EIGEN_DEVICE_FUNC DSizes(const DenseIndex i0, const DenseIndex i1, const DenseIndex i2, const DenseIndex i3) {\n    eigen_assert(NumDims == 4);\n    (*this)[0] = i0;\n    (*this)[1] = i1;\n    (*this)[2] = i2;\n    (*this)[3] = i3;\n  }\n  EIGEN_DEVICE_FUNC DSizes(const DenseIndex i0, const DenseIndex i1, const DenseIndex i2, const DenseIndex i3, const DenseIndex i4) {\n    eigen_assert(NumDims == 5);\n    (*this)[0] = i0;\n    (*this)[1] = i1;\n    (*this)[2] = i2;\n    (*this)[3] = i3;\n    (*this)[4] = i4;\n  }\n#endif\n\n  EIGEN_DEVICE_FUNC DSizes& operator = (const array<DenseIndex, NumDims>& other) {\n    *static_cast<Base*>(this) = other;\n    return *this;\n  }\n\n  // A constexpr would be so much better here\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex IndexOfColMajor(const array<DenseIndex, NumDims>& indices) const {\n    return internal::tensor_index_linearization_helper<DenseIndex, NumDims, NumDims - 1, false>::run(indices, *static_cast<const Base*>(this));\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex IndexOfRowMajor(const array<DenseIndex, NumDims>& indices) const {\n    return internal::tensor_index_linearization_helper<DenseIndex, NumDims, NumDims - 1, true>::run(indices, *static_cast<const Base*>(this));\n  }\n};\n\ntemplate <typename IndexType, int NumDims>\nstd::ostream& operator<<(std::ostream& os,\n                         const DSizes<IndexType, NumDims>& dims) {\n  os << \"[\";\n  for (int i = 0; i < NumDims; ++i) {\n    if (i > 0) os << \", \";\n    os << dims[i];\n  }\n  os << \"]\";\n  return os;\n}\n\n// Boilerplate\nnamespace internal {\ntemplate<typename Index, std::ptrdiff_t NumIndices, std::ptrdiff_t n, bool RowMajor>\nstruct tensor_vsize_index_linearization_helper\n{\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  Index run(array<Index, NumIndices> const& indices, std::vector<DenseIndex> const& dimensions)\n  {\n    return array_get<RowMajor ? n : (NumIndices - n - 1)>(indices) +\n      array_get<RowMajor ? n : (NumIndices - n - 1)>(dimensions) *\n        tensor_vsize_index_linearization_helper<Index, NumIndices, n - 1, RowMajor>::run(indices, dimensions);\n  }\n};\n\ntemplate<typename Index, std::ptrdiff_t NumIndices, bool RowMajor>\nstruct tensor_vsize_index_linearization_helper<Index, NumIndices, 0, RowMajor>\n{\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  Index run(array<Index, NumIndices> const& indices, std::vector<DenseIndex> const&)\n  {\n    return array_get<RowMajor ? 0 : NumIndices - 1>(indices);\n  }\n};\n}  // end namespace internal\n\n\nnamespace internal {\n\ntemplate <typename DenseIndex, int NumDims> struct array_size<const DSizes<DenseIndex, NumDims> > {\n  static const ptrdiff_t value = NumDims;\n};\ntemplate <typename DenseIndex, int NumDims> struct array_size<DSizes<DenseIndex, NumDims> > {\n  static const ptrdiff_t value = NumDims;\n};\n#ifndef EIGEN_EMULATE_CXX11_META_H\ntemplate <typename std::ptrdiff_t... Indices> struct array_size<const Sizes<Indices...> > {\nstatic const std::ptrdiff_t value = Sizes<Indices...>::count;\n};\ntemplate <typename std::ptrdiff_t... Indices> struct array_size<Sizes<Indices...> > {\nstatic const std::ptrdiff_t value = Sizes<Indices...>::count;\n};\ntemplate <std::ptrdiff_t n, typename std::ptrdiff_t... Indices> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t array_get(const Sizes<Indices...>&) {\n  return get<n, internal::numeric_list<std::ptrdiff_t, Indices...> >::value;\n}\ntemplate <std::ptrdiff_t n> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t array_get(const Sizes<>&) {\n  eigen_assert(false && \"should never be called\");\n  return -1;\n}\n#else\ntemplate <std::ptrdiff_t V1, std::ptrdiff_t V2, std::ptrdiff_t V3, std::ptrdiff_t V4, std::ptrdiff_t V5> struct array_size<const Sizes<V1,V2,V3,V4,V5> > {\n  static const ptrdiff_t value = Sizes<V1,V2,V3,V4,V5>::count;\n};\ntemplate <std::ptrdiff_t V1, std::ptrdiff_t V2, std::ptrdiff_t V3, std::ptrdiff_t V4, std::ptrdiff_t V5> struct array_size<Sizes<V1,V2,V3,V4,V5> > {\n  static const ptrdiff_t value = Sizes<V1,V2,V3,V4,V5>::count;\n};\ntemplate <std::ptrdiff_t n, std::ptrdiff_t V1, std::ptrdiff_t V2, std::ptrdiff_t V3, std::ptrdiff_t V4, std::ptrdiff_t V5> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t array_get(const Sizes<V1,V2,V3,V4,V5>&) {\n  return get<n, typename Sizes<V1,V2,V3,V4,V5>::Base>::value;\n}\n\n#endif\n\n\ntemplate <typename Dims1, typename Dims2, ptrdiff_t n, ptrdiff_t m>\nstruct sizes_match_below_dim {\n  static EIGEN_DEVICE_FUNC  EIGEN_STRONG_INLINE bool run(Dims1&, Dims2&) {\n    return false;\n  }\n};\ntemplate <typename Dims1, typename Dims2, ptrdiff_t n>\nstruct sizes_match_below_dim<Dims1, Dims2, n, n> {\n  static EIGEN_DEVICE_FUNC  EIGEN_STRONG_INLINE bool run(Dims1& dims1, Dims2& dims2) {\n    return (array_get<n-1>(dims1) == array_get<n-1>(dims2)) &&\n        sizes_match_below_dim<Dims1, Dims2, n-1, n-1>::run(dims1, dims2);\n  }\n};\ntemplate <typename Dims1, typename Dims2>\nstruct sizes_match_below_dim<Dims1, Dims2, 0, 0> {\n  static EIGEN_DEVICE_FUNC  EIGEN_STRONG_INLINE bool run(Dims1&, Dims2&) {\n    return true;\n  }\n};\n\n} // end namespace internal\n\n\ntemplate <typename Dims1, typename Dims2>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool dimensions_match(Dims1 dims1, Dims2 dims2) {\n  return internal::sizes_match_below_dim<Dims1, Dims2, internal::array_size<Dims1>::value, internal::array_size<Dims2>::value>::run(dims1, dims2);\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_DIMENSIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorEvalTo.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_EVAL_TO_H\n#define EIGEN_CXX11_TENSOR_TENSOR_EVAL_TO_H\n\nnamespace Eigen {\n\n/** \\class TensorForcedEval\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor reshaping class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename XprType, template <class> class MakePointer_>\nstruct traits<TensorEvalToOp<XprType, MakePointer_> >\n{\n  // Type promotion to handle the case where the types of the lhs and the rhs are different.\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename MakePointer_<Scalar>::Type PointerType;\n\n  enum {\n    Flags = 0\n  };\n  template <class T>\n  struct MakePointer {\n    // Intermediate typedef to workaround MSVC issue.\n    typedef MakePointer_<T> MakePointerT;\n    typedef typename MakePointerT::Type Type;\n\n\n  };\n};\n\ntemplate<typename XprType, template <class> class MakePointer_>\nstruct eval<TensorEvalToOp<XprType, MakePointer_>, Eigen::Dense>\n{\n  typedef const TensorEvalToOp<XprType, MakePointer_>& type;\n};\n\ntemplate<typename XprType, template <class> class MakePointer_>\nstruct nested<TensorEvalToOp<XprType, MakePointer_>, 1, typename eval<TensorEvalToOp<XprType, MakePointer_> >::type>\n{\n  typedef TensorEvalToOp<XprType, MakePointer_> type;\n};\n\n}  // end namespace internal\n\n\n\n\ntemplate<typename XprType, template <class> class MakePointer_>\nclass TensorEvalToOp : public TensorBase<TensorEvalToOp<XprType, MakePointer_>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorEvalToOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename internal::remove_const<typename XprType::CoeffReturnType>::type CoeffReturnType;\n  typedef typename MakePointer_<CoeffReturnType>::Type PointerType;\n  typedef typename Eigen::internal::nested<TensorEvalToOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorEvalToOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorEvalToOp>::Index Index;\n\n  static const int NumDims = Eigen::internal::traits<TensorEvalToOp>::NumDimensions;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvalToOp(PointerType buffer, const XprType& expr)\n      : m_xpr(expr), m_buffer(buffer) {}\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n    EIGEN_DEVICE_FUNC PointerType buffer() const { return m_buffer; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    PointerType m_buffer;\n};\n\n\n\ntemplate<typename ArgType, typename Device, template <class> class MakePointer_>\nstruct TensorEvaluator<const TensorEvalToOp<ArgType, MakePointer_>, Device>\n{\n  typedef TensorEvalToOp<ArgType, MakePointer_> XprType;\n  typedef typename ArgType::Scalar Scalar;\n  typedef typename TensorEvaluator<ArgType, Device>::Dimensions Dimensions;\n  typedef typename XprType::Index Index;\n  typedef typename internal::remove_const<typename XprType::CoeffReturnType>::type CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef typename Eigen::internal::traits<XprType>::PointerType TensorPointerType;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n  enum {\n    IsAligned         = TensorEvaluator<ArgType, Device>::IsAligned,\n    PacketAccess      = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess       = true,\n    PreferBlockAccess = false,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = true\n  };\n\n  static const int NumDims = internal::traits<ArgType>::NumDimensions;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename TensorEvaluator<const ArgType, Device>::TensorBlock\n      ArgTensorBlock;\n\n  typedef internal::TensorBlockAssignment<\n      CoeffReturnType, NumDims, typename ArgTensorBlock::XprType, Index>\n      TensorBlockAssignment;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device), m_buffer(device.get(op.buffer())), m_expression(op.expression()){}\n\n\n  EIGEN_STRONG_INLINE ~TensorEvaluator() {\n  }\n\n\n  EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_impl.dimensions(); }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType scalar) {\n    EIGEN_UNUSED_VARIABLE(scalar);\n    eigen_assert(scalar == NULL);\n    return m_impl.evalSubExprsIfNeeded(m_buffer);\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType scalar, EvalSubExprsCallback done) {\n    EIGEN_UNUSED_VARIABLE(scalar);\n    eigen_assert(scalar == NULL);\n    m_impl.evalSubExprsIfNeededAsync(m_buffer, std::move(done));\n  }\n#endif\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalScalar(Index i) {\n    m_buffer[i] = m_impl.coeff(i);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalPacket(Index i) {\n    internal::pstoret<CoeffReturnType, PacketReturnType, Aligned>(m_buffer + i, m_impl.template packet<TensorEvaluator<ArgType, Device>::IsAligned ? Aligned : Unaligned>(i));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    return m_impl.getResourceRequirements();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalBlock(\n      TensorBlockDesc& desc, TensorBlockScratch& scratch) {\n    // Add `m_buffer` as destination buffer to the block descriptor.\n    desc.template AddDestinationBuffer<Layout>(\n        /*dst_base=*/m_buffer + desc.offset(),\n        /*dst_strides=*/internal::strides<Layout>(m_impl.dimensions()));\n\n    ArgTensorBlock block =\n        m_impl.block(desc, scratch, /*root_of_expr_ast=*/true);\n\n    // If block was evaluated into a destination buffer, there is no need to do\n    // an assignment.\n    if (block.kind() != internal::TensorBlockKind::kMaterializedInOutput) {\n      TensorBlockAssignment::Run(\n          TensorBlockAssignment::target(\n              desc.dimensions(), internal::strides<Layout>(m_impl.dimensions()),\n              m_buffer, desc.offset()),\n          block.expr());\n    }\n    block.cleanup();\n  }\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    return m_buffer[index];\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    return internal::ploadt<PacketReturnType, LoadMode>(m_buffer + index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    // We assume that evalPacket or evalScalar is called to perform the\n    // assignment and account for the cost of the write here.\n    return m_impl.costPerCoeff(vectorized) +\n        TensorOpCost(0, sizeof(CoeffReturnType), 0, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return m_buffer; }\n  ArgType expression() const { return m_expression; }\n  #ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n    m_buffer.bind(cgh);\n  }\n  #endif\n\n\n private:\n  TensorEvaluator<ArgType, Device> m_impl;\n  EvaluatorPointerType m_buffer;\n  const ArgType m_expression;\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_EVAL_TO_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorEvaluator.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_EVALUATOR_H\n#define EIGEN_CXX11_TENSOR_TENSOR_EVALUATOR_H\n\nnamespace Eigen {\n\n/** \\class TensorEvaluator\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief The tensor evaluator classes.\n  *\n  * These classes are responsible for the evaluation of the tensor expression.\n  *\n  * TODO: add support for more types of expressions, in particular expressions\n  * leading to lvalues (slicing, reshaping, etc...)\n  */\n\n// Generic evaluator\ntemplate<typename Derived, typename Device>\nstruct TensorEvaluator\n{\n  typedef typename Derived::Index Index;\n  typedef typename Derived::Scalar Scalar;\n  typedef typename Derived::Scalar CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef typename Derived::Dimensions Dimensions;\n  typedef Derived XprType;\n  static const int PacketSize =  PacketType<CoeffReturnType, Device>::size;\n  typedef typename internal::traits<Derived>::template MakePointer<Scalar>::Type TensorPointerType;\n  typedef StorageMemory<Scalar, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  // NumDimensions is -1 for variable dim tensors\n  static const int NumCoords = internal::traits<Derived>::NumDimensions > 0 ?\n                               internal::traits<Derived>::NumDimensions : 0;\n\n  enum {\n    IsAligned          = Derived::IsAligned,\n    PacketAccess       = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess        = internal::is_arithmetic<typename internal::remove_const<Scalar>::type>::value,\n    PreferBlockAccess  = false,\n    Layout             = Derived::Layout,\n    CoordAccess        = NumCoords > 0,\n    RawAccess          = true\n  };\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumCoords, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename internal::TensorMaterializedBlock<ScalarNoConst, NumCoords,\n                                                     Layout, Index>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const Derived& m, const Device& device)\n      : m_data(device.get((const_cast<TensorPointerType>(m.data())))),\n        m_dims(m.dimensions()),\n        m_device(device)\n  { }\n\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dims; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType dest) {\n    if (!NumTraits<typename internal::remove_const<Scalar>::type>::RequireInitialization && dest) {\n      m_device.memcpy((void*)(m_device.get(dest)), m_device.get(m_data), m_dims.TotalSize() * sizeof(Scalar));\n      return false;\n    }\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType dest, EvalSubExprsCallback done) {\n    // TODO(ezhulenev): ThreadPoolDevice memcpy is blockign operation.\n    done(evalSubExprsIfNeeded(dest));\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_STRONG_INLINE void cleanup() {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const {\n    eigen_assert(m_data != NULL);\n    return m_data[index];\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index) {\n    eigen_assert(m_data != NULL);\n    return m_data[index];\n  }\n\n  template<int LoadMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  PacketReturnType packet(Index index) const\n  {\n    return internal::ploadt<PacketReturnType, LoadMode>(m_data + index);\n  }\n\n  // Return a packet starting at `index` where `umask` specifies which elements\n  // have to be loaded. Type/size of mask depends on PacketReturnType, e.g. for\n  // Packet16f, `umask` is of type uint16_t and if a bit is 1, corresponding\n  // float element will be loaded, otherwise 0 will be loaded.\n  // Function has been templatized to enable Sfinae.\n  template <typename PacketReturnTypeT> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  typename internal::enable_if<internal::unpacket_traits<PacketReturnTypeT>::masked_load_available, PacketReturnTypeT>::type\n  partialPacket(Index index, typename internal::unpacket_traits<PacketReturnTypeT>::mask_t umask) const\n  {\n    return internal::ploadu<PacketReturnTypeT>(m_data + index, umask);\n  }\n\n  template <int StoreMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void writePacket(Index index, const PacketReturnType& x)\n  {\n    return internal::pstoret<Scalar, PacketReturnType, StoreMode>(m_data + index, x);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(const array<DenseIndex, NumCoords>& coords) const {\n    eigen_assert(m_data != NULL);\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      return m_data[m_dims.IndexOfColMajor(coords)];\n    } else {\n      return m_data[m_dims.IndexOfRowMajor(coords)];\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType&\n  coeffRef(const array<DenseIndex, NumCoords>& coords) {\n    eigen_assert(m_data != NULL);\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      return m_data[m_dims.IndexOfColMajor(coords)];\n    } else {\n      return m_data[m_dims.IndexOfRowMajor(coords)];\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized,\n                        PacketType<CoeffReturnType, Device>::size);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    return internal::TensorBlockResourceRequirements::any();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    assert(m_data != NULL);\n    return TensorBlock::materialize(m_data, m_dims, desc, scratch);\n  }\n\n  template<typename TensorBlock>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void writeBlock(\n      const TensorBlockDesc& desc, const TensorBlock& block) {\n    assert(m_data != NULL);\n\n    typedef typename TensorBlock::XprType TensorBlockExpr;\n    typedef internal::TensorBlockAssignment<Scalar, NumCoords, TensorBlockExpr,\n                                            Index>\n        TensorBlockAssign;\n\n    TensorBlockAssign::Run(\n        TensorBlockAssign::target(desc.dimensions(),\n                                  internal::strides<Layout>(m_dims), m_data,\n                                  desc.offset()),\n        block.expr());\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return m_data; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_data.bind(cgh);\n  }\n#endif\n protected:\n  EvaluatorPointerType m_data;\n  Dimensions m_dims;\n  const Device EIGEN_DEVICE_REF m_device;\n};\n\nnamespace {\ntemplate <typename T> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nT loadConstant(const T* address) {\n  return *address;\n}\n// Use the texture cache on CUDA devices whenever possible\n#if defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 350\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nfloat loadConstant(const float* address) {\n  return __ldg(address);\n}\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\ndouble loadConstant(const double* address) {\n  return __ldg(address);\n}\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nEigen::half loadConstant(const Eigen::half* address) {\n  return Eigen::half(half_impl::raw_uint16_to_half(__ldg(&address->x)));\n}\n#endif\n#ifdef EIGEN_USE_SYCL\n// overload of load constant should be implemented here based on range access\ntemplate <cl::sycl::access::mode AcMd, typename T>\nT &loadConstant(const Eigen::TensorSycl::internal::RangeAccess<AcMd, T> &address) {\n  return *address;\n}\n#endif\n}\n\n\n// Default evaluator for rvalues\ntemplate<typename Derived, typename Device>\nstruct TensorEvaluator<const Derived, Device>\n{\n  typedef typename Derived::Index Index;\n  typedef typename Derived::Scalar Scalar;\n  typedef typename Derived::Scalar CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef typename Derived::Dimensions Dimensions;\n  typedef const Derived XprType;\n  typedef typename internal::traits<Derived>::template MakePointer<const Scalar>::Type TensorPointerType;\n  typedef StorageMemory<const Scalar, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  // NumDimensions is -1 for variable dim tensors\n  static const int NumCoords = internal::traits<Derived>::NumDimensions > 0 ?\n                               internal::traits<Derived>::NumDimensions : 0;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n\n  enum {\n    IsAligned         = Derived::IsAligned,\n    PacketAccess      = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess       = internal::is_arithmetic<ScalarNoConst>::value,\n    PreferBlockAccess = false,\n    Layout            = Derived::Layout,\n    CoordAccess       = NumCoords > 0,\n    RawAccess         = true\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumCoords, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename internal::TensorMaterializedBlock<ScalarNoConst, NumCoords,\n                                                     Layout, Index>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const Derived& m, const Device& device)\n      : m_data(device.get(m.data())), m_dims(m.dimensions()), m_device(device)\n  { }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dims; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    if (!NumTraits<typename internal::remove_const<Scalar>::type>::RequireInitialization && data) {\n      m_device.memcpy((void*)(m_device.get(data)),m_device.get(m_data), m_dims.TotalSize() * sizeof(Scalar));\n      return false;\n    }\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType dest, EvalSubExprsCallback done) {\n    // TODO(ezhulenev): ThreadPoolDevice memcpy is a blockign operation.\n    done(evalSubExprsIfNeeded(dest));\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_STRONG_INLINE void cleanup() { }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const {\n    eigen_assert(m_data != NULL);\n    return loadConstant(m_data+index);\n  }\n\n  template<int LoadMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  PacketReturnType packet(Index index) const\n  {\n    return internal::ploadt_ro<PacketReturnType, LoadMode>(m_data + index);\n  }\n\n  // Return a packet starting at `index` where `umask` specifies which elements\n  // have to be loaded. Type/size of mask depends on PacketReturnType, e.g. for\n  // Packet16f, `umask` is of type uint16_t and if a bit is 1, corresponding\n  // float element will be loaded, otherwise 0 will be loaded.\n  // Function has been templatized to enable Sfinae.\n  template <typename PacketReturnTypeT> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  typename internal::enable_if<internal::unpacket_traits<PacketReturnTypeT>::masked_load_available, PacketReturnTypeT>::type\n  partialPacket(Index index, typename internal::unpacket_traits<PacketReturnTypeT>::mask_t umask) const\n  {\n    return internal::ploadu<PacketReturnTypeT>(m_data + index, umask);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(const array<DenseIndex, NumCoords>& coords) const {\n    eigen_assert(m_data != NULL);\n    const Index index = (static_cast<int>(Layout) == static_cast<int>(ColMajor)) ? m_dims.IndexOfColMajor(coords)\n                        : m_dims.IndexOfRowMajor(coords);\n    return loadConstant(m_data+index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized,\n                        PacketType<CoeffReturnType, Device>::size);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    return internal::TensorBlockResourceRequirements::any();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    assert(m_data != NULL);\n    return TensorBlock::materialize(m_data, m_dims, desc, scratch);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return m_data; }\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_data.bind(cgh);\n  }\n#endif\n protected:\n  EvaluatorPointerType m_data;\n  Dimensions m_dims;\n  const Device EIGEN_DEVICE_REF m_device;\n};\n\n\n\n\n// -------------------- CwiseNullaryOp --------------------\n\ntemplate<typename NullaryOp, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorCwiseNullaryOp<NullaryOp, ArgType>, Device>\n{\n  typedef TensorCwiseNullaryOp<NullaryOp, ArgType> XprType;\n\n  TensorEvaluator(const XprType& op, const Device& device)\n      : m_functor(op.functor()), m_argImpl(op.nestedExpression(), device), m_wrapper()\n  { }\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename internal::traits<XprType>::Scalar CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef typename TensorEvaluator<ArgType, Device>::Dimensions Dimensions;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = true,\n    PacketAccess = internal::functor_traits<NullaryOp>::PacketAccess\n    #ifdef EIGEN_USE_SYCL\n    &&  (PacketType<CoeffReturnType, Device>::size >1)\n    #endif\n    ,\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_argImpl.dimensions(); }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) { return true; }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    done(true);\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_STRONG_INLINE void cleanup() { }\n\n  EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const\n  {\n    return m_wrapper(m_functor, index);\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    return m_wrapper.template packetOp<PacketReturnType, Index>(m_functor, index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized,\n                        PacketType<CoeffReturnType, Device>::size);\n  }\n\n  EIGEN_DEVICE_FUNC  EvaluatorPointerType data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n   // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_argImpl.bind(cgh);\n  }\n#endif\n\n private:\n  const NullaryOp m_functor;\n  TensorEvaluator<ArgType, Device> m_argImpl;\n  const internal::nullary_wrapper<CoeffReturnType,NullaryOp> m_wrapper;\n};\n\n\n\n// -------------------- CwiseUnaryOp --------------------\n\ntemplate<typename UnaryOp, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorCwiseUnaryOp<UnaryOp, ArgType>, Device>\n{\n  typedef TensorCwiseUnaryOp<UnaryOp, ArgType> XprType;\n\n  enum {\n    IsAligned          = TensorEvaluator<ArgType, Device>::IsAligned,\n    PacketAccess       = int(TensorEvaluator<ArgType, Device>::PacketAccess) &\n                         int(internal::functor_traits<UnaryOp>::PacketAccess),\n    BlockAccess        = TensorEvaluator<ArgType, Device>::BlockAccess,\n    PreferBlockAccess  = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout             = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess        = false,  // to be implemented\n    RawAccess          = false\n  };\n\n  TensorEvaluator(const XprType& op, const Device& device)\n    : m_device(device),\n      m_functor(op.functor()),\n      m_argImpl(op.nestedExpression(), device)\n  { }\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n  typedef typename internal::traits<XprType>::Scalar CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef typename TensorEvaluator<ArgType, Device>::Dimensions Dimensions;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n  static const int NumDims = internal::array_size<Dimensions>::value;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename TensorEvaluator<const ArgType, Device>::TensorBlock\n      ArgTensorBlock;\n\n  typedef internal::TensorCwiseUnaryBlock<UnaryOp, ArgTensorBlock>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_argImpl.dimensions(); }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    m_argImpl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    m_argImpl.evalSubExprsIfNeededAsync(nullptr, [done](bool) { done(true); });\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_argImpl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const\n  {\n    return m_functor(m_argImpl.coeff(index));\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    return m_functor.packetOp(m_argImpl.template packet<LoadMode>(index));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    const double functor_cost = internal::functor_traits<UnaryOp>::Cost;\n    return m_argImpl.costPerCoeff(vectorized) +\n        TensorOpCost(0, 0, functor_cost, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    static const double functor_cost = internal::functor_traits<UnaryOp>::Cost;\n    return m_argImpl.getResourceRequirements().addCostPerCoeff(\n        {0, 0, functor_cost / PacketSize});\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    return TensorBlock(m_argImpl.block(desc, scratch), m_functor);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const{\n    m_argImpl.bind(cgh);\n  }\n#endif\n\n\n private:\n  const Device EIGEN_DEVICE_REF m_device;\n  const UnaryOp m_functor;\n  TensorEvaluator<ArgType, Device> m_argImpl;\n};\n\n\n// -------------------- CwiseBinaryOp --------------------\n\ntemplate<typename BinaryOp, typename LeftArgType, typename RightArgType, typename Device>\nstruct TensorEvaluator<const TensorCwiseBinaryOp<BinaryOp, LeftArgType, RightArgType>, Device>\n{\n  typedef TensorCwiseBinaryOp<BinaryOp, LeftArgType, RightArgType> XprType;\n\n  enum {\n    IsAligned         = int(TensorEvaluator<LeftArgType, Device>::IsAligned) &\n                        int(TensorEvaluator<RightArgType, Device>::IsAligned),\n    PacketAccess      = int(TensorEvaluator<LeftArgType, Device>::PacketAccess) &\n                        int(TensorEvaluator<RightArgType, Device>::PacketAccess) &\n                        int(internal::functor_traits<BinaryOp>::PacketAccess),\n    BlockAccess       = int(TensorEvaluator<LeftArgType, Device>::BlockAccess) &\n                        int(TensorEvaluator<RightArgType, Device>::BlockAccess),\n    PreferBlockAccess = int(TensorEvaluator<LeftArgType, Device>::PreferBlockAccess) |\n                        int(TensorEvaluator<RightArgType, Device>::PreferBlockAccess),\n    Layout            = TensorEvaluator<LeftArgType, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = false\n  };\n\n  TensorEvaluator(const XprType& op, const Device& device)\n    : m_device(device),\n      m_functor(op.functor()),\n      m_leftImpl(op.lhsExpression(), device),\n      m_rightImpl(op.rhsExpression(), device)\n  {\n    EIGEN_STATIC_ASSERT((static_cast<int>(TensorEvaluator<LeftArgType, Device>::Layout) == static_cast<int>(TensorEvaluator<RightArgType, Device>::Layout) || internal::traits<XprType>::NumDimensions <= 1), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    eigen_assert(dimensions_match(m_leftImpl.dimensions(), m_rightImpl.dimensions()));\n  }\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename internal::traits<XprType>::Scalar CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef typename TensorEvaluator<LeftArgType, Device>::Dimensions Dimensions;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  static const int NumDims = internal::array_size<\n      typename TensorEvaluator<LeftArgType, Device>::Dimensions>::value;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename TensorEvaluator<const LeftArgType, Device>::TensorBlock\n      LeftTensorBlock;\n  typedef typename TensorEvaluator<const RightArgType, Device>::TensorBlock\n      RightTensorBlock;\n\n  typedef internal::TensorCwiseBinaryBlock<BinaryOp, LeftTensorBlock,\n                                           RightTensorBlock>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC const Dimensions& dimensions() const\n  {\n    // TODO: use right impl instead if right impl dimensions are known at compile time.\n    return m_leftImpl.dimensions();\n  }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    m_leftImpl.evalSubExprsIfNeeded(NULL);\n    m_rightImpl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    // TODO(ezhulenev): Evaluate two expression in parallel?\n    m_leftImpl.evalSubExprsIfNeededAsync(nullptr, [this, done](bool) {\n      m_rightImpl.evalSubExprsIfNeededAsync(nullptr,\n                                            [done](bool) { done(true); });\n    });\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_leftImpl.cleanup();\n    m_rightImpl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const\n  {\n    return m_functor(m_leftImpl.coeff(index), m_rightImpl.coeff(index));\n  }\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    return m_functor.packetOp(m_leftImpl.template packet<LoadMode>(index), m_rightImpl.template packet<LoadMode>(index));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    const double functor_cost = internal::functor_traits<BinaryOp>::Cost;\n    return m_leftImpl.costPerCoeff(vectorized) +\n           m_rightImpl.costPerCoeff(vectorized) +\n           TensorOpCost(0, 0, functor_cost, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    static const double functor_cost = internal::functor_traits<BinaryOp>::Cost;\n    return internal::TensorBlockResourceRequirements::merge(\n               m_leftImpl.getResourceRequirements(),\n               m_rightImpl.getResourceRequirements())\n        .addCostPerCoeff({0, 0, functor_cost / PacketSize});\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    desc.DropDestinationBuffer();\n    return TensorBlock(m_leftImpl.block(desc, scratch),\n                         m_rightImpl.block(desc, scratch), m_functor);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n  #ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_leftImpl.bind(cgh);\n    m_rightImpl.bind(cgh);\n  }\n  #endif\n private:\n  const Device EIGEN_DEVICE_REF m_device;\n  const BinaryOp m_functor;\n  TensorEvaluator<LeftArgType, Device> m_leftImpl;\n  TensorEvaluator<RightArgType, Device> m_rightImpl;\n};\n\n// -------------------- CwiseTernaryOp --------------------\n\ntemplate<typename TernaryOp, typename Arg1Type, typename Arg2Type, typename Arg3Type, typename Device>\nstruct TensorEvaluator<const TensorCwiseTernaryOp<TernaryOp, Arg1Type, Arg2Type, Arg3Type>, Device>\n{\n  typedef TensorCwiseTernaryOp<TernaryOp, Arg1Type, Arg2Type, Arg3Type> XprType;\n\n  enum {\n    IsAligned = TensorEvaluator<Arg1Type, Device>::IsAligned & TensorEvaluator<Arg2Type, Device>::IsAligned & TensorEvaluator<Arg3Type, Device>::IsAligned,\n    PacketAccess      = TensorEvaluator<Arg1Type, Device>::PacketAccess &&\n                        TensorEvaluator<Arg2Type, Device>::PacketAccess &&\n                        TensorEvaluator<Arg3Type, Device>::PacketAccess &&\n                        internal::functor_traits<TernaryOp>::PacketAccess,\n    BlockAccess       = false,\n    PreferBlockAccess = TensorEvaluator<Arg1Type, Device>::PreferBlockAccess ||\n                        TensorEvaluator<Arg2Type, Device>::PreferBlockAccess ||\n                        TensorEvaluator<Arg3Type, Device>::PreferBlockAccess,\n    Layout            = TensorEvaluator<Arg1Type, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = false\n  };\n\n  TensorEvaluator(const XprType& op, const Device& device)\n    : m_functor(op.functor()),\n      m_arg1Impl(op.arg1Expression(), device),\n      m_arg2Impl(op.arg2Expression(), device),\n      m_arg3Impl(op.arg3Expression(), device)\n  {\n    EIGEN_STATIC_ASSERT((static_cast<int>(TensorEvaluator<Arg1Type, Device>::Layout) == static_cast<int>(TensorEvaluator<Arg3Type, Device>::Layout) || internal::traits<XprType>::NumDimensions <= 1), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    EIGEN_STATIC_ASSERT((internal::is_same<typename internal::traits<Arg1Type>::StorageKind,\n                         typename internal::traits<Arg2Type>::StorageKind>::value),\n                        STORAGE_KIND_MUST_MATCH)\n    EIGEN_STATIC_ASSERT((internal::is_same<typename internal::traits<Arg1Type>::StorageKind,\n                         typename internal::traits<Arg3Type>::StorageKind>::value),\n                        STORAGE_KIND_MUST_MATCH)\n    EIGEN_STATIC_ASSERT((internal::is_same<typename internal::traits<Arg1Type>::Index,\n                         typename internal::traits<Arg2Type>::Index>::value),\n                        STORAGE_INDEX_MUST_MATCH)\n    EIGEN_STATIC_ASSERT((internal::is_same<typename internal::traits<Arg1Type>::Index,\n                         typename internal::traits<Arg3Type>::Index>::value),\n                        STORAGE_INDEX_MUST_MATCH)\n\n    eigen_assert(dimensions_match(m_arg1Impl.dimensions(), m_arg2Impl.dimensions()) && dimensions_match(m_arg1Impl.dimensions(), m_arg3Impl.dimensions()));\n  }\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename internal::traits<XprType>::Scalar CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef typename TensorEvaluator<Arg1Type, Device>::Dimensions Dimensions;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC const Dimensions& dimensions() const\n  {\n    // TODO: use arg2 or arg3 dimensions if they are known at compile time.\n    return m_arg1Impl.dimensions();\n  }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    m_arg1Impl.evalSubExprsIfNeeded(NULL);\n    m_arg2Impl.evalSubExprsIfNeeded(NULL);\n    m_arg3Impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_arg1Impl.cleanup();\n    m_arg2Impl.cleanup();\n    m_arg3Impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const\n  {\n    return m_functor(m_arg1Impl.coeff(index), m_arg2Impl.coeff(index), m_arg3Impl.coeff(index));\n  }\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    return m_functor.packetOp(m_arg1Impl.template packet<LoadMode>(index),\n                              m_arg2Impl.template packet<LoadMode>(index),\n                              m_arg3Impl.template packet<LoadMode>(index));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    const double functor_cost = internal::functor_traits<TernaryOp>::Cost;\n    return m_arg1Impl.costPerCoeff(vectorized) +\n           m_arg2Impl.costPerCoeff(vectorized) +\n           m_arg3Impl.costPerCoeff(vectorized) +\n           TensorOpCost(0, 0, functor_cost, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n   // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_arg1Impl.bind(cgh);\n    m_arg2Impl.bind(cgh);\n    m_arg3Impl.bind(cgh);\n  }\n#endif\n\n private:\n  const TernaryOp m_functor;\n  TensorEvaluator<Arg1Type, Device> m_arg1Impl;\n  TensorEvaluator<Arg2Type, Device> m_arg2Impl;\n  TensorEvaluator<Arg3Type, Device> m_arg3Impl;\n};\n\n\n// -------------------- SelectOp --------------------\n\ntemplate<typename IfArgType, typename ThenArgType, typename ElseArgType, typename Device>\nstruct TensorEvaluator<const TensorSelectOp<IfArgType, ThenArgType, ElseArgType>, Device>\n{\n  typedef TensorSelectOp<IfArgType, ThenArgType, ElseArgType> XprType;\n  typedef typename XprType::Scalar Scalar;\n\n  enum {\n    IsAligned         = TensorEvaluator<ThenArgType, Device>::IsAligned &\n                        TensorEvaluator<ElseArgType, Device>::IsAligned,\n    PacketAccess      = TensorEvaluator<ThenArgType, Device>::PacketAccess &\n                        TensorEvaluator<ElseArgType, Device>::PacketAccess &\n                        PacketType<Scalar, Device>::HasBlend,\n    BlockAccess       = TensorEvaluator<IfArgType, Device>::BlockAccess &&\n                        TensorEvaluator<ThenArgType, Device>::BlockAccess &&\n                        TensorEvaluator<ElseArgType, Device>::BlockAccess,\n    PreferBlockAccess = TensorEvaluator<IfArgType, Device>::PreferBlockAccess ||\n                        TensorEvaluator<ThenArgType, Device>::PreferBlockAccess ||\n                        TensorEvaluator<ElseArgType, Device>::PreferBlockAccess,\n    Layout            = TensorEvaluator<IfArgType, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = false\n  };\n\n  TensorEvaluator(const XprType& op, const Device& device)\n    : m_condImpl(op.ifExpression(), device),\n      m_thenImpl(op.thenExpression(), device),\n      m_elseImpl(op.elseExpression(), device)\n  {\n    EIGEN_STATIC_ASSERT((static_cast<int>(TensorEvaluator<IfArgType, Device>::Layout) == static_cast<int>(TensorEvaluator<ThenArgType, Device>::Layout)), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    EIGEN_STATIC_ASSERT((static_cast<int>(TensorEvaluator<IfArgType, Device>::Layout) == static_cast<int>(TensorEvaluator<ElseArgType, Device>::Layout)), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    eigen_assert(dimensions_match(m_condImpl.dimensions(), m_thenImpl.dimensions()));\n    eigen_assert(dimensions_match(m_thenImpl.dimensions(), m_elseImpl.dimensions()));\n  }\n\n  typedef typename XprType::Index Index;\n  typedef typename internal::traits<XprType>::Scalar CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef typename TensorEvaluator<IfArgType, Device>::Dimensions Dimensions;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  static const int NumDims = internal::array_size<Dimensions>::value;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n    typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename TensorEvaluator<const IfArgType, Device>::TensorBlock\n      IfArgTensorBlock;\n  typedef typename TensorEvaluator<const ThenArgType, Device>::TensorBlock\n      ThenArgTensorBlock;\n  typedef typename TensorEvaluator<const ElseArgType, Device>::TensorBlock\n      ElseArgTensorBlock;\n\n  struct TensorSelectOpBlockFactory {\n    template <typename IfArgXprType, typename ThenArgXprType, typename ElseArgXprType>\n    struct XprType {\n      typedef TensorSelectOp<const IfArgXprType, const ThenArgXprType, const ElseArgXprType> type;\n    };\n\n    template <typename IfArgXprType, typename ThenArgXprType, typename ElseArgXprType>\n    typename XprType<IfArgXprType, ThenArgXprType, ElseArgXprType>::type expr(\n        const IfArgXprType& if_expr, const ThenArgXprType& then_expr, const ElseArgXprType& else_expr) const {\n      return typename XprType<IfArgXprType, ThenArgXprType, ElseArgXprType>::type(if_expr, then_expr, else_expr);\n    }\n  };\n\n  typedef internal::TensorTernaryExprBlock<TensorSelectOpBlockFactory,\n                                           IfArgTensorBlock, ThenArgTensorBlock,\n                                           ElseArgTensorBlock>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC const Dimensions& dimensions() const\n  {\n    // TODO: use then or else impl instead if they happen to be known at compile time.\n    return m_condImpl.dimensions();\n  }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    m_condImpl.evalSubExprsIfNeeded(NULL);\n    m_thenImpl.evalSubExprsIfNeeded(NULL);\n    m_elseImpl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    m_condImpl.evalSubExprsIfNeeded(nullptr, [this, done](bool) {\n      m_thenImpl.evalSubExprsIfNeeded(nullptr, [this, done](bool) {\n        m_elseImpl.evalSubExprsIfNeeded(nullptr, [done](bool) { done(true); });\n      });\n    });\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_condImpl.cleanup();\n    m_thenImpl.cleanup();\n    m_elseImpl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const\n  {\n    return m_condImpl.coeff(index) ? m_thenImpl.coeff(index) : m_elseImpl.coeff(index);\n  }\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC PacketReturnType packet(Index index) const\n  {\n     internal::Selector<PacketSize> select;\n     EIGEN_UNROLL_LOOP\n     for (Index i = 0; i < PacketSize; ++i) {\n       select.select[i] = m_condImpl.coeff(index+i);\n     }\n     return internal::pblend(select,\n                             m_thenImpl.template packet<LoadMode>(index),\n                             m_elseImpl.template packet<LoadMode>(index));\n\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    return m_condImpl.costPerCoeff(vectorized) +\n           m_thenImpl.costPerCoeff(vectorized)\n        .cwiseMax(m_elseImpl.costPerCoeff(vectorized));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    auto then_req = m_thenImpl.getResourceRequirements();\n    auto else_req = m_elseImpl.getResourceRequirements();\n\n    auto merged_req =\n        internal::TensorBlockResourceRequirements::merge(then_req, else_req);\n    merged_req.cost_per_coeff =\n        then_req.cost_per_coeff.cwiseMax(else_req.cost_per_coeff);\n\n    return internal::TensorBlockResourceRequirements::merge(\n        m_condImpl.getResourceRequirements(), merged_req);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    // It's unsafe to pass destination buffer to underlying expressions, because\n    // output might be aliased with one of the inputs.\n    desc.DropDestinationBuffer();\n\n    return TensorBlock(\n        m_condImpl.block(desc, scratch), m_thenImpl.block(desc, scratch),\n        m_elseImpl.block(desc, scratch), TensorSelectOpBlockFactory());\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EvaluatorPointerType data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_condImpl.bind(cgh);\n    m_thenImpl.bind(cgh);\n    m_elseImpl.bind(cgh);\n  }\n#endif\n private:\n  TensorEvaluator<IfArgType, Device> m_condImpl;\n  TensorEvaluator<ThenArgType, Device> m_thenImpl;\n  TensorEvaluator<ElseArgType, Device> m_elseImpl;\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_EVALUATOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorExecutor.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_EXECUTOR_H\n#define EIGEN_CXX11_TENSOR_TENSOR_EXECUTOR_H\n\nnamespace Eigen {\n\n/**\n * \\class TensorExecutor\n * \\ingroup CXX11_Tensor_Module\n *\n * \\brief The tensor executor class.\n *\n * This class is responsible for launch the evaluation of the expression on\n * the specified computing device.\n *\n * @tparam Vectorizable can use packet math (SSE/AVX/etc... registers and\n *                      instructions)\n * @tparam Tiling       can use block based tensor evaluation\n *                      (see TensorBlock.h)\n */\nnamespace internal {\n\n/**\n * Evaluating TensorBroadcastingOp via coefficient of packet path is extremely\n * expensive. If expression has at least one broadcast op in it, and it supports\n * block based evaluation, we always prefer it, even for the small tensors. For\n * all other tileable ops, block evaluation overhead for small tensors (fits\n * into L1) is too large, and we fallback on vectorized evaluation.\n */\n\n// TODO(ezhulenev): Add specializations for all other types of Tensor ops.\n\ntemplate<typename Expression>\nstruct ExpressionHasTensorBroadcastingOp {\n  enum { value = false };\n};\n\ntemplate<typename LhsXprType, typename RhsXprType>\nstruct ExpressionHasTensorBroadcastingOp<\n    const TensorAssignOp<LhsXprType, RhsXprType> > {\n  enum { value = ExpressionHasTensorBroadcastingOp<RhsXprType>::value };\n};\n\ntemplate<typename UnaryOp, typename XprType>\nstruct ExpressionHasTensorBroadcastingOp<\n    const TensorCwiseUnaryOp<UnaryOp, XprType> > {\n  enum { value = ExpressionHasTensorBroadcastingOp<XprType>::value };\n};\n\ntemplate<typename BinaryOp, typename LhsXprType, typename RhsXprType>\nstruct ExpressionHasTensorBroadcastingOp<\n    const TensorCwiseBinaryOp<BinaryOp, LhsXprType, RhsXprType> > {\n  enum {\n    value = ExpressionHasTensorBroadcastingOp<LhsXprType>::value ||\n        ExpressionHasTensorBroadcastingOp<RhsXprType>::value\n  };\n};\n\ntemplate<typename Broadcast, typename XprType>\nstruct ExpressionHasTensorBroadcastingOp<\n    const TensorBroadcastingOp<Broadcast, XprType> > {\n  enum { value = true };\n};\n\n// -------------------------------------------------------------------------- //\n\n/**\n * Default strategy: the expression is evaluated sequentially with a single cpu\n * thread, without vectorization and block evaluation.\n */\ntemplate <typename Expression, typename Device, bool Vectorizable,\n          TiledEvaluation Tiling>\nclass TensorExecutor {\n public:\n  typedef typename Expression::Index StorageIndex;\n\n  // Including `unsupported/Eigen/CXX11/Tensor` in different translation units\n  // with/without `EIGEN_USE_THREADS` or `EIGEN_USE_GPU` is a potential ODR\n  // violation. If this template is instantiated with a non-default device, it\n  // means that this header file was included without defining\n  // `EIGEN_USE_THREADS`, `EIGEN_USE_GPU` or `EIGEN_USE_SYCL`.\n  static_assert(std::is_same<Device, DefaultDevice>::value,\n                \"Default executor instantiated with non-default device. \"\n                \"You must #define EIGEN_USE_THREADS, EIGEN_USE_GPU or \"\n                \"EIGEN_USE_SYCL before including Eigen headers.\");\n\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE void run(const Expression& expr,\n                                      const Device& device = Device()) {\n    TensorEvaluator<Expression, Device> evaluator(expr, device);\n    const bool needs_assign = evaluator.evalSubExprsIfNeeded(NULL);\n    if (needs_assign) {\n      const StorageIndex size = array_prod(evaluator.dimensions());\n      for (StorageIndex i = 0; i < size; ++i) {\n        evaluator.evalScalar(i);\n      }\n    }\n    evaluator.cleanup();\n  }\n};\n\n/**\n * Default async execution strategy is not implemented. Currently it's only\n * available for ThreadPoolDevice (see definition below).\n */\ntemplate <typename Expression, typename Device, typename DoneCallback,\n          bool Vectorizable, TiledEvaluation Tiling>\nclass TensorAsyncExecutor {};\n\n/**\n * Process all the data with a single cpu thread, using vectorized instructions.\n */\ntemplate <typename Expression>\nclass TensorExecutor<Expression, DefaultDevice, /*Vectorizable=*/true,\n                     /*Tiling=*/TiledEvaluation::Off> {\n public:\n  typedef typename Expression::Index StorageIndex;\n\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE void run(\n      const Expression& expr, const DefaultDevice& device = DefaultDevice()) {\n    TensorEvaluator<Expression, DefaultDevice> evaluator(expr, device);\n    const bool needs_assign = evaluator.evalSubExprsIfNeeded(NULL);\n    if (needs_assign) {\n      const StorageIndex size = array_prod(evaluator.dimensions());\n      const int PacketSize = unpacket_traits<typename TensorEvaluator<\n          Expression, DefaultDevice>::PacketReturnType>::size;\n\n      // Give compiler a strong possibility to unroll the loop. But don't insist\n      // on unrolling, because if the function is expensive compiler should not\n      // unroll the loop at the expense of inlining.\n      const StorageIndex UnrolledSize =\n          (size / (4 * PacketSize)) * 4 * PacketSize;\n      for (StorageIndex i = 0; i < UnrolledSize; i += 4 * PacketSize) {\n        for (StorageIndex j = 0; j < 4; j++) {\n          evaluator.evalPacket(i + j * PacketSize);\n        }\n      }\n      const StorageIndex VectorizedSize = (size / PacketSize) * PacketSize;\n      for (StorageIndex i = UnrolledSize; i < VectorizedSize; i += PacketSize) {\n        evaluator.evalPacket(i);\n      }\n      for (StorageIndex i = VectorizedSize; i < size; ++i) {\n        evaluator.evalScalar(i);\n      }\n    }\n    evaluator.cleanup();\n  }\n};\n\n/**\n * Process all the data with a single cpu thread, using blocks of data. By\n * sizing a block to fit L1 cache we get better cache performance.\n */\ntemplate <typename Expression, bool Vectorizable>\nclass TensorExecutor<Expression, DefaultDevice, Vectorizable,\n                     /*Tiling=*/TiledEvaluation::On> {\n public:\n  typedef typename traits<Expression>::Scalar Scalar;\n  typedef typename remove_const<Scalar>::type ScalarNoConst;\n\n  typedef TensorEvaluator<Expression, DefaultDevice> Evaluator;\n  typedef typename traits<Expression>::Index StorageIndex;\n\n  static const int NumDims = traits<Expression>::NumDimensions;\n\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE void run(const Expression& expr,\n                         const DefaultDevice& device = DefaultDevice()) {\n    typedef TensorBlockMapper<NumDims, Evaluator::Layout, StorageIndex>\n        TensorBlockMapper;\n\n    typedef internal::TensorBlockDescriptor<NumDims, StorageIndex>\n        TensorBlockDesc;\n    typedef internal::TensorBlockScratchAllocator<DefaultDevice>\n        TensorBlockScratch;\n\n    Evaluator evaluator(expr, device);\n\n    // TODO(ezhulenev): Do not use tiling for small tensors?\n    const bool needs_assign = evaluator.evalSubExprsIfNeeded(NULL);\n\n    if (needs_assign) {\n      // Query expression tree for desired block size/shape.\n      const TensorBlockResourceRequirements requirements =\n          evaluator.getResourceRequirements();\n\n      const TensorBlockMapper block_mapper(\n          typename TensorBlockDesc::Dimensions(evaluator.dimensions()),\n          requirements);\n\n      // Share scratch memory allocator between all blocks.\n      TensorBlockScratch scratch(device);\n\n      const StorageIndex total_block_count = block_mapper.blockCount();\n      for (StorageIndex i = 0; i < total_block_count; ++i) {\n        TensorBlockDesc desc = block_mapper.blockDescriptor(i);\n        evaluator.evalBlock(desc, scratch);\n        scratch.reset();\n      }\n    }\n    evaluator.cleanup();\n  }\n};\n\n/**\n * Multicore strategy: the index space is partitioned and each partition is\n * executed on a single core.\n *\n * (1) TensorExecutor will submit work to the ThreadPoolDevice managed thread\n *     pool, and will block the caller thread until all tasks are finished.\n *\n * (2) TensorAsyncExecutor is a non-blocking version, that will submit work to\n *     the ThreadPoolDevice managed thread pool, and will return immediately.\n *     It will call 'done' callback after all tasks are finished.\n */\n#ifdef EIGEN_USE_THREADS\n\ntemplate <typename TensorBlockMapper>\nstruct TensorExecutorTilingContext {\n  TensorExecutorTilingContext() = default;\n  TensorExecutorTilingContext(const TensorBlockMapper& b_mapper,\n                              const TensorOpCost& b_cost, size_t b_aligned_size)\n      : block_mapper(b_mapper),\n        cost(b_cost),\n        aligned_blocksize(b_aligned_size) {}\n\n  TensorBlockMapper block_mapper;  // navigate through blocks\n  TensorOpCost cost;               // cost of computing a single block\n  size_t aligned_blocksize;        // block size after memory alignment\n};\n\n// Computes a block evaluation parameters, and allocates temporary memory buffer\n// for blocks. See TensorExecutor/TensorAsyncExecutor (Tiling=On) below.\ntemplate <typename Evaluator, typename TensorBlockMapper, bool Vectorizable>\nTensorExecutorTilingContext<TensorBlockMapper> GetTensorExecutorTilingContext(\n    const Evaluator& evaluator) {\n  // Query expression tree for desired block size/shape.\n  TensorBlockResourceRequirements requirements =\n      evaluator.getResourceRequirements();\n\n  // Update target block size based on cost model.\n  double taskSize = TensorCostModel<ThreadPoolDevice>::taskSize(\n      1, requirements.cost_per_coeff);\n  requirements.size = static_cast<size_t>(1.0 / taskSize);\n\n  TensorBlockMapper block_mapper(\n      typename TensorBlockMapper::Dimensions(evaluator.dimensions()),\n      requirements);\n\n  size_t block_size = block_mapper.blockTotalSize();\n  const size_t align = numext::maxi(EIGEN_MAX_ALIGN_BYTES, 1);\n  const size_t aligned_blocksize =\n      align *\n      divup<size_t>(block_size * sizeof(typename Evaluator::Scalar), align);\n\n  return {block_mapper, requirements.cost_per_coeff * block_size,\n          aligned_blocksize};\n}\n\ntemplate <typename Evaluator, typename StorageIndex, bool Vectorizable>\nstruct EvalRange {\n  static void run(Evaluator* evaluator_in, const StorageIndex firstIdx,\n                  const StorageIndex lastIdx) {\n    Evaluator evaluator = *evaluator_in;\n    eigen_assert(lastIdx >= firstIdx);\n    for (StorageIndex i = firstIdx; i < lastIdx; ++i) {\n      evaluator.evalScalar(i);\n    }\n  }\n\n  static StorageIndex alignBlockSize(StorageIndex size) { return size; }\n};\n\ntemplate <typename Evaluator, typename StorageIndex>\nstruct EvalRange<Evaluator, StorageIndex, /*Vectorizable*/ true> {\n  static const int PacketSize =\n      unpacket_traits<typename Evaluator::PacketReturnType>::size;\n\n  static void run(Evaluator* evaluator_in, const StorageIndex firstIdx,\n                  const StorageIndex lastIdx) {\n    Evaluator evaluator = *evaluator_in;\n    eigen_assert(lastIdx >= firstIdx);\n    StorageIndex i = firstIdx;\n    if (lastIdx - firstIdx >= PacketSize) {\n      eigen_assert(firstIdx % PacketSize == 0);\n      StorageIndex last_chunk_offset = lastIdx - 4 * PacketSize;\n      // Give compiler a strong possibility to unroll the loop. But don't insist\n      // on unrolling, because if the function is expensive compiler should not\n      // unroll the loop at the expense of inlining.\n      for (; i <= last_chunk_offset; i += 4 * PacketSize) {\n        for (StorageIndex j = 0; j < 4; j++) {\n          evaluator.evalPacket(i + j * PacketSize);\n        }\n      }\n      last_chunk_offset = lastIdx - PacketSize;\n      for (; i <= last_chunk_offset; i += PacketSize) {\n        evaluator.evalPacket(i);\n      }\n    }\n    for (; i < lastIdx; ++i) {\n      evaluator.evalScalar(i);\n    }\n  }\n\n  static StorageIndex alignBlockSize(StorageIndex size) {\n    // Align block size to packet size and account for unrolling in run above.\n    if (size >= 16 * PacketSize) {\n      return (size + 4 * PacketSize - 1) & ~(4 * PacketSize - 1);\n    }\n    // Aligning to 4 * PacketSize would increase block size by more than 25%.\n    return (size + PacketSize - 1) & ~(PacketSize - 1);\n  }\n};\n\ntemplate <typename Expression, bool Vectorizable, TiledEvaluation Tiling>\nclass TensorExecutor<Expression, ThreadPoolDevice, Vectorizable, Tiling> {\n public:\n  typedef typename Expression::Index StorageIndex;\n\n  static EIGEN_STRONG_INLINE void run(const Expression& expr,\n                         const ThreadPoolDevice& device) {\n    typedef TensorEvaluator<Expression, ThreadPoolDevice> Evaluator;\n    typedef EvalRange<Evaluator, StorageIndex, Vectorizable> EvalRange;\n\n    Evaluator evaluator(expr, device);\n    const bool needs_assign = evaluator.evalSubExprsIfNeeded(nullptr);\n    if (needs_assign) {\n      const StorageIndex size = array_prod(evaluator.dimensions());\n      device.parallelFor(size, evaluator.costPerCoeff(Vectorizable),\n                         EvalRange::alignBlockSize,\n                         [&evaluator](StorageIndex firstIdx, StorageIndex lastIdx) {\n                           EvalRange::run(&evaluator, firstIdx, lastIdx);\n                         });\n    }\n    evaluator.cleanup();\n  }\n};\n\ntemplate <typename Expression, bool Vectorizable>\nclass TensorExecutor<Expression, ThreadPoolDevice, Vectorizable,\n                     /*Tiling=*/TiledEvaluation::On> {\n public:\n  typedef typename traits<Expression>::Index IndexType;\n  typedef typename traits<Expression>::Scalar Scalar;\n  typedef typename remove_const<Scalar>::type ScalarNoConst;\n\n  static const int NumDims = traits<Expression>::NumDimensions;\n\n  typedef TensorEvaluator<Expression, ThreadPoolDevice> Evaluator;\n  typedef TensorBlockMapper<NumDims, Evaluator::Layout, IndexType> BlockMapper;\n  typedef TensorExecutorTilingContext<BlockMapper> TilingContext;\n\n  typedef internal::TensorBlockDescriptor<NumDims, IndexType>\n      TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<ThreadPoolDevice>\n      TensorBlockScratch;\n\n  static EIGEN_STRONG_INLINE void run(const Expression& expr,\n                                      const ThreadPoolDevice& device) {\n    Evaluator evaluator(expr, device);\n\n    const bool needs_assign = evaluator.evalSubExprsIfNeeded(nullptr);\n    if (needs_assign) {\n      const TilingContext tiling =\n          internal::GetTensorExecutorTilingContext<Evaluator, BlockMapper,\n                                                   Vectorizable>(evaluator);\n\n      auto eval_block = [&device, &evaluator, &tiling](IndexType firstBlockIdx,\n                                                       IndexType lastBlockIdx) {\n        TensorBlockScratch scratch(device);\n\n        for (IndexType block_idx = firstBlockIdx; block_idx < lastBlockIdx;\n             ++block_idx) {\n          TensorBlockDesc desc = tiling.block_mapper.blockDescriptor(block_idx);\n          evaluator.evalBlock(desc, scratch);\n          scratch.reset();\n        }\n      };\n\n      // Evaluate small expressions directly as a single block.\n      if (tiling.block_mapper.blockCount() == 1) {\n        TensorBlockScratch scratch(device);\n        TensorBlockDesc desc(0, tiling.block_mapper.blockDimensions());\n        evaluator.evalBlock(desc, scratch);\n      } else {\n        device.parallelFor(tiling.block_mapper.blockCount(), tiling.cost,\n                           eval_block);\n      }\n    }\n    evaluator.cleanup();\n  }\n};\n\ntemplate <typename Expression, typename DoneCallback, bool Vectorizable,\n          TiledEvaluation Tiling>\nclass TensorAsyncExecutor<Expression, ThreadPoolDevice, DoneCallback,\n                          Vectorizable, Tiling> {\n public:\n  typedef typename Expression::Index StorageIndex;\n  typedef TensorEvaluator<Expression, ThreadPoolDevice> Evaluator;\n\n  static EIGEN_STRONG_INLINE void runAsync(const Expression& expr,\n                                           const ThreadPoolDevice& device,\n                                           DoneCallback done) {\n    TensorAsyncExecutorContext* const ctx =\n        new TensorAsyncExecutorContext(expr, device, std::move(done));\n\n    const auto on_eval_subexprs = [ctx, &device](bool need_assign) -> void {\n      if (!need_assign) {\n        delete ctx;\n        return;\n      }\n\n      typedef EvalRange<Evaluator, StorageIndex, Vectorizable> EvalRange;\n      const StorageIndex size = array_prod(ctx->evaluator.dimensions());\n      device.parallelForAsync(\n          size, ctx->evaluator.costPerCoeff(Vectorizable),\n          EvalRange::alignBlockSize,\n          [ctx](StorageIndex firstIdx, StorageIndex lastIdx) {\n            EvalRange::run(&ctx->evaluator, firstIdx, lastIdx);\n          },\n          [ctx]() { delete ctx; });\n    };\n\n    ctx->evaluator.evalSubExprsIfNeededAsync(nullptr, on_eval_subexprs);\n  }\n\n private:\n  struct TensorAsyncExecutorContext {\n    TensorAsyncExecutorContext(const Expression& expr,\n                               const ThreadPoolDevice& thread_pool,\n                               DoneCallback done)\n        : evaluator(expr, thread_pool), on_done(std::move(done)) {}\n\n    ~TensorAsyncExecutorContext() {\n      evaluator.cleanup();\n      on_done();\n    }\n\n    Evaluator evaluator;\n\n   private:\n    DoneCallback on_done;\n  };\n};\n\ntemplate <typename Expression, typename DoneCallback, bool Vectorizable>\nclass TensorAsyncExecutor<Expression, ThreadPoolDevice, DoneCallback,\n                          Vectorizable, /*Tileable*/ TiledEvaluation::On> {\n public:\n  typedef typename traits<Expression>::Index IndexType;\n  typedef typename traits<Expression>::Scalar Scalar;\n  typedef typename remove_const<Scalar>::type ScalarNoConst;\n\n  static const int NumDims = traits<Expression>::NumDimensions;\n\n  typedef TensorEvaluator<Expression, ThreadPoolDevice> Evaluator;\n  typedef TensorBlockMapper<NumDims, Evaluator::Layout, IndexType> BlockMapper;\n  typedef TensorExecutorTilingContext<BlockMapper> TilingContext;\n\n  typedef internal::TensorBlockDescriptor<NumDims, IndexType> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<ThreadPoolDevice>\n      TensorBlockScratch;\n\n  static EIGEN_STRONG_INLINE void runAsync(const Expression& expr,\n                                           const ThreadPoolDevice& device,\n                                           DoneCallback done) {\n\n    TensorAsyncExecutorContext* const ctx =\n        new TensorAsyncExecutorContext(expr, device, std::move(done));\n\n    const auto on_eval_subexprs = [ctx](bool need_assign) -> void {\n      if (!need_assign) {\n        delete ctx;\n        return;\n      }\n\n      ctx->tiling = internal::GetTensorExecutorTilingContext<\n          Evaluator, BlockMapper, Vectorizable>(ctx->evaluator);\n\n      auto eval_block = [ctx](IndexType firstBlockIdx, IndexType lastBlockIdx) {\n        TensorBlockScratch scratch(ctx->device);\n\n        for (IndexType block_idx = firstBlockIdx; block_idx < lastBlockIdx;\n             ++block_idx) {\n          TensorBlockDesc desc =\n              ctx->tiling.block_mapper.blockDescriptor(block_idx);\n          ctx->evaluator.evalBlock(desc, scratch);\n          scratch.reset();\n        }\n      };\n\n      // Evaluate small expressions directly as a single block.\n      if (ctx->tiling.block_mapper.blockCount() == 1) {\n        TensorBlockScratch scratch(ctx->device);\n        TensorBlockDesc desc(0, ctx->tiling.block_mapper.blockDimensions());\n        ctx->evaluator.evalBlock(desc, scratch);\n        delete ctx;\n      } else {\n        ctx->device.parallelForAsync(ctx->tiling.block_mapper.blockCount(),\n                                     ctx->tiling.cost, eval_block,\n                                     [ctx]() { delete ctx; });\n      }\n    };\n\n    ctx->evaluator.evalSubExprsIfNeededAsync(nullptr, on_eval_subexprs);\n  }\n\n private:\n  struct TensorAsyncExecutorContext {\n    TensorAsyncExecutorContext(const Expression& expr,\n                               const ThreadPoolDevice& thread_pool,\n                               DoneCallback done)\n        : device(thread_pool),\n          evaluator(expr, thread_pool),\n          on_done(std::move(done)) {}\n\n    ~TensorAsyncExecutorContext() {\n      evaluator.cleanup();\n      on_done();\n    }\n\n    const ThreadPoolDevice& device;\n    Evaluator evaluator;\n    TilingContext tiling;\n\n   private:\n    DoneCallback on_done;\n  };\n};\n\n#endif  // EIGEN_USE_THREADS\n\n// GPU: the evaluation of the expression is offloaded to a GPU.\n#if defined(EIGEN_USE_GPU)\n\ntemplate <typename Expression, bool Vectorizable, TiledEvaluation Tiling>\nclass TensorExecutor<Expression, GpuDevice, Vectorizable, Tiling> {\n public:\n  typedef typename Expression::Index StorageIndex;\n  static void run(const Expression& expr, const GpuDevice& device);\n};\n\n#if defined(EIGEN_GPUCC)\ntemplate <typename Evaluator, typename StorageIndex, bool Vectorizable>\nstruct EigenMetaKernelEval {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  void run(Evaluator& eval, StorageIndex firstIdx, StorageIndex lastIdx, StorageIndex step_size) {\n    for (StorageIndex i = firstIdx; i < lastIdx; i += step_size) {\n      eval.evalScalar(i);\n    }\n  }\n};\n\ntemplate <typename Evaluator, typename StorageIndex>\nstruct EigenMetaKernelEval<Evaluator, StorageIndex, true> {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  void run(Evaluator& eval, StorageIndex firstIdx, StorageIndex lastIdx, StorageIndex step_size) {\n    const StorageIndex PacketSize = unpacket_traits<typename Evaluator::PacketReturnType>::size;\n    const StorageIndex vectorized_size = (lastIdx / PacketSize) * PacketSize;\n    const StorageIndex vectorized_step_size = step_size * PacketSize;\n\n    // Use the vector path\n    for (StorageIndex i = firstIdx * PacketSize; i < vectorized_size;\n         i += vectorized_step_size) {\n      eval.evalPacket(i);\n    }\n    for (StorageIndex i = vectorized_size + firstIdx; i < lastIdx; i += step_size) {\n      eval.evalScalar(i);\n    }\n  }\n};\n\ntemplate <typename Evaluator, typename StorageIndex>\n__global__ void\n__launch_bounds__(1024)\nEigenMetaKernel(Evaluator eval, StorageIndex size) {\n\n  const StorageIndex first_index = blockIdx.x * blockDim.x + threadIdx.x;\n  const StorageIndex step_size = blockDim.x * gridDim.x;\n\n  const bool vectorizable = Evaluator::PacketAccess & Evaluator::IsAligned;\n  EigenMetaKernelEval<Evaluator, StorageIndex, vectorizable>::run(eval, first_index, size, step_size);\n}\n\n/*static*/\ntemplate <typename Expression, bool Vectorizable, TiledEvaluation Tiling>\nEIGEN_STRONG_INLINE void TensorExecutor<Expression, GpuDevice, Vectorizable, Tiling>::run(\n    const Expression& expr, const GpuDevice& device) {\n  TensorEvaluator<Expression, GpuDevice> evaluator(expr, device);\n  const bool needs_assign = evaluator.evalSubExprsIfNeeded(nullptr);\n  if (needs_assign) {\n\n    const int block_size = device.maxGpuThreadsPerBlock();\n    const int max_blocks = device.getNumGpuMultiProcessors() *\n                           device.maxGpuThreadsPerMultiProcessor() / block_size;\n    const StorageIndex size = array_prod(evaluator.dimensions());\n    // Create a least one block to ensure we won't crash when tensorflow calls with tensors of size 0.\n    const int num_blocks = numext::maxi<int>(numext::mini<int>(max_blocks, divup<int>(size, block_size)), 1);\n\n    LAUNCH_GPU_KERNEL(\n        (EigenMetaKernel<TensorEvaluator<Expression, GpuDevice>, StorageIndex>),\n        num_blocks, block_size, 0, device, evaluator, size);\n  }\n  evaluator.cleanup();\n}\n\n#endif  // EIGEN_GPUCC\n#endif  // EIGEN_USE_GPU\n\n// SYCL Executor policy\n#ifdef EIGEN_USE_SYCL\n\ntemplate <typename Evaluator>\nstruct ExecExprFunctorKernel {\n  typedef typename Evaluator::Index Index;\n  Evaluator evaluator;\n  const Index range;\n  template <typename Scratch>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE ExecExprFunctorKernel(\n      const Scratch, Evaluator evaluator_, const Index range_)\n      : evaluator(evaluator_), range(range_) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void operator()(\n      cl::sycl::nd_item<1> itemID) {\n    compute(itemID);\n  }\n  template <bool is_vec = Evaluator::PacketAccess>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE typename std::enable_if<!is_vec>::type\n  compute(const cl::sycl::nd_item<1>& itemID) {\n    Index gId = static_cast<Index>(itemID.get_global_linear_id());\n    Index total_threads = itemID.get_global_range(0);\n\n    for (Index i = gId; i < range; i += total_threads) {\n      evaluator.evalScalar(i);\n    }\n  }\n  template <bool is_vec = Evaluator::PacketAccess>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE typename std::enable_if<is_vec>::type\n  compute(const cl::sycl::nd_item<1>& itemID) {\n    const Index vectorizedRange =\n        (range / Evaluator::PacketSize) * Evaluator::PacketSize;\n    Index gId = static_cast<Index>(itemID.get_global_linear_id());\n    const Index step = Evaluator::PacketSize * itemID.get_global_range(0);\n    const Index start = Evaluator::PacketSize * gId;\n    for (Index i = start; i < vectorizedRange; i += step) {\n      evaluator.evalPacket(i);\n    }\n    gId += vectorizedRange;\n    for (Index i = gId; i < range; i += itemID.get_global_range(0)) {\n      evaluator.evalScalar(i);\n    }\n  }\n};\n\ntemplate <typename Expression, bool Vectorizable, TiledEvaluation Tiling>\nclass TensorExecutor<Expression, Eigen::SyclDevice, Vectorizable, Tiling> {\n public:\n  typedef typename Expression::Index Index;\n  static EIGEN_STRONG_INLINE void run(const Expression& expr,\n                                      const Eigen::SyclDevice& dev) {\n    typedef Eigen::TensorEvaluator<Expression, Eigen::SyclDevice> Evaluator;\n    Evaluator evaluator(expr, dev);\n    const bool needs_assign = evaluator.evalSubExprsIfNeeded(NULL);\n    if (needs_assign) {\n      Index range, GRange, tileSize;\n      Index total_size = ::Eigen::internal::array_prod(evaluator.dimensions());\n      total_size = (total_size == 0) ? 1 : total_size;\n      const int PacketSize =\n          Eigen::PacketType<typename Evaluator::CoeffReturnType,\n                            Eigen::SyclDevice>::size;\n      Index vectorizable_threads = static_cast<Index>(total_size / PacketSize);\n      dev.parallel_for_setup(vectorizable_threads, tileSize, range, GRange);\n      range = total_size;\n\n      dev.template nullary_kernel_launcher<\n          typename Evaluator::CoeffReturnType,\n          ExecExprFunctorKernel<Evaluator> >(\n          evaluator,\n          cl::sycl::nd_range<1>(cl::sycl::range<1>(GRange),\n                                cl::sycl::range<1>(tileSize)),\n          Index(1), range);\n    }\n    evaluator.cleanup();\n  }\n};\n\n#endif\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_EXECUTOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorExpr.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_EXPR_H\n#define EIGEN_CXX11_TENSOR_TENSOR_EXPR_H\n\nnamespace Eigen {\n\n/** \\class TensorExpr\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor expression classes.\n  *\n  * The TensorCwiseNullaryOp class applies a nullary operators to an expression.\n  * This is typically used to generate constants.\n  *\n  * The TensorCwiseUnaryOp class represents an expression where a unary operator\n  * (e.g. cwiseSqrt) is applied to an expression.\n  *\n  * The TensorCwiseBinaryOp class represents an expression where a binary\n  * operator (e.g. addition) is applied to a lhs and a rhs expression.\n  *\n  */\nnamespace internal {\ntemplate<typename NullaryOp, typename XprType>\nstruct traits<TensorCwiseNullaryOp<NullaryOp, XprType> >\n    : traits<XprType>\n{\n  typedef traits<XprType> XprTraits;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::Nested XprTypeNested;\n  typedef typename remove_reference<XprTypeNested>::type _XprTypeNested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n  enum {\n    Flags = 0\n  };\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename NullaryOp, typename XprType>\nclass TensorCwiseNullaryOp : public TensorBase<TensorCwiseNullaryOp<NullaryOp, XprType>, ReadOnlyAccessors>\n{\n  public:\n    typedef typename Eigen::internal::traits<TensorCwiseNullaryOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef typename XprType::CoeffReturnType CoeffReturnType;\n    typedef TensorCwiseNullaryOp<NullaryOp, XprType> Nested;\n    typedef typename Eigen::internal::traits<TensorCwiseNullaryOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorCwiseNullaryOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCwiseNullaryOp(const XprType& xpr, const NullaryOp& func = NullaryOp())\n        : m_xpr(xpr), m_functor(func) {}\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    nestedExpression() const { return m_xpr; }\n\n    EIGEN_DEVICE_FUNC\n    const NullaryOp& functor() const { return m_functor; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const NullaryOp m_functor;\n};\n\n\n\nnamespace internal {\ntemplate<typename UnaryOp, typename XprType>\nstruct traits<TensorCwiseUnaryOp<UnaryOp, XprType> >\n    : traits<XprType>\n{\n  // TODO(phli): Add InputScalar, InputPacket.  Check references to\n  // current Scalar/Packet to see if the intent is Input or Output.\n  typedef typename result_of<UnaryOp(typename XprType::Scalar)>::type Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprType::Nested XprTypeNested;\n  typedef typename remove_reference<XprTypeNested>::type _XprTypeNested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename TypeConversion<Scalar, \n                                  typename XprTraits::PointerType\n                                  >::type \n                                  PointerType;\n};\n\ntemplate<typename UnaryOp, typename XprType>\nstruct eval<TensorCwiseUnaryOp<UnaryOp, XprType>, Eigen::Dense>\n{\n  typedef const TensorCwiseUnaryOp<UnaryOp, XprType>& type;\n};\n\ntemplate<typename UnaryOp, typename XprType>\nstruct nested<TensorCwiseUnaryOp<UnaryOp, XprType>, 1, typename eval<TensorCwiseUnaryOp<UnaryOp, XprType> >::type>\n{\n  typedef TensorCwiseUnaryOp<UnaryOp, XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename UnaryOp, typename XprType>\nclass TensorCwiseUnaryOp : public TensorBase<TensorCwiseUnaryOp<UnaryOp, XprType>, ReadOnlyAccessors>\n{\n  public:\n    // TODO(phli): Add InputScalar, InputPacket.  Check references to\n    // current Scalar/Packet to see if the intent is Input or Output.\n    typedef typename Eigen::internal::traits<TensorCwiseUnaryOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef Scalar CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorCwiseUnaryOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorCwiseUnaryOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorCwiseUnaryOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCwiseUnaryOp(const XprType& xpr, const UnaryOp& func = UnaryOp())\n      : m_xpr(xpr), m_functor(func) {}\n\n    EIGEN_DEVICE_FUNC\n    const UnaryOp& functor() const { return m_functor; }\n\n    /** \\returns the nested expression */\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    nestedExpression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const UnaryOp m_functor;\n};\n\n\nnamespace internal {\ntemplate<typename BinaryOp, typename LhsXprType, typename RhsXprType>\nstruct traits<TensorCwiseBinaryOp<BinaryOp, LhsXprType, RhsXprType> >\n{\n  // Type promotion to handle the case where the types of the lhs and the rhs\n  // are different.\n  // TODO(phli): Add Lhs/RhsScalar, Lhs/RhsPacket.  Check references to\n  // current Scalar/Packet to see if the intent is Inputs or Output.\n  typedef typename result_of<\n      BinaryOp(typename LhsXprType::Scalar,\n               typename RhsXprType::Scalar)>::type Scalar;\n  typedef traits<LhsXprType> XprTraits;\n  typedef typename promote_storage_type<\n      typename traits<LhsXprType>::StorageKind,\n      typename traits<RhsXprType>::StorageKind>::ret StorageKind;\n  typedef typename promote_index_type<\n      typename traits<LhsXprType>::Index,\n      typename traits<RhsXprType>::Index>::type Index;\n  typedef typename LhsXprType::Nested LhsNested;\n  typedef typename RhsXprType::Nested RhsNested;\n  typedef typename remove_reference<LhsNested>::type _LhsNested;\n  typedef typename remove_reference<RhsNested>::type _RhsNested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename TypeConversion<Scalar,\n                                  typename conditional<Pointer_type_promotion<typename LhsXprType::Scalar, Scalar>::val,\n                                                      typename traits<LhsXprType>::PointerType,\n                                                      typename traits<RhsXprType>::PointerType>::type\n                                  >::type \n                                  PointerType;\n  enum {\n    Flags = 0\n  };\n};\n\ntemplate<typename BinaryOp, typename LhsXprType, typename RhsXprType>\nstruct eval<TensorCwiseBinaryOp<BinaryOp, LhsXprType, RhsXprType>, Eigen::Dense>\n{\n  typedef const TensorCwiseBinaryOp<BinaryOp, LhsXprType, RhsXprType>& type;\n};\n\ntemplate<typename BinaryOp, typename LhsXprType, typename RhsXprType>\nstruct nested<TensorCwiseBinaryOp<BinaryOp, LhsXprType, RhsXprType>, 1, typename eval<TensorCwiseBinaryOp<BinaryOp, LhsXprType, RhsXprType> >::type>\n{\n  typedef TensorCwiseBinaryOp<BinaryOp, LhsXprType, RhsXprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename BinaryOp, typename LhsXprType, typename RhsXprType>\nclass TensorCwiseBinaryOp : public TensorBase<TensorCwiseBinaryOp<BinaryOp, LhsXprType, RhsXprType>, ReadOnlyAccessors>\n{\n  public:\n    // TODO(phli): Add Lhs/RhsScalar, Lhs/RhsPacket.  Check references to\n    // current Scalar/Packet to see if the intent is Inputs or Output.\n    typedef typename Eigen::internal::traits<TensorCwiseBinaryOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef Scalar CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorCwiseBinaryOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorCwiseBinaryOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorCwiseBinaryOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCwiseBinaryOp(const LhsXprType& lhs, const RhsXprType& rhs, const BinaryOp& func = BinaryOp())\n        : m_lhs_xpr(lhs), m_rhs_xpr(rhs), m_functor(func) {}\n\n    EIGEN_DEVICE_FUNC\n    const BinaryOp& functor() const { return m_functor; }\n\n    /** \\returns the nested expressions */\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename LhsXprType::Nested>::type&\n    lhsExpression() const { return m_lhs_xpr; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename RhsXprType::Nested>::type&\n    rhsExpression() const { return m_rhs_xpr; }\n\n  protected:\n    typename LhsXprType::Nested m_lhs_xpr;\n    typename RhsXprType::Nested m_rhs_xpr;\n    const BinaryOp m_functor;\n};\n\n\nnamespace internal {\ntemplate<typename TernaryOp, typename Arg1XprType, typename Arg2XprType, typename Arg3XprType>\nstruct traits<TensorCwiseTernaryOp<TernaryOp, Arg1XprType, Arg2XprType, Arg3XprType> >\n{\n  // Type promotion to handle the case where the types of the args are different.\n  typedef typename result_of<\n      TernaryOp(typename Arg1XprType::Scalar,\n                typename Arg2XprType::Scalar,\n                typename Arg3XprType::Scalar)>::type Scalar;\n  typedef traits<Arg1XprType> XprTraits;\n  typedef typename traits<Arg1XprType>::StorageKind StorageKind;\n  typedef typename traits<Arg1XprType>::Index Index;\n  typedef typename Arg1XprType::Nested Arg1Nested;\n  typedef typename Arg2XprType::Nested Arg2Nested;\n  typedef typename Arg3XprType::Nested Arg3Nested;\n  typedef typename remove_reference<Arg1Nested>::type _Arg1Nested;\n  typedef typename remove_reference<Arg2Nested>::type _Arg2Nested;\n  typedef typename remove_reference<Arg3Nested>::type _Arg3Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename TypeConversion<Scalar,\n                                  typename conditional<Pointer_type_promotion<typename Arg2XprType::Scalar, Scalar>::val,\n                                                      typename traits<Arg2XprType>::PointerType,\n                                                      typename traits<Arg3XprType>::PointerType>::type\n                                  >::type \n                                  PointerType;\n  enum {\n    Flags = 0\n  };\n};\n\ntemplate<typename TernaryOp, typename Arg1XprType, typename Arg2XprType, typename Arg3XprType>\nstruct eval<TensorCwiseTernaryOp<TernaryOp, Arg1XprType, Arg2XprType, Arg3XprType>, Eigen::Dense>\n{\n  typedef const TensorCwiseTernaryOp<TernaryOp, Arg1XprType, Arg2XprType, Arg3XprType>& type;\n};\n\ntemplate<typename TernaryOp, typename Arg1XprType, typename Arg2XprType, typename Arg3XprType>\nstruct nested<TensorCwiseTernaryOp<TernaryOp, Arg1XprType, Arg2XprType, Arg3XprType>, 1, typename eval<TensorCwiseTernaryOp<TernaryOp, Arg1XprType, Arg2XprType, Arg3XprType> >::type>\n{\n  typedef TensorCwiseTernaryOp<TernaryOp, Arg1XprType, Arg2XprType, Arg3XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename TernaryOp, typename Arg1XprType, typename Arg2XprType, typename Arg3XprType>\nclass TensorCwiseTernaryOp : public TensorBase<TensorCwiseTernaryOp<TernaryOp, Arg1XprType, Arg2XprType, Arg3XprType>, ReadOnlyAccessors>\n{\n  public:\n    typedef typename Eigen::internal::traits<TensorCwiseTernaryOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef Scalar CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorCwiseTernaryOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorCwiseTernaryOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorCwiseTernaryOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCwiseTernaryOp(const Arg1XprType& arg1, const Arg2XprType& arg2, const Arg3XprType& arg3, const TernaryOp& func = TernaryOp())\n        : m_arg1_xpr(arg1), m_arg2_xpr(arg2), m_arg3_xpr(arg3), m_functor(func) {}\n\n    EIGEN_DEVICE_FUNC\n    const TernaryOp& functor() const { return m_functor; }\n\n    /** \\returns the nested expressions */\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename Arg1XprType::Nested>::type&\n    arg1Expression() const { return m_arg1_xpr; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename Arg2XprType::Nested>::type&\n    arg2Expression() const { return m_arg2_xpr; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename Arg3XprType::Nested>::type&\n    arg3Expression() const { return m_arg3_xpr; }\n\n  protected:\n    typename Arg1XprType::Nested m_arg1_xpr;\n    typename Arg2XprType::Nested m_arg2_xpr;\n    typename Arg3XprType::Nested m_arg3_xpr;\n    const TernaryOp m_functor;\n};\n\n\nnamespace internal {\ntemplate<typename IfXprType, typename ThenXprType, typename ElseXprType>\nstruct traits<TensorSelectOp<IfXprType, ThenXprType, ElseXprType> >\n    : traits<ThenXprType>\n{\n  typedef typename traits<ThenXprType>::Scalar Scalar;\n  typedef traits<ThenXprType> XprTraits;\n  typedef typename promote_storage_type<typename traits<ThenXprType>::StorageKind,\n                                        typename traits<ElseXprType>::StorageKind>::ret StorageKind;\n  typedef typename promote_index_type<typename traits<ElseXprType>::Index,\n                                      typename traits<ThenXprType>::Index>::type Index;\n  typedef typename IfXprType::Nested IfNested;\n  typedef typename ThenXprType::Nested ThenNested;\n  typedef typename ElseXprType::Nested ElseNested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename conditional<Pointer_type_promotion<typename ThenXprType::Scalar, Scalar>::val,\n                               typename traits<ThenXprType>::PointerType,\n                               typename traits<ElseXprType>::PointerType>::type PointerType;\n};\n\ntemplate<typename IfXprType, typename ThenXprType, typename ElseXprType>\nstruct eval<TensorSelectOp<IfXprType, ThenXprType, ElseXprType>, Eigen::Dense>\n{\n  typedef const TensorSelectOp<IfXprType, ThenXprType, ElseXprType>& type;\n};\n\ntemplate<typename IfXprType, typename ThenXprType, typename ElseXprType>\nstruct nested<TensorSelectOp<IfXprType, ThenXprType, ElseXprType>, 1, typename eval<TensorSelectOp<IfXprType, ThenXprType, ElseXprType> >::type>\n{\n  typedef TensorSelectOp<IfXprType, ThenXprType, ElseXprType> type;\n};\n\n}  // end namespace internal\n\n\ntemplate<typename IfXprType, typename ThenXprType, typename ElseXprType>\nclass TensorSelectOp : public TensorBase<TensorSelectOp<IfXprType, ThenXprType, ElseXprType>, ReadOnlyAccessors>\n{\n  public:\n    typedef typename Eigen::internal::traits<TensorSelectOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef typename internal::promote_storage_type<typename ThenXprType::CoeffReturnType,\n                                                    typename ElseXprType::CoeffReturnType>::ret CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorSelectOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorSelectOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorSelectOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC\n    TensorSelectOp(const IfXprType& a_condition,\n                   const ThenXprType& a_then,\n                   const ElseXprType& a_else)\n      : m_condition(a_condition), m_then(a_then), m_else(a_else)\n    { }\n\n    EIGEN_DEVICE_FUNC\n    const IfXprType& ifExpression() const { return m_condition; }\n\n    EIGEN_DEVICE_FUNC\n    const ThenXprType& thenExpression() const { return m_then; }\n\n    EIGEN_DEVICE_FUNC\n    const ElseXprType& elseExpression() const { return m_else; }\n\n  protected:\n    typename IfXprType::Nested m_condition;\n    typename ThenXprType::Nested m_then;\n    typename ElseXprType::Nested m_else;\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_EXPR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFFT.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Jianwei Cui <thucjw@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_FFT_H\n#define EIGEN_CXX11_TENSOR_TENSOR_FFT_H\n\nnamespace Eigen {\n\n/** \\class TensorFFT\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor FFT class.\n  *\n  * TODO:\n  * Vectorize the Cooley Tukey and the Bluestein algorithm\n  * Add support for multithreaded evaluation\n  * Improve the performance on GPU\n  */\n\ntemplate <bool NeedUprade> struct MakeComplex {\n  template <typename T>\n  EIGEN_DEVICE_FUNC\n  T operator() (const T& val) const { return val; }\n};\n\ntemplate <> struct MakeComplex<true> {\n  template <typename T>\n  EIGEN_DEVICE_FUNC\n  std::complex<T> operator() (const T& val) const { return std::complex<T>(val, 0); }\n};\n\ntemplate <> struct MakeComplex<false> {\n  template <typename T>\n  EIGEN_DEVICE_FUNC\n  std::complex<T> operator() (const std::complex<T>& val) const { return val; }\n};\n\ntemplate <int ResultType> struct PartOf {\n  template <typename T> T operator() (const T& val) const { return val; }\n};\n\ntemplate <> struct PartOf<RealPart> {\n  template <typename T> T operator() (const std::complex<T>& val) const { return val.real(); }\n};\n\ntemplate <> struct PartOf<ImagPart> {\n  template <typename T> T operator() (const std::complex<T>& val) const { return val.imag(); }\n};\n\nnamespace internal {\ntemplate <typename FFT, typename XprType, int FFTResultType, int FFTDir>\nstruct traits<TensorFFTOp<FFT, XprType, FFTResultType, FFTDir> > : public traits<XprType> {\n  typedef traits<XprType> XprTraits;\n  typedef typename NumTraits<typename XprTraits::Scalar>::Real RealScalar;\n  typedef typename std::complex<RealScalar> ComplexScalar;\n  typedef typename XprTraits::Scalar InputScalar;\n  typedef typename conditional<FFTResultType == RealPart || FFTResultType == ImagPart, RealScalar, ComplexScalar>::type OutputScalar;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename traits<XprType>::PointerType PointerType;\n};\n\ntemplate <typename FFT, typename XprType, int FFTResultType, int FFTDirection>\nstruct eval<TensorFFTOp<FFT, XprType, FFTResultType, FFTDirection>, Eigen::Dense> {\n  typedef const TensorFFTOp<FFT, XprType, FFTResultType, FFTDirection>& type;\n};\n\ntemplate <typename FFT, typename XprType, int FFTResultType, int FFTDirection>\nstruct nested<TensorFFTOp<FFT, XprType, FFTResultType, FFTDirection>, 1, typename eval<TensorFFTOp<FFT, XprType, FFTResultType, FFTDirection> >::type> {\n  typedef TensorFFTOp<FFT, XprType, FFTResultType, FFTDirection> type;\n};\n\n}  // end namespace internal\n\ntemplate <typename FFT, typename XprType, int FFTResultType, int FFTDir>\nclass TensorFFTOp : public TensorBase<TensorFFTOp<FFT, XprType, FFTResultType, FFTDir>, ReadOnlyAccessors> {\n public:\n  typedef typename Eigen::internal::traits<TensorFFTOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename std::complex<RealScalar> ComplexScalar;\n  typedef typename internal::conditional<FFTResultType == RealPart || FFTResultType == ImagPart, RealScalar, ComplexScalar>::type OutputScalar;\n  typedef OutputScalar CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorFFTOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorFFTOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorFFTOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorFFTOp(const XprType& expr, const FFT& fft)\n      : m_xpr(expr), m_fft(fft) {}\n\n  EIGEN_DEVICE_FUNC\n  const FFT& fft() const { return m_fft; }\n\n  EIGEN_DEVICE_FUNC\n  const typename internal::remove_all<typename XprType::Nested>::type& expression() const {\n    return m_xpr;\n  }\n\n protected:\n  typename XprType::Nested m_xpr;\n  const FFT m_fft;\n};\n\n// Eval as rvalue\ntemplate <typename FFT, typename ArgType, typename Device, int FFTResultType, int FFTDir>\nstruct TensorEvaluator<const TensorFFTOp<FFT, ArgType, FFTResultType, FFTDir>, Device> {\n  typedef TensorFFTOp<FFT, ArgType, FFTResultType, FFTDir> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename std::complex<RealScalar> ComplexScalar;\n  typedef typename TensorEvaluator<ArgType, Device>::Dimensions InputDimensions;\n  typedef internal::traits<XprType> XprTraits;\n  typedef typename XprTraits::Scalar InputScalar;\n  typedef typename internal::conditional<FFTResultType == RealPart || FFTResultType == ImagPart, RealScalar, ComplexScalar>::type OutputScalar;\n  typedef OutputScalar CoeffReturnType;\n  typedef typename PacketType<OutputScalar, Device>::type PacketReturnType;\n  static const int PacketSize = internal::unpacket_traits<PacketReturnType>::size;\n    typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = true,\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) : m_fft(op.fft()), m_impl(op.expression(), device), m_data(NULL), m_device(device) {\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n    for (int i = 0; i < NumDims; ++i) {\n      eigen_assert(input_dims[i] > 0);\n      m_dimensions[i] = input_dims[i];\n    }\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_strides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_strides[i] = m_strides[i - 1] * m_dimensions[i - 1];\n      }\n    } else {\n      m_strides[NumDims - 1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_strides[i] = m_strides[i + 1] * m_dimensions[i + 1];\n      }\n    }\n    m_size = m_dimensions.TotalSize();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const {\n    return m_dimensions;\n  }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    if (data) {\n      evalToBuf(data);\n      return false;\n    } else {\n      m_data = (EvaluatorPointerType)m_device.get((CoeffReturnType*)(m_device.allocate_temp(sizeof(CoeffReturnType) * m_size)));\n      evalToBuf(m_data);\n      return true;\n    }\n  }\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    if (m_data) {\n      m_device.deallocate(m_data);\n      m_data = NULL;\n    }\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE CoeffReturnType coeff(Index index) const {\n    return m_data[index];\n  }\n\n  template <int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketReturnType\n  packet(Index index) const {\n    return internal::ploadt<PacketReturnType, LoadMode>(m_data + index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return m_data; }\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_data.bind(cgh);\n  }\n#endif\n\n private:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalToBuf(EvaluatorPointerType data) {\n    const bool write_to_out = internal::is_same<OutputScalar, ComplexScalar>::value;\n    ComplexScalar* buf = write_to_out ? (ComplexScalar*)data : (ComplexScalar*)m_device.allocate(sizeof(ComplexScalar) * m_size);\n\n    for (Index i = 0; i < m_size; ++i) {\n      buf[i] = MakeComplex<internal::is_same<InputScalar, RealScalar>::value>()(m_impl.coeff(i));\n    }\n\n    for (size_t i = 0; i < m_fft.size(); ++i) {\n      Index dim = m_fft[i];\n      eigen_assert(dim >= 0 && dim < NumDims);\n      Index line_len = m_dimensions[dim];\n      eigen_assert(line_len >= 1);\n      ComplexScalar* line_buf = (ComplexScalar*)m_device.allocate(sizeof(ComplexScalar) * line_len);\n      const bool is_power_of_two = isPowerOfTwo(line_len);\n      const Index good_composite = is_power_of_two ? 0 : findGoodComposite(line_len);\n      const Index log_len = is_power_of_two ? getLog2(line_len) : getLog2(good_composite);\n\n      ComplexScalar* a = is_power_of_two ? NULL : (ComplexScalar*)m_device.allocate(sizeof(ComplexScalar) * good_composite);\n      ComplexScalar* b = is_power_of_two ? NULL : (ComplexScalar*)m_device.allocate(sizeof(ComplexScalar) * good_composite);\n      ComplexScalar* pos_j_base_powered = is_power_of_two ? NULL : (ComplexScalar*)m_device.allocate(sizeof(ComplexScalar) * (line_len + 1));\n      if (!is_power_of_two) {\n        // Compute twiddle factors\n        //   t_n = exp(sqrt(-1) * pi * n^2 / line_len)\n        // for n = 0, 1,..., line_len-1.\n        // For n > 2 we use the recurrence t_n = t_{n-1}^2 / t_{n-2} * t_1^2\n\n        // The recurrence is correct in exact arithmetic, but causes\n        // numerical issues for large transforms, especially in\n        // single-precision floating point.\n        //\n        // pos_j_base_powered[0] = ComplexScalar(1, 0);\n        // if (line_len > 1) {\n        //   const ComplexScalar pos_j_base = ComplexScalar(\n        //       numext::cos(M_PI / line_len), numext::sin(M_PI / line_len));\n        //   pos_j_base_powered[1] = pos_j_base;\n        //   if (line_len > 2) {\n        //     const ComplexScalar pos_j_base_sq = pos_j_base * pos_j_base;\n        //     for (int i = 2; i < line_len + 1; ++i) {\n        //       pos_j_base_powered[i] = pos_j_base_powered[i - 1] *\n        //           pos_j_base_powered[i - 1] /\n        //           pos_j_base_powered[i - 2] *\n        //           pos_j_base_sq;\n        //     }\n        //   }\n        // }\n        // TODO(rmlarsen): Find a way to use Eigen's vectorized sin\n        // and cosine functions here.\n        for (int j = 0; j < line_len + 1; ++j) {\n          double arg = ((EIGEN_PI * j) * j) / line_len;\n          std::complex<double> tmp(numext::cos(arg), numext::sin(arg));\n          pos_j_base_powered[j] = static_cast<ComplexScalar>(tmp);\n        }\n      }\n\n      for (Index partial_index = 0; partial_index < m_size / line_len; ++partial_index) {\n        const Index base_offset = getBaseOffsetFromIndex(partial_index, dim);\n\n        // get data into line_buf\n        const Index stride = m_strides[dim];\n        if (stride == 1) {\n          m_device.memcpy(line_buf, &buf[base_offset], line_len*sizeof(ComplexScalar));\n        } else {\n          Index offset = base_offset;\n          for (int j = 0; j < line_len; ++j, offset += stride) {\n            line_buf[j] = buf[offset];\n          }\n        }\n\n        // process the line\n        if (is_power_of_two) {\n          processDataLineCooleyTukey(line_buf, line_len, log_len);\n        }\n        else {\n          processDataLineBluestein(line_buf, line_len, good_composite, log_len, a, b, pos_j_base_powered);\n        }\n\n        // write back\n        if (FFTDir == FFT_FORWARD && stride == 1) {\n          m_device.memcpy(&buf[base_offset], line_buf, line_len*sizeof(ComplexScalar));\n        } else {\n          Index offset = base_offset;\n          const ComplexScalar div_factor =  ComplexScalar(1.0 / line_len, 0);\n          for (int j = 0; j < line_len; ++j, offset += stride) {\n             buf[offset] = (FFTDir == FFT_FORWARD) ? line_buf[j] : line_buf[j] * div_factor;\n          }\n        }\n      }\n      m_device.deallocate(line_buf);\n      if (!is_power_of_two) {\n        m_device.deallocate(a);\n        m_device.deallocate(b);\n        m_device.deallocate(pos_j_base_powered);\n      }\n    }\n\n    if(!write_to_out) {\n      for (Index i = 0; i < m_size; ++i) {\n        data[i] = PartOf<FFTResultType>()(buf[i]);\n      }\n      m_device.deallocate(buf);\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static bool isPowerOfTwo(Index x) {\n    eigen_assert(x > 0);\n    return !(x & (x - 1));\n  }\n\n  // The composite number for padding, used in Bluestein's FFT algorithm\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static Index findGoodComposite(Index n) {\n    Index i = 2;\n    while (i < 2 * n - 1) i *= 2;\n    return i;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static Index getLog2(Index m) {\n    Index log2m = 0;\n    while (m >>= 1) log2m++;\n    return log2m;\n  }\n\n  // Call Cooley Tukey algorithm directly, data length must be power of 2\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void processDataLineCooleyTukey(ComplexScalar* line_buf, Index line_len, Index log_len) {\n    eigen_assert(isPowerOfTwo(line_len));\n    scramble_FFT(line_buf, line_len);\n    compute_1D_Butterfly<FFTDir>(line_buf, line_len, log_len);\n  }\n\n  // Call Bluestein's FFT algorithm, m is a good composite number greater than (2 * n - 1), used as the padding length\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void processDataLineBluestein(ComplexScalar* line_buf, Index line_len, Index good_composite, Index log_len, ComplexScalar* a, ComplexScalar* b, const ComplexScalar* pos_j_base_powered) {\n    Index n = line_len;\n    Index m = good_composite;\n    ComplexScalar* data = line_buf;\n\n    for (Index i = 0; i < n; ++i) {\n      if(FFTDir == FFT_FORWARD) {\n        a[i] = data[i] * numext::conj(pos_j_base_powered[i]);\n      }\n      else {\n        a[i] = data[i] * pos_j_base_powered[i];\n      }\n    }\n    for (Index i = n; i < m; ++i) {\n      a[i] = ComplexScalar(0, 0);\n    }\n\n    for (Index i = 0; i < n; ++i) {\n      if(FFTDir == FFT_FORWARD) {\n        b[i] = pos_j_base_powered[i];\n      }\n      else {\n        b[i] = numext::conj(pos_j_base_powered[i]);\n      }\n    }\n    for (Index i = n; i < m - n; ++i) {\n      b[i] = ComplexScalar(0, 0);\n    }\n    for (Index i = m - n; i < m; ++i) {\n      if(FFTDir == FFT_FORWARD) {\n        b[i] = pos_j_base_powered[m-i];\n      }\n      else {\n        b[i] = numext::conj(pos_j_base_powered[m-i]);\n      }\n    }\n\n    scramble_FFT(a, m);\n    compute_1D_Butterfly<FFT_FORWARD>(a, m, log_len);\n\n    scramble_FFT(b, m);\n    compute_1D_Butterfly<FFT_FORWARD>(b, m, log_len);\n\n    for (Index i = 0; i < m; ++i) {\n      a[i] *= b[i];\n    }\n\n    scramble_FFT(a, m);\n    compute_1D_Butterfly<FFT_REVERSE>(a, m, log_len);\n\n    //Do the scaling after ifft\n    for (Index i = 0; i < m; ++i) {\n      a[i] /= m;\n    }\n\n    for (Index i = 0; i < n; ++i) {\n      if(FFTDir == FFT_FORWARD) {\n        data[i] = a[i] * numext::conj(pos_j_base_powered[i]);\n      }\n      else {\n        data[i] = a[i] * pos_j_base_powered[i];\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static void scramble_FFT(ComplexScalar* data, Index n) {\n    eigen_assert(isPowerOfTwo(n));\n    Index j = 1;\n    for (Index i = 1; i < n; ++i){\n      if (j > i) {\n        std::swap(data[j-1], data[i-1]);\n      }\n      Index m = n >> 1;\n      while (m >= 2 && j > m) {\n        j -= m;\n        m >>= 1;\n      }\n      j += m;\n    }\n  }\n\n  template <int Dir>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void butterfly_2(ComplexScalar* data) {\n    ComplexScalar tmp = data[1];\n    data[1] = data[0] - data[1];\n    data[0] += tmp;\n  }\n\n  template <int Dir>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void butterfly_4(ComplexScalar* data) {\n    ComplexScalar tmp[4];\n    tmp[0] = data[0] + data[1];\n    tmp[1] = data[0] - data[1];\n    tmp[2] = data[2] + data[3];\n    if (Dir == FFT_FORWARD) {\n      tmp[3] = ComplexScalar(0.0, -1.0) * (data[2] - data[3]);\n    } else {\n      tmp[3] = ComplexScalar(0.0, 1.0) * (data[2] - data[3]);\n    }\n    data[0] = tmp[0] + tmp[2];\n    data[1] = tmp[1] + tmp[3];\n    data[2] = tmp[0] - tmp[2];\n    data[3] = tmp[1] - tmp[3];\n  }\n\n  template <int Dir>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void butterfly_8(ComplexScalar* data) {\n    ComplexScalar tmp_1[8];\n    ComplexScalar tmp_2[8];\n\n    tmp_1[0] = data[0] + data[1];\n    tmp_1[1] = data[0] - data[1];\n    tmp_1[2] = data[2] + data[3];\n    if (Dir == FFT_FORWARD) {\n      tmp_1[3] = (data[2] - data[3]) * ComplexScalar(0, -1);\n    } else {\n      tmp_1[3] = (data[2] - data[3]) * ComplexScalar(0, 1);\n    }\n    tmp_1[4] = data[4] + data[5];\n    tmp_1[5] = data[4] - data[5];\n    tmp_1[6] = data[6] + data[7];\n    if (Dir == FFT_FORWARD) {\n      tmp_1[7] = (data[6] - data[7]) * ComplexScalar(0, -1);\n    } else {\n      tmp_1[7] = (data[6] - data[7]) * ComplexScalar(0, 1);\n    }\n    tmp_2[0] = tmp_1[0] + tmp_1[2];\n    tmp_2[1] = tmp_1[1] + tmp_1[3];\n    tmp_2[2] = tmp_1[0] - tmp_1[2];\n    tmp_2[3] = tmp_1[1] - tmp_1[3];\n    tmp_2[4] = tmp_1[4] + tmp_1[6];\n// SQRT2DIV2 = sqrt(2)/2\n#define SQRT2DIV2 0.7071067811865476\n    if (Dir == FFT_FORWARD) {\n      tmp_2[5] = (tmp_1[5] + tmp_1[7]) * ComplexScalar(SQRT2DIV2, -SQRT2DIV2);\n      tmp_2[6] = (tmp_1[4] - tmp_1[6]) * ComplexScalar(0, -1);\n      tmp_2[7] = (tmp_1[5] - tmp_1[7]) * ComplexScalar(-SQRT2DIV2, -SQRT2DIV2);\n    } else {\n      tmp_2[5] = (tmp_1[5] + tmp_1[7]) * ComplexScalar(SQRT2DIV2, SQRT2DIV2);\n      tmp_2[6] = (tmp_1[4] - tmp_1[6]) * ComplexScalar(0, 1);\n      tmp_2[7] = (tmp_1[5] - tmp_1[7]) * ComplexScalar(-SQRT2DIV2, SQRT2DIV2);\n    }\n    data[0] = tmp_2[0] + tmp_2[4];\n    data[1] = tmp_2[1] + tmp_2[5];\n    data[2] = tmp_2[2] + tmp_2[6];\n    data[3] = tmp_2[3] + tmp_2[7];\n    data[4] = tmp_2[0] - tmp_2[4];\n    data[5] = tmp_2[1] - tmp_2[5];\n    data[6] = tmp_2[2] - tmp_2[6];\n    data[7] = tmp_2[3] - tmp_2[7];\n  }\n\n  template <int Dir>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void butterfly_1D_merge(\n      ComplexScalar* data, Index n, Index n_power_of_2) {\n    // Original code:\n    // RealScalar wtemp = std::sin(M_PI/n);\n    // RealScalar wpi =  -std::sin(2 * M_PI/n);\n    const RealScalar wtemp = m_sin_PI_div_n_LUT[n_power_of_2];\n    const RealScalar wpi = (Dir == FFT_FORWARD)\n                               ? m_minus_sin_2_PI_div_n_LUT[n_power_of_2]\n                               : -m_minus_sin_2_PI_div_n_LUT[n_power_of_2];\n\n    const ComplexScalar wp(wtemp, wpi);\n    const ComplexScalar wp_one = wp + ComplexScalar(1, 0);\n    const ComplexScalar wp_one_2 = wp_one * wp_one;\n    const ComplexScalar wp_one_3 = wp_one_2 * wp_one;\n    const ComplexScalar wp_one_4 = wp_one_3 * wp_one;\n    const Index n2 = n / 2;\n    ComplexScalar w(1.0, 0.0);\n    for (Index i = 0; i < n2; i += 4) {\n       ComplexScalar temp0(data[i + n2] * w);\n       ComplexScalar temp1(data[i + 1 + n2] * w * wp_one);\n       ComplexScalar temp2(data[i + 2 + n2] * w * wp_one_2);\n       ComplexScalar temp3(data[i + 3 + n2] * w * wp_one_3);\n       w = w * wp_one_4;\n\n       data[i + n2] = data[i] - temp0;\n       data[i] += temp0;\n\n       data[i + 1 + n2] = data[i + 1] - temp1;\n       data[i + 1] += temp1;\n\n       data[i + 2 + n2] = data[i + 2] - temp2;\n       data[i + 2] += temp2;\n\n       data[i + 3 + n2] = data[i + 3] - temp3;\n       data[i + 3] += temp3;\n    }\n  }\n\n template <int Dir>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void compute_1D_Butterfly(\n      ComplexScalar* data, Index n, Index n_power_of_2) {\n    eigen_assert(isPowerOfTwo(n));\n    if (n > 8) {\n      compute_1D_Butterfly<Dir>(data, n / 2, n_power_of_2 - 1);\n      compute_1D_Butterfly<Dir>(data + n / 2, n / 2, n_power_of_2 - 1);\n      butterfly_1D_merge<Dir>(data, n, n_power_of_2);\n    } else if (n == 8) {\n      butterfly_8<Dir>(data);\n    } else if (n == 4) {\n      butterfly_4<Dir>(data);\n    } else if (n == 2) {\n      butterfly_2<Dir>(data);\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index getBaseOffsetFromIndex(Index index, Index omitted_dim) const {\n    Index result = 0;\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = NumDims - 1; i > omitted_dim; --i) {\n        const Index partial_m_stride = m_strides[i] / m_dimensions[omitted_dim];\n        const Index idx = index / partial_m_stride;\n        index -= idx * partial_m_stride;\n        result += idx * m_strides[i];\n      }\n      result += index;\n    }\n    else {\n      for (Index i = 0; i < omitted_dim; ++i) {\n        const Index partial_m_stride = m_strides[i] / m_dimensions[omitted_dim];\n        const Index idx = index / partial_m_stride;\n        index -= idx * partial_m_stride;\n        result += idx * m_strides[i];\n      }\n      result += index;\n    }\n    // Value of index_coords[omitted_dim] is not determined to this step\n    return result;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index getIndexFromOffset(Index base, Index omitted_dim, Index offset) const {\n    Index result = base + offset * m_strides[omitted_dim] ;\n    return result;\n  }\n\n protected:\n  Index m_size;\n  const FFT EIGEN_DEVICE_REF m_fft;\n  Dimensions m_dimensions;\n  array<Index, NumDims> m_strides;\n  TensorEvaluator<ArgType, Device> m_impl;\n  EvaluatorPointerType m_data;\n  const Device EIGEN_DEVICE_REF m_device;\n\n  // This will support a maximum FFT size of 2^32 for each dimension\n  // m_sin_PI_div_n_LUT[i] = (-2) * std::sin(M_PI / std::pow(2,i)) ^ 2;\n  const RealScalar m_sin_PI_div_n_LUT[32] = {\n    RealScalar(0.0),\n    RealScalar(-2),\n    RealScalar(-0.999999999999999),\n    RealScalar(-0.292893218813453),\n    RealScalar(-0.0761204674887130),\n    RealScalar(-0.0192147195967696),\n    RealScalar(-0.00481527332780311),\n    RealScalar(-0.00120454379482761),\n    RealScalar(-3.01181303795779e-04),\n    RealScalar(-7.52981608554592e-05),\n    RealScalar(-1.88247173988574e-05),\n    RealScalar(-4.70619042382852e-06),\n    RealScalar(-1.17654829809007e-06),\n    RealScalar(-2.94137117780840e-07),\n    RealScalar(-7.35342821488550e-08),\n    RealScalar(-1.83835707061916e-08),\n    RealScalar(-4.59589268710903e-09),\n    RealScalar(-1.14897317243732e-09),\n    RealScalar(-2.87243293150586e-10),\n    RealScalar( -7.18108232902250e-11),\n    RealScalar(-1.79527058227174e-11),\n    RealScalar(-4.48817645568941e-12),\n    RealScalar(-1.12204411392298e-12),\n    RealScalar(-2.80511028480785e-13),\n    RealScalar(-7.01277571201985e-14),\n    RealScalar(-1.75319392800498e-14),\n    RealScalar(-4.38298482001247e-15),\n    RealScalar(-1.09574620500312e-15),\n    RealScalar(-2.73936551250781e-16),\n    RealScalar(-6.84841378126949e-17),\n    RealScalar(-1.71210344531737e-17),\n    RealScalar(-4.28025861329343e-18)\n  };\n\n  // m_minus_sin_2_PI_div_n_LUT[i] = -std::sin(2 * M_PI / std::pow(2,i));\n  const RealScalar m_minus_sin_2_PI_div_n_LUT[32] = {\n    RealScalar(0.0),\n    RealScalar(0.0),\n    RealScalar(-1.00000000000000e+00),\n    RealScalar(-7.07106781186547e-01),\n    RealScalar(-3.82683432365090e-01),\n    RealScalar(-1.95090322016128e-01),\n    RealScalar(-9.80171403295606e-02),\n    RealScalar(-4.90676743274180e-02),\n    RealScalar(-2.45412285229123e-02),\n    RealScalar(-1.22715382857199e-02),\n    RealScalar(-6.13588464915448e-03),\n    RealScalar(-3.06795676296598e-03),\n    RealScalar(-1.53398018628477e-03),\n    RealScalar(-7.66990318742704e-04),\n    RealScalar(-3.83495187571396e-04),\n    RealScalar(-1.91747597310703e-04),\n    RealScalar(-9.58737990959773e-05),\n    RealScalar(-4.79368996030669e-05),\n    RealScalar(-2.39684498084182e-05),\n    RealScalar(-1.19842249050697e-05),\n    RealScalar(-5.99211245264243e-06),\n    RealScalar(-2.99605622633466e-06),\n    RealScalar(-1.49802811316901e-06),\n    RealScalar(-7.49014056584716e-07),\n    RealScalar(-3.74507028292384e-07),\n    RealScalar(-1.87253514146195e-07),\n    RealScalar(-9.36267570730981e-08),\n    RealScalar(-4.68133785365491e-08),\n    RealScalar(-2.34066892682746e-08),\n    RealScalar(-1.17033446341373e-08),\n    RealScalar(-5.85167231706864e-09),\n    RealScalar(-2.92583615853432e-09)\n  };\n};\n\n}  // end namespace Eigen\n\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_FFT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFixedSize.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_FIXED_SIZE_H\n#define EIGEN_CXX11_TENSOR_TENSOR_FIXED_SIZE_H\n\nnamespace Eigen {\n\n/** \\class TensorFixedSize\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief The fixed sized version of the tensor class.\n  *\n  * The fixed sized equivalent of\n  * Eigen::Tensor<float, 3> t(3, 5, 7);\n  * is\n  * Eigen::TensorFixedSize<float, Sizes<3,5,7>> t;\n  */\n\ntemplate<typename Scalar_, typename Dimensions_, int Options_, typename IndexType>\nclass TensorFixedSize : public TensorBase<TensorFixedSize<Scalar_, Dimensions_, Options_, IndexType> >\n{\n  public:\n    typedef TensorFixedSize<Scalar_, Dimensions_, Options_, IndexType> Self;\n    typedef TensorBase<TensorFixedSize<Scalar_, Dimensions_, Options_, IndexType> > Base;\n    typedef typename Eigen::internal::nested<Self>::type Nested;\n    typedef typename internal::traits<Self>::StorageKind StorageKind;\n    typedef typename internal::traits<Self>::Index Index;\n    typedef Scalar_ Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef typename Base::CoeffReturnType CoeffReturnType;\n\n    static const int Options = Options_;\n\n    enum {\n      IsAligned = bool(EIGEN_MAX_ALIGN_BYTES>0),\n      PacketAccess = (internal::packet_traits<Scalar>::size > 1),\n      BlockAccess = false,\n      PreferBlockAccess = false,\n      Layout = Options_ & RowMajor ? RowMajor : ColMajor,\n      CoordAccess = true,\n      RawAccess = true\n    };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  typedef Dimensions_ Dimensions;\n  static const std::size_t NumIndices = Dimensions::count;\n\n  protected:\n  TensorStorage<Scalar, Dimensions, Options> m_storage;\n\n  public:\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index                    rank()                   const { return NumIndices; }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index                    dimension(std::size_t n) const { return m_storage.dimensions()[n]; }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions&        dimensions()             const { return m_storage.dimensions(); }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index                    size()                   const { return m_storage.size(); }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar                   *data()                        { return m_storage.data(); }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar             *data()                  const { return m_storage.data(); }\n\n    // This makes EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED\n    // work, because that uses base().coeffRef() - and we don't yet\n    // implement a similar class hierarchy\n    inline Self& base()             { return *this; }\n    inline const Self& base() const { return *this; }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(Index firstIndex, IndexTypes... otherIndices) const\n    {\n      // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return coeff(array<Index, NumIndices>{{firstIndex, otherIndices...}});\n    }\n#endif\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& coeff(const array<Index, NumIndices>& indices) const\n    {\n      eigen_internal_assert(checkIndexRange(indices));\n      return m_storage.data()[linearizedIndex(indices)];\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& coeff(Index index) const\n    {\n      eigen_internal_assert(index >= 0 && index < size());\n      return m_storage.data()[index];\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& coeff() const\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return m_storage.data()[0];\n    }\n\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index firstIndex, IndexTypes... otherIndices)\n    {\n      // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return coeffRef(array<Index, NumIndices>{{firstIndex, otherIndices...}});\n    }\n#endif\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& coeffRef(const array<Index, NumIndices>& indices)\n    {\n      eigen_internal_assert(checkIndexRange(indices));\n      return m_storage.data()[linearizedIndex(indices)];\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& coeffRef(Index index)\n    {\n      eigen_internal_assert(index >= 0 && index < size());\n      return m_storage.data()[index];\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& coeffRef()\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return m_storage.data()[0];\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator()(Index firstIndex, IndexTypes... otherIndices) const\n    {\n      // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return this->operator()(array<Index, NumIndices>{{firstIndex, otherIndices...}});\n    }\n#else\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1) const\n    {\n      if (Options&RowMajor) {\n        const Index index = i1 + i0 * m_storage.dimensions()[1];\n        return m_storage.data()[index];\n      } else {\n        const Index index = i0 + i1 * m_storage.dimensions()[0];\n        return m_storage.data()[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2) const\n    {\n      if (Options&RowMajor) {\n         const Index index = i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0);\n         return m_storage.data()[index];\n      } else {\n         const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * i2);\n        return m_storage.data()[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2, Index i3) const\n    {\n      if (Options&RowMajor) {\n        const Index index = i3 + m_storage.dimensions()[3] * (i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0));\n        return m_storage.data()[index];\n      } else {\n        const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * (i2 + m_storage.dimensions()[2] * i3));\n        return m_storage.data()[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2, Index i3, Index i4) const\n    {\n      if (Options&RowMajor) {\n        const Index index = i4 + m_storage.dimensions()[4] * (i3 + m_storage.dimensions()[3] * (i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0)));\n        return m_storage.data()[index];\n      } else {\n        const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * (i2 + m_storage.dimensions()[2] * (i3 + m_storage.dimensions()[3] * i4)));\n        return m_storage.data()[index];\n      }\n    }\n#endif\n\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()(const array<Index, NumIndices>& indices) const\n    {\n      eigen_assert(checkIndexRange(indices));\n      return coeff(indices);\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()(Index index) const\n    {\n      eigen_internal_assert(index >= 0 && index < size());\n      return coeff(index);\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()() const\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return coeff();\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator[](Index index) const\n    {\n      // The bracket operator is only for vectors, use the parenthesis operator instead.\n      EIGEN_STATIC_ASSERT(NumIndices == 1, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return coeff(index);\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator()(Index firstIndex, IndexTypes... otherIndices)\n    {\n      // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return operator()(array<Index, NumIndices>{{firstIndex, otherIndices...}});\n    }\n#else\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1)\n    {\n       if (Options&RowMajor) {\n         const Index index = i1 + i0 * m_storage.dimensions()[1];\n        return m_storage.data()[index];\n      } else {\n        const Index index = i0 + i1 * m_storage.dimensions()[0];\n        return m_storage.data()[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2)\n    {\n       if (Options&RowMajor) {\n         const Index index = i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0);\n        return m_storage.data()[index];\n      } else {\n         const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * i2);\n        return m_storage.data()[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3)\n    {\n      if (Options&RowMajor) {\n        const Index index = i3 + m_storage.dimensions()[3] * (i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0));\n        return m_storage.data()[index];\n      } else {\n        const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * (i2 + m_storage.dimensions()[2] * i3));\n        return m_storage.data()[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3, Index i4)\n    {\n      if (Options&RowMajor) {\n        const Index index = i4 + m_storage.dimensions()[4] * (i3 + m_storage.dimensions()[3] * (i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0)));\n        return m_storage.data()[index];\n      } else {\n        const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * (i2 + m_storage.dimensions()[2] * (i3 + m_storage.dimensions()[3] * i4)));\n        return m_storage.data()[index];\n      }\n    }\n#endif\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(const array<Index, NumIndices>& indices)\n    {\n      eigen_assert(checkIndexRange(indices));\n      return coeffRef(indices);\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(Index index)\n    {\n      eigen_assert(index >= 0 && index < size());\n      return coeffRef(index);\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()()\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return coeffRef();\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator[](Index index)\n    {\n      // The bracket operator is only for vectors, use the parenthesis operator instead\n      EIGEN_STATIC_ASSERT(NumIndices == 1, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return coeffRef(index);\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorFixedSize()\n      : m_storage()\n    {\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorFixedSize(const Self& other)\n      : m_storage(other.m_storage)\n    {\n    }\n\n#if EIGEN_HAS_RVALUE_REFERENCES\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorFixedSize(Self&& other)\n      : m_storage(other.m_storage)\n    {\n    }\n#endif\n\n    template<typename OtherDerived>\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorFixedSize(const TensorBase<OtherDerived, ReadOnlyAccessors>& other)\n    {\n      typedef TensorAssignOp<TensorFixedSize, const OtherDerived> Assign;\n      Assign assign(*this, other.derived());\n      internal::TensorExecutor<const Assign, DefaultDevice>::run(assign, DefaultDevice());\n    }\n    template<typename OtherDerived>\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorFixedSize(const TensorBase<OtherDerived, WriteAccessors>& other)\n    {\n      typedef TensorAssignOp<TensorFixedSize, const OtherDerived> Assign;\n      Assign assign(*this, other.derived());\n      internal::TensorExecutor<const Assign, DefaultDevice>::run(assign, DefaultDevice());\n    }\n\n    // FIXME: check that the dimensions of other match the dimensions of *this.\n    // Unfortunately this isn't possible yet when the rhs is an expression.\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(TensorFixedSize)\n\n\n  protected:\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE bool checkIndexRange(const array<Index, NumIndices>& /*indices*/) const\n    {\n      using internal::array_apply_and_reduce;\n      using internal::array_zip_and_reduce;\n      using internal::greater_equal_zero_op;\n      using internal::logical_and_op;\n      using internal::lesser_op;\n\n      return true;\n        // check whether the indices are all >= 0\n          /*       array_apply_and_reduce<logical_and_op, greater_equal_zero_op>(indices) &&\n        // check whether the indices fit in the dimensions\n        array_zip_and_reduce<logical_and_op, lesser_op>(indices, m_storage.dimensions());*/\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Index linearizedIndex(const array<Index, NumIndices>& indices) const\n    {\n      if (Options&RowMajor) {\n        return m_storage.dimensions().IndexOfRowMajor(indices);\n      } else {\n        return m_storage.dimensions().IndexOfColMajor(indices);\n      }\n    }\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_FIXED_SIZE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorForcedEval.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_FORCED_EVAL_H\n#define EIGEN_CXX11_TENSOR_TENSOR_FORCED_EVAL_H\n\nnamespace Eigen {\n\n/** \\class TensorForcedEval\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor reshaping class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename XprType>\nstruct traits<TensorForcedEvalOp<XprType> >\n{\n  // Type promotion to handle the case where the types of the lhs and the rhs are different.\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename traits<XprType>::StorageKind StorageKind;\n  typedef typename traits<XprType>::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n\n  enum {\n    Flags = 0\n  };\n};\n\ntemplate<typename XprType>\nstruct eval<TensorForcedEvalOp<XprType>, Eigen::Dense>\n{\n  typedef const TensorForcedEvalOp<XprType>& type;\n};\n\ntemplate<typename XprType>\nstruct nested<TensorForcedEvalOp<XprType>, 1, typename eval<TensorForcedEvalOp<XprType> >::type>\n{\n  typedef TensorForcedEvalOp<XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename XprType>\nclass TensorForcedEvalOp : public TensorBase<TensorForcedEvalOp<XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorForcedEvalOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename internal::remove_const<typename XprType::CoeffReturnType>::type CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorForcedEvalOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorForcedEvalOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorForcedEvalOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorForcedEvalOp(const XprType& expr)\n      : m_xpr(expr) {}\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n};\n\nnamespace internal {\ntemplate <typename Device, typename CoeffReturnType>\nstruct non_integral_type_placement_new{\n  template <typename StorageType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void operator()(Index numValues, StorageType m_buffer) {\n   // Initialize non-trivially constructible types.\n    if (!internal::is_arithmetic<CoeffReturnType>::value) {\n      for (Index i = 0; i < numValues; ++i) new (m_buffer + i) CoeffReturnType();\n    }\n}\n};\n\n// SYCL does not support non-integral types \n// having new (m_buffer + i) CoeffReturnType() causes the following compiler error for SYCL Devices \n// no matching function for call to 'operator new'\ntemplate <typename CoeffReturnType>\nstruct non_integral_type_placement_new<Eigen::SyclDevice, CoeffReturnType> {\n  template <typename StorageType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void operator()(Index, StorageType) {\n}\n};\n} // end namespace internal\n\ntemplate<typename ArgType_, typename Device>\nstruct TensorEvaluator<const TensorForcedEvalOp<ArgType_>, Device>\n{\n  typedef const typename internal::remove_all<ArgType_>::type ArgType;\n  typedef TensorForcedEvalOp<ArgType> XprType;\n  typedef typename ArgType::Scalar Scalar;\n  typedef typename TensorEvaluator<ArgType, Device>::Dimensions Dimensions;\n  typedef typename XprType::Index Index;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef typename Eigen::internal::traits<XprType>::PointerType TensorPointerType;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned         = true,\n    PacketAccess      = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess       = internal::is_arithmetic<CoeffReturnType>::value,\n    PreferBlockAccess = false,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    RawAccess         = true\n  };\n\n  static const int NumDims = internal::traits<ArgType>::NumDimensions;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename internal::TensorMaterializedBlock<CoeffReturnType, NumDims,\n                                                     Layout, Index>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device), m_op(op.expression()),\n      m_device(device), m_buffer(NULL)\n  { }\n\n  EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_impl.dimensions(); }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    const Index numValues =  internal::array_prod(m_impl.dimensions());\n    m_buffer = m_device.get((CoeffReturnType*)m_device.allocate_temp(numValues * sizeof(CoeffReturnType)));\n\n   internal::non_integral_type_placement_new<Device, CoeffReturnType>()(numValues, m_buffer);\n\n    typedef TensorEvalToOp< const typename internal::remove_const<ArgType>::type > EvalTo;\n    EvalTo evalToTmp(m_device.get(m_buffer), m_op);\n\n    internal::TensorExecutor<\n        const EvalTo, typename internal::remove_const<Device>::type,\n        /*Vectorizable=*/internal::IsVectorizable<Device, const ArgType>::value,\n        /*Tiling=*/internal::IsTileable<Device, const ArgType>::value>::\n        run(evalToTmp, m_device);\n\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    const Index numValues = internal::array_prod(m_impl.dimensions());\n    m_buffer = m_device.get((CoeffReturnType*)m_device.allocate_temp(\n        numValues * sizeof(CoeffReturnType)));\n    typedef TensorEvalToOp<const typename internal::remove_const<ArgType>::type>\n        EvalTo;\n    EvalTo evalToTmp(m_device.get(m_buffer), m_op);\n\n    auto on_done = std::bind([](EvalSubExprsCallback done_) { done_(true); },\n                             std::move(done));\n    internal::TensorAsyncExecutor<\n        const EvalTo, typename internal::remove_const<Device>::type,\n        decltype(on_done),\n        /*Vectorizable=*/internal::IsVectorizable<Device, const ArgType>::value,\n        /*Tiling=*/internal::IsTileable<Device, const ArgType>::value>::\n        runAsync(evalToTmp, m_device, std::move(on_done));\n  }\n#endif\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_device.deallocate_temp(m_buffer);\n    m_buffer = NULL;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    return m_buffer[index];\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    return internal::ploadt<PacketReturnType, LoadMode>(m_buffer + index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    return internal::TensorBlockResourceRequirements::any();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    assert(m_buffer != NULL);\n    return TensorBlock::materialize(m_buffer, m_impl.dimensions(), desc, scratch);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  EvaluatorPointerType data() const { return m_buffer; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_buffer.bind(cgh);\n    m_impl.bind(cgh);\n  }\n#endif\n private:\n  TensorEvaluator<ArgType, Device> m_impl;\n  const ArgType m_op;\n  const Device EIGEN_DEVICE_REF m_device;\n  EvaluatorPointerType m_buffer;\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_FORCED_EVAL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorForwardDeclarations.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_FORWARD_DECLARATIONS_H\n#define EIGEN_CXX11_TENSOR_TENSOR_FORWARD_DECLARATIONS_H\n\nnamespace Eigen {\n\n// MakePointer class is used as a container of the address space of the pointer\n// on the host and on the device. From the host side it generates the T* pointer\n// and when EIGEN_USE_SYCL is used it construct a buffer with a map_allocator to\n// T* m_data on the host. It is always called on the device.\n// Specialisation of MakePointer class for creating the sycl buffer with\n// map_allocator.\ntemplate<typename T> struct MakePointer {\n  typedef T* Type;\n  typedef const T* ConstType;\n};\n\ntemplate <typename T>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T* constCast(const T* data) {\n  return const_cast<T*>(data);\n}\n\n// The StorageMemory class is a container of the device specific pointer\n// used for refering to a Pointer on TensorEvaluator class. While the TensorExpression\n// is a device-agnostic type and need MakePointer class for type conversion,\n// the TensorEvaluator class can be specialized for a device, hence it is possible\n// to construct different types of temproray storage memory in TensorEvaluator\n// for different devices by specializing the following StorageMemory class.\ntemplate<typename T, typename device> struct StorageMemory: MakePointer <T> {};\n\nnamespace internal{\ntemplate<typename A, typename B> struct Pointer_type_promotion {\n  static const bool val=false;\n};\ntemplate<typename A> struct Pointer_type_promotion<A, A> {\n  static const bool val = true;\n};\ntemplate<typename A, typename B> struct TypeConversion {\n  typedef A* type;\n};\n}\n\n\ntemplate<typename PlainObjectType, int Options_ = Unaligned, template <class> class MakePointer_ = MakePointer> class TensorMap;\ntemplate<typename Scalar_, int NumIndices_, int Options_ = 0, typename IndexType = DenseIndex> class Tensor;\ntemplate<typename Scalar_, typename Dimensions, int Options_ = 0, typename IndexType = DenseIndex> class TensorFixedSize;\ntemplate<typename PlainObjectType> class TensorRef;\ntemplate<typename Derived, int AccessLevel> class TensorBase;\n\ntemplate<typename NullaryOp, typename PlainObjectType> class TensorCwiseNullaryOp;\ntemplate<typename UnaryOp, typename XprType> class TensorCwiseUnaryOp;\ntemplate<typename BinaryOp, typename LeftXprType, typename RightXprType> class TensorCwiseBinaryOp;\ntemplate<typename TernaryOp, typename Arg1XprType, typename Arg2XprType, typename Arg3XprType> class TensorCwiseTernaryOp;\ntemplate<typename IfXprType, typename ThenXprType, typename ElseXprType> class TensorSelectOp;\ntemplate<typename Op, typename Dims, typename XprType, template <class> class MakePointer_ = MakePointer > class TensorReductionOp;\ntemplate<typename XprType> class TensorIndexTupleOp;\ntemplate<typename ReduceOp, typename Dims, typename XprType> class TensorTupleReducerOp;\ntemplate<typename Axis, typename LeftXprType, typename RightXprType> class TensorConcatenationOp;\ntemplate<typename Dimensions, typename LeftXprType, typename RightXprType, typename OutputKernelType> class TensorContractionOp;\ntemplate<typename TargetType, typename XprType> class TensorConversionOp;\ntemplate<typename Dimensions, typename InputXprType, typename KernelXprType> class TensorConvolutionOp;\ntemplate<typename FFT, typename XprType, int FFTDataType, int FFTDirection> class TensorFFTOp;\ntemplate<typename PatchDim, typename XprType> class TensorPatchOp;\ntemplate<DenseIndex Rows, DenseIndex Cols, typename XprType> class TensorImagePatchOp;\ntemplate<DenseIndex Planes, DenseIndex Rows, DenseIndex Cols, typename XprType> class TensorVolumePatchOp;\ntemplate<typename Broadcast, typename XprType> class TensorBroadcastingOp;\ntemplate<DenseIndex DimId, typename XprType> class TensorChippingOp;\ntemplate<typename NewDimensions, typename XprType> class TensorReshapingOp;\ntemplate<typename XprType> class TensorLayoutSwapOp;\ntemplate<typename StartIndices, typename Sizes, typename XprType> class TensorSlicingOp;\ntemplate<typename ReverseDimensions, typename XprType> class TensorReverseOp;\ntemplate<typename PaddingDimensions, typename XprType> class TensorPaddingOp;\ntemplate<typename Shuffle, typename XprType> class TensorShufflingOp;\ntemplate<typename Strides, typename XprType> class TensorStridingOp;\ntemplate<typename StartIndices, typename StopIndices, typename Strides, typename XprType> class TensorStridingSlicingOp;\ntemplate<typename Strides, typename XprType> class TensorInflationOp;\ntemplate<typename Generator, typename XprType> class TensorGeneratorOp;\ntemplate<typename LeftXprType, typename RightXprType> class TensorAssignOp;\ntemplate<typename Op, typename XprType> class TensorScanOp;\ntemplate<typename Dims, typename XprType> class TensorTraceOp;\n\ntemplate<typename CustomUnaryFunc, typename XprType> class TensorCustomUnaryOp;\ntemplate<typename CustomBinaryFunc, typename LhsXprType, typename RhsXprType> class TensorCustomBinaryOp;\n\ntemplate<typename XprType, template <class> class MakePointer_ = MakePointer> class TensorEvalToOp;\ntemplate<typename XprType> class TensorForcedEvalOp;\n\ntemplate<typename ExpressionType, typename DeviceType> class TensorDevice;\ntemplate<typename ExpressionType, typename DeviceType, typename DoneCallback> class TensorAsyncDevice;\ntemplate<typename Derived, typename Device> struct TensorEvaluator;\n\nstruct NoOpOutputKernel;\n\nstruct DefaultDevice;\nstruct ThreadPoolDevice;\nstruct GpuDevice;\nstruct SyclDevice;\n\n#ifdef EIGEN_USE_SYCL\n\ntemplate <typename T> struct MakeSYCLPointer {\n  typedef Eigen::TensorSycl::internal::RangeAccess<cl::sycl::access::mode::read_write, T> Type;\n};\n\ntemplate <typename T>\nEIGEN_STRONG_INLINE const Eigen::TensorSycl::internal::RangeAccess<cl::sycl::access::mode::read_write, T>&\nconstCast(const Eigen::TensorSycl::internal::RangeAccess<cl::sycl::access::mode::read_write, T>& data) {\n  return data;\n}\n\ntemplate <typename T>\nstruct StorageMemory<T, SyclDevice> : MakeSYCLPointer<T> {};\ntemplate <typename T>\nstruct StorageMemory<T, const SyclDevice> : StorageMemory<T, SyclDevice> {};\n\nnamespace TensorSycl {\nnamespace internal{\ntemplate <typename Evaluator, typename Op> class GenericNondeterministicReducer;\n}\n}\n#endif\n\n\nenum FFTResultType {\n  RealPart = 0,\n  ImagPart = 1,\n  BothParts = 2\n};\n\nenum FFTDirection {\n    FFT_FORWARD = 0,\n    FFT_REVERSE = 1\n};\n\n\nnamespace internal {\n\ntemplate <typename Device, typename Expression>\nstruct IsVectorizable {\n  static const bool value = TensorEvaluator<Expression, Device>::PacketAccess;\n};\n\ntemplate <typename Expression>\nstruct IsVectorizable<GpuDevice, Expression> {\n  static const bool value = TensorEvaluator<Expression, GpuDevice>::PacketAccess &&\n                            TensorEvaluator<Expression, GpuDevice>::IsAligned;\n};\n\n// Tiled evaluation strategy.\nenum TiledEvaluation {\n  Off = 0,    // tiled evaluation is not supported\n  On = 1,     // still work in progress (see TensorBlock.h)\n};\n\ntemplate <typename Device, typename Expression>\nstruct IsTileable {\n  // Check that block evaluation is supported and it's a preferred option (at\n  // least one sub-expression has much faster block evaluation, e.g.\n  // broadcasting).\n  static const bool BlockAccess =\n      TensorEvaluator<Expression, Device>::BlockAccess &&\n      TensorEvaluator<Expression, Device>::PreferBlockAccess;\n\n  static const TiledEvaluation value =\n      BlockAccess ? TiledEvaluation::On : TiledEvaluation::Off;\n};\n\ntemplate <typename Expression, typename Device,\n          bool Vectorizable      = IsVectorizable<Device, Expression>::value,\n          TiledEvaluation Tiling = IsTileable<Device, Expression>::value>\nclass TensorExecutor;\n\ntemplate <typename Expression, typename Device, typename DoneCallback,\n          bool Vectorizable = IsVectorizable<Device, Expression>::value,\n          TiledEvaluation Tiling = IsTileable<Device, Expression>::value>\nclass TensorAsyncExecutor;\n\n\n}  // end namespace internal\n\n}  // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_FORWARD_DECLARATIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFunctors.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_FUNCTORS_H\n#define EIGEN_CXX11_TENSOR_TENSOR_FUNCTORS_H\n\nnamespace Eigen {\nnamespace internal {\n\n\n/** \\internal\n * \\brief Template functor to compute the modulo between an array and a scalar.\n */\ntemplate <typename Scalar>\nstruct scalar_mod_op {\n  EIGEN_DEVICE_FUNC scalar_mod_op(const Scalar& divisor) : m_divisor(divisor) {}\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar operator() (const Scalar& a) const { return a % m_divisor; }\n  const Scalar m_divisor;\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_mod_op<Scalar> >\n{ enum { Cost = scalar_div_cost<Scalar,false>::value, PacketAccess = false }; };\n\n\n/** \\internal\n * \\brief Template functor to compute the modulo between 2 arrays.\n */\ntemplate <typename Scalar>\nstruct scalar_mod2_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_mod2_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar operator() (const Scalar& a, const Scalar& b) const { return a % b; }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_mod2_op<Scalar> >\n{ enum { Cost = scalar_div_cost<Scalar,false>::value, PacketAccess = false }; };\n\ntemplate <typename Scalar>\nstruct scalar_fmod_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_fmod_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar\n  operator()(const Scalar& a, const Scalar& b) const {\n    return numext::fmod(a, b);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_fmod_op<Scalar> > {\n  enum { Cost = 13,  // Reciprocal throughput of FPREM on Haswell.\n         PacketAccess = false };\n};\n\ntemplate<typename Reducer, typename Device>\nstruct reducer_traits {\n  enum {\n    Cost = 1,\n    PacketAccess = false,\n    IsStateful = false,\n    IsExactlyAssociative = true\n  };\n};\n\n// Standard reduction functors\ntemplate <typename T> struct SumReducer\n{\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) const {\n    internal::scalar_sum_op<T> sum_op;\n    *accum = sum_op(*accum, t);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reducePacket(const Packet& p, Packet* accum) const {\n    (*accum) = padd<Packet>(*accum, p);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const {\n    internal::scalar_cast_op<int, T> conv;\n    return conv(0);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet initializePacket() const {\n    return pset1<Packet>(initialize());\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T accum) const {\n    return accum;\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet finalizePacket(const Packet& vaccum) const {\n    return vaccum;\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalizeBoth(const T saccum, const Packet& vaccum) const {\n    internal::scalar_sum_op<T> sum_op;\n    return sum_op(saccum, predux(vaccum));\n  }\n};\n\ntemplate <typename T, typename Device>\nstruct reducer_traits<SumReducer<T>, Device> {\n  enum {\n    Cost = NumTraits<T>::AddCost,\n    PacketAccess = PacketType<T, Device>::HasAdd,\n    IsStateful = false,\n    IsExactlyAssociative = NumTraits<T>::IsInteger\n  };\n};\n\ntemplate <typename T> struct MeanReducer\n{\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  MeanReducer() : scalarCount_(0), packetCount_(0) { }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) {\n    internal::scalar_sum_op<T> sum_op;\n    *accum = sum_op(*accum, t);\n    scalarCount_++;\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reducePacket(const Packet& p, Packet* accum) {\n    (*accum) = padd<Packet>(*accum, p);\n    packetCount_++;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const {\n    internal::scalar_cast_op<int, T> conv;\n    return conv(0);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet initializePacket() const {\n    return pset1<Packet>(initialize());\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T accum) const {\n    internal::scalar_quotient_op<T> quotient_op;\n    return quotient_op(accum, T(scalarCount_));\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet finalizePacket(const Packet& vaccum) const {\n    return pdiv(vaccum, pset1<Packet>(T(packetCount_)));\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalizeBoth(const T saccum, const Packet& vaccum) const {\n    internal::scalar_sum_op<T> sum_op;\n    internal::scalar_quotient_op<T> quotient_op;\n    return quotient_op(\n        sum_op(saccum, predux(vaccum)),\n        T(scalarCount_ + packetCount_ * unpacket_traits<Packet>::size));\n  }\n\n  protected:\n    DenseIndex scalarCount_;\n    DenseIndex packetCount_;\n};\n\ntemplate <typename T, typename Device>\nstruct reducer_traits<MeanReducer<T>, Device> {\n  enum {\n    Cost = NumTraits<T>::AddCost,\n    PacketAccess = PacketType<T, Device>::HasAdd &&\n                   PacketType<T, Device>::HasDiv && !NumTraits<T>::IsInteger,\n    IsStateful = true,\n    IsExactlyAssociative = NumTraits<T>::IsInteger\n  };\n};\n\n\ntemplate <typename T, bool IsMax = true, bool IsInteger = true>\nstruct MinMaxBottomValue {\n  EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE T bottom_value() {\n    return Eigen::NumTraits<T>::lowest();\n  }\n};\ntemplate <typename T>\nstruct MinMaxBottomValue<T, true, false> {\n  EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE T bottom_value() {\n    return -Eigen::NumTraits<T>::infinity();\n  }\n};\ntemplate <typename T>\nstruct MinMaxBottomValue<T, false, true> {\n  EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE T bottom_value() {\n    return Eigen::NumTraits<T>::highest();\n  }\n};\ntemplate <typename T>\nstruct MinMaxBottomValue<T, false, false> {\n  EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE T bottom_value() {\n    return Eigen::NumTraits<T>::infinity();\n  }\n};\n\n\ntemplate <typename T, int NaNPropagation=PropagateFast> struct MaxReducer\n{\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) const {\n    scalar_max_op<T, T, NaNPropagation> op;\n    *accum = op(t, *accum);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reducePacket(const Packet& p, Packet* accum) const {\n    scalar_max_op<T, T, NaNPropagation> op;\n    (*accum) = op.packetOp(*accum, p);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const {\n    return MinMaxBottomValue<T, /*IsMax=*/true, Eigen::NumTraits<T>::IsInteger>::bottom_value();\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet initializePacket() const {\n    return pset1<Packet>(initialize());\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T accum) const {\n    return accum;\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet finalizePacket(const Packet& vaccum) const {\n    return vaccum;\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalizeBoth(const T saccum, const Packet& vaccum) const {\n    scalar_max_op<T, T, NaNPropagation> op;\n    return op(saccum, op.predux(vaccum));\n  }\n};\n\ntemplate <typename T, typename Device, int NaNPropagation>\n    struct reducer_traits<MaxReducer<T, NaNPropagation>, Device> {\n  enum {\n    Cost = NumTraits<T>::AddCost,\n    PacketAccess = PacketType<T, Device>::HasMax,\n    IsStateful = false,\n    IsExactlyAssociative = (NaNPropagation!=PropagateFast)\n  };\n};\n\ntemplate <typename T, int NaNPropagation=PropagateFast> struct MinReducer\n{\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) const {\n    scalar_min_op<T, T, NaNPropagation> op;\n    *accum = op(t, *accum);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reducePacket(const Packet& p, Packet* accum) const {\n    scalar_min_op<T, T, NaNPropagation> op;\n    (*accum) = op.packetOp(*accum, p);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const {\n    return MinMaxBottomValue<T, /*IsMax=*/false, Eigen::NumTraits<T>::IsInteger>::bottom_value();\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet initializePacket() const {\n    return pset1<Packet>(initialize());\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T accum) const {\n    return accum;\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet finalizePacket(const Packet& vaccum) const {\n    return vaccum;\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalizeBoth(const T saccum, const Packet& vaccum) const {\n    scalar_min_op<T, T, NaNPropagation> op;\n    return op(saccum, op.predux(vaccum));\n  }\n};\n\ntemplate <typename T, typename Device, int NaNPropagation>\n    struct reducer_traits<MinReducer<T, NaNPropagation>, Device> {\n  enum {\n    Cost = NumTraits<T>::AddCost,\n    PacketAccess = PacketType<T, Device>::HasMin,\n    IsStateful = false,\n    IsExactlyAssociative = (NaNPropagation!=PropagateFast)\n  };\n};\n\ntemplate <typename T> struct ProdReducer\n{\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) const {\n    internal::scalar_product_op<T> prod_op;\n    (*accum) = prod_op(*accum, t);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reducePacket(const Packet& p, Packet* accum) const {\n    (*accum) = pmul<Packet>(*accum, p);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const {\n    internal::scalar_cast_op<int, T> conv;\n    return conv(1);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet initializePacket() const {\n    return pset1<Packet>(initialize());\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T accum) const {\n    return accum;\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet finalizePacket(const Packet& vaccum) const {\n    return vaccum;\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalizeBoth(const T saccum, const Packet& vaccum) const {\n    internal::scalar_product_op<T> prod_op;\n    return prod_op(saccum, predux_mul(vaccum));\n  }\n};\n\ntemplate <typename T, typename Device>\nstruct reducer_traits<ProdReducer<T>, Device> {\n  enum {\n    Cost = NumTraits<T>::MulCost,\n    PacketAccess = PacketType<T, Device>::HasMul,\n    IsStateful = false,\n    IsExactlyAssociative = true\n  };\n};\n\n\nstruct AndReducer\n{\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(bool t, bool* accum) const {\n    *accum = *accum && t;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool initialize() const {\n    return true;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool finalize(bool accum) const {\n    return accum;\n  }\n};\n\ntemplate <typename Device>\nstruct reducer_traits<AndReducer, Device> {\n  enum {\n    Cost = 1,\n    PacketAccess = false,\n    IsStateful = false,\n    IsExactlyAssociative = true\n  };\n};\n\n\nstruct OrReducer {\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(bool t, bool* accum) const {\n    *accum = *accum || t;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool initialize() const {\n    return false;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool finalize(bool accum) const {\n    return accum;\n  }\n};\n\ntemplate <typename Device>\nstruct reducer_traits<OrReducer, Device> {\n  enum {\n    Cost = 1,\n    PacketAccess = false,\n    IsStateful = false,\n    IsExactlyAssociative = true\n  };\n};\n\n// Argmin/Argmax reducers.  Returns the first occurrence if multiple locations\n// contain the same min/max value.\ntemplate <typename T> struct ArgMaxTupleReducer\n{\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) const {\n    if (t.second < accum->second) {\n      return;\n    } else if (t.second > accum->second || accum->first > t.first ) {\n      *accum = t;\n    }\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const {\n    return T(0, NumTraits<typename T::second_type>::lowest());\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T& accum) const {\n    return accum;\n  }\n};\n\ntemplate <typename T, typename Device>\nstruct reducer_traits<ArgMaxTupleReducer<T>, Device> {\n  enum {\n    Cost = NumTraits<T>::AddCost,\n    PacketAccess = false,\n    IsStateful = false,\n    IsExactlyAssociative = true\n  };\n};\n\n\ntemplate <typename T> struct ArgMinTupleReducer\n{\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T& t, T* accum) const {\n    if (t.second > accum->second) {\n      return;\n    } else if (t.second < accum->second || accum->first > t.first) {\n      *accum = t;\n    }\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const {\n    return T(0, NumTraits<typename T::second_type>::highest());\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T& accum) const {\n    return accum;\n  }\n};\n\ntemplate <typename T, typename Device>\nstruct reducer_traits<ArgMinTupleReducer<T>, Device> {\n  enum {\n    Cost = NumTraits<T>::AddCost,\n    PacketAccess = false,\n    IsStateful = false,\n    IsExactlyAssociative = true\n  };\n};\n\n\ntemplate <typename T, typename Index, size_t NumDims>\nclass GaussianGenerator {\n public:\n  static const bool PacketAccess = false;\n\n  EIGEN_DEVICE_FUNC GaussianGenerator(const array<T, NumDims>& means,\n                                      const array<T, NumDims>& std_devs)\n      : m_means(means)\n  {\n    EIGEN_UNROLL_LOOP\n    for (size_t i = 0; i < NumDims; ++i) {\n      m_two_sigmas[i] = std_devs[i] * std_devs[i] * 2;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC T operator()(const array<Index, NumDims>& coordinates) const {\n    T tmp = T(0);\n    EIGEN_UNROLL_LOOP\n    for (size_t i = 0; i < NumDims; ++i) {\n      T offset = coordinates[i] - m_means[i];\n      tmp += offset * offset / m_two_sigmas[i];\n    }\n    return numext::exp(-tmp);\n  }\n\n private:\n  array<T, NumDims> m_means;\n  array<T, NumDims> m_two_sigmas;\n};\n\ntemplate <typename T, typename Index, size_t NumDims>\nstruct functor_traits<GaussianGenerator<T, Index, NumDims> > {\n  enum {\n    Cost = NumDims * (2 * NumTraits<T>::AddCost + NumTraits<T>::MulCost +\n                      functor_traits<scalar_quotient_op<T, T> >::Cost) +\n           functor_traits<scalar_exp_op<T> >::Cost,\n    PacketAccess = GaussianGenerator<T, Index, NumDims>::PacketAccess\n  };\n};\n\ntemplate <typename Scalar>\nstruct scalar_clamp_op {\n  EIGEN_DEVICE_FUNC inline scalar_clamp_op(const Scalar& _min, const Scalar& _max) : m_min(_min), m_max(_max) {}\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar\n  operator()(const Scalar& x) const {\n    return numext::mini(numext::maxi(x, m_min), m_max);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet\n  packetOp(const Packet& x) const {\n    return internal::pmin(internal::pmax(x, pset1<Packet>(m_min)), pset1<Packet>(m_max));\n  }\n  const Scalar m_min;\n  const Scalar m_max;\n};\ntemplate<typename Scalar>\nstruct functor_traits<scalar_clamp_op<Scalar> >\n{ enum { Cost = 2 * NumTraits<Scalar>::AddCost, PacketAccess = (packet_traits<Scalar>::HasMin && packet_traits<Scalar>::HasMax)}; };\n\n} // end namespace internal\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_FUNCTORS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGenerator.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_GENERATOR_H\n#define EIGEN_CXX11_TENSOR_TENSOR_GENERATOR_H\n\nnamespace Eigen {\n\n/** \\class TensorGeneratorOp\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor generator class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename Generator, typename XprType>\nstruct traits<TensorGeneratorOp<Generator, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename Generator, typename XprType>\nstruct eval<TensorGeneratorOp<Generator, XprType>, Eigen::Dense>\n{\n  typedef const TensorGeneratorOp<Generator, XprType>& type;\n};\n\ntemplate<typename Generator, typename XprType>\nstruct nested<TensorGeneratorOp<Generator, XprType>, 1, typename eval<TensorGeneratorOp<Generator, XprType> >::type>\n{\n  typedef TensorGeneratorOp<Generator, XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename Generator, typename XprType>\nclass TensorGeneratorOp : public TensorBase<TensorGeneratorOp<Generator, XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorGeneratorOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorGeneratorOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorGeneratorOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorGeneratorOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorGeneratorOp(const XprType& expr, const Generator& generator)\n      : m_xpr(expr), m_generator(generator) {}\n\n    EIGEN_DEVICE_FUNC\n    const Generator& generator() const { return m_generator; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const Generator m_generator;\n};\n\n\n// Eval as rvalue\ntemplate<typename Generator, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorGeneratorOp<Generator, ArgType>, Device>\n{\n  typedef TensorGeneratorOp<Generator, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  typedef typename TensorEvaluator<ArgType, Device>::Dimensions Dimensions;\n  static const int NumDims = internal::array_size<Dimensions>::value;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n  enum {\n    IsAligned         = false,\n    PacketAccess      = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess       = true,\n    PreferBlockAccess = true,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = false\n  };\n\n  typedef internal::TensorIntDivisor<Index> IndexDivisor;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename internal::TensorMaterializedBlock<CoeffReturnType, NumDims,\n                                                     Layout, Index>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      :  m_device(device), m_generator(op.generator())\n  {\n    TensorEvaluator<ArgType, Device> argImpl(op.expression(), device);\n    m_dimensions = argImpl.dimensions();\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_strides[0] = 1;\n      EIGEN_UNROLL_LOOP\n      for (int i = 1; i < NumDims; ++i) {\n        m_strides[i] = m_strides[i - 1] * m_dimensions[i - 1];\n        if (m_strides[i] != 0) m_fast_strides[i] = IndexDivisor(m_strides[i]);\n      }\n    } else {\n      m_strides[NumDims - 1] = 1;\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_strides[i] = m_strides[i + 1] * m_dimensions[i + 1];\n        if (m_strides[i] != 0) m_fast_strides[i] = IndexDivisor(m_strides[i]);\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType /*data*/) {\n    return true;\n  }\n  EIGEN_STRONG_INLINE void cleanup() {\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    array<Index, NumDims> coords;\n    extract_coordinates(index, coords);\n    return m_generator(coords);\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    const int packetSize = PacketType<CoeffReturnType, Device>::size;\n    EIGEN_STATIC_ASSERT((packetSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+packetSize-1 < dimensions().TotalSize());\n\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[packetSize];\n    for (int i = 0; i < packetSize; ++i) {\n      values[i] = coeff(index+i);\n    }\n    PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n    return rslt;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    const size_t target_size = m_device.firstLevelCacheSize();\n    // TODO(ezhulenev): Generator should have a cost.\n    return internal::TensorBlockResourceRequirements::skewed<Scalar>(\n        target_size);\n  }\n\n  struct BlockIteratorState {\n    Index stride;\n    Index span;\n    Index size;\n    Index count;\n  };\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    static const bool is_col_major =\n        static_cast<int>(Layout) == static_cast<int>(ColMajor);\n\n    // Compute spatial coordinates for the first block element.\n    array<Index, NumDims> coords;\n    extract_coordinates(desc.offset(), coords);\n    array<Index, NumDims> initial_coords = coords;\n\n    // Offset in the output block buffer.\n    Index offset = 0;\n\n    // Initialize output block iterator state. Dimension in this array are\n    // always in inner_most -> outer_most order (col major layout).\n    array<BlockIteratorState, NumDims> it;\n    for (int i = 0; i < NumDims; ++i) {\n      const int dim = is_col_major ? i : NumDims - 1 - i;\n      it[i].size = desc.dimension(dim);\n      it[i].stride = i == 0 ? 1 : (it[i - 1].size * it[i - 1].stride);\n      it[i].span = it[i].stride * (it[i].size - 1);\n      it[i].count = 0;\n    }\n    eigen_assert(it[0].stride == 1);\n\n    // Prepare storage for the materialized generator result.\n    const typename TensorBlock::Storage block_storage =\n        TensorBlock::prepareStorage(desc, scratch);\n\n    CoeffReturnType* block_buffer = block_storage.data();\n\n    static const int packet_size = PacketType<CoeffReturnType, Device>::size;\n\n    static const int inner_dim = is_col_major ? 0 : NumDims - 1;\n    const Index inner_dim_size = it[0].size;\n    const Index inner_dim_vectorized = inner_dim_size - packet_size;\n\n    while (it[NumDims - 1].count < it[NumDims - 1].size) {\n      Index i = 0;\n      // Generate data for the vectorized part of the inner-most dimension.\n      for (; i <= inner_dim_vectorized; i += packet_size) {\n        for (Index j = 0; j < packet_size; ++j) {\n          array<Index, NumDims> j_coords = coords;  // Break loop dependence.\n          j_coords[inner_dim] += j;\n          *(block_buffer + offset + i + j) = m_generator(j_coords);\n        }\n        coords[inner_dim] += packet_size;\n      }\n      // Finalize non-vectorized part of the inner-most dimension.\n      for (; i < inner_dim_size; ++i) {\n        *(block_buffer + offset + i) = m_generator(coords);\n        coords[inner_dim]++;\n      }\n      coords[inner_dim] = initial_coords[inner_dim];\n\n      // For the 1d tensor we need to generate only one inner-most dimension.\n      if (NumDims == 1) break;\n\n      // Update offset.\n      for (i = 1; i < NumDims; ++i) {\n        if (++it[i].count < it[i].size) {\n          offset += it[i].stride;\n          coords[is_col_major ? i : NumDims - 1 - i]++;\n          break;\n        }\n        if (i != NumDims - 1) it[i].count = 0;\n        coords[is_col_major ? i : NumDims - 1 - i] =\n            initial_coords[is_col_major ? i : NumDims - 1 - i];\n        offset -= it[i].span;\n      }\n    }\n\n    return block_storage.AsTensorMaterializedBlock();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool) const {\n    // TODO(rmlarsen): This is just a placeholder. Define interface to make\n    // generators return their cost.\n    return TensorOpCost(0, 0, TensorOpCost::AddCost<Scalar>() +\n                                  TensorOpCost::MulCost<Scalar>());\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType  data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler&) const {}\n#endif\n\n protected:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void extract_coordinates(Index index, array<Index, NumDims>& coords) const {\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx = index / m_fast_strides[i];\n        index -= idx * m_strides[i];\n        coords[i] = idx;\n      }\n      coords[0] = index;\n    } else {\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx = index / m_fast_strides[i];\n        index -= idx * m_strides[i];\n        coords[i] = idx;\n      }\n      coords[NumDims-1] = index;\n    }\n  }\n\n  const Device EIGEN_DEVICE_REF m_device;\n  Dimensions m_dimensions;\n  array<Index, NumDims> m_strides;\n  array<IndexDivisor, NumDims> m_fast_strides;\n  Generator m_generator;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_GENERATOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGlobalFunctions.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Eugene Brevdo <ebrevdo@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_GLOBAL_FUNCTIONS_H\n#define EIGEN_CXX11_TENSOR_TENSOR_GLOBAL_FUNCTIONS_H\n\nnamespace Eigen {\n\n/** \\cpp11 \\returns an expression of the coefficient-wise betainc(\\a x, \\a a, \\a b) to the given tensors.\n *\n * This function computes the regularized incomplete beta function (integral).\n *\n */\ntemplate <typename ADerived, typename BDerived, typename XDerived>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const\n    TensorCwiseTernaryOp<internal::scalar_betainc_op<typename XDerived::Scalar>,\n                         const ADerived, const BDerived, const XDerived>\n    betainc(const ADerived& a, const BDerived& b, const XDerived& x) {\n  return TensorCwiseTernaryOp<\n      internal::scalar_betainc_op<typename XDerived::Scalar>, const ADerived,\n      const BDerived, const XDerived>(\n      a, b, x, internal::scalar_betainc_op<typename XDerived::Scalar>());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_GLOBAL_FUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGpuHipCudaDefines.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n// Copyright (C) 2018 Deven Desai <deven.desai.amd@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#if defined(EIGEN_USE_GPU) && !defined(EIGEN_CXX11_TENSOR_GPU_HIP_CUDA_DEFINES_H)\n#define EIGEN_CXX11_TENSOR_GPU_HIP_CUDA_DEFINES_H\n\n// Note that we are using EIGEN_USE_HIP here instead of EIGEN_HIPCC...this is by design\n// There is code in the Tensorflow codebase that will define EIGEN_USE_GPU,  but\n// for some reason gets sent to the gcc/host compiler instead of the gpu/nvcc/hipcc compiler\n// When compiling such files, gcc will end up trying to pick up the CUDA headers by \n// default (see the code within \"unsupported/Eigen/CXX11/Tensor\" that is guarded by EIGEN_USE_GPU)\n// This will obviously not work when trying to compile tensorflow on a system with no CUDA\n// To work around this issue for HIP systems (and leave the default behaviour intact), the\n// HIP tensorflow build defines EIGEN_USE_HIP when compiling all source files, and \n// \"unsupported/Eigen/CXX11/Tensor\" has been updated to use HIP header when EIGEN_USE_HIP is\n// defined. In continuation of that requirement, the guard here needs to be EIGEN_USE_HIP as well\n\n#if defined(EIGEN_USE_HIP)\n\n#define gpuStream_t hipStream_t\n#define gpuDeviceProp_t hipDeviceProp_t\n#define gpuError_t hipError_t\n#define gpuSuccess hipSuccess\n#define gpuErrorNotReady hipErrorNotReady\n#define gpuGetDeviceCount hipGetDeviceCount\n#define gpuGetLastError hipGetLastError\n#define gpuPeekAtLastError hipPeekAtLastError\n#define gpuGetErrorName hipGetErrorName\n#define gpuGetErrorString hipGetErrorString\n#define gpuGetDeviceProperties hipGetDeviceProperties\n#define gpuStreamDefault hipStreamDefault\n#define gpuGetDevice hipGetDevice\n#define gpuSetDevice hipSetDevice\n#define gpuMalloc hipMalloc\n#define gpuFree hipFree\n#define gpuMemsetAsync hipMemsetAsync\n#define gpuMemset2DAsync hipMemset2DAsync\n#define gpuMemcpyAsync hipMemcpyAsync\n#define gpuMemcpyDeviceToDevice hipMemcpyDeviceToDevice\n#define gpuMemcpyDeviceToHost hipMemcpyDeviceToHost\n#define gpuMemcpyHostToDevice hipMemcpyHostToDevice\n#define gpuStreamQuery hipStreamQuery\n#define gpuSharedMemConfig hipSharedMemConfig\n#define gpuDeviceSetSharedMemConfig hipDeviceSetSharedMemConfig\n#define gpuStreamSynchronize hipStreamSynchronize\n#define gpuDeviceSynchronize hipDeviceSynchronize\n#define gpuMemcpy hipMemcpy\n\n#else\n\n#define gpuStream_t cudaStream_t\n#define gpuDeviceProp_t cudaDeviceProp\n#define gpuError_t cudaError_t\n#define gpuSuccess cudaSuccess\n#define gpuErrorNotReady cudaErrorNotReady\n#define gpuGetDeviceCount cudaGetDeviceCount\n#define gpuGetLastError cudaGetLastError\n#define gpuPeekAtLastError cudaPeekAtLastError\n#define gpuGetErrorName cudaGetErrorName\n#define gpuGetErrorString cudaGetErrorString\n#define gpuGetDeviceProperties cudaGetDeviceProperties\n#define gpuStreamDefault cudaStreamDefault\n#define gpuGetDevice cudaGetDevice\n#define gpuSetDevice cudaSetDevice\n#define gpuMalloc cudaMalloc\n#define gpuFree cudaFree\n#define gpuMemsetAsync cudaMemsetAsync\n#define gpuMemset2DAsync cudaMemset2DAsync\n#define gpuMemcpyAsync cudaMemcpyAsync\n#define gpuMemcpyDeviceToDevice cudaMemcpyDeviceToDevice\n#define gpuMemcpyDeviceToHost cudaMemcpyDeviceToHost\n#define gpuMemcpyHostToDevice cudaMemcpyHostToDevice\n#define gpuStreamQuery cudaStreamQuery\n#define gpuSharedMemConfig cudaSharedMemConfig\n#define gpuDeviceSetSharedMemConfig cudaDeviceSetSharedMemConfig\n#define gpuStreamSynchronize cudaStreamSynchronize\n#define gpuDeviceSynchronize cudaDeviceSynchronize\n#define gpuMemcpy cudaMemcpy\n\n#endif\n\n// gpu_assert can be overridden\n#ifndef gpu_assert\n\n#if defined(EIGEN_HIP_DEVICE_COMPILE)\n// HIPCC do not support the use of assert on the GPU side.\n#define gpu_assert(COND)\n#else\n#define gpu_assert(COND) assert(COND)\n#endif\n\n#endif // gpu_assert\n\n#endif  // EIGEN_CXX11_TENSOR_GPU_HIP_CUDA_DEFINES_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGpuHipCudaUndefines.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n// Copyright (C) 2018 Deven Desai <deven.desai.amd@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#if defined(EIGEN_CXX11_TENSOR_GPU_HIP_CUDA_DEFINES_H)\n\n#ifndef EIGEN_PERMANENTLY_ENABLE_GPU_HIP_CUDA_DEFINES\n\n#undef gpuStream_t\n#undef gpuDeviceProp_t \n#undef gpuError_t\n#undef gpuSuccess\n#undef gpuErrorNotReady\n#undef gpuGetDeviceCount\n#undef gpuGetErrorString\n#undef gpuGetDeviceProperties\n#undef gpuStreamDefault\n#undef gpuGetDevice\n#undef gpuSetDevice\n#undef gpuMalloc\n#undef gpuFree\n#undef gpuMemsetAsync\n#undef gpuMemset2DAsync\n#undef gpuMemcpyAsync\n#undef gpuMemcpyDeviceToDevice\n#undef gpuMemcpyDeviceToHost\n#undef gpuMemcpyHostToDevice\n#undef gpuStreamQuery\n#undef gpuSharedMemConfig\n#undef gpuDeviceSetSharedMemConfig\n#undef gpuStreamSynchronize\n#undef gpuDeviceSynchronize\n#undef gpuMemcpy\n\n#endif // EIGEN_PERMANENTLY_ENABLE_GPU_HIP_CUDA_DEFINES\n\n#undef EIGEN_CXX11_TENSOR_GPU_HIP_CUDA_DEFINES_H\n\n#endif // EIGEN_CXX11_TENSOR_GPU_HIP_CUDA_DEFINES_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIO.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_IO_H\n#define EIGEN_CXX11_TENSOR_TENSOR_IO_H\n\nnamespace Eigen {\n\nnamespace internal {\n\n// Print the tensor as a 2d matrix\ntemplate <typename Tensor, int Rank>\nstruct TensorPrinter {\n  static void run (std::ostream& os, const Tensor& tensor) {\n    typedef typename internal::remove_const<typename Tensor::Scalar>::type Scalar;\n    typedef typename Tensor::Index Index;\n    const Index total_size = internal::array_prod(tensor.dimensions());\n    if (total_size > 0) {\n      const Index first_dim = Eigen::internal::array_get<0>(tensor.dimensions());\n      static const int layout = Tensor::Layout;\n      Map<const Array<Scalar, Dynamic, Dynamic, layout> > matrix(const_cast<Scalar*>(tensor.data()), first_dim, total_size/first_dim);\n      os << matrix;\n    }\n  }\n};\n\n\n// Print the tensor as a vector\ntemplate <typename Tensor>\nstruct TensorPrinter<Tensor, 1> {\n  static void run (std::ostream& os, const Tensor& tensor) {\n    typedef typename internal::remove_const<typename Tensor::Scalar>::type Scalar;\n    typedef typename Tensor::Index Index;\n    const Index total_size = internal::array_prod(tensor.dimensions());\n    if (total_size > 0) {\n      Map<const Array<Scalar, Dynamic, 1> > array(const_cast<Scalar*>(tensor.data()), total_size);\n      os << array;\n    }\n  }\n};\n\n\n// Print the tensor as a scalar\ntemplate <typename Tensor>\nstruct TensorPrinter<Tensor, 0> {\n  static void run (std::ostream& os, const Tensor& tensor) {\n    os << tensor.coeff(0);\n  }\n};\n}\n\ntemplate <typename T>\nstd::ostream& operator << (std::ostream& os, const TensorBase<T, ReadOnlyAccessors>& expr) {\n  typedef TensorEvaluator<const TensorForcedEvalOp<const T>, DefaultDevice> Evaluator;\n  typedef typename Evaluator::Dimensions Dimensions;\n\n  // Evaluate the expression if needed\n  TensorForcedEvalOp<const T> eval = expr.eval();\n  Evaluator tensor(eval, DefaultDevice());\n  tensor.evalSubExprsIfNeeded(NULL);\n\n  // Print the result\n  static const int rank = internal::array_size<Dimensions>::value;\n  internal::TensorPrinter<Evaluator, rank>::run(os, tensor);\n\n  // Cleanup.\n  tensor.cleanup();\n  return os;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_IO_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorImagePatch.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_IMAGE_PATCH_H\n#define EIGEN_CXX11_TENSOR_TENSOR_IMAGE_PATCH_H\n\nnamespace Eigen {\n\n/** \\class TensorImagePatch\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Patch extraction specialized for image processing.\n  * This assumes that the input has a least 3 dimensions ordered as follow:\n  *  1st dimension: channels (of size d)\n  *  2nd dimension: rows (of size r)\n  *  3rd dimension: columns (of size c)\n  *  There can be additional dimensions such as time (for video) or batch (for\n  * bulk processing after the first 3.\n  * Calling the image patch code with patch_rows and patch_cols is equivalent\n  * to calling the regular patch extraction code with parameters d, patch_rows,\n  * patch_cols, and 1 for all the additional dimensions.\n  */\nnamespace internal {\n\ntemplate<DenseIndex Rows, DenseIndex Cols, typename XprType>\nstruct traits<TensorImagePatchOp<Rows, Cols, XprType> > : public traits<XprType>\n{\n  typedef typename internal::remove_const<typename XprType::Scalar>::type Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions + 1;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<DenseIndex Rows, DenseIndex Cols, typename XprType>\nstruct eval<TensorImagePatchOp<Rows, Cols, XprType>, Eigen::Dense>\n{\n  typedef const TensorImagePatchOp<Rows, Cols, XprType>& type;\n};\n\ntemplate<DenseIndex Rows, DenseIndex Cols, typename XprType>\nstruct nested<TensorImagePatchOp<Rows, Cols, XprType>, 1, typename eval<TensorImagePatchOp<Rows, Cols, XprType> >::type>\n{\n  typedef TensorImagePatchOp<Rows, Cols, XprType> type;\n};\n\ntemplate <typename Self, bool Vectorizable>\nstruct ImagePatchCopyOp {\n  typedef typename Self::Index Index;\n  typedef typename Self::Scalar Scalar;\n  typedef typename Self::Impl Impl;\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void Run(\n      const Self& self, const Index num_coeff_to_copy, const Index dst_index,\n      Scalar* dst_data, const Index src_index) {\n    const Impl& impl = self.impl();\n    for (Index i = 0; i < num_coeff_to_copy; ++i) {\n      dst_data[dst_index + i] = impl.coeff(src_index + i);\n    }\n  }\n};\n\ntemplate <typename Self>\nstruct ImagePatchCopyOp<Self, true> {\n  typedef typename Self::Index Index;\n  typedef typename Self::Scalar Scalar;\n  typedef typename Self::Impl Impl;\n  typedef typename packet_traits<Scalar>::type Packet;\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void Run(\n      const Self& self, const Index num_coeff_to_copy, const Index dst_index,\n      Scalar* dst_data, const Index src_index) {\n    const Impl& impl = self.impl();\n    const Index packet_size = internal::unpacket_traits<Packet>::size;\n    const Index vectorized_size =\n        (num_coeff_to_copy / packet_size) * packet_size;\n    for (Index i = 0; i < vectorized_size; i += packet_size) {\n      Packet p = impl.template packet<Unaligned>(src_index + i);\n      internal::pstoret<Scalar, Packet, Unaligned>(dst_data + dst_index + i, p);\n    }\n    for (Index i = vectorized_size; i < num_coeff_to_copy; ++i) {\n      dst_data[dst_index + i] = impl.coeff(src_index + i);\n    }\n  }\n};\n\ntemplate <typename Self>\nstruct ImagePatchPaddingOp {\n  typedef typename Self::Index Index;\n  typedef typename Self::Scalar Scalar;\n  typedef typename packet_traits<Scalar>::type Packet;\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void Run(\n      const Index num_coeff_to_pad, const Scalar padding_value,\n      const Index dst_index, Scalar* dst_data) {\n    const Index packet_size = internal::unpacket_traits<Packet>::size;\n    const Packet padded_packet = internal::pset1<Packet>(padding_value);\n    const Index vectorized_size =\n        (num_coeff_to_pad / packet_size) * packet_size;\n    for (Index i = 0; i < vectorized_size; i += packet_size) {\n      internal::pstoret<Scalar, Packet, Unaligned>(dst_data + dst_index + i,\n                                                   padded_packet);\n    }\n    for (Index i = vectorized_size; i < num_coeff_to_pad; ++i) {\n      dst_data[dst_index + i] = padding_value;\n    }\n  }\n};\n\n}  // end namespace internal\n\ntemplate<DenseIndex Rows, DenseIndex Cols, typename XprType>\nclass TensorImagePatchOp : public TensorBase<TensorImagePatchOp<Rows, Cols, XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorImagePatchOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorImagePatchOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorImagePatchOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorImagePatchOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorImagePatchOp(const XprType& expr, DenseIndex patch_rows, DenseIndex patch_cols,\n                                                           DenseIndex row_strides, DenseIndex col_strides,\n                                                           DenseIndex in_row_strides, DenseIndex in_col_strides,\n                                                           DenseIndex row_inflate_strides, DenseIndex col_inflate_strides,\n                                                           PaddingType padding_type, Scalar padding_value)\n                                                           : m_xpr(expr), m_patch_rows(patch_rows), m_patch_cols(patch_cols),\n                                                           m_row_strides(row_strides), m_col_strides(col_strides),\n                                                           m_in_row_strides(in_row_strides), m_in_col_strides(in_col_strides),\n                                                           m_row_inflate_strides(row_inflate_strides), m_col_inflate_strides(col_inflate_strides),\n                                                           m_padding_explicit(false), m_padding_top(0), m_padding_bottom(0), m_padding_left(0), m_padding_right(0),\n                                                           m_padding_type(padding_type), m_padding_value(padding_value) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorImagePatchOp(const XprType& expr, DenseIndex patch_rows, DenseIndex patch_cols,\n                                                           DenseIndex row_strides, DenseIndex col_strides,\n                                                           DenseIndex in_row_strides, DenseIndex in_col_strides,\n                                                           DenseIndex row_inflate_strides, DenseIndex col_inflate_strides,\n                                                           DenseIndex padding_top, DenseIndex padding_bottom,\n                                                           DenseIndex padding_left, DenseIndex padding_right,\n                                                           Scalar padding_value)\n                                                           : m_xpr(expr), m_patch_rows(patch_rows), m_patch_cols(patch_cols),\n                                                           m_row_strides(row_strides), m_col_strides(col_strides),\n                                                           m_in_row_strides(in_row_strides), m_in_col_strides(in_col_strides),\n                                                           m_row_inflate_strides(row_inflate_strides), m_col_inflate_strides(col_inflate_strides),\n                                                           m_padding_explicit(true), m_padding_top(padding_top), m_padding_bottom(padding_bottom),\n                                                           m_padding_left(padding_left), m_padding_right(padding_right),\n                                                           m_padding_type(PADDING_VALID), m_padding_value(padding_value) {}\n\n\n    EIGEN_DEVICE_FUNC\n    DenseIndex patch_rows() const { return m_patch_rows; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex patch_cols() const { return m_patch_cols; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex row_strides() const { return m_row_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex col_strides() const { return m_col_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex in_row_strides() const { return m_in_row_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex in_col_strides() const { return m_in_col_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex row_inflate_strides() const { return m_row_inflate_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex col_inflate_strides() const { return m_col_inflate_strides; }\n    EIGEN_DEVICE_FUNC\n    bool padding_explicit() const { return m_padding_explicit; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex padding_top() const { return m_padding_top; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex padding_bottom() const { return m_padding_bottom; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex padding_left() const { return m_padding_left; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex padding_right() const { return m_padding_right; }\n    EIGEN_DEVICE_FUNC\n    PaddingType padding_type() const { return m_padding_type; }\n    EIGEN_DEVICE_FUNC\n    Scalar padding_value() const { return m_padding_value; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const DenseIndex m_patch_rows;\n    const DenseIndex m_patch_cols;\n    const DenseIndex m_row_strides;\n    const DenseIndex m_col_strides;\n    const DenseIndex m_in_row_strides;\n    const DenseIndex m_in_col_strides;\n    const DenseIndex m_row_inflate_strides;\n    const DenseIndex m_col_inflate_strides;\n    const bool m_padding_explicit;\n    const DenseIndex m_padding_top;\n    const DenseIndex m_padding_bottom;\n    const DenseIndex m_padding_left;\n    const DenseIndex m_padding_right;\n    const PaddingType m_padding_type;\n    const Scalar m_padding_value;\n};\n\n// Eval as rvalue\ntemplate<DenseIndex Rows, DenseIndex Cols, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorImagePatchOp<Rows, Cols, ArgType>, Device>\n{\n  typedef TensorImagePatchOp<Rows, Cols, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumInputDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  static const int NumDims = NumInputDims + 1;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename internal::remove_const<typename XprType::Scalar>::type Scalar;\n  typedef TensorEvaluator<const TensorImagePatchOp<Rows, Cols, ArgType>,\n                          Device> Self;\n  typedef TensorEvaluator<ArgType, Device> Impl;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned         = false,\n    PacketAccess      = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess       = false,\n    PreferBlockAccess = true,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess       = false,\n    RawAccess         = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator( const XprType& op, const Device& device)\n      : m_device(device), m_impl(op.expression(), device)\n  {\n    EIGEN_STATIC_ASSERT((NumDims >= 4), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    m_paddingValue = op.padding_value();\n\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n\n    // Caches a few variables.\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_inputDepth = input_dims[0];\n      m_inputRows = input_dims[1];\n      m_inputCols = input_dims[2];\n    } else {\n      m_inputDepth = input_dims[NumInputDims-1];\n      m_inputRows = input_dims[NumInputDims-2];\n      m_inputCols = input_dims[NumInputDims-3];\n    }\n\n    m_row_strides = op.row_strides();\n    m_col_strides = op.col_strides();\n\n    // Input strides and effective input/patch size\n    m_in_row_strides = op.in_row_strides();\n    m_in_col_strides = op.in_col_strides();\n    m_row_inflate_strides = op.row_inflate_strides();\n    m_col_inflate_strides = op.col_inflate_strides();\n    // The \"effective\" input rows and input cols are the input rows and cols\n    // after inflating them with zeros.\n    // For examples, a 2x3 matrix with row_inflate_strides and\n    // col_inflate_strides of 2 comes from:\n    //   A B C\n    //   D E F\n    //\n    // to a matrix is 3 x 5:\n    //\n    //   A . B . C\n    //   . . . . .\n    //   D . E . F\n\n    m_input_rows_eff = (m_inputRows - 1) * m_row_inflate_strides + 1;\n    m_input_cols_eff = (m_inputCols - 1) * m_col_inflate_strides + 1;\n    m_patch_rows_eff = op.patch_rows() + (op.patch_rows() - 1) * (m_in_row_strides - 1);\n    m_patch_cols_eff = op.patch_cols() + (op.patch_cols() - 1) * (m_in_col_strides - 1);\n\n    if (op.padding_explicit()) {\n      m_outputRows = numext::ceil((m_input_rows_eff + op.padding_top() + op.padding_bottom() - m_patch_rows_eff + 1.f) / static_cast<float>(m_row_strides));\n      m_outputCols = numext::ceil((m_input_cols_eff + op.padding_left() + op.padding_right() - m_patch_cols_eff + 1.f) / static_cast<float>(m_col_strides));\n      m_rowPaddingTop = op.padding_top();\n      m_colPaddingLeft = op.padding_left();\n    } else {\n      // Computing padding from the type\n      switch (op.padding_type()) {\n        case PADDING_VALID:\n          m_outputRows = numext::ceil((m_input_rows_eff - m_patch_rows_eff + 1.f) / static_cast<float>(m_row_strides));\n          m_outputCols = numext::ceil((m_input_cols_eff - m_patch_cols_eff + 1.f) / static_cast<float>(m_col_strides));\n          // Calculate the padding\n          m_rowPaddingTop = numext::maxi<Index>(0, ((m_outputRows - 1) * m_row_strides + m_patch_rows_eff - m_input_rows_eff) / 2);\n          m_colPaddingLeft = numext::maxi<Index>(0, ((m_outputCols - 1) * m_col_strides + m_patch_cols_eff - m_input_cols_eff) / 2);\n          break;\n        case PADDING_SAME:\n          m_outputRows = numext::ceil(m_input_rows_eff / static_cast<float>(m_row_strides));\n          m_outputCols = numext::ceil(m_input_cols_eff / static_cast<float>(m_col_strides));\n          // Calculate the padding\n          m_rowPaddingTop = ((m_outputRows - 1) * m_row_strides + m_patch_rows_eff - m_input_rows_eff) / 2;\n          m_colPaddingLeft = ((m_outputCols - 1) * m_col_strides + m_patch_cols_eff - m_input_cols_eff) / 2;\n          // The padding size calculation for PADDING_SAME has been updated to\n          // be consistent with how TensorFlow extracts its paddings.\n          m_rowPaddingTop = numext::maxi<Index>(0, m_rowPaddingTop);\n          m_colPaddingLeft = numext::maxi<Index>(0, m_colPaddingLeft);\n          break;\n        default:\n          eigen_assert(false && \"unexpected padding\");\n          m_outputCols=0; // silence the uninitialised warning;\n          m_outputRows=0; //// silence the uninitialised warning;\n      }\n    }\n    eigen_assert(m_outputRows > 0);\n    eigen_assert(m_outputCols > 0);\n\n    // Dimensions for result of extraction.\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      // ColMajor\n      // 0: depth\n      // 1: patch_rows\n      // 2: patch_cols\n      // 3: number of patches\n      // 4 and beyond: anything else (such as batch).\n      m_dimensions[0] = input_dims[0];\n      m_dimensions[1] = op.patch_rows();\n      m_dimensions[2] = op.patch_cols();\n      m_dimensions[3] = m_outputRows * m_outputCols;\n      for (int i = 4; i < NumDims; ++i) {\n        m_dimensions[i] = input_dims[i-1];\n      }\n    } else {\n      // RowMajor\n      // NumDims-1: depth\n      // NumDims-2: patch_rows\n      // NumDims-3: patch_cols\n      // NumDims-4: number of patches\n      // NumDims-5 and beyond: anything else (such as batch).\n      m_dimensions[NumDims-1] = input_dims[NumInputDims-1];\n      m_dimensions[NumDims-2] = op.patch_rows();\n      m_dimensions[NumDims-3] = op.patch_cols();\n      m_dimensions[NumDims-4] = m_outputRows * m_outputCols;\n      for (int i = NumDims-5; i >= 0; --i) {\n        m_dimensions[i] = input_dims[i];\n      }\n    }\n\n    // Strides for moving the patch in various dimensions.\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_colStride = m_dimensions[1];\n      m_patchStride = m_colStride * m_dimensions[2] * m_dimensions[0];\n      m_otherStride = m_patchStride * m_dimensions[3];\n    } else {\n      m_colStride = m_dimensions[NumDims-2];\n      m_patchStride = m_colStride * m_dimensions[NumDims-3] * m_dimensions[NumDims-1];\n      m_otherStride = m_patchStride * m_dimensions[NumDims-4];\n    }\n\n    // Strides for navigating through the input tensor.\n    m_rowInputStride = m_inputDepth;\n    m_colInputStride = m_inputDepth * m_inputRows;\n    m_patchInputStride = m_inputDepth * m_inputRows * m_inputCols;\n\n    // Fast representations of different variables.\n    m_fastOtherStride = internal::TensorIntDivisor<Index>(m_otherStride);\n    m_fastPatchStride = internal::TensorIntDivisor<Index>(m_patchStride);\n    m_fastColStride = internal::TensorIntDivisor<Index>(m_colStride);\n    m_fastInflateRowStride = internal::TensorIntDivisor<Index>(m_row_inflate_strides);\n    m_fastInflateColStride = internal::TensorIntDivisor<Index>(m_col_inflate_strides);\n    m_fastInputColsEff = internal::TensorIntDivisor<Index>(m_input_cols_eff);\n\n    // Number of patches in the width dimension.\n    m_fastOutputRows = internal::TensorIntDivisor<Index>(m_outputRows);\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_fastOutputDepth = internal::TensorIntDivisor<Index>(m_dimensions[0]);\n    } else {\n      m_fastOutputDepth = internal::TensorIntDivisor<Index>(m_dimensions[NumDims-1]);\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType /*data*/) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    m_impl.evalSubExprsIfNeededAsync(nullptr, [done](bool) { done(true); });\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    // Patch index corresponding to the passed in index.\n    const Index patchIndex = index / m_fastPatchStride;\n    // Find the offset of the element wrt the location of the first element.\n    const Index patchOffset = (index - patchIndex * m_patchStride) / m_fastOutputDepth;\n\n    // Other ways to index this element.\n    const Index otherIndex = (NumDims == 4) ? 0 : index / m_fastOtherStride;\n    const Index patch2DIndex = (NumDims == 4) ? patchIndex : (index - otherIndex * m_otherStride) / m_fastPatchStride;\n\n    // Calculate col index in the input original tensor.\n    const Index colIndex = patch2DIndex / m_fastOutputRows;\n    const Index colOffset = patchOffset / m_fastColStride;\n    const Index inputCol = colIndex * m_col_strides + colOffset * m_in_col_strides - m_colPaddingLeft;\n    const Index origInputCol = (m_col_inflate_strides == 1) ? inputCol : ((inputCol >= 0) ? (inputCol / m_fastInflateColStride) : 0);\n    if (inputCol < 0 || inputCol >= m_input_cols_eff ||\n        ((m_col_inflate_strides != 1) && (inputCol != origInputCol * m_col_inflate_strides))) {\n      return Scalar(m_paddingValue);\n    }\n\n    // Calculate row index in the original input tensor.\n    const Index rowIndex = patch2DIndex - colIndex * m_outputRows;\n    const Index rowOffset = patchOffset - colOffset * m_colStride;\n    const Index inputRow = rowIndex * m_row_strides + rowOffset * m_in_row_strides - m_rowPaddingTop;\n    const Index origInputRow = (m_row_inflate_strides == 1) ? inputRow : ((inputRow >= 0) ? (inputRow / m_fastInflateRowStride) : 0);\n    if (inputRow < 0 || inputRow >= m_input_rows_eff ||\n        ((m_row_inflate_strides != 1) && (inputRow != origInputRow * m_row_inflate_strides))) {\n      return Scalar(m_paddingValue);\n    }\n\n    const int depth_index = static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 0 : NumDims - 1;\n    const Index depth = index - (index / m_fastOutputDepth) * m_dimensions[depth_index];\n\n    const Index inputIndex = depth + origInputRow * m_rowInputStride + origInputCol * m_colInputStride + otherIndex * m_patchInputStride;\n    return m_impl.coeff(inputIndex);\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    if (m_in_row_strides != 1 || m_in_col_strides != 1 || m_row_inflate_strides != 1 || m_col_inflate_strides != 1) {\n      return packetWithPossibleZero(index);\n    }\n\n    const Index indices[2] = {index, index + PacketSize - 1};\n    const Index patchIndex = indices[0] / m_fastPatchStride;\n    if (patchIndex != indices[1] / m_fastPatchStride) {\n      return packetWithPossibleZero(index);\n    }\n    const Index otherIndex = (NumDims == 4) ? 0 : indices[0] / m_fastOtherStride;\n    eigen_assert(otherIndex == indices[1] / m_fastOtherStride);\n\n    // Find the offset of the element wrt the location of the first element.\n    const Index patchOffsets[2] = {(indices[0] - patchIndex * m_patchStride) / m_fastOutputDepth,\n                                   (indices[1] - patchIndex * m_patchStride) / m_fastOutputDepth};\n\n    const Index patch2DIndex = (NumDims == 4) ? patchIndex : (indices[0] - otherIndex * m_otherStride) / m_fastPatchStride;\n    eigen_assert(patch2DIndex == (indices[1] - otherIndex * m_otherStride) / m_fastPatchStride);\n\n    const Index colIndex = patch2DIndex / m_fastOutputRows;\n    const Index colOffsets[2] = {patchOffsets[0] / m_fastColStride, patchOffsets[1] / m_fastColStride};\n\n    // Calculate col indices in the original input tensor.\n    const Index inputCols[2] = {colIndex * m_col_strides + colOffsets[0] -\n      m_colPaddingLeft, colIndex * m_col_strides + colOffsets[1] - m_colPaddingLeft};\n    if (inputCols[1] < 0 || inputCols[0] >= m_inputCols) {\n      return internal::pset1<PacketReturnType>(Scalar(m_paddingValue));\n    }\n\n    if (inputCols[0] == inputCols[1]) {\n      const Index rowIndex = patch2DIndex - colIndex * m_outputRows;\n      const Index rowOffsets[2] = {patchOffsets[0] - colOffsets[0]*m_colStride, patchOffsets[1] - colOffsets[1]*m_colStride};\n      eigen_assert(rowOffsets[0] <= rowOffsets[1]);\n      // Calculate col indices in the original input tensor.\n      const Index inputRows[2] = {rowIndex * m_row_strides + rowOffsets[0] -\n        m_rowPaddingTop, rowIndex * m_row_strides + rowOffsets[1] - m_rowPaddingTop};\n\n      if (inputRows[1] < 0 || inputRows[0] >= m_inputRows) {\n        return internal::pset1<PacketReturnType>(Scalar(m_paddingValue));\n      }\n\n      if (inputRows[0] >= 0 && inputRows[1] < m_inputRows) {\n        // no padding\n        const int depth_index = static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 0 : NumDims - 1;\n        const Index depth = index - (index / m_fastOutputDepth) * m_dimensions[depth_index];\n        const Index inputIndex = depth + inputRows[0] * m_rowInputStride + inputCols[0] * m_colInputStride + otherIndex * m_patchInputStride;\n        return m_impl.template packet<Unaligned>(inputIndex);\n      }\n    }\n\n    return packetWithPossibleZero(index);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const TensorEvaluator<ArgType, Device>& impl() const { return m_impl; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rowPaddingTop() const { return m_rowPaddingTop; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index colPaddingLeft() const { return m_colPaddingLeft; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index outputRows() const { return m_outputRows; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index outputCols() const { return m_outputCols; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index userRowStride() const { return m_row_strides; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index userColStride() const { return m_col_strides; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index userInRowStride() const { return m_in_row_strides; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index userInColStride() const { return m_in_col_strides; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rowInflateStride() const { return m_row_inflate_strides; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index colInflateStride() const { return m_col_inflate_strides; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    // We conservatively estimate the cost for the code path where the computed\n    // index is inside the original image and\n    // TensorEvaluator<ArgType, Device>::CoordAccess is false.\n    const double compute_cost = 3 * TensorOpCost::DivCost<Index>() +\n                                6 * TensorOpCost::MulCost<Index>() +\n                                8 * TensorOpCost::MulCost<Index>();\n    return m_impl.costPerCoeff(vectorized) +\n           TensorOpCost(0, 0, compute_cost, vectorized, PacketSize);\n  }\n\n protected:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetWithPossibleZero(Index index) const\n  {\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < PacketSize; ++i) {\n      values[i] = coeff(index+i);\n    }\n    PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n    return rslt;\n  }\n\n  Dimensions m_dimensions;\n\n  Index m_otherStride;\n  Index m_patchStride;\n  Index m_colStride;\n  Index m_row_strides;\n  Index m_col_strides;\n\n  Index m_in_row_strides;\n  Index m_in_col_strides;\n  Index m_row_inflate_strides;\n  Index m_col_inflate_strides;\n\n  Index m_input_rows_eff;\n  Index m_input_cols_eff;\n  Index m_patch_rows_eff;\n  Index m_patch_cols_eff;\n\n  internal::TensorIntDivisor<Index> m_fastOtherStride;\n  internal::TensorIntDivisor<Index> m_fastPatchStride;\n  internal::TensorIntDivisor<Index> m_fastColStride;\n  internal::TensorIntDivisor<Index> m_fastInflateRowStride;\n  internal::TensorIntDivisor<Index> m_fastInflateColStride;\n  internal::TensorIntDivisor<Index> m_fastInputColsEff;\n\n  Index m_rowInputStride;\n  Index m_colInputStride;\n  Index m_patchInputStride;\n\n  Index m_inputDepth;\n  Index m_inputRows;\n  Index m_inputCols;\n\n  Index m_outputRows;\n  Index m_outputCols;\n\n  Index m_rowPaddingTop;\n  Index m_colPaddingLeft;\n\n  internal::TensorIntDivisor<Index> m_fastOutputRows;\n  internal::TensorIntDivisor<Index> m_fastOutputDepth;\n\n  Scalar m_paddingValue;\n\n  const Device EIGEN_DEVICE_REF m_device;\n  TensorEvaluator<ArgType, Device> m_impl;\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_IMAGE_PATCH_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIndexList.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_INDEX_LIST_H\n#define EIGEN_CXX11_TENSOR_TENSOR_INDEX_LIST_H\n\n\n#if EIGEN_HAS_CONSTEXPR && EIGEN_HAS_VARIADIC_TEMPLATES\n\n#define EIGEN_HAS_INDEX_LIST\n\nnamespace Eigen {\n\n/** \\internal\n  *\n  * \\class TensorIndexList\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Set of classes used to encode a set of Tensor dimensions/indices.\n  *\n  * The indices in the list can be known at compile time or at runtime. A mix\n  * of static and dynamic indices can also be provided if needed. The tensor\n  * code will attempt to take advantage of the indices that are known at\n  * compile time to optimize the code it generates.\n  *\n  * This functionality requires a c++11 compliant compiler. If your compiler\n  * is older you need to use arrays of indices instead.\n  *\n  * Several examples are provided in the cxx11_tensor_index_list.cpp file.\n  *\n  * \\sa Tensor\n  */\n\ntemplate <Index n>\nstruct type2index {\n  static const Index value = n;\n  EIGEN_DEVICE_FUNC constexpr operator Index() const { return n; }\n  EIGEN_DEVICE_FUNC void set(Index val) {\n    eigen_assert(val == n);\n  }\n};\n\n// This can be used with IndexPairList to get compile-time constant pairs,\n// such as IndexPairList<type2indexpair<1,2>, type2indexpair<3,4>>().\ntemplate <Index f, Index s>\nstruct type2indexpair {\n  static const Index first = f;\n  static const Index second = s;\n\n  constexpr EIGEN_DEVICE_FUNC operator IndexPair<Index>() const {\n    return IndexPair<Index>(f, s);\n  }\n\n  EIGEN_DEVICE_FUNC void set(const IndexPair<Index>& val) {\n    eigen_assert(val.first == f);\n    eigen_assert(val.second == s);\n  }\n};\n\n\ntemplate<Index n> struct NumTraits<type2index<n> >\n{\n  typedef Index Real;\n  enum {\n    IsComplex = 0,\n    RequireInitialization = false,\n    ReadCost = 1,\n    AddCost = 1,\n    MulCost = 1\n  };\n\n  EIGEN_DEVICE_FUNC static EIGEN_CONSTEXPR EIGEN_STRONG_INLINE Real epsilon() { return 0; }\n  EIGEN_DEVICE_FUNC static EIGEN_CONSTEXPR EIGEN_STRONG_INLINE Real dummy_precision() { return 0; }\n  EIGEN_DEVICE_FUNC static EIGEN_CONSTEXPR EIGEN_STRONG_INLINE Real highest() { return n; }\n  EIGEN_DEVICE_FUNC static EIGEN_CONSTEXPR EIGEN_STRONG_INLINE Real lowest() { return n; }\n};\n\nnamespace internal {\ntemplate <typename T>\nEIGEN_DEVICE_FUNC void update_value(T& val, Index new_val) {\n  val = internal::convert_index<T>(new_val);\n}\ntemplate <Index n>\nEIGEN_DEVICE_FUNC void update_value(type2index<n>& val, Index new_val) {\n  val.set(new_val);\n}\n\ntemplate <typename T>\nEIGEN_DEVICE_FUNC void update_value(T& val, IndexPair<Index> new_val) {\n  val = new_val;\n}\ntemplate <Index f, Index s>\nEIGEN_DEVICE_FUNC void update_value(type2indexpair<f, s>& val, IndexPair<Index> new_val) {\n  val.set(new_val);\n}\n\n\ntemplate <typename T>\nstruct is_compile_time_constant {\n  static constexpr bool value = false;\n};\n\ntemplate <Index idx>\nstruct is_compile_time_constant<type2index<idx> > {\n  static constexpr bool value = true;\n};\ntemplate <Index idx>\nstruct is_compile_time_constant<const type2index<idx> > {\n  static constexpr bool value = true;\n};\ntemplate <Index idx>\nstruct is_compile_time_constant<type2index<idx>& > {\n  static constexpr bool value = true;\n};\ntemplate <Index idx>\nstruct is_compile_time_constant<const type2index<idx>& > {\n  static constexpr bool value = true;\n};\n\ntemplate <Index f, Index s>\nstruct is_compile_time_constant<type2indexpair<f, s> > {\n  static constexpr bool value = true;\n};\ntemplate <Index f, Index s>\nstruct is_compile_time_constant<const type2indexpair<f, s> > {\n  static constexpr bool value = true;\n};\ntemplate <Index f, Index s>\nstruct is_compile_time_constant<type2indexpair<f, s>& > {\n  static constexpr bool value = true;\n};\ntemplate <Index f, Index s>\nstruct is_compile_time_constant<const type2indexpair<f, s>& > {\n  static constexpr bool value = true;\n};\n\n\ntemplate<typename... T>\nstruct IndexTuple;\n\ntemplate<typename T, typename... O>\nstruct IndexTuple<T, O...> {\n  EIGEN_DEVICE_FUNC constexpr IndexTuple() : head(), others() { }\n  EIGEN_DEVICE_FUNC constexpr IndexTuple(const T& v, const O... o) : head(v), others(o...) { }\n\n  constexpr static int count = 1 + sizeof...(O);\n  T head;\n  IndexTuple<O...> others;\n  typedef T Head;\n  typedef IndexTuple<O...> Other;\n};\n\ntemplate<typename T>\n  struct IndexTuple<T> {\n  EIGEN_DEVICE_FUNC constexpr IndexTuple() : head() { }\n  EIGEN_DEVICE_FUNC constexpr IndexTuple(const T& v) : head(v) { }\n\n  constexpr static int count = 1;\n  T head;\n  typedef T Head;\n};\n\n\ntemplate<int N, typename... T>\nstruct IndexTupleExtractor;\n\ntemplate<int N, typename T, typename... O>\nstruct IndexTupleExtractor<N, T, O...> {\n\n  typedef typename IndexTupleExtractor<N-1, O...>::ValType ValType;\n\n  EIGEN_DEVICE_FUNC static constexpr ValType& get_val(IndexTuple<T, O...>& val) {\n    return IndexTupleExtractor<N-1, O...>::get_val(val.others);\n  }\n\n  EIGEN_DEVICE_FUNC static constexpr const ValType& get_val(const IndexTuple<T, O...>& val) {\n    return IndexTupleExtractor<N-1, O...>::get_val(val.others);\n  }\n  template <typename V>\n  EIGEN_DEVICE_FUNC static void set_val(IndexTuple<T, O...>& val, V& new_val) {\n    IndexTupleExtractor<N-1, O...>::set_val(val.others, new_val);\n  }\n\n};\n\ntemplate<typename T, typename... O>\n  struct IndexTupleExtractor<0, T, O...> {\n\n  typedef T ValType;\n\n  EIGEN_DEVICE_FUNC static constexpr ValType& get_val(IndexTuple<T, O...>& val) {\n    return val.head;\n  }\n  EIGEN_DEVICE_FUNC static constexpr const ValType& get_val(const IndexTuple<T, O...>& val) {\n    return val.head;\n  }\n  template <typename V>\n  EIGEN_DEVICE_FUNC static void set_val(IndexTuple<T, O...>& val, V& new_val) {\n    val.head = new_val;\n  }\n};\n\n\n\ntemplate <int N, typename T, typename... O>\nEIGEN_DEVICE_FUNC constexpr typename IndexTupleExtractor<N, T, O...>::ValType& array_get(IndexTuple<T, O...>& tuple) {\n  return IndexTupleExtractor<N, T, O...>::get_val(tuple);\n}\ntemplate <int N, typename T, typename... O>\nEIGEN_DEVICE_FUNC constexpr const typename IndexTupleExtractor<N, T, O...>::ValType& array_get(const IndexTuple<T, O...>& tuple) {\n  return IndexTupleExtractor<N, T, O...>::get_val(tuple);\n}\ntemplate <typename T, typename... O>\n  struct array_size<IndexTuple<T, O...> > {\n  static const size_t value = IndexTuple<T, O...>::count;\n};\ntemplate <typename T, typename... O>\n  struct array_size<const IndexTuple<T, O...> > {\n  static const size_t value = IndexTuple<T, O...>::count;\n};\n\n\n\n\ntemplate <Index Idx, typename ValueT>\nstruct tuple_coeff {\n  template <typename... T>\n  EIGEN_DEVICE_FUNC static constexpr ValueT get(const Index i, const IndexTuple<T...>& t) {\n    //    return array_get<Idx>(t) * (i == Idx) + tuple_coeff<Idx-1>::get(i, t) * (i != Idx);\n    return (i == Idx ? array_get<Idx>(t) : tuple_coeff<Idx-1, ValueT>::get(i, t));\n  }\n  template <typename... T>\n  EIGEN_DEVICE_FUNC static void set(const Index i, IndexTuple<T...>& t, const ValueT& value) {\n    if (i == Idx) {\n      update_value(array_get<Idx>(t), value);\n    } else {\n      tuple_coeff<Idx-1, ValueT>::set(i, t, value);\n    }\n  }\n\n  template <typename... T>\n  EIGEN_DEVICE_FUNC static constexpr bool value_known_statically(const Index i, const IndexTuple<T...>& t) {\n    return ((i == Idx) & is_compile_time_constant<typename IndexTupleExtractor<Idx, T...>::ValType>::value) ||\n        tuple_coeff<Idx-1, ValueT>::value_known_statically(i, t);\n  }\n\n  template <typename... T>\n  EIGEN_DEVICE_FUNC static constexpr bool values_up_to_known_statically(const IndexTuple<T...>& t) {\n    return is_compile_time_constant<typename IndexTupleExtractor<Idx, T...>::ValType>::value &&\n        tuple_coeff<Idx-1, ValueT>::values_up_to_known_statically(t);\n  }\n\n  template <typename... T>\n  EIGEN_DEVICE_FUNC static constexpr bool values_up_to_statically_known_to_increase(const IndexTuple<T...>& t) {\n    return is_compile_time_constant<typename IndexTupleExtractor<Idx, T...>::ValType>::value &&\n           is_compile_time_constant<typename IndexTupleExtractor<Idx, T...>::ValType>::value &&\n           array_get<Idx>(t) > array_get<Idx-1>(t) &&\n           tuple_coeff<Idx-1, ValueT>::values_up_to_statically_known_to_increase(t);\n  }\n};\n\ntemplate <typename ValueT>\nstruct tuple_coeff<0, ValueT> {\n  template <typename... T>\n  EIGEN_DEVICE_FUNC static constexpr ValueT get(const Index /*i*/, const IndexTuple<T...>& t) {\n    //  eigen_assert (i == 0);  // gcc fails to compile assertions in constexpr\n    return array_get<0>(t)/* * (i == 0)*/;\n  }\n  template <typename... T>\n  EIGEN_DEVICE_FUNC static void set(const Index i, IndexTuple<T...>& t, const ValueT value) {\n    eigen_assert (i == 0);\n    update_value(array_get<0>(t), value);\n  }\n  template <typename... T>\n  EIGEN_DEVICE_FUNC static constexpr bool value_known_statically(const Index i, const IndexTuple<T...>&) {\n    return is_compile_time_constant<typename IndexTupleExtractor<0, T...>::ValType>::value && (i == 0);\n  }\n\n  template <typename... T>\n  EIGEN_DEVICE_FUNC static constexpr bool values_up_to_known_statically(const IndexTuple<T...>&) {\n    return is_compile_time_constant<typename IndexTupleExtractor<0, T...>::ValType>::value;\n  }\n\n  template <typename... T>\n  EIGEN_DEVICE_FUNC static constexpr bool values_up_to_statically_known_to_increase(const IndexTuple<T...>&) {\n    return true;\n  }\n};\n}  // namespace internal\n\n\n\ntemplate<typename FirstType, typename... OtherTypes>\nstruct IndexList : internal::IndexTuple<FirstType, OtherTypes...> {\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC constexpr Index operator[] (const Index i) const {\n    return internal::tuple_coeff<internal::array_size<internal::IndexTuple<FirstType, OtherTypes...> >::value-1, Index>::get(i, *this);\n  }\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC constexpr Index get(const Index i) const {\n    return internal::tuple_coeff<internal::array_size<internal::IndexTuple<FirstType, OtherTypes...> >::value-1, Index>::get(i, *this);\n  }\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC void set(const Index i, const Index value) {\n    return internal::tuple_coeff<internal::array_size<internal::IndexTuple<FirstType, OtherTypes...> >::value-1, Index>::set(i, *this, value);\n  }\n\n  EIGEN_DEVICE_FUNC constexpr IndexList(const internal::IndexTuple<FirstType, OtherTypes...>& other) : internal::IndexTuple<FirstType, OtherTypes...>(other) { }\n  EIGEN_DEVICE_FUNC constexpr IndexList(FirstType& first, OtherTypes... other) : internal::IndexTuple<FirstType, OtherTypes...>(first, other...) { }\n  EIGEN_DEVICE_FUNC constexpr IndexList() : internal::IndexTuple<FirstType, OtherTypes...>() { }\n\n  EIGEN_DEVICE_FUNC constexpr bool value_known_statically(const Index i) const {\n    return internal::tuple_coeff<internal::array_size<internal::IndexTuple<FirstType, OtherTypes...> >::value-1, Index>::value_known_statically(i, *this);\n  }\n  EIGEN_DEVICE_FUNC constexpr bool all_values_known_statically() const {\n    return internal::tuple_coeff<internal::array_size<internal::IndexTuple<FirstType, OtherTypes...> >::value-1, Index>::values_up_to_known_statically(*this);\n  }\n\n  EIGEN_DEVICE_FUNC constexpr bool values_statically_known_to_increase() const {\n    return internal::tuple_coeff<internal::array_size<internal::IndexTuple<FirstType, OtherTypes...> >::value-1, Index>::values_up_to_statically_known_to_increase(*this);\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstd::ostream& operator<<(std::ostream& os,\n                         const IndexList<FirstType, OtherTypes...>& dims) {\n  os << \"[\";\n  for (size_t i = 0; i < 1 + sizeof...(OtherTypes); ++i) {\n    if (i > 0) os << \", \";\n    os << dims[i];\n  }\n  os << \"]\";\n  return os;\n}\n\ntemplate<typename FirstType, typename... OtherTypes>\nconstexpr IndexList<FirstType, OtherTypes...> make_index_list(FirstType val1, OtherTypes... other_vals) {\n  return IndexList<FirstType, OtherTypes...>(val1, other_vals...);\n}\n\n\ntemplate<typename FirstType, typename... OtherTypes>\nstruct IndexPairList : internal::IndexTuple<FirstType, OtherTypes...> {\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC constexpr IndexPair<Index> operator[] (const Index i) const {\n    return internal::tuple_coeff<internal::array_size<internal::IndexTuple<FirstType, OtherTypes...> >::value-1, IndexPair<Index>>::get(i, *this);\n  }\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC void set(const Index i, const IndexPair<Index> value) {\n    return internal::tuple_coeff<internal::array_size<internal::IndexTuple<FirstType, OtherTypes...>>::value-1, IndexPair<Index> >::set(i, *this, value);\n  }\n\n  EIGEN_DEVICE_FUNC  constexpr IndexPairList(const internal::IndexTuple<FirstType, OtherTypes...>& other) : internal::IndexTuple<FirstType, OtherTypes...>(other) { }\n  EIGEN_DEVICE_FUNC  constexpr IndexPairList() : internal::IndexTuple<FirstType, OtherTypes...>() { }\n\n  EIGEN_DEVICE_FUNC constexpr bool value_known_statically(const Index i) const {\n    return internal::tuple_coeff<internal::array_size<internal::IndexTuple<FirstType, OtherTypes...> >::value-1, Index>::value_known_statically(i, *this);\n  }\n};\n\nnamespace internal {\n\ntemplate<typename FirstType, typename... OtherTypes>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index array_prod(const IndexList<FirstType, OtherTypes...>& sizes) {\n  Index result = 1;\n  EIGEN_UNROLL_LOOP\n  for (size_t i = 0; i < array_size<IndexList<FirstType, OtherTypes...> >::value; ++i) {\n    result *= sizes[i];\n  }\n  return result;\n}\n\ntemplate<typename FirstType, typename... OtherTypes> struct array_size<IndexList<FirstType, OtherTypes...> > {\n  static const size_t value = array_size<IndexTuple<FirstType, OtherTypes...> >::value;\n};\ntemplate<typename FirstType, typename... OtherTypes> struct array_size<const IndexList<FirstType, OtherTypes...> > {\n  static const size_t value = array_size<IndexTuple<FirstType, OtherTypes...> >::value;\n};\n\ntemplate<typename FirstType, typename... OtherTypes> struct array_size<IndexPairList<FirstType, OtherTypes...> > {\n  static const size_t value = std::tuple_size<std::tuple<FirstType, OtherTypes...> >::value;\n};\ntemplate<typename FirstType, typename... OtherTypes> struct array_size<const IndexPairList<FirstType, OtherTypes...> > {\n  static const size_t value = std::tuple_size<std::tuple<FirstType, OtherTypes...> >::value;\n};\n\ntemplate<Index N, typename FirstType, typename... OtherTypes> EIGEN_DEVICE_FUNC constexpr Index array_get(IndexList<FirstType, OtherTypes...>& a) {\n  return IndexTupleExtractor<N, FirstType, OtherTypes...>::get_val(a);\n}\ntemplate<Index N, typename FirstType, typename... OtherTypes> EIGEN_DEVICE_FUNC constexpr Index array_get(const IndexList<FirstType, OtherTypes...>& a) {\n  return IndexTupleExtractor<N, FirstType, OtherTypes...>::get_val(a);\n}\n\ntemplate <typename T>\nstruct index_known_statically_impl {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index) {\n    return false;\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_known_statically_impl<IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i) {\n    return IndexList<FirstType, OtherTypes...>().value_known_statically(i);\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_known_statically_impl<const IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i) {\n    return IndexList<FirstType, OtherTypes...>().value_known_statically(i);\n  }\n};\n\n\ntemplate <typename T>\nstruct all_indices_known_statically_impl {\n  static constexpr bool run() {\n    return false;\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct all_indices_known_statically_impl<IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run() {\n    return IndexList<FirstType, OtherTypes...>().all_values_known_statically();\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct all_indices_known_statically_impl<const IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run() {\n    return IndexList<FirstType, OtherTypes...>().all_values_known_statically();\n  }\n};\n\n\ntemplate <typename T>\nstruct indices_statically_known_to_increase_impl {\n  EIGEN_DEVICE_FUNC static constexpr bool run() {\n    return false;\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\n  struct indices_statically_known_to_increase_impl<IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run() {\n    return Eigen::IndexList<FirstType, OtherTypes...>().values_statically_known_to_increase();\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\n  struct indices_statically_known_to_increase_impl<const IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run() {\n    return Eigen::IndexList<FirstType, OtherTypes...>().values_statically_known_to_increase();\n  }\n};\n\n\ntemplate <typename Tx>\nstruct index_statically_eq_impl {\n  EIGEN_DEVICE_FUNC static constexpr bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_statically_eq_impl<IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexList<FirstType, OtherTypes...>().get(i) == value);\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_statically_eq_impl<const IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexList<FirstType, OtherTypes...>().get(i) == value);\n  }\n};\n\n\ntemplate <typename T>\nstruct index_statically_ne_impl {\n  EIGEN_DEVICE_FUNC static constexpr bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_statically_ne_impl<IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexList<FirstType, OtherTypes...>().get(i) != value);\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_statically_ne_impl<const IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexList<FirstType, OtherTypes...>().get(i) != value);\n  }\n};\n\n\ntemplate <typename T>\nstruct index_statically_gt_impl {\n  EIGEN_DEVICE_FUNC static constexpr bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_statically_gt_impl<IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexList<FirstType, OtherTypes...>().get(i) > value);\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_statically_gt_impl<const IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexList<FirstType, OtherTypes...>().get(i) > value);\n  }\n};\n\n\n\ntemplate <typename T>\nstruct index_statically_lt_impl {\n  EIGEN_DEVICE_FUNC static constexpr bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_statically_lt_impl<IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexList<FirstType, OtherTypes...>().get(i) < value);\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_statically_lt_impl<const IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexList<FirstType, OtherTypes...>().get(i) < value);\n  }\n};\n\n\n\ntemplate <typename Tx>\nstruct index_pair_first_statically_eq_impl {\n  EIGEN_DEVICE_FUNC static constexpr bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_pair_first_statically_eq_impl<IndexPairList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexPairList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexPairList<FirstType, OtherTypes...>().operator[](i).first == value);\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_pair_first_statically_eq_impl<const IndexPairList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexPairList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexPairList<FirstType, OtherTypes...>().operator[](i).first == value);\n  }\n};\n\n\n\ntemplate <typename Tx>\nstruct index_pair_second_statically_eq_impl {\n  EIGEN_DEVICE_FUNC static constexpr bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_pair_second_statically_eq_impl<IndexPairList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexPairList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexPairList<FirstType, OtherTypes...>().operator[](i).second == value);\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_pair_second_statically_eq_impl<const IndexPairList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexPairList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexPairList<FirstType, OtherTypes...>().operator[](i).second == value);\n  }\n};\n\n\n}  // end namespace internal\n}  // end namespace Eigen\n\n#else\n\nnamespace Eigen {\nnamespace internal {\n\ntemplate <typename T>\nstruct index_known_statically_impl {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const Index) {\n    return false;\n  }\n};\n\ntemplate <typename T>\nstruct all_indices_known_statically_impl {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run() {\n    return false;\n  }\n};\n\ntemplate <typename T>\nstruct indices_statically_known_to_increase_impl {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run() {\n    return false;\n  }\n};\n\ntemplate <typename T>\nstruct index_statically_eq_impl {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename T>\nstruct index_statically_ne_impl {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename T>\nstruct index_statically_gt_impl {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename T>\nstruct index_statically_lt_impl {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename Tx>\nstruct index_pair_first_statically_eq_impl {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename Tx>\nstruct index_pair_second_statically_eq_impl {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(Index, Index) {\n    return false;\n  }\n};\n\n\n\n}  // end namespace internal\n}  // end namespace Eigen\n\n#endif\n\n\nnamespace Eigen {\nnamespace internal {\ntemplate <typename T>\nstatic EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_known_statically(Index i) {\n  return index_known_statically_impl<T>::run(i);\n}\n\ntemplate <typename T>\nstatic EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool all_indices_known_statically() {\n  return all_indices_known_statically_impl<T>::run();\n}\n\ntemplate <typename T>\nstatic EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool indices_statically_known_to_increase() {\n  return indices_statically_known_to_increase_impl<T>::run();\n}\n\ntemplate <typename T>\nstatic EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_statically_eq(Index i, Index value) {\n  return index_statically_eq_impl<T>::run(i, value);\n}\n\ntemplate <typename T>\nstatic EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_statically_ne(Index i, Index value) {\n  return index_statically_ne_impl<T>::run(i, value);\n}\n\ntemplate <typename T>\nstatic EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_statically_gt(Index i, Index value) {\n  return index_statically_gt_impl<T>::run(i, value);\n}\n\ntemplate <typename T>\nstatic EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_statically_lt(Index i, Index value) {\n  return index_statically_lt_impl<T>::run(i, value);\n}\n\ntemplate <typename T>\nstatic EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_pair_first_statically_eq(Index i, Index value) {\n  return index_pair_first_statically_eq_impl<T>::run(i, value);\n}\n\ntemplate <typename T>\nstatic EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_pair_second_statically_eq(Index i, Index value) {\n  return index_pair_second_statically_eq_impl<T>::run(i, value);\n}\n\n}  // end namespace internal\n}  // end namespace Eigen\n\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_INDEX_LIST_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorInflation.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Ke Yang <yangke@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_INFLATION_H\n#define EIGEN_CXX11_TENSOR_TENSOR_INFLATION_H\n\nnamespace Eigen {\n\n/** \\class TensorInflation\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor inflation class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename Strides, typename XprType>\nstruct traits<TensorInflationOp<Strides, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename Strides, typename XprType>\nstruct eval<TensorInflationOp<Strides, XprType>, Eigen::Dense>\n{\n  typedef const TensorInflationOp<Strides, XprType>& type;\n};\n\ntemplate<typename Strides, typename XprType>\nstruct nested<TensorInflationOp<Strides, XprType>, 1, typename eval<TensorInflationOp<Strides, XprType> >::type>\n{\n  typedef TensorInflationOp<Strides, XprType> type;\n};\n\n}  // end namespace internal\n\ntemplate<typename Strides, typename XprType>\nclass TensorInflationOp : public TensorBase<TensorInflationOp<Strides, XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorInflationOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorInflationOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorInflationOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorInflationOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorInflationOp(const XprType& expr, const Strides& strides)\n      : m_xpr(expr), m_strides(strides) {}\n\n    EIGEN_DEVICE_FUNC\n    const Strides& strides() const { return m_strides; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const Strides m_strides;\n};\n\n// Eval as rvalue\ntemplate<typename Strides, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorInflationOp<Strides, ArgType>, Device>\n{\n  typedef TensorInflationOp<Strides, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = /*TensorEvaluator<ArgType, Device>::IsAligned*/ false,\n    PacketAccess = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device), m_strides(op.strides())\n  {\n    m_dimensions = m_impl.dimensions();\n    // Expand each dimension to the inflated dimension.\n    for (int i = 0; i < NumDims; ++i) {\n      m_dimensions[i] = (m_dimensions[i] - 1) * op.strides()[i] + 1;\n    }\n\n    // Remember the strides for fast division.\n    for (int i = 0; i < NumDims; ++i) {\n      m_fastStrides[i] = internal::TensorIntDivisor<Index>(m_strides[i]);\n    }\n\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_outputStrides[0] = 1;\n      m_inputStrides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_outputStrides[i] = m_outputStrides[i-1] * m_dimensions[i-1];\n        m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1];\n      }\n    } else {  // RowMajor\n      m_outputStrides[NumDims-1] = 1;\n      m_inputStrides[NumDims-1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_outputStrides[i] = m_outputStrides[i+1] * m_dimensions[i+1];\n        m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1];\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType /*data*/) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  // Computes the input index given the output index. Returns true if the output\n  // index doesn't fall into a hole.\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool getInputIndex(Index index, Index* inputIndex) const\n  {\n    eigen_assert(index < dimensions().TotalSize());\n    *inputIndex = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx = index / m_outputStrides[i];\n        if (idx != idx / m_fastStrides[i] * m_strides[i]) {\n          return false;\n        }\n        *inputIndex += idx / m_strides[i] * m_inputStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      if (index != index / m_fastStrides[0] * m_strides[0]) {\n        return false;\n      }\n      *inputIndex += index / m_strides[0];\n      return true;\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx = index / m_outputStrides[i];\n        if (idx != idx / m_fastStrides[i] * m_strides[i]) {\n          return false;\n        }\n        *inputIndex += idx / m_strides[i] * m_inputStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      if (index != index / m_fastStrides[NumDims-1] * m_strides[NumDims-1]) {\n        return false;\n      }\n      *inputIndex += index / m_strides[NumDims - 1];\n    }\n    return true;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    Index inputIndex = 0;\n    if (getInputIndex(index, &inputIndex)) {\n     return m_impl.coeff(inputIndex);\n    } else {\n     return Scalar(0);\n    }\n  }\n\n  // TODO(yangke): optimize this function so that we can detect and produce\n  // all-zero packets\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < PacketSize; ++i) {\n      values[i] = coeff(index+i);\n    }\n    PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n    return rslt;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    const double compute_cost = NumDims * (3 * TensorOpCost::DivCost<Index>() +\n                                           3 * TensorOpCost::MulCost<Index>() +\n                                           2 * TensorOpCost::AddCost<Index>());\n    const double input_size = m_impl.dimensions().TotalSize();\n    const double output_size = m_dimensions.TotalSize();\n    if (output_size == 0)\n      return TensorOpCost();\n    return m_impl.costPerCoeff(vectorized) +\n           TensorOpCost(sizeof(CoeffReturnType) * input_size / output_size, 0,\n                        compute_cost, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n\n protected:\n  Dimensions m_dimensions;\n  array<Index, NumDims> m_outputStrides;\n  array<Index, NumDims> m_inputStrides;\n  TensorEvaluator<ArgType, Device> m_impl;\n  const Strides m_strides;\n  array<internal::TensorIntDivisor<Index>, NumDims> m_fastStrides;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_INFLATION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorInitializer.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_INITIALIZER_H\n#define EIGEN_CXX11_TENSOR_TENSOR_INITIALIZER_H\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n\n#include <initializer_list>\n\nnamespace Eigen {\n\n/** \\class TensorInitializer\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Helper template to initialize Tensors from std::initializer_lists.\n  */\nnamespace internal {\n\ntemplate <typename Derived, int N>\nstruct Initializer {\n  typedef std::initializer_list<\n    typename Initializer<Derived, N - 1>::InitList> InitList;\n\n  static void run(TensorEvaluator<Derived, DefaultDevice>& tensor,\n                  Eigen::array<typename traits<Derived>::Index, traits<Derived>::NumDimensions>* indices,\n                  const InitList& vals) {\n    int i = 0;\n    for (const auto& v : vals) {\n      (*indices)[traits<Derived>::NumDimensions - N] = i++;\n      Initializer<Derived, N - 1>::run(tensor, indices, v);\n    }\n  }\n};\n\ntemplate <typename Derived>\nstruct Initializer<Derived, 1> {\n  typedef std::initializer_list<typename traits<Derived>::Scalar> InitList;\n\n  static void run(TensorEvaluator<Derived, DefaultDevice>& tensor,\n                  Eigen::array<typename traits<Derived>::Index, traits<Derived>::NumDimensions>* indices,\n                  const InitList& vals) {\n    int i = 0;\n    // There is likely a faster way to do that than iterating.\n    for (const auto& v : vals) {\n      (*indices)[traits<Derived>::NumDimensions - 1] = i++;\n      tensor.coeffRef(*indices) = v;\n    }\n  }\n};\n\ntemplate <typename Derived>\nstruct Initializer<Derived, 0> {\n  typedef typename traits<Derived>::Scalar InitList;\n\n  static void run(TensorEvaluator<Derived, DefaultDevice>& tensor,\n                  Eigen::array<typename traits<Derived>::Index, traits<Derived>::NumDimensions>*,\n                  const InitList& v) {\n    tensor.coeffRef(0) = v;\n  }\n};\n\n\ntemplate <typename Derived, int N>\nvoid initialize_tensor(TensorEvaluator<Derived, DefaultDevice>& tensor,\n                       const typename Initializer<Derived, traits<Derived>::NumDimensions>::InitList& vals) {\n  Eigen::array<typename traits<Derived>::Index, traits<Derived>::NumDimensions> indices;\n  Initializer<Derived, traits<Derived>::NumDimensions>::run(tensor, &indices, vals);\n}\n\n}  // namespace internal\n}  // namespace Eigen\n\n#endif  // EIGEN_HAS_VARIADIC_TEMPLATES\n\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_INITIALIZER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIntDiv.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_INTDIV_H\n#define EIGEN_CXX11_TENSOR_TENSOR_INTDIV_H\n\n\nnamespace Eigen {\n\n/** \\internal\n  *\n  * \\class TensorIntDiv\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Fast integer division by a constant.\n  *\n  * See the paper from Granlund and Montgomery for explanation.\n  *   (at https://doi.org/10.1145/773473.178249)\n  *\n  * \\sa Tensor\n  */\n\nnamespace internal {\n\nnamespace {\n\n  // Note: result is undefined if val == 0\n  template <typename T>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  typename internal::enable_if<sizeof(T)==4,int>::type count_leading_zeros(const T val)\n  {\n#ifdef EIGEN_GPU_COMPILE_PHASE\n    return __clz(val);\n#elif defined(SYCL_DEVICE_ONLY)\n    return cl::sycl::clz(val);\n#elif EIGEN_COMP_MSVC\n    unsigned long index;\n    _BitScanReverse(&index, val);\n    return 31 - index;\n#else\n    EIGEN_STATIC_ASSERT(sizeof(unsigned long long) == 8, YOU_MADE_A_PROGRAMMING_MISTAKE);\n    return __builtin_clz(static_cast<uint32_t>(val));\n#endif\n  }\n\n  template <typename T>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  typename internal::enable_if<sizeof(T)==8,int>::type count_leading_zeros(const T val)\n  {\n#ifdef EIGEN_GPU_COMPILE_PHASE\n    return __clzll(val);\n#elif defined(SYCL_DEVICE_ONLY)\n    return static_cast<int>(cl::sycl::clz(val));\n#elif EIGEN_COMP_MSVC && EIGEN_ARCH_x86_64\n    unsigned long index;\n    _BitScanReverse64(&index, val);\n    return 63 - index;\n#elif EIGEN_COMP_MSVC\n    // MSVC's _BitScanReverse64 is not available for 32bits builds.\n    unsigned int lo = (unsigned int)(val&0xffffffff);\n    unsigned int hi = (unsigned int)((val>>32)&0xffffffff);\n    int n;\n    if(hi==0)\n      n = 32 + count_leading_zeros<unsigned int>(lo);\n    else\n      n = count_leading_zeros<unsigned int>(hi);\n    return n;\n#else\n    EIGEN_STATIC_ASSERT(sizeof(unsigned long long) == 8, YOU_MADE_A_PROGRAMMING_MISTAKE);\n    return __builtin_clzll(static_cast<uint64_t>(val));\n#endif\n  }\n\n  template <typename T>\n  struct UnsignedTraits {\n    typedef typename conditional<sizeof(T) == 8, uint64_t, uint32_t>::type type;\n  };\n\n  template <typename T>\n  struct DividerTraits {\n    typedef typename UnsignedTraits<T>::type type;\n    static const int N = sizeof(T) * 8;\n  };\n\n  template <typename T>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE uint32_t muluh(const uint32_t a, const T b) {\n#if defined(EIGEN_GPU_COMPILE_PHASE)\n    return __umulhi(a, b);\n#elif defined(SYCL_DEVICE_ONLY)\n    return cl::sycl::mul_hi(a, static_cast<uint32_t>(b));\n#else\n    return (static_cast<uint64_t>(a) * b) >> 32;\n#endif\n  }\n\n  template <typename T>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE uint64_t muluh(const uint64_t a, const T b) {\n#if defined(EIGEN_GPU_COMPILE_PHASE)\n    return __umul64hi(a, b);\n#elif defined(SYCL_DEVICE_ONLY)\n    return cl::sycl::mul_hi(a, static_cast<uint64_t>(b));\n#elif EIGEN_HAS_BUILTIN_INT128\n    __uint128_t v = static_cast<__uint128_t>(a) * static_cast<__uint128_t>(b);\n    return static_cast<uint64_t>(v >> 64);\n#else\n    return (TensorUInt128<static_val<0>, uint64_t>(a) * TensorUInt128<static_val<0>, uint64_t>(b)).upper();\n#endif\n  }\n\n  template <int N, typename T>\n  struct DividerHelper {\n    static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE uint32_t computeMultiplier(const int log_div, const T divider) {\n      EIGEN_STATIC_ASSERT(N == 32, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return static_cast<uint32_t>((static_cast<uint64_t>(1) << (N+log_div)) / divider - (static_cast<uint64_t>(1) << N) + 1);\n    }\n  };\n\n  template <typename T>\n  struct DividerHelper<64, T> {\n    static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE uint64_t computeMultiplier(const int log_div, const T divider) {\n#if EIGEN_HAS_BUILTIN_INT128 && !defined(EIGEN_GPU_COMPILE_PHASE) && !defined(SYCL_DEVICE_ONLY)\n      return static_cast<uint64_t>((static_cast<__uint128_t>(1) << (64+log_div)) / static_cast<__uint128_t>(divider) - (static_cast<__uint128_t>(1) << 64) + 1);\n#else\n      const uint64_t shift = 1ULL << log_div;\n      TensorUInt128<uint64_t, uint64_t> result = TensorUInt128<uint64_t, static_val<0> >(shift, 0) / TensorUInt128<static_val<0>, uint64_t>(divider)\n                                               - TensorUInt128<static_val<1>, static_val<0> >(1, 0)\n                                               + TensorUInt128<static_val<0>, static_val<1> >(1);\n      return static_cast<uint64_t>(result);\n#endif\n    }\n  };\n}\n\n\ntemplate <typename T, bool div_gt_one = false>\nstruct TensorIntDivisor {\n public:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorIntDivisor() {\n    multiplier = 0;\n    shift1 = 0;\n    shift2 = 0;\n  }\n\n  // Must have 0 < divider < 2^31. This is relaxed to\n  // 0 < divider < 2^63 when using 64-bit indices on platforms that support\n  // the __uint128_t type.\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorIntDivisor(const T divider) {\n    const int N = DividerTraits<T>::N;\n    eigen_assert(static_cast<typename UnsignedTraits<T>::type>(divider) < NumTraits<UnsignedType>::highest()/2);\n    eigen_assert(divider > 0);\n\n    // fast ln2\n    const int leading_zeros = count_leading_zeros(static_cast<UnsignedType>(divider));\n    int log_div = N - leading_zeros;\n    // if divider is a power of two then log_div is 1 more than it should be.\n    if ((static_cast<typename UnsignedTraits<T>::type>(1) << (log_div-1)) == static_cast<typename UnsignedTraits<T>::type>(divider))\n      log_div--;\n\n    multiplier = DividerHelper<N, T>::computeMultiplier(log_div, divider);\n    shift1 = log_div > 1 ? 1 : log_div;\n    shift2 = log_div > 1 ? log_div-1 : 0;\n  }\n\n  // Must have 0 <= numerator. On platforms that don't support the __uint128_t\n  // type numerator should also be less than 2^32-1.\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T divide(const T numerator) const {\n    eigen_assert(static_cast<typename UnsignedTraits<T>::type>(numerator) < NumTraits<UnsignedType>::highest()/2);\n    //eigen_assert(numerator >= 0); // this is implicitly asserted by the line above\n\n    UnsignedType t1 = muluh(multiplier, numerator);\n    UnsignedType t = (static_cast<UnsignedType>(numerator) - t1) >> shift1;\n    return (t1 + t) >> shift2;\n  }\n\n private:\n  typedef typename DividerTraits<T>::type UnsignedType;\n  UnsignedType multiplier;\n  int32_t shift1;\n  int32_t shift2;\n};\n\n\n// Optimized version for signed 32 bit integers.\n// Derived from Hacker's Delight.\n// Only works for divisors strictly greater than one\ntemplate <>\nclass TensorIntDivisor<int32_t, true> {\n public:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorIntDivisor() {\n    magic = 0;\n    shift = 0;\n  }\n  // Must have 2 <= divider\n  EIGEN_DEVICE_FUNC TensorIntDivisor(int32_t divider)  {\n    eigen_assert(divider >= 2);\n    calcMagic(divider);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE int divide(const int32_t n) const {\n#ifdef EIGEN_GPU_COMPILE_PHASE\n    return (__umulhi(magic, n) >> shift);\n#elif defined(SYCL_DEVICE_ONLY)\n    return (cl::sycl::mul_hi(magic, static_cast<uint32_t>(n)) >> shift);\n#else\n    uint64_t v = static_cast<uint64_t>(magic) * static_cast<uint64_t>(n);\n    return (static_cast<uint32_t>(v >> 32) >> shift);\n#endif\n  }\n\nprivate:\n  // Compute the magic numbers. See Hacker's Delight section 10 for an in\n  // depth explanation.\n  EIGEN_DEVICE_FUNC void calcMagic(int32_t d) {\n   const unsigned two31 = 0x80000000;     // 2**31.\n   unsigned ad = d;\n   unsigned t = two31 + (ad >> 31);\n   unsigned anc = t - 1 - t%ad;     // Absolute value of nc.\n   int p = 31;                      // Init. p.\n   unsigned q1 = two31/anc;         // Init. q1 = 2**p/|nc|.\n   unsigned r1 = two31 - q1*anc;    // Init. r1 = rem(2**p, |nc|).\n   unsigned q2 = two31/ad;          // Init. q2 = 2**p/|d|.\n   unsigned r2 = two31 - q2*ad;     // Init. r2 = rem(2**p, |d|).\n   unsigned delta = 0;\n   do {\n      p = p + 1;\n      q1 = 2*q1;           // Update q1 = 2**p/|nc|.\n      r1 = 2*r1;           // Update r1 = rem(2**p, |nc|).\n      if (r1 >= anc) {     // (Must be an unsigned\n         q1 = q1 + 1;      // comparison here).\n         r1 = r1 - anc;}\n      q2 = 2*q2;           // Update q2 = 2**p/|d|.\n      r2 = 2*r2;           // Update r2 = rem(2**p, |d|).\n      if (r2 >= ad) {      // (Must be an unsigned\n         q2 = q2 + 1;      // comparison here).\n         r2 = r2 - ad;}\n      delta = ad - r2;\n   } while (q1 < delta || (q1 == delta && r1 == 0));\n\n   magic = (unsigned)(q2 + 1);\n   shift = p - 32;\n  }\n\n  uint32_t magic;\n  int32_t shift;\n};\n\n\ntemplate <typename T, bool div_gt_one>\nstatic EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T operator / (const T& numerator, const TensorIntDivisor<T, div_gt_one>& divisor) {\n  return divisor.divide(numerator);\n}\n\n\n} // end namespace internal\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_INTDIV_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorLayoutSwap.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_LAYOUT_SWAP_H\n#define EIGEN_CXX11_TENSOR_TENSOR_LAYOUT_SWAP_H\n\nnamespace Eigen {\n\n/** \\class TensorLayoutSwap\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Swap the layout from col-major to row-major, or row-major\n  * to col-major, and invert the order of the dimensions.\n  *\n  * Beware: the dimensions are reversed by this operation. If you want to\n  * preserve the ordering of the dimensions, you need to combine this\n  * operation with a shuffle.\n  *\n  * \\example:\n  * Tensor<float, 2, ColMajor> input(2, 4);\n  * Tensor<float, 2, RowMajor> output = input.swap_layout();\n  * eigen_assert(output.dimension(0) == 4);\n  * eigen_assert(output.dimension(1) == 2);\n  *\n  * array<int, 2> shuffle(1, 0);\n  * output = input.swap_layout().shuffle(shuffle);\n  * eigen_assert(output.dimension(0) == 2);\n  * eigen_assert(output.dimension(1) == 4);\n  *\n  */\nnamespace internal {\ntemplate<typename XprType>\nstruct traits<TensorLayoutSwapOp<XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = traits<XprType>::NumDimensions;\n  static const int Layout = (traits<XprType>::Layout == ColMajor) ? RowMajor : ColMajor;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename XprType>\nstruct eval<TensorLayoutSwapOp<XprType>, Eigen::Dense>\n{\n  typedef const TensorLayoutSwapOp<XprType>& type;\n};\n\ntemplate<typename XprType>\nstruct nested<TensorLayoutSwapOp<XprType>, 1, typename eval<TensorLayoutSwapOp<XprType> >::type>\n{\n  typedef TensorLayoutSwapOp<XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename XprType>\nclass TensorLayoutSwapOp : public TensorBase<TensorLayoutSwapOp<XprType>, WriteAccessors>\n{\n  public:\n    typedef TensorBase<TensorLayoutSwapOp<XprType>, WriteAccessors> Base;\n    typedef typename Eigen::internal::traits<TensorLayoutSwapOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef typename internal::remove_const<typename XprType::CoeffReturnType>::type CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorLayoutSwapOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorLayoutSwapOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorLayoutSwapOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorLayoutSwapOp(const XprType& expr)\n        : m_xpr(expr) {}\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(TensorLayoutSwapOp)\n  protected:\n    typename XprType::Nested m_xpr;\n};\n\n\n// Eval as rvalue\ntemplate<typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorLayoutSwapOp<ArgType>, Device>\n{\n  typedef TensorLayoutSwapOp<ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n\n  enum {\n    IsAligned = TensorEvaluator<ArgType, Device>::IsAligned,\n    PacketAccess = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess = false,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout = (static_cast<int>(TensorEvaluator<ArgType, Device>::Layout) == static_cast<int>(ColMajor)) ? RowMajor : ColMajor,\n    CoordAccess = false,  // to be implemented\n    RawAccess = TensorEvaluator<ArgType, Device>::RawAccess\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device)\n  {\n    for(int i = 0; i < NumDims; ++i) {\n      m_dimensions[i] = m_impl.dimensions()[NumDims-1-i];\n    }\n  }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    return m_impl.evalSubExprsIfNeeded(data);\n  }\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    return m_impl.coeff(index);\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    return m_impl.template packet<LoadMode>(index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    return m_impl.costPerCoeff(vectorized);\n  }\n\n  EIGEN_DEVICE_FUNC typename Storage::Type data() const {\n    return constCast(m_impl.data());\n  }\n\n  const TensorEvaluator<ArgType, Device>& impl() const { return m_impl; }\n\n protected:\n  TensorEvaluator<ArgType, Device> m_impl;\n  Dimensions m_dimensions;\n};\n\n\n// Eval as lvalue\ntemplate<typename ArgType, typename Device>\n  struct TensorEvaluator<TensorLayoutSwapOp<ArgType>, Device>\n  : public TensorEvaluator<const TensorLayoutSwapOp<ArgType>, Device>\n{\n  typedef TensorEvaluator<const TensorLayoutSwapOp<ArgType>, Device> Base;\n  typedef TensorLayoutSwapOp<ArgType> XprType;\n\n  enum {\n    IsAligned = TensorEvaluator<ArgType, Device>::IsAligned,\n    PacketAccess = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess = false,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout = (static_cast<int>(TensorEvaluator<ArgType, Device>::Layout) == static_cast<int>(ColMajor)) ? RowMajor : ColMajor,\n    CoordAccess = false  // to be implemented\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n    : Base(op, device)\n  { }\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index)\n  {\n    return this->m_impl.coeffRef(index);\n  }\n  template <int StoreMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void writePacket(Index index, const PacketReturnType& x)\n  {\n    this->m_impl.template writePacket<StoreMode>(index, x);\n  }\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_LAYOUT_SWAP_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMacros.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_META_MACROS_H\n#define EIGEN_CXX11_TENSOR_TENSOR_META_MACROS_H\n\n\n/** use this macro in sfinae selection in templated functions\n *\n *   template<typename T,\n *            typename std::enable_if< isBanana<T>::value , int >::type = 0\n *   >\n *   void foo(){}\n *\n *   becomes =>\n *\n *   template<typename TopoType,\n *           SFINAE_ENABLE_IF( isBanana<T>::value )\n *   >\n *   void foo(){}\n */\n\n// SFINAE requires variadic templates\n#if !defined(EIGEN_GPUCC)\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  // SFINAE doesn't work for gcc <= 4.7\n  #ifdef EIGEN_COMP_GNUC\n    #if EIGEN_GNUC_AT_LEAST(4,8)\n      #define EIGEN_HAS_SFINAE\n    #endif\n  #else\n    #define EIGEN_HAS_SFINAE\n  #endif\n#endif\n#endif\n\n#define EIGEN_SFINAE_ENABLE_IF( __condition__ ) \\\n    typename internal::enable_if< ( __condition__ ) , int >::type = 0\n\n// Define a macro to use a reference on the host but a value on the device\n#if defined(SYCL_DEVICE_ONLY)\n  #define EIGEN_DEVICE_REF\n#else\n  #define EIGEN_DEVICE_REF &\n#endif\n\n// Define a macro for catching SYCL exceptions if exceptions are enabled\n#define EIGEN_SYCL_TRY_CATCH(X) \\\n  do { \\\n    EIGEN_TRY {X;} \\\n    EIGEN_CATCH(const cl::sycl::exception& e) { \\\n      EIGEN_THROW_X(std::runtime_error(\"SYCL exception at \" + \\\n                                       std::string(__FILE__) + \":\" + \\\n                                       std::to_string(__LINE__) + \"\\n\" + \\\n                                       e.what())); \\\n    } \\\n  } while (false)\n\n// Define a macro if local memory flags are unset or one of them is set\n// Setting both flags is the same as unsetting them\n#if (!defined(EIGEN_SYCL_LOCAL_MEM) && !defined(EIGEN_SYCL_NO_LOCAL_MEM)) || \\\n     (defined(EIGEN_SYCL_LOCAL_MEM) &&  defined(EIGEN_SYCL_NO_LOCAL_MEM))\n  #define EIGEN_SYCL_LOCAL_MEM_UNSET_OR_ON 1\n  #define EIGEN_SYCL_LOCAL_MEM_UNSET_OR_OFF 1\n#elif defined(EIGEN_SYCL_LOCAL_MEM) && !defined(EIGEN_SYCL_NO_LOCAL_MEM)\n  #define EIGEN_SYCL_LOCAL_MEM_UNSET_OR_ON 1\n#elif !defined(EIGEN_SYCL_LOCAL_MEM) && defined(EIGEN_SYCL_NO_LOCAL_MEM)\n  #define EIGEN_SYCL_LOCAL_MEM_UNSET_OR_OFF 1\n#endif\n\n#if EIGEN_COMP_CLANG // workaround clang bug (see http://forum.kde.org/viewtopic.php?f=74&t=102653)\n  #define EIGEN_TENSOR_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Derived) \\\n    using Base::operator =; \\\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const Derived& other) { Base::operator=(other); return *this; } \\\n    template <typename OtherDerived> \\\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const OtherDerived& other) { Base::operator=(other); return *this; }\n#else\n  #define EIGEN_TENSOR_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Derived) \\\n    EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Derived)\n#endif\n\n/** \\internal\n * \\brief Macro to manually inherit assignment operators.\n * This is necessary, because the implicitly defined assignment operator gets deleted when a custom operator= is defined.\n * This also inherits template<OtherDerived> operator=(const OtherDerived&) assignments.\n * With C++11 or later this also default-implements the copy-constructor\n */\n#define EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(Derived)  \\\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Derived) \\\n    EIGEN_DEFAULT_COPY_CONSTRUCTOR(Derived)\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMap.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_MAP_H\n#define EIGEN_CXX11_TENSOR_TENSOR_MAP_H\n\nnamespace Eigen {\n\n// FIXME use proper doxygen documentation (e.g. \\tparam MakePointer_)\n\n/** \\class TensorMap\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief A tensor expression mapping an existing array of data.\n  *\n  */\n/// `template <class> class MakePointer_` is added to convert the host pointer to the device pointer.\n/// It is added due to the fact that for our device compiler `T*` is not allowed.\n/// If we wanted to use the same Evaluator functions we have to convert that type to our pointer `T`.\n/// This is done through our `MakePointer_` class. By default the Type in the `MakePointer_<T>` is `T*` .\n/// Therefore, by adding the default value, we managed to convert the type and it does not break any\n/// existing code as its default value is `T*`.\ntemplate<typename PlainObjectType, int Options_, template <class> class MakePointer_> class TensorMap : public TensorBase<TensorMap<PlainObjectType, Options_, MakePointer_> >\n{\n  public:\n    typedef TensorMap<PlainObjectType, Options_, MakePointer_> Self;\n    typedef TensorBase<TensorMap<PlainObjectType, Options_, MakePointer_> > Base;\n  #ifdef EIGEN_USE_SYCL\n    typedef  typename Eigen::internal::remove_reference<typename Eigen::internal::nested<Self>::type>::type Nested;\n  #else\n     typedef typename Eigen::internal::nested<Self>::type Nested;\n  #endif\n   typedef typename internal::traits<PlainObjectType>::StorageKind StorageKind;\n    typedef typename internal::traits<PlainObjectType>::Index Index;\n    typedef typename internal::traits<PlainObjectType>::Scalar Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef typename PlainObjectType::Base::CoeffReturnType CoeffReturnType;\n\n    typedef typename MakePointer_<Scalar>::Type PointerType;\n    typedef typename MakePointer_<Scalar>::ConstType PointerConstType;\n\n    // WARN: PointerType still can be a pointer to const (const Scalar*), for\n    // example in TensorMap<Tensor<const Scalar, ...>> expression. This type of\n    // expression should be illegal, but adding this restriction is not possible\n    // in practice (see https://bitbucket.org/eigen/eigen/pull-requests/488).\n    typedef typename internal::conditional<\n        bool(internal::is_lvalue<PlainObjectType>::value),\n        PointerType,      // use simple pointer in lvalue expressions\n        PointerConstType  // use const pointer in rvalue expressions\n        >::type StoragePointerType;\n\n    // If TensorMap was constructed over rvalue expression (e.g. const Tensor),\n    // we should return a reference to const from operator() (and others), even\n    // if TensorMap itself is not const.\n    typedef typename internal::conditional<\n        bool(internal::is_lvalue<PlainObjectType>::value),\n        Scalar&,\n        const Scalar&\n        >::type StorageRefType;\n\n    static const int Options = Options_;\n\n    static const Index NumIndices = PlainObjectType::NumIndices;\n    typedef typename PlainObjectType::Dimensions Dimensions;\n\n    enum {\n      IsAligned = ((int(Options_)&Aligned)==Aligned),\n      Layout = PlainObjectType::Layout,\n      CoordAccess = true,\n      RawAccess = true\n    };\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorMap(StoragePointerType dataPtr) : m_data(dataPtr), m_dimensions() {\n      // The number of dimensions used to construct a tensor must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT((0 == NumIndices || NumIndices == Dynamic), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorMap(StoragePointerType dataPtr, Index firstDimension, IndexTypes... otherDimensions) : m_data(dataPtr), m_dimensions(firstDimension, otherDimensions...) {\n      // The number of dimensions used to construct a tensor must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT((sizeof...(otherDimensions) + 1 == NumIndices || NumIndices == Dynamic), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n#else\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorMap(StoragePointerType dataPtr, Index firstDimension) : m_data(dataPtr), m_dimensions(firstDimension) {\n      // The number of dimensions used to construct a tensor must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT((1 == NumIndices || NumIndices == Dynamic), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorMap(StoragePointerType dataPtr, Index dim1, Index dim2) : m_data(dataPtr), m_dimensions(dim1, dim2) {\n      EIGEN_STATIC_ASSERT(2 == NumIndices || NumIndices == Dynamic, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorMap(StoragePointerType dataPtr, Index dim1, Index dim2, Index dim3) : m_data(dataPtr), m_dimensions(dim1, dim2, dim3) {\n      EIGEN_STATIC_ASSERT(3 == NumIndices || NumIndices == Dynamic, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorMap(StoragePointerType dataPtr, Index dim1, Index dim2, Index dim3, Index dim4) : m_data(dataPtr), m_dimensions(dim1, dim2, dim3, dim4) {\n      EIGEN_STATIC_ASSERT(4 == NumIndices || NumIndices == Dynamic, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorMap(StoragePointerType dataPtr, Index dim1, Index dim2, Index dim3, Index dim4, Index dim5) : m_data(dataPtr), m_dimensions(dim1, dim2, dim3, dim4, dim5) {\n      EIGEN_STATIC_ASSERT(5 == NumIndices || NumIndices == Dynamic, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n#endif\n\n   EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorMap(StoragePointerType dataPtr, const array<Index, NumIndices>& dimensions)\n      : m_data(dataPtr), m_dimensions(dimensions)\n    { }\n\n    template <typename Dimensions>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorMap(StoragePointerType dataPtr, const Dimensions& dimensions)\n      : m_data(dataPtr), m_dimensions(dimensions)\n    { }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorMap(PlainObjectType& tensor)\n      : m_data(tensor.data()), m_dimensions(tensor.dimensions())\n    { }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Index rank() const { return m_dimensions.rank(); }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Index dimension(Index n) const { return m_dimensions[n]; }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Index size() const { return m_dimensions.TotalSize(); }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StoragePointerType data() { return m_data; }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StoragePointerType data() const { return m_data; }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(const array<Index, NumIndices>& indices) const\n    {\n      //      eigen_assert(checkIndexRange(indices));\n      if (PlainObjectType::Options&RowMajor) {\n        const Index index = m_dimensions.IndexOfRowMajor(indices);\n        return m_data[index];\n      } else {\n        const Index index = m_dimensions.IndexOfColMajor(indices);\n        return m_data[index];\n      }\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()() const\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return m_data[0];\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index index) const\n    {\n      eigen_internal_assert(index >= 0 && index < size());\n      return m_data[index];\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index firstIndex, Index secondIndex, IndexTypes... otherIndices) const\n    {\n      EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      eigen_assert(internal::all((Eigen::NumTraits<Index>::highest() >= otherIndices)...));\n      if (PlainObjectType::Options&RowMajor) {\n        const Index index = m_dimensions.IndexOfRowMajor(array<Index, NumIndices>{{firstIndex, secondIndex, otherIndices...}});\n        return m_data[index];\n      } else {\n        const Index index = m_dimensions.IndexOfColMajor(array<Index, NumIndices>{{firstIndex, secondIndex, otherIndices...}});\n        return m_data[index];\n      }\n    }\n#else\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index i0, Index i1) const\n    {\n      if (PlainObjectType::Options&RowMajor) {\n        const Index index = i1 + i0 * m_dimensions[1];\n        return m_data[index];\n      } else {\n        const Index index = i0 + i1 * m_dimensions[0];\n        return m_data[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index i0, Index i1, Index i2) const\n    {\n      if (PlainObjectType::Options&RowMajor) {\n         const Index index = i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0);\n         return m_data[index];\n      } else {\n         const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * i2);\n        return m_data[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index i0, Index i1, Index i2, Index i3) const\n    {\n      if (PlainObjectType::Options&RowMajor) {\n        const Index index = i3 + m_dimensions[3] * (i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0));\n        return m_data[index];\n      } else {\n        const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * (i2 + m_dimensions[2] * i3));\n        return m_data[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index i0, Index i1, Index i2, Index i3, Index i4) const\n    {\n      if (PlainObjectType::Options&RowMajor) {\n        const Index index = i4 + m_dimensions[4] * (i3 + m_dimensions[3] * (i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0)));\n        return m_data[index];\n      } else {\n        const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * (i2 + m_dimensions[2] * (i3 + m_dimensions[3] * i4)));\n        return m_data[index];\n      }\n    }\n#endif\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(const array<Index, NumIndices>& indices)\n    {\n      //      eigen_assert(checkIndexRange(indices));\n      if (PlainObjectType::Options&RowMajor) {\n        const Index index = m_dimensions.IndexOfRowMajor(indices);\n        return m_data[index];\n      } else {\n        const Index index = m_dimensions.IndexOfColMajor(indices);\n        return m_data[index];\n      }\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()()\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return m_data[0];\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index index)\n    {\n      eigen_internal_assert(index >= 0 && index < size());\n      return m_data[index];\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index firstIndex, Index secondIndex, IndexTypes... otherIndices)\n    {\n      static_assert(sizeof...(otherIndices) + 2 == NumIndices || NumIndices == Dynamic, \"Number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\");\n       eigen_assert(internal::all((Eigen::NumTraits<Index>::highest() >= otherIndices)...));\n      const std::size_t NumDims = sizeof...(otherIndices) + 2;\n      if (PlainObjectType::Options&RowMajor) {\n        const Index index = m_dimensions.IndexOfRowMajor(array<Index, NumDims>{{firstIndex, secondIndex, otherIndices...}});\n        return m_data[index];\n      } else {\n        const Index index = m_dimensions.IndexOfColMajor(array<Index, NumDims>{{firstIndex, secondIndex, otherIndices...}});\n        return m_data[index];\n      }\n    }\n#else\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index i0, Index i1)\n    {\n       if (PlainObjectType::Options&RowMajor) {\n         const Index index = i1 + i0 * m_dimensions[1];\n        return m_data[index];\n      } else {\n        const Index index = i0 + i1 * m_dimensions[0];\n        return m_data[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index i0, Index i1, Index i2)\n    {\n       if (PlainObjectType::Options&RowMajor) {\n         const Index index = i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0);\n        return m_data[index];\n      } else {\n         const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * i2);\n        return m_data[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index i0, Index i1, Index i2, Index i3)\n    {\n      if (PlainObjectType::Options&RowMajor) {\n        const Index index = i3 + m_dimensions[3] * (i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0));\n        return m_data[index];\n      } else {\n        const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * (i2 + m_dimensions[2] * i3));\n        return m_data[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index i0, Index i1, Index i2, Index i3, Index i4)\n    {\n      if (PlainObjectType::Options&RowMajor) {\n        const Index index = i4 + m_dimensions[4] * (i3 + m_dimensions[3] * (i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0)));\n        return m_data[index];\n      } else {\n        const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * (i2 + m_dimensions[2] * (i3 + m_dimensions[3] * i4)));\n        return m_data[index];\n      }\n    }\n#endif\n\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(TensorMap)\n\n  private:\n    StoragePointerType m_data;\n    Dimensions m_dimensions;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_MAP_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMeta.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_META_H\n#define EIGEN_CXX11_TENSOR_TENSOR_META_H\n\nnamespace Eigen {\n\ntemplate<bool cond> struct Cond {};\n\ntemplate<typename T1, typename T2> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nconst T1& choose(Cond<true>, const T1& first, const T2&) {\n  return first;\n}\n\ntemplate<typename T1, typename T2> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nconst T2& choose(Cond<false>, const T1&, const T2& second) {\n  return second;\n}\n\n\ntemplate <typename T, typename X, typename Y>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nT divup(const X x, const Y y) {\n  return static_cast<T>((x + y - 1) / y);\n}\n\ntemplate <typename T>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nT divup(const T x, const T y) {\n  return static_cast<T>((x + y - 1) / y);\n}\n\ntemplate <size_t n> struct max_n_1 {\n  static const size_t size = n;\n};\ntemplate <> struct max_n_1<0> {\n  static const size_t size = 1;\n};\n\n\n// Default packet types\ntemplate <typename Scalar, typename Device>\nstruct PacketType : internal::packet_traits<Scalar> {\n  typedef typename internal::packet_traits<Scalar>::type type;\n};\n\n// For CUDA packet types when using a GpuDevice\n#if defined(EIGEN_USE_GPU) && defined(EIGEN_HAS_GPU_FP16) && defined(EIGEN_GPU_COMPILE_PHASE)\n\ntypedef ulonglong2 Packet4h2;\ntemplate<>\nstruct PacketType<half, GpuDevice> {\n  typedef Packet4h2 type;\n  static const int size = 8;\n  enum {\n    HasAdd    = 1,\n    HasSub    = 1,\n    HasMul    = 1,\n    HasNegate = 1,\n    HasAbs    = 1,\n    HasArg    = 0,\n    HasAbs2   = 0,\n    HasMin    = 1,\n    HasMax    = 1,\n    HasConj   = 0,\n    HasSetLinear = 0,\n    HasBlend  = 0,\n\n    HasDiv    = 1,\n    HasSqrt   = 1,\n    HasRsqrt  = 1,\n    HasExp    = 1,\n    HasExpm1  = 0,\n    HasLog    = 1,\n    HasLog1p  = 0,\n    HasLog10  = 0,\n    HasPow    = 1,\n  };\n};\n#endif\n\n#if defined(EIGEN_USE_SYCL)\n\nnamespace TensorSycl {\nnamespace internal {\n\ntemplate <typename Index, Index A, Index B> struct PlusOp {\n  static constexpr Index Value = A + B;\n};\n\ntemplate <typename Index, Index A, Index B> struct DivOp {\n  static constexpr Index Value = A / B;\n};\n\ntemplate <typename Index, Index start, Index end, Index step,\n          template <class Indx, Indx...> class StepOp>\nstruct static_for {\n  template <typename UnaryOperator>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void loop(UnaryOperator op) {\n    op(start);\n    static_for<Index, StepOp<Index, start, step>::Value, end, step,\n               StepOp>::loop(op);\n  }\n};\ntemplate <typename Index, Index end, Index step,\n          template <class Indx, Indx...> class StepOp>\nstruct static_for<Index, end, end, step, StepOp> {\n  template <typename UnaryOperator>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void loop(UnaryOperator) {}\n};\n\ntemplate <typename OutScalar, typename Device, bool Vectorizable>\nstruct Vectorise {\n  static const int PacketSize = 1;\n  typedef OutScalar PacketReturnType;\n};\n\ntemplate <typename OutScalar, typename Device>\nstruct Vectorise<OutScalar, Device, true> {\n  static const int PacketSize = Eigen::PacketType<OutScalar, Device>::size;\n  typedef typename Eigen::PacketType<OutScalar, Device>::type PacketReturnType;\n};\n\nstatic EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Index roundUp(Index x, Index y) {\n  return ((((x) + (y)-1) / (y)) * (y));\n}\n\n} // namespace internal\n} // namespace TensorSycl\n\ntemplate <>\n  struct PacketType<half, SyclDevice> {\n  typedef half type;\n  static const int size = 1;\n  enum {\n    HasAdd    = 0,\n    HasSub    = 0,\n    HasMul    = 0,\n    HasNegate = 0,\n    HasAbs    = 0,\n    HasArg    = 0,\n    HasAbs2   = 0,\n    HasMin    = 0,\n    HasMax    = 0,\n    HasConj   = 0,\n    HasSetLinear = 0,\n    HasBlend  = 0\n  };\n};\ntemplate <typename Scalar>\nstruct PacketType<Scalar, SyclDevice> : internal::default_packet_traits {\n  typedef Scalar type;\n  typedef Scalar half;\n  enum {\n    Vectorizable = 0,\n    size = 1,\n    AlignedOnScalar = 0,\n    HasHalfPacket = 0\n  };\n  enum {\n    HasAdd    = 0,\n    HasSub    = 0,\n    HasMul    = 0,\n    HasNegate = 0,\n    HasAbs    = 0,\n    HasAbs2   = 0,\n    HasMin    = 0,\n    HasMax    = 0,\n    HasConj   = 0,\n    HasSetLinear = 0\n  };\n\n};\n\ntemplate <typename Scalar>\nstruct PacketType<Scalar, const SyclDevice> : PacketType<Scalar, SyclDevice>{};\n\n#ifndef EIGEN_DONT_VECTORIZE_SYCL\n#define PACKET_TYPE(CVQual, Type, val, lengths, DEV)\\\ntemplate<> struct PacketType<CVQual Type, DEV> : internal::sycl_packet_traits<val, lengths> \\\n{\\\n  typedef typename internal::packet_traits<Type>::type type;\\\n  typedef typename internal::packet_traits<Type>::half half;\\\n};\n\n\nPACKET_TYPE(const, float, 1, 4, SyclDevice)\nPACKET_TYPE(, float, 1, 4, SyclDevice)\nPACKET_TYPE(const, float, 1, 4, const SyclDevice)\nPACKET_TYPE(, float, 1, 4, const SyclDevice)\n\nPACKET_TYPE(const, double, 0, 2, SyclDevice)\nPACKET_TYPE(, double, 0, 2, SyclDevice)\nPACKET_TYPE(const, double, 0, 2, const SyclDevice)\nPACKET_TYPE(, double, 0, 2, const SyclDevice)\n#undef PACKET_TYPE\n\ntemplate<> struct PacketType<half, const SyclDevice>: PacketType<half, SyclDevice>{};\ntemplate<> struct PacketType<const half, const SyclDevice>: PacketType<half, SyclDevice>{};\n#endif\n#endif\n\n// Tuple mimics std::pair but works on e.g. nvcc.\ntemplate <typename U, typename V> struct Tuple {\n public:\n  U first;\n  V second;\n\n  typedef U first_type;\n  typedef V second_type;\n\n  EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  Tuple() : first(), second() {}\n\n  EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  Tuple(const U& f, const V& s) : first(f), second(s) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void swap(Tuple& rhs) {\n    using numext::swap;\n    swap(first, rhs.first);\n    swap(second, rhs.second);\n  }\n};\n\ntemplate <typename U, typename V>\nEIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nbool operator==(const Tuple<U, V>& x, const Tuple<U, V>& y) {\n  return (x.first == y.first && x.second == y.second);\n}\n\ntemplate <typename U, typename V>\nEIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nbool operator!=(const Tuple<U, V>& x, const Tuple<U, V>& y) {\n  return !(x == y);\n}\n\n\n// Can't use std::pairs on cuda devices\ntemplate <typename Idx> struct IndexPair {\n  EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE IndexPair() : first(0), second(0) {}\n  EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE IndexPair(Idx f, Idx s) : first(f), second(s) {}\n\n  EIGEN_DEVICE_FUNC void set(IndexPair<Idx> val) {\n    first = val.first;\n    second = val.second;\n  }\n\n  Idx first;\n  Idx second;\n};\n\n\n#ifdef EIGEN_HAS_SFINAE\nnamespace internal {\n\n  template<typename IndexType, typename Index, Index... Is>\n  EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  array<Index, sizeof...(Is)> customIndices2Array(IndexType& idx, numeric_list<Index, Is...>) {\n    return { idx[Is]... };\n  }\n  template<typename IndexType, typename Index>\n  EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  array<Index, 0> customIndices2Array(IndexType&, numeric_list<Index>) {\n    return array<Index, 0>();\n  }\n\n  /** Make an array (for index/dimensions) out of a custom index */\n  template<typename Index, std::size_t NumIndices, typename IndexType>\n  EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  array<Index, NumIndices> customIndices2Array(IndexType& idx) {\n    return customIndices2Array(idx, typename gen_numeric_list<Index, NumIndices>::type{});\n  }\n\n\n  template <typename B, typename D>\n  struct is_base_of\n  {\n\n    typedef char (&yes)[1];\n    typedef char (&no)[2];\n\n    template <typename BB, typename DD>\n    struct Host\n    {\n      operator BB*() const;\n      operator DD*();\n    };\n\n    template<typename T>\n    static yes check(D*, T);\n    static no check(B*, int);\n\n    static const bool value = sizeof(check(Host<B,D>(), int())) == sizeof(yes);\n  };\n\n}\n#endif\n\n\n\n}  // namespace Eigen\n\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_META_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMorphing.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_MORPHING_H\n#define EIGEN_CXX11_TENSOR_TENSOR_MORPHING_H\n\nnamespace Eigen {\n\n/** \\class TensorReshaping\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor reshaping class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename NewDimensions, typename XprType>\nstruct traits<TensorReshapingOp<NewDimensions, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = array_size<NewDimensions>::value;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename NewDimensions, typename XprType>\nstruct eval<TensorReshapingOp<NewDimensions, XprType>, Eigen::Dense>\n{\n  typedef const TensorReshapingOp<NewDimensions, XprType>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename NewDimensions, typename XprType>\nstruct nested<TensorReshapingOp<NewDimensions, XprType>, 1, typename eval<TensorReshapingOp<NewDimensions, XprType> >::type>\n{\n  typedef TensorReshapingOp<NewDimensions, XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename NewDimensions, typename XprType>\nclass TensorReshapingOp : public TensorBase<TensorReshapingOp<NewDimensions, XprType>, WriteAccessors>\n{\n  public:\n  typedef TensorBase<TensorReshapingOp<NewDimensions, XprType>, WriteAccessors> Base;\n  typedef typename Eigen::internal::traits<TensorReshapingOp>::Scalar Scalar;\n  typedef typename internal::remove_const<typename XprType::CoeffReturnType>::type CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorReshapingOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorReshapingOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorReshapingOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorReshapingOp(const XprType& expr, const NewDimensions& dims)\n      : m_xpr(expr), m_dims(dims) {}\n\n    EIGEN_DEVICE_FUNC\n    const NewDimensions& dimensions() const { return m_dims; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(TensorReshapingOp)\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const NewDimensions m_dims;\n};\n\n\n// Eval as rvalue\ntemplate<typename NewDimensions, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorReshapingOp<NewDimensions, ArgType>, Device>\n{\n  typedef TensorReshapingOp<NewDimensions, ArgType> XprType;\n  typedef NewDimensions Dimensions;\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n  typedef StorageMemory<typename internal::remove_const<CoeffReturnType>::type, Device> ConstCastStorage;\n\n  static const int NumOutputDims = internal::array_size<Dimensions>::value;\n  static const int NumInputDims  = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n\n  enum ReshapingKind {\n    // We do not use layout information to determine reshaping kind.\n    // Depending on the layout `N` can be inner or outer dimension.\n    OneByN = 0,  // expr.reshape(1, N)\n    NByOne = 1,  // expr.reshape(N, 1)\n    Runtime = 2  // Reshape dimensions are dynamic (specified at runtime).\n  };\n\n  // clang-format off\n  static const ReshapingKind kind =\n#if defined(EIGEN_HAS_INDEX_LIST)\n        (NumOutputDims == 2 && internal::index_statically_eq<NewDimensions>(/*index=*/0, /*value=*/1)) ? OneByN\n      : (NumOutputDims == 2 && internal::index_statically_eq<NewDimensions>(/*index=*/1, /*value=*/1)) ? NByOne\n      : Runtime;\n#else\n        Runtime;\n#endif\n  // clang-format on\n\n  enum {\n    IsAligned         = TensorEvaluator<ArgType, Device>::IsAligned,\n    PacketAccess      = TensorEvaluator<ArgType, Device>::PacketAccess,\n    // For trivial reshapes with raw access to underlying data we will provide\n    // zero overhead block access.\n    // TODO(ezhulenev): Consider adding block access without raw access?\n    BlockAccess       = TensorEvaluator<ArgType, Device>::RawAccess &&\n                        NumInputDims > 0 && NumOutputDims > 0,\n    PreferBlockAccess = false,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = TensorEvaluator<ArgType, Device>::RawAccess\n  };\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumOutputDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef\n      typename internal::TensorMaterializedBlock<ScalarNoConst, NumOutputDims,\n                                                 Layout, Index>\n          TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device), m_dimensions(op.dimensions())\n  {\n    // The total size of the reshaped tensor must be equal to the total size\n    // of the input tensor.\n    eigen_assert(internal::array_prod(m_impl.dimensions()) == internal::array_prod(op.dimensions()));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType data, EvalSubExprsCallback done) {\n    m_impl.evalSubExprsIfNeededAsync(data, std::move(done));\n  }\n#endif\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    return m_impl.evalSubExprsIfNeeded(data);\n  }\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    return m_impl.coeff(index);\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    return m_impl.template packet<LoadMode>(index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    return m_impl.costPerCoeff(vectorized);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    return internal::TensorBlockResourceRequirements::any();\n  }\n\n  // required in block(OutputTensorBlock* output_block) const\n  // For C++03 compatibility this must be defined outside the method\n  struct BlockIteratorState {\n    Index stride;\n    Index span;\n    Index size;\n    Index count;\n  };\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    eigen_assert(m_impl.data() != NULL);\n    eigen_assert((kind == Runtime) ||\n                 (kind == OneByN && desc.dimensions()[0] == 1) ||\n                 (kind == NByOne && desc.dimensions()[1] == 1));\n\n    if (kind == OneByN || kind == NByOne) {\n      // We can guarantee at compile time that block is just a contiguous slice\n      // of the underlying expression memory buffer.\n      return TensorBlock(internal::TensorBlockKind::kView,\n                           m_impl.data() + desc.offset(), desc.dimensions());\n    } else {\n      // This will do additional runtime checks, and in the end it might be also\n      // a view, or it might be a block materialized in the temporary buffer.\n      return TensorBlock::materialize(m_impl.data(), m_dimensions, desc,\n                                        scratch);\n    }\n  }\n\n  EIGEN_DEVICE_FUNC typename Storage::Type data() const {\n    return constCast(m_impl.data());\n  }\n\n  EIGEN_DEVICE_FUNC const TensorEvaluator<ArgType, Device>& impl() const { return m_impl; }\n\n  #ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n  #endif\n protected:\n  TensorEvaluator<ArgType, Device> m_impl;\n  NewDimensions m_dimensions;\n};\n\n\n// Eval as lvalue\ntemplate<typename NewDimensions, typename ArgType, typename Device>\n  struct TensorEvaluator<TensorReshapingOp<NewDimensions, ArgType>, Device>\n  : public TensorEvaluator<const TensorReshapingOp<NewDimensions, ArgType>, Device>\n\n{\n  typedef TensorEvaluator<const TensorReshapingOp<NewDimensions, ArgType>, Device> Base;\n  typedef TensorReshapingOp<NewDimensions, ArgType> XprType;\n  typedef NewDimensions Dimensions;\n\n  enum {\n    IsAligned         = TensorEvaluator<ArgType, Device>::IsAligned,\n    PacketAccess      = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess       = TensorEvaluator<ArgType, Device>::RawAccess,\n    PreferBlockAccess = false,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = TensorEvaluator<ArgType, Device>::RawAccess\n  };\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n    : Base(op, device)\n  { }\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<TensorEvaluator::NumOutputDims, Index>\n      TensorBlockDesc;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index)\n  {\n    return this->m_impl.coeffRef(index);\n  }\n\n  template <int StoreMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void writePacket(Index index, const PacketReturnType& x)\n  {\n    this->m_impl.template writePacket<StoreMode>(index, x);\n  }\n\n  template <typename TensorBlock>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void writeBlock(\n      const TensorBlockDesc& desc, const TensorBlock& block) {\n    assert(this->m_impl.data() != NULL);\n\n    typedef typename TensorBlock::XprType TensorBlockExpr;\n    typedef internal::TensorBlockAssignment<\n        Scalar, TensorEvaluator::NumOutputDims, TensorBlockExpr, Index>\n        TensorBlockAssign;\n\n    TensorBlockAssign::Run(\n        TensorBlockAssign::target(desc.dimensions(),\n                                  internal::strides<Layout>(this->dimensions()),\n                                  this->m_impl.data(), desc.offset()),\n        block.expr());\n  }\n};\n\n\n/** \\class TensorSlicing\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor slicing class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename StartIndices, typename Sizes, typename XprType>\nstruct traits<TensorSlicingOp<StartIndices, Sizes, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = array_size<StartIndices>::value;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename StartIndices, typename Sizes, typename XprType>\nstruct eval<TensorSlicingOp<StartIndices, Sizes, XprType>, Eigen::Dense>\n{\n  typedef const TensorSlicingOp<StartIndices, Sizes, XprType>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename StartIndices, typename Sizes, typename XprType>\nstruct nested<TensorSlicingOp<StartIndices, Sizes, XprType>, 1, typename eval<TensorSlicingOp<StartIndices, Sizes, XprType> >::type>\n{\n  typedef TensorSlicingOp<StartIndices, Sizes, XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename StartIndices, typename Sizes, typename XprType>\nclass TensorSlicingOp : public TensorBase<TensorSlicingOp<StartIndices, Sizes, XprType> >\n{\n  public:\n  typedef TensorBase<TensorSlicingOp<StartIndices, Sizes, XprType> > Base;\n  typedef typename Eigen::internal::traits<TensorSlicingOp>::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorSlicingOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorSlicingOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorSlicingOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorSlicingOp(const XprType& expr, const StartIndices& indices, const Sizes& sizes)\n      : m_xpr(expr), m_indices(indices), m_sizes(sizes) {}\n\n    EIGEN_DEVICE_FUNC\n    const StartIndices& startIndices() const { return m_indices; }\n    EIGEN_DEVICE_FUNC\n    const Sizes& sizes() const { return m_sizes; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(TensorSlicingOp)\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const StartIndices m_indices;\n    const Sizes m_sizes;\n};\n\n\n// Fixme: figure out the exact threshold\nnamespace {\ntemplate <typename Index, typename Device, bool BlockAccess> struct MemcpyTriggerForSlicing {\n  EIGEN_DEVICE_FUNC MemcpyTriggerForSlicing(const Device& device) : threshold_(2 * device.numThreads()) { }\n  EIGEN_DEVICE_FUNC bool operator ()(Index total, Index contiguous) const {\n    const bool prefer_block_evaluation = BlockAccess && total > 32*1024;\n    return !prefer_block_evaluation && contiguous > threshold_;\n  }\n\n private:\n  Index threshold_;\n};\n\n// It is very expensive to start the memcpy kernel on GPU: we therefore only\n// use it for large copies.\n#ifdef EIGEN_USE_GPU\ntemplate <typename Index, bool BlockAccess> struct MemcpyTriggerForSlicing<Index, GpuDevice, BlockAccess>  {\n  EIGEN_DEVICE_FUNC MemcpyTriggerForSlicing(const GpuDevice&) { }\n  EIGEN_DEVICE_FUNC bool operator ()(Index, Index contiguous) const { return contiguous > 4*1024*1024; }\n};\n#endif\n\n// It is very expensive to start the memcpy kernel on GPU: we therefore only\n// use it for large copies.\n#ifdef EIGEN_USE_SYCL\ntemplate <typename Index, bool BlockAccess> struct MemcpyTriggerForSlicing<Index, Eigen::SyclDevice, BlockAccess>  {\n  EIGEN_DEVICE_FUNC MemcpyTriggerForSlicing(const SyclDevice&) { }\n  EIGEN_DEVICE_FUNC bool operator ()(Index, Index contiguous) const { return contiguous > 4*1024*1024; }\n};\n#endif\n\n}\n\n// Eval as rvalue\ntemplate<typename StartIndices, typename Sizes, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorSlicingOp<StartIndices, Sizes, ArgType>, Device>\n{\n  typedef TensorSlicingOp<StartIndices, Sizes, ArgType> XprType;\n  static const int NumDims = internal::array_size<Sizes>::value;\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef Sizes Dimensions;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef StorageMemory<typename internal::remove_const<CoeffReturnType>::type, Device> ConstCastStorage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    // Alignment can't be guaranteed at compile time since it depends on the\n    // slice offsets and sizes.\n    IsAligned         = false,\n    PacketAccess      = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess       = TensorEvaluator<ArgType, Device>::BlockAccess &&\n                        // FIXME: Temporary workaround for bug in slicing of bool tensors.\n                        !internal::is_same<typename internal::remove_const<Scalar>::type, bool>::value,\n    PreferBlockAccess = true,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess       = false,\n    RawAccess         = false\n  };\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  // Tensor slicing does not change the block type.\n  typedef typename TensorEvaluator<const ArgType, Device>::TensorBlock\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device), m_device(device), m_dimensions(op.sizes()), m_offsets(op.startIndices())\n  {\n    m_is_identity = true;\n    for (int i = 0; i < internal::array_size<Dimensions>::value; ++i) {\n      eigen_assert(m_impl.dimensions()[i] >=\n                   op.sizes()[i] + op.startIndices()[i]);\n      if (m_impl.dimensions()[i] != op.sizes()[i] ||\n          op.startIndices()[i] != 0) {\n        m_is_identity = false;\n      }\n    }\n\n    // No strides for scalars.\n    if (NumDims == 0) return;\n\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n    const Sizes& output_dims = op.sizes();\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_inputStrides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1];\n      }\n\n     // Don't initialize m_fastOutputStrides[0] since it won't ever be accessed.\n      m_outputStrides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_outputStrides[i] = m_outputStrides[i-1] * output_dims[i-1];\n        m_fastOutputStrides[i] = internal::TensorIntDivisor<Index>(m_outputStrides[i] > 0 ? m_outputStrides[i] : 1);\n      }\n    } else {\n      m_inputStrides[NumDims-1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1];\n      }\n\n     // Don't initialize m_fastOutputStrides[NumDims-1] since it won't ever be accessed.\n      m_outputStrides[NumDims-1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_outputStrides[i] = m_outputStrides[i+1] * output_dims[i+1];\n        m_fastOutputStrides[i] = internal::TensorIntDivisor<Index>(m_outputStrides[i] > 0 ? m_outputStrides[i] : 1);\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    if (!NumTraits<typename internal::remove_const<Scalar>::type>::RequireInitialization\n        && data && m_impl.data()) {\n      Index contiguous_values = 1;\n      if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n        for (int i = 0; i < NumDims; ++i) {\n          contiguous_values *= dimensions()[i];\n          if (dimensions()[i] != m_impl.dimensions()[i]) {\n            break;\n          }\n        }\n      } else {\n        for (int i = NumDims-1; i >= 0; --i) {\n          contiguous_values *= dimensions()[i];\n          if (dimensions()[i] != m_impl.dimensions()[i]) {\n            break;\n          }\n        }\n      }\n      // Use memcpy if it's going to be faster than using the regular evaluation.\n      const MemcpyTriggerForSlicing<Index, Device, BlockAccess> trigger(m_device);\n      if (trigger(internal::array_prod(dimensions()), contiguous_values)) {\n        EvaluatorPointerType src = (EvaluatorPointerType)m_impl.data();\n        for (Index i = 0; i < internal::array_prod(dimensions()); i += contiguous_values) {\n          Index offset = srcCoeff(i);\n          m_device.memcpy((void*)(m_device.get(data + i)), m_device.get(src+offset), contiguous_values * sizeof(Scalar));\n        }\n        return false;\n      }\n    }\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType /*data*/, EvalSubExprsCallback done) {\n    m_impl.evalSubExprsIfNeededAsync(nullptr, [done](bool) { done(true); });\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    if (m_is_identity) {\n      return m_impl.coeff(index);\n    } else {\n      return m_impl.coeff(srcCoeff(index));\n    }\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    const int packetSize = PacketType<CoeffReturnType, Device>::size;\n    EIGEN_STATIC_ASSERT((packetSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+packetSize-1 < internal::array_prod(dimensions()));\n\n    if (m_is_identity) {\n      return m_impl.template packet<LoadMode>(index);\n    }\n\n    Index inputIndices[] = {0, 0};\n    Index indices[] = {index, index + packetSize - 1};\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx0 = indices[0] / m_fastOutputStrides[i];\n        const Index idx1 = indices[1] / m_fastOutputStrides[i];\n        inputIndices[0] += (idx0 + m_offsets[i]) * m_inputStrides[i];\n        inputIndices[1] += (idx1 + m_offsets[i]) * m_inputStrides[i];\n        indices[0] -= idx0 * m_outputStrides[i];\n        indices[1] -= idx1 * m_outputStrides[i];\n      }\n      inputIndices[0] += (indices[0] + m_offsets[0]);\n      inputIndices[1] += (indices[1] + m_offsets[0]);\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx0 = indices[0] / m_fastOutputStrides[i];\n        const Index idx1 = indices[1] / m_fastOutputStrides[i];\n        inputIndices[0] += (idx0 + m_offsets[i]) * m_inputStrides[i];\n        inputIndices[1] += (idx1 + m_offsets[i]) * m_inputStrides[i];\n        indices[0] -= idx0 * m_outputStrides[i];\n        indices[1] -= idx1 * m_outputStrides[i];\n      }\n      inputIndices[0] += (indices[0] + m_offsets[NumDims-1]);\n      inputIndices[1] += (indices[1] + m_offsets[NumDims-1]);\n    }\n    if (inputIndices[1] - inputIndices[0] == packetSize - 1) {\n      PacketReturnType rslt = m_impl.template packet<Unaligned>(inputIndices[0]);\n      return rslt;\n    }\n    else {\n      EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[packetSize];\n      values[0] = m_impl.coeff(inputIndices[0]);\n      values[packetSize-1] = m_impl.coeff(inputIndices[1]);\n      EIGEN_UNROLL_LOOP\n      for (int i = 1; i < packetSize-1; ++i) {\n        values[i] = coeff(index+i);\n      }\n      PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n      return rslt;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    return m_impl.costPerCoeff(vectorized) + TensorOpCost(0, 0, m_is_identity ? 1 : NumDims);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    const size_t target_size = m_device.lastLevelCacheSize();\n    return internal::TensorBlockResourceRequirements::merge(\n        internal::TensorBlockResourceRequirements::skewed<Scalar>(target_size),\n        m_impl.getResourceRequirements());\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    TensorBlockDesc arg_desc = desc.WithOffset(srcCoeff(desc.offset()));\n    TensorBlock block = m_impl.block(arg_desc, scratch);\n    if (!arg_desc.HasDestinationBuffer()) desc.DropDestinationBuffer();\n    return block;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Storage::Type data() const {\n    typename Storage::Type result = constCast(m_impl.data());\n    if (result) {\n      Index offset = 0;\n      if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n        for (int i = 0; i < NumDims; ++i) {\n          if (m_dimensions[i] != m_impl.dimensions()[i]) {\n            offset += m_offsets[i] * m_inputStrides[i];\n            for (int j = i+1; j < NumDims; ++j) {\n              if (m_dimensions[j] > 1) {\n                return NULL;\n              }\n              offset += m_offsets[j] * m_inputStrides[j];\n            }\n            break;\n          }\n        }\n      } else {\n        for (int i = NumDims - 1; i >= 0; --i) {\n          if (m_dimensions[i] != m_impl.dimensions()[i]) {\n            offset += m_offsets[i] * m_inputStrides[i];\n            for (int j = i-1; j >= 0; --j) {\n              if (m_dimensions[j] > 1) {\n                return NULL;\n              }\n              offset += m_offsets[j] * m_inputStrides[j];\n            }\n            break;\n          }\n        }\n      }\n      return result + offset;\n    }\n    return NULL;\n  }\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n\n protected:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index srcCoeff(Index index) const\n  {\n    Index inputIndex = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx = index / m_fastOutputStrides[i];\n        inputIndex += (idx + m_offsets[i]) * m_inputStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      inputIndex += (index + m_offsets[0]);\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx = index / m_fastOutputStrides[i];\n        inputIndex += (idx + m_offsets[i]) * m_inputStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      inputIndex += (index + m_offsets[NumDims-1]);\n    }\n    return inputIndex;\n  }\n\n  array<Index, NumDims> m_outputStrides;\n  array<internal::TensorIntDivisor<Index>, NumDims> m_fastOutputStrides;\n  array<Index, NumDims> m_inputStrides;\n  TensorEvaluator<ArgType, Device> m_impl;\n  const Device EIGEN_DEVICE_REF m_device;\n  Dimensions m_dimensions;\n  bool m_is_identity;\n  const StartIndices m_offsets;\n};\n\n\n// Eval as lvalue\ntemplate<typename StartIndices, typename Sizes, typename ArgType, typename Device>\nstruct TensorEvaluator<TensorSlicingOp<StartIndices, Sizes, ArgType>, Device>\n  : public TensorEvaluator<const TensorSlicingOp<StartIndices, Sizes, ArgType>, Device>\n{\n  typedef TensorEvaluator<const TensorSlicingOp<StartIndices, Sizes, ArgType>, Device> Base;\n  typedef TensorSlicingOp<StartIndices, Sizes, ArgType> XprType;\n  static const int NumDims = internal::array_size<Sizes>::value;\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef Sizes Dimensions;\n\n  enum {\n    IsAligned         = false,\n    PacketAccess      = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess       = TensorEvaluator<ArgType, Device>::BlockAccess,\n    PreferBlockAccess = true,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess       = false,\n    RawAccess         = (NumDims == 1) & TensorEvaluator<ArgType, Device>::RawAccess\n  };\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n    : Base(op, device)\n    { }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index)\n  {\n    if (this->m_is_identity) {\n      return this->m_impl.coeffRef(index);\n    } else {\n      return this->m_impl.coeffRef(this->srcCoeff(index));\n    }\n  }\n\n  template <int StoreMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void writePacket(Index index, const PacketReturnType& x)\n  {\n    if (this->m_is_identity) {\n      this->m_impl.template writePacket<StoreMode>(index, x);\n      return;\n    }\n\n    const int packetSize = PacketType<CoeffReturnType, Device>::size;\n    Index inputIndices[] = {0, 0};\n    Index indices[] = {index, index + packetSize - 1};\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx0 = indices[0] / this->m_fastOutputStrides[i];\n        const Index idx1 = indices[1] / this->m_fastOutputStrides[i];\n        inputIndices[0] += (idx0 + this->m_offsets[i]) * this->m_inputStrides[i];\n        inputIndices[1] += (idx1 + this->m_offsets[i]) * this->m_inputStrides[i];\n        indices[0] -= idx0 * this->m_outputStrides[i];\n        indices[1] -= idx1 * this->m_outputStrides[i];\n      }\n      inputIndices[0] += (indices[0] + this->m_offsets[0]);\n      inputIndices[1] += (indices[1] + this->m_offsets[0]);\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx0 = indices[0] / this->m_fastOutputStrides[i];\n        const Index idx1 = indices[1] / this->m_fastOutputStrides[i];\n        inputIndices[0] += (idx0 + this->m_offsets[i]) * this->m_inputStrides[i];\n        inputIndices[1] += (idx1 + this->m_offsets[i]) * this->m_inputStrides[i];\n        indices[0] -= idx0 * this->m_outputStrides[i];\n        indices[1] -= idx1 * this->m_outputStrides[i];\n      }\n      inputIndices[0] += (indices[0] + this->m_offsets[NumDims-1]);\n      inputIndices[1] += (indices[1] + this->m_offsets[NumDims-1]);\n    }\n    if (inputIndices[1] - inputIndices[0] == packetSize - 1) {\n      this->m_impl.template writePacket<StoreMode>(inputIndices[0], x);\n    }\n    else {\n      EIGEN_ALIGN_MAX CoeffReturnType values[packetSize];\n      internal::pstore<CoeffReturnType, PacketReturnType>(values, x);\n      this->m_impl.coeffRef(inputIndices[0]) = values[0];\n      this->m_impl.coeffRef(inputIndices[1]) = values[packetSize-1];\n      EIGEN_UNROLL_LOOP\n      for (int i = 1; i < packetSize-1; ++i) {\n        this->coeffRef(index+i) = values[i];\n      }\n    }\n  }\n\n  template<typename TensorBlock>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void writeBlock(\n      const TensorBlockDesc& desc, const TensorBlock& block) {\n    TensorBlockDesc arg_desc = desc.WithOffset(this->srcCoeff(desc.offset()));\n    this->m_impl.writeBlock(arg_desc, block);\n  }\n};\n\nnamespace internal {\ntemplate<typename StartIndices, typename StopIndices, typename Strides, typename XprType>\nstruct traits<TensorStridingSlicingOp<StartIndices, StopIndices, Strides, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = array_size<StartIndices>::value;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename StartIndices, typename StopIndices, typename Strides, typename XprType>\nstruct eval<TensorStridingSlicingOp<StartIndices, StopIndices, Strides, XprType>, Eigen::Dense>\n{\n  typedef const TensorStridingSlicingOp<StartIndices, StopIndices, Strides, XprType>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename StartIndices, typename StopIndices, typename Strides, typename XprType>\nstruct nested<TensorStridingSlicingOp<StartIndices, StopIndices, Strides, XprType>, 1, typename eval<TensorStridingSlicingOp<StartIndices, StopIndices, Strides, XprType> >::type>\n{\n  typedef TensorStridingSlicingOp<StartIndices, StopIndices, Strides, XprType> type;\n};\n\n}  // end namespace internal\n\n\ntemplate<typename StartIndices, typename StopIndices, typename Strides, typename XprType>\nclass TensorStridingSlicingOp : public TensorBase<TensorStridingSlicingOp<StartIndices, StopIndices, Strides, XprType> >\n{\n  public:\n  typedef TensorBase<TensorStridingSlicingOp<StartIndices, StopIndices, Strides, XprType> > Base;\n  typedef typename internal::traits<TensorStridingSlicingOp>::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename internal::nested<TensorStridingSlicingOp>::type Nested;\n  typedef typename internal::traits<TensorStridingSlicingOp>::StorageKind StorageKind;\n  typedef typename internal::traits<TensorStridingSlicingOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorStridingSlicingOp(\n    const XprType& expr, const StartIndices& startIndices,\n    const StopIndices& stopIndices, const Strides& strides)\n      : m_xpr(expr), m_startIndices(startIndices), m_stopIndices(stopIndices),\n        m_strides(strides) {}\n\n    EIGEN_DEVICE_FUNC\n    const StartIndices& startIndices() const { return m_startIndices; }\n    EIGEN_DEVICE_FUNC\n    const StartIndices& stopIndices() const { return m_stopIndices; }\n    EIGEN_DEVICE_FUNC\n    const StartIndices& strides() const { return m_strides; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(TensorStridingSlicingOp)\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const StartIndices m_startIndices;\n    const StopIndices m_stopIndices;\n    const Strides m_strides;\n};\n\n// Eval as rvalue\ntemplate<typename StartIndices, typename StopIndices, typename Strides, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorStridingSlicingOp<StartIndices, StopIndices, Strides, ArgType>, Device>\n{\n  typedef TensorStridingSlicingOp<StartIndices, StopIndices, Strides, ArgType> XprType;\n  static const int NumDims = internal::array_size<Strides>::value;\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n  typedef Strides Dimensions;\n\n  enum {\n    // Alignment can't be guaranteed at compile time since it depends on the\n    // slice offsets and sizes.\n    IsAligned = false,\n    PacketAccess = false,\n    BlockAccess = false,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device),\n        m_device(device),\n        m_strides(op.strides())\n  {\n    // Handle degenerate intervals by gracefully clamping and allowing m_dimensions to be zero\n    DSizes<Index, NumDims> startIndicesClamped, stopIndicesClamped;\n    for (ptrdiff_t i = 0; i < internal::array_size<Dimensions>::value; ++i) {\n      eigen_assert(m_strides[i] != 0 && \"0 stride is invalid\");\n      if (m_strides[i] > 0) {\n        startIndicesClamped[i] =\n            clamp(op.startIndices()[i], 0, m_impl.dimensions()[i]);\n        stopIndicesClamped[i] =\n            clamp(op.stopIndices()[i], 0, m_impl.dimensions()[i]);\n      } else {\n        /* implies m_strides[i] < 0 by assert */\n        startIndicesClamped[i] =\n            clamp(op.startIndices()[i], -1, m_impl.dimensions()[i] - 1);\n        stopIndicesClamped[i] =\n            clamp(op.stopIndices()[i], -1, m_impl.dimensions()[i] - 1);\n      }\n      m_startIndices[i] = startIndicesClamped[i];\n    }\n\n    typedef typename TensorEvaluator<ArgType, Device>::Dimensions InputDimensions;\n    const InputDimensions& input_dims = m_impl.dimensions();\n\n    // compute output tensor shape\n    m_is_identity = true;\n    for (int i = 0; i < NumDims; i++) {\n      Index interval = stopIndicesClamped[i] - startIndicesClamped[i];\n      if (interval == 0 || ((interval < 0) != (m_strides[i] < 0))) {\n        m_dimensions[i] = 0;\n      } else {\n        m_dimensions[i] =\n            (interval / m_strides[i]) + (interval % m_strides[i] != 0 ? 1 : 0);\n        eigen_assert(m_dimensions[i] >= 0);\n      }\n      if (m_strides[i] != 1 || interval != m_impl.dimensions()[i]) {\n        m_is_identity = false;\n      }\n    }\n\n    Strides output_dims = m_dimensions;\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_inputStrides[0] = m_strides[0];\n      m_offsets[0] = startIndicesClamped[0];\n      Index previousDimProduct = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        previousDimProduct *= input_dims[i-1];\n        m_inputStrides[i] = previousDimProduct * m_strides[i];\n        m_offsets[i] = startIndicesClamped[i] * previousDimProduct;\n      }\n\n      // Don't initialize m_fastOutputStrides[0] since it won't ever be accessed.\n      m_outputStrides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_outputStrides[i] = m_outputStrides[i-1] * output_dims[i-1];\n        m_fastOutputStrides[i] = internal::TensorIntDivisor<Index>(m_outputStrides[i] > 0 ? m_outputStrides[i] : 1);\n      }\n    } else {\n      m_inputStrides[NumDims-1] = m_strides[NumDims-1];\n      m_offsets[NumDims-1] = startIndicesClamped[NumDims-1];\n      Index previousDimProduct = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        previousDimProduct *= input_dims[i+1];\n        m_inputStrides[i] = previousDimProduct * m_strides[i];\n        m_offsets[i] = startIndicesClamped[i] * previousDimProduct;\n      }\n\n      m_outputStrides[NumDims-1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_outputStrides[i] = m_outputStrides[i+1] * output_dims[i+1];\n        m_fastOutputStrides[i] = internal::TensorIntDivisor<Index>(m_outputStrides[i] > 0 ? m_outputStrides[i] : 1);\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    if (m_is_identity) {\n      return m_impl.coeff(index);\n    } else {\n      return m_impl.coeff(srcCoeff(index));\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    return m_impl.costPerCoeff(vectorized) + TensorOpCost(0, 0, m_is_identity ? 1 : NumDims);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Storage::Type data() const {\n    return NULL;\n  }\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n protected:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index srcCoeff(Index index) const\n  {\n    Index inputIndex = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i >= 0; --i) {\n        const Index idx = index / m_fastOutputStrides[i];\n        inputIndex += idx * m_inputStrides[i] + m_offsets[i];\n        index -= idx * m_outputStrides[i];\n      }\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims; ++i) {\n        const Index idx = index / m_fastOutputStrides[i];\n        inputIndex += idx * m_inputStrides[i] + m_offsets[i];\n        index -= idx * m_outputStrides[i];\n      }\n    }\n    return inputIndex;\n  }\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index clamp(Index value, Index min, Index max) {\n#ifndef SYCL_DEVICE_ONLY\n    return numext::maxi(min, numext::mini(max,value));\n#else\n    return cl::sycl::clamp(value, min, max);\n#endif\n  }\n\n  array<Index, NumDims> m_outputStrides;\n  array<internal::TensorIntDivisor<Index>, NumDims> m_fastOutputStrides;\n  array<Index, NumDims> m_inputStrides;\n  bool m_is_identity;\n  TensorEvaluator<ArgType, Device> m_impl;\n  const Device EIGEN_DEVICE_REF m_device;\n  DSizes<Index, NumDims> m_startIndices; // clamped startIndices\n  DSizes<Index, NumDims> m_dimensions;\n  DSizes<Index, NumDims> m_offsets; // offset in a flattened shape\n  const Strides m_strides;\n};\n\n// Eval as lvalue\ntemplate<typename StartIndices, typename StopIndices, typename Strides, typename ArgType, typename Device>\nstruct TensorEvaluator<TensorStridingSlicingOp<StartIndices, StopIndices, Strides, ArgType>, Device>\n  : public TensorEvaluator<const TensorStridingSlicingOp<StartIndices, StopIndices, Strides, ArgType>, Device>\n{\n  typedef TensorEvaluator<const TensorStridingSlicingOp<StartIndices, StopIndices, Strides, ArgType>, Device> Base;\n  typedef TensorStridingSlicingOp<StartIndices, StopIndices, Strides, ArgType> XprType;\n  static const int NumDims = internal::array_size<Strides>::value;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = false,\n    BlockAccess = false,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = TensorEvaluator<ArgType, Device>::CoordAccess,\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n    : Base(op, device)\n    { }\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef Strides Dimensions;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index)\n  {\n    if (this->m_is_identity) {\n      return this->m_impl.coeffRef(index);\n    } else {\n      return this->m_impl.coeffRef(this->srcCoeff(index));\n    }\n  }\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_MORPHING_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorPadding.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_PADDING_H\n#define EIGEN_CXX11_TENSOR_TENSOR_PADDING_H\n\nnamespace Eigen {\n\n/** \\class TensorPadding\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor padding class.\n  * At the moment only padding with a constant value is supported.\n  *\n  */\nnamespace internal {\ntemplate<typename PaddingDimensions, typename XprType>\nstruct traits<TensorPaddingOp<PaddingDimensions, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename PaddingDimensions, typename XprType>\nstruct eval<TensorPaddingOp<PaddingDimensions, XprType>, Eigen::Dense>\n{\n  typedef const TensorPaddingOp<PaddingDimensions, XprType>& type;\n};\n\ntemplate<typename PaddingDimensions, typename XprType>\nstruct nested<TensorPaddingOp<PaddingDimensions, XprType>, 1, typename eval<TensorPaddingOp<PaddingDimensions, XprType> >::type>\n{\n  typedef TensorPaddingOp<PaddingDimensions, XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename PaddingDimensions, typename XprType>\nclass TensorPaddingOp : public TensorBase<TensorPaddingOp<PaddingDimensions, XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorPaddingOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorPaddingOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorPaddingOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorPaddingOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorPaddingOp(const XprType& expr, const PaddingDimensions& padding_dims, const Scalar padding_value)\n      : m_xpr(expr), m_padding_dims(padding_dims), m_padding_value(padding_value) {}\n\n    EIGEN_DEVICE_FUNC\n    const PaddingDimensions& padding() const { return m_padding_dims; }\n    EIGEN_DEVICE_FUNC\n    Scalar padding_value() const { return m_padding_value; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const PaddingDimensions m_padding_dims;\n    const Scalar m_padding_value;\n};\n\n\n// Eval as rvalue\ntemplate<typename PaddingDimensions, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorPaddingOp<PaddingDimensions, ArgType>, Device>\n{\n  typedef TensorPaddingOp<PaddingDimensions, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<PaddingDimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned         = true,\n    PacketAccess      = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess       = TensorEvaluator<ArgType, Device>::RawAccess,\n    PreferBlockAccess = true,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess       = true,\n    RawAccess         = false\n  };\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename internal::TensorMaterializedBlock<ScalarNoConst, NumDims,\n                                                     Layout, Index>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device), m_padding(op.padding()), m_paddingValue(op.padding_value()), m_device(device)\n  {\n    // The padding op doesn't change the rank of the tensor. Directly padding a scalar would lead\n    // to a vector, which doesn't make sense. Instead one should reshape the scalar into a vector\n    // of 1 element first and then pad.\n    EIGEN_STATIC_ASSERT((NumDims > 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    // Compute dimensions\n    m_dimensions = m_impl.dimensions();\n    for (int i = 0; i < NumDims; ++i) {\n      m_dimensions[i] += m_padding[i].first + m_padding[i].second;\n    }\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_inputStrides[0] = 1;\n      m_outputStrides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1];\n        m_outputStrides[i] = m_outputStrides[i-1] * m_dimensions[i-1];\n      }\n      m_outputStrides[NumDims] = m_outputStrides[NumDims-1] * m_dimensions[NumDims-1];\n    } else {\n      m_inputStrides[NumDims - 1] = 1;\n      m_outputStrides[NumDims] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1];\n        m_outputStrides[i+1] = m_outputStrides[i+2] * m_dimensions[i+1];\n      }\n      m_outputStrides[0] = m_outputStrides[1] * m_dimensions[0];\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    m_impl.evalSubExprsIfNeededAsync(nullptr, [done](bool) { done(true); });\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    eigen_assert(index < dimensions().TotalSize());\n    Index inputIndex = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx = index / m_outputStrides[i];\n        if (isPaddingAtIndexForDim(idx, i)) {\n          return m_paddingValue;\n        }\n        inputIndex += (idx - m_padding[i].first) * m_inputStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      if (isPaddingAtIndexForDim(index, 0)) {\n        return m_paddingValue;\n      }\n      inputIndex += (index - m_padding[0].first);\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx = index / m_outputStrides[i+1];\n        if (isPaddingAtIndexForDim(idx, i)) {\n          return m_paddingValue;\n        }\n        inputIndex += (idx - m_padding[i].first) * m_inputStrides[i];\n        index -= idx * m_outputStrides[i+1];\n      }\n      if (isPaddingAtIndexForDim(index, NumDims-1)) {\n        return m_paddingValue;\n      }\n      inputIndex += (index - m_padding[NumDims-1].first);\n    }\n    return m_impl.coeff(inputIndex);\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      return packetColMajor(index);\n    }\n    return packetRowMajor(index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    TensorOpCost cost = m_impl.costPerCoeff(vectorized);\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims; ++i)\n        updateCostPerDimension(cost, i, i == 0);\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i >= 0; --i)\n        updateCostPerDimension(cost, i, i == NumDims - 1);\n    }\n    return cost;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    const size_t target_size = m_device.lastLevelCacheSize();\n    return internal::TensorBlockResourceRequirements::merge(\n        internal::TensorBlockResourceRequirements::skewed<Scalar>(target_size),\n        m_impl.getResourceRequirements());\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    // If one of the dimensions is zero, return empty block view.\n    if (desc.size() == 0) {\n      return TensorBlock(internal::TensorBlockKind::kView, NULL,\n                           desc.dimensions());\n    }\n\n    static const bool IsColMajor = Layout == static_cast<int>(ColMajor);\n    const int inner_dim_idx = IsColMajor ? 0 : NumDims - 1;\n\n    Index offset = desc.offset();\n\n    // Compute offsets in the output tensor corresponding to the desc.offset().\n    DSizes<Index, NumDims> output_offsets;\n    for (int i = NumDims - 1; i > 0; --i) {\n      const int dim = IsColMajor ? i : NumDims - i - 1;\n      const int stride_dim = IsColMajor ? dim : dim + 1;\n      output_offsets[dim] = offset / m_outputStrides[stride_dim];\n      offset -= output_offsets[dim] * m_outputStrides[stride_dim];\n    }\n    output_offsets[inner_dim_idx] = offset;\n\n    // Offsets in the input corresponding to output offsets.\n    DSizes<Index, NumDims> input_offsets = output_offsets;\n    for (int i = 0; i < NumDims; ++i) {\n      const int dim = IsColMajor ? i : NumDims - i - 1;\n      input_offsets[dim] = input_offsets[dim] - m_padding[dim].first;\n    }\n\n    // Compute offset in the input buffer (at this point it might be illegal and\n    // point outside of the input buffer, because we don't check for negative\n    // offsets, it will be autocorrected in the block iteration loop below).\n    Index input_offset = 0;\n    for (int i = 0; i < NumDims; ++i) {\n      const int dim = IsColMajor ? i : NumDims - i - 1;\n      input_offset += input_offsets[dim] * m_inputStrides[dim];\n    }\n\n    // Destination buffer and scratch buffer both indexed from 0 and have the\n    // same dimensions as the requested block (for destination buffer this\n    // property is guaranteed by `desc.destination()`).\n    Index output_offset = 0;\n    const DSizes<Index, NumDims> output_strides =\n        internal::strides<Layout>(desc.dimensions());\n\n    // NOTE(ezhulenev): We initialize bock iteration state for `NumDims - 1`\n    // dimensions, skipping innermost dimension. In theory it should be possible\n    // to squeeze matching innermost dimensions, however in practice that did\n    // not show any improvements in benchmarks. Also in practice first outer\n    // dimension usually has padding, and will prevent squeezing.\n\n    // Initialize output block iterator state. Dimension in this array are\n    // always in inner_most -> outer_most order (col major layout).\n    array<BlockIteratorState, NumDims - 1> it;\n    for (int i = 0; i < NumDims - 1; ++i) {\n      const int dim = IsColMajor ? i + 1 : NumDims - i - 2;\n      it[i].count = 0;\n      it[i].size = desc.dimension(dim);\n\n      it[i].input_stride = m_inputStrides[dim];\n      it[i].input_span = it[i].input_stride * (it[i].size - 1);\n\n      it[i].output_stride = output_strides[dim];\n      it[i].output_span = it[i].output_stride * (it[i].size - 1);\n    }\n\n    const Index input_inner_dim_size =\n        static_cast<Index>(m_impl.dimensions()[inner_dim_idx]);\n\n    // Total output size.\n    const Index output_size = desc.size();\n\n    // We will fill inner dimension of this size in the output. It might be\n    // larger than the inner dimension in the input, so we might have to pad\n    // before/after we copy values from the input inner dimension.\n    const Index output_inner_dim_size = desc.dimension(inner_dim_idx);\n\n    // How many values to fill with padding BEFORE reading from the input inner\n    // dimension.\n    const Index output_inner_pad_before_size =\n        input_offsets[inner_dim_idx] < 0\n            ? numext::mini(numext::abs(input_offsets[inner_dim_idx]),\n                           output_inner_dim_size)\n            : 0;\n\n    // How many values we can actually copy from the input inner dimension.\n    const Index output_inner_copy_size = numext::mini(\n        // Want to copy from input.\n        (output_inner_dim_size - output_inner_pad_before_size),\n        // Can copy from input.\n        numext::maxi(input_inner_dim_size - (input_offsets[inner_dim_idx] +\n                                             output_inner_pad_before_size),\n                     Index(0)));\n\n    eigen_assert(output_inner_copy_size >= 0);\n\n    // How many values to fill with padding AFTER reading from the input inner\n    // dimension.\n    const Index output_inner_pad_after_size =\n        (output_inner_dim_size - output_inner_copy_size -\n         output_inner_pad_before_size);\n\n    // Sanity check, sum of all sizes must be equal to the output size.\n    eigen_assert(output_inner_dim_size ==\n                 (output_inner_pad_before_size + output_inner_copy_size +\n                  output_inner_pad_after_size));\n\n    // Keep track of current coordinates and padding in the output.\n    DSizes<Index, NumDims> output_coord = output_offsets;\n    DSizes<Index, NumDims> output_padded;\n    for (int i = 0; i < NumDims; ++i) {\n      const int dim = IsColMajor ? i : NumDims - i - 1;\n      output_padded[dim] = isPaddingAtIndexForDim(output_coord[dim], dim);\n    }\n\n    typedef internal::StridedLinearBufferCopy<ScalarNoConst, Index> LinCopy;\n\n    // Prepare storage for the materialized padding result.\n    const typename TensorBlock::Storage block_storage =\n        TensorBlock::prepareStorage(desc, scratch);\n\n    // TODO(ezhulenev): Squeeze multiple non-padded inner dimensions into a\n    // single logical inner dimension.\n\n    // When possible we squeeze writes for the innermost (only if non-padded)\n    // dimension with the first padded dimension. This allows to reduce the\n    // number of calls to LinCopy and better utilize vector instructions.\n    const bool squeeze_writes =\n        NumDims > 1 &&\n        // inner dimension is not padded\n        (input_inner_dim_size == m_dimensions[inner_dim_idx]) &&\n        // and equal to the block inner dimension\n        (input_inner_dim_size == output_inner_dim_size);\n\n    const int squeeze_dim = IsColMajor ? inner_dim_idx + 1 : inner_dim_idx - 1;\n\n    // Maximum coordinate on a squeeze dimension that we can write to.\n    const Index squeeze_max_coord =\n        squeeze_writes ? numext::mini(\n                             // max non-padded element in the input\n                             static_cast<Index>(m_dimensions[squeeze_dim] -\n                                                m_padding[squeeze_dim].second),\n                             // max element in the output buffer\n                             static_cast<Index>(output_offsets[squeeze_dim] +\n                                                desc.dimension(squeeze_dim)))\n                       : static_cast<Index>(0);\n\n    // Iterate copying data from `m_impl.data()` to the output buffer.\n    for (Index size = 0; size < output_size;) {\n      // Detect if we are in the padded region (exclude innermost dimension).\n      bool is_padded = false;\n      for (int j = 1; j < NumDims; ++j) {\n        const int dim = IsColMajor ? j : NumDims - j - 1;\n        is_padded = output_padded[dim];\n        if (is_padded) break;\n      }\n\n      if (is_padded) {\n        // Fill single innermost dimension with padding value.\n        size += output_inner_dim_size;\n\n        LinCopy::template Run<LinCopy::Kind::FillLinear>(\n            typename LinCopy::Dst(output_offset, 1, block_storage.data()),\n            typename LinCopy::Src(0, 0, &m_paddingValue),\n            output_inner_dim_size);\n\n\n      } else if (squeeze_writes) {\n        // Squeeze multiple reads from innermost dimensions.\n        const Index squeeze_num = squeeze_max_coord - output_coord[squeeze_dim];\n        size += output_inner_dim_size * squeeze_num;\n\n        // Copy `squeeze_num` inner dimensions from input to output.\n        LinCopy::template Run<LinCopy::Kind::Linear>(\n            typename LinCopy::Dst(output_offset, 1, block_storage.data()),\n            typename LinCopy::Src(input_offset, 1, m_impl.data()),\n            output_inner_dim_size * squeeze_num);\n\n        // Update iteration state for only `squeeze_num - 1` processed inner\n        // dimensions, because we have another iteration state update at the end\n        // of the loop that will update iteration state for the last inner\n        // processed dimension.\n        it[0].count += (squeeze_num - 1);\n        input_offset += it[0].input_stride * (squeeze_num - 1);\n        output_offset += it[0].output_stride * (squeeze_num - 1);\n        output_coord[squeeze_dim] += (squeeze_num - 1);\n\n      } else {\n        // Single read from innermost dimension.\n        size += output_inner_dim_size;\n\n        {  // Fill with padding before copying from input inner dimension.\n          const Index out = output_offset;\n\n          LinCopy::template Run<LinCopy::Kind::FillLinear>(\n              typename LinCopy::Dst(out, 1, block_storage.data()),\n              typename LinCopy::Src(0, 0, &m_paddingValue),\n              output_inner_pad_before_size);\n        }\n\n        {  // Copy data from input inner dimension.\n          const Index out = output_offset + output_inner_pad_before_size;\n          const Index in = input_offset + output_inner_pad_before_size;\n\n          eigen_assert(output_inner_copy_size == 0 || m_impl.data() != NULL);\n\n          LinCopy::template Run<LinCopy::Kind::Linear>(\n              typename LinCopy::Dst(out, 1, block_storage.data()),\n              typename LinCopy::Src(in, 1, m_impl.data()),\n              output_inner_copy_size);\n        }\n\n        {  // Fill with padding after copying from input inner dimension.\n          const Index out = output_offset + output_inner_pad_before_size +\n                            output_inner_copy_size;\n\n          LinCopy::template Run<LinCopy::Kind::FillLinear>(\n              typename LinCopy::Dst(out, 1, block_storage.data()),\n              typename LinCopy::Src(0, 0, &m_paddingValue),\n              output_inner_pad_after_size);\n        }\n      }\n\n      for (int j = 0; j < NumDims - 1; ++j) {\n        const int dim = IsColMajor ? j + 1 : NumDims - j - 2;\n\n        if (++it[j].count < it[j].size) {\n          input_offset += it[j].input_stride;\n          output_offset += it[j].output_stride;\n          output_coord[dim] += 1;\n          output_padded[dim] = isPaddingAtIndexForDim(output_coord[dim], dim);\n          break;\n        }\n        it[j].count = 0;\n        input_offset -= it[j].input_span;\n        output_offset -= it[j].output_span;\n        output_coord[dim] -= it[j].size - 1;\n        output_padded[dim] = isPaddingAtIndexForDim(output_coord[dim], dim);\n      }\n    }\n\n    return block_storage.AsTensorMaterializedBlock();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EvaluatorPointerType data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n\n private:\n  struct BlockIteratorState {\n    BlockIteratorState()\n        : count(0),\n          size(0),\n          input_stride(0),\n          input_span(0),\n          output_stride(0),\n          output_span(0) {}\n\n    Index count;\n    Index size;\n    Index input_stride;\n    Index input_span;\n    Index output_stride;\n    Index output_span;\n  };\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool isPaddingAtIndexForDim(\n      Index index, int dim_index) const {\n#if defined(EIGEN_HAS_INDEX_LIST)\n    return (!internal::index_pair_first_statically_eq<PaddingDimensions>(dim_index, 0) &&\n            index < m_padding[dim_index].first) ||\n        (!internal::index_pair_second_statically_eq<PaddingDimensions>(dim_index, 0) &&\n         index >= m_dimensions[dim_index] - m_padding[dim_index].second);\n#else\n    return (index < m_padding[dim_index].first) ||\n           (index >= m_dimensions[dim_index] - m_padding[dim_index].second);\n#endif\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool isLeftPaddingCompileTimeZero(\n      int dim_index) const {\n#if defined(EIGEN_HAS_INDEX_LIST)\n    return internal::index_pair_first_statically_eq<PaddingDimensions>(dim_index, 0);\n#else\n    EIGEN_UNUSED_VARIABLE(dim_index);\n    return false;\n#endif\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool isRightPaddingCompileTimeZero(\n      int dim_index) const {\n#if defined(EIGEN_HAS_INDEX_LIST)\n    return internal::index_pair_second_statically_eq<PaddingDimensions>(dim_index, 0);\n#else\n    EIGEN_UNUSED_VARIABLE(dim_index);\n    return false;\n#endif\n  }\n\n\n  void updateCostPerDimension(TensorOpCost& cost, int i, bool first) const {\n    const double in = static_cast<double>(m_impl.dimensions()[i]);\n    const double out = in + m_padding[i].first + m_padding[i].second;\n    if (out == 0)\n      return;\n    const double reduction = in / out;\n    cost *= reduction;\n    if (first) {\n      cost += TensorOpCost(0, 0, 2 * TensorOpCost::AddCost<Index>() +\n                    reduction * (1 * TensorOpCost::AddCost<Index>()));\n    } else {\n      cost += TensorOpCost(0, 0, 2 * TensorOpCost::AddCost<Index>() +\n                                 2 * TensorOpCost::MulCost<Index>() +\n                    reduction * (2 * TensorOpCost::MulCost<Index>() +\n                                 1 * TensorOpCost::DivCost<Index>()));\n    }\n  }\n\n protected:\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetColMajor(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    const Index initialIndex = index;\n    Index inputIndex = 0;\n    EIGEN_UNROLL_LOOP\n    for (int i = NumDims - 1; i > 0; --i) {\n      const Index firstIdx = index;\n      const Index lastIdx = index + PacketSize - 1;\n      const Index lastPaddedLeft = m_padding[i].first * m_outputStrides[i];\n      const Index firstPaddedRight = (m_dimensions[i] - m_padding[i].second) * m_outputStrides[i];\n      const Index lastPaddedRight = m_outputStrides[i+1];\n\n      if (!isLeftPaddingCompileTimeZero(i) && lastIdx < lastPaddedLeft) {\n        // all the coefficient are in the padding zone.\n        return internal::pset1<PacketReturnType>(m_paddingValue);\n      }\n      else if (!isRightPaddingCompileTimeZero(i) && firstIdx >= firstPaddedRight && lastIdx < lastPaddedRight) {\n        // all the coefficient are in the padding zone.\n        return internal::pset1<PacketReturnType>(m_paddingValue);\n      }\n      else if ((isLeftPaddingCompileTimeZero(i) && isRightPaddingCompileTimeZero(i)) || (firstIdx >= lastPaddedLeft && lastIdx < firstPaddedRight)) {\n        // all the coefficient are between the 2 padding zones.\n        const Index idx = index / m_outputStrides[i];\n        inputIndex += (idx - m_padding[i].first) * m_inputStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      else {\n        // Every other case\n        return packetWithPossibleZero(initialIndex);\n      }\n    }\n\n    const Index lastIdx = index + PacketSize - 1;\n    const Index firstIdx = index;\n    const Index lastPaddedLeft = m_padding[0].first;\n    const Index firstPaddedRight = (m_dimensions[0] - m_padding[0].second);\n    const Index lastPaddedRight = m_outputStrides[1];\n\n    if (!isLeftPaddingCompileTimeZero(0) && lastIdx < lastPaddedLeft) {\n      // all the coefficient are in the padding zone.\n      return internal::pset1<PacketReturnType>(m_paddingValue);\n    }\n    else if (!isRightPaddingCompileTimeZero(0) && firstIdx >= firstPaddedRight && lastIdx < lastPaddedRight) {\n      // all the coefficient are in the padding zone.\n      return internal::pset1<PacketReturnType>(m_paddingValue);\n    }\n    else if ((isLeftPaddingCompileTimeZero(0) && isRightPaddingCompileTimeZero(0)) || (firstIdx >= lastPaddedLeft && lastIdx < firstPaddedRight)) {\n      // all the coefficient are between the 2 padding zones.\n      inputIndex += (index - m_padding[0].first);\n      return m_impl.template packet<Unaligned>(inputIndex);\n    }\n    // Every other case\n    return packetWithPossibleZero(initialIndex);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetRowMajor(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    const Index initialIndex = index;\n    Index inputIndex = 0;\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < NumDims - 1; ++i) {\n      const Index firstIdx = index;\n      const Index lastIdx = index + PacketSize - 1;\n      const Index lastPaddedLeft = m_padding[i].first * m_outputStrides[i+1];\n      const Index firstPaddedRight = (m_dimensions[i] - m_padding[i].second) * m_outputStrides[i+1];\n      const Index lastPaddedRight = m_outputStrides[i];\n\n      if (!isLeftPaddingCompileTimeZero(i) && lastIdx < lastPaddedLeft) {\n        // all the coefficient are in the padding zone.\n        return internal::pset1<PacketReturnType>(m_paddingValue);\n      }\n      else if (!isRightPaddingCompileTimeZero(i) && firstIdx >= firstPaddedRight && lastIdx < lastPaddedRight) {\n        // all the coefficient are in the padding zone.\n        return internal::pset1<PacketReturnType>(m_paddingValue);\n      }\n      else if ((isLeftPaddingCompileTimeZero(i) && isRightPaddingCompileTimeZero(i)) || (firstIdx >= lastPaddedLeft && lastIdx < firstPaddedRight)) {\n        // all the coefficient are between the 2 padding zones.\n        const Index idx = index / m_outputStrides[i+1];\n        inputIndex += (idx - m_padding[i].first) * m_inputStrides[i];\n        index -= idx * m_outputStrides[i+1];\n      }\n      else {\n        // Every other case\n        return packetWithPossibleZero(initialIndex);\n      }\n    }\n\n    const Index lastIdx = index + PacketSize - 1;\n    const Index firstIdx = index;\n    const Index lastPaddedLeft = m_padding[NumDims-1].first;\n    const Index firstPaddedRight = (m_dimensions[NumDims-1] - m_padding[NumDims-1].second);\n    const Index lastPaddedRight = m_outputStrides[NumDims-1];\n\n    if (!isLeftPaddingCompileTimeZero(NumDims-1) && lastIdx < lastPaddedLeft) {\n      // all the coefficient are in the padding zone.\n      return internal::pset1<PacketReturnType>(m_paddingValue);\n    }\n    else if (!isRightPaddingCompileTimeZero(NumDims-1) && firstIdx >= firstPaddedRight && lastIdx < lastPaddedRight) {\n      // all the coefficient are in the padding zone.\n      return internal::pset1<PacketReturnType>(m_paddingValue);\n    }\n    else if ((isLeftPaddingCompileTimeZero(NumDims-1) && isRightPaddingCompileTimeZero(NumDims-1)) || (firstIdx >= lastPaddedLeft && lastIdx < firstPaddedRight)) {\n      // all the coefficient are between the 2 padding zones.\n      inputIndex += (index - m_padding[NumDims-1].first);\n      return m_impl.template packet<Unaligned>(inputIndex);\n    }\n    // Every other case\n    return packetWithPossibleZero(initialIndex);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetWithPossibleZero(Index index) const\n  {\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < PacketSize; ++i) {\n      values[i] = coeff(index+i);\n    }\n    PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n    return rslt;\n  }\n\n  Dimensions m_dimensions;\n  array<Index, NumDims+1> m_outputStrides;\n  array<Index, NumDims> m_inputStrides;\n  TensorEvaluator<ArgType, Device> m_impl;\n  PaddingDimensions m_padding;\n\n  Scalar m_paddingValue;\n\n  const Device EIGEN_DEVICE_REF m_device;\n};\n\n\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_PADDING_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorPatch.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_PATCH_H\n#define EIGEN_CXX11_TENSOR_TENSOR_PATCH_H\n\nnamespace Eigen {\n\n/** \\class TensorPatch\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor patch class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename PatchDim, typename XprType>\nstruct traits<TensorPatchOp<PatchDim, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions + 1;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename PatchDim, typename XprType>\nstruct eval<TensorPatchOp<PatchDim, XprType>, Eigen::Dense>\n{\n  typedef const TensorPatchOp<PatchDim, XprType>& type;\n};\n\ntemplate<typename PatchDim, typename XprType>\nstruct nested<TensorPatchOp<PatchDim, XprType>, 1, typename eval<TensorPatchOp<PatchDim, XprType> >::type>\n{\n  typedef TensorPatchOp<PatchDim, XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename PatchDim, typename XprType>\nclass TensorPatchOp : public TensorBase<TensorPatchOp<PatchDim, XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorPatchOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorPatchOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorPatchOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorPatchOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorPatchOp(const XprType& expr, const PatchDim& patch_dims)\n      : m_xpr(expr), m_patch_dims(patch_dims) {}\n\n    EIGEN_DEVICE_FUNC\n    const PatchDim& patch_dims() const { return m_patch_dims; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const PatchDim m_patch_dims;\n};\n\n\n// Eval as rvalue\ntemplate<typename PatchDim, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorPatchOp<PatchDim, ArgType>, Device>\n{\n  typedef TensorPatchOp<PatchDim, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value + 1;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n\n  enum {\n    IsAligned = false,\n    PacketAccess = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess = false,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,\n    RawAccess = false\n };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device)\n  {\n    Index num_patches = 1;\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n    const PatchDim& patch_dims = op.patch_dims();\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = 0; i < NumDims-1; ++i) {\n        m_dimensions[i] = patch_dims[i];\n        num_patches *= (input_dims[i] - patch_dims[i] + 1);\n      }\n      m_dimensions[NumDims-1] = num_patches;\n\n      m_inputStrides[0] = 1;\n      m_patchStrides[0] = 1;\n      for (int i = 1; i < NumDims-1; ++i) {\n        m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1];\n        m_patchStrides[i] = m_patchStrides[i-1] * (input_dims[i-1] - patch_dims[i-1] + 1);\n      }\n      m_outputStrides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_outputStrides[i] = m_outputStrides[i-1] * m_dimensions[i-1];\n      }\n    } else {\n      for (int i = 0; i < NumDims-1; ++i) {\n        m_dimensions[i+1] = patch_dims[i];\n        num_patches *= (input_dims[i] - patch_dims[i] + 1);\n      }\n      m_dimensions[0] = num_patches;\n\n      m_inputStrides[NumDims-2] = 1;\n      m_patchStrides[NumDims-2] = 1;\n      for (int i = NumDims-3; i >= 0; --i) {\n        m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1];\n        m_patchStrides[i] = m_patchStrides[i+1] * (input_dims[i+1] - patch_dims[i+1] + 1);\n      }\n      m_outputStrides[NumDims-1] = 1;\n      for (int i = NumDims-2; i >= 0; --i) {\n        m_outputStrides[i] = m_outputStrides[i+1] * m_dimensions[i+1];\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType /*data*/) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    Index output_stride_index = (static_cast<int>(Layout) == static_cast<int>(ColMajor)) ? NumDims - 1 : 0;\n    // Find the location of the first element of the patch.\n    Index patchIndex = index / m_outputStrides[output_stride_index];\n    // Find the offset of the element wrt the location of the first element.\n    Index patchOffset = index - patchIndex * m_outputStrides[output_stride_index];\n    Index inputIndex = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 2; i > 0; --i) {\n        const Index patchIdx = patchIndex / m_patchStrides[i];\n        patchIndex -= patchIdx * m_patchStrides[i];\n        const Index offsetIdx = patchOffset / m_outputStrides[i];\n        patchOffset -= offsetIdx * m_outputStrides[i];\n        inputIndex += (patchIdx + offsetIdx) * m_inputStrides[i];\n      }\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 2; ++i) {\n        const Index patchIdx = patchIndex / m_patchStrides[i];\n        patchIndex -= patchIdx * m_patchStrides[i];\n        const Index offsetIdx = patchOffset / m_outputStrides[i+1];\n        patchOffset -= offsetIdx * m_outputStrides[i+1];\n        inputIndex += (patchIdx + offsetIdx) * m_inputStrides[i];\n      }\n    }\n    inputIndex += (patchIndex + patchOffset);\n    return m_impl.coeff(inputIndex);\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    Index output_stride_index = (static_cast<int>(Layout) == static_cast<int>(ColMajor)) ? NumDims - 1 : 0;\n    Index indices[2] = {index, index + PacketSize - 1};\n    Index patchIndices[2] = {indices[0] / m_outputStrides[output_stride_index],\n                             indices[1] / m_outputStrides[output_stride_index]};\n    Index patchOffsets[2] = {indices[0] - patchIndices[0] * m_outputStrides[output_stride_index],\n                             indices[1] - patchIndices[1] * m_outputStrides[output_stride_index]};\n\n    Index inputIndices[2] = {0, 0};\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 2; i > 0; --i) {\n        const Index patchIdx[2] = {patchIndices[0] / m_patchStrides[i],\n                                   patchIndices[1] / m_patchStrides[i]};\n        patchIndices[0] -= patchIdx[0] * m_patchStrides[i];\n        patchIndices[1] -= patchIdx[1] * m_patchStrides[i];\n\n        const Index offsetIdx[2] = {patchOffsets[0] / m_outputStrides[i],\n                                    patchOffsets[1] / m_outputStrides[i]};\n        patchOffsets[0] -= offsetIdx[0] * m_outputStrides[i];\n        patchOffsets[1] -= offsetIdx[1] * m_outputStrides[i];\n\n        inputIndices[0] += (patchIdx[0] + offsetIdx[0]) * m_inputStrides[i];\n        inputIndices[1] += (patchIdx[1] + offsetIdx[1]) * m_inputStrides[i];\n      }\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 2; ++i) {\n        const Index patchIdx[2] = {patchIndices[0] / m_patchStrides[i],\n                                   patchIndices[1] / m_patchStrides[i]};\n        patchIndices[0] -= patchIdx[0] * m_patchStrides[i];\n        patchIndices[1] -= patchIdx[1] * m_patchStrides[i];\n\n        const Index offsetIdx[2] = {patchOffsets[0] / m_outputStrides[i+1],\n                                    patchOffsets[1] / m_outputStrides[i+1]};\n        patchOffsets[0] -= offsetIdx[0] * m_outputStrides[i+1];\n        patchOffsets[1] -= offsetIdx[1] * m_outputStrides[i+1];\n\n        inputIndices[0] += (patchIdx[0] + offsetIdx[0]) * m_inputStrides[i];\n        inputIndices[1] += (patchIdx[1] + offsetIdx[1]) * m_inputStrides[i];\n      }\n    }\n    inputIndices[0] += (patchIndices[0] + patchOffsets[0]);\n    inputIndices[1] += (patchIndices[1] + patchOffsets[1]);\n\n    if (inputIndices[1] - inputIndices[0] == PacketSize - 1) {\n      PacketReturnType rslt = m_impl.template packet<Unaligned>(inputIndices[0]);\n      return rslt;\n    }\n    else {\n      EIGEN_ALIGN_MAX CoeffReturnType values[PacketSize];\n      values[0] = m_impl.coeff(inputIndices[0]);\n      values[PacketSize-1] = m_impl.coeff(inputIndices[1]);\n      EIGEN_UNROLL_LOOP\n      for (int i = 1; i < PacketSize-1; ++i) {\n        values[i] = coeff(index+i);\n      }\n      PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n      return rslt;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    const double compute_cost = NumDims * (TensorOpCost::DivCost<Index>() +\n                                           TensorOpCost::MulCost<Index>() +\n                                           2 * TensorOpCost::AddCost<Index>());\n    return m_impl.costPerCoeff(vectorized) +\n           TensorOpCost(0, 0, compute_cost, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh); \n  }\n#endif\n\n protected:\n  Dimensions m_dimensions;\n  array<Index, NumDims> m_outputStrides;\n  array<Index, NumDims-1> m_inputStrides;\n  array<Index, NumDims-1> m_patchStrides;\n\n  TensorEvaluator<ArgType, Device> m_impl;\n\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_PATCH_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorRandom.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n// Copyright (C) 2018 Mehdi Goli <eigen@codeplay.com> Codeplay Software Ltd.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_RANDOM_H\n#define EIGEN_CXX11_TENSOR_TENSOR_RANDOM_H\n\nnamespace Eigen {\nnamespace internal {\n\nnamespace {\n\nEIGEN_DEVICE_FUNC uint64_t get_random_seed() {\n#if defined(EIGEN_GPU_COMPILE_PHASE)\n  // We don't support 3d kernels since we currently only use 1 and\n  // 2d kernels.\n  gpu_assert(threadIdx.z == 0);\n  return blockIdx.x * blockDim.x + threadIdx.x \n         + gridDim.x * blockDim.x * (blockIdx.y * blockDim.y + threadIdx.y);\n#else\n  // Rely on Eigen's random implementation.\n  return random<uint64_t>();\n#endif\n}\n\nstatic EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE unsigned PCG_XSH_RS_generator(uint64_t* state, uint64_t stream) {\n  // TODO: Unify with the implementation in the non blocking thread pool.\n  uint64_t current = *state;\n  // Update the internal state\n  *state = current * 6364136223846793005ULL + (stream << 1 | 1);\n  // Generate the random output (using the PCG-XSH-RS scheme)\n  return static_cast<unsigned>((current ^ (current >> 22)) >> (22 + (current >> 61)));\n}\n\nstatic EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE uint64_t PCG_XSH_RS_state(uint64_t seed) {\n  seed = seed ? seed : get_random_seed();\n  return seed * 6364136223846793005ULL + 0xda3e39cb94b95bdbULL;\n}\n\n}  // namespace\n\n\ntemplate <typename T> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nT RandomToTypeUniform(uint64_t* state, uint64_t stream) {\n  unsigned rnd = PCG_XSH_RS_generator(state, stream);\n  return static_cast<T>(rnd);\n}\n\n\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nEigen::half RandomToTypeUniform<Eigen::half>(uint64_t* state, uint64_t stream) {\n  // Generate 10 random bits for the mantissa, merge with exponent.\n  unsigned rnd = PCG_XSH_RS_generator(state, stream);\n  const uint16_t half_bits = static_cast<uint16_t>(rnd & 0x3ffu) | (static_cast<uint16_t>(15) << 10);\n  Eigen::half result = Eigen::numext::bit_cast<Eigen::half>(half_bits);\n  // Return the final result\n  return result - Eigen::half(1.0f);\n}\n\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nEigen::bfloat16 RandomToTypeUniform<Eigen::bfloat16>(uint64_t* state, uint64_t stream) {\n\n  // Generate 7 random bits for the mantissa, merge with exponent.\n  unsigned rnd = PCG_XSH_RS_generator(state, stream);\n  const uint16_t half_bits = static_cast<uint16_t>(rnd & 0x7fu) | (static_cast<uint16_t>(127) << 7);\n  Eigen::bfloat16 result = Eigen::numext::bit_cast<Eigen::bfloat16>(half_bits);\n  // Return the final result\n  return result - Eigen::bfloat16(1.0f);\n}\n\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat RandomToTypeUniform<float>(uint64_t* state, uint64_t stream) {\n  typedef union {\n    uint32_t raw;\n    float fp;\n  } internal;\n  internal result;\n  // Generate 23 random bits for the mantissa mantissa\n  const unsigned rnd = PCG_XSH_RS_generator(state, stream);\n  result.raw = rnd & 0x7fffffu;\n  // Set the exponent\n  result.raw |= (static_cast<uint32_t>(127) << 23);\n  // Return the final result\n  return result.fp - 1.0f;\n}\n\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble RandomToTypeUniform<double>(uint64_t* state, uint64_t stream) {\n  typedef union {\n    uint64_t raw;\n    double dp;\n  } internal;\n  internal result;\n  result.raw = 0;\n  // Generate 52 random bits for the mantissa\n  // First generate the upper 20 bits\n  unsigned rnd1 = PCG_XSH_RS_generator(state, stream) & 0xfffffu;\n  // The generate the lower 32 bits\n  unsigned rnd2 = PCG_XSH_RS_generator(state, stream);\n  result.raw = (static_cast<uint64_t>(rnd1) << 32) | rnd2;\n  // Set the exponent\n  result.raw |= (static_cast<uint64_t>(1023) << 52);\n  // Return the final result\n  return result.dp - 1.0;\n}\n\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nstd::complex<float> RandomToTypeUniform<std::complex<float> >(uint64_t* state, uint64_t stream) {\n  return std::complex<float>(RandomToTypeUniform<float>(state, stream),\n                             RandomToTypeUniform<float>(state, stream));\n}\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nstd::complex<double> RandomToTypeUniform<std::complex<double> >(uint64_t* state, uint64_t stream) {\n  return std::complex<double>(RandomToTypeUniform<double>(state, stream),\n                              RandomToTypeUniform<double>(state, stream));\n}\n\ntemplate <typename T> class UniformRandomGenerator {\n public:\n  static const bool PacketAccess = true;\n\n  // Uses the given \"seed\" if non-zero, otherwise uses a random seed.\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE UniformRandomGenerator(\n      uint64_t seed = 0) {\n    m_state = PCG_XSH_RS_state(seed);\n    #ifdef EIGEN_USE_SYCL\n    // In SYCL it is not possible to build PCG_XSH_RS_state in one step.\n    // Therefor, we need two step to initializate the m_state.\n    // IN SYCL, the constructor of the functor is s called on the CPU\n    // and we get the clock seed here from the CPU. However, This seed is\n    //the same for all the thread. As unlike CUDA, the thread.ID, BlockID, etc is not a global function.\n    // and only  available on the Operator() function (which is called on the GPU).\n    // Thus for CUDA (((CLOCK  + global_thread_id)* 6364136223846793005ULL) + 0xda3e39cb94b95bdbULL) is passed to each thread\n    // but for SYCL ((CLOCK * 6364136223846793005ULL) + 0xda3e39cb94b95bdbULL) is passed to each thread and each thread adds\n    // the  (global_thread_id* 6364136223846793005ULL) for itself only once, in order to complete the construction\n    // similar to CUDA Therefore, the thread Id injection is not available at this stage.\n    //However when the operator() is called the thread ID will be avilable. So inside the opeator,\n    // we add the thrreadID, BlockId,... (which is equivalent of i)\n    //to the seed and construct the unique m_state per thead similar to cuda.\n    m_exec_once =false;\n   #endif\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE UniformRandomGenerator(\n      const UniformRandomGenerator& other) {\n    m_state = other.m_state;\n    #ifdef EIGEN_USE_SYCL\n     m_exec_once =other.m_exec_once;\n    #endif\n  }\n\n  template<typename Index> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  T operator()(Index i) const {\n    #ifdef EIGEN_USE_SYCL\n      if(!m_exec_once) {\n      // This is the second stage of adding thread Id to the CPU clock seed and build unique seed per thread\n      // The (i * 6364136223846793005ULL) is the remaining part of the PCG_XSH_RS_state on the GPU side\n       m_state += (i * 6364136223846793005ULL);\n       m_exec_once =true;\n      }\n    #endif\n    T result = RandomToTypeUniform<T>(&m_state, i);\n    return result;\n  }\n\n  template<typename Packet, typename Index> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  Packet packetOp(Index i) const {\n    const int packetSize = internal::unpacket_traits<Packet>::size;\n    EIGEN_ALIGN_MAX T values[packetSize];\n      #ifdef EIGEN_USE_SYCL\n      if(!m_exec_once) {\n      // This is the second stage of adding thread Id to the CPU clock seed and build unique seed per thread\n       m_state += (i * 6364136223846793005ULL);\n       m_exec_once =true;\n      }\n    #endif\n    EIGEN_UNROLL_LOOP\n    for (int j = 0; j < packetSize; ++j) {\n      values[j] = RandomToTypeUniform<T>(&m_state, i);\n    }\n    return internal::pload<Packet>(values);\n  }\n\n private:\n  mutable uint64_t m_state;\n  #ifdef EIGEN_USE_SYCL\n  mutable bool m_exec_once;\n  #endif\n};\n\ntemplate <typename Scalar>\nstruct functor_traits<UniformRandomGenerator<Scalar> > {\n  enum {\n    // Rough estimate for floating point, multiplied by ceil(sizeof(T) / sizeof(float)).\n    Cost = 12 * NumTraits<Scalar>::AddCost *\n           ((sizeof(Scalar) + sizeof(float) - 1) / sizeof(float)),\n    PacketAccess = UniformRandomGenerator<Scalar>::PacketAccess\n  };\n};\n\n\n\ntemplate <typename T> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nT RandomToTypeNormal(uint64_t* state, uint64_t stream) {\n  // Use the ratio of uniform method to generate numbers following a normal\n  // distribution. See for example Numerical Recipes chapter 7.3.9 for the\n  // details.\n  T u, v, q;\n  do {\n    u = RandomToTypeUniform<T>(state, stream);\n    v = T(1.7156) * (RandomToTypeUniform<T>(state, stream) - T(0.5));\n    const T x = u - T(0.449871);\n    const T y = numext::abs(v) + T(0.386595);\n    q = x*x + y * (T(0.196)*y - T(0.25472)*x);\n  } while (q > T(0.27597) &&\n           (q > T(0.27846) || v*v > T(-4) * numext::log(u) * u*u));\n\n  return v/u;\n}\n\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nstd::complex<float> RandomToTypeNormal<std::complex<float> >(uint64_t* state, uint64_t stream) {\n  return std::complex<float>(RandomToTypeNormal<float>(state, stream),\n                             RandomToTypeNormal<float>(state, stream));\n}\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nstd::complex<double> RandomToTypeNormal<std::complex<double> >(uint64_t* state, uint64_t stream) {\n  return std::complex<double>(RandomToTypeNormal<double>(state, stream),\n                              RandomToTypeNormal<double>(state, stream));\n}\n\n\ntemplate <typename T> class NormalRandomGenerator {\n public:\n  static const bool PacketAccess = true;\n\n  // Uses the given \"seed\" if non-zero, otherwise uses a random seed.\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE NormalRandomGenerator(uint64_t seed = 0) {\n    m_state = PCG_XSH_RS_state(seed);\n    #ifdef EIGEN_USE_SYCL\n    // In SYCL it is not possible to build PCG_XSH_RS_state in one step.\n    // Therefor, we need two steps to initializate the m_state.\n    // IN SYCL, the constructor of the functor is s called on the CPU\n    // and we get the clock seed here from the CPU. However, This seed is\n    //the same for all the thread. As unlike CUDA, the thread.ID, BlockID, etc is not a global function.\n    // and only  available on the Operator() function (which is called on the GPU).\n    // Therefore, the thread Id injection is not available at this stage. However when the operator()\n    //is called the thread ID will be avilable. So inside the opeator,\n    // we add the thrreadID, BlockId,... (which is equivalent of i)\n    //to the seed and construct the unique m_state per thead similar to cuda.\n    m_exec_once =false;\n   #endif\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE NormalRandomGenerator(\n      const NormalRandomGenerator& other) {\n    m_state = other.m_state;\n#ifdef EIGEN_USE_SYCL\n    m_exec_once=other.m_exec_once;\n#endif\n  }\n\n template<typename Index> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  T operator()(Index i) const {\n    #ifdef EIGEN_USE_SYCL\n    if(!m_exec_once) {\n      // This is the second stage of adding thread Id to the CPU clock seed and build unique seed per thread\n      m_state += (i * 6364136223846793005ULL);\n      m_exec_once =true;\n    }\n    #endif\n    T result = RandomToTypeNormal<T>(&m_state, i);\n    return result;\n  }\n\n  template<typename Packet, typename Index> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  Packet packetOp(Index i) const {\n    const int packetSize = internal::unpacket_traits<Packet>::size;\n    EIGEN_ALIGN_MAX T values[packetSize];\n    #ifdef EIGEN_USE_SYCL\n    if(!m_exec_once) {\n      // This is the second stage of adding thread Id to the CPU clock seed and build unique seed per thread\n      m_state += (i * 6364136223846793005ULL);\n      m_exec_once =true;\n    }\n    #endif\n    EIGEN_UNROLL_LOOP\n    for (int j = 0; j < packetSize; ++j) {\n      values[j] = RandomToTypeNormal<T>(&m_state, i);\n    }\n    return internal::pload<Packet>(values);\n  }\n\n private:\n  mutable uint64_t m_state;\n   #ifdef EIGEN_USE_SYCL\n  mutable bool m_exec_once;\n  #endif\n};\n\n\ntemplate <typename Scalar>\nstruct functor_traits<NormalRandomGenerator<Scalar> > {\n  enum {\n    // On average, we need to generate about 3 random numbers\n    // 15 mul, 8 add, 1.5 logs\n    Cost = 3 * functor_traits<UniformRandomGenerator<Scalar> >::Cost +\n           15 * NumTraits<Scalar>::AddCost + 8 * NumTraits<Scalar>::AddCost +\n           3 * functor_traits<scalar_log_op<Scalar> >::Cost / 2,\n    PacketAccess = NormalRandomGenerator<Scalar>::PacketAccess\n  };\n};\n\n\n} // end namespace internal\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_RANDOM_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReduction.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n// Copyright (C) 2016 Mehdi Goli, Codeplay Software Ltd <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_H\n#define EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_H\n\n// clang is incompatible with the CUDA syntax wrt making a kernel a class friend,\n// so we'll use a macro to make clang happy.\n#ifndef KERNEL_FRIEND\n#if defined(__clang__) && (defined(__CUDA__) || defined(__HIP__))\n#define KERNEL_FRIEND friend __global__ EIGEN_HIP_LAUNCH_BOUNDS_1024\n#else\n#define KERNEL_FRIEND friend\n#endif\n#endif\n\n\nnamespace Eigen {\n\n\n/** \\class TensorReduction\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor reduction class.\n  *\n  */\n\nnamespace internal {\n  template<typename Op, typename Dims, typename XprType,template <class> class MakePointer_ >\n  struct traits<TensorReductionOp<Op, Dims, XprType, MakePointer_> >\n : traits<XprType>\n{\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::Scalar Scalar;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  static const int NumDimensions = XprTraits::NumDimensions - array_size<Dims>::value;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n\n  template <class T> struct MakePointer {\n    // Intermediate typedef to workaround MSVC issue.\n    typedef MakePointer_<T> MakePointerT;\n    typedef typename MakePointerT::Type Type;\n  };\n};\n\ntemplate<typename Op, typename Dims, typename XprType, template <class> class MakePointer_>\nstruct eval<TensorReductionOp<Op, Dims, XprType, MakePointer_>, Eigen::Dense>\n{\n  typedef const TensorReductionOp<Op, Dims, XprType, MakePointer_>& type;\n};\n\ntemplate<typename Op, typename Dims, typename XprType, template <class> class MakePointer_>\nstruct nested<TensorReductionOp<Op, Dims, XprType, MakePointer_>, 1, typename eval<TensorReductionOp<Op, Dims, XprType, MakePointer_> >::type>\n{\n  typedef TensorReductionOp<Op, Dims, XprType, MakePointer_> type;\n};\n\n\ntemplate <typename OutputDims> struct DimInitializer {\n  template <typename InputDims, typename ReducedDims> EIGEN_DEVICE_FUNC\n  static void run(const InputDims& input_dims,\n                  const array<bool, internal::array_size<InputDims>::value>& reduced,\n                  OutputDims* output_dims, ReducedDims* reduced_dims) {\n    const int NumInputDims = internal::array_size<InputDims>::value;\n    int outputIndex = 0;\n    int reduceIndex = 0;\n    for (int i = 0; i < NumInputDims; ++i) {\n      if (reduced[i]) {\n        (*reduced_dims)[reduceIndex] = input_dims[i];\n        ++reduceIndex;\n      } else {\n        (*output_dims)[outputIndex] = input_dims[i];\n        ++outputIndex;\n      }\n    }\n  }\n};\n\ntemplate <> struct DimInitializer<Sizes<> > {\n  template <typename InputDims, typename Index, size_t Rank> EIGEN_DEVICE_FUNC\n  static void run(const InputDims& input_dims, const array<bool, Rank>&,\n                  Sizes<>*, array<Index, Rank>* reduced_dims) {\n    const int NumInputDims = internal::array_size<InputDims>::value;\n    for (int i = 0; i < NumInputDims; ++i) {\n      (*reduced_dims)[i] = input_dims[i];\n    }\n  }\n};\n\n\ntemplate <typename ReducedDims, int NumTensorDims, int Layout>\nstruct are_inner_most_dims {\n  static const bool value = false;\n};\ntemplate <typename ReducedDims, int NumTensorDims, int Layout>\nstruct preserve_inner_most_dims {\n  static const bool value = false;\n};\n\n#if EIGEN_HAS_CONSTEXPR && EIGEN_HAS_VARIADIC_TEMPLATES\ntemplate <typename ReducedDims, int NumTensorDims>\nstruct are_inner_most_dims<ReducedDims, NumTensorDims, ColMajor>{\n  static const bool tmp1 = indices_statically_known_to_increase<ReducedDims>();\n  static const bool tmp2 = index_statically_eq<ReducedDims>(0, 0);\n  static const bool tmp3 = index_statically_eq<ReducedDims>(array_size<ReducedDims>::value-1, array_size<ReducedDims>::value-1);\n  static const bool value = tmp1 & tmp2 & tmp3;\n};\ntemplate <typename ReducedDims, int NumTensorDims>\nstruct are_inner_most_dims<ReducedDims, NumTensorDims, RowMajor>{\n  static const bool tmp1 = indices_statically_known_to_increase<ReducedDims>();\n  static const bool tmp2 = index_statically_eq<ReducedDims>(0, NumTensorDims - array_size<ReducedDims>::value);\n  static const bool tmp3 = index_statically_eq<ReducedDims>(array_size<ReducedDims>::value - 1, NumTensorDims - 1);\n  static const bool value = tmp1 & tmp2 & tmp3;\n\n};\ntemplate <typename ReducedDims, int NumTensorDims>\nstruct preserve_inner_most_dims<ReducedDims, NumTensorDims, ColMajor>{\n  static const bool tmp1 = indices_statically_known_to_increase<ReducedDims>();\n  static const bool tmp2 = index_statically_gt<ReducedDims>(0, 0);\n  static const bool value = tmp1 & tmp2;\n\n};\ntemplate <typename ReducedDims, int NumTensorDims>\nstruct preserve_inner_most_dims<ReducedDims, NumTensorDims, RowMajor>{\n  static const bool tmp1 = indices_statically_known_to_increase<ReducedDims>();\n  static const bool tmp2 = index_statically_lt<ReducedDims>(array_size<ReducedDims>::value - 1, NumTensorDims - 1);\n  static const bool value = tmp1 & tmp2;\n};\n#endif\n\n\ntemplate <int DimIndex, typename Self, typename Op>\nstruct GenericDimReducer {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self& self, typename Self::Index firstIndex, Op& reducer, typename Self::CoeffReturnType* accum) {\n    EIGEN_STATIC_ASSERT((DimIndex > 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    for (int j = 0; j < self.m_reducedDims[DimIndex]; ++j) {\n      const typename Self::Index input = firstIndex + j * self.m_reducedStrides[DimIndex];\n      GenericDimReducer<DimIndex-1, Self, Op>::reduce(self, input, reducer, accum);\n    }\n  }\n};\ntemplate <typename Self, typename Op>\nstruct GenericDimReducer<0, Self, Op> {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self& self, typename Self::Index firstIndex, Op& reducer, typename Self::CoeffReturnType* accum) {\n    for (int j = 0; j < self.m_reducedDims[0]; ++j) {\n      const typename Self::Index input = firstIndex + j * self.m_reducedStrides[0];\n      reducer.reduce(self.m_impl.coeff(input), accum);\n    }\n  }\n};\ntemplate <typename Self, typename Op>\nstruct GenericDimReducer<-1, Self, Op> {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self& self, typename Self::Index index, Op& reducer, typename Self::CoeffReturnType* accum) {\n    reducer.reduce(self.m_impl.coeff(index), accum);\n  }\n};\n\ntemplate <typename Self, typename Op, bool Vectorizable = (Self::InputPacketAccess && Self::ReducerTraits::PacketAccess),\n          bool UseTreeReduction = (!Self::ReducerTraits::IsStateful &&\n                                   !Self::ReducerTraits::IsExactlyAssociative)>\nstruct InnerMostDimReducer {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Self::CoeffReturnType reduce(const Self& self, typename Self::Index firstIndex, typename Self::Index numValuesToReduce, Op& reducer) {\n    typename Self::CoeffReturnType accum = reducer.initialize();\n    for (typename Self::Index j = 0; j < numValuesToReduce; ++j) {\n      reducer.reduce(self.m_impl.coeff(firstIndex + j), &accum);\n    }\n    return reducer.finalize(accum);\n  }\n};\n\ntemplate <typename Self, typename Op>\nstruct InnerMostDimReducer<Self, Op, true, false> {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Self::CoeffReturnType reduce(const Self& self, typename Self::Index firstIndex, typename Self::Index numValuesToReduce, Op& reducer) {\n    const typename Self::Index packetSize = internal::unpacket_traits<typename Self::PacketReturnType>::size;\n    const typename Self::Index VectorizedSize = (numValuesToReduce / packetSize) * packetSize;\n    typename Self::PacketReturnType paccum = reducer.template initializePacket<typename Self::PacketReturnType>();\n    for (typename Self::Index j = 0; j < VectorizedSize; j += packetSize) {\n      reducer.reducePacket(self.m_impl.template packet<Unaligned>(firstIndex + j), &paccum);\n    }\n    typename Self::CoeffReturnType accum = reducer.initialize();\n    for (typename Self::Index j = VectorizedSize; j < numValuesToReduce; ++j) {\n      reducer.reduce(self.m_impl.coeff(firstIndex + j), &accum);\n    }\n    return reducer.finalizeBoth(accum, paccum);\n  }\n};\n\n#if !defined(EIGEN_HIPCC) \nstatic const int kLeafSize = 1024;\n\ntemplate <typename Self, typename Op>\nstruct InnerMostDimReducer<Self, Op, false, true> {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Self::CoeffReturnType\n  reduce(const Self& self, typename Self::Index firstIndex,\n         typename Self::Index numValuesToReduce, Op& reducer) {\n    typename Self::CoeffReturnType accum = reducer.initialize();\n    if (numValuesToReduce > kLeafSize) {\n      const typename Self::Index half = numValuesToReduce / 2;\n      reducer.reduce(reduce(self, firstIndex, half, reducer), &accum);\n      reducer.reduce(\n          reduce(self, firstIndex + half, numValuesToReduce - half, reducer),\n          &accum);\n    } else {\n      for (typename Self::Index j = 0; j < numValuesToReduce; ++j) {\n        reducer.reduce(self.m_impl.coeff(firstIndex + j), &accum);\n      }\n    }\n    return reducer.finalize(accum);\n  }\n};\n\ntemplate <typename Self, typename Op>\nstruct InnerMostDimReducer<Self, Op, true, true> {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Self::CoeffReturnType\n  reduce(const Self& self, typename Self::Index firstIndex,\n         typename Self::Index numValuesToReduce, Op& reducer) {\n    const typename Self::Index packetSize =\n        internal::unpacket_traits<typename Self::PacketReturnType>::size;\n    typename Self::CoeffReturnType accum = reducer.initialize();\n    if (numValuesToReduce > packetSize * kLeafSize) {\n      // Make sure the split point is aligned on a packet boundary.\n      const typename Self::Index split =\n          packetSize *\n          divup(firstIndex + divup(numValuesToReduce, typename Self::Index(2)),\n                packetSize);\n      const typename Self::Index num_left =\n          numext::mini(split - firstIndex, numValuesToReduce);\n      reducer.reduce(reduce(self, firstIndex, num_left, reducer), &accum);\n      if (num_left < numValuesToReduce) {\n        reducer.reduce(\n            reduce(self, split, numValuesToReduce - num_left, reducer), &accum);\n      }\n      return reducer.finalize(accum);\n    } else {\n      const typename Self::Index UnrollSize =\n          (numValuesToReduce / (2*packetSize)) * 2*packetSize;\n      const typename Self::Index VectorizedSize =\n          (numValuesToReduce / packetSize) * packetSize;\n      typename Self::PacketReturnType paccum =\n          reducer.template initializePacket<typename Self::PacketReturnType>();\n      typename Self::PacketReturnType paccum2 =\n          reducer.template initializePacket<typename Self::PacketReturnType>();\n      for (typename Self::Index j = 0; j < UnrollSize; j += packetSize * 2) {\n        reducer.reducePacket(\n            self.m_impl.template packet<Unaligned>(firstIndex + j), &paccum);\n        reducer.reducePacket(\n            self.m_impl.template packet<Unaligned>(firstIndex + j + packetSize),\n            &paccum2);\n      }\n      for (typename Self::Index j = UnrollSize; j < VectorizedSize; j+= packetSize) {\n        reducer.reducePacket(self.m_impl.template packet<Unaligned>(\n                                 firstIndex + j), &paccum);\n      }\n      reducer.reducePacket(paccum2, &paccum);\n      for (typename Self::Index j = VectorizedSize; j < numValuesToReduce;\n           ++j) {\n        reducer.reduce(self.m_impl.coeff(firstIndex + j), &accum);\n      }\n      return reducer.finalizeBoth(accum, paccum);\n    }\n  }\n};\n#endif\n \ntemplate <int DimIndex, typename Self, typename Op, bool vectorizable = (Self::InputPacketAccess && Self::ReducerTraits::PacketAccess)>\nstruct InnerMostDimPreserver {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self&, typename Self::Index, Op&, typename Self::PacketReturnType*) {\n    eigen_assert(false && \"should never be called\");\n  }\n};\n\ntemplate <int DimIndex, typename Self, typename Op>\nstruct InnerMostDimPreserver<DimIndex, Self, Op, true> {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self& self, typename Self::Index firstIndex, Op& reducer, typename Self::PacketReturnType* accum) {\n    EIGEN_STATIC_ASSERT((DimIndex > 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    for (typename Self::Index j = 0; j < self.m_reducedDims[DimIndex]; ++j) {\n      const typename Self::Index input = firstIndex + j * self.m_reducedStrides[DimIndex];\n      InnerMostDimPreserver<DimIndex-1, Self, Op>::reduce(self, input, reducer, accum);\n    }\n  }\n};\n\ntemplate <typename Self, typename Op>\nstruct InnerMostDimPreserver<0, Self, Op, true> {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self& self, typename Self::Index firstIndex, Op& reducer, typename Self::PacketReturnType* accum) {\n    for (typename Self::Index j = 0; j < self.m_reducedDims[0]; ++j) {\n      const typename Self::Index input = firstIndex + j * self.m_reducedStrides[0];\n      reducer.reducePacket(self.m_impl.template packet<Unaligned>(input), accum);\n    }\n  }\n};\ntemplate <typename Self, typename Op>\nstruct InnerMostDimPreserver<-1, Self, Op, true> {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self&, typename Self::Index, Op&, typename Self::PacketReturnType*) {\n    eigen_assert(false && \"should never be called\");\n  }\n};\n\n// Default full reducer\ntemplate <typename Self, typename Op, typename Device, bool Vectorizable = (Self::InputPacketAccess && Self::ReducerTraits::PacketAccess)>\nstruct FullReducer {\n  static const bool HasOptimizedImplementation = false;\n\n  static EIGEN_DEVICE_FUNC void run(const Self& self, Op& reducer, const Device&, typename Self::EvaluatorPointerType output) {\n    const typename Self::Index num_coeffs = array_prod(self.m_impl.dimensions());\n    *output = InnerMostDimReducer<Self, Op, Vectorizable>::reduce(self, 0, num_coeffs, reducer);\n  }\n};\n\n\n#ifdef EIGEN_USE_THREADS\n// Multithreaded full reducers\ntemplate <typename Self, typename Op,\n          bool Vectorizable = (Self::InputPacketAccess && Self::ReducerTraits::PacketAccess)>\nstruct FullReducerShard {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(const Self& self, typename Self::Index firstIndex,\n                  typename Self::Index numValuesToReduce, Op& reducer,\n                  typename Self::CoeffReturnType* output) {\n    *output = InnerMostDimReducer<Self, Op, Vectorizable>::reduce(\n        self, firstIndex, numValuesToReduce, reducer);\n  }\n};\n\n// Multithreaded full reducer\ntemplate <typename Self, typename Op, bool Vectorizable>\nstruct FullReducer<Self, Op, ThreadPoolDevice, Vectorizable> {\n  static const bool HasOptimizedImplementation = !Self::ReducerTraits::IsStateful;\n  static const Index PacketSize =\n      unpacket_traits<typename Self::PacketReturnType>::size;\n\n  // launch one reducer per thread and accumulate the result.\n  static void run(const Self& self, Op& reducer, const ThreadPoolDevice& device,\n                  typename Self::CoeffReturnType* output) {\n    typedef typename Self::Index Index;\n    const Index num_coeffs = array_prod(self.m_impl.dimensions());\n    if (num_coeffs == 0) {\n      *output = reducer.finalize(reducer.initialize());\n      return;\n    }\n    const TensorOpCost cost =\n        self.m_impl.costPerCoeff(Vectorizable) +\n        TensorOpCost(0, 0, internal::functor_traits<Op>::Cost, Vectorizable,\n                     PacketSize);\n    const int num_threads = TensorCostModel<ThreadPoolDevice>::numThreads(\n        num_coeffs, cost, device.numThreads());\n    if (num_threads == 1) {\n      *output =\n          InnerMostDimReducer<Self, Op, Vectorizable>::reduce(self, 0, num_coeffs, reducer);\n      return;\n    }\n    const Index blocksize =\n        std::floor<Index>(static_cast<float>(num_coeffs) / num_threads);\n    const Index numblocks = blocksize > 0 ? num_coeffs / blocksize : 0;\n    eigen_assert(num_coeffs >= numblocks * blocksize);\n\n    Barrier barrier(internal::convert_index<unsigned int>(numblocks));\n    MaxSizeVector<typename Self::CoeffReturnType> shards(numblocks, reducer.initialize());\n    for (Index i = 0; i < numblocks; ++i) {\n      device.enqueue_with_barrier(&barrier, &FullReducerShard<Self, Op, Vectorizable>::run,\n                                  self, i * blocksize, blocksize, reducer,\n                                  &shards[i]);\n    }\n    typename Self::CoeffReturnType finalShard;\n    if (numblocks * blocksize < num_coeffs) {\n      finalShard = InnerMostDimReducer<Self, Op, Vectorizable>::reduce(\n          self, numblocks * blocksize, num_coeffs - numblocks * blocksize,\n          reducer);\n    } else {\n      finalShard = reducer.initialize();\n    }\n    barrier.Wait();\n\n    for (Index i = 0; i < numblocks; ++i) {\n      reducer.reduce(shards[i], &finalShard);\n    }\n    *output = reducer.finalize(finalShard);\n  }\n};\n\n#endif\n\n\n// Default inner reducer\ntemplate <typename Self, typename Op, typename Device>\nstruct InnerReducer {\n  static const bool HasOptimizedImplementation = false;\n\n  EIGEN_DEVICE_FUNC static bool run(const Self&, Op&, const Device&, typename Self::CoeffReturnType*, typename Self::Index, typename Self::Index) {\n    eigen_assert(false && \"Not implemented\");\n    return true;\n  }\n};\n\n// Default outer reducer\ntemplate <typename Self, typename Op, typename Device>\nstruct OuterReducer {\n  static const bool HasOptimizedImplementation = false;\n\n  EIGEN_DEVICE_FUNC static bool run(const Self&, Op&, const Device&, typename Self::CoeffReturnType*, typename Self::Index, typename Self::Index) {\n    eigen_assert(false && \"Not implemented\");\n    return true;\n  }\n};\n\n#ifdef EIGEN_USE_SYCL\n// Default Generic reducer\ntemplate <typename Self, typename Op, typename Device>\nstruct GenericReducer {\n  static const bool HasOptimizedImplementation = false;\n\n  EIGEN_DEVICE_FUNC static bool run(const Self&, Op&, const Device&, typename Self::CoeffReturnType*, typename Self::Index, typename Self::Index) {\n    eigen_assert(false && \"Not implemented\");\n    return true;\n  }\n};\n#endif\n\n#if defined(EIGEN_USE_GPU) && (defined(EIGEN_GPUCC))\ntemplate <int B, int N, typename S, typename R, typename I_>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void FullReductionKernel(R, const S, I_, typename S::CoeffReturnType*, unsigned int*);\n\n\n#if defined(EIGEN_HAS_GPU_FP16)\ntemplate <typename S, typename R, typename I_>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void ReductionInitFullReduxKernelHalfFloat(R, const S, I_, internal::packet_traits<half>::type*);\ntemplate <int B, int N, typename S, typename R, typename I_>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void FullReductionKernelHalfFloat(R, const S, I_, half*, internal::packet_traits<half>::type*);\ntemplate <int NPT, typename S, typename R, typename I_>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void InnerReductionKernelHalfFloat(R, const S, I_, I_, half*);\n\n#endif\n\ntemplate <int NPT, typename S, typename R, typename I_>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void InnerReductionKernel(R, const S, I_, I_, typename S::CoeffReturnType*);\n\ntemplate <int NPT, typename S, typename R, typename I_>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void OuterReductionKernel(R, const S, I_, I_, typename S::CoeffReturnType*);\n#endif\n\n/**\n * For SYCL, the return type of the reduction is deduced from the initialize method of the given Op.\n * This allows the reduction to have a different type for the accumulator than the input data type.\n * If this is the case, the functor needs to have two reduce method: one for reducing an element of the input\n * with the accumulator and the other for reducing two accumulators.\n * Such a reducer can be useful for instance when the accumulator is a boolean or a bitset that checks for\n * some properties of the input.\n */\ntemplate <typename Op, typename CoeffReturnType>\nstruct ReductionReturnType {\n#if defined(EIGEN_USE_SYCL)\n  typedef typename remove_const<decltype(std::declval<Op>().initialize())>::type type;\n#else\n  typedef typename remove_const<CoeffReturnType>::type type;\n#endif\n};\n\n}  // end namespace internal\n\n\ntemplate <typename Op, typename Dims, typename XprType,  template <class> class MakePointer_>\nclass TensorReductionOp : public TensorBase<TensorReductionOp<Op, Dims, XprType, MakePointer_>, ReadOnlyAccessors> {\n  public:\n    typedef typename Eigen::internal::traits<TensorReductionOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef typename internal::remove_const<typename XprType::CoeffReturnType>::type CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorReductionOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorReductionOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorReductionOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorReductionOp(const XprType& expr, const Dims& dims) : m_expr(expr), m_dims(dims)\n    { }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorReductionOp(const XprType& expr, const Dims& dims, const Op& reducer) : m_expr(expr), m_dims(dims), m_reducer(reducer)\n    { }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const XprType& expression() const { return m_expr; }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const Dims& dims() const { return m_dims; }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const Op& reducer() const { return m_reducer; }\n\n  protected:\n    typename XprType::Nested m_expr;\n    const Dims m_dims;\n    const Op m_reducer;\n};\n\ntemplate<typename ArgType, typename Device>\nstruct TensorReductionEvaluatorBase;\n\n// Eval as rvalue\ntemplate<typename Op, typename Dims, typename ArgType, template <class> class MakePointer_, typename Device>\nstruct TensorReductionEvaluatorBase<const TensorReductionOp<Op, Dims, ArgType, MakePointer_>, Device>\n{\n  typedef internal::reducer_traits<Op, Device> ReducerTraits;\n  typedef Dims ReducedDims;\n  typedef TensorReductionOp<Op, Dims, ArgType, MakePointer_> XprType;\n  typedef typename XprType::Index Index;\n  typedef ArgType ChildType;\n  typedef typename TensorEvaluator<ArgType, Device>::Dimensions InputDimensions;\n  static const int NumInputDims = internal::array_size<InputDimensions>::value;\n  static const int NumReducedDims = internal::array_size<Dims>::value;\n  static const int NumOutputDims = NumInputDims - NumReducedDims;\n  typedef typename internal::conditional<NumOutputDims==0, Sizes<>, DSizes<Index, NumOutputDims> >::type Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef TensorReductionEvaluatorBase<const TensorReductionOp<Op, Dims, ArgType, MakePointer_>, Device> Self;\n  static const bool InputPacketAccess = TensorEvaluator<ArgType, Device>::PacketAccess;\n  typedef typename internal::ReductionReturnType<Op, typename XprType::CoeffReturnType>::type CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const Index PacketSize = PacketType<CoeffReturnType, Device>::size;\n\n  typedef typename Eigen::internal::traits<XprType>::PointerType TensorPointerType;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n    // Subset of strides of the input tensor for the non-reduced dimensions.\n  // Indexed by output dimensions.\n  static const int NumPreservedStrides = max_n_1<NumOutputDims>::size;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = Self::InputPacketAccess && ReducerTraits::PacketAccess,\n    BlockAccess = false,\n    PreferBlockAccess = true,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  static const bool ReducingInnerMostDims = internal::are_inner_most_dims<Dims, NumInputDims, Layout>::value;\n  static const bool PreservingInnerMostDims = internal::preserve_inner_most_dims<Dims, NumInputDims, Layout>::value;\n  static const bool RunningFullReduction = (NumOutputDims==0);\n\n  EIGEN_STRONG_INLINE TensorReductionEvaluatorBase(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device), m_reducer(op.reducer()), m_result(NULL), m_device(device)\n  {\n    EIGEN_STATIC_ASSERT((NumInputDims >= NumReducedDims), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    EIGEN_STATIC_ASSERT((!ReducingInnerMostDims | !PreservingInnerMostDims | (NumReducedDims == NumInputDims)),\n                        YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    // Build the bitmap indicating if an input dimension is reduced or not.\n    for (int i = 0; i < NumInputDims; ++i) {\n      m_reduced[i] = false;\n    }\n    for (int i = 0; i < NumReducedDims; ++i) {\n      eigen_assert(op.dims()[i] >= 0);\n      eigen_assert(op.dims()[i] < NumInputDims);\n      m_reduced[op.dims()[i]] = true;\n    }\n\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n    internal::DimInitializer<Dimensions>::run(input_dims, m_reduced, &m_dimensions, &m_reducedDims);\n\n    // Precompute output strides.\n    if (NumOutputDims > 0) {\n      if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n        m_outputStrides[0] = 1;\n        for (int i = 1; i < NumOutputDims; ++i) {\n          m_outputStrides[i] = m_outputStrides[i - 1] * m_dimensions[i - 1];\n          m_fastOutputStrides[i] = internal::TensorIntDivisor<Index>(m_outputStrides[i]);\n        }\n      } else {\n        m_outputStrides[NumOutputDims - 1] = 1;\n        for (int i = NumOutputDims - 2; i >= 0; --i) {\n          m_outputStrides[i] = m_outputStrides[i + 1] * m_dimensions[i + 1];\n          m_fastOutputStrides[i] = internal::TensorIntDivisor<Index>(m_outputStrides[i]);\n        }\n      }\n    }\n\n    // Precompute input strides.\n    if (NumInputDims > 0) {\n      array<Index, NumInputDims> input_strides;\n      if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n        input_strides[0] = 1;\n        for (int i = 1; i < NumInputDims; ++i) {\n          input_strides[i] = input_strides[i-1] * input_dims[i-1];\n        }\n      } else {\n        input_strides.back() = 1;\n        for (int i = NumInputDims - 2; i >= 0; --i) {\n          input_strides[i] = input_strides[i + 1] * input_dims[i + 1];\n        }\n      }\n\n      int outputIndex = 0;\n      int reduceIndex = 0;\n      for (int i = 0; i < NumInputDims; ++i) {\n        if (m_reduced[i]) {\n          m_reducedStrides[reduceIndex] = input_strides[i];\n          ++reduceIndex;\n        } else {\n          m_preservedStrides[outputIndex] = input_strides[i];\n          m_output_to_input_dim_map[outputIndex] = i;\n          ++outputIndex;\n        }\n      }\n    }\n\n    // Special case for full reductions\n    if (NumOutputDims == 0) {\n      m_preservedStrides[0] = internal::array_prod(input_dims);\n    }\n\n    m_numValuesToReduce =\n        NumOutputDims == 0\n            ? internal::array_prod(input_dims)\n            : (static_cast<int>(Layout) == static_cast<int>(ColMajor))\n                  ? m_preservedStrides[0]\n                  : m_preservedStrides[NumOutputDims - 1];\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE\n  bool evalSubExprsIfNeededCommon(EvaluatorPointerType data) {\n    // Use the FullReducer if possible.\n    if ((RunningFullReduction && RunningOnSycl) ||(RunningFullReduction &&\n        internal::FullReducer<Self, Op, Device>::HasOptimizedImplementation &&\n        ((RunningOnGPU && (m_device.majorDeviceVersion() >= 3)) ||\n         !RunningOnGPU))) {\n      bool need_assign = false;\n      if (!data) {\n        m_result = static_cast<EvaluatorPointerType>(m_device.get((CoeffReturnType*)m_device.allocate_temp(sizeof(CoeffReturnType))));\n        data = m_result;\n        need_assign = true;\n      }\n      Op reducer(m_reducer);\n      internal::FullReducer<Self, Op, Device>::run(*this, reducer, m_device, data);\n      return need_assign;\n    }\n\n    // Attempt to use an optimized reduction.\n    else if ((RunningOnGPU && (m_device.majorDeviceVersion() >= 3)) || (RunningOnSycl)) {\n      bool reducing_inner_dims = true;\n      for (int i = 0; i < NumReducedDims; ++i) {\n        if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n          reducing_inner_dims &= m_reduced[i];\n        } else {\n          reducing_inner_dims &= m_reduced[NumInputDims - 1 - i];\n        }\n      }\n      if (internal::InnerReducer<Self, Op, Device>::HasOptimizedImplementation &&\n          (reducing_inner_dims || ReducingInnerMostDims)) {\n        const Index num_values_to_reduce = internal::array_prod(m_reducedDims);\n        const Index num_coeffs_to_preserve = internal::array_prod(m_dimensions);\n        if (!data) {\n          if ((num_coeffs_to_preserve < 1024 && num_values_to_reduce > num_coeffs_to_preserve && num_values_to_reduce > 128) || (RunningOnSycl)) {\n            data = static_cast<EvaluatorPointerType>(m_device.get((CoeffReturnType*)m_device.allocate_temp(sizeof(CoeffReturnType) * num_coeffs_to_preserve)));\n            m_result = data;\n          }\n          else {\n            return true;\n          }\n        }\n        Op reducer(m_reducer);\n        // For SYCL this if always return false\n        if (internal::InnerReducer<Self, Op, Device>::run(*this, reducer, m_device, data, num_values_to_reduce, num_coeffs_to_preserve)) {\n          if (m_result) {\n            m_device.deallocate_temp(m_result);\n            m_result = NULL;\n          }\n          return true;\n        } else {\n          return (m_result != NULL);\n        }\n      }\n\n      bool preserving_inner_dims = true;\n      for (int i = 0; i < NumReducedDims; ++i) {\n        if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n          preserving_inner_dims &= m_reduced[NumInputDims - 1 - i];\n        } else {\n          preserving_inner_dims &= m_reduced[i];\n        }\n      }\n      if (internal::OuterReducer<Self, Op, Device>::HasOptimizedImplementation &&\n          preserving_inner_dims) {\n        const Index num_values_to_reduce = internal::array_prod(m_reducedDims);\n        const Index num_coeffs_to_preserve = internal::array_prod(m_dimensions);\n        if (!data) {\n          if ((num_coeffs_to_preserve < 1024 && num_values_to_reduce > num_coeffs_to_preserve && num_values_to_reduce > 32) || (RunningOnSycl)) {\n            data = static_cast<EvaluatorPointerType>(m_device.get((CoeffReturnType*)m_device.allocate_temp(sizeof(CoeffReturnType) * num_coeffs_to_preserve)));\n            m_result = data;\n          }\n          else {\n            return true;\n          }\n        }\n        Op reducer(m_reducer);\n        // For SYCL this if always return false\n        if (internal::OuterReducer<Self, Op, Device>::run(*this, reducer, m_device, data, num_values_to_reduce, num_coeffs_to_preserve)) {\n          if (m_result) {\n            m_device.deallocate_temp(m_result);\n            m_result = NULL;\n          }\n          return true;\n        } else {\n          return (m_result != NULL);\n        }\n      }\n      #if defined(EIGEN_USE_SYCL)\n      // If there is no Optimised version for SYCL, the reduction expression \n      // must break into two subexpression and use the SYCL generic Reducer on the device.\n      if(RunningOnSycl) {\n         const Index num_values_to_reduce = internal::array_prod(m_reducedDims);\n         const Index num_coeffs_to_preserve = internal::array_prod(m_dimensions);\n         if (!data) {\n           data = static_cast<EvaluatorPointerType>(m_device.get((CoeffReturnType*)m_device.allocate_temp(sizeof(CoeffReturnType) * num_coeffs_to_preserve)));\n           m_result = data;\n         }\n         Op reducer(m_reducer);\n         internal::GenericReducer<Self, Op, Device>::run(*this, reducer, m_device, data, num_values_to_reduce, num_coeffs_to_preserve);\n         return (m_result != NULL);\n       }\n      #endif\n    }\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE\n      void\n      evalSubExprsIfNeededAsync(EvaluatorPointerType data,\n                                EvalSubExprsCallback done) {\n    m_impl.evalSubExprsIfNeededAsync(NULL, [this, data, done](bool) {\n      done(evalSubExprsIfNeededCommon(data));\n    });\n  }\n#endif\n\n  EIGEN_STRONG_INLINE\n  bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return evalSubExprsIfNeededCommon(data);\n  }\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n    if (m_result) {\n      m_device.deallocate_temp(m_result);\n      m_result = NULL;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    if (( RunningFullReduction || RunningOnGPU) && m_result ) {\n      return *(m_result + index);\n    }\n    Op reducer(m_reducer);\n    if (ReducingInnerMostDims || RunningFullReduction) {\n      const Index num_values_to_reduce =\n        (static_cast<int>(Layout) == static_cast<int>(ColMajor)) ? m_preservedStrides[0] : m_preservedStrides[NumPreservedStrides - 1];\n      return internal::InnerMostDimReducer<Self, Op>::reduce(*this, firstInput(index),\n                                                             num_values_to_reduce, reducer);\n    } else {\n      typename Self::CoeffReturnType accum = reducer.initialize();\n      internal::GenericDimReducer<NumReducedDims-1, Self, Op>::reduce(*this, firstInput(index), reducer, &accum);\n      return reducer.finalize(accum);\n    }\n  }\n\n  // TODO(bsteiner): provide a more efficient implementation.\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index + PacketSize - 1 < Index(internal::array_prod(dimensions())));\n\n    if (RunningOnGPU && m_result) {\n      return internal::pload<PacketReturnType>(m_result + index);\n    }\n\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n    if (ReducingInnerMostDims) {\n      const Index num_values_to_reduce =\n        (static_cast<int>(Layout) == static_cast<int>(ColMajor)) ? m_preservedStrides[0] : m_preservedStrides[NumPreservedStrides - 1];\n      const Index firstIndex = firstInput(index);\n      for (Index i = 0; i < PacketSize; ++i) {\n        Op reducer(m_reducer);\n        values[i] = internal::InnerMostDimReducer<Self, Op>::reduce(*this, firstIndex + i * num_values_to_reduce,\n                                                                    num_values_to_reduce, reducer);\n      }\n    } else if (PreservingInnerMostDims) {\n      const Index firstIndex = firstInput(index);\n      const int innermost_dim = (static_cast<int>(Layout) == static_cast<int>(ColMajor)) ? 0 : NumOutputDims - 1;\n      // TBD: extend this the the n innermost dimensions that we preserve.\n      if (((firstIndex % m_dimensions[innermost_dim]) + PacketSize - 1) < m_dimensions[innermost_dim]) {\n        Op reducer(m_reducer);\n        typename Self::PacketReturnType accum = reducer.template initializePacket<typename Self::PacketReturnType>();\n        internal::InnerMostDimPreserver<NumReducedDims-1, Self, Op>::reduce(*this, firstIndex, reducer, &accum);\n        return reducer.finalizePacket(accum);\n      } else {\n        for (int i = 0; i < PacketSize; ++i) {\n          values[i] = coeff(index + i);\n        }\n      }\n    } else {\n      for (int i = 0; i < PacketSize; ++i) {\n        values[i] = coeff(index + i);\n      }\n    }\n    PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n    return rslt;\n  }\n\n  // Must be called after evalSubExprsIfNeeded().\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    if (RunningFullReduction && m_result) {\n      return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, PacketSize);\n    } else {\n      const Index num_values_to_reduce = internal::array_prod(m_reducedDims);\n      const double compute_cost = num_values_to_reduce * internal::functor_traits<Op>::Cost;\n      return m_impl.costPerCoeff(vectorized) * num_values_to_reduce +\n          TensorOpCost(0, 0, compute_cost, vectorized, PacketSize);\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return m_result; }\n  EIGEN_DEVICE_FUNC const TensorEvaluator<ArgType, Device>& impl() const { return m_impl; }\n  EIGEN_DEVICE_FUNC const Device& device() const { return m_device; }\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n    m_result.bind(cgh);\n  }\n#endif\n\n  private:\n  template <int, typename, typename> friend struct internal::GenericDimReducer;\n  template <typename, typename, bool, bool> friend struct internal::InnerMostDimReducer;\n  template <int, typename, typename, bool> friend struct internal::InnerMostDimPreserver;\n  template <typename S, typename O, typename D, bool V> friend struct internal::FullReducer;\n#ifdef EIGEN_USE_THREADS\n  template <typename S, typename O, bool V> friend struct internal::FullReducerShard;\n#endif\n#if defined(EIGEN_USE_GPU) && (defined(EIGEN_GPUCC))\n  template <int B, int N, typename S, typename R, typename I_> KERNEL_FRIEND void internal::FullReductionKernel(R, const S, I_, typename S::CoeffReturnType*, unsigned int*);\n#if defined(EIGEN_HAS_GPU_FP16)\n  template <typename S, typename R, typename I_> KERNEL_FRIEND void internal::ReductionInitFullReduxKernelHalfFloat(R, const S, I_, internal::packet_traits<Eigen::half>::type*);\n  template <int B, int N, typename S, typename R, typename I_> KERNEL_FRIEND void internal::FullReductionKernelHalfFloat(R, const S, I_, half*, internal::packet_traits<Eigen::half>::type*);\n  template <int NPT, typename S, typename R, typename I_> KERNEL_FRIEND void internal::InnerReductionKernelHalfFloat(R, const S, I_, I_, half*);\n#endif\n  template <int NPT, typename S, typename R, typename I_> KERNEL_FRIEND void internal::InnerReductionKernel(R, const S, I_, I_, typename S::CoeffReturnType*);\n\n  template <int NPT, typename S, typename R, typename I_> KERNEL_FRIEND void internal::OuterReductionKernel(R, const S, I_, I_, typename S::CoeffReturnType*);\n#endif\n\n#if defined(EIGEN_USE_SYCL)\n template < typename Evaluator_, typename Op__> friend class TensorSycl::internal::GenericNondeterministicReducer;\n // SYCL need the Generic reducer for the case the recution algorithm is neither inner, outer, and full reducer\n template <typename, typename, typename> friend struct internal::GenericReducer;\n#endif\n\n\n  template <typename S, typename O, typename D> friend struct internal::InnerReducer;\n\n  struct BlockIteratorState {\n    Index input_dim;\n    Index output_size;\n    Index output_count;\n  };\n\n  // Returns the Index in the input tensor of the first value that needs to be\n  // used to compute the reduction at output index \"index\".\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index firstInput(Index index) const {\n    if (ReducingInnerMostDims) {\n      if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n        return index * m_preservedStrides[0];\n      } else {\n        return index * m_preservedStrides[NumPreservedStrides - 1];\n      }\n    }\n    // TBD: optimize the case where we preserve the innermost dimensions.\n    Index startInput = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = NumOutputDims - 1; i > 0; --i) {\n        // This is index_i in the output tensor.\n        const Index idx = index / m_outputStrides[i];\n        startInput += idx * m_preservedStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      if (PreservingInnerMostDims) {\n        eigen_assert(m_preservedStrides[0] == 1);\n        startInput += index;\n      } else {\n        startInput += index * m_preservedStrides[0];\n      }\n    } else {\n      for (int i = 0; i < NumOutputDims - 1; ++i) {\n        // This is index_i in the output tensor.\n        const Index idx = index / m_outputStrides[i];\n        startInput += idx * m_preservedStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      if (PreservingInnerMostDims) {\n        eigen_assert(m_preservedStrides[NumPreservedStrides - 1] == 1);\n        startInput += index;\n      } else {\n        startInput += index * m_preservedStrides[NumPreservedStrides - 1];\n      }\n    }\n    return startInput;\n  }\n\n  // Bitmap indicating if an input dimension is reduced or not.\n  array<bool, NumInputDims> m_reduced;\n  // Dimensions of the output of the operation.\n  Dimensions m_dimensions;\n  // Precomputed strides for the output tensor.\n  array<Index, NumOutputDims> m_outputStrides;\n  array<internal::TensorIntDivisor<Index>, NumOutputDims> m_fastOutputStrides;\n  array<Index, NumPreservedStrides> m_preservedStrides;\n  // Map from output to input dimension index.\n  array<Index, NumOutputDims> m_output_to_input_dim_map;\n  // How many values go into each reduction\n  Index m_numValuesToReduce;\n\n  // Subset of strides of the input tensor for the reduced dimensions.\n  // Indexed by reduced dimensions.\n  array<Index, NumReducedDims> m_reducedStrides;\n  // Size of the input dimensions that are reduced.\n  // Indexed by reduced dimensions.\n  array<Index, NumReducedDims> m_reducedDims;\n\n  // Evaluator for the input expression.\n  TensorEvaluator<ArgType, Device> m_impl;\n\n  // Operation to apply for computing the reduction.\n  Op m_reducer;\n\n  // For full reductions\n#if defined(EIGEN_USE_GPU) && (defined(EIGEN_GPUCC))\n  static const bool RunningOnGPU = internal::is_same<Device, Eigen::GpuDevice>::value;\n  static const bool RunningOnSycl = false;\n#elif defined(EIGEN_USE_SYCL)\nstatic const bool RunningOnSycl = internal::is_same<typename internal::remove_all<Device>::type, Eigen::SyclDevice>::value;\nstatic const bool RunningOnGPU = false;\n#else\n  static const bool RunningOnGPU = false;\n  static const bool RunningOnSycl = false;\n#endif\n  EvaluatorPointerType m_result;\n\n  const Device EIGEN_DEVICE_REF m_device;\n};\n\ntemplate<typename Op, typename Dims, typename ArgType, template <class> class MakePointer_, typename Device>\nstruct TensorEvaluator<const TensorReductionOp<Op, Dims, ArgType, MakePointer_>, Device>\n: public TensorReductionEvaluatorBase<const TensorReductionOp<Op, Dims, ArgType, MakePointer_>, Device> {\n  typedef TensorReductionEvaluatorBase<const TensorReductionOp<Op, Dims, ArgType, MakePointer_>, Device> Base;\n  EIGEN_STRONG_INLINE TensorEvaluator(const typename Base::XprType& op, const Device& device) : Base(op, device){}\n};\n\n\ntemplate<typename Op, typename Dims, typename ArgType, template <class> class MakePointer_>\nstruct TensorEvaluator<const TensorReductionOp<Op, Dims, ArgType, MakePointer_>, Eigen::SyclDevice>\n: public TensorReductionEvaluatorBase<const TensorReductionOp<Op, Dims, ArgType, MakePointer_>, Eigen::SyclDevice> {\n\n  typedef TensorReductionEvaluatorBase<const TensorReductionOp<Op, Dims, ArgType, MakePointer_>, Eigen::SyclDevice> Base;\n  EIGEN_STRONG_INLINE TensorEvaluator(const typename Base::XprType& op, const Eigen::SyclDevice& device) : Base(op, device){}\n  // The coeff function in the base the recursive method which is not an standard layout and cannot be used in the SYCL kernel\n  //Therefore the coeff function should be overridden by for SYCL kernel\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Base::CoeffReturnType coeff(typename Base::Index index) const {\n    return *(this->data() + index);\n  }\n  // The packet function in the base the recursive method which is not an standard layout and cannot be used in the SYCL kernel\n  //Therefore the packet function should be overridden by for SYCL kernel\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Base::PacketReturnType packet(typename Base::Index index) const {\n    return internal::pload<typename Base::PacketReturnType>(this->data() + index);\n  }\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReductionCuda.h",
    "content": "\n#if defined(__clang__) || defined(__GNUC__)\n#warning \"Deprecated header file, please either include the main Eigen/CXX11/Tensor header or the respective TensorReductionGpu.h file\"\n#endif\n\n#include \"TensorReductionGpu.h\"\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReductionGpu.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_GPU_H\n#define EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_GPU_H\n\nnamespace Eigen {\nnamespace internal {\n\n\n#if defined(EIGEN_USE_GPU) && defined(EIGEN_GPUCC)\n// Full reducers for GPU, don't vectorize for now\n\n// Reducer function that enables multiple gpu thread to safely accumulate at the same\n// output address. It basically reads the current value of the output variable, and\n// attempts to update it with the new value. If in the meantime another gpu thread\n// updated the content of the output address it will try again.\ntemplate <typename T, typename R>\n__device__ EIGEN_ALWAYS_INLINE void atomicReduce(T* output, T accum, R& reducer) {\n#if (defined(EIGEN_HIP_DEVICE_COMPILE) && defined(__HIP_ARCH_HAS_WARP_SHUFFLE__)) || (EIGEN_CUDA_ARCH >= 300)\n  if (sizeof(T) == 4)\n  {\n    unsigned int oldval = *reinterpret_cast<unsigned int*>(output);\n    unsigned int newval = oldval;\n    reducer.reduce(accum, reinterpret_cast<T*>(&newval));\n    if (newval == oldval) {\n      return;\n    }\n    unsigned int readback;\n    while ((readback = atomicCAS((unsigned int*)output, oldval, newval)) != oldval) {\n      oldval = readback;\n      newval = oldval;\n      reducer.reduce(accum, reinterpret_cast<T*>(&newval));\n      if (newval == oldval) {\n        return;\n      }\n    }\n  }\n  else if (sizeof(T) == 8) {\n    unsigned long long oldval = *reinterpret_cast<unsigned long long*>(output);\n    unsigned long long newval = oldval;\n    reducer.reduce(accum, reinterpret_cast<T*>(&newval));\n    if (newval == oldval) {\n      return;\n    }\n    unsigned long long readback;\n    while ((readback = atomicCAS((unsigned long long*)output, oldval, newval)) != oldval) {\n      oldval = readback;\n      newval = oldval;\n      reducer.reduce(accum, reinterpret_cast<T*>(&newval));\n      if (newval == oldval) {\n        return;\n      }\n    }\n  }\n  else {\n    gpu_assert(0 && \"Wordsize not supported\");\n  }\n#else // EIGEN_CUDA_ARCH >= 300\n  gpu_assert(0 && \"Shouldn't be called on unsupported device\");\n#endif // EIGEN_CUDA_ARCH >= 300\n}\n\n// We extend atomicExch to support extra data types\ntemplate <typename Type>\n__device__ inline Type atomicExchCustom(Type* address, Type val) {\n  return atomicExch(address, val);\n}\n\ntemplate <>\n__device__ inline double atomicExchCustom(double* address, double val) {\n  unsigned long long int* address_as_ull = reinterpret_cast<unsigned long long int*>(address);\n  return __longlong_as_double(atomicExch(address_as_ull, __double_as_longlong(val)));\n}\n\n#ifdef EIGEN_HAS_GPU_FP16\ntemplate <typename R>\n__device__ inline void atomicReduce(half2* output, half2 accum, R& reducer) {\n  unsigned int oldval = *reinterpret_cast<unsigned int*>(output);\n  unsigned int newval = oldval;\n  reducer.reducePacket(accum, reinterpret_cast<half2*>(&newval));\n  if (newval == oldval) {\n    return;\n  }\n  unsigned int readback;\n  while ((readback = atomicCAS((unsigned int*)output, oldval, newval)) != oldval) {\n    oldval = readback;\n    newval = oldval;\n    reducer.reducePacket(accum, reinterpret_cast<half2*>(&newval));\n    if (newval == oldval) {\n      return;\n    }\n  }\n}\n#ifdef EIGEN_GPU_COMPILE_PHASE\n// reduction should be associative since reduction is not atomic in wide vector but atomic in half2 operations\ntemplate <typename R>\n__device__ inline void atomicReduce(Packet4h2* output, Packet4h2 accum, R& reducer) {\n  half2* houtput=reinterpret_cast<half2*>(output);\n  half2* haccum=reinterpret_cast<half2*>(&accum);\n  for(int i=0;i<4;++i){\n    atomicReduce(houtput+i,*(haccum+i),reducer);\n  }\n}\n#endif  // EIGEN_GPU_COMPILE_PHASE\n#endif  // EIGEN_HAS_GPU_FP16\n\ntemplate <>\n__device__ inline void atomicReduce(float* output, float accum, SumReducer<float>&) {\n#if (defined(EIGEN_HIP_DEVICE_COMPILE) && defined(__HIP_ARCH_HAS_WARP_SHUFFLE__)) || (EIGEN_CUDA_ARCH >= 300)\n  atomicAdd(output, accum);\n#else // EIGEN_CUDA_ARCH >= 300\n  gpu_assert(0 && \"Shouldn't be called on unsupported device\");\n#endif // EIGEN_CUDA_ARCH >= 300\n}\n\n\ntemplate <typename CoeffType, typename Index>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void ReductionInitKernel(const CoeffType val, Index num_preserved_coeffs, CoeffType* output) {\n  const Index thread_id = blockIdx.x * blockDim.x + threadIdx.x;\n  const Index num_threads = blockDim.x * gridDim.x;\n  for (Index i = thread_id; i < num_preserved_coeffs; i += num_threads) {\n    output[i] = val;\n  }\n}\n\n\ntemplate <int BlockSize, int NumPerThread, typename Self,\n          typename Reducer, typename Index>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void FullReductionKernel(Reducer reducer, const Self input, Index num_coeffs,\n                                    typename Self::CoeffReturnType* output, unsigned int* semaphore) {\n#if (defined(EIGEN_HIP_DEVICE_COMPILE) && defined(__HIP_ARCH_HAS_WARP_SHUFFLE__)) || (EIGEN_CUDA_ARCH >= 300)\n  // Initialize the output value\n  const Index first_index = blockIdx.x * BlockSize * NumPerThread + threadIdx.x;\n  if (gridDim.x == 1) {\n    if (first_index == 0) {\n      *output = reducer.initialize();\n    }\n  }\n  else {\n    if (threadIdx.x == 0) {\n      unsigned int block = atomicCAS(semaphore, 0u, 1u);\n      if (block == 0) {\n        // We're the first block to run, initialize the output value\n        atomicExchCustom(output, reducer.initialize());\n        __threadfence();\n        atomicExch(semaphore, 2u);\n      }\n      else {\n        // Wait for the first block to initialize the output value.\n        // Use atomicCAS here to ensure that the reads aren't cached\n        unsigned int val;\n        do {\n          val = atomicCAS(semaphore, 2u, 2u);\n        }\n        while (val < 2u);\n      }\n    }\n  }\n\n  __syncthreads();\n\n  eigen_assert(gridDim.x == 1 || *semaphore >= 2u);\n\n  typename Self::CoeffReturnType accum = reducer.initialize();\n  Index max_iter = numext::mini<Index>(num_coeffs - first_index, NumPerThread*BlockSize);\n  for (Index i = 0; i < max_iter; i+=BlockSize) {\n    const Index index = first_index + i;\n    eigen_assert(index < num_coeffs);\n    typename Self::CoeffReturnType val = input.m_impl.coeff(index);\n    reducer.reduce(val, &accum);\n  }\n\n#pragma unroll\n  for (int offset = warpSize/2; offset > 0; offset /= 2) {\n  #if defined(EIGEN_HIPCC)\n    // use std::is_floating_point to determine the type of reduced_val \n    // This is needed because when Type == double, hipcc will give a \"call to __shfl_down is ambguous\" error \n    // and list the float and int versions of __shfl_down as the candidate functions. \n    if (std::is_floating_point<typename Self::CoeffReturnType>::value) {\n      reducer.reduce(__shfl_down(static_cast<float>(accum), offset, warpSize), &accum);\n    } else {\n      reducer.reduce(__shfl_down(static_cast<int>(accum), offset, warpSize), &accum);\n    }\n  #elif defined(EIGEN_CUDA_SDK_VER) && EIGEN_CUDA_SDK_VER < 90000\n    reducer.reduce(__shfl_down(accum, offset, warpSize), &accum);\n  #else\n    reducer.reduce(__shfl_down_sync(0xFFFFFFFF, accum, offset, warpSize), &accum);\n  #endif\n  }\n\n  if ((threadIdx.x & (warpSize - 1)) == 0) {\n    atomicReduce(output, accum, reducer);\n  }\n\n  if (gridDim.x > 1 && threadIdx.x == 0) {\n    // Let the last block reset the semaphore\n    atomicInc(semaphore, gridDim.x + 1);\n#if defined(EIGEN_HIPCC)\n    __threadfence_system();\n#endif\n  }\n#else // EIGEN_CUDA_ARCH >= 300\n  gpu_assert(0 && \"Shouldn't be called on unsupported device\");\n#endif // EIGEN_CUDA_ARCH >= 300\n}\n\n\n#ifdef EIGEN_HAS_GPU_FP16\ntemplate <typename Self,\n          typename Reducer, typename Index>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void ReductionInitFullReduxKernelHalfFloat(\n    Reducer reducer, const Self input, Index num_coeffs, half* scratch) {\n  eigen_assert(blockDim.x == 1);\n  eigen_assert(gridDim.x == 1);\n  typedef packet_traits<Eigen::half>::type packet_type;\n  Index packet_remainder =\n      num_coeffs % Index(unpacket_traits<packet_type>::size);\n  if (packet_remainder != 0) {\n    half2* h2scratch = reinterpret_cast<half2*>(scratch);\n    for (Index i = num_coeffs - packet_remainder; i + 2 <= num_coeffs; i += 2) {\n      *h2scratch =\n          __halves2half2(input.coeff(i), input.coeff(i + 1));\n      h2scratch++;\n    }\n    if ((num_coeffs & 1) != 0) {\n      half lastCoeff = input.coeff(num_coeffs - 1);\n      *h2scratch = __halves2half2(lastCoeff, reducer.initialize());\n    }\n  } else {\n    packet_type reduce = reducer.template initializePacket<packet_type>();\n    internal::pstoreu(scratch, reduce);\n  }\n}\n\ntemplate <typename Self,\n          typename Reducer, typename Index>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void ReductionInitKernelHalfFloat(Reducer reducer, const Self input, Index num_coeffs, half* output) {\n  const Index thread_id = blockIdx.x * blockDim.x + threadIdx.x;\n  const Index num_threads = blockDim.x * gridDim.x;\n  typedef typename packet_traits<Eigen::half>::type PacketType;\n\n  const Index num_packets =\n      num_coeffs / Index(unpacket_traits<PacketType>::size);\n  PacketType* p_output = reinterpret_cast<PacketType*>(output);\n  for (Index i = thread_id; i < num_packets; i += num_threads) {\n    p_output[i] = reducer.template initializePacket<PacketType>();\n  }\n  Index packet_remainder =\n      num_coeffs % Index(unpacket_traits<PacketType>::size);\n  if (thread_id < packet_remainder) {\n    output[num_coeffs - packet_remainder + thread_id] = reducer.initialize();\n  }\n}\n\ntemplate <int BlockSize, int NumPerThread, typename Self,\n          typename Reducer, typename Index>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void FullReductionKernelHalfFloat(\n    Reducer reducer, const Self input, Index num_coeffs,\n    half* output, half* scratch) {\n  typedef typename packet_traits<Eigen::half>::type PacketType;\n  const int packet_width = unpacket_traits<PacketType>::size;\n  eigen_assert(NumPerThread % packet_width == 0);\n  const Index first_index =\n      blockIdx.x * BlockSize * NumPerThread + packet_width * threadIdx.x;\n\n  // Initialize the output value if it wasn't initialized by the ReductionInitKernel\n\n  if (gridDim.x == 1) {\n    if (first_index == 0) {\n      int rem = num_coeffs % packet_width;\n      if (rem != 0) {\n        half2* p_scratch = reinterpret_cast<half2*>(scratch);\n        pstoreu(scratch, reducer.template initializePacket<PacketType>());\n        for (int i = 0; i < rem / 2; i++) {\n          *p_scratch = __halves2half2(\n              input.coeff(num_coeffs - packet_width + 2 * i),\n              input.coeff(num_coeffs - packet_width + 2 * i + 1));\n          p_scratch++;\n        }\n        if ((num_coeffs & 1) != 0) {\n          half last = input.coeff(num_coeffs - 1);\n          *p_scratch = __halves2half2(last, reducer.initialize());\n        }\n      } else {\n        PacketType reduce = reducer.template initializePacket<PacketType>();\n        pstoreu(scratch, reduce);\n      }\n    }\n    __syncthreads();\n  }\n\n  PacketType accum = reducer.template initializePacket<PacketType>();\n  const Index max_iter =\n      numext::mini<Index>((num_coeffs - first_index) / packet_width,\n                          NumPerThread * BlockSize / packet_width);\n  for (Index i = 0; i < max_iter; i += BlockSize) {\n    const Index index = first_index + packet_width * i;\n    eigen_assert(index + packet_width < num_coeffs);\n    PacketType val = input.template packet<Unaligned>(index);\n    reducer.reducePacket(val, &accum);\n  }\n\n#pragma unroll\n  for (int offset = warpSize/2; offset > 0; offset /= 2) {\n  #if defined(EIGEN_HIPCC)\n    PacketType r1;\n    half2* hr = reinterpret_cast<half2*>(&r1);\n    half2* hacc = reinterpret_cast<half2*>(&accum);\n    for (int i = 0; i < packet_width / 2; i++) {\n      // FIXME : remove this workaround once we have native half/half2 support for __shfl_down\n      union { int i; half2 h; } wka_in, wka_out;\n      wka_in.h = hacc[i];\n      wka_out.i = __shfl_down(wka_in.i, offset, warpSize);\n      hr[i] = wka_out.h;\n    }\n    reducer.reducePacket(r1, &accum);\n  #elif defined(EIGEN_CUDA_SDK_VER) && EIGEN_CUDA_SDK_VER < 90000\n    PacketType r1;\n    half2* hr = reinterpret_cast<half2*>(&r1);\n    half2* hacc = reinterpret_cast<half2*>(&accum);\n    for (int i = 0; i < packet_width / 2; i++) {\n      hr[i] = __shfl_down(hacc[i], offset, warpSize);\n    }\n    reducer.reducePacket(r1, &accum);\n  #else\n    PacketType r1;\n    half2* hr = reinterpret_cast<half2*>(&r1);\n    half2* hacc = reinterpret_cast<half2*>(&accum);\n    for (int i = 0; i < packet_width / 2; i++) {\n      hr[i] = __shfl_down_sync(0xFFFFFFFF, hacc[i], (unsigned)offset, warpSize);\n    }\n    reducer.reducePacket(r1, &accum);\n\n  #endif\n  }\n\n  if ((threadIdx.x & (warpSize - 1)) == 0) {\n    atomicReduce(reinterpret_cast<PacketType*>(scratch), accum, reducer);\n  }\n\n  __syncthreads();\n  half2* rv1 = reinterpret_cast<half2*>(scratch);\n  if (packet_width > 2) {\n    reducer.reducePacket(rv1[2], rv1);\n    reducer.reducePacket(rv1[3], rv1 + 1);\n    reducer.reducePacket(rv1[1], rv1);\n  }\n  if (gridDim.x == 1) {\n    if (first_index == 0) {\n      half tmp = __low2half(*rv1);\n      reducer.reduce(__high2half(*rv1), &tmp);\n      *output = tmp;\n    }\n  }\n}\n\ntemplate <typename Op>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void ReductionCleanupKernelHalfFloat(Op reducer, half* output, half* scratch) {\n  eigen_assert(threadIdx.x == 1);\n  typedef packet_traits<Eigen::half>::type packet_type;\n  if (unpacket_traits<packet_type>::size == 1) {\n    *output = *scratch;\n  } else {\n    half2* pscratch = reinterpret_cast<half2*>(scratch);\n    half tmp = __float2half(0.f);\n    for (int i = 0; i < unpacket_traits<packet_type>::size; i += 2) {\n      reducer.reduce(__low2half(*pscratch), &tmp);\n      reducer.reduce(__high2half(*pscratch), &tmp);\n      pscratch++;\n    }\n    *output = tmp;\n  }\n}\n\n#endif // EIGEN_HAS_GPU_FP16\n\ntemplate <typename Self, typename Op, typename OutputType, bool PacketAccess, typename Enabled = void>\nstruct FullReductionLauncher {\n  static void run(const Self&, Op&, const GpuDevice&, OutputType*, typename Self::Index) {\n    gpu_assert(false && \"Should only be called on doubles, floats and half floats\");\n  }\n};\n\n// Specialization for float and double\ntemplate <typename Self, typename Op, typename OutputType, bool PacketAccess>\nstruct FullReductionLauncher<\n    Self, Op, OutputType, PacketAccess,\n    typename internal::enable_if<\n      internal::is_same<float, OutputType>::value ||\n      internal::is_same<double, OutputType>::value,\n    void>::type> {\n  static void run(const Self& self, Op& reducer, const GpuDevice& device, OutputType* output, typename Self::Index num_coeffs) {\n\n    typedef typename Self::Index Index;\n    const int block_size = 256;\n    const int num_per_thread = 128;\n    const int num_blocks = divup<int>(num_coeffs, block_size * num_per_thread);\n\n    unsigned int* semaphore = NULL;\n    if (num_blocks > 1) {\n      semaphore = device.semaphore();\n    }\n\n    LAUNCH_GPU_KERNEL((FullReductionKernel<block_size, num_per_thread, Self, Op, Index>),\n                       num_blocks, block_size, 0, device, reducer, self, num_coeffs, output, semaphore);\n  }\n};\n\n#ifdef EIGEN_HAS_GPU_FP16\ntemplate <typename Self, typename Op>\nstruct FullReductionLauncher<Self, Op, Eigen::half, false> {\n  static void run(const Self&, Op&, const GpuDevice&, half*, typename Self::Index) {\n    gpu_assert(false && \"Should not be called since there is no packet accessor\");\n  }\n};\n\ntemplate <typename Self, typename Op>\nstruct FullReductionLauncher<Self, Op, Eigen::half, true> {\n  static void run(const Self& self, Op& reducer, const GpuDevice& device, half* output, typename Self::Index num_coeffs) {\n    typedef typename Self::Index Index;\n\n    const int block_size = 256;\n    const int num_per_thread = 128;\n    const int num_blocks = divup<int>(num_coeffs, block_size * num_per_thread);\n    half* scratch = static_cast<half*>(device.scratchpad());\n\n    if (num_blocks > 1) {\n      // We initialize the output and the scrathpad outside the reduction kernel when we can't be sure that there\n      // won't be a race conditions between multiple thread blocks.\n      LAUNCH_GPU_KERNEL((ReductionInitFullReduxKernelHalfFloat<Self, Op, Index>),\n                         1, 1, 0, device, reducer, self, num_coeffs, scratch);\n    }\n\n    LAUNCH_GPU_KERNEL((FullReductionKernelHalfFloat<block_size, num_per_thread, Self, Op, Index>),\n                       num_blocks, block_size, 0, device, reducer, self, num_coeffs, output, scratch);\n\n    if (num_blocks > 1) {\n      LAUNCH_GPU_KERNEL((ReductionCleanupKernelHalfFloat<Op>),\n                         1, 1, 0, device, reducer, output, scratch);\n    }\n  }\n};\n#endif // EIGEN_HAS_GPU_FP16\n\n\ntemplate <typename Self, typename Op, bool Vectorizable>\nstruct FullReducer<Self, Op, GpuDevice, Vectorizable> {\n  // Unfortunately nvidia doesn't support well exotic types such as complex,\n  // so reduce the scope of the optimized version of the code to the simple cases\n  // of doubles, floats and half floats\n#ifdef EIGEN_HAS_GPU_FP16\n  static const bool HasOptimizedImplementation = !Self::ReducerTraits::IsStateful &&\n      (internal::is_same<typename Self::CoeffReturnType, float>::value ||\n       internal::is_same<typename Self::CoeffReturnType, double>::value ||\n       (internal::is_same<typename Self::CoeffReturnType, Eigen::half>::value && reducer_traits<Op, GpuDevice>::PacketAccess));\n#else // EIGEN_HAS_GPU_FP16\n  static const bool HasOptimizedImplementation = !Self::ReducerTraits::IsStateful &&\n                                                (internal::is_same<typename Self::CoeffReturnType, float>::value ||\n                                                 internal::is_same<typename Self::CoeffReturnType, double>::value);\n#endif // EIGEN_HAS_GPU_FP16\n\n  template <typename OutputType>\n  static void run(const Self& self, Op& reducer, const GpuDevice& device, OutputType* output) {\n    gpu_assert(HasOptimizedImplementation && \"Should only be called on doubles, floats or half floats\");\n    const Index num_coeffs = array_prod(self.m_impl.dimensions());\n    // Don't crash when we're called with an input tensor of size 0.\n    if (num_coeffs == 0) {\n      return;\n    }\n\n    FullReductionLauncher<Self, Op, OutputType, reducer_traits<Op, GpuDevice>::PacketAccess>::run(self, reducer, device, output, num_coeffs);\n  }\n};\n\n\ntemplate <int NumPerThread, typename Self,\n          typename Reducer, typename Index>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void InnerReductionKernel(Reducer reducer, const Self input, Index num_coeffs_to_reduce, Index num_preserved_coeffs,\n                                         typename Self::CoeffReturnType* output) {\n#if (defined(EIGEN_HIP_DEVICE_COMPILE) && defined(__HIP_ARCH_HAS_WARP_SHUFFLE__)) || (EIGEN_CUDA_ARCH >= 300)\n  typedef typename Self::CoeffReturnType Type;\n  eigen_assert(blockDim.y == 1);\n  eigen_assert(blockDim.z == 1);\n  eigen_assert(gridDim.y == 1);\n  eigen_assert(gridDim.z == 1);\n\n  const int unroll_times = 16;\n  eigen_assert(NumPerThread % unroll_times == 0);\n\n  const Index input_col_blocks = divup<Index>(num_coeffs_to_reduce, blockDim.x * NumPerThread);\n  const Index num_input_blocks = input_col_blocks * num_preserved_coeffs;\n\n  const Index num_threads = blockDim.x * gridDim.x;\n  const Index thread_id = blockIdx.x * blockDim.x + threadIdx.x;\n\n  // Initialize the output values if they weren't initialized by the ReductionInitKernel\n  if (gridDim.x == 1) {\n    for (Index i = thread_id; i < num_preserved_coeffs; i += num_threads) {\n      output[i] = reducer.initialize();\n    }\n    __syncthreads();\n  }\n\n  for (Index i = blockIdx.x; i < num_input_blocks; i += gridDim.x) {\n    const Index row = i / input_col_blocks;\n\n    if (row < num_preserved_coeffs) {\n      const Index col_block = i % input_col_blocks;\n      const Index col_begin = col_block * blockDim.x * NumPerThread + threadIdx.x;\n\n      Type reduced_val = reducer.initialize();\n\n      for (Index j = 0; j < NumPerThread; j += unroll_times) {\n        const Index last_col = col_begin + blockDim.x * (j + unroll_times - 1);\n        if (last_col >= num_coeffs_to_reduce) {\n          for (Index col = col_begin + blockDim.x * j; col < num_coeffs_to_reduce; col += blockDim.x) {\n            const Type val = input.m_impl.coeff(row * num_coeffs_to_reduce + col);\n            reducer.reduce(val, &reduced_val);\n          }\n          break;\n        } else {\n          // Faster version of the loop with no branches after unrolling.\n#pragma unroll\n          for (int k = 0; k < unroll_times; ++k) {\n            const Index col = col_begin + blockDim.x * (j + k);\n            reducer.reduce(input.m_impl.coeff(row * num_coeffs_to_reduce + col), &reduced_val);\n          }\n        }\n      }\n\n#pragma unroll\n      for (int offset = warpSize/2; offset > 0; offset /= 2) {\n      #if defined(EIGEN_HIPCC)\n        // use std::is_floating_point to determine the type of reduced_val \n       // This is needed because when Type == double, hipcc will give a \"call to __shfl_down is ambguous\" error \n       // and list the float and int versions of __shfl_down as the candidate functions. \n        if (std::is_floating_point<Type>::value) {\n          reducer.reduce(__shfl_down(static_cast<float>(reduced_val), offset), &reduced_val);\n        } else {\n          reducer.reduce(__shfl_down(static_cast<int>(reduced_val), offset), &reduced_val);\n        }\n      #elif defined(EIGEN_CUDA_SDK_VER) && EIGEN_CUDA_SDK_VER < 90000\n        reducer.reduce(__shfl_down(reduced_val, offset), &reduced_val);\n      #else\n        reducer.reduce(__shfl_down_sync(0xFFFFFFFF, reduced_val, offset), &reduced_val);\n      #endif\n      }\n\n      if ((threadIdx.x & (warpSize - 1)) == 0) {\n        atomicReduce(&(output[row]), reduced_val, reducer);\n      }\n    }\n  }\n#else // EIGEN_CUDA_ARCH >= 300\n  gpu_assert(0 && \"Shouldn't be called on unsupported device\");\n#endif // EIGEN_CUDA_ARCH >= 300\n}\n\n#ifdef EIGEN_HAS_GPU_FP16\n\ntemplate <int NumPerThread, typename Self,\n          typename Reducer, typename Index>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void InnerReductionKernelHalfFloat(Reducer reducer, const Self input, Index num_coeffs_to_reduce, Index num_preserved_coeffs,\n                                              half* output) {\n  eigen_assert(blockDim.y == 1);\n  eigen_assert(blockDim.z == 1);\n  eigen_assert(gridDim.y == 1);\n  eigen_assert(gridDim.z == 1);\n\n  typedef typename packet_traits<Eigen::half>::type PacketType;\n  const int packet_width = unpacket_traits<PacketType>::size;\n  const int unroll_times = 16 / packet_width;\n  eigen_assert(NumPerThread % unroll_times == 0);\n  eigen_assert(unroll_times % 2 == 0);\n\n  const Index input_col_blocks = divup<Index>(num_coeffs_to_reduce, blockDim.x * NumPerThread * 2);\n  const Index num_input_blocks = divup<Index>(input_col_blocks * num_preserved_coeffs, 2);\n\n  const Index num_threads = blockDim.x * gridDim.x;\n  const Index thread_id = blockIdx.x * blockDim.x + threadIdx.x;\n\n  // Initialize the output values if they weren't initialized by the ReductionInitKernel\n  if (gridDim.x == 1) {\n    Index i = packet_width * thread_id;\n    for (; i + packet_width <= num_preserved_coeffs;\n         i += packet_width * num_threads) {\n      PacketType* poutput = reinterpret_cast<PacketType*>(output + i);\n      *poutput = reducer.template initializePacket<PacketType>();\n    }\n    if (i < num_preserved_coeffs) {\n      output[i] = reducer.initialize();\n    }\n    __syncthreads();\n  }\n\n  for (Index i = blockIdx.x; i < num_input_blocks; i += gridDim.x) {\n    const Index row = 2 * (i / input_col_blocks);  // everybody takes 2 rows\n\n    if (row + 1 < num_preserved_coeffs) {\n      const Index col_block = i % input_col_blocks;\n      const Index col_begin =\n          packet_width * (col_block * blockDim.x * NumPerThread + threadIdx.x);\n\n      PacketType reduced_val1 = reducer.template initializePacket<PacketType>();\n      PacketType reduced_val2 = reducer.template initializePacket<PacketType>();\n\n      for (Index j = 0; j < NumPerThread; j += unroll_times) {\n        const Index last_col =\n            col_begin + blockDim.x * (j + unroll_times - 1) * packet_width;\n        if (last_col >= num_coeffs_to_reduce) {\n          Index col = col_begin + blockDim.x * j;\n          for (; col + packet_width <= num_coeffs_to_reduce;\n               col += blockDim.x) {\n            const PacketType val1 = input.m_impl.template packet<Unaligned>(\n                row * num_coeffs_to_reduce + col);\n            reducer.reducePacket(val1, &reduced_val1);\n            const PacketType val2 = input.m_impl.template packet<Unaligned>(\n                (row + 1) * num_coeffs_to_reduce + col);\n            reducer.reducePacket(val2, &reduced_val2);\n          }\n          if (col < num_coeffs_to_reduce) {\n            PacketType r1 = reducer.template initializePacket<PacketType>();\n            PacketType r2 = reducer.template initializePacket<PacketType>();\n            half2* hr1 = reinterpret_cast<half2*>(&r1);\n            half2* hr2 = reinterpret_cast<half2*>(&r2);\n            while (col + 1 < num_coeffs_to_reduce) {\n              *hr1 = __halves2half2(\n                  input.m_impl.coeff(row * num_coeffs_to_reduce + col),\n                  input.m_impl.coeff(row * num_coeffs_to_reduce + col + 1));\n              *hr2 = __halves2half2(\n                  input.m_impl.coeff((row + 1) * num_coeffs_to_reduce + col),\n                  input.m_impl.coeff((row + 1) * num_coeffs_to_reduce + col +\n                                     1));\n              hr1++;\n              hr2++;\n              col += 2;\n            }\n            if (col < num_coeffs_to_reduce) {\n              // Peel;\n              const half last1 =\n                  input.m_impl.coeff(row * num_coeffs_to_reduce + col);\n              *hr1 = __halves2half2(last1, reducer.initialize());\n              const half last2 =\n                  input.m_impl.coeff((row + 1) * num_coeffs_to_reduce + col);\n              *hr2 = __halves2half2(last2, reducer.initialize());\n            }\n            reducer.reducePacket(r1, &reduced_val1);\n            reducer.reducePacket(r2, &reduced_val2);\n          }\n          break;\n        } else {\n          // Faster version of the loop with no branches after unrolling.\n#pragma unroll\n          for (int k = 0; k < unroll_times; ++k) {\n            const Index col = col_begin + blockDim.x * (j + k) * packet_width;\n            reducer.reducePacket(input.m_impl.template packet<Unaligned>(\n                                     row * num_coeffs_to_reduce + col),\n                                 &reduced_val1);\n            reducer.reducePacket(input.m_impl.template packet<Unaligned>(\n                                     (row + 1) * num_coeffs_to_reduce + col),\n                                 &reduced_val2);\n          }\n        }\n      }\n\n#pragma unroll\n      for (int offset = warpSize/2; offset > 0; offset /= 2) {\n      #if defined(EIGEN_HIPCC)\n        PacketType r1;\n        PacketType r2;\n        half2* hr1 = reinterpret_cast<half2*>(&r1);\n        half2* hr2 = reinterpret_cast<half2*>(&r2);\n        half2* rv1 = reinterpret_cast<half2*>(&reduced_val1);\n        half2* rv2 = reinterpret_cast<half2*>(&reduced_val2);\n        for (int i = 0; i < packet_width / 2; i++) {\n\t  // FIXME : remove this workaround once we have native half/half2 support for __shfl_down\n\t  union { int i; half2 h; } wka_in1, wka_out1;\n\t  wka_in1.h = rv1[i];\n\t  wka_out1.i = __shfl_down(wka_in1.i, offset, warpSize);\n\t  hr1[i] = wka_out1.h;\n\n\t  union { int i; half2 h; } wka_in2, wka_out2;\n\t  wka_in2.h = rv2[i];\n\t  wka_out2.i = __shfl_down(wka_in2.i, offset, warpSize);\n\t  hr2[i] = wka_out2.h;\n        }\n        reducer.reducePacket(r1, &reduced_val1);\n        reducer.reducePacket(r2, &reduced_val2);\n      #elif defined(EIGEN_CUDA_SDK_VER) && EIGEN_CUDA_SDK_VER < 90000\n        PacketType r1;\n        PacketType r2;\n        half2* hr1 = reinterpret_cast<half2*>(&r1);\n        half2* hr2 = reinterpret_cast<half2*>(&r2);\n        half2* rv1 = reinterpret_cast<half2*>(&reduced_val1);\n        half2* rv2 = reinterpret_cast<half2*>(&reduced_val2);\n        for (int i = 0; i < packet_width / 2; i++) {\n          hr1[i] = __shfl_down(rv1[i], offset, warpSize);\n          hr2[i] = __shfl_down(rv2[i], offset, warpSize);\n        }\n        reducer.reducePacket(r1, &reduced_val1);\n        reducer.reducePacket(r2, &reduced_val2);\n      #else\n        PacketType r1;\n        PacketType r2;\n        half2* hr1 = reinterpret_cast<half2*>(&r1);\n        half2* hr2 = reinterpret_cast<half2*>(&r2);\n        half2* rr1 = reinterpret_cast<half2*>(&reduced_val1);\n        half2* rr2 = reinterpret_cast<half2*>(&reduced_val2);\n        for (int i = 0; i < packet_width / 2; i++) {\n          hr1[i] =\n              __shfl_down_sync(0xFFFFFFFF, rr1[i], (unsigned)offset, warpSize);\n          hr2[i] =\n              __shfl_down_sync(0xFFFFFFFF, rr2[i], (unsigned)offset, warpSize);\n        }\n        reducer.reducePacket(r1, &reduced_val1);\n        reducer.reducePacket(r2, &reduced_val2);\n\n      #endif\n      }\n      half2* rv1 = reinterpret_cast<half2*>(&reduced_val1);\n      half2* rv2 = reinterpret_cast<half2*>(&reduced_val2);\n      half2 val;\n      if (packet_width > 2) {\n        reducer.reducePacket(rv1[2], rv1);\n        reducer.reducePacket(rv1[3], rv1 + 1);\n        reducer.reducePacket(rv1[1], rv1);\n        reducer.reducePacket(rv2[2], rv2);\n        reducer.reducePacket(rv2[3], rv2 + 1);\n        reducer.reducePacket(rv2[1], rv2);\n      }\n      half val1 = __low2half(*rv1);\n      reducer.reduce(__high2half(*rv1), &val1);\n      half val2 = __low2half(*rv2);\n      reducer.reduce(__high2half(*rv2), &val2);\n      val = __halves2half2(val1, val2);\n      if ((threadIdx.x & (warpSize - 1)) == 0) {\n        half* loc = output + row;\n        atomicReduce((half2*)loc, val, reducer);\n      }\n    }\n  }\n}\n\n#endif // EIGEN_HAS_GPU_FP16\n\ntemplate <typename Self, typename Op, typename OutputType, bool PacketAccess, typename Enabled = void>\nstruct InnerReductionLauncher {\n  static EIGEN_DEVICE_FUNC bool run(const Self&, Op&, const GpuDevice&, OutputType*, typename Self::Index, typename Self::Index) {\n    gpu_assert(false && \"Should only be called to reduce doubles, floats and half floats on a gpu device\");\n    return true;\n  }\n};\n\n// Specialization for float and double\ntemplate <typename Self, typename Op, typename OutputType, bool PacketAccess>\nstruct InnerReductionLauncher<\n  Self, Op, OutputType, PacketAccess,\n  typename internal::enable_if<\n    internal::is_same<float, OutputType>::value ||\n    internal::is_same<double, OutputType>::value,\n  void>::type> {\n  static bool run(const Self& self, Op& reducer, const GpuDevice& device, OutputType* output, typename Self::Index num_coeffs_to_reduce, typename Self::Index num_preserved_vals) {\n    typedef typename Self::Index Index;\n\n    const Index num_coeffs = num_coeffs_to_reduce * num_preserved_vals;\n    const int block_size = 256;\n    const int num_per_thread = 128;\n    const int dyn_blocks = divup<int>(num_coeffs, block_size * num_per_thread);\n    const int max_blocks = device.getNumGpuMultiProcessors() *\n                           device.maxGpuThreadsPerMultiProcessor() / block_size;\n    const int num_blocks = numext::mini<int>(max_blocks, dyn_blocks);\n\n    if (num_blocks > 1) {\n      // We initialize the outputs outside the reduction kernel when we can't be sure that there\n      // won't be a race conditions between multiple thread blocks.\n      const int dyn_blocks = divup<int>(num_preserved_vals, 1024);\n      const int max_blocks = device.getNumGpuMultiProcessors() *\n                           device.maxGpuThreadsPerMultiProcessor() / 1024;\n      const int num_blocks = numext::mini<int>(max_blocks, dyn_blocks);\n      LAUNCH_GPU_KERNEL((ReductionInitKernel<OutputType, Index>),\n                         num_blocks, 1024, 0, device, reducer.initialize(),\n                         num_preserved_vals, output);\n    }\n\n    LAUNCH_GPU_KERNEL((InnerReductionKernel<num_per_thread, Self, Op, Index>),\n                       num_blocks, block_size, 0, device, reducer, self, num_coeffs_to_reduce, num_preserved_vals, output);\n\n    return false;\n  }\n};\n\n#ifdef EIGEN_HAS_GPU_FP16\ntemplate <typename Self, typename Op>\nstruct InnerReductionLauncher<Self, Op, Eigen::half, false> {\n  static bool run(const Self&, Op&, const GpuDevice&, half*, typename Self::Index, typename Self::Index) {\n    gpu_assert(false && \"Should not be called since there is no packet accessor\");\n    return true;\n  }\n};\n\ntemplate <typename Self, typename Op>\nstruct InnerReductionLauncher<Self, Op, Eigen::half, true> {\n  static bool run(const Self& self, Op& reducer, const GpuDevice& device, half* output, typename Self::Index num_coeffs_to_reduce, typename Self::Index num_preserved_vals) {\n    typedef typename Self::Index Index;\n\n    if (num_preserved_vals % 2 != 0) {\n      // Not supported yet, revert to the slower code path\n      return true;\n    }\n\n    const Index num_coeffs = num_coeffs_to_reduce * num_preserved_vals;\n    const int block_size = /*256*/128;\n    const int num_per_thread = /*128*/64;\n    const int dyn_blocks = divup<int>(num_coeffs, block_size * num_per_thread);\n    const int max_blocks = device.getNumGpuMultiProcessors() *\n                           device.maxGpuThreadsPerMultiProcessor() / block_size;\n    const int num_blocks = numext::mini<int>(max_blocks, dyn_blocks);\n\n    if (num_blocks > 1) {\n      // We initialize the outputs outside the reduction kernel when we can't be sure that there\n      // won't be a race conditions between multiple thread blocks.\n      LAUNCH_GPU_KERNEL((ReductionInitKernelHalfFloat<Self, Op, Index>),\n                         1, 1, 0, device, reducer, self, num_preserved_vals, output);\n    }\n\n    LAUNCH_GPU_KERNEL((InnerReductionKernelHalfFloat<num_per_thread, Self, Op, Index>),\n                       num_blocks, block_size, 0, device, reducer, self, num_coeffs_to_reduce, num_preserved_vals, output);\n\n    return false;\n  }\n};\n#endif // EIGEN_HAS_GPU_FP16\n\n\ntemplate <typename Self, typename Op>\nstruct InnerReducer<Self, Op, GpuDevice> {\n  // Unfortunately nvidia doesn't support well exotic types such as complex,\n  // so reduce the scope of the optimized version of the code to the simple case\n  // of floats and half floats.\n#ifdef EIGEN_HAS_GPU_FP16\n  static const bool HasOptimizedImplementation = !Self::ReducerTraits::IsStateful &&\n      (internal::is_same<typename Self::CoeffReturnType, float>::value ||\n       internal::is_same<typename Self::CoeffReturnType, double>::value ||\n       (internal::is_same<typename Self::CoeffReturnType, Eigen::half>::value && reducer_traits<Op, GpuDevice>::PacketAccess));\n#else // EIGEN_HAS_GPU_FP16\n  static const bool HasOptimizedImplementation = !Self::ReducerTraits::IsStateful &&\n                                                 (internal::is_same<typename Self::CoeffReturnType, float>::value ||\n                                                  internal::is_same<typename Self::CoeffReturnType, double>::value);\n#endif // EIGEN_HAS_GPU_FP16\n\n  template <typename OutputType>\n  static bool run(const Self& self, Op& reducer, const GpuDevice& device, OutputType* output, typename Self::Index num_coeffs_to_reduce, typename Self::Index num_preserved_vals) {\n    gpu_assert(HasOptimizedImplementation && \"Should only be called on doubles, floats or half floats\");\n    const Index num_coeffs = array_prod(self.m_impl.dimensions());\n    // Don't crash when we're called with an input tensor of size 0.\n    if (num_coeffs == 0) {\n      return true;\n    }\n    // It's faster to use the usual code.\n    if (num_coeffs_to_reduce <= 128) {\n      return true;\n    }\n\n    return InnerReductionLauncher<Self, Op, OutputType, reducer_traits<Op, GpuDevice>::PacketAccess>::run(self, reducer, device, output, num_coeffs_to_reduce, num_preserved_vals);\n  }\n};\n\ntemplate <int NumPerThread, typename Self,\n          typename Reducer, typename Index>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void OuterReductionKernel(Reducer reducer, const Self input, Index num_coeffs_to_reduce, Index num_preserved_coeffs,\n                                     typename Self::CoeffReturnType* output) {\n  const Index num_threads = blockDim.x * gridDim.x;\n  const Index thread_id = blockIdx.x * blockDim.x + threadIdx.x;\n  // Initialize the output values if they weren't initialized by the ReductionInitKernel\n  if (gridDim.x == 1) {\n    for (Index i = thread_id; i < num_preserved_coeffs; i += num_threads) {\n      output[i] = reducer.initialize();\n    }\n    __syncthreads();\n  }\n\n  // Do the reduction.\n  const Index max_iter = num_preserved_coeffs * divup<Index>(num_coeffs_to_reduce, NumPerThread);\n  for (Index i = thread_id; i < max_iter; i += num_threads) {\n    const Index input_col = i % num_preserved_coeffs;\n    const Index input_row = (i / num_preserved_coeffs) * NumPerThread;\n    typename Self::CoeffReturnType reduced_val = reducer.initialize();\n    const Index max_row = numext::mini(input_row + NumPerThread, num_coeffs_to_reduce);\n    for (Index j = input_row; j < max_row; j++) {\n      typename Self::CoeffReturnType val = input.m_impl.coeff(j * num_preserved_coeffs + input_col);\n      reducer.reduce(val, &reduced_val);\n    }\n    atomicReduce(&(output[input_col]), reduced_val, reducer);\n  }\n}\n\n\ntemplate <typename Self, typename Op>\nstruct OuterReducer<Self, Op, GpuDevice> {\n  // Unfortunately nvidia doesn't support well exotic types such as complex,\n  // so reduce the scope of the optimized version of the code to the simple case\n  // of floats.\n  static const bool HasOptimizedImplementation = !Self::ReducerTraits::IsStateful &&\n                                                 (internal::is_same<typename Self::CoeffReturnType, float>::value ||\n                                                  internal::is_same<typename Self::CoeffReturnType, double>::value);\n  template <typename Device, typename OutputType>\n  static\n    #if !defined(EIGEN_HIPCC)\n    // FIXME :  leaving this EIGEN_DEVICE_FUNC in, results in the following runtime error\n    //          (in the cxx11_tensor_reduction_gpu test)\n    //\n    // terminate called after throwing an instance of 'std::runtime_error'\n    //   what():  No device code available for function: _ZN5Eigen8internal20OuterReductionKernelIL...\n    //\n    // don't know why this happens (and why is it a runtime error instead of a compile time error)\n    //\n    // this will be fixed by HIP PR#457\n    EIGEN_DEVICE_FUNC\n    #endif\n    bool run(const Self&, Op&, const Device&, OutputType*, typename Self::Index, typename Self::Index) {\n    gpu_assert(false && \"Should only be called to reduce doubles or floats on a gpu device\");\n    return true;\n  }\n\n  static bool run(const Self& self, Op& reducer, const GpuDevice& device, float* output, typename Self::Index num_coeffs_to_reduce, typename Self::Index num_preserved_vals) {\n    typedef typename Self::Index Index;\n\n    // It's faster to use the usual code.\n    if (num_coeffs_to_reduce <= 32) {\n      return true;\n    }\n\n    const Index num_coeffs = num_coeffs_to_reduce * num_preserved_vals;\n    const int block_size = 256;\n    const int num_per_thread = 16;\n    const int dyn_blocks = divup<int>(num_coeffs, block_size * num_per_thread);\n    const int max_blocks = device.getNumGpuMultiProcessors() *\n                           device.maxGpuThreadsPerMultiProcessor() / block_size;\n    const int num_blocks = numext::mini<int>(max_blocks, dyn_blocks);\n\n    if (num_blocks > 1) {\n      // We initialize the outputs in the reduction kernel itself when we don't have to worry\n      // about race conditions between multiple thread blocks.\n      const int dyn_blocks = divup<int>(num_preserved_vals, 1024);\n      const int max_blocks = device.getNumGpuMultiProcessors() *\n                             device.maxGpuThreadsPerMultiProcessor() / 1024;\n      const int num_blocks = numext::mini<int>(max_blocks, dyn_blocks);\n      LAUNCH_GPU_KERNEL((ReductionInitKernel<float, Index>),\n                         num_blocks, 1024, 0, device, reducer.initialize(),\n                         num_preserved_vals, output);\n    }\n\n    LAUNCH_GPU_KERNEL((OuterReductionKernel<num_per_thread, Self, Op, Index>),\n                       num_blocks, block_size, 0, device, reducer, self, num_coeffs_to_reduce, num_preserved_vals, output);\n\n    return false;\n  }\n};\n\n#endif // defined(EIGEN_USE_GPU) && defined(EIGEN_GPUCC)\n\n\n} // end namespace internal\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_GPU_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReductionSycl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/*****************************************************************\n * TensorReductionSycl.h\n *\n * \\brief:\n *  This is the specialization of the reduction operation. Two phase reduction approach \n * is used since the GPU does not have Global Synchronization for global memory among \n * different work-group/thread block. To solve the problem, we need to create two kernels \n * to reduce the data, where the first kernel reduce the data locally and each local \n * workgroup/thread-block save the input data into global memory. In the second phase (global reduction)\n * one work-group uses one work-group/thread-block to reduces the intermediate data into one single element. \n * Here is an NVIDIA presentation explaining the optimized two phase reduction algorithm on GPU:\n * https://developer.download.nvidia.com/assets/cuda/files/reduction.pdf\n *\n *****************************************************************/\n\n#ifndef UNSUPPORTED_EIGEN_CXX11_SRC_TENSOR_TENSOR_REDUCTION_SYCL_HPP\n#define UNSUPPORTED_EIGEN_CXX11_SRC_TENSOR_TENSOR_REDUCTION_SYCL_HPP\nnamespace Eigen {\nnamespace TensorSycl {\nnamespace internal {\n\ntemplate <typename Op, typename CoeffReturnType, typename Index, bool Vectorizable>\nstruct OpDefiner {\n  typedef typename Vectorise<CoeffReturnType, Eigen::SyclDevice, Vectorizable>::PacketReturnType PacketReturnType;\n  typedef Op type;\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE type get_op(Op &op) { return op; }\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType finalise_op(const PacketReturnType &accumulator,\n                                                                            const Index &) {\n    return accumulator;\n  }\n};\n\ntemplate <typename CoeffReturnType, typename Index>\nstruct OpDefiner<Eigen::internal::MeanReducer<CoeffReturnType>, CoeffReturnType, Index, false> {\n  typedef Eigen::internal::SumReducer<CoeffReturnType> type;\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE type get_op(Eigen::internal::MeanReducer<CoeffReturnType> &) {\n    return type();\n  }\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType finalise_op(const CoeffReturnType &accumulator,\n                                                                           const Index &scale) {\n    ::Eigen::internal::scalar_quotient_op<CoeffReturnType> quotient_op;\n    return quotient_op(accumulator, CoeffReturnType(scale));\n  }\n};\n\ntemplate <typename CoeffReturnType, typename Index>\nstruct OpDefiner<Eigen::internal::MeanReducer<CoeffReturnType>, CoeffReturnType, Index, true> {\n  typedef typename Vectorise<CoeffReturnType, Eigen::SyclDevice, true>::PacketReturnType PacketReturnType;\n  typedef Eigen::internal::SumReducer<CoeffReturnType> type;\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE type get_op(Eigen::internal::MeanReducer<CoeffReturnType> &) {\n    return type();\n  }\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType finalise_op(const PacketReturnType &accumulator,\n                                                                            const Index &scale) {\n    return ::Eigen::internal::pdiv(accumulator, ::Eigen::internal::pset1<PacketReturnType>(CoeffReturnType(scale)));\n  }\n};\n\ntemplate <typename CoeffReturnType, typename OpType, typename InputAccessor, typename OutputAccessor, typename Index,\n          Index local_range>\nstruct SecondStepFullReducer {\n  typedef cl::sycl::accessor<CoeffReturnType, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local>\n      LocalAccessor;\n  typedef OpDefiner<OpType, CoeffReturnType, Index, true> OpDef;\n  typedef typename OpDef::type Op;\n  LocalAccessor scratch;\n  InputAccessor aI;\n  OutputAccessor outAcc;\n  Op op;\n  SecondStepFullReducer(LocalAccessor scratch_, InputAccessor aI_, OutputAccessor outAcc_, OpType op_)\n      : scratch(scratch_), aI(aI_), outAcc(outAcc_), op(OpDef::get_op(op_)) {}\n\n  void operator()(cl::sycl::nd_item<1> itemID) {\n    // Our empirical research shows that the best performance will be achieved\n    // when there is only one element per thread to reduce in the second step.\n    // in this step the second step reduction time is almost negligible.\n    // Hence, in the second step of reduction the input size is fixed to the\n    // local size, thus, there is only one element read per thread. The\n    // algorithm must be changed if the number of reduce per thread in the\n    // second step is greater than 1. Otherwise, the result will be wrong.\n    const Index localid = itemID.get_local_id(0);\n    auto aInPtr = aI.get_pointer() + localid;\n    auto aOutPtr = outAcc.get_pointer();\n    CoeffReturnType *scratchptr = scratch.get_pointer();\n    CoeffReturnType accumulator = *aInPtr;\n\n    scratchptr[localid] = op.finalize(accumulator);\n    for (Index offset = itemID.get_local_range(0) / 2; offset > 0; offset /= 2) {\n      itemID.barrier(cl::sycl::access::fence_space::local_space);\n      if (localid < offset) {\n        op.reduce(scratchptr[localid + offset], &accumulator);\n        scratchptr[localid] = op.finalize(accumulator);\n      }\n    }\n    if (localid == 0) *aOutPtr = op.finalize(accumulator);\n  }\n};\n\n// Full reduction first phase. In this version the vectorization is true and the reduction accept \n// any generic reducerOp  e.g( max, min, sum, mean, iamax, iamin, etc ). \ntemplate <typename Evaluator, typename OpType, typename Evaluator::Index local_range>\nclass FullReductionKernelFunctor {\n public:\n  typedef typename Evaluator::CoeffReturnType CoeffReturnType;\n  typedef typename Evaluator::Index Index;\n  typedef OpDefiner<OpType, typename Evaluator::CoeffReturnType, Index,\n                    (Evaluator::ReducerTraits::PacketAccess & Evaluator::InputPacketAccess)>\n      OpDef;\n\n  typedef typename OpDef::type Op;\n  typedef typename Evaluator::EvaluatorPointerType EvaluatorPointerType;\n  typedef typename Evaluator::PacketReturnType PacketReturnType;\n  typedef\n      typename ::Eigen::internal::conditional<(Evaluator::ReducerTraits::PacketAccess & Evaluator::InputPacketAccess),\n                                              PacketReturnType, CoeffReturnType>::type OutType;\n  typedef cl::sycl::accessor<OutType, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local>\n      LocalAccessor;\n  LocalAccessor scratch;\n  Evaluator evaluator;\n  EvaluatorPointerType final_output;\n  Index rng;\n  Op op;\n\n  FullReductionKernelFunctor(LocalAccessor scratch_, Evaluator evaluator_, EvaluatorPointerType final_output_,\n                             Index rng_, OpType op_)\n      : scratch(scratch_), evaluator(evaluator_), final_output(final_output_), rng(rng_), op(OpDef::get_op(op_)) {}\n\n  void operator()(cl::sycl::nd_item<1> itemID) { compute_reduction(itemID); }\n\n  template <bool Vect = (Evaluator::ReducerTraits::PacketAccess & Evaluator::InputPacketAccess)>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename ::Eigen::internal::enable_if<Vect>::type compute_reduction(\n      const cl::sycl::nd_item<1> &itemID) {\n    auto output_ptr = final_output.get_pointer();\n    Index VectorizedRange = (rng / Evaluator::PacketSize) * Evaluator::PacketSize;\n    Index globalid = itemID.get_global_id(0);\n    Index localid = itemID.get_local_id(0);\n    Index step = Evaluator::PacketSize * itemID.get_global_range(0);\n    Index start = Evaluator::PacketSize * globalid;\n    // vectorizable parts\n    PacketReturnType packetAccumulator = op.template initializePacket<PacketReturnType>();\n    for (Index i = start; i < VectorizedRange; i += step) {\n      op.template reducePacket<PacketReturnType>(evaluator.impl().template packet<Unaligned>(i), &packetAccumulator);\n    }\n    globalid += VectorizedRange;\n    // non vectorizable parts\n    for (Index i = globalid; i < rng; i += itemID.get_global_range(0)) {\n      op.template reducePacket<PacketReturnType>(\n          ::Eigen::TensorSycl::internal::PacketWrapper<PacketReturnType, Evaluator::PacketSize>::convert_to_packet_type(\n              evaluator.impl().coeff(i), op.initialize()),\n          &packetAccumulator);\n    }\n    scratch[localid] = packetAccumulator =\n        OpDef::finalise_op(op.template finalizePacket<PacketReturnType>(packetAccumulator), rng);\n    // reduction parts // Local size is always power of 2\n    EIGEN_UNROLL_LOOP\n    for (Index offset = local_range / 2; offset > 0; offset /= 2) {\n      itemID.barrier(cl::sycl::access::fence_space::local_space);\n      if (localid < offset) {\n        op.template reducePacket<PacketReturnType>(scratch[localid + offset], &packetAccumulator);\n        scratch[localid] = op.template finalizePacket<PacketReturnType>(packetAccumulator);\n      }\n    }\n    if (localid == 0) {\n      output_ptr[itemID.get_group(0)] =\n          op.finalizeBoth(op.initialize(), op.template finalizePacket<PacketReturnType>(packetAccumulator));\n    }\n  }\n\n  template <bool Vect = (Evaluator::ReducerTraits::PacketAccess & Evaluator::InputPacketAccess)>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename ::Eigen::internal::enable_if<!Vect>::type compute_reduction(\n      const cl::sycl::nd_item<1> &itemID) {\n    auto output_ptr = final_output.get_pointer();\n    Index globalid = itemID.get_global_id(0);\n    Index localid = itemID.get_local_id(0);\n    // vectorizable parts\n    CoeffReturnType accumulator = op.initialize();\n    // non vectorizable parts\n    for (Index i = globalid; i < rng; i += itemID.get_global_range(0)) {\n      op.reduce(evaluator.impl().coeff(i), &accumulator);\n    }\n    scratch[localid] = accumulator = OpDef::finalise_op(op.finalize(accumulator), rng);\n\n    // reduction parts. the local size is always power of 2\n    EIGEN_UNROLL_LOOP\n    for (Index offset = local_range / 2; offset > 0; offset /= 2) {\n      itemID.barrier(cl::sycl::access::fence_space::local_space);\n      if (localid < offset) {\n        op.reduce(scratch[localid + offset], &accumulator);\n        scratch[localid] = op.finalize(accumulator);\n      }\n    }\n    if (localid == 0) {\n      output_ptr[itemID.get_group(0)] = op.finalize(accumulator);\n    }\n  }\n};\n\ntemplate <typename Evaluator, typename OpType>\nclass GenericNondeterministicReducer {\n public:\n  typedef typename Evaluator::CoeffReturnType CoeffReturnType;\n  typedef typename Evaluator::EvaluatorPointerType EvaluatorPointerType;\n  typedef typename Evaluator::Index Index;\n  typedef OpDefiner<OpType, CoeffReturnType, Index, false> OpDef;\n  typedef typename OpDef::type Op;\n  template <typename Scratch>\n  GenericNondeterministicReducer(Scratch, Evaluator evaluator_, EvaluatorPointerType output_accessor_, OpType functor_,\n                       Index range_, Index num_values_to_reduce_)\n      : evaluator(evaluator_),\n        output_accessor(output_accessor_),\n        functor(OpDef::get_op(functor_)),\n        range(range_),\n        num_values_to_reduce(num_values_to_reduce_) {}\n\n  void operator()(cl::sycl::nd_item<1> itemID) {\n    auto output_accessor_ptr = output_accessor.get_pointer();\n    /// const cast added as a naive solution to solve the qualifier drop error\n    Index globalid = static_cast<Index>(itemID.get_global_linear_id());\n    if (globalid < range) {\n      CoeffReturnType accum = functor.initialize();\n      Eigen::internal::GenericDimReducer<Evaluator::NumReducedDims - 1, Evaluator, Op>::reduce(\n          evaluator, evaluator.firstInput(globalid), functor, &accum);\n      output_accessor_ptr[globalid] = OpDef::finalise_op(functor.finalize(accum), num_values_to_reduce);\n    }\n  }\n\n private:\n  Evaluator evaluator;\n  EvaluatorPointerType output_accessor;\n  Op functor;\n  Index range;\n  Index num_values_to_reduce;\n};\n\nenum class reduction_dim { inner_most, outer_most };\n// default is preserver\ntemplate <typename Evaluator, typename OpType, typename PannelParameters, reduction_dim rt>\nstruct PartialReductionKernel {\n  typedef typename Evaluator::CoeffReturnType CoeffReturnType;\n  typedef typename Evaluator::EvaluatorPointerType EvaluatorPointerType;\n  typedef typename Evaluator::Index Index;\n  typedef OpDefiner<OpType, CoeffReturnType, Index, false> OpDef;\n  typedef typename OpDef::type Op;\n  typedef cl::sycl::accessor<CoeffReturnType, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local>\n      ScratchAcc;\n  ScratchAcc scratch;\n  Evaluator evaluator;\n  EvaluatorPointerType output_accessor;\n  Op op;\n  const Index preserve_elements_num_groups;\n  const Index reduce_elements_num_groups;\n  const Index num_coeffs_to_preserve;\n  const Index num_coeffs_to_reduce;\n\n  PartialReductionKernel(ScratchAcc scratch_, Evaluator evaluator_, EvaluatorPointerType output_accessor_, OpType op_,\n                         const Index preserve_elements_num_groups_, const Index reduce_elements_num_groups_,\n                         const Index num_coeffs_to_preserve_, const Index num_coeffs_to_reduce_)\n      : scratch(scratch_),\n        evaluator(evaluator_),\n        output_accessor(output_accessor_),\n        op(OpDef::get_op(op_)),\n        preserve_elements_num_groups(preserve_elements_num_groups_),\n        reduce_elements_num_groups(reduce_elements_num_groups_),\n        num_coeffs_to_preserve(num_coeffs_to_preserve_),\n        num_coeffs_to_reduce(num_coeffs_to_reduce_) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void element_wise_reduce(Index globalRId, Index globalPId,\n                                                                 CoeffReturnType &accumulator) {\n    if (globalPId >= num_coeffs_to_preserve) {\n      return;\n    }\n    Index global_offset = rt == reduction_dim::outer_most ? globalPId + (globalRId * num_coeffs_to_preserve)\n                                                          : globalRId + (globalPId * num_coeffs_to_reduce);\n    Index localOffset = globalRId;\n\n    const Index per_thread_local_stride = PannelParameters::LocalThreadSizeR * reduce_elements_num_groups;\n    const Index per_thread_global_stride =\n        rt == reduction_dim::outer_most ? num_coeffs_to_preserve * per_thread_local_stride : per_thread_local_stride;\n    for (Index i = globalRId; i < num_coeffs_to_reduce; i += per_thread_local_stride) {\n      op.reduce(evaluator.impl().coeff(global_offset), &accumulator);\n      localOffset += per_thread_local_stride;\n      global_offset += per_thread_global_stride;\n    }\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void operator()(cl::sycl::nd_item<1> itemID) {\n    const Index linearLocalThreadId = itemID.get_local_id(0);\n    Index pLocalThreadId = rt == reduction_dim::outer_most ? linearLocalThreadId % PannelParameters::LocalThreadSizeP\n                                                           : linearLocalThreadId / PannelParameters::LocalThreadSizeR;\n    Index rLocalThreadId = rt == reduction_dim::outer_most ? linearLocalThreadId / PannelParameters::LocalThreadSizeP\n                                                           : linearLocalThreadId % PannelParameters::LocalThreadSizeR;\n    const Index pGroupId = rt == reduction_dim::outer_most ? itemID.get_group(0) % preserve_elements_num_groups\n                                                           : itemID.get_group(0) / reduce_elements_num_groups;\n    const Index rGroupId = rt == reduction_dim::outer_most ? itemID.get_group(0) / preserve_elements_num_groups\n                                                           : itemID.get_group(0) % reduce_elements_num_groups;\n\n    Index globalPId = pGroupId * PannelParameters::LocalThreadSizeP + pLocalThreadId;\n    const Index globalRId = rGroupId * PannelParameters::LocalThreadSizeR + rLocalThreadId;\n    auto scratchPtr = scratch.get_pointer().get();\n    auto outPtr =\n        output_accessor.get_pointer() + (reduce_elements_num_groups > 1 ? rGroupId * num_coeffs_to_preserve : 0);\n    CoeffReturnType accumulator = op.initialize();\n\n    element_wise_reduce(globalRId, globalPId, accumulator);\n\n    accumulator = OpDef::finalise_op(op.finalize(accumulator), num_coeffs_to_reduce);\n    scratchPtr[pLocalThreadId + rLocalThreadId * (PannelParameters::LocalThreadSizeP + PannelParameters::BC)] =\n        accumulator;\n    if (rt == reduction_dim::inner_most) {\n      pLocalThreadId = linearLocalThreadId % PannelParameters::LocalThreadSizeP;\n      rLocalThreadId = linearLocalThreadId / PannelParameters::LocalThreadSizeP;\n      globalPId = pGroupId * PannelParameters::LocalThreadSizeP + pLocalThreadId;\n    }\n\n    /* Apply the reduction operation between the current local\n     * id and the one on the other half of the vector. */\n    auto out_scratch_ptr =\n        scratchPtr + (pLocalThreadId + (rLocalThreadId * (PannelParameters::LocalThreadSizeP + PannelParameters::BC)));\n    itemID.barrier(cl::sycl::access::fence_space::local_space);\n    if (rt == reduction_dim::inner_most) {\n      accumulator = *out_scratch_ptr;\n    }\n    // The Local LocalThreadSizeR is always power of 2\n    EIGEN_UNROLL_LOOP\n    for (Index offset = PannelParameters::LocalThreadSizeR >> 1; offset > 0; offset >>= 1) {\n      if (rLocalThreadId < offset) {\n        op.reduce(out_scratch_ptr[(PannelParameters::LocalThreadSizeP + PannelParameters::BC) * offset], &accumulator);\n        // The result has already been divided for mean reducer in the\n        // previous reduction so no need to divide furthermore\n        *out_scratch_ptr = op.finalize(accumulator);\n      }\n      /* All threads collectively read from global memory into local.\n       * The barrier ensures all threads' IO is resolved before\n       * execution continues (strictly speaking, all threads within\n       * a single work-group - there is no co-ordination between\n       * work-groups, only work-items). */\n      itemID.barrier(cl::sycl::access::fence_space::local_space);\n    }\n\n    if (rLocalThreadId == 0 && (globalPId < num_coeffs_to_preserve)) {\n      outPtr[globalPId] = op.finalize(accumulator);\n    }\n  }\n};\n\ntemplate <typename OutScalar, typename Index, typename InputAccessor, typename OutputAccessor, typename OpType>\nstruct SecondStepPartialReduction {\n  typedef OpDefiner<OpType, OutScalar, Index, false> OpDef;\n  typedef typename OpDef::type Op;\n  typedef cl::sycl::accessor<OutScalar, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local>\n      ScratchAccessor;\n  InputAccessor input_accessor;\n  OutputAccessor output_accessor;\n  Op op;\n  const Index num_coeffs_to_preserve;\n  const Index num_coeffs_to_reduce;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE SecondStepPartialReduction(ScratchAccessor, InputAccessor input_accessor_,\n                                                                   OutputAccessor output_accessor_, OpType op_,\n                                                                   const Index num_coeffs_to_preserve_,\n                                                                   const Index num_coeffs_to_reduce_)\n      : input_accessor(input_accessor_),\n        output_accessor(output_accessor_),\n        op(OpDef::get_op(op_)),\n        num_coeffs_to_preserve(num_coeffs_to_preserve_),\n        num_coeffs_to_reduce(num_coeffs_to_reduce_) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void operator()(cl::sycl::nd_item<1> itemID) {\n    const Index globalId = itemID.get_global_id(0);\n\n    if (globalId >= num_coeffs_to_preserve) return;\n\n    auto in_ptr = input_accessor.get_pointer() + globalId;\n\n    OutScalar accumulator = op.initialize();\n// num_coeffs_to_reduce is not bigger that 256\n    for (Index i = 0; i < num_coeffs_to_reduce; i++) {\n      op.reduce(*in_ptr, &accumulator);\n      in_ptr += num_coeffs_to_preserve;\n    }\n    output_accessor.get_pointer()[globalId] = op.finalize(accumulator);\n  }\n};  // namespace internal\n\ntemplate <typename Index, Index LTP, Index LTR, bool BC_>\nstruct ReductionPannel {\n  static EIGEN_CONSTEXPR Index LocalThreadSizeP = LTP;\n  static EIGEN_CONSTEXPR Index LocalThreadSizeR = LTR;\n  static EIGEN_CONSTEXPR bool BC = BC_;\n};\n\ntemplate <typename Self, typename Op, TensorSycl::internal::reduction_dim rt>\nstruct PartialReducerLauncher {\n  typedef typename Self::EvaluatorPointerType EvaluatorPointerType;\n  typedef typename Self::CoeffReturnType CoeffReturnType;\n  typedef typename Self::Storage Storage;\n  typedef typename Self::Index Index;\n  typedef ReductionPannel<typename Self::Index, EIGEN_SYCL_LOCAL_THREAD_DIM0, EIGEN_SYCL_LOCAL_THREAD_DIM1, true>\n      PannelParameters;\n\n  typedef PartialReductionKernel<Self, Op, PannelParameters, rt> SyclReducerKerneType;\n\n  static bool run(const Self &self, const Op &reducer, const Eigen::SyclDevice &dev, EvaluatorPointerType output,\n                  Index num_coeffs_to_reduce, Index num_coeffs_to_preserve) {\n    Index roundUpP = roundUp(num_coeffs_to_preserve, PannelParameters::LocalThreadSizeP);\n\n    // getPowerOfTwo makes sure local range is power of 2 and <=\n    // maxSyclThreadPerBlock this will help us to avoid extra check on the\n    // kernel\n    static_assert(!((PannelParameters::LocalThreadSizeP * PannelParameters::LocalThreadSizeR) &\n                    (PannelParameters::LocalThreadSizeP * PannelParameters::LocalThreadSizeR - 1)),\n                  \"The Local thread size must be a power of 2 for the reduction \"\n                  \"operation\");\n\n    EIGEN_CONSTEXPR Index localRange = PannelParameters::LocalThreadSizeP * PannelParameters::LocalThreadSizeR;\n    // In this step, we force the code not to be more than 2-step reduction:\n    // Our empirical research shows that if each thread reduces at least 64\n    // elemnts individually, we get better performance. However, this can change\n    // on different platforms. In this step we force the code not to be\n    // morthan step reduction: Our empirical research shows that for inner_most\n    // dim reducer, it is better to have 8 group in a reduce dimension for sizes\n    // > 1024 to achieve the best performance.\n    const Index reductionPerThread = 64;\n    Index cu = dev.getPowerOfTwo(dev.getNumSyclMultiProcessors(), true);\n    const Index pNumGroups = roundUpP / PannelParameters::LocalThreadSizeP;\n    Index rGroups = (cu + pNumGroups - 1) / pNumGroups;\n    const Index rNumGroups = num_coeffs_to_reduce > reductionPerThread * localRange ? std::min(rGroups, localRange) : 1;\n    const Index globalRange = pNumGroups * rNumGroups * localRange;\n\n    EIGEN_CONSTEXPR Index scratchSize =\n        PannelParameters::LocalThreadSizeR * (PannelParameters::LocalThreadSizeP + PannelParameters::BC);\n    auto thread_range = cl::sycl::nd_range<1>(cl::sycl::range<1>(globalRange), cl::sycl::range<1>(localRange));\n    if (rNumGroups > 1) {\n      CoeffReturnType *temp_pointer = static_cast<CoeffReturnType *>(\n          dev.allocate_temp(num_coeffs_to_preserve * rNumGroups * sizeof(CoeffReturnType)));\n      EvaluatorPointerType temp_accessor = dev.get(temp_pointer);\n      dev.template unary_kernel_launcher<CoeffReturnType, SyclReducerKerneType>(\n          self, temp_accessor, thread_range, scratchSize, reducer, pNumGroups, rNumGroups, num_coeffs_to_preserve,\n          num_coeffs_to_reduce);\n\n      typedef SecondStepPartialReduction<CoeffReturnType, Index, EvaluatorPointerType, EvaluatorPointerType, Op>\n          SecondStepPartialReductionKernel;\n\n      dev.template unary_kernel_launcher<CoeffReturnType, SecondStepPartialReductionKernel>(\n          temp_accessor, output,\n          cl::sycl::nd_range<1>(cl::sycl::range<1>(pNumGroups * localRange), cl::sycl::range<1>(localRange)), Index(1),\n          reducer, num_coeffs_to_preserve, rNumGroups);\n\n      self.device().deallocate_temp(temp_pointer);\n    } else {\n      dev.template unary_kernel_launcher<CoeffReturnType, SyclReducerKerneType>(\n          self, output, thread_range, scratchSize, reducer, pNumGroups, rNumGroups, num_coeffs_to_preserve,\n          num_coeffs_to_reduce);\n    }\n    return false;\n  }\n};\n}  // namespace internal\n}  // namespace TensorSycl\n\nnamespace internal {\n\ntemplate <typename Self, typename Op, bool Vectorizable>\nstruct FullReducer<Self, Op, Eigen::SyclDevice, Vectorizable> {\n  typedef typename Self::CoeffReturnType CoeffReturnType;\n  typedef typename Self::EvaluatorPointerType EvaluatorPointerType;\n  static EIGEN_CONSTEXPR bool HasOptimizedImplementation = true;\n  static EIGEN_CONSTEXPR int PacketSize = Self::PacketAccess ? Self::PacketSize : 1;\n  static void run(const Self &self, Op &reducer, const Eigen::SyclDevice &dev, EvaluatorPointerType data) {\n    typedef typename conditional<Self::PacketAccess, typename Self::PacketReturnType, CoeffReturnType>::type OutType;\n    static_assert(!((EIGEN_SYCL_LOCAL_THREAD_DIM0 * EIGEN_SYCL_LOCAL_THREAD_DIM1) &\n                    (EIGEN_SYCL_LOCAL_THREAD_DIM0 * EIGEN_SYCL_LOCAL_THREAD_DIM1 - 1)),\n                  \"The Local thread size must be a power of 2 for the reduction \"\n                  \"operation\");\n    EIGEN_CONSTEXPR Index local_range = EIGEN_SYCL_LOCAL_THREAD_DIM0 * EIGEN_SYCL_LOCAL_THREAD_DIM1;\n\n    typename Self::Index inputSize = self.impl().dimensions().TotalSize();\n    // In this step we force the code not to be more than 2-step reduction:\n    // Our empirical research shows that if each thread reduces at least 512\n    // elemnts individually, we get better performance.\n    const Index reductionPerThread = 2048;\n    // const Index num_work_group =\n    Index reductionGroup = dev.getPowerOfTwo(\n        (inputSize + (reductionPerThread * local_range - 1)) / (reductionPerThread * local_range), true);\n    const Index num_work_group = std::min(reductionGroup, local_range);\n    // 1\n    // ? local_range\n    // : 1);\n    const Index global_range = num_work_group * local_range;\n\n    auto thread_range = cl::sycl::nd_range<1>(cl::sycl::range<1>(global_range), cl::sycl::range<1>(local_range));\n    typedef TensorSycl::internal::FullReductionKernelFunctor<Self, Op, local_range> reduction_kernel_t;\n    if (num_work_group > 1) {\n      CoeffReturnType *temp_pointer =\n          static_cast<CoeffReturnType *>(dev.allocate_temp(num_work_group * sizeof(CoeffReturnType)));\n      typename Self::EvaluatorPointerType tmp_global_accessor = dev.get(temp_pointer);\n      dev.template unary_kernel_launcher<OutType, reduction_kernel_t>(self, tmp_global_accessor, thread_range,\n                                                                      local_range, inputSize, reducer);\n\n      typedef TensorSycl::internal::SecondStepFullReducer<CoeffReturnType, Op, EvaluatorPointerType,\n                                                          EvaluatorPointerType, Index, local_range>\n          GenericRKernel;\n      dev.template unary_kernel_launcher<CoeffReturnType, GenericRKernel>(\n          tmp_global_accessor, data,\n          cl::sycl::nd_range<1>(cl::sycl::range<1>(num_work_group), cl::sycl::range<1>(num_work_group)), num_work_group,\n          reducer);\n\n      dev.deallocate_temp(temp_pointer);\n    } else {\n      dev.template unary_kernel_launcher<OutType, reduction_kernel_t>(self, data, thread_range, local_range, inputSize,\n                                                                      reducer);\n    }\n  }\n};\n// vectorizable inner_most most dim preserver\n// col reduction\ntemplate <typename Self, typename Op>\nstruct OuterReducer<Self, Op, Eigen::SyclDevice> {\n  static EIGEN_CONSTEXPR bool HasOptimizedImplementation = true;\n\n  static bool run(const Self &self, const Op &reducer, const Eigen::SyclDevice &dev,\n                  typename Self::EvaluatorPointerType output, typename Self::Index num_coeffs_to_reduce,\n                  typename Self::Index num_coeffs_to_preserve) {\n    return ::Eigen::TensorSycl::internal::PartialReducerLauncher<\n        Self, Op, ::Eigen::TensorSycl::internal::reduction_dim::outer_most>::run(self, reducer, dev, output,\n                                                                                 num_coeffs_to_reduce,\n                                                                                 num_coeffs_to_preserve);\n  }\n};\n// row reduction\ntemplate <typename Self, typename Op>\nstruct InnerReducer<Self, Op, Eigen::SyclDevice> {\n  static EIGEN_CONSTEXPR bool HasOptimizedImplementation = true;\n\n  static bool run(const Self &self, const Op &reducer, const Eigen::SyclDevice &dev,\n                  typename Self::EvaluatorPointerType output, typename Self::Index num_coeffs_to_reduce,\n                  typename Self::Index num_coeffs_to_preserve) {\n    return ::Eigen::TensorSycl::internal::PartialReducerLauncher<\n        Self, Op, ::Eigen::TensorSycl::internal::reduction_dim::inner_most>::run(self, reducer, dev, output,\n                                                                                 num_coeffs_to_reduce,\n                                                                                 num_coeffs_to_preserve);\n  }\n};\n\n// ArmgMax uses this kernel for partial reduction//\n// TODO(@mehdi.goli) come up with a better kernel\n// generic partial reduction\ntemplate <typename Self, typename Op>\nstruct GenericReducer<Self, Op, Eigen::SyclDevice> {\n  static EIGEN_CONSTEXPR bool HasOptimizedImplementation = false;\n  static bool run(const Self &self, const Op &reducer, const Eigen::SyclDevice &dev,\n                  typename Self::EvaluatorPointerType output, typename Self::Index num_values_to_reduce,\n                  typename Self::Index num_coeffs_to_preserve) {\n    typename Self::Index range, GRange, tileSize;\n    dev.parallel_for_setup(num_coeffs_to_preserve, tileSize, range, GRange);\n\n    dev.template unary_kernel_launcher<typename Self::CoeffReturnType,\n                                       TensorSycl::internal::GenericNondeterministicReducer<Self, Op>>(\n        self, output, cl::sycl::nd_range<1>(cl::sycl::range<1>(GRange), cl::sycl::range<1>(tileSize)), Index(1),\n        reducer, range, (num_values_to_reduce != 0) ? num_values_to_reduce : static_cast<Index>(1));\n    return false;\n  }\n};\n\n}  // namespace internal\n}  // namespace Eigen\n\n#endif  // UNSUPPORTED_EIGEN_CXX11_SRC_TENSOR_TENSOR_REDUCTION_SYCL_HPP\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorRef.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_REF_H\n#define EIGEN_CXX11_TENSOR_TENSOR_REF_H\n\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate <typename Dimensions, typename Scalar>\nclass TensorLazyBaseEvaluator {\n public:\n  TensorLazyBaseEvaluator() : m_refcount(0) { }\n  virtual ~TensorLazyBaseEvaluator() { }\n\n  EIGEN_DEVICE_FUNC virtual const Dimensions& dimensions() const = 0;\n  EIGEN_DEVICE_FUNC virtual const Scalar* data() const = 0;\n\n  EIGEN_DEVICE_FUNC virtual const Scalar coeff(DenseIndex index) const = 0;\n  EIGEN_DEVICE_FUNC virtual Scalar& coeffRef(DenseIndex index) = 0;\n\n  void incrRefCount() { ++m_refcount; }\n  void decrRefCount() { --m_refcount; }\n  int refCount() const { return m_refcount; }\n\n private:\n  // No copy, no assignment;\n  TensorLazyBaseEvaluator(const TensorLazyBaseEvaluator& other);\n  TensorLazyBaseEvaluator& operator = (const TensorLazyBaseEvaluator& other);\n\n  int m_refcount;\n};\n\n\ntemplate <typename Dimensions, typename Expr, typename Device>\nclass TensorLazyEvaluatorReadOnly : public TensorLazyBaseEvaluator<Dimensions, typename TensorEvaluator<Expr, Device>::Scalar> {\n public:\n  //  typedef typename TensorEvaluator<Expr, Device>::Dimensions Dimensions;\n  typedef typename TensorEvaluator<Expr, Device>::Scalar Scalar;\n  typedef StorageMemory<Scalar, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n  typedef  TensorEvaluator<Expr, Device> EvalType;\n\n  TensorLazyEvaluatorReadOnly(const Expr& expr, const Device& device) : m_impl(expr, device), m_dummy(Scalar(0)) {\n    m_dims = m_impl.dimensions();\n    m_impl.evalSubExprsIfNeeded(NULL);\n  }\n  virtual ~TensorLazyEvaluatorReadOnly() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC virtual const Dimensions& dimensions() const {\n    return m_dims;\n  }\n  EIGEN_DEVICE_FUNC virtual const Scalar* data() const {\n    return m_impl.data();\n  }\n\n  EIGEN_DEVICE_FUNC virtual const Scalar coeff(DenseIndex index) const {\n    return m_impl.coeff(index);\n  }\n  EIGEN_DEVICE_FUNC virtual Scalar& coeffRef(DenseIndex /*index*/) {\n    eigen_assert(false && \"can't reference the coefficient of a rvalue\");\n    return m_dummy;\n  };\n\n protected:\n  TensorEvaluator<Expr, Device> m_impl;\n  Dimensions m_dims;\n  Scalar m_dummy;\n};\n\ntemplate <typename Dimensions, typename Expr, typename Device>\nclass TensorLazyEvaluatorWritable : public TensorLazyEvaluatorReadOnly<Dimensions, Expr, Device> {\n public:\n  typedef TensorLazyEvaluatorReadOnly<Dimensions, Expr, Device> Base;\n  typedef typename Base::Scalar Scalar;\n  typedef StorageMemory<Scalar, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  TensorLazyEvaluatorWritable(const Expr& expr, const Device& device) : Base(expr, device) {\n  }\n  virtual ~TensorLazyEvaluatorWritable() {\n  }\n\n  EIGEN_DEVICE_FUNC virtual Scalar& coeffRef(DenseIndex index) {\n    return this->m_impl.coeffRef(index);\n  }\n};\n\ntemplate <typename Dimensions, typename Expr, typename Device>\nclass TensorLazyEvaluator : public internal::conditional<bool(internal::is_lvalue<Expr>::value),\n                            TensorLazyEvaluatorWritable<Dimensions, Expr, Device>,\n                            TensorLazyEvaluatorReadOnly<Dimensions, const Expr, Device> >::type {\n public:\n  typedef typename internal::conditional<bool(internal::is_lvalue<Expr>::value),\n                                         TensorLazyEvaluatorWritable<Dimensions, Expr, Device>,\n                                         TensorLazyEvaluatorReadOnly<Dimensions, const Expr, Device> >::type Base;\n  typedef typename Base::Scalar Scalar;\n\n  TensorLazyEvaluator(const Expr& expr, const Device& device) : Base(expr, device) {\n  }\n  virtual ~TensorLazyEvaluator() {\n  }\n};\n\n}  // namespace internal\n\n\n/** \\class TensorRef\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief A reference to a tensor expression\n  * The expression will be evaluated lazily (as much as possible).\n  *\n  */\ntemplate<typename PlainObjectType> class TensorRef : public TensorBase<TensorRef<PlainObjectType> >\n{\n  public:\n    typedef TensorRef<PlainObjectType> Self;\n    typedef typename PlainObjectType::Base Base;\n    typedef typename Eigen::internal::nested<Self>::type Nested;\n    typedef typename internal::traits<PlainObjectType>::StorageKind StorageKind;\n    typedef typename internal::traits<PlainObjectType>::Index Index;\n    typedef typename internal::traits<PlainObjectType>::Scalar Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef typename Base::CoeffReturnType CoeffReturnType;\n    typedef Scalar* PointerType;\n    typedef PointerType PointerArgType;\n\n    static const Index NumIndices = PlainObjectType::NumIndices;\n    typedef typename PlainObjectType::Dimensions Dimensions;\n\n    enum {\n      IsAligned = false,\n      PacketAccess = false,\n      BlockAccess = false,\n      PreferBlockAccess = false,\n      Layout = PlainObjectType::Layout,\n      CoordAccess = false,  // to be implemented\n      RawAccess = false\n    };\n\n    //===- Tensor block evaluation strategy (see TensorBlock.h) -----------===//\n    typedef internal::TensorBlockNotImplemented TensorBlock;\n    //===------------------------------------------------------------------===//\n\n    EIGEN_STRONG_INLINE TensorRef() : m_evaluator(NULL) {\n    }\n\n    template <typename Expression>\n    EIGEN_STRONG_INLINE TensorRef(const Expression& expr) : m_evaluator(new internal::TensorLazyEvaluator<Dimensions, Expression, DefaultDevice>(expr, DefaultDevice())) {\n      m_evaluator->incrRefCount();\n    }\n\n    template <typename Expression>\n    EIGEN_STRONG_INLINE TensorRef& operator = (const Expression& expr) {\n      unrefEvaluator();\n      m_evaluator = new internal::TensorLazyEvaluator<Dimensions, Expression, DefaultDevice>(expr, DefaultDevice());\n      m_evaluator->incrRefCount();\n      return *this;\n    }\n\n    ~TensorRef() {\n      unrefEvaluator();\n    }\n\n    TensorRef(const TensorRef& other) : m_evaluator(other.m_evaluator) {\n      eigen_assert(m_evaluator->refCount() > 0);\n      m_evaluator->incrRefCount();\n    }\n\n    TensorRef& operator = (const TensorRef& other) {\n      if (this != &other) {\n        unrefEvaluator();\n        m_evaluator = other.m_evaluator;\n        eigen_assert(m_evaluator->refCount() > 0);\n        m_evaluator->incrRefCount();\n      }\n      return *this;\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Index rank() const { return m_evaluator->dimensions().size(); }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Index dimension(Index n) const { return m_evaluator->dimensions()[n]; }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_evaluator->dimensions(); }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Index size() const { return m_evaluator->dimensions().TotalSize(); }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar* data() const { return m_evaluator->data(); }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar operator()(Index index) const\n    {\n      return m_evaluator->coeff(index);\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar operator()(Index firstIndex, IndexTypes... otherIndices) const\n    {\n      const std::size_t num_indices = (sizeof...(otherIndices) + 1);\n      const array<Index, num_indices> indices{{firstIndex, otherIndices...}};\n      return coeff(indices);\n    }\n    template<typename... IndexTypes> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& coeffRef(Index firstIndex, IndexTypes... otherIndices)\n    {\n      const std::size_t num_indices = (sizeof...(otherIndices) + 1);\n      const array<Index, num_indices> indices{{firstIndex, otherIndices...}};\n      return coeffRef(indices);\n    }\n#else\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar operator()(Index i0, Index i1) const\n    {\n      array<Index, 2> indices;\n      indices[0] = i0;\n      indices[1] = i1;\n      return coeff(indices);\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar operator()(Index i0, Index i1, Index i2) const\n    {\n      array<Index, 3> indices;\n      indices[0] = i0;\n      indices[1] = i1;\n      indices[2] = i2;\n      return coeff(indices);\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar operator()(Index i0, Index i1, Index i2, Index i3) const\n    {\n      array<Index, 4> indices;\n      indices[0] = i0;\n      indices[1] = i1;\n      indices[2] = i2;\n      indices[3] = i3;\n      return coeff(indices);\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar operator()(Index i0, Index i1, Index i2, Index i3, Index i4) const\n    {\n      array<Index, 5> indices;\n      indices[0] = i0;\n      indices[1] = i1;\n      indices[2] = i2;\n      indices[3] = i3;\n      indices[4] = i4;\n      return coeff(indices);\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& coeffRef(Index i0, Index i1)\n    {\n      array<Index, 2> indices;\n      indices[0] = i0;\n      indices[1] = i1;\n      return coeffRef(indices);\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& coeffRef(Index i0, Index i1, Index i2)\n    {\n      array<Index, 3> indices;\n      indices[0] = i0;\n      indices[1] = i1;\n      indices[2] = i2;\n      return coeffRef(indices);\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3)\n    {\n      array<Index, 4> indices;\n      indices[0] = i0;\n      indices[1] = i1;\n      indices[2] = i2;\n      indices[3] = i3;\n      return coeffRef(indices);\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& coeffRef(Index i0, Index i1, Index i2, Index i3, Index i4)\n    {\n      array<Index, 5> indices;\n      indices[0] = i0;\n      indices[1] = i1;\n      indices[2] = i2;\n      indices[3] = i3;\n      indices[4] = i4;\n      return coeffRef(indices);\n    }\n#endif\n\n    template <std::size_t NumIndices> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar coeff(const array<Index, NumIndices>& indices) const\n    {\n      const Dimensions& dims = this->dimensions();\n      Index index = 0;\n      if (PlainObjectType::Options & RowMajor) {\n        index += indices[0];\n        for (size_t i = 1; i < NumIndices; ++i) {\n          index = index * dims[i] + indices[i];\n        }\n      } else {\n        index += indices[NumIndices-1];\n        for (int i = NumIndices-2; i >= 0; --i) {\n          index = index * dims[i] + indices[i];\n        }\n      }\n      return m_evaluator->coeff(index);\n    }\n    template <std::size_t NumIndices> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& coeffRef(const array<Index, NumIndices>& indices)\n    {\n      const Dimensions& dims = this->dimensions();\n      Index index = 0;\n      if (PlainObjectType::Options & RowMajor) {\n        index += indices[0];\n        for (size_t i = 1; i < NumIndices; ++i) {\n          index = index * dims[i] + indices[i];\n        }\n      } else {\n        index += indices[NumIndices-1];\n        for (int i = NumIndices-2; i >= 0; --i) {\n          index = index * dims[i] + indices[i];\n        }\n      }\n      return m_evaluator->coeffRef(index);\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar coeff(Index index) const\n    {\n      return m_evaluator->coeff(index);\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& coeffRef(Index index)\n    {\n      return m_evaluator->coeffRef(index);\n    }\n\n  private:\n    EIGEN_STRONG_INLINE void unrefEvaluator() {\n      if (m_evaluator) {\n        m_evaluator->decrRefCount();\n        if (m_evaluator->refCount() == 0) {\n          delete m_evaluator;\n        }\n      }\n    }\n\n  internal::TensorLazyBaseEvaluator<Dimensions, Scalar>* m_evaluator;\n};\n\n\n// evaluator for rvalues\ntemplate<typename Derived, typename Device>\nstruct TensorEvaluator<const TensorRef<Derived>, Device>\n{\n  typedef typename Derived::Index Index;\n  typedef typename Derived::Scalar Scalar;\n  typedef typename Derived::Scalar CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef typename Derived::Dimensions Dimensions;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = false,\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorRef<Derived>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const TensorRef<Derived>& m, const Device&)\n      : m_ref(m)\n  { }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_ref.dimensions(); }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    return true;\n  }\n\n  EIGEN_STRONG_INLINE void cleanup() { }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const {\n    return m_ref.coeff(index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index index) {\n    return m_ref.coeffRef(index);\n  }\n\n  EIGEN_DEVICE_FUNC const Scalar* data() const { return m_ref.data(); }\n\n protected:\n  TensorRef<Derived> m_ref;\n};\n\n\n// evaluator for lvalues\ntemplate<typename Derived, typename Device>\nstruct TensorEvaluator<TensorRef<Derived>, Device> : public TensorEvaluator<const TensorRef<Derived>, Device>\n{\n  typedef typename Derived::Index Index;\n  typedef typename Derived::Scalar Scalar;\n  typedef typename Derived::Scalar CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef typename Derived::Dimensions Dimensions;\n\n  typedef TensorEvaluator<const TensorRef<Derived>, Device> Base;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = false,\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(TensorRef<Derived>& m, const Device& d) : Base(m, d)\n  { }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index index) {\n    return this->m_ref.coeffRef(index);\n  }\n};\n\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_REF_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReverse.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Navdeep Jaitly <ndjaitly@google.com>\n//                    Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_REVERSE_H\n#define EIGEN_CXX11_TENSOR_TENSOR_REVERSE_H\nnamespace Eigen {\n\n/** \\class TensorReverse\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor reverse elements class.\n  *\n  */\nnamespace internal {\ntemplate<typename ReverseDimensions, typename XprType>\nstruct traits<TensorReverseOp<ReverseDimensions,\n                              XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename ReverseDimensions, typename XprType>\nstruct eval<TensorReverseOp<ReverseDimensions, XprType>, Eigen::Dense>\n{\n  typedef const TensorReverseOp<ReverseDimensions, XprType>& type;\n};\n\ntemplate<typename ReverseDimensions, typename XprType>\nstruct nested<TensorReverseOp<ReverseDimensions, XprType>, 1,\n            typename eval<TensorReverseOp<ReverseDimensions, XprType> >::type>\n{\n  typedef TensorReverseOp<ReverseDimensions, XprType> type;\n};\n\n}  // end namespace internal\n\ntemplate<typename ReverseDimensions, typename XprType>\nclass TensorReverseOp : public TensorBase<TensorReverseOp<ReverseDimensions,\n                                          XprType>, WriteAccessors>\n{\n  public:\n    typedef TensorBase<TensorReverseOp<ReverseDimensions, XprType>, WriteAccessors>Base;\n    typedef typename Eigen::internal::traits<TensorReverseOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef typename XprType::CoeffReturnType CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorReverseOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorReverseOp>::StorageKind\n                                                                      StorageKind;\n    typedef typename Eigen::internal::traits<TensorReverseOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorReverseOp(\n      const XprType& expr, const ReverseDimensions& reverse_dims)\n      : m_xpr(expr), m_reverse_dims(reverse_dims) { }\n\n    EIGEN_DEVICE_FUNC\n    const ReverseDimensions& reverse() const { return m_reverse_dims; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(TensorReverseOp)\n\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const ReverseDimensions m_reverse_dims;\n};\n\n// Eval as rvalue\ntemplate<typename ReverseDimensions, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorReverseOp<ReverseDimensions, ArgType>, Device>\n{\n  typedef TensorReverseOp<ReverseDimensions, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<ReverseDimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned         = false,\n    PacketAccess      = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess       = NumDims > 0,\n    PreferBlockAccess = true,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = false\n  };\n\n  typedef internal::TensorIntDivisor<Index> IndexDivisor;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename TensorEvaluator<const ArgType, Device>::TensorBlock\n      ArgTensorBlock;\n\n  typedef typename internal::TensorMaterializedBlock<CoeffReturnType, NumDims,\n                                                     Layout, Index>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device),\n        m_reverse(op.reverse()),\n        m_device(device)\n  {\n    // Reversing a scalar isn't supported yet. It would be a no-op anyway.\n    EIGEN_STATIC_ASSERT((NumDims > 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    // Compute strides\n    m_dimensions = m_impl.dimensions();\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_strides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_strides[i] = m_strides[i-1] * m_dimensions[i-1];\n        if (m_strides[i] > 0) m_fastStrides[i] = IndexDivisor(m_strides[i]);\n      }\n    } else {\n      m_strides[NumDims-1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_strides[i] = m_strides[i+1] * m_dimensions[i+1];\n        if (m_strides[i] > 0) m_fastStrides[i] = IndexDivisor(m_strides[i]);\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    m_impl.evalSubExprsIfNeededAsync(nullptr, [done](bool) { done(true); });\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index reverseIndex(\n      Index index) const {\n    eigen_assert(index < dimensions().TotalSize());\n    Index inputIndex = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i > 0; --i) {\n        Index idx = index / m_fastStrides[i];\n        index -= idx * m_strides[i];\n        if (m_reverse[i]) {\n          idx = m_dimensions[i] - idx - 1;\n        }\n        inputIndex += idx * m_strides[i] ;\n      }\n      if (m_reverse[0]) {\n        inputIndex += (m_dimensions[0] - index - 1);\n      } else {\n        inputIndex += index;\n      }\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 1; ++i) {\n        Index idx = index / m_fastStrides[i];\n        index -= idx * m_strides[i];\n        if (m_reverse[i]) {\n          idx = m_dimensions[i] - idx - 1;\n        }\n        inputIndex += idx * m_strides[i] ;\n      }\n      if (m_reverse[NumDims-1]) {\n        inputIndex += (m_dimensions[NumDims-1] - index - 1);\n      } else {\n        inputIndex += index;\n      }\n    }\n    return inputIndex;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(\n      Index index) const  {\n    return m_impl.coeff(reverseIndex(index));\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  PacketReturnType packet(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    // TODO(ndjaitly): write a better packing routine that uses\n    // local structure.\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type\n                                                            values[PacketSize];\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < PacketSize; ++i) {\n      values[i] = coeff(index+i);\n    }\n    PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n    return rslt;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    const size_t target_size = m_device.lastLevelCacheSize();\n    // Block evaluation reads underlying memory in reverse order, and default\n    // cost model does not properly catch this in bytes stored/loaded.\n    return internal::TensorBlockResourceRequirements::skewed<Scalar>(\n               target_size)\n        .addCostPerCoeff({0, 0, 24});\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    // TODO(ezhulenev): If underlying tensor expression supports and prefers\n    // block evaluation we must use it. Currently we use coeff and packet\n    // access into the underlying tensor expression.\n    // static const bool useBlockAccessForArgType =\n    //     TensorEvaluator<ArgType, Device>::BlockAccess &&\n    //     TensorEvaluator<ArgType, Device>::PreferBlockAccess;\n\n    static const bool isColMajor =\n        static_cast<int>(Layout) == static_cast<int>(ColMajor);\n\n    static const Index inner_dim_idx = isColMajor ? 0 : NumDims - 1;\n    const bool inner_dim_reversed = m_reverse[inner_dim_idx];\n\n    // Offset in the output block.\n    Index block_offset = 0;\n\n    // Offset in the input Tensor.\n    Index input_offset = reverseIndex(desc.offset());\n\n    // Initialize output block iterator state. Dimension in this array are\n    // always in inner_most -> outer_most order (col major layout).\n    array<BlockIteratorState, NumDims> it;\n    for (int i = 0; i < NumDims; ++i) {\n      const int dim = isColMajor ? i : NumDims - 1 - i;\n      it[i].size = desc.dimension(dim);\n      it[i].count = 0;\n      it[i].reverse = m_reverse[dim];\n\n      it[i].block_stride =\n          i == 0 ? 1 : (it[i - 1].size * it[i - 1].block_stride);\n      it[i].block_span = it[i].block_stride * (it[i].size - 1);\n\n      it[i].input_stride = m_strides[dim];\n      it[i].input_span = it[i].input_stride * (it[i].size - 1);\n\n      if (it[i].reverse) {\n        it[i].input_stride = -1 * it[i].input_stride;\n        it[i].input_span = -1 * it[i].input_span;\n      }\n    }\n\n    // If multiple inner dimensions have the same reverse flag, check if we can\n    // merge them into a single virtual inner dimension.\n    int effective_inner_dim = 0;\n    for (int i = 1; i < NumDims; ++i) {\n      if (it[i].reverse != it[effective_inner_dim].reverse) break;\n      if (it[i].block_stride != it[effective_inner_dim].size) break;\n      if (it[i].block_stride != numext::abs(it[i].input_stride)) break;\n\n      it[i].size = it[effective_inner_dim].size * it[i].size;\n\n      it[i].block_stride = 1;\n      it[i].input_stride = (inner_dim_reversed ? -1 : 1);\n\n      it[i].block_span = it[i].block_stride * (it[i].size - 1);\n      it[i].input_span = it[i].input_stride * (it[i].size - 1);\n\n      effective_inner_dim = i;\n    }\n\n    eigen_assert(it[effective_inner_dim].block_stride == 1);\n    eigen_assert(it[effective_inner_dim].input_stride ==\n                 (inner_dim_reversed ? -1 : 1));\n\n    const Index inner_dim_size = it[effective_inner_dim].size;\n\n    // Prepare storage for the materialized reverse result.\n    const typename TensorBlock::Storage block_storage =\n        TensorBlock::prepareStorage(desc, scratch);\n    CoeffReturnType* block_buffer = block_storage.data();\n\n    while (it[NumDims - 1].count < it[NumDims - 1].size) {\n      // Copy inner-most dimension data from reversed location in input.\n      Index dst = block_offset;\n      Index src = input_offset;\n\n      // NOTE(ezhulenev): Adding vectorized path with internal::preverse showed\n      // worse results in benchmarks than a simple coefficient loop.\n      if (inner_dim_reversed) {\n        for (Index i = 0; i < inner_dim_size; ++i) {\n          block_buffer[dst] = m_impl.coeff(src);\n          ++dst;\n          --src;\n        }\n      } else {\n        for (Index i = 0; i < inner_dim_size; ++i) {\n          block_buffer[dst] = m_impl.coeff(src);\n          ++dst;\n          ++src;\n        }\n      }\n\n      // For the 1d tensor we need to generate only one inner-most dimension.\n      if ((NumDims - effective_inner_dim) == 1) break;\n\n      // Update offset.\n      for (Index i = effective_inner_dim + 1; i < NumDims; ++i) {\n        if (++it[i].count < it[i].size) {\n          block_offset += it[i].block_stride;\n          input_offset += it[i].input_stride;\n          break;\n        }\n        if (i != NumDims - 1) it[i].count = 0;\n        block_offset -= it[i].block_span;\n        input_offset -= it[i].input_span;\n      }\n    }\n\n    return block_storage.AsTensorMaterializedBlock();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    double compute_cost = NumDims * (2 * TensorOpCost::AddCost<Index>() +\n                                     2 * TensorOpCost::MulCost<Index>() +\n                                     TensorOpCost::DivCost<Index>());\n    for (int i = 0; i < NumDims; ++i) {\n      if (m_reverse[i]) {\n        compute_cost += 2 * TensorOpCost::AddCost<Index>();\n      }\n    }\n    return m_impl.costPerCoeff(vectorized) +\n           TensorOpCost(0, 0, compute_cost, false /* vectorized */, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC typename Storage::Type data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n\n protected:\n  Dimensions m_dimensions;\n  array<Index, NumDims> m_strides;\n  array<IndexDivisor, NumDims> m_fastStrides;\n  TensorEvaluator<ArgType, Device> m_impl;\n  ReverseDimensions m_reverse;\n  const Device EIGEN_DEVICE_REF m_device;\n\n private:\n  struct BlockIteratorState {\n    BlockIteratorState()\n        : size(0),\n          count(0),\n          reverse(false),\n          block_stride(0),\n          block_span(0),\n          input_stride(0),\n          input_span(0) {}\n\n    Index size;\n    Index count;\n    bool reverse;\n    Index block_stride;\n    Index block_span;\n    Index input_stride;\n    Index input_span;\n  };\n};\n\n// Eval as lvalue\n\ntemplate <typename ReverseDimensions, typename ArgType, typename Device>\nstruct TensorEvaluator<TensorReverseOp<ReverseDimensions, ArgType>, Device>\n    : public TensorEvaluator<const TensorReverseOp<ReverseDimensions, ArgType>,\n                             Device> {\n  typedef TensorEvaluator<const TensorReverseOp<ReverseDimensions, ArgType>,\n                          Device> Base;\n  typedef TensorReverseOp<ReverseDimensions, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<ReverseDimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : Base(op, device) {}\n\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  const Dimensions& dimensions() const { return this->m_dimensions; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index index) {\n    return this->m_impl.coeffRef(this->reverseIndex(index));\n  }\n\n  template <int StoreMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void writePacket(Index index, const PacketReturnType& x) {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    // This code is pilfered from TensorMorphing.h\n    EIGEN_ALIGN_MAX CoeffReturnType values[PacketSize];\n    internal::pstore<CoeffReturnType, PacketReturnType>(values, x);\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < PacketSize; ++i) {\n      this->coeffRef(index+i) = values[i];\n    }\n  }\n};\n\n\n}  // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_REVERSE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorScan.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Igor Babuschkin <igor@babuschk.in>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_SCAN_H\n#define EIGEN_CXX11_TENSOR_TENSOR_SCAN_H\n\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate <typename Op, typename XprType>\nstruct traits<TensorScanOp<Op, XprType> >\n    : public traits<XprType> {\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename Op, typename XprType>\nstruct eval<TensorScanOp<Op, XprType>, Eigen::Dense>\n{\n  typedef const TensorScanOp<Op, XprType>& type;\n};\n\ntemplate<typename Op, typename XprType>\nstruct nested<TensorScanOp<Op, XprType>, 1,\n            typename eval<TensorScanOp<Op, XprType> >::type>\n{\n  typedef TensorScanOp<Op, XprType> type;\n};\n} // end namespace internal\n\n/** \\class TensorScan\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor scan class.\n  */\ntemplate <typename Op, typename XprType>\nclass TensorScanOp\n    : public TensorBase<TensorScanOp<Op, XprType>, ReadOnlyAccessors> {\npublic:\n  typedef typename Eigen::internal::traits<TensorScanOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorScanOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorScanOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorScanOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorScanOp(\n      const XprType& expr, const Index& axis, bool exclusive = false, const Op& op = Op())\n      : m_expr(expr), m_axis(axis), m_accumulator(op), m_exclusive(exclusive) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  const Index axis() const { return m_axis; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  const XprType& expression() const { return m_expr; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  const Op accumulator() const { return m_accumulator; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  bool exclusive() const { return m_exclusive; }\n\nprotected:\n  typename XprType::Nested m_expr;\n  const Index m_axis;\n  const Op m_accumulator;\n  const bool m_exclusive;\n};\n\n\nnamespace internal {\n\ntemplate <typename Self>\nEIGEN_STRONG_INLINE void ReduceScalar(Self& self, Index offset,\n                                      typename Self::CoeffReturnType* data) {\n  // Compute the scan along the axis, starting at the given offset\n  typename Self::CoeffReturnType accum = self.accumulator().initialize();\n  if (self.stride() == 1) {\n    if (self.exclusive()) {\n      for (Index curr = offset; curr < offset + self.size(); ++curr) {\n        data[curr] = self.accumulator().finalize(accum);\n        self.accumulator().reduce(self.inner().coeff(curr), &accum);\n      }\n    } else {\n      for (Index curr = offset; curr < offset + self.size(); ++curr) {\n        self.accumulator().reduce(self.inner().coeff(curr), &accum);\n        data[curr] = self.accumulator().finalize(accum);\n      }\n    }\n  } else {\n    if (self.exclusive()) {\n      for (Index idx3 = 0; idx3 < self.size(); idx3++) {\n        Index curr = offset + idx3 * self.stride();\n        data[curr] = self.accumulator().finalize(accum);\n        self.accumulator().reduce(self.inner().coeff(curr), &accum);\n      }\n    } else {\n      for (Index idx3 = 0; idx3 < self.size(); idx3++) {\n        Index curr = offset + idx3 * self.stride();\n        self.accumulator().reduce(self.inner().coeff(curr), &accum);\n        data[curr] = self.accumulator().finalize(accum);\n      }\n    }\n  }\n}\n\ntemplate <typename Self>\nEIGEN_STRONG_INLINE void ReducePacket(Self& self, Index offset,\n                                      typename Self::CoeffReturnType* data) {\n  using Scalar = typename Self::CoeffReturnType;\n  using Packet = typename Self::PacketReturnType;\n  // Compute the scan along the axis, starting at the calculated offset\n  Packet accum = self.accumulator().template initializePacket<Packet>();\n  if (self.stride() == 1) {\n    if (self.exclusive()) {\n      for (Index curr = offset; curr < offset + self.size(); ++curr) {\n        internal::pstoreu<Scalar, Packet>(data + curr, self.accumulator().finalizePacket(accum));\n        self.accumulator().reducePacket(self.inner().template packet<Unaligned>(curr), &accum);\n      }\n    } else {\n      for (Index curr = offset; curr < offset + self.size(); ++curr) {\n        self.accumulator().reducePacket(self.inner().template packet<Unaligned>(curr), &accum);\n        internal::pstoreu<Scalar, Packet>(data + curr, self.accumulator().finalizePacket(accum));\n      }\n    }\n  } else {\n    if (self.exclusive()) {\n      for (Index idx3 = 0; idx3 < self.size(); idx3++) {\n        const Index curr = offset + idx3 * self.stride();\n        internal::pstoreu<Scalar, Packet>(data + curr, self.accumulator().finalizePacket(accum));\n        self.accumulator().reducePacket(self.inner().template packet<Unaligned>(curr), &accum);\n      }\n    } else {\n      for (Index idx3 = 0; idx3 < self.size(); idx3++) {\n        const Index curr = offset + idx3 * self.stride();\n        self.accumulator().reducePacket(self.inner().template packet<Unaligned>(curr), &accum);\n        internal::pstoreu<Scalar, Packet>(data + curr, self.accumulator().finalizePacket(accum));\n      }\n    }\n  }\n}\n\ntemplate <typename Self, bool Vectorize, bool Parallel>\nstruct ReduceBlock {\n  EIGEN_STRONG_INLINE void operator()(Self& self, Index idx1,\n                                      typename Self::CoeffReturnType* data) {\n    for (Index idx2 = 0; idx2 < self.stride(); idx2++) {\n      // Calculate the starting offset for the scan\n      Index offset = idx1 + idx2;\n      ReduceScalar(self, offset, data);\n    }\n  }\n};\n\n// Specialization for vectorized reduction.\ntemplate <typename Self>\nstruct ReduceBlock<Self, /*Vectorize=*/true, /*Parallel=*/false> {\n  EIGEN_STRONG_INLINE void operator()(Self& self, Index idx1,\n                                      typename Self::CoeffReturnType* data) {\n    using Packet = typename Self::PacketReturnType;\n    const int PacketSize = internal::unpacket_traits<Packet>::size;\n    Index idx2 = 0;\n    for (; idx2 + PacketSize <= self.stride(); idx2 += PacketSize) {\n      // Calculate the starting offset for the packet scan\n      Index offset = idx1 + idx2;\n      ReducePacket(self, offset, data);\n    }\n    for (; idx2 < self.stride(); idx2++) {\n      // Calculate the starting offset for the scan\n      Index offset = idx1 + idx2;\n      ReduceScalar(self, offset, data);\n    }\n  }\n};\n\n// Single-threaded CPU implementation of scan\ntemplate <typename Self, typename Reducer, typename Device,\n          bool Vectorize =\n              (TensorEvaluator<typename Self::ChildTypeNoConst, Device>::PacketAccess &&\n               internal::reducer_traits<Reducer, Device>::PacketAccess)>\nstruct ScanLauncher {\n  void operator()(Self& self, typename Self::CoeffReturnType* data) {\n    Index total_size = internal::array_prod(self.dimensions());\n\n    // We fix the index along the scan axis to 0 and perform a\n    // scan per remaining entry. The iteration is split into two nested\n    // loops to avoid an integer division by keeping track of each idx1 and\n    // idx2.\n    for (Index idx1 = 0; idx1 < total_size; idx1 += self.stride() * self.size()) {\n      ReduceBlock<Self, Vectorize, /*Parallel=*/false> block_reducer;\n      block_reducer(self, idx1, data);\n    }\n  }\n};\n\n#ifdef EIGEN_USE_THREADS\n\n// Adjust block_size to avoid false sharing of cachelines among\n// threads. Currently set to twice the cache line size on Intel and ARM\n// processors.\nEIGEN_STRONG_INLINE Index AdjustBlockSize(Index item_size, Index block_size) {\n  EIGEN_CONSTEXPR Index kBlockAlignment = 128;\n  const Index items_per_cacheline =\n      numext::maxi<Index>(1, kBlockAlignment / item_size);\n  return items_per_cacheline * divup(block_size, items_per_cacheline);\n}\n\ntemplate <typename Self>\nstruct ReduceBlock<Self, /*Vectorize=*/true, /*Parallel=*/true> {\n  EIGEN_STRONG_INLINE void operator()(Self& self, Index idx1,\n                                      typename Self::CoeffReturnType* data) {\n    using Scalar = typename Self::CoeffReturnType;\n    using Packet = typename Self::PacketReturnType;\n    const int PacketSize = internal::unpacket_traits<Packet>::size;\n    Index num_scalars = self.stride();\n    Index num_packets = 0;\n    if (self.stride() >= PacketSize) {\n      num_packets = self.stride() / PacketSize;\n      self.device().parallelFor(\n          num_packets,\n        TensorOpCost(PacketSize * self.size(), PacketSize * self.size(),\n                     16 * PacketSize * self.size(), true, PacketSize),\n        // Make the shard size large enough that two neighboring threads\n        // won't write to the same cacheline of `data`.\n        [=](Index blk_size) {\n          return AdjustBlockSize(PacketSize * sizeof(Scalar), blk_size);\n        },\n        [&](Index first, Index last) {\n          for (Index packet = first; packet < last; ++packet) {\n            const Index idx2 = packet * PacketSize;\n            ReducePacket(self, idx1 + idx2, data);\n          }\n        });\n      num_scalars -= num_packets * PacketSize;\n    }\n    self.device().parallelFor(\n        num_scalars, TensorOpCost(self.size(), self.size(), 16 * self.size()),\n        // Make the shard size large enough that two neighboring threads\n        // won't write to the same cacheline of `data`.\n        [=](Index blk_size) {\n          return AdjustBlockSize(sizeof(Scalar), blk_size);\n        },\n        [&](Index first, Index last) {\n          for (Index scalar = first; scalar < last; ++scalar) {\n            const Index idx2 = num_packets * PacketSize + scalar;\n            ReduceScalar(self, idx1 + idx2, data);\n          }\n        });\n  }\n};\n\ntemplate <typename Self>\nstruct ReduceBlock<Self, /*Vectorize=*/false, /*Parallel=*/true> {\n  EIGEN_STRONG_INLINE void operator()(Self& self, Index idx1,\n                                      typename Self::CoeffReturnType* data) {\n    using Scalar = typename Self::CoeffReturnType;\n    self.device().parallelFor(\n        self.stride(), TensorOpCost(self.size(), self.size(), 16 * self.size()),\n        // Make the shard size large enough that two neighboring threads\n        // won't write to the same cacheline of `data`.\n        [=](Index blk_size) {\n          return AdjustBlockSize(sizeof(Scalar), blk_size);\n        },\n        [&](Index first, Index last) {\n          for (Index idx2 = first; idx2 < last; ++idx2) {\n            ReduceScalar(self, idx1 + idx2, data);\n          }\n        });\n  }\n};\n\n// Specialization for multi-threaded execution.\ntemplate <typename Self, typename Reducer, bool Vectorize>\nstruct ScanLauncher<Self, Reducer, ThreadPoolDevice, Vectorize> {\n  void operator()(Self& self, typename Self::CoeffReturnType* data) {\n    using Scalar = typename Self::CoeffReturnType;\n    using Packet = typename Self::PacketReturnType;\n    const int PacketSize = internal::unpacket_traits<Packet>::size;\n    const Index total_size = internal::array_prod(self.dimensions());\n    const Index inner_block_size = self.stride() * self.size();\n    bool parallelize_by_outer_blocks = (total_size >= (self.stride() * inner_block_size));\n\n    if ((parallelize_by_outer_blocks && total_size <= 4096) ||\n        (!parallelize_by_outer_blocks && self.stride() < PacketSize)) {\n      ScanLauncher<Self, Reducer, DefaultDevice, Vectorize> launcher;\n      launcher(self, data);\n      return;\n    }\n\n    if (parallelize_by_outer_blocks) {\n      // Parallelize over outer blocks.\n      const Index num_outer_blocks = total_size / inner_block_size;\n      self.device().parallelFor(\n          num_outer_blocks,\n          TensorOpCost(inner_block_size, inner_block_size,\n                       16 * PacketSize * inner_block_size, Vectorize,\n                       PacketSize),\n          [=](Index blk_size) {\n            return AdjustBlockSize(inner_block_size * sizeof(Scalar), blk_size);\n          },\n          [&](Index first, Index last) {\n            for (Index idx1 = first; idx1 < last; ++idx1) {\n              ReduceBlock<Self, Vectorize, /*Parallelize=*/false> block_reducer;\n              block_reducer(self, idx1 * inner_block_size, data);\n            }\n          });\n    } else {\n      // Parallelize over inner packets/scalars dimensions when the reduction\n      // axis is not an inner dimension.\n      ReduceBlock<Self, Vectorize, /*Parallelize=*/true> block_reducer;\n      for (Index idx1 = 0; idx1 < total_size;\n           idx1 += self.stride() * self.size()) {\n        block_reducer(self, idx1, data);\n      }\n    }\n  }\n};\n#endif  // EIGEN_USE_THREADS\n\n#if defined(EIGEN_USE_GPU) && (defined(EIGEN_GPUCC))\n\n// GPU implementation of scan\n// TODO(ibab) This placeholder implementation performs multiple scans in\n// parallel, but it would be better to use a parallel scan algorithm and\n// optimize memory access.\ntemplate <typename Self, typename Reducer>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void ScanKernel(Self self, Index total_size, typename Self::CoeffReturnType* data) {\n  // Compute offset as in the CPU version\n  Index val = threadIdx.x + blockIdx.x * blockDim.x;\n  Index offset = (val / self.stride()) * self.stride() * self.size() + val % self.stride();\n\n  if (offset + (self.size() - 1) * self.stride() < total_size) {\n    // Compute the scan along the axis, starting at the calculated offset\n    typename Self::CoeffReturnType accum = self.accumulator().initialize();\n    for (Index idx = 0; idx < self.size(); idx++) {\n      Index curr = offset + idx * self.stride();\n      if (self.exclusive()) {\n        data[curr] = self.accumulator().finalize(accum);\n        self.accumulator().reduce(self.inner().coeff(curr), &accum);\n      } else {\n        self.accumulator().reduce(self.inner().coeff(curr), &accum);\n        data[curr] = self.accumulator().finalize(accum);\n      }\n    }\n  }\n  __syncthreads();\n\n}\n\ntemplate <typename Self, typename Reducer, bool Vectorize>\nstruct ScanLauncher<Self, Reducer, GpuDevice, Vectorize> {\n  void operator()(const Self& self, typename Self::CoeffReturnType* data) {\n     Index total_size = internal::array_prod(self.dimensions());\n     Index num_blocks = (total_size / self.size() + 63) / 64;\n     Index block_size = 64;\n\n     LAUNCH_GPU_KERNEL((ScanKernel<Self, Reducer>), num_blocks, block_size, 0, self.device(), self, total_size, data);\n  }\n};\n#endif  // EIGEN_USE_GPU && (EIGEN_GPUCC)\n\n}  // namespace internal\n\n// Eval as rvalue\ntemplate <typename Op, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorScanOp<Op, ArgType>, Device> {\n\n  typedef TensorScanOp<Op, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  typedef const ArgType ChildTypeNoConst;\n  typedef const ArgType ChildType;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename internal::remove_const<typename XprType::Scalar>::type Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef TensorEvaluator<const TensorScanOp<Op, ArgType>, Device> Self;\n  typedef StorageMemory<Scalar, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,\n    RawAccess = true\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device),\n        m_device(device),\n        m_exclusive(op.exclusive()),\n        m_accumulator(op.accumulator()),\n        m_size(m_impl.dimensions()[op.axis()]),\n        m_stride(1), m_consume_dim(op.axis()),\n        m_output(NULL) {\n\n    // Accumulating a scalar isn't supported.\n    EIGEN_STATIC_ASSERT((NumDims > 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    eigen_assert(op.axis() >= 0 && op.axis() < NumDims);\n\n    // Compute stride of scan axis\n    const Dimensions& dims = m_impl.dimensions();\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = 0; i < op.axis(); ++i) {\n        m_stride = m_stride * dims[i];\n      }\n    } else {\n      // dims can only be indexed through unsigned integers,\n      // so let's use an unsigned type to let the compiler knows.\n      // This prevents stupid warnings: \"\"'*((void*)(& evaluator)+64)[18446744073709551615]' may be used uninitialized in this function\"\n      unsigned int axis = internal::convert_index<unsigned int>(op.axis());\n      for (unsigned int i = NumDims - 1; i > axis; --i) {\n        m_stride = m_stride * dims[i];\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const {\n    return m_impl.dimensions();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Index& stride() const {\n    return m_stride;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Index& consume_dim() const {\n    return m_consume_dim;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Index& size() const {\n    return m_size;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Op& accumulator() const {\n    return m_accumulator;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool exclusive() const {\n    return m_exclusive;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const TensorEvaluator<ArgType, Device>& inner() const {\n    return m_impl;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Device& device() const {\n    return m_device;\n  }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    internal::ScanLauncher<Self, Op, Device> launcher;\n    if (data) {\n      launcher(*this, data);\n      return false;\n    }\n\n    const Index total_size = internal::array_prod(dimensions());\n    m_output = static_cast<EvaluatorPointerType>(m_device.get((Scalar*) m_device.allocate_temp(total_size * sizeof(Scalar))));\n    launcher(*this, m_output);\n    return true;\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC PacketReturnType packet(Index index) const {\n    return internal::ploadt<PacketReturnType, LoadMode>(m_output + index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EvaluatorPointerType data() const\n  {\n    return m_output;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    return m_output[index];\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool) const {\n    return TensorOpCost(sizeof(CoeffReturnType), 0, 0);\n  }\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    if (m_output) {\n      m_device.deallocate_temp(m_output);\n      m_output = NULL;\n    }\n    m_impl.cleanup();\n  }\n\n#ifdef EIGEN_USE_SYCL\n // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n    m_output.bind(cgh);\n  }\n#endif\nprotected:\n  TensorEvaluator<ArgType, Device> m_impl;\n  const Device EIGEN_DEVICE_REF m_device;\n  const bool m_exclusive;\n  Op m_accumulator;\n  const Index m_size;\n  Index m_stride;\n  Index m_consume_dim;\n  EvaluatorPointerType m_output;\n};\n\n}  // end namespace Eigen\n\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_SCAN_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorScanSycl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/*****************************************************************\n * TensorScanSycl.h\n *\n * \\brief:\n *  Tensor Scan Sycl implement the extend  version of\n * \"Efficient parallel scan algorithms for GPUs.\" .for Tensor operations.\n * The algorithm requires up to 3 stage (consequently 3 kernels) depending on\n * the size of the tensor. In the first kernel (ScanKernelFunctor), each\n * threads within the work-group individually reduces the allocated elements per\n * thread in order to reduces the total number of blocks. In the next step all\n * thread within the work-group will reduce the associated blocks into the\n * temporary buffers. In the next kernel(ScanBlockKernelFunctor), the temporary\n * buffer is given as an input and all the threads within a work-group scan and\n * reduces the boundaries between the blocks (generated from the previous\n * kernel). and write the data on the temporary buffer. If the second kernel is\n * required, the third and final kerenl (ScanAdjustmentKernelFunctor) will\n * adjust the final result into the output buffer.\n * The original algorithm for the parallel prefix sum can be found here:\n *\n * Sengupta, Shubhabrata, Mark Harris, and Michael Garland. \"Efficient parallel\n * scan algorithms for GPUs.\" NVIDIA, Santa Clara, CA, Tech. Rep. NVR-2008-003\n *1, no. 1 (2008): 1-17.\n *****************************************************************/\n\n#ifndef UNSUPPORTED_EIGEN_CXX11_SRC_TENSOR_TENSOR_SYCL_SYCL_HPP\n#define UNSUPPORTED_EIGEN_CXX11_SRC_TENSOR_TENSOR_SYCL_SYCL_HPP\n\nnamespace Eigen {\nnamespace TensorSycl {\nnamespace internal {\n\n#ifndef EIGEN_SYCL_MAX_GLOBAL_RANGE\n#define EIGEN_SYCL_MAX_GLOBAL_RANGE (EIGEN_SYCL_LOCAL_THREAD_DIM0 * EIGEN_SYCL_LOCAL_THREAD_DIM1 * 4)\n#endif\n\ntemplate <typename index_t>\nstruct ScanParameters {\n  // must be power of 2\n  static EIGEN_CONSTEXPR index_t ScanPerThread = 8;\n  const index_t total_size;\n  const index_t non_scan_size;\n  const index_t scan_size;\n  const index_t non_scan_stride;\n  const index_t scan_stride;\n  const index_t panel_threads;\n  const index_t group_threads;\n  const index_t block_threads;\n  const index_t elements_per_group;\n  const index_t elements_per_block;\n  const index_t loop_range;\n\n  ScanParameters(index_t total_size_, index_t non_scan_size_, index_t scan_size_, index_t non_scan_stride_,\n                 index_t scan_stride_, index_t panel_threads_, index_t group_threads_, index_t block_threads_,\n                 index_t elements_per_group_, index_t elements_per_block_, index_t loop_range_)\n      : total_size(total_size_),\n        non_scan_size(non_scan_size_),\n        scan_size(scan_size_),\n        non_scan_stride(non_scan_stride_),\n        scan_stride(scan_stride_),\n        panel_threads(panel_threads_),\n        group_threads(group_threads_),\n        block_threads(block_threads_),\n        elements_per_group(elements_per_group_),\n        elements_per_block(elements_per_block_),\n        loop_range(loop_range_) {}\n};\n\nenum class scan_step { first, second };\ntemplate <typename Evaluator, typename CoeffReturnType, typename OutAccessor, typename Op, typename Index,\n          scan_step stp>\nstruct ScanKernelFunctor {\n  typedef cl::sycl::accessor<CoeffReturnType, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local>\n      LocalAccessor;\n  static EIGEN_CONSTEXPR int PacketSize = ScanParameters<Index>::ScanPerThread / 2;\n\n  LocalAccessor scratch;\n  Evaluator dev_eval;\n  OutAccessor out_accessor;\n  OutAccessor temp_accessor;\n  const ScanParameters<Index> scanParameters;\n  Op accumulator;\n  const bool inclusive;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ScanKernelFunctor(LocalAccessor scratch_, const Evaluator dev_eval_,\n                                                          OutAccessor out_accessor_, OutAccessor temp_accessor_,\n                                                          const ScanParameters<Index> scanParameters_, Op accumulator_,\n                                                          const bool inclusive_)\n      : scratch(scratch_),\n        dev_eval(dev_eval_),\n        out_accessor(out_accessor_),\n        temp_accessor(temp_accessor_),\n        scanParameters(scanParameters_),\n        accumulator(accumulator_),\n        inclusive(inclusive_) {}\n\n  template <scan_step sst = stp, typename Input>\n  typename ::Eigen::internal::enable_if<sst == scan_step::first, CoeffReturnType>::type EIGEN_DEVICE_FUNC\n      EIGEN_STRONG_INLINE\n      read(const Input &inpt, Index global_id) {\n    return inpt.coeff(global_id);\n  }\n\n  template <scan_step sst = stp, typename Input>\n  typename ::Eigen::internal::enable_if<sst != scan_step::first, CoeffReturnType>::type EIGEN_DEVICE_FUNC\n      EIGEN_STRONG_INLINE\n      read(const Input &inpt, Index global_id) {\n    return inpt[global_id];\n  }\n\n  template <scan_step sst = stp, typename InclusiveOp>\n  typename ::Eigen::internal::enable_if<sst == scan_step::first>::type EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  first_step_inclusive_Operation(InclusiveOp inclusive_op) {\n    inclusive_op();\n  }\n\n  template <scan_step sst = stp, typename InclusiveOp>\n  typename ::Eigen::internal::enable_if<sst != scan_step::first>::type EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  first_step_inclusive_Operation(InclusiveOp) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void operator()(cl::sycl::nd_item<1> itemID) {\n    auto out_ptr = out_accessor.get_pointer();\n    auto tmp_ptr = temp_accessor.get_pointer();\n    auto scratch_ptr = scratch.get_pointer().get();\n\n    for (Index loop_offset = 0; loop_offset < scanParameters.loop_range; loop_offset++) {\n      Index data_offset = (itemID.get_global_id(0) + (itemID.get_global_range(0) * loop_offset));\n      Index tmp = data_offset % scanParameters.panel_threads;\n      const Index panel_id = data_offset / scanParameters.panel_threads;\n      const Index group_id = tmp / scanParameters.group_threads;\n      tmp = tmp % scanParameters.group_threads;\n      const Index block_id = tmp / scanParameters.block_threads;\n      const Index local_id = tmp % scanParameters.block_threads;\n      // we put one element per packet in scratch_mem\n      const Index scratch_stride = scanParameters.elements_per_block / PacketSize;\n      const Index scratch_offset = (itemID.get_local_id(0) / scanParameters.block_threads) * scratch_stride;\n      CoeffReturnType private_scan[ScanParameters<Index>::ScanPerThread];\n      CoeffReturnType inclusive_scan;\n      // the actual panel size is scan_size * non_scan_size.\n      // elements_per_panel is roundup to power of 2 for binary tree\n      const Index panel_offset = panel_id * scanParameters.scan_size * scanParameters.non_scan_size;\n      const Index group_offset = group_id * scanParameters.non_scan_stride;\n      // This will be effective when the size is bigger than elements_per_block\n      const Index block_offset = block_id * scanParameters.elements_per_block * scanParameters.scan_stride;\n      const Index thread_offset = (ScanParameters<Index>::ScanPerThread * local_id * scanParameters.scan_stride);\n      const Index global_offset = panel_offset + group_offset + block_offset + thread_offset;\n      Index next_elements = 0;\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < ScanParameters<Index>::ScanPerThread; i++) {\n        Index global_id = global_offset + next_elements;\n        private_scan[i] = ((((block_id * scanParameters.elements_per_block) +\n                             (ScanParameters<Index>::ScanPerThread * local_id) + i) < scanParameters.scan_size) &&\n                           (global_id < scanParameters.total_size))\n                              ? read(dev_eval, global_id)\n                              : accumulator.initialize();\n        next_elements += scanParameters.scan_stride;\n      }\n      first_step_inclusive_Operation([&]() EIGEN_DEVICE_FUNC {\n        if (inclusive) {\n          inclusive_scan = private_scan[ScanParameters<Index>::ScanPerThread - 1];\n        }\n      });\n      // This for loop must be 2\n      EIGEN_UNROLL_LOOP\n      for (int packetIndex = 0; packetIndex < ScanParameters<Index>::ScanPerThread; packetIndex += PacketSize) {\n        Index private_offset = 1;\n        // build sum in place up the tree\n        EIGEN_UNROLL_LOOP\n        for (Index d = PacketSize >> 1; d > 0; d >>= 1) {\n          EIGEN_UNROLL_LOOP\n          for (Index l = 0; l < d; l++) {\n            Index ai = private_offset * (2 * l + 1) - 1 + packetIndex;\n            Index bi = private_offset * (2 * l + 2) - 1 + packetIndex;\n            CoeffReturnType accum = accumulator.initialize();\n            accumulator.reduce(private_scan[ai], &accum);\n            accumulator.reduce(private_scan[bi], &accum);\n            private_scan[bi] = accumulator.finalize(accum);\n          }\n          private_offset *= 2;\n        }\n        scratch_ptr[2 * local_id + (packetIndex / PacketSize) + scratch_offset] =\n            private_scan[PacketSize - 1 + packetIndex];\n        private_scan[PacketSize - 1 + packetIndex] = accumulator.initialize();\n        // traverse down tree & build scan\n        EIGEN_UNROLL_LOOP\n        for (Index d = 1; d < PacketSize; d *= 2) {\n          private_offset >>= 1;\n          EIGEN_UNROLL_LOOP\n          for (Index l = 0; l < d; l++) {\n            Index ai = private_offset * (2 * l + 1) - 1 + packetIndex;\n            Index bi = private_offset * (2 * l + 2) - 1 + packetIndex;\n            CoeffReturnType accum = accumulator.initialize();\n            accumulator.reduce(private_scan[ai], &accum);\n            accumulator.reduce(private_scan[bi], &accum);\n            private_scan[ai] = private_scan[bi];\n            private_scan[bi] = accumulator.finalize(accum);\n          }\n        }\n      }\n\n      Index offset = 1;\n      // build sum in place up the tree\n      for (Index d = scratch_stride >> 1; d > 0; d >>= 1) {\n        // Synchronise\n        itemID.barrier(cl::sycl::access::fence_space::local_space);\n        if (local_id < d) {\n          Index ai = offset * (2 * local_id + 1) - 1 + scratch_offset;\n          Index bi = offset * (2 * local_id + 2) - 1 + scratch_offset;\n          CoeffReturnType accum = accumulator.initialize();\n          accumulator.reduce(scratch_ptr[ai], &accum);\n          accumulator.reduce(scratch_ptr[bi], &accum);\n          scratch_ptr[bi] = accumulator.finalize(accum);\n        }\n        offset *= 2;\n      }\n      // Synchronise\n      itemID.barrier(cl::sycl::access::fence_space::local_space);\n      // next step optimisation\n      if (local_id == 0) {\n        if (((scanParameters.elements_per_group / scanParameters.elements_per_block) > 1)) {\n          const Index temp_id = panel_id * (scanParameters.elements_per_group / scanParameters.elements_per_block) *\n                                    scanParameters.non_scan_size +\n                                group_id * (scanParameters.elements_per_group / scanParameters.elements_per_block) +\n                                block_id;\n          tmp_ptr[temp_id] = scratch_ptr[scratch_stride - 1 + scratch_offset];\n        }\n        // clear the last element\n        scratch_ptr[scratch_stride - 1 + scratch_offset] = accumulator.initialize();\n      }\n      // traverse down tree & build scan\n      for (Index d = 1; d < scratch_stride; d *= 2) {\n        offset >>= 1;\n        // Synchronise\n        itemID.barrier(cl::sycl::access::fence_space::local_space);\n        if (local_id < d) {\n          Index ai = offset * (2 * local_id + 1) - 1 + scratch_offset;\n          Index bi = offset * (2 * local_id + 2) - 1 + scratch_offset;\n          CoeffReturnType accum = accumulator.initialize();\n          accumulator.reduce(scratch_ptr[ai], &accum);\n          accumulator.reduce(scratch_ptr[bi], &accum);\n          scratch_ptr[ai] = scratch_ptr[bi];\n          scratch_ptr[bi] = accumulator.finalize(accum);\n        }\n      }\n      // Synchronise\n      itemID.barrier(cl::sycl::access::fence_space::local_space);\n      // This for loop must be 2\n      EIGEN_UNROLL_LOOP\n      for (int packetIndex = 0; packetIndex < ScanParameters<Index>::ScanPerThread; packetIndex += PacketSize) {\n        EIGEN_UNROLL_LOOP\n        for (Index i = 0; i < PacketSize; i++) {\n          CoeffReturnType accum = private_scan[packetIndex + i];\n          accumulator.reduce(scratch_ptr[2 * local_id + (packetIndex / PacketSize) + scratch_offset], &accum);\n          private_scan[packetIndex + i] = accumulator.finalize(accum);\n        }\n      }\n      first_step_inclusive_Operation([&]() EIGEN_DEVICE_FUNC {\n        if (inclusive) {\n          accumulator.reduce(private_scan[ScanParameters<Index>::ScanPerThread - 1], &inclusive_scan);\n          private_scan[0] = accumulator.finalize(inclusive_scan);\n        }\n      });\n      next_elements = 0;\n      // right the first set of private param\n      EIGEN_UNROLL_LOOP\n      for (Index i = 0; i < ScanParameters<Index>::ScanPerThread; i++) {\n        Index global_id = global_offset + next_elements;\n        if ((((block_id * scanParameters.elements_per_block) + (ScanParameters<Index>::ScanPerThread * local_id) + i) <\n             scanParameters.scan_size) &&\n            (global_id < scanParameters.total_size)) {\n          Index private_id = (i * !inclusive) + (((i + 1) % ScanParameters<Index>::ScanPerThread) * (inclusive));\n          out_ptr[global_id] = private_scan[private_id];\n        }\n        next_elements += scanParameters.scan_stride;\n      }\n    }  // end for loop\n  }\n};\n\ntemplate <typename CoeffReturnType, typename InAccessor, typename OutAccessor, typename Op, typename Index>\nstruct ScanAdjustmentKernelFunctor {\n  typedef cl::sycl::accessor<CoeffReturnType, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local>\n      LocalAccessor;\n  static EIGEN_CONSTEXPR int PacketSize = ScanParameters<Index>::ScanPerThread / 2;\n  InAccessor in_accessor;\n  OutAccessor out_accessor;\n  const ScanParameters<Index> scanParameters;\n  Op accumulator;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ScanAdjustmentKernelFunctor(LocalAccessor, InAccessor in_accessor_,\n                                                                    OutAccessor out_accessor_,\n                                                                    const ScanParameters<Index> scanParameters_,\n                                                                    Op accumulator_)\n      : in_accessor(in_accessor_),\n        out_accessor(out_accessor_),\n        scanParameters(scanParameters_),\n        accumulator(accumulator_) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void operator()(cl::sycl::nd_item<1> itemID) {\n    auto in_ptr = in_accessor.get_pointer();\n    auto out_ptr = out_accessor.get_pointer();\n\n    for (Index loop_offset = 0; loop_offset < scanParameters.loop_range; loop_offset++) {\n      Index data_offset = (itemID.get_global_id(0) + (itemID.get_global_range(0) * loop_offset));\n      Index tmp = data_offset % scanParameters.panel_threads;\n      const Index panel_id = data_offset / scanParameters.panel_threads;\n      const Index group_id = tmp / scanParameters.group_threads;\n      tmp = tmp % scanParameters.group_threads;\n      const Index block_id = tmp / scanParameters.block_threads;\n      const Index local_id = tmp % scanParameters.block_threads;\n\n      // the actual panel size is scan_size * non_scan_size.\n      // elements_per_panel is roundup to power of 2 for binary tree\n      const Index panel_offset = panel_id * scanParameters.scan_size * scanParameters.non_scan_size;\n      const Index group_offset = group_id * scanParameters.non_scan_stride;\n      // This will be effective when the size is bigger than elements_per_block\n      const Index block_offset = block_id * scanParameters.elements_per_block * scanParameters.scan_stride;\n      const Index thread_offset = ScanParameters<Index>::ScanPerThread * local_id * scanParameters.scan_stride;\n\n      const Index global_offset = panel_offset + group_offset + block_offset + thread_offset;\n      const Index block_size = scanParameters.elements_per_group / scanParameters.elements_per_block;\n      const Index in_id = (panel_id * block_size * scanParameters.non_scan_size) + (group_id * block_size) + block_id;\n      CoeffReturnType adjust_val = in_ptr[in_id];\n\n      Index next_elements = 0;\n      EIGEN_UNROLL_LOOP\n      for (Index i = 0; i < ScanParameters<Index>::ScanPerThread; i++) {\n        Index global_id = global_offset + next_elements;\n        if ((((block_id * scanParameters.elements_per_block) + (ScanParameters<Index>::ScanPerThread * local_id) + i) <\n             scanParameters.scan_size) &&\n            (global_id < scanParameters.total_size)) {\n          CoeffReturnType accum = adjust_val;\n          accumulator.reduce(out_ptr[global_id], &accum);\n          out_ptr[global_id] = accumulator.finalize(accum);\n        }\n        next_elements += scanParameters.scan_stride;\n      }\n    }\n  }\n};\n\ntemplate <typename Index>\nstruct ScanInfo {\n  const Index &total_size;\n  const Index &scan_size;\n  const Index &panel_size;\n  const Index &non_scan_size;\n  const Index &scan_stride;\n  const Index &non_scan_stride;\n\n  Index max_elements_per_block;\n  Index block_size;\n  Index panel_threads;\n  Index group_threads;\n  Index block_threads;\n  Index elements_per_group;\n  Index elements_per_block;\n  Index loop_range;\n  Index global_range;\n  Index local_range;\n  const Eigen::SyclDevice &dev;\n  EIGEN_STRONG_INLINE ScanInfo(const Index &total_size_, const Index &scan_size_, const Index &panel_size_,\n                               const Index &non_scan_size_, const Index &scan_stride_, const Index &non_scan_stride_,\n                               const Eigen::SyclDevice &dev_)\n      : total_size(total_size_),\n        scan_size(scan_size_),\n        panel_size(panel_size_),\n        non_scan_size(non_scan_size_),\n        scan_stride(scan_stride_),\n        non_scan_stride(non_scan_stride_),\n        dev(dev_) {\n    // must be power of 2\n    local_range = std::min(Index(dev.getNearestPowerOfTwoWorkGroupSize()),\n                           Index(EIGEN_SYCL_LOCAL_THREAD_DIM0 * EIGEN_SYCL_LOCAL_THREAD_DIM1));\n\n    max_elements_per_block = local_range * ScanParameters<Index>::ScanPerThread;\n\n    elements_per_group =\n        dev.getPowerOfTwo(Index(roundUp(Index(scan_size), ScanParameters<Index>::ScanPerThread)), true);\n    const Index elements_per_panel = elements_per_group * non_scan_size;\n    elements_per_block = std::min(Index(elements_per_group), Index(max_elements_per_block));\n    panel_threads = elements_per_panel / ScanParameters<Index>::ScanPerThread;\n    group_threads = elements_per_group / ScanParameters<Index>::ScanPerThread;\n    block_threads = elements_per_block / ScanParameters<Index>::ScanPerThread;\n    block_size = elements_per_group / elements_per_block;\n#ifdef EIGEN_SYCL_MAX_GLOBAL_RANGE\n    const Index max_threads = std::min(Index(panel_threads * panel_size), Index(EIGEN_SYCL_MAX_GLOBAL_RANGE));\n#else\n    const Index max_threads = panel_threads * panel_size;\n#endif\n    global_range = roundUp(max_threads, local_range);\n    loop_range = Index(\n        std::ceil(double(elements_per_panel * panel_size) / (global_range * ScanParameters<Index>::ScanPerThread)));\n  }\n  inline ScanParameters<Index> get_scan_parameter() {\n    return ScanParameters<Index>(total_size, non_scan_size, scan_size, non_scan_stride, scan_stride, panel_threads,\n                                 group_threads, block_threads, elements_per_group, elements_per_block, loop_range);\n  }\n  inline cl::sycl::nd_range<1> get_thread_range() {\n    return cl::sycl::nd_range<1>(cl::sycl::range<1>(global_range), cl::sycl::range<1>(local_range));\n  }\n};\n\ntemplate <typename EvaluatorPointerType, typename CoeffReturnType, typename Reducer, typename Index>\nstruct SYCLAdjustBlockOffset {\n  EIGEN_STRONG_INLINE static void adjust_scan_block_offset(EvaluatorPointerType in_ptr, EvaluatorPointerType out_ptr,\n                                                           Reducer &accumulator, const Index total_size,\n                                                           const Index scan_size, const Index panel_size,\n                                                           const Index non_scan_size, const Index scan_stride,\n                                                           const Index non_scan_stride, const Eigen::SyclDevice &dev) {\n    auto scan_info =\n        ScanInfo<Index>(total_size, scan_size, panel_size, non_scan_size, scan_stride, non_scan_stride, dev);\n\n    typedef ScanAdjustmentKernelFunctor<CoeffReturnType, EvaluatorPointerType, EvaluatorPointerType, Reducer, Index>\n        AdjustFuctor;\n    dev.template unary_kernel_launcher<CoeffReturnType, AdjustFuctor>(in_ptr, out_ptr, scan_info.get_thread_range(),\n                                                                      scan_info.max_elements_per_block,\n                                                                      scan_info.get_scan_parameter(), accumulator);\n  }\n};\n\ntemplate <typename CoeffReturnType, scan_step stp>\nstruct ScanLauncher_impl {\n  template <typename Input, typename EvaluatorPointerType, typename Reducer, typename Index>\n  EIGEN_STRONG_INLINE static void scan_block(Input in_ptr, EvaluatorPointerType out_ptr, Reducer &accumulator,\n                                             const Index total_size, const Index scan_size, const Index panel_size,\n                                             const Index non_scan_size, const Index scan_stride,\n                                             const Index non_scan_stride, const bool inclusive,\n                                             const Eigen::SyclDevice &dev) {\n    auto scan_info =\n        ScanInfo<Index>(total_size, scan_size, panel_size, non_scan_size, scan_stride, non_scan_stride, dev);\n    const Index temp_pointer_size = scan_info.block_size * non_scan_size * panel_size;\n    const Index scratch_size = scan_info.max_elements_per_block / (ScanParameters<Index>::ScanPerThread / 2);\n    CoeffReturnType *temp_pointer =\n        static_cast<CoeffReturnType *>(dev.allocate_temp(temp_pointer_size * sizeof(CoeffReturnType)));\n    EvaluatorPointerType tmp_global_accessor = dev.get(temp_pointer);\n\n    typedef ScanKernelFunctor<Input, CoeffReturnType, EvaluatorPointerType, Reducer, Index, stp> ScanFunctor;\n    dev.template binary_kernel_launcher<CoeffReturnType, ScanFunctor>(\n        in_ptr, out_ptr, tmp_global_accessor, scan_info.get_thread_range(), scratch_size,\n        scan_info.get_scan_parameter(), accumulator, inclusive);\n\n    if (scan_info.block_size > 1) {\n      ScanLauncher_impl<CoeffReturnType, scan_step::second>::scan_block(\n          tmp_global_accessor, tmp_global_accessor, accumulator, temp_pointer_size, scan_info.block_size, panel_size,\n          non_scan_size, Index(1), scan_info.block_size, false, dev);\n\n      SYCLAdjustBlockOffset<EvaluatorPointerType, CoeffReturnType, Reducer, Index>::adjust_scan_block_offset(\n          tmp_global_accessor, out_ptr, accumulator, total_size, scan_size, panel_size, non_scan_size, scan_stride,\n          non_scan_stride, dev);\n    }\n    dev.deallocate_temp(temp_pointer);\n  }\n};\n\n}  // namespace internal\n}  // namespace TensorSycl\nnamespace internal {\ntemplate <typename Self, typename Reducer, bool vectorize>\nstruct ScanLauncher<Self, Reducer, Eigen::SyclDevice, vectorize> {\n  typedef typename Self::Index Index;\n  typedef typename Self::CoeffReturnType CoeffReturnType;\n  typedef typename Self::Storage Storage;\n  typedef typename Self::EvaluatorPointerType EvaluatorPointerType;\n  void operator()(Self &self, EvaluatorPointerType data) {\n    const Index total_size = internal::array_prod(self.dimensions());\n    const Index scan_size = self.size();\n    const Index scan_stride = self.stride();\n    // this is the scan op (can be sum or ...)\n    auto accumulator = self.accumulator();\n    auto inclusive = !self.exclusive();\n    auto consume_dim = self.consume_dim();\n    auto dev = self.device();\n\n    auto dims = self.inner().dimensions();\n\n    Index non_scan_size = 1;\n    Index panel_size = 1;\n    if (static_cast<int>(Self::Layout) == static_cast<int>(ColMajor)) {\n      for (int i = 0; i < consume_dim; i++) {\n        non_scan_size *= dims[i];\n      }\n      for (int i = consume_dim + 1; i < Self::NumDims; i++) {\n        panel_size *= dims[i];\n      }\n    } else {\n      for (int i = Self::NumDims - 1; i > consume_dim; i--) {\n        non_scan_size *= dims[i];\n      }\n      for (int i = consume_dim - 1; i >= 0; i--) {\n        panel_size *= dims[i];\n      }\n    }\n    const Index non_scan_stride = (scan_stride > 1) ? 1 : scan_size;\n    auto eval_impl = self.inner();\n    TensorSycl::internal::ScanLauncher_impl<CoeffReturnType, TensorSycl::internal::scan_step::first>::scan_block(\n        eval_impl, data, accumulator, total_size, scan_size, panel_size, non_scan_size, scan_stride, non_scan_stride,\n        inclusive, dev);\n  }\n};\n} // namespace internal\n}  // namespace Eigen\n\n#endif  // UNSUPPORTED_EIGEN_CXX11_SRC_TENSOR_TENSOR_SYCL_SYCL_HPP\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorShuffling.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_SHUFFLING_H\n#define EIGEN_CXX11_TENSOR_TENSOR_SHUFFLING_H\n\nnamespace Eigen {\n\n/** \\class TensorShuffling\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor shuffling class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename Shuffle, typename XprType>\nstruct traits<TensorShufflingOp<Shuffle, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename Shuffle, typename XprType>\nstruct eval<TensorShufflingOp<Shuffle, XprType>, Eigen::Dense>\n{\n  typedef const TensorShufflingOp<Shuffle, XprType>& type;\n};\n\ntemplate<typename Shuffle, typename XprType>\nstruct nested<TensorShufflingOp<Shuffle, XprType>, 1, typename eval<TensorShufflingOp<Shuffle, XprType> >::type>\n{\n  typedef TensorShufflingOp<Shuffle, XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename Shuffle, typename XprType>\nclass TensorShufflingOp : public TensorBase<TensorShufflingOp<Shuffle, XprType> >\n{\n  public:\n    typedef TensorBase<TensorShufflingOp<Shuffle, XprType> > Base;\n    typedef typename Eigen::internal::traits<TensorShufflingOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef typename XprType::CoeffReturnType CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorShufflingOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorShufflingOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorShufflingOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorShufflingOp(const XprType& expr, const Shuffle& shfl)\n      : m_xpr(expr), m_shuffle(shfl) {}\n\n    EIGEN_DEVICE_FUNC\n    const Shuffle& shufflePermutation() const { return m_shuffle; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(TensorShufflingOp)\n\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const Shuffle m_shuffle;\n};\n\n\n// Eval as rvalue\ntemplate<typename Shuffle, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorShufflingOp<Shuffle, ArgType>, Device>\n{\n  typedef TensorEvaluator<const TensorShufflingOp<Shuffle, ArgType>, Device> Self;\n  typedef TensorShufflingOp<Shuffle, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned         = false,\n    PacketAccess      = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess       = TensorEvaluator<ArgType, Device>::RawAccess,\n    PreferBlockAccess = true,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = false\n  };\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename internal::TensorMaterializedBlock<ScalarNoConst, NumDims,\n                                                     Layout, Index>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_device(device),\n        m_impl(op.expression(), device)\n  {\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n    const Shuffle& shuffle = op.shufflePermutation();\n    m_is_identity = true;\n    for (int i = 0; i < NumDims; ++i) {\n      m_shuffle[i] = static_cast<int>(shuffle[i]);\n      m_dimensions[i] = input_dims[shuffle[i]];\n      m_inverseShuffle[shuffle[i]] = i;\n      if (m_is_identity && shuffle[i] != i) {\n        m_is_identity = false;\n      }\n    }\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_unshuffledInputStrides[0] = 1;\n      m_outputStrides[0] = 1;\n\n      for (int i = 1; i < NumDims; ++i) {\n        m_unshuffledInputStrides[i] =\n            m_unshuffledInputStrides[i - 1] * input_dims[i - 1];\n        m_outputStrides[i] = m_outputStrides[i - 1] * m_dimensions[i - 1];\n        m_fastOutputStrides[i] = internal::TensorIntDivisor<Index>(\n                  m_outputStrides[i] > 0 ? m_outputStrides[i] : Index(1));\n      }\n    } else {\n      m_unshuffledInputStrides[NumDims - 1] = 1;\n      m_outputStrides[NumDims - 1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_unshuffledInputStrides[i] =\n            m_unshuffledInputStrides[i + 1] * input_dims[i + 1];\n        m_outputStrides[i] = m_outputStrides[i + 1] * m_dimensions[i + 1];\n        m_fastOutputStrides[i] = internal::TensorIntDivisor<Index>(\n                  m_outputStrides[i] > 0 ? m_outputStrides[i] : Index(1));\n      }\n    }\n\n    for (int i = 0; i < NumDims; ++i) {\n      m_inputStrides[i] = m_unshuffledInputStrides[shuffle[i]];\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType /*data*/) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    m_impl.evalSubExprsIfNeededAsync(nullptr, [done](bool) { done(true); });\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    if (m_is_identity) {\n      return m_impl.coeff(index);\n    } else {\n      return m_impl.coeff(srcCoeff(index));\n    }\n  }\n\n  template <int LoadMode, typename Self, bool ImplPacketAccess>\n  struct PacketLoader {\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    static PacketReturnType Run(const Self& self, Index index) {\n      EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < PacketSize; ++i) {\n        values[i] = self.coeff(index + i);\n      }\n      PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n      return rslt;\n    }\n  };\n\n  template<int LoadMode, typename Self>\n  struct PacketLoader<LoadMode, Self, true> {\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    static PacketReturnType Run(const Self& self, Index index) {\n      if (self.m_is_identity) {\n        return self.m_impl.template packet<LoadMode>(index);\n      } else {\n        EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n        EIGEN_UNROLL_LOOP\n        for (int i = 0; i < PacketSize; ++i) {\n          values[i] = self.coeff(index + i);\n        }\n        PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n        return rslt;\n      }\n    }\n  };\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n        eigen_assert(index + PacketSize - 1 < dimensions().TotalSize());\n    return PacketLoader<LoadMode, Self, TensorEvaluator<ArgType, Device>::PacketAccess>::Run(*this, index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    static const int inner_dim =\n        Layout == static_cast<int>(ColMajor) ? 0 : NumDims - 1;\n\n    const size_t target_size = m_device.firstLevelCacheSize();\n    const bool inner_dim_shuffled = m_shuffle[inner_dim] != inner_dim;\n\n    // Shuffled inner dimensions leads to a random memory access, which is not\n    // captured by default cost model bytes loaded/stored. We add this cost\n    // explicitly. The number of cycles picked based on the benchmarks.\n    // TODO(ezhulenev): This number was picked based on a very questionable\n    // benchmarks, add benchmarks that are representative of real workloads.\n    using BlockRequirements = internal::TensorBlockResourceRequirements;\n    if (inner_dim_shuffled) {\n      return BlockRequirements::uniform<Scalar>(target_size)\n          .addCostPerCoeff({0, 0, NumDims * 28});\n    } else {\n      return BlockRequirements::skewed<Scalar>(target_size);\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool root_of_expr_ast = false) const {\n    assert(m_impl.data() != NULL);\n\n    typedef internal::TensorBlockIO<ScalarNoConst, Index, NumDims, Layout>\n        TensorBlockIO;\n    typedef typename TensorBlockIO::Dst TensorBlockIODst;\n    typedef typename TensorBlockIO::Src TensorBlockIOSrc;\n\n    const typename TensorBlock::Storage block_storage =\n        TensorBlock::prepareStorage(\n            desc, scratch, /*allow_strided_storage=*/root_of_expr_ast);\n\n    typename TensorBlockIO::Dimensions input_strides(m_unshuffledInputStrides);\n    TensorBlockIOSrc src(input_strides, m_impl.data(), srcCoeff(desc.offset()));\n\n    TensorBlockIODst dst(block_storage.dimensions(), block_storage.strides(),\n                         block_storage.data());\n\n    typename TensorBlockIO::DimensionsMap dst_to_src_dim_map(m_shuffle);\n    TensorBlockIO::Copy(dst, src, dst_to_src_dim_map);\n\n    return block_storage.AsTensorMaterializedBlock();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    const double compute_cost = m_is_identity ? TensorOpCost::AddCost<Index>() :\n                                NumDims * (2 * TensorOpCost::AddCost<Index>() +\n                                           2 * TensorOpCost::MulCost<Index>() +\n                                           TensorOpCost::DivCost<Index>());\n    return m_impl.costPerCoeff(vectorized) +\n           TensorOpCost(0, 0, compute_cost, m_is_identity /* vectorized */, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC typename Storage::Type data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n   // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n protected:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index GetBlockOutputIndex(\n      Index input_index,\n      const DSizes<Index, NumDims>& input_block_strides,\n      const DSizes<Index, NumDims>& output_block_strides,\n      const DSizes<internal::TensorIntDivisor<Index>, NumDims>& fast_input_block_strides) const {\n    Index output_index = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx = input_index / fast_input_block_strides[i];\n        output_index += idx * output_block_strides[m_inverseShuffle[i]];\n        input_index -= idx * input_block_strides[i];\n      }\n      return output_index + input_index *\n          output_block_strides[m_inverseShuffle[0]];\n    } else {\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx = input_index / fast_input_block_strides[i];\n        output_index += idx * output_block_strides[m_inverseShuffle[i]];\n        input_index -= idx * input_block_strides[i];\n      }\n      return output_index + input_index *\n          output_block_strides[m_inverseShuffle[NumDims - 1]];\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index srcCoeff(Index index) const {\n    Index inputIndex = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx = index / m_fastOutputStrides[i];\n        inputIndex += idx * m_inputStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      return inputIndex + index * m_inputStrides[0];\n    } else {\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx = index / m_fastOutputStrides[i];\n        inputIndex += idx * m_inputStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      return inputIndex + index * m_inputStrides[NumDims - 1];\n    }\n  }\n\n  Dimensions m_dimensions;\n  bool m_is_identity;\n  array<int, NumDims> m_shuffle;\n  array<Index, NumDims> m_inverseShuffle;  // TODO(ezhulenev): Make it int type.\n  array<Index, NumDims> m_outputStrides;\n  array<internal::TensorIntDivisor<Index>, NumDims> m_fastOutputStrides;\n  array<Index, NumDims> m_inputStrides;\n  array<Index, NumDims> m_unshuffledInputStrides;\n\n  const Device EIGEN_DEVICE_REF m_device;\n  TensorEvaluator<ArgType, Device> m_impl;\n};\n\n\n// Eval as lvalue\ntemplate<typename Shuffle, typename ArgType, typename Device>\nstruct TensorEvaluator<TensorShufflingOp<Shuffle, ArgType>, Device>\n    : public TensorEvaluator<const TensorShufflingOp<Shuffle, ArgType>, Device>\n{\n  typedef TensorEvaluator<const TensorShufflingOp<Shuffle, ArgType>, Device> Base;\n\n  typedef TensorShufflingOp<Shuffle, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n\n  enum {\n    IsAligned         = false,\n    PacketAccess      = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess       = TensorEvaluator<ArgType, Device>::RawAccess,\n    PreferBlockAccess = true,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    RawAccess         = false\n  };\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : Base(op, device)\n  { }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index)\n  {\n    return this->m_impl.coeffRef(this->srcCoeff(index));\n  }\n\n  template <int StoreMode> EIGEN_STRONG_INLINE\n  void writePacket(Index index, const PacketReturnType& x)\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n    internal::pstore<CoeffReturnType, PacketReturnType>(values, x);\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < PacketSize; ++i) {\n      this->coeffRef(index+i) = values[i];\n    }\n  }\n\n  template <typename TensorBlock>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void writeBlock(\n      const TensorBlockDesc& desc, const TensorBlock& block) {\n    eigen_assert(this->m_impl.data() != NULL);\n\n    typedef internal::TensorBlockIO<ScalarNoConst, Index, NumDims, Layout>\n        TensorBlockIO;\n    typedef typename TensorBlockIO::Dst TensorBlockIODst;\n    typedef typename TensorBlockIO::Src TensorBlockIOSrc;\n\n    const Scalar* block_buffer = block.data();\n\n    // TODO(ezhulenev): TensorBlockIO should be able to read from any Eigen\n    // expression with coefficient and packet access as `src`.\n    void* mem = NULL;\n    if (block_buffer == NULL) {\n      mem = this->m_device.allocate(desc.size() * sizeof(Scalar));\n      ScalarNoConst* buf = static_cast<ScalarNoConst*>(mem);\n\n      typedef internal::TensorBlockAssignment<\n          ScalarNoConst, NumDims, typename TensorBlock::XprType, Index>\n          TensorBlockAssignment;\n\n      TensorBlockAssignment::Run(\n          TensorBlockAssignment::target(\n              desc.dimensions(), internal::strides<Layout>(desc.dimensions()),\n              buf),\n          block.expr());\n\n      block_buffer = buf;\n    }\n\n    // Read from block.\n    TensorBlockIOSrc src(internal::strides<Layout>(desc.dimensions()),\n                         block_buffer);\n\n    // Write to the output buffer.\n    typename TensorBlockIO::Dimensions output_strides(\n        this->m_unshuffledInputStrides);\n    typename TensorBlockIO::Dimensions output_dimensions;\n    for (int i = 0; i < NumDims; ++i) {\n      output_dimensions[this->m_shuffle[i]] = desc.dimension(i);\n    }\n    TensorBlockIODst dst(output_dimensions, output_strides, this->m_impl.data(),\n                         this->srcCoeff(desc.offset()));\n\n    // Reorder dimensions according to the shuffle.\n    typename TensorBlockIO::DimensionsMap dst_to_src_dim_map;\n    for (int i = 0; i < NumDims; ++i) {\n      dst_to_src_dim_map[i] = static_cast<int>(this->m_inverseShuffle[i]);\n    }\n    TensorBlockIO::Copy(dst, src, dst_to_src_dim_map);\n\n    // Deallocate temporary buffer used for the block materialization.\n    if (mem != NULL) this->m_device.deallocate(mem);\n  }\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_SHUFFLING_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorStorage.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n// Copyright (C) 2014-2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSORSTORAGE_H\n#define EIGEN_CXX11_TENSOR_TENSORSTORAGE_H\n\n#ifdef EIGEN_TENSOR_STORAGE_CTOR_PLUGIN\n  #define EIGEN_INTERNAL_TENSOR_STORAGE_CTOR_PLUGIN EIGEN_TENSOR_STORAGE_CTOR_PLUGIN;\n#else\n  #define EIGEN_INTERNAL_TENSOR_STORAGE_CTOR_PLUGIN\n#endif\n\nnamespace Eigen {\n\n/** \\internal\n  *\n  * \\class TensorStorage\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Stores the data of a tensor\n  *\n  * This class stores the data of fixed-size, dynamic-size or mixed tensors\n  * in a way as compact as possible.\n  *\n  * \\sa Tensor\n  */\ntemplate<typename T, typename Dimensions, int Options> class TensorStorage;\n\n\n// Pure fixed-size storage\ntemplate<typename T, typename FixedDimensions, int Options_>\nclass TensorStorage\n{\n private:\n  static const std::size_t Size = FixedDimensions::total_size;\n\n  // Allocate an array of size at least one to prevent compiler warnings.\n  static const std::size_t MinSize = max_n_1<Size>::size;\n  EIGEN_ALIGN_MAX T m_data[MinSize];\n\n public:\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE TensorStorage() {\n  }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE T *data() { return m_data; }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE const T *data() const { return m_data; }\n\n  static EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE const FixedDimensions& dimensions()\n  {\n    static const FixedDimensions* singleton_dimensions = new FixedDimensions();\n    return *singleton_dimensions;\n  }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE DenseIndex size() const { return Size; }\n};\n\n// pure dynamic\ntemplate<typename T, typename IndexType, int NumIndices_, int Options_>\nclass TensorStorage<T, DSizes<IndexType, NumIndices_>, Options_>\n{\n  public:\n    typedef IndexType Index;\n    typedef DSizes<IndexType, NumIndices_> Dimensions;\n    typedef TensorStorage<T, DSizes<IndexType, NumIndices_>, Options_> Self;\n\n    EIGEN_DEVICE_FUNC TensorStorage() : m_data(0), m_dimensions() {\n      if (NumIndices_ == 0) {\n\tm_data = internal::conditional_aligned_new_auto<T,(Options_&DontAlign)==0>(1);\n      }\n    }\n    EIGEN_DEVICE_FUNC TensorStorage(internal::constructor_without_unaligned_array_assert)\n      : m_data(0), m_dimensions(internal::template repeat<NumIndices_, Index>(0)) {}\n    EIGEN_DEVICE_FUNC TensorStorage(Index size, const array<Index, NumIndices_>& dimensions)\n        : m_data(internal::conditional_aligned_new_auto<T,(Options_&DontAlign)==0>(size)), m_dimensions(dimensions)\n      { EIGEN_INTERNAL_TENSOR_STORAGE_CTOR_PLUGIN }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template <typename... DenseIndex>\n    EIGEN_DEVICE_FUNC TensorStorage(DenseIndex... indices) : m_dimensions(indices...) {\n      m_data = internal::conditional_aligned_new_auto<T,(Options_&DontAlign)==0>(internal::array_prod(m_dimensions));\n    }\n#endif\n\n    EIGEN_DEVICE_FUNC TensorStorage(const Self& other)\n      : m_data(internal::conditional_aligned_new_auto<T,(Options_&DontAlign)==0>(internal::array_prod(other.m_dimensions)))\n      , m_dimensions(other.m_dimensions)\n    {\n      internal::smart_copy(other.m_data, other.m_data+internal::array_prod(other.m_dimensions), m_data);\n    }\n    EIGEN_DEVICE_FUNC Self& operator=(const Self& other)\n    {\n      if (this != &other) {\n        Self tmp(other);\n        this->swap(tmp);\n      }\n      return *this;\n    }\n\n#if EIGEN_HAS_RVALUE_REFERENCES\n    EIGEN_DEVICE_FUNC TensorStorage(Self&& other) : TensorStorage()\n    {\n      *this = std::move(other);\n    }\n    \n    EIGEN_DEVICE_FUNC Self& operator=(Self&& other)\n    {\n      numext::swap(m_data, other.m_data);\n      numext::swap(m_dimensions, other.m_dimensions);\n      return *this;\n    }\n#endif\n\n    EIGEN_DEVICE_FUNC  ~TensorStorage() { internal::conditional_aligned_delete_auto<T,(Options_&DontAlign)==0>(m_data, internal::array_prod(m_dimensions)); }\n    EIGEN_DEVICE_FUNC  void swap(Self& other)\n    { numext::swap(m_data,other.m_data); numext::swap(m_dimensions,other.m_dimensions); }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const {return m_dimensions;}\n\n    EIGEN_DEVICE_FUNC void resize(Index size, const array<Index, NumIndices_>& nbDimensions)\n    {\n      const Index currentSz = internal::array_prod(m_dimensions);\n      if(size != currentSz)\n      {\n        internal::conditional_aligned_delete_auto<T,(Options_&DontAlign)==0>(m_data, currentSz);\n        if (size)\n          m_data = internal::conditional_aligned_new_auto<T,(Options_&DontAlign)==0>(size);\n        else if (NumIndices_ == 0) {\n\t  m_data = internal::conditional_aligned_new_auto<T,(Options_&DontAlign)==0>(1);\n\t}\n\telse \n          m_data = 0;\n        EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN({})\n      }\n      m_dimensions = nbDimensions;\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T *data() { return m_data; }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const T *data() const { return m_data; }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index size() const { return m_dimensions.TotalSize(); }\n\n private:\n  T *m_data;\n  Dimensions m_dimensions;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSORSTORAGE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorStriding.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_STRIDING_H\n#define EIGEN_CXX11_TENSOR_TENSOR_STRIDING_H\n\nnamespace Eigen {\n\n/** \\class TensorStriding\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor striding class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename Strides, typename XprType>\nstruct traits<TensorStridingOp<Strides, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename Strides, typename XprType>\nstruct eval<TensorStridingOp<Strides, XprType>, Eigen::Dense>\n{\n  typedef const TensorStridingOp<Strides, XprType>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename Strides, typename XprType>\nstruct nested<TensorStridingOp<Strides, XprType>, 1, typename eval<TensorStridingOp<Strides, XprType> >::type>\n{\n  typedef TensorStridingOp<Strides, XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename Strides, typename XprType>\nclass TensorStridingOp : public TensorBase<TensorStridingOp<Strides, XprType> >\n{\n  public:\n    typedef TensorBase<TensorStridingOp<Strides, XprType> > Base;\n    typedef typename Eigen::internal::traits<TensorStridingOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef typename XprType::CoeffReturnType CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorStridingOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorStridingOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorStridingOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorStridingOp(const XprType& expr, const Strides& dims)\n      : m_xpr(expr), m_dims(dims) {}\n\n    EIGEN_DEVICE_FUNC\n    const Strides& strides() const { return m_dims; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(TensorStridingOp)\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const Strides m_dims;\n};\n\n\n// Eval as rvalue\ntemplate<typename Strides, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorStridingOp<Strides, ArgType>, Device>\n{\n  typedef TensorStridingOp<Strides, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = /*TensorEvaluator<ArgType, Device>::IsAligned*/false,\n    PacketAccess = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess = false,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device)\n  {\n    m_dimensions = m_impl.dimensions();\n    for (int i = 0; i < NumDims; ++i) {\n      m_dimensions[i] =Eigen::numext::ceil(static_cast<float>(m_dimensions[i]) / op.strides()[i]);\n    }\n\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_outputStrides[0] = 1;\n      m_inputStrides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_outputStrides[i] = m_outputStrides[i-1] * m_dimensions[i-1];\n        m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1];\n        m_inputStrides[i-1] *= op.strides()[i-1];\n      }\n      m_inputStrides[NumDims-1] *= op.strides()[NumDims-1];\n    } else {  // RowMajor\n      m_outputStrides[NumDims-1] = 1;\n      m_inputStrides[NumDims-1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_outputStrides[i] = m_outputStrides[i+1] * m_dimensions[i+1];\n        m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1];\n        m_inputStrides[i+1] *= op.strides()[i+1];\n      }\n      m_inputStrides[0] *= op.strides()[0];\n    }\n  }\n\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType/*data*/) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    return m_impl.coeff(srcCoeff(index));\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    Index inputIndices[] = {0, 0};\n    Index indices[] = {index, index + PacketSize - 1};\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx0 = indices[0] / m_outputStrides[i];\n        const Index idx1 = indices[1] / m_outputStrides[i];\n        inputIndices[0] += idx0 * m_inputStrides[i];\n        inputIndices[1] += idx1 * m_inputStrides[i];\n        indices[0] -= idx0 * m_outputStrides[i];\n        indices[1] -= idx1 * m_outputStrides[i];\n      }\n      inputIndices[0] += indices[0] * m_inputStrides[0];\n      inputIndices[1] += indices[1] * m_inputStrides[0];\n    } else {  // RowMajor\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx0 = indices[0] / m_outputStrides[i];\n        const Index idx1 = indices[1] / m_outputStrides[i];\n        inputIndices[0] += idx0 * m_inputStrides[i];\n        inputIndices[1] += idx1 * m_inputStrides[i];\n        indices[0] -= idx0 * m_outputStrides[i];\n        indices[1] -= idx1 * m_outputStrides[i];\n      }\n      inputIndices[0] += indices[0] * m_inputStrides[NumDims-1];\n      inputIndices[1] += indices[1] * m_inputStrides[NumDims-1];\n    }\n    if (inputIndices[1] - inputIndices[0] == PacketSize - 1) {\n      PacketReturnType rslt = m_impl.template packet<Unaligned>(inputIndices[0]);\n      return rslt;\n    }\n    else {\n      EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n      values[0] = m_impl.coeff(inputIndices[0]);\n      values[PacketSize-1] = m_impl.coeff(inputIndices[1]);\n      EIGEN_UNROLL_LOOP\n      for (int i = 1; i < PacketSize-1; ++i) {\n        values[i] = coeff(index+i);\n      }\n      PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n      return rslt;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    double compute_cost = (NumDims - 1) * (TensorOpCost::AddCost<Index>() +\n                                           TensorOpCost::MulCost<Index>() +\n                                           TensorOpCost::DivCost<Index>()) +\n        TensorOpCost::MulCost<Index>();\n    if (vectorized) {\n      compute_cost *= 2;  // packet() computes two indices\n    }\n    const int innerDim = (static_cast<int>(Layout) == static_cast<int>(ColMajor)) ? 0 : (NumDims - 1);\n    return m_impl.costPerCoeff(vectorized && m_inputStrides[innerDim] == 1) +\n        // Computation is not vectorized per se, but it is done once per packet.\n        TensorOpCost(0, 0, compute_cost, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC typename Storage::Type data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n protected:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index srcCoeff(Index index) const\n  {\n    Index inputIndex = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx = index / m_outputStrides[i];\n        inputIndex += idx * m_inputStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      inputIndex += index * m_inputStrides[0];\n    } else {  // RowMajor\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx = index / m_outputStrides[i];\n        inputIndex += idx * m_inputStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      inputIndex += index * m_inputStrides[NumDims-1];\n    }\n    return inputIndex;\n  }\n\n  Dimensions m_dimensions;\n  array<Index, NumDims> m_outputStrides;\n  array<Index, NumDims> m_inputStrides;\n  TensorEvaluator<ArgType, Device> m_impl;\n};\n\n// Eval as lvalue\ntemplate<typename Strides, typename ArgType, typename Device>\nstruct TensorEvaluator<TensorStridingOp<Strides, ArgType>, Device>\n    : public TensorEvaluator<const TensorStridingOp<Strides, ArgType>, Device>\n{\n  typedef TensorStridingOp<Strides, ArgType> XprType;\n  typedef TensorEvaluator<const XprType, Device> Base;\n  //  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  //  typedef DSizes<Index, NumDims> Dimensions;\n\n  enum {\n    IsAligned = /*TensorEvaluator<ArgType, Device>::IsAligned*/false,\n    PacketAccess = TensorEvaluator<ArgType, Device>::PacketAccess,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : Base(op, device) { }\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index index)\n  {\n    return this->m_impl.coeffRef(this->srcCoeff(index));\n  }\n\n  template <int StoreMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void writePacket(Index index, const PacketReturnType& x)\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < this->dimensions().TotalSize());\n\n    Index inputIndices[] = {0, 0};\n    Index indices[] = {index, index + PacketSize - 1};\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx0 = indices[0] / this->m_outputStrides[i];\n        const Index idx1 = indices[1] / this->m_outputStrides[i];\n        inputIndices[0] += idx0 * this->m_inputStrides[i];\n        inputIndices[1] += idx1 * this->m_inputStrides[i];\n        indices[0] -= idx0 * this->m_outputStrides[i];\n        indices[1] -= idx1 * this->m_outputStrides[i];\n      }\n      inputIndices[0] += indices[0] * this->m_inputStrides[0];\n      inputIndices[1] += indices[1] * this->m_inputStrides[0];\n    } else {  // RowMajor\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx0 = indices[0] / this->m_outputStrides[i];\n        const Index idx1 = indices[1] / this->m_outputStrides[i];\n        inputIndices[0] += idx0 * this->m_inputStrides[i];\n        inputIndices[1] += idx1 * this->m_inputStrides[i];\n        indices[0] -= idx0 * this->m_outputStrides[i];\n        indices[1] -= idx1 * this->m_outputStrides[i];\n      }\n      inputIndices[0] += indices[0] * this->m_inputStrides[NumDims-1];\n      inputIndices[1] += indices[1] * this->m_inputStrides[NumDims-1];\n    }\n    if (inputIndices[1] - inputIndices[0] == PacketSize - 1) {\n      this->m_impl.template writePacket<Unaligned>(inputIndices[0], x);\n    }\n    else {\n      EIGEN_ALIGN_MAX Scalar values[PacketSize];\n      internal::pstore<Scalar, PacketReturnType>(values, x);\n      this->m_impl.coeffRef(inputIndices[0]) = values[0];\n      this->m_impl.coeffRef(inputIndices[1]) = values[PacketSize-1];\n      EIGEN_UNROLL_LOOP\n      for (int i = 1; i < PacketSize-1; ++i) {\n        this->coeffRef(index+i) = values[i];\n      }\n    }\n  }\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_STRIDING_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorTrace.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2017 Gagan Goel <gagan.nith@gmail.com>\n// Copyright (C) 2017 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_TRACE_H\n#define EIGEN_CXX11_TENSOR_TENSOR_TRACE_H\n\nnamespace Eigen {\n\n/** \\class TensorTrace\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor Trace class.\n  *\n  *\n  */\n\nnamespace internal {\ntemplate<typename Dims, typename XprType>\nstruct traits<TensorTraceOp<Dims, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions - array_size<Dims>::value;\n  static const int Layout = XprTraits::Layout;\n};\n\ntemplate<typename Dims, typename XprType>\nstruct eval<TensorTraceOp<Dims, XprType>, Eigen::Dense>\n{\n  typedef const TensorTraceOp<Dims, XprType>& type;\n};\n\ntemplate<typename Dims, typename XprType>\nstruct nested<TensorTraceOp<Dims, XprType>, 1, typename eval<TensorTraceOp<Dims, XprType> >::type>\n{\n  typedef TensorTraceOp<Dims, XprType> type;\n};\n\n} // end namespace internal\n\n\ntemplate<typename Dims, typename XprType>\nclass TensorTraceOp : public TensorBase<TensorTraceOp<Dims, XprType> >\n{\n  public:\n    typedef typename Eigen::internal::traits<TensorTraceOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef typename XprType::CoeffReturnType CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorTraceOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorTraceOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorTraceOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorTraceOp(const XprType& expr, const Dims& dims)\n      : m_xpr(expr), m_dims(dims) {\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const Dims& dims() const { return m_dims; }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const typename internal::remove_all<typename XprType::Nested>::type& expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const Dims m_dims;\n};\n\n\n// Eval as rvalue\ntemplate<typename Dims, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorTraceOp<Dims, ArgType>, Device>\n{\n  typedef TensorTraceOp<Dims, ArgType> XprType;\n  static const int NumInputDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  static const int NumReducedDims = internal::array_size<Dims>::value;\n  static const int NumOutputDims = NumInputDims - NumReducedDims;\n  typedef typename XprType::Index Index;\n  typedef DSizes<Index, NumOutputDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = internal::unpacket_traits<PacketReturnType>::size;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess = false,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n    : m_impl(op.expression(), device), m_traceDim(1), m_device(device)\n  {\n\n    EIGEN_STATIC_ASSERT((NumOutputDims >= 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    EIGEN_STATIC_ASSERT((NumReducedDims >= 2) || ((NumReducedDims == 0) && (NumInputDims == 0)), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    for (int i = 0; i < NumInputDims; ++i) {\n      m_reduced[i] = false;\n    }\n\n    const Dims& op_dims = op.dims();\n    for (int i = 0; i < NumReducedDims; ++i) {\n      eigen_assert(op_dims[i] >= 0);\n      eigen_assert(op_dims[i] < NumInputDims);\n      m_reduced[op_dims[i]] = true;\n    }\n\n    // All the dimensions should be distinct to compute the trace\n    int num_distinct_reduce_dims = 0;\n    for (int i = 0; i < NumInputDims; ++i) {\n      if (m_reduced[i]) {\n        ++num_distinct_reduce_dims;\n      }\n    }\n\n    eigen_assert(num_distinct_reduce_dims == NumReducedDims);\n\n    // Compute the dimensions of the result.\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n\n    int output_index = 0;\n    int reduced_index = 0;\n    for (int i = 0; i < NumInputDims; ++i) {\n      if (m_reduced[i]) {\n        m_reducedDims[reduced_index] = input_dims[i];\n        if (reduced_index > 0) {\n          // All the trace dimensions must have the same size\n          eigen_assert(m_reducedDims[0] == m_reducedDims[reduced_index]);\n        }\n        ++reduced_index;\n      }\n      else {\n        m_dimensions[output_index] = input_dims[i];\n        ++output_index;\n      }\n    }\n\n    if (NumReducedDims != 0) {\n      m_traceDim = m_reducedDims[0];\n    }\n\n    // Compute the output strides\n    if (NumOutputDims > 0) {\n      if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n        m_outputStrides[0] = 1;\n        for (int i = 1; i < NumOutputDims; ++i) {\n          m_outputStrides[i] = m_outputStrides[i - 1] * m_dimensions[i - 1];\n        }\n      }\n      else {\n        m_outputStrides.back() = 1;\n        for (int i = NumOutputDims - 2; i >= 0; --i) {\n          m_outputStrides[i] = m_outputStrides[i + 1] * m_dimensions[i + 1];\n        }\n      }\n    }\n\n    // Compute the input strides\n    if (NumInputDims > 0) {\n      array<Index, NumInputDims> input_strides;\n      if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n        input_strides[0] = 1;\n        for (int i = 1; i < NumInputDims; ++i) {\n          input_strides[i] = input_strides[i - 1] * input_dims[i - 1];\n        }\n      }\n      else {\n        input_strides.back() = 1;\n        for (int i = NumInputDims - 2; i >= 0; --i) {\n          input_strides[i] = input_strides[i + 1] * input_dims[i + 1];\n        }\n      }\n\n      output_index = 0;\n      reduced_index = 0;\n      for (int i = 0; i < NumInputDims; ++i) {\n        if(m_reduced[i]) {\n          m_reducedStrides[reduced_index] = input_strides[i];\n          ++reduced_index;\n        }\n        else {\n          m_preservedStrides[output_index] = input_strides[i];\n          ++output_index;\n        }\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const {\n    return m_dimensions;\n  }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType /*data*/) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    // Initialize the result\n    CoeffReturnType result = internal::cast<int, CoeffReturnType>(0);\n    Index index_stride = 0;\n    for (int i = 0; i < NumReducedDims; ++i) {\n      index_stride += m_reducedStrides[i];\n    }\n\n    // If trace is requested along all dimensions, starting index would be 0\n    Index cur_index = 0;\n    if (NumOutputDims != 0)\n      cur_index = firstInput(index);\n    for (Index i = 0; i < m_traceDim; ++i) {\n        result += m_impl.coeff(cur_index);\n        cur_index += index_stride;\n    }\n\n    return result;\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const {\n\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    eigen_assert(index + PacketSize - 1 < dimensions().TotalSize());\n\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n    for (int i = 0; i < PacketSize; ++i) {\n        values[i] = coeff(index + i);\n    }\n    PacketReturnType result = internal::ploadt<PacketReturnType, LoadMode>(values);\n    return result;\n  }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n\n protected:\n  // Given the output index, finds the first index in the input tensor used to compute the trace\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index firstInput(Index index) const {\n    Index startInput = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = NumOutputDims - 1; i > 0; --i) {\n        const Index idx = index / m_outputStrides[i];\n        startInput += idx * m_preservedStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      startInput += index * m_preservedStrides[0];\n    }\n    else {\n      for (int i = 0; i < NumOutputDims - 1; ++i) {\n        const Index idx = index / m_outputStrides[i];\n        startInput += idx * m_preservedStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      startInput += index * m_preservedStrides[NumOutputDims - 1];\n    }\n    return startInput;\n  }\n\n  Dimensions m_dimensions;\n  TensorEvaluator<ArgType, Device> m_impl;\n  // Initialize the size of the trace dimension\n  Index m_traceDim;\n  const Device EIGEN_DEVICE_REF m_device;\n  array<bool, NumInputDims> m_reduced;\n  array<Index, NumReducedDims> m_reducedDims;\n  array<Index, NumOutputDims> m_outputStrides;\n  array<Index, NumReducedDims> m_reducedStrides;\n  array<Index, NumOutputDims> m_preservedStrides;\n};\n\n\n} // End namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_TRACE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorTraits.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_TRAITS_H\n#define EIGEN_CXX11_TENSOR_TENSOR_TRAITS_H\n\nnamespace Eigen {\nnamespace internal {\n\n\ntemplate<typename Scalar, int Options>\nclass compute_tensor_flags\n{\n  enum {\n    is_dynamic_size_storage = 1,\n\n    is_aligned =\n    (\n        ((Options&DontAlign)==0) && (\n#if EIGEN_MAX_STATIC_ALIGN_BYTES>0\n            (!is_dynamic_size_storage)\n#else\n            0\n#endif\n            |\n#if EIGEN_MAX_ALIGN_BYTES>0\n            is_dynamic_size_storage\n#else\n            0\n#endif\n      )\n     ),\n    packet_access_bit = packet_traits<Scalar>::Vectorizable && is_aligned ? PacketAccessBit : 0\n  };\n\n  public:\n    enum { ret = packet_access_bit };\n};\n\n\ntemplate<typename Scalar_, int NumIndices_, int Options_, typename IndexType_>\nstruct traits<Tensor<Scalar_, NumIndices_, Options_, IndexType_> >\n{\n  typedef Scalar_ Scalar;\n  typedef Dense StorageKind;\n  typedef IndexType_ Index;\n  static const int NumDimensions = NumIndices_;\n  static const int Layout = Options_ & RowMajor ? RowMajor : ColMajor;\n  enum {\n    Options = Options_,\n    Flags = compute_tensor_flags<Scalar_, Options_>::ret | (is_const<Scalar_>::value ? 0 : LvalueBit)\n  };\n  template <typename T> struct MakePointer {\n    typedef T* Type;\n  };\n  typedef typename MakePointer<Scalar>::Type PointerType;\n};\n\n\ntemplate<typename Scalar_, typename Dimensions, int Options_, typename IndexType_>\nstruct traits<TensorFixedSize<Scalar_, Dimensions, Options_, IndexType_> >\n{\n  typedef Scalar_ Scalar;\n  typedef Dense StorageKind;\n  typedef IndexType_ Index;\n  static const int NumDimensions = array_size<Dimensions>::value;\n  static const int Layout = Options_ & RowMajor ? RowMajor : ColMajor;\n  enum {\n    Options = Options_,\n    Flags = compute_tensor_flags<Scalar_, Options_>::ret | (is_const<Scalar_>::value ? 0: LvalueBit)\n  };\n  template <typename T> struct MakePointer {\n    typedef T* Type;\n  };\n  typedef typename MakePointer<Scalar>::Type PointerType;\n};\n\n\ntemplate<typename PlainObjectType, int Options_, template <class> class MakePointer_>\nstruct traits<TensorMap<PlainObjectType, Options_, MakePointer_> >\n  : public traits<PlainObjectType>\n{\n  typedef traits<PlainObjectType> BaseTraits;\n  typedef typename BaseTraits::Scalar Scalar;\n  typedef typename BaseTraits::StorageKind StorageKind;\n  typedef typename BaseTraits::Index Index;\n  static const int NumDimensions = BaseTraits::NumDimensions;\n  static const int Layout = BaseTraits::Layout;\n  enum {\n    Options = Options_,\n    Flags = BaseTraits::Flags\n  };\n  template <class T> struct MakePointer {\n    // Intermediate typedef to workaround MSVC issue.\n    typedef MakePointer_<T> MakePointerT;\n    typedef typename MakePointerT::Type Type;\n  };\n  typedef typename MakePointer<Scalar>::Type PointerType;\n};\n\ntemplate<typename PlainObjectType>\nstruct traits<TensorRef<PlainObjectType> >\n  : public traits<PlainObjectType>\n{\n  typedef traits<PlainObjectType> BaseTraits;\n  typedef typename BaseTraits::Scalar Scalar;\n  typedef typename BaseTraits::StorageKind StorageKind;\n  typedef typename BaseTraits::Index Index;\n  static const int NumDimensions = BaseTraits::NumDimensions;\n  static const int Layout = BaseTraits::Layout;\n  enum {\n    Options = BaseTraits::Options,\n    Flags = BaseTraits::Flags\n  };\n  typedef typename BaseTraits::PointerType PointerType;\n};\n\n\ntemplate<typename Scalar_, int NumIndices_, int Options, typename IndexType_>\nstruct eval<Tensor<Scalar_, NumIndices_, Options, IndexType_>, Eigen::Dense>\n{\n  typedef const Tensor<Scalar_, NumIndices_, Options, IndexType_>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename Scalar_, int NumIndices_, int Options, typename IndexType_>\nstruct eval<const Tensor<Scalar_, NumIndices_, Options, IndexType_>, Eigen::Dense>\n{\n  typedef const Tensor<Scalar_, NumIndices_, Options, IndexType_>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename Scalar_, typename Dimensions, int Options, typename IndexType_>\nstruct eval<TensorFixedSize<Scalar_, Dimensions, Options, IndexType_>, Eigen::Dense>\n{\n  typedef const TensorFixedSize<Scalar_, Dimensions, Options, IndexType_>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename Scalar_, typename Dimensions, int Options, typename IndexType_>\nstruct eval<const TensorFixedSize<Scalar_, Dimensions, Options, IndexType_>, Eigen::Dense>\n{\n  typedef const TensorFixedSize<Scalar_, Dimensions, Options, IndexType_>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename PlainObjectType, int Options, template <class> class MakePointer>\nstruct eval<TensorMap<PlainObjectType, Options, MakePointer>, Eigen::Dense>\n{\n  typedef const TensorMap<PlainObjectType, Options, MakePointer>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename PlainObjectType, int Options, template <class> class MakePointer>\nstruct eval<const TensorMap<PlainObjectType, Options, MakePointer>, Eigen::Dense>\n{\n  typedef const TensorMap<PlainObjectType, Options, MakePointer>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename PlainObjectType>\nstruct eval<TensorRef<PlainObjectType>, Eigen::Dense>\n{\n  typedef const TensorRef<PlainObjectType>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename PlainObjectType>\nstruct eval<const TensorRef<PlainObjectType>, Eigen::Dense>\n{\n  typedef const TensorRef<PlainObjectType>EIGEN_DEVICE_REF type;\n};\n\n// TODO nested<> does not exist anymore in Eigen/Core, and it thus has to be removed in favor of ref_selector.\ntemplate<typename T, int n=1, typename PlainObject = void> struct nested\n{\n  typedef typename ref_selector<T>::type type;\n};\n\ntemplate <typename Scalar_, int NumIndices_, int Options_, typename IndexType_>\nstruct nested<Tensor<Scalar_, NumIndices_, Options_, IndexType_> >\n{\n  typedef const Tensor<Scalar_, NumIndices_, Options_, IndexType_>EIGEN_DEVICE_REF type;\n};\n\ntemplate <typename Scalar_, int NumIndices_, int Options_, typename IndexType_>\nstruct nested<const Tensor<Scalar_, NumIndices_, Options_, IndexType_> >\n{\n  typedef const Tensor<Scalar_, NumIndices_, Options_, IndexType_>EIGEN_DEVICE_REF type;\n};\n\ntemplate <typename Scalar_, typename Dimensions, int Options, typename IndexType_>\nstruct nested<TensorFixedSize<Scalar_, Dimensions, Options, IndexType_> >\n{\n  typedef const TensorFixedSize<Scalar_, Dimensions, Options, IndexType_>EIGEN_DEVICE_REF type;\n};\n\ntemplate <typename Scalar_, typename Dimensions, int Options, typename IndexType_>\nstruct nested<const TensorFixedSize<Scalar_, Dimensions, Options, IndexType_> >\n{\n  typedef const TensorFixedSize<Scalar_, Dimensions, Options, IndexType_>EIGEN_DEVICE_REF type;\n};\n\n\ntemplate <typename PlainObjectType>\nstruct nested<TensorRef<PlainObjectType> >\n{\n  typedef const TensorRef<PlainObjectType>EIGEN_DEVICE_REF type;\n};\n\ntemplate <typename PlainObjectType>\nstruct nested<const TensorRef<PlainObjectType> >\n{\n  typedef const TensorRef<PlainObjectType>EIGEN_DEVICE_REF type;\n};\n\n}  // end namespace internal\n\n// Convolutional layers take in an input tensor of shape (D, R, C, B), or (D, C,\n// R, B), and convolve it with a set of filters, which can also be presented as\n// a tensor (D, K, K, M), where M is the number of filters, K is the filter\n// size, and each 3-dimensional tensor of size (D, K, K) is a filter. For\n// simplicity we assume that we always use square filters (which is usually the\n// case in images), hence the two Ks in the tensor dimension.  It also takes in\n// a few additional parameters:\n// Stride (S): The convolution stride is the offset between locations where we\n//             apply the filters.  A larger stride means that the output will be\n//             spatially smaller.\n// Padding (P): The padding we apply to the input tensor along the R and C\n//              dimensions.  This is usually used to make sure that the spatial\n//              dimensions of the output matches our intention.\n//\n// Two types of padding are often used:\n//   SAME: The pad value is computed so that the output will have size\n//         R/S and C/S.\n//   VALID: no padding is carried out.\n// When we do padding, the padded values at the padded locations are usually\n// zero.\n//\n// The output dimensions for convolution, when given all the parameters above,\n// are as follows:\n// When Padding = SAME: the output size is (B, R', C', M), where\n//   R' = ceil(float(R) / float(S))\n//   C' = ceil(float(C) / float(S))\n// where ceil is the ceiling function.  The input tensor is padded with 0 as\n// needed.  The number of padded rows and columns are computed as:\n//   Pr = ((R' - 1) * S + K - R) / 2\n//   Pc = ((C' - 1) * S + K - C) / 2\n// when the stride is 1, we have the simplified case R'=R, C'=C, Pr=Pc=(K-1)/2.\n// This is where SAME comes from - the output has the same size as the input has.\n// When Padding = VALID: the output size is computed as\n//   R' = ceil(float(R - K + 1) / float(S))\n//   C' = ceil(float(C - K + 1) / float(S))\n// and the number of padded rows and columns are computed in the same way as in\n// the SAME case.\n// When the stride is 1, we have the simplified case R'=R-K+1, C'=C-K+1, Pr=0,\n// Pc=0.\ntypedef enum {\n  PADDING_VALID = 1,\n  PADDING_SAME = 2\n} PaddingType;\n\n}  // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_TRAITS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorUInt128.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_UINT128_H\n#define EIGEN_CXX11_TENSOR_TENSOR_UINT128_H\n\nnamespace Eigen {\nnamespace internal {\n\n\ntemplate <uint64_t n>\nstruct static_val {\n  static const uint64_t value = n;\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE operator uint64_t() const { return n; }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE static_val() { }\n\n  template <typename T>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE static_val(const T& v) {\n    EIGEN_UNUSED_VARIABLE(v);\n    eigen_assert(v == n);\n  }\n};\n\n\ntemplate <typename HIGH = uint64_t, typename LOW = uint64_t>\nstruct TensorUInt128\n{\n  HIGH high;\n  LOW low;\n\n  template<typename OTHER_HIGH, typename OTHER_LOW>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  TensorUInt128(const TensorUInt128<OTHER_HIGH, OTHER_LOW>& other) : high(other.high), low(other.low) {\n    EIGEN_STATIC_ASSERT(sizeof(OTHER_HIGH) <= sizeof(HIGH), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    EIGEN_STATIC_ASSERT(sizeof(OTHER_LOW) <= sizeof(LOW), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  }\n\n  template<typename OTHER_HIGH, typename OTHER_LOW>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  TensorUInt128& operator = (const TensorUInt128<OTHER_HIGH, OTHER_LOW>& other) {\n    EIGEN_STATIC_ASSERT(sizeof(OTHER_HIGH) <= sizeof(HIGH), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    EIGEN_STATIC_ASSERT(sizeof(OTHER_LOW) <= sizeof(LOW), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    high = other.high;\n    low = other.low;\n    return *this;\n  }\n\n  template<typename T>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  explicit TensorUInt128(const T& x) : high(0), low(x) {\n    eigen_assert((static_cast<typename conditional<sizeof(T) == 8, uint64_t, uint32_t>::type>(x) <= NumTraits<uint64_t>::highest()));\n    eigen_assert(x >= 0);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  TensorUInt128(HIGH y, LOW x) : high(y), low(x) { }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE operator LOW() const {\n    return low;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE LOW lower() const {\n    return low;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE HIGH upper() const {\n    return high;\n  }\n};\n\n\ntemplate <typename HL, typename LL, typename HR, typename LR>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nbool operator == (const TensorUInt128<HL, LL>& lhs, const TensorUInt128<HR, LR>& rhs)\n{\n  return (lhs.high == rhs.high) & (lhs.low == rhs.low);\n}\n\ntemplate <typename HL, typename LL, typename HR, typename LR>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nbool operator != (const TensorUInt128<HL, LL>& lhs, const TensorUInt128<HR, LR>& rhs)\n{\n  return (lhs.high != rhs.high) | (lhs.low != rhs.low);\n}\n\ntemplate <typename HL, typename LL, typename HR, typename LR>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nbool operator >= (const TensorUInt128<HL, LL>& lhs, const TensorUInt128<HR, LR>& rhs)\n{\n  if (lhs.high != rhs.high) {\n    return lhs.high > rhs.high;\n  }\n  return lhs.low >= rhs.low;\n}\n\ntemplate <typename HL, typename LL, typename HR, typename LR>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nbool operator < (const TensorUInt128<HL, LL>& lhs, const TensorUInt128<HR, LR>& rhs)\n{\n  if (lhs.high != rhs.high) {\n    return lhs.high < rhs.high;\n  }\n  return lhs.low < rhs.low;\n}\n\ntemplate <typename HL, typename LL, typename HR, typename LR>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nTensorUInt128<uint64_t, uint64_t> operator + (const TensorUInt128<HL, LL>& lhs, const TensorUInt128<HR, LR>& rhs)\n{\n  TensorUInt128<uint64_t, uint64_t> result(lhs.high + rhs.high, lhs.low + rhs.low);\n  if (result.low < rhs.low) {\n    result.high += 1;\n  }\n  return result;\n}\n\ntemplate <typename HL, typename LL, typename HR, typename LR>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nTensorUInt128<uint64_t, uint64_t> operator - (const TensorUInt128<HL, LL>& lhs, const TensorUInt128<HR, LR>& rhs)\n{\n  TensorUInt128<uint64_t, uint64_t> result(lhs.high - rhs.high, lhs.low - rhs.low);\n  if (result.low > lhs.low) {\n    result.high -= 1;\n  }\n  return result;\n}\n\n\ntemplate <typename HL, typename LL, typename HR, typename LR>\nstatic EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nTensorUInt128<uint64_t, uint64_t> operator * (const TensorUInt128<HL, LL>& lhs, const TensorUInt128<HR, LR>& rhs)\n{\n  // Split each 128-bit integer into 4 32-bit integers, and then do the\n  // multiplications by hand as follow:\n  //   lhs      a  b  c  d\n  //   rhs      e  f  g  h\n  //           -----------\n  //           ah bh ch dh\n  //           bg cg dg\n  //           cf df\n  //           de\n  // The result is stored in 2 64bit integers, high and low.\n\n  const uint64_t LOW = 0x00000000FFFFFFFFLL;\n  const uint64_t HIGH = 0xFFFFFFFF00000000LL;\n\n  uint64_t d = lhs.low & LOW;\n  uint64_t c = (lhs.low & HIGH) >> 32LL;\n  uint64_t b = lhs.high & LOW;\n  uint64_t a = (lhs.high & HIGH) >> 32LL;\n\n  uint64_t h = rhs.low & LOW;\n  uint64_t g = (rhs.low & HIGH) >> 32LL;\n  uint64_t f = rhs.high & LOW;\n  uint64_t e = (rhs.high & HIGH) >> 32LL;\n\n  // Compute the low 32 bits of low\n  uint64_t acc = d * h;\n  uint64_t low = acc & LOW;\n  //  Compute the high 32 bits of low. Add a carry every time we wrap around\n  acc >>= 32LL;\n  uint64_t carry = 0;\n  uint64_t acc2 = acc + c * h;\n  if (acc2 < acc) {\n    carry++;\n  }\n  acc = acc2 + d * g;\n  if (acc < acc2) {\n    carry++;\n  }\n  low |= (acc << 32LL);\n\n  // Carry forward the high bits of acc to initiate the computation of the\n  // low 32 bits of high\n  acc2 = (acc >> 32LL) | (carry << 32LL);\n  carry = 0;\n\n  acc = acc2 + b * h;\n  if (acc < acc2) {\n    carry++;\n  }\n  acc2 = acc + c * g;\n  if (acc2 < acc) {\n    carry++;\n  }\n  acc = acc2 + d * f;\n  if (acc < acc2) {\n    carry++;\n  }\n  uint64_t high = acc & LOW;\n\n  // Start to compute the high 32 bits of high.\n  acc2 = (acc >> 32LL) | (carry << 32LL);\n\n  acc = acc2 + a * h;\n  acc2 = acc + b * g;\n  acc = acc2 + c * f;\n  acc2 = acc + d * e;\n  high |= (acc2 << 32LL);\n\n  return TensorUInt128<uint64_t, uint64_t>(high, low);\n}\n\ntemplate <typename HL, typename LL, typename HR, typename LR>\nstatic EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nTensorUInt128<uint64_t, uint64_t> operator / (const TensorUInt128<HL, LL>& lhs, const TensorUInt128<HR, LR>& rhs)\n{\n  if (rhs == TensorUInt128<static_val<0>, static_val<1> >(1)) {\n    return TensorUInt128<uint64_t, uint64_t>(lhs.high, lhs.low);\n  } else if (lhs < rhs) {\n    return TensorUInt128<uint64_t, uint64_t>(0);\n  } else {\n    // calculate the biggest power of 2 times rhs that's less than or equal to lhs\n    TensorUInt128<uint64_t, uint64_t> power2(1);\n    TensorUInt128<uint64_t, uint64_t> d(rhs);\n    TensorUInt128<uint64_t, uint64_t> tmp(lhs - d);\n    while (lhs >= d) {\n      tmp = tmp - d;\n      d = d + d;\n      power2 = power2 + power2;\n    }\n\n    tmp = TensorUInt128<uint64_t, uint64_t>(lhs.high, lhs.low);\n    TensorUInt128<uint64_t, uint64_t> result(0);\n    while (power2 != TensorUInt128<static_val<0>, static_val<0> >(0)) {\n      if (tmp >= d) {\n        tmp = tmp - d;\n        result = result + power2;\n      }\n      // Shift right\n      power2 = TensorUInt128<uint64_t, uint64_t>(power2.high >> 1, (power2.low >> 1) | (power2.high << 63));\n      d = TensorUInt128<uint64_t, uint64_t>(d.high >> 1, (d.low >> 1) | (d.high << 63));\n    }\n\n    return result;\n  }\n}\n\n\n}  // namespace internal\n}  // namespace Eigen\n\n\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_UINT128_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorVolumePatch.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_VOLUME_PATCH_H\n#define EIGEN_CXX11_TENSOR_TENSOR_VOLUME_PATCH_H\n\nnamespace Eigen {\n\n/** \\class TensorVolumePatch\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Patch extraction specialized for processing of volumetric data.\n  * This assumes that the input has a least 4 dimensions ordered as follows:\n  *  - channels\n  *  - planes\n  *  - rows\n  *  - columns\n  *  - (optional) additional dimensions such as time or batch size.\n  * Calling the volume patch code with patch_planes, patch_rows, and patch_cols\n  * is equivalent to calling the regular patch extraction code with parameters\n  * d, patch_planes, patch_rows, patch_cols, and 1 for all the additional\n  * dimensions.\n  */\nnamespace internal {\n\ntemplate<DenseIndex Planes, DenseIndex Rows, DenseIndex Cols, typename XprType>\nstruct traits<TensorVolumePatchOp<Planes, Rows, Cols, XprType> > : public traits<XprType>\n{\n  typedef typename internal::remove_const<typename XprType::Scalar>::type Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions + 1;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n\n};\n\ntemplate<DenseIndex Planes, DenseIndex Rows, DenseIndex Cols, typename XprType>\nstruct eval<TensorVolumePatchOp<Planes, Rows, Cols, XprType>, Eigen::Dense>\n{\n  typedef const TensorVolumePatchOp<Planes, Rows, Cols, XprType>& type;\n};\n\ntemplate<DenseIndex Planes, DenseIndex Rows, DenseIndex Cols, typename XprType>\nstruct nested<TensorVolumePatchOp<Planes, Rows, Cols, XprType>, 1, typename eval<TensorVolumePatchOp<Planes, Rows, Cols, XprType> >::type>\n{\n  typedef TensorVolumePatchOp<Planes, Rows, Cols, XprType> type;\n};\n\n}  // end namespace internal\n\ntemplate<DenseIndex Planes, DenseIndex Rows, DenseIndex Cols, typename XprType>\nclass TensorVolumePatchOp : public TensorBase<TensorVolumePatchOp<Planes, Rows, Cols, XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorVolumePatchOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorVolumePatchOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorVolumePatchOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorVolumePatchOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorVolumePatchOp(const XprType& expr, DenseIndex patch_planes, DenseIndex patch_rows, DenseIndex patch_cols,\n                                                            DenseIndex plane_strides, DenseIndex row_strides, DenseIndex col_strides,\n                                                            DenseIndex in_plane_strides, DenseIndex in_row_strides, DenseIndex in_col_strides,\n                                                            DenseIndex plane_inflate_strides, DenseIndex row_inflate_strides, DenseIndex col_inflate_strides,\n                                                            PaddingType padding_type, Scalar padding_value)\n                                                            : m_xpr(expr), m_patch_planes(patch_planes), m_patch_rows(patch_rows), m_patch_cols(patch_cols),\n                                                            m_plane_strides(plane_strides), m_row_strides(row_strides), m_col_strides(col_strides),\n                                                            m_in_plane_strides(in_plane_strides), m_in_row_strides(in_row_strides), m_in_col_strides(in_col_strides),\n                                                            m_plane_inflate_strides(plane_inflate_strides), m_row_inflate_strides(row_inflate_strides), m_col_inflate_strides(col_inflate_strides),\n                                                            m_padding_explicit(false), m_padding_top_z(0), m_padding_bottom_z(0), m_padding_top(0), m_padding_bottom(0), m_padding_left(0), m_padding_right(0),\n                                                            m_padding_type(padding_type), m_padding_value(padding_value) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorVolumePatchOp(const XprType& expr, DenseIndex patch_planes, DenseIndex patch_rows, DenseIndex patch_cols,\n                                                           DenseIndex plane_strides, DenseIndex row_strides, DenseIndex col_strides,\n                                                           DenseIndex in_plane_strides, DenseIndex in_row_strides, DenseIndex in_col_strides,\n                                                           DenseIndex plane_inflate_strides, DenseIndex row_inflate_strides, DenseIndex col_inflate_strides,\n                                                           DenseIndex padding_top_z, DenseIndex padding_bottom_z,\n                                                           DenseIndex padding_top, DenseIndex padding_bottom,\n                                                           DenseIndex padding_left, DenseIndex padding_right,\n                                                           Scalar padding_value)\n                                                           : m_xpr(expr), m_patch_planes(patch_planes), m_patch_rows(patch_rows), m_patch_cols(patch_cols),\n                                                           m_plane_strides(plane_strides), m_row_strides(row_strides), m_col_strides(col_strides),\n                                                           m_in_plane_strides(in_plane_strides), m_in_row_strides(in_row_strides), m_in_col_strides(in_col_strides),\n                                                           m_plane_inflate_strides(plane_inflate_strides), m_row_inflate_strides(row_inflate_strides), m_col_inflate_strides(col_inflate_strides),\n                                                           m_padding_explicit(true), m_padding_top_z(padding_top_z), m_padding_bottom_z(padding_bottom_z), m_padding_top(padding_top), m_padding_bottom(padding_bottom),\n                                                           m_padding_left(padding_left), m_padding_right(padding_right),\n                                                           m_padding_type(PADDING_VALID), m_padding_value(padding_value) {}\n\n    EIGEN_DEVICE_FUNC\n    DenseIndex patch_planes() const { return m_patch_planes; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex patch_rows() const { return m_patch_rows; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex patch_cols() const { return m_patch_cols; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex plane_strides() const { return m_plane_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex row_strides() const { return m_row_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex col_strides() const { return m_col_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex in_plane_strides() const { return m_in_plane_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex in_row_strides() const { return m_in_row_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex in_col_strides() const { return m_in_col_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex plane_inflate_strides() const { return m_plane_inflate_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex row_inflate_strides() const { return m_row_inflate_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex col_inflate_strides() const { return m_col_inflate_strides; }\n    EIGEN_DEVICE_FUNC\n    bool padding_explicit() const { return m_padding_explicit; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex padding_top_z() const { return m_padding_top_z; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex padding_bottom_z() const { return m_padding_bottom_z; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex padding_top() const { return m_padding_top; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex padding_bottom() const { return m_padding_bottom; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex padding_left() const { return m_padding_left; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex padding_right() const { return m_padding_right; }\n    EIGEN_DEVICE_FUNC\n    PaddingType padding_type() const { return m_padding_type; }\n    EIGEN_DEVICE_FUNC\n    Scalar padding_value() const { return m_padding_value; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const DenseIndex m_patch_planes;\n    const DenseIndex m_patch_rows;\n    const DenseIndex m_patch_cols;\n    const DenseIndex m_plane_strides;\n    const DenseIndex m_row_strides;\n    const DenseIndex m_col_strides;\n    const DenseIndex m_in_plane_strides;\n    const DenseIndex m_in_row_strides;\n    const DenseIndex m_in_col_strides;\n    const DenseIndex m_plane_inflate_strides;\n    const DenseIndex m_row_inflate_strides;\n    const DenseIndex m_col_inflate_strides;\n    const bool m_padding_explicit;\n    const DenseIndex m_padding_top_z;\n    const DenseIndex m_padding_bottom_z;\n    const DenseIndex m_padding_top;\n    const DenseIndex m_padding_bottom;\n    const DenseIndex m_padding_left;\n    const DenseIndex m_padding_right;\n    const PaddingType m_padding_type;\n    const Scalar m_padding_value;\n};\n\n\n// Eval as rvalue\ntemplate<DenseIndex Planes, DenseIndex Rows, DenseIndex Cols, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorVolumePatchOp<Planes, Rows, Cols, ArgType>, Device>\n{\n  typedef TensorVolumePatchOp<Planes, Rows, Cols, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumInputDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  static const int NumDims = NumInputDims + 1;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename internal::remove_const<typename XprType::Scalar>::type Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess = false,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) :\n m_impl(op.expression(), device)\n  {\n    EIGEN_STATIC_ASSERT((NumDims >= 5), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    m_paddingValue = op.padding_value();\n\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n\n    // Cache a few variables.\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_inputDepth = input_dims[0];\n      m_inputPlanes = input_dims[1];\n      m_inputRows = input_dims[2];\n      m_inputCols = input_dims[3];\n    } else {\n      m_inputDepth = input_dims[NumInputDims-1];\n      m_inputPlanes = input_dims[NumInputDims-2];\n      m_inputRows = input_dims[NumInputDims-3];\n      m_inputCols = input_dims[NumInputDims-4];\n    }\n\n    m_plane_strides = op.plane_strides();\n    m_row_strides = op.row_strides();\n    m_col_strides = op.col_strides();\n\n    // Input strides and effective input/patch size\n    m_in_plane_strides = op.in_plane_strides();\n    m_in_row_strides = op.in_row_strides();\n    m_in_col_strides = op.in_col_strides();\n    m_plane_inflate_strides = op.plane_inflate_strides();\n    m_row_inflate_strides = op.row_inflate_strides();\n    m_col_inflate_strides = op.col_inflate_strides();\n\n    // The \"effective\" spatial size after inflating data with zeros.\n    m_input_planes_eff = (m_inputPlanes - 1) * m_plane_inflate_strides + 1;\n    m_input_rows_eff = (m_inputRows - 1) * m_row_inflate_strides + 1;\n    m_input_cols_eff = (m_inputCols - 1) * m_col_inflate_strides + 1;\n    m_patch_planes_eff = op.patch_planes() + (op.patch_planes() - 1) * (m_in_plane_strides - 1);\n    m_patch_rows_eff = op.patch_rows() + (op.patch_rows() - 1) * (m_in_row_strides - 1);\n    m_patch_cols_eff = op.patch_cols() + (op.patch_cols() - 1) * (m_in_col_strides - 1);\n\n    if (op.padding_explicit()) {\n      m_outputPlanes = numext::ceil((m_input_planes_eff + op.padding_top_z() + op.padding_bottom_z() - m_patch_planes_eff + 1.f) / static_cast<float>(m_plane_strides));\n      m_outputRows = numext::ceil((m_input_rows_eff + op.padding_top() + op.padding_bottom() - m_patch_rows_eff + 1.f) / static_cast<float>(m_row_strides));\n      m_outputCols = numext::ceil((m_input_cols_eff + op.padding_left() + op.padding_right() - m_patch_cols_eff + 1.f) / static_cast<float>(m_col_strides));\n      m_planePaddingTop = op.padding_top_z();\n      m_rowPaddingTop = op.padding_top();\n      m_colPaddingLeft = op.padding_left();\n    } else {\n      // Computing padding from the type\n      switch (op.padding_type()) {\n        case PADDING_VALID:\n          m_outputPlanes = numext::ceil((m_input_planes_eff - m_patch_planes_eff + 1.f) / static_cast<float>(m_plane_strides));\n          m_outputRows = numext::ceil((m_input_rows_eff - m_patch_rows_eff + 1.f) / static_cast<float>(m_row_strides));\n          m_outputCols = numext::ceil((m_input_cols_eff - m_patch_cols_eff + 1.f) / static_cast<float>(m_col_strides));\n          m_planePaddingTop = 0;\n          m_rowPaddingTop = 0;\n          m_colPaddingLeft = 0;\n          break;\n        case PADDING_SAME: {\n          m_outputPlanes = numext::ceil(m_input_planes_eff / static_cast<float>(m_plane_strides));\n          m_outputRows = numext::ceil(m_input_rows_eff / static_cast<float>(m_row_strides));\n          m_outputCols = numext::ceil(m_input_cols_eff / static_cast<float>(m_col_strides));\n          const Index dz = (m_outputPlanes - 1) * m_plane_strides + m_patch_planes_eff - m_input_planes_eff;\n          const Index dy = (m_outputRows - 1) * m_row_strides + m_patch_rows_eff - m_input_rows_eff;\n          const Index dx = (m_outputCols - 1) * m_col_strides + m_patch_cols_eff - m_input_cols_eff;\n          m_planePaddingTop = dz / 2;\n          m_rowPaddingTop = dy / 2;\n          m_colPaddingLeft = dx / 2;\n          break;\n        }\n        default:\n          eigen_assert(false && \"unexpected padding\");\n      }\n    }\n    eigen_assert(m_outputRows > 0);\n    eigen_assert(m_outputCols > 0);\n    eigen_assert(m_outputPlanes > 0);\n\n    // Dimensions for result of extraction.\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      // ColMajor\n      // 0: depth\n      // 1: patch_planes\n      // 2: patch_rows\n      // 3: patch_cols\n      // 4: number of patches\n      // 5 and beyond: anything else (such as batch).\n      m_dimensions[0] = input_dims[0];\n      m_dimensions[1] = op.patch_planes();\n      m_dimensions[2] = op.patch_rows();\n      m_dimensions[3] = op.patch_cols();\n      m_dimensions[4] = m_outputPlanes * m_outputRows * m_outputCols;\n      for (int i = 5; i < NumDims; ++i) {\n        m_dimensions[i] = input_dims[i-1];\n      }\n    } else {\n      // RowMajor\n      // NumDims-1: depth\n      // NumDims-2: patch_planes\n      // NumDims-3: patch_rows\n      // NumDims-4: patch_cols\n      // NumDims-5: number of patches\n      // NumDims-6 and beyond: anything else (such as batch).\n      m_dimensions[NumDims-1] = input_dims[NumInputDims-1];\n      m_dimensions[NumDims-2] = op.patch_planes();\n      m_dimensions[NumDims-3] = op.patch_rows();\n      m_dimensions[NumDims-4] = op.patch_cols();\n      m_dimensions[NumDims-5] = m_outputPlanes * m_outputRows * m_outputCols;\n      for (int i = NumDims-6; i >= 0; --i) {\n        m_dimensions[i] = input_dims[i];\n      }\n    }\n\n    // Strides for the output tensor.\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_rowStride = m_dimensions[1];\n      m_colStride = m_dimensions[2] * m_rowStride;\n      m_patchStride = m_colStride * m_dimensions[3] * m_dimensions[0];\n      m_otherStride = m_patchStride * m_dimensions[4];\n    } else {\n      m_rowStride = m_dimensions[NumDims-2];\n      m_colStride = m_dimensions[NumDims-3] * m_rowStride;\n      m_patchStride = m_colStride * m_dimensions[NumDims-4] * m_dimensions[NumDims-1];\n      m_otherStride = m_patchStride * m_dimensions[NumDims-5];\n    }\n\n    // Strides for navigating through the input tensor.\n    m_planeInputStride = m_inputDepth;\n    m_rowInputStride = m_inputDepth * m_inputPlanes;\n    m_colInputStride = m_inputDepth * m_inputRows * m_inputPlanes;\n    m_otherInputStride = m_inputDepth * m_inputRows * m_inputCols * m_inputPlanes;\n\n    m_outputPlanesRows = m_outputPlanes * m_outputRows;\n\n    // Fast representations of different variables.\n    m_fastOtherStride = internal::TensorIntDivisor<Index>(m_otherStride);\n\n    m_fastPatchStride = internal::TensorIntDivisor<Index>(m_patchStride);\n    m_fastColStride = internal::TensorIntDivisor<Index>(m_colStride);\n    m_fastRowStride = internal::TensorIntDivisor<Index>(m_rowStride);\n    m_fastInputRowStride = internal::TensorIntDivisor<Index>(m_row_inflate_strides);\n    m_fastInputColStride = internal::TensorIntDivisor<Index>(m_col_inflate_strides);\n    m_fastInputPlaneStride = internal::TensorIntDivisor<Index>(m_plane_inflate_strides);\n    m_fastInputColsEff = internal::TensorIntDivisor<Index>(m_input_cols_eff);\n    m_fastOutputPlanes = internal::TensorIntDivisor<Index>(m_outputPlanes);\n    m_fastOutputPlanesRows = internal::TensorIntDivisor<Index>(m_outputPlanesRows);\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_fastOutputDepth = internal::TensorIntDivisor<Index>(m_dimensions[0]);\n    } else {\n      m_fastOutputDepth = internal::TensorIntDivisor<Index>(m_dimensions[NumDims-1]);\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType /*data*/) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    // Patch index corresponding to the passed in index.\n    const Index patchIndex = index / m_fastPatchStride;\n\n    // Spatial offset within the patch. This has to be translated into 3D\n    // coordinates within the patch.\n    const Index patchOffset = (index - patchIndex * m_patchStride) / m_fastOutputDepth;\n\n    // Batch, etc.\n    const Index otherIndex = (NumDims == 5) ? 0 : index / m_fastOtherStride;\n    const Index patch3DIndex = (NumDims == 5) ? patchIndex : (index - otherIndex * m_otherStride) / m_fastPatchStride;\n\n    // Calculate column index in the input original tensor.\n    const Index colIndex = patch3DIndex / m_fastOutputPlanesRows;\n    const Index colOffset = patchOffset / m_fastColStride;\n    const Index inputCol = colIndex * m_col_strides + colOffset * m_in_col_strides - m_colPaddingLeft;\n    const Index origInputCol = (m_col_inflate_strides == 1) ? inputCol : ((inputCol >= 0) ? (inputCol / m_fastInputColStride) : 0);\n    if (inputCol < 0 || inputCol >= m_input_cols_eff ||\n        ((m_col_inflate_strides != 1) && (inputCol != origInputCol * m_col_inflate_strides))) {\n      return Scalar(m_paddingValue);\n    }\n\n    // Calculate row index in the original input tensor.\n    const Index rowIndex = (patch3DIndex - colIndex * m_outputPlanesRows) / m_fastOutputPlanes;\n    const Index rowOffset = (patchOffset - colOffset * m_colStride) / m_fastRowStride;\n    const Index inputRow = rowIndex * m_row_strides + rowOffset * m_in_row_strides - m_rowPaddingTop;\n    const Index origInputRow = (m_row_inflate_strides == 1) ? inputRow : ((inputRow >= 0) ? (inputRow / m_fastInputRowStride) : 0);\n    if (inputRow < 0 || inputRow >= m_input_rows_eff ||\n        ((m_row_inflate_strides != 1) && (inputRow != origInputRow * m_row_inflate_strides))) {\n      return Scalar(m_paddingValue);\n    }\n\n    // Calculate plane index in the original input tensor.\n    const Index planeIndex = (patch3DIndex - m_outputPlanes * (colIndex * m_outputRows + rowIndex));\n    const Index planeOffset = patchOffset - colOffset * m_colStride - rowOffset * m_rowStride;\n    const Index inputPlane = planeIndex * m_plane_strides + planeOffset * m_in_plane_strides - m_planePaddingTop;\n    const Index origInputPlane = (m_plane_inflate_strides == 1) ? inputPlane : ((inputPlane >= 0) ? (inputPlane / m_fastInputPlaneStride) : 0);\n    if (inputPlane < 0 || inputPlane >= m_input_planes_eff ||\n        ((m_plane_inflate_strides != 1) && (inputPlane != origInputPlane * m_plane_inflate_strides))) {\n      return Scalar(m_paddingValue);\n    }\n\n    const int depth_index = static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 0 : NumDims - 1;\n    const Index depth = index - (index / m_fastOutputDepth) * m_dimensions[depth_index];\n\n    const Index inputIndex = depth +\n        origInputRow * m_rowInputStride +\n        origInputCol * m_colInputStride +\n        origInputPlane * m_planeInputStride +\n        otherIndex * m_otherInputStride;\n\n    return m_impl.coeff(inputIndex);\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    if (m_in_row_strides != 1 || m_in_col_strides != 1 || m_row_inflate_strides != 1 || m_col_inflate_strides != 1 ||\n        m_in_plane_strides != 1 || m_plane_inflate_strides != 1) {\n      return packetWithPossibleZero(index);\n    }\n\n    const Index indices[2] = {index, index + PacketSize - 1};\n    const Index patchIndex = indices[0] / m_fastPatchStride;\n    if (patchIndex != indices[1] / m_fastPatchStride) {\n      return packetWithPossibleZero(index);\n    }\n    const Index otherIndex = (NumDims == 5) ? 0 : indices[0] / m_fastOtherStride;\n    eigen_assert(otherIndex == indices[1] / m_fastOtherStride);\n\n    // Find the offset of the element wrt the location of the first element.\n    const Index patchOffsets[2] = {(indices[0] - patchIndex * m_patchStride) / m_fastOutputDepth,\n                                   (indices[1] - patchIndex * m_patchStride) / m_fastOutputDepth};\n\n    const Index patch3DIndex = (NumDims == 5) ? patchIndex : (indices[0] - otherIndex * m_otherStride) / m_fastPatchStride;\n    eigen_assert(patch3DIndex == (indices[1] - otherIndex * m_otherStride) / m_fastPatchStride);\n\n    const Index colIndex = patch3DIndex / m_fastOutputPlanesRows;\n    const Index colOffsets[2] = {\n      patchOffsets[0] / m_fastColStride,\n      patchOffsets[1] / m_fastColStride};\n\n    // Calculate col indices in the original input tensor.\n    const Index inputCols[2] = {\n      colIndex * m_col_strides + colOffsets[0] - m_colPaddingLeft,\n      colIndex * m_col_strides + colOffsets[1] - m_colPaddingLeft};\n    if (inputCols[1] < 0 || inputCols[0] >= m_inputCols) {\n      return internal::pset1<PacketReturnType>(Scalar(m_paddingValue));\n    }\n\n    if (inputCols[0] != inputCols[1]) {\n      return packetWithPossibleZero(index);\n    }\n\n    const Index rowIndex = (patch3DIndex - colIndex * m_outputPlanesRows) / m_fastOutputPlanes;\n    const Index rowOffsets[2] = {\n      (patchOffsets[0] - colOffsets[0] * m_colStride) / m_fastRowStride,\n      (patchOffsets[1] - colOffsets[1] * m_colStride) / m_fastRowStride};\n    eigen_assert(rowOffsets[0] <= rowOffsets[1]);\n    // Calculate col indices in the original input tensor.\n    const Index inputRows[2] = {\n      rowIndex * m_row_strides + rowOffsets[0] - m_rowPaddingTop,\n      rowIndex * m_row_strides + rowOffsets[1] - m_rowPaddingTop};\n\n    if (inputRows[1] < 0 || inputRows[0] >= m_inputRows) {\n      return internal::pset1<PacketReturnType>(Scalar(m_paddingValue));\n    }\n\n    if (inputRows[0] != inputRows[1]) {\n      return packetWithPossibleZero(index);\n    }\n\n    const Index planeIndex = (patch3DIndex - m_outputPlanes * (colIndex * m_outputRows + rowIndex));\n    const Index planeOffsets[2] = {\n      patchOffsets[0] - colOffsets[0] * m_colStride - rowOffsets[0] * m_rowStride,\n      patchOffsets[1] - colOffsets[1] * m_colStride - rowOffsets[1] * m_rowStride};\n    eigen_assert(planeOffsets[0] <= planeOffsets[1]);\n    const Index inputPlanes[2] = {\n      planeIndex * m_plane_strides + planeOffsets[0] - m_planePaddingTop,\n      planeIndex * m_plane_strides + planeOffsets[1] - m_planePaddingTop};\n\n    if (inputPlanes[1] < 0 || inputPlanes[0] >= m_inputPlanes) {\n      return internal::pset1<PacketReturnType>(Scalar(m_paddingValue));\n    }\n\n    if (inputPlanes[0] >= 0 && inputPlanes[1] < m_inputPlanes) {\n      // no padding\n      const int depth_index = static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 0 : NumDims - 1;\n      const Index depth = index - (index / m_fastOutputDepth) * m_dimensions[depth_index];\n      const Index inputIndex = depth +\n          inputRows[0] * m_rowInputStride +\n          inputCols[0] * m_colInputStride +\n          m_planeInputStride * inputPlanes[0] +\n          otherIndex * m_otherInputStride;\n      return m_impl.template packet<Unaligned>(inputIndex);\n    }\n\n    return packetWithPossibleZero(index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    const double compute_cost =\n        10 * TensorOpCost::DivCost<Index>() + 21 * TensorOpCost::MulCost<Index>() +\n        8 * TensorOpCost::AddCost<Index>();\n    return TensorOpCost(0, 0, compute_cost, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n  const TensorEvaluator<ArgType, Device>& impl() const { return m_impl; }\n\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index planePaddingTop() const { return m_planePaddingTop; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rowPaddingTop() const { return m_rowPaddingTop; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index colPaddingLeft() const { return m_colPaddingLeft; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index outputPlanes() const { return m_outputPlanes; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index outputRows() const { return m_outputRows; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index outputCols() const { return m_outputCols; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index userPlaneStride() const { return m_plane_strides; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index userRowStride() const { return m_row_strides; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index userColStride() const { return m_col_strides; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index userInPlaneStride() const { return m_in_plane_strides; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index userInRowStride() const { return m_in_row_strides; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index userInColStride() const { return m_in_col_strides; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index planeInflateStride() const { return m_plane_inflate_strides; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rowInflateStride() const { return m_row_inflate_strides; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index colInflateStride() const { return m_col_inflate_strides; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n protected:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetWithPossibleZero(Index index) const\n  {\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < PacketSize; ++i) {\n      values[i] = coeff(index+i);\n    }\n    PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n    return rslt;\n  }\n\n  Dimensions m_dimensions;\n\n  // Parameters passed to the constructor.\n  Index m_plane_strides;\n  Index m_row_strides;\n  Index m_col_strides;\n\n  Index m_outputPlanes;\n  Index m_outputRows;\n  Index m_outputCols;\n\n  Index m_planePaddingTop;\n  Index m_rowPaddingTop;\n  Index m_colPaddingLeft;\n\n  Index m_in_plane_strides;\n  Index m_in_row_strides;\n  Index m_in_col_strides;\n\n  Index m_plane_inflate_strides;\n  Index m_row_inflate_strides;\n  Index m_col_inflate_strides;\n\n  // Cached input size.\n  Index m_inputDepth;\n  Index m_inputPlanes;\n  Index m_inputRows;\n  Index m_inputCols;\n\n  // Other cached variables.\n  Index m_outputPlanesRows;\n\n  // Effective input/patch post-inflation size.\n  Index m_input_planes_eff;\n  Index m_input_rows_eff;\n  Index m_input_cols_eff;\n  Index m_patch_planes_eff;\n  Index m_patch_rows_eff;\n  Index m_patch_cols_eff;\n\n  // Strides for the output tensor.\n  Index m_otherStride;\n  Index m_patchStride;\n  Index m_rowStride;\n  Index m_colStride;\n\n  // Strides for the input tensor.\n  Index m_planeInputStride;\n  Index m_rowInputStride;\n  Index m_colInputStride;\n  Index m_otherInputStride;\n\n  internal::TensorIntDivisor<Index> m_fastOtherStride;\n  internal::TensorIntDivisor<Index> m_fastPatchStride;\n  internal::TensorIntDivisor<Index> m_fastColStride;\n  internal::TensorIntDivisor<Index> m_fastRowStride;\n  internal::TensorIntDivisor<Index> m_fastInputPlaneStride;\n  internal::TensorIntDivisor<Index> m_fastInputRowStride;\n  internal::TensorIntDivisor<Index> m_fastInputColStride;\n  internal::TensorIntDivisor<Index> m_fastInputColsEff;\n  internal::TensorIntDivisor<Index> m_fastOutputPlanesRows;\n  internal::TensorIntDivisor<Index> m_fastOutputPlanes;\n  internal::TensorIntDivisor<Index> m_fastOutputDepth;\n\n  Scalar m_paddingValue;\n\n  TensorEvaluator<ArgType, Device> m_impl;\n\n\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_VOLUME_PATCH_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/TensorSymmetry/DynamicSymmetry.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSORSYMMETRY_DYNAMICSYMMETRY_H\n#define EIGEN_CXX11_TENSORSYMMETRY_DYNAMICSYMMETRY_H\n\nnamespace Eigen {\n\nclass DynamicSGroup\n{\n  public:\n    inline explicit DynamicSGroup() : m_numIndices(1), m_elements(), m_generators(), m_globalFlags(0) { m_elements.push_back(ge(Generator(0, 0, 0))); }\n    inline DynamicSGroup(const DynamicSGroup& o) : m_numIndices(o.m_numIndices), m_elements(o.m_elements), m_generators(o.m_generators), m_globalFlags(o.m_globalFlags) { }\n    inline DynamicSGroup(DynamicSGroup&& o) : m_numIndices(o.m_numIndices), m_elements(), m_generators(o.m_generators), m_globalFlags(o.m_globalFlags) { std::swap(m_elements, o.m_elements); }\n    inline DynamicSGroup& operator=(const DynamicSGroup& o) { m_numIndices = o.m_numIndices; m_elements = o.m_elements; m_generators = o.m_generators; m_globalFlags = o.m_globalFlags; return *this; }\n    inline DynamicSGroup& operator=(DynamicSGroup&& o) { m_numIndices = o.m_numIndices; std::swap(m_elements, o.m_elements); m_generators = o.m_generators; m_globalFlags = o.m_globalFlags; return *this; }\n\n    void add(int one, int two, int flags = 0);\n\n    template<typename Gen_>\n    inline void add(Gen_) { add(Gen_::One, Gen_::Two, Gen_::Flags); }\n    inline void addSymmetry(int one, int two) { add(one, two, 0); }\n    inline void addAntiSymmetry(int one, int two) { add(one, two, NegationFlag); }\n    inline void addHermiticity(int one, int two) { add(one, two, ConjugationFlag); }\n    inline void addAntiHermiticity(int one, int two) { add(one, two, NegationFlag | ConjugationFlag); }\n\n    template<typename Op, typename RV, typename Index, std::size_t N, typename... Args>\n    inline RV apply(const std::array<Index, N>& idx, RV initial, Args&&... args) const\n    {\n      eigen_assert(N >= m_numIndices && \"Can only apply symmetry group to objects that have at least the required amount of indices.\");\n      for (std::size_t i = 0; i < size(); i++)\n        initial = Op::run(h_permute(i, idx, typename internal::gen_numeric_list<int, N>::type()), m_elements[i].flags, initial, std::forward<Args>(args)...);\n      return initial;\n    }\n\n    template<typename Op, typename RV, typename Index, typename... Args>\n    inline RV apply(const std::vector<Index>& idx, RV initial, Args&&... args) const\n    {\n      eigen_assert(idx.size() >= m_numIndices && \"Can only apply symmetry group to objects that have at least the required amount of indices.\");\n      for (std::size_t i = 0; i < size(); i++)\n        initial = Op::run(h_permute(i, idx), m_elements[i].flags, initial, std::forward<Args>(args)...);\n      return initial;\n    }\n\n    inline int globalFlags() const { return m_globalFlags; }\n    inline std::size_t size() const { return m_elements.size(); }\n\n    template<typename Tensor_, typename... IndexTypes>\n    inline internal::tensor_symmetry_value_setter<Tensor_, DynamicSGroup> operator()(Tensor_& tensor, typename Tensor_::Index firstIndex, IndexTypes... otherIndices) const\n    {\n      static_assert(sizeof...(otherIndices) + 1 == Tensor_::NumIndices, \"Number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\");\n      return operator()(tensor, std::array<typename Tensor_::Index, Tensor_::NumIndices>{{firstIndex, otherIndices...}});\n    }\n\n    template<typename Tensor_>\n    inline internal::tensor_symmetry_value_setter<Tensor_, DynamicSGroup> operator()(Tensor_& tensor, std::array<typename Tensor_::Index, Tensor_::NumIndices> const& indices) const\n    {\n      return internal::tensor_symmetry_value_setter<Tensor_, DynamicSGroup>(tensor, *this, indices);\n    }\n  private:\n    struct GroupElement {\n      std::vector<int> representation;\n      int flags;\n      bool isId() const\n      {\n        for (std::size_t i = 0; i < representation.size(); i++)\n          if (i != (size_t)representation[i])\n            return false;\n        return true;\n      }\n    };\n    struct Generator {\n      int one;\n      int two;\n      int flags;\n      constexpr inline Generator(int one_, int two_, int flags_) : one(one_), two(two_), flags(flags_) {}\n    };\n\n    std::size_t m_numIndices;\n    std::vector<GroupElement> m_elements;\n    std::vector<Generator> m_generators;\n    int m_globalFlags;\n\n    template<typename Index, std::size_t N, int... n>\n    inline std::array<Index, N> h_permute(std::size_t which, const std::array<Index, N>& idx, internal::numeric_list<int, n...>) const\n    {\n      return std::array<Index, N>{{ idx[n >= m_numIndices ? n : m_elements[which].representation[n]]... }};\n    }\n\n    template<typename Index>\n    inline std::vector<Index> h_permute(std::size_t which, std::vector<Index> idx) const\n    {\n      std::vector<Index> result;\n      result.reserve(idx.size());\n      for (auto k : m_elements[which].representation)\n        result.push_back(idx[k]);\n      for (std::size_t i = m_numIndices; i < idx.size(); i++)\n        result.push_back(idx[i]);\n      return result;\n    }\n\n    inline GroupElement ge(Generator const& g) const\n    {\n      GroupElement result;\n      result.representation.reserve(m_numIndices);\n      result.flags = g.flags;\n      for (std::size_t k = 0; k < m_numIndices; k++) {\n        if (k == (std::size_t)g.one)\n          result.representation.push_back(g.two);\n        else if (k == (std::size_t)g.two)\n          result.representation.push_back(g.one);\n        else\n          result.representation.push_back(int(k));\n      }\n      return result;\n    }\n\n    GroupElement mul(GroupElement, GroupElement) const;\n    inline GroupElement mul(Generator g1, GroupElement g2) const\n    {\n      return mul(ge(g1), g2);\n    }\n\n    inline GroupElement mul(GroupElement g1, Generator g2) const\n    {\n      return mul(g1, ge(g2));\n    }\n\n    inline GroupElement mul(Generator g1, Generator g2) const\n    {\n      return mul(ge(g1), ge(g2));\n    }\n\n    inline int findElement(GroupElement e) const\n    {\n      for (auto ee : m_elements) {\n        if (ee.representation == e.representation)\n          return ee.flags ^ e.flags;\n      }\n      return -1;\n    }\n\n    void updateGlobalFlags(int flagDiffOfSameGenerator);\n};\n\n// dynamic symmetry group that auto-adds the template parameters in the constructor\ntemplate<typename... Gen>\nclass DynamicSGroupFromTemplateArgs : public DynamicSGroup\n{\n  public:\n    inline DynamicSGroupFromTemplateArgs() : DynamicSGroup()\n    {\n      add_all(internal::type_list<Gen...>());\n    }\n    inline DynamicSGroupFromTemplateArgs(DynamicSGroupFromTemplateArgs const& other) : DynamicSGroup(other) { }\n    inline DynamicSGroupFromTemplateArgs(DynamicSGroupFromTemplateArgs&& other) : DynamicSGroup(other) { }\n    inline DynamicSGroupFromTemplateArgs<Gen...>& operator=(const DynamicSGroupFromTemplateArgs<Gen...>& o) { DynamicSGroup::operator=(o); return *this; }\n    inline DynamicSGroupFromTemplateArgs<Gen...>& operator=(DynamicSGroupFromTemplateArgs<Gen...>&& o) { DynamicSGroup::operator=(o); return *this; }\n  \n  private:\n    template<typename Gen1, typename... GenNext>\n    inline void add_all(internal::type_list<Gen1, GenNext...>)\n    {\n      add(Gen1());\n      add_all(internal::type_list<GenNext...>());\n    }\n\n    inline void add_all(internal::type_list<>)\n    {\n    }\n};\n\ninline DynamicSGroup::GroupElement DynamicSGroup::mul(GroupElement g1, GroupElement g2) const\n{\n  eigen_internal_assert(g1.representation.size() == m_numIndices);\n  eigen_internal_assert(g2.representation.size() == m_numIndices);\n\n  GroupElement result;\n  result.representation.reserve(m_numIndices);\n  for (std::size_t i = 0; i < m_numIndices; i++) {\n    int v = g2.representation[g1.representation[i]];\n    eigen_assert(v >= 0);\n    result.representation.push_back(v);\n  }\n  result.flags = g1.flags ^ g2.flags;\n  return result;\n}\n\ninline void DynamicSGroup::add(int one, int two, int flags)\n{\n  eigen_assert(one >= 0);\n  eigen_assert(two >= 0);\n  eigen_assert(one != two);\n\n  if ((std::size_t)one >= m_numIndices || (std::size_t)two >= m_numIndices) {\n    std::size_t newNumIndices = (one > two) ? one : two + 1;\n    for (auto& gelem : m_elements) {\n      gelem.representation.reserve(newNumIndices);\n      for (std::size_t i = m_numIndices; i < newNumIndices; i++)\n        gelem.representation.push_back(i);\n    }\n    m_numIndices = newNumIndices;\n  }\n\n  Generator g{one, two, flags};\n  GroupElement e = ge(g);\n\n  /* special case for first generator */\n  if (m_elements.size() == 1) {\n    while (!e.isId()) {\n      m_elements.push_back(e);\n      e = mul(e, g);\n    }\n\n    if (e.flags > 0)\n      updateGlobalFlags(e.flags);\n\n    // only add in case we didn't have identity\n    if (m_elements.size() > 1)\n      m_generators.push_back(g);\n    return;\n  }\n\n  int p = findElement(e);\n  if (p >= 0) {\n    updateGlobalFlags(p);\n    return;\n  }\n\n  std::size_t coset_order = m_elements.size();\n  m_elements.push_back(e);\n  for (std::size_t i = 1; i < coset_order; i++)\n    m_elements.push_back(mul(m_elements[i], e));\n  m_generators.push_back(g);\n\n  std::size_t coset_rep = coset_order;\n  do {\n    for (auto g : m_generators) {\n      e = mul(m_elements[coset_rep], g);\n      p = findElement(e);\n      if (p < 0) {\n        // element not yet in group\n        m_elements.push_back(e);\n        for (std::size_t i = 1; i < coset_order; i++)\n          m_elements.push_back(mul(m_elements[i], e));\n      } else if (p > 0) {\n        updateGlobalFlags(p);\n      }\n    }\n    coset_rep += coset_order;\n  } while (coset_rep < m_elements.size());\n}\n\ninline void DynamicSGroup::updateGlobalFlags(int flagDiffOfSameGenerator)\n{\n    switch (flagDiffOfSameGenerator) {\n      case 0:\n      default:\n        // nothing happened\n        break;\n      case NegationFlag:\n        // every element is it's own negative => whole tensor is zero\n        m_globalFlags |= GlobalZeroFlag;\n        break;\n      case ConjugationFlag:\n        // every element is it's own conjugate => whole tensor is real\n        m_globalFlags |= GlobalRealFlag;\n        break;\n      case (NegationFlag | ConjugationFlag):\n        // every element is it's own negative conjugate => whole tensor is imaginary\n        m_globalFlags |= GlobalImagFlag;\n        break;\n      /* NOTE:\n       *   since GlobalZeroFlag == GlobalRealFlag | GlobalImagFlag, if one generator\n       *   causes the tensor to be real and the next one to be imaginary, this will\n       *   trivially give the correct result\n       */\n    }\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSORSYMMETRY_DYNAMICSYMMETRY_H\n\n/*\n * kate: space-indent on; indent-width 2; mixedindent off; indent-mode cstyle;\n */\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/TensorSymmetry/StaticSymmetry.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSORSYMMETRY_STATICSYMMETRY_H\n#define EIGEN_CXX11_TENSORSYMMETRY_STATICSYMMETRY_H\n\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate<typename list> struct tensor_static_symgroup_permutate;\n\ntemplate<int... nn>\nstruct tensor_static_symgroup_permutate<numeric_list<int, nn...>>\n{\n  constexpr static std::size_t N = sizeof...(nn);\n\n  template<typename T>\n  constexpr static inline std::array<T, N> run(const std::array<T, N>& indices)\n  {\n    return {{indices[nn]...}};\n  }\n};\n\ntemplate<typename indices_, int flags_>\nstruct tensor_static_symgroup_element\n{\n  typedef indices_ indices;\n  constexpr static int flags = flags_;\n};\n\ntemplate<typename Gen, int N>\nstruct tensor_static_symgroup_element_ctor\n{\n  typedef tensor_static_symgroup_element<\n    typename gen_numeric_list_swapped_pair<int, N, Gen::One, Gen::Two>::type,\n    Gen::Flags\n  > type;\n};\n\ntemplate<int N>\nstruct tensor_static_symgroup_identity_ctor\n{\n  typedef tensor_static_symgroup_element<\n    typename gen_numeric_list<int, N>::type,\n    0\n  > type;\n};\n\ntemplate<typename iib>\nstruct tensor_static_symgroup_multiply_helper\n{\n  template<int... iia>\n  constexpr static inline numeric_list<int, get<iia, iib>::value...> helper(numeric_list<int, iia...>) {\n    return numeric_list<int, get<iia, iib>::value...>();\n  }\n};\n\ntemplate<typename A, typename B>\nstruct tensor_static_symgroup_multiply\n{\n  private:\n    typedef typename A::indices iia;\n    typedef typename B::indices iib;\n    constexpr static int ffa = A::flags;\n    constexpr static int ffb = B::flags;\n  \n  public:\n    static_assert(iia::count == iib::count, \"Cannot multiply symmetry elements with different number of indices.\");\n\n    typedef tensor_static_symgroup_element<\n      decltype(tensor_static_symgroup_multiply_helper<iib>::helper(iia())),\n      ffa ^ ffb\n    > type;\n};\n\ntemplate<typename A, typename B>\nstruct tensor_static_symgroup_equality\n{\n    typedef typename A::indices iia;\n    typedef typename B::indices iib;\n    constexpr static int ffa = A::flags;\n    constexpr static int ffb = B::flags;\n    static_assert(iia::count == iib::count, \"Cannot compare symmetry elements with different number of indices.\");\n\n    constexpr static bool value = is_same<iia, iib>::value;\n\n  private:\n    /* this should be zero if they are identical, or else the tensor\n     * will be forced to be pure real, pure imaginary or even pure zero\n     */\n    constexpr static int flags_cmp_ = ffa ^ ffb;\n\n    /* either they are not equal, then we don't care whether the flags\n     * match, or they are equal, and then we have to check\n     */\n    constexpr static bool is_zero      = value && flags_cmp_ == NegationFlag;\n    constexpr static bool is_real      = value && flags_cmp_ == ConjugationFlag;\n    constexpr static bool is_imag      = value && flags_cmp_ == (NegationFlag | ConjugationFlag);\n\n  public:\n    constexpr static int global_flags = \n      (is_real ? GlobalRealFlag : 0) |\n      (is_imag ? GlobalImagFlag : 0) |\n      (is_zero ? GlobalZeroFlag : 0);\n};\n\ntemplate<std::size_t NumIndices, typename... Gen>\nstruct tensor_static_symgroup\n{\n  typedef StaticSGroup<Gen...> type;\n  constexpr static std::size_t size = type::static_size;\n};\n\ntemplate<typename Index, std::size_t N, int... ii, int... jj>\nconstexpr static inline std::array<Index, N> tensor_static_symgroup_index_permute(std::array<Index, N> idx, internal::numeric_list<int, ii...>, internal::numeric_list<int, jj...>)\n{\n  return {{ idx[ii]..., idx[jj]... }};\n}\n\ntemplate<typename Index, int... ii>\nstatic inline std::vector<Index> tensor_static_symgroup_index_permute(std::vector<Index> idx, internal::numeric_list<int, ii...>)\n{\n  std::vector<Index> result{{ idx[ii]... }};\n  std::size_t target_size = idx.size();\n  for (std::size_t i = result.size(); i < target_size; i++)\n    result.push_back(idx[i]);\n  return result;\n}\n\ntemplate<typename T> struct tensor_static_symgroup_do_apply;\n\ntemplate<typename first, typename... next>\nstruct tensor_static_symgroup_do_apply<internal::type_list<first, next...>>\n{\n  template<typename Op, typename RV, std::size_t SGNumIndices, typename Index, std::size_t NumIndices, typename... Args>\n  static inline RV run(const std::array<Index, NumIndices>& idx, RV initial, Args&&... args)\n  {\n    static_assert(NumIndices >= SGNumIndices, \"Can only apply symmetry group to objects that have at least the required amount of indices.\");\n    typedef typename internal::gen_numeric_list<int, NumIndices - SGNumIndices, SGNumIndices>::type remaining_indices;\n    initial = Op::run(tensor_static_symgroup_index_permute(idx, typename first::indices(), remaining_indices()), first::flags, initial, std::forward<Args>(args)...);\n    return tensor_static_symgroup_do_apply<internal::type_list<next...>>::template run<Op, RV, SGNumIndices>(idx, initial, args...);\n  }\n\n  template<typename Op, typename RV, std::size_t SGNumIndices, typename Index, typename... Args>\n  static inline RV run(const std::vector<Index>& idx, RV initial, Args&&... args)\n  {\n    eigen_assert(idx.size() >= SGNumIndices && \"Can only apply symmetry group to objects that have at least the required amount of indices.\");\n    initial = Op::run(tensor_static_symgroup_index_permute(idx, typename first::indices()), first::flags, initial, std::forward<Args>(args)...);\n    return tensor_static_symgroup_do_apply<internal::type_list<next...>>::template run<Op, RV, SGNumIndices>(idx, initial, args...);\n  }\n};\n\ntemplate<EIGEN_TPL_PP_SPEC_HACK_DEF(typename, empty)>\nstruct tensor_static_symgroup_do_apply<internal::type_list<EIGEN_TPL_PP_SPEC_HACK_USE(empty)>>\n{\n  template<typename Op, typename RV, std::size_t SGNumIndices, typename Index, std::size_t NumIndices, typename... Args>\n  static inline RV run(const std::array<Index, NumIndices>&, RV initial, Args&&...)\n  {\n    // do nothing\n    return initial;\n  }\n\n  template<typename Op, typename RV, std::size_t SGNumIndices, typename Index, typename... Args>\n  static inline RV run(const std::vector<Index>&, RV initial, Args&&...)\n  {\n    // do nothing\n    return initial;\n  }\n};\n\n} // end namespace internal\n\ntemplate<typename... Gen>\nclass StaticSGroup\n{\n    constexpr static std::size_t NumIndices = internal::tensor_symmetry_num_indices<Gen...>::value;\n    typedef internal::group_theory::enumerate_group_elements<\n      internal::tensor_static_symgroup_multiply,\n      internal::tensor_static_symgroup_equality,\n      typename internal::tensor_static_symgroup_identity_ctor<NumIndices>::type,\n      internal::type_list<typename internal::tensor_static_symgroup_element_ctor<Gen, NumIndices>::type...>\n    > group_elements;\n    typedef typename group_elements::type ge;\n  public:\n    constexpr inline StaticSGroup() {}\n    constexpr inline StaticSGroup(const StaticSGroup<Gen...>&) {}\n    constexpr inline StaticSGroup(StaticSGroup<Gen...>&&) {}\n\n    template<typename Op, typename RV, typename Index, std::size_t N, typename... Args>\n    static inline RV apply(const std::array<Index, N>& idx, RV initial, Args&&... args)\n    {\n      return internal::tensor_static_symgroup_do_apply<ge>::template run<Op, RV, NumIndices>(idx, initial, args...);\n    }\n\n    template<typename Op, typename RV, typename Index, typename... Args>\n    static inline RV apply(const std::vector<Index>& idx, RV initial, Args&&... args)\n    {\n      eigen_assert(idx.size() == NumIndices);\n      return internal::tensor_static_symgroup_do_apply<ge>::template run<Op, RV, NumIndices>(idx, initial, args...);\n    }\n\n    constexpr static std::size_t static_size = ge::count;\n\n    constexpr static inline std::size_t size() {\n      return ge::count;\n    }\n    constexpr static inline int globalFlags() { return group_elements::global_flags; }\n\n    template<typename Tensor_, typename... IndexTypes>\n    inline internal::tensor_symmetry_value_setter<Tensor_, StaticSGroup<Gen...>> operator()(Tensor_& tensor, typename Tensor_::Index firstIndex, IndexTypes... otherIndices) const\n    {\n      static_assert(sizeof...(otherIndices) + 1 == Tensor_::NumIndices, \"Number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\");\n      return operator()(tensor, std::array<typename Tensor_::Index, Tensor_::NumIndices>{{firstIndex, otherIndices...}});\n    }\n\n    template<typename Tensor_>\n    inline internal::tensor_symmetry_value_setter<Tensor_, StaticSGroup<Gen...>> operator()(Tensor_& tensor, std::array<typename Tensor_::Index, Tensor_::NumIndices> const& indices) const\n    {\n      return internal::tensor_symmetry_value_setter<Tensor_, StaticSGroup<Gen...>>(tensor, *this, indices);\n    }\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSORSYMMETRY_STATICSYMMETRY_H\n\n/*\n * kate: space-indent on; indent-width 2; mixedindent off; indent-mode cstyle;\n */\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/TensorSymmetry/Symmetry.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSORSYMMETRY_SYMMETRY_H\n#define EIGEN_CXX11_TENSORSYMMETRY_SYMMETRY_H\n\nnamespace Eigen {\n\nenum {\n  NegationFlag           = 0x01,\n  ConjugationFlag        = 0x02\n};\n\nenum {\n  GlobalRealFlag         = 0x01,\n  GlobalImagFlag         = 0x02,\n  GlobalZeroFlag         = 0x03\n};\n\nnamespace internal {\n\ntemplate<std::size_t NumIndices, typename... Sym>                   struct tensor_symmetry_pre_analysis;\ntemplate<std::size_t NumIndices, typename... Sym>                   struct tensor_static_symgroup;\ntemplate<bool instantiate, std::size_t NumIndices, typename... Sym> struct tensor_static_symgroup_if;\ntemplate<typename Tensor_> struct tensor_symmetry_calculate_flags;\ntemplate<typename Tensor_> struct tensor_symmetry_assign_value;\ntemplate<typename... Sym> struct tensor_symmetry_num_indices;\n\n} // end namespace internal\n\ntemplate<int One_, int Two_>\nstruct Symmetry\n{\n  static_assert(One_ != Two_, \"Symmetries must cover distinct indices.\");\n  constexpr static int One = One_;\n  constexpr static int Two = Two_;\n  constexpr static int Flags = 0;\n};\n\ntemplate<int One_, int Two_>\nstruct AntiSymmetry\n{\n  static_assert(One_ != Two_, \"Symmetries must cover distinct indices.\");\n  constexpr static int One = One_;\n  constexpr static int Two = Two_;\n  constexpr static int Flags = NegationFlag;\n};\n\ntemplate<int One_, int Two_>\nstruct Hermiticity\n{\n  static_assert(One_ != Two_, \"Symmetries must cover distinct indices.\");\n  constexpr static int One = One_;\n  constexpr static int Two = Two_;\n  constexpr static int Flags = ConjugationFlag;\n};\n\ntemplate<int One_, int Two_>\nstruct AntiHermiticity\n{\n  static_assert(One_ != Two_, \"Symmetries must cover distinct indices.\");\n  constexpr static int One = One_;\n  constexpr static int Two = Two_;\n  constexpr static int Flags = ConjugationFlag | NegationFlag;\n};\n\n/** \\class DynamicSGroup\n  * \\ingroup TensorSymmetry_Module\n  *\n  * \\brief Dynamic symmetry group\n  *\n  * The %DynamicSGroup class represents a symmetry group that need not be known at\n  * compile time. It is useful if one wants to support arbitrary run-time defineable\n  * symmetries for tensors, but it is also instantiated if a symmetry group is defined\n  * at compile time that would be either too large for the compiler to reasonably\n  * generate (using templates to calculate this at compile time is very inefficient)\n  * or that the compiler could generate the group but that it wouldn't make sense to\n  * unroll the loop for setting coefficients anymore.\n  */\nclass DynamicSGroup;\n\n/** \\internal\n  *\n  * \\class DynamicSGroupFromTemplateArgs\n  * \\ingroup TensorSymmetry_Module\n  *\n  * \\brief Dynamic symmetry group, initialized from template arguments\n  *\n  * This class is a child class of DynamicSGroup. It uses the template arguments\n  * specified to initialize itself.\n  */\ntemplate<typename... Gen>\nclass DynamicSGroupFromTemplateArgs;\n\n/** \\class StaticSGroup\n  * \\ingroup TensorSymmetry_Module\n  *\n  * \\brief Static symmetry group\n  *\n  * This class represents a symmetry group that is known and resolved completely\n  * at compile time. Ideally, no run-time penalty is incurred compared to the\n  * manual unrolling of the symmetry.\n  *\n  * <b><i>CAUTION:</i></b>\n  *\n  * Do not use this class directly for large symmetry groups. The compiler\n  * may run into a limit, or segfault or in the very least will take a very,\n  * very, very long time to compile the code. Use the SGroup class instead\n  * if you want a static group. That class contains logic that will\n  * automatically select the DynamicSGroup class instead if the symmetry\n  * group becomes too large. (In that case, unrolling may not even be\n  * beneficial.)\n  */\ntemplate<typename... Gen>\nclass StaticSGroup;\n\n/** \\class SGroup\n  * \\ingroup TensorSymmetry_Module\n  *\n  * \\brief Symmetry group, initialized from template arguments\n  *\n  * This class represents a symmetry group whose generators are already\n  * known at compile time. It may or may not be resolved at compile time,\n  * depending on the estimated size of the group.\n  *\n  * \\sa StaticSGroup\n  * \\sa DynamicSGroup\n  */\ntemplate<typename... Gen>\nclass SGroup : public internal::tensor_symmetry_pre_analysis<internal::tensor_symmetry_num_indices<Gen...>::value, Gen...>::root_type\n{\n  public:\n    constexpr static std::size_t NumIndices = internal::tensor_symmetry_num_indices<Gen...>::value;\n    typedef typename internal::tensor_symmetry_pre_analysis<NumIndices, Gen...>::root_type Base;\n\n    // make standard constructors + assignment operators public\n    inline SGroup() : Base() { }\n    inline SGroup(const SGroup<Gen...>& other) : Base(other) { }\n    inline SGroup(SGroup<Gen...>&& other) : Base(other) { }\n    inline SGroup<Gen...>& operator=(const SGroup<Gen...>& other) { Base::operator=(other); return *this; }\n    inline SGroup<Gen...>& operator=(SGroup<Gen...>&& other) { Base::operator=(other); return *this; }\n\n    // all else is defined in the base class\n};\n\nnamespace internal {\n\ntemplate<typename... Sym> struct tensor_symmetry_num_indices\n{\n  constexpr static std::size_t value = 1;\n};\n\ntemplate<int One_, int Two_, typename... Sym> struct tensor_symmetry_num_indices<Symmetry<One_, Two_>, Sym...>\n{\nprivate:\n  constexpr static std::size_t One = static_cast<std::size_t>(One_);\n  constexpr static std::size_t Two = static_cast<std::size_t>(Two_);\n  constexpr static std::size_t Three = tensor_symmetry_num_indices<Sym...>::value;\n\n  // don't use std::max, since it's not constexpr until C++14...\n  constexpr static std::size_t maxOneTwoPlusOne = ((One > Two) ? One : Two) + 1;\npublic:\n  constexpr static std::size_t value = (maxOneTwoPlusOne > Three) ? maxOneTwoPlusOne : Three;\n};\n\ntemplate<int One_, int Two_, typename... Sym> struct tensor_symmetry_num_indices<AntiSymmetry<One_, Two_>, Sym...>\n  : public tensor_symmetry_num_indices<Symmetry<One_, Two_>, Sym...> {};\ntemplate<int One_, int Two_, typename... Sym> struct tensor_symmetry_num_indices<Hermiticity<One_, Two_>, Sym...>\n  : public tensor_symmetry_num_indices<Symmetry<One_, Two_>, Sym...> {};\ntemplate<int One_, int Two_, typename... Sym> struct tensor_symmetry_num_indices<AntiHermiticity<One_, Two_>, Sym...>\n  : public tensor_symmetry_num_indices<Symmetry<One_, Two_>, Sym...> {};\n\n/** \\internal\n  *\n  * \\class tensor_symmetry_pre_analysis\n  * \\ingroup TensorSymmetry_Module\n  *\n  * \\brief Pre-select whether to use a static or dynamic symmetry group\n  *\n  * When a symmetry group could in principle be determined at compile time,\n  * this template implements the logic whether to actually do that or whether\n  * to rather defer that to runtime.\n  *\n  * The logic is as follows:\n  * <dl>\n  * <dt><b>No generators (trivial symmetry):</b></dt>\n  * <dd>Use a trivial static group. Ideally, this has no performance impact\n  *     compared to not using symmetry at all. In practice, this might not\n  *     be the case.</dd>\n  * <dt><b>More than 4 generators:</b></dt>\n  * <dd>Calculate the group at run time, it is likely far too large for the\n  *     compiler to be able to properly generate it in a realistic time.</dd>\n  * <dt><b>Up to and including 4 generators:</b></dt>\n  * <dd>Actually enumerate all group elements, but then check how many there\n  *     are. If there are more than 16, it is unlikely that unrolling the\n  *     loop (as is done in the static compile-time case) is sensible, so\n  *     use a dynamic group instead. If there are at most 16 elements, actually\n  *     use that static group. Note that the largest group with 4 generators\n  *     still compiles with reasonable resources.</dd>\n  * </dl>\n  *\n  * Note: Example compile time performance with g++-4.6 on an Intenl Core i5-3470\n  *       with 16 GiB RAM (all generators non-redundant and the subgroups don't\n  *       factorize):\n  *\n  *          # Generators          -O0 -ggdb               -O2\n  *          -------------------------------------------------------------------\n  *          1                 0.5 s  /   250 MiB     0.45s /   230 MiB\n  *          2                 0.5 s  /   260 MiB     0.5 s /   250 MiB\n  *          3                 0.65s  /   310 MiB     0.62s /   310 MiB\n  *          4                 2.2 s  /   860 MiB     1.7 s /   770 MiB\n  *          5               130   s  / 13000 MiB   120   s / 11000 MiB\n  *\n  * It is clear that everything is still very efficient up to 4 generators, then\n  * the memory and CPU requirements become unreasonable. Thus we only instantiate\n  * the template group theory logic if the number of generators supplied is 4 or\n  * lower, otherwise this will be forced to be done during runtime, where the\n  * algorithm is reasonably fast.\n  */\ntemplate<std::size_t NumIndices>\nstruct tensor_symmetry_pre_analysis<NumIndices>\n{\n  typedef StaticSGroup<> root_type;\n};\n\ntemplate<std::size_t NumIndices, typename Gen_, typename... Gens_>\nstruct tensor_symmetry_pre_analysis<NumIndices, Gen_, Gens_...>\n{\n  constexpr static std::size_t max_static_generators = 4;\n  constexpr static std::size_t max_static_elements = 16;\n  typedef tensor_static_symgroup_if<(sizeof...(Gens_) + 1 <= max_static_generators), NumIndices, Gen_, Gens_...> helper;\n  constexpr static std::size_t possible_size = helper::size;\n\n  typedef typename conditional<\n    possible_size == 0 || possible_size >= max_static_elements,\n    DynamicSGroupFromTemplateArgs<Gen_, Gens_...>,\n    typename helper::type\n  >::type root_type;\n};\n\ntemplate<bool instantiate, std::size_t NumIndices, typename... Gens>\nstruct tensor_static_symgroup_if\n{\n  constexpr static std::size_t size = 0;\n  typedef void type;\n};\n\ntemplate<std::size_t NumIndices, typename... Gens>\nstruct tensor_static_symgroup_if<true, NumIndices, Gens...> : tensor_static_symgroup<NumIndices, Gens...> {};\n\ntemplate<typename Tensor_>\nstruct tensor_symmetry_assign_value\n{\n  typedef typename Tensor_::Index Index;\n  typedef typename Tensor_::Scalar Scalar;\n  constexpr static std::size_t NumIndices = Tensor_::NumIndices;\n\n  static inline int run(const std::array<Index, NumIndices>& transformed_indices, int transformation_flags, int dummy, Tensor_& tensor, const Scalar& value_)\n  {\n    Scalar value(value_);\n    if (transformation_flags & ConjugationFlag)\n      value = numext::conj(value);\n    if (transformation_flags & NegationFlag)\n      value = -value;\n    tensor.coeffRef(transformed_indices) = value;\n    return dummy;\n  }\n};\n\ntemplate<typename Tensor_>\nstruct tensor_symmetry_calculate_flags\n{\n  typedef typename Tensor_::Index Index;\n  constexpr static std::size_t NumIndices = Tensor_::NumIndices;\n\n  static inline int run(const std::array<Index, NumIndices>& transformed_indices, int transform_flags, int current_flags, const std::array<Index, NumIndices>& orig_indices)\n  {\n    if (transformed_indices == orig_indices) {\n      if (transform_flags & (ConjugationFlag | NegationFlag))\n        return current_flags | GlobalImagFlag; // anti-hermitian diagonal\n      else if (transform_flags & ConjugationFlag)\n        return current_flags | GlobalRealFlag; // hermitian diagonal\n      else if (transform_flags & NegationFlag)\n        return current_flags | GlobalZeroFlag; // anti-symmetric diagonal\n    }\n    return current_flags;\n  }\n};\n\ntemplate<typename Tensor_, typename Symmetry_, int Flags = 0>\nclass tensor_symmetry_value_setter\n{\n  public:\n    typedef typename Tensor_::Index Index;\n    typedef typename Tensor_::Scalar Scalar;\n    constexpr static std::size_t NumIndices = Tensor_::NumIndices;\n\n    inline tensor_symmetry_value_setter(Tensor_& tensor, Symmetry_ const& symmetry, std::array<Index, NumIndices> const& indices)\n      : m_tensor(tensor), m_symmetry(symmetry), m_indices(indices) { }\n\n    inline tensor_symmetry_value_setter<Tensor_, Symmetry_, Flags>& operator=(Scalar const& value)\n    {\n      doAssign(value);\n      return *this;\n    }\n  private:\n    Tensor_& m_tensor;\n    Symmetry_ m_symmetry;\n    std::array<Index, NumIndices> m_indices;\n\n    inline void doAssign(Scalar const& value)\n    {\n      #ifdef EIGEN_TENSOR_SYMMETRY_CHECK_VALUES\n        int value_flags = m_symmetry.template apply<internal::tensor_symmetry_calculate_flags<Tensor_>, int>(m_indices, m_symmetry.globalFlags(), m_indices);\n        if (value_flags & GlobalRealFlag)\n          eigen_assert(numext::imag(value) == 0);\n        if (value_flags & GlobalImagFlag)\n          eigen_assert(numext::real(value) == 0);\n      #endif\n      m_symmetry.template apply<internal::tensor_symmetry_assign_value<Tensor_>, int>(m_indices, 0, m_tensor, value);\n    }\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSORSYMMETRY_SYMMETRY_H\n\n/*\n * kate: space-indent on; indent-width 2; mixedindent off; indent-mode cstyle;\n */\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/TensorSymmetry/util/TemplateGroupTheory.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSORSYMMETRY_TEMPLATEGROUPTHEORY_H\n#define EIGEN_CXX11_TENSORSYMMETRY_TEMPLATEGROUPTHEORY_H\n\nnamespace Eigen {\n\nnamespace internal {\n\nnamespace group_theory {\n\n/** \\internal\n  * \\file CXX11/src/TensorSymmetry/util/TemplateGroupTheory.h\n  * This file contains C++ templates that implement group theory algorithms.\n  *\n  * The algorithms allow for a compile-time analysis of finite groups.\n  *\n  * Currently only Dimino's algorithm is implemented, which returns a list\n  * of all elements in a group given a set of (possibly redundant) generators.\n  * (One could also do that with the so-called orbital algorithm, but that\n  * is much more expensive and usually has no advantages.)\n  */\n\n/**********************************************************************\n *                \"Ok kid, here is where it gets complicated.\"\n *                         - Amelia Pond in the \"Doctor Who\" episode\n *                           \"The Big Bang\"\n *\n * Dimino's algorithm\n * ==================\n *\n * The following is Dimino's algorithm in sequential form:\n *\n * Input: identity element, list of generators, equality check,\n *        multiplication operation\n * Output: list of group elements\n *\n * 1. add identity element\n * 2. remove identities from list of generators\n * 3. add all powers of first generator that aren't the\n *    identity element\n * 4. go through all remaining generators:\n *        a. if generator is already in the list of elements\n *                -> do nothing\n *        b. otherwise\n *                i.   remember current # of elements\n *                     (i.e. the size of the current subgroup)\n *                ii.  add all current elements (which includes\n *                     the identity) each multiplied from right\n *                     with the current generator to the group\n *                iii. add all remaining cosets that are generated\n *                     by products of the new generator with itself\n *                     and all other generators seen so far\n *\n * In functional form, this is implemented as a long set of recursive\n * templates that have a complicated relationship.\n *\n * The main interface for Dimino's algorithm is the template\n * enumerate_group_elements. All lists are implemented as variadic\n * type_list<typename...> and numeric_list<typename = int, int...>\n * templates.\n *\n * 'Calling' templates is usually done via typedefs.\n *\n * This algorithm is an extended version of the basic version. The\n * extension consists in the fact that each group element has a set\n * of flags associated with it. Multiplication of two group elements\n * with each other results in a group element whose flags are the\n * XOR of the flags of the previous elements. Each time the algorithm\n * notices that a group element it just calculated is already in the\n * list of current elements, the flags of both will be compared and\n * added to the so-called 'global flags' of the group.\n *\n * The rationale behind this extension is that this allows not only\n * for the description of symmetries between tensor indices, but\n * also allows for the description of hermiticity, antisymmetry and\n * antihermiticity. Negation and conjugation each are specific bit\n * in the flags value and if two different ways to reach a group\n * element lead to two different flags, this poses a constraint on\n * the allowed values of the resulting tensor. For example, if a\n * group element is reach both with and without the conjugation\n * flags, it is clear that the resulting tensor has to be real.\n *\n * Note that this flag mechanism is quite generic and may have other\n * uses beyond tensor properties.\n *\n * IMPORTANT: \n *     This algorithm assumes the group to be finite. If you try to\n *     run it with a group that's infinite, the algorithm will only\n *     terminate once you hit a compiler limit (max template depth).\n *     Also note that trying to use this implementation to create a\n *     very large group will probably either make you hit the same\n *     limit, cause the compiler to segfault or at the very least\n *     take a *really* long time (hours, days, weeks - sic!) to\n *     compile. It is not recommended to plug in more than 4\n *     generators, unless they are independent of each other.\n */\n\n/** \\internal\n  *\n  * \\class strip_identities\n  * \\ingroup CXX11_TensorSymmetry_Module\n  *\n  * \\brief Cleanse a list of group elements of the identity element\n  *\n  * This template is used to make a first pass through all initial\n  * generators of Dimino's algorithm and remove the identity\n  * elements.\n  *\n  * \\sa enumerate_group_elements\n  */\ntemplate<template<typename, typename> class Equality, typename id, typename L> struct strip_identities;\n\ntemplate<\n  template<typename, typename> class Equality,\n  typename id,\n  typename t,\n  typename... ts\n>\nstruct strip_identities<Equality, id, type_list<t, ts...>>\n{\n  typedef typename conditional<\n    Equality<id, t>::value,\n    typename strip_identities<Equality, id, type_list<ts...>>::type,\n    typename concat<type_list<t>, typename strip_identities<Equality, id, type_list<ts...>>::type>::type\n  >::type type;\n  constexpr static int global_flags = Equality<id, t>::global_flags | strip_identities<Equality, id, type_list<ts...>>::global_flags;\n};\n\ntemplate<\n  template<typename, typename> class Equality,\n  typename id\n  EIGEN_TPL_PP_SPEC_HACK_DEFC(typename, ts)\n>\nstruct strip_identities<Equality, id, type_list<EIGEN_TPL_PP_SPEC_HACK_USE(ts)>>\n{\n  typedef type_list<> type;\n  constexpr static int global_flags = 0;\n};\n\n/** \\internal\n  *\n  * \\class dimino_first_step_elements_helper \n  * \\ingroup CXX11_TensorSymmetry_Module\n  *\n  * \\brief Recursive template that adds powers of the first generator to the list of group elements\n  *\n  * This template calls itself recursively to add powers of the first\n  * generator to the list of group elements. It stops if it reaches\n  * the identity element again.\n  *\n  * \\sa enumerate_group_elements, dimino_first_step_elements\n  */\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename g,\n  typename current_element,\n  typename elements,\n  bool dont_add_current_element   // = false\n>\nstruct dimino_first_step_elements_helper\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n  : // recursive inheritance is too difficult for Doxygen\n  public dimino_first_step_elements_helper<\n    Multiply,\n    Equality,\n    id,\n    g,\n    typename Multiply<current_element, g>::type,\n    typename concat<elements, type_list<current_element>>::type,\n    Equality<typename Multiply<current_element, g>::type, id>::value\n  > {};\n\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename g,\n  typename current_element,\n  typename elements\n>\nstruct dimino_first_step_elements_helper<Multiply, Equality, id, g, current_element, elements, true>\n#endif // EIGEN_PARSED_BY_DOXYGEN\n{\n  typedef elements type;\n  constexpr static int global_flags = Equality<current_element, id>::global_flags;\n};\n\n/** \\internal\n  *\n  * \\class dimino_first_step_elements\n  * \\ingroup CXX11_TensorSymmetry_Module\n  *\n  * \\brief Add all powers of the first generator to the list of group elements\n  *\n  * This template takes the first non-identity generator and generates the initial\n  * list of elements which consists of all powers of that generator. For a group\n  * with just one generated, it would be enumerated after this.\n  *\n  * \\sa enumerate_group_elements\n  */\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename generators\n>\nstruct dimino_first_step_elements\n{\n  typedef typename get<0, generators>::type first_generator;\n  typedef typename skip<1, generators>::type next_generators;\n  typedef type_list<first_generator> generators_done;\n\n  typedef dimino_first_step_elements_helper<\n    Multiply,\n    Equality,\n    id,\n    first_generator,\n    first_generator,\n    type_list<id>,\n    false\n  > helper;\n  typedef typename helper::type type;\n  constexpr static int global_flags = helper::global_flags;\n};\n\n/** \\internal\n  *\n  * \\class dimino_get_coset_elements\n  * \\ingroup CXX11_TensorSymmetry_Module\n  *\n  * \\brief Generate all elements of a specific coset\n  *\n  * This template generates all the elements of a specific coset by\n  * multiplying all elements in the given subgroup with the new\n  * coset representative. Note that the first element of the\n  * subgroup is always the identity element, so the first element of\n  * the result of this template is going to be the coset\n  * representative itself.\n  *\n  * Note that this template accepts an additional boolean parameter\n  * that specifies whether to actually generate the coset (true) or\n  * just return an empty list (false).\n  *\n  * \\sa enumerate_group_elements, dimino_add_cosets_for_rep\n  */\ntemplate<\n  template<typename, typename> class Multiply,\n  typename sub_group_elements,\n  typename new_coset_rep,\n  bool generate_coset      // = true\n>\nstruct dimino_get_coset_elements\n{\n  typedef typename apply_op_from_right<Multiply, new_coset_rep, sub_group_elements>::type type;\n};\n\ntemplate<\n  template<typename, typename> class Multiply,\n  typename sub_group_elements,\n  typename new_coset_rep\n>\nstruct dimino_get_coset_elements<Multiply, sub_group_elements, new_coset_rep, false>\n{\n  typedef type_list<> type;\n};\n\n/** \\internal\n  *\n  * \\class dimino_add_cosets_for_rep\n  * \\ingroup CXX11_TensorSymmetry_Module\n  *\n  * \\brief Recursive template for adding coset spaces\n  *\n  * This template multiplies the coset representative with a generator\n  * from the list of previous generators. If the new element is not in\n  * the group already, it adds the corresponding coset. Finally it\n  * proceeds to call itself with the next generator from the list.\n  *\n  * \\sa enumerate_group_elements, dimino_add_all_coset_spaces\n  */\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename sub_group_elements,\n  typename elements,\n  typename generators,\n  typename rep_element,\n  int sub_group_size\n>\nstruct dimino_add_cosets_for_rep;\n\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename sub_group_elements,\n  typename elements,\n  typename g,\n  typename... gs,\n  typename rep_element,\n  int sub_group_size\n>\nstruct dimino_add_cosets_for_rep<Multiply, Equality, id, sub_group_elements, elements, type_list<g, gs...>, rep_element, sub_group_size>\n{\n  typedef typename Multiply<rep_element, g>::type new_coset_rep;\n  typedef contained_in_list_gf<Equality, new_coset_rep, elements> _cil;\n  constexpr static bool add_coset = !_cil::value;\n\n  typedef typename dimino_get_coset_elements<\n    Multiply,\n    sub_group_elements,\n    new_coset_rep,\n    add_coset\n  >::type coset_elements;\n\n  typedef dimino_add_cosets_for_rep<\n    Multiply,\n    Equality,\n    id,\n    sub_group_elements,\n    typename concat<elements, coset_elements>::type,\n    type_list<gs...>,\n    rep_element,\n    sub_group_size\n  > _helper;\n\n  typedef typename _helper::type type;\n  constexpr static int global_flags = _cil::global_flags | _helper::global_flags;\n\n  /* Note that we don't have to update global flags here, since\n   * we will only add these elements if they are not part of\n   * the group already. But that only happens if the coset rep\n   * is not already in the group, so the check for the coset rep\n   * will catch this.\n   */\n};\n\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename sub_group_elements,\n  typename elements\n  EIGEN_TPL_PP_SPEC_HACK_DEFC(typename, empty),\n  typename rep_element,\n  int sub_group_size\n>\nstruct dimino_add_cosets_for_rep<Multiply, Equality, id, sub_group_elements, elements, type_list<EIGEN_TPL_PP_SPEC_HACK_USE(empty)>, rep_element, sub_group_size>\n{\n  typedef elements type;\n  constexpr static int global_flags = 0;\n};\n\n/** \\internal\n  *\n  * \\class dimino_add_all_coset_spaces\n  * \\ingroup CXX11_TensorSymmetry_Module\n  *\n  * \\brief Recursive template for adding all coset spaces for a new generator\n  *\n  * This template tries to go through the list of generators (with\n  * the help of the dimino_add_cosets_for_rep template) as long as\n  * it still finds elements that are not part of the group and add\n  * the corresponding cosets.\n  *\n  * \\sa enumerate_group_elements, dimino_add_cosets_for_rep\n  */\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename sub_group_elements,\n  typename elements,\n  typename generators,\n  int sub_group_size,\n  int rep_pos,\n  bool stop_condition        // = false\n>\nstruct dimino_add_all_coset_spaces\n{\n  typedef typename get<rep_pos, elements>::type rep_element;\n  typedef dimino_add_cosets_for_rep<\n    Multiply,\n    Equality,\n    id,\n    sub_group_elements,\n    elements,\n    generators,\n    rep_element,\n    sub_group_elements::count\n  > _ac4r;\n  typedef typename _ac4r::type new_elements;\n  \n  constexpr static int new_rep_pos = rep_pos + sub_group_elements::count;\n  constexpr static bool new_stop_condition = new_rep_pos >= new_elements::count;\n\n  typedef dimino_add_all_coset_spaces<\n    Multiply,\n    Equality,\n    id,\n    sub_group_elements,\n    new_elements,\n    generators,\n    sub_group_size,\n    new_rep_pos,\n    new_stop_condition\n  > _helper;\n\n  typedef typename _helper::type type;\n  constexpr static int global_flags = _helper::global_flags | _ac4r::global_flags;\n};\n\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename sub_group_elements,\n  typename elements,\n  typename generators,\n  int sub_group_size,\n  int rep_pos\n>\nstruct dimino_add_all_coset_spaces<Multiply, Equality, id, sub_group_elements, elements, generators, sub_group_size, rep_pos, true>\n{\n  typedef elements type;\n  constexpr static int global_flags = 0;\n};\n\n/** \\internal\n  *\n  * \\class dimino_add_generator\n  * \\ingroup CXX11_TensorSymmetry_Module\n  *\n  * \\brief Enlarge the group by adding a new generator.\n  *\n  * It accepts a boolean parameter that determines if the generator is redundant,\n  * i.e. was already seen in the group. In that case, it reduces to a no-op.\n  *\n  * \\sa enumerate_group_elements, dimino_add_all_coset_spaces\n  */\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename elements,\n  typename generators_done,\n  typename current_generator,\n  bool redundant          // = false\n>\nstruct dimino_add_generator\n{\n  /* this template is only called if the generator is not redundant\n   * => all elements of the group multiplied with the new generator\n   *    are going to be new elements of the most trivial coset space\n   */\n  typedef typename apply_op_from_right<Multiply, current_generator, elements>::type multiplied_elements;\n  typedef typename concat<elements, multiplied_elements>::type new_elements;\n\n  constexpr static int rep_pos = elements::count;\n\n  typedef dimino_add_all_coset_spaces<\n    Multiply,\n    Equality,\n    id,\n    elements, // elements of previous subgroup\n    new_elements,\n    typename concat<generators_done, type_list<current_generator>>::type,\n    elements::count, // size of previous subgroup\n    rep_pos,\n    false // don't stop (because rep_pos >= new_elements::count is always false at this point)\n  > _helper;\n  typedef typename _helper::type type;\n  constexpr static int global_flags = _helper::global_flags;\n};\n\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename elements,\n  typename generators_done,\n  typename current_generator\n>\nstruct dimino_add_generator<Multiply, Equality, id, elements, generators_done, current_generator, true>\n{\n  // redundant case\n  typedef elements type;\n  constexpr static int global_flags = 0;\n};\n\n/** \\internal\n  *\n  * \\class dimino_add_remaining_generators\n  * \\ingroup CXX11_TensorSymmetry_Module\n  *\n  * \\brief Recursive template that adds all remaining generators to a group\n  *\n  * Loop through the list of generators that remain and successively\n  * add them to the group.\n  *\n  * \\sa enumerate_group_elements, dimino_add_generator\n  */\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename generators_done,\n  typename remaining_generators,\n  typename elements\n>\nstruct dimino_add_remaining_generators\n{\n  typedef typename get<0, remaining_generators>::type first_generator;\n  typedef typename skip<1, remaining_generators>::type next_generators;\n\n  typedef contained_in_list_gf<Equality, first_generator, elements> _cil;\n\n  typedef dimino_add_generator<\n    Multiply,\n    Equality,\n    id,\n    elements,\n    generators_done,\n    first_generator,\n    _cil::value\n  > _helper;\n\n  typedef typename _helper::type new_elements;\n\n  typedef dimino_add_remaining_generators<\n    Multiply,\n    Equality,\n    id,\n    typename concat<generators_done, type_list<first_generator>>::type,\n    next_generators,\n    new_elements\n  > _next_iter;\n\n  typedef typename _next_iter::type type;\n  constexpr static int global_flags =\n    _cil::global_flags |\n    _helper::global_flags |\n    _next_iter::global_flags;\n};\n\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename generators_done,\n  typename elements\n>\nstruct dimino_add_remaining_generators<Multiply, Equality, id, generators_done, type_list<>, elements>\n{\n  typedef elements type;\n  constexpr static int global_flags = 0;\n};\n\n/** \\internal\n  *\n  * \\class enumerate_group_elements_noid\n  * \\ingroup CXX11_TensorSymmetry_Module\n  *\n  * \\brief Helper template that implements group element enumeration\n  *\n  * This is a helper template that implements the actual enumeration\n  * of group elements. This has been split so that the list of\n  * generators can be cleansed of the identity element before\n  * performing the actual operation.\n  *\n  * \\sa enumerate_group_elements\n  */\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename generators,\n  int initial_global_flags = 0\n>\nstruct enumerate_group_elements_noid\n{\n  typedef dimino_first_step_elements<Multiply, Equality, id, generators> first_step;\n  typedef typename first_step::type first_step_elements;\n\n  typedef dimino_add_remaining_generators<\n    Multiply,\n    Equality,\n    id,\n    typename first_step::generators_done,\n    typename first_step::next_generators, // remaining_generators\n    typename first_step::type // first_step elements\n  > _helper;\n\n  typedef typename _helper::type type;\n  constexpr static int global_flags =\n    initial_global_flags |\n    first_step::global_flags |\n    _helper::global_flags;\n};\n\n// in case when no generators are specified\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  int initial_global_flags\n>\nstruct enumerate_group_elements_noid<Multiply, Equality, id, type_list<>, initial_global_flags>\n{\n  typedef type_list<id> type;\n  constexpr static int global_flags = initial_global_flags;\n};\n\n/** \\internal\n  *\n  * \\class enumerate_group_elements\n  * \\ingroup CXX11_TensorSymmetry_Module\n  *\n  * \\brief Enumerate all elements in a finite group\n  *\n  * This template enumerates all elements in a finite group. It accepts\n  * the following template parameters:\n  *\n  * \\tparam Multiply      The multiplication operation that multiplies two group elements\n  *                       with each other.\n  * \\tparam Equality      The equality check operation that checks if two group elements\n  *                       are equal to another.\n  * \\tparam id            The identity element\n  * \\tparam Generators_   A list of (possibly redundant) generators of the group\n  */\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename Generators_\n>\nstruct enumerate_group_elements\n  : public enumerate_group_elements_noid<\n      Multiply,\n      Equality,\n      id,\n      typename strip_identities<Equality, id, Generators_>::type,\n      strip_identities<Equality, id, Generators_>::global_flags\n    >\n{\n};\n\n} // end namespace group_theory\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSORSYMMETRY_TEMPLATEGROUPTHEORY_H\n\n/*\n * kate: space-indent on; indent-width 2; mixedindent off; indent-mode cstyle;\n */\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/ThreadPool/Barrier.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2018 Rasmus Munk Larsen <rmlarsen@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// Barrier is an object that allows one or more threads to wait until\n// Notify has been called a specified number of times.\n\n#ifndef EIGEN_CXX11_THREADPOOL_BARRIER_H\n#define EIGEN_CXX11_THREADPOOL_BARRIER_H\n\nnamespace Eigen {\n\nclass Barrier {\n public:\n  Barrier(unsigned int count) : state_(count << 1), notified_(false) {\n    eigen_plain_assert(((count << 1) >> 1) == count);\n  }\n  ~Barrier() { eigen_plain_assert((state_ >> 1) == 0); }\n\n  void Notify() {\n    unsigned int v = state_.fetch_sub(2, std::memory_order_acq_rel) - 2;\n    if (v != 1) {\n      // Clear the lowest bit (waiter flag) and check that the original state\n      // value was not zero. If it was zero, it means that notify was called\n      // more times than the original count.\n      eigen_plain_assert(((v + 2) & ~1) != 0);\n      return;  // either count has not dropped to 0, or waiter is not waiting\n    }\n    std::unique_lock<std::mutex> l(mu_);\n    eigen_plain_assert(!notified_);\n    notified_ = true;\n    cv_.notify_all();\n  }\n\n  void Wait() {\n    unsigned int v = state_.fetch_or(1, std::memory_order_acq_rel);\n    if ((v >> 1) == 0) return;\n    std::unique_lock<std::mutex> l(mu_);\n    while (!notified_) {\n      cv_.wait(l);\n    }\n  }\n\n private:\n  std::mutex mu_;\n  std::condition_variable cv_;\n  std::atomic<unsigned int> state_;  // low bit is waiter flag\n  bool notified_;\n};\n\n// Notification is an object that allows a user to to wait for another\n// thread to signal a notification that an event has occurred.\n//\n// Multiple threads can wait on the same Notification object,\n// but only one caller must call Notify() on the object.\nstruct Notification : Barrier {\n  Notification() : Barrier(1){};\n};\n\n}  // namespace Eigen\n\n#endif  // EIGEN_CXX11_THREADPOOL_BARRIER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/ThreadPool/EventCount.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Dmitry Vyukov <dvyukov@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_THREADPOOL_EVENTCOUNT_H_\n#define EIGEN_CXX11_THREADPOOL_EVENTCOUNT_H_\n\nnamespace Eigen {\n\n// EventCount allows to wait for arbitrary predicates in non-blocking\n// algorithms. Think of condition variable, but wait predicate does not need to\n// be protected by a mutex. Usage:\n// Waiting thread does:\n//\n//   if (predicate)\n//     return act();\n//   EventCount::Waiter& w = waiters[my_index];\n//   ec.Prewait(&w);\n//   if (predicate) {\n//     ec.CancelWait(&w);\n//     return act();\n//   }\n//   ec.CommitWait(&w);\n//\n// Notifying thread does:\n//\n//   predicate = true;\n//   ec.Notify(true);\n//\n// Notify is cheap if there are no waiting threads. Prewait/CommitWait are not\n// cheap, but they are executed only if the preceding predicate check has\n// failed.\n//\n// Algorithm outline:\n// There are two main variables: predicate (managed by user) and state_.\n// Operation closely resembles Dekker mutual algorithm:\n// https://en.wikipedia.org/wiki/Dekker%27s_algorithm\n// Waiting thread sets state_ then checks predicate, Notifying thread sets\n// predicate then checks state_. Due to seq_cst fences in between these\n// operations it is guaranteed than either waiter will see predicate change\n// and won't block, or notifying thread will see state_ change and will unblock\n// the waiter, or both. But it can't happen that both threads don't see each\n// other changes, which would lead to deadlock.\nclass EventCount {\n public:\n  class Waiter;\n\n  EventCount(MaxSizeVector<Waiter>& waiters)\n      : state_(kStackMask), waiters_(waiters) {\n    eigen_plain_assert(waiters.size() < (1 << kWaiterBits) - 1);\n  }\n\n  ~EventCount() {\n    // Ensure there are no waiters.\n    eigen_plain_assert(state_.load() == kStackMask);\n  }\n\n  // Prewait prepares for waiting.\n  // After calling Prewait, the thread must re-check the wait predicate\n  // and then call either CancelWait or CommitWait.\n  void Prewait() {\n    uint64_t state = state_.load(std::memory_order_relaxed);\n    for (;;) {\n      CheckState(state);\n      uint64_t newstate = state + kWaiterInc;\n      CheckState(newstate);\n      if (state_.compare_exchange_weak(state, newstate,\n                                       std::memory_order_seq_cst))\n        return;\n    }\n  }\n\n  // CommitWait commits waiting after Prewait.\n  void CommitWait(Waiter* w) {\n    eigen_plain_assert((w->epoch & ~kEpochMask) == 0);\n    w->state = Waiter::kNotSignaled;\n    const uint64_t me = (w - &waiters_[0]) | w->epoch;\n    uint64_t state = state_.load(std::memory_order_seq_cst);\n    for (;;) {\n      CheckState(state, true);\n      uint64_t newstate;\n      if ((state & kSignalMask) != 0) {\n        // Consume the signal and return immidiately.\n        newstate = state - kWaiterInc - kSignalInc;\n      } else {\n        // Remove this thread from pre-wait counter and add to the waiter stack.\n        newstate = ((state & kWaiterMask) - kWaiterInc) | me;\n        w->next.store(state & (kStackMask | kEpochMask),\n                      std::memory_order_relaxed);\n      }\n      CheckState(newstate);\n      if (state_.compare_exchange_weak(state, newstate,\n                                       std::memory_order_acq_rel)) {\n        if ((state & kSignalMask) == 0) {\n          w->epoch += kEpochInc;\n          Park(w);\n        }\n        return;\n      }\n    }\n  }\n\n  // CancelWait cancels effects of the previous Prewait call.\n  void CancelWait() {\n    uint64_t state = state_.load(std::memory_order_relaxed);\n    for (;;) {\n      CheckState(state, true);\n      uint64_t newstate = state - kWaiterInc;\n      // We don't know if the thread was also notified or not,\n      // so we should not consume a signal unconditionaly.\n      // Only if number of waiters is equal to number of signals,\n      // we know that the thread was notified and we must take away the signal.\n      if (((state & kWaiterMask) >> kWaiterShift) ==\n          ((state & kSignalMask) >> kSignalShift))\n        newstate -= kSignalInc;\n      CheckState(newstate);\n      if (state_.compare_exchange_weak(state, newstate,\n                                       std::memory_order_acq_rel))\n        return;\n    }\n  }\n\n  // Notify wakes one or all waiting threads.\n  // Must be called after changing the associated wait predicate.\n  void Notify(bool notifyAll) {\n    std::atomic_thread_fence(std::memory_order_seq_cst);\n    uint64_t state = state_.load(std::memory_order_acquire);\n    for (;;) {\n      CheckState(state);\n      const uint64_t waiters = (state & kWaiterMask) >> kWaiterShift;\n      const uint64_t signals = (state & kSignalMask) >> kSignalShift;\n      // Easy case: no waiters.\n      if ((state & kStackMask) == kStackMask && waiters == signals) return;\n      uint64_t newstate;\n      if (notifyAll) {\n        // Empty wait stack and set signal to number of pre-wait threads.\n        newstate =\n            (state & kWaiterMask) | (waiters << kSignalShift) | kStackMask;\n      } else if (signals < waiters) {\n        // There is a thread in pre-wait state, unblock it.\n        newstate = state + kSignalInc;\n      } else {\n        // Pop a waiter from list and unpark it.\n        Waiter* w = &waiters_[state & kStackMask];\n        uint64_t next = w->next.load(std::memory_order_relaxed);\n        newstate = (state & (kWaiterMask | kSignalMask)) | next;\n      }\n      CheckState(newstate);\n      if (state_.compare_exchange_weak(state, newstate,\n                                       std::memory_order_acq_rel)) {\n        if (!notifyAll && (signals < waiters))\n          return;  // unblocked pre-wait thread\n        if ((state & kStackMask) == kStackMask) return;\n        Waiter* w = &waiters_[state & kStackMask];\n        if (!notifyAll) w->next.store(kStackMask, std::memory_order_relaxed);\n        Unpark(w);\n        return;\n      }\n    }\n  }\n\n  class Waiter {\n    friend class EventCount;\n    // Align to 128 byte boundary to prevent false sharing with other Waiter\n    // objects in the same vector.\n    EIGEN_ALIGN_TO_BOUNDARY(128) std::atomic<uint64_t> next;\n    std::mutex mu;\n    std::condition_variable cv;\n    uint64_t epoch = 0;\n    unsigned state = kNotSignaled;\n    enum {\n      kNotSignaled,\n      kWaiting,\n      kSignaled,\n    };\n  };\n\n private:\n  // State_ layout:\n  // - low kWaiterBits is a stack of waiters committed wait\n  //   (indexes in waiters_ array are used as stack elements,\n  //   kStackMask means empty stack).\n  // - next kWaiterBits is count of waiters in prewait state.\n  // - next kWaiterBits is count of pending signals.\n  // - remaining bits are ABA counter for the stack.\n  //   (stored in Waiter node and incremented on push).\n  static const uint64_t kWaiterBits = 14;\n  static const uint64_t kStackMask = (1ull << kWaiterBits) - 1;\n  static const uint64_t kWaiterShift = kWaiterBits;\n  static const uint64_t kWaiterMask = ((1ull << kWaiterBits) - 1)\n                                      << kWaiterShift;\n  static const uint64_t kWaiterInc = 1ull << kWaiterShift;\n  static const uint64_t kSignalShift = 2 * kWaiterBits;\n  static const uint64_t kSignalMask = ((1ull << kWaiterBits) - 1)\n                                      << kSignalShift;\n  static const uint64_t kSignalInc = 1ull << kSignalShift;\n  static const uint64_t kEpochShift = 3 * kWaiterBits;\n  static const uint64_t kEpochBits = 64 - kEpochShift;\n  static const uint64_t kEpochMask = ((1ull << kEpochBits) - 1) << kEpochShift;\n  static const uint64_t kEpochInc = 1ull << kEpochShift;\n  std::atomic<uint64_t> state_;\n  MaxSizeVector<Waiter>& waiters_;\n\n  static void CheckState(uint64_t state, bool waiter = false) {\n    static_assert(kEpochBits >= 20, \"not enough bits to prevent ABA problem\");\n    const uint64_t waiters = (state & kWaiterMask) >> kWaiterShift;\n    const uint64_t signals = (state & kSignalMask) >> kSignalShift;\n    eigen_plain_assert(waiters >= signals);\n    eigen_plain_assert(waiters < (1 << kWaiterBits) - 1);\n    eigen_plain_assert(!waiter || waiters > 0);\n    (void)waiters;\n    (void)signals;\n  }\n\n  void Park(Waiter* w) {\n    std::unique_lock<std::mutex> lock(w->mu);\n    while (w->state != Waiter::kSignaled) {\n      w->state = Waiter::kWaiting;\n      w->cv.wait(lock);\n    }\n  }\n\n  void Unpark(Waiter* w) {\n    for (Waiter* next; w; w = next) {\n      uint64_t wnext = w->next.load(std::memory_order_relaxed) & kStackMask;\n      next = wnext == kStackMask ? nullptr : &waiters_[wnext];\n      unsigned state;\n      {\n        std::unique_lock<std::mutex> lock(w->mu);\n        state = w->state;\n        w->state = Waiter::kSignaled;\n      }\n      // Avoid notifying if it wasn't waiting.\n      if (state == Waiter::kWaiting) w->cv.notify_one();\n    }\n  }\n\n  EventCount(const EventCount&) = delete;\n  void operator=(const EventCount&) = delete;\n};\n\n}  // namespace Eigen\n\n#endif  // EIGEN_CXX11_THREADPOOL_EVENTCOUNT_H_\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/ThreadPool/NonBlockingThreadPool.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Dmitry Vyukov <dvyukov@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_THREADPOOL_NONBLOCKING_THREAD_POOL_H\n#define EIGEN_CXX11_THREADPOOL_NONBLOCKING_THREAD_POOL_H\n\nnamespace Eigen {\n\ntemplate <typename Environment>\nclass ThreadPoolTempl : public Eigen::ThreadPoolInterface {\n public:\n  typedef typename Environment::Task Task;\n  typedef RunQueue<Task, 1024> Queue;\n\n  ThreadPoolTempl(int num_threads, Environment env = Environment())\n      : ThreadPoolTempl(num_threads, true, env) {}\n\n  ThreadPoolTempl(int num_threads, bool allow_spinning,\n                  Environment env = Environment())\n      : env_(env),\n        num_threads_(num_threads),\n        allow_spinning_(allow_spinning),\n        thread_data_(num_threads),\n        all_coprimes_(num_threads),\n        waiters_(num_threads),\n        global_steal_partition_(EncodePartition(0, num_threads_)),\n        blocked_(0),\n        spinning_(0),\n        done_(false),\n        cancelled_(false),\n        ec_(waiters_) {\n    waiters_.resize(num_threads_);\n    // Calculate coprimes of all numbers [1, num_threads].\n    // Coprimes are used for random walks over all threads in Steal\n    // and NonEmptyQueueIndex. Iteration is based on the fact that if we take\n    // a random starting thread index t and calculate num_threads - 1 subsequent\n    // indices as (t + coprime) % num_threads, we will cover all threads without\n    // repetitions (effectively getting a presudo-random permutation of thread\n    // indices).\n    eigen_plain_assert(num_threads_ < kMaxThreads);\n    for (int i = 1; i <= num_threads_; ++i) {\n      all_coprimes_.emplace_back(i);\n      ComputeCoprimes(i, &all_coprimes_.back());\n    }\n#ifndef EIGEN_THREAD_LOCAL\n    init_barrier_.reset(new Barrier(num_threads_));\n#endif\n    thread_data_.resize(num_threads_);\n    for (int i = 0; i < num_threads_; i++) {\n      SetStealPartition(i, EncodePartition(0, num_threads_));\n      thread_data_[i].thread.reset(\n          env_.CreateThread([this, i]() { WorkerLoop(i); }));\n    }\n#ifndef EIGEN_THREAD_LOCAL\n    // Wait for workers to initialize per_thread_map_. Otherwise we might race\n    // with them in Schedule or CurrentThreadId.\n    init_barrier_->Wait();\n#endif\n  }\n\n  ~ThreadPoolTempl() {\n    done_ = true;\n\n    // Now if all threads block without work, they will start exiting.\n    // But note that threads can continue to work arbitrary long,\n    // block, submit new work, unblock and otherwise live full life.\n    if (!cancelled_) {\n      ec_.Notify(true);\n    } else {\n      // Since we were cancelled, there might be entries in the queues.\n      // Empty them to prevent their destructor from asserting.\n      for (size_t i = 0; i < thread_data_.size(); i++) {\n        thread_data_[i].queue.Flush();\n      }\n    }\n    // Join threads explicitly (by destroying) to avoid destruction order within\n    // this class.\n    for (size_t i = 0; i < thread_data_.size(); ++i)\n      thread_data_[i].thread.reset();\n  }\n\n  void SetStealPartitions(const std::vector<std::pair<unsigned, unsigned>>& partitions) {\n    eigen_plain_assert(partitions.size() == static_cast<std::size_t>(num_threads_));\n\n    // Pass this information to each thread queue.\n    for (int i = 0; i < num_threads_; i++) {\n      const auto& pair = partitions[i];\n      unsigned start = pair.first, end = pair.second;\n      AssertBounds(start, end);\n      unsigned val = EncodePartition(start, end);\n      SetStealPartition(i, val);\n    }\n  }\n\n  void Schedule(std::function<void()> fn) EIGEN_OVERRIDE {\n    ScheduleWithHint(std::move(fn), 0, num_threads_);\n  }\n\n  void ScheduleWithHint(std::function<void()> fn, int start,\n                        int limit) override {\n    Task t = env_.CreateTask(std::move(fn));\n    PerThread* pt = GetPerThread();\n    if (pt->pool == this) {\n      // Worker thread of this pool, push onto the thread's queue.\n      Queue& q = thread_data_[pt->thread_id].queue;\n      t = q.PushFront(std::move(t));\n    } else {\n      // A free-standing thread (or worker of another pool), push onto a random\n      // queue.\n      eigen_plain_assert(start < limit);\n      eigen_plain_assert(limit <= num_threads_);\n      int num_queues = limit - start;\n      int rnd = Rand(&pt->rand) % num_queues;\n      eigen_plain_assert(start + rnd < limit);\n      Queue& q = thread_data_[start + rnd].queue;\n      t = q.PushBack(std::move(t));\n    }\n    // Note: below we touch this after making w available to worker threads.\n    // Strictly speaking, this can lead to a racy-use-after-free. Consider that\n    // Schedule is called from a thread that is neither main thread nor a worker\n    // thread of this pool. Then, execution of w directly or indirectly\n    // completes overall computations, which in turn leads to destruction of\n    // this. We expect that such scenario is prevented by program, that is,\n    // this is kept alive while any threads can potentially be in Schedule.\n    if (!t.f) {\n      ec_.Notify(false);\n    } else {\n      env_.ExecuteTask(t);  // Push failed, execute directly.\n    }\n  }\n\n  void Cancel() EIGEN_OVERRIDE {\n    cancelled_ = true;\n    done_ = true;\n\n    // Let each thread know it's been cancelled.\n#ifdef EIGEN_THREAD_ENV_SUPPORTS_CANCELLATION\n    for (size_t i = 0; i < thread_data_.size(); i++) {\n      thread_data_[i].thread->OnCancel();\n    }\n#endif\n\n    // Wake up the threads without work to let them exit on their own.\n    ec_.Notify(true);\n  }\n\n  int NumThreads() const EIGEN_FINAL { return num_threads_; }\n\n  int CurrentThreadId() const EIGEN_FINAL {\n    const PerThread* pt = const_cast<ThreadPoolTempl*>(this)->GetPerThread();\n    if (pt->pool == this) {\n      return pt->thread_id;\n    } else {\n      return -1;\n    }\n  }\n\n private:\n  // Create a single atomic<int> that encodes start and limit information for\n  // each thread.\n  // We expect num_threads_ < 65536, so we can store them in a single\n  // std::atomic<unsigned>.\n  // Exposed publicly as static functions so that external callers can reuse\n  // this encode/decode logic for maintaining their own thread-safe copies of\n  // scheduling and steal domain(s).\n  static const int kMaxPartitionBits = 16;\n  static const int kMaxThreads = 1 << kMaxPartitionBits;\n\n  inline unsigned EncodePartition(unsigned start, unsigned limit) {\n    return (start << kMaxPartitionBits) | limit;\n  }\n\n  inline void DecodePartition(unsigned val, unsigned* start, unsigned* limit) {\n    *limit = val & (kMaxThreads - 1);\n    val >>= kMaxPartitionBits;\n    *start = val;\n  }\n\n  void AssertBounds(int start, int end) {\n    eigen_plain_assert(start >= 0);\n    eigen_plain_assert(start < end);  // non-zero sized partition\n    eigen_plain_assert(end <= num_threads_);\n  }\n\n  inline void SetStealPartition(size_t i, unsigned val) {\n    thread_data_[i].steal_partition.store(val, std::memory_order_relaxed);\n  }\n\n  inline unsigned GetStealPartition(int i) {\n    return thread_data_[i].steal_partition.load(std::memory_order_relaxed);\n  }\n\n  void ComputeCoprimes(int N, MaxSizeVector<unsigned>* coprimes) {\n    for (int i = 1; i <= N; i++) {\n      unsigned a = i;\n      unsigned b = N;\n      // If GCD(a, b) == 1, then a and b are coprimes.\n      while (b != 0) {\n        unsigned tmp = a;\n        a = b;\n        b = tmp % b;\n      }\n      if (a == 1) {\n        coprimes->push_back(i);\n      }\n    }\n  }\n\n  typedef typename Environment::EnvThread Thread;\n\n  struct PerThread {\n    constexpr PerThread() : pool(NULL), rand(0), thread_id(-1) {}\n    ThreadPoolTempl* pool;  // Parent pool, or null for normal threads.\n    uint64_t rand;          // Random generator state.\n    int thread_id;          // Worker thread index in pool.\n#ifndef EIGEN_THREAD_LOCAL\n    // Prevent false sharing.\n    char pad_[128];\n#endif\n  };\n\n  struct ThreadData {\n    constexpr ThreadData() : thread(), steal_partition(0), queue() {}\n    std::unique_ptr<Thread> thread;\n    std::atomic<unsigned> steal_partition;\n    Queue queue;\n  };\n\n  Environment env_;\n  const int num_threads_;\n  const bool allow_spinning_;\n  MaxSizeVector<ThreadData> thread_data_;\n  MaxSizeVector<MaxSizeVector<unsigned>> all_coprimes_;\n  MaxSizeVector<EventCount::Waiter> waiters_;\n  unsigned global_steal_partition_;\n  std::atomic<unsigned> blocked_;\n  std::atomic<bool> spinning_;\n  std::atomic<bool> done_;\n  std::atomic<bool> cancelled_;\n  EventCount ec_;\n#ifndef EIGEN_THREAD_LOCAL\n  std::unique_ptr<Barrier> init_barrier_;\n  std::mutex per_thread_map_mutex_;  // Protects per_thread_map_.\n  std::unordered_map<uint64_t, std::unique_ptr<PerThread>> per_thread_map_;\n#endif\n\n  // Main worker thread loop.\n  void WorkerLoop(int thread_id) {\n#ifndef EIGEN_THREAD_LOCAL\n    std::unique_ptr<PerThread> new_pt(new PerThread());\n    per_thread_map_mutex_.lock();\n    bool insertOK = per_thread_map_.emplace(GlobalThreadIdHash(), std::move(new_pt)).second;\n    eigen_plain_assert(insertOK);\n    EIGEN_UNUSED_VARIABLE(insertOK);\n    per_thread_map_mutex_.unlock();\n    init_barrier_->Notify();\n    init_barrier_->Wait();\n#endif\n    PerThread* pt = GetPerThread();\n    pt->pool = this;\n    pt->rand = GlobalThreadIdHash();\n    pt->thread_id = thread_id;\n    Queue& q = thread_data_[thread_id].queue;\n    EventCount::Waiter* waiter = &waiters_[thread_id];\n    // TODO(dvyukov,rmlarsen): The time spent in NonEmptyQueueIndex() is\n    // proportional to num_threads_ and we assume that new work is scheduled at\n    // a constant rate, so we set spin_count to 5000 / num_threads_. The\n    // constant was picked based on a fair dice roll, tune it.\n    const int spin_count =\n        allow_spinning_ && num_threads_ > 0 ? 5000 / num_threads_ : 0;\n    if (num_threads_ == 1) {\n      // For num_threads_ == 1 there is no point in going through the expensive\n      // steal loop. Moreover, since NonEmptyQueueIndex() calls PopBack() on the\n      // victim queues it might reverse the order in which ops are executed\n      // compared to the order in which they are scheduled, which tends to be\n      // counter-productive for the types of I/O workloads the single thread\n      // pools tend to be used for.\n      while (!cancelled_) {\n        Task t = q.PopFront();\n        for (int i = 0; i < spin_count && !t.f; i++) {\n          if (!cancelled_.load(std::memory_order_relaxed)) {\n            t = q.PopFront();\n          }\n        }\n        if (!t.f) {\n          if (!WaitForWork(waiter, &t)) {\n            return;\n          }\n        }\n        if (t.f) {\n          env_.ExecuteTask(t);\n        }\n      }\n    } else {\n      while (!cancelled_) {\n        Task t = q.PopFront();\n        if (!t.f) {\n          t = LocalSteal();\n          if (!t.f) {\n            t = GlobalSteal();\n            if (!t.f) {\n              // Leave one thread spinning. This reduces latency.\n              if (allow_spinning_ && !spinning_ && !spinning_.exchange(true)) {\n                for (int i = 0; i < spin_count && !t.f; i++) {\n                  if (!cancelled_.load(std::memory_order_relaxed)) {\n                    t = GlobalSteal();\n                  } else {\n                    return;\n                  }\n                }\n                spinning_ = false;\n              }\n              if (!t.f) {\n                if (!WaitForWork(waiter, &t)) {\n                  return;\n                }\n              }\n            }\n          }\n        }\n        if (t.f) {\n          env_.ExecuteTask(t);\n        }\n      }\n    }\n  }\n\n  // Steal tries to steal work from other worker threads in the range [start,\n  // limit) in best-effort manner.\n  Task Steal(unsigned start, unsigned limit) {\n    PerThread* pt = GetPerThread();\n    const size_t size = limit - start;\n    unsigned r = Rand(&pt->rand);\n    // Reduce r into [0, size) range, this utilizes trick from\n    // https://lemire.me/blog/2016/06/27/a-fast-alternative-to-the-modulo-reduction/\n    eigen_plain_assert(all_coprimes_[size - 1].size() < (1<<30));\n    unsigned victim = ((uint64_t)r * (uint64_t)size) >> 32;\n    unsigned index = ((uint64_t) all_coprimes_[size - 1].size() * (uint64_t)r) >> 32;\n    unsigned inc = all_coprimes_[size - 1][index];\n\n    for (unsigned i = 0; i < size; i++) {\n      eigen_plain_assert(start + victim < limit);\n      Task t = thread_data_[start + victim].queue.PopBack();\n      if (t.f) {\n        return t;\n      }\n      victim += inc;\n      if (victim >= size) {\n        victim -= size;\n      }\n    }\n    return Task();\n  }\n\n  // Steals work within threads belonging to the partition.\n  Task LocalSteal() {\n    PerThread* pt = GetPerThread();\n    unsigned partition = GetStealPartition(pt->thread_id);\n    // If thread steal partition is the same as global partition, there is no\n    // need to go through the steal loop twice.\n    if (global_steal_partition_ == partition) return Task();\n    unsigned start, limit;\n    DecodePartition(partition, &start, &limit);\n    AssertBounds(start, limit);\n\n    return Steal(start, limit);\n  }\n\n  // Steals work from any other thread in the pool.\n  Task GlobalSteal() {\n    return Steal(0, num_threads_);\n  }\n\n\n  // WaitForWork blocks until new work is available (returns true), or if it is\n  // time to exit (returns false). Can optionally return a task to execute in t\n  // (in such case t.f != nullptr on return).\n  bool WaitForWork(EventCount::Waiter* waiter, Task* t) {\n    eigen_plain_assert(!t->f);\n    // We already did best-effort emptiness check in Steal, so prepare for\n    // blocking.\n    ec_.Prewait();\n    // Now do a reliable emptiness check.\n    int victim = NonEmptyQueueIndex();\n    if (victim != -1) {\n      ec_.CancelWait();\n      if (cancelled_) {\n        return false;\n      } else {\n        *t = thread_data_[victim].queue.PopBack();\n        return true;\n      }\n    }\n    // Number of blocked threads is used as termination condition.\n    // If we are shutting down and all worker threads blocked without work,\n    // that's we are done.\n    blocked_++;\n    // TODO is blocked_ required to be unsigned?\n    if (done_ && blocked_ == static_cast<unsigned>(num_threads_)) {\n      ec_.CancelWait();\n      // Almost done, but need to re-check queues.\n      // Consider that all queues are empty and all worker threads are preempted\n      // right after incrementing blocked_ above. Now a free-standing thread\n      // submits work and calls destructor (which sets done_). If we don't\n      // re-check queues, we will exit leaving the work unexecuted.\n      if (NonEmptyQueueIndex() != -1) {\n        // Note: we must not pop from queues before we decrement blocked_,\n        // otherwise the following scenario is possible. Consider that instead\n        // of checking for emptiness we popped the only element from queues.\n        // Now other worker threads can start exiting, which is bad if the\n        // work item submits other work. So we just check emptiness here,\n        // which ensures that all worker threads exit at the same time.\n        blocked_--;\n        return true;\n      }\n      // Reached stable termination state.\n      ec_.Notify(true);\n      return false;\n    }\n    ec_.CommitWait(waiter);\n    blocked_--;\n    return true;\n  }\n\n  int NonEmptyQueueIndex() {\n    PerThread* pt = GetPerThread();\n    // We intentionally design NonEmptyQueueIndex to steal work from\n    // anywhere in the queue so threads don't block in WaitForWork() forever\n    // when all threads in their partition go to sleep. Steal is still local.\n    const size_t size = thread_data_.size();\n    unsigned r = Rand(&pt->rand);\n    unsigned inc = all_coprimes_[size - 1][r % all_coprimes_[size - 1].size()];\n    unsigned victim = r % size;\n    for (unsigned i = 0; i < size; i++) {\n      if (!thread_data_[victim].queue.Empty()) {\n        return victim;\n      }\n      victim += inc;\n      if (victim >= size) {\n        victim -= size;\n      }\n    }\n    return -1;\n  }\n\n  static EIGEN_STRONG_INLINE uint64_t GlobalThreadIdHash() {\n    return std::hash<std::thread::id>()(std::this_thread::get_id());\n  }\n\n  EIGEN_STRONG_INLINE PerThread* GetPerThread() {\n#ifndef EIGEN_THREAD_LOCAL\n    static PerThread dummy;\n    auto it = per_thread_map_.find(GlobalThreadIdHash());\n    if (it == per_thread_map_.end()) {\n      return &dummy;\n    } else {\n      return it->second.get();\n    }\n#else\n    EIGEN_THREAD_LOCAL PerThread per_thread_;\n    PerThread* pt = &per_thread_;\n    return pt;\n#endif\n  }\n\n  static EIGEN_STRONG_INLINE unsigned Rand(uint64_t* state) {\n    uint64_t current = *state;\n    // Update the internal state\n    *state = current * 6364136223846793005ULL + 0xda3e39cb94b95bdbULL;\n    // Generate the random output (using the PCG-XSH-RS scheme)\n    return static_cast<unsigned>((current ^ (current >> 22)) >>\n                                 (22 + (current >> 61)));\n  }\n};\n\ntypedef ThreadPoolTempl<StlThreadEnvironment> ThreadPool;\n\n}  // namespace Eigen\n\n#endif  // EIGEN_CXX11_THREADPOOL_NONBLOCKING_THREAD_POOL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/ThreadPool/RunQueue.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Dmitry Vyukov <dvyukov@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_THREADPOOL_RUNQUEUE_H_\n#define EIGEN_CXX11_THREADPOOL_RUNQUEUE_H_\n\nnamespace Eigen {\n\n// RunQueue is a fixed-size, partially non-blocking deque or Work items.\n// Operations on front of the queue must be done by a single thread (owner),\n// operations on back of the queue can be done by multiple threads concurrently.\n//\n// Algorithm outline:\n// All remote threads operating on the queue back are serialized by a mutex.\n// This ensures that at most two threads access state: owner and one remote\n// thread (Size aside). The algorithm ensures that the occupied region of the\n// underlying array is logically continuous (can wraparound, but no stray\n// occupied elements). Owner operates on one end of this region, remote thread\n// operates on the other end. Synchronization between these threads\n// (potential consumption of the last element and take up of the last empty\n// element) happens by means of state variable in each element. States are:\n// empty, busy (in process of insertion of removal) and ready. Threads claim\n// elements (empty->busy and ready->busy transitions) by means of a CAS\n// operation. The finishing transition (busy->empty and busy->ready) are done\n// with plain store as the element is exclusively owned by the current thread.\n//\n// Note: we could permit only pointers as elements, then we would not need\n// separate state variable as null/non-null pointer value would serve as state,\n// but that would require malloc/free per operation for large, complex values\n// (and this is designed to store std::function<()>).\ntemplate <typename Work, unsigned kSize>\nclass RunQueue {\n public:\n  RunQueue() : front_(0), back_(0) {\n    // require power-of-two for fast masking\n    eigen_plain_assert((kSize & (kSize - 1)) == 0);\n    eigen_plain_assert(kSize > 2);            // why would you do this?\n    eigen_plain_assert(kSize <= (64 << 10));  // leave enough space for counter\n    for (unsigned i = 0; i < kSize; i++)\n      array_[i].state.store(kEmpty, std::memory_order_relaxed);\n  }\n\n  ~RunQueue() { eigen_plain_assert(Size() == 0); }\n\n  // PushFront inserts w at the beginning of the queue.\n  // If queue is full returns w, otherwise returns default-constructed Work.\n  Work PushFront(Work w) {\n    unsigned front = front_.load(std::memory_order_relaxed);\n    Elem* e = &array_[front & kMask];\n    uint8_t s = e->state.load(std::memory_order_relaxed);\n    if (s != kEmpty ||\n        !e->state.compare_exchange_strong(s, kBusy, std::memory_order_acquire))\n      return w;\n    front_.store(front + 1 + (kSize << 1), std::memory_order_relaxed);\n    e->w = std::move(w);\n    e->state.store(kReady, std::memory_order_release);\n    return Work();\n  }\n\n  // PopFront removes and returns the first element in the queue.\n  // If the queue was empty returns default-constructed Work.\n  Work PopFront() {\n    unsigned front = front_.load(std::memory_order_relaxed);\n    Elem* e = &array_[(front - 1) & kMask];\n    uint8_t s = e->state.load(std::memory_order_relaxed);\n    if (s != kReady ||\n        !e->state.compare_exchange_strong(s, kBusy, std::memory_order_acquire))\n      return Work();\n    Work w = std::move(e->w);\n    e->state.store(kEmpty, std::memory_order_release);\n    front = ((front - 1) & kMask2) | (front & ~kMask2);\n    front_.store(front, std::memory_order_relaxed);\n    return w;\n  }\n\n  // PushBack adds w at the end of the queue.\n  // If queue is full returns w, otherwise returns default-constructed Work.\n  Work PushBack(Work w) {\n    std::unique_lock<std::mutex> lock(mutex_);\n    unsigned back = back_.load(std::memory_order_relaxed);\n    Elem* e = &array_[(back - 1) & kMask];\n    uint8_t s = e->state.load(std::memory_order_relaxed);\n    if (s != kEmpty ||\n        !e->state.compare_exchange_strong(s, kBusy, std::memory_order_acquire))\n      return w;\n    back = ((back - 1) & kMask2) | (back & ~kMask2);\n    back_.store(back, std::memory_order_relaxed);\n    e->w = std::move(w);\n    e->state.store(kReady, std::memory_order_release);\n    return Work();\n  }\n\n  // PopBack removes and returns the last elements in the queue.\n  Work PopBack() {\n    if (Empty()) return Work();\n    std::unique_lock<std::mutex> lock(mutex_);\n    unsigned back = back_.load(std::memory_order_relaxed);\n    Elem* e = &array_[back & kMask];\n    uint8_t s = e->state.load(std::memory_order_relaxed);\n    if (s != kReady ||\n        !e->state.compare_exchange_strong(s, kBusy, std::memory_order_acquire))\n      return Work();\n    Work w = std::move(e->w);\n    e->state.store(kEmpty, std::memory_order_release);\n    back_.store(back + 1 + (kSize << 1), std::memory_order_relaxed);\n    return w;\n  }\n\n  // PopBackHalf removes and returns half last elements in the queue.\n  // Returns number of elements removed.\n  unsigned PopBackHalf(std::vector<Work>* result) {\n    if (Empty()) return 0;\n    std::unique_lock<std::mutex> lock(mutex_);\n    unsigned back = back_.load(std::memory_order_relaxed);\n    unsigned size = Size();\n    unsigned mid = back;\n    if (size > 1) mid = back + (size - 1) / 2;\n    unsigned n = 0;\n    unsigned start = 0;\n    for (; static_cast<int>(mid - back) >= 0; mid--) {\n      Elem* e = &array_[mid & kMask];\n      uint8_t s = e->state.load(std::memory_order_relaxed);\n      if (n == 0) {\n        if (s != kReady || !e->state.compare_exchange_strong(\n                               s, kBusy, std::memory_order_acquire))\n          continue;\n        start = mid;\n      } else {\n        // Note: no need to store temporal kBusy, we exclusively own these\n        // elements.\n        eigen_plain_assert(s == kReady);\n      }\n      result->push_back(std::move(e->w));\n      e->state.store(kEmpty, std::memory_order_release);\n      n++;\n    }\n    if (n != 0)\n      back_.store(start + 1 + (kSize << 1), std::memory_order_relaxed);\n    return n;\n  }\n\n  // Size returns current queue size.\n  // Can be called by any thread at any time.\n  unsigned Size() const { return SizeOrNotEmpty<true>(); }\n\n  // Empty tests whether container is empty.\n  // Can be called by any thread at any time.\n  bool Empty() const { return SizeOrNotEmpty<false>() == 0; }\n\n  // Delete all the elements from the queue.\n  void Flush() {\n    while (!Empty()) {\n      PopFront();\n    }\n  }\n\n private:\n  static const unsigned kMask = kSize - 1;\n  static const unsigned kMask2 = (kSize << 1) - 1;\n  struct Elem {\n    std::atomic<uint8_t> state;\n    Work w;\n  };\n  enum {\n    kEmpty,\n    kBusy,\n    kReady,\n  };\n  std::mutex mutex_;\n  // Low log(kSize) + 1 bits in front_ and back_ contain rolling index of\n  // front/back, respectively. The remaining bits contain modification counters\n  // that are incremented on Push operations. This allows us to (1) distinguish\n  // between empty and full conditions (if we would use log(kSize) bits for\n  // position, these conditions would be indistinguishable); (2) obtain\n  // consistent snapshot of front_/back_ for Size operation using the\n  // modification counters.\n  std::atomic<unsigned> front_;\n  std::atomic<unsigned> back_;\n  Elem array_[kSize];\n\n  // SizeOrNotEmpty returns current queue size; if NeedSizeEstimate is false,\n  // only whether the size is 0 is guaranteed to be correct.\n  // Can be called by any thread at any time.\n  template<bool NeedSizeEstimate>\n  unsigned SizeOrNotEmpty() const {\n    // Emptiness plays critical role in thread pool blocking. So we go to great\n    // effort to not produce false positives (claim non-empty queue as empty).\n    unsigned front = front_.load(std::memory_order_acquire);\n    for (;;) {\n      // Capture a consistent snapshot of front/tail.\n      unsigned back = back_.load(std::memory_order_acquire);\n      unsigned front1 = front_.load(std::memory_order_relaxed);\n      if (front != front1) {\n        front = front1;\n        std::atomic_thread_fence(std::memory_order_acquire);\n        continue;\n      }\n      if (NeedSizeEstimate) {\n        return CalculateSize(front, back);\n      } else {\n        // This value will be 0 if the queue is empty, and undefined otherwise.\n        unsigned maybe_zero = ((front ^ back) & kMask2);\n        // Queue size estimate must agree with maybe zero check on the queue\n        // empty/non-empty state.\n        eigen_assert((CalculateSize(front, back) == 0) == (maybe_zero == 0));\n        return maybe_zero;\n      }\n    }\n  }\n\n  EIGEN_ALWAYS_INLINE\n  unsigned CalculateSize(unsigned front, unsigned back) const {\n    int size = (front & kMask2) - (back & kMask2);\n    // Fix overflow.\n    if (size < 0) size += 2 * kSize;\n    // Order of modification in push/pop is crafted to make the queue look\n    // larger than it is during concurrent modifications. E.g. push can\n    // increment size before the corresponding pop has decremented it.\n    // So the computed size can be up to kSize + 1, fix it.\n    if (size > static_cast<int>(kSize)) size = kSize;\n    return static_cast<unsigned>(size);\n  }\n\n  RunQueue(const RunQueue&) = delete;\n  void operator=(const RunQueue&) = delete;\n};\n\n}  // namespace Eigen\n\n#endif  // EIGEN_CXX11_THREADPOOL_RUNQUEUE_H_\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/ThreadPool/ThreadCancel.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_THREADPOOL_THREAD_CANCEL_H\n#define EIGEN_CXX11_THREADPOOL_THREAD_CANCEL_H\n\n// Try to come up with a portable way to cancel a thread\n#if EIGEN_OS_GNULINUX\n  #define EIGEN_THREAD_CANCEL(t)                  \\\n    pthread_cancel(t.native_handle());\n  #define EIGEN_SUPPORTS_THREAD_CANCELLATION 1\n#else\n#define EIGEN_THREAD_CANCEL(t)\n#endif\n\n\n#endif  // EIGEN_CXX11_THREADPOOL_THREAD_CANCEL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/ThreadPool/ThreadEnvironment.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_THREADPOOL_THREAD_ENVIRONMENT_H\n#define EIGEN_CXX11_THREADPOOL_THREAD_ENVIRONMENT_H\n\nnamespace Eigen {\n\nstruct StlThreadEnvironment {\n  struct Task {\n    std::function<void()> f;\n  };\n\n  // EnvThread constructor must start the thread,\n  // destructor must join the thread.\n  class EnvThread {\n   public:\n    EnvThread(std::function<void()> f) : thr_(std::move(f)) {}\n    ~EnvThread() { thr_.join(); }\n    // This function is called when the threadpool is cancelled.\n    void OnCancel() { }\n\n   private:\n    std::thread thr_;\n  };\n\n  EnvThread* CreateThread(std::function<void()> f) { return new EnvThread(std::move(f)); }\n  Task CreateTask(std::function<void()> f) { return Task{std::move(f)}; }\n  void ExecuteTask(const Task& t) { t.f(); }\n};\n\n}  // namespace Eigen\n\n#endif  // EIGEN_CXX11_THREADPOOL_THREAD_ENVIRONMENT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/ThreadPool/ThreadLocal.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_THREADPOOL_THREAD_LOCAL_H\n#define EIGEN_CXX11_THREADPOOL_THREAD_LOCAL_H\n\n#ifdef EIGEN_AVOID_THREAD_LOCAL\n\n#ifdef EIGEN_THREAD_LOCAL\n#undef EIGEN_THREAD_LOCAL\n#endif\n\n#else\n\n#if EIGEN_MAX_CPP_VER >= 11 &&                         \\\n    ((EIGEN_COMP_GNUC && EIGEN_GNUC_AT_LEAST(4, 8)) || \\\n     __has_feature(cxx_thread_local)                || \\\n     (EIGEN_COMP_MSVC >= 1900) )\n#define EIGEN_THREAD_LOCAL static thread_local\n#endif\n\n// Disable TLS for Apple and Android builds with older toolchains.\n#if defined(__APPLE__)\n// Included for TARGET_OS_IPHONE, __IPHONE_OS_VERSION_MIN_REQUIRED,\n// __IPHONE_8_0.\n#include <Availability.h>\n#include <TargetConditionals.h>\n#endif\n// Checks whether C++11's `thread_local` storage duration specifier is\n// supported.\n#if defined(__apple_build_version__) &&     \\\n    ((__apple_build_version__ < 8000042) || \\\n     (TARGET_OS_IPHONE && __IPHONE_OS_VERSION_MIN_REQUIRED < __IPHONE_9_0))\n// Notes: Xcode's clang did not support `thread_local` until version\n// 8, and even then not for all iOS < 9.0.\n#undef EIGEN_THREAD_LOCAL\n\n#elif defined(__ANDROID__) && EIGEN_COMP_CLANG\n// There are platforms for which TLS should not be used even though the compiler\n// makes it seem like it's supported (Android NDK < r12b for example).\n// This is primarily because of linker problems and toolchain misconfiguration:\n// TLS isn't supported until NDK r12b per\n// https://developer.android.com/ndk/downloads/revision_history.html\n// Since NDK r16, `__NDK_MAJOR__` and `__NDK_MINOR__` are defined in\n// <android/ndk-version.h>. For NDK < r16, users should define these macros,\n// e.g. `-D__NDK_MAJOR__=11 -D__NKD_MINOR__=0` for NDK r11.\n#if __has_include(<android/ndk-version.h>)\n#include <android/ndk-version.h>\n#endif  // __has_include(<android/ndk-version.h>)\n#if defined(__ANDROID__) && defined(__clang__) && defined(__NDK_MAJOR__) && \\\n    defined(__NDK_MINOR__) &&                                               \\\n    ((__NDK_MAJOR__ < 12) || ((__NDK_MAJOR__ == 12) && (__NDK_MINOR__ < 1)))\n#undef EIGEN_THREAD_LOCAL\n#endif\n#endif  // defined(__ANDROID__) && defined(__clang__)\n\n#endif  // EIGEN_AVOID_THREAD_LOCAL\n\nnamespace Eigen {\n\nnamespace internal {\ntemplate <typename T>\nstruct ThreadLocalNoOpInitialize {\n  void operator()(T&) const {}\n};\n\ntemplate <typename T>\nstruct ThreadLocalNoOpRelease {\n  void operator()(T&) const {}\n};\n\n}  // namespace internal\n\n// Thread local container for elements of type T, that does not use thread local\n// storage. As long as the number of unique threads accessing this storage\n// is smaller than `capacity_`, it is lock-free and wait-free. Otherwise it will\n// use a mutex for synchronization.\n//\n// Type `T` has to be default constructible, and by default each thread will get\n// a default constructed value. It is possible to specify custom `initialize`\n// callable, that will be called lazily from each thread accessing this object,\n// and will be passed a default initialized object of type `T`. Also it's\n// possible to pass a custom `release` callable, that will be invoked before\n// calling ~T().\n//\n// Example:\n//\n//   struct Counter {\n//     int value = 0;\n//   }\n//\n//   Eigen::ThreadLocal<Counter> counter(10);\n//\n//   // Each thread will have access to it's own counter object.\n//   Counter& cnt = counter.local();\n//   cnt++;\n//\n// WARNING: Eigen::ThreadLocal uses the OS-specific value returned by\n// std::this_thread::get_id() to identify threads. This value is not guaranteed\n// to be unique except for the life of the thread. A newly created thread may\n// get an OS-specific ID equal to that of an already destroyed thread.\n//\n// Somewhat similar to TBB thread local storage, with similar restrictions:\n// https://www.threadingbuildingblocks.org/docs/help/reference/thread_local_storage/enumerable_thread_specific_cls.html\n//\ntemplate <typename T,\n          typename Initialize = internal::ThreadLocalNoOpInitialize<T>,\n          typename Release = internal::ThreadLocalNoOpRelease<T>>\nclass ThreadLocal {\n  // We preallocate default constructed elements in MaxSizedVector.\n  static_assert(std::is_default_constructible<T>::value,\n                \"ThreadLocal data type must be default constructible\");\n\n public:\n  explicit ThreadLocal(int capacity)\n      : ThreadLocal(capacity, internal::ThreadLocalNoOpInitialize<T>(),\n                    internal::ThreadLocalNoOpRelease<T>()) {}\n\n  ThreadLocal(int capacity, Initialize initialize)\n      : ThreadLocal(capacity, std::move(initialize),\n                    internal::ThreadLocalNoOpRelease<T>()) {}\n\n  ThreadLocal(int capacity, Initialize initialize, Release release)\n      : initialize_(std::move(initialize)),\n        release_(std::move(release)),\n        capacity_(capacity),\n        data_(capacity_),\n        ptr_(capacity_),\n        filled_records_(0) {\n    eigen_assert(capacity_ >= 0);\n    data_.resize(capacity_);\n    for (int i = 0; i < capacity_; ++i) {\n      ptr_.emplace_back(nullptr);\n    }\n  }\n\n  T& local() {\n    std::thread::id this_thread = std::this_thread::get_id();\n    if (capacity_ == 0) return SpilledLocal(this_thread);\n\n    std::size_t h = std::hash<std::thread::id>()(this_thread);\n    const int start_idx = h % capacity_;\n\n    // NOTE: From the definition of `std::this_thread::get_id()` it is\n    // guaranteed that we never can have concurrent insertions with the same key\n    // to our hash-map like data structure. If we didn't find an element during\n    // the initial traversal, it's guaranteed that no one else could have\n    // inserted it while we are in this function. This allows to massively\n    // simplify out lock-free insert-only hash map.\n\n    // Check if we already have an element for `this_thread`.\n    int idx = start_idx;\n    while (ptr_[idx].load() != nullptr) {\n      ThreadIdAndValue& record = *(ptr_[idx].load());\n      if (record.thread_id == this_thread) return record.value;\n\n      idx += 1;\n      if (idx >= capacity_) idx -= capacity_;\n      if (idx == start_idx) break;\n    }\n\n    // If we are here, it means that we found an insertion point in lookup\n    // table at `idx`, or we did a full traversal and table is full.\n\n    // If lock-free storage is full, fallback on mutex.\n    if (filled_records_.load() >= capacity_) return SpilledLocal(this_thread);\n\n    // We double check that we still have space to insert an element into a lock\n    // free storage. If old value in `filled_records_` is larger than the\n    // records capacity, it means that some other thread added an element while\n    // we were traversing lookup table.\n    int insertion_index =\n        filled_records_.fetch_add(1, std::memory_order_relaxed);\n    if (insertion_index >= capacity_) return SpilledLocal(this_thread);\n\n    // At this point it's guaranteed that we can access to\n    // data_[insertion_index_] without a data race.\n    data_[insertion_index].thread_id = this_thread;\n    initialize_(data_[insertion_index].value);\n\n    // That's the pointer we'll put into the lookup table.\n    ThreadIdAndValue* inserted = &data_[insertion_index];\n\n    // We'll use nullptr pointer to ThreadIdAndValue in a compare-and-swap loop.\n    ThreadIdAndValue* empty = nullptr;\n\n    // Now we have to find an insertion point into the lookup table. We start\n    // from the `idx` that was identified as an insertion point above, it's\n    // guaranteed that we will have an empty record somewhere in a lookup table\n    // (because we created a record in the `data_`).\n    const int insertion_idx = idx;\n\n    do {\n      // Always start search from the original insertion candidate.\n      idx = insertion_idx;\n      while (ptr_[idx].load() != nullptr) {\n        idx += 1;\n        if (idx >= capacity_) idx -= capacity_;\n        // If we did a full loop, it means that we don't have any free entries\n        // in the lookup table, and this means that something is terribly wrong.\n        eigen_assert(idx != insertion_idx);\n      }\n      // Atomic CAS of the pointer guarantees that any other thread, that will\n      // follow this pointer will see all the mutations in the `data_`.\n    } while (!ptr_[idx].compare_exchange_weak(empty, inserted));\n\n    return inserted->value;\n  }\n\n  // WARN: It's not thread safe to call it concurrently with `local()`.\n  void ForEach(std::function<void(std::thread::id, T&)> f) {\n    // Reading directly from `data_` is unsafe, because only CAS to the\n    // record in `ptr_` makes all changes visible to other threads.\n    for (auto& ptr : ptr_) {\n      ThreadIdAndValue* record = ptr.load();\n      if (record == nullptr) continue;\n      f(record->thread_id, record->value);\n    }\n\n    // We did not spill into the map based storage.\n    if (filled_records_.load(std::memory_order_relaxed) < capacity_) return;\n\n    // Adds a happens before edge from the last call to SpilledLocal().\n    std::unique_lock<std::mutex> lock(mu_);\n    for (auto& kv : per_thread_map_) {\n      f(kv.first, kv.second);\n    }\n  }\n\n  // WARN: It's not thread safe to call it concurrently with `local()`.\n  ~ThreadLocal() {\n    // Reading directly from `data_` is unsafe, because only CAS to the record\n    // in `ptr_` makes all changes visible to other threads.\n    for (auto& ptr : ptr_) {\n      ThreadIdAndValue* record = ptr.load();\n      if (record == nullptr) continue;\n      release_(record->value);\n    }\n\n    // We did not spill into the map based storage.\n    if (filled_records_.load(std::memory_order_relaxed) < capacity_) return;\n\n    // Adds a happens before edge from the last call to SpilledLocal().\n    std::unique_lock<std::mutex> lock(mu_);\n    for (auto& kv : per_thread_map_) {\n      release_(kv.second);\n    }\n  }\n\n private:\n  struct ThreadIdAndValue {\n    std::thread::id thread_id;\n    T value;\n  };\n\n  // Use unordered map guarded by a mutex when lock free storage is full.\n  T& SpilledLocal(std::thread::id this_thread) {\n    std::unique_lock<std::mutex> lock(mu_);\n\n    auto it = per_thread_map_.find(this_thread);\n    if (it == per_thread_map_.end()) {\n      auto result = per_thread_map_.emplace(this_thread, T());\n      eigen_assert(result.second);\n      initialize_((*result.first).second);\n      return (*result.first).second;\n    } else {\n      return it->second;\n    }\n  }\n\n  Initialize initialize_;\n  Release release_;\n  const int capacity_;\n\n  // Storage that backs lock-free lookup table `ptr_`. Records stored in this\n  // storage contiguously starting from index 0.\n  MaxSizeVector<ThreadIdAndValue> data_;\n\n  // Atomic pointers to the data stored in `data_`. Used as a lookup table for\n  // linear probing hash map (https://en.wikipedia.org/wiki/Linear_probing).\n  MaxSizeVector<std::atomic<ThreadIdAndValue*>> ptr_;\n\n  // Number of records stored in the `data_`.\n  std::atomic<int> filled_records_;\n\n  // We fallback on per thread map if lock-free storage is full. In practice\n  // this should never happen, if `capacity_` is a reasonable estimate of the\n  // number of threads running in a system.\n  std::mutex mu_;  // Protects per_thread_map_.\n  std::unordered_map<std::thread::id, T> per_thread_map_;\n};\n\n}  // namespace Eigen\n\n#endif  // EIGEN_CXX11_THREADPOOL_THREAD_LOCAL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/ThreadPool/ThreadPoolInterface.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_THREADPOOL_THREAD_POOL_INTERFACE_H\n#define EIGEN_CXX11_THREADPOOL_THREAD_POOL_INTERFACE_H\n\nnamespace Eigen {\n\n// This defines an interface that ThreadPoolDevice can take to use\n// custom thread pools underneath.\nclass ThreadPoolInterface {\n public:\n  // Submits a closure to be run by a thread in the pool.\n  virtual void Schedule(std::function<void()> fn) = 0;\n\n  // Submits a closure to be run by threads in the range [start, end) in the\n  // pool.\n  virtual void ScheduleWithHint(std::function<void()> fn, int /*start*/,\n                                int /*end*/) {\n    // Just defer to Schedule in case sub-classes aren't interested in\n    // overriding this functionality.\n    Schedule(fn);\n  }\n\n  // If implemented, stop processing the closures that have been enqueued.\n  // Currently running closures may still be processed.\n  // If not implemented, does nothing.\n  virtual void Cancel() {}\n\n  // Returns the number of threads in the pool.\n  virtual int NumThreads() const = 0;\n\n  // Returns a logical thread index between 0 and NumThreads() - 1 if called\n  // from one of the threads in the pool. Returns -1 otherwise.\n  virtual int CurrentThreadId() const = 0;\n\n  virtual ~ThreadPoolInterface() {}\n};\n\n}  // namespace Eigen\n\n#endif  // EIGEN_CXX11_THREADPOOL_THREAD_POOL_INTERFACE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/ThreadPool/ThreadYield.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_THREADPOOL_THREAD_YIELD_H\n#define EIGEN_CXX11_THREADPOOL_THREAD_YIELD_H\n\n// Try to come up with a portable way to yield\n#if EIGEN_COMP_GNUC && EIGEN_GNUC_AT_MOST(4, 7)\n#define EIGEN_THREAD_YIELD() sched_yield()\n#else\n#define EIGEN_THREAD_YIELD() std::this_thread::yield()\n#endif\n\n#endif  // EIGEN_CXX11_THREADPOOL_THREAD_YIELD_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/util/CXX11Meta.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11META_H\n#define EIGEN_CXX11META_H\n\n#include <vector>\n#include \"EmulateArray.h\"\n\n#include \"CXX11Workarounds.h\"\n\nnamespace Eigen {\n\nnamespace internal {\n\n/** \\internal\n  * \\file CXX11/util/CXX11Meta.h\n  * This file contains generic metaprogramming classes which are not specifically related to Eigen.\n  * This file expands upon Core/util/Meta.h and adds support for C++11 specific features.\n  */\n\ntemplate<typename... tt>\nstruct type_list { constexpr static int count = sizeof...(tt); };\n\ntemplate<typename t, typename... tt>\nstruct type_list<t, tt...> { constexpr static int count = sizeof...(tt) + 1; typedef t first_type; };\n\ntemplate<typename T, T... nn>\nstruct numeric_list { constexpr static std::size_t count = sizeof...(nn); };\n\ntemplate<typename T, T n, T... nn>\nstruct numeric_list<T, n, nn...> { static const std::size_t count = sizeof...(nn) + 1; const static T first_value = n; };\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n/* numeric list constructors\n *\n * equivalencies:\n *     constructor                                              result\n *     typename gen_numeric_list<int, 5>::type                  numeric_list<int, 0,1,2,3,4>\n *     typename gen_numeric_list_reversed<int, 5>::type         numeric_list<int, 4,3,2,1,0>\n *     typename gen_numeric_list_swapped_pair<int, 5,1,2>::type numeric_list<int, 0,2,1,3,4>\n *     typename gen_numeric_list_repeated<int, 0, 5>::type      numeric_list<int, 0,0,0,0,0>\n */\n\ntemplate<typename T, std::size_t n, T start = 0, T... ii> struct gen_numeric_list                     : gen_numeric_list<T, n-1, start, start + n-1, ii...> {};\ntemplate<typename T, T start, T... ii>                    struct gen_numeric_list<T, 0, start, ii...> { typedef numeric_list<T, ii...> type; };\n\ntemplate<typename T, std::size_t n, T start = 0, T... ii> struct gen_numeric_list_reversed                     : gen_numeric_list_reversed<T, n-1, start, ii..., start + n-1> {};\ntemplate<typename T, T start, T... ii>                    struct gen_numeric_list_reversed<T, 0, start, ii...> { typedef numeric_list<T, ii...> type; };\n\ntemplate<typename T, std::size_t n, T a, T b, T start = 0, T... ii> struct gen_numeric_list_swapped_pair                           : gen_numeric_list_swapped_pair<T, n-1, a, b, start, (start + n-1) == a ? b : ((start + n-1) == b ? a : (start + n-1)), ii...> {};\ntemplate<typename T, T a, T b, T start, T... ii>                    struct gen_numeric_list_swapped_pair<T, 0, a, b, start, ii...> { typedef numeric_list<T, ii...> type; };\n\ntemplate<typename T, std::size_t n, T V, T... nn> struct gen_numeric_list_repeated                 : gen_numeric_list_repeated<T, n-1, V, V, nn...> {};\ntemplate<typename T, T V, T... nn>                struct gen_numeric_list_repeated<T, 0, V, nn...> { typedef numeric_list<T, nn...> type; };\n\n/* list manipulation: concatenate */\n\ntemplate<class a, class b> struct concat;\n\ntemplate<typename... as, typename... bs> struct concat<type_list<as...>,       type_list<bs...>>        { typedef type_list<as..., bs...> type; };\ntemplate<typename T, T... as, T... bs>   struct concat<numeric_list<T, as...>, numeric_list<T, bs...> > { typedef numeric_list<T, as..., bs...> type; };\n\ntemplate<typename... p> struct mconcat;\ntemplate<typename a>                             struct mconcat<a>           { typedef a type; };\ntemplate<typename a, typename b>                 struct mconcat<a, b>        : concat<a, b> {};\ntemplate<typename a, typename b, typename... cs> struct mconcat<a, b, cs...> : concat<a, typename mconcat<b, cs...>::type> {};\n\n/* list manipulation: extract slices */\n\ntemplate<int n, typename x> struct take;\ntemplate<int n, typename a, typename... as> struct take<n, type_list<a, as...>> : concat<type_list<a>, typename take<n-1, type_list<as...>>::type> {};\ntemplate<int n>                             struct take<n, type_list<>>         { typedef type_list<> type; };\ntemplate<typename a, typename... as>        struct take<0, type_list<a, as...>> { typedef type_list<> type; };\ntemplate<>                                  struct take<0, type_list<>>         { typedef type_list<> type; };\n\ntemplate<typename T, int n, T a, T... as> struct take<n, numeric_list<T, a, as...>> : concat<numeric_list<T, a>, typename take<n-1, numeric_list<T, as...>>::type> {};\ntemplate<typename T, int n>               struct take<n, numeric_list<T>>           { typedef numeric_list<T> type; };\ntemplate<typename T, T a, T... as>        struct take<0, numeric_list<T, a, as...>> { typedef numeric_list<T> type; };\ntemplate<typename T>                      struct take<0, numeric_list<T>>           { typedef numeric_list<T> type; };\n\ntemplate<typename T, int n, T... ii>      struct h_skip_helper_numeric;\ntemplate<typename T, int n, T i, T... ii> struct h_skip_helper_numeric<T, n, i, ii...> : h_skip_helper_numeric<T, n-1, ii...> {};\ntemplate<typename T, T i, T... ii>        struct h_skip_helper_numeric<T, 0, i, ii...> { typedef numeric_list<T, i, ii...> type; };\ntemplate<typename T, int n>               struct h_skip_helper_numeric<T, n>           { typedef numeric_list<T> type; };\ntemplate<typename T>                      struct h_skip_helper_numeric<T, 0>           { typedef numeric_list<T> type; };\n\ntemplate<int n, typename... tt>             struct h_skip_helper_type;\ntemplate<int n, typename t, typename... tt> struct h_skip_helper_type<n, t, tt...> : h_skip_helper_type<n-1, tt...> {};\ntemplate<typename t, typename... tt>        struct h_skip_helper_type<0, t, tt...> { typedef type_list<t, tt...> type; };\ntemplate<int n>                             struct h_skip_helper_type<n>           { typedef type_list<> type; };\ntemplate<>                                  struct h_skip_helper_type<0>           { typedef type_list<> type; };\n#endif //not EIGEN_PARSED_BY_DOXYGEN\n\ntemplate<int n>\nstruct h_skip {\n  template<typename T, T... ii>\n  constexpr static EIGEN_STRONG_INLINE typename h_skip_helper_numeric<T, n, ii...>::type helper(numeric_list<T, ii...>) { return typename h_skip_helper_numeric<T, n, ii...>::type(); }\n  template<typename... tt>\n  constexpr static EIGEN_STRONG_INLINE typename h_skip_helper_type<n, tt...>::type helper(type_list<tt...>) { return typename h_skip_helper_type<n, tt...>::type(); }\n};\n\ntemplate<int n, typename a> struct skip { typedef decltype(h_skip<n>::helper(a())) type; };\n\ntemplate<int start, int count, typename a> struct slice : take<count, typename skip<start, a>::type> {};\n\n/* list manipulation: retrieve single element from list */\n\ntemplate<int n, typename x> struct get;\n\ntemplate<int n, typename a, typename... as>               struct get<n, type_list<a, as...>>   : get<n-1, type_list<as...>> {};\ntemplate<typename a, typename... as>                      struct get<0, type_list<a, as...>>   { typedef a type; };\n\ntemplate<typename T, int n, T a, T... as>                        struct get<n, numeric_list<T, a, as...>>   : get<n-1, numeric_list<T, as...>> {};\ntemplate<typename T, T a, T... as>                               struct get<0, numeric_list<T, a, as...>>   { constexpr static T value = a; };\n\ntemplate<std::size_t n, typename T, T a, T... as> constexpr T       array_get(const numeric_list<T, a, as...>&) {\n   return get<(int)n, numeric_list<T, a, as...>>::value;\n}\n\n/* always get type, regardless of dummy; good for parameter pack expansion */\n\ntemplate<typename T, T dummy, typename t> struct id_numeric  { typedef t type; };\ntemplate<typename dummy, typename t>      struct id_type     { typedef t type; };\n\n/* equality checking, flagged version */\n\ntemplate<typename a, typename b> struct is_same_gf : is_same<a, b> { constexpr static int global_flags = 0; };\n\n/* apply_op to list */\n\ntemplate<\n  bool from_left, // false\n  template<typename, typename> class op,\n  typename additional_param,\n  typename... values\n>\nstruct h_apply_op_helper                                        { typedef type_list<typename op<values, additional_param>::type...> type; };\ntemplate<\n  template<typename, typename> class op,\n  typename additional_param,\n  typename... values\n>\nstruct h_apply_op_helper<true, op, additional_param, values...> { typedef type_list<typename op<additional_param, values>::type...> type; };\n\ntemplate<\n  bool from_left,\n  template<typename, typename> class op,\n  typename additional_param\n>\nstruct h_apply_op\n{\n  template<typename... values>\n  constexpr static typename h_apply_op_helper<from_left, op, additional_param, values...>::type helper(type_list<values...>)\n  { return typename h_apply_op_helper<from_left, op, additional_param, values...>::type(); }\n};\n\ntemplate<\n  template<typename, typename> class op,\n  typename additional_param,\n  typename a\n>\nstruct apply_op_from_left { typedef decltype(h_apply_op<true, op, additional_param>::helper(a())) type; };\n\ntemplate<\n  template<typename, typename> class op,\n  typename additional_param,\n  typename a\n>\nstruct apply_op_from_right { typedef decltype(h_apply_op<false, op, additional_param>::helper(a())) type; };\n\n/* see if an element is in a list */\n\ntemplate<\n  template<typename, typename> class test,\n  typename check_against,\n  typename h_list,\n  bool last_check_positive = false\n>\nstruct contained_in_list;\n\ntemplate<\n  template<typename, typename> class test,\n  typename check_against,\n  typename h_list\n>\nstruct contained_in_list<test, check_against, h_list, true>\n{\n  constexpr static bool value = true;\n};\n\ntemplate<\n  template<typename, typename> class test,\n  typename check_against,\n  typename a,\n  typename... as\n>\nstruct contained_in_list<test, check_against, type_list<a, as...>, false> : contained_in_list<test, check_against, type_list<as...>, test<check_against, a>::value> {};\n\ntemplate<\n  template<typename, typename> class test,\n  typename check_against\n  EIGEN_TPL_PP_SPEC_HACK_DEFC(typename, empty)\n>\nstruct contained_in_list<test, check_against, type_list<EIGEN_TPL_PP_SPEC_HACK_USE(empty)>, false> { constexpr static bool value = false; };\n\n/* see if an element is in a list and check for global flags */\n\ntemplate<\n  template<typename, typename> class test,\n  typename check_against,\n  typename h_list,\n  int default_flags = 0,\n  bool last_check_positive = false,\n  int last_check_flags = default_flags\n>\nstruct contained_in_list_gf;\n\ntemplate<\n  template<typename, typename> class test,\n  typename check_against,\n  typename h_list,\n  int default_flags,\n  int last_check_flags\n>\nstruct contained_in_list_gf<test, check_against, h_list, default_flags, true, last_check_flags>\n{\n  constexpr static bool value = true;\n  constexpr static int global_flags = last_check_flags;\n};\n\ntemplate<\n  template<typename, typename> class test,\n  typename check_against,\n  typename a,\n  typename... as,\n  int default_flags,\n  int last_check_flags\n>\nstruct contained_in_list_gf<test, check_against, type_list<a, as...>, default_flags, false, last_check_flags> : contained_in_list_gf<test, check_against, type_list<as...>, default_flags, test<check_against, a>::value, test<check_against, a>::global_flags> {};\n\ntemplate<\n  template<typename, typename> class test,\n  typename check_against\n  EIGEN_TPL_PP_SPEC_HACK_DEFC(typename, empty),\n  int default_flags,\n  int last_check_flags\n>\nstruct contained_in_list_gf<test, check_against, type_list<EIGEN_TPL_PP_SPEC_HACK_USE(empty)>, default_flags, false, last_check_flags> { constexpr static bool value = false; constexpr static int global_flags = default_flags; };\n\n/* generic reductions */\n\ntemplate<\n  typename Reducer,\n  typename... Ts\n> struct reduce;\n\ntemplate<\n  typename Reducer\n> struct reduce<Reducer>\n{\n  EIGEN_DEVICE_FUNC constexpr static EIGEN_STRONG_INLINE int run() { return Reducer::Identity; }\n};\n\ntemplate<\n  typename Reducer,\n  typename A\n> struct reduce<Reducer, A>\n{\n  EIGEN_DEVICE_FUNC constexpr static EIGEN_STRONG_INLINE A run(A a) { return a; }\n};\n\ntemplate<\n  typename Reducer,\n  typename A,\n  typename... Ts\n> struct reduce<Reducer, A, Ts...>\n{\n  EIGEN_DEVICE_FUNC constexpr static EIGEN_STRONG_INLINE auto run(A a, Ts... ts) -> decltype(Reducer::run(a, reduce<Reducer, Ts...>::run(ts...))) {\n    return Reducer::run(a, reduce<Reducer, Ts...>::run(ts...));\n  }\n};\n\n/* generic binary operations */\n\nstruct sum_op           {\n  template<typename A, typename B> EIGEN_DEVICE_FUNC constexpr static EIGEN_STRONG_INLINE auto run(A a, B b) -> decltype(a + b)   { return a + b;   }\n  static constexpr int Identity = 0;\n};\nstruct product_op       {\n  template<typename A, typename B> EIGEN_DEVICE_FUNC constexpr static EIGEN_STRONG_INLINE auto run(A a, B b) -> decltype(a * b)   { return a * b;   }\n  static constexpr int Identity = 1;\n};\n\nstruct logical_and_op   { template<typename A, typename B> constexpr static EIGEN_STRONG_INLINE auto run(A a, B b) -> decltype(a && b)  { return a && b;  } };\nstruct logical_or_op    { template<typename A, typename B> constexpr static EIGEN_STRONG_INLINE auto run(A a, B b) -> decltype(a || b)  { return a || b;  } };\n\nstruct equal_op         { template<typename A, typename B> constexpr static EIGEN_STRONG_INLINE auto run(A a, B b) -> decltype(a == b)  { return a == b;  } };\nstruct not_equal_op     { template<typename A, typename B> constexpr static EIGEN_STRONG_INLINE auto run(A a, B b) -> decltype(a != b)  { return a != b;  } };\nstruct lesser_op        { template<typename A, typename B> constexpr static EIGEN_STRONG_INLINE auto run(A a, B b) -> decltype(a < b)   { return a < b;   } };\nstruct lesser_equal_op  { template<typename A, typename B> constexpr static EIGEN_STRONG_INLINE auto run(A a, B b) -> decltype(a <= b)  { return a <= b;  } };\nstruct greater_op       { template<typename A, typename B> constexpr static EIGEN_STRONG_INLINE auto run(A a, B b) -> decltype(a > b)   { return a > b;   } };\nstruct greater_equal_op { template<typename A, typename B> constexpr static EIGEN_STRONG_INLINE auto run(A a, B b) -> decltype(a >= b)  { return a >= b;  } };\n\n/* generic unary operations */\n\nstruct not_op                { template<typename A> constexpr static EIGEN_STRONG_INLINE auto run(A a) -> decltype(!a)      { return !a;      } };\nstruct negation_op           { template<typename A> constexpr static EIGEN_STRONG_INLINE auto run(A a) -> decltype(-a)      { return -a;      } };\nstruct greater_equal_zero_op { template<typename A> constexpr static EIGEN_STRONG_INLINE auto run(A a) -> decltype(a >= 0)  { return a >= 0;  } };\n\n\n/* reductions for lists */\n\n// using auto -> return value spec makes ICC 13.0 and 13.1 crash here, so we have to hack it\n// together in front... (13.0 doesn't work with array_prod/array_reduce/... anyway, but 13.1\n// does...\ntemplate<typename... Ts>\nEIGEN_DEVICE_FUNC constexpr EIGEN_STRONG_INLINE decltype(reduce<product_op, Ts...>::run((*((Ts*)0))...)) arg_prod(Ts... ts)\n{\n  return reduce<product_op, Ts...>::run(ts...);\n}\n\ntemplate<typename... Ts>\nconstexpr EIGEN_STRONG_INLINE decltype(reduce<sum_op, Ts...>::run((*((Ts*)0))...)) arg_sum(Ts... ts)\n{\n  return reduce<sum_op, Ts...>::run(ts...);\n}\n\n/* reverse arrays */\n\ntemplate<typename Array, int... n>\nconstexpr EIGEN_STRONG_INLINE Array h_array_reverse(Array arr, numeric_list<int, n...>)\n{\n  return {{array_get<sizeof...(n) - n - 1>(arr)...}};\n}\n\ntemplate<typename T, std::size_t N>\nconstexpr EIGEN_STRONG_INLINE array<T, N> array_reverse(array<T, N> arr)\n{\n  return h_array_reverse(arr, typename gen_numeric_list<int, N>::type());\n}\n\n\n/* generic array reductions */\n\n// can't reuse standard reduce() interface above because Intel's Compiler\n// *really* doesn't like it, so we just reimplement the stuff\n// (start from N - 1 and work down to 0 because specialization for\n// n == N - 1 also doesn't work in Intel's compiler, so it goes into\n// an infinite loop)\ntemplate<typename Reducer, typename T, std::size_t N, std::size_t n = N - 1>\nstruct h_array_reduce {\n  EIGEN_DEVICE_FUNC constexpr static EIGEN_STRONG_INLINE auto run(array<T, N> arr, T identity) -> decltype(Reducer::run(h_array_reduce<Reducer, T, N, n - 1>::run(arr, identity), array_get<n>(arr)))\n  {\n    return Reducer::run(h_array_reduce<Reducer, T, N, n - 1>::run(arr, identity), array_get<n>(arr));\n  }\n};\n\ntemplate<typename Reducer, typename T, std::size_t N>\nstruct h_array_reduce<Reducer, T, N, 0>\n{\n  EIGEN_DEVICE_FUNC constexpr static EIGEN_STRONG_INLINE T run(const array<T, N>& arr, T)\n  {\n    return array_get<0>(arr);\n  }\n};\n\ntemplate<typename Reducer, typename T>\nstruct h_array_reduce<Reducer, T, 0>\n{\n  EIGEN_DEVICE_FUNC constexpr static EIGEN_STRONG_INLINE T run(const array<T, 0>&, T identity)\n  {\n    return identity;\n  }\n};\n\ntemplate<typename Reducer, typename T, std::size_t N>\nEIGEN_DEVICE_FUNC constexpr EIGEN_STRONG_INLINE auto array_reduce(const array<T, N>& arr, T identity) -> decltype(h_array_reduce<Reducer, T, N>::run(arr, identity))\n{\n  return h_array_reduce<Reducer, T, N>::run(arr, identity);\n}\n\n/* standard array reductions */\n\ntemplate<typename T, std::size_t N>\nEIGEN_DEVICE_FUNC constexpr EIGEN_STRONG_INLINE auto array_sum(const array<T, N>& arr) -> decltype(array_reduce<sum_op, T, N>(arr, static_cast<T>(0)))\n{\n  return array_reduce<sum_op, T, N>(arr, static_cast<T>(0));\n}\n\ntemplate<typename T, std::size_t N>\nEIGEN_DEVICE_FUNC constexpr EIGEN_STRONG_INLINE auto array_prod(const array<T, N>& arr) -> decltype(array_reduce<product_op, T, N>(arr, static_cast<T>(1)))\n{\n  return array_reduce<product_op, T, N>(arr, static_cast<T>(1));\n}\n\ntemplate<typename t>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE t array_prod(const std::vector<t>& a) {\n  eigen_assert(a.size() > 0);\n  t prod = 1;\n  for (size_t i = 0; i < a.size(); ++i) { prod *= a[i]; }\n  return prod;\n}\n\n/* zip an array */\n\ntemplate<typename Op, typename A, typename B, std::size_t N, int... n>\nconstexpr EIGEN_STRONG_INLINE array<decltype(Op::run(A(), B())),N> h_array_zip(array<A, N> a, array<B, N> b, numeric_list<int, n...>)\n{\n  return array<decltype(Op::run(A(), B())),N>{{ Op::run(array_get<n>(a), array_get<n>(b))... }};\n}\n\ntemplate<typename Op, typename A, typename B, std::size_t N>\nconstexpr EIGEN_STRONG_INLINE array<decltype(Op::run(A(), B())),N> array_zip(array<A, N> a, array<B, N> b)\n{\n  return h_array_zip<Op>(a, b, typename gen_numeric_list<int, N>::type());\n}\n\n/* zip an array and reduce the result */\n\ntemplate<typename Reducer, typename Op, typename A, typename B, std::size_t N, int... n>\nconstexpr EIGEN_STRONG_INLINE auto h_array_zip_and_reduce(array<A, N> a, array<B, N> b, numeric_list<int, n...>) -> decltype(reduce<Reducer, typename id_numeric<int,n,decltype(Op::run(A(), B()))>::type...>::run(Op::run(array_get<n>(a), array_get<n>(b))...))\n{\n  return reduce<Reducer, typename id_numeric<int,n,decltype(Op::run(A(), B()))>::type...>::run(Op::run(array_get<n>(a), array_get<n>(b))...);\n}\n\ntemplate<typename Reducer, typename Op, typename A, typename B, std::size_t N>\nconstexpr EIGEN_STRONG_INLINE auto array_zip_and_reduce(array<A, N> a, array<B, N> b) -> decltype(h_array_zip_and_reduce<Reducer, Op, A, B, N>(a, b, typename gen_numeric_list<int, N>::type()))\n{\n  return h_array_zip_and_reduce<Reducer, Op, A, B, N>(a, b, typename gen_numeric_list<int, N>::type());\n}\n\n/* apply stuff to an array */\n\ntemplate<typename Op, typename A, std::size_t N, int... n>\nconstexpr EIGEN_STRONG_INLINE array<decltype(Op::run(A())),N> h_array_apply(array<A, N> a, numeric_list<int, n...>)\n{\n  return array<decltype(Op::run(A())),N>{{ Op::run(array_get<n>(a))... }};\n}\n\ntemplate<typename Op, typename A, std::size_t N>\nconstexpr EIGEN_STRONG_INLINE array<decltype(Op::run(A())),N> array_apply(array<A, N> a)\n{\n  return h_array_apply<Op>(a, typename gen_numeric_list<int, N>::type());\n}\n\n/* apply stuff to an array and reduce */\n\ntemplate<typename Reducer, typename Op, typename A, std::size_t N, int... n>\nconstexpr EIGEN_STRONG_INLINE auto h_array_apply_and_reduce(array<A, N> arr, numeric_list<int, n...>) -> decltype(reduce<Reducer, typename id_numeric<int,n,decltype(Op::run(A()))>::type...>::run(Op::run(array_get<n>(arr))...))\n{\n  return reduce<Reducer, typename id_numeric<int,n,decltype(Op::run(A()))>::type...>::run(Op::run(array_get<n>(arr))...);\n}\n\ntemplate<typename Reducer, typename Op, typename A, std::size_t N>\nconstexpr EIGEN_STRONG_INLINE auto array_apply_and_reduce(array<A, N> a) -> decltype(h_array_apply_and_reduce<Reducer, Op, A, N>(a, typename gen_numeric_list<int, N>::type()))\n{\n  return h_array_apply_and_reduce<Reducer, Op, A, N>(a, typename gen_numeric_list<int, N>::type());\n}\n\n/* repeat a value n times (and make an array out of it\n * usage:\n *   array<int, 16> = repeat<16>(42);\n */\n\ntemplate<int n>\nstruct h_repeat\n{\n  template<typename t, int... ii>\n  constexpr static EIGEN_STRONG_INLINE array<t, n> run(t v, numeric_list<int, ii...>)\n  {\n    return {{ typename id_numeric<int, ii, t>::type(v)... }};\n  }\n};\n\ntemplate<int n, typename t>\nconstexpr array<t, n> repeat(t v) { return h_repeat<n>::run(v, typename gen_numeric_list<int, n>::type()); }\n\n/* instantiate a class by a C-style array */\ntemplate<class InstType, typename ArrType, std::size_t N, bool Reverse, typename... Ps>\nstruct h_instantiate_by_c_array;\n\ntemplate<class InstType, typename ArrType, std::size_t N, typename... Ps>\nstruct h_instantiate_by_c_array<InstType, ArrType, N, false, Ps...>\n{\n  static InstType run(ArrType* arr, Ps... args)\n  {\n    return h_instantiate_by_c_array<InstType, ArrType, N - 1, false, Ps..., ArrType>::run(arr + 1, args..., arr[0]);\n  }\n};\n\ntemplate<class InstType, typename ArrType, std::size_t N, typename... Ps>\nstruct h_instantiate_by_c_array<InstType, ArrType, N, true, Ps...>\n{\n  static InstType run(ArrType* arr, Ps... args)\n  {\n    return h_instantiate_by_c_array<InstType, ArrType, N - 1, false, ArrType, Ps...>::run(arr + 1, arr[0], args...);\n  }\n};\n\ntemplate<class InstType, typename ArrType, typename... Ps>\nstruct h_instantiate_by_c_array<InstType, ArrType, 0, false, Ps...>\n{\n  static InstType run(ArrType* arr, Ps... args)\n  {\n    (void)arr;\n    return InstType(args...);\n  }\n};\n\ntemplate<class InstType, typename ArrType, typename... Ps>\nstruct h_instantiate_by_c_array<InstType, ArrType, 0, true, Ps...>\n{\n  static InstType run(ArrType* arr, Ps... args)\n  {\n    (void)arr;\n    return InstType(args...);\n  }\n};\n\ntemplate<class InstType, typename ArrType, std::size_t N, bool Reverse = false>\nInstType instantiate_by_c_array(ArrType* arr)\n{\n  return h_instantiate_by_c_array<InstType, ArrType, N, Reverse>::run(arr);\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11META_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/util/CXX11Workarounds.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11WORKAROUNDS_H\n#define EIGEN_CXX11WORKAROUNDS_H\n\n/* COMPATIBILITY CHECKS\n * (so users of compilers that are too old get some realistic error messages)\n */\n#if defined(__INTEL_COMPILER) && (__INTEL_COMPILER < 1310)\n#error Intel Compiler only supports required C++ features since version 13.1.\n// note that most stuff in principle works with 13.0 but when combining\n// some features, at some point 13.0 will just fail with an internal assertion\n#elif defined(__GNUC__) && !defined(__clang__) && !defined(__INTEL_COMPILER) && (__GNUC__ < 4 || (__GNUC__ == 4 && __GNUC_MINOR__ < 6))\n// G++ < 4.6 by default will continue processing the source files - even if we use #error to make\n// it error out. For this reason, we use the pragma to make sure G++ aborts at the first error\n// it sees. Unfortunately, that is still not our #error directive, but at least the output is\n// short enough the user has a chance to see that the compiler version is not sufficient for\n// the funky template mojo we use.\n#pragma GCC diagnostic error \"-Wfatal-errors\"\n#error GNU C++ Compiler (g++) only supports required C++ features since version 4.6.\n#endif\n\n/* Check that the compiler at least claims to support C++11. It might not be sufficient\n * because the compiler may not implement it correctly, but at least we'll know.\n * On the other hand, visual studio still doesn't claim to support C++11 although it's\n * compliant enugh for our purpose.\n */\n#if (EIGEN_COMP_CXXVER < 11)\n#if defined(__GNUC__) && !defined(__clang__) && !defined(__INTEL_COMPILER)\n#pragma GCC diagnostic error \"-Wfatal-errors\"\n#endif\n#error This library needs at least a C++11 compliant compiler. If you use g++/clang, please enable the -std=c++11 compiler flag. (-std=c++0x on older versions.)\n#endif\n\nnamespace Eigen {\n\nnamespace internal {\n\n/* std::get is only constexpr in C++14, not yet in C++11\n */\n\n\ntemplate<std::size_t I_, class T> constexpr inline T&       array_get(std::vector<T>&       a) { return a[I_]; }\ntemplate<std::size_t I_, class T> constexpr inline T&&      array_get(std::vector<T>&&      a) { return a[I_]; }\ntemplate<std::size_t I_, class T> constexpr inline T const& array_get(std::vector<T> const& a) { return a[I_]; }\n\n/* Suppose you have a template of the form\n * template<typename T> struct X;\n * And you want to specialize it in such a way:\n *    template<typename S1, typename... SN> struct X<Foo<S1, SN...>> { ::: };\n *    template<>                            struct X<Foo<>>          { ::: };\n * This will work in Intel's compiler 13.0, but only to some extent in g++ 4.6, since\n * g++ can only match templates called with parameter packs if the number of template\n * arguments is not a fixed size (so inside the first specialization, referencing\n * X<Foo<Sn...>> will fail in g++). On the other hand, g++ will accept the following:\n *    template<typename S...> struct X<Foo<S...>> { ::: }:\n * as an additional (!) specialization, which will then only match the empty case.\n * But Intel's compiler 13.0 won't accept that, it will only accept the empty syntax,\n * so we have to create a workaround for this.\n */\n#if defined(__GNUC__) && !defined(__INTEL_COMPILER)\n#define EIGEN_TPL_PP_SPEC_HACK_DEF(mt, n)    mt... n\n#define EIGEN_TPL_PP_SPEC_HACK_DEFC(mt, n)   , EIGEN_TPL_PP_SPEC_HACK_DEF(mt, n)\n#define EIGEN_TPL_PP_SPEC_HACK_USE(n)        n...\n#define EIGEN_TPL_PP_SPEC_HACK_USEC(n)       , n...\n#else\n#define EIGEN_TPL_PP_SPEC_HACK_DEF(mt, n)\n#define EIGEN_TPL_PP_SPEC_HACK_DEFC(mt, n)\n#define EIGEN_TPL_PP_SPEC_HACK_USE(n)\n#define EIGEN_TPL_PP_SPEC_HACK_USEC(n)\n#endif\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11WORKAROUNDS_H\n\n/*\n * kate: space-indent on; indent-width 2; mixedindent off; indent-mode cstyle;\n */\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/util/EmulateArray.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_EMULATE_ARRAY_H\n#define EIGEN_EMULATE_ARRAY_H\n\n\n\n// The array class is only available starting with cxx11. Emulate our own here\n// if needed. Beware, msvc still doesn't advertise itself as a c++11 compiler!\n// Moreover, CUDA doesn't support the STL containers, so we use our own instead.\n#if (__cplusplus <= 199711L && EIGEN_COMP_MSVC < 1900) || defined(EIGEN_GPUCC) || defined(EIGEN_AVOID_STL_ARRAY)\n\nnamespace Eigen {\ntemplate <typename T, size_t n> class array {\n public:\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE T& operator[] (size_t index) { eigen_internal_assert(index < size()); return values[index]; }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE const T& operator[] (size_t index) const { eigen_internal_assert(index < size()); return values[index]; }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE T& at(size_t index) { eigen_assert(index < size()); return values[index]; }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE const T& at(size_t index) const { eigen_assert(index < size()); return values[index]; }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE T& front() { return values[0]; }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE const T& front() const { return values[0]; }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE T& back() { return values[n-1]; }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE const T& back() const { return values[n-1]; }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  static std::size_t size() { return n; }\n\n  T values[n];\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array() { }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array(const T& v) {\n    EIGEN_STATIC_ASSERT(n==1, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    values[0] = v;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array(const T& v1, const T& v2) {\n    EIGEN_STATIC_ASSERT(n==2, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    values[0] = v1;\n    values[1] = v2;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array(const T& v1, const T& v2, const T& v3) {\n    EIGEN_STATIC_ASSERT(n==3, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    values[0] = v1;\n    values[1] = v2;\n    values[2] = v3;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array(const T& v1, const T& v2, const T& v3,\n                            const T& v4) {\n    EIGEN_STATIC_ASSERT(n==4, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    values[0] = v1;\n    values[1] = v2;\n    values[2] = v3;\n    values[3] = v4;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array(const T& v1, const T& v2, const T& v3, const T& v4,\n                            const T& v5) {\n    EIGEN_STATIC_ASSERT(n==5, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    values[0] = v1;\n    values[1] = v2;\n    values[2] = v3;\n    values[3] = v4;\n    values[4] = v5;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array(const T& v1, const T& v2, const T& v3, const T& v4,\n                            const T& v5, const T& v6) {\n    EIGEN_STATIC_ASSERT(n==6, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    values[0] = v1;\n    values[1] = v2;\n    values[2] = v3;\n    values[3] = v4;\n    values[4] = v5;\n    values[5] = v6;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array(const T& v1, const T& v2, const T& v3, const T& v4,\n                            const T& v5, const T& v6, const T& v7) {\n    EIGEN_STATIC_ASSERT(n==7, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    values[0] = v1;\n    values[1] = v2;\n    values[2] = v3;\n    values[3] = v4;\n    values[4] = v5;\n    values[5] = v6;\n    values[6] = v7;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array(\n      const T& v1, const T& v2, const T& v3, const T& v4,\n      const T& v5, const T& v6, const T& v7, const T& v8) {\n    EIGEN_STATIC_ASSERT(n==8, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    values[0] = v1;\n    values[1] = v2;\n    values[2] = v3;\n    values[3] = v4;\n    values[4] = v5;\n    values[5] = v6;\n    values[6] = v7;\n    values[7] = v8;\n  }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array(std::initializer_list<T> l) {\n    eigen_assert(l.size() == n);\n    internal::smart_copy(l.begin(), l.end(), values);\n  }\n#endif\n};\n\n\n// Specialize array for zero size\ntemplate <typename T> class array<T, 0> {\n public:\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE T& operator[] (size_t) {\n    eigen_assert(false && \"Can't index a zero size array\");\n    return dummy;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE const T& operator[] (size_t) const {\n    eigen_assert(false && \"Can't index a zero size array\");\n    return dummy;\n  }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE T& front() {\n    eigen_assert(false && \"Can't index a zero size array\");\n    return dummy;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE const T& front() const {\n    eigen_assert(false && \"Can't index a zero size array\");\n    return dummy;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE T& back() {\n    eigen_assert(false && \"Can't index a zero size array\");\n    return dummy;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE const T& back() const {\n    eigen_assert(false && \"Can't index a zero size array\");\n    return dummy;\n  }\n\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE std::size_t size() { return 0; }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array() : dummy() { }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  EIGEN_DEVICE_FUNC array(std::initializer_list<T> l) : dummy() {\n    EIGEN_UNUSED_VARIABLE(l);\n    eigen_assert(l.size() == 0);\n  }\n#endif\n\n private:\n  T dummy;\n};\n\n// Comparison operator\n// Todo: implement !=, <, <=, >,  and >=\ntemplate<class T, std::size_t N>\nEIGEN_DEVICE_FUNC bool operator==(const array<T,N>& lhs, const array<T,N>& rhs) {\n  for (std::size_t i = 0; i < N; ++i) {\n    if (lhs[i] != rhs[i]) {\n      return false;\n    }\n  }\n  return true;\n}\n\n\nnamespace internal {\ntemplate<std::size_t I_, class T, std::size_t N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T& array_get(array<T,N>& a) {\n  return a[I_];\n}\ntemplate<std::size_t I_, class T, std::size_t N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const T& array_get(const array<T,N>& a) {\n  return a[I_];\n}\n\ntemplate<class T, std::size_t N> struct array_size<array<T,N> > {\n  enum { value = N };\n};\ntemplate<class T, std::size_t N> struct array_size<array<T,N>& > {\n  enum { value = N };\n};\ntemplate<class T, std::size_t N> struct array_size<const array<T,N> > {\n  enum { value = N };\n};\ntemplate<class T, std::size_t N> struct array_size<const array<T,N>& > {\n  enum { value = N };\n};\n\n}  // end namespace internal\n}  // end namespace Eigen\n\n#else\n\n// The compiler supports c++11, and we're not targeting cuda: use std::array as Eigen::array\n#include <array>\nnamespace Eigen {\n\ntemplate <typename T, std::size_t N> using array = std::array<T, N>;\n\nnamespace internal {\n/* std::get is only constexpr in C++14, not yet in C++11\n *     - libstdc++ from version 4.7 onwards has it nevertheless,\n *                                          so use that\n *     - libstdc++ older versions: use _M_instance directly\n *     - libc++ all versions so far: use __elems_ directly\n *     - all other libs: use std::get to be portable, but\n *                       this may not be constexpr\n */\n#if defined(__GLIBCXX__) && __GLIBCXX__ < 20120322\n#define STD_GET_ARR_HACK             a._M_instance[I_]\n#elif defined(_LIBCPP_VERSION)\n#define STD_GET_ARR_HACK             a.__elems_[I_]\n#else\n#define STD_GET_ARR_HACK             std::template get<I_, T, N>(a)\n#endif\n\ntemplate<std::size_t I_, class T, std::size_t N> constexpr inline T&       array_get(std::array<T,N>&       a) { return (T&)       STD_GET_ARR_HACK; }\ntemplate<std::size_t I_, class T, std::size_t N> constexpr inline T&&      array_get(std::array<T,N>&&      a) { return (T&&)      STD_GET_ARR_HACK; }\ntemplate<std::size_t I_, class T, std::size_t N> constexpr inline T const& array_get(std::array<T,N> const& a) { return (T const&) STD_GET_ARR_HACK; }\n\n#undef STD_GET_ARR_HACK\n\n}  // end namespace internal\n}  // end namespace Eigen\n\n#endif\n\n#endif  // EIGEN_EMULATE_ARRAY_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/CXX11/src/util/MaxSizeVector.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_FIXEDSIZEVECTOR_H\n#define EIGEN_FIXEDSIZEVECTOR_H\n\nnamespace Eigen {\n\n/** \\class MaxSizeVector\n  * \\ingroup Core\n  *\n  * \\brief The MaxSizeVector class.\n  *\n  * The %MaxSizeVector provides a subset of std::vector functionality.\n  *\n  * The goal is to provide basic std::vector operations when using\n  * std::vector is not an option (e.g. on GPU or when compiling using\n  * FMA/AVX, as this can cause either compilation failures or illegal\n  * instruction failures).\n  *\n  * Beware: The constructors are not API compatible with these of\n  * std::vector.\n  */\ntemplate <typename T>\nclass MaxSizeVector {\n  static const size_t alignment = EIGEN_PLAIN_ENUM_MAX(EIGEN_ALIGNOF(T), sizeof(void*));\n public:\n  // Construct a new MaxSizeVector, reserve n elements.\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  explicit MaxSizeVector(size_t n)\n      : reserve_(n), size_(0),\n        data_(static_cast<T*>(internal::handmade_aligned_malloc(n * sizeof(T), alignment))) {\n  }\n\n  // Construct a new MaxSizeVector, reserve and resize to n.\n  // Copy the init value to all elements.\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  MaxSizeVector(size_t n, const T& init)\n      : reserve_(n), size_(n),\n        data_(static_cast<T*>(internal::handmade_aligned_malloc(n * sizeof(T), alignment))) {\n    size_t i = 0;\n    EIGEN_TRY\n    {\n      for(; i < size_; ++i) { new (&data_[i]) T(init); }\n    }\n    EIGEN_CATCH(...)\n    {\n      // Construction failed, destruct in reverse order:\n      for(; (i+1) > 0; --i) { data_[i-1].~T(); }\n      internal::handmade_aligned_free(data_);\n      EIGEN_THROW;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  ~MaxSizeVector() {\n    for (size_t i = size_; i > 0; --i) {\n      data_[i-1].~T();\n    }\n    internal::handmade_aligned_free(data_);\n  }\n\n  void resize(size_t n) {\n    eigen_assert(n <= reserve_);\n    for (; size_ < n; ++size_) {\n      new (&data_[size_]) T;\n    }\n    for (; size_ > n; --size_) {\n      data_[size_-1].~T();\n    }\n    eigen_assert(size_ == n);\n  }\n\n  // Append new elements (up to reserved size).\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void push_back(const T& t) {\n    eigen_assert(size_ < reserve_);\n    new (&data_[size_++]) T(t);\n  }\n\n  // For C++03 compatibility this only takes one argument\n  template<class X>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void emplace_back(const X& x) {\n    eigen_assert(size_ < reserve_);\n    new (&data_[size_++]) T(x);\n  }\n\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  const T& operator[] (size_t i) const {\n    eigen_assert(i < size_);\n    return data_[i];\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  T& operator[] (size_t i) {\n    eigen_assert(i < size_);\n    return data_[i];\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  T& back() {\n    eigen_assert(size_ > 0);\n    return data_[size_ - 1];\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  const T& back() const {\n    eigen_assert(size_ > 0);\n    return data_[size_ - 1];\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void pop_back() {\n    eigen_assert(size_ > 0);\n    data_[--size_].~T();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  size_t size() const { return size_; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  bool empty() const { return size_ == 0; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  T* data() { return data_; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  const T* data() const { return data_; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  T* begin() { return data_; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  T* end() { return data_ + size_; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  const T* begin() const { return data_; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  const T* end() const { return data_ + size_; }\n\n private:\n  size_t reserve_;\n  size_t size_;\n  T* data_;\n};\n\n}  // namespace Eigen\n\n#endif  // EIGEN_FIXEDSIZEVECTOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/EulerAngles",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Tal Hadad <tal_hd@hotmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_EULERANGLES_MODULE_H\n#define EIGEN_EULERANGLES_MODULE_H\n\n\n#include \"../../Eigen/Core\"\n#include \"../../Eigen/Geometry\"\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\nnamespace Eigen {\n\n/**\n  * \\defgroup EulerAngles_Module EulerAngles module\n  * \\brief This module provides generic euler angles rotation.\n  *\n  * Euler angles are a way to represent 3D rotation.\n  *\n  * In order to use this module in your code, include this header:\n  * \\code\n  * #include <unsupported/Eigen/EulerAngles>\n  * \\endcode\n  *\n  * See \\ref EulerAngles for more information.\n  *\n  */\n\n}\n\n#include \"src/EulerAngles/EulerSystem.h\"\n#include \"src/EulerAngles/EulerAngles.h\"\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_EULERANGLES_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/FFT",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra. \n//\n// Copyright (C) 2009 Mark Borgerding mark a borgerding net\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_FFT_H\n#define EIGEN_FFT_H\n\n#include <complex>\n#include <vector>\n#include <map>\n#include \"../../Eigen/Core\"\n\n\n/**\n  * \\defgroup FFT_Module Fast Fourier Transform module\n  *\n  * \\code\n  * #include <unsupported/Eigen/FFT>\n  * \\endcode\n  *\n  * This module provides Fast Fourier transformation, with a configurable backend\n  * implementation.\n  *\n  * The default implementation is based on kissfft. It is a small, free, and\n  * reasonably efficient default.\n  *\n  * There are currently two implementation backend:\n  *\n  * - fftw (http://www.fftw.org) : faster, GPL -- incompatible with Eigen in LGPL form, bigger code size.\n  * - MKL (http://en.wikipedia.org/wiki/Math_Kernel_Library) : fastest, commercial -- may be incompatible with Eigen in GPL form.\n  *\n  * \\section FFTDesign Design\n  *\n  * The following design decisions were made concerning scaling and\n  * half-spectrum for real FFT.\n  *\n  * The intent is to facilitate generic programming and ease migrating code\n  * from  Matlab/octave.\n  * We think the default behavior of Eigen/FFT should favor correctness and\n  * generality over speed. Of course, the caller should be able to \"opt-out\" from this\n  * behavior and get the speed increase if they want it.\n  *\n  * 1) %Scaling:\n  * Other libraries (FFTW,IMKL,KISSFFT)  do not perform scaling, so there\n  * is a constant gain incurred after the forward&inverse transforms , so \n  * IFFT(FFT(x)) = Kx;  this is done to avoid a vector-by-value multiply.  \n  * The downside is that algorithms that worked correctly in Matlab/octave \n  * don't behave the same way once implemented in C++.\n  *\n  * How Eigen/FFT differs: invertible scaling is performed so IFFT( FFT(x) ) = x. \n  *\n  * 2) Real FFT half-spectrum\n  * Other libraries use only half the frequency spectrum (plus one extra \n  * sample for the Nyquist bin) for a real FFT, the other half is the \n  * conjugate-symmetric of the first half.  This saves them a copy and some \n  * memory.  The downside is the caller needs to have special logic for the \n  * number of bins in complex vs real.\n  *\n  * How Eigen/FFT differs: The full spectrum is returned from the forward \n  * transform.  This facilitates generic template programming by obviating \n  * separate specializations for real vs complex.  On the inverse\n  * transform, only half the spectrum is actually used if the output type is real.\n  */\n \n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n#ifdef EIGEN_FFTW_DEFAULT\n// FFTW: faster, GPL -- incompatible with Eigen in LGPL form, bigger code size\n#  include <fftw3.h>\n#  include \"src/FFT/ei_fftw_impl.h\"\n   namespace Eigen {\n     //template <typename T> typedef struct internal::fftw_impl  default_fft_impl; this does not work\n     template <typename T> struct default_fft_impl : public internal::fftw_impl<T> {};\n   }\n#elif defined EIGEN_MKL_DEFAULT\n// TODO \n// intel Math Kernel Library: fastest, commercial -- may be incompatible with Eigen in GPL form\n#  include \"src/FFT/ei_imklfft_impl.h\"\n   namespace Eigen {\n     template <typename T> struct default_fft_impl : public internal::imklfft_impl {};\n   }\n#else\n// internal::kissfft_impl:  small, free, reasonably efficient default, derived from kissfft\n//\n# include \"src/FFT/ei_kissfft_impl.h\"\n  namespace Eigen {\n     template <typename T> \n       struct default_fft_impl : public internal::kissfft_impl<T> {};\n  }\n#endif\n\nnamespace Eigen {\n\n \n// \ntemplate<typename T_SrcMat,typename T_FftIfc> struct fft_fwd_proxy;\ntemplate<typename T_SrcMat,typename T_FftIfc> struct fft_inv_proxy;\n\nnamespace internal {\ntemplate<typename T_SrcMat,typename T_FftIfc>\nstruct traits< fft_fwd_proxy<T_SrcMat,T_FftIfc> >\n{\n  typedef typename T_SrcMat::PlainObject ReturnType;\n};\ntemplate<typename T_SrcMat,typename T_FftIfc>\nstruct traits< fft_inv_proxy<T_SrcMat,T_FftIfc> >\n{\n  typedef typename T_SrcMat::PlainObject ReturnType;\n};\n}\n\ntemplate<typename T_SrcMat,typename T_FftIfc> \nstruct fft_fwd_proxy\n : public ReturnByValue<fft_fwd_proxy<T_SrcMat,T_FftIfc> >\n{\n  typedef DenseIndex Index;\n\n  fft_fwd_proxy(const T_SrcMat& src,T_FftIfc & fft, Index nfft) : m_src(src),m_ifc(fft), m_nfft(nfft) {}\n\n  template<typename T_DestMat> void evalTo(T_DestMat& dst) const;\n\n  Index rows() const { return m_src.rows(); }\n  Index cols() const { return m_src.cols(); }\nprotected:\n  const T_SrcMat & m_src;\n  T_FftIfc & m_ifc;\n  Index m_nfft;\n};\n\ntemplate<typename T_SrcMat,typename T_FftIfc> \nstruct fft_inv_proxy\n : public ReturnByValue<fft_inv_proxy<T_SrcMat,T_FftIfc> >\n{\n  typedef DenseIndex Index;\n\n  fft_inv_proxy(const T_SrcMat& src,T_FftIfc & fft, Index nfft) : m_src(src),m_ifc(fft), m_nfft(nfft) {}\n\n  template<typename T_DestMat> void evalTo(T_DestMat& dst) const;\n\n  Index rows() const { return m_src.rows(); }\n  Index cols() const { return m_src.cols(); }\nprotected:\n  const T_SrcMat & m_src;\n  T_FftIfc & m_ifc;\n  Index m_nfft;\n};\n\n\ntemplate <typename T_Scalar,\n         typename T_Impl=default_fft_impl<T_Scalar> >\nclass FFT\n{\n  public:\n    typedef T_Impl impl_type;\n    typedef DenseIndex Index;\n    typedef typename impl_type::Scalar Scalar;\n    typedef typename impl_type::Complex Complex;\n\n    enum Flag {\n      Default=0, // goof proof\n      Unscaled=1,\n      HalfSpectrum=2,\n      // SomeOtherSpeedOptimization=4\n      Speedy=32767\n    };\n\n    FFT( const impl_type & impl=impl_type() , Flag flags=Default ) :m_impl(impl),m_flag(flags) { }\n\n    inline\n    bool HasFlag(Flag f) const { return (m_flag & (int)f) == f;}\n\n    inline\n    void SetFlag(Flag f) { m_flag |= (int)f;}\n\n    inline\n    void ClearFlag(Flag f) { m_flag &= (~(int)f);}\n\n    inline\n    void fwd( Complex * dst, const Scalar * src, Index nfft)\n    {\n        m_impl.fwd(dst,src,static_cast<int>(nfft));\n        if ( HasFlag(HalfSpectrum) == false)\n          ReflectSpectrum(dst,nfft);\n    }\n\n    inline\n    void fwd( Complex * dst, const Complex * src, Index nfft)\n    {\n        m_impl.fwd(dst,src,static_cast<int>(nfft));\n    }\n\n    /*\n    inline \n    void fwd2(Complex * dst, const Complex * src, int n0,int n1)\n    {\n      m_impl.fwd2(dst,src,n0,n1);\n    }\n    */\n\n    template <typename Input_>\n    inline\n    void fwd( std::vector<Complex> & dst, const std::vector<Input_> & src)\n    {\n      if ( NumTraits<Input_>::IsComplex == 0 && HasFlag(HalfSpectrum) )\n        dst.resize( (src.size()>>1)+1); // half the bins + Nyquist bin\n      else\n        dst.resize(src.size());\n      fwd(&dst[0],&src[0],src.size());\n    }\n\n    template<typename InputDerived, typename ComplexDerived>\n    inline\n    void fwd( MatrixBase<ComplexDerived> & dst, const MatrixBase<InputDerived> & src, Index nfft=-1)\n    {\n      typedef typename ComplexDerived::Scalar dst_type;\n      typedef typename InputDerived::Scalar src_type;\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(InputDerived)\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(ComplexDerived)\n      EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(ComplexDerived,InputDerived) // size at compile-time\n      EIGEN_STATIC_ASSERT((internal::is_same<dst_type, Complex>::value),\n            YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n      EIGEN_STATIC_ASSERT(int(InputDerived::Flags)&int(ComplexDerived::Flags)&DirectAccessBit,\n            THIS_METHOD_IS_ONLY_FOR_EXPRESSIONS_WITH_DIRECT_MEMORY_ACCESS_SUCH_AS_MAP_OR_PLAIN_MATRICES)\n\n      if (nfft<1)\n        nfft = src.size();\n\n      if ( NumTraits< src_type >::IsComplex == 0 && HasFlag(HalfSpectrum) )\n        dst.derived().resize( (nfft>>1)+1);\n      else\n        dst.derived().resize(nfft);\n\n      if ( src.innerStride() != 1 || src.size() < nfft ) {\n        Matrix<src_type,1,Dynamic> tmp;\n        if (src.size()<nfft) {\n          tmp.setZero(nfft);\n          tmp.block(0,0,src.size(),1 ) = src;\n        }else{\n          tmp = src;\n        }\n        fwd( &dst[0],&tmp[0],nfft );\n      }else{\n        fwd( &dst[0],&src[0],nfft );\n      }\n    }\n \n    template<typename InputDerived>\n    inline\n    fft_fwd_proxy< MatrixBase<InputDerived>, FFT<T_Scalar,T_Impl> >\n    fwd( const MatrixBase<InputDerived> & src, Index nfft=-1)\n    {\n      return fft_fwd_proxy< MatrixBase<InputDerived> ,FFT<T_Scalar,T_Impl> >( src, *this,nfft );\n    }\n\n    template<typename InputDerived>\n    inline\n    fft_inv_proxy< MatrixBase<InputDerived>, FFT<T_Scalar,T_Impl> >\n    inv( const MatrixBase<InputDerived> & src, Index nfft=-1)\n    {\n      return  fft_inv_proxy< MatrixBase<InputDerived> ,FFT<T_Scalar,T_Impl> >( src, *this,nfft );\n    }\n\n    inline\n    void inv( Complex * dst, const Complex * src, Index nfft)\n    {\n      m_impl.inv( dst,src,static_cast<int>(nfft) );\n      if ( HasFlag( Unscaled ) == false)\n        scale(dst,Scalar(1./nfft),nfft); // scale the time series\n    }\n\n    inline\n    void inv( Scalar * dst, const Complex * src, Index nfft)\n    {\n      m_impl.inv( dst,src,static_cast<int>(nfft) );\n      if ( HasFlag( Unscaled ) == false)\n        scale(dst,Scalar(1./nfft),nfft); // scale the time series\n    }\n\n    template<typename OutputDerived, typename ComplexDerived>\n    inline\n    void inv( MatrixBase<OutputDerived> & dst, const MatrixBase<ComplexDerived> & src, Index nfft=-1)\n    {\n      typedef typename ComplexDerived::Scalar src_type;\n      typedef typename ComplexDerived::RealScalar real_type;\n      typedef typename OutputDerived::Scalar dst_type;\n      const bool realfft= (NumTraits<dst_type>::IsComplex == 0);\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(OutputDerived)\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(ComplexDerived)\n      EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(ComplexDerived,OutputDerived) // size at compile-time\n      EIGEN_STATIC_ASSERT((internal::is_same<src_type, Complex>::value),\n            YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n      EIGEN_STATIC_ASSERT(int(OutputDerived::Flags)&int(ComplexDerived::Flags)&DirectAccessBit,\n            THIS_METHOD_IS_ONLY_FOR_EXPRESSIONS_WITH_DIRECT_MEMORY_ACCESS_SUCH_AS_MAP_OR_PLAIN_MATRICES)\n\n      if (nfft<1) { //automatic FFT size determination\n        if ( realfft && HasFlag(HalfSpectrum) ) \n          nfft = 2*(src.size()-1); //assume even fft size\n        else\n          nfft = src.size();\n      }\n      dst.derived().resize( nfft );\n\n      // check for nfft that does not fit the input data size\n      Index resize_input= ( realfft && HasFlag(HalfSpectrum) )\n        ? ( (nfft/2+1) - src.size() )\n        : ( nfft - src.size() );\n\n      if ( src.innerStride() != 1 || resize_input ) {\n        // if the vector is strided, then we need to copy it to a packed temporary\n        Matrix<src_type,1,Dynamic> tmp;\n        if ( resize_input ) {\n          size_t ncopy = (std::min)(src.size(),src.size() + resize_input);\n          tmp.setZero(src.size() + resize_input);\n          if ( realfft && HasFlag(HalfSpectrum) ) {\n            // pad at the Nyquist bin\n            tmp.head(ncopy) = src.head(ncopy);\n            tmp(ncopy-1) = real(tmp(ncopy-1)); // enforce real-only Nyquist bin\n          }else{\n            size_t nhead,ntail;\n            nhead = 1+ncopy/2-1; // range  [0:pi)\n            ntail = ncopy/2-1;   // range (-pi:0)\n            tmp.head(nhead) = src.head(nhead);\n            tmp.tail(ntail) = src.tail(ntail);\n            if (resize_input<0) { //shrinking -- create the Nyquist bin as the average of the two bins that fold into it\n              tmp(nhead) = ( src(nfft/2) + src( src.size() - nfft/2 ) )*real_type(.5);\n            }else{ // expanding -- split the old Nyquist bin into two halves\n              tmp(nhead) = src(nhead) * real_type(.5);\n              tmp(tmp.size()-nhead) = tmp(nhead);\n            }\n          }\n        }else{\n          tmp = src;\n        }\n        inv( &dst[0],&tmp[0], nfft);\n      }else{\n        inv( &dst[0],&src[0], nfft);\n      }\n    }\n\n    template <typename Output_>\n    inline\n    void inv( std::vector<Output_> & dst, const std::vector<Complex> & src,Index nfft=-1)\n    {\n      if (nfft<1)\n        nfft = ( NumTraits<Output_>::IsComplex == 0 && HasFlag(HalfSpectrum) ) ? 2*(src.size()-1) : src.size();\n      dst.resize( nfft );\n      inv( &dst[0],&src[0],nfft);\n    }\n\n\n    /*\n    // TODO: multi-dimensional FFTs\n    inline \n    void inv2(Complex * dst, const Complex * src, int n0,int n1)\n    {\n      m_impl.inv2(dst,src,n0,n1);\n      if ( HasFlag( Unscaled ) == false)\n          scale(dst,1./(n0*n1),n0*n1);\n    }\n  */\n\n    inline\n    impl_type & impl() {return m_impl;}\n  private:\n\n    template <typename T_Data>\n    inline\n    void scale(T_Data * x,Scalar s,Index nx)\n    {\n#if 1\n      for (int k=0;k<nx;++k)\n        *x++ *= s;\n#else\n      if ( ((ptrdiff_t)x) & 15 )\n        Matrix<T_Data, Dynamic, 1>::Map(x,nx) *= s;\n      else\n        Matrix<T_Data, Dynamic, 1>::MapAligned(x,nx) *= s;\n         //Matrix<T_Data, Dynamic, Dynamic>::Map(x,nx) * s;\n#endif  \n    }\n\n    inline\n    void ReflectSpectrum(Complex * freq, Index nfft)\n    {\n      // create the implicit right-half spectrum (conjugate-mirror of the left-half)\n      Index nhbins=(nfft>>1)+1;\n      for (Index k=nhbins;k < nfft; ++k )\n        freq[k] = conj(freq[nfft-k]);\n    }\n\n    impl_type m_impl;\n    int m_flag;\n};\n\ntemplate<typename T_SrcMat,typename T_FftIfc> \ntemplate<typename T_DestMat> inline \nvoid fft_fwd_proxy<T_SrcMat,T_FftIfc>::evalTo(T_DestMat& dst) const\n{\n    m_ifc.fwd( dst, m_src, m_nfft);\n}\n\ntemplate<typename T_SrcMat,typename T_FftIfc> \ntemplate<typename T_DestMat> inline \nvoid fft_inv_proxy<T_SrcMat,T_FftIfc>::evalTo(T_DestMat& dst) const\n{\n    m_ifc.inv( dst, m_src, m_nfft);\n}\n\n}\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/IterativeSolvers",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ITERATIVE_SOLVERS_MODULE_H\n#define EIGEN_ITERATIVE_SOLVERS_MODULE_H\n\n#include \"../../Eigen/Sparse\"\n#include \"../../Eigen/Jacobi\"\n#include \"../../Eigen/Householder\"\n\n\n/**\n  * \\defgroup IterativeLinearSolvers_Module Iterative Solvers module\n  * This module aims to provide various iterative linear and non linear solver algorithms.\n  * It currently provides:\n  *  - a constrained conjugate gradient\n  *  - a Householder GMRES implementation\n  *  - an IDR(s) implementation\n  *  - a DGMRES implementation\n  *  - a MINRES implementation\n  *\n  * Choosing the best solver for solving \\c A \\c x = \\c b depends a lot on the preconditioner chosen as well as the properties of \\c A. The following flowchart might help you.\n  * \\dot width=50%\n  * digraph g {\n* node [ fontname=Arial, fontsize=11];\n* edge [ fontname=Helvetica, fontsize=10 ];\n*\tA1[label=\"hermitian\",shape=\"box\"];\n* A2[label=\"positive definite\",shape=\"box\"];\n* CG[shape=\"plaintext\"];\n* A3[label=\"ill conditioned\",shape=\"box\"];\n* A4[label=\"good preconditioner\",shape=\"box\"];\n* A5[label=\"flexible preconditioner\",shape=\"box\"];\n* A6[label=\"strongly indefinite\",shape=\"box\"];\n* A8[label=\"large imaginary eigenvalue\",shape=\"box\"];\n* A7[label=\"large imaginary eigenvalue\",shape=\"box\"];\n*\n* SYMMLQ[shape=\"plaintext\"];\n* MINRES[shape=\"plaintext\"];\n* GCR[shape=\"plaintext\"];\n* GMRES[shape=\"plaintext\"];\n* IDRSTABL[shape=\"plaintext\"];\n* IDRS[shape=\"plaintext\"];\n* BICGSTABL[shape=\"plaintext\"];\n* BICGSTAB[shape=\"plaintext\"];\n*\t\n*\tA1 -> A2 [label=\"yes\"];\n*\tA2 -> CG [label=\"yes\"];\n*\tA2 -> A3 [label=\"no\"];\n*\tA3 -> SYMMLQ [label=\"yes\"];\n*\tA3 -> MINRES [label=\"no\"];\n*\n*\tA1 -> A4 [label=\"no\"];\n*\tA4 -> A5 [label=\"yes\"];\n*\tA5 -> GCR [label=\"yes\"];\n*\tA5 -> GMRES [label=\"no\"];\n*\n*\tA4 -> A6 [label=\"no\"];\n*\tA6 -> A8 [label=\"yes\"];\n*\tA6 -> A7 [label=\"no\"];\n*\tA7 -> BICGSTABL [label=\"yes\"];\n*\tA7 -> BICGSTAB [label=\"no\"];\n*\tA8 -> IDRSTABL [label=\"yes\"];\n*\tA8 -> IDRS [label=\"no\"];\n* }\n  * \\enddot\n  * \\code\n  * #include <unsupported/Eigen/IterativeSolvers>\n  * \\endcode\n  */\n\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n#ifndef EIGEN_MPL2_ONLY\n#include \"src/IterativeSolvers/IterationController.h\"\n#include \"src/IterativeSolvers/ConstrainedConjGrad.h\"\n#endif\n\n#include \"src/IterativeSolvers/IncompleteLU.h\"\n#include \"src/IterativeSolvers/GMRES.h\"\n#include \"src/IterativeSolvers/DGMRES.h\"\n#include \"src/IterativeSolvers/MINRES.h\"\n#include \"src/IterativeSolvers/IDRS.h\"\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n\n#endif // EIGEN_ITERATIVE_SOLVERS_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/KroneckerProduct",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_KRONECKER_PRODUCT_MODULE_H\n#define EIGEN_KRONECKER_PRODUCT_MODULE_H\n\n#include \"../../Eigen/Core\"\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n#include \"../../Eigen/src/SparseCore/SparseUtil.h\"\n\nnamespace Eigen {\n\n/**\n  * \\defgroup KroneckerProduct_Module KroneckerProduct module\n  *\n  * This module contains an experimental Kronecker product implementation.\n  *\n  * \\code\n  * #include <Eigen/KroneckerProduct>\n  * \\endcode\n  */\n\n} // namespace Eigen\n\n#include \"src/KroneckerProduct/KroneckerTensorProduct.h\"\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_KRONECKER_PRODUCT_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/LevenbergMarquardt",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_LEVENBERGMARQUARDT_MODULE\n#define EIGEN_LEVENBERGMARQUARDT_MODULE\n\n// #include <vector>\n\n#include \"../../Eigen/Core\"\n#include \"../../Eigen/Jacobi\"\n#include \"../../Eigen/QR\"\n#include \"NumericalDiff\"\n\n#include \"../../Eigen/SparseQR\"\n\n/**\n  * \\defgroup LevenbergMarquardt_Module Levenberg-Marquardt module\n  *\n  * \\code\n  * #include </Eigen/LevenbergMarquardt>\n  * \\endcode\n  *\n  * \n  */\n\n#include \"../../Eigen/SparseCore\"\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n\n#include \"src/LevenbergMarquardt/LMqrsolv.h\"\n#include \"src/LevenbergMarquardt/LMcovar.h\"\n#include \"src/LevenbergMarquardt/LMpar.h\"\n\n#endif\n\n#include \"src/LevenbergMarquardt/LevenbergMarquardt.h\"\n#include \"src/LevenbergMarquardt/LMonestep.h\"\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_LEVENBERGMARQUARDT_MODULE\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/MPRealSupport",
    "content": "// This file is part of a joint effort between Eigen, a lightweight C++ template library\n// for linear algebra, and MPFR C++, a C++ interface to MPFR library (http://www.holoborodko.com/pavel/)\n//\n// Copyright (C) 2010-2012 Pavel Holoborodko <pavel@holoborodko.com>\n// Copyright (C) 2010 Konstantin Holoborodko <konstantin@holoborodko.com>\n// Copyright (C) 2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MPREALSUPPORT_MODULE_H\n#define EIGEN_MPREALSUPPORT_MODULE_H\n\n#include \"../../Eigen/Core\"\n#include <mpreal.h>\n\nnamespace Eigen {\n  \n/**\n  * \\defgroup MPRealSupport_Module MPFRC++ Support module\n  * \\code\n  * #include <Eigen/MPRealSupport>\n  * \\endcode\n  *\n  * This module provides support for multi precision floating point numbers\n  * via the <a href=\"http://www.holoborodko.com/pavel/mpfr\">MPFR C++</a>\n  * library which itself is built upon <a href=\"http://www.mpfr.org/\">MPFR</a>/<a href=\"http://gmplib.org/\">GMP</a>.\n  *\n  * \\warning MPFR C++ is licensed under the GPL.\n  *\n  * You can find a copy of MPFR C++ that is known to be compatible in the unsupported/test/mpreal folder.\n  *\n  * Here is an example:\n  *\n\\code\n#include <iostream>\n#include <Eigen/MPRealSupport>\n#include <Eigen/LU>\nusing namespace mpfr;\nusing namespace Eigen;\nint main()\n{\n  // set precision to 256 bits (double has only 53 bits)\n  mpreal::set_default_prec(256);\n  // Declare matrix and vector types with multi-precision scalar type\n  typedef Matrix<mpreal,Dynamic,Dynamic>  MatrixXmp;\n  typedef Matrix<mpreal,Dynamic,1>        VectorXmp;\n\n  MatrixXmp A = MatrixXmp::Random(100,100);\n  VectorXmp b = VectorXmp::Random(100);\n\n  // Solve Ax=b using LU\n  VectorXmp x = A.lu().solve(b);\n  std::cout << \"relative error: \" << (A*x - b).norm() / b.norm() << std::endl;\n  return 0;\n}\n\\endcode\n  *\n  */\n\t\n  template<> struct NumTraits<mpfr::mpreal>\n    : GenericNumTraits<mpfr::mpreal>\n  {\n    enum {\n      IsInteger = 0,\n      IsSigned = 1,\n      IsComplex = 0,\n      RequireInitialization = 1,\n      ReadCost = HugeCost,\n      AddCost  = HugeCost,\n      MulCost  = HugeCost\n    };\n\n    typedef mpfr::mpreal Real;\n    typedef mpfr::mpreal NonInteger;\n    \n    static inline Real highest  (long Precision = mpfr::mpreal::get_default_prec()) { return  mpfr::maxval(Precision); }\n    static inline Real lowest   (long Precision = mpfr::mpreal::get_default_prec()) { return -mpfr::maxval(Precision); }\n\n    // Constants\n    static inline Real Pi      (long Precision = mpfr::mpreal::get_default_prec())  { return mpfr::const_pi(Precision);        }\n    static inline Real Euler   (long Precision = mpfr::mpreal::get_default_prec())  { return mpfr::const_euler(Precision);     }\n    static inline Real Log2    (long Precision = mpfr::mpreal::get_default_prec())  { return mpfr::const_log2(Precision);      }\n    static inline Real Catalan (long Precision = mpfr::mpreal::get_default_prec())  { return mpfr::const_catalan(Precision);   }\n\n    static inline Real epsilon (long Precision = mpfr::mpreal::get_default_prec())  { return mpfr::machine_epsilon(Precision); }\n    static inline Real epsilon (const Real& x)                                      { return mpfr::machine_epsilon(x); }\n\n#ifdef MPREAL_HAVE_DYNAMIC_STD_NUMERIC_LIMITS\n    static inline int digits10 (long Precision = mpfr::mpreal::get_default_prec())  { return std::numeric_limits<Real>::digits10(Precision); }\n    static inline int digits10 (const Real& x)                                      { return std::numeric_limits<Real>::digits10(x); }\n    \n    static inline int digits ()               { return std::numeric_limits<Real>::digits(); }\n    static inline int digits (const Real& x)  { return std::numeric_limits<Real>::digits(x); }\n#endif\n\n    static inline Real dummy_precision()\n    {\n      mpfr_prec_t weak_prec = ((mpfr::mpreal::get_default_prec()-1) * 90) / 100;\n      return mpfr::machine_epsilon(weak_prec);\n    }\n  };\n\n  namespace internal {\n\n  template<> inline mpfr::mpreal random<mpfr::mpreal>()\n  {\n    return mpfr::random();\n  }\n\n  template<> inline mpfr::mpreal random<mpfr::mpreal>(const mpfr::mpreal& a, const mpfr::mpreal& b)\n  {\n    return a + (b-a) * random<mpfr::mpreal>();\n  }\n\n  inline bool isMuchSmallerThan(const mpfr::mpreal& a, const mpfr::mpreal& b, const mpfr::mpreal& eps)\n  {\n    return mpfr::abs(a) <= mpfr::abs(b) * eps;\n  }\n\n  inline bool isApprox(const mpfr::mpreal& a, const mpfr::mpreal& b, const mpfr::mpreal& eps)\n  {\n    return mpfr::isEqualFuzzy(a,b,eps);\n  }\n\n  inline bool isApproxOrLessThan(const mpfr::mpreal& a, const mpfr::mpreal& b, const mpfr::mpreal& eps)\n  {\n    return a <= b || mpfr::isEqualFuzzy(a,b,eps);\n  }\n\n  template<> inline long double cast<mpfr::mpreal,long double>(const mpfr::mpreal& x)\n  { return x.toLDouble(); }\n\n  template<> inline double cast<mpfr::mpreal,double>(const mpfr::mpreal& x)\n  { return x.toDouble(); }\n\n  template<> inline long cast<mpfr::mpreal,long>(const mpfr::mpreal& x)\n  { return x.toLong(); }\n\n  template<> inline int cast<mpfr::mpreal,int>(const mpfr::mpreal& x)\n  { return int(x.toLong()); }\n\n  // Specialize GEBP kernel and traits for mpreal (no need for peeling, nor complicated stuff)\n  // This also permits to directly call mpfr's routines and avoid many temporaries produced by mpreal\n    template<>\n    class gebp_traits<mpfr::mpreal, mpfr::mpreal, false, false>\n    {\n    public:\n      typedef mpfr::mpreal ResScalar;\n      enum {\n        Vectorizable = false,\n        LhsPacketSize = 1,\n        RhsPacketSize = 1,\n        ResPacketSize = 1,\n        NumberOfRegisters = 1,\n        nr = 1,\n        mr = 1,\n        LhsProgress = 1,\n        RhsProgress = 1\n      };\n      typedef ResScalar LhsPacket;\n      typedef ResScalar RhsPacket;\n      typedef ResScalar ResPacket;\n      typedef LhsPacket LhsPacket4Packing;\n      \n    };\n\n\n\n    template<typename Index, typename DataMapper, bool ConjugateLhs, bool ConjugateRhs>\n    struct gebp_kernel<mpfr::mpreal,mpfr::mpreal,Index,DataMapper,1,1,ConjugateLhs,ConjugateRhs>\n    {\n      typedef mpfr::mpreal mpreal;\n\n      EIGEN_DONT_INLINE\n      void operator()(const DataMapper& res, const mpreal* blockA, const mpreal* blockB, \n                      Index rows, Index depth, Index cols, const mpreal& alpha,\n                      Index strideA=-1, Index strideB=-1, Index offsetA=0, Index offsetB=0)\n      {\n        if(rows==0 || cols==0 || depth==0)\n          return;\n\n        mpreal  acc1(0,mpfr_get_prec(blockA[0].mpfr_srcptr())),\n                tmp (0,mpfr_get_prec(blockA[0].mpfr_srcptr()));\n\n        if(strideA==-1) strideA = depth;\n        if(strideB==-1) strideB = depth;\n\n        for(Index i=0; i<rows; ++i)\n        {\n          for(Index j=0; j<cols; ++j)\n          {\n            const mpreal *A = blockA + i*strideA + offsetA;\n            const mpreal *B = blockB + j*strideB + offsetB;\n            \n            acc1 = 0;\n            for(Index k=0; k<depth; k++)\n            {\n              mpfr_mul(tmp.mpfr_ptr(), A[k].mpfr_srcptr(), B[k].mpfr_srcptr(), mpreal::get_default_rnd());\n              mpfr_add(acc1.mpfr_ptr(), acc1.mpfr_ptr(), tmp.mpfr_ptr(),  mpreal::get_default_rnd());\n            }\n            \n            mpfr_mul(acc1.mpfr_ptr(), acc1.mpfr_srcptr(), alpha.mpfr_srcptr(), mpreal::get_default_rnd());\n            mpfr_add(res(i,j).mpfr_ptr(), res(i,j).mpfr_srcptr(), acc1.mpfr_srcptr(),  mpreal::get_default_rnd());\n          }\n        }\n      }\n    };\n  } // end namespace internal\n}\n\n#endif // EIGEN_MPREALSUPPORT_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/MatrixFunctions",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Jitse Niesen <jitse@maths.leeds.ac.uk>\n// Copyright (C) 2012 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MATRIX_FUNCTIONS\n#define EIGEN_MATRIX_FUNCTIONS\n\n#include <cfloat>\n#include <list>\n\n#include \"../../Eigen/Core\"\n#include \"../../Eigen/LU\"\n#include \"../../Eigen/Eigenvalues\"\n\n/**\n  * \\defgroup MatrixFunctions_Module Matrix functions module\n  * \\brief This module aims to provide various methods for the computation of\n  * matrix functions. \n  *\n  * To use this module, add \n  * \\code\n  * #include <unsupported/Eigen/MatrixFunctions>\n  * \\endcode\n  * at the start of your source file.\n  *\n  * This module defines the following MatrixBase methods.\n  *  - \\ref matrixbase_cos \"MatrixBase::cos()\", for computing the matrix cosine\n  *  - \\ref matrixbase_cosh \"MatrixBase::cosh()\", for computing the matrix hyperbolic cosine\n  *  - \\ref matrixbase_exp \"MatrixBase::exp()\", for computing the matrix exponential\n  *  - \\ref matrixbase_log \"MatrixBase::log()\", for computing the matrix logarithm\n  *  - \\ref matrixbase_pow \"MatrixBase::pow()\", for computing the matrix power\n  *  - \\ref matrixbase_matrixfunction \"MatrixBase::matrixFunction()\", for computing general matrix functions\n  *  - \\ref matrixbase_sin \"MatrixBase::sin()\", for computing the matrix sine\n  *  - \\ref matrixbase_sinh \"MatrixBase::sinh()\", for computing the matrix hyperbolic sine\n  *  - \\ref matrixbase_sqrt \"MatrixBase::sqrt()\", for computing the matrix square root\n  *\n  * These methods are the main entry points to this module. \n  *\n  * %Matrix functions are defined as follows.  Suppose that \\f$ f \\f$\n  * is an entire function (that is, a function on the complex plane\n  * that is everywhere complex differentiable).  Then its Taylor\n  * series\n  * \\f[ f(0) + f'(0) x + \\frac{f''(0)}{2} x^2 + \\frac{f'''(0)}{3!} x^3 + \\cdots \\f]\n  * converges to \\f$ f(x) \\f$. In this case, we can define the matrix\n  * function by the same series:\n  * \\f[ f(M) = f(0) + f'(0) M + \\frac{f''(0)}{2} M^2 + \\frac{f'''(0)}{3!} M^3 + \\cdots \\f]\n  *\n  */\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n#include \"src/MatrixFunctions/MatrixExponential.h\"\n#include \"src/MatrixFunctions/MatrixFunction.h\"\n#include \"src/MatrixFunctions/MatrixSquareRoot.h\"\n#include \"src/MatrixFunctions/MatrixLogarithm.h\"\n#include \"src/MatrixFunctions/MatrixPower.h\"\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n\n/** \n\\page matrixbaseextra_page\n\\ingroup MatrixFunctions_Module\n\n\\section matrixbaseextra MatrixBase methods defined in the MatrixFunctions module\n\nThe remainder of the page documents the following MatrixBase methods\nwhich are defined in the MatrixFunctions module.\n\n\n\n\\subsection matrixbase_cos MatrixBase::cos()\n\nCompute the matrix cosine.\n\n\\code\nconst MatrixFunctionReturnValue<Derived> MatrixBase<Derived>::cos() const\n\\endcode\n\n\\param[in]  M  a square matrix.\n\\returns  expression representing \\f$ \\cos(M) \\f$.\n\nThis function computes the matrix cosine. Use ArrayBase::cos() for computing the entry-wise cosine.\n\nThe implementation calls \\ref matrixbase_matrixfunction \"matrixFunction()\" with StdStemFunctions::cos().\n\n\\sa \\ref matrixbase_sin \"sin()\" for an example.\n\n\n\n\\subsection matrixbase_cosh MatrixBase::cosh()\n\nCompute the matrix hyberbolic cosine.\n\n\\code\nconst MatrixFunctionReturnValue<Derived> MatrixBase<Derived>::cosh() const\n\\endcode\n\n\\param[in]  M  a square matrix.\n\\returns  expression representing \\f$ \\cosh(M) \\f$\n\nThis function calls \\ref matrixbase_matrixfunction \"matrixFunction()\" with StdStemFunctions::cosh().\n\n\\sa \\ref matrixbase_sinh \"sinh()\" for an example.\n\n\n\n\\subsection matrixbase_exp MatrixBase::exp()\n\nCompute the matrix exponential.\n\n\\code\nconst MatrixExponentialReturnValue<Derived> MatrixBase<Derived>::exp() const\n\\endcode\n\n\\param[in]  M  matrix whose exponential is to be computed.\n\\returns    expression representing the matrix exponential of \\p M.\n\nThe matrix exponential of \\f$ M \\f$ is defined by\n\\f[ \\exp(M) = \\sum_{k=0}^\\infty \\frac{M^k}{k!}. \\f]\nThe matrix exponential can be used to solve linear ordinary\ndifferential equations: the solution of \\f$ y' = My \\f$ with the\ninitial condition \\f$ y(0) = y_0 \\f$ is given by\n\\f$ y(t) = \\exp(M) y_0 \\f$.\n\nThe matrix exponential is different from applying the exp function to all the entries in the matrix.\nUse ArrayBase::exp() if you want to do the latter.\n\nThe cost of the computation is approximately \\f$ 20 n^3 \\f$ for\nmatrices of size \\f$ n \\f$. The number 20 depends weakly on the\nnorm of the matrix.\n\nThe matrix exponential is computed using the scaling-and-squaring\nmethod combined with Pad&eacute; approximation. The matrix is first\nrescaled, then the exponential of the reduced matrix is computed\napproximant, and then the rescaling is undone by repeated\nsquaring. The degree of the Pad&eacute; approximant is chosen such\nthat the approximation error is less than the round-off\nerror. However, errors may accumulate during the squaring phase.\n\nDetails of the algorithm can be found in: Nicholas J. Higham, \"The\nscaling and squaring method for the matrix exponential revisited,\"\n<em>SIAM J. %Matrix Anal. Applic.</em>, <b>26</b>:1179&ndash;1193,\n2005.\n\nExample: The following program checks that\n\\f[ \\exp \\left[ \\begin{array}{ccc}\n      0 & \\frac14\\pi & 0 \\\\\n      -\\frac14\\pi & 0 & 0 \\\\\n      0 & 0 & 0\n    \\end{array} \\right] = \\left[ \\begin{array}{ccc}\n      \\frac12\\sqrt2 & -\\frac12\\sqrt2 & 0 \\\\\n      \\frac12\\sqrt2 & \\frac12\\sqrt2 & 0 \\\\\n      0 & 0 & 1\n    \\end{array} \\right]. \\f]\nThis corresponds to a rotation of \\f$ \\frac14\\pi \\f$ radians around\nthe z-axis.\n\n\\include MatrixExponential.cpp\nOutput: \\verbinclude MatrixExponential.out\n\n\\note \\p M has to be a matrix of \\c float, \\c double, `long double`\n\\c complex<float>, \\c complex<double>, or `complex<long double>` .\n\n\n\\subsection matrixbase_log MatrixBase::log()\n\nCompute the matrix logarithm.\n\n\\code\nconst MatrixLogarithmReturnValue<Derived> MatrixBase<Derived>::log() const\n\\endcode\n\n\\param[in]  M  invertible matrix whose logarithm is to be computed.\n\\returns    expression representing the matrix logarithm root of \\p M.\n\nThe matrix logarithm of \\f$ M \\f$ is a matrix \\f$ X \\f$ such that \n\\f$ \\exp(X) = M \\f$ where exp denotes the matrix exponential. As for\nthe scalar logarithm, the equation \\f$ \\exp(X) = M \\f$ may have\nmultiple solutions; this function returns a matrix whose eigenvalues\nhave imaginary part in the interval \\f$ (-\\pi,\\pi] \\f$.\n\nThe matrix logarithm is different from applying the log function to all the entries in the matrix.\nUse ArrayBase::log() if you want to do the latter.\n\nIn the real case, the matrix \\f$ M \\f$ should be invertible and\nit should have no eigenvalues which are real and negative (pairs of\ncomplex conjugate eigenvalues are allowed). In the complex case, it\nonly needs to be invertible.\n\nThis function computes the matrix logarithm using the Schur-Parlett\nalgorithm as implemented by MatrixBase::matrixFunction(). The\nlogarithm of an atomic block is computed by MatrixLogarithmAtomic,\nwhich uses direct computation for 1-by-1 and 2-by-2 blocks and an\ninverse scaling-and-squaring algorithm for bigger blocks, with the\nsquare roots computed by MatrixBase::sqrt().\n\nDetails of the algorithm can be found in Section 11.6.2 of:\nNicholas J. Higham,\n<em>Functions of Matrices: Theory and Computation</em>,\nSIAM 2008. ISBN 978-0-898716-46-7.\n\nExample: The following program checks that\n\\f[ \\log \\left[ \\begin{array}{ccc} \n      \\frac12\\sqrt2 & -\\frac12\\sqrt2 & 0 \\\\\n      \\frac12\\sqrt2 & \\frac12\\sqrt2 & 0 \\\\\n      0 & 0 & 1\n    \\end{array} \\right] = \\left[ \\begin{array}{ccc}\n      0 & \\frac14\\pi & 0 \\\\ \n      -\\frac14\\pi & 0 & 0 \\\\\n      0 & 0 & 0 \n    \\end{array} \\right]. \\f]\nThis corresponds to a rotation of \\f$ \\frac14\\pi \\f$ radians around\nthe z-axis. This is the inverse of the example used in the\ndocumentation of \\ref matrixbase_exp \"exp()\".\n\n\\include MatrixLogarithm.cpp\nOutput: \\verbinclude MatrixLogarithm.out\n\n\\note \\p M has to be a matrix of \\c float, \\c double, `long\ndouble`, \\c complex<float>, \\c complex<double>, or `complex<long double>`.\n\n\\sa MatrixBase::exp(), MatrixBase::matrixFunction(), \n    class MatrixLogarithmAtomic, MatrixBase::sqrt().\n\n\n\\subsection matrixbase_pow MatrixBase::pow()\n\nCompute the matrix raised to arbitrary real power.\n\n\\code\nconst MatrixPowerReturnValue<Derived> MatrixBase<Derived>::pow(RealScalar p) const\n\\endcode\n\n\\param[in]  M  base of the matrix power, should be a square matrix.\n\\param[in]  p  exponent of the matrix power.\n\nThe matrix power \\f$ M^p \\f$ is defined as \\f$ \\exp(p \\log(M)) \\f$,\nwhere exp denotes the matrix exponential, and log denotes the matrix\nlogarithm. This is different from raising all the entries in the matrix\nto the p-th power. Use ArrayBase::pow() if you want to do the latter.\n\nIf \\p p is complex, the scalar type of \\p M should be the type of \\p\np . \\f$ M^p \\f$ simply evaluates into \\f$ \\exp(p \\log(M)) \\f$.\nTherefore, the matrix \\f$ M \\f$ should meet the conditions to be an\nargument of matrix logarithm.\n\nIf \\p p is real, it is casted into the real scalar type of \\p M. Then\nthis function computes the matrix power using the Schur-Pad&eacute;\nalgorithm as implemented by class MatrixPower. The exponent is split\ninto integral part and fractional part, where the fractional part is\nin the interval \\f$ (-1, 1) \\f$. The main diagonal and the first\nsuper-diagonal is directly computed.\n\nIf \\p M is singular with a semisimple zero eigenvalue and \\p p is\npositive, the Schur factor \\f$ T \\f$ is reordered with Givens\nrotations, i.e.\n\n\\f[ T = \\left[ \\begin{array}{cc}\n      T_1 & T_2 \\\\\n      0   & 0\n    \\end{array} \\right] \\f]\n\nwhere \\f$ T_1 \\f$ is invertible. Then \\f$ T^p \\f$ is given by\n\n\\f[ T^p = \\left[ \\begin{array}{cc}\n      T_1^p & T_1^{-1} T_1^p T_2 \\\\\n      0     & 0\n    \\end{array}. \\right] \\f]\n\n\\warning Fractional power of a matrix with a non-semisimple zero\neigenvalue is not well-defined. We introduce an assertion failure\nagainst inaccurate result, e.g. \\code\n#include <unsupported/Eigen/MatrixFunctions>\n#include <iostream>\n\nint main()\n{\n  Eigen::Matrix4d A;\n  A << 0, 0, 2, 3,\n       0, 0, 4, 5,\n       0, 0, 6, 7,\n       0, 0, 8, 9;\n  std::cout << A.pow(0.37) << std::endl;\n  \n  // The 1 makes eigenvalue 0 non-semisimple.\n  A.coeffRef(0, 1) = 1;\n\n  // This fails if EIGEN_NO_DEBUG is undefined.\n  std::cout << A.pow(0.37) << std::endl;\n\n  return 0;\n}\n\\endcode\n\nDetails of the algorithm can be found in: Nicholas J. Higham and\nLijing Lin, \"A Schur-Pad&eacute; algorithm for fractional powers of a\nmatrix,\" <em>SIAM J. %Matrix Anal. Applic.</em>,\n<b>32(3)</b>:1056&ndash;1078, 2011.\n\nExample: The following program checks that\n\\f[ \\left[ \\begin{array}{ccc}\n      \\cos1 & -\\sin1 & 0 \\\\\n      \\sin1 & \\cos1 & 0 \\\\\n      0 & 0 & 1\n    \\end{array} \\right]^{\\frac14\\pi} = \\left[ \\begin{array}{ccc}\n      \\frac12\\sqrt2 & -\\frac12\\sqrt2 & 0 \\\\\n      \\frac12\\sqrt2 & \\frac12\\sqrt2 & 0 \\\\\n      0 & 0 & 1\n    \\end{array} \\right]. \\f]\nThis corresponds to \\f$ \\frac14\\pi \\f$ rotations of 1 radian around\nthe z-axis.\n\n\\include MatrixPower.cpp\nOutput: \\verbinclude MatrixPower.out\n\nMatrixBase::pow() is user-friendly. However, there are some\ncircumstances under which you should use class MatrixPower directly.\nMatrixPower can save the result of Schur decomposition, so it's\nbetter for computing various powers for the same matrix.\n\nExample:\n\\include MatrixPower_optimal.cpp\nOutput: \\verbinclude MatrixPower_optimal.out\n\n\\note \\p M has to be a matrix of \\c float, \\c double, `long\ndouble`, \\c complex<float>, \\c complex<double>, or\n\\c complex<long double> .\n\n\\sa MatrixBase::exp(), MatrixBase::log(), class MatrixPower.\n\n\n\\subsection matrixbase_matrixfunction MatrixBase::matrixFunction()\n\nCompute a matrix function.\n\n\\code\nconst MatrixFunctionReturnValue<Derived> MatrixBase<Derived>::matrixFunction(typename internal::stem_function<typename internal::traits<Derived>::Scalar>::type f) const\n\\endcode\n\n\\param[in]  M  argument of matrix function, should be a square matrix.\n\\param[in]  f  an entire function; \\c f(x,n) should compute the n-th\nderivative of f at x.\n\\returns  expression representing \\p f applied to \\p M.\n\nSuppose that \\p M is a matrix whose entries have type \\c Scalar. \nThen, the second argument, \\p f, should be a function with prototype\n\\code \nComplexScalar f(ComplexScalar, int) \n\\endcode\nwhere \\c ComplexScalar = \\c std::complex<Scalar> if \\c Scalar is\nreal (e.g., \\c float or \\c double) and \\c ComplexScalar =\n\\c Scalar if \\c Scalar is complex. The return value of \\c f(x,n)\nshould be \\f$ f^{(n)}(x) \\f$, the n-th derivative of f at x.\n\nThis routine uses the algorithm described in:\nPhilip Davies and Nicholas J. Higham, \n\"A Schur-Parlett algorithm for computing matrix functions\", \n<em>SIAM J. %Matrix Anal. Applic.</em>, <b>25</b>:464&ndash;485, 2003.\n\nThe actual work is done by the MatrixFunction class.\n\nExample: The following program checks that\n\\f[ \\exp \\left[ \\begin{array}{ccc} \n      0 & \\frac14\\pi & 0 \\\\ \n      -\\frac14\\pi & 0 & 0 \\\\\n      0 & 0 & 0 \n    \\end{array} \\right] = \\left[ \\begin{array}{ccc}\n      \\frac12\\sqrt2 & -\\frac12\\sqrt2 & 0 \\\\\n      \\frac12\\sqrt2 & \\frac12\\sqrt2 & 0 \\\\\n      0 & 0 & 1\n    \\end{array} \\right]. \\f]\nThis corresponds to a rotation of \\f$ \\frac14\\pi \\f$ radians around\nthe z-axis. This is the same example as used in the documentation\nof \\ref matrixbase_exp \"exp()\".\n\n\\include MatrixFunction.cpp\nOutput: \\verbinclude MatrixFunction.out\n\nNote that the function \\c expfn is defined for complex numbers \n\\c x, even though the matrix \\c A is over the reals. Instead of\n\\c expfn, we could also have used StdStemFunctions::exp:\n\\code\nA.matrixFunction(StdStemFunctions<std::complex<double> >::exp, &B);\n\\endcode\n\n\n\n\\subsection matrixbase_sin MatrixBase::sin()\n\nCompute the matrix sine.\n\n\\code\nconst MatrixFunctionReturnValue<Derived> MatrixBase<Derived>::sin() const\n\\endcode\n\n\\param[in]  M  a square matrix.\n\\returns  expression representing \\f$ \\sin(M) \\f$.\n\nThis function computes the matrix sine. Use ArrayBase::sin() for computing the entry-wise sine.\n\nThe implementation calls \\ref matrixbase_matrixfunction \"matrixFunction()\" with StdStemFunctions::sin().\n\nExample: \\include MatrixSine.cpp\nOutput: \\verbinclude MatrixSine.out\n\n\n\n\\subsection matrixbase_sinh MatrixBase::sinh()\n\nCompute the matrix hyperbolic sine.\n\n\\code\nMatrixFunctionReturnValue<Derived> MatrixBase<Derived>::sinh() const\n\\endcode\n\n\\param[in]  M  a square matrix.\n\\returns  expression representing \\f$ \\sinh(M) \\f$\n\nThis function calls \\ref matrixbase_matrixfunction \"matrixFunction()\" with StdStemFunctions::sinh().\n\nExample: \\include MatrixSinh.cpp\nOutput: \\verbinclude MatrixSinh.out\n\n\n\\subsection matrixbase_sqrt MatrixBase::sqrt()\n\nCompute the matrix square root.\n\n\\code\nconst MatrixSquareRootReturnValue<Derived> MatrixBase<Derived>::sqrt() const\n\\endcode\n\n\\param[in]  M  invertible matrix whose square root is to be computed.\n\\returns    expression representing the matrix square root of \\p M.\n\nThe matrix square root of \\f$ M \\f$ is the matrix \\f$ M^{1/2} \\f$\nwhose square is the original matrix; so if \\f$ S = M^{1/2} \\f$ then\n\\f$ S^2 = M \\f$. This is different from taking the square root of all\nthe entries in the matrix; use ArrayBase::sqrt() if you want to do the\nlatter.\n\nIn the <b>real case</b>, the matrix \\f$ M \\f$ should be invertible and\nit should have no eigenvalues which are real and negative (pairs of\ncomplex conjugate eigenvalues are allowed). In that case, the matrix\nhas a square root which is also real, and this is the square root\ncomputed by this function. \n\nThe matrix square root is computed by first reducing the matrix to\nquasi-triangular form with the real Schur decomposition. The square\nroot of the quasi-triangular matrix can then be computed directly. The\ncost is approximately \\f$ 25 n^3 \\f$ real flops for the real Schur\ndecomposition and \\f$ 3\\frac13 n^3 \\f$ real flops for the remainder\n(though the computation time in practice is likely more than this\nindicates).\n\nDetails of the algorithm can be found in: Nicholas J. Highan,\n\"Computing real square roots of a real matrix\", <em>Linear Algebra\nAppl.</em>, 88/89:405&ndash;430, 1987.\n\nIf the matrix is <b>positive-definite symmetric</b>, then the square\nroot is also positive-definite symmetric. In this case, it is best to\nuse SelfAdjointEigenSolver::operatorSqrt() to compute it.\n\nIn the <b>complex case</b>, the matrix \\f$ M \\f$ should be invertible;\nthis is a restriction of the algorithm. The square root computed by\nthis algorithm is the one whose eigenvalues have an argument in the\ninterval \\f$ (-\\frac12\\pi, \\frac12\\pi] \\f$. This is the usual branch\ncut.\n\nThe computation is the same as in the real case, except that the\ncomplex Schur decomposition is used to reduce the matrix to a\ntriangular matrix. The theoretical cost is the same. Details are in:\n&Aring;ke Bj&ouml;rck and Sven Hammarling, \"A Schur method for the\nsquare root of a matrix\", <em>Linear Algebra Appl.</em>,\n52/53:127&ndash;140, 1983.\n\nExample: The following program checks that the square root of\n\\f[ \\left[ \\begin{array}{cc} \n              \\cos(\\frac13\\pi) & -\\sin(\\frac13\\pi) \\\\\n              \\sin(\\frac13\\pi) & \\cos(\\frac13\\pi)\n    \\end{array} \\right], \\f]\ncorresponding to a rotation over 60 degrees, is a rotation over 30 degrees:\n\\f[ \\left[ \\begin{array}{cc} \n              \\cos(\\frac16\\pi) & -\\sin(\\frac16\\pi) \\\\\n              \\sin(\\frac16\\pi) & \\cos(\\frac16\\pi)\n    \\end{array} \\right]. \\f]\n\n\\include MatrixSquareRoot.cpp\nOutput: \\verbinclude MatrixSquareRoot.out\n\n\\sa class RealSchur, class ComplexSchur, class MatrixSquareRoot,\n    SelfAdjointEigenSolver::operatorSqrt().\n\n*/\n\n#endif // EIGEN_MATRIX_FUNCTIONS\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/MoreVectorization",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MOREVECTORIZATION_MODULE_H\n#define EIGEN_MOREVECTORIZATION_MODULE_H\n\n#include \"../../Eigen/Core\"\n\nnamespace Eigen {\n\n/**\n  * \\defgroup MoreVectorization More vectorization module\n  */\n\n}\n\n#include \"src/MoreVectorization/MathFunctions.h\"\n\n#endif // EIGEN_MOREVECTORIZATION_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/NonLinearOptimization",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_NONLINEAROPTIMIZATION_MODULE\n#define EIGEN_NONLINEAROPTIMIZATION_MODULE\n\n#include <vector>\n\n#include \"../../Eigen/Core\"\n#include \"../../Eigen/Jacobi\"\n#include \"../../Eigen/QR\"\n#include \"NumericalDiff\"\n\n/**\n  * \\defgroup NonLinearOptimization_Module Non linear optimization module\n  *\n  * \\code\n  * #include <unsupported/Eigen/NonLinearOptimization>\n  * \\endcode\n  *\n  * This module provides implementation of two important algorithms in non linear\n  * optimization. In both cases, we consider a system of non linear functions. Of\n  * course, this should work, and even work very well if those functions are\n  * actually linear. But if this is so, you should probably better use other\n  * methods more fitted to this special case.\n  *\n  * One algorithm allows to find a least-squares solution of such a system\n  * (Levenberg-Marquardt algorithm) and the second one is used to find \n  * a zero for the system (Powell hybrid \"dogleg\" method).\n  *\n  * This code is a port of minpack (http://en.wikipedia.org/wiki/MINPACK).\n  * Minpack is a very famous, old, robust and well renowned package, written in\n  * fortran. Those implementations have been carefully tuned, tested, and used\n  * for several decades.\n  *\n  * The original fortran code was automatically translated using f2c (http://en.wikipedia.org/wiki/F2c) in C,\n  * then c++, and then cleaned by several different authors.\n  * The last one of those cleanings being our starting point : \n  * http://devernay.free.fr/hacks/cminpack.html\n  * \n  * Finally, we ported this code to Eigen, creating classes and API\n  * coherent with Eigen. When possible, we switched to Eigen\n  * implementation, such as most linear algebra (vectors, matrices, stable norms).\n  *\n  * Doing so, we were very careful to check the tests we setup at the very\n  * beginning, which ensure that the same results are found.\n  *\n  * \\section Tests Tests\n  * \n  * The tests are placed in the file unsupported/test/NonLinear.cpp.\n  * \n  * There are two kinds of tests : those that come from examples bundled with cminpack.\n  * They guaranty we get the same results as the original algorithms (value for 'x',\n  * for the number of evaluations of the function, and for the number of evaluations\n  * of the Jacobian if ever).\n  * \n  * Other tests were added by myself at the very beginning of the \n  * process and check the results for Levenberg-Marquardt using the reference data \n  * on http://www.itl.nist.gov/div898/strd/nls/nls_main.shtml. Since then i've \n  * carefully checked that the same results were obtained when modifying the\n  * code. Please note that we do not always get the exact same decimals as they do,\n  * but this is ok : they use 128bits float, and we do the tests using the C type 'double',\n  * which is 64 bits on most platforms (x86 and amd64, at least).\n  * I've performed those tests on several other implementations of Levenberg-Marquardt, and\n  * (c)minpack performs VERY well compared to those, both in accuracy and speed.\n  * \n  * The documentation for running the tests is on the wiki\n  * http://eigen.tuxfamily.org/index.php?title=Tests\n  * \n  * \\section API API: overview of methods\n  * \n  * Both algorithms needs a functor computing the Jacobian. It can be computed by\n  * hand, using auto-differentiation (see \\ref AutoDiff_Module), or using numerical\n  * differences (see \\ref NumericalDiff_Module). For instance:\n  *\\code\n  * MyFunc func;\n  * NumericalDiff<MyFunc> func_with_num_diff(func);\n  * LevenbergMarquardt<NumericalDiff<MyFunc> > lm(func_with_num_diff);\n  * \\endcode\n  * For HybridNonLinearSolver, the method solveNumericalDiff() does the above wrapping for\n  * you.\n  * \n  * The methods LevenbergMarquardt.lmder1()/lmdif1()/lmstr1() and \n  * HybridNonLinearSolver.hybrj1()/hybrd1() are specific methods from the original \n  * minpack package that you probably should NOT use until you are porting a code that\n  * was previously using minpack. They just define a 'simple' API with default values \n  * for some parameters.\n  * \n  * All algorithms are provided using two APIs :\n  *     - one where the user inits the algorithm, and uses '*OneStep()' as much as he wants : \n  * this way the caller have control over the steps\n  *     - one where the user just calls a method (optimize() or solve()) which will \n  * handle the loop: init + loop until a stop condition is met. Those are provided for\n  *  convenience.\n  * \n  * As an example, the method LevenbergMarquardt::minimize() is \n  * implemented as follow: \n  * \\code\n  * Status LevenbergMarquardt<FunctorType,Scalar>::minimize(FVectorType  &x, const int mode)\n  * {\n  *     Status status = minimizeInit(x, mode);\n  *     do {\n  *         status = minimizeOneStep(x, mode);\n  *     } while (status==Running);\n  *     return status;\n  * }\n  * \\endcode\n  * \n  * \\section examples Examples\n  * \n  * The easiest way to understand how to use this module is by looking at the many examples in the file\n  * unsupported/test/NonLinearOptimization.cpp.\n  */\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n\n#include \"src/NonLinearOptimization/qrsolv.h\"\n#include \"src/NonLinearOptimization/r1updt.h\"\n#include \"src/NonLinearOptimization/r1mpyq.h\"\n#include \"src/NonLinearOptimization/rwupdt.h\"\n#include \"src/NonLinearOptimization/fdjac1.h\"\n#include \"src/NonLinearOptimization/lmpar.h\"\n#include \"src/NonLinearOptimization/dogleg.h\"\n#include \"src/NonLinearOptimization/covar.h\"\n\n#include \"src/NonLinearOptimization/chkder.h\"\n\n#endif\n\n#include \"src/NonLinearOptimization/HybridNonLinearSolver.h\"\n#include \"src/NonLinearOptimization/LevenbergMarquardt.h\"\n\n\n#endif // EIGEN_NONLINEAROPTIMIZATION_MODULE\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/NumericalDiff",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_NUMERICALDIFF_MODULE\n#define EIGEN_NUMERICALDIFF_MODULE\n\n#include \"../../Eigen/Core\"\n\nnamespace Eigen {\n\n/**\n  * \\defgroup NumericalDiff_Module Numerical differentiation module\n  *\n  * \\code\n  * #include <unsupported/Eigen/NumericalDiff>\n  * \\endcode\n  *\n  * See http://en.wikipedia.org/wiki/Numerical_differentiation\n  *\n  * Warning : this should NOT be confused with automatic differentiation, which\n  * is a different method and has its own module in Eigen : \\ref\n  * AutoDiff_Module.\n  *\n  * Currently only \"Forward\" and \"Central\" schemes are implemented. Those\n  * are basic methods, and there exist some more elaborated way of\n  * computing such approximates. They are implemented using both\n  * proprietary and free software, and usually requires linking to an\n  * external library. It is very easy for you to write a functor\n  * using such software, and the purpose is quite orthogonal to what we\n  * want to achieve with Eigen.\n  *\n  * This is why we will not provide wrappers for every great numerical\n  * differentiation software that exist, but should rather stick with those\n  * basic ones, that still are useful for testing.\n  *\n  * Also, the \\ref NonLinearOptimization_Module needs this in order to\n  * provide full features compatibility with the original (c)minpack\n  * package.\n  *\n  */\n}\n\n//@{\n\n#include \"src/NumericalDiff/NumericalDiff.h\"\n\n//@}\n\n\n#endif // EIGEN_NUMERICALDIFF_MODULE\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/OpenGLSupport",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_OPENGL_MODULE\n#define EIGEN_OPENGL_MODULE\n\n#include \"../../Eigen/Geometry\"\n\n#if defined(__APPLE_CC__)\n  #include <OpenGL/gl.h>\n#else\n  #include <GL/gl.h>\n#endif\n\nnamespace Eigen {\n\n/**\n  * \\defgroup OpenGLSUpport_Module OpenGL Support module\n  *\n  * This module provides wrapper functions for a couple of OpenGL functions\n  * which simplify the way to pass Eigen's object to openGL.\n  * Here is an example:\n  * \n  * \\code\n  * // You need to add path_to_eigen/unsupported to your include path.\n  * #include <Eigen/OpenGLSupport>\n  * // ...\n  * Vector3f x, y;\n  * Matrix3f rot;\n  * \n  * glVertex(y + x * rot);\n  * \n  * Quaternion q;\n  * glRotate(q);\n  * \n  * // ...\n  * \\endcode\n  *\n  */\n//@{\n\n#define EIGEN_GL_FUNC_DECLARATION(FUNC)                                                                             \\\nnamespace internal {                                                                                                \\\n  template< typename XprType,                                                                                       \\\n            typename Scalar = typename XprType::Scalar,                                                             \\\n            int Rows = XprType::RowsAtCompileTime,                                                                  \\\n            int Cols = XprType::ColsAtCompileTime,                                                                  \\\n            bool IsGLCompatible = bool(internal::evaluator<XprType>::Flags&LinearAccessBit)                         \\\n                              && bool(XprType::Flags&DirectAccessBit)                                               \\\n                              && (XprType::IsVectorAtCompileTime || (XprType::Flags&RowMajorBit)==0)>               \\\n  struct EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl);                                                                      \\\n                                                                                                                    \\\n  template<typename XprType, typename Scalar, int Rows, int Cols>                                                   \\\n  struct EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl)<XprType,Scalar,Rows,Cols,false> {                                     \\\n    inline static void run(const XprType& p) {                                                                      \\\n      EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl)<typename plain_matrix_type_column_major<XprType>::type>::run(p); }       \\\n  };                                                                                                                \\\n}                                                                                                                   \\\n                                                                                                                    \\\ntemplate<typename Derived> inline void FUNC(const Eigen::DenseBase<Derived>& p) {                                   \\\n  EIGEN_CAT(EIGEN_CAT(internal::gl_,FUNC),_impl)<Derived>::run(p.derived());                                        \\\n}\n\n\n#define EIGEN_GL_FUNC_SPECIALIZATION_MAT(FUNC,SCALAR,ROWS,COLS,SUFFIX)                                              \\\nnamespace internal {                                                                                                \\\n  template< typename XprType> struct EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl)<XprType, SCALAR, ROWS, COLS, true> {      \\\n    inline static void run(const XprType& p) { FUNC##SUFFIX(p.data()); }                                            \\\n  };                                                                                                                \\\n}\n\n  \n#define EIGEN_GL_FUNC_SPECIALIZATION_VEC(FUNC,SCALAR,SIZE,SUFFIX)                                                   \\\nnamespace internal {                                                                                                \\\n  template< typename XprType> struct EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl)<XprType, SCALAR, SIZE, 1, true> {         \\\n    inline static void run(const XprType& p) { FUNC##SUFFIX(p.data()); }                                            \\\n  };                                                                                                                \\\n  template< typename XprType> struct EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl)<XprType, SCALAR, 1, SIZE, true> {         \\\n    inline static void run(const XprType& p) { FUNC##SUFFIX(p.data()); }                                            \\\n  };                                                                                                                \\\n}\n\n  \nEIGEN_GL_FUNC_DECLARATION       (glVertex)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,int,    2,2iv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,short,  2,2sv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,float,  2,2fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,double, 2,2dv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,int,    3,3iv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,short,  3,3sv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,float,  3,3fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,double, 3,3dv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,int,    4,4iv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,short,  4,4sv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,float,  4,4fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,double, 4,4dv)\n\nEIGEN_GL_FUNC_DECLARATION       (glTexCoord)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,int,    2,2iv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,short,  2,2sv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,float,  2,2fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,double, 2,2dv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,int,    3,3iv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,short,  3,3sv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,float,  3,3fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,double, 3,3dv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,int,    4,4iv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,short,  4,4sv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,float,  4,4fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,double, 4,4dv)\n\nEIGEN_GL_FUNC_DECLARATION       (glColor)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,int,    2,2iv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,short,  2,2sv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,float,  2,2fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,double, 2,2dv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,int,    3,3iv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,short,  3,3sv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,float,  3,3fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,double, 3,3dv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,int,    4,4iv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,short,  4,4sv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,float,  4,4fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,double, 4,4dv)\n\nEIGEN_GL_FUNC_DECLARATION       (glNormal)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glNormal,int,    3,3iv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glNormal,short,  3,3sv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glNormal,float,  3,3fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glNormal,double, 3,3dv)\n\ninline void glScale2fv(const float*  v) { glScalef(v[0], v[1], 1.f);  }\ninline void glScale2dv(const double* v) { glScaled(v[0], v[1], 1.0);  }\ninline void glScale3fv(const float*  v) { glScalef(v[0], v[1], v[2]); }\ninline void glScale3dv(const double* v) { glScaled(v[0], v[1], v[2]); }\n\nEIGEN_GL_FUNC_DECLARATION       (glScale)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glScale,float,  2,2fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glScale,double, 2,2dv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glScale,float,  3,3fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glScale,double, 3,3dv)\n\ntemplate<typename Scalar> void glScale(const UniformScaling<Scalar>& s)  { glScale(Matrix<Scalar,3,1>::Constant(s.factor())); }\n\ninline void glTranslate2fv(const float*  v) { glTranslatef(v[0], v[1], 0.f);  }\ninline void glTranslate2dv(const double* v) { glTranslated(v[0], v[1], 0.0);  }\ninline void glTranslate3fv(const float*  v) { glTranslatef(v[0], v[1], v[2]); }\ninline void glTranslate3dv(const double* v) { glTranslated(v[0], v[1], v[2]); }\n\nEIGEN_GL_FUNC_DECLARATION       (glTranslate)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTranslate,float,  2,2fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTranslate,double, 2,2dv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTranslate,float,  3,3fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTranslate,double, 3,3dv)\n\ntemplate<typename Scalar> void glTranslate(const Translation<Scalar,2>& t)  { glTranslate(t.vector()); }\ntemplate<typename Scalar> void glTranslate(const Translation<Scalar,3>& t)  { glTranslate(t.vector()); }\n\nEIGEN_GL_FUNC_DECLARATION       (glMultMatrix)\nEIGEN_GL_FUNC_SPECIALIZATION_MAT(glMultMatrix,float,  4,4,f)\nEIGEN_GL_FUNC_SPECIALIZATION_MAT(glMultMatrix,double, 4,4,d)\n\ntemplate<typename Scalar> void glMultMatrix(const Transform<Scalar,3,Affine>& t)        { glMultMatrix(t.matrix()); }\ntemplate<typename Scalar> void glMultMatrix(const Transform<Scalar,3,Projective>& t)    { glMultMatrix(t.matrix()); }\ntemplate<typename Scalar> void glMultMatrix(const Transform<Scalar,3,AffineCompact>& t) { glMultMatrix(Transform<Scalar,3,Affine>(t).matrix()); }\n\nEIGEN_GL_FUNC_DECLARATION       (glLoadMatrix)\nEIGEN_GL_FUNC_SPECIALIZATION_MAT(glLoadMatrix,float,  4,4,f)\nEIGEN_GL_FUNC_SPECIALIZATION_MAT(glLoadMatrix,double, 4,4,d)\n\ntemplate<typename Scalar> void glLoadMatrix(const Transform<Scalar,3,Affine>& t)        { glLoadMatrix(t.matrix()); }\ntemplate<typename Scalar> void glLoadMatrix(const Transform<Scalar,3,Projective>& t)    { glLoadMatrix(t.matrix()); }\ntemplate<typename Scalar> void glLoadMatrix(const Transform<Scalar,3,AffineCompact>& t) { glLoadMatrix(Transform<Scalar,3,Affine>(t).matrix()); }\n\ninline void glRotate(const Rotation2D<float>& rot)\n{\n  glRotatef(rot.angle()*180.f/float(EIGEN_PI), 0.f, 0.f, 1.f);\n}\ninline void glRotate(const Rotation2D<double>& rot)\n{\n  glRotated(rot.angle()*180.0/double(EIGEN_PI), 0.0, 0.0, 1.0);\n}\n\ntemplate<typename Derived> void glRotate(const RotationBase<Derived,3>& rot)\n{  \n  Transform<typename Derived::Scalar,3,Projective> tr(rot);\n  glMultMatrix(tr.matrix());\n}\n\n#define EIGEN_GL_MAKE_CONST_const const\n#define EIGEN_GL_MAKE_CONST__ \n#define EIGEN_GL_EVAL(X) X\n\n#define EIGEN_GL_FUNC1_DECLARATION(FUNC,ARG1,CONST)                                                                             \\\nnamespace internal {                                                                                                            \\\n  template< typename XprType,                                                                                                   \\\n            typename Scalar = typename XprType::Scalar,                                                                         \\\n            int Rows = XprType::RowsAtCompileTime,                                                                              \\\n            int Cols = XprType::ColsAtCompileTime,                                                                              \\\n            bool IsGLCompatible = bool(internal::evaluator<XprType>::Flags&LinearAccessBit)                                     \\\n                              && bool(XprType::Flags&DirectAccessBit)                                                           \\\n                              && (XprType::IsVectorAtCompileTime || (XprType::Flags&RowMajorBit)==0)>                           \\\n  struct EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl);                                                                                  \\\n                                                                                                                                \\\n  template<typename XprType, typename Scalar, int Rows, int Cols>                                                               \\\n  struct EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl)<XprType,Scalar,Rows,Cols,false> {                                                 \\\n    inline static void run(ARG1 a,EIGEN_GL_EVAL(EIGEN_GL_MAKE_CONST_##CONST) XprType& p) {                                      \\\n      EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl)<typename plain_matrix_type_column_major<XprType>::type>::run(a,p); }                 \\\n  };                                                                                                                            \\\n}                                                                                                                               \\\n                                                                                                                                \\\ntemplate<typename Derived> inline void FUNC(ARG1 a,EIGEN_GL_EVAL(EIGEN_GL_MAKE_CONST_##CONST) Eigen::DenseBase<Derived>& p) {   \\\n  EIGEN_CAT(EIGEN_CAT(internal::gl_,FUNC),_impl)<Derived>::run(a,p.derived());                                                  \\\n}\n\n\n#define EIGEN_GL_FUNC1_SPECIALIZATION_MAT(FUNC,ARG1,CONST,SCALAR,ROWS,COLS,SUFFIX)                                              \\\nnamespace internal {                                                                                                            \\\n  template< typename XprType> struct EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl)<XprType, SCALAR, ROWS, COLS, true> {                  \\\n    inline static void run(ARG1 a, EIGEN_GL_EVAL(EIGEN_GL_MAKE_CONST_##CONST) XprType& p) { FUNC##SUFFIX(a,p.data()); }         \\\n  }; \\\n}\n\n  \n#define EIGEN_GL_FUNC1_SPECIALIZATION_VEC(FUNC,ARG1,CONST,SCALAR,SIZE,SUFFIX)                                                   \\\nnamespace internal {                                                                                                            \\\n  template< typename XprType> struct EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl)<XprType, SCALAR, SIZE, 1, true> {                     \\\n    inline static void run(ARG1 a, EIGEN_GL_EVAL(EIGEN_GL_MAKE_CONST_##CONST) XprType& p) { FUNC##SUFFIX(a,p.data()); }         \\\n  };                                                                                                                            \\\n  template< typename XprType> struct EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl)<XprType, SCALAR, 1, SIZE, true> {                     \\\n    inline static void run(ARG1 a, EIGEN_GL_EVAL(EIGEN_GL_MAKE_CONST_##CONST) XprType& p) { FUNC##SUFFIX(a,p.data()); }         \\\n  };                                                                                                                            \\\n}\n\nEIGEN_GL_FUNC1_DECLARATION       (glGet,GLenum,_)\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glGet,GLenum,_,float,  4,4,Floatv)\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glGet,GLenum,_,double, 4,4,Doublev)\n\n// glUniform API\n\n#ifdef GL_VERSION_2_0\n\ninline void glUniform2fv_ei  (GLint loc, const float* v)         { glUniform2fv(loc,1,v); }\ninline void glUniform2iv_ei  (GLint loc, const int* v)           { glUniform2iv(loc,1,v); }\n\ninline void glUniform3fv_ei  (GLint loc, const float* v)         { glUniform3fv(loc,1,v); }\ninline void glUniform3iv_ei  (GLint loc, const int* v)           { glUniform3iv(loc,1,v); }\n\ninline void glUniform4fv_ei  (GLint loc, const float* v)         { glUniform4fv(loc,1,v); }\ninline void glUniform4iv_ei  (GLint loc, const int* v)           { glUniform4iv(loc,1,v); }\n\ninline void glUniformMatrix2fv_ei  (GLint loc, const float* v)         { glUniformMatrix2fv(loc,1,false,v); }\ninline void glUniformMatrix3fv_ei  (GLint loc, const float* v)         { glUniformMatrix3fv(loc,1,false,v); }\ninline void glUniformMatrix4fv_ei  (GLint loc, const float* v)         { glUniformMatrix4fv(loc,1,false,v); }\n\n\nEIGEN_GL_FUNC1_DECLARATION       (glUniform,GLint,const)\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,float,        2,2fv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,int,          2,2iv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,float,        3,3fv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,int,          3,3iv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,float,        4,4fv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,int,          4,4iv_ei)\n\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glUniform,GLint,const,float,        2,2,Matrix2fv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glUniform,GLint,const,float,        3,3,Matrix3fv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glUniform,GLint,const,float,        4,4,Matrix4fv_ei)\n\n#endif\n\n#ifdef GL_VERSION_2_1\n\ninline void glUniformMatrix2x3fv_ei(GLint loc, const float* v)         { glUniformMatrix2x3fv(loc,1,false,v); }\ninline void glUniformMatrix3x2fv_ei(GLint loc, const float* v)         { glUniformMatrix3x2fv(loc,1,false,v); }\ninline void glUniformMatrix2x4fv_ei(GLint loc, const float* v)         { glUniformMatrix2x4fv(loc,1,false,v); }\ninline void glUniformMatrix4x2fv_ei(GLint loc, const float* v)         { glUniformMatrix4x2fv(loc,1,false,v); }\ninline void glUniformMatrix3x4fv_ei(GLint loc, const float* v)         { glUniformMatrix3x4fv(loc,1,false,v); }\ninline void glUniformMatrix4x3fv_ei(GLint loc, const float* v)         { glUniformMatrix4x3fv(loc,1,false,v); }\n\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glUniform,GLint,const,float,        2,3,Matrix2x3fv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glUniform,GLint,const,float,        3,2,Matrix3x2fv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glUniform,GLint,const,float,        2,4,Matrix2x4fv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glUniform,GLint,const,float,        4,2,Matrix4x2fv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glUniform,GLint,const,float,        3,4,Matrix3x4fv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glUniform,GLint,const,float,        4,3,Matrix4x3fv_ei)\n\n#endif\n\n#ifdef GL_VERSION_3_0\n\ninline void glUniform2uiv_ei (GLint loc, const unsigned int* v)  { glUniform2uiv(loc,1,v); }\ninline void glUniform3uiv_ei (GLint loc, const unsigned int* v)  { glUniform3uiv(loc,1,v); }\ninline void glUniform4uiv_ei (GLint loc, const unsigned int* v)  { glUniform4uiv(loc,1,v); }\n\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,unsigned int, 2,2uiv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,unsigned int, 3,3uiv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,unsigned int, 4,4uiv_ei)\n\n#endif\n\n#ifdef GL_ARB_gpu_shader_fp64\ninline void glUniform2dv_ei  (GLint loc, const double* v)        { glUniform2dv(loc,1,v); }\ninline void glUniform3dv_ei  (GLint loc, const double* v)        { glUniform3dv(loc,1,v); }\ninline void glUniform4dv_ei  (GLint loc, const double* v)        { glUniform4dv(loc,1,v); }\n\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,double,       2,2dv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,double,       3,3dv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,double,       4,4dv_ei)\n#endif\n\n\n//@}\n\n}\n\n#endif // EIGEN_OPENGL_MODULE\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/Polynomials",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_POLYNOMIALS_MODULE_H\n#define EIGEN_POLYNOMIALS_MODULE_H\n\n#include \"../../Eigen/Core\"\n\n#include \"../../Eigen/Eigenvalues\"\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n// Note that EIGEN_HIDE_HEAVY_CODE has to be defined per module\n#if (defined EIGEN_EXTERN_INSTANTIATIONS) && (EIGEN_EXTERN_INSTANTIATIONS>=2)\n  #ifndef EIGEN_HIDE_HEAVY_CODE\n  #define EIGEN_HIDE_HEAVY_CODE\n  #endif\n#elif defined EIGEN_HIDE_HEAVY_CODE\n  #undef EIGEN_HIDE_HEAVY_CODE\n#endif\n\n/**\n  * \\defgroup Polynomials_Module Polynomials module\n  * \\brief This module provides a QR based polynomial solver.\n\t*\n  * To use this module, add\n  * \\code\n  * #include <unsupported/Eigen/Polynomials>\n  * \\endcode\n\t* at the start of your source file.\n  */\n\n#include \"src/Polynomials/PolynomialUtils.h\"\n#include \"src/Polynomials/Companion.h\"\n#include \"src/Polynomials/PolynomialSolver.h\"\n\n/**\n\t\\page polynomials Polynomials defines functions for dealing with polynomials\n\tand a QR based polynomial solver.\n\t\\ingroup Polynomials_Module\n\n\tThe remainder of the page documents first the functions for evaluating, computing\n\tpolynomials, computing estimates about polynomials and next the QR based polynomial\n\tsolver.\n\n\t\\section polynomialUtils convenient functions to deal with polynomials\n\t\\subsection roots_to_monicPolynomial\n\tThe function\n\t\\code\n\tvoid roots_to_monicPolynomial( const RootVector& rv, Polynomial& poly )\n\t\\endcode\n\tcomputes the coefficients \\f$ a_i \\f$ of\n\n\t\\f$ p(x) = a_0 + a_{1}x + ... + a_{n-1}x^{n-1} + x^n \\f$\n\n\twhere \\f$ p \\f$ is known through its roots i.e. \\f$ p(x) = (x-r_1)(x-r_2)...(x-r_n) \\f$.\n\n\t\\subsection poly_eval\n\tThe function\n\t\\code\n\tT poly_eval( const Polynomials& poly, const T& x )\n\t\\endcode\n\tevaluates a polynomial at a given point using stabilized H&ouml;rner method.\n\n\tThe following code: first computes the coefficients in the monomial basis of the monic polynomial that has the provided roots;\n\tthen, it evaluates the computed polynomial, using a stabilized H&ouml;rner method.\n\n\t\\include PolynomialUtils1.cpp\n  Output: \\verbinclude PolynomialUtils1.out\n\n\t\\subsection Cauchy bounds\n\tThe function\n\t\\code\n\tReal cauchy_max_bound( const Polynomial& poly )\n\t\\endcode\n\tprovides a maximum bound (the Cauchy one: \\f$C(p)\\f$) for the absolute value of a root of the given polynomial i.e.\n\t\\f$ \\forall r_i \\f$ root of \\f$ p(x) = \\sum_{k=0}^d a_k x^k \\f$,\n\t\\f$ |r_i| \\le C(p) = \\sum_{k=0}^{d} \\left | \\frac{a_k}{a_d} \\right | \\f$\n\tThe leading coefficient \\f$ p \\f$: should be non zero \\f$a_d \\neq 0\\f$.\n\n\n\tThe function\n\t\\code\n\tReal cauchy_min_bound( const Polynomial& poly )\n\t\\endcode\n\tprovides a minimum bound (the Cauchy one: \\f$c(p)\\f$) for the absolute value of a non zero root of the given polynomial i.e.\n\t\\f$ \\forall r_i \\neq 0 \\f$ root of \\f$ p(x) = \\sum_{k=0}^d a_k x^k \\f$,\n\t\\f$ |r_i| \\ge c(p) = \\left( \\sum_{k=0}^{d} \\left | \\frac{a_k}{a_0} \\right | \\right)^{-1} \\f$\n\n\n\n\n\t\\section QR polynomial solver class\n\tComputes the complex roots of a polynomial by computing the eigenvalues of the associated companion matrix with the QR algorithm.\n\t\n\tThe roots of \\f$ p(x) = a_0 + a_1 x + a_2 x^2 + a_{3} x^3 + x^4 \\f$ are the eigenvalues of\n\t\\f$\n\t\\left [\n\t\\begin{array}{cccc}\n\t0 & 0 &  0 & a_0 \\\\\n\t1 & 0 &  0 & a_1 \\\\\n\t0 & 1 &  0 & a_2 \\\\\n\t0 & 0 &  1 & a_3\n\t\\end{array} \\right ]\n\t\\f$\n\n\tHowever, the QR algorithm is not guaranteed to converge when there are several eigenvalues with same modulus.\n\n\tTherefore the current polynomial solver is guaranteed to provide a correct result only when the complex roots \\f$r_1,r_2,...,r_d\\f$ have distinct moduli i.e.\n\t\n\t\\f$ \\forall i,j \\in [1;d],~ \\| r_i \\| \\neq \\| r_j \\| \\f$.\n\n\tWith 32bit (float) floating types this problem shows up frequently.\n  However, almost always, correct accuracy is reached even in these cases for 64bit\n  (double) floating types and small polynomial degree (<20).\n\n\t\\include PolynomialSolver1.cpp\n\t\n\tIn the above example:\n\t\n\t-# a simple use of the polynomial solver is shown;\n\t-# the accuracy problem with the QR algorithm is presented: a polynomial with almost conjugate roots is provided to the solver.\n\tThose roots have almost same module therefore the QR algorithm failed to converge: the accuracy\n\tof the last root is bad;\n\t-# a simple way to circumvent the problem is shown: use doubles instead of floats.\n\n  Output: \\verbinclude PolynomialSolver1.out\n*/\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_POLYNOMIALS_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/Skyline",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SKYLINE_MODULE_H\n#define EIGEN_SKYLINE_MODULE_H\n\n\n#include \"../../Eigen/Core\"\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n#include <map>\n#include <cstdlib>\n#include <cstring>\n#include <algorithm>\n\n/**\n *  \\defgroup Skyline_Module Skyline module\n *\n *\n *\n *\n */\n\n#include \"src/Skyline/SkylineUtil.h\"\n#include \"src/Skyline/SkylineMatrixBase.h\"\n#include \"src/Skyline/SkylineStorage.h\"\n#include \"src/Skyline/SkylineMatrix.h\"\n#include \"src/Skyline/SkylineInplaceLU.h\"\n#include \"src/Skyline/SkylineProduct.h\"\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_SKYLINE_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/SparseExtra",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_EXTRA_MODULE_H\n#define EIGEN_SPARSE_EXTRA_MODULE_H\n\n#include \"../../Eigen/Sparse\"\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n#include <vector>\n#include <map>\n#include <unordered_map>\n#include <cstdlib>\n#include <cstring>\n#include <algorithm>\n#include <fstream>\n#include <sstream>\n\n#ifdef EIGEN_GOOGLEHASH_SUPPORT\n  #include <google/dense_hash_map>\n  #include <google/sparse_hash_map>\n#endif\n\n/**\n  * \\defgroup SparseExtra_Module SparseExtra module\n  *\n  * This module contains some experimental features extending the sparse module.\n  *\n  * \\code\n  * #include <Eigen/SparseExtra>\n  * \\endcode\n  */\n\n\n#include \"src/SparseExtra/RandomSetter.h\"\n\n#include \"src/SparseExtra/MarketIO.h\"\n\n#if !defined(_WIN32)\n#include <dirent.h>\n#include \"src/SparseExtra/MatrixMarketIterator.h\"\n#endif\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_SPARSE_EXTRA_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/SpecialFunctions",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPECIALFUNCTIONS_MODULE\n#define EIGEN_SPECIALFUNCTIONS_MODULE\n\n#include <math.h>\n\n#include \"../../Eigen/Core\"\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\nnamespace Eigen {\n\n/**\n  * \\defgroup SpecialFunctions_Module Special math functions module\n  *\n  * This module features additional coefficient-wise math functions available\n  * within the numext:: namespace for the scalar version, and as method and/or free\n  * functions of Array. Those include:\n  *\n  * - erf\n  * - erfc\n  * - lgamma\n  * - igamma\n  * - igamma_der_a\n  * - gamma_sample_der_alpha\n  * - igammac\n  * - digamma\n  * - ndtri\n  * - polygamma\n  * - zeta\n  * - betainc\n  *\n  * Bessel Functions\n  * - bessel_i0\n  * - bessel_i0e\n  * - bessel_i1\n  * - bessel_i1e\n  * - bessel_j0\n  * - bessel_j1\n  * - bessel_k0\n  * - bessel_k0e\n  * - bessel_k1\n  * - bessel_k1e\n  * - bessel_y0\n  * - bessel_y1\n  *\n  * \\code\n  * #include <unsupported/Eigen/SpecialFunctions>\n  * \\endcode\n  */\n//@{\n\n}\n\n#include \"src/SpecialFunctions/BesselFunctionsImpl.h\"\n#include \"src/SpecialFunctions/BesselFunctionsBFloat16.h\"\n#include \"src/SpecialFunctions/BesselFunctionsHalf.h\"\n#include \"src/SpecialFunctions/BesselFunctionsPacketMath.h\"\n#include \"src/SpecialFunctions/BesselFunctionsFunctors.h\"\n#include \"src/SpecialFunctions/BesselFunctionsArrayAPI.h\"\n#include \"src/SpecialFunctions/SpecialFunctionsImpl.h\"\n#if defined(EIGEN_HIPCC)\n#include \"src/SpecialFunctions/HipVectorCompatibility.h\"\n#endif\n#include \"src/SpecialFunctions/SpecialFunctionsBFloat16.h\"\n#include \"src/SpecialFunctions/SpecialFunctionsHalf.h\"\n#include \"src/SpecialFunctions/SpecialFunctionsPacketMath.h\"\n#include \"src/SpecialFunctions/SpecialFunctionsFunctors.h\"\n#include \"src/SpecialFunctions/SpecialFunctionsArrayAPI.h\"\n\n#if defined EIGEN_VECTORIZE_AVX512\n  #include \"src/SpecialFunctions/arch/AVX/BesselFunctions.h\"\n  #include \"src/SpecialFunctions/arch/AVX/SpecialFunctions.h\"\n  #include \"src/SpecialFunctions/arch/AVX512/BesselFunctions.h\"\n  #include \"src/SpecialFunctions/arch/AVX512/SpecialFunctions.h\"\n#elif defined EIGEN_VECTORIZE_AVX\n  #include \"src/SpecialFunctions/arch/AVX/BesselFunctions.h\"\n  #include \"src/SpecialFunctions/arch/AVX/SpecialFunctions.h\"\n#elif defined EIGEN_VECTORIZE_NEON\n  #include \"src/SpecialFunctions/arch/NEON/BesselFunctions.h\"\n  #include \"src/SpecialFunctions/arch/NEON/SpecialFunctions.h\"\n#endif\n\n#if defined EIGEN_VECTORIZE_GPU\n  #include \"src/SpecialFunctions/arch/GPU/SpecialFunctions.h\"\n#endif\n\nnamespace Eigen {\n//@}\n}\n\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_SPECIALFUNCTIONS_MODULE\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/Splines",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 20010-2011 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPLINES_MODULE_H\n#define EIGEN_SPLINES_MODULE_H\n\nnamespace Eigen \n{\n/**\n  * \\defgroup Splines_Module Spline and spline fitting module\n  *\n  * This module provides a simple multi-dimensional spline class while\n  * offering most basic functionality to fit a spline to point sets.\n  *\n  * \\code\n  * #include <unsupported/Eigen/Splines>\n  * \\endcode\n  */\n}\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n#include \"src/Splines/SplineFwd.h\"\n#include \"src/Splines/Spline.h\"\n#include \"src/Splines/SplineFitting.h\"\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_SPLINES_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/AutoDiff/AutoDiffJacobian.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_AUTODIFF_JACOBIAN_H\n#define EIGEN_AUTODIFF_JACOBIAN_H\n\nnamespace Eigen\n{\n\ntemplate<typename Functor> class AutoDiffJacobian : public Functor\n{\npublic:\n  AutoDiffJacobian() : Functor() {}\n  AutoDiffJacobian(const Functor& f) : Functor(f) {}\n\n  // forward constructors\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  template<typename... T>\n  AutoDiffJacobian(const T& ...Values) : Functor(Values...) {}\n#else\n  template<typename T0>\n  AutoDiffJacobian(const T0& a0) : Functor(a0) {}\n  template<typename T0, typename T1>\n  AutoDiffJacobian(const T0& a0, const T1& a1) : Functor(a0, a1) {}\n  template<typename T0, typename T1, typename T2>\n  AutoDiffJacobian(const T0& a0, const T1& a1, const T2& a2) : Functor(a0, a1, a2) {}\n#endif\n\n  typedef typename Functor::InputType InputType;\n  typedef typename Functor::ValueType ValueType;\n  typedef typename ValueType::Scalar Scalar;\n\n  enum {\n    InputsAtCompileTime = InputType::RowsAtCompileTime,\n    ValuesAtCompileTime = ValueType::RowsAtCompileTime\n  };\n\n  typedef Matrix<Scalar, ValuesAtCompileTime, InputsAtCompileTime> JacobianType;\n  typedef typename JacobianType::Index Index;\n\n  typedef Matrix<Scalar, InputsAtCompileTime, 1> DerivativeType;\n  typedef AutoDiffScalar<DerivativeType> ActiveScalar;\n\n  typedef Matrix<ActiveScalar, InputsAtCompileTime, 1> ActiveInput;\n  typedef Matrix<ActiveScalar, ValuesAtCompileTime, 1> ActiveValue;\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  // Some compilers don't accept variadic parameters after a default parameter,\n  // i.e., we can't just write _jac=0 but we need to overload operator():\n  EIGEN_STRONG_INLINE\n  void operator() (const InputType& x, ValueType* v) const\n  {\n      this->operator()(x, v, 0);\n  }\n  template<typename... ParamsType>\n  void operator() (const InputType& x, ValueType* v, JacobianType* _jac,\n                   const ParamsType&... Params) const\n#else\n  void operator() (const InputType& x, ValueType* v, JacobianType* _jac=0) const\n#endif\n  {\n    eigen_assert(v!=0);\n\n    if (!_jac)\n    {\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n      Functor::operator()(x, v, Params...);\n#else\n      Functor::operator()(x, v);\n#endif\n      return;\n    }\n\n    JacobianType& jac = *_jac;\n\n    ActiveInput ax = x.template cast<ActiveScalar>();\n    ActiveValue av(jac.rows());\n\n    if(InputsAtCompileTime==Dynamic)\n      for (Index j=0; j<jac.rows(); j++)\n        av[j].derivatives().resize(x.rows());\n\n    for (Index i=0; i<jac.cols(); i++)\n      ax[i].derivatives() = DerivativeType::Unit(x.rows(),i);\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    Functor::operator()(ax, &av, Params...);\n#else\n    Functor::operator()(ax, &av);\n#endif\n\n    for (Index i=0; i<jac.rows(); i++)\n    {\n      (*v)[i] = av[i].value();\n      jac.row(i) = av[i].derivatives();\n    }\n  }\n};\n\n}\n\n#endif // EIGEN_AUTODIFF_JACOBIAN_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/AutoDiff/AutoDiffScalar.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_AUTODIFF_SCALAR_H\n#define EIGEN_AUTODIFF_SCALAR_H\n\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate<typename A, typename B>\nstruct make_coherent_impl {\n  static void run(A&, B&) {}\n};\n\n// resize a to match b is a.size()==0, and conversely.\ntemplate<typename A, typename B>\nvoid make_coherent(const A& a, const B&b)\n{\n  make_coherent_impl<A,B>::run(a.const_cast_derived(), b.const_cast_derived());\n}\n\ntemplate<typename DerivativeType, bool Enable> struct auto_diff_special_op;\n\n} // end namespace internal\n\ntemplate<typename DerivativeType> class AutoDiffScalar;\n\ntemplate<typename NewDerType>\ninline AutoDiffScalar<NewDerType> MakeAutoDiffScalar(const typename NewDerType::Scalar& value, const NewDerType &der) {\n  return AutoDiffScalar<NewDerType>(value,der);\n}\n\n/** \\class AutoDiffScalar\n  * \\brief A scalar type replacement with automatic differentiation capability\n  *\n  * \\param DerivativeType the vector type used to store/represent the derivatives. The base scalar type\n  *                 as well as the number of derivatives to compute are determined from this type.\n  *                 Typical choices include, e.g., \\c Vector4f for 4 derivatives, or \\c VectorXf\n  *                 if the number of derivatives is not known at compile time, and/or, the number\n  *                 of derivatives is large.\n  *                 Note that DerivativeType can also be a reference (e.g., \\c VectorXf&) to wrap a\n  *                 existing vector into an AutoDiffScalar.\n  *                 Finally, DerivativeType can also be any Eigen compatible expression.\n  *\n  * This class represents a scalar value while tracking its respective derivatives using Eigen's expression\n  * template mechanism.\n  *\n  * It supports the following list of global math function:\n  *  - std::abs, std::sqrt, std::pow, std::exp, std::log, std::sin, std::cos,\n  *  - internal::abs, internal::sqrt, numext::pow, internal::exp, internal::log, internal::sin, internal::cos,\n  *  - internal::conj, internal::real, internal::imag, numext::abs2.\n  *\n  * AutoDiffScalar can be used as the scalar type of an Eigen::Matrix object. However,\n  * in that case, the expression template mechanism only occurs at the top Matrix level,\n  * while derivatives are computed right away.\n  *\n  */\n\ntemplate<typename DerivativeType>\nclass AutoDiffScalar\n  : public internal::auto_diff_special_op\n            <DerivativeType, !internal::is_same<typename internal::traits<typename internal::remove_all<DerivativeType>::type>::Scalar,\n                                          typename NumTraits<typename internal::traits<typename internal::remove_all<DerivativeType>::type>::Scalar>::Real>::value>\n{\n  public:\n    typedef internal::auto_diff_special_op\n            <DerivativeType, !internal::is_same<typename internal::traits<typename internal::remove_all<DerivativeType>::type>::Scalar,\n                       typename NumTraits<typename internal::traits<typename internal::remove_all<DerivativeType>::type>::Scalar>::Real>::value> Base;\n    typedef typename internal::remove_all<DerivativeType>::type DerType;\n    typedef typename internal::traits<DerType>::Scalar Scalar;\n    typedef typename NumTraits<Scalar>::Real Real;\n\n    using Base::operator+;\n    using Base::operator*;\n\n    /** Default constructor without any initialization. */\n    AutoDiffScalar() {}\n\n    /** Constructs an active scalar from its \\a value,\n        and initializes the \\a nbDer derivatives such that it corresponds to the \\a derNumber -th variable */\n    AutoDiffScalar(const Scalar& value, int nbDer, int derNumber)\n      : m_value(value), m_derivatives(DerType::Zero(nbDer))\n    {\n      m_derivatives.coeffRef(derNumber) = Scalar(1);\n    }\n\n    /** Conversion from a scalar constant to an active scalar.\n      * The derivatives are set to zero. */\n    /*explicit*/ AutoDiffScalar(const Real& value)\n      : m_value(value)\n    {\n      if(m_derivatives.size()>0)\n        m_derivatives.setZero();\n    }\n\n    /** Constructs an active scalar from its \\a value and derivatives \\a der */\n    AutoDiffScalar(const Scalar& value, const DerType& der)\n      : m_value(value), m_derivatives(der)\n    {}\n\n    template<typename OtherDerType>\n    AutoDiffScalar(const AutoDiffScalar<OtherDerType>& other\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n    , typename internal::enable_if<\n            internal::is_same<Scalar, typename internal::traits<typename internal::remove_all<OtherDerType>::type>::Scalar>::value\n        &&  internal::is_convertible<OtherDerType,DerType>::value , void*>::type = 0\n#endif\n    )\n      : m_value(other.value()), m_derivatives(other.derivatives())\n    {}\n\n    friend  std::ostream & operator << (std::ostream & s, const AutoDiffScalar& a)\n    {\n      return s << a.value();\n    }\n\n    AutoDiffScalar(const AutoDiffScalar& other)\n      : m_value(other.value()), m_derivatives(other.derivatives())\n    {}\n\n    template<typename OtherDerType>\n    inline AutoDiffScalar& operator=(const AutoDiffScalar<OtherDerType>& other)\n    {\n      m_value = other.value();\n      m_derivatives = other.derivatives();\n      return *this;\n    }\n\n    inline AutoDiffScalar& operator=(const AutoDiffScalar& other)\n    {\n      m_value = other.value();\n      m_derivatives = other.derivatives();\n      return *this;\n    }\n\n    inline AutoDiffScalar& operator=(const Scalar& other)\n    {\n      m_value = other;\n      if(m_derivatives.size()>0)\n        m_derivatives.setZero();\n      return *this;\n    }\n\n//     inline operator const Scalar& () const { return m_value; }\n//     inline operator Scalar& () { return m_value; }\n\n    inline const Scalar& value() const { return m_value; }\n    inline Scalar& value() { return m_value; }\n\n    inline const DerType& derivatives() const { return m_derivatives; }\n    inline DerType& derivatives() { return m_derivatives; }\n\n    inline bool operator< (const Scalar& other) const  { return m_value <  other; }\n    inline bool operator<=(const Scalar& other) const  { return m_value <= other; }\n    inline bool operator> (const Scalar& other) const  { return m_value >  other; }\n    inline bool operator>=(const Scalar& other) const  { return m_value >= other; }\n    inline bool operator==(const Scalar& other) const  { return m_value == other; }\n    inline bool operator!=(const Scalar& other) const  { return m_value != other; }\n\n    friend inline bool operator< (const Scalar& a, const AutoDiffScalar& b) { return a <  b.value(); }\n    friend inline bool operator<=(const Scalar& a, const AutoDiffScalar& b) { return a <= b.value(); }\n    friend inline bool operator> (const Scalar& a, const AutoDiffScalar& b) { return a >  b.value(); }\n    friend inline bool operator>=(const Scalar& a, const AutoDiffScalar& b) { return a >= b.value(); }\n    friend inline bool operator==(const Scalar& a, const AutoDiffScalar& b) { return a == b.value(); }\n    friend inline bool operator!=(const Scalar& a, const AutoDiffScalar& b) { return a != b.value(); }\n\n    template<typename OtherDerType> inline bool operator< (const AutoDiffScalar<OtherDerType>& b) const  { return m_value <  b.value(); }\n    template<typename OtherDerType> inline bool operator<=(const AutoDiffScalar<OtherDerType>& b) const  { return m_value <= b.value(); }\n    template<typename OtherDerType> inline bool operator> (const AutoDiffScalar<OtherDerType>& b) const  { return m_value >  b.value(); }\n    template<typename OtherDerType> inline bool operator>=(const AutoDiffScalar<OtherDerType>& b) const  { return m_value >= b.value(); }\n    template<typename OtherDerType> inline bool operator==(const AutoDiffScalar<OtherDerType>& b) const  { return m_value == b.value(); }\n    template<typename OtherDerType> inline bool operator!=(const AutoDiffScalar<OtherDerType>& b) const  { return m_value != b.value(); }\n\n    inline const AutoDiffScalar<DerType&> operator+(const Scalar& other) const\n    {\n      return AutoDiffScalar<DerType&>(m_value + other, m_derivatives);\n    }\n\n    friend inline const AutoDiffScalar<DerType&> operator+(const Scalar& a, const AutoDiffScalar& b)\n    {\n      return AutoDiffScalar<DerType&>(a + b.value(), b.derivatives());\n    }\n\n//     inline const AutoDiffScalar<DerType&> operator+(const Real& other) const\n//     {\n//       return AutoDiffScalar<DerType&>(m_value + other, m_derivatives);\n//     }\n\n//     friend inline const AutoDiffScalar<DerType&> operator+(const Real& a, const AutoDiffScalar& b)\n//     {\n//       return AutoDiffScalar<DerType&>(a + b.value(), b.derivatives());\n//     }\n\n    inline AutoDiffScalar& operator+=(const Scalar& other)\n    {\n      value() += other;\n      return *this;\n    }\n\n    template<typename OtherDerType>\n    inline const AutoDiffScalar<CwiseBinaryOp<internal::scalar_sum_op<Scalar>,const DerType,const typename internal::remove_all<OtherDerType>::type> >\n    operator+(const AutoDiffScalar<OtherDerType>& other) const\n    {\n      internal::make_coherent(m_derivatives, other.derivatives());\n      return AutoDiffScalar<CwiseBinaryOp<internal::scalar_sum_op<Scalar>,const DerType,const typename internal::remove_all<OtherDerType>::type> >(\n        m_value + other.value(),\n        m_derivatives + other.derivatives());\n    }\n\n    template<typename OtherDerType>\n    inline AutoDiffScalar&\n    operator+=(const AutoDiffScalar<OtherDerType>& other)\n    {\n      (*this) = (*this) + other;\n      return *this;\n    }\n\n    inline const AutoDiffScalar<DerType&> operator-(const Scalar& b) const\n    {\n      return AutoDiffScalar<DerType&>(m_value - b, m_derivatives);\n    }\n\n    friend inline const AutoDiffScalar<CwiseUnaryOp<internal::scalar_opposite_op<Scalar>, const DerType> >\n    operator-(const Scalar& a, const AutoDiffScalar& b)\n    {\n      return AutoDiffScalar<CwiseUnaryOp<internal::scalar_opposite_op<Scalar>, const DerType> >\n            (a - b.value(), -b.derivatives());\n    }\n\n    inline AutoDiffScalar& operator-=(const Scalar& other)\n    {\n      value() -= other;\n      return *this;\n    }\n\n    template<typename OtherDerType>\n    inline const AutoDiffScalar<CwiseBinaryOp<internal::scalar_difference_op<Scalar>, const DerType,const typename internal::remove_all<OtherDerType>::type> >\n    operator-(const AutoDiffScalar<OtherDerType>& other) const\n    {\n      internal::make_coherent(m_derivatives, other.derivatives());\n      return AutoDiffScalar<CwiseBinaryOp<internal::scalar_difference_op<Scalar>, const DerType,const typename internal::remove_all<OtherDerType>::type> >(\n        m_value - other.value(),\n        m_derivatives - other.derivatives());\n    }\n\n    template<typename OtherDerType>\n    inline AutoDiffScalar&\n    operator-=(const AutoDiffScalar<OtherDerType>& other)\n    {\n      *this = *this - other;\n      return *this;\n    }\n\n    inline const AutoDiffScalar<CwiseUnaryOp<internal::scalar_opposite_op<Scalar>, const DerType> >\n    operator-() const\n    {\n      return AutoDiffScalar<CwiseUnaryOp<internal::scalar_opposite_op<Scalar>, const DerType> >(\n        -m_value,\n        -m_derivatives);\n    }\n\n    inline const AutoDiffScalar<EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(DerType,Scalar,product) >\n    operator*(const Scalar& other) const\n    {\n      return MakeAutoDiffScalar(m_value * other, m_derivatives * other);\n    }\n\n    friend inline const AutoDiffScalar<EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(DerType,Scalar,product) >\n    operator*(const Scalar& other, const AutoDiffScalar& a)\n    {\n      return MakeAutoDiffScalar(a.value() * other, a.derivatives() * other);\n    }\n\n//     inline const AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >\n//     operator*(const Real& other) const\n//     {\n//       return AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >(\n//         m_value * other,\n//         (m_derivatives * other));\n//     }\n//\n//     friend inline const AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >\n//     operator*(const Real& other, const AutoDiffScalar& a)\n//     {\n//       return AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >(\n//         a.value() * other,\n//         a.derivatives() * other);\n//     }\n\n    inline const AutoDiffScalar<EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(DerType,Scalar,product) >\n    operator/(const Scalar& other) const\n    {\n      return MakeAutoDiffScalar(m_value / other, (m_derivatives * (Scalar(1)/other)));\n    }\n\n    friend inline const AutoDiffScalar<EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(DerType,Scalar,product) >\n    operator/(const Scalar& other, const AutoDiffScalar& a)\n    {\n      return MakeAutoDiffScalar(other / a.value(), a.derivatives() * (Scalar(-other) / (a.value()*a.value())));\n    }\n\n//     inline const AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >\n//     operator/(const Real& other) const\n//     {\n//       return AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >(\n//         m_value / other,\n//         (m_derivatives * (Real(1)/other)));\n//     }\n//\n//     friend inline const AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >\n//     operator/(const Real& other, const AutoDiffScalar& a)\n//     {\n//       return AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >(\n//         other / a.value(),\n//         a.derivatives() * (-Real(1)/other));\n//     }\n\n    template<typename OtherDerType>\n    inline const AutoDiffScalar<EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(\n        CwiseBinaryOp<internal::scalar_difference_op<Scalar> EIGEN_COMMA\n          const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(DerType,Scalar,product) EIGEN_COMMA\n          const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(typename internal::remove_all<OtherDerType>::type,Scalar,product) >,Scalar,product) >\n    operator/(const AutoDiffScalar<OtherDerType>& other) const\n    {\n      internal::make_coherent(m_derivatives, other.derivatives());\n      return MakeAutoDiffScalar(\n        m_value / other.value(),\n          ((m_derivatives * other.value()) - (other.derivatives() * m_value))\n        * (Scalar(1)/(other.value()*other.value())));\n    }\n\n    template<typename OtherDerType>\n    inline const AutoDiffScalar<CwiseBinaryOp<internal::scalar_sum_op<Scalar>,\n        const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(DerType,Scalar,product),\n        const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(typename internal::remove_all<OtherDerType>::type,Scalar,product) > >\n    operator*(const AutoDiffScalar<OtherDerType>& other) const\n    {\n      internal::make_coherent(m_derivatives, other.derivatives());\n      return MakeAutoDiffScalar(\n        m_value * other.value(),\n        (m_derivatives * other.value()) + (other.derivatives() * m_value));\n    }\n\n    inline AutoDiffScalar& operator*=(const Scalar& other)\n    {\n      *this = *this * other;\n      return *this;\n    }\n\n    template<typename OtherDerType>\n    inline AutoDiffScalar& operator*=(const AutoDiffScalar<OtherDerType>& other)\n    {\n      *this = *this * other;\n      return *this;\n    }\n\n    inline AutoDiffScalar& operator/=(const Scalar& other)\n    {\n      *this = *this / other;\n      return *this;\n    }\n\n    template<typename OtherDerType>\n    inline AutoDiffScalar& operator/=(const AutoDiffScalar<OtherDerType>& other)\n    {\n      *this = *this / other;\n      return *this;\n    }\n\n  protected:\n    Scalar m_value;\n    DerType m_derivatives;\n\n};\n\nnamespace internal {\n\ntemplate<typename DerivativeType>\nstruct auto_diff_special_op<DerivativeType, true>\n//   : auto_diff_scalar_op<DerivativeType, typename NumTraits<Scalar>::Real,\n//                            is_same<Scalar,typename NumTraits<Scalar>::Real>::value>\n{\n  typedef typename remove_all<DerivativeType>::type DerType;\n  typedef typename traits<DerType>::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real Real;\n\n//   typedef auto_diff_scalar_op<DerivativeType, typename NumTraits<Scalar>::Real,\n//                            is_same<Scalar,typename NumTraits<Scalar>::Real>::value> Base;\n\n//   using Base::operator+;\n//   using Base::operator+=;\n//   using Base::operator-;\n//   using Base::operator-=;\n//   using Base::operator*;\n//   using Base::operator*=;\n\n  const AutoDiffScalar<DerivativeType>& derived() const { return *static_cast<const AutoDiffScalar<DerivativeType>*>(this); }\n  AutoDiffScalar<DerivativeType>& derived() { return *static_cast<AutoDiffScalar<DerivativeType>*>(this); }\n\n\n  inline const AutoDiffScalar<DerType&> operator+(const Real& other) const\n  {\n    return AutoDiffScalar<DerType&>(derived().value() + other, derived().derivatives());\n  }\n\n  friend inline const AutoDiffScalar<DerType&> operator+(const Real& a, const AutoDiffScalar<DerivativeType>& b)\n  {\n    return AutoDiffScalar<DerType&>(a + b.value(), b.derivatives());\n  }\n\n  inline AutoDiffScalar<DerivativeType>& operator+=(const Real& other)\n  {\n    derived().value() += other;\n    return derived();\n  }\n\n\n  inline const AutoDiffScalar<typename CwiseUnaryOp<bind2nd_op<scalar_product_op<Scalar,Real> >, DerType>::Type >\n  operator*(const Real& other) const\n  {\n    return AutoDiffScalar<typename CwiseUnaryOp<bind2nd_op<scalar_product_op<Scalar,Real> >, DerType>::Type >(\n      derived().value() * other,\n      derived().derivatives() * other);\n  }\n\n  friend inline const AutoDiffScalar<typename CwiseUnaryOp<bind1st_op<scalar_product_op<Real,Scalar> >, DerType>::Type >\n  operator*(const Real& other, const AutoDiffScalar<DerivativeType>& a)\n  {\n    return AutoDiffScalar<typename CwiseUnaryOp<bind1st_op<scalar_product_op<Real,Scalar> >, DerType>::Type >(\n      a.value() * other,\n      a.derivatives() * other);\n  }\n\n  inline AutoDiffScalar<DerivativeType>& operator*=(const Scalar& other)\n  {\n    *this = *this * other;\n    return derived();\n  }\n};\n\ntemplate<typename DerivativeType>\nstruct auto_diff_special_op<DerivativeType, false>\n{\n  void operator*() const;\n  void operator-() const;\n  void operator+() const;\n};\n\ntemplate<typename BinOp, typename A, typename B, typename RefType>\nvoid make_coherent_expression(CwiseBinaryOp<BinOp,A,B> xpr, const RefType &ref)\n{\n  make_coherent(xpr.const_cast_derived().lhs(), ref);\n  make_coherent(xpr.const_cast_derived().rhs(), ref);\n}\n\ntemplate<typename UnaryOp, typename A, typename RefType>\nvoid make_coherent_expression(const CwiseUnaryOp<UnaryOp,A> &xpr, const RefType &ref)\n{\n  make_coherent(xpr.nestedExpression().const_cast_derived(), ref);\n}\n\n// needed for compilation only\ntemplate<typename UnaryOp, typename A, typename RefType>\nvoid make_coherent_expression(const CwiseNullaryOp<UnaryOp,A> &, const RefType &)\n{}\n\ntemplate<typename A_Scalar, int A_Rows, int A_Cols, int A_Options, int A_MaxRows, int A_MaxCols, typename B>\nstruct make_coherent_impl<Matrix<A_Scalar, A_Rows, A_Cols, A_Options, A_MaxRows, A_MaxCols>, B> {\n  typedef Matrix<A_Scalar, A_Rows, A_Cols, A_Options, A_MaxRows, A_MaxCols> A;\n  static void run(A& a, B& b) {\n    if((A_Rows==Dynamic || A_Cols==Dynamic) && (a.size()==0))\n    {\n      a.resize(b.size());\n      a.setZero();\n    }\n    else if (B::SizeAtCompileTime==Dynamic && a.size()!=0 && b.size()==0)\n    {\n      make_coherent_expression(b,a);\n    }\n  }\n};\n\ntemplate<typename A, typename B_Scalar, int B_Rows, int B_Cols, int B_Options, int B_MaxRows, int B_MaxCols>\nstruct make_coherent_impl<A, Matrix<B_Scalar, B_Rows, B_Cols, B_Options, B_MaxRows, B_MaxCols> > {\n  typedef Matrix<B_Scalar, B_Rows, B_Cols, B_Options, B_MaxRows, B_MaxCols> B;\n  static void run(A& a, B& b) {\n    if((B_Rows==Dynamic || B_Cols==Dynamic) && (b.size()==0))\n    {\n      b.resize(a.size());\n      b.setZero();\n    }\n    else if (A::SizeAtCompileTime==Dynamic && b.size()!=0 && a.size()==0)\n    {\n      make_coherent_expression(a,b);\n    }\n  }\n};\n\ntemplate<typename A_Scalar, int A_Rows, int A_Cols, int A_Options, int A_MaxRows, int A_MaxCols,\n         typename B_Scalar, int B_Rows, int B_Cols, int B_Options, int B_MaxRows, int B_MaxCols>\nstruct make_coherent_impl<Matrix<A_Scalar, A_Rows, A_Cols, A_Options, A_MaxRows, A_MaxCols>,\n                          Matrix<B_Scalar, B_Rows, B_Cols, B_Options, B_MaxRows, B_MaxCols> > {\n  typedef Matrix<A_Scalar, A_Rows, A_Cols, A_Options, A_MaxRows, A_MaxCols> A;\n  typedef Matrix<B_Scalar, B_Rows, B_Cols, B_Options, B_MaxRows, B_MaxCols> B;\n  static void run(A& a, B& b) {\n    if((A_Rows==Dynamic || A_Cols==Dynamic) && (a.size()==0))\n    {\n      a.resize(b.size());\n      a.setZero();\n    }\n    else if((B_Rows==Dynamic || B_Cols==Dynamic) && (b.size()==0))\n    {\n      b.resize(a.size());\n      b.setZero();\n    }\n  }\n};\n\n} // end namespace internal\n\ntemplate<typename DerType, typename BinOp>\nstruct ScalarBinaryOpTraits<AutoDiffScalar<DerType>,typename DerType::Scalar,BinOp>\n{\n  typedef AutoDiffScalar<DerType> ReturnType;\n};\n\ntemplate<typename DerType, typename BinOp>\nstruct ScalarBinaryOpTraits<typename DerType::Scalar,AutoDiffScalar<DerType>, BinOp>\n{\n  typedef AutoDiffScalar<DerType> ReturnType;\n};\n\n\n// The following is an attempt to let Eigen's known about expression template, but that's more tricky!\n\n// template<typename DerType, typename BinOp>\n// struct ScalarBinaryOpTraits<AutoDiffScalar<DerType>,AutoDiffScalar<DerType>, BinOp>\n// {\n//   enum { Defined = 1 };\n//   typedef AutoDiffScalar<typename DerType::PlainObject> ReturnType;\n// };\n//\n// template<typename DerType1,typename DerType2, typename BinOp>\n// struct ScalarBinaryOpTraits<AutoDiffScalar<DerType1>,AutoDiffScalar<DerType2>, BinOp>\n// {\n//   enum { Defined = 1 };//internal::is_same<typename DerType1::Scalar,typename DerType2::Scalar>::value };\n//   typedef AutoDiffScalar<typename DerType1::PlainObject> ReturnType;\n// };\n\n#define EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(FUNC,CODE) \\\n  template<typename DerType> \\\n  inline const Eigen::AutoDiffScalar< \\\n  EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(typename Eigen::internal::remove_all<DerType>::type, typename Eigen::internal::traits<typename Eigen::internal::remove_all<DerType>::type>::Scalar, product) > \\\n  FUNC(const Eigen::AutoDiffScalar<DerType>& x) { \\\n    using namespace Eigen; \\\n    typedef typename Eigen::internal::traits<typename Eigen::internal::remove_all<DerType>::type>::Scalar Scalar; \\\n    EIGEN_UNUSED_VARIABLE(sizeof(Scalar)); \\\n    CODE; \\\n  }\n\ntemplate<typename DerType>\nstruct CleanedUpDerType {\n  typedef AutoDiffScalar<typename Eigen::internal::remove_all<DerType>::type::PlainObject> type;\n};\n\ntemplate<typename DerType>\ninline const AutoDiffScalar<DerType>& conj(const AutoDiffScalar<DerType>& x)  { return x; }\ntemplate<typename DerType>\ninline const AutoDiffScalar<DerType>& real(const AutoDiffScalar<DerType>& x)  { return x; }\ntemplate<typename DerType>\ninline typename DerType::Scalar imag(const AutoDiffScalar<DerType>&)    { return 0.; }\ntemplate<typename DerType, typename T>\ninline typename CleanedUpDerType<DerType>::type (min)(const AutoDiffScalar<DerType>& x, const T& y) {\n  typedef typename CleanedUpDerType<DerType>::type ADS;\n  return (x <= y ? ADS(x) : ADS(y));\n}\ntemplate<typename DerType, typename T>\ninline typename CleanedUpDerType<DerType>::type (max)(const AutoDiffScalar<DerType>& x, const T& y) {\n  typedef typename CleanedUpDerType<DerType>::type ADS;\n  return (x >= y ? ADS(x) : ADS(y));\n}\ntemplate<typename DerType, typename T>\ninline typename CleanedUpDerType<DerType>::type (min)(const T& x, const AutoDiffScalar<DerType>& y) {\n  typedef typename CleanedUpDerType<DerType>::type ADS;\n  return (x < y ? ADS(x) : ADS(y));\n}\ntemplate<typename DerType, typename T>\ninline typename CleanedUpDerType<DerType>::type (max)(const T& x, const AutoDiffScalar<DerType>& y) {\n  typedef typename CleanedUpDerType<DerType>::type ADS;\n  return (x > y ? ADS(x) : ADS(y));\n}\ntemplate<typename DerType>\ninline typename CleanedUpDerType<DerType>::type (min)(const AutoDiffScalar<DerType>& x, const AutoDiffScalar<DerType>& y) {\n  return (x.value() < y.value() ? x : y);\n}\ntemplate<typename DerType>\ninline typename CleanedUpDerType<DerType>::type (max)(const AutoDiffScalar<DerType>& x, const AutoDiffScalar<DerType>& y) {\n  return (x.value() >= y.value() ? x : y);\n}\n\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(abs,\n  using std::abs;\n  return Eigen::MakeAutoDiffScalar(abs(x.value()), x.derivatives() * (x.value()<0 ? -1 : 1) );)\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(abs2,\n  using numext::abs2;\n  return Eigen::MakeAutoDiffScalar(abs2(x.value()), x.derivatives() * (Scalar(2)*x.value()));)\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(sqrt,\n  using std::sqrt;\n  Scalar sqrtx = sqrt(x.value());\n  return Eigen::MakeAutoDiffScalar(sqrtx,x.derivatives() * (Scalar(0.5) / sqrtx));)\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(cos,\n  using std::cos;\n  using std::sin;\n  return Eigen::MakeAutoDiffScalar(cos(x.value()), x.derivatives() * (-sin(x.value())));)\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(sin,\n  using std::sin;\n  using std::cos;\n  return Eigen::MakeAutoDiffScalar(sin(x.value()),x.derivatives() * cos(x.value()));)\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(exp,\n  using std::exp;\n  Scalar expx = exp(x.value());\n  return Eigen::MakeAutoDiffScalar(expx,x.derivatives() * expx);)\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(log,\n  using std::log;\n  return Eigen::MakeAutoDiffScalar(log(x.value()),x.derivatives() * (Scalar(1)/x.value()));)\n\ntemplate<typename DerType>\ninline const Eigen::AutoDiffScalar<\nEIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(typename internal::remove_all<DerType>::type,typename internal::traits<typename internal::remove_all<DerType>::type>::Scalar,product) >\npow(const Eigen::AutoDiffScalar<DerType> &x, const typename internal::traits<typename internal::remove_all<DerType>::type>::Scalar &y)\n{\n  using namespace Eigen;\n  using std::pow;\n  return Eigen::MakeAutoDiffScalar(pow(x.value(),y), x.derivatives() * (y * pow(x.value(),y-1)));\n}\n\n\ntemplate<typename DerTypeA,typename DerTypeB>\ninline const AutoDiffScalar<Matrix<typename internal::traits<typename internal::remove_all<DerTypeA>::type>::Scalar,Dynamic,1> >\natan2(const AutoDiffScalar<DerTypeA>& a, const AutoDiffScalar<DerTypeB>& b)\n{\n  using std::atan2;\n  typedef typename internal::traits<typename internal::remove_all<DerTypeA>::type>::Scalar Scalar;\n  typedef AutoDiffScalar<Matrix<Scalar,Dynamic,1> > PlainADS;\n  PlainADS ret;\n  ret.value() = atan2(a.value(), b.value());\n  \n  Scalar squared_hypot = a.value() * a.value() + b.value() * b.value();\n  \n  // if (squared_hypot==0) the derivation is undefined and the following results in a NaN:\n  ret.derivatives() = (a.derivatives() * b.value() - a.value() * b.derivatives()) / squared_hypot;\n\n  return ret;\n}\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(tan,\n  using std::tan;\n  using std::cos;\n  return Eigen::MakeAutoDiffScalar(tan(x.value()),x.derivatives() * (Scalar(1)/numext::abs2(cos(x.value()))));)\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(asin,\n  using std::sqrt;\n  using std::asin;\n  return Eigen::MakeAutoDiffScalar(asin(x.value()),x.derivatives() * (Scalar(1)/sqrt(1-numext::abs2(x.value()))));)\n  \nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(acos,\n  using std::sqrt;\n  using std::acos;\n  return Eigen::MakeAutoDiffScalar(acos(x.value()),x.derivatives() * (Scalar(-1)/sqrt(1-numext::abs2(x.value()))));)\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(tanh,\n  using std::cosh;\n  using std::tanh;\n  return Eigen::MakeAutoDiffScalar(tanh(x.value()),x.derivatives() * (Scalar(1)/numext::abs2(cosh(x.value()))));)\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(sinh,\n  using std::sinh;\n  using std::cosh;\n  return Eigen::MakeAutoDiffScalar(sinh(x.value()),x.derivatives() * cosh(x.value()));)\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(cosh,\n  using std::sinh;\n  using std::cosh;\n  return Eigen::MakeAutoDiffScalar(cosh(x.value()),x.derivatives() * sinh(x.value()));)\n\n#undef EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY\n\ntemplate<typename DerType> struct NumTraits<AutoDiffScalar<DerType> >\n  : NumTraits< typename NumTraits<typename internal::remove_all<DerType>::type::Scalar>::Real >\n{\n  typedef typename internal::remove_all<DerType>::type DerTypeCleaned;\n  typedef AutoDiffScalar<Matrix<typename NumTraits<typename DerTypeCleaned::Scalar>::Real,DerTypeCleaned::RowsAtCompileTime,DerTypeCleaned::ColsAtCompileTime,\n                                0, DerTypeCleaned::MaxRowsAtCompileTime, DerTypeCleaned::MaxColsAtCompileTime> > Real;\n  typedef AutoDiffScalar<DerType> NonInteger;\n  typedef AutoDiffScalar<DerType> Nested;\n  typedef typename NumTraits<typename DerTypeCleaned::Scalar>::Literal Literal;\n  enum{\n    RequireInitialization = 1\n  };\n};\n\n}\n\nnamespace std {\n\ntemplate <typename T>\nclass numeric_limits<Eigen::AutoDiffScalar<T> >\n  : public numeric_limits<typename T::Scalar> {};\n\ntemplate <typename T>\nclass numeric_limits<Eigen::AutoDiffScalar<T&> >\n  : public numeric_limits<typename T::Scalar> {};\n\n}  // namespace std\n\n#endif // EIGEN_AUTODIFF_SCALAR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/AutoDiff/AutoDiffVector.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_AUTODIFF_VECTOR_H\n#define EIGEN_AUTODIFF_VECTOR_H\n\nnamespace Eigen {\n\n/* \\class AutoDiffScalar\n  * \\brief A scalar type replacement with automatic differentation capability\n  *\n  * \\param DerType the vector type used to store/represent the derivatives (e.g. Vector3f)\n  *\n  * This class represents a scalar value while tracking its respective derivatives.\n  *\n  * It supports the following list of global math function:\n  *  - std::abs, std::sqrt, std::pow, std::exp, std::log, std::sin, std::cos,\n  *  - internal::abs, internal::sqrt, numext::pow, internal::exp, internal::log, internal::sin, internal::cos,\n  *  - internal::conj, internal::real, internal::imag, numext::abs2.\n  *\n  * AutoDiffScalar can be used as the scalar type of an Eigen::Matrix object. However,\n  * in that case, the expression template mechanism only occurs at the top Matrix level,\n  * while derivatives are computed right away.\n  *\n  */\ntemplate<typename ValueType, typename JacobianType>\nclass AutoDiffVector\n{\n  public:\n    //typedef typename internal::traits<ValueType>::Scalar Scalar;\n    typedef typename internal::traits<ValueType>::Scalar BaseScalar;\n    typedef AutoDiffScalar<Matrix<BaseScalar,JacobianType::RowsAtCompileTime,1> > ActiveScalar;\n    typedef ActiveScalar Scalar;\n    typedef AutoDiffScalar<typename JacobianType::ColXpr> CoeffType;\n    typedef typename JacobianType::Index Index;\n\n    inline AutoDiffVector() {}\n\n    inline AutoDiffVector(const ValueType& values)\n      : m_values(values)\n    {\n      m_jacobian.setZero();\n    }\n\n\n    CoeffType operator[] (Index i) { return CoeffType(m_values[i], m_jacobian.col(i)); }\n    const CoeffType operator[] (Index i) const { return CoeffType(m_values[i], m_jacobian.col(i)); }\n\n    CoeffType operator() (Index i) { return CoeffType(m_values[i], m_jacobian.col(i)); }\n    const CoeffType operator() (Index i) const { return CoeffType(m_values[i], m_jacobian.col(i)); }\n\n    CoeffType coeffRef(Index i) { return CoeffType(m_values[i], m_jacobian.col(i)); }\n    const CoeffType coeffRef(Index i) const { return CoeffType(m_values[i], m_jacobian.col(i)); }\n\n    Index size() const { return m_values.size(); }\n\n    // FIXME here we could return an expression of the sum\n    Scalar sum() const { /*std::cerr << \"sum \\n\\n\";*/ /*std::cerr << m_jacobian.rowwise().sum() << \"\\n\\n\";*/ return Scalar(m_values.sum(), m_jacobian.rowwise().sum()); }\n\n\n    inline AutoDiffVector(const ValueType& values, const JacobianType& jac)\n      : m_values(values), m_jacobian(jac)\n    {}\n\n    template<typename OtherValueType, typename OtherJacobianType>\n    inline AutoDiffVector(const AutoDiffVector<OtherValueType, OtherJacobianType>& other)\n      : m_values(other.values()), m_jacobian(other.jacobian())\n    {}\n\n    inline AutoDiffVector(const AutoDiffVector& other)\n      : m_values(other.values()), m_jacobian(other.jacobian())\n    {}\n\n    template<typename OtherValueType, typename OtherJacobianType>\n    inline AutoDiffVector& operator=(const AutoDiffVector<OtherValueType, OtherJacobianType>& other)\n    {\n      m_values = other.values();\n      m_jacobian = other.jacobian();\n      return *this;\n    }\n\n    inline AutoDiffVector& operator=(const AutoDiffVector& other)\n    {\n      m_values = other.values();\n      m_jacobian = other.jacobian();\n      return *this;\n    }\n\n    inline const ValueType& values() const { return m_values; }\n    inline ValueType& values() { return m_values; }\n\n    inline const JacobianType& jacobian() const { return m_jacobian; }\n    inline JacobianType& jacobian() { return m_jacobian; }\n\n    template<typename OtherValueType,typename OtherJacobianType>\n    inline const AutoDiffVector<\n      typename MakeCwiseBinaryOp<internal::scalar_sum_op<BaseScalar>,ValueType,OtherValueType>::Type,\n      typename MakeCwiseBinaryOp<internal::scalar_sum_op<BaseScalar>,JacobianType,OtherJacobianType>::Type >\n    operator+(const AutoDiffVector<OtherValueType,OtherJacobianType>& other) const\n    {\n      return AutoDiffVector<\n      typename MakeCwiseBinaryOp<internal::scalar_sum_op<BaseScalar>,ValueType,OtherValueType>::Type,\n      typename MakeCwiseBinaryOp<internal::scalar_sum_op<BaseScalar>,JacobianType,OtherJacobianType>::Type >(\n        m_values + other.values(),\n        m_jacobian + other.jacobian());\n    }\n\n    template<typename OtherValueType, typename OtherJacobianType>\n    inline AutoDiffVector&\n    operator+=(const AutoDiffVector<OtherValueType,OtherJacobianType>& other)\n    {\n      m_values += other.values();\n      m_jacobian += other.jacobian();\n      return *this;\n    }\n\n    template<typename OtherValueType,typename OtherJacobianType>\n    inline const AutoDiffVector<\n      typename MakeCwiseBinaryOp<internal::scalar_difference_op<Scalar>,ValueType,OtherValueType>::Type,\n      typename MakeCwiseBinaryOp<internal::scalar_difference_op<Scalar>,JacobianType,OtherJacobianType>::Type >\n    operator-(const AutoDiffVector<OtherValueType,OtherJacobianType>& other) const\n    {\n      return AutoDiffVector<\n        typename MakeCwiseBinaryOp<internal::scalar_difference_op<Scalar>,ValueType,OtherValueType>::Type,\n        typename MakeCwiseBinaryOp<internal::scalar_difference_op<Scalar>,JacobianType,OtherJacobianType>::Type >(\n          m_values - other.values(),\n          m_jacobian - other.jacobian());\n    }\n\n    template<typename OtherValueType, typename OtherJacobianType>\n    inline AutoDiffVector&\n    operator-=(const AutoDiffVector<OtherValueType,OtherJacobianType>& other)\n    {\n      m_values -= other.values();\n      m_jacobian -= other.jacobian();\n      return *this;\n    }\n\n    inline const AutoDiffVector<\n      typename MakeCwiseUnaryOp<internal::scalar_opposite_op<Scalar>, ValueType>::Type,\n      typename MakeCwiseUnaryOp<internal::scalar_opposite_op<Scalar>, JacobianType>::Type >\n    operator-() const\n    {\n      return AutoDiffVector<\n        typename MakeCwiseUnaryOp<internal::scalar_opposite_op<Scalar>, ValueType>::Type,\n        typename MakeCwiseUnaryOp<internal::scalar_opposite_op<Scalar>, JacobianType>::Type >(\n          -m_values,\n          -m_jacobian);\n    }\n\n    inline const AutoDiffVector<\n      typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, ValueType>::Type,\n      typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, JacobianType>::Type>\n    operator*(const BaseScalar& other) const\n    {\n      return AutoDiffVector<\n        typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, ValueType>::Type,\n        typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, JacobianType>::Type >(\n          m_values * other,\n          m_jacobian * other);\n    }\n\n    friend inline const AutoDiffVector<\n      typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, ValueType>::Type,\n      typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, JacobianType>::Type >\n    operator*(const Scalar& other, const AutoDiffVector& v)\n    {\n      return AutoDiffVector<\n        typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, ValueType>::Type,\n        typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, JacobianType>::Type >(\n          v.values() * other,\n          v.jacobian() * other);\n    }\n\n//     template<typename OtherValueType,typename OtherJacobianType>\n//     inline const AutoDiffVector<\n//       CwiseBinaryOp<internal::scalar_multiple_op<Scalar>, ValueType, OtherValueType>\n//       CwiseBinaryOp<internal::scalar_sum_op<Scalar>,\n//         CwiseUnaryOp<internal::scalar_multiple_op<Scalar>, JacobianType>,\n//         CwiseUnaryOp<internal::scalar_multiple_op<Scalar>, OtherJacobianType> > >\n//     operator*(const AutoDiffVector<OtherValueType,OtherJacobianType>& other) const\n//     {\n//       return AutoDiffVector<\n//         CwiseBinaryOp<internal::scalar_multiple_op<Scalar>, ValueType, OtherValueType>\n//         CwiseBinaryOp<internal::scalar_sum_op<Scalar>,\n//           CwiseUnaryOp<internal::scalar_multiple_op<Scalar>, JacobianType>,\n//           CwiseUnaryOp<internal::scalar_multiple_op<Scalar>, OtherJacobianType> > >(\n//             m_values.cwise() * other.values(),\n//             (m_jacobian * other.values()) + (m_values * other.jacobian()));\n//     }\n\n    inline AutoDiffVector& operator*=(const Scalar& other)\n    {\n      m_values *= other;\n      m_jacobian *= other;\n      return *this;\n    }\n\n    template<typename OtherValueType,typename OtherJacobianType>\n    inline AutoDiffVector& operator*=(const AutoDiffVector<OtherValueType,OtherJacobianType>& other)\n    {\n      *this = *this * other;\n      return *this;\n    }\n\n  protected:\n    ValueType m_values;\n    JacobianType m_jacobian;\n\n};\n\n}\n\n#endif // EIGEN_AUTODIFF_VECTOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/BVH/BVAlgorithms.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Ilya Baran <ibaran@mit.edu>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BVALGORITHMS_H\n#define EIGEN_BVALGORITHMS_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename BVH, typename Intersector>\nbool intersect_helper(const BVH &tree, Intersector &intersector, typename BVH::Index root)\n{\n  typedef typename BVH::Index Index;\n  typedef typename BVH::VolumeIterator VolIter;\n  typedef typename BVH::ObjectIterator ObjIter;\n\n  VolIter vBegin = VolIter(), vEnd = VolIter();\n  ObjIter oBegin = ObjIter(), oEnd = ObjIter();\n\n  std::vector<Index> todo(1, root);\n\n  while(!todo.empty()) {\n    tree.getChildren(todo.back(), vBegin, vEnd, oBegin, oEnd);\n    todo.pop_back();\n\n    for(; vBegin != vEnd; ++vBegin) //go through child volumes\n      if(intersector.intersectVolume(tree.getVolume(*vBegin)))\n        todo.push_back(*vBegin);\n\n    for(; oBegin != oEnd; ++oBegin) //go through child objects\n      if(intersector.intersectObject(*oBegin))\n        return true; //intersector said to stop query\n  }\n  return false;\n}\n#endif //not EIGEN_PARSED_BY_DOXYGEN\n\ntemplate<typename Volume1, typename Object1, typename Object2, typename Intersector>\nstruct intersector_helper1\n{\n  intersector_helper1(const Object2 &inStored, Intersector &in) : stored(inStored), intersector(in) {}\n  bool intersectVolume(const Volume1 &vol) { return intersector.intersectVolumeObject(vol, stored); }\n  bool intersectObject(const Object1 &obj) { return intersector.intersectObjectObject(obj, stored); }\n  Object2 stored;\n  Intersector &intersector;\nprivate:\n  intersector_helper1& operator=(const intersector_helper1&);\n};\n\ntemplate<typename Volume2, typename Object2, typename Object1, typename Intersector>\nstruct intersector_helper2\n{\n  intersector_helper2(const Object1 &inStored, Intersector &in) : stored(inStored), intersector(in) {}\n  bool intersectVolume(const Volume2 &vol) { return intersector.intersectObjectVolume(stored, vol); }\n  bool intersectObject(const Object2 &obj) { return intersector.intersectObjectObject(stored, obj); }\n  Object1 stored;\n  Intersector &intersector;\nprivate:\n  intersector_helper2& operator=(const intersector_helper2&);\n};\n\n} // end namespace internal\n\n/**  Given a BVH, runs the query encapsulated by \\a intersector.\n  *  The Intersector type must provide the following members: \\code\n     bool intersectVolume(const BVH::Volume &volume) //returns true if volume intersects the query\n     bool intersectObject(const BVH::Object &object) //returns true if the search should terminate immediately\n  \\endcode\n  */\ntemplate<typename BVH, typename Intersector>\nvoid BVIntersect(const BVH &tree, Intersector &intersector)\n{\n  internal::intersect_helper(tree, intersector, tree.getRootIndex());\n}\n\n/**  Given two BVH's, runs the query on their Cartesian product encapsulated by \\a intersector.\n  *  The Intersector type must provide the following members: \\code\n     bool intersectVolumeVolume(const BVH1::Volume &v1, const BVH2::Volume &v2) //returns true if product of volumes intersects the query\n     bool intersectVolumeObject(const BVH1::Volume &v1, const BVH2::Object &o2) //returns true if the volume-object product intersects the query\n     bool intersectObjectVolume(const BVH1::Object &o1, const BVH2::Volume &v2) //returns true if the volume-object product intersects the query\n     bool intersectObjectObject(const BVH1::Object &o1, const BVH2::Object &o2) //returns true if the search should terminate immediately\n  \\endcode\n  */\ntemplate<typename BVH1, typename BVH2, typename Intersector>\nvoid BVIntersect(const BVH1 &tree1, const BVH2 &tree2, Intersector &intersector) //TODO: tandem descent when it makes sense\n{\n  typedef typename BVH1::Index Index1;\n  typedef typename BVH2::Index Index2;\n  typedef internal::intersector_helper1<typename BVH1::Volume, typename BVH1::Object, typename BVH2::Object, Intersector> Helper1;\n  typedef internal::intersector_helper2<typename BVH2::Volume, typename BVH2::Object, typename BVH1::Object, Intersector> Helper2;\n  typedef typename BVH1::VolumeIterator VolIter1;\n  typedef typename BVH1::ObjectIterator ObjIter1;\n  typedef typename BVH2::VolumeIterator VolIter2;\n  typedef typename BVH2::ObjectIterator ObjIter2;\n\n  VolIter1 vBegin1 = VolIter1(), vEnd1 = VolIter1();\n  ObjIter1 oBegin1 = ObjIter1(), oEnd1 = ObjIter1();\n  VolIter2 vBegin2 = VolIter2(), vEnd2 = VolIter2(), vCur2 = VolIter2();\n  ObjIter2 oBegin2 = ObjIter2(), oEnd2 = ObjIter2(), oCur2 = ObjIter2();\n\n  std::vector<std::pair<Index1, Index2> > todo(1, std::make_pair(tree1.getRootIndex(), tree2.getRootIndex()));\n\n  while(!todo.empty()) {\n    tree1.getChildren(todo.back().first, vBegin1, vEnd1, oBegin1, oEnd1);\n    tree2.getChildren(todo.back().second, vBegin2, vEnd2, oBegin2, oEnd2);\n    todo.pop_back();\n\n    for(; vBegin1 != vEnd1; ++vBegin1) { //go through child volumes of first tree\n      const typename BVH1::Volume &vol1 = tree1.getVolume(*vBegin1);\n      for(vCur2 = vBegin2; vCur2 != vEnd2; ++vCur2) { //go through child volumes of second tree\n        if(intersector.intersectVolumeVolume(vol1, tree2.getVolume(*vCur2)))\n          todo.push_back(std::make_pair(*vBegin1, *vCur2));\n      }\n\n      for(oCur2 = oBegin2; oCur2 != oEnd2; ++oCur2) {//go through child objects of second tree\n        Helper1 helper(*oCur2, intersector);\n        if(internal::intersect_helper(tree1, helper, *vBegin1))\n          return; //intersector said to stop query\n      }\n    }\n\n    for(; oBegin1 != oEnd1; ++oBegin1) { //go through child objects of first tree\n      for(vCur2 = vBegin2; vCur2 != vEnd2; ++vCur2) { //go through child volumes of second tree\n        Helper2 helper(*oBegin1, intersector);\n        if(internal::intersect_helper(tree2, helper, *vCur2))\n          return; //intersector said to stop query\n      }\n\n      for(oCur2 = oBegin2; oCur2 != oEnd2; ++oCur2) {//go through child objects of second tree\n        if(intersector.intersectObjectObject(*oBegin1, *oCur2))\n          return; //intersector said to stop query\n      }\n    }\n  }\n}\n\nnamespace internal {\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename BVH, typename Minimizer>\ntypename Minimizer::Scalar minimize_helper(const BVH &tree, Minimizer &minimizer, typename BVH::Index root, typename Minimizer::Scalar minimum)\n{\n  typedef typename Minimizer::Scalar Scalar;\n  typedef typename BVH::Index Index;\n  typedef std::pair<Scalar, Index> QueueElement; //first element is priority\n  typedef typename BVH::VolumeIterator VolIter;\n  typedef typename BVH::ObjectIterator ObjIter;\n\n  VolIter vBegin = VolIter(), vEnd = VolIter();\n  ObjIter oBegin = ObjIter(), oEnd = ObjIter();\n  std::priority_queue<QueueElement, std::vector<QueueElement>, std::greater<QueueElement> > todo; //smallest is at the top\n\n  todo.push(std::make_pair(Scalar(), root));\n\n  while(!todo.empty()) {\n    tree.getChildren(todo.top().second, vBegin, vEnd, oBegin, oEnd);\n    todo.pop();\n\n    for(; oBegin != oEnd; ++oBegin) //go through child objects\n      minimum = (std::min)(minimum, minimizer.minimumOnObject(*oBegin));\n\n    for(; vBegin != vEnd; ++vBegin) { //go through child volumes\n      Scalar val = minimizer.minimumOnVolume(tree.getVolume(*vBegin));\n      if(val < minimum)\n        todo.push(std::make_pair(val, *vBegin));\n    }\n  }\n\n  return minimum;\n}\n#endif //not EIGEN_PARSED_BY_DOXYGEN\n\n\ntemplate<typename Volume1, typename Object1, typename Object2, typename Minimizer>\nstruct minimizer_helper1\n{\n  typedef typename Minimizer::Scalar Scalar;\n  minimizer_helper1(const Object2 &inStored, Minimizer &m) : stored(inStored), minimizer(m) {}\n  Scalar minimumOnVolume(const Volume1 &vol) { return minimizer.minimumOnVolumeObject(vol, stored); }\n  Scalar minimumOnObject(const Object1 &obj) { return minimizer.minimumOnObjectObject(obj, stored); }\n  Object2 stored;\n  Minimizer &minimizer;\nprivate:\n  minimizer_helper1& operator=(const minimizer_helper1&);\n};\n\ntemplate<typename Volume2, typename Object2, typename Object1, typename Minimizer>\nstruct minimizer_helper2\n{\n  typedef typename Minimizer::Scalar Scalar;\n  minimizer_helper2(const Object1 &inStored, Minimizer &m) : stored(inStored), minimizer(m) {}\n  Scalar minimumOnVolume(const Volume2 &vol) { return minimizer.minimumOnObjectVolume(stored, vol); }\n  Scalar minimumOnObject(const Object2 &obj) { return minimizer.minimumOnObjectObject(stored, obj); }\n  Object1 stored;\n  Minimizer &minimizer;\nprivate:\n  minimizer_helper2& operator=(const minimizer_helper2&);\n};\n\n} // end namespace internal\n\n/**  Given a BVH, runs the query encapsulated by \\a minimizer.\n  *  \\returns the minimum value.\n  *  The Minimizer type must provide the following members: \\code\n     typedef Scalar //the numeric type of what is being minimized--not necessarily the Scalar type of the BVH (if it has one)\n     Scalar minimumOnVolume(const BVH::Volume &volume)\n     Scalar minimumOnObject(const BVH::Object &object)\n  \\endcode\n  */\ntemplate<typename BVH, typename Minimizer>\ntypename Minimizer::Scalar BVMinimize(const BVH &tree, Minimizer &minimizer)\n{\n  return internal::minimize_helper(tree, minimizer, tree.getRootIndex(), (std::numeric_limits<typename Minimizer::Scalar>::max)());\n}\n\n/**  Given two BVH's, runs the query on their cartesian product encapsulated by \\a minimizer.\n  *  \\returns the minimum value.\n  *  The Minimizer type must provide the following members: \\code\n     typedef Scalar //the numeric type of what is being minimized--not necessarily the Scalar type of the BVH (if it has one)\n     Scalar minimumOnVolumeVolume(const BVH1::Volume &v1, const BVH2::Volume &v2)\n     Scalar minimumOnVolumeObject(const BVH1::Volume &v1, const BVH2::Object &o2)\n     Scalar minimumOnObjectVolume(const BVH1::Object &o1, const BVH2::Volume &v2)\n     Scalar minimumOnObjectObject(const BVH1::Object &o1, const BVH2::Object &o2)\n  \\endcode\n  */\ntemplate<typename BVH1, typename BVH2, typename Minimizer>\ntypename Minimizer::Scalar BVMinimize(const BVH1 &tree1, const BVH2 &tree2, Minimizer &minimizer)\n{\n  typedef typename Minimizer::Scalar Scalar;\n  typedef typename BVH1::Index Index1;\n  typedef typename BVH2::Index Index2;\n  typedef internal::minimizer_helper1<typename BVH1::Volume, typename BVH1::Object, typename BVH2::Object, Minimizer> Helper1;\n  typedef internal::minimizer_helper2<typename BVH2::Volume, typename BVH2::Object, typename BVH1::Object, Minimizer> Helper2;\n  typedef std::pair<Scalar, std::pair<Index1, Index2> > QueueElement; //first element is priority\n  typedef typename BVH1::VolumeIterator VolIter1;\n  typedef typename BVH1::ObjectIterator ObjIter1;\n  typedef typename BVH2::VolumeIterator VolIter2;\n  typedef typename BVH2::ObjectIterator ObjIter2;\n\n  VolIter1 vBegin1 = VolIter1(), vEnd1 = VolIter1();\n  ObjIter1 oBegin1 = ObjIter1(), oEnd1 = ObjIter1();\n  VolIter2 vBegin2 = VolIter2(), vEnd2 = VolIter2(), vCur2 = VolIter2();\n  ObjIter2 oBegin2 = ObjIter2(), oEnd2 = ObjIter2(), oCur2 = ObjIter2();\n  std::priority_queue<QueueElement, std::vector<QueueElement>, std::greater<QueueElement> > todo; //smallest is at the top\n\n  Scalar minimum = (std::numeric_limits<Scalar>::max)();\n  todo.push(std::make_pair(Scalar(), std::make_pair(tree1.getRootIndex(), tree2.getRootIndex())));\n\n  while(!todo.empty()) {\n    tree1.getChildren(todo.top().second.first, vBegin1, vEnd1, oBegin1, oEnd1);\n    tree2.getChildren(todo.top().second.second, vBegin2, vEnd2, oBegin2, oEnd2);\n    todo.pop();\n\n    for(; oBegin1 != oEnd1; ++oBegin1) { //go through child objects of first tree\n      for(oCur2 = oBegin2; oCur2 != oEnd2; ++oCur2) {//go through child objects of second tree\n        minimum = (std::min)(minimum, minimizer.minimumOnObjectObject(*oBegin1, *oCur2));\n      }\n\n      for(vCur2 = vBegin2; vCur2 != vEnd2; ++vCur2) { //go through child volumes of second tree\n        Helper2 helper(*oBegin1, minimizer);\n        minimum = (std::min)(minimum, internal::minimize_helper(tree2, helper, *vCur2, minimum));\n      }\n    }\n\n    for(; vBegin1 != vEnd1; ++vBegin1) { //go through child volumes of first tree\n      const typename BVH1::Volume &vol1 = tree1.getVolume(*vBegin1);\n\n      for(oCur2 = oBegin2; oCur2 != oEnd2; ++oCur2) {//go through child objects of second tree\n        Helper1 helper(*oCur2, minimizer);\n        minimum = (std::min)(minimum, internal::minimize_helper(tree1, helper, *vBegin1, minimum));\n      }\n\n      for(vCur2 = vBegin2; vCur2 != vEnd2; ++vCur2) { //go through child volumes of second tree\n        Scalar val = minimizer.minimumOnVolumeVolume(vol1, tree2.getVolume(*vCur2));\n        if(val < minimum)\n          todo.push(std::make_pair(val, std::make_pair(*vBegin1, *vCur2)));\n      }\n    }\n  }\n  return minimum;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_BVALGORITHMS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/BVH/KdBVH.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Ilya Baran <ibaran@mit.edu>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef KDBVH_H_INCLUDED\n#define KDBVH_H_INCLUDED\n\nnamespace Eigen { \n\nnamespace internal {\n\n//internal pair class for the BVH--used instead of std::pair because of alignment\ntemplate<typename Scalar, int Dim>\nstruct vector_int_pair\n{\nEIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(Scalar, Dim)\n  typedef Matrix<Scalar, Dim, 1> VectorType;\n\n  vector_int_pair(const VectorType &v, int i) : first(v), second(i) {}\n\n  VectorType first;\n  int second;\n};\n\n//these templates help the tree initializer get the bounding boxes either from a provided\n//iterator range or using bounding_box in a unified way\ntemplate<typename ObjectList, typename VolumeList, typename BoxIter>\nstruct get_boxes_helper {\n  void operator()(const ObjectList &objects, BoxIter boxBegin, BoxIter boxEnd, VolumeList &outBoxes)\n  {\n    outBoxes.insert(outBoxes.end(), boxBegin, boxEnd);\n    eigen_assert(outBoxes.size() == objects.size());\n    EIGEN_ONLY_USED_FOR_DEBUG(objects);\n  }\n};\n\ntemplate<typename ObjectList, typename VolumeList>\nstruct get_boxes_helper<ObjectList, VolumeList, int> {\n  void operator()(const ObjectList &objects, int, int, VolumeList &outBoxes)\n  {\n    outBoxes.reserve(objects.size());\n    for(int i = 0; i < (int)objects.size(); ++i)\n      outBoxes.push_back(bounding_box(objects[i]));\n  }\n};\n\n} // end namespace internal\n\n\n/** \\class KdBVH\n *  \\brief A simple bounding volume hierarchy based on AlignedBox\n *\n *  \\param Scalar_ The underlying scalar type of the bounding boxes\n *  \\param Dim_ The dimension of the space in which the hierarchy lives\n *  \\param _Object The object type that lives in the hierarchy.  It must have value semantics.  Either bounding_box(_Object) must\n *                 be defined and return an AlignedBox<Scalar_, Dim_> or bounding boxes must be provided to the tree initializer.\n *\n *  This class provides a simple (as opposed to optimized) implementation of a bounding volume hierarchy analogous to a Kd-tree.\n *  Given a sequence of objects, it computes their bounding boxes, constructs a Kd-tree of their centers\n *  and builds a BVH with the structure of that Kd-tree.  When the elements of the tree are too expensive to be copied around,\n *  it is useful for _Object to be a pointer.\n */\ntemplate<typename Scalar_, int Dim_, typename _Object> class KdBVH\n{\npublic:\n  enum { Dim = Dim_ };\n  typedef _Object Object;\n  typedef std::vector<Object, aligned_allocator<Object> > ObjectList;\n  typedef Scalar_ Scalar;\n  typedef AlignedBox<Scalar, Dim> Volume;\n  typedef std::vector<Volume, aligned_allocator<Volume> > VolumeList;\n  typedef int Index;\n  typedef const int *VolumeIterator; //the iterators are just pointers into the tree's vectors\n  typedef const Object *ObjectIterator;\n\n  KdBVH() {}\n\n  /** Given an iterator range over \\a Object references, constructs the BVH.  Requires that bounding_box(Object) return a Volume. */\n  template<typename Iter> KdBVH(Iter begin, Iter end) { init(begin, end, 0, 0); } //int is recognized by init as not being an iterator type\n\n  /** Given an iterator range over \\a Object references and an iterator range over their bounding boxes, constructs the BVH */\n  template<typename OIter, typename BIter> KdBVH(OIter begin, OIter end, BIter boxBegin, BIter boxEnd) { init(begin, end, boxBegin, boxEnd); }\n\n  /** Given an iterator range over \\a Object references, constructs the BVH, overwriting whatever is in there currently.\n    * Requires that bounding_box(Object) return a Volume. */\n  template<typename Iter> void init(Iter begin, Iter end) { init(begin, end, 0, 0); }\n\n  /** Given an iterator range over \\a Object references and an iterator range over their bounding boxes,\n    * constructs the BVH, overwriting whatever is in there currently. */\n  template<typename OIter, typename BIter> void init(OIter begin, OIter end, BIter boxBegin, BIter boxEnd)\n  {\n    objects.clear();\n    boxes.clear();\n    children.clear();\n\n    objects.insert(objects.end(), begin, end);\n    int n = static_cast<int>(objects.size());\n\n    if(n < 2)\n      return; //if we have at most one object, we don't need any internal nodes\n\n    VolumeList objBoxes;\n    VIPairList objCenters;\n\n    //compute the bounding boxes depending on BIter type\n    internal::get_boxes_helper<ObjectList, VolumeList, BIter>()(objects, boxBegin, boxEnd, objBoxes);\n\n    objCenters.reserve(n);\n    boxes.reserve(n - 1);\n    children.reserve(2 * n - 2);\n\n    for(int i = 0; i < n; ++i)\n      objCenters.push_back(VIPair(objBoxes[i].center(), i));\n\n    build(objCenters, 0, n, objBoxes, 0); //the recursive part of the algorithm\n\n    ObjectList tmp(n);\n    tmp.swap(objects);\n    for(int i = 0; i < n; ++i)\n      objects[i] = tmp[objCenters[i].second];\n  }\n\n  /** \\returns the index of the root of the hierarchy */\n  inline Index getRootIndex() const { return (int)boxes.size() - 1; }\n\n  /** Given an \\a index of a node, on exit, \\a outVBegin and \\a outVEnd range over the indices of the volume children of the node\n    * and \\a outOBegin and \\a outOEnd range over the object children of the node */\n  EIGEN_STRONG_INLINE void getChildren(Index index, VolumeIterator &outVBegin, VolumeIterator &outVEnd,\n                                       ObjectIterator &outOBegin, ObjectIterator &outOEnd) const\n  { //inlining this function should open lots of optimization opportunities to the compiler\n    if(index < 0) {\n      outVBegin = outVEnd;\n      if(!objects.empty())\n        outOBegin = &(objects[0]);\n      outOEnd = outOBegin + objects.size(); //output all objects--necessary when the tree has only one object\n      return;\n    }\n\n    int numBoxes = static_cast<int>(boxes.size());\n\n    int idx = index * 2;\n    if(children[idx + 1] < numBoxes) { //second index is always bigger\n      outVBegin = &(children[idx]);\n      outVEnd = outVBegin + 2;\n      outOBegin = outOEnd;\n    }\n    else if(children[idx] >= numBoxes) { //if both children are objects\n      outVBegin = outVEnd;\n      outOBegin = &(objects[children[idx] - numBoxes]);\n      outOEnd = outOBegin + 2;\n    } else { //if the first child is a volume and the second is an object\n      outVBegin = &(children[idx]);\n      outVEnd = outVBegin + 1;\n      outOBegin = &(objects[children[idx + 1] - numBoxes]);\n      outOEnd = outOBegin + 1;\n    }\n  }\n\n  /** \\returns the bounding box of the node at \\a index */\n  inline const Volume &getVolume(Index index) const\n  {\n    return boxes[index];\n  }\n\nprivate:\n  typedef internal::vector_int_pair<Scalar, Dim> VIPair;\n  typedef std::vector<VIPair, aligned_allocator<VIPair> > VIPairList;\n  typedef Matrix<Scalar, Dim, 1> VectorType;\n  struct VectorComparator //compares vectors, or more specifically, VIPairs along a particular dimension\n  {\n    VectorComparator(int inDim) : dim(inDim) {}\n    inline bool operator()(const VIPair &v1, const VIPair &v2) const { return v1.first[dim] < v2.first[dim]; }\n    int dim;\n  };\n\n  //Build the part of the tree between objects[from] and objects[to] (not including objects[to]).\n  //This routine partitions the objCenters in [from, to) along the dimension dim, recursively constructs\n  //the two halves, and adds their parent node.  TODO: a cache-friendlier layout\n  void build(VIPairList &objCenters, int from, int to, const VolumeList &objBoxes, int dim)\n  {\n    eigen_assert(to - from > 1);\n    if(to - from == 2) {\n      boxes.push_back(objBoxes[objCenters[from].second].merged(objBoxes[objCenters[from + 1].second]));\n      children.push_back(from + (int)objects.size() - 1); //there are objects.size() - 1 tree nodes\n      children.push_back(from + (int)objects.size());\n    }\n    else if(to - from == 3) {\n      int mid = from + 2;\n      std::nth_element(objCenters.begin() + from, objCenters.begin() + mid,\n                        objCenters.begin() + to, VectorComparator(dim)); //partition\n      build(objCenters, from, mid, objBoxes, (dim + 1) % Dim);\n      int idx1 = (int)boxes.size() - 1;\n      boxes.push_back(boxes[idx1].merged(objBoxes[objCenters[mid].second]));\n      children.push_back(idx1);\n      children.push_back(mid + (int)objects.size() - 1);\n    }\n    else {\n      int mid = from + (to - from) / 2;\n      nth_element(objCenters.begin() + from, objCenters.begin() + mid,\n                  objCenters.begin() + to, VectorComparator(dim)); //partition\n      build(objCenters, from, mid, objBoxes, (dim + 1) % Dim);\n      int idx1 = (int)boxes.size() - 1;\n      build(objCenters, mid, to, objBoxes, (dim + 1) % Dim);\n      int idx2 = (int)boxes.size() - 1;\n      boxes.push_back(boxes[idx1].merged(boxes[idx2]));\n      children.push_back(idx1);\n      children.push_back(idx2);\n    }\n  }\n\n  std::vector<int> children; //children of x are children[2x] and children[2x+1], indices bigger than boxes.size() index into objects.\n  VolumeList boxes;\n  ObjectList objects;\n};\n\n} // end namespace Eigen\n\n#endif //KDBVH_H_INCLUDED\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/Eigenvalues/ArpackSelfAdjointEigenSolver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 David Harmon <dharmon@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ARPACKGENERALIZEDSELFADJOINTEIGENSOLVER_H\n#define EIGEN_ARPACKGENERALIZEDSELFADJOINTEIGENSOLVER_H\n\n#include \"../../../../Eigen/Dense\"\n\nnamespace Eigen { \n\nnamespace internal {\n  template<typename Scalar, typename RealScalar> struct arpack_wrapper;\n  template<typename MatrixSolver, typename MatrixType, typename Scalar, bool BisSPD> struct OP;\n}\n\n\n\ntemplate<typename MatrixType, typename MatrixSolver=SimplicialLLT<MatrixType>, bool BisSPD=false>\nclass ArpackGeneralizedSelfAdjointEigenSolver\n{\npublic:\n  //typedef typename MatrixSolver::MatrixType MatrixType;\n\n  /** \\brief Scalar type for matrices of type \\p MatrixType. */\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::Index Index;\n\n  /** \\brief Real scalar type for \\p MatrixType.\n   *\n   * This is just \\c Scalar if #Scalar is real (e.g., \\c float or\n   * \\c Scalar), and the type of the real part of \\c Scalar if #Scalar is\n   * complex.\n   */\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  /** \\brief Type for vector of eigenvalues as returned by eigenvalues().\n   *\n   * This is a column vector with entries of type #RealScalar.\n   * The length of the vector is the size of \\p nbrEigenvalues.\n   */\n  typedef typename internal::plain_col_type<MatrixType, RealScalar>::type RealVectorType;\n\n  /** \\brief Default constructor.\n   *\n   * The default constructor is for cases in which the user intends to\n   * perform decompositions via compute().\n   *\n   */\n  ArpackGeneralizedSelfAdjointEigenSolver()\n   : m_eivec(),\n     m_eivalues(),\n     m_isInitialized(false),\n     m_eigenvectorsOk(false),\n     m_nbrConverged(0),\n     m_nbrIterations(0)\n  { }\n\n  /** \\brief Constructor; computes generalized eigenvalues of given matrix with respect to another matrix.\n   *\n   * \\param[in] A Self-adjoint matrix whose eigenvalues / eigenvectors will\n   *    computed. By default, the upper triangular part is used, but can be changed\n   *    through the template parameter.\n   * \\param[in] B Self-adjoint matrix for the generalized eigenvalue problem.\n   * \\param[in] nbrEigenvalues The number of eigenvalues / eigenvectors to compute.\n   *    Must be less than the size of the input matrix, or an error is returned.\n   * \\param[in] eigs_sigma String containing either \"LM\", \"SM\", \"LA\", or \"SA\", with\n   *    respective meanings to find the largest magnitude , smallest magnitude,\n   *    largest algebraic, or smallest algebraic eigenvalues. Alternatively, this\n   *    value can contain floating point value in string form, in which case the\n   *    eigenvalues closest to this value will be found.\n   * \\param[in]  options Can be #ComputeEigenvectors (default) or #EigenvaluesOnly.\n   * \\param[in] tol What tolerance to find the eigenvalues to. Default is 0, which\n   *    means machine precision.\n   *\n   * This constructor calls compute(const MatrixType&, const MatrixType&, Index, string, int, RealScalar)\n   * to compute the eigenvalues of the matrix \\p A with respect to \\p B. The eigenvectors are computed if\n   * \\p options equals #ComputeEigenvectors.\n   *\n   */\n  ArpackGeneralizedSelfAdjointEigenSolver(const MatrixType& A, const MatrixType& B,\n                                          Index nbrEigenvalues, std::string eigs_sigma=\"LM\",\n                               int options=ComputeEigenvectors, RealScalar tol=0.0)\n    : m_eivec(),\n      m_eivalues(),\n      m_isInitialized(false),\n      m_eigenvectorsOk(false),\n      m_nbrConverged(0),\n      m_nbrIterations(0)\n  {\n    compute(A, B, nbrEigenvalues, eigs_sigma, options, tol);\n  }\n\n  /** \\brief Constructor; computes eigenvalues of given matrix.\n   *\n   * \\param[in] A Self-adjoint matrix whose eigenvalues / eigenvectors will\n   *    computed. By default, the upper triangular part is used, but can be changed\n   *    through the template parameter.\n   * \\param[in] nbrEigenvalues The number of eigenvalues / eigenvectors to compute.\n   *    Must be less than the size of the input matrix, or an error is returned.\n   * \\param[in] eigs_sigma String containing either \"LM\", \"SM\", \"LA\", or \"SA\", with\n   *    respective meanings to find the largest magnitude , smallest magnitude,\n   *    largest algebraic, or smallest algebraic eigenvalues. Alternatively, this\n   *    value can contain floating point value in string form, in which case the\n   *    eigenvalues closest to this value will be found.\n   * \\param[in]  options Can be #ComputeEigenvectors (default) or #EigenvaluesOnly.\n   * \\param[in] tol What tolerance to find the eigenvalues to. Default is 0, which\n   *    means machine precision.\n   *\n   * This constructor calls compute(const MatrixType&, Index, string, int, RealScalar)\n   * to compute the eigenvalues of the matrix \\p A. The eigenvectors are computed if\n   * \\p options equals #ComputeEigenvectors.\n   *\n   */\n\n  ArpackGeneralizedSelfAdjointEigenSolver(const MatrixType& A,\n                                          Index nbrEigenvalues, std::string eigs_sigma=\"LM\",\n                               int options=ComputeEigenvectors, RealScalar tol=0.0)\n    : m_eivec(),\n      m_eivalues(),\n      m_isInitialized(false),\n      m_eigenvectorsOk(false),\n      m_nbrConverged(0),\n      m_nbrIterations(0)\n  {\n    compute(A, nbrEigenvalues, eigs_sigma, options, tol);\n  }\n\n\n  /** \\brief Computes generalized eigenvalues / eigenvectors of given matrix using the external ARPACK library.\n   *\n   * \\param[in]  A  Selfadjoint matrix whose eigendecomposition is to be computed.\n   * \\param[in]  B  Selfadjoint matrix for generalized eigenvalues.\n   * \\param[in] nbrEigenvalues The number of eigenvalues / eigenvectors to compute.\n   *    Must be less than the size of the input matrix, or an error is returned.\n   * \\param[in] eigs_sigma String containing either \"LM\", \"SM\", \"LA\", or \"SA\", with\n   *    respective meanings to find the largest magnitude , smallest magnitude,\n   *    largest algebraic, or smallest algebraic eigenvalues. Alternatively, this\n   *    value can contain floating point value in string form, in which case the\n   *    eigenvalues closest to this value will be found.\n   * \\param[in]  options Can be #ComputeEigenvectors (default) or #EigenvaluesOnly.\n   * \\param[in] tol What tolerance to find the eigenvalues to. Default is 0, which\n   *    means machine precision.\n   *\n   * \\returns    Reference to \\c *this\n   *\n   * This function computes the generalized eigenvalues of \\p A with respect to \\p B using ARPACK.  The eigenvalues()\n   * function can be used to retrieve them.  If \\p options equals #ComputeEigenvectors,\n   * then the eigenvectors are also computed and can be retrieved by\n   * calling eigenvectors().\n   *\n   */\n  ArpackGeneralizedSelfAdjointEigenSolver& compute(const MatrixType& A, const MatrixType& B,\n                                                   Index nbrEigenvalues, std::string eigs_sigma=\"LM\",\n                                        int options=ComputeEigenvectors, RealScalar tol=0.0);\n  \n  /** \\brief Computes eigenvalues / eigenvectors of given matrix using the external ARPACK library.\n   *\n   * \\param[in]  A  Selfadjoint matrix whose eigendecomposition is to be computed.\n   * \\param[in] nbrEigenvalues The number of eigenvalues / eigenvectors to compute.\n   *    Must be less than the size of the input matrix, or an error is returned.\n   * \\param[in] eigs_sigma String containing either \"LM\", \"SM\", \"LA\", or \"SA\", with\n   *    respective meanings to find the largest magnitude , smallest magnitude,\n   *    largest algebraic, or smallest algebraic eigenvalues. Alternatively, this\n   *    value can contain floating point value in string form, in which case the\n   *    eigenvalues closest to this value will be found.\n   * \\param[in]  options Can be #ComputeEigenvectors (default) or #EigenvaluesOnly.\n   * \\param[in] tol What tolerance to find the eigenvalues to. Default is 0, which\n   *    means machine precision.\n   *\n   * \\returns    Reference to \\c *this\n   *\n   * This function computes the eigenvalues of \\p A using ARPACK.  The eigenvalues()\n   * function can be used to retrieve them.  If \\p options equals #ComputeEigenvectors,\n   * then the eigenvectors are also computed and can be retrieved by\n   * calling eigenvectors().\n   *\n   */\n  ArpackGeneralizedSelfAdjointEigenSolver& compute(const MatrixType& A,\n                                                   Index nbrEigenvalues, std::string eigs_sigma=\"LM\",\n                                        int options=ComputeEigenvectors, RealScalar tol=0.0);\n\n\n  /** \\brief Returns the eigenvectors of given matrix.\n   *\n   * \\returns  A const reference to the matrix whose columns are the eigenvectors.\n   *\n   * \\pre The eigenvectors have been computed before.\n   *\n   * Column \\f$ k \\f$ of the returned matrix is an eigenvector corresponding\n   * to eigenvalue number \\f$ k \\f$ as returned by eigenvalues().  The\n   * eigenvectors are normalized to have (Euclidean) norm equal to one. If\n   * this object was used to solve the eigenproblem for the selfadjoint\n   * matrix \\f$ A \\f$, then the matrix returned by this function is the\n   * matrix \\f$ V \\f$ in the eigendecomposition \\f$ A V = D V \\f$.\n   * For the generalized eigenproblem, the matrix returned is the solution \\f$ A V = D B V \\f$\n   *\n   * Example: \\include SelfAdjointEigenSolver_eigenvectors.cpp\n   * Output: \\verbinclude SelfAdjointEigenSolver_eigenvectors.out\n   *\n   * \\sa eigenvalues()\n   */\n  const Matrix<Scalar, Dynamic, Dynamic>& eigenvectors() const\n  {\n    eigen_assert(m_isInitialized && \"ArpackGeneralizedSelfAdjointEigenSolver is not initialized.\");\n    eigen_assert(m_eigenvectorsOk && \"The eigenvectors have not been computed together with the eigenvalues.\");\n    return m_eivec;\n  }\n\n  /** \\brief Returns the eigenvalues of given matrix.\n   *\n   * \\returns A const reference to the column vector containing the eigenvalues.\n   *\n   * \\pre The eigenvalues have been computed before.\n   *\n   * The eigenvalues are repeated according to their algebraic multiplicity,\n   * so there are as many eigenvalues as rows in the matrix. The eigenvalues\n   * are sorted in increasing order.\n   *\n   * Example: \\include SelfAdjointEigenSolver_eigenvalues.cpp\n   * Output: \\verbinclude SelfAdjointEigenSolver_eigenvalues.out\n   *\n   * \\sa eigenvectors(), MatrixBase::eigenvalues()\n   */\n  const Matrix<Scalar, Dynamic, 1>& eigenvalues() const\n  {\n    eigen_assert(m_isInitialized && \"ArpackGeneralizedSelfAdjointEigenSolver is not initialized.\");\n    return m_eivalues;\n  }\n\n  /** \\brief Computes the positive-definite square root of the matrix.\n   *\n   * \\returns the positive-definite square root of the matrix\n   *\n   * \\pre The eigenvalues and eigenvectors of a positive-definite matrix\n   * have been computed before.\n   *\n   * The square root of a positive-definite matrix \\f$ A \\f$ is the\n   * positive-definite matrix whose square equals \\f$ A \\f$. This function\n   * uses the eigendecomposition \\f$ A = V D V^{-1} \\f$ to compute the\n   * square root as \\f$ A^{1/2} = V D^{1/2} V^{-1} \\f$.\n   *\n   * Example: \\include SelfAdjointEigenSolver_operatorSqrt.cpp\n   * Output: \\verbinclude SelfAdjointEigenSolver_operatorSqrt.out\n   *\n   * \\sa operatorInverseSqrt(),\n   *     \\ref MatrixFunctions_Module \"MatrixFunctions Module\"\n   */\n  Matrix<Scalar, Dynamic, Dynamic> operatorSqrt() const\n  {\n    eigen_assert(m_isInitialized && \"SelfAdjointEigenSolver is not initialized.\");\n    eigen_assert(m_eigenvectorsOk && \"The eigenvectors have not been computed together with the eigenvalues.\");\n    return m_eivec * m_eivalues.cwiseSqrt().asDiagonal() * m_eivec.adjoint();\n  }\n\n  /** \\brief Computes the inverse square root of the matrix.\n   *\n   * \\returns the inverse positive-definite square root of the matrix\n   *\n   * \\pre The eigenvalues and eigenvectors of a positive-definite matrix\n   * have been computed before.\n   *\n   * This function uses the eigendecomposition \\f$ A = V D V^{-1} \\f$ to\n   * compute the inverse square root as \\f$ V D^{-1/2} V^{-1} \\f$. This is\n   * cheaper than first computing the square root with operatorSqrt() and\n   * then its inverse with MatrixBase::inverse().\n   *\n   * Example: \\include SelfAdjointEigenSolver_operatorInverseSqrt.cpp\n   * Output: \\verbinclude SelfAdjointEigenSolver_operatorInverseSqrt.out\n   *\n   * \\sa operatorSqrt(), MatrixBase::inverse(),\n   *     \\ref MatrixFunctions_Module \"MatrixFunctions Module\"\n   */\n  Matrix<Scalar, Dynamic, Dynamic> operatorInverseSqrt() const\n  {\n    eigen_assert(m_isInitialized && \"SelfAdjointEigenSolver is not initialized.\");\n    eigen_assert(m_eigenvectorsOk && \"The eigenvectors have not been computed together with the eigenvalues.\");\n    return m_eivec * m_eivalues.cwiseInverse().cwiseSqrt().asDiagonal() * m_eivec.adjoint();\n  }\n\n  /** \\brief Reports whether previous computation was successful.\n   *\n   * \\returns \\c Success if computation was successful, \\c NoConvergence otherwise.\n   */\n  ComputationInfo info() const\n  {\n    eigen_assert(m_isInitialized && \"ArpackGeneralizedSelfAdjointEigenSolver is not initialized.\");\n    return m_info;\n  }\n\n  size_t getNbrConvergedEigenValues() const\n  { return m_nbrConverged; }\n\n  size_t getNbrIterations() const\n  { return m_nbrIterations; }\n\nprotected:\n  Matrix<Scalar, Dynamic, Dynamic> m_eivec;\n  Matrix<Scalar, Dynamic, 1> m_eivalues;\n  ComputationInfo m_info;\n  bool m_isInitialized;\n  bool m_eigenvectorsOk;\n\n  size_t m_nbrConverged;\n  size_t m_nbrIterations;\n};\n\n\n\n\n\ntemplate<typename MatrixType, typename MatrixSolver, bool BisSPD>\nArpackGeneralizedSelfAdjointEigenSolver<MatrixType, MatrixSolver, BisSPD>&\n    ArpackGeneralizedSelfAdjointEigenSolver<MatrixType, MatrixSolver, BisSPD>\n::compute(const MatrixType& A, Index nbrEigenvalues,\n          std::string eigs_sigma, int options, RealScalar tol)\n{\n    MatrixType B(0,0);\n    compute(A, B, nbrEigenvalues, eigs_sigma, options, tol);\n    \n    return *this;\n}\n\n\ntemplate<typename MatrixType, typename MatrixSolver, bool BisSPD>\nArpackGeneralizedSelfAdjointEigenSolver<MatrixType, MatrixSolver, BisSPD>&\n    ArpackGeneralizedSelfAdjointEigenSolver<MatrixType, MatrixSolver, BisSPD>\n::compute(const MatrixType& A, const MatrixType& B, Index nbrEigenvalues,\n          std::string eigs_sigma, int options, RealScalar tol)\n{\n  eigen_assert(A.cols() == A.rows());\n  eigen_assert(B.cols() == B.rows());\n  eigen_assert(B.rows() == 0 || A.cols() == B.rows());\n  eigen_assert((options &~ (EigVecMask | GenEigMask)) == 0\n            && (options & EigVecMask) != EigVecMask\n            && \"invalid option parameter\");\n\n  bool isBempty = (B.rows() == 0) || (B.cols() == 0);\n\n  // For clarity, all parameters match their ARPACK name\n  //\n  // Always 0 on the first call\n  //\n  int ido = 0;\n\n  int n = (int)A.cols();\n\n  // User options: \"LA\", \"SA\", \"SM\", \"LM\", \"BE\"\n  //\n  char whch[3] = \"LM\";\n    \n  // Specifies the shift if iparam[6] = { 3, 4, 5 }, not used if iparam[6] = { 1, 2 }\n  //\n  RealScalar sigma = 0.0;\n\n  if (eigs_sigma.length() >= 2 && isalpha(eigs_sigma[0]) && isalpha(eigs_sigma[1]))\n  {\n      eigs_sigma[0] = toupper(eigs_sigma[0]);\n      eigs_sigma[1] = toupper(eigs_sigma[1]);\n\n      // In the following special case we're going to invert the problem, since solving\n      // for larger magnitude is much much faster\n      // i.e., if 'SM' is specified, we're going to really use 'LM', the default\n      //\n      if (eigs_sigma.substr(0,2) != \"SM\")\n      {\n          whch[0] = eigs_sigma[0];\n          whch[1] = eigs_sigma[1];\n      }\n  }\n  else\n  {\n      eigen_assert(false && \"Specifying clustered eigenvalues is not yet supported!\");\n\n      // If it's not scalar values, then the user may be explicitly\n      // specifying the sigma value to cluster the evs around\n      //\n      sigma = atof(eigs_sigma.c_str());\n\n      // If atof fails, it returns 0.0, which is a fine default\n      //\n  }\n\n  // \"I\" means normal eigenvalue problem, \"G\" means generalized\n  //\n  char bmat[2] = \"I\";\n  if (eigs_sigma.substr(0,2) == \"SM\" || !(isalpha(eigs_sigma[0]) && isalpha(eigs_sigma[1])) || (!isBempty && !BisSPD))\n      bmat[0] = 'G';\n\n  // Now we determine the mode to use\n  //\n  int mode = (bmat[0] == 'G') + 1;\n  if (eigs_sigma.substr(0,2) == \"SM\" || !(isalpha(eigs_sigma[0]) && isalpha(eigs_sigma[1])))\n  {\n      // We're going to use shift-and-invert mode, and basically find\n      // the largest eigenvalues of the inverse operator\n      //\n      mode = 3;\n  }\n\n  // The user-specified number of eigenvalues/vectors to compute\n  //\n  int nev = (int)nbrEigenvalues;\n\n  // Allocate space for ARPACK to store the residual\n  //\n  Scalar *resid = new Scalar[n];\n\n  // Number of Lanczos vectors, must satisfy nev < ncv <= n\n  // Note that this indicates that nev != n, and we cannot compute\n  // all eigenvalues of a mtrix\n  //\n  int ncv = std::min(std::max(2*nev, 20), n);\n\n  // The working n x ncv matrix, also store the final eigenvectors (if computed)\n  //\n  Scalar *v = new Scalar[n*ncv];\n  int ldv = n;\n\n  // Working space\n  //\n  Scalar *workd = new Scalar[3*n];\n  int lworkl = ncv*ncv+8*ncv; // Must be at least this length\n  Scalar *workl = new Scalar[lworkl];\n\n  int *iparam= new int[11];\n  iparam[0] = 1; // 1 means we let ARPACK perform the shifts, 0 means we'd have to do it\n  iparam[2] = std::max(300, (int)std::ceil(2*n/std::max(ncv,1)));\n  iparam[6] = mode; // The mode, 1 is standard ev problem, 2 for generalized ev, 3 for shift-and-invert\n\n  // Used during reverse communicate to notify where arrays start\n  //\n  int *ipntr = new int[11]; \n\n  // Error codes are returned in here, initial value of 0 indicates a random initial\n  // residual vector is used, any other values means resid contains the initial residual\n  // vector, possibly from a previous run\n  //\n  int info = 0;\n\n  Scalar scale = 1.0;\n  //if (!isBempty)\n  //{\n  //Scalar scale = B.norm() / std::sqrt(n);\n  //scale = std::pow(2, std::floor(std::log(scale+1)));\n  ////M /= scale;\n  //for (size_t i=0; i<(size_t)B.outerSize(); i++)\n  //    for (typename MatrixType::InnerIterator it(B, i); it; ++it)\n  //        it.valueRef() /= scale;\n  //}\n\n  MatrixSolver OP;\n  if (mode == 1 || mode == 2)\n  {\n      if (!isBempty)\n          OP.compute(B);\n  }\n  else if (mode == 3)\n  {\n      if (sigma == 0.0)\n      {\n          OP.compute(A);\n      }\n      else\n      {\n          // Note: We will never enter here because sigma must be 0.0\n          //\n          if (isBempty)\n          {\n            MatrixType AminusSigmaB(A);\n            for (Index i=0; i<A.rows(); ++i)\n                AminusSigmaB.coeffRef(i,i) -= sigma;\n            \n            OP.compute(AminusSigmaB);\n          }\n          else\n          {\n              MatrixType AminusSigmaB = A - sigma * B;\n              OP.compute(AminusSigmaB);\n          }\n      }\n  }\n \n  if (!(mode == 1 && isBempty) && !(mode == 2 && isBempty) && OP.info() != Success)\n      std::cout << \"Error factoring matrix\" << std::endl;\n\n  do\n  {\n    internal::arpack_wrapper<Scalar, RealScalar>::saupd(&ido, bmat, &n, whch, &nev, &tol, resid, \n                                                        &ncv, v, &ldv, iparam, ipntr, workd, workl,\n                                                        &lworkl, &info);\n\n    if (ido == -1 || ido == 1)\n    {\n      Scalar *in  = workd + ipntr[0] - 1;\n      Scalar *out = workd + ipntr[1] - 1;\n\n      if (ido == 1 && mode != 2)\n      {\n          Scalar *out2 = workd + ipntr[2] - 1;\n          if (isBempty || mode == 1)\n            Matrix<Scalar, Dynamic, 1>::Map(out2, n) = Matrix<Scalar, Dynamic, 1>::Map(in, n);\n          else\n            Matrix<Scalar, Dynamic, 1>::Map(out2, n) = B * Matrix<Scalar, Dynamic, 1>::Map(in, n);\n          \n          in = workd + ipntr[2] - 1;\n      }\n\n      if (mode == 1)\n      {\n        if (isBempty)\n        {\n          // OP = A\n          //\n          Matrix<Scalar, Dynamic, 1>::Map(out, n) = A * Matrix<Scalar, Dynamic, 1>::Map(in, n);\n        }\n        else\n        {\n          // OP = L^{-1}AL^{-T}\n          //\n          internal::OP<MatrixSolver, MatrixType, Scalar, BisSPD>::applyOP(OP, A, n, in, out);\n        }\n      }\n      else if (mode == 2)\n      {\n        if (ido == 1)\n          Matrix<Scalar, Dynamic, 1>::Map(in, n)  = A * Matrix<Scalar, Dynamic, 1>::Map(in, n);\n        \n        // OP = B^{-1} A\n        //\n        Matrix<Scalar, Dynamic, 1>::Map(out, n) = OP.solve(Matrix<Scalar, Dynamic, 1>::Map(in, n));\n      }\n      else if (mode == 3)\n      {\n        // OP = (A-\\sigmaB)B (\\sigma could be 0, and B could be I)\n        // The B * in is already computed and stored at in if ido == 1\n        //\n        if (ido == 1 || isBempty)\n          Matrix<Scalar, Dynamic, 1>::Map(out, n) = OP.solve(Matrix<Scalar, Dynamic, 1>::Map(in, n));\n        else\n          Matrix<Scalar, Dynamic, 1>::Map(out, n) = OP.solve(B * Matrix<Scalar, Dynamic, 1>::Map(in, n));\n      }\n    }\n    else if (ido == 2)\n    {\n      Scalar *in  = workd + ipntr[0] - 1;\n      Scalar *out = workd + ipntr[1] - 1;\n\n      if (isBempty || mode == 1)\n        Matrix<Scalar, Dynamic, 1>::Map(out, n) = Matrix<Scalar, Dynamic, 1>::Map(in, n);\n      else\n        Matrix<Scalar, Dynamic, 1>::Map(out, n) = B * Matrix<Scalar, Dynamic, 1>::Map(in, n);\n    }\n  } while (ido != 99);\n\n  if (info == 1)\n    m_info = NoConvergence;\n  else if (info == 3)\n    m_info = NumericalIssue;\n  else if (info < 0)\n    m_info = InvalidInput;\n  else if (info != 0)\n    eigen_assert(false && \"Unknown ARPACK return value!\");\n  else\n  {\n    // Do we compute eigenvectors or not?\n    //\n    int rvec = (options & ComputeEigenvectors) == ComputeEigenvectors;\n\n    // \"A\" means \"All\", use \"S\" to choose specific eigenvalues (not yet supported in ARPACK))\n    //\n    char howmny[2] = \"A\"; \n\n    // if howmny == \"S\", specifies the eigenvalues to compute (not implemented in ARPACK)\n    //\n    int *select = new int[ncv];\n\n    // Final eigenvalues\n    //\n    m_eivalues.resize(nev, 1);\n\n    internal::arpack_wrapper<Scalar, RealScalar>::seupd(&rvec, howmny, select, m_eivalues.data(), v, &ldv,\n                                                        &sigma, bmat, &n, whch, &nev, &tol, resid, &ncv,\n                                                        v, &ldv, iparam, ipntr, workd, workl, &lworkl, &info);\n\n    if (info == -14)\n      m_info = NoConvergence;\n    else if (info != 0)\n      m_info = InvalidInput;\n    else\n    {\n      if (rvec)\n      {\n        m_eivec.resize(A.rows(), nev);\n        for (int i=0; i<nev; i++)\n          for (int j=0; j<n; j++)\n            m_eivec(j,i) = v[i*n+j] / scale;\n      \n        if (mode == 1 && !isBempty && BisSPD)\n          internal::OP<MatrixSolver, MatrixType, Scalar, BisSPD>::project(OP, n, nev, m_eivec.data());\n\n        m_eigenvectorsOk = true;\n      }\n\n      m_nbrIterations = iparam[2];\n      m_nbrConverged  = iparam[4];\n\n      m_info = Success;\n    }\n\n    delete[] select;\n  }\n\n  delete[] v;\n  delete[] iparam;\n  delete[] ipntr;\n  delete[] workd;\n  delete[] workl;\n  delete[] resid;\n\n  m_isInitialized = true;\n\n  return *this;\n}\n\n\n// Single precision\n//\nextern \"C\" void ssaupd_(int *ido, char *bmat, int *n, char *which,\n    int *nev, float *tol, float *resid, int *ncv,\n    float *v, int *ldv, int *iparam, int *ipntr,\n    float *workd, float *workl, int *lworkl,\n    int *info);\n\nextern \"C\" void sseupd_(int *rvec, char *All, int *select, float *d,\n    float *z, int *ldz, float *sigma, \n    char *bmat, int *n, char *which, int *nev,\n    float *tol, float *resid, int *ncv, float *v,\n    int *ldv, int *iparam, int *ipntr, float *workd,\n    float *workl, int *lworkl, int *ierr);\n\n// Double precision\n//\nextern \"C\" void dsaupd_(int *ido, char *bmat, int *n, char *which,\n    int *nev, double *tol, double *resid, int *ncv,\n    double *v, int *ldv, int *iparam, int *ipntr,\n    double *workd, double *workl, int *lworkl,\n    int *info);\n\nextern \"C\" void dseupd_(int *rvec, char *All, int *select, double *d,\n    double *z, int *ldz, double *sigma, \n    char *bmat, int *n, char *which, int *nev,\n    double *tol, double *resid, int *ncv, double *v,\n    int *ldv, int *iparam, int *ipntr, double *workd,\n    double *workl, int *lworkl, int *ierr);\n\n\nnamespace internal {\n\ntemplate<typename Scalar, typename RealScalar> struct arpack_wrapper\n{\n  static inline void saupd(int *ido, char *bmat, int *n, char *which,\n      int *nev, RealScalar *tol, Scalar *resid, int *ncv,\n      Scalar *v, int *ldv, int *iparam, int *ipntr,\n      Scalar *workd, Scalar *workl, int *lworkl, int *info)\n  { \n    EIGEN_STATIC_ASSERT(!NumTraits<Scalar>::IsComplex, NUMERIC_TYPE_MUST_BE_REAL)\n  }\n\n  static inline void seupd(int *rvec, char *All, int *select, Scalar *d,\n      Scalar *z, int *ldz, RealScalar *sigma,\n      char *bmat, int *n, char *which, int *nev,\n      RealScalar *tol, Scalar *resid, int *ncv, Scalar *v,\n      int *ldv, int *iparam, int *ipntr, Scalar *workd,\n      Scalar *workl, int *lworkl, int *ierr)\n  {\n    EIGEN_STATIC_ASSERT(!NumTraits<Scalar>::IsComplex, NUMERIC_TYPE_MUST_BE_REAL)\n  }\n};\n\ntemplate <> struct arpack_wrapper<float, float>\n{\n  static inline void saupd(int *ido, char *bmat, int *n, char *which,\n      int *nev, float *tol, float *resid, int *ncv,\n      float *v, int *ldv, int *iparam, int *ipntr,\n      float *workd, float *workl, int *lworkl, int *info)\n  {\n    ssaupd_(ido, bmat, n, which, nev, tol, resid, ncv, v, ldv, iparam, ipntr, workd, workl, lworkl, info);\n  }\n\n  static inline void seupd(int *rvec, char *All, int *select, float *d,\n      float *z, int *ldz, float *sigma,\n      char *bmat, int *n, char *which, int *nev,\n      float *tol, float *resid, int *ncv, float *v,\n      int *ldv, int *iparam, int *ipntr, float *workd,\n      float *workl, int *lworkl, int *ierr)\n  {\n    sseupd_(rvec, All, select, d, z, ldz, sigma, bmat, n, which, nev, tol, resid, ncv, v, ldv, iparam, ipntr,\n        workd, workl, lworkl, ierr);\n  }\n};\n\ntemplate <> struct arpack_wrapper<double, double>\n{\n  static inline void saupd(int *ido, char *bmat, int *n, char *which,\n      int *nev, double *tol, double *resid, int *ncv,\n      double *v, int *ldv, int *iparam, int *ipntr,\n      double *workd, double *workl, int *lworkl, int *info)\n  {\n    dsaupd_(ido, bmat, n, which, nev, tol, resid, ncv, v, ldv, iparam, ipntr, workd, workl, lworkl, info);\n  }\n\n  static inline void seupd(int *rvec, char *All, int *select, double *d,\n      double *z, int *ldz, double *sigma,\n      char *bmat, int *n, char *which, int *nev,\n      double *tol, double *resid, int *ncv, double *v,\n      int *ldv, int *iparam, int *ipntr, double *workd,\n      double *workl, int *lworkl, int *ierr)\n  {\n    dseupd_(rvec, All, select, d, v, ldv, sigma, bmat, n, which, nev, tol, resid, ncv, v, ldv, iparam, ipntr,\n        workd, workl, lworkl, ierr);\n  }\n};\n\n\ntemplate<typename MatrixSolver, typename MatrixType, typename Scalar, bool BisSPD>\nstruct OP\n{\n    static inline void applyOP(MatrixSolver &OP, const MatrixType &A, int n, Scalar *in, Scalar *out);\n    static inline void project(MatrixSolver &OP, int n, int k, Scalar *vecs);\n};\n\ntemplate<typename MatrixSolver, typename MatrixType, typename Scalar>\nstruct OP<MatrixSolver, MatrixType, Scalar, true>\n{\n  static inline void applyOP(MatrixSolver &OP, const MatrixType &A, int n, Scalar *in, Scalar *out)\n{\n    // OP = L^{-1} A L^{-T}  (B = LL^T)\n    //\n    // First solve L^T out = in\n    //\n    Matrix<Scalar, Dynamic, 1>::Map(out, n) = OP.matrixU().solve(Matrix<Scalar, Dynamic, 1>::Map(in, n));\n    Matrix<Scalar, Dynamic, 1>::Map(out, n) = OP.permutationPinv() * Matrix<Scalar, Dynamic, 1>::Map(out, n);\n\n    // Then compute out = A out\n    //\n    Matrix<Scalar, Dynamic, 1>::Map(out, n) = A * Matrix<Scalar, Dynamic, 1>::Map(out, n);\n\n    // Then solve L out = out\n    //\n    Matrix<Scalar, Dynamic, 1>::Map(out, n) = OP.permutationP() * Matrix<Scalar, Dynamic, 1>::Map(out, n);\n    Matrix<Scalar, Dynamic, 1>::Map(out, n) = OP.matrixL().solve(Matrix<Scalar, Dynamic, 1>::Map(out, n));\n}\n\n  static inline void project(MatrixSolver &OP, int n, int k, Scalar *vecs)\n{\n    // Solve L^T out = in\n    //\n    Matrix<Scalar, Dynamic, Dynamic>::Map(vecs, n, k) = OP.matrixU().solve(Matrix<Scalar, Dynamic, Dynamic>::Map(vecs, n, k));\n    Matrix<Scalar, Dynamic, Dynamic>::Map(vecs, n, k) = OP.permutationPinv() * Matrix<Scalar, Dynamic, Dynamic>::Map(vecs, n, k);\n}\n\n};\n\ntemplate<typename MatrixSolver, typename MatrixType, typename Scalar>\nstruct OP<MatrixSolver, MatrixType, Scalar, false>\n{\n  static inline void applyOP(MatrixSolver &OP, const MatrixType &A, int n, Scalar *in, Scalar *out)\n{\n    eigen_assert(false && \"Should never be in here...\");\n}\n\n  static inline void project(MatrixSolver &OP, int n, int k, Scalar *vecs)\n{\n    eigen_assert(false && \"Should never be in here...\");\n}\n\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_ARPACKSELFADJOINTEIGENSOLVER_H\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/EulerAngles/CMakeLists.txt",
    "content": "file(GLOB Eigen_EulerAngles_SRCS \"*.h\")\n\ninstall(FILES\n  ${Eigen_EulerAngles_SRCS}\n  DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen/src/EulerAngles COMPONENT Devel\n  )\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/EulerAngles/EulerAngles.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Tal Hadad <tal_hd@hotmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_EULERANGLESCLASS_H// TODO: Fix previous \"EIGEN_EULERANGLES_H\" definition?\n#define EIGEN_EULERANGLESCLASS_H\n\nnamespace Eigen\n{\n  /** \\class EulerAngles\n    *\n    * \\ingroup EulerAngles_Module\n    *\n    * \\brief Represents a rotation in a 3 dimensional space as three Euler angles.\n    *\n    * Euler rotation is a set of three rotation of three angles over three fixed axes, defined by the EulerSystem given as a template parameter.\n    * \n    * Here is how intrinsic Euler angles works:\n    *  - first, rotate the axes system over the alpha axis in angle alpha\n    *  - then, rotate the axes system over the beta axis(which was rotated in the first stage) in angle beta\n    *  - then, rotate the axes system over the gamma axis(which was rotated in the two stages above) in angle gamma\n    *\n    * \\note This class support only intrinsic Euler angles for simplicity,\n    *  see EulerSystem how to easily overcome this for extrinsic systems.\n    *\n    * ### Rotation representation and conversions ###\n    *\n    * It has been proved(see Wikipedia link below) that every rotation can be represented\n    *  by Euler angles, but there is no single representation (e.g. unlike rotation matrices).\n    * Therefore, you can convert from Eigen rotation and to them\n    *  (including rotation matrices, which is not called \"rotations\" by Eigen design).\n    *\n    * Euler angles usually used for:\n    *  - convenient human representation of rotation, especially in interactive GUI.\n    *  - gimbal systems and robotics\n    *  - efficient encoding(i.e. 3 floats only) of rotation for network protocols.\n    *\n    * However, Euler angles are slow comparing to quaternion or matrices,\n    *  because their unnatural math definition, although it's simple for human.\n    * To overcome this, this class provide easy movement from the math friendly representation\n    *  to the human friendly representation, and vise-versa.\n    *\n    * All the user need to do is a safe simple C++ type conversion,\n    *  and this class take care for the math.\n    * Additionally, some axes related computation is done in compile time.\n    *\n    * #### Euler angles ranges in conversions ####\n    * Rotations representation as EulerAngles are not single (unlike matrices),\n    *  and even have infinite EulerAngles representations.<BR>\n    * For example, add or subtract 2*PI from either angle of EulerAngles\n    *  and you'll get the same rotation.\n    * This is the general reason for infinite representation,\n    *  but it's not the only general reason for not having a single representation.\n    *\n    * When converting rotation to EulerAngles, this class convert it to specific ranges\n    * When converting some rotation to EulerAngles, the rules for ranges are as follow:\n    * - If the rotation we converting from is an EulerAngles\n    *  (even when it represented as RotationBase explicitly), angles ranges are __undefined__.\n    * - otherwise, alpha and gamma angles will be in the range [-PI, PI].<BR>\n    *   As for Beta angle:\n    *    - If the system is Tait-Bryan, the beta angle will be in the range [-PI/2, PI/2].\n    *    - otherwise:\n    *      - If the beta axis is positive, the beta angle will be in the range [0, PI]\n    *      - If the beta axis is negative, the beta angle will be in the range [-PI, 0]\n    *\n    * \\sa EulerAngles(const MatrixBase<Derived>&)\n    * \\sa EulerAngles(const RotationBase<Derived, 3>&)\n    *\n    * ### Convenient user typedefs ###\n    *\n    * Convenient typedefs for EulerAngles exist for float and double scalar,\n    *  in a form of EulerAngles{A}{B}{C}{scalar},\n    *  e.g. \\ref EulerAnglesXYZd, \\ref EulerAnglesZYZf.\n    *\n    * Only for positive axes{+x,+y,+z} Euler systems are have convenient typedef.\n    * If you need negative axes{-x,-y,-z}, it is recommended to create you own typedef with\n    *  a word that represent what you need.\n    *\n    * ### Example ###\n    *\n    * \\include EulerAngles.cpp\n    * Output: \\verbinclude EulerAngles.out\n    *\n    * ### Additional reading ###\n    *\n    * If you're want to get more idea about how Euler system work in Eigen see EulerSystem.\n    *\n    * More information about Euler angles: https://en.wikipedia.org/wiki/Euler_angles\n    *\n    * \\tparam Scalar_ the scalar type, i.e. the type of the angles.\n    *\n    * \\tparam _System the EulerSystem to use, which represents the axes of rotation.\n    */\n  template <typename Scalar_, class _System>\n  class EulerAngles : public RotationBase<EulerAngles<Scalar_, _System>, 3>\n  {\n    public:\n      typedef RotationBase<EulerAngles<Scalar_, _System>, 3> Base;\n      \n      /** the scalar type of the angles */\n      typedef Scalar_ Scalar;\n      typedef typename NumTraits<Scalar>::Real RealScalar;\n      \n      /** the EulerSystem to use, which represents the axes of rotation. */\n      typedef _System System;\n    \n      typedef Matrix<Scalar,3,3> Matrix3; /*!< the equivalent rotation matrix type */\n      typedef Matrix<Scalar,3,1> Vector3; /*!< the equivalent 3 dimension vector type */\n      typedef Quaternion<Scalar> QuaternionType; /*!< the equivalent quaternion type */\n      typedef AngleAxis<Scalar> AngleAxisType; /*!< the equivalent angle-axis type */\n      \n      /** \\returns the axis vector of the first (alpha) rotation */\n      static Vector3 AlphaAxisVector() {\n        const Vector3& u = Vector3::Unit(System::AlphaAxisAbs - 1);\n        return System::IsAlphaOpposite ? -u : u;\n      }\n      \n      /** \\returns the axis vector of the second (beta) rotation */\n      static Vector3 BetaAxisVector() {\n        const Vector3& u = Vector3::Unit(System::BetaAxisAbs - 1);\n        return System::IsBetaOpposite ? -u : u;\n      }\n      \n      /** \\returns the axis vector of the third (gamma) rotation */\n      static Vector3 GammaAxisVector() {\n        const Vector3& u = Vector3::Unit(System::GammaAxisAbs - 1);\n        return System::IsGammaOpposite ? -u : u;\n      }\n\n    private:\n      Vector3 m_angles;\n\n    public:\n      /** Default constructor without initialization. */\n      EulerAngles() {}\n      /** Constructs and initialize an EulerAngles (\\p alpha, \\p beta, \\p gamma). */\n      EulerAngles(const Scalar& alpha, const Scalar& beta, const Scalar& gamma) :\n        m_angles(alpha, beta, gamma) {}\n      \n      // TODO: Test this constructor\n      /** Constructs and initialize an EulerAngles from the array data {alpha, beta, gamma} */\n      explicit EulerAngles(const Scalar* data) : m_angles(data) {}\n      \n      /** Constructs and initializes an EulerAngles from either:\n        *  - a 3x3 rotation matrix expression(i.e. pure orthogonal matrix with determinant of +1),\n        *  - a 3D vector expression representing Euler angles.\n        *\n        * \\note If \\p other is a 3x3 rotation matrix, the angles range rules will be as follow:<BR>\n        *  Alpha and gamma angles will be in the range [-PI, PI].<BR>\n        *  As for Beta angle:\n        *   - If the system is Tait-Bryan, the beta angle will be in the range [-PI/2, PI/2].\n        *   - otherwise:\n        *     - If the beta axis is positive, the beta angle will be in the range [0, PI]\n        *     - If the beta axis is negative, the beta angle will be in the range [-PI, 0]\n       */\n      template<typename Derived>\n      explicit EulerAngles(const MatrixBase<Derived>& other) { *this = other; }\n      \n      /** Constructs and initialize Euler angles from a rotation \\p rot.\n        *\n        * \\note If \\p rot is an EulerAngles (even when it represented as RotationBase explicitly),\n        *  angles ranges are __undefined__.\n        *  Otherwise, alpha and gamma angles will be in the range [-PI, PI].<BR>\n        *  As for Beta angle:\n        *   - If the system is Tait-Bryan, the beta angle will be in the range [-PI/2, PI/2].\n        *   - otherwise:\n        *     - If the beta axis is positive, the beta angle will be in the range [0, PI]\n        *     - If the beta axis is negative, the beta angle will be in the range [-PI, 0]\n      */\n      template<typename Derived>\n      EulerAngles(const RotationBase<Derived, 3>& rot) { System::CalcEulerAngles(*this, rot.toRotationMatrix()); }\n      \n      /*EulerAngles(const QuaternionType& q)\n      {\n        // TODO: Implement it in a faster way for quaternions\n        // According to http://www.euclideanspace.com/maths/geometry/rotations/conversions/quaternionToEuler/\n        //  we can compute only the needed matrix cells and then convert to euler angles. (see ZYX example below)\n        // Currently we compute all matrix cells from quaternion.\n\n        // Special case only for ZYX\n        //Scalar y2 = q.y() * q.y();\n        //m_angles[0] = std::atan2(2*(q.w()*q.z() + q.x()*q.y()), (1 - 2*(y2 + q.z()*q.z())));\n        //m_angles[1] = std::asin( 2*(q.w()*q.y() - q.z()*q.x()));\n        //m_angles[2] = std::atan2(2*(q.w()*q.x() + q.y()*q.z()), (1 - 2*(q.x()*q.x() + y2)));\n      }*/\n\n      /** \\returns The angle values stored in a vector (alpha, beta, gamma). */\n      const Vector3& angles() const { return m_angles; }\n      /** \\returns A read-write reference to the angle values stored in a vector (alpha, beta, gamma). */\n      Vector3& angles() { return m_angles; }\n\n      /** \\returns The value of the first angle. */\n      Scalar alpha() const { return m_angles[0]; }\n      /** \\returns A read-write reference to the angle of the first angle. */\n      Scalar& alpha() { return m_angles[0]; }\n\n      /** \\returns The value of the second angle. */\n      Scalar beta() const { return m_angles[1]; }\n      /** \\returns A read-write reference to the angle of the second angle. */\n      Scalar& beta() { return m_angles[1]; }\n\n      /** \\returns The value of the third angle. */\n      Scalar gamma() const { return m_angles[2]; }\n      /** \\returns A read-write reference to the angle of the third angle. */\n      Scalar& gamma() { return m_angles[2]; }\n\n      /** \\returns The Euler angles rotation inverse (which is as same as the negative),\n        *  (-alpha, -beta, -gamma).\n      */\n      EulerAngles inverse() const\n      {\n        EulerAngles res;\n        res.m_angles = -m_angles;\n        return res;\n      }\n\n      /** \\returns The Euler angles rotation negative (which is as same as the inverse),\n        *  (-alpha, -beta, -gamma).\n      */\n      EulerAngles operator -() const\n      {\n        return inverse();\n      }\n      \n      /** Set \\c *this from either:\n        *  - a 3x3 rotation matrix expression(i.e. pure orthogonal matrix with determinant of +1),\n        *  - a 3D vector expression representing Euler angles.\n        *\n        * See EulerAngles(const MatrixBase<Derived, 3>&) for more information about\n        *  angles ranges output.\n      */\n      template<class Derived>\n      EulerAngles& operator=(const MatrixBase<Derived>& other)\n      {\n        EIGEN_STATIC_ASSERT((internal::is_same<Scalar, typename Derived::Scalar>::value),\n         YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n        \n        internal::eulerangles_assign_impl<System, Derived>::run(*this, other.derived());\n        return *this;\n      }\n\n      // TODO: Assign and construct from another EulerAngles (with different system)\n      \n      /** Set \\c *this from a rotation.\n        *\n        * See EulerAngles(const RotationBase<Derived, 3>&) for more information about\n        *  angles ranges output.\n      */\n      template<typename Derived>\n      EulerAngles& operator=(const RotationBase<Derived, 3>& rot) {\n        System::CalcEulerAngles(*this, rot.toRotationMatrix());\n        return *this;\n      }\n      \n      /** \\returns \\c true if \\c *this is approximately equal to \\a other, within the precision\n        * determined by \\a prec.\n        *\n        * \\sa MatrixBase::isApprox() */\n      bool isApprox(const EulerAngles& other,\n        const RealScalar& prec = NumTraits<Scalar>::dummy_precision()) const\n      { return angles().isApprox(other.angles(), prec); }\n\n      /** \\returns an equivalent 3x3 rotation matrix. */\n      Matrix3 toRotationMatrix() const\n      {\n        // TODO: Calc it faster\n        return static_cast<QuaternionType>(*this).toRotationMatrix();\n      }\n\n      /** Convert the Euler angles to quaternion. */\n      operator QuaternionType() const\n      {\n        return\n          AngleAxisType(alpha(), AlphaAxisVector()) *\n          AngleAxisType(beta(), BetaAxisVector())   *\n          AngleAxisType(gamma(), GammaAxisVector());\n      }\n      \n      friend std::ostream& operator<<(std::ostream& s, const EulerAngles<Scalar, System>& eulerAngles)\n      {\n        s << eulerAngles.angles().transpose();\n        return s;\n      }\n      \n      /** \\returns \\c *this with scalar type casted to \\a NewScalarType */\n      template <typename NewScalarType>\n      EulerAngles<NewScalarType, System> cast() const\n      {\n        EulerAngles<NewScalarType, System> e;\n        e.angles() = angles().template cast<NewScalarType>();\n        return e;\n      }\n  };\n\n#define EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(AXES, SCALAR_TYPE, SCALAR_POSTFIX) \\\n  /** \\ingroup EulerAngles_Module */ \\\n  typedef EulerAngles<SCALAR_TYPE, EulerSystem##AXES> EulerAngles##AXES##SCALAR_POSTFIX;\n\n#define EIGEN_EULER_ANGLES_TYPEDEFS(SCALAR_TYPE, SCALAR_POSTFIX) \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(XYZ, SCALAR_TYPE, SCALAR_POSTFIX) \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(XYX, SCALAR_TYPE, SCALAR_POSTFIX) \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(XZY, SCALAR_TYPE, SCALAR_POSTFIX) \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(XZX, SCALAR_TYPE, SCALAR_POSTFIX) \\\n \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(YZX, SCALAR_TYPE, SCALAR_POSTFIX) \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(YZY, SCALAR_TYPE, SCALAR_POSTFIX) \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(YXZ, SCALAR_TYPE, SCALAR_POSTFIX) \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(YXY, SCALAR_TYPE, SCALAR_POSTFIX) \\\n \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(ZXY, SCALAR_TYPE, SCALAR_POSTFIX) \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(ZXZ, SCALAR_TYPE, SCALAR_POSTFIX) \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(ZYX, SCALAR_TYPE, SCALAR_POSTFIX) \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(ZYZ, SCALAR_TYPE, SCALAR_POSTFIX)\n\nEIGEN_EULER_ANGLES_TYPEDEFS(float, f)\nEIGEN_EULER_ANGLES_TYPEDEFS(double, d)\n\n  namespace internal\n  {\n    template<typename Scalar_, class _System>\n    struct traits<EulerAngles<Scalar_, _System> >\n    {\n      typedef Scalar_ Scalar;\n    };\n    \n    // set from a rotation matrix\n    template<class System, class Other>\n    struct eulerangles_assign_impl<System,Other,3,3>\n    {\n      typedef typename Other::Scalar Scalar;\n      static void run(EulerAngles<Scalar, System>& e, const Other& m)\n      {\n        System::CalcEulerAngles(e, m);\n      }\n    };\n    \n    // set from a vector of Euler angles\n    template<class System, class Other>\n    struct eulerangles_assign_impl<System,Other,3,1>\n    {\n      typedef typename Other::Scalar Scalar;\n      static void run(EulerAngles<Scalar, System>& e, const Other& vec)\n      {\n        e.angles() = vec;\n      }\n    };\n  }\n}\n\n#endif // EIGEN_EULERANGLESCLASS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/EulerAngles/EulerSystem.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Tal Hadad <tal_hd@hotmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_EULERSYSTEM_H\n#define EIGEN_EULERSYSTEM_H\n\nnamespace Eigen\n{\n  // Forward declarations\n  template <typename Scalar_, class _System>\n  class EulerAngles;\n  \n  namespace internal\n  {\n    // TODO: Add this trait to the Eigen internal API?\n    template <int Num, bool IsPositive = (Num > 0)>\n    struct Abs\n    {\n      enum { value = Num };\n    };\n  \n    template <int Num>\n    struct Abs<Num, false>\n    {\n      enum { value = -Num };\n    };\n\n    template <int Axis>\n    struct IsValidAxis\n    {\n      enum { value = Axis != 0 && Abs<Axis>::value <= 3 };\n    };\n    \n    template<typename System,\n            typename Other,\n            int OtherRows=Other::RowsAtCompileTime,\n            int OtherCols=Other::ColsAtCompileTime>\n    struct eulerangles_assign_impl;\n  }\n  \n  #define EIGEN_EULER_ANGLES_CLASS_STATIC_ASSERT(COND,MSG) typedef char static_assertion_##MSG[(COND)?1:-1]\n  \n  /** \\brief Representation of a fixed signed rotation axis for EulerSystem.\n    *\n    * \\ingroup EulerAngles_Module\n    *\n    * Values here represent:\n    *  - The axis of the rotation: X, Y or Z.\n    *  - The sign (i.e. direction of the rotation along the axis): positive(+) or negative(-)\n    *\n    * Therefore, this could express all the axes {+X,+Y,+Z,-X,-Y,-Z}\n    *\n    * For positive axis, use +EULER_{axis}, and for negative axis use -EULER_{axis}.\n    */\n  enum EulerAxis\n  {\n    EULER_X = 1, /*!< the X axis */\n    EULER_Y = 2, /*!< the Y axis */\n    EULER_Z = 3  /*!< the Z axis */\n  };\n  \n  /** \\class EulerSystem\n    *\n    * \\ingroup EulerAngles_Module\n    *\n    * \\brief Represents a fixed Euler rotation system.\n    *\n    * This meta-class goal is to represent the Euler system in compilation time, for EulerAngles.\n    *\n    * You can use this class to get two things:\n    *  - Build an Euler system, and then pass it as a template parameter to EulerAngles.\n    *  - Query some compile time data about an Euler system. (e.g. Whether it's Tait-Bryan)\n    *\n    * Euler rotation is a set of three rotation on fixed axes. (see \\ref EulerAngles)\n    * This meta-class store constantly those signed axes. (see \\ref EulerAxis)\n    *\n    * ### Types of Euler systems ###\n    *\n    * All and only valid 3 dimension Euler rotation over standard\n    *  signed axes{+X,+Y,+Z,-X,-Y,-Z} are supported:\n    *  - all axes X, Y, Z in each valid order (see below what order is valid)\n    *  - rotation over the axis is supported both over the positive and negative directions.\n    *  - both Tait-Bryan and proper/classic Euler angles (i.e. the opposite).\n    *\n    * Since EulerSystem support both positive and negative directions,\n    *  you may call this rotation distinction in other names:\n    *  - _right handed_ or _left handed_\n    *  - _counterclockwise_ or _clockwise_\n    *\n    * Notice all axed combination are valid, and would trigger a static assertion.\n    * Same unsigned axes can't be neighbors, e.g. {X,X,Y} is invalid.\n    * This yield two and only two classes:\n    *  - _Tait-Bryan_ - all unsigned axes are distinct, e.g. {X,Y,Z}\n    *  - _proper/classic Euler angles_ - The first and the third unsigned axes is equal,\n    *     and the second is different, e.g. {X,Y,X}\n    *\n    * ### Intrinsic vs extrinsic Euler systems ###\n    *\n    * Only intrinsic Euler systems are supported for simplicity.\n    *  If you want to use extrinsic Euler systems,\n    *   just use the equal intrinsic opposite order for axes and angles.\n    *  I.e axes (A,B,C) becomes (C,B,A), and angles (a,b,c) becomes (c,b,a).\n    *\n    * ### Convenient user typedefs ###\n    *\n    * Convenient typedefs for EulerSystem exist (only for positive axes Euler systems),\n    *  in a form of EulerSystem{A}{B}{C}, e.g. \\ref EulerSystemXYZ.\n    *\n    * ### Additional reading ###\n    *\n    * More information about Euler angles: https://en.wikipedia.org/wiki/Euler_angles\n    *\n    * \\tparam _AlphaAxis the first fixed EulerAxis\n    *\n    * \\tparam _BetaAxis the second fixed EulerAxis\n    *\n    * \\tparam _GammaAxis the third fixed EulerAxis\n    */\n  template <int _AlphaAxis, int _BetaAxis, int _GammaAxis>\n  class EulerSystem\n  {\n    public:\n    // It's defined this way and not as enum, because I think\n    //  that enum is not guerantee to support negative numbers\n    \n    /** The first rotation axis */\n    static const int AlphaAxis = _AlphaAxis;\n    \n    /** The second rotation axis */\n    static const int BetaAxis = _BetaAxis;\n    \n    /** The third rotation axis */\n    static const int GammaAxis = _GammaAxis;\n\n    enum\n    {\n      AlphaAxisAbs = internal::Abs<AlphaAxis>::value, /*!< the first rotation axis unsigned */\n      BetaAxisAbs = internal::Abs<BetaAxis>::value, /*!< the second rotation axis unsigned */\n      GammaAxisAbs = internal::Abs<GammaAxis>::value, /*!< the third rotation axis unsigned */\n      \n      IsAlphaOpposite = (AlphaAxis < 0) ? 1 : 0, /*!< whether alpha axis is negative */\n      IsBetaOpposite = (BetaAxis < 0) ? 1 : 0, /*!< whether beta axis is negative */\n      IsGammaOpposite = (GammaAxis < 0) ? 1 : 0, /*!< whether gamma axis is negative */\n\n      // Parity is even if alpha axis X is followed by beta axis Y, or Y is followed\n      // by Z, or Z is followed by X; otherwise it is odd.\n      IsOdd = ((AlphaAxisAbs)%3 == (BetaAxisAbs - 1)%3) ? 0 : 1, /*!< whether the Euler system is odd */\n      IsEven = IsOdd ? 0 : 1, /*!< whether the Euler system is even */\n\n      IsTaitBryan = ((unsigned)AlphaAxisAbs != (unsigned)GammaAxisAbs) ? 1 : 0 /*!< whether the Euler system is Tait-Bryan */\n    };\n    \n    private:\n    \n    EIGEN_EULER_ANGLES_CLASS_STATIC_ASSERT(internal::IsValidAxis<AlphaAxis>::value,\n      ALPHA_AXIS_IS_INVALID);\n      \n    EIGEN_EULER_ANGLES_CLASS_STATIC_ASSERT(internal::IsValidAxis<BetaAxis>::value,\n      BETA_AXIS_IS_INVALID);\n      \n    EIGEN_EULER_ANGLES_CLASS_STATIC_ASSERT(internal::IsValidAxis<GammaAxis>::value,\n      GAMMA_AXIS_IS_INVALID);\n      \n    EIGEN_EULER_ANGLES_CLASS_STATIC_ASSERT((unsigned)AlphaAxisAbs != (unsigned)BetaAxisAbs,\n      ALPHA_AXIS_CANT_BE_EQUAL_TO_BETA_AXIS);\n      \n    EIGEN_EULER_ANGLES_CLASS_STATIC_ASSERT((unsigned)BetaAxisAbs != (unsigned)GammaAxisAbs,\n      BETA_AXIS_CANT_BE_EQUAL_TO_GAMMA_AXIS);\n\n    static const int\n      // I, J, K are the pivot indexes permutation for the rotation matrix, that match this Euler system. \n      // They are used in this class converters.\n      // They are always different from each other, and their possible values are: 0, 1, or 2.\n      I_ = AlphaAxisAbs - 1,\n      J_ = (AlphaAxisAbs - 1 + 1 + IsOdd)%3,\n      K_ = (AlphaAxisAbs - 1 + 2 - IsOdd)%3\n    ;\n    \n    // TODO: Get @mat parameter in form that avoids double evaluation.\n    template <typename Derived>\n    static void CalcEulerAngles_imp(Matrix<typename MatrixBase<Derived>::Scalar, 3, 1>& res, const MatrixBase<Derived>& mat, internal::true_type /*isTaitBryan*/)\n    {\n      using std::atan2;\n      using std::sqrt;\n      \n      typedef typename Derived::Scalar Scalar;\n\n      const Scalar plusMinus = IsEven? 1 : -1;\n      const Scalar minusPlus = IsOdd?  1 : -1;\n\n      const Scalar Rsum = sqrt((mat(I_,I_) * mat(I_,I_) + mat(I_,J_) * mat(I_,J_) + mat(J_,K_) * mat(J_,K_) + mat(K_,K_) * mat(K_,K_))/2);\n      res[1] = atan2(plusMinus * mat(I_,K_), Rsum);\n\n      // There is a singularity when cos(beta) == 0\n      if(Rsum > 4 * NumTraits<Scalar>::epsilon()) {// cos(beta) != 0\n        res[0] = atan2(minusPlus * mat(J_, K_), mat(K_, K_));\n        res[2] = atan2(minusPlus * mat(I_, J_), mat(I_, I_));\n      }\n      else if(plusMinus * mat(I_, K_) > 0) {// cos(beta) == 0 and sin(beta) == 1\n        Scalar spos = mat(J_, I_) + plusMinus * mat(K_, J_); // 2*sin(alpha + plusMinus * gamma\n        Scalar cpos = mat(J_, J_) + minusPlus * mat(K_, I_); // 2*cos(alpha + plusMinus * gamma)\n        Scalar alphaPlusMinusGamma = atan2(spos, cpos);\n        res[0] = alphaPlusMinusGamma;\n        res[2] = 0;\n      }\n      else {// cos(beta) == 0 and sin(beta) == -1\n        Scalar sneg = plusMinus * (mat(K_, J_) + minusPlus * mat(J_, I_)); // 2*sin(alpha + minusPlus*gamma)\n        Scalar cneg = mat(J_, J_) + plusMinus * mat(K_, I_);               // 2*cos(alpha + minusPlus*gamma)\n        Scalar alphaMinusPlusBeta = atan2(sneg, cneg);\n        res[0] = alphaMinusPlusBeta;\n        res[2] = 0;\n      }\n    }\n\n    template <typename Derived>\n    static void CalcEulerAngles_imp(Matrix<typename MatrixBase<Derived>::Scalar,3,1>& res,\n                                    const MatrixBase<Derived>& mat, internal::false_type /*isTaitBryan*/)\n    {\n      using std::atan2;\n      using std::sqrt;\n\n      typedef typename Derived::Scalar Scalar;\n\n      const Scalar plusMinus = IsEven? 1 : -1;\n      const Scalar minusPlus = IsOdd?  1 : -1;\n\n      const Scalar Rsum = sqrt((mat(I_, J_) * mat(I_, J_) + mat(I_, K_) * mat(I_, K_) + mat(J_, I_) * mat(J_, I_) + mat(K_, I_) * mat(K_, I_)) / 2);\n\n      res[1] = atan2(Rsum, mat(I_, I_));\n\n      // There is a singularity when sin(beta) == 0\n      if(Rsum > 4 * NumTraits<Scalar>::epsilon()) {// sin(beta) != 0\n        res[0] = atan2(mat(J_, I_), minusPlus * mat(K_, I_));\n        res[2] = atan2(mat(I_, J_), plusMinus * mat(I_, K_));\n      }\n      else if(mat(I_, I_) > 0) {// sin(beta) == 0 and cos(beta) == 1\n        Scalar spos = plusMinus * mat(K_, J_) + minusPlus * mat(J_, K_); // 2*sin(alpha + gamma)\n        Scalar cpos = mat(J_, J_) + mat(K_, K_);                         // 2*cos(alpha + gamma)\n        res[0] = atan2(spos, cpos);\n        res[2] = 0;\n      }\n      else {// sin(beta) == 0 and cos(beta) == -1\n        Scalar sneg = plusMinus * mat(K_, J_) + plusMinus * mat(J_, K_); // 2*sin(alpha - gamma)\n        Scalar cneg = mat(J_, J_) - mat(K_, K_);                         // 2*cos(alpha - gamma)\n        res[0] = atan2(sneg, cneg);\n        res[2] = 0;\n      }\n    }\n    \n    template<typename Scalar>\n    static void CalcEulerAngles(\n      EulerAngles<Scalar, EulerSystem>& res,\n      const typename EulerAngles<Scalar, EulerSystem>::Matrix3& mat)\n    {\n      CalcEulerAngles_imp(\n        res.angles(), mat,\n        typename internal::conditional<IsTaitBryan, internal::true_type, internal::false_type>::type());\n\n      if (IsAlphaOpposite)\n        res.alpha() = -res.alpha();\n        \n      if (IsBetaOpposite)\n        res.beta() = -res.beta();\n        \n      if (IsGammaOpposite)\n        res.gamma() = -res.gamma();\n    }\n    \n    template <typename Scalar_, class _System>\n    friend class Eigen::EulerAngles;\n    \n    template<typename System,\n            typename Other,\n            int OtherRows,\n            int OtherCols>\n    friend struct internal::eulerangles_assign_impl;\n  };\n\n#define EIGEN_EULER_SYSTEM_TYPEDEF(A, B, C) \\\n  /** \\ingroup EulerAngles_Module */ \\\n  typedef EulerSystem<EULER_##A, EULER_##B, EULER_##C> EulerSystem##A##B##C;\n  \n  EIGEN_EULER_SYSTEM_TYPEDEF(X,Y,Z)\n  EIGEN_EULER_SYSTEM_TYPEDEF(X,Y,X)\n  EIGEN_EULER_SYSTEM_TYPEDEF(X,Z,Y)\n  EIGEN_EULER_SYSTEM_TYPEDEF(X,Z,X)\n  \n  EIGEN_EULER_SYSTEM_TYPEDEF(Y,Z,X)\n  EIGEN_EULER_SYSTEM_TYPEDEF(Y,Z,Y)\n  EIGEN_EULER_SYSTEM_TYPEDEF(Y,X,Z)\n  EIGEN_EULER_SYSTEM_TYPEDEF(Y,X,Y)\n  \n  EIGEN_EULER_SYSTEM_TYPEDEF(Z,X,Y)\n  EIGEN_EULER_SYSTEM_TYPEDEF(Z,X,Z)\n  EIGEN_EULER_SYSTEM_TYPEDEF(Z,Y,X)\n  EIGEN_EULER_SYSTEM_TYPEDEF(Z,Y,Z)\n}\n\n#endif // EIGEN_EULERSYSTEM_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/FFT/ei_fftw_impl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra. \n//\n// Copyright (C) 2009 Mark Borgerding mark a borgerding net\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\nnamespace Eigen { \n\nnamespace internal {\n\n  // FFTW uses non-const arguments\n  // so we must use ugly const_cast calls for all the args it uses\n  //\n  // This should be safe as long as \n  // 1. we use FFTW_ESTIMATE for all our planning\n  //       see the FFTW docs section 4.3.2 \"Planner Flags\"\n  // 2. fftw_complex is compatible with std::complex\n  //    This assumes std::complex<T> layout is array of size 2 with real,imag\n  template <typename T> \n  inline \n  T * fftw_cast(const T* p)\n  { \n      return const_cast<T*>( p); \n  }\n\n  inline \n  fftw_complex * fftw_cast( const std::complex<double> * p)\n  {\n      return const_cast<fftw_complex*>( reinterpret_cast<const fftw_complex*>(p) ); \n  }\n\n  inline \n  fftwf_complex * fftw_cast( const std::complex<float> * p)\n  { \n      return const_cast<fftwf_complex*>( reinterpret_cast<const fftwf_complex*>(p) ); \n  }\n\n  inline \n  fftwl_complex * fftw_cast( const std::complex<long double> * p)\n  { \n      return const_cast<fftwl_complex*>( reinterpret_cast<const fftwl_complex*>(p) ); \n  }\n\n  template <typename T> \n  struct fftw_plan {};\n\n  template <> \n  struct fftw_plan<float>\n  {\n      typedef float scalar_type;\n      typedef fftwf_complex complex_type;\n      fftwf_plan m_plan;\n      fftw_plan() :m_plan(NULL) {}\n      ~fftw_plan() {if (m_plan) fftwf_destroy_plan(m_plan);}\n\n      inline\n      void fwd(complex_type * dst,complex_type * src,int nfft) {\n          if (m_plan==NULL) m_plan = fftwf_plan_dft_1d(nfft,src,dst, FFTW_FORWARD, FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwf_execute_dft( m_plan, src,dst);\n      }\n      inline\n      void inv(complex_type * dst,complex_type * src,int nfft) {\n          if (m_plan==NULL) m_plan = fftwf_plan_dft_1d(nfft,src,dst, FFTW_BACKWARD , FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwf_execute_dft( m_plan, src,dst);\n      }\n      inline\n      void fwd(complex_type * dst,scalar_type * src,int nfft) {\n          if (m_plan==NULL) m_plan = fftwf_plan_dft_r2c_1d(nfft,src,dst,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwf_execute_dft_r2c( m_plan,src,dst);\n      }\n      inline\n      void inv(scalar_type * dst,complex_type * src,int nfft) {\n          if (m_plan==NULL)\n              m_plan = fftwf_plan_dft_c2r_1d(nfft,src,dst,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwf_execute_dft_c2r( m_plan, src,dst);\n      }\n\n      inline \n      void fwd2( complex_type * dst,complex_type * src,int n0,int n1) {\n          if (m_plan==NULL) m_plan = fftwf_plan_dft_2d(n0,n1,src,dst,FFTW_FORWARD,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwf_execute_dft( m_plan, src,dst);\n      }\n      inline \n      void inv2( complex_type * dst,complex_type * src,int n0,int n1) {\n          if (m_plan==NULL) m_plan = fftwf_plan_dft_2d(n0,n1,src,dst,FFTW_BACKWARD,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwf_execute_dft( m_plan, src,dst);\n      }\n\n  };\n  template <> \n  struct fftw_plan<double>\n  {\n      typedef double scalar_type;\n      typedef fftw_complex complex_type;\n      ::fftw_plan m_plan;\n      fftw_plan() :m_plan(NULL) {}\n      ~fftw_plan() {if (m_plan) fftw_destroy_plan(m_plan);}\n\n      inline\n      void fwd(complex_type * dst,complex_type * src,int nfft) {\n          if (m_plan==NULL) m_plan = fftw_plan_dft_1d(nfft,src,dst, FFTW_FORWARD, FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftw_execute_dft( m_plan, src,dst);\n      }\n      inline\n      void inv(complex_type * dst,complex_type * src,int nfft) {\n          if (m_plan==NULL) m_plan = fftw_plan_dft_1d(nfft,src,dst, FFTW_BACKWARD , FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftw_execute_dft( m_plan, src,dst);\n      }\n      inline\n      void fwd(complex_type * dst,scalar_type * src,int nfft) {\n          if (m_plan==NULL) m_plan = fftw_plan_dft_r2c_1d(nfft,src,dst,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftw_execute_dft_r2c( m_plan,src,dst);\n      }\n      inline\n      void inv(scalar_type * dst,complex_type * src,int nfft) {\n          if (m_plan==NULL)\n              m_plan = fftw_plan_dft_c2r_1d(nfft,src,dst,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftw_execute_dft_c2r( m_plan, src,dst);\n      }\n      inline \n      void fwd2( complex_type * dst,complex_type * src,int n0,int n1) {\n          if (m_plan==NULL) m_plan = fftw_plan_dft_2d(n0,n1,src,dst,FFTW_FORWARD,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftw_execute_dft( m_plan, src,dst);\n      }\n      inline \n      void inv2( complex_type * dst,complex_type * src,int n0,int n1) {\n          if (m_plan==NULL) m_plan = fftw_plan_dft_2d(n0,n1,src,dst,FFTW_BACKWARD,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftw_execute_dft( m_plan, src,dst);\n      }\n  };\n  template <> \n  struct fftw_plan<long double>\n  {\n      typedef long double scalar_type;\n      typedef fftwl_complex complex_type;\n      fftwl_plan m_plan;\n      fftw_plan() :m_plan(NULL) {}\n      ~fftw_plan() {if (m_plan) fftwl_destroy_plan(m_plan);}\n\n      inline\n      void fwd(complex_type * dst,complex_type * src,int nfft) {\n          if (m_plan==NULL) m_plan = fftwl_plan_dft_1d(nfft,src,dst, FFTW_FORWARD, FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwl_execute_dft( m_plan, src,dst);\n      }\n      inline\n      void inv(complex_type * dst,complex_type * src,int nfft) {\n          if (m_plan==NULL) m_plan = fftwl_plan_dft_1d(nfft,src,dst, FFTW_BACKWARD , FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwl_execute_dft( m_plan, src,dst);\n      }\n      inline\n      void fwd(complex_type * dst,scalar_type * src,int nfft) {\n          if (m_plan==NULL) m_plan = fftwl_plan_dft_r2c_1d(nfft,src,dst,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwl_execute_dft_r2c( m_plan,src,dst);\n      }\n      inline\n      void inv(scalar_type * dst,complex_type * src,int nfft) {\n          if (m_plan==NULL)\n              m_plan = fftwl_plan_dft_c2r_1d(nfft,src,dst,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwl_execute_dft_c2r( m_plan, src,dst);\n      }\n      inline \n      void fwd2( complex_type * dst,complex_type * src,int n0,int n1) {\n          if (m_plan==NULL) m_plan = fftwl_plan_dft_2d(n0,n1,src,dst,FFTW_FORWARD,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwl_execute_dft( m_plan, src,dst);\n      }\n      inline \n      void inv2( complex_type * dst,complex_type * src,int n0,int n1) {\n          if (m_plan==NULL) m_plan = fftwl_plan_dft_2d(n0,n1,src,dst,FFTW_BACKWARD,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwl_execute_dft( m_plan, src,dst);\n      }\n  };\n\n  template <typename Scalar_>\n  struct fftw_impl\n  {\n      typedef Scalar_ Scalar;\n      typedef std::complex<Scalar> Complex;\n\n      inline\n      void clear() \n      {\n        m_plans.clear();\n      }\n\n      // complex-to-complex forward FFT\n      inline\n      void fwd( Complex * dst,const Complex *src,int nfft)\n      {\n        get_plan(nfft,false,dst,src).fwd(fftw_cast(dst), fftw_cast(src),nfft );\n      }\n\n      // real-to-complex forward FFT\n      inline\n      void fwd( Complex * dst,const Scalar * src,int nfft) \n      {\n          get_plan(nfft,false,dst,src).fwd(fftw_cast(dst), fftw_cast(src) ,nfft);\n      }\n\n      // 2-d complex-to-complex\n      inline\n      void fwd2(Complex * dst, const Complex * src, int n0,int n1)\n      {\n          get_plan(n0,n1,false,dst,src).fwd2(fftw_cast(dst), fftw_cast(src) ,n0,n1);\n      }\n\n      // inverse complex-to-complex\n      inline\n      void inv(Complex * dst,const Complex  *src,int nfft)\n      {\n        get_plan(nfft,true,dst,src).inv(fftw_cast(dst), fftw_cast(src),nfft );\n      }\n\n      // half-complex to scalar\n      inline\n      void inv( Scalar * dst,const Complex * src,int nfft) \n      {\n        get_plan(nfft,true,dst,src).inv(fftw_cast(dst), fftw_cast(src),nfft );\n      }\n\n      // 2-d complex-to-complex\n      inline\n      void inv2(Complex * dst, const Complex * src, int n0,int n1)\n      {\n        get_plan(n0,n1,true,dst,src).inv2(fftw_cast(dst), fftw_cast(src) ,n0,n1);\n      }\n\n\n  protected:\n      typedef fftw_plan<Scalar> PlanData;\n\n      typedef Eigen::numext::int64_t int64_t;\n\n      typedef std::map<int64_t,PlanData> PlanMap;\n\n      PlanMap m_plans;\n\n      inline\n      PlanData & get_plan(int nfft,bool inverse,void * dst,const void * src)\n      {\n          bool inplace = (dst==src);\n          bool aligned = ( (reinterpret_cast<size_t>(src)&15) | (reinterpret_cast<size_t>(dst)&15) ) == 0;\n          int64_t key = ( (nfft<<3 ) | (inverse<<2) | (inplace<<1) | aligned ) << 1;\n          return m_plans[key];\n      }\n\n      inline\n      PlanData & get_plan(int n0,int n1,bool inverse,void * dst,const void * src)\n      {\n          bool inplace = (dst==src);\n          bool aligned = ( (reinterpret_cast<size_t>(src)&15) | (reinterpret_cast<size_t>(dst)&15) ) == 0;\n          int64_t key = ( ( (((int64_t)n0) << 30)|(n1<<3 ) | (inverse<<2) | (inplace<<1) | aligned ) << 1 ) + 1;\n          return m_plans[key];\n      }\n  };\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/FFT/ei_kissfft_impl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Mark Borgerding mark a borgerding net\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\nnamespace Eigen { \n\nnamespace internal {\n\n  // This FFT implementation was derived from kissfft http:sourceforge.net/projects/kissfft\n  // Copyright 2003-2009 Mark Borgerding\n\ntemplate <typename Scalar_>\nstruct kiss_cpx_fft\n{\n  typedef Scalar_ Scalar;\n  typedef std::complex<Scalar> Complex;\n  std::vector<Complex> m_twiddles;\n  std::vector<int> m_stageRadix;\n  std::vector<int> m_stageRemainder;\n  std::vector<Complex> m_scratchBuf;\n  bool m_inverse;\n\n  inline void make_twiddles(int nfft, bool inverse)\n  {\n    using numext::sin;\n    using numext::cos;\n    m_inverse = inverse;\n    m_twiddles.resize(nfft);\n    double phinc =  0.25 * double(EIGEN_PI) / nfft;\n    Scalar flip = inverse ? Scalar(1) : Scalar(-1);\n    m_twiddles[0] = Complex(Scalar(1), Scalar(0));\n    if ((nfft&1)==0)\n      m_twiddles[nfft/2] = Complex(Scalar(-1), Scalar(0));\n    int i=1;\n    for (;i*8<nfft;++i)\n    {\n      Scalar c = Scalar(cos(i*8*phinc));\n      Scalar s = Scalar(sin(i*8*phinc));\n      m_twiddles[i] = Complex(c, s*flip);\n      m_twiddles[nfft-i] = Complex(c, -s*flip);\n    }\n    for (;i*4<nfft;++i)\n    {\n      Scalar c = Scalar(cos((2*nfft-8*i)*phinc));\n      Scalar s = Scalar(sin((2*nfft-8*i)*phinc));\n      m_twiddles[i] = Complex(s, c*flip);\n      m_twiddles[nfft-i] = Complex(s, -c*flip);\n    }\n    for (;i*8<3*nfft;++i)\n    {\n      Scalar c = Scalar(cos((8*i-2*nfft)*phinc));\n      Scalar s = Scalar(sin((8*i-2*nfft)*phinc));\n      m_twiddles[i] = Complex(-s, c*flip);\n      m_twiddles[nfft-i] = Complex(-s, -c*flip);\n    }\n    for (;i*2<nfft;++i)\n    {\n      Scalar c = Scalar(cos((4*nfft-8*i)*phinc));\n      Scalar s = Scalar(sin((4*nfft-8*i)*phinc));\n      m_twiddles[i] = Complex(-c, s*flip);\n      m_twiddles[nfft-i] = Complex(-c, -s*flip);\n    }\n  }\n\n  void factorize(int nfft)\n  {\n    //start factoring out 4's, then 2's, then 3,5,7,9,...\n    int n= nfft;\n    int p=4;\n    do {\n      while (n % p) {\n        switch (p) {\n          case 4: p = 2; break;\n          case 2: p = 3; break;\n          default: p += 2; break;\n        }\n        if (p*p>n)\n          p=n;// impossible to have a factor > sqrt(n)\n      }\n      n /= p;\n      m_stageRadix.push_back(p);\n      m_stageRemainder.push_back(n);\n      if ( p > 5 )\n        m_scratchBuf.resize(p); // scratchbuf will be needed in bfly_generic\n    }while(n>1);\n  }\n\n  template <typename Src_>\n    inline\n    void work( int stage,Complex * xout, const Src_ * xin, size_t fstride,size_t in_stride)\n    {\n      int p = m_stageRadix[stage];\n      int m = m_stageRemainder[stage];\n      Complex * Fout_beg = xout;\n      Complex * Fout_end = xout + p*m;\n\n      if (m>1) {\n        do{\n          // recursive call:\n          // DFT of size m*p performed by doing\n          // p instances of smaller DFTs of size m, \n          // each one takes a decimated version of the input\n          work(stage+1, xout , xin, fstride*p,in_stride);\n          xin += fstride*in_stride;\n        }while( (xout += m) != Fout_end );\n      }else{\n        do{\n          *xout = *xin;\n          xin += fstride*in_stride;\n        }while(++xout != Fout_end );\n      }\n      xout=Fout_beg;\n\n      // recombine the p smaller DFTs \n      switch (p) {\n        case 2: bfly2(xout,fstride,m); break;\n        case 3: bfly3(xout,fstride,m); break;\n        case 4: bfly4(xout,fstride,m); break;\n        case 5: bfly5(xout,fstride,m); break;\n        default: bfly_generic(xout,fstride,m,p); break;\n      }\n    }\n\n  inline\n    void bfly2( Complex * Fout, const size_t fstride, int m)\n    {\n      for (int k=0;k<m;++k) {\n        Complex t = Fout[m+k] * m_twiddles[k*fstride];\n        Fout[m+k] = Fout[k] - t;\n        Fout[k] += t;\n      }\n    }\n\n  inline\n    void bfly4( Complex * Fout, const size_t fstride, const size_t m)\n    {\n      Complex scratch[6];\n      int negative_if_inverse = m_inverse * -2 +1;\n      for (size_t k=0;k<m;++k) {\n        scratch[0] = Fout[k+m] * m_twiddles[k*fstride];\n        scratch[1] = Fout[k+2*m] * m_twiddles[k*fstride*2];\n        scratch[2] = Fout[k+3*m] * m_twiddles[k*fstride*3];\n        scratch[5] = Fout[k] - scratch[1];\n\n        Fout[k] += scratch[1];\n        scratch[3] = scratch[0] + scratch[2];\n        scratch[4] = scratch[0] - scratch[2];\n        scratch[4] = Complex( scratch[4].imag()*negative_if_inverse , -scratch[4].real()* negative_if_inverse );\n\n        Fout[k+2*m]  = Fout[k] - scratch[3];\n        Fout[k] += scratch[3];\n        Fout[k+m] = scratch[5] + scratch[4];\n        Fout[k+3*m] = scratch[5] - scratch[4];\n      }\n    }\n\n  inline\n    void bfly3( Complex * Fout, const size_t fstride, const size_t m)\n    {\n      size_t k=m;\n      const size_t m2 = 2*m;\n      Complex *tw1,*tw2;\n      Complex scratch[5];\n      Complex epi3;\n      epi3 = m_twiddles[fstride*m];\n\n      tw1=tw2=&m_twiddles[0];\n\n      do{\n        scratch[1]=Fout[m] * *tw1;\n        scratch[2]=Fout[m2] * *tw2;\n\n        scratch[3]=scratch[1]+scratch[2];\n        scratch[0]=scratch[1]-scratch[2];\n        tw1 += fstride;\n        tw2 += fstride*2;\n        Fout[m] = Complex( Fout->real() - Scalar(.5)*scratch[3].real() , Fout->imag() - Scalar(.5)*scratch[3].imag() );\n        scratch[0] *= epi3.imag();\n        *Fout += scratch[3];\n        Fout[m2] = Complex(  Fout[m].real() + scratch[0].imag() , Fout[m].imag() - scratch[0].real() );\n        Fout[m] += Complex( -scratch[0].imag(),scratch[0].real() );\n        ++Fout;\n      }while(--k);\n    }\n\n  inline\n    void bfly5( Complex * Fout, const size_t fstride, const size_t m)\n    {\n      Complex *Fout0,*Fout1,*Fout2,*Fout3,*Fout4;\n      size_t u;\n      Complex scratch[13];\n      Complex * twiddles = &m_twiddles[0];\n      Complex *tw;\n      Complex ya,yb;\n      ya = twiddles[fstride*m];\n      yb = twiddles[fstride*2*m];\n\n      Fout0=Fout;\n      Fout1=Fout0+m;\n      Fout2=Fout0+2*m;\n      Fout3=Fout0+3*m;\n      Fout4=Fout0+4*m;\n\n      tw=twiddles;\n      for ( u=0; u<m; ++u ) {\n        scratch[0] = *Fout0;\n\n        scratch[1]  = *Fout1 * tw[u*fstride];\n        scratch[2]  = *Fout2 * tw[2*u*fstride];\n        scratch[3]  = *Fout3 * tw[3*u*fstride];\n        scratch[4]  = *Fout4 * tw[4*u*fstride];\n\n        scratch[7] = scratch[1] + scratch[4];\n        scratch[10] = scratch[1] - scratch[4];\n        scratch[8] = scratch[2] + scratch[3];\n        scratch[9] = scratch[2] - scratch[3];\n\n        *Fout0 +=  scratch[7];\n        *Fout0 +=  scratch[8];\n\n        scratch[5] = scratch[0] + Complex(\n            (scratch[7].real()*ya.real() ) + (scratch[8].real() *yb.real() ),\n            (scratch[7].imag()*ya.real()) + (scratch[8].imag()*yb.real())\n            );\n\n        scratch[6] = Complex(\n            (scratch[10].imag()*ya.imag()) + (scratch[9].imag()*yb.imag()),\n            -(scratch[10].real()*ya.imag()) - (scratch[9].real()*yb.imag())\n            );\n\n        *Fout1 = scratch[5] - scratch[6];\n        *Fout4 = scratch[5] + scratch[6];\n\n        scratch[11] = scratch[0] +\n          Complex(\n              (scratch[7].real()*yb.real()) + (scratch[8].real()*ya.real()),\n              (scratch[7].imag()*yb.real()) + (scratch[8].imag()*ya.real())\n              );\n\n        scratch[12] = Complex(\n            -(scratch[10].imag()*yb.imag()) + (scratch[9].imag()*ya.imag()),\n            (scratch[10].real()*yb.imag()) - (scratch[9].real()*ya.imag())\n            );\n\n        *Fout2=scratch[11]+scratch[12];\n        *Fout3=scratch[11]-scratch[12];\n\n        ++Fout0;++Fout1;++Fout2;++Fout3;++Fout4;\n      }\n    }\n\n  /* perform the butterfly for one stage of a mixed radix FFT */\n  inline\n    void bfly_generic(\n        Complex * Fout,\n        const size_t fstride,\n        int m,\n        int p\n        )\n    {\n      int u,k,q1,q;\n      Complex * twiddles = &m_twiddles[0];\n      Complex t;\n      int Norig = static_cast<int>(m_twiddles.size());\n      Complex * scratchbuf = &m_scratchBuf[0];\n\n      for ( u=0; u<m; ++u ) {\n        k=u;\n        for ( q1=0 ; q1<p ; ++q1 ) {\n          scratchbuf[q1] = Fout[ k  ];\n          k += m;\n        }\n\n        k=u;\n        for ( q1=0 ; q1<p ; ++q1 ) {\n          int twidx=0;\n          Fout[ k ] = scratchbuf[0];\n          for (q=1;q<p;++q ) {\n            twidx += static_cast<int>(fstride) * k;\n            if (twidx>=Norig) twidx-=Norig;\n            t=scratchbuf[q] * twiddles[twidx];\n            Fout[ k ] += t;\n          }\n          k += m;\n        }\n      }\n    }\n};\n\ntemplate <typename Scalar_>\nstruct kissfft_impl\n{\n  typedef Scalar_ Scalar;\n  typedef std::complex<Scalar> Complex;\n\n  void clear() \n  {\n    m_plans.clear();\n    m_realTwiddles.clear();\n  }\n\n  inline\n    void fwd( Complex * dst,const Complex *src,int nfft)\n    {\n      get_plan(nfft,false).work(0, dst, src, 1,1);\n    }\n\n  inline\n    void fwd2( Complex * dst,const Complex *src,int n0,int n1)\n    {\n        EIGEN_UNUSED_VARIABLE(dst);\n        EIGEN_UNUSED_VARIABLE(src);\n        EIGEN_UNUSED_VARIABLE(n0);\n        EIGEN_UNUSED_VARIABLE(n1);\n    }\n\n  inline\n    void inv2( Complex * dst,const Complex *src,int n0,int n1)\n    {\n        EIGEN_UNUSED_VARIABLE(dst);\n        EIGEN_UNUSED_VARIABLE(src);\n        EIGEN_UNUSED_VARIABLE(n0);\n        EIGEN_UNUSED_VARIABLE(n1);\n    }\n\n  // real-to-complex forward FFT\n  // perform two FFTs of src even and src odd\n  // then twiddle to recombine them into the half-spectrum format\n  // then fill in the conjugate symmetric half\n  inline\n    void fwd( Complex * dst,const Scalar * src,int nfft) \n    {\n      if ( nfft&3  ) {\n        // use generic mode for odd\n        m_tmpBuf1.resize(nfft);\n        get_plan(nfft,false).work(0, &m_tmpBuf1[0], src, 1,1);\n        std::copy(m_tmpBuf1.begin(),m_tmpBuf1.begin()+(nfft>>1)+1,dst );\n      }else{\n        int ncfft = nfft>>1;\n        int ncfft2 = nfft>>2;\n        Complex * rtw = real_twiddles(ncfft2);\n\n        // use optimized mode for even real\n        fwd( dst, reinterpret_cast<const Complex*> (src), ncfft);\n        Complex dc(dst[0].real() +  dst[0].imag());\n        Complex nyquist(dst[0].real() -  dst[0].imag());\n        int k;\n        for ( k=1;k <= ncfft2 ; ++k ) {\n          Complex fpk = dst[k];\n          Complex fpnk = conj(dst[ncfft-k]);\n          Complex f1k = fpk + fpnk;\n          Complex f2k = fpk - fpnk;\n          Complex tw= f2k * rtw[k-1];\n          dst[k] =  (f1k + tw) * Scalar(.5);\n          dst[ncfft-k] =  conj(f1k -tw)*Scalar(.5);\n        }\n        dst[0] = dc;\n        dst[ncfft] = nyquist;\n      }\n    }\n\n  // inverse complex-to-complex\n  inline\n    void inv(Complex * dst,const Complex  *src,int nfft)\n    {\n      get_plan(nfft,true).work(0, dst, src, 1,1);\n    }\n\n  // half-complex to scalar\n  inline\n    void inv( Scalar * dst,const Complex * src,int nfft) \n    {\n      if (nfft&3) {\n        m_tmpBuf1.resize(nfft);\n        m_tmpBuf2.resize(nfft);\n        std::copy(src,src+(nfft>>1)+1,m_tmpBuf1.begin() );\n        for (int k=1;k<(nfft>>1)+1;++k)\n          m_tmpBuf1[nfft-k] = conj(m_tmpBuf1[k]);\n        inv(&m_tmpBuf2[0],&m_tmpBuf1[0],nfft);\n        for (int k=0;k<nfft;++k)\n          dst[k] = m_tmpBuf2[k].real();\n      }else{\n        // optimized version for multiple of 4\n        int ncfft = nfft>>1;\n        int ncfft2 = nfft>>2;\n        Complex * rtw = real_twiddles(ncfft2);\n        m_tmpBuf1.resize(ncfft);\n        m_tmpBuf1[0] = Complex( src[0].real() + src[ncfft].real(), src[0].real() - src[ncfft].real() );\n        for (int k = 1; k <= ncfft / 2; ++k) {\n          Complex fk = src[k];\n          Complex fnkc = conj(src[ncfft-k]);\n          Complex fek = fk + fnkc;\n          Complex tmp = fk - fnkc;\n          Complex fok = tmp * conj(rtw[k-1]);\n          m_tmpBuf1[k] = fek + fok;\n          m_tmpBuf1[ncfft-k] = conj(fek - fok);\n        }\n        get_plan(ncfft,true).work(0, reinterpret_cast<Complex*>(dst), &m_tmpBuf1[0], 1,1);\n      }\n    }\n\n  protected:\n  typedef kiss_cpx_fft<Scalar> PlanData;\n  typedef std::map<int,PlanData> PlanMap;\n\n  PlanMap m_plans;\n  std::map<int, std::vector<Complex> > m_realTwiddles;\n  std::vector<Complex> m_tmpBuf1;\n  std::vector<Complex> m_tmpBuf2;\n\n  inline\n    int PlanKey(int nfft, bool isinverse) const { return (nfft<<1) | int(isinverse); }\n\n  inline\n    PlanData & get_plan(int nfft, bool inverse)\n    {\n      // TODO look for PlanKey(nfft, ! inverse) and conjugate the twiddles\n      PlanData & pd = m_plans[ PlanKey(nfft,inverse) ];\n      if ( pd.m_twiddles.size() == 0 ) {\n        pd.make_twiddles(nfft,inverse);\n        pd.factorize(nfft);\n      }\n      return pd;\n    }\n\n  inline\n    Complex * real_twiddles(int ncfft2)\n    {\n      using std::acos;\n      std::vector<Complex> & twidref = m_realTwiddles[ncfft2];// creates new if not there\n      if ( (int)twidref.size() != ncfft2 ) {\n        twidref.resize(ncfft2);\n        int ncfft= ncfft2<<1;\n        Scalar pi =  acos( Scalar(-1) );\n        for (int k=1;k<=ncfft2;++k) \n          twidref[k-1] = exp( Complex(0,-pi * (Scalar(k) / ncfft + Scalar(.5)) ) );\n      }\n      return &twidref[0];\n    }\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/IterativeSolvers/ConstrainedConjGrad.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n\n/* NOTE The functions of this file have been adapted from the GMM++ library */\n\n//========================================================================\n//\n// Copyright (C) 2002-2007 Yves Renard\n//\n// This file is a part of GETFEM++\n//\n// Getfem++ is free software; you can redistribute it and/or modify\n// it under the terms of the GNU Lesser General Public License as\n// published by the Free Software Foundation; version 2.1 of the License.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU Lesser General Public License for more details.\n// You should have received a copy of the GNU Lesser General Public\n// License along with this program; if not, write to the Free Software\n// Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301,\n// USA.\n//\n//========================================================================\n\n#include \"../../../../Eigen/src/Core/util/NonMPL2.h\"\n\n#ifndef EIGEN_CONSTRAINEDCG_H\n#define EIGEN_CONSTRAINEDCG_H\n\n#include \"../../../../Eigen/Core\"\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * Compute the pseudo inverse of the non-square matrix C such that\n  * \\f$ CINV = (C * C^T)^{-1} * C \\f$ based on a conjugate gradient method.\n  *\n  * This function is internally used by constrained_cg.\n  */\ntemplate <typename CMatrix, typename CINVMatrix>\nvoid pseudo_inverse(const CMatrix &C, CINVMatrix &CINV)\n{\n  // optimisable : copie de la ligne, precalcul de C * trans(C).\n  typedef typename CMatrix::Scalar Scalar;\n  typedef typename CMatrix::Index Index;\n  // FIXME use sparse vectors ?\n  typedef Matrix<Scalar,Dynamic,1> TmpVec;\n\n  Index rows = C.rows(), cols = C.cols();\n\n  TmpVec d(rows), e(rows), l(cols), p(rows), q(rows), r(rows);\n  Scalar rho, rho_1, alpha;\n  d.setZero();\n\n  typedef Triplet<double> T;\n  std::vector<T> tripletList;\n    \n  for (Index i = 0; i < rows; ++i)\n  {\n    d[i] = 1.0;\n    rho = 1.0;\n    e.setZero();\n    r = d;\n    p = d;\n\n    while (rho >= 1e-38)\n    { /* conjugate gradient to compute e             */\n      /* which is the i-th row of inv(C * trans(C))  */\n      l = C.transpose() * p;\n      q = C * l;\n      alpha = rho / p.dot(q);\n      e +=  alpha * p;\n      r += -alpha * q;\n      rho_1 = rho;\n      rho = r.dot(r);\n      p = (rho/rho_1) * p + r;\n    }\n\n    l = C.transpose() * e; // l is the i-th row of CINV\n    // FIXME add a generic \"prune/filter\" expression for both dense and sparse object to sparse\n    for (Index j=0; j<l.size(); ++j)\n      if (l[j]<1e-15)\n\ttripletList.push_back(T(i,j,l(j)));\n\n\t\n    d[i] = 0.0;\n  }\n  CINV.setFromTriplets(tripletList.begin(), tripletList.end());\n}\n\n\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * Constrained conjugate gradient\n  *\n  * Computes the minimum of \\f$ 1/2((Ax).x) - bx \\f$ under the constraint \\f$ Cx \\le f \\f$\n  */\ntemplate<typename TMatrix, typename CMatrix,\n         typename VectorX, typename VectorB, typename VectorF>\nvoid constrained_cg(const TMatrix& A, const CMatrix& C, VectorX& x,\n                       const VectorB& b, const VectorF& f, IterationController &iter)\n{\n  using std::sqrt;\n  typedef typename TMatrix::Scalar Scalar;\n  typedef typename TMatrix::Index Index;\n  typedef Matrix<Scalar,Dynamic,1>  TmpVec;\n\n  Scalar rho = 1.0, rho_1, lambda, gamma;\n  Index xSize = x.size();\n  TmpVec  p(xSize), q(xSize), q2(xSize),\n          r(xSize), old_z(xSize), z(xSize),\n          memox(xSize);\n  std::vector<bool> satured(C.rows());\n  p.setZero();\n  iter.setRhsNorm(sqrt(b.dot(b))); // gael vect_sp(PS, b, b)\n  if (iter.rhsNorm() == 0.0) iter.setRhsNorm(1.0);\n\n  SparseMatrix<Scalar,RowMajor> CINV(C.rows(), C.cols());\n  pseudo_inverse(C, CINV);\n\n  while(true)\n  {\n    // computation of residual\n    old_z = z;\n    memox = x;\n    r = b;\n    r += A * -x;\n    z = r;\n    bool transition = false;\n    for (Index i = 0; i < C.rows(); ++i)\n    {\n      Scalar al = C.row(i).dot(x) - f.coeff(i);\n      if (al >= -1.0E-15)\n      {\n        if (!satured[i])\n        {\n          satured[i] = true;\n          transition = true;\n        }\n        Scalar bb = CINV.row(i).dot(z);\n        if (bb > 0.0)\n          // FIXME: we should allow that: z += -bb * C.row(i);\n          for (typename CMatrix::InnerIterator it(C,i); it; ++it)\n            z.coeffRef(it.index()) -= bb*it.value();\n      }\n      else\n        satured[i] = false;\n    }\n\n    // descent direction\n    rho_1 = rho;\n    rho = r.dot(z);\n\n    if (iter.finished(rho)) break;\n    if (transition || iter.first()) gamma = 0.0;\n    else gamma = (std::max)(0.0, (rho - old_z.dot(z)) / rho_1);\n    p = z + gamma*p;\n\n    ++iter;\n    // one dimensionnal optimization\n    q = A * p;\n    lambda = rho / q.dot(p);\n    for (Index i = 0; i < C.rows(); ++i)\n    {\n      if (!satured[i])\n      {\n        Scalar bb = C.row(i).dot(p) - f[i];\n        if (bb > 0.0)\n          lambda = (std::min)(lambda, (f.coeff(i)-C.row(i).dot(x)) / bb);\n      }\n    }\n    x += lambda * p;\n    memox -= x;\n  }\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_CONSTRAINEDCG_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/IterativeSolvers/DGMRES.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_DGMRES_H\n#define EIGEN_DGMRES_H\n\n#include \"../../../../Eigen/Eigenvalues\"\n\nnamespace Eigen { \n  \ntemplate< typename MatrixType_,\n          typename Preconditioner_ = DiagonalPreconditioner<typename MatrixType_::Scalar> >\nclass DGMRES;\n\nnamespace internal {\n\ntemplate< typename MatrixType_, typename Preconditioner_>\nstruct traits<DGMRES<MatrixType_,Preconditioner_> >\n{\n  typedef MatrixType_ MatrixType;\n  typedef Preconditioner_ Preconditioner;\n};\n\n/** \\brief Computes a permutation vector to have a sorted sequence\n  * \\param vec The vector to reorder.\n  * \\param perm gives the sorted sequence on output. Must be initialized with 0..n-1\n  * \\param ncut Put  the ncut smallest elements at the end of the vector\n  * WARNING This is an expensive sort, so should be used only \n  * for small size vectors\n  * TODO Use modified QuickSplit or std::nth_element to get the smallest values \n  */\ntemplate <typename VectorType, typename IndexType>\nvoid sortWithPermutation (VectorType& vec, IndexType& perm, typename IndexType::Scalar& ncut)\n{\n  eigen_assert(vec.size() == perm.size());\n  bool flag; \n  for (Index k  = 0; k < ncut; k++)\n  {\n    flag = false;\n    for (Index j = 0; j < vec.size()-1; j++)\n    {\n      if ( vec(perm(j)) < vec(perm(j+1)) )\n      {\n        std::swap(perm(j),perm(j+1)); \n        flag = true;\n      }\n      if (!flag) break; // The vector is in sorted order\n    }\n  }\n}\n\n}\n/**\n * \\ingroup IterativeLinearSolvers_Module\n * \\brief A Restarted GMRES with deflation.\n * This class implements a modification of the GMRES solver for\n * sparse linear systems. The basis is built with modified \n * Gram-Schmidt. At each restart, a few approximated eigenvectors\n * corresponding to the smallest eigenvalues are used to build a\n * preconditioner for the next cycle. This preconditioner \n * for deflation can be combined with any other preconditioner, \n * the IncompleteLUT for instance. The preconditioner is applied \n * at right of the matrix and the combination is multiplicative.\n * \n * \\tparam MatrixType_ the type of the sparse matrix A, can be a dense or a sparse matrix.\n * \\tparam Preconditioner_ the type of the preconditioner. Default is DiagonalPreconditioner\n * Typical usage :\n * \\code\n * SparseMatrix<double> A;\n * VectorXd x, b; \n * //Fill A and b ...\n * DGMRES<SparseMatrix<double> > solver;\n * solver.set_restart(30); // Set restarting value\n * solver.setEigenv(1); // Set the number of eigenvalues to deflate\n * solver.compute(A);\n * x = solver.solve(b);\n * \\endcode\n * \n * DGMRES can also be used in a matrix-free context, see the following \\link MatrixfreeSolverExample example \\endlink.\n *\n * References :\n * [1] D. NUENTSA WAKAM and F. PACULL, Memory Efficient Hybrid\n *  Algebraic Solvers for Linear Systems Arising from Compressible\n *  Flows, Computers and Fluids, In Press,\n *  https://doi.org/10.1016/j.compfluid.2012.03.023   \n * [2] K. Burrage and J. Erhel, On the performance of various \n * adaptive preconditioned GMRES strategies, 5(1998), 101-121.\n * [3] J. Erhel, K. Burrage and B. Pohl, Restarted GMRES \n *  preconditioned by deflation,J. Computational and Applied\n *  Mathematics, 69(1996), 303-318. \n\n * \n */\ntemplate< typename MatrixType_, typename Preconditioner_>\nclass DGMRES : public IterativeSolverBase<DGMRES<MatrixType_,Preconditioner_> >\n{\n    typedef IterativeSolverBase<DGMRES> Base;\n    using Base::matrix;\n    using Base::m_error;\n    using Base::m_iterations;\n    using Base::m_info;\n    using Base::m_isInitialized;\n    using Base::m_tolerance; \n  public:\n    using Base::_solve_impl;\n    using Base::_solve_with_guess_impl;\n    typedef MatrixType_ MatrixType;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef Preconditioner_ Preconditioner;\n    typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix; \n    typedef Matrix<RealScalar,Dynamic,Dynamic> DenseRealMatrix; \n    typedef Matrix<Scalar,Dynamic,1> DenseVector;\n    typedef Matrix<RealScalar,Dynamic,1> DenseRealVector; \n    typedef Matrix<std::complex<RealScalar>, Dynamic, 1> ComplexVector;\n \n    \n  /** Default constructor. */\n  DGMRES() : Base(),m_restart(30),m_neig(0),m_r(0),m_maxNeig(5),m_isDeflAllocated(false),m_isDeflInitialized(false) {}\n\n  /** Initialize the solver with matrix \\a A for further \\c Ax=b solving.\n    * \n    * This constructor is a shortcut for the default constructor followed\n    * by a call to compute().\n    * \n    * \\warning this class stores a reference to the matrix A as well as some\n    * precomputed values that depend on it. Therefore, if \\a A is changed\n    * this class becomes invalid. Call compute() to update it with the new\n    * matrix A, or modify a copy of A.\n    */\n  template<typename MatrixDerived>\n  explicit DGMRES(const EigenBase<MatrixDerived>& A) : Base(A.derived()), m_restart(30),m_neig(0),m_r(0),m_maxNeig(5),m_isDeflAllocated(false),m_isDeflInitialized(false) {}\n\n  ~DGMRES() {}\n  \n  /** \\internal */\n  template<typename Rhs,typename Dest>\n  void _solve_vector_with_guess_impl(const Rhs& b, Dest& x) const\n  {\n    EIGEN_STATIC_ASSERT(Rhs::ColsAtCompileTime==1 || Dest::ColsAtCompileTime==1, YOU_TRIED_CALLING_A_VECTOR_METHOD_ON_A_MATRIX);\n    \n    m_iterations = Base::maxIterations();\n    m_error = Base::m_tolerance;\n    \n    dgmres(matrix(), b, x, Base::m_preconditioner);\n  }\n\n  /** \n   * Get the restart value\n    */\n  Index restart() { return m_restart; }\n  \n  /** \n   * Set the restart value (default is 30)  \n   */\n  void set_restart(const Index restart) { m_restart=restart; }\n  \n  /** \n   * Set the number of eigenvalues to deflate at each restart \n   */\n  void setEigenv(const Index neig) \n  {\n    m_neig = neig;\n    if (neig+1 > m_maxNeig) m_maxNeig = neig+1; // To allow for complex conjugates\n  }\n  \n  /** \n   * Get the size of the deflation subspace size\n   */ \n  Index deflSize() {return m_r; }\n  \n  /**\n   * Set the maximum size of the deflation subspace\n   */\n  void setMaxEigenv(const Index maxNeig) { m_maxNeig = maxNeig; }\n  \n  protected:\n    // DGMRES algorithm \n    template<typename Rhs, typename Dest>\n    void dgmres(const MatrixType& mat,const Rhs& rhs, Dest& x, const Preconditioner& precond) const;\n    // Perform one cycle of GMRES\n    template<typename Dest>\n    Index dgmresCycle(const MatrixType& mat, const Preconditioner& precond, Dest& x, DenseVector& r0, RealScalar& beta, const RealScalar& normRhs, Index& nbIts) const; \n    // Compute data to use for deflation \n    Index dgmresComputeDeflationData(const MatrixType& mat, const Preconditioner& precond, const Index& it, StorageIndex& neig) const;\n    // Apply deflation to a vector\n    template<typename RhsType, typename DestType>\n    Index dgmresApplyDeflation(const RhsType& In, DestType& Out) const; \n    ComplexVector schurValues(const ComplexSchur<DenseMatrix>& schurofH) const;\n    ComplexVector schurValues(const RealSchur<DenseMatrix>& schurofH) const;\n    // Init data for deflation\n    void dgmresInitDeflation(Index& rows) const; \n    mutable DenseMatrix m_V; // Krylov basis vectors\n    mutable DenseMatrix m_H; // Hessenberg matrix \n    mutable DenseMatrix m_Hes; // Initial hessenberg matrix without Givens rotations applied\n    mutable Index m_restart; // Maximum size of the Krylov subspace\n    mutable DenseMatrix m_U; // Vectors that form the basis of the invariant subspace \n    mutable DenseMatrix m_MU; // matrix operator applied to m_U (for next cycles)\n    mutable DenseMatrix m_T; /* T=U^T*M^{-1}*A*U */\n    mutable PartialPivLU<DenseMatrix> m_luT; // LU factorization of m_T\n    mutable StorageIndex m_neig; //Number of eigenvalues to extract at each restart\n    mutable Index m_r; // Current number of deflated eigenvalues, size of m_U\n    mutable Index m_maxNeig; // Maximum number of eigenvalues to deflate\n    mutable RealScalar m_lambdaN; //Modulus of the largest eigenvalue of A\n    mutable bool m_isDeflAllocated;\n    mutable bool m_isDeflInitialized;\n    \n    //Adaptive strategy \n    mutable RealScalar m_smv; // Smaller multiple of the remaining number of steps allowed\n    mutable bool m_force; // Force the use of deflation at each restart\n    \n}; \n/** \n * \\brief Perform several cycles of restarted GMRES with modified Gram Schmidt, \n * \n * A right preconditioner is used combined with deflation.\n * \n */\ntemplate< typename MatrixType_, typename Preconditioner_>\ntemplate<typename Rhs, typename Dest>\nvoid DGMRES<MatrixType_, Preconditioner_>::dgmres(const MatrixType& mat,const Rhs& rhs, Dest& x,\n              const Preconditioner& precond) const\n{\n  const RealScalar considerAsZero = (std::numeric_limits<RealScalar>::min)();\n\n  RealScalar normRhs = rhs.norm();\n  if(normRhs <= considerAsZero) \n  {\n    x.setZero();\n    m_error = 0;\n    return;\n  }\n\n  //Initialization\n  m_isDeflInitialized = false;\n  Index n = mat.rows(); \n  DenseVector r0(n); \n  Index nbIts = 0; \n  m_H.resize(m_restart+1, m_restart);\n  m_Hes.resize(m_restart, m_restart);\n  m_V.resize(n,m_restart+1);\n  //Initial residual vector and initial norm\n  if(x.squaredNorm()==0) \n    x = precond.solve(rhs);\n  r0 = rhs - mat * x; \n  RealScalar beta = r0.norm(); \n  \n  m_error = beta/normRhs; \n  if(m_error < m_tolerance)\n    m_info = Success; \n  else\n    m_info = NoConvergence;\n  \n  // Iterative process\n  while (nbIts < m_iterations && m_info == NoConvergence)\n  {\n    dgmresCycle(mat, precond, x, r0, beta, normRhs, nbIts); \n    \n    // Compute the new residual vector for the restart \n    if (nbIts < m_iterations && m_info == NoConvergence) {\n      r0 = rhs - mat * x;\n      beta = r0.norm();\n    }\n  }\n} \n\n/**\n * \\brief Perform one restart cycle of DGMRES\n * \\param mat The coefficient matrix\n * \\param precond The preconditioner\n * \\param x the new approximated solution\n * \\param r0 The initial residual vector\n * \\param beta The norm of the residual computed so far\n * \\param normRhs The norm of the right hand side vector\n * \\param nbIts The number of iterations\n */\ntemplate< typename MatrixType_, typename Preconditioner_>\ntemplate<typename Dest>\nIndex DGMRES<MatrixType_, Preconditioner_>::dgmresCycle(const MatrixType& mat, const Preconditioner& precond, Dest& x, DenseVector& r0, RealScalar& beta, const RealScalar& normRhs, Index& nbIts) const\n{\n  //Initialization \n  DenseVector g(m_restart+1); // Right hand side of the least square problem\n  g.setZero();  \n  g(0) = Scalar(beta); \n  m_V.col(0) = r0/beta; \n  m_info = NoConvergence; \n  std::vector<JacobiRotation<Scalar> >gr(m_restart); // Givens rotations\n  Index it = 0; // Number of inner iterations \n  Index n = mat.rows();\n  DenseVector tv1(n), tv2(n);  //Temporary vectors\n  while (m_info == NoConvergence && it < m_restart && nbIts < m_iterations)\n  {    \n    // Apply preconditioner(s) at right\n    if (m_isDeflInitialized )\n    {\n      dgmresApplyDeflation(m_V.col(it), tv1); // Deflation\n      tv2 = precond.solve(tv1); \n    }\n    else\n    {\n      tv2 = precond.solve(m_V.col(it)); // User's selected preconditioner\n    }\n    tv1 = mat * tv2; \n   \n    // Orthogonalize it with the previous basis in the basis using modified Gram-Schmidt\n    Scalar coef; \n    for (Index i = 0; i <= it; ++i)\n    { \n      coef = tv1.dot(m_V.col(i));\n      tv1 = tv1 - coef * m_V.col(i); \n      m_H(i,it) = coef; \n      m_Hes(i,it) = coef; \n    }\n    // Normalize the vector \n    coef = tv1.norm(); \n    m_V.col(it+1) = tv1/coef;\n    m_H(it+1, it) = coef;\n//     m_Hes(it+1,it) = coef; \n    \n    // FIXME Check for happy breakdown \n    \n    // Update Hessenberg matrix with Givens rotations\n    for (Index i = 1; i <= it; ++i) \n    {\n      m_H.col(it).applyOnTheLeft(i-1,i,gr[i-1].adjoint());\n    }\n    // Compute the new plane rotation \n    gr[it].makeGivens(m_H(it, it), m_H(it+1,it)); \n    // Apply the new rotation\n    m_H.col(it).applyOnTheLeft(it,it+1,gr[it].adjoint());\n    g.applyOnTheLeft(it,it+1, gr[it].adjoint()); \n    \n    beta = std::abs(g(it+1));\n    m_error = beta/normRhs; \n    // std::cerr << nbIts << \" Relative Residual Norm \" << m_error << std::endl;\n    it++; nbIts++; \n    \n    if (m_error < m_tolerance)\n    {\n      // The method has converged\n      m_info = Success;\n      break;\n    }\n  }\n  \n  // Compute the new coefficients by solving the least square problem\n//   it++;\n  //FIXME  Check first if the matrix is singular ... zero diagonal\n  DenseVector nrs(m_restart); \n  nrs = m_H.topLeftCorner(it,it).template triangularView<Upper>().solve(g.head(it)); \n  \n  // Form the new solution\n  if (m_isDeflInitialized)\n  {\n    tv1 = m_V.leftCols(it) * nrs; \n    dgmresApplyDeflation(tv1, tv2); \n    x = x + precond.solve(tv2);\n  }\n  else\n    x = x + precond.solve(m_V.leftCols(it) * nrs); \n  \n  // Go for a new cycle and compute data for deflation\n  if(nbIts < m_iterations && m_info == NoConvergence && m_neig > 0 && (m_r+m_neig) < m_maxNeig)\n    dgmresComputeDeflationData(mat, precond, it, m_neig); \n  return 0; \n  \n}\n\n\ntemplate< typename MatrixType_, typename Preconditioner_>\nvoid DGMRES<MatrixType_, Preconditioner_>::dgmresInitDeflation(Index& rows) const\n{\n  m_U.resize(rows, m_maxNeig);\n  m_MU.resize(rows, m_maxNeig); \n  m_T.resize(m_maxNeig, m_maxNeig);\n  m_lambdaN = 0.0; \n  m_isDeflAllocated = true; \n}\n\ntemplate< typename MatrixType_, typename Preconditioner_>\ninline typename DGMRES<MatrixType_, Preconditioner_>::ComplexVector DGMRES<MatrixType_, Preconditioner_>::schurValues(const ComplexSchur<DenseMatrix>& schurofH) const\n{\n  return schurofH.matrixT().diagonal();\n}\n\ntemplate< typename MatrixType_, typename Preconditioner_>\ninline typename DGMRES<MatrixType_, Preconditioner_>::ComplexVector DGMRES<MatrixType_, Preconditioner_>::schurValues(const RealSchur<DenseMatrix>& schurofH) const\n{\n  const DenseMatrix& T = schurofH.matrixT();\n  Index it = T.rows();\n  ComplexVector eig(it);\n  Index j = 0;\n  while (j < it-1)\n  {\n    if (T(j+1,j) ==Scalar(0))\n    {\n      eig(j) = std::complex<RealScalar>(T(j,j),RealScalar(0)); \n      j++; \n    }\n    else\n    {\n      eig(j) = std::complex<RealScalar>(T(j,j),T(j+1,j)); \n      eig(j+1) = std::complex<RealScalar>(T(j,j+1),T(j+1,j+1));\n      j++;\n    }\n  }\n  if (j < it-1) eig(j) = std::complex<RealScalar>(T(j,j),RealScalar(0));\n  return eig;\n}\n\ntemplate< typename MatrixType_, typename Preconditioner_>\nIndex DGMRES<MatrixType_, Preconditioner_>::dgmresComputeDeflationData(const MatrixType& mat, const Preconditioner& precond, const Index& it, StorageIndex& neig) const\n{\n  // First, find the Schur form of the Hessenberg matrix H\n  typename internal::conditional<NumTraits<Scalar>::IsComplex, ComplexSchur<DenseMatrix>, RealSchur<DenseMatrix> >::type schurofH; \n  bool computeU = true;\n  DenseMatrix matrixQ(it,it); \n  matrixQ.setIdentity();\n  schurofH.computeFromHessenberg(m_Hes.topLeftCorner(it,it), matrixQ, computeU); \n  \n  ComplexVector eig(it);\n  Matrix<StorageIndex,Dynamic,1>perm(it);\n  eig = this->schurValues(schurofH);\n  \n  // Reorder the absolute values of Schur values\n  DenseRealVector modulEig(it); \n  for (Index j=0; j<it; ++j) modulEig(j) = std::abs(eig(j)); \n  perm.setLinSpaced(it,0,internal::convert_index<StorageIndex>(it-1));\n  internal::sortWithPermutation(modulEig, perm, neig);\n  \n  if (!m_lambdaN)\n  {\n    m_lambdaN = (std::max)(modulEig.maxCoeff(), m_lambdaN);\n  }\n  //Count the real number of extracted eigenvalues (with complex conjugates)\n  Index nbrEig = 0; \n  while (nbrEig < neig)\n  {\n    if(eig(perm(it-nbrEig-1)).imag() == RealScalar(0)) nbrEig++; \n    else nbrEig += 2; \n  }\n  // Extract the  Schur vectors corresponding to the smallest Ritz values\n  DenseMatrix Sr(it, nbrEig); \n  Sr.setZero();\n  for (Index j = 0; j < nbrEig; j++)\n  {\n    Sr.col(j) = schurofH.matrixU().col(perm(it-j-1));\n  }\n  \n  // Form the Schur vectors of the initial matrix using the Krylov basis\n  DenseMatrix X; \n  X = m_V.leftCols(it) * Sr;\n  if (m_r)\n  {\n   // Orthogonalize X against m_U using modified Gram-Schmidt\n   for (Index j = 0; j < nbrEig; j++)\n     for (Index k =0; k < m_r; k++)\n      X.col(j) = X.col(j) - (m_U.col(k).dot(X.col(j)))*m_U.col(k); \n  }\n  \n  // Compute m_MX = A * M^-1 * X\n  Index m = m_V.rows();\n  if (!m_isDeflAllocated) \n    dgmresInitDeflation(m); \n  DenseMatrix MX(m, nbrEig);\n  DenseVector tv1(m);\n  for (Index j = 0; j < nbrEig; j++)\n  {\n    tv1 = mat * X.col(j);\n    MX.col(j) = precond.solve(tv1);\n  }\n  \n  //Update m_T = [U'MU U'MX; X'MU X'MX]\n  m_T.block(m_r, m_r, nbrEig, nbrEig) = X.transpose() * MX; \n  if(m_r)\n  {\n    m_T.block(0, m_r, m_r, nbrEig) = m_U.leftCols(m_r).transpose() * MX; \n    m_T.block(m_r, 0, nbrEig, m_r) = X.transpose() * m_MU.leftCols(m_r);\n  }\n  \n  // Save X into m_U and m_MX in m_MU\n  for (Index j = 0; j < nbrEig; j++) m_U.col(m_r+j) = X.col(j);\n  for (Index j = 0; j < nbrEig; j++) m_MU.col(m_r+j) = MX.col(j);\n  // Increase the size of the invariant subspace\n  m_r += nbrEig; \n  \n  // Factorize m_T into m_luT\n  m_luT.compute(m_T.topLeftCorner(m_r, m_r));\n  \n  //FIXME CHeck if the factorization was correctly done (nonsingular matrix)\n  m_isDeflInitialized = true;\n  return 0; \n}\ntemplate<typename MatrixType_, typename Preconditioner_>\ntemplate<typename RhsType, typename DestType>\nIndex DGMRES<MatrixType_, Preconditioner_>::dgmresApplyDeflation(const RhsType &x, DestType &y) const\n{\n  DenseVector x1 = m_U.leftCols(m_r).transpose() * x; \n  y = x + m_U.leftCols(m_r) * ( m_lambdaN * m_luT.solve(x1) - x1);\n  return 0; \n}\n\n} // end namespace Eigen\n#endif \n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/IterativeSolvers/GMRES.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2012, 2014 Kolja Brix <brix@igpm.rwth-aaachen.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_GMRES_H\n#define EIGEN_GMRES_H\n\nnamespace Eigen {\n\nnamespace internal {\n\n/**\n* Generalized Minimal Residual Algorithm based on the\n* Arnoldi algorithm implemented with Householder reflections.\n*\n* Parameters:\n*  \\param mat       matrix of linear system of equations\n*  \\param rhs       right hand side vector of linear system of equations\n*  \\param x         on input: initial guess, on output: solution\n*  \\param precond   preconditioner used\n*  \\param iters     on input: maximum number of iterations to perform\n*                   on output: number of iterations performed\n*  \\param restart   number of iterations for a restart\n*  \\param tol_error on input: relative residual tolerance\n*                   on output: residuum achieved\n*\n* \\sa IterativeMethods::bicgstab()\n*\n*\n* For references, please see:\n*\n* Saad, Y. and Schultz, M. H.\n* GMRES: A Generalized Minimal Residual Algorithm for Solving Nonsymmetric Linear Systems.\n* SIAM J.Sci.Stat.Comp. 7, 1986, pp. 856 - 869.\n*\n* Saad, Y.\n* Iterative Methods for Sparse Linear Systems.\n* Society for Industrial and Applied Mathematics, Philadelphia, 2003.\n*\n* Walker, H. F.\n* Implementations of the GMRES method.\n* Comput.Phys.Comm. 53, 1989, pp. 311 - 320.\n*\n* Walker, H. F.\n* Implementation of the GMRES Method using Householder Transformations.\n* SIAM J.Sci.Stat.Comp. 9, 1988, pp. 152 - 163.\n*\n*/\ntemplate<typename MatrixType, typename Rhs, typename Dest, typename Preconditioner>\nbool gmres(const MatrixType & mat, const Rhs & rhs, Dest & x, const Preconditioner & precond,\n    Index &iters, const Index &restart, typename Dest::RealScalar & tol_error) {\n\n  using std::sqrt;\n  using std::abs;\n\n  typedef typename Dest::RealScalar RealScalar;\n  typedef typename Dest::Scalar Scalar;\n  typedef Matrix < Scalar, Dynamic, 1 > VectorType;\n  typedef Matrix < Scalar, Dynamic, Dynamic, ColMajor> FMatrixType;\n\n  const RealScalar considerAsZero = (std::numeric_limits<RealScalar>::min)();\n\n  if(rhs.norm() <= considerAsZero) \n  {\n    x.setZero();\n    tol_error = 0;\n    return true;\n  }\n\n  RealScalar tol = tol_error;\n  const Index maxIters = iters;\n  iters = 0;\n\n  const Index m = mat.rows();\n\n  // residual and preconditioned residual\n  VectorType p0 = rhs - mat*x;\n  VectorType r0 = precond.solve(p0);\n\n  const RealScalar r0Norm = r0.norm();\n\n  // is initial guess already good enough?\n  if(r0Norm == 0)\n  {\n    tol_error = 0;\n    return true;\n  }\n\n  // storage for Hessenberg matrix and Householder data\n  FMatrixType H   = FMatrixType::Zero(m, restart + 1);\n  VectorType w    = VectorType::Zero(restart + 1);\n  VectorType tau  = VectorType::Zero(restart + 1);\n\n  // storage for Jacobi rotations\n  std::vector < JacobiRotation < Scalar > > G(restart);\n  \n  // storage for temporaries\n  VectorType t(m), v(m), workspace(m), x_new(m);\n\n  // generate first Householder vector\n  Ref<VectorType> H0_tail = H.col(0).tail(m - 1);\n  RealScalar beta;\n  r0.makeHouseholder(H0_tail, tau.coeffRef(0), beta);\n  w(0) = Scalar(beta);\n  \n  for (Index k = 1; k <= restart; ++k)\n  {\n    ++iters;\n\n    v = VectorType::Unit(m, k - 1);\n\n    // apply Householder reflections H_{1} ... H_{k-1} to v\n    // TODO: use a HouseholderSequence\n    for (Index i = k - 1; i >= 0; --i) {\n      v.tail(m - i).applyHouseholderOnTheLeft(H.col(i).tail(m - i - 1), tau.coeffRef(i), workspace.data());\n    }\n\n    // apply matrix M to v:  v = mat * v;\n    t.noalias() = mat * v;\n    v = precond.solve(t);\n\n    // apply Householder reflections H_{k-1} ... H_{1} to v\n    // TODO: use a HouseholderSequence\n    for (Index i = 0; i < k; ++i) {\n      v.tail(m - i).applyHouseholderOnTheLeft(H.col(i).tail(m - i - 1), tau.coeffRef(i), workspace.data());\n    }\n\n    if (v.tail(m - k).norm() != 0.0)\n    {\n      if (k <= restart)\n      {\n        // generate new Householder vector\n        Ref<VectorType> Hk_tail = H.col(k).tail(m - k - 1);\n        v.tail(m - k).makeHouseholder(Hk_tail, tau.coeffRef(k), beta);\n\n        // apply Householder reflection H_{k} to v\n        v.tail(m - k).applyHouseholderOnTheLeft(Hk_tail, tau.coeffRef(k), workspace.data());\n      }\n    }\n\n    if (k > 1)\n    {\n      for (Index i = 0; i < k - 1; ++i)\n      {\n        // apply old Givens rotations to v\n        v.applyOnTheLeft(i, i + 1, G[i].adjoint());\n      }\n    }\n\n    if (k<m && v(k) != (Scalar) 0)\n    {\n      // determine next Givens rotation\n      G[k - 1].makeGivens(v(k - 1), v(k));\n\n      // apply Givens rotation to v and w\n      v.applyOnTheLeft(k - 1, k, G[k - 1].adjoint());\n      w.applyOnTheLeft(k - 1, k, G[k - 1].adjoint());\n    }\n\n    // insert coefficients into upper matrix triangle\n    H.col(k-1).head(k) = v.head(k);\n\n    tol_error = abs(w(k)) / r0Norm;\n    bool stop = (k==m || tol_error < tol || iters == maxIters);\n\n    if (stop || k == restart)\n    {\n      // solve upper triangular system\n      Ref<VectorType> y = w.head(k);\n      H.topLeftCorner(k, k).template triangularView <Upper>().solveInPlace(y);\n\n      // use Horner-like scheme to calculate solution vector\n      x_new.setZero();\n      for (Index i = k - 1; i >= 0; --i)\n      {\n        x_new(i) += y(i);\n        // apply Householder reflection H_{i} to x_new\n        x_new.tail(m - i).applyHouseholderOnTheLeft(H.col(i).tail(m - i - 1), tau.coeffRef(i), workspace.data());\n      }\n\n      x += x_new;\n\n      if(stop)\n      {\n        return true;\n      }\n      else\n      {\n        k=0;\n\n        // reset data for restart\n        p0.noalias() = rhs - mat*x;\n        r0 = precond.solve(p0);\n\n        // clear Hessenberg matrix and Householder data\n        H.setZero();\n        w.setZero();\n        tau.setZero();\n\n        // generate first Householder vector\n        r0.makeHouseholder(H0_tail, tau.coeffRef(0), beta);\n        w(0) = Scalar(beta);\n      }\n    }\n  }\n\n  return false;\n\n}\n\n}\n\ntemplate< typename MatrixType_,\n          typename Preconditioner_ = DiagonalPreconditioner<typename MatrixType_::Scalar> >\nclass GMRES;\n\nnamespace internal {\n\ntemplate< typename MatrixType_, typename Preconditioner_>\nstruct traits<GMRES<MatrixType_,Preconditioner_> >\n{\n  typedef MatrixType_ MatrixType;\n  typedef Preconditioner_ Preconditioner;\n};\n\n}\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\brief A GMRES solver for sparse square problems\n  *\n  * This class allows to solve for A.x = b sparse linear problems using a generalized minimal\n  * residual method. The vectors x and b can be either dense or sparse.\n  *\n  * \\tparam MatrixType_ the type of the sparse matrix A, can be a dense or a sparse matrix.\n  * \\tparam Preconditioner_ the type of the preconditioner. Default is DiagonalPreconditioner\n  *\n  * The maximal number of iterations and tolerance value can be controlled via the setMaxIterations()\n  * and setTolerance() methods. The defaults are the size of the problem for the maximal number of iterations\n  * and NumTraits<Scalar>::epsilon() for the tolerance.\n  *\n  * This class can be used as the direct solver classes. Here is a typical usage example:\n  * \\code\n  * int n = 10000;\n  * VectorXd x(n), b(n);\n  * SparseMatrix<double> A(n,n);\n  * // fill A and b\n  * GMRES<SparseMatrix<double> > solver(A);\n  * x = solver.solve(b);\n  * std::cout << \"#iterations:     \" << solver.iterations() << std::endl;\n  * std::cout << \"estimated error: \" << solver.error()      << std::endl;\n  * // update b, and solve again\n  * x = solver.solve(b);\n  * \\endcode\n  *\n  * By default the iterations start with x=0 as an initial guess of the solution.\n  * One can control the start using the solveWithGuess() method.\n  * \n  * GMRES can also be used in a matrix-free context, see the following \\link MatrixfreeSolverExample example \\endlink.\n  *\n  * \\sa class SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner\n  */\ntemplate< typename MatrixType_, typename Preconditioner_>\nclass GMRES : public IterativeSolverBase<GMRES<MatrixType_,Preconditioner_> >\n{\n  typedef IterativeSolverBase<GMRES> Base;\n  using Base::matrix;\n  using Base::m_error;\n  using Base::m_iterations;\n  using Base::m_info;\n  using Base::m_isInitialized;\n\nprivate:\n  Index m_restart;\n\npublic:\n  using Base::_solve_impl;\n  typedef MatrixType_ MatrixType;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef Preconditioner_ Preconditioner;\n\npublic:\n\n  /** Default constructor. */\n  GMRES() : Base(), m_restart(30) {}\n\n  /** Initialize the solver with matrix \\a A for further \\c Ax=b solving.\n    *\n    * This constructor is a shortcut for the default constructor followed\n    * by a call to compute().\n    *\n    * \\warning this class stores a reference to the matrix A as well as some\n    * precomputed values that depend on it. Therefore, if \\a A is changed\n    * this class becomes invalid. Call compute() to update it with the new\n    * matrix A, or modify a copy of A.\n    */\n  template<typename MatrixDerived>\n  explicit GMRES(const EigenBase<MatrixDerived>& A) : Base(A.derived()), m_restart(30) {}\n\n  ~GMRES() {}\n\n  /** Get the number of iterations after that a restart is performed.\n    */\n  Index get_restart() { return m_restart; }\n\n  /** Set the number of iterations after that a restart is performed.\n    *  \\param restart   number of iterations for a restarti, default is 30.\n    */\n  void set_restart(const Index restart) { m_restart=restart; }\n\n  /** \\internal */\n  template<typename Rhs,typename Dest>\n  void _solve_vector_with_guess_impl(const Rhs& b, Dest& x) const\n  {\n    m_iterations = Base::maxIterations();\n    m_error = Base::m_tolerance;\n    bool ret = internal::gmres(matrix(), b, x, Base::m_preconditioner, m_iterations, m_restart, m_error);\n    m_info = (!ret) ? NumericalIssue\n          : m_error <= Base::m_tolerance ? Success\n          : NoConvergence;\n  }\n\nprotected:\n\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_GMRES_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/IterativeSolvers/IDRS.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2020 Chris Schoutrop <c.e.m.schoutrop@tue.nl>\n// Copyright (C) 2020 Jens Wehner <j.wehner@esciencecenter.nl>\n// Copyright (C) 2020 Jan van Dijk <j.v.dijk@tue.nl>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#ifndef EIGEN_IDRS_H\n#define EIGEN_IDRS_H\n\nnamespace Eigen\n{\n\n\tnamespace internal\n\t{\n\t\t/**     \\internal Low-level Induced Dimension Reduction algoritm\n\t\t        \\param A The matrix A\n\t\t        \\param b The right hand side vector b\n\t\t        \\param x On input and initial solution, on output the computed solution.\n\t\t        \\param precond A preconditioner being able to efficiently solve for an\n\t\t                  approximation of Ax=b (regardless of b)\n\t\t        \\param iter On input the max number of iteration, on output the number of performed iterations.\n\t\t        \\param relres On input the tolerance error, on output an estimation of the relative error.\n\t\t        \\param S On input Number of the dimension of the shadow space.\n\t\t\t\t\\param smoothing switches residual smoothing on.\n\t\t\t\t\\param angle small omega lead to faster convergence at the expense of numerical stability\n\t\t\t\t\\param replacement switches on a residual replacement strategy to increase accuracy of residual at the expense of more Mat*vec products\n\t\t        \\return false in the case of numerical issue, for example a break down of IDRS.\n\t\t*/\n\t\ttemplate<typename Vector, typename RealScalar>\n\t\ttypename Vector::Scalar omega(const Vector& t, const Vector& s, RealScalar angle)\n\t\t{\n\t\t\tusing numext::abs;\n\t\t\ttypedef typename Vector::Scalar Scalar;\n\t\t\tconst RealScalar ns = s.norm();\n\t\t\tconst RealScalar nt = t.norm();\n\t\t\tconst Scalar ts = t.dot(s);\n\t\t\tconst RealScalar rho = abs(ts / (nt * ns));\n\n\t\t\tif (rho < angle) {\n\t\t\t\tif (ts == Scalar(0)) {\n\t\t\t\t\treturn Scalar(0);\n\t\t\t\t}\n\t\t\t\t// Original relation for om is given by\n\t\t\t\t// om = om * angle / rho;\n\t\t\t\t// To alleviate potential (near) division by zero this can be rewritten as\n\t\t\t\t// om = angle * (ns / nt) * (ts / abs(ts)) = angle * (ns / nt) * sgn(ts)\n  \t\t\t\treturn angle * (ns / nt) * (ts / abs(ts));\n\t\t\t}\n\t\t\treturn ts / (nt * nt);\n\t\t}\n\n\t\ttemplate <typename MatrixType, typename Rhs, typename Dest, typename Preconditioner>\n\t\tbool idrs(const MatrixType& A, const Rhs& b, Dest& x, const Preconditioner& precond,\n\t\t\tIndex& iter,\n\t\t\ttypename Dest::RealScalar& relres, Index S, bool smoothing, typename Dest::RealScalar angle, bool replacement)\n\t\t{\n\t\t\ttypedef typename Dest::RealScalar RealScalar;\n\t\t\ttypedef typename Dest::Scalar Scalar;\n\t\t\ttypedef Matrix<Scalar, Dynamic, 1> VectorType;\n\t\t\ttypedef Matrix<Scalar, Dynamic, Dynamic, ColMajor> DenseMatrixType;\n\t\t\tconst Index N = b.size();\n\t\t\tS = S < x.rows() ? S : x.rows();\n\t\t\tconst RealScalar tol = relres;\n\t\t\tconst Index maxit = iter;\n\n\t\t\tIndex replacements = 0;\n\t\t\tbool trueres = false;\n\n\t\t\tFullPivLU<DenseMatrixType> lu_solver;\n\n\t\t\tDenseMatrixType P;\n\t\t\t{\n\t\t\t\tHouseholderQR<DenseMatrixType> qr(DenseMatrixType::Random(N, S));\n\t\t\t    P = (qr.householderQ() * DenseMatrixType::Identity(N, S));\n\t\t\t}\n\n\t\t\tconst RealScalar normb = b.norm();\n\n\t\t\tif (internal::isApprox(normb, RealScalar(0)))\n\t\t\t{\n\t\t\t\t//Solution is the zero vector\n\t\t\t\tx.setZero();\n\t\t\t\titer = 0;\n\t\t\t\trelres = 0;\n\t\t\t\treturn true;\n\t\t\t}\n\t\t\t // from http://homepage.tudelft.nl/1w5b5/IDRS/manual.pdf\n\t\t\t // A peak in the residual is considered dangerously high if‖ri‖/‖b‖> C(tol/epsilon).\n\t\t\t // With epsilon the\n             // relative machine precision. The factor tol/epsilon corresponds to the size of a\n             // finite precision number that is so large that the absolute round-off error in\n             // this number, when propagated through the process, makes it impossible to\n             // achieve the required accuracy.The factor C accounts for the accumulation of\n             // round-off errors. This parameter has beenset to 10−3.\n\t\t\t // mp is epsilon/C\n\t\t\t // 10^3 * eps is very conservative, so normally no residual replacements will take place. \n\t\t\t // It only happens if things go very wrong. Too many restarts may ruin the convergence.\n\t\t\tconst RealScalar mp = RealScalar(1e3) * NumTraits<Scalar>::epsilon();\n\n\n\n\t\t\t//Compute initial residual\n\t\t\tconst RealScalar tolb = tol * normb; //Relative tolerance\n\t\t\tVectorType r = b - A * x;\n\n\t\t\tVectorType x_s, r_s;\n\n\t\t\tif (smoothing)\n\t\t\t{\n\t\t\t\tx_s = x;\n\t\t\t\tr_s = r;\n\t\t\t}\n\n\t\t\tRealScalar normr = r.norm();\n\n\t\t\tif (normr <= tolb)\n\t\t\t{\n\t\t\t\t//Initial guess is a good enough solution\n\t\t\t\titer = 0;\n\t\t\t\trelres = normr / normb;\n\t\t\t\treturn true;\n\t\t\t}\n\n\t\t\tDenseMatrixType G = DenseMatrixType::Zero(N, S);\n\t\t\tDenseMatrixType U = DenseMatrixType::Zero(N, S);\n\t\t\tDenseMatrixType M = DenseMatrixType::Identity(S, S);\n\t\t\tVectorType t(N), v(N);\n\t\t\tScalar om = 1.;\n\n\t\t\t//Main iteration loop, guild G-spaces:\n\t\t\titer = 0;\n\n\t\t\twhile (normr > tolb && iter < maxit)\n\t\t\t{\n\t\t\t\t//New right hand size for small system:\n\t\t\t\tVectorType f = (r.adjoint() * P).adjoint();\n\n\t\t\t\tfor (Index k = 0; k < S; ++k)\n\t\t\t\t{\n\t\t\t\t\t//Solve small system and make v orthogonal to P:\n\t\t\t\t\t//c = M(k:s,k:s)\\f(k:s);\n\t\t\t\t\tlu_solver.compute(M.block(k , k , S -k, S - k ));\n\t\t\t\t\tVectorType c = lu_solver.solve(f.segment(k , S - k ));\n\t\t\t\t\t//v = r - G(:,k:s)*c;\n\t\t\t\t\tv = r - G.rightCols(S - k ) * c;\n\t\t\t\t\t//Preconditioning\n\t\t\t\t\tv = precond.solve(v);\n\n\t\t\t\t\t//Compute new U(:,k) and G(:,k), G(:,k) is in space G_j\n\t\t\t\t\tU.col(k) = U.rightCols(S - k ) * c + om * v;\n\t\t\t\t\tG.col(k) = A * U.col(k );\n\n\t\t\t\t\t//Bi-Orthogonalise the new basis vectors:\n\t\t\t\t\tfor (Index i = 0; i < k-1 ; ++i)\n\t\t\t\t\t{\n\t\t\t\t\t\t//alpha =  ( P(:,i)'*G(:,k) )/M(i,i);\n\t\t\t\t\t\tScalar alpha = P.col(i ).dot(G.col(k )) / M(i, i );\n\t\t\t\t\t\tG.col(k ) = G.col(k ) - alpha * G.col(i );\n\t\t\t\t\t\tU.col(k ) = U.col(k ) - alpha * U.col(i );\n\t\t\t\t\t}\n\n\t\t\t\t\t//New column of M = P'*G  (first k-1 entries are zero)\n\t\t\t\t\t//M(k:s,k) = (G(:,k)'*P(:,k:s))';\n\t\t\t\t\tM.block(k , k , S - k , 1) = (G.col(k ).adjoint() * P.rightCols(S - k )).adjoint();\n\n\t\t\t\t\tif (internal::isApprox(M(k,k), Scalar(0)))\n\t\t\t\t\t{\n\t\t\t\t\t\treturn false;\n\t\t\t\t\t}\n\n\t\t\t\t\t//Make r orthogonal to q_i, i = 0..k-1\n\t\t\t\t\tScalar beta = f(k ) / M(k , k );\n\t\t\t\t\tr = r - beta * G.col(k );\n\t\t\t\t\tx = x + beta * U.col(k );\n\t\t\t\t\tnormr = r.norm();\n\n\t\t\t\t\tif (replacement && normr > tolb / mp)\n\t\t\t\t\t{\n\t\t\t\t\t\ttrueres = true;\n\t\t\t\t\t}\n\n\t\t\t\t\t//Smoothing:\n\t\t\t\t\tif (smoothing)\n\t\t\t\t\t{\n\t\t\t\t\t\tt = r_s - r;\n\t\t\t\t\t\t//gamma is a Scalar, but the conversion is not allowed\n\t\t\t\t\t\tScalar gamma = t.dot(r_s) / t.norm();\n\t\t\t\t\t\tr_s = r_s - gamma * t;\n\t\t\t\t\t\tx_s = x_s - gamma * (x_s - x);\n\t\t\t\t\t\tnormr = r_s.norm();\n\t\t\t\t\t}\n\n\t\t\t\t\tif (normr < tolb || iter == maxit)\n\t\t\t\t\t{\n\t\t\t\t\t\tbreak;\n\t\t\t\t\t}\n\n\t\t\t\t\t//New f = P'*r (first k  components are zero)\n\t\t\t\t\tif (k < S-1)\n\t\t\t\t\t{\n\t\t\t\t\t\tf.segment(k + 1, S - (k + 1) ) = f.segment(k + 1 , S - (k + 1)) - beta * M.block(k + 1 , k , S - (k + 1), 1);\n\t\t\t\t\t}\n\t\t\t\t}//end for\n\n\t\t\t\tif (normr < tolb || iter == maxit)\n\t\t\t\t{\n\t\t\t\t\tbreak;\n\t\t\t\t}\n\n\t\t\t\t//Now we have sufficient vectors in G_j to compute residual in G_j+1\n\t\t\t\t//Note: r is already perpendicular to P so v = r\n\t\t\t\t//Preconditioning\n\t\t\t\tv = r;\n\t\t\t\tv = precond.solve(v);\n\n\t\t\t\t//Matrix-vector multiplication:\n\t\t\t\tt = A * v;\n\n\t\t\t\t//Computation of a new omega\n\t\t\t\tom = internal::omega(t, r, angle);\n\n\t\t\t\tif (om == RealScalar(0.0))\n\t\t\t\t{\n\t\t\t\t\treturn false;\n\t\t\t\t}\n\n\t\t\t\tr = r - om * t;\n\t\t\t\tx = x + om * v;\n\t\t\t\tnormr = r.norm();\n\n\t\t\t\tif (replacement && normr > tolb / mp)\n\t\t\t\t{\n\t\t\t\t\ttrueres = true;\n\t\t\t\t}\n\n\t\t\t\t//Residual replacement?\n\t\t\t\tif (trueres && normr < normb)\n\t\t\t\t{\n\t\t\t\t\tr = b - A * x;\n\t\t\t\t\ttrueres = false;\n\t\t\t\t\treplacements++;\n\t\t\t\t}\n\n\t\t\t\t//Smoothing:\n\t\t\t\tif (smoothing)\n\t\t\t\t{\n\t\t\t\t\tt = r_s - r;\n\t\t\t\t\tScalar gamma = t.dot(r_s) /t.norm();\n\t\t\t\t\tr_s = r_s - gamma * t;\n\t\t\t\t\tx_s = x_s - gamma * (x_s - x);\n\t\t\t\t\tnormr = r_s.norm();\n\t\t\t\t}\n\n\t\t\t\titer++;\n\n\t\t\t}//end while\n\n\t\t\tif (smoothing)\n\t\t\t{\n\t\t\t\tx = x_s;\n\t\t\t}\n\t\t\trelres=normr/normb;\n\t\t\treturn true;\n\t\t}\n\n\t}  // namespace internal\n\n\ttemplate <typename MatrixType_, typename Preconditioner_ = DiagonalPreconditioner<typename MatrixType_::Scalar> >\n\tclass IDRS;\n\n\tnamespace internal\n\t{\n\n\t\ttemplate <typename MatrixType_, typename Preconditioner_>\n\t\tstruct traits<Eigen::IDRS<MatrixType_, Preconditioner_> >\n\t\t{\n\t\t\ttypedef MatrixType_ MatrixType;\n\t\t\ttypedef Preconditioner_ Preconditioner;\n\t\t};\n\n\t}  // namespace internal\n\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\brief The Induced Dimension Reduction method (IDR(s)) is a short-recurrences Krylov method for sparse square problems.\n  *\n  * This class allows to solve for A.x = b sparse linear problems. The vectors x and b can be either dense or sparse.\n  * he Induced Dimension Reduction method, IDR(), is a robust and efficient short-recurrence Krylov subspace method for\n  * solving large nonsymmetric systems of linear equations.\n  *\n  * For indefinite systems IDR(S) outperforms both BiCGStab and BiCGStab(L). Additionally, IDR(S) can handle matrices\n  * with complex eigenvalues more efficiently than BiCGStab.\n  *\n  * Many problems that do not converge for BiCGSTAB converge for IDR(s) (for larger values of s). And if both methods \n  * converge the convergence for IDR(s) is typically much faster for difficult systems (for example indefinite problems). \n  *\n  * IDR(s) is a limited memory finite termination method. In exact arithmetic it converges in at most N+N/s iterations,\n  * with N the system size.  It uses a fixed number of 4+3s vector. In comparison, BiCGSTAB terminates in 2N iterations \n  * and uses 7 vectors. GMRES terminates in at most N iterations, and uses I+3 vectors, with I the number of iterations. \n  * Restarting GMRES limits the memory consumption, but destroys the finite termination property.\n  *\n  * \\tparam MatrixType_ the type of the sparse matrix A, can be a dense or a sparse matrix.\n  * \\tparam Preconditioner_ the type of the preconditioner. Default is DiagonalPreconditioner\n  *\n  * \\implsparsesolverconcept\n  *\n  * The maximal number of iterations and tolerance value can be controlled via the setMaxIterations()\n  * and setTolerance() methods. The defaults are the size of the problem for the maximal number of iterations\n  * and NumTraits<Scalar>::epsilon() for the tolerance.\n  *\n  * The tolerance corresponds to the relative residual error: |Ax-b|/|b|\n  *\n  * \\b Performance: when using sparse matrices, best performance is achied for a row-major sparse matrix format.\n  * Moreover, in this case multi-threading can be exploited if the user code is compiled with OpenMP enabled.\n  * See \\ref TopicMultiThreading for details.\n  *\n  * By default the iterations start with x=0 as an initial guess of the solution.\n  * One can control the start using the solveWithGuess() method.\n  *\n  * IDR(s) can also be used in a matrix-free context, see the following \\link MatrixfreeSolverExample example \\endlink.\n  *\n  * \\sa class SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner\n  */\n\ttemplate <typename MatrixType_, typename Preconditioner_>\n\tclass IDRS : public IterativeSolverBase<IDRS<MatrixType_, Preconditioner_> >\n\t{\n\n\t\tpublic:\n\t\t\ttypedef MatrixType_ MatrixType;\n\t\t\ttypedef typename MatrixType::Scalar Scalar;\n\t\t\ttypedef typename MatrixType::RealScalar RealScalar;\n\t\t\ttypedef Preconditioner_ Preconditioner;\n\n\t\tprivate:\n\t\t\ttypedef IterativeSolverBase<IDRS> Base;\n\t\t\tusing Base::m_error;\n\t\t\tusing Base::m_info;\n\t\t\tusing Base::m_isInitialized;\n\t\t\tusing Base::m_iterations;\n\t\t\tusing Base::matrix;\n\t\t\tIndex m_S;\n\t\t\tbool m_smoothing;\n\t\t\tRealScalar m_angle;\n\t\t\tbool m_residual;\n\n\t\tpublic:\n\t\t\t/** Default constructor. */\n\t\t\tIDRS(): m_S(4), m_smoothing(false), m_angle(RealScalar(0.7)), m_residual(false) {}\n\n\t\t\t/**     Initialize the solver with matrix \\a A for further \\c Ax=b solving.\n\n\t\t\t        This constructor is a shortcut for the default constructor followed\n\t\t\t        by a call to compute().\n\n\t\t\t        \\warning this class stores a reference to the matrix A as well as some\n\t\t\t        precomputed values that depend on it. Therefore, if \\a A is changed\n\t\t\t        this class becomes invalid. Call compute() to update it with the new\n\t\t\t        matrix A, or modify a copy of A.\n\t\t\t*/\n\t\t\ttemplate <typename MatrixDerived>\n\t\t\texplicit IDRS(const EigenBase<MatrixDerived>& A) : Base(A.derived()), m_S(4), m_smoothing(false),\n\t\t\t\t\t\t\t\t\t\t\t\t\t\t\t   m_angle(RealScalar(0.7)), m_residual(false) {}\n\n\n\t\t\t/** \\internal */\n\t\t\t/**     Loops over the number of columns of b and does the following:\n\t\t\t                1. sets the tolerence and maxIterations\n\t\t\t                2. Calls the function that has the core solver routine\n\t\t\t*/\n\t\t\ttemplate <typename Rhs, typename Dest>\n\t\t\tvoid _solve_vector_with_guess_impl(const Rhs& b, Dest& x) const\n\t\t\t{\n\t\t\t\tm_iterations = Base::maxIterations();\n\t\t\t\tm_error = Base::m_tolerance;\n\n\t\t\t\tbool ret = internal::idrs(matrix(), b, x, Base::m_preconditioner, m_iterations, m_error, m_S,m_smoothing,m_angle,m_residual);\n\n\t\t\t\tm_info = (!ret) ? NumericalIssue : m_error <= Base::m_tolerance ? Success : NoConvergence;\n\t\t\t}\n\n\t\t\t/** Sets the parameter S, indicating the dimension of the shadow space. Default is 4*/\n\t\t\tvoid setS(Index S)\n\t\t\t{\n\t\t\t\tif (S < 1)\n\t\t\t\t{\n\t\t\t\t\tS = 4;\n\t\t\t\t}\n\n\t\t\t\tm_S = S;\n\t\t\t}\n\n\t\t\t/** Switches off and on smoothing.\n\t\t\tResidual smoothing results in monotonically decreasing residual norms at\n\t\t\tthe expense of two extra vectors of storage and a few extra vector\n\t\t\toperations. Although monotonic decrease of the residual norms is a\n\t\t\tdesirable property, the rate of convergence of the unsmoothed process and\n\t\t\tthe smoothed process is basically the same. Default is off */\n\t\t\tvoid setSmoothing(bool smoothing)\n\t\t\t{\n\t\t\t\tm_smoothing=smoothing;\n\t\t\t}\n\n\t\t\t/** The angle must be a real scalar. In IDR(s), a value for the\n\t\t\titeration parameter omega must be chosen in every s+1th step. The most\n\t\t\tnatural choice is to select a value to minimize the norm of the next residual.\n\t\t\tThis corresponds to the parameter omega = 0. In practice, this may lead to\n\t\t\tvalues of omega that are so small that the other iteration parameters\n\t\t\tcannot be computed with sufficient accuracy. In such cases it is better to\n\t\t\tincrease the value of omega sufficiently such that a compromise is reached\n\t\t\tbetween accurate computations and reduction of the residual norm. The\n\t\t\tparameter angle =0.7 (”maintaining the convergence strategy”)\n\t\t\tresults in such a compromise. */\n\t\t\tvoid setAngle(RealScalar angle)\n\t\t\t{\n\t\t\t\tm_angle=angle;\n\t\t\t}\n\n\t\t\t/** The parameter replace is a logical that determines whether a\n\t\t\tresidual replacement strategy is employed to increase the accuracy of the\n\t\t\tsolution. */\n\t\t\tvoid setResidualUpdate(bool update)\n\t\t\t{\n\t\t\t\tm_residual=update;\n\t\t\t}\n\n\t};\n\n}  // namespace Eigen\n\n#endif /* EIGEN_IDRS_H */\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/IterativeSolvers/IncompleteLU.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_INCOMPLETE_LU_H\n#define EIGEN_INCOMPLETE_LU_H\n\nnamespace Eigen { \n\ntemplate <typename Scalar_>\nclass IncompleteLU : public SparseSolverBase<IncompleteLU<Scalar_> >\n{\n  protected:\n    typedef SparseSolverBase<IncompleteLU<Scalar_> > Base;\n    using Base::m_isInitialized;\n    \n    typedef Scalar_ Scalar;\n    typedef Matrix<Scalar,Dynamic,1> Vector;\n    typedef typename Vector::Index Index;\n    typedef SparseMatrix<Scalar,RowMajor> FactorType;\n\n  public:\n    typedef Matrix<Scalar,Dynamic,Dynamic> MatrixType;\n\n    IncompleteLU() {}\n\n    template<typename MatrixType>\n    IncompleteLU(const MatrixType& mat)\n    {\n      compute(mat);\n    }\n\n    Index rows() const { return m_lu.rows(); }\n    Index cols() const { return m_lu.cols(); }\n\n    template<typename MatrixType>\n    IncompleteLU& compute(const MatrixType& mat)\n    {\n      m_lu = mat;\n      int size = mat.cols();\n      Vector diag(size);\n      for(int i=0; i<size; ++i)\n      {\n        typename FactorType::InnerIterator k_it(m_lu,i);\n        for(; k_it && k_it.index()<i; ++k_it)\n        {\n          int k = k_it.index();\n          k_it.valueRef() /= diag(k);\n\n          typename FactorType::InnerIterator j_it(k_it);\n          typename FactorType::InnerIterator kj_it(m_lu, k);\n          while(kj_it && kj_it.index()<=k) ++kj_it;\n          for(++j_it; j_it; )\n          {\n            if(kj_it.index()==j_it.index())\n            {\n              j_it.valueRef() -= k_it.value() * kj_it.value();\n              ++j_it;\n              ++kj_it;\n            }\n            else if(kj_it.index()<j_it.index()) ++kj_it;\n            else                                ++j_it;\n          }\n        }\n        if(k_it && k_it.index()==i) diag(i) = k_it.value();\n        else                        diag(i) = 1;\n      }\n      m_isInitialized = true;\n      return *this;\n    }\n\n    template<typename Rhs, typename Dest>\n    void _solve_impl(const Rhs& b, Dest& x) const\n    {\n      x = m_lu.template triangularView<UnitLower>().solve(b);\n      x = m_lu.template triangularView<Upper>().solve(x);\n    }\n\n  protected:\n    FactorType m_lu;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_INCOMPLETE_LU_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/IterativeSolvers/IterationController.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n\n/* NOTE The class IterationController has been adapted from the iteration\n *      class of the GMM++ and ITL libraries.\n */\n\n//=======================================================================\n// Copyright (C) 1997-2001\n// Authors: Andrew Lumsdaine <lums@osl.iu.edu> \n//          Lie-Quan Lee     <llee@osl.iu.edu>\n//\n// This file is part of the Iterative Template Library\n//\n// You should have received a copy of the License Agreement for the\n// Iterative Template Library along with the software;  see the\n// file LICENSE.  \n//\n// Permission to modify the code and to distribute modified code is\n// granted, provided the text of this NOTICE is retained, a notice that\n// the code was modified is included with the above COPYRIGHT NOTICE and\n// with the COPYRIGHT NOTICE in the LICENSE file, and that the LICENSE\n// file is distributed with the modified code.\n//\n// LICENSOR MAKES NO REPRESENTATIONS OR WARRANTIES, EXPRESS OR IMPLIED.\n// By way of example, but not limitation, Licensor MAKES NO\n// REPRESENTATIONS OR WARRANTIES OF MERCHANTABILITY OR FITNESS FOR ANY\n// PARTICULAR PURPOSE OR THAT THE USE OF THE LICENSED SOFTWARE COMPONENTS\n// OR DOCUMENTATION WILL NOT INFRINGE ANY PATENTS, COPYRIGHTS, TRADEMARKS\n// OR OTHER RIGHTS.\n//=======================================================================\n\n//========================================================================\n//\n// Copyright (C) 2002-2007 Yves Renard\n//\n// This file is a part of GETFEM++\n//\n// Getfem++ is free software; you can redistribute it and/or modify\n// it under the terms of the GNU Lesser General Public License as\n// published by the Free Software Foundation; version 2.1 of the License.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU Lesser General Public License for more details.\n// You should have received a copy of the GNU Lesser General Public\n// License along with this program; if not, write to the Free Software\n// Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301,\n// USA.\n//\n//========================================================================\n\n#include \"../../../../Eigen/src/Core/util/NonMPL2.h\"\n\n#ifndef EIGEN_ITERATION_CONTROLLER_H\n#define EIGEN_ITERATION_CONTROLLER_H\n\nnamespace Eigen { \n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\class IterationController\n  *\n  * \\brief Controls the iterations of the iterative solvers\n  *\n  * This class has been adapted from the iteration class of GMM++ and ITL libraries.\n  *\n  */\nclass IterationController\n{\n  protected :\n    double m_rhsn;        ///< Right hand side norm\n    size_t m_maxiter;     ///< Max. number of iterations\n    int m_noise;          ///< if noise > 0 iterations are printed\n    double m_resmax;      ///< maximum residual\n    double m_resminreach, m_resadd;\n    size_t m_nit;         ///< iteration number\n    double m_res;         ///< last computed residual\n    bool m_written;\n    void (*m_callback)(const IterationController&);\n  public :\n\n    void init()\n    {\n      m_nit = 0; m_res = 0.0; m_written = false;\n      m_resminreach = 1E50; m_resadd = 0.0;\n      m_callback = 0;\n    }\n\n    IterationController(double r = 1.0E-8, int noi = 0, size_t mit = size_t(-1))\n      : m_rhsn(1.0), m_maxiter(mit), m_noise(noi), m_resmax(r) { init(); }\n\n    void operator ++(int) { m_nit++; m_written = false; m_resadd += m_res; }\n    void operator ++() { (*this)++; }\n\n    bool first() { return m_nit == 0; }\n\n    /* get/set the \"noisyness\" (verbosity) of the solvers */\n    int noiseLevel() const { return m_noise; }\n    void setNoiseLevel(int n) { m_noise = n; }\n    void reduceNoiseLevel() { if (m_noise > 0) m_noise--; }\n\n    double maxResidual() const { return m_resmax; }\n    void setMaxResidual(double r) { m_resmax = r; }\n\n    double residual() const { return m_res; }\n\n    /* change the user-definable callback, called after each iteration */\n    void setCallback(void (*t)(const IterationController&))\n    {\n      m_callback = t;\n    }\n\n    size_t iteration() const { return m_nit; }\n    void setIteration(size_t i) { m_nit = i; }\n\n    size_t maxIterarions() const { return m_maxiter; }\n    void setMaxIterations(size_t i) { m_maxiter = i; }\n\n    double rhsNorm() const { return m_rhsn; }\n    void setRhsNorm(double r) { m_rhsn = r; }\n\n    bool converged() const { return m_res <= m_rhsn * m_resmax; }\n    bool converged(double nr)\n    {\n      using std::abs;\n      m_res = abs(nr); \n      m_resminreach = (std::min)(m_resminreach, m_res);\n      return converged();\n    }\n    template<typename VectorType> bool converged(const VectorType &v)\n    { return converged(v.squaredNorm()); }\n\n    bool finished(double nr)\n    {\n      if (m_callback) m_callback(*this);\n      if (m_noise > 0 && !m_written)\n      {\n        converged(nr);\n        m_written = true;\n      }\n      return (m_nit >= m_maxiter || converged(nr));\n    }\n    template <typename VectorType>\n    bool finished(const MatrixBase<VectorType> &v)\n    { return finished(double(v.squaredNorm())); }\n\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_ITERATION_CONTROLLER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/IterativeSolvers/MINRES.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Giacomo Po <gpo@ucla.edu>\n// Copyright (C) 2011-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2018 David Hyde <dabh@stanford.edu>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#ifndef EIGEN_MINRES_H_\n#define EIGEN_MINRES_H_\n\n\nnamespace Eigen {\n    \n    namespace internal {\n        \n        /** \\internal Low-level MINRES algorithm\n         * \\param mat The matrix A\n         * \\param rhs The right hand side vector b\n         * \\param x On input and initial solution, on output the computed solution.\n         * \\param precond A right preconditioner being able to efficiently solve for an\n         *                approximation of Ax=b (regardless of b)\n         * \\param iters On input the max number of iteration, on output the number of performed iterations.\n         * \\param tol_error On input the tolerance error, on output an estimation of the relative error.\n         */\n        template<typename MatrixType, typename Rhs, typename Dest, typename Preconditioner>\n        EIGEN_DONT_INLINE\n        void minres(const MatrixType& mat, const Rhs& rhs, Dest& x,\n                    const Preconditioner& precond, Index& iters,\n                    typename Dest::RealScalar& tol_error)\n        {\n            using std::sqrt;\n            typedef typename Dest::RealScalar RealScalar;\n            typedef typename Dest::Scalar Scalar;\n            typedef Matrix<Scalar,Dynamic,1> VectorType;\n\n            // Check for zero rhs\n            const RealScalar rhsNorm2(rhs.squaredNorm());\n            if(rhsNorm2 == 0)\n            {\n                x.setZero();\n                iters = 0;\n                tol_error = 0;\n                return;\n            }\n            \n            // initialize\n            const Index maxIters(iters);  // initialize maxIters to iters\n            const Index N(mat.cols());    // the size of the matrix\n            const RealScalar threshold2(tol_error*tol_error*rhsNorm2); // convergence threshold (compared to residualNorm2)\n            \n            // Initialize preconditioned Lanczos\n            VectorType v_old(N); // will be initialized inside loop\n            VectorType v( VectorType::Zero(N) ); //initialize v\n            VectorType v_new(rhs-mat*x); //initialize v_new\n            RealScalar residualNorm2(v_new.squaredNorm());\n            VectorType w(N); // will be initialized inside loop\n            VectorType w_new(precond.solve(v_new)); // initialize w_new\n//            RealScalar beta; // will be initialized inside loop\n            RealScalar beta_new2(v_new.dot(w_new));\n            eigen_assert(beta_new2 >= 0.0 && \"PRECONDITIONER IS NOT POSITIVE DEFINITE\");\n            RealScalar beta_new(sqrt(beta_new2));\n            const RealScalar beta_one(beta_new);\n            // Initialize other variables\n            RealScalar c(1.0); // the cosine of the Givens rotation\n            RealScalar c_old(1.0);\n            RealScalar s(0.0); // the sine of the Givens rotation\n            RealScalar s_old(0.0); // the sine of the Givens rotation\n            VectorType p_oold(N); // will be initialized in loop\n            VectorType p_old(VectorType::Zero(N)); // initialize p_old=0\n            VectorType p(p_old); // initialize p=0\n            RealScalar eta(1.0);\n                        \n            iters = 0; // reset iters\n            while ( iters < maxIters )\n            {\n                // Preconditioned Lanczos\n                /* Note that there are 4 variants on the Lanczos algorithm. These are\n                 * described in Paige, C. C. (1972). Computational variants of\n                 * the Lanczos method for the eigenproblem. IMA Journal of Applied\n                 * Mathematics, 10(3), 373-381. The current implementation corresponds \n                 * to the case A(2,7) in the paper. It also corresponds to \n                 * algorithm 6.14 in Y. Saad, Iterative Methods for Sparse Linear\n                 * Systems, 2003 p.173. For the preconditioned version see \n                 * A. Greenbaum, Iterative Methods for Solving Linear Systems, SIAM (1987).\n                 */\n                const RealScalar beta(beta_new);\n                v_old = v; // update: at first time step, this makes v_old = 0 so value of beta doesn't matter\n                v_new /= beta_new; // overwrite v_new for next iteration\n                w_new /= beta_new; // overwrite w_new for next iteration\n                v = v_new; // update\n                w = w_new; // update\n                v_new.noalias() = mat*w - beta*v_old; // compute v_new\n                const RealScalar alpha = v_new.dot(w);\n                v_new -= alpha*v; // overwrite v_new\n                w_new = precond.solve(v_new); // overwrite w_new\n                beta_new2 = v_new.dot(w_new); // compute beta_new\n                eigen_assert(beta_new2 >= 0.0 && \"PRECONDITIONER IS NOT POSITIVE DEFINITE\");\n                beta_new = sqrt(beta_new2); // compute beta_new\n                \n                // Givens rotation\n                const RealScalar r2 =s*alpha+c*c_old*beta; // s, s_old, c and c_old are still from previous iteration\n                const RealScalar r3 =s_old*beta; // s, s_old, c and c_old are still from previous iteration\n                const RealScalar r1_hat=c*alpha-c_old*s*beta;\n                const RealScalar r1 =sqrt( std::pow(r1_hat,2) + std::pow(beta_new,2) );\n                c_old = c; // store for next iteration\n                s_old = s; // store for next iteration\n                c=r1_hat/r1; // new cosine\n                s=beta_new/r1; // new sine\n                \n                // Update solution\n                p_oold = p_old;\n                p_old = p;\n                p.noalias()=(w-r2*p_old-r3*p_oold) /r1; // IS NOALIAS REQUIRED?\n                x += beta_one*c*eta*p;\n                \n                /* Update the squared residual. Note that this is the estimated residual.\n                The real residual |Ax-b|^2 may be slightly larger */\n                residualNorm2 *= s*s;\n                \n                if ( residualNorm2 < threshold2)\n                {\n                    break;\n                }\n                \n                eta=-s*eta; // update eta\n                iters++; // increment iteration number (for output purposes)\n            }\n            \n            /* Compute error. Note that this is the estimated error. The real \n             error |Ax-b|/|b| may be slightly larger */\n            tol_error = std::sqrt(residualNorm2 / rhsNorm2);\n        }\n        \n    }\n    \n    template< typename MatrixType_, int UpLo_=Lower,\n    typename Preconditioner_ = IdentityPreconditioner>\n    class MINRES;\n    \n    namespace internal {\n        \n        template< typename MatrixType_, int UpLo_, typename Preconditioner_>\n        struct traits<MINRES<MatrixType_,UpLo_,Preconditioner_> >\n        {\n            typedef MatrixType_ MatrixType;\n            typedef Preconditioner_ Preconditioner;\n        };\n        \n    }\n    \n    /** \\ingroup IterativeLinearSolvers_Module\n     * \\brief A minimal residual solver for sparse symmetric problems\n     *\n     * This class allows to solve for A.x = b sparse linear problems using the MINRES algorithm\n     * of Paige and Saunders (1975). The sparse matrix A must be symmetric (possibly indefinite).\n     * The vectors x and b can be either dense or sparse.\n     *\n     * \\tparam MatrixType_ the type of the sparse matrix A, can be a dense or a sparse matrix.\n     * \\tparam UpLo_ the triangular part that will be used for the computations. It can be Lower,\n     *               Upper, or Lower|Upper in which the full matrix entries will be considered. Default is Lower.\n     * \\tparam Preconditioner_ the type of the preconditioner. Default is DiagonalPreconditioner\n     *\n     * The maximal number of iterations and tolerance value can be controlled via the setMaxIterations()\n     * and setTolerance() methods. The defaults are the size of the problem for the maximal number of iterations\n     * and NumTraits<Scalar>::epsilon() for the tolerance.\n     *\n     * This class can be used as the direct solver classes. Here is a typical usage example:\n     * \\code\n     * int n = 10000;\n     * VectorXd x(n), b(n);\n     * SparseMatrix<double> A(n,n);\n     * // fill A and b\n     * MINRES<SparseMatrix<double> > mr;\n     * mr.compute(A);\n     * x = mr.solve(b);\n     * std::cout << \"#iterations:     \" << mr.iterations() << std::endl;\n     * std::cout << \"estimated error: \" << mr.error()      << std::endl;\n     * // update b, and solve again\n     * x = mr.solve(b);\n     * \\endcode\n     *\n     * By default the iterations start with x=0 as an initial guess of the solution.\n     * One can control the start using the solveWithGuess() method.\n     *\n     * MINRES can also be used in a matrix-free context, see the following \\link MatrixfreeSolverExample example \\endlink.\n     *\n     * \\sa class ConjugateGradient, BiCGSTAB, SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner\n     */\n    template< typename MatrixType_, int UpLo_, typename Preconditioner_>\n    class MINRES : public IterativeSolverBase<MINRES<MatrixType_,UpLo_,Preconditioner_> >\n    {\n        \n        typedef IterativeSolverBase<MINRES> Base;\n        using Base::matrix;\n        using Base::m_error;\n        using Base::m_iterations;\n        using Base::m_info;\n        using Base::m_isInitialized;\n    public:\n        using Base::_solve_impl;\n        typedef MatrixType_ MatrixType;\n        typedef typename MatrixType::Scalar Scalar;\n        typedef typename MatrixType::RealScalar RealScalar;\n        typedef Preconditioner_ Preconditioner;\n        \n        enum {UpLo = UpLo_};\n        \n    public:\n        \n        /** Default constructor. */\n        MINRES() : Base() {}\n        \n        /** Initialize the solver with matrix \\a A for further \\c Ax=b solving.\n         *\n         * This constructor is a shortcut for the default constructor followed\n         * by a call to compute().\n         *\n         * \\warning this class stores a reference to the matrix A as well as some\n         * precomputed values that depend on it. Therefore, if \\a A is changed\n         * this class becomes invalid. Call compute() to update it with the new\n         * matrix A, or modify a copy of A.\n         */\n        template<typename MatrixDerived>\n        explicit MINRES(const EigenBase<MatrixDerived>& A) : Base(A.derived()) {}\n        \n        /** Destructor. */\n        ~MINRES(){}\n\n        /** \\internal */\n        template<typename Rhs,typename Dest>\n        void _solve_vector_with_guess_impl(const Rhs& b, Dest& x) const\n        {\n            typedef typename Base::MatrixWrapper MatrixWrapper;\n            typedef typename Base::ActualMatrixType ActualMatrixType;\n            enum {\n              TransposeInput  =   (!MatrixWrapper::MatrixFree)\n                              &&  (UpLo==(Lower|Upper))\n                              &&  (!MatrixType::IsRowMajor)\n                              &&  (!NumTraits<Scalar>::IsComplex)\n            };\n            typedef typename internal::conditional<TransposeInput,Transpose<const ActualMatrixType>, ActualMatrixType const&>::type RowMajorWrapper;\n            EIGEN_STATIC_ASSERT(EIGEN_IMPLIES(MatrixWrapper::MatrixFree,UpLo==(Lower|Upper)),MATRIX_FREE_CONJUGATE_GRADIENT_IS_COMPATIBLE_WITH_UPPER_UNION_LOWER_MODE_ONLY);\n            typedef typename internal::conditional<UpLo==(Lower|Upper),\n                                                  RowMajorWrapper,\n                                                  typename MatrixWrapper::template ConstSelfAdjointViewReturnType<UpLo>::Type\n                                            >::type SelfAdjointWrapper;\n\n            m_iterations = Base::maxIterations();\n            m_error = Base::m_tolerance;\n            RowMajorWrapper row_mat(matrix());\n            internal::minres(SelfAdjointWrapper(row_mat), b, x,\n                             Base::m_preconditioner, m_iterations, m_error);\n            m_info = m_error <= Base::m_tolerance ? Success : NoConvergence;\n        }\n        \n    protected:\n        \n    };\n\n} // end namespace Eigen\n\n#endif // EIGEN_MINRES_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/IterativeSolvers/Scaling.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Desire NUENTSA WAKAM <desire.nuentsa_wakam@inria.fr\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ITERSCALING_H\n#define EIGEN_ITERSCALING_H\n\nnamespace Eigen {\n\n/**\n  * \\ingroup IterativeSolvers_Module\n  * \\brief iterative scaling algorithm to equilibrate rows and column norms in matrices\n  * \n  * This class can be used as a preprocessing tool to accelerate the convergence of iterative methods \n  * \n  * This feature is  useful to limit the pivoting amount during LU/ILU factorization\n  * The  scaling strategy as presented here preserves the symmetry of the problem\n  * NOTE It is assumed that the matrix does not have empty row or column, \n  * \n  * Example with key steps \n  * \\code\n  * VectorXd x(n), b(n);\n  * SparseMatrix<double> A;\n  * // fill A and b;\n  * IterScaling<SparseMatrix<double> > scal; \n  * // Compute the left and right scaling vectors. The matrix is equilibrated at output\n  * scal.computeRef(A); \n  * // Scale the right hand side\n  * b = scal.LeftScaling().cwiseProduct(b); \n  * // Now, solve the equilibrated linear system with any available solver\n  * \n  * // Scale back the computed solution\n  * x = scal.RightScaling().cwiseProduct(x); \n  * \\endcode\n  * \n  * \\tparam MatrixType_ the type of the matrix. It should be a real square sparsematrix\n  * \n  * References : D. Ruiz and B. Ucar, A Symmetry Preserving Algorithm for Matrix Scaling, INRIA Research report RR-7552\n  * \n  * \\sa \\ref IncompleteLUT \n  */\ntemplate<typename MatrixType_>\nclass IterScaling\n{\n  public:\n    typedef MatrixType_ MatrixType;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::Index Index;\n    \n  public:\n    IterScaling() { init(); }\n    \n    IterScaling(const MatrixType& matrix)\n    {\n      init();\n      compute(matrix);\n    }\n    \n    ~IterScaling() { }\n    \n    /** \n     * Compute the left and right diagonal matrices to scale the input matrix @p mat\n     * \n     * FIXME This algorithm will be modified such that the diagonal elements are permuted on the diagonal. \n     * \n     * \\sa LeftScaling() RightScaling()\n     */\n    void compute (const MatrixType& mat)\n    {\n      using std::abs;\n      int m = mat.rows(); \n      int n = mat.cols();\n      eigen_assert((m>0 && m == n) && \"Please give a non - empty matrix\");\n      m_left.resize(m); \n      m_right.resize(n);\n      m_left.setOnes();\n      m_right.setOnes();\n      m_matrix = mat;\n      VectorXd Dr, Dc, DrRes, DcRes; // Temporary Left and right scaling vectors\n      Dr.resize(m); Dc.resize(n);\n      DrRes.resize(m); DcRes.resize(n);\n      double EpsRow = 1.0, EpsCol = 1.0;\n      int its = 0; \n      do\n      { // Iterate until the infinite norm of each row and column is approximately 1\n        // Get the maximum value in each row and column\n        Dr.setZero(); Dc.setZero();\n        for (int k=0; k<m_matrix.outerSize(); ++k)\n        {\n          for (typename MatrixType::InnerIterator it(m_matrix, k); it; ++it)\n          {\n            if ( Dr(it.row()) < abs(it.value()) )\n              Dr(it.row()) = abs(it.value());\n            \n            if ( Dc(it.col()) < abs(it.value()) )\n              Dc(it.col()) = abs(it.value());\n          }\n        }\n        for (int i = 0; i < m; ++i) \n        {\n          Dr(i) = std::sqrt(Dr(i));\n        }\n        for (int i = 0; i < n; ++i) \n        {\n          Dc(i) = std::sqrt(Dc(i));\n        }\n        // Save the scaling factors \n        for (int i = 0; i < m; ++i) \n        {\n          m_left(i) /= Dr(i);\n        }\n        for (int i = 0; i < n; ++i) \n        {\n          m_right(i) /= Dc(i);\n        }\n        // Scale the rows and the columns of the matrix\n        DrRes.setZero(); DcRes.setZero(); \n        for (int k=0; k<m_matrix.outerSize(); ++k)\n        {\n          for (typename MatrixType::InnerIterator it(m_matrix, k); it; ++it)\n          {\n            it.valueRef() = it.value()/( Dr(it.row()) * Dc(it.col()) );\n            // Accumulate the norms of the row and column vectors   \n            if ( DrRes(it.row()) < abs(it.value()) )\n              DrRes(it.row()) = abs(it.value());\n            \n            if ( DcRes(it.col()) < abs(it.value()) )\n              DcRes(it.col()) = abs(it.value());\n          }\n        }  \n        DrRes.array() = (1-DrRes.array()).abs();\n        EpsRow = DrRes.maxCoeff();\n        DcRes.array() = (1-DcRes.array()).abs();\n        EpsCol = DcRes.maxCoeff();\n        its++;\n      }while ( (EpsRow >m_tol || EpsCol > m_tol) && (its < m_maxits) );\n      m_isInitialized = true;\n    }\n    /** Compute the left and right vectors to scale the vectors\n     * the input matrix is scaled with the computed vectors at output\n     * \n     * \\sa compute()\n     */\n    void computeRef (MatrixType& mat)\n    {\n      compute (mat);\n      mat = m_matrix;\n    }\n    /** Get the vector to scale the rows of the matrix \n     */\n    VectorXd& LeftScaling()\n    {\n      return m_left;\n    }\n    \n    /** Get the vector to scale the columns of the matrix \n     */\n    VectorXd& RightScaling()\n    {\n      return m_right;\n    }\n    \n    /** Set the tolerance for the convergence of the iterative scaling algorithm\n     */\n    void setTolerance(double tol)\n    {\n      m_tol = tol; \n    }\n      \n  protected:\n    \n    void init()\n    {\n      m_tol = 1e-10;\n      m_maxits = 5;\n      m_isInitialized = false;\n    }\n    \n    MatrixType m_matrix;\n    mutable ComputationInfo m_info; \n    bool m_isInitialized; \n    VectorXd m_left; // Left scaling vector\n    VectorXd m_right; // m_right scaling vector\n    double m_tol; \n    int m_maxits; // Maximum number of iterations allowed\n};\n}\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/KroneckerProduct/KroneckerTensorProduct.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Kolja Brix <brix@igpm.rwth-aachen.de>\n// Copyright (C) 2011 Andreas Platen <andiplaten@gmx.de>\n// Copyright (C) 2012 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef KRONECKER_TENSOR_PRODUCT_H\n#define KRONECKER_TENSOR_PRODUCT_H\n\nnamespace Eigen {\n\n/*!\n * \\ingroup KroneckerProduct_Module\n *\n * \\brief The base class of dense and sparse Kronecker product.\n *\n * \\tparam Derived is the derived type.\n */\ntemplate<typename Derived>\nclass KroneckerProductBase : public ReturnByValue<Derived>\n{\n  private:\n    typedef typename internal::traits<Derived> Traits;\n    typedef typename Traits::Scalar Scalar;\n\n  protected:\n    typedef typename Traits::Lhs Lhs;\n    typedef typename Traits::Rhs Rhs;\n\n  public:\n    /*! \\brief Constructor. */\n    KroneckerProductBase(const Lhs& A, const Rhs& B)\n      : m_A(A), m_B(B)\n    {}\n\n    inline Index rows() const { return m_A.rows() * m_B.rows(); }\n    inline Index cols() const { return m_A.cols() * m_B.cols(); }\n\n    /*!\n     * This overrides ReturnByValue::coeff because this function is\n     * efficient enough.\n     */\n    Scalar coeff(Index row, Index col) const\n    {\n      return m_A.coeff(row / m_B.rows(), col / m_B.cols()) *\n             m_B.coeff(row % m_B.rows(), col % m_B.cols());\n    }\n\n    /*!\n     * This overrides ReturnByValue::coeff because this function is\n     * efficient enough.\n     */\n    Scalar coeff(Index i) const\n    {\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived);\n      return m_A.coeff(i / m_A.size()) * m_B.coeff(i % m_A.size());\n    }\n\n  protected:\n    typename Lhs::Nested m_A;\n    typename Rhs::Nested m_B;\n};\n\n/*!\n * \\ingroup KroneckerProduct_Module\n *\n * \\brief Kronecker tensor product helper class for dense matrices\n *\n * This class is the return value of kroneckerProduct(MatrixBase,\n * MatrixBase). Use the function rather than construct this class\n * directly to avoid specifying template prarameters.\n *\n * \\tparam Lhs  Type of the left-hand side, a matrix expression.\n * \\tparam Rhs  Type of the rignt-hand side, a matrix expression.\n */\ntemplate<typename Lhs, typename Rhs>\nclass KroneckerProduct : public KroneckerProductBase<KroneckerProduct<Lhs,Rhs> >\n{\n  private:\n    typedef KroneckerProductBase<KroneckerProduct> Base;\n    using Base::m_A;\n    using Base::m_B;\n\n  public:\n    /*! \\brief Constructor. */\n    KroneckerProduct(const Lhs& A, const Rhs& B)\n      : Base(A, B)\n    {}\n\n    /*! \\brief Evaluate the Kronecker tensor product. */\n    template<typename Dest> void evalTo(Dest& dst) const;\n};\n\n/*!\n * \\ingroup KroneckerProduct_Module\n *\n * \\brief Kronecker tensor product helper class for sparse matrices\n *\n * If at least one of the operands is a sparse matrix expression,\n * then this class is returned and evaluates into a sparse matrix.\n *\n * This class is the return value of kroneckerProduct(EigenBase,\n * EigenBase). Use the function rather than construct this class\n * directly to avoid specifying template prarameters.\n *\n * \\tparam Lhs  Type of the left-hand side, a matrix expression.\n * \\tparam Rhs  Type of the rignt-hand side, a matrix expression.\n */\ntemplate<typename Lhs, typename Rhs>\nclass KroneckerProductSparse : public KroneckerProductBase<KroneckerProductSparse<Lhs,Rhs> >\n{\n  private:\n    typedef KroneckerProductBase<KroneckerProductSparse> Base;\n    using Base::m_A;\n    using Base::m_B;\n\n  public:\n    /*! \\brief Constructor. */\n    KroneckerProductSparse(const Lhs& A, const Rhs& B)\n      : Base(A, B)\n    {}\n\n    /*! \\brief Evaluate the Kronecker tensor product. */\n    template<typename Dest> void evalTo(Dest& dst) const;\n};\n\ntemplate<typename Lhs, typename Rhs>\ntemplate<typename Dest>\nvoid KroneckerProduct<Lhs,Rhs>::evalTo(Dest& dst) const\n{\n  const int BlockRows = Rhs::RowsAtCompileTime,\n            BlockCols = Rhs::ColsAtCompileTime;\n  const Index Br = m_B.rows(),\n              Bc = m_B.cols();\n  for (Index i=0; i < m_A.rows(); ++i)\n    for (Index j=0; j < m_A.cols(); ++j)\n      Block<Dest,BlockRows,BlockCols>(dst,i*Br,j*Bc,Br,Bc) = m_A.coeff(i,j) * m_B;\n}\n\ntemplate<typename Lhs, typename Rhs>\ntemplate<typename Dest>\nvoid KroneckerProductSparse<Lhs,Rhs>::evalTo(Dest& dst) const\n{\n  Index Br = m_B.rows(), Bc = m_B.cols();\n  dst.resize(this->rows(), this->cols());\n  dst.resizeNonZeros(0);\n  \n  // 1 - evaluate the operands if needed:\n  typedef typename internal::nested_eval<Lhs,Dynamic>::type Lhs1;\n  typedef typename internal::remove_all<Lhs1>::type Lhs1Cleaned;\n  const Lhs1 lhs1(m_A);\n  typedef typename internal::nested_eval<Rhs,Dynamic>::type Rhs1;\n  typedef typename internal::remove_all<Rhs1>::type Rhs1Cleaned;\n  const Rhs1 rhs1(m_B);\n    \n  // 2 - construct respective iterators\n  typedef Eigen::InnerIterator<Lhs1Cleaned> LhsInnerIterator;\n  typedef Eigen::InnerIterator<Rhs1Cleaned> RhsInnerIterator;\n  \n  // compute number of non-zeros per innervectors of dst\n  {\n    // TODO VectorXi is not necessarily big enough!\n    VectorXi nnzA = VectorXi::Zero(Dest::IsRowMajor ? m_A.rows() : m_A.cols());\n    for (Index kA=0; kA < m_A.outerSize(); ++kA)\n      for (LhsInnerIterator itA(lhs1,kA); itA; ++itA)\n        nnzA(Dest::IsRowMajor ? itA.row() : itA.col())++;\n      \n    VectorXi nnzB = VectorXi::Zero(Dest::IsRowMajor ? m_B.rows() : m_B.cols());\n    for (Index kB=0; kB < m_B.outerSize(); ++kB)\n      for (RhsInnerIterator itB(rhs1,kB); itB; ++itB)\n        nnzB(Dest::IsRowMajor ? itB.row() : itB.col())++;\n    \n    Matrix<int,Dynamic,Dynamic,ColMajor> nnzAB = nnzB * nnzA.transpose();\n    dst.reserve(VectorXi::Map(nnzAB.data(), nnzAB.size()));\n  }\n\n  for (Index kA=0; kA < m_A.outerSize(); ++kA)\n  {\n    for (Index kB=0; kB < m_B.outerSize(); ++kB)\n    {\n      for (LhsInnerIterator itA(lhs1,kA); itA; ++itA)\n      {\n        for (RhsInnerIterator itB(rhs1,kB); itB; ++itB)\n        {\n          Index i = itA.row() * Br + itB.row(),\n                j = itA.col() * Bc + itB.col();\n          dst.insert(i,j) = itA.value() * itB.value();\n        }\n      }\n    }\n  }\n}\n\nnamespace internal {\n\ntemplate<typename Lhs_, typename Rhs_>\nstruct traits<KroneckerProduct<Lhs_,Rhs_> >\n{\n  typedef typename remove_all<Lhs_>::type Lhs;\n  typedef typename remove_all<Rhs_>::type Rhs;\n  typedef typename ScalarBinaryOpTraits<typename Lhs::Scalar, typename Rhs::Scalar>::ReturnType Scalar;\n  typedef typename promote_index_type<typename Lhs::StorageIndex, typename Rhs::StorageIndex>::type StorageIndex;\n\n  enum {\n    Rows = size_at_compile_time<traits<Lhs>::RowsAtCompileTime, traits<Rhs>::RowsAtCompileTime>::ret,\n    Cols = size_at_compile_time<traits<Lhs>::ColsAtCompileTime, traits<Rhs>::ColsAtCompileTime>::ret,\n    MaxRows = size_at_compile_time<traits<Lhs>::MaxRowsAtCompileTime, traits<Rhs>::MaxRowsAtCompileTime>::ret,\n    MaxCols = size_at_compile_time<traits<Lhs>::MaxColsAtCompileTime, traits<Rhs>::MaxColsAtCompileTime>::ret\n  };\n\n  typedef Matrix<Scalar,Rows,Cols> ReturnType;\n};\n\ntemplate<typename Lhs_, typename Rhs_>\nstruct traits<KroneckerProductSparse<Lhs_,Rhs_> >\n{\n  typedef MatrixXpr XprKind;\n  typedef typename remove_all<Lhs_>::type Lhs;\n  typedef typename remove_all<Rhs_>::type Rhs;\n  typedef typename ScalarBinaryOpTraits<typename Lhs::Scalar, typename Rhs::Scalar>::ReturnType Scalar;\n  typedef typename cwise_promote_storage_type<typename traits<Lhs>::StorageKind, typename traits<Rhs>::StorageKind, scalar_product_op<typename Lhs::Scalar, typename Rhs::Scalar> >::ret StorageKind;\n  typedef typename promote_index_type<typename Lhs::StorageIndex, typename Rhs::StorageIndex>::type StorageIndex;\n\n  enum {\n    LhsFlags = Lhs::Flags,\n    RhsFlags = Rhs::Flags,\n\n    RowsAtCompileTime = size_at_compile_time<traits<Lhs>::RowsAtCompileTime, traits<Rhs>::RowsAtCompileTime>::ret,\n    ColsAtCompileTime = size_at_compile_time<traits<Lhs>::ColsAtCompileTime, traits<Rhs>::ColsAtCompileTime>::ret,\n    MaxRowsAtCompileTime = size_at_compile_time<traits<Lhs>::MaxRowsAtCompileTime, traits<Rhs>::MaxRowsAtCompileTime>::ret,\n    MaxColsAtCompileTime = size_at_compile_time<traits<Lhs>::MaxColsAtCompileTime, traits<Rhs>::MaxColsAtCompileTime>::ret,\n\n    EvalToRowMajor = (int(LhsFlags) & int(RhsFlags) & RowMajorBit),\n    RemovedBits = ~(EvalToRowMajor ? 0 : RowMajorBit),\n\n    Flags = ((int(LhsFlags) | int(RhsFlags)) & HereditaryBits & RemovedBits)\n          | EvalBeforeNestingBit,\n    CoeffReadCost = HugeCost\n  };\n\n  typedef SparseMatrix<Scalar, 0, StorageIndex> ReturnType;\n};\n\n} // end namespace internal\n\n/*!\n * \\ingroup KroneckerProduct_Module\n *\n * Computes Kronecker tensor product of two dense matrices\n *\n * \\warning If you want to replace a matrix by its Kronecker product\n *          with some matrix, do \\b NOT do this:\n * \\code\n * A = kroneckerProduct(A,B); // bug!!! caused by aliasing effect\n * \\endcode\n * instead, use eval() to work around this:\n * \\code\n * A = kroneckerProduct(A,B).eval();\n * \\endcode\n *\n * \\param a  Dense matrix a\n * \\param b  Dense matrix b\n * \\return   Kronecker tensor product of a and b\n */\ntemplate<typename A, typename B>\nKroneckerProduct<A,B> kroneckerProduct(const MatrixBase<A>& a, const MatrixBase<B>& b)\n{\n  return KroneckerProduct<A, B>(a.derived(), b.derived());\n}\n\n/*!\n * \\ingroup KroneckerProduct_Module\n *\n * Computes Kronecker tensor product of two matrices, at least one of\n * which is sparse\n *\n * \\warning If you want to replace a matrix by its Kronecker product\n *          with some matrix, do \\b NOT do this:\n * \\code\n * A = kroneckerProduct(A,B); // bug!!! caused by aliasing effect\n * \\endcode\n * instead, use eval() to work around this:\n * \\code\n * A = kroneckerProduct(A,B).eval();\n * \\endcode\n *\n * \\param a  Dense/sparse matrix a\n * \\param b  Dense/sparse matrix b\n * \\return   Kronecker tensor product of a and b, stored in a sparse\n *           matrix\n */\ntemplate<typename A, typename B>\nKroneckerProductSparse<A,B> kroneckerProduct(const EigenBase<A>& a, const EigenBase<B>& b)\n{\n  return KroneckerProductSparse<A,B>(a.derived(), b.derived());\n}\n\n} // end namespace Eigen\n\n#endif // KRONECKER_TENSOR_PRODUCT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/LevenbergMarquardt/CopyrightMINPACK.txt",
    "content": "Minpack Copyright Notice (1999) University of Chicago.  All rights reserved\n\nRedistribution and use in source and binary forms, with or\nwithout modification, are permitted provided that the\nfollowing conditions are met:\n\n1. Redistributions of source code must retain the above\ncopyright notice, this list of conditions and the following\ndisclaimer.\n\n2. Redistributions in binary form must reproduce the above\ncopyright notice, this list of conditions and the following\ndisclaimer in the documentation and/or other materials\nprovided with the distribution.\n\n3. The end-user documentation included with the\nredistribution, if any, must include the following\nacknowledgment:\n\n   \"This product includes software developed by the\n   University of Chicago, as Operator of Argonne National\n   Laboratory.\n\nAlternately, this acknowledgment may appear in the software\nitself, if and wherever such third-party acknowledgments\nnormally appear.\n\n4. WARRANTY DISCLAIMER. THE SOFTWARE IS SUPPLIED \"AS IS\"\nWITHOUT WARRANTY OF ANY KIND. THE COPYRIGHT HOLDER, THE\nUNITED STATES, THE UNITED STATES DEPARTMENT OF ENERGY, AND\nTHEIR EMPLOYEES: (1) DISCLAIM ANY WARRANTIES, EXPRESS OR\nIMPLIED, INCLUDING BUT NOT LIMITED TO ANY IMPLIED WARRANTIES\nOF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, TITLE\nOR NON-INFRINGEMENT, (2) DO NOT ASSUME ANY LEGAL LIABILITY\nOR RESPONSIBILITY FOR THE ACCURACY, COMPLETENESS, OR\nUSEFULNESS OF THE SOFTWARE, (3) DO NOT REPRESENT THAT USE OF\nTHE SOFTWARE WOULD NOT INFRINGE PRIVATELY OWNED RIGHTS, (4)\nDO NOT WARRANT THAT THE SOFTWARE WILL FUNCTION\nUNINTERRUPTED, THAT IT IS ERROR-FREE OR THAT ANY ERRORS WILL\nBE CORRECTED.\n\n5. LIMITATION OF LIABILITY. IN NO EVENT WILL THE COPYRIGHT\nHOLDER, THE UNITED STATES, THE UNITED STATES DEPARTMENT OF\nENERGY, OR THEIR EMPLOYEES: BE LIABLE FOR ANY INDIRECT,\nINCIDENTAL, CONSEQUENTIAL, SPECIAL OR PUNITIVE DAMAGES OF\nANY KIND OR NATURE, INCLUDING BUT NOT LIMITED TO LOSS OF\nPROFITS OR LOSS OF DATA, FOR ANY REASON WHATSOEVER, WHETHER\nSUCH LIABILITY IS ASSERTED ON THE BASIS OF CONTRACT, TORT\n(INCLUDING NEGLIGENCE OR STRICT LIABILITY), OR OTHERWISE,\nEVEN IF ANY OF SAID PARTIES HAS BEEN WARNED OF THE\nPOSSIBILITY OF SUCH LOSS OR DAMAGES.\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/LevenbergMarquardt/LMcovar.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This code initially comes from MINPACK whose original authors are:\n// Copyright Jorge More - Argonne National Laboratory\n// Copyright Burt Garbow - Argonne National Laboratory\n// Copyright Ken Hillstrom - Argonne National Laboratory\n//\n// This Source Code Form is subject to the terms of the Minpack license\n// (a BSD-like license) described in the campaigned CopyrightMINPACK.txt file.\n\n#ifndef EIGEN_LMCOVAR_H\n#define EIGEN_LMCOVAR_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate <typename Scalar>\nvoid covar(\n        Matrix< Scalar, Dynamic, Dynamic > &r,\n        const VectorXi& ipvt,\n        Scalar tol = std::sqrt(NumTraits<Scalar>::epsilon()) )\n{\n    using std::abs;\n    /* Local variables */\n    Index i, j, k, l, ii, jj;\n    bool sing;\n    Scalar temp;\n\n    /* Function Body */\n    const Index n = r.cols();\n    const Scalar tolr = tol * abs(r(0,0));\n    Matrix< Scalar, Dynamic, 1 > wa(n);\n    eigen_assert(ipvt.size()==n);\n\n    /* form the inverse of r in the full upper triangle of r. */\n    l = -1;\n    for (k = 0; k < n; ++k)\n        if (abs(r(k,k)) > tolr) {\n            r(k,k) = 1. / r(k,k);\n            for (j = 0; j <= k-1; ++j) {\n                temp = r(k,k) * r(j,k);\n                r(j,k) = 0.;\n                r.col(k).head(j+1) -= r.col(j).head(j+1) * temp;\n            }\n            l = k;\n        }\n\n    /* form the full upper triangle of the inverse of (r transpose)*r */\n    /* in the full upper triangle of r. */\n    for (k = 0; k <= l; ++k) {\n        for (j = 0; j <= k-1; ++j)\n            r.col(j).head(j+1) += r.col(k).head(j+1) * r(j,k);\n        r.col(k).head(k+1) *= r(k,k);\n    }\n\n    /* form the full lower triangle of the covariance matrix */\n    /* in the strict lower triangle of r and in wa. */\n    for (j = 0; j < n; ++j) {\n        jj = ipvt[j];\n        sing = j > l;\n        for (i = 0; i <= j; ++i) {\n            if (sing)\n                r(i,j) = 0.;\n            ii = ipvt[i];\n            if (ii > jj)\n                r(ii,jj) = r(i,j);\n            if (ii < jj)\n                r(jj,ii) = r(i,j);\n        }\n        wa[jj] = r(j,j);\n    }\n\n    /* symmetrize the covariance matrix in r. */\n    r.topLeftCorner(n,n).template triangularView<StrictlyUpper>() = r.topLeftCorner(n,n).transpose();\n    r.diagonal() = wa;\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_LMCOVAR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/LevenbergMarquardt/LMonestep.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n//\n// This code initially comes from MINPACK whose original authors are:\n// Copyright Jorge More - Argonne National Laboratory\n// Copyright Burt Garbow - Argonne National Laboratory\n// Copyright Ken Hillstrom - Argonne National Laboratory\n//\n// This Source Code Form is subject to the terms of the Minpack license\n// (a BSD-like license) described in the campaigned CopyrightMINPACK.txt file.\n\n#ifndef EIGEN_LMONESTEP_H\n#define EIGEN_LMONESTEP_H\n\nnamespace Eigen {\n\ntemplate<typename FunctorType>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType>::minimizeOneStep(FVectorType  &x)\n{\n  using std::abs;\n  using std::sqrt;\n  RealScalar temp, temp1,temp2; \n  RealScalar ratio; \n  RealScalar pnorm, xnorm, fnorm1, actred, dirder, prered;\n  eigen_assert(x.size()==n); // check the caller is not cheating us\n\n  temp = 0.0; xnorm = 0.0;\n  /* calculate the jacobian matrix. */\n  Index df_ret = m_functor.df(x, m_fjac);\n  if (df_ret<0)\n      return LevenbergMarquardtSpace::UserAsked;\n  if (df_ret>0)\n      // numerical diff, we evaluated the function df_ret times\n      m_nfev += df_ret;\n  else m_njev++;\n\n  /* compute the qr factorization of the jacobian. */\n  for (int j = 0; j < x.size(); ++j)\n    m_wa2(j) = m_fjac.col(j).blueNorm();\n  QRSolver qrfac(m_fjac);\n  if(qrfac.info() != Success) {\n    m_info = NumericalIssue;\n    return LevenbergMarquardtSpace::ImproperInputParameters;\n  }\n  // Make a copy of the first factor with the associated permutation\n  m_rfactor = qrfac.matrixR();\n  m_permutation = (qrfac.colsPermutation());\n\n  /* on the first iteration and if external scaling is not used, scale according */\n  /* to the norms of the columns of the initial jacobian. */\n  if (m_iter == 1) {\n      if (!m_useExternalScaling)\n          for (Index j = 0; j < n; ++j)\n              m_diag[j] = (m_wa2[j]==0.)? 1. : m_wa2[j];\n\n      /* on the first iteration, calculate the norm of the scaled x */\n      /* and initialize the step bound m_delta. */\n      xnorm = m_diag.cwiseProduct(x).stableNorm();\n      m_delta = m_factor * xnorm;\n      if (m_delta == 0.)\n          m_delta = m_factor;\n  }\n\n  /* form (q transpose)*m_fvec and store the first n components in */\n  /* m_qtf. */\n  m_wa4 = m_fvec;\n  m_wa4 = qrfac.matrixQ().adjoint() * m_fvec; \n  m_qtf = m_wa4.head(n);\n\n  /* compute the norm of the scaled gradient. */\n  m_gnorm = 0.;\n  if (m_fnorm != 0.)\n      for (Index j = 0; j < n; ++j)\n          if (m_wa2[m_permutation.indices()[j]] != 0.)\n              m_gnorm = (std::max)(m_gnorm, abs( m_rfactor.col(j).head(j+1).dot(m_qtf.head(j+1)/m_fnorm) / m_wa2[m_permutation.indices()[j]]));\n\n  /* test for convergence of the gradient norm. */\n  if (m_gnorm <= m_gtol) {\n    m_info = Success;\n    return LevenbergMarquardtSpace::CosinusTooSmall;\n  }\n\n  /* rescale if necessary. */\n  if (!m_useExternalScaling)\n      m_diag = m_diag.cwiseMax(m_wa2);\n\n  do {\n    /* determine the levenberg-marquardt parameter. */\n    internal::lmpar2(qrfac, m_diag, m_qtf, m_delta, m_par, m_wa1);\n\n    /* store the direction p and x + p. calculate the norm of p. */\n    m_wa1 = -m_wa1;\n    m_wa2 = x + m_wa1;\n    pnorm = m_diag.cwiseProduct(m_wa1).stableNorm();\n\n    /* on the first iteration, adjust the initial step bound. */\n    if (m_iter == 1)\n        m_delta = (std::min)(m_delta,pnorm);\n\n    /* evaluate the function at x + p and calculate its norm. */\n    if ( m_functor(m_wa2, m_wa4) < 0)\n        return LevenbergMarquardtSpace::UserAsked;\n    ++m_nfev;\n    fnorm1 = m_wa4.stableNorm();\n\n    /* compute the scaled actual reduction. */\n    actred = -1.;\n    if (Scalar(.1) * fnorm1 < m_fnorm)\n        actred = 1. - numext::abs2(fnorm1 / m_fnorm);\n\n    /* compute the scaled predicted reduction and */\n    /* the scaled directional derivative. */\n    m_wa3 = m_rfactor.template triangularView<Upper>() * (m_permutation.inverse() *m_wa1);\n    temp1 = numext::abs2(m_wa3.stableNorm() / m_fnorm);\n    temp2 = numext::abs2(sqrt(m_par) * pnorm / m_fnorm);\n    prered = temp1 + temp2 / Scalar(.5);\n    dirder = -(temp1 + temp2);\n\n    /* compute the ratio of the actual to the predicted */\n    /* reduction. */\n    ratio = 0.;\n    if (prered != 0.)\n        ratio = actred / prered;\n\n    /* update the step bound. */\n    if (ratio <= Scalar(.25)) {\n        if (actred >= 0.)\n            temp = RealScalar(.5);\n        if (actred < 0.)\n            temp = RealScalar(.5) * dirder / (dirder + RealScalar(.5) * actred);\n        if (RealScalar(.1) * fnorm1 >= m_fnorm || temp < RealScalar(.1))\n            temp = Scalar(.1);\n        /* Computing MIN */\n        m_delta = temp * (std::min)(m_delta, pnorm / RealScalar(.1));\n        m_par /= temp;\n    } else if (!(m_par != 0. && ratio < RealScalar(.75))) {\n        m_delta = pnorm / RealScalar(.5);\n        m_par = RealScalar(.5) * m_par;\n    }\n\n    /* test for successful iteration. */\n    if (ratio >= RealScalar(1e-4)) {\n        /* successful iteration. update x, m_fvec, and their norms. */\n        x = m_wa2;\n        m_wa2 = m_diag.cwiseProduct(x);\n        m_fvec = m_wa4;\n        xnorm = m_wa2.stableNorm();\n        m_fnorm = fnorm1;\n        ++m_iter;\n    }\n\n    /* tests for convergence. */\n    if (abs(actred) <= m_ftol && prered <= m_ftol && Scalar(.5) * ratio <= 1. && m_delta <= m_xtol * xnorm)\n    {\n       m_info = Success;\n      return LevenbergMarquardtSpace::RelativeErrorAndReductionTooSmall;\n    }\n    if (abs(actred) <= m_ftol && prered <= m_ftol && Scalar(.5) * ratio <= 1.) \n    {\n      m_info = Success;\n      return LevenbergMarquardtSpace::RelativeReductionTooSmall;\n    }\n    if (m_delta <= m_xtol * xnorm)\n    {\n      m_info = Success;\n      return LevenbergMarquardtSpace::RelativeErrorTooSmall;\n    }\n\n    /* tests for termination and stringent tolerances. */\n    if (m_nfev >= m_maxfev) \n    {\n      m_info = NoConvergence;\n      return LevenbergMarquardtSpace::TooManyFunctionEvaluation;\n    }\n    if (abs(actred) <= NumTraits<Scalar>::epsilon() && prered <= NumTraits<Scalar>::epsilon() && Scalar(.5) * ratio <= 1.)\n    {\n      m_info = Success;\n      return LevenbergMarquardtSpace::FtolTooSmall;\n    }\n    if (m_delta <= NumTraits<Scalar>::epsilon() * xnorm) \n    {\n      m_info = Success;\n      return LevenbergMarquardtSpace::XtolTooSmall;\n    }\n    if (m_gnorm <= NumTraits<Scalar>::epsilon())\n    {\n      m_info = Success;\n      return LevenbergMarquardtSpace::GtolTooSmall;\n    }\n\n  } while (ratio < Scalar(1e-4));\n\n  return LevenbergMarquardtSpace::Running;\n}\n\n  \n} // end namespace Eigen\n\n#endif // EIGEN_LMONESTEP_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/LevenbergMarquardt/LMpar.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This code initially comes from MINPACK whose original authors are:\n// Copyright Jorge More - Argonne National Laboratory\n// Copyright Burt Garbow - Argonne National Laboratory\n// Copyright Ken Hillstrom - Argonne National Laboratory\n//\n// This Source Code Form is subject to the terms of the Minpack license\n// (a BSD-like license) described in the campaigned CopyrightMINPACK.txt file.\n\n#ifndef EIGEN_LMPAR_H\n#define EIGEN_LMPAR_H\n\nnamespace Eigen {\n\nnamespace internal {\n  \n  template <typename QRSolver, typename VectorType>\n    void lmpar2(\n    const QRSolver &qr,\n    const VectorType  &diag,\n    const VectorType  &qtb,\n    typename VectorType::Scalar m_delta,\n    typename VectorType::Scalar &par,\n    VectorType  &x)\n\n  {\n    using std::sqrt;\n    using std::abs;\n    typedef typename QRSolver::MatrixType MatrixType;\n    typedef typename QRSolver::Scalar Scalar;\n//    typedef typename QRSolver::StorageIndex StorageIndex;\n\n    /* Local variables */\n    Index j;\n    Scalar fp;\n    Scalar parc, parl;\n    Index iter;\n    Scalar temp, paru;\n    Scalar gnorm;\n    Scalar dxnorm;\n    \n    // Make a copy of the triangular factor. \n    // This copy is modified during call the qrsolv\n    MatrixType s;\n    s = qr.matrixR();\n\n    /* Function Body */\n    const Scalar dwarf = (std::numeric_limits<Scalar>::min)();\n    const Index n = qr.matrixR().cols();\n    eigen_assert(n==diag.size());\n    eigen_assert(n==qtb.size());\n\n    VectorType  wa1, wa2;\n\n    /* compute and store in x the gauss-newton direction. if the */\n    /* jacobian is rank-deficient, obtain a least squares solution. */\n\n    //    const Index rank = qr.nonzeroPivots(); // exactly double(0.)\n    const Index rank = qr.rank(); // use a threshold\n    wa1 = qtb;\n    wa1.tail(n-rank).setZero();\n    //FIXME There is no solve in place for sparse triangularView\n    wa1.head(rank) = s.topLeftCorner(rank,rank).template triangularView<Upper>().solve(qtb.head(rank));\n\n    x = qr.colsPermutation()*wa1;\n\n    /* initialize the iteration counter. */\n    /* evaluate the function at the origin, and test */\n    /* for acceptance of the gauss-newton direction. */\n    iter = 0;\n    wa2 = diag.cwiseProduct(x);\n    dxnorm = wa2.blueNorm();\n    fp = dxnorm - m_delta;\n    if (fp <= Scalar(0.1) * m_delta) {\n      par = 0;\n      return;\n    }\n\n    /* if the jacobian is not rank deficient, the newton */\n    /* step provides a lower bound, parl, for the zero of */\n    /* the function. otherwise set this bound to zero. */\n    parl = 0.;\n    if (rank==n) {\n      wa1 = qr.colsPermutation().inverse() *  diag.cwiseProduct(wa2)/dxnorm;\n      s.topLeftCorner(n,n).transpose().template triangularView<Lower>().solveInPlace(wa1);\n      temp = wa1.blueNorm();\n      parl = fp / m_delta / temp / temp;\n    }\n\n    /* calculate an upper bound, paru, for the zero of the function. */\n    for (j = 0; j < n; ++j)\n      wa1[j] = s.col(j).head(j+1).dot(qtb.head(j+1)) / diag[qr.colsPermutation().indices()(j)];\n\n    gnorm = wa1.stableNorm();\n    paru = gnorm / m_delta;\n    if (paru == 0.)\n      paru = dwarf / (std::min)(m_delta,Scalar(0.1));\n\n    /* if the input par lies outside of the interval (parl,paru), */\n    /* set par to the closer endpoint. */\n    par = (std::max)(par,parl);\n    par = (std::min)(par,paru);\n    if (par == 0.)\n      par = gnorm / dxnorm;\n\n    /* beginning of an iteration. */\n    while (true) {\n      ++iter;\n\n      /* evaluate the function at the current value of par. */\n      if (par == 0.)\n        par = (std::max)(dwarf,Scalar(.001) * paru); /* Computing MAX */\n      wa1 = sqrt(par)* diag;\n\n      VectorType sdiag(n);\n      lmqrsolv(s, qr.colsPermutation(), wa1, qtb, x, sdiag);\n\n      wa2 = diag.cwiseProduct(x);\n      dxnorm = wa2.blueNorm();\n      temp = fp;\n      fp = dxnorm - m_delta;\n\n      /* if the function is small enough, accept the current value */\n      /* of par. also test for the exceptional cases where parl */\n      /* is zero or the number of iterations has reached 10. */\n      if (abs(fp) <= Scalar(0.1) * m_delta || (parl == 0. && fp <= temp && temp < 0.) || iter == 10)\n        break;\n\n      /* compute the newton correction. */\n      wa1 = qr.colsPermutation().inverse() * diag.cwiseProduct(wa2/dxnorm);\n      // we could almost use this here, but the diagonal is outside qr, in sdiag[]\n      for (j = 0; j < n; ++j) {\n        wa1[j] /= sdiag[j];\n        temp = wa1[j];\n        for (Index i = j+1; i < n; ++i)\n          wa1[i] -= s.coeff(i,j) * temp;\n      }\n      temp = wa1.blueNorm();\n      parc = fp / m_delta / temp / temp;\n\n      /* depending on the sign of the function, update parl or paru. */\n      if (fp > 0.)\n        parl = (std::max)(parl,par);\n      if (fp < 0.)\n        paru = (std::min)(paru,par);\n\n      /* compute an improved estimate for par. */\n      par = (std::max)(parl,par+parc);\n    }\n    if (iter == 0)\n      par = 0.;\n    return;\n  }\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_LMPAR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/LevenbergMarquardt/LMqrsolv.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n// Copyright (C) 2012 Desire Nuentsa <desire.nuentsa_wakam@inria.fr>\n//\n// This code initially comes from MINPACK whose original authors are:\n// Copyright Jorge More - Argonne National Laboratory\n// Copyright Burt Garbow - Argonne National Laboratory\n// Copyright Ken Hillstrom - Argonne National Laboratory\n//\n// This Source Code Form is subject to the terms of the Minpack license\n// (a BSD-like license) described in the campaigned CopyrightMINPACK.txt file.\n\n#ifndef EIGEN_LMQRSOLV_H\n#define EIGEN_LMQRSOLV_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate <typename Scalar,int Rows, int Cols, typename PermIndex>\nvoid lmqrsolv(\n  Matrix<Scalar,Rows,Cols> &s,\n  const PermutationMatrix<Dynamic,Dynamic,PermIndex> &iPerm,\n  const Matrix<Scalar,Dynamic,1> &diag,\n  const Matrix<Scalar,Dynamic,1> &qtb,\n  Matrix<Scalar,Dynamic,1> &x,\n  Matrix<Scalar,Dynamic,1> &sdiag)\n{\n    /* Local variables */\n    Index i, j, k;\n    Scalar temp;\n    Index n = s.cols();\n    Matrix<Scalar,Dynamic,1>  wa(n);\n    JacobiRotation<Scalar> givens;\n\n    /* Function Body */\n    // the following will only change the lower triangular part of s, including\n    // the diagonal, though the diagonal is restored afterward\n\n    /*     copy r and (q transpose)*b to preserve input and initialize s. */\n    /*     in particular, save the diagonal elements of r in x. */\n    x = s.diagonal();\n    wa = qtb;\n    \n   \n    s.topLeftCorner(n,n).template triangularView<StrictlyLower>() = s.topLeftCorner(n,n).transpose();\n    /*     eliminate the diagonal matrix d using a givens rotation. */\n    for (j = 0; j < n; ++j) {\n\n        /*        prepare the row of d to be eliminated, locating the */\n        /*        diagonal element using p from the qr factorization. */\n        const PermIndex l = iPerm.indices()(j);\n        if (diag[l] == 0.)\n            break;\n        sdiag.tail(n-j).setZero();\n        sdiag[j] = diag[l];\n\n        /*        the transformations to eliminate the row of d */\n        /*        modify only a single element of (q transpose)*b */\n        /*        beyond the first n, which is initially zero. */\n        Scalar qtbpj = 0.;\n        for (k = j; k < n; ++k) {\n            /*           determine a givens rotation which eliminates the */\n            /*           appropriate element in the current row of d. */\n            givens.makeGivens(-s(k,k), sdiag[k]);\n\n            /*           compute the modified diagonal element of r and */\n            /*           the modified element of ((q transpose)*b,0). */\n            s(k,k) = givens.c() * s(k,k) + givens.s() * sdiag[k];\n            temp = givens.c() * wa[k] + givens.s() * qtbpj;\n            qtbpj = -givens.s() * wa[k] + givens.c() * qtbpj;\n            wa[k] = temp;\n\n            /*           accumulate the transformation in the row of s. */\n            for (i = k+1; i<n; ++i) {\n                temp = givens.c() * s(i,k) + givens.s() * sdiag[i];\n                sdiag[i] = -givens.s() * s(i,k) + givens.c() * sdiag[i];\n                s(i,k) = temp;\n            }\n        }\n    }\n  \n    /*     solve the triangular system for z. if the system is */\n    /*     singular, then obtain a least squares solution. */\n    Index nsing;\n    for(nsing=0; nsing<n && sdiag[nsing]!=0; nsing++) {}\n\n    wa.tail(n-nsing).setZero();\n    s.topLeftCorner(nsing, nsing).transpose().template triangularView<Upper>().solveInPlace(wa.head(nsing));\n  \n    // restore\n    sdiag = s.diagonal();\n    s.diagonal() = x;\n\n    /* permute the components of z back to components of x. */\n    x = iPerm * wa; \n}\n\ntemplate <typename Scalar, int Options_, typename Index>\nvoid lmqrsolv(\n  SparseMatrix<Scalar,Options_,Index> &s,\n  const PermutationMatrix<Dynamic,Dynamic> &iPerm,\n  const Matrix<Scalar,Dynamic,1> &diag,\n  const Matrix<Scalar,Dynamic,1> &qtb,\n  Matrix<Scalar,Dynamic,1> &x,\n  Matrix<Scalar,Dynamic,1> &sdiag)\n{\n  /* Local variables */\n  typedef SparseMatrix<Scalar,RowMajor,Index> FactorType;\n    Index i, j, k, l;\n    Scalar temp;\n    Index n = s.cols();\n    Matrix<Scalar,Dynamic,1>  wa(n);\n    JacobiRotation<Scalar> givens;\n\n    /* Function Body */\n    // the following will only change the lower triangular part of s, including\n    // the diagonal, though the diagonal is restored afterward\n\n    /*     copy r and (q transpose)*b to preserve input and initialize R. */\n    wa = qtb;\n    FactorType R(s);\n    // Eliminate the diagonal matrix d using a givens rotation\n    for (j = 0; j < n; ++j)\n    {\n      // Prepare the row of d to be eliminated, locating the \n      // diagonal element using p from the qr factorization\n      l = iPerm.indices()(j);\n      if (diag(l) == Scalar(0)) \n        break; \n      sdiag.tail(n-j).setZero();\n      sdiag[j] = diag[l];\n      // the transformations to eliminate the row of d\n      // modify only a single element of (q transpose)*b\n      // beyond the first n, which is initially zero. \n      \n      Scalar qtbpj = 0; \n      // Browse the nonzero elements of row j of the upper triangular s\n      for (k = j; k < n; ++k)\n      {\n        typename FactorType::InnerIterator itk(R,k);\n        for (; itk; ++itk){\n          if (itk.index() < k) continue;\n          else break;\n        }\n        //At this point, we have the diagonal element R(k,k)\n        // Determine a givens rotation which eliminates \n        // the appropriate element in the current row of d\n        givens.makeGivens(-itk.value(), sdiag(k));\n        \n        // Compute the modified diagonal element of r and \n        // the modified element of ((q transpose)*b,0).\n        itk.valueRef() = givens.c() * itk.value() + givens.s() * sdiag(k);\n        temp = givens.c() * wa(k) + givens.s() * qtbpj; \n        qtbpj = -givens.s() * wa(k) + givens.c() * qtbpj;\n        wa(k) = temp;\n        \n        // Accumulate the transformation in the remaining k row/column of R\n        for (++itk; itk; ++itk)\n        {\n          i = itk.index();\n          temp = givens.c() *  itk.value() + givens.s() * sdiag(i);\n          sdiag(i) = -givens.s() * itk.value() + givens.c() * sdiag(i);\n          itk.valueRef() = temp;\n        }\n      }\n    }\n    \n    // Solve the triangular system for z. If the system is \n    // singular, then obtain a least squares solution\n    Index nsing;\n    for(nsing = 0; nsing<n && sdiag(nsing) !=0; nsing++) {}\n    \n    wa.tail(n-nsing).setZero();\n//     x = wa; \n    wa.head(nsing) = R.topLeftCorner(nsing,nsing).template triangularView<Upper>().solve/*InPlace*/(wa.head(nsing));\n    \n    sdiag = R.diagonal();\n    // Permute the components of z back to components of x\n    x = iPerm * wa; \n}\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_LMQRSOLV_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/LevenbergMarquardt/LevenbergMarquardt.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n// Copyright (C) 2012 Desire Nuentsa <desire.nuentsa_wakam@inria.fr>\n//\n// The algorithm of this class initially comes from MINPACK whose original authors are:\n// Copyright Jorge More - Argonne National Laboratory\n// Copyright Burt Garbow - Argonne National Laboratory\n// Copyright Ken Hillstrom - Argonne National Laboratory\n//\n// This Source Code Form is subject to the terms of the Minpack license\n// (a BSD-like license) described in the campaigned CopyrightMINPACK.txt file.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_LEVENBERGMARQUARDT_H\n#define EIGEN_LEVENBERGMARQUARDT_H\n\n\nnamespace Eigen {\nnamespace LevenbergMarquardtSpace {\n    enum Status {\n        NotStarted = -2,\n        Running = -1,\n        ImproperInputParameters = 0,\n        RelativeReductionTooSmall = 1,\n        RelativeErrorTooSmall = 2,\n        RelativeErrorAndReductionTooSmall = 3,\n        CosinusTooSmall = 4,\n        TooManyFunctionEvaluation = 5,\n        FtolTooSmall = 6,\n        XtolTooSmall = 7,\n        GtolTooSmall = 8,\n        UserAsked = 9\n    };\n}\n\ntemplate <typename Scalar_, int NX=Dynamic, int NY=Dynamic>\nstruct DenseFunctor\n{\n  typedef Scalar_ Scalar;\n  enum {\n    InputsAtCompileTime = NX,\n    ValuesAtCompileTime = NY\n  };\n  typedef Matrix<Scalar,InputsAtCompileTime,1> InputType;\n  typedef Matrix<Scalar,ValuesAtCompileTime,1> ValueType;\n  typedef Matrix<Scalar,ValuesAtCompileTime,InputsAtCompileTime> JacobianType;\n  typedef ColPivHouseholderQR<JacobianType> QRSolver;\n  const int m_inputs, m_values;\n\n  DenseFunctor() : m_inputs(InputsAtCompileTime), m_values(ValuesAtCompileTime) {}\n  DenseFunctor(int inputs, int values) : m_inputs(inputs), m_values(values) {}\n\n  int inputs() const { return m_inputs; }\n  int values() const { return m_values; }\n\n  //int operator()(const InputType &x, ValueType& fvec) { }\n  // should be defined in derived classes\n  \n  //int df(const InputType &x, JacobianType& fjac) { }\n  // should be defined in derived classes\n};\n\ntemplate <typename Scalar_, typename Index_>\nstruct SparseFunctor\n{\n  typedef Scalar_ Scalar;\n  typedef Index_ Index;\n  typedef Matrix<Scalar,Dynamic,1> InputType;\n  typedef Matrix<Scalar,Dynamic,1> ValueType;\n  typedef SparseMatrix<Scalar, ColMajor, Index> JacobianType;\n  typedef SparseQR<JacobianType, COLAMDOrdering<int> > QRSolver;\n  enum {\n    InputsAtCompileTime = Dynamic,\n    ValuesAtCompileTime = Dynamic\n  };\n  \n  SparseFunctor(int inputs, int values) : m_inputs(inputs), m_values(values) {}\n\n  int inputs() const { return m_inputs; }\n  int values() const { return m_values; }\n  \n  const int m_inputs, m_values;\n  //int operator()(const InputType &x, ValueType& fvec) { }\n  // to be defined in the functor\n  \n  //int df(const InputType &x, JacobianType& fjac) { }\n  // to be defined in the functor if no automatic differentiation\n  \n};\nnamespace internal {\ntemplate <typename QRSolver, typename VectorType>\nvoid lmpar2(const QRSolver &qr, const VectorType  &diag, const VectorType  &qtb,\n\t    typename VectorType::Scalar m_delta, typename VectorType::Scalar &par,\n\t    VectorType  &x);\n    }\n/**\n  * \\ingroup NonLinearOptimization_Module\n  * \\brief Performs non linear optimization over a non-linear function,\n  * using a variant of the Levenberg Marquardt algorithm.\n  *\n  * Check wikipedia for more information.\n  * http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm\n  */\ntemplate<typename FunctorType_>\nclass LevenbergMarquardt : internal::no_assignment_operator\n{\n  public:\n    typedef FunctorType_ FunctorType;\n    typedef typename FunctorType::QRSolver QRSolver;\n    typedef typename FunctorType::JacobianType JacobianType;\n    typedef typename JacobianType::Scalar Scalar;\n    typedef typename JacobianType::RealScalar RealScalar; \n    typedef typename QRSolver::StorageIndex PermIndex;\n    typedef Matrix<Scalar,Dynamic,1> FVectorType;\n    typedef PermutationMatrix<Dynamic,Dynamic,int> PermutationType;\n  public:\n    LevenbergMarquardt(FunctorType& functor) \n    : m_functor(functor),m_nfev(0),m_njev(0),m_fnorm(0.0),m_gnorm(0),\n      m_isInitialized(false),m_info(InvalidInput)\n    {\n      resetParameters();\n      m_useExternalScaling=false; \n    }\n    \n    LevenbergMarquardtSpace::Status minimize(FVectorType &x);\n    LevenbergMarquardtSpace::Status minimizeInit(FVectorType &x);\n    LevenbergMarquardtSpace::Status minimizeOneStep(FVectorType &x);\n    LevenbergMarquardtSpace::Status lmder1(\n      FVectorType  &x, \n      const Scalar tol = std::sqrt(NumTraits<Scalar>::epsilon())\n    );\n    static LevenbergMarquardtSpace::Status lmdif1(\n            FunctorType &functor,\n            FVectorType  &x,\n            Index *nfev,\n            const Scalar tol = std::sqrt(NumTraits<Scalar>::epsilon())\n            );\n    \n    /** Sets the default parameters */\n    void resetParameters() \n    {\n      using std::sqrt;        \n\n      m_factor = 100.; \n      m_maxfev = 400; \n      m_ftol = sqrt(NumTraits<RealScalar>::epsilon());\n      m_xtol = sqrt(NumTraits<RealScalar>::epsilon());\n      m_gtol = 0. ; \n      m_epsfcn = 0. ;\n    }\n    \n    /** Sets the tolerance for the norm of the solution vector*/\n    void setXtol(RealScalar xtol) { m_xtol = xtol; }\n    \n    /** Sets the tolerance for the norm of the vector function*/\n    void setFtol(RealScalar ftol) { m_ftol = ftol; }\n    \n    /** Sets the tolerance for the norm of the gradient of the error vector*/\n    void setGtol(RealScalar gtol) { m_gtol = gtol; }\n    \n    /** Sets the step bound for the diagonal shift */\n    void setFactor(RealScalar factor) { m_factor = factor; }    \n    \n    /** Sets the error precision  */\n    void setEpsilon (RealScalar epsfcn) { m_epsfcn = epsfcn; }\n    \n    /** Sets the maximum number of function evaluation */\n    void setMaxfev(Index maxfev) {m_maxfev = maxfev; }\n    \n    /** Use an external Scaling. If set to true, pass a nonzero diagonal to diag() */\n    void setExternalScaling(bool value) {m_useExternalScaling  = value; }\n    \n    /** \\returns the tolerance for the norm of the solution vector */\n    RealScalar xtol() const {return m_xtol; }\n    \n    /** \\returns the tolerance for the norm of the vector function */\n    RealScalar ftol() const {return m_ftol; }\n    \n    /** \\returns the tolerance for the norm of the gradient of the error vector */\n    RealScalar gtol() const {return m_gtol; }\n    \n    /** \\returns the step bound for the diagonal shift */\n    RealScalar factor() const {return m_factor; }\n    \n    /** \\returns the error precision */\n    RealScalar epsilon() const {return m_epsfcn; }\n    \n    /** \\returns the maximum number of function evaluation */\n    Index maxfev() const {return m_maxfev; }\n    \n    /** \\returns a reference to the diagonal of the jacobian */\n    FVectorType& diag() {return m_diag; }\n    \n    /** \\returns the number of iterations performed */\n    Index iterations() { return m_iter; }\n    \n    /** \\returns the number of functions evaluation */\n    Index nfev() { return m_nfev; }\n    \n    /** \\returns the number of jacobian evaluation */\n    Index njev() { return m_njev; }\n    \n    /** \\returns the norm of current vector function */\n    RealScalar fnorm() {return m_fnorm; }\n    \n    /** \\returns the norm of the gradient of the error */\n    RealScalar gnorm() {return m_gnorm; }\n    \n    /** \\returns the LevenbergMarquardt parameter */\n    RealScalar lm_param(void) { return m_par; }\n    \n    /** \\returns a reference to the  current vector function \n     */\n    FVectorType& fvec() {return m_fvec; }\n    \n    /** \\returns a reference to the matrix where the current Jacobian matrix is stored\n     */\n    JacobianType& jacobian() {return m_fjac; }\n    \n    /** \\returns a reference to the triangular matrix R from the QR of the jacobian matrix.\n     * \\sa jacobian()\n     */\n    JacobianType& matrixR() {return m_rfactor; }\n    \n    /** the permutation used in the QR factorization\n     */\n    PermutationType permutation() {return m_permutation; }\n    \n    /** \n     * \\brief Reports whether the minimization was successful\n     * \\returns \\c Success if the minimization was successful,\n     *         \\c NumericalIssue if a numerical problem arises during the \n     *          minimization process, for example during the QR factorization\n     *         \\c NoConvergence if the minimization did not converge after \n     *          the maximum number of function evaluation allowed\n     *          \\c InvalidInput if the input matrix is invalid\n     */\n    ComputationInfo info() const\n    {\n      \n      return m_info;\n    }\n  private:\n    JacobianType m_fjac; \n    JacobianType m_rfactor; // The triangular matrix R from the QR of the jacobian matrix m_fjac\n    FunctorType &m_functor;\n    FVectorType m_fvec, m_qtf, m_diag; \n    Index n;\n    Index m; \n    Index m_nfev;\n    Index m_njev; \n    RealScalar m_fnorm; // Norm of the current vector function\n    RealScalar m_gnorm; //Norm of the gradient of the error \n    RealScalar m_factor; //\n    Index m_maxfev; // Maximum number of function evaluation\n    RealScalar m_ftol; //Tolerance in the norm of the vector function\n    RealScalar m_xtol; // \n    RealScalar m_gtol; //tolerance of the norm of the error gradient\n    RealScalar m_epsfcn; //\n    Index m_iter; // Number of iterations performed\n    RealScalar m_delta;\n    bool m_useExternalScaling;\n    PermutationType m_permutation;\n    FVectorType m_wa1, m_wa2, m_wa3, m_wa4; //Temporary vectors\n    RealScalar m_par;\n    bool m_isInitialized; // Check whether the minimization step has been called\n    ComputationInfo m_info; \n};\n\ntemplate<typename FunctorType>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType>::minimize(FVectorType  &x)\n{\n    LevenbergMarquardtSpace::Status status = minimizeInit(x);\n    if (status==LevenbergMarquardtSpace::ImproperInputParameters) {\n      m_isInitialized = true;\n      return status;\n    }\n    do {\n//       std::cout << \" uv \" << x.transpose() << \"\\n\";\n        status = minimizeOneStep(x);\n    } while (status==LevenbergMarquardtSpace::Running);\n     m_isInitialized = true;\n     return status;\n}\n\ntemplate<typename FunctorType>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType>::minimizeInit(FVectorType  &x)\n{\n    n = x.size();\n    m = m_functor.values();\n\n    m_wa1.resize(n); m_wa2.resize(n); m_wa3.resize(n);\n    m_wa4.resize(m);\n    m_fvec.resize(m);\n    //FIXME Sparse Case : Allocate space for the jacobian\n    m_fjac.resize(m, n);\n//     m_fjac.reserve(VectorXi::Constant(n,5)); // FIXME Find a better alternative\n    if (!m_useExternalScaling)\n        m_diag.resize(n);\n    eigen_assert( (!m_useExternalScaling || m_diag.size()==n) && \"When m_useExternalScaling is set, the caller must provide a valid 'm_diag'\");\n    m_qtf.resize(n);\n\n    /* Function Body */\n    m_nfev = 0;\n    m_njev = 0;\n\n    /*     check the input parameters for errors. */\n    if (n <= 0 || m < n || m_ftol < 0. || m_xtol < 0. || m_gtol < 0. || m_maxfev <= 0 || m_factor <= 0.){\n      m_info = InvalidInput;\n      return LevenbergMarquardtSpace::ImproperInputParameters;\n    }\n\n    if (m_useExternalScaling)\n        for (Index j = 0; j < n; ++j)\n            if (m_diag[j] <= 0.) \n            {\n              m_info = InvalidInput;\n              return LevenbergMarquardtSpace::ImproperInputParameters;\n            }\n\n    /*     evaluate the function at the starting point */\n    /*     and calculate its norm. */\n    m_nfev = 1;\n    if ( m_functor(x, m_fvec) < 0)\n        return LevenbergMarquardtSpace::UserAsked;\n    m_fnorm = m_fvec.stableNorm();\n\n    /*     initialize levenberg-marquardt parameter and iteration counter. */\n    m_par = 0.;\n    m_iter = 1;\n\n    return LevenbergMarquardtSpace::NotStarted;\n}\n\ntemplate<typename FunctorType>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType>::lmder1(\n        FVectorType  &x,\n        const Scalar tol\n        )\n{\n    n = x.size();\n    m = m_functor.values();\n\n    /* check the input parameters for errors. */\n    if (n <= 0 || m < n || tol < 0.)\n        return LevenbergMarquardtSpace::ImproperInputParameters;\n\n    resetParameters();\n    m_ftol = tol;\n    m_xtol = tol;\n    m_maxfev = 100*(n+1);\n\n    return minimize(x);\n}\n\n\ntemplate<typename FunctorType>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType>::lmdif1(\n        FunctorType &functor,\n        FVectorType  &x,\n        Index *nfev,\n        const Scalar tol\n        )\n{\n    Index n = x.size();\n    Index m = functor.values();\n\n    /* check the input parameters for errors. */\n    if (n <= 0 || m < n || tol < 0.)\n        return LevenbergMarquardtSpace::ImproperInputParameters;\n\n    NumericalDiff<FunctorType> numDiff(functor);\n    // embedded LevenbergMarquardt\n    LevenbergMarquardt<NumericalDiff<FunctorType> > lm(numDiff);\n    lm.setFtol(tol);\n    lm.setXtol(tol);\n    lm.setMaxfev(200*(n+1));\n\n    LevenbergMarquardtSpace::Status info = LevenbergMarquardtSpace::Status(lm.minimize(x));\n    if (nfev)\n        * nfev = lm.nfev();\n    return info;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_LEVENBERGMARQUARDT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/MatrixFunctions/MatrixExponential.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009, 2010, 2013 Jitse Niesen <jitse@maths.leeds.ac.uk>\n// Copyright (C) 2011, 2013 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MATRIX_EXPONENTIAL\n#define EIGEN_MATRIX_EXPONENTIAL\n\n#include \"StemFunction.h\"\n\nnamespace Eigen {\nnamespace internal {\n\n/** \\brief Scaling operator.\n *\n * This struct is used by CwiseUnaryOp to scale a matrix by \\f$ 2^{-s} \\f$.\n */\ntemplate <typename RealScalar>\nstruct MatrixExponentialScalingOp\n{\n  /** \\brief Constructor.\n   *\n   * \\param[in] squarings  The integer \\f$ s \\f$ in this document.\n   */\n  MatrixExponentialScalingOp(int squarings) : m_squarings(squarings) { }\n\n\n  /** \\brief Scale a matrix coefficient.\n   *\n   * \\param[in,out] x  The scalar to be scaled, becoming \\f$ 2^{-s} x \\f$.\n   */\n  inline const RealScalar operator() (const RealScalar& x) const\n  {\n    using std::ldexp;\n    return ldexp(x, -m_squarings);\n  }\n\n  typedef std::complex<RealScalar> ComplexScalar;\n\n  /** \\brief Scale a matrix coefficient.\n   *\n   * \\param[in,out] x  The scalar to be scaled, becoming \\f$ 2^{-s} x \\f$.\n   */\n  inline const ComplexScalar operator() (const ComplexScalar& x) const\n  {\n    using std::ldexp;\n    return ComplexScalar(ldexp(x.real(), -m_squarings), ldexp(x.imag(), -m_squarings));\n  }\n\n  private:\n    int m_squarings;\n};\n\n/** \\brief Compute the (3,3)-Pad&eacute; approximant to the exponential.\n *\n *  After exit, \\f$ (V+U)(V-U)^{-1} \\f$ is the Pad&eacute;\n *  approximant of \\f$ \\exp(A) \\f$ around \\f$ A = 0 \\f$.\n */\ntemplate <typename MatA, typename MatU, typename MatV>\nvoid matrix_exp_pade3(const MatA& A, MatU& U, MatV& V)\n{\n  typedef typename MatA::PlainObject MatrixType;\n  typedef typename NumTraits<typename traits<MatA>::Scalar>::Real RealScalar;\n  const RealScalar b[] = {120.L, 60.L, 12.L, 1.L};\n  const MatrixType A2 = A * A;\n  const MatrixType tmp = b[3] * A2 + b[1] * MatrixType::Identity(A.rows(), A.cols());\n  U.noalias() = A * tmp;\n  V = b[2] * A2 + b[0] * MatrixType::Identity(A.rows(), A.cols());\n}\n\n/** \\brief Compute the (5,5)-Pad&eacute; approximant to the exponential.\n *\n *  After exit, \\f$ (V+U)(V-U)^{-1} \\f$ is the Pad&eacute;\n *  approximant of \\f$ \\exp(A) \\f$ around \\f$ A = 0 \\f$.\n */\ntemplate <typename MatA, typename MatU, typename MatV>\nvoid matrix_exp_pade5(const MatA& A, MatU& U, MatV& V)\n{\n  typedef typename MatA::PlainObject MatrixType;\n  typedef typename NumTraits<typename traits<MatrixType>::Scalar>::Real RealScalar;\n  const RealScalar b[] = {30240.L, 15120.L, 3360.L, 420.L, 30.L, 1.L};\n  const MatrixType A2 = A * A;\n  const MatrixType A4 = A2 * A2;\n  const MatrixType tmp = b[5] * A4 + b[3] * A2 + b[1] * MatrixType::Identity(A.rows(), A.cols());\n  U.noalias() = A * tmp;\n  V = b[4] * A4 + b[2] * A2 + b[0] * MatrixType::Identity(A.rows(), A.cols());\n}\n\n/** \\brief Compute the (7,7)-Pad&eacute; approximant to the exponential.\n *\n *  After exit, \\f$ (V+U)(V-U)^{-1} \\f$ is the Pad&eacute;\n *  approximant of \\f$ \\exp(A) \\f$ around \\f$ A = 0 \\f$.\n */\ntemplate <typename MatA, typename MatU, typename MatV>\nvoid matrix_exp_pade7(const MatA& A, MatU& U, MatV& V)\n{\n  typedef typename MatA::PlainObject MatrixType;\n  typedef typename NumTraits<typename traits<MatrixType>::Scalar>::Real RealScalar;\n  const RealScalar b[] = {17297280.L, 8648640.L, 1995840.L, 277200.L, 25200.L, 1512.L, 56.L, 1.L};\n  const MatrixType A2 = A * A;\n  const MatrixType A4 = A2 * A2;\n  const MatrixType A6 = A4 * A2;\n  const MatrixType tmp = b[7] * A6 + b[5] * A4 + b[3] * A2 \n    + b[1] * MatrixType::Identity(A.rows(), A.cols());\n  U.noalias() = A * tmp;\n  V = b[6] * A6 + b[4] * A4 + b[2] * A2 + b[0] * MatrixType::Identity(A.rows(), A.cols());\n\n}\n\n/** \\brief Compute the (9,9)-Pad&eacute; approximant to the exponential.\n *\n *  After exit, \\f$ (V+U)(V-U)^{-1} \\f$ is the Pad&eacute;\n *  approximant of \\f$ \\exp(A) \\f$ around \\f$ A = 0 \\f$.\n */\ntemplate <typename MatA, typename MatU, typename MatV>\nvoid matrix_exp_pade9(const MatA& A, MatU& U, MatV& V)\n{\n  typedef typename MatA::PlainObject MatrixType;\n  typedef typename NumTraits<typename traits<MatrixType>::Scalar>::Real RealScalar;\n  const RealScalar b[] = {17643225600.L, 8821612800.L, 2075673600.L, 302702400.L, 30270240.L,\n                          2162160.L, 110880.L, 3960.L, 90.L, 1.L};\n  const MatrixType A2 = A * A;\n  const MatrixType A4 = A2 * A2;\n  const MatrixType A6 = A4 * A2;\n  const MatrixType A8 = A6 * A2;\n  const MatrixType tmp = b[9] * A8 + b[7] * A6 + b[5] * A4 + b[3] * A2 \n    + b[1] * MatrixType::Identity(A.rows(), A.cols());\n  U.noalias() = A * tmp;\n  V = b[8] * A8 + b[6] * A6 + b[4] * A4 + b[2] * A2 + b[0] * MatrixType::Identity(A.rows(), A.cols());\n}\n\n/** \\brief Compute the (13,13)-Pad&eacute; approximant to the exponential.\n *\n *  After exit, \\f$ (V+U)(V-U)^{-1} \\f$ is the Pad&eacute;\n *  approximant of \\f$ \\exp(A) \\f$ around \\f$ A = 0 \\f$.\n */\ntemplate <typename MatA, typename MatU, typename MatV>\nvoid matrix_exp_pade13(const MatA& A, MatU& U, MatV& V)\n{\n  typedef typename MatA::PlainObject MatrixType;\n  typedef typename NumTraits<typename traits<MatrixType>::Scalar>::Real RealScalar;\n  const RealScalar b[] = {64764752532480000.L, 32382376266240000.L, 7771770303897600.L,\n                          1187353796428800.L, 129060195264000.L, 10559470521600.L, 670442572800.L,\n                          33522128640.L, 1323241920.L, 40840800.L, 960960.L, 16380.L, 182.L, 1.L};\n  const MatrixType A2 = A * A;\n  const MatrixType A4 = A2 * A2;\n  const MatrixType A6 = A4 * A2;\n  V = b[13] * A6 + b[11] * A4 + b[9] * A2; // used for temporary storage\n  MatrixType tmp = A6 * V;\n  tmp += b[7] * A6 + b[5] * A4 + b[3] * A2 + b[1] * MatrixType::Identity(A.rows(), A.cols());\n  U.noalias() = A * tmp;\n  tmp = b[12] * A6 + b[10] * A4 + b[8] * A2;\n  V.noalias() = A6 * tmp;\n  V += b[6] * A6 + b[4] * A4 + b[2] * A2 + b[0] * MatrixType::Identity(A.rows(), A.cols());\n}\n\n/** \\brief Compute the (17,17)-Pad&eacute; approximant to the exponential.\n *\n *  After exit, \\f$ (V+U)(V-U)^{-1} \\f$ is the Pad&eacute;\n *  approximant of \\f$ \\exp(A) \\f$ around \\f$ A = 0 \\f$.\n *\n *  This function activates only if your long double is double-double or quadruple.\n */\n#if LDBL_MANT_DIG > 64\ntemplate <typename MatA, typename MatU, typename MatV>\nvoid matrix_exp_pade17(const MatA& A, MatU& U, MatV& V)\n{\n  typedef typename MatA::PlainObject MatrixType;\n  typedef typename NumTraits<typename traits<MatrixType>::Scalar>::Real RealScalar;\n  const RealScalar b[] = {830034394580628357120000.L, 415017197290314178560000.L,\n                          100610229646136770560000.L, 15720348382208870400000.L,\n                          1774878043152614400000.L, 153822763739893248000.L, 10608466464820224000.L,\n                          595373117923584000.L, 27563570274240000.L, 1060137318240000.L,\n                          33924394183680.L, 899510451840.L, 19554575040.L, 341863200.L, 4651200.L,\n                          46512.L, 306.L, 1.L};\n  const MatrixType A2 = A * A;\n  const MatrixType A4 = A2 * A2;\n  const MatrixType A6 = A4 * A2;\n  const MatrixType A8 = A4 * A4;\n  V = b[17] * A8 + b[15] * A6 + b[13] * A4 + b[11] * A2; // used for temporary storage\n  MatrixType tmp = A8 * V;\n  tmp += b[9] * A8 + b[7] * A6 + b[5] * A4 + b[3] * A2 \n    + b[1] * MatrixType::Identity(A.rows(), A.cols());\n  U.noalias() = A * tmp;\n  tmp = b[16] * A8 + b[14] * A6 + b[12] * A4 + b[10] * A2;\n  V.noalias() = tmp * A8;\n  V += b[8] * A8 + b[6] * A6 + b[4] * A4 + b[2] * A2 \n    + b[0] * MatrixType::Identity(A.rows(), A.cols());\n}\n#endif\n\ntemplate <typename MatrixType, typename RealScalar = typename NumTraits<typename traits<MatrixType>::Scalar>::Real>\nstruct matrix_exp_computeUV\n{\n  /** \\brief Compute Pad&eacute; approximant to the exponential.\n    *\n    * Computes \\c U, \\c V and \\c squarings such that \\f$ (V+U)(V-U)^{-1} \\f$ is a Pad&eacute;\n    * approximant of \\f$ \\exp(2^{-\\mbox{squarings}}M) \\f$ around \\f$ M = 0 \\f$, where \\f$ M \\f$\n    * denotes the matrix \\c arg. The degree of the Pad&eacute; approximant and the value of squarings\n    * are chosen such that the approximation error is no more than the round-off error.\n    */\n  static void run(const MatrixType& arg, MatrixType& U, MatrixType& V, int& squarings);\n};\n\ntemplate <typename MatrixType>\nstruct matrix_exp_computeUV<MatrixType, float>\n{\n  template <typename ArgType>\n  static void run(const ArgType& arg, MatrixType& U, MatrixType& V, int& squarings)\n  {\n    using std::frexp;\n    using std::pow;\n    const float l1norm = arg.cwiseAbs().colwise().sum().maxCoeff();\n    squarings = 0;\n    if (l1norm < 4.258730016922831e-001f) {\n      matrix_exp_pade3(arg, U, V);\n    } else if (l1norm < 1.880152677804762e+000f) {\n      matrix_exp_pade5(arg, U, V);\n    } else {\n      const float maxnorm = 3.925724783138660f;\n      frexp(l1norm / maxnorm, &squarings);\n      if (squarings < 0) squarings = 0;\n      MatrixType A = arg.unaryExpr(MatrixExponentialScalingOp<float>(squarings));\n      matrix_exp_pade7(A, U, V);\n    }\n  }\n};\n\ntemplate <typename MatrixType>\nstruct matrix_exp_computeUV<MatrixType, double>\n{\n  typedef typename NumTraits<typename traits<MatrixType>::Scalar>::Real RealScalar;\n  template <typename ArgType>\n  static void run(const ArgType& arg, MatrixType& U, MatrixType& V, int& squarings)\n  {\n    using std::frexp;\n    using std::pow;\n    const RealScalar l1norm = arg.cwiseAbs().colwise().sum().maxCoeff();\n    squarings = 0;\n    if (l1norm < 1.495585217958292e-002) {\n      matrix_exp_pade3(arg, U, V);\n    } else if (l1norm < 2.539398330063230e-001) {\n      matrix_exp_pade5(arg, U, V);\n    } else if (l1norm < 9.504178996162932e-001) {\n      matrix_exp_pade7(arg, U, V);\n    } else if (l1norm < 2.097847961257068e+000) {\n      matrix_exp_pade9(arg, U, V);\n    } else {\n      const RealScalar maxnorm = 5.371920351148152;\n      frexp(l1norm / maxnorm, &squarings);\n      if (squarings < 0) squarings = 0;\n      MatrixType A = arg.unaryExpr(MatrixExponentialScalingOp<RealScalar>(squarings));\n      matrix_exp_pade13(A, U, V);\n    }\n  }\n};\n  \ntemplate <typename MatrixType>\nstruct matrix_exp_computeUV<MatrixType, long double>\n{\n  template <typename ArgType>\n  static void run(const ArgType& arg, MatrixType& U, MatrixType& V, int& squarings)\n  {\n#if   LDBL_MANT_DIG == 53   // double precision\n    matrix_exp_computeUV<MatrixType, double>::run(arg, U, V, squarings);\n  \n#else\n  \n    using std::frexp;\n    using std::pow;\n    const long double l1norm = arg.cwiseAbs().colwise().sum().maxCoeff();\n    squarings = 0;\n  \n#if LDBL_MANT_DIG <= 64   // extended precision\n  \n    if (l1norm < 4.1968497232266989671e-003L) {\n      matrix_exp_pade3(arg, U, V);\n    } else if (l1norm < 1.1848116734693823091e-001L) {\n      matrix_exp_pade5(arg, U, V);\n    } else if (l1norm < 5.5170388480686700274e-001L) {\n      matrix_exp_pade7(arg, U, V);\n    } else if (l1norm < 1.3759868875587845383e+000L) {\n      matrix_exp_pade9(arg, U, V);\n    } else {\n      const long double maxnorm = 4.0246098906697353063L;\n      frexp(l1norm / maxnorm, &squarings);\n      if (squarings < 0) squarings = 0;\n      MatrixType A = arg.unaryExpr(MatrixExponentialScalingOp<long double>(squarings));\n      matrix_exp_pade13(A, U, V);\n    }\n  \n#elif LDBL_MANT_DIG <= 106  // double-double\n  \n    if (l1norm < 3.2787892205607026992947488108213e-005L) {\n      matrix_exp_pade3(arg, U, V);\n    } else if (l1norm < 6.4467025060072760084130906076332e-003L) {\n      matrix_exp_pade5(arg, U, V);\n    } else if (l1norm < 6.8988028496595374751374122881143e-002L) {\n      matrix_exp_pade7(arg, U, V);\n    } else if (l1norm < 2.7339737518502231741495857201670e-001L) {\n      matrix_exp_pade9(arg, U, V);\n    } else if (l1norm < 1.3203382096514474905666448850278e+000L) {\n      matrix_exp_pade13(arg, U, V);\n    } else {\n      const long double maxnorm = 3.2579440895405400856599663723517L;\n      frexp(l1norm / maxnorm, &squarings);\n      if (squarings < 0) squarings = 0;\n      MatrixType A = arg.unaryExpr(MatrixExponentialScalingOp<long double>(squarings));\n      matrix_exp_pade17(A, U, V);\n    }\n  \n#elif LDBL_MANT_DIG <= 113  // quadruple precision\n  \n    if (l1norm < 1.639394610288918690547467954466970e-005L) {\n      matrix_exp_pade3(arg, U, V);\n    } else if (l1norm < 4.253237712165275566025884344433009e-003L) {\n      matrix_exp_pade5(arg, U, V);\n    } else if (l1norm < 5.125804063165764409885122032933142e-002L) {\n      matrix_exp_pade7(arg, U, V);\n    } else if (l1norm < 2.170000765161155195453205651889853e-001L) {\n      matrix_exp_pade9(arg, U, V);\n    } else if (l1norm < 1.125358383453143065081397882891878e+000L) {\n      matrix_exp_pade13(arg, U, V);\n    } else {\n      const long double maxnorm = 2.884233277829519311757165057717815L;\n      frexp(l1norm / maxnorm, &squarings);\n      if (squarings < 0) squarings = 0;\n      MatrixType A = arg.unaryExpr(MatrixExponentialScalingOp<long double>(squarings));\n      matrix_exp_pade17(A, U, V);\n    }\n  \n#else\n  \n    // this case should be handled in compute()\n    eigen_assert(false && \"Bug in MatrixExponential\"); \n  \n#endif\n#endif  // LDBL_MANT_DIG\n  }\n};\n\ntemplate<typename T> struct is_exp_known_type : false_type {};\ntemplate<> struct is_exp_known_type<float> : true_type {};\ntemplate<> struct is_exp_known_type<double> : true_type {};\n#if LDBL_MANT_DIG <= 113\ntemplate<> struct is_exp_known_type<long double> : true_type {};\n#endif\n\ntemplate <typename ArgType, typename ResultType>\nvoid matrix_exp_compute(const ArgType& arg, ResultType &result, true_type) // natively supported scalar type\n{\n  typedef typename ArgType::PlainObject MatrixType;\n  MatrixType U, V;\n  int squarings;\n  matrix_exp_computeUV<MatrixType>::run(arg, U, V, squarings); // Pade approximant is (U+V) / (-U+V)\n  MatrixType numer = U + V;\n  MatrixType denom = -U + V;\n  result = denom.partialPivLu().solve(numer);\n  for (int i=0; i<squarings; i++)\n    result *= result;   // undo scaling by repeated squaring\n}\n\n\n/* Computes the matrix exponential\n *\n * \\param arg    argument of matrix exponential (should be plain object)\n * \\param result variable in which result will be stored\n */\ntemplate <typename ArgType, typename ResultType>\nvoid matrix_exp_compute(const ArgType& arg, ResultType &result, false_type) // default\n{\n  typedef typename ArgType::PlainObject MatrixType;\n  typedef typename traits<MatrixType>::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef typename std::complex<RealScalar> ComplexScalar;\n  result = arg.matrixFunction(internal::stem_function_exp<ComplexScalar>);\n}\n\n} // end namespace Eigen::internal\n\n/** \\ingroup MatrixFunctions_Module\n  *\n  * \\brief Proxy for the matrix exponential of some matrix (expression).\n  *\n  * \\tparam Derived  Type of the argument to the matrix exponential.\n  *\n  * This class holds the argument to the matrix exponential until it is assigned or evaluated for\n  * some other reason (so the argument should not be changed in the meantime). It is the return type\n  * of MatrixBase::exp() and most of the time this is the only way it is used.\n  */\ntemplate<typename Derived> struct MatrixExponentialReturnValue\n: public ReturnByValue<MatrixExponentialReturnValue<Derived> >\n{\n  public:\n    /** \\brief Constructor.\n      *\n      * \\param src %Matrix (expression) forming the argument of the matrix exponential.\n      */\n    MatrixExponentialReturnValue(const Derived& src) : m_src(src) { }\n\n    /** \\brief Compute the matrix exponential.\n      *\n      * \\param result the matrix exponential of \\p src in the constructor.\n      */\n    template <typename ResultType>\n    inline void evalTo(ResultType& result) const\n    {\n      const typename internal::nested_eval<Derived, 10>::type tmp(m_src);\n      internal::matrix_exp_compute(tmp, result, internal::is_exp_known_type<typename Derived::RealScalar>());\n    }\n\n    Index rows() const { return m_src.rows(); }\n    Index cols() const { return m_src.cols(); }\n\n  protected:\n    const typename internal::ref_selector<Derived>::type m_src;\n};\n\nnamespace internal {\ntemplate<typename Derived>\nstruct traits<MatrixExponentialReturnValue<Derived> >\n{\n  typedef typename Derived::PlainObject ReturnType;\n};\n}\n\ntemplate <typename Derived>\nconst MatrixExponentialReturnValue<Derived> MatrixBase<Derived>::exp() const\n{\n  eigen_assert(rows() == cols());\n  return MatrixExponentialReturnValue<Derived>(derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_MATRIX_EXPONENTIAL\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/MatrixFunctions/MatrixFunction.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2011, 2013 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MATRIX_FUNCTION_H\n#define EIGEN_MATRIX_FUNCTION_H\n\n#include \"StemFunction.h\"\n\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\brief Maximum distance allowed between eigenvalues to be considered \"close\". */\nstatic const float matrix_function_separation = 0.1f;\n\n/** \\ingroup MatrixFunctions_Module\n  * \\class MatrixFunctionAtomic\n  * \\brief Helper class for computing matrix functions of atomic matrices.\n  *\n  * Here, an atomic matrix is a triangular matrix whose diagonal entries are close to each other.\n  */\ntemplate <typename MatrixType>\nclass MatrixFunctionAtomic \n{\n  public:\n\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename stem_function<Scalar>::type StemFunction;\n\n    /** \\brief Constructor\n      * \\param[in]  f  matrix function to compute.\n      */\n    MatrixFunctionAtomic(StemFunction f) : m_f(f) { }\n\n    /** \\brief Compute matrix function of atomic matrix\n      * \\param[in]  A  argument of matrix function, should be upper triangular and atomic\n      * \\returns  f(A), the matrix function evaluated at the given matrix\n      */\n    MatrixType compute(const MatrixType& A);\n\n  private:\n    StemFunction* m_f;\n};\n\ntemplate <typename MatrixType>\ntypename NumTraits<typename MatrixType::Scalar>::Real matrix_function_compute_mu(const MatrixType& A)\n{\n  typedef typename plain_col_type<MatrixType>::type VectorType;\n  Index rows = A.rows();\n  const MatrixType N = MatrixType::Identity(rows, rows) - A;\n  VectorType e = VectorType::Ones(rows);\n  N.template triangularView<Upper>().solveInPlace(e);\n  return e.cwiseAbs().maxCoeff();\n}\n\ntemplate <typename MatrixType>\nMatrixType MatrixFunctionAtomic<MatrixType>::compute(const MatrixType& A)\n{\n  // TODO: Use that A is upper triangular\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  Index rows = A.rows();\n  Scalar avgEival = A.trace() / Scalar(RealScalar(rows));\n  MatrixType Ashifted = A - avgEival * MatrixType::Identity(rows, rows);\n  RealScalar mu = matrix_function_compute_mu(Ashifted);\n  MatrixType F = m_f(avgEival, 0) * MatrixType::Identity(rows, rows);\n  MatrixType P = Ashifted;\n  MatrixType Fincr;\n  for (Index s = 1; double(s) < 1.1 * double(rows) + 10.0; s++) { // upper limit is fairly arbitrary\n    Fincr = m_f(avgEival, static_cast<int>(s)) * P;\n    F += Fincr;\n    P = Scalar(RealScalar(1)/RealScalar(s + 1)) * P * Ashifted;\n\n    // test whether Taylor series converged\n    const RealScalar F_norm = F.cwiseAbs().rowwise().sum().maxCoeff();\n    const RealScalar Fincr_norm = Fincr.cwiseAbs().rowwise().sum().maxCoeff();\n    if (Fincr_norm < NumTraits<Scalar>::epsilon() * F_norm) {\n      RealScalar delta = 0;\n      RealScalar rfactorial = 1;\n      for (Index r = 0; r < rows; r++) {\n        RealScalar mx = 0;\n        for (Index i = 0; i < rows; i++)\n          mx = (std::max)(mx, std::abs(m_f(Ashifted(i, i) + avgEival, static_cast<int>(s+r))));\n        if (r != 0)\n          rfactorial *= RealScalar(r);\n        delta = (std::max)(delta, mx / rfactorial);\n      }\n      const RealScalar P_norm = P.cwiseAbs().rowwise().sum().maxCoeff();\n      if (mu * delta * P_norm < NumTraits<Scalar>::epsilon() * F_norm) // series converged\n        break;\n    }\n  }\n  return F;\n}\n\n/** \\brief Find cluster in \\p clusters containing some value \n  * \\param[in] key Value to find\n  * \\returns Iterator to cluster containing \\p key, or \\c clusters.end() if no cluster in \\p m_clusters\n  * contains \\p key.\n  */\ntemplate <typename Index, typename ListOfClusters>\ntypename ListOfClusters::iterator matrix_function_find_cluster(Index key, ListOfClusters& clusters)\n{\n  typename std::list<Index>::iterator j;\n  for (typename ListOfClusters::iterator i = clusters.begin(); i != clusters.end(); ++i) {\n    j = std::find(i->begin(), i->end(), key);\n    if (j != i->end())\n      return i;\n  }\n  return clusters.end();\n}\n\n/** \\brief Partition eigenvalues in clusters of ei'vals close to each other\n  * \n  * \\param[in]  eivals    Eigenvalues\n  * \\param[out] clusters  Resulting partition of eigenvalues\n  *\n  * The partition satisfies the following two properties:\n  * # Any eigenvalue in a certain cluster is at most matrix_function_separation() away from another eigenvalue\n  *   in the same cluster.\n  * # The distance between two eigenvalues in different clusters is more than matrix_function_separation().  \n  * The implementation follows Algorithm 4.1 in the paper of Davies and Higham.\n  */\ntemplate <typename EivalsType, typename Cluster>\nvoid matrix_function_partition_eigenvalues(const EivalsType& eivals, std::list<Cluster>& clusters)\n{\n  typedef typename EivalsType::RealScalar RealScalar;\n  for (Index i=0; i<eivals.rows(); ++i) {\n    // Find cluster containing i-th ei'val, adding a new cluster if necessary\n    typename std::list<Cluster>::iterator qi = matrix_function_find_cluster(i, clusters);\n    if (qi == clusters.end()) {\n      Cluster l;\n      l.push_back(i);\n      clusters.push_back(l);\n      qi = clusters.end();\n      --qi;\n    }\n\n    // Look for other element to add to the set\n    for (Index j=i+1; j<eivals.rows(); ++j) {\n      if (abs(eivals(j) - eivals(i)) <= RealScalar(matrix_function_separation)\n          && std::find(qi->begin(), qi->end(), j) == qi->end()) {\n        typename std::list<Cluster>::iterator qj = matrix_function_find_cluster(j, clusters);\n        if (qj == clusters.end()) {\n          qi->push_back(j);\n        } else {\n          qi->insert(qi->end(), qj->begin(), qj->end());\n          clusters.erase(qj);\n        }\n      }\n    }\n  }\n}\n\n/** \\brief Compute size of each cluster given a partitioning */\ntemplate <typename ListOfClusters, typename Index>\nvoid matrix_function_compute_cluster_size(const ListOfClusters& clusters, Matrix<Index, Dynamic, 1>& clusterSize)\n{\n  const Index numClusters = static_cast<Index>(clusters.size());\n  clusterSize.setZero(numClusters);\n  Index clusterIndex = 0;\n  for (typename ListOfClusters::const_iterator cluster = clusters.begin(); cluster != clusters.end(); ++cluster) {\n    clusterSize[clusterIndex] = cluster->size();\n    ++clusterIndex;\n  }\n}\n\n/** \\brief Compute start of each block using clusterSize */\ntemplate <typename VectorType>\nvoid matrix_function_compute_block_start(const VectorType& clusterSize, VectorType& blockStart)\n{\n  blockStart.resize(clusterSize.rows());\n  blockStart(0) = 0;\n  for (Index i = 1; i < clusterSize.rows(); i++) {\n    blockStart(i) = blockStart(i-1) + clusterSize(i-1);\n  }\n}\n\n/** \\brief Compute mapping of eigenvalue indices to cluster indices */\ntemplate <typename EivalsType, typename ListOfClusters, typename VectorType>\nvoid matrix_function_compute_map(const EivalsType& eivals, const ListOfClusters& clusters, VectorType& eivalToCluster)\n{\n  eivalToCluster.resize(eivals.rows());\n  Index clusterIndex = 0;\n  for (typename ListOfClusters::const_iterator cluster = clusters.begin(); cluster != clusters.end(); ++cluster) {\n    for (Index i = 0; i < eivals.rows(); ++i) {\n      if (std::find(cluster->begin(), cluster->end(), i) != cluster->end()) {\n        eivalToCluster[i] = clusterIndex;\n      }\n    }\n    ++clusterIndex;\n  }\n}\n\n/** \\brief Compute permutation which groups ei'vals in same cluster together */\ntemplate <typename DynVectorType, typename VectorType>\nvoid matrix_function_compute_permutation(const DynVectorType& blockStart, const DynVectorType& eivalToCluster, VectorType& permutation)\n{\n  DynVectorType indexNextEntry = blockStart;\n  permutation.resize(eivalToCluster.rows());\n  for (Index i = 0; i < eivalToCluster.rows(); i++) {\n    Index cluster = eivalToCluster[i];\n    permutation[i] = indexNextEntry[cluster];\n    ++indexNextEntry[cluster];\n  }\n}  \n\n/** \\brief Permute Schur decomposition in U and T according to permutation */\ntemplate <typename VectorType, typename MatrixType>\nvoid matrix_function_permute_schur(VectorType& permutation, MatrixType& U, MatrixType& T)\n{\n  for (Index i = 0; i < permutation.rows() - 1; i++) {\n    Index j;\n    for (j = i; j < permutation.rows(); j++) {\n      if (permutation(j) == i) break;\n    }\n    eigen_assert(permutation(j) == i);\n    for (Index k = j-1; k >= i; k--) {\n      JacobiRotation<typename MatrixType::Scalar> rotation;\n      rotation.makeGivens(T(k, k+1), T(k+1, k+1) - T(k, k));\n      T.applyOnTheLeft(k, k+1, rotation.adjoint());\n      T.applyOnTheRight(k, k+1, rotation);\n      U.applyOnTheRight(k, k+1, rotation);\n      std::swap(permutation.coeffRef(k), permutation.coeffRef(k+1));\n    }\n  }\n}\n\n/** \\brief Compute block diagonal part of matrix function.\n  *\n  * This routine computes the matrix function applied to the block diagonal part of \\p T (which should be\n  * upper triangular), with the blocking given by \\p blockStart and \\p clusterSize. The matrix function of\n  * each diagonal block is computed by \\p atomic. The off-diagonal parts of \\p fT are set to zero.\n  */\ntemplate <typename MatrixType, typename AtomicType, typename VectorType>\nvoid matrix_function_compute_block_atomic(const MatrixType& T, AtomicType& atomic, const VectorType& blockStart, const VectorType& clusterSize, MatrixType& fT)\n{ \n  fT.setZero(T.rows(), T.cols());\n  for (Index i = 0; i < clusterSize.rows(); ++i) {\n    fT.block(blockStart(i), blockStart(i), clusterSize(i), clusterSize(i))\n      = atomic.compute(T.block(blockStart(i), blockStart(i), clusterSize(i), clusterSize(i)));\n  }\n}\n\n/** \\brief Solve a triangular Sylvester equation AX + XB = C \n  *\n  * \\param[in]  A  the matrix A; should be square and upper triangular\n  * \\param[in]  B  the matrix B; should be square and upper triangular\n  * \\param[in]  C  the matrix C; should have correct size.\n  *\n  * \\returns the solution X.\n  *\n  * If A is m-by-m and B is n-by-n, then both C and X are m-by-n.  The (i,j)-th component of the Sylvester\n  * equation is\n  * \\f[ \n  *     \\sum_{k=i}^m A_{ik} X_{kj} + \\sum_{k=1}^j X_{ik} B_{kj} = C_{ij}. \n  * \\f]\n  * This can be re-arranged to yield:\n  * \\f[ \n  *     X_{ij} = \\frac{1}{A_{ii} + B_{jj}} \\Bigl( C_{ij}\n  *     - \\sum_{k=i+1}^m A_{ik} X_{kj} - \\sum_{k=1}^{j-1} X_{ik} B_{kj} \\Bigr).\n  * \\f]\n  * It is assumed that A and B are such that the numerator is never zero (otherwise the Sylvester equation\n  * does not have a unique solution). In that case, these equations can be evaluated in the order \n  * \\f$ i=m,\\ldots,1 \\f$ and \\f$ j=1,\\ldots,n \\f$.\n  */\ntemplate <typename MatrixType>\nMatrixType matrix_function_solve_triangular_sylvester(const MatrixType& A, const MatrixType& B, const MatrixType& C)\n{\n  eigen_assert(A.rows() == A.cols());\n  eigen_assert(A.isUpperTriangular());\n  eigen_assert(B.rows() == B.cols());\n  eigen_assert(B.isUpperTriangular());\n  eigen_assert(C.rows() == A.rows());\n  eigen_assert(C.cols() == B.rows());\n\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index m = A.rows();\n  Index n = B.rows();\n  MatrixType X(m, n);\n\n  for (Index i = m - 1; i >= 0; --i) {\n    for (Index j = 0; j < n; ++j) {\n\n      // Compute AX = \\sum_{k=i+1}^m A_{ik} X_{kj}\n      Scalar AX;\n      if (i == m - 1) {\n\tAX = 0; \n      } else {\n\tMatrix<Scalar,1,1> AXmatrix = A.row(i).tail(m-1-i) * X.col(j).tail(m-1-i);\n\tAX = AXmatrix(0,0);\n      }\n\n      // Compute XB = \\sum_{k=1}^{j-1} X_{ik} B_{kj}\n      Scalar XB;\n      if (j == 0) {\n\tXB = 0; \n      } else {\n\tMatrix<Scalar,1,1> XBmatrix = X.row(i).head(j) * B.col(j).head(j);\n\tXB = XBmatrix(0,0);\n      }\n\n      X(i,j) = (C(i,j) - AX - XB) / (A(i,i) + B(j,j));\n    }\n  }\n  return X;\n}\n\n/** \\brief Compute part of matrix function above block diagonal.\n  *\n  * This routine completes the computation of \\p fT, denoting a matrix function applied to the triangular\n  * matrix \\p T. It assumes that the block diagonal part of \\p fT has already been computed. The part below\n  * the diagonal is zero, because \\p T is upper triangular.\n  */\ntemplate <typename MatrixType, typename VectorType>\nvoid matrix_function_compute_above_diagonal(const MatrixType& T, const VectorType& blockStart, const VectorType& clusterSize, MatrixType& fT)\n{ \n  typedef internal::traits<MatrixType> Traits;\n  typedef typename MatrixType::Scalar Scalar;\n  static const int Options = MatrixType::Options;\n  typedef Matrix<Scalar, Dynamic, Dynamic, Options, Traits::RowsAtCompileTime, Traits::ColsAtCompileTime> DynMatrixType;\n\n  for (Index k = 1; k < clusterSize.rows(); k++) {\n    for (Index i = 0; i < clusterSize.rows() - k; i++) {\n      // compute (i, i+k) block\n      DynMatrixType A = T.block(blockStart(i), blockStart(i), clusterSize(i), clusterSize(i));\n      DynMatrixType B = -T.block(blockStart(i+k), blockStart(i+k), clusterSize(i+k), clusterSize(i+k));\n      DynMatrixType C = fT.block(blockStart(i), blockStart(i), clusterSize(i), clusterSize(i))\n        * T.block(blockStart(i), blockStart(i+k), clusterSize(i), clusterSize(i+k));\n      C -= T.block(blockStart(i), blockStart(i+k), clusterSize(i), clusterSize(i+k))\n        * fT.block(blockStart(i+k), blockStart(i+k), clusterSize(i+k), clusterSize(i+k));\n      for (Index m = i + 1; m < i + k; m++) {\n        C += fT.block(blockStart(i), blockStart(m), clusterSize(i), clusterSize(m))\n          * T.block(blockStart(m), blockStart(i+k), clusterSize(m), clusterSize(i+k));\n        C -= T.block(blockStart(i), blockStart(m), clusterSize(i), clusterSize(m))\n          * fT.block(blockStart(m), blockStart(i+k), clusterSize(m), clusterSize(i+k));\n      }\n      fT.block(blockStart(i), blockStart(i+k), clusterSize(i), clusterSize(i+k))\n        = matrix_function_solve_triangular_sylvester(A, B, C);\n    }\n  }\n}\n\n/** \\ingroup MatrixFunctions_Module\n  * \\brief Class for computing matrix functions.\n  * \\tparam  MatrixType  type of the argument of the matrix function,\n  *                      expected to be an instantiation of the Matrix class template.\n  * \\tparam  AtomicType  type for computing matrix function of atomic blocks.\n  * \\tparam  IsComplex   used internally to select correct specialization.\n  *\n  * This class implements the Schur-Parlett algorithm for computing matrix functions. The spectrum of the\n  * matrix is divided in clustered of eigenvalues that lies close together. This class delegates the\n  * computation of the matrix function on every block corresponding to these clusters to an object of type\n  * \\p AtomicType and uses these results to compute the matrix function of the whole matrix. The class\n  * \\p AtomicType should have a \\p compute() member function for computing the matrix function of a block.\n  *\n  * \\sa class MatrixFunctionAtomic, class MatrixLogarithmAtomic\n  */\ntemplate <typename MatrixType, int IsComplex = NumTraits<typename internal::traits<MatrixType>::Scalar>::IsComplex>\nstruct matrix_function_compute\n{  \n    /** \\brief Compute the matrix function.\n      *\n      * \\param[in]  A       argument of matrix function, should be a square matrix.\n      * \\param[in]  atomic  class for computing matrix function of atomic blocks.\n      * \\param[out] result  the function \\p f applied to \\p A, as\n      * specified in the constructor.\n      *\n      * See MatrixBase::matrixFunction() for details on how this computation\n      * is implemented.\n      */\n    template <typename AtomicType, typename ResultType> \n    static void run(const MatrixType& A, AtomicType& atomic, ResultType &result);    \n};\n\n/** \\internal \\ingroup MatrixFunctions_Module \n  * \\brief Partial specialization of MatrixFunction for real matrices\n  *\n  * This converts the real matrix to a complex matrix, compute the matrix function of that matrix, and then\n  * converts the result back to a real matrix.\n  */\ntemplate <typename MatrixType>\nstruct matrix_function_compute<MatrixType, 0>\n{  \n  template <typename MatA, typename AtomicType, typename ResultType>\n  static void run(const MatA& A, AtomicType& atomic, ResultType &result)\n  {\n    typedef internal::traits<MatrixType> Traits;\n    typedef typename Traits::Scalar Scalar;\n    static const int Rows = Traits::RowsAtCompileTime, Cols = Traits::ColsAtCompileTime;\n    static const int MaxRows = Traits::MaxRowsAtCompileTime, MaxCols = Traits::MaxColsAtCompileTime;\n\n    typedef std::complex<Scalar> ComplexScalar;\n    typedef Matrix<ComplexScalar, Rows, Cols, 0, MaxRows, MaxCols> ComplexMatrix;\n\n    ComplexMatrix CA = A.template cast<ComplexScalar>();\n    ComplexMatrix Cresult;\n    matrix_function_compute<ComplexMatrix>::run(CA, atomic, Cresult);\n    result = Cresult.real();\n  }\n};\n\n/** \\internal \\ingroup MatrixFunctions_Module \n  * \\brief Partial specialization of MatrixFunction for complex matrices\n  */\ntemplate <typename MatrixType>\nstruct matrix_function_compute<MatrixType, 1>\n{\n  template <typename MatA, typename AtomicType, typename ResultType>\n  static void run(const MatA& A, AtomicType& atomic, ResultType &result)\n  {\n    typedef internal::traits<MatrixType> Traits;\n    \n    // compute Schur decomposition of A\n    const ComplexSchur<MatrixType> schurOfA(A);\n    eigen_assert(schurOfA.info()==Success);\n    MatrixType T = schurOfA.matrixT();\n    MatrixType U = schurOfA.matrixU();\n\n    // partition eigenvalues into clusters of ei'vals \"close\" to each other\n    std::list<std::list<Index> > clusters; \n    matrix_function_partition_eigenvalues(T.diagonal(), clusters);\n\n    // compute size of each cluster\n    Matrix<Index, Dynamic, 1> clusterSize;\n    matrix_function_compute_cluster_size(clusters, clusterSize);\n\n    // blockStart[i] is row index at which block corresponding to i-th cluster starts \n    Matrix<Index, Dynamic, 1> blockStart; \n    matrix_function_compute_block_start(clusterSize, blockStart);\n\n    // compute map so that eivalToCluster[i] = j means that i-th ei'val is in j-th cluster \n    Matrix<Index, Dynamic, 1> eivalToCluster;\n    matrix_function_compute_map(T.diagonal(), clusters, eivalToCluster);\n\n    // compute permutation which groups ei'vals in same cluster together \n    Matrix<Index, Traits::RowsAtCompileTime, 1> permutation;\n    matrix_function_compute_permutation(blockStart, eivalToCluster, permutation);\n\n    // permute Schur decomposition\n    matrix_function_permute_schur(permutation, U, T);\n\n    // compute result\n    MatrixType fT; // matrix function applied to T\n    matrix_function_compute_block_atomic(T, atomic, blockStart, clusterSize, fT);\n    matrix_function_compute_above_diagonal(T, blockStart, clusterSize, fT);\n    result = U * (fT.template triangularView<Upper>() * U.adjoint());\n  }\n};\n\n} // end of namespace internal\n\n/** \\ingroup MatrixFunctions_Module\n  *\n  * \\brief Proxy for the matrix function of some matrix (expression).\n  *\n  * \\tparam Derived  Type of the argument to the matrix function.\n  *\n  * This class holds the argument to the matrix function until it is assigned or evaluated for some other\n  * reason (so the argument should not be changed in the meantime). It is the return type of\n  * matrixBase::matrixFunction() and related functions and most of the time this is the only way it is used.\n  */\ntemplate<typename Derived> class MatrixFunctionReturnValue\n: public ReturnByValue<MatrixFunctionReturnValue<Derived> >\n{\n  public:\n    typedef typename Derived::Scalar Scalar;\n    typedef typename internal::stem_function<Scalar>::type StemFunction;\n\n  protected:\n    typedef typename internal::ref_selector<Derived>::type DerivedNested;\n\n  public:\n\n    /** \\brief Constructor.\n      *\n      * \\param[in] A  %Matrix (expression) forming the argument of the matrix function.\n      * \\param[in] f  Stem function for matrix function under consideration.\n      */\n    MatrixFunctionReturnValue(const Derived& A, StemFunction f) : m_A(A), m_f(f) { }\n\n    /** \\brief Compute the matrix function.\n      *\n      * \\param[out] result \\p f applied to \\p A, where \\p f and \\p A are as in the constructor.\n      */\n    template <typename ResultType>\n    inline void evalTo(ResultType& result) const\n    {\n      typedef typename internal::nested_eval<Derived, 10>::type NestedEvalType;\n      typedef typename internal::remove_all<NestedEvalType>::type NestedEvalTypeClean;\n      typedef internal::traits<NestedEvalTypeClean> Traits;\n      typedef std::complex<typename NumTraits<Scalar>::Real> ComplexScalar;\n      typedef Matrix<ComplexScalar, Dynamic, Dynamic, 0, Traits::RowsAtCompileTime, Traits::ColsAtCompileTime> DynMatrixType;\n\n      typedef internal::MatrixFunctionAtomic<DynMatrixType> AtomicType;\n      AtomicType atomic(m_f);\n\n      internal::matrix_function_compute<typename NestedEvalTypeClean::PlainObject>::run(m_A, atomic, result);\n    }\n\n    Index rows() const { return m_A.rows(); }\n    Index cols() const { return m_A.cols(); }\n\n  private:\n    const DerivedNested m_A;\n    StemFunction *m_f;\n};\n\nnamespace internal {\ntemplate<typename Derived>\nstruct traits<MatrixFunctionReturnValue<Derived> >\n{\n  typedef typename Derived::PlainObject ReturnType;\n};\n}\n\n\n/********** MatrixBase methods **********/\n\n\ntemplate <typename Derived>\nconst MatrixFunctionReturnValue<Derived> MatrixBase<Derived>::matrixFunction(typename internal::stem_function<typename internal::traits<Derived>::Scalar>::type f) const\n{\n  eigen_assert(rows() == cols());\n  return MatrixFunctionReturnValue<Derived>(derived(), f);\n}\n\ntemplate <typename Derived>\nconst MatrixFunctionReturnValue<Derived> MatrixBase<Derived>::sin() const\n{\n  eigen_assert(rows() == cols());\n  typedef typename internal::stem_function<Scalar>::ComplexScalar ComplexScalar;\n  return MatrixFunctionReturnValue<Derived>(derived(), internal::stem_function_sin<ComplexScalar>);\n}\n\ntemplate <typename Derived>\nconst MatrixFunctionReturnValue<Derived> MatrixBase<Derived>::cos() const\n{\n  eigen_assert(rows() == cols());\n  typedef typename internal::stem_function<Scalar>::ComplexScalar ComplexScalar;\n  return MatrixFunctionReturnValue<Derived>(derived(), internal::stem_function_cos<ComplexScalar>);\n}\n\ntemplate <typename Derived>\nconst MatrixFunctionReturnValue<Derived> MatrixBase<Derived>::sinh() const\n{\n  eigen_assert(rows() == cols());\n  typedef typename internal::stem_function<Scalar>::ComplexScalar ComplexScalar;\n  return MatrixFunctionReturnValue<Derived>(derived(), internal::stem_function_sinh<ComplexScalar>);\n}\n\ntemplate <typename Derived>\nconst MatrixFunctionReturnValue<Derived> MatrixBase<Derived>::cosh() const\n{\n  eigen_assert(rows() == cols());\n  typedef typename internal::stem_function<Scalar>::ComplexScalar ComplexScalar;\n  return MatrixFunctionReturnValue<Derived>(derived(), internal::stem_function_cosh<ComplexScalar>);\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_MATRIX_FUNCTION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/MatrixFunctions/MatrixLogarithm.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011, 2013 Jitse Niesen <jitse@maths.leeds.ac.uk>\n// Copyright (C) 2011 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MATRIX_LOGARITHM\n#define EIGEN_MATRIX_LOGARITHM\n\nnamespace Eigen { \n\nnamespace internal { \n\ntemplate <typename Scalar>\nstruct matrix_log_min_pade_degree \n{\n  static const int value = 3;\n};\n\ntemplate <typename Scalar>\nstruct matrix_log_max_pade_degree \n{\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  static const int value = std::numeric_limits<RealScalar>::digits<= 24?  5:  // single precision\n                           std::numeric_limits<RealScalar>::digits<= 53?  7:  // double precision\n                           std::numeric_limits<RealScalar>::digits<= 64?  8:  // extended precision\n                           std::numeric_limits<RealScalar>::digits<=106? 10:  // double-double\n                                                                         11;  // quadruple precision\n};\n\n/** \\brief Compute logarithm of 2x2 triangular matrix. */\ntemplate <typename MatrixType>\nvoid matrix_log_compute_2x2(const MatrixType& A, MatrixType& result)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  using std::abs;\n  using std::ceil;\n  using std::imag;\n  using std::log;\n\n  Scalar logA00 = log(A(0,0));\n  Scalar logA11 = log(A(1,1));\n\n  result(0,0) = logA00;\n  result(1,0) = Scalar(0);\n  result(1,1) = logA11;\n\n  Scalar y = A(1,1) - A(0,0);\n  if (y==Scalar(0))\n  {\n    result(0,1) = A(0,1) / A(0,0);\n  }\n  else if ((abs(A(0,0)) < RealScalar(0.5)*abs(A(1,1))) || (abs(A(0,0)) > 2*abs(A(1,1))))\n  {\n    result(0,1) = A(0,1) * (logA11 - logA00) / y;\n  }\n  else\n  {\n    // computation in previous branch is inaccurate if A(1,1) \\approx A(0,0)\n    RealScalar unwindingNumber = ceil((imag(logA11 - logA00) - RealScalar(EIGEN_PI)) / RealScalar(2*EIGEN_PI));\n    result(0,1) = A(0,1) * (numext::log1p(y/A(0,0)) + Scalar(0,RealScalar(2*EIGEN_PI)*unwindingNumber)) / y;\n  }\n}\n\n/* \\brief Get suitable degree for Pade approximation. (specialized for RealScalar = float) */\ninline int matrix_log_get_pade_degree(float normTminusI)\n{\n  const float maxNormForPade[] = { 2.5111573934555054e-1 /* degree = 3 */ , 4.0535837411880493e-1,\n            5.3149729967117310e-1 };\n  const int minPadeDegree = matrix_log_min_pade_degree<float>::value;\n  const int maxPadeDegree = matrix_log_max_pade_degree<float>::value;\n  int degree = minPadeDegree;\n  for (; degree <= maxPadeDegree; ++degree) \n    if (normTminusI <= maxNormForPade[degree - minPadeDegree])\n      break;\n  return degree;\n}\n\n/* \\brief Get suitable degree for Pade approximation. (specialized for RealScalar = double) */\ninline int matrix_log_get_pade_degree(double normTminusI)\n{\n  const double maxNormForPade[] = { 1.6206284795015624e-2 /* degree = 3 */ , 5.3873532631381171e-2,\n            1.1352802267628681e-1, 1.8662860613541288e-1, 2.642960831111435e-1 };\n  const int minPadeDegree = matrix_log_min_pade_degree<double>::value;\n  const int maxPadeDegree = matrix_log_max_pade_degree<double>::value;\n  int degree = minPadeDegree;\n  for (; degree <= maxPadeDegree; ++degree)\n    if (normTminusI <= maxNormForPade[degree - minPadeDegree])\n      break;\n  return degree;\n}\n\n/* \\brief Get suitable degree for Pade approximation. (specialized for RealScalar = long double) */\ninline int matrix_log_get_pade_degree(long double normTminusI)\n{\n#if   LDBL_MANT_DIG == 53         // double precision\n  const long double maxNormForPade[] = { 1.6206284795015624e-2L /* degree = 3 */ , 5.3873532631381171e-2L,\n            1.1352802267628681e-1L, 1.8662860613541288e-1L, 2.642960831111435e-1L };\n#elif LDBL_MANT_DIG <= 64         // extended precision\n  const long double maxNormForPade[] = { 5.48256690357782863103e-3L /* degree = 3 */, 2.34559162387971167321e-2L,\n            5.84603923897347449857e-2L, 1.08486423756725170223e-1L, 1.68385767881294446649e-1L,\n            2.32777776523703892094e-1L };\n#elif LDBL_MANT_DIG <= 106        // double-double\n  const long double maxNormForPade[] = { 8.58970550342939562202529664318890e-5L /* degree = 3 */,\n            9.34074328446359654039446552677759e-4L, 4.26117194647672175773064114582860e-3L,\n            1.21546224740281848743149666560464e-2L, 2.61100544998339436713088248557444e-2L,\n            4.66170074627052749243018566390567e-2L, 7.32585144444135027565872014932387e-2L,\n            1.05026503471351080481093652651105e-1L };\n#else                             // quadruple precision\n  const long double maxNormForPade[] = { 4.7419931187193005048501568167858103e-5L /* degree = 3 */,\n            5.8853168473544560470387769480192666e-4L, 2.9216120366601315391789493628113520e-3L,\n            8.8415758124319434347116734705174308e-3L, 1.9850836029449446668518049562565291e-2L,\n            3.6688019729653446926585242192447447e-2L, 5.9290962294020186998954055264528393e-2L,\n            8.6998436081634343903250580992127677e-2L, 1.1880960220216759245467951592883642e-1L };\n#endif\n  const int minPadeDegree = matrix_log_min_pade_degree<long double>::value;\n  const int maxPadeDegree = matrix_log_max_pade_degree<long double>::value;\n  int degree = minPadeDegree;\n  for (; degree <= maxPadeDegree; ++degree)\n    if (normTminusI <= maxNormForPade[degree - minPadeDegree])\n      break;\n  return degree;\n}\n\n/* \\brief Compute Pade approximation to matrix logarithm */\ntemplate <typename MatrixType>\nvoid matrix_log_compute_pade(MatrixType& result, const MatrixType& T, int degree)\n{\n  typedef typename NumTraits<typename MatrixType::Scalar>::Real RealScalar;\n  const int minPadeDegree = 3;\n  const int maxPadeDegree = 11;\n  assert(degree >= minPadeDegree && degree <= maxPadeDegree);\n  // FIXME this creates float-conversion-warnings if these are enabled.\n  // Either manually convert each value, or disable the warning locally\n  const RealScalar nodes[][maxPadeDegree] = { \n    { 0.1127016653792583114820734600217600L, 0.5000000000000000000000000000000000L,  // degree 3\n      0.8872983346207416885179265399782400L }, \n    { 0.0694318442029737123880267555535953L, 0.3300094782075718675986671204483777L,  // degree 4\n      0.6699905217924281324013328795516223L, 0.9305681557970262876119732444464048L },\n    { 0.0469100770306680036011865608503035L, 0.2307653449471584544818427896498956L,  // degree 5\n      0.5000000000000000000000000000000000L, 0.7692346550528415455181572103501044L,\n      0.9530899229693319963988134391496965L },\n    { 0.0337652428984239860938492227530027L, 0.1693953067668677431693002024900473L,  // degree 6\n      0.3806904069584015456847491391596440L, 0.6193095930415984543152508608403560L,\n      0.8306046932331322568306997975099527L, 0.9662347571015760139061507772469973L },\n    { 0.0254460438286207377369051579760744L, 0.1292344072003027800680676133596058L,  // degree 7\n      0.2970774243113014165466967939615193L, 0.5000000000000000000000000000000000L,\n      0.7029225756886985834533032060384807L, 0.8707655927996972199319323866403942L,\n      0.9745539561713792622630948420239256L },\n    { 0.0198550717512318841582195657152635L, 0.1016667612931866302042230317620848L,  // degree 8\n      0.2372337950418355070911304754053768L, 0.4082826787521750975302619288199080L,\n      0.5917173212478249024697380711800920L, 0.7627662049581644929088695245946232L,\n      0.8983332387068133697957769682379152L, 0.9801449282487681158417804342847365L },\n    { 0.0159198802461869550822118985481636L, 0.0819844463366821028502851059651326L,  // degree 9\n      0.1933142836497048013456489803292629L, 0.3378732882980955354807309926783317L,\n      0.5000000000000000000000000000000000L, 0.6621267117019044645192690073216683L,\n      0.8066857163502951986543510196707371L, 0.9180155536633178971497148940348674L,\n      0.9840801197538130449177881014518364L },\n    { 0.0130467357414141399610179939577740L, 0.0674683166555077446339516557882535L,  // degree 10\n      0.1602952158504877968828363174425632L, 0.2833023029353764046003670284171079L,\n      0.4255628305091843945575869994351400L, 0.5744371694908156054424130005648600L,\n      0.7166976970646235953996329715828921L, 0.8397047841495122031171636825574368L,\n      0.9325316833444922553660483442117465L, 0.9869532642585858600389820060422260L },\n    { 0.0108856709269715035980309994385713L, 0.0564687001159523504624211153480364L,  // degree 11\n      0.1349239972129753379532918739844233L, 0.2404519353965940920371371652706952L,\n      0.3652284220238275138342340072995692L, 0.5000000000000000000000000000000000L,\n      0.6347715779761724861657659927004308L, 0.7595480646034059079628628347293048L,\n      0.8650760027870246620467081260155767L, 0.9435312998840476495375788846519636L,\n      0.9891143290730284964019690005614287L } };\n\n  const RealScalar weights[][maxPadeDegree] = { \n    { 0.2777777777777777777777777777777778L, 0.4444444444444444444444444444444444L,  // degree 3\n      0.2777777777777777777777777777777778L },\n    { 0.1739274225687269286865319746109997L, 0.3260725774312730713134680253890003L,  // degree 4\n      0.3260725774312730713134680253890003L, 0.1739274225687269286865319746109997L },\n    { 0.1184634425280945437571320203599587L, 0.2393143352496832340206457574178191L,  // degree 5\n      0.2844444444444444444444444444444444L, 0.2393143352496832340206457574178191L,\n      0.1184634425280945437571320203599587L },\n    { 0.0856622461895851725201480710863665L, 0.1803807865240693037849167569188581L,  // degree 6\n      0.2339569672863455236949351719947755L, 0.2339569672863455236949351719947755L,\n      0.1803807865240693037849167569188581L, 0.0856622461895851725201480710863665L },\n    { 0.0647424830844348466353057163395410L, 0.1398526957446383339507338857118898L,  // degree 7\n      0.1909150252525594724751848877444876L, 0.2089795918367346938775510204081633L,\n      0.1909150252525594724751848877444876L, 0.1398526957446383339507338857118898L,\n      0.0647424830844348466353057163395410L },\n    { 0.0506142681451881295762656771549811L, 0.1111905172266872352721779972131204L,  // degree 8\n      0.1568533229389436436689811009933007L, 0.1813418916891809914825752246385978L,\n      0.1813418916891809914825752246385978L, 0.1568533229389436436689811009933007L,\n      0.1111905172266872352721779972131204L, 0.0506142681451881295762656771549811L },\n    { 0.0406371941807872059859460790552618L, 0.0903240803474287020292360156214564L,  // degree 9\n      0.1303053482014677311593714347093164L, 0.1561735385200014200343152032922218L,\n      0.1651196775006298815822625346434870L, 0.1561735385200014200343152032922218L,\n      0.1303053482014677311593714347093164L, 0.0903240803474287020292360156214564L,\n      0.0406371941807872059859460790552618L },\n    { 0.0333356721543440687967844049466659L, 0.0747256745752902965728881698288487L,  // degree 10\n      0.1095431812579910219977674671140816L, 0.1346333596549981775456134607847347L,\n      0.1477621123573764350869464973256692L, 0.1477621123573764350869464973256692L,\n      0.1346333596549981775456134607847347L, 0.1095431812579910219977674671140816L,\n      0.0747256745752902965728881698288487L, 0.0333356721543440687967844049466659L },\n    { 0.0278342835580868332413768602212743L, 0.0627901847324523123173471496119701L,  // degree 11\n      0.0931451054638671257130488207158280L, 0.1165968822959952399592618524215876L,\n      0.1314022722551233310903444349452546L, 0.1364625433889503153572417641681711L,\n      0.1314022722551233310903444349452546L, 0.1165968822959952399592618524215876L,\n      0.0931451054638671257130488207158280L, 0.0627901847324523123173471496119701L,\n      0.0278342835580868332413768602212743L } };\n\n  MatrixType TminusI = T - MatrixType::Identity(T.rows(), T.rows());\n  result.setZero(T.rows(), T.rows());\n  for (int k = 0; k < degree; ++k) {\n    RealScalar weight = weights[degree-minPadeDegree][k];\n    RealScalar node = nodes[degree-minPadeDegree][k];\n    result += weight * (MatrixType::Identity(T.rows(), T.rows()) + node * TminusI)\n                       .template triangularView<Upper>().solve(TminusI);\n  }\n} \n\n/** \\brief Compute logarithm of triangular matrices with size > 2. \n  * \\details This uses a inverse scale-and-square algorithm. */\ntemplate <typename MatrixType>\nvoid matrix_log_compute_big(const MatrixType& A, MatrixType& result)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  using std::pow;\n\n  int numberOfSquareRoots = 0;\n  int numberOfExtraSquareRoots = 0;\n  int degree;\n  MatrixType T = A, sqrtT;\n\n  const int maxPadeDegree = matrix_log_max_pade_degree<Scalar>::value;\n  const RealScalar maxNormForPade = RealScalar(\n                                    maxPadeDegree<= 5? 5.3149729967117310e-1L:                    // single precision\n                                    maxPadeDegree<= 7? 2.6429608311114350e-1L:                    // double precision\n                                    maxPadeDegree<= 8? 2.32777776523703892094e-1L:                // extended precision\n                                    maxPadeDegree<=10? 1.05026503471351080481093652651105e-1L:    // double-double\n                                                       1.1880960220216759245467951592883642e-1L); // quadruple precision\n\n  while (true) {\n    RealScalar normTminusI = (T - MatrixType::Identity(T.rows(), T.rows())).cwiseAbs().colwise().sum().maxCoeff();\n    if (normTminusI < maxNormForPade) {\n      degree = matrix_log_get_pade_degree(normTminusI);\n      int degree2 = matrix_log_get_pade_degree(normTminusI / RealScalar(2));\n      if ((degree - degree2 <= 1) || (numberOfExtraSquareRoots == 1)) \n        break;\n      ++numberOfExtraSquareRoots;\n    }\n    matrix_sqrt_triangular(T, sqrtT);\n    T = sqrtT.template triangularView<Upper>();\n    ++numberOfSquareRoots;\n  }\n\n  matrix_log_compute_pade(result, T, degree);\n  result *= pow(RealScalar(2), RealScalar(numberOfSquareRoots)); // TODO replace by bitshift if possible\n}\n\n/** \\ingroup MatrixFunctions_Module\n  * \\class MatrixLogarithmAtomic\n  * \\brief Helper class for computing matrix logarithm of atomic matrices.\n  *\n  * Here, an atomic matrix is a triangular matrix whose diagonal entries are close to each other.\n  *\n  * \\sa class MatrixFunctionAtomic, MatrixBase::log()\n  */\ntemplate <typename MatrixType>\nclass MatrixLogarithmAtomic\n{\npublic:\n  /** \\brief Compute matrix logarithm of atomic matrix\n    * \\param[in]  A  argument of matrix logarithm, should be upper triangular and atomic\n    * \\returns  The logarithm of \\p A.\n    */\n  MatrixType compute(const MatrixType& A);\n};\n\ntemplate <typename MatrixType>\nMatrixType MatrixLogarithmAtomic<MatrixType>::compute(const MatrixType& A)\n{\n  using std::log;\n  MatrixType result(A.rows(), A.rows());\n  if (A.rows() == 1)\n    result(0,0) = log(A(0,0));\n  else if (A.rows() == 2)\n    matrix_log_compute_2x2(A, result);\n  else\n    matrix_log_compute_big(A, result);\n  return result;\n}\n\n} // end of namespace internal\n\n/** \\ingroup MatrixFunctions_Module\n  *\n  * \\brief Proxy for the matrix logarithm of some matrix (expression).\n  *\n  * \\tparam Derived  Type of the argument to the matrix function.\n  *\n  * This class holds the argument to the matrix function until it is\n  * assigned or evaluated for some other reason (so the argument\n  * should not be changed in the meantime). It is the return type of\n  * MatrixBase::log() and most of the time this is the only way it\n  * is used.\n  */\ntemplate<typename Derived> class MatrixLogarithmReturnValue\n: public ReturnByValue<MatrixLogarithmReturnValue<Derived> >\n{\npublic:\n  typedef typename Derived::Scalar Scalar;\n  typedef typename Derived::Index Index;\n\nprotected:\n  typedef typename internal::ref_selector<Derived>::type DerivedNested;\n\npublic:\n\n  /** \\brief Constructor.\n    *\n    * \\param[in]  A  %Matrix (expression) forming the argument of the matrix logarithm.\n    */\n  explicit MatrixLogarithmReturnValue(const Derived& A) : m_A(A) { }\n  \n  /** \\brief Compute the matrix logarithm.\n    *\n    * \\param[out]  result  Logarithm of \\c A, where \\c A is as specified in the constructor.\n    */\n  template <typename ResultType>\n  inline void evalTo(ResultType& result) const\n  {\n    typedef typename internal::nested_eval<Derived, 10>::type DerivedEvalType;\n    typedef typename internal::remove_all<DerivedEvalType>::type DerivedEvalTypeClean;\n    typedef internal::traits<DerivedEvalTypeClean> Traits;\n    typedef std::complex<typename NumTraits<Scalar>::Real> ComplexScalar;\n    typedef Matrix<ComplexScalar, Dynamic, Dynamic, 0, Traits::RowsAtCompileTime, Traits::ColsAtCompileTime> DynMatrixType;\n    typedef internal::MatrixLogarithmAtomic<DynMatrixType> AtomicType;\n    AtomicType atomic;\n    \n    internal::matrix_function_compute<typename DerivedEvalTypeClean::PlainObject>::run(m_A, atomic, result);\n  }\n\n  Index rows() const { return m_A.rows(); }\n  Index cols() const { return m_A.cols(); }\n  \nprivate:\n  const DerivedNested m_A;\n};\n\nnamespace internal {\n  template<typename Derived>\n  struct traits<MatrixLogarithmReturnValue<Derived> >\n  {\n    typedef typename Derived::PlainObject ReturnType;\n  };\n}\n\n\n/********** MatrixBase method **********/\n\n\ntemplate <typename Derived>\nconst MatrixLogarithmReturnValue<Derived> MatrixBase<Derived>::log() const\n{\n  eigen_assert(rows() == cols());\n  return MatrixLogarithmReturnValue<Derived>(derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_MATRIX_LOGARITHM\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/MatrixFunctions/MatrixPower.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012, 2013 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MATRIX_POWER\n#define EIGEN_MATRIX_POWER\n\nnamespace Eigen {\n\ntemplate<typename MatrixType> class MatrixPower;\n\n/**\n * \\ingroup MatrixFunctions_Module\n *\n * \\brief Proxy for the matrix power of some matrix.\n *\n * \\tparam MatrixType  type of the base, a matrix.\n *\n * This class holds the arguments to the matrix power until it is\n * assigned or evaluated for some other reason (so the argument\n * should not be changed in the meantime). It is the return type of\n * MatrixPower::operator() and related functions and most of the\n * time this is the only way it is used.\n */\n/* TODO This class is only used by MatrixPower, so it should be nested\n * into MatrixPower, like MatrixPower::ReturnValue. However, my\n * compiler complained about unused template parameter in the\n * following declaration in namespace internal.\n *\n * template<typename MatrixType>\n * struct traits<MatrixPower<MatrixType>::ReturnValue>;\n */\ntemplate<typename MatrixType>\nclass MatrixPowerParenthesesReturnValue : public ReturnByValue< MatrixPowerParenthesesReturnValue<MatrixType> >\n{\n  public:\n    typedef typename MatrixType::RealScalar RealScalar;\n\n    /**\n     * \\brief Constructor.\n     *\n     * \\param[in] pow  %MatrixPower storing the base.\n     * \\param[in] p    scalar, the exponent of the matrix power.\n     */\n    MatrixPowerParenthesesReturnValue(MatrixPower<MatrixType>& pow, RealScalar p) : m_pow(pow), m_p(p)\n    { }\n\n    /**\n     * \\brief Compute the matrix power.\n     *\n     * \\param[out] result\n     */\n    template<typename ResultType>\n    inline void evalTo(ResultType& result) const\n    { m_pow.compute(result, m_p); }\n\n    Index rows() const { return m_pow.rows(); }\n    Index cols() const { return m_pow.cols(); }\n\n  private:\n    MatrixPower<MatrixType>& m_pow;\n    const RealScalar m_p;\n};\n\n/**\n * \\ingroup MatrixFunctions_Module\n *\n * \\brief Class for computing matrix powers.\n *\n * \\tparam MatrixType  type of the base, expected to be an instantiation\n * of the Matrix class template.\n *\n * This class is capable of computing triangular real/complex matrices\n * raised to a power in the interval \\f$ (-1, 1) \\f$.\n *\n * \\note Currently this class is only used by MatrixPower. One may\n * insist that this be nested into MatrixPower. This class is here to\n * facilitate future development of triangular matrix functions.\n */\ntemplate<typename MatrixType>\nclass MatrixPowerAtomic : internal::noncopyable\n{\n  private:\n    enum {\n      RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime\n    };\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef std::complex<RealScalar> ComplexScalar;\n    typedef Block<MatrixType,Dynamic,Dynamic> ResultType;\n\n    const MatrixType& m_A;\n    RealScalar m_p;\n\n    void computePade(int degree, const MatrixType& IminusT, ResultType& res) const;\n    void compute2x2(ResultType& res, RealScalar p) const;\n    void computeBig(ResultType& res) const;\n    static int getPadeDegree(float normIminusT);\n    static int getPadeDegree(double normIminusT);\n    static int getPadeDegree(long double normIminusT);\n    static ComplexScalar computeSuperDiag(const ComplexScalar&, const ComplexScalar&, RealScalar p);\n    static RealScalar computeSuperDiag(RealScalar, RealScalar, RealScalar p);\n\n  public:\n    /**\n     * \\brief Constructor.\n     *\n     * \\param[in] T  the base of the matrix power.\n     * \\param[in] p  the exponent of the matrix power, should be in\n     * \\f$ (-1, 1) \\f$.\n     *\n     * The class stores a reference to T, so it should not be changed\n     * (or destroyed) before evaluation. Only the upper triangular\n     * part of T is read.\n     */\n    MatrixPowerAtomic(const MatrixType& T, RealScalar p);\n    \n    /**\n     * \\brief Compute the matrix power.\n     *\n     * \\param[out] res  \\f$ A^p \\f$ where A and p are specified in the\n     * constructor.\n     */\n    void compute(ResultType& res) const;\n};\n\ntemplate<typename MatrixType>\nMatrixPowerAtomic<MatrixType>::MatrixPowerAtomic(const MatrixType& T, RealScalar p) :\n  m_A(T), m_p(p)\n{\n  eigen_assert(T.rows() == T.cols());\n  eigen_assert(p > -1 && p < 1);\n}\n\ntemplate<typename MatrixType>\nvoid MatrixPowerAtomic<MatrixType>::compute(ResultType& res) const\n{\n  using std::pow;\n  switch (m_A.rows()) {\n    case 0:\n      break;\n    case 1:\n      res(0,0) = pow(m_A(0,0), m_p);\n      break;\n    case 2:\n      compute2x2(res, m_p);\n      break;\n    default:\n      computeBig(res);\n  }\n}\n\ntemplate<typename MatrixType>\nvoid MatrixPowerAtomic<MatrixType>::computePade(int degree, const MatrixType& IminusT, ResultType& res) const\n{\n  int i = 2*degree;\n  res = (m_p-RealScalar(degree)) / RealScalar(2*i-2) * IminusT;\n\n  for (--i; i; --i) {\n    res = (MatrixType::Identity(IminusT.rows(), IminusT.cols()) + res).template triangularView<Upper>()\n\t.solve((i==1 ? -m_p : i&1 ? (-m_p-RealScalar(i/2))/RealScalar(2*i) : (m_p-RealScalar(i/2))/RealScalar(2*i-2)) * IminusT).eval();\n  }\n  res += MatrixType::Identity(IminusT.rows(), IminusT.cols());\n}\n\n// This function assumes that res has the correct size (see bug 614)\ntemplate<typename MatrixType>\nvoid MatrixPowerAtomic<MatrixType>::compute2x2(ResultType& res, RealScalar p) const\n{\n  using std::abs;\n  using std::pow;\n  res.coeffRef(0,0) = pow(m_A.coeff(0,0), p);\n\n  for (Index i=1; i < m_A.cols(); ++i) {\n    res.coeffRef(i,i) = pow(m_A.coeff(i,i), p);\n    if (m_A.coeff(i-1,i-1) == m_A.coeff(i,i))\n      res.coeffRef(i-1,i) = p * pow(m_A.coeff(i,i), p-1);\n    else if (2*abs(m_A.coeff(i-1,i-1)) < abs(m_A.coeff(i,i)) || 2*abs(m_A.coeff(i,i)) < abs(m_A.coeff(i-1,i-1)))\n      res.coeffRef(i-1,i) = (res.coeff(i,i)-res.coeff(i-1,i-1)) / (m_A.coeff(i,i)-m_A.coeff(i-1,i-1));\n    else\n      res.coeffRef(i-1,i) = computeSuperDiag(m_A.coeff(i,i), m_A.coeff(i-1,i-1), p);\n    res.coeffRef(i-1,i) *= m_A.coeff(i-1,i);\n  }\n}\n\ntemplate<typename MatrixType>\nvoid MatrixPowerAtomic<MatrixType>::computeBig(ResultType& res) const\n{\n  using std::ldexp;\n  const int digits = std::numeric_limits<RealScalar>::digits;\n  const RealScalar maxNormForPade = RealScalar(\n                                    digits <=  24? 4.3386528e-1L                            // single precision\n                                  : digits <=  53? 2.789358995219730e-1L                    // double precision\n                                  : digits <=  64? 2.4471944416607995472e-1L                // extended precision\n                                  : digits <= 106? 1.1016843812851143391275867258512e-1L    // double-double\n                                  :                9.134603732914548552537150753385375e-2L); // quadruple precision\n  MatrixType IminusT, sqrtT, T = m_A.template triangularView<Upper>();\n  RealScalar normIminusT;\n  int degree, degree2, numberOfSquareRoots = 0;\n  bool hasExtraSquareRoot = false;\n\n  for (Index i=0; i < m_A.cols(); ++i)\n    eigen_assert(m_A(i,i) != RealScalar(0));\n\n  while (true) {\n    IminusT = MatrixType::Identity(m_A.rows(), m_A.cols()) - T;\n    normIminusT = IminusT.cwiseAbs().colwise().sum().maxCoeff();\n    if (normIminusT < maxNormForPade) {\n      degree = getPadeDegree(normIminusT);\n      degree2 = getPadeDegree(normIminusT/2);\n      if (degree - degree2 <= 1 || hasExtraSquareRoot)\n\tbreak;\n      hasExtraSquareRoot = true;\n    }\n    matrix_sqrt_triangular(T, sqrtT);\n    T = sqrtT.template triangularView<Upper>();\n    ++numberOfSquareRoots;\n  }\n  computePade(degree, IminusT, res);\n\n  for (; numberOfSquareRoots; --numberOfSquareRoots) {\n    compute2x2(res, ldexp(m_p, -numberOfSquareRoots));\n    res = res.template triangularView<Upper>() * res;\n  }\n  compute2x2(res, m_p);\n}\n  \ntemplate<typename MatrixType>\ninline int MatrixPowerAtomic<MatrixType>::getPadeDegree(float normIminusT)\n{\n  const float maxNormForPade[] = { 2.8064004e-1f /* degree = 3 */ , 4.3386528e-1f };\n  int degree = 3;\n  for (; degree <= 4; ++degree)\n    if (normIminusT <= maxNormForPade[degree - 3])\n      break;\n  return degree;\n}\n\ntemplate<typename MatrixType>\ninline int MatrixPowerAtomic<MatrixType>::getPadeDegree(double normIminusT)\n{\n  const double maxNormForPade[] = { 1.884160592658218e-2 /* degree = 3 */ , 6.038881904059573e-2, 1.239917516308172e-1,\n      1.999045567181744e-1, 2.789358995219730e-1 };\n  int degree = 3;\n  for (; degree <= 7; ++degree)\n    if (normIminusT <= maxNormForPade[degree - 3])\n      break;\n  return degree;\n}\n\ntemplate<typename MatrixType>\ninline int MatrixPowerAtomic<MatrixType>::getPadeDegree(long double normIminusT)\n{\n#if   LDBL_MANT_DIG == 53\n  const int maxPadeDegree = 7;\n  const double maxNormForPade[] = { 1.884160592658218e-2L /* degree = 3 */ , 6.038881904059573e-2L, 1.239917516308172e-1L,\n      1.999045567181744e-1L, 2.789358995219730e-1L };\n#elif LDBL_MANT_DIG <= 64\n  const int maxPadeDegree = 8;\n  const long double maxNormForPade[] = { 6.3854693117491799460e-3L /* degree = 3 */ , 2.6394893435456973676e-2L,\n      6.4216043030404063729e-2L, 1.1701165502926694307e-1L, 1.7904284231268670284e-1L, 2.4471944416607995472e-1L };\n#elif LDBL_MANT_DIG <= 106\n  const int maxPadeDegree = 10;\n  const double maxNormForPade[] = { 1.0007161601787493236741409687186e-4L /* degree = 3 */ ,\n      1.0007161601787493236741409687186e-3L, 4.7069769360887572939882574746264e-3L, 1.3220386624169159689406653101695e-2L,\n      2.8063482381631737920612944054906e-2L, 4.9625993951953473052385361085058e-2L, 7.7367040706027886224557538328171e-2L,\n      1.1016843812851143391275867258512e-1L };\n#else\n  const int maxPadeDegree = 10;\n  const double maxNormForPade[] = { 5.524506147036624377378713555116378e-5L /* degree = 3 */ ,\n      6.640600568157479679823602193345995e-4L, 3.227716520106894279249709728084626e-3L,\n      9.619593944683432960546978734646284e-3L, 2.134595382433742403911124458161147e-2L,\n      3.908166513900489428442993794761185e-2L, 6.266780814639442865832535460550138e-2L,\n      9.134603732914548552537150753385375e-2L };\n#endif\n  int degree = 3;\n  for (; degree <= maxPadeDegree; ++degree)\n    if (normIminusT <= maxNormForPade[degree - 3])\n      break;\n  return degree;\n}\n\ntemplate<typename MatrixType>\ninline typename MatrixPowerAtomic<MatrixType>::ComplexScalar\nMatrixPowerAtomic<MatrixType>::computeSuperDiag(const ComplexScalar& curr, const ComplexScalar& prev, RealScalar p)\n{\n  using std::ceil;\n  using std::exp;\n  using std::log;\n  using std::sinh;\n\n  ComplexScalar logCurr = log(curr);\n  ComplexScalar logPrev = log(prev);\n  RealScalar unwindingNumber = ceil((numext::imag(logCurr - logPrev) - RealScalar(EIGEN_PI)) / RealScalar(2*EIGEN_PI));\n  ComplexScalar w = numext::log1p((curr-prev)/prev)/RealScalar(2) + ComplexScalar(0, RealScalar(EIGEN_PI)*unwindingNumber);\n  return RealScalar(2) * exp(RealScalar(0.5) * p * (logCurr + logPrev)) * sinh(p * w) / (curr - prev);\n}\n\ntemplate<typename MatrixType>\ninline typename MatrixPowerAtomic<MatrixType>::RealScalar\nMatrixPowerAtomic<MatrixType>::computeSuperDiag(RealScalar curr, RealScalar prev, RealScalar p)\n{\n  using std::exp;\n  using std::log;\n  using std::sinh;\n\n  RealScalar w = numext::log1p((curr-prev)/prev)/RealScalar(2);\n  return 2 * exp(p * (log(curr) + log(prev)) / 2) * sinh(p * w) / (curr - prev);\n}\n\n/**\n * \\ingroup MatrixFunctions_Module\n *\n * \\brief Class for computing matrix powers.\n *\n * \\tparam MatrixType  type of the base, expected to be an instantiation\n * of the Matrix class template.\n *\n * This class is capable of computing real/complex matrices raised to\n * an arbitrary real power. Meanwhile, it saves the result of Schur\n * decomposition if an non-integral power has even been calculated.\n * Therefore, if you want to compute multiple (>= 2) matrix powers\n * for the same matrix, using the class directly is more efficient than\n * calling MatrixBase::pow().\n *\n * Example:\n * \\include MatrixPower_optimal.cpp\n * Output: \\verbinclude MatrixPower_optimal.out\n */\ntemplate<typename MatrixType>\nclass MatrixPower : internal::noncopyable\n{\n  private:\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n\n  public:\n    /**\n     * \\brief Constructor.\n     *\n     * \\param[in] A  the base of the matrix power.\n     *\n     * The class stores a reference to A, so it should not be changed\n     * (or destroyed) before evaluation.\n     */\n    explicit MatrixPower(const MatrixType& A) :\n      m_A(A),\n      m_conditionNumber(0),\n      m_rank(A.cols()),\n      m_nulls(0)\n    { eigen_assert(A.rows() == A.cols()); }\n\n    /**\n     * \\brief Returns the matrix power.\n     *\n     * \\param[in] p  exponent, a real scalar.\n     * \\return The expression \\f$ A^p \\f$, where A is specified in the\n     * constructor.\n     */\n    const MatrixPowerParenthesesReturnValue<MatrixType> operator()(RealScalar p)\n    { return MatrixPowerParenthesesReturnValue<MatrixType>(*this, p); }\n\n    /**\n     * \\brief Compute the matrix power.\n     *\n     * \\param[in]  p    exponent, a real scalar.\n     * \\param[out] res  \\f$ A^p \\f$ where A is specified in the\n     * constructor.\n     */\n    template<typename ResultType>\n    void compute(ResultType& res, RealScalar p);\n    \n    Index rows() const { return m_A.rows(); }\n    Index cols() const { return m_A.cols(); }\n\n  private:\n    typedef std::complex<RealScalar> ComplexScalar;\n    typedef Matrix<ComplexScalar, Dynamic, Dynamic, 0,\n              MatrixType::RowsAtCompileTime, MatrixType::ColsAtCompileTime> ComplexMatrix;\n\n    /** \\brief Reference to the base of matrix power. */\n    typename MatrixType::Nested m_A;\n\n    /** \\brief Temporary storage. */\n    MatrixType m_tmp;\n\n    /** \\brief Store the result of Schur decomposition. */\n    ComplexMatrix m_T, m_U;\n    \n    /** \\brief Store fractional power of m_T. */\n    ComplexMatrix m_fT;\n\n    /**\n     * \\brief Condition number of m_A.\n     *\n     * It is initialized as 0 to avoid performing unnecessary Schur\n     * decomposition, which is the bottleneck.\n     */\n    RealScalar m_conditionNumber;\n\n    /** \\brief Rank of m_A. */\n    Index m_rank;\n    \n    /** \\brief Rank deficiency of m_A. */\n    Index m_nulls;\n\n    /**\n     * \\brief Split p into integral part and fractional part.\n     *\n     * \\param[in]  p        The exponent.\n     * \\param[out] p        The fractional part ranging in \\f$ (-1, 1) \\f$.\n     * \\param[out] intpart  The integral part.\n     *\n     * Only if the fractional part is nonzero, it calls initialize().\n     */\n    void split(RealScalar& p, RealScalar& intpart);\n\n    /** \\brief Perform Schur decomposition for fractional power. */\n    void initialize();\n\n    template<typename ResultType>\n    void computeIntPower(ResultType& res, RealScalar p);\n\n    template<typename ResultType>\n    void computeFracPower(ResultType& res, RealScalar p);\n\n    template<int Rows, int Cols, int Options, int MaxRows, int MaxCols>\n    static void revertSchur(\n        Matrix<ComplexScalar, Rows, Cols, Options, MaxRows, MaxCols>& res,\n        const ComplexMatrix& T,\n        const ComplexMatrix& U);\n\n    template<int Rows, int Cols, int Options, int MaxRows, int MaxCols>\n    static void revertSchur(\n        Matrix<RealScalar, Rows, Cols, Options, MaxRows, MaxCols>& res,\n        const ComplexMatrix& T,\n        const ComplexMatrix& U);\n};\n\ntemplate<typename MatrixType>\ntemplate<typename ResultType>\nvoid MatrixPower<MatrixType>::compute(ResultType& res, RealScalar p)\n{\n  using std::pow;\n  switch (cols()) {\n    case 0:\n      break;\n    case 1:\n      res(0,0) = pow(m_A.coeff(0,0), p);\n      break;\n    default:\n      RealScalar intpart;\n      split(p, intpart);\n\n      res = MatrixType::Identity(rows(), cols());\n      computeIntPower(res, intpart);\n      if (p) computeFracPower(res, p);\n  }\n}\n\ntemplate<typename MatrixType>\nvoid MatrixPower<MatrixType>::split(RealScalar& p, RealScalar& intpart)\n{\n  using std::floor;\n  using std::pow;\n\n  intpart = floor(p);\n  p -= intpart;\n\n  // Perform Schur decomposition if it is not yet performed and the power is\n  // not an integer.\n  if (!m_conditionNumber && p)\n    initialize();\n\n  // Choose the more stable of intpart = floor(p) and intpart = ceil(p).\n  if (p > RealScalar(0.5) && p > (1-p) * pow(m_conditionNumber, p)) {\n    --p;\n    ++intpart;\n  }\n}\n\ntemplate<typename MatrixType>\nvoid MatrixPower<MatrixType>::initialize()\n{\n  const ComplexSchur<MatrixType> schurOfA(m_A);\n  JacobiRotation<ComplexScalar> rot;\n  ComplexScalar eigenvalue;\n\n  m_fT.resizeLike(m_A);\n  m_T = schurOfA.matrixT();\n  m_U = schurOfA.matrixU();\n  m_conditionNumber = m_T.diagonal().array().abs().maxCoeff() / m_T.diagonal().array().abs().minCoeff();\n\n  // Move zero eigenvalues to the bottom right corner.\n  for (Index i = cols()-1; i>=0; --i) {\n    if (m_rank <= 2)\n      return;\n    if (m_T.coeff(i,i) == RealScalar(0)) {\n      for (Index j=i+1; j < m_rank; ++j) {\n        eigenvalue = m_T.coeff(j,j);\n        rot.makeGivens(m_T.coeff(j-1,j), eigenvalue);\n        m_T.applyOnTheRight(j-1, j, rot);\n        m_T.applyOnTheLeft(j-1, j, rot.adjoint());\n        m_T.coeffRef(j-1,j-1) = eigenvalue;\n        m_T.coeffRef(j,j) = RealScalar(0);\n        m_U.applyOnTheRight(j-1, j, rot);\n      }\n      --m_rank;\n    }\n  }\n\n  m_nulls = rows() - m_rank;\n  if (m_nulls) {\n    eigen_assert(m_T.bottomRightCorner(m_nulls, m_nulls).isZero()\n        && \"Base of matrix power should be invertible or with a semisimple zero eigenvalue.\");\n    m_fT.bottomRows(m_nulls).fill(RealScalar(0));\n  }\n}\n\ntemplate<typename MatrixType>\ntemplate<typename ResultType>\nvoid MatrixPower<MatrixType>::computeIntPower(ResultType& res, RealScalar p)\n{\n  using std::abs;\n  using std::fmod;\n  RealScalar pp = abs(p);\n\n  if (p<0) \n    m_tmp = m_A.inverse();\n  else     \n    m_tmp = m_A;\n\n  while (true) {\n    if (fmod(pp, 2) >= 1)\n      res = m_tmp * res;\n    pp /= 2;\n    if (pp < 1)\n      break;\n    m_tmp *= m_tmp;\n  }\n}\n\ntemplate<typename MatrixType>\ntemplate<typename ResultType>\nvoid MatrixPower<MatrixType>::computeFracPower(ResultType& res, RealScalar p)\n{\n  Block<ComplexMatrix,Dynamic,Dynamic> blockTp(m_fT, 0, 0, m_rank, m_rank);\n  eigen_assert(m_conditionNumber);\n  eigen_assert(m_rank + m_nulls == rows());\n\n  MatrixPowerAtomic<ComplexMatrix>(m_T.topLeftCorner(m_rank, m_rank), p).compute(blockTp);\n  if (m_nulls) {\n    m_fT.topRightCorner(m_rank, m_nulls) = m_T.topLeftCorner(m_rank, m_rank).template triangularView<Upper>()\n        .solve(blockTp * m_T.topRightCorner(m_rank, m_nulls));\n  }\n  revertSchur(m_tmp, m_fT, m_U);\n  res = m_tmp * res;\n}\n\ntemplate<typename MatrixType>\ntemplate<int Rows, int Cols, int Options, int MaxRows, int MaxCols>\ninline void MatrixPower<MatrixType>::revertSchur(\n    Matrix<ComplexScalar, Rows, Cols, Options, MaxRows, MaxCols>& res,\n    const ComplexMatrix& T,\n    const ComplexMatrix& U)\n{ res.noalias() = U * (T.template triangularView<Upper>() * U.adjoint()); }\n\ntemplate<typename MatrixType>\ntemplate<int Rows, int Cols, int Options, int MaxRows, int MaxCols>\ninline void MatrixPower<MatrixType>::revertSchur(\n    Matrix<RealScalar, Rows, Cols, Options, MaxRows, MaxCols>& res,\n    const ComplexMatrix& T,\n    const ComplexMatrix& U)\n{ res.noalias() = (U * (T.template triangularView<Upper>() * U.adjoint())).real(); }\n\n/**\n * \\ingroup MatrixFunctions_Module\n *\n * \\brief Proxy for the matrix power of some matrix (expression).\n *\n * \\tparam Derived  type of the base, a matrix (expression).\n *\n * This class holds the arguments to the matrix power until it is\n * assigned or evaluated for some other reason (so the argument\n * should not be changed in the meantime). It is the return type of\n * MatrixBase::pow() and related functions and most of the\n * time this is the only way it is used.\n */\ntemplate<typename Derived>\nclass MatrixPowerReturnValue : public ReturnByValue< MatrixPowerReturnValue<Derived> >\n{\n  public:\n    typedef typename Derived::PlainObject PlainObject;\n    typedef typename Derived::RealScalar RealScalar;\n\n    /**\n     * \\brief Constructor.\n     *\n     * \\param[in] A  %Matrix (expression), the base of the matrix power.\n     * \\param[in] p  real scalar, the exponent of the matrix power.\n     */\n    MatrixPowerReturnValue(const Derived& A, RealScalar p) : m_A(A), m_p(p)\n    { }\n\n    /**\n     * \\brief Compute the matrix power.\n     *\n     * \\param[out] result  \\f$ A^p \\f$ where \\p A and \\p p are as in the\n     * constructor.\n     */\n    template<typename ResultType>\n    inline void evalTo(ResultType& result) const\n    { MatrixPower<PlainObject>(m_A.eval()).compute(result, m_p); }\n\n    Index rows() const { return m_A.rows(); }\n    Index cols() const { return m_A.cols(); }\n\n  private:\n    const Derived& m_A;\n    const RealScalar m_p;\n};\n\n/**\n * \\ingroup MatrixFunctions_Module\n *\n * \\brief Proxy for the matrix power of some matrix (expression).\n *\n * \\tparam Derived  type of the base, a matrix (expression).\n *\n * This class holds the arguments to the matrix power until it is\n * assigned or evaluated for some other reason (so the argument\n * should not be changed in the meantime). It is the return type of\n * MatrixBase::pow() and related functions and most of the\n * time this is the only way it is used.\n */\ntemplate<typename Derived>\nclass MatrixComplexPowerReturnValue : public ReturnByValue< MatrixComplexPowerReturnValue<Derived> >\n{\n  public:\n    typedef typename Derived::PlainObject PlainObject;\n    typedef typename std::complex<typename Derived::RealScalar> ComplexScalar;\n\n    /**\n     * \\brief Constructor.\n     *\n     * \\param[in] A  %Matrix (expression), the base of the matrix power.\n     * \\param[in] p  complex scalar, the exponent of the matrix power.\n     */\n    MatrixComplexPowerReturnValue(const Derived& A, const ComplexScalar& p) : m_A(A), m_p(p)\n    { }\n\n    /**\n     * \\brief Compute the matrix power.\n     *\n     * Because \\p p is complex, \\f$ A^p \\f$ is simply evaluated as \\f$\n     * \\exp(p \\log(A)) \\f$.\n     *\n     * \\param[out] result  \\f$ A^p \\f$ where \\p A and \\p p are as in the\n     * constructor.\n     */\n    template<typename ResultType>\n    inline void evalTo(ResultType& result) const\n    { result = (m_p * m_A.log()).exp(); }\n\n    Index rows() const { return m_A.rows(); }\n    Index cols() const { return m_A.cols(); }\n\n  private:\n    const Derived& m_A;\n    const ComplexScalar m_p;\n};\n\nnamespace internal {\n\ntemplate<typename MatrixPowerType>\nstruct traits< MatrixPowerParenthesesReturnValue<MatrixPowerType> >\n{ typedef typename MatrixPowerType::PlainObject ReturnType; };\n\ntemplate<typename Derived>\nstruct traits< MatrixPowerReturnValue<Derived> >\n{ typedef typename Derived::PlainObject ReturnType; };\n\ntemplate<typename Derived>\nstruct traits< MatrixComplexPowerReturnValue<Derived> >\n{ typedef typename Derived::PlainObject ReturnType; };\n\n}\n\ntemplate<typename Derived>\nconst MatrixPowerReturnValue<Derived> MatrixBase<Derived>::pow(const RealScalar& p) const\n{ return MatrixPowerReturnValue<Derived>(derived(), p); }\n\ntemplate<typename Derived>\nconst MatrixComplexPowerReturnValue<Derived> MatrixBase<Derived>::pow(const std::complex<RealScalar>& p) const\n{ return MatrixComplexPowerReturnValue<Derived>(derived(), p); }\n\n} // namespace Eigen\n\n#endif // EIGEN_MATRIX_POWER\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/MatrixFunctions/MatrixSquareRoot.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011, 2013 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MATRIX_SQUARE_ROOT\n#define EIGEN_MATRIX_SQUARE_ROOT\n\nnamespace Eigen { \n\nnamespace internal {\n\n// pre:  T.block(i,i,2,2) has complex conjugate eigenvalues\n// post: sqrtT.block(i,i,2,2) is square root of T.block(i,i,2,2)\ntemplate <typename MatrixType, typename ResultType>\nvoid matrix_sqrt_quasi_triangular_2x2_diagonal_block(const MatrixType& T, Index i, ResultType& sqrtT)\n{\n  // TODO: This case (2-by-2 blocks with complex conjugate eigenvalues) is probably hidden somewhere\n  //       in EigenSolver. If we expose it, we could call it directly from here.\n  typedef typename traits<MatrixType>::Scalar Scalar;\n  Matrix<Scalar,2,2> block = T.template block<2,2>(i,i);\n  EigenSolver<Matrix<Scalar,2,2> > es(block);\n  sqrtT.template block<2,2>(i,i)\n    = (es.eigenvectors() * es.eigenvalues().cwiseSqrt().asDiagonal() * es.eigenvectors().inverse()).real();\n}\n\n// pre:  block structure of T is such that (i,j) is a 1x1 block,\n//       all blocks of sqrtT to left of and below (i,j) are correct\n// post: sqrtT(i,j) has the correct value\ntemplate <typename MatrixType, typename ResultType>\nvoid matrix_sqrt_quasi_triangular_1x1_off_diagonal_block(const MatrixType& T, Index i, Index j, ResultType& sqrtT)\n{\n  typedef typename traits<MatrixType>::Scalar Scalar;\n  Scalar tmp = (sqrtT.row(i).segment(i+1,j-i-1) * sqrtT.col(j).segment(i+1,j-i-1)).value();\n  sqrtT.coeffRef(i,j) = (T.coeff(i,j) - tmp) / (sqrtT.coeff(i,i) + sqrtT.coeff(j,j));\n}\n\n// similar to compute1x1offDiagonalBlock()\ntemplate <typename MatrixType, typename ResultType>\nvoid matrix_sqrt_quasi_triangular_1x2_off_diagonal_block(const MatrixType& T, Index i, Index j, ResultType& sqrtT)\n{\n  typedef typename traits<MatrixType>::Scalar Scalar;\n  Matrix<Scalar,1,2> rhs = T.template block<1,2>(i,j);\n  if (j-i > 1)\n    rhs -= sqrtT.block(i, i+1, 1, j-i-1) * sqrtT.block(i+1, j, j-i-1, 2);\n  Matrix<Scalar,2,2> A = sqrtT.coeff(i,i) * Matrix<Scalar,2,2>::Identity();\n  A += sqrtT.template block<2,2>(j,j).transpose();\n  sqrtT.template block<1,2>(i,j).transpose() = A.fullPivLu().solve(rhs.transpose());\n}\n\n// similar to compute1x1offDiagonalBlock()\ntemplate <typename MatrixType, typename ResultType>\nvoid matrix_sqrt_quasi_triangular_2x1_off_diagonal_block(const MatrixType& T, Index i, Index j, ResultType& sqrtT)\n{\n  typedef typename traits<MatrixType>::Scalar Scalar;\n  Matrix<Scalar,2,1> rhs = T.template block<2,1>(i,j);\n  if (j-i > 2)\n    rhs -= sqrtT.block(i, i+2, 2, j-i-2) * sqrtT.block(i+2, j, j-i-2, 1);\n  Matrix<Scalar,2,2> A = sqrtT.coeff(j,j) * Matrix<Scalar,2,2>::Identity();\n  A += sqrtT.template block<2,2>(i,i);\n  sqrtT.template block<2,1>(i,j) = A.fullPivLu().solve(rhs);\n}\n\n// solves the equation A X + X B = C where all matrices are 2-by-2\ntemplate <typename MatrixType>\nvoid matrix_sqrt_quasi_triangular_solve_auxiliary_equation(MatrixType& X, const MatrixType& A, const MatrixType& B, const MatrixType& C)\n{\n  typedef typename traits<MatrixType>::Scalar Scalar;\n  Matrix<Scalar,4,4> coeffMatrix = Matrix<Scalar,4,4>::Zero();\n  coeffMatrix.coeffRef(0,0) = A.coeff(0,0) + B.coeff(0,0);\n  coeffMatrix.coeffRef(1,1) = A.coeff(0,0) + B.coeff(1,1);\n  coeffMatrix.coeffRef(2,2) = A.coeff(1,1) + B.coeff(0,0);\n  coeffMatrix.coeffRef(3,3) = A.coeff(1,1) + B.coeff(1,1);\n  coeffMatrix.coeffRef(0,1) = B.coeff(1,0);\n  coeffMatrix.coeffRef(0,2) = A.coeff(0,1);\n  coeffMatrix.coeffRef(1,0) = B.coeff(0,1);\n  coeffMatrix.coeffRef(1,3) = A.coeff(0,1);\n  coeffMatrix.coeffRef(2,0) = A.coeff(1,0);\n  coeffMatrix.coeffRef(2,3) = B.coeff(1,0);\n  coeffMatrix.coeffRef(3,1) = A.coeff(1,0);\n  coeffMatrix.coeffRef(3,2) = B.coeff(0,1);\n\n  Matrix<Scalar,4,1> rhs;\n  rhs.coeffRef(0) = C.coeff(0,0);\n  rhs.coeffRef(1) = C.coeff(0,1);\n  rhs.coeffRef(2) = C.coeff(1,0);\n  rhs.coeffRef(3) = C.coeff(1,1);\n\n  Matrix<Scalar,4,1> result;\n  result = coeffMatrix.fullPivLu().solve(rhs);\n\n  X.coeffRef(0,0) = result.coeff(0);\n  X.coeffRef(0,1) = result.coeff(1);\n  X.coeffRef(1,0) = result.coeff(2);\n  X.coeffRef(1,1) = result.coeff(3);\n}\n\n// similar to compute1x1offDiagonalBlock()\ntemplate <typename MatrixType, typename ResultType>\nvoid matrix_sqrt_quasi_triangular_2x2_off_diagonal_block(const MatrixType& T, Index i, Index j, ResultType& sqrtT)\n{\n  typedef typename traits<MatrixType>::Scalar Scalar;\n  Matrix<Scalar,2,2> A = sqrtT.template block<2,2>(i,i);\n  Matrix<Scalar,2,2> B = sqrtT.template block<2,2>(j,j);\n  Matrix<Scalar,2,2> C = T.template block<2,2>(i,j);\n  if (j-i > 2)\n    C -= sqrtT.block(i, i+2, 2, j-i-2) * sqrtT.block(i+2, j, j-i-2, 2);\n  Matrix<Scalar,2,2> X;\n  matrix_sqrt_quasi_triangular_solve_auxiliary_equation(X, A, B, C);\n  sqrtT.template block<2,2>(i,j) = X;\n}\n\n// pre:  T is quasi-upper-triangular and sqrtT is a zero matrix of the same size\n// post: the diagonal blocks of sqrtT are the square roots of the diagonal blocks of T\ntemplate <typename MatrixType, typename ResultType>\nvoid matrix_sqrt_quasi_triangular_diagonal(const MatrixType& T, ResultType& sqrtT)\n{\n  using std::sqrt;\n  const Index size = T.rows();\n  for (Index i = 0; i < size; i++) {\n    if (i == size - 1 || T.coeff(i+1, i) == 0) {\n      eigen_assert(T(i,i) >= 0);\n      sqrtT.coeffRef(i,i) = sqrt(T.coeff(i,i));\n    }\n    else {\n      matrix_sqrt_quasi_triangular_2x2_diagonal_block(T, i, sqrtT);\n      ++i;\n    }\n  }\n}\n\n// pre:  T is quasi-upper-triangular and diagonal blocks of sqrtT are square root of diagonal blocks of T.\n// post: sqrtT is the square root of T.\ntemplate <typename MatrixType, typename ResultType>\nvoid matrix_sqrt_quasi_triangular_off_diagonal(const MatrixType& T, ResultType& sqrtT)\n{\n  const Index size = T.rows();\n  for (Index j = 1; j < size; j++) {\n      if (T.coeff(j, j-1) != 0)  // if T(j-1:j, j-1:j) is a 2-by-2 block\n\tcontinue;\n    for (Index i = j-1; i >= 0; i--) {\n      if (i > 0 && T.coeff(i, i-1) != 0)  // if T(i-1:i, i-1:i) is a 2-by-2 block\n\tcontinue;\n      bool iBlockIs2x2 = (i < size - 1) && (T.coeff(i+1, i) != 0);\n      bool jBlockIs2x2 = (j < size - 1) && (T.coeff(j+1, j) != 0);\n      if (iBlockIs2x2 && jBlockIs2x2) \n        matrix_sqrt_quasi_triangular_2x2_off_diagonal_block(T, i, j, sqrtT);\n      else if (iBlockIs2x2 && !jBlockIs2x2) \n        matrix_sqrt_quasi_triangular_2x1_off_diagonal_block(T, i, j, sqrtT);\n      else if (!iBlockIs2x2 && jBlockIs2x2) \n        matrix_sqrt_quasi_triangular_1x2_off_diagonal_block(T, i, j, sqrtT);\n      else if (!iBlockIs2x2 && !jBlockIs2x2) \n        matrix_sqrt_quasi_triangular_1x1_off_diagonal_block(T, i, j, sqrtT);\n    }\n  }\n}\n\n} // end of namespace internal\n\n/** \\ingroup MatrixFunctions_Module\n  * \\brief Compute matrix square root of quasi-triangular matrix.\n  *\n  * \\tparam  MatrixType  type of \\p arg, the argument of matrix square root,\n  *                      expected to be an instantiation of the Matrix class template.\n  * \\tparam  ResultType  type of \\p result, where result is to be stored.\n  * \\param[in]  arg      argument of matrix square root.\n  * \\param[out] result   matrix square root of upper Hessenberg part of \\p arg.\n  *\n  * This function computes the square root of the upper quasi-triangular matrix stored in the upper\n  * Hessenberg part of \\p arg.  Only the upper Hessenberg part of \\p result is updated, the rest is\n  * not touched.  See MatrixBase::sqrt() for details on how this computation is implemented.\n  *\n  * \\sa MatrixSquareRoot, MatrixSquareRootQuasiTriangular\n  */\ntemplate <typename MatrixType, typename ResultType> \nvoid matrix_sqrt_quasi_triangular(const MatrixType &arg, ResultType &result)\n{\n  eigen_assert(arg.rows() == arg.cols());\n  result.resize(arg.rows(), arg.cols());\n  internal::matrix_sqrt_quasi_triangular_diagonal(arg, result);\n  internal::matrix_sqrt_quasi_triangular_off_diagonal(arg, result);\n}\n\n\n/** \\ingroup MatrixFunctions_Module\n  * \\brief Compute matrix square root of triangular matrix.\n  *\n  * \\tparam  MatrixType  type of \\p arg, the argument of matrix square root,\n  *                      expected to be an instantiation of the Matrix class template.\n  * \\tparam  ResultType  type of \\p result, where result is to be stored.\n  * \\param[in]  arg      argument of matrix square root.\n  * \\param[out] result   matrix square root of upper triangular part of \\p arg.\n  *\n  * Only the upper triangular part (including the diagonal) of \\p result is updated, the rest is not\n  * touched.  See MatrixBase::sqrt() for details on how this computation is implemented.\n  *\n  * \\sa MatrixSquareRoot, MatrixSquareRootQuasiTriangular\n  */\ntemplate <typename MatrixType, typename ResultType> \nvoid matrix_sqrt_triangular(const MatrixType &arg, ResultType &result)\n{\n  using std::sqrt;\n  typedef typename MatrixType::Scalar Scalar;\n\n  eigen_assert(arg.rows() == arg.cols());\n\n  // Compute square root of arg and store it in upper triangular part of result\n  // This uses that the square root of triangular matrices can be computed directly.\n  result.resize(arg.rows(), arg.cols());\n  for (Index i = 0; i < arg.rows(); i++) {\n    result.coeffRef(i,i) = sqrt(arg.coeff(i,i));\n  }\n  for (Index j = 1; j < arg.cols(); j++) {\n    for (Index i = j-1; i >= 0; i--) {\n      // if i = j-1, then segment has length 0 so tmp = 0\n      Scalar tmp = (result.row(i).segment(i+1,j-i-1) * result.col(j).segment(i+1,j-i-1)).value();\n      // denominator may be zero if original matrix is singular\n      result.coeffRef(i,j) = (arg.coeff(i,j) - tmp) / (result.coeff(i,i) + result.coeff(j,j));\n    }\n  }\n}\n\n\nnamespace internal {\n\n/** \\ingroup MatrixFunctions_Module\n  * \\brief Helper struct for computing matrix square roots of general matrices.\n  * \\tparam  MatrixType  type of the argument of the matrix square root,\n  *                      expected to be an instantiation of the Matrix class template.\n  *\n  * \\sa MatrixSquareRootTriangular, MatrixSquareRootQuasiTriangular, MatrixBase::sqrt()\n  */\ntemplate <typename MatrixType, int IsComplex = NumTraits<typename internal::traits<MatrixType>::Scalar>::IsComplex>\nstruct matrix_sqrt_compute\n{\n  /** \\brief Compute the matrix square root\n    *\n    * \\param[in]  arg     matrix whose square root is to be computed.\n    * \\param[out] result  square root of \\p arg.\n    *\n    * See MatrixBase::sqrt() for details on how this computation is implemented.\n    */\n  template <typename ResultType> static void run(const MatrixType &arg, ResultType &result);    \n};\n\n\n// ********** Partial specialization for real matrices **********\n\ntemplate <typename MatrixType>\nstruct matrix_sqrt_compute<MatrixType, 0>\n{\n  typedef typename MatrixType::PlainObject PlainType;\n  template <typename ResultType>\n  static void run(const MatrixType &arg, ResultType &result)\n  {\n    eigen_assert(arg.rows() == arg.cols());\n\n    // Compute Schur decomposition of arg\n    const RealSchur<PlainType> schurOfA(arg);\n    const PlainType& T = schurOfA.matrixT();\n    const PlainType& U = schurOfA.matrixU();\n    \n    // Compute square root of T\n    PlainType sqrtT = PlainType::Zero(arg.rows(), arg.cols());\n    matrix_sqrt_quasi_triangular(T, sqrtT);\n    \n    // Compute square root of arg\n    result = U * sqrtT * U.adjoint();\n  }\n};\n\n\n// ********** Partial specialization for complex matrices **********\n\ntemplate <typename MatrixType>\nstruct matrix_sqrt_compute<MatrixType, 1>\n{\n  typedef typename MatrixType::PlainObject PlainType;\n  template <typename ResultType>\n  static void run(const MatrixType &arg, ResultType &result)\n  {\n    eigen_assert(arg.rows() == arg.cols());\n\n    // Compute Schur decomposition of arg\n    const ComplexSchur<PlainType> schurOfA(arg);\n    const PlainType& T = schurOfA.matrixT();\n    const PlainType& U = schurOfA.matrixU();\n    \n    // Compute square root of T\n    PlainType sqrtT;\n    matrix_sqrt_triangular(T, sqrtT);\n    \n    // Compute square root of arg\n    result = U * (sqrtT.template triangularView<Upper>() * U.adjoint());\n  }\n};\n\n} // end namespace internal\n\n/** \\ingroup MatrixFunctions_Module\n  *\n  * \\brief Proxy for the matrix square root of some matrix (expression).\n  *\n  * \\tparam Derived  Type of the argument to the matrix square root.\n  *\n  * This class holds the argument to the matrix square root until it\n  * is assigned or evaluated for some other reason (so the argument\n  * should not be changed in the meantime). It is the return type of\n  * MatrixBase::sqrt() and most of the time this is the only way it is\n  * used.\n  */\ntemplate<typename Derived> class MatrixSquareRootReturnValue\n: public ReturnByValue<MatrixSquareRootReturnValue<Derived> >\n{\n  protected:\n    typedef typename internal::ref_selector<Derived>::type DerivedNested;\n\n  public:\n    /** \\brief Constructor.\n      *\n      * \\param[in]  src  %Matrix (expression) forming the argument of the\n      * matrix square root.\n      */\n    explicit MatrixSquareRootReturnValue(const Derived& src) : m_src(src) { }\n\n    /** \\brief Compute the matrix square root.\n      *\n      * \\param[out]  result  the matrix square root of \\p src in the\n      * constructor.\n      */\n    template <typename ResultType>\n    inline void evalTo(ResultType& result) const\n    {\n      typedef typename internal::nested_eval<Derived, 10>::type DerivedEvalType;\n      typedef typename internal::remove_all<DerivedEvalType>::type DerivedEvalTypeClean;\n      DerivedEvalType tmp(m_src);\n      internal::matrix_sqrt_compute<DerivedEvalTypeClean>::run(tmp, result);\n    }\n\n    Index rows() const { return m_src.rows(); }\n    Index cols() const { return m_src.cols(); }\n\n  protected:\n    const DerivedNested m_src;\n};\n\nnamespace internal {\ntemplate<typename Derived>\nstruct traits<MatrixSquareRootReturnValue<Derived> >\n{\n  typedef typename Derived::PlainObject ReturnType;\n};\n}\n\ntemplate <typename Derived>\nconst MatrixSquareRootReturnValue<Derived> MatrixBase<Derived>::sqrt() const\n{\n  eigen_assert(rows() == cols());\n  return MatrixSquareRootReturnValue<Derived>(derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_MATRIX_FUNCTION\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/MatrixFunctions/StemFunction.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010, 2013 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_STEM_FUNCTION\n#define EIGEN_STEM_FUNCTION\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\brief The exponential function (and its derivatives). */\ntemplate <typename Scalar>\nScalar stem_function_exp(Scalar x, int)\n{\n  using std::exp;\n  return exp(x);\n}\n\n/** \\brief Cosine (and its derivatives). */\ntemplate <typename Scalar>\nScalar stem_function_cos(Scalar x, int n)\n{\n  using std::cos;\n  using std::sin;\n  Scalar res;\n\n  switch (n % 4) {\n  case 0: \n    res = std::cos(x);\n    break;\n  case 1:\n    res = -std::sin(x);\n    break;\n  case 2:\n    res = -std::cos(x);\n    break;\n  case 3:\n    res = std::sin(x);\n    break;\n  }\n  return res;\n}\n\n/** \\brief Sine (and its derivatives). */\ntemplate <typename Scalar>\nScalar stem_function_sin(Scalar x, int n)\n{\n  using std::cos;\n  using std::sin;\n  Scalar res;\n\n  switch (n % 4) {\n  case 0:\n    res = std::sin(x);\n    break;\n  case 1:\n    res = std::cos(x);\n    break;\n  case 2:\n    res = -std::sin(x);\n    break;\n  case 3:\n    res = -std::cos(x);\n    break;\n  }\n  return res;\n}\n\n/** \\brief Hyperbolic cosine (and its derivatives). */\ntemplate <typename Scalar>\nScalar stem_function_cosh(Scalar x, int n)\n{\n  using std::cosh;\n  using std::sinh;\n  Scalar res;\n  \n  switch (n % 2) {\n  case 0:\n    res = std::cosh(x);\n    break;\n  case 1:\n    res = std::sinh(x);\n    break;\n  }\n  return res;\n}\n\t\n/** \\brief Hyperbolic sine (and its derivatives). */\ntemplate <typename Scalar>\nScalar stem_function_sinh(Scalar x, int n)\n{\n  using std::cosh;\n  using std::sinh;\n  Scalar res;\n  \n  switch (n % 2) {\n  case 0:\n    res = std::sinh(x);\n    break;\n  case 1:\n    res = std::cosh(x);\n    break;\n  }\n  return res;\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_STEM_FUNCTION\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/MoreVectorization/MathFunctions.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Rohit Garg <rpg.314@gmail.com>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MOREVECTORIZATION_MATHFUNCTIONS_H\n#define EIGEN_MOREVECTORIZATION_MATHFUNCTIONS_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\internal \\returns the arcsin of \\a a (coeff-wise) */\ntemplate<typename Packet> inline static Packet pasin(Packet a) { return std::asin(a); }\n\n#ifdef EIGEN_VECTORIZE_SSE\n\ntemplate<> EIGEN_DONT_INLINE Packet4f pasin(Packet4f x)\n{\n  _EIGEN_DECLARE_CONST_Packet4f(half, 0.5);\n  _EIGEN_DECLARE_CONST_Packet4f(minus_half, -0.5);\n  _EIGEN_DECLARE_CONST_Packet4f(3half, 1.5);\n\n  _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(sign_mask, 0x80000000);\n\n  _EIGEN_DECLARE_CONST_Packet4f(pi, 3.141592654);\n  _EIGEN_DECLARE_CONST_Packet4f(pi_over_2, 3.141592654*0.5);\n\n  _EIGEN_DECLARE_CONST_Packet4f(asin1, 4.2163199048E-2);\n  _EIGEN_DECLARE_CONST_Packet4f(asin2, 2.4181311049E-2);\n  _EIGEN_DECLARE_CONST_Packet4f(asin3, 4.5470025998E-2);\n  _EIGEN_DECLARE_CONST_Packet4f(asin4, 7.4953002686E-2);\n  _EIGEN_DECLARE_CONST_Packet4f(asin5, 1.6666752422E-1);\n\n  Packet4f a = pabs(x);//got the absolute value\n\n  Packet4f sign_bit= _mm_and_ps(x, p4f_sign_mask);//extracted the sign bit\n\n  Packet4f z1,z2;//will need them during computation    \n\n\n//will compute the two branches for asin\n//so first compare with half\n\n  Packet4f branch_mask= _mm_cmpgt_ps(a, p4f_half);//this is to select which branch to take\n//both will be taken, and finally results will be merged\n//the branch for values >0.5\n\n    {\n//the core series expansion \n    z1=pmadd(p4f_minus_half,a,p4f_half);\n    Packet4f x1=psqrt(z1);\n    Packet4f s1=pmadd(p4f_asin1, z1, p4f_asin2);\n    Packet4f s2=pmadd(s1, z1, p4f_asin3);\n    Packet4f s3=pmadd(s2,z1, p4f_asin4);\n    Packet4f s4=pmadd(s3,z1, p4f_asin5);\n    Packet4f temp=pmul(s4,z1);//not really a madd but a mul by z so that the next term can be a madd\n    z1=pmadd(temp,x1,x1);\n    z1=padd(z1,z1);\n    z1=psub(p4f_pi_over_2,z1);\n    }\n\n    {\n//the core series expansion \n    Packet4f x2=a;\n    z2=pmul(x2,x2);\n    Packet4f s1=pmadd(p4f_asin1, z2, p4f_asin2);\n    Packet4f s2=pmadd(s1, z2, p4f_asin3);\n    Packet4f s3=pmadd(s2,z2, p4f_asin4);\n    Packet4f s4=pmadd(s3,z2, p4f_asin5);\n    Packet4f temp=pmul(s4,z2);//not really a madd but a mul by z so that the next term can be a madd\n    z2=pmadd(temp,x2,x2);\n    }\n\n/* select the correct result from the two branch evaluations */\n  z1  = _mm_and_ps(branch_mask, z1);\n  z2  = _mm_andnot_ps(branch_mask, z2);\n  Packet4f z  = _mm_or_ps(z1,z2);\n\n/* update the sign */\n  return _mm_xor_ps(z, sign_bit);\n}\n\n#endif // EIGEN_VECTORIZE_SSE\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_MOREVECTORIZATION_MATHFUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/NonLinearOptimization/HybridNonLinearSolver.h",
    "content": "// -*- coding: utf-8\n// vim: set fileencoding=utf-8\n\n// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_HYBRIDNONLINEARSOLVER_H\n#define EIGEN_HYBRIDNONLINEARSOLVER_H\n\nnamespace Eigen { \n\nnamespace HybridNonLinearSolverSpace { \n    enum Status {\n        Running = -1,\n        ImproperInputParameters = 0,\n        RelativeErrorTooSmall = 1,\n        TooManyFunctionEvaluation = 2,\n        TolTooSmall = 3,\n        NotMakingProgressJacobian = 4,\n        NotMakingProgressIterations = 5,\n        UserAsked = 6\n    };\n}\n\n/**\n  * \\ingroup NonLinearOptimization_Module\n  * \\brief Finds a zero of a system of n\n  * nonlinear functions in n variables by a modification of the Powell\n  * hybrid method (\"dogleg\").\n  *\n  * The user must provide a subroutine which calculates the\n  * functions. The Jacobian is either provided by the user, or approximated\n  * using a forward-difference method.\n  *\n  */\ntemplate<typename FunctorType, typename Scalar=double>\nclass HybridNonLinearSolver\n{\npublic:\n    typedef DenseIndex Index;\n\n    HybridNonLinearSolver(FunctorType &_functor)\n        : functor(_functor) { nfev=njev=iter = 0;  fnorm= 0.; useExternalScaling=false;}\n\n    struct Parameters {\n        Parameters()\n            : factor(Scalar(100.))\n            , maxfev(1000)\n            , xtol(numext::sqrt(NumTraits<Scalar>::epsilon()))\n            , nb_of_subdiagonals(-1)\n            , nb_of_superdiagonals(-1)\n            , epsfcn(Scalar(0.)) {}\n        Scalar factor;\n        Index maxfev;   // maximum number of function evaluation\n        Scalar xtol;\n        Index nb_of_subdiagonals;\n        Index nb_of_superdiagonals;\n        Scalar epsfcn;\n    };\n    typedef Matrix< Scalar, Dynamic, 1 > FVectorType;\n    typedef Matrix< Scalar, Dynamic, Dynamic > JacobianType;\n    /* TODO: if eigen provides a triangular storage, use it here */\n    typedef Matrix< Scalar, Dynamic, Dynamic > UpperTriangularType;\n\n    HybridNonLinearSolverSpace::Status hybrj1(\n            FVectorType  &x,\n            const Scalar tol = numext::sqrt(NumTraits<Scalar>::epsilon())\n            );\n\n    HybridNonLinearSolverSpace::Status solveInit(FVectorType  &x);\n    HybridNonLinearSolverSpace::Status solveOneStep(FVectorType  &x);\n    HybridNonLinearSolverSpace::Status solve(FVectorType  &x);\n\n    HybridNonLinearSolverSpace::Status hybrd1(\n            FVectorType  &x,\n            const Scalar tol = numext::sqrt(NumTraits<Scalar>::epsilon())\n            );\n\n    HybridNonLinearSolverSpace::Status solveNumericalDiffInit(FVectorType  &x);\n    HybridNonLinearSolverSpace::Status solveNumericalDiffOneStep(FVectorType  &x);\n    HybridNonLinearSolverSpace::Status solveNumericalDiff(FVectorType  &x);\n\n    void resetParameters(void) { parameters = Parameters(); }\n    Parameters parameters;\n    FVectorType  fvec, qtf, diag;\n    JacobianType fjac;\n    UpperTriangularType R;\n    Index nfev;\n    Index njev;\n    Index iter;\n    Scalar fnorm;\n    bool useExternalScaling; \nprivate:\n    FunctorType &functor;\n    Index n;\n    Scalar sum;\n    bool sing;\n    Scalar temp;\n    Scalar delta;\n    bool jeval;\n    Index ncsuc;\n    Scalar ratio;\n    Scalar pnorm, xnorm, fnorm1;\n    Index nslow1, nslow2;\n    Index ncfail;\n    Scalar actred, prered;\n    FVectorType wa1, wa2, wa3, wa4;\n\n    HybridNonLinearSolver& operator=(const HybridNonLinearSolver&);\n};\n\n\n\ntemplate<typename FunctorType, typename Scalar>\nHybridNonLinearSolverSpace::Status\nHybridNonLinearSolver<FunctorType,Scalar>::hybrj1(\n        FVectorType  &x,\n        const Scalar tol\n        )\n{\n    n = x.size();\n\n    /* check the input parameters for errors. */\n    if (n <= 0 || tol < 0.)\n        return HybridNonLinearSolverSpace::ImproperInputParameters;\n\n    resetParameters();\n    parameters.maxfev = 100*(n+1);\n    parameters.xtol = tol;\n    diag.setConstant(n, 1.);\n    useExternalScaling = true;\n    return solve(x);\n}\n\ntemplate<typename FunctorType, typename Scalar>\nHybridNonLinearSolverSpace::Status\nHybridNonLinearSolver<FunctorType,Scalar>::solveInit(FVectorType  &x)\n{\n    n = x.size();\n\n    wa1.resize(n); wa2.resize(n); wa3.resize(n); wa4.resize(n);\n    fvec.resize(n);\n    qtf.resize(n);\n    fjac.resize(n, n);\n    if (!useExternalScaling)\n        diag.resize(n);\n    eigen_assert( (!useExternalScaling || diag.size()==n) && \"When useExternalScaling is set, the caller must provide a valid 'diag'\");\n\n    /* Function Body */\n    nfev = 0;\n    njev = 0;\n\n    /*     check the input parameters for errors. */\n    if (n <= 0 || parameters.xtol < 0. || parameters.maxfev <= 0 || parameters.factor <= 0. )\n        return HybridNonLinearSolverSpace::ImproperInputParameters;\n    if (useExternalScaling)\n        for (Index j = 0; j < n; ++j)\n            if (diag[j] <= 0.)\n                return HybridNonLinearSolverSpace::ImproperInputParameters;\n\n    /*     evaluate the function at the starting point */\n    /*     and calculate its norm. */\n    nfev = 1;\n    if ( functor(x, fvec) < 0)\n        return HybridNonLinearSolverSpace::UserAsked;\n    fnorm = fvec.stableNorm();\n\n    /*     initialize iteration counter and monitors. */\n    iter = 1;\n    ncsuc = 0;\n    ncfail = 0;\n    nslow1 = 0;\n    nslow2 = 0;\n\n    return HybridNonLinearSolverSpace::Running;\n}\n\ntemplate<typename FunctorType, typename Scalar>\nHybridNonLinearSolverSpace::Status\nHybridNonLinearSolver<FunctorType,Scalar>::solveOneStep(FVectorType  &x)\n{\n    using std::abs;\n    \n    eigen_assert(x.size()==n); // check the caller is not cheating us\n\n    Index j;\n    std::vector<JacobiRotation<Scalar> > v_givens(n), w_givens(n);\n\n    jeval = true;\n\n    /* calculate the jacobian matrix. */\n    if ( functor.df(x, fjac) < 0)\n        return HybridNonLinearSolverSpace::UserAsked;\n    ++njev;\n\n    wa2 = fjac.colwise().blueNorm();\n\n    /* on the first iteration and if external scaling is not used, scale according */\n    /* to the norms of the columns of the initial jacobian. */\n    if (iter == 1) {\n        if (!useExternalScaling)\n            for (j = 0; j < n; ++j)\n                diag[j] = (wa2[j]==0.) ? 1. : wa2[j];\n\n        /* on the first iteration, calculate the norm of the scaled x */\n        /* and initialize the step bound delta. */\n        xnorm = diag.cwiseProduct(x).stableNorm();\n        delta = parameters.factor * xnorm;\n        if (delta == 0.)\n            delta = parameters.factor;\n    }\n\n    /* compute the qr factorization of the jacobian. */\n    HouseholderQR<JacobianType> qrfac(fjac); // no pivoting:\n\n    /* copy the triangular factor of the qr factorization into r. */\n    R = qrfac.matrixQR();\n\n    /* accumulate the orthogonal factor in fjac. */\n    fjac = qrfac.householderQ();\n\n    /* form (q transpose)*fvec and store in qtf. */\n    qtf = fjac.transpose() * fvec;\n\n    /* rescale if necessary. */\n    if (!useExternalScaling)\n        diag = diag.cwiseMax(wa2);\n\n    while (true) {\n        /* determine the direction p. */\n        internal::dogleg<Scalar>(R, diag, qtf, delta, wa1);\n\n        /* store the direction p and x + p. calculate the norm of p. */\n        wa1 = -wa1;\n        wa2 = x + wa1;\n        pnorm = diag.cwiseProduct(wa1).stableNorm();\n\n        /* on the first iteration, adjust the initial step bound. */\n        if (iter == 1)\n            delta = (std::min)(delta,pnorm);\n\n        /* evaluate the function at x + p and calculate its norm. */\n        if ( functor(wa2, wa4) < 0)\n            return HybridNonLinearSolverSpace::UserAsked;\n        ++nfev;\n        fnorm1 = wa4.stableNorm();\n\n        /* compute the scaled actual reduction. */\n        actred = -1.;\n        if (fnorm1 < fnorm) /* Computing 2nd power */\n            actred = 1. - numext::abs2(fnorm1 / fnorm);\n\n        /* compute the scaled predicted reduction. */\n        wa3 = R.template triangularView<Upper>()*wa1 + qtf;\n        temp = wa3.stableNorm();\n        prered = 0.;\n        if (temp < fnorm) /* Computing 2nd power */\n            prered = 1. - numext::abs2(temp / fnorm);\n\n        /* compute the ratio of the actual to the predicted reduction. */\n        ratio = 0.;\n        if (prered > 0.)\n            ratio = actred / prered;\n\n        /* update the step bound. */\n        if (ratio < Scalar(.1)) {\n            ncsuc = 0;\n            ++ncfail;\n            delta = Scalar(.5) * delta;\n        } else {\n            ncfail = 0;\n            ++ncsuc;\n            if (ratio >= Scalar(.5) || ncsuc > 1)\n                delta = (std::max)(delta, pnorm / Scalar(.5));\n            if (abs(ratio - 1.) <= Scalar(.1)) {\n                delta = pnorm / Scalar(.5);\n            }\n        }\n\n        /* test for successful iteration. */\n        if (ratio >= Scalar(1e-4)) {\n            /* successful iteration. update x, fvec, and their norms. */\n            x = wa2;\n            wa2 = diag.cwiseProduct(x);\n            fvec = wa4;\n            xnorm = wa2.stableNorm();\n            fnorm = fnorm1;\n            ++iter;\n        }\n\n        /* determine the progress of the iteration. */\n        ++nslow1;\n        if (actred >= Scalar(.001))\n            nslow1 = 0;\n        if (jeval)\n            ++nslow2;\n        if (actred >= Scalar(.1))\n            nslow2 = 0;\n\n        /* test for convergence. */\n        if (delta <= parameters.xtol * xnorm || fnorm == 0.)\n            return HybridNonLinearSolverSpace::RelativeErrorTooSmall;\n\n        /* tests for termination and stringent tolerances. */\n        if (nfev >= parameters.maxfev)\n            return HybridNonLinearSolverSpace::TooManyFunctionEvaluation;\n        if (Scalar(.1) * (std::max)(Scalar(.1) * delta, pnorm) <= NumTraits<Scalar>::epsilon() * xnorm)\n            return HybridNonLinearSolverSpace::TolTooSmall;\n        if (nslow2 == 5)\n            return HybridNonLinearSolverSpace::NotMakingProgressJacobian;\n        if (nslow1 == 10)\n            return HybridNonLinearSolverSpace::NotMakingProgressIterations;\n\n        /* criterion for recalculating jacobian. */\n        if (ncfail == 2)\n            break; // leave inner loop and go for the next outer loop iteration\n\n        /* calculate the rank one modification to the jacobian */\n        /* and update qtf if necessary. */\n        wa1 = diag.cwiseProduct( diag.cwiseProduct(wa1)/pnorm );\n        wa2 = fjac.transpose() * wa4;\n        if (ratio >= Scalar(1e-4))\n            qtf = wa2;\n        wa2 = (wa2-wa3)/pnorm;\n\n        /* compute the qr factorization of the updated jacobian. */\n        internal::r1updt<Scalar>(R, wa1, v_givens, w_givens, wa2, wa3, &sing);\n        internal::r1mpyq<Scalar>(n, n, fjac.data(), v_givens, w_givens);\n        internal::r1mpyq<Scalar>(1, n, qtf.data(), v_givens, w_givens);\n\n        jeval = false;\n    }\n    return HybridNonLinearSolverSpace::Running;\n}\n\ntemplate<typename FunctorType, typename Scalar>\nHybridNonLinearSolverSpace::Status\nHybridNonLinearSolver<FunctorType,Scalar>::solve(FVectorType  &x)\n{\n    HybridNonLinearSolverSpace::Status status = solveInit(x);\n    if (status==HybridNonLinearSolverSpace::ImproperInputParameters)\n        return status;\n    while (status==HybridNonLinearSolverSpace::Running)\n        status = solveOneStep(x);\n    return status;\n}\n\n\n\ntemplate<typename FunctorType, typename Scalar>\nHybridNonLinearSolverSpace::Status\nHybridNonLinearSolver<FunctorType,Scalar>::hybrd1(\n        FVectorType  &x,\n        const Scalar tol\n        )\n{\n    n = x.size();\n\n    /* check the input parameters for errors. */\n    if (n <= 0 || tol < 0.)\n        return HybridNonLinearSolverSpace::ImproperInputParameters;\n\n    resetParameters();\n    parameters.maxfev = 200*(n+1);\n    parameters.xtol = tol;\n\n    diag.setConstant(n, 1.);\n    useExternalScaling = true;\n    return solveNumericalDiff(x);\n}\n\ntemplate<typename FunctorType, typename Scalar>\nHybridNonLinearSolverSpace::Status\nHybridNonLinearSolver<FunctorType,Scalar>::solveNumericalDiffInit(FVectorType  &x)\n{\n    n = x.size();\n\n    if (parameters.nb_of_subdiagonals<0) parameters.nb_of_subdiagonals= n-1;\n    if (parameters.nb_of_superdiagonals<0) parameters.nb_of_superdiagonals= n-1;\n\n    wa1.resize(n); wa2.resize(n); wa3.resize(n); wa4.resize(n);\n    qtf.resize(n);\n    fjac.resize(n, n);\n    fvec.resize(n);\n    if (!useExternalScaling)\n        diag.resize(n);\n    eigen_assert( (!useExternalScaling || diag.size()==n) && \"When useExternalScaling is set, the caller must provide a valid 'diag'\");\n\n    /* Function Body */\n    nfev = 0;\n    njev = 0;\n\n    /*     check the input parameters for errors. */\n    if (n <= 0 || parameters.xtol < 0. || parameters.maxfev <= 0 || parameters.nb_of_subdiagonals< 0 || parameters.nb_of_superdiagonals< 0 || parameters.factor <= 0. )\n        return HybridNonLinearSolverSpace::ImproperInputParameters;\n    if (useExternalScaling)\n        for (Index j = 0; j < n; ++j)\n            if (diag[j] <= 0.)\n                return HybridNonLinearSolverSpace::ImproperInputParameters;\n\n    /*     evaluate the function at the starting point */\n    /*     and calculate its norm. */\n    nfev = 1;\n    if ( functor(x, fvec) < 0)\n        return HybridNonLinearSolverSpace::UserAsked;\n    fnorm = fvec.stableNorm();\n\n    /*     initialize iteration counter and monitors. */\n    iter = 1;\n    ncsuc = 0;\n    ncfail = 0;\n    nslow1 = 0;\n    nslow2 = 0;\n\n    return HybridNonLinearSolverSpace::Running;\n}\n\ntemplate<typename FunctorType, typename Scalar>\nHybridNonLinearSolverSpace::Status\nHybridNonLinearSolver<FunctorType,Scalar>::solveNumericalDiffOneStep(FVectorType  &x)\n{\n    using std::sqrt;\n    using std::abs;\n    \n    assert(x.size()==n); // check the caller is not cheating us\n\n    Index j;\n    std::vector<JacobiRotation<Scalar> > v_givens(n), w_givens(n);\n\n    jeval = true;\n    if (parameters.nb_of_subdiagonals<0) parameters.nb_of_subdiagonals= n-1;\n    if (parameters.nb_of_superdiagonals<0) parameters.nb_of_superdiagonals= n-1;\n\n    /* calculate the jacobian matrix. */\n    if (internal::fdjac1(functor, x, fvec, fjac, parameters.nb_of_subdiagonals, parameters.nb_of_superdiagonals, parameters.epsfcn) <0)\n        return HybridNonLinearSolverSpace::UserAsked;\n    nfev += (std::min)(parameters.nb_of_subdiagonals+parameters.nb_of_superdiagonals+ 1, n);\n\n    wa2 = fjac.colwise().blueNorm();\n\n    /* on the first iteration and if external scaling is not used, scale according */\n    /* to the norms of the columns of the initial jacobian. */\n    if (iter == 1) {\n        if (!useExternalScaling)\n            for (j = 0; j < n; ++j)\n                diag[j] = (wa2[j]==0.) ? 1. : wa2[j];\n\n        /* on the first iteration, calculate the norm of the scaled x */\n        /* and initialize the step bound delta. */\n        xnorm = diag.cwiseProduct(x).stableNorm();\n        delta = parameters.factor * xnorm;\n        if (delta == 0.)\n            delta = parameters.factor;\n    }\n\n    /* compute the qr factorization of the jacobian. */\n    HouseholderQR<JacobianType> qrfac(fjac); // no pivoting:\n\n    /* copy the triangular factor of the qr factorization into r. */\n    R = qrfac.matrixQR();\n\n    /* accumulate the orthogonal factor in fjac. */\n    fjac = qrfac.householderQ();\n\n    /* form (q transpose)*fvec and store in qtf. */\n    qtf = fjac.transpose() * fvec;\n\n    /* rescale if necessary. */\n    if (!useExternalScaling)\n        diag = diag.cwiseMax(wa2);\n\n    while (true) {\n        /* determine the direction p. */\n        internal::dogleg<Scalar>(R, diag, qtf, delta, wa1);\n\n        /* store the direction p and x + p. calculate the norm of p. */\n        wa1 = -wa1;\n        wa2 = x + wa1;\n        pnorm = diag.cwiseProduct(wa1).stableNorm();\n\n        /* on the first iteration, adjust the initial step bound. */\n        if (iter == 1)\n            delta = (std::min)(delta,pnorm);\n\n        /* evaluate the function at x + p and calculate its norm. */\n        if ( functor(wa2, wa4) < 0)\n            return HybridNonLinearSolverSpace::UserAsked;\n        ++nfev;\n        fnorm1 = wa4.stableNorm();\n\n        /* compute the scaled actual reduction. */\n        actred = -1.;\n        if (fnorm1 < fnorm) /* Computing 2nd power */\n            actred = 1. - numext::abs2(fnorm1 / fnorm);\n\n        /* compute the scaled predicted reduction. */\n        wa3 = R.template triangularView<Upper>()*wa1 + qtf;\n        temp = wa3.stableNorm();\n        prered = 0.;\n        if (temp < fnorm) /* Computing 2nd power */\n            prered = 1. - numext::abs2(temp / fnorm);\n\n        /* compute the ratio of the actual to the predicted reduction. */\n        ratio = 0.;\n        if (prered > 0.)\n            ratio = actred / prered;\n\n        /* update the step bound. */\n        if (ratio < Scalar(.1)) {\n            ncsuc = 0;\n            ++ncfail;\n            delta = Scalar(.5) * delta;\n        } else {\n            ncfail = 0;\n            ++ncsuc;\n            if (ratio >= Scalar(.5) || ncsuc > 1)\n                delta = (std::max)(delta, pnorm / Scalar(.5));\n            if (abs(ratio - 1.) <= Scalar(.1)) {\n                delta = pnorm / Scalar(.5);\n            }\n        }\n\n        /* test for successful iteration. */\n        if (ratio >= Scalar(1e-4)) {\n            /* successful iteration. update x, fvec, and their norms. */\n            x = wa2;\n            wa2 = diag.cwiseProduct(x);\n            fvec = wa4;\n            xnorm = wa2.stableNorm();\n            fnorm = fnorm1;\n            ++iter;\n        }\n\n        /* determine the progress of the iteration. */\n        ++nslow1;\n        if (actred >= Scalar(.001))\n            nslow1 = 0;\n        if (jeval)\n            ++nslow2;\n        if (actred >= Scalar(.1))\n            nslow2 = 0;\n\n        /* test for convergence. */\n        if (delta <= parameters.xtol * xnorm || fnorm == 0.)\n            return HybridNonLinearSolverSpace::RelativeErrorTooSmall;\n\n        /* tests for termination and stringent tolerances. */\n        if (nfev >= parameters.maxfev)\n            return HybridNonLinearSolverSpace::TooManyFunctionEvaluation;\n        if (Scalar(.1) * (std::max)(Scalar(.1) * delta, pnorm) <= NumTraits<Scalar>::epsilon() * xnorm)\n            return HybridNonLinearSolverSpace::TolTooSmall;\n        if (nslow2 == 5)\n            return HybridNonLinearSolverSpace::NotMakingProgressJacobian;\n        if (nslow1 == 10)\n            return HybridNonLinearSolverSpace::NotMakingProgressIterations;\n\n        /* criterion for recalculating jacobian. */\n        if (ncfail == 2)\n            break; // leave inner loop and go for the next outer loop iteration\n\n        /* calculate the rank one modification to the jacobian */\n        /* and update qtf if necessary. */\n        wa1 = diag.cwiseProduct( diag.cwiseProduct(wa1)/pnorm );\n        wa2 = fjac.transpose() * wa4;\n        if (ratio >= Scalar(1e-4))\n            qtf = wa2;\n        wa2 = (wa2-wa3)/pnorm;\n\n        /* compute the qr factorization of the updated jacobian. */\n        internal::r1updt<Scalar>(R, wa1, v_givens, w_givens, wa2, wa3, &sing);\n        internal::r1mpyq<Scalar>(n, n, fjac.data(), v_givens, w_givens);\n        internal::r1mpyq<Scalar>(1, n, qtf.data(), v_givens, w_givens);\n\n        jeval = false;\n    }\n    return HybridNonLinearSolverSpace::Running;\n}\n\ntemplate<typename FunctorType, typename Scalar>\nHybridNonLinearSolverSpace::Status\nHybridNonLinearSolver<FunctorType,Scalar>::solveNumericalDiff(FVectorType  &x)\n{\n    HybridNonLinearSolverSpace::Status status = solveNumericalDiffInit(x);\n    if (status==HybridNonLinearSolverSpace::ImproperInputParameters)\n        return status;\n    while (status==HybridNonLinearSolverSpace::Running)\n        status = solveNumericalDiffOneStep(x);\n    return status;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_HYBRIDNONLINEARSOLVER_H\n\n//vim: ai ts=4 sts=4 et sw=4\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/NonLinearOptimization/LevenbergMarquardt.h",
    "content": "// -*- coding: utf-8\n// vim: set fileencoding=utf-8\n\n// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_LEVENBERGMARQUARDT__H\n#define EIGEN_LEVENBERGMARQUARDT__H\n\nnamespace Eigen { \n\nnamespace LevenbergMarquardtSpace {\n    enum Status {\n        NotStarted = -2,\n        Running = -1,\n        ImproperInputParameters = 0,\n        RelativeReductionTooSmall = 1,\n        RelativeErrorTooSmall = 2,\n        RelativeErrorAndReductionTooSmall = 3,\n        CosinusTooSmall = 4,\n        TooManyFunctionEvaluation = 5,\n        FtolTooSmall = 6,\n        XtolTooSmall = 7,\n        GtolTooSmall = 8,\n        UserAsked = 9\n    };\n}\n\n\n\n/**\n  * \\ingroup NonLinearOptimization_Module\n  * \\brief Performs non linear optimization over a non-linear function,\n  * using a variant of the Levenberg Marquardt algorithm.\n  *\n  * Check wikipedia for more information.\n  * http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm\n  */\ntemplate<typename FunctorType, typename Scalar=double>\nclass LevenbergMarquardt\n{\n    static Scalar sqrt_epsilon()\n    {\n      using std::sqrt;\n      return sqrt(NumTraits<Scalar>::epsilon());\n    }\n    \npublic:\n    LevenbergMarquardt(FunctorType &_functor)\n        : functor(_functor) { nfev = njev = iter = 0;  fnorm = gnorm = 0.; useExternalScaling=false; }\n\n    typedef DenseIndex Index;\n    \n    struct Parameters {\n        Parameters()\n            : factor(Scalar(100.))\n            , maxfev(400)\n            , ftol(sqrt_epsilon())\n            , xtol(sqrt_epsilon())\n            , gtol(Scalar(0.))\n            , epsfcn(Scalar(0.)) {}\n        Scalar factor;\n        Index maxfev;   // maximum number of function evaluation\n        Scalar ftol;\n        Scalar xtol;\n        Scalar gtol;\n        Scalar epsfcn;\n    };\n\n    typedef Matrix< Scalar, Dynamic, 1 > FVectorType;\n    typedef Matrix< Scalar, Dynamic, Dynamic > JacobianType;\n\n    LevenbergMarquardtSpace::Status lmder1(\n            FVectorType &x,\n            const Scalar tol = sqrt_epsilon()\n            );\n\n    LevenbergMarquardtSpace::Status minimize(FVectorType &x);\n    LevenbergMarquardtSpace::Status minimizeInit(FVectorType &x);\n    LevenbergMarquardtSpace::Status minimizeOneStep(FVectorType &x);\n\n    static LevenbergMarquardtSpace::Status lmdif1(\n            FunctorType &functor,\n            FVectorType &x,\n            Index *nfev,\n            const Scalar tol = sqrt_epsilon()\n            );\n\n    LevenbergMarquardtSpace::Status lmstr1(\n            FVectorType  &x,\n            const Scalar tol = sqrt_epsilon()\n            );\n\n    LevenbergMarquardtSpace::Status minimizeOptimumStorage(FVectorType  &x);\n    LevenbergMarquardtSpace::Status minimizeOptimumStorageInit(FVectorType  &x);\n    LevenbergMarquardtSpace::Status minimizeOptimumStorageOneStep(FVectorType  &x);\n\n    void resetParameters(void) { parameters = Parameters(); }\n\n    Parameters parameters;\n    FVectorType  fvec, qtf, diag;\n    JacobianType fjac;\n    PermutationMatrix<Dynamic,Dynamic> permutation;\n    Index nfev;\n    Index njev;\n    Index iter;\n    Scalar fnorm, gnorm;\n    bool useExternalScaling; \n\n    Scalar lm_param(void) { return par; }\nprivate:\n    \n    FunctorType &functor;\n    Index n;\n    Index m;\n    FVectorType wa1, wa2, wa3, wa4;\n\n    Scalar par, sum;\n    Scalar temp, temp1, temp2;\n    Scalar delta;\n    Scalar ratio;\n    Scalar pnorm, xnorm, fnorm1, actred, dirder, prered;\n\n    LevenbergMarquardt& operator=(const LevenbergMarquardt&);\n};\n\ntemplate<typename FunctorType, typename Scalar>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType,Scalar>::lmder1(\n        FVectorType  &x,\n        const Scalar tol\n        )\n{\n    n = x.size();\n    m = functor.values();\n\n    /* check the input parameters for errors. */\n    if (n <= 0 || m < n || tol < 0.)\n        return LevenbergMarquardtSpace::ImproperInputParameters;\n\n    resetParameters();\n    parameters.ftol = tol;\n    parameters.xtol = tol;\n    parameters.maxfev = 100*(n+1);\n\n    return minimize(x);\n}\n\n\ntemplate<typename FunctorType, typename Scalar>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType,Scalar>::minimize(FVectorType  &x)\n{\n    LevenbergMarquardtSpace::Status status = minimizeInit(x);\n    if (status==LevenbergMarquardtSpace::ImproperInputParameters)\n        return status;\n    do {\n        status = minimizeOneStep(x);\n    } while (status==LevenbergMarquardtSpace::Running);\n    return status;\n}\n\ntemplate<typename FunctorType, typename Scalar>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType,Scalar>::minimizeInit(FVectorType  &x)\n{\n    n = x.size();\n    m = functor.values();\n\n    wa1.resize(n); wa2.resize(n); wa3.resize(n);\n    wa4.resize(m);\n    fvec.resize(m);\n    fjac.resize(m, n);\n    if (!useExternalScaling)\n        diag.resize(n);\n    eigen_assert( (!useExternalScaling || diag.size()==n) && \"When useExternalScaling is set, the caller must provide a valid 'diag'\");\n    qtf.resize(n);\n\n    /* Function Body */\n    nfev = 0;\n    njev = 0;\n\n    /*     check the input parameters for errors. */\n    if (n <= 0 || m < n || parameters.ftol < 0. || parameters.xtol < 0. || parameters.gtol < 0. || parameters.maxfev <= 0 || parameters.factor <= 0.)\n        return LevenbergMarquardtSpace::ImproperInputParameters;\n\n    if (useExternalScaling)\n        for (Index j = 0; j < n; ++j)\n            if (diag[j] <= 0.)\n                return LevenbergMarquardtSpace::ImproperInputParameters;\n\n    /*     evaluate the function at the starting point */\n    /*     and calculate its norm. */\n    nfev = 1;\n    if ( functor(x, fvec) < 0)\n        return LevenbergMarquardtSpace::UserAsked;\n    fnorm = fvec.stableNorm();\n\n    /*     initialize levenberg-marquardt parameter and iteration counter. */\n    par = 0.;\n    iter = 1;\n\n    return LevenbergMarquardtSpace::NotStarted;\n}\n\ntemplate<typename FunctorType, typename Scalar>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType,Scalar>::minimizeOneStep(FVectorType  &x)\n{\n    using std::abs;\n    using std::sqrt;\n\n    eigen_assert(x.size()==n); // check the caller is not cheating us\n\n    /* calculate the jacobian matrix. */\n    Index df_ret = functor.df(x, fjac);\n    if (df_ret<0)\n        return LevenbergMarquardtSpace::UserAsked;\n    if (df_ret>0)\n        // numerical diff, we evaluated the function df_ret times\n        nfev += df_ret;\n    else njev++;\n\n    /* compute the qr factorization of the jacobian. */\n    wa2 = fjac.colwise().blueNorm();\n    ColPivHouseholderQR<JacobianType> qrfac(fjac);\n    fjac = qrfac.matrixQR();\n    permutation = qrfac.colsPermutation();\n\n    /* on the first iteration and if external scaling is not used, scale according */\n    /* to the norms of the columns of the initial jacobian. */\n    if (iter == 1) {\n        if (!useExternalScaling)\n            for (Index j = 0; j < n; ++j)\n                diag[j] = (wa2[j]==0.)? 1. : wa2[j];\n\n        /* on the first iteration, calculate the norm of the scaled x */\n        /* and initialize the step bound delta. */\n        xnorm = diag.cwiseProduct(x).stableNorm();\n        delta = parameters.factor * xnorm;\n        if (delta == 0.)\n            delta = parameters.factor;\n    }\n\n    /* form (q transpose)*fvec and store the first n components in */\n    /* qtf. */\n    wa4 = fvec;\n    wa4.applyOnTheLeft(qrfac.householderQ().adjoint());\n    qtf = wa4.head(n);\n\n    /* compute the norm of the scaled gradient. */\n    gnorm = 0.;\n    if (fnorm != 0.)\n        for (Index j = 0; j < n; ++j)\n            if (wa2[permutation.indices()[j]] != 0.)\n                gnorm = (std::max)(gnorm, abs( fjac.col(j).head(j+1).dot(qtf.head(j+1)/fnorm) / wa2[permutation.indices()[j]]));\n\n    /* test for convergence of the gradient norm. */\n    if (gnorm <= parameters.gtol)\n        return LevenbergMarquardtSpace::CosinusTooSmall;\n\n    /* rescale if necessary. */\n    if (!useExternalScaling)\n        diag = diag.cwiseMax(wa2);\n\n    do {\n\n        /* determine the levenberg-marquardt parameter. */\n        internal::lmpar2<Scalar>(qrfac, diag, qtf, delta, par, wa1);\n\n        /* store the direction p and x + p. calculate the norm of p. */\n        wa1 = -wa1;\n        wa2 = x + wa1;\n        pnorm = diag.cwiseProduct(wa1).stableNorm();\n\n        /* on the first iteration, adjust the initial step bound. */\n        if (iter == 1)\n            delta = (std::min)(delta,pnorm);\n\n        /* evaluate the function at x + p and calculate its norm. */\n        if ( functor(wa2, wa4) < 0)\n            return LevenbergMarquardtSpace::UserAsked;\n        ++nfev;\n        fnorm1 = wa4.stableNorm();\n\n        /* compute the scaled actual reduction. */\n        actred = -1.;\n        if (Scalar(.1) * fnorm1 < fnorm)\n            actred = 1. - numext::abs2(fnorm1 / fnorm);\n\n        /* compute the scaled predicted reduction and */\n        /* the scaled directional derivative. */\n        wa3 = fjac.template triangularView<Upper>() * (qrfac.colsPermutation().inverse() *wa1);\n        temp1 = numext::abs2(wa3.stableNorm() / fnorm);\n        temp2 = numext::abs2(sqrt(par) * pnorm / fnorm);\n        prered = temp1 + temp2 / Scalar(.5);\n        dirder = -(temp1 + temp2);\n\n        /* compute the ratio of the actual to the predicted */\n        /* reduction. */\n        ratio = 0.;\n        if (prered != 0.)\n            ratio = actred / prered;\n\n        /* update the step bound. */\n        if (ratio <= Scalar(.25)) {\n            if (actred >= 0.)\n                temp = Scalar(.5);\n            if (actred < 0.)\n                temp = Scalar(.5) * dirder / (dirder + Scalar(.5) * actred);\n            if (Scalar(.1) * fnorm1 >= fnorm || temp < Scalar(.1))\n                temp = Scalar(.1);\n            /* Computing MIN */\n            delta = temp * (std::min)(delta, pnorm / Scalar(.1));\n            par /= temp;\n        } else if (!(par != 0. && ratio < Scalar(.75))) {\n            delta = pnorm / Scalar(.5);\n            par = Scalar(.5) * par;\n        }\n\n        /* test for successful iteration. */\n        if (ratio >= Scalar(1e-4)) {\n            /* successful iteration. update x, fvec, and their norms. */\n            x = wa2;\n            wa2 = diag.cwiseProduct(x);\n            fvec = wa4;\n            xnorm = wa2.stableNorm();\n            fnorm = fnorm1;\n            ++iter;\n        }\n\n        /* tests for convergence. */\n        if (abs(actred) <= parameters.ftol && prered <= parameters.ftol && Scalar(.5) * ratio <= 1. && delta <= parameters.xtol * xnorm)\n            return LevenbergMarquardtSpace::RelativeErrorAndReductionTooSmall;\n        if (abs(actred) <= parameters.ftol && prered <= parameters.ftol && Scalar(.5) * ratio <= 1.)\n            return LevenbergMarquardtSpace::RelativeReductionTooSmall;\n        if (delta <= parameters.xtol * xnorm)\n            return LevenbergMarquardtSpace::RelativeErrorTooSmall;\n\n        /* tests for termination and stringent tolerances. */\n        if (nfev >= parameters.maxfev)\n            return LevenbergMarquardtSpace::TooManyFunctionEvaluation;\n        if (abs(actred) <= NumTraits<Scalar>::epsilon() && prered <= NumTraits<Scalar>::epsilon() && Scalar(.5) * ratio <= 1.)\n            return LevenbergMarquardtSpace::FtolTooSmall;\n        if (delta <= NumTraits<Scalar>::epsilon() * xnorm)\n            return LevenbergMarquardtSpace::XtolTooSmall;\n        if (gnorm <= NumTraits<Scalar>::epsilon())\n            return LevenbergMarquardtSpace::GtolTooSmall;\n\n    } while (ratio < Scalar(1e-4));\n\n    return LevenbergMarquardtSpace::Running;\n}\n\ntemplate<typename FunctorType, typename Scalar>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType,Scalar>::lmstr1(\n        FVectorType  &x,\n        const Scalar tol\n        )\n{\n    n = x.size();\n    m = functor.values();\n\n    /* check the input parameters for errors. */\n    if (n <= 0 || m < n || tol < 0.)\n        return LevenbergMarquardtSpace::ImproperInputParameters;\n\n    resetParameters();\n    parameters.ftol = tol;\n    parameters.xtol = tol;\n    parameters.maxfev = 100*(n+1);\n\n    return minimizeOptimumStorage(x);\n}\n\ntemplate<typename FunctorType, typename Scalar>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType,Scalar>::minimizeOptimumStorageInit(FVectorType  &x)\n{\n    n = x.size();\n    m = functor.values();\n\n    wa1.resize(n); wa2.resize(n); wa3.resize(n);\n    wa4.resize(m);\n    fvec.resize(m);\n    // Only R is stored in fjac. Q is only used to compute 'qtf', which is\n    // Q.transpose()*rhs. qtf will be updated using givens rotation,\n    // instead of storing them in Q.\n    // The purpose it to only use a nxn matrix, instead of mxn here, so\n    // that we can handle cases where m>>n :\n    fjac.resize(n, n);\n    if (!useExternalScaling)\n        diag.resize(n);\n    eigen_assert( (!useExternalScaling || diag.size()==n) && \"When useExternalScaling is set, the caller must provide a valid 'diag'\");\n    qtf.resize(n);\n\n    /* Function Body */\n    nfev = 0;\n    njev = 0;\n\n    /*     check the input parameters for errors. */\n    if (n <= 0 || m < n || parameters.ftol < 0. || parameters.xtol < 0. || parameters.gtol < 0. || parameters.maxfev <= 0 || parameters.factor <= 0.)\n        return LevenbergMarquardtSpace::ImproperInputParameters;\n\n    if (useExternalScaling)\n        for (Index j = 0; j < n; ++j)\n            if (diag[j] <= 0.)\n                return LevenbergMarquardtSpace::ImproperInputParameters;\n\n    /*     evaluate the function at the starting point */\n    /*     and calculate its norm. */\n    nfev = 1;\n    if ( functor(x, fvec) < 0)\n        return LevenbergMarquardtSpace::UserAsked;\n    fnorm = fvec.stableNorm();\n\n    /*     initialize levenberg-marquardt parameter and iteration counter. */\n    par = 0.;\n    iter = 1;\n\n    return LevenbergMarquardtSpace::NotStarted;\n}\n\n\ntemplate<typename FunctorType, typename Scalar>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType,Scalar>::minimizeOptimumStorageOneStep(FVectorType  &x)\n{\n    using std::abs;\n    using std::sqrt;\n    \n    eigen_assert(x.size()==n); // check the caller is not cheating us\n\n    Index i, j;\n    bool sing;\n\n    /* compute the qr factorization of the jacobian matrix */\n    /* calculated one row at a time, while simultaneously */\n    /* forming (q transpose)*fvec and storing the first */\n    /* n components in qtf. */\n    qtf.fill(0.);\n    fjac.fill(0.);\n    Index rownb = 2;\n    for (i = 0; i < m; ++i) {\n        if (functor.df(x, wa3, rownb) < 0) return LevenbergMarquardtSpace::UserAsked;\n        internal::rwupdt<Scalar>(fjac, wa3, qtf, fvec[i]);\n        ++rownb;\n    }\n    ++njev;\n\n    /* if the jacobian is rank deficient, call qrfac to */\n    /* reorder its columns and update the components of qtf. */\n    sing = false;\n    for (j = 0; j < n; ++j) {\n        if (fjac(j,j) == 0.)\n            sing = true;\n        wa2[j] = fjac.col(j).head(j).stableNorm();\n    }\n    permutation.setIdentity(n);\n    if (sing) {\n        wa2 = fjac.colwise().blueNorm();\n        // TODO We have no unit test covering this code path, do not modify\n        // until it is carefully tested\n        ColPivHouseholderQR<JacobianType> qrfac(fjac);\n        fjac = qrfac.matrixQR();\n        wa1 = fjac.diagonal();\n        fjac.diagonal() = qrfac.hCoeffs();\n        permutation = qrfac.colsPermutation();\n        // TODO : avoid this:\n        for(Index ii=0; ii< fjac.cols(); ii++) fjac.col(ii).segment(ii+1, fjac.rows()-ii-1) *= fjac(ii,ii); // rescale vectors\n\n        for (j = 0; j < n; ++j) {\n            if (fjac(j,j) != 0.) {\n                sum = 0.;\n                for (i = j; i < n; ++i)\n                    sum += fjac(i,j) * qtf[i];\n                temp = -sum / fjac(j,j);\n                for (i = j; i < n; ++i)\n                    qtf[i] += fjac(i,j) * temp;\n            }\n            fjac(j,j) = wa1[j];\n        }\n    }\n\n    /* on the first iteration and if external scaling is not used, scale according */\n    /* to the norms of the columns of the initial jacobian. */\n    if (iter == 1) {\n        if (!useExternalScaling)\n            for (j = 0; j < n; ++j)\n                diag[j] = (wa2[j]==0.)? 1. : wa2[j];\n\n        /* on the first iteration, calculate the norm of the scaled x */\n        /* and initialize the step bound delta. */\n        xnorm = diag.cwiseProduct(x).stableNorm();\n        delta = parameters.factor * xnorm;\n        if (delta == 0.)\n            delta = parameters.factor;\n    }\n\n    /* compute the norm of the scaled gradient. */\n    gnorm = 0.;\n    if (fnorm != 0.)\n        for (j = 0; j < n; ++j)\n            if (wa2[permutation.indices()[j]] != 0.)\n                gnorm = (std::max)(gnorm, abs( fjac.col(j).head(j+1).dot(qtf.head(j+1)/fnorm) / wa2[permutation.indices()[j]]));\n\n    /* test for convergence of the gradient norm. */\n    if (gnorm <= parameters.gtol)\n        return LevenbergMarquardtSpace::CosinusTooSmall;\n\n    /* rescale if necessary. */\n    if (!useExternalScaling)\n        diag = diag.cwiseMax(wa2);\n\n    do {\n\n        /* determine the levenberg-marquardt parameter. */\n        internal::lmpar<Scalar>(fjac, permutation.indices(), diag, qtf, delta, par, wa1);\n\n        /* store the direction p and x + p. calculate the norm of p. */\n        wa1 = -wa1;\n        wa2 = x + wa1;\n        pnorm = diag.cwiseProduct(wa1).stableNorm();\n\n        /* on the first iteration, adjust the initial step bound. */\n        if (iter == 1)\n            delta = (std::min)(delta,pnorm);\n\n        /* evaluate the function at x + p and calculate its norm. */\n        if ( functor(wa2, wa4) < 0)\n            return LevenbergMarquardtSpace::UserAsked;\n        ++nfev;\n        fnorm1 = wa4.stableNorm();\n\n        /* compute the scaled actual reduction. */\n        actred = -1.;\n        if (Scalar(.1) * fnorm1 < fnorm)\n            actred = 1. - numext::abs2(fnorm1 / fnorm);\n\n        /* compute the scaled predicted reduction and */\n        /* the scaled directional derivative. */\n        wa3 = fjac.topLeftCorner(n,n).template triangularView<Upper>() * (permutation.inverse() * wa1);\n        temp1 = numext::abs2(wa3.stableNorm() / fnorm);\n        temp2 = numext::abs2(sqrt(par) * pnorm / fnorm);\n        prered = temp1 + temp2 / Scalar(.5);\n        dirder = -(temp1 + temp2);\n\n        /* compute the ratio of the actual to the predicted */\n        /* reduction. */\n        ratio = 0.;\n        if (prered != 0.)\n            ratio = actred / prered;\n\n        /* update the step bound. */\n        if (ratio <= Scalar(.25)) {\n            if (actred >= 0.)\n                temp = Scalar(.5);\n            if (actred < 0.)\n                temp = Scalar(.5) * dirder / (dirder + Scalar(.5) * actred);\n            if (Scalar(.1) * fnorm1 >= fnorm || temp < Scalar(.1))\n                temp = Scalar(.1);\n            /* Computing MIN */\n            delta = temp * (std::min)(delta, pnorm / Scalar(.1));\n            par /= temp;\n        } else if (!(par != 0. && ratio < Scalar(.75))) {\n            delta = pnorm / Scalar(.5);\n            par = Scalar(.5) * par;\n        }\n\n        /* test for successful iteration. */\n        if (ratio >= Scalar(1e-4)) {\n            /* successful iteration. update x, fvec, and their norms. */\n            x = wa2;\n            wa2 = diag.cwiseProduct(x);\n            fvec = wa4;\n            xnorm = wa2.stableNorm();\n            fnorm = fnorm1;\n            ++iter;\n        }\n\n        /* tests for convergence. */\n        if (abs(actred) <= parameters.ftol && prered <= parameters.ftol && Scalar(.5) * ratio <= 1. && delta <= parameters.xtol * xnorm)\n            return LevenbergMarquardtSpace::RelativeErrorAndReductionTooSmall;\n        if (abs(actred) <= parameters.ftol && prered <= parameters.ftol && Scalar(.5) * ratio <= 1.)\n            return LevenbergMarquardtSpace::RelativeReductionTooSmall;\n        if (delta <= parameters.xtol * xnorm)\n            return LevenbergMarquardtSpace::RelativeErrorTooSmall;\n\n        /* tests for termination and stringent tolerances. */\n        if (nfev >= parameters.maxfev)\n            return LevenbergMarquardtSpace::TooManyFunctionEvaluation;\n        if (abs(actred) <= NumTraits<Scalar>::epsilon() && prered <= NumTraits<Scalar>::epsilon() && Scalar(.5) * ratio <= 1.)\n            return LevenbergMarquardtSpace::FtolTooSmall;\n        if (delta <= NumTraits<Scalar>::epsilon() * xnorm)\n            return LevenbergMarquardtSpace::XtolTooSmall;\n        if (gnorm <= NumTraits<Scalar>::epsilon())\n            return LevenbergMarquardtSpace::GtolTooSmall;\n\n    } while (ratio < Scalar(1e-4));\n\n    return LevenbergMarquardtSpace::Running;\n}\n\ntemplate<typename FunctorType, typename Scalar>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType,Scalar>::minimizeOptimumStorage(FVectorType  &x)\n{\n    LevenbergMarquardtSpace::Status status = minimizeOptimumStorageInit(x);\n    if (status==LevenbergMarquardtSpace::ImproperInputParameters)\n        return status;\n    do {\n        status = minimizeOptimumStorageOneStep(x);\n    } while (status==LevenbergMarquardtSpace::Running);\n    return status;\n}\n\ntemplate<typename FunctorType, typename Scalar>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType,Scalar>::lmdif1(\n        FunctorType &functor,\n        FVectorType  &x,\n        Index *nfev,\n        const Scalar tol\n        )\n{\n    Index n = x.size();\n    Index m = functor.values();\n\n    /* check the input parameters for errors. */\n    if (n <= 0 || m < n || tol < 0.)\n        return LevenbergMarquardtSpace::ImproperInputParameters;\n\n    NumericalDiff<FunctorType> numDiff(functor);\n    // embedded LevenbergMarquardt\n    LevenbergMarquardt<NumericalDiff<FunctorType>, Scalar > lm(numDiff);\n    lm.parameters.ftol = tol;\n    lm.parameters.xtol = tol;\n    lm.parameters.maxfev = 200*(n+1);\n\n    LevenbergMarquardtSpace::Status info = LevenbergMarquardtSpace::Status(lm.minimize(x));\n    if (nfev)\n        * nfev = lm.nfev;\n    return info;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_LEVENBERGMARQUARDT__H\n\n//vim: ai ts=4 sts=4 et sw=4\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/NonLinearOptimization/chkder.h",
    "content": "#define chkder_log10e 0.43429448190325182765\n#define chkder_factor 100.\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate<typename Scalar>\nvoid chkder(\n        const Matrix< Scalar, Dynamic, 1 >  &x,\n        const Matrix< Scalar, Dynamic, 1 >  &fvec,\n        const Matrix< Scalar, Dynamic, Dynamic > &fjac,\n        Matrix< Scalar, Dynamic, 1 >  &xp,\n        const Matrix< Scalar, Dynamic, 1 >  &fvecp,\n        int mode,\n        Matrix< Scalar, Dynamic, 1 >  &err\n        )\n{\n    using std::sqrt;\n    using std::abs;\n    using std::log;\n    \n    typedef DenseIndex Index;\n\n    const Scalar eps = sqrt(NumTraits<Scalar>::epsilon());\n    const Scalar epsf = chkder_factor * NumTraits<Scalar>::epsilon();\n    const Scalar epslog = chkder_log10e * log(eps);\n    Scalar temp;\n\n    const Index m = fvec.size(), n = x.size();\n\n    if (mode != 2) {\n        /* mode = 1. */\n        xp.resize(n);\n        for (Index j = 0; j < n; ++j) {\n            temp = eps * abs(x[j]);\n            if (temp == 0.)\n                temp = eps;\n            xp[j] = x[j] + temp;\n        }\n    }\n    else {\n        /* mode = 2. */\n        err.setZero(m); \n        for (Index j = 0; j < n; ++j) {\n            temp = abs(x[j]);\n            if (temp == 0.)\n                temp = 1.;\n            err += temp * fjac.col(j);\n        }\n        for (Index i = 0; i < m; ++i) {\n            temp = 1.;\n            if (fvec[i] != 0. && fvecp[i] != 0. && abs(fvecp[i] - fvec[i]) >= epsf * abs(fvec[i]))\n                temp = eps * abs((fvecp[i] - fvec[i]) / eps - err[i]) / (abs(fvec[i]) + abs(fvecp[i]));\n            err[i] = 1.;\n            if (temp > NumTraits<Scalar>::epsilon() && temp < eps)\n                err[i] = (chkder_log10e * log(temp) - epslog) / epslog;\n            if (temp >= eps)\n                err[i] = 0.;\n        }\n    }\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/NonLinearOptimization/covar.h",
    "content": "namespace Eigen { \n\nnamespace internal {\n\ntemplate <typename Scalar>\nvoid covar(\n        Matrix< Scalar, Dynamic, Dynamic > &r,\n        const VectorXi &ipvt,\n        Scalar tol = std::sqrt(NumTraits<Scalar>::epsilon()) )\n{\n    using std::abs;\n    typedef DenseIndex Index;\n\n    /* Local variables */\n    Index i, j, k, l, ii, jj;\n    bool sing;\n    Scalar temp;\n\n    /* Function Body */\n    const Index n = r.cols();\n    const Scalar tolr = tol * abs(r(0,0));\n    Matrix< Scalar, Dynamic, 1 > wa(n);\n    eigen_assert(ipvt.size()==n);\n\n    /* form the inverse of r in the full upper triangle of r. */\n    l = -1;\n    for (k = 0; k < n; ++k)\n        if (abs(r(k,k)) > tolr) {\n            r(k,k) = 1. / r(k,k);\n            for (j = 0; j <= k-1; ++j) {\n                temp = r(k,k) * r(j,k);\n                r(j,k) = 0.;\n                r.col(k).head(j+1) -= r.col(j).head(j+1) * temp;\n            }\n            l = k;\n        }\n\n    /* form the full upper triangle of the inverse of (r transpose)*r */\n    /* in the full upper triangle of r. */\n    for (k = 0; k <= l; ++k) {\n        for (j = 0; j <= k-1; ++j)\n            r.col(j).head(j+1) += r.col(k).head(j+1) * r(j,k);\n        r.col(k).head(k+1) *= r(k,k);\n    }\n\n    /* form the full lower triangle of the covariance matrix */\n    /* in the strict lower triangle of r and in wa. */\n    for (j = 0; j < n; ++j) {\n        jj = ipvt[j];\n        sing = j > l;\n        for (i = 0; i <= j; ++i) {\n            if (sing)\n                r(i,j) = 0.;\n            ii = ipvt[i];\n            if (ii > jj)\n                r(ii,jj) = r(i,j);\n            if (ii < jj)\n                r(jj,ii) = r(i,j);\n        }\n        wa[jj] = r(j,j);\n    }\n\n    /* symmetrize the covariance matrix in r. */\n    r.topLeftCorner(n,n).template triangularView<StrictlyUpper>() = r.topLeftCorner(n,n).transpose();\n    r.diagonal() = wa;\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/NonLinearOptimization/dogleg.h",
    "content": "namespace Eigen { \n\nnamespace internal {\n\ntemplate <typename Scalar>\nvoid dogleg(\n        const Matrix< Scalar, Dynamic, Dynamic >  &qrfac,\n        const Matrix< Scalar, Dynamic, 1 >  &diag,\n        const Matrix< Scalar, Dynamic, 1 >  &qtb,\n        Scalar delta,\n        Matrix< Scalar, Dynamic, 1 >  &x)\n{\n    using std::abs;\n    using std::sqrt;\n    \n    typedef DenseIndex Index;\n\n    /* Local variables */\n    Index i, j;\n    Scalar sum, temp, alpha, bnorm;\n    Scalar gnorm, qnorm;\n    Scalar sgnorm;\n\n    /* Function Body */\n    const Scalar epsmch = NumTraits<Scalar>::epsilon();\n    const Index n = qrfac.cols();\n    eigen_assert(n==qtb.size());\n    eigen_assert(n==x.size());\n    eigen_assert(n==diag.size());\n    Matrix< Scalar, Dynamic, 1 >  wa1(n), wa2(n);\n\n    /* first, calculate the gauss-newton direction. */\n    for (j = n-1; j >=0; --j) {\n        temp = qrfac(j,j);\n        if (temp == 0.) {\n            temp = epsmch * qrfac.col(j).head(j+1).maxCoeff();\n            if (temp == 0.)\n                temp = epsmch;\n        }\n        if (j==n-1)\n            x[j] = qtb[j] / temp;\n        else\n            x[j] = (qtb[j] - qrfac.row(j).tail(n-j-1).dot(x.tail(n-j-1))) / temp;\n    }\n\n    /* test whether the gauss-newton direction is acceptable. */\n    qnorm = diag.cwiseProduct(x).stableNorm();\n    if (qnorm <= delta)\n        return;\n\n    // TODO : this path is not tested by Eigen unit tests\n\n    /* the gauss-newton direction is not acceptable. */\n    /* next, calculate the scaled gradient direction. */\n\n    wa1.fill(0.);\n    for (j = 0; j < n; ++j) {\n        wa1.tail(n-j) += qrfac.row(j).tail(n-j) * qtb[j];\n        wa1[j] /= diag[j];\n    }\n\n    /* calculate the norm of the scaled gradient and test for */\n    /* the special case in which the scaled gradient is zero. */\n    gnorm = wa1.stableNorm();\n    sgnorm = 0.;\n    alpha = delta / qnorm;\n    if (gnorm == 0.)\n        goto algo_end;\n\n    /* calculate the point along the scaled gradient */\n    /* at which the quadratic is minimized. */\n    wa1.array() /= (diag*gnorm).array();\n    // TODO : once unit tests cover this part,:\n    // wa2 = qrfac.template triangularView<Upper>() * wa1;\n    for (j = 0; j < n; ++j) {\n        sum = 0.;\n        for (i = j; i < n; ++i) {\n            sum += qrfac(j,i) * wa1[i];\n        }\n        wa2[j] = sum;\n    }\n    temp = wa2.stableNorm();\n    sgnorm = gnorm / temp / temp;\n\n    /* test whether the scaled gradient direction is acceptable. */\n    alpha = 0.;\n    if (sgnorm >= delta)\n        goto algo_end;\n\n    /* the scaled gradient direction is not acceptable. */\n    /* finally, calculate the point along the dogleg */\n    /* at which the quadratic is minimized. */\n    bnorm = qtb.stableNorm();\n    temp = bnorm / gnorm * (bnorm / qnorm) * (sgnorm / delta);\n    temp = temp - delta / qnorm * numext::abs2(sgnorm / delta) + sqrt(numext::abs2(temp - delta / qnorm) + (1.-numext::abs2(delta / qnorm)) * (1.-numext::abs2(sgnorm / delta)));\n    alpha = delta / qnorm * (1. - numext::abs2(sgnorm / delta)) / temp;\nalgo_end:\n\n    /* form appropriate convex combination of the gauss-newton */\n    /* direction and the scaled gradient direction. */\n    temp = (1.-alpha) * (std::min)(sgnorm,delta);\n    x = temp * wa1 + alpha * x;\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/NonLinearOptimization/fdjac1.h",
    "content": "namespace Eigen { \n\nnamespace internal {\n\ntemplate<typename FunctorType, typename Scalar>\nDenseIndex fdjac1(\n        const FunctorType &Functor,\n        Matrix< Scalar, Dynamic, 1 >  &x,\n        Matrix< Scalar, Dynamic, 1 >  &fvec,\n        Matrix< Scalar, Dynamic, Dynamic > &fjac,\n        DenseIndex ml, DenseIndex mu,\n        Scalar epsfcn)\n{\n    using std::sqrt;\n    using std::abs;\n    \n    typedef DenseIndex Index;\n\n    /* Local variables */\n    Scalar h;\n    Index j, k;\n    Scalar eps, temp;\n    Index msum;\n    int iflag;\n    Index start, length;\n\n    /* Function Body */\n    const Scalar epsmch = NumTraits<Scalar>::epsilon();\n    const Index n = x.size();\n    eigen_assert(fvec.size()==n);\n    Matrix< Scalar, Dynamic, 1 >  wa1(n);\n    Matrix< Scalar, Dynamic, 1 >  wa2(n);\n\n    eps = sqrt((std::max)(epsfcn,epsmch));\n    msum = ml + mu + 1;\n    if (msum >= n) {\n        /* computation of dense approximate jacobian. */\n        for (j = 0; j < n; ++j) {\n            temp = x[j];\n            h = eps * abs(temp);\n            if (h == 0.)\n                h = eps;\n            x[j] = temp + h;\n            iflag = Functor(x, wa1);\n            if (iflag < 0)\n                return iflag;\n            x[j] = temp;\n            fjac.col(j) = (wa1-fvec)/h;\n        }\n\n    }else {\n        /* computation of banded approximate jacobian. */\n        for (k = 0; k < msum; ++k) {\n            for (j = k; (msum<0) ? (j>n): (j<n); j += msum) {\n                wa2[j] = x[j];\n                h = eps * abs(wa2[j]);\n                if (h == 0.) h = eps;\n                x[j] = wa2[j] + h;\n            }\n            iflag = Functor(x, wa1);\n            if (iflag < 0)\n                return iflag;\n            for (j = k; (msum<0) ? (j>n): (j<n); j += msum) {\n                x[j] = wa2[j];\n                h = eps * abs(wa2[j]);\n                if (h == 0.) h = eps;\n                fjac.col(j).setZero();\n                start = std::max<Index>(0,j-mu);\n                length = (std::min)(n-1, j+ml) - start + 1;\n                fjac.col(j).segment(start, length) = ( wa1.segment(start, length)-fvec.segment(start, length))/h;\n            }\n        }\n    }\n    return 0;\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/NonLinearOptimization/lmpar.h",
    "content": "namespace Eigen { \n\nnamespace internal {\n\ntemplate <typename Scalar>\nvoid lmpar(\n        Matrix< Scalar, Dynamic, Dynamic > &r,\n        const VectorXi &ipvt,\n        const Matrix< Scalar, Dynamic, 1 >  &diag,\n        const Matrix< Scalar, Dynamic, 1 >  &qtb,\n        Scalar delta,\n        Scalar &par,\n        Matrix< Scalar, Dynamic, 1 >  &x)\n{\n    using std::abs;\n    using std::sqrt;\n    typedef DenseIndex Index;\n\n    /* Local variables */\n    Index i, j, l;\n    Scalar fp;\n    Scalar parc, parl;\n    Index iter;\n    Scalar temp, paru;\n    Scalar gnorm;\n    Scalar dxnorm;\n\n\n    /* Function Body */\n    const Scalar dwarf = (std::numeric_limits<Scalar>::min)();\n    const Index n = r.cols();\n    eigen_assert(n==diag.size());\n    eigen_assert(n==qtb.size());\n    eigen_assert(n==x.size());\n\n    Matrix< Scalar, Dynamic, 1 >  wa1, wa2;\n\n    /* compute and store in x the gauss-newton direction. if the */\n    /* jacobian is rank-deficient, obtain a least squares solution. */\n    Index nsing = n-1;\n    wa1 = qtb;\n    for (j = 0; j < n; ++j) {\n        if (r(j,j) == 0. && nsing == n-1)\n            nsing = j - 1;\n        if (nsing < n-1)\n            wa1[j] = 0.;\n    }\n    for (j = nsing; j>=0; --j) {\n        wa1[j] /= r(j,j);\n        temp = wa1[j];\n        for (i = 0; i < j ; ++i)\n            wa1[i] -= r(i,j) * temp;\n    }\n\n    for (j = 0; j < n; ++j)\n        x[ipvt[j]] = wa1[j];\n\n    /* initialize the iteration counter. */\n    /* evaluate the function at the origin, and test */\n    /* for acceptance of the gauss-newton direction. */\n    iter = 0;\n    wa2 = diag.cwiseProduct(x);\n    dxnorm = wa2.blueNorm();\n    fp = dxnorm - delta;\n    if (fp <= Scalar(0.1) * delta) {\n        par = 0;\n        return;\n    }\n\n    /* if the jacobian is not rank deficient, the newton */\n    /* step provides a lower bound, parl, for the zero of */\n    /* the function. otherwise set this bound to zero. */\n    parl = 0.;\n    if (nsing >= n-1) {\n        for (j = 0; j < n; ++j) {\n            l = ipvt[j];\n            wa1[j] = diag[l] * (wa2[l] / dxnorm);\n        }\n        // it's actually a triangularView.solveInplace(), though in a weird\n        // way:\n        for (j = 0; j < n; ++j) {\n            Scalar sum = 0.;\n            for (i = 0; i < j; ++i)\n                sum += r(i,j) * wa1[i];\n            wa1[j] = (wa1[j] - sum) / r(j,j);\n        }\n        temp = wa1.blueNorm();\n        parl = fp / delta / temp / temp;\n    }\n\n    /* calculate an upper bound, paru, for the zero of the function. */\n    for (j = 0; j < n; ++j)\n        wa1[j] = r.col(j).head(j+1).dot(qtb.head(j+1)) / diag[ipvt[j]];\n\n    gnorm = wa1.stableNorm();\n    paru = gnorm / delta;\n    if (paru == 0.)\n        paru = dwarf / (std::min)(delta,Scalar(0.1));\n\n    /* if the input par lies outside of the interval (parl,paru), */\n    /* set par to the closer endpoint. */\n    par = (std::max)(par,parl);\n    par = (std::min)(par,paru);\n    if (par == 0.)\n        par = gnorm / dxnorm;\n\n    /* beginning of an iteration. */\n    while (true) {\n        ++iter;\n\n        /* evaluate the function at the current value of par. */\n        if (par == 0.)\n            par = (std::max)(dwarf,Scalar(.001) * paru); /* Computing MAX */\n        wa1 = sqrt(par)* diag;\n\n        Matrix< Scalar, Dynamic, 1 > sdiag(n);\n        qrsolv<Scalar>(r, ipvt, wa1, qtb, x, sdiag);\n\n        wa2 = diag.cwiseProduct(x);\n        dxnorm = wa2.blueNorm();\n        temp = fp;\n        fp = dxnorm - delta;\n\n        /* if the function is small enough, accept the current value */\n        /* of par. also test for the exceptional cases where parl */\n        /* is zero or the number of iterations has reached 10. */\n        if (abs(fp) <= Scalar(0.1) * delta || (parl == 0. && fp <= temp && temp < 0.) || iter == 10)\n            break;\n\n        /* compute the newton correction. */\n        for (j = 0; j < n; ++j) {\n            l = ipvt[j];\n            wa1[j] = diag[l] * (wa2[l] / dxnorm);\n        }\n        for (j = 0; j < n; ++j) {\n            wa1[j] /= sdiag[j];\n            temp = wa1[j];\n            for (i = j+1; i < n; ++i)\n                wa1[i] -= r(i,j) * temp;\n        }\n        temp = wa1.blueNorm();\n        parc = fp / delta / temp / temp;\n\n        /* depending on the sign of the function, update parl or paru. */\n        if (fp > 0.)\n            parl = (std::max)(parl,par);\n        if (fp < 0.)\n            paru = (std::min)(paru,par);\n\n        /* compute an improved estimate for par. */\n        /* Computing MAX */\n        par = (std::max)(parl,par+parc);\n\n        /* end of an iteration. */\n    }\n\n    /* termination. */\n    if (iter == 0)\n        par = 0.;\n    return;\n}\n\ntemplate <typename Scalar>\nvoid lmpar2(\n        const ColPivHouseholderQR<Matrix< Scalar, Dynamic, Dynamic> > &qr,\n        const Matrix< Scalar, Dynamic, 1 >  &diag,\n        const Matrix< Scalar, Dynamic, 1 >  &qtb,\n        Scalar delta,\n        Scalar &par,\n        Matrix< Scalar, Dynamic, 1 >  &x)\n\n{\n    using std::sqrt;\n    using std::abs;\n    typedef DenseIndex Index;\n\n    /* Local variables */\n    Index j;\n    Scalar fp;\n    Scalar parc, parl;\n    Index iter;\n    Scalar temp, paru;\n    Scalar gnorm;\n    Scalar dxnorm;\n\n\n    /* Function Body */\n    const Scalar dwarf = (std::numeric_limits<Scalar>::min)();\n    const Index n = qr.matrixQR().cols();\n    eigen_assert(n==diag.size());\n    eigen_assert(n==qtb.size());\n\n    Matrix< Scalar, Dynamic, 1 >  wa1, wa2;\n\n    /* compute and store in x the gauss-newton direction. if the */\n    /* jacobian is rank-deficient, obtain a least squares solution. */\n\n//    const Index rank = qr.nonzeroPivots(); // exactly double(0.)\n    const Index rank = qr.rank(); // use a threshold\n    wa1 = qtb;\n    wa1.tail(n-rank).setZero();\n    qr.matrixQR().topLeftCorner(rank, rank).template triangularView<Upper>().solveInPlace(wa1.head(rank));\n\n    x = qr.colsPermutation()*wa1;\n\n    /* initialize the iteration counter. */\n    /* evaluate the function at the origin, and test */\n    /* for acceptance of the gauss-newton direction. */\n    iter = 0;\n    wa2 = diag.cwiseProduct(x);\n    dxnorm = wa2.blueNorm();\n    fp = dxnorm - delta;\n    if (fp <= Scalar(0.1) * delta) {\n        par = 0;\n        return;\n    }\n\n    /* if the jacobian is not rank deficient, the newton */\n    /* step provides a lower bound, parl, for the zero of */\n    /* the function. otherwise set this bound to zero. */\n    parl = 0.;\n    if (rank==n) {\n        wa1 = qr.colsPermutation().inverse() *  diag.cwiseProduct(wa2)/dxnorm;\n        qr.matrixQR().topLeftCorner(n, n).transpose().template triangularView<Lower>().solveInPlace(wa1);\n        temp = wa1.blueNorm();\n        parl = fp / delta / temp / temp;\n    }\n\n    /* calculate an upper bound, paru, for the zero of the function. */\n    for (j = 0; j < n; ++j)\n        wa1[j] = qr.matrixQR().col(j).head(j+1).dot(qtb.head(j+1)) / diag[qr.colsPermutation().indices()(j)];\n\n    gnorm = wa1.stableNorm();\n    paru = gnorm / delta;\n    if (paru == 0.)\n        paru = dwarf / (std::min)(delta,Scalar(0.1));\n\n    /* if the input par lies outside of the interval (parl,paru), */\n    /* set par to the closer endpoint. */\n    par = (std::max)(par,parl);\n    par = (std::min)(par,paru);\n    if (par == 0.)\n        par = gnorm / dxnorm;\n\n    /* beginning of an iteration. */\n    Matrix< Scalar, Dynamic, Dynamic > s = qr.matrixQR();\n    while (true) {\n        ++iter;\n\n        /* evaluate the function at the current value of par. */\n        if (par == 0.)\n            par = (std::max)(dwarf,Scalar(.001) * paru); /* Computing MAX */\n        wa1 = sqrt(par)* diag;\n\n        Matrix< Scalar, Dynamic, 1 > sdiag(n);\n        qrsolv<Scalar>(s, qr.colsPermutation().indices(), wa1, qtb, x, sdiag);\n\n        wa2 = diag.cwiseProduct(x);\n        dxnorm = wa2.blueNorm();\n        temp = fp;\n        fp = dxnorm - delta;\n\n        /* if the function is small enough, accept the current value */\n        /* of par. also test for the exceptional cases where parl */\n        /* is zero or the number of iterations has reached 10. */\n        if (abs(fp) <= Scalar(0.1) * delta || (parl == 0. && fp <= temp && temp < 0.) || iter == 10)\n            break;\n\n        /* compute the newton correction. */\n        wa1 = qr.colsPermutation().inverse() * diag.cwiseProduct(wa2/dxnorm);\n        // we could almost use this here, but the diagonal is outside qr, in sdiag[]\n        // qr.matrixQR().topLeftCorner(n, n).transpose().template triangularView<Lower>().solveInPlace(wa1);\n        for (j = 0; j < n; ++j) {\n            wa1[j] /= sdiag[j];\n            temp = wa1[j];\n            for (Index i = j+1; i < n; ++i)\n                wa1[i] -= s(i,j) * temp;\n        }\n        temp = wa1.blueNorm();\n        parc = fp / delta / temp / temp;\n\n        /* depending on the sign of the function, update parl or paru. */\n        if (fp > 0.)\n            parl = (std::max)(parl,par);\n        if (fp < 0.)\n            paru = (std::min)(paru,par);\n\n        /* compute an improved estimate for par. */\n        par = (std::max)(parl,par+parc);\n    }\n    if (iter == 0)\n        par = 0.;\n    return;\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/NonLinearOptimization/qrsolv.h",
    "content": "namespace Eigen { \n\nnamespace internal {\n\n// TODO : once qrsolv2 is removed, use ColPivHouseholderQR or PermutationMatrix instead of ipvt\ntemplate <typename Scalar>\nvoid qrsolv(\n        Matrix< Scalar, Dynamic, Dynamic > &s,\n        // TODO : use a PermutationMatrix once lmpar is no more:\n        const VectorXi &ipvt,\n        const Matrix< Scalar, Dynamic, 1 >  &diag,\n        const Matrix< Scalar, Dynamic, 1 >  &qtb,\n        Matrix< Scalar, Dynamic, 1 >  &x,\n        Matrix< Scalar, Dynamic, 1 >  &sdiag)\n\n{\n    typedef DenseIndex Index;\n\n    /* Local variables */\n    Index i, j, k, l;\n    Scalar temp;\n    Index n = s.cols();\n    Matrix< Scalar, Dynamic, 1 >  wa(n);\n    JacobiRotation<Scalar> givens;\n\n    /* Function Body */\n    // the following will only change the lower triangular part of s, including\n    // the diagonal, though the diagonal is restored afterward\n\n    /*     copy r and (q transpose)*b to preserve input and initialize s. */\n    /*     in particular, save the diagonal elements of r in x. */\n    x = s.diagonal();\n    wa = qtb;\n\n    s.topLeftCorner(n,n).template triangularView<StrictlyLower>() = s.topLeftCorner(n,n).transpose();\n\n    /*     eliminate the diagonal matrix d using a givens rotation. */\n    for (j = 0; j < n; ++j) {\n\n        /*        prepare the row of d to be eliminated, locating the */\n        /*        diagonal element using p from the qr factorization. */\n        l = ipvt[j];\n        if (diag[l] == 0.)\n            break;\n        sdiag.tail(n-j).setZero();\n        sdiag[j] = diag[l];\n\n        /*        the transformations to eliminate the row of d */\n        /*        modify only a single element of (q transpose)*b */\n        /*        beyond the first n, which is initially zero. */\n        Scalar qtbpj = 0.;\n        for (k = j; k < n; ++k) {\n            /*           determine a givens rotation which eliminates the */\n            /*           appropriate element in the current row of d. */\n            givens.makeGivens(-s(k,k), sdiag[k]);\n\n            /*           compute the modified diagonal element of r and */\n            /*           the modified element of ((q transpose)*b,0). */\n            s(k,k) = givens.c() * s(k,k) + givens.s() * sdiag[k];\n            temp = givens.c() * wa[k] + givens.s() * qtbpj;\n            qtbpj = -givens.s() * wa[k] + givens.c() * qtbpj;\n            wa[k] = temp;\n\n            /*           accumulate the transformation in the row of s. */\n            for (i = k+1; i<n; ++i) {\n                temp = givens.c() * s(i,k) + givens.s() * sdiag[i];\n                sdiag[i] = -givens.s() * s(i,k) + givens.c() * sdiag[i];\n                s(i,k) = temp;\n            }\n        }\n    }\n\n    /*     solve the triangular system for z. if the system is */\n    /*     singular, then obtain a least squares solution. */\n    Index nsing;\n    for(nsing=0; nsing<n && sdiag[nsing]!=0; nsing++) {}\n\n    wa.tail(n-nsing).setZero();\n    s.topLeftCorner(nsing, nsing).transpose().template triangularView<Upper>().solveInPlace(wa.head(nsing));\n\n    // restore\n    sdiag = s.diagonal();\n    s.diagonal() = x;\n\n    /*     permute the components of z back to components of x. */\n    for (j = 0; j < n; ++j) x[ipvt[j]] = wa[j];\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/NonLinearOptimization/r1mpyq.h",
    "content": "namespace Eigen { \n\nnamespace internal {\n\n// TODO : move this to GivensQR once there's such a thing in Eigen\n\ntemplate <typename Scalar>\nvoid r1mpyq(DenseIndex m, DenseIndex n, Scalar *a, const std::vector<JacobiRotation<Scalar> > &v_givens, const std::vector<JacobiRotation<Scalar> > &w_givens)\n{\n    typedef DenseIndex Index;\n\n    /*     apply the first set of givens rotations to a. */\n    for (Index j = n-2; j>=0; --j)\n        for (Index i = 0; i<m; ++i) {\n            Scalar temp = v_givens[j].c() * a[i+m*j] - v_givens[j].s() * a[i+m*(n-1)];\n            a[i+m*(n-1)] = v_givens[j].s() * a[i+m*j] + v_givens[j].c() * a[i+m*(n-1)];\n            a[i+m*j] = temp;\n        }\n    /*     apply the second set of givens rotations to a. */\n    for (Index j = 0; j<n-1; ++j)\n        for (Index i = 0; i<m; ++i) {\n            Scalar temp = w_givens[j].c() * a[i+m*j] + w_givens[j].s() * a[i+m*(n-1)];\n            a[i+m*(n-1)] = -w_givens[j].s() * a[i+m*j] + w_givens[j].c() * a[i+m*(n-1)];\n            a[i+m*j] = temp;\n        }\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/NonLinearOptimization/r1updt.h",
    "content": "namespace Eigen { \n\nnamespace internal {\n\ntemplate <typename Scalar>\nvoid r1updt(\n        Matrix< Scalar, Dynamic, Dynamic > &s,\n        const Matrix< Scalar, Dynamic, 1> &u,\n        std::vector<JacobiRotation<Scalar> > &v_givens,\n        std::vector<JacobiRotation<Scalar> > &w_givens,\n        Matrix< Scalar, Dynamic, 1> &v,\n        Matrix< Scalar, Dynamic, 1> &w,\n        bool *sing)\n{\n    typedef DenseIndex Index;\n    const JacobiRotation<Scalar> IdentityRotation = JacobiRotation<Scalar>(1,0);\n\n    /* Local variables */\n    const Index m = s.rows();\n    const Index n = s.cols();\n    Index i, j=1;\n    Scalar temp;\n    JacobiRotation<Scalar> givens;\n\n    // r1updt had a broader usecase, but we don't use it here. And, more\n    // importantly, we can not test it.\n    eigen_assert(m==n);\n    eigen_assert(u.size()==m);\n    eigen_assert(v.size()==n);\n    eigen_assert(w.size()==n);\n\n    /* move the nontrivial part of the last column of s into w. */\n    w[n-1] = s(n-1,n-1);\n\n    /* rotate the vector v into a multiple of the n-th unit vector */\n    /* in such a way that a spike is introduced into w. */\n    for (j=n-2; j>=0; --j) {\n        w[j] = 0.;\n        if (v[j] != 0.) {\n            /* determine a givens rotation which eliminates the */\n            /* j-th element of v. */\n            givens.makeGivens(-v[n-1], v[j]);\n\n            /* apply the transformation to v and store the information */\n            /* necessary to recover the givens rotation. */\n            v[n-1] = givens.s() * v[j] + givens.c() * v[n-1];\n            v_givens[j] = givens;\n\n            /* apply the transformation to s and extend the spike in w. */\n            for (i = j; i < m; ++i) {\n                temp = givens.c() * s(j,i) - givens.s() * w[i];\n                w[i] = givens.s() * s(j,i) + givens.c() * w[i];\n                s(j,i) = temp;\n            }\n        } else\n            v_givens[j] = IdentityRotation;\n    }\n\n    /* add the spike from the rank 1 update to w. */\n    w += v[n-1] * u;\n\n    /* eliminate the spike. */\n    *sing = false;\n    for (j = 0; j < n-1; ++j) {\n        if (w[j] != 0.) {\n            /* determine a givens rotation which eliminates the */\n            /* j-th element of the spike. */\n            givens.makeGivens(-s(j,j), w[j]);\n\n            /* apply the transformation to s and reduce the spike in w. */\n            for (i = j; i < m; ++i) {\n                temp = givens.c() * s(j,i) + givens.s() * w[i];\n                w[i] = -givens.s() * s(j,i) + givens.c() * w[i];\n                s(j,i) = temp;\n            }\n\n            /* store the information necessary to recover the */\n            /* givens rotation. */\n            w_givens[j] = givens;\n        } else\n            v_givens[j] = IdentityRotation;\n\n        /* test for zero diagonal elements in the output s. */\n        if (s(j,j) == 0.) {\n            *sing = true;\n        }\n    }\n    /* move w back into the last column of the output s. */\n    s(n-1,n-1) = w[n-1];\n\n    if (s(j,j) == 0.) {\n        *sing = true;\n    }\n    return;\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/NonLinearOptimization/rwupdt.h",
    "content": "namespace Eigen { \n\nnamespace internal {\n\ntemplate <typename Scalar>\nvoid rwupdt(\n        Matrix< Scalar, Dynamic, Dynamic >  &r,\n        const Matrix< Scalar, Dynamic, 1>  &w,\n        Matrix< Scalar, Dynamic, 1>  &b,\n        Scalar alpha)\n{\n    typedef DenseIndex Index;\n\n    const Index n = r.cols();\n    eigen_assert(r.rows()>=n);\n    std::vector<JacobiRotation<Scalar> > givens(n);\n\n    /* Local variables */\n    Scalar temp, rowj;\n\n    /* Function Body */\n    for (Index j = 0; j < n; ++j) {\n        rowj = w[j];\n\n        /* apply the previous transformations to */\n        /* r(i,j), i=0,1,...,j-1, and to w(j). */\n        for (Index i = 0; i < j; ++i) {\n            temp = givens[i].c() * r(i,j) + givens[i].s() * rowj;\n            rowj = -givens[i].s() * r(i,j) + givens[i].c() * rowj;\n            r(i,j) = temp;\n        }\n\n        /* determine a givens rotation which eliminates w(j). */\n        givens[j].makeGivens(-r(j,j), rowj);\n\n        if (rowj == 0.)\n            continue; // givens[j] is identity\n\n        /* apply the current transformation to r(j,j), b(j), and alpha. */\n        r(j,j) = givens[j].c() * r(j,j) + givens[j].s() * rowj;\n        temp = givens[j].c() * b[j] + givens[j].s() * alpha;\n        alpha = -givens[j].s() * b[j] + givens[j].c() * alpha;\n        b[j] = temp;\n    }\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/NumericalDiff/NumericalDiff.h",
    "content": "// -*- coding: utf-8\n// vim: set fileencoding=utf-8\n\n// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_NUMERICAL_DIFF_H\n#define EIGEN_NUMERICAL_DIFF_H\n\nnamespace Eigen { \n\nenum NumericalDiffMode {\n    Forward,\n    Central\n};\n\n\n/**\n  * This class allows you to add a method df() to your functor, which will \n  * use numerical differentiation to compute an approximate of the\n  * derivative for the functor. Of course, if you have an analytical form\n  * for the derivative, you should rather implement df() by yourself.\n  *\n  * More information on\n  * http://en.wikipedia.org/wiki/Numerical_differentiation\n  *\n  * Currently only \"Forward\" and \"Central\" scheme are implemented.\n  */\ntemplate<typename Functor_, NumericalDiffMode mode=Forward>\nclass NumericalDiff : public Functor_\n{\npublic:\n    typedef Functor_ Functor;\n    typedef typename Functor::Scalar Scalar;\n    typedef typename Functor::InputType InputType;\n    typedef typename Functor::ValueType ValueType;\n    typedef typename Functor::JacobianType JacobianType;\n\n    NumericalDiff(Scalar _epsfcn=0.) : Functor(), epsfcn(_epsfcn) {}\n    NumericalDiff(const Functor& f, Scalar _epsfcn=0.) : Functor(f), epsfcn(_epsfcn) {}\n\n    // forward constructors\n    template<typename T0>\n        NumericalDiff(const T0& a0) : Functor(a0), epsfcn(0) {}\n    template<typename T0, typename T1>\n        NumericalDiff(const T0& a0, const T1& a1) : Functor(a0, a1), epsfcn(0) {}\n    template<typename T0, typename T1, typename T2>\n        NumericalDiff(const T0& a0, const T1& a1, const T2& a2) : Functor(a0, a1, a2), epsfcn(0) {}\n\n    enum {\n        InputsAtCompileTime = Functor::InputsAtCompileTime,\n        ValuesAtCompileTime = Functor::ValuesAtCompileTime\n    };\n\n    /**\n      * return the number of evaluation of functor\n     */\n    int df(const InputType& _x, JacobianType &jac) const\n    {\n        using std::sqrt;\n        using std::abs;\n        /* Local variables */\n        Scalar h;\n        int nfev=0;\n        const typename InputType::Index n = _x.size();\n        const Scalar eps = sqrt(((std::max)(epsfcn,NumTraits<Scalar>::epsilon() )));\n        ValueType val1, val2;\n        InputType x = _x;\n        // TODO : we should do this only if the size is not already known\n        val1.resize(Functor::values());\n        val2.resize(Functor::values());\n\n        // initialization\n        switch(mode) {\n            case Forward:\n                // compute f(x)\n                Functor::operator()(x, val1); nfev++;\n                break;\n            case Central:\n                // do nothing\n                break;\n            default:\n                eigen_assert(false);\n        };\n\n        // Function Body\n        for (int j = 0; j < n; ++j) {\n            h = eps * abs(x[j]);\n            if (h == 0.) {\n                h = eps;\n            }\n            switch(mode) {\n                case Forward:\n                    x[j] += h;\n                    Functor::operator()(x, val2);\n                    nfev++;\n                    x[j] = _x[j];\n                    jac.col(j) = (val2-val1)/h;\n                    break;\n                case Central:\n                    x[j] += h;\n                    Functor::operator()(x, val2); nfev++;\n                    x[j] -= 2*h;\n                    Functor::operator()(x, val1); nfev++;\n                    x[j] = _x[j];\n                    jac.col(j) = (val2-val1)/(2*h);\n                    break;\n                default:\n                    eigen_assert(false);\n            };\n        }\n        return nfev;\n    }\nprivate:\n    Scalar epsfcn;\n\n    NumericalDiff& operator=(const NumericalDiff&);\n};\n\n} // end namespace Eigen\n\n//vim: ai ts=4 sts=4 et sw=4\n#endif // EIGEN_NUMERICAL_DIFF_H\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/Polynomials/Companion.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Manuel Yguel <manuel.yguel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_COMPANION_H\n#define EIGEN_COMPANION_H\n\n// This file requires the user to include\n// * Eigen/Core\n// * Eigen/src/PolynomialSolver.h\n\nnamespace Eigen { \n\nnamespace internal {\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n\ntemplate<int Size>\nstruct decrement_if_fixed_size\n{\n  enum {\n    ret = (Size == Dynamic) ? Dynamic : Size-1 };\n};\n\n#endif\n\ntemplate< typename Scalar_, int _Deg >\nclass companion\n{\n  public:\n    EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(Scalar_,_Deg==Dynamic ? Dynamic : _Deg)\n\n    enum {\n      Deg = _Deg,\n      Deg_1=decrement_if_fixed_size<Deg>::ret\n    };\n\n    typedef Scalar_                                Scalar;\n    typedef typename NumTraits<Scalar>::Real       RealScalar;\n    typedef Matrix<Scalar, Deg, 1>                 RightColumn;\n    //typedef DiagonalMatrix< Scalar, Deg_1, Deg_1 > BottomLeftDiagonal;\n    typedef Matrix<Scalar, Deg_1, 1>               BottomLeftDiagonal;\n\n    typedef Matrix<Scalar, Deg, Deg>               DenseCompanionMatrixType;\n    typedef Matrix< Scalar, _Deg, Deg_1 >          LeftBlock;\n    typedef Matrix< Scalar, Deg_1, Deg_1 >         BottomLeftBlock;\n    typedef Matrix< Scalar, 1, Deg_1 >             LeftBlockFirstRow;\n\n    typedef DenseIndex Index;\n\n  public:\n    EIGEN_STRONG_INLINE const Scalar_ operator()(Index row, Index col ) const\n    {\n      if( m_bl_diag.rows() > col )\n      {\n        if( 0 < row ){ return m_bl_diag[col]; }\n        else{ return 0; }\n      }\n      else{ return m_monic[row]; }\n    }\n\n  public:\n    template<typename VectorType>\n    void setPolynomial( const VectorType& poly )\n    {\n      const Index deg = poly.size()-1;\n      m_monic = -poly.head(deg)/poly[deg];\n      m_bl_diag.setOnes(deg-1);\n    }\n\n    template<typename VectorType>\n    companion( const VectorType& poly ){\n      setPolynomial( poly ); }\n\n  public:\n    DenseCompanionMatrixType denseMatrix() const\n    {\n      const Index deg   = m_monic.size();\n      const Index deg_1 = deg-1;\n      DenseCompanionMatrixType companMat(deg,deg);\n      companMat <<\n        ( LeftBlock(deg,deg_1)\n          << LeftBlockFirstRow::Zero(1,deg_1),\n          BottomLeftBlock::Identity(deg-1,deg-1)*m_bl_diag.asDiagonal() ).finished()\n        , m_monic;\n      return companMat;\n    }\n\n\n\n  protected:\n    /** Helper function for the balancing algorithm.\n     * \\returns true if the row and the column, having colNorm and rowNorm\n     * as norms, are balanced, false otherwise.\n     * colB and rowB are respectively the multipliers for\n     * the column and the row in order to balance them.\n     * */\n    bool balanced( RealScalar colNorm, RealScalar rowNorm,\n        bool& isBalanced, RealScalar& colB, RealScalar& rowB );\n\n    /** Helper function for the balancing algorithm.\n     * \\returns true if the row and the column, having colNorm and rowNorm\n     * as norms, are balanced, false otherwise.\n     * colB and rowB are respectively the multipliers for\n     * the column and the row in order to balance them.\n     * */\n    bool balancedR( RealScalar colNorm, RealScalar rowNorm,\n        bool& isBalanced, RealScalar& colB, RealScalar& rowB );\n\n  public:\n    /**\n     * Balancing algorithm from B. N. PARLETT and C. REINSCH (1969)\n     * \"Balancing a matrix for calculation of eigenvalues and eigenvectors\"\n     * adapted to the case of companion matrices.\n     * A matrix with non zero row and non zero column is balanced\n     * for a certain norm if the i-th row and the i-th column\n     * have same norm for all i.\n     */\n    void balance();\n\n  protected:\n      RightColumn                m_monic;\n      BottomLeftDiagonal         m_bl_diag;\n};\n\n\n\ntemplate< typename Scalar_, int _Deg >\ninline\nbool companion<Scalar_,_Deg>::balanced( RealScalar colNorm, RealScalar rowNorm,\n    bool& isBalanced, RealScalar& colB, RealScalar& rowB )\n{\n  if( RealScalar(0) == colNorm || RealScalar(0) == rowNorm \n      || !(numext::isfinite)(colNorm) || !(numext::isfinite)(rowNorm)){\n    return true;\n  }\n  else\n  {\n    //To find the balancing coefficients, if the radix is 2,\n    //one finds \\f$ \\sigma \\f$ such that\n    // \\f$ 2^{2\\sigma-1} < rowNorm / colNorm \\le 2^{2\\sigma+1} \\f$\n    // then the balancing coefficient for the row is \\f$ 1/2^{\\sigma} \\f$\n    // and the balancing coefficient for the column is \\f$ 2^{\\sigma} \\f$\n    const RealScalar radix = RealScalar(2);\n    const RealScalar radix2 = RealScalar(4);\n    \n    rowB = rowNorm / radix;\n    colB = RealScalar(1);\n    const RealScalar s = colNorm + rowNorm;\n\n    // Find sigma s.t. rowNorm / 2 <= 2^(2*sigma) * colNorm\n    RealScalar scout = colNorm;\n    while (scout < rowB)\n    {\n      colB *= radix;\n      scout *= radix2;\n    }\n    \n    // We now have an upper-bound for sigma, try to lower it.\n    // Find sigma s.t. 2^(2*sigma) * colNorm / 2 < rowNorm\n    scout = colNorm * (colB / radix) * colB;  // Avoid overflow.\n    while (scout >= rowNorm)\n    {\n      colB /= radix;\n      scout /= radix2;\n    }\n\n    // This line is used to avoid insubstantial balancing.\n    if ((rowNorm + radix * scout) < RealScalar(0.95) * s * colB)\n    {\n      isBalanced = false;\n      rowB = RealScalar(1) / colB;\n      return false;\n    }\n    else\n    {\n      return true;\n    }\n  }\n}\n\ntemplate< typename Scalar_, int _Deg >\ninline\nbool companion<Scalar_,_Deg>::balancedR( RealScalar colNorm, RealScalar rowNorm,\n    bool& isBalanced, RealScalar& colB, RealScalar& rowB )\n{\n  if( RealScalar(0) == colNorm || RealScalar(0) == rowNorm ){ return true; }\n  else\n  {\n    /**\n     * Set the norm of the column and the row to the geometric mean\n     * of the row and column norm\n     */\n    const RealScalar q = colNorm/rowNorm;\n    if( !isApprox( q, Scalar_(1) ) )\n    {\n      rowB = sqrt( colNorm/rowNorm );\n      colB = RealScalar(1)/rowB;\n\n      isBalanced = false;\n      return false;\n    }\n    else{\n      return true; }\n  }\n}\n\n\ntemplate< typename Scalar_, int _Deg >\nvoid companion<Scalar_,_Deg>::balance()\n{\n  using std::abs;\n  EIGEN_STATIC_ASSERT( Deg == Dynamic || 1 < Deg, YOU_MADE_A_PROGRAMMING_MISTAKE );\n  const Index deg   = m_monic.size();\n  const Index deg_1 = deg-1;\n\n  bool hasConverged=false;\n  while( !hasConverged )\n  {\n    hasConverged = true;\n    RealScalar colNorm,rowNorm;\n    RealScalar colB,rowB;\n\n    //First row, first column excluding the diagonal\n    //==============================================\n    colNorm = abs(m_bl_diag[0]);\n    rowNorm = abs(m_monic[0]);\n\n    //Compute balancing of the row and the column\n    if( !balanced( colNorm, rowNorm, hasConverged, colB, rowB ) )\n    {\n      m_bl_diag[0] *= colB;\n      m_monic[0] *= rowB;\n    }\n\n    //Middle rows and columns excluding the diagonal\n    //==============================================\n    for( Index i=1; i<deg_1; ++i )\n    {\n      // column norm, excluding the diagonal\n      colNorm = abs(m_bl_diag[i]);\n\n      // row norm, excluding the diagonal\n      rowNorm = abs(m_bl_diag[i-1]) + abs(m_monic[i]);\n\n      //Compute balancing of the row and the column\n      if( !balanced( colNorm, rowNorm, hasConverged, colB, rowB ) )\n      {\n        m_bl_diag[i]   *= colB;\n        m_bl_diag[i-1] *= rowB;\n        m_monic[i]     *= rowB;\n      }\n    }\n\n    //Last row, last column excluding the diagonal\n    //============================================\n    const Index ebl = m_bl_diag.size()-1;\n    VectorBlock<RightColumn,Deg_1> headMonic( m_monic, 0, deg_1 );\n    colNorm = headMonic.array().abs().sum();\n    rowNorm = abs( m_bl_diag[ebl] );\n\n    //Compute balancing of the row and the column\n    if( !balanced( colNorm, rowNorm, hasConverged, colB, rowB ) )\n    {\n      headMonic      *= colB;\n      m_bl_diag[ebl] *= rowB;\n    }\n  }\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_COMPANION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/Polynomials/PolynomialSolver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Manuel Yguel <manuel.yguel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_POLYNOMIAL_SOLVER_H\n#define EIGEN_POLYNOMIAL_SOLVER_H\n\nnamespace Eigen { \n\n/** \\ingroup Polynomials_Module\n *  \\class PolynomialSolverBase.\n *\n * \\brief Defined to be inherited by polynomial solvers: it provides\n * convenient methods such as\n *  - real roots,\n *  - greatest, smallest complex roots,\n *  - real roots with greatest, smallest absolute real value,\n *  - greatest, smallest real roots.\n *\n * It stores the set of roots as a vector of complexes.\n *\n */\ntemplate< typename Scalar_, int _Deg >\nclass PolynomialSolverBase\n{\n  public:\n    EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(Scalar_,_Deg==Dynamic ? Dynamic : _Deg)\n\n    typedef Scalar_                             Scalar;\n    typedef typename NumTraits<Scalar>::Real    RealScalar;\n    typedef std::complex<RealScalar>            RootType;\n    typedef Matrix<RootType,_Deg,1>             RootsType;\n\n    typedef DenseIndex Index;\n\n  protected:\n    template< typename OtherPolynomial >\n    inline void setPolynomial( const OtherPolynomial& poly ){\n      m_roots.resize(poly.size()-1); }\n\n  public:\n    template< typename OtherPolynomial >\n    inline PolynomialSolverBase( const OtherPolynomial& poly ){\n      setPolynomial( poly() ); }\n\n    inline PolynomialSolverBase(){}\n\n  public:\n    /** \\returns the complex roots of the polynomial */\n    inline const RootsType& roots() const { return m_roots; }\n\n  public:\n    /** Clear and fills the back insertion sequence with the real roots of the polynomial\n     * i.e. the real part of the complex roots that have an imaginary part which\n     * absolute value is smaller than absImaginaryThreshold.\n     * absImaginaryThreshold takes the dummy_precision associated\n     * with the Scalar_ template parameter of the PolynomialSolver class as the default value.\n     *\n     * \\param[out] bi_seq : the back insertion sequence (stl concept)\n     * \\param[in]  absImaginaryThreshold : the maximum bound of the imaginary part of a complex\n     *  number that is considered as real.\n     * */\n    template<typename Stl_back_insertion_sequence>\n    inline void realRoots( Stl_back_insertion_sequence& bi_seq,\n        const RealScalar& absImaginaryThreshold = NumTraits<Scalar>::dummy_precision() ) const\n    {\n      using std::abs;\n      bi_seq.clear();\n      for(Index i=0; i<m_roots.size(); ++i )\n      {\n        if( abs( m_roots[i].imag() ) < absImaginaryThreshold ){\n          bi_seq.push_back( m_roots[i].real() ); }\n      }\n    }\n\n  protected:\n    template<typename squaredNormBinaryPredicate>\n    inline const RootType& selectComplexRoot_withRespectToNorm( squaredNormBinaryPredicate& pred ) const\n    {\n      Index res=0;\n      RealScalar norm2 = numext::abs2( m_roots[0] );\n      for( Index i=1; i<m_roots.size(); ++i )\n      {\n        const RealScalar currNorm2 = numext::abs2( m_roots[i] );\n        if( pred( currNorm2, norm2 ) ){\n          res=i; norm2=currNorm2; }\n      }\n      return m_roots[res];\n    }\n\n  public:\n    /**\n     * \\returns the complex root with greatest norm.\n     */\n    inline const RootType& greatestRoot() const\n    {\n      std::greater<RealScalar> greater;\n      return selectComplexRoot_withRespectToNorm( greater );\n    }\n\n    /**\n     * \\returns the complex root with smallest norm.\n     */\n    inline const RootType& smallestRoot() const\n    {\n      std::less<RealScalar> less;\n      return selectComplexRoot_withRespectToNorm( less );\n    }\n\n  protected:\n    template<typename squaredRealPartBinaryPredicate>\n    inline const RealScalar& selectRealRoot_withRespectToAbsRealPart(\n        squaredRealPartBinaryPredicate& pred,\n        bool& hasArealRoot,\n        const RealScalar& absImaginaryThreshold = NumTraits<Scalar>::dummy_precision() ) const\n    {\n      using std::abs;\n      hasArealRoot = false;\n      Index res=0;\n      RealScalar abs2(0);\n\n      for( Index i=0; i<m_roots.size(); ++i )\n      {\n        if( abs( m_roots[i].imag() ) <= absImaginaryThreshold )\n        {\n          if( !hasArealRoot )\n          {\n            hasArealRoot = true;\n            res = i;\n            abs2 = m_roots[i].real() * m_roots[i].real();\n          }\n          else\n          {\n            const RealScalar currAbs2 = m_roots[i].real() * m_roots[i].real();\n            if( pred( currAbs2, abs2 ) )\n            {\n              abs2 = currAbs2;\n              res = i;\n            }\n          }\n        }\n        else if(!hasArealRoot)\n        {\n          if( abs( m_roots[i].imag() ) < abs( m_roots[res].imag() ) ){\n            res = i;}\n        }\n      }\n      return numext::real_ref(m_roots[res]);\n    }\n\n\n    template<typename RealPartBinaryPredicate>\n    inline const RealScalar& selectRealRoot_withRespectToRealPart(\n        RealPartBinaryPredicate& pred,\n        bool& hasArealRoot,\n        const RealScalar& absImaginaryThreshold = NumTraits<Scalar>::dummy_precision() ) const\n    {\n      using std::abs;\n      hasArealRoot = false;\n      Index res=0;\n      RealScalar val(0);\n\n      for( Index i=0; i<m_roots.size(); ++i )\n      {\n        if( abs( m_roots[i].imag() ) <= absImaginaryThreshold )\n        {\n          if( !hasArealRoot )\n          {\n            hasArealRoot = true;\n            res = i;\n            val = m_roots[i].real();\n          }\n          else\n          {\n            const RealScalar curr = m_roots[i].real();\n            if( pred( curr, val ) )\n            {\n              val = curr;\n              res = i;\n            }\n          }\n        }\n        else\n        {\n          if( abs( m_roots[i].imag() ) < abs( m_roots[res].imag() ) ){\n            res = i; }\n        }\n      }\n      return numext::real_ref(m_roots[res]);\n    }\n\n  public:\n    /**\n     * \\returns a real root with greatest absolute magnitude.\n     * A real root is defined as the real part of a complex root with absolute imaginary\n     * part smallest than absImaginaryThreshold.\n     * absImaginaryThreshold takes the dummy_precision associated\n     * with the Scalar_ template parameter of the PolynomialSolver class as the default value.\n     * If no real root is found the boolean hasArealRoot is set to false and the real part of\n     * the root with smallest absolute imaginary part is returned instead.\n     *\n     * \\param[out] hasArealRoot : boolean true if a real root is found according to the\n     *  absImaginaryThreshold criterion, false otherwise.\n     * \\param[in] absImaginaryThreshold : threshold on the absolute imaginary part to decide\n     *  whether or not a root is real.\n     */\n    inline const RealScalar& absGreatestRealRoot(\n        bool& hasArealRoot,\n        const RealScalar& absImaginaryThreshold = NumTraits<Scalar>::dummy_precision() ) const\n    {\n      std::greater<RealScalar> greater;\n      return selectRealRoot_withRespectToAbsRealPart( greater, hasArealRoot, absImaginaryThreshold );\n    }\n\n\n    /**\n     * \\returns a real root with smallest absolute magnitude.\n     * A real root is defined as the real part of a complex root with absolute imaginary\n     * part smallest than absImaginaryThreshold.\n     * absImaginaryThreshold takes the dummy_precision associated\n     * with the Scalar_ template parameter of the PolynomialSolver class as the default value.\n     * If no real root is found the boolean hasArealRoot is set to false and the real part of\n     * the root with smallest absolute imaginary part is returned instead.\n     *\n     * \\param[out] hasArealRoot : boolean true if a real root is found according to the\n     *  absImaginaryThreshold criterion, false otherwise.\n     * \\param[in] absImaginaryThreshold : threshold on the absolute imaginary part to decide\n     *  whether or not a root is real.\n     */\n    inline const RealScalar& absSmallestRealRoot(\n        bool& hasArealRoot,\n        const RealScalar& absImaginaryThreshold = NumTraits<Scalar>::dummy_precision() ) const\n    {\n      std::less<RealScalar> less;\n      return selectRealRoot_withRespectToAbsRealPart( less, hasArealRoot, absImaginaryThreshold );\n    }\n\n\n    /**\n     * \\returns the real root with greatest value.\n     * A real root is defined as the real part of a complex root with absolute imaginary\n     * part smallest than absImaginaryThreshold.\n     * absImaginaryThreshold takes the dummy_precision associated\n     * with the Scalar_ template parameter of the PolynomialSolver class as the default value.\n     * If no real root is found the boolean hasArealRoot is set to false and the real part of\n     * the root with smallest absolute imaginary part is returned instead.\n     *\n     * \\param[out] hasArealRoot : boolean true if a real root is found according to the\n     *  absImaginaryThreshold criterion, false otherwise.\n     * \\param[in] absImaginaryThreshold : threshold on the absolute imaginary part to decide\n     *  whether or not a root is real.\n     */\n    inline const RealScalar& greatestRealRoot(\n        bool& hasArealRoot,\n        const RealScalar& absImaginaryThreshold = NumTraits<Scalar>::dummy_precision() ) const\n    {\n      std::greater<RealScalar> greater;\n      return selectRealRoot_withRespectToRealPart( greater, hasArealRoot, absImaginaryThreshold );\n    }\n\n\n    /**\n     * \\returns the real root with smallest value.\n     * A real root is defined as the real part of a complex root with absolute imaginary\n     * part smallest than absImaginaryThreshold.\n     * absImaginaryThreshold takes the dummy_precision associated\n     * with the Scalar_ template parameter of the PolynomialSolver class as the default value.\n     * If no real root is found the boolean hasArealRoot is set to false and the real part of\n     * the root with smallest absolute imaginary part is returned instead.\n     *\n     * \\param[out] hasArealRoot : boolean true if a real root is found according to the\n     *  absImaginaryThreshold criterion, false otherwise.\n     * \\param[in] absImaginaryThreshold : threshold on the absolute imaginary part to decide\n     *  whether or not a root is real.\n     */\n    inline const RealScalar& smallestRealRoot(\n        bool& hasArealRoot,\n        const RealScalar& absImaginaryThreshold = NumTraits<Scalar>::dummy_precision() ) const\n    {\n      std::less<RealScalar> less;\n      return selectRealRoot_withRespectToRealPart( less, hasArealRoot, absImaginaryThreshold );\n    }\n\n  protected:\n    RootsType               m_roots;\n};\n\n#define EIGEN_POLYNOMIAL_SOLVER_BASE_INHERITED_TYPES( BASE )  \\\n  typedef typename BASE::Scalar                 Scalar;       \\\n  typedef typename BASE::RealScalar             RealScalar;   \\\n  typedef typename BASE::RootType               RootType;     \\\n  typedef typename BASE::RootsType              RootsType;\n\n\n\n/** \\ingroup Polynomials_Module\n  *\n  * \\class PolynomialSolver\n  *\n  * \\brief A polynomial solver\n  *\n  * Computes the complex roots of a real polynomial.\n  *\n  * \\param Scalar_ the scalar type, i.e., the type of the polynomial coefficients\n  * \\param _Deg the degree of the polynomial, can be a compile time value or Dynamic.\n  *             Notice that the number of polynomial coefficients is _Deg+1.\n  *\n  * This class implements a polynomial solver and provides convenient methods such as\n  * - real roots,\n  * - greatest, smallest complex roots,\n  * - real roots with greatest, smallest absolute real value.\n  * - greatest, smallest real roots.\n  *\n  * WARNING: this polynomial solver is experimental, part of the unsupported Eigen modules.\n  *\n  *\n  * Currently a QR algorithm is used to compute the eigenvalues of the companion matrix of\n  * the polynomial to compute its roots.\n  * This supposes that the complex moduli of the roots are all distinct: e.g. there should\n  * be no multiple roots or conjugate roots for instance.\n  * With 32bit (float) floating types this problem shows up frequently.\n  * However, almost always, correct accuracy is reached even in these cases for 64bit\n  * (double) floating types and small polynomial degree (<20).\n  */\ntemplate<typename Scalar_, int _Deg>\nclass PolynomialSolver : public PolynomialSolverBase<Scalar_,_Deg>\n{\n  public:\n    EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(Scalar_,_Deg==Dynamic ? Dynamic : _Deg)\n\n    typedef PolynomialSolverBase<Scalar_,_Deg>    PS_Base;\n    EIGEN_POLYNOMIAL_SOLVER_BASE_INHERITED_TYPES( PS_Base )\n\n    typedef Matrix<Scalar,_Deg,_Deg>                 CompanionMatrixType;\n    typedef typename internal::conditional<NumTraits<Scalar>::IsComplex,\n                                          ComplexEigenSolver<CompanionMatrixType>,\n                                          EigenSolver<CompanionMatrixType> >::type EigenSolverType;\n    typedef typename internal::conditional<NumTraits<Scalar>::IsComplex, Scalar, std::complex<Scalar> >::type ComplexScalar;\n\n  public:\n    /** Computes the complex roots of a new polynomial. */\n    template< typename OtherPolynomial >\n    void compute( const OtherPolynomial& poly )\n    {\n      eigen_assert( Scalar(0) != poly[poly.size()-1] );\n      eigen_assert( poly.size() > 1 );\n      if(poly.size() >  2 )\n      {\n        internal::companion<Scalar,_Deg> companion( poly );\n        companion.balance();\n        m_eigenSolver.compute( companion.denseMatrix() );\n        m_roots = m_eigenSolver.eigenvalues();\n        // cleanup noise in imaginary part of real roots:\n        // if the imaginary part is rather small compared to the real part\n        // and that cancelling the imaginary part yield a smaller evaluation,\n        // then it's safe to keep the real part only.\n        RealScalar coarse_prec = RealScalar(std::pow(4,poly.size()+1))*NumTraits<RealScalar>::epsilon();\n        for(Index i = 0; i<m_roots.size(); ++i)\n        {\n          if( internal::isMuchSmallerThan(numext::abs(numext::imag(m_roots[i])),\n                                          numext::abs(numext::real(m_roots[i])),\n                                          coarse_prec) )\n          {\n            ComplexScalar as_real_root = ComplexScalar(numext::real(m_roots[i]));\n            if(    numext::abs(poly_eval(poly, as_real_root))\n                <= numext::abs(poly_eval(poly, m_roots[i])))\n            {\n              m_roots[i] = as_real_root;\n            }\n          }\n        }\n      }\n      else if(poly.size () == 2)\n      {\n        m_roots.resize(1);\n        m_roots[0] = -poly[0]/poly[1];\n      }\n    }\n\n  public:\n    template< typename OtherPolynomial >\n    inline PolynomialSolver( const OtherPolynomial& poly ){\n      compute( poly ); }\n\n    inline PolynomialSolver(){}\n\n  protected:\n    using                   PS_Base::m_roots;\n    EigenSolverType         m_eigenSolver;\n};\n\n\ntemplate< typename Scalar_ >\nclass PolynomialSolver<Scalar_,1> : public PolynomialSolverBase<Scalar_,1>\n{\n  public:\n    typedef PolynomialSolverBase<Scalar_,1>    PS_Base;\n    EIGEN_POLYNOMIAL_SOLVER_BASE_INHERITED_TYPES( PS_Base )\n\n  public:\n    /** Computes the complex roots of a new polynomial. */\n    template< typename OtherPolynomial >\n    void compute( const OtherPolynomial& poly )\n    {\n      eigen_assert( poly.size() == 2 );\n      eigen_assert( Scalar(0) != poly[1] );\n      m_roots[0] = -poly[0]/poly[1];\n    }\n\n  public:\n    template< typename OtherPolynomial >\n    inline PolynomialSolver( const OtherPolynomial& poly ){\n      compute( poly ); }\n\n    inline PolynomialSolver(){}\n\n  protected:\n    using                   PS_Base::m_roots;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_POLYNOMIAL_SOLVER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/Polynomials/PolynomialUtils.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Manuel Yguel <manuel.yguel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_POLYNOMIAL_UTILS_H\n#define EIGEN_POLYNOMIAL_UTILS_H\n\nnamespace Eigen { \n\n/** \\ingroup Polynomials_Module\n * \\returns the evaluation of the polynomial at x using Horner algorithm.\n *\n * \\param[in] poly : the vector of coefficients of the polynomial ordered\n *  by degrees i.e. poly[i] is the coefficient of degree i of the polynomial\n *  e.g. \\f$ 1 + 3x^2 \\f$ is stored as a vector \\f$ [ 1, 0, 3 ] \\f$.\n * \\param[in] x : the value to evaluate the polynomial at.\n *\n * \\note for stability:\n *   \\f$ |x| \\le 1 \\f$\n */\ntemplate <typename Polynomials, typename T>\ninline\nT poly_eval_horner( const Polynomials& poly, const T& x )\n{\n  T val=poly[poly.size()-1];\n  for(DenseIndex i=poly.size()-2; i>=0; --i ){\n    val = val*x + poly[i]; }\n  return val;\n}\n\n/** \\ingroup Polynomials_Module\n * \\returns the evaluation of the polynomial at x using stabilized Horner algorithm.\n *\n * \\param[in] poly : the vector of coefficients of the polynomial ordered\n *  by degrees i.e. poly[i] is the coefficient of degree i of the polynomial\n *  e.g. \\f$ 1 + 3x^2 \\f$ is stored as a vector \\f$ [ 1, 0, 3 ] \\f$.\n * \\param[in] x : the value to evaluate the polynomial at.\n */\ntemplate <typename Polynomials, typename T>\ninline\nT poly_eval( const Polynomials& poly, const T& x )\n{\n  typedef typename NumTraits<T>::Real Real;\n\n  if( numext::abs2( x ) <= Real(1) ){\n    return poly_eval_horner( poly, x ); }\n  else\n  {\n    T val=poly[0];\n    T inv_x = T(1)/x;\n    for( DenseIndex i=1; i<poly.size(); ++i ){\n      val = val*inv_x + poly[i]; }\n\n    return numext::pow(x,(T)(poly.size()-1)) * val;\n  }\n}\n\n/** \\ingroup Polynomials_Module\n * \\returns a maximum bound for the absolute value of any root of the polynomial.\n *\n * \\param[in] poly : the vector of coefficients of the polynomial ordered\n *  by degrees i.e. poly[i] is the coefficient of degree i of the polynomial\n *  e.g. \\f$ 1 + 3x^2 \\f$ is stored as a vector \\f$ [ 1, 0, 3 ] \\f$.\n *\n *  \\pre\n *   the leading coefficient of the input polynomial poly must be non zero\n */\ntemplate <typename Polynomial>\ninline\ntypename NumTraits<typename Polynomial::Scalar>::Real cauchy_max_bound( const Polynomial& poly )\n{\n  using std::abs;\n  typedef typename Polynomial::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real Real;\n\n  eigen_assert( Scalar(0) != poly[poly.size()-1] );\n  const Scalar inv_leading_coeff = Scalar(1)/poly[poly.size()-1];\n  Real cb(0);\n\n  for( DenseIndex i=0; i<poly.size()-1; ++i ){\n    cb += abs(poly[i]*inv_leading_coeff); }\n  return cb + Real(1);\n}\n\n/** \\ingroup Polynomials_Module\n * \\returns a minimum bound for the absolute value of any non zero root of the polynomial.\n * \\param[in] poly : the vector of coefficients of the polynomial ordered\n *  by degrees i.e. poly[i] is the coefficient of degree i of the polynomial\n *  e.g. \\f$ 1 + 3x^2 \\f$ is stored as a vector \\f$ [ 1, 0, 3 ] \\f$.\n */\ntemplate <typename Polynomial>\ninline\ntypename NumTraits<typename Polynomial::Scalar>::Real cauchy_min_bound( const Polynomial& poly )\n{\n  using std::abs;\n  typedef typename Polynomial::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real Real;\n\n  DenseIndex i=0;\n  while( i<poly.size()-1 && Scalar(0) == poly(i) ){ ++i; }\n  if( poly.size()-1 == i ){\n    return Real(1); }\n\n  const Scalar inv_min_coeff = Scalar(1)/poly[i];\n  Real cb(1);\n  for( DenseIndex j=i+1; j<poly.size(); ++j ){\n    cb += abs(poly[j]*inv_min_coeff); }\n  return Real(1)/cb;\n}\n\n/** \\ingroup Polynomials_Module\n * Given the roots of a polynomial compute the coefficients in the\n * monomial basis of the monic polynomial with same roots and minimal degree.\n * If RootVector is a vector of complexes, Polynomial should also be a vector\n * of complexes.\n * \\param[in] rv : a vector containing the roots of a polynomial.\n * \\param[out] poly : the vector of coefficients of the polynomial ordered\n *  by degrees i.e. poly[i] is the coefficient of degree i of the polynomial\n *  e.g. \\f$ 3 + x^2 \\f$ is stored as a vector \\f$ [ 3, 0, 1 ] \\f$.\n */\ntemplate <typename RootVector, typename Polynomial>\nvoid roots_to_monicPolynomial( const RootVector& rv, Polynomial& poly )\n{\n\n  typedef typename Polynomial::Scalar Scalar;\n\n  poly.setZero( rv.size()+1 );\n  poly[0] = -rv[0]; poly[1] = Scalar(1);\n  for( DenseIndex i=1; i< rv.size(); ++i )\n  {\n    for( DenseIndex j=i+1; j>0; --j ){ poly[j] = poly[j-1] - rv[i]*poly[j]; }\n    poly[0] = -rv[i]*poly[0];\n  }\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_POLYNOMIAL_UTILS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/Skyline/SkylineInplaceLU.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Guillaume Saupin <guillaume.saupin@cea.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SKYLINEINPLACELU_H\n#define EIGEN_SKYLINEINPLACELU_H\n\nnamespace Eigen { \n\n/** \\ingroup Skyline_Module\n *\n * \\class SkylineInplaceLU\n *\n * \\brief Inplace LU decomposition of a skyline matrix and associated features\n *\n * \\param MatrixType the type of the matrix of which we are computing the LU factorization\n *\n */\ntemplate<typename MatrixType>\nclass SkylineInplaceLU {\nprotected:\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::Index Index;\n    \n    typedef typename NumTraits<typename MatrixType::Scalar>::Real RealScalar;\n\npublic:\n\n    /** Creates a LU object and compute the respective factorization of \\a matrix using\n     * flags \\a flags. */\n    SkylineInplaceLU(MatrixType& matrix, int flags = 0)\n    : /*m_matrix(matrix.rows(), matrix.cols()),*/ m_flags(flags), m_status(0), m_lu(matrix) {\n        m_precision = RealScalar(0.1) * Eigen::dummy_precision<RealScalar > ();\n        m_lu.IsRowMajor ? computeRowMajor() : compute();\n    }\n\n    /** Sets the relative threshold value used to prune zero coefficients during the decomposition.\n     *\n     * Setting a value greater than zero speeds up computation, and yields to an incomplete\n     * factorization with fewer non zero coefficients. Such approximate factors are especially\n     * useful to initialize an iterative solver.\n     *\n     * Note that the exact meaning of this parameter might depends on the actual\n     * backend. Moreover, not all backends support this feature.\n     *\n     * \\sa precision() */\n    void setPrecision(RealScalar v) {\n        m_precision = v;\n    }\n\n    /** \\returns the current precision.\n     *\n     * \\sa setPrecision() */\n    RealScalar precision() const {\n        return m_precision;\n    }\n\n    /** Sets the flags. Possible values are:\n     *  - CompleteFactorization\n     *  - IncompleteFactorization\n     *  - MemoryEfficient\n     *  - one of the ordering methods\n     *  - etc...\n     *\n     * \\sa flags() */\n    void setFlags(int f) {\n        m_flags = f;\n    }\n\n    /** \\returns the current flags */\n    int flags() const {\n        return m_flags;\n    }\n\n    void setOrderingMethod(int m) {\n        m_flags = m;\n    }\n\n    int orderingMethod() const {\n        return m_flags;\n    }\n\n    /** Computes/re-computes the LU factorization */\n    void compute();\n    void computeRowMajor();\n\n    /** \\returns the lower triangular matrix L */\n    //inline const MatrixType& matrixL() const { return m_matrixL; }\n\n    /** \\returns the upper triangular matrix U */\n    //inline const MatrixType& matrixU() const { return m_matrixU; }\n\n    template<typename BDerived, typename XDerived>\n    bool solve(const MatrixBase<BDerived> &b, MatrixBase<XDerived>* x,\n            const int transposed = 0) const;\n\n    /** \\returns true if the factorization succeeded */\n    inline bool succeeded(void) const {\n        return m_succeeded;\n    }\n\nprotected:\n    RealScalar m_precision;\n    int m_flags;\n    mutable int m_status;\n    bool m_succeeded;\n    MatrixType& m_lu;\n};\n\n/** Computes / recomputes the in place LU decomposition of the SkylineInplaceLU.\n * using the default algorithm.\n */\ntemplate<typename MatrixType>\n//template<typename Scalar_>\nvoid SkylineInplaceLU<MatrixType>::compute() {\n    const size_t rows = m_lu.rows();\n    const size_t cols = m_lu.cols();\n\n    eigen_assert(rows == cols && \"We do not (yet) support rectangular LU.\");\n    eigen_assert(!m_lu.IsRowMajor && \"LU decomposition does not work with rowMajor Storage\");\n\n    for (Index row = 0; row < rows; row++) {\n        const double pivot = m_lu.coeffDiag(row);\n\n        //Lower matrix Columns update\n        const Index& col = row;\n        for (typename MatrixType::InnerLowerIterator lIt(m_lu, col); lIt; ++lIt) {\n            lIt.valueRef() /= pivot;\n        }\n\n        //Upper matrix update -> contiguous memory access\n        typename MatrixType::InnerLowerIterator lIt(m_lu, col);\n        for (Index rrow = row + 1; rrow < m_lu.rows(); rrow++) {\n            typename MatrixType::InnerUpperIterator uItPivot(m_lu, row);\n            typename MatrixType::InnerUpperIterator uIt(m_lu, rrow);\n            const double coef = lIt.value();\n\n            uItPivot += (rrow - row - 1);\n\n            //update upper part  -> contiguous memory access\n            for (++uItPivot; uIt && uItPivot;) {\n                uIt.valueRef() -= uItPivot.value() * coef;\n\n                ++uIt;\n                ++uItPivot;\n            }\n            ++lIt;\n        }\n\n        //Upper matrix update -> non contiguous memory access\n        typename MatrixType::InnerLowerIterator lIt3(m_lu, col);\n        for (Index rrow = row + 1; rrow < m_lu.rows(); rrow++) {\n            typename MatrixType::InnerUpperIterator uItPivot(m_lu, row);\n            const double coef = lIt3.value();\n\n            //update lower part ->  non contiguous memory access\n            for (Index i = 0; i < rrow - row - 1; i++) {\n                m_lu.coeffRefLower(rrow, row + i + 1) -= uItPivot.value() * coef;\n                ++uItPivot;\n            }\n            ++lIt3;\n        }\n        //update diag -> contiguous\n        typename MatrixType::InnerLowerIterator lIt2(m_lu, col);\n        for (Index rrow = row + 1; rrow < m_lu.rows(); rrow++) {\n\n            typename MatrixType::InnerUpperIterator uItPivot(m_lu, row);\n            typename MatrixType::InnerUpperIterator uIt(m_lu, rrow);\n            const double coef = lIt2.value();\n\n            uItPivot += (rrow - row - 1);\n            m_lu.coeffRefDiag(rrow) -= uItPivot.value() * coef;\n            ++lIt2;\n        }\n    }\n}\n\ntemplate<typename MatrixType>\nvoid SkylineInplaceLU<MatrixType>::computeRowMajor() {\n    const size_t rows = m_lu.rows();\n    const size_t cols = m_lu.cols();\n\n    eigen_assert(rows == cols && \"We do not (yet) support rectangular LU.\");\n    eigen_assert(m_lu.IsRowMajor && \"You're trying to apply rowMajor decomposition on a ColMajor matrix !\");\n\n    for (Index row = 0; row < rows; row++) {\n        typename MatrixType::InnerLowerIterator llIt(m_lu, row);\n\n\n        for (Index col = llIt.col(); col < row; col++) {\n            if (m_lu.coeffExistLower(row, col)) {\n                const double diag = m_lu.coeffDiag(col);\n\n                typename MatrixType::InnerLowerIterator lIt(m_lu, row);\n                typename MatrixType::InnerUpperIterator uIt(m_lu, col);\n\n\n                const Index offset = lIt.col() - uIt.row();\n\n\n                Index stop = offset > 0 ? col - lIt.col() : col - uIt.row();\n\n                //#define VECTORIZE\n#ifdef VECTORIZE\n                Map<VectorXd > rowVal(lIt.valuePtr() + (offset > 0 ? 0 : -offset), stop);\n                Map<VectorXd > colVal(uIt.valuePtr() + (offset > 0 ? offset : 0), stop);\n\n\n                Scalar newCoeff = m_lu.coeffLower(row, col) - rowVal.dot(colVal);\n#else\n                if (offset > 0) //Skip zero value of lIt\n                    uIt += offset;\n                else //Skip zero values of uIt\n                    lIt += -offset;\n                Scalar newCoeff = m_lu.coeffLower(row, col);\n\n                for (Index k = 0; k < stop; ++k) {\n                    const Scalar tmp = newCoeff;\n                    newCoeff = tmp - lIt.value() * uIt.value();\n                    ++lIt;\n                    ++uIt;\n                }\n#endif\n\n                m_lu.coeffRefLower(row, col) = newCoeff / diag;\n            }\n        }\n\n        //Upper matrix update\n        const Index col = row;\n        typename MatrixType::InnerUpperIterator uuIt(m_lu, col);\n        for (Index rrow = uuIt.row(); rrow < col; rrow++) {\n\n            typename MatrixType::InnerLowerIterator lIt(m_lu, rrow);\n            typename MatrixType::InnerUpperIterator uIt(m_lu, col);\n            const Index offset = lIt.col() - uIt.row();\n\n            Index stop = offset > 0 ? rrow - lIt.col() : rrow - uIt.row();\n\n#ifdef VECTORIZE\n            Map<VectorXd > rowVal(lIt.valuePtr() + (offset > 0 ? 0 : -offset), stop);\n            Map<VectorXd > colVal(uIt.valuePtr() + (offset > 0 ? offset : 0), stop);\n\n            Scalar newCoeff = m_lu.coeffUpper(rrow, col) - rowVal.dot(colVal);\n#else\n            if (offset > 0) //Skip zero value of lIt\n                uIt += offset;\n            else //Skip zero values of uIt\n                lIt += -offset;\n            Scalar newCoeff = m_lu.coeffUpper(rrow, col);\n            for (Index k = 0; k < stop; ++k) {\n                const Scalar tmp = newCoeff;\n                newCoeff = tmp - lIt.value() * uIt.value();\n\n                ++lIt;\n                ++uIt;\n            }\n#endif\n            m_lu.coeffRefUpper(rrow, col) = newCoeff;\n        }\n\n\n        //Diag matrix update\n        typename MatrixType::InnerLowerIterator lIt(m_lu, row);\n        typename MatrixType::InnerUpperIterator uIt(m_lu, row);\n\n        const Index offset = lIt.col() - uIt.row();\n\n\n        Index stop = offset > 0 ? lIt.size() : uIt.size();\n#ifdef VECTORIZE\n        Map<VectorXd > rowVal(lIt.valuePtr() + (offset > 0 ? 0 : -offset), stop);\n        Map<VectorXd > colVal(uIt.valuePtr() + (offset > 0 ? offset : 0), stop);\n        Scalar newCoeff = m_lu.coeffDiag(row) - rowVal.dot(colVal);\n#else\n        if (offset > 0) //Skip zero value of lIt\n            uIt += offset;\n        else //Skip zero values of uIt\n            lIt += -offset;\n        Scalar newCoeff = m_lu.coeffDiag(row);\n        for (Index k = 0; k < stop; ++k) {\n            const Scalar tmp = newCoeff;\n            newCoeff = tmp - lIt.value() * uIt.value();\n            ++lIt;\n            ++uIt;\n        }\n#endif\n        m_lu.coeffRefDiag(row) = newCoeff;\n    }\n}\n\n/** Computes *x = U^-1 L^-1 b\n *\n * If \\a transpose is set to SvTranspose or SvAdjoint, the solution\n * of the transposed/adjoint system is computed instead.\n *\n * Not all backends implement the solution of the transposed or\n * adjoint system.\n */\ntemplate<typename MatrixType>\ntemplate<typename BDerived, typename XDerived>\nbool SkylineInplaceLU<MatrixType>::solve(const MatrixBase<BDerived> &b, MatrixBase<XDerived>* x, const int transposed) const {\n    const size_t rows = m_lu.rows();\n    const size_t cols = m_lu.cols();\n\n\n    for (Index row = 0; row < rows; row++) {\n        x->coeffRef(row) = b.coeff(row);\n        Scalar newVal = x->coeff(row);\n        typename MatrixType::InnerLowerIterator lIt(m_lu, row);\n\n        Index col = lIt.col();\n        while (lIt.col() < row) {\n\n            newVal -= x->coeff(col++) * lIt.value();\n            ++lIt;\n        }\n\n        x->coeffRef(row) = newVal;\n    }\n\n\n    for (Index col = rows - 1; col > 0; col--) {\n        x->coeffRef(col) = x->coeff(col) / m_lu.coeffDiag(col);\n\n        const Scalar x_col = x->coeff(col);\n\n        typename MatrixType::InnerUpperIterator uIt(m_lu, col);\n        uIt += uIt.size()-1;\n\n\n        while (uIt) {\n            x->coeffRef(uIt.row()) -= x_col * uIt.value();\n            //TODO : introduce --operator\n            uIt += -1;\n        }\n\n\n    }\n    x->coeffRef(0) = x->coeff(0) / m_lu.coeffDiag(0);\n\n    return true;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SKYLINEINPLACELU_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/Skyline/SkylineMatrix.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Guillaume Saupin <guillaume.saupin@cea.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SKYLINEMATRIX_H\n#define EIGEN_SKYLINEMATRIX_H\n\n#include \"SkylineStorage.h\"\n#include \"SkylineMatrixBase.h\"\n\nnamespace Eigen { \n\n/** \\ingroup Skyline_Module\n *\n * \\class SkylineMatrix\n *\n * \\brief The main skyline matrix class\n *\n * This class implements a skyline matrix using the very uncommon storage\n * scheme.\n *\n * \\param Scalar_ the scalar type, i.e. the type of the coefficients\n * \\param Options_ Union of bit flags controlling the storage scheme. Currently the only possibility\n *                 is RowMajor. The default is 0 which means column-major.\n *\n *\n */\nnamespace internal {\ntemplate<typename Scalar_, int Options_>\nstruct traits<SkylineMatrix<Scalar_, Options_> > {\n    typedef Scalar_ Scalar;\n    typedef Sparse StorageKind;\n\n    enum {\n        RowsAtCompileTime = Dynamic,\n        ColsAtCompileTime = Dynamic,\n        MaxRowsAtCompileTime = Dynamic,\n        MaxColsAtCompileTime = Dynamic,\n        Flags = SkylineBit | Options_,\n        CoeffReadCost = NumTraits<Scalar>::ReadCost,\n    };\n};\n}\n\ntemplate<typename Scalar_, int Options_>\nclass SkylineMatrix\n: public SkylineMatrixBase<SkylineMatrix<Scalar_, Options_> > {\npublic:\n    EIGEN_SKYLINE_GENERIC_PUBLIC_INTERFACE(SkylineMatrix)\n    EIGEN_SKYLINE_INHERIT_ASSIGNMENT_OPERATOR(SkylineMatrix, +=)\n    EIGEN_SKYLINE_INHERIT_ASSIGNMENT_OPERATOR(SkylineMatrix, -=)\n\n    using Base::IsRowMajor;\n\nprotected:\n\n    typedef SkylineMatrix<Scalar, (Flags&~RowMajorBit) | (IsRowMajor ? RowMajorBit : 0) > TransposedSkylineMatrix;\n\n    Index m_outerSize;\n    Index m_innerSize;\n\npublic:\n    Index* m_colStartIndex;\n    Index* m_rowStartIndex;\n    SkylineStorage<Scalar> m_data;\n\npublic:\n\n    inline Index rows() const {\n        return IsRowMajor ? m_outerSize : m_innerSize;\n    }\n\n    inline Index cols() const {\n        return IsRowMajor ? m_innerSize : m_outerSize;\n    }\n\n    inline Index innerSize() const {\n        return m_innerSize;\n    }\n\n    inline Index outerSize() const {\n        return m_outerSize;\n    }\n\n    inline Index upperNonZeros() const {\n        return m_data.upperSize();\n    }\n\n    inline Index lowerNonZeros() const {\n        return m_data.lowerSize();\n    }\n\n    inline Index upperNonZeros(Index j) const {\n        return m_colStartIndex[j + 1] - m_colStartIndex[j];\n    }\n\n    inline Index lowerNonZeros(Index j) const {\n        return m_rowStartIndex[j + 1] - m_rowStartIndex[j];\n    }\n\n    inline const Scalar* _diagPtr() const {\n        return &m_data.diag(0);\n    }\n\n    inline Scalar* _diagPtr() {\n        return &m_data.diag(0);\n    }\n\n    inline const Scalar* _upperPtr() const {\n        return &m_data.upper(0);\n    }\n\n    inline Scalar* _upperPtr() {\n        return &m_data.upper(0);\n    }\n\n    inline const Scalar* _lowerPtr() const {\n        return &m_data.lower(0);\n    }\n\n    inline Scalar* _lowerPtr() {\n        return &m_data.lower(0);\n    }\n\n    inline const Index* _upperProfilePtr() const {\n        return &m_data.upperProfile(0);\n    }\n\n    inline Index* _upperProfilePtr() {\n        return &m_data.upperProfile(0);\n    }\n\n    inline const Index* _lowerProfilePtr() const {\n        return &m_data.lowerProfile(0);\n    }\n\n    inline Index* _lowerProfilePtr() {\n        return &m_data.lowerProfile(0);\n    }\n\n    inline Scalar coeff(Index row, Index col) const {\n        const Index outer = IsRowMajor ? row : col;\n        const Index inner = IsRowMajor ? col : row;\n\n        eigen_assert(outer < outerSize());\n        eigen_assert(inner < innerSize());\n\n        if (outer == inner)\n            return this->m_data.diag(outer);\n\n        if (IsRowMajor) {\n            if (inner > outer) //upper matrix\n            {\n                const Index minOuterIndex = inner - m_data.upperProfile(inner);\n                if (outer >= minOuterIndex)\n                    return this->m_data.upper(m_colStartIndex[inner] + outer - (inner - m_data.upperProfile(inner)));\n                else\n                    return Scalar(0);\n            }\n            if (inner < outer) //lower matrix\n            {\n                const Index minInnerIndex = outer - m_data.lowerProfile(outer);\n                if (inner >= minInnerIndex)\n                    return this->m_data.lower(m_rowStartIndex[outer] + inner - (outer - m_data.lowerProfile(outer)));\n                else\n                    return Scalar(0);\n            }\n            return m_data.upper(m_colStartIndex[inner] + outer - inner);\n        } else {\n            if (outer > inner) //upper matrix\n            {\n                const Index maxOuterIndex = inner + m_data.upperProfile(inner);\n                if (outer <= maxOuterIndex)\n                    return this->m_data.upper(m_colStartIndex[inner] + (outer - inner));\n                else\n                    return Scalar(0);\n            }\n            if (outer < inner) //lower matrix\n            {\n                const Index maxInnerIndex = outer + m_data.lowerProfile(outer);\n\n                if (inner <= maxInnerIndex)\n                    return this->m_data.lower(m_rowStartIndex[outer] + (inner - outer));\n                else\n                    return Scalar(0);\n            }\n        }\n    }\n\n    inline Scalar& coeffRef(Index row, Index col) {\n        const Index outer = IsRowMajor ? row : col;\n        const Index inner = IsRowMajor ? col : row;\n\n        eigen_assert(outer < outerSize());\n        eigen_assert(inner < innerSize());\n\n        if (outer == inner)\n            return this->m_data.diag(outer);\n\n        if (IsRowMajor) {\n            if (col > row) //upper matrix\n            {\n                const Index minOuterIndex = inner - m_data.upperProfile(inner);\n                eigen_assert(outer >= minOuterIndex && \"You tried to access a coeff that does not exist in the storage\");\n                return this->m_data.upper(m_colStartIndex[inner] + outer - (inner - m_data.upperProfile(inner)));\n            }\n            if (col < row) //lower matrix\n            {\n                const Index minInnerIndex = outer - m_data.lowerProfile(outer);\n                eigen_assert(inner >= minInnerIndex && \"You tried to access a coeff that does not exist in the storage\");\n                return this->m_data.lower(m_rowStartIndex[outer] + inner - (outer - m_data.lowerProfile(outer)));\n            }\n        } else {\n            if (outer > inner) //upper matrix\n            {\n                const Index maxOuterIndex = inner + m_data.upperProfile(inner);\n                eigen_assert(outer <= maxOuterIndex && \"You tried to access a coeff that does not exist in the storage\");\n                return this->m_data.upper(m_colStartIndex[inner] + (outer - inner));\n            }\n            if (outer < inner) //lower matrix\n            {\n                const Index maxInnerIndex = outer + m_data.lowerProfile(outer);\n                eigen_assert(inner <= maxInnerIndex && \"You tried to access a coeff that does not exist in the storage\");\n                return this->m_data.lower(m_rowStartIndex[outer] + (inner - outer));\n            }\n        }\n    }\n\n    inline Scalar coeffDiag(Index idx) const {\n        eigen_assert(idx < outerSize());\n        eigen_assert(idx < innerSize());\n        return this->m_data.diag(idx);\n    }\n\n    inline Scalar coeffLower(Index row, Index col) const {\n        const Index outer = IsRowMajor ? row : col;\n        const Index inner = IsRowMajor ? col : row;\n\n        eigen_assert(outer < outerSize());\n        eigen_assert(inner < innerSize());\n        eigen_assert(inner != outer);\n\n        if (IsRowMajor) {\n            const Index minInnerIndex = outer - m_data.lowerProfile(outer);\n            if (inner >= minInnerIndex)\n                return this->m_data.lower(m_rowStartIndex[outer] + inner - (outer - m_data.lowerProfile(outer)));\n            else\n                return Scalar(0);\n\n        } else {\n            const Index maxInnerIndex = outer + m_data.lowerProfile(outer);\n            if (inner <= maxInnerIndex)\n                return this->m_data.lower(m_rowStartIndex[outer] + (inner - outer));\n            else\n                return Scalar(0);\n        }\n    }\n\n    inline Scalar coeffUpper(Index row, Index col) const {\n        const Index outer = IsRowMajor ? row : col;\n        const Index inner = IsRowMajor ? col : row;\n\n        eigen_assert(outer < outerSize());\n        eigen_assert(inner < innerSize());\n        eigen_assert(inner != outer);\n\n        if (IsRowMajor) {\n            const Index minOuterIndex = inner - m_data.upperProfile(inner);\n            if (outer >= minOuterIndex)\n                return this->m_data.upper(m_colStartIndex[inner] + outer - (inner - m_data.upperProfile(inner)));\n            else\n                return Scalar(0);\n        } else {\n            const Index maxOuterIndex = inner + m_data.upperProfile(inner);\n            if (outer <= maxOuterIndex)\n                return this->m_data.upper(m_colStartIndex[inner] + (outer - inner));\n            else\n                return Scalar(0);\n        }\n    }\n\n    inline Scalar& coeffRefDiag(Index idx) {\n        eigen_assert(idx < outerSize());\n        eigen_assert(idx < innerSize());\n        return this->m_data.diag(idx);\n    }\n\n    inline Scalar& coeffRefLower(Index row, Index col) {\n        const Index outer = IsRowMajor ? row : col;\n        const Index inner = IsRowMajor ? col : row;\n\n        eigen_assert(outer < outerSize());\n        eigen_assert(inner < innerSize());\n        eigen_assert(inner != outer);\n\n        if (IsRowMajor) {\n            const Index minInnerIndex = outer - m_data.lowerProfile(outer);\n            eigen_assert(inner >= minInnerIndex && \"You tried to access a coeff that does not exist in the storage\");\n            return this->m_data.lower(m_rowStartIndex[outer] + inner - (outer - m_data.lowerProfile(outer)));\n        } else {\n            const Index maxInnerIndex = outer + m_data.lowerProfile(outer);\n            eigen_assert(inner <= maxInnerIndex && \"You tried to access a coeff that does not exist in the storage\");\n            return this->m_data.lower(m_rowStartIndex[outer] + (inner - outer));\n        }\n    }\n\n    inline bool coeffExistLower(Index row, Index col) {\n        const Index outer = IsRowMajor ? row : col;\n        const Index inner = IsRowMajor ? col : row;\n\n        eigen_assert(outer < outerSize());\n        eigen_assert(inner < innerSize());\n        eigen_assert(inner != outer);\n\n        if (IsRowMajor) {\n            const Index minInnerIndex = outer - m_data.lowerProfile(outer);\n            return inner >= minInnerIndex;\n        } else {\n            const Index maxInnerIndex = outer + m_data.lowerProfile(outer);\n            return inner <= maxInnerIndex;\n        }\n    }\n\n    inline Scalar& coeffRefUpper(Index row, Index col) {\n        const Index outer = IsRowMajor ? row : col;\n        const Index inner = IsRowMajor ? col : row;\n\n        eigen_assert(outer < outerSize());\n        eigen_assert(inner < innerSize());\n        eigen_assert(inner != outer);\n\n        if (IsRowMajor) {\n            const Index minOuterIndex = inner - m_data.upperProfile(inner);\n            eigen_assert(outer >= minOuterIndex && \"You tried to access a coeff that does not exist in the storage\");\n            return this->m_data.upper(m_colStartIndex[inner] + outer - (inner - m_data.upperProfile(inner)));\n        } else {\n            const Index maxOuterIndex = inner + m_data.upperProfile(inner);\n            eigen_assert(outer <= maxOuterIndex && \"You tried to access a coeff that does not exist in the storage\");\n            return this->m_data.upper(m_colStartIndex[inner] + (outer - inner));\n        }\n    }\n\n    inline bool coeffExistUpper(Index row, Index col) {\n        const Index outer = IsRowMajor ? row : col;\n        const Index inner = IsRowMajor ? col : row;\n\n        eigen_assert(outer < outerSize());\n        eigen_assert(inner < innerSize());\n        eigen_assert(inner != outer);\n\n        if (IsRowMajor) {\n            const Index minOuterIndex = inner - m_data.upperProfile(inner);\n            return outer >= minOuterIndex;\n        } else {\n            const Index maxOuterIndex = inner + m_data.upperProfile(inner);\n            return outer <= maxOuterIndex;\n        }\n    }\n\n\nprotected:\n\npublic:\n    class InnerUpperIterator;\n    class InnerLowerIterator;\n\n    class OuterUpperIterator;\n    class OuterLowerIterator;\n\n    /** Removes all non zeros */\n    inline void setZero() {\n        m_data.clear();\n        std::fill_n(m_colStartIndex, m_outerSize + 1, Index(0));\n        std::fill_n(m_rowStartIndex, m_outerSize + 1, Index(0));\n    }\n\n    /** \\returns the number of non zero coefficients */\n    inline Index nonZeros() const {\n        return m_data.diagSize() + m_data.upperSize() + m_data.lowerSize();\n    }\n\n    /** Preallocates \\a reserveSize non zeros */\n    inline void reserve(Index reserveSize, Index reserveUpperSize, Index reserveLowerSize) {\n        m_data.reserve(reserveSize, reserveUpperSize, reserveLowerSize);\n    }\n\n    /** \\returns a reference to a novel non zero coefficient with coordinates \\a row x \\a col.\n\n     *\n     * \\warning This function can be extremely slow if the non zero coefficients\n     * are not inserted in a coherent order.\n     *\n     * After an insertion session, you should call the finalize() function.\n     */\n    EIGEN_DONT_INLINE Scalar & insert(Index row, Index col) {\n        const Index outer = IsRowMajor ? row : col;\n        const Index inner = IsRowMajor ? col : row;\n\n        eigen_assert(outer < outerSize());\n        eigen_assert(inner < innerSize());\n\n        if (outer == inner)\n            return m_data.diag(col);\n\n        if (IsRowMajor) {\n            if (outer < inner) //upper matrix\n            {\n                Index minOuterIndex = 0;\n                minOuterIndex = inner - m_data.upperProfile(inner);\n\n                if (outer < minOuterIndex) //The value does not yet exist\n                {\n                    const Index previousProfile = m_data.upperProfile(inner);\n\n                    m_data.upperProfile(inner) = inner - outer;\n\n\n                    const Index bandIncrement = m_data.upperProfile(inner) - previousProfile;\n                    //shift data stored after this new one\n                    const Index stop = m_colStartIndex[cols()];\n                    const Index start = m_colStartIndex[inner];\n\n\n                    for (Index innerIdx = stop; innerIdx >= start; innerIdx--) {\n                        m_data.upper(innerIdx + bandIncrement) = m_data.upper(innerIdx);\n                    }\n\n                    for (Index innerIdx = cols(); innerIdx > inner; innerIdx--) {\n                        m_colStartIndex[innerIdx] += bandIncrement;\n                    }\n\n                    //zeros new data\n                    std::fill_n(this->_upperPtr() + start, bandIncrement - 1, Scalar(0));\n\n                    return m_data.upper(m_colStartIndex[inner]);\n                } else {\n                    return m_data.upper(m_colStartIndex[inner] + outer - (inner - m_data.upperProfile(inner)));\n                }\n            }\n\n            if (outer > inner) //lower matrix\n            {\n                const Index minInnerIndex = outer - m_data.lowerProfile(outer);\n                if (inner < minInnerIndex) //The value does not yet exist\n                {\n                    const Index previousProfile = m_data.lowerProfile(outer);\n                    m_data.lowerProfile(outer) = outer - inner;\n\n                    const Index bandIncrement = m_data.lowerProfile(outer) - previousProfile;\n                    //shift data stored after this new one\n                    const Index stop = m_rowStartIndex[rows()];\n                    const Index start = m_rowStartIndex[outer];\n\n\n                    for (Index innerIdx = stop; innerIdx >= start; innerIdx--) {\n                        m_data.lower(innerIdx + bandIncrement) = m_data.lower(innerIdx);\n                    }\n\n                    for (Index innerIdx = rows(); innerIdx > outer; innerIdx--) {\n                        m_rowStartIndex[innerIdx] += bandIncrement;\n                    }\n\n                    //zeros new data\n                    std::fill_n(this->_lowerPtr() + start, bandIncrement - 1, Scalar(0));\n                    return m_data.lower(m_rowStartIndex[outer]);\n                } else {\n                    return m_data.lower(m_rowStartIndex[outer] + inner - (outer - m_data.lowerProfile(outer)));\n                }\n            }\n        } else {\n            if (outer > inner) //upper matrix\n            {\n                const Index maxOuterIndex = inner + m_data.upperProfile(inner);\n                if (outer > maxOuterIndex) //The value does not yet exist\n                {\n                    const Index previousProfile = m_data.upperProfile(inner);\n                    m_data.upperProfile(inner) = outer - inner;\n\n                    const Index bandIncrement = m_data.upperProfile(inner) - previousProfile;\n                    //shift data stored after this new one\n                    const Index stop = m_rowStartIndex[rows()];\n                    const Index start = m_rowStartIndex[inner + 1];\n\n                    for (Index innerIdx = stop; innerIdx >= start; innerIdx--) {\n                        m_data.upper(innerIdx + bandIncrement) = m_data.upper(innerIdx);\n                    }\n\n                    for (Index innerIdx = inner + 1; innerIdx < outerSize() + 1; innerIdx++) {\n                        m_rowStartIndex[innerIdx] += bandIncrement;\n                    }\n                    std::fill_n(this->_upperPtr() + m_rowStartIndex[inner] + previousProfile + 1, bandIncrement - 1, Scalar(0));\n                    return m_data.upper(m_rowStartIndex[inner] + m_data.upperProfile(inner));\n                } else {\n                    return m_data.upper(m_rowStartIndex[inner] + (outer - inner));\n                }\n            }\n\n            if (outer < inner) //lower matrix\n            {\n                const Index maxInnerIndex = outer + m_data.lowerProfile(outer);\n                if (inner > maxInnerIndex) //The value does not yet exist\n                {\n                    const Index previousProfile = m_data.lowerProfile(outer);\n                    m_data.lowerProfile(outer) = inner - outer;\n\n                    const Index bandIncrement = m_data.lowerProfile(outer) - previousProfile;\n                    //shift data stored after this new one\n                    const Index stop = m_colStartIndex[cols()];\n                    const Index start = m_colStartIndex[outer + 1];\n\n                    for (Index innerIdx = stop; innerIdx >= start; innerIdx--) {\n                        m_data.lower(innerIdx + bandIncrement) = m_data.lower(innerIdx);\n                    }\n\n                    for (Index innerIdx = outer + 1; innerIdx < outerSize() + 1; innerIdx++) {\n                        m_colStartIndex[innerIdx] += bandIncrement;\n                    }\n                    std::fill_n(this->_lowerPtr() + m_colStartIndex[outer] + previousProfile + 1, bandIncrement - 1, Scalar(0));\n                    return m_data.lower(m_colStartIndex[outer] + m_data.lowerProfile(outer));\n                } else {\n                    return m_data.lower(m_colStartIndex[outer] + (inner - outer));\n                }\n            }\n        }\n    }\n\n    /** Must be called after inserting a set of non zero entries.\n     */\n    inline void finalize() {\n        if (IsRowMajor) {\n            if (rows() > cols())\n                m_data.resize(cols(), cols(), rows(), m_colStartIndex[cols()] + 1, m_rowStartIndex[rows()] + 1);\n            else\n                m_data.resize(rows(), cols(), rows(), m_colStartIndex[cols()] + 1, m_rowStartIndex[rows()] + 1);\n\n            //            eigen_assert(rows() == cols() && \"memory reorganisatrion only works with suare matrix\");\n            //\n            //            Scalar* newArray = new Scalar[m_colStartIndex[cols()] + 1 + m_rowStartIndex[rows()] + 1];\n            //            Index dataIdx = 0;\n            //            for (Index row = 0; row < rows(); row++) {\n            //\n            //                const Index nbLowerElts = m_rowStartIndex[row + 1] - m_rowStartIndex[row];\n            //                //                std::cout << \"nbLowerElts\" << nbLowerElts << std::endl;\n            //                memcpy(newArray + dataIdx, m_data.m_lower + m_rowStartIndex[row], nbLowerElts * sizeof (Scalar));\n            //                m_rowStartIndex[row] = dataIdx;\n            //                dataIdx += nbLowerElts;\n            //\n            //                const Index nbUpperElts = m_colStartIndex[row + 1] - m_colStartIndex[row];\n            //                memcpy(newArray + dataIdx, m_data.m_upper + m_colStartIndex[row], nbUpperElts * sizeof (Scalar));\n            //                m_colStartIndex[row] = dataIdx;\n            //                dataIdx += nbUpperElts;\n            //\n            //\n            //            }\n            //            //todo : don't access m_data profile directly : add an accessor from SkylineMatrix\n            //            m_rowStartIndex[rows()] = m_rowStartIndex[rows()-1] + m_data.lowerProfile(rows()-1);\n            //            m_colStartIndex[cols()] = m_colStartIndex[cols()-1] + m_data.upperProfile(cols()-1);\n            //\n            //            delete[] m_data.m_lower;\n            //            delete[] m_data.m_upper;\n            //\n            //            m_data.m_lower = newArray;\n            //            m_data.m_upper = newArray;\n        } else {\n            if (rows() > cols())\n                m_data.resize(cols(), rows(), cols(), m_rowStartIndex[cols()] + 1, m_colStartIndex[cols()] + 1);\n            else\n                m_data.resize(rows(), rows(), cols(), m_rowStartIndex[rows()] + 1, m_colStartIndex[rows()] + 1);\n        }\n    }\n\n    inline void squeeze() {\n        finalize();\n        m_data.squeeze();\n    }\n\n    void prune(Scalar reference, RealScalar epsilon = dummy_precision<RealScalar > ()) {\n        //TODO\n    }\n\n    /** Resizes the matrix to a \\a rows x \\a cols matrix and initializes it to zero\n     * \\sa resizeNonZeros(Index), reserve(), setZero()\n     */\n    void resize(size_t rows, size_t cols) {\n        const Index diagSize = rows > cols ? cols : rows;\n        m_innerSize = IsRowMajor ? cols : rows;\n\n        eigen_assert(rows == cols && \"Skyline matrix must be square matrix\");\n\n        if (diagSize % 2) { // diagSize is odd\n            const Index k = (diagSize - 1) / 2;\n\n            m_data.resize(diagSize, IsRowMajor ? cols : rows, IsRowMajor ? rows : cols,\n                    2 * k * k + k + 1,\n                    2 * k * k + k + 1);\n\n        } else // diagSize is even\n        {\n            const Index k = diagSize / 2;\n            m_data.resize(diagSize, IsRowMajor ? cols : rows, IsRowMajor ? rows : cols,\n                    2 * k * k - k + 1,\n                    2 * k * k - k + 1);\n        }\n\n        if (m_colStartIndex && m_rowStartIndex) {\n            delete[] m_colStartIndex;\n            delete[] m_rowStartIndex;\n        }\n        m_colStartIndex = new Index [cols + 1];\n        m_rowStartIndex = new Index [rows + 1];\n        m_outerSize = diagSize;\n\n        m_data.reset();\n        m_data.clear();\n\n        m_outerSize = diagSize;\n        std::fill_n(m_colStartIndex, cols + 1, Index(0));\n        std::fill_n(m_rowStartIndex, rows + 1, Index(0));\n    }\n\n    void resizeNonZeros(Index size) {\n        m_data.resize(size);\n    }\n\n    inline SkylineMatrix()\n    : m_outerSize(-1), m_innerSize(0), m_colStartIndex(0), m_rowStartIndex(0) {\n        resize(0, 0);\n    }\n\n    inline SkylineMatrix(size_t rows, size_t cols)\n    : m_outerSize(0), m_innerSize(0), m_colStartIndex(0), m_rowStartIndex(0) {\n        resize(rows, cols);\n    }\n\n    template<typename OtherDerived>\n    inline SkylineMatrix(const SkylineMatrixBase<OtherDerived>& other)\n    : m_outerSize(0), m_innerSize(0), m_colStartIndex(0), m_rowStartIndex(0) {\n        *this = other.derived();\n    }\n\n    inline SkylineMatrix(const SkylineMatrix & other)\n    : Base(), m_outerSize(0), m_innerSize(0), m_colStartIndex(0), m_rowStartIndex(0) {\n        *this = other.derived();\n    }\n\n    inline void swap(SkylineMatrix & other) {\n        //EIGEN_DBG_SKYLINE(std::cout << \"SkylineMatrix:: swap\\n\");\n        std::swap(m_colStartIndex, other.m_colStartIndex);\n        std::swap(m_rowStartIndex, other.m_rowStartIndex);\n        std::swap(m_innerSize, other.m_innerSize);\n        std::swap(m_outerSize, other.m_outerSize);\n        m_data.swap(other.m_data);\n    }\n\n    inline SkylineMatrix & operator=(const SkylineMatrix & other) {\n        std::cout << \"SkylineMatrix& operator=(const SkylineMatrix& other)\\n\";\n        if (other.isRValue()) {\n            swap(other.const_cast_derived());\n        } else {\n            resize(other.rows(), other.cols());\n            memcpy(m_colStartIndex, other.m_colStartIndex, (m_outerSize + 1) * sizeof (Index));\n            memcpy(m_rowStartIndex, other.m_rowStartIndex, (m_outerSize + 1) * sizeof (Index));\n            m_data = other.m_data;\n        }\n        return *this;\n    }\n\n    template<typename OtherDerived>\n            inline SkylineMatrix & operator=(const SkylineMatrixBase<OtherDerived>& other) {\n        const bool needToTranspose = (Flags & RowMajorBit) != (OtherDerived::Flags & RowMajorBit);\n        if (needToTranspose) {\n            //         TODO\n            //            return *this;\n        } else {\n            // there is no special optimization\n            return SkylineMatrixBase<SkylineMatrix>::operator=(other.derived());\n        }\n    }\n\n    friend std::ostream & operator <<(std::ostream & s, const SkylineMatrix & m) {\n\n        EIGEN_DBG_SKYLINE(\n        std::cout << \"upper elements : \" << std::endl;\n        for (Index i = 0; i < m.m_data.upperSize(); i++)\n            std::cout << m.m_data.upper(i) << \"\\t\";\n        std::cout << std::endl;\n        std::cout << \"upper profile : \" << std::endl;\n        for (Index i = 0; i < m.m_data.upperProfileSize(); i++)\n            std::cout << m.m_data.upperProfile(i) << \"\\t\";\n        std::cout << std::endl;\n        std::cout << \"lower startIdx : \" << std::endl;\n        for (Index i = 0; i < m.m_data.upperProfileSize(); i++)\n            std::cout << (IsRowMajor ? m.m_colStartIndex[i] : m.m_rowStartIndex[i]) << \"\\t\";\n        std::cout << std::endl;\n\n\n        std::cout << \"lower elements : \" << std::endl;\n        for (Index i = 0; i < m.m_data.lowerSize(); i++)\n            std::cout << m.m_data.lower(i) << \"\\t\";\n        std::cout << std::endl;\n        std::cout << \"lower profile : \" << std::endl;\n        for (Index i = 0; i < m.m_data.lowerProfileSize(); i++)\n            std::cout << m.m_data.lowerProfile(i) << \"\\t\";\n        std::cout << std::endl;\n        std::cout << \"lower startIdx : \" << std::endl;\n        for (Index i = 0; i < m.m_data.lowerProfileSize(); i++)\n            std::cout << (IsRowMajor ? m.m_rowStartIndex[i] : m.m_colStartIndex[i]) << \"\\t\";\n        std::cout << std::endl;\n        );\n        for (Index rowIdx = 0; rowIdx < m.rows(); rowIdx++) {\n            for (Index colIdx = 0; colIdx < m.cols(); colIdx++) {\n                s << m.coeff(rowIdx, colIdx) << \"\\t\";\n            }\n            s << std::endl;\n        }\n        return s;\n    }\n\n    /** Destructor */\n    inline ~SkylineMatrix() {\n        delete[] m_colStartIndex;\n        delete[] m_rowStartIndex;\n    }\n\n    /** Overloaded for performance */\n    Scalar sum() const;\n};\n\ntemplate<typename Scalar, int Options_>\nclass SkylineMatrix<Scalar, Options_>::InnerUpperIterator {\npublic:\n\n    InnerUpperIterator(const SkylineMatrix& mat, Index outer)\n    : m_matrix(mat), m_outer(outer),\n    m_id(Options_ == RowMajor ? mat.m_colStartIndex[outer] : mat.m_rowStartIndex[outer] + 1),\n    m_start(m_id),\n    m_end(Options_ == RowMajor ? mat.m_colStartIndex[outer + 1] : mat.m_rowStartIndex[outer + 1] + 1) {\n    }\n\n    inline InnerUpperIterator & operator++() {\n        m_id++;\n        return *this;\n    }\n\n    inline InnerUpperIterator & operator+=(Index shift) {\n        m_id += shift;\n        return *this;\n    }\n\n    inline Scalar value() const {\n        return m_matrix.m_data.upper(m_id);\n    }\n\n    inline Scalar* valuePtr() {\n        return const_cast<Scalar*> (&(m_matrix.m_data.upper(m_id)));\n    }\n\n    inline Scalar& valueRef() {\n        return const_cast<Scalar&> (m_matrix.m_data.upper(m_id));\n    }\n\n    inline Index index() const {\n        return IsRowMajor ? m_outer - m_matrix.m_data.upperProfile(m_outer) + (m_id - m_start) :\n                m_outer + (m_id - m_start) + 1;\n    }\n\n    inline Index row() const {\n        return IsRowMajor ? index() : m_outer;\n    }\n\n    inline Index col() const {\n        return IsRowMajor ? m_outer : index();\n    }\n\n    inline size_t size() const {\n        return m_matrix.m_data.upperProfile(m_outer);\n    }\n\n    inline operator bool() const {\n        return (m_id < m_end) && (m_id >= m_start);\n    }\n\nprotected:\n    const SkylineMatrix& m_matrix;\n    const Index m_outer;\n    Index m_id;\n    const Index m_start;\n    const Index m_end;\n};\n\ntemplate<typename Scalar, int Options_>\nclass SkylineMatrix<Scalar, Options_>::InnerLowerIterator {\npublic:\n\n    InnerLowerIterator(const SkylineMatrix& mat, Index outer)\n    : m_matrix(mat),\n    m_outer(outer),\n    m_id(Options_ == RowMajor ? mat.m_rowStartIndex[outer] : mat.m_colStartIndex[outer] + 1),\n    m_start(m_id),\n    m_end(Options_ == RowMajor ? mat.m_rowStartIndex[outer + 1] : mat.m_colStartIndex[outer + 1] + 1) {\n    }\n\n    inline InnerLowerIterator & operator++() {\n        m_id++;\n        return *this;\n    }\n\n    inline InnerLowerIterator & operator+=(Index shift) {\n        m_id += shift;\n        return *this;\n    }\n\n    inline Scalar value() const {\n        return m_matrix.m_data.lower(m_id);\n    }\n\n    inline Scalar* valuePtr() {\n        return const_cast<Scalar*> (&(m_matrix.m_data.lower(m_id)));\n    }\n\n    inline Scalar& valueRef() {\n        return const_cast<Scalar&> (m_matrix.m_data.lower(m_id));\n    }\n\n    inline Index index() const {\n        return IsRowMajor ? m_outer - m_matrix.m_data.lowerProfile(m_outer) + (m_id - m_start) :\n                m_outer + (m_id - m_start) + 1;\n        ;\n    }\n\n    inline Index row() const {\n        return IsRowMajor ? m_outer : index();\n    }\n\n    inline Index col() const {\n        return IsRowMajor ? index() : m_outer;\n    }\n\n    inline size_t size() const {\n        return m_matrix.m_data.lowerProfile(m_outer);\n    }\n\n    inline operator bool() const {\n        return (m_id < m_end) && (m_id >= m_start);\n    }\n\nprotected:\n    const SkylineMatrix& m_matrix;\n    const Index m_outer;\n    Index m_id;\n    const Index m_start;\n    const Index m_end;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_SKYLINEMATRIX_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/Skyline/SkylineMatrixBase.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Guillaume Saupin <guillaume.saupin@cea.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SKYLINEMATRIXBASE_H\n#define EIGEN_SKYLINEMATRIXBASE_H\n\n#include \"SkylineUtil.h\"\n\nnamespace Eigen {\n\n/** \\ingroup Skyline_Module\n *\n * \\class SkylineMatrixBase\n *\n * \\brief Base class of any skyline matrices or skyline expressions\n *\n * \\param Derived\n *\n */\ntemplate<typename Derived> class SkylineMatrixBase : public EigenBase<Derived> {\npublic:\n\n    typedef typename internal::traits<Derived>::Scalar Scalar;\n    typedef typename internal::traits<Derived>::StorageKind StorageKind;\n    typedef typename internal::index<StorageKind>::type Index;\n\n    enum {\n        RowsAtCompileTime = internal::traits<Derived>::RowsAtCompileTime,\n        /**< The number of rows at compile-time. This is just a copy of the value provided\n         * by the \\a Derived type. If a value is not known at compile-time,\n         * it is set to the \\a Dynamic constant.\n         * \\sa MatrixBase::rows(), MatrixBase::cols(), ColsAtCompileTime, SizeAtCompileTime */\n\n        ColsAtCompileTime = internal::traits<Derived>::ColsAtCompileTime,\n        /**< The number of columns at compile-time. This is just a copy of the value provided\n         * by the \\a Derived type. If a value is not known at compile-time,\n         * it is set to the \\a Dynamic constant.\n         * \\sa MatrixBase::rows(), MatrixBase::cols(), RowsAtCompileTime, SizeAtCompileTime */\n\n\n        SizeAtCompileTime = (internal::size_at_compile_time<internal::traits<Derived>::RowsAtCompileTime,\n        internal::traits<Derived>::ColsAtCompileTime>::ret),\n        /**< This is equal to the number of coefficients, i.e. the number of\n         * rows times the number of columns, or to \\a Dynamic if this is not\n         * known at compile-time. \\sa RowsAtCompileTime, ColsAtCompileTime */\n\n        MaxRowsAtCompileTime = RowsAtCompileTime,\n        MaxColsAtCompileTime = ColsAtCompileTime,\n\n        MaxSizeAtCompileTime = (internal::size_at_compile_time<MaxRowsAtCompileTime,\n        MaxColsAtCompileTime>::ret),\n\n        IsVectorAtCompileTime = RowsAtCompileTime == 1 || ColsAtCompileTime == 1,\n        /**< This is set to true if either the number of rows or the number of\n         * columns is known at compile-time to be equal to 1. Indeed, in that case,\n         * we are dealing with a column-vector (if there is only one column) or with\n         * a row-vector (if there is only one row). */\n\n        Flags = internal::traits<Derived>::Flags,\n        /**< This stores expression \\ref flags flags which may or may not be inherited by new expressions\n         * constructed from this one. See the \\ref flags \"list of flags\".\n         */\n\n        CoeffReadCost = internal::traits<Derived>::CoeffReadCost,\n        /**< This is a rough measure of how expensive it is to read one coefficient from\n         * this expression.\n         */\n\n        IsRowMajor = Flags & RowMajorBit ? 1 : 0\n    };\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n    /** This is the \"real scalar\" type; if the \\a Scalar type is already real numbers\n     * (e.g. int, float or double) then \\a RealScalar is just the same as \\a Scalar. If\n     * \\a Scalar is \\a std::complex<T> then RealScalar is \\a T.\n     *\n     * \\sa class NumTraits\n     */\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n\n    /** type of the equivalent square matrix */\n    typedef Matrix<Scalar, EIGEN_SIZE_MAX(RowsAtCompileTime, ColsAtCompileTime),\n                           EIGEN_SIZE_MAX(RowsAtCompileTime, ColsAtCompileTime) > SquareMatrixType;\n\n    inline const Derived& derived() const {\n        return *static_cast<const Derived*> (this);\n    }\n\n    inline Derived& derived() {\n        return *static_cast<Derived*> (this);\n    }\n\n    inline Derived& const_cast_derived() const {\n        return *static_cast<Derived*> (const_cast<SkylineMatrixBase*> (this));\n    }\n#endif // not EIGEN_PARSED_BY_DOXYGEN\n\n    /** \\returns the number of rows. \\sa cols(), RowsAtCompileTime */\n    inline EIGEN_CONSTEXPR Index rows() const EIGEN_NOEXCEPT {\n        return derived().rows();\n    }\n\n    /** \\returns the number of columns. \\sa rows(), ColsAtCompileTime*/\n    inline EIGEN_CONSTEXPR Index cols() const EIGEN_NOEXCEPT {\n        return derived().cols();\n    }\n\n    /** \\returns the number of coefficients, which is \\a rows()*cols().\n     * \\sa rows(), cols(), SizeAtCompileTime. */\n    inline EIGEN_CONSTEXPR Index size() const EIGEN_NOEXCEPT {\n        return rows() * cols();\n    }\n\n    /** \\returns the number of nonzero coefficients which is in practice the number\n     * of stored coefficients. */\n    inline Index nonZeros() const {\n        return derived().nonZeros();\n    }\n\n    /** \\returns the size of the storage major dimension,\n     * i.e., the number of columns for a columns major matrix, and the number of rows otherwise */\n    Index outerSize() const {\n        return (int(Flags) & RowMajorBit) ? this->rows() : this->cols();\n    }\n\n    /** \\returns the size of the inner dimension according to the storage order,\n     * i.e., the number of rows for a columns major matrix, and the number of cols otherwise */\n    Index innerSize() const {\n        return (int(Flags) & RowMajorBit) ? this->cols() : this->rows();\n    }\n\n    bool isRValue() const {\n        return m_isRValue;\n    }\n\n    Derived& markAsRValue() {\n        m_isRValue = true;\n        return derived();\n    }\n\n    SkylineMatrixBase() : m_isRValue(false) {\n        /* TODO check flags */\n    }\n\n    inline Derived & operator=(const Derived& other) {\n        this->operator=<Derived > (other);\n        return derived();\n    }\n\n    template<typename OtherDerived>\n    inline void assignGeneric(const OtherDerived& other) {\n        derived().resize(other.rows(), other.cols());\n        for (Index row = 0; row < rows(); row++)\n            for (Index col = 0; col < cols(); col++) {\n                if (other.coeff(row, col) != Scalar(0))\n                    derived().insert(row, col) = other.coeff(row, col);\n            }\n        derived().finalize();\n    }\n\n    template<typename OtherDerived>\n            inline Derived & operator=(const SkylineMatrixBase<OtherDerived>& other) {\n        //TODO\n    }\n\n    template<typename Lhs, typename Rhs>\n            inline Derived & operator=(const SkylineProduct<Lhs, Rhs, SkylineTimeSkylineProduct>& product);\n\n    friend std::ostream & operator <<(std::ostream & s, const SkylineMatrixBase& m) {\n        s << m.derived();\n        return s;\n    }\n\n    template<typename OtherDerived>\n    const typename SkylineProductReturnType<Derived, OtherDerived>::Type\n    operator*(const MatrixBase<OtherDerived> &other) const;\n\n    /** \\internal use operator= */\n    template<typename DenseDerived>\n    void evalTo(MatrixBase<DenseDerived>& dst) const {\n        dst.setZero();\n        for (Index i = 0; i < rows(); i++)\n            for (Index j = 0; j < rows(); j++)\n                dst(i, j) = derived().coeff(i, j);\n    }\n\n    Matrix<Scalar, RowsAtCompileTime, ColsAtCompileTime> toDense() const {\n        return derived();\n    }\n\n    /** \\returns the matrix or vector obtained by evaluating this expression.\n     *\n     * Notice that in the case of a plain matrix or vector (not an expression) this function just returns\n     * a const reference, in order to avoid a useless copy.\n     */\n    EIGEN_STRONG_INLINE const typename internal::eval<Derived, IsSkyline>::type eval() const {\n        return typename internal::eval<Derived>::type(derived());\n    }\n\nprotected:\n    bool m_isRValue;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_SKYLINEMATRIXBASE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/Skyline/SkylineProduct.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Guillaume Saupin <guillaume.saupin@cea.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SKYLINEPRODUCT_H\n#define EIGEN_SKYLINEPRODUCT_H\n\nnamespace Eigen { \n\ntemplate<typename Lhs, typename Rhs, int ProductMode>\nstruct SkylineProductReturnType {\n    typedef const typename internal::nested_eval<Lhs, Rhs::RowsAtCompileTime>::type LhsNested;\n    typedef const typename internal::nested_eval<Rhs, Lhs::RowsAtCompileTime>::type RhsNested;\n\n    typedef SkylineProduct<LhsNested, RhsNested, ProductMode> Type;\n};\n\ntemplate<typename LhsNested, typename RhsNested, int ProductMode>\nstruct internal::traits<SkylineProduct<LhsNested, RhsNested, ProductMode> > {\n    // clean the nested types:\n    typedef typename internal::remove_all<LhsNested>::type _LhsNested;\n    typedef typename internal::remove_all<RhsNested>::type _RhsNested;\n    typedef typename _LhsNested::Scalar Scalar;\n\n    enum {\n        LhsCoeffReadCost = _LhsNested::CoeffReadCost,\n        RhsCoeffReadCost = _RhsNested::CoeffReadCost,\n        LhsFlags = _LhsNested::Flags,\n        RhsFlags = _RhsNested::Flags,\n\n        RowsAtCompileTime = _LhsNested::RowsAtCompileTime,\n        ColsAtCompileTime = _RhsNested::ColsAtCompileTime,\n        InnerSize = EIGEN_SIZE_MIN_PREFER_FIXED(_LhsNested::ColsAtCompileTime, _RhsNested::RowsAtCompileTime),\n\n        MaxRowsAtCompileTime = _LhsNested::MaxRowsAtCompileTime,\n        MaxColsAtCompileTime = _RhsNested::MaxColsAtCompileTime,\n\n        EvalToRowMajor = (RhsFlags & LhsFlags & RowMajorBit),\n        ResultIsSkyline = ProductMode == SkylineTimeSkylineProduct,\n\n        RemovedBits = ~((EvalToRowMajor ? 0 : RowMajorBit) | (ResultIsSkyline ? 0 : SkylineBit)),\n\n        Flags = (int(LhsFlags | RhsFlags) & HereditaryBits & RemovedBits)\n        | EvalBeforeAssigningBit\n        | EvalBeforeNestingBit,\n\n        CoeffReadCost = HugeCost\n    };\n\n    typedef typename internal::conditional<ResultIsSkyline,\n            SkylineMatrixBase<SkylineProduct<LhsNested, RhsNested, ProductMode> >,\n            MatrixBase<SkylineProduct<LhsNested, RhsNested, ProductMode> > >::type Base;\n};\n\nnamespace internal {\ntemplate<typename LhsNested, typename RhsNested, int ProductMode>\nclass SkylineProduct : no_assignment_operator,\npublic traits<SkylineProduct<LhsNested, RhsNested, ProductMode> >::Base {\npublic:\n\n    EIGEN_GENERIC_PUBLIC_INTERFACE(SkylineProduct)\n\nprivate:\n\n    typedef typename traits<SkylineProduct>::_LhsNested _LhsNested;\n    typedef typename traits<SkylineProduct>::_RhsNested _RhsNested;\n\npublic:\n\n    template<typename Lhs, typename Rhs>\n    EIGEN_STRONG_INLINE SkylineProduct(const Lhs& lhs, const Rhs& rhs)\n    : m_lhs(lhs), m_rhs(rhs) {\n        eigen_assert(lhs.cols() == rhs.rows());\n\n        enum {\n            ProductIsValid = _LhsNested::ColsAtCompileTime == Dynamic\n            || _RhsNested::RowsAtCompileTime == Dynamic\n            || int(_LhsNested::ColsAtCompileTime) == int(_RhsNested::RowsAtCompileTime),\n            AreVectors = _LhsNested::IsVectorAtCompileTime && _RhsNested::IsVectorAtCompileTime,\n            SameSizes = EIGEN_PREDICATE_SAME_MATRIX_SIZE(_LhsNested, _RhsNested)\n        };\n        // note to the lost user:\n        //    * for a dot product use: v1.dot(v2)\n        //    * for a coeff-wise product use: v1.cwise()*v2\n        EIGEN_STATIC_ASSERT(ProductIsValid || !(AreVectors && SameSizes),\n                INVALID_VECTOR_VECTOR_PRODUCT__IF_YOU_WANTED_A_DOT_OR_COEFF_WISE_PRODUCT_YOU_MUST_USE_THE_EXPLICIT_FUNCTIONS)\n                EIGEN_STATIC_ASSERT(ProductIsValid || !(SameSizes && !AreVectors),\n                INVALID_MATRIX_PRODUCT__IF_YOU_WANTED_A_COEFF_WISE_PRODUCT_YOU_MUST_USE_THE_EXPLICIT_FUNCTION)\n                EIGEN_STATIC_ASSERT(ProductIsValid || SameSizes, INVALID_MATRIX_PRODUCT)\n    }\n\n    EIGEN_STRONG_INLINE Index rows() const {\n        return m_lhs.rows();\n    }\n\n    EIGEN_STRONG_INLINE Index cols() const {\n        return m_rhs.cols();\n    }\n\n    EIGEN_STRONG_INLINE const _LhsNested& lhs() const {\n        return m_lhs;\n    }\n\n    EIGEN_STRONG_INLINE const _RhsNested& rhs() const {\n        return m_rhs;\n    }\n\nprotected:\n    LhsNested m_lhs;\n    RhsNested m_rhs;\n};\n\n// dense = skyline * dense\n// Note that here we force no inlining and separate the setZero() because GCC messes up otherwise\n\ntemplate<typename Lhs, typename Rhs, typename Dest>\nEIGEN_DONT_INLINE void skyline_row_major_time_dense_product(const Lhs& lhs, const Rhs& rhs, Dest& dst) {\n    typedef typename remove_all<Lhs>::type Lhs_;\n    typedef typename remove_all<Rhs>::type Rhs_;\n    typedef typename traits<Lhs>::Scalar Scalar;\n\n    enum {\n        LhsIsRowMajor = (Lhs_::Flags & RowMajorBit) == RowMajorBit,\n        LhsIsSelfAdjoint = (Lhs_::Flags & SelfAdjointBit) == SelfAdjointBit,\n        ProcessFirstHalf = LhsIsSelfAdjoint\n        && (((Lhs_::Flags & (UpperTriangularBit | LowerTriangularBit)) == 0)\n        || ((Lhs_::Flags & UpperTriangularBit) && !LhsIsRowMajor)\n        || ((Lhs_::Flags & LowerTriangularBit) && LhsIsRowMajor)),\n        ProcessSecondHalf = LhsIsSelfAdjoint && (!ProcessFirstHalf)\n    };\n\n    //Use matrix diagonal part <- Improvement : use inner iterator on dense matrix.\n    for (Index col = 0; col < rhs.cols(); col++) {\n        for (Index row = 0; row < lhs.rows(); row++) {\n            dst(row, col) = lhs.coeffDiag(row) * rhs(row, col);\n        }\n    }\n    //Use matrix lower triangular part\n    for (Index row = 0; row < lhs.rows(); row++) {\n        typename Lhs_::InnerLowerIterator lIt(lhs, row);\n        const Index stop = lIt.col() + lIt.size();\n        for (Index col = 0; col < rhs.cols(); col++) {\n\n            Index k = lIt.col();\n            Scalar tmp = 0;\n            while (k < stop) {\n                tmp +=\n                        lIt.value() *\n                        rhs(k++, col);\n                ++lIt;\n            }\n            dst(row, col) += tmp;\n            lIt += -lIt.size();\n        }\n\n    }\n\n    //Use matrix upper triangular part\n    for (Index lhscol = 0; lhscol < lhs.cols(); lhscol++) {\n        typename Lhs_::InnerUpperIterator uIt(lhs, lhscol);\n        const Index stop = uIt.size() + uIt.row();\n        for (Index rhscol = 0; rhscol < rhs.cols(); rhscol++) {\n\n\n            const Scalar rhsCoeff = rhs.coeff(lhscol, rhscol);\n            Index k = uIt.row();\n            while (k < stop) {\n                dst(k++, rhscol) +=\n                        uIt.value() *\n                        rhsCoeff;\n                ++uIt;\n            }\n            uIt += -uIt.size();\n        }\n    }\n\n}\n\ntemplate<typename Lhs, typename Rhs, typename Dest>\nEIGEN_DONT_INLINE void skyline_col_major_time_dense_product(const Lhs& lhs, const Rhs& rhs, Dest& dst) {\n    typedef typename remove_all<Lhs>::type Lhs_;\n    typedef typename remove_all<Rhs>::type Rhs_;\n    typedef typename traits<Lhs>::Scalar Scalar;\n\n    enum {\n        LhsIsRowMajor = (Lhs_::Flags & RowMajorBit) == RowMajorBit,\n        LhsIsSelfAdjoint = (Lhs_::Flags & SelfAdjointBit) == SelfAdjointBit,\n        ProcessFirstHalf = LhsIsSelfAdjoint\n        && (((Lhs_::Flags & (UpperTriangularBit | LowerTriangularBit)) == 0)\n        || ((Lhs_::Flags & UpperTriangularBit) && !LhsIsRowMajor)\n        || ((Lhs_::Flags & LowerTriangularBit) && LhsIsRowMajor)),\n        ProcessSecondHalf = LhsIsSelfAdjoint && (!ProcessFirstHalf)\n    };\n\n    //Use matrix diagonal part <- Improvement : use inner iterator on dense matrix.\n    for (Index col = 0; col < rhs.cols(); col++) {\n        for (Index row = 0; row < lhs.rows(); row++) {\n            dst(row, col) = lhs.coeffDiag(row) * rhs(row, col);\n        }\n    }\n\n    //Use matrix upper triangular part\n    for (Index row = 0; row < lhs.rows(); row++) {\n        typename Lhs_::InnerUpperIterator uIt(lhs, row);\n        const Index stop = uIt.col() + uIt.size();\n        for (Index col = 0; col < rhs.cols(); col++) {\n\n            Index k = uIt.col();\n            Scalar tmp = 0;\n            while (k < stop) {\n                tmp +=\n                        uIt.value() *\n                        rhs(k++, col);\n                ++uIt;\n            }\n\n\n            dst(row, col) += tmp;\n            uIt += -uIt.size();\n        }\n    }\n\n    //Use matrix lower triangular part\n    for (Index lhscol = 0; lhscol < lhs.cols(); lhscol++) {\n        typename Lhs_::InnerLowerIterator lIt(lhs, lhscol);\n        const Index stop = lIt.size() + lIt.row();\n        for (Index rhscol = 0; rhscol < rhs.cols(); rhscol++) {\n\n            const Scalar rhsCoeff = rhs.coeff(lhscol, rhscol);\n            Index k = lIt.row();\n            while (k < stop) {\n                dst(k++, rhscol) +=\n                        lIt.value() *\n                        rhsCoeff;\n                ++lIt;\n            }\n            lIt += -lIt.size();\n        }\n    }\n\n}\n\ntemplate<typename Lhs, typename Rhs, typename ResultType,\n        int LhsStorageOrder = traits<Lhs>::Flags&RowMajorBit>\n        struct skyline_product_selector;\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct skyline_product_selector<Lhs, Rhs, ResultType, RowMajor> {\n    typedef typename traits<typename remove_all<Lhs>::type>::Scalar Scalar;\n\n    static void run(const Lhs& lhs, const Rhs& rhs, ResultType & res) {\n        skyline_row_major_time_dense_product<Lhs, Rhs, ResultType > (lhs, rhs, res);\n    }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct skyline_product_selector<Lhs, Rhs, ResultType, ColMajor> {\n    typedef typename traits<typename remove_all<Lhs>::type>::Scalar Scalar;\n\n    static void run(const Lhs& lhs, const Rhs& rhs, ResultType & res) {\n        skyline_col_major_time_dense_product<Lhs, Rhs, ResultType > (lhs, rhs, res);\n    }\n};\n\n} // end namespace internal\n\n// template<typename Derived>\n// template<typename Lhs, typename Rhs >\n// Derived & MatrixBase<Derived>::lazyAssign(const SkylineProduct<Lhs, Rhs, SkylineTimeDenseProduct>& product) {\n//     typedef typename internal::remove_all<Lhs>::type Lhs_;\n//     internal::skyline_product_selector<typename internal::remove_all<Lhs>::type,\n//             typename internal::remove_all<Rhs>::type,\n//             Derived>::run(product.lhs(), product.rhs(), derived());\n// \n//     return derived();\n// }\n\n// skyline * dense\n\ntemplate<typename Derived>\ntemplate<typename OtherDerived >\nEIGEN_STRONG_INLINE const typename SkylineProductReturnType<Derived, OtherDerived>::Type\nSkylineMatrixBase<Derived>::operator*(const MatrixBase<OtherDerived> &other) const {\n\n    return typename SkylineProductReturnType<Derived, OtherDerived>::Type(derived(), other.derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SKYLINEPRODUCT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/Skyline/SkylineStorage.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Guillaume Saupin <guillaume.saupin@cea.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SKYLINE_STORAGE_H\n#define EIGEN_SKYLINE_STORAGE_H\n\nnamespace Eigen { \n\n/** Stores a skyline set of values in three structures :\n * The diagonal elements\n * The upper elements\n * The lower elements\n *\n */\ntemplate<typename Scalar>\nclass SkylineStorage {\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef SparseIndex Index;\npublic:\n\n    SkylineStorage()\n    : m_diag(0),\n    m_lower(0),\n    m_upper(0),\n    m_lowerProfile(0),\n    m_upperProfile(0),\n    m_diagSize(0),\n    m_upperSize(0),\n    m_lowerSize(0),\n    m_upperProfileSize(0),\n    m_lowerProfileSize(0),\n    m_allocatedSize(0) {\n    }\n\n    SkylineStorage(const SkylineStorage& other)\n    : m_diag(0),\n    m_lower(0),\n    m_upper(0),\n    m_lowerProfile(0),\n    m_upperProfile(0),\n    m_diagSize(0),\n    m_upperSize(0),\n    m_lowerSize(0),\n    m_upperProfileSize(0),\n    m_lowerProfileSize(0),\n    m_allocatedSize(0) {\n        *this = other;\n    }\n\n    SkylineStorage & operator=(const SkylineStorage& other) {\n        resize(other.diagSize(), other.m_upperProfileSize, other.m_lowerProfileSize, other.upperSize(), other.lowerSize());\n        memcpy(m_diag, other.m_diag, m_diagSize * sizeof (Scalar));\n        memcpy(m_upper, other.m_upper, other.upperSize() * sizeof (Scalar));\n        memcpy(m_lower, other.m_lower, other.lowerSize() * sizeof (Scalar));\n        memcpy(m_upperProfile, other.m_upperProfile, m_upperProfileSize * sizeof (Index));\n        memcpy(m_lowerProfile, other.m_lowerProfile, m_lowerProfileSize * sizeof (Index));\n        return *this;\n    }\n\n    void swap(SkylineStorage& other) {\n        std::swap(m_diag, other.m_diag);\n        std::swap(m_upper, other.m_upper);\n        std::swap(m_lower, other.m_lower);\n        std::swap(m_upperProfile, other.m_upperProfile);\n        std::swap(m_lowerProfile, other.m_lowerProfile);\n        std::swap(m_diagSize, other.m_diagSize);\n        std::swap(m_upperSize, other.m_upperSize);\n        std::swap(m_lowerSize, other.m_lowerSize);\n        std::swap(m_allocatedSize, other.m_allocatedSize);\n    }\n\n    ~SkylineStorage() {\n        delete[] m_diag;\n        delete[] m_upper;\n        if (m_upper != m_lower)\n            delete[] m_lower;\n        delete[] m_upperProfile;\n        delete[] m_lowerProfile;\n    }\n\n    void reserve(Index size, Index upperProfileSize, Index lowerProfileSize, Index upperSize, Index lowerSize) {\n        Index newAllocatedSize = size + upperSize + lowerSize;\n        if (newAllocatedSize > m_allocatedSize)\n            reallocate(size, upperProfileSize, lowerProfileSize, upperSize, lowerSize);\n    }\n\n    void squeeze() {\n        if (m_allocatedSize > m_diagSize + m_upperSize + m_lowerSize)\n            reallocate(m_diagSize, m_upperProfileSize, m_lowerProfileSize, m_upperSize, m_lowerSize);\n    }\n\n    void resize(Index diagSize, Index upperProfileSize, Index lowerProfileSize, Index upperSize, Index lowerSize, float reserveSizeFactor = 0) {\n        if (m_allocatedSize < diagSize + upperSize + lowerSize)\n            reallocate(diagSize, upperProfileSize, lowerProfileSize, upperSize + Index(reserveSizeFactor * upperSize), lowerSize + Index(reserveSizeFactor * lowerSize));\n        m_diagSize = diagSize;\n        m_upperSize = upperSize;\n        m_lowerSize = lowerSize;\n        m_upperProfileSize = upperProfileSize;\n        m_lowerProfileSize = lowerProfileSize;\n    }\n\n    inline Index diagSize() const {\n        return m_diagSize;\n    }\n\n    inline Index upperSize() const {\n        return m_upperSize;\n    }\n\n    inline Index lowerSize() const {\n        return m_lowerSize;\n    }\n\n    inline Index upperProfileSize() const {\n        return m_upperProfileSize;\n    }\n\n    inline Index lowerProfileSize() const {\n        return m_lowerProfileSize;\n    }\n\n    inline Index allocatedSize() const {\n        return m_allocatedSize;\n    }\n\n    inline void clear() {\n        m_diagSize = 0;\n    }\n\n    inline Scalar& diag(Index i) {\n        return m_diag[i];\n    }\n\n    inline const Scalar& diag(Index i) const {\n        return m_diag[i];\n    }\n\n    inline Scalar& upper(Index i) {\n        return m_upper[i];\n    }\n\n    inline const Scalar& upper(Index i) const {\n        return m_upper[i];\n    }\n\n    inline Scalar& lower(Index i) {\n        return m_lower[i];\n    }\n\n    inline const Scalar& lower(Index i) const {\n        return m_lower[i];\n    }\n\n    inline Index& upperProfile(Index i) {\n        return m_upperProfile[i];\n    }\n\n    inline const Index& upperProfile(Index i) const {\n        return m_upperProfile[i];\n    }\n\n    inline Index& lowerProfile(Index i) {\n        return m_lowerProfile[i];\n    }\n\n    inline const Index& lowerProfile(Index i) const {\n        return m_lowerProfile[i];\n    }\n\n    static SkylineStorage Map(Index* upperProfile, Index* lowerProfile, Scalar* diag, Scalar* upper, Scalar* lower, Index size, Index upperSize, Index lowerSize) {\n        SkylineStorage res;\n        res.m_upperProfile = upperProfile;\n        res.m_lowerProfile = lowerProfile;\n        res.m_diag = diag;\n        res.m_upper = upper;\n        res.m_lower = lower;\n        res.m_allocatedSize = res.m_diagSize = size;\n        res.m_upperSize = upperSize;\n        res.m_lowerSize = lowerSize;\n        return res;\n    }\n\n    inline void reset() {\n        std::fill_n(m_diag, m_diagSize, Scalar(0));\n        std::fill_n(m_upper, m_upperSize, Scalar(0));\n        std::fill_n(m_lower, m_lowerSize, Scalar(0));\n        std::fill_n(m_upperProfile, m_diagSize, Index(0));\n        std::fill_n(m_lowerProfile, m_diagSize, Index(0));\n    }\n\n    void prune(Scalar reference, RealScalar epsilon = dummy_precision<RealScalar>()) {\n        //TODO\n    }\n\nprotected:\n\n    inline void reallocate(Index diagSize, Index upperProfileSize, Index lowerProfileSize, Index upperSize, Index lowerSize) {\n\n        Scalar* diag = new Scalar[diagSize];\n        Scalar* upper = new Scalar[upperSize];\n        Scalar* lower = new Scalar[lowerSize];\n        Index* upperProfile = new Index[upperProfileSize];\n        Index* lowerProfile = new Index[lowerProfileSize];\n\n        Index copyDiagSize = (std::min)(diagSize, m_diagSize);\n        Index copyUpperSize = (std::min)(upperSize, m_upperSize);\n        Index copyLowerSize = (std::min)(lowerSize, m_lowerSize);\n        Index copyUpperProfileSize = (std::min)(upperProfileSize, m_upperProfileSize);\n        Index copyLowerProfileSize = (std::min)(lowerProfileSize, m_lowerProfileSize);\n\n        // copy\n        memcpy(diag, m_diag, copyDiagSize * sizeof (Scalar));\n        memcpy(upper, m_upper, copyUpperSize * sizeof (Scalar));\n        memcpy(lower, m_lower, copyLowerSize * sizeof (Scalar));\n        memcpy(upperProfile, m_upperProfile, copyUpperProfileSize * sizeof (Index));\n        memcpy(lowerProfile, m_lowerProfile, copyLowerProfileSize * sizeof (Index));\n\n\n\n        // delete old stuff\n        delete[] m_diag;\n        delete[] m_upper;\n        delete[] m_lower;\n        delete[] m_upperProfile;\n        delete[] m_lowerProfile;\n        m_diag = diag;\n        m_upper = upper;\n        m_lower = lower;\n        m_upperProfile = upperProfile;\n        m_lowerProfile = lowerProfile;\n        m_allocatedSize = diagSize + upperSize + lowerSize;\n        m_upperSize = upperSize;\n        m_lowerSize = lowerSize;\n    }\n\npublic:\n    Scalar* m_diag;\n    Scalar* m_upper;\n    Scalar* m_lower;\n    Index* m_upperProfile;\n    Index* m_lowerProfile;\n    Index m_diagSize;\n    Index m_upperSize;\n    Index m_lowerSize;\n    Index m_upperProfileSize;\n    Index m_lowerProfileSize;\n    Index m_allocatedSize;\n\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_SKYLINE_STORAGE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/Skyline/SkylineUtil.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Guillaume Saupin <guillaume.saupin@cea.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SKYLINEUTIL_H\n#define EIGEN_SKYLINEUTIL_H\n\nnamespace Eigen { \n\n#ifdef NDEBUG\n#define EIGEN_DBG_SKYLINE(X)\n#else\n#define EIGEN_DBG_SKYLINE(X) X\n#endif\n\nconst unsigned int SkylineBit = 0x1200;\ntemplate<typename Lhs, typename Rhs, int ProductMode> class SkylineProduct;\nenum AdditionalProductEvaluationMode {SkylineTimeDenseProduct, SkylineTimeSkylineProduct, DenseTimeSkylineProduct};\nenum {IsSkyline = SkylineBit};\n\n\n#define EIGEN_SKYLINE_INHERIT_ASSIGNMENT_OPERATOR(Derived, Op) \\\ntemplate<typename OtherDerived> \\\nEIGEN_STRONG_INLINE Derived& operator Op(const Eigen::SkylineMatrixBase<OtherDerived>& other) \\\n{ \\\n  return Base::operator Op(other.derived()); \\\n} \\\nEIGEN_STRONG_INLINE Derived& operator Op(const Derived& other) \\\n{ \\\n  return Base::operator Op(other); \\\n}\n\n#define EIGEN_SKYLINE_INHERIT_SCALAR_ASSIGNMENT_OPERATOR(Derived, Op) \\\ntemplate<typename Other> \\\nEIGEN_STRONG_INLINE Derived& operator Op(const Other& scalar) \\\n{ \\\n  return Base::operator Op(scalar); \\\n}\n\n#define EIGEN_SKYLINE_INHERIT_ASSIGNMENT_OPERATORS(Derived) \\\n  EIGEN_SKYLINE_INHERIT_ASSIGNMENT_OPERATOR(Derived, =) \\\n  EIGEN_SKYLINE_INHERIT_ASSIGNMENT_OPERATOR(Derived, +=) \\\n  EIGEN_SKYLINE_INHERIT_ASSIGNMENT_OPERATOR(Derived, -=) \\\n  EIGEN_SKYLINE_INHERIT_SCALAR_ASSIGNMENT_OPERATOR(Derived, *=) \\\n  EIGEN_SKYLINE_INHERIT_SCALAR_ASSIGNMENT_OPERATOR(Derived, /=)\n\n#define _EIGEN_SKYLINE_GENERIC_PUBLIC_INTERFACE(Derived, BaseClass) \\\n  typedef BaseClass Base; \\\n  typedef typename Eigen::internal::traits<Derived>::Scalar Scalar; \\\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar; \\\n  typedef typename Eigen::internal::traits<Derived>::StorageKind StorageKind; \\\n  typedef typename Eigen::internal::index<StorageKind>::type Index; \\\n  enum {  Flags = Eigen::internal::traits<Derived>::Flags, };\n\n#define EIGEN_SKYLINE_GENERIC_PUBLIC_INTERFACE(Derived) \\\n  _EIGEN_SKYLINE_GENERIC_PUBLIC_INTERFACE(Derived, Eigen::SkylineMatrixBase<Derived>)\n\ntemplate<typename Derived> class SkylineMatrixBase;\ntemplate<typename Scalar_, int _Flags = 0> class SkylineMatrix;\ntemplate<typename Scalar_, int _Flags = 0> class DynamicSkylineMatrix;\ntemplate<typename Scalar_, int _Flags = 0> class SkylineVector;\ntemplate<typename Scalar_, int _Flags = 0> class MappedSkylineMatrix;\n\nnamespace internal {\n\ntemplate<typename Lhs, typename Rhs> struct skyline_product_mode;\ntemplate<typename Lhs, typename Rhs, int ProductMode = skyline_product_mode<Lhs,Rhs>::value> struct SkylineProductReturnType;\n\ntemplate<typename T> class eval<T,IsSkyline>\n{\n    typedef typename traits<T>::Scalar Scalar_;\n    enum {\n          _Flags = traits<T>::Flags\n    };\n\n  public:\n    typedef SkylineMatrix<Scalar_, _Flags> type;\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SKYLINEUTIL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SparseExtra/BlockSparseMatrix.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Desire Nuentsa <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2013 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEBLOCKMATRIX_H\n#define EIGEN_SPARSEBLOCKMATRIX_H\n\nnamespace Eigen { \n/** \\ingroup SparseCore_Module\n  *\n  * \\class BlockSparseMatrix\n  *\n  * \\brief A versatile sparse matrix representation where each element is a block\n  *\n  * This class provides routines to manipulate block sparse matrices stored in a\n  * BSR-like representation. There are two main types :\n  *\n  * 1. All blocks have the same number of rows and columns, called block size\n  * in the following. In this case, if this block size is known at compile time,\n  * it can be given as a template parameter like\n  * \\code\n  * BlockSparseMatrix<Scalar, 3, ColMajor> bmat(b_rows, b_cols);\n  * \\endcode\n  * Here, bmat is a b_rows x b_cols block sparse matrix\n  * where each coefficient is a 3x3 dense matrix.\n  * If the block size is fixed but will be given at runtime,\n  * \\code\n  * BlockSparseMatrix<Scalar, Dynamic, ColMajor> bmat(b_rows, b_cols);\n  * bmat.setBlockSize(block_size);\n  * \\endcode\n  *\n  * 2. The second case is for variable-block sparse matrices.\n  * Here each block has its own dimensions. The only restriction is that all the blocks\n  * in a row (resp. a column) should have the same number of rows (resp. of columns).\n  * It is thus required in this case to describe the layout of the matrix by calling\n  * setBlockLayout(rowBlocks, colBlocks).\n  *\n  * In any of the previous case, the matrix can be filled by calling setFromTriplets().\n  * A regular sparse matrix can be converted to a block sparse matrix and vice versa.\n  * It is obviously required to describe the block layout beforehand by calling either\n  * setBlockSize() for fixed-size blocks or setBlockLayout for variable-size blocks.\n  *\n  * \\tparam Scalar_ The Scalar type\n  * \\tparam _BlockAtCompileTime The block layout option. It takes the following values\n  * Dynamic : block size known at runtime\n  * a numeric number : fixed-size block known at compile time\n  */\ntemplate<typename Scalar_, int _BlockAtCompileTime=Dynamic, int Options_=ColMajor, typename StorageIndex_=int> class BlockSparseMatrix;\n\ntemplate<typename BlockSparseMatrixT> class BlockSparseMatrixView;\n\nnamespace internal {\ntemplate<typename Scalar_, int _BlockAtCompileTime, int Options_, typename Index_>\nstruct traits<BlockSparseMatrix<Scalar_,_BlockAtCompileTime,Options_, Index_> >\n{\n  typedef Scalar_ Scalar;\n  typedef Index_ Index;\n  typedef Sparse StorageKind; // FIXME Where is it used ??\n  typedef MatrixXpr XprKind;\n  enum {\n    RowsAtCompileTime = Dynamic,\n    ColsAtCompileTime = Dynamic,\n    MaxRowsAtCompileTime = Dynamic,\n    MaxColsAtCompileTime = Dynamic,\n    BlockSize = _BlockAtCompileTime,\n    Flags = Options_ | NestByRefBit | LvalueBit,\n    CoeffReadCost = NumTraits<Scalar>::ReadCost,\n    SupportedAccessPatterns = InnerRandomAccessPattern\n  };\n};\ntemplate<typename BlockSparseMatrixT>\nstruct traits<BlockSparseMatrixView<BlockSparseMatrixT> >\n{\n  typedef Ref<Matrix<typename BlockSparseMatrixT::Scalar, BlockSparseMatrixT::BlockSize, BlockSparseMatrixT::BlockSize> > Scalar;\n  typedef Ref<Matrix<typename BlockSparseMatrixT::RealScalar, BlockSparseMatrixT::BlockSize, BlockSparseMatrixT::BlockSize> > RealScalar;\n\n};\n\n// Function object to sort a triplet list\ntemplate<typename Iterator, bool IsColMajor>\nstruct TripletComp\n{\n  typedef typename Iterator::value_type Triplet;\n  bool operator()(const Triplet& a, const Triplet& b)\n  { if(IsColMajor)\n      return ((a.col() == b.col() && a.row() < b.row()) || (a.col() < b.col()));\n    else\n      return ((a.row() == b.row() && a.col() < b.col()) || (a.row() < b.row()));\n  }\n};\n} // end namespace internal\n\n\n/* Proxy to view the block sparse matrix as a regular sparse matrix */\ntemplate<typename BlockSparseMatrixT>\nclass BlockSparseMatrixView : public SparseMatrixBase<BlockSparseMatrixT>\n{\n  public:\n    typedef Ref<typename BlockSparseMatrixT::BlockScalar> Scalar;\n    typedef Ref<typename BlockSparseMatrixT::BlockRealScalar> RealScalar;\n    typedef typename BlockSparseMatrixT::Index Index;\n    typedef  BlockSparseMatrixT Nested;\n    enum {\n      Flags = BlockSparseMatrixT::Options,\n      Options = BlockSparseMatrixT::Options,\n      RowsAtCompileTime = BlockSparseMatrixT::RowsAtCompileTime,\n      ColsAtCompileTime = BlockSparseMatrixT::ColsAtCompileTime,\n      MaxColsAtCompileTime = BlockSparseMatrixT::MaxColsAtCompileTime,\n      MaxRowsAtCompileTime = BlockSparseMatrixT::MaxRowsAtCompileTime\n    };\n  public:\n    BlockSparseMatrixView(const BlockSparseMatrixT& spblockmat)\n     : m_spblockmat(spblockmat)\n    {}\n\n    Index outerSize() const\n    {\n      return (Flags&RowMajorBit) == 1 ? this->rows() : this->cols();\n    }\n    Index cols() const\n    {\n      return m_spblockmat.blockCols();\n    }\n    Index rows() const\n    {\n      return m_spblockmat.blockRows();\n    }\n    Scalar coeff(Index row, Index col)\n    {\n      return m_spblockmat.coeff(row, col);\n    }\n    Scalar coeffRef(Index row, Index col)\n    {\n      return m_spblockmat.coeffRef(row, col);\n    }\n    // Wrapper to iterate over all blocks\n    class InnerIterator : public BlockSparseMatrixT::BlockInnerIterator\n    {\n      public:\n      InnerIterator(const BlockSparseMatrixView& mat, Index outer)\n          : BlockSparseMatrixT::BlockInnerIterator(mat.m_spblockmat, outer)\n      {}\n\n    };\n\n  protected:\n    const BlockSparseMatrixT& m_spblockmat;\n};\n\n// Proxy to view a regular vector as a block vector\ntemplate<typename BlockSparseMatrixT, typename VectorType>\nclass BlockVectorView\n{\n  public:\n    enum {\n      BlockSize = BlockSparseMatrixT::BlockSize,\n      ColsAtCompileTime = VectorType::ColsAtCompileTime,\n      RowsAtCompileTime = VectorType::RowsAtCompileTime,\n      Flags = VectorType::Flags\n    };\n    typedef Ref<const Matrix<typename BlockSparseMatrixT::Scalar, (RowsAtCompileTime==1)? 1 : BlockSize, (ColsAtCompileTime==1)? 1 : BlockSize> >Scalar;\n    typedef typename BlockSparseMatrixT::Index Index;\n  public:\n    BlockVectorView(const BlockSparseMatrixT& spblockmat, const VectorType& vec)\n    : m_spblockmat(spblockmat),m_vec(vec)\n    { }\n    inline Index cols() const\n    {\n      return m_vec.cols();\n    }\n    inline Index size() const\n    {\n      return m_spblockmat.blockRows();\n    }\n    inline Scalar coeff(Index bi) const\n    {\n      Index startRow = m_spblockmat.blockRowsIndex(bi);\n      Index rowSize = m_spblockmat.blockRowsIndex(bi+1) - startRow;\n      return m_vec.middleRows(startRow, rowSize);\n    }\n    inline Scalar coeff(Index bi, Index j) const\n    {\n      Index startRow = m_spblockmat.blockRowsIndex(bi);\n      Index rowSize = m_spblockmat.blockRowsIndex(bi+1) - startRow;\n      return m_vec.block(startRow, j, rowSize, 1);\n    }\n  protected:\n    const BlockSparseMatrixT& m_spblockmat;\n    const VectorType& m_vec;\n};\n\ntemplate<typename VectorType, typename Index> class BlockVectorReturn;\n\n\n// Proxy to view a regular vector as a block vector\ntemplate<typename BlockSparseMatrixT, typename VectorType>\nclass BlockVectorReturn\n{\n  public:\n    enum {\n      ColsAtCompileTime = VectorType::ColsAtCompileTime,\n      RowsAtCompileTime = VectorType::RowsAtCompileTime,\n      Flags = VectorType::Flags\n    };\n    typedef Ref<Matrix<typename VectorType::Scalar, RowsAtCompileTime, ColsAtCompileTime> > Scalar;\n    typedef typename BlockSparseMatrixT::Index Index;\n  public:\n    BlockVectorReturn(const BlockSparseMatrixT& spblockmat, VectorType& vec)\n    : m_spblockmat(spblockmat),m_vec(vec)\n    { }\n    inline Index size() const\n    {\n      return m_spblockmat.blockRows();\n    }\n    inline Scalar coeffRef(Index bi)\n    {\n      Index startRow = m_spblockmat.blockRowsIndex(bi);\n      Index rowSize = m_spblockmat.blockRowsIndex(bi+1) - startRow;\n      return m_vec.middleRows(startRow, rowSize);\n    }\n    inline Scalar coeffRef(Index bi, Index j)\n    {\n      Index startRow = m_spblockmat.blockRowsIndex(bi);\n      Index rowSize = m_spblockmat.blockRowsIndex(bi+1) - startRow;\n      return m_vec.block(startRow, j, rowSize, 1);\n    }\n\n  protected:\n    const BlockSparseMatrixT& m_spblockmat;\n    VectorType& m_vec;\n};\n\n// Block version of the sparse dense product\ntemplate<typename Lhs, typename Rhs>\nclass BlockSparseTimeDenseProduct;\n\nnamespace internal {\n\ntemplate<typename BlockSparseMatrixT, typename VecType>\nstruct traits<BlockSparseTimeDenseProduct<BlockSparseMatrixT, VecType> >\n{\n  typedef Dense StorageKind;\n  typedef MatrixXpr XprKind;\n  typedef typename BlockSparseMatrixT::Scalar Scalar;\n  typedef typename BlockSparseMatrixT::Index Index;\n  enum {\n    RowsAtCompileTime = Dynamic,\n    ColsAtCompileTime = Dynamic,\n    MaxRowsAtCompileTime = Dynamic,\n    MaxColsAtCompileTime = Dynamic,\n    Flags = 0,\n    CoeffReadCost = internal::traits<BlockSparseMatrixT>::CoeffReadCost\n  };\n};\n} // end namespace internal\n\ntemplate<typename Lhs, typename Rhs>\nclass BlockSparseTimeDenseProduct\n  : public ProductBase<BlockSparseTimeDenseProduct<Lhs,Rhs>, Lhs, Rhs>\n{\n  public:\n    EIGEN_PRODUCT_PUBLIC_INTERFACE(BlockSparseTimeDenseProduct)\n\n    BlockSparseTimeDenseProduct(const Lhs& lhs, const Rhs& rhs) : Base(lhs,rhs)\n    {}\n\n    template<typename Dest> void scaleAndAddTo(Dest& dest, const typename Rhs::Scalar& alpha) const\n    {\n      BlockVectorReturn<Lhs,Dest> tmpDest(m_lhs, dest);\n      internal::sparse_time_dense_product( BlockSparseMatrixView<Lhs>(m_lhs),  BlockVectorView<Lhs, Rhs>(m_lhs, m_rhs), tmpDest, alpha);\n    }\n\n  private:\n    BlockSparseTimeDenseProduct& operator=(const BlockSparseTimeDenseProduct&);\n};\n\ntemplate<typename Scalar_, int _BlockAtCompileTime, int Options_, typename StorageIndex_>\nclass BlockSparseMatrix : public SparseMatrixBase<BlockSparseMatrix<Scalar_,_BlockAtCompileTime, Options_,StorageIndex_> >\n{\n  public:\n    typedef Scalar_ Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef StorageIndex_ StorageIndex;\n    typedef typename internal::ref_selector<BlockSparseMatrix<Scalar_, _BlockAtCompileTime, Options_, StorageIndex_> >::type Nested;\n\n    enum {\n      Options = Options_,\n      Flags = Options,\n      BlockSize=_BlockAtCompileTime,\n      RowsAtCompileTime = Dynamic,\n      ColsAtCompileTime = Dynamic,\n      MaxRowsAtCompileTime = Dynamic,\n      MaxColsAtCompileTime = Dynamic,\n      IsVectorAtCompileTime = 0,\n      IsColMajor = Flags&RowMajorBit ? 0 : 1\n    };\n    typedef Matrix<Scalar, _BlockAtCompileTime, _BlockAtCompileTime,IsColMajor ? ColMajor : RowMajor> BlockScalar;\n    typedef Matrix<RealScalar, _BlockAtCompileTime, _BlockAtCompileTime,IsColMajor ? ColMajor : RowMajor> BlockRealScalar;\n    typedef typename internal::conditional<_BlockAtCompileTime==Dynamic, Scalar, BlockScalar>::type BlockScalarReturnType;\n    typedef BlockSparseMatrix<Scalar, BlockSize, IsColMajor ? ColMajor : RowMajor, StorageIndex> PlainObject;\n  public:\n    // Default constructor\n    BlockSparseMatrix()\n    : m_innerBSize(0),m_outerBSize(0),m_innerOffset(0),m_outerOffset(0),\n      m_nonzerosblocks(0),m_values(0),m_blockPtr(0),m_indices(0),\n      m_outerIndex(0),m_blockSize(BlockSize)\n    { }\n\n\n    /**\n     * \\brief Construct and resize\n     *\n     */\n    BlockSparseMatrix(Index brow, Index bcol)\n      : m_innerBSize(IsColMajor ? brow : bcol),\n        m_outerBSize(IsColMajor ? bcol : brow),\n        m_innerOffset(0),m_outerOffset(0),m_nonzerosblocks(0),\n        m_values(0),m_blockPtr(0),m_indices(0),\n        m_outerIndex(0),m_blockSize(BlockSize)\n    { }\n\n    /**\n     * \\brief Copy-constructor\n     */\n    BlockSparseMatrix(const BlockSparseMatrix& other)\n      : m_innerBSize(other.m_innerBSize),m_outerBSize(other.m_outerBSize),\n        m_nonzerosblocks(other.m_nonzerosblocks),m_nonzeros(other.m_nonzeros),\n        m_blockPtr(0),m_blockSize(other.m_blockSize)\n    {\n      // should we allow copying between variable-size blocks and fixed-size blocks ??\n      eigen_assert(m_blockSize == BlockSize && \" CAN NOT COPY BETWEEN FIXED-SIZE AND VARIABLE-SIZE BLOCKS\");\n\n      std::copy(other.m_innerOffset, other.m_innerOffset+m_innerBSize+1, m_innerOffset);\n      std::copy(other.m_outerOffset, other.m_outerOffset+m_outerBSize+1, m_outerOffset);\n      std::copy(other.m_values, other.m_values+m_nonzeros, m_values);\n\n      if(m_blockSize != Dynamic)\n        std::copy(other.m_blockPtr, other.m_blockPtr+m_nonzerosblocks, m_blockPtr);\n\n      std::copy(other.m_indices, other.m_indices+m_nonzerosblocks, m_indices);\n      std::copy(other.m_outerIndex, other.m_outerIndex+m_outerBSize, m_outerIndex);\n    }\n\n    friend void swap(BlockSparseMatrix& first, BlockSparseMatrix& second)\n    {\n      std::swap(first.m_innerBSize, second.m_innerBSize);\n      std::swap(first.m_outerBSize, second.m_outerBSize);\n      std::swap(first.m_innerOffset, second.m_innerOffset);\n      std::swap(first.m_outerOffset, second.m_outerOffset);\n      std::swap(first.m_nonzerosblocks, second.m_nonzerosblocks);\n      std::swap(first.m_nonzeros, second.m_nonzeros);\n      std::swap(first.m_values, second.m_values);\n      std::swap(first.m_blockPtr, second.m_blockPtr);\n      std::swap(first.m_indices, second.m_indices);\n      std::swap(first.m_outerIndex, second.m_outerIndex);\n      std::swap(first.m_BlockSize, second.m_blockSize);\n    }\n\n    BlockSparseMatrix& operator=(BlockSparseMatrix other)\n    {\n      //Copy-and-swap paradigm ... avoid leaked data if thrown\n      swap(*this, other);\n      return *this;\n    }\n\n    // Destructor\n    ~BlockSparseMatrix()\n    {\n      delete[] m_outerIndex;\n      delete[] m_innerOffset;\n      delete[] m_outerOffset;\n      delete[] m_indices;\n      delete[] m_blockPtr;\n      delete[] m_values;\n    }\n\n\n    /**\n      * \\brief Constructor from a sparse matrix\n      *\n      */\n    template<typename MatrixType>\n    inline BlockSparseMatrix(const MatrixType& spmat) : m_blockSize(BlockSize)\n    {\n      EIGEN_STATIC_ASSERT((m_blockSize != Dynamic), THIS_METHOD_IS_ONLY_FOR_FIXED_SIZE);\n\n      *this = spmat;\n    }\n\n    /**\n      * \\brief Assignment from a sparse matrix with the same storage order\n      *\n      * Convert from a sparse matrix to block sparse matrix.\n      * \\warning Before calling this function, tt is necessary to call\n      * either setBlockLayout() (matrices with variable-size blocks)\n      * or setBlockSize() (for fixed-size blocks).\n      */\n    template<typename MatrixType>\n    inline BlockSparseMatrix& operator=(const MatrixType& spmat)\n    {\n      eigen_assert((m_innerBSize != 0 && m_outerBSize != 0)\n                   && \"Trying to assign to a zero-size matrix, call resize() first\");\n      eigen_assert(((MatrixType::Options&RowMajorBit) != IsColMajor) && \"Wrong storage order\");\n      typedef SparseMatrix<bool,MatrixType::Options,typename MatrixType::Index> MatrixPatternType;\n      MatrixPatternType  blockPattern(blockRows(), blockCols());\n      m_nonzeros = 0;\n\n      // First, compute the number of nonzero blocks and their locations\n      for(StorageIndex bj = 0; bj < m_outerBSize; ++bj)\n      {\n        // Browse each outer block and compute the structure\n        std::vector<bool> nzblocksFlag(m_innerBSize,false);  // Record the existing blocks\n        blockPattern.startVec(bj);\n        for(StorageIndex j = blockOuterIndex(bj); j < blockOuterIndex(bj+1); ++j)\n        {\n          typename MatrixType::InnerIterator it_spmat(spmat, j);\n          for(; it_spmat; ++it_spmat)\n          {\n            StorageIndex bi = innerToBlock(it_spmat.index()); // Index of the current nonzero block\n            if(!nzblocksFlag[bi])\n            {\n              // Save the index of this nonzero block\n              nzblocksFlag[bi] = true;\n              blockPattern.insertBackByOuterInnerUnordered(bj, bi) = true;\n              // Compute the total number of nonzeros (including explicit zeros in blocks)\n              m_nonzeros += blockOuterSize(bj) * blockInnerSize(bi);\n            }\n          }\n        } // end current outer block\n      }\n      blockPattern.finalize();\n\n      // Allocate the internal arrays\n      setBlockStructure(blockPattern);\n\n      for(StorageIndex nz = 0; nz < m_nonzeros; ++nz) m_values[nz] = Scalar(0);\n      for(StorageIndex bj = 0; bj < m_outerBSize; ++bj)\n      {\n        // Now copy the values\n        for(StorageIndex j = blockOuterIndex(bj); j < blockOuterIndex(bj+1); ++j)\n        {\n          // Browse the outer block column by column (for column-major matrices)\n          typename MatrixType::InnerIterator it_spmat(spmat, j);\n          for(; it_spmat; ++it_spmat)\n          {\n            StorageIndex idx = 0; // Position of this block in the column block\n            StorageIndex bi = innerToBlock(it_spmat.index()); // Index of the current nonzero block\n            // Go to the inner block where this element belongs to\n            while(bi > m_indices[m_outerIndex[bj]+idx]) ++idx; // Not expensive for ordered blocks\n            StorageIndex idxVal;// Get the right position in the array of values for this element\n            if(m_blockSize == Dynamic)\n            {\n              // Offset from all blocks before ...\n              idxVal =  m_blockPtr[m_outerIndex[bj]+idx];\n              // ... and offset inside the block\n              idxVal += (j - blockOuterIndex(bj)) * blockOuterSize(bj) + it_spmat.index() - m_innerOffset[bi];\n            }\n            else\n            {\n              // All blocks before\n              idxVal = (m_outerIndex[bj] + idx) * m_blockSize * m_blockSize;\n              // inside the block\n              idxVal += (j - blockOuterIndex(bj)) * m_blockSize + (it_spmat.index()%m_blockSize);\n            }\n            // Insert the value\n            m_values[idxVal] = it_spmat.value();\n          } // end of this column\n        } // end of this block\n      } // end of this outer block\n\n      return *this;\n    }\n\n    /**\n      * \\brief Set the nonzero block pattern of the matrix\n      *\n      * Given a sparse matrix describing the nonzero block pattern,\n      * this function prepares the internal pointers for values.\n      * After calling this function, any *nonzero* block (bi, bj) can be set\n      * with a simple call to coeffRef(bi,bj).\n      *\n      *\n      * \\warning Before calling this function, tt is necessary to call\n      * either setBlockLayout() (matrices with variable-size blocks)\n      * or setBlockSize() (for fixed-size blocks).\n      *\n      * \\param blockPattern Sparse matrix of boolean elements describing the block structure\n      *\n      * \\sa setBlockLayout() \\sa setBlockSize()\n      */\n    template<typename MatrixType>\n    void setBlockStructure(const MatrixType& blockPattern)\n    {\n      resize(blockPattern.rows(), blockPattern.cols());\n      reserve(blockPattern.nonZeros());\n\n      // Browse the block pattern and set up the various pointers\n      m_outerIndex[0] = 0;\n      if(m_blockSize == Dynamic) m_blockPtr[0] = 0;\n      for(StorageIndex nz = 0; nz < m_nonzeros; ++nz) m_values[nz] = Scalar(0);\n      for(StorageIndex bj = 0; bj < m_outerBSize; ++bj)\n      {\n        //Browse each outer block\n\n        //First, copy and save the indices of nonzero blocks\n        //FIXME : find a way to avoid this ...\n        std::vector<int> nzBlockIdx;\n        typename MatrixType::InnerIterator it(blockPattern, bj);\n        for(; it; ++it)\n        {\n          nzBlockIdx.push_back(it.index());\n        }\n        std::sort(nzBlockIdx.begin(), nzBlockIdx.end());\n\n        // Now, fill block indices and (eventually) pointers to blocks\n        for(StorageIndex idx = 0; idx < nzBlockIdx.size(); ++idx)\n        {\n          StorageIndex offset = m_outerIndex[bj]+idx; // offset in m_indices\n          m_indices[offset] = nzBlockIdx[idx];\n          if(m_blockSize == Dynamic)\n            m_blockPtr[offset] = m_blockPtr[offset-1] + blockInnerSize(nzBlockIdx[idx]) * blockOuterSize(bj);\n          // There is no blockPtr for fixed-size blocks... not needed !???\n        }\n        // Save the pointer to the next outer block\n        m_outerIndex[bj+1] = m_outerIndex[bj] + nzBlockIdx.size();\n      }\n    }\n\n    /**\n      * \\brief Set the number of rows and columns blocks\n      */\n    inline void resize(Index brow, Index bcol)\n    {\n      m_innerBSize = IsColMajor ? brow : bcol;\n      m_outerBSize = IsColMajor ? bcol : brow;\n    }\n\n    /**\n      * \\brief set the block size at runtime for fixed-size block layout\n      *\n      * Call this only for fixed-size blocks\n      */\n    inline void setBlockSize(Index blockSize)\n    {\n      m_blockSize = blockSize;\n    }\n\n    /**\n      * \\brief Set the row and column block layouts,\n      *\n      * This function set the size of each row and column block.\n      * So this function should be used only for blocks with variable size.\n      * \\param rowBlocks : Number of rows per row block\n      * \\param colBlocks : Number of columns per column block\n      * \\sa resize(), setBlockSize()\n      */\n    inline void setBlockLayout(const VectorXi& rowBlocks, const VectorXi& colBlocks)\n    {\n      const VectorXi& innerBlocks = IsColMajor ? rowBlocks : colBlocks;\n      const VectorXi& outerBlocks = IsColMajor ? colBlocks : rowBlocks;\n      eigen_assert(m_innerBSize == innerBlocks.size() && \"CHECK THE NUMBER OF ROW OR COLUMN BLOCKS\");\n      eigen_assert(m_outerBSize == outerBlocks.size() && \"CHECK THE NUMBER OF ROW OR COLUMN BLOCKS\");\n      m_outerBSize = outerBlocks.size();\n      //  starting index of blocks... cumulative sums\n      m_innerOffset = new StorageIndex[m_innerBSize+1];\n      m_outerOffset = new StorageIndex[m_outerBSize+1];\n      m_innerOffset[0] = 0;\n      m_outerOffset[0] = 0;\n      std::partial_sum(&innerBlocks[0], &innerBlocks[m_innerBSize-1]+1, &m_innerOffset[1]);\n      std::partial_sum(&outerBlocks[0], &outerBlocks[m_outerBSize-1]+1, &m_outerOffset[1]);\n\n      // Compute the total number of nonzeros\n      m_nonzeros = 0;\n      for(StorageIndex bj = 0; bj < m_outerBSize; ++bj)\n        for(StorageIndex bi = 0; bi < m_innerBSize; ++bi)\n          m_nonzeros += outerBlocks[bj] * innerBlocks[bi];\n\n    }\n\n    /**\n      * \\brief Allocate the internal array of pointers to blocks and their inner indices\n      *\n      * \\note For fixed-size blocks, call setBlockSize() to set the block.\n      * And For variable-size blocks, call setBlockLayout() before using this function\n      *\n      * \\param nonzerosblocks Number of nonzero blocks. The total number of nonzeros is\n      * is computed in setBlockLayout() for variable-size blocks\n      * \\sa setBlockSize()\n      */\n    inline void reserve(const Index nonzerosblocks)\n    {\n      eigen_assert((m_innerBSize != 0 && m_outerBSize != 0) &&\n          \"TRYING TO RESERVE ZERO-SIZE MATRICES, CALL resize() first\");\n\n      //FIXME Should free if already allocated\n      m_outerIndex = new StorageIndex[m_outerBSize+1];\n\n      m_nonzerosblocks = nonzerosblocks;\n      if(m_blockSize != Dynamic)\n      {\n        m_nonzeros = nonzerosblocks * (m_blockSize * m_blockSize);\n        m_blockPtr = 0;\n      }\n      else\n      {\n        // m_nonzeros  is already computed in setBlockLayout()\n        m_blockPtr = new StorageIndex[m_nonzerosblocks+1];\n      }\n      m_indices = new StorageIndex[m_nonzerosblocks+1];\n      m_values = new Scalar[m_nonzeros];\n    }\n\n\n    /**\n      * \\brief Fill values in a matrix  from a triplet list.\n      *\n      * Each triplet item has a block stored in an Eigen dense matrix.\n      * The InputIterator class should provide the functions row(), col() and value()\n      *\n      * \\note For fixed-size blocks, call setBlockSize() before this function.\n      *\n      * FIXME Do not accept duplicates\n      */\n    template<typename InputIterator>\n    void setFromTriplets(const InputIterator& begin, const InputIterator& end)\n    {\n      eigen_assert((m_innerBSize!=0 && m_outerBSize !=0) && \"ZERO BLOCKS, PLEASE CALL resize() before\");\n\n      /* First, sort the triplet list\n        * FIXME This can be unnecessarily expensive since only the inner indices have to be sorted\n        * The best approach is like in SparseMatrix::setFromTriplets()\n        */\n      internal::TripletComp<InputIterator, IsColMajor> tripletcomp;\n      std::sort(begin, end, tripletcomp);\n\n      /* Count the number of rows and column blocks,\n       * and the number of nonzero blocks per outer dimension\n       */\n      VectorXi rowBlocks(m_innerBSize); // Size of each block row\n      VectorXi colBlocks(m_outerBSize); // Size of each block column\n      rowBlocks.setZero(); colBlocks.setZero();\n      VectorXi nzblock_outer(m_outerBSize); // Number of nz blocks per outer vector\n      VectorXi nz_outer(m_outerBSize); // Number of nz per outer vector...for variable-size blocks\n      nzblock_outer.setZero();\n      nz_outer.setZero();\n      for(InputIterator it(begin); it !=end; ++it)\n      {\n        eigen_assert(it->row() >= 0 && it->row() < this->blockRows() && it->col() >= 0 && it->col() < this->blockCols());\n        eigen_assert((it->value().rows() == it->value().cols() && (it->value().rows() == m_blockSize))\n                     || (m_blockSize == Dynamic));\n\n        if(m_blockSize == Dynamic)\n        {\n          eigen_assert((rowBlocks[it->row()] == 0 || rowBlocks[it->row()] == it->value().rows()) &&\n              \"NON CORRESPONDING SIZES FOR ROW BLOCKS\");\n          eigen_assert((colBlocks[it->col()] == 0 || colBlocks[it->col()] == it->value().cols()) &&\n              \"NON CORRESPONDING SIZES FOR COLUMN BLOCKS\");\n          rowBlocks[it->row()] =it->value().rows();\n          colBlocks[it->col()] = it->value().cols();\n        }\n        nz_outer(IsColMajor ? it->col() : it->row()) += it->value().rows() * it->value().cols();\n        nzblock_outer(IsColMajor ? it->col() : it->row())++;\n      }\n      // Allocate member arrays\n      if(m_blockSize == Dynamic) setBlockLayout(rowBlocks, colBlocks);\n      StorageIndex nzblocks = nzblock_outer.sum();\n      reserve(nzblocks);\n\n       // Temporary markers\n      VectorXi block_id(m_outerBSize); // To be used as a block marker during insertion\n\n      // Setup outer index pointers and markers\n      m_outerIndex[0] = 0;\n      if (m_blockSize == Dynamic)  m_blockPtr[0] =  0;\n      for(StorageIndex bj = 0; bj < m_outerBSize; ++bj)\n      {\n        m_outerIndex[bj+1] = m_outerIndex[bj] + nzblock_outer(bj);\n        block_id(bj) = m_outerIndex[bj];\n        if(m_blockSize==Dynamic)\n        {\n          m_blockPtr[m_outerIndex[bj+1]] = m_blockPtr[m_outerIndex[bj]] + nz_outer(bj);\n        }\n      }\n\n      // Fill the matrix\n      for(InputIterator it(begin); it!=end; ++it)\n      {\n        StorageIndex outer = IsColMajor ? it->col() : it->row();\n        StorageIndex inner = IsColMajor ? it->row() : it->col();\n        m_indices[block_id(outer)] = inner;\n        StorageIndex block_size = it->value().rows()*it->value().cols();\n        StorageIndex nz_marker = blockPtr(block_id[outer]);\n        memcpy(&(m_values[nz_marker]), it->value().data(), block_size * sizeof(Scalar));\n        if(m_blockSize == Dynamic)\n        {\n          m_blockPtr[block_id(outer)+1] = m_blockPtr[block_id(outer)] + block_size;\n        }\n        block_id(outer)++;\n      }\n\n      // An alternative when the outer indices are sorted...no need to use an array of markers\n//      for(Index bcol = 0; bcol < m_outerBSize; ++bcol)\n//      {\n//      Index id = 0, id_nz = 0, id_nzblock = 0;\n//      for(InputIterator it(begin); it!=end; ++it)\n//      {\n//        while (id<bcol) // one pass should do the job unless there are empty columns\n//        {\n//          id++;\n//          m_outerIndex[id+1]=m_outerIndex[id];\n//        }\n//        m_outerIndex[id+1] += 1;\n//        m_indices[id_nzblock]=brow;\n//        Index block_size = it->value().rows()*it->value().cols();\n//        m_blockPtr[id_nzblock+1] = m_blockPtr[id_nzblock] + block_size;\n//        id_nzblock++;\n//        memcpy(&(m_values[id_nz]),it->value().data(), block_size*sizeof(Scalar));\n//        id_nz += block_size;\n//      }\n//      while(id < m_outerBSize-1) // Empty columns at the end\n//      {\n//        id++;\n//        m_outerIndex[id+1]=m_outerIndex[id];\n//      }\n//      }\n    }\n\n\n    /**\n      * \\returns the number of rows\n      */\n    inline Index rows() const\n    {\n//      return blockRows();\n      return (IsColMajor ? innerSize() : outerSize());\n    }\n\n    /**\n      * \\returns the number of cols\n      */\n    inline Index cols() const\n    {\n//      return blockCols();\n      return (IsColMajor ? outerSize() : innerSize());\n    }\n\n    inline Index innerSize() const\n    {\n      if(m_blockSize == Dynamic) return m_innerOffset[m_innerBSize];\n      else return  (m_innerBSize * m_blockSize) ;\n    }\n\n    inline Index outerSize() const\n    {\n      if(m_blockSize == Dynamic) return m_outerOffset[m_outerBSize];\n      else return  (m_outerBSize * m_blockSize) ;\n    }\n    /** \\returns the number of rows grouped by blocks */\n    inline Index blockRows() const\n    {\n      return (IsColMajor ? m_innerBSize : m_outerBSize);\n    }\n    /** \\returns the number of columns grouped by blocks */\n    inline Index blockCols() const\n    {\n      return (IsColMajor ? m_outerBSize : m_innerBSize);\n    }\n\n    inline Index outerBlocks() const { return m_outerBSize; }\n    inline Index innerBlocks() const { return m_innerBSize; }\n\n    /** \\returns the block index where outer belongs to */\n    inline Index outerToBlock(Index outer) const\n    {\n      eigen_assert(outer < outerSize() && \"OUTER INDEX OUT OF BOUNDS\");\n\n      if(m_blockSize != Dynamic)\n        return (outer / m_blockSize); // Integer division\n\n      StorageIndex b_outer = 0;\n      while(m_outerOffset[b_outer] <= outer) ++b_outer;\n      return b_outer - 1;\n    }\n    /** \\returns  the block index where inner belongs to */\n    inline Index innerToBlock(Index inner) const\n    {\n      eigen_assert(inner < innerSize() && \"OUTER INDEX OUT OF BOUNDS\");\n\n      if(m_blockSize != Dynamic)\n        return (inner / m_blockSize); // Integer division\n\n      StorageIndex b_inner = 0;\n      while(m_innerOffset[b_inner] <= inner) ++b_inner;\n      return b_inner - 1;\n    }\n\n    /**\n      *\\returns a reference to the (i,j) block as an Eigen Dense Matrix\n      */\n    Ref<BlockScalar> coeffRef(Index brow, Index bcol)\n    {\n      eigen_assert(brow < blockRows() && \"BLOCK ROW INDEX OUT OF BOUNDS\");\n      eigen_assert(bcol < blockCols() && \"BLOCK nzblocksFlagCOLUMN OUT OF BOUNDS\");\n\n      StorageIndex rsize = IsColMajor ? blockInnerSize(brow): blockOuterSize(bcol);\n      StorageIndex csize = IsColMajor ? blockOuterSize(bcol) : blockInnerSize(brow);\n      StorageIndex inner = IsColMajor ? brow : bcol;\n      StorageIndex outer = IsColMajor ? bcol : brow;\n      StorageIndex offset = m_outerIndex[outer];\n      while(offset < m_outerIndex[outer+1] && m_indices[offset] != inner)\n        offset++;\n      if(m_indices[offset] == inner)\n      {\n        return Map<BlockScalar>(&(m_values[blockPtr(offset)]), rsize, csize);\n      }\n      else\n      {\n        //FIXME the block does not exist, Insert it !!!!!!!!!\n        eigen_assert(\"DYNAMIC INSERTION IS NOT YET SUPPORTED\");\n      }\n    }\n\n    /**\n      * \\returns the value of the (i,j) block as an Eigen Dense Matrix\n      */\n    Map<const BlockScalar> coeff(Index brow, Index bcol) const\n    {\n      eigen_assert(brow < blockRows() && \"BLOCK ROW INDEX OUT OF BOUNDS\");\n      eigen_assert(bcol < blockCols() && \"BLOCK COLUMN OUT OF BOUNDS\");\n\n      StorageIndex rsize = IsColMajor ? blockInnerSize(brow): blockOuterSize(bcol);\n      StorageIndex csize = IsColMajor ? blockOuterSize(bcol) : blockInnerSize(brow);\n      StorageIndex inner = IsColMajor ? brow : bcol;\n      StorageIndex outer = IsColMajor ? bcol : brow;\n      StorageIndex offset = m_outerIndex[outer];\n      while(offset < m_outerIndex[outer+1] && m_indices[offset] != inner) offset++;\n      if(m_indices[offset] == inner)\n      {\n        return Map<const BlockScalar> (&(m_values[blockPtr(offset)]), rsize, csize);\n      }\n      else\n//        return BlockScalar::Zero(rsize, csize);\n        eigen_assert(\"NOT YET SUPPORTED\");\n    }\n\n    // Block Matrix times vector product\n    template<typename VecType>\n    BlockSparseTimeDenseProduct<BlockSparseMatrix, VecType> operator*(const VecType& lhs) const\n    {\n      return BlockSparseTimeDenseProduct<BlockSparseMatrix, VecType>(*this, lhs);\n    }\n\n    /** \\returns the number of nonzero blocks */\n    inline Index nonZerosBlocks() const { return m_nonzerosblocks; }\n    /** \\returns the total number of nonzero elements, including eventual explicit zeros in blocks */\n    inline Index nonZeros() const { return m_nonzeros; }\n\n    inline BlockScalarReturnType *valuePtr() {return static_cast<BlockScalarReturnType *>(m_values);}\n//    inline Scalar *valuePtr(){ return m_values; }\n    inline StorageIndex *innerIndexPtr() {return m_indices; }\n    inline const StorageIndex *innerIndexPtr() const {return m_indices; }\n    inline StorageIndex *outerIndexPtr() {return m_outerIndex; }\n    inline const StorageIndex* outerIndexPtr() const {return m_outerIndex; }\n\n    /** \\brief for compatibility purposes with the SparseMatrix class */\n    inline bool isCompressed() const {return true;}\n    /**\n      * \\returns the starting index of the bi row block\n      */\n    inline Index blockRowsIndex(Index bi) const\n    {\n      return IsColMajor ? blockInnerIndex(bi) : blockOuterIndex(bi);\n    }\n\n    /**\n      * \\returns the starting index of the bj col block\n      */\n    inline Index blockColsIndex(Index bj) const\n    {\n      return IsColMajor ? blockOuterIndex(bj) : blockInnerIndex(bj);\n    }\n\n    inline Index blockOuterIndex(Index bj) const\n    {\n      return (m_blockSize == Dynamic) ? m_outerOffset[bj] : (bj * m_blockSize);\n    }\n    inline Index blockInnerIndex(Index bi) const\n    {\n      return (m_blockSize == Dynamic) ? m_innerOffset[bi] : (bi * m_blockSize);\n    }\n\n    // Not needed ???\n    inline Index blockInnerSize(Index bi) const\n    {\n      return (m_blockSize == Dynamic) ? (m_innerOffset[bi+1] - m_innerOffset[bi]) : m_blockSize;\n    }\n    inline Index blockOuterSize(Index bj) const\n    {\n      return (m_blockSize == Dynamic) ? (m_outerOffset[bj+1]- m_outerOffset[bj]) : m_blockSize;\n    }\n\n    /**\n      * \\brief Browse the matrix by outer index\n      */\n    class InnerIterator; // Browse column by column\n\n    /**\n      * \\brief Browse the matrix by block outer index\n      */\n    class BlockInnerIterator; // Browse block by block\n\n    friend std::ostream & operator << (std::ostream & s, const BlockSparseMatrix& m)\n    {\n      for (StorageIndex j = 0; j < m.outerBlocks(); ++j)\n      {\n        BlockInnerIterator itb(m, j);\n        for(; itb; ++itb)\n        {\n          s << \"(\"<<itb.row() << \", \" << itb.col() << \")\\n\";\n          s << itb.value() <<\"\\n\";\n        }\n      }\n      s << std::endl;\n      return s;\n    }\n\n    /**\n      * \\returns the starting position of the block \\p id in the array of values\n      */\n    Index blockPtr(Index id) const\n    {\n      if(m_blockSize == Dynamic) return m_blockPtr[id];\n      else return id * m_blockSize * m_blockSize;\n      //return blockDynIdx(id, typename internal::conditional<(BlockSize==Dynamic), internal::true_type, internal::false_type>::type());\n    }\n\n\n  protected:\n//    inline Index blockDynIdx(Index id, internal::true_type) const\n//    {\n//      return m_blockPtr[id];\n//    }\n//    inline Index blockDynIdx(Index id, internal::false_type) const\n//    {\n//      return id * BlockSize * BlockSize;\n//    }\n\n    // To be implemented\n    // Insert a block at a particular location... need to make a room for that\n    Map<BlockScalar> insert(Index brow, Index bcol);\n\n    Index m_innerBSize; // Number of block rows\n    Index m_outerBSize; // Number of block columns\n    StorageIndex *m_innerOffset; // Starting index of each inner block (size m_innerBSize+1)\n    StorageIndex *m_outerOffset; // Starting index of each outer block (size m_outerBSize+1)\n    Index m_nonzerosblocks; // Total nonzeros blocks (lower than  m_innerBSize x m_outerBSize)\n    Index m_nonzeros; // Total nonzeros elements\n    Scalar *m_values; //Values stored block column after block column (size m_nonzeros)\n    StorageIndex *m_blockPtr; // Pointer to the beginning of each block in m_values, size m_nonzeroblocks ... null for fixed-size blocks\n    StorageIndex *m_indices; //Inner block indices, size m_nonzerosblocks ... OK\n    StorageIndex *m_outerIndex; // Starting pointer of each block column in m_indices (size m_outerBSize)... OK\n    Index m_blockSize; // Size of a block for fixed-size blocks, otherwise -1\n};\n\ntemplate<typename Scalar_, int _BlockAtCompileTime, int Options_, typename StorageIndex_>\nclass BlockSparseMatrix<Scalar_, _BlockAtCompileTime, Options_, StorageIndex_>::BlockInnerIterator\n{\n  public:\n\n    enum{\n      Flags = Options_\n    };\n\n    BlockInnerIterator(const BlockSparseMatrix& mat, const Index outer)\n    : m_mat(mat),m_outer(outer),\n      m_id(mat.m_outerIndex[outer]),\n      m_end(mat.m_outerIndex[outer+1])\n    {\n    }\n\n    inline BlockInnerIterator& operator++() {m_id++; return *this; }\n\n    inline const Map<const BlockScalar> value() const\n    {\n      return Map<const BlockScalar>(&(m_mat.m_values[m_mat.blockPtr(m_id)]),\n          rows(),cols());\n    }\n    inline Map<BlockScalar> valueRef()\n    {\n      return Map<BlockScalar>(&(m_mat.m_values[m_mat.blockPtr(m_id)]),\n          rows(),cols());\n    }\n    // Block inner index\n    inline Index index() const {return m_mat.m_indices[m_id]; }\n    inline Index outer() const { return m_outer; }\n    // block row index\n    inline Index row() const  {return index(); }\n    // block column index\n    inline Index col() const {return outer(); }\n    // FIXME Number of rows in the current block\n    inline Index rows() const { return (m_mat.m_blockSize==Dynamic) ? (m_mat.m_innerOffset[index()+1] - m_mat.m_innerOffset[index()]) : m_mat.m_blockSize; }\n    // Number of columns in the current block ...\n    inline Index cols() const { return (m_mat.m_blockSize==Dynamic) ? (m_mat.m_outerOffset[m_outer+1]-m_mat.m_outerOffset[m_outer]) : m_mat.m_blockSize;}\n    inline operator bool() const { return (m_id < m_end); }\n\n  protected:\n    const BlockSparseMatrix<Scalar_, _BlockAtCompileTime, Options_, StorageIndex>& m_mat;\n    const Index m_outer;\n    Index m_id;\n    Index m_end;\n};\n\ntemplate<typename Scalar_, int _BlockAtCompileTime, int Options_, typename StorageIndex_>\nclass BlockSparseMatrix<Scalar_, _BlockAtCompileTime, Options_, StorageIndex_>::InnerIterator\n{\n  public:\n    InnerIterator(const BlockSparseMatrix& mat, Index outer)\n    : m_mat(mat),m_outerB(mat.outerToBlock(outer)),m_outer(outer),\n      itb(mat, mat.outerToBlock(outer)),\n      m_offset(outer - mat.blockOuterIndex(m_outerB))\n     {\n        if (itb)\n        {\n          m_id = m_mat.blockInnerIndex(itb.index());\n          m_start = m_id;\n          m_end = m_mat.blockInnerIndex(itb.index()+1);\n        }\n     }\n    inline InnerIterator& operator++()\n    {\n      m_id++;\n      if (m_id >= m_end)\n      {\n        ++itb;\n        if (itb)\n        {\n          m_id = m_mat.blockInnerIndex(itb.index());\n          m_start = m_id;\n          m_end = m_mat.blockInnerIndex(itb.index()+1);\n        }\n      }\n      return *this;\n    }\n    inline const Scalar& value() const\n    {\n      return itb.value().coeff(m_id - m_start, m_offset);\n    }\n    inline Scalar& valueRef()\n    {\n      return itb.valueRef().coeff(m_id - m_start, m_offset);\n    }\n    inline Index index() const { return m_id; }\n    inline Index outer() const {return m_outer; }\n    inline Index col() const {return outer(); }\n    inline Index row() const { return index();}\n    inline operator bool() const\n    {\n      return itb;\n    }\n  protected:\n    const BlockSparseMatrix& m_mat;\n    const Index m_outer;\n    const Index m_outerB;\n    BlockInnerIterator itb; // Iterator through the blocks\n    const Index m_offset; // Position of this column in the block\n    Index m_start; // starting inner index of this block\n    Index m_id; // current inner index in the block\n    Index m_end; // starting inner index of the next block\n\n};\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSEBLOCKMATRIX_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SparseExtra/MarketIO.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2012 Desire NUENTSA WAKAM <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_MARKET_IO_H\n#define EIGEN_SPARSE_MARKET_IO_H\n\n#include <iostream>\n#include <vector>\n\nnamespace Eigen { \n\nnamespace internal \n{\n  template <typename Scalar, typename StorageIndex>\n  inline void GetMarketLine (const char* line, StorageIndex& i, StorageIndex& j, Scalar& value)\n  {\n    std::stringstream sline(line);\n    sline >> i >> j >> value;\n  }\n\n  template<> inline void GetMarketLine (const char* line, int& i, int& j, float& value)\n  { std::sscanf(line, \"%d %d %g\", &i, &j, &value); }\n\n  template<> inline void GetMarketLine (const char* line, int& i, int& j, double& value)\n  { std::sscanf(line, \"%d %d %lg\", &i, &j, &value); }\n\n  template<> inline void GetMarketLine (const char* line, int& i, int& j, std::complex<float>& value)\n  { std::sscanf(line, \"%d %d %g %g\", &i, &j, &numext::real_ref(value), &numext::imag_ref(value)); }\n\n  template<> inline void GetMarketLine (const char* line, int& i, int& j, std::complex<double>& value)\n  { std::sscanf(line, \"%d %d %lg %lg\", &i, &j, &numext::real_ref(value), &numext::imag_ref(value)); }\n\n  template <typename Scalar, typename StorageIndex>\n  inline void GetMarketLine (const char* line, StorageIndex& i, StorageIndex& j, std::complex<Scalar>& value)\n  {\n    std::stringstream sline(line);\n    Scalar valR, valI;\n    sline >> i >> j >> valR >> valI;\n    value = std::complex<Scalar>(valR,valI);\n  }\n\n  template <typename RealScalar>\n  inline void  GetVectorElt (const std::string& line, RealScalar& val)\n  {\n    std::istringstream newline(line);\n    newline >> val;  \n  }\n\n  template <typename RealScalar>\n  inline void GetVectorElt (const std::string& line, std::complex<RealScalar>& val)\n  {\n    RealScalar valR, valI; \n    std::istringstream newline(line);\n    newline >> valR >> valI; \n    val = std::complex<RealScalar>(valR, valI);\n  }\n  \n  template<typename Scalar>\n  inline void putMarketHeader(std::string& header,int sym)\n  {\n    header= \"%%MatrixMarket matrix coordinate \";\n    if(internal::is_same<Scalar, std::complex<float> >::value || internal::is_same<Scalar, std::complex<double> >::value)\n    {\n      header += \" complex\"; \n      if(sym == Symmetric) header += \" symmetric\";\n      else if (sym == SelfAdjoint) header += \" Hermitian\";\n      else header += \" general\";\n    }\n    else\n    {\n      header += \" real\"; \n      if(sym == Symmetric) header += \" symmetric\";\n      else header += \" general\";\n    }\n  }\n\n  template<typename Scalar, typename StorageIndex>\n  inline void PutMatrixElt(Scalar value, StorageIndex row, StorageIndex col, std::ofstream& out)\n  {\n    out << row << \" \"<< col << \" \" << value << \"\\n\";\n  }\n  template<typename Scalar, typename StorageIndex>\n  inline void PutMatrixElt(std::complex<Scalar> value, StorageIndex row, StorageIndex col, std::ofstream& out)\n  {\n    out << row << \" \" << col << \" \" << value.real() << \" \" << value.imag() << \"\\n\";\n  }\n\n\n  template<typename Scalar>\n  inline void putVectorElt(Scalar value, std::ofstream& out)\n  {\n    out << value << \"\\n\"; \n  }\n  template<typename Scalar>\n  inline void putVectorElt(std::complex<Scalar> value, std::ofstream& out)\n  {\n    out << value.real() << \" \" << value.imag()<< \"\\n\"; \n  }\n\n} // end namespace internal\n\ninline bool getMarketHeader(const std::string& filename, int& sym, bool& iscomplex, bool& isvector)\n{\n  sym = 0; \n  iscomplex = false;\n  isvector = false;\n  std::ifstream in(filename.c_str(),std::ios::in);\n  if(!in)\n    return false;\n  \n  std::string line; \n  // The matrix header is always the first line in the file \n  std::getline(in, line); eigen_assert(in.good());\n  \n  std::stringstream fmtline(line); \n  std::string substr[5];\n  fmtline>> substr[0] >> substr[1] >> substr[2] >> substr[3] >> substr[4];\n  if(substr[2].compare(\"array\") == 0) isvector = true;\n  if(substr[3].compare(\"complex\") == 0) iscomplex = true;\n  if(substr[4].compare(\"symmetric\") == 0) sym = Symmetric;\n  else if (substr[4].compare(\"Hermitian\") == 0) sym = SelfAdjoint;\n  \n  return true;\n}\n  \ntemplate<typename SparseMatrixType>\nbool loadMarket(SparseMatrixType& mat, const std::string& filename)\n{\n  typedef typename SparseMatrixType::Scalar Scalar;\n  typedef typename SparseMatrixType::StorageIndex StorageIndex;\n  std::ifstream input(filename.c_str(),std::ios::in);\n  if(!input)\n    return false;\n\n  char rdbuffer[4096];\n  input.rdbuf()->pubsetbuf(rdbuffer, 4096);\n  \n  const int maxBuffersize = 2048;\n  char buffer[maxBuffersize];\n  \n  bool readsizes = false;\n\n  typedef Triplet<Scalar,StorageIndex> T;\n  std::vector<T> elements;\n  \n  Index M(-1), N(-1), NNZ(-1);\n  Index count = 0;\n  while(input.getline(buffer, maxBuffersize))\n  {\n    // skip comments   \n    //NOTE An appropriate test should be done on the header to get the  symmetry\n    if(buffer[0]=='%')\n      continue;\n\n    if(!readsizes)\n    {\n      std::stringstream line(buffer);\n      line >> M >> N >> NNZ;\n      if(M > 0 && N > 0)\n      {\n        readsizes = true;\n        mat.resize(M,N);\n        mat.reserve(NNZ);\n      }\n    }\n    else\n    { \n      StorageIndex i(-1), j(-1);\n      Scalar value; \n      internal::GetMarketLine(buffer, i, j, value);\n\n      i--;\n      j--;\n      if(i>=0 && j>=0 && i<M && j<N)\n      {\n        ++count;\n        elements.push_back(T(i,j,value));\n      }\n      else\n        std::cerr << \"Invalid read: \" << i << \",\" << j << \"\\n\";        \n    }\n  }\n\n  mat.setFromTriplets(elements.begin(), elements.end());\n  if(count!=NNZ)\n    std::cerr << count << \"!=\" << NNZ << \"\\n\";\n  \n  input.close();\n  return true;\n}\n\ntemplate<typename VectorType>\nbool loadMarketVector(VectorType& vec, const std::string& filename)\n{\n   typedef typename VectorType::Scalar Scalar;\n  std::ifstream in(filename.c_str(), std::ios::in);\n  if(!in)\n    return false;\n  \n  std::string line; \n  int n(0), col(0); \n  do \n  { // Skip comments\n    std::getline(in, line); eigen_assert(in.good());\n  } while (line[0] == '%');\n  std::istringstream newline(line);\n  newline  >> n >> col; \n  eigen_assert(n>0 && col>0);\n  vec.resize(n);\n  int i = 0; \n  Scalar value; \n  while ( std::getline(in, line) && (i < n) ){\n    internal::GetVectorElt(line, value); \n    vec(i++) = value; \n  }\n  in.close();\n  if (i!=n){\n    std::cerr<< \"Unable to read all elements from file \" << filename << \"\\n\";\n    return false;\n  }\n  return true;\n}\n\ntemplate<typename SparseMatrixType>\nbool saveMarket(const SparseMatrixType& mat, const std::string& filename, int sym = 0)\n{\n  typedef typename SparseMatrixType::Scalar Scalar;\n  typedef typename SparseMatrixType::RealScalar RealScalar;\n  std::ofstream out(filename.c_str(),std::ios::out);\n  if(!out)\n    return false;\n  \n  out.flags(std::ios_base::scientific);\n  out.precision(std::numeric_limits<RealScalar>::digits10 + 2);\n  std::string header; \n  internal::putMarketHeader<Scalar>(header, sym); \n  out << header << std::endl; \n  out << mat.rows() << \" \" << mat.cols() << \" \" << mat.nonZeros() << \"\\n\";\n  int count = 0;\n  for(int j=0; j<mat.outerSize(); ++j)\n    for(typename SparseMatrixType::InnerIterator it(mat,j); it; ++it)\n    {\n      ++ count;\n      internal::PutMatrixElt(it.value(), it.row()+1, it.col()+1, out);\n    }\n  out.close();\n  return true;\n}\n\ntemplate<typename VectorType>\nbool saveMarketVector (const VectorType& vec, const std::string& filename)\n{\n typedef typename VectorType::Scalar Scalar;\n typedef typename VectorType::RealScalar RealScalar;\n std::ofstream out(filename.c_str(),std::ios::out);\n  if(!out)\n    return false;\n  \n  out.flags(std::ios_base::scientific);\n  out.precision(std::numeric_limits<RealScalar>::digits10 + 2);\n  if(internal::is_same<Scalar, std::complex<float> >::value || internal::is_same<Scalar, std::complex<double> >::value)\n      out << \"%%MatrixMarket matrix array complex general\\n\"; \n  else\n    out << \"%%MatrixMarket matrix array real general\\n\"; \n  out << vec.size() << \" \"<< 1 << \"\\n\";\n  for (int i=0; i < vec.size(); i++){\n    internal::putVectorElt(vec(i), out); \n  }\n  out.close();\n  return true; \n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_MARKET_IO_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SparseExtra/MatrixMarketIterator.h",
    "content": "\n// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Desire NUENTSA WAKAM <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BROWSE_MATRICES_H\n#define EIGEN_BROWSE_MATRICES_H\n\nnamespace Eigen {\n\nenum {\n  SPD = 0x100,\n  NonSymmetric = 0x0\n}; \n\n/** \n * @brief Iterator to browse matrices from a specified folder\n * \n * This is used to load all the matrices from a folder. \n * The matrices should be in Matrix Market format\n * It is assumed that the matrices are named as matname.mtx\n * and matname_SPD.mtx if the matrix is Symmetric and positive definite (or Hermitian)\n * The right hand side vectors are loaded as well, if they exist.\n * They should be named as matname_b.mtx. \n * Note that the right hand side for a SPD matrix is named as matname_SPD_b.mtx\n * \n * Sometimes a reference solution is available. In this case, it should be named as matname_x.mtx\n * \n * Sample code\n * \\code\n * \n * \\endcode\n * \n * \\tparam Scalar The scalar type \n */\ntemplate <typename Scalar>\nclass MatrixMarketIterator \n{\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n  public:\n    typedef Matrix<Scalar,Dynamic,1> VectorType; \n    typedef SparseMatrix<Scalar,ColMajor> MatrixType; \n  \n  public:\n    MatrixMarketIterator(const std::string &folder)\n      : m_sym(0), m_isvalid(false), m_matIsLoaded(false), m_hasRhs(false), m_hasrefX(false), m_folder(folder)\n    {\n      m_folder_id = opendir(folder.c_str());\n      if(m_folder_id)\n        Getnextvalidmatrix();\n    }\n    \n    ~MatrixMarketIterator()\n    {\n      if (m_folder_id) closedir(m_folder_id); \n    }\n    \n    inline MatrixMarketIterator& operator++()\n    {\n      m_matIsLoaded = false;\n      m_hasrefX = false;\n      m_hasRhs = false;\n      Getnextvalidmatrix();\n      return *this;\n    }\n    inline operator bool() const { return m_isvalid;}\n    \n    /** Return the sparse matrix corresponding to the current file */\n    inline MatrixType& matrix() \n    { \n      // Read the matrix\n      if (m_matIsLoaded) return m_mat;\n      \n      std::string matrix_file = m_folder + \"/\" + m_matname + \".mtx\";\n      if ( !loadMarket(m_mat, matrix_file)) \n      {\n        std::cerr << \"Warning loadMarket failed when loading \\\"\" << matrix_file << \"\\\"\" << std::endl;\n        m_matIsLoaded = false;\n        return m_mat;\n      }\n      m_matIsLoaded = true; \n\n      if (m_sym != NonSymmetric) \n      {\n        // Check whether we need to restore a full matrix:\n        RealScalar diag_norm  = m_mat.diagonal().norm();\n        RealScalar lower_norm = m_mat.template triangularView<Lower>().norm();\n        RealScalar upper_norm = m_mat.template triangularView<Upper>().norm();\n        if(lower_norm>diag_norm && upper_norm==diag_norm)\n        {\n          // only the lower part is stored\n          MatrixType tmp(m_mat);\n          m_mat = tmp.template selfadjointView<Lower>();\n        }\n        else if(upper_norm>diag_norm && lower_norm==diag_norm)\n        {\n          // only the upper part is stored\n          MatrixType tmp(m_mat);\n          m_mat = tmp.template selfadjointView<Upper>();\n        }\n      }\n      return m_mat; \n    }\n    \n    /** Return the right hand side corresponding to the current matrix. \n     * If the rhs file is not provided, a random rhs is generated\n     */\n    inline VectorType& rhs() \n    { \n       // Get the right hand side\n      if (m_hasRhs) return m_rhs;\n      \n      std::string rhs_file;\n      rhs_file = m_folder + \"/\" + m_matname + \"_b.mtx\"; // The pattern is matname_b.mtx\n      m_hasRhs = Fileexists(rhs_file);\n      if (m_hasRhs)\n      {\n        m_rhs.resize(m_mat.cols());\n        m_hasRhs = loadMarketVector(m_rhs, rhs_file);\n      }\n      if (!m_hasRhs)\n      {\n        // Generate a random right hand side\n        if (!m_matIsLoaded) this->matrix(); \n        m_refX.resize(m_mat.cols());\n        m_refX.setRandom();\n        m_rhs = m_mat * m_refX;\n        m_hasrefX = true;\n        m_hasRhs = true;\n      }\n      return m_rhs; \n    }\n    \n    /** Return a reference solution\n     * If it is not provided and if the right hand side is not available\n     * then refX is randomly generated such that A*refX = b \n     * where A and b are the matrix and the rhs. \n     * Note that when a rhs is provided, refX is not available \n     */\n    inline VectorType& refX() \n    { \n      // Check if a reference solution is provided\n      if (m_hasrefX) return m_refX;\n      \n      std::string lhs_file;\n      lhs_file = m_folder + \"/\" + m_matname + \"_x.mtx\"; \n      m_hasrefX = Fileexists(lhs_file);\n      if (m_hasrefX)\n      {\n        m_refX.resize(m_mat.cols());\n        m_hasrefX = loadMarketVector(m_refX, lhs_file);\n      }\n      else\n        m_refX.resize(0);\n      return m_refX; \n    }\n    \n    inline std::string& matname() { return m_matname; }\n    \n    inline int sym() { return m_sym; }\n    \n    bool hasRhs() {return m_hasRhs; }\n    bool hasrefX() {return m_hasrefX; }\n    bool isFolderValid() { return bool(m_folder_id); }\n    \n  protected:\n    \n    inline bool Fileexists(std::string file)\n    {\n      std::ifstream file_id(file.c_str());\n      if (!file_id.good() ) \n      {\n        return false;\n      }\n      else \n      {\n        file_id.close();\n        return true;\n      }\n    }\n    \n    void Getnextvalidmatrix( )\n    {\n      m_isvalid = false;\n      // Here, we return with the next valid matrix in the folder\n      while ( (m_curs_id = readdir(m_folder_id)) != NULL) {\n        m_isvalid = false;\n        std::string curfile;\n        curfile = m_folder + \"/\" + m_curs_id->d_name;\n        // Discard if it is a folder\n        if (m_curs_id->d_type == DT_DIR) continue; //FIXME This may not be available on non BSD systems\n//         struct stat st_buf; \n//         stat (curfile.c_str(), &st_buf);\n//         if (S_ISDIR(st_buf.st_mode)) continue;\n        \n        // Determine from the header if it is a matrix or a right hand side \n        bool isvector,iscomplex=false;\n        if(!getMarketHeader(curfile,m_sym,iscomplex,isvector)) continue;\n        if(isvector) continue;\n        if (!iscomplex)\n        {\n          if(internal::is_same<Scalar, std::complex<float> >::value || internal::is_same<Scalar, std::complex<double> >::value)\n            continue; \n        }\n        if (iscomplex)\n        {\n          if(internal::is_same<Scalar, float>::value || internal::is_same<Scalar, double>::value)\n            continue; \n        }\n        \n        \n        // Get the matrix name\n        std::string filename = m_curs_id->d_name;\n        m_matname = filename.substr(0, filename.length()-4); \n        \n        // Find if the matrix is SPD \n        size_t found = m_matname.find(\"SPD\");\n        if( (found!=std::string::npos) && (m_sym != NonSymmetric) )\n          m_sym = SPD;\n       \n        m_isvalid = true;\n        break; \n      }\n    }\n    int m_sym; // Symmetry of the matrix\n    MatrixType m_mat; // Current matrix  \n    VectorType m_rhs;  // Current vector\n    VectorType m_refX; // The reference solution, if exists\n    std::string m_matname; // Matrix Name\n    bool m_isvalid; \n    bool m_matIsLoaded; // Determine if the matrix has already been loaded from the file\n    bool m_hasRhs; // The right hand side exists\n    bool m_hasrefX; // A reference solution is provided\n    std::string m_folder;\n    DIR * m_folder_id;\n    struct dirent *m_curs_id; \n    \n};\n\n} // end namespace Eigen\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SparseExtra/RandomSetter.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_RANDOMSETTER_H\n#define EIGEN_RANDOMSETTER_H\n\n#if defined(EIGEN_GOOGLEHASH_SUPPORT)\n// Ensure the ::google namespace exists, required for checking existence of \n// ::google::dense_hash_map and ::google::sparse_hash_map.\nnamespace google {}\n#endif\n\nnamespace Eigen {\n\n/** Represents a std::map\n  *\n  * \\see RandomSetter\n  */\ntemplate<typename Scalar> struct StdMapTraits\n{\n  typedef int KeyType;\n  typedef std::map<KeyType,Scalar> Type;\n  enum {\n    IsSorted = 1\n  };\n\n  static void setInvalidKey(Type&, const KeyType&) {}\n};\n\n\n/** Represents a std::unordered_map\n  * \\see RandomSetter\n  */\ntemplate<typename Scalar> struct StdUnorderedMapTraits\n{\n  typedef int KeyType;\n  typedef std::unordered_map<KeyType,Scalar> Type;\n  enum {\n    IsSorted = 0\n  };\n\n  static void setInvalidKey(Type&, const KeyType&) {}\n};\n\n#if defined(EIGEN_GOOGLEHASH_SUPPORT)\n\nnamespace google {\n  \n// Namespace work-around, since sometimes dense_hash_map and sparse_hash_map\n// are in the global namespace, and other times they are under ::google.\nusing namespace ::google;\n\ntemplate<typename KeyType, typename Scalar>\nstruct DenseHashMap {\n  typedef dense_hash_map<KeyType, Scalar> type;\n};\n\ntemplate<typename KeyType, typename Scalar>\nstruct SparseHashMap {\n  typedef sparse_hash_map<KeyType, Scalar> type;\n};\n\n} // namespace google\n\n/** Represents a google::dense_hash_map\n  *\n  * \\see RandomSetter\n  */\ntemplate<typename Scalar> struct GoogleDenseHashMapTraits\n{\n  typedef int KeyType;\n  typedef typename google::DenseHashMap<KeyType,Scalar>::type Type;\n  enum {\n    IsSorted = 0\n  };\n\n  static void setInvalidKey(Type& map, const KeyType& k)\n  { map.set_empty_key(k); }\n};\n\n/** Represents a google::sparse_hash_map\n  *\n  * \\see RandomSetter\n  */\ntemplate<typename Scalar> struct GoogleSparseHashMapTraits\n{\n  typedef int KeyType;\n  typedef typename google::SparseHashMap<KeyType,Scalar>::type Type;\n  enum {\n    IsSorted = 0\n  };\n\n  static void setInvalidKey(Type&, const KeyType&) {}\n};\n#endif\n\n/** \\class RandomSetter\n  *\n  * \\brief The RandomSetter is a wrapper object allowing to set/update a sparse matrix with random access\n  *\n  * \\tparam SparseMatrixType the type of the sparse matrix we are updating\n  * \\tparam MapTraits a traits class representing the map implementation used for the temporary sparse storage.\n  *                  Its default value depends on the system.\n  * \\tparam OuterPacketBits defines the number of rows (or columns) manage by a single map object\n  *                        as a power of two exponent.\n  *\n  * This class temporarily represents a sparse matrix object using a generic map implementation allowing for\n  * efficient random access. The conversion from the compressed representation to a hash_map object is performed\n  * in the RandomSetter constructor, while the sparse matrix is updated back at destruction time. This strategy\n  * suggest the use of nested blocks as in this example:\n  *\n  * \\code\n  * SparseMatrix<double> m(rows,cols);\n  * {\n  *   RandomSetter<SparseMatrix<double> > w(m);\n  *   // don't use m but w instead with read/write random access to the coefficients:\n  *   for(;;)\n  *     w(rand(),rand()) = rand;\n  * }\n  * // when w is deleted, the data are copied back to m\n  * // and m is ready to use.\n  * \\endcode\n  *\n  * Since hash_map objects are not fully sorted, representing a full matrix as a single hash_map would\n  * involve a big and costly sort to update the compressed matrix back. To overcome this issue, a RandomSetter\n  * use multiple hash_map, each representing 2^OuterPacketBits columns or rows according to the storage order.\n  * To reach optimal performance, this value should be adjusted according to the average number of nonzeros\n  * per rows/columns.\n  *\n  * The possible values for the template parameter MapTraits are:\n  *  - \\b StdMapTraits: corresponds to std::map. (does not perform very well)\n  *  - \\b StdUnorderedMapTraits: corresponds to std::unordered_map\n  *  - \\b GoogleDenseHashMapTraits: corresponds to google::dense_hash_map (best efficiency, reasonable memory consumption)\n  *  - \\b GoogleSparseHashMapTraits: corresponds to google::sparse_hash_map (best memory consumption, relatively good performance)\n  *\n  * The default map implementation depends on the availability, and the preferred order is:\n  * GoogleSparseHashMapTraits, StdUnorderedMapTraits, and finally StdMapTraits.\n  *\n  * For performance and memory consumption reasons it is highly recommended to use one of\n  * Google's hash_map implementations. To enable the support for them, you must define\n  * EIGEN_GOOGLEHASH_SUPPORT. This will include both <google/dense_hash_map> and\n  * <google/sparse_hash_map> for you.\n  *\n  * \\see https://github.com/sparsehash/sparsehash\n  */\ntemplate<typename SparseMatrixType,\n         template <typename T> class MapTraits =\n#if defined(EIGEN_GOOGLEHASH_SUPPORT)\n          GoogleDenseHashMapTraits\n#else\n          StdUnorderedMapTraits\n#endif\n         ,int OuterPacketBits = 6>\nclass RandomSetter\n{\n    typedef typename SparseMatrixType::Scalar Scalar;\n    typedef typename SparseMatrixType::StorageIndex StorageIndex;\n\n    struct ScalarWrapper\n    {\n      ScalarWrapper() : value(0) {}\n      Scalar value;\n    };\n    typedef typename MapTraits<ScalarWrapper>::KeyType KeyType;\n    typedef typename MapTraits<ScalarWrapper>::Type HashMapType;\n    static const int OuterPacketMask = (1 << OuterPacketBits) - 1;\n    enum {\n      SwapStorage = 1 - MapTraits<ScalarWrapper>::IsSorted,\n      TargetRowMajor = (SparseMatrixType::Flags & RowMajorBit) ? 1 : 0,\n      SetterRowMajor = SwapStorage ? 1-TargetRowMajor : TargetRowMajor\n    };\n\n  public:\n\n    /** Constructs a random setter object from the sparse matrix \\a target\n      *\n      * Note that the initial value of \\a target are imported. If you want to re-set\n      * a sparse matrix from scratch, then you must set it to zero first using the\n      * setZero() function.\n      */\n    inline RandomSetter(SparseMatrixType& target)\n      : mp_target(&target)\n    {\n      const Index outerSize = SwapStorage ? target.innerSize() : target.outerSize();\n      const Index innerSize = SwapStorage ? target.outerSize() : target.innerSize();\n      m_outerPackets = outerSize >> OuterPacketBits;\n      if (outerSize&OuterPacketMask)\n        m_outerPackets += 1;\n      m_hashmaps = new HashMapType[m_outerPackets];\n      // compute number of bits needed to store inner indices\n      Index aux = innerSize - 1;\n      m_keyBitsOffset = 0;\n      while (aux)\n      {\n        ++m_keyBitsOffset;\n        aux = aux >> 1;\n      }\n      KeyType ik = (1<<(OuterPacketBits+m_keyBitsOffset));\n      for (Index k=0; k<m_outerPackets; ++k)\n        MapTraits<ScalarWrapper>::setInvalidKey(m_hashmaps[k],ik);\n\n      // insert current coeffs\n      for (Index j=0; j<mp_target->outerSize(); ++j)\n        for (typename SparseMatrixType::InnerIterator it(*mp_target,j); it; ++it)\n          (*this)(TargetRowMajor?j:it.index(), TargetRowMajor?it.index():j) = it.value();\n    }\n\n    /** Destructor updating back the sparse matrix target */\n    ~RandomSetter()\n    {\n      KeyType keyBitsMask = (1<<m_keyBitsOffset)-1;\n      if (!SwapStorage) // also means the map is sorted\n      {\n        mp_target->setZero();\n        mp_target->makeCompressed();\n        mp_target->reserve(nonZeros());\n        Index prevOuter = -1;\n        for (Index k=0; k<m_outerPackets; ++k)\n        {\n          const Index outerOffset = (1<<OuterPacketBits) * k;\n          typename HashMapType::iterator end = m_hashmaps[k].end();\n          for (typename HashMapType::iterator it = m_hashmaps[k].begin(); it!=end; ++it)\n          {\n            const Index outer = (it->first >> m_keyBitsOffset) + outerOffset;\n            const Index inner = it->first & keyBitsMask;\n            if (prevOuter!=outer)\n            {\n              for (Index j=prevOuter+1;j<=outer;++j)\n                mp_target->startVec(j);\n              prevOuter = outer;\n            }\n            mp_target->insertBackByOuterInner(outer, inner) = it->second.value;\n          }\n        }\n        mp_target->finalize();\n      }\n      else\n      {\n        VectorXi positions(mp_target->outerSize());\n        positions.setZero();\n        // pass 1\n        for (Index k=0; k<m_outerPackets; ++k)\n        {\n          typename HashMapType::iterator end = m_hashmaps[k].end();\n          for (typename HashMapType::iterator it = m_hashmaps[k].begin(); it!=end; ++it)\n          {\n            const Index outer = it->first & keyBitsMask;\n            ++positions[outer];\n          }\n        }\n        // prefix sum\n        StorageIndex count = 0;\n        for (Index j=0; j<mp_target->outerSize(); ++j)\n        {\n          StorageIndex tmp = positions[j];\n          mp_target->outerIndexPtr()[j] = count;\n          positions[j] = count;\n          count += tmp;\n        }\n        mp_target->makeCompressed();\n        mp_target->outerIndexPtr()[mp_target->outerSize()] = count;\n        mp_target->resizeNonZeros(count);\n        // pass 2\n        for (Index k=0; k<m_outerPackets; ++k)\n        {\n          const Index outerOffset = (1<<OuterPacketBits) * k;\n          typename HashMapType::iterator end = m_hashmaps[k].end();\n          for (typename HashMapType::iterator it = m_hashmaps[k].begin(); it!=end; ++it)\n          {\n            const Index inner = (it->first >> m_keyBitsOffset) + outerOffset;\n            const Index outer = it->first & keyBitsMask;\n            // sorted insertion\n            // Note that we have to deal with at most 2^OuterPacketBits unsorted coefficients,\n            // moreover those 2^OuterPacketBits coeffs are likely to be sparse, an so only a\n            // small fraction of them have to be sorted, whence the following simple procedure:\n            Index posStart = mp_target->outerIndexPtr()[outer];\n            Index i = (positions[outer]++) - 1;\n            while ( (i >= posStart) && (mp_target->innerIndexPtr()[i] > inner) )\n            {\n              mp_target->valuePtr()[i+1] = mp_target->valuePtr()[i];\n              mp_target->innerIndexPtr()[i+1] = mp_target->innerIndexPtr()[i];\n              --i;\n            }\n            mp_target->innerIndexPtr()[i+1] = internal::convert_index<StorageIndex>(inner);\n            mp_target->valuePtr()[i+1] = it->second.value;\n          }\n        }\n      }\n      delete[] m_hashmaps;\n    }\n\n    /** \\returns a reference to the coefficient at given coordinates \\a row, \\a col */\n    Scalar& operator() (Index row, Index col)\n    {\n      const Index outer = SetterRowMajor ? row : col;\n      const Index inner = SetterRowMajor ? col : row;\n      const Index outerMajor = outer >> OuterPacketBits; // index of the packet/map\n      const Index outerMinor = outer & OuterPacketMask;  // index of the inner vector in the packet\n      const KeyType key = internal::convert_index<KeyType>((outerMinor<<m_keyBitsOffset) | inner);\n      return m_hashmaps[outerMajor][key].value;\n    }\n\n    /** \\returns the number of non zero coefficients\n      *\n      * \\note According to the underlying map/hash_map implementation,\n      * this function might be quite expensive.\n      */\n    Index nonZeros() const\n    {\n      Index nz = 0;\n      for (Index k=0; k<m_outerPackets; ++k)\n        nz += static_cast<Index>(m_hashmaps[k].size());\n      return nz;\n    }\n\n\n  protected:\n\n    HashMapType* m_hashmaps;\n    SparseMatrixType* mp_target;\n    Index m_outerPackets;\n    unsigned char m_keyBitsOffset;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_RANDOMSETTER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SpecialFunctions/BesselFunctionsArrayAPI.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#ifndef EIGEN_BESSELFUNCTIONS_ARRAYAPI_H\n#define EIGEN_BESSELFUNCTIONS_ARRAYAPI_H\n\nnamespace Eigen {\n\n/** \\returns an expression of the coefficient-wise i0(\\a x) to the given\n * arrays.\n  *\n  * It returns the modified Bessel function of the first kind of order zero.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of i0(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_i0()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_i0_op<typename Derived::Scalar>, const Derived>\nbessel_i0(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_i0_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise i0e(\\a x) to the given\n * arrays.\n  *\n  * It returns the exponentially scaled modified Bessel\n  * function of the first kind of order zero.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of i0e(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_i0e()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_i0e_op<typename Derived::Scalar>, const Derived>\nbessel_i0e(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_i0e_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise i1(\\a x) to the given\n * arrays.\n  *\n  * It returns the modified Bessel function of the first kind of order one.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of i1(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_i1()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_i1_op<typename Derived::Scalar>, const Derived>\nbessel_i1(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_i1_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise i1e(\\a x) to the given\n * arrays.\n  *\n  * It returns the exponentially scaled modified Bessel\n  * function of the first kind of order one.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of i1e(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_i1e()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_i1e_op<typename Derived::Scalar>, const Derived>\nbessel_i1e(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_i1e_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise k0(\\a x) to the given\n * arrays.\n  *\n  * It returns the modified Bessel function of the second kind of order zero.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of k0(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_k0()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_k0_op<typename Derived::Scalar>, const Derived>\nbessel_k0(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_k0_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise k0e(\\a x) to the given\n * arrays.\n  *\n  * It returns the exponentially scaled modified Bessel\n  * function of the second kind of order zero.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of k0e(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_k0e()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_k0e_op<typename Derived::Scalar>, const Derived>\nbessel_k0e(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_k0e_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise k1(\\a x) to the given\n * arrays.\n  *\n  * It returns the modified Bessel function of the second kind of order one.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of k1(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_k1()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_k1_op<typename Derived::Scalar>, const Derived>\nbessel_k1(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_k1_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise k1e(\\a x) to the given\n * arrays.\n  *\n  * It returns the exponentially scaled modified Bessel\n  * function of the second kind of order one.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of k1e(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_k1e()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_k1e_op<typename Derived::Scalar>, const Derived>\nbessel_k1e(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_k1e_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise j0(\\a x) to the given\n * arrays.\n  *\n  * It returns the Bessel function of the first kind of order zero.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of j0(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_j0()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_j0_op<typename Derived::Scalar>, const Derived>\nbessel_j0(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_j0_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise y0(\\a x) to the given\n * arrays.\n  *\n  * It returns the Bessel function of the second kind of order zero.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of y0(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_y0()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_y0_op<typename Derived::Scalar>, const Derived>\nbessel_y0(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_y0_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise j1(\\a x) to the given\n * arrays.\n  *\n  * It returns the modified Bessel function of the first kind of order one.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of j1(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_j1()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_j1_op<typename Derived::Scalar>, const Derived>\nbessel_j1(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_j1_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise y1(\\a x) to the given\n * arrays.\n  *\n  * It returns the Bessel function of the second kind of order one.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of y1(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_y1()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_y1_op<typename Derived::Scalar>, const Derived>\nbessel_y1(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_y1_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_BESSELFUNCTIONS_ARRAYAPI_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SpecialFunctions/BesselFunctionsBFloat16.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BESSELFUNCTIONS_BFLOAT16_H\n#define EIGEN_BESSELFUNCTIONS_BFLOAT16_H\n\nnamespace Eigen {\nnamespace numext {\n\n#if EIGEN_HAS_C99_MATH\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_i0(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_i0(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_i0e(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_i0e(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_i1(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_i1(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_i1e(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_i1e(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_j0(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_j0(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_j1(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_j1(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_y0(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_y0(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_y1(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_y1(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_k0(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_k0(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_k0e(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_k0e(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_k1(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_k1(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_k1e(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_k1e(static_cast<float>(x)));\n}\n#endif\n\n}  // end namespace numext\n}  // end namespace Eigen\n\n#endif  // EIGEN_BESSELFUNCTIONS_BFLOAT16_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SpecialFunctions/BesselFunctionsFunctors.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Eugene Brevdo <ebrevdo@gmail.com>\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BESSELFUNCTIONS_FUNCTORS_H\n#define EIGEN_BESSELFUNCTIONS_FUNCTORS_H\n\nnamespace Eigen {\n\nnamespace internal {\n\n/** \\internal\n * \\brief Template functor to compute the modified Bessel function of the first\n * kind of order zero.\n * \\sa class CwiseUnaryOp, Cwise::bessel_i0()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_i0_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_i0_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_i0;\n    return bessel_i0(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_i0(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_i0_op<Scalar> > {\n  enum {\n    // On average, a Chebyshev polynomial of order N=20 is computed.\n    // The cost is N multiplications and 2N additions. We also add\n    // the cost of an additional exp over i0e.\n    Cost = 28 * NumTraits<Scalar>::MulCost + 48 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the exponentially scaled modified Bessel\n * function of the first kind of order zero\n * \\sa class CwiseUnaryOp, Cwise::bessel_i0e()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_i0e_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_i0e_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_i0e;\n    return bessel_i0e(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_i0e(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_i0e_op<Scalar> > {\n  enum {\n    // On average, a Chebyshev polynomial of order N=20 is computed.\n    // The cost is N multiplications and 2N additions.\n    Cost = 20 * NumTraits<Scalar>::MulCost + 40 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the modified Bessel function of the first\n * kind of order one\n * \\sa class CwiseUnaryOp, Cwise::bessel_i1()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_i1_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_i1_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_i1;\n    return bessel_i1(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_i1(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_i1_op<Scalar> > {\n  enum {\n    // On average, a Chebyshev polynomial of order N=20 is computed.\n    // The cost is N multiplications and 2N additions. We also add\n    // the cost of an additional exp over i1e.\n    Cost = 28 * NumTraits<Scalar>::MulCost + 48 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the exponentially scaled modified Bessel\n * function of the first kind of order zero\n * \\sa class CwiseUnaryOp, Cwise::bessel_i1e()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_i1e_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_i1e_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_i1e;\n    return bessel_i1e(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_i1e(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_i1e_op<Scalar> > {\n  enum {\n    // On average, a Chebyshev polynomial of order N=20 is computed.\n    // The cost is N multiplications and 2N additions.\n    Cost = 20 * NumTraits<Scalar>::MulCost + 40 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the Bessel function of the second kind of\n * order zero\n * \\sa class CwiseUnaryOp, Cwise::bessel_j0()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_j0_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_j0_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_j0;\n    return bessel_j0(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_j0(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_j0_op<Scalar> > {\n  enum {\n    // 6 polynomial of order ~N=8 is computed.\n    // The cost is N multiplications and N additions each, along with a\n    // sine, cosine and rsqrt cost.\n    Cost = 63 * NumTraits<Scalar>::MulCost + 48 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the Bessel function of the second kind of\n * order zero\n * \\sa class CwiseUnaryOp, Cwise::bessel_y0()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_y0_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_y0_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_y0;\n    return bessel_y0(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_y0(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_y0_op<Scalar> > {\n  enum {\n    // 6 polynomial of order ~N=8 is computed.\n    // The cost is N multiplications and N additions each, along with a\n    // sine, cosine, rsqrt and j0 cost.\n    Cost = 126 * NumTraits<Scalar>::MulCost + 96 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the Bessel function of the first kind of\n * order one\n * \\sa class CwiseUnaryOp, Cwise::bessel_j1()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_j1_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_j1_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_j1;\n    return bessel_j1(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_j1(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_j1_op<Scalar> > {\n  enum {\n    // 6 polynomial of order ~N=8 is computed.\n    // The cost is N multiplications and N additions each, along with a\n    // sine, cosine and rsqrt cost.\n    Cost = 63 * NumTraits<Scalar>::MulCost + 48 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the Bessel function of the second kind of\n * order one\n * \\sa class CwiseUnaryOp, Cwise::bessel_j1e()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_y1_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_y1_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_y1;\n    return bessel_y1(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_y1(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_y1_op<Scalar> > {\n  enum {\n    // 6 polynomial of order ~N=8 is computed.\n    // The cost is N multiplications and N additions each, along with a\n    // sine, cosine, rsqrt and j1 cost.\n    Cost = 126 * NumTraits<Scalar>::MulCost + 96 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the modified Bessel function of the second\n * kind of order zero\n * \\sa class CwiseUnaryOp, Cwise::bessel_k0()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_k0_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_k0_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_k0;\n    return bessel_k0(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_k0(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_k0_op<Scalar> > {\n  enum {\n    // On average, a Chebyshev polynomial of order N=10 is computed.\n    // The cost is N multiplications and 2N additions. In addition we compute\n    // i0, a log, exp and prsqrt and sin and cos.\n    Cost = 68 * NumTraits<Scalar>::MulCost + 88 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the exponentially scaled modified Bessel\n * function of the second kind of order zero\n * \\sa class CwiseUnaryOp, Cwise::bessel_k0e()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_k0e_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_k0e_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_k0e;\n    return bessel_k0e(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_k0e(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_k0e_op<Scalar> > {\n  enum {\n    // On average, a Chebyshev polynomial of order N=10 is computed.\n    // The cost is N multiplications and 2N additions. In addition we compute\n    // i0, a log, exp and prsqrt and sin and cos.\n    Cost = 68 * NumTraits<Scalar>::MulCost + 88 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the modified Bessel function of the\n * second kind of order one\n * \\sa class CwiseUnaryOp, Cwise::bessel_k1()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_k1_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_k1_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_k1;\n    return bessel_k1(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_k1(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_k1_op<Scalar> > {\n  enum {\n    // On average, a Chebyshev polynomial of order N=10 is computed.\n    // The cost is N multiplications and 2N additions. In addition we compute\n    // i1, a log, exp and prsqrt and sin and cos.\n    Cost = 68 * NumTraits<Scalar>::MulCost + 88 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the exponentially scaled modified Bessel\n * function of the second kind of order one\n * \\sa class CwiseUnaryOp, Cwise::bessel_k1e()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_k1e_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_k1e_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_k1e;\n    return bessel_k1e(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_k1e(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_k1e_op<Scalar> > {\n  enum {\n    // On average, a Chebyshev polynomial of order N=10 is computed.\n    // The cost is N multiplications and 2N additions. In addition we compute\n    // i1, a log, exp and prsqrt and sin and cos.\n    Cost = 68 * NumTraits<Scalar>::MulCost + 88 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_BESSELFUNCTIONS_FUNCTORS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SpecialFunctions/BesselFunctionsHalf.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BESSELFUNCTIONS_HALF_H\n#define EIGEN_BESSELFUNCTIONS_HALF_H\n\nnamespace Eigen {\nnamespace numext {\n\n#if EIGEN_HAS_C99_MATH\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_i0(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_i0(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_i0e(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_i0e(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_i1(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_i1(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_i1e(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_i1e(static_cast<float>(x)));\n}\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_j0(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_j0(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_j1(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_j1(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_y0(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_y0(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_y1(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_y1(static_cast<float>(x)));\n}\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_k0(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_k0(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_k0e(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_k0e(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_k1(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_k1(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_k1e(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_k1e(static_cast<float>(x)));\n}\n#endif\n\n}  // end namespace numext\n}  // end namespace Eigen\n\n#endif  // EIGEN_BESSELFUNCTIONS_HALF_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SpecialFunctions/BesselFunctionsImpl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Eugene Brevdo <ebrevdo@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BESSEL_FUNCTIONS_H\n#define EIGEN_BESSEL_FUNCTIONS_H\n\nnamespace Eigen {\nnamespace internal {\n\n//  Parts of this code are based on the Cephes Math Library.\n//\n//  Cephes Math Library Release 2.8:  June, 2000\n//  Copyright 1984, 1987, 1992, 2000 by Stephen L. Moshier\n//\n//  Permission has been kindly provided by the original author\n//  to incorporate the Cephes software into the Eigen codebase:\n//\n//    From: Stephen Moshier\n//    To: Eugene Brevdo\n//    Subject: Re: Permission to wrap several cephes functions in Eigen\n//\n//    Hello Eugene,\n//\n//    Thank you for writing.\n//\n//    If your licensing is similar to BSD, the formal way that has been\n//    handled is simply to add a statement to the effect that you are incorporating\n//    the Cephes software by permission of the author.\n//\n//    Good luck with your project,\n//    Steve\n\n\n/****************************************************************************\n * Implementation of Bessel function, based on Cephes                       *\n ****************************************************************************/\n\ntemplate <typename Scalar>\nstruct bessel_i0e_retval {\n  typedef Scalar type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_i0e {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T&) {\n    EIGEN_STATIC_ASSERT((internal::is_same<T, T>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return ScalarType(0);\n  }\n};\n\ntemplate <typename T>\nstruct generic_i0e<T, float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  i0ef.c\n     *\n     *  Modified Bessel function of order zero,\n     *  exponentially scaled\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float x, y, i0ef();\n     *\n     * y = i0ef( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns exponentially scaled modified Bessel function\n     * of order zero of the argument.\n     *\n     * The function is defined as i0e(x) = exp(-|x|) j0( ix ).\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0,30        100000      3.7e-7      7.0e-8\n     * See i0f().\n     *\n     */\n\n    const float A[] = {-1.30002500998624804212E-8f, 6.04699502254191894932E-8f,\n                       -2.67079385394061173391E-7f, 1.11738753912010371815E-6f,\n                       -4.41673835845875056359E-6f, 1.64484480707288970893E-5f,\n                       -5.75419501008210370398E-5f, 1.88502885095841655729E-4f,\n                       -5.76375574538582365885E-4f, 1.63947561694133579842E-3f,\n                       -4.32430999505057594430E-3f, 1.05464603945949983183E-2f,\n                       -2.37374148058994688156E-2f, 4.93052842396707084878E-2f,\n                       -9.49010970480476444210E-2f, 1.71620901522208775349E-1f,\n                       -3.04682672343198398683E-1f, 6.76795274409476084995E-1f};\n\n    const float B[] = {3.39623202570838634515E-9f, 2.26666899049817806459E-8f,\n                       2.04891858946906374183E-7f, 2.89137052083475648297E-6f,\n                       6.88975834691682398426E-5f, 3.36911647825569408990E-3f,\n                       8.04490411014108831608E-1f};\n    T y = pabs(x);\n    T y_le_eight = internal::pchebevl<T, 18>::run(\n        pmadd(pset1<T>(0.5f), y, pset1<T>(-2.0f)), A);\n    T y_gt_eight = pmul(\n        internal::pchebevl<T, 7>::run(\n            psub(pdiv(pset1<T>(32.0f), y), pset1<T>(2.0f)), B),\n        prsqrt(y));\n    // TODO: Perhaps instead check whether all packet elements are in\n    // [-8, 8] and evaluate a branch based off of that. It's possible\n    // in practice most elements are in this region.\n    return pselect(pcmp_le(y, pset1<T>(8.0f)), y_le_eight, y_gt_eight);\n  }\n};\n\ntemplate <typename T>\nstruct generic_i0e<T, double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  i0e.c\n     *\n     *  Modified Bessel function of order zero,\n     *  exponentially scaled\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, i0e();\n     *\n     * y = i0e( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns exponentially scaled modified Bessel function\n     * of order zero of the argument.\n     *\n     * The function is defined as i0e(x) = exp(-|x|) j0( ix ).\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0,30        30000       5.4e-16     1.2e-16\n     * See i0().\n     *\n     */\n\n    const double A[] = {-4.41534164647933937950E-18, 3.33079451882223809783E-17,\n                        -2.43127984654795469359E-16, 1.71539128555513303061E-15,\n                        -1.16853328779934516808E-14, 7.67618549860493561688E-14,\n                        -4.85644678311192946090E-13, 2.95505266312963983461E-12,\n                        -1.72682629144155570723E-11, 9.67580903537323691224E-11,\n                        -5.18979560163526290666E-10, 2.65982372468238665035E-9,\n                        -1.30002500998624804212E-8,  6.04699502254191894932E-8,\n                        -2.67079385394061173391E-7,  1.11738753912010371815E-6,\n                        -4.41673835845875056359E-6,  1.64484480707288970893E-5,\n                        -5.75419501008210370398E-5,  1.88502885095841655729E-4,\n                        -5.76375574538582365885E-4,  1.63947561694133579842E-3,\n                        -4.32430999505057594430E-3,  1.05464603945949983183E-2,\n                        -2.37374148058994688156E-2,  4.93052842396707084878E-2,\n                        -9.49010970480476444210E-2,  1.71620901522208775349E-1,\n                        -3.04682672343198398683E-1,  6.76795274409476084995E-1};\n    const double B[] = {\n        -7.23318048787475395456E-18, -4.83050448594418207126E-18,\n        4.46562142029675999901E-17,  3.46122286769746109310E-17,\n        -2.82762398051658348494E-16, -3.42548561967721913462E-16,\n        1.77256013305652638360E-15,  3.81168066935262242075E-15,\n        -9.55484669882830764870E-15, -4.15056934728722208663E-14,\n        1.54008621752140982691E-14,  3.85277838274214270114E-13,\n        7.18012445138366623367E-13,  -1.79417853150680611778E-12,\n        -1.32158118404477131188E-11, -3.14991652796324136454E-11,\n        1.18891471078464383424E-11,  4.94060238822496958910E-10,\n        3.39623202570838634515E-9,   2.26666899049817806459E-8,\n        2.04891858946906374183E-7,   2.89137052083475648297E-6,\n        6.88975834691682398426E-5,   3.36911647825569408990E-3,\n        8.04490411014108831608E-1};\n    T y = pabs(x);\n    T y_le_eight = internal::pchebevl<T, 30>::run(\n        pmadd(pset1<T>(0.5), y, pset1<T>(-2.0)), A);\n    T y_gt_eight = pmul(\n        internal::pchebevl<T, 25>::run(\n            psub(pdiv(pset1<T>(32.0), y), pset1<T>(2.0)), B),\n        prsqrt(y));\n    // TODO: Perhaps instead check whether all packet elements are in\n    // [-8, 8] and evaluate a branch based off of that. It's possible\n    // in practice most elements are in this region.\n    return pselect(pcmp_le(y, pset1<T>(8.0)), y_le_eight, y_gt_eight);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_i0e_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_i0e<T>::run(x);\n  }\n};\n\ntemplate <typename Scalar>\nstruct bessel_i0_retval {\n  typedef Scalar type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_i0 {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    return pmul(\n        pexp(pabs(x)),\n        generic_i0e<T, ScalarType>::run(x));\n  }\n};\n\ntemplate <typename T>\nstruct bessel_i0_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_i0<T>::run(x);\n  }\n};\n\ntemplate <typename Scalar>\nstruct bessel_i1e_retval {\n  typedef Scalar type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type >\nstruct generic_i1e {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T&) {\n    EIGEN_STATIC_ASSERT((internal::is_same<T, T>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return ScalarType(0);\n  }\n};\n\ntemplate <typename T>\nstruct generic_i1e<T, float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /* i1ef.c\n     *\n     *  Modified Bessel function of order one,\n     *  exponentially scaled\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float x, y, i1ef();\n     *\n     * y = i1ef( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns exponentially scaled modified Bessel function\n     * of order one of the argument.\n     *\n     * The function is defined as i1(x) = -i exp(-|x|) j1( ix ).\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 30       30000       1.5e-6      1.5e-7\n     * See i1().\n     *\n     */\n    const float A[] = {9.38153738649577178388E-9f, -4.44505912879632808065E-8f,\n                       2.00329475355213526229E-7f, -8.56872026469545474066E-7f,\n                       3.47025130813767847674E-6f, -1.32731636560394358279E-5f,\n                       4.78156510755005422638E-5f, -1.61760815825896745588E-4f,\n                       5.12285956168575772895E-4f, -1.51357245063125314899E-3f,\n                       4.15642294431288815669E-3f, -1.05640848946261981558E-2f,\n                       2.47264490306265168283E-2f, -5.29459812080949914269E-2f,\n                       1.02643658689847095384E-1f, -1.76416518357834055153E-1f,\n                       2.52587186443633654823E-1f};\n\n    const float B[] = {-3.83538038596423702205E-9f, -2.63146884688951950684E-8f,\n                       -2.51223623787020892529E-7f, -3.88256480887769039346E-6f,\n                       -1.10588938762623716291E-4f, -9.76109749136146840777E-3f,\n                       7.78576235018280120474E-1f};\n\n\n    T y = pabs(x);\n    T y_le_eight = pmul(y, internal::pchebevl<T, 17>::run(\n        pmadd(pset1<T>(0.5f), y, pset1<T>(-2.0f)), A));\n    T y_gt_eight = pmul(\n        internal::pchebevl<T, 7>::run(\n            psub(pdiv(pset1<T>(32.0f), y),\n                 pset1<T>(2.0f)), B),\n        prsqrt(y));\n    // TODO: Perhaps instead check whether all packet elements are in\n    // [-8, 8] and evaluate a branch based off of that. It's possible\n    // in practice most elements are in this region.\n    y = pselect(pcmp_le(y, pset1<T>(8.0f)), y_le_eight, y_gt_eight);\n    return pselect(pcmp_lt(x, pset1<T>(0.0f)), pnegate(y), y);\n  }\n};\n\ntemplate <typename T>\nstruct generic_i1e<T, double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  i1e.c\n     *\n     *  Modified Bessel function of order one,\n     *  exponentially scaled\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, i1e();\n     *\n     * y = i1e( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns exponentially scaled modified Bessel function\n     * of order one of the argument.\n     *\n     * The function is defined as i1(x) = -i exp(-|x|) j1( ix ).\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 30       30000       2.0e-15     2.0e-16\n     * See i1().\n     *\n     */\n    const double A[] = {2.77791411276104639959E-18, -2.11142121435816608115E-17,\n                        1.55363195773620046921E-16, -1.10559694773538630805E-15,\n                        7.60068429473540693410E-15, -5.04218550472791168711E-14,\n                        3.22379336594557470981E-13, -1.98397439776494371520E-12,\n                        1.17361862988909016308E-11, -6.66348972350202774223E-11,\n                        3.62559028155211703701E-10, -1.88724975172282928790E-9,\n                        9.38153738649577178388E-9,  -4.44505912879632808065E-8,\n                        2.00329475355213526229E-7,  -8.56872026469545474066E-7,\n                        3.47025130813767847674E-6,  -1.32731636560394358279E-5,\n                        4.78156510755005422638E-5,  -1.61760815825896745588E-4,\n                        5.12285956168575772895E-4,  -1.51357245063125314899E-3,\n                        4.15642294431288815669E-3,  -1.05640848946261981558E-2,\n                        2.47264490306265168283E-2,  -5.29459812080949914269E-2,\n                        1.02643658689847095384E-1,  -1.76416518357834055153E-1,\n                        2.52587186443633654823E-1};\n    const double B[] = {\n        7.51729631084210481353E-18,  4.41434832307170791151E-18,\n        -4.65030536848935832153E-17, -3.20952592199342395980E-17,\n        2.96262899764595013876E-16,  3.30820231092092828324E-16,\n        -1.88035477551078244854E-15, -3.81440307243700780478E-15,\n        1.04202769841288027642E-14,  4.27244001671195135429E-14,\n        -2.10154184277266431302E-14, -4.08355111109219731823E-13,\n        -7.19855177624590851209E-13, 2.03562854414708950722E-12,\n        1.41258074366137813316E-11,  3.25260358301548823856E-11,\n        -1.89749581235054123450E-11, -5.58974346219658380687E-10,\n        -3.83538038596423702205E-9,  -2.63146884688951950684E-8,\n        -2.51223623787020892529E-7,  -3.88256480887769039346E-6,\n        -1.10588938762623716291E-4,  -9.76109749136146840777E-3,\n        7.78576235018280120474E-1};\n    T y = pabs(x);\n    T y_le_eight = pmul(y, internal::pchebevl<T, 29>::run(\n        pmadd(pset1<T>(0.5), y, pset1<T>(-2.0)), A));\n    T y_gt_eight = pmul(\n        internal::pchebevl<T, 25>::run(\n            psub(pdiv(pset1<T>(32.0), y),\n                 pset1<T>(2.0)), B),\n        prsqrt(y));\n    // TODO: Perhaps instead check whether all packet elements are in\n    // [-8, 8] and evaluate a branch based off of that. It's possible\n    // in practice most elements are in this region.\n    y = pselect(pcmp_le(y, pset1<T>(8.0)), y_le_eight, y_gt_eight);\n    return pselect(pcmp_lt(x, pset1<T>(0.0)), pnegate(y), y);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_i1e_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_i1e<T>::run(x);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_i1_retval {\n  typedef T type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_i1 {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    return pmul(\n        pexp(pabs(x)),\n        generic_i1e<T, ScalarType>::run(x));\n  }\n};\n\ntemplate <typename T>\nstruct bessel_i1_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_i1<T>::run(x);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_k0e_retval {\n  typedef T type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_k0e {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T&) {\n    EIGEN_STATIC_ASSERT((internal::is_same<T, T>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return ScalarType(0);\n  }\n};\n\ntemplate <typename T>\nstruct generic_k0e<T, float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  k0ef.c\n     *\tModified Bessel function, third kind, order zero,\n     *\texponentially scaled\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float x, y, k0ef();\n     *\n     * y = k0ef( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns exponentially scaled modified Bessel function\n     * of the third kind of order zero of the argument.\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 30       30000       8.1e-7      7.8e-8\n     * See k0().\n     *\n     */\n\n    const float A[] = {1.90451637722020886025E-9f, 2.53479107902614945675E-7f,\n                       2.28621210311945178607E-5f, 1.26461541144692592338E-3f,\n                       3.59799365153615016266E-2f, 3.44289899924628486886E-1f,\n                       -5.35327393233902768720E-1f};\n\n    const float B[] = {-1.69753450938905987466E-9f, 8.57403401741422608519E-9f,\n                       -4.66048989768794782956E-8f, 2.76681363944501510342E-7f,\n                       -1.83175552271911948767E-6f, 1.39498137188764993662E-5f,\n                       -1.28495495816278026384E-4f, 1.56988388573005337491E-3f,\n                       -3.14481013119645005427E-2f, 2.44030308206595545468E0f};\n    const T MAXNUM = pset1<T>(NumTraits<float>::infinity());\n    const T two = pset1<T>(2.0);\n    T x_le_two = internal::pchebevl<T, 7>::run(\n        pmadd(x, x, pset1<T>(-2.0)), A);\n    x_le_two = pmadd(\n        generic_i0<T, float>::run(x), pnegate(\n            plog(pmul(pset1<T>(0.5), x))), x_le_two);\n    x_le_two = pmul(pexp(x), x_le_two);\n    T x_gt_two = pmul(\n            internal::pchebevl<T, 10>::run(\n                psub(pdiv(pset1<T>(8.0), x), two), B),\n            prsqrt(x));\n    return pselect(\n        pcmp_le(x, pset1<T>(0.0)),\n        MAXNUM,\n        pselect(pcmp_le(x, two), x_le_two, x_gt_two));\n  }\n};\n\ntemplate <typename T>\nstruct generic_k0e<T, double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  k0e.c\n     *\tModified Bessel function, third kind, order zero,\n     *\texponentially scaled\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, k0e();\n     *\n     * y = k0e( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns exponentially scaled modified Bessel function\n     * of the third kind of order zero of the argument.\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 30       30000       1.4e-15     1.4e-16\n     * See k0().\n     *\n     */\n\n    const double A[] = {\n      1.37446543561352307156E-16,\n      4.25981614279661018399E-14,\n      1.03496952576338420167E-11,\n      1.90451637722020886025E-9,\n      2.53479107902614945675E-7,\n      2.28621210311945178607E-5,\n      1.26461541144692592338E-3,\n      3.59799365153615016266E-2,\n      3.44289899924628486886E-1,\n      -5.35327393233902768720E-1};\n    const double B[] = {\n       5.30043377268626276149E-18, -1.64758043015242134646E-17,\n       5.21039150503902756861E-17, -1.67823109680541210385E-16,\n       5.51205597852431940784E-16, -1.84859337734377901440E-15,\n       6.34007647740507060557E-15, -2.22751332699166985548E-14,\n       8.03289077536357521100E-14, -2.98009692317273043925E-13,\n       1.14034058820847496303E-12, -4.51459788337394416547E-12,\n       1.85594911495471785253E-11, -7.95748924447710747776E-11,\n       3.57739728140030116597E-10, -1.69753450938905987466E-9,\n       8.57403401741422608519E-9, -4.66048989768794782956E-8,\n       2.76681363944501510342E-7, -1.83175552271911948767E-6,\n       1.39498137188764993662E-5, -1.28495495816278026384E-4,\n       1.56988388573005337491E-3, -3.14481013119645005427E-2,\n       2.44030308206595545468E0\n    };\n    const T MAXNUM = pset1<T>(NumTraits<double>::infinity());\n    const T two = pset1<T>(2.0);\n    T x_le_two = internal::pchebevl<T, 10>::run(\n        pmadd(x, x, pset1<T>(-2.0)), A);\n    x_le_two = pmadd(\n        generic_i0<T, double>::run(x), pmul(\n            pset1<T>(-1.0), plog(pmul(pset1<T>(0.5), x))), x_le_two);\n    x_le_two = pmul(pexp(x), x_le_two);\n    x_le_two = pselect(pcmp_le(x, pset1<T>(0.0)), MAXNUM, x_le_two);\n    T x_gt_two = pmul(\n            internal::pchebevl<T, 25>::run(\n                psub(pdiv(pset1<T>(8.0), x), two), B),\n            prsqrt(x));\n    return pselect(pcmp_le(x, two), x_le_two, x_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_k0e_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_k0e<T>::run(x);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_k0_retval {\n  typedef T type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_k0 {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T&) {\n    EIGEN_STATIC_ASSERT((internal::is_same<T, T>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return ScalarType(0);\n  }\n};\n\ntemplate <typename T>\nstruct generic_k0<T, float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  k0f.c\n     *\tModified Bessel function, third kind, order zero\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float x, y, k0f();\n     *\n     * y = k0f( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns modified Bessel function of the third kind\n     * of order zero of the argument.\n     *\n     * The range is partitioned into the two intervals [0,8] and\n     * (8, infinity).  Chebyshev polynomial expansions are employed\n     * in each interval.\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     * Tested at 2000 random points between 0 and 8.  Peak absolute\n     * error (relative when K0 > 1) was 1.46e-14; rms, 4.26e-15.\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 30       30000       7.8e-7      8.5e-8\n     *\n     * ERROR MESSAGES:\n     *\n     *   message         condition      value returned\n     *  K0 domain          x <= 0          MAXNUM\n     *\n     */\n\n    const float A[] = {1.90451637722020886025E-9f, 2.53479107902614945675E-7f,\n                       2.28621210311945178607E-5f, 1.26461541144692592338E-3f,\n                       3.59799365153615016266E-2f, 3.44289899924628486886E-1f,\n                       -5.35327393233902768720E-1f};\n\n    const float B[] = {-1.69753450938905987466E-9f, 8.57403401741422608519E-9f,\n                       -4.66048989768794782956E-8f, 2.76681363944501510342E-7f,\n                       -1.83175552271911948767E-6f, 1.39498137188764993662E-5f,\n                       -1.28495495816278026384E-4f, 1.56988388573005337491E-3f,\n                       -3.14481013119645005427E-2f, 2.44030308206595545468E0f};\n    const T MAXNUM = pset1<T>(NumTraits<float>::infinity());\n    const T two = pset1<T>(2.0);\n    T x_le_two = internal::pchebevl<T, 7>::run(\n        pmadd(x, x, pset1<T>(-2.0)), A);\n    x_le_two = pmadd(\n        generic_i0<T, float>::run(x), pnegate(\n            plog(pmul(pset1<T>(0.5), x))), x_le_two);\n    x_le_two = pselect(pcmp_le(x, pset1<T>(0.0)), MAXNUM, x_le_two);\n    T x_gt_two = pmul(\n        pmul(\n            pexp(pnegate(x)),\n            internal::pchebevl<T, 10>::run(\n                psub(pdiv(pset1<T>(8.0), x), two), B)),\n        prsqrt(x));\n    return pselect(pcmp_le(x, two), x_le_two, x_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct generic_k0<T, double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*\n     *\n     *\tModified Bessel function, third kind, order zero,\n     *\texponentially scaled\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, k0();\n     *\n     * y = k0( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns exponentially scaled modified Bessel function\n     * of the third kind of order zero of the argument.\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 30       30000       1.4e-15     1.4e-16\n     * See k0().\n     *\n     */\n    const double A[] = {\n      1.37446543561352307156E-16,\n      4.25981614279661018399E-14,\n      1.03496952576338420167E-11,\n      1.90451637722020886025E-9,\n      2.53479107902614945675E-7,\n      2.28621210311945178607E-5,\n      1.26461541144692592338E-3,\n      3.59799365153615016266E-2,\n      3.44289899924628486886E-1,\n      -5.35327393233902768720E-1};\n    const double B[] = {\n       5.30043377268626276149E-18, -1.64758043015242134646E-17,\n       5.21039150503902756861E-17, -1.67823109680541210385E-16,\n       5.51205597852431940784E-16, -1.84859337734377901440E-15,\n       6.34007647740507060557E-15, -2.22751332699166985548E-14,\n       8.03289077536357521100E-14, -2.98009692317273043925E-13,\n       1.14034058820847496303E-12, -4.51459788337394416547E-12,\n       1.85594911495471785253E-11, -7.95748924447710747776E-11,\n       3.57739728140030116597E-10, -1.69753450938905987466E-9,\n       8.57403401741422608519E-9, -4.66048989768794782956E-8,\n       2.76681363944501510342E-7, -1.83175552271911948767E-6,\n       1.39498137188764993662E-5, -1.28495495816278026384E-4,\n       1.56988388573005337491E-3, -3.14481013119645005427E-2,\n       2.44030308206595545468E0\n    };\n    const T MAXNUM = pset1<T>(NumTraits<double>::infinity());\n    const T two = pset1<T>(2.0);\n    T x_le_two = internal::pchebevl<T, 10>::run(\n        pmadd(x, x, pset1<T>(-2.0)), A);\n    x_le_two = pmadd(\n        generic_i0<T, double>::run(x), pnegate(\n            plog(pmul(pset1<T>(0.5), x))), x_le_two);\n    x_le_two = pselect(pcmp_le(x, pset1<T>(0.0)), MAXNUM, x_le_two);\n    T x_gt_two = pmul(\n        pmul(\n            pexp(-x),\n            internal::pchebevl<T, 25>::run(\n                psub(pdiv(pset1<T>(8.0), x), two), B)),\n        prsqrt(x));\n    return pselect(pcmp_le(x, two), x_le_two, x_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_k0_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_k0<T>::run(x);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_k1e_retval {\n  typedef T type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_k1e {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T&) {\n    EIGEN_STATIC_ASSERT((internal::is_same<T, T>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return ScalarType(0);\n  }\n};\n\ntemplate <typename T>\nstruct generic_k1e<T, float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /* k1ef.c\n     *\n     *\tModified Bessel function, third kind, order one,\n     *\texponentially scaled\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float x, y, k1ef();\n     *\n     * y = k1ef( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns exponentially scaled modified Bessel function\n     * of the third kind of order one of the argument:\n     *\n     *      k1e(x) = exp(x) * k1(x).\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 30       30000       4.9e-7      6.7e-8\n     * See k1().\n     *\n     */\n\n    const float A[] = {-2.21338763073472585583E-8f, -2.43340614156596823496E-6f,\n                        -1.73028895751305206302E-4f, -6.97572385963986435018E-3f,\n                        -1.22611180822657148235E-1f, -3.53155960776544875667E-1f,\n                        1.52530022733894777053E0f};\n    const float B[] = {2.01504975519703286596E-9f, -1.03457624656780970260E-8f,\n                       5.74108412545004946722E-8f, -3.50196060308781257119E-7f,\n                       2.40648494783721712015E-6f, -1.93619797416608296024E-5f,\n                       1.95215518471351631108E-4f, -2.85781685962277938680E-3f,\n                       1.03923736576817238437E-1f, 2.72062619048444266945E0f};\n    const T MAXNUM = pset1<T>(NumTraits<float>::infinity());\n    const T two = pset1<T>(2.0);\n    T x_le_two = pdiv(internal::pchebevl<T, 7>::run(\n        pmadd(x, x, pset1<T>(-2.0)), A), x);\n    x_le_two = pmadd(\n        generic_i1<T, float>::run(x), plog(pmul(pset1<T>(0.5), x)), x_le_two);\n    x_le_two = pmul(x_le_two, pexp(x));\n    x_le_two = pselect(pcmp_le(x, pset1<T>(0.0)), MAXNUM, x_le_two);\n    T x_gt_two = pmul(\n        internal::pchebevl<T, 10>::run(\n            psub(pdiv(pset1<T>(8.0), x), two), B),\n        prsqrt(x));\n    return pselect(pcmp_le(x, two), x_le_two, x_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct generic_k1e<T, double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  k1e.c\n     *\n     *\tModified Bessel function, third kind, order one,\n     *\texponentially scaled\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, k1e();\n     *\n     * y = k1e( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns exponentially scaled modified Bessel function\n     * of the third kind of order one of the argument:\n     *\n     *      k1e(x) = exp(x) * k1(x).\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 30       30000       7.8e-16     1.2e-16\n     * See k1().\n     *\n     */\n    const double A[] = {-7.02386347938628759343E-18, -2.42744985051936593393E-15,\n                        -6.66690169419932900609E-13, -1.41148839263352776110E-10,\n                        -2.21338763073472585583E-8, -2.43340614156596823496E-6,\n                        -1.73028895751305206302E-4, -6.97572385963986435018E-3,\n                        -1.22611180822657148235E-1, -3.53155960776544875667E-1,\n                        1.52530022733894777053E0};\n    const double B[] = {-5.75674448366501715755E-18, 1.79405087314755922667E-17,\n                        -5.68946255844285935196E-17, 1.83809354436663880070E-16,\n                        -6.05704724837331885336E-16, 2.03870316562433424052E-15,\n                        -7.01983709041831346144E-15, 2.47715442448130437068E-14,\n                        -8.97670518232499435011E-14, 3.34841966607842919884E-13,\n                        -1.28917396095102890680E-12, 5.13963967348173025100E-12,\n                        -2.12996783842756842877E-11, 9.21831518760500529508E-11,\n                        -4.19035475934189648750E-10, 2.01504975519703286596E-9,\n                        -1.03457624656780970260E-8, 5.74108412545004946722E-8,\n                        -3.50196060308781257119E-7, 2.40648494783721712015E-6,\n                        -1.93619797416608296024E-5, 1.95215518471351631108E-4,\n                        -2.85781685962277938680E-3, 1.03923736576817238437E-1,\n                        2.72062619048444266945E0};\n    const T MAXNUM = pset1<T>(NumTraits<double>::infinity());\n    const T two = pset1<T>(2.0);\n    T x_le_two = pdiv(internal::pchebevl<T, 11>::run(\n        pmadd(x, x, pset1<T>(-2.0)), A), x);\n    x_le_two = pmadd(\n        generic_i1<T, double>::run(x), plog(pmul(pset1<T>(0.5), x)), x_le_two);\n    x_le_two = pmul(x_le_two, pexp(x));\n    x_le_two = pselect(pcmp_le(x, pset1<T>(0.0)), MAXNUM, x_le_two);\n    T x_gt_two = pmul(\n        internal::pchebevl<T, 25>::run(\n            psub(pdiv(pset1<T>(8.0), x), two), B),\n        prsqrt(x));\n    return pselect(pcmp_le(x, two), x_le_two, x_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_k1e_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_k1e<T>::run(x);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_k1_retval {\n  typedef T type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_k1 {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T&) {\n    EIGEN_STATIC_ASSERT((internal::is_same<T, T>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return ScalarType(0);\n  }\n};\n\ntemplate <typename T>\nstruct generic_k1<T, float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /* k1f.c\n     *\tModified Bessel function, third kind, order one\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float x, y, k1f();\n     *\n     * y = k1f( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Computes the modified Bessel function of the third kind\n     * of order one of the argument.\n     *\n     * The range is partitioned into the two intervals [0,2] and\n     * (2, infinity).  Chebyshev polynomial expansions are employed\n     * in each interval.\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 30       30000       4.6e-7      7.6e-8\n     *\n     * ERROR MESSAGES:\n     *\n     *   message         condition      value returned\n     * k1 domain          x <= 0          MAXNUM\n     *\n     */\n\n    const float A[] = {-2.21338763073472585583E-8f, -2.43340614156596823496E-6f,\n                        -1.73028895751305206302E-4f, -6.97572385963986435018E-3f,\n                        -1.22611180822657148235E-1f, -3.53155960776544875667E-1f,\n                        1.52530022733894777053E0f};\n    const float B[] = {2.01504975519703286596E-9f, -1.03457624656780970260E-8f,\n                       5.74108412545004946722E-8f, -3.50196060308781257119E-7f,\n                       2.40648494783721712015E-6f, -1.93619797416608296024E-5f,\n                       1.95215518471351631108E-4f, -2.85781685962277938680E-3f,\n                       1.03923736576817238437E-1f, 2.72062619048444266945E0f};\n    const T MAXNUM = pset1<T>(NumTraits<float>::infinity());\n    const T two = pset1<T>(2.0);\n    T x_le_two = pdiv(internal::pchebevl<T, 7>::run(\n        pmadd(x, x, pset1<T>(-2.0)), A), x);\n    x_le_two = pmadd(\n        generic_i1<T, float>::run(x), plog(pmul(pset1<T>(0.5), x)), x_le_two);\n    x_le_two = pselect(pcmp_le(x, pset1<T>(0.0)), MAXNUM, x_le_two);\n    T x_gt_two = pmul(\n        pexp(pnegate(x)),\n        pmul(\n            internal::pchebevl<T, 10>::run(\n                psub(pdiv(pset1<T>(8.0), x), two), B),\n            prsqrt(x)));\n    return pselect(pcmp_le(x, two), x_le_two, x_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct generic_k1<T, double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  k1.c\n     *\tModified Bessel function, third kind, order one\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float x, y, k1f();\n     *\n     * y = k1f( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Computes the modified Bessel function of the third kind\n     * of order one of the argument.\n     *\n     * The range is partitioned into the two intervals [0,2] and\n     * (2, infinity).  Chebyshev polynomial expansions are employed\n     * in each interval.\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 30       30000       4.6e-7      7.6e-8\n     *\n     * ERROR MESSAGES:\n     *\n     *   message         condition      value returned\n     * k1 domain          x <= 0          MAXNUM\n     *\n     */\n    const double A[] = {-7.02386347938628759343E-18, -2.42744985051936593393E-15,\n                        -6.66690169419932900609E-13, -1.41148839263352776110E-10,\n                        -2.21338763073472585583E-8, -2.43340614156596823496E-6,\n                        -1.73028895751305206302E-4, -6.97572385963986435018E-3,\n                        -1.22611180822657148235E-1, -3.53155960776544875667E-1,\n                        1.52530022733894777053E0};\n    const double B[] = {-5.75674448366501715755E-18, 1.79405087314755922667E-17,\n                        -5.68946255844285935196E-17, 1.83809354436663880070E-16,\n                        -6.05704724837331885336E-16, 2.03870316562433424052E-15,\n                        -7.01983709041831346144E-15, 2.47715442448130437068E-14,\n                        -8.97670518232499435011E-14, 3.34841966607842919884E-13,\n                        -1.28917396095102890680E-12, 5.13963967348173025100E-12,\n                        -2.12996783842756842877E-11, 9.21831518760500529508E-11,\n                        -4.19035475934189648750E-10, 2.01504975519703286596E-9,\n                        -1.03457624656780970260E-8, 5.74108412545004946722E-8,\n                        -3.50196060308781257119E-7, 2.40648494783721712015E-6,\n                        -1.93619797416608296024E-5, 1.95215518471351631108E-4,\n                        -2.85781685962277938680E-3, 1.03923736576817238437E-1,\n                        2.72062619048444266945E0};\n    const T MAXNUM = pset1<T>(NumTraits<double>::infinity());\n    const T two = pset1<T>(2.0);\n    T x_le_two = pdiv(internal::pchebevl<T, 11>::run(\n        pmadd(x, x, pset1<T>(-2.0)), A), x);\n    x_le_two = pmadd(\n        generic_i1<T, double>::run(x), plog(pmul(pset1<T>(0.5), x)), x_le_two);\n    x_le_two = pselect(pcmp_le(x, pset1<T>(0.0)), MAXNUM, x_le_two);\n    T x_gt_two = pmul(\n        pexp(-x),\n        pmul(\n            internal::pchebevl<T, 25>::run(\n                psub(pdiv(pset1<T>(8.0), x), two), B),\n            prsqrt(x)));\n    return pselect(pcmp_le(x, two), x_le_two, x_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_k1_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_k1<T>::run(x);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_j0_retval {\n  typedef T type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_j0 {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T&) {\n    EIGEN_STATIC_ASSERT((internal::is_same<T, T>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return ScalarType(0);\n  }\n};\n\ntemplate <typename T>\nstruct generic_j0<T, float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /* j0f.c\n     *\tBessel function of order zero\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float x, y, j0f();\n     *\n     * y = j0f( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns Bessel function of order zero of the argument.\n     *\n     * The domain is divided into the intervals [0, 2] and\n     * (2, infinity). In the first interval the following polynomial\n     * approximation is used:\n     *\n     *\n     *        2         2         2\n     * (w - r  ) (w - r  ) (w - r  ) P(w)\n     *       1         2         3\n     *\n     *            2\n     * where w = x  and the three r's are zeros of the function.\n     *\n     * In the second interval, the modulus and phase are approximated\n     * by polynomials of the form Modulus(x) = sqrt(1/x) Q(1/x)\n     * and Phase(x) = x + 1/x R(1/x^2) - pi/4.  The function is\n     *\n     *   j0(x) = Modulus(x) cos( Phase(x) ).\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Absolute error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 2        100000      1.3e-7      3.6e-8\n     *    IEEE      2, 32       100000      1.9e-7      5.4e-8\n     *\n     */\n\n    const float JP[] = {-6.068350350393235E-008f, 6.388945720783375E-006f,\n                        -3.969646342510940E-004f, 1.332913422519003E-002f,\n                        -1.729150680240724E-001f};\n    const float MO[] = {-6.838999669318810E-002f, 1.864949361379502E-001f,\n                        -2.145007480346739E-001f, 1.197549369473540E-001f,\n                        -3.560281861530129E-003f, -4.969382655296620E-002f,\n                        -3.355424622293709E-006f, 7.978845717621440E-001f};\n    const float PH[] = {3.242077816988247E+001f, -3.630592630518434E+001f,\n                        1.756221482109099E+001f, -4.974978466280903E+000f,\n                        1.001973420681837E+000f, -1.939906941791308E-001f,\n                        6.490598792654666E-002f, -1.249992184872738E-001f};\n    const T DR1 =  pset1<T>(5.78318596294678452118f);\n    const T NEG_PIO4F = pset1<T>(-0.7853981633974483096f); /* -pi / 4 */\n    T y = pabs(x);\n    T z = pmul(y, y);\n    T y_le_two = pselect(\n        pcmp_lt(y, pset1<T>(1.0e-3f)),\n        pmadd(z, pset1<T>(-0.25f), pset1<T>(1.0f)),\n        pmul(psub(z, DR1), internal::ppolevl<T, 4>::run(z, JP)));\n    T q = pdiv(pset1<T>(1.0f), y);\n    T w = prsqrt(y);\n    T p = pmul(w, internal::ppolevl<T, 7>::run(q, MO));\n    w = pmul(q, q);\n    T yn = pmadd(q, internal::ppolevl<T, 7>::run(w, PH), NEG_PIO4F);\n    T y_gt_two = pmul(p, pcos(padd(yn, y)));\n    return pselect(pcmp_le(y, pset1<T>(2.0)), y_le_two, y_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct generic_j0<T, double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  j0.c\n     *\tBessel function of order zero\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, j0();\n     *\n     * y = j0( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns Bessel function of order zero of the argument.\n     *\n     * The domain is divided into the intervals [0, 5] and\n     * (5, infinity). In the first interval the following rational\n     * approximation is used:\n     *\n     *\n     *        2         2\n     * (w - r  ) (w - r  ) P (w) / Q (w)\n     *       1         2    3       8\n     *\n     *            2\n     * where w = x  and the two r's are zeros of the function.\n     *\n     * In the second interval, the Hankel asymptotic expansion\n     * is employed with two rational functions of degree 6/6\n     * and 7/7.\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Absolute error:\n     * arithmetic   domain     # trials      peak         rms\n     *    DEC       0, 30       10000       4.4e-17     6.3e-18\n     *    IEEE      0, 30       60000       4.2e-16     1.1e-16\n     *\n     */\n    const double PP[] = {7.96936729297347051624E-4, 8.28352392107440799803E-2,\n                        1.23953371646414299388E0, 5.44725003058768775090E0,\n                        8.74716500199817011941E0, 5.30324038235394892183E0,\n                        9.99999999999999997821E-1};\n    const double PQ[] = {9.24408810558863637013E-4, 8.56288474354474431428E-2,\n                         1.25352743901058953537E0, 5.47097740330417105182E0,\n                         8.76190883237069594232E0, 5.30605288235394617618E0,\n                         1.00000000000000000218E0};\n    const double QP[] = {-1.13663838898469149931E-2, -1.28252718670509318512E0,\n                         -1.95539544257735972385E1, -9.32060152123768231369E1,\n                         -1.77681167980488050595E2, -1.47077505154951170175E2,\n                         -5.14105326766599330220E1, -6.05014350600728481186E0};\n    const double QQ[] = {1.00000000000000000000E0, 6.43178256118178023184E1,\n                         8.56430025976980587198E2, 3.88240183605401609683E3,\n                         7.24046774195652478189E3, 5.93072701187316984827E3,\n                         2.06209331660327847417E3, 2.42005740240291393179E2};\n    const double RP[] = {-4.79443220978201773821E9, 1.95617491946556577543E12,\n                         -2.49248344360967716204E14, 9.70862251047306323952E15};\n    const double RQ[] = {1.00000000000000000000E0, 4.99563147152651017219E2,\n                         1.73785401676374683123E5, 4.84409658339962045305E7,\n                         1.11855537045356834862E10, 2.11277520115489217587E12,\n                         3.10518229857422583814E14, 3.18121955943204943306E16,\n                         1.71086294081043136091E18};\n    const T DR1 = pset1<T>(5.78318596294678452118E0);\n    const T DR2 = pset1<T>(3.04712623436620863991E1);\n    const T SQ2OPI = pset1<T>(7.9788456080286535587989E-1); /* sqrt(2 / pi) */\n    const T NEG_PIO4 = pset1<T>(-0.7853981633974483096); /* pi / 4 */\n\n    T y = pabs(x);\n    T z = pmul(y, y);\n    T y_le_five = pselect(\n        pcmp_lt(y, pset1<T>(1.0e-5)),\n        pmadd(z, pset1<T>(-0.25), pset1<T>(1.0)),\n        pmul(pmul(psub(z, DR1), psub(z, DR2)),\n             pdiv(internal::ppolevl<T, 3>::run(z, RP),\n                  internal::ppolevl<T, 8>::run(z, RQ))));\n    T s = pdiv(pset1<T>(25.0), z);\n    T p = pdiv(\n        internal::ppolevl<T, 6>::run(s, PP),\n        internal::ppolevl<T, 6>::run(s, PQ));\n    T q = pdiv(\n        internal::ppolevl<T, 7>::run(s, QP),\n        internal::ppolevl<T, 7>::run(s, QQ));\n    T yn = padd(y, NEG_PIO4);\n    T w = pdiv(pset1<T>(-5.0), y);\n    p = pmadd(p, pcos(yn), pmul(w, pmul(q, psin(yn))));\n    T y_gt_five = pmul(p, pmul(SQ2OPI, prsqrt(y)));\n    return pselect(pcmp_le(y, pset1<T>(5.0)), y_le_five, y_gt_five);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_j0_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_j0<T>::run(x);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_y0_retval {\n  typedef T type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_y0 {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T&) {\n    EIGEN_STATIC_ASSERT((internal::is_same<T, T>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return ScalarType(0);\n  }\n};\n\ntemplate <typename T>\nstruct generic_y0<T, float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /* j0f.c\n     * \tBessel function of the second kind, order zero\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float x, y, y0f();\n     *\n     * y = y0f( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns Bessel function of the second kind, of order\n     * zero, of the argument.\n     *\n     * The domain is divided into the intervals [0, 2] and\n     * (2, infinity). In the first interval a rational approximation\n     * R(x) is employed to compute\n     *\n     *                  2         2         2\n     * y0(x)  =  (w - r  ) (w - r  ) (w - r  ) R(x)  +  2/pi ln(x) j0(x).\n     *                 1         2         3\n     *\n     * Thus a call to j0() is required.  The three zeros are removed\n     * from R(x) to improve its numerical stability.\n     *\n     * In the second interval, the modulus and phase are approximated\n     * by polynomials of the form Modulus(x) = sqrt(1/x) Q(1/x)\n     * and Phase(x) = x + 1/x S(1/x^2) - pi/4.  Then the function is\n     *\n     *   y0(x) = Modulus(x) sin( Phase(x) ).\n     *\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *  Absolute error, when y0(x) < 1; else relative error:\n     *\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0,  2       100000      2.4e-7      3.4e-8\n     *    IEEE      2, 32       100000      1.8e-7      5.3e-8\n     *\n     */\n\n    const float YP[] = {9.454583683980369E-008f, -9.413212653797057E-006f,\n                        5.344486707214273E-004f, -1.584289289821316E-002f,\n                        1.707584643733568E-001f};\n    const float MO[] = {-6.838999669318810E-002f, 1.864949361379502E-001f,\n                        -2.145007480346739E-001f, 1.197549369473540E-001f,\n                        -3.560281861530129E-003f, -4.969382655296620E-002f,\n                        -3.355424622293709E-006f, 7.978845717621440E-001f};\n    const float PH[] = {3.242077816988247E+001f, -3.630592630518434E+001f,\n                        1.756221482109099E+001f, -4.974978466280903E+000f,\n                        1.001973420681837E+000f, -1.939906941791308E-001f,\n                        6.490598792654666E-002f, -1.249992184872738E-001f};\n    const T YZ1 = pset1<T>(0.43221455686510834878f);\n    const T TWOOPI =  pset1<T>(0.636619772367581343075535f); /* 2 / pi */\n    const T NEG_PIO4F = pset1<T>(-0.7853981633974483096f); /* -pi / 4 */\n    const T NEG_MAXNUM = pset1<T>(-NumTraits<float>::infinity());\n    T z = pmul(x, x);\n    T x_le_two = pmul(TWOOPI, pmul(plog(x), generic_j0<T, float>::run(x)));\n    x_le_two = pmadd(\n        psub(z, YZ1), internal::ppolevl<T, 4>::run(z, YP), x_le_two);\n    x_le_two = pselect(pcmp_le(x, pset1<T>(0.0)), NEG_MAXNUM, x_le_two);\n    T q = pdiv(pset1<T>(1.0), x);\n    T w = prsqrt(x);\n    T p = pmul(w, internal::ppolevl<T, 7>::run(q, MO));\n    T u = pmul(q, q);\n    T xn = pmadd(q, internal::ppolevl<T, 7>::run(u, PH), NEG_PIO4F);\n    T x_gt_two = pmul(p, psin(padd(xn, x)));\n    return pselect(pcmp_le(x, pset1<T>(2.0)), x_le_two, x_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct generic_y0<T, double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  j0.c\n     *\tBessel function of the second kind, order zero\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, y0();\n     *\n     * y = y0( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns Bessel function of the second kind, of order\n     * zero, of the argument.\n     *\n     * The domain is divided into the intervals [0, 5] and\n     * (5, infinity). In the first interval a rational approximation\n     * R(x) is employed to compute\n     *   y0(x)  = R(x)  +   2 * log(x) * j0(x) / PI.\n     * Thus a call to j0() is required.\n     *\n     * In the second interval, the Hankel asymptotic expansion\n     * is employed with two rational functions of degree 6/6\n     * and 7/7.\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *  Absolute error, when y0(x) < 1; else relative error:\n     *\n     * arithmetic   domain     # trials      peak         rms\n     *    DEC       0, 30        9400       7.0e-17     7.9e-18\n     *    IEEE      0, 30       30000       1.3e-15     1.6e-16\n     *\n     */\n    const double PP[] = {7.96936729297347051624E-4, 8.28352392107440799803E-2,\n                        1.23953371646414299388E0, 5.44725003058768775090E0,\n                        8.74716500199817011941E0, 5.30324038235394892183E0,\n                        9.99999999999999997821E-1};\n    const double PQ[] = {9.24408810558863637013E-4, 8.56288474354474431428E-2,\n                         1.25352743901058953537E0, 5.47097740330417105182E0,\n                         8.76190883237069594232E0, 5.30605288235394617618E0,\n                         1.00000000000000000218E0};\n    const double QP[] = {-1.13663838898469149931E-2, -1.28252718670509318512E0,\n                         -1.95539544257735972385E1, -9.32060152123768231369E1,\n                         -1.77681167980488050595E2, -1.47077505154951170175E2,\n                         -5.14105326766599330220E1, -6.05014350600728481186E0};\n    const double QQ[] = {1.00000000000000000000E0, 6.43178256118178023184E1,\n                         8.56430025976980587198E2, 3.88240183605401609683E3,\n                         7.24046774195652478189E3, 5.93072701187316984827E3,\n                         2.06209331660327847417E3, 2.42005740240291393179E2};\n    const double YP[] = {1.55924367855235737965E4, -1.46639295903971606143E7,\n                         5.43526477051876500413E9, -9.82136065717911466409E11,\n                         8.75906394395366999549E13, -3.46628303384729719441E15,\n                         4.42733268572569800351E16, -1.84950800436986690637E16};\n    const double YQ[] = {1.00000000000000000000E0,  1.04128353664259848412E3,\n                         6.26107330137134956842E5, 2.68919633393814121987E8,\n                         8.64002487103935000337E10, 2.02979612750105546709E13,\n                         3.17157752842975028269E15, 2.50596256172653059228E17};\n    const T SQ2OPI = pset1<T>(7.9788456080286535587989E-1); /* sqrt(2 / pi) */\n    const T TWOOPI =  pset1<T>(0.636619772367581343075535); /* 2 / pi */\n    const T NEG_PIO4 = pset1<T>(-0.7853981633974483096); /* -pi / 4 */\n    const T NEG_MAXNUM = pset1<T>(-NumTraits<double>::infinity());\n\n    T z = pmul(x, x);\n    T x_le_five = pdiv(internal::ppolevl<T, 7>::run(z, YP),\n                       internal::ppolevl<T, 7>::run(z, YQ));\n    x_le_five = pmadd(\n        pmul(TWOOPI, plog(x)), generic_j0<T, double>::run(x), x_le_five);\n    x_le_five = pselect(pcmp_le(x, pset1<T>(0.0)), NEG_MAXNUM, x_le_five);\n    T s = pdiv(pset1<T>(25.0), z);\n    T p = pdiv(\n        internal::ppolevl<T, 6>::run(s, PP),\n        internal::ppolevl<T, 6>::run(s, PQ));\n    T q = pdiv(\n        internal::ppolevl<T, 7>::run(s, QP),\n        internal::ppolevl<T, 7>::run(s, QQ));\n    T xn = padd(x, NEG_PIO4);\n    T w = pdiv(pset1<T>(5.0), x);\n    p = pmadd(p, psin(xn), pmul(w, pmul(q, pcos(xn))));\n    T x_gt_five = pmul(p, pmul(SQ2OPI, prsqrt(x)));\n    return pselect(pcmp_le(x, pset1<T>(5.0)), x_le_five, x_gt_five);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_y0_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_y0<T>::run(x);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_j1_retval {\n  typedef T type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_j1 {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T&) {\n    EIGEN_STATIC_ASSERT((internal::is_same<T, T>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return ScalarType(0);\n  }\n};\n\ntemplate <typename T>\nstruct generic_j1<T, float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /* j1f.c\n     *\tBessel function of order one\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float x, y, j1f();\n     *\n     * y = j1f( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns Bessel function of order one of the argument.\n     *\n     * The domain is divided into the intervals [0, 2] and\n     * (2, infinity). In the first interval a polynomial approximation\n     *        2\n     * (w - r  ) x P(w)\n     *       1\n     *                     2\n     * is used, where w = x  and r is the first zero of the function.\n     *\n     * In the second interval, the modulus and phase are approximated\n     * by polynomials of the form Modulus(x) = sqrt(1/x) Q(1/x)\n     * and Phase(x) = x + 1/x R(1/x^2) - 3pi/4.  The function is\n     *\n     *   j0(x) = Modulus(x) cos( Phase(x) ).\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Absolute error:\n     * arithmetic   domain      # trials      peak       rms\n     *    IEEE      0,  2       100000       1.2e-7     2.5e-8\n     *    IEEE      2, 32       100000       2.0e-7     5.3e-8\n     *\n     *\n     */\n\n    const float JP[] = {-4.878788132172128E-009f, 6.009061827883699E-007f,\n                        -4.541343896997497E-005f, 1.937383947804541E-003f,\n                        -3.405537384615824E-002f};\n    const float MO1[] = {6.913942741265801E-002f, -2.284801500053359E-001f,\n                        3.138238455499697E-001f, -2.102302420403875E-001f,\n                        5.435364690523026E-003f, 1.493389585089498E-001f,\n                        4.976029650847191E-006f, 7.978845453073848E-001f};\n    const float PH1[] = {-4.497014141919556E+001f, 5.073465654089319E+001f,\n                        -2.485774108720340E+001f, 7.222973196770240E+000f,\n                        -1.544842782180211E+000f, 3.503787691653334E-001f,\n                        -1.637986776941202E-001f, 3.749989509080821E-001f};\n    const T Z1 = pset1<T>(1.46819706421238932572E1f);\n    const T NEG_THPIO4F = pset1<T>(-2.35619449019234492885f);    /* -3*pi/4 */\n\n    T y = pabs(x);\n    T z = pmul(y, y);\n    T y_le_two = pmul(\n        psub(z, Z1),\n        pmul(x, internal::ppolevl<T, 4>::run(z, JP)));\n    T q = pdiv(pset1<T>(1.0f), y);\n    T w = prsqrt(y);\n    T p = pmul(w, internal::ppolevl<T, 7>::run(q, MO1));\n    w = pmul(q, q);\n    T yn = pmadd(q, internal::ppolevl<T, 7>::run(w, PH1), NEG_THPIO4F);\n    T y_gt_two = pmul(p, pcos(padd(yn, y)));\n    // j1 is an odd function. This implementation differs from cephes to\n    // take this fact in to account. Cephes returns -j1(x) for y > 2 range.\n    y_gt_two = pselect(\n        pcmp_lt(x, pset1<T>(0.0f)), pnegate(y_gt_two), y_gt_two);\n    return pselect(pcmp_le(y, pset1<T>(2.0f)), y_le_two, y_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct generic_j1<T, double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  j1.c\n     *\tBessel function of order one\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, j1();\n     *\n     * y = j1( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns Bessel function of order one of the argument.\n     *\n     * The domain is divided into the intervals [0, 8] and\n     * (8, infinity). In the first interval a 24 term Chebyshev\n     * expansion is used. In the second, the asymptotic\n     * trigonometric representation is employed using two\n     * rational functions of degree 5/5.\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Absolute error:\n     * arithmetic   domain      # trials      peak         rms\n     *    DEC       0, 30       10000       4.0e-17     1.1e-17\n     *    IEEE      0, 30       30000       2.6e-16     1.1e-16\n     *\n     */\n    const double PP[] = {7.62125616208173112003E-4, 7.31397056940917570436E-2,\n                         1.12719608129684925192E0, 5.11207951146807644818E0,\n                         8.42404590141772420927E0, 5.21451598682361504063E0,\n                         1.00000000000000000254E0};\n    const double PQ[] = {5.71323128072548699714E-4, 6.88455908754495404082E-2,\n                         1.10514232634061696926E0, 5.07386386128601488557E0,\n                         8.39985554327604159757E0, 5.20982848682361821619E0,\n                         9.99999999999999997461E-1};\n    const double QP[] = {5.10862594750176621635E-2, 4.98213872951233449420E0,\n                         7.58238284132545283818E1, 3.66779609360150777800E2,\n                         7.10856304998926107277E2, 5.97489612400613639965E2,\n                         2.11688757100572135698E2, 2.52070205858023719784E1};\n    const double QQ[] = {1.00000000000000000000E0, 7.42373277035675149943E1,\n                         1.05644886038262816351E3, 4.98641058337653607651E3,\n                         9.56231892404756170795E3, 7.99704160447350683650E3,\n                         2.82619278517639096600E3, 3.36093607810698293419E2};\n    const double RP[] = {-8.99971225705559398224E8, 4.52228297998194034323E11,\n                         -7.27494245221818276015E13, 3.68295732863852883286E15};\n    const double RQ[] = {1.00000000000000000000E0, 6.20836478118054335476E2,\n                         2.56987256757748830383E5, 8.35146791431949253037E7,\n                         2.21511595479792499675E10, 4.74914122079991414898E12,\n                         7.84369607876235854894E14, 8.95222336184627338078E16,\n                         5.32278620332680085395E18};\n    const T Z1 = pset1<T>(1.46819706421238932572E1);\n    const T Z2 = pset1<T>(4.92184563216946036703E1);\n    const T NEG_THPIO4 = pset1<T>(-2.35619449019234492885);    /* -3*pi/4 */\n    const T SQ2OPI = pset1<T>(7.9788456080286535587989E-1); /* sqrt(2 / pi) */\n    T y = pabs(x);\n    T z = pmul(y, y);\n    T y_le_five = pdiv(internal::ppolevl<T, 3>::run(z, RP),\n                       internal::ppolevl<T, 8>::run(z, RQ));\n    y_le_five = pmul(pmul(pmul(y_le_five, x), psub(z, Z1)), psub(z, Z2));\n    T s = pdiv(pset1<T>(25.0), z);\n    T p = pdiv(\n        internal::ppolevl<T, 6>::run(s, PP),\n        internal::ppolevl<T, 6>::run(s, PQ));\n    T q = pdiv(\n        internal::ppolevl<T, 7>::run(s, QP),\n        internal::ppolevl<T, 7>::run(s, QQ));\n    T yn = padd(y, NEG_THPIO4);\n    T w = pdiv(pset1<T>(-5.0), y);\n    p = pmadd(p, pcos(yn), pmul(w, pmul(q, psin(yn))));\n    T y_gt_five = pmul(p, pmul(SQ2OPI, prsqrt(y)));\n    // j1 is an odd function. This implementation differs from cephes to\n    // take this fact in to account. Cephes returns -j1(x) for y > 5 range.\n    y_gt_five = pselect(\n        pcmp_lt(x, pset1<T>(0.0)), pnegate(y_gt_five), y_gt_five);\n    return pselect(pcmp_le(y, pset1<T>(5.0)), y_le_five, y_gt_five);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_j1_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_j1<T>::run(x);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_y1_retval {\n  typedef T type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_y1 {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T&) {\n    EIGEN_STATIC_ASSERT((internal::is_same<T, T>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return ScalarType(0);\n  }\n};\n\ntemplate <typename T>\nstruct generic_y1<T, float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /* j1f.c\n     *\tBessel function of second kind of order one\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, y1();\n     *\n     * y = y1( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns Bessel function of the second kind of order one\n     * of the argument.\n     *\n     * The domain is divided into the intervals [0, 2] and\n     * (2, infinity). In the first interval a rational approximation\n     * R(x) is employed to compute\n     *\n     *                  2\n     * y0(x)  =  (w - r  ) x R(x^2)  +  2/pi (ln(x) j1(x) - 1/x) .\n     *                 1\n     *\n     * Thus a call to j1() is required.\n     *\n     * In the second interval, the modulus and phase are approximated\n     * by polynomials of the form Modulus(x) = sqrt(1/x) Q(1/x)\n     * and Phase(x) = x + 1/x S(1/x^2) - 3pi/4.  Then the function is\n     *\n     *   y0(x) = Modulus(x) sin( Phase(x) ).\n     *\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Absolute error:\n     * arithmetic   domain      # trials      peak         rms\n     *    IEEE      0,  2       100000       2.2e-7     4.6e-8\n     *    IEEE      2, 32       100000       1.9e-7     5.3e-8\n     *\n     * (error criterion relative when |y1| > 1).\n     *\n     */\n\n    const float YP[] = {8.061978323326852E-009f, -9.496460629917016E-007f,\n                        6.719543806674249E-005f, -2.641785726447862E-003f,\n                        4.202369946500099E-002f};\n    const float MO1[] = {6.913942741265801E-002f, -2.284801500053359E-001f,\n                        3.138238455499697E-001f, -2.102302420403875E-001f,\n                        5.435364690523026E-003f, 1.493389585089498E-001f,\n                        4.976029650847191E-006f, 7.978845453073848E-001f};\n    const float PH1[] = {-4.497014141919556E+001f, 5.073465654089319E+001f,\n                        -2.485774108720340E+001f, 7.222973196770240E+000f,\n                        -1.544842782180211E+000f, 3.503787691653334E-001f,\n                        -1.637986776941202E-001f, 3.749989509080821E-001f};\n    const T YO1 = pset1<T>(4.66539330185668857532f);\n    const T NEG_THPIO4F = pset1<T>(-2.35619449019234492885f);    /* -3*pi/4 */\n    const T TWOOPI = pset1<T>(0.636619772367581343075535f); /* 2/pi */\n    const T NEG_MAXNUM = pset1<T>(-NumTraits<float>::infinity());\n\n    T z = pmul(x, x);\n    T x_le_two = pmul(psub(z, YO1), internal::ppolevl<T, 4>::run(z, YP));\n    x_le_two = pmadd(\n       x_le_two, x,\n       pmul(TWOOPI, pmadd(\n           generic_j1<T, float>::run(x), plog(x),\n           pdiv(pset1<T>(-1.0f), x))));\n    x_le_two = pselect(pcmp_lt(x, pset1<T>(0.0f)), NEG_MAXNUM, x_le_two);\n\n    T q = pdiv(pset1<T>(1.0), x);\n    T w = prsqrt(x);\n    T p = pmul(w, internal::ppolevl<T, 7>::run(q, MO1));\n    w = pmul(q, q);\n    T xn = pmadd(q, internal::ppolevl<T, 7>::run(w, PH1), NEG_THPIO4F);\n    T x_gt_two = pmul(p, psin(padd(xn, x)));\n    return pselect(pcmp_le(x, pset1<T>(2.0)), x_le_two, x_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct generic_y1<T, double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  j1.c\n     *\tBessel function of second kind of order one\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, y1();\n     *\n     * y = y1( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns Bessel function of the second kind of order one\n     * of the argument.\n     *\n     * The domain is divided into the intervals [0, 8] and\n     * (8, infinity). In the first interval a 25 term Chebyshev\n     * expansion is used, and a call to j1() is required.\n     * In the second, the asymptotic trigonometric representation\n     * is employed using two rational functions of degree 5/5.\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Absolute error:\n     * arithmetic   domain      # trials      peak         rms\n     *    DEC       0, 30       10000       8.6e-17     1.3e-17\n     *    IEEE      0, 30       30000       1.0e-15     1.3e-16\n     *\n     * (error criterion relative when |y1| > 1).\n     *\n     */\n    const double PP[] = {7.62125616208173112003E-4, 7.31397056940917570436E-2,\n                         1.12719608129684925192E0, 5.11207951146807644818E0,\n                         8.42404590141772420927E0, 5.21451598682361504063E0,\n                         1.00000000000000000254E0};\n    const double PQ[] = {5.71323128072548699714E-4, 6.88455908754495404082E-2,\n                         1.10514232634061696926E0, 5.07386386128601488557E0,\n                         8.39985554327604159757E0, 5.20982848682361821619E0,\n                         9.99999999999999997461E-1};\n    const double QP[] = {5.10862594750176621635E-2, 4.98213872951233449420E0,\n                         7.58238284132545283818E1, 3.66779609360150777800E2,\n                         7.10856304998926107277E2, 5.97489612400613639965E2,\n                         2.11688757100572135698E2, 2.52070205858023719784E1};\n    const double QQ[] = {1.00000000000000000000E0, 7.42373277035675149943E1,\n                         1.05644886038262816351E3, 4.98641058337653607651E3,\n                         9.56231892404756170795E3, 7.99704160447350683650E3,\n                         2.82619278517639096600E3, 3.36093607810698293419E2};\n    const double YP[] = {1.26320474790178026440E9, -6.47355876379160291031E11,\n                         1.14509511541823727583E14, -8.12770255501325109621E15,\n                         2.02439475713594898196E17, -7.78877196265950026825E17};\n    const double YQ[] = {1.00000000000000000000E0, 5.94301592346128195359E2,\n                         2.35564092943068577943E5, 7.34811944459721705660E7,\n                         1.87601316108706159478E10, 3.88231277496238566008E12,\n                         6.20557727146953693363E14, 6.87141087355300489866E16,\n                         3.97270608116560655612E18};\n    const T SQ2OPI = pset1<T>(.79788456080286535588);\n    const T NEG_THPIO4 = pset1<T>(-2.35619449019234492885);    /* -3*pi/4 */\n    const T TWOOPI = pset1<T>(0.636619772367581343075535); /* 2/pi */\n    const T NEG_MAXNUM = pset1<T>(-NumTraits<double>::infinity());\n\n    T z = pmul(x, x);\n    T x_le_five = pdiv(internal::ppolevl<T, 5>::run(z, YP),\n                   internal::ppolevl<T, 8>::run(z, YQ));\n    x_le_five = pmadd(\n        x_le_five, x, pmul(\n            TWOOPI, pmadd(generic_j1<T, double>::run(x), plog(x),\n                          pdiv(pset1<T>(-1.0), x))));\n\n    x_le_five = pselect(pcmp_le(x, pset1<T>(0.0)), NEG_MAXNUM, x_le_five);\n    T s = pdiv(pset1<T>(25.0), z);\n    T p = pdiv(\n        internal::ppolevl<T, 6>::run(s, PP),\n        internal::ppolevl<T, 6>::run(s, PQ));\n    T q = pdiv(\n        internal::ppolevl<T, 7>::run(s, QP),\n        internal::ppolevl<T, 7>::run(s, QQ));\n    T xn = padd(x, NEG_THPIO4);\n    T w = pdiv(pset1<T>(5.0), x);\n    p = pmadd(p, psin(xn), pmul(w, pmul(q, pcos(xn))));\n    T x_gt_five = pmul(p, pmul(SQ2OPI, prsqrt(x)));\n    return pselect(pcmp_le(x, pset1<T>(5.0)), x_le_five, x_gt_five);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_y1_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_y1<T>::run(x);\n  }\n};\n\n}  // end namespace internal\n\nnamespace numext {\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_i0, Scalar)\n    bessel_i0(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_i0, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_i0e, Scalar)\n    bessel_i0e(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_i0e, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_i1, Scalar)\n    bessel_i1(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_i1, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_i1e, Scalar)\n    bessel_i1e(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_i1e, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_k0, Scalar)\n    bessel_k0(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_k0, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_k0e, Scalar)\n    bessel_k0e(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_k0e, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_k1, Scalar)\n    bessel_k1(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_k1, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_k1e, Scalar)\n    bessel_k1e(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_k1e, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_j0, Scalar)\n    bessel_j0(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_j0, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_y0, Scalar)\n    bessel_y0(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_y0, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_j1, Scalar)\n    bessel_j1(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_j1, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_y1, Scalar)\n    bessel_y1(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_y1, Scalar)::run(x);\n}\n\n}  // end namespace numext\n\n}  // end namespace Eigen\n\n#endif  // EIGEN_BESSEL_FUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SpecialFunctions/BesselFunctionsPacketMath.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BESSELFUNCTIONS_PACKETMATH_H\n#define EIGEN_BESSELFUNCTIONS_PACKETMATH_H\n\nnamespace Eigen {\n\nnamespace internal {\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order zero i0(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_i0(const Packet& x) {\n  return numext::bessel_i0(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order zero i0e(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_i0e(const Packet& x) {\n  return numext::bessel_i0e(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order one i1(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_i1(const Packet& x) {\n  return numext::bessel_i1(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order one i1e(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_i1e(const Packet& x) {\n  return numext::bessel_i1e(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order zero j0(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_j0(const Packet& x) {\n  return numext::bessel_j0(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order zero j1(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_j1(const Packet& x) {\n  return numext::bessel_j1(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order one y0(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_y0(const Packet& x) {\n  return numext::bessel_y0(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order one y1(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_y1(const Packet& x) {\n  return numext::bessel_y1(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order zero k0(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_k0(const Packet& x) {\n  return numext::bessel_k0(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order zero k0e(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_k0e(const Packet& x) {\n  return numext::bessel_k0e(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order one k1e(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_k1(const Packet& x) {\n  return numext::bessel_k1(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order one k1e(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_k1e(const Packet& x) {\n  return numext::bessel_k1e(x);\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_BESSELFUNCTIONS_PACKETMATH_H\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SpecialFunctions/HipVectorCompatibility.h",
    "content": "#ifndef HIP_VECTOR_COMPATIBILITY_H\n#define HIP_VECTOR_COMPATIBILITY_H\n\nnamespace hip_impl {\n  template <typename, typename, unsigned int> struct Scalar_accessor;\n}   // end namespace hip_impl\n\nnamespace Eigen {\nnamespace internal {\n\n#define HIP_SCALAR_ACCESSOR_BUILDER(NAME) \\\ntemplate <typename T, typename U, unsigned int n> \\\nstruct NAME <hip_impl::Scalar_accessor<T, U, n>> : NAME <T> {};\n\n#define HIP_SCALAR_ACCESSOR_BUILDER_RETVAL(NAME) \\\ntemplate <typename T, typename U, unsigned int n> \\\nstruct NAME##_impl <hip_impl::Scalar_accessor<T, U, n>> : NAME##_impl <T> {}; \\\ntemplate <typename T, typename U, unsigned int n> \\\nstruct NAME##_retval <hip_impl::Scalar_accessor<T, U, n>> : NAME##_retval <T> {};\n\n#define HIP_SCALAR_ACCESSOR_BUILDER_IGAMMA(NAME) \\\ntemplate <typename T, typename U, unsigned int n, IgammaComputationMode mode> \\\nstruct NAME <hip_impl::Scalar_accessor<T, U, n>, mode> : NAME <T, mode> {};\n\n#if EIGEN_HAS_C99_MATH\nHIP_SCALAR_ACCESSOR_BUILDER(betainc_helper)\nHIP_SCALAR_ACCESSOR_BUILDER(incbeta_cfe)\n\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(erf)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(erfc)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(igammac)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(lgamma)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(ndtri)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(polygamma)\n\nHIP_SCALAR_ACCESSOR_BUILDER_IGAMMA(igamma_generic_impl)\n#endif\n\nHIP_SCALAR_ACCESSOR_BUILDER(digamma_impl_maybe_poly)\nHIP_SCALAR_ACCESSOR_BUILDER(zeta_impl_series)\n\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_i0)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_i0e)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_i1)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_i1e)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_j0)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_j1)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_k0)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_k0e)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_k1)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_k1e)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_y0)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_y1)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(betainc)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(digamma)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(gamma_sample_der_alpha)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(igamma_der_a)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(igamma)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(zeta)\n\nHIP_SCALAR_ACCESSOR_BUILDER_IGAMMA(igamma_series_impl)\nHIP_SCALAR_ACCESSOR_BUILDER_IGAMMA(igammac_cf_impl)\n\n}  // end namespace internal\n}  // end namespace Eigen\n\n#endif  // HIP_VECTOR_COMPATIBILITY_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsArrayAPI.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#ifndef EIGEN_SPECIALFUNCTIONS_ARRAYAPI_H\n#define EIGEN_SPECIALFUNCTIONS_ARRAYAPI_H\n\nnamespace Eigen {\n\n/** \\cpp11 \\returns an expression of the coefficient-wise igamma(\\a a, \\a x) to the given arrays.\n  *\n  * This function computes the coefficient-wise incomplete gamma function.\n  *\n  * \\note This function supports only float and double scalar types in c++11 mode. To support other scalar types,\n  * or float/double in non c++11 mode, the user has to provide implementations of igammac(T,T) for any scalar\n  * type T to be supported.\n  *\n  * \\sa Eigen::igammac(), Eigen::lgamma()\n  */\ntemplate<typename Derived,typename ExponentDerived>\nEIGEN_STRONG_INLINE const Eigen::CwiseBinaryOp<Eigen::internal::scalar_igamma_op<typename Derived::Scalar>, const Derived, const ExponentDerived>\nigamma(const Eigen::ArrayBase<Derived>& a, const Eigen::ArrayBase<ExponentDerived>& x)\n{\n  return Eigen::CwiseBinaryOp<Eigen::internal::scalar_igamma_op<typename Derived::Scalar>, const Derived, const ExponentDerived>(\n    a.derived(),\n    x.derived()\n  );\n}\n\n/** \\cpp11 \\returns an expression of the coefficient-wise igamma_der_a(\\a a, \\a x) to the given arrays.\n  *\n  * This function computes the coefficient-wise derivative of the incomplete\n  * gamma function with respect to the parameter a.\n  *\n  * \\note This function supports only float and double scalar types in c++11\n  * mode. To support other scalar types,\n  * or float/double in non c++11 mode, the user has to provide implementations\n  * of igamma_der_a(T,T) for any scalar\n  * type T to be supported.\n  *\n  * \\sa Eigen::igamma(), Eigen::lgamma()\n  */\ntemplate <typename Derived, typename ExponentDerived>\nEIGEN_STRONG_INLINE const Eigen::CwiseBinaryOp<Eigen::internal::scalar_igamma_der_a_op<typename Derived::Scalar>, const Derived, const ExponentDerived>\nigamma_der_a(const Eigen::ArrayBase<Derived>& a, const Eigen::ArrayBase<ExponentDerived>& x) {\n  return Eigen::CwiseBinaryOp<Eigen::internal::scalar_igamma_der_a_op<typename Derived::Scalar>, const Derived, const ExponentDerived>(\n    a.derived(),\n    x.derived());\n}\n\n/** \\cpp11 \\returns an expression of the coefficient-wise gamma_sample_der_alpha(\\a alpha, \\a sample) to the given arrays.\n  *\n  * This function computes the coefficient-wise derivative of the sample\n  * of a Gamma(alpha, 1) random variable with respect to the parameter alpha.\n  *\n  * \\note This function supports only float and double scalar types in c++11\n  * mode. To support other scalar types,\n  * or float/double in non c++11 mode, the user has to provide implementations\n  * of gamma_sample_der_alpha(T,T) for any scalar\n  * type T to be supported.\n  *\n  * \\sa Eigen::igamma(), Eigen::lgamma()\n  */\ntemplate <typename AlphaDerived, typename SampleDerived>\nEIGEN_STRONG_INLINE const Eigen::CwiseBinaryOp<Eigen::internal::scalar_gamma_sample_der_alpha_op<typename AlphaDerived::Scalar>, const AlphaDerived, const SampleDerived>\ngamma_sample_der_alpha(const Eigen::ArrayBase<AlphaDerived>& alpha, const Eigen::ArrayBase<SampleDerived>& sample) {\n  return Eigen::CwiseBinaryOp<Eigen::internal::scalar_gamma_sample_der_alpha_op<typename AlphaDerived::Scalar>, const AlphaDerived, const SampleDerived>(\n      alpha.derived(),\n      sample.derived());\n}\n\n/** \\cpp11 \\returns an expression of the coefficient-wise igammac(\\a a, \\a x) to the given arrays.\n  *\n  * This function computes the coefficient-wise complementary incomplete gamma function.\n  *\n  * \\note This function supports only float and double scalar types in c++11 mode. To support other scalar types,\n  * or float/double in non c++11 mode, the user has to provide implementations of igammac(T,T) for any scalar\n  * type T to be supported.\n  *\n  * \\sa Eigen::igamma(), Eigen::lgamma()\n  */\ntemplate<typename Derived,typename ExponentDerived>\nEIGEN_STRONG_INLINE const Eigen::CwiseBinaryOp<Eigen::internal::scalar_igammac_op<typename Derived::Scalar>, const Derived, const ExponentDerived>\nigammac(const Eigen::ArrayBase<Derived>& a, const Eigen::ArrayBase<ExponentDerived>& x)\n{\n  return Eigen::CwiseBinaryOp<Eigen::internal::scalar_igammac_op<typename Derived::Scalar>, const Derived, const ExponentDerived>(\n    a.derived(),\n    x.derived()\n  );\n}\n\n/** \\cpp11 \\returns an expression of the coefficient-wise polygamma(\\a n, \\a x) to the given arrays.\n  *\n  * It returns the \\a n -th derivative of the digamma(psi) evaluated at \\c x.\n  *\n  * \\note This function supports only float and double scalar types in c++11 mode. To support other scalar types,\n  * or float/double in non c++11 mode, the user has to provide implementations of polygamma(T,T) for any scalar\n  * type T to be supported.\n  *\n  * \\sa Eigen::digamma()\n  */\n// * \\warning Be careful with the order of the parameters: x.polygamma(n) is equivalent to polygamma(n,x)\n// * \\sa ArrayBase::polygamma()\ntemplate<typename DerivedN,typename DerivedX>\nEIGEN_STRONG_INLINE const Eigen::CwiseBinaryOp<Eigen::internal::scalar_polygamma_op<typename DerivedX::Scalar>, const DerivedN, const DerivedX>\npolygamma(const Eigen::ArrayBase<DerivedN>& n, const Eigen::ArrayBase<DerivedX>& x)\n{\n  return Eigen::CwiseBinaryOp<Eigen::internal::scalar_polygamma_op<typename DerivedX::Scalar>, const DerivedN, const DerivedX>(\n    n.derived(),\n    x.derived()\n  );\n}\n\n/** \\cpp11 \\returns an expression of the coefficient-wise betainc(\\a x, \\a a, \\a b) to the given arrays.\n  *\n  * This function computes the regularized incomplete beta function (integral).\n  *\n  * \\note This function supports only float and double scalar types in c++11 mode. To support other scalar types,\n  * or float/double in non c++11 mode, the user has to provide implementations of betainc(T,T,T) for any scalar\n  * type T to be supported.\n  *\n  * \\sa Eigen::betainc(), Eigen::lgamma()\n  */\ntemplate<typename ArgADerived, typename ArgBDerived, typename ArgXDerived>\nEIGEN_STRONG_INLINE const Eigen::CwiseTernaryOp<Eigen::internal::scalar_betainc_op<typename ArgXDerived::Scalar>, const ArgADerived, const ArgBDerived, const ArgXDerived>\nbetainc(const Eigen::ArrayBase<ArgADerived>& a, const Eigen::ArrayBase<ArgBDerived>& b, const Eigen::ArrayBase<ArgXDerived>& x)\n{\n  return Eigen::CwiseTernaryOp<Eigen::internal::scalar_betainc_op<typename ArgXDerived::Scalar>, const ArgADerived, const ArgBDerived, const ArgXDerived>(\n    a.derived(),\n    b.derived(),\n    x.derived()\n  );\n}\n\n\n/** \\returns an expression of the coefficient-wise zeta(\\a x, \\a q) to the given arrays.\n  *\n  * It returns the Riemann zeta function of two arguments \\a x and \\a q:\n  *\n  * \\param x is the exponent, it must be > 1\n  * \\param q is the shift, it must be > 0\n  *\n  * \\note This function supports only float and double scalar types. To support other scalar types, the user has\n  * to provide implementations of zeta(T,T) for any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::zeta()\n  */\ntemplate<typename DerivedX,typename DerivedQ>\nEIGEN_STRONG_INLINE const Eigen::CwiseBinaryOp<Eigen::internal::scalar_zeta_op<typename DerivedX::Scalar>, const DerivedX, const DerivedQ>\nzeta(const Eigen::ArrayBase<DerivedX>& x, const Eigen::ArrayBase<DerivedQ>& q)\n{\n  return Eigen::CwiseBinaryOp<Eigen::internal::scalar_zeta_op<typename DerivedX::Scalar>, const DerivedX, const DerivedQ>(\n    x.derived(),\n    q.derived()\n  );\n}\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPECIALFUNCTIONS_ARRAYAPI_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsBFloat16.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPECIALFUNCTIONS_BFLOAT16_H\n#define EIGEN_SPECIALFUNCTIONS_BFLOAT16_H\n\nnamespace Eigen {\nnamespace numext {\n\n#if EIGEN_HAS_C99_MATH\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 lgamma(const Eigen::bfloat16& a) {\n  return Eigen::bfloat16(Eigen::numext::lgamma(static_cast<float>(a)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 digamma(const Eigen::bfloat16& a) {\n  return Eigen::bfloat16(Eigen::numext::digamma(static_cast<float>(a)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 zeta(const Eigen::bfloat16& x, const Eigen::bfloat16& q) {\n  return Eigen::bfloat16(Eigen::numext::zeta(static_cast<float>(x), static_cast<float>(q)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 polygamma(const Eigen::bfloat16& n, const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::polygamma(static_cast<float>(n), static_cast<float>(x)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 erf(const Eigen::bfloat16& a) {\n  return Eigen::bfloat16(Eigen::numext::erf(static_cast<float>(a)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 erfc(const Eigen::bfloat16& a) {\n  return Eigen::bfloat16(Eigen::numext::erfc(static_cast<float>(a)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 ndtri(const Eigen::bfloat16& a) {\n  return Eigen::bfloat16(Eigen::numext::ndtri(static_cast<float>(a)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 igamma(const Eigen::bfloat16& a, const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::igamma(static_cast<float>(a), static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 igamma_der_a(const Eigen::bfloat16& a, const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::igamma_der_a(static_cast<float>(a), static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 gamma_sample_der_alpha(const Eigen::bfloat16& alpha, const Eigen::bfloat16& sample) {\n  return Eigen::bfloat16(Eigen::numext::gamma_sample_der_alpha(static_cast<float>(alpha), static_cast<float>(sample)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 igammac(const Eigen::bfloat16& a, const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::igammac(static_cast<float>(a), static_cast<float>(x)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 betainc(const Eigen::bfloat16& a, const Eigen::bfloat16& b, const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::betainc(static_cast<float>(a), static_cast<float>(b), static_cast<float>(x)));\n}\n#endif\n\n}  // end namespace numext\n}  // end namespace Eigen\n\n#endif  // EIGEN_SPECIALFUNCTIONS_BFLOAT16_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsFunctors.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Eugene Brevdo <ebrevdo@gmail.com>\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPECIALFUNCTIONS_FUNCTORS_H\n#define EIGEN_SPECIALFUNCTIONS_FUNCTORS_H\n\nnamespace Eigen {\n\nnamespace internal {\n\n\n/** \\internal\n  * \\brief Template functor to compute the incomplete gamma function igamma(a, x)\n  *\n  * \\sa class CwiseBinaryOp, Cwise::igamma\n  */\ntemplate<typename Scalar> struct scalar_igamma_op : binary_op_base<Scalar,Scalar>\n{\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_igamma_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a, const Scalar& x) const {\n    using numext::igamma; return igamma(a, x);\n  }\n  template<typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& x) const {\n    return internal::pigamma(a, x);\n  }\n};\ntemplate<typename Scalar>\nstruct functor_traits<scalar_igamma_op<Scalar> > {\n  enum {\n    // Guesstimate\n    Cost = 20 * NumTraits<Scalar>::MulCost + 10 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasIGamma\n  };\n};\n\n/** \\internal\n  * \\brief Template functor to compute the derivative of the incomplete gamma\n  * function igamma_der_a(a, x)\n  *\n  * \\sa class CwiseBinaryOp, Cwise::igamma_der_a\n  */\ntemplate <typename Scalar>\nstruct scalar_igamma_der_a_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_igamma_der_a_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& a, const Scalar& x) const {\n    using numext::igamma_der_a;\n    return igamma_der_a(a, x);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& x) const {\n    return internal::pigamma_der_a(a, x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_igamma_der_a_op<Scalar> > {\n  enum {\n    // 2x the cost of igamma\n    Cost = 40 * NumTraits<Scalar>::MulCost + 20 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasIGammaDerA\n  };\n};\n\n/** \\internal\n  * \\brief Template functor to compute the derivative of the sample\n  * of a Gamma(alpha, 1) random variable with respect to the parameter alpha\n  * gamma_sample_der_alpha(alpha, sample)\n  *\n  * \\sa class CwiseBinaryOp, Cwise::gamma_sample_der_alpha\n  */\ntemplate <typename Scalar>\nstruct scalar_gamma_sample_der_alpha_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_gamma_sample_der_alpha_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& alpha, const Scalar& sample) const {\n    using numext::gamma_sample_der_alpha;\n    return gamma_sample_der_alpha(alpha, sample);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& alpha, const Packet& sample) const {\n    return internal::pgamma_sample_der_alpha(alpha, sample);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_gamma_sample_der_alpha_op<Scalar> > {\n  enum {\n    // 2x the cost of igamma, minus the lgamma cost (the lgamma cancels out)\n    Cost = 30 * NumTraits<Scalar>::MulCost + 15 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasGammaSampleDerAlpha\n  };\n};\n\n/** \\internal\n  * \\brief Template functor to compute the complementary incomplete gamma function igammac(a, x)\n  *\n  * \\sa class CwiseBinaryOp, Cwise::igammac\n  */\ntemplate<typename Scalar> struct scalar_igammac_op : binary_op_base<Scalar,Scalar>\n{\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_igammac_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a, const Scalar& x) const {\n    using numext::igammac; return igammac(a, x);\n  }\n  template<typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& x) const\n  {\n    return internal::pigammac(a, x);\n  }\n};\ntemplate<typename Scalar>\nstruct functor_traits<scalar_igammac_op<Scalar> > {\n  enum {\n    // Guesstimate\n    Cost = 20 * NumTraits<Scalar>::MulCost + 10 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasIGammac\n  };\n};\n\n\n/** \\internal\n  * \\brief Template functor to compute the incomplete beta integral betainc(a, b, x)\n  *\n  */\ntemplate<typename Scalar> struct scalar_betainc_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_betainc_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& x, const Scalar& a, const Scalar& b) const {\n    using numext::betainc; return betainc(x, a, b);\n  }\n  template<typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& x, const Packet& a, const Packet& b) const\n  {\n    return internal::pbetainc(x, a, b);\n  }\n};\ntemplate<typename Scalar>\nstruct functor_traits<scalar_betainc_op<Scalar> > {\n  enum {\n    // Guesstimate\n    Cost = 400 * NumTraits<Scalar>::MulCost + 400 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBetaInc\n  };\n};\n\n\n/** \\internal\n * \\brief Template functor to compute the natural log of the absolute\n * value of Gamma of a scalar\n * \\sa class CwiseUnaryOp, Cwise::lgamma()\n */\ntemplate<typename Scalar> struct scalar_lgamma_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_lgamma_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a) const {\n    using numext::lgamma; return lgamma(a);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& a) const { return internal::plgamma(a); }\n};\ntemplate<typename Scalar>\nstruct functor_traits<scalar_lgamma_op<Scalar> >\n{\n  enum {\n    // Guesstimate\n    Cost = 10 * NumTraits<Scalar>::MulCost + 5 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasLGamma\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute psi, the derivative of lgamma of a scalar.\n * \\sa class CwiseUnaryOp, Cwise::digamma()\n */\ntemplate<typename Scalar> struct scalar_digamma_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_digamma_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a) const {\n    using numext::digamma; return digamma(a);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& a) const { return internal::pdigamma(a); }\n};\ntemplate<typename Scalar>\nstruct functor_traits<scalar_digamma_op<Scalar> >\n{\n  enum {\n    // Guesstimate\n    Cost = 10 * NumTraits<Scalar>::MulCost + 5 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasDiGamma\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the Riemann Zeta function of two arguments.\n * \\sa class CwiseUnaryOp, Cwise::zeta()\n */\ntemplate<typename Scalar> struct scalar_zeta_op {\n    EIGEN_EMPTY_STRUCT_CTOR(scalar_zeta_op)\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& x, const Scalar& q) const {\n        using numext::zeta; return zeta(x, q);\n    }\n    typedef typename packet_traits<Scalar>::type Packet;\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x, const Packet& q) const { return internal::pzeta(x, q); }\n};\ntemplate<typename Scalar>\nstruct functor_traits<scalar_zeta_op<Scalar> >\n{\n    enum {\n        // Guesstimate\n        Cost = 10 * NumTraits<Scalar>::MulCost + 5 * NumTraits<Scalar>::AddCost,\n        PacketAccess = packet_traits<Scalar>::HasZeta\n    };\n};\n\n/** \\internal\n * \\brief Template functor to compute the polygamma function.\n * \\sa class CwiseUnaryOp, Cwise::polygamma()\n */\ntemplate<typename Scalar> struct scalar_polygamma_op {\n    EIGEN_EMPTY_STRUCT_CTOR(scalar_polygamma_op)\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& n, const Scalar& x) const {\n        using numext::polygamma; return polygamma(n, x);\n    }\n    typedef typename packet_traits<Scalar>::type Packet;\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& n, const Packet& x) const { return internal::ppolygamma(n, x); }\n};\ntemplate<typename Scalar>\nstruct functor_traits<scalar_polygamma_op<Scalar> >\n{\n    enum {\n        // Guesstimate\n        Cost = 10 * NumTraits<Scalar>::MulCost + 5 * NumTraits<Scalar>::AddCost,\n        PacketAccess = packet_traits<Scalar>::HasPolygamma\n    };\n};\n\n/** \\internal\n * \\brief Template functor to compute the error function of a scalar\n * \\sa class CwiseUnaryOp, ArrayBase::erf()\n */\ntemplate<typename Scalar> struct scalar_erf_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_erf_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar\n  operator()(const Scalar& a) const {\n    return numext::erf(a);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return perf(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_erf_op<Scalar> > {\n  enum {\n    PacketAccess = packet_traits<Scalar>::HasErf,\n    Cost =\n        (PacketAccess\n#ifdef EIGEN_VECTORIZE_FMA\n             // TODO(rmlarsen): Move the FMA cost model to a central location.\n             // Haswell can issue 2 add/mul/madd per cycle.\n             // 10 pmadd, 2 pmul, 1 div, 2 other\n             ? (2 * NumTraits<Scalar>::AddCost +\n                7 * NumTraits<Scalar>::MulCost +\n                scalar_div_cost<Scalar, packet_traits<Scalar>::HasDiv>::value)\n#else\n             ? (12 * NumTraits<Scalar>::AddCost +\n                12 * NumTraits<Scalar>::MulCost +\n                scalar_div_cost<Scalar, packet_traits<Scalar>::HasDiv>::value)\n#endif\n             // Assume for simplicity that this is as expensive as an exp().\n             : (functor_traits<scalar_exp_op<Scalar> >::Cost))\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the Complementary Error Function\n * of a scalar\n * \\sa class CwiseUnaryOp, Cwise::erfc()\n */\ntemplate<typename Scalar> struct scalar_erfc_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_erfc_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a) const {\n    using numext::erfc; return erfc(a);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& a) const { return internal::perfc(a); }\n};\ntemplate<typename Scalar>\nstruct functor_traits<scalar_erfc_op<Scalar> >\n{\n  enum {\n    // Guesstimate\n    Cost = 10 * NumTraits<Scalar>::MulCost + 5 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasErfc\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the Inverse of the normal distribution\n * function of a scalar\n * \\sa class CwiseUnaryOp, Cwise::ndtri()\n */\ntemplate<typename Scalar> struct scalar_ndtri_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_ndtri_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a) const {\n    using numext::ndtri; return ndtri(a);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& a) const { return internal::pndtri(a); }\n};\ntemplate<typename Scalar>\nstruct functor_traits<scalar_ndtri_op<Scalar> >\n{\n  enum {\n    // On average, We are evaluating rational functions with degree N=9 in the\n    // numerator and denominator. This results in 2*N additions and 2*N\n    // multiplications.\n    Cost = 18 * NumTraits<Scalar>::MulCost + 18 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasNdtri\n  };\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPECIALFUNCTIONS_FUNCTORS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsHalf.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPECIALFUNCTIONS_HALF_H\n#define EIGEN_SPECIALFUNCTIONS_HALF_H\n\nnamespace Eigen {\nnamespace numext {\n\n#if EIGEN_HAS_C99_MATH\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half lgamma(const Eigen::half& a) {\n  return Eigen::half(Eigen::numext::lgamma(static_cast<float>(a)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half digamma(const Eigen::half& a) {\n  return Eigen::half(Eigen::numext::digamma(static_cast<float>(a)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half zeta(const Eigen::half& x, const Eigen::half& q) {\n  return Eigen::half(Eigen::numext::zeta(static_cast<float>(x), static_cast<float>(q)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half polygamma(const Eigen::half& n, const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::polygamma(static_cast<float>(n), static_cast<float>(x)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half erf(const Eigen::half& a) {\n  return Eigen::half(Eigen::numext::erf(static_cast<float>(a)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half erfc(const Eigen::half& a) {\n  return Eigen::half(Eigen::numext::erfc(static_cast<float>(a)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half ndtri(const Eigen::half& a) {\n  return Eigen::half(Eigen::numext::ndtri(static_cast<float>(a)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half igamma(const Eigen::half& a, const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::igamma(static_cast<float>(a), static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half igamma_der_a(const Eigen::half& a, const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::igamma_der_a(static_cast<float>(a), static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half gamma_sample_der_alpha(const Eigen::half& alpha, const Eigen::half& sample) {\n  return Eigen::half(Eigen::numext::gamma_sample_der_alpha(static_cast<float>(alpha), static_cast<float>(sample)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half igammac(const Eigen::half& a, const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::igammac(static_cast<float>(a), static_cast<float>(x)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half betainc(const Eigen::half& a, const Eigen::half& b, const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::betainc(static_cast<float>(a), static_cast<float>(b), static_cast<float>(x)));\n}\n#endif\n\n}  // end namespace numext\n}  // end namespace Eigen\n\n#endif  // EIGEN_SPECIALFUNCTIONS_HALF_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsImpl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Eugene Brevdo <ebrevdo@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPECIAL_FUNCTIONS_H\n#define EIGEN_SPECIAL_FUNCTIONS_H\n\nnamespace Eigen {\nnamespace internal {\n\n//  Parts of this code are based on the Cephes Math Library.\n//\n//  Cephes Math Library Release 2.8:  June, 2000\n//  Copyright 1984, 1987, 1992, 2000 by Stephen L. Moshier\n//\n//  Permission has been kindly provided by the original author\n//  to incorporate the Cephes software into the Eigen codebase:\n//\n//    From: Stephen Moshier\n//    To: Eugene Brevdo\n//    Subject: Re: Permission to wrap several cephes functions in Eigen\n//\n//    Hello Eugene,\n//\n//    Thank you for writing.\n//\n//    If your licensing is similar to BSD, the formal way that has been\n//    handled is simply to add a statement to the effect that you are incorporating\n//    the Cephes software by permission of the author.\n//\n//    Good luck with your project,\n//    Steve\n\n\n/****************************************************************************\n * Implementation of lgamma, requires C++11/C99                             *\n ****************************************************************************/\n\ntemplate <typename Scalar>\nstruct lgamma_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar run(const Scalar) {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar, Scalar>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return Scalar(0);\n  }\n};\n\ntemplate <typename Scalar>\nstruct lgamma_retval {\n  typedef Scalar type;\n};\n\n#if EIGEN_HAS_C99_MATH\n// Since glibc 2.19\n#if defined(__GLIBC__) && ((__GLIBC__>=2 && __GLIBC_MINOR__ >= 19) || __GLIBC__>2) \\\n && (defined(_DEFAULT_SOURCE) || defined(_BSD_SOURCE) || defined(_SVID_SOURCE))\n#define EIGEN_HAS_LGAMMA_R\n#endif\n\n// Glibc versions before 2.19\n#if defined(__GLIBC__) && ((__GLIBC__==2 && __GLIBC_MINOR__ < 19) || __GLIBC__<2) \\\n && (defined(_BSD_SOURCE) || defined(_SVID_SOURCE))\n#define EIGEN_HAS_LGAMMA_R\n#endif\n\ntemplate <>\nstruct lgamma_impl<float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE float run(float x) {\n#if !defined(EIGEN_GPU_COMPILE_PHASE) && defined (EIGEN_HAS_LGAMMA_R) && !defined(__APPLE__)\n    int dummy;\n    return ::lgammaf_r(x, &dummy);\n#elif defined(SYCL_DEVICE_ONLY)\n    return cl::sycl::lgamma(x);\n#else\n    return ::lgammaf(x);\n#endif\n  }\n};\n\ntemplate <>\nstruct lgamma_impl<double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE double run(double x) {\n#if !defined(EIGEN_GPU_COMPILE_PHASE) && defined(EIGEN_HAS_LGAMMA_R) && !defined(__APPLE__)\n    int dummy;\n    return ::lgamma_r(x, &dummy);\n#elif defined(SYCL_DEVICE_ONLY)\n    return cl::sycl::lgamma(x);\n#else\n    return ::lgamma(x);\n#endif\n  }\n};\n\n#undef EIGEN_HAS_LGAMMA_R\n#endif\n\n/****************************************************************************\n * Implementation of digamma (psi), based on Cephes                         *\n ****************************************************************************/\n\ntemplate <typename Scalar>\nstruct digamma_retval {\n  typedef Scalar type;\n};\n\n/*\n *\n * Polynomial evaluation helper for the Psi (digamma) function.\n *\n * digamma_impl_maybe_poly::run(s) evaluates the asymptotic Psi expansion for\n * input Scalar s, assuming s is above 10.0.\n *\n * If s is above a certain threshold for the given Scalar type, zero\n * is returned.  Otherwise the polynomial is evaluated with enough\n * coefficients for results matching Scalar machine precision.\n *\n *\n */\ntemplate <typename Scalar>\nstruct digamma_impl_maybe_poly {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar run(const Scalar) {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar, Scalar>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return Scalar(0);\n  }\n};\n\n\ntemplate <>\nstruct digamma_impl_maybe_poly<float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE float run(const float s) {\n    const float A[] = {\n      -4.16666666666666666667E-3f,\n      3.96825396825396825397E-3f,\n      -8.33333333333333333333E-3f,\n      8.33333333333333333333E-2f\n    };\n\n    float z;\n    if (s < 1.0e8f) {\n      z = 1.0f / (s * s);\n      return z * internal::ppolevl<float, 3>::run(z, A);\n    } else return 0.0f;\n  }\n};\n\ntemplate <>\nstruct digamma_impl_maybe_poly<double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE double run(const double s) {\n    const double A[] = {\n      8.33333333333333333333E-2,\n      -2.10927960927960927961E-2,\n      7.57575757575757575758E-3,\n      -4.16666666666666666667E-3,\n      3.96825396825396825397E-3,\n      -8.33333333333333333333E-3,\n      8.33333333333333333333E-2\n    };\n\n    double z;\n    if (s < 1.0e17) {\n      z = 1.0 / (s * s);\n      return z * internal::ppolevl<double, 6>::run(z, A);\n    }\n    else return 0.0;\n  }\n};\n\ntemplate <typename Scalar>\nstruct digamma_impl {\n  EIGEN_DEVICE_FUNC\n  static Scalar run(Scalar x) {\n    /*\n     *\n     *     Psi (digamma) function (modified for Eigen)\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, psi();\n     *\n     * y = psi( x );\n     *\n     *\n     * DESCRIPTION:\n     *\n     *              d      -\n     *   psi(x)  =  -- ln | (x)\n     *              dx\n     *\n     * is the logarithmic derivative of the gamma function.\n     * For integer x,\n     *                   n-1\n     *                    -\n     * psi(n) = -EUL  +   >  1/k.\n     *                    -\n     *                   k=1\n     *\n     * If x is negative, it is transformed to a positive argument by the\n     * reflection formula  psi(1-x) = psi(x) + pi cot(pi x).\n     * For general positive x, the argument is made greater than 10\n     * using the recurrence  psi(x+1) = psi(x) + 1/x.\n     * Then the following asymptotic expansion is applied:\n     *\n     *                           inf.   B\n     *                            -      2k\n     * psi(x) = log(x) - 1/2x -   >   -------\n     *                            -        2k\n     *                           k=1   2k x\n     *\n     * where the B2k are Bernoulli numbers.\n     *\n     * ACCURACY (float):\n     *    Relative error (except absolute when |psi| < 1):\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0,30        30000       1.3e-15     1.4e-16\n     *    IEEE      -30,0       40000       1.5e-15     2.2e-16\n     *\n     * ACCURACY (double):\n     *    Absolute error,  relative when |psi| > 1 :\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      -33,0        30000      8.2e-7      1.2e-7\n     *    IEEE      0,33        100000      7.3e-7      7.7e-8\n     *\n     * ERROR MESSAGES:\n     *     message         condition      value returned\n     * psi singularity    x integer <=0      INFINITY\n     */\n\n    Scalar p, q, nz, s, w, y;\n    bool negative = false;\n\n    const Scalar nan = NumTraits<Scalar>::quiet_NaN();\n    const Scalar m_pi = Scalar(EIGEN_PI);\n\n    const Scalar zero = Scalar(0);\n    const Scalar one = Scalar(1);\n    const Scalar half = Scalar(0.5);\n    nz = zero;\n\n    if (x <= zero) {\n      negative = true;\n      q = x;\n      p = numext::floor(q);\n      if (p == q) {\n        return nan;\n      }\n      /* Remove the zeros of tan(m_pi x)\n       * by subtracting the nearest integer from x\n       */\n      nz = q - p;\n      if (nz != half) {\n        if (nz > half) {\n          p += one;\n          nz = q - p;\n        }\n        nz = m_pi / numext::tan(m_pi * nz);\n      }\n      else {\n        nz = zero;\n      }\n      x = one - x;\n    }\n\n    /* use the recurrence psi(x+1) = psi(x) + 1/x. */\n    s = x;\n    w = zero;\n    while (s < Scalar(10)) {\n      w += one / s;\n      s += one;\n    }\n\n    y = digamma_impl_maybe_poly<Scalar>::run(s);\n\n    y = numext::log(s) - (half / s) - y - w;\n\n    return (negative) ? y - nz : y;\n  }\n};\n\n/****************************************************************************\n * Implementation of erf, requires C++11/C99                                *\n ****************************************************************************/\n\n/** \\internal \\returns the error function of \\a a (coeff-wise)\n    Doesn't do anything fancy, just a 13/8-degree rational interpolant which\n    is accurate up to a couple of ulp in the range [-4, 4], outside of which\n    fl(erf(x)) = +/-1.\n\n    This implementation works on both scalars and Ts.\n*/\ntemplate <typename T>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T generic_fast_erf_float(const T& a_x) {\n  // Clamp the inputs to the range [-4, 4] since anything outside\n  // this range is +/-1.0f in single-precision.\n  const T plus_4 = pset1<T>(4.f);\n  const T minus_4 = pset1<T>(-4.f);\n  const T x = pmax(pmin(a_x, plus_4), minus_4);\n  // The monomial coefficients of the numerator polynomial (odd).\n  const T alpha_1 = pset1<T>(-1.60960333262415e-02f);\n  const T alpha_3 = pset1<T>(-2.95459980854025e-03f);\n  const T alpha_5 = pset1<T>(-7.34990630326855e-04f);\n  const T alpha_7 = pset1<T>(-5.69250639462346e-05f);\n  const T alpha_9 = pset1<T>(-2.10102402082508e-06f);\n  const T alpha_11 = pset1<T>(2.77068142495902e-08f);\n  const T alpha_13 = pset1<T>(-2.72614225801306e-10f);\n\n  // The monomial coefficients of the denominator polynomial (even).\n  const T beta_0 = pset1<T>(-1.42647390514189e-02f);\n  const T beta_2 = pset1<T>(-7.37332916720468e-03f);\n  const T beta_4 = pset1<T>(-1.68282697438203e-03f);\n  const T beta_6 = pset1<T>(-2.13374055278905e-04f);\n  const T beta_8 = pset1<T>(-1.45660718464996e-05f);\n\n  // Since the polynomials are odd/even, we need x^2.\n  const T x2 = pmul(x, x);\n\n  // Evaluate the numerator polynomial p.\n  T p = pmadd(x2, alpha_13, alpha_11);\n  p = pmadd(x2, p, alpha_9);\n  p = pmadd(x2, p, alpha_7);\n  p = pmadd(x2, p, alpha_5);\n  p = pmadd(x2, p, alpha_3);\n  p = pmadd(x2, p, alpha_1);\n  p = pmul(x, p);\n\n  // Evaluate the denominator polynomial p.\n  T q = pmadd(x2, beta_8, beta_6);\n  q = pmadd(x2, q, beta_4);\n  q = pmadd(x2, q, beta_2);\n  q = pmadd(x2, q, beta_0);\n\n  // Divide the numerator by the denominator.\n  return pdiv(p, q);\n}\n\ntemplate <typename T>\nstruct erf_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    return generic_fast_erf_float(x);\n  }\n};\n\ntemplate <typename Scalar>\nstruct erf_retval {\n  typedef Scalar type;\n};\n\n#if EIGEN_HAS_C99_MATH\ntemplate <>\nstruct erf_impl<float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE float run(float x) {\n#if defined(SYCL_DEVICE_ONLY)\n    return cl::sycl::erf(x);\n#else\n    return generic_fast_erf_float(x);\n#endif\n  }\n};\n\ntemplate <>\nstruct erf_impl<double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE double run(double x) {\n#if defined(SYCL_DEVICE_ONLY)\n    return cl::sycl::erf(x);\n#else\n    return ::erf(x);\n#endif\n  }\n};\n#endif  // EIGEN_HAS_C99_MATH\n\n/***************************************************************************\n* Implementation of erfc, requires C++11/C99                               *\n****************************************************************************/\n\ntemplate <typename Scalar>\nstruct erfc_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar run(const Scalar) {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar, Scalar>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return Scalar(0);\n  }\n};\n\ntemplate <typename Scalar>\nstruct erfc_retval {\n  typedef Scalar type;\n};\n\n#if EIGEN_HAS_C99_MATH\ntemplate <>\nstruct erfc_impl<float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE float run(const float x) {\n#if defined(SYCL_DEVICE_ONLY)\n    return cl::sycl::erfc(x);\n#else\n    return ::erfcf(x);\n#endif\n  }\n};\n\ntemplate <>\nstruct erfc_impl<double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE double run(const double x) {\n#if defined(SYCL_DEVICE_ONLY)\n    return cl::sycl::erfc(x);\n#else\n    return ::erfc(x);\n#endif\n  }\n};\n#endif  // EIGEN_HAS_C99_MATH\n\n\n/***************************************************************************\n* Implementation of ndtri.                                                 *\n****************************************************************************/\n\n/* Inverse of Normal distribution function (modified for Eigen).\n *\n *\n * SYNOPSIS:\n *\n * double x, y, ndtri();\n *\n * x = ndtri( y );\n *\n *\n *\n * DESCRIPTION:\n *\n * Returns the argument, x, for which the area under the\n * Gaussian probability density function (integrated from\n * minus infinity to x) is equal to y.\n *\n *\n * For small arguments 0 < y < exp(-2), the program computes\n * z = sqrt( -2.0 * log(y) );  then the approximation is\n * x = z - log(z)/z  - (1/z) P(1/z) / Q(1/z).\n * There are two rational functions P/Q, one for 0 < y < exp(-32)\n * and the other for y up to exp(-2).  For larger arguments,\n * w = y - 0.5, and  x/sqrt(2pi) = w + w**3 R(w**2)/S(w**2)).\n *\n *\n * ACCURACY:\n *\n *                      Relative error:\n * arithmetic   domain        # trials      peak         rms\n *    DEC      0.125, 1         5500       9.5e-17     2.1e-17\n *    DEC      6e-39, 0.135     3500       5.7e-17     1.3e-17\n *    IEEE     0.125, 1        20000       7.2e-16     1.3e-16\n *    IEEE     3e-308, 0.135   50000       4.6e-16     9.8e-17\n *\n *\n * ERROR MESSAGES:\n *\n *   message         condition    value returned\n * ndtri domain       x <= 0        -MAXNUM\n * ndtri domain       x >= 1         MAXNUM\n *\n */\n /*\n   Cephes Math Library Release 2.2: June, 1992\n   Copyright 1985, 1987, 1992 by Stephen L. Moshier\n   Direct inquiries to 30 Frost Street, Cambridge, MA 02140\n */\n\n\n// TODO: Add a cheaper approximation for float.\n\n\ntemplate<typename T>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T flipsign(\n    const T& should_flipsign, const T& x) {\n  typedef typename unpacket_traits<T>::type Scalar;\n  const T sign_mask = pset1<T>(Scalar(-0.0));\n  T sign_bit = pand<T>(should_flipsign, sign_mask);\n  return pxor<T>(sign_bit, x);\n}\n\ntemplate<>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double flipsign<double>(\n    const double& should_flipsign, const double& x) {\n  return should_flipsign == 0 ? x : -x;\n}\n\ntemplate<>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float flipsign<float>(\n    const float& should_flipsign, const float& x) {\n  return should_flipsign == 0 ? x : -x;\n}\n\n// We split this computation in to two so that in the scalar path\n// only one branch is evaluated (due to our template specialization of pselect\n// being an if statement.)\n\ntemplate <typename T, typename ScalarType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T generic_ndtri_gt_exp_neg_two(const T& b) {\n  const ScalarType p0[] = {\n    ScalarType(-5.99633501014107895267e1),\n    ScalarType(9.80010754185999661536e1),\n    ScalarType(-5.66762857469070293439e1),\n    ScalarType(1.39312609387279679503e1),\n    ScalarType(-1.23916583867381258016e0)\n  };\n  const ScalarType q0[] = {\n    ScalarType(1.0),\n    ScalarType(1.95448858338141759834e0),\n    ScalarType(4.67627912898881538453e0),\n    ScalarType(8.63602421390890590575e1),\n    ScalarType(-2.25462687854119370527e2),\n    ScalarType(2.00260212380060660359e2),\n    ScalarType(-8.20372256168333339912e1),\n    ScalarType(1.59056225126211695515e1),\n    ScalarType(-1.18331621121330003142e0)\n  };\n  const T sqrt2pi = pset1<T>(ScalarType(2.50662827463100050242e0));\n  const T half = pset1<T>(ScalarType(0.5));\n  T c, c2, ndtri_gt_exp_neg_two;\n\n  c = psub(b, half);\n  c2 = pmul(c, c);\n  ndtri_gt_exp_neg_two = pmadd(c, pmul(\n      c2, pdiv(\n          internal::ppolevl<T, 4>::run(c2, p0),\n          internal::ppolevl<T, 8>::run(c2, q0))), c);\n  return pmul(ndtri_gt_exp_neg_two, sqrt2pi);\n}\n\ntemplate <typename T, typename ScalarType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T generic_ndtri_lt_exp_neg_two(\n    const T& b, const T& should_flipsign) {\n  /* Approximation for interval z = sqrt(-2 log a ) between 2 and 8\n   * i.e., a between exp(-2) = .135 and exp(-32) = 1.27e-14.\n   */\n  const ScalarType p1[] = {\n    ScalarType(4.05544892305962419923e0),\n    ScalarType(3.15251094599893866154e1),\n    ScalarType(5.71628192246421288162e1),\n    ScalarType(4.40805073893200834700e1),\n    ScalarType(1.46849561928858024014e1),\n    ScalarType(2.18663306850790267539e0),\n    ScalarType(-1.40256079171354495875e-1),\n    ScalarType(-3.50424626827848203418e-2),\n    ScalarType(-8.57456785154685413611e-4)\n  };\n  const ScalarType q1[] = {\n    ScalarType(1.0),\n    ScalarType(1.57799883256466749731e1),\n    ScalarType(4.53907635128879210584e1),\n    ScalarType(4.13172038254672030440e1),\n    ScalarType(1.50425385692907503408e1),\n    ScalarType(2.50464946208309415979e0),\n    ScalarType(-1.42182922854787788574e-1),\n    ScalarType(-3.80806407691578277194e-2),\n    ScalarType(-9.33259480895457427372e-4)\n  };\n  /* Approximation for interval z = sqrt(-2 log a ) between 8 and 64\n   * i.e., a between exp(-32) = 1.27e-14 and exp(-2048) = 3.67e-890.\n   */\n  const ScalarType p2[] = {\n    ScalarType(3.23774891776946035970e0),\n    ScalarType(6.91522889068984211695e0),\n    ScalarType(3.93881025292474443415e0),\n    ScalarType(1.33303460815807542389e0),\n    ScalarType(2.01485389549179081538e-1),\n    ScalarType(1.23716634817820021358e-2),\n    ScalarType(3.01581553508235416007e-4),\n    ScalarType(2.65806974686737550832e-6),\n    ScalarType(6.23974539184983293730e-9)\n  };\n  const ScalarType q2[] = {\n    ScalarType(1.0),\n    ScalarType(6.02427039364742014255e0),\n    ScalarType(3.67983563856160859403e0),\n    ScalarType(1.37702099489081330271e0),\n    ScalarType(2.16236993594496635890e-1),\n    ScalarType(1.34204006088543189037e-2),\n    ScalarType(3.28014464682127739104e-4),\n    ScalarType(2.89247864745380683936e-6),\n    ScalarType(6.79019408009981274425e-9)\n  };\n  const T eight = pset1<T>(ScalarType(8.0));\n  const T one = pset1<T>(ScalarType(1));\n  const T neg_two = pset1<T>(ScalarType(-2));\n  T x, x0, x1, z;\n\n  x = psqrt(pmul(neg_two, plog(b)));\n  x0 = psub(x, pdiv(plog(x), x));\n  z = pdiv(one, x);\n  x1 = pmul(\n      z, pselect(\n          pcmp_lt(x, eight),\n          pdiv(internal::ppolevl<T, 8>::run(z, p1),\n               internal::ppolevl<T, 8>::run(z, q1)),\n          pdiv(internal::ppolevl<T, 8>::run(z, p2),\n               internal::ppolevl<T, 8>::run(z, q2))));\n  return flipsign(should_flipsign, psub(x0, x1));\n}\n\ntemplate <typename T, typename ScalarType>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nT generic_ndtri(const T& a) {\n  const T maxnum = pset1<T>(NumTraits<ScalarType>::infinity());\n  const T neg_maxnum = pset1<T>(-NumTraits<ScalarType>::infinity());\n\n  const T zero = pset1<T>(ScalarType(0));\n  const T one = pset1<T>(ScalarType(1));\n  // exp(-2)\n  const T exp_neg_two = pset1<T>(ScalarType(0.13533528323661269189));\n  T b, ndtri, should_flipsign;\n\n  should_flipsign = pcmp_le(a, psub(one, exp_neg_two));\n  b = pselect(should_flipsign, a, psub(one, a));\n\n  ndtri = pselect(\n      pcmp_lt(exp_neg_two, b),\n      generic_ndtri_gt_exp_neg_two<T, ScalarType>(b),\n      generic_ndtri_lt_exp_neg_two<T, ScalarType>(b, should_flipsign));\n\n  return pselect(\n      pcmp_le(a, zero), neg_maxnum,\n      pselect(pcmp_le(one, a), maxnum, ndtri));\n}\n\ntemplate <typename Scalar>\nstruct ndtri_retval {\n  typedef Scalar type;\n};\n\n#if !EIGEN_HAS_C99_MATH\n\ntemplate <typename Scalar>\nstruct ndtri_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar run(const Scalar) {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar, Scalar>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return Scalar(0);\n  }\n};\n\n# else\n\ntemplate <typename Scalar>\nstruct ndtri_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar run(const Scalar x) {\n    return generic_ndtri<Scalar, Scalar>(x);\n  }\n};\n\n#endif  // EIGEN_HAS_C99_MATH\n\n\n/**************************************************************************************************************\n * Implementation of igammac (complemented incomplete gamma integral), based on Cephes but requires C++11/C99 *\n **************************************************************************************************************/\n\ntemplate <typename Scalar>\nstruct igammac_retval {\n  typedef Scalar type;\n};\n\n// NOTE: cephes_helper is also used to implement zeta\ntemplate <typename Scalar>\nstruct cephes_helper {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar machep() { assert(false && \"machep not supported for this type\"); return 0.0; }\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar big() { assert(false && \"big not supported for this type\"); return 0.0; }\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar biginv() { assert(false && \"biginv not supported for this type\"); return 0.0; }\n};\n\ntemplate <>\nstruct cephes_helper<float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE float machep() {\n    return NumTraits<float>::epsilon() / 2;  // 1.0 - machep == 1.0\n  }\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE float big() {\n    // use epsneg (1.0 - epsneg == 1.0)\n    return 1.0f / (NumTraits<float>::epsilon() / 2);\n  }\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE float biginv() {\n    // epsneg\n    return machep();\n  }\n};\n\ntemplate <>\nstruct cephes_helper<double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE double machep() {\n    return NumTraits<double>::epsilon() / 2;  // 1.0 - machep == 1.0\n  }\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE double big() {\n    return 1.0 / NumTraits<double>::epsilon();\n  }\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE double biginv() {\n    // inverse of eps\n    return NumTraits<double>::epsilon();\n  }\n};\n\nenum IgammaComputationMode { VALUE, DERIVATIVE, SAMPLE_DERIVATIVE };\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC\nstatic EIGEN_STRONG_INLINE Scalar main_igamma_term(Scalar a, Scalar x) {\n    /* Compute  x**a * exp(-x) / gamma(a)  */\n    Scalar logax = a * numext::log(x) - x - lgamma_impl<Scalar>::run(a);\n    if (logax < -numext::log(NumTraits<Scalar>::highest()) ||\n        // Assuming x and a aren't Nan.\n        (numext::isnan)(logax)) {\n      return Scalar(0);\n    }\n    return numext::exp(logax);\n}\n\ntemplate <typename Scalar, IgammaComputationMode mode>\nEIGEN_DEVICE_FUNC\nint igamma_num_iterations() {\n  /* Returns the maximum number of internal iterations for igamma computation.\n   */\n  if (mode == VALUE) {\n    return 2000;\n  }\n\n  if (internal::is_same<Scalar, float>::value) {\n    return 200;\n  } else if (internal::is_same<Scalar, double>::value) {\n    return 500;\n  } else {\n    return 2000;\n  }\n}\n\ntemplate <typename Scalar, IgammaComputationMode mode>\nstruct igammac_cf_impl {\n  /* Computes igamc(a, x) or derivative (depending on the mode)\n   * using the continued fraction expansion of the complementary\n   * incomplete Gamma function.\n   *\n   * Preconditions:\n   *   a > 0\n   *   x >= 1\n   *   x >= a\n   */\n  EIGEN_DEVICE_FUNC\n  static Scalar run(Scalar a, Scalar x) {\n    const Scalar zero = 0;\n    const Scalar one = 1;\n    const Scalar two = 2;\n    const Scalar machep = cephes_helper<Scalar>::machep();\n    const Scalar big = cephes_helper<Scalar>::big();\n    const Scalar biginv = cephes_helper<Scalar>::biginv();\n\n    if ((numext::isinf)(x)) {\n      return zero;\n    }\n\n    Scalar ax = main_igamma_term<Scalar>(a, x);\n    // This is independent of mode. If this value is zero,\n    // then the function value is zero. If the function value is zero,\n    // then we are in a neighborhood where the function value evalutes to zero,\n    // so the derivative is zero.\n    if (ax == zero) {\n      return zero;\n    }\n\n    // continued fraction\n    Scalar y = one - a;\n    Scalar z = x + y + one;\n    Scalar c = zero;\n    Scalar pkm2 = one;\n    Scalar qkm2 = x;\n    Scalar pkm1 = x + one;\n    Scalar qkm1 = z * x;\n    Scalar ans = pkm1 / qkm1;\n\n    Scalar dpkm2_da = zero;\n    Scalar dqkm2_da = zero;\n    Scalar dpkm1_da = zero;\n    Scalar dqkm1_da = -x;\n    Scalar dans_da = (dpkm1_da - ans * dqkm1_da) / qkm1;\n\n    for (int i = 0; i < igamma_num_iterations<Scalar, mode>(); i++) {\n      c += one;\n      y += one;\n      z += two;\n\n      Scalar yc = y * c;\n      Scalar pk = pkm1 * z - pkm2 * yc;\n      Scalar qk = qkm1 * z - qkm2 * yc;\n\n      Scalar dpk_da = dpkm1_da * z - pkm1 - dpkm2_da * yc + pkm2 * c;\n      Scalar dqk_da = dqkm1_da * z - qkm1 - dqkm2_da * yc + qkm2 * c;\n\n      if (qk != zero) {\n        Scalar ans_prev = ans;\n        ans = pk / qk;\n\n        Scalar dans_da_prev = dans_da;\n        dans_da = (dpk_da - ans * dqk_da) / qk;\n\n        if (mode == VALUE) {\n          if (numext::abs(ans_prev - ans) <= machep * numext::abs(ans)) {\n            break;\n          }\n        } else {\n          if (numext::abs(dans_da - dans_da_prev) <= machep) {\n            break;\n          }\n        }\n      }\n\n      pkm2 = pkm1;\n      pkm1 = pk;\n      qkm2 = qkm1;\n      qkm1 = qk;\n\n      dpkm2_da = dpkm1_da;\n      dpkm1_da = dpk_da;\n      dqkm2_da = dqkm1_da;\n      dqkm1_da = dqk_da;\n\n      if (numext::abs(pk) > big) {\n        pkm2 *= biginv;\n        pkm1 *= biginv;\n        qkm2 *= biginv;\n        qkm1 *= biginv;\n\n        dpkm2_da *= biginv;\n        dpkm1_da *= biginv;\n        dqkm2_da *= biginv;\n        dqkm1_da *= biginv;\n      }\n    }\n\n    /* Compute  x**a * exp(-x) / gamma(a)  */\n    Scalar dlogax_da = numext::log(x) - digamma_impl<Scalar>::run(a);\n    Scalar dax_da = ax * dlogax_da;\n\n    switch (mode) {\n      case VALUE:\n        return ans * ax;\n      case DERIVATIVE:\n        return ans * dax_da + dans_da * ax;\n      case SAMPLE_DERIVATIVE:\n      default: // this is needed to suppress clang warning\n        return -(dans_da + ans * dlogax_da) * x;\n    }\n  }\n};\n\ntemplate <typename Scalar, IgammaComputationMode mode>\nstruct igamma_series_impl {\n  /* Computes igam(a, x) or its derivative (depending on the mode)\n   * using the series expansion of the incomplete Gamma function.\n   *\n   * Preconditions:\n   *   x > 0\n   *   a > 0\n   *   !(x > 1 && x > a)\n   */\n  EIGEN_DEVICE_FUNC\n  static Scalar run(Scalar a, Scalar x) {\n    const Scalar zero = 0;\n    const Scalar one = 1;\n    const Scalar machep = cephes_helper<Scalar>::machep();\n\n    Scalar ax = main_igamma_term<Scalar>(a, x);\n\n    // This is independent of mode. If this value is zero,\n    // then the function value is zero. If the function value is zero,\n    // then we are in a neighborhood where the function value evalutes to zero,\n    // so the derivative is zero.\n    if (ax == zero) {\n      return zero;\n    }\n\n    ax /= a;\n\n    /* power series */\n    Scalar r = a;\n    Scalar c = one;\n    Scalar ans = one;\n\n    Scalar dc_da = zero;\n    Scalar dans_da = zero;\n\n    for (int i = 0; i < igamma_num_iterations<Scalar, mode>(); i++) {\n      r += one;\n      Scalar term = x / r;\n      Scalar dterm_da = -x / (r * r);\n      dc_da = term * dc_da + dterm_da * c;\n      dans_da += dc_da;\n      c *= term;\n      ans += c;\n\n      if (mode == VALUE) {\n        if (c <= machep * ans) {\n          break;\n        }\n      } else {\n        if (numext::abs(dc_da) <= machep * numext::abs(dans_da)) {\n          break;\n        }\n      }\n    }\n\n    Scalar dlogax_da = numext::log(x) - digamma_impl<Scalar>::run(a + one);\n    Scalar dax_da = ax * dlogax_da;\n\n    switch (mode) {\n      case VALUE:\n        return ans * ax;\n      case DERIVATIVE:\n        return ans * dax_da + dans_da * ax;\n      case SAMPLE_DERIVATIVE:\n      default: // this is needed to suppress clang warning\n        return -(dans_da + ans * dlogax_da) * x / a;\n    }\n  }\n};\n\n#if !EIGEN_HAS_C99_MATH\n\ntemplate <typename Scalar>\nstruct igammac_impl {\n  EIGEN_DEVICE_FUNC\n  static Scalar run(Scalar a, Scalar x) {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar, Scalar>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return Scalar(0);\n  }\n};\n\n#else\n\ntemplate <typename Scalar>\nstruct igammac_impl {\n  EIGEN_DEVICE_FUNC\n  static Scalar run(Scalar a, Scalar x) {\n    /*  igamc()\n     *\n     *\tIncomplete gamma integral (modified for Eigen)\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double a, x, y, igamc();\n     *\n     * y = igamc( a, x );\n     *\n     * DESCRIPTION:\n     *\n     * The function is defined by\n     *\n     *\n     *  igamc(a,x)   =   1 - igam(a,x)\n     *\n     *                            inf.\n     *                              -\n     *                     1       | |  -t  a-1\n     *               =   -----     |   e   t   dt.\n     *                    -      | |\n     *                   | (a)    -\n     *                             x\n     *\n     *\n     * In this implementation both arguments must be positive.\n     * The integral is evaluated by either a power series or\n     * continued fraction expansion, depending on the relative\n     * values of a and x.\n     *\n     * ACCURACY (float):\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0,30        30000       7.8e-6      5.9e-7\n     *\n     *\n     * ACCURACY (double):\n     *\n     * Tested at random a, x.\n     *                a         x                      Relative error:\n     * arithmetic   domain   domain     # trials      peak         rms\n     *    IEEE     0.5,100   0,100      200000       1.9e-14     1.7e-15\n     *    IEEE     0.01,0.5  0,100      200000       1.4e-13     1.6e-15\n     *\n     */\n    /*\n      Cephes Math Library Release 2.2: June, 1992\n      Copyright 1985, 1987, 1992 by Stephen L. Moshier\n      Direct inquiries to 30 Frost Street, Cambridge, MA 02140\n    */\n    const Scalar zero = 0;\n    const Scalar one = 1;\n    const Scalar nan = NumTraits<Scalar>::quiet_NaN();\n\n    if ((x < zero) || (a <= zero)) {\n      // domain error\n      return nan;\n    }\n\n    if ((numext::isnan)(a) || (numext::isnan)(x)) {  // propagate nans\n      return nan;\n    }\n\n    if ((x < one) || (x < a)) {\n      return (one - igamma_series_impl<Scalar, VALUE>::run(a, x));\n    }\n\n    return igammac_cf_impl<Scalar, VALUE>::run(a, x);\n  }\n};\n\n#endif  // EIGEN_HAS_C99_MATH\n\n/************************************************************************************************\n * Implementation of igamma (incomplete gamma integral), based on Cephes but requires C++11/C99 *\n ************************************************************************************************/\n\n#if !EIGEN_HAS_C99_MATH\n\ntemplate <typename Scalar, IgammaComputationMode mode>\nstruct igamma_generic_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar run(Scalar a, Scalar x) {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar, Scalar>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return Scalar(0);\n  }\n};\n\n#else\n\ntemplate <typename Scalar, IgammaComputationMode mode>\nstruct igamma_generic_impl {\n  EIGEN_DEVICE_FUNC\n  static Scalar run(Scalar a, Scalar x) {\n    /* Depending on the mode, returns\n     * - VALUE: incomplete Gamma function igamma(a, x)\n     * - DERIVATIVE: derivative of incomplete Gamma function d/da igamma(a, x)\n     * - SAMPLE_DERIVATIVE: implicit derivative of a Gamma random variable\n     * x ~ Gamma(x | a, 1), dx/da = -1 / Gamma(x | a, 1) * d igamma(a, x) / dx\n     *\n     * Derivatives are implemented by forward-mode differentiation.\n     */\n    const Scalar zero = 0;\n    const Scalar one = 1;\n    const Scalar nan = NumTraits<Scalar>::quiet_NaN();\n\n    if (x == zero) return zero;\n\n    if ((x < zero) || (a <= zero)) {  // domain error\n      return nan;\n    }\n\n    if ((numext::isnan)(a) || (numext::isnan)(x)) {  // propagate nans\n      return nan;\n    }\n\n    if ((x > one) && (x > a)) {\n      Scalar ret = igammac_cf_impl<Scalar, mode>::run(a, x);\n      if (mode == VALUE) {\n        return one - ret;\n      } else {\n        return -ret;\n      }\n    }\n\n    return igamma_series_impl<Scalar, mode>::run(a, x);\n  }\n};\n\n#endif  // EIGEN_HAS_C99_MATH\n\ntemplate <typename Scalar>\nstruct igamma_retval {\n  typedef Scalar type;\n};\n\ntemplate <typename Scalar>\nstruct igamma_impl : igamma_generic_impl<Scalar, VALUE> {\n  /* igam()\n   * Incomplete gamma integral.\n   *\n   * The CDF of Gamma(a, 1) random variable at the point x.\n   *\n   * Accuracy estimation. For each a in [10^-2, 10^-1...10^3] we sample\n   * 50 Gamma random variables x ~ Gamma(x | a, 1), a total of 300 points.\n   * The ground truth is computed by mpmath. Mean absolute error:\n   * float: 1.26713e-05\n   * double: 2.33606e-12\n   *\n   * Cephes documentation below.\n   *\n   * SYNOPSIS:\n   *\n   * double a, x, y, igam();\n   *\n   * y = igam( a, x );\n   *\n   * DESCRIPTION:\n   *\n   * The function is defined by\n   *\n   *                           x\n   *                            -\n   *                   1       | |  -t  a-1\n   *  igam(a,x)  =   -----     |   e   t   dt.\n   *                  -      | |\n   *                 | (a)    -\n   *                           0\n   *\n   *\n   * In this implementation both arguments must be positive.\n   * The integral is evaluated by either a power series or\n   * continued fraction expansion, depending on the relative\n   * values of a and x.\n   *\n   * ACCURACY (double):\n   *\n   *                      Relative error:\n   * arithmetic   domain     # trials      peak         rms\n   *    IEEE      0,30       200000       3.6e-14     2.9e-15\n   *    IEEE      0,100      300000       9.9e-14     1.5e-14\n   *\n   *\n   * ACCURACY (float):\n   *\n   *                      Relative error:\n   * arithmetic   domain     # trials      peak         rms\n   *    IEEE      0,30        20000       7.8e-6      5.9e-7\n   *\n   */\n  /*\n    Cephes Math Library Release 2.2: June, 1992\n    Copyright 1985, 1987, 1992 by Stephen L. Moshier\n    Direct inquiries to 30 Frost Street, Cambridge, MA 02140\n  */\n\n  /* left tail of incomplete gamma function:\n   *\n   *          inf.      k\n   *   a  -x   -       x\n   *  x  e     >   ----------\n   *           -     -\n   *          k=0   | (a+k+1)\n   *\n   */\n};\n\ntemplate <typename Scalar>\nstruct igamma_der_a_retval : igamma_retval<Scalar> {};\n\ntemplate <typename Scalar>\nstruct igamma_der_a_impl : igamma_generic_impl<Scalar, DERIVATIVE> {\n  /* Derivative of the incomplete Gamma function with respect to a.\n   *\n   * Computes d/da igamma(a, x) by forward differentiation of the igamma code.\n   *\n   * Accuracy estimation. For each a in [10^-2, 10^-1...10^3] we sample\n   * 50 Gamma random variables x ~ Gamma(x | a, 1), a total of 300 points.\n   * The ground truth is computed by mpmath. Mean absolute error:\n   * float: 6.17992e-07\n   * double: 4.60453e-12\n   *\n   * Reference:\n   * R. Moore. \"Algorithm AS 187: Derivatives of the incomplete gamma\n   * integral\". Journal of the Royal Statistical Society. 1982\n   */\n};\n\ntemplate <typename Scalar>\nstruct gamma_sample_der_alpha_retval : igamma_retval<Scalar> {};\n\ntemplate <typename Scalar>\nstruct gamma_sample_der_alpha_impl\n    : igamma_generic_impl<Scalar, SAMPLE_DERIVATIVE> {\n  /* Derivative of a Gamma random variable sample with respect to alpha.\n   *\n   * Consider a sample of a Gamma random variable with the concentration\n   * parameter alpha: sample ~ Gamma(alpha, 1). The reparameterization\n   * derivative that we want to compute is dsample / dalpha =\n   * d igammainv(alpha, u) / dalpha, where u = igamma(alpha, sample).\n   * However, this formula is numerically unstable and expensive, so instead\n   * we use implicit differentiation:\n   *\n   * igamma(alpha, sample) = u, where u ~ Uniform(0, 1).\n   * Apply d / dalpha to both sides:\n   * d igamma(alpha, sample) / dalpha\n   *     + d igamma(alpha, sample) / dsample * dsample/dalpha  = 0\n   * d igamma(alpha, sample) / dalpha\n   *     + Gamma(sample | alpha, 1) dsample / dalpha = 0\n   * dsample/dalpha = - (d igamma(alpha, sample) / dalpha)\n   *                   / Gamma(sample | alpha, 1)\n   *\n   * Here Gamma(sample | alpha, 1) is the PDF of the Gamma distribution\n   * (note that the derivative of the CDF w.r.t. sample is the PDF).\n   * See the reference below for more details.\n   *\n   * The derivative of igamma(alpha, sample) is computed by forward\n   * differentiation of the igamma code. Division by the Gamma PDF is performed\n   * in the same code, increasing the accuracy and speed due to cancellation\n   * of some terms.\n   *\n   * Accuracy estimation. For each alpha in [10^-2, 10^-1...10^3] we sample\n   * 50 Gamma random variables sample ~ Gamma(sample | alpha, 1), a total of 300\n   * points. The ground truth is computed by mpmath. Mean absolute error:\n   * float: 2.1686e-06\n   * double: 1.4774e-12\n   *\n   * Reference:\n   * M. Figurnov, S. Mohamed, A. Mnih \"Implicit Reparameterization Gradients\".\n   * 2018\n   */\n};\n\n/*****************************************************************************\n * Implementation of Riemann zeta function of two arguments, based on Cephes *\n *****************************************************************************/\n\ntemplate <typename Scalar>\nstruct zeta_retval {\n    typedef Scalar type;\n};\n\ntemplate <typename Scalar>\nstruct zeta_impl_series {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar run(const Scalar) {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar, Scalar>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return Scalar(0);\n  }\n};\n\ntemplate <>\nstruct zeta_impl_series<float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE bool run(float& a, float& b, float& s, const float x, const float machep) {\n    int i = 0;\n    while(i < 9)\n    {\n        i += 1;\n        a += 1.0f;\n        b = numext::pow( a, -x );\n        s += b;\n        if( numext::abs(b/s) < machep )\n            return true;\n    }\n\n    //Return whether we are done\n    return false;\n  }\n};\n\ntemplate <>\nstruct zeta_impl_series<double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE bool run(double& a, double& b, double& s, const double x, const double machep) {\n    int i = 0;\n    while( (i < 9) || (a <= 9.0) )\n    {\n        i += 1;\n        a += 1.0;\n        b = numext::pow( a, -x );\n        s += b;\n        if( numext::abs(b/s) < machep )\n            return true;\n    }\n\n    //Return whether we are done\n    return false;\n  }\n};\n\ntemplate <typename Scalar>\nstruct zeta_impl {\n    EIGEN_DEVICE_FUNC\n    static Scalar run(Scalar x, Scalar q) {\n        /*\t\t\t\t\t\t\tzeta.c\n         *\n         *\tRiemann zeta function of two arguments\n         *\n         *\n         *\n         * SYNOPSIS:\n         *\n         * double x, q, y, zeta();\n         *\n         * y = zeta( x, q );\n         *\n         *\n         *\n         * DESCRIPTION:\n         *\n         *\n         *\n         *                 inf.\n         *                  -        -x\n         *   zeta(x,q)  =   >   (k+q)\n         *                  -\n         *                 k=0\n         *\n         * where x > 1 and q is not a negative integer or zero.\n         * The Euler-Maclaurin summation formula is used to obtain\n         * the expansion\n         *\n         *                n\n         *                -       -x\n         * zeta(x,q)  =   >  (k+q)\n         *                -\n         *               k=1\n         *\n         *           1-x                 inf.  B   x(x+1)...(x+2j)\n         *      (n+q)           1         -     2j\n         *  +  ---------  -  -------  +   >    --------------------\n         *        x-1              x      -                   x+2j+1\n         *                   2(n+q)      j=1       (2j)! (n+q)\n         *\n         * where the B2j are Bernoulli numbers.  Note that (see zetac.c)\n         * zeta(x,1) = zetac(x) + 1.\n         *\n         *\n         *\n         * ACCURACY:\n         *\n         * Relative error for single precision:\n         * arithmetic   domain     # trials      peak         rms\n         *    IEEE      0,25        10000       6.9e-7      1.0e-7\n         *\n         * Large arguments may produce underflow in powf(), in which\n         * case the results are inaccurate.\n         *\n         * REFERENCE:\n         *\n         * Gradshteyn, I. S., and I. M. Ryzhik, Tables of Integrals,\n         * Series, and Products, p. 1073; Academic Press, 1980.\n         *\n         */\n\n        int i;\n        Scalar p, r, a, b, k, s, t, w;\n\n        const Scalar A[] = {\n            Scalar(12.0),\n            Scalar(-720.0),\n            Scalar(30240.0),\n            Scalar(-1209600.0),\n            Scalar(47900160.0),\n            Scalar(-1.8924375803183791606e9), /*1.307674368e12/691*/\n            Scalar(7.47242496e10),\n            Scalar(-2.950130727918164224e12), /*1.067062284288e16/3617*/\n            Scalar(1.1646782814350067249e14), /*5.109094217170944e18/43867*/\n            Scalar(-4.5979787224074726105e15), /*8.028576626982912e20/174611*/\n            Scalar(1.8152105401943546773e17), /*1.5511210043330985984e23/854513*/\n            Scalar(-7.1661652561756670113e18) /*1.6938241367317436694528e27/236364091*/\n            };\n\n        const Scalar maxnum = NumTraits<Scalar>::infinity();\n        const Scalar zero = 0.0, half = 0.5, one = 1.0;\n        const Scalar machep = cephes_helper<Scalar>::machep();\n        const Scalar nan = NumTraits<Scalar>::quiet_NaN();\n\n        if( x == one )\n            return maxnum;\n\n        if( x < one )\n        {\n            return nan;\n        }\n\n        if( q <= zero )\n        {\n            if(q == numext::floor(q))\n            {\n                if (x == numext::floor(x) && long(x) % 2 == 0) {\n                    return maxnum;\n                }\n                else {\n                    return nan;\n                }\n            }\n            p = x;\n            r = numext::floor(p);\n            if (p != r)\n                return nan;\n        }\n\n        /* Permit negative q but continue sum until n+q > +9 .\n         * This case should be handled by a reflection formula.\n         * If q<0 and x is an integer, there is a relation to\n         * the polygamma function.\n         */\n        s = numext::pow( q, -x );\n        a = q;\n        b = zero;\n        // Run the summation in a helper function that is specific to the floating precision\n        if (zeta_impl_series<Scalar>::run(a, b, s, x, machep)) {\n            return s;\n        }\n\n        w = a;\n        s += b*w/(x-one);\n        s -= half * b;\n        a = one;\n        k = zero;\n        for( i=0; i<12; i++ )\n        {\n            a *= x + k;\n            b /= w;\n            t = a*b/A[i];\n            s = s + t;\n            t = numext::abs(t/s);\n            if( t < machep ) {\n              break;\n            }\n            k += one;\n            a *= x + k;\n            b /= w;\n            k += one;\n        }\n        return s;\n  }\n};\n\n/****************************************************************************\n * Implementation of polygamma function, requires C++11/C99                 *\n ****************************************************************************/\n\ntemplate <typename Scalar>\nstruct polygamma_retval {\n    typedef Scalar type;\n};\n\n#if !EIGEN_HAS_C99_MATH\n\ntemplate <typename Scalar>\nstruct polygamma_impl {\n    EIGEN_DEVICE_FUNC\n    static EIGEN_STRONG_INLINE Scalar run(Scalar n, Scalar x) {\n        EIGEN_STATIC_ASSERT((internal::is_same<Scalar, Scalar>::value == false),\n                            THIS_TYPE_IS_NOT_SUPPORTED);\n        return Scalar(0);\n    }\n};\n\n#else\n\ntemplate <typename Scalar>\nstruct polygamma_impl {\n    EIGEN_DEVICE_FUNC\n    static Scalar run(Scalar n, Scalar x) {\n        Scalar zero = 0.0, one = 1.0;\n        Scalar nplus = n + one;\n        const Scalar nan = NumTraits<Scalar>::quiet_NaN();\n\n        // Check that n is a non-negative integer\n        if (numext::floor(n) != n || n < zero) {\n            return nan;\n        }\n        // Just return the digamma function for n = 0\n        else if (n == zero) {\n            return digamma_impl<Scalar>::run(x);\n        }\n        // Use the same implementation as scipy\n        else {\n            Scalar factorial = numext::exp(lgamma_impl<Scalar>::run(nplus));\n            return numext::pow(-one, nplus) * factorial * zeta_impl<Scalar>::run(nplus, x);\n        }\n  }\n};\n\n#endif  // EIGEN_HAS_C99_MATH\n\n/************************************************************************************************\n * Implementation of betainc (incomplete beta integral), based on Cephes but requires C++11/C99 *\n ************************************************************************************************/\n\ntemplate <typename Scalar>\nstruct betainc_retval {\n  typedef Scalar type;\n};\n\n#if !EIGEN_HAS_C99_MATH\n\ntemplate <typename Scalar>\nstruct betainc_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar run(Scalar a, Scalar b, Scalar x) {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar, Scalar>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return Scalar(0);\n  }\n};\n\n#else\n\ntemplate <typename Scalar>\nstruct betainc_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar run(Scalar, Scalar, Scalar) {\n    /*\tbetaincf.c\n     *\n     *\tIncomplete beta integral\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float a, b, x, y, betaincf();\n     *\n     * y = betaincf( a, b, x );\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns incomplete beta integral of the arguments, evaluated\n     * from zero to x.  The function is defined as\n     *\n     *                  x\n     *     -            -\n     *    | (a+b)      | |  a-1     b-1\n     *  -----------    |   t   (1-t)   dt.\n     *   -     -     | |\n     *  | (a) | (b)   -\n     *                 0\n     *\n     * The domain of definition is 0 <= x <= 1.  In this\n     * implementation a and b are restricted to positive values.\n     * The integral from x to 1 may be obtained by the symmetry\n     * relation\n     *\n     *    1 - betainc( a, b, x )  =  betainc( b, a, 1-x ).\n     *\n     * The integral is evaluated by a continued fraction expansion.\n     * If a < 1, the function calls itself recursively after a\n     * transformation to increase a to a+1.\n     *\n     * ACCURACY (float):\n     *\n     * Tested at random points (a,b,x) with a and b in the indicated\n     * interval and x between 0 and 1.\n     *\n     * arithmetic   domain     # trials      peak         rms\n     * Relative error:\n     *    IEEE       0,30       10000       3.7e-5      5.1e-6\n     *    IEEE       0,100      10000       1.7e-4      2.5e-5\n     * The useful domain for relative error is limited by underflow\n     * of the single precision exponential function.\n     * Absolute error:\n     *    IEEE       0,30      100000       2.2e-5      9.6e-7\n     *    IEEE       0,100      10000       6.5e-5      3.7e-6\n     *\n     * Larger errors may occur for extreme ratios of a and b.\n     *\n     * ACCURACY (double):\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0,5         10000       6.9e-15     4.5e-16\n     *    IEEE      0,85       250000       2.2e-13     1.7e-14\n     *    IEEE      0,1000      30000       5.3e-12     6.3e-13\n     *    IEEE      0,10000    250000       9.3e-11     7.1e-12\n     *    IEEE      0,100000    10000       8.7e-10     4.8e-11\n     * Outputs smaller than the IEEE gradual underflow threshold\n     * were excluded from these statistics.\n     *\n     * ERROR MESSAGES:\n     *   message         condition      value returned\n     * incbet domain      x<0, x>1          nan\n     * incbet underflow                     nan\n     */\n\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar, Scalar>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return Scalar(0);\n  }\n};\n\n/* Continued fraction expansion #1 for incomplete beta integral (small_branch = True)\n * Continued fraction expansion #2 for incomplete beta integral (small_branch = False)\n */\ntemplate <typename Scalar>\nstruct incbeta_cfe {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar run(Scalar a, Scalar b, Scalar x, bool small_branch) {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar, float>::value ||\n                         internal::is_same<Scalar, double>::value),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    const Scalar big = cephes_helper<Scalar>::big();\n    const Scalar machep = cephes_helper<Scalar>::machep();\n    const Scalar biginv = cephes_helper<Scalar>::biginv();\n\n    const Scalar zero = 0;\n    const Scalar one = 1;\n    const Scalar two = 2;\n\n    Scalar xk, pk, pkm1, pkm2, qk, qkm1, qkm2;\n    Scalar k1, k2, k3, k4, k5, k6, k7, k8, k26update;\n    Scalar ans;\n    int n;\n\n    const int num_iters = (internal::is_same<Scalar, float>::value) ? 100 : 300;\n    const Scalar thresh =\n        (internal::is_same<Scalar, float>::value) ? machep : Scalar(3) * machep;\n    Scalar r = (internal::is_same<Scalar, float>::value) ? zero : one;\n\n    if (small_branch) {\n      k1 = a;\n      k2 = a + b;\n      k3 = a;\n      k4 = a + one;\n      k5 = one;\n      k6 = b - one;\n      k7 = k4;\n      k8 = a + two;\n      k26update = one;\n    } else {\n      k1 = a;\n      k2 = b - one;\n      k3 = a;\n      k4 = a + one;\n      k5 = one;\n      k6 = a + b;\n      k7 = a + one;\n      k8 = a + two;\n      k26update = -one;\n      x = x / (one - x);\n    }\n\n    pkm2 = zero;\n    qkm2 = one;\n    pkm1 = one;\n    qkm1 = one;\n    ans = one;\n    n = 0;\n\n    do {\n      xk = -(x * k1 * k2) / (k3 * k4);\n      pk = pkm1 + pkm2 * xk;\n      qk = qkm1 + qkm2 * xk;\n      pkm2 = pkm1;\n      pkm1 = pk;\n      qkm2 = qkm1;\n      qkm1 = qk;\n\n      xk = (x * k5 * k6) / (k7 * k8);\n      pk = pkm1 + pkm2 * xk;\n      qk = qkm1 + qkm2 * xk;\n      pkm2 = pkm1;\n      pkm1 = pk;\n      qkm2 = qkm1;\n      qkm1 = qk;\n\n      if (qk != zero) {\n        r = pk / qk;\n        if (numext::abs(ans - r) < numext::abs(r) * thresh) {\n          return r;\n        }\n        ans = r;\n      }\n\n      k1 += one;\n      k2 += k26update;\n      k3 += two;\n      k4 += two;\n      k5 += one;\n      k6 -= k26update;\n      k7 += two;\n      k8 += two;\n\n      if ((numext::abs(qk) + numext::abs(pk)) > big) {\n        pkm2 *= biginv;\n        pkm1 *= biginv;\n        qkm2 *= biginv;\n        qkm1 *= biginv;\n      }\n      if ((numext::abs(qk) < biginv) || (numext::abs(pk) < biginv)) {\n        pkm2 *= big;\n        pkm1 *= big;\n        qkm2 *= big;\n        qkm1 *= big;\n      }\n    } while (++n < num_iters);\n\n    return ans;\n  }\n};\n\n/* Helper functions depending on the Scalar type */\ntemplate <typename Scalar>\nstruct betainc_helper {};\n\ntemplate <>\nstruct betainc_helper<float> {\n  /* Core implementation, assumes a large (> 1.0) */\n  EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE float incbsa(float aa, float bb,\n                                                            float xx) {\n    float ans, a, b, t, x, onemx;\n    bool reversed_a_b = false;\n\n    onemx = 1.0f - xx;\n\n    /* see if x is greater than the mean */\n    if (xx > (aa / (aa + bb))) {\n      reversed_a_b = true;\n      a = bb;\n      b = aa;\n      t = xx;\n      x = onemx;\n    } else {\n      a = aa;\n      b = bb;\n      t = onemx;\n      x = xx;\n    }\n\n    /* Choose expansion for optimal convergence */\n    if (b > 10.0f) {\n      if (numext::abs(b * x / a) < 0.3f) {\n        t = betainc_helper<float>::incbps(a, b, x);\n        if (reversed_a_b) t = 1.0f - t;\n        return t;\n      }\n    }\n\n    ans = x * (a + b - 2.0f) / (a - 1.0f);\n    if (ans < 1.0f) {\n      ans = incbeta_cfe<float>::run(a, b, x, true /* small_branch */);\n      t = b * numext::log(t);\n    } else {\n      ans = incbeta_cfe<float>::run(a, b, x, false /* small_branch */);\n      t = (b - 1.0f) * numext::log(t);\n    }\n\n    t += a * numext::log(x) + lgamma_impl<float>::run(a + b) -\n         lgamma_impl<float>::run(a) - lgamma_impl<float>::run(b);\n    t += numext::log(ans / a);\n    t = numext::exp(t);\n\n    if (reversed_a_b) t = 1.0f - t;\n    return t;\n  }\n\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE float incbps(float a, float b, float x) {\n    float t, u, y, s;\n    const float machep = cephes_helper<float>::machep();\n\n    y = a * numext::log(x) + (b - 1.0f) * numext::log1p(-x) - numext::log(a);\n    y -= lgamma_impl<float>::run(a) + lgamma_impl<float>::run(b);\n    y += lgamma_impl<float>::run(a + b);\n\n    t = x / (1.0f - x);\n    s = 0.0f;\n    u = 1.0f;\n    do {\n      b -= 1.0f;\n      if (b == 0.0f) {\n        break;\n      }\n      a += 1.0f;\n      u *= t * b / a;\n      s += u;\n    } while (numext::abs(u) > machep);\n\n    return numext::exp(y) * (1.0f + s);\n  }\n};\n\ntemplate <>\nstruct betainc_impl<float> {\n  EIGEN_DEVICE_FUNC\n  static float run(float a, float b, float x) {\n    const float nan = NumTraits<float>::quiet_NaN();\n    float ans, t;\n\n    if (a <= 0.0f) return nan;\n    if (b <= 0.0f) return nan;\n    if ((x <= 0.0f) || (x >= 1.0f)) {\n      if (x == 0.0f) return 0.0f;\n      if (x == 1.0f) return 1.0f;\n      // mtherr(\"betaincf\", DOMAIN);\n      return nan;\n    }\n\n    /* transformation for small aa */\n    if (a <= 1.0f) {\n      ans = betainc_helper<float>::incbsa(a + 1.0f, b, x);\n      t = a * numext::log(x) + b * numext::log1p(-x) +\n          lgamma_impl<float>::run(a + b) - lgamma_impl<float>::run(a + 1.0f) -\n          lgamma_impl<float>::run(b);\n      return (ans + numext::exp(t));\n    } else {\n      return betainc_helper<float>::incbsa(a, b, x);\n    }\n  }\n};\n\ntemplate <>\nstruct betainc_helper<double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE double incbps(double a, double b, double x) {\n    const double machep = cephes_helper<double>::machep();\n\n    double s, t, u, v, n, t1, z, ai;\n\n    ai = 1.0 / a;\n    u = (1.0 - b) * x;\n    v = u / (a + 1.0);\n    t1 = v;\n    t = u;\n    n = 2.0;\n    s = 0.0;\n    z = machep * ai;\n    while (numext::abs(v) > z) {\n      u = (n - b) * x / n;\n      t *= u;\n      v = t / (a + n);\n      s += v;\n      n += 1.0;\n    }\n    s += t1;\n    s += ai;\n\n    u = a * numext::log(x);\n    // TODO: gamma() is not directly implemented in Eigen.\n    /*\n    if ((a + b) < maxgam && numext::abs(u) < maxlog) {\n      t = gamma(a + b) / (gamma(a) * gamma(b));\n      s = s * t * pow(x, a);\n    }\n    */\n    t = lgamma_impl<double>::run(a + b) - lgamma_impl<double>::run(a) -\n        lgamma_impl<double>::run(b) + u + numext::log(s);\n    return s = numext::exp(t);\n  }\n};\n\ntemplate <>\nstruct betainc_impl<double> {\n  EIGEN_DEVICE_FUNC\n  static double run(double aa, double bb, double xx) {\n    const double nan = NumTraits<double>::quiet_NaN();\n    const double machep = cephes_helper<double>::machep();\n    // const double maxgam = 171.624376956302725;\n\n    double a, b, t, x, xc, w, y;\n    bool reversed_a_b = false;\n\n    if (aa <= 0.0 || bb <= 0.0) {\n      return nan;  // goto domerr;\n    }\n\n    if ((xx <= 0.0) || (xx >= 1.0)) {\n      if (xx == 0.0) return (0.0);\n      if (xx == 1.0) return (1.0);\n      // mtherr(\"incbet\", DOMAIN);\n      return nan;\n    }\n\n    if ((bb * xx) <= 1.0 && xx <= 0.95) {\n      return betainc_helper<double>::incbps(aa, bb, xx);\n    }\n\n    w = 1.0 - xx;\n\n    /* Reverse a and b if x is greater than the mean. */\n    if (xx > (aa / (aa + bb))) {\n      reversed_a_b = true;\n      a = bb;\n      b = aa;\n      xc = xx;\n      x = w;\n    } else {\n      a = aa;\n      b = bb;\n      xc = w;\n      x = xx;\n    }\n\n    if (reversed_a_b && (b * x) <= 1.0 && x <= 0.95) {\n      t = betainc_helper<double>::incbps(a, b, x);\n      if (t <= machep) {\n        t = 1.0 - machep;\n      } else {\n        t = 1.0 - t;\n      }\n      return t;\n    }\n\n    /* Choose expansion for better convergence. */\n    y = x * (a + b - 2.0) - (a - 1.0);\n    if (y < 0.0) {\n      w = incbeta_cfe<double>::run(a, b, x, true /* small_branch */);\n    } else {\n      w = incbeta_cfe<double>::run(a, b, x, false /* small_branch */) / xc;\n    }\n\n    /* Multiply w by the factor\n         a      b   _             _     _\n        x  (1-x)   | (a+b) / ( a | (a) | (b) ) .   */\n\n    y = a * numext::log(x);\n    t = b * numext::log(xc);\n    // TODO: gamma is not directly implemented in Eigen.\n    /*\n    if ((a + b) < maxgam && numext::abs(y) < maxlog && numext::abs(t) < maxlog)\n    {\n      t = pow(xc, b);\n      t *= pow(x, a);\n      t /= a;\n      t *= w;\n      t *= gamma(a + b) / (gamma(a) * gamma(b));\n    } else {\n    */\n    /* Resort to logarithms.  */\n    y += t + lgamma_impl<double>::run(a + b) - lgamma_impl<double>::run(a) -\n         lgamma_impl<double>::run(b);\n    y += numext::log(w / a);\n    t = numext::exp(y);\n\n    /* } */\n    // done:\n\n    if (reversed_a_b) {\n      if (t <= machep) {\n        t = 1.0 - machep;\n      } else {\n        t = 1.0 - t;\n      }\n    }\n    return t;\n  }\n};\n\n#endif  // EIGEN_HAS_C99_MATH\n\n}  // end namespace internal\n\nnamespace numext {\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(lgamma, Scalar)\n    lgamma(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(lgamma, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(digamma, Scalar)\n    digamma(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(digamma, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(zeta, Scalar)\nzeta(const Scalar& x, const Scalar& q) {\n    return EIGEN_MATHFUNC_IMPL(zeta, Scalar)::run(x, q);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(polygamma, Scalar)\npolygamma(const Scalar& n, const Scalar& x) {\n    return EIGEN_MATHFUNC_IMPL(polygamma, Scalar)::run(n, x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(erf, Scalar)\n    erf(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(erf, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(erfc, Scalar)\n    erfc(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(erfc, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(ndtri, Scalar)\n    ndtri(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(ndtri, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(igamma, Scalar)\n    igamma(const Scalar& a, const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(igamma, Scalar)::run(a, x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(igamma_der_a, Scalar)\n    igamma_der_a(const Scalar& a, const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(igamma_der_a, Scalar)::run(a, x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(gamma_sample_der_alpha, Scalar)\n    gamma_sample_der_alpha(const Scalar& a, const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(gamma_sample_der_alpha, Scalar)::run(a, x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(igammac, Scalar)\n    igammac(const Scalar& a, const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(igammac, Scalar)::run(a, x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(betainc, Scalar)\n    betainc(const Scalar& a, const Scalar& b, const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(betainc, Scalar)::run(a, b, x);\n}\n\n}  // end namespace numext\n}  // end namespace Eigen\n\n#endif  // EIGEN_SPECIAL_FUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsPacketMath.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPECIALFUNCTIONS_PACKETMATH_H\n#define EIGEN_SPECIALFUNCTIONS_PACKETMATH_H\n\nnamespace Eigen {\n\nnamespace internal {\n\n/** \\internal \\returns the ln(|gamma(\\a a)|) (coeff-wise) */\ntemplate<typename Packet> EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket plgamma(const Packet& a) { using numext::lgamma; return lgamma(a); }\n\n/** \\internal \\returns the derivative of lgamma, psi(\\a a) (coeff-wise) */\ntemplate<typename Packet> EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pdigamma(const Packet& a) { using numext::digamma; return digamma(a); }\n\n/** \\internal \\returns the zeta function of two arguments (coeff-wise) */\ntemplate<typename Packet> EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pzeta(const Packet& x, const Packet& q) { using numext::zeta; return zeta(x, q); }\n\n/** \\internal \\returns the polygamma function (coeff-wise) */\ntemplate<typename Packet> EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket ppolygamma(const Packet& n, const Packet& x) { using numext::polygamma; return polygamma(n, x); }\n\n/** \\internal \\returns the erf(\\a a) (coeff-wise) */\ntemplate<typename Packet> EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket perf(const Packet& a) { using numext::erf; return erf(a); }\n\n/** \\internal \\returns the erfc(\\a a) (coeff-wise) */\ntemplate<typename Packet> EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket perfc(const Packet& a) { using numext::erfc; return erfc(a); }\n\n/** \\internal \\returns the ndtri(\\a a) (coeff-wise) */\ntemplate<typename Packet> EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pndtri(const Packet& a) {\n  typedef typename unpacket_traits<Packet>::type ScalarType;\n  using internal::generic_ndtri; return generic_ndtri<Packet, ScalarType>(a);\n}\n\n/** \\internal \\returns the incomplete gamma function igamma(\\a a, \\a x) */\ntemplate<typename Packet> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nPacket pigamma(const Packet& a, const Packet& x) { using numext::igamma; return igamma(a, x); }\n\n/** \\internal \\returns the derivative of the incomplete gamma function\n * igamma_der_a(\\a a, \\a x) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet pigamma_der_a(const Packet& a, const Packet& x) {\n  using numext::igamma_der_a; return igamma_der_a(a, x);\n}\n\n/** \\internal \\returns compute the derivative of the sample\n  * of Gamma(alpha, 1) random variable with respect to the parameter a\n  * gamma_sample_der_alpha(\\a alpha, \\a sample) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet pgamma_sample_der_alpha(const Packet& alpha, const Packet& sample) {\n  using numext::gamma_sample_der_alpha; return gamma_sample_der_alpha(alpha, sample);\n}\n\n/** \\internal \\returns the complementary incomplete gamma function igammac(\\a a, \\a x) */\ntemplate<typename Packet> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nPacket pigammac(const Packet& a, const Packet& x) { using numext::igammac; return igammac(a, x); }\n\n/** \\internal \\returns the complementary incomplete gamma function betainc(\\a a, \\a b, \\a x) */\ntemplate<typename Packet> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nPacket pbetainc(const Packet& a, const Packet& b,const Packet& x) { using numext::betainc; return betainc(a, b, x); }\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPECIALFUNCTIONS_PACKETMATH_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SpecialFunctions/arch/AVX/BesselFunctions.h",
    "content": "#ifndef EIGEN_AVX_BESSELFUNCTIONS_H\n#define EIGEN_AVX_BESSELFUNCTIONS_H\n\nnamespace Eigen {\nnamespace internal {\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_i0)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_i0)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_i0e)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_i0e)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_i1)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_i1)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_i1e)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_i1e)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_j0)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_j0)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_j1)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_j1)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_k0)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_k0)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_k0e)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_k0e)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_k1)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_k1)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_k1e)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_k1e)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_y0)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_y0)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_y1)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_y1)\n\n}  // namespace internal\n}  // namespace Eigen\n\n#endif  // EIGEN_AVX_BESSELFUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SpecialFunctions/arch/AVX/SpecialFunctions.h",
    "content": "#ifndef EIGEN_AVX_SPECIALFUNCTIONS_H\n#define EIGEN_AVX_SPECIALFUNCTIONS_H\n\nnamespace Eigen {\nnamespace internal {\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, perf)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, perf)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pndtri)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pndtri)\n\n}  // namespace internal\n}  // namespace Eigen\n\n#endif  // EIGEN_AVX_SPECIAL_FUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SpecialFunctions/arch/AVX512/BesselFunctions.h",
    "content": "#ifndef EIGEN_AVX512_BESSELFUNCTIONS_H\n#define EIGEN_AVX512_BESSELFUNCTIONS_H\n\nnamespace Eigen {\nnamespace internal {\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_i0)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_i0)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_i0e)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_i0e)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_i1)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_i1)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_i1e)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_i1e)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_j0)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_j0)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_j1)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_j1)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_k0)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_k0)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_k0e)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_k0e)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_k1)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_k1)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_k1e)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_k1e)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_y0)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_y0)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_y1)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_y1)\n\n}  // namespace internal\n}  // namespace Eigen\n\n#endif  // EIGEN_AVX512_BESSELFUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SpecialFunctions/arch/AVX512/SpecialFunctions.h",
    "content": "#ifndef EIGEN_AVX512_SPECIALFUNCTIONS_H\n#define EIGEN_AVX512_SPECIALFUNCTIONS_H\n\nnamespace Eigen {\nnamespace internal {\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, perf)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, perf)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pndtri)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pndtri)\n\n}  // namespace internal\n}  // namespace Eigen\n\n#endif  // EIGEN_AVX512_SPECIAL_FUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SpecialFunctions/arch/GPU/SpecialFunctions.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_GPU_SPECIALFUNCTIONS_H\n#define EIGEN_GPU_SPECIALFUNCTIONS_H\n\nnamespace Eigen {\n\nnamespace internal {\n\n// Make sure this is only available when targeting a GPU: we don't want to\n// introduce conflicts between these packet_traits definitions and the ones\n// we'll use on the host side (SSE, AVX, ...)\n#if defined(EIGEN_GPUCC) && defined(EIGEN_USE_GPU)\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat4 plgamma<float4>(const float4& a)\n{\n  return make_float4(lgammaf(a.x), lgammaf(a.y), lgammaf(a.z), lgammaf(a.w));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble2 plgamma<double2>(const double2& a)\n{\n  using numext::lgamma;\n  return make_double2(lgamma(a.x), lgamma(a.y));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat4 pdigamma<float4>(const float4& a)\n{\n  using numext::digamma;\n  return make_float4(digamma(a.x), digamma(a.y), digamma(a.z), digamma(a.w));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble2 pdigamma<double2>(const double2& a)\n{\n  using numext::digamma;\n  return make_double2(digamma(a.x), digamma(a.y));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat4 pzeta<float4>(const float4& x, const float4& q)\n{\n    using numext::zeta;\n    return make_float4(zeta(x.x, q.x), zeta(x.y, q.y), zeta(x.z, q.z), zeta(x.w, q.w));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble2 pzeta<double2>(const double2& x, const double2& q)\n{\n    using numext::zeta;\n    return make_double2(zeta(x.x, q.x), zeta(x.y, q.y));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat4 ppolygamma<float4>(const float4& n, const float4& x)\n{\n    using numext::polygamma;\n    return make_float4(polygamma(n.x, x.x), polygamma(n.y, x.y), polygamma(n.z, x.z), polygamma(n.w, x.w));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble2 ppolygamma<double2>(const double2& n, const double2& x)\n{\n    using numext::polygamma;\n    return make_double2(polygamma(n.x, x.x), polygamma(n.y, x.y));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat4 perf<float4>(const float4& a)\n{\n  return make_float4(erff(a.x), erff(a.y), erff(a.z), erff(a.w));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble2 perf<double2>(const double2& a)\n{\n  using numext::erf;\n  return make_double2(erf(a.x), erf(a.y));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat4 perfc<float4>(const float4& a)\n{\n  using numext::erfc;\n  return make_float4(erfc(a.x), erfc(a.y), erfc(a.z), erfc(a.w));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble2 perfc<double2>(const double2& a)\n{\n  using numext::erfc;\n  return make_double2(erfc(a.x), erfc(a.y));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat4 pndtri<float4>(const float4& a)\n{\n  using numext::ndtri;\n  return make_float4(ndtri(a.x), ndtri(a.y), ndtri(a.z), ndtri(a.w));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble2 pndtri<double2>(const double2& a)\n{\n  using numext::ndtri;\n  return make_double2(ndtri(a.x), ndtri(a.y));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat4 pigamma<float4>(const float4& a, const float4& x)\n{\n  using numext::igamma;\n  return make_float4(\n      igamma(a.x, x.x),\n      igamma(a.y, x.y),\n      igamma(a.z, x.z),\n      igamma(a.w, x.w));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble2 pigamma<double2>(const double2& a, const double2& x)\n{\n  using numext::igamma;\n  return make_double2(igamma(a.x, x.x), igamma(a.y, x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pigamma_der_a<float4>(\n    const float4& a, const float4& x) {\n  using numext::igamma_der_a;\n  return make_float4(igamma_der_a(a.x, x.x), igamma_der_a(a.y, x.y),\n                     igamma_der_a(a.z, x.z), igamma_der_a(a.w, x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npigamma_der_a<double2>(const double2& a, const double2& x) {\n  using numext::igamma_der_a;\n  return make_double2(igamma_der_a(a.x, x.x), igamma_der_a(a.y, x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pgamma_sample_der_alpha<float4>(\n    const float4& alpha, const float4& sample) {\n  using numext::gamma_sample_der_alpha;\n  return make_float4(\n      gamma_sample_der_alpha(alpha.x, sample.x),\n      gamma_sample_der_alpha(alpha.y, sample.y),\n      gamma_sample_der_alpha(alpha.z, sample.z),\n      gamma_sample_der_alpha(alpha.w, sample.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npgamma_sample_der_alpha<double2>(const double2& alpha, const double2& sample) {\n  using numext::gamma_sample_der_alpha;\n  return make_double2(\n      gamma_sample_der_alpha(alpha.x, sample.x),\n      gamma_sample_der_alpha(alpha.y, sample.y));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat4 pigammac<float4>(const float4& a, const float4& x)\n{\n  using numext::igammac;\n  return make_float4(\n      igammac(a.x, x.x),\n      igammac(a.y, x.y),\n      igammac(a.z, x.z),\n      igammac(a.w, x.w));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble2 pigammac<double2>(const double2& a, const double2& x)\n{\n  using numext::igammac;\n  return make_double2(igammac(a.x, x.x), igammac(a.y, x.y));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat4 pbetainc<float4>(const float4& a, const float4& b, const float4& x)\n{\n  using numext::betainc;\n  return make_float4(\n      betainc(a.x, b.x, x.x),\n      betainc(a.y, b.y, x.y),\n      betainc(a.z, b.z, x.z),\n      betainc(a.w, b.w, x.w));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble2 pbetainc<double2>(const double2& a, const double2& b, const double2& x)\n{\n  using numext::betainc;\n  return make_double2(betainc(a.x, b.x, x.x), betainc(a.y, b.y, x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_i0e<float4>(const float4& x) {\n  using numext::bessel_i0e;\n  return make_float4(bessel_i0e(x.x), bessel_i0e(x.y), bessel_i0e(x.z), bessel_i0e(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_i0e<double2>(const double2& x) {\n  using numext::bessel_i0e;\n  return make_double2(bessel_i0e(x.x), bessel_i0e(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_i0<float4>(const float4& x) {\n  using numext::bessel_i0;\n  return make_float4(bessel_i0(x.x), bessel_i0(x.y), bessel_i0(x.z), bessel_i0(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_i0<double2>(const double2& x) {\n  using numext::bessel_i0;\n  return make_double2(bessel_i0(x.x), bessel_i0(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_i1e<float4>(const float4& x) {\n  using numext::bessel_i1e;\n  return make_float4(bessel_i1e(x.x), bessel_i1e(x.y), bessel_i1e(x.z), bessel_i1e(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_i1e<double2>(const double2& x) {\n  using numext::bessel_i1e;\n  return make_double2(bessel_i1e(x.x), bessel_i1e(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_i1<float4>(const float4& x) {\n  using numext::bessel_i1;\n  return make_float4(bessel_i1(x.x), bessel_i1(x.y), bessel_i1(x.z), bessel_i1(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_i1<double2>(const double2& x) {\n  using numext::bessel_i1;\n  return make_double2(bessel_i1(x.x), bessel_i1(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_k0e<float4>(const float4& x) {\n  using numext::bessel_k0e;\n  return make_float4(bessel_k0e(x.x), bessel_k0e(x.y), bessel_k0e(x.z), bessel_k0e(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_k0e<double2>(const double2& x) {\n  using numext::bessel_k0e;\n  return make_double2(bessel_k0e(x.x), bessel_k0e(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_k0<float4>(const float4& x) {\n  using numext::bessel_k0;\n  return make_float4(bessel_k0(x.x), bessel_k0(x.y), bessel_k0(x.z), bessel_k0(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_k0<double2>(const double2& x) {\n  using numext::bessel_k0;\n  return make_double2(bessel_k0(x.x), bessel_k0(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_k1e<float4>(const float4& x) {\n  using numext::bessel_k1e;\n  return make_float4(bessel_k1e(x.x), bessel_k1e(x.y), bessel_k1e(x.z), bessel_k1e(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_k1e<double2>(const double2& x) {\n  using numext::bessel_k1e;\n  return make_double2(bessel_k1e(x.x), bessel_k1e(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_k1<float4>(const float4& x) {\n  using numext::bessel_k1;\n  return make_float4(bessel_k1(x.x), bessel_k1(x.y), bessel_k1(x.z), bessel_k1(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_k1<double2>(const double2& x) {\n  using numext::bessel_k1;\n  return make_double2(bessel_k1(x.x), bessel_k1(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_j0<float4>(const float4& x) {\n  using numext::bessel_j0;\n  return make_float4(bessel_j0(x.x), bessel_j0(x.y), bessel_j0(x.z), bessel_j0(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_j0<double2>(const double2& x) {\n  using numext::bessel_j0;\n  return make_double2(bessel_j0(x.x), bessel_j0(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_j1<float4>(const float4& x) {\n  using numext::bessel_j1;\n  return make_float4(bessel_j1(x.x), bessel_j1(x.y), bessel_j1(x.z), bessel_j1(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_j1<double2>(const double2& x) {\n  using numext::bessel_j1;\n  return make_double2(bessel_j1(x.x), bessel_j1(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_y0<float4>(const float4& x) {\n  using numext::bessel_y0;\n  return make_float4(bessel_y0(x.x), bessel_y0(x.y), bessel_y0(x.z), bessel_y0(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_y0<double2>(const double2& x) {\n  using numext::bessel_y0;\n  return make_double2(bessel_y0(x.x), bessel_y0(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_y1<float4>(const float4& x) {\n  using numext::bessel_y1;\n  return make_float4(bessel_y1(x.x), bessel_y1(x.y), bessel_y1(x.z), bessel_y1(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_y1<double2>(const double2& x) {\n  using numext::bessel_y1;\n  return make_double2(bessel_y1(x.x), bessel_y1(x.y));\n}\n\n#endif\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_GPU_SPECIALFUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SpecialFunctions/arch/NEON/BesselFunctions.h",
    "content": "#ifndef EIGEN_NEON_BESSELFUNCTIONS_H\n#define EIGEN_NEON_BESSELFUNCTIONS_H\n\nnamespace Eigen {\nnamespace internal {\n\n#if EIGEN_HAS_ARM64_FP16_VECTOR_ARITHMETIC\n\n#define NEON_HALF_TO_FLOAT_FUNCTIONS(METHOD)                            \\\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE                       \\\nPacket8hf METHOD<Packet8hf>(const Packet8hf& x) {                       \\\n  const Packet4f lo = METHOD<Packet4f>(vcvt_f32_f16(vget_low_f16(x)));  \\\n  const Packet4f hi = METHOD<Packet4f>(vcvt_f32_f16(vget_high_f16(x))); \\\n  return vcombine_f16(vcvt_f16_f32(lo), vcvt_f16_f32(hi));              \\\n}                                                                       \\\n                                                                        \\\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE                       \\\nPacket4hf METHOD<Packet4hf>(const Packet4hf& x) {                       \\\n  return vcvt_f16_f32(METHOD<Packet4f>(vcvt_f32_f16(x)));               \\\n}\n\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_i0)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_i0e)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_i1)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_i1e)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_j0)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_j1)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_k0)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_k0e)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_k1)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_k1e)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_y0)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_y1)\n\n#undef NEON_HALF_TO_FLOAT_FUNCTIONS\n#endif\n\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_i0)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_i0e)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_i1)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_i1e)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_j0)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_j1)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_k0)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_k0e)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_k1)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_k1e)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_y0)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_y1)\n\n}  // namespace internal\n}  // namespace Eigen\n\n#endif  // EIGEN_NEON_BESSELFUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/SpecialFunctions/arch/NEON/SpecialFunctions.h",
    "content": "#ifndef EIGEN_NEON_SPECIALFUNCTIONS_H\n#define EIGEN_NEON_SPECIALFUNCTIONS_H\n\nnamespace Eigen {\nnamespace internal {\n\n#if EIGEN_HAS_ARM64_FP16_VECTOR_ARITHMETIC\n\n#define NEON_HALF_TO_FLOAT_FUNCTIONS(METHOD)                            \\\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE                       \\\nPacket8hf METHOD<Packet8hf>(const Packet8hf& x) {                       \\\n  const Packet4f lo = METHOD<Packet4f>(vcvt_f32_f16(vget_low_f16(x)));  \\\n  const Packet4f hi = METHOD<Packet4f>(vcvt_f32_f16(vget_high_f16(x))); \\\n  return vcombine_f16(vcvt_f16_f32(lo), vcvt_f16_f32(hi));              \\\n}                                                                       \\\n                                                                        \\\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE                       \\\nPacket4hf METHOD<Packet4hf>(const Packet4hf& x) {                       \\\n  return vcvt_f16_f32(METHOD<Packet4f>(vcvt_f32_f16(x)));               \\\n}\n\nNEON_HALF_TO_FLOAT_FUNCTIONS(perf)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pndtri)\n\n#undef NEON_HALF_TO_FLOAT_FUNCTIONS\n#endif\n\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, perf)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pndtri)\n\n}  // namespace internal\n}  // namespace Eigen\n\n#endif  // EIGEN_NEON_SPECIALFUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/Splines/Spline.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 20010-2011 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPLINE_H\n#define EIGEN_SPLINE_H\n\n#include \"SplineFwd.h\"\n\nnamespace Eigen\n{\n    /**\n     * \\ingroup Splines_Module\n     * \\class Spline\n     * \\brief A class representing multi-dimensional spline curves.\n     *\n     * The class represents B-splines with non-uniform knot vectors. Each control\n     * point of the B-spline is associated with a basis function\n     * \\f{align*}\n     *   C(u) & = \\sum_{i=0}^{n}N_{i,p}(u)P_i\n     * \\f}\n     *\n     * \\tparam Scalar_ The underlying data type (typically float or double)\n     * \\tparam Dim_ The curve dimension (e.g. 2 or 3)\n     * \\tparam _Degree Per default set to Dynamic; could be set to the actual desired\n     *                degree for optimization purposes (would result in stack allocation\n     *                of several temporary variables).\n     **/\n  template <typename Scalar_, int Dim_, int _Degree>\n  class Spline\n  {\n  public:\n    typedef Scalar_ Scalar; /*!< The spline curve's scalar type. */\n    enum { Dimension = Dim_ /*!< The spline curve's dimension. */ };\n    enum { Degree = _Degree /*!< The spline curve's degree. */ };\n\n    /** \\brief The point type the spline is representing. */\n    typedef typename SplineTraits<Spline>::PointType PointType;\n    \n    /** \\brief The data type used to store knot vectors. */\n    typedef typename SplineTraits<Spline>::KnotVectorType KnotVectorType;\n\n    /** \\brief The data type used to store parameter vectors. */\n    typedef typename SplineTraits<Spline>::ParameterVectorType ParameterVectorType;\n    \n    /** \\brief The data type used to store non-zero basis functions. */\n    typedef typename SplineTraits<Spline>::BasisVectorType BasisVectorType;\n\n    /** \\brief The data type used to store the values of the basis function derivatives. */\n    typedef typename SplineTraits<Spline>::BasisDerivativeType BasisDerivativeType;\n    \n    /** \\brief The data type representing the spline's control points. */\n    typedef typename SplineTraits<Spline>::ControlPointVectorType ControlPointVectorType;\n    \n    /**\n    * \\brief Creates a (constant) zero spline.\n    * For Splines with dynamic degree, the resulting degree will be 0.\n    **/\n    Spline() \n    : m_knots(1, (Degree==Dynamic ? 2 : 2*Degree+2))\n    , m_ctrls(ControlPointVectorType::Zero(Dimension,(Degree==Dynamic ? 1 : Degree+1))) \n    {\n      // in theory this code can go to the initializer list but it will get pretty\n      // much unreadable ...\n      enum { MinDegree = (Degree==Dynamic ? 0 : Degree) };\n      m_knots.template segment<MinDegree+1>(0) = Array<Scalar,1,MinDegree+1>::Zero();\n      m_knots.template segment<MinDegree+1>(MinDegree+1) = Array<Scalar,1,MinDegree+1>::Ones();\n    }\n\n    /**\n    * \\brief Creates a spline from a knot vector and control points.\n    * \\param knots The spline's knot vector.\n    * \\param ctrls The spline's control point vector.\n    **/\n    template <typename OtherVectorType, typename OtherArrayType>\n    Spline(const OtherVectorType& knots, const OtherArrayType& ctrls) : m_knots(knots), m_ctrls(ctrls) {}\n\n    /**\n    * \\brief Copy constructor for splines.\n    * \\param spline The input spline.\n    **/\n    template <int OtherDegree>\n    Spline(const Spline<Scalar, Dimension, OtherDegree>& spline) : \n    m_knots(spline.knots()), m_ctrls(spline.ctrls()) {}\n\n    /**\n     * \\brief Returns the knots of the underlying spline.\n     **/\n    const KnotVectorType& knots() const { return m_knots; }\n    \n    /**\n     * \\brief Returns the ctrls of the underlying spline.\n     **/    \n    const ControlPointVectorType& ctrls() const { return m_ctrls; }\n\n    /**\n     * \\brief Returns the spline value at a given site \\f$u\\f$.\n     *\n     * The function returns\n     * \\f{align*}\n     *   C(u) & = \\sum_{i=0}^{n}N_{i,p}P_i\n     * \\f}\n     *\n     * \\param u Parameter \\f$u \\in [0;1]\\f$ at which the spline is evaluated.\n     * \\return The spline value at the given location \\f$u\\f$.\n     **/\n    PointType operator()(Scalar u) const;\n\n    /**\n     * \\brief Evaluation of spline derivatives of up-to given order.\n     *\n     * The function returns\n     * \\f{align*}\n     *   \\frac{d^i}{du^i}C(u) & = \\sum_{i=0}^{n} \\frac{d^i}{du^i} N_{i,p}(u)P_i\n     * \\f}\n     * for i ranging between 0 and order.\n     *\n     * \\param u Parameter \\f$u \\in [0;1]\\f$ at which the spline derivative is evaluated.\n     * \\param order The order up to which the derivatives are computed.\n     **/\n    typename SplineTraits<Spline>::DerivativeType\n      derivatives(Scalar u, DenseIndex order) const;\n\n    /**\n     * \\copydoc Spline::derivatives\n     * Using the template version of this function is more efficieent since\n     * temporary objects are allocated on the stack whenever this is possible.\n     **/    \n    template <int DerivativeOrder>\n    typename SplineTraits<Spline,DerivativeOrder>::DerivativeType\n      derivatives(Scalar u, DenseIndex order = DerivativeOrder) const;\n\n    /**\n     * \\brief Computes the non-zero basis functions at the given site.\n     *\n     * Splines have local support and a point from their image is defined\n     * by exactly \\f$p+1\\f$ control points \\f$P_i\\f$ where \\f$p\\f$ is the\n     * spline degree.\n     *\n     * This function computes the \\f$p+1\\f$ non-zero basis function values\n     * for a given parameter value \\f$u\\f$. It returns\n     * \\f{align*}{\n     *   N_{i,p}(u), \\hdots, N_{i+p+1,p}(u)\n     * \\f}\n     *\n     * \\param u Parameter \\f$u \\in [0;1]\\f$ at which the non-zero basis functions \n     *          are computed.\n     **/\n    typename SplineTraits<Spline>::BasisVectorType\n      basisFunctions(Scalar u) const;\n\n    /**\n     * \\brief Computes the non-zero spline basis function derivatives up to given order.\n     *\n     * The function computes\n     * \\f{align*}{\n     *   \\frac{d^i}{du^i} N_{i,p}(u), \\hdots, \\frac{d^i}{du^i} N_{i+p+1,p}(u)\n     * \\f}\n     * with i ranging from 0 up to the specified order.\n     *\n     * \\param u Parameter \\f$u \\in [0;1]\\f$ at which the non-zero basis function\n     *          derivatives are computed.\n     * \\param order The order up to which the basis function derivatives are computes.\n     **/\n    typename SplineTraits<Spline>::BasisDerivativeType\n      basisFunctionDerivatives(Scalar u, DenseIndex order) const;\n\n    /**\n     * \\copydoc Spline::basisFunctionDerivatives\n     * Using the template version of this function is more efficieent since\n     * temporary objects are allocated on the stack whenever this is possible.\n     **/    \n    template <int DerivativeOrder>\n    typename SplineTraits<Spline,DerivativeOrder>::BasisDerivativeType\n      basisFunctionDerivatives(Scalar u, DenseIndex order = DerivativeOrder) const;\n\n    /**\n     * \\brief Returns the spline degree.\n     **/ \n    DenseIndex degree() const;\n\n    /** \n     * \\brief Returns the span within the knot vector in which u is falling.\n     * \\param u The site for which the span is determined.\n     **/\n    DenseIndex span(Scalar u) const;\n\n    /**\n     * \\brief Computes the span within the provided knot vector in which u is falling.\n     **/\n    static DenseIndex Span(typename SplineTraits<Spline>::Scalar u, DenseIndex degree, const typename SplineTraits<Spline>::KnotVectorType& knots);\n    \n    /**\n     * \\brief Returns the spline's non-zero basis functions.\n     *\n     * The function computes and returns\n     * \\f{align*}{\n     *   N_{i,p}(u), \\hdots, N_{i+p+1,p}(u)\n     * \\f}\n     *\n     * \\param u The site at which the basis functions are computed.\n     * \\param degree The degree of the underlying spline.\n     * \\param knots The underlying spline's knot vector.\n     **/\n    static BasisVectorType BasisFunctions(Scalar u, DenseIndex degree, const KnotVectorType& knots);\n\n    /**\n     * \\copydoc Spline::basisFunctionDerivatives\n     * \\param degree The degree of the underlying spline\n     * \\param knots The underlying spline's knot vector.\n     **/    \n    static BasisDerivativeType BasisFunctionDerivatives(\n      const Scalar u, const DenseIndex order, const DenseIndex degree, const KnotVectorType& knots);\n\n  private:\n    KnotVectorType m_knots; /*!< Knot vector. */\n    ControlPointVectorType  m_ctrls; /*!< Control points. */\n\n    template <typename DerivativeType>\n    static void BasisFunctionDerivativesImpl(\n      const typename Spline<Scalar_, Dim_, _Degree>::Scalar u,\n      const DenseIndex order,\n      const DenseIndex p, \n      const typename Spline<Scalar_, Dim_, _Degree>::KnotVectorType& U,\n      DerivativeType& N_);\n  };\n\n  template <typename Scalar_, int Dim_, int _Degree>\n  DenseIndex Spline<Scalar_, Dim_, _Degree>::Span(\n    typename SplineTraits< Spline<Scalar_, Dim_, _Degree> >::Scalar u,\n    DenseIndex degree,\n    const typename SplineTraits< Spline<Scalar_, Dim_, _Degree> >::KnotVectorType& knots)\n  {\n    // Piegl & Tiller, \"The NURBS Book\", A2.1 (p. 68)\n    if (u <= knots(0)) return degree;\n    const Scalar* pos = std::upper_bound(knots.data()+degree-1, knots.data()+knots.size()-degree-1, u);\n    return static_cast<DenseIndex>( std::distance(knots.data(), pos) - 1 );\n  }\n\n  template <typename Scalar_, int Dim_, int _Degree>\n  typename Spline<Scalar_, Dim_, _Degree>::BasisVectorType\n    Spline<Scalar_, Dim_, _Degree>::BasisFunctions(\n    typename Spline<Scalar_, Dim_, _Degree>::Scalar u,\n    DenseIndex degree,\n    const typename Spline<Scalar_, Dim_, _Degree>::KnotVectorType& knots)\n  {\n    const DenseIndex p = degree;\n    const DenseIndex i = Spline::Span(u, degree, knots);\n\n    const KnotVectorType& U = knots;\n\n    BasisVectorType left(p+1); left(0) = Scalar(0);\n    BasisVectorType right(p+1); right(0) = Scalar(0);\n\n    VectorBlock<BasisVectorType,Degree>(left,1,p) = u - VectorBlock<const KnotVectorType,Degree>(U,i+1-p,p).reverse();\n    VectorBlock<BasisVectorType,Degree>(right,1,p) = VectorBlock<const KnotVectorType,Degree>(U,i+1,p) - u;\n\n    BasisVectorType N(1,p+1);\n    N(0) = Scalar(1);\n    for (DenseIndex j=1; j<=p; ++j)\n    {\n      Scalar saved = Scalar(0);\n      for (DenseIndex r=0; r<j; r++)\n      {\n        const Scalar tmp = N(r)/(right(r+1)+left(j-r));\n        N[r] = saved + right(r+1)*tmp;\n        saved = left(j-r)*tmp;\n      }\n      N(j) = saved;\n    }\n    return N;\n  }\n\n  template <typename Scalar_, int Dim_, int _Degree>\n  DenseIndex Spline<Scalar_, Dim_, _Degree>::degree() const\n  {\n    if (_Degree == Dynamic)\n      return m_knots.size() - m_ctrls.cols() - 1;\n    else\n      return _Degree;\n  }\n\n  template <typename Scalar_, int Dim_, int _Degree>\n  DenseIndex Spline<Scalar_, Dim_, _Degree>::span(Scalar u) const\n  {\n    return Spline::Span(u, degree(), knots());\n  }\n\n  template <typename Scalar_, int Dim_, int _Degree>\n  typename Spline<Scalar_, Dim_, _Degree>::PointType Spline<Scalar_, Dim_, _Degree>::operator()(Scalar u) const\n  {\n    enum { Order = SplineTraits<Spline>::OrderAtCompileTime };\n\n    const DenseIndex span = this->span(u);\n    const DenseIndex p = degree();\n    const BasisVectorType basis_funcs = basisFunctions(u);\n\n    const Replicate<BasisVectorType,Dimension,1> ctrl_weights(basis_funcs);\n    const Block<const ControlPointVectorType,Dimension,Order> ctrl_pts(ctrls(),0,span-p,Dimension,p+1);\n    return (ctrl_weights * ctrl_pts).rowwise().sum();\n  }\n\n  /* --------------------------------------------------------------------------------------------- */\n\n  template <typename SplineType, typename DerivativeType>\n  void derivativesImpl(const SplineType& spline, typename SplineType::Scalar u, DenseIndex order, DerivativeType& der)\n  {    \n    enum { Dimension = SplineTraits<SplineType>::Dimension };\n    enum { Order = SplineTraits<SplineType>::OrderAtCompileTime };\n    enum { DerivativeOrder = DerivativeType::ColsAtCompileTime };\n\n    typedef typename SplineTraits<SplineType>::ControlPointVectorType ControlPointVectorType;\n    typedef typename SplineTraits<SplineType,DerivativeOrder>::BasisDerivativeType BasisDerivativeType;\n    typedef typename BasisDerivativeType::ConstRowXpr BasisDerivativeRowXpr;    \n\n    const DenseIndex p = spline.degree();\n    const DenseIndex span = spline.span(u);\n\n    const DenseIndex n = (std::min)(p, order);\n\n    der.resize(Dimension,n+1);\n\n    // Retrieve the basis function derivatives up to the desired order...    \n    const BasisDerivativeType basis_func_ders = spline.template basisFunctionDerivatives<DerivativeOrder>(u, n+1);\n\n    // ... and perform the linear combinations of the control points.\n    for (DenseIndex der_order=0; der_order<n+1; ++der_order)\n    {\n      const Replicate<BasisDerivativeRowXpr,Dimension,1> ctrl_weights( basis_func_ders.row(der_order) );\n      const Block<const ControlPointVectorType,Dimension,Order> ctrl_pts(spline.ctrls(),0,span-p,Dimension,p+1);\n      der.col(der_order) = (ctrl_weights * ctrl_pts).rowwise().sum();\n    }\n  }\n\n  template <typename Scalar_, int Dim_, int _Degree>\n  typename SplineTraits< Spline<Scalar_, Dim_, _Degree> >::DerivativeType\n    Spline<Scalar_, Dim_, _Degree>::derivatives(Scalar u, DenseIndex order) const\n  {\n    typename SplineTraits< Spline >::DerivativeType res;\n    derivativesImpl(*this, u, order, res);\n    return res;\n  }\n\n  template <typename Scalar_, int Dim_, int _Degree>\n  template <int DerivativeOrder>\n  typename SplineTraits< Spline<Scalar_, Dim_, _Degree>, DerivativeOrder >::DerivativeType\n    Spline<Scalar_, Dim_, _Degree>::derivatives(Scalar u, DenseIndex order) const\n  {\n    typename SplineTraits< Spline, DerivativeOrder >::DerivativeType res;\n    derivativesImpl(*this, u, order, res);\n    return res;\n  }\n\n  template <typename Scalar_, int Dim_, int _Degree>\n  typename SplineTraits< Spline<Scalar_, Dim_, _Degree> >::BasisVectorType\n    Spline<Scalar_, Dim_, _Degree>::basisFunctions(Scalar u) const\n  {\n    return Spline::BasisFunctions(u, degree(), knots());\n  }\n\n  /* --------------------------------------------------------------------------------------------- */\n  \n  \n  template <typename Scalar_, int Dim_, int _Degree>\n  template <typename DerivativeType>\n  void Spline<Scalar_, Dim_, _Degree>::BasisFunctionDerivativesImpl(\n    const typename Spline<Scalar_, Dim_, _Degree>::Scalar u,\n    const DenseIndex order,\n    const DenseIndex p, \n    const typename Spline<Scalar_, Dim_, _Degree>::KnotVectorType& U,\n    DerivativeType& N_)\n  {\n    typedef Spline<Scalar_, Dim_, _Degree> SplineType;\n    enum { Order = SplineTraits<SplineType>::OrderAtCompileTime };\n\n    const DenseIndex span = SplineType::Span(u, p, U);\n\n    const DenseIndex n = (std::min)(p, order);\n\n    N_.resize(n+1, p+1);\n\n    BasisVectorType left = BasisVectorType::Zero(p+1);\n    BasisVectorType right = BasisVectorType::Zero(p+1);\n\n    Matrix<Scalar,Order,Order> ndu(p+1,p+1);\n\n    Scalar saved, temp; // FIXME These were double instead of Scalar. Was there a reason for that?\n\n    ndu(0,0) = 1.0;\n\n    DenseIndex j;\n    for (j=1; j<=p; ++j)\n    {\n      left[j] = u-U[span+1-j];\n      right[j] = U[span+j]-u;\n      saved = 0.0;\n\n      for (DenseIndex r=0; r<j; ++r)\n      {\n        /* Lower triangle */\n        ndu(j,r) = right[r+1]+left[j-r];\n        temp = ndu(r,j-1)/ndu(j,r);\n        /* Upper triangle */\n        ndu(r,j) = static_cast<Scalar>(saved+right[r+1] * temp);\n        saved = left[j-r] * temp;\n      }\n\n      ndu(j,j) = static_cast<Scalar>(saved);\n    }\n\n    for (j = p; j>=0; --j) \n      N_(0,j) = ndu(j,p);\n\n    // Compute the derivatives\n    DerivativeType a(n+1,p+1);\n    DenseIndex r=0;\n    for (; r<=p; ++r)\n    {\n      DenseIndex s1,s2;\n      s1 = 0; s2 = 1; // alternate rows in array a\n      a(0,0) = 1.0;\n\n      // Compute the k-th derivative\n      for (DenseIndex k=1; k<=static_cast<DenseIndex>(n); ++k)\n      {\n        Scalar d = 0.0;\n        DenseIndex rk,pk,j1,j2;\n        rk = r-k; pk = p-k;\n\n        if (r>=k)\n        {\n          a(s2,0) = a(s1,0)/ndu(pk+1,rk);\n          d = a(s2,0)*ndu(rk,pk);\n        }\n\n        if (rk>=-1) j1 = 1;\n        else        j1 = -rk;\n\n        if (r-1 <= pk) j2 = k-1;\n        else           j2 = p-r;\n\n        for (j=j1; j<=j2; ++j)\n        {\n          a(s2,j) = (a(s1,j)-a(s1,j-1))/ndu(pk+1,rk+j);\n          d += a(s2,j)*ndu(rk+j,pk);\n        }\n\n        if (r<=pk)\n        {\n          a(s2,k) = -a(s1,k-1)/ndu(pk+1,r);\n          d += a(s2,k)*ndu(r,pk);\n        }\n\n        N_(k,r) = static_cast<Scalar>(d);\n        j = s1; s1 = s2; s2 = j; // Switch rows\n      }\n    }\n\n    /* Multiply through by the correct factors */\n    /* (Eq. [2.9])                             */\n    r = p;\n    for (DenseIndex k=1; k<=static_cast<DenseIndex>(n); ++k)\n    {\n      for (j=p; j>=0; --j) N_(k,j) *= r;\n      r *= p-k;\n    }\n  }\n\n  template <typename Scalar_, int Dim_, int _Degree>\n  typename SplineTraits< Spline<Scalar_, Dim_, _Degree> >::BasisDerivativeType\n    Spline<Scalar_, Dim_, _Degree>::basisFunctionDerivatives(Scalar u, DenseIndex order) const\n  {\n    typename SplineTraits<Spline<Scalar_, Dim_, _Degree> >::BasisDerivativeType der;\n    BasisFunctionDerivativesImpl(u, order, degree(), knots(), der);\n    return der;\n  }\n\n  template <typename Scalar_, int Dim_, int _Degree>\n  template <int DerivativeOrder>\n  typename SplineTraits< Spline<Scalar_, Dim_, _Degree>, DerivativeOrder >::BasisDerivativeType\n    Spline<Scalar_, Dim_, _Degree>::basisFunctionDerivatives(Scalar u, DenseIndex order) const\n  {\n    typename SplineTraits< Spline<Scalar_, Dim_, _Degree>, DerivativeOrder >::BasisDerivativeType der;\n    BasisFunctionDerivativesImpl(u, order, degree(), knots(), der);\n    return der;\n  }\n\n  template <typename Scalar_, int Dim_, int _Degree>\n  typename SplineTraits<Spline<Scalar_, Dim_, _Degree> >::BasisDerivativeType\n  Spline<Scalar_, Dim_, _Degree>::BasisFunctionDerivatives(\n    const typename Spline<Scalar_, Dim_, _Degree>::Scalar u,\n    const DenseIndex order,\n    const DenseIndex degree,\n    const typename Spline<Scalar_, Dim_, _Degree>::KnotVectorType& knots)\n  {\n    typename SplineTraits<Spline>::BasisDerivativeType der;\n    BasisFunctionDerivativesImpl(u, order, degree, knots, der);\n    return der;\n  }\n}\n\n#endif // EIGEN_SPLINE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/Splines/SplineFitting.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 20010-2011 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPLINE_FITTING_H\n#define EIGEN_SPLINE_FITTING_H\n\n#include <algorithm>\n#include <functional>\n#include <numeric>\n#include <vector>\n\n#include \"SplineFwd.h\"\n\n#include \"../../../../Eigen/LU\"\n#include \"../../../../Eigen/QR\"\n\nnamespace Eigen\n{\n  /**\n   * \\brief Computes knot averages.\n   * \\ingroup Splines_Module\n   *\n   * The knots are computed as\n   * \\f{align*}\n   *  u_0 & = \\hdots = u_p = 0 \\\\\n   *  u_{m-p} & = \\hdots = u_{m} = 1 \\\\\n   *  u_{j+p} & = \\frac{1}{p}\\sum_{i=j}^{j+p-1}\\bar{u}_i \\quad\\quad j=1,\\hdots,n-p\n   * \\f}\n   * where \\f$p\\f$ is the degree and \\f$m+1\\f$ the number knots\n   * of the desired interpolating spline.\n   *\n   * \\param[in] parameters The input parameters. During interpolation one for each data point.\n   * \\param[in] degree The spline degree which is used during the interpolation.\n   * \\param[out] knots The output knot vector.\n   *\n   * \\sa Les Piegl and Wayne Tiller, The NURBS book (2nd ed.), 1997, 9.2.1 Global Curve Interpolation to Point Data\n   **/\n  template <typename KnotVectorType>\n  void KnotAveraging(const KnotVectorType& parameters, DenseIndex degree, KnotVectorType& knots)\n  {\n    knots.resize(parameters.size()+degree+1);      \n\n    for (DenseIndex j=1; j<parameters.size()-degree; ++j)\n      knots(j+degree) = parameters.segment(j,degree).mean();\n\n    knots.segment(0,degree+1) = KnotVectorType::Zero(degree+1);\n    knots.segment(knots.size()-degree-1,degree+1) = KnotVectorType::Ones(degree+1);\n  }\n\n  /**\n   * \\brief Computes knot averages when derivative constraints are present.\n   * Note that this is a technical interpretation of the referenced article\n   * since the algorithm contained therein is incorrect as written.\n   * \\ingroup Splines_Module\n   *\n   * \\param[in] parameters The parameters at which the interpolation B-Spline\n   *            will intersect the given interpolation points. The parameters\n   *            are assumed to be a non-decreasing sequence.\n   * \\param[in] degree The degree of the interpolating B-Spline. This must be\n   *            greater than zero.\n   * \\param[in] derivativeIndices The indices corresponding to parameters at\n   *            which there are derivative constraints. The indices are assumed\n   *            to be a non-decreasing sequence.\n   * \\param[out] knots The calculated knot vector. These will be returned as a\n   *             non-decreasing sequence\n   *\n   * \\sa Les A. Piegl, Khairan Rajab, Volha Smarodzinana. 2008.\n   * Curve interpolation with directional constraints for engineering design. \n   * Engineering with Computers\n   **/\n  template <typename KnotVectorType, typename ParameterVectorType, typename IndexArray>\n  void KnotAveragingWithDerivatives(const ParameterVectorType& parameters,\n                                    const unsigned int degree,\n                                    const IndexArray& derivativeIndices,\n                                    KnotVectorType& knots)\n  {\n    typedef typename ParameterVectorType::Scalar Scalar;\n\n    DenseIndex numParameters = parameters.size();\n    DenseIndex numDerivatives = derivativeIndices.size();\n\n    if (numDerivatives < 1)\n    {\n      KnotAveraging(parameters, degree, knots);\n      return;\n    }\n\n    DenseIndex startIndex;\n    DenseIndex endIndex;\n  \n    DenseIndex numInternalDerivatives = numDerivatives;\n    \n    if (derivativeIndices[0] == 0)\n    {\n      startIndex = 0;\n      --numInternalDerivatives;\n    }\n    else\n    {\n      startIndex = 1;\n    }\n    if (derivativeIndices[numDerivatives - 1] == numParameters - 1)\n    {\n      endIndex = numParameters - degree;\n      --numInternalDerivatives;\n    }\n    else\n    {\n      endIndex = numParameters - degree - 1;\n    }\n\n    // There are (endIndex - startIndex + 1) knots obtained from the averaging\n    // and 2 for the first and last parameters.\n    DenseIndex numAverageKnots = endIndex - startIndex + 3;\n    KnotVectorType averageKnots(numAverageKnots);\n    averageKnots[0] = parameters[0];\n\n    int newKnotIndex = 0;\n    for (DenseIndex i = startIndex; i <= endIndex; ++i)\n      averageKnots[++newKnotIndex] = parameters.segment(i, degree).mean();\n    averageKnots[++newKnotIndex] = parameters[numParameters - 1];\n\n    newKnotIndex = -1;\n  \n    ParameterVectorType temporaryParameters(numParameters + 1);\n    KnotVectorType derivativeKnots(numInternalDerivatives);\n    for (DenseIndex i = 0; i < numAverageKnots - 1; ++i)\n    {\n      temporaryParameters[0] = averageKnots[i];\n      ParameterVectorType parameterIndices(numParameters);\n      int temporaryParameterIndex = 1;\n      for (DenseIndex j = 0; j < numParameters; ++j)\n      {\n        Scalar parameter = parameters[j];\n        if (parameter >= averageKnots[i] && parameter < averageKnots[i + 1])\n        {\n          parameterIndices[temporaryParameterIndex] = j;\n          temporaryParameters[temporaryParameterIndex++] = parameter;\n        }\n      }\n      temporaryParameters[temporaryParameterIndex] = averageKnots[i + 1];\n\n      for (int j = 0; j <= temporaryParameterIndex - 2; ++j)\n      {\n        for (DenseIndex k = 0; k < derivativeIndices.size(); ++k)\n        {\n          if (parameterIndices[j + 1] == derivativeIndices[k]\n              && parameterIndices[j + 1] != 0\n              && parameterIndices[j + 1] != numParameters - 1)\n          {\n            derivativeKnots[++newKnotIndex] = temporaryParameters.segment(j, 3).mean();\n            break;\n          }\n        }\n      }\n    }\n    \n    KnotVectorType temporaryKnots(averageKnots.size() + derivativeKnots.size());\n\n    std::merge(averageKnots.data(), averageKnots.data() + averageKnots.size(),\n               derivativeKnots.data(), derivativeKnots.data() + derivativeKnots.size(),\n               temporaryKnots.data());\n\n    // Number of knots (one for each point and derivative) plus spline order.\n    DenseIndex numKnots = numParameters + numDerivatives + degree + 1;\n    knots.resize(numKnots);\n\n    knots.head(degree).fill(temporaryKnots[0]);\n    knots.tail(degree).fill(temporaryKnots.template tail<1>()[0]);\n    knots.segment(degree, temporaryKnots.size()) = temporaryKnots;\n  }\n\n  /**\n   * \\brief Computes chord length parameters which are required for spline interpolation.\n   * \\ingroup Splines_Module\n   *\n   * \\param[in] pts The data points to which a spline should be fit.\n   * \\param[out] chord_lengths The resulting chord length vector.\n   *\n   * \\sa Les Piegl and Wayne Tiller, The NURBS book (2nd ed.), 1997, 9.2.1 Global Curve Interpolation to Point Data\n   **/   \n  template <typename PointArrayType, typename KnotVectorType>\n  void ChordLengths(const PointArrayType& pts, KnotVectorType& chord_lengths)\n  {\n    typedef typename KnotVectorType::Scalar Scalar;\n\n    const DenseIndex n = pts.cols();\n\n    // 1. compute the column-wise norms\n    chord_lengths.resize(pts.cols());\n    chord_lengths[0] = 0;\n    chord_lengths.rightCols(n-1) = (pts.array().leftCols(n-1) - pts.array().rightCols(n-1)).matrix().colwise().norm();\n\n    // 2. compute the partial sums\n    std::partial_sum(chord_lengths.data(), chord_lengths.data()+n, chord_lengths.data());\n\n    // 3. normalize the data\n    chord_lengths /= chord_lengths(n-1);\n    chord_lengths(n-1) = Scalar(1);\n  }\n\n  /**\n   * \\brief Spline fitting methods.\n   * \\ingroup Splines_Module\n   **/     \n  template <typename SplineType>\n  struct SplineFitting\n  {\n    typedef typename SplineType::KnotVectorType KnotVectorType;\n    typedef typename SplineType::ParameterVectorType ParameterVectorType;\n\n    /**\n     * \\brief Fits an interpolating Spline to the given data points.\n     *\n     * \\param pts The points for which an interpolating spline will be computed.\n     * \\param degree The degree of the interpolating spline.\n     *\n     * \\returns A spline interpolating the initially provided points.\n     **/\n    template <typename PointArrayType>\n    static SplineType Interpolate(const PointArrayType& pts, DenseIndex degree);\n\n    /**\n     * \\brief Fits an interpolating Spline to the given data points.\n     *\n     * \\param pts The points for which an interpolating spline will be computed.\n     * \\param degree The degree of the interpolating spline.\n     * \\param knot_parameters The knot parameters for the interpolation.\n     *\n     * \\returns A spline interpolating the initially provided points.\n     **/\n    template <typename PointArrayType>\n    static SplineType Interpolate(const PointArrayType& pts, DenseIndex degree, const KnotVectorType& knot_parameters);\n\n    /**\n     * \\brief Fits an interpolating spline to the given data points and\n     * derivatives.\n     * \n     * \\param points The points for which an interpolating spline will be computed.\n     * \\param derivatives The desired derivatives of the interpolating spline at interpolation\n     *                    points.\n     * \\param derivativeIndices An array indicating which point each derivative belongs to. This\n     *                          must be the same size as @a derivatives.\n     * \\param degree The degree of the interpolating spline.\n     *\n     * \\returns A spline interpolating @a points with @a derivatives at those points.\n     *\n     * \\sa Les A. Piegl, Khairan Rajab, Volha Smarodzinana. 2008.\n     * Curve interpolation with directional constraints for engineering design. \n     * Engineering with Computers\n     **/\n    template <typename PointArrayType, typename IndexArray>\n    static SplineType InterpolateWithDerivatives(const PointArrayType& points,\n                                                 const PointArrayType& derivatives,\n                                                 const IndexArray& derivativeIndices,\n                                                 const unsigned int degree);\n\n    /**\n     * \\brief Fits an interpolating spline to the given data points and derivatives.\n     * \n     * \\param points The points for which an interpolating spline will be computed.\n     * \\param derivatives The desired derivatives of the interpolating spline at interpolation points.\n     * \\param derivativeIndices An array indicating which point each derivative belongs to. This\n     *                          must be the same size as @a derivatives.\n     * \\param degree The degree of the interpolating spline.\n     * \\param parameters The parameters corresponding to the interpolation points.\n     *\n     * \\returns A spline interpolating @a points with @a derivatives at those points.\n     *\n     * \\sa Les A. Piegl, Khairan Rajab, Volha Smarodzinana. 2008.\n     * Curve interpolation with directional constraints for engineering design. \n     * Engineering with Computers\n     */\n    template <typename PointArrayType, typename IndexArray>\n    static SplineType InterpolateWithDerivatives(const PointArrayType& points,\n                                                 const PointArrayType& derivatives,\n                                                 const IndexArray& derivativeIndices,\n                                                 const unsigned int degree,\n                                                 const ParameterVectorType& parameters);\n  };\n\n  template <typename SplineType>\n  template <typename PointArrayType>\n  SplineType SplineFitting<SplineType>::Interpolate(const PointArrayType& pts, DenseIndex degree, const KnotVectorType& knot_parameters)\n  {\n    typedef typename SplineType::KnotVectorType::Scalar Scalar;      \n    typedef typename SplineType::ControlPointVectorType ControlPointVectorType;      \n\n    typedef Matrix<Scalar,Dynamic,Dynamic> MatrixType;\n\n    KnotVectorType knots;\n    KnotAveraging(knot_parameters, degree, knots);\n\n    DenseIndex n = pts.cols();\n    MatrixType A = MatrixType::Zero(n,n);\n    for (DenseIndex i=1; i<n-1; ++i)\n    {\n      const DenseIndex span = SplineType::Span(knot_parameters[i], degree, knots);\n\n      // The segment call should somehow be told the spline order at compile time.\n      A.row(i).segment(span-degree, degree+1) = SplineType::BasisFunctions(knot_parameters[i], degree, knots);\n    }\n    A(0,0) = 1.0;\n    A(n-1,n-1) = 1.0;\n\n    HouseholderQR<MatrixType> qr(A);\n\n    // Here, we are creating a temporary due to an Eigen issue.\n    ControlPointVectorType ctrls = qr.solve(MatrixType(pts.transpose())).transpose();\n\n    return SplineType(knots, ctrls);\n  }\n\n  template <typename SplineType>\n  template <typename PointArrayType>\n  SplineType SplineFitting<SplineType>::Interpolate(const PointArrayType& pts, DenseIndex degree)\n  {\n    KnotVectorType chord_lengths; // knot parameters\n    ChordLengths(pts, chord_lengths);\n    return Interpolate(pts, degree, chord_lengths);\n  }\n  \n  template <typename SplineType>\n  template <typename PointArrayType, typename IndexArray>\n  SplineType \n  SplineFitting<SplineType>::InterpolateWithDerivatives(const PointArrayType& points,\n                                                        const PointArrayType& derivatives,\n                                                        const IndexArray& derivativeIndices,\n                                                        const unsigned int degree,\n                                                        const ParameterVectorType& parameters)\n  {\n    typedef typename SplineType::KnotVectorType::Scalar Scalar;      \n    typedef typename SplineType::ControlPointVectorType ControlPointVectorType;\n\n    typedef Matrix<Scalar, Dynamic, Dynamic> MatrixType;\n\n    const DenseIndex n = points.cols() + derivatives.cols();\n    \n    KnotVectorType knots;\n\n    KnotAveragingWithDerivatives(parameters, degree, derivativeIndices, knots);\n    \n    // fill matrix\n    MatrixType A = MatrixType::Zero(n, n);\n\n    // Use these dimensions for quicker populating, then transpose for solving.\n    MatrixType b(points.rows(), n);\n\n    DenseIndex startRow;\n    DenseIndex derivativeStart;\n\n    // End derivatives.\n    if (derivativeIndices[0] == 0)\n    {\n      A.template block<1, 2>(1, 0) << -1, 1;\n      \n      Scalar y = (knots(degree + 1) - knots(0)) / degree;\n      b.col(1) = y*derivatives.col(0);\n      \n      startRow = 2;\n      derivativeStart = 1;\n    }\n    else\n    {\n      startRow = 1;\n      derivativeStart = 0;\n    }\n    if (derivativeIndices[derivatives.cols() - 1] == points.cols() - 1)\n    {\n      A.template block<1, 2>(n - 2, n - 2) << -1, 1;\n\n      Scalar y = (knots(knots.size() - 1) - knots(knots.size() - (degree + 2))) / degree;\n      b.col(b.cols() - 2) = y*derivatives.col(derivatives.cols() - 1);\n    }\n    \n    DenseIndex row = startRow;\n    DenseIndex derivativeIndex = derivativeStart;\n    for (DenseIndex i = 1; i < parameters.size() - 1; ++i)\n    {\n      const DenseIndex span = SplineType::Span(parameters[i], degree, knots);\n\n      if (derivativeIndex < derivativeIndices.size() && derivativeIndices[derivativeIndex] == i)\n      {\n        A.block(row, span - degree, 2, degree + 1)\n          = SplineType::BasisFunctionDerivatives(parameters[i], 1, degree, knots);\n\n        b.col(row++) = points.col(i);\n        b.col(row++) = derivatives.col(derivativeIndex++);\n      }\n      else\n      {\n        A.row(row).segment(span - degree, degree + 1)\n          = SplineType::BasisFunctions(parameters[i], degree, knots);\n        b.col(row++) = points.col(i);\n      }\n    }\n    b.col(0) = points.col(0);\n    b.col(b.cols() - 1) = points.col(points.cols() - 1);\n    A(0,0) = 1;\n    A(n - 1, n - 1) = 1;\n    \n    // Solve\n    FullPivLU<MatrixType> lu(A);\n    ControlPointVectorType controlPoints = lu.solve(MatrixType(b.transpose())).transpose();\n\n    SplineType spline(knots, controlPoints);\n    \n    return spline;\n  }\n  \n  template <typename SplineType>\n  template <typename PointArrayType, typename IndexArray>\n  SplineType\n  SplineFitting<SplineType>::InterpolateWithDerivatives(const PointArrayType& points,\n                                                        const PointArrayType& derivatives,\n                                                        const IndexArray& derivativeIndices,\n                                                        const unsigned int degree)\n  {\n    ParameterVectorType parameters;\n    ChordLengths(points, parameters);\n    return InterpolateWithDerivatives(points, derivatives, derivativeIndices, degree, parameters);\n  }\n}\n\n#endif // EIGEN_SPLINE_FITTING_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/Eigen/src/Splines/SplineFwd.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 20010-2011 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPLINES_FWD_H\n#define EIGEN_SPLINES_FWD_H\n\n#include \"../../../../Eigen/Core\"\n\nnamespace Eigen\n{\n    template <typename Scalar, int Dim, int Degree = Dynamic> class Spline;\n\n    template < typename SplineType, int DerivativeOrder = Dynamic > struct SplineTraits {};\n\n    /**\n     * \\ingroup Splines_Module\n     * \\brief Compile-time attributes of the Spline class for Dynamic degree.\n     **/\n    template <typename Scalar_, int Dim_, int _Degree>\n    struct SplineTraits< Spline<Scalar_, Dim_, _Degree>, Dynamic >\n    {\n      typedef Scalar_ Scalar; /*!< The spline curve's scalar type. */\n      enum { Dimension = Dim_ /*!< The spline curve's dimension. */ };\n      enum { Degree = _Degree /*!< The spline curve's degree. */ };\n\n      enum { OrderAtCompileTime = _Degree==Dynamic ? Dynamic : _Degree+1 /*!< The spline curve's order at compile-time. */ };\n      enum { NumOfDerivativesAtCompileTime = OrderAtCompileTime /*!< The number of derivatives defined for the current spline. */ };\n      \n      enum { DerivativeMemoryLayout = Dimension==1 ? RowMajor : ColMajor /*!< The derivative type's memory layout. */ };\n\n      /** \\brief The data type used to store non-zero basis functions. */\n      typedef Array<Scalar,1,OrderAtCompileTime> BasisVectorType;\n\n      /** \\brief The data type used to store the values of the basis function derivatives. */\n      typedef Array<Scalar,Dynamic,Dynamic,RowMajor,NumOfDerivativesAtCompileTime,OrderAtCompileTime> BasisDerivativeType;\n      \n      /** \\brief The data type used to store the spline's derivative values. */\n      typedef Array<Scalar,Dimension,Dynamic,DerivativeMemoryLayout,Dimension,NumOfDerivativesAtCompileTime> DerivativeType;\n\n      /** \\brief The point type the spline is representing. */\n      typedef Array<Scalar,Dimension,1> PointType;\n      \n      /** \\brief The data type used to store knot vectors. */\n      typedef Array<Scalar,1,Dynamic> KnotVectorType;\n\n      /** \\brief The data type used to store parameter vectors. */\n      typedef Array<Scalar,1,Dynamic> ParameterVectorType;\n      \n      /** \\brief The data type representing the spline's control points. */\n      typedef Array<Scalar,Dimension,Dynamic> ControlPointVectorType;\n    };\n\n    /**\n     * \\ingroup Splines_Module\n     * \\brief Compile-time attributes of the Spline class for fixed degree.\n     *\n     * The traits class inherits all attributes from the SplineTraits of Dynamic degree.\n     **/\n    template < typename Scalar_, int Dim_, int _Degree, int _DerivativeOrder >\n    struct SplineTraits< Spline<Scalar_, Dim_, _Degree>, _DerivativeOrder > : public SplineTraits< Spline<Scalar_, Dim_, _Degree> >\n    {\n      enum { OrderAtCompileTime = _Degree==Dynamic ? Dynamic : _Degree+1 /*!< The spline curve's order at compile-time. */ };\n      enum { NumOfDerivativesAtCompileTime = _DerivativeOrder==Dynamic ? Dynamic : _DerivativeOrder+1 /*!< The number of derivatives defined for the current spline. */ };\n      \n      enum { DerivativeMemoryLayout = Dim_==1 ? RowMajor : ColMajor /*!< The derivative type's memory layout. */ };\n\n      /** \\brief The data type used to store the values of the basis function derivatives. */\n      typedef Array<Scalar_,Dynamic,Dynamic,RowMajor,NumOfDerivativesAtCompileTime,OrderAtCompileTime> BasisDerivativeType;\n      \n      /** \\brief The data type used to store the spline's derivative values. */      \n      typedef Array<Scalar_,Dim_,Dynamic,DerivativeMemoryLayout,Dim_,NumOfDerivativesAtCompileTime> DerivativeType;\n    };\n\n    /** \\brief 2D float B-spline with dynamic degree. */\n    typedef Spline<float,2> Spline2f;\n    \n    /** \\brief 3D float B-spline with dynamic degree. */\n    typedef Spline<float,3> Spline3f;\n\n    /** \\brief 2D double B-spline with dynamic degree. */\n    typedef Spline<double,2> Spline2d;\n    \n    /** \\brief 3D double B-spline with dynamic degree. */\n    typedef Spline<double,3> Spline3d;\n}\n\n#endif // EIGEN_SPLINES_FWD_H\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/README.txt",
    "content": "This directory contains contributions from various users.\nThey are provided \"as is\", without any support. Nevertheless,\nmost of them are subject to be included in Eigen in the future.\n\nIn order to use an unsupported module you have to do either:\n\n - add the path_to_eigen/unsupported directory to your include path and do:\n   #include <Eigen/ModuleHeader>\n\n - or directly do:\n   #include <unsupported/Eigen/ModuleHeader>\n\n\nIf you are interested in contributing to one of them, or have other stuff\nyou would like to share, feel free to contact us:\nhttp://eigen.tuxfamily.org/index.php?title=Main_Page#Mailing_list\n\nAny kind of contributions are much appreciated, even very preliminary ones.\nHowever, it:\n - must rely on Eigen,\n - must be highly related to math,\n - should have some general purpose in the sense that it could\n   potentially become an official Eigen module (or be merged into another one).\n\nIn doubt feel free to contact us. For instance, if your addons is very too specific\nbut it shows an interesting way of using Eigen, then it could be a nice demo.\n\n\nThis directory is organized as follow:\n\nunsupported/Eigen/ModuleHeader1\nunsupported/Eigen/ModuleHeader2\nunsupported/Eigen/...\nunsupported/Eigen/src/Module1/SourceFile1.h\nunsupported/Eigen/src/Module1/SourceFile2.h\nunsupported/Eigen/src/Module1/...\nunsupported/Eigen/src/Module2/SourceFile1.h\nunsupported/Eigen/src/Module2/SourceFile2.h\nunsupported/Eigen/src/Module2/...\nunsupported/Eigen/src/...\nunsupported/doc/snippets/.cpp   <- code snippets for the doc\nunsupported/doc/examples/.cpp   <- examples for the doc\nunsupported/doc/TutorialModule1.dox\nunsupported/doc/TutorialModule2.dox\nunsupported/doc/...\nunsupported/test/.cpp           <- unit test files\n\nThe documentation is generated at the same time than the main Eigen documentation.\nThe .html files are generated in: build_dir/doc/html/unsupported/\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/bench/bench_svd.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Gauthier Brun <brun.gauthier@gmail.com>\n// Copyright (C) 2013 Nicolas Carre <nicolas.carre@ensimag.fr>\n// Copyright (C) 2013 Jean Ceccato <jean.ceccato@ensimag.fr>\n// Copyright (C) 2013 Pierre Zoppitelli <pierre.zoppitelli@ensimag.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/\n\n// Bench to compare the efficiency of SVD algorithms\n\n#include <iostream>\n#include <bench/BenchTimer.h>\n#include <unsupported/Eigen/SVD>\n\n\nusing namespace Eigen;\nusing namespace std;\n\n// number of computations of each algorithm before the print of the time\n#ifndef REPEAT\n#define REPEAT 10\n#endif\n\n// number of tests of the same type\n#ifndef NUMBER_SAMPLE\n#define NUMBER_SAMPLE 2\n#endif\n\ntemplate<typename MatrixType>\nvoid bench_svd(const MatrixType& a = MatrixType())\n{\n  MatrixType m = MatrixType::Random(a.rows(), a.cols());\n  BenchTimer timerJacobi;\n  BenchTimer timerBDC;\n  timerJacobi.reset();\n  timerBDC.reset();\n\n  cout << \" Only compute Singular Values\" <<endl;\n  for (int k=1; k<=NUMBER_SAMPLE; ++k)\n  {\n    timerBDC.start();\n    for (int i=0; i<REPEAT; ++i) \n    {\n      BDCSVD<MatrixType> bdc_matrix(m);\n    }\n    timerBDC.stop();\n    \n    timerJacobi.start();\n    for (int i=0; i<REPEAT; ++i) \n    {\n      JacobiSVD<MatrixType> jacobi_matrix(m);\n    }\n    timerJacobi.stop();\n\n\n    cout << \"Sample \" << k << \" : \" << REPEAT << \" computations :  Jacobi : \" << fixed << timerJacobi.value() << \"s \";\n    cout << \" || \" << \" BDC : \" << timerBDC.value() << \"s \" <<endl <<endl;\n      \n    if (timerBDC.value() >= timerJacobi.value())  \n      cout << \"KO : BDC is \" <<  timerJacobi.value() / timerBDC.value() << \"  times faster than Jacobi\" <<endl;\n    else \n      cout << \"OK : BDC is \" << timerJacobi.value() / timerBDC.value() << \"  times faster than Jacobi\"  <<endl;\n      \n  }\n  cout << \"       =================\" <<endl;\n  std::cout<< std::endl;\n  timerJacobi.reset();\n  timerBDC.reset();\n  cout << \" Computes rotation matrix\" <<endl;\n  for (int k=1; k<=NUMBER_SAMPLE; ++k)\n  {\n    timerBDC.start();\n    for (int i=0; i<REPEAT; ++i) \n    {\n      BDCSVD<MatrixType> bdc_matrix(m, ComputeFullU|ComputeFullV);\n    }\n    timerBDC.stop();\n    \n    timerJacobi.start();\n    for (int i=0; i<REPEAT; ++i) \n    {\n      JacobiSVD<MatrixType> jacobi_matrix(m, ComputeFullU|ComputeFullV);\n    }\n    timerJacobi.stop();\n\n\n    cout << \"Sample \" << k << \" : \" << REPEAT << \" computations :  Jacobi : \" << fixed << timerJacobi.value() << \"s \";\n    cout << \" || \" << \" BDC : \" << timerBDC.value() << \"s \" <<endl <<endl;\n      \n    if (timerBDC.value() >= timerJacobi.value())  \n      cout << \"KO : BDC is \" <<  timerJacobi.value() / timerBDC.value() << \"  times faster than Jacobi\" <<endl;\n    else \n      cout << \"OK : BDC is \" << timerJacobi.value() / timerBDC.value() << \"  times faster than Jacobi\"  <<endl;\n      \n  }\n  std::cout<< std::endl;\n}\n\n\n\nint main(int argc, char* argv[])\n{\n  std::cout<< std::endl;\n\n  std::cout<<\"On a (Dynamic, Dynamic) (6, 6) Matrix\" <<std::endl;\n  bench_svd<Matrix<double,Dynamic,Dynamic> >(Matrix<double,Dynamic,Dynamic>(6, 6));\n  \n  std::cout<<\"On a (Dynamic, Dynamic) (32, 32) Matrix\" <<std::endl;\n  bench_svd<Matrix<double,Dynamic,Dynamic> >(Matrix<double,Dynamic,Dynamic>(32, 32));\n\n  //std::cout<<\"On a (Dynamic, Dynamic) (128, 128) Matrix\" <<std::endl;\n  //bench_svd<Matrix<double,Dynamic,Dynamic> >(Matrix<double,Dynamic,Dynamic>(128, 128));\n\n  std::cout<<\"On a (Dynamic, Dynamic) (160, 160) Matrix\" <<std::endl;\n  bench_svd<Matrix<double,Dynamic,Dynamic> >(Matrix<double,Dynamic,Dynamic>(160, 160));\n  \n  std::cout<< \"--------------------------------------------------------------------\"<< std::endl;\n           \n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/CMakeLists.txt",
    "content": "set_directory_properties(PROPERTIES EXCLUDE_FROM_ALL TRUE)\n\nadd_subdirectory(examples)\nadd_subdirectory(snippets)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/Overview.dox",
    "content": "/// \\brief Namespace containing all symbols from the %Eigen library.\nnamespace Eigen {\n\n/** \\mainpage %Eigen's unsupported modules\n\nThis is the API documentation for %Eigen's unsupported modules.\n\nThese modules are contributions from various users. They are provided \"as is\", without any support.\n\nClick on the \\e Modules tab at the top of this page to get a list of all unsupported modules.\n\nDon't miss the <a href=\"../index.html\">official Eigen documentation</a>.\n\n \\subpage SYCL_EIGEN \"SYCL backend for Eigen\"\n\n*/\n\n/*\n\n\\defgroup Unsupported_modules Unsupported modules\n\nThe unsupported modules are contributions from various users. They are\nprovided \"as is\", without any support. Nevertheless, some of them are\nsubject to be included in %Eigen in the future.\n\n*/\n\n/// \\internal \\brief Namespace containing low-level routines from the %Eigen library.\nnamespace internal {}\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/SYCL.dox",
    "content": "/** \\page SYCL_EIGEN Eigen SYCL Backend\n\nUseful information for Eigen SYCL Backend:\n\n- <a href=\"https://developer.codeplay.com/computecppce/latest/getting-started-with-eigen\">Getting Started with Eigen</a> \n\n- <a href=\"https://developer.codeplay.com/computecppce/latest/options-for-building-eigen-sycl\">Options for Building Eigen SYCL</a>  \n\n*/\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/eigendoxy_layout.xml.in",
    "content": "<?xml version=\"1.0\"?>\n<doxygenlayout version=\"1.0\">\n  <!-- Navigation index tabs for HTML output -->\n  <navindex>\n    <tab type=\"user\" url=\"index.html\" title=\"Overview\" />\n    <tab type=\"modules\" visible=\"yes\" title=\"Unsupported Modules\" intro=\"\"/>\n<!--     <tab type=\"mainpage\" visible=\"yes\" title=\"\"/> -->\n    <tab type=\"classlist\" visible=\"yes\" title=\"\" intro=\"\"/>\n<!--     <tab type=\"classmembers\" visible=\"yes\" title=\"\" intro=\"\"/> -->\n  </navindex>\n\n  <!-- Layout definition for a class page -->\n  <class>\n    <briefdescription visible=\"no\"/>\n    <includes visible=\"$SHOW_INCLUDE_FILES\"/>\n    <detaileddescription title=\"\"/>\n    <inheritancegraph visible=\"$CLASS_GRAPH\"/>\n    <collaborationgraph visible=\"$COLLABORATION_GRAPH\"/>\n    <allmemberslink visible=\"yes\"/>\n    <memberdecl>\n      <nestedclasses visible=\"yes\" title=\"\"/>\n      <publictypes title=\"\"/>\n      <publicslots title=\"\"/>\n      <signals title=\"\"/>\n      <publicmethods title=\"\"/>\n      <publicstaticmethods title=\"\"/>\n      <publicattributes title=\"\"/>\n      <publicstaticattributes title=\"\"/>\n      <protectedtypes title=\"\"/>\n      <protectedslots title=\"\"/>\n      <protectedmethods title=\"\"/>\n      <protectedstaticmethods title=\"\"/>\n      <protectedattributes title=\"\"/>\n      <protectedstaticattributes title=\"\"/>\n      <packagetypes title=\"\"/>\n      <packagemethods title=\"\"/>\n      <packagestaticmethods title=\"\"/>\n      <packageattributes title=\"\"/>\n      <packagestaticattributes title=\"\"/>\n      <properties title=\"\"/>\n      <events title=\"\"/>\n      <privatetypes title=\"\"/>\n      <privateslots title=\"\"/>\n      <privatemethods title=\"\"/>\n      <privatestaticmethods title=\"\"/>\n      <privateattributes title=\"\"/>\n      <privatestaticattributes title=\"\"/>\n      <friends title=\"\"/>\n      <related title=\"\" subtitle=\"\"/>\n      <membergroups visible=\"yes\"/>\n    </memberdecl>\n    \n    <memberdef>\n      <inlineclasses title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <constructors title=\"\"/>\n      <functions title=\"\"/>\n      <related title=\"\"/>\n      <variables title=\"\"/>\n      <properties title=\"\"/>\n      <events title=\"\"/>\n    </memberdef>\n    <usedfiles visible=\"$SHOW_USED_FILES\"/>\n    <authorsection visible=\"yes\"/>\n  </class>\n\n  <!-- Layout definition for a namespace page -->\n  <namespace>\n    <briefdescription visible=\"yes\"/>\n    <memberdecl>\n      <nestednamespaces visible=\"yes\" title=\"\"/>\n      <classes visible=\"yes\" title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n      <membergroups visible=\"yes\"/>\n    </memberdecl>\n    <detaileddescription title=\"\"/>\n    <memberdef>\n      <inlineclasses title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n    </memberdef>\n    <authorsection visible=\"yes\"/>\n  </namespace>\n\n  <!-- Layout definition for a file page -->\n  <file>\n    <briefdescription visible=\"yes\"/>\n    <includes visible=\"$SHOW_INCLUDE_FILES\"/>\n    <includegraph visible=\"$INCLUDE_GRAPH\"/>\n    <includedbygraph visible=\"$INCLUDED_BY_GRAPH\"/>\n    <sourcelink visible=\"yes\"/>\n    <memberdecl>\n      <classes visible=\"yes\" title=\"\"/>\n      <namespaces visible=\"yes\" title=\"\"/>\n      <defines title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n      <membergroups visible=\"yes\"/>\n    </memberdecl>\n    <detaileddescription title=\"\"/>\n    <memberdef>\n      <inlineclasses title=\"\"/>\n      <defines title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n    </memberdef>\n    <authorsection/>\n  </file>\n\n  <!-- Layout definition for a group page -->\n  <group>\n    <briefdescription visible=\"no\"/>\n    <detaileddescription title=\"\"/>\n    <groupgraph visible=\"$GROUP_GRAPHS\"/>\n    <memberdecl>\n      <nestedgroups visible=\"yes\" title=\"\"/>\n      <dirs visible=\"yes\" title=\"\"/>\n      <files visible=\"yes\" title=\"\"/>\n      <namespaces visible=\"yes\" title=\"\"/>\n      <classes visible=\"yes\" title=\"\"/>\n      <defines title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <enumvalues title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n      <signals title=\"\"/>\n      <publicslots title=\"\"/>\n      <protectedslots title=\"\"/>\n      <privateslots title=\"\"/>\n      <events title=\"\"/>\n      <properties title=\"\"/>\n      <friends title=\"\"/>\n      <membergroups visible=\"yes\"/>\n    </memberdecl>\n    \n    <memberdef>\n      <pagedocs/>\n      <inlineclasses title=\"\"/>\n      <defines title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <enumvalues title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n      <signals title=\"\"/>\n      <publicslots title=\"\"/>\n      <protectedslots title=\"\"/>\n      <privateslots title=\"\"/>\n      <events title=\"\"/>\n      <properties title=\"\"/>\n      <friends title=\"\"/>\n    </memberdef>\n    <authorsection visible=\"yes\"/>\n  </group>\n\n  <!-- Layout definition for a directory page -->\n  <directory>\n    <briefdescription visible=\"yes\"/>\n    <directorygraph visible=\"yes\"/>\n    <memberdecl>\n      <dirs visible=\"yes\"/>\n      <files visible=\"yes\"/>\n    </memberdecl>\n    <detaileddescription title=\"\"/>\n  </directory>\n</doxygenlayout>\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/examples/BVH_Example.cpp",
    "content": "#include <Eigen/StdVector>\n#include <unsupported/Eigen/BVH>\n#include <iostream>\n\nusing namespace Eigen;\ntypedef AlignedBox<double, 2> Box2d;\n\nnamespace Eigen {\n  Box2d bounding_box(const Vector2d &v) { return Box2d(v, v); } //compute the bounding box of a single point\n}\n\nstruct PointPointMinimizer //how to compute squared distances between points and rectangles\n{\n  PointPointMinimizer() : calls(0) {}\n  typedef double Scalar;\n\n  double minimumOnVolumeVolume(const Box2d &r1, const Box2d &r2) { ++calls; return r1.squaredExteriorDistance(r2); }\n  double minimumOnVolumeObject(const Box2d &r, const Vector2d &v) { ++calls; return r.squaredExteriorDistance(v); }\n  double minimumOnObjectVolume(const Vector2d &v, const Box2d &r) { ++calls; return r.squaredExteriorDistance(v); }\n  double minimumOnObjectObject(const Vector2d &v1, const Vector2d &v2) { ++calls; return (v1 - v2).squaredNorm(); }\n\n  int calls;\n};\n\nint main()\n{\n  typedef std::vector<Vector2d, aligned_allocator<Vector2d> > StdVectorOfVector2d;\n  StdVectorOfVector2d redPoints, bluePoints;\n  for(int i = 0; i < 100; ++i) { //initialize random set of red points and blue points\n    redPoints.push_back(Vector2d::Random());\n    bluePoints.push_back(Vector2d::Random());\n  }\n\n  PointPointMinimizer minimizer;\n  double minDistSq = std::numeric_limits<double>::max();\n\n  //brute force to find closest red-blue pair\n  for(int i = 0; i < (int)redPoints.size(); ++i)\n    for(int j = 0; j < (int)bluePoints.size(); ++j)\n      minDistSq = std::min(minDistSq, minimizer.minimumOnObjectObject(redPoints[i], bluePoints[j]));\n  std::cout << \"Brute force distance = \" << sqrt(minDistSq) << \", calls = \" << minimizer.calls << std::endl;\n\n  //using BVH to find closest red-blue pair\n  minimizer.calls = 0;\n  KdBVH<double, 2, Vector2d> redTree(redPoints.begin(), redPoints.end()), blueTree(bluePoints.begin(), bluePoints.end()); //construct the trees\n  minDistSq = BVMinimize(redTree, blueTree, minimizer); //actual BVH minimization call\n  std::cout << \"BVH distance         = \" << sqrt(minDistSq) << \", calls = \" << minimizer.calls << std::endl;\n\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/examples/CMakeLists.txt",
    "content": "file(GLOB examples_SRCS \"*.cpp\")\n\nadd_custom_target(unsupported_examples)\n\ninclude_directories(../../../unsupported ../../../unsupported/test)\n\nforeach(example_src ${examples_SRCS})\n  get_filename_component(example ${example_src} NAME_WE)\n  add_executable(example_${example} ${example_src})\n  if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO)\n    target_link_libraries(example_${example} ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO})\n  endif()\n  add_custom_command(\n    TARGET example_${example}\n    POST_BUILD\n    COMMAND example_${example}\n    ARGS >${CMAKE_CURRENT_BINARY_DIR}/${example}.out\n  )\n  add_dependencies(unsupported_examples example_${example})\nendforeach(example_src)\n\nif(EIGEN_TEST_SYCL)\n  add_subdirectory(SYCL)\nendif(EIGEN_TEST_SYCL)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/examples/EulerAngles.cpp",
    "content": "#include <unsupported/Eigen/EulerAngles>\n#include <iostream>\n\nusing namespace Eigen;\n\nint main()\n{\n  // A common Euler system by many armies around the world,\n  //  where the first one is the azimuth(the angle from the north -\n  //   the same angle that is show in compass)\n  //  and the second one is elevation(the angle from the horizon)\n  //  and the third one is roll(the angle between the horizontal body\n  //   direction and the plane ground surface)\n  // Keep remembering we're using radian angles here!\n  typedef EulerSystem<-EULER_Z, EULER_Y, EULER_X> MyArmySystem;\n  typedef EulerAngles<double, MyArmySystem> MyArmyAngles;\n  \n  MyArmyAngles vehicleAngles(\n    3.14/*PI*/ / 2, /* heading to east, notice that this angle is counter-clockwise */\n    -0.3, /* going down from a mountain */\n    0.1); /* slightly rolled to the right */\n  \n  // Some Euler angles representation that our plane use.\n  EulerAnglesZYZd planeAngles(0.78474, 0.5271, -0.513794);\n  \n  MyArmyAngles planeAnglesInMyArmyAngles(planeAngles);\n  \n  std::cout << \"vehicle angles(MyArmy):     \" << vehicleAngles << std::endl;\n  std::cout << \"plane angles(ZYZ):        \" << planeAngles << std::endl;\n  std::cout << \"plane angles(MyArmy):     \" << planeAnglesInMyArmyAngles << std::endl;\n  \n  // Now lets rotate the plane a little bit\n  std::cout << \"==========================================================\\n\";\n  std::cout << \"rotating plane now!\\n\";\n  std::cout << \"==========================================================\\n\";\n  \n  Quaterniond planeRotated = AngleAxisd(-0.342, Vector3d::UnitY()) * planeAngles;\n  \n  planeAngles = planeRotated;\n  planeAnglesInMyArmyAngles = planeRotated;\n  \n  std::cout << \"new plane angles(ZYZ):     \" << planeAngles << std::endl;\n  std::cout << \"new plane angles(MyArmy): \" << planeAnglesInMyArmyAngles << std::endl;\n  \n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/examples/FFT.cpp",
    "content": "//  To use the simple FFT implementation\n//  g++ -o demofft -I.. -Wall -O3 FFT.cpp \n\n//  To use the FFTW implementation\n//  g++ -o demofft -I.. -DUSE_FFTW -Wall -O3 FFT.cpp -lfftw3 -lfftw3f -lfftw3l\n\n#ifdef USE_FFTW\n#include <fftw3.h>\n#endif\n\n#include <vector>\n#include <complex>\n#include <algorithm>\n#include <iterator>\n#include <iostream>\n#include <Eigen/Core>\n#include <unsupported/Eigen/FFT>\n\nusing namespace std;\nusing namespace Eigen;\n\ntemplate <typename T>\nT mag2(T a)\n{\n    return a*a;\n}\ntemplate <typename T>\nT mag2(std::complex<T> a)\n{\n    return norm(a);\n}\n\ntemplate <typename T>\nT mag2(const std::vector<T> & vec)\n{\n    T out=0;\n    for (size_t k=0;k<vec.size();++k)\n        out += mag2(vec[k]);\n    return out;\n}\n\ntemplate <typename T>\nT mag2(const std::vector<std::complex<T> > & vec)\n{\n    T out=0;\n    for (size_t k=0;k<vec.size();++k)\n        out += mag2(vec[k]);\n    return out;\n}\n\ntemplate <typename T>\nvector<T> operator-(const vector<T> & a,const vector<T> & b )\n{\n    vector<T> c(a);\n    for (size_t k=0;k<b.size();++k) \n        c[k] -= b[k];\n    return c;\n}\n\ntemplate <typename T>\nvoid RandomFill(std::vector<T> & vec)\n{\n    for (size_t k=0;k<vec.size();++k)\n        vec[k] = T( rand() )/T(RAND_MAX) - T(.5);\n}\n\ntemplate <typename T>\nvoid RandomFill(std::vector<std::complex<T> > & vec)\n{\n    for (size_t k=0;k<vec.size();++k)\n        vec[k] = std::complex<T> ( T( rand() )/T(RAND_MAX) - T(.5), T( rand() )/T(RAND_MAX) - T(.5));\n}\n\ntemplate <typename T_time,typename T_freq>\nvoid fwd_inv(size_t nfft)\n{\n    typedef typename NumTraits<T_freq>::Real Scalar;\n    vector<T_time> timebuf(nfft);\n    RandomFill(timebuf);\n\n    vector<T_freq> freqbuf;\n    static FFT<Scalar> fft;\n    fft.fwd(freqbuf,timebuf);\n\n    vector<T_time> timebuf2;\n    fft.inv(timebuf2,freqbuf);\n\n    T_time rmse = mag2(timebuf - timebuf2) / mag2(timebuf);\n    cout << \"roundtrip rmse: \" << rmse << endl;\n}\n\ntemplate <typename T_scalar>\nvoid two_demos(int nfft)\n{\n    cout << \"     scalar \";\n    fwd_inv<T_scalar,std::complex<T_scalar> >(nfft);\n    cout << \"    complex \";\n    fwd_inv<std::complex<T_scalar>,std::complex<T_scalar> >(nfft);\n}\n\nvoid demo_all_types(int nfft)\n{\n    cout << \"nfft=\" << nfft << endl;\n    cout << \"   float\" << endl;\n    two_demos<float>(nfft);\n    cout << \"   double\" << endl;\n    two_demos<double>(nfft);\n    cout << \"   long double\" << endl;\n    two_demos<long double>(nfft);\n}\n\nint main()\n{\n    demo_all_types( 2*3*4*5*7 );\n    demo_all_types( 2*9*16*25 );\n    demo_all_types( 1024 );\n    return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/examples/MatrixExponential.cpp",
    "content": "#include <unsupported/Eigen/MatrixFunctions>\n#include <iostream>\n\nusing namespace Eigen;\n\nint main()\n{\n  const double pi = std::acos(-1.0);\n\n  MatrixXd A(3,3);\n  A << 0,    -pi/4, 0,\n       pi/4, 0,     0,\n       0,    0,     0;\n  std::cout << \"The matrix A is:\\n\" << A << \"\\n\\n\";\n  std::cout << \"The matrix exponential of A is:\\n\" << A.exp() << \"\\n\\n\";\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/examples/MatrixFunction.cpp",
    "content": "#include <unsupported/Eigen/MatrixFunctions>\n#include <iostream>\n\nusing namespace Eigen;\n\nstd::complex<double> expfn(std::complex<double> x, int)\n{\n  return std::exp(x);\n}\n\nint main()\n{\n  const double pi = std::acos(-1.0);\n\n  MatrixXd A(3,3);\n  A << 0,    -pi/4, 0,\n       pi/4, 0,     0,\n       0,    0,     0;\n\n  std::cout << \"The matrix A is:\\n\" << A << \"\\n\\n\";\n  std::cout << \"The matrix exponential of A is:\\n\" \n            << A.matrixFunction(expfn) << \"\\n\\n\";\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/examples/MatrixLogarithm.cpp",
    "content": "#include <unsupported/Eigen/MatrixFunctions>\n#include <iostream>\n\nusing namespace Eigen;\n\nint main()\n{\n  using std::sqrt;\n  MatrixXd A(3,3);\n  A << 0.5*sqrt(2), -0.5*sqrt(2), 0,\n       0.5*sqrt(2),  0.5*sqrt(2), 0,\n       0,            0,           1;\n  std::cout << \"The matrix A is:\\n\" << A << \"\\n\\n\";\n  std::cout << \"The matrix logarithm of A is:\\n\" << A.log() << \"\\n\";\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/examples/MatrixPower.cpp",
    "content": "#include <unsupported/Eigen/MatrixFunctions>\n#include <iostream>\n\nusing namespace Eigen;\n\nint main()\n{\n  const double pi = std::acos(-1.0);\n  Matrix3d A;\n  A << cos(1), -sin(1), 0,\n       sin(1),  cos(1), 0,\n\t   0 ,      0 , 1;\n  std::cout << \"The matrix A is:\\n\" << A << \"\\n\\n\"\n\t       \"The matrix power A^(pi/4) is:\\n\" << A.pow(pi/4) << std::endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/examples/MatrixPower_optimal.cpp",
    "content": "#include <unsupported/Eigen/MatrixFunctions>\n#include <iostream>\n\nusing namespace Eigen;\n\nint main()\n{\n  Matrix4cd A = Matrix4cd::Random();\n  MatrixPower<Matrix4cd> Apow(A);\n\n  std::cout << \"The matrix A is:\\n\" << A << \"\\n\\n\"\n\t       \"A^3.1 is:\\n\" << Apow(3.1) << \"\\n\\n\"\n\t       \"A^3.3 is:\\n\" << Apow(3.3) << \"\\n\\n\"\n\t       \"A^3.7 is:\\n\" << Apow(3.7) << \"\\n\\n\"\n\t       \"A^3.9 is:\\n\" << Apow(3.9) << std::endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/examples/MatrixSine.cpp",
    "content": "#include <unsupported/Eigen/MatrixFunctions>\n#include <iostream>\n\nusing namespace Eigen;\n\nint main()\n{\n  MatrixXd A = MatrixXd::Random(3,3);\n  std::cout << \"A = \\n\" << A << \"\\n\\n\";\n\n  MatrixXd sinA = A.sin();\n  std::cout << \"sin(A) = \\n\" << sinA << \"\\n\\n\";\n\n  MatrixXd cosA = A.cos();\n  std::cout << \"cos(A) = \\n\" << cosA << \"\\n\\n\";\n  \n  // The matrix functions satisfy sin^2(A) + cos^2(A) = I, \n  // like the scalar functions.\n  std::cout << \"sin^2(A) + cos^2(A) = \\n\" << sinA*sinA + cosA*cosA << \"\\n\\n\";\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/examples/MatrixSinh.cpp",
    "content": "#include <unsupported/Eigen/MatrixFunctions>\n#include <iostream>\n\nusing namespace Eigen;\n\nint main()\n{\n  MatrixXf A = MatrixXf::Random(3,3);\n  std::cout << \"A = \\n\" << A << \"\\n\\n\";\n\n  MatrixXf sinhA = A.sinh();\n  std::cout << \"sinh(A) = \\n\" << sinhA << \"\\n\\n\";\n\n  MatrixXf coshA = A.cosh();\n  std::cout << \"cosh(A) = \\n\" << coshA << \"\\n\\n\";\n  \n  // The matrix functions satisfy cosh^2(A) - sinh^2(A) = I, \n  // like the scalar functions.\n  std::cout << \"cosh^2(A) - sinh^2(A) = \\n\" << coshA*coshA - sinhA*sinhA << \"\\n\\n\";\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/examples/MatrixSquareRoot.cpp",
    "content": "#include <unsupported/Eigen/MatrixFunctions>\n#include <iostream>\n\nusing namespace Eigen;\n\nint main()\n{\n  const double pi = std::acos(-1.0);\n\n  MatrixXd A(2,2);\n  A << cos(pi/3), -sin(pi/3), \n       sin(pi/3),  cos(pi/3);\n  std::cout << \"The matrix A is:\\n\" << A << \"\\n\\n\";\n  std::cout << \"The matrix square root of A is:\\n\" << A.sqrt() << \"\\n\\n\";\n  std::cout << \"The square of the last matrix is:\\n\" << A.sqrt() * A.sqrt() << \"\\n\";\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/examples/PolynomialSolver1.cpp",
    "content": "#include <unsupported/Eigen/Polynomials>\n#include <vector>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  typedef Matrix<double,5,1> Vector5d;\n\n  Vector5d roots = Vector5d::Random();\n  cout << \"Roots: \" << roots.transpose() << endl;\n  Eigen::Matrix<double,6,1> polynomial;\n  roots_to_monicPolynomial( roots, polynomial );\n\n  PolynomialSolver<double,5> psolve( polynomial );\n  cout << \"Complex roots: \" << psolve.roots().transpose() << endl;\n\n  std::vector<double> realRoots;\n  psolve.realRoots( realRoots );\n  Map<Vector5d> mapRR( &realRoots[0] );\n  cout << \"Real roots: \" << mapRR.transpose() << endl;\n\n  cout << endl;\n  cout << \"Illustration of the convergence problem with the QR algorithm: \" << endl;\n  cout << \"---------------------------------------------------------------\" << endl;\n  Eigen::Matrix<float,7,1> hardCase_polynomial;\n  hardCase_polynomial <<\n  -0.957, 0.9219, 0.3516, 0.9453, -0.4023, -0.5508, -0.03125;\n  cout << \"Hard case polynomial defined by floats: \" << hardCase_polynomial.transpose() << endl;\n  PolynomialSolver<float,6> psolvef( hardCase_polynomial );\n  cout << \"Complex roots: \" << psolvef.roots().transpose() << endl;\n  Eigen::Matrix<float,6,1> evals;\n  for( int i=0; i<6; ++i ){ evals[i] = std::abs( poly_eval( hardCase_polynomial, psolvef.roots()[i] ) ); }\n  cout << \"Norms of the evaluations of the polynomial at the roots: \" << evals.transpose() << endl << endl;\n\n  cout << \"Using double's almost always solves the problem for small degrees: \" << endl;\n  cout << \"-------------------------------------------------------------------\" << endl;\n  PolynomialSolver<double,6> psolve6d( hardCase_polynomial.cast<double>() );\n  cout << \"Complex roots: \" << psolve6d.roots().transpose() << endl;\n  for( int i=0; i<6; ++i )\n  {\n    std::complex<float> castedRoot( psolve6d.roots()[i].real(), psolve6d.roots()[i].imag() );\n    evals[i] = std::abs( poly_eval( hardCase_polynomial, castedRoot ) );\n  }\n  cout << \"Norms of the evaluations of the polynomial at the roots: \" << evals.transpose() << endl << endl;\n\n  cout.precision(10);\n  cout << \"The last root in float then in double: \" << psolvef.roots()[5] << \"\\t\" << psolve6d.roots()[5] << endl;\n  std::complex<float> castedRoot( psolve6d.roots()[5].real(), psolve6d.roots()[5].imag() );\n  cout << \"Norm of the difference: \" << std::abs( psolvef.roots()[5] - castedRoot ) << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/examples/PolynomialUtils1.cpp",
    "content": "#include <unsupported/Eigen/Polynomials>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  Vector4d roots = Vector4d::Random();\n  cout << \"Roots: \" << roots.transpose() << endl;\n  Eigen::Matrix<double,5,1> polynomial;\n  roots_to_monicPolynomial( roots, polynomial );\n  cout << \"Polynomial: \";\n  for( int i=0; i<4; ++i ){ cout << polynomial[i] << \".x^\" << i << \"+ \"; }\n  cout << polynomial[4] << \".x^4\" << endl;\n  Vector4d evaluation;\n  for( int i=0; i<4; ++i ){\n    evaluation[i] = poly_eval( polynomial, roots[i] ); }\n  cout << \"Evaluation of the polynomial at the roots: \" << evaluation.transpose();\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/examples/SYCL/CMakeLists.txt",
    "content": "FILE(GLOB examples_SRCS \"*.cpp\")\n\nset(EIGEN_SYCL ON)\nlist(APPEND CMAKE_EXE_LINKER_FLAGS -pthread)\nif(EIGEN_SYCL_TRISYCL)\n  set(CMAKE_CXX_STANDARD 17)\nelse(EIGEN_SYCL_TRISYCL)\n  if(MSVC)\n    # Set the host and device compilers C++ standard to C++14. On Windows setting this to C++11\n    # can cause issues with the ComputeCpp device compiler parsing Visual Studio Headers.\n    set(CMAKE_CXX_STANDARD 14)\n    list(APPEND COMPUTECPP_USER_FLAGS -DWIN32)\n  else()\n    set(CMAKE_CXX_STANDARD 11)\n    list(APPEND COMPUTECPP_USER_FLAGS -Wall)\n  endif()\n  # The following flags are not supported by Clang and can cause warnings\n  # if used with -Werror so they are removed here.\n  if(COMPUTECPP_USE_COMPILER_DRIVER)\n    set(CMAKE_CXX_COMPILER ${ComputeCpp_DEVICE_COMPILER_EXECUTABLE})\n    string(REPLACE \"-Wlogical-op\" \"\" CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS})\n    string(REPLACE \"-Wno-psabi\" \"\" CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS})\n  endif()\n  list(APPEND COMPUTECPP_USER_FLAGS\n      -DEIGEN_NO_ASSERTION_CHECKING=1\n      -no-serial-memop\n      -Xclang\n      -cl-mad-enable)\nendif(EIGEN_SYCL_TRISYCL)\n\nFOREACH(example_src ${examples_SRCS})\n  GET_FILENAME_COMPONENT(example ${example_src} NAME_WE)\n  ei_add_test_internal(${example} example_${example})\n  ADD_DEPENDENCIES(unsupported_examples example_${example})\nENDFOREACH(example_src)\nset(EIGEN_SYCL OFF)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/examples/SYCL/CwiseMul.cpp",
    "content": "#include <iostream>\n#define EIGEN_USE_SYCL\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\nint main()\n{\n  using DataType = float;\n  using IndexType = int64_t;\n  constexpr auto DataLayout = Eigen::RowMajor;\n\n  auto devices = Eigen::get_sycl_supported_devices();\n  const auto device_selector = *devices.begin();\n  Eigen::QueueInterface queueInterface(device_selector);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  \n  // create the tensors to be used in the operation\n  IndexType sizeDim1 = 3;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 3;\n  array<IndexType, 3> tensorRange = {{sizeDim1, sizeDim2, sizeDim3}};\n\n  // initialize the tensors with the data we want manipulate to\n  Tensor<DataType, 3,DataLayout, IndexType> in1(tensorRange);\n  Tensor<DataType, 3,DataLayout, IndexType> in2(tensorRange);\n  Tensor<DataType, 3,DataLayout, IndexType> out(tensorRange);\n\n  // set up some random data in the tensors to be multiplied\n  in1 = in1.random();\n  in2 = in2.random();\n\n  // allocate memory for the tensors\n  DataType * gpu_in1_data  = static_cast<DataType*>(sycl_device.allocate(in1.size()*sizeof(DataType)));\n  DataType * gpu_in2_data  = static_cast<DataType*>(sycl_device.allocate(in2.size()*sizeof(DataType)));\n  DataType * gpu_out_data =  static_cast<DataType*>(sycl_device.allocate(out.size()*sizeof(DataType)));\n\n  // \n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu_in1(gpu_in1_data, tensorRange);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu_in2(gpu_in2_data, tensorRange);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu_out(gpu_out_data, tensorRange);\n\n  // copy the memory to the device and do the c=a*b calculation\n  sycl_device.memcpyHostToDevice(gpu_in1_data, in1.data(),(in1.size())*sizeof(DataType));\n  sycl_device.memcpyHostToDevice(gpu_in2_data, in2.data(),(in2.size())*sizeof(DataType));\n  gpu_out.device(sycl_device) = gpu_in1 * gpu_in2;\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data,(out.size())*sizeof(DataType));\n  sycl_device.synchronize();\n\n  // print out the results\n   for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        std::cout << \"device_out\" << \"(\" << i << \", \" << j << \", \" << k << \") : \" << out(i,j,k) \n                  << \" vs host_out\" << \"(\" << i << \", \" << j << \", \" << k << \") : \" << in1(i,j,k) * in2(i,j,k) << \"\\n\";\n      }\n    }\n  }\n  printf(\"c=a*b Done\\n\");\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/doc/snippets/CMakeLists.txt",
    "content": "file(GLOB snippets_SRCS \"*.cpp\")\n\nadd_custom_target(unsupported_snippets)\n\nforeach(snippet_src ${snippets_SRCS})\n  get_filename_component(snippet ${snippet_src} NAME_WE)\n  set(compile_snippet_target compile_${snippet})\n  set(compile_snippet_src ${compile_snippet_target}.cpp)\n  file(READ ${snippet_src} snippet_source_code)\n  configure_file(${PROJECT_SOURCE_DIR}/doc/snippets/compile_snippet.cpp.in\n                 ${CMAKE_CURRENT_BINARY_DIR}/${compile_snippet_src})\n  add_executable(${compile_snippet_target}\n                 ${CMAKE_CURRENT_BINARY_DIR}/${compile_snippet_src})\n  if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO)\n    target_link_libraries(${compile_snippet_target} ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO})\n  endif()\n  add_custom_command(\n    TARGET ${compile_snippet_target}\n    POST_BUILD\n    COMMAND ${compile_snippet_target}\n    ARGS >${CMAKE_CURRENT_BINARY_DIR}/${snippet}.out\n  )\n  add_dependencies(unsupported_snippets ${compile_snippet_target})\n  set_source_files_properties(${CMAKE_CURRENT_BINARY_DIR}/${compile_snippet_src}\n                              PROPERTIES OBJECT_DEPENDS ${snippet_src})\nendforeach(snippet_src)\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/BVH.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Ilya Baran <ibaran@mit.edu>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/StdVector>\n#include <Eigen/Geometry>\n#include <unsupported/Eigen/BVH>\n\nnamespace Eigen {\n\ntemplate<typename Scalar, int Dim> AlignedBox<Scalar, Dim> bounding_box(const Matrix<Scalar, Dim, 1> &v) { return AlignedBox<Scalar, Dim>(v); }\n\n}\n\n\ntemplate<int Dim>\nstruct Ball\n{\nEIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(double, Dim)\n\n  typedef Matrix<double, Dim, 1> VectorType;\n\n  Ball() {}\n  Ball(const VectorType &c, double r) : center(c), radius(r) {}\n\n  VectorType center;\n  double radius;\n};\ntemplate<int Dim> AlignedBox<double, Dim> bounding_box(const Ball<Dim> &b)\n{ return AlignedBox<double, Dim>(b.center.array() - b.radius, b.center.array() + b.radius); }\n\ninline double SQR(double x) { return x * x; }\n\ntemplate<int Dim>\nstruct BallPointStuff //this class provides functions to be both an intersector and a minimizer, both for a ball and a point and for two trees\n{\n  typedef double Scalar;\n  typedef Matrix<double, Dim, 1> VectorType;\n  typedef Ball<Dim> BallType;\n  typedef AlignedBox<double, Dim> BoxType;\n\n  BallPointStuff() : calls(0), count(0) {}\n  BallPointStuff(const VectorType &inP) : p(inP), calls(0), count(0) {}\n\n\n  bool intersectVolume(const BoxType &r) { ++calls; return r.contains(p); }\n  bool intersectObject(const BallType &b) {\n    ++calls;\n    if((b.center - p).squaredNorm() < SQR(b.radius))\n      ++count;\n    return false; //continue\n  }\n\n  bool intersectVolumeVolume(const BoxType &r1, const BoxType &r2) { ++calls; return !(r1.intersection(r2)).isNull(); }\n  bool intersectVolumeObject(const BoxType &r, const BallType &b) { ++calls; return r.squaredExteriorDistance(b.center) < SQR(b.radius); }\n  bool intersectObjectVolume(const BallType &b, const BoxType &r) { ++calls; return r.squaredExteriorDistance(b.center) < SQR(b.radius); }\n  bool intersectObjectObject(const BallType &b1, const BallType &b2){\n    ++calls;\n    if((b1.center - b2.center).norm() < b1.radius + b2.radius)\n      ++count;\n    return false;\n  }\n  bool intersectVolumeObject(const BoxType &r, const VectorType &v) { ++calls; return r.contains(v); }\n  bool intersectObjectObject(const BallType &b, const VectorType &v){\n    ++calls;\n    if((b.center - v).squaredNorm() < SQR(b.radius))\n      ++count;\n    return false;\n  }\n\n  double minimumOnVolume(const BoxType &r) { ++calls; return r.squaredExteriorDistance(p); }\n  double minimumOnObject(const BallType &b) { ++calls; return (std::max)(0., (b.center - p).squaredNorm() - SQR(b.radius)); }\n  double minimumOnVolumeVolume(const BoxType &r1, const BoxType &r2) { ++calls; return r1.squaredExteriorDistance(r2); }\n  double minimumOnVolumeObject(const BoxType &r, const BallType &b) { ++calls; return SQR((std::max)(0., r.exteriorDistance(b.center) - b.radius)); }\n  double minimumOnObjectVolume(const BallType &b, const BoxType &r) { ++calls; return SQR((std::max)(0., r.exteriorDistance(b.center) - b.radius)); }\n  double minimumOnObjectObject(const BallType &b1, const BallType &b2){ ++calls; return SQR((std::max)(0., (b1.center - b2.center).norm() - b1.radius - b2.radius)); }\n  double minimumOnVolumeObject(const BoxType &r, const VectorType &v) { ++calls; return r.squaredExteriorDistance(v); }\n  double minimumOnObjectObject(const BallType &b, const VectorType &v){ ++calls; return SQR((std::max)(0., (b.center - v).norm() - b.radius)); }\n\n  VectorType p;\n  int calls;\n  int count;\n};\n\n\ntemplate<int Dim>\nstruct TreeTest\n{\n  typedef Matrix<double, Dim, 1> VectorType;\n  typedef std::vector<VectorType, aligned_allocator<VectorType> > VectorTypeList;\n  typedef Ball<Dim> BallType;\n  typedef std::vector<BallType, aligned_allocator<BallType> > BallTypeList;\n  typedef AlignedBox<double, Dim> BoxType;\n\n  void testIntersect1()\n  {\n    BallTypeList b;\n    for(int i = 0; i < 500; ++i) {\n        b.push_back(BallType(VectorType::Random(), 0.5 * internal::random(0., 1.)));\n    }\n    KdBVH<double, Dim, BallType> tree(b.begin(), b.end());\n\n    VectorType pt = VectorType::Random();\n    BallPointStuff<Dim> i1(pt), i2(pt);\n\n    for(int i = 0; i < (int)b.size(); ++i)\n      i1.intersectObject(b[i]);\n\n    BVIntersect(tree, i2);\n\n    VERIFY(i1.count == i2.count);\n  }\n\n  void testMinimize1()\n  {\n    BallTypeList b;\n    for(int i = 0; i < 500; ++i) {\n        b.push_back(BallType(VectorType::Random(), 0.01 * internal::random(0., 1.)));\n    }\n    KdBVH<double, Dim, BallType> tree(b.begin(), b.end());\n\n    VectorType pt = VectorType::Random();\n    BallPointStuff<Dim> i1(pt), i2(pt);\n\n    double m1 = (std::numeric_limits<double>::max)(), m2 = m1;\n\n    for(int i = 0; i < (int)b.size(); ++i)\n      m1 = (std::min)(m1, i1.minimumOnObject(b[i]));\n\n    m2 = BVMinimize(tree, i2);\n\n    VERIFY_IS_APPROX(m1, m2);\n  }\n\n  void testIntersect2()\n  {\n    BallTypeList b;\n    VectorTypeList v;\n\n    for(int i = 0; i < 50; ++i) {\n        b.push_back(BallType(VectorType::Random(), 0.5 * internal::random(0., 1.)));\n        for(int j = 0; j < 3; ++j)\n            v.push_back(VectorType::Random());\n    }\n\n    KdBVH<double, Dim, BallType> tree(b.begin(), b.end());\n    KdBVH<double, Dim, VectorType> vTree(v.begin(), v.end());\n\n    BallPointStuff<Dim> i1, i2;\n\n    for(int i = 0; i < (int)b.size(); ++i)\n        for(int j = 0; j < (int)v.size(); ++j)\n            i1.intersectObjectObject(b[i], v[j]);\n\n    BVIntersect(tree, vTree, i2);\n\n    VERIFY(i1.count == i2.count);\n  }\n\n  void testMinimize2()\n  {\n    BallTypeList b;\n    VectorTypeList v;\n\n    for(int i = 0; i < 50; ++i) {\n        b.push_back(BallType(VectorType::Random(), 1e-7 + 1e-6 * internal::random(0., 1.)));\n        for(int j = 0; j < 3; ++j)\n            v.push_back(VectorType::Random());\n    }\n\n    KdBVH<double, Dim, BallType> tree(b.begin(), b.end());\n    KdBVH<double, Dim, VectorType> vTree(v.begin(), v.end());\n\n    BallPointStuff<Dim> i1, i2;\n\n    double m1 = (std::numeric_limits<double>::max)(), m2 = m1;\n\n    for(int i = 0; i < (int)b.size(); ++i)\n        for(int j = 0; j < (int)v.size(); ++j)\n            m1 = (std::min)(m1, i1.minimumOnObjectObject(b[i], v[j]));\n\n    m2 = BVMinimize(tree, vTree, i2);\n\n    VERIFY_IS_APPROX(m1, m2);\n  }\n};\n\n\nEIGEN_DECLARE_TEST(BVH)\n{\n  for(int i = 0; i < g_repeat; i++) {\n#ifdef EIGEN_TEST_PART_1\n    TreeTest<2> test2;\n    CALL_SUBTEST(test2.testIntersect1());\n    CALL_SUBTEST(test2.testMinimize1());\n    CALL_SUBTEST(test2.testIntersect2());\n    CALL_SUBTEST(test2.testMinimize2());\n#endif\n\n#ifdef EIGEN_TEST_PART_2\n    TreeTest<3> test3;\n    CALL_SUBTEST(test3.testIntersect1());\n    CALL_SUBTEST(test3.testMinimize1());\n    CALL_SUBTEST(test3.testIntersect2());\n    CALL_SUBTEST(test3.testMinimize2());\n#endif\n\n#ifdef EIGEN_TEST_PART_3\n    TreeTest<4> test4;\n    CALL_SUBTEST(test4.testIntersect1());\n    CALL_SUBTEST(test4.testMinimize1());\n    CALL_SUBTEST(test4.testIntersect2());\n    CALL_SUBTEST(test4.testMinimize2());\n#endif\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/CMakeLists.txt",
    "content": "# The file split_test_helper.h was generated at first run,\n# it is now included in test/\nif(EXISTS ${CMAKE_CURRENT_BINARY_DIR}/split_test_helper.h)\n  file(REMOVE ${CMAKE_CURRENT_BINARY_DIR}/split_test_helper.h)\nendif()\n\nset_property(GLOBAL PROPERTY EIGEN_CURRENT_SUBPROJECT \"Unsupported\")\nadd_custom_target(BuildUnsupported)\n\ninclude_directories(../../test ../../unsupported ../../Eigen\n                    ${CMAKE_CURRENT_BINARY_DIR}/../../test)\n\nfind_package (Threads)\n\nfind_package(GoogleHash)\nif(GoogleHash_FOUND)\n  add_definitions(\"-DEIGEN_GOOGLEHASH_SUPPORT\")\n  include_directories(${GOOGLEHASH_INCLUDES})\n  ei_add_property(EIGEN_TESTED_BACKENDS  \"GoogleHash, \")\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS  \"GoogleHash, \")\nendif()\n\n\nfind_package(Adolc)\nif(Adolc_FOUND)\n  include_directories(${ADOLC_INCLUDES})\n  ei_add_property(EIGEN_TESTED_BACKENDS \"Adolc, \")\n  ei_add_test(forward_adolc \"\" ${ADOLC_LIBRARIES})\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS \"Adolc, \")\nendif()\n\n# this test seems to never have been successful on x87, so is considered to contain a FP-related bug.\n# see thread: \"non-linear optimization test summary\"\nei_add_test(NonLinearOptimization)\n\nei_add_test(NumericalDiff)\nei_add_test(autodiff_scalar)\nei_add_test(autodiff)\n\nei_add_test(BVH)\n\nei_add_test(matrix_exponential)\nei_add_test(matrix_function)\nei_add_test(matrix_power)\nei_add_test(matrix_square_root)\nei_add_test(alignedvector3)\n\nei_add_test(FFT)\n\nei_add_test(EulerAngles)\n\nfind_package(MPREAL)\nif(MPREAL_FOUND)\n  ei_add_property(EIGEN_TESTED_BACKENDS \"MPFR C++, \")\n  include_directories(${MPREAL_INCLUDES})\n  ei_add_test(mpreal_support \"\" \"${MPREAL_LIBRARIES}\" )\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS \"MPFR C++, \")\nendif()\n\nei_add_test(sparse_extra   \"\" \"\")\n\nfind_package(FFTW)\nif(FFTW_FOUND)\n  ei_add_property(EIGEN_TESTED_BACKENDS \"fftw, \")\n  include_directories( ${FFTW_INCLUDES} )\n  if(FFTWL_LIB)\n    ei_add_test(FFTW  \"-DEIGEN_FFTW_DEFAULT -DEIGEN_HAS_FFTWL\" \"${FFTW_LIBRARIES}\" )\n  else()\n    ei_add_test(FFTW  \"-DEIGEN_FFTW_DEFAULT\" \"${FFTW_LIBRARIES}\" )\n  endif()\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS \"fftw, \")\nendif()\n\noption(EIGEN_TEST_OPENGL \"Enable OpenGL support in unit tests\" OFF)\nif(EIGEN_TEST_OPENGL)\n  find_package(OpenGL)\n  find_package(GLUT)\n  find_package(GLEW)\n  if(OPENGL_FOUND AND GLUT_FOUND AND GLEW_FOUND)\n    include_directories(${OPENGL_INCLUDE_DIR} ${GLUT_INCLUDE_DIR} ${GLEW_INCLUDE_DIRS})\n    ei_add_property(EIGEN_TESTED_BACKENDS \"OpenGL, \")\n    set(EIGEN_GL_LIB ${GLUT_LIBRARIES} ${GLEW_LIBRARIES} ${OPENGL_LIBRARIES})\n    ei_add_test(openglsupport  \"\" \"${EIGEN_GL_LIB}\" )\n  else()\n    ei_add_property(EIGEN_MISSING_BACKENDS \"OpenGL, \")\n  endif()\nelse()\n    ei_add_property(EIGEN_MISSING_BACKENDS \"OpenGL, \")\nendif()\n\nei_add_test(polynomialsolver)\nei_add_test(polynomialutils)\nei_add_test(splines)\nei_add_test(gmres)\nei_add_test(dgmres)\nei_add_test(minres)\nei_add_test(idrs)\nei_add_test(levenberg_marquardt)\nei_add_test(kronecker_product)\nei_add_test(bessel_functions)\nei_add_test(special_functions)\nei_add_test(special_packetmath \"-DEIGEN_FAST_MATH=1\")\n\nif(EIGEN_TEST_CXX11)\n  if(EIGEN_TEST_SYCL)\n    set(EIGEN_SYCL ON)\n    # Forward CMake options as preprocessor definitions\n    if(EIGEN_SYCL_USE_DEFAULT_SELECTOR)\n      add_definitions(-DEIGEN_SYCL_USE_DEFAULT_SELECTOR=${EIGEN_SYCL_USE_DEFAULT_SELECTOR})\n    endif()\n    if(EIGEN_SYCL_NO_LOCAL_MEM)\n      add_definitions(-DEIGEN_SYCL_NO_LOCAL_MEM=${EIGEN_SYCL_NO_LOCAL_MEM})\n    endif()\n    if(EIGEN_SYCL_LOCAL_MEM)\n      add_definitions(-DEIGEN_SYCL_LOCAL_MEM=${EIGEN_SYCL_LOCAL_MEM})\n    endif()\n    if(EIGEN_SYCL_MAX_GLOBAL_RANGE)\n      add_definitions(-DEIGEN_SYCL_MAX_GLOBAL_RANGE=${EIGEN_SYCL_MAX_GLOBAL_RANGE})\n    endif()\n    if(EIGEN_SYCL_LOCAL_THREAD_DIM0)\n      add_definitions(-DEIGEN_SYCL_LOCAL_THREAD_DIM0=${EIGEN_SYCL_LOCAL_THREAD_DIM0})\n    endif()\n    if(EIGEN_SYCL_LOCAL_THREAD_DIM1)\n      add_definitions(-DEIGEN_SYCL_LOCAL_THREAD_DIM1=${EIGEN_SYCL_LOCAL_THREAD_DIM1})\n    endif()\n    if(EIGEN_SYCL_REG_M)\n      add_definitions(-DEIGEN_SYCL_REG_M=${EIGEN_SYCL_REG_M})\n    endif()\n    if(EIGEN_SYCL_REG_N)\n      add_definitions(-DEIGEN_SYCL_REG_N=${EIGEN_SYCL_REG_N})\n    endif()\n    if(EIGEN_SYCL_USE_PROGRAM_CLASS)\n      add_definitions(-DEIGEN_SYCL_USE_PROGRAM_CLASS=${EIGEN_SYCL_USE_PROGRAM_CLASS})\n    endif()\n    if(EIGEN_SYCL_ASYNC_EXECUTION)\n      add_definitions(-DEIGEN_SYCL_ASYNC_EXECUTION=${EIGEN_SYCL_ASYNC_EXECUTION})\n    endif()\n    if(EIGEN_SYCL_DISABLE_SKINNY)\n      add_definitions(-DEIGEN_SYCL_DISABLE_SKINNY=${EIGEN_SYCL_DISABLE_SKINNY})\n    endif()\n    if(EIGEN_SYCL_DISABLE_DOUBLE_BUFFER)\n      add_definitions(-DEIGEN_SYCL_DISABLE_DOUBLE_BUFFER=${EIGEN_SYCL_DISABLE_DOUBLE_BUFFER})\n    endif()\n    if(EIGEN_SYCL_DISABLE_RANK1)\n      add_definitions(-DEIGEN_SYCL_DISABLE_RANK1=${EIGEN_SYCL_DISABLE_RANK1})\n    endif()\n    if(EIGEN_SYCL_DISABLE_SCALAR)\n      add_definitions(-DEIGEN_SYCL_DISABLE_SCALAR=${EIGEN_SYCL_DISABLE_SCALAR})\n    endif()\n    if(EIGEN_SYCL_DISABLE_GEMV)\n      add_definitions(-DEIGEN_SYCL_DISABLE_GEMV=${EIGEN_SYCL_DISABLE_GEMV})\n    endif()\n    if(EIGEN_SYCL_DISABLE_ARM_GPU_CACHE_OPTIMISATION)\n      add_definitions(-DEIGEN_SYCL_DISABLE_ARM_GPU_CACHE_OPTIMISATION=${EIGEN_SYCL_DISABLE_ARM_GPU_CACHE_OPTIMISATION})\n    endif()\n\n    if(EIGEN_SYCL_TRISYCL)\n      # triSYCL now requires c++17.\n      set(CMAKE_CXX_STANDARD 17)\n    else()\n      if(MSVC)\n        # Set the host and device compilers C++ standard to C++14. On Windows setting this to C++11\n        # can cause issues with the ComputeCpp device compiler parsing Visual Studio Headers.\n        set(CMAKE_CXX_STANDARD 14)\n        list(APPEND COMPUTECPP_USER_FLAGS -DWIN32)\n      else()\n        set(CMAKE_CXX_STANDARD 11)\n        list(APPEND COMPUTECPP_USER_FLAGS -Wall)\n      endif()\n      # The following flags are not supported by Clang and can cause warnings\n      # if used with -Werror so they are removed here.\n      if(COMPUTECPP_USE_COMPILER_DRIVER)\n        set(CMAKE_CXX_COMPILER ${ComputeCpp_DEVICE_COMPILER_EXECUTABLE})\n        string(REPLACE \"-Wlogical-op\" \"\" CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS})\n        string(REPLACE \"-Wno-psabi\" \"\" CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS})\n      endif()\n      list(APPEND COMPUTECPP_USER_FLAGS\n          -DEIGEN_NO_ASSERTION_CHECKING=1\n          -no-serial-memop\n          -Xclang\n          -cl-mad-enable)\n    endif()\n\n    ei_add_test(cxx11_tensor_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_image_op_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_math_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_forced_eval_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_broadcast_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_device_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_reduction_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_morphing_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_shuffling_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_padding_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_builtins_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_contract_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_concatenation_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_reverse_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_convolution_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_striding_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_chipping_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_layout_swap_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_inflation_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_random_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_generator_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_patch_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_image_patch_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_volume_patch_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_argmax_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_custom_op_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_scan_sycl ${STD_CXX_FLAG})\n    set(EIGEN_SYCL OFF)\n  endif()\n\n  ei_add_test(cxx11_eventcount \"-pthread\" \"${CMAKE_THREAD_LIBS_INIT}\")\n  ei_add_test(cxx11_runqueue \"-pthread\" \"${CMAKE_THREAD_LIBS_INIT}\")\n  ei_add_test(cxx11_non_blocking_thread_pool \"-pthread\" \"${CMAKE_THREAD_LIBS_INIT}\")\n\n  ei_add_test(cxx11_meta)\n  ei_add_test(cxx11_maxsizevector)\n  ei_add_test(cxx11_tensor_argmax)\n  ei_add_test(cxx11_tensor_assign)\n  ei_add_test(cxx11_tensor_block_access)\n  ei_add_test(cxx11_tensor_block_eval)\n  ei_add_test(cxx11_tensor_block_io)\n  ei_add_test(cxx11_tensor_broadcasting)\n  ei_add_test(cxx11_tensor_casts)\n  ei_add_test(cxx11_tensor_chipping)\n  ei_add_test(cxx11_tensor_comparisons)\n  ei_add_test(cxx11_tensor_concatenation)\n  ei_add_test(cxx11_tensor_const)\n  ei_add_test(cxx11_tensor_contraction)\n  ei_add_test(cxx11_tensor_convolution)\n  ei_add_test(cxx11_tensor_custom_index)\n  ei_add_test(cxx11_tensor_custom_op)\n  ei_add_test(cxx11_tensor_dimension)\n  ei_add_test(cxx11_tensor_empty)\n  ei_add_test(cxx11_tensor_executor \"-pthread\" \"${CMAKE_THREAD_LIBS_INIT}\")\n  ei_add_test(cxx11_tensor_expr)\n  ei_add_test(cxx11_tensor_fft)\n  ei_add_test(cxx11_tensor_fixed_size)\n  ei_add_test(cxx11_tensor_forced_eval)\n  ei_add_test(cxx11_tensor_generator)\n  ei_add_test(cxx11_tensor_ifft)\n  ei_add_test(cxx11_tensor_image_patch)\n  ei_add_test(cxx11_tensor_index_list)\n  ei_add_test(cxx11_tensor_inflation)\n  ei_add_test(cxx11_tensor_intdiv)\n  ei_add_test(cxx11_tensor_io)\n  ei_add_test(cxx11_tensor_layout_swap)\n  ei_add_test(cxx11_tensor_lvalue)\n  ei_add_test(cxx11_tensor_map)\n  ei_add_test(cxx11_tensor_math)\n  ei_add_test(cxx11_tensor_mixed_indices)\n  ei_add_test(cxx11_tensor_morphing)\n  ei_add_test(cxx11_tensor_move)\n  ei_add_test(cxx11_tensor_notification \"-pthread\" \"${CMAKE_THREAD_LIBS_INIT}\")\n  ei_add_test(cxx11_tensor_of_complex)\n  ei_add_test(cxx11_tensor_of_const_values)\n  ei_add_test(cxx11_tensor_of_strings)\n  ei_add_test(cxx11_tensor_padding)\n  ei_add_test(cxx11_tensor_patch)\n  ei_add_test(cxx11_tensor_random)\n  ei_add_test(cxx11_tensor_reduction)\n  ei_add_test(cxx11_tensor_ref)\n  ei_add_test(cxx11_tensor_roundings)\n  ei_add_test(cxx11_tensor_scan)\n  ei_add_test(cxx11_tensor_shuffling)\n  ei_add_test(cxx11_tensor_simple)\n  ei_add_test(cxx11_tensor_striding)\n  ei_add_test(cxx11_tensor_sugar)\n  ei_add_test(cxx11_tensor_thread_local \"-pthread\" \"${CMAKE_THREAD_LIBS_INIT}\")\n  ei_add_test(cxx11_tensor_thread_pool \"-pthread\" \"${CMAKE_THREAD_LIBS_INIT}\")\n  ei_add_test(cxx11_tensor_trace)\n  ei_add_test(cxx11_tensor_volume_patch)\n  #  ei_add_test(cxx11_tensor_symmetry)\n  if(\"${CMAKE_SIZEOF_VOID_P}\" EQUAL \"8\" AND NOT CMAKE_CXX_COMPILER_ID STREQUAL \"MSVC\")\n    # This test requires __uint128_t which is only available on 64bit systems\n    ei_add_test(cxx11_tensor_uint128)\n  endif()\n\nendif()\n\n# These tests needs nvcc\nfind_package(CUDA 7.0)\nif(CUDA_FOUND AND EIGEN_TEST_CUDA)\n  # Make sure to compile without the -pedantic, -Wundef, -Wnon-virtual-dtor\n  # and -fno-check-new flags since they trigger thousands of compilation warnings\n  # in the CUDA runtime\n  string(REPLACE \"-pedantic\" \"\" CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS}\")\n  string(REPLACE \"-Wundef\" \"\" CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS}\")\n  string(REPLACE \"-Wnon-virtual-dtor\" \"\" CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS}\")\n  string(REPLACE \"-fno-check-new\" \"\" CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS}\")\n\n  message(STATUS \"Flags used to compile cuda code: \" ${CMAKE_CXX_FLAGS})\n\n  if(\"${CMAKE_CXX_COMPILER_ID}\" STREQUAL \"Clang\")\n    set(CUDA_NVCC_FLAGS \"-ccbin ${CMAKE_C_COMPILER}\" CACHE STRING \"nvcc flags\" FORCE)\n  endif()\n  if(EIGEN_TEST_CUDA_CLANG)\n    string(APPEND CMAKE_CXX_FLAGS \" --cuda-path=${CUDA_TOOLKIT_ROOT_DIR}\")\n    foreach(ARCH IN LISTS EIGEN_CUDA_COMPUTE_ARCH)\n        string(APPEND CMAKE_CXX_FLAGS \" --cuda-gpu-arch=sm_${ARCH}\")\n    endforeach()\n  endif()\n\n  set(EIGEN_CUDA_RELAXED_CONSTEXPR \"--expt-relaxed-constexpr\")\n  if (${CUDA_VERSION} STREQUAL \"7.0\")\n    set(EIGEN_CUDA_RELAXED_CONSTEXPR \"--relaxed-constexpr\")\n  endif()\n\n  set(NVCC_ARCH_FLAGS)\n  foreach(ARCH IN LISTS EIGEN_CUDA_COMPUTE_ARCH)\n    string(APPEND NVCC_ARCH_FLAGS \" -gencode arch=compute_${ARCH},code=sm_${ARCH}\")\n  endforeach()\n  set(CUDA_NVCC_FLAGS  \"${EIGEN_CUDA_RELAXED_CONSTEXPR} -Xcudafe \\\"--display_error_number\\\" ${NVCC_ARCH_FLAGS} ${CUDA_NVCC_FLAGS}\")\n  cuda_include_directories(\"${CMAKE_CURRENT_BINARY_DIR}\" \"${CUDA_TOOLKIT_ROOT_DIR}/include\")\n  set(EIGEN_ADD_TEST_FILENAME_EXTENSION \"cu\")\n\n  ei_add_test(cxx11_tensor_complex_gpu)\n  ei_add_test(cxx11_tensor_complex_cwise_ops_gpu)\n  ei_add_test(cxx11_tensor_reduction_gpu)\n  ei_add_test(cxx11_tensor_argmax_gpu)\n  ei_add_test(cxx11_tensor_cast_float16_gpu)\n  ei_add_test(cxx11_tensor_scan_gpu)\n\n  set(EIGEN_CUDA_OLDEST_COMPUTE_ARCH 9999)\n  foreach(ARCH IN LISTS EIGEN_CUDA_COMPUTE_ARCH)\n    if(${ARCH} LESS ${EIGEN_CUDA_OLDEST_COMPUTE_ARCH})\n      set(EIGEN_CUDA_OLDEST_COMPUTE_ARCH ${ARCH})\n    endif()\n  endforeach()\n\n  # Contractions require arch 3.0 or higher\n  if (${EIGEN_CUDA_OLDEST_COMPUTE_ARCH} GREATER 29)\n    ei_add_test(cxx11_tensor_device)\n    ei_add_test(cxx11_tensor_gpu)\n    ei_add_test(cxx11_tensor_contract_gpu)\n    ei_add_test(cxx11_tensor_of_float16_gpu)\n  endif()\n\n  # The random number generation code requires arch 3.5 or greater.\n  if (${EIGEN_CUDA_OLDEST_COMPUTE_ARCH} GREATER 34)\n    ei_add_test(cxx11_tensor_random_gpu)\n  endif()\n\n  unset(EIGEN_ADD_TEST_FILENAME_EXTENSION)\nendif()\n\n# Add HIP specific tests\nif (EIGEN_TEST_HIP)\n\n  set(HIP_PATH \"/opt/rocm/hip\" CACHE STRING \"Path to the HIP installation.\")\n\n  if (EXISTS ${HIP_PATH})\n    list(APPEND CMAKE_MODULE_PATH ${HIP_PATH}/cmake)\n\n    find_package(HIP REQUIRED)\n    if (HIP_FOUND)\n      execute_process(COMMAND ${HIP_PATH}/bin/hipconfig --platform OUTPUT_VARIABLE HIP_PLATFORM)\n\n      if ((${HIP_PLATFORM} STREQUAL \"hcc\") OR (${HIP_PLATFORM} STREQUAL \"amd\"))\n        include_directories(${CMAKE_CURRENT_BINARY_DIR})\n        include_directories(${HIP_PATH}/include)\n\n        set(EIGEN_ADD_TEST_FILENAME_EXTENSION  \"cu\")\n        #\n        # complex datatype is not yet supported by HIP\n        # so leaving out those tests for now\n        #\n        # ei_add_test(cxx11_tensor_complex_gpu)\n        # ei_add_test(cxx11_tensor_complex_cwise_ops_gpu)\n        #\n        ei_add_test(cxx11_tensor_reduction_gpu)\n        ei_add_test(cxx11_tensor_argmax_gpu)\n        ei_add_test(cxx11_tensor_cast_float16_gpu)\n        ei_add_test(cxx11_tensor_scan_gpu)\n        ei_add_test(cxx11_tensor_device)\n\n        ei_add_test(cxx11_tensor_gpu)\n        ei_add_test(cxx11_tensor_contract_gpu)\n        ei_add_test(cxx11_tensor_of_float16_gpu)\n        ei_add_test(cxx11_tensor_random_gpu)\n\n        unset(EIGEN_ADD_TEST_FILENAME_EXTENSION)\n\n      elseif ((${HIP_PLATFORM} STREQUAL \"nvcc\") OR (${HIP_PLATFORM} STREQUAL \"nvidia\"))\n        message(FATAL_ERROR \"HIP_PLATFORM = nvcc is not supported within Eigen\")\n      else ()\n        message(FATAL_ERROR \"Unknown HIP_PLATFORM = ${HIP_PLATFORM}\")\n      endif()\n    endif()\n  else ()\n    message(FATAL_ERROR \"EIGEN_TEST_HIP is ON, but the specified HIP_PATH (${HIP_PATH}) does not exist\")\n  endif()\n\nendif()\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/EulerAngles.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Tal Hadad <tal_hd@hotmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <unsupported/Eigen/EulerAngles>\n\nusing namespace Eigen;\n\n// Unfortunately, we need to specialize it in order to work. (We could add it in main.h test framework)\ntemplate <typename Scalar, class System>\nbool verifyIsApprox(const Eigen::EulerAngles<Scalar, System>& a, const Eigen::EulerAngles<Scalar, System>& b)\n{\n  return verifyIsApprox(a.angles(), b.angles());\n}\n\n// Verify that x is in the approxed range [a, b]\n#define VERIFY_APPROXED_RANGE(a, x, b) \\\n  do { \\\n  VERIFY_IS_APPROX_OR_LESS_THAN(a, x); \\\n  VERIFY_IS_APPROX_OR_LESS_THAN(x, b); \\\n  } while(0)\n\nconst char X = EULER_X;\nconst char Y = EULER_Y;\nconst char Z = EULER_Z;\n\ntemplate<typename Scalar, class EulerSystem>\nvoid verify_euler(const EulerAngles<Scalar, EulerSystem>& e)\n{\n  typedef EulerAngles<Scalar, EulerSystem> EulerAnglesType;\n  typedef Matrix<Scalar,3,3> Matrix3;\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef Quaternion<Scalar> QuaternionType;\n  typedef AngleAxis<Scalar> AngleAxisType;\n  \n  const Scalar ONE = Scalar(1);\n  const Scalar HALF_PI = Scalar(EIGEN_PI / 2);\n  const Scalar PI = Scalar(EIGEN_PI);\n  \n  // It's very important calc the acceptable precision depending on the distance from the pole.\n  const Scalar longitudeRadius = std::abs(\n    EulerSystem::IsTaitBryan ?\n    std::cos(e.beta()) :\n    std::sin(e.beta())\n    );\n  Scalar precision = test_precision<Scalar>() / longitudeRadius;\n  \n  Scalar betaRangeStart, betaRangeEnd;\n  if (EulerSystem::IsTaitBryan)\n  {\n    betaRangeStart = -HALF_PI;\n    betaRangeEnd = HALF_PI;\n  }\n  else\n  {\n    if (!EulerSystem::IsBetaOpposite)\n    {\n      betaRangeStart = 0;\n      betaRangeEnd = PI;\n    }\n    else\n    {\n      betaRangeStart = -PI;\n      betaRangeEnd = 0;\n    }\n  }\n  \n  const Vector3 I_ = EulerAnglesType::AlphaAxisVector();\n  const Vector3 J_ = EulerAnglesType::BetaAxisVector();\n  const Vector3 K_ = EulerAnglesType::GammaAxisVector();\n  \n  // Is approx checks\n  VERIFY(e.isApprox(e));\n  VERIFY_IS_APPROX(e, e);\n  VERIFY_IS_NOT_APPROX(e, EulerAnglesType(e.alpha() + ONE, e.beta() + ONE, e.gamma() + ONE));\n\n  const Matrix3 m(e);\n  VERIFY_IS_APPROX(Scalar(m.determinant()), ONE);\n\n  EulerAnglesType ebis(m);\n  \n  // When no roll(acting like polar representation), we have the best precision.\n  // One of those cases is when the Euler angles are on the pole, and because it's singular case,\n  //  the computation returns no roll.\n  if (ebis.beta() == 0)\n    precision = test_precision<Scalar>();\n  \n  // Check that eabis in range\n  VERIFY_APPROXED_RANGE(-PI, ebis.alpha(), PI);\n  VERIFY_APPROXED_RANGE(betaRangeStart, ebis.beta(), betaRangeEnd);\n  VERIFY_APPROXED_RANGE(-PI, ebis.gamma(), PI);\n\n  const Matrix3 mbis(AngleAxisType(ebis.alpha(), I_) * AngleAxisType(ebis.beta(), J_) * AngleAxisType(ebis.gamma(), K_));\n  VERIFY_IS_APPROX(Scalar(mbis.determinant()), ONE);\n  VERIFY_IS_APPROX(mbis, ebis.toRotationMatrix());\n  /*std::cout << \"===================\\n\" <<\n    \"e: \" << e << std::endl <<\n    \"eabis: \" << eabis.transpose() << std::endl <<\n    \"m: \" << m << std::endl <<\n    \"mbis: \" << mbis << std::endl <<\n    \"X: \" << (m * Vector3::UnitX()).transpose() << std::endl <<\n    \"X: \" << (mbis * Vector3::UnitX()).transpose() << std::endl;*/\n  VERIFY(m.isApprox(mbis, precision));\n\n  // Test if ea and eabis are the same\n  // Need to check both singular and non-singular cases\n  // There are two singular cases.\n  // 1. When I==K and sin(ea(1)) == 0\n  // 2. When I!=K and cos(ea(1)) == 0\n\n  // TODO: Make this test work well, and use range saturation function.\n  /*// If I==K, and ea[1]==0, then there no unique solution.\n  // The remark apply in the case where I!=K, and |ea[1]| is close to +-pi/2.\n  if( (i!=k || ea[1]!=0) && (i==k || !internal::isApprox(abs(ea[1]),Scalar(EIGEN_PI/2),test_precision<Scalar>())) ) \n      VERIFY_IS_APPROX(ea, eabis);*/\n  \n  // Quaternions\n  const QuaternionType q(e);\n  ebis = q;\n  const QuaternionType qbis(ebis);\n  VERIFY(internal::isApprox<Scalar>(std::abs(q.dot(qbis)), ONE, precision));\n  //VERIFY_IS_APPROX(eabis, eabis2);// Verify that the euler angles are still the same\n  \n  // A suggestion for simple product test when will be supported.\n  /*EulerAnglesType e2(PI/2, PI/2, PI/2);\n  Matrix3 m2(e2);\n  VERIFY_IS_APPROX(e*e2, m*m2);*/\n}\n\ntemplate<signed char A, signed char B, signed char C, typename Scalar>\nvoid verify_euler_vec(const Matrix<Scalar,3,1>& ea)\n{\n  verify_euler(EulerAngles<Scalar, EulerSystem<A, B, C> >(ea[0], ea[1], ea[2]));\n}\n\ntemplate<signed char A, signed char B, signed char C, typename Scalar>\nvoid verify_euler_all_neg(const Matrix<Scalar,3,1>& ea)\n{\n  verify_euler_vec<+A,+B,+C>(ea);\n  verify_euler_vec<+A,+B,-C>(ea);\n  verify_euler_vec<+A,-B,+C>(ea);\n  verify_euler_vec<+A,-B,-C>(ea);\n  \n  verify_euler_vec<-A,+B,+C>(ea);\n  verify_euler_vec<-A,+B,-C>(ea);\n  verify_euler_vec<-A,-B,+C>(ea);\n  verify_euler_vec<-A,-B,-C>(ea);\n}\n\ntemplate<typename Scalar> void check_all_var(const Matrix<Scalar,3,1>& ea)\n{\n  verify_euler_all_neg<X,Y,Z>(ea);\n  verify_euler_all_neg<X,Y,X>(ea);\n  verify_euler_all_neg<X,Z,Y>(ea);\n  verify_euler_all_neg<X,Z,X>(ea);\n  \n  verify_euler_all_neg<Y,Z,X>(ea);\n  verify_euler_all_neg<Y,Z,Y>(ea);\n  verify_euler_all_neg<Y,X,Z>(ea);\n  verify_euler_all_neg<Y,X,Y>(ea);\n  \n  verify_euler_all_neg<Z,X,Y>(ea);\n  verify_euler_all_neg<Z,X,Z>(ea);\n  verify_euler_all_neg<Z,Y,X>(ea);\n  verify_euler_all_neg<Z,Y,Z>(ea);\n}\n\ntemplate<typename Scalar> void check_singular_cases(const Scalar& singularBeta)\n{\n  typedef Matrix<Scalar,3,1> Vector3;\n  const Scalar PI = Scalar(EIGEN_PI);\n  \n  for (Scalar epsilon = NumTraits<Scalar>::epsilon(); epsilon < 1; epsilon *= Scalar(1.2))\n  {\n    check_all_var(Vector3(PI/4, singularBeta, PI/3));\n    check_all_var(Vector3(PI/4, singularBeta - epsilon, PI/3));\n    check_all_var(Vector3(PI/4, singularBeta - Scalar(1.5)*epsilon, PI/3));\n    check_all_var(Vector3(PI/4, singularBeta - 2*epsilon, PI/3));\n    check_all_var(Vector3(PI*Scalar(0.8), singularBeta - epsilon, Scalar(0.9)*PI));\n    check_all_var(Vector3(PI*Scalar(-0.9), singularBeta + epsilon, PI*Scalar(0.3)));\n    check_all_var(Vector3(PI*Scalar(-0.6), singularBeta + Scalar(1.5)*epsilon, PI*Scalar(0.3)));\n    check_all_var(Vector3(PI*Scalar(-0.5), singularBeta + 2*epsilon, PI*Scalar(0.4)));\n    check_all_var(Vector3(PI*Scalar(0.9), singularBeta + epsilon, Scalar(0.8)*PI));\n  }\n  \n  // This one for sanity, it had a problem with near pole cases in float scalar.\n  check_all_var(Vector3(PI*Scalar(0.8), singularBeta - Scalar(1E-6), Scalar(0.9)*PI));\n}\n\ntemplate<typename Scalar> void eulerangles_manual()\n{\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef Matrix<Scalar,Dynamic,1> VectorX;\n  const Vector3 Zero = Vector3::Zero();\n  const Scalar PI = Scalar(EIGEN_PI);\n  \n  check_all_var(Zero);\n  \n  // singular cases\n  check_singular_cases(PI/2);\n  check_singular_cases(-PI/2);\n  \n  check_singular_cases(Scalar(0));\n  check_singular_cases(Scalar(-0));\n  \n  check_singular_cases(PI);\n  check_singular_cases(-PI);\n  \n  // non-singular cases\n  VectorX alpha = VectorX::LinSpaced(20, Scalar(-0.99) * PI, PI);\n  VectorX beta =  VectorX::LinSpaced(20, Scalar(-0.49) * PI, Scalar(0.49) * PI);\n  VectorX gamma = VectorX::LinSpaced(20, Scalar(-0.99) * PI, PI);\n  for (int i = 0; i < alpha.size(); ++i) {\n    for (int j = 0; j < beta.size(); ++j) {\n      for (int k = 0; k < gamma.size(); ++k) {\n        check_all_var(Vector3(alpha(i), beta(j), gamma(k)));\n      }\n    }\n  }\n}\n\ntemplate<typename Scalar> void eulerangles_rand()\n{\n  typedef Matrix<Scalar,3,3> Matrix3;\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef Array<Scalar,3,1> Array3;\n  typedef Quaternion<Scalar> Quaternionx;\n  typedef AngleAxis<Scalar> AngleAxisType;\n\n  Scalar a = internal::random<Scalar>(-Scalar(EIGEN_PI), Scalar(EIGEN_PI));\n  Quaternionx q1;\n  q1 = AngleAxisType(a, Vector3::Random().normalized());\n  Matrix3 m;\n  m = q1;\n  \n  Vector3 ea = m.eulerAngles(0,1,2);\n  check_all_var(ea);\n  ea = m.eulerAngles(0,1,0);\n  check_all_var(ea);\n  \n  // Check with purely random Quaternion:\n  q1.coeffs() = Quaternionx::Coefficients::Random().normalized();\n  m = q1;\n  ea = m.eulerAngles(0,1,2);\n  check_all_var(ea);\n  ea = m.eulerAngles(0,1,0);\n  check_all_var(ea);\n  \n  // Check with random angles in range [0:pi]x[-pi:pi]x[-pi:pi].\n  ea = (Array3::Random() + Array3(1,0,0))*Scalar(EIGEN_PI)*Array3(0.5,1,1);\n  check_all_var(ea);\n  \n  ea[2] = ea[0] = internal::random<Scalar>(0,Scalar(EIGEN_PI));\n  check_all_var(ea);\n  \n  ea[0] = ea[1] = internal::random<Scalar>(0,Scalar(EIGEN_PI));\n  check_all_var(ea);\n  \n  ea[1] = 0;\n  check_all_var(ea);\n  \n  ea.head(2).setZero();\n  check_all_var(ea);\n  \n  ea.setZero();\n  check_all_var(ea);\n}\n\nEIGEN_DECLARE_TEST(EulerAngles)\n{\n  // Simple cast test\n  EulerAnglesXYZd onesEd(1, 1, 1);\n  EulerAnglesXYZf onesEf = onesEd.cast<float>();\n  VERIFY_IS_APPROX(onesEd, onesEf.cast<double>());\n\n  // Simple Construction from Vector3 test\n  VERIFY_IS_APPROX(onesEd, EulerAnglesXYZd(Vector3d::Ones()));\n  \n  CALL_SUBTEST_1( eulerangles_manual<float>() );\n  CALL_SUBTEST_2( eulerangles_manual<double>() );\n  \n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_3( eulerangles_rand<float>() );\n    CALL_SUBTEST_4( eulerangles_rand<double>() );\n  }\n  \n  // TODO: Add tests for auto diff\n  // TODO: Add tests for complex numbers\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/FFT.cpp",
    "content": "#define test_FFTW test_FFT\n#include \"FFTW.cpp\"\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/FFTW.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Mark Borgerding mark a borgerding net\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <unsupported/Eigen/FFT>\n\ntemplate <typename T> \nstd::complex<T> RandomCpx() { return std::complex<T>( (T)(rand()/(T)RAND_MAX - .5), (T)(rand()/(T)RAND_MAX - .5) ); }\n\nusing namespace std;\nusing namespace Eigen;\n\n\ntemplate < typename T>\ncomplex<long double>  promote(complex<T> x) { return complex<long double>((long double)x.real(),(long double)x.imag()); }\n\ncomplex<long double>  promote(float x) { return complex<long double>((long double)x); }\ncomplex<long double>  promote(double x) { return complex<long double>((long double)x); }\ncomplex<long double>  promote(long double x) { return complex<long double>((long double)x); }\n    \n\n    template <typename VT1,typename VT2>\n    long double fft_rmse( const VT1 & fftbuf,const VT2 & timebuf)\n    {\n        long double totalpower=0;\n        long double difpower=0;\n        long double pi = acos((long double)-1 );\n        for (size_t k0=0;k0<(size_t)fftbuf.size();++k0) {\n            complex<long double> acc = 0;\n            long double phinc = (long double)(-2.)*k0* pi / timebuf.size();\n            for (size_t k1=0;k1<(size_t)timebuf.size();++k1) {\n                acc +=  promote( timebuf[k1] ) * exp( complex<long double>(0,k1*phinc) );\n            }\n            totalpower += numext::abs2(acc);\n            complex<long double> x = promote(fftbuf[k0]); \n            complex<long double> dif = acc - x;\n            difpower += numext::abs2(dif);\n            //cerr << k0 << \"\\t\" << acc << \"\\t\" <<  x << \"\\t\" << sqrt(numext::abs2(dif)) << endl;\n        }\n        cerr << \"rmse:\" << sqrt(difpower/totalpower) << endl;\n        return sqrt(difpower/totalpower);\n    }\n\n    template <typename VT1,typename VT2>\n    long double dif_rmse( const VT1 buf1,const VT2 buf2)\n    {\n        long double totalpower=0;\n        long double difpower=0;\n        size_t n = (min)( buf1.size(),buf2.size() );\n        for (size_t k=0;k<n;++k) {\n            totalpower += (long double)((numext::abs2( buf1[k] ) + numext::abs2(buf2[k]) )/2);\n            difpower += (long double)(numext::abs2(buf1[k] - buf2[k]));\n        }\n        return sqrt(difpower/totalpower);\n    }\n\nenum { StdVectorContainer, EigenVectorContainer };\n\ntemplate<int Container, typename Scalar> struct VectorType;\n\ntemplate<typename Scalar> struct VectorType<StdVectorContainer,Scalar>\n{\n  typedef vector<Scalar> type;\n};\n\ntemplate<typename Scalar> struct VectorType<EigenVectorContainer,Scalar>\n{\n  typedef Matrix<Scalar,Dynamic,1> type;\n};\n\ntemplate <int Container, typename T>\nvoid test_scalar_generic(int nfft)\n{\n    typedef typename FFT<T>::Complex Complex;\n    typedef typename FFT<T>::Scalar Scalar;\n    typedef typename VectorType<Container,Scalar>::type ScalarVector;\n    typedef typename VectorType<Container,Complex>::type ComplexVector;\n\n    FFT<T> fft;\n    ScalarVector tbuf(nfft);\n    ComplexVector freqBuf;\n    for (int k=0;k<nfft;++k)\n        tbuf[k]= (T)( rand()/(double)RAND_MAX - .5);\n\n    // make sure it DOESN'T give the right full spectrum answer\n    // if we've asked for half-spectrum\n    fft.SetFlag(fft.HalfSpectrum );\n    fft.fwd( freqBuf,tbuf);\n    VERIFY((size_t)freqBuf.size() == (size_t)( (nfft>>1)+1) );\n    VERIFY( T(fft_rmse(freqBuf,tbuf)) < test_precision<T>()  );// gross check\n\n    fft.ClearFlag(fft.HalfSpectrum );\n    fft.fwd( freqBuf,tbuf);\n    VERIFY( (size_t)freqBuf.size() == (size_t)nfft);\n    VERIFY( T(fft_rmse(freqBuf,tbuf)) < test_precision<T>()  );// gross check\n\n    if (nfft&1)\n        return; // odd FFTs get the wrong size inverse FFT\n\n    ScalarVector tbuf2;\n    fft.inv( tbuf2 , freqBuf);\n    VERIFY( T(dif_rmse(tbuf,tbuf2)) < test_precision<T>()  );// gross check\n\n\n    // verify that the Unscaled flag takes effect\n    ScalarVector tbuf3;\n    fft.SetFlag(fft.Unscaled);\n\n    fft.inv( tbuf3 , freqBuf);\n\n    for (int k=0;k<nfft;++k)\n        tbuf3[k] *= T(1./nfft);\n\n\n    //for (size_t i=0;i<(size_t) tbuf.size();++i)\n    //    cout << \"freqBuf=\" << freqBuf[i] << \" in2=\" << tbuf3[i] << \" -  in=\" << tbuf[i] << \" => \" << (tbuf3[i] - tbuf[i] ) <<  endl;\n\n    VERIFY( T(dif_rmse(tbuf,tbuf3)) < test_precision<T>()  );// gross check\n\n    // verify that ClearFlag works\n    fft.ClearFlag(fft.Unscaled);\n    fft.inv( tbuf2 , freqBuf);\n    VERIFY( T(dif_rmse(tbuf,tbuf2)) < test_precision<T>()  );// gross check\n}\n\ntemplate <typename T>\nvoid test_scalar(int nfft)\n{\n  test_scalar_generic<StdVectorContainer,T>(nfft);\n  //test_scalar_generic<EigenVectorContainer,T>(nfft);\n}\n\n\ntemplate <int Container, typename T>\nvoid test_complex_generic(int nfft)\n{\n    typedef typename FFT<T>::Complex Complex;\n    typedef typename VectorType<Container,Complex>::type ComplexVector;\n\n    FFT<T> fft;\n\n    ComplexVector inbuf(nfft);\n    ComplexVector outbuf;\n    ComplexVector buf3;\n    for (int k=0;k<nfft;++k)\n        inbuf[k]= Complex( (T)(rand()/(double)RAND_MAX - .5), (T)(rand()/(double)RAND_MAX - .5) );\n    fft.fwd( outbuf , inbuf);\n\n    VERIFY( T(fft_rmse(outbuf,inbuf)) < test_precision<T>()  );// gross check\n    fft.inv( buf3 , outbuf);\n\n    VERIFY( T(dif_rmse(inbuf,buf3)) < test_precision<T>()  );// gross check\n\n    // verify that the Unscaled flag takes effect\n    ComplexVector buf4;\n    fft.SetFlag(fft.Unscaled);\n    fft.inv( buf4 , outbuf);\n    for (int k=0;k<nfft;++k)\n        buf4[k] *= T(1./nfft);\n    VERIFY( T(dif_rmse(inbuf,buf4)) < test_precision<T>()  );// gross check\n\n    // verify that ClearFlag works\n    fft.ClearFlag(fft.Unscaled);\n    fft.inv( buf3 , outbuf);\n    VERIFY( T(dif_rmse(inbuf,buf3)) < test_precision<T>()  );// gross check\n}\n\ntemplate <typename T>\nvoid test_complex(int nfft)\n{\n  test_complex_generic<StdVectorContainer,T>(nfft);\n  test_complex_generic<EigenVectorContainer,T>(nfft);\n}\n/*\ntemplate <typename T,int nrows,int ncols>\nvoid test_complex2d()\n{\n    typedef typename Eigen::FFT<T>::Complex Complex;\n    FFT<T> fft;\n    Eigen::Matrix<Complex,nrows,ncols> src,src2,dst,dst2;\n\n    src = Eigen::Matrix<Complex,nrows,ncols>::Random();\n    //src =  Eigen::Matrix<Complex,nrows,ncols>::Identity();\n\n    for (int k=0;k<ncols;k++) {\n        Eigen::Matrix<Complex,nrows,1> tmpOut;\n        fft.fwd( tmpOut,src.col(k) );\n        dst2.col(k) = tmpOut;\n    }\n\n    for (int k=0;k<nrows;k++) {\n        Eigen::Matrix<Complex,1,ncols> tmpOut;\n        fft.fwd( tmpOut,  dst2.row(k) );\n        dst2.row(k) = tmpOut;\n    }\n\n    fft.fwd2(dst.data(),src.data(),ncols,nrows);\n    fft.inv2(src2.data(),dst.data(),ncols,nrows);\n    VERIFY( (src-src2).norm() < test_precision<T>() );\n    VERIFY( (dst-dst2).norm() < test_precision<T>() );\n}\n*/\n\n\nvoid test_return_by_value(int len)\n{\n    VectorXf in;\n    VectorXf in1;\n    in.setRandom( len );\n    VectorXcf out1,out2;\n    FFT<float> fft;\n\n    fft.SetFlag(fft.HalfSpectrum );\n\n    fft.fwd(out1,in);\n    out2 = fft.fwd(in);\n    VERIFY( (out1-out2).norm() < test_precision<float>() );\n    in1 = fft.inv(out1);\n    VERIFY( (in1-in).norm() < test_precision<float>() );\n}\n\nEIGEN_DECLARE_TEST(FFTW)\n{\n  CALL_SUBTEST( test_return_by_value(32) );\n  //CALL_SUBTEST( ( test_complex2d<float,4,8> () ) ); CALL_SUBTEST( ( test_complex2d<double,4,8> () ) );\n  //CALL_SUBTEST( ( test_complex2d<long double,4,8> () ) );\n  CALL_SUBTEST( test_complex<float>(32) ); CALL_SUBTEST( test_complex<double>(32) ); \n  CALL_SUBTEST( test_complex<float>(256) ); CALL_SUBTEST( test_complex<double>(256) ); \n  CALL_SUBTEST( test_complex<float>(3*8) ); CALL_SUBTEST( test_complex<double>(3*8) ); \n  CALL_SUBTEST( test_complex<float>(5*32) ); CALL_SUBTEST( test_complex<double>(5*32) ); \n  CALL_SUBTEST( test_complex<float>(2*3*4) ); CALL_SUBTEST( test_complex<double>(2*3*4) ); \n  CALL_SUBTEST( test_complex<float>(2*3*4*5) ); CALL_SUBTEST( test_complex<double>(2*3*4*5) ); \n  CALL_SUBTEST( test_complex<float>(2*3*4*5*7) ); CALL_SUBTEST( test_complex<double>(2*3*4*5*7) ); \n\n  CALL_SUBTEST( test_scalar<float>(32) ); CALL_SUBTEST( test_scalar<double>(32) ); \n  CALL_SUBTEST( test_scalar<float>(45) ); CALL_SUBTEST( test_scalar<double>(45) ); \n  CALL_SUBTEST( test_scalar<float>(50) ); CALL_SUBTEST( test_scalar<double>(50) ); \n  CALL_SUBTEST( test_scalar<float>(256) ); CALL_SUBTEST( test_scalar<double>(256) ); \n  CALL_SUBTEST( test_scalar<float>(2*3*4*5*7) ); CALL_SUBTEST( test_scalar<double>(2*3*4*5*7) ); \n  \n  #ifdef EIGEN_HAS_FFTWL\n  CALL_SUBTEST( test_complex<long double>(32) );\n  CALL_SUBTEST( test_complex<long double>(256) );\n  CALL_SUBTEST( test_complex<long double>(3*8) );\n  CALL_SUBTEST( test_complex<long double>(5*32) );\n  CALL_SUBTEST( test_complex<long double>(2*3*4) );\n  CALL_SUBTEST( test_complex<long double>(2*3*4*5) );\n  CALL_SUBTEST( test_complex<long double>(2*3*4*5*7) );\n  \n  CALL_SUBTEST( test_scalar<long double>(32) );\n  CALL_SUBTEST( test_scalar<long double>(45) );\n  CALL_SUBTEST( test_scalar<long double>(50) );\n  CALL_SUBTEST( test_scalar<long double>(256) );\n  CALL_SUBTEST( test_scalar<long double>(2*3*4*5*7) );\n  #endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/NonLinearOptimization.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n\n#include <stdio.h>\n\n#include \"main.h\"\n#include <unsupported/Eigen/NonLinearOptimization>\n\n// This disables some useless Warnings on MSVC.\n// It is intended to be done for this test only.\n#include <Eigen/src/Core/util/DisableStupidWarnings.h>\n\n// tolerance for chekcing number of iterations\n#define LM_EVAL_COUNT_TOL 4/3\n\n#define LM_CHECK_N_ITERS(SOLVER,NFEV,NJEV) { \\\n            ++g_test_level; \\\n            VERIFY_IS_EQUAL(SOLVER.nfev, NFEV); \\\n            VERIFY_IS_EQUAL(SOLVER.njev, NJEV); \\\n            --g_test_level; \\\n            VERIFY(SOLVER.nfev <= NFEV * LM_EVAL_COUNT_TOL); \\\n            VERIFY(SOLVER.njev <= NJEV * LM_EVAL_COUNT_TOL); \\\n        }\n\nint fcn_chkder(const VectorXd &x, VectorXd &fvec, MatrixXd &fjac, int iflag)\n{\n    /*      subroutine fcn for chkder example. */\n\n    int i;\n    assert(15 ==  fvec.size());\n    assert(3 ==  x.size());\n    double tmp1, tmp2, tmp3, tmp4;\n    static const double y[15]={1.4e-1, 1.8e-1, 2.2e-1, 2.5e-1, 2.9e-1, 3.2e-1, 3.5e-1,\n        3.9e-1, 3.7e-1, 5.8e-1, 7.3e-1, 9.6e-1, 1.34, 2.1, 4.39};\n\n\n    if (iflag == 0)\n        return 0;\n\n    if (iflag != 2)\n        for (i=0; i<15; i++) {\n            tmp1 = i+1;\n            tmp2 = 16-i-1;\n            tmp3 = tmp1;\n            if (i >= 8) tmp3 = tmp2;\n            fvec[i] = y[i] - (x[0] + tmp1/(x[1]*tmp2 + x[2]*tmp3));\n        }\n    else {\n        for (i = 0; i < 15; i++) {\n            tmp1 = i+1;\n            tmp2 = 16-i-1;\n\n            /* error introduced into next statement for illustration. */\n            /* corrected statement should read    tmp3 = tmp1 . */\n\n            tmp3 = tmp2;\n            if (i >= 8) tmp3 = tmp2;\n            tmp4 = (x[1]*tmp2 + x[2]*tmp3); tmp4=tmp4*tmp4;\n            fjac(i,0) = -1.;\n            fjac(i,1) = tmp1*tmp2/tmp4;\n            fjac(i,2) = tmp1*tmp3/tmp4;\n        }\n    }\n    return 0;\n}\n\n\nvoid testChkder()\n{\n  const int m=15, n=3;\n  VectorXd x(n), fvec(m), xp, fvecp(m), err;\n  MatrixXd fjac(m,n);\n  VectorXi ipvt;\n\n  /*      the following values should be suitable for */\n  /*      checking the jacobian matrix. */\n  x << 9.2e-1, 1.3e-1, 5.4e-1;\n\n  internal::chkder(x, fvec, fjac, xp, fvecp, 1, err);\n  fcn_chkder(x, fvec, fjac, 1);\n  fcn_chkder(x, fvec, fjac, 2);\n  fcn_chkder(xp, fvecp, fjac, 1);\n  internal::chkder(x, fvec, fjac, xp, fvecp, 2, err);\n\n  fvecp -= fvec;\n\n  // check those\n  VectorXd fvec_ref(m), fvecp_ref(m), err_ref(m);\n  fvec_ref <<\n      -1.181606, -1.429655, -1.606344,\n      -1.745269, -1.840654, -1.921586,\n      -1.984141, -2.022537, -2.468977,\n      -2.827562, -3.473582, -4.437612,\n      -6.047662, -9.267761, -18.91806;\n  fvecp_ref <<\n      -7.724666e-09, -3.432406e-09, -2.034843e-10,\n      2.313685e-09,  4.331078e-09,  5.984096e-09,\n      7.363281e-09,   8.53147e-09,  1.488591e-08,\n      2.33585e-08,  3.522012e-08,  5.301255e-08,\n      8.26666e-08,  1.419747e-07,   3.19899e-07;\n  err_ref <<\n      0.1141397,  0.09943516,  0.09674474,\n      0.09980447,  0.1073116, 0.1220445,\n      0.1526814, 1, 1,\n      1, 1, 1,\n      1, 1, 1;\n\n  VERIFY_IS_APPROX(fvec, fvec_ref);\n  VERIFY_IS_APPROX(fvecp, fvecp_ref);\n  VERIFY_IS_APPROX(err, err_ref);\n}\n\n// Generic functor\ntemplate<typename Scalar_, int NX=Dynamic, int NY=Dynamic>\nstruct Functor\n{\n  typedef Scalar_ Scalar;\n  enum {\n    InputsAtCompileTime = NX,\n    ValuesAtCompileTime = NY\n  };\n  typedef Matrix<Scalar,InputsAtCompileTime,1> InputType;\n  typedef Matrix<Scalar,ValuesAtCompileTime,1> ValueType;\n  typedef Matrix<Scalar,ValuesAtCompileTime,InputsAtCompileTime> JacobianType;\n\n  const int m_inputs, m_values;\n\n  Functor() : m_inputs(InputsAtCompileTime), m_values(ValuesAtCompileTime) {}\n  Functor(int inputs, int values) : m_inputs(inputs), m_values(values) {}\n\n  int inputs() const { return m_inputs; }\n  int values() const { return m_values; }\n\n  // you should define that in the subclass :\n//  void operator() (const InputType& x, ValueType* v, JacobianType* _j=0) const;\n};\n\nstruct lmder_functor : Functor<double>\n{\n    lmder_functor(void): Functor<double>(3,15) {}\n    int operator()(const VectorXd &x, VectorXd &fvec) const\n    {\n        double tmp1, tmp2, tmp3;\n        static const double y[15] = {1.4e-1, 1.8e-1, 2.2e-1, 2.5e-1, 2.9e-1, 3.2e-1, 3.5e-1,\n            3.9e-1, 3.7e-1, 5.8e-1, 7.3e-1, 9.6e-1, 1.34, 2.1, 4.39};\n\n        for (int i = 0; i < values(); i++)\n        {\n            tmp1 = i+1;\n            tmp2 = 16 - i - 1;\n            tmp3 = (i>=8)? tmp2 : tmp1;\n            fvec[i] = y[i] - (x[0] + tmp1/(x[1]*tmp2 + x[2]*tmp3));\n        }\n        return 0;\n    }\n\n    int df(const VectorXd &x, MatrixXd &fjac) const\n    {\n        double tmp1, tmp2, tmp3, tmp4;\n        for (int i = 0; i < values(); i++)\n        {\n            tmp1 = i+1;\n            tmp2 = 16 - i - 1;\n            tmp3 = (i>=8)? tmp2 : tmp1;\n            tmp4 = (x[1]*tmp2 + x[2]*tmp3); tmp4 = tmp4*tmp4;\n            fjac(i,0) = -1;\n            fjac(i,1) = tmp1*tmp2/tmp4;\n            fjac(i,2) = tmp1*tmp3/tmp4;\n        }\n        return 0;\n    }\n};\n\nvoid testLmder1()\n{\n  int n=3, info;\n\n  VectorXd x;\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, 1.);\n\n  // do the computation\n  lmder_functor functor;\n  LevenbergMarquardt<lmder_functor> lm(functor);\n  info = lm.lmder1(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 6, 5);\n\n  // check norm\n  VERIFY_IS_APPROX(lm.fvec.blueNorm(), 0.09063596);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << 0.08241058, 1.133037, 2.343695;\n  VERIFY_IS_APPROX(x, x_ref);\n}\n\nvoid testLmder()\n{\n  const int m=15, n=3;\n  int info;\n  double fnorm, covfac;\n  VectorXd x;\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, 1.);\n\n  // do the computation\n  lmder_functor functor;\n  LevenbergMarquardt<lmder_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return values\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 6, 5);\n\n  // check norm\n  fnorm = lm.fvec.blueNorm();\n  VERIFY_IS_APPROX(fnorm, 0.09063596);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << 0.08241058, 1.133037, 2.343695;\n  VERIFY_IS_APPROX(x, x_ref);\n\n  // check covariance\n  covfac = fnorm*fnorm/(m-n);\n  internal::covar(lm.fjac, lm.permutation.indices()); // TODO : move this as a function of lm\n\n  MatrixXd cov_ref(n,n);\n  cov_ref <<\n      0.0001531202,   0.002869941,  -0.002656662,\n      0.002869941,    0.09480935,   -0.09098995,\n      -0.002656662,   -0.09098995,    0.08778727;\n\n//  std::cout << fjac*covfac << std::endl;\n\n  MatrixXd cov;\n  cov =  covfac*lm.fjac.topLeftCorner<n,n>();\n  VERIFY_IS_APPROX( cov, cov_ref);\n  // TODO: why isn't this allowed ? :\n  // VERIFY_IS_APPROX( covfac*fjac.topLeftCorner<n,n>() , cov_ref);\n}\n\nstruct hybrj_functor : Functor<double>\n{\n    hybrj_functor(void) : Functor<double>(9,9) {}\n\n    int operator()(const VectorXd &x, VectorXd &fvec)\n    {\n        double temp, temp1, temp2;\n        const VectorXd::Index n = x.size();\n        assert(fvec.size()==n);\n        for (VectorXd::Index k = 0; k < n; k++)\n        {\n            temp = (3. - 2.*x[k])*x[k];\n            temp1 = 0.;\n            if (k) temp1 = x[k-1];\n            temp2 = 0.;\n            if (k != n-1) temp2 = x[k+1];\n            fvec[k] = temp - temp1 - 2.*temp2 + 1.;\n        }\n        return 0;\n    }\n    int df(const VectorXd &x, MatrixXd &fjac)\n    {\n        const VectorXd::Index n = x.size();\n        assert(fjac.rows()==n);\n        assert(fjac.cols()==n);\n        for (VectorXd::Index k = 0; k < n; k++)\n        {\n            for (VectorXd::Index j = 0; j < n; j++)\n                fjac(k,j) = 0.;\n            fjac(k,k) = 3.- 4.*x[k];\n            if (k) fjac(k,k-1) = -1.;\n            if (k != n-1) fjac(k,k+1) = -2.;\n        }\n        return 0;\n    }\n};\n\n\nvoid testHybrj1()\n{\n  const int n=9;\n  int info;\n  VectorXd x(n);\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, -1.);\n\n  // do the computation\n  hybrj_functor functor;\n  HybridNonLinearSolver<hybrj_functor> solver(functor);\n  info = solver.hybrj1(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(solver, 11, 1);\n\n  // check norm\n  VERIFY_IS_APPROX(solver.fvec.blueNorm(), 1.192636e-08);\n\n\n// check x\n  VectorXd x_ref(n);\n  x_ref <<\n     -0.5706545,    -0.6816283,    -0.7017325,\n     -0.7042129,     -0.701369,    -0.6918656,\n     -0.665792,    -0.5960342,    -0.4164121;\n  VERIFY_IS_APPROX(x, x_ref);\n}\n\nvoid testHybrj()\n{\n  const int n=9;\n  int info;\n  VectorXd x(n);\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, -1.);\n\n\n  // do the computation\n  hybrj_functor functor;\n  HybridNonLinearSolver<hybrj_functor> solver(functor);\n  solver.diag.setConstant(n, 1.);\n  solver.useExternalScaling = true;\n  info = solver.solve(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(solver, 11, 1);\n\n  // check norm\n  VERIFY_IS_APPROX(solver.fvec.blueNorm(), 1.192636e-08);\n\n\n// check x\n  VectorXd x_ref(n);\n  x_ref <<\n     -0.5706545,    -0.6816283,    -0.7017325,\n     -0.7042129,     -0.701369,    -0.6918656,\n     -0.665792,    -0.5960342,    -0.4164121;\n  VERIFY_IS_APPROX(x, x_ref);\n\n}\n\nstruct hybrd_functor : Functor<double>\n{\n    hybrd_functor(void) : Functor<double>(9,9) {}\n    int operator()(const VectorXd &x, VectorXd &fvec) const\n    {\n        double temp, temp1, temp2;\n        const VectorXd::Index n = x.size();\n\n        assert(fvec.size()==n);\n        for (VectorXd::Index k=0; k < n; k++)\n        {\n            temp = (3. - 2.*x[k])*x[k];\n            temp1 = 0.;\n            if (k) temp1 = x[k-1];\n            temp2 = 0.;\n            if (k != n-1) temp2 = x[k+1];\n            fvec[k] = temp - temp1 - 2.*temp2 + 1.;\n        }\n        return 0;\n    }\n};\n\nvoid testHybrd1()\n{\n  int n=9, info;\n  VectorXd x(n);\n\n  /* the following starting values provide a rough solution. */\n  x.setConstant(n, -1.);\n\n  // do the computation\n  hybrd_functor functor;\n  HybridNonLinearSolver<hybrd_functor> solver(functor);\n  info = solver.hybrd1(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(solver.nfev, 20);\n\n  // check norm\n  VERIFY_IS_APPROX(solver.fvec.blueNorm(), 1.192636e-08);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << -0.5706545, -0.6816283, -0.7017325, -0.7042129, -0.701369, -0.6918656, -0.665792, -0.5960342, -0.4164121;\n  VERIFY_IS_APPROX(x, x_ref);\n}\n\nvoid testHybrd()\n{\n  const int n=9;\n  int info;\n  VectorXd x;\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, -1.);\n\n  // do the computation\n  hybrd_functor functor;\n  HybridNonLinearSolver<hybrd_functor> solver(functor);\n  solver.parameters.nb_of_subdiagonals = 1;\n  solver.parameters.nb_of_superdiagonals = 1;\n  solver.diag.setConstant(n, 1.);\n  solver.useExternalScaling = true;\n  info = solver.solveNumericalDiff(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(solver.nfev, 14);\n\n  // check norm\n  VERIFY_IS_APPROX(solver.fvec.blueNorm(), 1.192636e-08);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref <<\n      -0.5706545,    -0.6816283,    -0.7017325,\n      -0.7042129,     -0.701369,    -0.6918656,\n      -0.665792,    -0.5960342,    -0.4164121;\n  VERIFY_IS_APPROX(x, x_ref);\n}\n\nstruct lmstr_functor : Functor<double>\n{\n    lmstr_functor(void) : Functor<double>(3,15) {}\n    int operator()(const VectorXd &x, VectorXd &fvec)\n    {\n        /*  subroutine fcn for lmstr1 example. */\n        double tmp1, tmp2, tmp3;\n        static const double y[15]={1.4e-1, 1.8e-1, 2.2e-1, 2.5e-1, 2.9e-1, 3.2e-1, 3.5e-1,\n            3.9e-1, 3.7e-1, 5.8e-1, 7.3e-1, 9.6e-1, 1.34, 2.1, 4.39};\n\n        assert(15==fvec.size());\n        assert(3==x.size());\n\n        for (int i=0; i<15; i++)\n        {\n            tmp1 = i+1;\n            tmp2 = 16 - i - 1;\n            tmp3 = (i>=8)? tmp2 : tmp1;\n            fvec[i] = y[i] - (x[0] + tmp1/(x[1]*tmp2 + x[2]*tmp3));\n        }\n        return 0;\n    }\n    int df(const VectorXd &x, VectorXd &jac_row, VectorXd::Index rownb)\n    {\n        assert(x.size()==3);\n        assert(jac_row.size()==x.size());\n        double tmp1, tmp2, tmp3, tmp4;\n\n        VectorXd::Index i = rownb-2;\n        tmp1 = i+1;\n        tmp2 = 16 - i - 1;\n        tmp3 = (i>=8)? tmp2 : tmp1;\n        tmp4 = (x[1]*tmp2 + x[2]*tmp3); tmp4 = tmp4*tmp4;\n        jac_row[0] = -1;\n        jac_row[1] = tmp1*tmp2/tmp4;\n        jac_row[2] = tmp1*tmp3/tmp4;\n        return 0;\n    }\n};\n\nvoid testLmstr1()\n{\n  const int n=3;\n  int info;\n\n  VectorXd x(n);\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, 1.);\n\n  // do the computation\n  lmstr_functor functor;\n  LevenbergMarquardt<lmstr_functor> lm(functor);\n  info = lm.lmstr1(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 6, 5);\n\n  // check norm\n  VERIFY_IS_APPROX(lm.fvec.blueNorm(), 0.09063596);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << 0.08241058, 1.133037, 2.343695 ;\n  VERIFY_IS_APPROX(x, x_ref);\n}\n\nvoid testLmstr()\n{\n  const int n=3;\n  int info;\n  double fnorm;\n  VectorXd x(n);\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, 1.);\n\n  // do the computation\n  lmstr_functor functor;\n  LevenbergMarquardt<lmstr_functor> lm(functor);\n  info = lm.minimizeOptimumStorage(x);\n\n  // check return values\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 6, 5);\n\n  // check norm\n  fnorm = lm.fvec.blueNorm();\n  VERIFY_IS_APPROX(fnorm, 0.09063596);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << 0.08241058, 1.133037, 2.343695;\n  VERIFY_IS_APPROX(x, x_ref);\n\n}\n\nstruct lmdif_functor : Functor<double>\n{\n    lmdif_functor(void) : Functor<double>(3,15) {}\n    int operator()(const VectorXd &x, VectorXd &fvec) const\n    {\n        int i;\n        double tmp1,tmp2,tmp3;\n        static const double y[15]={1.4e-1,1.8e-1,2.2e-1,2.5e-1,2.9e-1,3.2e-1,3.5e-1,3.9e-1,\n            3.7e-1,5.8e-1,7.3e-1,9.6e-1,1.34e0,2.1e0,4.39e0};\n\n        assert(x.size()==3);\n        assert(fvec.size()==15);\n        for (i=0; i<15; i++)\n        {\n            tmp1 = i+1;\n            tmp2 = 15 - i;\n            tmp3 = tmp1;\n\n            if (i >= 8) tmp3 = tmp2;\n            fvec[i] = y[i] - (x[0] + tmp1/(x[1]*tmp2 + x[2]*tmp3));\n        }\n        return 0;\n    }\n};\n\nvoid testLmdif1()\n{\n  const int n=3;\n  int info;\n\n  VectorXd x(n), fvec(15);\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, 1.);\n\n  // do the computation\n  lmdif_functor functor;\n  DenseIndex nfev = -1; // initialize to avoid maybe-uninitialized warning\n  info = LevenbergMarquardt<lmdif_functor>::lmdif1(functor, x, &nfev);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(nfev, 26);\n\n  // check norm\n  functor(x, fvec);\n  VERIFY_IS_APPROX(fvec.blueNorm(), 0.09063596);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << 0.0824106, 1.1330366, 2.3436947;\n  VERIFY_IS_APPROX(x, x_ref);\n\n}\n\nvoid testLmdif()\n{\n  const int m=15, n=3;\n  int info;\n  double fnorm, covfac;\n  VectorXd x(n);\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, 1.);\n\n  // do the computation\n  lmdif_functor functor;\n  NumericalDiff<lmdif_functor> numDiff(functor);\n  LevenbergMarquardt<NumericalDiff<lmdif_functor> > lm(numDiff);\n  info = lm.minimize(x);\n\n  // check return values\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev, 26);\n\n  // check norm\n  fnorm = lm.fvec.blueNorm();\n  VERIFY_IS_APPROX(fnorm, 0.09063596);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << 0.08241058, 1.133037, 2.343695;\n  VERIFY_IS_APPROX(x, x_ref);\n\n  // check covariance\n  covfac = fnorm*fnorm/(m-n);\n  internal::covar(lm.fjac, lm.permutation.indices()); // TODO : move this as a function of lm\n\n  MatrixXd cov_ref(n,n);\n  cov_ref <<\n      0.0001531202,   0.002869942,  -0.002656662,\n      0.002869942,    0.09480937,   -0.09098997,\n      -0.002656662,   -0.09098997,    0.08778729;\n\n//  std::cout << fjac*covfac << std::endl;\n\n  MatrixXd cov;\n  cov =  covfac*lm.fjac.topLeftCorner<n,n>();\n  VERIFY_IS_APPROX( cov, cov_ref);\n  // TODO: why isn't this allowed ? :\n  // VERIFY_IS_APPROX( covfac*fjac.topLeftCorner<n,n>() , cov_ref);\n}\n\nstruct chwirut2_functor : Functor<double>\n{\n    chwirut2_functor(void) : Functor<double>(3,54) {}\n    static const double m_x[54];\n    static const double m_y[54];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        int i;\n\n        assert(b.size()==3);\n        assert(fvec.size()==54);\n        for(i=0; i<54; i++) {\n            double x = m_x[i];\n            fvec[i] = exp(-b[0]*x)/(b[1]+b[2]*x) - m_y[i];\n        }\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==3);\n        assert(fjac.rows()==54);\n        assert(fjac.cols()==3);\n        for(int i=0; i<54; i++) {\n            double x = m_x[i];\n            double factor = 1./(b[1]+b[2]*x);\n            double e = exp(-b[0]*x);\n            fjac(i,0) = -x*e*factor;\n            fjac(i,1) = -e*factor*factor;\n            fjac(i,2) = -x*e*factor*factor;\n        }\n        return 0;\n    }\n};\nconst double chwirut2_functor::m_x[54] = { 0.500E0, 1.000E0, 1.750E0, 3.750E0, 5.750E0, 0.875E0, 2.250E0, 3.250E0, 5.250E0, 0.750E0, 1.750E0, 2.750E0, 4.750E0, 0.625E0, 1.250E0, 2.250E0, 4.250E0, .500E0, 3.000E0, .750E0, 3.000E0, 1.500E0, 6.000E0, 3.000E0, 6.000E0, 1.500E0, 3.000E0, .500E0, 2.000E0, 4.000E0, .750E0, 2.000E0, 5.000E0, .750E0, 2.250E0, 3.750E0, 5.750E0, 3.000E0, .750E0, 2.500E0, 4.000E0, .750E0, 2.500E0, 4.000E0, .750E0, 2.500E0, 4.000E0, .500E0, 6.000E0, 3.000E0, .500E0, 2.750E0, .500E0, 1.750E0};\nconst double chwirut2_functor::m_y[54] = { 92.9000E0 ,57.1000E0 ,31.0500E0 ,11.5875E0 ,8.0250E0 ,63.6000E0 ,21.4000E0 ,14.2500E0 ,8.4750E0 ,63.8000E0 ,26.8000E0 ,16.4625E0 ,7.1250E0 ,67.3000E0 ,41.0000E0 ,21.1500E0 ,8.1750E0 ,81.5000E0 ,13.1200E0 ,59.9000E0 ,14.6200E0 ,32.9000E0 ,5.4400E0 ,12.5600E0 ,5.4400E0 ,32.0000E0 ,13.9500E0 ,75.8000E0 ,20.0000E0 ,10.4200E0 ,59.5000E0 ,21.6700E0 ,8.5500E0 ,62.0000E0 ,20.2000E0 ,7.7600E0 ,3.7500E0 ,11.8100E0 ,54.7000E0 ,23.7000E0 ,11.5500E0 ,61.3000E0 ,17.7000E0 ,8.7400E0 ,59.2000E0 ,16.3000E0 ,8.6200E0 ,81.0000E0 ,4.8700E0 ,14.6200E0 ,81.7000E0 ,17.1700E0 ,81.3000E0 ,28.9000E0  };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/chwirut2.shtml\nvoid testNistChwirut2(void)\n{\n  const int n=3;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 0.1, 0.01, 0.02;\n  // do the computation\n  chwirut2_functor functor;\n  LevenbergMarquardt<chwirut2_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 10, 8);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 5.1304802941E+02);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.6657666537E-01);\n  VERIFY_IS_APPROX(x[1], 5.1653291286E-03);\n  VERIFY_IS_APPROX(x[2], 1.2150007096E-02);\n\n  /*\n   * Second try\n   */\n  x<< 0.15, 0.008, 0.010;\n  // do the computation\n  lm.resetParameters();\n  lm.parameters.ftol = 1.E6*NumTraits<double>::epsilon();\n  lm.parameters.xtol = 1.E6*NumTraits<double>::epsilon();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 7, 6);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 5.1304802941E+02);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.6657666537E-01);\n  VERIFY_IS_APPROX(x[1], 5.1653291286E-03);\n  VERIFY_IS_APPROX(x[2], 1.2150007096E-02);\n}\n\n\nstruct misra1a_functor : Functor<double>\n{\n    misra1a_functor(void) : Functor<double>(2,14) {}\n    static const double m_x[14];\n    static const double m_y[14];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==2);\n        assert(fvec.size()==14);\n        for(int i=0; i<14; i++) {\n            fvec[i] = b[0]*(1.-exp(-b[1]*m_x[i])) - m_y[i] ;\n        }\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==2);\n        assert(fjac.rows()==14);\n        assert(fjac.cols()==2);\n        for(int i=0; i<14; i++) {\n            fjac(i,0) = (1.-exp(-b[1]*m_x[i]));\n            fjac(i,1) = (b[0]*m_x[i]*exp(-b[1]*m_x[i]));\n        }\n        return 0;\n    }\n};\nconst double misra1a_functor::m_x[14] = { 77.6E0, 114.9E0, 141.1E0, 190.8E0, 239.9E0, 289.0E0, 332.8E0, 378.4E0, 434.8E0, 477.3E0, 536.8E0, 593.1E0, 689.1E0, 760.0E0};\nconst double misra1a_functor::m_y[14] = { 10.07E0, 14.73E0, 17.94E0, 23.93E0, 29.61E0, 35.18E0, 40.02E0, 44.82E0, 50.76E0, 55.05E0, 61.01E0, 66.40E0, 75.47E0, 81.78E0};\n\n// http://www.itl.nist.gov/div898/strd/nls/data/misra1a.shtml\nvoid testNistMisra1a(void)\n{\n  const int n=2;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 500., 0.0001;\n  // do the computation\n  misra1a_functor functor;\n  LevenbergMarquardt<misra1a_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 19, 15);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 1.2455138894E-01);\n  // check x\n  VERIFY_IS_APPROX(x[0], 2.3894212918E+02);\n  VERIFY_IS_APPROX(x[1], 5.5015643181E-04);\n\n  /*\n   * Second try\n   */\n  x<< 250., 0.0005;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 5, 4);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 1.2455138894E-01);\n  // check x\n  VERIFY_IS_APPROX(x[0], 2.3894212918E+02);\n  VERIFY_IS_APPROX(x[1], 5.5015643181E-04);\n}\n\nstruct hahn1_functor : Functor<double>\n{\n    hahn1_functor(void) : Functor<double>(7,236) {}\n    static const double m_x[236];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        static const double m_y[236] = { .591E0 , 1.547E0 , 2.902E0 , 2.894E0 , 4.703E0 , 6.307E0 , 7.03E0  , 7.898E0 , 9.470E0 , 9.484E0 , 10.072E0 , 10.163E0 , 11.615E0 , 12.005E0 , 12.478E0 , 12.982E0 , 12.970E0 , 13.926E0 , 14.452E0 , 14.404E0 , 15.190E0 , 15.550E0 , 15.528E0 , 15.499E0 , 16.131E0 , 16.438E0 , 16.387E0 , 16.549E0 , 16.872E0 , 16.830E0 , 16.926E0 , 16.907E0 , 16.966E0 , 17.060E0 , 17.122E0 , 17.311E0 , 17.355E0 , 17.668E0 , 17.767E0 , 17.803E0 , 17.765E0 , 17.768E0 , 17.736E0 , 17.858E0 , 17.877E0 , 17.912E0 , 18.046E0 , 18.085E0 , 18.291E0 , 18.357E0 , 18.426E0 , 18.584E0 , 18.610E0 , 18.870E0 , 18.795E0 , 19.111E0 , .367E0 , .796E0 , 0.892E0 , 1.903E0 , 2.150E0 , 3.697E0 , 5.870E0 , 6.421E0 , 7.422E0 , 9.944E0 , 11.023E0 , 11.87E0  , 12.786E0 , 14.067E0 , 13.974E0 , 14.462E0 , 14.464E0 , 15.381E0 , 15.483E0 , 15.59E0  , 16.075E0 , 16.347E0 , 16.181E0 , 16.915E0 , 17.003E0 , 16.978E0 , 17.756E0 , 17.808E0 , 17.868E0 , 18.481E0 , 18.486E0 , 19.090E0 , 16.062E0 , 16.337E0 , 16.345E0 ,\n        16.388E0 , 17.159E0 , 17.116E0 , 17.164E0 , 17.123E0 , 17.979E0 , 17.974E0 , 18.007E0 , 17.993E0 , 18.523E0 , 18.669E0 , 18.617E0 , 19.371E0 , 19.330E0 , 0.080E0 , 0.248E0 , 1.089E0 , 1.418E0 , 2.278E0 , 3.624E0 , 4.574E0 , 5.556E0 , 7.267E0 , 7.695E0 , 9.136E0 , 9.959E0 , 9.957E0 , 11.600E0 , 13.138E0 , 13.564E0 , 13.871E0 , 13.994E0 , 14.947E0 , 15.473E0 , 15.379E0 , 15.455E0 , 15.908E0 , 16.114E0 , 17.071E0 , 17.135E0 , 17.282E0 , 17.368E0 , 17.483E0 , 17.764E0 , 18.185E0 , 18.271E0 , 18.236E0 , 18.237E0 , 18.523E0 , 18.627E0 , 18.665E0 , 19.086E0 , 0.214E0 , 0.943E0 , 1.429E0 , 2.241E0 , 2.951E0 , 3.782E0 , 4.757E0 , 5.602E0 , 7.169E0 , 8.920E0 , 10.055E0 , 12.035E0 , 12.861E0 , 13.436E0 , 14.167E0 , 14.755E0 , 15.168E0 , 15.651E0 , 15.746E0 , 16.216E0 , 16.445E0 , 16.965E0 , 17.121E0 , 17.206E0 , 17.250E0 , 17.339E0 , 17.793E0 , 18.123E0 , 18.49E0  , 18.566E0 , 18.645E0 , 18.706E0 , 18.924E0 , 19.1E0   , 0.375E0 , 0.471E0 , 1.504E0 , 2.204E0 , 2.813E0 , 4.765E0 , 9.835E0 , 10.040E0 , 11.946E0 , 12.596E0 , \n13.303E0 , 13.922E0 , 14.440E0 , 14.951E0 , 15.627E0 , 15.639E0 , 15.814E0 , 16.315E0 , 16.334E0 , 16.430E0 , 16.423E0 , 17.024E0 , 17.009E0 , 17.165E0 , 17.134E0 , 17.349E0 , 17.576E0 , 17.848E0 , 18.090E0 , 18.276E0 , 18.404E0 , 18.519E0 , 19.133E0 , 19.074E0 , 19.239E0 , 19.280E0 , 19.101E0 , 19.398E0 , 19.252E0 , 19.89E0  , 20.007E0 , 19.929E0 , 19.268E0 , 19.324E0 , 20.049E0 , 20.107E0 , 20.062E0 , 20.065E0 , 19.286E0 , 19.972E0 , 20.088E0 , 20.743E0 , 20.83E0  , 20.935E0 , 21.035E0 , 20.93E0  , 21.074E0 , 21.085E0 , 20.935E0 };\n\n        //        int called=0; printf(\"call hahn1_functor with  iflag=%d, called=%d\\n\", iflag, called); if (iflag==1) called++;\n\n        assert(b.size()==7);\n        assert(fvec.size()==236);\n        for(int i=0; i<236; i++) {\n            double x=m_x[i], xx=x*x, xxx=xx*x;\n            fvec[i] = (b[0]+b[1]*x+b[2]*xx+b[3]*xxx) / (1.+b[4]*x+b[5]*xx+b[6]*xxx) - m_y[i];\n        }\n        return 0;\n    }\n\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==7);\n        assert(fjac.rows()==236);\n        assert(fjac.cols()==7);\n        for(int i=0; i<236; i++) {\n            double x=m_x[i], xx=x*x, xxx=xx*x;\n            double fact = 1./(1.+b[4]*x+b[5]*xx+b[6]*xxx);\n            fjac(i,0) = 1.*fact;\n            fjac(i,1) = x*fact;\n            fjac(i,2) = xx*fact;\n            fjac(i,3) = xxx*fact;\n            fact = - (b[0]+b[1]*x+b[2]*xx+b[3]*xxx) * fact * fact;\n            fjac(i,4) = x*fact;\n            fjac(i,5) = xx*fact;\n            fjac(i,6) = xxx*fact;\n        }\n        return 0;\n    }\n};\nconst double hahn1_functor::m_x[236] = { 24.41E0 , 34.82E0 , 44.09E0 , 45.07E0 , 54.98E0 , 65.51E0 , 70.53E0 , 75.70E0 , 89.57E0 , 91.14E0 , 96.40E0 , 97.19E0 , 114.26E0 , 120.25E0 , 127.08E0 , 133.55E0 , 133.61E0 , 158.67E0 , 172.74E0 , 171.31E0 , 202.14E0 , 220.55E0 , 221.05E0 , 221.39E0 , 250.99E0 , 268.99E0 , 271.80E0 , 271.97E0 , 321.31E0 , 321.69E0 , 330.14E0 , 333.03E0 , 333.47E0 , 340.77E0 , 345.65E0 , 373.11E0 , 373.79E0 , 411.82E0 , 419.51E0 , 421.59E0 , 422.02E0 , 422.47E0 , 422.61E0 , 441.75E0 , 447.41E0 , 448.7E0  , 472.89E0 , 476.69E0 , 522.47E0 , 522.62E0 , 524.43E0 , 546.75E0 , 549.53E0 , 575.29E0 , 576.00E0 , 625.55E0 , 20.15E0 , 28.78E0 , 29.57E0 , 37.41E0 , 39.12E0 , 50.24E0 , 61.38E0 , 66.25E0 , 73.42E0 , 95.52E0 , 107.32E0 , 122.04E0 , 134.03E0 , 163.19E0 , 163.48E0 , 175.70E0 , 179.86E0 , 211.27E0 , 217.78E0 , 219.14E0 , 262.52E0 , 268.01E0 , 268.62E0 , 336.25E0 , 337.23E0 , 339.33E0 , 427.38E0 , 428.58E0 , 432.68E0 , 528.99E0 , 531.08E0 , 628.34E0 , 253.24E0 , 273.13E0 , 273.66E0 ,\n282.10E0 , 346.62E0 , 347.19E0 , 348.78E0 , 351.18E0 , 450.10E0 , 450.35E0 , 451.92E0 , 455.56E0 , 552.22E0 , 553.56E0 , 555.74E0 , 652.59E0 , 656.20E0 , 14.13E0 , 20.41E0 , 31.30E0 , 33.84E0 , 39.70E0 , 48.83E0 , 54.50E0 , 60.41E0 , 72.77E0 , 75.25E0 , 86.84E0 , 94.88E0 , 96.40E0 , 117.37E0 , 139.08E0 , 147.73E0 , 158.63E0 , 161.84E0 , 192.11E0 , 206.76E0 , 209.07E0 , 213.32E0 , 226.44E0 , 237.12E0 , 330.90E0 , 358.72E0 , 370.77E0 , 372.72E0 , 396.24E0 , 416.59E0 , 484.02E0 , 495.47E0 , 514.78E0 , 515.65E0 , 519.47E0 , 544.47E0 , 560.11E0 , 620.77E0 , 18.97E0 , 28.93E0 , 33.91E0 , 40.03E0 , 44.66E0 , 49.87E0 , 55.16E0 , 60.90E0 , 72.08E0 , 85.15E0 , 97.06E0 , 119.63E0 , 133.27E0 , 143.84E0 , 161.91E0 , 180.67E0 , 198.44E0 , 226.86E0 , 229.65E0 , 258.27E0 , 273.77E0 , 339.15E0 , 350.13E0 , 362.75E0 , 371.03E0 , 393.32E0 , 448.53E0 , 473.78E0 , 511.12E0 , 524.70E0 , 548.75E0 , 551.64E0 , 574.02E0 , 623.86E0 , 21.46E0 , 24.33E0 , 33.43E0 , 39.22E0 , 44.18E0 , 55.02E0 , 94.33E0 , 96.44E0 , 118.82E0 , 128.48E0 ,\n141.94E0 , 156.92E0 , 171.65E0 , 190.00E0 , 223.26E0 , 223.88E0 , 231.50E0 , 265.05E0 , 269.44E0 , 271.78E0 , 273.46E0 , 334.61E0 , 339.79E0 , 349.52E0 , 358.18E0 , 377.98E0 , 394.77E0 , 429.66E0 , 468.22E0 , 487.27E0 , 519.54E0 , 523.03E0 , 612.99E0 , 638.59E0 , 641.36E0 , 622.05E0 , 631.50E0 , 663.97E0 , 646.9E0  , 748.29E0 , 749.21E0 , 750.14E0 , 647.04E0 , 646.89E0 , 746.9E0  , 748.43E0 , 747.35E0 , 749.27E0 , 647.61E0 , 747.78E0 , 750.51E0 , 851.37E0 , 845.97E0 , 847.54E0 , 849.93E0 , 851.61E0 , 849.75E0 , 850.98E0 , 848.23E0};\n\n// http://www.itl.nist.gov/div898/strd/nls/data/hahn1.shtml\nvoid testNistHahn1(void)\n{\n  const int  n=7;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 10., -1., .05, -.00001, -.05, .001, -.000001;\n  // do the computation\n  hahn1_functor functor;\n  LevenbergMarquardt<hahn1_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 11, 10);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 1.5324382854E+00);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.0776351733E+00);\n  VERIFY_IS_APPROX(x[1],-1.2269296921E-01);\n  VERIFY_IS_APPROX(x[2], 4.0863750610E-03);\n  VERIFY_IS_APPROX(x[3],-1.426264e-06); // shoulde be : -1.4262662514E-06\n  VERIFY_IS_APPROX(x[4],-5.7609940901E-03);\n  VERIFY_IS_APPROX(x[5], 2.4053735503E-04);\n  VERIFY_IS_APPROX(x[6],-1.2314450199E-07);\n\n  /*\n   * Second try\n   */\n  x<< .1, -.1, .005, -.000001, -.005, .0001, -.0000001;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 11, 10);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 1.5324382854E+00);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.077640); // should be :  1.0776351733E+00\n  VERIFY_IS_APPROX(x[1], -0.1226933); // should be : -1.2269296921E-01\n  VERIFY_IS_APPROX(x[2], 0.004086383); // should be : 4.0863750610E-03\n  VERIFY_IS_APPROX(x[3], -1.426277e-06); // shoulde be : -1.4262662514E-06\n  VERIFY_IS_APPROX(x[4],-5.7609940901E-03);\n  VERIFY_IS_APPROX(x[5], 0.00024053772); // should be : 2.4053735503E-04\n  VERIFY_IS_APPROX(x[6], -1.231450e-07); // should be : -1.2314450199E-07\n\n}\n\nstruct misra1d_functor : Functor<double>\n{\n    misra1d_functor(void) : Functor<double>(2,14) {}\n    static const double x[14];\n    static const double y[14];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==2);\n        assert(fvec.size()==14);\n        for(int i=0; i<14; i++) {\n            fvec[i] = b[0]*b[1]*x[i]/(1.+b[1]*x[i]) - y[i];\n        }\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==2);\n        assert(fjac.rows()==14);\n        assert(fjac.cols()==2);\n        for(int i=0; i<14; i++) {\n            double den = 1.+b[1]*x[i];\n            fjac(i,0) = b[1]*x[i] / den;\n            fjac(i,1) = b[0]*x[i]*(den-b[1]*x[i])/den/den;\n        }\n        return 0;\n    }\n};\nconst double misra1d_functor::x[14] = { 77.6E0, 114.9E0, 141.1E0, 190.8E0, 239.9E0, 289.0E0, 332.8E0, 378.4E0, 434.8E0, 477.3E0, 536.8E0, 593.1E0, 689.1E0, 760.0E0};\nconst double misra1d_functor::y[14] = { 10.07E0, 14.73E0, 17.94E0, 23.93E0, 29.61E0, 35.18E0, 40.02E0, 44.82E0, 50.76E0, 55.05E0, 61.01E0, 66.40E0, 75.47E0, 81.78E0};\n\n// http://www.itl.nist.gov/div898/strd/nls/data/misra1d.shtml\nvoid testNistMisra1d(void)\n{\n  const int n=2;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 500., 0.0001;\n  // do the computation\n  misra1d_functor functor;\n  LevenbergMarquardt<misra1d_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 3);\n  LM_CHECK_N_ITERS(lm, 9, 7);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 5.6419295283E-02);\n  // check x\n  VERIFY_IS_APPROX(x[0], 4.3736970754E+02);\n  VERIFY_IS_APPROX(x[1], 3.0227324449E-04);\n\n  /*\n   * Second try\n   */\n  x<< 450., 0.0003;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 4, 3);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 5.6419295283E-02);\n  // check x\n  VERIFY_IS_APPROX(x[0], 4.3736970754E+02);\n  VERIFY_IS_APPROX(x[1], 3.0227324449E-04);\n}\n\n\nstruct lanczos1_functor : Functor<double>\n{\n    lanczos1_functor(void) : Functor<double>(6,24) {}\n    static const double x[24];\n    static const double y[24];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==6);\n        assert(fvec.size()==24);\n        for(int i=0; i<24; i++)\n            fvec[i] = b[0]*exp(-b[1]*x[i]) + b[2]*exp(-b[3]*x[i]) + b[4]*exp(-b[5]*x[i])  - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==6);\n        assert(fjac.rows()==24);\n        assert(fjac.cols()==6);\n        for(int i=0; i<24; i++) {\n            fjac(i,0) = exp(-b[1]*x[i]);\n            fjac(i,1) = -b[0]*x[i]*exp(-b[1]*x[i]);\n            fjac(i,2) = exp(-b[3]*x[i]);\n            fjac(i,3) = -b[2]*x[i]*exp(-b[3]*x[i]);\n            fjac(i,4) = exp(-b[5]*x[i]);\n            fjac(i,5) = -b[4]*x[i]*exp(-b[5]*x[i]);\n        }\n        return 0;\n    }\n};\nconst double lanczos1_functor::x[24] = { 0.000000000000E+00, 5.000000000000E-02, 1.000000000000E-01, 1.500000000000E-01, 2.000000000000E-01, 2.500000000000E-01, 3.000000000000E-01, 3.500000000000E-01, 4.000000000000E-01, 4.500000000000E-01, 5.000000000000E-01, 5.500000000000E-01, 6.000000000000E-01, 6.500000000000E-01, 7.000000000000E-01, 7.500000000000E-01, 8.000000000000E-01, 8.500000000000E-01, 9.000000000000E-01, 9.500000000000E-01, 1.000000000000E+00, 1.050000000000E+00, 1.100000000000E+00, 1.150000000000E+00 };\nconst double lanczos1_functor::y[24] = { 2.513400000000E+00 ,2.044333373291E+00 ,1.668404436564E+00 ,1.366418021208E+00 ,1.123232487372E+00 ,9.268897180037E-01 ,7.679338563728E-01 ,6.388775523106E-01 ,5.337835317402E-01 ,4.479363617347E-01 ,3.775847884350E-01 ,3.197393199326E-01 ,2.720130773746E-01 ,2.324965529032E-01 ,1.996589546065E-01 ,1.722704126914E-01 ,1.493405660168E-01 ,1.300700206922E-01 ,1.138119324644E-01 ,1.000415587559E-01 ,8.833209084540E-02 ,7.833544019350E-02 ,6.976693743449E-02 ,6.239312536719E-02 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/lanczos1.shtml\nvoid testNistLanczos1(void)\n{\n  const int n=6;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 1.2, 0.3, 5.6, 5.5, 6.5, 7.6;\n  // do the computation\n  lanczos1_functor functor;\n  LevenbergMarquardt<lanczos1_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 2);\n  LM_CHECK_N_ITERS(lm, 79, 72);\n  // check norm^2\n  std::cout.precision(30);\n  std::cout << lm.fvec.squaredNorm() << \"\\n\";\n  VERIFY(lm.fvec.squaredNorm() <= 1.4307867721E-25);\n  // check x\n  VERIFY_IS_APPROX(x[0], 9.5100000027E-02);\n  VERIFY_IS_APPROX(x[1], 1.0000000001E+00);\n  VERIFY_IS_APPROX(x[2], 8.6070000013E-01);\n  VERIFY_IS_APPROX(x[3], 3.0000000002E+00);\n  VERIFY_IS_APPROX(x[4], 1.5575999998E+00);\n  VERIFY_IS_APPROX(x[5], 5.0000000001E+00);\n\n  /*\n   * Second try\n   */\n  x<< 0.5, 0.7, 3.6, 4.2, 4., 6.3;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 2);\n  LM_CHECK_N_ITERS(lm, 9, 8);\n  // check norm^2\n  VERIFY(lm.fvec.squaredNorm() <= 1.4307867721E-25);\n  // check x\n  VERIFY_IS_APPROX(x[0], 9.5100000027E-02);\n  VERIFY_IS_APPROX(x[1], 1.0000000001E+00);\n  VERIFY_IS_APPROX(x[2], 8.6070000013E-01);\n  VERIFY_IS_APPROX(x[3], 3.0000000002E+00);\n  VERIFY_IS_APPROX(x[4], 1.5575999998E+00);\n  VERIFY_IS_APPROX(x[5], 5.0000000001E+00);\n\n}\n\nstruct rat42_functor : Functor<double>\n{\n    rat42_functor(void) : Functor<double>(3,9) {}\n    static const double x[9];\n    static const double y[9];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==3);\n        assert(fvec.size()==9);\n        for(int i=0; i<9; i++) {\n            fvec[i] = b[0] / (1.+exp(b[1]-b[2]*x[i])) - y[i];\n        }\n        return 0;\n    }\n\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==3);\n        assert(fjac.rows()==9);\n        assert(fjac.cols()==3);\n        for(int i=0; i<9; i++) {\n            double e = exp(b[1]-b[2]*x[i]);\n            fjac(i,0) = 1./(1.+e);\n            fjac(i,1) = -b[0]*e/(1.+e)/(1.+e);\n            fjac(i,2) = +b[0]*e*x[i]/(1.+e)/(1.+e);\n        }\n        return 0;\n    }\n};\nconst double rat42_functor::x[9] = { 9.000E0, 14.000E0, 21.000E0, 28.000E0, 42.000E0, 57.000E0, 63.000E0, 70.000E0, 79.000E0 };\nconst double rat42_functor::y[9] = { 8.930E0 ,10.800E0 ,18.590E0 ,22.330E0 ,39.350E0 ,56.110E0 ,61.730E0 ,64.620E0 ,67.080E0 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/ratkowsky2.shtml\nvoid testNistRat42(void)\n{\n  const int n=3;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 100., 1., 0.1;\n  // do the computation\n  rat42_functor functor;\n  LevenbergMarquardt<rat42_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 10, 8);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 8.0565229338E+00);\n  // check x\n  VERIFY_IS_APPROX(x[0], 7.2462237576E+01);\n  VERIFY_IS_APPROX(x[1], 2.6180768402E+00);\n  VERIFY_IS_APPROX(x[2], 6.7359200066E-02);\n\n  /*\n   * Second try\n   */\n  x<< 75., 2.5, 0.07;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 6, 5);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 8.0565229338E+00);\n  // check x\n  VERIFY_IS_APPROX(x[0], 7.2462237576E+01);\n  VERIFY_IS_APPROX(x[1], 2.6180768402E+00);\n  VERIFY_IS_APPROX(x[2], 6.7359200066E-02);\n}\n\nstruct MGH10_functor : Functor<double>\n{\n    MGH10_functor(void) : Functor<double>(3,16) {}\n    static const double x[16];\n    static const double y[16];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==3);\n        assert(fvec.size()==16);\n        for(int i=0; i<16; i++)\n            fvec[i] =  b[0] * exp(b[1]/(x[i]+b[2])) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==3);\n        assert(fjac.rows()==16);\n        assert(fjac.cols()==3);\n        for(int i=0; i<16; i++) {\n            double factor = 1./(x[i]+b[2]);\n            double e = exp(b[1]*factor);\n            fjac(i,0) = e;\n            fjac(i,1) = b[0]*factor*e;\n            fjac(i,2) = -b[1]*b[0]*factor*factor*e;\n        }\n        return 0;\n    }\n};\nconst double MGH10_functor::x[16] = { 5.000000E+01, 5.500000E+01, 6.000000E+01, 6.500000E+01, 7.000000E+01, 7.500000E+01, 8.000000E+01, 8.500000E+01, 9.000000E+01, 9.500000E+01, 1.000000E+02, 1.050000E+02, 1.100000E+02, 1.150000E+02, 1.200000E+02, 1.250000E+02 };\nconst double MGH10_functor::y[16] = { 3.478000E+04, 2.861000E+04, 2.365000E+04, 1.963000E+04, 1.637000E+04, 1.372000E+04, 1.154000E+04, 9.744000E+03, 8.261000E+03, 7.030000E+03, 6.005000E+03, 5.147000E+03, 4.427000E+03, 3.820000E+03, 3.307000E+03, 2.872000E+03 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/mgh10.shtml\nvoid testNistMGH10(void)\n{\n  const int n=3;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 2., 400000., 25000.;\n  // do the computation\n  MGH10_functor functor;\n  LevenbergMarquardt<MGH10_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 2); \n  LM_CHECK_N_ITERS(lm, 284, 249); \n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 8.7945855171E+01);\n  // check x\n  VERIFY_IS_APPROX(x[0], 5.6096364710E-03);\n  VERIFY_IS_APPROX(x[1], 6.1813463463E+03);\n  VERIFY_IS_APPROX(x[2], 3.4522363462E+02);\n\n  /*\n   * Second try\n   */\n  x<< 0.02, 4000., 250.;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 3);\n  LM_CHECK_N_ITERS(lm, 126, 116);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 8.7945855171E+01);\n  // check x\n  VERIFY_IS_APPROX(x[0], 5.6096364710E-03);\n  VERIFY_IS_APPROX(x[1], 6.1813463463E+03);\n  VERIFY_IS_APPROX(x[2], 3.4522363462E+02);\n}\n\n\nstruct BoxBOD_functor : Functor<double>\n{\n    BoxBOD_functor(void) : Functor<double>(2,6) {}\n    static const double x[6];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        static const double y[6] = { 109., 149., 149., 191., 213., 224. };\n        assert(b.size()==2);\n        assert(fvec.size()==6);\n        for(int i=0; i<6; i++)\n            fvec[i] =  b[0]*(1.-exp(-b[1]*x[i])) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==2);\n        assert(fjac.rows()==6);\n        assert(fjac.cols()==2);\n        for(int i=0; i<6; i++) {\n            double e = exp(-b[1]*x[i]);\n            fjac(i,0) = 1.-e;\n            fjac(i,1) = b[0]*x[i]*e;\n        }\n        return 0;\n    }\n};\nconst double BoxBOD_functor::x[6] = { 1., 2., 3., 5., 7., 10. };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/boxbod.shtml\nvoid testNistBoxBOD(void)\n{\n  const int n=2;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 1., 1.;\n  // do the computation\n  BoxBOD_functor functor;\n  LevenbergMarquardt<BoxBOD_functor> lm(functor);\n  lm.parameters.ftol = 1.E6*NumTraits<double>::epsilon();\n  lm.parameters.xtol = 1.E6*NumTraits<double>::epsilon();\n  lm.parameters.factor = 10.;\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 31, 25);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 1.1680088766E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 2.1380940889E+02);\n  VERIFY_IS_APPROX(x[1], 5.4723748542E-01);\n\n  /*\n   * Second try\n   */\n  x<< 100., 0.75;\n  // do the computation\n  lm.resetParameters();\n  lm.parameters.ftol = NumTraits<double>::epsilon();\n  lm.parameters.xtol = NumTraits<double>::epsilon();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 15, 14);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 1.1680088766E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 2.1380940889E+02);\n  VERIFY_IS_APPROX(x[1], 5.4723748542E-01);\n}\n\nstruct MGH17_functor : Functor<double>\n{\n    MGH17_functor(void) : Functor<double>(5,33) {}\n    static const double x[33];\n    static const double y[33];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==5);\n        assert(fvec.size()==33);\n        for(int i=0; i<33; i++)\n            fvec[i] =  b[0] + b[1]*exp(-b[3]*x[i]) +  b[2]*exp(-b[4]*x[i]) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==5);\n        assert(fjac.rows()==33);\n        assert(fjac.cols()==5);\n        for(int i=0; i<33; i++) {\n            fjac(i,0) = 1.;\n            fjac(i,1) = exp(-b[3]*x[i]);\n            fjac(i,2) = exp(-b[4]*x[i]);\n            fjac(i,3) = -x[i]*b[1]*exp(-b[3]*x[i]);\n            fjac(i,4) = -x[i]*b[2]*exp(-b[4]*x[i]);\n        }\n        return 0;\n    }\n};\nconst double MGH17_functor::x[33] = { 0.000000E+00, 1.000000E+01, 2.000000E+01, 3.000000E+01, 4.000000E+01, 5.000000E+01, 6.000000E+01, 7.000000E+01, 8.000000E+01, 9.000000E+01, 1.000000E+02, 1.100000E+02, 1.200000E+02, 1.300000E+02, 1.400000E+02, 1.500000E+02, 1.600000E+02, 1.700000E+02, 1.800000E+02, 1.900000E+02, 2.000000E+02, 2.100000E+02, 2.200000E+02, 2.300000E+02, 2.400000E+02, 2.500000E+02, 2.600000E+02, 2.700000E+02, 2.800000E+02, 2.900000E+02, 3.000000E+02, 3.100000E+02, 3.200000E+02 };\nconst double MGH17_functor::y[33] = { 8.440000E-01, 9.080000E-01, 9.320000E-01, 9.360000E-01, 9.250000E-01, 9.080000E-01, 8.810000E-01, 8.500000E-01, 8.180000E-01, 7.840000E-01, 7.510000E-01, 7.180000E-01, 6.850000E-01, 6.580000E-01, 6.280000E-01, 6.030000E-01, 5.800000E-01, 5.580000E-01, 5.380000E-01, 5.220000E-01, 5.060000E-01, 4.900000E-01, 4.780000E-01, 4.670000E-01, 4.570000E-01, 4.480000E-01, 4.380000E-01, 4.310000E-01, 4.240000E-01, 4.200000E-01, 4.140000E-01, 4.110000E-01, 4.060000E-01 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/mgh17.shtml\nvoid testNistMGH17(void)\n{\n  const int n=5;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 50., 150., -100., 1., 2.;\n  // do the computation\n  MGH17_functor functor;\n  LevenbergMarquardt<MGH17_functor> lm(functor);\n  lm.parameters.ftol = NumTraits<double>::epsilon();\n  lm.parameters.xtol = NumTraits<double>::epsilon();\n  lm.parameters.maxfev = 1000;\n  info = lm.minimize(x);\n\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 5.4648946975E-05);\n  // check x\n  VERIFY_IS_APPROX(x[0], 3.7541005211E-01);\n  VERIFY_IS_APPROX(x[1], 1.9358469127E+00);\n  VERIFY_IS_APPROX(x[2], -1.4646871366E+00);\n  VERIFY_IS_APPROX(x[3], 1.2867534640E-02);\n  VERIFY_IS_APPROX(x[4], 2.2122699662E-02);\n  \n  // check return value\n  VERIFY_IS_EQUAL(info, 2); \n  LM_CHECK_N_ITERS(lm, 602, 545);\n\n  /*\n   * Second try\n   */\n  x<< 0.5  ,1.5  ,-1   ,0.01 ,0.02;\n  // do the computation\n  lm.resetParameters();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 18, 15);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 5.4648946975E-05);\n  // check x\n  VERIFY_IS_APPROX(x[0], 3.7541005211E-01);\n  VERIFY_IS_APPROX(x[1], 1.9358469127E+00);\n  VERIFY_IS_APPROX(x[2], -1.4646871366E+00);\n  VERIFY_IS_APPROX(x[3], 1.2867534640E-02);\n  VERIFY_IS_APPROX(x[4], 2.2122699662E-02);\n}\n\nstruct MGH09_functor : Functor<double>\n{\n    MGH09_functor(void) : Functor<double>(4,11) {}\n    static const double _x[11];\n    static const double y[11];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==4);\n        assert(fvec.size()==11);\n        for(int i=0; i<11; i++) {\n            double x = _x[i], xx=x*x;\n            fvec[i] = b[0]*(xx+x*b[1])/(xx+x*b[2]+b[3]) - y[i];\n        }\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==4);\n        assert(fjac.rows()==11);\n        assert(fjac.cols()==4);\n        for(int i=0; i<11; i++) {\n            double x = _x[i], xx=x*x;\n            double factor = 1./(xx+x*b[2]+b[3]);\n            fjac(i,0) = (xx+x*b[1]) * factor;\n            fjac(i,1) = b[0]*x* factor;\n            fjac(i,2) = - b[0]*(xx+x*b[1]) * x * factor * factor;\n            fjac(i,3) = - b[0]*(xx+x*b[1]) * factor * factor;\n        }\n        return 0;\n    }\n};\nconst double MGH09_functor::_x[11] = { 4., 2., 1., 5.E-1 , 2.5E-01, 1.670000E-01, 1.250000E-01,  1.E-01, 8.330000E-02, 7.140000E-02, 6.250000E-02 };\nconst double MGH09_functor::y[11] = { 1.957000E-01, 1.947000E-01, 1.735000E-01, 1.600000E-01, 8.440000E-02, 6.270000E-02, 4.560000E-02, 3.420000E-02, 3.230000E-02, 2.350000E-02, 2.460000E-02 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/mgh09.shtml\nvoid testNistMGH09(void)\n{\n  const int n=4;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 25., 39, 41.5, 39.;\n  // do the computation\n  MGH09_functor functor;\n  LevenbergMarquardt<MGH09_functor> lm(functor);\n  lm.parameters.maxfev = 1000;\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 490, 376);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 3.0750560385E-04);\n  // check x\n  VERIFY_IS_APPROX(x[0], 0.1928077089); // should be 1.9280693458E-01\n  VERIFY_IS_APPROX(x[1], 0.19126423573); // should be 1.9128232873E-01\n  VERIFY_IS_APPROX(x[2], 0.12305309914); // should be 1.2305650693E-01\n  VERIFY_IS_APPROX(x[3], 0.13605395375); // should be 1.3606233068E-01\n\n  /*\n   * Second try\n   */\n  x<< 0.25, 0.39, 0.415, 0.39;\n  // do the computation\n  lm.resetParameters();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 18, 16);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 3.0750560385E-04);\n  // check x\n  VERIFY_IS_APPROX(x[0], 0.19280781); // should be 1.9280693458E-01\n  VERIFY_IS_APPROX(x[1], 0.19126265); // should be 1.9128232873E-01\n  VERIFY_IS_APPROX(x[2], 0.12305280); // should be 1.2305650693E-01\n  VERIFY_IS_APPROX(x[3], 0.13605322); // should be 1.3606233068E-01\n}\n\n\n\nstruct Bennett5_functor : Functor<double>\n{\n    Bennett5_functor(void) : Functor<double>(3,154) {}\n    static const double x[154];\n    static const double y[154];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==3);\n        assert(fvec.size()==154);\n        for(int i=0; i<154; i++)\n            fvec[i] = b[0]* pow(b[1]+x[i],-1./b[2]) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==3);\n        assert(fjac.rows()==154);\n        assert(fjac.cols()==3);\n        for(int i=0; i<154; i++) {\n            double e = pow(b[1]+x[i],-1./b[2]);\n            fjac(i,0) = e;\n            fjac(i,1) = - b[0]*e/b[2]/(b[1]+x[i]);\n            fjac(i,2) = b[0]*e*log(b[1]+x[i])/b[2]/b[2];\n        }\n        return 0;\n    }\n};\nconst double Bennett5_functor::x[154] = { 7.447168E0, 8.102586E0, 8.452547E0, 8.711278E0, 8.916774E0, 9.087155E0, 9.232590E0, 9.359535E0, 9.472166E0, 9.573384E0, 9.665293E0, 9.749461E0, 9.827092E0, 9.899128E0, 9.966321E0, 10.029280E0, 10.088510E0, 10.144430E0, 10.197380E0, 10.247670E0, 10.295560E0, 10.341250E0, 10.384950E0, 10.426820E0, 10.467000E0, 10.505640E0, 10.542830E0, 10.578690E0, 10.613310E0, 10.646780E0, 10.679150E0, 10.710520E0, 10.740920E0, 10.770440E0, 10.799100E0, 10.826970E0, 10.854080E0, 10.880470E0, 10.906190E0, 10.931260E0, 10.955720E0, 10.979590E0, 11.002910E0, 11.025700E0, 11.047980E0, 11.069770E0, 11.091100E0, 11.111980E0, 11.132440E0, 11.152480E0, 11.172130E0, 11.191410E0, 11.210310E0, 11.228870E0, 11.247090E0, 11.264980E0, 11.282560E0, 11.299840E0, 11.316820E0, 11.333520E0, 11.349940E0, 11.366100E0, 11.382000E0, 11.397660E0, 11.413070E0, 11.428240E0, 11.443200E0, 11.457930E0, 11.472440E0, 11.486750E0, 11.500860E0, 11.514770E0, 11.528490E0, 11.542020E0, 11.555380E0, 11.568550E0,\n11.581560E0, 11.594420E0, 11.607121E0, 11.619640E0, 11.632000E0, 11.644210E0, 11.656280E0, 11.668200E0, 11.679980E0, 11.691620E0, 11.703130E0, 11.714510E0, 11.725760E0, 11.736880E0, 11.747890E0, 11.758780E0, 11.769550E0, 11.780200E0, 11.790730E0, 11.801160E0, 11.811480E0, 11.821700E0, 11.831810E0, 11.841820E0, 11.851730E0, 11.861550E0, 11.871270E0, 11.880890E0, 11.890420E0, 11.899870E0, 11.909220E0, 11.918490E0, 11.927680E0, 11.936780E0, 11.945790E0, 11.954730E0, 11.963590E0, 11.972370E0, 11.981070E0, 11.989700E0, 11.998260E0, 12.006740E0, 12.015150E0, 12.023490E0, 12.031760E0, 12.039970E0, 12.048100E0, 12.056170E0, 12.064180E0, 12.072120E0, 12.080010E0, 12.087820E0, 12.095580E0, 12.103280E0, 12.110920E0, 12.118500E0, 12.126030E0, 12.133500E0, 12.140910E0, 12.148270E0, 12.155570E0, 12.162830E0, 12.170030E0, 12.177170E0, 12.184270E0, 12.191320E0, 12.198320E0, 12.205270E0, 12.212170E0, 12.219030E0, 12.225840E0, 12.232600E0, 12.239320E0, 12.245990E0, 12.252620E0, 12.259200E0, 12.265750E0, 12.272240E0 };\nconst double Bennett5_functor::y[154] = { -34.834702E0 ,-34.393200E0 ,-34.152901E0 ,-33.979099E0 ,-33.845901E0 ,-33.732899E0 ,-33.640301E0 ,-33.559200E0 ,-33.486801E0 ,-33.423100E0 ,-33.365101E0 ,-33.313000E0 ,-33.260899E0 ,-33.217400E0 ,-33.176899E0 ,-33.139198E0 ,-33.101601E0 ,-33.066799E0 ,-33.035000E0 ,-33.003101E0 ,-32.971298E0 ,-32.942299E0 ,-32.916302E0 ,-32.890202E0 ,-32.864101E0 ,-32.841000E0 ,-32.817799E0 ,-32.797501E0 ,-32.774300E0 ,-32.757000E0 ,-32.733799E0 ,-32.716400E0 ,-32.699100E0 ,-32.678799E0 ,-32.661400E0 ,-32.644001E0 ,-32.626701E0 ,-32.612202E0 ,-32.597698E0 ,-32.583199E0 ,-32.568699E0 ,-32.554298E0 ,-32.539799E0 ,-32.525299E0 ,-32.510799E0 ,-32.499199E0 ,-32.487598E0 ,-32.473202E0 ,-32.461601E0 ,-32.435501E0 ,-32.435501E0 ,-32.426800E0 ,-32.412300E0 ,-32.400799E0 ,-32.392101E0 ,-32.380501E0 ,-32.366001E0 ,-32.357300E0 ,-32.348598E0 ,-32.339901E0 ,-32.328400E0 ,-32.319698E0 ,-32.311001E0 ,-32.299400E0 ,-32.290699E0 ,-32.282001E0 ,-32.273300E0 ,-32.264599E0 ,-32.256001E0 ,-32.247299E0\n,-32.238602E0 ,-32.229900E0 ,-32.224098E0 ,-32.215401E0 ,-32.203800E0 ,-32.198002E0 ,-32.189400E0 ,-32.183601E0 ,-32.174900E0 ,-32.169102E0 ,-32.163300E0 ,-32.154598E0 ,-32.145901E0 ,-32.140099E0 ,-32.131401E0 ,-32.125599E0 ,-32.119801E0 ,-32.111198E0 ,-32.105400E0 ,-32.096699E0 ,-32.090900E0 ,-32.088001E0 ,-32.079300E0 ,-32.073502E0 ,-32.067699E0 ,-32.061901E0 ,-32.056099E0 ,-32.050301E0 ,-32.044498E0 ,-32.038799E0 ,-32.033001E0 ,-32.027199E0 ,-32.024300E0 ,-32.018501E0 ,-32.012699E0 ,-32.004002E0 ,-32.001099E0 ,-31.995300E0 ,-31.989500E0 ,-31.983700E0 ,-31.977900E0 ,-31.972099E0 ,-31.969299E0 ,-31.963501E0 ,-31.957701E0 ,-31.951900E0 ,-31.946100E0 ,-31.940300E0 ,-31.937401E0 ,-31.931601E0 ,-31.925800E0 ,-31.922899E0 ,-31.917101E0 ,-31.911301E0 ,-31.908400E0 ,-31.902599E0 ,-31.896900E0 ,-31.893999E0 ,-31.888201E0 ,-31.885300E0 ,-31.882401E0 ,-31.876600E0 ,-31.873699E0 ,-31.867901E0 ,-31.862101E0 ,-31.859200E0 ,-31.856300E0 ,-31.850500E0 ,-31.844700E0 ,-31.841801E0 ,-31.838900E0 ,-31.833099E0 ,-31.830200E0 ,\n-31.827299E0 ,-31.821600E0 ,-31.818701E0 ,-31.812901E0 ,-31.809999E0 ,-31.807100E0 ,-31.801300E0 ,-31.798401E0 ,-31.795500E0 ,-31.789700E0 ,-31.786800E0 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/bennett5.shtml\nvoid testNistBennett5(void)\n{\n  const int  n=3;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< -2000., 50., 0.8;\n  // do the computation\n  Bennett5_functor functor;\n  LevenbergMarquardt<Bennett5_functor> lm(functor);\n  lm.parameters.maxfev = 1000;\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 758, 744);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 5.2404744073E-04);\n  // check x\n  VERIFY_IS_APPROX(x[0], -2.5235058043E+03);\n  VERIFY_IS_APPROX(x[1], 4.6736564644E+01);\n  VERIFY_IS_APPROX(x[2], 9.3218483193E-01);\n  /*\n   * Second try\n   */\n  x<< -1500., 45., 0.85;\n  // do the computation\n  lm.resetParameters();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 203, 192);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 5.2404744073E-04);\n  // check x\n  VERIFY_IS_APPROX(x[0], -2523.3007865); // should be -2.5235058043E+03\n  VERIFY_IS_APPROX(x[1], 46.735705771); // should be 4.6736564644E+01);\n  VERIFY_IS_APPROX(x[2], 0.93219881891); // should be 9.3218483193E-01);\n}\n\nstruct thurber_functor : Functor<double>\n{\n    thurber_functor(void) : Functor<double>(7,37) {}\n    static const double _x[37];\n    static const double _y[37];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        //        int called=0; printf(\"call hahn1_functor with  iflag=%d, called=%d\\n\", iflag, called); if (iflag==1) called++;\n        assert(b.size()==7);\n        assert(fvec.size()==37);\n        for(int i=0; i<37; i++) {\n            double x=_x[i], xx=x*x, xxx=xx*x;\n            fvec[i] = (b[0]+b[1]*x+b[2]*xx+b[3]*xxx) / (1.+b[4]*x+b[5]*xx+b[6]*xxx) - _y[i];\n        }\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==7);\n        assert(fjac.rows()==37);\n        assert(fjac.cols()==7);\n        for(int i=0; i<37; i++) {\n            double x=_x[i], xx=x*x, xxx=xx*x;\n            double fact = 1./(1.+b[4]*x+b[5]*xx+b[6]*xxx);\n            fjac(i,0) = 1.*fact;\n            fjac(i,1) = x*fact;\n            fjac(i,2) = xx*fact;\n            fjac(i,3) = xxx*fact;\n            fact = - (b[0]+b[1]*x+b[2]*xx+b[3]*xxx) * fact * fact;\n            fjac(i,4) = x*fact;\n            fjac(i,5) = xx*fact;\n            fjac(i,6) = xxx*fact;\n        }\n        return 0;\n    }\n};\nconst double thurber_functor::_x[37] = { -3.067E0, -2.981E0, -2.921E0, -2.912E0, -2.840E0, -2.797E0, -2.702E0, -2.699E0, -2.633E0, -2.481E0, -2.363E0, -2.322E0, -1.501E0, -1.460E0, -1.274E0, -1.212E0, -1.100E0, -1.046E0, -0.915E0, -0.714E0, -0.566E0, -0.545E0, -0.400E0, -0.309E0, -0.109E0, -0.103E0, 0.010E0, 0.119E0, 0.377E0, 0.790E0, 0.963E0, 1.006E0, 1.115E0, 1.572E0, 1.841E0, 2.047E0, 2.200E0 };\nconst double thurber_functor::_y[37] = { 80.574E0, 84.248E0, 87.264E0, 87.195E0, 89.076E0, 89.608E0, 89.868E0, 90.101E0, 92.405E0, 95.854E0, 100.696E0, 101.060E0, 401.672E0, 390.724E0, 567.534E0, 635.316E0, 733.054E0, 759.087E0, 894.206E0, 990.785E0, 1090.109E0, 1080.914E0, 1122.643E0, 1178.351E0, 1260.531E0, 1273.514E0, 1288.339E0, 1327.543E0, 1353.863E0, 1414.509E0, 1425.208E0, 1421.384E0, 1442.962E0, 1464.350E0, 1468.705E0, 1447.894E0, 1457.628E0};\n\n// http://www.itl.nist.gov/div898/strd/nls/data/thurber.shtml\nvoid testNistThurber(void)\n{\n  const int n=7;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 1000 ,1000 ,400 ,40 ,0.7,0.3,0.0 ;\n  // do the computation\n  thurber_functor functor;\n  LevenbergMarquardt<thurber_functor> lm(functor);\n  lm.parameters.ftol = 1.E4*NumTraits<double>::epsilon();\n  lm.parameters.xtol = 1.E4*NumTraits<double>::epsilon();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 39,36);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 5.6427082397E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.2881396800E+03);\n  VERIFY_IS_APPROX(x[1], 1.4910792535E+03);\n  VERIFY_IS_APPROX(x[2], 5.8323836877E+02);\n  VERIFY_IS_APPROX(x[3], 7.5416644291E+01);\n  VERIFY_IS_APPROX(x[4], 9.6629502864E-01);\n  VERIFY_IS_APPROX(x[5], 3.9797285797E-01);\n  VERIFY_IS_APPROX(x[6], 4.9727297349E-02);\n\n  /*\n   * Second try\n   */\n  x<< 1300 ,1500 ,500  ,75   ,1    ,0.4  ,0.05  ;\n  // do the computation\n  lm.resetParameters();\n  lm.parameters.ftol = 1.E4*NumTraits<double>::epsilon();\n  lm.parameters.xtol = 1.E4*NumTraits<double>::epsilon();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 29, 28);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 5.6427082397E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.2881396800E+03);\n  VERIFY_IS_APPROX(x[1], 1.4910792535E+03);\n  VERIFY_IS_APPROX(x[2], 5.8323836877E+02);\n  VERIFY_IS_APPROX(x[3], 7.5416644291E+01);\n  VERIFY_IS_APPROX(x[4], 9.6629502864E-01);\n  VERIFY_IS_APPROX(x[5], 3.9797285797E-01);\n  VERIFY_IS_APPROX(x[6], 4.9727297349E-02);\n}\n\nstruct rat43_functor : Functor<double>\n{\n    rat43_functor(void) : Functor<double>(4,15) {}\n    static const double x[15];\n    static const double y[15];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==4);\n        assert(fvec.size()==15);\n        for(int i=0; i<15; i++)\n            fvec[i] = b[0] * pow(1.+exp(b[1]-b[2]*x[i]),-1./b[3]) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==4);\n        assert(fjac.rows()==15);\n        assert(fjac.cols()==4);\n        for(int i=0; i<15; i++) {\n            double e = exp(b[1]-b[2]*x[i]);\n            double power = -1./b[3];\n            fjac(i,0) = pow(1.+e, power);\n            fjac(i,1) = power*b[0]*e*pow(1.+e, power-1.);\n            fjac(i,2) = -power*b[0]*e*x[i]*pow(1.+e, power-1.);\n            fjac(i,3) = b[0]*power*power*log(1.+e)*pow(1.+e, power);\n        }\n        return 0;\n    }\n};\nconst double rat43_functor::x[15] = { 1., 2., 3., 4., 5., 6., 7., 8., 9., 10., 11., 12., 13., 14., 15. };\nconst double rat43_functor::y[15] = { 16.08, 33.83, 65.80, 97.20, 191.55, 326.20, 386.87, 520.53, 590.03, 651.92, 724.93, 699.56, 689.96, 637.56, 717.41 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/ratkowsky3.shtml\nvoid testNistRat43(void)\n{\n  const int n=4;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 100., 10., 1., 1.;\n  // do the computation\n  rat43_functor functor;\n  LevenbergMarquardt<rat43_functor> lm(functor);\n  lm.parameters.ftol = 1.E6*NumTraits<double>::epsilon();\n  lm.parameters.xtol = 1.E6*NumTraits<double>::epsilon();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 27, 20);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 8.7864049080E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 6.9964151270E+02);\n  VERIFY_IS_APPROX(x[1], 5.2771253025E+00);\n  VERIFY_IS_APPROX(x[2], 7.5962938329E-01);\n  VERIFY_IS_APPROX(x[3], 1.2792483859E+00);\n\n  /*\n   * Second try\n   */\n  x<< 700., 5., 0.75, 1.3;\n  // do the computation\n  lm.resetParameters();\n  lm.parameters.ftol = 1.E5*NumTraits<double>::epsilon();\n  lm.parameters.xtol = 1.E5*NumTraits<double>::epsilon();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 9, 8);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 8.7864049080E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 6.9964151270E+02);\n  VERIFY_IS_APPROX(x[1], 5.2771253025E+00);\n  VERIFY_IS_APPROX(x[2], 7.5962938329E-01);\n  VERIFY_IS_APPROX(x[3], 1.2792483859E+00);\n}\n\n\n\nstruct eckerle4_functor : Functor<double>\n{\n    eckerle4_functor(void) : Functor<double>(3,35) {}\n    static const double x[35];\n    static const double y[35];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==3);\n        assert(fvec.size()==35);\n        for(int i=0; i<35; i++)\n            fvec[i] = b[0]/b[1] * exp(-0.5*(x[i]-b[2])*(x[i]-b[2])/(b[1]*b[1])) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==3);\n        assert(fjac.rows()==35);\n        assert(fjac.cols()==3);\n        for(int i=0; i<35; i++) {\n            double b12 = b[1]*b[1];\n            double e = exp(-0.5*(x[i]-b[2])*(x[i]-b[2])/b12);\n            fjac(i,0) = e / b[1];\n            fjac(i,1) = ((x[i]-b[2])*(x[i]-b[2])/b12-1.) * b[0]*e/b12;\n            fjac(i,2) = (x[i]-b[2])*e*b[0]/b[1]/b12;\n        }\n        return 0;\n    }\n};\nconst double eckerle4_functor::x[35] = { 400.0, 405.0, 410.0, 415.0, 420.0, 425.0, 430.0, 435.0, 436.5, 438.0, 439.5, 441.0, 442.5, 444.0, 445.5, 447.0, 448.5, 450.0, 451.5, 453.0, 454.5, 456.0, 457.5, 459.0, 460.5, 462.0, 463.5, 465.0, 470.0, 475.0, 480.0, 485.0, 490.0, 495.0, 500.0};\nconst double eckerle4_functor::y[35] = { 0.0001575, 0.0001699, 0.0002350, 0.0003102, 0.0004917, 0.0008710, 0.0017418, 0.0046400, 0.0065895, 0.0097302, 0.0149002, 0.0237310, 0.0401683, 0.0712559, 0.1264458, 0.2073413, 0.2902366, 0.3445623, 0.3698049, 0.3668534, 0.3106727, 0.2078154, 0.1164354, 0.0616764, 0.0337200, 0.0194023, 0.0117831, 0.0074357, 0.0022732, 0.0008800, 0.0004579, 0.0002345, 0.0001586, 0.0001143, 0.0000710 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/eckerle4.shtml\nvoid testNistEckerle4(void)\n{\n  const int n=3;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 1., 10., 500.;\n  // do the computation\n  eckerle4_functor functor;\n  LevenbergMarquardt<eckerle4_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 18, 15);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 1.4635887487E-03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.5543827178);\n  VERIFY_IS_APPROX(x[1], 4.0888321754);\n  VERIFY_IS_APPROX(x[2], 4.5154121844E+02);\n\n  /*\n   * Second try\n   */\n  x<< 1.5, 5., 450.;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 7, 6);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 1.4635887487E-03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.5543827178);\n  VERIFY_IS_APPROX(x[1], 4.0888321754);\n  VERIFY_IS_APPROX(x[2], 4.5154121844E+02);\n}\n\nEIGEN_DECLARE_TEST(NonLinearOptimization)\n{\n    // Tests using the examples provided by (c)minpack\n    CALL_SUBTEST/*_1*/(testChkder());\n    CALL_SUBTEST/*_1*/(testLmder1());\n    CALL_SUBTEST/*_1*/(testLmder());\n    CALL_SUBTEST/*_2*/(testHybrj1());\n    CALL_SUBTEST/*_2*/(testHybrj());\n    CALL_SUBTEST/*_2*/(testHybrd1());\n    CALL_SUBTEST/*_2*/(testHybrd());\n    CALL_SUBTEST/*_3*/(testLmstr1());\n    CALL_SUBTEST/*_3*/(testLmstr());\n    CALL_SUBTEST/*_3*/(testLmdif1());\n    CALL_SUBTEST/*_3*/(testLmdif());\n\n    // NIST tests, level of difficulty = \"Lower\"\n    CALL_SUBTEST/*_4*/(testNistMisra1a());\n    CALL_SUBTEST/*_4*/(testNistChwirut2());\n\n    // NIST tests, level of difficulty = \"Average\"\n    CALL_SUBTEST/*_5*/(testNistHahn1());\n    CALL_SUBTEST/*_6*/(testNistMisra1d());\n    CALL_SUBTEST/*_7*/(testNistMGH17());\n    CALL_SUBTEST/*_8*/(testNistLanczos1());\n\n//     // NIST tests, level of difficulty = \"Higher\"\n    CALL_SUBTEST/*_9*/(testNistRat42());\n//     CALL_SUBTEST/*_10*/(testNistMGH10());\n    CALL_SUBTEST/*_11*/(testNistBoxBOD());\n//     CALL_SUBTEST/*_12*/(testNistMGH09());\n    CALL_SUBTEST/*_13*/(testNistBennett5());\n    CALL_SUBTEST/*_14*/(testNistThurber());\n    CALL_SUBTEST/*_15*/(testNistRat43());\n    CALL_SUBTEST/*_16*/(testNistEckerle4());\n}\n\n/*\n * Can be useful for debugging...\n  printf(\"info, nfev : %d, %d\\n\", info, lm.nfev);\n  printf(\"info, nfev, njev : %d, %d, %d\\n\", info, solver.nfev, solver.njev);\n  printf(\"info, nfev : %d, %d\\n\", info, solver.nfev);\n  printf(\"x[0] : %.32g\\n\", x[0]);\n  printf(\"x[1] : %.32g\\n\", x[1]);\n  printf(\"x[2] : %.32g\\n\", x[2]);\n  printf(\"x[3] : %.32g\\n\", x[3]);\n  printf(\"fvec.blueNorm() : %.32g\\n\", solver.fvec.blueNorm());\n  printf(\"fvec.blueNorm() : %.32g\\n\", lm.fvec.blueNorm());\n\n  printf(\"info, nfev, njev : %d, %d, %d\\n\", info, lm.nfev, lm.njev);\n  printf(\"fvec.squaredNorm() : %.13g\\n\", lm.fvec.squaredNorm());\n  std::cout << x << std::endl;\n  std::cout.precision(9);\n  std::cout << x[0] << std::endl;\n  std::cout << x[1] << std::endl;\n  std::cout << x[2] << std::endl;\n  std::cout << x[3] << std::endl;\n*/\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/NumericalDiff.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n\n#include <stdio.h>\n\n#include \"main.h\"\n#include <unsupported/Eigen/NumericalDiff>\n    \n// Generic functor\ntemplate<typename Scalar_, int NX=Dynamic, int NY=Dynamic>\nstruct Functor\n{\n  typedef Scalar_ Scalar;\n  enum {\n    InputsAtCompileTime = NX,\n    ValuesAtCompileTime = NY\n  };\n  typedef Matrix<Scalar,InputsAtCompileTime,1> InputType;\n  typedef Matrix<Scalar,ValuesAtCompileTime,1> ValueType;\n  typedef Matrix<Scalar,ValuesAtCompileTime,InputsAtCompileTime> JacobianType;\n  \n  int m_inputs, m_values;\n  \n  Functor() : m_inputs(InputsAtCompileTime), m_values(ValuesAtCompileTime) {}\n  Functor(int inputs_, int values_) : m_inputs(inputs_), m_values(values_) {}\n  \n  int inputs() const { return m_inputs; }\n  int values() const { return m_values; }\n\n};\n\nstruct my_functor : Functor<double>\n{\n    my_functor(void): Functor<double>(3,15) {}\n    int operator()(const VectorXd &x, VectorXd &fvec) const\n    {\n        double tmp1, tmp2, tmp3;\n        double y[15] = {1.4e-1, 1.8e-1, 2.2e-1, 2.5e-1, 2.9e-1, 3.2e-1, 3.5e-1,\n            3.9e-1, 3.7e-1, 5.8e-1, 7.3e-1, 9.6e-1, 1.34, 2.1, 4.39};\n\n        for (int i = 0; i < values(); i++)\n        {\n            tmp1 = i+1;\n            tmp2 = 16 - i - 1;\n            tmp3 = (i>=8)? tmp2 : tmp1;\n            fvec[i] = y[i] - (x[0] + tmp1/(x[1]*tmp2 + x[2]*tmp3));\n        }\n        return 0;\n    }\n\n    int actual_df(const VectorXd &x, MatrixXd &fjac) const\n    {\n        double tmp1, tmp2, tmp3, tmp4;\n        for (int i = 0; i < values(); i++)\n        {\n            tmp1 = i+1;\n            tmp2 = 16 - i - 1;\n            tmp3 = (i>=8)? tmp2 : tmp1;\n            tmp4 = (x[1]*tmp2 + x[2]*tmp3); tmp4 = tmp4*tmp4;\n            fjac(i,0) = -1;\n            fjac(i,1) = tmp1*tmp2/tmp4;\n            fjac(i,2) = tmp1*tmp3/tmp4;\n        }\n        return 0;\n    }\n};\n\nvoid test_forward()\n{\n    VectorXd x(3);\n    MatrixXd jac(15,3);\n    MatrixXd actual_jac(15,3);\n    my_functor functor;\n\n    x << 0.082, 1.13, 2.35;\n\n    // real one \n    functor.actual_df(x, actual_jac);\n//    std::cout << actual_jac << std::endl << std::endl;\n\n    // using NumericalDiff\n    NumericalDiff<my_functor> numDiff(functor);\n    numDiff.df(x, jac);\n//    std::cout << jac << std::endl;\n\n    VERIFY_IS_APPROX(jac, actual_jac);\n}\n\nvoid test_central()\n{\n    VectorXd x(3);\n    MatrixXd jac(15,3);\n    MatrixXd actual_jac(15,3);\n    my_functor functor;\n\n    x << 0.082, 1.13, 2.35;\n\n    // real one \n    functor.actual_df(x, actual_jac);\n\n    // using NumericalDiff\n    NumericalDiff<my_functor,Central> numDiff(functor);\n    numDiff.df(x, jac);\n\n    VERIFY_IS_APPROX(jac, actual_jac);\n}\n\nEIGEN_DECLARE_TEST(NumericalDiff)\n{\n    CALL_SUBTEST(test_forward());\n    CALL_SUBTEST(test_central());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/alignedvector3.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <unsupported/Eigen/AlignedVector3>\n\nnamespace Eigen {\n\ntemplate<typename T,typename Derived>\nT test_relative_error(const AlignedVector3<T> &a, const MatrixBase<Derived> &b)\n{\n  return test_relative_error(a.coeffs().template head<3>(), b);\n}\n\n}\n\ntemplate<typename Scalar>\nvoid alignedvector3()\n{\n  Scalar s1 = internal::random<Scalar>();\n  Scalar s2 = internal::random<Scalar>();\n  typedef Matrix<Scalar,3,1> RefType;\n  typedef Matrix<Scalar,3,3> Mat33;\n  typedef AlignedVector3<Scalar> FastType;\n  RefType  r1(RefType::Random()), r2(RefType::Random()), r3(RefType::Random()),\n           r4(RefType::Random()), r5(RefType::Random());\n  FastType f1(r1), f2(r2), f3(r3), f4(r4), f5(r5);\n  Mat33 m1(Mat33::Random());\n  \n  VERIFY_IS_APPROX(f1,r1);\n  VERIFY_IS_APPROX(f4,r4);\n\n  VERIFY_IS_APPROX(f4+f1,r4+r1);\n  VERIFY_IS_APPROX(f4-f1,r4-r1);\n  VERIFY_IS_APPROX(f4+f1-f2,r4+r1-r2);\n  VERIFY_IS_APPROX(f4+=f3,r4+=r3);\n  VERIFY_IS_APPROX(f4-=f5,r4-=r5);\n  VERIFY_IS_APPROX(f4-=f5+f1,r4-=r5+r1);\n  VERIFY_IS_APPROX(f5+f1-s1*f2,r5+r1-s1*r2);\n  VERIFY_IS_APPROX(f5+f1/s2-s1*f2,r5+r1/s2-s1*r2);\n  \n  VERIFY_IS_APPROX(m1*f4,m1*r4);\n  VERIFY_IS_APPROX(f4.transpose()*m1,r4.transpose()*m1);\n  \n  VERIFY_IS_APPROX(f2.dot(f3),r2.dot(r3));\n  VERIFY_IS_APPROX(f2.cross(f3),r2.cross(r3));\n  VERIFY_IS_APPROX(f2.norm(),r2.norm());\n\n  VERIFY_IS_APPROX(f2.normalized(),r2.normalized());\n\n  VERIFY_IS_APPROX((f2+f1).normalized(),(r2+r1).normalized());\n  \n  f2.normalize();\n  r2.normalize();\n  VERIFY_IS_APPROX(f2,r2);\n  \n  {\n    FastType f6 = RefType::Zero();\n    FastType f7 = FastType::Zero();\n    VERIFY_IS_APPROX(f6,f7);\n    f6 = r4+r1;\n    VERIFY_IS_APPROX(f6,r4+r1);\n    f6 -= Scalar(2)*r4;\n    VERIFY_IS_APPROX(f6,r1-r4);\n  }\n  \n  FastType f8, f9(0,0,0);\n  VERIFY_IS_APPROX(f9-f1,-f1);\n\n  std::stringstream ss1, ss2;\n  ss1 << f1;\n  ss2 << r1;\n  VERIFY(ss1.str()==ss2.str());\n}\n\nEIGEN_DECLARE_TEST(alignedvector3)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST( alignedvector3<float>() );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/autodiff.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <unsupported/Eigen/AutoDiff>\n\ntemplate<typename Scalar>\nEIGEN_DONT_INLINE Scalar foo(const Scalar& x, const Scalar& y)\n{\n  using namespace std;\n//   return x+std::sin(y);\n  EIGEN_ASM_COMMENT(\"mybegin\");\n  // pow(float, int) promotes to pow(double, double)\n  return x*2 - 1 + static_cast<Scalar>(pow(1+x,2)) + 2*sqrt(y*y+0) - 4 * sin(0+x) + 2 * cos(y+0) - exp(Scalar(-0.5)*x*x+0);\n  //return x+2*y*x;//x*2 -std::pow(x,2);//(2*y/x);// - y*2;\n  EIGEN_ASM_COMMENT(\"myend\");\n}\n\ntemplate<typename Vector>\nEIGEN_DONT_INLINE typename Vector::Scalar foo(const Vector& p)\n{\n  typedef typename Vector::Scalar Scalar;\n  return (p-Vector(Scalar(-1),Scalar(1.))).norm() + (p.array() * p.array()).sum() + p.dot(p);\n}\n\ntemplate<typename Scalar_, int NX=Dynamic, int NY=Dynamic>\nstruct TestFunc1\n{\n  typedef Scalar_ Scalar;\n  enum {\n    InputsAtCompileTime = NX,\n    ValuesAtCompileTime = NY\n  };\n  typedef Matrix<Scalar,InputsAtCompileTime,1> InputType;\n  typedef Matrix<Scalar,ValuesAtCompileTime,1> ValueType;\n  typedef Matrix<Scalar,ValuesAtCompileTime,InputsAtCompileTime> JacobianType;\n\n  int m_inputs, m_values;\n\n  TestFunc1() : m_inputs(InputsAtCompileTime), m_values(ValuesAtCompileTime) {}\n  TestFunc1(int inputs_, int values_) : m_inputs(inputs_), m_values(values_) {}\n\n  int inputs() const { return m_inputs; }\n  int values() const { return m_values; }\n\n  template<typename T>\n  void operator() (const Matrix<T,InputsAtCompileTime,1>& x, Matrix<T,ValuesAtCompileTime,1>* _v) const\n  {\n    Matrix<T,ValuesAtCompileTime,1>& v = *_v;\n\n    v[0] = 2 * x[0] * x[0] + x[0] * x[1];\n    v[1] = 3 * x[1] * x[0] + 0.5 * x[1] * x[1];\n    if(inputs()>2)\n    {\n      v[0] += 0.5 * x[2];\n      v[1] += x[2];\n    }\n    if(values()>2)\n    {\n      v[2] = 3 * x[1] * x[0] * x[0];\n    }\n    if (inputs()>2 && values()>2)\n      v[2] *= x[2];\n  }\n\n  void operator() (const InputType& x, ValueType* v, JacobianType* _j) const\n  {\n    (*this)(x, v);\n\n    if(_j)\n    {\n      JacobianType& j = *_j;\n\n      j(0,0) = 4 * x[0] + x[1];\n      j(1,0) = 3 * x[1];\n\n      j(0,1) = x[0];\n      j(1,1) = 3 * x[0] + 2 * 0.5 * x[1];\n\n      if (inputs()>2)\n      {\n        j(0,2) = 0.5;\n        j(1,2) = 1;\n      }\n      if(values()>2)\n      {\n        j(2,0) = 3 * x[1] * 2 * x[0];\n        j(2,1) = 3 * x[0] * x[0];\n      }\n      if (inputs()>2 && values()>2)\n      {\n        j(2,0) *= x[2];\n        j(2,1) *= x[2];\n\n        j(2,2) = 3 * x[1] * x[0] * x[0];\n        j(2,2) = 3 * x[1] * x[0] * x[0];\n      }\n    }\n  }\n};\n\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n/* Test functor for the C++11 features. */\ntemplate <typename Scalar>\nstruct integratorFunctor\n{\n    typedef Matrix<Scalar, 2, 1> InputType;\n    typedef Matrix<Scalar, 2, 1> ValueType;\n\n    /*\n     * Implementation starts here.\n     */\n    integratorFunctor(const Scalar gain) : _gain(gain) {}\n    integratorFunctor(const integratorFunctor& f) : _gain(f._gain) {}\n    const Scalar _gain;\n\n    template <typename T1, typename T2>\n    void operator() (const T1 &input, T2 *output, const Scalar dt) const\n    {\n        T2 &o = *output;\n\n        /* Integrator to test the AD. */\n        o[0] = input[0] + input[1] * dt * _gain;\n        o[1] = input[1] * _gain;\n    }\n\n    /* Only needed for the test */\n    template <typename T1, typename T2, typename T3>\n    void operator() (const T1 &input, T2 *output, T3 *jacobian, const Scalar dt) const\n    {\n        T2 &o = *output;\n\n        /* Integrator to test the AD. */\n        o[0] = input[0] + input[1] * dt * _gain;\n        o[1] = input[1] * _gain;\n\n        if (jacobian)\n        {\n            T3 &j = *jacobian;\n\n            j(0, 0) = 1;\n            j(0, 1) = dt * _gain;\n            j(1, 0) = 0;\n            j(1, 1) = _gain;\n        }\n    }\n\n};\n\ntemplate<typename Func> void forward_jacobian_cpp11(const Func& f)\n{\n    typedef typename Func::ValueType::Scalar Scalar;\n    typedef typename Func::ValueType ValueType;\n    typedef typename Func::InputType InputType;\n    typedef typename AutoDiffJacobian<Func>::JacobianType JacobianType;\n\n    InputType x = InputType::Random(InputType::RowsAtCompileTime);\n    ValueType y, yref;\n    JacobianType j, jref;\n\n    const Scalar dt = internal::random<double>();\n\n    jref.setZero();\n    yref.setZero();\n    f(x, &yref, &jref, dt);\n\n    //std::cerr << \"y, yref, jref: \" << \"\\n\";\n    //std::cerr << y.transpose() << \"\\n\\n\";\n    //std::cerr << yref << \"\\n\\n\";\n    //std::cerr << jref << \"\\n\\n\";\n\n    AutoDiffJacobian<Func> autoj(f);\n    autoj(x, &y, &j, dt);\n\n    //std::cerr << \"y j (via autodiff): \" << \"\\n\";\n    //std::cerr << y.transpose() << \"\\n\\n\";\n    //std::cerr << j << \"\\n\\n\";\n\n    VERIFY_IS_APPROX(y, yref);\n    VERIFY_IS_APPROX(j, jref);\n}\n#endif\n\ntemplate<typename Func> void forward_jacobian(const Func& f)\n{\n    typename Func::InputType x = Func::InputType::Random(f.inputs());\n    typename Func::ValueType y(f.values()), yref(f.values());\n    typename Func::JacobianType j(f.values(),f.inputs()), jref(f.values(),f.inputs());\n\n    jref.setZero();\n    yref.setZero();\n    f(x,&yref,&jref);\n//     std::cerr << y.transpose() << \"\\n\\n\";;\n//     std::cerr << j << \"\\n\\n\";;\n\n    j.setZero();\n    y.setZero();\n    AutoDiffJacobian<Func> autoj(f);\n    autoj(x, &y, &j);\n//     std::cerr << y.transpose() << \"\\n\\n\";;\n//     std::cerr << j << \"\\n\\n\";;\n\n    VERIFY_IS_APPROX(y, yref);\n    VERIFY_IS_APPROX(j, jref);\n}\n\n// TODO also check actual derivatives!\ntemplate <int>\nvoid test_autodiff_scalar()\n{\n  Vector2f p = Vector2f::Random();\n  typedef AutoDiffScalar<Vector2f> AD;\n  AD ax(p.x(),Vector2f::UnitX());\n  AD ay(p.y(),Vector2f::UnitY());\n  AD res = foo<AD>(ax,ay);\n  VERIFY_IS_APPROX(res.value(), foo(p.x(),p.y()));\n}\n\n\n// TODO also check actual derivatives!\ntemplate <int>\nvoid test_autodiff_vector()\n{\n  Vector2f p = Vector2f::Random();\n  typedef AutoDiffScalar<Vector2f> AD;\n  typedef Matrix<AD,2,1> VectorAD;\n  VectorAD ap = p.cast<AD>();\n  ap.x().derivatives() = Vector2f::UnitX();\n  ap.y().derivatives() = Vector2f::UnitY();\n\n  AD res = foo<VectorAD>(ap);\n  VERIFY_IS_APPROX(res.value(), foo(p));\n}\n\ntemplate <int>\nvoid test_autodiff_jacobian()\n{\n  CALL_SUBTEST(( forward_jacobian(TestFunc1<double,2,2>()) ));\n  CALL_SUBTEST(( forward_jacobian(TestFunc1<double,2,3>()) ));\n  CALL_SUBTEST(( forward_jacobian(TestFunc1<double,3,2>()) ));\n  CALL_SUBTEST(( forward_jacobian(TestFunc1<double,3,3>()) ));\n  CALL_SUBTEST(( forward_jacobian(TestFunc1<double>(3,3)) ));\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  CALL_SUBTEST(( forward_jacobian_cpp11(integratorFunctor<double>(10)) ));\n#endif\n}\n\n\ntemplate <int>\nvoid test_autodiff_hessian()\n{\n  typedef AutoDiffScalar<VectorXd> AD;\n  typedef Matrix<AD,Eigen::Dynamic,1> VectorAD;\n  typedef AutoDiffScalar<VectorAD> ADD;\n  typedef Matrix<ADD,Eigen::Dynamic,1> VectorADD;\n  VectorADD x(2);\n  double s1 = internal::random<double>(), s2 = internal::random<double>(), s3 = internal::random<double>(), s4 = internal::random<double>();\n  x(0).value()=s1;\n  x(1).value()=s2;\n\n  //set unit vectors for the derivative directions (partial derivatives of the input vector)\n  x(0).derivatives().resize(2);\n  x(0).derivatives().setZero();\n  x(0).derivatives()(0)= 1;\n  x(1).derivatives().resize(2);\n  x(1).derivatives().setZero();\n  x(1).derivatives()(1)=1;\n\n  //repeat partial derivatives for the inner AutoDiffScalar\n  x(0).value().derivatives() = VectorXd::Unit(2,0);\n  x(1).value().derivatives() = VectorXd::Unit(2,1);\n\n  //set the hessian matrix to zero\n  for(int idx=0; idx<2; idx++) {\n      x(0).derivatives()(idx).derivatives()  = VectorXd::Zero(2);\n      x(1).derivatives()(idx).derivatives()  = VectorXd::Zero(2);\n  }\n\n  ADD y = sin(AD(s3)*x(0) + AD(s4)*x(1));\n\n  VERIFY_IS_APPROX(y.value().derivatives()(0), y.derivatives()(0).value());\n  VERIFY_IS_APPROX(y.value().derivatives()(1), y.derivatives()(1).value());\n  VERIFY_IS_APPROX(y.value().derivatives()(0), s3*std::cos(s1*s3+s2*s4));\n  VERIFY_IS_APPROX(y.value().derivatives()(1), s4*std::cos(s1*s3+s2*s4));\n  VERIFY_IS_APPROX(y.derivatives()(0).derivatives(), -std::sin(s1*s3+s2*s4)*Vector2d(s3*s3,s4*s3));\n  VERIFY_IS_APPROX(y.derivatives()(1).derivatives(),  -std::sin(s1*s3+s2*s4)*Vector2d(s3*s4,s4*s4));\n\n  ADD z = x(0)*x(1);\n  VERIFY_IS_APPROX(z.derivatives()(0).derivatives(), Vector2d(0,1));\n  VERIFY_IS_APPROX(z.derivatives()(1).derivatives(), Vector2d(1,0));\n}\n\ndouble bug_1222() {\n  typedef Eigen::AutoDiffScalar<Eigen::Vector3d> AD;\n  const double _cv1_3 = 1.0;\n  const AD chi_3 = 1.0;\n  // this line did not work, because operator+ returns ADS<DerType&>, which then cannot be converted to ADS<DerType>\n  const AD denom = chi_3 + _cv1_3;\n  return denom.value();\n}\n\n#ifdef EIGEN_TEST_PART_5\n\ndouble bug_1223() {\n  using std::min;\n  typedef Eigen::AutoDiffScalar<Eigen::Vector3d> AD;\n\n  const double _cv1_3 = 1.0;\n  const AD chi_3 = 1.0;\n  const AD denom = 1.0;\n\n  // failed because implementation of min attempts to construct ADS<DerType&> via constructor AutoDiffScalar(const Real& value)\n  // without initializing m_derivatives (which is a reference in this case)\n  #define EIGEN_TEST_SPACE\n  const AD t = min EIGEN_TEST_SPACE (denom / chi_3, 1.0);\n\n  const AD t2 = min EIGEN_TEST_SPACE (denom / (chi_3 * _cv1_3), 1.0);\n\n  return t.value() + t2.value();\n}\n\n// regression test for some compilation issues with specializations of ScalarBinaryOpTraits\nvoid bug_1260() {\n  Matrix4d A = Matrix4d::Ones();\n  Vector4d v = Vector4d::Ones();\n  A*v;\n}\n\n// check a compilation issue with numext::max\ndouble bug_1261() {\n  typedef AutoDiffScalar<Matrix2d> AD;\n  typedef Matrix<AD,2,1> VectorAD;\n\n  VectorAD v(0.,0.);\n  const AD maxVal = v.maxCoeff();\n  const AD minVal = v.minCoeff();\n  return maxVal.value() + minVal.value();\n}\n\ndouble bug_1264() {\n  typedef AutoDiffScalar<Vector2d> AD;\n  const AD s = 0.;\n  const Matrix<AD, 3, 1> v1(0.,0.,0.);\n  const Matrix<AD, 3, 1> v2 = (s + 3.0) * v1;\n  return v2(0).value();\n}\n\n// check with expressions on constants\ndouble bug_1281() {\n  int n = 2;\n  typedef AutoDiffScalar<VectorXd> AD;\n  const AD c = 1.;\n  AD x0(2,n,0);\n  AD y1 = (AD(c)+AD(c))*x0;\n  y1 = x0 * (AD(c)+AD(c));\n  AD y2 = (-AD(c))+x0;\n  y2 = x0+(-AD(c));\n  AD y3 = (AD(c)*(-AD(c))+AD(c))*x0;\n  y3 = x0 * (AD(c)*(-AD(c))+AD(c));\n  return (y1+y2+y3).value();\n}\n\n#endif\n\nEIGEN_DECLARE_TEST(autodiff)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( test_autodiff_scalar<1>() );\n    CALL_SUBTEST_2( test_autodiff_vector<1>() );\n    CALL_SUBTEST_3( test_autodiff_jacobian<1>() );\n    CALL_SUBTEST_4( test_autodiff_hessian<1>() );\n  }\n\n  CALL_SUBTEST_5( bug_1222() );\n  CALL_SUBTEST_5( bug_1223() );\n  CALL_SUBTEST_5( bug_1260() );\n  CALL_SUBTEST_5( bug_1261() );\n  CALL_SUBTEST_5( bug_1281() );\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/autodiff_scalar.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christoph Hertzberg <chtz@informatik.uni-bremen.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <unsupported/Eigen/AutoDiff>\n\n/*\n * In this file scalar derivations are tested for correctness.\n * TODO add more tests!\n */\n\ntemplate<typename Scalar> void check_atan2()\n{\n  typedef Matrix<Scalar, 1, 1> Deriv1;\n  typedef AutoDiffScalar<Deriv1> AD;\n  \n  AD x(internal::random<Scalar>(-3.0, 3.0), Deriv1::UnitX());\n  \n  using std::exp;\n  Scalar r = exp(internal::random<Scalar>(-10, 10));\n  \n  AD s = sin(x), c = cos(x);\n  AD res = atan2(r*s, r*c);\n  \n  VERIFY_IS_APPROX(res.value(), x.value());\n  VERIFY_IS_APPROX(res.derivatives(), x.derivatives());\n\n  res = atan2(r*s+0, r*c+0);\n  VERIFY_IS_APPROX(res.value(), x.value());\n  VERIFY_IS_APPROX(res.derivatives(), x.derivatives());\n}\n\ntemplate<typename Scalar> void check_hyperbolic_functions()\n{\n  using std::sinh;\n  using std::cosh;\n  using std::tanh;\n  typedef Matrix<Scalar, 1, 1> Deriv1;\n  typedef AutoDiffScalar<Deriv1> AD;\n  Deriv1 p = Deriv1::Random();\n  AD val(p.x(),Deriv1::UnitX());\n\n  Scalar cosh_px = std::cosh(p.x());\n  AD res1 = tanh(val);\n  VERIFY_IS_APPROX(res1.value(), std::tanh(p.x()));\n  VERIFY_IS_APPROX(res1.derivatives().x(), Scalar(1.0) / (cosh_px * cosh_px));\n\n  AD res2 = sinh(val);\n  VERIFY_IS_APPROX(res2.value(), std::sinh(p.x()));\n  VERIFY_IS_APPROX(res2.derivatives().x(), cosh_px);\n\n  AD res3 = cosh(val);\n  VERIFY_IS_APPROX(res3.value(), cosh_px);\n  VERIFY_IS_APPROX(res3.derivatives().x(), std::sinh(p.x()));\n\n  // Check constant values.\n  const Scalar sample_point = Scalar(1) / Scalar(3); \n  val = AD(sample_point,Deriv1::UnitX());\n  res1 = tanh(val);\n  VERIFY_IS_APPROX(res1.derivatives().x(), Scalar(0.896629559604914));\n\n  res2 = sinh(val);\n  VERIFY_IS_APPROX(res2.derivatives().x(), Scalar(1.056071867829939));\n\n  res3 = cosh(val);\n  VERIFY_IS_APPROX(res3.derivatives().x(), Scalar(0.339540557256150));\n}\n\ntemplate <typename Scalar>\nvoid check_limits_specialization()\n{\n  typedef Eigen::Matrix<Scalar, 1, 1> Deriv;\n  typedef Eigen::AutoDiffScalar<Deriv> AD;\n\n  typedef std::numeric_limits<AD> A;\n  typedef std::numeric_limits<Scalar> B;\n\n  // workaround \"unused typedef\" warning:\n  VERIFY(!bool(internal::is_same<B, A>::value));\n\n#if EIGEN_HAS_CXX11\n  VERIFY(bool(std::is_base_of<B, A>::value));\n#endif\n}\n\nEIGEN_DECLARE_TEST(autodiff_scalar)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( check_atan2<float>() );\n    CALL_SUBTEST_2( check_atan2<double>() );\n    CALL_SUBTEST_3( check_hyperbolic_functions<float>() );\n    CALL_SUBTEST_4( check_hyperbolic_functions<double>() );\n    CALL_SUBTEST_5( check_limits_specialization<double>());\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/bessel_functions.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include \"../Eigen/SpecialFunctions\"\n\ntemplate<typename X, typename Y>\nvoid verify_component_wise(const X& x, const Y& y)\n{\n  for(Index i=0; i<x.size(); ++i)\n  {\n    if((numext::isfinite)(y(i))) {\n      VERIFY_IS_APPROX( x(i), y(i) );\n    }\n    else if((numext::isnan)(y(i)))\n      VERIFY((numext::isnan)(x(i)));\n    else\n      VERIFY_IS_EQUAL( x(i), y(i) );\n  }\n}\n\ntemplate<typename ArrayType> void array_bessel_functions() \n{\n  // Test Bessel function i0. Reference results obtained with SciPy.\n  {\n    ArrayType x(21);\n    ArrayType expected(21);\n    ArrayType res(21);\n\n    x << -20.0, -18.0, -16.0, -14.0, -12.0, -10.0, -8.0, -6.0, -4.0, -2.0, 0.0,\n        2.0, 4.0, 6.0, 8.0, 10.0, 12.0, 14.0, 16.0, 18.0, 20.0;\n\n    expected << 4.35582826e+07, 6.21841242e+06, 8.93446228e+05, 1.29418563e+05,\n       1.89489253e+04, 2.81571663e+03, 4.27564116e+02, 6.72344070e+01,\n       1.13019220e+01, 2.27958530e+00, 1.00000000e+00, 2.27958530e+00,\n       1.13019220e+01, 6.72344070e+01, 4.27564116e+02, 2.81571663e+03,\n       1.89489253e+04, 1.29418563e+05, 8.93446228e+05, 6.21841242e+06,\n       4.35582826e+07;\n\n    CALL_SUBTEST(res = bessel_i0(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function i0e. Reference results obtained with SciPy.\n  {\n    ArrayType x(21);\n    ArrayType expected(21);\n    ArrayType res(21);\n\n    x << -20.0, -18.0, -16.0, -14.0, -12.0, -10.0, -8.0, -6.0, -4.0, -2.0, 0.0,\n        2.0, 4.0, 6.0, 8.0, 10.0, 12.0, 14.0, 16.0, 18.0, 20.0;\n\n    expected << 0.0897803118848, 0.0947062952128, 0.100544127361,\n        0.107615251671, 0.116426221213, 0.127833337163, 0.143431781857,\n        0.16665743264, 0.207001921224, 0.308508322554, 1.0, 0.308508322554,\n        0.207001921224, 0.16665743264, 0.143431781857, 0.127833337163,\n        0.116426221213, 0.107615251671, 0.100544127361, 0.0947062952128,\n        0.0897803118848;\n\n    CALL_SUBTEST(res = bessel_i0e(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function i1. Reference results obtained with SciPy.\n  {\n    ArrayType x(21);\n    ArrayType expected(21);\n    ArrayType res(21);\n\n    x << -20.0, -18.0, -16.0, -14.0, -12.0, -10.0, -8.0, -6.0, -4.0, -2.0, 0.0,\n        2.0, 4.0, 6.0, 8.0, 10.0, 12.0, 14.0, 16.0, 18.0, 20.0;\n\n    expected << -4.24549734e+07, -6.04313324e+06, -8.65059436e+05, -1.24707259e+05,\n       -1.81413488e+04, -2.67098830e+03, -3.99873137e+02, -6.13419368e+01,\n       -9.75946515e+00, -1.59063685e+00,  0.00000000e+00,  1.59063685e+00,\n        9.75946515e+00,  6.13419368e+01,  3.99873137e+02,  2.67098830e+03,\n        1.81413488e+04,  1.24707259e+05,  8.65059436e+05,  6.04313324e+06,\n        4.24549734e+07;\n\n    CALL_SUBTEST(res = bessel_i1(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function i1e. Reference results obtained with SciPy.\n  {\n    ArrayType x(21);\n    ArrayType expected(21);\n    ArrayType res(21);\n\n    x << -20.0, -18.0, -16.0, -14.0, -12.0, -10.0, -8.0, -6.0, -4.0, -2.0, 0.0,\n        2.0, 4.0, 6.0, 8.0, 10.0, 12.0, 14.0, 16.0, 18.0, 20.0;\n\n    expected << -0.0875062221833, -0.092036796872, -0.0973496147565,\n        -0.103697667463, -0.11146429929, -0.121262681384, -0.134142493293,\n        -0.152051459309, -0.178750839502, -0.215269289249, 0.0, 0.215269289249,\n        0.178750839502, 0.152051459309, 0.134142493293, 0.121262681384,\n        0.11146429929, 0.103697667463, 0.0973496147565, 0.092036796872,\n        0.0875062221833;\n\n    CALL_SUBTEST(res = bessel_i1e(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function j0. Reference results obtained with SciPy.\n  {\n    ArrayType x(77);\n    ArrayType expected(77);\n    ArrayType res(77);\n\n    x << -38., -37., -36., -35., -34., -33., -32., -31., -30.,\n      -29., -28., -27., -26., -25., -24., -23., -22., -21., -20., -19.,\n      -18., -17., -16., -15., -14., -13., -12., -11., -10.,  -9.,  -8.,\n       -7.,  -6.,  -5.,  -4.,  -3.,  -2.,  -1.,   0.,   1.,   2.,   3.,\n        4.,   5.,   6.,   7.,   8.,   9.,  10.,  11.,  12.,  13.,  14.,\n       15.,  16.,  17.,  18.,  19.,  20.,  21.,  22.,  23.,  24.,  25.,\n       26.,  27.,  28.,  29.,  30.,  31.,  32.,  33.,  34.,  35.,  36.,\n       37.,  38.;\n\n    expected << 0.11433274,  0.01086237, -0.10556738,\n             -0.12684568, -0.03042119,  0.09727067,  0.13807901,  0.05120815,\n             -0.08636798, -0.14784876, -0.07315701,  0.07274192,  0.15599932,\n              0.09626678, -0.05623027, -0.16241278, -0.12065148,  0.03657907,\n              0.16702466,  0.14662944, -0.01335581, -0.16985425, -0.17489907,\n             -0.01422447,  0.17107348,  0.2069261 ,  0.04768931, -0.1711903 ,\n             -0.24593576, -0.09033361,  0.17165081,  0.30007927,  0.15064526,\n             -0.17759677, -0.39714981, -0.26005195,  0.22389078,  0.76519769,\n              1.        ,  0.76519769,  0.22389078, -0.26005195, -0.39714981,\n             -0.17759677,  0.15064526,  0.30007927,  0.17165081, -0.09033361,\n             -0.24593576, -0.1711903 ,  0.04768931,  0.2069261 ,  0.17107348,\n             -0.01422447, -0.17489907, -0.16985425, -0.01335581,  0.14662944,\n              0.16702466,  0.03657907, -0.12065148, -0.16241278, -0.05623027,\n              0.09626678,  0.15599932,  0.07274192, -0.07315701, -0.14784876,\n             -0.08636798,  0.05120815,  0.13807901,  0.09727067, -0.03042119,\n             -0.12684568, -0.10556738,  0.01086237,  0.11433274;\n\n    CALL_SUBTEST(res = bessel_j0(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function j1. Reference results obtained with SciPy.\n  {\n    ArrayType x(81);\n    ArrayType expected(81);\n    ArrayType res(81);\n\n    x << -40., -39., -38., -37., -36., -35., -34., -33., -32., -31., -30.,\n      -29., -28., -27., -26., -25., -24., -23., -22., -21., -20., -19.,\n      -18., -17., -16., -15., -14., -13., -12., -11., -10.,  -9.,  -8.,\n       -7.,  -6.,  -5.,  -4.,  -3.,  -2.,  -1.,   0.,   1.,   2.,   3.,\n        4.,   5.,   6.,   7.,   8.,   9.,  10.,  11.,  12.,  13.,  14.,\n       15.,  16.,  17.,  18.,  19.,  20.,  21.,  22.,  23.,  24.,  25.,\n       26.,  27.,  28.,  29.,  30.,  31.,  32.,  33.,  34.,  35.,  36.,\n       37.,  38.,  39.,  40.;\n\n    expected << -0.12603832, -0.0640561 ,  0.05916189,  0.13058004,  0.08232981,\n             -0.04399094, -0.13297118, -0.10061965,  0.02658903,  0.13302432,\n              0.11875106, -0.0069342 , -0.13055149, -0.13658472, -0.01504573,\n              0.12535025,  0.15403807,  0.03951932, -0.11717779, -0.17112027,\n             -0.06683312,  0.10570143,  0.18799489,  0.09766849, -0.09039718,\n             -0.20510404, -0.13337515,  0.07031805,  0.2234471 ,  0.1767853 ,\n             -0.04347275, -0.24531179, -0.23463635,  0.00468282,  0.27668386,\n              0.32757914,  0.06604333, -0.33905896, -0.57672481, -0.44005059,\n              0.        ,  0.44005059,  0.57672481,  0.33905896, -0.06604333,\n             -0.32757914, -0.27668386, -0.00468282,  0.23463635,  0.24531179,\n              0.04347275, -0.1767853 , -0.2234471 , -0.07031805,  0.13337515,\n              0.20510404,  0.09039718, -0.09766849, -0.18799489, -0.10570143,\n              0.06683312,  0.17112027,  0.11717779, -0.03951932, -0.15403807,\n             -0.12535025,  0.01504573,  0.13658472,  0.13055149,  0.0069342 ,\n             -0.11875106, -0.13302432, -0.02658903,  0.10061965,  0.13297118,\n              0.04399094, -0.08232981, -0.13058004, -0.05916189,  0.0640561 ,\n              0.12603832;\n\n    CALL_SUBTEST(res = bessel_j1(x);\n                 verify_component_wise(res, expected););\n  }\n  // Test Bessel function k0e. Reference results obtained with SciPy.\n  {\n    ArrayType x(42);\n    ArrayType expected(42);\n    ArrayType res(42);\n\n    x << 0.25, 0.5,  1.,  2.,  3.,  4.,  5.,  6.,  7.,  8.,  9., 10., 11., 12.,\n       13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25.,\n       26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36., 37., 38.,\n       39., 40.;\n\n    expected << 1.97933385, 1.52410939, 1.14446308, 0.84156822,\n             0.6977616 , 0.60929767, 0.54780756, 0.50186313, 0.4658451 ,\n             0.43662302, 0.41229555, 0.39163193, 0.3737955 , 0.35819488,\n             0.34439865, 0.33208364, 0.32100235, 0.31096159, 0.30180802,\n             0.29341821, 0.28569149, 0.27854488, 0.2719092 , 0.26572635,\n             0.25994703, 0.25452917, 0.2494366 , 0.24463801, 0.24010616,\n             0.23581722, 0.23175022, 0.22788667, 0.22421014, 0.22070602,\n             0.21736123, 0.21416406, 0.21110397, 0.20817141, 0.20535778,\n             0.20265524, 0.20005668, 0.19755558;\n\n    CALL_SUBTEST(res = bessel_k0e(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function k0. Reference results obtained with SciPy.\n  {\n    ArrayType x(42);\n    ArrayType expected(42);\n    ArrayType res(42);\n\n    x << 0.25, 0.5,  1.,  2.,  3.,  4.,  5.,  6.,  7.,  8.,  9., 10., 11., 12.,\n       13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25.,\n       26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36., 37., 38.,\n       39., 40.;\n\n    expected << 1.54150675, 0.92441907, 4.21024438e-01, 1.13893873e-01,\n             3.47395044e-02, 1.11596761e-02, 3.69109833e-03, 1.24399433e-03,\n             4.24795742e-04, 1.46470705e-04, 5.08813130e-05, 1.77800623e-05,\n             6.24302055e-06, 2.20082540e-06, 7.78454386e-07, 2.76137082e-07,\n             9.81953648e-08, 3.49941166e-08, 1.24946640e-08, 4.46875334e-09,\n             1.60067129e-09, 5.74123782e-10, 2.06176797e-10, 7.41235161e-11,\n             2.66754511e-11, 9.60881878e-12, 3.46416156e-12, 1.24987740e-12,\n             4.51286453e-13, 1.63053459e-13, 5.89495073e-14, 2.13247750e-14,\n             7.71838266e-15, 2.79505752e-15, 1.01266123e-15, 3.67057597e-16,\n             1.33103515e-16, 4.82858338e-17, 1.75232770e-17, 6.36161716e-18,\n             2.31029936e-18, 8.39286110e-19;\n\n    CALL_SUBTEST(res = bessel_k0(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function k0e. Reference results obtained with SciPy.\n  {\n    ArrayType x(42);\n    ArrayType expected(42);\n    ArrayType res(42);\n\n    x << 0.25, 0.5,  1.,  2.,  3.,  4.,  5.,  6.,  7.,  8.,  9., 10., 11., 12.,\n       13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25.,\n       26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36., 37., 38.,\n       39., 40.;\n\n    expected << 1.97933385, 1.52410939, 1.14446308, 0.84156822,\n             0.6977616 , 0.60929767, 0.54780756, 0.50186313,\n             0.4658451 , 0.43662302, 0.41229555, 0.39163193,\n             0.3737955 , 0.35819488, 0.34439865, 0.33208364,\n             0.32100235, 0.31096159, 0.30180802, 0.29341821,\n             0.28569149, 0.27854488, 0.2719092 , 0.26572635,\n             0.25994703, 0.25452917, 0.2494366 , 0.24463801,\n             0.24010616, 0.23581722, 0.23175022, 0.22788667,\n             0.22421014, 0.22070602, 0.21736123, 0.21416406,\n             0.21110397, 0.20817141, 0.20535778, 0.20265524,\n             0.20005668, 0.19755558;\n\n    CALL_SUBTEST(res = bessel_k0e(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function k1. Reference results obtained with SciPy.\n  {\n    ArrayType x(42);\n    ArrayType expected(42);\n    ArrayType res(42);\n\n    x << 0.25, 0.5,  1.,  2.,  3.,  4.,  5.,  6.,  7.,  8.,  9., 10., 11., 12.,\n       13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25.,\n       26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36., 37., 38.,\n       39., 40.;\n\n    expected << 3.74702597, 1.65644112, 6.01907230e-01, 1.39865882e-01,\n             4.01564311e-02, 1.24834989e-02, 4.04461345e-03, 1.34391972e-03,\n             4.54182487e-04, 1.55369212e-04, 5.36370164e-05, 1.86487735e-05,\n             6.52086067e-06, 2.29075746e-06, 8.07858841e-07, 2.85834365e-07,\n             1.01417294e-07, 3.60715712e-08, 1.28570417e-08, 4.59124963e-09,\n             1.64226697e-09, 5.88305797e-10, 2.11029922e-10, 7.57898116e-11,\n             2.72493059e-11, 9.80699893e-12, 3.53277807e-12, 1.27369078e-12,\n             4.59568940e-13, 1.65940011e-13, 5.99574032e-14, 2.16773200e-14,\n             7.84189960e-15, 2.83839927e-15, 1.02789171e-15, 3.72416929e-16,\n             1.34991783e-16, 4.89519373e-17, 1.77585196e-17, 6.44478588e-18,\n             2.33973340e-18, 8.49713195e-19;\n\n    CALL_SUBTEST(res = bessel_k1(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function k1e. Reference results obtained with SciPy.\n  {\n    ArrayType x(42);\n    ArrayType expected(42);\n    ArrayType res(42);\n\n    x << 0.25, 0.5,  1.,  2.,  3.,  4.,  5.,  6.,  7.,  8.,  9., 10., 11., 12.,\n       13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25.,\n       26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36., 37., 38.,\n       39., 40.;\n\n    expected << 4.81127659, 2.73100971, 1.63615349, 1.03347685,\n             0.80656348, 0.68157595, 0.60027386, 0.54217591,\n             0.49807158, 0.46314909, 0.43462525, 0.41076657,\n             0.39043094, 0.37283175, 0.35740757, 0.34374563,\n             0.33153489, 0.32053597, 0.31056123, 0.30146131,\n             0.29311559, 0.2854255 , 0.27830958, 0.27169987,\n             0.26553913, 0.25977879, 0.25437733, 0.249299  ,\n             0.24451285, 0.23999191, 0.2357126 , 0.23165413,\n             0.22779816, 0.22412841, 0.22063036, 0.21729103,\n             0.21409878, 0.21104314, 0.20811462, 0.20530466,\n             0.20260547, 0.20000997;\n\n    CALL_SUBTEST(res = bessel_k1e(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function y0. Reference results obtained with SciPy.\n  {\n    ArrayType x(42);\n    ArrayType expected(42);\n    ArrayType res(42);\n\n    x << 0.25, 0.5,  1.,  2.,  3.,  4.,  5.,  6.,  7.,  8.,  9., 10., 11., 12.,\n       13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25.,\n       26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36., 37., 38.,\n       39., 40.;\n\n    expected << -0.93157302, -0.44451873, 0.08825696,  0.51037567,  0.37685001,\n             -0.01694074, -0.30851763, -0.28819468, -0.02594974,  0.22352149,\n             0.2499367 ,  0.05567117, -0.16884732, -0.22523731, -0.07820786,\n             0.12719257,  0.2054643 , 0.095811  , -0.0926372 , -0.18755216,\n             -0.10951969,  0.0626406 , 0.17020176,  0.1198876 , -0.03598179,\n             -0.15283403, -0.12724943, 0.01204463,  0.13521498,  0.13183647,\n             0.00948116, -0.11729573, -0.13383266, -0.02874248,  0.09913483,\n             0.13340405,  0.04579799, -0.08085609, -0.13071488, -0.06066076,\n             0.06262353,  0.12593642;\n\n    CALL_SUBTEST(res = bessel_y0(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function y1. Reference results obtained with SciPy.\n  {\n    ArrayType x(42);\n    ArrayType expected(42);\n    ArrayType res(42);\n\n    x << 0.25, 0.5,  1.,  2.,  3.,  4.,  5.,  6.,  7.,  8.,  9., 10., 11., 12.,\n       13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25.,\n       26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36., 37., 38.,\n       39., 40.;\n\n    expected << -2.70410523, -1.47147239, -0.78121282, -0.10703243,\n             0.32467442,  0.39792571,  0.14786314, -0.17501034, -0.30266724,\n             -0.15806046,  0.10431458,  0.24901542, 0.16370554, -0.05709922,\n             -0.21008141, -0.16664484,  0.02107363, 0.17797517,  0.16720504,\n             0.00815513, -0.14956011, -0.16551161, -0.03253926,  0.12340586,\n             0.1616692 ,  0.05305978, -0.09882996, -0.15579655, -0.07025124,\n             0.07552213,  0.14803412,  0.08442557, -0.05337283, -0.13854483,\n             -0.09578012,  0.03238588,  0.12751273, 0.10445477, -0.01262946,\n             -0.11514066, -0.11056411, -0.00579351;\n\n    CALL_SUBTEST(res = bessel_y1(x);\n                 verify_component_wise(res, expected););\n  }\n}\n\nEIGEN_DECLARE_TEST(bessel_functions)\n{\n  CALL_SUBTEST_1(array_bessel_functions<ArrayXf>());\n  CALL_SUBTEST_2(array_bessel_functions<ArrayXd>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_eventcount.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Dmitry Vyukov <dvyukov@google.com>\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_USE_THREADS\n#include \"main.h\"\n#include <Eigen/CXX11/ThreadPool>\n\n// Visual studio doesn't implement a rand_r() function since its\n// implementation of rand() is already thread safe\nint rand_reentrant(unsigned int* s) {\n#ifdef EIGEN_COMP_MSVC_STRICT\n  EIGEN_UNUSED_VARIABLE(s);\n  return rand();\n#else\n  return rand_r(s);\n#endif\n}\n\nstatic void test_basic_eventcount()\n{\n  MaxSizeVector<EventCount::Waiter> waiters(1);\n  waiters.resize(1);\n  EventCount ec(waiters);\n  EventCount::Waiter& w = waiters[0];\n  ec.Notify(false);\n  ec.Prewait();\n  ec.Notify(true);\n  ec.CommitWait(&w);\n  ec.Prewait();\n  ec.CancelWait();\n}\n\n// Fake bounded counter-based queue.\nstruct TestQueue {\n  std::atomic<int> val_;\n  static const int kQueueSize = 10;\n\n  TestQueue() : val_() {}\n\n  ~TestQueue() { VERIFY_IS_EQUAL(val_.load(), 0); }\n\n  bool Push() {\n    int val = val_.load(std::memory_order_relaxed);\n    for (;;) {\n      VERIFY_GE(val, 0);\n      VERIFY_LE(val, kQueueSize);\n      if (val == kQueueSize) return false;\n      if (val_.compare_exchange_weak(val, val + 1, std::memory_order_relaxed))\n        return true;\n    }\n  }\n\n  bool Pop() {\n    int val = val_.load(std::memory_order_relaxed);\n    for (;;) {\n      VERIFY_GE(val, 0);\n      VERIFY_LE(val, kQueueSize);\n      if (val == 0) return false;\n      if (val_.compare_exchange_weak(val, val - 1, std::memory_order_relaxed))\n        return true;\n    }\n  }\n\n  bool Empty() { return val_.load(std::memory_order_relaxed) == 0; }\n};\n\nconst int TestQueue::kQueueSize;\n\n// A number of producers send messages to a set of consumers using a set of\n// fake queues. Ensure that it does not crash, consumers don't deadlock and\n// number of blocked and unblocked threads match.\nstatic void test_stress_eventcount()\n{\n  const int kThreads = std::thread::hardware_concurrency();\n  static const int kEvents = 1 << 16;\n  static const int kQueues = 10;\n\n  MaxSizeVector<EventCount::Waiter> waiters(kThreads);\n  waiters.resize(kThreads);\n  EventCount ec(waiters);\n  TestQueue queues[kQueues];\n\n  std::vector<std::unique_ptr<std::thread>> producers;\n  for (int i = 0; i < kThreads; i++) {\n    producers.emplace_back(new std::thread([&ec, &queues]() {\n      unsigned int rnd = static_cast<unsigned int>(std::hash<std::thread::id>()(std::this_thread::get_id()));\n      for (int j = 0; j < kEvents; j++) {\n        unsigned idx = rand_reentrant(&rnd) % kQueues;\n        if (queues[idx].Push()) {\n          ec.Notify(false);\n          continue;\n        }\n        EIGEN_THREAD_YIELD();\n        j--;\n      }\n    }));\n  }\n\n  std::vector<std::unique_ptr<std::thread>> consumers;\n  for (int i = 0; i < kThreads; i++) {\n    consumers.emplace_back(new std::thread([&ec, &queues, &waiters, i]() {\n      EventCount::Waiter& w = waiters[i];\n      unsigned int rnd = static_cast<unsigned int>(std::hash<std::thread::id>()(std::this_thread::get_id()));\n      for (int j = 0; j < kEvents; j++) {\n        unsigned idx = rand_reentrant(&rnd) % kQueues;\n        if (queues[idx].Pop()) continue;\n        j--;\n        ec.Prewait();\n        bool empty = true;\n        for (int q = 0; q < kQueues; q++) {\n          if (!queues[q].Empty()) {\n            empty = false;\n            break;\n          }\n        }\n        if (!empty) {\n          ec.CancelWait();\n          continue;\n        }\n        ec.CommitWait(&w);\n      }\n    }));\n  }\n\n  for (int i = 0; i < kThreads; i++) {\n    producers[i]->join();\n    consumers[i]->join();\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_eventcount)\n{\n  CALL_SUBTEST(test_basic_eventcount());\n  CALL_SUBTEST(test_stress_eventcount());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_maxsizevector.cpp",
    "content": "#include \"main.h\"\n\n#include <exception>  // std::exception\n\n#include <unsupported/Eigen/CXX11/Tensor>\n\nstruct Foo\n{\n  static Index object_count;\n  static Index object_limit;\n  EIGEN_ALIGN_TO_BOUNDARY(128) int dummy;\n\n  Foo(int x=0) : dummy(x)\n  {\n#ifdef EIGEN_EXCEPTIONS\n    // TODO: Is this the correct way to handle this?\n    if (Foo::object_count > Foo::object_limit) { std::cout << \"\\nThrow!\\n\"; throw Foo::Fail(); }\n#endif\n    std::cout << '+';\n    ++Foo::object_count;\n    eigen_assert((internal::UIntPtr(this) & (127)) == 0);\n  }\n  Foo(const Foo&)\n  {\n    std::cout << 'c';\n    ++Foo::object_count;\n    eigen_assert((internal::UIntPtr(this) & (127)) == 0);\n  }\n\n  ~Foo()\n  {\n    std::cout << '~';\n    --Foo::object_count;\n  }\n\n  class Fail : public std::exception {};\n};\n\nIndex Foo::object_count = 0;\nIndex Foo::object_limit = 0;\n\n\n\nEIGEN_DECLARE_TEST(cxx11_maxsizevector)\n{\n  typedef MaxSizeVector<Foo> VectorX;\n  Foo::object_count = 0;\n  for(int r = 0; r < g_repeat; r++) {\n    Index rows = internal::random<Index>(3,30);\n    Foo::object_limit = internal::random<Index>(0, rows - 2);\n    std::cout << \"object_limit = \" << Foo::object_limit << std::endl;\n    bool exception_raised = false;\n#ifdef EIGEN_EXCEPTIONS\n    try\n    {\n#endif\n      std::cout <<       \"\\nVectorX m(\" << rows << \");\\n\";\n      VectorX vect(rows);\n      for(int i=0; i<rows; ++i)\n          vect.push_back(Foo());\n#ifdef EIGEN_EXCEPTIONS\n      VERIFY(false);  // not reached if exceptions are enabled\n    }\n    catch (const Foo::Fail&) { exception_raised = true; }\n    VERIFY(exception_raised);\n#endif\n    VERIFY_IS_EQUAL(Index(0), Foo::object_count);\n\n    {\n      Foo::object_limit = rows+1;\n      VectorX vect2(rows, Foo());\n      VERIFY_IS_EQUAL(Foo::object_count, rows);\n    }\n    VERIFY_IS_EQUAL(Index(0), Foo::object_count);\n    std::cout << '\\n';\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_meta.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <array>\n#include <Eigen/CXX11/src/util/CXX11Meta.h>\n\nusing Eigen::internal::is_same;\nusing Eigen::internal::type_list;\nusing Eigen::internal::numeric_list;\nusing Eigen::internal::gen_numeric_list;\nusing Eigen::internal::gen_numeric_list_reversed;\nusing Eigen::internal::gen_numeric_list_swapped_pair;\nusing Eigen::internal::gen_numeric_list_repeated;\nusing Eigen::internal::concat;\nusing Eigen::internal::mconcat;\nusing Eigen::internal::take;\nusing Eigen::internal::skip;\nusing Eigen::internal::slice;\nusing Eigen::internal::get;\nusing Eigen::internal::id_numeric;\nusing Eigen::internal::id_type;\nusing Eigen::internal::is_same_gf;\nusing Eigen::internal::apply_op_from_left;\nusing Eigen::internal::apply_op_from_right;\nusing Eigen::internal::contained_in_list;\nusing Eigen::internal::contained_in_list_gf;\nusing Eigen::internal::arg_prod;\nusing Eigen::internal::arg_sum;\nusing Eigen::internal::sum_op;\nusing Eigen::internal::product_op;\nusing Eigen::internal::array_reverse;\nusing Eigen::internal::array_sum;\nusing Eigen::internal::array_prod;\nusing Eigen::internal::array_reduce;\nusing Eigen::internal::array_zip;\nusing Eigen::internal::array_zip_and_reduce;\nusing Eigen::internal::array_apply;\nusing Eigen::internal::array_apply_and_reduce;\nusing Eigen::internal::repeat;\nusing Eigen::internal::instantiate_by_c_array;\n\nstruct dummy_a {};\nstruct dummy_b {};\nstruct dummy_c {};\nstruct dummy_d {};\nstruct dummy_e {};\n\n// dummy operation for testing apply\ntemplate<typename A, typename B> struct dummy_op;\ntemplate<> struct dummy_op<dummy_a, dummy_b> { typedef dummy_c type; };\ntemplate<> struct dummy_op<dummy_b, dummy_a> { typedef dummy_d type; };\ntemplate<> struct dummy_op<dummy_b, dummy_c> { typedef dummy_a type; };\ntemplate<> struct dummy_op<dummy_c, dummy_b> { typedef dummy_d type; };\ntemplate<> struct dummy_op<dummy_c, dummy_a> { typedef dummy_b type; };\ntemplate<> struct dummy_op<dummy_a, dummy_c> { typedef dummy_d type; };\ntemplate<> struct dummy_op<dummy_a, dummy_a> { typedef dummy_e type; };\ntemplate<> struct dummy_op<dummy_b, dummy_b> { typedef dummy_e type; };\ntemplate<> struct dummy_op<dummy_c, dummy_c> { typedef dummy_e type; };\n\ntemplate<typename A, typename B> struct dummy_test { constexpr static bool value = false; constexpr static int global_flags = 0; };\ntemplate<> struct dummy_test<dummy_a, dummy_a>     { constexpr static bool value = true;  constexpr static int global_flags = 1; };\ntemplate<> struct dummy_test<dummy_b, dummy_b>     { constexpr static bool value = true;  constexpr static int global_flags = 2; };\ntemplate<> struct dummy_test<dummy_c, dummy_c>     { constexpr static bool value = true;  constexpr static int global_flags = 4; };\n\nstruct times2_op { template<typename A> static A run(A v) { return v * 2; } };\n\nstruct dummy_inst\n{\n  int c;\n\n  dummy_inst() : c(0) {}\n  explicit dummy_inst(int) : c(1) {}\n  dummy_inst(int, int) : c(2) {}\n  dummy_inst(int, int, int) : c(3) {}\n  dummy_inst(int, int, int, int) : c(4) {}\n  dummy_inst(int, int, int, int, int) : c(5) {}\n};\n\nstatic void test_gen_numeric_list()\n{\n  VERIFY((is_same<typename gen_numeric_list<int, 0>::type, numeric_list<int>>::value));\n  VERIFY((is_same<typename gen_numeric_list<int, 1>::type, numeric_list<int, 0>>::value));\n  VERIFY((is_same<typename gen_numeric_list<int, 2>::type, numeric_list<int, 0, 1>>::value));\n  VERIFY((is_same<typename gen_numeric_list<int, 5>::type, numeric_list<int, 0, 1, 2, 3, 4>>::value));\n  VERIFY((is_same<typename gen_numeric_list<int, 10>::type, numeric_list<int, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9>>::value));\n\n  VERIFY((is_same<typename gen_numeric_list<int, 0, 42>::type, numeric_list<int>>::value));\n  VERIFY((is_same<typename gen_numeric_list<int, 1, 42>::type, numeric_list<int, 42>>::value));\n  VERIFY((is_same<typename gen_numeric_list<int, 2, 42>::type, numeric_list<int, 42, 43>>::value));\n  VERIFY((is_same<typename gen_numeric_list<int, 5, 42>::type, numeric_list<int, 42, 43, 44, 45, 46>>::value));\n  VERIFY((is_same<typename gen_numeric_list<int, 10, 42>::type, numeric_list<int, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51>>::value));\n\n  VERIFY((is_same<typename gen_numeric_list_reversed<int, 0>::type, numeric_list<int>>::value));\n  VERIFY((is_same<typename gen_numeric_list_reversed<int, 1>::type, numeric_list<int, 0>>::value));\n  VERIFY((is_same<typename gen_numeric_list_reversed<int, 2>::type, numeric_list<int, 1, 0>>::value));\n  VERIFY((is_same<typename gen_numeric_list_reversed<int, 5>::type, numeric_list<int, 4, 3, 2, 1, 0>>::value));\n  VERIFY((is_same<typename gen_numeric_list_reversed<int, 10>::type, numeric_list<int, 9, 8, 7, 6, 5, 4, 3, 2, 1, 0>>::value));\n\n  VERIFY((is_same<typename gen_numeric_list_reversed<int, 0, 42>::type, numeric_list<int>>::value));\n  VERIFY((is_same<typename gen_numeric_list_reversed<int, 1, 42>::type, numeric_list<int, 42>>::value));\n  VERIFY((is_same<typename gen_numeric_list_reversed<int, 2, 42>::type, numeric_list<int, 43, 42>>::value));\n  VERIFY((is_same<typename gen_numeric_list_reversed<int, 5, 42>::type, numeric_list<int, 46, 45, 44, 43, 42>>::value));\n  VERIFY((is_same<typename gen_numeric_list_reversed<int, 10, 42>::type, numeric_list<int, 51, 50, 49, 48, 47, 46, 45, 44, 43, 42>>::value));\n\n  VERIFY((is_same<typename gen_numeric_list_swapped_pair<int, 0, 2, 3>::type, numeric_list<int>>::value));\n  VERIFY((is_same<typename gen_numeric_list_swapped_pair<int, 1, 2, 3>::type, numeric_list<int, 0>>::value));\n  VERIFY((is_same<typename gen_numeric_list_swapped_pair<int, 2, 2, 3>::type, numeric_list<int, 0, 1>>::value));\n  VERIFY((is_same<typename gen_numeric_list_swapped_pair<int, 5, 2, 3>::type, numeric_list<int, 0, 1, 3, 2, 4>>::value));\n  VERIFY((is_same<typename gen_numeric_list_swapped_pair<int, 10, 2, 3>::type, numeric_list<int, 0, 1, 3, 2, 4, 5, 6, 7, 8, 9>>::value));\n\n  VERIFY((is_same<typename gen_numeric_list_swapped_pair<int, 0, 44, 45, 42>::type, numeric_list<int>>::value));\n  VERIFY((is_same<typename gen_numeric_list_swapped_pair<int, 1, 44, 45, 42>::type, numeric_list<int, 42>>::value));\n  VERIFY((is_same<typename gen_numeric_list_swapped_pair<int, 2, 44, 45, 42>::type, numeric_list<int, 42, 43>>::value));\n  VERIFY((is_same<typename gen_numeric_list_swapped_pair<int, 5, 44, 45, 42>::type, numeric_list<int, 42, 43, 45, 44, 46>>::value));\n  VERIFY((is_same<typename gen_numeric_list_swapped_pair<int, 10, 44, 45, 42>::type, numeric_list<int, 42, 43, 45, 44, 46, 47, 48, 49, 50, 51>>::value));\n\n  VERIFY((is_same<typename gen_numeric_list_repeated<int, 0, 0>::type, numeric_list<int>>::value));\n  VERIFY((is_same<typename gen_numeric_list_repeated<int, 1, 0>::type, numeric_list<int, 0>>::value));\n  VERIFY((is_same<typename gen_numeric_list_repeated<int, 2, 0>::type, numeric_list<int, 0, 0>>::value));\n  VERIFY((is_same<typename gen_numeric_list_repeated<int, 5, 0>::type, numeric_list<int, 0, 0, 0, 0, 0>>::value));\n  VERIFY((is_same<typename gen_numeric_list_repeated<int, 10, 0>::type, numeric_list<int, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0>>::value));\n}\n\nstatic void test_concat()\n{\n  VERIFY((is_same<typename concat<type_list<dummy_a, dummy_a>, type_list<>>::type, type_list<dummy_a, dummy_a>>::value));\n  VERIFY((is_same<typename concat<type_list<>, type_list<dummy_a, dummy_a>>::type, type_list<dummy_a, dummy_a>>::value));\n  VERIFY((is_same<typename concat<type_list<dummy_a, dummy_a>, type_list<dummy_a, dummy_a>>::type, type_list<dummy_a, dummy_a, dummy_a, dummy_a>>::value));\n  VERIFY((is_same<typename concat<type_list<dummy_a, dummy_a>, type_list<dummy_b, dummy_c>>::type, type_list<dummy_a, dummy_a, dummy_b, dummy_c>>::value));\n  VERIFY((is_same<typename concat<type_list<dummy_a>, type_list<dummy_b, dummy_c>>::type, type_list<dummy_a, dummy_b, dummy_c>>::value));\n\n  VERIFY((is_same<typename concat<numeric_list<int, 0, 0>, numeric_list<int>>::type, numeric_list<int, 0, 0>>::value));\n  VERIFY((is_same<typename concat<numeric_list<int>, numeric_list<int, 0, 0>>::type, numeric_list<int, 0, 0>>::value));\n  VERIFY((is_same<typename concat<numeric_list<int, 0, 0>, numeric_list<int, 0, 0>>::type, numeric_list<int, 0, 0, 0, 0>>::value));\n  VERIFY((is_same<typename concat<numeric_list<int, 0, 0>, numeric_list<int, 1, 2>>::type, numeric_list<int, 0, 0, 1, 2>>::value));\n  VERIFY((is_same<typename concat<numeric_list<int, 0>, numeric_list<int, 1, 2>>::type, numeric_list<int, 0, 1, 2>>::value));\n\n  VERIFY((is_same<typename mconcat<type_list<dummy_a>>::type, type_list<dummy_a>>::value));\n  VERIFY((is_same<typename mconcat<type_list<dummy_a>, type_list<dummy_b>>::type, type_list<dummy_a, dummy_b>>::value));\n  VERIFY((is_same<typename mconcat<type_list<dummy_a>, type_list<dummy_b>, type_list<dummy_c>>::type, type_list<dummy_a, dummy_b, dummy_c>>::value));\n  VERIFY((is_same<typename mconcat<type_list<dummy_a>, type_list<dummy_b, dummy_c>>::type, type_list<dummy_a, dummy_b, dummy_c>>::value));\n  VERIFY((is_same<typename mconcat<type_list<dummy_a, dummy_b>, type_list<dummy_c>>::type, type_list<dummy_a, dummy_b, dummy_c>>::value));\n\n  VERIFY((is_same<typename mconcat<numeric_list<int, 0>>::type, numeric_list<int, 0>>::value));\n  VERIFY((is_same<typename mconcat<numeric_list<int, 0>, numeric_list<int, 1>>::type, numeric_list<int, 0, 1>>::value));\n  VERIFY((is_same<typename mconcat<numeric_list<int, 0>, numeric_list<int, 1>, numeric_list<int, 2>>::type, numeric_list<int, 0, 1, 2>>::value));\n  VERIFY((is_same<typename mconcat<numeric_list<int, 0>, numeric_list<int, 1, 2>>::type, numeric_list<int, 0, 1, 2>>::value));\n  VERIFY((is_same<typename mconcat<numeric_list<int, 0, 1>, numeric_list<int, 2>>::type, numeric_list<int, 0, 1, 2>>::value));\n}\n\nstatic void test_slice()\n{\n  typedef type_list<dummy_a, dummy_a, dummy_b, dummy_b, dummy_c, dummy_c> tl;\n  typedef numeric_list<int, 0, 1, 2, 3, 4, 5> il;\n\n  VERIFY((is_same<typename take<0, tl>::type, type_list<>>::value));\n  VERIFY((is_same<typename take<1, tl>::type, type_list<dummy_a>>::value));\n  VERIFY((is_same<typename take<2, tl>::type, type_list<dummy_a, dummy_a>>::value));\n  VERIFY((is_same<typename take<3, tl>::type, type_list<dummy_a, dummy_a, dummy_b>>::value));\n  VERIFY((is_same<typename take<4, tl>::type, type_list<dummy_a, dummy_a, dummy_b, dummy_b>>::value));\n  VERIFY((is_same<typename take<5, tl>::type, type_list<dummy_a, dummy_a, dummy_b, dummy_b, dummy_c>>::value));\n  VERIFY((is_same<typename take<6, tl>::type, type_list<dummy_a, dummy_a, dummy_b, dummy_b, dummy_c, dummy_c>>::value));\n\n  VERIFY((is_same<typename take<0, il>::type, numeric_list<int>>::value));\n  VERIFY((is_same<typename take<1, il>::type, numeric_list<int, 0>>::value));\n  VERIFY((is_same<typename take<2, il>::type, numeric_list<int, 0, 1>>::value));\n  VERIFY((is_same<typename take<3, il>::type, numeric_list<int, 0, 1, 2>>::value));\n  VERIFY((is_same<typename take<4, il>::type, numeric_list<int, 0, 1, 2, 3>>::value));\n  VERIFY((is_same<typename take<5, il>::type, numeric_list<int, 0, 1, 2, 3, 4>>::value));\n  VERIFY((is_same<typename take<6, il>::type, numeric_list<int, 0, 1, 2, 3, 4, 5>>::value));\n  \n  VERIFY((is_same<typename skip<0, tl>::type, type_list<dummy_a, dummy_a, dummy_b, dummy_b, dummy_c, dummy_c>>::value));\n  VERIFY((is_same<typename skip<1, tl>::type, type_list<dummy_a, dummy_b, dummy_b, dummy_c, dummy_c>>::value));\n  VERIFY((is_same<typename skip<2, tl>::type, type_list<dummy_b, dummy_b, dummy_c, dummy_c>>::value));\n  VERIFY((is_same<typename skip<3, tl>::type, type_list<dummy_b, dummy_c, dummy_c>>::value));\n  VERIFY((is_same<typename skip<4, tl>::type, type_list<dummy_c, dummy_c>>::value));\n  VERIFY((is_same<typename skip<5, tl>::type, type_list<dummy_c>>::value));\n  VERIFY((is_same<typename skip<6, tl>::type, type_list<>>::value));\n\n  VERIFY((is_same<typename skip<0, il>::type, numeric_list<int, 0, 1, 2, 3, 4, 5>>::value));\n  VERIFY((is_same<typename skip<1, il>::type, numeric_list<int, 1, 2, 3, 4, 5>>::value));\n  VERIFY((is_same<typename skip<2, il>::type, numeric_list<int, 2, 3, 4, 5>>::value));\n  VERIFY((is_same<typename skip<3, il>::type, numeric_list<int, 3, 4, 5>>::value));\n  VERIFY((is_same<typename skip<4, il>::type, numeric_list<int, 4, 5>>::value));\n  VERIFY((is_same<typename skip<5, il>::type, numeric_list<int, 5>>::value));\n  VERIFY((is_same<typename skip<6, il>::type, numeric_list<int>>::value));\n\n  VERIFY((is_same<typename slice<0, 3, tl>::type, typename take<3, tl>::type>::value));\n  VERIFY((is_same<typename slice<0, 3, il>::type, typename take<3, il>::type>::value));\n  VERIFY((is_same<typename slice<1, 3, tl>::type, type_list<dummy_a, dummy_b, dummy_b>>::value));\n  VERIFY((is_same<typename slice<1, 3, il>::type, numeric_list<int, 1, 2, 3>>::value));\n}\n\nstatic void test_get()\n{\n  typedef type_list<dummy_a, dummy_a, dummy_b, dummy_b, dummy_c, dummy_c> tl;\n  typedef numeric_list<int, 4, 8, 15, 16, 23, 42> il;\n\n  VERIFY((is_same<typename get<0, tl>::type, dummy_a>::value));\n  VERIFY((is_same<typename get<1, tl>::type, dummy_a>::value));\n  VERIFY((is_same<typename get<2, tl>::type, dummy_b>::value));\n  VERIFY((is_same<typename get<3, tl>::type, dummy_b>::value));\n  VERIFY((is_same<typename get<4, tl>::type, dummy_c>::value));\n  VERIFY((is_same<typename get<5, tl>::type, dummy_c>::value));\n\n  VERIFY_IS_EQUAL(((int)get<0, il>::value), 4);\n  VERIFY_IS_EQUAL(((int)get<1, il>::value), 8);\n  VERIFY_IS_EQUAL(((int)get<2, il>::value), 15);\n  VERIFY_IS_EQUAL(((int)get<3, il>::value), 16);\n  VERIFY_IS_EQUAL(((int)get<4, il>::value), 23);\n  VERIFY_IS_EQUAL(((int)get<5, il>::value), 42);\n}\n\nstatic void test_id_helper(dummy_a a, dummy_a b, dummy_a c)\n{\n  (void)a;\n  (void)b;\n  (void)c;\n}\n\ntemplate<int... ii>\nstatic void test_id_numeric()\n{\n  test_id_helper(typename id_numeric<int, ii, dummy_a>::type()...);\n}\n\ntemplate<typename... tt>\nstatic void test_id_type()\n{\n  test_id_helper(typename id_type<tt, dummy_a>::type()...);\n}\n\nstatic void test_id()\n{\n  // don't call VERIFY here, just assume it works if it compiles\n  // (otherwise it will complain that it can't find the function)\n  test_id_numeric<1, 4, 6>();\n  test_id_type<dummy_a, dummy_b, dummy_c>();\n}\n\nstatic void test_is_same_gf()\n{\n  VERIFY((!is_same_gf<dummy_a, dummy_b>::value));\n  VERIFY((!!is_same_gf<dummy_a, dummy_a>::value));\n  VERIFY_IS_EQUAL((!!is_same_gf<dummy_a, dummy_b>::global_flags), false);\n  VERIFY_IS_EQUAL((!!is_same_gf<dummy_a, dummy_a>::global_flags), false);\n}\n\nstatic void test_apply_op()\n{\n  typedef type_list<dummy_a, dummy_b, dummy_c> tl;\n  VERIFY((!!is_same<typename apply_op_from_left<dummy_op, dummy_a, tl>::type, type_list<dummy_e, dummy_c, dummy_d>>::value));\n  VERIFY((!!is_same<typename apply_op_from_right<dummy_op, dummy_a, tl>::type, type_list<dummy_e, dummy_d, dummy_b>>::value));\n}\n\nstatic void test_contained_in_list()\n{\n  typedef type_list<dummy_a, dummy_b, dummy_c> tl;\n\n  VERIFY((!!contained_in_list<is_same, dummy_a, tl>::value));\n  VERIFY((!!contained_in_list<is_same, dummy_b, tl>::value));\n  VERIFY((!!contained_in_list<is_same, dummy_c, tl>::value));\n  VERIFY((!contained_in_list<is_same, dummy_d, tl>::value));\n  VERIFY((!contained_in_list<is_same, dummy_e, tl>::value));\n\n  VERIFY((!!contained_in_list_gf<dummy_test, dummy_a, tl>::value));\n  VERIFY((!!contained_in_list_gf<dummy_test, dummy_b, tl>::value));\n  VERIFY((!!contained_in_list_gf<dummy_test, dummy_c, tl>::value));\n  VERIFY((!contained_in_list_gf<dummy_test, dummy_d, tl>::value));\n  VERIFY((!contained_in_list_gf<dummy_test, dummy_e, tl>::value));\n\n  VERIFY_IS_EQUAL(((int)contained_in_list_gf<dummy_test, dummy_a, tl>::global_flags), 1);\n  VERIFY_IS_EQUAL(((int)contained_in_list_gf<dummy_test, dummy_b, tl>::global_flags), 2);\n  VERIFY_IS_EQUAL(((int)contained_in_list_gf<dummy_test, dummy_c, tl>::global_flags), 4);\n  VERIFY_IS_EQUAL(((int)contained_in_list_gf<dummy_test, dummy_d, tl>::global_flags), 0);\n  VERIFY_IS_EQUAL(((int)contained_in_list_gf<dummy_test, dummy_e, tl>::global_flags), 0);\n}\n\nstatic void test_arg_reductions()\n{\n  VERIFY_IS_EQUAL(arg_sum(1,2,3,4), 10);\n  VERIFY_IS_EQUAL(arg_prod(1,2,3,4), 24);\n  VERIFY_IS_APPROX(arg_sum(0.5, 2, 5), 7.5);\n  VERIFY_IS_APPROX(arg_prod(0.5, 2, 5), 5.0);\n}\n\nstatic void test_array_reverse_and_reduce()\n{\n  array<int, 6> a{{4, 8, 15, 16, 23, 42}};\n  array<int, 6> b{{42, 23, 16, 15, 8, 4}};\n\n  // there is no operator<< for std::array, so VERIFY_IS_EQUAL will\n  // not compile\n  VERIFY((array_reverse(a) == b));\n  VERIFY((array_reverse(b) == a));\n  VERIFY_IS_EQUAL((array_sum(a)), 108);\n  VERIFY_IS_EQUAL((array_sum(b)), 108);\n  VERIFY_IS_EQUAL((array_prod(a)), 7418880);\n  VERIFY_IS_EQUAL((array_prod(b)), 7418880);\n}\n\nstatic void test_array_zip_and_apply()\n{\n  array<int, 6> a{{4, 8, 15, 16, 23, 42}};\n  array<int, 6> b{{0, 1, 2, 3, 4, 5}};\n  array<int, 6> c{{4, 9, 17, 19, 27, 47}};\n  array<int, 6> d{{0, 8, 30, 48, 92, 210}};\n  array<int, 6> e{{0, 2, 4, 6, 8, 10}};\n\n  VERIFY((array_zip<sum_op>(a, b) == c));\n  VERIFY((array_zip<product_op>(a, b) == d));\n  VERIFY((array_apply<times2_op>(b) == e));\n  VERIFY_IS_EQUAL((array_apply_and_reduce<sum_op, times2_op>(a)), 216);\n  VERIFY_IS_EQUAL((array_apply_and_reduce<sum_op, times2_op>(b)), 30);\n  VERIFY_IS_EQUAL((array_zip_and_reduce<product_op, sum_op>(a, b)), 14755932);\n  VERIFY_IS_EQUAL((array_zip_and_reduce<sum_op, product_op>(a, b)), 388);\n}\n\nstatic void test_array_misc()\n{\n  array<int, 3> a3{{1, 1, 1}};\n  array<int, 6> a6{{2, 2, 2, 2, 2, 2}};\n  VERIFY((repeat<3, int>(1) == a3));\n  VERIFY((repeat<6, int>(2) == a6));\n\n  int data[5] = { 0, 1, 2, 3, 4 };\n  VERIFY_IS_EQUAL((instantiate_by_c_array<dummy_inst, int, 0>(data).c), 0);\n  VERIFY_IS_EQUAL((instantiate_by_c_array<dummy_inst, int, 1>(data).c), 1);\n  VERIFY_IS_EQUAL((instantiate_by_c_array<dummy_inst, int, 2>(data).c), 2);\n  VERIFY_IS_EQUAL((instantiate_by_c_array<dummy_inst, int, 3>(data).c), 3);\n  VERIFY_IS_EQUAL((instantiate_by_c_array<dummy_inst, int, 4>(data).c), 4);\n  VERIFY_IS_EQUAL((instantiate_by_c_array<dummy_inst, int, 5>(data).c), 5);\n}\n\nEIGEN_DECLARE_TEST(cxx11_meta)\n{\n  CALL_SUBTEST(test_gen_numeric_list());\n  CALL_SUBTEST(test_concat());\n  CALL_SUBTEST(test_slice());\n  CALL_SUBTEST(test_get());\n  CALL_SUBTEST(test_id());\n  CALL_SUBTEST(test_is_same_gf());\n  CALL_SUBTEST(test_apply_op());\n  CALL_SUBTEST(test_contained_in_list());\n  CALL_SUBTEST(test_arg_reductions());\n  CALL_SUBTEST(test_array_reverse_and_reduce());\n  CALL_SUBTEST(test_array_zip_and_apply());\n  CALL_SUBTEST(test_array_misc());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_non_blocking_thread_pool.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Dmitry Vyukov <dvyukov@google.com>\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_USE_THREADS\n#include \"main.h\"\n#include \"Eigen/CXX11/ThreadPool\"\n#include \"Eigen/CXX11/Tensor\"\n\nstatic void test_create_destroy_empty_pool()\n{\n  // Just create and destroy the pool. This will wind up and tear down worker\n  // threads. Ensure there are no issues in that logic.\n  for (int i = 0; i < 16; ++i) {\n    ThreadPool tp(i);\n  }\n}\n\n\nstatic void test_parallelism(bool allow_spinning)\n{\n  // Test we never-ever fail to match available tasks with idle threads.\n  const int kThreads = 16;  // code below expects that this is a multiple of 4\n  ThreadPool tp(kThreads, allow_spinning);\n  VERIFY_IS_EQUAL(tp.NumThreads(), kThreads);\n  VERIFY_IS_EQUAL(tp.CurrentThreadId(), -1);\n  for (int iter = 0; iter < 100; ++iter) {\n    std::atomic<int> running(0);\n    std::atomic<int> done(0);\n    std::atomic<int> phase(0);\n    // Schedule kThreads tasks and ensure that they all are running.\n    for (int i = 0; i < kThreads; ++i) {\n      tp.Schedule([&]() {\n        const int thread_id = tp.CurrentThreadId();\n        VERIFY_GE(thread_id, 0);\n        VERIFY_LE(thread_id, kThreads - 1);\n        running++;\n        while (phase < 1) {\n        }\n        done++;\n      });\n    }\n    while (running != kThreads) {\n    }\n    running = 0;\n    phase = 1;\n    // Now, while the previous tasks exit, schedule another kThreads tasks and\n    // ensure that they are running.\n    for (int i = 0; i < kThreads; ++i) {\n      tp.Schedule([&, i]() {\n        running++;\n        while (phase < 2) {\n        }\n        // When all tasks are running, half of tasks exit, quarter of tasks\n        // continue running and quarter of tasks schedule another 2 tasks each.\n        // Concurrently main thread schedules another quarter of tasks.\n        // This gives us another kThreads tasks and we ensure that they all\n        // are running.\n        if (i < kThreads / 2) {\n        } else if (i < 3 * kThreads / 4) {\n          running++;\n          while (phase < 3) {\n          }\n          done++;\n        } else {\n          for (int j = 0; j < 2; ++j) {\n            tp.Schedule([&]() {\n              running++;\n              while (phase < 3) {\n              }\n              done++;\n            });\n          }\n        }\n        done++;\n      });\n    }\n    while (running != kThreads) {\n    }\n    running = 0;\n    phase = 2;\n    for (int i = 0; i < kThreads / 4; ++i) {\n      tp.Schedule([&]() {\n        running++;\n        while (phase < 3) {\n        }\n        done++;\n      });\n    }\n    while (running != kThreads) {\n    }\n    phase = 3;\n    while (done != 3 * kThreads) {\n    }\n  }\n}\n\n\nstatic void test_cancel()\n{\n  ThreadPool tp(2);\n\n  // Schedule a large number of closure that each sleeps for one second. This\n  // will keep the thread pool busy for much longer than the default test timeout.\n  for (int i = 0; i < 1000; ++i) {\n    tp.Schedule([]() {\n      std::this_thread::sleep_for(std::chrono::milliseconds(2000));\n    });\n  }\n\n  // Cancel the processing of all the closures that are still pending.\n  tp.Cancel();\n}\n\nstatic void test_pool_partitions() {\n  const int kThreads = 2;\n  ThreadPool tp(kThreads);\n\n  // Assign each thread to its own partition, so that stealing other work only\n  // occurs globally when a thread is idle.\n  std::vector<std::pair<unsigned, unsigned>> steal_partitions(kThreads);\n  for (int i = 0; i < kThreads; ++i) {\n    steal_partitions[i] = std::make_pair(i, i + 1);\n  }\n  tp.SetStealPartitions(steal_partitions);\n\n  std::atomic<int> running(0);\n  std::atomic<int> done(0);\n  std::atomic<int> phase(0);\n\n  // Schedule kThreads tasks and ensure that they all are running.\n  for (int i = 0; i < kThreads; ++i) {\n    tp.Schedule([&]() {\n      const int thread_id = tp.CurrentThreadId();\n      VERIFY_GE(thread_id, 0);\n      VERIFY_LE(thread_id, kThreads - 1);\n      ++running;\n      while (phase < 1) {\n      }\n      ++done;\n    });\n  }\n  while (running != kThreads) {\n  }\n  // Schedule each closure to only run on thread 'i' and verify that it does.\n  for (int i = 0; i < kThreads; ++i) {\n    tp.ScheduleWithHint(\n        [&, i]() {\n          ++running;\n          const int thread_id = tp.CurrentThreadId();\n          VERIFY_IS_EQUAL(thread_id, i);\n          while (phase < 2) {\n          }\n          ++done;\n        },\n        i, i + 1);\n  }\n  running = 0;\n  phase = 1;\n  while (running != kThreads) {\n  }\n  running = 0;\n  phase = 2;\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_non_blocking_thread_pool)\n{\n  CALL_SUBTEST(test_create_destroy_empty_pool());\n  CALL_SUBTEST(test_parallelism(true));\n  CALL_SUBTEST(test_parallelism(false));\n  CALL_SUBTEST(test_cancel());\n  CALL_SUBTEST(test_pool_partitions());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_runqueue.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Dmitry Vyukov <dvyukov@google.com>\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_USE_THREADS\n#include <cstdlib>\n#include \"main.h\"\n#include <Eigen/CXX11/ThreadPool>\n\n\n// Visual studio doesn't implement a rand_r() function since its\n// implementation of rand() is already thread safe\nint rand_reentrant(unsigned int* s) {\n#ifdef EIGEN_COMP_MSVC_STRICT\n  EIGEN_UNUSED_VARIABLE(s);\n  return rand();\n#else\n  return rand_r(s);\n#endif\n}\n\nvoid test_basic_runqueue()\n{\n  RunQueue<int, 4> q;\n  // Check empty state.\n  VERIFY(q.Empty());\n  VERIFY_IS_EQUAL(0u, q.Size());\n  VERIFY_IS_EQUAL(0, q.PopFront());\n  std::vector<int> stolen;\n  VERIFY_IS_EQUAL(0u, q.PopBackHalf(&stolen));\n  VERIFY_IS_EQUAL(0u, stolen.size());\n  // Push one front, pop one front.\n  VERIFY_IS_EQUAL(0, q.PushFront(1));\n  VERIFY_IS_EQUAL(1u, q.Size());\n  VERIFY_IS_EQUAL(1, q.PopFront());\n  VERIFY_IS_EQUAL(0u, q.Size());\n  // Push front to overflow.\n  VERIFY_IS_EQUAL(0, q.PushFront(2));\n  VERIFY_IS_EQUAL(1u, q.Size());\n  VERIFY_IS_EQUAL(0, q.PushFront(3));\n  VERIFY_IS_EQUAL(2u, q.Size());\n  VERIFY_IS_EQUAL(0, q.PushFront(4));\n  VERIFY_IS_EQUAL(3u, q.Size());\n  VERIFY_IS_EQUAL(0, q.PushFront(5));\n  VERIFY_IS_EQUAL(4u, q.Size());\n  VERIFY_IS_EQUAL(6, q.PushFront(6));\n  VERIFY_IS_EQUAL(4u, q.Size());\n  VERIFY_IS_EQUAL(5, q.PopFront());\n  VERIFY_IS_EQUAL(3u, q.Size());\n  VERIFY_IS_EQUAL(4, q.PopFront());\n  VERIFY_IS_EQUAL(2u, q.Size());\n  VERIFY_IS_EQUAL(3, q.PopFront());\n  VERIFY_IS_EQUAL(1u, q.Size());\n  VERIFY_IS_EQUAL(2, q.PopFront());\n  VERIFY_IS_EQUAL(0u, q.Size());\n  VERIFY_IS_EQUAL(0, q.PopFront());\n  // Push one back, pop one back.\n  VERIFY_IS_EQUAL(0, q.PushBack(7));\n  VERIFY_IS_EQUAL(1u, q.Size());\n  VERIFY_IS_EQUAL(1u, q.PopBackHalf(&stolen));\n  VERIFY_IS_EQUAL(1u, stolen.size());\n  VERIFY_IS_EQUAL(7, stolen[0]);\n  VERIFY_IS_EQUAL(0u, q.Size());\n  stolen.clear();\n  // Push back to overflow.\n  VERIFY_IS_EQUAL(0, q.PushBack(8));\n  VERIFY_IS_EQUAL(1u, q.Size());\n  VERIFY_IS_EQUAL(0, q.PushBack(9));\n  VERIFY_IS_EQUAL(2u, q.Size());\n  VERIFY_IS_EQUAL(0, q.PushBack(10));\n  VERIFY_IS_EQUAL(3u, q.Size());\n  VERIFY_IS_EQUAL(0, q.PushBack(11));\n  VERIFY_IS_EQUAL(4u, q.Size());\n  VERIFY_IS_EQUAL(12, q.PushBack(12));\n  VERIFY_IS_EQUAL(4u, q.Size());\n  // Pop back in halves.\n  VERIFY_IS_EQUAL(2u, q.PopBackHalf(&stolen));\n  VERIFY_IS_EQUAL(2u, stolen.size());\n  VERIFY_IS_EQUAL(10, stolen[0]);\n  VERIFY_IS_EQUAL(11, stolen[1]);\n  VERIFY_IS_EQUAL(2u, q.Size());\n  stolen.clear();\n  VERIFY_IS_EQUAL(1u, q.PopBackHalf(&stolen));\n  VERIFY_IS_EQUAL(1u, stolen.size());\n  VERIFY_IS_EQUAL(9, stolen[0]);\n  VERIFY_IS_EQUAL(1u, q.Size());\n  stolen.clear();\n  VERIFY_IS_EQUAL(1u, q.PopBackHalf(&stolen));\n  VERIFY_IS_EQUAL(1u, stolen.size());\n  VERIFY_IS_EQUAL(8, stolen[0]);\n  stolen.clear();\n  VERIFY_IS_EQUAL(0u, q.PopBackHalf(&stolen));\n  VERIFY_IS_EQUAL(0u, stolen.size());\n  // Empty again.\n  VERIFY(q.Empty());\n  VERIFY_IS_EQUAL(0u, q.Size());\n  VERIFY_IS_EQUAL(0, q.PushFront(1));\n  VERIFY_IS_EQUAL(0, q.PushFront(2));\n  VERIFY_IS_EQUAL(0, q.PushFront(3));\n  VERIFY_IS_EQUAL(1, q.PopBack());\n  VERIFY_IS_EQUAL(2, q.PopBack());\n  VERIFY_IS_EQUAL(3, q.PopBack());\n  VERIFY(q.Empty());\n  VERIFY_IS_EQUAL(0u, q.Size());\n}\n\n// Empty tests that the queue is not claimed to be empty when is is in fact not.\n// Emptiness property is crucial part of thread pool blocking scheme,\n// so we go to great effort to ensure this property. We create a queue with\n// 1 element and then push 1 element (either front or back at random) and pop\n// 1 element (either front or back at random). So queue always contains at least\n// 1 element, but otherwise changes chaotically. Another thread constantly tests\n// that the queue is not claimed to be empty.\nvoid test_empty_runqueue()\n{\n  RunQueue<int, 4> q;\n  q.PushFront(1);\n  std::atomic<bool> done(false);\n  std::thread mutator([&q, &done]() {\n    unsigned rnd = 0;\n    std::vector<int> stolen;\n    for (int i = 0; i < 1 << 18; i++) {\n      if (rand_reentrant(&rnd) % 2)\n        VERIFY_IS_EQUAL(0, q.PushFront(1));\n      else\n        VERIFY_IS_EQUAL(0, q.PushBack(1));\n      if (rand_reentrant(&rnd) % 2)\n        VERIFY_IS_EQUAL(1, q.PopFront());\n      else {\n        for (;;) {\n          if (q.PopBackHalf(&stolen) == 1) {\n            stolen.clear();\n            break;\n          }\n          VERIFY_IS_EQUAL(0u, stolen.size());\n        }\n      }\n    }\n    done = true;\n  });\n  while (!done) {\n    VERIFY(!q.Empty());\n    int size = q.Size();\n    VERIFY_GE(size, 1);\n    VERIFY_LE(size, 2);\n  }\n  VERIFY_IS_EQUAL(1, q.PopFront());\n  mutator.join();\n}\n\n// Stress is a chaotic random test.\n// One thread (owner) calls PushFront/PopFront, other threads call PushBack/\n// PopBack. Ensure that we don't crash, deadlock, and all sanity checks pass.\nvoid test_stress_runqueue()\n{\n  static const int kEvents = 1 << 18;\n  RunQueue<int, 8> q;\n  std::atomic<int> total(0);\n  std::vector<std::unique_ptr<std::thread>> threads;\n  threads.emplace_back(new std::thread([&q, &total]() {\n    int sum = 0;\n    int pushed = 1;\n    int popped = 1;\n    while (pushed < kEvents || popped < kEvents) {\n      if (pushed < kEvents) {\n        if (q.PushFront(pushed) == 0) {\n          sum += pushed;\n          pushed++;\n        }\n      }\n      if (popped < kEvents) {\n        int v = q.PopFront();\n        if (v != 0) {\n          sum -= v;\n          popped++;\n        }\n      }\n    }\n    total += sum;\n  }));\n  for (int i = 0; i < 2; i++) {\n    threads.emplace_back(new std::thread([&q, &total]() {\n      int sum = 0;\n      for (int j = 1; j < kEvents; j++) {\n        if (q.PushBack(j) == 0) {\n          sum += j;\n          continue;\n        }\n        EIGEN_THREAD_YIELD();\n        j--;\n      }\n      total += sum;\n    }));\n    threads.emplace_back(new std::thread([&q, &total]() {\n      int sum = 0;\n      std::vector<int> stolen;\n      for (int j = 1; j < kEvents;) {\n        if (q.PopBackHalf(&stolen) == 0) {\n          EIGEN_THREAD_YIELD();\n          continue;\n        }\n        while (stolen.size() && j < kEvents) {\n          int v = stolen.back();\n          stolen.pop_back();\n          VERIFY_IS_NOT_EQUAL(v, 0);\n          sum += v;\n          j++;\n        }\n      }\n      while (stolen.size()) {\n        int v = stolen.back();\n        stolen.pop_back();\n        VERIFY_IS_NOT_EQUAL(v, 0);\n        while ((v = q.PushBack(v)) != 0) EIGEN_THREAD_YIELD();\n      }\n      total -= sum;\n    }));\n  }\n  for (size_t i = 0; i < threads.size(); i++) threads[i]->join();\n  VERIFY(q.Empty());\n  VERIFY(total.load() == 0);\n}\n\nEIGEN_DECLARE_TEST(cxx11_runqueue)\n{\n  CALL_SUBTEST_1(test_basic_runqueue());\n  CALL_SUBTEST_2(test_empty_runqueue());\n  CALL_SUBTEST_3(test_stress_runqueue());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_argmax.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Eugene Brevdo <ebrevdo@google.com>\n//                    Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::array;\nusing Eigen::Tuple;\n\ntemplate <int DataLayout>\nstatic void test_simple_index_tuples()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  tensor = (tensor + tensor.constant(0.5)).log();\n\n  Tensor<Tuple<DenseIndex, float>, 4, DataLayout> index_tuples(2,3,5,7);\n  index_tuples = tensor.index_tuples();\n\n  for (DenseIndex n = 0; n < 2*3*5*7; ++n) {\n    const Tuple<DenseIndex, float>& v = index_tuples.coeff(n);\n    VERIFY_IS_EQUAL(v.first, n);\n    VERIFY_IS_EQUAL(v.second, tensor.coeff(n));\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_index_tuples_dim()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  tensor = (tensor + tensor.constant(0.5)).log();\n\n  Tensor<Tuple<DenseIndex, float>, 4, DataLayout> index_tuples(2,3,5,7);\n\n  index_tuples = tensor.index_tuples();\n\n  for (Eigen::DenseIndex n = 0; n < tensor.size(); ++n) {\n    const Tuple<DenseIndex, float>& v = index_tuples(n); //(i, j, k, l);\n    VERIFY_IS_EQUAL(v.first, n);\n    VERIFY_IS_EQUAL(v.second, tensor(n));\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_argmax_tuple_reducer()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  tensor = (tensor + tensor.constant(0.5)).log();\n\n  Tensor<Tuple<DenseIndex, float>, 4, DataLayout> index_tuples(2,3,5,7);\n  index_tuples = tensor.index_tuples();\n\n  Tensor<Tuple<DenseIndex, float>, 0, DataLayout> reduced;\n  DimensionList<DenseIndex, 4> dims;\n  reduced = index_tuples.reduce(\n      dims, internal::ArgMaxTupleReducer<Tuple<DenseIndex, float> >());\n\n  Tensor<float, 0, DataLayout> maxi = tensor.maximum();\n\n  VERIFY_IS_EQUAL(maxi(), reduced(0).second);\n\n  array<DenseIndex, 3> reduce_dims;\n  for (int d = 0; d < 3; ++d) reduce_dims[d] = d;\n  Tensor<Tuple<DenseIndex, float>, 1, DataLayout> reduced_by_dims(7);\n  reduced_by_dims = index_tuples.reduce(\n      reduce_dims, internal::ArgMaxTupleReducer<Tuple<DenseIndex, float> >());\n\n  Tensor<float, 1, DataLayout> max_by_dims = tensor.maximum(reduce_dims);\n\n  for (int l = 0; l < 7; ++l) {\n    VERIFY_IS_EQUAL(max_by_dims(l), reduced_by_dims(l).second);\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_argmin_tuple_reducer()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  tensor = (tensor + tensor.constant(0.5)).log();\n\n  Tensor<Tuple<DenseIndex, float>, 4, DataLayout> index_tuples(2,3,5,7);\n  index_tuples = tensor.index_tuples();\n\n  Tensor<Tuple<DenseIndex, float>, 0, DataLayout> reduced;\n  DimensionList<DenseIndex, 4> dims;\n  reduced = index_tuples.reduce(\n      dims, internal::ArgMinTupleReducer<Tuple<DenseIndex, float> >());\n\n  Tensor<float, 0, DataLayout> mini = tensor.minimum();\n\n  VERIFY_IS_EQUAL(mini(), reduced(0).second);\n\n  array<DenseIndex, 3> reduce_dims;\n  for (int d = 0; d < 3; ++d) reduce_dims[d] = d;\n  Tensor<Tuple<DenseIndex, float>, 1, DataLayout> reduced_by_dims(7);\n  reduced_by_dims = index_tuples.reduce(\n      reduce_dims, internal::ArgMinTupleReducer<Tuple<DenseIndex, float> >());\n\n  Tensor<float, 1, DataLayout> min_by_dims = tensor.minimum(reduce_dims);\n\n  for (int l = 0; l < 7; ++l) {\n    VERIFY_IS_EQUAL(min_by_dims(l), reduced_by_dims(l).second);\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_simple_argmax()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  tensor = (tensor + tensor.constant(0.5)).log();\n  tensor(0,0,0,0) = 10.0;\n\n  Tensor<DenseIndex, 0, DataLayout> tensor_argmax;\n\n  tensor_argmax = tensor.argmax();\n\n  VERIFY_IS_EQUAL(tensor_argmax(0), 0);\n\n  tensor(1,2,4,6) = 20.0;\n\n  tensor_argmax = tensor.argmax();\n\n  VERIFY_IS_EQUAL(tensor_argmax(0), 2*3*5*7 - 1);\n}\n\ntemplate <int DataLayout>\nstatic void test_simple_argmin()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  tensor = (tensor + tensor.constant(0.5)).log();\n  tensor(0,0,0,0) = -10.0;\n\n  Tensor<DenseIndex, 0, DataLayout> tensor_argmin;\n\n  tensor_argmin = tensor.argmin();\n\n  VERIFY_IS_EQUAL(tensor_argmin(0), 0);\n\n  tensor(1,2,4,6) = -20.0;\n\n  tensor_argmin = tensor.argmin();\n\n  VERIFY_IS_EQUAL(tensor_argmin(0), 2*3*5*7 - 1);\n}\n\ntemplate <int DataLayout>\nstatic void test_argmax_dim()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  std::vector<int> dims {2, 3, 5, 7};\n\n  for (int dim = 0; dim < 4; ++dim) {\n    tensor.setRandom();\n    tensor = (tensor + tensor.constant(0.5)).log();\n\n    Tensor<DenseIndex, 3, DataLayout> tensor_argmax;\n    array<DenseIndex, 4> ix;\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 3; ++j) {\n        for (int k = 0; k < 5; ++k) {\n          for (int l = 0; l < 7; ++l) {\n            ix[0] = i; ix[1] = j; ix[2] = k; ix[3] = l;\n            if (ix[dim] != 0) continue;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 0, k, l) = 10.0\n            tensor(ix) = 10.0;\n          }\n        }\n      }\n    }\n\n    tensor_argmax = tensor.argmax(dim);\n\n    VERIFY_IS_EQUAL(tensor_argmax.size(),\n                    ptrdiff_t(2*3*5*7 / tensor.dimension(dim)));\n    for (ptrdiff_t n = 0; n < tensor_argmax.size(); ++n) {\n      // Expect max to be in the first index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_argmax.data()[n], 0);\n    }\n\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 3; ++j) {\n        for (int k = 0; k < 5; ++k) {\n          for (int l = 0; l < 7; ++l) {\n            ix[0] = i; ix[1] = j; ix[2] = k; ix[3] = l;\n            if (ix[dim] != tensor.dimension(dim) - 1) continue;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 2, k, l) = 20.0\n            tensor(ix) = 20.0;\n          }\n        }\n      }\n    }\n\n    tensor_argmax = tensor.argmax(dim);\n\n    VERIFY_IS_EQUAL(tensor_argmax.size(),\n                    ptrdiff_t(2*3*5*7 / tensor.dimension(dim)));\n    for (ptrdiff_t n = 0; n < tensor_argmax.size(); ++n) {\n      // Expect max to be in the last index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_argmax.data()[n], tensor.dimension(dim) - 1);\n    }\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_argmin_dim()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  std::vector<int> dims {2, 3, 5, 7};\n\n  for (int dim = 0; dim < 4; ++dim) {\n    tensor.setRandom();\n    tensor = (tensor + tensor.constant(0.5)).log();\n\n    Tensor<DenseIndex, 3, DataLayout> tensor_argmin;\n    array<DenseIndex, 4> ix;\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 3; ++j) {\n        for (int k = 0; k < 5; ++k) {\n          for (int l = 0; l < 7; ++l) {\n            ix[0] = i; ix[1] = j; ix[2] = k; ix[3] = l;\n            if (ix[dim] != 0) continue;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 0, k, l) = -10.0\n            tensor(ix) = -10.0;\n          }\n        }\n      }\n    }\n\n    tensor_argmin = tensor.argmin(dim);\n\n    VERIFY_IS_EQUAL(tensor_argmin.size(),\n                    ptrdiff_t(2*3*5*7 / tensor.dimension(dim)));\n    for (ptrdiff_t n = 0; n < tensor_argmin.size(); ++n) {\n      // Expect min to be in the first index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_argmin.data()[n], 0);\n    }\n\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 3; ++j) {\n        for (int k = 0; k < 5; ++k) {\n          for (int l = 0; l < 7; ++l) {\n            ix[0] = i; ix[1] = j; ix[2] = k; ix[3] = l;\n            if (ix[dim] != tensor.dimension(dim) - 1) continue;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 2, k, l) = -20.0\n            tensor(ix) = -20.0;\n          }\n        }\n      }\n    }\n\n    tensor_argmin = tensor.argmin(dim);\n\n    VERIFY_IS_EQUAL(tensor_argmin.size(),\n                    ptrdiff_t(2*3*5*7 / tensor.dimension(dim)));\n    for (ptrdiff_t n = 0; n < tensor_argmin.size(); ++n) {\n      // Expect min to be in the last index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_argmin.data()[n], tensor.dimension(dim) - 1);\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_argmax)\n{\n  CALL_SUBTEST(test_simple_index_tuples<RowMajor>());\n  CALL_SUBTEST(test_simple_index_tuples<ColMajor>());\n  CALL_SUBTEST(test_index_tuples_dim<RowMajor>());\n  CALL_SUBTEST(test_index_tuples_dim<ColMajor>());\n  CALL_SUBTEST(test_argmax_tuple_reducer<RowMajor>());\n  CALL_SUBTEST(test_argmax_tuple_reducer<ColMajor>());\n  CALL_SUBTEST(test_argmin_tuple_reducer<RowMajor>());\n  CALL_SUBTEST(test_argmin_tuple_reducer<ColMajor>());\n  CALL_SUBTEST(test_simple_argmax<RowMajor>());\n  CALL_SUBTEST(test_simple_argmax<ColMajor>());\n  CALL_SUBTEST(test_simple_argmin<RowMajor>());\n  CALL_SUBTEST(test_simple_argmin<ColMajor>());\n  CALL_SUBTEST(test_argmax_dim<RowMajor>());\n  CALL_SUBTEST(test_argmax_dim<ColMajor>());\n  CALL_SUBTEST(test_argmin_dim<RowMajor>());\n  CALL_SUBTEST(test_argmin_dim<ColMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_argmax_gpu.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\n#include <unsupported/Eigen/CXX11/src/Tensor/TensorGpuHipCudaDefines.h>\n\nusing Eigen::Tensor;\n\ntemplate <int Layout>\nvoid test_gpu_simple_argmax()\n{\n  Tensor<double, 3, Layout> in(Eigen::array<DenseIndex, 3>(72,53,97));\n  Tensor<DenseIndex, 1, Layout> out_max(Eigen::array<DenseIndex, 1>(1));\n  Tensor<DenseIndex, 1, Layout> out_min(Eigen::array<DenseIndex, 1>(1));\n  in.setRandom();\n  in *= in.constant(100.0);\n  in(0, 0, 0) = -1000.0;\n  in(71, 52, 96) = 1000.0;\n\n  std::size_t in_bytes = in.size() * sizeof(double);\n  std::size_t out_bytes = out_max.size() * sizeof(DenseIndex);\n\n  double* d_in;\n  DenseIndex* d_out_max;\n  DenseIndex* d_out_min;\n  gpuMalloc((void**)(&d_in), in_bytes);\n  gpuMalloc((void**)(&d_out_max), out_bytes);\n  gpuMalloc((void**)(&d_out_min), out_bytes);\n\n  gpuMemcpy(d_in, in.data(), in_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<double, 3, Layout>, Aligned > gpu_in(d_in, Eigen::array<DenseIndex, 3>(72,53,97));\n  Eigen::TensorMap<Eigen::Tensor<DenseIndex, 1, Layout>, Aligned > gpu_out_max(d_out_max, Eigen::array<DenseIndex, 1>(1));\n  Eigen::TensorMap<Eigen::Tensor<DenseIndex, 1, Layout>, Aligned > gpu_out_min(d_out_min, Eigen::array<DenseIndex, 1>(1));\n\n  gpu_out_max.device(gpu_device) = gpu_in.argmax();\n  gpu_out_min.device(gpu_device) = gpu_in.argmin();\n\n  assert(gpuMemcpyAsync(out_max.data(), d_out_max, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuMemcpyAsync(out_min.data(), d_out_min, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  VERIFY_IS_EQUAL(out_max(Eigen::array<DenseIndex, 1>(0)), 72*53*97 - 1);\n  VERIFY_IS_EQUAL(out_min(Eigen::array<DenseIndex, 1>(0)), 0);\n\n  gpuFree(d_in);\n  gpuFree(d_out_max);\n  gpuFree(d_out_min);\n}\n\ntemplate <int DataLayout>\nvoid test_gpu_argmax_dim()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  std::vector<int> dims;\n  dims.push_back(2); dims.push_back(3); dims.push_back(5); dims.push_back(7);\n\n  for (int dim = 0; dim < 4; ++dim) {\n    tensor.setRandom();\n    tensor = (tensor + tensor.constant(0.5)).log();\n\n    array<DenseIndex, 3> out_shape;\n    for (int d = 0; d < 3; ++d) out_shape[d] = (d < dim) ? dims[d] : dims[d+1];\n\n    Tensor<DenseIndex, 3, DataLayout> tensor_arg(out_shape);\n\n    array<DenseIndex, 4> ix;\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 3; ++j) {\n        for (int k = 0; k < 5; ++k) {\n          for (int l = 0; l < 7; ++l) {\n            ix[0] = i; ix[1] = j; ix[2] = k; ix[3] = l;\n            if (ix[dim] != 0) continue;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 0, k, l) = 10.0\n            tensor(ix) = 10.0;\n          }\n        }\n      }\n    }\n\n    std::size_t in_bytes = tensor.size() * sizeof(float);\n    std::size_t out_bytes = tensor_arg.size() * sizeof(DenseIndex);\n\n    float* d_in;\n    DenseIndex* d_out;\n    gpuMalloc((void**)(&d_in), in_bytes);\n    gpuMalloc((void**)(&d_out), out_bytes);\n\n    gpuMemcpy(d_in, tensor.data(), in_bytes, gpuMemcpyHostToDevice);\n\n    Eigen::GpuStreamDevice stream;\n    Eigen::GpuDevice gpu_device(&stream);\n\n    Eigen::TensorMap<Eigen::Tensor<float, 4, DataLayout>, Aligned > gpu_in(d_in, Eigen::array<DenseIndex, 4>(2, 3, 5, 7));\n    Eigen::TensorMap<Eigen::Tensor<DenseIndex, 3, DataLayout>, Aligned > gpu_out(d_out, out_shape);\n\n    gpu_out.device(gpu_device) = gpu_in.argmax(dim);\n\n    assert(gpuMemcpyAsync(tensor_arg.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n    assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n    VERIFY_IS_EQUAL(tensor_arg.size(),\n                    size_t(2*3*5*7 / tensor.dimension(dim)));\n\n    for (DenseIndex n = 0; n < tensor_arg.size(); ++n) {\n      // Expect max to be in the first index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_arg.data()[n], 0);\n    }\n\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 3; ++j) {\n        for (int k = 0; k < 5; ++k) {\n          for (int l = 0; l < 7; ++l) {\n            ix[0] = i; ix[1] = j; ix[2] = k; ix[3] = l;\n            if (ix[dim] != tensor.dimension(dim) - 1) continue;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 2, k, l) = 20.0\n            tensor(ix) = 20.0;\n          }\n        }\n      }\n    }\n\n    gpuMemcpy(d_in, tensor.data(), in_bytes, gpuMemcpyHostToDevice);\n\n    gpu_out.device(gpu_device) = gpu_in.argmax(dim);\n\n    assert(gpuMemcpyAsync(tensor_arg.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n    assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n    for (DenseIndex n = 0; n < tensor_arg.size(); ++n) {\n      // Expect max to be in the last index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_arg.data()[n], tensor.dimension(dim) - 1);\n    }\n\n    gpuFree(d_in);\n    gpuFree(d_out);\n  }\n}\n\ntemplate <int DataLayout>\nvoid test_gpu_argmin_dim()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  std::vector<int> dims;\n  dims.push_back(2); dims.push_back(3); dims.push_back(5); dims.push_back(7);\n\n  for (int dim = 0; dim < 4; ++dim) {\n    tensor.setRandom();\n    tensor = (tensor + tensor.constant(0.5)).log();\n\n    array<DenseIndex, 3> out_shape;\n    for (int d = 0; d < 3; ++d) out_shape[d] = (d < dim) ? dims[d] : dims[d+1];\n\n    Tensor<DenseIndex, 3, DataLayout> tensor_arg(out_shape);\n\n    array<DenseIndex, 4> ix;\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 3; ++j) {\n        for (int k = 0; k < 5; ++k) {\n          for (int l = 0; l < 7; ++l) {\n            ix[0] = i; ix[1] = j; ix[2] = k; ix[3] = l;\n            if (ix[dim] != 0) continue;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 0, k, l) = 10.0\n            tensor(ix) = -10.0;\n          }\n        }\n      }\n    }\n\n    std::size_t in_bytes = tensor.size() * sizeof(float);\n    std::size_t out_bytes = tensor_arg.size() * sizeof(DenseIndex);\n\n    float* d_in;\n    DenseIndex* d_out;\n    gpuMalloc((void**)(&d_in), in_bytes);\n    gpuMalloc((void**)(&d_out), out_bytes);\n\n    gpuMemcpy(d_in, tensor.data(), in_bytes, gpuMemcpyHostToDevice);\n\n    Eigen::GpuStreamDevice stream;\n    Eigen::GpuDevice gpu_device(&stream);\n\n    Eigen::TensorMap<Eigen::Tensor<float, 4, DataLayout>, Aligned > gpu_in(d_in, Eigen::array<DenseIndex, 4>(2, 3, 5, 7));\n    Eigen::TensorMap<Eigen::Tensor<DenseIndex, 3, DataLayout>, Aligned > gpu_out(d_out, out_shape);\n\n    gpu_out.device(gpu_device) = gpu_in.argmin(dim);\n\n    assert(gpuMemcpyAsync(tensor_arg.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n    assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n    VERIFY_IS_EQUAL(tensor_arg.size(),\n                    2*3*5*7 / tensor.dimension(dim));\n\n    for (DenseIndex n = 0; n < tensor_arg.size(); ++n) {\n      // Expect min to be in the first index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_arg.data()[n], 0);\n    }\n\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 3; ++j) {\n        for (int k = 0; k < 5; ++k) {\n          for (int l = 0; l < 7; ++l) {\n            ix[0] = i; ix[1] = j; ix[2] = k; ix[3] = l;\n            if (ix[dim] != tensor.dimension(dim) - 1) continue;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 2, k, l) = 20.0\n            tensor(ix) = -20.0;\n          }\n        }\n      }\n    }\n\n    gpuMemcpy(d_in, tensor.data(), in_bytes, gpuMemcpyHostToDevice);\n\n    gpu_out.device(gpu_device) = gpu_in.argmin(dim);\n\n    assert(gpuMemcpyAsync(tensor_arg.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n    assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n    for (DenseIndex n = 0; n < tensor_arg.size(); ++n) {\n      // Expect max to be in the last index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_arg.data()[n], tensor.dimension(dim) - 1);\n    }\n\n    gpuFree(d_in);\n    gpuFree(d_out);\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_argmax_gpu)\n{\n  CALL_SUBTEST_1(test_gpu_simple_argmax<RowMajor>());\n  CALL_SUBTEST_1(test_gpu_simple_argmax<ColMajor>());\n  CALL_SUBTEST_2(test_gpu_argmax_dim<RowMajor>());\n  CALL_SUBTEST_2(test_gpu_argmax_dim<ColMajor>());\n  CALL_SUBTEST_3(test_gpu_argmin_dim<RowMajor>());\n  CALL_SUBTEST_3(test_gpu_argmin_dim<ColMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_argmax_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n#define EIGEN_HAS_CONSTEXPR 1\n\n#include \"main.h\"\n\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\ntemplate <typename DataType, int Layout, typename DenseIndex>\nstatic void test_sycl_simple_argmax(const Eigen::SyclDevice& sycl_device) {\n  Tensor<DataType, 3, Layout, DenseIndex> in(Eigen::array<DenseIndex, 3>{{2, 2, 2}});\n  Tensor<DenseIndex, 0, Layout, DenseIndex> out_max;\n  Tensor<DenseIndex, 0, Layout, DenseIndex> out_min;\n  in.setRandom();\n  in *= in.constant(100.0);\n  in(0, 0, 0) = -1000.0;\n  in(1, 1, 1) = 1000.0;\n\n  std::size_t in_bytes = in.size() * sizeof(DataType);\n  std::size_t out_bytes = out_max.size() * sizeof(DenseIndex);\n\n  DataType* d_in = static_cast<DataType*>(sycl_device.allocate(in_bytes));\n  DenseIndex* d_out_max = static_cast<DenseIndex*>(sycl_device.allocate(out_bytes));\n  DenseIndex* d_out_min = static_cast<DenseIndex*>(sycl_device.allocate(out_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, Layout, DenseIndex> > gpu_in(d_in,\n                                                                           Eigen::array<DenseIndex, 3>{{2, 2, 2}});\n  Eigen::TensorMap<Eigen::Tensor<DenseIndex, 0, Layout, DenseIndex> > gpu_out_max(d_out_max);\n  Eigen::TensorMap<Eigen::Tensor<DenseIndex, 0, Layout, DenseIndex> > gpu_out_min(d_out_min);\n  sycl_device.memcpyHostToDevice(d_in, in.data(), in_bytes);\n\n  gpu_out_max.device(sycl_device) = gpu_in.argmax();\n  gpu_out_min.device(sycl_device) = gpu_in.argmin();\n\n  sycl_device.memcpyDeviceToHost(out_max.data(), d_out_max, out_bytes);\n  sycl_device.memcpyDeviceToHost(out_min.data(), d_out_min, out_bytes);\n\n  VERIFY_IS_EQUAL(out_max(), 2 * 2 * 2 - 1);\n  VERIFY_IS_EQUAL(out_min(), 0);\n\n  sycl_device.deallocate(d_in);\n  sycl_device.deallocate(d_out_max);\n  sycl_device.deallocate(d_out_min);\n}\n\ntemplate <typename DataType, int DataLayout, typename DenseIndex>\nstatic void test_sycl_argmax_dim(const Eigen::SyclDevice& sycl_device) {\n  DenseIndex sizeDim0 = 9;\n  DenseIndex sizeDim1 = 3;\n  DenseIndex sizeDim2 = 5;\n  DenseIndex sizeDim3 = 7;\n  Tensor<DataType, 4, DataLayout, DenseIndex> tensor(sizeDim0, sizeDim1, sizeDim2, sizeDim3);\n\n  std::vector<DenseIndex> dims;\n  dims.push_back(sizeDim0);\n  dims.push_back(sizeDim1);\n  dims.push_back(sizeDim2);\n  dims.push_back(sizeDim3);\n  for (DenseIndex dim = 0; dim < 4; ++dim) {\n    array<DenseIndex, 3> out_shape;\n    for (DenseIndex d = 0; d < 3; ++d) out_shape[d] = (d < dim) ? dims[d] : dims[d + 1];\n\n    Tensor<DenseIndex, 3, DataLayout, DenseIndex> tensor_arg(out_shape);\n\n    array<DenseIndex, 4> ix;\n    for (DenseIndex i = 0; i < sizeDim0; ++i) {\n      for (DenseIndex j = 0; j < sizeDim1; ++j) {\n        for (DenseIndex k = 0; k < sizeDim2; ++k) {\n          for (DenseIndex l = 0; l < sizeDim3; ++l) {\n            ix[0] = i;\n            ix[1] = j;\n            ix[2] = k;\n            ix[3] = l;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 0, k, l)\n            // = 10.0\n            tensor(ix) = (ix[dim] != 0) ? -1.0 : 10.0;\n          }\n        }\n      }\n    }\n\n    std::size_t in_bytes = tensor.size() * sizeof(DataType);\n    std::size_t out_bytes = tensor_arg.size() * sizeof(DenseIndex);\n\n    DataType* d_in = static_cast<DataType*>(sycl_device.allocate(in_bytes));\n    DenseIndex* d_out = static_cast<DenseIndex*>(sycl_device.allocate(out_bytes));\n\n    Eigen::TensorMap<Eigen::Tensor<DataType, 4, DataLayout, DenseIndex> > gpu_in(\n        d_in, Eigen::array<DenseIndex, 4>{{sizeDim0, sizeDim1, sizeDim2, sizeDim3}});\n    Eigen::TensorMap<Eigen::Tensor<DenseIndex, 3, DataLayout, DenseIndex> > gpu_out(d_out, out_shape);\n\n    sycl_device.memcpyHostToDevice(d_in, tensor.data(), in_bytes);\n    gpu_out.device(sycl_device) = gpu_in.argmax(dim);\n    sycl_device.memcpyDeviceToHost(tensor_arg.data(), d_out, out_bytes);\n\n    VERIFY_IS_EQUAL(static_cast<size_t>(tensor_arg.size()),\n                    size_t(sizeDim0 * sizeDim1 * sizeDim2 * sizeDim3 / tensor.dimension(dim)));\n\n    for (DenseIndex n = 0; n < tensor_arg.size(); ++n) {\n      // Expect max to be in the first index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_arg.data()[n], 0);\n    }\n\n    sycl_device.synchronize();\n\n    for (DenseIndex i = 0; i < sizeDim0; ++i) {\n      for (DenseIndex j = 0; j < sizeDim1; ++j) {\n        for (DenseIndex k = 0; k < sizeDim2; ++k) {\n          for (DenseIndex l = 0; l < sizeDim3; ++l) {\n            ix[0] = i;\n            ix[1] = j;\n            ix[2] = k;\n            ix[3] = l;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 2, k, l) = 20.0\n            tensor(ix) = (ix[dim] != tensor.dimension(dim) - 1) ? -1.0 : 20.0;\n          }\n        }\n      }\n    }\n\n    sycl_device.memcpyHostToDevice(d_in, tensor.data(), in_bytes);\n    gpu_out.device(sycl_device) = gpu_in.argmax(dim);\n    sycl_device.memcpyDeviceToHost(tensor_arg.data(), d_out, out_bytes);\n\n    for (DenseIndex n = 0; n < tensor_arg.size(); ++n) {\n      // Expect max to be in the last index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_arg.data()[n], tensor.dimension(dim) - 1);\n    }\n    sycl_device.deallocate(d_in);\n    sycl_device.deallocate(d_out);\n  }\n}\n\ntemplate <typename DataType, int DataLayout, typename DenseIndex>\nstatic void test_sycl_argmin_dim(const Eigen::SyclDevice& sycl_device) {\n  DenseIndex sizeDim0 = 9;\n  DenseIndex sizeDim1 = 3;\n  DenseIndex sizeDim2 = 5;\n  DenseIndex sizeDim3 = 7;\n  Tensor<DataType, 4, DataLayout, DenseIndex> tensor(sizeDim0, sizeDim1, sizeDim2, sizeDim3);\n\n  std::vector<DenseIndex> dims;\n  dims.push_back(sizeDim0);\n  dims.push_back(sizeDim1);\n  dims.push_back(sizeDim2);\n  dims.push_back(sizeDim3);\n  for (DenseIndex dim = 0; dim < 4; ++dim) {\n    array<DenseIndex, 3> out_shape;\n    for (DenseIndex d = 0; d < 3; ++d) out_shape[d] = (d < dim) ? dims[d] : dims[d + 1];\n\n    Tensor<DenseIndex, 3, DataLayout, DenseIndex> tensor_arg(out_shape);\n\n    array<DenseIndex, 4> ix;\n    for (DenseIndex i = 0; i < sizeDim0; ++i) {\n      for (DenseIndex j = 0; j < sizeDim1; ++j) {\n        for (DenseIndex k = 0; k < sizeDim2; ++k) {\n          for (DenseIndex l = 0; l < sizeDim3; ++l) {\n            ix[0] = i;\n            ix[1] = j;\n            ix[2] = k;\n            ix[3] = l;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 0, k, l) = -10.0\n            tensor(ix) = (ix[dim] != 0) ? 1.0 : -10.0;\n          }\n        }\n      }\n    }\n\n    std::size_t in_bytes = tensor.size() * sizeof(DataType);\n    std::size_t out_bytes = tensor_arg.size() * sizeof(DenseIndex);\n\n    DataType* d_in = static_cast<DataType*>(sycl_device.allocate(in_bytes));\n    DenseIndex* d_out = static_cast<DenseIndex*>(sycl_device.allocate(out_bytes));\n\n    Eigen::TensorMap<Eigen::Tensor<DataType, 4, DataLayout, DenseIndex> > gpu_in(\n        d_in, Eigen::array<DenseIndex, 4>{{sizeDim0, sizeDim1, sizeDim2, sizeDim3}});\n    Eigen::TensorMap<Eigen::Tensor<DenseIndex, 3, DataLayout, DenseIndex> > gpu_out(d_out, out_shape);\n\n    sycl_device.memcpyHostToDevice(d_in, tensor.data(), in_bytes);\n    gpu_out.device(sycl_device) = gpu_in.argmin(dim);\n    sycl_device.memcpyDeviceToHost(tensor_arg.data(), d_out, out_bytes);\n\n    VERIFY_IS_EQUAL(static_cast<size_t>(tensor_arg.size()),\n                    size_t(sizeDim0 * sizeDim1 * sizeDim2 * sizeDim3 / tensor.dimension(dim)));\n\n    for (DenseIndex n = 0; n < tensor_arg.size(); ++n) {\n      // Expect max to be in the first index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_arg.data()[n], 0);\n    }\n\n    sycl_device.synchronize();\n\n    for (DenseIndex i = 0; i < sizeDim0; ++i) {\n      for (DenseIndex j = 0; j < sizeDim1; ++j) {\n        for (DenseIndex k = 0; k < sizeDim2; ++k) {\n          for (DenseIndex l = 0; l < sizeDim3; ++l) {\n            ix[0] = i;\n            ix[1] = j;\n            ix[2] = k;\n            ix[3] = l;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 2, k, l) = -20.0\n            tensor(ix) = (ix[dim] != tensor.dimension(dim) - 1) ? 1.0 : -20.0;\n          }\n        }\n      }\n    }\n\n    sycl_device.memcpyHostToDevice(d_in, tensor.data(), in_bytes);\n    gpu_out.device(sycl_device) = gpu_in.argmin(dim);\n    sycl_device.memcpyDeviceToHost(tensor_arg.data(), d_out, out_bytes);\n\n    for (DenseIndex n = 0; n < tensor_arg.size(); ++n) {\n      // Expect max to be in the last index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_arg.data()[n], tensor.dimension(dim) - 1);\n    }\n    sycl_device.deallocate(d_in);\n    sycl_device.deallocate(d_out);\n  }\n}\n\ntemplate <typename DataType, typename Device_Selector>\nvoid sycl_argmax_test_per_device(const Device_Selector& d) {\n  QueueInterface queueInterface(d);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_sycl_simple_argmax<DataType, RowMajor, int64_t>(sycl_device);\n  test_sycl_simple_argmax<DataType, ColMajor, int64_t>(sycl_device);\n  test_sycl_argmax_dim<DataType, ColMajor, int64_t>(sycl_device);\n  test_sycl_argmax_dim<DataType, RowMajor, int64_t>(sycl_device);\n  test_sycl_argmin_dim<DataType, ColMajor, int64_t>(sycl_device);\n  test_sycl_argmin_dim<DataType, RowMajor, int64_t>(sycl_device);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_argmax_sycl) {\n  for (const auto& device : Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_argmax_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_assign.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\nstatic void test_1d()\n{\n  Tensor<int, 1> vec1(6);\n  Tensor<int, 1, RowMajor> vec2(6);\n  vec1(0) = 4;  vec2(0) = 0;\n  vec1(1) = 8;  vec2(1) = 1;\n  vec1(2) = 15; vec2(2) = 2;\n  vec1(3) = 16; vec2(3) = 3;\n  vec1(4) = 23; vec2(4) = 4;\n  vec1(5) = 42; vec2(5) = 5;\n\n  int col_major[6] = {0};\n  int row_major[6] = {0};\n  TensorMap<Tensor<int, 1> > vec3(col_major, 6);\n  TensorMap<Tensor<int, 1, RowMajor> > vec4(row_major, 6);\n\n  vec3 = vec1;\n  vec4 = vec2;\n\n  VERIFY_IS_EQUAL(vec3(0), 4);\n  VERIFY_IS_EQUAL(vec3(1), 8);\n  VERIFY_IS_EQUAL(vec3(2), 15);\n  VERIFY_IS_EQUAL(vec3(3), 16);\n  VERIFY_IS_EQUAL(vec3(4), 23);\n  VERIFY_IS_EQUAL(vec3(5), 42);\n\n  VERIFY_IS_EQUAL(vec4(0), 0);\n  VERIFY_IS_EQUAL(vec4(1), 1);\n  VERIFY_IS_EQUAL(vec4(2), 2);\n  VERIFY_IS_EQUAL(vec4(3), 3);\n  VERIFY_IS_EQUAL(vec4(4), 4);\n  VERIFY_IS_EQUAL(vec4(5), 5);\n\n  vec1.setZero();\n  vec2.setZero();\n  vec1 = vec3;\n  vec2 = vec4;\n\n  VERIFY_IS_EQUAL(vec1(0), 4);\n  VERIFY_IS_EQUAL(vec1(1), 8);\n  VERIFY_IS_EQUAL(vec1(2), 15);\n  VERIFY_IS_EQUAL(vec1(3), 16);\n  VERIFY_IS_EQUAL(vec1(4), 23);\n  VERIFY_IS_EQUAL(vec1(5), 42);\n\n  VERIFY_IS_EQUAL(vec2(0), 0);\n  VERIFY_IS_EQUAL(vec2(1), 1);\n  VERIFY_IS_EQUAL(vec2(2), 2);\n  VERIFY_IS_EQUAL(vec2(3), 3);\n  VERIFY_IS_EQUAL(vec2(4), 4);\n  VERIFY_IS_EQUAL(vec2(5), 5);\n}\n\nstatic void test_2d()\n{\n  Tensor<int, 2> mat1(2,3);\n  Tensor<int, 2, RowMajor> mat2(2,3);\n\n  mat1(0,0) = 0;\n  mat1(0,1) = 1;\n  mat1(0,2) = 2;\n  mat1(1,0) = 3;\n  mat1(1,1) = 4;\n  mat1(1,2) = 5;\n\n  mat2(0,0) = 0;\n  mat2(0,1) = 1;\n  mat2(0,2) = 2;\n  mat2(1,0) = 3;\n  mat2(1,1) = 4;\n  mat2(1,2) = 5;\n\n  int col_major[6] = {0};\n  int row_major[6] = {0};\n  TensorMap<Tensor<int, 2> > mat3(row_major, 2, 3);\n  TensorMap<Tensor<int, 2, RowMajor> > mat4(col_major, 2, 3);\n\n  mat3 = mat1;\n  mat4 = mat2;\n\n  VERIFY_IS_EQUAL(mat3(0,0), 0);\n  VERIFY_IS_EQUAL(mat3(0,1), 1);\n  VERIFY_IS_EQUAL(mat3(0,2), 2);\n  VERIFY_IS_EQUAL(mat3(1,0), 3);\n  VERIFY_IS_EQUAL(mat3(1,1), 4);\n  VERIFY_IS_EQUAL(mat3(1,2), 5);\n\n  VERIFY_IS_EQUAL(mat4(0,0), 0);\n  VERIFY_IS_EQUAL(mat4(0,1), 1);\n  VERIFY_IS_EQUAL(mat4(0,2), 2);\n  VERIFY_IS_EQUAL(mat4(1,0), 3);\n  VERIFY_IS_EQUAL(mat4(1,1), 4);\n  VERIFY_IS_EQUAL(mat4(1,2), 5);\n\n  mat1.setZero();\n  mat2.setZero();\n  mat1 = mat3;\n  mat2 = mat4;\n\n  VERIFY_IS_EQUAL(mat1(0,0), 0);\n  VERIFY_IS_EQUAL(mat1(0,1), 1);\n  VERIFY_IS_EQUAL(mat1(0,2), 2);\n  VERIFY_IS_EQUAL(mat1(1,0), 3);\n  VERIFY_IS_EQUAL(mat1(1,1), 4);\n  VERIFY_IS_EQUAL(mat1(1,2), 5);\n\n  VERIFY_IS_EQUAL(mat2(0,0), 0);\n  VERIFY_IS_EQUAL(mat2(0,1), 1);\n  VERIFY_IS_EQUAL(mat2(0,2), 2);\n  VERIFY_IS_EQUAL(mat2(1,0), 3);\n  VERIFY_IS_EQUAL(mat2(1,1), 4);\n  VERIFY_IS_EQUAL(mat2(1,2), 5);\n}\n\nstatic void test_3d()\n{\n  Tensor<int, 3> mat1(2,3,7);\n  Tensor<int, 3, RowMajor> mat2(2,3,7);\n\n  int val = 0;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        mat1(i,j,k) = val;\n        mat2(i,j,k) = val;\n        val++;\n      }\n    }\n  }\n\n  int col_major[2*3*7] = {0};\n  int row_major[2*3*7] = {0};\n  TensorMap<Tensor<int, 3> > mat3(col_major, 2, 3, 7);\n  TensorMap<Tensor<int, 3, RowMajor> > mat4(row_major, 2, 3, 7);\n\n  mat3 = mat1;\n  mat4 = mat2;\n\n  val = 0;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(mat3(i,j,k), val);\n        VERIFY_IS_EQUAL(mat4(i,j,k), val);\n        val++;\n      }\n    }\n  }\n\n  mat1.setZero();\n  mat2.setZero();\n  mat1 = mat3;\n  mat2 = mat4;\n\n  val = 0;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(mat1(i,j,k), val);\n        VERIFY_IS_EQUAL(mat2(i,j,k), val);\n        val++;\n      }\n    }\n  }\n}\n\nstatic void test_same_type()\n{\n  Tensor<int, 1> orig_tensor(5);\n  Tensor<int, 1> dest_tensor(5);\n  orig_tensor.setRandom();\n  dest_tensor.setRandom();\n  int* orig_data = orig_tensor.data();\n  int* dest_data = dest_tensor.data();\n  dest_tensor = orig_tensor;\n  VERIFY_IS_EQUAL(orig_tensor.data(), orig_data);\n  VERIFY_IS_EQUAL(dest_tensor.data(), dest_data);\n  for (int i = 0; i < 5; ++i) {\n    VERIFY_IS_EQUAL(dest_tensor(i), orig_tensor(i));\n  }\n\n  TensorFixedSize<int, Sizes<5> > orig_array;\n  TensorFixedSize<int, Sizes<5> > dest_array;\n  orig_array.setRandom();\n  dest_array.setRandom();\n  orig_data = orig_array.data();\n  dest_data = dest_array.data();\n  dest_array = orig_array;\n  VERIFY_IS_EQUAL(orig_array.data(), orig_data);\n  VERIFY_IS_EQUAL(dest_array.data(), dest_data);\n  for (int i = 0; i < 5; ++i) {\n    VERIFY_IS_EQUAL(dest_array(i), orig_array(i));\n  }\n\n  int orig[5] = {1, 2, 3, 4, 5};\n  int dest[5] = {6, 7, 8, 9, 10};\n  TensorMap<Tensor<int, 1> > orig_map(orig, 5);\n  TensorMap<Tensor<int, 1> > dest_map(dest, 5);\n  orig_data = orig_map.data();\n  dest_data = dest_map.data();\n  dest_map = orig_map;\n  VERIFY_IS_EQUAL(orig_map.data(), orig_data);\n  VERIFY_IS_EQUAL(dest_map.data(), dest_data);\n  for (int i = 0; i < 5; ++i) {\n    VERIFY_IS_EQUAL(dest[i], i+1);\n  }\n}\n\nstatic void test_auto_resize()\n{\n  Tensor<int, 1> tensor1;\n  Tensor<int, 1> tensor2(3);\n  Tensor<int, 1> tensor3(5);\n  Tensor<int, 1> tensor4(7);\n\n  Tensor<int, 1> new_tensor(5);\n  new_tensor.setRandom();\n\n  tensor1 = tensor2 = tensor3 = tensor4 = new_tensor;\n\n  VERIFY_IS_EQUAL(tensor1.dimension(0), new_tensor.dimension(0));\n  VERIFY_IS_EQUAL(tensor2.dimension(0), new_tensor.dimension(0));\n  VERIFY_IS_EQUAL(tensor3.dimension(0), new_tensor.dimension(0));\n  VERIFY_IS_EQUAL(tensor4.dimension(0), new_tensor.dimension(0));\n  for (int i = 0; i < new_tensor.dimension(0); ++i) {\n    VERIFY_IS_EQUAL(tensor1(i), new_tensor(i));\n    VERIFY_IS_EQUAL(tensor2(i), new_tensor(i));\n    VERIFY_IS_EQUAL(tensor3(i), new_tensor(i));\n    VERIFY_IS_EQUAL(tensor4(i), new_tensor(i));\n  }\n}\n\n\nstatic void test_compound_assign()\n{\n  Tensor<int, 1> start_tensor(10);\n  Tensor<int, 1> offset_tensor(10);\n  start_tensor.setRandom();\n  offset_tensor.setRandom();\n\n  Tensor<int, 1> tensor = start_tensor;\n  tensor += offset_tensor;\n  for (int i = 0; i < 10; ++i) {\n    VERIFY_IS_EQUAL(tensor(i), start_tensor(i) + offset_tensor(i));\n  }\n\n  tensor = start_tensor;\n  tensor -= offset_tensor;\n  for (int i = 0; i < 10; ++i) {\n    VERIFY_IS_EQUAL(tensor(i), start_tensor(i) - offset_tensor(i));\n  }\n\n  tensor = start_tensor;\n  tensor *= offset_tensor;\n  for (int i = 0; i < 10; ++i) {\n    VERIFY_IS_EQUAL(tensor(i), start_tensor(i) * offset_tensor(i));\n  }\n\n  tensor = start_tensor;\n  tensor /= offset_tensor;\n  for (int i = 0; i < 10; ++i) {\n    VERIFY_IS_EQUAL(tensor(i), start_tensor(i) / offset_tensor(i));\n  }\n}\n\nstatic void test_std_initializers_tensor() {\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  Tensor<int, 1> a(3);\n  a.setValues({0, 1, 2});\n  VERIFY_IS_EQUAL(a(0), 0);\n  VERIFY_IS_EQUAL(a(1), 1);\n  VERIFY_IS_EQUAL(a(2), 2);\n\n  // It fills the top-left slice.\n  a.setValues({10, 20});\n  VERIFY_IS_EQUAL(a(0), 10);\n  VERIFY_IS_EQUAL(a(1), 20);\n  VERIFY_IS_EQUAL(a(2), 2);\n\n  // Chaining.\n  Tensor<int, 1> a2(3);\n  a2 = a.setValues({100, 200, 300});\n  VERIFY_IS_EQUAL(a(0), 100);\n  VERIFY_IS_EQUAL(a(1), 200);\n  VERIFY_IS_EQUAL(a(2), 300);\n  VERIFY_IS_EQUAL(a2(0), 100);\n  VERIFY_IS_EQUAL(a2(1), 200);\n  VERIFY_IS_EQUAL(a2(2), 300);\n\n  Tensor<int, 2> b(2, 3);\n  b.setValues({{0, 1, 2}, {3, 4, 5}});\n  VERIFY_IS_EQUAL(b(0, 0), 0);\n  VERIFY_IS_EQUAL(b(0, 1), 1);\n  VERIFY_IS_EQUAL(b(0, 2), 2);\n  VERIFY_IS_EQUAL(b(1, 0), 3);\n  VERIFY_IS_EQUAL(b(1, 1), 4);\n  VERIFY_IS_EQUAL(b(1, 2), 5);\n\n  // It fills the top-left slice.\n  b.setValues({{10, 20}, {30}});\n  VERIFY_IS_EQUAL(b(0, 0), 10);\n  VERIFY_IS_EQUAL(b(0, 1), 20);\n  VERIFY_IS_EQUAL(b(0, 2), 2);\n  VERIFY_IS_EQUAL(b(1, 0), 30);\n  VERIFY_IS_EQUAL(b(1, 1), 4);\n  VERIFY_IS_EQUAL(b(1, 2), 5);\n\n  Eigen::Tensor<int, 3> c(3, 2, 4);\n  c.setValues({{{0, 1, 2, 3}, {4, 5, 6, 7}},\n               {{10, 11, 12, 13}, {14, 15, 16, 17}},\n               {{20, 21, 22, 23}, {24, 25, 26, 27}}});\n  VERIFY_IS_EQUAL(c(0, 0, 0), 0);\n  VERIFY_IS_EQUAL(c(0, 0, 1), 1);\n  VERIFY_IS_EQUAL(c(0, 0, 2), 2);\n  VERIFY_IS_EQUAL(c(0, 0, 3), 3);\n  VERIFY_IS_EQUAL(c(0, 1, 0), 4);\n  VERIFY_IS_EQUAL(c(0, 1, 1), 5);\n  VERIFY_IS_EQUAL(c(0, 1, 2), 6);\n  VERIFY_IS_EQUAL(c(0, 1, 3), 7);\n  VERIFY_IS_EQUAL(c(1, 0, 0), 10);\n  VERIFY_IS_EQUAL(c(1, 0, 1), 11);\n  VERIFY_IS_EQUAL(c(1, 0, 2), 12);\n  VERIFY_IS_EQUAL(c(1, 0, 3), 13);\n  VERIFY_IS_EQUAL(c(1, 1, 0), 14);\n  VERIFY_IS_EQUAL(c(1, 1, 1), 15);\n  VERIFY_IS_EQUAL(c(1, 1, 2), 16);\n  VERIFY_IS_EQUAL(c(1, 1, 3), 17);\n  VERIFY_IS_EQUAL(c(2, 0, 0), 20);\n  VERIFY_IS_EQUAL(c(2, 0, 1), 21);\n  VERIFY_IS_EQUAL(c(2, 0, 2), 22);\n  VERIFY_IS_EQUAL(c(2, 0, 3), 23);\n  VERIFY_IS_EQUAL(c(2, 1, 0), 24);\n  VERIFY_IS_EQUAL(c(2, 1, 1), 25);\n  VERIFY_IS_EQUAL(c(2, 1, 2), 26);\n  VERIFY_IS_EQUAL(c(2, 1, 3), 27);\n#endif  // EIGEN_HAS_VARIADIC_TEMPLATES\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_assign)\n{\n  CALL_SUBTEST(test_1d());\n  CALL_SUBTEST(test_2d());\n  CALL_SUBTEST(test_3d());\n  CALL_SUBTEST(test_same_type());\n  CALL_SUBTEST(test_auto_resize());\n  CALL_SUBTEST(test_compound_assign());\n  CALL_SUBTEST(test_std_initializers_tensor());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_block_access.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2018 Andy Davis <andydavis@google.com>\n// Copyright (C) 2018 Eugene Zhulenev <ezhulenev@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <algorithm>\n#include <set>\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::Index;\nusing Eigen::RowMajor;\nusing Eigen::ColMajor;\nusing Eigen::internal::TensorBlockShapeType;\n\nstatic TensorOpCost zeroCost() { return {0, 0, 0}; }\n\ntemplate<typename T>\nstatic const T& choose(int layout, const T& col, const T& row) {\n  return layout == ColMajor ? col : row;\n}\n\nstatic TensorBlockShapeType RandomShape() {\n  return internal::random<bool>()\n         ? TensorBlockShapeType::kUniformAllDims\n         : TensorBlockShapeType::kSkewedInnerDims;\n}\n\ntemplate <int NumDims>\nstatic size_t RandomTargetSize(const DSizes<Index, NumDims>& dims) {\n  return internal::random<size_t>(1, dims.TotalSize());\n}\n\ntemplate <int NumDims>\nstatic DSizes<Index, NumDims> RandomDims() {\n  array<Index, NumDims> dims;\n  for (int i = 0; i < NumDims; ++i) {\n    dims[i] = internal::random<int>(1, 20);\n  }\n  return DSizes<Index, NumDims>(dims);\n}\n\ntemplate <typename T>\nstatic T* GenerateRandomData(const Index& size) {\n  T* data = new T[size];\n  for (int i = 0; i < size; ++i) {\n    data[i] = internal::random<T>();\n  }\n  return data;\n}\n\ntemplate <int NumDims>\nstatic void Debug(DSizes<Index, NumDims> dims) {\n  for (int i = 0; i < NumDims; ++i) {\n    std::cout << dims[i] << \"; \";\n  }\n  std::cout << std::endl;\n}\n\ntemplate <int Layout>\nstatic void test_block_mapper_sanity()\n{\n  typedef internal::TensorBlockMapper<2, Layout> TensorBlockMapper;\n\n  DSizes<Index, 2> tensor_dims(100, 100);\n\n  // Test uniform blocks.\n  TensorBlockMapper uniform_block_mapper(\n      tensor_dims, {TensorBlockShapeType::kUniformAllDims, 100, zeroCost()});\n\n  VERIFY_IS_EQUAL(uniform_block_mapper.blockCount(), 100);\n  VERIFY_IS_EQUAL(uniform_block_mapper.blockTotalSize(), 100);\n\n  // 10x10 blocks\n  auto uniform_b0 = uniform_block_mapper.blockDescriptor(0);\n  VERIFY_IS_EQUAL(uniform_b0.dimensions().at(0), 10);\n  VERIFY_IS_EQUAL(uniform_b0.dimensions().at(1), 10);\n\n  // Test skewed to inner dims blocks.\n  TensorBlockMapper skewed_block_mapper(\n      tensor_dims, {TensorBlockShapeType::kSkewedInnerDims, 100, zeroCost()});\n\n  VERIFY_IS_EQUAL(skewed_block_mapper.blockCount(), 100);\n  VERIFY_IS_EQUAL(skewed_block_mapper.blockTotalSize(), 100);\n\n  // 1x100 (100x1) rows/cols depending on a tensor layout.\n  auto skewed_b0 = skewed_block_mapper.blockDescriptor(0);\n  VERIFY_IS_EQUAL(skewed_b0.dimensions().at(0), choose(Layout, 100, 1));\n  VERIFY_IS_EQUAL(skewed_b0.dimensions().at(1), choose(Layout, 1, 100));\n}\n\n// Given a TensorBlock \"visit\" every element accessible though it, and a keep an\n// index in the visited set. Verify that every coeff accessed only once.\ntemplate<int NumDims, int Layout>\nstatic void UpdateCoeffSet(\n    const DSizes<Index, NumDims>& tensor_strides,\n    const internal::TensorBlockDescriptor<NumDims>& block,\n    Index first_coeff_index, int dim_index, std::set<Index>* visited_coeffs) {\n  const DSizes<Index, NumDims>& block_sizes = block.dimensions();\n\n  for (int i = 0; i < block_sizes[dim_index]; ++i) {\n    if (tensor_strides[dim_index] == 1) {\n      typedef std::pair<std::set<Index>::iterator, bool> ReturnType;\n      ReturnType inserted = visited_coeffs->insert(first_coeff_index + i);\n      VERIFY_IS_EQUAL(inserted.second, true);\n    } else {\n      int next_dim_index = dim_index + choose(Layout, -1, 1);\n      UpdateCoeffSet<NumDims, Layout>(tensor_strides, block, first_coeff_index,\n                                         next_dim_index, visited_coeffs);\n      first_coeff_index += tensor_strides[dim_index];\n    }\n  }\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_block_mapper_maps_every_element() {\n  typedef internal::TensorBlockMapper<NumDims, Layout> TensorBlockMapper;\n\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>();\n  DSizes<Index, NumDims> strides = internal::strides<Layout>(dims);\n\n  // Keep track of elements indices available via block access.\n  std::set<Index> coeff_set;\n\n  // Try different combinations of block types and sizes.\n  TensorBlockMapper block_mapper(\n      dims, {RandomShape(), RandomTargetSize(dims), zeroCost()});\n\n  for (int i = 0; i < block_mapper.blockCount(); ++i) {\n    auto block = block_mapper.blockDescriptor(i);\n    UpdateCoeffSet<NumDims, Layout>(strides, block, block.offset(),\n                                    choose(Layout, NumDims - 1, 0),\n                                    &coeff_set);\n  }\n\n  // Verify that every coefficient in the original Tensor is accessible through\n  // TensorBlock only once.\n  Index total_coeffs = dims.TotalSize();\n  VERIFY_IS_EQUAL(Index(coeff_set.size()), total_coeffs);\n  VERIFY_IS_EQUAL(*coeff_set.begin(), 0);\n  VERIFY_IS_EQUAL(*coeff_set.rbegin(), total_coeffs - 1);\n}\n\ntemplate <int Layout, int NumDims>\nstatic Index GetInputIndex(Index output_index,\n                         const array<Index, NumDims>& output_to_input_dim_map,\n                         const array<Index, NumDims>& input_strides,\n                         const array<Index, NumDims>& output_strides) {\n  int input_index = 0;\n  if (Layout == ColMajor) {\n    for (int i = NumDims - 1; i > 0; --i) {\n      const Index idx = output_index / output_strides[i];\n      input_index += idx * input_strides[output_to_input_dim_map[i]];\n      output_index -= idx * output_strides[i];\n    }\n    return input_index +\n           output_index * input_strides[output_to_input_dim_map[0]];\n  } else {\n    for (int i = 0; i < NumDims - 1; ++i) {\n      const Index idx = output_index / output_strides[i];\n      input_index += idx * input_strides[output_to_input_dim_map[i]];\n      output_index -= idx * output_strides[i];\n    }\n    return input_index +\n           output_index * input_strides[output_to_input_dim_map[NumDims - 1]];\n  }\n}\n\ntemplate <int Layout, int NumDims>\nstatic array<Index, NumDims> ComputeStrides(\n    const array<Index, NumDims>& sizes) {\n  array<Index, NumDims> strides;\n  if (Layout == ColMajor) {\n    strides[0] = 1;\n    for (int i = 1; i < NumDims; ++i) {\n      strides[i] = strides[i - 1] * sizes[i - 1];\n    }\n  } else {\n    strides[NumDims - 1] = 1;\n    for (int i = NumDims - 2; i >= 0; --i) {\n      strides[i] = strides[i + 1] * sizes[i + 1];\n    }\n  }\n  return strides;\n}\n\ntemplate<typename Scalar, typename StorageIndex, int Dim>\nclass EqualityChecker\n{\n    const Scalar* input_data;\n    const DSizes<StorageIndex, Dim> &input_dims, &input_strides, &output_dims, &output_strides;\n    void check_recursive(const Scalar* input, const Scalar* output, int depth=0) const\n    {\n        if(depth==Dim)\n        {\n            VERIFY_IS_EQUAL(*input, *output);\n            return;\n        }\n\n        for(int i=0; i<output_dims[depth]; ++i)\n        {\n            check_recursive(input + i % input_dims[depth] * input_strides[depth], output + i*output_strides[depth], depth+1);\n        }\n    }\npublic:\n    EqualityChecker(const Scalar* input_data_,\n            const DSizes<StorageIndex, Dim> &input_dims_, const DSizes<StorageIndex, Dim> &input_strides_,\n            const DSizes<StorageIndex, Dim> &output_dims_, const DSizes<StorageIndex, Dim> &output_strides_)\n        : input_data(input_data_)\n        , input_dims(input_dims_), input_strides(input_strides_)\n        , output_dims(output_dims_), output_strides(output_strides_)\n        {}\n\n    void operator()(const Scalar* output_data) const\n    {\n        check_recursive(input_data, output_data);\n    }\n};\n\ntemplate <int Layout>\nstatic void test_uniform_block_shape()\n{\n  typedef internal::TensorBlockDescriptor<5> TensorBlock;\n  typedef internal::TensorBlockMapper<5, Layout> TensorBlockMapper;\n\n  {\n    // Test shape 'UniformAllDims' with uniform 'max_coeff count'.\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 5 * 5 * 5 * 5 * 5;\n    TensorBlockMapper block_mapper(dims, {TensorBlockShapeType::kUniformAllDims,\n                                          max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    for (int i = 0; i < 5; ++i) {\n      VERIFY_IS_EQUAL(5, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  }\n\n  // Test shape 'UniformAllDims' with larger 'max_coeff count' which spills\n  // partially into first inner-most dimension.\n  if (Layout == ColMajor) {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 7 * 5 * 5 * 5 * 5;\n    TensorBlockMapper block_mapper(dims, {TensorBlockShapeType::kUniformAllDims,\n                                          max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(7, block.dimensions()[0]);\n    for (int i = 1; i < 5; ++i) {\n      VERIFY_IS_EQUAL(5, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  } else {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 5 * 5 * 5 * 5 * 6;\n    TensorBlockMapper block_mapper(dims, {TensorBlockShapeType::kUniformAllDims,\n                                          max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(6, block.dimensions()[4]);\n    for (int i = 3; i >= 0; --i) {\n      VERIFY_IS_EQUAL(5, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  }\n\n  // Test shape 'UniformAllDims' with larger 'max_coeff count' which spills\n  // fully into first inner-most dimension.\n  if (Layout == ColMajor) {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 11 * 5 * 5 * 5 * 5;\n    TensorBlockMapper block_mapper(dims, {TensorBlockShapeType::kUniformAllDims,\n                                          max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(11, block.dimensions()[0]);\n    for (int i = 1; i < 5; ++i) {\n      VERIFY_IS_EQUAL(5, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  } else {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 5 * 5 * 5 * 5 * 7;\n    TensorBlockMapper block_mapper(dims, {TensorBlockShapeType::kUniformAllDims,\n                                          max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(7, block.dimensions()[4]);\n    for (int i = 3; i >= 0; --i) {\n      VERIFY_IS_EQUAL(5, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  }\n\n  // Test shape 'UniformAllDims' with larger 'max_coeff count' which spills\n  // fully into first few inner-most dimensions.\n  if (Layout == ColMajor) {\n    DSizes<Index, 5> dims(7, 5, 6, 17, 7);\n    const Index max_coeff_count = 7 * 5 * 6 * 7 * 5;\n    TensorBlockMapper block_mapper(dims, {TensorBlockShapeType::kUniformAllDims,\n                                          max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(7, block.dimensions()[0]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[1]);\n    VERIFY_IS_EQUAL(6, block.dimensions()[2]);\n    VERIFY_IS_EQUAL(7, block.dimensions()[3]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[4]);\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  } else {\n    DSizes<Index, 5> dims(7, 5, 6, 9, 7);\n    const Index max_coeff_count = 5 * 5 * 5 * 6 * 7;\n    TensorBlockMapper block_mapper(dims, {TensorBlockShapeType::kUniformAllDims,\n                                          max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(7, block.dimensions()[4]);\n    VERIFY_IS_EQUAL(6, block.dimensions()[3]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[2]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[1]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[0]);\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  }\n\n  // Test shape 'UniformAllDims' with full allocation to all dims.\n  if (Layout == ColMajor) {\n    DSizes<Index, 5> dims(7, 5, 6, 17, 7);\n    const Index max_coeff_count = 7 * 5 * 6 * 17 * 7;\n    TensorBlockMapper block_mapper(dims, {TensorBlockShapeType::kUniformAllDims,\n                                          max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(7, block.dimensions()[0]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[1]);\n    VERIFY_IS_EQUAL(6, block.dimensions()[2]);\n    VERIFY_IS_EQUAL(17, block.dimensions()[3]);\n    VERIFY_IS_EQUAL(7, block.dimensions()[4]);\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  } else {\n    DSizes<Index, 5> dims(7, 5, 6, 9, 7);\n    const Index max_coeff_count = 7 * 5 * 6 * 9 * 7;\n    TensorBlockMapper block_mapper(dims, {TensorBlockShapeType::kUniformAllDims,\n                                          max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(7, block.dimensions()[4]);\n    VERIFY_IS_EQUAL(9, block.dimensions()[3]);\n    VERIFY_IS_EQUAL(6, block.dimensions()[2]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[1]);\n    VERIFY_IS_EQUAL(7, block.dimensions()[0]);\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  }\n}\n\ntemplate <int Layout>\nstatic void test_skewed_inner_dim_block_shape()\n{\n  typedef internal::TensorBlockDescriptor<5> TensorBlock;\n  typedef internal::TensorBlockMapper<5, Layout> TensorBlockMapper;\n\n  // Test shape 'SkewedInnerDims' with partial allocation to inner-most dim.\n  if (Layout == ColMajor) {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 10 * 1 * 1 * 1 * 1;\n    TensorBlockMapper block_mapper(\n        dims,\n        {TensorBlockShapeType::kSkewedInnerDims, max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(10, block.dimensions()[0]);\n    for (int i = 1; i < 5; ++i) {\n      VERIFY_IS_EQUAL(1, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  } else {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 1 * 1 * 1 * 1 * 6;\n    TensorBlockMapper block_mapper(\n        dims,\n        {TensorBlockShapeType::kSkewedInnerDims, max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(6, block.dimensions()[4]);\n    for (int i = 3; i >= 0; --i) {\n      VERIFY_IS_EQUAL(1, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  }\n\n  // Test shape 'SkewedInnerDims' with full allocation to inner-most dim.\n  if (Layout == ColMajor) {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 11 * 1 * 1 * 1 * 1;\n    TensorBlockMapper block_mapper(\n        dims,\n        {TensorBlockShapeType::kSkewedInnerDims, max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(11, block.dimensions()[0]);\n    for (int i = 1; i < 5; ++i) {\n      VERIFY_IS_EQUAL(1, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  } else {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 1 * 1 * 1 * 1 * 7;\n    TensorBlockMapper block_mapper(\n        dims,\n        {TensorBlockShapeType::kSkewedInnerDims, max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(7, block.dimensions()[4]);\n    for (int i = 3; i >= 0; --i) {\n      VERIFY_IS_EQUAL(1, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  }\n\n  // Test shape 'SkewedInnerDims' with full allocation to inner-most dim,\n  // and partial allocation to second inner-dim.\n  if (Layout == ColMajor) {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 11 * 3 * 1 * 1 * 1;\n    TensorBlockMapper block_mapper(\n        dims,\n        {TensorBlockShapeType::kSkewedInnerDims, max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(11, block.dimensions()[0]);\n    VERIFY_IS_EQUAL(3, block.dimensions()[1]);\n    for (int i = 2; i < 5; ++i) {\n      VERIFY_IS_EQUAL(1, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  } else {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 1 * 1 * 1 * 15 * 7;\n    TensorBlockMapper block_mapper(\n        dims,\n        {TensorBlockShapeType::kSkewedInnerDims, max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(7, block.dimensions()[4]);\n    VERIFY_IS_EQUAL(15, block.dimensions()[3]);\n    for (int i = 2; i >= 0; --i) {\n      VERIFY_IS_EQUAL(1, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  }\n\n  // Test shape 'SkewedInnerDims' with full allocation to inner-most dim,\n  // and partial allocation to third inner-dim.\n  if (Layout == ColMajor) {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 11 * 5 * 5 * 1 * 1;\n    TensorBlockMapper block_mapper(\n        dims,\n        {TensorBlockShapeType::kSkewedInnerDims, max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(11, block.dimensions()[0]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[1]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[2]);\n    for (int i = 3; i < 5; ++i) {\n      VERIFY_IS_EQUAL(1, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  } else {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 1 * 1 * 5 * 17 * 7;\n    TensorBlockMapper block_mapper(\n        dims,\n        {TensorBlockShapeType::kSkewedInnerDims, max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(7, block.dimensions()[4]);\n    VERIFY_IS_EQUAL(17, block.dimensions()[3]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[2]);\n    for (int i = 1; i >= 0; --i) {\n      VERIFY_IS_EQUAL(1, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  }\n\n  // Test shape 'SkewedInnerDims' with full allocation to all dims.\n  if (Layout == ColMajor) {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 11 * 5 * 6 * 17 * 7;\n    TensorBlockMapper block_mapper(\n        dims,\n        {TensorBlockShapeType::kSkewedInnerDims, max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(11, block.dimensions()[0]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[1]);\n    VERIFY_IS_EQUAL(6, block.dimensions()[2]);\n    VERIFY_IS_EQUAL(17, block.dimensions()[3]);\n    VERIFY_IS_EQUAL(7, block.dimensions()[4]);\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  } else {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 11 * 5 * 6 * 17 * 7;\n    TensorBlockMapper block_mapper(\n        dims,\n        {TensorBlockShapeType::kSkewedInnerDims, max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(7, block.dimensions()[4]);\n    VERIFY_IS_EQUAL(17, block.dimensions()[3]);\n    VERIFY_IS_EQUAL(6, block.dimensions()[2]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[1]);\n    VERIFY_IS_EQUAL(11, block.dimensions()[0]);\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  }\n}\n\ntemplate <int Layout>\nstatic void test_empty_dims(const internal::TensorBlockShapeType block_shape)\n{\n  // Test blocking of tensors with zero dimensions:\n  //  - we must not crash on asserts and divisions by zero\n  //  - we must not return block with zero dimensions\n  //    (recipe for overflows/underflows, divisions by zero and NaNs later)\n  //  - total block count must be zero\n  {\n    typedef internal::TensorBlockMapper<1, Layout> TensorBlockMapper;\n\n    DSizes<Index, 1> dims(0);\n    for (size_t max_coeff_count = 0; max_coeff_count < 2; ++max_coeff_count) {\n      TensorBlockMapper block_mapper(\n          dims, {block_shape, max_coeff_count, zeroCost()});\n      VERIFY_IS_EQUAL(block_mapper.blockCount(), 0);\n      VERIFY(block_mapper.blockTotalSize() >= 1);\n    }\n  }\n\n  {\n    typedef internal::TensorBlockMapper<2, Layout> TensorBlockMapper;\n\n    for (int dim1 = 0; dim1 < 3; ++dim1) {\n      for (int dim2 = 0; dim2 < 3; ++dim2) {\n        DSizes<Index, 2> dims(dim1, dim2);\n        for (size_t max_coeff_count = 0; max_coeff_count < 2; ++max_coeff_count) {\n          TensorBlockMapper block_mapper(\n              dims, {block_shape, max_coeff_count, zeroCost()});\n          if (dim1 * dim2 == 0) {\n            VERIFY_IS_EQUAL(block_mapper.blockCount(), 0);\n          }\n          VERIFY(block_mapper.blockTotalSize() >= 1);\n        }\n      }\n    }\n  }\n}\n\n#define TEST_LAYOUTS(NAME) \\\n  CALL_SUBTEST(NAME<ColMajor>()); \\\n  CALL_SUBTEST(NAME<RowMajor>())\n\n#define TEST_LAYOUTS_AND_DIMS(TYPE, NAME)    \\\n  CALL_SUBTEST((NAME<TYPE, 1, ColMajor>())); \\\n  CALL_SUBTEST((NAME<TYPE, 1, RowMajor>())); \\\n  CALL_SUBTEST((NAME<TYPE, 2, ColMajor>())); \\\n  CALL_SUBTEST((NAME<TYPE, 2, RowMajor>())); \\\n  CALL_SUBTEST((NAME<TYPE, 3, ColMajor>())); \\\n  CALL_SUBTEST((NAME<TYPE, 3, RowMajor>())); \\\n  CALL_SUBTEST((NAME<TYPE, 4, ColMajor>())); \\\n  CALL_SUBTEST((NAME<TYPE, 4, RowMajor>())); \\\n  CALL_SUBTEST((NAME<TYPE, 5, ColMajor>())); \\\n  CALL_SUBTEST((NAME<TYPE, 5, RowMajor>()))\n\n#define TEST_LAYOUTS_WITH_ARG(NAME, ARG) \\\n  CALL_SUBTEST(NAME<ColMajor>(ARG)); \\\n  CALL_SUBTEST(NAME<RowMajor>(ARG))\n\nEIGEN_DECLARE_TEST(cxx11_tensor_block_access) {\n  TEST_LAYOUTS(test_block_mapper_sanity);\n  TEST_LAYOUTS_AND_DIMS(float, test_block_mapper_maps_every_element);\n  TEST_LAYOUTS(test_uniform_block_shape);\n  TEST_LAYOUTS(test_skewed_inner_dim_block_shape);\n  TEST_LAYOUTS_WITH_ARG(test_empty_dims, TensorBlockShapeType::kUniformAllDims);\n  TEST_LAYOUTS_WITH_ARG(test_empty_dims, TensorBlockShapeType::kSkewedInnerDims);\n}\n\n#undef TEST_LAYOUTS\n#undef TEST_LAYOUTS_WITH_ARG\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_block_eval.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// clang-format off\n#include \"main.h\"\n#include <Eigen/CXX11/Tensor>\n// clang-format on\n\nusing Eigen::internal::TensorBlockDescriptor;\nusing Eigen::internal::TensorExecutor;\n\n// -------------------------------------------------------------------------- //\n// Utility functions to generate random tensors, blocks, and evaluate them.\n\ntemplate <int NumDims>\nstatic DSizes<Index, NumDims> RandomDims(Index min, Index max) {\n  DSizes<Index, NumDims> dims;\n  for (int i = 0; i < NumDims; ++i) {\n    dims[i] = internal::random<Index>(min, max);\n  }\n  return DSizes<Index, NumDims>(dims);\n}\n\n// Block offsets and extents allows to construct a TensorSlicingOp corresponding\n// to a TensorBlockDescriptor.\ntemplate <int NumDims>\nstruct TensorBlockParams {\n  DSizes<Index, NumDims> offsets;\n  DSizes<Index, NumDims> sizes;\n  TensorBlockDescriptor<NumDims, Index> desc;\n};\n\ntemplate <int Layout, int NumDims>\nstatic TensorBlockParams<NumDims> RandomBlock(DSizes<Index, NumDims> dims,\n                                              Index min, Index max) {\n  // Choose random offsets and sizes along all tensor dimensions.\n  DSizes<Index, NumDims> offsets(RandomDims<NumDims>(min, max));\n  DSizes<Index, NumDims> sizes(RandomDims<NumDims>(min, max));\n\n  // Make sure that offset + size do not overflow dims.\n  for (int i = 0; i < NumDims; ++i) {\n    offsets[i] = numext::mini(dims[i] - 1, offsets[i]);\n    sizes[i] = numext::mini(sizes[i], dims[i] - offsets[i]);\n  }\n\n  Index offset = 0;\n  DSizes<Index, NumDims> strides = Eigen::internal::strides<Layout>(dims);\n  for (int i = 0; i < NumDims; ++i) {\n    offset += strides[i] * offsets[i];\n  }\n\n  return {offsets, sizes, TensorBlockDescriptor<NumDims, Index>(offset, sizes)};\n}\n\n// Generate block with block sizes skewed towards inner dimensions. This type of\n// block is required for evaluating broadcast expressions.\ntemplate <int Layout, int NumDims>\nstatic TensorBlockParams<NumDims> SkewedInnerBlock(\n    DSizes<Index, NumDims> dims) {\n  using BlockMapper = internal::TensorBlockMapper<NumDims, Layout, Index>;\n  BlockMapper block_mapper(dims,\n                           {internal::TensorBlockShapeType::kSkewedInnerDims,\n                            internal::random<size_t>(1, dims.TotalSize()),\n                            {0, 0, 0}});\n\n  Index total_blocks = block_mapper.blockCount();\n  Index block_index = internal::random<Index>(0, total_blocks - 1);\n  auto block = block_mapper.blockDescriptor(block_index);\n  DSizes<Index, NumDims> sizes = block.dimensions();\n\n  auto strides = internal::strides<Layout>(dims);\n  DSizes<Index, NumDims> offsets;\n\n  // Compute offsets for the first block coefficient.\n  Index index = block.offset();\n  if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n    for (int i = NumDims - 1; i > 0; --i) {\n      const Index idx = index / strides[i];\n      index -= idx * strides[i];\n      offsets[i] = idx;\n    }\n    if (NumDims > 0) offsets[0] = index;\n  } else {\n    for (int i = 0; i < NumDims - 1; ++i) {\n      const Index idx = index / strides[i];\n      index -= idx * strides[i];\n      offsets[i] = idx;\n    }\n    if (NumDims > 0) offsets[NumDims - 1] = index;\n  }\n\n  return {offsets, sizes, block};\n}\n\ntemplate <int NumDims>\nstatic TensorBlockParams<NumDims> FixedSizeBlock(DSizes<Index, NumDims> dims) {\n  DSizes<Index, NumDims> offsets;\n  for (int i = 0; i < NumDims; ++i) offsets[i] = 0;\n\n  return {offsets, dims, TensorBlockDescriptor<NumDims, Index>(0, dims)};\n}\n\ninline Eigen::IndexList<Index, Eigen::type2index<1>> NByOne(Index n) {\n  Eigen::IndexList<Index, Eigen::type2index<1>> ret;\n  ret.set(0, n);\n  return ret;\n}\ninline Eigen::IndexList<Eigen::type2index<1>, Index> OneByM(Index m) {\n  Eigen::IndexList<Eigen::type2index<1>, Index> ret;\n  ret.set(1, m);\n  return ret;\n}\n\n// -------------------------------------------------------------------------- //\n// Verify that block expression evaluation produces the same result as a\n// TensorSliceOp (reading a tensor block is same to taking a tensor slice).\n\ntemplate <typename T, int NumDims, int Layout, typename Expression,\n          typename GenBlockParams>\nstatic void VerifyBlockEvaluator(Expression expr, GenBlockParams gen_block) {\n  using Device = DefaultDevice;\n  auto d = Device();\n\n  // Scratch memory allocator for block evaluation.\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n  TensorBlockScratch scratch(d);\n\n  // TensorEvaluator is needed to produce tensor blocks of the expression.\n  auto eval = TensorEvaluator<const decltype(expr), Device>(expr, d);\n  eval.evalSubExprsIfNeeded(nullptr);\n\n  // Choose a random offsets, sizes and TensorBlockDescriptor.\n  TensorBlockParams<NumDims> block_params = gen_block();\n\n  // Evaluate TensorBlock expression into a tensor.\n  Tensor<T, NumDims, Layout> block(block_params.desc.dimensions());\n\n  // Dimensions for the potential destination buffer.\n  DSizes<Index, NumDims> dst_dims;\n  if (internal::random<bool>()) {\n    dst_dims = block_params.desc.dimensions();\n  } else {\n    for (int i = 0; i < NumDims; ++i) {\n      Index extent = internal::random<Index>(0, 5);\n      dst_dims[i] = block_params.desc.dimension(i) + extent;\n    }\n  }\n\n  // Maybe use this tensor as a block desc destination.\n  Tensor<T, NumDims, Layout> dst(dst_dims);\n  dst.setZero();\n  if (internal::random<bool>()) {\n    block_params.desc.template AddDestinationBuffer<Layout>(\n        dst.data(), internal::strides<Layout>(dst.dimensions()));\n  }\n\n  const bool root_of_expr = internal::random<bool>();\n  auto tensor_block = eval.block(block_params.desc, scratch, root_of_expr);\n\n  if (tensor_block.kind() == internal::TensorBlockKind::kMaterializedInOutput) {\n    // Copy data from destination buffer.\n    if (dimensions_match(dst.dimensions(), block.dimensions())) {\n      block = dst;\n    } else {\n      DSizes<Index, NumDims> offsets;\n      for (int i = 0; i < NumDims; ++i) offsets[i] = 0;\n      block = dst.slice(offsets, block.dimensions());\n    }\n\n  } else {\n    // Assign to block from expression.\n    auto b_expr = tensor_block.expr();\n\n    // We explicitly disable vectorization and tiling, to run a simple coefficient\n    // wise assignment loop, because it's very simple and should be correct.\n    using BlockAssign = TensorAssignOp<decltype(block), const decltype(b_expr)>;\n    using BlockExecutor = TensorExecutor<const BlockAssign, Device, false,\n                                         internal::TiledEvaluation::Off>;\n    BlockExecutor::run(BlockAssign(block, b_expr), d);\n  }\n\n  // Cleanup temporary buffers owned by a tensor block.\n  tensor_block.cleanup();\n\n  // Compute a Tensor slice corresponding to a Tensor block.\n  Tensor<T, NumDims, Layout> slice(block_params.desc.dimensions());\n  auto s_expr = expr.slice(block_params.offsets, block_params.sizes);\n\n  // Explicitly use coefficient assignment to evaluate slice expression.\n  using SliceAssign = TensorAssignOp<decltype(slice), const decltype(s_expr)>;\n  using SliceExecutor = TensorExecutor<const SliceAssign, Device, false,\n                                       internal::TiledEvaluation::Off>;\n  SliceExecutor::run(SliceAssign(slice, s_expr), d);\n\n  // Tensor block and tensor slice must be the same.\n  for (Index i = 0; i < block.dimensions().TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(block.coeff(i), slice.coeff(i));\n  }\n}\n\n// -------------------------------------------------------------------------- //\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_block() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  // Identity tensor expression transformation.\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input, [&dims]() { return RandomBlock<Layout>(dims, 1, 10); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_unary_expr_block() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.abs(), [&dims]() { return RandomBlock<Layout>(dims, 1, 10); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_binary_expr_block() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> lhs(dims), rhs(dims);\n  lhs.setRandom();\n  rhs.setRandom();\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      lhs * rhs, [&dims]() { return RandomBlock<Layout>(dims, 1, 10); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_binary_with_unary_expr_block() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> lhs(dims), rhs(dims);\n  lhs.setRandom();\n  rhs.setRandom();\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      (lhs.square() + rhs.square()).sqrt(),\n      [&dims]() { return RandomBlock<Layout>(dims, 1, 10); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_broadcast() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(1, 10);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  DSizes<Index, NumDims> bcast = RandomDims<NumDims>(1, 5);\n\n  DSizes<Index, NumDims> bcasted_dims;\n  for (int i = 0; i < NumDims; ++i) bcasted_dims[i] = dims[i] * bcast[i];\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.broadcast(bcast),\n      [&bcasted_dims]() { return SkewedInnerBlock<Layout>(bcasted_dims); });\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.broadcast(bcast),\n      [&bcasted_dims]() { return RandomBlock<Layout>(bcasted_dims, 5, 10); });\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.broadcast(bcast),\n      [&bcasted_dims]() { return FixedSizeBlock(bcasted_dims); });\n\n  // Check that desc.destination() memory is not shared between two broadcast\n  // materializations.\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.broadcast(bcast) * input.abs().broadcast(bcast),\n      [&bcasted_dims]() { return SkewedInnerBlock<Layout>(bcasted_dims); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_reshape() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(1, 10);\n\n  DSizes<Index, NumDims> shuffled = dims;\n  std::shuffle(&shuffled[0], &shuffled[NumDims - 1], std::mt19937(g_seed));\n\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.reshape(shuffled),\n      [&shuffled]() { return RandomBlock<Layout>(shuffled, 1, 10); });\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.reshape(shuffled),\n      [&shuffled]() { return SkewedInnerBlock<Layout>(shuffled); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_cast() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.template cast<int>().template cast<T>(),\n      [&dims]() { return RandomBlock<Layout>(dims, 1, 10); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_select() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> lhs(dims);\n  Tensor<T, NumDims, Layout> rhs(dims);\n  Tensor<bool, NumDims, Layout> cond(dims);\n  lhs.setRandom();\n  rhs.setRandom();\n  cond.setRandom();\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(cond.select(lhs, rhs), [&dims]() {\n    return RandomBlock<Layout>(dims, 1, 20);\n  });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_padding() {\n  const int inner_dim = Layout == static_cast<int>(ColMajor) ? 0 : NumDims - 1;\n\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  DSizes<Index, NumDims> pad_before = RandomDims<NumDims>(0, 4);\n  DSizes<Index, NumDims> pad_after = RandomDims<NumDims>(0, 4);\n  array<std::pair<Index, Index>, NumDims> paddings;\n  for (int i = 0; i < NumDims; ++i) {\n    paddings[i] = std::make_pair(pad_before[i], pad_after[i]);\n  }\n\n  // Test squeezing reads from inner dim.\n  if (internal::random<bool>()) {\n    pad_before[inner_dim] = 0;\n    pad_after[inner_dim] = 0;\n    paddings[inner_dim] = std::make_pair(0, 0);\n  }\n\n  DSizes<Index, NumDims> padded_dims;\n  for (int i = 0; i < NumDims; ++i) {\n    padded_dims[i] = dims[i] + pad_before[i] + pad_after[i];\n  }\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.pad(paddings),\n      [&padded_dims]() { return FixedSizeBlock(padded_dims); });\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.pad(paddings),\n      [&padded_dims]() { return RandomBlock<Layout>(padded_dims, 1, 10); });\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.pad(paddings),\n      [&padded_dims]() { return SkewedInnerBlock<Layout>(padded_dims); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_chipping() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  Index chip_dim = internal::random<int>(0, NumDims - 1);\n  Index chip_offset = internal::random<Index>(0, dims[chip_dim] - 2);\n\n  DSizes<Index, NumDims - 1> chipped_dims;\n  for (Index i = 0; i < chip_dim; ++i) {\n    chipped_dims[i] = dims[i];\n  }\n  for (Index i = chip_dim + 1; i < NumDims; ++i) {\n    chipped_dims[i - 1] = dims[i];\n  }\n\n  // Block buffer forwarding.\n  VerifyBlockEvaluator<T, NumDims - 1, Layout>(\n      input.chip(chip_offset, chip_dim),\n      [&chipped_dims]() { return FixedSizeBlock(chipped_dims); });\n\n  VerifyBlockEvaluator<T, NumDims - 1, Layout>(\n      input.chip(chip_offset, chip_dim),\n      [&chipped_dims]() { return RandomBlock<Layout>(chipped_dims, 1, 10); });\n\n  // Block expression assignment.\n  VerifyBlockEvaluator<T, NumDims - 1, Layout>(\n      input.abs().chip(chip_offset, chip_dim),\n      [&chipped_dims]() { return FixedSizeBlock(chipped_dims); });\n\n  VerifyBlockEvaluator<T, NumDims - 1, Layout>(\n      input.abs().chip(chip_offset, chip_dim),\n      [&chipped_dims]() { return RandomBlock<Layout>(chipped_dims, 1, 10); });\n}\n\n\ntemplate<typename T, int NumDims>\nstruct SimpleTensorGenerator {\n  T operator()(const array<Index, NumDims>& coords) const {\n    T result = static_cast<T>(0);\n    for (int i = 0; i < NumDims; ++i) {\n      result += static_cast<T>((i + 1) * coords[i]);\n    }\n    return result;\n  }\n};\n\n// Boolean specialization to avoid -Wint-in-bool-context warnings on GCC.\ntemplate<int NumDims>\nstruct SimpleTensorGenerator<bool, NumDims> {\n  bool operator()(const array<Index, NumDims>& coords) const {\n    bool result = false;\n    for (int i = 0; i < NumDims; ++i) {\n      result ^= coords[i];\n    }\n    return result;\n  }\n};\n\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_generator() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  auto generator = SimpleTensorGenerator<T, NumDims>();\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.generate(generator), [&dims]() { return FixedSizeBlock(dims); });\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.generate(generator),\n      [&dims]() { return RandomBlock<Layout>(dims, 1, 10); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_reverse() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  // Randomly reverse dimensions.\n  Eigen::DSizes<bool, NumDims> reverse;\n  for (int i = 0; i < NumDims; ++i) reverse[i] = internal::random<bool>();\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.reverse(reverse), [&dims]() { return FixedSizeBlock(dims); });\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(input.reverse(reverse), [&dims]() {\n    return RandomBlock<Layout>(dims, 1, 10);\n  });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_slice() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  // Pick a random slice of an input tensor.\n  DSizes<Index, NumDims> slice_start = RandomDims<NumDims>(5, 10);\n  DSizes<Index, NumDims> slice_size = RandomDims<NumDims>(5, 10);\n\n  // Make sure that slice start + size do not overflow tensor dims.\n  for (int i = 0; i < NumDims; ++i) {\n    slice_start[i] = numext::mini(dims[i] - 1, slice_start[i]);\n    slice_size[i] = numext::mini(slice_size[i], dims[i] - slice_start[i]);\n  }\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.slice(slice_start, slice_size),\n      [&slice_size]() { return FixedSizeBlock(slice_size); });\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.slice(slice_start, slice_size),\n      [&slice_size]() { return RandomBlock<Layout>(slice_size, 1, 10); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_shuffle() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(5, 15);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  DSizes<Index, NumDims> shuffle;\n  for (int i = 0; i < NumDims; ++i) shuffle[i] = i;\n\n  do {\n    DSizes<Index, NumDims> shuffled_dims;\n    for (int i = 0; i < NumDims; ++i) shuffled_dims[i] = dims[shuffle[i]];\n\n    VerifyBlockEvaluator<T, NumDims, Layout>(\n        input.shuffle(shuffle),\n        [&shuffled_dims]() { return FixedSizeBlock(shuffled_dims); });\n\n    VerifyBlockEvaluator<T, NumDims, Layout>(\n        input.shuffle(shuffle), [&shuffled_dims]() {\n          return RandomBlock<Layout>(shuffled_dims, 1, 5);\n        });\n\n    break;\n\n  } while (std::next_permutation(&shuffle[0], &shuffle[0] + NumDims));\n}\n\ntemplate <typename T, int Layout>\nstatic void test_eval_tensor_reshape_with_bcast() {\n  Index dim = internal::random<Index>(1, 100);\n\n  Tensor<T, 2, Layout> lhs(1, dim);\n  Tensor<T, 2, Layout> rhs(dim, 1);\n  lhs.setRandom();\n  rhs.setRandom();\n\n  auto reshapeLhs = NByOne(dim);\n  auto reshapeRhs = OneByM(dim);\n\n  auto bcastLhs = OneByM(dim);\n  auto bcastRhs = NByOne(dim);\n\n  DSizes<Index, 2> dims(dim, dim);\n\n  VerifyBlockEvaluator<T, 2, Layout>(\n      lhs.reshape(reshapeLhs).broadcast(bcastLhs) *\n          rhs.reshape(reshapeRhs).broadcast(bcastRhs),\n      [dims]() { return SkewedInnerBlock<Layout, 2>(dims); });\n}\n\ntemplate <typename T, int Layout>\nstatic void test_eval_tensor_forced_eval() {\n  Index dim = internal::random<Index>(1, 100);\n\n  Tensor<T, 2, Layout> lhs(dim, 1);\n  Tensor<T, 2, Layout> rhs(1, dim);\n  lhs.setRandom();\n  rhs.setRandom();\n\n  auto bcastLhs = OneByM(dim);\n  auto bcastRhs = NByOne(dim);\n\n  DSizes<Index, 2> dims(dim, dim);\n\n  VerifyBlockEvaluator<T, 2, Layout>(\n      (lhs.broadcast(bcastLhs) * rhs.broadcast(bcastRhs)).eval().reshape(dims),\n      [dims]() { return SkewedInnerBlock<Layout, 2>(dims); });\n\n  VerifyBlockEvaluator<T, 2, Layout>(\n      (lhs.broadcast(bcastLhs) * rhs.broadcast(bcastRhs)).eval().reshape(dims),\n      [dims]() { return RandomBlock<Layout, 2>(dims, 1, 50); });\n}\n\ntemplate <typename T, int Layout>\nstatic void test_eval_tensor_chipping_of_bcast() {\n  if (Layout != static_cast<int>(RowMajor)) return;\n\n  Index dim0 = internal::random<Index>(1, 10);\n  Index dim1 = internal::random<Index>(1, 10);\n  Index dim2 = internal::random<Index>(1, 10);\n\n  Tensor<T, 3, Layout> input(1, dim1, dim2);\n  input.setRandom();\n\n  Eigen::array<Index, 3> bcast = {{dim0, 1, 1}};\n  DSizes<Index, 2> chipped_dims(dim0, dim2);\n\n  VerifyBlockEvaluator<T, 2, Layout>(\n      input.broadcast(bcast).chip(0, 1),\n      [chipped_dims]() { return FixedSizeBlock(chipped_dims); });\n\n  VerifyBlockEvaluator<T, 2, Layout>(\n      input.broadcast(bcast).chip(0, 1),\n      [chipped_dims]() { return SkewedInnerBlock<Layout, 2>(chipped_dims); });\n\n  VerifyBlockEvaluator<T, 2, Layout>(\n      input.broadcast(bcast).chip(0, 1),\n      [chipped_dims]() { return RandomBlock<Layout, 2>(chipped_dims, 1, 5); });\n}\n\n// -------------------------------------------------------------------------- //\n// Verify that assigning block to a Tensor expression produces the same result\n// as an assignment to TensorSliceOp (writing a block is is identical to\n// assigning one tensor to a slice of another tensor).\n\ntemplate <typename T, int NumDims, int Layout, int NumExprDims = NumDims,\n          typename Expression, typename GenBlockParams>\nstatic void VerifyBlockAssignment(Tensor<T, NumDims, Layout>& tensor,\n                                  Expression expr, GenBlockParams gen_block) {\n  using Device = DefaultDevice;\n  auto d = Device();\n\n  // We use tensor evaluator as a target for block and slice assignments.\n  auto eval = TensorEvaluator<decltype(expr), Device>(expr, d);\n\n  // Generate a random block, or choose a block that fits in full expression.\n  TensorBlockParams<NumExprDims> block_params = gen_block();\n\n  // Generate random data of the selected block size.\n  Tensor<T, NumExprDims, Layout> block(block_params.desc.dimensions());\n  block.setRandom();\n\n  // ************************************************************************ //\n  // (1) Assignment from a block.\n\n  // Construct a materialize block from a random generated block tensor.\n  internal::TensorMaterializedBlock<T, NumExprDims, Layout> blk(\n      internal::TensorBlockKind::kView, block.data(), block.dimensions());\n\n  // Reset all underlying tensor values to zero.\n  tensor.setZero();\n\n  // Use evaluator to write block into a tensor.\n  eval.writeBlock(block_params.desc, blk);\n\n  // Make a copy of the result after assignment.\n  Tensor<T, NumDims, Layout> block_assigned = tensor;\n\n  // ************************************************************************ //\n  // (2) Assignment to a slice\n\n  // Reset all underlying tensor values to zero.\n  tensor.setZero();\n\n  // Assign block to a slice of original expression\n  auto s_expr = expr.slice(block_params.offsets, block_params.sizes);\n\n  // Explicitly use coefficient assignment to evaluate slice expression.\n  using SliceAssign = TensorAssignOp<decltype(s_expr), const decltype(block)>;\n  using SliceExecutor = TensorExecutor<const SliceAssign, Device, false,\n                                       internal::TiledEvaluation::Off>;\n  SliceExecutor::run(SliceAssign(s_expr, block), d);\n\n  // Make a copy of the result after assignment.\n  Tensor<T, NumDims, Layout> slice_assigned = tensor;\n\n  for (Index i = 0; i < tensor.dimensions().TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(block_assigned.coeff(i), slice_assigned.coeff(i));\n  }\n}\n\n// -------------------------------------------------------------------------- //\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_assign_to_tensor() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> tensor(dims);\n\n  TensorMap<Tensor<T, NumDims, Layout>> map(tensor.data(), dims);\n\n  VerifyBlockAssignment<T, NumDims, Layout>(\n      tensor, map, [&dims]() { return RandomBlock<Layout>(dims, 10, 20); });\n  VerifyBlockAssignment<T, NumDims, Layout>(\n      tensor, map, [&dims]() { return FixedSizeBlock(dims); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_assign_to_tensor_reshape() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> tensor(dims);\n\n  TensorMap<Tensor<T, NumDims, Layout>> map(tensor.data(), dims);\n\n  DSizes<Index, NumDims> shuffled = dims;\n  std::shuffle(&shuffled[0], &shuffled[NumDims - 1], std::mt19937(g_seed));\n\n  VerifyBlockAssignment<T, NumDims, Layout>(\n      tensor, map.reshape(shuffled),\n      [&shuffled]() { return RandomBlock<Layout>(shuffled, 1, 10); });\n\n  VerifyBlockAssignment<T, NumDims, Layout>(\n      tensor, map.reshape(shuffled),\n      [&shuffled]() { return SkewedInnerBlock<Layout>(shuffled); });\n\n  VerifyBlockAssignment<T, NumDims, Layout>(\n      tensor, map.reshape(shuffled),\n      [&shuffled]() { return FixedSizeBlock(shuffled); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_assign_to_tensor_chipping() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> tensor(dims);\n\n  Index chip_dim = internal::random<int>(0, NumDims - 1);\n  Index chip_offset = internal::random<Index>(0, dims[chip_dim] - 2);\n\n  DSizes<Index, NumDims - 1> chipped_dims;\n  for (Index i = 0; i < chip_dim; ++i) {\n    chipped_dims[i] = dims[i];\n  }\n  for (Index i = chip_dim + 1; i < NumDims; ++i) {\n    chipped_dims[i - 1] = dims[i];\n  }\n\n  TensorMap<Tensor<T, NumDims, Layout>> map(tensor.data(), dims);\n\n  VerifyBlockAssignment<T, NumDims, Layout, NumDims - 1>(\n      tensor, map.chip(chip_offset, chip_dim),\n      [&chipped_dims]() { return RandomBlock<Layout>(chipped_dims, 1, 10); });\n\n  VerifyBlockAssignment<T, NumDims, Layout, NumDims - 1>(\n      tensor, map.chip(chip_offset, chip_dim),\n      [&chipped_dims]() { return SkewedInnerBlock<Layout>(chipped_dims); });\n\n  VerifyBlockAssignment<T, NumDims, Layout, NumDims - 1>(\n      tensor, map.chip(chip_offset, chip_dim),\n      [&chipped_dims]() { return FixedSizeBlock(chipped_dims); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_assign_to_tensor_slice() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> tensor(dims);\n\n  // Pick a random slice of tensor.\n  DSizes<Index, NumDims> slice_start = RandomDims<NumDims>(5, 10);\n  DSizes<Index, NumDims> slice_size = RandomDims<NumDims>(5, 10);\n\n  // Make sure that slice start + size do not overflow tensor dims.\n  for (int i = 0; i < NumDims; ++i) {\n    slice_start[i] = numext::mini(dims[i] - 1, slice_start[i]);\n    slice_size[i] = numext::mini(slice_size[i], dims[i] - slice_start[i]);\n  }\n\n  TensorMap<Tensor<T, NumDims, Layout>> map(tensor.data(), dims);\n\n  VerifyBlockAssignment<T, NumDims, Layout>(\n      tensor, map.slice(slice_start, slice_size),\n      [&slice_size]() { return RandomBlock<Layout>(slice_size, 1, 10); });\n\n  VerifyBlockAssignment<T, NumDims, Layout>(\n      tensor, map.slice(slice_start, slice_size),\n      [&slice_size]() { return SkewedInnerBlock<Layout>(slice_size); });\n\n  VerifyBlockAssignment<T, NumDims, Layout>(\n      tensor, map.slice(slice_start, slice_size),\n      [&slice_size]() { return FixedSizeBlock(slice_size); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_assign_to_tensor_shuffle() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(5, 15);\n  Tensor<T, NumDims, Layout> tensor(dims);\n\n  DSizes<Index, NumDims> shuffle;\n  for (int i = 0; i < NumDims; ++i) shuffle[i] = i;\n\n  TensorMap<Tensor<T, NumDims, Layout>> map(tensor.data(), dims);\n\n  do {\n    DSizes<Index, NumDims> shuffled_dims;\n    for (int i = 0; i < NumDims; ++i) shuffled_dims[i] = dims[shuffle[i]];\n\n    VerifyBlockAssignment<T, NumDims, Layout>(\n        tensor, map.shuffle(shuffle),\n        [&shuffled_dims]() { return FixedSizeBlock(shuffled_dims); });\n\n    VerifyBlockAssignment<T, NumDims, Layout>(\n        tensor, map.shuffle(shuffle), [&shuffled_dims]() {\n          return RandomBlock<Layout>(shuffled_dims, 1, 5);\n        });\n\n  } while (std::next_permutation(&shuffle[0], &shuffle[0] + NumDims));\n}\n\n// -------------------------------------------------------------------------- //\n\n#define CALL_SUBTEST_PART(PART) \\\n  CALL_SUBTEST_##PART\n\n#define CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(PART, NAME)           \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 1, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 2, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 3, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 4, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 5, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 1, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 2, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 4, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 4, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 5, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<int, 1, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<int, 2, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<int, 3, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<int, 4, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<int, 5, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<int, 1, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<int, 2, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<int, 4, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<int, 4, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<int, 5, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, 1, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, 2, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, 3, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, 4, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, 5, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, 1, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, 2, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, 4, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, 4, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, 5, ColMajor>()))\n\n#define CALL_SUBTESTS_DIMS_LAYOUTS(PART, NAME)     \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 1, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 2, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 3, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 4, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 5, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 1, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 2, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 4, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 4, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 5, ColMajor>()))\n\n#define CALL_SUBTESTS_LAYOUTS_TYPES(PART, NAME)       \\\n  CALL_SUBTEST_PART(PART)((NAME<float, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, ColMajor>()));  \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, ColMajor>()))\n\nEIGEN_DECLARE_TEST(cxx11_tensor_block_eval) {\n  // clang-format off\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(1, test_eval_tensor_block);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(1, test_eval_tensor_binary_expr_block);\n  CALL_SUBTESTS_DIMS_LAYOUTS(1, test_eval_tensor_unary_expr_block);\n  CALL_SUBTESTS_DIMS_LAYOUTS(2, test_eval_tensor_binary_with_unary_expr_block);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(2, test_eval_tensor_broadcast);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(2, test_eval_tensor_reshape);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(3, test_eval_tensor_cast);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(3, test_eval_tensor_select);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(3, test_eval_tensor_padding);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(4, test_eval_tensor_chipping);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(4, test_eval_tensor_generator);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(4, test_eval_tensor_reverse);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(5, test_eval_tensor_slice);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(5, test_eval_tensor_shuffle);\n\n  CALL_SUBTESTS_LAYOUTS_TYPES(6, test_eval_tensor_reshape_with_bcast);\n  CALL_SUBTESTS_LAYOUTS_TYPES(6, test_eval_tensor_forced_eval);\n  CALL_SUBTESTS_LAYOUTS_TYPES(6, test_eval_tensor_chipping_of_bcast);\n\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(7, test_assign_to_tensor);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(7, test_assign_to_tensor_reshape);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(7, test_assign_to_tensor_chipping);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(8, test_assign_to_tensor_slice);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(8, test_assign_to_tensor_shuffle);\n\n  // Force CMake to split this test.\n  // EIGEN_SUFFIXES;1;2;3;4;5;6;7;8\n\n  // clang-format on\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_block_io.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// clang-format off\n#include \"main.h\"\n#include <Eigen/CXX11/Tensor>\n// clang-format on\n\n// -------------------------------------------------------------------------- //\n// A set of tests for TensorBlockIO: copying data between tensor blocks.\n\ntemplate <int NumDims>\nstatic DSizes<Index, NumDims> RandomDims(Index min, Index max) {\n  DSizes<Index, NumDims> dims;\n  for (int i = 0; i < NumDims; ++i) {\n    dims[i] = internal::random<Index>(min, max);\n  }\n  return DSizes<Index, NumDims>(dims);\n}\n\nstatic internal::TensorBlockShapeType RandomBlockShape() {\n  return internal::random<bool>()\n         ? internal::TensorBlockShapeType::kUniformAllDims\n         : internal::TensorBlockShapeType::kSkewedInnerDims;\n}\n\ntemplate <int NumDims>\nstatic size_t RandomTargetBlockSize(const DSizes<Index, NumDims>& dims) {\n  return internal::random<size_t>(1, dims.TotalSize());\n}\n\ntemplate <int Layout, int NumDims>\nstatic Index GetInputIndex(Index output_index,\n                           const array<Index, NumDims>& output_to_input_dim_map,\n                           const array<Index, NumDims>& input_strides,\n                           const array<Index, NumDims>& output_strides) {\n  int input_index = 0;\n  if (Layout == ColMajor) {\n    for (int i = NumDims - 1; i > 0; --i) {\n      const Index idx = output_index / output_strides[i];\n      input_index += idx * input_strides[output_to_input_dim_map[i]];\n      output_index -= idx * output_strides[i];\n    }\n    return input_index +\n           output_index * input_strides[output_to_input_dim_map[0]];\n  } else {\n    for (int i = 0; i < NumDims - 1; ++i) {\n      const Index idx = output_index / output_strides[i];\n      input_index += idx * input_strides[output_to_input_dim_map[i]];\n      output_index -= idx * output_strides[i];\n    }\n    return input_index +\n           output_index * input_strides[output_to_input_dim_map[NumDims - 1]];\n  }\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_block_io_copy_data_from_source_to_target() {\n  using TensorBlockIO = internal::TensorBlockIO<T, Index, NumDims, Layout>;\n  using IODst = typename TensorBlockIO::Dst;\n  using IOSrc = typename TensorBlockIO::Src;\n\n  // Generate a random input Tensor.\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(1, 30);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  // Write data to an output Tensor.\n  Tensor<T, NumDims, Layout> output(dims);\n\n  // Construct a tensor block mapper.\n  using TensorBlockMapper =\n      internal::TensorBlockMapper<NumDims, Layout, Index>;\n  TensorBlockMapper block_mapper(\n      dims, {RandomBlockShape(), RandomTargetBlockSize(dims), {0, 0, 0}});\n\n  // We will copy data from input to output through this buffer.\n  Tensor<T, NumDims, Layout> block(block_mapper.blockDimensions());\n\n  // Precompute strides for TensorBlockIO::Copy.\n  auto input_strides = internal::strides<Layout>(dims);\n  auto output_strides = internal::strides<Layout>(dims);\n\n  const T* input_data = input.data();\n  T* output_data = output.data();\n  T* block_data = block.data();\n\n  for (int i = 0; i < block_mapper.blockCount(); ++i) {\n    auto desc = block_mapper.blockDescriptor(i);\n\n    auto blk_dims = desc.dimensions();\n    auto blk_strides = internal::strides<Layout>(blk_dims);\n\n    {\n      // Read from input into a block buffer.\n      IODst dst(blk_dims, blk_strides, block_data, 0);\n      IOSrc src(input_strides, input_data, desc.offset());\n\n      TensorBlockIO::Copy(dst, src);\n    }\n\n    {\n      // Write from block buffer to output.\n      IODst dst(blk_dims, output_strides, output_data, desc.offset());\n      IOSrc src(blk_strides, block_data, 0);\n\n      TensorBlockIO::Copy(dst, src);\n    }\n  }\n\n  for (int i = 0; i < dims.TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(input_data[i], output_data[i]);\n  }\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_block_io_copy_using_reordered_dimensions() {\n  // Generate a random input Tensor.\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(1, 30);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  // Create a random dimension re-ordering/shuffle.\n  std::vector<int> shuffle;\n\n  for (int i = 0; i < NumDims; ++i) shuffle.push_back(i);\n  std::shuffle(shuffle.begin(), shuffle.end(), std::mt19937(g_seed));\n\n  DSizes<Index, NumDims> output_tensor_dims;\n  DSizes<Index, NumDims> input_to_output_dim_map;\n  DSizes<Index, NumDims> output_to_input_dim_map;\n  for (Index i = 0; i < NumDims; ++i) {\n    output_tensor_dims[shuffle[i]] = dims[i];\n    input_to_output_dim_map[i] = shuffle[i];\n    output_to_input_dim_map[shuffle[i]] = i;\n  }\n\n  // Write data to an output Tensor.\n  Tensor<T, NumDims, Layout> output(output_tensor_dims);\n\n  // Construct a tensor block mapper.\n  // NOTE: Tensor block mapper works with shuffled dimensions.\n  using TensorBlockMapper =\n      internal::TensorBlockMapper<NumDims, Layout, Index>;\n  TensorBlockMapper block_mapper(output_tensor_dims,\n                                 {RandomBlockShape(),\n                                  RandomTargetBlockSize(output_tensor_dims),\n                                  {0, 0, 0}});\n\n  // We will copy data from input to output through this buffer.\n  Tensor<T, NumDims, Layout> block(block_mapper.blockDimensions());\n\n  // Precompute strides for TensorBlockIO::Copy.\n  auto input_strides = internal::strides<Layout>(dims);\n  auto output_strides = internal::strides<Layout>(output_tensor_dims);\n\n  const T* input_data = input.data();\n  T* output_data = output.data();\n  T* block_data = block.data();\n\n  for (Index i = 0; i < block_mapper.blockCount(); ++i) {\n    auto desc = block_mapper.blockDescriptor(i);\n\n    const Index first_coeff_index = GetInputIndex<Layout, NumDims>(\n        desc.offset(), output_to_input_dim_map, input_strides,\n        output_strides);\n\n    // NOTE: Block dimensions are in the same order as output dimensions.\n\n    using TensorBlockIO = internal::TensorBlockIO<T, Index, NumDims, Layout>;\n    using IODst = typename TensorBlockIO::Dst;\n    using IOSrc = typename TensorBlockIO::Src;\n\n    auto blk_dims = desc.dimensions();\n    auto blk_strides = internal::strides<Layout>(blk_dims);\n\n    {\n      // Read from input into a block buffer.\n      IODst dst(blk_dims, blk_strides, block_data, 0);\n      IOSrc src(input_strides, input_data, first_coeff_index);\n\n      // TODO(ezhulenev): Remove when fully switched to TensorBlock.\n      DSizes<int, NumDims> dim_map;\n      for (int j = 0; j < NumDims; ++j)\n        dim_map[j] = static_cast<int>(output_to_input_dim_map[j]);\n      TensorBlockIO::Copy(dst, src, /*dst_to_src_dim_map=*/dim_map);\n    }\n\n    {\n      // We need to convert block dimensions from output to input order.\n      auto dst_dims = blk_dims;\n      for (int out_dim = 0; out_dim < NumDims; ++out_dim) {\n        dst_dims[output_to_input_dim_map[out_dim]] = blk_dims[out_dim];\n      }\n\n      // Write from block buffer to output.\n      IODst dst(dst_dims, input_strides, output_data, first_coeff_index);\n      IOSrc src(blk_strides, block_data, 0);\n\n      // TODO(ezhulenev): Remove when fully switched to TensorBlock.\n      DSizes<int, NumDims> dim_map;\n      for (int j = 0; j < NumDims; ++j)\n        dim_map[j] = static_cast<int>(input_to_output_dim_map[j]);\n      TensorBlockIO::Copy(dst, src, /*dst_to_src_dim_map=*/dim_map);\n    }\n  }\n\n  for (Index i = 0; i < dims.TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(input_data[i], output_data[i]);\n  }\n}\n\n// This is the special case for reading data with reordering, when dimensions\n// before/after reordering are the same. Squeezing reads along inner dimensions\n// in this case is illegal, because we reorder innermost dimension.\ntemplate <int Layout>\nstatic void test_block_io_copy_using_reordered_dimensions_do_not_squeeze() {\n  DSizes<Index, 3> tensor_dims(7, 9, 7);\n  DSizes<Index, 3> block_dims = tensor_dims;\n\n  DSizes<int, 3> block_to_tensor_dim;\n  block_to_tensor_dim[0] = 2;\n  block_to_tensor_dim[1] = 1;\n  block_to_tensor_dim[2] = 0;\n\n  auto tensor_strides = internal::strides<Layout>(tensor_dims);\n  auto block_strides = internal::strides<Layout>(block_dims);\n\n  Tensor<float, 3, Layout> block(block_dims);\n  Tensor<float, 3, Layout> tensor(tensor_dims);\n  tensor.setRandom();\n\n  float* tensor_data = tensor.data();\n  float* block_data = block.data();\n\n  using TensorBlockIO = internal::TensorBlockIO<float, Index, 3, Layout>;\n  using IODst = typename TensorBlockIO::Dst;\n  using IOSrc = typename TensorBlockIO::Src;\n\n  // Read from a tensor into a block.\n  IODst dst(block_dims, block_strides, block_data, 0);\n  IOSrc src(tensor_strides, tensor_data, 0);\n\n  TensorBlockIO::Copy(dst, src, /*dst_to_src_dim_map=*/block_to_tensor_dim);\n\n  TensorMap<Tensor<float, 3, Layout> > block_tensor(block_data, block_dims);\n  TensorMap<Tensor<float, 3, Layout> > tensor_tensor(tensor_data, tensor_dims);\n\n  for (Index d0 = 0; d0 < tensor_dims[0]; ++d0) {\n    for (Index d1 = 0; d1 < tensor_dims[1]; ++d1) {\n      for (Index d2 = 0; d2 < tensor_dims[2]; ++d2) {\n        float block_value = block_tensor(d2, d1, d0);\n        float tensor_value = tensor_tensor(d0, d1, d2);\n        VERIFY_IS_EQUAL(block_value, tensor_value);\n      }\n    }\n  }\n}\n\n// This is the special case for reading data with reordering, when dimensions\n// before/after reordering are the same. Squeezing reads in this case is allowed\n// because we reorder outer dimensions.\ntemplate <int Layout>\nstatic void test_block_io_copy_using_reordered_dimensions_squeeze() {\n  DSizes<Index, 4> tensor_dims(7, 5, 9, 9);\n  DSizes<Index, 4> block_dims = tensor_dims;\n\n  DSizes<int, 4> block_to_tensor_dim;\n  block_to_tensor_dim[0] = 0;\n  block_to_tensor_dim[1] = 1;\n  block_to_tensor_dim[2] = 3;\n  block_to_tensor_dim[3] = 2;\n\n  auto tensor_strides = internal::strides<Layout>(tensor_dims);\n  auto block_strides = internal::strides<Layout>(block_dims);\n\n  Tensor<float, 4, Layout> block(block_dims);\n  Tensor<float, 4, Layout> tensor(tensor_dims);\n  tensor.setRandom();\n\n  float* tensor_data = tensor.data();\n  float* block_data = block.data();\n\n  using TensorBlockIO = internal::TensorBlockIO<float, Index, 4, Layout>;\n  using IODst = typename TensorBlockIO::Dst;\n  using IOSrc = typename TensorBlockIO::Src;\n\n  // Read from a tensor into a block.\n  IODst dst(block_dims, block_strides, block_data, 0);\n  IOSrc src(tensor_strides, tensor_data, 0);\n\n  TensorBlockIO::Copy(dst, src, /*dst_to_src_dim_map=*/block_to_tensor_dim);\n\n  TensorMap<Tensor<float, 4, Layout> > block_tensor(block_data, block_dims);\n  TensorMap<Tensor<float, 4, Layout> > tensor_tensor(tensor_data, tensor_dims);\n\n  for (Index d0 = 0; d0 < tensor_dims[0]; ++d0) {\n    for (Index d1 = 0; d1 < tensor_dims[1]; ++d1) {\n      for (Index d2 = 0; d2 < tensor_dims[2]; ++d2) {\n        for (Index d3 = 0; d3 < tensor_dims[3]; ++d3) {\n          float block_value = block_tensor(d0, d1, d3, d2);\n          float tensor_value = tensor_tensor(d0, d1, d2, d3);\n          VERIFY_IS_EQUAL(block_value, tensor_value);\n        }\n      }\n    }\n  }\n}\n\ntemplate <int Layout>\nstatic void test_block_io_zero_stride() {\n  DSizes<Index, 5> rnd_dims = RandomDims<5>(1, 30);\n\n  DSizes<Index, 5> input_tensor_dims = rnd_dims;\n  input_tensor_dims[0] = 1;\n  input_tensor_dims[2] = 1;\n  input_tensor_dims[4] = 1;\n\n  Tensor<float, 5, Layout> input(input_tensor_dims);\n  input.setRandom();\n\n  DSizes<Index, 5> output_tensor_dims = rnd_dims;\n\n  auto input_tensor_strides = internal::strides<Layout>(input_tensor_dims);\n  auto output_tensor_strides = internal::strides<Layout>(output_tensor_dims);\n\n  auto input_tensor_strides_with_zeros = input_tensor_strides;\n  input_tensor_strides_with_zeros[0] = 0;\n  input_tensor_strides_with_zeros[2] = 0;\n  input_tensor_strides_with_zeros[4] = 0;\n\n  Tensor<float, 5, Layout> output(output_tensor_dims);\n  output.setRandom();\n\n  using TensorBlockIO = internal::TensorBlockIO<float, Index, 5, Layout>;\n  using IODst = typename TensorBlockIO::Dst;\n  using IOSrc = typename TensorBlockIO::Src;\n\n  // Write data from input to output with broadcasting in dims [0, 2, 4].\n  IODst dst(output_tensor_dims, output_tensor_strides, output.data(), 0);\n  IOSrc src(input_tensor_strides_with_zeros, input.data(), 0);\n  TensorBlockIO::Copy(dst, src);\n\n  for (int i = 0; i < output_tensor_dims[0]; ++i) {\n    for (int j = 0; j < output_tensor_dims[1]; ++j) {\n      for (int k = 0; k < output_tensor_dims[2]; ++k) {\n        for (int l = 0; l < output_tensor_dims[3]; ++l) {\n          for (int m = 0; m < output_tensor_dims[4]; ++m) {\n            float input_value = input(0, j, 0, l, 0);\n            float output_value = output(i, j, k, l, m);\n            VERIFY_IS_EQUAL(input_value, output_value);\n          }\n        }\n      }\n    }\n  }\n}\n\ntemplate <int Layout>\nstatic void test_block_io_squeeze_ones() {\n  using TensorBlockIO = internal::TensorBlockIO<float, Index, 5, Layout>;\n  using IODst = typename TensorBlockIO::Dst;\n  using IOSrc = typename TensorBlockIO::Src;\n\n  // Total size > 1.\n  {\n    DSizes<Index, 5> block_sizes(1, 2, 1, 2, 1);\n    auto strides = internal::strides<Layout>(block_sizes);\n\n    // Create a random input tensor.\n    Tensor<float, 5> input(block_sizes);\n    input.setRandom();\n\n    Tensor<float, 5> output(block_sizes);\n\n    IODst dst(block_sizes, strides, output.data(), 0);\n    IOSrc src(strides, input.data());\n    TensorBlockIO::Copy(dst, src);\n\n    for (Index i = 0; i < block_sizes.TotalSize(); ++i) {\n      VERIFY_IS_EQUAL(output.data()[i], input.data()[i]);\n    }\n  }\n\n  // Total size == 1.\n  {\n    DSizes<Index, 5> block_sizes(1, 1, 1, 1, 1);\n    auto strides = internal::strides<Layout>(block_sizes);\n\n    // Create a random input tensor.\n    Tensor<float, 5> input(block_sizes);\n    input.setRandom();\n\n    Tensor<float, 5> output(block_sizes);\n\n    IODst dst(block_sizes, strides, output.data(), 0);\n    IOSrc src(strides, input.data());\n    TensorBlockIO::Copy(dst, src);\n\n    for (Index i = 0; i < block_sizes.TotalSize(); ++i) {\n      VERIFY_IS_EQUAL(output.data()[i], input.data()[i]);\n    }\n  }\n}\n\n#define CALL_SUBTESTS(NAME)                   \\\n  CALL_SUBTEST((NAME<float, 1, RowMajor>())); \\\n  CALL_SUBTEST((NAME<float, 2, RowMajor>())); \\\n  CALL_SUBTEST((NAME<float, 4, RowMajor>())); \\\n  CALL_SUBTEST((NAME<float, 5, RowMajor>())); \\\n  CALL_SUBTEST((NAME<float, 1, ColMajor>())); \\\n  CALL_SUBTEST((NAME<float, 2, ColMajor>())); \\\n  CALL_SUBTEST((NAME<float, 4, ColMajor>())); \\\n  CALL_SUBTEST((NAME<float, 5, ColMajor>())); \\\n  CALL_SUBTEST((NAME<bool, 1, RowMajor>())); \\\n  CALL_SUBTEST((NAME<bool, 2, RowMajor>())); \\\n  CALL_SUBTEST((NAME<bool, 4, RowMajor>())); \\\n  CALL_SUBTEST((NAME<bool, 5, RowMajor>())); \\\n  CALL_SUBTEST((NAME<bool, 1, ColMajor>())); \\\n  CALL_SUBTEST((NAME<bool, 2, ColMajor>())); \\\n  CALL_SUBTEST((NAME<bool, 4, ColMajor>())); \\\n  CALL_SUBTEST((NAME<bool, 5, ColMajor>()))\n\nEIGEN_DECLARE_TEST(cxx11_tensor_block_io) {\n  // clang-format off\n  CALL_SUBTESTS(test_block_io_copy_data_from_source_to_target);\n  CALL_SUBTESTS(test_block_io_copy_using_reordered_dimensions);\n\n  CALL_SUBTEST(test_block_io_copy_using_reordered_dimensions_do_not_squeeze<RowMajor>());\n  CALL_SUBTEST(test_block_io_copy_using_reordered_dimensions_do_not_squeeze<ColMajor>());\n\n  CALL_SUBTEST(test_block_io_copy_using_reordered_dimensions_squeeze<RowMajor>());\n  CALL_SUBTEST(test_block_io_copy_using_reordered_dimensions_squeeze<ColMajor>());\n\n  CALL_SUBTEST(test_block_io_zero_stride<RowMajor>());\n  CALL_SUBTEST(test_block_io_zero_stride<ColMajor>());\n\n  CALL_SUBTEST(test_block_io_squeeze_ones<RowMajor>());\n  CALL_SUBTEST(test_block_io_squeeze_ones<ColMajor>());\n  // clang-format on\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_broadcast_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_broadcast_sycl_fixed(const Eigen::SyclDevice &sycl_device){\n\n  // BROADCAST test:\n  IndexType inDim1=2;\n  IndexType inDim2=3;\n  IndexType inDim3=5;\n  IndexType inDim4=7;\n  IndexType bDim1=2;\n  IndexType bDim2=3;\n  IndexType bDim3=1;\n  IndexType bDim4=4;\n  array<IndexType, 4> in_range   = {{inDim1, inDim2, inDim3, inDim4}};\n  array<IndexType, 4> broadcasts = {{bDim1, bDim2, bDim3, bDim4}};\n  array<IndexType, 4> out_range;  // = in_range * broadcasts\n  for (size_t i = 0; i < out_range.size(); ++i)\n    out_range[i] = in_range[i] * broadcasts[i];\n\n  Tensor<DataType, 4, DataLayout, IndexType>  input(in_range);\n  Tensor<DataType, 4, DataLayout, IndexType> out(out_range);\n\n  for (size_t i = 0; i < in_range.size(); ++i)\n    VERIFY_IS_EQUAL(out.dimension(i), out_range[i]);\n\n\n  for (IndexType i = 0; i < input.size(); ++i)\n    input(i) = static_cast<DataType>(i);\n\n  DataType * gpu_in_data  = static_cast<DataType*>(sycl_device.allocate(input.dimensions().TotalSize()*sizeof(DataType)));\n  DataType * gpu_out_data  = static_cast<DataType*>(sycl_device.allocate(out.dimensions().TotalSize()*sizeof(DataType)));\n\n  TensorMap<TensorFixedSize<DataType, Sizes<2, 3, 5, 7>, DataLayout, IndexType>> gpu_in(gpu_in_data, in_range);\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType>> gpu_out(gpu_out_data, out_range);\n  sycl_device.memcpyHostToDevice(gpu_in_data, input.data(),(input.dimensions().TotalSize())*sizeof(DataType));\n  gpu_out.device(sycl_device) = gpu_in.broadcast(broadcasts);\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data,(out.dimensions().TotalSize())*sizeof(DataType));\n\n  for (IndexType i = 0; i < inDim1*bDim1; ++i) {\n    for (IndexType j = 0; j < inDim2*bDim2; ++j) {\n      for (IndexType k = 0; k < inDim3*bDim3; ++k) {\n        for (IndexType l = 0; l < inDim4*bDim4; ++l) {\n          VERIFY_IS_APPROX(input(i%2,j%3,k%5,l%7), out(i,j,k,l));\n        }\n      }\n    }\n  }\n  printf(\"Broadcast Test with fixed size Passed\\n\");\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_broadcast_sycl(const Eigen::SyclDevice &sycl_device){\n\n  // BROADCAST test:\n  IndexType inDim1=2;\n  IndexType inDim2=3;\n  IndexType inDim3=5;\n  IndexType inDim4=7;\n  IndexType bDim1=2;\n  IndexType bDim2=3;\n  IndexType bDim3=1;\n  IndexType bDim4=4;\n  array<IndexType, 4> in_range   = {{inDim1, inDim2, inDim3, inDim4}};\n  array<IndexType, 4> broadcasts = {{bDim1, bDim2, bDim3, bDim4}};\n  array<IndexType, 4> out_range;  // = in_range * broadcasts\n  for (size_t i = 0; i < out_range.size(); ++i)\n    out_range[i] = in_range[i] * broadcasts[i];\n\n  Tensor<DataType, 4, DataLayout, IndexType>  input(in_range);\n  Tensor<DataType, 4, DataLayout, IndexType> out(out_range);\n\n  for (size_t i = 0; i < in_range.size(); ++i)\n    VERIFY_IS_EQUAL(out.dimension(i), out_range[i]);\n\n\n  for (IndexType i = 0; i < input.size(); ++i)\n    input(i) = static_cast<DataType>(i);\n\n  DataType * gpu_in_data  = static_cast<DataType*>(sycl_device.allocate(input.dimensions().TotalSize()*sizeof(DataType)));\n  DataType * gpu_out_data  = static_cast<DataType*>(sycl_device.allocate(out.dimensions().TotalSize()*sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType>>  gpu_in(gpu_in_data, in_range);\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType>> gpu_out(gpu_out_data, out_range);\n  sycl_device.memcpyHostToDevice(gpu_in_data, input.data(),(input.dimensions().TotalSize())*sizeof(DataType));\n  gpu_out.device(sycl_device) = gpu_in.broadcast(broadcasts);\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data,(out.dimensions().TotalSize())*sizeof(DataType));\n\n  for (IndexType i = 0; i < inDim1*bDim1; ++i) {\n    for (IndexType j = 0; j < inDim2*bDim2; ++j) {\n      for (IndexType k = 0; k < inDim3*bDim3; ++k) {\n        for (IndexType l = 0; l < inDim4*bDim4; ++l) {\n          VERIFY_IS_APPROX(input(i%inDim1,j%inDim2,k%inDim3,l%inDim4), out(i,j,k,l));\n        }\n      }\n    }\n  }\n  printf(\"Broadcast Test Passed\\n\");\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate<typename DataType> void sycl_broadcast_test_per_device(const cl::sycl::device& d){\n  std::cout << \"Running on \" << d.template get_info<cl::sycl::info::device::name>() << std::endl;\n  QueueInterface queueInterface(d);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_broadcast_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_broadcast_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_broadcast_sycl_fixed<DataType, RowMajor, int64_t>(sycl_device);\n  test_broadcast_sycl_fixed<DataType, ColMajor, int64_t>(sycl_device);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_broadcast_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_broadcast_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_broadcasting.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate <int DataLayout>\nstatic void test_simple_broadcasting()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> broadcasts;\n  broadcasts[0] = 1;\n  broadcasts[1] = 1;\n  broadcasts[2] = 1;\n  broadcasts[3] = 1;\n\n  Tensor<float, 4, DataLayout> no_broadcast;\n  no_broadcast = tensor.broadcast(broadcasts);\n\n  VERIFY_IS_EQUAL(no_broadcast.dimension(0), 2);\n  VERIFY_IS_EQUAL(no_broadcast.dimension(1), 3);\n  VERIFY_IS_EQUAL(no_broadcast.dimension(2), 5);\n  VERIFY_IS_EQUAL(no_broadcast.dimension(3), 7);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), no_broadcast(i,j,k,l));\n        }\n      }\n    }\n  }\n\n  broadcasts[0] = 2;\n  broadcasts[1] = 3;\n  broadcasts[2] = 1;\n  broadcasts[3] = 4;\n  Tensor<float, 4, DataLayout> broadcast;\n  broadcast = tensor.broadcast(broadcasts);\n\n  VERIFY_IS_EQUAL(broadcast.dimension(0), 4);\n  VERIFY_IS_EQUAL(broadcast.dimension(1), 9);\n  VERIFY_IS_EQUAL(broadcast.dimension(2), 5);\n  VERIFY_IS_EQUAL(broadcast.dimension(3), 28);\n\n  for (int i = 0; i < 4; ++i) {\n    for (int j = 0; j < 9; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 28; ++l) {\n          VERIFY_IS_EQUAL(tensor(i%2,j%3,k%5,l%7), broadcast(i,j,k,l));\n        }\n      }\n    }\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_vectorized_broadcasting()\n{\n  Tensor<float, 3, DataLayout> tensor(8,3,5);\n  tensor.setRandom();\n  array<ptrdiff_t, 3> broadcasts;\n  broadcasts[0] = 2;\n  broadcasts[1] = 3;\n  broadcasts[2] = 4;\n\n  Tensor<float, 3, DataLayout> broadcast;\n  broadcast = tensor.broadcast(broadcasts);\n\n  VERIFY_IS_EQUAL(broadcast.dimension(0), 16);\n  VERIFY_IS_EQUAL(broadcast.dimension(1), 9);\n  VERIFY_IS_EQUAL(broadcast.dimension(2), 20);\n\n  for (int i = 0; i < 16; ++i) {\n    for (int j = 0; j < 9; ++j) {\n      for (int k = 0; k < 20; ++k) {\n        VERIFY_IS_EQUAL(tensor(i%8,j%3,k%5), broadcast(i,j,k));\n      }\n    }\n  }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  tensor.resize(11,3,5);\n#else\n  array<Index, 3> new_dims;\n  new_dims[0] = 11;\n  new_dims[1] = 3;\n  new_dims[2] = 5;\n  tensor.resize(new_dims);\n#endif\n\n  tensor.setRandom();\n  broadcast = tensor.broadcast(broadcasts);\n\n  VERIFY_IS_EQUAL(broadcast.dimension(0), 22);\n  VERIFY_IS_EQUAL(broadcast.dimension(1), 9);\n  VERIFY_IS_EQUAL(broadcast.dimension(2), 20);\n\n  for (int i = 0; i < 22; ++i) {\n    for (int j = 0; j < 9; ++j) {\n      for (int k = 0; k < 20; ++k) {\n        VERIFY_IS_EQUAL(tensor(i%11,j%3,k%5), broadcast(i,j,k));\n      }\n    }\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_static_broadcasting()\n{\n  Tensor<float, 3, DataLayout> tensor(8,3,5);\n  tensor.setRandom();\n\n#if defined(EIGEN_HAS_INDEX_LIST)\n  Eigen::IndexList<Eigen::type2index<2>, Eigen::type2index<3>, Eigen::type2index<4>> broadcasts;\n#else\n  Eigen::array<int, 3> broadcasts;\n  broadcasts[0] = 2;\n  broadcasts[1] = 3;\n  broadcasts[2] = 4;\n#endif\n\n  Tensor<float, 3, DataLayout> broadcast;\n  broadcast = tensor.broadcast(broadcasts);\n\n  VERIFY_IS_EQUAL(broadcast.dimension(0), 16);\n  VERIFY_IS_EQUAL(broadcast.dimension(1), 9);\n  VERIFY_IS_EQUAL(broadcast.dimension(2), 20);\n\n  for (int i = 0; i < 16; ++i) {\n    for (int j = 0; j < 9; ++j) {\n      for (int k = 0; k < 20; ++k) {\n        VERIFY_IS_EQUAL(tensor(i%8,j%3,k%5), broadcast(i,j,k));\n      }\n    }\n  }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  tensor.resize(11,3,5);\n#else\n  array<Index, 3> new_dims;\n  new_dims[0] = 11;\n  new_dims[1] = 3;\n  new_dims[2] = 5;\n  tensor.resize(new_dims);\n#endif\n\n  tensor.setRandom();\n  broadcast = tensor.broadcast(broadcasts);\n\n  VERIFY_IS_EQUAL(broadcast.dimension(0), 22);\n  VERIFY_IS_EQUAL(broadcast.dimension(1), 9);\n  VERIFY_IS_EQUAL(broadcast.dimension(2), 20);\n\n  for (int i = 0; i < 22; ++i) {\n    for (int j = 0; j < 9; ++j) {\n      for (int k = 0; k < 20; ++k) {\n        VERIFY_IS_EQUAL(tensor(i%11,j%3,k%5), broadcast(i,j,k));\n      }\n    }\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_fixed_size_broadcasting()\n{\n  // Need to add a [] operator to the Size class for this to work\n#if 0\n  Tensor<float, 1, DataLayout> t1(10);\n  t1.setRandom();\n  TensorFixedSize<float, Sizes<1>, DataLayout> t2;\n  t2 = t2.constant(20.0f);\n\n  Tensor<float, 1, DataLayout> t3 = t1 + t2.broadcast(Eigen::array<int, 1>{{10}});\n  for (int i = 0; i < 10; ++i) {\n    VERIFY_IS_APPROX(t3(i), t1(i) + t2(0));\n  }\n\n  TensorMap<TensorFixedSize<float, Sizes<1>, DataLayout> > t4(t2.data(), {{1}});\n  Tensor<float, 1, DataLayout> t5 = t1 + t4.broadcast(Eigen::array<int, 1>{{10}});\n  for (int i = 0; i < 10; ++i) {\n    VERIFY_IS_APPROX(t5(i), t1(i) + t2(0));\n  }\n#endif\n}\n\ntemplate <int DataLayout>\nstatic void test_simple_broadcasting_one_by_n()\n{\n  Tensor<float, 4, DataLayout> tensor(1,13,5,7);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> broadcasts;\n  broadcasts[0] = 9;\n  broadcasts[1] = 1;\n  broadcasts[2] = 1;\n  broadcasts[3] = 1;\n  Tensor<float, 4, DataLayout> broadcast;\n  broadcast = tensor.broadcast(broadcasts);\n\n  VERIFY_IS_EQUAL(broadcast.dimension(0), 9);\n  VERIFY_IS_EQUAL(broadcast.dimension(1), 13);\n  VERIFY_IS_EQUAL(broadcast.dimension(2), 5);\n  VERIFY_IS_EQUAL(broadcast.dimension(3), 7);\n\n  for (int i = 0; i < 9; ++i) {\n    for (int j = 0; j < 13; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i%1,j%13,k%5,l%7), broadcast(i,j,k,l));\n        }\n      }\n    }\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_simple_broadcasting_n_by_one()\n{\n  Tensor<float, 4, DataLayout> tensor(7,3,5,1);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> broadcasts;\n  broadcasts[0] = 1;\n  broadcasts[1] = 1;\n  broadcasts[2] = 1;\n  broadcasts[3] = 19;\n  Tensor<float, 4, DataLayout> broadcast;\n  broadcast = tensor.broadcast(broadcasts);\n\n  VERIFY_IS_EQUAL(broadcast.dimension(0), 7);\n  VERIFY_IS_EQUAL(broadcast.dimension(1), 3);\n  VERIFY_IS_EQUAL(broadcast.dimension(2), 5);\n  VERIFY_IS_EQUAL(broadcast.dimension(3), 19);\n\n  for (int i = 0; i < 7; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 19; ++l) {\n          VERIFY_IS_EQUAL(tensor(i%7,j%3,k%5,l%1), broadcast(i,j,k,l));\n        }\n      }\n    }\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_simple_broadcasting_one_by_n_by_one_1d()\n{\n  Tensor<float, 3, DataLayout> tensor(1,7,1);\n  tensor.setRandom();\n  array<ptrdiff_t, 3> broadcasts;\n  broadcasts[0] = 5;\n  broadcasts[1] = 1;\n  broadcasts[2] = 13;\n  Tensor<float, 3, DataLayout> broadcasted;\n  broadcasted = tensor.broadcast(broadcasts);\n\n  VERIFY_IS_EQUAL(broadcasted.dimension(0), 5);\n  VERIFY_IS_EQUAL(broadcasted.dimension(1), 7);\n  VERIFY_IS_EQUAL(broadcasted.dimension(2), 13);\n\n  for (int i = 0; i < 5; ++i) {\n    for (int j = 0; j < 7; ++j) {\n      for (int k = 0; k < 13; ++k) {\n        VERIFY_IS_EQUAL(tensor(0,j%7,0), broadcasted(i,j,k));\n      }\n    }\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_simple_broadcasting_one_by_n_by_one_2d()\n{\n  Tensor<float, 4, DataLayout> tensor(1,7,13,1);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> broadcasts;\n  broadcasts[0] = 5;\n  broadcasts[1] = 1;\n  broadcasts[2] = 1;\n  broadcasts[3] = 19;\n  Tensor<float, 4, DataLayout> broadcast;\n  broadcast = tensor.broadcast(broadcasts);\n\n  VERIFY_IS_EQUAL(broadcast.dimension(0), 5);\n  VERIFY_IS_EQUAL(broadcast.dimension(1), 7);\n  VERIFY_IS_EQUAL(broadcast.dimension(2), 13);\n  VERIFY_IS_EQUAL(broadcast.dimension(3), 19);\n\n  for (int i = 0; i < 5; ++i) {\n    for (int j = 0; j < 7; ++j) {\n      for (int k = 0; k < 13; ++k) {\n        for (int l = 0; l < 19; ++l) {\n          VERIFY_IS_EQUAL(tensor(0,j%7,k%13,0), broadcast(i,j,k,l));\n        }\n      }\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_broadcasting)\n{\n  CALL_SUBTEST(test_simple_broadcasting<ColMajor>());\n  CALL_SUBTEST(test_simple_broadcasting<RowMajor>());\n  CALL_SUBTEST(test_vectorized_broadcasting<ColMajor>());\n  CALL_SUBTEST(test_vectorized_broadcasting<RowMajor>());\n  CALL_SUBTEST(test_static_broadcasting<ColMajor>());\n  CALL_SUBTEST(test_static_broadcasting<RowMajor>());\n  CALL_SUBTEST(test_fixed_size_broadcasting<ColMajor>());\n  CALL_SUBTEST(test_fixed_size_broadcasting<RowMajor>());\n  CALL_SUBTEST(test_simple_broadcasting_one_by_n<RowMajor>());\n  CALL_SUBTEST(test_simple_broadcasting_n_by_one<RowMajor>());\n  CALL_SUBTEST(test_simple_broadcasting_one_by_n<ColMajor>());\n  CALL_SUBTEST(test_simple_broadcasting_n_by_one<ColMajor>());\n  CALL_SUBTEST(test_simple_broadcasting_one_by_n_by_one_1d<ColMajor>());\n  CALL_SUBTEST(test_simple_broadcasting_one_by_n_by_one_2d<ColMajor>());\n  CALL_SUBTEST(test_simple_broadcasting_one_by_n_by_one_1d<RowMajor>());\n  CALL_SUBTEST(test_simple_broadcasting_one_by_n_by_one_2d<RowMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_builtins_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\n// Functions used to compare the TensorMap implementation on the device with\n// the equivalent on the host\nnamespace cl {\nnamespace sycl {\ntemplate <typename T> T abs(T x) { return cl::sycl::fabs(x); }\ntemplate <typename T> T square(T x) { return x * x; }\ntemplate <typename T> T cube(T x) { return x * x * x; }\ntemplate <typename T> T inverse(T x) { return T(1) / x; }\ntemplate <typename T> T cwiseMax(T x, T y) { return cl::sycl::max(x, y); }\ntemplate <typename T> T cwiseMin(T x, T y) { return cl::sycl::min(x, y); }\n}\n}\n\nstruct EqualAssignement {\n  template <typename Lhs, typename Rhs>\n  void operator()(Lhs& lhs, const Rhs& rhs) { lhs = rhs; }\n};\n\nstruct PlusEqualAssignement {\n  template <typename Lhs, typename Rhs>\n  void operator()(Lhs& lhs, const Rhs& rhs) { lhs += rhs; }\n};\n\ntemplate <typename DataType, int DataLayout,\n          typename Assignement, typename Operator>\nvoid test_unary_builtins_for_scalar(const Eigen::SyclDevice& sycl_device,\n                                    const array<int64_t, 3>& tensor_range) {\n  Operator op;\n  Assignement asgn;\n  {\n    /* Assignement(out, Operator(in)) */\n    Tensor<DataType, 3, DataLayout, int64_t> in(tensor_range);\n    Tensor<DataType, 3, DataLayout, int64_t> out(tensor_range);\n    in = in.random() + DataType(0.01);\n    out = out.random() + DataType(0.01);\n    Tensor<DataType, 3, DataLayout, int64_t> reference(out);\n    DataType *gpu_data = static_cast<DataType *>(\n        sycl_device.allocate(in.size() * sizeof(DataType)));\n    DataType *gpu_data_out = static_cast<DataType *>(\n        sycl_device.allocate(out.size() * sizeof(DataType)));\n    TensorMap<Tensor<DataType, 3, DataLayout, int64_t>> gpu(gpu_data, tensor_range);\n    TensorMap<Tensor<DataType, 3, DataLayout, int64_t>> gpu_out(gpu_data_out, tensor_range);\n    sycl_device.memcpyHostToDevice(gpu_data, in.data(),\n                                   (in.size()) * sizeof(DataType));\n    sycl_device.memcpyHostToDevice(gpu_data_out, out.data(),\n                                   (out.size()) * sizeof(DataType));\n    auto device_expr = gpu_out.device(sycl_device);\n    asgn(device_expr, op(gpu));\n    sycl_device.memcpyDeviceToHost(out.data(), gpu_data_out,\n                                   (out.size()) * sizeof(DataType));\n    for (int64_t i = 0; i < out.size(); ++i) {\n      DataType ver = reference(i);\n      asgn(ver, op(in(i)));\n      VERIFY_IS_APPROX(out(i), ver);\n    }\n    sycl_device.deallocate(gpu_data);\n    sycl_device.deallocate(gpu_data_out);\n  }\n  {\n    /* Assignement(out, Operator(out)) */\n    Tensor<DataType, 3, DataLayout, int64_t> out(tensor_range);\n    out = out.random() + DataType(0.01);\n    Tensor<DataType, 3, DataLayout, int64_t> reference(out);\n    DataType *gpu_data_out = static_cast<DataType *>(\n        sycl_device.allocate(out.size() * sizeof(DataType)));\n    TensorMap<Tensor<DataType, 3, DataLayout, int64_t>> gpu_out(gpu_data_out, tensor_range);\n    sycl_device.memcpyHostToDevice(gpu_data_out, out.data(),\n                                   (out.size()) * sizeof(DataType));\n    auto device_expr = gpu_out.device(sycl_device);\n    asgn(device_expr, op(gpu_out));\n    sycl_device.memcpyDeviceToHost(out.data(), gpu_data_out,\n                                   (out.size()) * sizeof(DataType));\n    for (int64_t i = 0; i < out.size(); ++i) {\n      DataType ver = reference(i);\n      asgn(ver, op(reference(i)));\n      VERIFY_IS_APPROX(out(i), ver);\n    }\n    sycl_device.deallocate(gpu_data_out);\n  }\n}\n\n#define DECLARE_UNARY_STRUCT(FUNC)                                 \\\n  struct op_##FUNC {                                               \\\n    template <typename T>                                          \\\n    auto operator()(const T& x) -> decltype(cl::sycl::FUNC(x)) {   \\\n      return cl::sycl::FUNC(x);                                    \\\n    }                                                              \\\n    template <typename T>                                          \\\n    auto operator()(const TensorMap<T>& x) -> decltype(x.FUNC()) { \\\n      return x.FUNC();                                             \\\n    }                                                              \\\n  };\n\nDECLARE_UNARY_STRUCT(abs)\nDECLARE_UNARY_STRUCT(sqrt)\nDECLARE_UNARY_STRUCT(rsqrt)\nDECLARE_UNARY_STRUCT(square)\nDECLARE_UNARY_STRUCT(cube)\nDECLARE_UNARY_STRUCT(inverse)\nDECLARE_UNARY_STRUCT(tanh)\nDECLARE_UNARY_STRUCT(exp)\nDECLARE_UNARY_STRUCT(expm1)\nDECLARE_UNARY_STRUCT(log)\nDECLARE_UNARY_STRUCT(ceil)\nDECLARE_UNARY_STRUCT(floor)\nDECLARE_UNARY_STRUCT(round)\nDECLARE_UNARY_STRUCT(log1p)\nDECLARE_UNARY_STRUCT(sign)\nDECLARE_UNARY_STRUCT(isnan)\nDECLARE_UNARY_STRUCT(isfinite)\nDECLARE_UNARY_STRUCT(isinf)\n\ntemplate <typename DataType, int DataLayout, typename Assignement>\nvoid test_unary_builtins_for_assignement(const Eigen::SyclDevice& sycl_device,\n                                         const array<int64_t, 3>& tensor_range) {\n#define RUN_UNARY_TEST(FUNC) \\\n  test_unary_builtins_for_scalar<DataType, DataLayout, Assignement, \\\n                                 op_##FUNC>(sycl_device, tensor_range)\n  RUN_UNARY_TEST(abs);\n  RUN_UNARY_TEST(sqrt);\n  RUN_UNARY_TEST(rsqrt);\n  RUN_UNARY_TEST(square);\n  RUN_UNARY_TEST(cube);\n  RUN_UNARY_TEST(inverse);\n  RUN_UNARY_TEST(tanh);\n  RUN_UNARY_TEST(exp);\n  RUN_UNARY_TEST(expm1);\n  RUN_UNARY_TEST(log);\n  RUN_UNARY_TEST(ceil);\n  RUN_UNARY_TEST(floor);\n  RUN_UNARY_TEST(round);\n  RUN_UNARY_TEST(log1p);\n  RUN_UNARY_TEST(sign);\n}\n\ntemplate <typename DataType, int DataLayout, typename Operator>\nvoid test_unary_builtins_return_bool(const Eigen::SyclDevice& sycl_device,\n                                     const array<int64_t, 3>& tensor_range) {\n  /* out = op(in) */\n  Operator op;\n  Tensor<DataType, 3, DataLayout, int64_t> in(tensor_range);\n  Tensor<bool, 3, DataLayout, int64_t> out(tensor_range);\n  in = in.random() + DataType(0.01);\n  DataType *gpu_data = static_cast<DataType *>(\n      sycl_device.allocate(in.size() * sizeof(DataType)));\n  bool *gpu_data_out =\n      static_cast<bool *>(sycl_device.allocate(out.size() * sizeof(bool)));\n  TensorMap<Tensor<DataType, 3, DataLayout, int64_t>> gpu(gpu_data, tensor_range);\n  TensorMap<Tensor<bool, 3, DataLayout, int64_t>> gpu_out(gpu_data_out, tensor_range);\n  sycl_device.memcpyHostToDevice(gpu_data, in.data(),\n                                 (in.size()) * sizeof(DataType));\n  gpu_out.device(sycl_device) = op(gpu);\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_data_out,\n                                 (out.size()) * sizeof(bool));\n  for (int64_t i = 0; i < out.size(); ++i) {\n    VERIFY_IS_EQUAL(out(i), op(in(i)));\n  }\n  sycl_device.deallocate(gpu_data);\n  sycl_device.deallocate(gpu_data_out);\n}\n\ntemplate <typename DataType, int DataLayout>\nvoid test_unary_builtins(const Eigen::SyclDevice& sycl_device,\n                         const array<int64_t, 3>& tensor_range) {\n  test_unary_builtins_for_assignement<DataType, DataLayout,\n                                      PlusEqualAssignement>(sycl_device, tensor_range);\n  test_unary_builtins_for_assignement<DataType, DataLayout,\n                                      EqualAssignement>(sycl_device, tensor_range);\n  test_unary_builtins_return_bool<DataType, DataLayout,\n                                  op_isnan>(sycl_device, tensor_range);\n  test_unary_builtins_return_bool<DataType, DataLayout,\n                                  op_isfinite>(sycl_device, tensor_range);\n  test_unary_builtins_return_bool<DataType, DataLayout,\n                                  op_isinf>(sycl_device, tensor_range);\n}\n\ntemplate <typename DataType>\nstatic void test_builtin_unary_sycl(const Eigen::SyclDevice &sycl_device) {\n  int64_t sizeDim1 = 10;\n  int64_t sizeDim2 = 10;\n  int64_t sizeDim3 = 10;\n  array<int64_t, 3> tensor_range = {{sizeDim1, sizeDim2, sizeDim3}};\n\n  test_unary_builtins<DataType, RowMajor>(sycl_device, tensor_range);\n  test_unary_builtins<DataType, ColMajor>(sycl_device, tensor_range);\n}\n\ntemplate <typename DataType, int DataLayout, typename Operator>\nvoid test_binary_builtins_func(const Eigen::SyclDevice& sycl_device,\n                               const array<int64_t, 3>& tensor_range) {\n  /* out = op(in_1, in_2) */\n  Operator op;\n  Tensor<DataType, 3, DataLayout, int64_t> in_1(tensor_range);\n  Tensor<DataType, 3, DataLayout, int64_t> in_2(tensor_range);\n  Tensor<DataType, 3, DataLayout, int64_t> out(tensor_range);\n  in_1 = in_1.random() + DataType(0.01);\n  in_2 = in_2.random() + DataType(0.01);\n  Tensor<DataType, 3, DataLayout, int64_t> reference(out);\n  DataType *gpu_data_1 = static_cast<DataType *>(\n      sycl_device.allocate(in_1.size() * sizeof(DataType)));\n  DataType *gpu_data_2 = static_cast<DataType *>(\n      sycl_device.allocate(in_2.size() * sizeof(DataType)));\n  DataType *gpu_data_out = static_cast<DataType *>(\n      sycl_device.allocate(out.size() * sizeof(DataType)));\n  TensorMap<Tensor<DataType, 3, DataLayout, int64_t>> gpu_1(gpu_data_1, tensor_range);\n  TensorMap<Tensor<DataType, 3, DataLayout, int64_t>> gpu_2(gpu_data_2, tensor_range);\n  TensorMap<Tensor<DataType, 3, DataLayout, int64_t>> gpu_out(gpu_data_out, tensor_range);\n  sycl_device.memcpyHostToDevice(gpu_data_1, in_1.data(),\n                                 (in_1.size()) * sizeof(DataType));\n  sycl_device.memcpyHostToDevice(gpu_data_2, in_2.data(),\n                                 (in_2.size()) * sizeof(DataType));\n  gpu_out.device(sycl_device) = op(gpu_1, gpu_2);\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_data_out,\n                                 (out.size()) * sizeof(DataType));\n  for (int64_t i = 0; i < out.size(); ++i) {\n    VERIFY_IS_APPROX(out(i), op(in_1(i), in_2(i)));\n  }\n  sycl_device.deallocate(gpu_data_1);\n  sycl_device.deallocate(gpu_data_2);\n  sycl_device.deallocate(gpu_data_out);\n}\n\ntemplate <typename DataType, int DataLayout, typename Operator>\nvoid test_binary_builtins_fixed_arg2(const Eigen::SyclDevice& sycl_device,\n                                     const array<int64_t, 3>& tensor_range) {\n  /* out = op(in_1, 2) */\n  Operator op;\n  const DataType arg2(2);\n  Tensor<DataType, 3, DataLayout, int64_t> in_1(tensor_range);\n  Tensor<DataType, 3, DataLayout, int64_t> out(tensor_range);\n  in_1 = in_1.random();\n  Tensor<DataType, 3, DataLayout, int64_t> reference(out);\n  DataType *gpu_data_1 = static_cast<DataType *>(\n      sycl_device.allocate(in_1.size() * sizeof(DataType)));\n  DataType *gpu_data_out = static_cast<DataType *>(\n      sycl_device.allocate(out.size() * sizeof(DataType)));\n  TensorMap<Tensor<DataType, 3, DataLayout, int64_t>> gpu_1(gpu_data_1, tensor_range);\n  TensorMap<Tensor<DataType, 3, DataLayout, int64_t>> gpu_out(gpu_data_out, tensor_range);\n  sycl_device.memcpyHostToDevice(gpu_data_1, in_1.data(),\n                                 (in_1.size()) * sizeof(DataType));\n  gpu_out.device(sycl_device) = op(gpu_1, arg2);\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_data_out,\n                                 (out.size()) * sizeof(DataType));\n  for (int64_t i = 0; i < out.size(); ++i) {\n    VERIFY_IS_APPROX(out(i), op(in_1(i), arg2));\n  }\n  sycl_device.deallocate(gpu_data_1);\n  sycl_device.deallocate(gpu_data_out);\n}\n\n#define DECLARE_BINARY_STRUCT(FUNC)                                                          \\\n  struct op_##FUNC {                                                                         \\\n    template <typename T1, typename T2>                                                      \\\n    auto operator()(const T1& x, const T2& y) -> decltype(cl::sycl::FUNC(x, y)) {            \\\n      return cl::sycl::FUNC(x, y);                                                           \\\n    }                                                                                        \\\n    template <typename T1, typename T2>                                                      \\\n    auto operator()(const TensorMap<T1>& x, const TensorMap<T2>& y) -> decltype(x.FUNC(y)) { \\\n      return x.FUNC(y);                                                                      \\\n    }                                                                                        \\\n  };\n\nDECLARE_BINARY_STRUCT(cwiseMax)\nDECLARE_BINARY_STRUCT(cwiseMin)\n\n#define DECLARE_BINARY_STRUCT_OP(NAME, OPERATOR)                          \\\n  struct op_##NAME {                                                      \\\n    template <typename T1, typename T2>                                   \\\n    auto operator()(const T1& x, const T2& y) -> decltype(x OPERATOR y) { \\\n      return x OPERATOR y;                                                \\\n    }                                                                     \\\n  };\n\nDECLARE_BINARY_STRUCT_OP(plus, +)\nDECLARE_BINARY_STRUCT_OP(minus, -)\nDECLARE_BINARY_STRUCT_OP(times, *)\nDECLARE_BINARY_STRUCT_OP(divide, /)\nDECLARE_BINARY_STRUCT_OP(modulo, %)\n\ntemplate <typename DataType, int DataLayout>\nvoid test_binary_builtins(const Eigen::SyclDevice& sycl_device,\n                          const array<int64_t, 3>& tensor_range) {\n  test_binary_builtins_func<DataType, DataLayout,\n                            op_cwiseMax>(sycl_device, tensor_range);\n  test_binary_builtins_func<DataType, DataLayout,\n                            op_cwiseMin>(sycl_device, tensor_range);\n  test_binary_builtins_func<DataType, DataLayout,\n                            op_plus>(sycl_device, tensor_range);\n  test_binary_builtins_func<DataType, DataLayout,\n                            op_minus>(sycl_device, tensor_range);\n  test_binary_builtins_func<DataType, DataLayout,\n                            op_times>(sycl_device, tensor_range);\n  test_binary_builtins_func<DataType, DataLayout,\n                            op_divide>(sycl_device, tensor_range);\n}\n\ntemplate <typename DataType>\nstatic void test_floating_builtin_binary_sycl(const Eigen::SyclDevice &sycl_device) {\n  int64_t sizeDim1 = 10;\n  int64_t sizeDim2 = 10;\n  int64_t sizeDim3 = 10;\n  array<int64_t, 3> tensor_range = {{sizeDim1, sizeDim2, sizeDim3}};\n  test_binary_builtins<DataType, RowMajor>(sycl_device, tensor_range);\n  test_binary_builtins<DataType, ColMajor>(sycl_device, tensor_range);\n}\n\ntemplate <typename DataType>\nstatic void test_integer_builtin_binary_sycl(const Eigen::SyclDevice &sycl_device) {\n  int64_t sizeDim1 = 10;\n  int64_t sizeDim2 = 10;\n  int64_t sizeDim3 = 10;\n  array<int64_t, 3> tensor_range = {{sizeDim1, sizeDim2, sizeDim3}};\n  test_binary_builtins_fixed_arg2<DataType, RowMajor,\n                                  op_modulo>(sycl_device, tensor_range);\n  test_binary_builtins_fixed_arg2<DataType, ColMajor,\n                                  op_modulo>(sycl_device, tensor_range);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_builtins_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    QueueInterface queueInterface(device);\n    Eigen::SyclDevice sycl_device(&queueInterface);\n    CALL_SUBTEST_1(test_builtin_unary_sycl<float>(sycl_device));\n    CALL_SUBTEST_2(test_floating_builtin_binary_sycl<float>(sycl_device));\n    CALL_SUBTEST_3(test_integer_builtin_binary_sycl<int>(sycl_device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_cast_float16_gpu.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\nvoid test_gpu_conversion() {\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n  int num_elem = 101;\n\n  Tensor<float, 1> floats(num_elem);\n  floats.setRandom();\n\n  float* d_float = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  Eigen::half* d_half = (Eigen::half*)gpu_device.allocate(num_elem * sizeof(Eigen::half));\n  float* d_conv = (float*)gpu_device.allocate(num_elem * sizeof(float));\n\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_float(\n      d_float, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_half(\n      d_half, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_conv(\n      d_conv, num_elem);\n\n  gpu_device.memcpyHostToDevice(d_float, floats.data(), num_elem*sizeof(float));\n\n  gpu_half.device(gpu_device) = gpu_float.cast<Eigen::half>();\n  gpu_conv.device(gpu_device) = gpu_half.cast<float>();\n\n  Tensor<float, 1> initial(num_elem);\n  Tensor<float, 1> final(num_elem);\n  gpu_device.memcpyDeviceToHost(initial.data(), d_float, num_elem*sizeof(float));\n  gpu_device.memcpyDeviceToHost(final.data(), d_conv, num_elem*sizeof(float));\n  gpu_device.synchronize();\n\n  for (int i = 0; i < num_elem; ++i) {\n    VERIFY_IS_APPROX(initial(i), final(i));\n  }\n\n  gpu_device.deallocate(d_float);\n  gpu_device.deallocate(d_half);\n  gpu_device.deallocate(d_conv);\n}\n\n\nvoid test_fallback_conversion() {\n  int num_elem = 101;\n  Tensor<float, 1> floats(num_elem);\n  floats.setRandom();\n\n  Eigen::Tensor<Eigen::half, 1> halfs = floats.cast<Eigen::half>();\n  Eigen::Tensor<float, 1> conv = halfs.cast<float>();\n\n  for (int i = 0; i < num_elem; ++i) {\n    VERIFY_IS_APPROX(floats(i), conv(i));\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_cast_float16_gpu)\n{\n  CALL_SUBTEST(test_gpu_conversion());\n  CALL_SUBTEST(test_fallback_conversion());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_casts.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include \"random_without_cast_overflow.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::array;\n\nstatic void test_simple_cast()\n{\n  Tensor<float, 2> ftensor(20,30);\n  ftensor = ftensor.random() * 100.f;\n  Tensor<char, 2> chartensor(20,30);\n  chartensor.setRandom();\n  Tensor<std::complex<float>, 2> cplextensor(20,30);\n  cplextensor.setRandom();\n\n  chartensor = ftensor.cast<char>();\n  cplextensor = ftensor.cast<std::complex<float> >();\n\n  for (int i = 0; i < 20; ++i) {\n    for (int j = 0; j < 30; ++j) {\n      VERIFY_IS_EQUAL(chartensor(i,j), static_cast<char>(ftensor(i,j)));\n      VERIFY_IS_EQUAL(cplextensor(i,j), static_cast<std::complex<float> >(ftensor(i,j)));\n    }\n  }\n}\n\n\nstatic void test_vectorized_cast()\n{\n  Tensor<int, 2> itensor(20,30);\n  itensor = itensor.random() / 1000;\n  Tensor<float, 2> ftensor(20,30);\n  ftensor.setRandom();\n  Tensor<double, 2> dtensor(20,30);\n  dtensor.setRandom();\n\n  ftensor = itensor.cast<float>();\n  dtensor = itensor.cast<double>();\n\n  for (int i = 0; i < 20; ++i) {\n    for (int j = 0; j < 30; ++j) {\n      VERIFY_IS_EQUAL(itensor(i,j), static_cast<int>(ftensor(i,j)));\n      VERIFY_IS_EQUAL(dtensor(i,j), static_cast<double>(ftensor(i,j)));\n    }\n  }\n}\n\n\nstatic void test_float_to_int_cast()\n{\n  Tensor<float, 2> ftensor(20,30);\n  ftensor = ftensor.random() * 1000.0f;\n  Tensor<double, 2> dtensor(20,30);\n  dtensor = dtensor.random() * 1000.0;\n\n  Tensor<int, 2> i1tensor = ftensor.cast<int>();\n  Tensor<int, 2> i2tensor = dtensor.cast<int>();\n\n  for (int i = 0; i < 20; ++i) {\n    for (int j = 0; j < 30; ++j) {\n      VERIFY_IS_EQUAL(i1tensor(i,j), static_cast<int>(ftensor(i,j)));\n      VERIFY_IS_EQUAL(i2tensor(i,j), static_cast<int>(dtensor(i,j)));\n    }\n  }\n}\n\n\nstatic void test_big_to_small_type_cast()\n{\n  Tensor<double, 2> dtensor(20, 30);\n  dtensor.setRandom();\n  Tensor<float, 2> ftensor(20, 30);\n  ftensor = dtensor.cast<float>();\n\n  for (int i = 0; i < 20; ++i) {\n    for (int j = 0; j < 30; ++j) {\n      VERIFY_IS_APPROX(dtensor(i,j), static_cast<double>(ftensor(i,j)));\n    }\n  }\n}\n\n\nstatic void test_small_to_big_type_cast()\n{\n  Tensor<float, 2> ftensor(20, 30);\n  ftensor.setRandom();\n  Tensor<double, 2> dtensor(20, 30);\n  dtensor = ftensor.cast<double>();\n\n  for (int i = 0; i < 20; ++i) {\n    for (int j = 0; j < 30; ++j) {\n      VERIFY_IS_APPROX(dtensor(i,j), static_cast<double>(ftensor(i,j)));\n    }\n  }\n}\n\ntemplate <typename FromType, typename ToType>\nstatic void test_type_cast() {\n  Tensor<FromType, 2> ftensor(100, 200);\n  // Generate random values for a valid cast.\n  for (int i = 0; i < 100; ++i) {\n    for (int j = 0; j < 200; ++j) {\n      ftensor(i, j) = internal::random_without_cast_overflow<FromType,ToType>::value();\n    }\n  }\n\n  Tensor<ToType, 2> ttensor(100, 200);\n  ttensor = ftensor.template cast<ToType>();\n\n  for (int i = 0; i < 100; ++i) {\n    for (int j = 0; j < 200; ++j) {\n      const ToType ref = internal::cast<FromType,ToType>(ftensor(i, j));\n      VERIFY_IS_APPROX(ttensor(i, j), ref);\n    }\n  }\n}\n\ntemplate<typename Scalar, typename EnableIf = void>\nstruct test_cast_runner {\n  static void run() {\n    test_type_cast<Scalar, bool>();\n    test_type_cast<Scalar, int8_t>();\n    test_type_cast<Scalar, int16_t>();\n    test_type_cast<Scalar, int32_t>();\n    test_type_cast<Scalar, int64_t>();\n    test_type_cast<Scalar, uint8_t>();\n    test_type_cast<Scalar, uint16_t>();\n    test_type_cast<Scalar, uint32_t>();\n    test_type_cast<Scalar, uint64_t>();\n    test_type_cast<Scalar, half>();\n    test_type_cast<Scalar, bfloat16>();\n    test_type_cast<Scalar, float>();\n    test_type_cast<Scalar, double>();\n    test_type_cast<Scalar, std::complex<float>>();\n    test_type_cast<Scalar, std::complex<double>>();\n  }\n};\n\n// Only certain types allow cast from std::complex<>.\ntemplate<typename Scalar>\nstruct test_cast_runner<Scalar, typename internal::enable_if<NumTraits<Scalar>::IsComplex>::type> {\n  static void run() {\n    test_type_cast<Scalar, half>();\n    test_type_cast<Scalar, bfloat16>();\n    test_type_cast<Scalar, std::complex<float>>();\n    test_type_cast<Scalar, std::complex<double>>();\n  }\n};\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_casts)\n{\n  CALL_SUBTEST(test_simple_cast());\n  CALL_SUBTEST(test_vectorized_cast());\n  CALL_SUBTEST(test_float_to_int_cast());\n  CALL_SUBTEST(test_big_to_small_type_cast());\n  CALL_SUBTEST(test_small_to_big_type_cast());\n\n  CALL_SUBTEST(test_cast_runner<bool>::run());\n  CALL_SUBTEST(test_cast_runner<int8_t>::run());\n  CALL_SUBTEST(test_cast_runner<int16_t>::run());\n  CALL_SUBTEST(test_cast_runner<int32_t>::run());\n  CALL_SUBTEST(test_cast_runner<int64_t>::run());\n  CALL_SUBTEST(test_cast_runner<uint8_t>::run());\n  CALL_SUBTEST(test_cast_runner<uint16_t>::run());\n  CALL_SUBTEST(test_cast_runner<uint32_t>::run());\n  CALL_SUBTEST(test_cast_runner<uint64_t>::run());\n  CALL_SUBTEST(test_cast_runner<half>::run());\n  CALL_SUBTEST(test_cast_runner<bfloat16>::run());\n  CALL_SUBTEST(test_cast_runner<float>::run());\n  CALL_SUBTEST(test_cast_runner<double>::run());\n  CALL_SUBTEST(test_cast_runner<std::complex<float>>::run());\n  CALL_SUBTEST(test_cast_runner<std::complex<double>>::run());\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_chipping.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate<int DataLayout>\nstatic void test_simple_chip()\n{\n  Tensor<float, 5, DataLayout> tensor(2,3,5,7,11);\n  tensor.setRandom();\n\n  Tensor<float, 4, DataLayout> chip1;\n  chip1 = tensor.template chip<0>(1);\n\n  VERIFY_IS_EQUAL(chip1.dimension(0), 3);\n  VERIFY_IS_EQUAL(chip1.dimension(1), 5);\n  VERIFY_IS_EQUAL(chip1.dimension(2), 7);\n  VERIFY_IS_EQUAL(chip1.dimension(3), 11);\n\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        for (int l = 0; l < 11; ++l) {\n          VERIFY_IS_EQUAL(chip1(i,j,k,l), tensor(1,i,j,k,l));\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> chip2 = tensor.template chip<1>(1);\n  VERIFY_IS_EQUAL(chip2.dimension(0), 2);\n  VERIFY_IS_EQUAL(chip2.dimension(1), 5);\n  VERIFY_IS_EQUAL(chip2.dimension(2), 7);\n  VERIFY_IS_EQUAL(chip2.dimension(3), 11);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        for (int l = 0; l < 11; ++l) {\n          VERIFY_IS_EQUAL(chip2(i,j,k,l), tensor(i,1,j,k,l));\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> chip3 = tensor.template chip<2>(2);\n  VERIFY_IS_EQUAL(chip3.dimension(0), 2);\n  VERIFY_IS_EQUAL(chip3.dimension(1), 3);\n  VERIFY_IS_EQUAL(chip3.dimension(2), 7);\n  VERIFY_IS_EQUAL(chip3.dimension(3), 11);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        for (int l = 0; l < 11; ++l) {\n          VERIFY_IS_EQUAL(chip3(i,j,k,l), tensor(i,j,2,k,l));\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> chip4(tensor.template chip<3>(5));\n  VERIFY_IS_EQUAL(chip4.dimension(0), 2);\n  VERIFY_IS_EQUAL(chip4.dimension(1), 3);\n  VERIFY_IS_EQUAL(chip4.dimension(2), 5);\n  VERIFY_IS_EQUAL(chip4.dimension(3), 11);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 11; ++l) {\n          VERIFY_IS_EQUAL(chip4(i,j,k,l), tensor(i,j,k,5,l));\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> chip5(tensor.template chip<4>(7));\n  VERIFY_IS_EQUAL(chip5.dimension(0), 2);\n  VERIFY_IS_EQUAL(chip5.dimension(1), 3);\n  VERIFY_IS_EQUAL(chip5.dimension(2), 5);\n  VERIFY_IS_EQUAL(chip5.dimension(3), 7);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(chip5(i,j,k,l), tensor(i,j,k,l,7));\n        }\n      }\n    }\n  }\n}\n\ntemplate<int DataLayout>\nstatic void test_dynamic_chip()\n{\n  Tensor<float, 5, DataLayout> tensor(2,3,5,7,11);\n  tensor.setRandom();\n\n  Tensor<float, 4, DataLayout> chip1;\n  chip1 = tensor.chip(1, 0);\n  VERIFY_IS_EQUAL(chip1.dimension(0), 3);\n  VERIFY_IS_EQUAL(chip1.dimension(1), 5);\n  VERIFY_IS_EQUAL(chip1.dimension(2), 7);\n  VERIFY_IS_EQUAL(chip1.dimension(3), 11);\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        for (int l = 0; l < 11; ++l) {\n          VERIFY_IS_EQUAL(chip1(i,j,k,l), tensor(1,i,j,k,l));\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> chip2 = tensor.chip(1, 1);\n  VERIFY_IS_EQUAL(chip2.dimension(0), 2);\n  VERIFY_IS_EQUAL(chip2.dimension(1), 5);\n  VERIFY_IS_EQUAL(chip2.dimension(2), 7);\n  VERIFY_IS_EQUAL(chip2.dimension(3), 11);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        for (int l = 0; l < 11; ++l) {\n          VERIFY_IS_EQUAL(chip2(i,j,k,l), tensor(i,1,j,k,l));\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> chip3 = tensor.chip(2, 2);\n  VERIFY_IS_EQUAL(chip3.dimension(0), 2);\n  VERIFY_IS_EQUAL(chip3.dimension(1), 3);\n  VERIFY_IS_EQUAL(chip3.dimension(2), 7);\n  VERIFY_IS_EQUAL(chip3.dimension(3), 11);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        for (int l = 0; l < 11; ++l) {\n          VERIFY_IS_EQUAL(chip3(i,j,k,l), tensor(i,j,2,k,l));\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> chip4(tensor.chip(5, 3));\n  VERIFY_IS_EQUAL(chip4.dimension(0), 2);\n  VERIFY_IS_EQUAL(chip4.dimension(1), 3);\n  VERIFY_IS_EQUAL(chip4.dimension(2), 5);\n  VERIFY_IS_EQUAL(chip4.dimension(3), 11);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 11; ++l) {\n          VERIFY_IS_EQUAL(chip4(i,j,k,l), tensor(i,j,k,5,l));\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> chip5(tensor.chip(7, 4));\n  VERIFY_IS_EQUAL(chip5.dimension(0), 2);\n  VERIFY_IS_EQUAL(chip5.dimension(1), 3);\n  VERIFY_IS_EQUAL(chip5.dimension(2), 5);\n  VERIFY_IS_EQUAL(chip5.dimension(3), 7);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(chip5(i,j,k,l), tensor(i,j,k,l,7));\n        }\n      }\n    }\n  }\n}\n\ntemplate<int DataLayout>\nstatic void test_chip_in_expr() {\n  Tensor<float, 5, DataLayout> input1(2,3,5,7,11);\n  input1.setRandom();\n  Tensor<float, 4, DataLayout> input2(3,5,7,11);\n  input2.setRandom();\n\n  Tensor<float, 4, DataLayout> result = input1.template chip<0>(0) + input2;\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        for (int l = 0; l < 11; ++l) {\n          float expected = input1(0,i,j,k,l) + input2(i,j,k,l);\n          VERIFY_IS_EQUAL(result(i,j,k,l), expected);\n        }\n      }\n    }\n  }\n\n  Tensor<float, 3, DataLayout> input3(3,7,11);\n  input3.setRandom();\n  Tensor<float, 3, DataLayout> result2 = input1.template chip<0>(0).template chip<1>(2) + input3;\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 7; ++j) {\n      for (int k = 0; k < 11; ++k) {\n        float expected = input1(0,i,2,j,k) + input3(i,j,k);\n        VERIFY_IS_EQUAL(result2(i,j,k), expected);\n      }\n    }\n  }\n}\n\ntemplate<int DataLayout>\nstatic void test_chip_as_lvalue()\n{\n  Tensor<float, 5, DataLayout> input1(2,3,5,7,11);\n  input1.setRandom();\n\n  Tensor<float, 4, DataLayout> input2(3,5,7,11);\n  input2.setRandom();\n  Tensor<float, 5, DataLayout> tensor = input1;\n  tensor.template chip<0>(1) = input2;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          for (int m = 0; m < 11; ++m) {\n            if (i != 1) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input2(j,k,l,m));\n            }\n          }\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> input3(2,5,7,11);\n  input3.setRandom();\n  tensor = input1;\n  tensor.template chip<1>(1) = input3;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          for (int m = 0; m < 11; ++m) {\n            if (j != 1) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input3(i,k,l,m));\n            }\n          }\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> input4(2,3,7,11);\n  input4.setRandom();\n  tensor = input1;\n  tensor.template chip<2>(3) = input4;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          for (int m = 0; m < 11; ++m) {\n            if (k != 3) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input4(i,j,l,m));\n            }\n          }\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> input5(2,3,5,11);\n  input5.setRandom();\n  tensor = input1;\n  tensor.template chip<3>(4) = input5;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          for (int m = 0; m < 11; ++m) {\n            if (l != 4) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input5(i,j,k,m));\n            }\n          }\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> input6(2,3,5,7);\n  input6.setRandom();\n  tensor = input1;\n  tensor.template chip<4>(5) = input6;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          for (int m = 0; m < 11; ++m) {\n            if (m != 5) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input6(i,j,k,l));\n            }\n          }\n        }\n      }\n    }\n  }\n\n  Tensor<float, 5, DataLayout> input7(2,3,5,7,11);\n  input7.setRandom();\n  tensor = input1;\n  tensor.chip(0, 0) = input7.chip(0, 0);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          for (int m = 0; m < 11; ++m) {\n            if (i != 0) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input7(i,j,k,l,m));\n            }\n          }\n        }\n      }\n    }\n  }\n}\n\nstatic void test_chip_raw_data_col_major()\n{\n  Tensor<float, 5, ColMajor> tensor(2,3,5,7,11);\n  tensor.setRandom();\n\n  typedef TensorEvaluator<decltype(tensor.chip<4>(3)), DefaultDevice> Evaluator4;\n  auto chip = Evaluator4(tensor.chip<4>(3), DefaultDevice());\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          int chip_index = i + 2 * (j + 3 * (k + 5 * l));\n          VERIFY_IS_EQUAL(chip.data()[chip_index], tensor(i,j,k,l,3));\n        }\n      }\n    }\n  }\n\n  typedef TensorEvaluator<decltype(tensor.chip<0>(0)), DefaultDevice> Evaluator0;\n  auto chip0 = Evaluator0(tensor.chip<0>(0), DefaultDevice());\n  VERIFY_IS_EQUAL(chip0.data(), static_cast<float*>(0));\n\n  typedef TensorEvaluator<decltype(tensor.chip<1>(0)), DefaultDevice> Evaluator1;\n  auto chip1 = Evaluator1(tensor.chip<1>(0), DefaultDevice());\n  VERIFY_IS_EQUAL(chip1.data(), static_cast<float*>(0));\n\n  typedef TensorEvaluator<decltype(tensor.chip<2>(0)), DefaultDevice> Evaluator2;\n  auto chip2 = Evaluator2(tensor.chip<2>(0), DefaultDevice());\n  VERIFY_IS_EQUAL(chip2.data(), static_cast<float*>(0));\n\n  typedef TensorEvaluator<decltype(tensor.chip<3>(0)), DefaultDevice> Evaluator3;\n  auto chip3 = Evaluator3(tensor.chip<3>(0), DefaultDevice());\n  VERIFY_IS_EQUAL(chip3.data(), static_cast<float*>(0));\n}\n\nstatic void test_chip_raw_data_row_major()\n{\n  Tensor<float, 5, RowMajor> tensor(11,7,5,3,2);\n  tensor.setRandom();\n\n  typedef TensorEvaluator<decltype(tensor.chip<0>(3)), DefaultDevice> Evaluator0;\n  auto chip = Evaluator0(tensor.chip<0>(3), DefaultDevice());\n  for (int i = 0; i < 7; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 3; ++k) {\n        for (int l = 0; l < 2; ++l) {\n          int chip_index = l + 2 * (k + 3 * (j + 5 * i));\n          VERIFY_IS_EQUAL(chip.data()[chip_index], tensor(3,i,j,k,l));\n        }\n      }\n    }\n  }\n\n  typedef TensorEvaluator<decltype(tensor.chip<1>(0)), DefaultDevice> Evaluator1;\n  auto chip1 = Evaluator1(tensor.chip<1>(0), DefaultDevice());\n  VERIFY_IS_EQUAL(chip1.data(), static_cast<float*>(0));\n\n  typedef TensorEvaluator<decltype(tensor.chip<2>(0)), DefaultDevice> Evaluator2;\n  auto chip2 = Evaluator2(tensor.chip<2>(0), DefaultDevice());\n  VERIFY_IS_EQUAL(chip2.data(), static_cast<float*>(0));\n\n  typedef TensorEvaluator<decltype(tensor.chip<3>(0)), DefaultDevice> Evaluator3;\n  auto chip3 = Evaluator3(tensor.chip<3>(0), DefaultDevice());\n  VERIFY_IS_EQUAL(chip3.data(), static_cast<float*>(0));\n\n  typedef TensorEvaluator<decltype(tensor.chip<4>(0)), DefaultDevice> Evaluator4;\n  auto chip4 = Evaluator4(tensor.chip<4>(0), DefaultDevice());\n  VERIFY_IS_EQUAL(chip4.data(), static_cast<float*>(0));\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_chipping)\n{\n  CALL_SUBTEST(test_simple_chip<ColMajor>());\n  CALL_SUBTEST(test_simple_chip<RowMajor>());\n  CALL_SUBTEST(test_dynamic_chip<ColMajor>());\n  CALL_SUBTEST(test_dynamic_chip<RowMajor>());\n  CALL_SUBTEST(test_chip_in_expr<ColMajor>());\n  CALL_SUBTEST(test_chip_in_expr<RowMajor>());\n  CALL_SUBTEST(test_chip_as_lvalue<ColMajor>());\n  CALL_SUBTEST(test_chip_as_lvalue<RowMajor>());\n  CALL_SUBTEST(test_chip_raw_data_col_major());\n  CALL_SUBTEST(test_chip_raw_data_row_major());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_chipping_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_static_chip_sycl(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  IndexType sizeDim5 = 11;\n\n  array<IndexType, 5> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4, sizeDim5}};\n  array<IndexType, 4> chip1TensorRange = {{sizeDim2, sizeDim3, sizeDim4, sizeDim5}};\n\n  Tensor<DataType, 5, DataLayout,IndexType> tensor(tensorRange);\n  Tensor<DataType, 4, DataLayout,IndexType> chip1(chip1TensorRange);\n\n  tensor.setRandom();\n\n  const size_t tensorBuffSize =tensor.size()*sizeof(DataType);\n  const size_t chip1TensorBuffSize =chip1.size()*sizeof(DataType);\n  DataType* gpu_data_tensor  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  DataType* gpu_data_chip1  = static_cast<DataType*>(sycl_device.allocate(chip1TensorBuffSize));\n\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_tensor(gpu_data_tensor, tensorRange);\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip1(gpu_data_chip1, chip1TensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_tensor, tensor.data(), tensorBuffSize);\n  gpu_chip1.device(sycl_device)=gpu_tensor.template chip<0l>(1l);\n  sycl_device.memcpyDeviceToHost(chip1.data(), gpu_data_chip1, chip1TensorBuffSize);\n\n  VERIFY_IS_EQUAL(chip1.dimension(0), sizeDim2);\n  VERIFY_IS_EQUAL(chip1.dimension(1), sizeDim3);\n  VERIFY_IS_EQUAL(chip1.dimension(2), sizeDim4);\n  VERIFY_IS_EQUAL(chip1.dimension(3), sizeDim5);\n\n  for (IndexType i = 0; i < sizeDim2; ++i) {\n    for (IndexType j = 0; j < sizeDim3; ++j) {\n      for (IndexType k = 0; k < sizeDim4; ++k) {\n        for (IndexType l = 0; l < sizeDim5; ++l) {\n          VERIFY_IS_EQUAL(chip1(i,j,k,l), tensor(1l,i,j,k,l));\n        }\n      }\n    }\n  }\n\n  array<IndexType, 4> chip2TensorRange = {{sizeDim1, sizeDim3, sizeDim4, sizeDim5}};\n  Tensor<DataType, 4, DataLayout,IndexType> chip2(chip2TensorRange);\n  const size_t chip2TensorBuffSize =chip2.size()*sizeof(DataType);\n  DataType* gpu_data_chip2  = static_cast<DataType*>(sycl_device.allocate(chip2TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip2(gpu_data_chip2, chip2TensorRange);\n\n  gpu_chip2.device(sycl_device)=gpu_tensor.template chip<1l>(1l);\n  sycl_device.memcpyDeviceToHost(chip2.data(), gpu_data_chip2, chip2TensorBuffSize);\n\n  VERIFY_IS_EQUAL(chip2.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(chip2.dimension(1), sizeDim3);\n  VERIFY_IS_EQUAL(chip2.dimension(2), sizeDim4);\n  VERIFY_IS_EQUAL(chip2.dimension(3), sizeDim5);\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim3; ++j) {\n      for (IndexType k = 0; k < sizeDim4; ++k) {\n        for (IndexType l = 0; l < sizeDim5; ++l) {\n          VERIFY_IS_EQUAL(chip2(i,j,k,l), tensor(i,1l,j,k,l));\n        }\n      }\n    }\n  }\n\n  array<IndexType, 4> chip3TensorRange = {{sizeDim1, sizeDim2, sizeDim4, sizeDim5}};\n  Tensor<DataType, 4, DataLayout,IndexType> chip3(chip3TensorRange);\n  const size_t chip3TensorBuffSize =chip3.size()*sizeof(DataType);\n  DataType* gpu_data_chip3  = static_cast<DataType*>(sycl_device.allocate(chip3TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip3(gpu_data_chip3, chip3TensorRange);\n\n  gpu_chip3.device(sycl_device)=gpu_tensor.template chip<2l>(2l);\n  sycl_device.memcpyDeviceToHost(chip3.data(), gpu_data_chip3, chip3TensorBuffSize);\n\n  VERIFY_IS_EQUAL(chip3.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(chip3.dimension(1), sizeDim2);\n  VERIFY_IS_EQUAL(chip3.dimension(2), sizeDim4);\n  VERIFY_IS_EQUAL(chip3.dimension(3), sizeDim5);\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim4; ++k) {\n        for (IndexType l = 0; l < sizeDim5; ++l) {\n          VERIFY_IS_EQUAL(chip3(i,j,k,l), tensor(i,j,2l,k,l));\n        }\n      }\n    }\n  }\n\n  array<IndexType, 4> chip4TensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim5}};\n  Tensor<DataType, 4, DataLayout,IndexType> chip4(chip4TensorRange);\n  const size_t chip4TensorBuffSize =chip4.size()*sizeof(DataType);\n  DataType* gpu_data_chip4  = static_cast<DataType*>(sycl_device.allocate(chip4TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip4(gpu_data_chip4, chip4TensorRange);\n\n  gpu_chip4.device(sycl_device)=gpu_tensor.template chip<3l>(5l);\n  sycl_device.memcpyDeviceToHost(chip4.data(), gpu_data_chip4, chip4TensorBuffSize);\n\n  VERIFY_IS_EQUAL(chip4.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(chip4.dimension(1), sizeDim2);\n  VERIFY_IS_EQUAL(chip4.dimension(2), sizeDim3);\n  VERIFY_IS_EQUAL(chip4.dimension(3), sizeDim5);\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        for (IndexType l = 0; l < sizeDim5; ++l) {\n          VERIFY_IS_EQUAL(chip4(i,j,k,l), tensor(i,j,k,5l,l));\n        }\n      }\n    }\n  }\n\n\n  array<IndexType, 4> chip5TensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  Tensor<DataType, 4, DataLayout,IndexType> chip5(chip5TensorRange);\n  const size_t chip5TensorBuffSize =chip5.size()*sizeof(DataType);\n  DataType* gpu_data_chip5  = static_cast<DataType*>(sycl_device.allocate(chip5TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip5(gpu_data_chip5, chip5TensorRange);\n\n  gpu_chip5.device(sycl_device)=gpu_tensor.template chip<4l>(7l);\n  sycl_device.memcpyDeviceToHost(chip5.data(), gpu_data_chip5, chip5TensorBuffSize);\n\n  VERIFY_IS_EQUAL(chip5.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(chip5.dimension(1), sizeDim2);\n  VERIFY_IS_EQUAL(chip5.dimension(2), sizeDim3);\n  VERIFY_IS_EQUAL(chip5.dimension(3), sizeDim4);\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        for (IndexType l = 0; l < sizeDim4; ++l) {\n          VERIFY_IS_EQUAL(chip5(i,j,k,l), tensor(i,j,k,l,7l));\n        }\n      }\n    }\n  }\n\n  sycl_device.deallocate(gpu_data_tensor);\n  sycl_device.deallocate(gpu_data_chip1);\n  sycl_device.deallocate(gpu_data_chip2);\n  sycl_device.deallocate(gpu_data_chip3);\n  sycl_device.deallocate(gpu_data_chip4);\n  sycl_device.deallocate(gpu_data_chip5);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_dynamic_chip_sycl(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  IndexType sizeDim5 = 11;\n\n  array<IndexType, 5> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4, sizeDim5}};\n  array<IndexType, 4> chip1TensorRange = {{sizeDim2, sizeDim3, sizeDim4, sizeDim5}};\n\n  Tensor<DataType, 5, DataLayout,IndexType> tensor(tensorRange);\n  Tensor<DataType, 4, DataLayout,IndexType> chip1(chip1TensorRange);\n\n  tensor.setRandom();\n\n  const size_t tensorBuffSize =tensor.size()*sizeof(DataType);\n  const size_t chip1TensorBuffSize =chip1.size()*sizeof(DataType);\n  DataType* gpu_data_tensor  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  DataType* gpu_data_chip1  = static_cast<DataType*>(sycl_device.allocate(chip1TensorBuffSize));\n\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_tensor(gpu_data_tensor, tensorRange);\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip1(gpu_data_chip1, chip1TensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_tensor, tensor.data(), tensorBuffSize);\n  gpu_chip1.device(sycl_device)=gpu_tensor.chip(1l,0l);\n  sycl_device.memcpyDeviceToHost(chip1.data(), gpu_data_chip1, chip1TensorBuffSize);\n\n  VERIFY_IS_EQUAL(chip1.dimension(0), sizeDim2);\n  VERIFY_IS_EQUAL(chip1.dimension(1), sizeDim3);\n  VERIFY_IS_EQUAL(chip1.dimension(2), sizeDim4);\n  VERIFY_IS_EQUAL(chip1.dimension(3), sizeDim5);\n\n  for (IndexType i = 0; i < sizeDim2; ++i) {\n    for (IndexType j = 0; j < sizeDim3; ++j) {\n      for (IndexType k = 0; k < sizeDim4; ++k) {\n        for (IndexType l = 0; l < sizeDim5; ++l) {\n          VERIFY_IS_EQUAL(chip1(i,j,k,l), tensor(1l,i,j,k,l));\n        }\n      }\n    }\n  }\n\n  array<IndexType, 4> chip2TensorRange = {{sizeDim1, sizeDim3, sizeDim4, sizeDim5}};\n  Tensor<DataType, 4, DataLayout,IndexType> chip2(chip2TensorRange);\n  const size_t chip2TensorBuffSize =chip2.size()*sizeof(DataType);\n  DataType* gpu_data_chip2  = static_cast<DataType*>(sycl_device.allocate(chip2TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip2(gpu_data_chip2, chip2TensorRange);\n\n  gpu_chip2.device(sycl_device)=gpu_tensor.chip(1l,1l);\n  sycl_device.memcpyDeviceToHost(chip2.data(), gpu_data_chip2, chip2TensorBuffSize);\n\n  VERIFY_IS_EQUAL(chip2.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(chip2.dimension(1), sizeDim3);\n  VERIFY_IS_EQUAL(chip2.dimension(2), sizeDim4);\n  VERIFY_IS_EQUAL(chip2.dimension(3), sizeDim5);\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim3; ++j) {\n      for (IndexType k = 0; k < sizeDim4; ++k) {\n        for (IndexType l = 0; l < sizeDim5; ++l) {\n          VERIFY_IS_EQUAL(chip2(i,j,k,l), tensor(i,1l,j,k,l));\n        }\n      }\n    }\n  }\n\n  array<IndexType, 4> chip3TensorRange = {{sizeDim1, sizeDim2, sizeDim4, sizeDim5}};\n  Tensor<DataType, 4, DataLayout,IndexType> chip3(chip3TensorRange);\n  const size_t chip3TensorBuffSize =chip3.size()*sizeof(DataType);\n  DataType* gpu_data_chip3  = static_cast<DataType*>(sycl_device.allocate(chip3TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip3(gpu_data_chip3, chip3TensorRange);\n\n  gpu_chip3.device(sycl_device)=gpu_tensor.chip(2l,2l);\n  sycl_device.memcpyDeviceToHost(chip3.data(), gpu_data_chip3, chip3TensorBuffSize);\n\n  VERIFY_IS_EQUAL(chip3.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(chip3.dimension(1), sizeDim2);\n  VERIFY_IS_EQUAL(chip3.dimension(2), sizeDim4);\n  VERIFY_IS_EQUAL(chip3.dimension(3), sizeDim5);\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim4; ++k) {\n        for (IndexType l = 0; l < sizeDim5; ++l) {\n          VERIFY_IS_EQUAL(chip3(i,j,k,l), tensor(i,j,2l,k,l));\n        }\n      }\n    }\n  }\n\n  array<IndexType, 4> chip4TensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim5}};\n  Tensor<DataType, 4, DataLayout,IndexType> chip4(chip4TensorRange);\n  const size_t chip4TensorBuffSize =chip4.size()*sizeof(DataType);\n  DataType* gpu_data_chip4  = static_cast<DataType*>(sycl_device.allocate(chip4TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip4(gpu_data_chip4, chip4TensorRange);\n\n  gpu_chip4.device(sycl_device)=gpu_tensor.chip(5l,3l);\n  sycl_device.memcpyDeviceToHost(chip4.data(), gpu_data_chip4, chip4TensorBuffSize);\n\n  VERIFY_IS_EQUAL(chip4.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(chip4.dimension(1), sizeDim2);\n  VERIFY_IS_EQUAL(chip4.dimension(2), sizeDim3);\n  VERIFY_IS_EQUAL(chip4.dimension(3), sizeDim5);\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        for (IndexType l = 0; l < sizeDim5; ++l) {\n          VERIFY_IS_EQUAL(chip4(i,j,k,l), tensor(i,j,k,5l,l));\n        }\n      }\n    }\n  }\n\n\n  array<IndexType, 4> chip5TensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  Tensor<DataType, 4, DataLayout,IndexType> chip5(chip5TensorRange);\n  const size_t chip5TensorBuffSize =chip5.size()*sizeof(DataType);\n  DataType* gpu_data_chip5  = static_cast<DataType*>(sycl_device.allocate(chip5TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip5(gpu_data_chip5, chip5TensorRange);\n\n  gpu_chip5.device(sycl_device)=gpu_tensor.chip(7l,4l);\n  sycl_device.memcpyDeviceToHost(chip5.data(), gpu_data_chip5, chip5TensorBuffSize);\n\n  VERIFY_IS_EQUAL(chip5.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(chip5.dimension(1), sizeDim2);\n  VERIFY_IS_EQUAL(chip5.dimension(2), sizeDim3);\n  VERIFY_IS_EQUAL(chip5.dimension(3), sizeDim4);\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        for (IndexType l = 0; l < sizeDim4; ++l) {\n          VERIFY_IS_EQUAL(chip5(i,j,k,l), tensor(i,j,k,l,7l));\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data_tensor);\n  sycl_device.deallocate(gpu_data_chip1);\n  sycl_device.deallocate(gpu_data_chip2);\n  sycl_device.deallocate(gpu_data_chip3);\n  sycl_device.deallocate(gpu_data_chip4);\n  sycl_device.deallocate(gpu_data_chip5);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_chip_in_expr(const Eigen::SyclDevice& sycl_device) {\n\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  IndexType sizeDim5 = 11;\n\n  array<IndexType, 5> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4, sizeDim5}};\n  array<IndexType, 4> chip1TensorRange = {{sizeDim2, sizeDim3, sizeDim4, sizeDim5}};\n\n  Tensor<DataType, 5, DataLayout,IndexType> tensor(tensorRange);\n\n  Tensor<DataType, 4, DataLayout,IndexType> chip1(chip1TensorRange);\n  Tensor<DataType, 4, DataLayout,IndexType> tensor1(chip1TensorRange);\n  tensor.setRandom();\n  tensor1.setRandom();\n\n  const size_t tensorBuffSize =tensor.size()*sizeof(DataType);\n  const size_t chip1TensorBuffSize =chip1.size()*sizeof(DataType);\n  DataType* gpu_data_tensor  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  DataType* gpu_data_chip1  = static_cast<DataType*>(sycl_device.allocate(chip1TensorBuffSize));\n  DataType* gpu_data_tensor1  = static_cast<DataType*>(sycl_device.allocate(chip1TensorBuffSize));\n\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_tensor(gpu_data_tensor, tensorRange);\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip1(gpu_data_chip1, chip1TensorRange);\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_tensor1(gpu_data_tensor1, chip1TensorRange);\n\n\n  sycl_device.memcpyHostToDevice(gpu_data_tensor, tensor.data(), tensorBuffSize);\n  sycl_device.memcpyHostToDevice(gpu_data_tensor1, tensor1.data(), chip1TensorBuffSize);\n  gpu_chip1.device(sycl_device)=gpu_tensor.template chip<0l>(0l) + gpu_tensor1;\n  sycl_device.memcpyDeviceToHost(chip1.data(), gpu_data_chip1, chip1TensorBuffSize);\n\n  for (int i = 0; i < sizeDim2; ++i) {\n    for (int j = 0; j < sizeDim3; ++j) {\n      for (int k = 0; k < sizeDim4; ++k) {\n        for (int l = 0; l < sizeDim5; ++l) {\n          float expected = tensor(0l,i,j,k,l) + tensor1(i,j,k,l);\n          VERIFY_IS_EQUAL(chip1(i,j,k,l), expected);\n        }\n      }\n    }\n  }\n\n  array<IndexType, 3> chip2TensorRange = {{sizeDim2, sizeDim4, sizeDim5}};\n  Tensor<DataType, 3, DataLayout,IndexType> tensor2(chip2TensorRange);\n  Tensor<DataType, 3, DataLayout,IndexType> chip2(chip2TensorRange);\n  tensor2.setRandom();\n  const size_t chip2TensorBuffSize =tensor2.size()*sizeof(DataType);\n  DataType* gpu_data_tensor2  = static_cast<DataType*>(sycl_device.allocate(chip2TensorBuffSize));\n  DataType* gpu_data_chip2  = static_cast<DataType*>(sycl_device.allocate(chip2TensorBuffSize));\n  TensorMap<Tensor<DataType, 3, DataLayout,IndexType>> gpu_tensor2(gpu_data_tensor2, chip2TensorRange);\n  TensorMap<Tensor<DataType, 3, DataLayout,IndexType>> gpu_chip2(gpu_data_chip2, chip2TensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_tensor2, tensor2.data(), chip2TensorBuffSize);\n  gpu_chip2.device(sycl_device)=gpu_tensor.template chip<0l>(0l).template chip<1l>(2l) + gpu_tensor2;\n  sycl_device.memcpyDeviceToHost(chip2.data(), gpu_data_chip2, chip2TensorBuffSize);\n\n  for (int i = 0; i < sizeDim2; ++i) {\n    for (int j = 0; j < sizeDim4; ++j) {\n      for (int k = 0; k < sizeDim5; ++k) {\n        float expected = tensor(0l,i,2l,j,k) + tensor2(i,j,k);\n        VERIFY_IS_EQUAL(chip2(i,j,k), expected);\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data_tensor);\n  sycl_device.deallocate(gpu_data_tensor1);\n  sycl_device.deallocate(gpu_data_chip1);\n  sycl_device.deallocate(gpu_data_tensor2);\n  sycl_device.deallocate(gpu_data_chip2);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_chip_as_lvalue_sycl(const Eigen::SyclDevice& sycl_device)\n{\n\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  IndexType sizeDim5 = 11;\n\n  array<IndexType, 5> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4, sizeDim5}};\n  array<IndexType, 4> input2TensorRange = {{sizeDim2, sizeDim3, sizeDim4, sizeDim5}};\n\n  Tensor<DataType, 5, DataLayout,IndexType> tensor(tensorRange);\n  Tensor<DataType, 5, DataLayout,IndexType> input1(tensorRange);\n  Tensor<DataType, 4, DataLayout,IndexType> input2(input2TensorRange);\n  input1.setRandom();\n  input2.setRandom();\n\n\n  const size_t tensorBuffSize =tensor.size()*sizeof(DataType);\n  const size_t input2TensorBuffSize =input2.size()*sizeof(DataType);\n  std::cout << tensorBuffSize << \" , \"<<  input2TensorBuffSize << std::endl;\n  DataType* gpu_data_tensor  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  DataType* gpu_data_input1  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  DataType* gpu_data_input2  = static_cast<DataType*>(sycl_device.allocate(input2TensorBuffSize));\n\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_tensor(gpu_data_tensor, tensorRange);\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_input1(gpu_data_input1, tensorRange);\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_input2(gpu_data_input2, input2TensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_input1, input1.data(), tensorBuffSize);\n  gpu_tensor.device(sycl_device)=gpu_input1;\n  sycl_device.memcpyHostToDevice(gpu_data_input2, input2.data(), input2TensorBuffSize);\n  gpu_tensor.template chip<0l>(1l).device(sycl_device)=gpu_input2;\n  sycl_device.memcpyDeviceToHost(tensor.data(), gpu_data_tensor, tensorBuffSize);\n\n  for (int i = 0; i < sizeDim1; ++i) {\n    for (int j = 0; j < sizeDim2; ++j) {\n      for (int k = 0; k < sizeDim3; ++k) {\n        for (int l = 0; l < sizeDim4; ++l) {\n          for (int m = 0; m < sizeDim5; ++m) {\n            if (i != 1) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input2(j,k,l,m));\n            }\n          }\n        }\n      }\n    }\n  }\n\n  gpu_tensor.device(sycl_device)=gpu_input1;\n  array<IndexType, 4> input3TensorRange = {{sizeDim1, sizeDim3, sizeDim4, sizeDim5}};\n  Tensor<DataType, 4, DataLayout,IndexType> input3(input3TensorRange);\n  input3.setRandom();\n\n  const size_t input3TensorBuffSize =input3.size()*sizeof(DataType);\n  DataType* gpu_data_input3  = static_cast<DataType*>(sycl_device.allocate(input3TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_input3(gpu_data_input3, input3TensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_input3, input3.data(), input3TensorBuffSize);\n  gpu_tensor.template chip<1l>(1l).device(sycl_device)=gpu_input3;\n  sycl_device.memcpyDeviceToHost(tensor.data(), gpu_data_tensor, tensorBuffSize);\n\n  for (int i = 0; i < sizeDim1; ++i) {\n    for (int j = 0; j < sizeDim2; ++j) {\n      for (int k = 0; k <sizeDim3; ++k) {\n        for (int l = 0; l < sizeDim4; ++l) {\n          for (int m = 0; m < sizeDim5; ++m) {\n            if (j != 1) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input3(i,k,l,m));\n            }\n          }\n        }\n      }\n    }\n  }\n\n  gpu_tensor.device(sycl_device)=gpu_input1;\n  array<IndexType, 4> input4TensorRange = {{sizeDim1, sizeDim2, sizeDim4, sizeDim5}};\n  Tensor<DataType, 4, DataLayout,IndexType> input4(input4TensorRange);\n  input4.setRandom();\n\n  const size_t input4TensorBuffSize =input4.size()*sizeof(DataType);\n  DataType* gpu_data_input4  = static_cast<DataType*>(sycl_device.allocate(input4TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_input4(gpu_data_input4, input4TensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_input4, input4.data(), input4TensorBuffSize);\n  gpu_tensor.template chip<2l>(3l).device(sycl_device)=gpu_input4;\n  sycl_device.memcpyDeviceToHost(tensor.data(), gpu_data_tensor, tensorBuffSize);\n\n  for (int i = 0; i < sizeDim1; ++i) {\n    for (int j = 0; j < sizeDim2; ++j) {\n      for (int k = 0; k <sizeDim3; ++k) {\n        for (int l = 0; l < sizeDim4; ++l) {\n          for (int m = 0; m < sizeDim5; ++m) {\n            if (k != 3) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input4(i,j,l,m));\n            }\n          }\n        }\n      }\n    }\n  }\n\n  gpu_tensor.device(sycl_device)=gpu_input1;\n  array<IndexType, 4> input5TensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim5}};\n  Tensor<DataType, 4, DataLayout,IndexType> input5(input5TensorRange);\n  input5.setRandom();\n\n  const size_t input5TensorBuffSize =input5.size()*sizeof(DataType);\n  DataType* gpu_data_input5  = static_cast<DataType*>(sycl_device.allocate(input5TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_input5(gpu_data_input5, input5TensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_input5, input5.data(), input5TensorBuffSize);\n  gpu_tensor.template chip<3l>(4l).device(sycl_device)=gpu_input5;\n  sycl_device.memcpyDeviceToHost(tensor.data(), gpu_data_tensor, tensorBuffSize);\n\n  for (int i = 0; i < sizeDim1; ++i) {\n    for (int j = 0; j < sizeDim2; ++j) {\n      for (int k = 0; k <sizeDim3; ++k) {\n        for (int l = 0; l < sizeDim4; ++l) {\n          for (int m = 0; m < sizeDim5; ++m) {\n            if (l != 4) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input5(i,j,k,m));\n            }\n          }\n        }\n      }\n    }\n  }\n  gpu_tensor.device(sycl_device)=gpu_input1;\n  array<IndexType, 4> input6TensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  Tensor<DataType, 4, DataLayout,IndexType> input6(input6TensorRange);\n  input6.setRandom();\n\n  const size_t input6TensorBuffSize =input6.size()*sizeof(DataType);\n  DataType* gpu_data_input6  = static_cast<DataType*>(sycl_device.allocate(input6TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_input6(gpu_data_input6, input6TensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_input6, input6.data(), input6TensorBuffSize);\n  gpu_tensor.template chip<4l>(5l).device(sycl_device)=gpu_input6;\n  sycl_device.memcpyDeviceToHost(tensor.data(), gpu_data_tensor, tensorBuffSize);\n\n  for (int i = 0; i < sizeDim1; ++i) {\n    for (int j = 0; j < sizeDim2; ++j) {\n      for (int k = 0; k <sizeDim3; ++k) {\n        for (int l = 0; l < sizeDim4; ++l) {\n          for (int m = 0; m < sizeDim5; ++m) {\n            if (m != 5) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input6(i,j,k,l));\n            }\n          }\n        }\n      }\n    }\n  }\n\n\n  gpu_tensor.device(sycl_device)=gpu_input1;\n  Tensor<DataType, 5, DataLayout,IndexType> input7(tensorRange);\n  input7.setRandom();\n\n  DataType* gpu_data_input7  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_input7(gpu_data_input7, tensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_input7, input7.data(), tensorBuffSize);\n  gpu_tensor.chip(0l,0l).device(sycl_device)=gpu_input7.chip(0l,0l);\n  sycl_device.memcpyDeviceToHost(tensor.data(), gpu_data_tensor, tensorBuffSize);\n\n  for (int i = 0; i < sizeDim1; ++i) {\n    for (int j = 0; j < sizeDim2; ++j) {\n      for (int k = 0; k <sizeDim3; ++k) {\n        for (int l = 0; l < sizeDim4; ++l) {\n          for (int m = 0; m < sizeDim5; ++m) {\n            if (i != 0) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input7(i,j,k,l,m));\n            }\n          }\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data_tensor);\n  sycl_device.deallocate(gpu_data_input1);\n  sycl_device.deallocate(gpu_data_input2);\n  sycl_device.deallocate(gpu_data_input3);\n  sycl_device.deallocate(gpu_data_input4);\n  sycl_device.deallocate(gpu_data_input5);\n  sycl_device.deallocate(gpu_data_input6);\n  sycl_device.deallocate(gpu_data_input7);\n\n}\n\ntemplate<typename DataType, typename dev_Selector> void sycl_chipping_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n /* test_static_chip_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_static_chip_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_dynamic_chip_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_dynamic_chip_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_chip_in_expr<DataType, RowMajor, int64_t>(sycl_device);\n  test_chip_in_expr<DataType, ColMajor, int64_t>(sycl_device);*/\n  test_chip_as_lvalue_sycl<DataType, RowMajor, int64_t>(sycl_device);\n // test_chip_as_lvalue_sycl<DataType, ColMajor, int64_t>(sycl_device);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_chipping_sycl)\n{\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_chipping_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_comparisons.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\nstatic void test_orderings()\n{\n  Tensor<float, 3> mat1(2,3,7);\n  Tensor<float, 3> mat2(2,3,7);\n  Tensor<bool, 3> lt(2,3,7);\n  Tensor<bool, 3> le(2,3,7);\n  Tensor<bool, 3> gt(2,3,7);\n  Tensor<bool, 3> ge(2,3,7);\n\n  mat1.setRandom();\n  mat2.setRandom();\n\n  lt = mat1 < mat2;\n  le = mat1 <= mat2;\n  gt = mat1 > mat2;\n  ge = mat1 >= mat2;\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(lt(i,j,k), mat1(i,j,k) < mat2(i,j,k));\n        VERIFY_IS_EQUAL(le(i,j,k), mat1(i,j,k) <= mat2(i,j,k));\n        VERIFY_IS_EQUAL(gt(i,j,k), mat1(i,j,k) > mat2(i,j,k));\n        VERIFY_IS_EQUAL(ge(i,j,k), mat1(i,j,k) >= mat2(i,j,k));\n      }\n    }\n  }\n}\n\n\nstatic void test_equality()\n{\n  Tensor<float, 3> mat1(2,3,7);\n  Tensor<float, 3> mat2(2,3,7);\n\n  mat1.setRandom();\n  mat2.setRandom();\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        if (internal::random<bool>()) {\n          mat2(i,j,k) = mat1(i,j,k);\n        }\n      }\n    }\n  }\n\n  Tensor<bool, 3> eq(2,3,7);\n  Tensor<bool, 3> ne(2,3,7);\n  eq = (mat1 == mat2);\n  ne = (mat1 != mat2);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(eq(i,j,k), mat1(i,j,k) == mat2(i,j,k));\n        VERIFY_IS_EQUAL(ne(i,j,k), mat1(i,j,k) != mat2(i,j,k));\n      }\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_comparisons)\n{\n  CALL_SUBTEST(test_orderings());\n  CALL_SUBTEST(test_equality());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_complex_cwise_ops_gpu.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate<typename T>\nvoid test_cuda_complex_cwise_ops() {\n  const int kNumItems = 2;\n  std::size_t complex_bytes = kNumItems * sizeof(std::complex<T>);\n\n  std::complex<T>* d_in1;\n  std::complex<T>* d_in2;\n  std::complex<T>* d_out;\n  cudaMalloc((void**)(&d_in1), complex_bytes);\n  cudaMalloc((void**)(&d_in2), complex_bytes);\n  cudaMalloc((void**)(&d_out), complex_bytes);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<std::complex<T>, 1, 0, int>, Eigen::Aligned> gpu_in1(\n      d_in1, kNumItems);\n  Eigen::TensorMap<Eigen::Tensor<std::complex<T>, 1, 0, int>, Eigen::Aligned> gpu_in2(\n      d_in2, kNumItems);\n  Eigen::TensorMap<Eigen::Tensor<std::complex<T>, 1, 0, int>, Eigen::Aligned> gpu_out(\n      d_out, kNumItems);\n\n  const std::complex<T> a(3.14f, 2.7f);\n  const std::complex<T> b(-10.6f, 1.4f);\n\n  gpu_in1.device(gpu_device) = gpu_in1.constant(a);\n  gpu_in2.device(gpu_device) = gpu_in2.constant(b);\n\n  enum CwiseOp {\n    Add = 0,\n    Sub,\n    Mul,\n    Div,\n    Neg,\n    NbOps\n  };\n\n  Tensor<std::complex<T>, 1, 0, int> actual(kNumItems);\n  for (int op = Add; op < NbOps; op++) {\n    std::complex<T> expected;\n    switch (static_cast<CwiseOp>(op)) {\n      case Add:\n        gpu_out.device(gpu_device) = gpu_in1 + gpu_in2;\n        expected = a + b;\n        break;\n      case Sub:\n        gpu_out.device(gpu_device) = gpu_in1 - gpu_in2;\n        expected = a - b;\n        break;\n      case Mul:\n        gpu_out.device(gpu_device) = gpu_in1 * gpu_in2;\n        expected = a * b;\n        break;\n      case Div:\n        gpu_out.device(gpu_device) = gpu_in1 / gpu_in2;\n        expected = a / b;\n        break;\n      case Neg:\n        gpu_out.device(gpu_device) = -gpu_in1;\n        expected = -a;\n        break;\n      case NbOps:\n        break;\n    }\n    assert(cudaMemcpyAsync(actual.data(), d_out, complex_bytes, cudaMemcpyDeviceToHost,\n                           gpu_device.stream()) == cudaSuccess);\n    assert(cudaStreamSynchronize(gpu_device.stream()) == cudaSuccess);\n\n    for (int i = 0; i < kNumItems; ++i) {\n      VERIFY_IS_APPROX(actual(i), expected);\n    }\n  }\n\n  cudaFree(d_in1);\n  cudaFree(d_in2);\n  cudaFree(d_out);\n}\n\n\nEIGEN_DECLARE_TEST(test_cxx11_tensor_complex_cwise_ops)\n{\n  CALL_SUBTEST(test_cuda_complex_cwise_ops<float>());\n  CALL_SUBTEST(test_cuda_complex_cwise_ops<double>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_complex_gpu.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\nvoid test_cuda_nullary() {\n  Tensor<std::complex<float>, 1, 0, int> in1(2);\n  Tensor<std::complex<float>, 1, 0, int> in2(2);\n  in1.setRandom();\n  in2.setRandom();\n\n  std::size_t float_bytes = in1.size() * sizeof(float);\n  std::size_t complex_bytes = in1.size() * sizeof(std::complex<float>);\n\n  std::complex<float>* d_in1;\n  std::complex<float>* d_in2;\n  float* d_out2;\n  cudaMalloc((void**)(&d_in1), complex_bytes);\n  cudaMalloc((void**)(&d_in2), complex_bytes);\n  cudaMalloc((void**)(&d_out2), float_bytes);\n  cudaMemcpy(d_in1, in1.data(), complex_bytes, cudaMemcpyHostToDevice);\n  cudaMemcpy(d_in2, in2.data(), complex_bytes, cudaMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<std::complex<float>, 1, 0, int>, Eigen::Aligned> gpu_in1(\n      d_in1, 2);\n  Eigen::TensorMap<Eigen::Tensor<std::complex<float>, 1, 0, int>, Eigen::Aligned> gpu_in2(\n      d_in2, 2);\n  Eigen::TensorMap<Eigen::Tensor<float, 1, 0, int>, Eigen::Aligned> gpu_out2(\n      d_out2, 2);\n\n  gpu_in1.device(gpu_device) = gpu_in1.constant(std::complex<float>(3.14f, 2.7f));\n  gpu_out2.device(gpu_device) = gpu_in2.abs();\n\n  Tensor<std::complex<float>, 1, 0, int> new1(2);\n  Tensor<float, 1, 0, int> new2(2);\n\n  assert(cudaMemcpyAsync(new1.data(), d_in1, complex_bytes, cudaMemcpyDeviceToHost,\n                         gpu_device.stream()) == cudaSuccess);\n  assert(cudaMemcpyAsync(new2.data(), d_out2, float_bytes, cudaMemcpyDeviceToHost,\n                         gpu_device.stream()) == cudaSuccess);\n\n  assert(cudaStreamSynchronize(gpu_device.stream()) == cudaSuccess);\n\n  for (int i = 0; i < 2; ++i) {\n    VERIFY_IS_APPROX(new1(i), std::complex<float>(3.14f, 2.7f));\n    VERIFY_IS_APPROX(new2(i), std::abs(in2(i)));\n  }\n\n  cudaFree(d_in1);\n  cudaFree(d_in2);\n  cudaFree(d_out2);\n}\n\n\nstatic void test_cuda_sum_reductions() {\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  const int num_rows = internal::random<int>(1024, 5*1024);\n  const int num_cols = internal::random<int>(1024, 5*1024);\n\n  Tensor<std::complex<float>, 2> in(num_rows, num_cols);\n  in.setRandom();\n\n  Tensor<std::complex<float>, 0> full_redux;\n  full_redux = in.sum();\n\n  std::size_t in_bytes = in.size() * sizeof(std::complex<float>);\n  std::size_t out_bytes = full_redux.size() * sizeof(std::complex<float>);\n  std::complex<float>* gpu_in_ptr = static_cast<std::complex<float>*>(gpu_device.allocate(in_bytes));\n  std::complex<float>* gpu_out_ptr = static_cast<std::complex<float>*>(gpu_device.allocate(out_bytes));\n  gpu_device.memcpyHostToDevice(gpu_in_ptr, in.data(), in_bytes);\n\n  TensorMap<Tensor<std::complex<float>, 2> > in_gpu(gpu_in_ptr, num_rows, num_cols);\n  TensorMap<Tensor<std::complex<float>, 0> > out_gpu(gpu_out_ptr);\n\n  out_gpu.device(gpu_device) = in_gpu.sum();\n\n  Tensor<std::complex<float>, 0> full_redux_gpu;\n  gpu_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_ptr, out_bytes);\n  gpu_device.synchronize();\n\n  // Check that the CPU and GPU reductions return the same result.\n  VERIFY_IS_APPROX(full_redux(), full_redux_gpu());\n\n  gpu_device.deallocate(gpu_in_ptr);\n  gpu_device.deallocate(gpu_out_ptr);\n}\n\nstatic void test_cuda_mean_reductions() {\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  const int num_rows = internal::random<int>(1024, 5*1024);\n  const int num_cols = internal::random<int>(1024, 5*1024);\n\n  Tensor<std::complex<float>, 2> in(num_rows, num_cols);\n  in.setRandom();\n\n  Tensor<std::complex<float>, 0> full_redux;\n  full_redux = in.mean();\n\n  std::size_t in_bytes = in.size() * sizeof(std::complex<float>);\n  std::size_t out_bytes = full_redux.size() * sizeof(std::complex<float>);\n  std::complex<float>* gpu_in_ptr = static_cast<std::complex<float>*>(gpu_device.allocate(in_bytes));\n  std::complex<float>* gpu_out_ptr = static_cast<std::complex<float>*>(gpu_device.allocate(out_bytes));\n  gpu_device.memcpyHostToDevice(gpu_in_ptr, in.data(), in_bytes);\n\n  TensorMap<Tensor<std::complex<float>, 2> > in_gpu(gpu_in_ptr, num_rows, num_cols);\n  TensorMap<Tensor<std::complex<float>, 0> > out_gpu(gpu_out_ptr);\n\n  out_gpu.device(gpu_device) = in_gpu.mean();\n\n  Tensor<std::complex<float>, 0> full_redux_gpu;\n  gpu_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_ptr, out_bytes);\n  gpu_device.synchronize();\n\n  // Check that the CPU and GPU reductions return the same result.\n  VERIFY_IS_APPROX(full_redux(), full_redux_gpu());\n\n  gpu_device.deallocate(gpu_in_ptr);\n  gpu_device.deallocate(gpu_out_ptr);\n}\n\nstatic void test_cuda_product_reductions() {\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  const int num_rows = internal::random<int>(1024, 5*1024);\n  const int num_cols = internal::random<int>(1024, 5*1024);\n\n  Tensor<std::complex<float>, 2> in(num_rows, num_cols);\n  in.setRandom();\n\n  Tensor<std::complex<float>, 0> full_redux;\n  full_redux = in.prod();\n\n  std::size_t in_bytes = in.size() * sizeof(std::complex<float>);\n  std::size_t out_bytes = full_redux.size() * sizeof(std::complex<float>);\n  std::complex<float>* gpu_in_ptr = static_cast<std::complex<float>*>(gpu_device.allocate(in_bytes));\n  std::complex<float>* gpu_out_ptr = static_cast<std::complex<float>*>(gpu_device.allocate(out_bytes));\n  gpu_device.memcpyHostToDevice(gpu_in_ptr, in.data(), in_bytes);\n\n  TensorMap<Tensor<std::complex<float>, 2> > in_gpu(gpu_in_ptr, num_rows, num_cols);\n  TensorMap<Tensor<std::complex<float>, 0> > out_gpu(gpu_out_ptr);\n\n  out_gpu.device(gpu_device) = in_gpu.prod();\n\n  Tensor<std::complex<float>, 0> full_redux_gpu;\n  gpu_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_ptr, out_bytes);\n  gpu_device.synchronize();\n\n  // Check that the CPU and GPU reductions return the same result.\n  VERIFY_IS_APPROX(full_redux(), full_redux_gpu());\n\n  gpu_device.deallocate(gpu_in_ptr);\n  gpu_device.deallocate(gpu_out_ptr);\n}\n\n\nEIGEN_DECLARE_TEST(test_cxx11_tensor_complex)\n{\n  CALL_SUBTEST(test_cuda_nullary());\n  CALL_SUBTEST(test_cuda_sum_reductions());\n  CALL_SUBTEST(test_cuda_mean_reductions());\n  CALL_SUBTEST(test_cuda_product_reductions());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_concatenation.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate<int DataLayout>\nstatic void test_dimension_failures()\n{\n  Tensor<int, 3, DataLayout> left(2, 3, 1);\n  Tensor<int, 3, DataLayout> right(3, 3, 1);\n  left.setRandom();\n  right.setRandom();\n\n  // Okay; other dimensions are equal.\n  Tensor<int, 3, DataLayout> concatenation = left.concatenate(right, 0);\n\n  // Dimension mismatches.\n  VERIFY_RAISES_ASSERT(concatenation = left.concatenate(right, 1));\n  VERIFY_RAISES_ASSERT(concatenation = left.concatenate(right, 2));\n\n  // Axis > NumDims or < 0.\n  VERIFY_RAISES_ASSERT(concatenation = left.concatenate(right, 3));\n  VERIFY_RAISES_ASSERT(concatenation = left.concatenate(right, -1));\n}\n\ntemplate<int DataLayout>\nstatic void test_static_dimension_failure()\n{\n  Tensor<int, 2, DataLayout> left(2, 3);\n  Tensor<int, 3, DataLayout> right(2, 3, 1);\n\n#ifdef CXX11_TENSOR_CONCATENATION_STATIC_DIMENSION_FAILURE\n  // Technically compatible, but we static assert that the inputs have same\n  // NumDims.\n  Tensor<int, 3, DataLayout> concatenation = left.concatenate(right, 0);\n#endif\n\n  // This can be worked around in this case.\n  Tensor<int, 3, DataLayout> concatenation = left\n      .reshape(Tensor<int, 3>::Dimensions(2, 3, 1))\n      .concatenate(right, 0);\n  Tensor<int, 2, DataLayout> alternative = left\n   // Clang compiler break with {{{}}} with an ambiguous error on copy constructor\n  // the variadic DSize constructor added for #ifndef EIGEN_EMULATE_CXX11_META_H.\n  // Solution:\n  // either the code should change to \n  //  Tensor<int, 2>::Dimensions{{2, 3}}\n  // or Tensor<int, 2>::Dimensions{Tensor<int, 2>::Dimensions{{2, 3}}}\n      .concatenate(right.reshape(Tensor<int, 2>::Dimensions(2, 3)), 0);\n}\n\ntemplate<int DataLayout>\nstatic void test_simple_concatenation()\n{\n  Tensor<int, 3, DataLayout> left(2, 3, 1);\n  Tensor<int, 3, DataLayout> right(2, 3, 1);\n  left.setRandom();\n  right.setRandom();\n\n  Tensor<int, 3, DataLayout> concatenation = left.concatenate(right, 0);\n  VERIFY_IS_EQUAL(concatenation.dimension(0), 4);\n  VERIFY_IS_EQUAL(concatenation.dimension(1), 3);\n  VERIFY_IS_EQUAL(concatenation.dimension(2), 1);\n  for (int j = 0; j < 3; ++j) {\n    for (int i = 0; i < 2; ++i) {\n      VERIFY_IS_EQUAL(concatenation(i, j, 0), left(i, j, 0));\n    }\n    for (int i = 2; i < 4; ++i) {\n      VERIFY_IS_EQUAL(concatenation(i, j, 0), right(i - 2, j, 0));\n    }\n  }\n\n  concatenation = left.concatenate(right, 1);\n  VERIFY_IS_EQUAL(concatenation.dimension(0), 2);\n  VERIFY_IS_EQUAL(concatenation.dimension(1), 6);\n  VERIFY_IS_EQUAL(concatenation.dimension(2), 1);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_EQUAL(concatenation(i, j, 0), left(i, j, 0));\n    }\n    for (int j = 3; j < 6; ++j) {\n      VERIFY_IS_EQUAL(concatenation(i, j, 0), right(i, j - 3, 0));\n    }\n  }\n\n  concatenation = left.concatenate(right, 2);\n  VERIFY_IS_EQUAL(concatenation.dimension(0), 2);\n  VERIFY_IS_EQUAL(concatenation.dimension(1), 3);\n  VERIFY_IS_EQUAL(concatenation.dimension(2), 2);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_EQUAL(concatenation(i, j, 0), left(i, j, 0));\n      VERIFY_IS_EQUAL(concatenation(i, j, 1), right(i, j, 0));\n    }\n  }\n}\n\n\n// TODO(phli): Add test once we have a real vectorized implementation.\n// static void test_vectorized_concatenation() {}\n\nstatic void test_concatenation_as_lvalue()\n{\n  Tensor<int, 2> t1(2, 3);\n  Tensor<int, 2> t2(2, 3);\n  t1.setRandom();\n  t2.setRandom();\n\n  Tensor<int, 2> result(4, 3);\n  result.setRandom();\n  t1.concatenate(t2, 0) = result;\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_EQUAL(t1(i, j), result(i, j));\n      VERIFY_IS_EQUAL(t2(i, j), result(i+2, j));\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_concatenation)\n{\n   CALL_SUBTEST(test_dimension_failures<ColMajor>());\n   CALL_SUBTEST(test_dimension_failures<RowMajor>());\n   CALL_SUBTEST(test_static_dimension_failure<ColMajor>());\n   CALL_SUBTEST(test_static_dimension_failure<RowMajor>());\n   CALL_SUBTEST(test_simple_concatenation<ColMajor>());\n   CALL_SUBTEST(test_simple_concatenation<RowMajor>());\n   // CALL_SUBTEST(test_vectorized_concatenation());\n   CALL_SUBTEST(test_concatenation_as_lvalue());\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_concatenation_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate<typename DataType, int DataLayout, typename IndexType>\nstatic void test_simple_concatenation(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType leftDim1 = 2;\n  IndexType leftDim2 = 3;\n  IndexType leftDim3 = 1;\n  Eigen::array<IndexType, 3> leftRange = {{leftDim1, leftDim2, leftDim3}};\n  IndexType rightDim1 = 2;\n  IndexType rightDim2 = 3;\n  IndexType rightDim3 = 1;\n  Eigen::array<IndexType, 3> rightRange = {{rightDim1, rightDim2, rightDim3}};\n\n  //IndexType concatDim1 = 3;\n//\tIndexType concatDim2 = 3;\n//\tIndexType concatDim3 = 1;\n  //Eigen::array<IndexType, 3> concatRange = {{concatDim1, concatDim2, concatDim3}};\n\n  Tensor<DataType, 3, DataLayout, IndexType> left(leftRange);\n  Tensor<DataType, 3, DataLayout, IndexType> right(rightRange);\n  left.setRandom();\n  right.setRandom();\n\n  DataType * gpu_in1_data  = static_cast<DataType*>(sycl_device.allocate(left.dimensions().TotalSize()*sizeof(DataType)));\n  DataType * gpu_in2_data  = static_cast<DataType*>(sycl_device.allocate(right.dimensions().TotalSize()*sizeof(DataType)));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType>> gpu_in1(gpu_in1_data, leftRange);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType>> gpu_in2(gpu_in2_data, rightRange);\n  sycl_device.memcpyHostToDevice(gpu_in1_data, left.data(),(left.dimensions().TotalSize())*sizeof(DataType));\n  sycl_device.memcpyHostToDevice(gpu_in2_data, right.data(),(right.dimensions().TotalSize())*sizeof(DataType));\n  ///\n  Tensor<DataType, 3, DataLayout, IndexType> concatenation1(leftDim1+rightDim1, leftDim2, leftDim3);\n  DataType * gpu_out_data1 =  static_cast<DataType*>(sycl_device.allocate(concatenation1.dimensions().TotalSize()*sizeof(DataType)));\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType>> gpu_out1(gpu_out_data1, concatenation1.dimensions());\n\n  //concatenation = left.concatenate(right, 0);\n  gpu_out1.device(sycl_device) =gpu_in1.concatenate(gpu_in2, 0);\n  sycl_device.memcpyDeviceToHost(concatenation1.data(), gpu_out_data1,(concatenation1.dimensions().TotalSize())*sizeof(DataType));\n\n  VERIFY_IS_EQUAL(concatenation1.dimension(0), 4);\n  VERIFY_IS_EQUAL(concatenation1.dimension(1), 3);\n  VERIFY_IS_EQUAL(concatenation1.dimension(2), 1);\n  for (IndexType j = 0; j < 3; ++j) {\n    for (IndexType i = 0; i < 2; ++i) {\n      VERIFY_IS_EQUAL(concatenation1(i, j, 0), left(i, j, 0));\n    }\n    for (IndexType i = 2; i < 4; ++i) {\n      VERIFY_IS_EQUAL(concatenation1(i, j, 0), right(i - 2, j, 0));\n    }\n  }\n\n  sycl_device.deallocate(gpu_out_data1);\n  Tensor<DataType, 3, DataLayout, IndexType> concatenation2(leftDim1, leftDim2 +rightDim2, leftDim3);\n  DataType * gpu_out_data2 =  static_cast<DataType*>(sycl_device.allocate(concatenation2.dimensions().TotalSize()*sizeof(DataType)));\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType>> gpu_out2(gpu_out_data2, concatenation2.dimensions());\n  gpu_out2.device(sycl_device) =gpu_in1.concatenate(gpu_in2, 1);\n  sycl_device.memcpyDeviceToHost(concatenation2.data(), gpu_out_data2,(concatenation2.dimensions().TotalSize())*sizeof(DataType));\n\n  //concatenation = left.concatenate(right, 1);\n  VERIFY_IS_EQUAL(concatenation2.dimension(0), 2);\n  VERIFY_IS_EQUAL(concatenation2.dimension(1), 6);\n  VERIFY_IS_EQUAL(concatenation2.dimension(2), 1);\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      VERIFY_IS_EQUAL(concatenation2(i, j, 0), left(i, j, 0));\n    }\n    for (IndexType j = 3; j < 6; ++j) {\n      VERIFY_IS_EQUAL(concatenation2(i, j, 0), right(i, j - 3, 0));\n    }\n  }\n  sycl_device.deallocate(gpu_out_data2);\n  Tensor<DataType, 3, DataLayout, IndexType> concatenation3(leftDim1, leftDim2, leftDim3+rightDim3);\n  DataType * gpu_out_data3 =  static_cast<DataType*>(sycl_device.allocate(concatenation3.dimensions().TotalSize()*sizeof(DataType)));\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType>> gpu_out3(gpu_out_data3, concatenation3.dimensions());\n  gpu_out3.device(sycl_device) =gpu_in1.concatenate(gpu_in2, 2);\n  sycl_device.memcpyDeviceToHost(concatenation3.data(), gpu_out_data3,(concatenation3.dimensions().TotalSize())*sizeof(DataType));\n\n  //concatenation = left.concatenate(right, 2);\n  VERIFY_IS_EQUAL(concatenation3.dimension(0), 2);\n  VERIFY_IS_EQUAL(concatenation3.dimension(1), 3);\n  VERIFY_IS_EQUAL(concatenation3.dimension(2), 2);\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      VERIFY_IS_EQUAL(concatenation3(i, j, 0), left(i, j, 0));\n      VERIFY_IS_EQUAL(concatenation3(i, j, 1), right(i, j, 0));\n    }\n  }\n  sycl_device.deallocate(gpu_out_data3);\n  sycl_device.deallocate(gpu_in1_data);\n  sycl_device.deallocate(gpu_in2_data);\n}\ntemplate<typename DataType, int DataLayout, typename IndexType>\nstatic void test_concatenation_as_lvalue(const Eigen::SyclDevice& sycl_device)\n{\n\n  IndexType leftDim1 = 2;\n  IndexType leftDim2 = 3;\n  Eigen::array<IndexType, 2> leftRange = {{leftDim1, leftDim2}};\n\n  IndexType rightDim1 = 2;\n  IndexType rightDim2 = 3;\n  Eigen::array<IndexType, 2> rightRange = {{rightDim1, rightDim2}};\n\n  IndexType concatDim1 = 4;\n  IndexType concatDim2 = 3;\n  Eigen::array<IndexType, 2> resRange = {{concatDim1, concatDim2}};\n\n  Tensor<DataType, 2, DataLayout, IndexType> left(leftRange);\n  Tensor<DataType, 2, DataLayout, IndexType> right(rightRange);\n  Tensor<DataType, 2, DataLayout, IndexType> result(resRange);\n\n  left.setRandom();\n  right.setRandom();\n  result.setRandom();\n\n  DataType * gpu_in1_data  = static_cast<DataType*>(sycl_device.allocate(left.dimensions().TotalSize()*sizeof(DataType)));\n  DataType * gpu_in2_data  = static_cast<DataType*>(sycl_device.allocate(right.dimensions().TotalSize()*sizeof(DataType)));\n  DataType * gpu_out_data =  static_cast<DataType*>(sycl_device.allocate(result.dimensions().TotalSize()*sizeof(DataType)));\n\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>> gpu_in1(gpu_in1_data, leftRange);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>> gpu_in2(gpu_in2_data, rightRange);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>> gpu_out(gpu_out_data, resRange);\n\n  sycl_device.memcpyHostToDevice(gpu_in1_data, left.data(),(left.dimensions().TotalSize())*sizeof(DataType));\n  sycl_device.memcpyHostToDevice(gpu_in2_data, right.data(),(right.dimensions().TotalSize())*sizeof(DataType));\n  sycl_device.memcpyHostToDevice(gpu_out_data, result.data(),(result.dimensions().TotalSize())*sizeof(DataType));\n\n//  t1.concatenate(t2, 0) = result;\n gpu_in1.concatenate(gpu_in2, 0).device(sycl_device) =gpu_out;\n sycl_device.memcpyDeviceToHost(left.data(), gpu_in1_data,(left.dimensions().TotalSize())*sizeof(DataType));\n sycl_device.memcpyDeviceToHost(right.data(), gpu_in2_data,(right.dimensions().TotalSize())*sizeof(DataType));\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      VERIFY_IS_EQUAL(left(i, j), result(i, j));\n      VERIFY_IS_EQUAL(right(i, j), result(i+2, j));\n    }\n  }\n  sycl_device.deallocate(gpu_in1_data);\n  sycl_device.deallocate(gpu_in2_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\n\ntemplate <typename DataType, typename Dev_selector> void tensorConcat_perDevice(Dev_selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_simple_concatenation<DataType, RowMajor, int64_t>(sycl_device);\n  test_simple_concatenation<DataType, ColMajor, int64_t>(sycl_device);\n  test_concatenation_as_lvalue<DataType, ColMajor, int64_t>(sycl_device);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_concatenation_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(tensorConcat_perDevice<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_const.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\nusing Eigen::Tensor;\n\n\nstatic void test_simple_assign()\n{\n  Tensor<int, 3> random(2,3,7);\n  random.setRandom();\n\n  TensorMap<Tensor<const int, 3> > constant(random.data(), 2, 3, 7);\n  Tensor<int, 3> result(2,3,7);\n  result = constant;\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL((result(i,j,k)), random(i,j,k));\n      }\n    }\n  }\n}\n\n\nstatic void test_assign_of_const_tensor()\n{\n  Tensor<int, 3> random(2,3,7);\n  random.setRandom();\n\n  TensorMap<Tensor<const int, 3> > constant1(random.data(), 2, 3, 7);\n  TensorMap<const Tensor<int, 3> > constant2(random.data(), 2, 3, 7);\n  const TensorMap<Tensor<int, 3> > constant3(random.data(), 2, 3, 7);\n\n  Tensor<int, 2> result1 = constant1.chip(0, 2);\n  Tensor<int, 2> result2 = constant2.chip(0, 2);\n  Tensor<int, 2> result3 = constant3.chip(0, 2);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_EQUAL((result1(i,j)), random(i,j,0));\n      VERIFY_IS_EQUAL((result2(i,j)), random(i,j,0));\n      VERIFY_IS_EQUAL((result3(i,j)), random(i,j,0));\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_const)\n{\n  CALL_SUBTEST(test_simple_assign());\n  CALL_SUBTEST(test_assign_of_const_tensor());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_contract_gpu.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n// Copyright (C) 2014 Navdeep Jaitly <ndjaitly@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\n#include <unsupported/Eigen/CXX11/src/Tensor/TensorGpuHipCudaDefines.h>\n\nusing Eigen::Tensor;\ntypedef Tensor<float, 1>::DimensionPair DimPair;\n\ntemplate<int DataLayout>\nvoid test_gpu_contraction(int m_size, int k_size, int n_size)\n{\n  std::cout << \"Testing for (\" << m_size << \",\" << k_size << \",\" << n_size << \")\" << std::endl;\n  // with these dimensions, the output has 300 * 140 elements, which is\n  // more than 30 * 1024, which is the number of threads in blocks on\n  // a 15 SM GK110 GPU\n  Tensor<float, 2, DataLayout> t_left(m_size, k_size);\n  Tensor<float, 2, DataLayout> t_right(k_size, n_size);\n  Tensor<float, 2, DataLayout> t_result(m_size, n_size);\n  Tensor<float, 2, DataLayout> t_result_gpu(m_size, n_size);\n  Eigen::array<DimPair, 1> dims(DimPair(1, 0));\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  std::size_t t_left_bytes = t_left.size()  * sizeof(float);\n  std::size_t t_right_bytes = t_right.size() * sizeof(float);\n  std::size_t t_result_bytes = t_result.size() * sizeof(float);\n\n  float* d_t_left;\n  float* d_t_right;\n  float* d_t_result;\n\n  gpuMalloc((void**)(&d_t_left), t_left_bytes);\n  gpuMalloc((void**)(&d_t_right), t_right_bytes);\n  gpuMalloc((void**)(&d_t_result), t_result_bytes);\n\n  gpuMemcpy(d_t_left, t_left.data(), t_left_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_t_right, t_right.data(), t_right_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 2, DataLayout> >\n      gpu_t_left(d_t_left, Eigen::array<int, 2>(m_size, k_size));\n  Eigen::TensorMap<Eigen::Tensor<float, 2, DataLayout> >\n      gpu_t_right(d_t_right, Eigen::array<int, 2>(k_size, n_size));\n  Eigen::TensorMap<Eigen::Tensor<float, 2, DataLayout> >\n      gpu_t_result(d_t_result, Eigen::array<int, 2>(m_size, n_size));\n\n\n  gpu_t_result.device(gpu_device) = gpu_t_left.contract(gpu_t_right, dims);\n  t_result = t_left.contract(t_right, dims);\n\n  gpuMemcpy(t_result_gpu.data(), d_t_result, t_result_bytes, gpuMemcpyDeviceToHost);\n  for (DenseIndex i = 0; i < t_result.size(); i++) {\n    if (fabs(t_result(i) - t_result_gpu(i)) < 1e-4f) {\n      continue;\n    }\n    if (Eigen::internal::isApprox(t_result(i), t_result_gpu(i), 1e-4f)) {\n      continue;\n    }\n    std::cout << \"mismatch detected at index \" << i << \": \" << t_result(i)\n              << \" vs \" <<  t_result_gpu(i) << std::endl;\n    assert(false);\n  }\n\n  gpuFree((void*)d_t_left);\n  gpuFree((void*)d_t_right);\n  gpuFree((void*)d_t_result);\n}\n\n\ntemplate<int DataLayout>\nvoid test_scalar(int m_size, int k_size, int n_size)\n{\n  std::cout << \"Testing for (\" << m_size << \",\" << k_size << \",\" << n_size << \")\" << std::endl;\n  // with these dimensions, the output has 300 * 140 elements, which is\n  // more than 30 * 1024, which is the number of threads in blocks on\n  // a 15 SM GK110 GPU\n  Tensor<float, 2, DataLayout> t_left(m_size, k_size);\n  Tensor<float, 2, DataLayout> t_right(k_size, n_size);\n  Tensor<float, 0, DataLayout> t_result;\n  Tensor<float, 0, DataLayout> t_result_gpu;\n  Eigen::array<DimPair, 2> dims(DimPair(0, 0), DimPair(1, 1));\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  std::size_t t_left_bytes = t_left.size()  * sizeof(float);\n  std::size_t t_right_bytes = t_right.size() * sizeof(float);\n  std::size_t t_result_bytes = sizeof(float);\n\n  float* d_t_left;\n  float* d_t_right;\n  float* d_t_result;\n\n  gpuMalloc((void**)(&d_t_left), t_left_bytes);\n  gpuMalloc((void**)(&d_t_right), t_right_bytes);\n  gpuMalloc((void**)(&d_t_result), t_result_bytes);\n\n  gpuMemcpy(d_t_left, t_left.data(), t_left_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_t_right, t_right.data(), t_right_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 2, DataLayout> >\n      gpu_t_left(d_t_left, m_size, k_size);\n  Eigen::TensorMap<Eigen::Tensor<float, 2, DataLayout> >\n      gpu_t_right(d_t_right, k_size, n_size);\n  Eigen::TensorMap<Eigen::Tensor<float, 0, DataLayout> >\n      gpu_t_result(d_t_result);\n\n  gpu_t_result.device(gpu_device) = gpu_t_left.contract(gpu_t_right, dims);\n  t_result = t_left.contract(t_right, dims);\n\n  gpuMemcpy(t_result_gpu.data(), d_t_result, t_result_bytes, gpuMemcpyDeviceToHost);\n  if (fabs(t_result() - t_result_gpu()) > 1e-4f &&\n      !Eigen::internal::isApprox(t_result(), t_result_gpu(), 1e-4f)) {\n    std::cout << \"mismatch detected: \" << t_result()\n              << \" vs \" <<  t_result_gpu() << std::endl;\n    assert(false);\n  }\n\n  gpuFree((void*)d_t_left);\n  gpuFree((void*)d_t_right);\n  gpuFree((void*)d_t_result);\n}\n\n\ntemplate<int DataLayout>\nvoid test_gpu_contraction_m() {\n  for (int k = 32; k < 256; k++) {\n    test_gpu_contraction<ColMajor>(k, 128, 128);\n    test_gpu_contraction<RowMajor>(k, 128, 128);\n  }\n}\n\ntemplate<int DataLayout>\nvoid test_gpu_contraction_k() {\n  for (int k = 32; k < 256; k++) {\n    test_gpu_contraction<ColMajor>(128, k, 128);\n    test_gpu_contraction<RowMajor>(128, k, 128);\n  }\n}\n\ntemplate<int DataLayout>\nvoid test_gpu_contraction_n() {\n  for (int k = 32; k < 256; k++) {\n    test_gpu_contraction<ColMajor>(128, 128, k);\n    test_gpu_contraction<RowMajor>(128, 128, k);\n  }\n}\n\n\ntemplate<int DataLayout>\nvoid test_gpu_contraction_sizes() {\n  int m_sizes[] = { 31,  39,   63,   64,   65,\n                   127, 129,  255,  257 , 511,\n                   512, 513, 1023, 1024, 1025};\n\n  int n_sizes[] = { 31,  39,   63,   64,   65,\n                   127, 129,  255,  257,  511,\n                   512, 513, 1023, 1024, 1025};\n\n  int k_sizes[] = {  31,   39,  63,  64,   65,\n                     95,   96, 127, 129,  255,\n                    257,  511, 512, 513, 1023,\n                   1024, 1025};\n\n  for (int i = 0; i < 15; i++) {\n    for (int j = 0; j < 15; j++) {\n      for (int k = 0; k < 17; k++) {\n        test_gpu_contraction<DataLayout>(m_sizes[i], n_sizes[j], k_sizes[k]);\n      }\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_contract_gpu)\n{\n  CALL_SUBTEST_1(test_gpu_contraction<ColMajor>(128, 128, 128));\n  CALL_SUBTEST_1(test_gpu_contraction<RowMajor>(128, 128, 128));\n\n  CALL_SUBTEST_1(test_scalar<ColMajor>(128, 128, 128));\n  CALL_SUBTEST_1(test_scalar<RowMajor>(128, 128, 128));\n\n  CALL_SUBTEST_2(test_gpu_contraction_m<ColMajor>());\n  CALL_SUBTEST_3(test_gpu_contraction_m<RowMajor>());\n\n  CALL_SUBTEST_4(test_gpu_contraction_k<ColMajor>());\n  CALL_SUBTEST_5(test_gpu_contraction_k<RowMajor>());\n\n  CALL_SUBTEST_6(test_gpu_contraction_n<ColMajor>());\n  CALL_SUBTEST_7(test_gpu_contraction_n<RowMajor>());\n\n#if !defined(EIGEN_USE_HIP)\n// disable these subtests for HIP\n  CALL_SUBTEST_8(test_gpu_contraction_sizes<ColMajor>());\n  CALL_SUBTEST_9(test_gpu_contraction_sizes<RowMajor>());\n#endif\t\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_contract_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include <algorithm>\n#include <chrono>\n#include <ctime>\n#include <iostream>\n\n#include \"main.h\"\n\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid static test_sycl_contraction(const Device &sycl_device, IndexType m_size,\n                                  IndexType k_size, IndexType n_size) {\n  typedef typename Tensor<DataType, 1, DataLayout, IndexType>::DimensionPair\n      DimPair;\n  static const DataType error_threshold = DataType(1e-4);\n  // with these dimensions, the output has 300 * 140 elements, which is\n  // more than 30 * 1024, which is the number of threads in blocks on\n  // a 15 SM GK110 GPU\n  Tensor<DataType, 2, DataLayout, IndexType> t_left(m_size, k_size);\n  Tensor<DataType, 2, DataLayout, IndexType> t_right(k_size, n_size);\n  Tensor<DataType, 2, DataLayout, IndexType> t_result(m_size, n_size);\n  Tensor<DataType, 2, DataLayout, IndexType> t_result_gpu(m_size, n_size);\n  Eigen::array<DimPair, 1> dims = {{DimPair(1, 0)}};\n  Eigen::array<IndexType, 2> left_dims = {{m_size, k_size}};\n  Eigen::array<IndexType, 2> right_dims = {{k_size, n_size}};\n  Eigen::array<IndexType, 2> result_dims = {{m_size, n_size}};\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  std::size_t t_left_bytes = t_left.size() * sizeof(DataType);\n  std::size_t t_right_bytes = t_right.size() * sizeof(DataType);\n  std::size_t t_result_bytes = t_result.size() * sizeof(DataType);\n\n  DataType *d_t_left =\n      static_cast<DataType *>(sycl_device.allocate(t_left_bytes));\n  DataType *d_t_right =\n      static_cast<DataType *>(sycl_device.allocate(t_right_bytes));\n  DataType *d_t_result =\n      static_cast<DataType *>(sycl_device.allocate(t_result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_left(d_t_left, left_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_right(d_t_right, right_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_result(d_t_result, result_dims);\n\n  sycl_device.memcpyHostToDevice(d_t_left, t_left.data(), t_left_bytes);\n  sycl_device.memcpyHostToDevice(d_t_right, t_right.data(), t_right_bytes);\n\n  gpu_t_result.device(sycl_device) = gpu_t_left.contract(gpu_t_right, dims);\n  sycl_device.memcpyDeviceToHost(t_result_gpu.data(), d_t_result,\n                                 t_result_bytes);\n\n  t_result = t_left.contract(t_right, dims);\n\n  for (IndexType i = 0; i < t_result.size(); i++) {\n    if (static_cast<DataType>(std::fabs(static_cast<DataType>(\n            t_result(i) - t_result_gpu(i)))) < error_threshold) {\n      continue;\n    }\n    if (Eigen::internal::isApprox(t_result(i), t_result_gpu(i),\n                                  error_threshold)) {\n      continue;\n    }\n\n    std::cout << \"M : \" << m_size << \", N : \" << n_size << \", K : \" << k_size\n              << \", mismatch detected at IndexType \" << i << \": \" << t_result(i)\n              << \" vs \" << t_result_gpu(i) << std::endl;\n    VERIFY_IS_APPROX(t_result_gpu(i), t_result(i));\n  }\n  sycl_device.deallocate(d_t_left);\n  sycl_device.deallocate(d_t_right);\n  sycl_device.deallocate(d_t_result);\n}\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid test_sycl_contraction_m(const Device &sycl_device) {\n  for (IndexType k = 32; k < 256; k++) {\n    test_sycl_contraction<DataLayout, DataType, IndexType>(sycl_device, k, 128,\n                                                           128);\n  }\n}\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid test_sycl_contraction_k(const Device &sycl_device) {\n  for (IndexType k = 32; k < 256; k++) {\n    test_sycl_contraction<DataLayout, DataType, IndexType>(sycl_device, 128, k,\n                                                           128);\n  }\n}\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid test_sycl_contraction_n(const Device &sycl_device) {\n  for (IndexType k = 32; k < 256; k++) {\n    test_sycl_contraction<DataLayout, DataType, IndexType>(sycl_device, 128,\n                                                           128, k);\n  }\n}\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid test_sycl_contraction_sizes(const Device &sycl_device) {\n  IndexType m_sizes[] = {31,  39,  63,  64,  65,   127,  129, 255,\n                         257, 511, 512, 513, 1023, 1024, 1025};\n\n  IndexType n_sizes[] = {31,  39,  63,  64,  65,   127,  129, 255,\n                         257, 511, 512, 513, 1023, 1024, 1025};\n\n  IndexType k_sizes[] = {31,  39,  63,  64,  65,  95,   96,   127, 129,\n                         255, 257, 511, 512, 513, 1023, 1024, 1025};\n\n  for (IndexType i = 0; i < 15; i++) {\n    for (IndexType j = 0; j < 15; j++) {\n      for (IndexType k = 0; k < 17; k++) {\n        test_sycl_contraction<DataLayout, DataType, IndexType>(\n            sycl_device, m_sizes[i], n_sizes[j], k_sizes[k]);\n      }\n    }\n  }\n}\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid static test_no_out_of_bounds(const Device &sycl_device, IndexType m_size,\n                                  IndexType k_size, IndexType n_size) {\n  typedef typename Tensor<DataType, 1, DataLayout, IndexType>::DimensionPair\n      DimPair;\n  static const DataType error_threshold = DataType(1e-4);\n  Tensor<DataType, 2, DataLayout, IndexType> t_left(m_size, k_size);\n  Tensor<DataType, 2, DataLayout, IndexType> t_right(k_size, n_size);\n  Tensor<DataType, 2, DataLayout, IndexType> t_result(m_size, n_size);\n\n  Eigen::array<DimPair, 1> dims = {{DimPair(1, 0)}};\n  Eigen::array<IndexType, 2> left_dims = {{m_size, k_size}};\n  Eigen::array<IndexType, 2> right_dims = {{k_size, n_size}};\n  Eigen::array<IndexType, 2> result_dims = {{m_size, n_size}};\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  // Allocate buffers twice as big to check for invalid read and write\n  auto padded_left_size = 2 * t_left.size();\n  auto padded_right_size = 2 * t_right.size();\n  auto padded_result_size = 2 * t_result.size();\n\n  std::size_t t_left_bytes = padded_left_size * sizeof(DataType);\n  std::size_t t_right_bytes = padded_right_size * sizeof(DataType);\n  std::size_t t_result_bytes = padded_result_size * sizeof(DataType);\n\n  DataType *d_t_left =\n      static_cast<DataType *>(sycl_device.allocate(t_left_bytes));\n  DataType *d_t_right =\n      static_cast<DataType *>(sycl_device.allocate(t_right_bytes));\n  DataType *d_t_result =\n      static_cast<DataType *>(sycl_device.allocate(t_result_bytes));\n\n  // TensorMaps are still of the same size than the Tensors\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_left(d_t_left, left_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_right(d_t_right, right_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_result(d_t_result, result_dims);\n\n  // Write nan after the actual buffer to propagate nans everywhere in case of\n  // invalid reads\n  DataType nan = std::numeric_limits<DataType>::quiet_NaN();\n  auto host_left_data = new DataType[padded_left_size];\n  std::copy_n(t_left.data(), t_left.size(), host_left_data);\n  std::fill_n(host_left_data + t_left.size(), t_left.size(), nan);\n  auto host_right_data = new DataType[padded_right_size];\n  std::copy_n(t_right.data(), t_right.size(), host_right_data);\n  std::fill_n(host_right_data + t_right.size(), t_right.size(), nan);\n  auto host_result_data = new DataType[padded_result_size];\n  std::fill_n(host_result_data, padded_result_size, nan);\n\n  sycl_device.memcpyHostToDevice(d_t_left, host_left_data, t_left_bytes);\n  sycl_device.memcpyHostToDevice(d_t_right, host_right_data, t_right_bytes);\n  sycl_device.memcpyHostToDevice(d_t_result, host_result_data, t_result_bytes);\n\n  gpu_t_result.device(sycl_device) = gpu_t_left.contract(gpu_t_right, dims);\n  sycl_device.memcpyDeviceToHost(host_result_data, d_t_result, t_result_bytes);\n\n  t_result = t_left.contract(t_right, dims);\n\n  for (IndexType i = 0; i < t_result.size(); i++) {\n    if (static_cast<DataType>(std::fabs(static_cast<DataType>(\n            t_result(i) - host_result_data[i]))) < error_threshold) {\n      continue;\n    }\n    if (Eigen::internal::isApprox(t_result(i), host_result_data[i],\n                                  error_threshold)) {\n      continue;\n    }\n    if (std::isnan(host_result_data[i])) {\n      std::cout << \"M : \" << m_size << \", N : \" << n_size << \", K : \" << k_size\n                << \", invalid read detected at IndexType \" << i << \": \"\n                << t_result(i) << \" vs \" << host_result_data[i] << std::endl;\n    } else {\n      std::cout << \"M : \" << m_size << \", N : \" << n_size << \", K : \" << k_size\n                << \", mismatch detected at IndexType \" << i << \": \"\n                << t_result(i) << \" vs \" << host_result_data[i] << std::endl;\n    }\n    VERIFY_IS_APPROX(host_result_data[i], t_result(i));\n  }\n  // Make sure that the rest of the result is still nans\n  for (IndexType i = t_result.size(); i < padded_result_size; i++) {\n    if (std::isnan(host_result_data[i])) {\n      continue;\n    }\n    std::cout << \"M : \" << m_size << \", N : \" << n_size << \", K : \" << k_size\n              << \", invalid write detected at IndexType \" << i << \": \"\n              << host_result_data[i] << std::endl;\n    VERIFY_IS_APPROX(host_result_data[i], t_result(i));\n  }\n  sycl_device.deallocate(d_t_left);\n  sycl_device.deallocate(d_t_right);\n  sycl_device.deallocate(d_t_result);\n\n  delete[] host_left_data;\n  delete[] host_right_data;\n  delete[] host_result_data;\n}\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid test_scalar(const Device &sycl_device, IndexType m_size, IndexType k_size,\n                 IndexType n_size) {\n  // std::cout << \"Testing for (\" << m_size << \",\" << k_size << \",\" << n_size <<\n  // \")\" << std::endl;\n  // with these dimensions, the output has 300 * 140 elements, which is\n  // more than 30 * 1024, which is the number of threads in blocks on\n  // a 15 SM GK110 GPU\n  typedef typename Tensor<DataType, 1, DataLayout, IndexType>::DimensionPair\n      DimPair;\n  static const DataType error_threshold = DataType(1e-4);\n  Tensor<DataType, 2, DataLayout, IndexType> t_left(m_size, k_size);\n  Tensor<DataType, 2, DataLayout, IndexType> t_right(k_size, n_size);\n  Tensor<DataType, 0, DataLayout, IndexType> t_result;\n  Tensor<DataType, 0, DataLayout, IndexType> t_result_gpu;\n  Eigen::array<DimPair, 2> dims = {{DimPair(0, 0), DimPair(1, 1)}};\n  Eigen::array<IndexType, 2> left_dims = {{m_size, k_size}};\n  Eigen::array<IndexType, 2> right_dims = {{k_size, n_size}};\n  t_left.setRandom();\n  t_right.setRandom();\n\n  std::size_t t_left_bytes = t_left.size() * sizeof(DataType);\n  std::size_t t_right_bytes = t_right.size() * sizeof(DataType);\n  std::size_t t_result_bytes = sizeof(DataType);\n\n  DataType *d_t_left =\n      static_cast<DataType *>(sycl_device.allocate(t_left_bytes));\n  DataType *d_t_right =\n      static_cast<DataType *>(sycl_device.allocate(t_right_bytes));\n  DataType *d_t_result =\n      static_cast<DataType *>(sycl_device.allocate(t_result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_left(d_t_left, left_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_right(d_t_right, right_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 0, DataLayout, IndexType>>\n      gpu_t_result(d_t_result);\n\n  sycl_device.memcpyHostToDevice(d_t_left, t_left.data(), t_left_bytes);\n  sycl_device.memcpyHostToDevice(d_t_right, t_right.data(), t_right_bytes);\n\n  gpu_t_result.device(sycl_device) = gpu_t_left.contract(gpu_t_right, dims);\n  sycl_device.memcpyDeviceToHost(t_result_gpu.data(), d_t_result,\n                                 t_result_bytes);\n\n  t_result = t_left.contract(t_right, dims);\n\n  if (static_cast<DataType>(std::fabs(static_cast<DataType>(\n          t_result() - t_result_gpu()))) > error_threshold &&\n      !Eigen::internal::isApprox(t_result(), t_result_gpu(), error_threshold)) {\n    std::cout << \"K: \" << k_size << \", N: \" << n_size << \", M: \" << m_size\n              << \" : mismatch detected: \" << t_result() << \" vs \"\n              << t_result_gpu() << std::endl;\n    VERIFY_IS_APPROX(t_result_gpu(), t_result());\n  }\n\n  sycl_device.deallocate(d_t_left);\n  sycl_device.deallocate(d_t_right);\n  sycl_device.deallocate(d_t_result);\n}\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid contraction_batch(const Device &sycl_device, IndexType m_size,\n                       IndexType k_size, IndexType n_size, IndexType m_batch,\n                       IndexType start, IndexType limit) {\n  typedef typename Tensor<DataType, 1, DataLayout, IndexType>::DimensionPair\n      DimPair;\n  static const DataType error_threshold = DataType(1e-4);\n  typedef Eigen::array<IndexType, 3> TensorDim;\n  typedef Eigen::Tensor<DataType, 3, DataLayout, IndexType> TensorType;\n  TensorDim left_dims = {{m_batch, k_size, m_size}};\n  TensorDim right_dims = {{m_batch, n_size, k_size}};\n  TensorDim res_dims = {{m_batch, m_size, n_size}};\n  Eigen::array<DimPair, 1> contract_pairs = {{DimPair(0, 1)}};\n\n  TensorType t_left(left_dims);\n  TensorType t_right(right_dims);\n  TensorType t_result_gpu(res_dims);\n  TensorType t_result(res_dims);\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  std::size_t t_left_bytes = t_left.size() * sizeof(DataType);\n  std::size_t t_right_bytes = t_right.size() * sizeof(DataType);\n  std::size_t t_result_bytes = t_result.size() * sizeof(DataType);\n\n  DataType *d_t_left =\n      static_cast<DataType *>(sycl_device.allocate(t_left_bytes));\n  DataType *d_t_right =\n      static_cast<DataType *>(sycl_device.allocate(t_right_bytes));\n  DataType *d_t_result =\n      static_cast<DataType *>(sycl_device.allocate(t_result_bytes));\n\n  Eigen::TensorMap<TensorType> gpu_t_left(d_t_left, left_dims);\n  Eigen::TensorMap<TensorType> gpu_t_right(d_t_right, right_dims);\n  Eigen::TensorMap<TensorType> gpu_t_result(d_t_result, res_dims);\n\n  sycl_device.memcpyHostToDevice(d_t_left, t_left.data(), t_left_bytes);\n  sycl_device.memcpyHostToDevice(d_t_right, t_right.data(), t_right_bytes);\n  for (int i = start; i < limit; ++i) {\n    auto x = gpu_t_left.template chip<0>(i);\n    auto y = gpu_t_right.template chip<0>(i);\n    auto z = gpu_t_result.template chip<0>(i);\n    z.device(sycl_device) = x.contract(y, contract_pairs);\n  }\n  sycl_device.memcpyDeviceToHost(t_result_gpu.data(), d_t_result,\n                                 t_result_bytes);\n\n  for (int i = start; i < limit; ++i) {\n    auto x = t_left.template chip<0>(i);\n    auto y = t_right.template chip<0>(i);\n    auto z = t_result.template chip<0>(i);\n    z = x.contract(y, contract_pairs);\n  }\n\n  for (IndexType i = 0; i < t_result.size(); i++) {\n    if (static_cast<DataType>(std::fabs(static_cast<DataType>(\n            t_result(i) - t_result_gpu(i)))) < error_threshold) {\n      continue;\n    }\n    if (Eigen::internal::isApprox(t_result(i), t_result_gpu(i),\n                                  error_threshold)) {\n      continue;\n    }\n    std::cout << \"mismatch detected at IndexType \" << i << \": \" << t_result(i)\n              << \" vs \" << t_result_gpu(i) << std::endl;\n    VERIFY_IS_APPROX(t_result_gpu(i), t_result(i));\n  }\n  sycl_device.deallocate(d_t_left);\n  sycl_device.deallocate(d_t_right);\n  sycl_device.deallocate(d_t_result);\n}\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid contraction_rhs_transposed(const Device &sycl_device, IndexType m_size,\n                                IndexType k_size, IndexType n_size) {\n  typedef typename Tensor<DataType, 1, DataLayout, IndexType>::DimensionPair\n      DimPair;\n  static const DataType error_threshold = DataType(1e-4);\n  Eigen::array<IndexType, 2> left_dims = {{m_size, k_size}};\n  Eigen::array<IndexType, 2> right_dims = {{n_size, k_size}};\n  Eigen::array<IndexType, 2> res_dims = {{m_size, n_size}};\n  Eigen::array<DimPair, 1> dims = {{DimPair(1, 1)}};\n\n  Tensor<DataType, 2, DataLayout, IndexType> t_left(left_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> t_right(right_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> t_result_gpu(res_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> t_result(res_dims);\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  std::size_t t_left_bytes = t_left.size() * sizeof(DataType);\n  std::size_t t_right_bytes = t_right.size() * sizeof(DataType);\n  std::size_t t_result_bytes = t_result.size() * sizeof(DataType);\n\n  DataType *d_t_left =\n      static_cast<DataType *>(sycl_device.allocate(t_left_bytes));\n  DataType *d_t_right =\n      static_cast<DataType *>(sycl_device.allocate(t_right_bytes));\n  DataType *d_t_result =\n      static_cast<DataType *>(sycl_device.allocate(t_result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_left(d_t_left, left_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_right(d_t_right, right_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_result(d_t_result, res_dims);\n\n  sycl_device.memcpyHostToDevice(d_t_left, t_left.data(), t_left_bytes);\n  sycl_device.memcpyHostToDevice(d_t_right, t_right.data(), t_right_bytes);\n\n  gpu_t_result.device(sycl_device) = gpu_t_left.contract(gpu_t_right, dims);\n  sycl_device.memcpyDeviceToHost(t_result_gpu.data(), d_t_result,\n                                 t_result_bytes);\n\n  t_result = t_left.contract(t_right, dims);\n\n  for (IndexType j = 0; j < m_size; j++) {\n    for (IndexType i = 0; i < n_size; i++) {\n      if (static_cast<DataType>(std::fabs(static_cast<DataType>(\n              t_result(j, i) - t_result_gpu(j, i)))) < error_threshold) {\n        continue;\n      }\n      if (Eigen::internal::isApprox(t_result(j, i), t_result_gpu(j, i),\n                                    error_threshold)) {\n        continue;\n      }\n      std::cout << \"M : \" << m_size << \", N : \" << n_size << \", K : \" << k_size\n                << \", mismatch detected at IndexType m: \" << j << \" n: \" << i\n                << \" CPU : \" << t_result(j, i)\n                << \" vs SYCL:\" << t_result_gpu(j, i) << std::endl;\n      VERIFY_IS_APPROX(t_result_gpu(j, i), t_result(j, i));\n    }\n  }\n  sycl_device.deallocate(d_t_left);\n  sycl_device.deallocate(d_t_right);\n  sycl_device.deallocate(d_t_result);\n}\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid contraction_lhs_transposed(const Device &sycl_device, IndexType m_size,\n                                IndexType k_size, IndexType n_size) {\n  typedef typename Tensor<DataType, 1, DataLayout, IndexType>::DimensionPair\n      DimPair;\n  static const DataType error_threshold = DataType(1e-4);\n  Eigen::array<IndexType, 2> left_dims = {{k_size, m_size}};\n  Eigen::array<IndexType, 2> right_dims = {{k_size, n_size}};\n  Eigen::array<IndexType, 2> res_dims = {{m_size, n_size}};\n  Eigen::array<DimPair, 1> dims = {{DimPair(0, 0)}};\n\n  Tensor<DataType, 2, DataLayout, IndexType> t_left(left_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> t_right(right_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> t_result_gpu(res_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> t_result(res_dims);\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  std::size_t t_left_bytes = t_left.size() * sizeof(DataType);\n  std::size_t t_right_bytes = t_right.size() * sizeof(DataType);\n  std::size_t t_result_bytes = t_result.size() * sizeof(DataType);\n\n  DataType *d_t_left =\n      static_cast<DataType *>(sycl_device.allocate(t_left_bytes));\n  DataType *d_t_right =\n      static_cast<DataType *>(sycl_device.allocate(t_right_bytes));\n  DataType *d_t_result =\n      static_cast<DataType *>(sycl_device.allocate(t_result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_left(d_t_left, left_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_right(d_t_right, right_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_result(d_t_result, res_dims);\n\n  sycl_device.memcpyHostToDevice(d_t_left, t_left.data(), t_left_bytes);\n  sycl_device.memcpyHostToDevice(d_t_right, t_right.data(), t_right_bytes);\n\n  gpu_t_result.device(sycl_device) = gpu_t_left.contract(gpu_t_right, dims);\n  sycl_device.memcpyDeviceToHost(t_result_gpu.data(), d_t_result,\n                                 t_result_bytes);\n\n  t_result = t_left.contract(t_right, dims);\n\n  for (IndexType i = 0; i < t_result.size(); i++) {\n    if (static_cast<DataType>(std::fabs(static_cast<DataType>(\n            t_result(i) - t_result_gpu(i)))) < error_threshold) {\n      continue;\n    }\n    if (Eigen::internal::isApprox(t_result(i), t_result_gpu(i),\n                                  error_threshold)) {\n      continue;\n    }\n    std::cout << \"M : \" << m_size << \", N : \" << n_size << \", K : \" << k_size\n              << \", mismatch detected at IndexType \" << i << \": \" << t_result(i)\n              << \" vs \" << t_result_gpu(i) << std::endl;\n    VERIFY_IS_APPROX(t_result_gpu(i), t_result(i));\n  }\n  sycl_device.deallocate(d_t_left);\n  sycl_device.deallocate(d_t_right);\n  sycl_device.deallocate(d_t_result);\n}\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid contraction_both_transposed(const Device &sycl_device, IndexType m_size,\n                                 IndexType k_size, IndexType n_size) {\n  typedef typename Tensor<DataType, 1, DataLayout, IndexType>::DimensionPair\n      DimPair;\n  static const DataType error_threshold = DataType(1e-4);\n  Eigen::array<IndexType, 2> left_dims = {{k_size, m_size}};\n  Eigen::array<IndexType, 2> right_dims = {{n_size, k_size}};\n  Eigen::array<IndexType, 2> res_dims = {{m_size, n_size}};\n  Eigen::array<DimPair, 1> dims = {{DimPair(0, 1)}};\n\n  Tensor<DataType, 2, DataLayout, IndexType> t_left(left_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> t_right(right_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> t_result_gpu(res_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> t_result(res_dims);\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  std::size_t t_left_bytes = t_left.size() * sizeof(DataType);\n  std::size_t t_right_bytes = t_right.size() * sizeof(DataType);\n  std::size_t t_result_bytes = t_result.size() * sizeof(DataType);\n\n  DataType *d_t_left =\n      static_cast<DataType *>(sycl_device.allocate(t_left_bytes));\n  DataType *d_t_right =\n      static_cast<DataType *>(sycl_device.allocate(t_right_bytes));\n  DataType *d_t_result =\n      static_cast<DataType *>(sycl_device.allocate(t_result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_left(d_t_left, left_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_right(d_t_right, right_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_result(d_t_result, res_dims);\n\n  sycl_device.memcpyHostToDevice(d_t_left, t_left.data(), t_left_bytes);\n  sycl_device.memcpyHostToDevice(d_t_right, t_right.data(), t_right_bytes);\n\n  gpu_t_result.device(sycl_device) = gpu_t_left.contract(gpu_t_right, dims);\n  sycl_device.memcpyDeviceToHost(t_result_gpu.data(), d_t_result,\n                                 t_result_bytes);\n\n  t_result = t_left.contract(t_right, dims);\n\n  for (IndexType i = 0; i < t_result.size(); i++) {\n    if (static_cast<DataType>(std::fabs(static_cast<DataType>(\n            t_result(i) - t_result_gpu(i)))) < error_threshold) {\n      continue;\n    }\n    if (Eigen::internal::isApprox(t_result(i), t_result_gpu(i),\n                                  error_threshold)) {\n      continue;\n    }\n    std::cout << \"M : \" << m_size << \", N : \" << n_size << \", K : \" << k_size\n              << \", mismatch detected at IndexType \" << i << \": \" << t_result(i)\n              << \" vs \" << t_result_gpu(i) << std::endl;\n\n    VERIFY_IS_APPROX(t_result_gpu(i), t_result(i));\n  }\n  sycl_device.deallocate(d_t_left);\n  sycl_device.deallocate(d_t_right);\n  sycl_device.deallocate(d_t_result);\n}\n\ntemplate <typename Dev>\nvoid inline tensorOutofBound(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // Test out of bound for Tensor-Tensor\n  test_no_out_of_bounds<RowMajor, DataType, IndexType>(sycl_device, 10, 1024,\n                                                       1024);\n  test_no_out_of_bounds<RowMajor, DataType, IndexType>(sycl_device, 1024, 1024,\n                                                       4096);\n  test_no_out_of_bounds<RowMajor, DataType, IndexType>(sycl_device, 4096, 1024,\n                                                       2048);\n  test_no_out_of_bounds<ColMajor, DataType, IndexType>(sycl_device, 784, 2048,\n                                                       1024);\n  test_no_out_of_bounds<ColMajor, DataType, IndexType>(sycl_device, 2048, 1024,\n                                                       784);\n  test_no_out_of_bounds<RowMajor, DataType, IndexType>(sycl_device, 10, 1024,\n                                                       10);\n  test_no_out_of_bounds<RowMajor, DataType, IndexType>(sycl_device, 513, 4096,\n                                                       513);\n  test_no_out_of_bounds<RowMajor, DataType, IndexType>(sycl_device, 783, 1024,\n                                                       783);\n  test_no_out_of_bounds<ColMajor, DataType, IndexType>(sycl_device, 784, 2048,\n                                                       784);\n  test_no_out_of_bounds<ColMajor, DataType, IndexType>(sycl_device, 11, 1024,\n                                                       11);\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"tensor out of bound tests finished computation at \"\n            << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensorTensor(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // Tensor Tensor Contraction\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 128, 128,\n                                                       128);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 128, 128,\n                                                       128);\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"tensor tensor tests finished computation at \"\n            << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensorTensor_m(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // Tensor Tensor Contraction\n  test_sycl_contraction_m<ColMajor, DataType, IndexType>(sycl_device);\n  test_sycl_contraction_m<RowMajor, DataType, IndexType>(sycl_device);\n\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"tensor tensor tests finished computation at \"\n            << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensorTensor_n(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // Tensor Tensor Contraction\n  test_sycl_contraction_n<ColMajor, DataType, IndexType>(sycl_device);\n  test_sycl_contraction_n<RowMajor, DataType, IndexType>(sycl_device);\n\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"tensor tensor tests finished computation at \"\n            << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensorTensor_k(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  test_sycl_contraction_k<ColMajor, DataType, IndexType>(sycl_device);\n  test_sycl_contraction_k<RowMajor, DataType, IndexType>(sycl_device);\n\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"tensor tensor tests finished computation at \"\n            << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensorTensor_sizes(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // Tensor Tensor Contraction\n  test_sycl_contraction_sizes<ColMajor, DataType, IndexType>(sycl_device);\n  test_sycl_contraction_sizes<RowMajor, DataType, IndexType>(sycl_device);\n\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"tensor tensor tests finished computation at \"\n            << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\ntemplate <typename Dev>\nvoid inline vectorVector(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // VECTOR-VECTOR\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1025, 1,\n                                                       1025);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1025, 1,\n                                                       1025);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1024, 1,\n                                                       1024);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1024, 1,\n                                                       1024);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1023, 1,\n                                                       1023);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1023, 1,\n                                                       1023);\n\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"contracted tensor tests finished computation at \"\n            << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline vectorTensor(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // Vector-Tensor\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1, 1025,\n                                                       1025);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1, 1025,\n                                                       1025);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1, 1024,\n                                                       1024);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1, 1024,\n                                                       1024);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1, 1023,\n                                                       1023);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1, 1023,\n                                                       1023);\n\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1, 4097,\n                                                       4097);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1, 4097,\n                                                       4097);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1, 4096,\n                                                       4096);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1, 4096,\n                                                       4096);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1, 4095,\n                                                       4095);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1, 4095,\n                                                       4095);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1, 802816,\n                                                       32);\n\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"finished computation at \" << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensorVector(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // Matrix-Vector\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1025, 1025,\n                                                       1);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1125, 1025,\n                                                       1);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1224, 1024,\n                                                       1);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1024, 1024,\n                                                       1);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1023, 1023,\n                                                       1);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1023, 1023,\n                                                       1);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 4097, 4197,\n                                                       1);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 4097, 4097,\n                                                       1);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 4096, 4096,\n                                                       1);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 4096, 8196,\n                                                       1);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 4095, 4095,\n                                                       1);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 4095, 4095,\n                                                       1);\n// If the GEMV disabled it will creates one kernel to calculate the contraction.\n// Therefore the acumuation of float number will overflow the precision\n// threshold for float and cause the test to fail. While it the GMV multiple\n// kernel will be created and each one run the overflow of accumutation breaks\n// among the kernels.\n#ifndef EIGEN_SYCL_DISABLE_GEMV\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 32, 802032,\n                                                       1);\n#endif\n\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"finished computation at \" << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensorScalar(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // SCALAR Contraction\n  test_scalar<ColMajor, DataType, IndexType>(sycl_device, 127, 127, 127);\n  test_scalar<RowMajor, DataType, IndexType>(sycl_device, 127, 127, 127);\n  test_scalar<ColMajor, DataType, IndexType>(sycl_device, 128, 128, 128);\n  test_scalar<RowMajor, DataType, IndexType>(sycl_device, 128, 128, 128);\n  test_scalar<ColMajor, DataType, IndexType>(sycl_device, 129, 129, 129);\n  test_scalar<RowMajor, DataType, IndexType>(sycl_device, 129, 129, 129);\n\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"finished computation at \" << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline skinnyTensor_row(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // Tensor Tensor Contraction\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 16, 4, 16);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 257, 131073,\n                                                       257);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 256, 131072,\n                                                       256);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 16, 131073,\n                                                       16);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 17, 131072,\n                                                       17);\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"finished computation at \" << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline skinnyTensor_col(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // Tensor Tensor Contraction\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 16, 4, 16);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 257, 131073,\n                                                       257);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 256, 131072,\n                                                       256);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 16, 131073,\n                                                       16);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 17, 131072,\n                                                       17);\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"finished computation at \" << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensor_contraction_batch_per_device(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n\n  contraction_batch<RowMajor, DataType, IndexType>(sycl_device, 64, 75, 30, 4,\n                                                   0, 4);\n  contraction_batch<ColMajor, DataType, IndexType>(sycl_device, 64, 75, 30, 4,\n                                                   0, 4);\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"finished computation at \" << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensor_contraction_lhs_transposed_per_device(\n    const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n\n  contraction_lhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 8, 4,\n                                                            8);\n  contraction_lhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 32, 8,\n                                                            32);\n  contraction_lhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 64, 16,\n                                                            64);\n  contraction_lhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 784,\n                                                            2048, 1024);\n  contraction_lhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 1024,\n                                                            10, 1024);\n  contraction_lhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 4096,\n                                                            1024, 1024);\n  contraction_lhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 2048,\n                                                            4096, 1024);\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"finished computation at \" << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensor_contraction_rhs_transposed_per_device(\n    const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n\n  contraction_rhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 16, 4,\n                                                            16);\n  contraction_rhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 17, 5,\n                                                            17);\n  contraction_rhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 32, 8,\n                                                            32);\n  contraction_rhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 64, 16,\n                                                            64);\n  contraction_rhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 10,\n                                                            1024, 1024);\n  contraction_rhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 1024,\n                                                            1024, 4096);\n  contraction_rhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 4096,\n                                                            1024, 2048);\n  contraction_rhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 2048,\n                                                            1024, 784);\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"finished computation at \" << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensor_contraction_both_transposed_per_device(\n    const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n\n  contraction_both_transposed<RowMajor, DataType, IndexType>(sycl_device, 17, 5,\n                                                             17);\n  contraction_both_transposed<RowMajor, DataType, IndexType>(sycl_device, 32, 8,\n                                                             32);\n  contraction_both_transposed<RowMajor, DataType, IndexType>(sycl_device, 64,\n                                                             16, 64);\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"finished computation at \" << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_contract_sycl) {\n  for (const auto &device : Eigen::get_sycl_supported_devices()) {\n    std::cout << \"Running on \"\n              << device.template get_info<cl::sycl::info::device::name>()\n              << std::endl;\n    QueueInterface queueInterface(device);\n    auto sycl_device = Eigen::SyclDevice(&queueInterface);\n    CALL_SUBTEST_1(tensorOutofBound(sycl_device));\n    CALL_SUBTEST_2(tensorTensor(sycl_device));\n    CALL_SUBTEST_2(tensorTensor_m(sycl_device));\n    CALL_SUBTEST_2(tensorTensor_n(sycl_device));\n    CALL_SUBTEST_2(tensorTensor_k(sycl_device));\n    CALL_SUBTEST_2(tensorTensor_sizes(sycl_device));\n    CALL_SUBTEST_3(vectorVector(sycl_device));\n    CALL_SUBTEST_4(vectorTensor(sycl_device));\n    CALL_SUBTEST_5(tensorVector(sycl_device));\n    CALL_SUBTEST_6(tensorScalar(sycl_device));\n    CALL_SUBTEST_7(skinnyTensor_row(sycl_device));\n    CALL_SUBTEST_7(skinnyTensor_col(sycl_device));\n    CALL_SUBTEST_8(tensor_contraction_batch_per_device(sycl_device));\n    CALL_SUBTEST_9(tensor_contraction_lhs_transposed_per_device(sycl_device));\n    CALL_SUBTEST_10(tensor_contraction_rhs_transposed_per_device(sycl_device));\n    CALL_SUBTEST_11(tensor_contraction_both_transposed_per_device(sycl_device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_contraction.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::DefaultDevice;\nusing Eigen::Tensor;\n\ntypedef Tensor<float, 1>::DimensionPair DimPair;\n\ntemplate<int DataLayout>\nstatic void test_evals()\n{\n  Tensor<float, 2, DataLayout> mat1(2, 3);\n  Tensor<float, 2, DataLayout> mat2(2, 3);\n  Tensor<float, 2, DataLayout> mat3(3, 2);\n\n  mat1.setRandom();\n  mat2.setRandom();\n  mat3.setRandom();\n\n  Tensor<float, 2, DataLayout> mat4(3,3);\n  mat4.setZero();\n  Eigen::array<DimPair, 1> dims3 = {{DimPair(0, 0)}};\n  typedef TensorEvaluator<decltype(mat1.contract(mat2, dims3)), DefaultDevice> Evaluator;\n  Evaluator eval(mat1.contract(mat2, dims3), DefaultDevice());\n  eval.evalTo(mat4.data());\n  EIGEN_STATIC_ASSERT(Evaluator::NumDims==2ul, YOU_MADE_A_PROGRAMMING_MISTAKE);\n  VERIFY_IS_EQUAL(eval.dimensions()[0], 3);\n  VERIFY_IS_EQUAL(eval.dimensions()[1], 3);\n\n  VERIFY_IS_APPROX(mat4(0,0), mat1(0,0)*mat2(0,0) + mat1(1,0)*mat2(1,0));\n  VERIFY_IS_APPROX(mat4(0,1), mat1(0,0)*mat2(0,1) + mat1(1,0)*mat2(1,1));\n  VERIFY_IS_APPROX(mat4(0,2), mat1(0,0)*mat2(0,2) + mat1(1,0)*mat2(1,2));\n  VERIFY_IS_APPROX(mat4(1,0), mat1(0,1)*mat2(0,0) + mat1(1,1)*mat2(1,0));\n  VERIFY_IS_APPROX(mat4(1,1), mat1(0,1)*mat2(0,1) + mat1(1,1)*mat2(1,1));\n  VERIFY_IS_APPROX(mat4(1,2), mat1(0,1)*mat2(0,2) + mat1(1,1)*mat2(1,2));\n  VERIFY_IS_APPROX(mat4(2,0), mat1(0,2)*mat2(0,0) + mat1(1,2)*mat2(1,0));\n  VERIFY_IS_APPROX(mat4(2,1), mat1(0,2)*mat2(0,1) + mat1(1,2)*mat2(1,1));\n  VERIFY_IS_APPROX(mat4(2,2), mat1(0,2)*mat2(0,2) + mat1(1,2)*mat2(1,2));\n\n  Tensor<float, 2, DataLayout> mat5(2,2);\n  mat5.setZero();\n  Eigen::array<DimPair, 1> dims4 = {{DimPair(1, 1)}};\n  typedef TensorEvaluator<decltype(mat1.contract(mat2, dims4)), DefaultDevice> Evaluator2;\n  Evaluator2 eval2(mat1.contract(mat2, dims4), DefaultDevice());\n  eval2.evalTo(mat5.data());\n  EIGEN_STATIC_ASSERT(Evaluator2::NumDims==2ul, YOU_MADE_A_PROGRAMMING_MISTAKE);\n  VERIFY_IS_EQUAL(eval2.dimensions()[0], 2);\n  VERIFY_IS_EQUAL(eval2.dimensions()[1], 2);\n\n  VERIFY_IS_APPROX(mat5(0,0), mat1(0,0)*mat2(0,0) + mat1(0,1)*mat2(0,1) + mat1(0,2)*mat2(0,2));\n  VERIFY_IS_APPROX(mat5(0,1), mat1(0,0)*mat2(1,0) + mat1(0,1)*mat2(1,1) + mat1(0,2)*mat2(1,2));\n  VERIFY_IS_APPROX(mat5(1,0), mat1(1,0)*mat2(0,0) + mat1(1,1)*mat2(0,1) + mat1(1,2)*mat2(0,2));\n  VERIFY_IS_APPROX(mat5(1,1), mat1(1,0)*mat2(1,0) + mat1(1,1)*mat2(1,1) + mat1(1,2)*mat2(1,2));\n\n  Tensor<float, 2, DataLayout> mat6(2,2);\n  mat6.setZero();\n  Eigen::array<DimPair, 1> dims6 = {{DimPair(1, 0)}};\n  typedef TensorEvaluator<decltype(mat1.contract(mat3, dims6)), DefaultDevice> Evaluator3;\n  Evaluator3 eval3(mat1.contract(mat3, dims6), DefaultDevice());\n  eval3.evalTo(mat6.data());\n  EIGEN_STATIC_ASSERT(Evaluator3::NumDims==2ul, YOU_MADE_A_PROGRAMMING_MISTAKE);\n  VERIFY_IS_EQUAL(eval3.dimensions()[0], 2);\n  VERIFY_IS_EQUAL(eval3.dimensions()[1], 2);\n\n  VERIFY_IS_APPROX(mat6(0,0), mat1(0,0)*mat3(0,0) + mat1(0,1)*mat3(1,0) + mat1(0,2)*mat3(2,0));\n  VERIFY_IS_APPROX(mat6(0,1), mat1(0,0)*mat3(0,1) + mat1(0,1)*mat3(1,1) + mat1(0,2)*mat3(2,1));\n  VERIFY_IS_APPROX(mat6(1,0), mat1(1,0)*mat3(0,0) + mat1(1,1)*mat3(1,0) + mat1(1,2)*mat3(2,0));\n  VERIFY_IS_APPROX(mat6(1,1), mat1(1,0)*mat3(0,1) + mat1(1,1)*mat3(1,1) + mat1(1,2)*mat3(2,1));\n}\n\ntemplate<int DataLayout>\nstatic void test_scalar()\n{\n  Tensor<float, 1, DataLayout> vec1({6});\n  Tensor<float, 1, DataLayout> vec2({6});\n\n  vec1.setRandom();\n  vec2.setRandom();\n\n  Eigen::array<DimPair, 1> dims = {{DimPair(0, 0)}};\n  Tensor<float, 0, DataLayout> scalar = vec1.contract(vec2, dims);\n\n  float expected = 0.0f;\n  for (int i = 0; i < 6; ++i) {\n    expected += vec1(i) * vec2(i);\n  }\n  VERIFY_IS_APPROX(scalar(), expected);\n}\n\ntemplate<int DataLayout>\nstatic void test_multidims()\n{\n  Tensor<float, 3, DataLayout> mat1(2, 2, 2);\n  Tensor<float, 4, DataLayout> mat2(2, 2, 2, 2);\n\n  mat1.setRandom();\n  mat2.setRandom();\n\n  Tensor<float, 3, DataLayout> mat3(2, 2, 2);\n  mat3.setZero();\n  Eigen::array<DimPair, 2> dims = {{DimPair(1, 2), DimPair(2, 3)}};\n  typedef TensorEvaluator<decltype(mat1.contract(mat2, dims)), DefaultDevice> Evaluator;\n  Evaluator eval(mat1.contract(mat2, dims), DefaultDevice());\n  eval.evalTo(mat3.data());\n  EIGEN_STATIC_ASSERT(Evaluator::NumDims==3ul, YOU_MADE_A_PROGRAMMING_MISTAKE);\n  VERIFY_IS_EQUAL(eval.dimensions()[0], 2);\n  VERIFY_IS_EQUAL(eval.dimensions()[1], 2);\n  VERIFY_IS_EQUAL(eval.dimensions()[2], 2);\n\n  VERIFY_IS_APPROX(mat3(0,0,0), mat1(0,0,0)*mat2(0,0,0,0) + mat1(0,1,0)*mat2(0,0,1,0) +\n                                mat1(0,0,1)*mat2(0,0,0,1) + mat1(0,1,1)*mat2(0,0,1,1));\n  VERIFY_IS_APPROX(mat3(0,0,1), mat1(0,0,0)*mat2(0,1,0,0) + mat1(0,1,0)*mat2(0,1,1,0) +\n                                mat1(0,0,1)*mat2(0,1,0,1) + mat1(0,1,1)*mat2(0,1,1,1));\n  VERIFY_IS_APPROX(mat3(0,1,0), mat1(0,0,0)*mat2(1,0,0,0) + mat1(0,1,0)*mat2(1,0,1,0) +\n                                mat1(0,0,1)*mat2(1,0,0,1) + mat1(0,1,1)*mat2(1,0,1,1));\n  VERIFY_IS_APPROX(mat3(0,1,1), mat1(0,0,0)*mat2(1,1,0,0) + mat1(0,1,0)*mat2(1,1,1,0) +\n                                mat1(0,0,1)*mat2(1,1,0,1) + mat1(0,1,1)*mat2(1,1,1,1));\n  VERIFY_IS_APPROX(mat3(1,0,0), mat1(1,0,0)*mat2(0,0,0,0) + mat1(1,1,0)*mat2(0,0,1,0) +\n                                mat1(1,0,1)*mat2(0,0,0,1) + mat1(1,1,1)*mat2(0,0,1,1));\n  VERIFY_IS_APPROX(mat3(1,0,1), mat1(1,0,0)*mat2(0,1,0,0) + mat1(1,1,0)*mat2(0,1,1,0) +\n                                mat1(1,0,1)*mat2(0,1,0,1) + mat1(1,1,1)*mat2(0,1,1,1));\n  VERIFY_IS_APPROX(mat3(1,1,0), mat1(1,0,0)*mat2(1,0,0,0) + mat1(1,1,0)*mat2(1,0,1,0) +\n                                mat1(1,0,1)*mat2(1,0,0,1) + mat1(1,1,1)*mat2(1,0,1,1));\n  VERIFY_IS_APPROX(mat3(1,1,1), mat1(1,0,0)*mat2(1,1,0,0) + mat1(1,1,0)*mat2(1,1,1,0) +\n                                mat1(1,0,1)*mat2(1,1,0,1) + mat1(1,1,1)*mat2(1,1,1,1));\n\n  Tensor<float, 2, DataLayout> mat4(2, 2);\n  Tensor<float, 3, DataLayout> mat5(2, 2, 2);\n\n  mat4.setRandom();\n  mat5.setRandom();\n\n  Tensor<float, 1, DataLayout> mat6(2);\n  mat6.setZero();\n  Eigen::array<DimPair, 2> dims2({{DimPair(0, 1), DimPair(1, 0)}});\n  typedef TensorEvaluator<decltype(mat4.contract(mat5, dims2)), DefaultDevice> Evaluator2;\n  Evaluator2 eval2(mat4.contract(mat5, dims2), DefaultDevice());\n  eval2.evalTo(mat6.data());\n  EIGEN_STATIC_ASSERT(Evaluator2::NumDims==1ul, YOU_MADE_A_PROGRAMMING_MISTAKE);\n  VERIFY_IS_EQUAL(eval2.dimensions()[0], 2);\n\n  VERIFY_IS_APPROX(mat6(0), mat4(0,0)*mat5(0,0,0) + mat4(1,0)*mat5(0,1,0) +\n                   mat4(0,1)*mat5(1,0,0) + mat4(1,1)*mat5(1,1,0));\n  VERIFY_IS_APPROX(mat6(1), mat4(0,0)*mat5(0,0,1) + mat4(1,0)*mat5(0,1,1) +\n                   mat4(0,1)*mat5(1,0,1) + mat4(1,1)*mat5(1,1,1));\n}\n\ntemplate<int DataLayout>\nstatic void test_holes() {\n  Tensor<float, 4, DataLayout> t1(2, 5, 7, 3);\n  Tensor<float, 5, DataLayout> t2(2, 7, 11, 13, 3);\n  t1.setRandom();\n  t2.setRandom();\n\n  Eigen::array<DimPair, 2> dims = {{DimPair(0, 0), DimPair(3, 4)}};\n  Tensor<float, 5, DataLayout> result = t1.contract(t2, dims);\n  VERIFY_IS_EQUAL(result.dimension(0), 5);\n  VERIFY_IS_EQUAL(result.dimension(1), 7);\n  VERIFY_IS_EQUAL(result.dimension(2), 7);\n  VERIFY_IS_EQUAL(result.dimension(3), 11);\n  VERIFY_IS_EQUAL(result.dimension(4), 13);\n\n  for (int i = 0; i < 5; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 5; ++l) {\n          for (int m = 0; m < 5; ++m) {\n            VERIFY_IS_APPROX(result(i, j, k, l, m),\n                             t1(0, i, j, 0) * t2(0, k, l, m, 0) +\n                             t1(1, i, j, 0) * t2(1, k, l, m, 0) +\n                             t1(0, i, j, 1) * t2(0, k, l, m, 1) +\n                             t1(1, i, j, 1) * t2(1, k, l, m, 1) +\n                             t1(0, i, j, 2) * t2(0, k, l, m, 2) +\n                             t1(1, i, j, 2) * t2(1, k, l, m, 2));\n          }\n        }\n      }\n    }\n  }\n}\n\ntemplate<int DataLayout>\nstatic void test_full_redux()\n{\n  Tensor<float, 2, DataLayout> t1(2, 2);\n  Tensor<float, 3, DataLayout> t2(2, 2, 2);\n  t1.setRandom();\n  t2.setRandom();\n\n  Eigen::array<DimPair, 2> dims = {{DimPair(0, 0), DimPair(1, 1)}};\n  Tensor<float, 1, DataLayout> result = t1.contract(t2, dims);\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_APPROX(result(0), t1(0, 0) * t2(0, 0, 0) +  t1(1, 0) * t2(1, 0, 0)\n                            + t1(0, 1) * t2(0, 1, 0) +  t1(1, 1) * t2(1, 1, 0));\n  VERIFY_IS_APPROX(result(1), t1(0, 0) * t2(0, 0, 1) +  t1(1, 0) * t2(1, 0, 1)\n                            + t1(0, 1) * t2(0, 1, 1) +  t1(1, 1) * t2(1, 1, 1));\n\n  dims[0] = DimPair(1, 0);\n  dims[1] = DimPair(2, 1);\n  result = t2.contract(t1, dims);\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_APPROX(result(0), t1(0, 0) * t2(0, 0, 0) +  t1(1, 0) * t2(0, 1, 0)\n                            + t1(0, 1) * t2(0, 0, 1) +  t1(1, 1) * t2(0, 1, 1));\n  VERIFY_IS_APPROX(result(1), t1(0, 0) * t2(1, 0, 0) +  t1(1, 0) * t2(1, 1, 0)\n                            + t1(0, 1) * t2(1, 0, 1) +  t1(1, 1) * t2(1, 1, 1));\n}\n\ntemplate<int DataLayout>\nstatic void test_contraction_of_contraction()\n{\n  Tensor<float, 2, DataLayout> t1(2, 2);\n  Tensor<float, 2, DataLayout> t2(2, 2);\n  Tensor<float, 2, DataLayout> t3(2, 2);\n  Tensor<float, 2, DataLayout> t4(2, 2);\n  t1.setRandom();\n  t2.setRandom();\n  t3.setRandom();\n  t4.setRandom();\n\n  Eigen::array<DimPair, 1> dims = {{DimPair(1, 0)}};\n  auto contract1 = t1.contract(t2, dims);\n  auto diff = t3 - contract1;\n  auto contract2 = t1.contract(t4, dims);\n  Tensor<float, 2, DataLayout> result = contract2.contract(diff, dims);\n\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_EQUAL(result.dimension(1), 2);\n\n  Eigen::Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>>\n      m1(t1.data(), 2, 2), m2(t2.data(), 2, 2), m3(t3.data(), 2, 2),\n      m4(t4.data(), 2, 2);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>\n      expected = (m1 * m4) * (m3 - m1 * m2);\n\n  VERIFY_IS_APPROX(result(0, 0), expected(0, 0));\n  VERIFY_IS_APPROX(result(0, 1), expected(0, 1));\n  VERIFY_IS_APPROX(result(1, 0), expected(1, 0));\n  VERIFY_IS_APPROX(result(1, 1), expected(1, 1));\n}\n\ntemplate<int DataLayout>\nstatic void test_expr()\n{\n  Tensor<float, 2, DataLayout> mat1(2, 3);\n  Tensor<float, 2, DataLayout> mat2(3, 2);\n  mat1.setRandom();\n  mat2.setRandom();\n\n  Tensor<float, 2, DataLayout> mat3(2,2);\n\n  Eigen::array<DimPair, 1> dims = {{DimPair(1, 0)}};\n  mat3 = mat1.contract(mat2, dims);\n\n  VERIFY_IS_APPROX(mat3(0,0), mat1(0,0)*mat2(0,0) + mat1(0,1)*mat2(1,0) + mat1(0,2)*mat2(2,0));\n  VERIFY_IS_APPROX(mat3(0,1), mat1(0,0)*mat2(0,1) + mat1(0,1)*mat2(1,1) + mat1(0,2)*mat2(2,1));\n  VERIFY_IS_APPROX(mat3(1,0), mat1(1,0)*mat2(0,0) + mat1(1,1)*mat2(1,0) + mat1(1,2)*mat2(2,0));\n  VERIFY_IS_APPROX(mat3(1,1), mat1(1,0)*mat2(0,1) + mat1(1,1)*mat2(1,1) + mat1(1,2)*mat2(2,1));\n}\n\ntemplate<int DataLayout>\nstatic void test_out_of_order_contraction()\n{\n  Tensor<float, 3, DataLayout> mat1(2, 2, 2);\n  Tensor<float, 3, DataLayout> mat2(2, 2, 2);\n\n  mat1.setRandom();\n  mat2.setRandom();\n\n  Tensor<float, 2, DataLayout> mat3(2, 2);\n\n  Eigen::array<DimPair, 2> dims = {{DimPair(2, 0), DimPair(0, 2)}};\n  mat3 = mat1.contract(mat2, dims);\n\n  VERIFY_IS_APPROX(mat3(0, 0),\n                   mat1(0,0,0)*mat2(0,0,0) + mat1(1,0,0)*mat2(0,0,1) +\n                   mat1(0,0,1)*mat2(1,0,0) + mat1(1,0,1)*mat2(1,0,1));\n  VERIFY_IS_APPROX(mat3(1, 0),\n                   mat1(0,1,0)*mat2(0,0,0) + mat1(1,1,0)*mat2(0,0,1) +\n                   mat1(0,1,1)*mat2(1,0,0) + mat1(1,1,1)*mat2(1,0,1));\n  VERIFY_IS_APPROX(mat3(0, 1),\n                   mat1(0,0,0)*mat2(0,1,0) + mat1(1,0,0)*mat2(0,1,1) +\n                   mat1(0,0,1)*mat2(1,1,0) + mat1(1,0,1)*mat2(1,1,1));\n  VERIFY_IS_APPROX(mat3(1, 1),\n                   mat1(0,1,0)*mat2(0,1,0) + mat1(1,1,0)*mat2(0,1,1) +\n                   mat1(0,1,1)*mat2(1,1,0) + mat1(1,1,1)*mat2(1,1,1));\n\n  Eigen::array<DimPair, 2> dims2 = {{DimPair(0, 2), DimPair(2, 0)}};\n  mat3 = mat1.contract(mat2, dims2);\n\n  VERIFY_IS_APPROX(mat3(0, 0),\n                   mat1(0,0,0)*mat2(0,0,0) + mat1(1,0,0)*mat2(0,0,1) +\n                   mat1(0,0,1)*mat2(1,0,0) + mat1(1,0,1)*mat2(1,0,1));\n  VERIFY_IS_APPROX(mat3(1, 0),\n                   mat1(0,1,0)*mat2(0,0,0) + mat1(1,1,0)*mat2(0,0,1) +\n                   mat1(0,1,1)*mat2(1,0,0) + mat1(1,1,1)*mat2(1,0,1));\n  VERIFY_IS_APPROX(mat3(0, 1),\n                   mat1(0,0,0)*mat2(0,1,0) + mat1(1,0,0)*mat2(0,1,1) +\n                   mat1(0,0,1)*mat2(1,1,0) + mat1(1,0,1)*mat2(1,1,1));\n  VERIFY_IS_APPROX(mat3(1, 1),\n                   mat1(0,1,0)*mat2(0,1,0) + mat1(1,1,0)*mat2(0,1,1) +\n                   mat1(0,1,1)*mat2(1,1,0) + mat1(1,1,1)*mat2(1,1,1));\n\n}\n\ntemplate<int DataLayout>\nstatic void test_consistency()\n{\n  // this does something like testing (A*B)^T = (B^T * A^T)\n\n  Tensor<float, 3, DataLayout> mat1(4, 3, 5);\n  Tensor<float, 5, DataLayout> mat2(3, 2, 1, 5, 4);\n  mat1.setRandom();\n  mat2.setRandom();\n\n  Tensor<float, 4, DataLayout> mat3(5, 2, 1, 5);\n  Tensor<float, 4, DataLayout> mat4(2, 1, 5, 5);\n\n  // contract on dimensions of size 4 and 3\n  Eigen::array<DimPair, 2> dims1 = {{DimPair(0, 4), DimPair(1, 0)}};\n  Eigen::array<DimPair, 2> dims2 = {{DimPair(4, 0), DimPair(0, 1)}};\n\n  mat3 = mat1.contract(mat2, dims1);\n  mat4 = mat2.contract(mat1, dims2);\n\n  // check that these are equal except for ordering of dimensions\n  if (DataLayout == ColMajor) {\n    for (size_t i = 0; i < 5; i++) {\n      for (size_t j = 0; j < 10; j++) {\n        VERIFY_IS_APPROX(mat3.data()[i + 5 * j], mat4.data()[j + 10 * i]);\n      }\n    }\n  } else {\n    // Row major\n    for (size_t i = 0; i < 5; i++) {\n      for (size_t j = 0; j < 10; j++) {\n        VERIFY_IS_APPROX(mat3.data()[10 * i + j], mat4.data()[i + 5 * j]);\n      }\n    }\n  }\n}\n\ntemplate<int DataLayout>\nstatic void test_large_contraction()\n{\n  Tensor<float, 4, DataLayout> t_left(30, 50, 8, 31);\n  Tensor<float, 5, DataLayout> t_right(8, 31, 7, 20, 10);\n  Tensor<float, 5, DataLayout> t_result(30, 50, 7, 20, 10);\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  // Add a little offset so that the results won't be close to zero.\n  t_left += t_left.constant(1.0f);\n  t_right += t_right.constant(1.0f);\n\n  typedef Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 1500, 248);\n  MapXf m_right(t_right.data(), 248, 1400);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result(1500, 1400);\n\n  // this contraction should be equivalent to a single matrix multiplication\n  Eigen::array<DimPair, 2> dims = {{DimPair(2, 0), DimPair(3, 1)}};\n\n  // compute results by separate methods\n  t_result = t_left.contract(t_right, dims);\n  m_result = m_left * m_right;\n\n  for (int i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY(&t_result.data()[i] != &m_result.data()[i]);\n    VERIFY_IS_APPROX(t_result.data()[i], m_result.data()[i]);\n  }\n}\n\ntemplate<int DataLayout>\nstatic void test_matrix_vector()\n{\n  Tensor<float, 2, DataLayout> t_left(30, 50);\n  Tensor<float, 1, DataLayout> t_right(50);\n  Tensor<float, 1, DataLayout> t_result(30);\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  typedef Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 30, 50);\n  MapXf m_right(t_right.data(), 50, 1);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result(30, 1);\n\n  // this contraction should be equivalent to a single matrix multiplication\n  Eigen::array<DimPair, 1> dims{{DimPair(1, 0)}};\n\n  // compute results by separate methods\n  t_result = t_left.contract(t_right, dims);\n  m_result = m_left * m_right;\n\n  for (int i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY(internal::isApprox(t_result(i), m_result(i, 0), 1));\n  }\n}\n\n\ntemplate<int DataLayout>\nstatic void test_tensor_vector()\n{\n  Tensor<float, 3, DataLayout> t_left(7, 13, 17);\n  Tensor<float, 2, DataLayout> t_right(1, 7);\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  typedef typename Tensor<float, 1, DataLayout>::DimensionPair DimensionPair;\n  Eigen::array<DimensionPair, 1> dim_pair01{{{0, 1}}};\n  Tensor<float, 3, DataLayout> t_result = t_left.contract(t_right, dim_pair01);\n\n  typedef Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 7, 13*17);\n  MapXf m_right(t_right.data(), 1, 7);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result = m_left.transpose() * m_right.transpose();\n\n  for (int i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY(internal::isApprox(t_result(i), m_result(i, 0), 1));\n  }\n}\n\n\ntemplate<int DataLayout>\nstatic void test_small_blocking_factors()\n{\n  Tensor<float, 4, DataLayout> t_left(30, 5, 3, 31);\n  Tensor<float, 5, DataLayout> t_right(3, 31, 7, 20, 1);\n  t_left.setRandom();\n  t_right.setRandom();\n\n  // Add a little offset so that the results won't be close to zero.\n  t_left += t_left.constant(1.0f);\n  t_right += t_right.constant(1.0f);\n\n  // Force the cache sizes, which results in smaller blocking factors.\n  Eigen::setCpuCacheSizes(896, 1920, 2944);\n\n  // this contraction should be equivalent to a single matrix multiplication\n  Eigen::array<DimPair, 2> dims = {{DimPair(2, 0), DimPair(3, 1)}};\n  Tensor<float, 5, DataLayout> t_result;\n  t_result = t_left.contract(t_right, dims);\n\n  // compute result using a simple eigen matrix product\n  Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> m_left(t_left.data(), 150, 93);\n  Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> m_right(t_right.data(), 93, 140);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result = m_left * m_right;\n\n  for (int i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY_IS_APPROX(t_result.data()[i], m_result.data()[i]);\n  }\n}\n\ntemplate<int DataLayout>\nstatic void test_tensor_product()\n{\n  Tensor<float, 2, DataLayout> mat1(2, 3);\n  Tensor<float, 2, DataLayout> mat2(4, 1);\n  mat1.setRandom();\n  mat2.setRandom();\n\n  Eigen::array<DimPair, 0> dims;\n  Tensor<float, 4, DataLayout> result = mat1.contract(mat2, dims);\n\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_EQUAL(result.dimension(1), 3);\n  VERIFY_IS_EQUAL(result.dimension(2), 4);\n  VERIFY_IS_EQUAL(result.dimension(3), 1);\n  for (int i = 0; i < result.dimension(0); ++i) {\n    for (int j = 0; j < result.dimension(1); ++j) {\n      for (int k = 0; k < result.dimension(2); ++k) {\n        for (int l = 0; l < result.dimension(3); ++l) {\n\t\t\tVERIFY_IS_APPROX(result(i, j, k, l), mat1(i, j) * mat2(k, l) );\n        }\n      }\n    }\n  }\n}\n\n\ntemplate<int DataLayout>\nstatic void test_const_inputs()\n{\n  Tensor<float, 2, DataLayout> in1(2, 3);\n  Tensor<float, 2, DataLayout> in2(3, 2);\n  in1.setRandom();\n  in2.setRandom();\n\n  TensorMap<Tensor<const float, 2, DataLayout> > mat1(in1.data(), 2, 3);\n  TensorMap<Tensor<const float, 2, DataLayout> > mat2(in2.data(), 3, 2);\n  Tensor<float, 2, DataLayout> mat3(2,2);\n\n  Eigen::array<DimPair, 1> dims = {{DimPair(1, 0)}};\n  mat3 = mat1.contract(mat2, dims);\n\n  VERIFY_IS_APPROX(mat3(0,0), mat1(0,0)*mat2(0,0) + mat1(0,1)*mat2(1,0) + mat1(0,2)*mat2(2,0));\n  VERIFY_IS_APPROX(mat3(0,1), mat1(0,0)*mat2(0,1) + mat1(0,1)*mat2(1,1) + mat1(0,2)*mat2(2,1));\n  VERIFY_IS_APPROX(mat3(1,0), mat1(1,0)*mat2(0,0) + mat1(1,1)*mat2(1,0) + mat1(1,2)*mat2(2,0));\n  VERIFY_IS_APPROX(mat3(1,1), mat1(1,0)*mat2(0,1) + mat1(1,1)*mat2(1,1) + mat1(1,2)*mat2(2,1));\n}\n\n// Apply Sqrt to all output elements.\nstruct SqrtOutputKernel {\n  template <typename Index, typename Scalar>\n  EIGEN_ALWAYS_INLINE void operator()(\n      const internal::blas_data_mapper<Scalar, Index, ColMajor>& output_mapper,\n      const TensorContractionParams&, Index, Index, Index num_rows,\n      Index num_cols) const {\n    for (int i = 0; i < num_rows; ++i) {\n      for (int j = 0; j < num_cols; ++j) {\n        output_mapper(i, j) = std::sqrt(output_mapper(i, j));\n      }\n    }\n  }\n};\n\ntemplate <int DataLayout>\nstatic void test_large_contraction_with_output_kernel() {\n  Tensor<float, 4, DataLayout> t_left(30, 50, 8, 31);\n  Tensor<float, 5, DataLayout> t_right(8, 31, 7, 20, 10);\n  Tensor<float, 5, DataLayout> t_result(30, 50, 7, 20, 10);\n\n  t_left.setRandom();\n  t_right.setRandom();\n  // Put trash in mat4 to verify contraction clears output memory.\n  t_result.setRandom();\n\n  // Add a little offset so that the results won't be close to zero.\n  t_left += t_left.constant(1.0f);\n  t_right += t_right.constant(1.0f);\n\n  typedef Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 1500, 248);\n  MapXf m_right(t_right.data(), 248, 1400);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result(1500, 1400);\n\n  // this contraction should be equivalent to a single matrix multiplication\n  Eigen::array<DimPair, 2> dims({{DimPair(2, 0), DimPair(3, 1)}});\n\n  // compute results by separate methods\n  t_result = t_left.contract(t_right, dims, SqrtOutputKernel());\n\n  m_result = m_left * m_right;\n\n  for (std::ptrdiff_t i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY(&t_result.data()[i] != &m_result.data()[i]);\n    VERIFY_IS_APPROX(t_result.data()[i], std::sqrt(m_result.data()[i]));\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_contraction)\n{\n  CALL_SUBTEST_1(test_evals<ColMajor>());\n  CALL_SUBTEST_1(test_evals<RowMajor>());\n  CALL_SUBTEST_1(test_scalar<ColMajor>());\n  CALL_SUBTEST_1(test_scalar<RowMajor>());\n  CALL_SUBTEST_2(test_multidims<ColMajor>());\n  CALL_SUBTEST_2(test_multidims<RowMajor>());\n  CALL_SUBTEST_2(test_holes<ColMajor>());\n  CALL_SUBTEST_2(test_holes<RowMajor>());\n  CALL_SUBTEST_3(test_full_redux<ColMajor>());\n  CALL_SUBTEST_3(test_full_redux<RowMajor>());\n  CALL_SUBTEST_3(test_contraction_of_contraction<ColMajor>());\n  CALL_SUBTEST_3(test_contraction_of_contraction<RowMajor>());\n  CALL_SUBTEST_4(test_expr<ColMajor>());\n  CALL_SUBTEST_4(test_expr<RowMajor>());\n  CALL_SUBTEST_4(test_out_of_order_contraction<ColMajor>());\n  CALL_SUBTEST_4(test_out_of_order_contraction<RowMajor>());\n  CALL_SUBTEST_5(test_consistency<ColMajor>());\n  CALL_SUBTEST_5(test_consistency<RowMajor>());\n  CALL_SUBTEST_5(test_large_contraction<ColMajor>());\n  CALL_SUBTEST_5(test_large_contraction<RowMajor>());\n  CALL_SUBTEST_6(test_matrix_vector<ColMajor>());\n  CALL_SUBTEST_6(test_matrix_vector<RowMajor>());\n  CALL_SUBTEST_6(test_tensor_vector<ColMajor>());\n  CALL_SUBTEST_6(test_tensor_vector<RowMajor>());\n  CALL_SUBTEST_7(test_small_blocking_factors<ColMajor>());\n  CALL_SUBTEST_7(test_small_blocking_factors<RowMajor>());\n  CALL_SUBTEST_7(test_tensor_product<ColMajor>());\n  CALL_SUBTEST_7(test_tensor_product<RowMajor>());\n  CALL_SUBTEST_8(test_const_inputs<ColMajor>());\n  CALL_SUBTEST_8(test_const_inputs<RowMajor>());\n  CALL_SUBTEST_8(test_large_contraction_with_output_kernel<ColMajor>());\n  CALL_SUBTEST_8(test_large_contraction_with_output_kernel<RowMajor>());\n\n  // Force CMake to split this test.\n  // EIGEN_SUFFIXES;1;2;3;4;5;6;7;8\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_convolution.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::DefaultDevice;\n\ntemplate <int DataLayout>\nstatic void test_evals()\n{\n  Tensor<float, 2, DataLayout> input(3, 3);\n  Tensor<float, 1, DataLayout> kernel(2);\n\n  input.setRandom();\n  kernel.setRandom();\n\n  Tensor<float, 2, DataLayout> result(2,3);\n  result.setZero();\n  Eigen::array<Tensor<float, 2>::Index, 1> dims3;\n  dims3[0] = 0;\n\n  typedef TensorEvaluator<decltype(input.convolve(kernel, dims3)), DefaultDevice> Evaluator;\n  Evaluator eval(input.convolve(kernel, dims3), DefaultDevice());\n  eval.evalTo(result.data());\n  EIGEN_STATIC_ASSERT(Evaluator::NumDims==2ul, YOU_MADE_A_PROGRAMMING_MISTAKE);\n  VERIFY_IS_EQUAL(eval.dimensions()[0], 2);\n  VERIFY_IS_EQUAL(eval.dimensions()[1], 3);\n\n  VERIFY_IS_APPROX(result(0,0), input(0,0)*kernel(0) + input(1,0)*kernel(1));  // index 0\n  VERIFY_IS_APPROX(result(0,1), input(0,1)*kernel(0) + input(1,1)*kernel(1));  // index 2\n  VERIFY_IS_APPROX(result(0,2), input(0,2)*kernel(0) + input(1,2)*kernel(1));  // index 4\n  VERIFY_IS_APPROX(result(1,0), input(1,0)*kernel(0) + input(2,0)*kernel(1));  // index 1\n  VERIFY_IS_APPROX(result(1,1), input(1,1)*kernel(0) + input(2,1)*kernel(1));  // index 3\n  VERIFY_IS_APPROX(result(1,2), input(1,2)*kernel(0) + input(2,2)*kernel(1));  // index 5\n}\n\ntemplate <int DataLayout>\nstatic void test_expr()\n{\n  Tensor<float, 2, DataLayout> input(3, 3);\n  Tensor<float, 2, DataLayout> kernel(2, 2);\n  input.setRandom();\n  kernel.setRandom();\n\n  Tensor<float, 2, DataLayout> result(2,2);\n  Eigen::array<ptrdiff_t, 2> dims;\n  dims[0] = 0;\n  dims[1] = 1;\n  result = input.convolve(kernel, dims);\n\n  VERIFY_IS_APPROX(result(0,0), input(0,0)*kernel(0,0) + input(0,1)*kernel(0,1) +\n                                input(1,0)*kernel(1,0) + input(1,1)*kernel(1,1));\n  VERIFY_IS_APPROX(result(0,1), input(0,1)*kernel(0,0) + input(0,2)*kernel(0,1) +\n                                input(1,1)*kernel(1,0) + input(1,2)*kernel(1,1));\n  VERIFY_IS_APPROX(result(1,0), input(1,0)*kernel(0,0) + input(1,1)*kernel(0,1) +\n                                input(2,0)*kernel(1,0) + input(2,1)*kernel(1,1));\n  VERIFY_IS_APPROX(result(1,1), input(1,1)*kernel(0,0) + input(1,2)*kernel(0,1) +\n                                input(2,1)*kernel(1,0) + input(2,2)*kernel(1,1));\n}\n\ntemplate <int DataLayout>\nstatic void test_modes() {\n  Tensor<float, 1, DataLayout> input(3);\n  Tensor<float, 1, DataLayout> kernel(3);\n  input(0) = 1.0f;\n  input(1) = 2.0f;\n  input(2) = 3.0f;\n  kernel(0) = 0.5f;\n  kernel(1) = 1.0f;\n  kernel(2) = 0.0f;\n\n  Eigen::array<ptrdiff_t, 1> dims;\n  dims[0] = 0;\n  Eigen::array<std::pair<ptrdiff_t, ptrdiff_t>, 1> padding;\n\n  // Emulate VALID mode (as defined in\n  // http://docs.scipy.org/doc/numpy/reference/generated/numpy.convolve.html).\n  padding[0] = std::make_pair(0, 0);\n  Tensor<float, 1, DataLayout> valid(1);\n  valid = input.pad(padding).convolve(kernel, dims);\n  VERIFY_IS_EQUAL(valid.dimension(0), 1);\n  VERIFY_IS_APPROX(valid(0), 2.5f);\n\n  // Emulate SAME mode (as defined in\n  // http://docs.scipy.org/doc/numpy/reference/generated/numpy.convolve.html).\n  padding[0] = std::make_pair(1, 1);\n  Tensor<float, 1, DataLayout> same(3);\n  same = input.pad(padding).convolve(kernel, dims);\n  VERIFY_IS_EQUAL(same.dimension(0), 3);\n  VERIFY_IS_APPROX(same(0), 1.0f);\n  VERIFY_IS_APPROX(same(1), 2.5f);\n  VERIFY_IS_APPROX(same(2), 4.0f);\n\n  // Emulate FULL mode (as defined in\n  // http://docs.scipy.org/doc/numpy/reference/generated/numpy.convolve.html).\n  padding[0] = std::make_pair(2, 2);\n  Tensor<float, 1, DataLayout> full(5);\n  full = input.pad(padding).convolve(kernel, dims);\n  VERIFY_IS_EQUAL(full.dimension(0), 5);\n  VERIFY_IS_APPROX(full(0), 0.0f);\n  VERIFY_IS_APPROX(full(1), 1.0f);\n  VERIFY_IS_APPROX(full(2), 2.5f);\n  VERIFY_IS_APPROX(full(3), 4.0f);\n  VERIFY_IS_APPROX(full(4), 1.5f);\n}\n\ntemplate <int DataLayout>\nstatic void test_strides() {\n  Tensor<float, 1, DataLayout> input(13);\n  Tensor<float, 1, DataLayout> kernel(3);\n  input.setRandom();\n  kernel.setRandom();\n\n  Eigen::array<ptrdiff_t, 1> dims;\n  dims[0] = 0;\n  Eigen::array<ptrdiff_t, 1> stride_of_3;\n  stride_of_3[0] = 3;\n  Eigen::array<ptrdiff_t, 1> stride_of_2;\n  stride_of_2[0] = 2;\n\n  Tensor<float, 1, DataLayout> result;\n  result = input.stride(stride_of_3).convolve(kernel, dims).stride(stride_of_2);\n\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_APPROX(result(0), (input(0)*kernel(0) + input(3)*kernel(1) +\n                               input(6)*kernel(2)));\n  VERIFY_IS_APPROX(result(1), (input(6)*kernel(0) + input(9)*kernel(1) +\n                               input(12)*kernel(2)));\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_convolution)\n{\n  CALL_SUBTEST(test_evals<ColMajor>());\n  CALL_SUBTEST(test_evals<RowMajor>());\n  CALL_SUBTEST(test_expr<ColMajor>());\n  CALL_SUBTEST(test_expr<RowMajor>());\n  CALL_SUBTEST(test_modes<ColMajor>());\n  CALL_SUBTEST(test_modes<RowMajor>());\n  CALL_SUBTEST(test_strides<ColMajor>());\n  CALL_SUBTEST(test_strides<RowMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_convolution_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include <iostream>\n#include <chrono>\n#include <ctime>\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n#include <iomanip>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\nstatic const float error_threshold =1e-4f;\n\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_larg_expr1D(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType indim0 =53;\n  IndexType indim1= 55;\n  IndexType indim2= 51;\n  IndexType outdim0=50;\n  IndexType outdim1=55;\n  IndexType outdim2=51;\n  Eigen::array<IndexType, 3> input_dims = {{indim0, indim1, indim2}};\n  Eigen::array<IndexType, 1> kernel_dims = {{4}};\n  Eigen::array<IndexType, 3> result_dims = {{outdim0, outdim1, outdim2}};\n\n  Tensor<DataType, 3, DataLayout, IndexType> input(input_dims);\n  Tensor<DataType, 1, DataLayout,IndexType> kernel(kernel_dims);\n  Tensor<DataType, 3, DataLayout,IndexType> result(result_dims);\n  Tensor<DataType, 3, DataLayout,IndexType> result_host(result_dims);\n\n  Eigen::array<IndexType, 1> dims3{{0}};\n\n  input.setRandom();\n  kernel.setRandom();\n  result.setZero();\n  result_host.setZero();\n\n  std::size_t input_bytes = input.size()  * sizeof(DataType);\n  std::size_t kernel_bytes = kernel.size() * sizeof(DataType);\n  std::size_t result_bytes = result.size() * sizeof(DataType);\n\n  DataType * d_input  = static_cast<DataType*>(sycl_device.allocate(input_bytes));\n  DataType * d_kernel  = static_cast<DataType*>(sycl_device.allocate(kernel_bytes));\n  DataType * d_result =  static_cast<DataType*>(sycl_device.allocate(result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType> > gpu_input(d_input, input_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 1, DataLayout, IndexType> > gpu_kernel(d_kernel, kernel_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType> > gpu_result(d_result, result_dims);\n  sycl_device.memcpyHostToDevice(d_input, input.data(), input_bytes);\n  sycl_device.memcpyHostToDevice(d_kernel, kernel.data(), kernel_bytes);\n\n  gpu_result.device(sycl_device)=gpu_input.convolve(gpu_kernel, dims3);\n  sycl_device.memcpyDeviceToHost(result.data(), d_result, result_bytes);\n\n  result_host=input.convolve(kernel, dims3);\n\nfor(IndexType i=0; i< outdim0; i++ ){\n  for(IndexType j=0; j< outdim1; j++ ){\n    for(IndexType k=0; k< outdim2; k++ ){\n      if (!(Eigen::internal::isApprox(result(i,j,k), result_host(i,j,k), error_threshold))) {\n        std::cout <<std::setprecision(16)<< \"mismatch detected at index  ( \"<< i  << \" , \"  << j  << \", \" << k << \" ) \" << \" \\t \" << result(i,j,k) << \" vs \"<<  result_host(i,j,k) << std::endl;\n        assert(false);\n      }\n    }\n  }\n}\n  sycl_device.deallocate(d_input);\n  sycl_device.deallocate(d_kernel);\n  sycl_device.deallocate(d_result);\n\n}\n\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_larg_expr2D(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType indim0 =53;\n  IndexType indim1= 55;\n  IndexType indim2= 51;\n  IndexType outdim0=50;\n  IndexType outdim1=51;\n  IndexType outdim2=51;\n  Eigen::array<IndexType, 3> input_dims = {{indim0, indim1, indim2}};\n  Eigen::array<IndexType, 2> kernel_dims = {{4,5}};\n  Eigen::array<IndexType, 3> result_dims = {{outdim0, outdim1, outdim2}};\n\n  Tensor<DataType, 3, DataLayout, IndexType> input(input_dims);\n  Tensor<DataType, 2, DataLayout,IndexType> kernel(kernel_dims);\n  Tensor<DataType, 3, DataLayout,IndexType> result(result_dims);\n  Tensor<DataType, 3, DataLayout,IndexType> result_host(result_dims);\n\n  Eigen::array<IndexType, 2> dims3{{0,1}};\n\n  input.setRandom();\n  kernel.setRandom();\n  result.setZero();\n  result_host.setZero();\n\n  std::size_t input_bytes = input.size()  * sizeof(DataType);\n  std::size_t kernel_bytes = kernel.size() * sizeof(DataType);\n  std::size_t result_bytes = result.size() * sizeof(DataType);\n\n  DataType * d_input  = static_cast<DataType*>(sycl_device.allocate(input_bytes));\n  DataType * d_kernel  = static_cast<DataType*>(sycl_device.allocate(kernel_bytes));\n  DataType * d_result =  static_cast<DataType*>(sycl_device.allocate(result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType> > gpu_input(d_input, input_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType> > gpu_kernel(d_kernel, kernel_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType> > gpu_result(d_result, result_dims);\n  sycl_device.memcpyHostToDevice(d_input, input.data(), input_bytes);\n  sycl_device.memcpyHostToDevice(d_kernel, kernel.data(), kernel_bytes);\n\n  gpu_result.device(sycl_device)=gpu_input.convolve(gpu_kernel, dims3);\n  sycl_device.memcpyDeviceToHost(result.data(), d_result, result_bytes);\n\n  result_host=input.convolve(kernel, dims3);\n\nfor(IndexType i=0; i< outdim0; i++ ){\n  for(IndexType j=0; j< outdim1; j++ ){\n    for(IndexType k=0; k< outdim2; k++ ){\n      if (!(Eigen::internal::isApprox(result(i,j,k), result_host(i,j,k), error_threshold))) {\n        std::cout <<std::setprecision(16)<< \"mismatch detected at index  ( \"<< i  << \" , \"  << j  << \", \" << k << \" ) \" << \" \\t \" << result(i,j,k) << \" vs \"<<  result_host(i,j,k) << std::endl;\n        assert(false);\n      }\n    }\n  }\n}\n  sycl_device.deallocate(d_input);\n  sycl_device.deallocate(d_kernel);\n  sycl_device.deallocate(d_result);\n\n}\n\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_larg_expr3D(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType indim0 =53;\n  IndexType indim1= 55;\n  IndexType indim2= 51;\n  IndexType outdim0=50;\n  IndexType outdim1=51;\n  IndexType outdim2=49;\n  Eigen::array<IndexType, 3> input_dims = {{indim0, indim1, indim2}};\n  Eigen::array<IndexType, 3> kernel_dims = {{4,5,3}};\n  Eigen::array<IndexType, 3> result_dims = {{outdim0, outdim1, outdim2}};\n\n  Tensor<DataType, 3, DataLayout, IndexType> input(input_dims);\n  Tensor<DataType, 3, DataLayout,IndexType> kernel(kernel_dims);\n  Tensor<DataType, 3, DataLayout,IndexType> result(result_dims);\n  Tensor<DataType, 3, DataLayout,IndexType> result_host(result_dims);\n\n  Eigen::array<IndexType, 3> dims3{{0,1,2}};\n\n  input.setRandom();\n  kernel.setRandom();\n  result.setZero();\n  result_host.setZero();\n\n  std::size_t input_bytes = input.size()  * sizeof(DataType);\n  std::size_t kernel_bytes = kernel.size() * sizeof(DataType);\n  std::size_t result_bytes = result.size() * sizeof(DataType);\n\n  DataType * d_input  = static_cast<DataType*>(sycl_device.allocate(input_bytes));\n  DataType * d_kernel  = static_cast<DataType*>(sycl_device.allocate(kernel_bytes));\n  DataType * d_result =  static_cast<DataType*>(sycl_device.allocate(result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType> > gpu_input(d_input, input_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType> > gpu_kernel(d_kernel, kernel_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType> > gpu_result(d_result, result_dims);\n  sycl_device.memcpyHostToDevice(d_input, input.data(), input_bytes);\n  sycl_device.memcpyHostToDevice(d_kernel, kernel.data(), kernel_bytes);\n\n  gpu_result.device(sycl_device)=gpu_input.convolve(gpu_kernel, dims3);\n  sycl_device.memcpyDeviceToHost(result.data(), d_result, result_bytes);\n\n  result_host=input.convolve(kernel, dims3);\n\nfor(IndexType i=0; i< outdim0; i++ ){\n  for(IndexType j=0; j< outdim1; j++ ){\n    for(IndexType k=0; k< outdim2; k++ ){\n      if (!(Eigen::internal::isApprox(result(i,j,k), result_host(i,j,k), error_threshold))) {\n        std::cout <<std::setprecision(16)<< \"mismatch detected at index  ( \"<< i  << \" , \"  << j  << \", \" << k << \" ) \" << \" \\t \" << result(i,j,k) << \" vs \"<<  result_host(i,j,k) << std::endl;\n        assert(false);\n      }\n    }\n  }\n}\n  sycl_device.deallocate(d_input);\n  sycl_device.deallocate(d_kernel);\n  sycl_device.deallocate(d_result);\n\n}\n\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_evals(const Eigen::SyclDevice& sycl_device)\n{\n  Eigen::array<IndexType, 2> input_dims = {{3, 3}};\n  Eigen::array<IndexType, 1> kernel_dims = {{2}};\n  Eigen::array<IndexType, 2> result_dims = {{2, 3}};\n\n  Tensor<DataType, 2, DataLayout, IndexType> input(input_dims);\n  Tensor<DataType, 1, DataLayout,IndexType> kernel(kernel_dims);\n  Tensor<DataType, 2, DataLayout,IndexType> result(result_dims);\n\n  Eigen::array<IndexType, 1> dims3{{0}};\n\n  input.setRandom();\n  kernel.setRandom();\n  result.setZero();\n\n  std::size_t input_bytes = input.size()  * sizeof(DataType);\n  std::size_t kernel_bytes = kernel.size() * sizeof(DataType);\n  std::size_t result_bytes = result.size() * sizeof(DataType);\n\n  DataType * d_input  = static_cast<DataType*>(sycl_device.allocate(input_bytes));\n  DataType * d_kernel  = static_cast<DataType*>(sycl_device.allocate(kernel_bytes));\n  DataType * d_result =  static_cast<DataType*>(sycl_device.allocate(result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType> > gpu_input(d_input, input_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 1, DataLayout, IndexType> > gpu_kernel(d_kernel, kernel_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType> > gpu_result(d_result, result_dims);\n  sycl_device.memcpyHostToDevice(d_input, input.data(), input_bytes);\n  sycl_device.memcpyHostToDevice(d_kernel, kernel.data(), kernel_bytes);\n\n  gpu_result.device(sycl_device)=gpu_input.convolve(gpu_kernel, dims3);\n  sycl_device.memcpyDeviceToHost(result.data(), d_result, result_bytes);\n\n  VERIFY_IS_APPROX(result(0,0), input(0,0)*kernel(0) + input(1,0)*kernel(1));  // index 0\n  VERIFY_IS_APPROX(result(0,1), input(0,1)*kernel(0) + input(1,1)*kernel(1));  // index 2\n  VERIFY_IS_APPROX(result(0,2), input(0,2)*kernel(0) + input(1,2)*kernel(1));  // index 4\n  VERIFY_IS_APPROX(result(1,0), input(1,0)*kernel(0) + input(2,0)*kernel(1));  // index 1\n  VERIFY_IS_APPROX(result(1,1), input(1,1)*kernel(0) + input(2,1)*kernel(1));  // index 3\n  VERIFY_IS_APPROX(result(1,2), input(1,2)*kernel(0) + input(2,2)*kernel(1));  // index 5\n\n  sycl_device.deallocate(d_input);\n  sycl_device.deallocate(d_kernel);\n  sycl_device.deallocate(d_result);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_expr(const Eigen::SyclDevice& sycl_device)\n{\n  Eigen::array<IndexType, 2> input_dims = {{3, 3}};\n  Eigen::array<IndexType, 2> kernel_dims = {{2, 2}};\n  Eigen::array<IndexType, 2> result_dims = {{2, 2}};\n\n  Tensor<DataType, 2, DataLayout, IndexType> input(input_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> kernel(kernel_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> result(result_dims);\n\n  input.setRandom();\n  kernel.setRandom();\n  Eigen::array<IndexType, 2> dims;\n  dims[0] = 0;\n  dims[1] = 1;\n\n  std::size_t input_bytes = input.size()  * sizeof(DataType);\n  std::size_t kernel_bytes = kernel.size() * sizeof(DataType);\n  std::size_t result_bytes = result.size() * sizeof(DataType);\n\n  DataType * d_input  = static_cast<DataType*>(sycl_device.allocate(input_bytes));\n  DataType * d_kernel  = static_cast<DataType*>(sycl_device.allocate(kernel_bytes));\n  DataType * d_result =  static_cast<DataType*>(sycl_device.allocate(result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout,IndexType> > gpu_input(d_input, input_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout,IndexType> > gpu_kernel(d_kernel, kernel_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout,IndexType> > gpu_result(d_result, result_dims);\n  sycl_device.memcpyHostToDevice(d_input, input.data(), input_bytes);\n  sycl_device.memcpyHostToDevice(d_kernel, kernel.data(), kernel_bytes);\n\n  gpu_result.device(sycl_device)=gpu_input.convolve(gpu_kernel, dims);\n  sycl_device.memcpyDeviceToHost(result.data(), d_result, result_bytes);\n\n  VERIFY_IS_APPROX(result(0,0), input(0,0)*kernel(0,0) + input(0,1)*kernel(0,1) +\n                                input(1,0)*kernel(1,0) + input(1,1)*kernel(1,1));\n  VERIFY_IS_APPROX(result(0,1), input(0,1)*kernel(0,0) + input(0,2)*kernel(0,1) +\n                                input(1,1)*kernel(1,0) + input(1,2)*kernel(1,1));\n  VERIFY_IS_APPROX(result(1,0), input(1,0)*kernel(0,0) + input(1,1)*kernel(0,1) +\n                                input(2,0)*kernel(1,0) + input(2,1)*kernel(1,1));\n  VERIFY_IS_APPROX(result(1,1), input(1,1)*kernel(0,0) + input(1,2)*kernel(0,1) +\n                                input(2,1)*kernel(1,0) + input(2,2)*kernel(1,1));\n\n  sycl_device.deallocate(d_input);\n  sycl_device.deallocate(d_kernel);\n  sycl_device.deallocate(d_result);\n}\n\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_modes(const Eigen::SyclDevice& sycl_device){\n\nEigen::array<IndexType, 1> input_dims = {{3}};\nEigen::array<IndexType, 1> kernel_dims = {{3}};\n\nTensor<DataType, 1, DataLayout, IndexType> input(input_dims);\nTensor<DataType, 1, DataLayout, IndexType> kernel(kernel_dims);\n\ninput.setRandom();\nkernel.setRandom();\nEigen::array<IndexType, 1> dims;\ndims[0] = 0;\n\n  input(0) = 1.0f;\n  input(1) = 2.0f;\n  input(2) = 3.0f;\n  kernel(0) = 0.5f;\n  kernel(1) = 1.0f;\n  kernel(2) = 0.0f;\n\n  Eigen::array<std::pair<IndexType, IndexType>, 1> padding;\n\n  // Emulate VALID mode (as defined in\n  // http://docs.scipy.org/doc/numpy/reference/generated/numpy.convolve.html).\n  padding[0] = std::make_pair(0, 0);\n  Tensor<DataType, 1, DataLayout, IndexType> valid(1);\n\n  std::size_t input_bytes = input.size()  * sizeof(DataType);\n  std::size_t kernel_bytes = kernel.size() * sizeof(DataType);\n  std::size_t valid_bytes = valid.size() * sizeof(DataType);\n\n  DataType * d_input  = static_cast<DataType*>(sycl_device.allocate(input_bytes));\n  DataType * d_kernel  = static_cast<DataType*>(sycl_device.allocate(kernel_bytes));\n  DataType * d_valid =  static_cast<DataType*>(sycl_device.allocate(valid_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 1, DataLayout,IndexType> > gpu_input(d_input, input_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 1, DataLayout,IndexType> > gpu_kernel(d_kernel, kernel_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 1, DataLayout,IndexType> > gpu_valid(d_valid, valid.dimensions());\n  sycl_device.memcpyHostToDevice(d_input, input.data(), input_bytes);\n  sycl_device.memcpyHostToDevice(d_kernel, kernel.data(), kernel_bytes);\n\n  gpu_valid.device(sycl_device)=gpu_input.pad(padding).convolve(gpu_kernel, dims);\n  sycl_device.memcpyDeviceToHost(valid.data(), d_valid, valid_bytes);\n\n  VERIFY_IS_EQUAL(valid.dimension(0), 1);\n  VERIFY_IS_APPROX(valid(0), 2.5f);\n\n  // Emulate SAME mode (as defined in\n  // http://docs.scipy.org/doc/numpy/reference/generated/numpy.convolve.html).\n  padding[0] = std::make_pair(1, 1);\n  Tensor<DataType, 1, DataLayout, IndexType> same(3);\n  std::size_t same_bytes = same.size() * sizeof(DataType);\n  DataType * d_same =  static_cast<DataType*>(sycl_device.allocate(same_bytes));\n  Eigen::TensorMap<Eigen::Tensor<DataType, 1, DataLayout,IndexType> > gpu_same(d_same, same.dimensions());\n  gpu_same.device(sycl_device)=gpu_input.pad(padding).convolve(gpu_kernel, dims);\n  sycl_device.memcpyDeviceToHost(same.data(), d_same, same_bytes);\n\n  VERIFY_IS_EQUAL(same.dimension(0), 3);\n  VERIFY_IS_APPROX(same(0), 1.0f);\n  VERIFY_IS_APPROX(same(1), 2.5f);\n  VERIFY_IS_APPROX(same(2), 4.0f);\n\n  // Emulate FULL mode (as defined in\n  // http://docs.scipy.org/doc/numpy/reference/generated/numpy.convolve.html).\n  padding[0] = std::make_pair(2, 2);\n\n  Tensor<DataType, 1, DataLayout, IndexType> full(5);\n  std::size_t full_bytes = full.size() * sizeof(DataType);\n  DataType * d_full =  static_cast<DataType*>(sycl_device.allocate(full_bytes));\n  Eigen::TensorMap<Eigen::Tensor<DataType, 1, DataLayout,IndexType> > gpu_full(d_full, full.dimensions());\n  gpu_full.device(sycl_device)=gpu_input.pad(padding).convolve(gpu_kernel, dims);\n  sycl_device.memcpyDeviceToHost(full.data(), d_full, full_bytes);\n\n  VERIFY_IS_EQUAL(full.dimension(0), 5);\n  VERIFY_IS_APPROX(full(0), 0.0f);\n  VERIFY_IS_APPROX(full(1), 1.0f);\n  VERIFY_IS_APPROX(full(2), 2.5f);\n  VERIFY_IS_APPROX(full(3), 4.0f);\n  VERIFY_IS_APPROX(full(4), 1.5f);\n\n  sycl_device.deallocate(d_input);\n  sycl_device.deallocate(d_kernel);\n  sycl_device.deallocate(d_valid);\n  sycl_device.deallocate(d_same);\n  sycl_device.deallocate(d_full);\n\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_strides(const Eigen::SyclDevice& sycl_device){\n\n  Eigen::array<IndexType, 1> input_dims = {{13}};\n  Eigen::array<IndexType, 1> kernel_dims = {{3}};\n\n  Tensor<DataType, 1, DataLayout, IndexType> input(input_dims);\n  Tensor<DataType, 1, DataLayout, IndexType> kernel(kernel_dims);\n  Tensor<DataType, 1, DataLayout, IndexType> result(2);\n\n  input.setRandom();\n  kernel.setRandom();\n  Eigen::array<IndexType, 1> dims;\n  dims[0] = 0;\n\n  Eigen::array<IndexType, 1> stride_of_3;\n  stride_of_3[0] = 3;\n  Eigen::array<IndexType, 1> stride_of_2;\n  stride_of_2[0] = 2;\n\n  std::size_t input_bytes = input.size()  * sizeof(DataType);\n  std::size_t kernel_bytes = kernel.size() * sizeof(DataType);\n  std::size_t result_bytes = result.size() * sizeof(DataType);\n\n  DataType * d_input  = static_cast<DataType*>(sycl_device.allocate(input_bytes));\n  DataType * d_kernel  = static_cast<DataType*>(sycl_device.allocate(kernel_bytes));\n  DataType * d_result =  static_cast<DataType*>(sycl_device.allocate(result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 1, DataLayout,IndexType> > gpu_input(d_input, input_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 1, DataLayout,IndexType> > gpu_kernel(d_kernel, kernel_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 1, DataLayout,IndexType> > gpu_result(d_result, result.dimensions());\n  sycl_device.memcpyHostToDevice(d_input, input.data(), input_bytes);\n  sycl_device.memcpyHostToDevice(d_kernel, kernel.data(), kernel_bytes);\n\n  gpu_result.device(sycl_device)=gpu_input.stride(stride_of_3).convolve(gpu_kernel, dims).stride(stride_of_2);\n  sycl_device.memcpyDeviceToHost(result.data(), d_result, result_bytes);\n\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_APPROX(result(0), (input(0)*kernel(0) + input(3)*kernel(1) +\n                               input(6)*kernel(2)));\n  VERIFY_IS_APPROX(result(1), (input(6)*kernel(0) + input(9)*kernel(1) +\n                               input(12)*kernel(2)));\n}\n\ntemplate <typename Dev_selector> void tensorConvolutionPerDevice(Dev_selector& s){\n  QueueInterface queueInterface(s);\n  auto sycl_device=Eigen::SyclDevice(&queueInterface);\n  test_larg_expr1D<float, RowMajor, int64_t>(sycl_device);\n  test_larg_expr1D<float, ColMajor, int64_t>(sycl_device);\n  test_larg_expr2D<float, RowMajor, int64_t>(sycl_device);\n  test_larg_expr2D<float, ColMajor, int64_t>(sycl_device);\n  test_larg_expr3D<float, RowMajor, int64_t>(sycl_device);\n  test_larg_expr3D<float, ColMajor, int64_t>(sycl_device);\n  test_evals<float, ColMajor, int64_t>(sycl_device);\n  test_evals<float, RowMajor, int64_t>(sycl_device);\n  test_expr<float, ColMajor, int64_t>(sycl_device);\n  test_expr<float, RowMajor, int64_t>(sycl_device);\n  test_modes<float, ColMajor, int64_t>(sycl_device);\n  test_modes<float, RowMajor, int64_t>(sycl_device);\n  test_strides<float, ColMajor, int64_t>(sycl_device);\n  test_strides<float, RowMajor, int64_t>(sycl_device);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_convolution_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(tensorConvolutionPerDevice(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_custom_index.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <limits>\n#include <map>\n\n#include <Eigen/Dense>\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\n\ntemplate <int DataLayout>\nstatic void test_map_as_index()\n{\n#ifdef EIGEN_HAS_SFINAE\n  Tensor<float, 4, DataLayout> tensor(2, 3, 5, 7);\n  tensor.setRandom();\n\n  using NormalIndex = DSizes<ptrdiff_t, 4>;\n  using CustomIndex = std::map<ptrdiff_t, ptrdiff_t>;\n  CustomIndex coeffC;\n  coeffC[0] = 1;\n  coeffC[1] = 2;\n  coeffC[2] = 4;\n  coeffC[3] = 1;\n  NormalIndex coeff(1,2,4,1);\n\n  VERIFY_IS_EQUAL(tensor.coeff(coeffC), tensor.coeff(coeff));\n  VERIFY_IS_EQUAL(tensor.coeffRef(coeffC), tensor.coeffRef(coeff));\n#endif\n}\n\n\ntemplate <int DataLayout>\nstatic void test_matrix_as_index()\n{\n#ifdef EIGEN_HAS_SFINAE\n  Tensor<float, 4, DataLayout> tensor(2, 3, 5, 7);\n  tensor.setRandom();\n\n  using NormalIndex = DSizes<ptrdiff_t, 4>;\n  using CustomIndex = Matrix<unsigned int, 4, 1>;\n  CustomIndex coeffC(1,2,4,1);\n  NormalIndex coeff(1,2,4,1);\n\n  VERIFY_IS_EQUAL(tensor.coeff(coeffC), tensor.coeff(coeff));\n  VERIFY_IS_EQUAL(tensor.coeffRef(coeffC), tensor.coeffRef(coeff));\n#endif\n}\n\n\ntemplate <int DataLayout>\nstatic void test_varlist_as_index()\n{\n#ifdef EIGEN_HAS_SFINAE\n  Tensor<float, 4, DataLayout> tensor(2, 3, 5, 7);\n  tensor.setRandom();\n\n  DSizes<ptrdiff_t, 4> coeff(1,2,4,1);\n\n  VERIFY_IS_EQUAL(tensor.coeff({1,2,4,1}), tensor.coeff(coeff));\n  VERIFY_IS_EQUAL(tensor.coeffRef({1,2,4,1}), tensor.coeffRef(coeff));\n#endif\n}\n\n\ntemplate <int DataLayout>\nstatic void test_sizes_as_index()\n{\n#ifdef EIGEN_HAS_SFINAE\n  Tensor<float, 4, DataLayout> tensor(2, 3, 5, 7);\n  tensor.setRandom();\n\n  DSizes<ptrdiff_t, 4> coeff(1,2,4,1);\n  Sizes<1,2,4,1> coeffC;\n\n  VERIFY_IS_EQUAL(tensor.coeff(coeffC), tensor.coeff(coeff));\n  VERIFY_IS_EQUAL(tensor.coeffRef(coeffC), tensor.coeffRef(coeff));\n#endif\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_custom_index) {\n  test_map_as_index<ColMajor>();\n  test_map_as_index<RowMajor>();\n  test_matrix_as_index<ColMajor>();\n  test_matrix_as_index<RowMajor>();\n  test_varlist_as_index<ColMajor>();\n  test_varlist_as_index<RowMajor>();\n  test_sizes_as_index<ColMajor>();\n  test_sizes_as_index<RowMajor>();\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_custom_op.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\n\nstruct InsertZeros {\n  DSizes<DenseIndex, 2> dimensions(const Tensor<float, 2>& input) const {\n    DSizes<DenseIndex, 2> result;\n    result[0] = input.dimension(0) * 2;\n    result[1] = input.dimension(1) * 2;\n    return result;\n  }\n\n  template <typename Output, typename Device>\n  void eval(const Tensor<float, 2>& input, Output& output, const Device& device) const\n  {\n    array<DenseIndex, 2> strides;\n    strides[0] = 2;\n    strides[1] = 2;\n    output.stride(strides).device(device) = input;\n\n    Eigen::DSizes<DenseIndex, 2> offsets(1,1);\n    Eigen::DSizes<DenseIndex, 2> extents(output.dimension(0)-1, output.dimension(1)-1);\n    output.slice(offsets, extents).stride(strides).device(device) = input.constant(0.0f);\n  }\n};\n\nstatic void test_custom_unary_op()\n{\n  Tensor<float, 2> tensor(3,5);\n  tensor.setRandom();\n\n  Tensor<float, 2> result = tensor.customOp(InsertZeros());\n  VERIFY_IS_EQUAL(result.dimension(0), 6);\n  VERIFY_IS_EQUAL(result.dimension(1), 10);\n\n  for (int i = 0; i < 6; i+=2) {\n    for (int j = 0; j < 10; j+=2) {\n      VERIFY_IS_EQUAL(result(i, j), tensor(i/2, j/2));\n    }\n  }\n  for (int i = 1; i < 6; i+=2) {\n    for (int j = 1; j < 10; j+=2) {\n      VERIFY_IS_EQUAL(result(i, j), 0);\n    }\n  }\n}\n\n\nstruct BatchMatMul {\n  DSizes<DenseIndex, 3> dimensions(const Tensor<float, 3>& input1, const Tensor<float, 3>& input2) const {\n    DSizes<DenseIndex, 3> result;\n    result[0] = input1.dimension(0);\n    result[1] = input2.dimension(1);\n    result[2] = input2.dimension(2);\n    return result;\n  }\n\n  template <typename Output, typename Device>\n  void eval(const Tensor<float, 3>& input1, const Tensor<float, 3>& input2,\n            Output& output, const Device& device) const\n  {\n    typedef Tensor<float, 3>::DimensionPair DimPair;\n    array<DimPair, 1> dims;\n    dims[0] = DimPair(1, 0);\n    for (int i = 0; i < output.dimension(2); ++i) {\n      output.template chip<2>(i).device(device) = input1.chip<2>(i).contract(input2.chip<2>(i), dims);\n    }\n  }\n};\n\n\nstatic void test_custom_binary_op()\n{\n  Tensor<float, 3> tensor1(2,3,5);\n  tensor1.setRandom();\n  Tensor<float, 3> tensor2(3,7,5);\n  tensor2.setRandom();\n\n  Tensor<float, 3> result = tensor1.customOp(tensor2, BatchMatMul());\n  for (int i = 0; i < 5; ++i) {\n    typedef Tensor<float, 3>::DimensionPair DimPair;\n    array<DimPair, 1> dims;\n    dims[0] = DimPair(1, 0);\n    Tensor<float, 2> reference = tensor1.chip<2>(i).contract(tensor2.chip<2>(i), dims);\n    TensorRef<Tensor<float, 2> > val = result.chip<2>(i);\n    for (int j = 0; j < 2; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(val(j, k), reference(j, k));\n      }\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_custom_op)\n{\n  CALL_SUBTEST(test_custom_unary_op());\n  CALL_SUBTEST(test_custom_binary_op());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_custom_op_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\ntemplate<typename TensorType>\nstruct InsertZeros {\n  DSizes<DenseIndex, 2> dimensions(const TensorType& input) const {\n    DSizes<DenseIndex, 2> result;\n    result[0] = input.dimension(0) * 2;\n    result[1] = input.dimension(1) * 2;\n    return result;\n  }\n\n  template <typename Output, typename Device>\n  void eval(const TensorType& input, Output& output, const Device& device) const\n  {\n    array<DenseIndex, 2> strides;\n    strides[0] = 2;\n    strides[1] = 2;\n    output.stride(strides).device(device) = input;\n\n    Eigen::DSizes<DenseIndex, 2> offsets(1,1);\n    Eigen::DSizes<DenseIndex, 2> extents(output.dimension(0)-1, output.dimension(1)-1);\n    output.slice(offsets, extents).stride(strides).device(device) = input.constant(0.0f);\n  }\n};\n\ntemplate<typename DataType, int DataLayout, typename IndexType>\nstatic void test_custom_unary_op_sycl(const Eigen::SyclDevice &sycl_device)\n{\n  IndexType sizeDim1 = 3;\n  IndexType sizeDim2 = 5;\n  Eigen::array<IndexType, 2> tensorRange = {{sizeDim1, sizeDim2}};\n  Eigen::array<IndexType, 2> tensorResultRange = {{6, 10}};\n\n  Eigen::Tensor<DataType, 2, DataLayout, IndexType> in1(tensorRange);\n  Eigen::Tensor<DataType, 2, DataLayout, IndexType> out(tensorResultRange);\n\n  DataType * gpu_in1_data  = static_cast<DataType*>(sycl_device.allocate(in1.dimensions().TotalSize()*sizeof(DataType)));\n  DataType * gpu_out_data =  static_cast<DataType*>(sycl_device.allocate(out.dimensions().TotalSize()*sizeof(DataType)));\n\n  typedef Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType> > TensorType;\n  TensorType gpu_in1(gpu_in1_data, tensorRange);\n  TensorType gpu_out(gpu_out_data, tensorResultRange);\n\n  in1.setRandom();\n  sycl_device.memcpyHostToDevice(gpu_in1_data, in1.data(),(in1.dimensions().TotalSize())*sizeof(DataType));\n  gpu_out.device(sycl_device) = gpu_in1.customOp(InsertZeros<TensorType>());\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data,(out.dimensions().TotalSize())*sizeof(DataType));\n\n  VERIFY_IS_EQUAL(out.dimension(0), 6);\n  VERIFY_IS_EQUAL(out.dimension(1), 10);\n\n  for (int i = 0; i < 6; i+=2) {\n    for (int j = 0; j < 10; j+=2) {\n      VERIFY_IS_EQUAL(out(i, j), in1(i/2, j/2));\n    }\n  }\n  for (int i = 1; i < 6; i+=2) {\n    for (int j = 1; j < 10; j+=2) {\n      VERIFY_IS_EQUAL(out(i, j), 0);\n    }\n  }\n  sycl_device.deallocate(gpu_in1_data);\nsycl_device.deallocate(gpu_out_data);\n}\n\ntemplate<typename TensorType>\nstruct BatchMatMul {\n  DSizes<DenseIndex, 3> dimensions(const TensorType& input1, const TensorType& input2) const {\n    DSizes<DenseIndex, 3> result;\n    result[0] = input1.dimension(0);\n    result[1] = input2.dimension(1);\n    result[2] = input2.dimension(2);\n    return result;\n  }\n\n  template <typename Output, typename Device>\n  void eval(const TensorType& input1, const TensorType& input2,\n            Output& output, const Device& device) const\n  {\n    typedef typename TensorType::DimensionPair DimPair;\n    array<DimPair, 1> dims;\n    dims[0] = DimPair(1, 0);\n    for (int64_t i = 0; i < output.dimension(2); ++i) {\n      output.template chip<2>(i).device(device) = input1.template chip<2>(i).contract(input2.template chip<2>(i), dims);\n    }\n  }\n};\n\ntemplate<typename DataType, int DataLayout, typename IndexType>\nstatic void test_custom_binary_op_sycl(const Eigen::SyclDevice &sycl_device)\n{\n\n  Eigen::array<IndexType, 3> tensorRange1 = {{2, 3, 5}};\n  Eigen::array<IndexType, 3> tensorRange2 = {{3,7,5}};\n  Eigen::array<IndexType, 3> tensorResultRange  = {{2, 7, 5}};\n\n  Eigen::Tensor<DataType, 3, DataLayout, IndexType> in1(tensorRange1);\n  Eigen::Tensor<DataType, 3, DataLayout, IndexType> in2(tensorRange2);\n  Eigen::Tensor<DataType, 3, DataLayout, IndexType> out(tensorResultRange);\n\n  DataType * gpu_in1_data  = static_cast<DataType*>(sycl_device.allocate(in1.dimensions().TotalSize()*sizeof(DataType)));\n  DataType * gpu_in2_data  = static_cast<DataType*>(sycl_device.allocate(in2.dimensions().TotalSize()*sizeof(DataType)));\n  DataType * gpu_out_data =  static_cast<DataType*>(sycl_device.allocate(out.dimensions().TotalSize()*sizeof(DataType)));\n\n  typedef Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType> > TensorType;\n  TensorType gpu_in1(gpu_in1_data, tensorRange1);\n  TensorType gpu_in2(gpu_in2_data, tensorRange2);\n  TensorType gpu_out(gpu_out_data, tensorResultRange);\n\n  in1.setRandom();\n  in2.setRandom();\n\n  sycl_device.memcpyHostToDevice(gpu_in1_data, in1.data(),(in1.dimensions().TotalSize())*sizeof(DataType));\n  sycl_device.memcpyHostToDevice(gpu_in2_data, in2.data(),(in2.dimensions().TotalSize())*sizeof(DataType));\n\n  gpu_out.device(sycl_device) = gpu_in1.customOp(gpu_in2, BatchMatMul<TensorType>());\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data,(out.dimensions().TotalSize())*sizeof(DataType));\n\n  for (IndexType i = 0; i < 5; ++i) {\n    typedef typename Eigen::Tensor<DataType, 3, DataLayout, IndexType>::DimensionPair DimPair;\n    array<DimPair, 1> dims;\n    dims[0] = DimPair(1, 0);\n    Eigen::Tensor<DataType, 2, DataLayout, IndexType> reference = in1.template chip<2>(i).contract(in2.template chip<2>(i), dims);\n    TensorRef<Eigen::Tensor<DataType, 2, DataLayout, IndexType> > val = out.template chip<2>(i);\n    for (IndexType j = 0; j < 2; ++j) {\n      for (IndexType k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(val(j, k), reference(j, k));\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_in1_data);\n  sycl_device.deallocate(gpu_in2_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, typename Dev_selector> void custom_op_perDevice(Dev_selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_custom_unary_op_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_custom_unary_op_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_custom_binary_op_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_custom_binary_op_sycl<DataType, RowMajor, int64_t>(sycl_device);\n\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_custom_op_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(custom_op_perDevice<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_device.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include \"OffByOneScalar.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\n#include <unsupported/Eigen/CXX11/src/Tensor/TensorGpuHipCudaDefines.h>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\n// Context for evaluation on cpu\nstruct CPUContext {\n  CPUContext(const Eigen::Tensor<float, 3>& in1, Eigen::Tensor<float, 3>& in2, Eigen::Tensor<float, 3>& out) : in1_(in1), in2_(in2), out_(out), kernel_1d_(2), kernel_2d_(2,2), kernel_3d_(2,2,2) {\n    kernel_1d_(0) = 3.14f;\n    kernel_1d_(1) = 2.7f;\n\n    kernel_2d_(0,0) = 3.14f;\n    kernel_2d_(1,0) = 2.7f;\n    kernel_2d_(0,1) = 0.2f;\n    kernel_2d_(1,1) = 7.0f;\n\n    kernel_3d_(0,0,0) = 3.14f;\n    kernel_3d_(0,1,0) = 2.7f;\n    kernel_3d_(0,0,1) = 0.2f;\n    kernel_3d_(0,1,1) = 7.0f;\n    kernel_3d_(1,0,0) = -1.0f;\n    kernel_3d_(1,1,0) = -0.3f;\n    kernel_3d_(1,0,1) = -0.7f;\n    kernel_3d_(1,1,1) = -0.5f;\n  }\n\n  const Eigen::DefaultDevice& device() const { return cpu_device_; }\n\n  const Eigen::Tensor<float, 3>& in1() const { return in1_; }\n  const Eigen::Tensor<float, 3>& in2() const { return in2_; }\n  Eigen::Tensor<float, 3>& out() { return out_; }\n  const Eigen::Tensor<float, 1>& kernel1d() const { return kernel_1d_; }\n  const Eigen::Tensor<float, 2>& kernel2d() const { return kernel_2d_; }\n  const Eigen::Tensor<float, 3>& kernel3d() const { return kernel_3d_; }\n\n private:\n  const Eigen::Tensor<float, 3>& in1_;\n  const Eigen::Tensor<float, 3>& in2_;\n  Eigen::Tensor<float, 3>& out_;\n\n  Eigen::Tensor<float, 1> kernel_1d_;\n  Eigen::Tensor<float, 2> kernel_2d_;\n  Eigen::Tensor<float, 3> kernel_3d_;\n\n  Eigen::DefaultDevice cpu_device_;\n};\n\n\n// Context for evaluation on GPU\nstruct GPUContext {\n  GPUContext(const Eigen::TensorMap<Eigen::Tensor<float, 3> >& in1, Eigen::TensorMap<Eigen::Tensor<float, 3> >& in2, Eigen::TensorMap<Eigen::Tensor<float, 3> >& out) : in1_(in1), in2_(in2), out_(out), gpu_device_(&stream_) {\n    assert(gpuMalloc((void**)(&kernel_1d_), 2*sizeof(float)) == gpuSuccess);\n    float kernel_1d_val[] = {3.14f, 2.7f};\n    assert(gpuMemcpy(kernel_1d_, kernel_1d_val, 2*sizeof(float), gpuMemcpyHostToDevice) == gpuSuccess);\n\n    assert(gpuMalloc((void**)(&kernel_2d_), 4*sizeof(float)) == gpuSuccess);\n    float kernel_2d_val[] = {3.14f, 2.7f, 0.2f, 7.0f};\n    assert(gpuMemcpy(kernel_2d_, kernel_2d_val, 4*sizeof(float), gpuMemcpyHostToDevice) == gpuSuccess);\n\n    assert(gpuMalloc((void**)(&kernel_3d_), 8*sizeof(float)) == gpuSuccess);\n    float kernel_3d_val[] = {3.14f, -1.0f, 2.7f, -0.3f, 0.2f, -0.7f, 7.0f, -0.5f};\n    assert(gpuMemcpy(kernel_3d_, kernel_3d_val, 8*sizeof(float), gpuMemcpyHostToDevice) == gpuSuccess);\n  }\n  ~GPUContext() {\n    assert(gpuFree(kernel_1d_) == gpuSuccess);\n    assert(gpuFree(kernel_2d_) == gpuSuccess);\n    assert(gpuFree(kernel_3d_) == gpuSuccess);\n  }\n\n  const Eigen::GpuDevice& device() const { return gpu_device_; }\n\n  const Eigen::TensorMap<Eigen::Tensor<float, 3> >& in1() const { return in1_; }\n  const Eigen::TensorMap<Eigen::Tensor<float, 3> >& in2() const { return in2_; }\n  Eigen::TensorMap<Eigen::Tensor<float, 3> >& out() { return out_; }\n  Eigen::TensorMap<Eigen::Tensor<float, 1> > kernel1d() const { return Eigen::TensorMap<Eigen::Tensor<float, 1> >(kernel_1d_, 2); }\n  Eigen::TensorMap<Eigen::Tensor<float, 2> > kernel2d() const { return Eigen::TensorMap<Eigen::Tensor<float, 2> >(kernel_2d_, 2, 2); }\n  Eigen::TensorMap<Eigen::Tensor<float, 3> > kernel3d() const { return Eigen::TensorMap<Eigen::Tensor<float, 3> >(kernel_3d_, 2, 2, 2); }\n\n private:\n  const Eigen::TensorMap<Eigen::Tensor<float, 3> >& in1_;\n  const Eigen::TensorMap<Eigen::Tensor<float, 3> >& in2_;\n  Eigen::TensorMap<Eigen::Tensor<float, 3> >& out_;\n\n  float* kernel_1d_;\n  float* kernel_2d_;\n  float* kernel_3d_;\n\n  Eigen::GpuStreamDevice stream_;\n  Eigen::GpuDevice gpu_device_;\n};\n\n\n// The actual expression to evaluate\ntemplate <typename Context>\nvoid test_contextual_eval(Context* context)\n{\n  context->out().device(context->device()) = context->in1() + context->in2() * 3.14f + context->in1().constant(2.718f);\n}\n\ntemplate <typename Context>\nvoid test_forced_contextual_eval(Context* context)\n{\n  context->out().device(context->device()) = (context->in1() + context->in2()).eval() * 3.14f + context->in1().constant(2.718f);\n}\n\ntemplate <typename Context>\nvoid test_compound_assignment(Context* context)\n{\n  context->out().device(context->device()) = context->in1().constant(2.718f);\n  context->out().device(context->device()) += context->in1() + context->in2() * 3.14f;\n}\n\n\ntemplate <typename Context>\nvoid test_contraction(Context* context)\n{\n  Eigen::array<std::pair<int, int>, 2> dims;\n  dims[0] = std::make_pair(1, 1);\n  dims[1] = std::make_pair(2, 2);\n\n  Eigen::array<int, 2> shape(40, 50*70);\n\n  Eigen::DSizes<int, 2> indices(0,0);\n  Eigen::DSizes<int, 2> sizes(40,40);\n\n  context->out().reshape(shape).slice(indices, sizes).device(context->device()) = context->in1().contract(context->in2(), dims);\n}\n\n\ntemplate <typename Context>\nvoid test_1d_convolution(Context* context)\n{\n  Eigen::DSizes<int, 3> indices(0,0,0);\n  Eigen::DSizes<int, 3> sizes(40,49,70);\n\n  Eigen::array<int, 1> dims(1);\n  context->out().slice(indices, sizes).device(context->device()) = context->in1().convolve(context->kernel1d(), dims);\n}\n\ntemplate <typename Context>\nvoid test_2d_convolution(Context* context)\n{\n  Eigen::DSizes<int, 3> indices(0,0,0);\n  Eigen::DSizes<int, 3> sizes(40,49,69);\n\n  Eigen::array<int, 2> dims(1,2);\n  context->out().slice(indices, sizes).device(context->device()) = context->in1().convolve(context->kernel2d(), dims);\n}\n\ntemplate <typename Context>\nvoid test_3d_convolution(Context* context)\n{\n  Eigen::DSizes<int, 3> indices(0,0,0);\n  Eigen::DSizes<int, 3> sizes(39,49,69);\n\n  Eigen::array<int, 3> dims(0,1,2);\n  context->out().slice(indices, sizes).device(context->device()) = context->in1().convolve(context->kernel3d(), dims);\n}\n\n// Helper method to synchronize device.\ntemplate<typename Device>\nvoid synchronize(Device& device) { /*nothing*/ }\ntemplate<>\nvoid synchronize(Eigen::GpuDevice& device) {\n  device.synchronize();\n}\n\ntemplate <typename DataType, typename TensorDevice>\nvoid test_device_memory(const TensorDevice& device) {\n  int count = 100;\n  Eigen::array<int, 1> tensorRange = {{count}};\n  Eigen::Tensor<DataType, 1> host(tensorRange);\n  Eigen::Tensor<DataType, 1> expected(tensorRange);\n  DataType* device_data  = static_cast<DataType*>(device.allocate(count * sizeof(DataType)));\n  \n  // memset\n  const char byte_value = static_cast<char>(0xAB);\n  device.memset(device_data, byte_value, count * sizeof(DataType));\n  device.memcpyDeviceToHost(host.data(), device_data, count * sizeof(DataType));\n  synchronize(device);\n  memset(expected.data(), byte_value, count * sizeof(DataType));\n  for (size_t i=0; i<count; i++) {\n    VERIFY_IS_EQUAL(host(i), expected(i));\n  }\n  \n  // fill\n  DataType fill_value = DataType(7);\n  std::fill_n(expected.data(), count, fill_value);\n  device.fill(device_data, device_data + count, fill_value);\n  device.memcpyDeviceToHost(host.data(), device_data, count * sizeof(DataType));\n  synchronize(device);\n  for (int i=0; i<count; i++) {\n    VERIFY_IS_EQUAL(host(i), expected(i));\n  }\n  \n  device.deallocate(device_data);\n}\n\nvoid test_cpu() {\n  Eigen::Tensor<float, 3> in1(40,50,70);\n  Eigen::Tensor<float, 3> in2(40,50,70);\n  Eigen::Tensor<float, 3> out(40,50,70);\n\n  in1 = in1.random() + in1.constant(10.0f);\n  in2 = in2.random() + in2.constant(10.0f);\n\n  CPUContext context(in1, in2, out);\n  test_contextual_eval(&context);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 50; ++j) {\n      for (int k = 0; k < 70; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k), in1(i,j,k) + in2(i,j,k) * 3.14f + 2.718f);\n      }\n    }\n  }\n\n  test_forced_contextual_eval(&context);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 50; ++j) {\n      for (int k = 0; k < 70; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k), (in1(i,j,k) + in2(i,j,k)) * 3.14f + 2.718f);\n      }\n    }\n  }\n\n  test_compound_assignment(&context);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 50; ++j) {\n      for (int k = 0; k < 70; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k), in1(i,j,k) + in2(i,j,k) * 3.14f + 2.718f);\n      }\n    }\n  }\n\n  test_contraction(&context);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 40; ++j) {\n      const float result = out(i,j,0);\n      float expected = 0;\n      for (int k = 0; k < 50; ++k) {\n        for (int l = 0; l < 70; ++l) {\n          expected += in1(i, k, l) * in2(j, k, l);\n        }\n      }\n      VERIFY_IS_APPROX(expected, result);\n    }\n  }\n\n  test_1d_convolution(&context);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 49; ++j) {\n      for (int k = 0; k < 70; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k), (in1(i,j,k) * 3.14f + in1(i,j+1,k) * 2.7f));\n      }\n    }\n  }\n\n  test_2d_convolution(&context);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 49; ++j) {\n      for (int k = 0; k < 69; ++k) {\n        const float result = out(i,j,k);\n        const float expected = (in1(i,j,k) * 3.14f + in1(i,j+1,k) * 2.7f) +\n                               (in1(i,j,k+1) * 0.2f + in1(i,j+1,k+1) * 7.0f);\n        if (fabs(expected) < 1e-4f && fabs(result) < 1e-4f) {\n          continue;\n        }\n        VERIFY_IS_APPROX(expected, result);\n      }\n    }\n  }\n\n  test_3d_convolution(&context);\n  for (int i = 0; i < 39; ++i) {\n    for (int j = 0; j < 49; ++j) {\n      for (int k = 0; k < 69; ++k) {\n        const float result = out(i,j,k);\n        const float expected = (in1(i,j,k) * 3.14f + in1(i,j+1,k) * 2.7f +\n                                in1(i,j,k+1) * 0.2f + in1(i,j+1,k+1) * 7.0f) +\n                               (in1(i+1,j,k) * -1.0f + in1(i+1,j+1,k) * -0.3f +\n                                in1(i+1,j,k+1) * -0.7f + in1(i+1,j+1,k+1) * -0.5f);\n        if (fabs(expected) < 1e-4f && fabs(result) < 1e-4f) {\n          continue;\n        }\n        VERIFY_IS_APPROX(expected, result);\n      }\n    }\n  }\n  \n  test_device_memory<float>(context.device());\n  test_device_memory<OffByOneScalar<int>>(context.device());\n}\n\nvoid test_gpu() {\n  Eigen::Tensor<float, 3> in1(40,50,70);\n  Eigen::Tensor<float, 3> in2(40,50,70);\n  Eigen::Tensor<float, 3> out(40,50,70);\n  in1 = in1.random() + in1.constant(10.0f);\n  in2 = in2.random() + in2.constant(10.0f);\n\n  std::size_t in1_bytes = in1.size() * sizeof(float);\n  std::size_t in2_bytes = in2.size() * sizeof(float);\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_in1;\n  float* d_in2;\n  float* d_out;\n  gpuMalloc((void**)(&d_in1), in1_bytes);\n  gpuMalloc((void**)(&d_in2), in2_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  gpuMemcpy(d_in1, in1.data(), in1_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_in2, in2.data(), in2_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 3> > gpu_in1(d_in1, 40,50,70);\n  Eigen::TensorMap<Eigen::Tensor<float, 3> > gpu_in2(d_in2, 40,50,70);\n  Eigen::TensorMap<Eigen::Tensor<float, 3> > gpu_out(d_out, 40,50,70);\n\n  GPUContext context(gpu_in1, gpu_in2, gpu_out);\n  test_contextual_eval(&context);\n  assert(gpuMemcpy(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost) == gpuSuccess);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 50; ++j) {\n      for (int k = 0; k < 70; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k), in1(i,j,k) + in2(i,j,k) * 3.14f + 2.718f);\n      }\n    }\n  }\n\n  test_forced_contextual_eval(&context);\n  assert(gpuMemcpy(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost) == gpuSuccess);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 50; ++j) {\n      for (int k = 0; k < 70; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k), (in1(i,j,k) + in2(i,j,k)) * 3.14f + 2.718f);\n      }\n    }\n  }\n\n  test_compound_assignment(&context);\n  assert(gpuMemcpy(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost) == gpuSuccess);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 50; ++j) {\n      for (int k = 0; k < 70; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k), in1(i,j,k) + in2(i,j,k) * 3.14f + 2.718f);\n      }\n    }\n  }\n\n  test_contraction(&context);\n  assert(gpuMemcpy(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost) == gpuSuccess);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 40; ++j) {\n      const float result = out(i,j,0);\n      float expected = 0;\n      for (int k = 0; k < 50; ++k) {\n        for (int l = 0; l < 70; ++l) {\n          expected += in1(i, k, l) * in2(j, k, l);\n        }\n      }\n      VERIFY_IS_APPROX(expected, result);\n    }\n  }\n\n  test_1d_convolution(&context);\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, context.device().stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(context.device().stream()) == gpuSuccess);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 49; ++j) {\n      for (int k = 0; k < 70; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k), (in1(i,j,k) * 3.14f + in1(i,j+1,k) * 2.7f));\n      }\n    }\n  }\n\n  test_2d_convolution(&context);\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, context.device().stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(context.device().stream()) == gpuSuccess);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 49; ++j) {\n      for (int k = 0; k < 69; ++k) {\n        const float result = out(i,j,k);\n        const float expected = (in1(i,j,k) * 3.14f + in1(i,j+1,k) * 2.7f +\n                                in1(i,j,k+1) * 0.2f + in1(i,j+1,k+1) * 7.0f);\n        VERIFY_IS_APPROX(expected, result);\n      }\n    }\n  }\n\n#if !defined(EIGEN_USE_HIP)\n// disable this test on the HIP platform\n// 3D tensor convolutions seem to hang on the HIP platform\n\n  test_3d_convolution(&context);\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, context.device().stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(context.device().stream()) == gpuSuccess);\n  for (int i = 0; i < 39; ++i) {\n    for (int j = 0; j < 49; ++j) {\n      for (int k = 0; k < 69; ++k) {\n       const float result = out(i,j,k);\n        const float expected = (in1(i,j,k) * 3.14f + in1(i,j+1,k) * 2.7f +\n                                in1(i,j,k+1) * 0.2f + in1(i,j+1,k+1) * 7.0f +\n                                in1(i+1,j,k) * -1.0f + in1(i+1,j+1,k) * -0.3f +\n                                in1(i+1,j,k+1) * -0.7f + in1(i+1,j+1,k+1) * -0.5f);\n        VERIFY_IS_APPROX(expected, result);\n      }\n    }\n  }\n\n#endif\n \n  test_device_memory<float>(context.device());\n  test_device_memory<OffByOneScalar<int>>(context.device());\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_device)\n{\n  CALL_SUBTEST_1(test_cpu());\n  CALL_SUBTEST_2(test_gpu());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_device_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include \"OffByOneScalar.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n#include <stdint.h>\n#include <iostream>\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_device_memory(const Eigen::SyclDevice &sycl_device) {\n  IndexType sizeDim1 = 100;\n  array<IndexType, 1> tensorRange = {{sizeDim1}};\n  Tensor<DataType, 1, DataLayout,IndexType> in(tensorRange);\n  Tensor<DataType, 1, DataLayout,IndexType> in1(tensorRange);\n  DataType* gpu_in_data  = static_cast<DataType*>(sycl_device.allocate(in.size()*sizeof(DataType)));\n  \n  // memset\n  memset(in1.data(), 1, in1.size() * sizeof(DataType));\n  sycl_device.memset(gpu_in_data, 1, in.size()*sizeof(DataType));\n  sycl_device.memcpyDeviceToHost(in.data(), gpu_in_data, in.size()*sizeof(DataType));\n  for (IndexType i=0; i<in.size(); i++) {\n    VERIFY_IS_EQUAL(in(i), in1(i));\n  }\n  \n  // fill\n  DataType value = DataType(7);\n  std::fill_n(in1.data(), in1.size(), value);\n  sycl_device.fill(gpu_in_data, gpu_in_data + in.size(), value);\n  sycl_device.memcpyDeviceToHost(in.data(), gpu_in_data, in.size()*sizeof(DataType));\n  for (IndexType i=0; i<in.size(); i++) {\n    VERIFY_IS_EQUAL(in(i), in1(i));\n  }\n\n  sycl_device.deallocate(gpu_in_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_device_exceptions(const Eigen::SyclDevice &sycl_device) {\n  VERIFY(sycl_device.ok());\n  IndexType sizeDim1 = 100;\n  array<IndexType, 1> tensorDims = {{sizeDim1}};\n  DataType* gpu_data = static_cast<DataType*>(sycl_device.allocate(sizeDim1*sizeof(DataType)));\n  sycl_device.memset(gpu_data, 1, sizeDim1*sizeof(DataType));\n\n  TensorMap<Tensor<DataType, 1, DataLayout,IndexType>> in(gpu_data, tensorDims);\n  TensorMap<Tensor<DataType, 1, DataLayout,IndexType>> out(gpu_data, tensorDims);\n  out.device(sycl_device) = in / in.constant(0);\n\n  sycl_device.synchronize();\n  VERIFY(!sycl_device.ok());\n  sycl_device.deallocate(gpu_data);\n}\n\ntemplate<typename DataType, int DataLayout, typename IndexType>\nvoid test_device_attach_buffer(const Eigen::SyclDevice &sycl_device) {\n  IndexType sizeDim1 = 100;\n  \n  array<IndexType, 1> tensorRange = {{sizeDim1}};\n  Tensor<DataType, 1, DataLayout, IndexType> in(tensorRange);\n  \n  cl::sycl::buffer<buffer_scalar_t, 1> buffer(cl::sycl::range<1>(sizeDim1 * sizeof(DataType)));\n  DataType* gpu_in_data = static_cast<DataType*>(sycl_device.attach_buffer(buffer));\n  \n  // fill\n  DataType value = DataType(7);\n  std::fill_n(in.data(), in.size(), value);\n  sycl_device.fill(gpu_in_data, gpu_in_data + in.size(), value);\n  \n  // Check that buffer is filled with the correct value.\n  auto reint = buffer.reinterpret<DataType>(cl::sycl::range<1>(sizeDim1));\n  auto access = reint.template get_access<cl::sycl::access::mode::read>();\n  for (IndexType i=0; i<in.size(); i++) {\n    VERIFY_IS_EQUAL(in(i), access[i]);\n  }\n  \n  sycl_device.detach_buffer(gpu_in_data);\n}\n\ntemplate<typename DataType> void sycl_device_test_per_device(const cl::sycl::device& d){\n  std::cout << \"Running on \" << d.template get_info<cl::sycl::info::device::name>() << std::endl;\n  QueueInterface queueInterface(d);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_device_memory<DataType, RowMajor, int64_t>(sycl_device);\n  test_device_memory<DataType, ColMajor, int64_t>(sycl_device);\n  /// this test throw an exception. enable it if you want to see the exception\n  //test_device_exceptions<DataType, RowMajor>(sycl_device);\n  /// this test throw an exception. enable it if you want to see the exception\n  //test_device_exceptions<DataType, ColMajor>(sycl_device);\n  test_device_attach_buffer<DataType, ColMajor, int64_t>(sycl_device);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_device_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_device_test_per_device<float>(device));\n    CALL_SUBTEST(sycl_device_test_per_device<OffByOneScalar<int>>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_dimension.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\n\nstatic void test_dynamic_size()\n{\n  Eigen::DSizes<int, 3> dimensions(2,3,7);\n\n  VERIFY_IS_EQUAL((int)Eigen::internal::array_get<0>(dimensions), 2);\n  VERIFY_IS_EQUAL((int)Eigen::internal::array_get<1>(dimensions), 3);\n  VERIFY_IS_EQUAL((int)Eigen::internal::array_get<2>(dimensions), 7);\n  VERIFY_IS_EQUAL((int)dimensions.TotalSize(), 2*3*7);\n  VERIFY_IS_EQUAL((int)dimensions[0], 2);\n  VERIFY_IS_EQUAL((int)dimensions[1], 3);\n  VERIFY_IS_EQUAL((int)dimensions[2], 7);\n}\n\nstatic void test_fixed_size()\n{\n  Eigen::Sizes<2,3,7> dimensions;\n\n  VERIFY_IS_EQUAL((int)Eigen::internal::array_get<0>(dimensions), 2);\n  VERIFY_IS_EQUAL((int)Eigen::internal::array_get<1>(dimensions), 3);\n  VERIFY_IS_EQUAL((int)Eigen::internal::array_get<2>(dimensions), 7);\n  VERIFY_IS_EQUAL((int)dimensions.TotalSize(), 2*3*7);\n}\n\nstatic void test_match()\n{\n  Eigen::DSizes<unsigned int, 3> dyn((unsigned int)2,(unsigned int)3,(unsigned int)7);\n  Eigen::Sizes<2,3,7> stat;\n  VERIFY_IS_EQUAL(Eigen::dimensions_match(dyn, stat), true);\n\n  Eigen::DSizes<int, 3> dyn1(2,3,7);\n  Eigen::DSizes<int, 2> dyn2(2,3);\n  VERIFY_IS_EQUAL(Eigen::dimensions_match(dyn1, dyn2), false);\n}\n\nstatic void test_rank_zero()\n{\n  Eigen::Sizes<> scalar;\n  VERIFY_IS_EQUAL((int)scalar.TotalSize(), 1);\n  VERIFY_IS_EQUAL((int)scalar.rank(), 0);\n  VERIFY_IS_EQUAL((int)internal::array_prod(scalar), 1);\n\n  Eigen::DSizes<ptrdiff_t, 0> dscalar;\n  VERIFY_IS_EQUAL((int)dscalar.TotalSize(), 1);\n  VERIFY_IS_EQUAL((int)dscalar.rank(), 0);\n}\n\nstatic void test_index_type_promotion() {\n  Eigen::DSizes<int, 3> src0(1, 2, 3);\n  Eigen::array<int, 3> src1;\n  src1[0] = 4;\n  src1[1] = 5;\n  src1[2] = 6;\n\n  Eigen::DSizes<long, 3> dst0(src0);\n  Eigen::DSizes<long, 3> dst1(src1);\n\n  VERIFY_IS_EQUAL(dst0[0], 1L);\n  VERIFY_IS_EQUAL(dst0[1], 2L);\n  VERIFY_IS_EQUAL(dst0[2], 3L);\n  VERIFY_IS_EQUAL(dst1[0], 4L);\n  VERIFY_IS_EQUAL(dst1[1], 5L);\n  VERIFY_IS_EQUAL(dst1[2], 6L);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_dimension)\n{\n  CALL_SUBTEST(test_dynamic_size());\n  CALL_SUBTEST(test_fixed_size());\n  CALL_SUBTEST(test_match());\n  CALL_SUBTEST(test_rank_zero());\n  CALL_SUBTEST(test_index_type_promotion());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_empty.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\n\nstatic void test_empty_tensor()\n{\n  Tensor<float, 2> source;\n  Tensor<float, 2> tgt1 = source;\n  Tensor<float, 2> tgt2(source);\n  Tensor<float, 2> tgt3;\n  tgt3 = tgt1;\n  tgt3 = tgt2;\n}\n\nstatic void test_empty_fixed_size_tensor()\n{\n  TensorFixedSize<float, Sizes<0> > source;\n  TensorFixedSize<float, Sizes<0> > tgt1 = source;\n  TensorFixedSize<float, Sizes<0> > tgt2(source);\n  TensorFixedSize<float, Sizes<0> > tgt3;\n  tgt3 = tgt1;\n  tgt3 = tgt2;\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_empty)\n{\n   CALL_SUBTEST(test_empty_tensor());\n   CALL_SUBTEST(test_empty_fixed_size_tensor());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_executor.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2018 Eugene Zhulenev <ezhulenev@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_USE_THREADS\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\nusing Eigen::ColMajor;\nusing Eigen::internal::TiledEvaluation;\n\n// A set of tests to verify that different TensorExecutor strategies yields the\n// same results for all the ops, supporting tiled evaluation.\n\n// Default assignment that does no use block evaluation or vectorization.\n// We assume that default coefficient evaluation is well tested and correct.\ntemplate <typename Dst, typename Expr>\nstatic void DefaultAssign(Dst& dst, Expr expr) {\n  using Assign = Eigen::TensorAssignOp<Dst, const Expr>;\n  using Executor =\n      Eigen::internal::TensorExecutor<const Assign, DefaultDevice,\n                                      /*Vectorizable=*/false,\n                                      /*Tiling=*/TiledEvaluation::Off>;\n\n  Executor::run(Assign(dst, expr), DefaultDevice());\n}\n\n// Assignment with specified device and tiling strategy.\ntemplate <bool Vectorizable, TiledEvaluation Tiling, typename Device,\n          typename Dst, typename Expr>\nstatic void DeviceAssign(Device& d, Dst& dst, Expr expr) {\n  using Assign = Eigen::TensorAssignOp<Dst, const Expr>;\n  using Executor = Eigen::internal::TensorExecutor<const Assign, Device,\n                                                   Vectorizable, Tiling>;\n\n  Executor::run(Assign(dst, expr), d);\n}\n\ntemplate <int NumDims>\nstatic array<Index, NumDims> RandomDims(int min_dim = 1, int max_dim = 20) {\n  array<Index, NumDims> dims;\n  for (int i = 0; i < NumDims; ++i) {\n    dims[i] = internal::random<int>(min_dim, max_dim);\n  }\n  return dims;\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n          TiledEvaluation Tiling, int Layout>\nstatic void test_execute_unary_expr(Device d)\n{\n  static constexpr int Options = 0 | Layout;\n\n  // Pick a large enough tensor size to bypass small tensor block evaluation\n  // optimization.\n  auto dims = RandomDims<NumDims>(50 / NumDims, 100 / NumDims);\n\n  Tensor<T, NumDims, Options, Index> src(dims);\n  Tensor<T, NumDims, Options, Index> dst(dims);\n\n  src.setRandom();\n  const auto expr = src.square();\n\n  using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;\n  using Executor =\n      internal::TensorExecutor<const Assign, Device, Vectorizable, Tiling>;\n\n  Executor::run(Assign(dst, expr), d);\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    T square = src.coeff(i) * src.coeff(i);\n    VERIFY_IS_EQUAL(square, dst.coeff(i));\n  }\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n          TiledEvaluation Tiling, int Layout>\nstatic void test_execute_binary_expr(Device d)\n{\n  static constexpr int Options = 0 | Layout;\n\n  // Pick a large enough tensor size to bypass small tensor block evaluation\n  // optimization.\n  auto dims = RandomDims<NumDims>(50 / NumDims, 100 / NumDims);\n\n  Tensor<T, NumDims, Options, Index> lhs(dims);\n  Tensor<T, NumDims, Options, Index> rhs(dims);\n  Tensor<T, NumDims, Options, Index> dst(dims);\n\n  lhs.setRandom();\n  rhs.setRandom();\n\n  const auto expr = lhs + rhs;\n\n  using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;\n  using Executor =\n      internal::TensorExecutor<const Assign, Device, Vectorizable, Tiling>;\n\n  Executor::run(Assign(dst, expr), d);\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    T sum = lhs.coeff(i) + rhs.coeff(i);\n    VERIFY_IS_EQUAL(sum, dst.coeff(i));\n  }\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n          TiledEvaluation Tiling, int Layout>\nstatic void test_execute_broadcasting(Device d)\n{\n  static constexpr int Options = 0 | Layout;\n\n  auto dims = RandomDims<NumDims>(1, 10);\n  Tensor<T, NumDims, Options, Index> src(dims);\n  src.setRandom();\n\n  const auto broadcasts = RandomDims<NumDims>(1, 7);\n  const auto expr = src.broadcast(broadcasts);\n\n  // We assume that broadcasting on a default device is tested and correct, so\n  // we can rely on it to verify correctness of tensor executor and tiling.\n  Tensor<T, NumDims, Options, Index> golden;\n  golden = expr;\n\n  // Now do the broadcasting using configured tensor executor.\n  Tensor<T, NumDims, Options, Index> dst(golden.dimensions());\n\n  using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;\n  using Executor =\n      internal::TensorExecutor<const Assign, Device, Vectorizable, Tiling>;\n\n  Executor::run(Assign(dst, expr), d);\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));\n  }\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n          TiledEvaluation Tiling, int Layout>\nstatic void test_execute_chipping_rvalue(Device d)\n{\n  auto dims = RandomDims<NumDims>(1, 10);\n  Tensor<T, NumDims, Layout, Index> src(dims);\n  src.setRandom();\n\n#define TEST_CHIPPING(CHIP_DIM)                                           \\\n  if (NumDims > (CHIP_DIM)) {                                             \\\n    const auto offset = internal::random<Index>(0, dims[(CHIP_DIM)] - 1); \\\n    const auto expr = src.template chip<(CHIP_DIM)>(offset);              \\\n                                                                          \\\n    Tensor<T, NumDims - 1, Layout, Index> golden;                         \\\n    golden = expr;                                                        \\\n                                                                          \\\n    Tensor<T, NumDims - 1, Layout, Index> dst(golden.dimensions());       \\\n                                                                          \\\n    using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;   \\\n    using Executor = internal::TensorExecutor<const Assign, Device,       \\\n                                              Vectorizable, Tiling>;      \\\n                                                                          \\\n    Executor::run(Assign(dst, expr), d);                                  \\\n                                                                          \\\n    for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {            \\\n      VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));                     \\\n    }                                                                     \\\n  }\n\n  TEST_CHIPPING(0)\n  TEST_CHIPPING(1)\n  TEST_CHIPPING(2)\n  TEST_CHIPPING(3)\n  TEST_CHIPPING(4)\n  TEST_CHIPPING(5)\n\n#undef TEST_CHIPPING\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n    TiledEvaluation Tiling, int Layout>\nstatic void test_execute_chipping_lvalue(Device d)\n{\n  auto dims = RandomDims<NumDims>(1, 10);\n\n#define TEST_CHIPPING(CHIP_DIM)                                             \\\n  if (NumDims > (CHIP_DIM)) {                                               \\\n    /* Generate random data that we'll assign to the chipped tensor dim. */ \\\n    array<Index, NumDims - 1> src_dims;                                     \\\n    for (int i = 0; i < NumDims - 1; ++i) {                                 \\\n      int dim = i < (CHIP_DIM) ? i : i + 1;                                 \\\n      src_dims[i] = dims[dim];                                              \\\n    }                                                                       \\\n                                                                            \\\n    Tensor<T, NumDims - 1, Layout, Index> src(src_dims);                    \\\n    src.setRandom();                                                        \\\n                                                                            \\\n    const auto offset = internal::random<Index>(0, dims[(CHIP_DIM)] - 1);   \\\n                                                                            \\\n    Tensor<T, NumDims, Layout, Index> random(dims);                         \\\n    random.setZero();                                                       \\\n                                                                            \\\n    Tensor<T, NumDims, Layout, Index> golden(dims);                         \\\n    golden = random;                                                        \\\n    golden.template chip<(CHIP_DIM)>(offset) = src;                         \\\n                                                                            \\\n    Tensor<T, NumDims, Layout, Index> dst(dims);                            \\\n    dst = random;                                                           \\\n    auto expr = dst.template chip<(CHIP_DIM)>(offset);                      \\\n                                                                            \\\n    using Assign = TensorAssignOp<decltype(expr), const decltype(src)>;     \\\n    using Executor = internal::TensorExecutor<const Assign, Device,         \\\n                                              Vectorizable, Tiling>;        \\\n                                                                            \\\n    Executor::run(Assign(expr, src), d);                                    \\\n                                                                            \\\n    for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {              \\\n      VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));                       \\\n    }                                                                       \\\n  }\n\n  TEST_CHIPPING(0)\n  TEST_CHIPPING(1)\n  TEST_CHIPPING(2)\n  TEST_CHIPPING(3)\n  TEST_CHIPPING(4)\n  TEST_CHIPPING(5)\n\n#undef TEST_CHIPPING\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n          TiledEvaluation Tiling, int Layout>\nstatic void test_execute_shuffle_rvalue(Device d)\n{\n  static constexpr int Options = 0 | Layout;\n\n  auto dims = RandomDims<NumDims>(1, 10);\n  Tensor<T, NumDims, Options, Index> src(dims);\n  src.setRandom();\n\n  DSizes<Index, NumDims> shuffle;\n  for (int i = 0; i < NumDims; ++i) shuffle[i] = i;\n\n  // Test all possible shuffle permutations.\n  do {\n    DSizes<Index, NumDims> shuffled_dims;\n    for (int i = 0; i < NumDims; ++i) {\n      shuffled_dims[i] = dims[shuffle[i]];\n    }\n\n    const auto expr = src.shuffle(shuffle);\n\n    // We assume that shuffling on a default device is tested and correct, so\n    // we can rely on it to verify correctness of tensor executor and tiling.\n    Tensor<T, NumDims, Options, Index> golden(shuffled_dims);\n    DefaultAssign(golden, expr);\n\n    // Now do the shuffling using configured tensor executor.\n    Tensor<T, NumDims, Options, Index> dst(shuffled_dims);\n    DeviceAssign<Vectorizable, Tiling>(d, dst, expr);\n\n    for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n      VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));\n    }\n\n  } while (std::next_permutation(&shuffle[0], &shuffle[0] + NumDims));\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n          TiledEvaluation Tiling, int Layout>\nstatic void test_execute_shuffle_lvalue(Device d)\n{\n  static constexpr int Options = 0 | Layout;\n\n  auto dims = RandomDims<NumDims>(5, 10);\n  Tensor<T, NumDims, Options, Index> src(dims);\n  src.setRandom();\n\n  DSizes<Index, NumDims> shuffle;\n  for (int i = 0; i < NumDims; ++i) shuffle[i] = i;\n\n  // Test all possible shuffle permutations.\n  do {\n    DSizes<Index, NumDims> shuffled_dims;\n    for (int i = 0; i < NumDims; ++i) shuffled_dims[shuffle[i]] = dims[i];\n\n    // We assume that shuffling on a default device is tested and correct, so\n    // we can rely on it to verify correctness of tensor executor and tiling.\n    Tensor<T, NumDims, Options, Index> golden(shuffled_dims);\n    auto golden_shuffle = golden.shuffle(shuffle);\n    DefaultAssign(golden_shuffle, src);\n\n    // Now do the shuffling using configured tensor executor.\n    Tensor<T, NumDims, Options, Index> dst(shuffled_dims);\n    auto dst_shuffle = dst.shuffle(shuffle);\n    DeviceAssign<Vectorizable, Tiling>(d, dst_shuffle, src);\n\n    for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n      VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));\n    }\n\n  } while (std::next_permutation(&shuffle[0], &shuffle[0] + NumDims));\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n    TiledEvaluation Tiling, int Layout>\nstatic void test_execute_reshape(Device d)\n{\n  static_assert(NumDims >= 2, \"NumDims must be greater or equal than 2\");\n\n  static constexpr int ReshapedDims = NumDims - 1;\n  static constexpr int Options = 0 | Layout;\n\n  auto dims = RandomDims<NumDims>(5, 10);\n  Tensor<T, NumDims, Options, Index> src(dims);\n  src.setRandom();\n\n  // Multiple 0th dimension and then shuffle.\n  std::vector<Index> shuffle;\n  for (int i = 0; i < ReshapedDims; ++i) shuffle.push_back(i);\n  std::shuffle(shuffle.begin(), shuffle.end(), std::mt19937());\n\n  DSizes<Index, ReshapedDims> reshaped_dims;\n  reshaped_dims[shuffle[0]] = dims[0] * dims[1];\n  for (int i = 1; i < ReshapedDims; ++i) reshaped_dims[shuffle[i]] = dims[i + 1];\n\n  Tensor<T, ReshapedDims, Options, Index> golden = src.reshape(reshaped_dims);\n\n  // Now reshape using configured tensor executor.\n  Tensor<T, ReshapedDims, Options, Index> dst(golden.dimensions());\n\n  auto expr = src.reshape(reshaped_dims);\n\n  using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;\n  using Executor =\n      internal::TensorExecutor<const Assign, Device, Vectorizable, Tiling>;\n\n  Executor::run(Assign(dst, expr), d);\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));\n  }\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n          TiledEvaluation Tiling, int Layout>\nstatic void test_execute_slice_rvalue(Device d)\n{\n  static_assert(NumDims >= 2, \"NumDims must be greater or equal than 2\");\n  static constexpr int Options = 0 | Layout;\n\n  auto dims = RandomDims<NumDims>(5, 10);\n  Tensor<T, NumDims, Options, Index> src(dims);\n  src.setRandom();\n\n  // Pick a random slice of src tensor.\n  auto slice_start = DSizes<Index, NumDims>(RandomDims<NumDims>());\n  auto slice_size = DSizes<Index, NumDims>(RandomDims<NumDims>());\n\n  // Make sure that slice start + size do not overflow tensor dims.\n  for (int i = 0; i < NumDims; ++i) {\n    slice_start[i] = numext::mini(dims[i] - 1, slice_start[i]);\n    slice_size[i] = numext::mini(slice_size[i], dims[i] - slice_start[i]);\n  }\n\n  Tensor<T, NumDims, Options, Index> golden =\n      src.slice(slice_start, slice_size);\n\n  // Now reshape using configured tensor executor.\n  Tensor<T, NumDims, Options, Index> dst(golden.dimensions());\n\n  auto expr = src.slice(slice_start, slice_size);\n\n  using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;\n  using Executor =\n      internal::TensorExecutor<const Assign, Device, Vectorizable, Tiling>;\n\n  Executor::run(Assign(dst, expr), d);\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));\n  }\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n    TiledEvaluation Tiling, int Layout>\nstatic void test_execute_slice_lvalue(Device d)\n{\n  static_assert(NumDims >= 2, \"NumDims must be greater or equal than 2\");\n  static constexpr int Options = 0 | Layout;\n\n  auto dims = RandomDims<NumDims>(5, 10);\n  Tensor<T, NumDims, Options, Index> src(dims);\n  src.setRandom();\n\n  // Pick a random slice of src tensor.\n  auto slice_start = DSizes<Index, NumDims>(RandomDims<NumDims>(1, 10));\n  auto slice_size = DSizes<Index, NumDims>(RandomDims<NumDims>(1, 10));\n\n  // Make sure that slice start + size do not overflow tensor dims.\n  for (int i = 0; i < NumDims; ++i) {\n    slice_start[i] = numext::mini(dims[i] - 1, slice_start[i]);\n    slice_size[i] = numext::mini(slice_size[i], dims[i] - slice_start[i]);\n  }\n\n  Tensor<T, NumDims, Options, Index> slice(slice_size);\n  slice.setRandom();\n\n  // Assign a slice using default executor.\n  Tensor<T, NumDims, Options, Index> golden = src;\n  golden.slice(slice_start, slice_size) = slice;\n\n  // And using configured execution strategy.\n  Tensor<T, NumDims, Options, Index> dst = src;\n  auto expr = dst.slice(slice_start, slice_size);\n\n  using Assign = TensorAssignOp<decltype(expr), const decltype(slice)>;\n  using Executor =\n      internal::TensorExecutor<const Assign, Device, Vectorizable, Tiling>;\n\n  Executor::run(Assign(expr, slice), d);\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));\n  }\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n    TiledEvaluation Tiling, int Layout>\nstatic void test_execute_broadcasting_of_forced_eval(Device d)\n{\n  static constexpr int Options = 0 | Layout;\n\n  auto dims = RandomDims<NumDims>(1, 10);\n  Tensor<T, NumDims, Options, Index> src(dims);\n  src.setRandom();\n\n  const auto broadcasts = RandomDims<NumDims>(1, 7);\n  const auto expr = src.square().eval().broadcast(broadcasts);\n\n  // We assume that broadcasting on a default device is tested and correct, so\n  // we can rely on it to verify correctness of tensor executor and tiling.\n  Tensor<T, NumDims, Options, Index> golden;\n  golden = expr;\n\n  // Now do the broadcasting using configured tensor executor.\n  Tensor<T, NumDims, Options, Index> dst(golden.dimensions());\n\n  using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;\n  using Executor =\n      internal::TensorExecutor<const Assign, Device, Vectorizable, Tiling>;\n\n  Executor::run(Assign(dst, expr), d);\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));\n  }\n}\n\ntemplate<typename T, int NumDims>\nstruct DummyGenerator {\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  T operator()(const array <Index, NumDims>& dims) const {\n    T result = static_cast<T>(0);\n    for (int i = 0; i < NumDims; ++i) {\n      result += static_cast<T>((i + 1) * dims[i]);\n    }\n    return result;\n  }\n};\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n    TiledEvaluation Tiling, int Layout>\nstatic void test_execute_generator_op(Device d)\n{\n  static constexpr int Options = 0 | Layout;\n\n  auto dims = RandomDims<NumDims>(20, 30);\n  Tensor<T, NumDims, Options, Index> src(dims);\n  src.setRandom();\n\n  const auto expr = src.generate(DummyGenerator<T, NumDims>());\n\n  // We assume that generator on a default device is tested and correct, so\n  // we can rely on it to verify correctness of tensor executor and tiling.\n  Tensor<T, NumDims, Options, Index> golden;\n  golden = expr;\n\n  // Now do the broadcasting using configured tensor executor.\n  Tensor<T, NumDims, Options, Index> dst(golden.dimensions());\n\n  using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;\n  using Executor =\n    internal::TensorExecutor<const Assign, Device, Vectorizable, Tiling>;\n\n  Executor::run(Assign(dst, expr), d);\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));\n  }\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n    TiledEvaluation Tiling, int Layout>\nstatic void test_execute_reverse_rvalue(Device d)\n{\n  static constexpr int Options = 0 | Layout;\n\n  auto dims = RandomDims<NumDims>(1, numext::pow(1000000.0, 1.0 / NumDims));\n  Tensor <T, NumDims, Options, Index> src(dims);\n  src.setRandom();\n\n  // Reverse half of the dimensions.\n  Eigen::array<bool, NumDims> reverse;\n  for (int i = 0; i < NumDims; ++i) reverse[i] = internal::random<bool>();\n\n  const auto expr = src.reverse(reverse);\n\n  // We assume that reversing on a default device is tested and correct, so\n  // we can rely on it to verify correctness of tensor executor and tiling.\n  Tensor <T, NumDims, Options, Index> golden;\n  golden = expr;\n\n  // Now do the reversing using configured tensor executor.\n  Tensor <T, NumDims, Options, Index> dst(golden.dimensions());\n\n  using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;\n  using Executor =\n    internal::TensorExecutor<const Assign, Device, Vectorizable, Tiling>;\n\n  Executor::run(Assign(dst, expr), d);\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));\n  }\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n          TiledEvaluation Tiling, int Layout>\nstatic void test_async_execute_unary_expr(Device d)\n{\n  static constexpr int Options = 0 | Layout;\n\n  // Pick a large enough tensor size to bypass small tensor block evaluation\n  // optimization.\n  auto dims = RandomDims<NumDims>(50 / NumDims, 100 / NumDims);\n\n  Tensor<T, NumDims, Options, Index> src(dims);\n  Tensor<T, NumDims, Options, Index> dst(dims);\n\n  src.setRandom();\n  const auto expr = src.square();\n\n  Eigen::Barrier done(1);\n  auto on_done = [&done]() { done.Notify(); };\n\n  using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;\n  using DoneCallback = decltype(on_done);\n  using Executor = internal::TensorAsyncExecutor<const Assign, Device, DoneCallback,\n                                                 Vectorizable, Tiling>;\n\n  Executor::runAsync(Assign(dst, expr), d, on_done);\n  done.Wait();\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    T square = src.coeff(i) * src.coeff(i);\n    VERIFY_IS_EQUAL(square, dst.coeff(i));\n  }\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n          TiledEvaluation Tiling, int Layout>\nstatic void test_async_execute_binary_expr(Device d)\n{\n  static constexpr int Options = 0 | Layout;\n\n  // Pick a large enough tensor size to bypass small tensor block evaluation\n  // optimization.\n  auto dims = RandomDims<NumDims>(50 / NumDims, 100 / NumDims);\n\n  Tensor<T, NumDims, Options, Index> lhs(dims);\n  Tensor<T, NumDims, Options, Index> rhs(dims);\n  Tensor<T, NumDims, Options, Index> dst(dims);\n\n  lhs.setRandom();\n  rhs.setRandom();\n\n  const auto expr = lhs + rhs;\n\n  Eigen::Barrier done(1);\n  auto on_done = [&done]() { done.Notify(); };\n\n  using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;\n  using DoneCallback = decltype(on_done);\n  using Executor = internal::TensorAsyncExecutor<const Assign, Device, DoneCallback,\n                                                 Vectorizable, Tiling>;\n\n  Executor::runAsync(Assign(dst, expr), d, on_done);\n  done.Wait();\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    T sum = lhs.coeff(i) + rhs.coeff(i);\n    VERIFY_IS_EQUAL(sum, dst.coeff(i));\n  }\n}\n\n#ifdef EIGEN_DONT_VECTORIZE\n#define VECTORIZABLE(VAL) !EIGEN_DONT_VECTORIZE && VAL\n#else\n#define VECTORIZABLE(VAL) VAL\n#endif\n\n#define CALL_SUBTEST_PART(PART) \\\n  CALL_SUBTEST_##PART\n\n#define CALL_SUBTEST_COMBINATIONS(PART, NAME, T, NUM_DIMS)                                                                                 \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, DefaultDevice,    false,               TiledEvaluation::Off,     ColMajor>(default_device))); \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, DefaultDevice,    false,               TiledEvaluation::On,  ColMajor>(default_device)));     \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, DefaultDevice,    VECTORIZABLE(true),  TiledEvaluation::Off,     ColMajor>(default_device))); \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, DefaultDevice,    VECTORIZABLE(true),  TiledEvaluation::On,  ColMajor>(default_device)));     \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, DefaultDevice,    false,               TiledEvaluation::Off,     RowMajor>(default_device))); \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, DefaultDevice,    false,               TiledEvaluation::On,  RowMajor>(default_device)));     \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, DefaultDevice,    VECTORIZABLE(true),  TiledEvaluation::Off,     RowMajor>(default_device))); \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, DefaultDevice,    VECTORIZABLE(true),  TiledEvaluation::On,  RowMajor>(default_device)));     \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, false,               TiledEvaluation::Off,     ColMajor>(tp_device)));      \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, false,               TiledEvaluation::On,  ColMajor>(tp_device)));          \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, VECTORIZABLE(true),  TiledEvaluation::Off,     ColMajor>(tp_device)));      \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, VECTORIZABLE(true),  TiledEvaluation::On,  ColMajor>(tp_device)));          \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, false,               TiledEvaluation::Off,     RowMajor>(tp_device)));      \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, false,               TiledEvaluation::On,  RowMajor>(tp_device)));          \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, VECTORIZABLE(true),  TiledEvaluation::Off,     RowMajor>(tp_device)));      \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, VECTORIZABLE(true),  TiledEvaluation::On,  RowMajor>(tp_device)))\n\n// NOTE: Currently only ThreadPoolDevice supports async expression evaluation.\n#define CALL_ASYNC_SUBTEST_COMBINATIONS(PART, NAME, T, NUM_DIMS)                                                                      \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, false,               TiledEvaluation::Off,     ColMajor>(tp_device))); \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, false,               TiledEvaluation::On,  ColMajor>(tp_device)));     \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, VECTORIZABLE(true),  TiledEvaluation::Off,     ColMajor>(tp_device))); \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, VECTORIZABLE(true),  TiledEvaluation::On,  ColMajor>(tp_device)));     \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, false,               TiledEvaluation::Off,     RowMajor>(tp_device))); \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, false,               TiledEvaluation::On,  RowMajor>(tp_device)));     \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, VECTORIZABLE(true),  TiledEvaluation::Off,     RowMajor>(tp_device))); \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, VECTORIZABLE(true),  TiledEvaluation::On,  RowMajor>(tp_device)))\n\nEIGEN_DECLARE_TEST(cxx11_tensor_executor) {\n  Eigen::DefaultDevice default_device;\n  // Default device is unused in ASYNC tests.\n  EIGEN_UNUSED_VARIABLE(default_device);\n\n  const auto num_threads = internal::random<int>(20, 24);\n  Eigen::ThreadPool tp(num_threads);\n  Eigen::ThreadPoolDevice tp_device(&tp, num_threads);\n\n  CALL_SUBTEST_COMBINATIONS(1, test_execute_unary_expr, float, 3);\n  CALL_SUBTEST_COMBINATIONS(1, test_execute_unary_expr, float, 4);\n  CALL_SUBTEST_COMBINATIONS(1, test_execute_unary_expr, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(2, test_execute_binary_expr, float, 3);\n  CALL_SUBTEST_COMBINATIONS(2, test_execute_binary_expr, float, 4);\n  CALL_SUBTEST_COMBINATIONS(2, test_execute_binary_expr, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(3, test_execute_broadcasting, float, 3);\n  CALL_SUBTEST_COMBINATIONS(3, test_execute_broadcasting, float, 4);\n  CALL_SUBTEST_COMBINATIONS(3, test_execute_broadcasting, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(4, test_execute_chipping_rvalue, float, 3);\n  CALL_SUBTEST_COMBINATIONS(4, test_execute_chipping_rvalue, float, 4);\n  CALL_SUBTEST_COMBINATIONS(4, test_execute_chipping_rvalue, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(5, test_execute_chipping_lvalue, float, 3);\n  CALL_SUBTEST_COMBINATIONS(5, test_execute_chipping_lvalue, float, 4);\n  CALL_SUBTEST_COMBINATIONS(5, test_execute_chipping_lvalue, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(6, test_execute_shuffle_rvalue, float, 3);\n  CALL_SUBTEST_COMBINATIONS(6, test_execute_shuffle_rvalue, float, 4);\n  CALL_SUBTEST_COMBINATIONS(6, test_execute_shuffle_rvalue, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(7, test_execute_shuffle_lvalue, float, 3);\n  CALL_SUBTEST_COMBINATIONS(7, test_execute_shuffle_lvalue, float, 4);\n  CALL_SUBTEST_COMBINATIONS(7, test_execute_shuffle_lvalue, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(9, test_execute_reshape, float, 2);\n  CALL_SUBTEST_COMBINATIONS(9, test_execute_reshape, float, 3);\n  CALL_SUBTEST_COMBINATIONS(9, test_execute_reshape, float, 4);\n  CALL_SUBTEST_COMBINATIONS(9, test_execute_reshape, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(10, test_execute_slice_rvalue, float, 2);\n  CALL_SUBTEST_COMBINATIONS(10, test_execute_slice_rvalue, float, 3);\n  CALL_SUBTEST_COMBINATIONS(10, test_execute_slice_rvalue, float, 4);\n  CALL_SUBTEST_COMBINATIONS(10, test_execute_slice_rvalue, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(11, test_execute_slice_lvalue, float, 2);\n  CALL_SUBTEST_COMBINATIONS(11, test_execute_slice_lvalue, float, 3);\n  CALL_SUBTEST_COMBINATIONS(11, test_execute_slice_lvalue, float, 4);\n  CALL_SUBTEST_COMBINATIONS(11, test_execute_slice_lvalue, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(12, test_execute_broadcasting_of_forced_eval, float, 2);\n  CALL_SUBTEST_COMBINATIONS(12, test_execute_broadcasting_of_forced_eval, float, 3);\n  CALL_SUBTEST_COMBINATIONS(12, test_execute_broadcasting_of_forced_eval, float, 4);\n  CALL_SUBTEST_COMBINATIONS(12, test_execute_broadcasting_of_forced_eval, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(13, test_execute_generator_op, float, 2);\n  CALL_SUBTEST_COMBINATIONS(13, test_execute_generator_op, float, 3);\n  CALL_SUBTEST_COMBINATIONS(13, test_execute_generator_op, float, 4);\n  CALL_SUBTEST_COMBINATIONS(13, test_execute_generator_op, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(14, test_execute_reverse_rvalue, float, 1);\n  CALL_SUBTEST_COMBINATIONS(14, test_execute_reverse_rvalue, float, 2);\n  CALL_SUBTEST_COMBINATIONS(14, test_execute_reverse_rvalue, float, 3);\n  CALL_SUBTEST_COMBINATIONS(14, test_execute_reverse_rvalue, float, 4);\n  CALL_SUBTEST_COMBINATIONS(14, test_execute_reverse_rvalue, float, 5);\n\n  CALL_ASYNC_SUBTEST_COMBINATIONS(15, test_async_execute_unary_expr, float, 3);\n  CALL_ASYNC_SUBTEST_COMBINATIONS(15, test_async_execute_unary_expr, float, 4);\n  CALL_ASYNC_SUBTEST_COMBINATIONS(15, test_async_execute_unary_expr, float, 5);\n\n  CALL_ASYNC_SUBTEST_COMBINATIONS(16, test_async_execute_binary_expr, float, 3);\n  CALL_ASYNC_SUBTEST_COMBINATIONS(16, test_async_execute_binary_expr, float, 4);\n  CALL_ASYNC_SUBTEST_COMBINATIONS(16, test_async_execute_binary_expr, float, 5);\n\n  // Force CMake to split this test.\n  // EIGEN_SUFFIXES;1;2;3;4;5;6;7;8;9;10;11;12;13;14;15;16\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_expr.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <numeric>\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\nstatic void test_1d()\n{\n  Tensor<float, 1> vec1(6);\n  Tensor<float, 1, RowMajor> vec2(6);\n\n  vec1(0) = 4.0;  vec2(0) = 0.0;\n  vec1(1) = 8.0;  vec2(1) = 1.0;\n  vec1(2) = 15.0; vec2(2) = 2.0;\n  vec1(3) = 16.0; vec2(3) = 3.0;\n  vec1(4) = 23.0; vec2(4) = 4.0;\n  vec1(5) = 42.0; vec2(5) = 5.0;\n\n  float data3[6];\n  TensorMap<Tensor<float, 1>> vec3(data3, 6);\n  vec3 = vec1.sqrt();\n  float data4[6];\n  TensorMap<Tensor<float, 1, RowMajor>> vec4(data4, 6);\n  vec4 = vec2.square();\n  float data5[6];\n  TensorMap<Tensor<float, 1, RowMajor>> vec5(data5, 6);\n  vec5 = vec2.cube();\n\n  VERIFY_IS_APPROX(vec3(0), sqrtf(4.0));\n  VERIFY_IS_APPROX(vec3(1), sqrtf(8.0));\n  VERIFY_IS_APPROX(vec3(2), sqrtf(15.0));\n  VERIFY_IS_APPROX(vec3(3), sqrtf(16.0));\n  VERIFY_IS_APPROX(vec3(4), sqrtf(23.0));\n  VERIFY_IS_APPROX(vec3(5), sqrtf(42.0));\n\n  VERIFY_IS_APPROX(vec4(0), 0.0f);\n  VERIFY_IS_APPROX(vec4(1), 1.0f);\n  VERIFY_IS_APPROX(vec4(2), 2.0f * 2.0f);\n  VERIFY_IS_APPROX(vec4(3), 3.0f * 3.0f);\n  VERIFY_IS_APPROX(vec4(4), 4.0f * 4.0f);\n  VERIFY_IS_APPROX(vec4(5), 5.0f * 5.0f);\n\n  VERIFY_IS_APPROX(vec5(0), 0.0f);\n  VERIFY_IS_APPROX(vec5(1), 1.0f);\n  VERIFY_IS_APPROX(vec5(2), 2.0f * 2.0f * 2.0f);\n  VERIFY_IS_APPROX(vec5(3), 3.0f * 3.0f * 3.0f);\n  VERIFY_IS_APPROX(vec5(4), 4.0f * 4.0f * 4.0f);\n  VERIFY_IS_APPROX(vec5(5), 5.0f * 5.0f * 5.0f);\n\n  vec3 = vec1 + vec2;\n  VERIFY_IS_APPROX(vec3(0), 4.0f + 0.0f);\n  VERIFY_IS_APPROX(vec3(1), 8.0f + 1.0f);\n  VERIFY_IS_APPROX(vec3(2), 15.0f + 2.0f);\n  VERIFY_IS_APPROX(vec3(3), 16.0f + 3.0f);\n  VERIFY_IS_APPROX(vec3(4), 23.0f + 4.0f);\n  VERIFY_IS_APPROX(vec3(5), 42.0f + 5.0f);\n}\n\nstatic void test_2d()\n{\n  float data1[6];\n  TensorMap<Tensor<float, 2>> mat1(data1, 2, 3);\n  float data2[6];\n  TensorMap<Tensor<float, 2, RowMajor>> mat2(data2, 2, 3);\n\n  mat1(0,0) = 0.0;\n  mat1(0,1) = 1.0;\n  mat1(0,2) = 2.0;\n  mat1(1,0) = 3.0;\n  mat1(1,1) = 4.0;\n  mat1(1,2) = 5.0;\n\n  mat2(0,0) = -0.0;\n  mat2(0,1) = -1.0;\n  mat2(0,2) = -2.0;\n  mat2(1,0) = -3.0;\n  mat2(1,1) = -4.0;\n  mat2(1,2) = -5.0;\n\n  Tensor<float, 2> mat3(2,3);\n  Tensor<float, 2, RowMajor> mat4(2,3);\n  mat3 = mat1.abs();\n  mat4 = mat2.abs();\n\n  VERIFY_IS_APPROX(mat3(0,0), 0.0f);\n  VERIFY_IS_APPROX(mat3(0,1), 1.0f);\n  VERIFY_IS_APPROX(mat3(0,2), 2.0f);\n  VERIFY_IS_APPROX(mat3(1,0), 3.0f);\n  VERIFY_IS_APPROX(mat3(1,1), 4.0f);\n  VERIFY_IS_APPROX(mat3(1,2), 5.0f);\n\n  VERIFY_IS_APPROX(mat4(0,0), 0.0f);\n  VERIFY_IS_APPROX(mat4(0,1), 1.0f);\n  VERIFY_IS_APPROX(mat4(0,2), 2.0f);\n  VERIFY_IS_APPROX(mat4(1,0), 3.0f);\n  VERIFY_IS_APPROX(mat4(1,1), 4.0f);\n  VERIFY_IS_APPROX(mat4(1,2), 5.0f);\n}\n\nstatic void test_3d()\n{\n  Tensor<float, 3> mat1(2,3,7);\n  Tensor<float, 3, RowMajor> mat2(2,3,7);\n\n  float val = 1.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        mat1(i,j,k) = val;\n        mat2(i,j,k) = val;\n        val += 1.0f;\n      }\n    }\n  }\n\n  Tensor<float, 3> mat3(2,3,7);\n  mat3 = mat1 + mat1;\n  Tensor<float, 3, RowMajor> mat4(2,3,7);\n  mat4 = mat2 * 3.14f;\n  Tensor<float, 3> mat5(2,3,7);\n  mat5 = mat1.inverse().log();\n  Tensor<float, 3, RowMajor> mat6(2,3,7);\n  mat6 = mat2.pow(0.5f) * 3.14f;\n  Tensor<float, 3> mat7(2,3,7);\n  mat7 = mat1.cwiseMax(mat5 * 2.0f).exp();\n  Tensor<float, 3, RowMajor> mat8(2,3,7);\n  mat8 = (-mat2).exp() * 3.14f;\n  Tensor<float, 3, RowMajor> mat9(2,3,7);\n  mat9 = mat2 + 3.14f;\n  Tensor<float, 3, RowMajor> mat10(2,3,7);\n  mat10 = mat2 - 3.14f;\n  Tensor<float, 3, RowMajor> mat11(2,3,7);\n  mat11 = mat2 / 3.14f;\n\n  val = 1.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(mat3(i,j,k), val + val);\n        VERIFY_IS_APPROX(mat4(i,j,k), val * 3.14f);\n        VERIFY_IS_APPROX(mat5(i,j,k), logf(1.0f/val));\n        VERIFY_IS_APPROX(mat6(i,j,k), sqrtf(val) * 3.14f);\n        VERIFY_IS_APPROX(mat7(i,j,k), expf((std::max)(val, mat5(i,j,k) * 2.0f)));\n        VERIFY_IS_APPROX(mat8(i,j,k), expf(-val) * 3.14f);\n        VERIFY_IS_APPROX(mat9(i,j,k), val + 3.14f);\n        VERIFY_IS_APPROX(mat10(i,j,k), val - 3.14f);\n        VERIFY_IS_APPROX(mat11(i,j,k), val / 3.14f);\n        val += 1.0f;\n      }\n    }\n  }\n}\n\nstatic void test_constants()\n{\n  Tensor<float, 3> mat1(2,3,7);\n  Tensor<float, 3> mat2(2,3,7);\n  Tensor<float, 3> mat3(2,3,7);\n\n  float val = 1.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        mat1(i,j,k) = val;\n        val += 1.0f;\n      }\n    }\n  }\n  mat2 = mat1.constant(3.14f);\n  mat3 = mat1.cwiseMax(7.3f).exp();\n\n  val = 1.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(mat2(i,j,k), 3.14f);\n        VERIFY_IS_APPROX(mat3(i,j,k), expf((std::max)(val, 7.3f)));\n        val += 1.0f;\n      }\n    }\n  }\n}\n\nstatic void test_boolean()\n{\n  const int kSize = 31;\n  Tensor<int, 1> vec(kSize);\n  std::iota(vec.data(), vec.data() + kSize, 0);\n\n  // Test ||.\n  Tensor<bool, 1> bool1 = vec < vec.constant(1) || vec > vec.constant(4);\n  for (int i = 0; i < kSize; ++i) {\n    bool expected = i < 1 || i > 4;\n    VERIFY_IS_EQUAL(bool1[i], expected);\n  }\n\n  // Test &&, including cast of operand vec.\n  Tensor<bool, 1> bool2 = vec.cast<bool>() && vec < vec.constant(4);\n  for (int i = 0; i < kSize; ++i) {\n    bool expected = bool(i) && i < 4;\n    VERIFY_IS_EQUAL(bool2[i], expected);\n  }\n\n  // Compilation tests:\n  // Test Tensor<bool> against results of cast or comparison; verifies that\n  // CoeffReturnType is set to match Op return type of bool for Unary and Binary\n  // Ops.\n  Tensor<bool, 1> bool3 = vec.cast<bool>() && bool2;\n  bool3 = vec < vec.constant(4) && bool2;\n}\n\nstatic void test_functors()\n{\n  Tensor<float, 3> mat1(2,3,7);\n  Tensor<float, 3> mat2(2,3,7);\n  Tensor<float, 3> mat3(2,3,7);\n\n  float val = 1.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        mat1(i,j,k) = val;\n        val += 1.0f;\n      }\n    }\n  }\n  mat2 = mat1.inverse().unaryExpr(&asinf);\n  mat3 = mat1.unaryExpr(&tanhf);\n\n  val = 1.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(mat2(i,j,k), asinf(1.0f / mat1(i,j,k)));\n        VERIFY_IS_APPROX(mat3(i,j,k), tanhf(mat1(i,j,k)));\n        val += 1.0f;\n      }\n    }\n  }\n}\n\nstatic void test_type_casting()\n{\n  Tensor<bool, 3> mat1(2,3,7);\n  Tensor<float, 3> mat2(2,3,7);\n  Tensor<double, 3> mat3(2,3,7);\n  mat1.setRandom();\n  mat2.setRandom();\n\n  mat3 = mat1.cast<double>();\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(mat3(i,j,k), mat1(i,j,k) ? 1.0 : 0.0);\n      }\n    }\n  }\n\n  mat3 = mat2.cast<double>();\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(mat3(i,j,k), static_cast<double>(mat2(i,j,k)));\n      }\n    }\n  }\n}\n\nstatic void test_select()\n{\n  Tensor<float, 3> selector(2,3,7);\n  Tensor<float, 3> mat1(2,3,7);\n  Tensor<float, 3> mat2(2,3,7);\n  Tensor<float, 3> result(2,3,7);\n\n  selector.setRandom();\n  mat1.setRandom();\n  mat2.setRandom();\n  result = (selector > selector.constant(0.5f)).select(mat1, mat2);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(result(i,j,k), (selector(i,j,k) > 0.5f) ? mat1(i,j,k) : mat2(i,j,k));\n      }\n    }\n  }\n}\n\ntemplate <typename Scalar>\nvoid test_minmax_nan_propagation_templ() {\n  for (int size = 1; size < 17; ++size) {\n    const Scalar kNaN = std::numeric_limits<Scalar>::quiet_NaN();\n    const Scalar kInf = std::numeric_limits<Scalar>::infinity();\n    const Scalar kZero(0);\n    Tensor<Scalar, 1> vec_full_nan(size);\n    Tensor<Scalar, 1> vec_one_nan(size);\n    Tensor<Scalar, 1> vec_zero(size);\n    vec_full_nan.setConstant(kNaN);\n    vec_zero.setZero();\n    vec_one_nan.setZero();\n    vec_one_nan(size/2) = kNaN;\n\n    auto verify_all_nan = [&](const Tensor<Scalar, 1>& v) {\n      for (int i = 0; i < size; ++i) {\n        VERIFY((numext::isnan)(v(i)));\n      }\n    };\n\n    auto verify_all_zero = [&](const Tensor<Scalar, 1>& v) {\n      for (int i = 0; i < size; ++i) {\n        VERIFY_IS_EQUAL(v(i), Scalar(0));\n      }\n    };\n\n    // Test NaN propagating max.\n    // max(nan, nan) = nan\n    // max(nan, 0) = nan\n    // max(0, nan) = nan\n    // max(0, 0) = 0\n    verify_all_nan(vec_full_nan.template cwiseMax<PropagateNaN>(kNaN));\n    verify_all_nan(vec_full_nan.template cwiseMax<PropagateNaN>(vec_full_nan));\n    verify_all_nan(vec_full_nan.template cwiseMax<PropagateNaN>(kZero));\n    verify_all_nan(vec_full_nan.template cwiseMax<PropagateNaN>(vec_zero));\n    verify_all_nan(vec_zero.template cwiseMax<PropagateNaN>(kNaN));\n    verify_all_nan(vec_zero.template cwiseMax<PropagateNaN>(vec_full_nan));\n    verify_all_zero(vec_zero.template cwiseMax<PropagateNaN>(kZero));\n    verify_all_zero(vec_zero.template cwiseMax<PropagateNaN>(vec_zero));\n\n    // Test number propagating max.\n    // max(nan, nan) = nan\n    // max(nan, 0) = 0\n    // max(0, nan) = 0\n    // max(0, 0) = 0\n    verify_all_nan(vec_full_nan.template cwiseMax<PropagateNumbers>(kNaN));\n    verify_all_nan(vec_full_nan.template cwiseMax<PropagateNumbers>(vec_full_nan));\n    verify_all_zero(vec_full_nan.template cwiseMax<PropagateNumbers>(kZero));\n    verify_all_zero(vec_full_nan.template cwiseMax<PropagateNumbers>(vec_zero));\n    verify_all_zero(vec_zero.template cwiseMax<PropagateNumbers>(kNaN));\n    verify_all_zero(vec_zero.template cwiseMax<PropagateNumbers>(vec_full_nan));\n    verify_all_zero(vec_zero.template cwiseMax<PropagateNumbers>(kZero));\n    verify_all_zero(vec_zero.template cwiseMax<PropagateNumbers>(vec_zero));\n\n    // Test NaN propagating min.\n    // min(nan, nan) = nan\n    // min(nan, 0) = nan\n    // min(0, nan) = nan\n    // min(0, 0) = 0\n    verify_all_nan(vec_full_nan.template cwiseMin<PropagateNaN>(kNaN));\n    verify_all_nan(vec_full_nan.template cwiseMin<PropagateNaN>(vec_full_nan));\n    verify_all_nan(vec_full_nan.template cwiseMin<PropagateNaN>(kZero));\n    verify_all_nan(vec_full_nan.template cwiseMin<PropagateNaN>(vec_zero));\n    verify_all_nan(vec_zero.template cwiseMin<PropagateNaN>(kNaN));\n    verify_all_nan(vec_zero.template cwiseMin<PropagateNaN>(vec_full_nan));\n    verify_all_zero(vec_zero.template cwiseMin<PropagateNaN>(kZero));\n    verify_all_zero(vec_zero.template cwiseMin<PropagateNaN>(vec_zero));\n\n    // Test number propagating min.\n    // min(nan, nan) = nan\n    // min(nan, 0) = 0\n    // min(0, nan) = 0\n    // min(0, 0) = 0\n    verify_all_nan(vec_full_nan.template cwiseMin<PropagateNumbers>(kNaN));\n    verify_all_nan(vec_full_nan.template cwiseMin<PropagateNumbers>(vec_full_nan));\n    verify_all_zero(vec_full_nan.template cwiseMin<PropagateNumbers>(kZero));\n    verify_all_zero(vec_full_nan.template cwiseMin<PropagateNumbers>(vec_zero));\n    verify_all_zero(vec_zero.template cwiseMin<PropagateNumbers>(kNaN));\n    verify_all_zero(vec_zero.template cwiseMin<PropagateNumbers>(vec_full_nan));\n    verify_all_zero(vec_zero.template cwiseMin<PropagateNumbers>(kZero));\n    verify_all_zero(vec_zero.template cwiseMin<PropagateNumbers>(vec_zero));\n\n    // Test min and max reduction\n    Tensor<Scalar, 0> val;\n    val = vec_zero.minimum();\n    VERIFY_IS_EQUAL(val(), kZero);\n    val = vec_zero.template minimum<PropagateNaN>();\n    VERIFY_IS_EQUAL(val(), kZero);\n    val = vec_zero.template minimum<PropagateNumbers>();\n    VERIFY_IS_EQUAL(val(), kZero);\n    val = vec_zero.maximum();\n    VERIFY_IS_EQUAL(val(), kZero);\n    val = vec_zero.template maximum<PropagateNaN>();\n    VERIFY_IS_EQUAL(val(), kZero);\n    val = vec_zero.template maximum<PropagateNumbers>();\n    VERIFY_IS_EQUAL(val(), kZero);\n\n    // Test NaN propagation for tensor of all NaNs.\n    val = vec_full_nan.template minimum<PropagateNaN>();\n    VERIFY((numext::isnan)(val()));\n    val = vec_full_nan.template minimum<PropagateNumbers>();\n    VERIFY_IS_EQUAL(val(), kInf);\n    val = vec_full_nan.template maximum<PropagateNaN>();\n    VERIFY((numext::isnan)(val()));\n    val = vec_full_nan.template maximum<PropagateNumbers>();\n    VERIFY_IS_EQUAL(val(), -kInf);\n\n    // Test NaN propagation for tensor with a single NaN.\n    val = vec_one_nan.template minimum<PropagateNaN>();\n    VERIFY((numext::isnan)(val()));\n    val = vec_one_nan.template minimum<PropagateNumbers>();\n    VERIFY_IS_EQUAL(val(), (size == 1 ? kInf : kZero));\n    val = vec_one_nan.template maximum<PropagateNaN>();\n    VERIFY((numext::isnan)(val()));\n    val = vec_one_nan.template maximum<PropagateNumbers>();\n    VERIFY_IS_EQUAL(val(), (size == 1 ? -kInf : kZero));\n  }\n}\n\nstatic void test_clip()\n{\n  Tensor<float, 1> vec(6);\n  vec(0) = 4.0;\n  vec(1) = 8.0;\n  vec(2) = 15.0;\n  vec(3) = 16.0;\n  vec(4) = 23.0;\n  vec(5) = 42.0;\n\n  float kMin = 20;\n  float kMax = 30;\n\n  Tensor<float, 1> vec_clipped(6);\n  vec_clipped = vec.clip(kMin, kMax);\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_EQUAL(vec_clipped(i), numext::mini(numext::maxi(vec(i), kMin), kMax));\n  }\n}\n\nstatic void test_minmax_nan_propagation()\n{\n  test_minmax_nan_propagation_templ<float>();\n  test_minmax_nan_propagation_templ<double>();\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_expr)\n{\n  CALL_SUBTEST(test_1d());\n  CALL_SUBTEST(test_2d());\n  CALL_SUBTEST(test_3d());\n  CALL_SUBTEST(test_constants());\n  CALL_SUBTEST(test_boolean());\n  CALL_SUBTEST(test_functors());\n  CALL_SUBTEST(test_type_casting());\n  CALL_SUBTEST(test_select());\n  CALL_SUBTEST(test_clip());\n\n// Nan propagation does currently not work like one would expect from std::max/std::min,\n// so we disable it for now\n#if !EIGEN_ARCH_ARM_OR_ARM64\n  CALL_SUBTEST(test_minmax_nan_propagation());\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_fft.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Jianwei Cui <thucjw@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate <int DataLayout>\nstatic void test_fft_2D_golden() {\n  Tensor<float, 2, DataLayout> input(2, 3);\n  input(0, 0) = 1;\n  input(0, 1) = 2;\n  input(0, 2) = 3;\n  input(1, 0) = 4;\n  input(1, 1) = 5;\n  input(1, 2) = 6;\n\n  array<ptrdiff_t, 2> fft;\n  fft[0] = 0;\n  fft[1] = 1;\n\n  Tensor<std::complex<float>, 2, DataLayout> output = input.template fft<Eigen::BothParts, Eigen::FFT_FORWARD>(fft);\n\n  std::complex<float> output_golden[6]; // in ColMajor order\n  output_golden[0] = std::complex<float>(21, 0);\n  output_golden[1] = std::complex<float>(-9, 0);\n  output_golden[2] = std::complex<float>(-3, 1.73205);\n  output_golden[3] = std::complex<float>( 0, 0);\n  output_golden[4] = std::complex<float>(-3, -1.73205);\n  output_golden[5] = std::complex<float>(0 ,0);\n\n  std::complex<float> c_offset = std::complex<float>(1.0, 1.0);\n\n  if (DataLayout == ColMajor) {\n    VERIFY_IS_APPROX(output(0) + c_offset, output_golden[0] + c_offset);\n    VERIFY_IS_APPROX(output(1) + c_offset, output_golden[1] + c_offset);\n    VERIFY_IS_APPROX(output(2) + c_offset, output_golden[2] + c_offset);\n    VERIFY_IS_APPROX(output(3) + c_offset, output_golden[3] + c_offset);\n    VERIFY_IS_APPROX(output(4) + c_offset, output_golden[4] + c_offset);\n    VERIFY_IS_APPROX(output(5) + c_offset, output_golden[5] + c_offset);\n  }\n  else {\n    VERIFY_IS_APPROX(output(0)+ c_offset, output_golden[0]+ c_offset);\n    VERIFY_IS_APPROX(output(1)+ c_offset, output_golden[2]+ c_offset);\n    VERIFY_IS_APPROX(output(2)+ c_offset, output_golden[4]+ c_offset);\n    VERIFY_IS_APPROX(output(3)+ c_offset, output_golden[1]+ c_offset);\n    VERIFY_IS_APPROX(output(4)+ c_offset, output_golden[3]+ c_offset);\n    VERIFY_IS_APPROX(output(5)+ c_offset, output_golden[5]+ c_offset);\n  }\n}\n\nstatic void test_fft_complex_input_golden() {\n  Tensor<std::complex<float>, 1, ColMajor> input(5);\n  input(0) = std::complex<float>(1, 1);\n  input(1) = std::complex<float>(2, 2);\n  input(2) = std::complex<float>(3, 3);\n  input(3) = std::complex<float>(4, 4);\n  input(4) = std::complex<float>(5, 5);\n\n  array<ptrdiff_t, 1> fft;\n  fft[0] = 0;\n\n  Tensor<std::complex<float>, 1, ColMajor> forward_output_both_parts = input.fft<BothParts, FFT_FORWARD>(fft);\n  Tensor<std::complex<float>, 1, ColMajor> reverse_output_both_parts = input.fft<BothParts, FFT_REVERSE>(fft);\n\n  Tensor<float, 1, ColMajor> forward_output_real_part = input.fft<RealPart, FFT_FORWARD>(fft);\n  Tensor<float, 1, ColMajor> reverse_output_real_part = input.fft<RealPart, FFT_REVERSE>(fft);\n\n  Tensor<float, 1, ColMajor> forward_output_imag_part = input.fft<ImagPart, FFT_FORWARD>(fft);\n  Tensor<float, 1, ColMajor> reverse_output_imag_part = input.fft<ImagPart, FFT_REVERSE>(fft);\n\n  VERIFY_IS_EQUAL(forward_output_both_parts.dimension(0), input.dimension(0));\n  VERIFY_IS_EQUAL(reverse_output_both_parts.dimension(0), input.dimension(0));\n\n  VERIFY_IS_EQUAL(forward_output_real_part.dimension(0), input.dimension(0));\n  VERIFY_IS_EQUAL(reverse_output_real_part.dimension(0), input.dimension(0));\n\n  VERIFY_IS_EQUAL(forward_output_imag_part.dimension(0), input.dimension(0));\n  VERIFY_IS_EQUAL(reverse_output_imag_part.dimension(0), input.dimension(0));\n\n  std::complex<float> forward_golden_result[5];\n  std::complex<float> reverse_golden_result[5];\n\n  forward_golden_result[0] = std::complex<float>(15.000000000000000,+15.000000000000000);\n  forward_golden_result[1] = std::complex<float>(-5.940954801177935, +0.940954801177934);\n  forward_golden_result[2] = std::complex<float>(-3.312299240582266, -1.687700759417735);\n  forward_golden_result[3] = std::complex<float>(-1.687700759417735, -3.312299240582266);\n  forward_golden_result[4] = std::complex<float>( 0.940954801177934, -5.940954801177935);\n\n  reverse_golden_result[0] = std::complex<float>( 3.000000000000000, + 3.000000000000000);\n  reverse_golden_result[1] = std::complex<float>( 0.188190960235587, - 1.188190960235587);\n  reverse_golden_result[2] = std::complex<float>(-0.337540151883547, - 0.662459848116453);\n  reverse_golden_result[3] = std::complex<float>(-0.662459848116453, - 0.337540151883547);\n  reverse_golden_result[4] = std::complex<float>(-1.188190960235587, + 0.188190960235587);\n\n  for(int i = 0; i < 5; ++i) {\n    VERIFY_IS_APPROX(forward_output_both_parts(i), forward_golden_result[i]);\n    VERIFY_IS_APPROX(forward_output_real_part(i), forward_golden_result[i].real());\n    VERIFY_IS_APPROX(forward_output_imag_part(i), forward_golden_result[i].imag());\n  }\n\n  for(int i = 0; i < 5; ++i) {\n    VERIFY_IS_APPROX(reverse_output_both_parts(i), reverse_golden_result[i]);\n    VERIFY_IS_APPROX(reverse_output_real_part(i), reverse_golden_result[i].real());\n    VERIFY_IS_APPROX(reverse_output_imag_part(i), reverse_golden_result[i].imag());\n  }\n}\n\nstatic void test_fft_real_input_golden() {\n  Tensor<float, 1, ColMajor> input(5);\n  input(0) = 1.0;\n  input(1) = 2.0;\n  input(2) = 3.0;\n  input(3) = 4.0;\n  input(4) = 5.0;\n\n  array<ptrdiff_t, 1> fft;\n  fft[0] = 0;\n\n  Tensor<std::complex<float>, 1, ColMajor> forward_output_both_parts = input.fft<BothParts, FFT_FORWARD>(fft);\n  Tensor<std::complex<float>, 1, ColMajor> reverse_output_both_parts = input.fft<BothParts, FFT_REVERSE>(fft);\n\n  Tensor<float, 1, ColMajor> forward_output_real_part = input.fft<RealPart, FFT_FORWARD>(fft);\n  Tensor<float, 1, ColMajor> reverse_output_real_part = input.fft<RealPart, FFT_REVERSE>(fft);\n\n  Tensor<float, 1, ColMajor> forward_output_imag_part = input.fft<ImagPart, FFT_FORWARD>(fft);\n  Tensor<float, 1, ColMajor> reverse_output_imag_part = input.fft<ImagPart, FFT_REVERSE>(fft);\n\n  VERIFY_IS_EQUAL(forward_output_both_parts.dimension(0), input.dimension(0));\n  VERIFY_IS_EQUAL(reverse_output_both_parts.dimension(0), input.dimension(0));\n\n  VERIFY_IS_EQUAL(forward_output_real_part.dimension(0), input.dimension(0));\n  VERIFY_IS_EQUAL(reverse_output_real_part.dimension(0), input.dimension(0));\n\n  VERIFY_IS_EQUAL(forward_output_imag_part.dimension(0), input.dimension(0));\n  VERIFY_IS_EQUAL(reverse_output_imag_part.dimension(0), input.dimension(0));\n\n  std::complex<float> forward_golden_result[5];\n  std::complex<float> reverse_golden_result[5];\n\n\n  forward_golden_result[0] = std::complex<float>(  15, 0);\n  forward_golden_result[1] = std::complex<float>(-2.5, +3.44095480117793);\n  forward_golden_result[2] = std::complex<float>(-2.5, +0.81229924058227);\n  forward_golden_result[3] = std::complex<float>(-2.5, -0.81229924058227);\n  forward_golden_result[4] = std::complex<float>(-2.5, -3.44095480117793);\n\n  reverse_golden_result[0] = std::complex<float>( 3.0, 0);\n  reverse_golden_result[1] = std::complex<float>(-0.5, -0.688190960235587);\n  reverse_golden_result[2] = std::complex<float>(-0.5, -0.162459848116453);\n  reverse_golden_result[3] = std::complex<float>(-0.5, +0.162459848116453);\n  reverse_golden_result[4] = std::complex<float>(-0.5, +0.688190960235587);\n\n  std::complex<float> c_offset(1.0, 1.0);\n  float r_offset = 1.0;\n\n  for(int i = 0; i < 5; ++i) {\n    VERIFY_IS_APPROX(forward_output_both_parts(i) + c_offset, forward_golden_result[i] + c_offset);\n    VERIFY_IS_APPROX(forward_output_real_part(i)  + r_offset, forward_golden_result[i].real() + r_offset);\n    VERIFY_IS_APPROX(forward_output_imag_part(i)  + r_offset, forward_golden_result[i].imag() + r_offset);\n  }\n\n  for(int i = 0; i < 5; ++i) {\n    VERIFY_IS_APPROX(reverse_output_both_parts(i) + c_offset, reverse_golden_result[i] + c_offset);\n    VERIFY_IS_APPROX(reverse_output_real_part(i)  + r_offset, reverse_golden_result[i].real() + r_offset);\n    VERIFY_IS_APPROX(reverse_output_imag_part(i)  + r_offset, reverse_golden_result[i].imag() + r_offset);\n  }\n}\n\n\ntemplate <int DataLayout, typename RealScalar, bool isComplexInput, int FFTResultType, int FFTDirection, int TensorRank>\nstatic void test_fft_real_input_energy() {\n\n  Eigen::DSizes<ptrdiff_t, TensorRank> dimensions;\n  ptrdiff_t total_size = 1;\n  for (int i = 0; i < TensorRank; ++i) {\n    dimensions[i] = rand() % 20 + 1;\n    total_size *= dimensions[i];\n  }\n  const DSizes<ptrdiff_t, TensorRank> arr = dimensions;\n\n  typedef typename internal::conditional<isComplexInput == true, std::complex<RealScalar>, RealScalar>::type InputScalar;\n\n  Tensor<InputScalar, TensorRank, DataLayout> input;\n  input.resize(arr);\n  input.setRandom();\n\n  array<ptrdiff_t, TensorRank> fft;\n  for (int i = 0; i < TensorRank; ++i) {\n    fft[i] = i;\n  }\n\n  typedef typename internal::conditional<FFTResultType == Eigen::BothParts, std::complex<RealScalar>, RealScalar>::type OutputScalar;\n  Tensor<OutputScalar, TensorRank, DataLayout> output;\n  output = input.template fft<FFTResultType, FFTDirection>(fft);\n\n  for (int i = 0; i < TensorRank; ++i) {\n    VERIFY_IS_EQUAL(output.dimension(i), input.dimension(i));\n  }\n\n  RealScalar energy_original = 0.0;\n  RealScalar energy_after_fft = 0.0;\n\n  for (int i = 0; i < total_size; ++i) {\n    energy_original += numext::abs2(input(i));\n  }\n\n  for (int i = 0; i < total_size; ++i) {\n    energy_after_fft += numext::abs2(output(i));\n  }\n\n  if(FFTDirection == FFT_FORWARD) {\n    VERIFY_IS_APPROX(energy_original, energy_after_fft / total_size);\n  }\n  else {\n    VERIFY_IS_APPROX(energy_original, energy_after_fft * total_size);\n  }\n}\n\ntemplate <typename RealScalar>\nstatic void test_fft_non_power_of_2_round_trip(int exponent) {\n  int n = (1 << exponent) + 1;\n\n  Eigen::DSizes<ptrdiff_t, 1> dimensions;\n  dimensions[0] = n;\n  const DSizes<ptrdiff_t, 1> arr = dimensions;\n  Tensor<RealScalar, 1, ColMajor, ptrdiff_t> input;\n\n  input.resize(arr);\n  input.setRandom();\n\n  array<int, 1> fft;\n  fft[0] = 0;\n\n  Tensor<std::complex<RealScalar>, 1, ColMajor> forward =\n      input.template fft<BothParts, FFT_FORWARD>(fft);\n\n  Tensor<RealScalar, 1, ColMajor, ptrdiff_t> output =\n      forward.template fft<RealPart, FFT_REVERSE>(fft);\n\n  for (int i = 0; i < n; ++i) {\n    RealScalar tol = test_precision<RealScalar>() *\n                     (std::abs(input[i]) + std::abs(output[i]) + 1);\n    VERIFY_IS_APPROX_OR_LESS_THAN(std::abs(input[i] - output[i]), tol);\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_fft) {\n    test_fft_complex_input_golden();\n    test_fft_real_input_golden();\n\n    test_fft_2D_golden<ColMajor>();\n    test_fft_2D_golden<RowMajor>();\n\n    test_fft_real_input_energy<ColMajor, float,  true,  Eigen::BothParts, FFT_FORWARD, 1>();\n    test_fft_real_input_energy<ColMajor, double, true,  Eigen::BothParts, FFT_FORWARD, 1>();\n    test_fft_real_input_energy<ColMajor, float,  false,  Eigen::BothParts, FFT_FORWARD, 1>();\n    test_fft_real_input_energy<ColMajor, double, false,  Eigen::BothParts, FFT_FORWARD, 1>();\n\n    test_fft_real_input_energy<ColMajor, float,  true,  Eigen::BothParts, FFT_FORWARD, 2>();\n    test_fft_real_input_energy<ColMajor, double, true,  Eigen::BothParts, FFT_FORWARD, 2>();\n    test_fft_real_input_energy<ColMajor, float,  false,  Eigen::BothParts, FFT_FORWARD, 2>();\n    test_fft_real_input_energy<ColMajor, double, false,  Eigen::BothParts, FFT_FORWARD, 2>();\n\n    test_fft_real_input_energy<ColMajor, float,  true,  Eigen::BothParts, FFT_FORWARD, 3>();\n    test_fft_real_input_energy<ColMajor, double, true,  Eigen::BothParts, FFT_FORWARD, 3>();\n    test_fft_real_input_energy<ColMajor, float,  false,  Eigen::BothParts, FFT_FORWARD, 3>();\n    test_fft_real_input_energy<ColMajor, double, false,  Eigen::BothParts, FFT_FORWARD, 3>();\n\n    test_fft_real_input_energy<ColMajor, float,  true,  Eigen::BothParts, FFT_FORWARD, 4>();\n    test_fft_real_input_energy<ColMajor, double, true,  Eigen::BothParts, FFT_FORWARD, 4>();\n    test_fft_real_input_energy<ColMajor, float,  false,  Eigen::BothParts, FFT_FORWARD, 4>();\n    test_fft_real_input_energy<ColMajor, double, false,  Eigen::BothParts, FFT_FORWARD, 4>();\n\n    test_fft_real_input_energy<RowMajor, float,  true,  Eigen::BothParts, FFT_FORWARD, 1>();\n    test_fft_real_input_energy<RowMajor, double, true,  Eigen::BothParts, FFT_FORWARD, 1>();\n    test_fft_real_input_energy<RowMajor, float,  false,  Eigen::BothParts, FFT_FORWARD, 1>();\n    test_fft_real_input_energy<RowMajor, double, false,  Eigen::BothParts, FFT_FORWARD, 1>();\n\n    test_fft_real_input_energy<RowMajor, float,  true,  Eigen::BothParts, FFT_FORWARD, 2>();\n    test_fft_real_input_energy<RowMajor, double, true,  Eigen::BothParts, FFT_FORWARD, 2>();\n    test_fft_real_input_energy<RowMajor, float,  false,  Eigen::BothParts, FFT_FORWARD, 2>();\n    test_fft_real_input_energy<RowMajor, double, false,  Eigen::BothParts, FFT_FORWARD, 2>();\n\n    test_fft_real_input_energy<RowMajor, float,  true,  Eigen::BothParts, FFT_FORWARD, 3>();\n    test_fft_real_input_energy<RowMajor, double, true,  Eigen::BothParts, FFT_FORWARD, 3>();\n    test_fft_real_input_energy<RowMajor, float,  false,  Eigen::BothParts, FFT_FORWARD, 3>();\n    test_fft_real_input_energy<RowMajor, double, false,  Eigen::BothParts, FFT_FORWARD, 3>();\n\n    test_fft_real_input_energy<RowMajor, float,  true,  Eigen::BothParts, FFT_FORWARD, 4>();\n    test_fft_real_input_energy<RowMajor, double, true,  Eigen::BothParts, FFT_FORWARD, 4>();\n    test_fft_real_input_energy<RowMajor, float,  false,  Eigen::BothParts, FFT_FORWARD, 4>();\n    test_fft_real_input_energy<RowMajor, double, false,  Eigen::BothParts, FFT_FORWARD, 4>();\n\n    test_fft_non_power_of_2_round_trip<float>(7);\n    test_fft_non_power_of_2_round_trip<double>(7);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_fixed_size.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\n\nstatic void test_0d()\n{\n  TensorFixedSize<float, Sizes<> > scalar1;\n  TensorFixedSize<float, Sizes<>, RowMajor> scalar2;\n  VERIFY_IS_EQUAL(scalar1.rank(), 0);\n  VERIFY_IS_EQUAL(scalar1.size(), 1);\n  VERIFY_IS_EQUAL(internal::array_prod(scalar1.dimensions()), 1);\n\n  scalar1() = 7.0;\n  scalar2() = 13.0;\n\n  // Test against shallow copy.\n  TensorFixedSize<float, Sizes<> > copy = scalar1;\n  VERIFY_IS_NOT_EQUAL(scalar1.data(), copy.data());\n  VERIFY_IS_APPROX(scalar1(), copy());\n  copy = scalar1;\n  VERIFY_IS_NOT_EQUAL(scalar1.data(), copy.data());\n  VERIFY_IS_APPROX(scalar1(), copy());\n\n  TensorFixedSize<float, Sizes<> > scalar3 = scalar1.sqrt();\n  TensorFixedSize<float, Sizes<>, RowMajor> scalar4 = scalar2.sqrt();\n  VERIFY_IS_EQUAL(scalar3.rank(), 0);\n  VERIFY_IS_APPROX(scalar3(), sqrtf(7.0));\n  VERIFY_IS_APPROX(scalar4(), sqrtf(13.0));\n\n  scalar3 = scalar1 + scalar2;\n  VERIFY_IS_APPROX(scalar3(), 7.0f + 13.0f);\n}\n\nstatic void test_1d()\n{\n  TensorFixedSize<float, Sizes<6> > vec1;\n  TensorFixedSize<float, Sizes<6>, RowMajor> vec2;\n\n  VERIFY_IS_EQUAL((vec1.size()), 6);\n  //  VERIFY_IS_EQUAL((vec1.dimensions()[0]), 6);\n  //  VERIFY_IS_EQUAL((vec1.dimension(0)), 6);\n\n  vec1(0) = 4.0;  vec2(0) = 0.0;\n  vec1(1) = 8.0;  vec2(1) = 1.0;\n  vec1(2) = 15.0; vec2(2) = 2.0;\n  vec1(3) = 16.0; vec2(3) = 3.0;\n  vec1(4) = 23.0; vec2(4) = 4.0;\n  vec1(5) = 42.0; vec2(5) = 5.0;\n\n  // Test against shallow copy.\n  TensorFixedSize<float, Sizes<6> > copy = vec1;\n  VERIFY_IS_NOT_EQUAL(vec1.data(), copy.data());\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_APPROX(vec1(i), copy(i));\n  }\n  copy = vec1;\n  VERIFY_IS_NOT_EQUAL(vec1.data(), copy.data());\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_APPROX(vec1(i), copy(i));\n  }\n\n  TensorFixedSize<float, Sizes<6> > vec3 = vec1.sqrt();\n  TensorFixedSize<float, Sizes<6>, RowMajor> vec4 = vec2.sqrt();\n\n  VERIFY_IS_EQUAL((vec3.size()), 6);\n  VERIFY_IS_EQUAL(vec3.rank(), 1);\n  //  VERIFY_IS_EQUAL((vec3.dimensions()[0]), 6);\n  //  VERIFY_IS_EQUAL((vec3.dimension(0)), 6);\n\n  VERIFY_IS_APPROX(vec3(0), sqrtf(4.0));\n  VERIFY_IS_APPROX(vec3(1), sqrtf(8.0));\n  VERIFY_IS_APPROX(vec3(2), sqrtf(15.0));\n  VERIFY_IS_APPROX(vec3(3), sqrtf(16.0));\n  VERIFY_IS_APPROX(vec3(4), sqrtf(23.0));\n  VERIFY_IS_APPROX(vec3(5), sqrtf(42.0));\n\n  VERIFY_IS_APPROX(vec4(0), sqrtf(0.0));\n  VERIFY_IS_APPROX(vec4(1), sqrtf(1.0));\n  VERIFY_IS_APPROX(vec4(2), sqrtf(2.0));\n  VERIFY_IS_APPROX(vec4(3), sqrtf(3.0));\n  VERIFY_IS_APPROX(vec4(4), sqrtf(4.0));\n  VERIFY_IS_APPROX(vec4(5), sqrtf(5.0));\n\n  vec3 = vec1 + vec2;\n  VERIFY_IS_APPROX(vec3(0), 4.0f + 0.0f);\n  VERIFY_IS_APPROX(vec3(1), 8.0f + 1.0f);\n  VERIFY_IS_APPROX(vec3(2), 15.0f + 2.0f);\n  VERIFY_IS_APPROX(vec3(3), 16.0f + 3.0f);\n  VERIFY_IS_APPROX(vec3(4), 23.0f + 4.0f);\n  VERIFY_IS_APPROX(vec3(5), 42.0f + 5.0f);\n}\n\nstatic void test_tensor_map()\n{\n  TensorFixedSize<float, Sizes<6> > vec1;\n  TensorFixedSize<float, Sizes<6>, RowMajor> vec2;\n\n  vec1(0) = 4.0;  vec2(0) = 0.0;\n  vec1(1) = 8.0;  vec2(1) = 1.0;\n  vec1(2) = 15.0; vec2(2) = 2.0;\n  vec1(3) = 16.0; vec2(3) = 3.0;\n  vec1(4) = 23.0; vec2(4) = 4.0;\n  vec1(5) = 42.0; vec2(5) = 5.0;\n\n  float data3[6];\n  TensorMap<TensorFixedSize<float, Sizes<6> > > vec3(data3, 6);\n  vec3 = vec1.sqrt() + vec2;\n\n  VERIFY_IS_APPROX(vec3(0), sqrtf(4.0));\n  VERIFY_IS_APPROX(vec3(1), sqrtf(8.0) + 1.0f);\n  VERIFY_IS_APPROX(vec3(2), sqrtf(15.0) + 2.0f);\n  VERIFY_IS_APPROX(vec3(3), sqrtf(16.0) + 3.0f);\n  VERIFY_IS_APPROX(vec3(4), sqrtf(23.0) + 4.0f);\n  VERIFY_IS_APPROX(vec3(5), sqrtf(42.0) + 5.0f);\n}\n\nstatic void test_2d()\n{\n  float data1[6];\n  TensorMap<TensorFixedSize<float, Sizes<2, 3> > > mat1(data1,2,3);\n  float data2[6];\n  TensorMap<TensorFixedSize<float, Sizes<2, 3>, RowMajor> > mat2(data2,2,3);\n\n  VERIFY_IS_EQUAL((mat1.size()), 2*3);\n  VERIFY_IS_EQUAL(mat1.rank(), 2);\n  //  VERIFY_IS_EQUAL((mat1.dimension(0)), 2);\n  //  VERIFY_IS_EQUAL((mat1.dimension(1)), 3);\n\n  mat1(0,0) = 0.0;\n  mat1(0,1) = 1.0;\n  mat1(0,2) = 2.0;\n  mat1(1,0) = 3.0;\n  mat1(1,1) = 4.0;\n  mat1(1,2) = 5.0;\n\n  mat2(0,0) = -0.0;\n  mat2(0,1) = -1.0;\n  mat2(0,2) = -2.0;\n  mat2(1,0) = -3.0;\n  mat2(1,1) = -4.0;\n  mat2(1,2) = -5.0;\n\n  TensorFixedSize<float, Sizes<2, 3> > mat3;\n  TensorFixedSize<float, Sizes<2, 3>, RowMajor> mat4;\n  mat3 = mat1.abs();\n  mat4 = mat2.abs();\n\n  VERIFY_IS_EQUAL((mat3.size()), 2*3);\n    //  VERIFY_IS_EQUAL((mat3.dimension(0)), 2);\n    //  VERIFY_IS_EQUAL((mat3.dimension(1)), 3);\n\n  VERIFY_IS_APPROX(mat3(0,0), 0.0f);\n  VERIFY_IS_APPROX(mat3(0,1), 1.0f);\n  VERIFY_IS_APPROX(mat3(0,2), 2.0f);\n  VERIFY_IS_APPROX(mat3(1,0), 3.0f);\n  VERIFY_IS_APPROX(mat3(1,1), 4.0f);\n  VERIFY_IS_APPROX(mat3(1,2), 5.0f);\n\n  VERIFY_IS_APPROX(mat4(0,0), 0.0f);\n  VERIFY_IS_APPROX(mat4(0,1), 1.0f);\n  VERIFY_IS_APPROX(mat4(0,2), 2.0f);\n  VERIFY_IS_APPROX(mat4(1,0), 3.0f);\n  VERIFY_IS_APPROX(mat4(1,1), 4.0f);\n  VERIFY_IS_APPROX(mat4(1,2), 5.0f);\n}\n\nstatic void test_3d()\n{\n  TensorFixedSize<float, Sizes<2, 3, 7> > mat1;\n  TensorFixedSize<float, Sizes<2, 3, 7>, RowMajor> mat2;\n\n  VERIFY_IS_EQUAL((mat1.size()), 2*3*7);\n  VERIFY_IS_EQUAL(mat1.rank(), 3);\n  //  VERIFY_IS_EQUAL((mat1.dimension(0)), 2);\n  //  VERIFY_IS_EQUAL((mat1.dimension(1)), 3);\n  //  VERIFY_IS_EQUAL((mat1.dimension(2)), 7);\n\n  float val = 0.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        mat1(i,j,k) = val;\n        mat2(i,j,k) = val;\n        val += 1.0f;\n      }\n    }\n  }\n\n  TensorFixedSize<float, Sizes<2, 3, 7> > mat3;\n  mat3 = mat1.sqrt();\n  TensorFixedSize<float, Sizes<2, 3, 7>, RowMajor> mat4;\n  mat4 = mat2.sqrt();\n\n  VERIFY_IS_EQUAL((mat3.size()), 2*3*7);\n  //  VERIFY_IS_EQUAL((mat3.dimension(0)), 2);\n  //  VERIFY_IS_EQUAL((mat3.dimension(1)), 3);\n  //  VERIFY_IS_EQUAL((mat3.dimension(2)), 7);\n\n\n  val = 0.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(mat3(i,j,k), sqrtf(val));\n        VERIFY_IS_APPROX(mat4(i,j,k), sqrtf(val));\n        val += 1.0f;\n      }\n    }\n  }\n}\n\n\nstatic void test_array()\n{\n  TensorFixedSize<float, Sizes<2, 3, 7> > mat1;\n  float val = 0.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        mat1(i,j,k) = val;\n        val += 1.0f;\n      }\n    }\n  }\n\n  TensorFixedSize<float, Sizes<2, 3, 7> > mat3;\n  mat3 = mat1.pow(3.5f);\n\n  val = 0.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(mat3(i,j,k), powf(val, 3.5f));\n        val += 1.0f;\n      }\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_fixed_size)\n{\n  CALL_SUBTEST(test_0d());\n  CALL_SUBTEST(test_1d());\n  CALL_SUBTEST(test_tensor_map());\n  CALL_SUBTEST(test_2d());\n  CALL_SUBTEST(test_3d());\n  CALL_SUBTEST(test_array());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_forced_eval.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/Core>\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::MatrixXf;\nusing Eigen::Tensor;\n\nstatic void test_simple()\n{\n  MatrixXf m1(3,3);\n  MatrixXf m2(3,3);\n  m1.setRandom();\n  m2.setRandom();\n\n  TensorMap<Tensor<float, 2> > mat1(m1.data(), 3,3);\n  TensorMap<Tensor<float, 2> > mat2(m2.data(), 3,3);\n\n  Tensor<float, 2> mat3(3,3);\n  mat3 = mat1;\n\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n  Eigen::array<DimPair, 1> dims;\n  dims[0] = DimPair(1, 0);\n\n  mat3 = mat3.contract(mat2, dims).eval();\n\n  VERIFY_IS_APPROX(mat3(0, 0), (m1*m2).eval()(0,0));\n  VERIFY_IS_APPROX(mat3(0, 1), (m1*m2).eval()(0,1));\n  VERIFY_IS_APPROX(mat3(0, 2), (m1*m2).eval()(0,2));\n  VERIFY_IS_APPROX(mat3(1, 0), (m1*m2).eval()(1,0));\n  VERIFY_IS_APPROX(mat3(1, 1), (m1*m2).eval()(1,1));\n  VERIFY_IS_APPROX(mat3(1, 2), (m1*m2).eval()(1,2));\n  VERIFY_IS_APPROX(mat3(2, 0), (m1*m2).eval()(2,0));\n  VERIFY_IS_APPROX(mat3(2, 1), (m1*m2).eval()(2,1));\n  VERIFY_IS_APPROX(mat3(2, 2), (m1*m2).eval()(2,2));\n}\n\n\nstatic void test_const()\n{\n  MatrixXf input(3,3);\n  input.setRandom();\n  MatrixXf output = input;\n  output.rowwise() -= input.colwise().maxCoeff();\n\n  Eigen::array<int, 1> depth_dim;\n  depth_dim[0] = 0;\n  Tensor<float, 2>::Dimensions dims2d;\n  dims2d[0] = 1;\n  dims2d[1] = 3;\n  Eigen::array<int, 2> bcast;\n  bcast[0] = 3;\n  bcast[1] = 1;\n  const TensorMap<const Tensor<float, 2> > input_tensor(input.data(), 3, 3);\n  Tensor<float, 2> output_tensor= (input_tensor - input_tensor.maximum(depth_dim).eval().reshape(dims2d).broadcast(bcast));\n\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_APPROX(output(i, j), output_tensor(i, j));\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_forced_eval)\n{\n  CALL_SUBTEST(test_simple());\n  CALL_SUBTEST(test_const());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_forced_eval_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_forced_eval_sycl(const Eigen::SyclDevice &sycl_device) {\n\n  IndexType sizeDim1 = 100;\n  IndexType sizeDim2 = 20;\n  IndexType sizeDim3 = 20;\n  Eigen::array<IndexType, 3> tensorRange = {{sizeDim1, sizeDim2, sizeDim3}};\n  Eigen::Tensor<DataType, 3, DataLayout, IndexType> in1(tensorRange);\n  Eigen::Tensor<DataType, 3, DataLayout, IndexType> in2(tensorRange);\n  Eigen::Tensor<DataType, 3, DataLayout, IndexType> out(tensorRange);\n\n  DataType * gpu_in1_data  = static_cast<DataType*>(sycl_device.allocate(in1.dimensions().TotalSize()*sizeof(DataType)));\n  DataType * gpu_in2_data  = static_cast<DataType*>(sycl_device.allocate(in2.dimensions().TotalSize()*sizeof(DataType)));\n  DataType * gpu_out_data =  static_cast<DataType*>(sycl_device.allocate(out.dimensions().TotalSize()*sizeof(DataType)));\n\n  in1 = in1.random() + in1.constant(static_cast<DataType>(10.0f));\n  in2 = in2.random() + in2.constant(static_cast<DataType>(10.0f));\n\n  // creating TensorMap from tensor\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType>> gpu_in1(gpu_in1_data, tensorRange);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType>> gpu_in2(gpu_in2_data, tensorRange);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType>> gpu_out(gpu_out_data, tensorRange);\n  sycl_device.memcpyHostToDevice(gpu_in1_data, in1.data(),(in1.dimensions().TotalSize())*sizeof(DataType));\n  sycl_device.memcpyHostToDevice(gpu_in2_data, in2.data(),(in2.dimensions().TotalSize())*sizeof(DataType));\n  /// c=(a+b)*b\n  gpu_out.device(sycl_device) =(gpu_in1 + gpu_in2).eval() * gpu_in2;\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data,(out.dimensions().TotalSize())*sizeof(DataType));\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        VERIFY_IS_APPROX(out(i, j, k),\n                         (in1(i, j, k) + in2(i, j, k)) * in2(i, j, k));\n      }\n    }\n  }\n  printf(\"(a+b)*b Test Passed\\n\");\n  sycl_device.deallocate(gpu_in1_data);\n  sycl_device.deallocate(gpu_in2_data);\n  sycl_device.deallocate(gpu_out_data);\n\n}\n\ntemplate <typename DataType, typename Dev_selector> void tensorForced_evalperDevice(Dev_selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_forced_eval_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_forced_eval_sycl<DataType, ColMajor, int64_t>(sycl_device);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_forced_eval_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(tensorForced_evalperDevice<float>(device));\n    CALL_SUBTEST(tensorForced_evalperDevice<half>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_generator.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nstruct Generator1D {\n  Generator1D() { }\n\n  float operator()(const array<Eigen::DenseIndex, 1>& coordinates) const {\n    return coordinates[0];\n  }\n};\n\ntemplate <int DataLayout>\nstatic void test_1D()\n{\n  Tensor<float, 1> vec(6);\n  Tensor<float, 1> result = vec.generate(Generator1D());\n\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_EQUAL(result(i), i);\n  }\n}\n\n\nstruct Generator2D {\n  Generator2D() { }\n\n  float operator()(const array<Eigen::DenseIndex, 2>& coordinates) const {\n    return 3 * coordinates[0] + 11 * coordinates[1];\n  }\n};\n\ntemplate <int DataLayout>\nstatic void test_2D()\n{\n  Tensor<float, 2> matrix(512, 512);\n  Tensor<float, 2> result = matrix.generate(Generator2D());\n\n  for (int i = 0; i < 512; ++i) {\n    for (int j = 0; j < 512; ++j) {\n      VERIFY_IS_EQUAL(result(i, j), 3*i + 11*j);\n    }\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_gaussian()\n{\n  int rows = 32;\n  int cols = 48;\n  array<float, 2> means;\n  means[0] = rows / 2.0f;\n  means[1] = cols / 2.0f;\n  array<float, 2> std_devs;\n  std_devs[0] = 3.14f;\n  std_devs[1] = 2.7f;\n  internal::GaussianGenerator<float, Eigen::DenseIndex, 2> gaussian_gen(means, std_devs);\n\n  Tensor<float, 2> matrix(rows, cols);\n  Tensor<float, 2> result = matrix.generate(gaussian_gen);\n\n  for (int i = 0; i < rows; ++i) {\n    for (int j = 0; j < cols; ++j) {\n      float g_rows = powf(rows/2.0f - i, 2) / (3.14f * 3.14f) * 0.5f;\n      float g_cols = powf(cols/2.0f - j, 2) / (2.7f * 2.7f) * 0.5f;\n      float gaussian = expf(-g_rows - g_cols);\n      VERIFY_IS_EQUAL(result(i, j), gaussian);\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_generator)\n{\n  CALL_SUBTEST(test_1D<ColMajor>());\n  CALL_SUBTEST(test_1D<RowMajor>());\n  CALL_SUBTEST(test_2D<ColMajor>());\n  CALL_SUBTEST(test_2D<RowMajor>());\n  CALL_SUBTEST(test_gaussian<ColMajor>());\n  CALL_SUBTEST(test_gaussian<RowMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_generator_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\nstatic const float error_threshold =1e-8f;\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nstruct Generator1D {\n  Generator1D() { }\n\n  float operator()(const array<Eigen::DenseIndex, 1>& coordinates) const {\n    return coordinates[0];\n  }\n};\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_1D_sycl(const Eigen::SyclDevice& sycl_device)\n{\n\n  IndexType sizeDim1 = 6;\n  array<IndexType, 1> tensorRange = {{sizeDim1}};\n  Tensor<DataType, 1, DataLayout,IndexType> vec(tensorRange);\n  Tensor<DataType, 1, DataLayout,IndexType> result(tensorRange);\n\n  const size_t tensorBuffSize =vec.size()*sizeof(DataType);\n  DataType* gpu_data_vec  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  DataType* gpu_data_result  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n\n  TensorMap<Tensor<DataType, 1, DataLayout,IndexType>> gpu_vec(gpu_data_vec, tensorRange);\n  TensorMap<Tensor<DataType, 1, DataLayout,IndexType>> gpu_result(gpu_data_result, tensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_vec, vec.data(), tensorBuffSize);\n  gpu_result.device(sycl_device)=gpu_vec.generate(Generator1D());\n  sycl_device.memcpyDeviceToHost(result.data(), gpu_data_result, tensorBuffSize);\n\n  for (IndexType i = 0; i < 6; ++i) {\n    VERIFY_IS_EQUAL(result(i), i);\n  }\n}\n\n\nstruct Generator2D {\n  Generator2D() { }\n\n  float operator()(const array<Eigen::DenseIndex, 2>& coordinates) const {\n    return 3 * coordinates[0] + 11 * coordinates[1];\n  }\n};\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_2D_sycl(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType sizeDim1 = 5;\n  IndexType sizeDim2 = 7;\n  array<IndexType, 2> tensorRange = {{sizeDim1, sizeDim2}};\n  Tensor<DataType, 2, DataLayout,IndexType> matrix(tensorRange);\n  Tensor<DataType, 2, DataLayout,IndexType> result(tensorRange);\n\n  const size_t tensorBuffSize =matrix.size()*sizeof(DataType);\n  DataType* gpu_data_matrix  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  DataType* gpu_data_result  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n\n  TensorMap<Tensor<DataType, 2, DataLayout,IndexType>> gpu_matrix(gpu_data_matrix, tensorRange);\n  TensorMap<Tensor<DataType, 2, DataLayout,IndexType>> gpu_result(gpu_data_result, tensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_matrix, matrix.data(), tensorBuffSize);\n  gpu_result.device(sycl_device)=gpu_matrix.generate(Generator2D());\n  sycl_device.memcpyDeviceToHost(result.data(), gpu_data_result, tensorBuffSize);\n\n  for (IndexType i = 0; i < 5; ++i) {\n    for (IndexType j = 0; j < 5; ++j) {\n      VERIFY_IS_EQUAL(result(i, j), 3*i + 11*j);\n    }\n  }\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_gaussian_sycl(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType rows = 32;\n  IndexType cols = 48;\n  array<DataType, 2> means;\n  means[0] = rows / 2.0f;\n  means[1] = cols / 2.0f;\n  array<DataType, 2> std_devs;\n  std_devs[0] = 3.14f;\n  std_devs[1] = 2.7f;\n  internal::GaussianGenerator<DataType, Eigen::DenseIndex, 2> gaussian_gen(means, std_devs);\n\n  array<IndexType, 2> tensorRange = {{rows, cols}};\n  Tensor<DataType, 2, DataLayout,IndexType> matrix(tensorRange);\n  Tensor<DataType, 2, DataLayout,IndexType> result(tensorRange);\n\n  const size_t tensorBuffSize =matrix.size()*sizeof(DataType);\n  DataType* gpu_data_matrix  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  DataType* gpu_data_result  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n\n  TensorMap<Tensor<DataType, 2, DataLayout,IndexType>> gpu_matrix(gpu_data_matrix, tensorRange);\n  TensorMap<Tensor<DataType, 2, DataLayout,IndexType>> gpu_result(gpu_data_result, tensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_matrix, matrix.data(), tensorBuffSize);\n  gpu_result.device(sycl_device)=gpu_matrix.generate(gaussian_gen);\n  sycl_device.memcpyDeviceToHost(result.data(), gpu_data_result, tensorBuffSize);\n\n  for (IndexType i = 0; i < rows; ++i) {\n    for (IndexType j = 0; j < cols; ++j) {\n      DataType g_rows = powf(rows/2.0f - i, 2) / (3.14f * 3.14f) * 0.5f;\n      DataType g_cols = powf(cols/2.0f - j, 2) / (2.7f * 2.7f) * 0.5f;\n      DataType gaussian = expf(-g_rows - g_cols);\n      Eigen::internal::isApprox(result(i, j), gaussian, error_threshold);\n    }\n  }\n}\n\ntemplate<typename DataType, typename dev_Selector> void sycl_generator_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_1D_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_1D_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_2D_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_2D_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_gaussian_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_gaussian_sycl<DataType, ColMajor, int64_t>(sycl_device);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_generator_sycl)\n{\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_generator_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_gpu.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\n#include <unsupported/Eigen/CXX11/src/Tensor/TensorGpuHipCudaDefines.h>\n\n#define EIGEN_GPU_TEST_C99_MATH  EIGEN_HAS_CXX11\n\nusing Eigen::Tensor;\n\nvoid test_gpu_nullary() {\n  Tensor<float, 1, 0, int> in1(2);\n  Tensor<float, 1, 0, int> in2(2);\n  in1.setRandom();\n  in2.setRandom();\n\n  std::size_t tensor_bytes = in1.size() * sizeof(float);\n\n  float* d_in1;\n  float* d_in2;\n  gpuMalloc((void**)(&d_in1), tensor_bytes);\n  gpuMalloc((void**)(&d_in2), tensor_bytes);\n  gpuMemcpy(d_in1, in1.data(), tensor_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_in2, in2.data(), tensor_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 1, 0, int>, Eigen::Aligned> gpu_in1(\n      d_in1, 2);\n  Eigen::TensorMap<Eigen::Tensor<float, 1, 0, int>, Eigen::Aligned> gpu_in2(\n      d_in2, 2);\n\n  gpu_in1.device(gpu_device) = gpu_in1.constant(3.14f);\n  gpu_in2.device(gpu_device) = gpu_in2.random();\n\n  Tensor<float, 1, 0, int> new1(2);\n  Tensor<float, 1, 0, int> new2(2);\n\n  assert(gpuMemcpyAsync(new1.data(), d_in1, tensor_bytes, gpuMemcpyDeviceToHost,\n                         gpu_device.stream()) == gpuSuccess);\n  assert(gpuMemcpyAsync(new2.data(), d_in2, tensor_bytes, gpuMemcpyDeviceToHost,\n                         gpu_device.stream()) == gpuSuccess);\n\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 2; ++i) {\n    VERIFY_IS_APPROX(new1(i), 3.14f);\n    VERIFY_IS_NOT_EQUAL(new2(i), in2(i));\n  }\n\n  gpuFree(d_in1);\n  gpuFree(d_in2);\n}\n\nvoid test_gpu_elementwise_small() {\n  Tensor<float, 1> in1(Eigen::array<Eigen::DenseIndex, 1>(2));\n  Tensor<float, 1> in2(Eigen::array<Eigen::DenseIndex, 1>(2));\n  Tensor<float, 1> out(Eigen::array<Eigen::DenseIndex, 1>(2));\n  in1.setRandom();\n  in2.setRandom();\n\n  std::size_t in1_bytes = in1.size() * sizeof(float);\n  std::size_t in2_bytes = in2.size() * sizeof(float);\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_in1;\n  float* d_in2;\n  float* d_out;\n  gpuMalloc((void**)(&d_in1), in1_bytes);\n  gpuMalloc((void**)(&d_in2), in2_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  gpuMemcpy(d_in1, in1.data(), in1_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_in2, in2.data(), in2_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_in1(\n      d_in1, Eigen::array<Eigen::DenseIndex, 1>(2));\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_in2(\n      d_in2, Eigen::array<Eigen::DenseIndex, 1>(2));\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_out(\n      d_out, Eigen::array<Eigen::DenseIndex, 1>(2));\n\n  gpu_out.device(gpu_device) = gpu_in1 + gpu_in2;\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost,\n                         gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 2; ++i) {\n    VERIFY_IS_APPROX(\n        out(Eigen::array<Eigen::DenseIndex, 1>(i)),\n        in1(Eigen::array<Eigen::DenseIndex, 1>(i)) + in2(Eigen::array<Eigen::DenseIndex, 1>(i)));\n  }\n\n  gpuFree(d_in1);\n  gpuFree(d_in2);\n  gpuFree(d_out);\n}\n\nvoid test_gpu_elementwise()\n{\n  Tensor<float, 3> in1(Eigen::array<Eigen::DenseIndex, 3>(72,53,97));\n  Tensor<float, 3> in2(Eigen::array<Eigen::DenseIndex, 3>(72,53,97));\n  Tensor<float, 3> in3(Eigen::array<Eigen::DenseIndex, 3>(72,53,97));\n  Tensor<float, 3> out(Eigen::array<Eigen::DenseIndex, 3>(72,53,97));\n  in1.setRandom();\n  in2.setRandom();\n  in3.setRandom();\n\n  std::size_t in1_bytes = in1.size() * sizeof(float);\n  std::size_t in2_bytes = in2.size() * sizeof(float);\n  std::size_t in3_bytes = in3.size() * sizeof(float);\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_in1;\n  float* d_in2;\n  float* d_in3;\n  float* d_out;\n  gpuMalloc((void**)(&d_in1), in1_bytes);\n  gpuMalloc((void**)(&d_in2), in2_bytes);\n  gpuMalloc((void**)(&d_in3), in3_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  gpuMemcpy(d_in1, in1.data(), in1_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_in2, in2.data(), in2_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_in3, in3.data(), in3_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 3> > gpu_in1(d_in1, Eigen::array<Eigen::DenseIndex, 3>(72,53,97));\n  Eigen::TensorMap<Eigen::Tensor<float, 3> > gpu_in2(d_in2, Eigen::array<Eigen::DenseIndex, 3>(72,53,97));\n  Eigen::TensorMap<Eigen::Tensor<float, 3> > gpu_in3(d_in3, Eigen::array<Eigen::DenseIndex, 3>(72,53,97));\n  Eigen::TensorMap<Eigen::Tensor<float, 3> > gpu_out(d_out, Eigen::array<Eigen::DenseIndex, 3>(72,53,97));\n\n  gpu_out.device(gpu_device) = gpu_in1 + gpu_in2 * gpu_in3;\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 72; ++i) {\n    for (int j = 0; j < 53; ++j) {\n      for (int k = 0; k < 97; ++k) {\n        VERIFY_IS_APPROX(out(Eigen::array<Eigen::DenseIndex, 3>(i,j,k)), in1(Eigen::array<Eigen::DenseIndex, 3>(i,j,k)) + in2(Eigen::array<Eigen::DenseIndex, 3>(i,j,k)) * in3(Eigen::array<Eigen::DenseIndex, 3>(i,j,k)));\n      }\n    }\n  }\n\n  gpuFree(d_in1);\n  gpuFree(d_in2);\n  gpuFree(d_in3);\n  gpuFree(d_out);\n}\n\nvoid test_gpu_props() {\n  Tensor<float, 1> in1(200);\n  Tensor<bool, 1> out(200);\n  in1.setRandom();\n\n  std::size_t in1_bytes = in1.size() * sizeof(float);\n  std::size_t out_bytes = out.size() * sizeof(bool);\n\n  float* d_in1;\n  bool* d_out;\n  gpuMalloc((void**)(&d_in1), in1_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  gpuMemcpy(d_in1, in1.data(), in1_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_in1(\n      d_in1, 200);\n  Eigen::TensorMap<Eigen::Tensor<bool, 1>, Eigen::Aligned> gpu_out(\n      d_out, 200);\n\n  gpu_out.device(gpu_device) = (gpu_in1.isnan)();\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost,\n                         gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 200; ++i) {\n    VERIFY_IS_EQUAL(out(i), (std::isnan)(in1(i)));\n  }\n\n  gpuFree(d_in1);\n  gpuFree(d_out);\n}\n\nvoid test_gpu_reduction()\n{\n  Tensor<float, 4> in1(72,53,97,113);\n  Tensor<float, 2> out(72,97);\n  in1.setRandom();\n\n  std::size_t in1_bytes = in1.size() * sizeof(float);\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_in1;\n  float* d_out;\n  gpuMalloc((void**)(&d_in1), in1_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  gpuMemcpy(d_in1, in1.data(), in1_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 4> > gpu_in1(d_in1, 72,53,97,113);\n  Eigen::TensorMap<Eigen::Tensor<float, 2> > gpu_out(d_out, 72,97);\n\n  array<Eigen::DenseIndex, 2> reduction_axis;\n  reduction_axis[0] = 1;\n  reduction_axis[1] = 3;\n\n  gpu_out.device(gpu_device) = gpu_in1.maximum(reduction_axis);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 72; ++i) {\n    for (int j = 0; j < 97; ++j) {\n      float expected = 0;\n      for (int k = 0; k < 53; ++k) {\n        for (int l = 0; l < 113; ++l) {\n          expected =\n              std::max<float>(expected, in1(i, k, j, l));\n        }\n      }\n      VERIFY_IS_APPROX(out(i,j), expected);\n    }\n  }\n\n  gpuFree(d_in1);\n  gpuFree(d_out);\n}\n\ntemplate<int DataLayout>\nvoid test_gpu_contraction()\n{\n  // with these dimensions, the output has 300 * 140 elements, which is\n  // more than 30 * 1024, which is the number of threads in blocks on\n  // a 15 SM GK110 GPU\n  Tensor<float, 4, DataLayout> t_left(6, 50, 3, 31);\n  Tensor<float, 5, DataLayout> t_right(Eigen::array<Eigen::DenseIndex, 5>(3, 31, 7, 20, 1));\n  Tensor<float, 5, DataLayout> t_result(Eigen::array<Eigen::DenseIndex, 5>(6, 50, 7, 20, 1));\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  std::size_t t_left_bytes = t_left.size()  * sizeof(float);\n  std::size_t t_right_bytes = t_right.size() * sizeof(float);\n  std::size_t t_result_bytes = t_result.size() * sizeof(float);\n\n  float* d_t_left;\n  float* d_t_right;\n  float* d_t_result;\n\n  gpuMalloc((void**)(&d_t_left), t_left_bytes);\n  gpuMalloc((void**)(&d_t_right), t_right_bytes);\n  gpuMalloc((void**)(&d_t_result), t_result_bytes);\n\n  gpuMemcpy(d_t_left, t_left.data(), t_left_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_t_right, t_right.data(), t_right_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 4, DataLayout> > gpu_t_left(d_t_left, 6, 50, 3, 31);\n  Eigen::TensorMap<Eigen::Tensor<float, 5, DataLayout> > gpu_t_right(d_t_right, 3, 31, 7, 20, 1);\n  Eigen::TensorMap<Eigen::Tensor<float, 5, DataLayout> > gpu_t_result(d_t_result, 6, 50, 7, 20, 1);\n\n  typedef Eigen::Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> > MapXf;\n  MapXf m_left(t_left.data(), 300, 93);\n  MapXf m_right(t_right.data(), 93, 140);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result(300, 140);\n\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n  Eigen::array<DimPair, 2> dims;\n  dims[0] = DimPair(2, 0);\n  dims[1] = DimPair(3, 1);\n\n  m_result = m_left * m_right;\n  gpu_t_result.device(gpu_device) = gpu_t_left.contract(gpu_t_right, dims);\n\n  gpuMemcpy(t_result.data(), d_t_result, t_result_bytes, gpuMemcpyDeviceToHost);\n\n  for (DenseIndex i = 0; i < t_result.size(); i++) {\n    if (fabs(t_result.data()[i] - m_result.data()[i]) >= 1e-4f) {\n      std::cout << \"mismatch detected at index \" << i << \": \" << t_result.data()[i] << \" vs \" <<  m_result.data()[i] << std::endl;\n      assert(false);\n    }\n  }\n\n  gpuFree(d_t_left);\n  gpuFree(d_t_right);\n  gpuFree(d_t_result);\n}\n\ntemplate<int DataLayout>\nvoid test_gpu_convolution_1d()\n{\n  Tensor<float, 4, DataLayout> input(74,37,11,137);\n  Tensor<float, 1, DataLayout> kernel(4);\n  Tensor<float, 4, DataLayout> out(74,34,11,137);\n  input = input.constant(10.0f) + input.random();\n  kernel = kernel.constant(7.0f) + kernel.random();\n\n  std::size_t input_bytes = input.size() * sizeof(float);\n  std::size_t kernel_bytes = kernel.size() * sizeof(float);\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_input;\n  float* d_kernel;\n  float* d_out;\n  gpuMalloc((void**)(&d_input), input_bytes);\n  gpuMalloc((void**)(&d_kernel), kernel_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  gpuMemcpy(d_input, input.data(), input_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_kernel, kernel.data(), kernel_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 4, DataLayout> > gpu_input(d_input, 74,37,11,137);\n  Eigen::TensorMap<Eigen::Tensor<float, 1, DataLayout> > gpu_kernel(d_kernel, 4);\n  Eigen::TensorMap<Eigen::Tensor<float, 4, DataLayout> > gpu_out(d_out, 74,34,11,137);\n\n  Eigen::array<Eigen::DenseIndex, 1> dims(1);\n  gpu_out.device(gpu_device) = gpu_input.convolve(gpu_kernel, dims);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 74; ++i) {\n    for (int j = 0; j < 34; ++j) {\n      for (int k = 0; k < 11; ++k) {\n        for (int l = 0; l < 137; ++l) {\n          const float result = out(i,j,k,l);\n          const float expected = input(i,j+0,k,l) * kernel(0) + input(i,j+1,k,l) * kernel(1) +\n                                 input(i,j+2,k,l) * kernel(2) + input(i,j+3,k,l) * kernel(3);\n          VERIFY_IS_APPROX(result, expected);\n        }\n      }\n    }\n  }\n\n  gpuFree(d_input);\n  gpuFree(d_kernel);\n  gpuFree(d_out);\n}\n\nvoid test_gpu_convolution_inner_dim_col_major_1d()\n{\n  Tensor<float, 4, ColMajor> input(74,9,11,7);\n  Tensor<float, 1, ColMajor> kernel(4);\n  Tensor<float, 4, ColMajor> out(71,9,11,7);\n  input = input.constant(10.0f) + input.random();\n  kernel = kernel.constant(7.0f) + kernel.random();\n\n  std::size_t input_bytes = input.size() * sizeof(float);\n  std::size_t kernel_bytes = kernel.size() * sizeof(float);\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_input;\n  float* d_kernel;\n  float* d_out;\n  gpuMalloc((void**)(&d_input), input_bytes);\n  gpuMalloc((void**)(&d_kernel), kernel_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  gpuMemcpy(d_input, input.data(), input_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_kernel, kernel.data(), kernel_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 4, ColMajor> > gpu_input(d_input,74,9,11,7);\n  Eigen::TensorMap<Eigen::Tensor<float, 1, ColMajor> > gpu_kernel(d_kernel,4);\n  Eigen::TensorMap<Eigen::Tensor<float, 4, ColMajor> > gpu_out(d_out,71,9,11,7);\n\n  Eigen::array<Eigen::DenseIndex, 1> dims(0);\n  gpu_out.device(gpu_device) = gpu_input.convolve(gpu_kernel, dims);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 71; ++i) {\n    for (int j = 0; j < 9; ++j) {\n      for (int k = 0; k < 11; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          const float result = out(i,j,k,l);\n          const float expected = input(i+0,j,k,l) * kernel(0) + input(i+1,j,k,l) * kernel(1) +\n                                 input(i+2,j,k,l) * kernel(2) + input(i+3,j,k,l) * kernel(3);\n          VERIFY_IS_APPROX(result, expected);\n        }\n      }\n    }\n  }\n\n  gpuFree(d_input);\n  gpuFree(d_kernel);\n  gpuFree(d_out);\n}\n\nvoid test_gpu_convolution_inner_dim_row_major_1d()\n{\n  Tensor<float, 4, RowMajor> input(7,9,11,74);\n  Tensor<float, 1, RowMajor> kernel(4);\n  Tensor<float, 4, RowMajor> out(7,9,11,71);\n  input = input.constant(10.0f) + input.random();\n  kernel = kernel.constant(7.0f) + kernel.random();\n\n  std::size_t input_bytes = input.size() * sizeof(float);\n  std::size_t kernel_bytes = kernel.size() * sizeof(float);\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_input;\n  float* d_kernel;\n  float* d_out;\n  gpuMalloc((void**)(&d_input), input_bytes);\n  gpuMalloc((void**)(&d_kernel), kernel_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  gpuMemcpy(d_input, input.data(), input_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_kernel, kernel.data(), kernel_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 4, RowMajor> > gpu_input(d_input, 7,9,11,74);\n  Eigen::TensorMap<Eigen::Tensor<float, 1, RowMajor> > gpu_kernel(d_kernel, 4);\n  Eigen::TensorMap<Eigen::Tensor<float, 4, RowMajor> > gpu_out(d_out, 7,9,11,71);\n\n  Eigen::array<Eigen::DenseIndex, 1> dims(3);\n  gpu_out.device(gpu_device) = gpu_input.convolve(gpu_kernel, dims);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 7; ++i) {\n    for (int j = 0; j < 9; ++j) {\n      for (int k = 0; k < 11; ++k) {\n        for (int l = 0; l < 71; ++l) {\n          const float result = out(i,j,k,l);\n          const float expected = input(i,j,k,l+0) * kernel(0) + input(i,j,k,l+1) * kernel(1) +\n                                 input(i,j,k,l+2) * kernel(2) + input(i,j,k,l+3) * kernel(3);\n          VERIFY_IS_APPROX(result, expected);\n        }\n      }\n    }\n  }\n\n  gpuFree(d_input);\n  gpuFree(d_kernel);\n  gpuFree(d_out);\n}\n\ntemplate<int DataLayout>\nvoid test_gpu_convolution_2d()\n{\n  Tensor<float, 4, DataLayout> input(74,37,11,137);\n  Tensor<float, 2, DataLayout> kernel(3,4);\n  Tensor<float, 4, DataLayout> out(74,35,8,137);\n  input = input.constant(10.0f) + input.random();\n  kernel = kernel.constant(7.0f) + kernel.random();\n\n  std::size_t input_bytes = input.size() * sizeof(float);\n  std::size_t kernel_bytes = kernel.size() * sizeof(float);\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_input;\n  float* d_kernel;\n  float* d_out;\n  gpuMalloc((void**)(&d_input), input_bytes);\n  gpuMalloc((void**)(&d_kernel), kernel_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  gpuMemcpy(d_input, input.data(), input_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_kernel, kernel.data(), kernel_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 4, DataLayout> > gpu_input(d_input,74,37,11,137);\n  Eigen::TensorMap<Eigen::Tensor<float, 2, DataLayout> > gpu_kernel(d_kernel,3,4);\n  Eigen::TensorMap<Eigen::Tensor<float, 4, DataLayout> > gpu_out(d_out,74,35,8,137);\n\n  Eigen::array<Eigen::DenseIndex, 2> dims(1,2);\n  gpu_out.device(gpu_device) = gpu_input.convolve(gpu_kernel, dims);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 74; ++i) {\n    for (int j = 0; j < 35; ++j) {\n      for (int k = 0; k < 8; ++k) {\n        for (int l = 0; l < 137; ++l) {\n          const float result = out(i,j,k,l);\n          const float expected = input(i,j+0,k+0,l) * kernel(0,0) +\n                                 input(i,j+1,k+0,l) * kernel(1,0) +\n                                 input(i,j+2,k+0,l) * kernel(2,0) +\n                                 input(i,j+0,k+1,l) * kernel(0,1) +\n                                 input(i,j+1,k+1,l) * kernel(1,1) +\n                                 input(i,j+2,k+1,l) * kernel(2,1) +\n                                 input(i,j+0,k+2,l) * kernel(0,2) +\n                                 input(i,j+1,k+2,l) * kernel(1,2) +\n                                 input(i,j+2,k+2,l) * kernel(2,2) +\n                                 input(i,j+0,k+3,l) * kernel(0,3) +\n                                 input(i,j+1,k+3,l) * kernel(1,3) +\n                                 input(i,j+2,k+3,l) * kernel(2,3);\n          VERIFY_IS_APPROX(result, expected);\n        }\n      }\n    }\n  }\n\n  gpuFree(d_input);\n  gpuFree(d_kernel);\n  gpuFree(d_out);\n}\n\ntemplate<int DataLayout>\nvoid test_gpu_convolution_3d()\n{\n  Tensor<float, 5, DataLayout> input(Eigen::array<Eigen::DenseIndex, 5>(74,37,11,137,17));\n  Tensor<float, 3, DataLayout> kernel(3,4,2);\n  Tensor<float, 5, DataLayout> out(Eigen::array<Eigen::DenseIndex, 5>(74,35,8,136,17));\n  input = input.constant(10.0f) + input.random();\n  kernel = kernel.constant(7.0f) + kernel.random();\n\n  std::size_t input_bytes = input.size() * sizeof(float);\n  std::size_t kernel_bytes = kernel.size() * sizeof(float);\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_input;\n  float* d_kernel;\n  float* d_out;\n  gpuMalloc((void**)(&d_input), input_bytes);\n  gpuMalloc((void**)(&d_kernel), kernel_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  gpuMemcpy(d_input, input.data(), input_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_kernel, kernel.data(), kernel_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;    \n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 5, DataLayout> > gpu_input(d_input,74,37,11,137,17);\n  Eigen::TensorMap<Eigen::Tensor<float, 3, DataLayout> > gpu_kernel(d_kernel,3,4,2);\n  Eigen::TensorMap<Eigen::Tensor<float, 5, DataLayout> > gpu_out(d_out,74,35,8,136,17);\n\n  Eigen::array<Eigen::DenseIndex, 3> dims(1,2,3);\n  gpu_out.device(gpu_device) = gpu_input.convolve(gpu_kernel, dims);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 74; ++i) {\n    for (int j = 0; j < 35; ++j) {\n      for (int k = 0; k < 8; ++k) {\n        for (int l = 0; l < 136; ++l) {\n          for (int m = 0; m < 17; ++m) {\n            const float result = out(i,j,k,l,m);\n            const float expected = input(i,j+0,k+0,l+0,m) * kernel(0,0,0) +\n                                   input(i,j+1,k+0,l+0,m) * kernel(1,0,0) +\n                                   input(i,j+2,k+0,l+0,m) * kernel(2,0,0) +\n                                   input(i,j+0,k+1,l+0,m) * kernel(0,1,0) +\n                                   input(i,j+1,k+1,l+0,m) * kernel(1,1,0) +\n                                   input(i,j+2,k+1,l+0,m) * kernel(2,1,0) +\n                                   input(i,j+0,k+2,l+0,m) * kernel(0,2,0) +\n                                   input(i,j+1,k+2,l+0,m) * kernel(1,2,0) +\n                                   input(i,j+2,k+2,l+0,m) * kernel(2,2,0) +\n                                   input(i,j+0,k+3,l+0,m) * kernel(0,3,0) +\n                                   input(i,j+1,k+3,l+0,m) * kernel(1,3,0) +\n                                   input(i,j+2,k+3,l+0,m) * kernel(2,3,0) +\n                                   input(i,j+0,k+0,l+1,m) * kernel(0,0,1) +\n                                   input(i,j+1,k+0,l+1,m) * kernel(1,0,1) +\n                                   input(i,j+2,k+0,l+1,m) * kernel(2,0,1) +\n                                   input(i,j+0,k+1,l+1,m) * kernel(0,1,1) +\n                                   input(i,j+1,k+1,l+1,m) * kernel(1,1,1) +\n                                   input(i,j+2,k+1,l+1,m) * kernel(2,1,1) +\n                                   input(i,j+0,k+2,l+1,m) * kernel(0,2,1) +\n                                   input(i,j+1,k+2,l+1,m) * kernel(1,2,1) +\n                                   input(i,j+2,k+2,l+1,m) * kernel(2,2,1) +\n                                   input(i,j+0,k+3,l+1,m) * kernel(0,3,1) +\n                                   input(i,j+1,k+3,l+1,m) * kernel(1,3,1) +\n                                   input(i,j+2,k+3,l+1,m) * kernel(2,3,1);\n            VERIFY_IS_APPROX(result, expected);\n          }\n        }\n      }\n    }\n  }\n\n  gpuFree(d_input);\n  gpuFree(d_kernel);\n  gpuFree(d_out);\n}\n\n\n#if EIGEN_GPU_TEST_C99_MATH\ntemplate <typename Scalar>\nvoid test_gpu_lgamma(const Scalar stddev)\n{\n  Tensor<Scalar, 2> in(72,97);\n  in.setRandom();\n  in *= in.constant(stddev);\n  Tensor<Scalar, 2> out(72,97);\n  out.setZero();\n\n  std::size_t bytes = in.size() * sizeof(Scalar);\n\n  Scalar* d_in;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_in), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_in, in.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_in(d_in, 72, 97);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_out(d_out, 72, 97);\n\n  gpu_out.device(gpu_device) = gpu_in.lgamma();\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 72; ++i) {\n    for (int j = 0; j < 97; ++j) {\n      VERIFY_IS_APPROX(out(i,j), (std::lgamma)(in(i,j)));\n    }\n  }\n\n  gpuFree(d_in);\n  gpuFree(d_out);\n}\n#endif\n\ntemplate <typename Scalar>\nvoid test_gpu_digamma()\n{\n  Tensor<Scalar, 1> in(7);\n  Tensor<Scalar, 1> out(7);\n  Tensor<Scalar, 1> expected_out(7);\n  out.setZero();\n\n  in(0) = Scalar(1);\n  in(1) = Scalar(1.5);\n  in(2) = Scalar(4);\n  in(3) = Scalar(-10.5);\n  in(4) = Scalar(10000.5);\n  in(5) = Scalar(0);\n  in(6) = Scalar(-1);\n\n  expected_out(0) = Scalar(-0.5772156649015329);\n  expected_out(1) = Scalar(0.03648997397857645);\n  expected_out(2) = Scalar(1.2561176684318);\n  expected_out(3) = Scalar(2.398239129535781);\n  expected_out(4) = Scalar(9.210340372392849);\n  expected_out(5) = std::numeric_limits<Scalar>::infinity();\n  expected_out(6) = std::numeric_limits<Scalar>::infinity();\n\n  std::size_t bytes = in.size() * sizeof(Scalar);\n\n  Scalar* d_in;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_in), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_in, in.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in(d_in, 7);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_out(d_out, 7);\n\n  gpu_out.device(gpu_device) = gpu_in.digamma();\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 5; ++i) {\n    VERIFY_IS_APPROX(out(i), expected_out(i));\n  }\n  for (int i = 5; i < 7; ++i) {\n    VERIFY_IS_EQUAL(out(i), expected_out(i));\n  }\n\n  gpuFree(d_in);\n  gpuFree(d_out);\n}\n\ntemplate <typename Scalar>\nvoid test_gpu_zeta()\n{\n  Tensor<Scalar, 1> in_x(6);\n  Tensor<Scalar, 1> in_q(6);\n  Tensor<Scalar, 1> out(6);\n  Tensor<Scalar, 1> expected_out(6);\n  out.setZero();\n\n  in_x(0) = Scalar(1);\n  in_x(1) = Scalar(1.5);\n  in_x(2) = Scalar(4);\n  in_x(3) = Scalar(-10.5);\n  in_x(4) = Scalar(10000.5);\n  in_x(5) = Scalar(3);\n  \n  in_q(0) = Scalar(1.2345);\n  in_q(1) = Scalar(2);\n  in_q(2) = Scalar(1.5);\n  in_q(3) = Scalar(3);\n  in_q(4) = Scalar(1.0001);\n  in_q(5) = Scalar(-2.5);\n\n  expected_out(0) = std::numeric_limits<Scalar>::infinity();\n  expected_out(1) = Scalar(1.61237534869);\n  expected_out(2) = Scalar(0.234848505667);\n  expected_out(3) = Scalar(1.03086757337e-5);\n  expected_out(4) = Scalar(0.367879440865);\n  expected_out(5) = Scalar(0.054102025820864097);\n\n  std::size_t bytes = in_x.size() * sizeof(Scalar);\n\n  Scalar* d_in_x;\n  Scalar* d_in_q;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_in_x), bytes);\n  gpuMalloc((void**)(&d_in_q), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_in_x, in_x.data(), bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_in_q, in_q.data(), bytes, gpuMemcpyHostToDevice);\n  \n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in_x(d_in_x, 6);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in_q(d_in_q, 6);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_out(d_out, 6);\n\n  gpu_out.device(gpu_device) = gpu_in_x.zeta(gpu_in_q);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  VERIFY_IS_EQUAL(out(0), expected_out(0));\n  VERIFY((std::isnan)(out(3)));\n\n  for (int i = 1; i < 6; ++i) {\n    if (i != 3) {\n      VERIFY_IS_APPROX(out(i), expected_out(i));\n    }\n  }\n\n  gpuFree(d_in_x);\n  gpuFree(d_in_q);\n  gpuFree(d_out);\n}\n\ntemplate <typename Scalar>\nvoid test_gpu_polygamma()\n{\n  Tensor<Scalar, 1> in_x(7);\n  Tensor<Scalar, 1> in_n(7);\n  Tensor<Scalar, 1> out(7);\n  Tensor<Scalar, 1> expected_out(7);\n  out.setZero();\n\n  in_n(0) = Scalar(1);\n  in_n(1) = Scalar(1);\n  in_n(2) = Scalar(1);\n  in_n(3) = Scalar(17);\n  in_n(4) = Scalar(31);\n  in_n(5) = Scalar(28);\n  in_n(6) = Scalar(8);\n  \n  in_x(0) = Scalar(2);\n  in_x(1) = Scalar(3);\n  in_x(2) = Scalar(25.5);\n  in_x(3) = Scalar(4.7);\n  in_x(4) = Scalar(11.8);\n  in_x(5) = Scalar(17.7);\n  in_x(6) = Scalar(30.2);\n\n  expected_out(0) = Scalar(0.644934066848);\n  expected_out(1) = Scalar(0.394934066848);\n  expected_out(2) = Scalar(0.0399946696496);\n  expected_out(3) = Scalar(293.334565435);\n  expected_out(4) = Scalar(0.445487887616);\n  expected_out(5) = Scalar(-2.47810300902e-07);\n  expected_out(6) = Scalar(-8.29668781082e-09);\n\n  std::size_t bytes = in_x.size() * sizeof(Scalar);\n\n  Scalar* d_in_x;\n  Scalar* d_in_n;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_in_x), bytes);\n  gpuMalloc((void**)(&d_in_n), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_in_x, in_x.data(), bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_in_n, in_n.data(), bytes, gpuMemcpyHostToDevice);\n  \n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in_x(d_in_x, 7);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in_n(d_in_n, 7);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_out(d_out, 7);\n\n  gpu_out.device(gpu_device) = gpu_in_n.polygamma(gpu_in_x);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 7; ++i) {\n    VERIFY_IS_APPROX(out(i), expected_out(i));\n  }\n\n  gpuFree(d_in_x);\n  gpuFree(d_in_n);\n  gpuFree(d_out);\n}\n\ntemplate <typename Scalar>\nvoid test_gpu_igamma()\n{\n  Tensor<Scalar, 2> a(6, 6);\n  Tensor<Scalar, 2> x(6, 6);\n  Tensor<Scalar, 2> out(6, 6);\n  out.setZero();\n\n  Scalar a_s[] = {Scalar(0), Scalar(1), Scalar(1.5), Scalar(4), Scalar(0.0001), Scalar(1000.5)};\n  Scalar x_s[] = {Scalar(0), Scalar(1), Scalar(1.5), Scalar(4), Scalar(0.0001), Scalar(1000.5)};\n\n  for (int i = 0; i < 6; ++i) {\n    for (int j = 0; j < 6; ++j) {\n      a(i, j) = a_s[i];\n      x(i, j) = x_s[j];\n    }\n  }\n\n  Scalar nan = std::numeric_limits<Scalar>::quiet_NaN();\n  Scalar igamma_s[][6] = {{0.0, nan, nan, nan, nan, nan},\n                          {0.0, 0.6321205588285578, 0.7768698398515702,\n                           0.9816843611112658, 9.999500016666262e-05, 1.0},\n                          {0.0, 0.4275932955291202, 0.608374823728911,\n                           0.9539882943107686, 7.522076445089201e-07, 1.0},\n                          {0.0, 0.01898815687615381, 0.06564245437845008,\n                           0.5665298796332909, 4.166333347221828e-18, 1.0},\n                          {0.0, 0.9999780593618628, 0.9999899967080838,\n                           0.9999996219837988, 0.9991370418689945, 1.0},\n                          {0.0, 0.0, 0.0, 0.0, 0.0, 0.5042041932513908}};\n\n\n\n  std::size_t bytes = a.size() * sizeof(Scalar);\n\n  Scalar* d_a;\n  Scalar* d_x;\n  Scalar* d_out;\n  assert(gpuMalloc((void**)(&d_a), bytes) == gpuSuccess);\n  assert(gpuMalloc((void**)(&d_x), bytes) == gpuSuccess);\n  assert(gpuMalloc((void**)(&d_out), bytes) == gpuSuccess);\n\n  gpuMemcpy(d_a, a.data(), bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_x, x.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_a(d_a, 6, 6);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_x(d_x, 6, 6);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_out(d_out, 6, 6);\n\n  gpu_out.device(gpu_device) = gpu_a.igamma(gpu_x);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 6; ++i) {\n    for (int j = 0; j < 6; ++j) {\n      if ((std::isnan)(igamma_s[i][j])) {\n        VERIFY((std::isnan)(out(i, j)));\n      } else {\n        VERIFY_IS_APPROX(out(i, j), igamma_s[i][j]);\n      }\n    }\n  }\n\n  gpuFree(d_a);\n  gpuFree(d_x);\n  gpuFree(d_out);\n}\n\ntemplate <typename Scalar>\nvoid test_gpu_igammac()\n{\n  Tensor<Scalar, 2> a(6, 6);\n  Tensor<Scalar, 2> x(6, 6);\n  Tensor<Scalar, 2> out(6, 6);\n  out.setZero();\n\n  Scalar a_s[] = {Scalar(0), Scalar(1), Scalar(1.5), Scalar(4), Scalar(0.0001), Scalar(1000.5)};\n  Scalar x_s[] = {Scalar(0), Scalar(1), Scalar(1.5), Scalar(4), Scalar(0.0001), Scalar(1000.5)};\n\n  for (int i = 0; i < 6; ++i) {\n    for (int j = 0; j < 6; ++j) {\n      a(i, j) = a_s[i];\n      x(i, j) = x_s[j];\n    }\n  }\n\n  Scalar nan = std::numeric_limits<Scalar>::quiet_NaN();\n  Scalar igammac_s[][6] = {{nan, nan, nan, nan, nan, nan},\n                           {1.0, 0.36787944117144233, 0.22313016014842982,\n                            0.018315638888734182, 0.9999000049998333, 0.0},\n                           {1.0, 0.5724067044708798, 0.3916251762710878,\n                            0.04601170568923136, 0.9999992477923555, 0.0},\n                           {1.0, 0.9810118431238462, 0.9343575456215499,\n                            0.4334701203667089, 1.0, 0.0},\n                           {1.0, 2.1940638138146658e-05, 1.0003291916285e-05,\n                            3.7801620118431334e-07, 0.0008629581310054535,\n                            0.0},\n                           {1.0, 1.0, 1.0, 1.0, 1.0, 0.49579580674813944}};\n\n  std::size_t bytes = a.size() * sizeof(Scalar);\n\n  Scalar* d_a;\n  Scalar* d_x;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_a), bytes);\n  gpuMalloc((void**)(&d_x), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_a, a.data(), bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_x, x.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_a(d_a, 6, 6);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_x(d_x, 6, 6);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_out(d_out, 6, 6);\n\n  gpu_out.device(gpu_device) = gpu_a.igammac(gpu_x);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 6; ++i) {\n    for (int j = 0; j < 6; ++j) {\n      if ((std::isnan)(igammac_s[i][j])) {\n        VERIFY((std::isnan)(out(i, j)));\n      } else {\n        VERIFY_IS_APPROX(out(i, j), igammac_s[i][j]);\n      }\n    }\n  }\n\n  gpuFree(d_a);\n  gpuFree(d_x);\n  gpuFree(d_out);\n}\n\n#if EIGEN_GPU_TEST_C99_MATH\ntemplate <typename Scalar>\nvoid test_gpu_erf(const Scalar stddev)\n{\n  Tensor<Scalar, 2> in(72,97);\n  in.setRandom();\n  in *= in.constant(stddev);\n  Tensor<Scalar, 2> out(72,97);\n  out.setZero();\n\n  std::size_t bytes = in.size() * sizeof(Scalar);\n\n  Scalar* d_in;\n  Scalar* d_out;\n  assert(gpuMalloc((void**)(&d_in), bytes) == gpuSuccess);\n  assert(gpuMalloc((void**)(&d_out), bytes) == gpuSuccess);\n\n  gpuMemcpy(d_in, in.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_in(d_in, 72, 97);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_out(d_out, 72, 97);\n\n  gpu_out.device(gpu_device) = gpu_in.erf();\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 72; ++i) {\n    for (int j = 0; j < 97; ++j) {\n      VERIFY_IS_APPROX(out(i,j), (std::erf)(in(i,j)));\n    }\n  }\n\n  gpuFree(d_in);\n  gpuFree(d_out);\n}\n\ntemplate <typename Scalar>\nvoid test_gpu_erfc(const Scalar stddev)\n{\n  Tensor<Scalar, 2> in(72,97);\n  in.setRandom();\n  in *= in.constant(stddev);\n  Tensor<Scalar, 2> out(72,97);\n  out.setZero();\n\n  std::size_t bytes = in.size() * sizeof(Scalar);\n\n  Scalar* d_in;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_in), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_in, in.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_in(d_in, 72, 97);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_out(d_out, 72, 97);\n\n  gpu_out.device(gpu_device) = gpu_in.erfc();\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 72; ++i) {\n    for (int j = 0; j < 97; ++j) {\n      VERIFY_IS_APPROX(out(i,j), (std::erfc)(in(i,j)));\n    }\n  }\n\n  gpuFree(d_in);\n  gpuFree(d_out);\n}\n#endif\ntemplate <typename Scalar>\nvoid test_gpu_ndtri()\n{\n  Tensor<Scalar, 1> in_x(8);\n  Tensor<Scalar, 1> out(8);\n  Tensor<Scalar, 1> expected_out(8);\n  out.setZero();\n\n  in_x(0) = Scalar(1);\n  in_x(1) = Scalar(0.);\n  in_x(2) = Scalar(0.5);\n  in_x(3) = Scalar(0.2);\n  in_x(4) = Scalar(0.8);\n  in_x(5) = Scalar(0.9);\n  in_x(6) = Scalar(0.1);\n  in_x(7) = Scalar(0.99);\n  in_x(8) = Scalar(0.01);\n\n  expected_out(0) = std::numeric_limits<Scalar>::infinity();\n  expected_out(1) = -std::numeric_limits<Scalar>::infinity();\n  expected_out(2) = Scalar(0.0);\n  expected_out(3) = Scalar(-0.8416212335729142);\n  expected_out(4) = Scalar(0.8416212335729142);\n  expected_out(5) = Scalar(1.2815515655446004);\n  expected_out(6) = Scalar(-1.2815515655446004);\n  expected_out(7) = Scalar(2.3263478740408408);\n  expected_out(8) = Scalar(-2.3263478740408408);\n\n  std::size_t bytes = in_x.size() * sizeof(Scalar);\n\n  Scalar* d_in_x;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_in_x), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_in_x, in_x.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in_x(d_in_x, 6);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_out(d_out, 6);\n\n  gpu_out.device(gpu_device) = gpu_in_x.ndtri();\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  VERIFY_IS_EQUAL(out(0), expected_out(0));\n  VERIFY((std::isnan)(out(3)));\n\n  for (int i = 1; i < 6; ++i) {\n    if (i != 3) {\n      VERIFY_IS_APPROX(out(i), expected_out(i));\n    }\n  }\n\n  gpuFree(d_in_x);\n  gpuFree(d_out);\n}\n\ntemplate <typename Scalar>\nvoid test_gpu_betainc()\n{\n  Tensor<Scalar, 1> in_x(125);\n  Tensor<Scalar, 1> in_a(125);\n  Tensor<Scalar, 1> in_b(125);\n  Tensor<Scalar, 1> out(125);\n  Tensor<Scalar, 1> expected_out(125);\n  out.setZero();\n\n  Scalar nan = std::numeric_limits<Scalar>::quiet_NaN();\n\n  Array<Scalar, 1, Dynamic> x(125);\n  Array<Scalar, 1, Dynamic> a(125);\n  Array<Scalar, 1, Dynamic> b(125);\n  Array<Scalar, 1, Dynamic> v(125);\n\n  a << 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,\n      0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999,\n      0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999,\n      0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379, 999.999, 999.999,\n      999.999, 999.999, 999.999, 999.999, 999.999, 999.999, 999.999, 999.999,\n      999.999, 999.999, 999.999, 999.999, 999.999, 999.999, 999.999, 999.999,\n      999.999, 999.999, 999.999, 999.999, 999.999, 999.999, 999.999;\n\n  b << 0.0, 0.0, 0.0, 0.0, 0.0, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379, 0.999,\n      0.999, 0.999, 0.999, 0.999, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379, 999.999, 999.999,\n      999.999, 999.999, 999.999, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.999, 0.999, 0.999, 0.999, 0.999, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 999.999, 999.999, 999.999, 999.999, 999.999, 0.0, 0.0,\n      0.0, 0.0, 0.0, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379, 0.999,\n      0.999, 0.999, 0.999, 0.999, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379, 999.999, 999.999,\n      999.999, 999.999, 999.999, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.999, 0.999, 0.999, 0.999, 0.999, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 999.999, 999.999, 999.999, 999.999, 999.999, 0.0, 0.0,\n      0.0, 0.0, 0.0, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379, 0.999,\n      0.999, 0.999, 0.999, 0.999, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379, 999.999, 999.999,\n      999.999, 999.999, 999.999;\n\n  x << -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8,\n      1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5,\n      0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2,\n      0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1,\n      0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1,\n      -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8,\n      1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5,\n      0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2,\n      0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1;\n\n  v << nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan,\n      nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan,\n      nan, nan, 0.47972119876364683, 0.5, 0.5202788012363533, nan, nan,\n      0.9518683957740043, 0.9789663010413743, 0.9931729188073435, nan, nan,\n      0.999995949033062, 0.9999999999993698, 0.9999999999999999, nan, nan,\n      0.9999999999999999, 0.9999999999999999, 0.9999999999999999, nan, nan, nan,\n      nan, nan, nan, nan, 0.006827081192655869, 0.0210336989586256,\n      0.04813160422599567, nan, nan, 0.20014344256217678, 0.5000000000000001,\n      0.7998565574378232, nan, nan, 0.9991401428435834, 0.999999999698403,\n      0.9999999999999999, nan, nan, 0.9999999999999999, 0.9999999999999999,\n      0.9999999999999999, nan, nan, nan, nan, nan, nan, nan,\n      1.0646600232370887e-25, 6.301722877826246e-13, 4.050966937974938e-06, nan,\n      nan, 7.864342668429763e-23, 3.015969667594166e-10, 0.0008598571564165444,\n      nan, nan, 6.031987710123844e-08, 0.5000000000000007, 0.9999999396801229,\n      nan, nan, 0.9999999999999999, 0.9999999999999999, 0.9999999999999999, nan,\n      nan, nan, nan, nan, nan, nan, 0.0, 7.029920380986636e-306,\n      2.2450728208591345e-101, nan, nan, 0.0, 9.275871147869727e-302,\n      1.2232913026152827e-97, nan, nan, 0.0, 3.0891393081932924e-252,\n      2.9303043666183996e-60, nan, nan, 2.248913486879199e-196,\n      0.5000000000004947, 0.9999999999999999, nan;\n\n  for (int i = 0; i < 125; ++i) {\n    in_x(i) = x(i);\n    in_a(i) = a(i);\n    in_b(i) = b(i);\n    expected_out(i) = v(i);\n  }\n\n  std::size_t bytes = in_x.size() * sizeof(Scalar);\n\n  Scalar* d_in_x;\n  Scalar* d_in_a;\n  Scalar* d_in_b;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_in_x), bytes);\n  gpuMalloc((void**)(&d_in_a), bytes);\n  gpuMalloc((void**)(&d_in_b), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_in_x, in_x.data(), bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_in_a, in_a.data(), bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_in_b, in_b.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in_x(d_in_x, 125);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in_a(d_in_a, 125);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in_b(d_in_b, 125);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_out(d_out, 125);\n\n  gpu_out.device(gpu_device) = betainc(gpu_in_a, gpu_in_b, gpu_in_x);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 1; i < 125; ++i) {\n    if ((std::isnan)(expected_out(i))) {\n      VERIFY((std::isnan)(out(i)));\n    } else {\n      VERIFY_IS_APPROX(out(i), expected_out(i));\n    }\n  }\n\n  gpuFree(d_in_x);\n  gpuFree(d_in_a);\n  gpuFree(d_in_b);\n  gpuFree(d_out);\n}\n\ntemplate <typename Scalar>\nvoid test_gpu_i0e()\n{\n  Tensor<Scalar, 1> in_x(21);\n  Tensor<Scalar, 1> out(21);\n  Tensor<Scalar, 1> expected_out(21);\n  out.setZero();\n\n  Array<Scalar, 1, Dynamic> in_x_array(21);\n  Array<Scalar, 1, Dynamic> expected_out_array(21);\n\n  in_x_array << -20.0, -18.0, -16.0, -14.0, -12.0, -10.0, -8.0, -6.0, -4.0,\n      -2.0, 0.0, 2.0, 4.0, 6.0, 8.0, 10.0, 12.0, 14.0, 16.0, 18.0, 20.0;\n\n  expected_out_array << 0.0897803118848, 0.0947062952128, 0.100544127361,\n      0.107615251671, 0.116426221213, 0.127833337163, 0.143431781857,\n      0.16665743264, 0.207001921224, 0.308508322554, 1.0, 0.308508322554,\n      0.207001921224, 0.16665743264, 0.143431781857, 0.127833337163,\n      0.116426221213, 0.107615251671, 0.100544127361, 0.0947062952128,\n      0.0897803118848;\n\n  for (int i = 0; i < 21; ++i) {\n    in_x(i) = in_x_array(i);\n    expected_out(i) = expected_out_array(i);\n  }\n\n  std::size_t bytes = in_x.size() * sizeof(Scalar);\n\n  Scalar* d_in;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_in), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_in, in_x.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in(d_in, 21);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_out(d_out, 21);\n\n  gpu_out.device(gpu_device) = gpu_in.bessel_i0e();\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost,\n                         gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 21; ++i) {\n    VERIFY_IS_APPROX(out(i), expected_out(i));\n  }\n\n  gpuFree(d_in);\n  gpuFree(d_out);\n}\n\ntemplate <typename Scalar>\nvoid test_gpu_i1e()\n{\n  Tensor<Scalar, 1> in_x(21);\n  Tensor<Scalar, 1> out(21);\n  Tensor<Scalar, 1> expected_out(21);\n  out.setZero();\n\n  Array<Scalar, 1, Dynamic> in_x_array(21);\n  Array<Scalar, 1, Dynamic> expected_out_array(21);\n\n  in_x_array << -20.0, -18.0, -16.0, -14.0, -12.0, -10.0, -8.0, -6.0, -4.0,\n      -2.0, 0.0, 2.0, 4.0, 6.0, 8.0, 10.0, 12.0, 14.0, 16.0, 18.0, 20.0;\n\n  expected_out_array << -0.0875062221833, -0.092036796872, -0.0973496147565,\n      -0.103697667463, -0.11146429929, -0.121262681384, -0.134142493293,\n      -0.152051459309, -0.178750839502, -0.215269289249, 0.0, 0.215269289249,\n      0.178750839502, 0.152051459309, 0.134142493293, 0.121262681384,\n      0.11146429929, 0.103697667463, 0.0973496147565, 0.092036796872,\n      0.0875062221833;\n\n  for (int i = 0; i < 21; ++i) {\n    in_x(i) = in_x_array(i);\n    expected_out(i) = expected_out_array(i);\n  }\n\n  std::size_t bytes = in_x.size() * sizeof(Scalar);\n\n  Scalar* d_in;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_in), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_in, in_x.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in(d_in, 21);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_out(d_out, 21);\n\n  gpu_out.device(gpu_device) = gpu_in.bessel_i1e();\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost,\n                         gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 21; ++i) {\n    VERIFY_IS_APPROX(out(i), expected_out(i));\n  }\n\n  gpuFree(d_in);\n  gpuFree(d_out);\n}\n\ntemplate <typename Scalar>\nvoid test_gpu_igamma_der_a()\n{\n  Tensor<Scalar, 1> in_x(30);\n  Tensor<Scalar, 1> in_a(30);\n  Tensor<Scalar, 1> out(30);\n  Tensor<Scalar, 1> expected_out(30);\n  out.setZero();\n\n  Array<Scalar, 1, Dynamic> in_a_array(30);\n  Array<Scalar, 1, Dynamic> in_x_array(30);\n  Array<Scalar, 1, Dynamic> expected_out_array(30);\n\n  // See special_functions.cpp for the Python code that generates the test data.\n\n  in_a_array << 0.01, 0.01, 0.01, 0.01, 0.01, 0.1, 0.1, 0.1, 0.1, 0.1, 1.0, 1.0,\n      1.0, 1.0, 1.0, 10.0, 10.0, 10.0, 10.0, 10.0, 100.0, 100.0, 100.0, 100.0,\n      100.0, 1000.0, 1000.0, 1000.0, 1000.0, 1000.0;\n\n  in_x_array << 1.25668890405e-26, 1.17549435082e-38, 1.20938905072e-05,\n      1.17549435082e-38, 1.17549435082e-38, 5.66572070696e-16, 0.0132865061065,\n      0.0200034203853, 6.29263709118e-17, 1.37160367764e-06, 0.333412038288,\n      1.18135687766, 0.580629033777, 0.170631439426, 0.786686768458,\n      7.63873279537, 13.1944344379, 11.896042354, 10.5830172417, 10.5020942233,\n      92.8918587747, 95.003720371, 86.3715926467, 96.0330217672, 82.6389930677,\n      968.702906754, 969.463546828, 1001.79726022, 955.047416547, 1044.27458568;\n\n  expected_out_array << -32.7256441441, -36.4394150514, -9.66467612263,\n      -36.4394150514, -36.4394150514, -1.0891900302, -2.66351229645,\n      -2.48666868596, -0.929700494428, -3.56327722764, -0.455320135314,\n      -0.391437214323, -0.491352055991, -0.350454834292, -0.471773162921,\n      -0.104084440522, -0.0723646747909, -0.0992828975532, -0.121638215446,\n      -0.122619605294, -0.0317670267286, -0.0359974812869, -0.0154359225363,\n      -0.0375775365921, -0.00794899153653, -0.00777303219211, -0.00796085782042,\n      -0.0125850719397, -0.00455500206958, -0.00476436993148;\n\n  for (int i = 0; i < 30; ++i) {\n    in_x(i) = in_x_array(i);\n    in_a(i) = in_a_array(i);\n    expected_out(i) = expected_out_array(i);\n  }\n\n  std::size_t bytes = in_x.size() * sizeof(Scalar);\n\n  Scalar* d_a;\n  Scalar* d_x;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_a), bytes);\n  gpuMalloc((void**)(&d_x), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_a, in_a.data(), bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_x, in_x.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_a(d_a, 30);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_x(d_x, 30);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_out(d_out, 30);\n\n  gpu_out.device(gpu_device) = gpu_a.igamma_der_a(gpu_x);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost,\n                         gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 30; ++i) {\n    VERIFY_IS_APPROX(out(i), expected_out(i));\n  }\n\n  gpuFree(d_a);\n  gpuFree(d_x);\n  gpuFree(d_out);\n}\n\ntemplate <typename Scalar>\nvoid test_gpu_gamma_sample_der_alpha()\n{\n  Tensor<Scalar, 1> in_alpha(30);\n  Tensor<Scalar, 1> in_sample(30);\n  Tensor<Scalar, 1> out(30);\n  Tensor<Scalar, 1> expected_out(30);\n  out.setZero();\n\n  Array<Scalar, 1, Dynamic> in_alpha_array(30);\n  Array<Scalar, 1, Dynamic> in_sample_array(30);\n  Array<Scalar, 1, Dynamic> expected_out_array(30);\n\n  // See special_functions.cpp for the Python code that generates the test data.\n\n  in_alpha_array << 0.01, 0.01, 0.01, 0.01, 0.01, 0.1, 0.1, 0.1, 0.1, 0.1, 1.0,\n      1.0, 1.0, 1.0, 1.0, 10.0, 10.0, 10.0, 10.0, 10.0, 100.0, 100.0, 100.0,\n      100.0, 100.0, 1000.0, 1000.0, 1000.0, 1000.0, 1000.0;\n\n  in_sample_array << 1.25668890405e-26, 1.17549435082e-38, 1.20938905072e-05,\n      1.17549435082e-38, 1.17549435082e-38, 5.66572070696e-16, 0.0132865061065,\n      0.0200034203853, 6.29263709118e-17, 1.37160367764e-06, 0.333412038288,\n      1.18135687766, 0.580629033777, 0.170631439426, 0.786686768458,\n      7.63873279537, 13.1944344379, 11.896042354, 10.5830172417, 10.5020942233,\n      92.8918587747, 95.003720371, 86.3715926467, 96.0330217672, 82.6389930677,\n      968.702906754, 969.463546828, 1001.79726022, 955.047416547, 1044.27458568;\n\n  expected_out_array << 7.42424742367e-23, 1.02004297287e-34, 0.0130155240738,\n      1.02004297287e-34, 1.02004297287e-34, 1.96505168277e-13, 0.525575786243,\n      0.713903991771, 2.32077561808e-14, 0.000179348049886, 0.635500453302,\n      1.27561284917, 0.878125852156, 0.41565819538, 1.03606488534,\n      0.885964824887, 1.16424049334, 1.10764479598, 1.04590810812,\n      1.04193666963, 0.965193152414, 0.976217589464, 0.93008035061,\n      0.98153216096, 0.909196397698, 0.98434963993, 0.984738050206,\n      1.00106492525, 0.97734200649, 1.02198794179;\n\n  for (int i = 0; i < 30; ++i) {\n    in_alpha(i) = in_alpha_array(i);\n    in_sample(i) = in_sample_array(i);\n    expected_out(i) = expected_out_array(i);\n  }\n\n  std::size_t bytes = in_alpha.size() * sizeof(Scalar);\n\n  Scalar* d_alpha;\n  Scalar* d_sample;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_alpha), bytes);\n  gpuMalloc((void**)(&d_sample), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_alpha, in_alpha.data(), bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_sample, in_sample.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_alpha(d_alpha, 30);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_sample(d_sample, 30);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_out(d_out, 30);\n\n  gpu_out.device(gpu_device) = gpu_alpha.gamma_sample_der_alpha(gpu_sample);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost,\n                         gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 30; ++i) {\n    VERIFY_IS_APPROX(out(i), expected_out(i));\n  }\n\n  gpuFree(d_alpha);\n  gpuFree(d_sample);\n  gpuFree(d_out);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_gpu)\n{\n  CALL_SUBTEST_1(test_gpu_nullary());\n  CALL_SUBTEST_1(test_gpu_elementwise_small());\n  CALL_SUBTEST_1(test_gpu_elementwise());\n  CALL_SUBTEST_1(test_gpu_props());\n  CALL_SUBTEST_1(test_gpu_reduction());\n  CALL_SUBTEST_2(test_gpu_contraction<ColMajor>());\n  CALL_SUBTEST_2(test_gpu_contraction<RowMajor>());\n  CALL_SUBTEST_3(test_gpu_convolution_1d<ColMajor>());\n  CALL_SUBTEST_3(test_gpu_convolution_1d<RowMajor>());\n  CALL_SUBTEST_3(test_gpu_convolution_inner_dim_col_major_1d());\n  CALL_SUBTEST_3(test_gpu_convolution_inner_dim_row_major_1d());\n  CALL_SUBTEST_3(test_gpu_convolution_2d<ColMajor>());\n  CALL_SUBTEST_3(test_gpu_convolution_2d<RowMajor>());\n#if !defined(EIGEN_USE_HIP)\n// disable these tests on HIP for now.\n// they hang..need to investigate and fix\n  CALL_SUBTEST_3(test_gpu_convolution_3d<ColMajor>());\n  CALL_SUBTEST_3(test_gpu_convolution_3d<RowMajor>());\n#endif\n\n#if EIGEN_GPU_TEST_C99_MATH\n  // std::erf, std::erfc, and so on where only added in c++11. We use them\n  // as a golden reference to validate the results produced by Eigen. Therefore\n  // we can only run these tests if we use a c++11 compiler.\n  CALL_SUBTEST_4(test_gpu_lgamma<float>(1.0f));\n  CALL_SUBTEST_4(test_gpu_lgamma<float>(100.0f));\n  CALL_SUBTEST_4(test_gpu_lgamma<float>(0.01f));\n  CALL_SUBTEST_4(test_gpu_lgamma<float>(0.001f));\n\n  CALL_SUBTEST_4(test_gpu_lgamma<double>(1.0));\n  CALL_SUBTEST_4(test_gpu_lgamma<double>(100.0));\n  CALL_SUBTEST_4(test_gpu_lgamma<double>(0.01));\n  CALL_SUBTEST_4(test_gpu_lgamma<double>(0.001));\n\n  CALL_SUBTEST_4(test_gpu_erf<float>(1.0f));\n  CALL_SUBTEST_4(test_gpu_erf<float>(100.0f));\n  CALL_SUBTEST_4(test_gpu_erf<float>(0.01f));\n  CALL_SUBTEST_4(test_gpu_erf<float>(0.001f));\n\n  CALL_SUBTEST_4(test_gpu_erfc<float>(1.0f));\n  // CALL_SUBTEST(test_gpu_erfc<float>(100.0f));\n  CALL_SUBTEST_4(test_gpu_erfc<float>(5.0f)); // GPU erfc lacks precision for large inputs\n  CALL_SUBTEST_4(test_gpu_erfc<float>(0.01f));\n  CALL_SUBTEST_4(test_gpu_erfc<float>(0.001f));\n\n  CALL_SUBTEST_4(test_gpu_erf<double>(1.0));\n  CALL_SUBTEST_4(test_gpu_erf<double>(100.0));\n  CALL_SUBTEST_4(test_gpu_erf<double>(0.01));\n  CALL_SUBTEST_4(test_gpu_erf<double>(0.001));\n\n  CALL_SUBTEST_4(test_gpu_erfc<double>(1.0));\n  // CALL_SUBTEST(test_gpu_erfc<double>(100.0));\n  CALL_SUBTEST_4(test_gpu_erfc<double>(5.0)); // GPU erfc lacks precision for large inputs\n  CALL_SUBTEST_4(test_gpu_erfc<double>(0.01));\n  CALL_SUBTEST_4(test_gpu_erfc<double>(0.001));\n\n#if !defined(EIGEN_USE_HIP)\n// disable these tests on HIP for now.\n\n  CALL_SUBTEST_5(test_gpu_ndtri<float>());\n  CALL_SUBTEST_5(test_gpu_ndtri<double>());\n\n  CALL_SUBTEST_5(test_gpu_digamma<float>());\n  CALL_SUBTEST_5(test_gpu_digamma<double>());\n\n  CALL_SUBTEST_5(test_gpu_polygamma<float>());\n  CALL_SUBTEST_5(test_gpu_polygamma<double>());\n\n  CALL_SUBTEST_5(test_gpu_zeta<float>());\n  CALL_SUBTEST_5(test_gpu_zeta<double>());\n#endif\n\n  CALL_SUBTEST_5(test_gpu_igamma<float>());\n  CALL_SUBTEST_5(test_gpu_igammac<float>());\n\n  CALL_SUBTEST_5(test_gpu_igamma<double>());\n  CALL_SUBTEST_5(test_gpu_igammac<double>());\n\n#if !defined(EIGEN_USE_HIP)\n// disable these tests on HIP for now.\n  CALL_SUBTEST_6(test_gpu_betainc<float>());\n  CALL_SUBTEST_6(test_gpu_betainc<double>());\n\n  CALL_SUBTEST_6(test_gpu_i0e<float>());\n  CALL_SUBTEST_6(test_gpu_i0e<double>());\n\n  CALL_SUBTEST_6(test_gpu_i1e<float>());\n  CALL_SUBTEST_6(test_gpu_i1e<double>());\n\n  CALL_SUBTEST_6(test_gpu_i1e<float>());\n  CALL_SUBTEST_6(test_gpu_i1e<double>());\n\n  CALL_SUBTEST_6(test_gpu_igamma_der_a<float>());\n  CALL_SUBTEST_6(test_gpu_igamma_der_a<double>());\n\n  CALL_SUBTEST_6(test_gpu_gamma_sample_der_alpha<float>());\n  CALL_SUBTEST_6(test_gpu_gamma_sample_der_alpha<double>());\n#endif\n\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_ifft.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Jianwei Cui <thucjw@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <complex>\n#include <cmath>\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate <int DataLayout>\nstatic void test_1D_fft_ifft_invariant(int sequence_length) {\n  Tensor<double, 1, DataLayout> tensor(sequence_length);\n  tensor.setRandom();\n\n  array<int, 1> fft;\n  fft[0] = 0;\n\n  Tensor<std::complex<double>, 1, DataLayout> tensor_after_fft;\n  Tensor<std::complex<double>, 1, DataLayout> tensor_after_fft_ifft;\n\n  tensor_after_fft = tensor.template fft<Eigen::BothParts, Eigen::FFT_FORWARD>(fft);\n  tensor_after_fft_ifft = tensor_after_fft.template fft<Eigen::BothParts, Eigen::FFT_REVERSE>(fft);\n\n  VERIFY_IS_EQUAL(tensor_after_fft.dimension(0), sequence_length);\n  VERIFY_IS_EQUAL(tensor_after_fft_ifft.dimension(0), sequence_length);\n\n  for (int i = 0; i < sequence_length; ++i) {\n    VERIFY_IS_APPROX(static_cast<float>(tensor(i)), static_cast<float>(std::real(tensor_after_fft_ifft(i))));\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_2D_fft_ifft_invariant(int dim0, int dim1) {\n  Tensor<double, 2, DataLayout> tensor(dim0, dim1);\n  tensor.setRandom();\n\n  array<int, 2> fft;\n  fft[0] = 0;\n  fft[1] = 1;\n\n  Tensor<std::complex<double>, 2, DataLayout> tensor_after_fft;\n  Tensor<std::complex<double>, 2, DataLayout> tensor_after_fft_ifft;\n\n  tensor_after_fft = tensor.template fft<Eigen::BothParts, Eigen::FFT_FORWARD>(fft);\n  tensor_after_fft_ifft = tensor_after_fft.template fft<Eigen::BothParts, Eigen::FFT_REVERSE>(fft);\n\n  VERIFY_IS_EQUAL(tensor_after_fft.dimension(0), dim0);\n  VERIFY_IS_EQUAL(tensor_after_fft.dimension(1), dim1);\n  VERIFY_IS_EQUAL(tensor_after_fft_ifft.dimension(0), dim0);\n  VERIFY_IS_EQUAL(tensor_after_fft_ifft.dimension(1), dim1);\n\n  for (int i = 0; i < dim0; ++i) {\n    for (int j = 0; j < dim1; ++j) {\n      //std::cout << \"[\" << i << \"][\" << j << \"]\" <<  \"  Original data: \" << tensor(i,j) << \" Transformed data:\" << tensor_after_fft_ifft(i,j) << std::endl;\n      VERIFY_IS_APPROX(static_cast<float>(tensor(i,j)), static_cast<float>(std::real(tensor_after_fft_ifft(i,j))));\n    }\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_3D_fft_ifft_invariant(int dim0, int dim1, int dim2) {\n  Tensor<double, 3, DataLayout> tensor(dim0, dim1, dim2);\n  tensor.setRandom();\n\n  array<int, 3> fft;\n  fft[0] = 0;\n  fft[1] = 1;\n  fft[2] = 2;\n\n  Tensor<std::complex<double>, 3, DataLayout> tensor_after_fft;\n  Tensor<std::complex<double>, 3, DataLayout> tensor_after_fft_ifft;\n\n  tensor_after_fft = tensor.template fft<Eigen::BothParts, Eigen::FFT_FORWARD>(fft);\n  tensor_after_fft_ifft = tensor_after_fft.template fft<Eigen::BothParts, Eigen::FFT_REVERSE>(fft);\n\n  VERIFY_IS_EQUAL(tensor_after_fft.dimension(0), dim0);\n  VERIFY_IS_EQUAL(tensor_after_fft.dimension(1), dim1);\n  VERIFY_IS_EQUAL(tensor_after_fft.dimension(2), dim2);\n  VERIFY_IS_EQUAL(tensor_after_fft_ifft.dimension(0), dim0);\n  VERIFY_IS_EQUAL(tensor_after_fft_ifft.dimension(1), dim1);\n  VERIFY_IS_EQUAL(tensor_after_fft_ifft.dimension(2), dim2);\n\n  for (int i = 0; i < dim0; ++i) {\n    for (int j = 0; j < dim1; ++j) {\n      for (int k = 0; k < dim2; ++k) {\n        VERIFY_IS_APPROX(static_cast<float>(tensor(i,j,k)), static_cast<float>(std::real(tensor_after_fft_ifft(i,j,k))));\n      }\n    }\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_sub_fft_ifft_invariant(int dim0, int dim1, int dim2, int dim3) {\n  Tensor<double, 4, DataLayout> tensor(dim0, dim1, dim2, dim3);\n  tensor.setRandom();\n\n  array<int, 2> fft;\n  fft[0] = 2;\n  fft[1] = 0;\n\n  Tensor<std::complex<double>, 4, DataLayout> tensor_after_fft;\n  Tensor<double, 4, DataLayout> tensor_after_fft_ifft;\n\n  tensor_after_fft = tensor.template fft<Eigen::BothParts, Eigen::FFT_FORWARD>(fft);\n  tensor_after_fft_ifft = tensor_after_fft.template fft<Eigen::RealPart, Eigen::FFT_REVERSE>(fft);\n\n  VERIFY_IS_EQUAL(tensor_after_fft.dimension(0), dim0);\n  VERIFY_IS_EQUAL(tensor_after_fft.dimension(1), dim1);\n  VERIFY_IS_EQUAL(tensor_after_fft.dimension(2), dim2);\n  VERIFY_IS_EQUAL(tensor_after_fft.dimension(3), dim3);\n  VERIFY_IS_EQUAL(tensor_after_fft_ifft.dimension(0), dim0);\n  VERIFY_IS_EQUAL(tensor_after_fft_ifft.dimension(1), dim1);\n  VERIFY_IS_EQUAL(tensor_after_fft_ifft.dimension(2), dim2);\n  VERIFY_IS_EQUAL(tensor_after_fft_ifft.dimension(3), dim3);\n\n  for (int i = 0; i < dim0; ++i) {\n    for (int j = 0; j < dim1; ++j) {\n      for (int k = 0; k < dim2; ++k) {\n        for (int l = 0; l < dim3; ++l) {\n          VERIFY_IS_APPROX(static_cast<float>(tensor(i,j,k,l)), static_cast<float>(tensor_after_fft_ifft(i,j,k,l)));\n        }\n      }\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_ifft) {\n  CALL_SUBTEST(test_1D_fft_ifft_invariant<ColMajor>(4));\n  CALL_SUBTEST(test_1D_fft_ifft_invariant<ColMajor>(16));\n  CALL_SUBTEST(test_1D_fft_ifft_invariant<ColMajor>(32));\n  CALL_SUBTEST(test_1D_fft_ifft_invariant<ColMajor>(1024*1024));\n\n  CALL_SUBTEST(test_2D_fft_ifft_invariant<ColMajor>(4,4));\n  CALL_SUBTEST(test_2D_fft_ifft_invariant<ColMajor>(8,16));\n  CALL_SUBTEST(test_2D_fft_ifft_invariant<ColMajor>(16,32));\n  CALL_SUBTEST(test_2D_fft_ifft_invariant<ColMajor>(1024,1024));\n\n  CALL_SUBTEST(test_3D_fft_ifft_invariant<ColMajor>(4,4,4));\n  CALL_SUBTEST(test_3D_fft_ifft_invariant<ColMajor>(8,16,32));\n  CALL_SUBTEST(test_3D_fft_ifft_invariant<ColMajor>(16,4,8));\n  CALL_SUBTEST(test_3D_fft_ifft_invariant<ColMajor>(256,256,256));\n\n  CALL_SUBTEST(test_sub_fft_ifft_invariant<ColMajor>(4,4,4,4));\n  CALL_SUBTEST(test_sub_fft_ifft_invariant<ColMajor>(8,16,32,64));\n  CALL_SUBTEST(test_sub_fft_ifft_invariant<ColMajor>(16,4,8,12));\n  CALL_SUBTEST(test_sub_fft_ifft_invariant<ColMajor>(64,64,64,64));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_image_op_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_image_op_sycl(const Eigen::SyclDevice &sycl_device)\n{\n  IndexType sizeDim1 = 245;\n  IndexType sizeDim2 = 343;\n  IndexType sizeDim3 = 577;\n\n  array<IndexType, 3> input_range ={{sizeDim1, sizeDim2, sizeDim3}};\n  array<IndexType, 3> slice_range ={{sizeDim1-1, sizeDim2, sizeDim3}};\n\n  Tensor<DataType, 3,DataLayout, IndexType> tensor1(input_range);\n  Tensor<DataType, 3,DataLayout, IndexType> tensor2(input_range);\n  Tensor<DataType, 3, DataLayout, IndexType> tensor3(slice_range);\n  Tensor<DataType, 3, DataLayout, IndexType> tensor3_cpu(slice_range);\n\n\n\n  typedef Eigen::DSizes<IndexType, 3> Index3;\n  Index3 strides1(1L,1L, 1L);\n  Index3 indicesStart1(1L, 0L, 0L);\n  Index3 indicesStop1(sizeDim1, sizeDim2, sizeDim3);\n\n  Index3 strides2(1L,1L, 1L);\n  Index3 indicesStart2(0L, 0L, 0L);\n  Index3 indicesStop2(sizeDim1-1, sizeDim2, sizeDim3);\n  Eigen::DSizes<IndexType, 3> sizes(sizeDim1-1,sizeDim2,sizeDim3);\n\n  tensor1.setRandom();\n  tensor2.setRandom();\n\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(tensor1.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(tensor2.size()*sizeof(DataType)));\n  DataType* gpu_data3  = static_cast<DataType*>(sycl_device.allocate(tensor3.size()*sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu1(gpu_data1, input_range);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu2(gpu_data2, input_range);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu3(gpu_data3, slice_range);\n\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor1.data(),(tensor1.size())*sizeof(DataType));\n  sycl_device.memcpyHostToDevice(gpu_data2, tensor2.data(),(tensor2.size())*sizeof(DataType));\n  gpu3.device(sycl_device)= gpu1.slice(indicesStart1, sizes) - gpu2.slice(indicesStart2, sizes);\n  sycl_device.memcpyDeviceToHost(tensor3.data(), gpu_data3,(tensor3.size())*sizeof(DataType));\n\n  tensor3_cpu = tensor1.stridedSlice(indicesStart1,indicesStop1,strides1) - tensor2.stridedSlice(indicesStart2,indicesStop2,strides2);\n\n\n  for (IndexType i = 0; i <slice_range[0] ; ++i) {\n    for (IndexType j = 0; j < slice_range[1]; ++j) {\n      for (IndexType k = 0; k < slice_range[2]; ++k) {\n        VERIFY_IS_EQUAL(tensor3_cpu(i,j,k), tensor3(i,j,k));\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n  sycl_device.deallocate(gpu_data3);\n}\n\n\ntemplate<typename DataType, typename dev_Selector> void sycl_computing_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_image_op_sycl<DataType, RowMajor, int64_t>(sycl_device);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_image_op_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) { \n   CALL_SUBTEST(sycl_computing_test_per_device<float>(device));\n#ifdef EIGEN_SYCL_DOUBLE_SUPPORT\n   CALL_SUBTEST(sycl_computing_test_per_device<double>(device));\n#endif\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_image_patch.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\nvoid test_simple_patch()\n{\n  Tensor<float, 4> tensor(2,3,5,7);\n  tensor.setRandom();\n  Tensor<float, 4, RowMajor> tensor_row_major = tensor.swap_layout();\n  VERIFY_IS_EQUAL(tensor.dimension(0), tensor_row_major.dimension(3));\n  VERIFY_IS_EQUAL(tensor.dimension(1), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor.dimension(2), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor.dimension(3), tensor_row_major.dimension(0));\n\n  // Single pixel patch: ColMajor\n  Tensor<float, 5> single_pixel_patch;\n  single_pixel_patch = tensor.extract_image_patches(1, 1);\n  VERIFY_IS_EQUAL(single_pixel_patch.dimension(0), 2);\n  VERIFY_IS_EQUAL(single_pixel_patch.dimension(1), 1);\n  VERIFY_IS_EQUAL(single_pixel_patch.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_pixel_patch.dimension(3), 3*5);\n  VERIFY_IS_EQUAL(single_pixel_patch.dimension(4), 7);\n\n  // Single pixel patch: RowMajor\n  Tensor<float, 5, RowMajor> single_pixel_patch_row_major;\n  single_pixel_patch_row_major = tensor_row_major.extract_image_patches(1, 1);\n  VERIFY_IS_EQUAL(single_pixel_patch_row_major.dimension(0), 7);\n  VERIFY_IS_EQUAL(single_pixel_patch_row_major.dimension(1), 3*5);\n  VERIFY_IS_EQUAL(single_pixel_patch_row_major.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_pixel_patch_row_major.dimension(3), 1);\n  VERIFY_IS_EQUAL(single_pixel_patch_row_major.dimension(4), 2);\n\n  for (int i = 0; i < tensor.size(); ++i) {\n    // ColMajor\n    if (tensor.data()[i] != single_pixel_patch.data()[i]) {\n      std::cout << \"Mismatch detected at index \" << i << \" : \"\n           << tensor.data()[i] << \" vs \" << single_pixel_patch.data()[i]\n           << std::endl;\n    }\n    VERIFY_IS_EQUAL(single_pixel_patch.data()[i], tensor.data()[i]);\n    // RowMajor\n    if (tensor_row_major.data()[i] != single_pixel_patch_row_major.data()[i]) {\n      std::cout << \"Mismatch detected at index \" << i << \" : \"\n           << tensor.data()[i] << \" vs \"\n           << single_pixel_patch_row_major.data()[i] << std::endl;\n    }\n    VERIFY_IS_EQUAL(single_pixel_patch_row_major.data()[i],\n                    tensor_row_major.data()[i]);\n    VERIFY_IS_EQUAL(tensor.data()[i], tensor_row_major.data()[i]);\n    VERIFY_IS_EQUAL(single_pixel_patch.data()[i],\n                    single_pixel_patch_row_major.data()[i]);\n  }\n\n  // Entire image patch: ColMajor\n  Tensor<float, 5> entire_image_patch;\n  entire_image_patch = tensor.extract_image_patches(3, 5);\n  VERIFY_IS_EQUAL(entire_image_patch.dimension(0), 2);\n  VERIFY_IS_EQUAL(entire_image_patch.dimension(1), 3);\n  VERIFY_IS_EQUAL(entire_image_patch.dimension(2), 5);\n  VERIFY_IS_EQUAL(entire_image_patch.dimension(3), 3*5);\n  VERIFY_IS_EQUAL(entire_image_patch.dimension(4), 7);\n\n  // Entire image patch: RowMajor\n  Tensor<float, 5, RowMajor> entire_image_patch_row_major;\n  entire_image_patch_row_major = tensor_row_major.extract_image_patches(3, 5);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(0), 7);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(1), 3*5);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(2), 5);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(3), 3);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(4), 2);\n\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      int patchId = i+3*j;\n      for (int r = 0; r < 3; ++r) {\n        for (int c = 0; c < 5; ++c) {\n          for (int d = 0; d < 2; ++d) {\n            for (int b = 0; b < 7; ++b) {\n              float expected = 0.0f;\n              float expected_row_major = 0.0f;\n              if (r-1+i >= 0 && c-2+j >= 0 && r-1+i < 3 && c-2+j < 5) {\n                expected = tensor(d, r-1+i, c-2+j, b);\n                expected_row_major = tensor_row_major(b, c-2+j, r-1+i, d);\n              }\n              // ColMajor\n              if (entire_image_patch(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(entire_image_patch(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (entire_image_patch_row_major(b, patchId, c, r, d) !=\n                  expected_row_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j\n                     << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b\n                     << std::endl;\n              }\n              VERIFY_IS_EQUAL(entire_image_patch_row_major(b, patchId, c, r, d),\n                              expected_row_major);\n              // Check that ColMajor and RowMajor agree.\n              VERIFY_IS_EQUAL(expected, expected_row_major);\n            }\n          }\n        }\n      }\n    }\n  }\n\n  // 2D patch: ColMajor\n  Tensor<float, 5> twod_patch;\n  twod_patch = tensor.extract_image_patches(2, 2);\n  VERIFY_IS_EQUAL(twod_patch.dimension(0), 2);\n  VERIFY_IS_EQUAL(twod_patch.dimension(1), 2);\n  VERIFY_IS_EQUAL(twod_patch.dimension(2), 2);\n  VERIFY_IS_EQUAL(twod_patch.dimension(3), 3*5);\n  VERIFY_IS_EQUAL(twod_patch.dimension(4), 7);\n\n  // 2D patch: RowMajor\n  Tensor<float, 5, RowMajor> twod_patch_row_major;\n  twod_patch_row_major = tensor_row_major.extract_image_patches(2, 2);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(0), 7);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(1), 3*5);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(2), 2);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(3), 2);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(4), 2);\n\n\n  // Based on the calculation described in TensorTraits.h, padding happens to be 0.\n  int row_padding = 0;\n  int col_padding = 0;\n  int stride = 1;\n\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      int patchId = i+3*j;\n      for (int r = 0; r < 2; ++r) {\n        for (int c = 0; c < 2; ++c) {\n          for (int d = 0; d < 2; ++d) {\n            for (int b = 0; b < 7; ++b) {\n              float expected = 0.0f;\n              float expected_row_major = 0.0f;\n              int row_offset = r*stride + i - row_padding;\n              int col_offset = c*stride + j - col_padding;\n              // ColMajor\n              if (row_offset >= 0 && col_offset >= 0 && row_offset < tensor.dimension(1) && col_offset < tensor.dimension(2)) {\n                expected = tensor(d, row_offset, col_offset, b);\n              }\n              if (twod_patch(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(twod_patch(d, r, c, patchId, b), expected);\n\n              // RowMajor\n              if (row_offset >= 0 && col_offset >= 0 && row_offset < tensor_row_major.dimension(2) && col_offset < tensor_row_major.dimension(1)) {\n                expected_row_major = tensor_row_major(b, col_offset, row_offset, d);\n\n              }\n              if (twod_patch_row_major(b, patchId, c, r, d) != expected_row_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(twod_patch_row_major(b, patchId, c, r, d), expected_row_major);\n              // Check that ColMajor and RowMajor agree.\n              VERIFY_IS_EQUAL(expected, expected_row_major);\n            }\n          }\n        }\n      }\n    }\n  }\n}\n\n// Verifies VALID padding (no padding) with incrementing values.\nvoid test_patch_padding_valid()\n{\n  int input_depth = 3;\n  int input_rows = 3;\n  int input_cols = 3;\n  int input_batches = 1;\n  int ksize = 2;  // Corresponds to the Rows and Cols for tensor.extract_image_patches<>.\n  int stride = 2;  // Only same stride is supported.\n  Tensor<float, 4> tensor(input_depth, input_rows, input_cols, input_batches);\n  // Initializes tensor with incrementing numbers.\n  for (int i = 0; i < tensor.size(); ++i) {\n    tensor.data()[i] = i + 1;\n  }\n  // ColMajor\n  Tensor<float, 5> result = tensor.extract_image_patches(ksize, ksize, stride, stride, 1, 1, PADDING_VALID);\n\n  VERIFY_IS_EQUAL(result.dimension(0), input_depth);  // depth\n  VERIFY_IS_EQUAL(result.dimension(1), ksize);  // kernel rows\n  VERIFY_IS_EQUAL(result.dimension(2), ksize);  // kernel cols\n  VERIFY_IS_EQUAL(result.dimension(3), 1);  // number of patches\n  VERIFY_IS_EQUAL(result.dimension(4), input_batches);  // number of batches\n\n  // RowMajor\n  Tensor<float, 4, RowMajor> tensor_row_major = tensor.swap_layout();\n  VERIFY_IS_EQUAL(tensor.dimension(0), tensor_row_major.dimension(3));\n  VERIFY_IS_EQUAL(tensor.dimension(1), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor.dimension(2), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor.dimension(3), tensor_row_major.dimension(0));\n\n  Tensor<float, 5, RowMajor> result_row_major = tensor_row_major.extract_image_patches(ksize, ksize, stride, stride, 1, 1, PADDING_VALID);\n  VERIFY_IS_EQUAL(result.dimension(0), result_row_major.dimension(4));\n  VERIFY_IS_EQUAL(result.dimension(1), result_row_major.dimension(3));\n  VERIFY_IS_EQUAL(result.dimension(2), result_row_major.dimension(2));\n  VERIFY_IS_EQUAL(result.dimension(3), result_row_major.dimension(1));\n  VERIFY_IS_EQUAL(result.dimension(4), result_row_major.dimension(0));\n\n  // No padding is carried out.\n  int row_padding = 0;\n  int col_padding = 0;\n\n  for (int i = 0; (i+stride+ksize-1) < input_rows; i += stride) {  // input rows\n    for (int j = 0; (j+stride+ksize-1) < input_cols; j += stride) {  // input cols\n      int patchId = i+input_rows*j;\n      for (int r = 0; r < ksize; ++r) {  // patch rows\n        for (int c = 0; c < ksize; ++c) {  // patch cols\n          for (int d = 0; d < input_depth; ++d) {  // depth\n            for (int b = 0; b < input_batches; ++b) {  // batch\n              float expected = 0.0f;\n              float expected_row_major = 0.0f;\n              int row_offset = r + i - row_padding;\n              int col_offset = c + j - col_padding;\n              if (row_offset >= 0 && col_offset >= 0 && row_offset < input_rows && col_offset < input_cols) {\n                expected = tensor(d, row_offset, col_offset, b);\n                expected_row_major = tensor_row_major(b, col_offset, row_offset, d);\n              }\n              // ColMajor\n              if (result(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (result_row_major(b, patchId, c, r, d) != expected_row_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result_row_major(b, patchId, c, r, d), expected_row_major);\n              // Check that ColMajor and RowMajor agree.\n              VERIFY_IS_EQUAL(expected, expected_row_major);\n            }\n          }\n        }\n      }\n    }\n  }\n}\n\n// Verifies VALID padding (no padding) with the same value.\nvoid test_patch_padding_valid_same_value()\n{\n  int input_depth = 1;\n  int input_rows = 5;\n  int input_cols = 5;\n  int input_batches = 2;\n  int ksize = 3;  // Corresponds to the Rows and Cols for tensor.extract_image_patches<>.\n  int stride = 2;  // Only same stride is supported.\n  // ColMajor\n  Tensor<float, 4> tensor(input_depth, input_rows, input_cols, input_batches);\n  tensor = tensor.constant(11.0f);\n  Tensor<float, 5> result = tensor.extract_image_patches(ksize, ksize, stride, stride, 1, 1, PADDING_VALID);\n\n  VERIFY_IS_EQUAL(result.dimension(0), input_depth);  // depth\n  VERIFY_IS_EQUAL(result.dimension(1), ksize);  // kernel rows\n  VERIFY_IS_EQUAL(result.dimension(2), ksize);  // kernel cols\n  VERIFY_IS_EQUAL(result.dimension(3), 4);  // number of patches\n  VERIFY_IS_EQUAL(result.dimension(4), input_batches);  // number of batches\n\n  // RowMajor\n  Tensor<float, 4, RowMajor> tensor_row_major = tensor.swap_layout();\n  VERIFY_IS_EQUAL(tensor.dimension(0), tensor_row_major.dimension(3));\n  VERIFY_IS_EQUAL(tensor.dimension(1), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor.dimension(2), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor.dimension(3), tensor_row_major.dimension(0));\n\n  Tensor<float, 5, RowMajor> result_row_major = tensor_row_major.extract_image_patches(ksize, ksize, stride, stride, 1, 1, PADDING_VALID);\n  VERIFY_IS_EQUAL(result.dimension(0), result_row_major.dimension(4));\n  VERIFY_IS_EQUAL(result.dimension(1), result_row_major.dimension(3));\n  VERIFY_IS_EQUAL(result.dimension(2), result_row_major.dimension(2));\n  VERIFY_IS_EQUAL(result.dimension(3), result_row_major.dimension(1));\n  VERIFY_IS_EQUAL(result.dimension(4), result_row_major.dimension(0));\n\n  // No padding is carried out.\n  int row_padding = 0;\n  int col_padding = 0;\n\n  for (int i = 0; (i+stride+ksize-1) <= input_rows; i += stride) {  // input rows\n    for (int j = 0; (j+stride+ksize-1) <= input_cols; j += stride) {  // input cols\n      int patchId = i+input_rows*j;\n      for (int r = 0; r < ksize; ++r) {  // patch rows\n        for (int c = 0; c < ksize; ++c) {  // patch cols\n          for (int d = 0; d < input_depth; ++d) {  // depth\n            for (int b = 0; b < input_batches; ++b) {  // batch\n              float expected = 0.0f;\n              float expected_row_major = 0.0f;\n              int row_offset = r + i - row_padding;\n              int col_offset = c + j - col_padding;\n              if (row_offset >= 0 && col_offset >= 0 && row_offset < input_rows && col_offset < input_cols) {\n                expected = tensor(d, row_offset, col_offset, b);\n                expected_row_major = tensor_row_major(b, col_offset, row_offset, d);\n              }\n              // ColMajor\n              if (result(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (result_row_major(b, patchId, c, r, d) != expected_row_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result_row_major(b, patchId, c, r, d), expected_row_major);\n              // Check that ColMajor and RowMajor agree.\n              VERIFY_IS_EQUAL(expected, expected_row_major);\n            }\n          }\n        }\n      }\n    }\n  }\n}\n\n// Verifies SAME padding.\nvoid test_patch_padding_same()\n{\n  int input_depth = 3;\n  int input_rows = 4;\n  int input_cols = 2;\n  int input_batches = 1;\n  int ksize = 2;  // Corresponds to the Rows and Cols for tensor.extract_image_patches<>.\n  int stride = 2;  // Only same stride is supported.\n  // ColMajor\n  Tensor<float, 4> tensor(input_depth, input_rows, input_cols, input_batches);\n  // Initializes tensor with incrementing numbers.\n  for (int i = 0; i < tensor.size(); ++i) {\n    tensor.data()[i] = i + 1;\n  }\n  Tensor<float, 5> result = tensor.extract_image_patches(ksize, ksize, stride, stride, PADDING_SAME);\n\n  VERIFY_IS_EQUAL(result.dimension(0), input_depth);  // depth\n  VERIFY_IS_EQUAL(result.dimension(1), ksize);  // kernel rows\n  VERIFY_IS_EQUAL(result.dimension(2), ksize);  // kernel cols\n  VERIFY_IS_EQUAL(result.dimension(3), 2);  // number of patches\n  VERIFY_IS_EQUAL(result.dimension(4), input_batches);  // number of batches\n\n  // RowMajor\n  Tensor<float, 4, RowMajor> tensor_row_major = tensor.swap_layout();\n  VERIFY_IS_EQUAL(tensor.dimension(0), tensor_row_major.dimension(3));\n  VERIFY_IS_EQUAL(tensor.dimension(1), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor.dimension(2), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor.dimension(3), tensor_row_major.dimension(0));\n\n  Tensor<float, 5, RowMajor> result_row_major = tensor_row_major.extract_image_patches(ksize, ksize, stride, stride, PADDING_SAME);\n  VERIFY_IS_EQUAL(result.dimension(0), result_row_major.dimension(4));\n  VERIFY_IS_EQUAL(result.dimension(1), result_row_major.dimension(3));\n  VERIFY_IS_EQUAL(result.dimension(2), result_row_major.dimension(2));\n  VERIFY_IS_EQUAL(result.dimension(3), result_row_major.dimension(1));\n  VERIFY_IS_EQUAL(result.dimension(4), result_row_major.dimension(0));\n\n  // Based on the calculation described in TensorTraits.h, padding happens to be\n  // 0.\n  int row_padding = 0;\n  int col_padding = 0;\n\n  for (int i = 0; (i+stride+ksize-1) <= input_rows; i += stride) {  // input rows\n    for (int j = 0; (j+stride+ksize-1) <= input_cols; j += stride) {  // input cols\n      int patchId = i+input_rows*j;\n      for (int r = 0; r < ksize; ++r) {  // patch rows\n        for (int c = 0; c < ksize; ++c) {  // patch cols\n          for (int d = 0; d < input_depth; ++d) {  // depth\n            for (int b = 0; b < input_batches; ++b) {  // batch\n              float expected = 0.0f;\n              float expected_row_major = 0.0f;\n              int row_offset = r*stride + i - row_padding;\n              int col_offset = c*stride + j - col_padding;\n              if (row_offset >= 0 && col_offset >= 0 && row_offset < input_rows && col_offset < input_cols) {\n                expected = tensor(d, row_offset, col_offset, b);\n                expected_row_major = tensor_row_major(b, col_offset, row_offset, d);\n              }\n              // ColMajor\n              if (result(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (result_row_major(b, patchId, c, r, d) != expected_row_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result_row_major(b, patchId, c, r, d), expected_row_major);\n              // Check that ColMajor and RowMajor agree.\n              VERIFY_IS_EQUAL(expected, expected_row_major);\n            }\n          }\n        }\n      }\n    }\n  }\n}\n\n// Verifies that SAME padding, when computed as negative values, will be clipped\n// to zero.\nvoid test_patch_padding_same_negative_padding_clip_to_zero() {\n  int input_depth = 1;\n  int input_rows = 15;\n  int input_cols = 1;\n  int input_batches = 1;\n  int ksize = 1;  // Corresponds to the Rows and Cols for\n                  // tensor.extract_image_patches<>.\n  int row_stride = 5;\n  int col_stride = 1;\n  // ColMajor\n  Tensor<float, 4> tensor(input_depth, input_rows, input_cols, input_batches);\n  // Initializes tensor with incrementing numbers.\n  for (int i = 0; i < tensor.size(); ++i) {\n    tensor.data()[i] = i + 1;\n  }\n  Tensor<float, 5> result = tensor.extract_image_patches(\n      ksize, ksize, row_stride, col_stride, 1, 1, PADDING_SAME);\n  // row padding will be computed as -2 originally and then be clipped to 0.\n  VERIFY_IS_EQUAL(result.coeff(0), 1.0f);\n  VERIFY_IS_EQUAL(result.coeff(1), 6.0f);\n  VERIFY_IS_EQUAL(result.coeff(2), 11.0f);\n\n  VERIFY_IS_EQUAL(result.dimension(0), input_depth);    // depth\n  VERIFY_IS_EQUAL(result.dimension(1), ksize);          // kernel rows\n  VERIFY_IS_EQUAL(result.dimension(2), ksize);          // kernel cols\n  VERIFY_IS_EQUAL(result.dimension(3), 3);              // number of patches\n  VERIFY_IS_EQUAL(result.dimension(4), input_batches);  // number of batches\n\n  // RowMajor\n  Tensor<float, 4, RowMajor> tensor_row_major = tensor.swap_layout();\n  VERIFY_IS_EQUAL(tensor.dimension(0), tensor_row_major.dimension(3));\n  VERIFY_IS_EQUAL(tensor.dimension(1), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor.dimension(2), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor.dimension(3), tensor_row_major.dimension(0));\n\n  Tensor<float, 5, RowMajor> result_row_major =\n      tensor_row_major.extract_image_patches(ksize, ksize, row_stride,\n                                             col_stride, 1, 1, PADDING_SAME);\n  VERIFY_IS_EQUAL(result_row_major.coeff(0), 1.0f);\n  VERIFY_IS_EQUAL(result_row_major.coeff(1), 6.0f);\n  VERIFY_IS_EQUAL(result_row_major.coeff(2), 11.0f);\n\n  VERIFY_IS_EQUAL(result.dimension(0), result_row_major.dimension(4));\n  VERIFY_IS_EQUAL(result.dimension(1), result_row_major.dimension(3));\n  VERIFY_IS_EQUAL(result.dimension(2), result_row_major.dimension(2));\n  VERIFY_IS_EQUAL(result.dimension(3), result_row_major.dimension(1));\n  VERIFY_IS_EQUAL(result.dimension(4), result_row_major.dimension(0));\n}\n\nvoid test_patch_no_extra_dim()\n{\n  Tensor<float, 3> tensor(2,3,5);\n  tensor.setRandom();\n  Tensor<float, 3, RowMajor> tensor_row_major = tensor.swap_layout();\n  VERIFY_IS_EQUAL(tensor.dimension(0), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor.dimension(1), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor.dimension(2), tensor_row_major.dimension(0));\n\n  // Single pixel patch: ColMajor\n  Tensor<float, 4> single_pixel_patch;\n  single_pixel_patch = tensor.extract_image_patches(1, 1);\n  VERIFY_IS_EQUAL(single_pixel_patch.dimension(0), 2);\n  VERIFY_IS_EQUAL(single_pixel_patch.dimension(1), 1);\n  VERIFY_IS_EQUAL(single_pixel_patch.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_pixel_patch.dimension(3), 3*5);\n\n  // Single pixel patch: RowMajor\n  Tensor<float, 4, RowMajor> single_pixel_patch_row_major;\n  single_pixel_patch_row_major = tensor_row_major.extract_image_patches(1, 1);\n  VERIFY_IS_EQUAL(single_pixel_patch_row_major.dimension(0), 3*5);\n  VERIFY_IS_EQUAL(single_pixel_patch_row_major.dimension(1), 1);\n  VERIFY_IS_EQUAL(single_pixel_patch_row_major.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_pixel_patch_row_major.dimension(3), 2);\n\n  for (int i = 0; i < tensor.size(); ++i) {\n    // ColMajor\n    if (tensor.data()[i] != single_pixel_patch.data()[i]) {\n      std::cout << \"Mismatch detected at index \" << i << \" : \" << tensor.data()[i] << \" vs \" << single_pixel_patch.data()[i] << std::endl;\n    }\n    VERIFY_IS_EQUAL(single_pixel_patch.data()[i], tensor.data()[i]);\n    // RowMajor\n    if (tensor_row_major.data()[i] != single_pixel_patch_row_major.data()[i]) {\n      std::cout << \"Mismatch detected at index \" << i << \" : \"\n           << tensor.data()[i] << \" vs \"\n           << single_pixel_patch_row_major.data()[i] << std::endl;\n    }\n    VERIFY_IS_EQUAL(single_pixel_patch_row_major.data()[i],\n                    tensor_row_major.data()[i]);\n    VERIFY_IS_EQUAL(tensor.data()[i], tensor_row_major.data()[i]);\n    VERIFY_IS_EQUAL(single_pixel_patch.data()[i],\n                    single_pixel_patch_row_major.data()[i]);\n  }\n\n  // Entire image patch: ColMajor\n  Tensor<float, 4> entire_image_patch;\n  entire_image_patch = tensor.extract_image_patches(3, 5);\n  VERIFY_IS_EQUAL(entire_image_patch.dimension(0), 2);\n  VERIFY_IS_EQUAL(entire_image_patch.dimension(1), 3);\n  VERIFY_IS_EQUAL(entire_image_patch.dimension(2), 5);\n  VERIFY_IS_EQUAL(entire_image_patch.dimension(3), 3*5);\n\n  // Entire image patch: RowMajor\n  Tensor<float, 4, RowMajor> entire_image_patch_row_major;\n  entire_image_patch_row_major = tensor_row_major.extract_image_patches(3, 5);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(0), 3*5);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(1), 5);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(2), 3);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(3), 2);\n\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      int patchId = i+3*j;\n      for (int r = 0; r < 3; ++r) {\n        for (int c = 0; c < 5; ++c) {\n          for (int d = 0; d < 2; ++d) {\n            float expected = 0.0f;\n            float expected_row_major = 0.0f;\n            if (r-1+i >= 0 && c-2+j >= 0 && r-1+i < 3 && c-2+j < 5) {\n              expected = tensor(d, r-1+i, c-2+j);\n              expected_row_major = tensor_row_major(c-2+j, r-1+i, d);\n            }\n            // ColMajor\n            if (entire_image_patch(d, r, c, patchId) != expected) {\n              std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << std::endl;\n            }\n            VERIFY_IS_EQUAL(entire_image_patch(d, r, c, patchId), expected);\n            // RowMajor\n            if (entire_image_patch_row_major(patchId, c, r, d) !=\n                expected_row_major) {\n              std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << std::endl;\n            }\n            VERIFY_IS_EQUAL(entire_image_patch_row_major(patchId, c, r, d),\n                            expected_row_major);\n            // Check that ColMajor and RowMajor agree.\n            VERIFY_IS_EQUAL(expected, expected_row_major);\n          }\n        }\n      }\n    }\n  }\n\n  // 2D patch: ColMajor\n  Tensor<float, 4> twod_patch;\n  twod_patch = tensor.extract_image_patches(2, 2);\n  VERIFY_IS_EQUAL(twod_patch.dimension(0), 2);\n  VERIFY_IS_EQUAL(twod_patch.dimension(1), 2);\n  VERIFY_IS_EQUAL(twod_patch.dimension(2), 2);\n  VERIFY_IS_EQUAL(twod_patch.dimension(3), 3*5);\n\n  // 2D patch: RowMajor\n  Tensor<float, 4, RowMajor> twod_patch_row_major;\n  twod_patch_row_major = tensor_row_major.extract_image_patches(2, 2);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(0), 3*5);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(1), 2);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(2), 2);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(3), 2);\n\n  // Based on the calculation described in TensorTraits.h, padding happens to be 0.\n  int row_padding = 0;\n  int col_padding = 0;\n  int stride = 1;\n\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      int patchId = i+3*j;\n      for (int r = 0; r < 2; ++r) {\n        for (int c = 0; c < 2; ++c) {\n          for (int d = 0; d < 2; ++d) {\n            float expected = 0.0f;\n            float expected_row_major = 0.0f;\n            int row_offset = r*stride + i - row_padding;\n            int col_offset = c*stride + j - col_padding;\n            // ColMajor\n            if (row_offset >= 0 && col_offset >= 0 && row_offset < tensor.dimension(1) && col_offset < tensor.dimension(2)) {\n              expected = tensor(d, row_offset, col_offset);\n            }\n            if (twod_patch(d, r, c, patchId) != expected) {\n              std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << std::endl;\n            }\n            VERIFY_IS_EQUAL(twod_patch(d, r, c, patchId), expected);\n            // RowMajor\n            if (row_offset >= 0 && col_offset >= 0 && row_offset < tensor_row_major.dimension(1) && col_offset < tensor_row_major.dimension(0)) {\n              expected_row_major = tensor_row_major(col_offset, row_offset, d);\n            }\n            if (twod_patch_row_major(patchId, c, r, d) != expected_row_major) {\n              std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << std::endl;\n            }\n            VERIFY_IS_EQUAL(twod_patch_row_major(patchId, c, r, d), expected_row_major);\n            // Check that ColMajor and RowMajor agree.\n            VERIFY_IS_EQUAL(expected, expected_row_major);\n          }\n        }\n      }\n    }\n  }\n}\n\nvoid test_imagenet_patches()\n{\n  // Test the code on typical configurations used by the 'imagenet' benchmarks at\n  // https://github.com/soumith/convnet-benchmarks\n  // ColMajor\n  Tensor<float, 4> l_in(3, 128, 128, 16);\n  l_in.setRandom();\n  Tensor<float, 5> l_out = l_in.extract_image_patches(11, 11);\n  VERIFY_IS_EQUAL(l_out.dimension(0), 3);\n  VERIFY_IS_EQUAL(l_out.dimension(1), 11);\n  VERIFY_IS_EQUAL(l_out.dimension(2), 11);\n  VERIFY_IS_EQUAL(l_out.dimension(3), 128*128);\n  VERIFY_IS_EQUAL(l_out.dimension(4), 16);\n\n  // RowMajor\n  Tensor<float, 5, RowMajor> l_out_row_major = l_in.swap_layout().extract_image_patches(11, 11);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(0), 16);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(1), 128*128);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(2), 11);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(3), 11);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(4), 3);\n\n  for (int b = 0; b < 16; ++b) {\n    for (int i = 0; i < 128; ++i) {\n      for (int j = 0; j < 128; ++j) {\n        int patchId = i+128*j;\n        for (int c = 0; c < 11; ++c) {\n          for (int r = 0; r < 11; ++r) {\n            for (int d = 0; d < 3; ++d) {\n              float expected = 0.0f;\n              if (r-5+i >= 0 && c-5+j >= 0 && r-5+i < 128 && c-5+j < 128) {\n                expected = l_in(d, r-5+i, c-5+j, b);\n              }\n              // ColMajor\n              if (l_out(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (l_out_row_major(b, patchId, c, r, d) !=\n                  expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j\n                     << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b\n                     << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_row_major(b, patchId, c, r, d),\n                              expected);\n            }\n          }\n        }\n      }\n    }\n  }\n\n  // ColMajor\n  l_in.resize(16, 64, 64, 32);\n  l_in.setRandom();\n  l_out = l_in.extract_image_patches(9, 9);\n  VERIFY_IS_EQUAL(l_out.dimension(0), 16);\n  VERIFY_IS_EQUAL(l_out.dimension(1), 9);\n  VERIFY_IS_EQUAL(l_out.dimension(2), 9);\n  VERIFY_IS_EQUAL(l_out.dimension(3), 64*64);\n  VERIFY_IS_EQUAL(l_out.dimension(4), 32);\n\n  // RowMajor\n  l_out_row_major = l_in.swap_layout().extract_image_patches(9, 9);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(0), 32);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(1), 64*64);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(2), 9);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(3), 9);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(4), 16);\n\n  for (int b = 0; b < 32; ++b) {\n    for (int i = 0; i < 64; ++i) {\n      for (int j = 0; j < 64; ++j) {\n        int patchId = i+64*j;\n        for (int c = 0; c < 9; ++c) {\n          for (int r = 0; r < 9; ++r) {\n            for (int d = 0; d < 16; ++d) {\n              float expected = 0.0f;\n              if (r-4+i >= 0 && c-4+j >= 0 && r-4+i < 64 && c-4+j < 64) {\n                expected = l_in(d, r-4+i, c-4+j, b);\n              }\n              // ColMajor\n              if (l_out(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (l_out_row_major(b, patchId, c, r, d) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_row_major(b, patchId, c, r, d), expected);\n            }\n          }\n        }\n      }\n    }\n  }\n\n  // ColMajor\n  l_in.resize(32, 16, 16, 32);\n  l_in.setRandom();\n  l_out = l_in.extract_image_patches(7, 7);\n  VERIFY_IS_EQUAL(l_out.dimension(0), 32);\n  VERIFY_IS_EQUAL(l_out.dimension(1), 7);\n  VERIFY_IS_EQUAL(l_out.dimension(2), 7);\n  VERIFY_IS_EQUAL(l_out.dimension(3), 16*16);\n  VERIFY_IS_EQUAL(l_out.dimension(4), 32);\n\n  // RowMajor\n  l_out_row_major = l_in.swap_layout().extract_image_patches(7, 7);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(0), 32);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(1), 16*16);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(2), 7);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(3), 7);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(4), 32);\n\n  for (int b = 0; b < 32; ++b) {\n    for (int i = 0; i < 16; ++i) {\n      for (int j = 0; j < 16; ++j) {\n        int patchId = i+16*j;\n        for (int c = 0; c < 7; ++c) {\n          for (int r = 0; r < 7; ++r) {\n            for (int d = 0; d < 32; ++d) {\n              float expected = 0.0f;\n              if (r-3+i >= 0 && c-3+j >= 0 && r-3+i < 16 && c-3+j < 16) {\n                expected = l_in(d, r-3+i, c-3+j, b);\n              }\n              // ColMajor\n              if (l_out(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (l_out_row_major(b, patchId, c, r, d) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_row_major(b, patchId, c, r, d), expected);\n            }\n          }\n        }\n      }\n    }\n  }\n\n  // ColMajor\n  l_in.resize(64, 13, 13, 32);\n  l_in.setRandom();\n  l_out = l_in.extract_image_patches(3, 3);\n  VERIFY_IS_EQUAL(l_out.dimension(0), 64);\n  VERIFY_IS_EQUAL(l_out.dimension(1), 3);\n  VERIFY_IS_EQUAL(l_out.dimension(2), 3);\n  VERIFY_IS_EQUAL(l_out.dimension(3), 13*13);\n  VERIFY_IS_EQUAL(l_out.dimension(4), 32);\n\n  // RowMajor\n  l_out_row_major = l_in.swap_layout().extract_image_patches(3, 3);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(0), 32);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(1), 13*13);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(2), 3);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(3), 3);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(4), 64);\n\n  for (int b = 0; b < 32; ++b) {\n    for (int i = 0; i < 13; ++i) {\n      for (int j = 0; j < 13; ++j) {\n        int patchId = i+13*j;\n        for (int c = 0; c < 3; ++c) {\n          for (int r = 0; r < 3; ++r) {\n            for (int d = 0; d < 64; ++d) {\n              float expected = 0.0f;\n              if (r-1+i >= 0 && c-1+j >= 0 && r-1+i < 13 && c-1+j < 13) {\n                expected = l_in(d, r-1+i, c-1+j, b);\n              }\n              // ColMajor\n              if (l_out(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (l_out_row_major(b, patchId, c, r, d) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_row_major(b, patchId, c, r, d), expected);\n            }\n          }\n        }\n      }\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_image_patch)\n{\n  CALL_SUBTEST_1(test_simple_patch());\n  CALL_SUBTEST_2(test_patch_no_extra_dim());\n  CALL_SUBTEST_3(test_patch_padding_valid());\n  CALL_SUBTEST_4(test_patch_padding_valid_same_value());\n  CALL_SUBTEST_5(test_patch_padding_same());\n  CALL_SUBTEST_6(test_imagenet_patches());\n  CALL_SUBTEST_7(test_patch_padding_same_negative_padding_clip_to_zero());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_image_patch_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nstatic const int DataLayout = ColMajor;\n\ntemplate <typename DataType, typename IndexType>\nstatic void test_simple_image_patch_sycl(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  array<IndexType, 4> tensorColMajorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  array<IndexType, 4> tensorRowMajorRange = {{sizeDim4, sizeDim3, sizeDim2, sizeDim1}};\n  Tensor<DataType, 4, DataLayout,IndexType> tensor_col_major(tensorColMajorRange);\n  Tensor<DataType, 4, RowMajor,IndexType> tensor_row_major(tensorRowMajorRange);\n  tensor_col_major.setRandom();\n\n  DataType* gpu_data_col_major  = static_cast<DataType*>(sycl_device.allocate(tensor_col_major.size()*sizeof(DataType)));\n  DataType* gpu_data_row_major  = static_cast<DataType*>(sycl_device.allocate(tensor_row_major.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 4, ColMajor, IndexType>> gpu_col_major(gpu_data_col_major, tensorColMajorRange);\n  TensorMap<Tensor<DataType, 4, RowMajor, IndexType>> gpu_row_major(gpu_data_row_major, tensorRowMajorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_col_major, tensor_col_major.data(),(tensor_col_major.size())*sizeof(DataType));\n  gpu_row_major.device(sycl_device)=gpu_col_major.swap_layout();\n  sycl_device.memcpyDeviceToHost(tensor_row_major.data(), gpu_data_row_major, (tensor_col_major.size())*sizeof(DataType));\n\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(0), tensor_row_major.dimension(3));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(1), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(2), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(3), tensor_row_major.dimension(0));\n\n  // Single pixel patch: ColMajor\n  array<IndexType, 5> patchColMajorTensorRange={{sizeDim1, 1, 1, sizeDim2*sizeDim3, sizeDim4}};\n  Tensor<DataType, 5, DataLayout,IndexType> single_patch_col_major(patchColMajorTensorRange);\n  size_t patchTensorBuffSize =single_patch_col_major.size()*sizeof(DataType);\n  DataType* gpu_data_single_patch_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_single_patch_col_major(gpu_data_single_patch_col_major, patchColMajorTensorRange);\n  gpu_single_patch_col_major.device(sycl_device)=gpu_col_major.extract_image_patches(1, 1);\n  sycl_device.memcpyDeviceToHost(single_patch_col_major.data(), gpu_data_single_patch_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(single_patch_col_major.dimension(0), 2);\n  VERIFY_IS_EQUAL(single_patch_col_major.dimension(1), 1);\n  VERIFY_IS_EQUAL(single_patch_col_major.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_patch_col_major.dimension(3), 3*5);\n  VERIFY_IS_EQUAL(single_patch_col_major.dimension(4), 7);\n\n  // Single pixel patch: RowMajor\n  array<IndexType, 5> patchRowMajorTensorRange={{sizeDim4, sizeDim2*sizeDim3, 1, 1, sizeDim1}};\n  Tensor<DataType, 5, RowMajor,IndexType> single_patch_row_major(patchRowMajorTensorRange);\n  patchTensorBuffSize =single_patch_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_single_patch_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, RowMajor,IndexType>> gpu_single_patch_row_major(gpu_data_single_patch_row_major, patchRowMajorTensorRange);\n  gpu_single_patch_row_major.device(sycl_device)=gpu_row_major.extract_image_patches(1, 1);\n  sycl_device.memcpyDeviceToHost(single_patch_row_major.data(), gpu_data_single_patch_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(single_patch_row_major.dimension(0), 7);\n  VERIFY_IS_EQUAL(single_patch_row_major.dimension(1), 3*5);\n  VERIFY_IS_EQUAL(single_patch_row_major.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_patch_row_major.dimension(3), 1);\n  VERIFY_IS_EQUAL(single_patch_row_major.dimension(4), 2);\n\n  for (IndexType i = 0; i < tensor_col_major.size(); ++i) {\n    // ColMajor\n    if (tensor_col_major.data()[i] != single_patch_col_major.data()[i]) {\n      std::cout << \"Mismatch detected at index colmajor \" << i << \" : \"\n           << tensor_col_major.data()[i] << \" vs \" << single_patch_col_major.data()[i]\n           << std::endl;\n    }\n    VERIFY_IS_EQUAL(single_patch_col_major.data()[i], tensor_col_major.data()[i]);\n    // RowMajor\n    if (tensor_row_major.data()[i] != single_patch_row_major.data()[i]) {\n      std::cout << \"Mismatch detected at index row major\" << i << \" : \"\n           << tensor_row_major.data()[i] << \" vs \"\n           << single_patch_row_major.data()[i] << std::endl;\n    }\n    VERIFY_IS_EQUAL(single_patch_row_major.data()[i],\n                    tensor_row_major.data()[i]);\n    VERIFY_IS_EQUAL(tensor_col_major.data()[i], tensor_row_major.data()[i]);\n    VERIFY_IS_EQUAL(single_patch_col_major.data()[i],\n                    single_patch_row_major.data()[i]);\n  }\n\n\n  // Entire image patch: ColMajor\n  patchColMajorTensorRange={{sizeDim1, sizeDim2, sizeDim3, sizeDim2*sizeDim3, sizeDim4}};\n  Tensor<DataType, 5, DataLayout,IndexType> entire_image_patch_col_major(patchColMajorTensorRange);\n  patchTensorBuffSize =entire_image_patch_col_major.size()*sizeof(DataType);\n  DataType* gpu_data_entire_image_patch_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_entire_image_patch_col_major(gpu_data_entire_image_patch_col_major, patchColMajorTensorRange);\n  gpu_entire_image_patch_col_major.device(sycl_device)=gpu_col_major.extract_image_patches(3, 5);\n  sycl_device.memcpyDeviceToHost(entire_image_patch_col_major.data(), gpu_data_entire_image_patch_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(entire_image_patch_col_major.dimension(0), 2);\n  VERIFY_IS_EQUAL(entire_image_patch_col_major.dimension(1), 3);\n  VERIFY_IS_EQUAL(entire_image_patch_col_major.dimension(2), 5);\n  VERIFY_IS_EQUAL(entire_image_patch_col_major.dimension(3), 3*5);\n  VERIFY_IS_EQUAL(entire_image_patch_col_major.dimension(4), 7);\n\n  // Entire image patch: RowMajor\n  patchRowMajorTensorRange={{sizeDim4, sizeDim2*sizeDim3, sizeDim3, sizeDim2, sizeDim1}};\n  Tensor<DataType, 5, RowMajor,IndexType> entire_image_patch_row_major(patchRowMajorTensorRange);\n  patchTensorBuffSize =entire_image_patch_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_entire_image_patch_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, RowMajor,IndexType>> gpu_entire_image_patch_row_major(gpu_data_entire_image_patch_row_major, patchRowMajorTensorRange);\n  gpu_entire_image_patch_row_major.device(sycl_device)=gpu_row_major.extract_image_patches(3, 5);\n  sycl_device.memcpyDeviceToHost(entire_image_patch_row_major.data(), gpu_data_entire_image_patch_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(0), 7);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(1), 3*5);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(2), 5);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(3), 3);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(4), 2);\n\n  for (IndexType i = 0; i < 3; ++i) {\n    for (IndexType j = 0; j < 5; ++j) {\n      IndexType patchId = i+3*j;\n      for (IndexType r = 0; r < 3; ++r) {\n        for (IndexType c = 0; c < 5; ++c) {\n          for (IndexType d = 0; d < 2; ++d) {\n            for (IndexType b = 0; b < 7; ++b) {\n              DataType expected_col_major = 0.0f;\n              DataType expected_row_major = 0.0f;\n              if (r-1+i >= 0 && c-2+j >= 0 && r-1+i < 3 && c-2+j < 5) {\n                expected_col_major = tensor_col_major(d, r-1+i, c-2+j, b);\n                expected_row_major = tensor_row_major(b, c-2+j, r-1+i, d);\n              }\n              // ColMajor\n              if (entire_image_patch_col_major(d, r, c, patchId, b) != expected_col_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(entire_image_patch_col_major(d, r, c, patchId, b), expected_col_major);\n              // RowMajor\n              if (entire_image_patch_row_major(b, patchId, c, r, d) !=\n                  expected_row_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j\n                     << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b\n                     << std::endl;\n              }\n              VERIFY_IS_EQUAL(entire_image_patch_row_major(b, patchId, c, r, d),\n                              expected_row_major);\n              // Check that ColMajor and RowMajor agree.\n              VERIFY_IS_EQUAL(expected_col_major, expected_row_major);\n            }\n          }\n        }\n      }\n    }\n  }\n\n  // 2D patch: ColMajor\n  patchColMajorTensorRange={{sizeDim1, 2, 2, sizeDim2*sizeDim3, sizeDim4}};\n  Tensor<DataType, 5, DataLayout,IndexType> twod_patch_col_major(patchColMajorTensorRange);\n  patchTensorBuffSize =twod_patch_col_major.size()*sizeof(DataType);\n  DataType* gpu_data_twod_patch_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_twod_patch_col_major(gpu_data_twod_patch_col_major, patchColMajorTensorRange);\n  gpu_twod_patch_col_major.device(sycl_device)=gpu_col_major.extract_image_patches(2, 2);\n  sycl_device.memcpyDeviceToHost(twod_patch_col_major.data(), gpu_data_twod_patch_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(twod_patch_col_major.dimension(0), 2);\n  VERIFY_IS_EQUAL(twod_patch_col_major.dimension(1), 2);\n  VERIFY_IS_EQUAL(twod_patch_col_major.dimension(2), 2);\n  VERIFY_IS_EQUAL(twod_patch_col_major.dimension(3), 3*5);\n  VERIFY_IS_EQUAL(twod_patch_col_major.dimension(4), 7);\n\n  // 2D patch: RowMajor\n  patchRowMajorTensorRange={{sizeDim4, sizeDim2*sizeDim3, 2, 2, sizeDim1}};\n  Tensor<DataType, 5, RowMajor,IndexType> twod_patch_row_major(patchRowMajorTensorRange);\n  patchTensorBuffSize =twod_patch_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_twod_patch_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, RowMajor,IndexType>> gpu_twod_patch_row_major(gpu_data_twod_patch_row_major, patchRowMajorTensorRange);\n  gpu_twod_patch_row_major.device(sycl_device)=gpu_row_major.extract_image_patches(2, 2);\n  sycl_device.memcpyDeviceToHost(twod_patch_row_major.data(), gpu_data_twod_patch_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(0), 7);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(1), 3*5);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(2), 2);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(3), 2);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(4), 2);\n\n\n  // Based on the calculation described in TensorTraits.h, padding happens to be 0.\n  IndexType row_padding = 0;\n  IndexType col_padding = 0;\n  IndexType stride = 1;\n\n  for (IndexType i = 0; i < 3; ++i) {\n    for (IndexType j = 0; j < 5; ++j) {\n      IndexType patchId = i+3*j;\n      for (IndexType r = 0; r < 2; ++r) {\n        for (IndexType c = 0; c < 2; ++c) {\n          for (IndexType d = 0; d < 2; ++d) {\n            for (IndexType b = 0; b < 7; ++b) {\n              DataType expected_col_major = 0.0f;\n              DataType expected_row_major = 0.0f;\n              IndexType row_offset = r*stride + i - row_padding;\n              IndexType col_offset = c*stride + j - col_padding;\n              // ColMajor\n              if (row_offset >= 0 && col_offset >= 0 && row_offset < tensor_col_major.dimension(1) && col_offset < tensor_col_major.dimension(2)) {\n                expected_col_major = tensor_col_major(d, row_offset, col_offset, b);\n              }\n              if (twod_patch_col_major(d, r, c, patchId, b) != expected_col_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(twod_patch_col_major(d, r, c, patchId, b), expected_col_major);\n\n              // RowMajor\n              if (row_offset >= 0 && col_offset >= 0 && row_offset < tensor_row_major.dimension(2) && col_offset < tensor_row_major.dimension(1)) {\n                expected_row_major = tensor_row_major(b, col_offset, row_offset, d);\n\n              }\n              if (twod_patch_row_major(b, patchId, c, r, d) != expected_row_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(twod_patch_row_major(b, patchId, c, r, d), expected_row_major);\n              // Check that ColMajor and RowMajor agree.\n              VERIFY_IS_EQUAL(expected_col_major, expected_row_major);\n            }\n          }\n        }\n      }\n    }\n  }\n\n  sycl_device.deallocate(gpu_data_col_major);\n  sycl_device.deallocate(gpu_data_row_major);\n  sycl_device.deallocate(gpu_data_single_patch_col_major);\n  sycl_device.deallocate(gpu_data_single_patch_row_major);\n  sycl_device.deallocate(gpu_data_entire_image_patch_col_major);\n  sycl_device.deallocate(gpu_data_entire_image_patch_row_major);\n  sycl_device.deallocate(gpu_data_twod_patch_col_major);\n  sycl_device.deallocate(gpu_data_twod_patch_row_major);\n\n}\n\n\n// Verifies VALID padding (no padding) with incrementing values.\ntemplate <typename DataType, typename IndexType>\nstatic void test_patch_padding_valid_sycl(const Eigen::SyclDevice& sycl_device){\n  IndexType input_depth = 3;\n  IndexType input_rows = 3;\n  IndexType input_cols = 3;\n  IndexType input_batches = 1;\n  IndexType ksize = 2;  // Corresponds to the Rows and Cols for tensor.extract_image_patches<>.\n  IndexType stride = 2;  // Only same stride is supported.\n\n  array<IndexType, 4> tensorColMajorRange = {{input_depth, input_rows, input_cols, input_batches}};\n  array<IndexType, 4> tensorRowMajorRange = {{input_batches, input_cols, input_rows, input_depth}};\n  Tensor<DataType, 4, DataLayout,IndexType> tensor_col_major(tensorColMajorRange);\n  Tensor<DataType, 4, RowMajor,IndexType> tensor_row_major(tensorRowMajorRange);\n\n  DataType* gpu_data_col_major  = static_cast<DataType*>(sycl_device.allocate(tensor_col_major.size()*sizeof(DataType)));\n  DataType* gpu_data_row_major  = static_cast<DataType*>(sycl_device.allocate(tensor_row_major.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 4, ColMajor, IndexType>> gpu_col_major(gpu_data_col_major, tensorColMajorRange);\n  TensorMap<Tensor<DataType, 4, RowMajor, IndexType>> gpu_row_major(gpu_data_row_major, tensorRowMajorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_col_major, tensor_col_major.data(),(tensor_col_major.size())*sizeof(DataType));\n  gpu_row_major.device(sycl_device)=gpu_col_major.swap_layout();\n  sycl_device.memcpyDeviceToHost(tensor_row_major.data(), gpu_data_row_major, (tensor_col_major.size())*sizeof(DataType));\n\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(0), tensor_row_major.dimension(3));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(1), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(2), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(3), tensor_row_major.dimension(0));\n\n  // Initializes tensor with incrementing numbers.\n  for (IndexType i = 0; i < tensor_col_major.size(); ++i) {\n    tensor_col_major.data()[i] = i + 1;\n  }\n  // ColMajor\n  array<IndexType, 5> patchColMajorTensorRange={{input_depth, ksize, ksize, 1, input_batches}};\n  Tensor<DataType, 5, DataLayout,IndexType> result_col_major(patchColMajorTensorRange);\n  size_t patchTensorBuffSize =result_col_major.size()*sizeof(DataType);\n  DataType* gpu_data_result_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_result_col_major(gpu_data_result_col_major, patchColMajorTensorRange);\n  gpu_result_col_major.device(sycl_device)=gpu_col_major.extract_image_patches(ksize, ksize, stride, stride, 1, 1, PADDING_VALID);\n  sycl_device.memcpyDeviceToHost(result_col_major.data(), gpu_data_result_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(result_col_major.dimension(0), input_depth);  // depth\n  VERIFY_IS_EQUAL(result_col_major.dimension(1), ksize);  // kernel rows\n  VERIFY_IS_EQUAL(result_col_major.dimension(2), ksize);  // kernel cols\n  VERIFY_IS_EQUAL(result_col_major.dimension(3), 1);  // number of patches\n  VERIFY_IS_EQUAL(result_col_major.dimension(4), input_batches);  // number of batches\n\n  // RowMajor\n  array<IndexType, 5> patchRowMajorTensorRange={{input_batches, 1, ksize, ksize, input_depth }};\n  Tensor<DataType, 5, RowMajor,IndexType> result_row_major(patchRowMajorTensorRange);\n  patchTensorBuffSize =result_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_result_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, RowMajor,IndexType>> gpu_result_row_major(gpu_data_result_row_major, patchRowMajorTensorRange);\n  gpu_result_row_major.device(sycl_device)=gpu_row_major.extract_image_patches(ksize, ksize, stride, stride, 1, 1, PADDING_VALID);\n  sycl_device.memcpyDeviceToHost(result_row_major.data(), gpu_data_result_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(result_col_major.dimension(0), result_row_major.dimension(4));\n  VERIFY_IS_EQUAL(result_col_major.dimension(1), result_row_major.dimension(3));\n  VERIFY_IS_EQUAL(result_col_major.dimension(2), result_row_major.dimension(2));\n  VERIFY_IS_EQUAL(result_col_major.dimension(3), result_row_major.dimension(1));\n  VERIFY_IS_EQUAL(result_col_major.dimension(4), result_row_major.dimension(0));\n\n  // No padding is carried out.\n  IndexType row_padding = 0;\n  IndexType col_padding = 0;\n\n  for (IndexType i = 0; (i+stride+ksize-1) < input_rows; i += stride) {  // input rows\n    for (IndexType j = 0; (j+stride+ksize-1) < input_cols; j += stride) {  // input cols\n      IndexType patchId = i+input_rows*j;\n      for (IndexType r = 0; r < ksize; ++r) {  // patch rows\n        for (IndexType c = 0; c < ksize; ++c) {  // patch cols\n          for (IndexType d = 0; d < input_depth; ++d) {  // depth\n            for (IndexType b = 0; b < input_batches; ++b) {  // batch\n              DataType expected_col_major = 0.0f;\n              DataType expected_row_major = 0.0f;\n              IndexType row_offset = r + i - row_padding;\n              IndexType col_offset = c + j - col_padding;\n              if (row_offset >= 0 && col_offset >= 0 && row_offset < input_rows && col_offset < input_cols) {\n                expected_col_major = tensor_col_major(d, row_offset, col_offset, b);\n                expected_row_major = tensor_row_major(b, col_offset, row_offset, d);\n              }\n              // ColMajor\n              if (result_col_major(d, r, c, patchId, b) != expected_col_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result_col_major(d, r, c, patchId, b), expected_col_major);\n              // RowMajor\n              if (result_row_major(b, patchId, c, r, d) != expected_row_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result_row_major(b, patchId, c, r, d), expected_row_major);\n              // Check that ColMajor and RowMajor agree.\n              VERIFY_IS_EQUAL(expected_col_major, expected_row_major);\n            }\n          }\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data_col_major);\n  sycl_device.deallocate(gpu_data_row_major);\n  sycl_device.deallocate(gpu_data_result_col_major);\n  sycl_device.deallocate(gpu_data_result_row_major);\n}\n\n// Verifies VALID padding (no padding) with the same value.\ntemplate <typename DataType, typename IndexType>\nstatic void test_patch_padding_valid_same_value_sycl(const Eigen::SyclDevice& sycl_device){\n  IndexType input_depth = 1;\n  IndexType input_rows = 5;\n  IndexType input_cols = 5;\n  IndexType input_batches = 2;\n  IndexType ksize = 3;  // Corresponds to the Rows and Cols for tensor.extract_image_patches<>.\n  IndexType stride = 2;  // Only same stride is supported.\n  // ColMajor\n\n  array<IndexType, 4> tensorColMajorRange = {{input_depth, input_rows, input_cols, input_batches}};\n  array<IndexType, 4> tensorRowMajorRange = {{input_batches, input_cols, input_rows, input_depth}};\n  Tensor<DataType, 4, DataLayout,IndexType> tensor_col_major(tensorColMajorRange);\n  Tensor<DataType, 4, RowMajor,IndexType> tensor_row_major(tensorRowMajorRange);\n\n  DataType* gpu_data_col_major  = static_cast<DataType*>(sycl_device.allocate(tensor_col_major.size()*sizeof(DataType)));\n  DataType* gpu_data_row_major  = static_cast<DataType*>(sycl_device.allocate(tensor_row_major.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 4, ColMajor, IndexType>> gpu_col_major(gpu_data_col_major, tensorColMajorRange);\n  TensorMap<Tensor<DataType, 4, RowMajor, IndexType>> gpu_row_major(gpu_data_row_major, tensorRowMajorRange);\n  gpu_col_major.device(sycl_device)=gpu_col_major.constant(11.0f);\n  gpu_row_major.device(sycl_device)=gpu_col_major.swap_layout();\n  sycl_device.memcpyDeviceToHost(tensor_col_major.data(), gpu_data_col_major, (tensor_col_major.size())*sizeof(DataType));\n  sycl_device.memcpyDeviceToHost(tensor_row_major.data(), gpu_data_row_major, (tensor_row_major.size())*sizeof(DataType));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(0), tensor_row_major.dimension(3));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(1), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(2), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(3), tensor_row_major.dimension(0));\n\n  array<IndexType, 5> patchColMajorTensorRange={{input_depth, ksize, ksize, 4, input_batches}};\n  Tensor<DataType, 5, DataLayout,IndexType> result_col_major(patchColMajorTensorRange);\n  size_t patchTensorBuffSize =result_col_major.size()*sizeof(DataType);\n  DataType* gpu_data_result_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_result_col_major(gpu_data_result_col_major, patchColMajorTensorRange);\n  gpu_result_col_major.device(sycl_device)=gpu_col_major.extract_image_patches(ksize, ksize, stride, stride, 1, 1, PADDING_VALID);\n  sycl_device.memcpyDeviceToHost(result_col_major.data(), gpu_data_result_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(result_col_major.dimension(0), input_depth);  // depth\n  VERIFY_IS_EQUAL(result_col_major.dimension(1), ksize);  // kernel rows\n  VERIFY_IS_EQUAL(result_col_major.dimension(2), ksize);  // kernel cols\n  VERIFY_IS_EQUAL(result_col_major.dimension(3), 4);  // number of patches\n  VERIFY_IS_EQUAL(result_col_major.dimension(4), input_batches);  // number of batches\n\n  // RowMajor\n  array<IndexType, 5> patchRowMajorTensorRange={{input_batches, 4, ksize, ksize, input_depth }};\n  Tensor<DataType, 5, RowMajor,IndexType> result_row_major(patchRowMajorTensorRange);\n  patchTensorBuffSize =result_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_result_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, RowMajor,IndexType>> gpu_result_row_major(gpu_data_result_row_major, patchRowMajorTensorRange);\n  gpu_result_row_major.device(sycl_device)=gpu_row_major.extract_image_patches(ksize, ksize, stride, stride, 1, 1, PADDING_VALID);\n  sycl_device.memcpyDeviceToHost(result_row_major.data(), gpu_data_result_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(result_col_major.dimension(0), result_row_major.dimension(4));\n  VERIFY_IS_EQUAL(result_col_major.dimension(1), result_row_major.dimension(3));\n  VERIFY_IS_EQUAL(result_col_major.dimension(2), result_row_major.dimension(2));\n  VERIFY_IS_EQUAL(result_col_major.dimension(3), result_row_major.dimension(1));\n  VERIFY_IS_EQUAL(result_col_major.dimension(4), result_row_major.dimension(0));\n\n  // No padding is carried out.\n  IndexType row_padding = 0;\n  IndexType col_padding = 0;\n\n  for (IndexType i = 0; (i+stride+ksize-1) <= input_rows; i += stride) {  // input rows\n    for (IndexType j = 0; (j+stride+ksize-1) <= input_cols; j += stride) {  // input cols\n      IndexType patchId = i+input_rows*j;\n      for (IndexType r = 0; r < ksize; ++r) {  // patch rows\n        for (IndexType c = 0; c < ksize; ++c) {  // patch cols\n          for (IndexType d = 0; d < input_depth; ++d) {  // depth\n            for (IndexType b = 0; b < input_batches; ++b) {  // batch\n              DataType expected_col_major = 0.0f;\n              DataType expected_row_major = 0.0f;\n              IndexType row_offset = r + i - row_padding;\n              IndexType col_offset = c + j - col_padding;\n              if (row_offset >= 0 && col_offset >= 0 && row_offset < input_rows && col_offset < input_cols) {\n                expected_col_major = tensor_col_major(d, row_offset, col_offset, b);\n                expected_row_major = tensor_row_major(b, col_offset, row_offset, d);\n              }\n              // ColMajor\n              if (result_col_major(d, r, c, patchId, b) != expected_col_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result_col_major(d, r, c, patchId, b), expected_col_major);\n              // RowMajor\n              if (result_row_major(b, patchId, c, r, d) != expected_row_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result_row_major(b, patchId, c, r, d), expected_row_major);\n              // Check that ColMajor and RowMajor agree.\n              VERIFY_IS_EQUAL(expected_col_major, expected_row_major);\n            }\n          }\n        }\n      }\n    }\n  }\n}\n\n// Verifies SAME padding.\ntemplate <typename DataType, typename IndexType>\nstatic void test_patch_padding_same_sycl(const Eigen::SyclDevice& sycl_device){\n  IndexType input_depth = 3;\n  IndexType input_rows = 4;\n  IndexType input_cols = 2;\n  IndexType input_batches = 1;\n  IndexType ksize = 2;  // Corresponds to the Rows and Cols for tensor.extract_image_patches<>.\n  IndexType stride = 2;  // Only same stride is supported.\n\n  // ColMajor\n  array<IndexType, 4> tensorColMajorRange = {{input_depth, input_rows, input_cols, input_batches}};\n  array<IndexType, 4> tensorRowMajorRange = {{input_batches, input_cols, input_rows, input_depth}};\n  Tensor<DataType, 4, DataLayout,IndexType> tensor_col_major(tensorColMajorRange);\n  Tensor<DataType, 4, RowMajor,IndexType> tensor_row_major(tensorRowMajorRange);\n\n  DataType* gpu_data_col_major  = static_cast<DataType*>(sycl_device.allocate(tensor_col_major.size()*sizeof(DataType)));\n  DataType* gpu_data_row_major  = static_cast<DataType*>(sycl_device.allocate(tensor_row_major.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 4, ColMajor, IndexType>> gpu_col_major(gpu_data_col_major, tensorColMajorRange);\n  TensorMap<Tensor<DataType, 4, RowMajor, IndexType>> gpu_row_major(gpu_data_row_major, tensorRowMajorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_col_major, tensor_col_major.data(),(tensor_col_major.size())*sizeof(DataType));\n  gpu_row_major.device(sycl_device)=gpu_col_major.swap_layout();\n  sycl_device.memcpyDeviceToHost(tensor_row_major.data(), gpu_data_row_major, (tensor_col_major.size())*sizeof(DataType));\n\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(0), tensor_row_major.dimension(3));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(1), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(2), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(3), tensor_row_major.dimension(0));\n\n  // Initializes tensor with incrementing numbers.\n  for (IndexType i = 0; i < tensor_col_major.size(); ++i) {\n    tensor_col_major.data()[i] = i + 1;\n  }\n\narray<IndexType, 5> patchColMajorTensorRange={{input_depth, ksize, ksize, 2, input_batches}};\nTensor<DataType, 5, DataLayout,IndexType> result_col_major(patchColMajorTensorRange);\nsize_t patchTensorBuffSize =result_col_major.size()*sizeof(DataType);\nDataType* gpu_data_result_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\nTensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_result_col_major(gpu_data_result_col_major, patchColMajorTensorRange);\ngpu_result_col_major.device(sycl_device)=gpu_col_major.extract_image_patches(ksize, ksize, stride, stride, PADDING_SAME);\nsycl_device.memcpyDeviceToHost(result_col_major.data(), gpu_data_result_col_major, patchTensorBuffSize);\n\n\n  VERIFY_IS_EQUAL(result_col_major.dimension(0), input_depth);  // depth\n  VERIFY_IS_EQUAL(result_col_major.dimension(1), ksize);  // kernel rows\n  VERIFY_IS_EQUAL(result_col_major.dimension(2), ksize);  // kernel cols\n  VERIFY_IS_EQUAL(result_col_major.dimension(3), 2);  // number of patches\n  VERIFY_IS_EQUAL(result_col_major.dimension(4), input_batches);  // number of batches\n\n  // RowMajor\n\n  array<IndexType, 5> patchRowMajorTensorRange={{input_batches, 2, ksize, ksize, input_depth }};\n  Tensor<DataType, 5, RowMajor,IndexType> result_row_major(patchRowMajorTensorRange);\n  patchTensorBuffSize =result_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_result_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, RowMajor,IndexType>> gpu_result_row_major(gpu_data_result_row_major, patchRowMajorTensorRange);\n  gpu_result_row_major.device(sycl_device)=gpu_row_major.extract_image_patches(ksize, ksize, stride, stride, PADDING_SAME);\n  sycl_device.memcpyDeviceToHost(result_row_major.data(), gpu_data_result_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(result_col_major.dimension(0), result_row_major.dimension(4));\n  VERIFY_IS_EQUAL(result_col_major.dimension(1), result_row_major.dimension(3));\n  VERIFY_IS_EQUAL(result_col_major.dimension(2), result_row_major.dimension(2));\n  VERIFY_IS_EQUAL(result_col_major.dimension(3), result_row_major.dimension(1));\n  VERIFY_IS_EQUAL(result_col_major.dimension(4), result_row_major.dimension(0));\n\n  // Based on the calculation described in TensorTraits.h, padding happens to be 0.\n  IndexType row_padding = 0;\n  IndexType col_padding = 0;\n\n  for (IndexType i = 0; (i+stride+ksize-1) <= input_rows; i += stride) {  // input rows\n    for (IndexType j = 0; (j+stride+ksize-1) <= input_cols; j += stride) {  // input cols\n      IndexType patchId = i+input_rows*j;\n      for (IndexType r = 0; r < ksize; ++r) {  // patch rows\n        for (IndexType c = 0; c < ksize; ++c) {  // patch cols\n          for (IndexType d = 0; d < input_depth; ++d) {  // depth\n            for (IndexType b = 0; b < input_batches; ++b) {  // batch\n              DataType expected_col_major = 0.0f;\n              DataType expected_row_major = 0.0f;\n              IndexType row_offset = r*stride + i - row_padding;\n              IndexType col_offset = c*stride + j - col_padding;\n              if (row_offset >= 0 && col_offset >= 0 && row_offset < input_rows && col_offset < input_cols) {\n                expected_col_major = tensor_col_major(d, row_offset, col_offset, b);\n                expected_row_major = tensor_row_major(b, col_offset, row_offset, d);\n              }\n              // ColMajor\n              if (result_col_major(d, r, c, patchId, b) != expected_col_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result_col_major(d, r, c, patchId, b), expected_col_major);\n              // RowMajor\n              if (result_row_major(b, patchId, c, r, d) != expected_row_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result_row_major(b, patchId, c, r, d), expected_row_major);\n              // Check that ColMajor and RowMajor agree.\n              VERIFY_IS_EQUAL(expected_col_major, expected_row_major);\n            }\n          }\n        }\n      }\n    }\n  }\n}\n\n\ntemplate <typename DataType, typename IndexType>\nstatic void test_patch_no_extra_dim_sycl(const Eigen::SyclDevice& sycl_device){\n\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n\n  // ColMajor\n  array<IndexType, 3> tensorColMajorRange = {{sizeDim1, sizeDim2, sizeDim3}};\n  array<IndexType, 3> tensorRowMajorRange = {{sizeDim3, sizeDim2, sizeDim1}};\n  Tensor<DataType, 3, DataLayout,IndexType> tensor_col_major(tensorColMajorRange);\n  tensor_col_major.setRandom();\n  Tensor<DataType, 3, RowMajor,IndexType> tensor_row_major(tensorRowMajorRange);\n\n  DataType* gpu_data_col_major  = static_cast<DataType*>(sycl_device.allocate(tensor_col_major.size()*sizeof(DataType)));\n  DataType* gpu_data_row_major  = static_cast<DataType*>(sycl_device.allocate(tensor_row_major.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 3, ColMajor, IndexType>> gpu_col_major(gpu_data_col_major, tensorColMajorRange);\n  TensorMap<Tensor<DataType, 3, RowMajor, IndexType>> gpu_row_major(gpu_data_row_major, tensorRowMajorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_col_major, tensor_col_major.data(),(tensor_col_major.size())*sizeof(DataType));\n  gpu_row_major.device(sycl_device)=gpu_col_major.swap_layout();\n  sycl_device.memcpyDeviceToHost(tensor_row_major.data(), gpu_data_row_major, (tensor_row_major.size())*sizeof(DataType));\n\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(0), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(1), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(2), tensor_row_major.dimension(0));\n\n\n  // Single pixel patch: ColMajor\n  array<IndexType, 4> patchColMajorTensorRange={{sizeDim1, 1, 1, sizeDim2*sizeDim3}};\n  Tensor<DataType, 4, DataLayout,IndexType> single_patch_col_major(patchColMajorTensorRange);\n  size_t patchTensorBuffSize =single_patch_col_major.size()*sizeof(DataType);\n  DataType* gpu_data_single_patch_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_single_patch_col_major(gpu_data_single_patch_col_major, patchColMajorTensorRange);\n  gpu_single_patch_col_major.device(sycl_device)=gpu_col_major.extract_image_patches(1, 1);\n  sycl_device.memcpyDeviceToHost(single_patch_col_major.data(), gpu_data_single_patch_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(single_patch_col_major.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(single_patch_col_major.dimension(1), 1);\n  VERIFY_IS_EQUAL(single_patch_col_major.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_patch_col_major.dimension(3), sizeDim2*sizeDim3);\n\n  // Single pixel patch: RowMajor\n  array<IndexType, 4> patchRowMajorTensorRange={{sizeDim2*sizeDim3, 1, 1, sizeDim1}};\n  Tensor<DataType, 4, RowMajor,IndexType> single_patch_row_major(patchRowMajorTensorRange);\n  patchTensorBuffSize =single_patch_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_single_patch_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 4, RowMajor,IndexType>> gpu_single_patch_row_major(gpu_data_single_patch_row_major, patchRowMajorTensorRange);\n  gpu_single_patch_row_major.device(sycl_device)=gpu_row_major.extract_image_patches(1, 1);\n  sycl_device.memcpyDeviceToHost(single_patch_row_major.data(), gpu_data_single_patch_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(single_patch_row_major.dimension(0), sizeDim2*sizeDim3);\n  VERIFY_IS_EQUAL(single_patch_row_major.dimension(1), 1);\n  VERIFY_IS_EQUAL(single_patch_row_major.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_patch_row_major.dimension(3), sizeDim1);\n\n  for (IndexType i = 0; i < tensor_col_major.size(); ++i) {\n    // ColMajor\n    if (tensor_col_major.data()[i] != single_patch_col_major.data()[i]) {\n      std::cout << \"Mismatch detected at index \" << i << \" : \" << tensor_col_major.data()[i] << \" vs \" << single_patch_col_major.data()[i] << std::endl;\n    }\n    VERIFY_IS_EQUAL(single_patch_col_major.data()[i], tensor_col_major.data()[i]);\n    // RowMajor\n    if (tensor_row_major.data()[i] != single_patch_row_major.data()[i]) {\n      std::cout << \"Mismatch detected at index \" << i << \" : \"\n           << tensor_col_major.data()[i] << \" vs \"\n           << single_patch_row_major.data()[i] << std::endl;\n    }\n    VERIFY_IS_EQUAL(single_patch_row_major.data()[i],\n                    tensor_row_major.data()[i]);\n    VERIFY_IS_EQUAL(tensor_col_major.data()[i], tensor_row_major.data()[i]);\n    VERIFY_IS_EQUAL(single_patch_col_major.data()[i],\n                    single_patch_row_major.data()[i]);\n  }\n\n  // Entire image patch: ColMajor\n  patchColMajorTensorRange={{sizeDim1, sizeDim2, sizeDim3, sizeDim2*sizeDim3}};\n  Tensor<DataType, 4, DataLayout,IndexType> entire_image_patch_col_major(patchColMajorTensorRange);\n  patchTensorBuffSize =entire_image_patch_col_major.size()*sizeof(DataType);\n  DataType* gpu_data_entire_image_patch_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_entire_image_patch_col_major(gpu_data_entire_image_patch_col_major, patchColMajorTensorRange);\n  gpu_entire_image_patch_col_major.device(sycl_device)=gpu_col_major.extract_image_patches(3, 5);\n  sycl_device.memcpyDeviceToHost(entire_image_patch_col_major.data(), gpu_data_entire_image_patch_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(entire_image_patch_col_major.dimension(0), 2);\n  VERIFY_IS_EQUAL(entire_image_patch_col_major.dimension(1), 3);\n  VERIFY_IS_EQUAL(entire_image_patch_col_major.dimension(2), 5);\n  VERIFY_IS_EQUAL(entire_image_patch_col_major.dimension(3), 3*5);\n\n  // Entire image patch: RowMajor\npatchRowMajorTensorRange={{sizeDim2*sizeDim3, sizeDim3, sizeDim2, sizeDim1}};\nTensor<DataType, 4, RowMajor,IndexType> entire_image_patch_row_major(patchRowMajorTensorRange);\npatchTensorBuffSize =entire_image_patch_row_major.size()*sizeof(DataType);\nDataType* gpu_data_entire_image_patch_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\nTensorMap<Tensor<DataType, 4, RowMajor,IndexType>> gpu_entire_image_patch_row_major(gpu_data_entire_image_patch_row_major, patchRowMajorTensorRange);\ngpu_entire_image_patch_row_major.device(sycl_device)=gpu_row_major.extract_image_patches(3, 5);\nsycl_device.memcpyDeviceToHost(entire_image_patch_row_major.data(), gpu_data_entire_image_patch_row_major, patchTensorBuffSize);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(0), 3*5);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(1), 5);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(2), 3);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(3), 2);\n\n  for (IndexType i = 0; i < 3; ++i) {\n    for (IndexType j = 0; j < 5; ++j) {\n      IndexType patchId = i+3*j;\n      for (IndexType r = 0; r < 3; ++r) {\n        for (IndexType c = 0; c < 5; ++c) {\n          for (IndexType d = 0; d < 2; ++d) {\n            DataType expected_col_major = 0.0f;\n            DataType expected_row_major = 0.0f;\n            if (r-1+i >= 0 && c-2+j >= 0 && r-1+i < 3 && c-2+j < 5) {\n              expected_col_major = tensor_col_major(d, r-1+i, c-2+j);\n              expected_row_major = tensor_row_major(c-2+j, r-1+i, d);\n            }\n            // ColMajor\n            if (entire_image_patch_col_major(d, r, c, patchId) != expected_col_major) {\n              std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << std::endl;\n            }\n            VERIFY_IS_EQUAL(entire_image_patch_col_major(d, r, c, patchId), expected_col_major);\n            // RowMajor\n            if (entire_image_patch_row_major(patchId, c, r, d) !=\n                expected_row_major) {\n              std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << std::endl;\n            }\n            VERIFY_IS_EQUAL(entire_image_patch_row_major(patchId, c, r, d),\n                            expected_row_major);\n            // Check that ColMajor and RowMajor agree.\n            VERIFY_IS_EQUAL(expected_col_major, expected_row_major);\n          }\n        }\n      }\n    }\n  }\n\n  // 2D patch: ColMajor\n  patchColMajorTensorRange={{sizeDim1, 2, 2, sizeDim2*sizeDim3}};\n  Tensor<DataType, 4, DataLayout,IndexType> twod_patch_col_major(patchColMajorTensorRange);\n  patchTensorBuffSize =twod_patch_col_major.size()*sizeof(DataType);\n  DataType* gpu_data_twod_patch_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_twod_patch_col_major(gpu_data_twod_patch_col_major, patchColMajorTensorRange);\n  gpu_twod_patch_col_major.device(sycl_device)=gpu_col_major.extract_image_patches(2, 2);\n  sycl_device.memcpyDeviceToHost(twod_patch_col_major.data(), gpu_data_twod_patch_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(twod_patch_col_major.dimension(0), 2);\n  VERIFY_IS_EQUAL(twod_patch_col_major.dimension(1), 2);\n  VERIFY_IS_EQUAL(twod_patch_col_major.dimension(2), 2);\n  VERIFY_IS_EQUAL(twod_patch_col_major.dimension(3), 3*5);\n\n  // 2D patch: RowMajor\n  patchRowMajorTensorRange={{sizeDim2*sizeDim3, 2, 2, sizeDim1}};\n  Tensor<DataType, 4, RowMajor,IndexType> twod_patch_row_major(patchRowMajorTensorRange);\n  patchTensorBuffSize =twod_patch_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_twod_patch_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 4, RowMajor,IndexType>> gpu_twod_patch_row_major(gpu_data_twod_patch_row_major, patchRowMajorTensorRange);\n  gpu_twod_patch_row_major.device(sycl_device)=gpu_row_major.extract_image_patches(2, 2);\n  sycl_device.memcpyDeviceToHost(twod_patch_row_major.data(), gpu_data_twod_patch_row_major, patchTensorBuffSize);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(0), 3*5);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(1), 2);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(2), 2);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(3), 2);\n\n  // Based on the calculation described in TensorTraits.h, padding happens to be 0.\n  IndexType row_padding = 0;\n  IndexType col_padding = 0;\n  IndexType stride = 1;\n\n  for (IndexType i = 0; i < 3; ++i) {\n    for (IndexType j = 0; j < 5; ++j) {\n      IndexType patchId = i+3*j;\n      for (IndexType r = 0; r < 2; ++r) {\n        for (IndexType c = 0; c < 2; ++c) {\n          for (IndexType d = 0; d < 2; ++d) {\n            DataType expected_col_major = 0.0f;\n            DataType expected_row_major = 0.0f;\n            IndexType row_offset = r*stride + i - row_padding;\n            IndexType col_offset = c*stride + j - col_padding;\n            // ColMajor\n            if (row_offset >= 0 && col_offset >= 0 && row_offset < tensor_col_major.dimension(1) && col_offset < tensor_col_major.dimension(2)) {\n              expected_col_major = tensor_col_major(d, row_offset, col_offset);\n            }\n            if (twod_patch_col_major(d, r, c, patchId) != expected_col_major) {\n              std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << std::endl;\n            }\n            VERIFY_IS_EQUAL(twod_patch_col_major(d, r, c, patchId), expected_col_major);\n            // RowMajor\n            if (row_offset >= 0 && col_offset >= 0 && row_offset < tensor_row_major.dimension(1) && col_offset < tensor_row_major.dimension(0)) {\n              expected_row_major = tensor_row_major(col_offset, row_offset, d);\n            }\n            if (twod_patch_row_major(patchId, c, r, d) != expected_row_major) {\n              std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << std::endl;\n            }\n            VERIFY_IS_EQUAL(twod_patch_row_major(patchId, c, r, d), expected_row_major);\n            // Check that ColMajor and RowMajor agree.\n            VERIFY_IS_EQUAL(expected_col_major, expected_row_major);\n          }\n        }\n      }\n    }\n  }\n\n  sycl_device.deallocate(gpu_data_col_major);\n  sycl_device.deallocate(gpu_data_row_major);\n  sycl_device.deallocate(gpu_data_single_patch_col_major);\n  sycl_device.deallocate(gpu_data_single_patch_row_major);\n  sycl_device.deallocate(gpu_data_entire_image_patch_col_major);\n  sycl_device.deallocate(gpu_data_entire_image_patch_row_major);\n  sycl_device.deallocate(gpu_data_twod_patch_col_major);\n  sycl_device.deallocate(gpu_data_twod_patch_row_major);\n}\n\ntemplate <typename DataType, typename IndexType>\nstatic void test_imagenet_patches_sycl(const Eigen::SyclDevice& sycl_device)\n{\n  // Test the code on typical configurations used by the 'imagenet' benchmarks at\n  // https://github.com/soumith/convnet-benchmarks\n  // ColMajor\n  IndexType sizeDim1 = 3;\n  IndexType sizeDim2 = 128;\n  IndexType sizeDim3 = 128;\n  IndexType sizeDim4 = 16;\n  array<IndexType, 4> tensorColMajorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  Tensor<DataType, 4, DataLayout,IndexType> l_in_col_major(tensorColMajorRange);\n  l_in_col_major.setRandom();\n\n  DataType* gpu_data_l_in_col_major  = static_cast<DataType*>(sycl_device.allocate(l_in_col_major.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 4, ColMajor, IndexType>> gpu_l_in_col_major(gpu_data_l_in_col_major, tensorColMajorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_l_in_col_major, l_in_col_major.data(),(l_in_col_major.size())*sizeof(DataType));\n\n  array<IndexType, 5> patchTensorRange={{sizeDim1, 11, 11, sizeDim2*sizeDim3, sizeDim4}};\n  Tensor<DataType, 5, DataLayout,IndexType> l_out_col_major(patchTensorRange);\n  size_t patchTensorBuffSize =l_out_col_major.size()*sizeof(DataType);\n  DataType* gpu_data_l_out_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_l_out_col_major(gpu_data_l_out_col_major, patchTensorRange);\n  gpu_l_out_col_major.device(sycl_device)=gpu_l_in_col_major.extract_image_patches(11, 11);\n  sycl_device.memcpyDeviceToHost(l_out_col_major.data(), gpu_data_l_out_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(1), 11);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(2), 11);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(3), sizeDim2*sizeDim3);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(4), sizeDim4);\n\n  // RowMajor\n  patchTensorRange={{sizeDim4, sizeDim2*sizeDim3, 11, 11, sizeDim1}};\n  Tensor<DataType, 5, RowMajor,IndexType> l_out_row_major(patchTensorRange);\n  patchTensorBuffSize =l_out_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_l_out_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, RowMajor,IndexType>> gpu_l_out_row_major(gpu_data_l_out_row_major, patchTensorRange);\n  gpu_l_out_row_major.device(sycl_device)=gpu_l_in_col_major.swap_layout().extract_image_patches(11, 11);\n  sycl_device.memcpyDeviceToHost(l_out_row_major.data(), gpu_data_l_out_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(0), sizeDim4);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(1), sizeDim2*sizeDim3);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(2), 11);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(3), 11);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(4), sizeDim1);\n\n  for (IndexType b = 0; b < 16; ++b) {\n    for (IndexType i = 0; i < 128; ++i) {\n      for (IndexType j = 0; j < 128; ++j) {\n        IndexType patchId = i+128*j;\n        for (IndexType c = 0; c < 11; ++c) {\n          for (IndexType r = 0; r < 11; ++r) {\n            for (IndexType d = 0; d < 3; ++d) {\n              DataType expected = 0.0f;\n              if (r-5+i >= 0 && c-5+j >= 0 && r-5+i < 128 && c-5+j < 128) {\n                expected = l_in_col_major(d, r-5+i, c-5+j, b);\n              }\n              // ColMajor\n              if (l_out_col_major(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_col_major(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (l_out_row_major(b, patchId, c, r, d) !=\n                  expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j\n                     << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b\n                     << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_row_major(b, patchId, c, r, d),\n                              expected);\n            }\n          }\n        }\n      }\n    }\n  }\n\n  // ColMajor\n  sycl_device.deallocate(gpu_data_l_in_col_major);\n  sycl_device.deallocate(gpu_data_l_out_col_major);\n  sizeDim1 = 16;\n  sizeDim2 = 64;\n  sizeDim3 = 64;\n  sizeDim4 = 32;\n  tensorColMajorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  l_in_col_major.resize(tensorColMajorRange);\n  l_in_col_major.setRandom();\n  gpu_data_l_in_col_major  = static_cast<DataType*>(sycl_device.allocate(l_in_col_major.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 4, ColMajor, IndexType>>gpu_l_in_col_major_resize1(gpu_data_l_in_col_major, tensorColMajorRange);\n\n  patchTensorRange={{sizeDim1, 9, 9, sizeDim2*sizeDim3, sizeDim4}};\n  l_out_col_major.resize(patchTensorRange);\n  patchTensorBuffSize =l_out_col_major.size()*sizeof(DataType);\n  gpu_data_l_out_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>>gpu_l_out_col_major_resize1(gpu_data_l_out_col_major, patchTensorRange);\n  sycl_device.memcpyHostToDevice(gpu_data_l_in_col_major, l_in_col_major.data(),(l_in_col_major.size())*sizeof(DataType));\n  gpu_l_out_col_major_resize1.device(sycl_device)=gpu_l_in_col_major_resize1.extract_image_patches(9, 9);\n  sycl_device.memcpyDeviceToHost(l_out_col_major.data(), gpu_data_l_out_col_major, patchTensorBuffSize);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(0), 16);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(1), 9);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(2), 9);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(3), 64*64);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(4), 32);\n\n// RowMajor\n  sycl_device.deallocate(gpu_data_l_out_row_major);\n  patchTensorRange={{sizeDim4, sizeDim2*sizeDim3, 9, 9 ,sizeDim1}};\n  l_out_row_major.resize(patchTensorRange);\n  patchTensorBuffSize =l_out_row_major.size()*sizeof(DataType);\n  gpu_data_l_out_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, RowMajor,IndexType>>gpu_l_out_row_major_resize1(gpu_data_l_out_row_major, patchTensorRange);\n  gpu_l_out_row_major_resize1.device(sycl_device)=gpu_l_in_col_major_resize1.swap_layout().extract_image_patches(9, 9);\n  sycl_device.memcpyDeviceToHost(l_out_row_major.data(), gpu_data_l_out_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(0), 32);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(1), 64*64);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(2), 9);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(3), 9);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(4), 16);\n\n  for (IndexType b = 0; b < 32; ++b) {\n    for (IndexType i = 0; i < 64; ++i) {\n      for (IndexType j = 0; j < 64; ++j) {\n        IndexType patchId = i+64*j;\n        for (IndexType c = 0; c < 9; ++c) {\n          for (IndexType r = 0; r < 9; ++r) {\n            for (IndexType d = 0; d < 16; ++d) {\n              DataType expected = 0.0f;\n              if (r-4+i >= 0 && c-4+j >= 0 && r-4+i < 64 && c-4+j < 64) {\n                expected = l_in_col_major(d, r-4+i, c-4+j, b);\n              }\n              // ColMajor\n              if (l_out_col_major(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_col_major(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (l_out_row_major(b, patchId, c, r, d) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_row_major(b, patchId, c, r, d), expected);\n            }\n          }\n        }\n      }\n    }\n  }\n\n  // ColMajor\n\n  sycl_device.deallocate(gpu_data_l_in_col_major);\n  sycl_device.deallocate(gpu_data_l_out_col_major);\n  sizeDim1 = 32;\n  sizeDim2 = 16;\n  sizeDim3 = 16;\n  sizeDim4 = 32;\n  tensorColMajorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  l_in_col_major.resize(tensorColMajorRange);\n  l_in_col_major.setRandom();\n  gpu_data_l_in_col_major  = static_cast<DataType*>(sycl_device.allocate(l_in_col_major.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 4, ColMajor, IndexType>>gpu_l_in_col_major_resize2(gpu_data_l_in_col_major, tensorColMajorRange);\n\n  patchTensorRange={{sizeDim1, 7, 7, sizeDim2*sizeDim3, sizeDim4}};\n  l_out_col_major.resize(patchTensorRange);\n  patchTensorBuffSize =l_out_col_major.size()*sizeof(DataType);\n  gpu_data_l_out_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>>gpu_l_out_col_major_resize2(gpu_data_l_out_col_major, patchTensorRange);\n  sycl_device.memcpyHostToDevice(gpu_data_l_in_col_major, l_in_col_major.data(),(l_in_col_major.size())*sizeof(DataType));\n  gpu_l_out_col_major_resize2.device(sycl_device)=gpu_l_in_col_major_resize2.extract_image_patches(7, 7);\n  sycl_device.memcpyDeviceToHost(l_out_col_major.data(), gpu_data_l_out_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(0), 32);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(1), 7);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(2), 7);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(3), 16*16);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(4), 32);\n\n  // RowMajor\n  sycl_device.deallocate(gpu_data_l_out_row_major);\n  patchTensorRange={{sizeDim4, sizeDim2*sizeDim3, 7, 7 ,sizeDim1}};\n  l_out_row_major.resize(patchTensorRange);\n  patchTensorBuffSize =l_out_row_major.size()*sizeof(DataType);\n  gpu_data_l_out_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, RowMajor,IndexType>>gpu_l_out_row_major_resize2(gpu_data_l_out_row_major, patchTensorRange);\n  gpu_l_out_row_major_resize2.device(sycl_device)=gpu_l_in_col_major_resize2.swap_layout().extract_image_patches(7, 7);\n  sycl_device.memcpyDeviceToHost(l_out_row_major.data(), gpu_data_l_out_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(0), 32);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(1), 16*16);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(2), 7);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(3), 7);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(4), 32);\n\n  for (IndexType b = 0; b < 32; ++b) {\n    for (IndexType i = 0; i < 16; ++i) {\n      for (IndexType j = 0; j < 16; ++j) {\n        IndexType patchId = i+16*j;\n        for (IndexType c = 0; c < 7; ++c) {\n          for (IndexType r = 0; r < 7; ++r) {\n            for (IndexType d = 0; d < 32; ++d) {\n              DataType expected = 0.0f;\n              if (r-3+i >= 0 && c-3+j >= 0 && r-3+i < 16 && c-3+j < 16) {\n                expected = l_in_col_major(d, r-3+i, c-3+j, b);\n              }\n              // ColMajor\n              if (l_out_col_major(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_col_major(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (l_out_row_major(b, patchId, c, r, d) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_row_major(b, patchId, c, r, d), expected);\n            }\n          }\n        }\n      }\n    }\n  }\n\n  // ColMajor\n  sycl_device.deallocate(gpu_data_l_in_col_major);\n  sycl_device.deallocate(gpu_data_l_out_col_major);\n  sizeDim1 = 64;\n  sizeDim2 = 13;\n  sizeDim3 = 13;\n  sizeDim4 = 32;\n  tensorColMajorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  l_in_col_major.resize(tensorColMajorRange);\n  l_in_col_major.setRandom();\n  gpu_data_l_in_col_major  = static_cast<DataType*>(sycl_device.allocate(l_in_col_major.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 4, ColMajor, IndexType>>gpu_l_in_col_major_resize3(gpu_data_l_in_col_major, tensorColMajorRange);\n\n  patchTensorRange={{sizeDim1, 3, 3, sizeDim2*sizeDim3, sizeDim4}};\n  l_out_col_major.resize(patchTensorRange);\n  patchTensorBuffSize =l_out_col_major.size()*sizeof(DataType);\n  gpu_data_l_out_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>>gpu_l_out_col_major_resize3(gpu_data_l_out_col_major, patchTensorRange);\n  sycl_device.memcpyHostToDevice(gpu_data_l_in_col_major, l_in_col_major.data(),(l_in_col_major.size())*sizeof(DataType));\n  gpu_l_out_col_major_resize3.device(sycl_device)=gpu_l_in_col_major_resize3.extract_image_patches(3, 3);\n  sycl_device.memcpyDeviceToHost(l_out_col_major.data(), gpu_data_l_out_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(0), 64);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(1), 3);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(2), 3);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(3), 13*13);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(4), 32);\n\n  // RowMajor\n  sycl_device.deallocate(gpu_data_l_out_row_major);\n  patchTensorRange={{sizeDim4, sizeDim2*sizeDim3, 3, 3 ,sizeDim1}};\n  l_out_row_major.resize(patchTensorRange);\n  patchTensorBuffSize =l_out_row_major.size()*sizeof(DataType);\n  gpu_data_l_out_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, RowMajor,IndexType>>gpu_l_out_row_major_resize3(gpu_data_l_out_row_major, patchTensorRange);\n  gpu_l_out_row_major_resize3.device(sycl_device)=gpu_l_in_col_major_resize3.swap_layout().extract_image_patches(3, 3);\n  sycl_device.memcpyDeviceToHost(l_out_row_major.data(), gpu_data_l_out_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(0), 32);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(1), 13*13);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(2), 3);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(3), 3);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(4), 64);\n\n  for (IndexType b = 0; b < 32; ++b) {\n    for (IndexType i = 0; i < 13; ++i) {\n      for (IndexType j = 0; j < 13; ++j) {\n        IndexType patchId = i+13*j;\n        for (IndexType c = 0; c < 3; ++c) {\n          for (IndexType r = 0; r < 3; ++r) {\n            for (IndexType d = 0; d < 64; ++d) {\n              DataType expected = 0.0f;\n              if (r-1+i >= 0 && c-1+j >= 0 && r-1+i < 13 && c-1+j < 13) {\n                expected = l_in_col_major(d, r-1+i, c-1+j, b);\n              }\n              // ColMajor\n              if (l_out_col_major(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_col_major(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (l_out_row_major(b, patchId, c, r, d) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_row_major(b, patchId, c, r, d), expected);\n            }\n          }\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data_l_in_col_major);\n  sycl_device.deallocate(gpu_data_l_out_col_major);\n  sycl_device.deallocate(gpu_data_l_out_row_major);\n}\n\n\ntemplate<typename DataType, typename dev_Selector> void sycl_tensor_image_patch_test_per_device(dev_Selector s){\nQueueInterface queueInterface(s);\nauto sycl_device = Eigen::SyclDevice(&queueInterface);\ntest_simple_image_patch_sycl<DataType, int64_t>(sycl_device);\ntest_patch_padding_valid_sycl<DataType, int64_t>(sycl_device);\ntest_patch_padding_valid_same_value_sycl<DataType, int64_t>(sycl_device);\ntest_patch_padding_same_sycl<DataType, int64_t>(sycl_device);\ntest_patch_no_extra_dim_sycl<DataType, int64_t>(sycl_device);\ntest_imagenet_patches_sycl<DataType, int64_t>(sycl_device);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_image_patch_sycl)\n{\nfor (const auto& device :Eigen::get_sycl_supported_devices()) {\n  CALL_SUBTEST(sycl_tensor_image_patch_test_per_device<float>(device));\n}\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_index_list.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\n#ifdef EIGEN_HAS_INDEX_LIST\n\nstatic void test_static_index_list()\n{\n  Tensor<float, 4> tensor(2,3,5,7);\n  tensor.setRandom();\n\n  constexpr auto reduction_axis = make_index_list(0, 1, 2);\n  VERIFY_IS_EQUAL(internal::array_get<0>(reduction_axis), 0);\n  VERIFY_IS_EQUAL(internal::array_get<1>(reduction_axis), 1);\n  VERIFY_IS_EQUAL(internal::array_get<2>(reduction_axis), 2);\n  VERIFY_IS_EQUAL(static_cast<Index>(reduction_axis[0]), 0);\n  VERIFY_IS_EQUAL(static_cast<Index>(reduction_axis[1]), 1);\n  VERIFY_IS_EQUAL(static_cast<Index>(reduction_axis[2]), 2);\n\n  EIGEN_STATIC_ASSERT((internal::array_get<0>(reduction_axis) == 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::array_get<1>(reduction_axis) == 1), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::array_get<2>(reduction_axis) == 2), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  Tensor<float, 1> result = tensor.sum(reduction_axis);\n  for (int i = 0; i < result.size(); ++i) {\n    float expected = 0.0f;\n    for (int j = 0; j < 2; ++j) {\n      for (int k = 0; k < 3; ++k) {\n        for (int l = 0; l < 5; ++l) {\n          expected += tensor(j,k,l,i);\n        }\n      }\n    }\n    VERIFY_IS_APPROX(result(i), expected);\n  }\n}\n\n\nstatic void test_type2index_list()\n{\n  Tensor<float, 5> tensor(2,3,5,7,11);\n  tensor.setRandom();\n  tensor += tensor.constant(10.0f);\n\n  typedef Eigen::IndexList<Eigen::type2index<0>> Dims0;\n  typedef Eigen::IndexList<Eigen::type2index<0>, Eigen::type2index<1>> Dims1;\n  typedef Eigen::IndexList<Eigen::type2index<0>, Eigen::type2index<1>, Eigen::type2index<2>> Dims2;\n  typedef Eigen::IndexList<Eigen::type2index<0>, Eigen::type2index<1>, Eigen::type2index<2>, Eigen::type2index<3>> Dims3;\n  typedef Eigen::IndexList<Eigen::type2index<0>, Eigen::type2index<1>, Eigen::type2index<2>, Eigen::type2index<3>, Eigen::type2index<4>> Dims4;\n\n#if 0\n  EIGEN_STATIC_ASSERT((internal::indices_statically_known_to_increase<Dims0>() == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::indices_statically_known_to_increase<Dims1>() == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::indices_statically_known_to_increase<Dims2>() == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::indices_statically_known_to_increase<Dims3>() == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::indices_statically_known_to_increase<Dims4>() == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n#endif\n\n  EIGEN_STATIC_ASSERT((internal::are_inner_most_dims<Dims0, 1, ColMajor>::value == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::are_inner_most_dims<Dims1, 2, ColMajor>::value == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::are_inner_most_dims<Dims2, 3, ColMajor>::value == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::are_inner_most_dims<Dims3, 4, ColMajor>::value == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::are_inner_most_dims<Dims4, 5, ColMajor>::value == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((internal::are_inner_most_dims<Dims0, 1, RowMajor>::value == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::are_inner_most_dims<Dims1, 2, RowMajor>::value == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::are_inner_most_dims<Dims2, 3, RowMajor>::value == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::are_inner_most_dims<Dims3, 4, RowMajor>::value == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::are_inner_most_dims<Dims4, 5, RowMajor>::value == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  const Dims0 reduction_axis0;\n  Tensor<float, 4> result0 = tensor.sum(reduction_axis0);\n  for (int m = 0; m < 11; ++m) {\n    for (int l = 0; l < 7; ++l) {\n      for (int k = 0; k < 5; ++k) {\n        for (int j = 0; j < 3; ++j) {\n          float expected = 0.0f;\n          for (int i = 0; i < 2; ++i) {\n            expected += tensor(i,j,k,l,m);\n          }\n          VERIFY_IS_APPROX(result0(j,k,l,m), expected);\n        }\n      }\n    }\n  }\n\n  const Dims1 reduction_axis1;\n  Tensor<float, 3> result1 = tensor.sum(reduction_axis1);\n  for (int m = 0; m < 11; ++m) {\n    for (int l = 0; l < 7; ++l) {\n      for (int k = 0; k < 5; ++k) {\n        float expected = 0.0f;\n        for (int j = 0; j < 3; ++j) {\n          for (int i = 0; i < 2; ++i) {\n            expected += tensor(i,j,k,l,m);\n          }\n        }\n        VERIFY_IS_APPROX(result1(k,l,m), expected);\n      }\n    }\n  }\n\n  const Dims2 reduction_axis2;\n  Tensor<float, 2> result2 = tensor.sum(reduction_axis2);\n  for (int m = 0; m < 11; ++m) {\n    for (int l = 0; l < 7; ++l) {\n      float expected = 0.0f;\n      for (int k = 0; k < 5; ++k) {\n        for (int j = 0; j < 3; ++j) {\n          for (int i = 0; i < 2; ++i) {\n            expected += tensor(i,j,k,l,m);\n          }\n        }\n      }\n      VERIFY_IS_APPROX(result2(l,m), expected);\n    }\n  }\n\n  const Dims3 reduction_axis3;\n  Tensor<float, 1> result3 = tensor.sum(reduction_axis3);\n  for (int m = 0; m < 11; ++m) {\n    float expected = 0.0f;\n    for (int l = 0; l < 7; ++l) {\n      for (int k = 0; k < 5; ++k) {\n        for (int j = 0; j < 3; ++j) {\n          for (int i = 0; i < 2; ++i) {\n            expected += tensor(i,j,k,l,m);\n          }\n        }\n      }\n    }\n    VERIFY_IS_APPROX(result3(m), expected);\n  }\n\n  const Dims4 reduction_axis4;\n  Tensor<float, 0> result4 = tensor.sum(reduction_axis4);\n  float expected = 0.0f;\n  for (int m = 0; m < 11; ++m) {\n    for (int l = 0; l < 7; ++l) {\n      for (int k = 0; k < 5; ++k) {\n        for (int j = 0; j < 3; ++j) {\n          for (int i = 0; i < 2; ++i) {\n            expected += tensor(i,j,k,l,m);\n          }\n        }\n      }\n    }\n  }\n  VERIFY_IS_APPROX(result4(), expected);\n}\n\n\nstatic void test_type2indexpair_list()\n{\n  Tensor<float, 5> tensor(2,3,5,7,11);\n  tensor.setRandom();\n  tensor += tensor.constant(10.0f);\n\n  typedef Eigen::IndexPairList<Eigen::type2indexpair<0,10>> Dims0;\n  typedef Eigen::IndexPairList<Eigen::type2indexpair<0,10>, Eigen::type2indexpair<1,11>, Eigen::type2indexpair<2,12>> Dims2_a;\n  typedef Eigen::IndexPairList<Eigen::type2indexpair<0,10>, Eigen::IndexPair<Index>, Eigen::type2indexpair<2,12>> Dims2_b;\n  typedef Eigen::IndexPairList<Eigen::IndexPair<Index>, Eigen::type2indexpair<1,11>, Eigen::IndexPair<Index>> Dims2_c;\n\n  Dims2_a d2_a;\n\n  Dims2_b d2_b;\n  d2_b.set(1, Eigen::IndexPair<Index>(1,11));\n\n  Dims2_c d2_c;\n  d2_c.set(0, Eigen::IndexPair<Index>(Eigen::IndexPair<Index>(0,10)));\n  d2_c.set(1, Eigen::IndexPair<Index>(1,11));  // setting type2indexpair to correct value.\n  d2_c.set(2, Eigen::IndexPair<Index>(2,12));\n\n  VERIFY_IS_EQUAL(d2_a[0].first, 0);\n  VERIFY_IS_EQUAL(d2_a[0].second, 10);\n  VERIFY_IS_EQUAL(d2_a[1].first, 1);\n  VERIFY_IS_EQUAL(d2_a[1].second, 11);\n  VERIFY_IS_EQUAL(d2_a[2].first, 2);\n  VERIFY_IS_EQUAL(d2_a[2].second, 12);\n\n  VERIFY_IS_EQUAL(d2_b[0].first, 0);\n  VERIFY_IS_EQUAL(d2_b[0].second, 10);\n  VERIFY_IS_EQUAL(d2_b[1].first, 1);\n  VERIFY_IS_EQUAL(d2_b[1].second, 11);\n  VERIFY_IS_EQUAL(d2_b[2].first, 2);\n  VERIFY_IS_EQUAL(d2_b[2].second, 12);\n\n  VERIFY_IS_EQUAL(d2_c[0].first, 0);\n  VERIFY_IS_EQUAL(d2_c[0].second, 10);\n  VERIFY_IS_EQUAL(d2_c[1].first, 1);\n  VERIFY_IS_EQUAL(d2_c[1].second, 11);\n  VERIFY_IS_EQUAL(d2_c[2].first, 2);\n  VERIFY_IS_EQUAL(d2_c[2].second, 12);\n\n  EIGEN_STATIC_ASSERT((d2_a.value_known_statically(0) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((d2_a.value_known_statically(1) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((d2_a.value_known_statically(2) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((d2_b.value_known_statically(0) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((d2_b.value_known_statically(1) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((d2_b.value_known_statically(2) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((d2_c.value_known_statically(0) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((d2_c.value_known_statically(1) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((d2_c.value_known_statically(2) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims0>(0, 0) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims0>(0, 1) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_a>(0, 0) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_a>(0, 1) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_a>(1, 1) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_a>(1, 2) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_a>(2, 2) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_a>(2, 3) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_b>(0, 0) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_b>(0, 1) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_b>(1, 1) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_b>(1, 2) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_b>(2, 2) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_b>(2, 3) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_c>(0, 0) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_c>(0, 1) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_c>(1, 1) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_c>(1, 2) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_c>(2, 2) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_c>(2, 3) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims0>(0, 10) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims0>(0, 11) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_a>(0, 10) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_a>(0, 11) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_a>(1, 11) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_a>(1, 12) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_a>(2, 12) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_a>(2, 13) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_b>(0, 10) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_b>(0, 11) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_b>(1, 11) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_b>(1, 12) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_b>(2, 12) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_b>(2, 13) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_c>(0, 10) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_c>(0, 11) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_c>(1, 11) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_c>(1, 12) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_c>(2, 12) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_c>(2, 13) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n}\n\n\nstatic void test_dynamic_index_list()\n{\n  Tensor<float, 4> tensor(2,3,5,7);\n  tensor.setRandom();\n\n  int dim1 = 2;\n  int dim2 = 1;\n  int dim3 = 0;\n\n  auto reduction_axis = make_index_list(dim1, dim2, dim3);\n\n  VERIFY_IS_EQUAL(internal::array_get<0>(reduction_axis), 2);\n  VERIFY_IS_EQUAL(internal::array_get<1>(reduction_axis), 1);\n  VERIFY_IS_EQUAL(internal::array_get<2>(reduction_axis), 0);\n  VERIFY_IS_EQUAL(static_cast<Index>(reduction_axis[0]), 2);\n  VERIFY_IS_EQUAL(static_cast<Index>(reduction_axis[1]), 1);\n  VERIFY_IS_EQUAL(static_cast<Index>(reduction_axis[2]), 0);\n\n  Tensor<float, 1> result = tensor.sum(reduction_axis);\n  for (int i = 0; i < result.size(); ++i) {\n    float expected = 0.0f;\n    for (int j = 0; j < 2; ++j) {\n      for (int k = 0; k < 3; ++k) {\n        for (int l = 0; l < 5; ++l) {\n          expected += tensor(j,k,l,i);\n        }\n      }\n    }\n    VERIFY_IS_APPROX(result(i), expected);\n  }\n}\n\nstatic void test_mixed_index_list()\n{\n  Tensor<float, 4> tensor(2,3,5,7);\n  tensor.setRandom();\n\n  int dim2 = 1;\n  int dim4 = 3;\n\n  auto reduction_axis = make_index_list(0, dim2, 2, dim4);\n\n  VERIFY_IS_EQUAL(internal::array_get<0>(reduction_axis), 0);\n  VERIFY_IS_EQUAL(internal::array_get<1>(reduction_axis), 1);\n  VERIFY_IS_EQUAL(internal::array_get<2>(reduction_axis), 2);\n  VERIFY_IS_EQUAL(internal::array_get<3>(reduction_axis), 3);\n  VERIFY_IS_EQUAL(static_cast<Index>(reduction_axis[0]), 0);\n  VERIFY_IS_EQUAL(static_cast<Index>(reduction_axis[1]), 1);\n  VERIFY_IS_EQUAL(static_cast<Index>(reduction_axis[2]), 2);\n  VERIFY_IS_EQUAL(static_cast<Index>(reduction_axis[3]), 3);\n\n  typedef IndexList<type2index<0>, int, type2index<2>, int> ReductionIndices;\n  ReductionIndices reduction_indices;\n  reduction_indices.set(1, 1);\n  reduction_indices.set(3, 3);\n  EIGEN_STATIC_ASSERT((internal::array_get<0>(reduction_indices) == 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::array_get<2>(reduction_indices) == 2), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::index_known_statically<ReductionIndices>(0) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::index_known_statically<ReductionIndices>(2) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::index_statically_eq<ReductionIndices>(0, 0) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::index_statically_eq<ReductionIndices>(2, 2) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n#if 0\n  EIGEN_STATIC_ASSERT((internal::all_indices_known_statically<ReductionIndices>() == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::indices_statically_known_to_increase<ReductionIndices>() == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n#endif\n\n  typedef IndexList<type2index<0>, type2index<1>, type2index<2>, type2index<3>> ReductionList;\n  ReductionList reduction_list;\n  EIGEN_STATIC_ASSERT((internal::index_statically_eq<ReductionList>(0, 0) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::index_statically_eq<ReductionList>(1, 1) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::index_statically_eq<ReductionList>(2, 2) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::index_statically_eq<ReductionList>(3, 3) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n#if 0\n  EIGEN_STATIC_ASSERT((internal::all_indices_known_statically<ReductionList>() == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::indices_statically_known_to_increase<ReductionList>() == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n#endif\n\n  Tensor<float, 0> result1 = tensor.sum(reduction_axis);\n  Tensor<float, 0> result2 = tensor.sum(reduction_indices);\n  Tensor<float, 0> result3 = tensor.sum(reduction_list);\n\n  float expected = 0.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          expected += tensor(i,j,k,l);\n        }\n      }\n    }\n  }\n  VERIFY_IS_APPROX(result1(), expected);\n  VERIFY_IS_APPROX(result2(), expected);\n  VERIFY_IS_APPROX(result3(), expected);\n}\n\n\nstatic void test_dim_check()\n{\n  Eigen::IndexList<Eigen::type2index<1>, int> dim1;\n  dim1.set(1, 2);\n  Eigen::IndexList<Eigen::type2index<1>, int> dim2;\n  dim2.set(1, 2);\n  VERIFY(dimensions_match(dim1, dim2));\n}\n\n\n#endif\n\nEIGEN_DECLARE_TEST(cxx11_tensor_index_list)\n{\n#ifdef EIGEN_HAS_INDEX_LIST\n  CALL_SUBTEST(test_static_index_list());\n  CALL_SUBTEST(test_type2index_list());\n  CALL_SUBTEST(test_type2indexpair_list());\n  CALL_SUBTEST(test_dynamic_index_list());\n  CALL_SUBTEST(test_mixed_index_list());\n  CALL_SUBTEST(test_dim_check());\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_inflation.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Ke Yang <yangke@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate<int DataLayout>\nstatic void test_simple_inflation()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> strides;\n\n  strides[0] = 1;\n  strides[1] = 1;\n  strides[2] = 1;\n  strides[3] = 1;\n\n  Tensor<float, 4, DataLayout> no_stride;\n  no_stride = tensor.inflate(strides);\n\n  VERIFY_IS_EQUAL(no_stride.dimension(0), 2);\n  VERIFY_IS_EQUAL(no_stride.dimension(1), 3);\n  VERIFY_IS_EQUAL(no_stride.dimension(2), 5);\n  VERIFY_IS_EQUAL(no_stride.dimension(3), 7);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), no_stride(i,j,k,l));\n        }\n      }\n    }\n  }\n\n  strides[0] = 2;\n  strides[1] = 4;\n  strides[2] = 2;\n  strides[3] = 3;\n  Tensor<float, 4, DataLayout> inflated;\n  inflated = tensor.inflate(strides);\n\n  VERIFY_IS_EQUAL(inflated.dimension(0), 3);\n  VERIFY_IS_EQUAL(inflated.dimension(1), 9);\n  VERIFY_IS_EQUAL(inflated.dimension(2), 9);\n  VERIFY_IS_EQUAL(inflated.dimension(3), 19);\n\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 9; ++j) {\n      for (int k = 0; k < 9; ++k) {\n        for (int l = 0; l < 19; ++l) {\n          if (i % 2 == 0 &&\n              j % 4 == 0 &&\n              k % 2 == 0 &&\n              l % 3 == 0) {\n            VERIFY_IS_EQUAL(inflated(i,j,k,l),\n                            tensor(i/2, j/4, k/2, l/3));\n          } else {\n            VERIFY_IS_EQUAL(0, inflated(i,j,k,l));\n          }\n        }\n      }\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_inflation)\n{\n  CALL_SUBTEST(test_simple_inflation<ColMajor>());\n  CALL_SUBTEST(test_simple_inflation<RowMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_inflation_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\n// Inflation Definition for each dimension the inflated val would be\n//((dim-1)*strid[dim] +1)\n\n// for 1 dimension vector of size 3 with value (4,4,4) with the inflated stride value of 3 would be changed to\n// tensor of size (2*3) +1 = 7 with the value of\n// (4, 0, 0, 4, 0, 0, 4).\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_simple_inflation_sycl(const Eigen::SyclDevice &sycl_device) {\n\n\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  array<IndexType, 4> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  Tensor<DataType, 4, DataLayout,IndexType> tensor(tensorRange);\n  Tensor<DataType, 4, DataLayout,IndexType> no_stride(tensorRange);\n  tensor.setRandom();\n\n  array<IndexType, 4> strides;\n  strides[0] = 1;\n  strides[1] = 1;\n  strides[2] = 1;\n  strides[3] = 1;\n\n\n  const size_t tensorBuffSize =tensor.size()*sizeof(DataType);\n  DataType* gpu_data_tensor  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  DataType* gpu_data_no_stride  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_tensor(gpu_data_tensor, tensorRange);\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_no_stride(gpu_data_no_stride, tensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_tensor, tensor.data(), tensorBuffSize);\n  gpu_no_stride.device(sycl_device)=gpu_tensor.inflate(strides);\n  sycl_device.memcpyDeviceToHost(no_stride.data(), gpu_data_no_stride, tensorBuffSize);\n\n  VERIFY_IS_EQUAL(no_stride.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(no_stride.dimension(1), sizeDim2);\n  VERIFY_IS_EQUAL(no_stride.dimension(2), sizeDim3);\n  VERIFY_IS_EQUAL(no_stride.dimension(3), sizeDim4);\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      for (IndexType k = 0; k < 5; ++k) {\n        for (IndexType l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), no_stride(i,j,k,l));\n        }\n      }\n    }\n  }\n\n\n  strides[0] = 2;\n  strides[1] = 4;\n  strides[2] = 2;\n  strides[3] = 3;\n\n  IndexType inflatedSizeDim1 = 3;\n  IndexType inflatedSizeDim2 = 9;\n  IndexType inflatedSizeDim3 = 9;\n  IndexType inflatedSizeDim4 = 19;\n  array<IndexType, 4> inflatedTensorRange = {{inflatedSizeDim1, inflatedSizeDim2, inflatedSizeDim3, inflatedSizeDim4}};\n\n  Tensor<DataType, 4, DataLayout, IndexType> inflated(inflatedTensorRange);\n\n  const size_t inflatedTensorBuffSize =inflated.size()*sizeof(DataType);\n  DataType* gpu_data_inflated  = static_cast<DataType*>(sycl_device.allocate(inflatedTensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType>> gpu_inflated(gpu_data_inflated, inflatedTensorRange);\n  gpu_inflated.device(sycl_device)=gpu_tensor.inflate(strides);\n  sycl_device.memcpyDeviceToHost(inflated.data(), gpu_data_inflated, inflatedTensorBuffSize);\n\n  VERIFY_IS_EQUAL(inflated.dimension(0), inflatedSizeDim1);\n  VERIFY_IS_EQUAL(inflated.dimension(1), inflatedSizeDim2);\n  VERIFY_IS_EQUAL(inflated.dimension(2), inflatedSizeDim3);\n  VERIFY_IS_EQUAL(inflated.dimension(3), inflatedSizeDim4);\n\n  for (IndexType i = 0; i < inflatedSizeDim1; ++i) {\n    for (IndexType j = 0; j < inflatedSizeDim2; ++j) {\n      for (IndexType k = 0; k < inflatedSizeDim3; ++k) {\n        for (IndexType l = 0; l < inflatedSizeDim4; ++l) {\n          if (i % strides[0] == 0 &&\n              j % strides[1] == 0 &&\n              k % strides[2] == 0 &&\n              l % strides[3] == 0) {\n            VERIFY_IS_EQUAL(inflated(i,j,k,l),\n                            tensor(i/strides[0], j/strides[1], k/strides[2], l/strides[3]));\n          } else {\n            VERIFY_IS_EQUAL(0, inflated(i,j,k,l));\n          }\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data_tensor);\n  sycl_device.deallocate(gpu_data_no_stride);\n  sycl_device.deallocate(gpu_data_inflated);\n}\n\ntemplate<typename DataType, typename dev_Selector> void sycl_inflation_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_simple_inflation_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_simple_inflation_sycl<DataType, ColMajor, int64_t>(sycl_device);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_inflation_sycl)\n{\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_inflation_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_intdiv.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014-2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\n\nvoid test_signed_32bit()\n{\n  // Divide by one\n  const Eigen::internal::TensorIntDivisor<int32_t, false> div_by_one(1);\n\n  for (int32_t j = 0; j < 25000; ++j) {\n    const int32_t fast_div = j / div_by_one;\n    const int32_t slow_div = j / 1;\n    VERIFY_IS_EQUAL(fast_div, slow_div);\n  }\n\n  // Standard divide by 2 or more\n  for (int32_t i = 2; i < 25000; ++i) {\n    const Eigen::internal::TensorIntDivisor<int32_t, false> div(i);\n\n    for (int32_t j = 0; j < 25000; ++j) {\n      const int32_t fast_div = j / div;\n      const int32_t slow_div = j / i;\n      VERIFY_IS_EQUAL(fast_div, slow_div);\n    }\n  }\n\n  // Optimized divide by 2 or more\n  for (int32_t i = 2; i < 25000; ++i) {\n    const Eigen::internal::TensorIntDivisor<int32_t, true> div(i);\n\n    for (int32_t j = 0; j < 25000; ++j) {\n      const int32_t fast_div = j / div;\n      const int32_t slow_div = j / i;\n      VERIFY_IS_EQUAL(fast_div, slow_div);\n    }\n  }\n}\n\n\nvoid test_unsigned_32bit()\n{\n  for (uint32_t i = 1; i < 25000; ++i) {\n    const Eigen::internal::TensorIntDivisor<uint32_t> div(i);\n\n    for (uint32_t j = 0; j < 25000; ++j) {\n      const uint32_t fast_div = j / div;\n      const uint32_t slow_div = j / i;\n      VERIFY_IS_EQUAL(fast_div, slow_div);\n    }\n  }\n}\n\n\nvoid test_signed_64bit()\n{\n  for (int64_t i = 1; i < 25000; ++i) {\n    const Eigen::internal::TensorIntDivisor<int64_t> div(i);\n\n    for (int64_t j = 0; j < 25000; ++j) {\n      const int64_t fast_div = j / div;\n      const int64_t slow_div = j / i;\n      VERIFY_IS_EQUAL(fast_div, slow_div);\n    }\n  }\n}\n\n\nvoid test_unsigned_64bit()\n{\n  for (uint64_t i = 1; i < 25000; ++i) {\n    const Eigen::internal::TensorIntDivisor<uint64_t> div(i);\n\n    for (uint64_t j = 0; j < 25000; ++j) {\n      const uint64_t fast_div = j / div;\n      const uint64_t slow_div = j / i;\n      VERIFY_IS_EQUAL(fast_div, slow_div);\n    }\n  }\n}\n\nvoid test_powers_32bit() {\n  for (int expon = 1; expon < 31; expon++) {\n    int32_t div = (1 << expon);\n    for (int num_expon = 0; num_expon < 32; num_expon++) {\n      int32_t start_num = (1 << num_expon) - 100;\n      int32_t end_num = (1 << num_expon) + 100;\n      if (start_num < 0)\n        start_num = 0;\n      for (int32_t num = start_num; num < end_num; num++) {\n        Eigen::internal::TensorIntDivisor<int32_t> divider =\n          Eigen::internal::TensorIntDivisor<int32_t>(div);\n        int32_t result = num/div;\n        int32_t result_op = divider.divide(num);\n        VERIFY_IS_EQUAL(result_op, result);\n      }\n    }\n  }\n}\n\nvoid test_powers_64bit() {\n  for (int expon = 0; expon < 63; expon++) {\n    int64_t div = (1ull << expon);\n    for (int num_expon = 0; num_expon < 63; num_expon++) {\n      int64_t start_num = (1ull << num_expon) - 10;\n      int64_t end_num = (1ull << num_expon) + 10;\n      if (start_num < 0)\n        start_num = 0;\n      for (int64_t num = start_num; num < end_num; num++) {\n        Eigen::internal::TensorIntDivisor<int64_t> divider(div);\n        int64_t result = num/div;\n        int64_t result_op = divider.divide(num);\n        VERIFY_IS_EQUAL(result_op, result);\n      }\n    }\n  }\n}\n\nvoid test_specific() {\n  // A particular combination that was previously failing\n  int64_t div = 209715200;\n  int64_t num = 3238002688ll;\n  Eigen::internal::TensorIntDivisor<int64_t> divider(div);\n  int64_t result = num/div;\n  int64_t result_op = divider.divide(num);\n  VERIFY_IS_EQUAL(result, result_op);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_intdiv)\n{\n  CALL_SUBTEST_1(test_signed_32bit());\n  CALL_SUBTEST_2(test_unsigned_32bit());\n  CALL_SUBTEST_3(test_signed_64bit());\n  CALL_SUBTEST_4(test_unsigned_64bit());\n  CALL_SUBTEST_5(test_powers_32bit());\n  CALL_SUBTEST_6(test_powers_64bit());\n  CALL_SUBTEST_7(test_specific());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_io.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <sstream>\n#include <string>\n#include <Eigen/CXX11/Tensor>\n\n\ntemplate<int DataLayout>\nstatic void test_output_0d()\n{\n  Tensor<int, 0, DataLayout> tensor;\n  tensor() = 123;\n\n  std::stringstream os;\n  os << tensor;\n\n  std::string expected(\"123\");\n  VERIFY_IS_EQUAL(std::string(os.str()), expected);\n}\n\n\ntemplate<int DataLayout>\nstatic void test_output_1d()\n{\n  Tensor<int, 1, DataLayout> tensor(5);\n  for (int i = 0; i < 5; ++i) {\n    tensor(i) = i;\n  }\n\n  std::stringstream os;\n  os << tensor;\n\n  std::string expected(\"0\\n1\\n2\\n3\\n4\");\n  VERIFY_IS_EQUAL(std::string(os.str()), expected);\n\n  Eigen::Tensor<double,1,DataLayout> empty_tensor(0);\n  std::stringstream empty_os;\n  empty_os << empty_tensor;\n  std::string empty_string;\n  VERIFY_IS_EQUAL(std::string(empty_os.str()), empty_string);\n}\n\n\ntemplate<int DataLayout>\nstatic void test_output_2d()\n{\n  Tensor<int, 2, DataLayout> tensor(5, 3);\n  for (int i = 0; i < 5; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      tensor(i, j) = i*j;\n    }\n  }\n\n  std::stringstream os;\n  os << tensor;\n\n  std::string expected(\"0  0  0\\n0  1  2\\n0  2  4\\n0  3  6\\n0  4  8\");\n  VERIFY_IS_EQUAL(std::string(os.str()), expected);\n}\n\n\ntemplate<int DataLayout>\nstatic void test_output_expr()\n{\n  Tensor<int, 1, DataLayout> tensor1(5);\n  Tensor<int, 1, DataLayout> tensor2(5);\n  for (int i = 0; i < 5; ++i) {\n    tensor1(i) = i;\n    tensor2(i) = 7;\n  }\n\n  std::stringstream os;\n  os << tensor1 + tensor2;\n\n  std::string expected(\" 7\\n 8\\n 9\\n10\\n11\");\n  VERIFY_IS_EQUAL(std::string(os.str()), expected);\n}\n\n\ntemplate<int DataLayout>\nstatic void test_output_string()\n{\n  Tensor<std::string, 2, DataLayout> tensor(5, 3);\n  tensor.setConstant(std::string(\"foo\"));\n\n  std::cout << tensor << std::endl;\n\n  std::stringstream os;\n  os << tensor;\n\n  std::string expected(\"foo  foo  foo\\nfoo  foo  foo\\nfoo  foo  foo\\nfoo  foo  foo\\nfoo  foo  foo\");\n  VERIFY_IS_EQUAL(std::string(os.str()), expected);\n}\n\n\ntemplate<int DataLayout>\nstatic void test_output_const()\n{\n  Tensor<int, 1, DataLayout> tensor(5);\n  for (int i = 0; i < 5; ++i) {\n    tensor(i) = i;\n  }\n\n  TensorMap<Tensor<const int, 1, DataLayout> > tensor_map(tensor.data(), 5);\n\n  std::stringstream os;\n  os << tensor_map;\n\n  std::string expected(\"0\\n1\\n2\\n3\\n4\");\n  VERIFY_IS_EQUAL(std::string(os.str()), expected);\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_io)\n{\n  CALL_SUBTEST(test_output_0d<ColMajor>());\n  CALL_SUBTEST(test_output_0d<RowMajor>());\n  CALL_SUBTEST(test_output_1d<ColMajor>());\n  CALL_SUBTEST(test_output_1d<RowMajor>());\n  CALL_SUBTEST(test_output_2d<ColMajor>());\n  CALL_SUBTEST(test_output_2d<RowMajor>());\n  CALL_SUBTEST(test_output_expr<ColMajor>());\n  CALL_SUBTEST(test_output_expr<RowMajor>());\n  CALL_SUBTEST(test_output_string<ColMajor>());\n  CALL_SUBTEST(test_output_string<RowMajor>());\n  CALL_SUBTEST(test_output_const<ColMajor>());\n  CALL_SUBTEST(test_output_const<RowMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_layout_swap.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\nstatic void test_simple_swap()\n{\n  Tensor<float, 3, ColMajor> tensor(2,3,7);\n  tensor.setRandom();\n\n  Tensor<float, 3, RowMajor> tensor2 = tensor.swap_layout();\n  VERIFY_IS_EQUAL(tensor.dimension(0), tensor2.dimension(2));\n  VERIFY_IS_EQUAL(tensor.dimension(1), tensor2.dimension(1));\n  VERIFY_IS_EQUAL(tensor.dimension(2), tensor2.dimension(0));\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(tensor(i,j,k), tensor2(k,j,i));\n      }\n    }\n  }\n}\n\n\nstatic void test_swap_as_lvalue()\n{\n  Tensor<float, 3, ColMajor> tensor(2,3,7);\n  tensor.setRandom();\n\n  Tensor<float, 3, RowMajor> tensor2(7,3,2);\n  tensor2.swap_layout() = tensor;\n  VERIFY_IS_EQUAL(tensor.dimension(0), tensor2.dimension(2));\n  VERIFY_IS_EQUAL(tensor.dimension(1), tensor2.dimension(1));\n  VERIFY_IS_EQUAL(tensor.dimension(2), tensor2.dimension(0));\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(tensor(i,j,k), tensor2(k,j,i));\n      }\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_layout_swap)\n{\n  CALL_SUBTEST(test_simple_swap());\n  CALL_SUBTEST(test_swap_as_lvalue());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_layout_swap_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate <typename DataType, typename IndexType>\nstatic void test_simple_swap_sycl(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 7;\n  array<IndexType, 3> tensorColRange = {{sizeDim1, sizeDim2, sizeDim3}};\n  array<IndexType, 3> tensorRowRange = {{sizeDim3, sizeDim2, sizeDim1}};\n\n\n  Tensor<DataType, 3, ColMajor, IndexType> tensor1(tensorColRange);\n  Tensor<DataType, 3, RowMajor, IndexType> tensor2(tensorRowRange);\n  tensor1.setRandom();\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(tensor1.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(tensor2.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 3, ColMajor, IndexType>> gpu1(gpu_data1, tensorColRange);\n  TensorMap<Tensor<DataType, 3, RowMajor, IndexType>> gpu2(gpu_data2, tensorRowRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor1.data(),(tensor1.size())*sizeof(DataType));\n  gpu2.device(sycl_device)=gpu1.swap_layout();\n  sycl_device.memcpyDeviceToHost(tensor2.data(), gpu_data2,(tensor2.size())*sizeof(DataType));\n\n\n//  Tensor<float, 3, ColMajor> tensor(2,3,7);\n  //tensor.setRandom();\n\n//  Tensor<float, 3, RowMajor> tensor2 = tensor.swap_layout();\n  VERIFY_IS_EQUAL(tensor1.dimension(0), tensor2.dimension(2));\n  VERIFY_IS_EQUAL(tensor1.dimension(1), tensor2.dimension(1));\n  VERIFY_IS_EQUAL(tensor1.dimension(2), tensor2.dimension(0));\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      for (IndexType k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(tensor1(i,j,k), tensor2(k,j,i));\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n}\n\ntemplate <typename DataType, typename IndexType>\nstatic void test_swap_as_lvalue_sycl(const Eigen::SyclDevice& sycl_device)\n{\n\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 7;\n  array<IndexType, 3> tensorColRange = {{sizeDim1, sizeDim2, sizeDim3}};\n  array<IndexType, 3> tensorRowRange = {{sizeDim3, sizeDim2, sizeDim1}};\n\n  Tensor<DataType, 3, ColMajor, IndexType> tensor1(tensorColRange);\n  Tensor<DataType, 3, RowMajor, IndexType> tensor2(tensorRowRange);\n  tensor1.setRandom();\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(tensor1.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(tensor2.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 3, ColMajor, IndexType>> gpu1(gpu_data1, tensorColRange);\n  TensorMap<Tensor<DataType, 3, RowMajor, IndexType>> gpu2(gpu_data2, tensorRowRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor1.data(),(tensor1.size())*sizeof(DataType));\n  gpu2.swap_layout().device(sycl_device)=gpu1;\n  sycl_device.memcpyDeviceToHost(tensor2.data(), gpu_data2,(tensor2.size())*sizeof(DataType));\n\n\n//  Tensor<float, 3, ColMajor> tensor(2,3,7);\n//  tensor.setRandom();\n\n  //Tensor<float, 3, RowMajor> tensor2(7,3,2);\n//  tensor2.swap_layout() = tensor;\n  VERIFY_IS_EQUAL(tensor1.dimension(0), tensor2.dimension(2));\n  VERIFY_IS_EQUAL(tensor1.dimension(1), tensor2.dimension(1));\n  VERIFY_IS_EQUAL(tensor1.dimension(2), tensor2.dimension(0));\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      for (IndexType k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(tensor1(i,j,k), tensor2(k,j,i));\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n}\n\n\ntemplate<typename DataType, typename dev_Selector> void sycl_tensor_layout_swap_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_simple_swap_sycl<DataType, int64_t>(sycl_device);\n  test_swap_as_lvalue_sycl<DataType, int64_t>(sycl_device);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_layout_swap_sycl)\n{\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_tensor_layout_swap_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_lvalue.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\n\nstatic void test_compound_assignment()\n{\n  Tensor<float, 3> mat1(2,3,7);\n  Tensor<float, 3> mat2(2,3,7);\n  Tensor<float, 3> mat3(2,3,7);\n\n  mat1.setRandom();\n  mat2.setRandom();\n  mat3 = mat1;\n  mat3 += mat2;\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(mat3(i,j,k), mat1(i,j,k) + mat2(i,j,k));\n      }\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_lvalue)\n{\n  CALL_SUBTEST(test_compound_assignment());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_map.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\nstatic void test_0d()\n{\n  Tensor<int, 0> scalar1;\n  Tensor<int, 0, RowMajor> scalar2;\n\n  TensorMap<const Tensor<int, 0> > scalar3(scalar1.data());\n  TensorMap<const Tensor<int, 0, RowMajor> > scalar4(scalar2.data());\n\n  scalar1() = 7;\n  scalar2() = 13;\n\n  VERIFY_IS_EQUAL(scalar1.rank(), 0);\n  VERIFY_IS_EQUAL(scalar1.size(), 1);\n\n  VERIFY_IS_EQUAL(scalar3(), 7);\n  VERIFY_IS_EQUAL(scalar4(), 13);\n}\n\nstatic void test_1d()\n{\n  Tensor<int, 1> vec1(6);\n  Tensor<int, 1, RowMajor> vec2(6);\n\n  TensorMap<const Tensor<int, 1> > vec3(vec1.data(), 6);\n  TensorMap<const Tensor<int, 1, RowMajor> > vec4(vec2.data(), 6);\n\n  vec1(0) = 4;  vec2(0) = 0;\n  vec1(1) = 8;  vec2(1) = 1;\n  vec1(2) = 15; vec2(2) = 2;\n  vec1(3) = 16; vec2(3) = 3;\n  vec1(4) = 23; vec2(4) = 4;\n  vec1(5) = 42; vec2(5) = 5;\n\n  VERIFY_IS_EQUAL(vec1.rank(), 1);\n  VERIFY_IS_EQUAL(vec1.size(), 6);\n  VERIFY_IS_EQUAL(vec1.dimension(0), 6);\n\n  VERIFY_IS_EQUAL(vec3(0), 4);\n  VERIFY_IS_EQUAL(vec3(1), 8);\n  VERIFY_IS_EQUAL(vec3(2), 15);\n  VERIFY_IS_EQUAL(vec3(3), 16);\n  VERIFY_IS_EQUAL(vec3(4), 23);\n  VERIFY_IS_EQUAL(vec3(5), 42);\n\n  VERIFY_IS_EQUAL(vec4(0), 0);\n  VERIFY_IS_EQUAL(vec4(1), 1);\n  VERIFY_IS_EQUAL(vec4(2), 2);\n  VERIFY_IS_EQUAL(vec4(3), 3);\n  VERIFY_IS_EQUAL(vec4(4), 4);\n  VERIFY_IS_EQUAL(vec4(5), 5);\n}\n\nstatic void test_2d()\n{\n  Tensor<int, 2> mat1(2,3);\n  Tensor<int, 2, RowMajor> mat2(2,3);\n\n  mat1(0,0) = 0;\n  mat1(0,1) = 1;\n  mat1(0,2) = 2;\n  mat1(1,0) = 3;\n  mat1(1,1) = 4;\n  mat1(1,2) = 5;\n\n  mat2(0,0) = 0;\n  mat2(0,1) = 1;\n  mat2(0,2) = 2;\n  mat2(1,0) = 3;\n  mat2(1,1) = 4;\n  mat2(1,2) = 5;\n\n  TensorMap<const Tensor<int, 2> > mat3(mat1.data(), 2, 3);\n  TensorMap<const Tensor<int, 2, RowMajor> > mat4(mat2.data(), 2, 3);\n\n  VERIFY_IS_EQUAL(mat3.rank(), 2);\n  VERIFY_IS_EQUAL(mat3.size(), 6);\n  VERIFY_IS_EQUAL(mat3.dimension(0), 2);\n  VERIFY_IS_EQUAL(mat3.dimension(1), 3);\n\n  VERIFY_IS_EQUAL(mat4.rank(), 2);\n  VERIFY_IS_EQUAL(mat4.size(), 6);\n  VERIFY_IS_EQUAL(mat4.dimension(0), 2);\n  VERIFY_IS_EQUAL(mat4.dimension(1), 3);\n\n  VERIFY_IS_EQUAL(mat3(0,0), 0);\n  VERIFY_IS_EQUAL(mat3(0,1), 1);\n  VERIFY_IS_EQUAL(mat3(0,2), 2);\n  VERIFY_IS_EQUAL(mat3(1,0), 3);\n  VERIFY_IS_EQUAL(mat3(1,1), 4);\n  VERIFY_IS_EQUAL(mat3(1,2), 5);\n\n  VERIFY_IS_EQUAL(mat4(0,0), 0);\n  VERIFY_IS_EQUAL(mat4(0,1), 1);\n  VERIFY_IS_EQUAL(mat4(0,2), 2);\n  VERIFY_IS_EQUAL(mat4(1,0), 3);\n  VERIFY_IS_EQUAL(mat4(1,1), 4);\n  VERIFY_IS_EQUAL(mat4(1,2), 5);\n}\n\nstatic void test_3d()\n{\n  Tensor<int, 3> mat1(2,3,7);\n  Tensor<int, 3, RowMajor> mat2(2,3,7);\n\n  int val = 0;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        mat1(i,j,k) = val;\n        mat2(i,j,k) = val;\n        val++;\n      }\n    }\n  }\n\n  TensorMap<const Tensor<int, 3> > mat3(mat1.data(), 2, 3, 7);\n  TensorMap<const Tensor<int, 3, RowMajor> > mat4(mat2.data(), 2, 3, 7);\n\n  VERIFY_IS_EQUAL(mat3.rank(), 3);\n  VERIFY_IS_EQUAL(mat3.size(), 2*3*7);\n  VERIFY_IS_EQUAL(mat3.dimension(0), 2);\n  VERIFY_IS_EQUAL(mat3.dimension(1), 3);\n  VERIFY_IS_EQUAL(mat3.dimension(2), 7);\n\n  VERIFY_IS_EQUAL(mat4.rank(), 3);\n  VERIFY_IS_EQUAL(mat4.size(), 2*3*7);\n  VERIFY_IS_EQUAL(mat4.dimension(0), 2);\n  VERIFY_IS_EQUAL(mat4.dimension(1), 3);\n  VERIFY_IS_EQUAL(mat4.dimension(2), 7);\n\n  val = 0;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(mat3(i,j,k), val);\n        VERIFY_IS_EQUAL(mat4(i,j,k), val);\n        val++;\n      }\n    }\n  }\n}\n\n\nstatic void test_from_tensor()\n{\n  Tensor<int, 3> mat1(2,3,7);\n  Tensor<int, 3, RowMajor> mat2(2,3,7);\n\n  int val = 0;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        mat1(i,j,k) = val;\n        mat2(i,j,k) = val;\n        val++;\n      }\n    }\n  }\n\n  TensorMap<Tensor<int, 3> > mat3(mat1);\n  TensorMap<Tensor<int, 3, RowMajor> > mat4(mat2);\n\n  VERIFY_IS_EQUAL(mat3.rank(), 3);\n  VERIFY_IS_EQUAL(mat3.size(), 2*3*7);\n  VERIFY_IS_EQUAL(mat3.dimension(0), 2);\n  VERIFY_IS_EQUAL(mat3.dimension(1), 3);\n  VERIFY_IS_EQUAL(mat3.dimension(2), 7);\n\n  VERIFY_IS_EQUAL(mat4.rank(), 3);\n  VERIFY_IS_EQUAL(mat4.size(), 2*3*7);\n  VERIFY_IS_EQUAL(mat4.dimension(0), 2);\n  VERIFY_IS_EQUAL(mat4.dimension(1), 3);\n  VERIFY_IS_EQUAL(mat4.dimension(2), 7);\n\n  val = 0;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(mat3(i,j,k), val);\n        VERIFY_IS_EQUAL(mat4(i,j,k), val);\n        val++;\n      }\n    }\n  }\n\n  TensorFixedSize<int, Sizes<2,3,7> > mat5;\n\n  val = 0;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        array<ptrdiff_t, 3> coords;\n        coords[0] = i;\n        coords[1] = j;\n        coords[2] = k;\n        mat5(coords) = val;\n        val++;\n      }\n    }\n  }\n\n  TensorMap<TensorFixedSize<int, Sizes<2,3,7> > > mat6(mat5);\n\n  VERIFY_IS_EQUAL(mat6.rank(), 3);\n  VERIFY_IS_EQUAL(mat6.size(), 2*3*7);\n  VERIFY_IS_EQUAL(mat6.dimension(0), 2);\n  VERIFY_IS_EQUAL(mat6.dimension(1), 3);\n  VERIFY_IS_EQUAL(mat6.dimension(2), 7);\n\n  val = 0;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(mat6(i,j,k), val);\n        val++;\n      }\n    }\n  }\n}\n\n\nstatic int f(const TensorMap<Tensor<int, 3> >& tensor) {\n  //  Size<0> empty;\n  EIGEN_STATIC_ASSERT((internal::array_size<Sizes<> >::value == 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::array_size<DSizes<int, 0> >::value == 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  Tensor<int, 0> result = tensor.sum();\n  return result();\n}\n\nstatic void test_casting()\n{\n  Tensor<int, 3> tensor(2,3,7);\n\n  int val = 0;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        tensor(i,j,k) = val;\n        val++;\n      }\n    }\n  }\n\n  TensorMap<Tensor<int, 3> > map(tensor);\n  int sum1 = f(map);\n  int sum2 = f(tensor);\n\n  VERIFY_IS_EQUAL(sum1, sum2);\n  VERIFY_IS_EQUAL(sum1, 861);\n}\n\ntemplate<typename T>\nstatic const T& add_const(T& value) {\n  return value;\n}\n\nstatic void test_0d_const_tensor()\n{\n  Tensor<int, 0> scalar1;\n  Tensor<int, 0, RowMajor> scalar2;\n\n  TensorMap<const Tensor<int, 0> > scalar3(add_const(scalar1).data());\n  TensorMap<const Tensor<int, 0, RowMajor> > scalar4(add_const(scalar2).data());\n\n  scalar1() = 7;\n  scalar2() = 13;\n\n  VERIFY_IS_EQUAL(scalar1.rank(), 0);\n  VERIFY_IS_EQUAL(scalar1.size(), 1);\n\n  VERIFY_IS_EQUAL(scalar3(), 7);\n  VERIFY_IS_EQUAL(scalar4(), 13);\n}\n\nstatic void test_0d_const_tensor_map()\n{\n  Tensor<int, 0> scalar1;\n  Tensor<int, 0, RowMajor> scalar2;\n\n  const TensorMap<Tensor<int, 0> > scalar3(scalar1.data());\n  const TensorMap<Tensor<int, 0, RowMajor> > scalar4(scalar2.data());\n\n  // Although TensorMap is constant, we still can write to the underlying\n  // storage, because we map over non-constant Tensor.\n  scalar3() = 7;\n  scalar4() = 13;\n\n  VERIFY_IS_EQUAL(scalar1(), 7);\n  VERIFY_IS_EQUAL(scalar2(), 13);\n\n  // Pointer to the underlying storage is also non-const.\n  scalar3.data()[0] = 8;\n  scalar4.data()[0] = 14;\n\n  VERIFY_IS_EQUAL(scalar1(), 8);\n  VERIFY_IS_EQUAL(scalar2(), 14);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_map)\n{\n  CALL_SUBTEST(test_0d());\n  CALL_SUBTEST(test_1d());\n  CALL_SUBTEST(test_2d());\n  CALL_SUBTEST(test_3d());\n\n  CALL_SUBTEST(test_from_tensor());\n  CALL_SUBTEST(test_casting());\n\n  CALL_SUBTEST(test_0d_const_tensor());\n  CALL_SUBTEST(test_0d_const_tensor_map());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_math.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\nstatic void test_tanh()\n{\n  Tensor<float, 1> vec1(6);\n  vec1.setRandom();\n\n  Tensor<float, 1> vec2 = vec1.tanh();\n\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_APPROX(vec2(i), tanhf(vec1(i)));\n  }\n}\n\nstatic void test_sigmoid()\n{\n  Tensor<float, 1> vec1(6);\n  vec1.setRandom();\n\n  Tensor<float, 1> vec2 = vec1.sigmoid();\n\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_APPROX(vec2(i), 1.0f / (1.0f + std::exp(-vec1(i))));\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_math)\n{\n  CALL_SUBTEST(test_tanh());\n  CALL_SUBTEST(test_sigmoid());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_math_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_tanh_sycl(const Eigen::SyclDevice &sycl_device)\n{\n\n  IndexType sizeDim1 = 4;\n  IndexType sizeDim2 = 4;\n  IndexType sizeDim3 = 1;\n  array<IndexType, 3> tensorRange = {{sizeDim1, sizeDim2, sizeDim3}};\n  Tensor<DataType, 3, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 3, DataLayout, IndexType> out(tensorRange);\n  Tensor<DataType, 3, DataLayout, IndexType> out_cpu(tensorRange);\n\n  in = in.random();\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(in.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(out.size()*sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu1(gpu_data1, tensorRange);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu2(gpu_data2, tensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data1, in.data(),(in.size())*sizeof(DataType));\n  gpu2.device(sycl_device) = gpu1.tanh();\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_data2,(out.size())*sizeof(DataType));\n\n  out_cpu=in.tanh();\n\n  for (int i = 0; i < in.size(); ++i) {\n    VERIFY_IS_APPROX(out(i), out_cpu(i));\n  }\n}\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_sigmoid_sycl(const Eigen::SyclDevice &sycl_device)\n{\n\n  IndexType sizeDim1 = 4;\n  IndexType sizeDim2 = 4;\n  IndexType sizeDim3 = 1;\n  array<IndexType, 3> tensorRange = {{sizeDim1, sizeDim2, sizeDim3}};\n  Tensor<DataType, 3, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 3, DataLayout, IndexType> out(tensorRange);\n  Tensor<DataType, 3, DataLayout, IndexType> out_cpu(tensorRange);\n\n  in = in.random();\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(in.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(out.size()*sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu1(gpu_data1, tensorRange);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu2(gpu_data2, tensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data1, in.data(),(in.size())*sizeof(DataType));\n  gpu2.device(sycl_device) = gpu1.sigmoid();\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_data2,(out.size())*sizeof(DataType));\n\n  out_cpu=in.sigmoid();\n\n  for (int i = 0; i < in.size(); ++i) {\n    VERIFY_IS_APPROX(out(i), out_cpu(i));\n  }\n}\n\n\ntemplate<typename DataType, typename dev_Selector> void sycl_computing_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_tanh_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_tanh_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_sigmoid_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_sigmoid_sycl<DataType, ColMajor, int64_t>(sycl_device);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_math_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_computing_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_mixed_indices.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\n\nstatic void test_simple()\n{\n  Tensor<float, 1, ColMajor> vec1(6);\n  Tensor<float, 1, ColMajor, int> vec2(6);\n\n  vec1(0) = 4.0;  vec2(0) = 0.0;\n  vec1(1) = 8.0;  vec2(1) = 1.0;\n  vec1(2) = 15.0; vec2(2) = 2.0;\n  vec1(3) = 16.0; vec2(3) = 3.0;\n  vec1(4) = 23.0; vec2(4) = 4.0;\n  vec1(5) = 42.0; vec2(5) = 5.0;\n\n  float data3[6];\n  TensorMap<Tensor<float, 1, ColMajor>> vec3(data3, 6);\n  vec3 = vec1.sqrt();\n  float data4[6];\n  TensorMap<Tensor<float, 1, ColMajor, int>> vec4(data4, 6);\n  vec4 = vec2.square();\n\n  VERIFY_IS_APPROX(vec3(0), sqrtf(4.0));\n  VERIFY_IS_APPROX(vec3(1), sqrtf(8.0));\n  VERIFY_IS_APPROX(vec3(2), sqrtf(15.0));\n  VERIFY_IS_APPROX(vec3(3), sqrtf(16.0));\n  VERIFY_IS_APPROX(vec3(4), sqrtf(23.0));\n  VERIFY_IS_APPROX(vec3(5), sqrtf(42.0));\n\n  VERIFY_IS_APPROX(vec4(0), 0.0f);\n  VERIFY_IS_APPROX(vec4(1), 1.0f);\n  VERIFY_IS_APPROX(vec4(2), 2.0f * 2.0f);\n  VERIFY_IS_APPROX(vec4(3), 3.0f * 3.0f);\n  VERIFY_IS_APPROX(vec4(4), 4.0f * 4.0f);\n  VERIFY_IS_APPROX(vec4(5), 5.0f * 5.0f);\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_mixed_indices)\n{\n  CALL_SUBTEST(test_simple());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_morphing.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate<typename>\nstatic void test_simple_reshape()\n{\n  Tensor<float, 5> tensor1(2,3,1,7,1);\n  tensor1.setRandom();\n\n  Tensor<float, 3> tensor2(2,3,7);\n  Tensor<float, 2> tensor3(6,7);\n  Tensor<float, 2> tensor4(2,21);\n\n  Tensor<float, 3>::Dimensions dim1(2,3,7);\n  tensor2 = tensor1.reshape(dim1);\n  Tensor<float, 2>::Dimensions dim2(6,7);\n  tensor3 = tensor1.reshape(dim2);\n  Tensor<float, 2>::Dimensions dim3(2,21);\n  tensor4 = tensor1.reshape(dim1).reshape(dim3);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(tensor1(i,j,0,k,0), tensor2(i,j,k));\n        VERIFY_IS_EQUAL(tensor1(i,j,0,k,0), tensor3(i+2*j,k));\n        VERIFY_IS_EQUAL(tensor1(i,j,0,k,0), tensor4(i,j+3*k));\n      }\n    }\n  }\n}\n\ntemplate <typename>\nstatic void test_static_reshape() {\n#if defined(EIGEN_HAS_INDEX_LIST)\n  using Eigen::type2index;\n\n  Tensor<float, 5> tensor(2, 3, 1, 7, 1);\n  tensor.setRandom();\n\n  // New dimensions: [2, 3, 7]\n  Eigen::IndexList<type2index<2>, type2index<3>, type2index<7>> dim;\n  Tensor<float, 3> reshaped = tensor.reshape(static_cast<Eigen::DSizes<ptrdiff_t,3>>(dim));\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(tensor(i, j, 0, k, 0), reshaped(i, j, k));\n      }\n    }\n  }\n#endif\n}\n\ntemplate <typename>\nstatic void test_reshape_in_expr() {\n  MatrixXf m1(2,3*5*7*11);\n  MatrixXf m2(3*5*7*11,13);\n  m1.setRandom();\n  m2.setRandom();\n  MatrixXf m3 = m1 * m2;\n\n  TensorMap<Tensor<float, 5>> tensor1(m1.data(), 2,3,5,7,11);\n  TensorMap<Tensor<float, 5>> tensor2(m2.data(), 3,5,7,11,13);\n  Tensor<float, 2>::Dimensions newDims1(2,3*5*7*11);\n  Tensor<float, 2>::Dimensions newDims2(3*5*7*11,13);\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n  array<DimPair, 1> contract_along{{DimPair(1, 0)}};\n  Tensor<float, 2> tensor3(2,13);\n  tensor3 = tensor1.reshape(newDims1).contract(tensor2.reshape(newDims2), contract_along);\n\n  Map<MatrixXf> res(tensor3.data(), 2, 13);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 13; ++j) {\n      VERIFY_IS_APPROX(res(i,j), m3(i,j));\n    }\n  }\n}\n\ntemplate<typename>\nstatic void test_reshape_as_lvalue()\n{\n  Tensor<float, 3> tensor(2,3,7);\n  tensor.setRandom();\n\n  Tensor<float, 2> tensor2d(6,7);\n  Tensor<float, 3>::Dimensions dim(2,3,7);\n  tensor2d.reshape(dim) = tensor;\n\n  float scratch[2*3*1*7*1];\n  TensorMap<Tensor<float, 5>> tensor5d(scratch, 2,3,1,7,1);\n  tensor5d.reshape(dim).device(Eigen::DefaultDevice()) = tensor;\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(tensor2d(i+2*j,k), tensor(i,j,k));\n        VERIFY_IS_EQUAL(tensor5d(i,j,0,k,0), tensor(i,j,k));\n      }\n    }\n  }\n}\n\ntemplate<typename T, int DataLayout>\nstatic void test_simple_slice()\n{\n  Tensor<T, 5, DataLayout> tensor(2,3,5,7,11);\n  tensor.setRandom();\n\n  Tensor<T, 5, DataLayout> slice1(1,1,1,1,1);\n  Eigen::DSizes<ptrdiff_t, 5> indices(1,2,3,4,5);\n  Eigen::DSizes<ptrdiff_t, 5> sizes(1,1,1,1,1);\n  slice1 = tensor.slice(indices, sizes);\n  VERIFY_IS_EQUAL(slice1(0,0,0,0,0), tensor(1,2,3,4,5));\n\n  Tensor<T, 5, DataLayout> slice2(1,1,2,2,3);\n  Eigen::DSizes<ptrdiff_t, 5> indices2(1,1,3,4,5);\n  Eigen::DSizes<ptrdiff_t, 5> sizes2(1,1,2,2,3);\n  slice2 = tensor.slice(indices2, sizes2);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 2; ++j) {\n      for (int k = 0; k < 3; ++k) {\n        VERIFY_IS_EQUAL(slice2(0,0,i,j,k), tensor(1,1,3+i,4+j,5+k));\n      }\n    }\n  }\n}\n\ntemplate<typename T>\nstatic void test_const_slice()\n{\n  const T b[1] = {42};\n  TensorMap<Tensor<const T, 1> > m(b, 1);\n  DSizes<DenseIndex, 1> offsets;\n  offsets[0] = 0;\n  TensorRef<Tensor<const T, 1> > slice_ref(m.slice(offsets, m.dimensions()));\n  VERIFY_IS_EQUAL(slice_ref(0), 42);\n}\n\ntemplate<typename T, int DataLayout>\nstatic void test_slice_in_expr() {\n  typedef Matrix<T, Dynamic, Dynamic, DataLayout> Mtx;\n  Mtx m1(7,7);\n  Mtx m2(3,3);\n  m1.setRandom();\n  m2.setRandom();\n\n  Mtx m3 = m1.block(1, 2, 3, 3) * m2.block(0, 2, 3, 1);\n\n  TensorMap<Tensor<T, 2, DataLayout>> tensor1(m1.data(), 7, 7);\n  TensorMap<Tensor<T, 2, DataLayout>> tensor2(m2.data(), 3, 3);\n  Tensor<T, 2, DataLayout> tensor3(3,1);\n  typedef typename Tensor<T, 1>::DimensionPair DimPair;\n  array<DimPair, 1> contract_along{{DimPair(1, 0)}};\n\n  Eigen::DSizes<ptrdiff_t, 2> indices1(1,2);\n  Eigen::DSizes<ptrdiff_t, 2> sizes1(3,3);\n  Eigen::DSizes<ptrdiff_t, 2> indices2(0,2);\n  Eigen::DSizes<ptrdiff_t, 2> sizes2(3,1);\n  tensor3 = tensor1.slice(indices1, sizes1).contract(tensor2.slice(indices2, sizes2), contract_along);\n\n  Map<Mtx> res(tensor3.data(), 3, 1);\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 1; ++j) {\n      VERIFY_IS_APPROX(res(i,j), m3(i,j));\n    }\n  }\n\n  // Take an arbitrary slice of an arbitrarily sized tensor.\n  TensorMap<Tensor<const T, 2, DataLayout>> tensor4(m1.data(), 7, 7);\n  Tensor<T, 1, DataLayout> tensor6 = tensor4.reshape(DSizes<ptrdiff_t, 1>(7*7)).exp().slice(DSizes<ptrdiff_t, 1>(0), DSizes<ptrdiff_t, 1>(35));\n  for (int i = 0; i < 35; ++i) {\n    VERIFY_IS_APPROX(tensor6(i), expf(tensor4.data()[i]));\n  }\n}\n\ntemplate<typename T, int DataLayout>\nstatic void test_slice_as_lvalue()\n{\n  Tensor<T, 3, DataLayout> tensor1(2,2,7);\n  tensor1.setRandom();\n  Tensor<T, 3, DataLayout> tensor2(2,2,7);\n  tensor2.setRandom();\n  Tensor<T, 3, DataLayout> tensor3(4,3,5);\n  tensor3.setRandom();\n  Tensor<T, 3, DataLayout> tensor4(4,3,2);\n  tensor4.setRandom();\n  Tensor<T, 3, DataLayout> tensor5(10,13,12);\n  tensor5.setRandom();\n\n  Tensor<T, 3, DataLayout> result(4,5,7);\n  Eigen::DSizes<ptrdiff_t, 3> sizes12(2,2,7);\n  Eigen::DSizes<ptrdiff_t, 3> first_slice(0,0,0);\n  result.slice(first_slice, sizes12) = tensor1;\n  Eigen::DSizes<ptrdiff_t, 3> second_slice(2,0,0);\n  result.slice(second_slice, sizes12).device(Eigen::DefaultDevice()) = tensor2;\n\n  Eigen::DSizes<ptrdiff_t, 3> sizes3(4,3,5);\n  Eigen::DSizes<ptrdiff_t, 3> third_slice(0,2,0);\n  result.slice(third_slice, sizes3) = tensor3;\n\n  Eigen::DSizes<ptrdiff_t, 3> sizes4(4,3,2);\n  Eigen::DSizes<ptrdiff_t, 3> fourth_slice(0,2,5);\n  result.slice(fourth_slice, sizes4) = tensor4;\n\n  for (int j = 0; j < 2; ++j) {\n    for (int k = 0; k < 7; ++k) {\n      for (int i = 0; i < 2; ++i) {\n        VERIFY_IS_EQUAL(result(i,j,k), tensor1(i,j,k));\n        VERIFY_IS_EQUAL(result(i+2,j,k), tensor2(i,j,k));\n      }\n    }\n  }\n  for (int i = 0; i < 4; ++i) {\n    for (int j = 2; j < 5; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        VERIFY_IS_EQUAL(result(i,j,k), tensor3(i,j-2,k));\n      }\n      for (int k = 5; k < 7; ++k) {\n        VERIFY_IS_EQUAL(result(i,j,k), tensor4(i,j-2,k-5));\n      }\n    }\n  }\n\n  Eigen::DSizes<ptrdiff_t, 3> sizes5(4,5,7);\n  Eigen::DSizes<ptrdiff_t, 3> fifth_slice(0,0,0);\n  result.slice(fifth_slice, sizes5) = tensor5.slice(fifth_slice, sizes5);\n  for (int i = 0; i < 4; ++i) {\n    for (int j = 2; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(result(i,j,k), tensor5(i,j,k));\n      }\n    }\n  }\n}\n\ntemplate<typename T, int DataLayout>\nstatic void test_slice_raw_data()\n{\n  Tensor<T, 4, DataLayout> tensor(3,5,7,11);\n  tensor.setRandom();\n\n  Eigen::DSizes<ptrdiff_t, 4> offsets(1,2,3,4);\n  Eigen::DSizes<ptrdiff_t, 4> extents(1,1,1,1);\n  typedef TensorEvaluator<decltype(tensor.slice(offsets, extents)), DefaultDevice> SliceEvaluator;\n  auto slice1 = SliceEvaluator(tensor.slice(offsets, extents), DefaultDevice());\n  VERIFY_IS_EQUAL(slice1.dimensions().TotalSize(), 1);\n  VERIFY_IS_EQUAL(slice1.data()[0], tensor(1,2,3,4));\n\n  if (DataLayout == ColMajor) {\n    extents = Eigen::DSizes<ptrdiff_t, 4>(2,1,1,1);\n    auto slice2 = SliceEvaluator(tensor.slice(offsets, extents), DefaultDevice());\n    VERIFY_IS_EQUAL(slice2.dimensions().TotalSize(), 2);\n    VERIFY_IS_EQUAL(slice2.data()[0], tensor(1,2,3,4));\n    VERIFY_IS_EQUAL(slice2.data()[1], tensor(2,2,3,4));\n  } else {\n    extents = Eigen::DSizes<ptrdiff_t, 4>(1,1,1,2);\n    auto slice2 = SliceEvaluator(tensor.slice(offsets, extents), DefaultDevice());\n    VERIFY_IS_EQUAL(slice2.dimensions().TotalSize(), 2);\n    VERIFY_IS_EQUAL(slice2.data()[0], tensor(1,2,3,4));\n    VERIFY_IS_EQUAL(slice2.data()[1], tensor(1,2,3,5));\n  }\n\n  extents = Eigen::DSizes<ptrdiff_t, 4>(1,2,1,1);\n  auto slice3 = SliceEvaluator(tensor.slice(offsets, extents), DefaultDevice());\n  VERIFY_IS_EQUAL(slice3.dimensions().TotalSize(), 2);\n  VERIFY_IS_EQUAL(slice3.data(), static_cast<T*>(0));\n\n  if (DataLayout == ColMajor) {\n    offsets = Eigen::DSizes<ptrdiff_t, 4>(0,2,3,4);\n    extents = Eigen::DSizes<ptrdiff_t, 4>(3,2,1,1);\n    auto slice4 = SliceEvaluator(tensor.slice(offsets, extents), DefaultDevice());\n    VERIFY_IS_EQUAL(slice4.dimensions().TotalSize(), 6);\n    for (int i = 0; i < 3; ++i) {\n      for (int j = 0; j < 2; ++j) {\n        VERIFY_IS_EQUAL(slice4.data()[i+3*j], tensor(i,2+j,3,4));\n      }\n    }\n  } else {\n    offsets = Eigen::DSizes<ptrdiff_t, 4>(1,2,3,0);\n    extents = Eigen::DSizes<ptrdiff_t, 4>(1,1,2,11);\n    auto slice4 = SliceEvaluator(tensor.slice(offsets, extents), DefaultDevice());\n    VERIFY_IS_EQUAL(slice4.dimensions().TotalSize(), 22);\n    for (int l = 0; l < 11; ++l) {\n      for (int k = 0; k < 2; ++k) {\n        VERIFY_IS_EQUAL(slice4.data()[l+11*k], tensor(1,2,3+k,l));\n      }\n    }\n  }\n\n  if (DataLayout == ColMajor) {\n    offsets = Eigen::DSizes<ptrdiff_t, 4>(0,0,0,4);\n    extents = Eigen::DSizes<ptrdiff_t, 4>(3,5,7,2);\n    auto slice5 = SliceEvaluator(tensor.slice(offsets, extents), DefaultDevice());\n    VERIFY_IS_EQUAL(slice5.dimensions().TotalSize(), 210);\n    for (int i = 0; i < 3; ++i) {\n      for (int j = 0; j < 5; ++j) {\n        for (int k = 0; k < 7; ++k) {\n          for (int l = 0; l < 2; ++l) {\n            int slice_index = i + 3 * (j + 5 * (k + 7 * l));\n            VERIFY_IS_EQUAL(slice5.data()[slice_index], tensor(i,j,k,l+4));\n          }\n        }\n      }\n    }\n  } else {\n    offsets = Eigen::DSizes<ptrdiff_t, 4>(1,0,0,0);\n    extents = Eigen::DSizes<ptrdiff_t, 4>(2,5,7,11);\n    auto slice5 = SliceEvaluator(tensor.slice(offsets, extents), DefaultDevice());\n    VERIFY_IS_EQUAL(slice5.dimensions().TotalSize(), 770);\n    for (int l = 0; l < 11; ++l) {\n      for (int k = 0; k < 7; ++k) {\n        for (int j = 0; j < 5; ++j) {\n          for (int i = 0; i < 2; ++i) {\n            int slice_index = l + 11 * (k + 7 * (j + 5 * i));\n            VERIFY_IS_EQUAL(slice5.data()[slice_index], tensor(i+1,j,k,l));\n          }\n        }\n      }\n    }\n\n  }\n\n  offsets = Eigen::DSizes<ptrdiff_t, 4>(0,0,0,0);\n  extents = Eigen::DSizes<ptrdiff_t, 4>(3,5,7,11);\n  auto slice6 = SliceEvaluator(tensor.slice(offsets, extents), DefaultDevice());\n  VERIFY_IS_EQUAL(slice6.dimensions().TotalSize(), 3*5*7*11);\n  VERIFY_IS_EQUAL(slice6.data(), tensor.data());\n}\n\n\ntemplate<typename T, int DataLayout>\nstatic void test_strided_slice()\n{\n  typedef Tensor<T, 5, DataLayout> Tensor5f;\n  typedef Eigen::DSizes<Eigen::DenseIndex, 5> Index5;\n  typedef Tensor<T, 2, DataLayout> Tensor2f;\n  typedef Eigen::DSizes<Eigen::DenseIndex, 2> Index2;\n  Tensor<T, 5, DataLayout> tensor(2,3,5,7,11);\n  Tensor<T, 2, DataLayout> tensor2(7,11);\n  tensor.setRandom();\n  tensor2.setRandom();\n\n  if (true) {\n    Tensor2f slice(2,3);\n    Index2 strides(-2,-1);\n    Index2 indicesStart(5,7);\n    Index2 indicesStop(0,4);\n    slice = tensor2.stridedSlice(indicesStart, indicesStop, strides);\n    for (int j = 0; j < 2; ++j) {\n      for (int k = 0; k < 3; ++k) {\n        VERIFY_IS_EQUAL(slice(j,k), tensor2(5-2*j,7-k));\n      }\n    }\n  }\n\n  if(true) {\n    Tensor2f slice(0,1);\n    Index2 strides(1,1);\n    Index2 indicesStart(5,4);\n    Index2 indicesStop(5,5);\n    slice = tensor2.stridedSlice(indicesStart, indicesStop, strides);\n  }\n\n  if(true) { // test clamped degenerate interavls\n    Tensor2f slice(7,11);\n    Index2 strides(1,-1);\n    Index2 indicesStart(-3,20); // should become 0,10\n    Index2 indicesStop(20,-11); // should become 11, -1\n    slice = tensor2.stridedSlice(indicesStart, indicesStop, strides);\n    for (int j = 0; j < 7; ++j) {\n      for (int k = 0; k < 11; ++k) {\n        VERIFY_IS_EQUAL(slice(j,k), tensor2(j,10-k));\n      }\n    }\n  }\n\n  if(true) {\n    Tensor5f slice1(1,1,1,1,1);\n    Eigen::DSizes<Eigen::DenseIndex, 5> indicesStart(1, 2, 3, 4, 5);\n    Eigen::DSizes<Eigen::DenseIndex, 5> indicesStop(2, 3, 4, 5, 6);\n    Eigen::DSizes<Eigen::DenseIndex, 5> strides(1, 1, 1, 1, 1);\n    slice1 = tensor.stridedSlice(indicesStart, indicesStop, strides);\n    VERIFY_IS_EQUAL(slice1(0,0,0,0,0), tensor(1,2,3,4,5));\n  }\n\n  if(true) {\n    Tensor5f slice(1,1,2,2,3);\n    Index5 start(1, 1, 3, 4, 5);\n    Index5 stop(2, 2, 5, 6, 8);\n    Index5 strides(1, 1, 1, 1, 1);\n    slice = tensor.stridedSlice(start, stop, strides);\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 2; ++j) {\n        for (int k = 0; k < 3; ++k) {\n          VERIFY_IS_EQUAL(slice(0,0,i,j,k), tensor(1,1,3+i,4+j,5+k));\n        }\n      }\n    }\n  }\n\n  if(true) {\n    Tensor5f slice(1,1,2,2,3);\n    Index5 strides3(1, 1, -2, 1, -1);\n    Index5 indices3Start(1, 1, 4, 4, 7);\n    Index5 indices3Stop(2, 2, 0, 6, 4);\n    slice = tensor.stridedSlice(indices3Start, indices3Stop, strides3);\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 2; ++j) {\n        for (int k = 0; k < 3; ++k) {\n          VERIFY_IS_EQUAL(slice(0,0,i,j,k), tensor(1,1,4-2*i,4+j,7-k));\n        }\n      }\n    }\n  }\n\n  if(false) { // tests degenerate interval\n    Tensor5f slice(1,1,2,2,3);\n    Index5 strides3(1, 1, 2, 1, 1);\n    Index5 indices3Start(1, 1, 4, 4, 7);\n    Index5 indices3Stop(2, 2, 0, 6, 4);\n    slice = tensor.stridedSlice(indices3Start, indices3Stop, strides3);\n  }\n}\n\ntemplate<typename T, int DataLayout>\nstatic void test_strided_slice_write()\n{\n  typedef Tensor<T, 2, DataLayout> Tensor2f;\n  typedef Eigen::DSizes<Eigen::DenseIndex, 2> Index2;\n\n  Tensor<T, 2, DataLayout> tensor(7,11),tensor2(7,11);\n  tensor.setRandom();\n  tensor2=tensor;\n  Tensor2f slice(2,3);\n\n  slice.setRandom();\n\n  Index2 strides(1,1);\n  Index2 indicesStart(3,4);\n  Index2 indicesStop(5,7);\n  Index2 lengths(2,3);\n\n  tensor.slice(indicesStart,lengths)=slice;\n  tensor2.stridedSlice(indicesStart,indicesStop,strides)=slice;\n\n  for(int i=0;i<7;i++) for(int j=0;j<11;j++){\n    VERIFY_IS_EQUAL(tensor(i,j), tensor2(i,j));\n  }\n}\n\ntemplate<typename T, int DataLayout>\nstatic void test_composition()\n{\n  Eigen::Tensor<T, 2, DataLayout> matrix(7, 11);\n  matrix.setRandom();\n\n  const DSizes<ptrdiff_t, 3> newDims(1, 1, 11);\n  Eigen::Tensor<T, 3, DataLayout> tensor =\n      matrix.slice(DSizes<ptrdiff_t, 2>(2, 0), DSizes<ptrdiff_t, 2>(1, 11)).reshape(newDims);\n\n  VERIFY_IS_EQUAL(tensor.dimensions().TotalSize(), 11);\n  VERIFY_IS_EQUAL(tensor.dimension(0), 1);\n  VERIFY_IS_EQUAL(tensor.dimension(1), 1);\n  VERIFY_IS_EQUAL(tensor.dimension(2), 11);\n  for (int i = 0; i < 11; ++i) {\n    VERIFY_IS_EQUAL(tensor(0,0,i), matrix(2,i));\n  }\n}\n\ntemplate<typename T, int DataLayout>\nstatic void test_empty_slice()\n{\n  Tensor<T, 3, DataLayout> tensor(2,3,5);\n  tensor.setRandom();\n  Tensor<T, 3, DataLayout> copy = tensor;\n\n  // empty size in first dimension\n  Eigen::DSizes<ptrdiff_t, 3> indices1(1,2,3);\n  Eigen::DSizes<ptrdiff_t, 3> sizes1(0,1,2);\n  Tensor<T, 3, DataLayout> slice1(0,1,2);\n  slice1.setRandom();\n  tensor.slice(indices1, sizes1) = slice1;\n\n  // empty size in second dimension\n  Eigen::DSizes<ptrdiff_t, 3> indices2(1,2,3);\n  Eigen::DSizes<ptrdiff_t, 3> sizes2(1,0,2);\n  Tensor<T, 3, DataLayout> slice2(1,0,2);\n  slice2.setRandom();\n  tensor.slice(indices2, sizes2) = slice2;\n\n  // empty size in third dimension\n  Eigen::DSizes<ptrdiff_t, 3> indices3(1,2,3);\n  Eigen::DSizes<ptrdiff_t, 3> sizes3(1,1,0);\n  Tensor<T, 3, DataLayout> slice3(1,1,0);\n  slice3.setRandom();\n  tensor.slice(indices3, sizes3) = slice3;\n\n  // empty size in first and second dimension\n  Eigen::DSizes<ptrdiff_t, 3> indices4(1,2,3);\n  Eigen::DSizes<ptrdiff_t, 3> sizes4(0,0,2);\n  Tensor<T, 3, DataLayout> slice4(0,0,2);\n  slice4.setRandom();\n  tensor.slice(indices4, sizes4) = slice4;\n\n  // empty size in second and third dimension\n  Eigen::DSizes<ptrdiff_t, 3> indices5(1,2,3);\n  Eigen::DSizes<ptrdiff_t, 3> sizes5(1,0,0);\n  Tensor<T, 3, DataLayout> slice5(1,0,0);\n  slice5.setRandom();\n  tensor.slice(indices5, sizes5) = slice5;\n\n  // empty size in all dimensions\n  Eigen::DSizes<ptrdiff_t, 3> indices6(1,2,3);\n  Eigen::DSizes<ptrdiff_t, 3> sizes6(0,0,0);\n  Tensor<T, 3, DataLayout> slice6(0,0,0);\n  slice6.setRandom();\n  tensor.slice(indices6, sizes6) = slice6;\n\n  // none of these operations should change the tensor's components\n  // because all of the rvalue slices have at least one zero dimension\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n          VERIFY_IS_EQUAL(tensor(i,j,k), copy(i,j,k));\n      }\n    }\n  }\n}\n\n#define CALL_SUBTEST_PART(PART) \\\n  CALL_SUBTEST_##PART\n\n#define CALL_SUBTESTS_TYPES_LAYOUTS(PART, NAME)       \\\n  CALL_SUBTEST_PART(PART)((NAME<float, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, RowMajor>()))\n\nEIGEN_DECLARE_TEST(cxx11_tensor_morphing)\n{\n  CALL_SUBTEST_1(test_simple_reshape<void>());\n  CALL_SUBTEST_1(test_static_reshape<void>());\n  CALL_SUBTEST_1(test_reshape_as_lvalue<void>());\n  CALL_SUBTEST_1(test_reshape_in_expr<void>());\n  CALL_SUBTEST_1(test_const_slice<float>());\n\n  CALL_SUBTESTS_TYPES_LAYOUTS(2, test_simple_slice);\n  CALL_SUBTESTS_TYPES_LAYOUTS(3, test_slice_as_lvalue);\n  CALL_SUBTESTS_TYPES_LAYOUTS(4, test_slice_raw_data);\n  CALL_SUBTESTS_TYPES_LAYOUTS(5, test_strided_slice_write);\n  CALL_SUBTESTS_TYPES_LAYOUTS(6, test_strided_slice);\n  CALL_SUBTESTS_TYPES_LAYOUTS(7, test_composition);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_morphing_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_simple_reshape(const Eigen::SyclDevice& sycl_device)\n{\n  typename Tensor<DataType, 5 ,DataLayout, IndexType>::Dimensions dim1(2,3,1,7,1);\n  typename Tensor<DataType, 3 ,DataLayout, IndexType>::Dimensions dim2(2,3,7);\n  typename Tensor<DataType, 2 ,DataLayout, IndexType>::Dimensions dim3(6,7);\n  typename Tensor<DataType, 2 ,DataLayout, IndexType>::Dimensions dim4(2,21);\n\n  Tensor<DataType, 5, DataLayout, IndexType> tensor1(dim1);\n  Tensor<DataType, 3, DataLayout, IndexType> tensor2(dim2);\n  Tensor<DataType, 2, DataLayout, IndexType> tensor3(dim3);\n  Tensor<DataType, 2, DataLayout, IndexType> tensor4(dim4);\n\n  tensor1.setRandom();\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(tensor1.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(tensor2.size()*sizeof(DataType)));\n  DataType* gpu_data3  = static_cast<DataType*>(sycl_device.allocate(tensor3.size()*sizeof(DataType)));\n  DataType* gpu_data4  = static_cast<DataType*>(sycl_device.allocate(tensor4.size()*sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 5,DataLayout, IndexType>> gpu1(gpu_data1, dim1);\n  TensorMap<Tensor<DataType, 3,DataLayout, IndexType>> gpu2(gpu_data2, dim2);\n  TensorMap<Tensor<DataType, 2,DataLayout, IndexType>> gpu3(gpu_data3, dim3);\n  TensorMap<Tensor<DataType, 2,DataLayout, IndexType>> gpu4(gpu_data4, dim4);\n\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor1.data(),(tensor1.size())*sizeof(DataType));\n\n  gpu2.device(sycl_device)=gpu1.reshape(dim2);\n  sycl_device.memcpyDeviceToHost(tensor2.data(), gpu_data2,(tensor1.size())*sizeof(DataType));\n\n  gpu3.device(sycl_device)=gpu1.reshape(dim3);\n  sycl_device.memcpyDeviceToHost(tensor3.data(), gpu_data3,(tensor3.size())*sizeof(DataType));\n\n  gpu4.device(sycl_device)=gpu1.reshape(dim2).reshape(dim4);\n  sycl_device.memcpyDeviceToHost(tensor4.data(), gpu_data4,(tensor4.size())*sizeof(DataType));\n  for (IndexType i = 0; i < 2; ++i){\n    for (IndexType j = 0; j < 3; ++j){\n      for (IndexType k = 0; k < 7; ++k){\n        VERIFY_IS_EQUAL(tensor1(i,j,0,k,0), tensor2(i,j,k));      ///ColMajor\n        if (static_cast<int>(DataLayout) == static_cast<int>(ColMajor)) {\n          VERIFY_IS_EQUAL(tensor1(i,j,0,k,0), tensor3(i+2*j,k));    ///ColMajor\n          VERIFY_IS_EQUAL(tensor1(i,j,0,k,0), tensor4(i,j+3*k));    ///ColMajor\n        }\n        else{\n          //VERIFY_IS_EQUAL(tensor1(i,j,0,k,0), tensor2(i,j,k));      /// RowMajor\n          VERIFY_IS_EQUAL(tensor1(i,j,0,k,0), tensor4(i,j*7 +k));   /// RowMajor\n          VERIFY_IS_EQUAL(tensor1(i,j,0,k,0), tensor3(i*3 +j,k));   /// RowMajor\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n  sycl_device.deallocate(gpu_data3);\n  sycl_device.deallocate(gpu_data4);\n}\n\n\ntemplate<typename DataType, int DataLayout, typename IndexType>\nstatic void test_reshape_as_lvalue(const Eigen::SyclDevice& sycl_device)\n{\n  typename Tensor<DataType, 3, DataLayout, IndexType>::Dimensions dim1(2,3,7);\n  typename Tensor<DataType, 2, DataLayout, IndexType>::Dimensions dim2(6,7);\n  typename Tensor<DataType, 5, DataLayout, IndexType>::Dimensions dim3(2,3,1,7,1);\n  Tensor<DataType, 3, DataLayout, IndexType> tensor(dim1);\n  Tensor<DataType, 2, DataLayout, IndexType> tensor2d(dim2);\n  Tensor<DataType, 5, DataLayout, IndexType> tensor5d(dim3);\n\n  tensor.setRandom();\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(tensor.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(tensor2d.size()*sizeof(DataType)));\n  DataType* gpu_data3  = static_cast<DataType*>(sycl_device.allocate(tensor5d.size()*sizeof(DataType)));\n\n  TensorMap< Tensor<DataType, 3, DataLayout, IndexType> > gpu1(gpu_data1, dim1);\n  TensorMap< Tensor<DataType, 2, DataLayout, IndexType> > gpu2(gpu_data2, dim2);\n  TensorMap< Tensor<DataType, 5, DataLayout, IndexType> > gpu3(gpu_data3, dim3);\n\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor.data(),(tensor.size())*sizeof(DataType));\n\n  gpu2.reshape(dim1).device(sycl_device)=gpu1;\n  sycl_device.memcpyDeviceToHost(tensor2d.data(), gpu_data2,(tensor2d.size())*sizeof(DataType));\n\n  gpu3.reshape(dim1).device(sycl_device)=gpu1;\n  sycl_device.memcpyDeviceToHost(tensor5d.data(), gpu_data3,(tensor5d.size())*sizeof(DataType));\n\n\n  for (IndexType i = 0; i < 2; ++i){\n    for (IndexType j = 0; j < 3; ++j){\n      for (IndexType k = 0; k < 7; ++k){\n        VERIFY_IS_EQUAL(tensor5d(i,j,0,k,0), tensor(i,j,k));\n        if (static_cast<int>(DataLayout) == static_cast<int>(ColMajor)) {\n          VERIFY_IS_EQUAL(tensor2d(i+2*j,k), tensor(i,j,k));    ///ColMajor\n        }\n        else{\n          VERIFY_IS_EQUAL(tensor2d(i*3 +j,k),tensor(i,j,k));   /// RowMajor\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n  sycl_device.deallocate(gpu_data3);\n}\n\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_simple_slice(const Eigen::SyclDevice &sycl_device)\n{\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  IndexType sizeDim5 = 11;\n  array<IndexType, 5> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4, sizeDim5}};\n  Tensor<DataType, 5,DataLayout, IndexType> tensor(tensorRange);\n  tensor.setRandom();\n  array<IndexType, 5> slice1_range ={{1, 1, 1, 1, 1}};\n  Tensor<DataType, 5,DataLayout, IndexType> slice1(slice1_range);\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(tensor.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(slice1.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 5,DataLayout, IndexType>> gpu1(gpu_data1, tensorRange);\n  TensorMap<Tensor<DataType, 5,DataLayout, IndexType>> gpu2(gpu_data2, slice1_range);\n  Eigen::DSizes<IndexType, 5> indices(1,2,3,4,5);\n  Eigen::DSizes<IndexType, 5> sizes(1,1,1,1,1);\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor.data(),(tensor.size())*sizeof(DataType));\n  gpu2.device(sycl_device)=gpu1.slice(indices, sizes);\n  sycl_device.memcpyDeviceToHost(slice1.data(), gpu_data2,(slice1.size())*sizeof(DataType));\n  VERIFY_IS_EQUAL(slice1(0,0,0,0,0), tensor(1,2,3,4,5));\n\n\n  array<IndexType, 5> slice2_range ={{1,1,2,2,3}};\n  Tensor<DataType, 5,DataLayout, IndexType> slice2(slice2_range);\n  DataType* gpu_data3  = static_cast<DataType*>(sycl_device.allocate(slice2.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 5,DataLayout, IndexType>> gpu3(gpu_data3, slice2_range);\n  Eigen::DSizes<IndexType, 5> indices2(1,1,3,4,5);\n  Eigen::DSizes<IndexType, 5> sizes2(1,1,2,2,3);\n  gpu3.device(sycl_device)=gpu1.slice(indices2, sizes2);\n  sycl_device.memcpyDeviceToHost(slice2.data(), gpu_data3,(slice2.size())*sizeof(DataType));\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 2; ++j) {\n      for (IndexType k = 0; k < 3; ++k) {\n        VERIFY_IS_EQUAL(slice2(0,0,i,j,k), tensor(1,1,3+i,4+j,5+k));\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n  sycl_device.deallocate(gpu_data3);\n}\n\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_strided_slice_as_rhs_sycl(const Eigen::SyclDevice &sycl_device)\n{\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  IndexType sizeDim5 = 11;\n  typedef Eigen::DSizes<IndexType, 5> Index5;\n  Index5 strides(1L,1L,1L,1L,1L);\n  Index5 indicesStart(1L,2L,3L,4L,5L);\n  Index5 indicesStop(2L,3L,4L,5L,6L);\n  Index5 lengths(1L,1L,1L,1L,1L);\n\n  array<IndexType, 5> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4, sizeDim5}};\n  Tensor<DataType, 5, DataLayout, IndexType> tensor(tensorRange);\n  tensor.setRandom();\n\n  array<IndexType, 5> slice1_range ={{1, 1, 1, 1, 1}};\n  Tensor<DataType, 5,DataLayout, IndexType> slice1(slice1_range);\n  Tensor<DataType, 5, DataLayout, IndexType> slice_stride1(slice1_range);\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(tensor.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(slice1.size()*sizeof(DataType)));\n  DataType* gpu_data_stride2  = static_cast<DataType*>(sycl_device.allocate(slice_stride1.size()*sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 5,DataLayout, IndexType>> gpu1(gpu_data1, tensorRange);\n  TensorMap<Tensor<DataType, 5,DataLayout, IndexType>> gpu2(gpu_data2, slice1_range);\n  TensorMap<Tensor<DataType, 5,DataLayout, IndexType>> gpu_stride2(gpu_data_stride2, slice1_range);\n\n  Eigen::DSizes<IndexType, 5> indices(1,2,3,4,5);\n  Eigen::DSizes<IndexType, 5> sizes(1,1,1,1,1);\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor.data(),(tensor.size())*sizeof(DataType));\n  gpu2.device(sycl_device)=gpu1.slice(indices, sizes);\n  sycl_device.memcpyDeviceToHost(slice1.data(), gpu_data2,(slice1.size())*sizeof(DataType));\n\n  gpu_stride2.device(sycl_device)=gpu1.stridedSlice(indicesStart,indicesStop,strides);\n  sycl_device.memcpyDeviceToHost(slice_stride1.data(), gpu_data_stride2,(slice_stride1.size())*sizeof(DataType));\n\n  VERIFY_IS_EQUAL(slice1(0,0,0,0,0), tensor(1,2,3,4,5));\n  VERIFY_IS_EQUAL(slice_stride1(0,0,0,0,0), tensor(1,2,3,4,5));\n\n  array<IndexType, 5> slice2_range ={{1,1,2,2,3}};\n  Tensor<DataType, 5,DataLayout, IndexType> slice2(slice2_range);\n  Tensor<DataType, 5, DataLayout, IndexType> strideSlice2(slice2_range);\n\n  DataType* gpu_data3  = static_cast<DataType*>(sycl_device.allocate(slice2.size()*sizeof(DataType)));\n  DataType* gpu_data_stride3  = static_cast<DataType*>(sycl_device.allocate(strideSlice2.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 5,DataLayout, IndexType>> gpu3(gpu_data3, slice2_range);\n  TensorMap<Tensor<DataType, 5,DataLayout, IndexType>> gpu_stride3(gpu_data_stride3, slice2_range);\n  Eigen::DSizes<IndexType, 5> indices2(1,1,3,4,5);\n  Eigen::DSizes<IndexType, 5> sizes2(1,1,2,2,3);\n  Index5 strides2(1L,1L,1L,1L,1L);\n  Index5 indicesStart2(1L,1L,3L,4L,5L);\n  Index5 indicesStop2(2L,2L,5L,6L,8L);\n\n  gpu3.device(sycl_device)=gpu1.slice(indices2, sizes2);\n  sycl_device.memcpyDeviceToHost(slice2.data(), gpu_data3,(slice2.size())*sizeof(DataType));\n\n  gpu_stride3.device(sycl_device)=gpu1.stridedSlice(indicesStart2,indicesStop2,strides2);\n  sycl_device.memcpyDeviceToHost(strideSlice2.data(), gpu_data_stride3,(strideSlice2.size())*sizeof(DataType));\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 2; ++j) {\n      for (IndexType k = 0; k < 3; ++k) {\n        VERIFY_IS_EQUAL(slice2(0,0,i,j,k), tensor(1,1,3+i,4+j,5+k));\n        VERIFY_IS_EQUAL(strideSlice2(0,0,i,j,k), tensor(1,1,3+i,4+j,5+k));\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n  sycl_device.deallocate(gpu_data3);\n}\n\ntemplate<typename DataType, int DataLayout, typename IndexType>\nstatic void test_strided_slice_write_sycl(const Eigen::SyclDevice& sycl_device)\n{\n  typedef Tensor<DataType, 2, DataLayout, IndexType> Tensor2f;\n  typedef Eigen::DSizes<IndexType, 2> Index2;\n  IndexType sizeDim1 = 7L;\n  IndexType sizeDim2 = 11L;\n  array<IndexType, 2> tensorRange = {{sizeDim1, sizeDim2}};\n  Tensor<DataType, 2, DataLayout, IndexType> tensor(tensorRange),tensor2(tensorRange);\n  IndexType sliceDim1 = 2;\n  IndexType sliceDim2 = 3;\n  array<IndexType, 2> sliceRange = {{sliceDim1, sliceDim2}};\n  Tensor2f slice(sliceRange);\n  Index2 strides(1L,1L);\n  Index2 indicesStart(3L,4L);\n  Index2 indicesStop(5L,7L);\n  Index2 lengths(2L,3L);\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(tensor.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(tensor2.size()*sizeof(DataType)));\n  DataType* gpu_data3  = static_cast<DataType*>(sycl_device.allocate(slice.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 2,DataLayout,IndexType>> gpu1(gpu_data1, tensorRange);\n  TensorMap<Tensor<DataType, 2,DataLayout,IndexType>> gpu2(gpu_data2, tensorRange);\n  TensorMap<Tensor<DataType, 2,DataLayout,IndexType>> gpu3(gpu_data3, sliceRange);\n\n\n  tensor.setRandom();\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor.data(),(tensor.size())*sizeof(DataType));\n  gpu2.device(sycl_device)=gpu1;\n\n  slice.setRandom();\n  sycl_device.memcpyHostToDevice(gpu_data3, slice.data(),(slice.size())*sizeof(DataType));\n\n\n  gpu1.slice(indicesStart,lengths).device(sycl_device)=gpu3;\n  gpu2.stridedSlice(indicesStart,indicesStop,strides).device(sycl_device)=gpu3;\n  sycl_device.memcpyDeviceToHost(tensor.data(), gpu_data1,(tensor.size())*sizeof(DataType));\n  sycl_device.memcpyDeviceToHost(tensor2.data(), gpu_data2,(tensor2.size())*sizeof(DataType));\n\n  for(IndexType i=0;i<sizeDim1;i++)\n    for(IndexType j=0;j<sizeDim2;j++){\n    VERIFY_IS_EQUAL(tensor(i,j), tensor2(i,j));\n  }\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n  sycl_device.deallocate(gpu_data3);\n}\n\ntemplate <typename OutIndex, typename DSizes>\nEigen::array<OutIndex, DSizes::count> To32BitDims(const DSizes& in) {\n  Eigen::array<OutIndex, DSizes::count> out;\n  for (int i = 0; i < DSizes::count; ++i) {\n    out[i] = in[i];\n  }\n  return out;\n}\n\ntemplate <class DataType, int DataLayout, typename IndexType, typename ConvertedIndexType>\nint run_eigen(const SyclDevice& sycl_device) {\n  using TensorI64 = Tensor<DataType, 5, DataLayout, IndexType>;\n  using TensorI32 = Tensor<DataType, 5, DataLayout, ConvertedIndexType>;\n  using TensorMI64 = TensorMap<TensorI64>;\n  using TensorMI32 = TensorMap<TensorI32>;\n  Eigen::array<IndexType, 5> tensor_range{{4, 1, 1, 1, 6}};\n  Eigen::array<IndexType, 5> slice_range{{4, 1, 1, 1, 3}};\n\n  TensorI64 out_tensor_gpu(tensor_range);\n  TensorI64 out_tensor_cpu(tensor_range);\n  out_tensor_cpu.setRandom();\n\n  TensorI64 sub_tensor(slice_range);\n  sub_tensor.setRandom();\n\n  DataType* out_gpu_data = static_cast<DataType*>(sycl_device.allocate(out_tensor_cpu.size() * sizeof(DataType)));\n  DataType* sub_gpu_data = static_cast<DataType*>(sycl_device.allocate(sub_tensor.size() * sizeof(DataType)));\n  TensorMI64 out_gpu(out_gpu_data, tensor_range);\n  TensorMI64 sub_gpu(sub_gpu_data, slice_range);\n\n  sycl_device.memcpyHostToDevice(out_gpu_data, out_tensor_cpu.data(), out_tensor_cpu.size() * sizeof(DataType));\n  sycl_device.memcpyHostToDevice(sub_gpu_data, sub_tensor.data(), sub_tensor.size() * sizeof(DataType));\n\n  Eigen::array<ConvertedIndexType, 5> slice_offset_32{{0, 0, 0, 0, 3}};\n  Eigen::array<ConvertedIndexType, 5> slice_range_32{{4, 1, 1, 1, 3}};\n  TensorMI32 out_cpu_32(out_tensor_cpu.data(), To32BitDims<ConvertedIndexType>(out_tensor_cpu.dimensions()));\n  TensorMI32 sub_cpu_32(sub_tensor.data(), To32BitDims<ConvertedIndexType>(sub_tensor.dimensions()));\n  TensorMI32 out_gpu_32(out_gpu.data(), To32BitDims<ConvertedIndexType>(out_gpu.dimensions()));\n  TensorMI32 sub_gpu_32(sub_gpu.data(), To32BitDims<ConvertedIndexType>(sub_gpu.dimensions()));\n\n  out_gpu_32.slice(slice_offset_32, slice_range_32).device(sycl_device) = sub_gpu_32;\n\n  out_cpu_32.slice(slice_offset_32, slice_range_32) = sub_cpu_32;\n\n  sycl_device.memcpyDeviceToHost(out_tensor_gpu.data(), out_gpu_data, out_tensor_cpu.size() * sizeof(DataType));\n  int has_err = 0;\n  for (IndexType i = 0; i < out_tensor_cpu.size(); ++i) {\n    auto exp = out_tensor_cpu(i);\n    auto val = out_tensor_gpu(i);\n    if (val != exp) {\n      std::cout << \"#\" << i << \" got \" << val << \" but expected \" << exp << std::endl;\n      has_err = 1;\n    }\n  }\n  sycl_device.deallocate(out_gpu_data);\n  sycl_device.deallocate(sub_gpu_data);\n  return has_err;\n}\n\ntemplate<typename DataType, typename dev_Selector> void sycl_morphing_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_simple_slice<DataType, RowMajor, int64_t>(sycl_device);\n  test_simple_slice<DataType, ColMajor, int64_t>(sycl_device);\n  test_simple_reshape<DataType, RowMajor, int64_t>(sycl_device);\n  test_simple_reshape<DataType, ColMajor, int64_t>(sycl_device);\n  test_reshape_as_lvalue<DataType, RowMajor, int64_t>(sycl_device);\n  test_reshape_as_lvalue<DataType, ColMajor, int64_t>(sycl_device);\n  test_strided_slice_write_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_strided_slice_write_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_strided_slice_as_rhs_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_strided_slice_as_rhs_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  run_eigen<float, RowMajor, long, int>(sycl_device); \n}\nEIGEN_DECLARE_TEST(cxx11_tensor_morphing_sycl)\n{\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_morphing_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_move.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2017 Viktor Csomor <viktor.csomor@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n#include <utility>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\nstatic void calc_indices(int i, int& x, int& y, int& z)\n{\n  x = i / 4;\n  y = (i % 4) / 2;\n  z = i % 2;\n}\n\nstatic void test_move()\n{\n  int x;\n  int y;\n  int z;\n\n  Tensor<int,3> tensor1(2, 2, 2);\n  Tensor<int,3,RowMajor> tensor2(2, 2, 2);\n\n  for (int i = 0; i < 8; i++)\n  {\n    calc_indices(i, x, y, z);\n    tensor1(x,y,z) = i;\n    tensor2(x,y,z) = 2 * i;\n  }\n\n  // Invokes the move constructor.\n  Tensor<int,3> moved_tensor1 = std::move(tensor1);\n  Tensor<int,3,RowMajor> moved_tensor2 = std::move(tensor2);\n\n  VERIFY_IS_EQUAL(tensor1.size(), 0);\n  VERIFY_IS_EQUAL(tensor2.size(), 0);\n\n  for (int i = 0; i < 8; i++)\n  {\n    calc_indices(i, x, y, z);\n    VERIFY_IS_EQUAL(moved_tensor1(x,y,z), i);\n    VERIFY_IS_EQUAL(moved_tensor2(x,y,z), 2 * i);\n  }\n\n  Tensor<int,3> moved_tensor3(2,2,2);\n  Tensor<int,3,RowMajor> moved_tensor4(2,2,2);\n\n  moved_tensor3.setZero();\n  moved_tensor4.setZero();\n\n  // Invokes the move assignment operator.\n  moved_tensor3 = std::move(moved_tensor1);\n  moved_tensor4 = std::move(moved_tensor2);\n\n  for (int i = 0; i < 8; i++)\n  {\n    calc_indices(i, x, y, z);\n    VERIFY_IS_EQUAL(moved_tensor3(x,y,z), i);\n    VERIFY_IS_EQUAL(moved_tensor4(x,y,z), 2 * i);\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_move)\n{\n  CALL_SUBTEST(test_move());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_notification.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Vijay Vasudevan <vrv@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_USE_THREADS\n\n#include <atomic>\n\n#include <stdlib.h>\n#include \"main.h\"\n#include <Eigen/CXX11/Tensor>\n\nstatic void test_notification_single()\n{\n  ThreadPool thread_pool(1);\n\n  std::atomic<int> counter(0);\n  Eigen::Notification n;\n  auto func = [&n, &counter](){ n.Wait(); ++counter;};\n  thread_pool.Schedule(func);\n  std::this_thread::sleep_for(std::chrono::milliseconds(1000));\n\n  // The thread should be waiting for the notification.\n  VERIFY_IS_EQUAL(counter, 0);\n\n  // Unblock the thread\n  n.Notify();\n\n  std::this_thread::sleep_for(std::chrono::milliseconds(1000));\n\n  // Verify the counter has been incremented\n  VERIFY_IS_EQUAL(counter, 1);\n}\n\n// Like test_notification_single() but enqueues multiple threads to\n// validate that all threads get notified by Notify().\nstatic void test_notification_multiple()\n{\n  ThreadPool thread_pool(1);\n\n  std::atomic<int> counter(0);\n  Eigen::Notification n;\n  auto func = [&n, &counter](){ n.Wait(); ++counter;};\n  thread_pool.Schedule(func);\n  thread_pool.Schedule(func);\n  thread_pool.Schedule(func);\n  thread_pool.Schedule(func);\n  std::this_thread::sleep_for(std::chrono::milliseconds(1000));\n  VERIFY_IS_EQUAL(counter, 0);\n  n.Notify();\n  std::this_thread::sleep_for(std::chrono::milliseconds(1000));\n  VERIFY_IS_EQUAL(counter, 4);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_notification)\n{\n  CALL_SUBTEST(test_notification_single());\n  CALL_SUBTEST(test_notification_multiple());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_of_complex.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\n\n\nstatic void test_additions()\n{\n  Tensor<std::complex<float>, 1> data1(3);\n  Tensor<std::complex<float>, 1> data2(3);\n  for (int i = 0; i < 3; ++i) {\n    data1(i) = std::complex<float>(i, -i);\n    data2(i) = std::complex<float>(i, 7 * i);\n  }\n\n  Tensor<std::complex<float>, 1> sum = data1 + data2;\n  for (int i = 0; i < 3; ++i) {\n    VERIFY_IS_EQUAL(sum(i),  std::complex<float>(2*i, 6*i));\n  }\n}\n\n\nstatic void test_abs()\n{\n  Tensor<std::complex<float>, 1> data1(3);\n  Tensor<std::complex<double>, 1> data2(3);\n  data1.setRandom();\n  data2.setRandom();\n\n  Tensor<float, 1> abs1 = data1.abs();\n  Tensor<double, 1> abs2 = data2.abs();\n  for (int i = 0; i < 3; ++i) {\n    VERIFY_IS_APPROX(abs1(i), std::abs(data1(i)));\n    VERIFY_IS_APPROX(abs2(i), std::abs(data2(i)));\n  }\n}\n\n\nstatic void test_conjugate()\n{\n  Tensor<std::complex<float>, 1> data1(3);\n  Tensor<std::complex<double>, 1> data2(3);\n  Tensor<int, 1> data3(3);\n  data1.setRandom();\n  data2.setRandom();\n  data3.setRandom();\n\n  Tensor<std::complex<float>, 1> conj1 = data1.conjugate();\n  Tensor<std::complex<double>, 1> conj2 = data2.conjugate();\n  Tensor<int, 1> conj3 = data3.conjugate();\n  for (int i = 0; i < 3; ++i) {\n    VERIFY_IS_APPROX(conj1(i), std::conj(data1(i)));\n    VERIFY_IS_APPROX(conj2(i), std::conj(data2(i)));\n    VERIFY_IS_APPROX(conj3(i), data3(i));\n  }\n}\n\nstatic void test_contractions()\n{\n  Tensor<std::complex<float>, 4> t_left(30, 50, 8, 31);\n  Tensor<std::complex<float>, 5> t_right(8, 31, 7, 20, 10);\n  Tensor<std::complex<float>, 5> t_result(30, 50, 7, 20, 10);\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  typedef Map<Matrix<std::complex<float>, Dynamic, Dynamic>> MapXcf;\n  MapXcf m_left(t_left.data(), 1500, 248);\n  MapXcf m_right(t_right.data(), 248, 1400);\n  Matrix<std::complex<float>, Dynamic, Dynamic> m_result(1500, 1400);\n\n  // This contraction should be equivalent to a regular matrix multiplication\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n  Eigen::array<DimPair, 2> dims;\n  dims[0] = DimPair(2, 0);\n  dims[1] = DimPair(3, 1);\n  t_result = t_left.contract(t_right, dims);\n  m_result = m_left * m_right;\n  for (int i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY_IS_APPROX(t_result.data()[i], m_result.data()[i]);\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_of_complex)\n{\n  CALL_SUBTEST(test_additions());\n  CALL_SUBTEST(test_abs());\n  CALL_SUBTEST(test_conjugate());\n  CALL_SUBTEST(test_contractions());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_of_const_values.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\nstatic void test_assign()\n{\n  float data1[6];\n  TensorMap<Tensor<const float, 2>> mat1(data1, 2, 3);\n  float data2[6];\n  const TensorMap<Tensor<float, 2>> mat2(data2, 2, 3);\n\n  for (int i = 0; i < 6; ++i) {\n    data1[i] = i;\n    data2[i] = -i;\n  }\n\n  Tensor<float, 2> rslt1;\n  rslt1 = mat1;\n  Tensor<float, 2> rslt2;\n  rslt2 = mat2;\n\n  Tensor<float, 2> rslt3 = mat1;\n  Tensor<float, 2> rslt4 = mat2;\n\n  Tensor<float, 2> rslt5(mat1);\n  Tensor<float, 2> rslt6(mat2);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_APPROX(rslt1(i,j), static_cast<float>(i + 2*j));\n      VERIFY_IS_APPROX(rslt2(i,j), static_cast<float>(-i - 2*j));\n      VERIFY_IS_APPROX(rslt3(i,j), static_cast<float>(i + 2*j));\n      VERIFY_IS_APPROX(rslt4(i,j), static_cast<float>(-i - 2*j));\n      VERIFY_IS_APPROX(rslt5(i,j), static_cast<float>(i + 2*j));\n      VERIFY_IS_APPROX(rslt6(i,j), static_cast<float>(-i - 2*j));\n    }\n  }\n}\n\n\nstatic void test_plus()\n{\n  float data1[6];\n  TensorMap<Tensor<const float, 2>> mat1(data1, 2, 3);\n  float data2[6];\n  TensorMap<Tensor<float, 2>> mat2(data2, 2, 3);\n\n  for (int i = 0; i < 6; ++i) {\n    data1[i] = i;\n    data2[i] = -i;\n  }\n\n  Tensor<float, 2> sum1;\n  sum1 = mat1 + mat2;\n  Tensor<float, 2> sum2;\n  sum2 = mat2 + mat1;\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_APPROX(sum1(i,j), 0.0f);\n      VERIFY_IS_APPROX(sum2(i,j), 0.0f);\n    }\n  }\n}\n\n\nstatic void test_plus_equal()\n{\n  float data1[6];\n  TensorMap<Tensor<const float, 2>> mat1(data1, 2, 3);\n  float data2[6];\n  TensorMap<Tensor<float, 2>> mat2(data2, 2, 3);\n\n  for (int i = 0; i < 6; ++i) {\n    data1[i] = i;\n    data2[i] = -i;\n  }\n  mat2 += mat1;\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_APPROX(mat2(i,j), 0.0f);\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_of_const_values)\n{\n  CALL_SUBTEST(test_assign());\n  CALL_SUBTEST(test_plus());\n  CALL_SUBTEST(test_plus_equal());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_of_float16_gpu.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\n\nusing Eigen::Tensor;\n\ntemplate<typename>\nvoid test_gpu_numext() {\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n  int num_elem = 101;\n\n  float* d_float = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  bool* d_res_half = (bool*)gpu_device.allocate(num_elem * sizeof(bool));\n  bool* d_res_float = (bool*)gpu_device.allocate(num_elem * sizeof(bool));\n\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_float(\n      d_float, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<bool, 1>, Eigen::Aligned> gpu_res_half(\n      d_res_half, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<bool, 1>, Eigen::Aligned> gpu_res_float(\n      d_res_float, num_elem);\n\n  gpu_float.device(gpu_device) = gpu_float.random() - gpu_float.constant(0.5f);\n  gpu_res_float.device(gpu_device) = gpu_float.unaryExpr(Eigen::internal::scalar_isnan_op<float>());\n  gpu_res_half.device(gpu_device) = gpu_float.cast<Eigen::half>().unaryExpr(Eigen::internal::scalar_isnan_op<Eigen::half>());\n\n  Tensor<bool, 1> half_prec(num_elem);\n  Tensor<bool, 1> full_prec(num_elem);\n  gpu_device.memcpyDeviceToHost(half_prec.data(), d_res_half, num_elem*sizeof(bool));\n  gpu_device.memcpyDeviceToHost(full_prec.data(), d_res_float, num_elem*sizeof(bool));\n  gpu_device.synchronize();\n\n  for (int i = 0; i < num_elem; ++i) {\n    std::cout << \"Checking numext \" << i << std::endl;\n    VERIFY_IS_EQUAL(full_prec(i), half_prec(i));\n  }\n\n  gpu_device.deallocate(d_float);\n  gpu_device.deallocate(d_res_half);\n  gpu_device.deallocate(d_res_float);\n}\n\n\n#ifdef EIGEN_HAS_GPU_FP16\n\ntemplate<typename>\nvoid test_gpu_conversion() {\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n  int num_elem = 101;\n\n  float* d_float = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  Eigen::half* d_half = (Eigen::half*)gpu_device.allocate(num_elem * sizeof(Eigen::half));\n  float* d_conv = (float*)gpu_device.allocate(num_elem * sizeof(float));\n\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_float(\n      d_float, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_half(\n      d_half, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_conv(\n      d_conv, num_elem);\n\n  gpu_float.device(gpu_device) = gpu_float.random();\n  gpu_half.device(gpu_device) = gpu_float.cast<Eigen::half>();\n  gpu_conv.device(gpu_device) = gpu_half.cast<float>();\n\n  Tensor<float, 1> initial(num_elem);\n  Tensor<float, 1> final(num_elem);\n  gpu_device.memcpyDeviceToHost(initial.data(), d_float, num_elem*sizeof(float));\n  gpu_device.memcpyDeviceToHost(final.data(), d_conv, num_elem*sizeof(float));\n\n  for (int i = 0; i < num_elem; ++i) {\n    VERIFY_IS_APPROX(initial(i), final(i));\n  }\n\n  gpu_device.deallocate(d_float);\n  gpu_device.deallocate(d_half);\n  gpu_device.deallocate(d_conv);\n}\n\ntemplate<typename>\nvoid test_gpu_unary() {\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n  int num_elem = 101;\n\n  float* d_float = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_res_half = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_res_float = (float*)gpu_device.allocate(num_elem * sizeof(float));\n\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_float(\n      d_float, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_res_half(\n      d_res_half, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_res_float(\n      d_res_float, num_elem);\n\n  gpu_float.device(gpu_device) = gpu_float.random() - gpu_float.constant(0.5f);\n  gpu_res_float.device(gpu_device) = gpu_float.abs();\n  gpu_res_half.device(gpu_device) = gpu_float.cast<Eigen::half>().abs().cast<float>();\n\n  Tensor<float, 1> half_prec(num_elem);\n  Tensor<float, 1> full_prec(num_elem);\n  gpu_device.memcpyDeviceToHost(half_prec.data(), d_res_half, num_elem*sizeof(float));\n  gpu_device.memcpyDeviceToHost(full_prec.data(), d_res_float, num_elem*sizeof(float));\n  gpu_device.synchronize();\n\n  for (int i = 0; i < num_elem; ++i) {\n    std::cout << \"Checking unary \" << i << std::endl;\n    VERIFY_IS_APPROX(full_prec(i), half_prec(i));\n  }\n\n  gpu_device.deallocate(d_float);\n  gpu_device.deallocate(d_res_half);\n  gpu_device.deallocate(d_res_float);\n}\n\ntemplate<typename>\nvoid test_gpu_elementwise() {\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n  int num_elem = 101;\n\n  float* d_float1 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_float2 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_res_half = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_res_float = (float*)gpu_device.allocate(num_elem * sizeof(float));\n\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_float1(\n      d_float1, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_float2(\n      d_float2, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_res_half(\n      d_res_half, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_res_float(\n      d_res_float, num_elem);\n\n  gpu_float1.device(gpu_device) = gpu_float1.random();\n  gpu_float2.device(gpu_device) = gpu_float2.random();\n  gpu_res_float.device(gpu_device) = (gpu_float1 + gpu_float2) * gpu_float1;\n  gpu_res_half.device(gpu_device) = ((gpu_float1.cast<Eigen::half>() + gpu_float2.cast<Eigen::half>()) * gpu_float1.cast<Eigen::half>()).cast<float>();\n\n  Tensor<float, 1> half_prec(num_elem);\n  Tensor<float, 1> full_prec(num_elem);\n  gpu_device.memcpyDeviceToHost(half_prec.data(), d_res_half, num_elem*sizeof(float));\n  gpu_device.memcpyDeviceToHost(full_prec.data(), d_res_float, num_elem*sizeof(float));\n  gpu_device.synchronize();\n\n  for (int i = 0; i < num_elem; ++i) {\n    std::cout << \"Checking elemwise \" << i << \": full prec = \" << full_prec(i) << \" vs half prec = \" << half_prec(i) << std::endl;\n    VERIFY_IS_APPROX(static_cast<Eigen::half>(full_prec(i)), static_cast<Eigen::half>(half_prec(i)));\n  }\n\n  gpu_device.deallocate(d_float1);\n  gpu_device.deallocate(d_float2);\n  gpu_device.deallocate(d_res_half);\n  gpu_device.deallocate(d_res_float);\n}\n\ntemplate<typename>\nvoid test_gpu_trancendental() {\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n  int num_elem = 101;\n\n  float* d_float1 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_float2 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_float3 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  Eigen::half* d_res1_half = (Eigen::half*)gpu_device.allocate(num_elem * sizeof(Eigen::half));\n  Eigen::half* d_res1_float = (Eigen::half*)gpu_device.allocate(num_elem * sizeof(Eigen::half));\n  Eigen::half* d_res2_half = (Eigen::half*)gpu_device.allocate(num_elem * sizeof(Eigen::half));\n  Eigen::half* d_res2_float = (Eigen::half*)gpu_device.allocate(num_elem * sizeof(Eigen::half));\n  Eigen::half* d_res3_half = (Eigen::half*)gpu_device.allocate(num_elem * sizeof(Eigen::half));\n  Eigen::half* d_res3_float = (Eigen::half*)gpu_device.allocate(num_elem * sizeof(Eigen::half));\n\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_float1(d_float1, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_float2(d_float2, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_float3(d_float3, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_res1_half(d_res1_half, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_res1_float(d_res1_float, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_res2_half(d_res2_half, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_res2_float(d_res2_float, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_res3_half(d_res3_half, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_res3_float(d_res3_float, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_res4_half(d_res3_half, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_res4_float(d_res3_float, num_elem);\n\n  gpu_float1.device(gpu_device) = gpu_float1.random() - gpu_float1.constant(0.5f);\n  gpu_float2.device(gpu_device) = gpu_float2.random() + gpu_float1.constant(0.5f);\n  gpu_float3.device(gpu_device) = gpu_float3.random();\n  gpu_res1_float.device(gpu_device) = gpu_float1.exp().cast<Eigen::half>();\n  gpu_res2_float.device(gpu_device) = gpu_float2.log().cast<Eigen::half>();\n  gpu_res3_float.device(gpu_device) = gpu_float3.log1p().cast<Eigen::half>();\n  gpu_res4_float.device(gpu_device) = gpu_float3.expm1().cast<Eigen::half>();\n\n  gpu_res1_half.device(gpu_device) = gpu_float1.cast<Eigen::half>();\n  gpu_res1_half.device(gpu_device) = gpu_res1_half.exp();\n\n  gpu_res2_half.device(gpu_device) = gpu_float2.cast<Eigen::half>();\n  gpu_res2_half.device(gpu_device) = gpu_res2_half.log();\n\n  gpu_res3_half.device(gpu_device) = gpu_float3.cast<Eigen::half>();\n  gpu_res3_half.device(gpu_device) = gpu_res3_half.log1p();\n\n  gpu_res3_half.device(gpu_device) = gpu_float3.cast<Eigen::half>();\n  gpu_res3_half.device(gpu_device) = gpu_res3_half.expm1();\n\n  Tensor<float, 1> input1(num_elem);\n  Tensor<Eigen::half, 1> half_prec1(num_elem);\n  Tensor<Eigen::half, 1> full_prec1(num_elem);\n  Tensor<float, 1> input2(num_elem);\n  Tensor<Eigen::half, 1> half_prec2(num_elem);\n  Tensor<Eigen::half, 1> full_prec2(num_elem);\n  Tensor<float, 1> input3(num_elem);\n  Tensor<Eigen::half, 1> half_prec3(num_elem);\n  Tensor<Eigen::half, 1> full_prec3(num_elem);\n  gpu_device.memcpyDeviceToHost(input1.data(), d_float1, num_elem*sizeof(float));\n  gpu_device.memcpyDeviceToHost(input2.data(), d_float2, num_elem*sizeof(float));\n  gpu_device.memcpyDeviceToHost(input3.data(), d_float3, num_elem*sizeof(float));\n  gpu_device.memcpyDeviceToHost(half_prec1.data(), d_res1_half, num_elem*sizeof(Eigen::half));\n  gpu_device.memcpyDeviceToHost(full_prec1.data(), d_res1_float, num_elem*sizeof(Eigen::half));\n  gpu_device.memcpyDeviceToHost(half_prec2.data(), d_res2_half, num_elem*sizeof(Eigen::half));\n  gpu_device.memcpyDeviceToHost(full_prec2.data(), d_res2_float, num_elem*sizeof(Eigen::half));\n  gpu_device.memcpyDeviceToHost(half_prec3.data(), d_res3_half, num_elem*sizeof(Eigen::half));\n  gpu_device.memcpyDeviceToHost(full_prec3.data(), d_res3_float, num_elem*sizeof(Eigen::half));\n  gpu_device.synchronize();\n\n  for (int i = 0; i < num_elem; ++i) {\n    std::cout << \"Checking elemwise exp \" << i << \" input = \" << input1(i) << \" full = \" << full_prec1(i) << \" half = \" << half_prec1(i) << std::endl;\n    VERIFY_IS_APPROX(full_prec1(i), half_prec1(i));\n  }\n  for (int i = 0; i < num_elem; ++i) {\n    std::cout << \"Checking elemwise log \" << i << \" input = \" << input2(i) << \" full = \" << full_prec2(i) << \" half = \" << half_prec2(i) << std::endl;\n    if(std::abs(input2(i)-1.f)<0.05f) // log lacks accuracy nearby 1\n      VERIFY_IS_APPROX(full_prec2(i)+Eigen::half(0.1f), half_prec2(i)+Eigen::half(0.1f));\n    else\n      VERIFY_IS_APPROX(full_prec2(i), half_prec2(i));\n  }\n  for (int i = 0; i < num_elem; ++i) {\n    std::cout << \"Checking elemwise plog1 \" << i << \" input = \" << input3(i) << \" full = \" << full_prec3(i) << \" half = \" << half_prec3(i) << std::endl;\n    VERIFY_IS_APPROX(full_prec3(i), half_prec3(i));\n  }\n  gpu_device.deallocate(d_float1);\n  gpu_device.deallocate(d_float2);\n  gpu_device.deallocate(d_float3);\n  gpu_device.deallocate(d_res1_half);\n  gpu_device.deallocate(d_res1_float);\n  gpu_device.deallocate(d_res2_half);\n  gpu_device.deallocate(d_res2_float);\n  gpu_device.deallocate(d_res3_float);\n  gpu_device.deallocate(d_res3_half);\n}\n\ntemplate<typename>\nvoid test_gpu_contractions() {\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n  int rows = 23;\n  int cols = 23;\n  int num_elem = rows*cols;\n\n  float* d_float1 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_float2 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  Eigen::half* d_res_half = (Eigen::half*)gpu_device.allocate(num_elem * sizeof(Eigen::half));\n  Eigen::half* d_res_float = (Eigen::half*)gpu_device.allocate(num_elem * sizeof(Eigen::half));\n\n  Eigen::TensorMap<Eigen::Tensor<float, 2>, Eigen::Aligned> gpu_float1(\n      d_float1, rows, cols);\n  Eigen::TensorMap<Eigen::Tensor<float, 2>, Eigen::Aligned> gpu_float2(\n      d_float2, rows, cols);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 2>, Eigen::Aligned> gpu_res_half(\n      d_res_half, rows, cols);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 2>, Eigen::Aligned> gpu_res_float(\n      d_res_float, rows, cols);\n\n  gpu_float1.device(gpu_device) = gpu_float1.random() - gpu_float1.constant(0.5f);\n  gpu_float2.device(gpu_device) = gpu_float2.random() - gpu_float2.constant(0.5f);\n\n  typedef Tensor<float, 2>::DimensionPair DimPair;\n  Eigen::array<DimPair, 1> dims(DimPair(1, 0));\n  gpu_res_float.device(gpu_device) = gpu_float1.contract(gpu_float2, dims).cast<Eigen::half>();\n  gpu_res_half.device(gpu_device) = gpu_float1.cast<Eigen::half>().contract(gpu_float2.cast<Eigen::half>(), dims);\n\n  Tensor<Eigen::half, 2> half_prec(rows, cols);\n  Tensor<Eigen::half, 2> full_prec(rows, cols);\n  gpu_device.memcpyDeviceToHost(half_prec.data(), d_res_half, num_elem*sizeof(Eigen::half));\n  gpu_device.memcpyDeviceToHost(full_prec.data(), d_res_float, num_elem*sizeof(Eigen::half));\n  gpu_device.synchronize();\n\n  for (int i = 0; i < rows; ++i) {\n    for (int j = 0; j < cols; ++j) {\n      std::cout << \"Checking contract \" << i << \" \" << j << full_prec(i, j) << \" \" << half_prec(i, j) << std::endl;\n      if (numext::abs(full_prec(i, j) - half_prec(i, j)) > Eigen::half(1e-2f)) {\n        VERIFY_IS_APPROX(full_prec(i, j), half_prec(i, j));\n      }\n    }\n  }\n\n  gpu_device.deallocate(d_float1);\n  gpu_device.deallocate(d_float2);\n  gpu_device.deallocate(d_res_half);\n  gpu_device.deallocate(d_res_float);\n}\n\ntemplate<typename>\nvoid test_gpu_reductions(int size1, int size2, int redux) {\n\n   std::cout << \"Reducing \" << size1 << \" by \" << size2\n             << \" tensor along dim \" << redux << std::endl;\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n  int num_elem = size1*size2;\n  int result_size = (redux == 1 ? size1 : size2);\n\n  float* d_float = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  Eigen::half* d_res_half = (Eigen::half*)gpu_device.allocate(result_size * sizeof(Eigen::half));\n  Eigen::half* d_res_float = (Eigen::half*)gpu_device.allocate(result_size * sizeof(Eigen::half));\n\n  Eigen::TensorMap<Eigen::Tensor<float, 2>, Eigen::Aligned> gpu_float(\n      d_float, size1, size2);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_res_half(\n      d_res_half, result_size);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_res_float(\n      d_res_float, result_size);\n\n  gpu_float.device(gpu_device) = gpu_float.random() * 2.0f;\n\n  Eigen::array<int, 1> redux_dim = {redux};\n  gpu_res_float.device(gpu_device) = gpu_float.sum(redux_dim).cast<Eigen::half>();\n  gpu_res_half.device(gpu_device) = gpu_float.cast<Eigen::half>().sum(redux_dim);\n\n  Tensor<Eigen::half, 1> half_prec(result_size);\n  Tensor<Eigen::half, 1> full_prec(result_size);\n  gpu_device.memcpyDeviceToHost(half_prec.data(), d_res_half, result_size*sizeof(Eigen::half));\n  gpu_device.memcpyDeviceToHost(full_prec.data(), d_res_float, result_size*sizeof(Eigen::half));\n  gpu_device.synchronize();\n\n  for (int i = 0; i < result_size; ++i) {\n    std::cout << \"EXPECTED \" << full_prec(i) << \" GOT \" << half_prec(i) << std::endl;\n    VERIFY_IS_APPROX(full_prec(i), half_prec(i));\n  }\n\n  gpu_device.deallocate(d_float);\n  gpu_device.deallocate(d_res_half);\n  gpu_device.deallocate(d_res_float);\n}\n\ntemplate<typename>\nvoid test_gpu_reductions() {\n  test_gpu_reductions<void>(13, 13, 0);\n  test_gpu_reductions<void>(13, 13, 1);\n\n  test_gpu_reductions<void>(35, 36, 0);\n  test_gpu_reductions<void>(35, 36, 1);\n\n  test_gpu_reductions<void>(36, 35, 0);\n  test_gpu_reductions<void>(36, 35, 1);\n}\n\ntemplate<typename>\nvoid test_gpu_full_reductions() {\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n  int size = 13;\n  int num_elem = size*size;\n\n  float* d_float = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  Eigen::half* d_res_half = (Eigen::half*)gpu_device.allocate(1 * sizeof(Eigen::half));\n  Eigen::half* d_res_float = (Eigen::half*)gpu_device.allocate(1 * sizeof(Eigen::half));\n\n  Eigen::TensorMap<Eigen::Tensor<float, 2>, Eigen::Aligned> gpu_float(\n      d_float, size, size);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 0>, Eigen::Aligned> gpu_res_half(\n      d_res_half);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 0>, Eigen::Aligned> gpu_res_float(\n      d_res_float);\n\n  gpu_float.device(gpu_device) = gpu_float.random();\n\n  gpu_res_float.device(gpu_device) = gpu_float.sum().cast<Eigen::half>();\n  gpu_res_half.device(gpu_device) = gpu_float.cast<Eigen::half>().sum();\n\n  Tensor<Eigen::half, 0> half_prec;\n  Tensor<Eigen::half, 0> full_prec;\n  gpu_device.memcpyDeviceToHost(half_prec.data(), d_res_half, sizeof(Eigen::half));\n  gpu_device.memcpyDeviceToHost(full_prec.data(), d_res_float, sizeof(Eigen::half));\n  gpu_device.synchronize();\n\n  VERIFY_IS_APPROX(full_prec(), half_prec());\n\n  gpu_res_float.device(gpu_device) = gpu_float.maximum().cast<Eigen::half>();\n  gpu_res_half.device(gpu_device) = gpu_float.cast<Eigen::half>().maximum();\n  gpu_device.memcpyDeviceToHost(half_prec.data(), d_res_half, sizeof(Eigen::half));\n  gpu_device.memcpyDeviceToHost(full_prec.data(), d_res_float, sizeof(Eigen::half));\n  gpu_device.synchronize();\n\n  VERIFY_IS_APPROX(full_prec(), half_prec());\n\n  gpu_device.deallocate(d_float);\n  gpu_device.deallocate(d_res_half);\n  gpu_device.deallocate(d_res_float);\n}\n\ntemplate<typename>\nvoid test_gpu_forced_evals() {\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n  int num_elem = 101;\n\n  float* d_float = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_res_half1 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_res_half2 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_res_float = (float*)gpu_device.allocate(num_elem * sizeof(float));\n\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_float(\n      d_float, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_res_half1(\n      d_res_half1, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Unaligned> gpu_res_half2(\n      d_res_half2, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_res_float(\n      d_res_float, num_elem);\n\n  Eigen::array<int, 1> no_bcast;\n  no_bcast[0] = 1;\n\n  gpu_float.device(gpu_device) = gpu_float.random() - gpu_float.constant(0.5f);\n  gpu_res_float.device(gpu_device) = gpu_float.abs();\n  gpu_res_half1.device(gpu_device) = gpu_float.cast<Eigen::half>().abs().eval().cast<float>();\n  gpu_res_half2.device(gpu_device) = gpu_float.cast<Eigen::half>().abs().broadcast(no_bcast).eval().cast<float>();\n\n  Tensor<float, 1> half_prec1(num_elem);\n  Tensor<float, 1> half_prec2(num_elem);\n  Tensor<float, 1> full_prec(num_elem);\n  gpu_device.memcpyDeviceToHost(half_prec1.data(), d_res_half1, num_elem*sizeof(float));\n  gpu_device.memcpyDeviceToHost(half_prec2.data(), d_res_half2, num_elem*sizeof(float));\n  gpu_device.memcpyDeviceToHost(full_prec.data(), d_res_float, num_elem*sizeof(float));\n  gpu_device.synchronize();\n\n  for (int i = 0; i < num_elem; ++i) {\n    std::cout << \"Checking forced eval \" << i << full_prec(i) << \" vs \" << half_prec1(i) << \" vs \" << half_prec2(i) << std::endl;\n    VERIFY_IS_APPROX(full_prec(i), half_prec1(i));\n    VERIFY_IS_APPROX(full_prec(i), half_prec2(i));\n  }\n\n  gpu_device.deallocate(d_float);\n  gpu_device.deallocate(d_res_half1);\n  gpu_device.deallocate(d_res_half2);\n  gpu_device.deallocate(d_res_float);\n}\n#endif\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_of_float16_gpu)\n{\n  CALL_SUBTEST_1(test_gpu_numext<void>());\n\n#ifdef EIGEN_HAS_GPU_FP16\n  CALL_SUBTEST_1(test_gpu_conversion<void>());\n  CALL_SUBTEST_1(test_gpu_unary<void>());\n  CALL_SUBTEST_1(test_gpu_elementwise<void>());\n  CALL_SUBTEST_1(test_gpu_trancendental<void>());\n  CALL_SUBTEST_2(test_gpu_contractions<void>());\n  CALL_SUBTEST_3(test_gpu_reductions<void>());\n  CALL_SUBTEST_4(test_gpu_full_reductions<void>());\n  CALL_SUBTEST_5(test_gpu_forced_evals<void>());\n#else\n  std::cout << \"Half floats are not supported by this version of gpu: skipping the test\" << std::endl;\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_of_strings.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\nstatic void test_assign()\n{\n  std::string data1[6];\n  TensorMap<Tensor<std::string, 2>> mat1(data1, 2, 3);\n  std::string data2[6];\n  const TensorMap<Tensor<const std::string, 2>> mat2(data2, 2, 3);\n\n  for (int i = 0; i < 6; ++i) {\n    std::ostringstream s1;\n    s1 << \"abc\" << i*3;\n    data1[i] = s1.str();\n    std::ostringstream s2;\n    s2 << \"def\" << i*5;\n    data2[i] = s2.str();\n  }\n\n  Tensor<std::string, 2> rslt1;\n  rslt1 = mat1;\n  Tensor<std::string, 2> rslt2;\n  rslt2 = mat2;\n\n  Tensor<std::string, 2> rslt3 = mat1;\n  Tensor<std::string, 2> rslt4 = mat2;\n\n  Tensor<std::string, 2> rslt5(mat1);\n  Tensor<std::string, 2> rslt6(mat2);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_EQUAL(rslt1(i,j), data1[i+2*j]);\n      VERIFY_IS_EQUAL(rslt2(i,j), data2[i+2*j]);\n      VERIFY_IS_EQUAL(rslt3(i,j), data1[i+2*j]);\n      VERIFY_IS_EQUAL(rslt4(i,j), data2[i+2*j]);\n      VERIFY_IS_EQUAL(rslt5(i,j), data1[i+2*j]);\n      VERIFY_IS_EQUAL(rslt6(i,j), data2[i+2*j]);\n    }\n  }\n}\n\n\nstatic void test_concat()\n{\n  Tensor<std::string, 2> t1(2, 3);\n  Tensor<std::string, 2> t2(2, 3);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      std::ostringstream s1;\n      s1 << \"abc\" << i + j*2;\n      t1(i, j) = s1.str();\n      std::ostringstream s2;\n      s2 << \"def\" << i*5 + j*32;\n      t2(i, j) = s2.str();\n    }\n  }\n\n  Tensor<std::string, 2> result = t1.concatenate(t2, 1);\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_EQUAL(result.dimension(1), 6);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_EQUAL(result(i, j),   t1(i, j));\n      VERIFY_IS_EQUAL(result(i, j+3), t2(i, j));\n    }\n  }\n}\n\n\nstatic void test_slices()\n{\n  Tensor<std::string, 2> data(2, 6);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      std::ostringstream s1;\n      s1 << \"abc\" << i + j*2;\n      data(i, j) = s1.str();\n    }\n  }\n\n  const Eigen::DSizes<ptrdiff_t, 2> half_size(2, 3);\n  const Eigen::DSizes<ptrdiff_t, 2> first_half(0, 0);\n  const Eigen::DSizes<ptrdiff_t, 2> second_half(0, 3);\n\n  Tensor<std::string, 2> t1 = data.slice(first_half, half_size);\n  Tensor<std::string, 2> t2 = data.slice(second_half, half_size);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_EQUAL(data(i, j),   t1(i, j));\n      VERIFY_IS_EQUAL(data(i, j+3), t2(i, j));\n    }\n  }\n}\n\n\nstatic void test_additions()\n{\n  Tensor<std::string, 1> data1(3);\n  Tensor<std::string, 1> data2(3);\n  for (int i = 0; i < 3; ++i) {\n    data1(i) = \"abc\";\n    std::ostringstream s1;\n    s1 << i;\n    data2(i) = s1.str();\n  }\n\n  Tensor<std::string, 1> sum = data1 + data2;\n  for (int i = 0; i < 3; ++i) {\n    std::ostringstream concat;\n    concat << \"abc\" << i;\n    std::string expected = concat.str();\n    VERIFY_IS_EQUAL(sum(i), expected);\n  }\n}\n\n\nstatic void test_initialization()\n{\n  Tensor<std::string, 2> a(2, 3);\n  a.setConstant(std::string(\"foo\"));\n  for (int i = 0; i < 2*3; ++i) {\n    VERIFY_IS_EQUAL(a(i), std::string(\"foo\"));\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_of_strings)\n{\n  // Beware: none of this is likely to ever work on a GPU.\n  CALL_SUBTEST(test_assign());\n  CALL_SUBTEST(test_concat());\n  CALL_SUBTEST(test_slices());\n  CALL_SUBTEST(test_additions());\n  CALL_SUBTEST(test_initialization());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_padding.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate<int DataLayout>\nstatic void test_simple_padding()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n\n  array<std::pair<ptrdiff_t, ptrdiff_t>, 4> paddings;\n  paddings[0] = std::make_pair(0, 0);\n  paddings[1] = std::make_pair(2, 1);\n  paddings[2] = std::make_pair(3, 4);\n  paddings[3] = std::make_pair(0, 0);\n\n  Tensor<float, 4, DataLayout> padded;\n  padded = tensor.pad(paddings);\n\n  VERIFY_IS_EQUAL(padded.dimension(0), 2+0);\n  VERIFY_IS_EQUAL(padded.dimension(1), 3+3);\n  VERIFY_IS_EQUAL(padded.dimension(2), 5+7);\n  VERIFY_IS_EQUAL(padded.dimension(3), 7+0);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 6; ++j) {\n      for (int k = 0; k < 12; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          if (j >= 2 && j < 5 && k >= 3 && k < 8) {\n            VERIFY_IS_EQUAL(padded(i,j,k,l), tensor(i,j-2,k-3,l));\n          } else {\n            VERIFY_IS_EQUAL(padded(i,j,k,l), 0.0f);\n          }\n        }\n      }\n    }\n  }\n}\n\ntemplate<int DataLayout>\nstatic void test_padded_expr()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n\n  array<std::pair<ptrdiff_t, ptrdiff_t>, 4> paddings;\n  paddings[0] = std::make_pair(0, 0);\n  paddings[1] = std::make_pair(2, 1);\n  paddings[2] = std::make_pair(3, 4);\n  paddings[3] = std::make_pair(0, 0);\n\n  Eigen::DSizes<ptrdiff_t, 2> reshape_dims;\n  reshape_dims[0] = 12;\n  reshape_dims[1] = 84;\n\n  Tensor<float, 2, DataLayout> result;\n  result = tensor.pad(paddings).reshape(reshape_dims);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 6; ++j) {\n      for (int k = 0; k < 12; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          const float result_value = DataLayout == ColMajor ?\n              result(i+2*j,k+12*l) : result(j+6*i,l+7*k);\n          if (j >= 2 && j < 5 && k >= 3 && k < 8) {\n            VERIFY_IS_EQUAL(result_value, tensor(i,j-2,k-3,l));\n          } else {\n            VERIFY_IS_EQUAL(result_value, 0.0f);\n          }\n        }\n      }\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_padding)\n{\n  CALL_SUBTEST(test_simple_padding<ColMajor>());\n  CALL_SUBTEST(test_simple_padding<RowMajor>());\n  CALL_SUBTEST(test_padded_expr<ColMajor>());\n  CALL_SUBTEST(test_padded_expr<RowMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_padding_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\n\ntemplate<typename DataType, int DataLayout, typename IndexType>\nstatic void test_simple_padding(const Eigen::SyclDevice& sycl_device)\n{\n\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  array<IndexType, 4> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n\n  Tensor<DataType, 4, DataLayout, IndexType> tensor(tensorRange);\n  tensor.setRandom();\n\n  array<std::pair<IndexType, IndexType>, 4> paddings;\n  paddings[0] = std::make_pair(0, 0);\n  paddings[1] = std::make_pair(2, 1);\n  paddings[2] = std::make_pair(3, 4);\n  paddings[3] = std::make_pair(0, 0);\n\n  IndexType padedSizeDim1 = 2;\n  IndexType padedSizeDim2 = 6;\n  IndexType padedSizeDim3 = 12;\n  IndexType padedSizeDim4 = 7;\n  array<IndexType, 4> padedtensorRange = {{padedSizeDim1, padedSizeDim2, padedSizeDim3, padedSizeDim4}};\n\n  Tensor<DataType, 4, DataLayout, IndexType> padded(padedtensorRange);\n\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(tensor.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(padded.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 4,DataLayout,IndexType>> gpu1(gpu_data1, tensorRange);\n  TensorMap<Tensor<DataType, 4,DataLayout,IndexType>> gpu2(gpu_data2, padedtensorRange);\n\n  VERIFY_IS_EQUAL(padded.dimension(0), 2+0);\n  VERIFY_IS_EQUAL(padded.dimension(1), 3+3);\n  VERIFY_IS_EQUAL(padded.dimension(2), 5+7);\n  VERIFY_IS_EQUAL(padded.dimension(3), 7+0);\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor.data(),(tensor.size())*sizeof(DataType));\n  gpu2.device(sycl_device)=gpu1.pad(paddings);\n  sycl_device.memcpyDeviceToHost(padded.data(), gpu_data2,(padded.size())*sizeof(DataType));\n  for (IndexType i = 0; i < padedSizeDim1; ++i) {\n    for (IndexType j = 0; j < padedSizeDim2; ++j) {\n      for (IndexType k = 0; k < padedSizeDim3; ++k) {\n        for (IndexType l = 0; l < padedSizeDim4; ++l) {\n          if (j >= 2 && j < 5 && k >= 3 && k < 8) {\n            VERIFY_IS_EQUAL(padded(i,j,k,l), tensor(i,j-2,k-3,l));\n          } else {\n            VERIFY_IS_EQUAL(padded(i,j,k,l), 0.0f);\n          }\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n}\n\ntemplate<typename DataType, int DataLayout, typename IndexType>\nstatic void test_padded_expr(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  array<IndexType, 4> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n\n  Tensor<DataType, 4, DataLayout, IndexType> tensor(tensorRange);\n  tensor.setRandom();\n\n  array<std::pair<IndexType, IndexType>, 4> paddings;\n  paddings[0] = std::make_pair(0, 0);\n  paddings[1] = std::make_pair(2, 1);\n  paddings[2] = std::make_pair(3, 4);\n  paddings[3] = std::make_pair(0, 0);\n\n  Eigen::DSizes<IndexType, 2> reshape_dims;\n  reshape_dims[0] = 12;\n  reshape_dims[1] = 84;\n\n\n  Tensor<DataType, 2, DataLayout, IndexType>  result(reshape_dims);\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(tensor.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(result.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 4,DataLayout,IndexType>> gpu1(gpu_data1, tensorRange);\n  TensorMap<Tensor<DataType, 2,DataLayout,IndexType>> gpu2(gpu_data2, reshape_dims);\n\n\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor.data(),(tensor.size())*sizeof(DataType));\n  gpu2.device(sycl_device)=gpu1.pad(paddings).reshape(reshape_dims);\n  sycl_device.memcpyDeviceToHost(result.data(), gpu_data2,(result.size())*sizeof(DataType));\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 6; ++j) {\n      for (IndexType k = 0; k < 12; ++k) {\n        for (IndexType l = 0; l < 7; ++l) {\n          const float result_value = DataLayout == ColMajor ?\n              result(i+2*j,k+12*l) : result(j+6*i,l+7*k);\n          if (j >= 2 && j < 5 && k >= 3 && k < 8) {\n            VERIFY_IS_EQUAL(result_value, tensor(i,j-2,k-3,l));\n          } else {\n            VERIFY_IS_EQUAL(result_value, 0.0f);\n          }\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n}\n\ntemplate<typename DataType, typename dev_Selector> void sycl_padding_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_simple_padding<DataType, RowMajor, int64_t>(sycl_device);\n  test_simple_padding<DataType, ColMajor, int64_t>(sycl_device);\n  test_padded_expr<DataType, RowMajor, int64_t>(sycl_device);\n  test_padded_expr<DataType, ColMajor, int64_t>(sycl_device);\n\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_padding_sycl)\n{\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_padding_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_patch.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate<int DataLayout>\nstatic void test_simple_patch()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> patch_dims;\n\n  patch_dims[0] = 1;\n  patch_dims[1] = 1;\n  patch_dims[2] = 1;\n  patch_dims[3] = 1;\n\n  Tensor<float, 5, DataLayout> no_patch;\n  no_patch = tensor.extract_patches(patch_dims);\n\n  if (DataLayout == ColMajor) {\n    VERIFY_IS_EQUAL(no_patch.dimension(0), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(1), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(2), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(3), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(4), tensor.size());\n  } else {\n    VERIFY_IS_EQUAL(no_patch.dimension(0), tensor.size());\n    VERIFY_IS_EQUAL(no_patch.dimension(1), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(2), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(3), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(4), 1);\n  }\n\n  for (int i = 0; i < tensor.size(); ++i) {\n    VERIFY_IS_EQUAL(tensor.data()[i], no_patch.data()[i]);\n  }\n\n  patch_dims[0] = 2;\n  patch_dims[1] = 3;\n  patch_dims[2] = 5;\n  patch_dims[3] = 7;\n  Tensor<float, 5, DataLayout> single_patch;\n  single_patch = tensor.extract_patches(patch_dims);\n\n  if (DataLayout == ColMajor) {\n    VERIFY_IS_EQUAL(single_patch.dimension(0), 2);\n    VERIFY_IS_EQUAL(single_patch.dimension(1), 3);\n    VERIFY_IS_EQUAL(single_patch.dimension(2), 5);\n    VERIFY_IS_EQUAL(single_patch.dimension(3), 7);\n    VERIFY_IS_EQUAL(single_patch.dimension(4), 1);\n  } else {\n    VERIFY_IS_EQUAL(single_patch.dimension(0), 1);\n    VERIFY_IS_EQUAL(single_patch.dimension(1), 2);\n    VERIFY_IS_EQUAL(single_patch.dimension(2), 3);\n    VERIFY_IS_EQUAL(single_patch.dimension(3), 5);\n    VERIFY_IS_EQUAL(single_patch.dimension(4), 7);\n  }\n\n  for (int i = 0; i < tensor.size(); ++i) {\n    VERIFY_IS_EQUAL(tensor.data()[i], single_patch.data()[i]);\n  }\n\n  patch_dims[0] = 1;\n  patch_dims[1] = 2;\n  patch_dims[2] = 2;\n  patch_dims[3] = 1;\n  Tensor<float, 5, DataLayout> twod_patch;\n  twod_patch = tensor.extract_patches(patch_dims);\n\n  if (DataLayout == ColMajor) {\n    VERIFY_IS_EQUAL(twod_patch.dimension(0), 1);\n    VERIFY_IS_EQUAL(twod_patch.dimension(1), 2);\n    VERIFY_IS_EQUAL(twod_patch.dimension(2), 2);\n    VERIFY_IS_EQUAL(twod_patch.dimension(3), 1);\n    VERIFY_IS_EQUAL(twod_patch.dimension(4), 2*2*4*7);\n  } else {\n    VERIFY_IS_EQUAL(twod_patch.dimension(0), 2*2*4*7);\n    VERIFY_IS_EQUAL(twod_patch.dimension(1), 1);\n    VERIFY_IS_EQUAL(twod_patch.dimension(2), 2);\n    VERIFY_IS_EQUAL(twod_patch.dimension(3), 2);\n    VERIFY_IS_EQUAL(twod_patch.dimension(4), 1);\n  }\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 2; ++j) {\n      for (int k = 0; k < 4; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          int patch_loc;\n          if (DataLayout == ColMajor) {\n            patch_loc = i + 2 * (j + 2 * (k + 4 * l));\n          } else {\n            patch_loc = l + 7 * (k + 4 * (j + 2 * i));\n          }\n          for (int x = 0; x < 2; ++x) {\n            for (int y = 0; y < 2; ++y) {\n              if (DataLayout == ColMajor) {\n                VERIFY_IS_EQUAL(tensor(i,j+x,k+y,l), twod_patch(0,x,y,0,patch_loc));\n              } else {\n                VERIFY_IS_EQUAL(tensor(i,j+x,k+y,l), twod_patch(patch_loc,0,x,y,0));\n              }\n            }\n          }\n        }\n      }\n    }\n  }\n\n  patch_dims[0] = 1;\n  patch_dims[1] = 2;\n  patch_dims[2] = 3;\n  patch_dims[3] = 5;\n  Tensor<float, 5, DataLayout> threed_patch;\n  threed_patch = tensor.extract_patches(patch_dims);\n\n  if (DataLayout == ColMajor) {\n    VERIFY_IS_EQUAL(threed_patch.dimension(0), 1);\n    VERIFY_IS_EQUAL(threed_patch.dimension(1), 2);\n    VERIFY_IS_EQUAL(threed_patch.dimension(2), 3);\n    VERIFY_IS_EQUAL(threed_patch.dimension(3), 5);\n    VERIFY_IS_EQUAL(threed_patch.dimension(4), 2*2*3*3);\n  } else {\n    VERIFY_IS_EQUAL(threed_patch.dimension(0), 2*2*3*3);\n    VERIFY_IS_EQUAL(threed_patch.dimension(1), 1);\n    VERIFY_IS_EQUAL(threed_patch.dimension(2), 2);\n    VERIFY_IS_EQUAL(threed_patch.dimension(3), 3);\n    VERIFY_IS_EQUAL(threed_patch.dimension(4), 5);\n  }\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 2; ++j) {\n      for (int k = 0; k < 3; ++k) {\n        for (int l = 0; l < 3; ++l) {\n          int patch_loc;\n          if (DataLayout == ColMajor) {\n            patch_loc = i + 2 * (j + 2 * (k + 3 * l));\n          } else {\n            patch_loc = l + 3 * (k + 3 * (j + 2 * i));\n          }\n          for (int x = 0; x < 2; ++x) {\n            for (int y = 0; y < 3; ++y) {\n              for (int z = 0; z < 5; ++z) {\n                if (DataLayout == ColMajor) {\n                  VERIFY_IS_EQUAL(tensor(i,j+x,k+y,l+z), threed_patch(0,x,y,z,patch_loc));\n                } else {\n                  VERIFY_IS_EQUAL(tensor(i,j+x,k+y,l+z), threed_patch(patch_loc,0,x,y,z));\n                }\n              }\n            }\n          }\n        }\n      }\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_patch)\n{\n   CALL_SUBTEST(test_simple_patch<ColMajor>());\n   CALL_SUBTEST(test_simple_patch<RowMajor>());\n   //   CALL_SUBTEST(test_expr_shuffling());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_patch_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_simple_patch_sycl(const Eigen::SyclDevice& sycl_device){\n\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  array<IndexType, 4> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  array<IndexType, 5> patchTensorRange;\n  if (DataLayout == ColMajor) {\n   patchTensorRange = {{1, 1, 1, 1, sizeDim1*sizeDim2*sizeDim3*sizeDim4}};\n  }else{\n     patchTensorRange = {{sizeDim1*sizeDim2*sizeDim3*sizeDim4,1, 1, 1, 1}};\n  }\n\n  Tensor<DataType, 4, DataLayout,IndexType> tensor(tensorRange);\n  Tensor<DataType, 5, DataLayout,IndexType> no_patch(patchTensorRange);\n\n  tensor.setRandom();\n\n  array<ptrdiff_t, 4> patch_dims;\n  patch_dims[0] = 1;\n  patch_dims[1] = 1;\n  patch_dims[2] = 1;\n  patch_dims[3] = 1;\n\n  const size_t tensorBuffSize =tensor.size()*sizeof(DataType);\n  size_t patchTensorBuffSize =no_patch.size()*sizeof(DataType);\n  DataType* gpu_data_tensor  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  DataType* gpu_data_no_patch  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_tensor(gpu_data_tensor, tensorRange);\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_no_patch(gpu_data_no_patch, patchTensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_tensor, tensor.data(), tensorBuffSize);\n  gpu_no_patch.device(sycl_device)=gpu_tensor.extract_patches(patch_dims);\n  sycl_device.memcpyDeviceToHost(no_patch.data(), gpu_data_no_patch, patchTensorBuffSize);\n\n  if (DataLayout == ColMajor) {\n    VERIFY_IS_EQUAL(no_patch.dimension(0), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(1), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(2), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(3), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(4), tensor.size());\n  } else {\n    VERIFY_IS_EQUAL(no_patch.dimension(0), tensor.size());\n    VERIFY_IS_EQUAL(no_patch.dimension(1), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(2), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(3), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(4), 1);\n  }\n\n  for (int i = 0; i < tensor.size(); ++i) {\n    VERIFY_IS_EQUAL(tensor.data()[i], no_patch.data()[i]);\n  }\n\n  patch_dims[0] = 2;\n  patch_dims[1] = 3;\n  patch_dims[2] = 5;\n  patch_dims[3] = 7;\n\n  if (DataLayout == ColMajor) {\n   patchTensorRange = {{sizeDim1,sizeDim2,sizeDim3,sizeDim4,1}};\n  }else{\n     patchTensorRange = {{1,sizeDim1,sizeDim2,sizeDim3,sizeDim4}};\n  }\n  Tensor<DataType, 5, DataLayout,IndexType> single_patch(patchTensorRange);\n  patchTensorBuffSize =single_patch.size()*sizeof(DataType);\n  DataType* gpu_data_single_patch  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_single_patch(gpu_data_single_patch, patchTensorRange);\n\n  gpu_single_patch.device(sycl_device)=gpu_tensor.extract_patches(patch_dims);\n  sycl_device.memcpyDeviceToHost(single_patch.data(), gpu_data_single_patch, patchTensorBuffSize);\n\n  if (DataLayout == ColMajor) {\n    VERIFY_IS_EQUAL(single_patch.dimension(0), 2);\n    VERIFY_IS_EQUAL(single_patch.dimension(1), 3);\n    VERIFY_IS_EQUAL(single_patch.dimension(2), 5);\n    VERIFY_IS_EQUAL(single_patch.dimension(3), 7);\n    VERIFY_IS_EQUAL(single_patch.dimension(4), 1);\n  } else {\n    VERIFY_IS_EQUAL(single_patch.dimension(0), 1);\n    VERIFY_IS_EQUAL(single_patch.dimension(1), 2);\n    VERIFY_IS_EQUAL(single_patch.dimension(2), 3);\n    VERIFY_IS_EQUAL(single_patch.dimension(3), 5);\n    VERIFY_IS_EQUAL(single_patch.dimension(4), 7);\n  }\n\n  for (int i = 0; i < tensor.size(); ++i) {\n    VERIFY_IS_EQUAL(tensor.data()[i], single_patch.data()[i]);\n  }\n  patch_dims[0] = 1;\n  patch_dims[1] = 2;\n  patch_dims[2] = 2;\n  patch_dims[3] = 1;\n  \n  if (DataLayout == ColMajor) {\n   patchTensorRange = {{1,2,2,1,2*2*4*7}};\n  }else{\n     patchTensorRange = {{2*2*4*7, 1, 2,2,1}};\n  }\n  Tensor<DataType, 5, DataLayout,IndexType> twod_patch(patchTensorRange);\n  patchTensorBuffSize =twod_patch.size()*sizeof(DataType);\n  DataType* gpu_data_twod_patch  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_twod_patch(gpu_data_twod_patch, patchTensorRange);\n\n  gpu_twod_patch.device(sycl_device)=gpu_tensor.extract_patches(patch_dims);\n  sycl_device.memcpyDeviceToHost(twod_patch.data(), gpu_data_twod_patch, patchTensorBuffSize);\n\n  if (DataLayout == ColMajor) {\n    VERIFY_IS_EQUAL(twod_patch.dimension(0), 1);\n    VERIFY_IS_EQUAL(twod_patch.dimension(1), 2);\n    VERIFY_IS_EQUAL(twod_patch.dimension(2), 2);\n    VERIFY_IS_EQUAL(twod_patch.dimension(3), 1);\n    VERIFY_IS_EQUAL(twod_patch.dimension(4), 2*2*4*7);\n  } else {\n    VERIFY_IS_EQUAL(twod_patch.dimension(0), 2*2*4*7);\n    VERIFY_IS_EQUAL(twod_patch.dimension(1), 1);\n    VERIFY_IS_EQUAL(twod_patch.dimension(2), 2);\n    VERIFY_IS_EQUAL(twod_patch.dimension(3), 2);\n    VERIFY_IS_EQUAL(twod_patch.dimension(4), 1);\n  }\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 2; ++j) {\n      for (int k = 0; k < 4; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          int patch_loc;\n          if (DataLayout == ColMajor) {\n            patch_loc = i + 2 * (j + 2 * (k + 4 * l));\n          } else {\n            patch_loc = l + 7 * (k + 4 * (j + 2 * i));\n          }\n          for (int x = 0; x < 2; ++x) {\n            for (int y = 0; y < 2; ++y) {\n              if (DataLayout == ColMajor) {\n                VERIFY_IS_EQUAL(tensor(i,j+x,k+y,l), twod_patch(0,x,y,0,patch_loc));\n              } else {\n                VERIFY_IS_EQUAL(tensor(i,j+x,k+y,l), twod_patch(patch_loc,0,x,y,0));\n              }\n            }\n          }\n        }\n      }\n    }\n  }\n\n  patch_dims[0] = 1;\n  patch_dims[1] = 2;\n  patch_dims[2] = 3;\n  patch_dims[3] = 5;\n\n  if (DataLayout == ColMajor) {\n   patchTensorRange = {{1,2,3,5,2*2*3*3}};\n  }else{\n     patchTensorRange = {{2*2*3*3, 1, 2,3,5}};\n  }\n  Tensor<DataType, 5, DataLayout,IndexType> threed_patch(patchTensorRange);\n  patchTensorBuffSize =threed_patch.size()*sizeof(DataType);\n  DataType* gpu_data_threed_patch  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_threed_patch(gpu_data_threed_patch, patchTensorRange);\n\n  gpu_threed_patch.device(sycl_device)=gpu_tensor.extract_patches(patch_dims);\n  sycl_device.memcpyDeviceToHost(threed_patch.data(), gpu_data_threed_patch, patchTensorBuffSize);\n\n  if (DataLayout == ColMajor) {\n    VERIFY_IS_EQUAL(threed_patch.dimension(0), 1);\n    VERIFY_IS_EQUAL(threed_patch.dimension(1), 2);\n    VERIFY_IS_EQUAL(threed_patch.dimension(2), 3);\n    VERIFY_IS_EQUAL(threed_patch.dimension(3), 5);\n    VERIFY_IS_EQUAL(threed_patch.dimension(4), 2*2*3*3);\n  } else {\n    VERIFY_IS_EQUAL(threed_patch.dimension(0), 2*2*3*3);\n    VERIFY_IS_EQUAL(threed_patch.dimension(1), 1);\n    VERIFY_IS_EQUAL(threed_patch.dimension(2), 2);\n    VERIFY_IS_EQUAL(threed_patch.dimension(3), 3);\n    VERIFY_IS_EQUAL(threed_patch.dimension(4), 5);\n  }\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 2; ++j) {\n      for (int k = 0; k < 3; ++k) {\n        for (int l = 0; l < 3; ++l) {\n          int patch_loc;\n          if (DataLayout == ColMajor) {\n            patch_loc = i + 2 * (j + 2 * (k + 3 * l));\n          } else {\n            patch_loc = l + 3 * (k + 3 * (j + 2 * i));\n          }\n          for (int x = 0; x < 2; ++x) {\n            for (int y = 0; y < 3; ++y) {\n              for (int z = 0; z < 5; ++z) {\n                if (DataLayout == ColMajor) {\n                  VERIFY_IS_EQUAL(tensor(i,j+x,k+y,l+z), threed_patch(0,x,y,z,patch_loc));\n                } else {\n                  VERIFY_IS_EQUAL(tensor(i,j+x,k+y,l+z), threed_patch(patch_loc,0,x,y,z));\n                }\n              }\n            }\n          }\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data_tensor);\n  sycl_device.deallocate(gpu_data_no_patch);\n  sycl_device.deallocate(gpu_data_single_patch);\n  sycl_device.deallocate(gpu_data_twod_patch);\n  sycl_device.deallocate(gpu_data_threed_patch);\n}\n\ntemplate<typename DataType, typename dev_Selector> void sycl_tensor_patch_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_simple_patch_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_simple_patch_sycl<DataType, ColMajor, int64_t>(sycl_device);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_patch_sycl)\n{\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_tensor_patch_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_random.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\ntemplate<typename Scalar>\nstatic void test_default()\n{\n  Tensor<Scalar, 1> vec(6);\n  vec.setRandom();\n\n  // Fixme: we should check that the generated numbers follow a uniform\n  // distribution instead.\n  for (int i = 1; i < 6; ++i) {\n    VERIFY_IS_NOT_EQUAL(vec(i), vec(i-1));\n  }\n}\n\ntemplate<typename Scalar>\nstatic void test_normal()\n{\n  Tensor<Scalar, 1> vec(6);\n  vec.template setRandom<Eigen::internal::NormalRandomGenerator<Scalar>>();\n\n  // Fixme: we should check that the generated numbers follow a gaussian\n  // distribution instead.\n  for (int i = 1; i < 6; ++i) {\n    VERIFY_IS_NOT_EQUAL(vec(i), vec(i-1));\n  }\n}\n\n\nstruct MyGenerator {\n  MyGenerator() { }\n  MyGenerator(const MyGenerator&) { }\n\n  // Return a random value to be used.  \"element_location\" is the\n  // location of the entry to set in the tensor, it can typically\n  // be ignored.\n  int operator()(Eigen::DenseIndex element_location, Eigen::DenseIndex /*unused*/ = 0) const {\n    return static_cast<int>(3 * element_location);\n  }\n\n  // Same as above but generates several numbers at a time.\n  internal::packet_traits<int>::type packetOp(\n      Eigen::DenseIndex packet_location, Eigen::DenseIndex /*unused*/ = 0) const {\n    const int packetSize = internal::packet_traits<int>::size;\n    EIGEN_ALIGN_MAX int values[packetSize];\n    for (int i = 0; i < packetSize; ++i) {\n      values[i] = static_cast<int>(3 * (packet_location + i));\n    }\n    return internal::pload<typename internal::packet_traits<int>::type>(values);\n  }\n};\n\n\nstatic void test_custom()\n{\n  Tensor<int, 1> vec(6);\n  vec.setRandom<MyGenerator>();\n\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_EQUAL(vec(i), 3*i);\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_random)\n{\n  CALL_SUBTEST((test_default<float>()));\n  CALL_SUBTEST((test_normal<float>()));\n  CALL_SUBTEST((test_default<double>()));\n  CALL_SUBTEST((test_normal<double>()));\n  CALL_SUBTEST((test_default<Eigen::half>()));\n  CALL_SUBTEST((test_normal<Eigen::half>()));\n  CALL_SUBTEST((test_default<Eigen::bfloat16>()));\n  CALL_SUBTEST((test_normal<Eigen::bfloat16>()));\n  CALL_SUBTEST(test_custom());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_random_gpu.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <Eigen/CXX11/Tensor>\n\n#include <Eigen/CXX11/src/Tensor/TensorGpuHipCudaDefines.h>\n\nvoid test_gpu_random_uniform()\n{\n  Tensor<float, 2> out(72,97);\n  out.setZero();\n\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_out;\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 2> > gpu_out(d_out, 72,97);\n\n  gpu_out.device(gpu_device) = gpu_out.random();\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  // For now we just check this code doesn't crash.\n  // TODO: come up with a valid test of randomness\n}\n\n\nvoid test_gpu_random_normal()\n{\n  Tensor<float, 2> out(72,97);\n  out.setZero();\n\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_out;\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 2> > gpu_out(d_out, 72,97);\n\n  Eigen::internal::NormalRandomGenerator<float> gen(true);\n  gpu_out.device(gpu_device) = gpu_out.random(gen);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n}\n\nstatic void test_complex()\n{\n  Tensor<std::complex<float>, 1> vec(6);\n  vec.setRandom();\n\n  // Fixme: we should check that the generated numbers follow a uniform\n  // distribution instead.\n  for (int i = 1; i < 6; ++i) {\n    VERIFY_IS_NOT_EQUAL(vec(i), vec(i-1));\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_random_gpu)\n{\n  CALL_SUBTEST(test_gpu_random_uniform());\n  CALL_SUBTEST(test_gpu_random_normal());\n  CALL_SUBTEST(test_complex());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_random_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_sycl_random_uniform(const Eigen::SyclDevice& sycl_device)\n{\n  Tensor<DataType, 2,DataLayout, IndexType> out(72,97);\n  out.setZero();\n\n  std::size_t out_bytes = out.size() * sizeof(DataType);\n\n  IndexType sizeDim0 = 72;\n  IndexType sizeDim1 = 97;\n\n  array<IndexType, 2> tensorRange = {{sizeDim0, sizeDim1}};\n\n  DataType* d_out  = static_cast<DataType*>(sycl_device.allocate(out_bytes));\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> gpu_out(d_out, tensorRange);\n\n  gpu_out.device(sycl_device)=gpu_out.random();\n  sycl_device.memcpyDeviceToHost(out.data(), d_out,out_bytes);\n  for(IndexType i=1; i<sizeDim0; i++)\n    for(IndexType j=1; j<sizeDim1; j++)\n    {\n      VERIFY_IS_NOT_EQUAL(out(i,j), out(i-1,j));\n      VERIFY_IS_NOT_EQUAL(out(i,j), out(i,j-1));\n      VERIFY_IS_NOT_EQUAL(out(i,j), out(i-1,j-1));    }\n\n  // For now we just check thes code doesn't crash.\n  // TODO: come up with a valid test of randomness\n  sycl_device.deallocate(d_out);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_sycl_random_normal(const Eigen::SyclDevice& sycl_device)\n{\n  Tensor<DataType, 2,DataLayout,IndexType> out(72,97);\n  out.setZero();\n  std::size_t out_bytes = out.size() * sizeof(DataType);\n\n  IndexType sizeDim0 = 72;\n  IndexType sizeDim1 = 97;\n\n  array<IndexType, 2> tensorRange = {{sizeDim0, sizeDim1}};\n\n  DataType* d_out  = static_cast<DataType*>(sycl_device.allocate(out_bytes));\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> gpu_out(d_out, tensorRange);\n  Eigen::internal::NormalRandomGenerator<DataType> gen(true);\n  gpu_out.device(sycl_device)=gpu_out.random(gen);\n  sycl_device.memcpyDeviceToHost(out.data(), d_out,out_bytes);\n  for(IndexType i=1; i<sizeDim0; i++)\n    for(IndexType j=1; j<sizeDim1; j++)\n    {\n      VERIFY_IS_NOT_EQUAL(out(i,j), out(i-1,j));\n      VERIFY_IS_NOT_EQUAL(out(i,j), out(i,j-1));\n      VERIFY_IS_NOT_EQUAL(out(i,j), out(i-1,j-1));\n\n    }\n\n  // For now we just check thes code doesn't crash.\n  // TODO: come up with a valid test of randomness\n  sycl_device.deallocate(d_out);\n}\n\ntemplate<typename DataType, typename dev_Selector> void sycl_random_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_sycl_random_uniform<DataType, RowMajor, int64_t>(sycl_device);\n  test_sycl_random_uniform<DataType, ColMajor, int64_t>(sycl_device);\n  test_sycl_random_normal<DataType, RowMajor, int64_t>(sycl_device);\n  test_sycl_random_normal<DataType, ColMajor, int64_t>(sycl_device);\n\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_random_sycl)\n{\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_random_test_per_device<float>(device));\n#ifdef EIGEN_SYCL_DOUBLE_SUPPORT\n    CALL_SUBTEST(sycl_random_test_per_device<double>(device));\n#endif\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_reduction.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <limits>\n#include <numeric>\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate <int DataLayout>\nstatic void test_trivial_reductions() {\n  {\n    Tensor<float, 0, DataLayout> tensor;\n    tensor.setRandom();\n    array<ptrdiff_t, 0> reduction_axis;\n\n    Tensor<float, 0, DataLayout> result = tensor.sum(reduction_axis);\n    VERIFY_IS_EQUAL(result(), tensor());\n  }\n\n  {\n    Tensor<float, 1, DataLayout> tensor(7);\n    tensor.setRandom();\n    array<ptrdiff_t, 0> reduction_axis;\n\n    Tensor<float, 1, DataLayout> result = tensor.sum(reduction_axis);\n    VERIFY_IS_EQUAL(result.dimension(0), 7);\n    for (int i = 0; i < 7; ++i) {\n      VERIFY_IS_EQUAL(result(i), tensor(i));\n    }\n  }\n\n  {\n    Tensor<float, 2, DataLayout> tensor(2, 3);\n    tensor.setRandom();\n    array<ptrdiff_t, 0> reduction_axis;\n\n    Tensor<float, 2, DataLayout> result = tensor.sum(reduction_axis);\n    VERIFY_IS_EQUAL(result.dimension(0), 2);\n    VERIFY_IS_EQUAL(result.dimension(1), 3);\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 3; ++j) {\n        VERIFY_IS_EQUAL(result(i, j), tensor(i, j));\n      }\n    }\n  }\n}\n\ntemplate <typename Scalar,int DataLayout>\nstatic void test_simple_reductions() {\n  Tensor<Scalar, 4, DataLayout> tensor(2, 3, 5, 7);\n  tensor.setRandom();\n  // Add a little offset so that the product reductions won't be close to zero.\n  tensor += tensor.constant(Scalar(0.5f));\n  array<ptrdiff_t, 2> reduction_axis2;\n  reduction_axis2[0] = 1;\n  reduction_axis2[1] = 3;\n\n  Tensor<Scalar, 2, DataLayout> result = tensor.sum(reduction_axis2);\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_EQUAL(result.dimension(1), 5);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      Scalar sum = Scalar(0.0f);\n      for (int k = 0; k < 3; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          sum += tensor(i, k, j, l);\n        }\n      }\n      VERIFY_IS_APPROX(result(i, j), sum);\n    }\n  }\n\n  {\n    Tensor<Scalar, 0, DataLayout> sum1 = tensor.sum();\n    VERIFY_IS_EQUAL(sum1.rank(), 0);\n\n    array<ptrdiff_t, 4> reduction_axis4;\n    reduction_axis4[0] = 0;\n    reduction_axis4[1] = 1;\n    reduction_axis4[2] = 2;\n    reduction_axis4[3] = 3;\n    Tensor<Scalar, 0, DataLayout> sum2 = tensor.sum(reduction_axis4);\n    VERIFY_IS_EQUAL(sum2.rank(), 0);\n\n    VERIFY_IS_APPROX(sum1(), sum2());\n  }\n\n  reduction_axis2[0] = 0;\n  reduction_axis2[1] = 2;\n  result = tensor.prod(reduction_axis2);\n  VERIFY_IS_EQUAL(result.dimension(0), 3);\n  VERIFY_IS_EQUAL(result.dimension(1), 7);\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 7; ++j) {\n      Scalar prod = Scalar(1.0f);\n      for (int k = 0; k < 2; ++k) {\n        for (int l = 0; l < 5; ++l) {\n          prod *= tensor(k, i, l, j);\n        }\n      }\n      VERIFY_IS_APPROX(result(i, j), prod);\n    }\n  }\n\n  {\n    Tensor<Scalar, 0, DataLayout> prod1 = tensor.prod();\n    VERIFY_IS_EQUAL(prod1.rank(), 0);\n\n    array<ptrdiff_t, 4> reduction_axis4;\n    reduction_axis4[0] = 0;\n    reduction_axis4[1] = 1;\n    reduction_axis4[2] = 2;\n    reduction_axis4[3] = 3;\n    Tensor<Scalar, 0, DataLayout> prod2 = tensor.prod(reduction_axis4);\n    VERIFY_IS_EQUAL(prod2.rank(), 0);\n\n    VERIFY_IS_APPROX(prod1(), prod2());\n  }\n\n  reduction_axis2[0] = 0;\n  reduction_axis2[1] = 2;\n  result = tensor.maximum(reduction_axis2);\n  VERIFY_IS_EQUAL(result.dimension(0), 3);\n  VERIFY_IS_EQUAL(result.dimension(1), 7);\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 7; ++j) {\n      Scalar max_val = std::numeric_limits<Scalar>::lowest();\n      for (int k = 0; k < 2; ++k) {\n        for (int l = 0; l < 5; ++l) {\n          max_val = (std::max)(max_val, tensor(k, i, l, j));\n        }\n      }\n      VERIFY_IS_APPROX(result(i, j), max_val);\n    }\n  }\n\n  {\n    Tensor<Scalar, 0, DataLayout> max1 = tensor.maximum();\n    VERIFY_IS_EQUAL(max1.rank(), 0);\n\n    array<ptrdiff_t, 4> reduction_axis4;\n    reduction_axis4[0] = 0;\n    reduction_axis4[1] = 1;\n    reduction_axis4[2] = 2;\n    reduction_axis4[3] = 3;\n    Tensor<Scalar, 0, DataLayout> max2 = tensor.maximum(reduction_axis4);\n    VERIFY_IS_EQUAL(max2.rank(), 0);\n\n    VERIFY_IS_APPROX(max1(), max2());\n  }\n\n  reduction_axis2[0] = 0;\n  reduction_axis2[1] = 1;\n  result = tensor.minimum(reduction_axis2);\n  VERIFY_IS_EQUAL(result.dimension(0), 5);\n  VERIFY_IS_EQUAL(result.dimension(1), 7);\n  for (int i = 0; i < 5; ++i) {\n    for (int j = 0; j < 7; ++j) {\n      Scalar min_val = (std::numeric_limits<Scalar>::max)();\n      for (int k = 0; k < 2; ++k) {\n        for (int l = 0; l < 3; ++l) {\n          min_val = (std::min)(min_val, tensor(k, l, i, j));\n        }\n      }\n      VERIFY_IS_APPROX(result(i, j), min_val);\n    }\n  }\n\n  {\n    Tensor<Scalar, 0, DataLayout> min1 = tensor.minimum();\n    VERIFY_IS_EQUAL(min1.rank(), 0);\n\n    array<ptrdiff_t, 4> reduction_axis4;\n    reduction_axis4[0] = 0;\n    reduction_axis4[1] = 1;\n    reduction_axis4[2] = 2;\n    reduction_axis4[3] = 3;\n    Tensor<Scalar, 0, DataLayout> min2 = tensor.minimum(reduction_axis4);\n    VERIFY_IS_EQUAL(min2.rank(), 0);\n\n    VERIFY_IS_APPROX(min1(), min2());\n  }\n\n  reduction_axis2[0] = 0;\n  reduction_axis2[1] = 1;\n  result = tensor.mean(reduction_axis2);\n  VERIFY_IS_EQUAL(result.dimension(0), 5);\n  VERIFY_IS_EQUAL(result.dimension(1), 7);\n  for (int i = 0; i < 5; ++i) {\n    for (int j = 0; j < 7; ++j) {\n      Scalar sum = Scalar(0.0f);\n      int count = 0;\n      for (int k = 0; k < 2; ++k) {\n        for (int l = 0; l < 3; ++l) {\n          sum += tensor(k, l, i, j);\n          ++count;\n        }\n      }\n      VERIFY_IS_APPROX(result(i, j), sum / Scalar(count));\n    }\n  }\n\n  {\n    Tensor<Scalar, 0, DataLayout> mean1 = tensor.mean();\n    VERIFY_IS_EQUAL(mean1.rank(), 0);\n\n    array<ptrdiff_t, 4> reduction_axis4;\n    reduction_axis4[0] = 0;\n    reduction_axis4[1] = 1;\n    reduction_axis4[2] = 2;\n    reduction_axis4[3] = 3;\n    Tensor<Scalar, 0, DataLayout> mean2 = tensor.mean(reduction_axis4);\n    VERIFY_IS_EQUAL(mean2.rank(), 0);\n\n    VERIFY_IS_APPROX(mean1(), mean2());\n  }\n\n  {\n    Tensor<int, 1> ints(10);\n    std::iota(ints.data(), ints.data() + ints.dimension(0), 0);\n\n    TensorFixedSize<bool, Sizes<> > all_;\n    all_ = ints.all();\n    VERIFY(!all_());\n    all_ = (ints >= ints.constant(0)).all();\n    VERIFY(all_());\n\n    TensorFixedSize<bool, Sizes<> > any;\n    any = (ints > ints.constant(10)).any();\n    VERIFY(!any());\n    any = (ints < ints.constant(1)).any();\n    VERIFY(any());\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_reductions_in_expr() {\n  Tensor<float, 4, DataLayout> tensor(2, 3, 5, 7);\n  tensor.setRandom();\n  array<ptrdiff_t, 2> reduction_axis2;\n  reduction_axis2[0] = 1;\n  reduction_axis2[1] = 3;\n\n  Tensor<float, 2, DataLayout> result(2, 5);\n  result = result.constant(1.0f) - tensor.sum(reduction_axis2);\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_EQUAL(result.dimension(1), 5);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      float sum = 0.0f;\n      for (int k = 0; k < 3; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          sum += tensor(i, k, j, l);\n        }\n      }\n      VERIFY_IS_APPROX(result(i, j), 1.0f - sum);\n    }\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_full_reductions() {\n  Tensor<float, 2, DataLayout> tensor(2, 3);\n  tensor.setRandom();\n  array<ptrdiff_t, 2> reduction_axis;\n  reduction_axis[0] = 0;\n  reduction_axis[1] = 1;\n\n  Tensor<float, 0, DataLayout> result = tensor.sum(reduction_axis);\n  VERIFY_IS_EQUAL(result.rank(), 0);\n\n  float sum = 0.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      sum += tensor(i, j);\n    }\n  }\n  VERIFY_IS_APPROX(result(0), sum);\n\n  result = tensor.square().sum(reduction_axis).sqrt();\n  VERIFY_IS_EQUAL(result.rank(), 0);\n\n  sum = 0.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      sum += tensor(i, j) * tensor(i, j);\n    }\n  }\n  VERIFY_IS_APPROX(result(), sqrtf(sum));\n}\n\nstruct UserReducer {\n  static const bool PacketAccess = false;\n  UserReducer(float offset) : offset_(offset) {}\n  void reduce(const float val, float* accum) { *accum += val * val; }\n  float initialize() const { return 0; }\n  float finalize(const float accum) const { return 1.0f / (accum + offset_); }\n\n private:\n  const float offset_;\n};\n\ntemplate <int DataLayout>\nstatic void test_user_defined_reductions() {\n  Tensor<float, 2, DataLayout> tensor(5, 7);\n  tensor.setRandom();\n  array<ptrdiff_t, 1> reduction_axis;\n  reduction_axis[0] = 1;\n\n  UserReducer reducer(10.0f);\n  Tensor<float, 1, DataLayout> result = tensor.reduce(reduction_axis, reducer);\n  VERIFY_IS_EQUAL(result.dimension(0), 5);\n  for (int i = 0; i < 5; ++i) {\n    float expected = 10.0f;\n    for (int j = 0; j < 7; ++j) {\n      expected += tensor(i, j) * tensor(i, j);\n    }\n    expected = 1.0f / expected;\n    VERIFY_IS_APPROX(result(i), expected);\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_tensor_maps() {\n  int inputs[2 * 3 * 5 * 7];\n  TensorMap<Tensor<int, 4, DataLayout> > tensor_map(inputs, 2, 3, 5, 7);\n  TensorMap<Tensor<const int, 4, DataLayout> > tensor_map_const(inputs, 2, 3, 5,\n                                                                7);\n  const TensorMap<Tensor<const int, 4, DataLayout> > tensor_map_const_const(\n      inputs, 2, 3, 5, 7);\n\n  tensor_map.setRandom();\n  array<ptrdiff_t, 2> reduction_axis;\n  reduction_axis[0] = 1;\n  reduction_axis[1] = 3;\n\n  Tensor<int, 2, DataLayout> result = tensor_map.sum(reduction_axis);\n  Tensor<int, 2, DataLayout> result2 = tensor_map_const.sum(reduction_axis);\n  Tensor<int, 2, DataLayout> result3 =\n      tensor_map_const_const.sum(reduction_axis);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      int sum = 0;\n      for (int k = 0; k < 3; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          sum += tensor_map(i, k, j, l);\n        }\n      }\n      VERIFY_IS_EQUAL(result(i, j), sum);\n      VERIFY_IS_EQUAL(result2(i, j), sum);\n      VERIFY_IS_EQUAL(result3(i, j), sum);\n    }\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_static_dims() {\n  Tensor<float, 4, DataLayout> in(72, 53, 97, 113);\n  Tensor<float, 2, DataLayout> out(72, 97);\n  in.setRandom();\n\n#if !EIGEN_HAS_CONSTEXPR\n  array<int, 2> reduction_axis;\n  reduction_axis[0] = 1;\n  reduction_axis[1] = 3;\n#else\n  Eigen::IndexList<Eigen::type2index<1>, Eigen::type2index<3> > reduction_axis;\n#endif\n\n  out = in.maximum(reduction_axis);\n\n  for (int i = 0; i < 72; ++i) {\n    for (int j = 0; j < 97; ++j) {\n      float expected = -1e10f;\n      for (int k = 0; k < 53; ++k) {\n        for (int l = 0; l < 113; ++l) {\n          expected = (std::max)(expected, in(i, k, j, l));\n        }\n      }\n      VERIFY_IS_EQUAL(out(i, j), expected);\n    }\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_innermost_last_dims() {\n  Tensor<float, 4, DataLayout> in(72, 53, 97, 113);\n  Tensor<float, 2, DataLayout> out(97, 113);\n  in.setRandom();\n\n// Reduce on the innermost dimensions.\n#if !EIGEN_HAS_CONSTEXPR\n  array<int, 2> reduction_axis;\n  reduction_axis[0] = 0;\n  reduction_axis[1] = 1;\n#else\n  // This triggers the use of packets for ColMajor.\n  Eigen::IndexList<Eigen::type2index<0>, Eigen::type2index<1> > reduction_axis;\n#endif\n\n  out = in.maximum(reduction_axis);\n\n  for (int i = 0; i < 97; ++i) {\n    for (int j = 0; j < 113; ++j) {\n      float expected = -1e10f;\n      for (int k = 0; k < 53; ++k) {\n        for (int l = 0; l < 72; ++l) {\n          expected = (std::max)(expected, in(l, k, i, j));\n        }\n      }\n      VERIFY_IS_EQUAL(out(i, j), expected);\n    }\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_innermost_first_dims() {\n  Tensor<float, 4, DataLayout> in(72, 53, 97, 113);\n  Tensor<float, 2, DataLayout> out(72, 53);\n  in.setRandom();\n\n// Reduce on the innermost dimensions.\n#if !EIGEN_HAS_CONSTEXPR\n  array<int, 2> reduction_axis;\n  reduction_axis[0] = 2;\n  reduction_axis[1] = 3;\n#else\n  // This triggers the use of packets for RowMajor.\n  Eigen::IndexList<Eigen::type2index<2>, Eigen::type2index<3>> reduction_axis;\n#endif\n\n  out = in.maximum(reduction_axis);\n\n  for (int i = 0; i < 72; ++i) {\n    for (int j = 0; j < 53; ++j) {\n      float expected = -1e10f;\n      for (int k = 0; k < 97; ++k) {\n        for (int l = 0; l < 113; ++l) {\n          expected = (std::max)(expected, in(i, j, k, l));\n        }\n      }\n      VERIFY_IS_EQUAL(out(i, j), expected);\n    }\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_reduce_middle_dims() {\n  Tensor<float, 4, DataLayout> in(72, 53, 97, 113);\n  Tensor<float, 2, DataLayout> out(72, 53);\n  in.setRandom();\n\n// Reduce on the innermost dimensions.\n#if !EIGEN_HAS_CONSTEXPR\n  array<int, 2> reduction_axis;\n  reduction_axis[0] = 1;\n  reduction_axis[1] = 2;\n#else\n  // This triggers the use of packets for RowMajor.\n  Eigen::IndexList<Eigen::type2index<1>, Eigen::type2index<2>> reduction_axis;\n#endif\n\n  out = in.maximum(reduction_axis);\n\n  for (int i = 0; i < 72; ++i) {\n    for (int j = 0; j < 113; ++j) {\n      float expected = -1e10f;\n      for (int k = 0; k < 53; ++k) {\n        for (int l = 0; l < 97; ++l) {\n          expected = (std::max)(expected, in(i, k, l, j));\n        }\n      }\n      VERIFY_IS_EQUAL(out(i, j), expected);\n    }\n  }\n}\n\nstatic void test_sum_accuracy() {\n  Tensor<float, 3> tensor(101, 101, 101);\n  for (float prescribed_mean : {1.0f, 10.0f, 100.0f, 1000.0f, 10000.0f}) {\n    tensor.setRandom();\n    tensor += tensor.constant(prescribed_mean);\n\n    Tensor<float, 0> sum = tensor.sum();\n    double expected_sum = 0.0;\n    for (int i = 0; i < 101; ++i) {\n      for (int j = 0; j < 101; ++j) {\n        for (int k = 0; k < 101; ++k) {\n          expected_sum += static_cast<double>(tensor(i, j, k));\n        }\n      }\n    }\n    VERIFY_IS_APPROX(sum(), static_cast<float>(expected_sum));\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_reduction) {\n  CALL_SUBTEST(test_trivial_reductions<ColMajor>());\n  CALL_SUBTEST(test_trivial_reductions<RowMajor>());\n  CALL_SUBTEST(( test_simple_reductions<float,ColMajor>() ));\n  CALL_SUBTEST(( test_simple_reductions<float,RowMajor>() ));\n  CALL_SUBTEST(( test_simple_reductions<Eigen::half,ColMajor>() ));\n  CALL_SUBTEST(( test_simple_reductions<Eigen::bfloat16,ColMajor>() ));\n  CALL_SUBTEST(test_reductions_in_expr<ColMajor>());\n  CALL_SUBTEST(test_reductions_in_expr<RowMajor>());\n  CALL_SUBTEST(test_full_reductions<ColMajor>());\n  CALL_SUBTEST(test_full_reductions<RowMajor>());\n  CALL_SUBTEST(test_user_defined_reductions<ColMajor>());\n  CALL_SUBTEST(test_user_defined_reductions<RowMajor>());\n  CALL_SUBTEST(test_tensor_maps<ColMajor>());\n  CALL_SUBTEST(test_tensor_maps<RowMajor>());\n  CALL_SUBTEST(test_static_dims<ColMajor>());\n  CALL_SUBTEST(test_static_dims<RowMajor>());\n  CALL_SUBTEST(test_innermost_last_dims<ColMajor>());\n  CALL_SUBTEST(test_innermost_last_dims<RowMajor>());\n  CALL_SUBTEST(test_innermost_first_dims<ColMajor>());\n  CALL_SUBTEST(test_innermost_first_dims<RowMajor>());\n  CALL_SUBTEST(test_reduce_middle_dims<ColMajor>());\n  CALL_SUBTEST(test_reduce_middle_dims<RowMajor>());\n  CALL_SUBTEST(test_sum_accuracy());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_reduction_gpu.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\n\ntemplate<typename Type, int DataLayout>\nstatic void test_full_reductions() {\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  const int num_rows = internal::random<int>(1024, 5*1024);\n  const int num_cols = internal::random<int>(1024, 5*1024);\n\n  Tensor<Type, 2, DataLayout> in(num_rows, num_cols);\n  in.setRandom();\n\n  Tensor<Type, 0, DataLayout> full_redux;\n  full_redux = in.sum();\n\n  std::size_t in_bytes = in.size() * sizeof(Type);\n  std::size_t out_bytes = full_redux.size() * sizeof(Type);\n  Type* gpu_in_ptr = static_cast<Type*>(gpu_device.allocate(in_bytes));\n  Type* gpu_out_ptr = static_cast<Type*>(gpu_device.allocate(out_bytes));\n  gpu_device.memcpyHostToDevice(gpu_in_ptr, in.data(), in_bytes);\n\n  TensorMap<Tensor<Type, 2, DataLayout> > in_gpu(gpu_in_ptr, num_rows, num_cols);\n  TensorMap<Tensor<Type, 0, DataLayout> > out_gpu(gpu_out_ptr);\n\n  out_gpu.device(gpu_device) = in_gpu.sum();\n\n  Tensor<Type, 0, DataLayout> full_redux_gpu;\n  gpu_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_ptr, out_bytes);\n  gpu_device.synchronize();\n\n  // Check that the CPU and GPU reductions return the same result.\n  VERIFY_IS_APPROX(full_redux(), full_redux_gpu());\n\n  gpu_device.deallocate(gpu_in_ptr);\n  gpu_device.deallocate(gpu_out_ptr);\n}\n\ntemplate<typename Type, int DataLayout>\nstatic void test_first_dim_reductions() {\n  int dim_x = 33;\n  int dim_y = 1;\n  int dim_z = 128;\n\n  Tensor<Type, 3, DataLayout> in(dim_x, dim_y, dim_z);\n  in.setRandom();\n\n  Eigen::array<int, 1> red_axis;\n  red_axis[0] = 0;\n  Tensor<Type, 2, DataLayout> redux = in.sum(red_axis);\n\n  // Create device\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice dev(&stream);\n  \n  // Create data(T)\n  Type* in_data = (Type*)dev.allocate(dim_x*dim_y*dim_z*sizeof(Type));\n  Type* out_data = (Type*)dev.allocate(dim_z*dim_y*sizeof(Type));\n  Eigen::TensorMap<Eigen::Tensor<Type, 3, DataLayout> > gpu_in(in_data, dim_x, dim_y, dim_z);\n  Eigen::TensorMap<Eigen::Tensor<Type, 2, DataLayout> > gpu_out(out_data, dim_y, dim_z);\n  \n  // Perform operation\n  dev.memcpyHostToDevice(in_data, in.data(), in.size()*sizeof(Type));\n  gpu_out.device(dev) = gpu_in.sum(red_axis);\n  gpu_out.device(dev) += gpu_in.sum(red_axis);\n  Tensor<Type, 2, DataLayout> redux_gpu(dim_y, dim_z);\n  dev.memcpyDeviceToHost(redux_gpu.data(), out_data, gpu_out.size()*sizeof(Type));\n  dev.synchronize();\n\n  // Check that the CPU and GPU reductions return the same result.\n  for (int i = 0; i < gpu_out.size(); ++i) {\n    VERIFY_IS_APPROX(2*redux(i), redux_gpu(i));\n  }\n\n  dev.deallocate(in_data);\n  dev.deallocate(out_data);\n}\n\ntemplate<typename Type, int DataLayout>\nstatic void test_last_dim_reductions() {\n  int dim_x = 128;\n  int dim_y = 1;\n  int dim_z = 33;\n\n  Tensor<Type, 3, DataLayout> in(dim_x, dim_y, dim_z);\n  in.setRandom();\n\n  Eigen::array<int, 1> red_axis;\n  red_axis[0] = 2;\n  Tensor<Type, 2, DataLayout> redux = in.sum(red_axis);\n\n  // Create device\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice dev(&stream);\n  \n  // Create data\n  Type* in_data = (Type*)dev.allocate(dim_x*dim_y*dim_z*sizeof(Type));\n  Type* out_data = (Type*)dev.allocate(dim_x*dim_y*sizeof(Type));\n  Eigen::TensorMap<Eigen::Tensor<Type, 3, DataLayout> > gpu_in(in_data, dim_x, dim_y, dim_z);\n  Eigen::TensorMap<Eigen::Tensor<Type, 2, DataLayout> > gpu_out(out_data, dim_x, dim_y);\n  \n  // Perform operation\n  dev.memcpyHostToDevice(in_data, in.data(), in.size()*sizeof(Type));\n  gpu_out.device(dev) = gpu_in.sum(red_axis);\n  gpu_out.device(dev) += gpu_in.sum(red_axis);\n  Tensor<Type, 2, DataLayout> redux_gpu(dim_x, dim_y);\n  dev.memcpyDeviceToHost(redux_gpu.data(), out_data, gpu_out.size()*sizeof(Type));\n  dev.synchronize();\n\n  // Check that the CPU and GPU reductions return the same result.\n  for (int i = 0; i < gpu_out.size(); ++i) {\n    VERIFY_IS_APPROX(2*redux(i), redux_gpu(i));\n  }\n\n  dev.deallocate(in_data);\n  dev.deallocate(out_data);\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_reduction_gpu) {\n  CALL_SUBTEST_1((test_full_reductions<float, ColMajor>()));\n  CALL_SUBTEST_1((test_full_reductions<double, ColMajor>()));\n  CALL_SUBTEST_2((test_full_reductions<float, RowMajor>()));\n  CALL_SUBTEST_2((test_full_reductions<double, RowMajor>()));\n  \n  CALL_SUBTEST_3((test_first_dim_reductions<float, ColMajor>()));\n  CALL_SUBTEST_3((test_first_dim_reductions<double, ColMajor>()));\n  CALL_SUBTEST_4((test_first_dim_reductions<float, RowMajor>()));\n// Outer reductions of doubles aren't supported just yet.  \t\t\t\t\t      \n//  CALL_SUBTEST_4((test_first_dim_reductions<double, RowMajor>()))\n\n  CALL_SUBTEST_5((test_last_dim_reductions<float, ColMajor>()));\n// Outer reductions of doubles aren't supported just yet.  \t\t\t\t\t      \n//  CALL_SUBTEST_5((test_last_dim_reductions<double, ColMajor>()));\n  CALL_SUBTEST_6((test_last_dim_reductions<float, RowMajor>()));\n  CALL_SUBTEST_6((test_last_dim_reductions<double, RowMajor>()));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_reduction_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n#define EIGEN_HAS_CONSTEXPR 1\n\n#include \"main.h\"\n\n#include <unsupported/Eigen/CXX11/Tensor>\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_full_reductions_sum_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  const IndexType num_rows = 753;\n  const IndexType num_cols = 537;\n  array<IndexType, 2> tensorRange = {{num_rows, num_cols}};\n\n  array<IndexType, 2> outRange = {{1, 1}};\n\n  Tensor<DataType, 2, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> full_redux(outRange);\n  Tensor<DataType, 2, DataLayout, IndexType> full_redux_gpu(outRange);\n\n  in.setRandom();\n  auto dim = DSizes<IndexType, 2>(1, 1);\n  full_redux = in.sum().reshape(dim);\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = (DataType*)sycl_device.allocate(\n      sizeof(DataType) * (full_redux_gpu.dimensions().TotalSize()));\n\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> in_gpu(gpu_in_data,\n                                                               tensorRange);\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> out_gpu(gpu_out_data,\n                                                                outRange);\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in.data(), (in.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.sum().reshape(dim);\n  sycl_device.memcpyDeviceToHost(\n      full_redux_gpu.data(), gpu_out_data,\n      (full_redux_gpu.dimensions().TotalSize()) * sizeof(DataType));\n  // Check that the CPU and GPU reductions return the same result.\n  std::cout << \"SYCL FULL :\" << full_redux_gpu(0, 0)\n            << \", CPU FULL: \" << full_redux(0, 0) << \"\\n\";\n  VERIFY_IS_APPROX(full_redux_gpu(0, 0), full_redux(0, 0));\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_full_reductions_sum_with_offset_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  using data_tensor = Tensor<DataType, 2, DataLayout, IndexType>;\n  using scalar_tensor = Tensor<DataType, 0, DataLayout, IndexType>;\n  const IndexType num_rows = 64;\n  const IndexType num_cols = 64;\n  array<IndexType, 2> tensor_range = {{num_rows, num_cols}};\n  const IndexType n_elems = internal::array_prod(tensor_range);\n\n  data_tensor in(tensor_range);\n  scalar_tensor full_redux;\n  scalar_tensor full_redux_gpu;\n\n  in.setRandom();\n  array<IndexType, 2> tensor_offset_range(tensor_range);\n  tensor_offset_range[0] -= 1;\n\n  const IndexType offset = 64;\n  TensorMap<data_tensor> in_offset(in.data() + offset, tensor_offset_range);\n  full_redux = in_offset.sum();\n\n  DataType* gpu_in_data =\n      static_cast<DataType*>(sycl_device.allocate(n_elems * sizeof(DataType)));\n  DataType* gpu_out_data =\n      static_cast<DataType*>(sycl_device.allocate(sizeof(DataType)));\n\n  TensorMap<data_tensor> in_gpu(gpu_in_data + offset, tensor_offset_range);\n  TensorMap<scalar_tensor> out_gpu(gpu_out_data);\n  sycl_device.memcpyHostToDevice(gpu_in_data, in.data(),\n                                 n_elems * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.sum();\n  sycl_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_data,\n                                 sizeof(DataType));\n\n  // Check that the CPU and GPU reductions return the same result.\n  VERIFY_IS_APPROX(full_redux_gpu(), full_redux());\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_full_reductions_max_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  const IndexType num_rows = 4096;\n  const IndexType num_cols = 4096;\n  array<IndexType, 2> tensorRange = {{num_rows, num_cols}};\n\n  Tensor<DataType, 2, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 0, DataLayout, IndexType> full_redux;\n  Tensor<DataType, 0, DataLayout, IndexType> full_redux_gpu;\n\n  in.setRandom();\n\n  full_redux = in.maximum();\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = (DataType*)sycl_device.allocate(sizeof(DataType));\n\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> in_gpu(gpu_in_data,\n                                                               tensorRange);\n  TensorMap<Tensor<DataType, 0, DataLayout, IndexType>> out_gpu(gpu_out_data);\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in.data(), (in.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.maximum();\n  sycl_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_data,\n                                 sizeof(DataType));\n  VERIFY_IS_APPROX(full_redux_gpu(), full_redux());\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_full_reductions_max_with_offset_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  using data_tensor = Tensor<DataType, 2, DataLayout, IndexType>;\n  using scalar_tensor = Tensor<DataType, 0, DataLayout, IndexType>;\n  const IndexType num_rows = 64;\n  const IndexType num_cols = 64;\n  array<IndexType, 2> tensor_range = {{num_rows, num_cols}};\n  const IndexType n_elems = internal::array_prod(tensor_range);\n\n  data_tensor in(tensor_range);\n  scalar_tensor full_redux;\n  scalar_tensor full_redux_gpu;\n\n  in.setRandom();\n  array<IndexType, 2> tensor_offset_range(tensor_range);\n  tensor_offset_range[0] -= 1;\n  // Set the initial value to be the max.\n  // As we don't include this in the reduction the result should not be 2.\n  in(0) = static_cast<DataType>(2);\n\n  const IndexType offset = 64;\n  TensorMap<data_tensor> in_offset(in.data() + offset, tensor_offset_range);\n  full_redux = in_offset.maximum();\n  VERIFY_IS_NOT_EQUAL(full_redux(), in(0));\n\n  DataType* gpu_in_data =\n      static_cast<DataType*>(sycl_device.allocate(n_elems * sizeof(DataType)));\n  DataType* gpu_out_data =\n      static_cast<DataType*>(sycl_device.allocate(sizeof(DataType)));\n\n  TensorMap<data_tensor> in_gpu(gpu_in_data + offset, tensor_offset_range);\n  TensorMap<scalar_tensor> out_gpu(gpu_out_data);\n  sycl_device.memcpyHostToDevice(gpu_in_data, in.data(),\n                                 n_elems * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.maximum();\n  sycl_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_data,\n                                 sizeof(DataType));\n\n  // Check that the CPU and GPU reductions return the same result.\n  VERIFY_IS_APPROX(full_redux_gpu(), full_redux());\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_full_reductions_mean_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  const IndexType num_rows = 4096;\n  const IndexType num_cols = 4096;\n  array<IndexType, 2> tensorRange = {{num_rows, num_cols}};\n  array<IndexType, 1> argRange = {{num_cols}};\n  Eigen::array<IndexType, 1> red_axis;\n  red_axis[0] = 0;\n  //  red_axis[1]=1;\n  Tensor<DataType, 2, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> in_arg1(tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> in_arg2(tensorRange);\n  Tensor<bool, 1, DataLayout, IndexType> out_arg_cpu(argRange);\n  Tensor<bool, 1, DataLayout, IndexType> out_arg_gpu(argRange);\n  Tensor<bool, 1, DataLayout, IndexType> out_arg_gpu_helper(argRange);\n  Tensor<DataType, 0, DataLayout, IndexType> full_redux;\n  Tensor<DataType, 0, DataLayout, IndexType> full_redux_gpu;\n\n  in.setRandom();\n  in_arg1.setRandom();\n  in_arg2.setRandom();\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_in_arg1_data = static_cast<DataType*>(sycl_device.allocate(\n      in_arg1.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_in_arg2_data = static_cast<DataType*>(sycl_device.allocate(\n      in_arg2.dimensions().TotalSize() * sizeof(DataType)));\n  bool* gpu_out_arg__gpu_helper_data = static_cast<bool*>(sycl_device.allocate(\n      out_arg_gpu.dimensions().TotalSize() * sizeof(DataType)));\n  bool* gpu_out_arg_data = static_cast<bool*>(sycl_device.allocate(\n      out_arg_gpu.dimensions().TotalSize() * sizeof(DataType)));\n\n  DataType* gpu_out_data = (DataType*)sycl_device.allocate(sizeof(DataType));\n\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> in_gpu(gpu_in_data,\n                                                               tensorRange);\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> in_Arg1_gpu(\n      gpu_in_arg1_data, tensorRange);\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> in_Arg2_gpu(\n      gpu_in_arg2_data, tensorRange);\n  TensorMap<Tensor<bool, 1, DataLayout, IndexType>> out_Argout_gpu(\n      gpu_out_arg_data, argRange);\n  TensorMap<Tensor<bool, 1, DataLayout, IndexType>> out_Argout_gpu_helper(\n      gpu_out_arg__gpu_helper_data, argRange);\n  TensorMap<Tensor<DataType, 0, DataLayout, IndexType>> out_gpu(gpu_out_data);\n\n  // CPU VERSION\n  out_arg_cpu =\n      (in_arg1.argmax(1) == in_arg2.argmax(1))\n          .select(out_arg_cpu.constant(true), out_arg_cpu.constant(false));\n  full_redux = (out_arg_cpu.template cast<float>())\n                   .reduce(red_axis, Eigen::internal::MeanReducer<DataType>());\n\n  // GPU VERSION\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in.data(), (in.dimensions().TotalSize()) * sizeof(DataType));\n  sycl_device.memcpyHostToDevice(\n      gpu_in_arg1_data, in_arg1.data(),\n      (in_arg1.dimensions().TotalSize()) * sizeof(DataType));\n  sycl_device.memcpyHostToDevice(\n      gpu_in_arg2_data, in_arg2.data(),\n      (in_arg2.dimensions().TotalSize()) * sizeof(DataType));\n  out_Argout_gpu_helper.device(sycl_device) =\n      (in_Arg1_gpu.argmax(1) == in_Arg2_gpu.argmax(1));\n  out_Argout_gpu.device(sycl_device) =\n      (out_Argout_gpu_helper)\n          .select(out_Argout_gpu.constant(true),\n                  out_Argout_gpu.constant(false));\n  out_gpu.device(sycl_device) =\n      (out_Argout_gpu.template cast<float>())\n          .reduce(red_axis, Eigen::internal::MeanReducer<DataType>());\n  sycl_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_data,\n                                 sizeof(DataType));\n  // Check that the CPU and GPU reductions return the same result.\n  std::cout << \"SYCL : \" << full_redux_gpu() << \" , CPU : \" << full_redux()\n            << '\\n';\n  VERIFY_IS_EQUAL(full_redux_gpu(), full_redux());\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_in_arg1_data);\n  sycl_device.deallocate(gpu_in_arg2_data);\n  sycl_device.deallocate(gpu_out_arg__gpu_helper_data);\n  sycl_device.deallocate(gpu_out_arg_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_full_reductions_mean_with_offset_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  using data_tensor = Tensor<DataType, 2, DataLayout, IndexType>;\n  using scalar_tensor = Tensor<DataType, 0, DataLayout, IndexType>;\n  const IndexType num_rows = 64;\n  const IndexType num_cols = 64;\n  array<IndexType, 2> tensor_range = {{num_rows, num_cols}};\n  const IndexType n_elems = internal::array_prod(tensor_range);\n\n  data_tensor in(tensor_range);\n  scalar_tensor full_redux;\n  scalar_tensor full_redux_gpu;\n\n  in.setRandom();\n  array<IndexType, 2> tensor_offset_range(tensor_range);\n  tensor_offset_range[0] -= 1;\n\n  const IndexType offset = 64;\n  TensorMap<data_tensor> in_offset(in.data() + offset, tensor_offset_range);\n  full_redux = in_offset.mean();\n  VERIFY_IS_NOT_EQUAL(full_redux(), in(0));\n\n  DataType* gpu_in_data =\n      static_cast<DataType*>(sycl_device.allocate(n_elems * sizeof(DataType)));\n  DataType* gpu_out_data =\n      static_cast<DataType*>(sycl_device.allocate(sizeof(DataType)));\n\n  TensorMap<data_tensor> in_gpu(gpu_in_data + offset, tensor_offset_range);\n  TensorMap<scalar_tensor> out_gpu(gpu_out_data);\n  sycl_device.memcpyHostToDevice(gpu_in_data, in.data(),\n                                 n_elems * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.mean();\n  sycl_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_data,\n                                 sizeof(DataType));\n\n  // Check that the CPU and GPU reductions return the same result.\n  VERIFY_IS_APPROX(full_redux_gpu(), full_redux());\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_full_reductions_mean_with_odd_offset_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  // This is a particular case which illustrates a possible problem when the\n  // number of local threads in a workgroup is even, but is not a power of two.\n  using data_tensor = Tensor<DataType, 1, DataLayout, IndexType>;\n  using scalar_tensor = Tensor<DataType, 0, DataLayout, IndexType>;\n  // 2177 = (17 * 128) + 1 gives rise to 18 local threads.\n  // 8708 = 4 * 2177 = 4 * (17 * 128) + 4 uses 18 vectorised local threads.\n  const IndexType n_elems = 8707;\n  array<IndexType, 1> tensor_range = {{n_elems}};\n\n  data_tensor in(tensor_range);\n  DataType full_redux;\n  DataType full_redux_gpu;\n  TensorMap<scalar_tensor> red_cpu(&full_redux);\n  TensorMap<scalar_tensor> red_gpu(&full_redux_gpu);\n\n  const DataType const_val = static_cast<DataType>(0.6391);\n  in = in.constant(const_val);\n\n  Eigen::IndexList<Eigen::type2index<0>> red_axis;\n  red_cpu = in.reduce(red_axis, Eigen::internal::MeanReducer<DataType>());\n  VERIFY_IS_APPROX(const_val, red_cpu());\n\n  DataType* gpu_in_data =\n      static_cast<DataType*>(sycl_device.allocate(n_elems * sizeof(DataType)));\n  DataType* gpu_out_data =\n      static_cast<DataType*>(sycl_device.allocate(sizeof(DataType)));\n\n  TensorMap<data_tensor> in_gpu(gpu_in_data, tensor_range);\n  TensorMap<scalar_tensor> out_gpu(gpu_out_data);\n  sycl_device.memcpyHostToDevice(gpu_in_data, in.data(),\n                                 n_elems * sizeof(DataType));\n  out_gpu.device(sycl_device) =\n      in_gpu.reduce(red_axis, Eigen::internal::MeanReducer<DataType>());\n  sycl_device.memcpyDeviceToHost(red_gpu.data(), gpu_out_data,\n                                 sizeof(DataType));\n\n  // Check that the CPU and GPU reductions return the same result.\n  VERIFY_IS_APPROX(full_redux_gpu, full_redux);\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_full_reductions_min_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  const IndexType num_rows = 876;\n  const IndexType num_cols = 953;\n  array<IndexType, 2> tensorRange = {{num_rows, num_cols}};\n\n  Tensor<DataType, 2, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 0, DataLayout, IndexType> full_redux;\n  Tensor<DataType, 0, DataLayout, IndexType> full_redux_gpu;\n\n  in.setRandom();\n\n  full_redux = in.minimum();\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = (DataType*)sycl_device.allocate(sizeof(DataType));\n\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> in_gpu(gpu_in_data,\n                                                               tensorRange);\n  TensorMap<Tensor<DataType, 0, DataLayout, IndexType>> out_gpu(gpu_out_data);\n\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in.data(), (in.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.minimum();\n  sycl_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_data,\n                                 sizeof(DataType));\n  // Check that the CPU and GPU reductions return the same result.\n  VERIFY_IS_APPROX(full_redux_gpu(), full_redux());\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_full_reductions_min_with_offset_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  using data_tensor = Tensor<DataType, 2, DataLayout, IndexType>;\n  using scalar_tensor = Tensor<DataType, 0, DataLayout, IndexType>;\n  const IndexType num_rows = 64;\n  const IndexType num_cols = 64;\n  array<IndexType, 2> tensor_range = {{num_rows, num_cols}};\n  const IndexType n_elems = internal::array_prod(tensor_range);\n\n  data_tensor in(tensor_range);\n  scalar_tensor full_redux;\n  scalar_tensor full_redux_gpu;\n\n  in.setRandom();\n  array<IndexType, 2> tensor_offset_range(tensor_range);\n  tensor_offset_range[0] -= 1;\n  // Set the initial value to be the min.\n  // As we don't include this in the reduction the result should not be -2.\n  in(0) = static_cast<DataType>(-2);\n\n  const IndexType offset = 64;\n  TensorMap<data_tensor> in_offset(in.data() + offset, tensor_offset_range);\n  full_redux = in_offset.minimum();\n  VERIFY_IS_NOT_EQUAL(full_redux(), in(0));\n\n  DataType* gpu_in_data =\n      static_cast<DataType*>(sycl_device.allocate(n_elems * sizeof(DataType)));\n  DataType* gpu_out_data =\n      static_cast<DataType*>(sycl_device.allocate(sizeof(DataType)));\n\n  TensorMap<data_tensor> in_gpu(gpu_in_data + offset, tensor_offset_range);\n  TensorMap<scalar_tensor> out_gpu(gpu_out_data);\n  sycl_device.memcpyHostToDevice(gpu_in_data, in.data(),\n                                 n_elems * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.minimum();\n  sycl_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_data,\n                                 sizeof(DataType));\n\n  // Check that the CPU and GPU reductions return the same result.\n  VERIFY_IS_APPROX(full_redux_gpu(), full_redux());\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_first_dim_reductions_max_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  IndexType dim_x = 145;\n  IndexType dim_y = 1;\n  IndexType dim_z = 67;\n\n  array<IndexType, 3> tensorRange = {{dim_x, dim_y, dim_z}};\n  Eigen::array<IndexType, 1> red_axis;\n  red_axis[0] = 0;\n  array<IndexType, 2> reduced_tensorRange = {{dim_y, dim_z}};\n\n  Tensor<DataType, 3, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> redux(reduced_tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> redux_gpu(reduced_tensorRange);\n\n  in.setRandom();\n\n  redux = in.maximum(red_axis);\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = static_cast<DataType*>(sycl_device.allocate(\n      redux_gpu.dimensions().TotalSize() * sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> in_gpu(gpu_in_data,\n                                                               tensorRange);\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> out_gpu(\n      gpu_out_data, reduced_tensorRange);\n\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in.data(), (in.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.maximum(red_axis);\n  sycl_device.memcpyDeviceToHost(\n      redux_gpu.data(), gpu_out_data,\n      redux_gpu.dimensions().TotalSize() * sizeof(DataType));\n\n  // Check that the CPU and GPU reductions return the same result.\n  for (IndexType j = 0; j < reduced_tensorRange[0]; j++)\n    for (IndexType k = 0; k < reduced_tensorRange[1]; k++)\n      VERIFY_IS_APPROX(redux_gpu(j, k), redux(j, k));\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_first_dim_reductions_max_with_offset_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  using data_tensor = Tensor<DataType, 2, DataLayout, IndexType>;\n  using reduced_tensor = Tensor<DataType, 1, DataLayout, IndexType>;\n\n  const IndexType num_rows = 64;\n  const IndexType num_cols = 64;\n  array<IndexType, 2> tensor_range = {{num_rows, num_cols}};\n  array<IndexType, 1> reduced_range = {{num_cols}};\n  const IndexType n_elems = internal::array_prod(tensor_range);\n  const IndexType n_reduced = num_cols;\n\n  data_tensor in(tensor_range);\n  reduced_tensor redux;\n  reduced_tensor redux_gpu(reduced_range);\n\n  in.setRandom();\n  array<IndexType, 2> tensor_offset_range(tensor_range);\n  tensor_offset_range[0] -= 1;\n  // Set maximum value outside of the considered range.\n  for (IndexType i = 0; i < n_reduced; i++) {\n    in(i) = static_cast<DataType>(2);\n  }\n\n  Eigen::array<IndexType, 1> red_axis;\n  red_axis[0] = 0;\n\n  const IndexType offset = 64;\n  TensorMap<data_tensor> in_offset(in.data() + offset, tensor_offset_range);\n  redux = in_offset.maximum(red_axis);\n  for (IndexType i = 0; i < n_reduced; i++) {\n    VERIFY_IS_NOT_EQUAL(redux(i), in(i));\n  }\n\n  DataType* gpu_in_data =\n      static_cast<DataType*>(sycl_device.allocate(n_elems * sizeof(DataType)));\n  DataType* gpu_out_data = static_cast<DataType*>(\n      sycl_device.allocate(n_reduced * sizeof(DataType)));\n\n  TensorMap<data_tensor> in_gpu(gpu_in_data + offset, tensor_offset_range);\n  TensorMap<reduced_tensor> out_gpu(gpu_out_data, reduced_range);\n  sycl_device.memcpyHostToDevice(gpu_in_data, in.data(),\n                                 n_elems * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.maximum(red_axis);\n  sycl_device.memcpyDeviceToHost(redux_gpu.data(), gpu_out_data,\n                                 n_reduced * sizeof(DataType));\n\n  // Check that the CPU and GPU reductions return the same result.\n  for (IndexType i = 0; i < n_reduced; i++) {\n    VERIFY_IS_APPROX(redux_gpu(i), redux(i));\n  }\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_last_dim_reductions_max_with_offset_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  using data_tensor = Tensor<DataType, 2, DataLayout, IndexType>;\n  using reduced_tensor = Tensor<DataType, 1, DataLayout, IndexType>;\n\n  const IndexType num_rows = 64;\n  const IndexType num_cols = 64;\n  array<IndexType, 2> tensor_range = {{num_rows, num_cols}};\n  array<IndexType, 1> full_reduced_range = {{num_rows}};\n  array<IndexType, 1> reduced_range = {{num_rows - 1}};\n  const IndexType n_elems = internal::array_prod(tensor_range);\n  const IndexType n_reduced = reduced_range[0];\n\n  data_tensor in(tensor_range);\n  reduced_tensor redux(full_reduced_range);\n  reduced_tensor redux_gpu(reduced_range);\n\n  in.setRandom();\n  redux.setZero();\n  array<IndexType, 2> tensor_offset_range(tensor_range);\n  tensor_offset_range[0] -= 1;\n  // Set maximum value outside of the considered range.\n  for (IndexType i = 0; i < n_reduced; i++) {\n    in(i) = static_cast<DataType>(2);\n  }\n\n  Eigen::array<IndexType, 1> red_axis;\n  red_axis[0] = 1;\n\n  const IndexType offset = 64;\n  // Introduce an offset in both the input and the output.\n  TensorMap<data_tensor> in_offset(in.data() + offset, tensor_offset_range);\n  TensorMap<reduced_tensor> red_offset(redux.data() + 1, reduced_range);\n  red_offset = in_offset.maximum(red_axis);\n\n  // Check that the first value hasn't been changed and that the reduced values\n  // are not equal to the previously set maximum in the input outside the range.\n  VERIFY_IS_EQUAL(redux(0), static_cast<DataType>(0));\n  for (IndexType i = 0; i < n_reduced; i++) {\n    VERIFY_IS_NOT_EQUAL(red_offset(i), in(i));\n  }\n\n  DataType* gpu_in_data =\n      static_cast<DataType*>(sycl_device.allocate(n_elems * sizeof(DataType)));\n  DataType* gpu_out_data = static_cast<DataType*>(\n      sycl_device.allocate((n_reduced + 1) * sizeof(DataType)));\n\n  TensorMap<data_tensor> in_gpu(gpu_in_data + offset, tensor_offset_range);\n  TensorMap<reduced_tensor> out_gpu(gpu_out_data + 1, reduced_range);\n  sycl_device.memcpyHostToDevice(gpu_in_data, in.data(),\n                                 n_elems * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.maximum(red_axis);\n  sycl_device.memcpyDeviceToHost(redux_gpu.data(), out_gpu.data(),\n                                 n_reduced * sizeof(DataType));\n\n  // Check that the CPU and GPU reductions return the same result.\n  for (IndexType i = 0; i < n_reduced; i++) {\n    VERIFY_IS_APPROX(redux_gpu(i), red_offset(i));\n  }\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_first_dim_reductions_sum_sycl(\n    const Eigen::SyclDevice& sycl_device, IndexType dim_x, IndexType dim_y) {\n  array<IndexType, 2> tensorRange = {{dim_x, dim_y}};\n  Eigen::array<IndexType, 1> red_axis;\n  red_axis[0] = 0;\n  array<IndexType, 1> reduced_tensorRange = {{dim_y}};\n\n  Tensor<DataType, 2, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 1, DataLayout, IndexType> redux(reduced_tensorRange);\n  Tensor<DataType, 1, DataLayout, IndexType> redux_gpu(reduced_tensorRange);\n\n  in.setRandom();\n  redux = in.sum(red_axis);\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = static_cast<DataType*>(sycl_device.allocate(\n      redux_gpu.dimensions().TotalSize() * sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> in_gpu(gpu_in_data,\n                                                               tensorRange);\n  TensorMap<Tensor<DataType, 1, DataLayout, IndexType>> out_gpu(\n      gpu_out_data, reduced_tensorRange);\n\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in.data(), (in.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.sum(red_axis);\n  sycl_device.memcpyDeviceToHost(\n      redux_gpu.data(), gpu_out_data,\n      redux_gpu.dimensions().TotalSize() * sizeof(DataType));\n\n  // Check that the CPU and GPU reductions return the same result.\n  for (IndexType i = 0; i < redux.size(); i++) {\n    VERIFY_IS_APPROX(redux_gpu.data()[i], redux.data()[i]);\n  }\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_first_dim_reductions_mean_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  IndexType dim_x = 145;\n  IndexType dim_y = 1;\n  IndexType dim_z = 67;\n\n  array<IndexType, 3> tensorRange = {{dim_x, dim_y, dim_z}};\n  Eigen::array<IndexType, 1> red_axis;\n  red_axis[0] = 0;\n  array<IndexType, 2> reduced_tensorRange = {{dim_y, dim_z}};\n\n  Tensor<DataType, 3, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> redux(reduced_tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> redux_gpu(reduced_tensorRange);\n\n  in.setRandom();\n\n  redux = in.mean(red_axis);\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = static_cast<DataType*>(sycl_device.allocate(\n      redux_gpu.dimensions().TotalSize() * sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> in_gpu(gpu_in_data,\n                                                               tensorRange);\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> out_gpu(\n      gpu_out_data, reduced_tensorRange);\n\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in.data(), (in.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.mean(red_axis);\n  sycl_device.memcpyDeviceToHost(\n      redux_gpu.data(), gpu_out_data,\n      redux_gpu.dimensions().TotalSize() * sizeof(DataType));\n\n  // Check that the CPU and GPU reductions return the same result.\n  for (IndexType j = 0; j < reduced_tensorRange[0]; j++)\n    for (IndexType k = 0; k < reduced_tensorRange[1]; k++)\n      VERIFY_IS_APPROX(redux_gpu(j, k), redux(j, k));\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_last_dim_reductions_mean_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  IndexType dim_x = 64;\n  IndexType dim_y = 1;\n  IndexType dim_z = 32;\n\n  array<IndexType, 3> tensorRange = {{dim_x, dim_y, dim_z}};\n  Eigen::array<IndexType, 1> red_axis;\n  red_axis[0] = 2;\n  array<IndexType, 2> reduced_tensorRange = {{dim_x, dim_y}};\n\n  Tensor<DataType, 3, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> redux(reduced_tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> redux_gpu(reduced_tensorRange);\n\n  in.setRandom();\n\n  redux = in.mean(red_axis);\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = static_cast<DataType*>(sycl_device.allocate(\n      redux_gpu.dimensions().TotalSize() * sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> in_gpu(gpu_in_data,\n                                                               tensorRange);\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> out_gpu(\n      gpu_out_data, reduced_tensorRange);\n\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in.data(), (in.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.mean(red_axis);\n  sycl_device.memcpyDeviceToHost(\n      redux_gpu.data(), gpu_out_data,\n      redux_gpu.dimensions().TotalSize() * sizeof(DataType));\n  // Check that the CPU and GPU reductions return the same result.\n  for (IndexType j = 0; j < reduced_tensorRange[0]; j++)\n    for (IndexType k = 0; k < reduced_tensorRange[1]; k++)\n      VERIFY_IS_APPROX(redux_gpu(j, k), redux(j, k));\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_last_dim_reductions_sum_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  IndexType dim_x = 64;\n  IndexType dim_y = 1;\n  IndexType dim_z = 32;\n\n  array<IndexType, 3> tensorRange = {{dim_x, dim_y, dim_z}};\n  Eigen::array<IndexType, 1> red_axis;\n  red_axis[0] = 2;\n  array<IndexType, 2> reduced_tensorRange = {{dim_x, dim_y}};\n\n  Tensor<DataType, 3, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> redux(reduced_tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> redux_gpu(reduced_tensorRange);\n\n  in.setRandom();\n\n  redux = in.sum(red_axis);\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = static_cast<DataType*>(sycl_device.allocate(\n      redux_gpu.dimensions().TotalSize() * sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> in_gpu(gpu_in_data,\n                                                               tensorRange);\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> out_gpu(\n      gpu_out_data, reduced_tensorRange);\n\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in.data(), (in.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.sum(red_axis);\n  sycl_device.memcpyDeviceToHost(\n      redux_gpu.data(), gpu_out_data,\n      redux_gpu.dimensions().TotalSize() * sizeof(DataType));\n  // Check that the CPU and GPU reductions return the same result.\n  for (IndexType j = 0; j < reduced_tensorRange[0]; j++)\n    for (IndexType k = 0; k < reduced_tensorRange[1]; k++)\n      VERIFY_IS_APPROX(redux_gpu(j, k), redux(j, k));\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_last_reductions_sum_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  auto tensorRange = Sizes<64, 32>(64, 32);\n  // auto red_axis =  Sizes<0,1>(0,1);\n  Eigen::IndexList<Eigen::type2index<1>> red_axis;\n  auto reduced_tensorRange = Sizes<64>(64);\n  TensorFixedSize<DataType, Sizes<64, 32>, DataLayout> in_fix;\n  TensorFixedSize<DataType, Sizes<64>, DataLayout> redux_fix;\n  TensorFixedSize<DataType, Sizes<64>, DataLayout> redux_gpu_fix;\n\n  in_fix.setRandom();\n\n  redux_fix = in_fix.sum(red_axis);\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in_fix.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = static_cast<DataType*>(sycl_device.allocate(\n      redux_gpu_fix.dimensions().TotalSize() * sizeof(DataType)));\n\n  TensorMap<TensorFixedSize<DataType, Sizes<64, 32>, DataLayout>> in_gpu_fix(\n      gpu_in_data, tensorRange);\n  TensorMap<TensorFixedSize<DataType, Sizes<64>, DataLayout>> out_gpu_fix(\n      gpu_out_data, reduced_tensorRange);\n\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in_fix.data(),\n      (in_fix.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu_fix.device(sycl_device) = in_gpu_fix.sum(red_axis);\n  sycl_device.memcpyDeviceToHost(\n      redux_gpu_fix.data(), gpu_out_data,\n      redux_gpu_fix.dimensions().TotalSize() * sizeof(DataType));\n  // Check that the CPU and GPU reductions return the same result.\n  for (IndexType j = 0; j < reduced_tensorRange[0]; j++) {\n    VERIFY_IS_APPROX(redux_gpu_fix(j), redux_fix(j));\n  }\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_last_reductions_mean_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  auto tensorRange = Sizes<64, 32>(64, 32);\n  Eigen::IndexList<Eigen::type2index<1>> red_axis;\n  auto reduced_tensorRange = Sizes<64>(64);\n  TensorFixedSize<DataType, Sizes<64, 32>, DataLayout> in_fix;\n  TensorFixedSize<DataType, Sizes<64>, DataLayout> redux_fix;\n  TensorFixedSize<DataType, Sizes<64>, DataLayout> redux_gpu_fix;\n\n  in_fix.setRandom();\n  redux_fix = in_fix.mean(red_axis);\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in_fix.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = static_cast<DataType*>(sycl_device.allocate(\n      redux_gpu_fix.dimensions().TotalSize() * sizeof(DataType)));\n\n  TensorMap<TensorFixedSize<DataType, Sizes<64, 32>, DataLayout>> in_gpu_fix(\n      gpu_in_data, tensorRange);\n  TensorMap<TensorFixedSize<DataType, Sizes<64>, DataLayout>> out_gpu_fix(\n      gpu_out_data, reduced_tensorRange);\n\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in_fix.data(),\n      (in_fix.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu_fix.device(sycl_device) = in_gpu_fix.mean(red_axis);\n  sycl_device.memcpyDeviceToHost(\n      redux_gpu_fix.data(), gpu_out_data,\n      redux_gpu_fix.dimensions().TotalSize() * sizeof(DataType));\n  sycl_device.synchronize();\n  // Check that the CPU and GPU reductions return the same result.\n  for (IndexType j = 0; j < reduced_tensorRange[0]; j++) {\n    VERIFY_IS_APPROX(redux_gpu_fix(j), redux_fix(j));\n  }\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\n// SYCL supports a generic case of reduction where the accumulator is a\n// different type than the input data This is an example on how to get if a\n// Tensor contains nan and/or inf in one reduction\ntemplate <typename InT, typename OutT>\nstruct CustomReducer {\n  static const bool PacketAccess = false;\n  static const bool IsStateful = false;\n\n  static constexpr OutT InfBit = 1;\n  static constexpr OutT NanBit = 2;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const InT x,\n                                                    OutT* accum) const {\n    if (Eigen::numext::isinf(x))\n      *accum |= InfBit;\n    else if (Eigen::numext::isnan(x))\n      *accum |= NanBit;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const OutT x,\n                                                    OutT* accum) const {\n    *accum |= x;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE OutT initialize() const {\n    return OutT(0);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE OutT finalize(const OutT accum) const {\n    return accum;\n  }\n};\n\ntemplate <typename DataType, typename AccumType, int DataLayout,\n          typename IndexType>\nstatic void test_full_reductions_custom_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  constexpr IndexType InSize = 64;\n  auto tensorRange = Sizes<InSize>(InSize);\n  Eigen::IndexList<Eigen::type2index<0>> dims;\n  auto reduced_tensorRange = Sizes<>();\n  TensorFixedSize<DataType, Sizes<InSize>, DataLayout> in_fix;\n  TensorFixedSize<AccumType, Sizes<>, DataLayout> redux_gpu_fix;\n\n  CustomReducer<DataType, AccumType> reducer;\n\n  in_fix.setRandom();\n\n  size_t in_size_bytes = in_fix.dimensions().TotalSize() * sizeof(DataType);\n  DataType* gpu_in_data =\n      static_cast<DataType*>(sycl_device.allocate(in_size_bytes));\n  AccumType* gpu_out_data =\n      static_cast<AccumType*>(sycl_device.allocate(sizeof(AccumType)));\n\n  TensorMap<TensorFixedSize<DataType, Sizes<InSize>, DataLayout>> in_gpu_fix(\n      gpu_in_data, tensorRange);\n  TensorMap<TensorFixedSize<AccumType, Sizes<>, DataLayout>> out_gpu_fix(\n      gpu_out_data, reduced_tensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_in_data, in_fix.data(), in_size_bytes);\n  out_gpu_fix.device(sycl_device) = in_gpu_fix.reduce(dims, reducer);\n  sycl_device.memcpyDeviceToHost(redux_gpu_fix.data(), gpu_out_data,\n                                 sizeof(AccumType));\n  VERIFY_IS_EQUAL(redux_gpu_fix(0), AccumType(0));\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, typename Dev>\nvoid sycl_reduction_test_full_per_device(const Dev& sycl_device) {\n  test_full_reductions_sum_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_full_reductions_sum_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_full_reductions_min_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_full_reductions_min_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_full_reductions_max_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_full_reductions_max_sycl<DataType, RowMajor, int64_t>(sycl_device);\n\n  test_full_reductions_mean_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_full_reductions_mean_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_full_reductions_custom_sycl<DataType, int, RowMajor, int64_t>(\n      sycl_device);\n  test_full_reductions_custom_sycl<DataType, int, ColMajor, int64_t>(\n      sycl_device);\n  sycl_device.synchronize();\n}\n\ntemplate <typename DataType, typename Dev>\nvoid sycl_reduction_full_offset_per_device(const Dev& sycl_device) {\n  test_full_reductions_sum_with_offset_sycl<DataType, RowMajor, int64_t>(\n      sycl_device);\n  test_full_reductions_sum_with_offset_sycl<DataType, ColMajor, int64_t>(\n      sycl_device);\n  test_full_reductions_min_with_offset_sycl<DataType, RowMajor, int64_t>(\n      sycl_device);\n  test_full_reductions_min_with_offset_sycl<DataType, ColMajor, int64_t>(\n      sycl_device);\n  test_full_reductions_max_with_offset_sycl<DataType, ColMajor, int64_t>(\n      sycl_device);\n  test_full_reductions_max_with_offset_sycl<DataType, RowMajor, int64_t>(\n      sycl_device);\n  test_full_reductions_mean_with_offset_sycl<DataType, RowMajor, int64_t>(\n      sycl_device);\n  test_full_reductions_mean_with_offset_sycl<DataType, ColMajor, int64_t>(\n      sycl_device);\n  test_full_reductions_mean_with_odd_offset_sycl<DataType, RowMajor, int64_t>(\n      sycl_device);\n  sycl_device.synchronize();\n}\n\ntemplate <typename DataType, typename Dev>\nvoid sycl_reduction_test_first_dim_per_device(const Dev& sycl_device) {\n  test_first_dim_reductions_sum_sycl<DataType, ColMajor, int64_t>(sycl_device,\n                                                                  4197, 4097);\n  test_first_dim_reductions_sum_sycl<DataType, RowMajor, int64_t>(sycl_device,\n                                                                  4197, 4097);\n  test_first_dim_reductions_sum_sycl<DataType, RowMajor, int64_t>(sycl_device,\n                                                                  129, 8);\n  test_first_dim_reductions_max_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_first_dim_reductions_max_with_offset_sycl<DataType, RowMajor, int64_t>(\n      sycl_device);\n  sycl_device.synchronize();\n}\n\ntemplate <typename DataType, typename Dev>\nvoid sycl_reduction_test_last_dim_per_device(const Dev& sycl_device) {\n  test_last_dim_reductions_sum_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_last_dim_reductions_max_with_offset_sycl<DataType, RowMajor, int64_t>(\n      sycl_device);\n  test_last_reductions_sum_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_last_reductions_sum_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_last_reductions_mean_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_last_reductions_mean_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  sycl_device.synchronize();\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_reduction_sycl) {\n  for (const auto& device : Eigen::get_sycl_supported_devices()) {\n    std::cout << \"Running on \"\n              << device.template get_info<cl::sycl::info::device::name>()\n              << std::endl;\n    QueueInterface queueInterface(device);\n    auto sycl_device = Eigen::SyclDevice(&queueInterface);\n    CALL_SUBTEST_1(sycl_reduction_test_full_per_device<float>(sycl_device));\n    CALL_SUBTEST_2(sycl_reduction_full_offset_per_device<float>(sycl_device));\n    CALL_SUBTEST_3(\n        sycl_reduction_test_first_dim_per_device<float>(sycl_device));\n    CALL_SUBTEST_4(sycl_reduction_test_last_dim_per_device<float>(sycl_device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_ref.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\nstatic void test_simple_lvalue_ref()\n{\n  Tensor<int, 1> input(6);\n  input.setRandom();\n\n  TensorRef<Tensor<int, 1>> ref3(input);\n  TensorRef<Tensor<int, 1>> ref4 = input;\n\n  VERIFY_IS_EQUAL(ref3.data(), input.data());\n  VERIFY_IS_EQUAL(ref4.data(), input.data());\n\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_EQUAL(ref3(i), input(i));\n    VERIFY_IS_EQUAL(ref4(i), input(i));\n  }\n\n  for (int i = 0; i < 6; ++i) {\n    ref3.coeffRef(i) = i;\n  }\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_EQUAL(input(i), i);\n  }\n  for (int i = 0; i < 6; ++i) {\n    ref4.coeffRef(i) = -i * 2;\n  }\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_EQUAL(input(i), -i*2);\n  }\n}\n\n\nstatic void test_simple_rvalue_ref()\n{\n  Tensor<int, 1> input1(6);\n  input1.setRandom();\n  Tensor<int, 1> input2(6);\n  input2.setRandom();\n\n  TensorRef<Tensor<int, 1>> ref3(input1 + input2);\n  TensorRef<Tensor<int, 1>> ref4 = input1 + input2;\n\n  VERIFY_IS_NOT_EQUAL(ref3.data(), input1.data());\n  VERIFY_IS_NOT_EQUAL(ref4.data(), input1.data());\n  VERIFY_IS_NOT_EQUAL(ref3.data(), input2.data());\n  VERIFY_IS_NOT_EQUAL(ref4.data(), input2.data());\n\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_EQUAL(ref3(i), input1(i) + input2(i));\n    VERIFY_IS_EQUAL(ref4(i), input1(i) + input2(i));\n  }\n}\n\n\nstatic void test_multiple_dims()\n{\n  Tensor<float, 3> input(3,5,7);\n  input.setRandom();\n\n  TensorRef<Tensor<float, 3>> ref(input);\n  VERIFY_IS_EQUAL(ref.data(), input.data());\n  VERIFY_IS_EQUAL(ref.dimension(0), 3);\n  VERIFY_IS_EQUAL(ref.dimension(1), 5);\n  VERIFY_IS_EQUAL(ref.dimension(2), 7);\n\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(ref(i,j,k), input(i,j,k));\n      }\n    }\n  }\n}\n\n\nstatic void test_slice()\n{\n  Tensor<float, 5> tensor(2,3,5,7,11);\n  tensor.setRandom();\n\n  Eigen::DSizes<ptrdiff_t, 5> indices(1,2,3,4,5);\n  Eigen::DSizes<ptrdiff_t, 5> sizes(1,1,1,1,1);\n  TensorRef<Tensor<float, 5>> slice = tensor.slice(indices, sizes);\n  VERIFY_IS_EQUAL(slice(0,0,0,0,0), tensor(1,2,3,4,5));\n\n  Eigen::DSizes<ptrdiff_t, 5> indices2(1,1,3,4,5);\n  Eigen::DSizes<ptrdiff_t, 5> sizes2(1,1,2,2,3);\n  slice = tensor.slice(indices2, sizes2);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 2; ++j) {\n      for (int k = 0; k < 3; ++k) {\n        VERIFY_IS_EQUAL(slice(0,0,i,j,k), tensor(1,1,3+i,4+j,5+k));\n      }\n    }\n  }\n\n  Eigen::DSizes<ptrdiff_t, 5> indices3(0,0,0,0,0);\n  Eigen::DSizes<ptrdiff_t, 5> sizes3(2,3,1,1,1);\n  slice = tensor.slice(indices3, sizes3);\n  VERIFY_IS_EQUAL(slice.data(), tensor.data());\n}\n\n\nstatic void test_ref_of_ref()\n{\n  Tensor<float, 3> input(3,5,7);\n  input.setRandom();\n\n  TensorRef<Tensor<float, 3>> ref(input);\n  TensorRef<Tensor<float, 3>> ref_of_ref(ref);\n  TensorRef<Tensor<float, 3>> ref_of_ref2;\n  ref_of_ref2 = ref;\n\n  VERIFY_IS_EQUAL(ref_of_ref.data(), input.data());\n  VERIFY_IS_EQUAL(ref_of_ref.dimension(0), 3);\n  VERIFY_IS_EQUAL(ref_of_ref.dimension(1), 5);\n  VERIFY_IS_EQUAL(ref_of_ref.dimension(2), 7);\n\n  VERIFY_IS_EQUAL(ref_of_ref2.data(), input.data());\n  VERIFY_IS_EQUAL(ref_of_ref2.dimension(0), 3);\n  VERIFY_IS_EQUAL(ref_of_ref2.dimension(1), 5);\n  VERIFY_IS_EQUAL(ref_of_ref2.dimension(2), 7);\n\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(ref_of_ref(i,j,k), input(i,j,k));\n        VERIFY_IS_EQUAL(ref_of_ref2(i,j,k), input(i,j,k));\n     }\n    }\n  }\n}\n\n\nstatic void test_ref_in_expr()\n{\n  Tensor<float, 3> input(3,5,7);\n  input.setRandom();\n  TensorRef<Tensor<float, 3>> input_ref(input);\n\n  Tensor<float, 3> result(3,5,7);\n  result.setRandom();\n  TensorRef<Tensor<float, 3>> result_ref(result);\n\n  Tensor<float, 3> bias(3,5,7);\n  bias.setRandom();\n\n  result_ref = input_ref + bias;\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(result_ref(i,j,k), input(i,j,k) + bias(i,j,k));\n        VERIFY_IS_NOT_EQUAL(result(i,j,k), input(i,j,k) + bias(i,j,k));\n      }\n    }\n  }\n\n  result = result_ref;\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(result(i,j,k), input(i,j,k) + bias(i,j,k));\n      }\n    }\n  }\n}\n\n\nstatic void test_coeff_ref()\n{\n  Tensor<float, 5> tensor(2,3,5,7,11);\n  tensor.setRandom();\n  Tensor<float, 5> original = tensor;\n\n  TensorRef<Tensor<float, 4>> slice = tensor.chip(7, 4);\n  slice.coeffRef(0, 0, 0, 0) = 1.0f;\n  slice.coeffRef(1, 0, 0, 0) += 2.0f;\n\n  VERIFY_IS_EQUAL(tensor(0,0,0,0,7), 1.0f);\n  VERIFY_IS_EQUAL(tensor(1,0,0,0,7), original(1,0,0,0,7) + 2.0f);\n}\n\n\nstatic void test_nested_ops_with_ref()\n{\n  Tensor<float, 4> t(2, 3, 5, 7);\n  t.setRandom();\n  TensorMap<Tensor<const float, 4> > m(t.data(), 2, 3, 5, 7);\n  array<std::pair<ptrdiff_t, ptrdiff_t>, 4> paddings;\n  paddings[0] = std::make_pair(0, 0);\n  paddings[1] = std::make_pair(2, 1);\n  paddings[2] = std::make_pair(3, 4);\n  paddings[3] = std::make_pair(0, 0);\n  DSizes<Eigen::DenseIndex, 4> shuffle_dims(0, 1, 2, 3);\n  TensorRef<Tensor<const float, 4> > ref(m.pad(paddings));\n  array<std::pair<ptrdiff_t, ptrdiff_t>, 4> trivial;\n  trivial[0] = std::make_pair(0, 0);\n  trivial[1] = std::make_pair(0, 0);\n  trivial[2] = std::make_pair(0, 0);\n  trivial[3] = std::make_pair(0, 0);\n  Tensor<float, 4> padded = ref.shuffle(shuffle_dims).pad(trivial);\n  VERIFY_IS_EQUAL(padded.dimension(0), 2+0);\n  VERIFY_IS_EQUAL(padded.dimension(1), 3+3);\n  VERIFY_IS_EQUAL(padded.dimension(2), 5+7);\n  VERIFY_IS_EQUAL(padded.dimension(3), 7+0);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 6; ++j) {\n      for (int k = 0; k < 12; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          if (j >= 2 && j < 5 && k >= 3 && k < 8) {\n            VERIFY_IS_EQUAL(padded(i,j,k,l), t(i,j-2,k-3,l));\n          } else {\n            VERIFY_IS_EQUAL(padded(i,j,k,l), 0.0f);\n          }\n        }\n      }\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_ref)\n{\n  CALL_SUBTEST(test_simple_lvalue_ref());\n  CALL_SUBTEST(test_simple_rvalue_ref());\n  CALL_SUBTEST(test_multiple_dims());\n  CALL_SUBTEST(test_slice());\n  CALL_SUBTEST(test_ref_of_ref());\n  CALL_SUBTEST(test_ref_in_expr());\n  CALL_SUBTEST(test_coeff_ref());\n  CALL_SUBTEST(test_nested_ops_with_ref());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_reverse.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Navdeep Jaitly <ndjaitly@google.com and\n//                    Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::array;\n\ntemplate <int DataLayout>\nstatic void test_simple_reverse()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n\n  array<bool, 4> dim_rev;\n  dim_rev[0] = false;\n  dim_rev[1] = true;\n  dim_rev[2] = true;\n  dim_rev[3] = false;\n\n  Tensor<float, 4, DataLayout> reversed_tensor;\n  reversed_tensor = tensor.reverse(dim_rev);\n\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(0), 2);\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(1), 3);\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(2), 5);\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(3), 7);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), reversed_tensor(i,2-j,4-k,l));\n        }\n      }\n    }\n  }\n\n  dim_rev[0] = true;\n  dim_rev[1] = false;\n  dim_rev[2] = false;\n  dim_rev[3] = false;\n\n  reversed_tensor = tensor.reverse(dim_rev);\n\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(0), 2);\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(1), 3);\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(2), 5);\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(3), 7);\n\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), reversed_tensor(1-i,j,k,l));\n        }\n      }\n    }\n  }\n\n  dim_rev[0] = true;\n  dim_rev[1] = false;\n  dim_rev[2] = false;\n  dim_rev[3] = true;\n\n  reversed_tensor = tensor.reverse(dim_rev);\n\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(0), 2);\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(1), 3);\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(2), 5);\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(3), 7);\n\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), reversed_tensor(1-i,j,k,6-l));\n        }\n      }\n    }\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_expr_reverse(bool LValue)\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n\n  array<bool, 4> dim_rev;\n  dim_rev[0] = false;\n  dim_rev[1] = true;\n  dim_rev[2] = false;\n  dim_rev[3] = true;\n\n  Tensor<float, 4, DataLayout> expected(2, 3, 5, 7);\n  if (LValue) {\n    expected.reverse(dim_rev) = tensor;\n  } else {\n    expected = tensor.reverse(dim_rev);\n  }\n\n  Tensor<float, 4, DataLayout> result(2,3,5,7);\n\n  array<ptrdiff_t, 4> src_slice_dim;\n  src_slice_dim[0] = 2;\n  src_slice_dim[1] = 3;\n  src_slice_dim[2] = 1;\n  src_slice_dim[3] = 7;\n  array<ptrdiff_t, 4> src_slice_start;\n  src_slice_start[0] = 0;\n  src_slice_start[1] = 0;\n  src_slice_start[2] = 0;\n  src_slice_start[3] = 0;\n  array<ptrdiff_t, 4> dst_slice_dim = src_slice_dim;\n  array<ptrdiff_t, 4> dst_slice_start = src_slice_start;\n\n  for (int i = 0; i < 5; ++i) {\n    if (LValue) {\n      result.slice(dst_slice_start, dst_slice_dim).reverse(dim_rev) =\n          tensor.slice(src_slice_start, src_slice_dim);\n    } else {\n      result.slice(dst_slice_start, dst_slice_dim) =\n          tensor.slice(src_slice_start, src_slice_dim).reverse(dim_rev);\n    }\n    src_slice_start[2] += 1;\n    dst_slice_start[2] += 1;\n  }\n\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_EQUAL(result.dimension(1), 3);\n  VERIFY_IS_EQUAL(result.dimension(2), 5);\n  VERIFY_IS_EQUAL(result.dimension(3), 7);\n\n  for (int i = 0; i < expected.dimension(0); ++i) {\n    for (int j = 0; j < expected.dimension(1); ++j) {\n      for (int k = 0; k < expected.dimension(2); ++k) {\n        for (int l = 0; l < expected.dimension(3); ++l) {\n          VERIFY_IS_EQUAL(result(i,j,k,l), expected(i,j,k,l));\n        }\n      }\n    }\n  }\n\n  dst_slice_start[2] = 0;\n  result.setRandom();\n  for (int i = 0; i < 5; ++i) {\n     if (LValue) {\n       result.slice(dst_slice_start, dst_slice_dim).reverse(dim_rev) =\n           tensor.slice(dst_slice_start, dst_slice_dim);\n     } else {\n       result.slice(dst_slice_start, dst_slice_dim) =\n           tensor.reverse(dim_rev).slice(dst_slice_start, dst_slice_dim);\n     }\n    dst_slice_start[2] += 1;\n  }\n\n  for (int i = 0; i < expected.dimension(0); ++i) {\n    for (int j = 0; j < expected.dimension(1); ++j) {\n      for (int k = 0; k < expected.dimension(2); ++k) {\n        for (int l = 0; l < expected.dimension(3); ++l) {\n          VERIFY_IS_EQUAL(result(i,j,k,l), expected(i,j,k,l));\n        }\n      }\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_reverse)\n{\n  CALL_SUBTEST(test_simple_reverse<ColMajor>());\n  CALL_SUBTEST(test_simple_reverse<RowMajor>());\n  CALL_SUBTEST(test_expr_reverse<ColMajor>(true));\n  CALL_SUBTEST(test_expr_reverse<RowMajor>(true));\n  CALL_SUBTEST(test_expr_reverse<ColMajor>(false));\n  CALL_SUBTEST(test_expr_reverse<RowMajor>(false));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_reverse_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_simple_reverse(const Eigen::SyclDevice& sycl_device) {\n  IndexType dim1 = 2;\n  IndexType dim2 = 3;\n  IndexType dim3 = 5;\n  IndexType dim4 = 7;\n\n  array<IndexType, 4> tensorRange = {{dim1, dim2, dim3, dim4}};\n  Tensor<DataType, 4, DataLayout, IndexType> tensor(tensorRange);\n  Tensor<DataType, 4, DataLayout, IndexType> reversed_tensor(tensorRange);\n  tensor.setRandom();\n\n  array<bool, 4> dim_rev;\n  dim_rev[0] = false;\n  dim_rev[1] = true;\n  dim_rev[2] = true;\n  dim_rev[3] = false;\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(tensor.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = static_cast<DataType*>(sycl_device.allocate(\n      reversed_tensor.dimensions().TotalSize() * sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType> > in_gpu(gpu_in_data,\n                                                                tensorRange);\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType> > out_gpu(gpu_out_data,\n                                                                 tensorRange);\n\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, tensor.data(),\n      (tensor.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.reverse(dim_rev);\n  sycl_device.memcpyDeviceToHost(\n      reversed_tensor.data(), gpu_out_data,\n      reversed_tensor.dimensions().TotalSize() * sizeof(DataType));\n  // Check that the CPU and GPU reductions return the same result.\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      for (IndexType k = 0; k < 5; ++k) {\n        for (IndexType l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i, j, k, l),\n                          reversed_tensor(i, 2 - j, 4 - k, l));\n        }\n      }\n    }\n  }\n  dim_rev[0] = true;\n  dim_rev[1] = false;\n  dim_rev[2] = false;\n  dim_rev[3] = false;\n\n  out_gpu.device(sycl_device) = in_gpu.reverse(dim_rev);\n  sycl_device.memcpyDeviceToHost(\n      reversed_tensor.data(), gpu_out_data,\n      reversed_tensor.dimensions().TotalSize() * sizeof(DataType));\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      for (IndexType k = 0; k < 5; ++k) {\n        for (IndexType l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i, j, k, l), reversed_tensor(1 - i, j, k, l));\n        }\n      }\n    }\n  }\n\n  dim_rev[0] = true;\n  dim_rev[1] = false;\n  dim_rev[2] = false;\n  dim_rev[3] = true;\n  out_gpu.device(sycl_device) = in_gpu.reverse(dim_rev);\n  sycl_device.memcpyDeviceToHost(\n      reversed_tensor.data(), gpu_out_data,\n      reversed_tensor.dimensions().TotalSize() * sizeof(DataType));\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      for (IndexType k = 0; k < 5; ++k) {\n        for (IndexType l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i, j, k, l),\n                          reversed_tensor(1 - i, j, k, 6 - l));\n        }\n      }\n    }\n  }\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_expr_reverse(const Eigen::SyclDevice& sycl_device,\n                              bool LValue) {\n  IndexType dim1 = 2;\n  IndexType dim2 = 3;\n  IndexType dim3 = 5;\n  IndexType dim4 = 7;\n\n  array<IndexType, 4> tensorRange = {{dim1, dim2, dim3, dim4}};\n  Tensor<DataType, 4, DataLayout, IndexType> tensor(tensorRange);\n  Tensor<DataType, 4, DataLayout, IndexType> expected(tensorRange);\n  Tensor<DataType, 4, DataLayout, IndexType> result(tensorRange);\n  tensor.setRandom();\n\n  array<bool, 4> dim_rev;\n  dim_rev[0] = false;\n  dim_rev[1] = true;\n  dim_rev[2] = false;\n  dim_rev[3] = true;\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(tensor.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data_expected = static_cast<DataType*>(sycl_device.allocate(\n      expected.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data_result = static_cast<DataType*>(\n      sycl_device.allocate(result.dimensions().TotalSize() * sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType> > in_gpu(gpu_in_data,\n                                                                tensorRange);\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType> > out_gpu_expected(\n      gpu_out_data_expected, tensorRange);\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType> > out_gpu_result(\n      gpu_out_data_result, tensorRange);\n\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, tensor.data(),\n      (tensor.dimensions().TotalSize()) * sizeof(DataType));\n\n  if (LValue) {\n    out_gpu_expected.reverse(dim_rev).device(sycl_device) = in_gpu;\n  } else {\n    out_gpu_expected.device(sycl_device) = in_gpu.reverse(dim_rev);\n  }\n  sycl_device.memcpyDeviceToHost(\n      expected.data(), gpu_out_data_expected,\n      expected.dimensions().TotalSize() * sizeof(DataType));\n\n  array<IndexType, 4> src_slice_dim;\n  src_slice_dim[0] = 2;\n  src_slice_dim[1] = 3;\n  src_slice_dim[2] = 1;\n  src_slice_dim[3] = 7;\n  array<IndexType, 4> src_slice_start;\n  src_slice_start[0] = 0;\n  src_slice_start[1] = 0;\n  src_slice_start[2] = 0;\n  src_slice_start[3] = 0;\n  array<IndexType, 4> dst_slice_dim = src_slice_dim;\n  array<IndexType, 4> dst_slice_start = src_slice_start;\n\n  for (IndexType i = 0; i < 5; ++i) {\n    if (LValue) {\n      out_gpu_result.slice(dst_slice_start, dst_slice_dim)\n          .reverse(dim_rev)\n          .device(sycl_device) = in_gpu.slice(src_slice_start, src_slice_dim);\n    } else {\n      out_gpu_result.slice(dst_slice_start, dst_slice_dim).device(sycl_device) =\n          in_gpu.slice(src_slice_start, src_slice_dim).reverse(dim_rev);\n    }\n    src_slice_start[2] += 1;\n    dst_slice_start[2] += 1;\n  }\n  sycl_device.memcpyDeviceToHost(\n      result.data(), gpu_out_data_result,\n      result.dimensions().TotalSize() * sizeof(DataType));\n\n  for (IndexType i = 0; i < expected.dimension(0); ++i) {\n    for (IndexType j = 0; j < expected.dimension(1); ++j) {\n      for (IndexType k = 0; k < expected.dimension(2); ++k) {\n        for (IndexType l = 0; l < expected.dimension(3); ++l) {\n          VERIFY_IS_EQUAL(result(i, j, k, l), expected(i, j, k, l));\n        }\n      }\n    }\n  }\n\n  dst_slice_start[2] = 0;\n  result.setRandom();\n  sycl_device.memcpyHostToDevice(\n      gpu_out_data_result, result.data(),\n      (result.dimensions().TotalSize()) * sizeof(DataType));\n  for (IndexType i = 0; i < 5; ++i) {\n    if (LValue) {\n      out_gpu_result.slice(dst_slice_start, dst_slice_dim)\n          .reverse(dim_rev)\n          .device(sycl_device) = in_gpu.slice(dst_slice_start, dst_slice_dim);\n    } else {\n      out_gpu_result.slice(dst_slice_start, dst_slice_dim).device(sycl_device) =\n          in_gpu.reverse(dim_rev).slice(dst_slice_start, dst_slice_dim);\n    }\n    dst_slice_start[2] += 1;\n  }\n  sycl_device.memcpyDeviceToHost(\n      result.data(), gpu_out_data_result,\n      result.dimensions().TotalSize() * sizeof(DataType));\n\n  for (IndexType i = 0; i < expected.dimension(0); ++i) {\n    for (IndexType j = 0; j < expected.dimension(1); ++j) {\n      for (IndexType k = 0; k < expected.dimension(2); ++k) {\n        for (IndexType l = 0; l < expected.dimension(3); ++l) {\n          VERIFY_IS_EQUAL(result(i, j, k, l), expected(i, j, k, l));\n        }\n      }\n    }\n  }\n}\n\ntemplate <typename DataType>\nvoid sycl_reverse_test_per_device(const cl::sycl::device& d) {\n  QueueInterface queueInterface(d);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_simple_reverse<DataType, RowMajor, int64_t>(sycl_device);\n  test_simple_reverse<DataType, ColMajor, int64_t>(sycl_device);\n  test_expr_reverse<DataType, RowMajor, int64_t>(sycl_device, false);\n  test_expr_reverse<DataType, ColMajor, int64_t>(sycl_device, false);\n  test_expr_reverse<DataType, RowMajor, int64_t>(sycl_device, true);\n  test_expr_reverse<DataType, ColMajor, int64_t>(sycl_device, true);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_reverse_sycl) {\n  for (const auto& device : Eigen::get_sycl_supported_devices()) {\n    std::cout << \"Running on \"\n              << device.get_info<cl::sycl::info::device::name>() << std::endl;\n    CALL_SUBTEST_1(sycl_reverse_test_per_device<short>(device));\n    CALL_SUBTEST_2(sycl_reverse_test_per_device<int>(device));\n    CALL_SUBTEST_3(sycl_reverse_test_per_device<unsigned int>(device));\n#ifdef EIGEN_SYCL_DOUBLE_SUPPORT\n    CALL_SUBTEST_4(sycl_reverse_test_per_device<double>(device));\n#endif\n    CALL_SUBTEST_5(sycl_reverse_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_roundings.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\n\nstatic void test_float_rounding()\n{\n  Tensor<float, 2> ftensor(20,30);\n  ftensor = ftensor.random() * 100.f;\n\n  Tensor<float, 2> result = ftensor.round();\n\n  for (int i = 0; i < 20; ++i) {\n    for (int j = 0; j < 30; ++j) {\n      VERIFY_IS_EQUAL(result(i,j), numext::round(ftensor(i,j)));\n    }\n  }\n}\n\nstatic void test_float_flooring()\n{\n  Tensor<float, 2> ftensor(20,30);\n  ftensor = ftensor.random() * 100.f;\n\n  Tensor<float, 2> result = ftensor.floor();\n\n  for (int i = 0; i < 20; ++i) {\n    for (int j = 0; j < 30; ++j) {\n      VERIFY_IS_EQUAL(result(i,j), numext::floor(ftensor(i,j)));\n    }\n  }\n}\n\nstatic void test_float_ceiling()\n{\n  Tensor<float, 2> ftensor(20,30);\n  ftensor = ftensor.random() * 100.f;\n\n  Tensor<float, 2> result = ftensor.ceil();\n\n  for (int i = 0; i < 20; ++i) {\n    for (int j = 0; j < 30; ++j) {\n      VERIFY_IS_EQUAL(result(i,j), numext::ceil(ftensor(i,j)));\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_roundings)\n{\n   CALL_SUBTEST(test_float_rounding());\n   CALL_SUBTEST(test_float_ceiling());\n   CALL_SUBTEST(test_float_flooring());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_scan.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Igor Babuschkin <igor@babuschk.in>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <limits>\n#include <numeric>\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate <int DataLayout, typename Type=float, bool Exclusive = false>\nstatic void test_1d_scan()\n{\n  int size = 50;\n  Tensor<Type, 1, DataLayout> tensor(size);\n  tensor.setRandom();\n  Tensor<Type, 1, DataLayout> result = tensor.cumsum(0, Exclusive);\n\n  VERIFY_IS_EQUAL(tensor.dimension(0), result.dimension(0));\n\n  float accum = 0;\n  for (int i = 0; i < size; i++) {\n    if (Exclusive) {\n      VERIFY_IS_EQUAL(result(i), accum);\n      accum += tensor(i);\n    } else {\n      accum += tensor(i);\n      VERIFY_IS_EQUAL(result(i), accum);\n    }\n  }\n\n  accum = 1;\n  result = tensor.cumprod(0, Exclusive);\n  for (int i = 0; i < size; i++) {\n    if (Exclusive) {\n      VERIFY_IS_EQUAL(result(i), accum);\n      accum *= tensor(i);\n    } else {\n      accum *= tensor(i);\n      VERIFY_IS_EQUAL(result(i), accum);\n    }\n  }\n}\n\ntemplate <int DataLayout, typename Type=float>\nstatic void test_4d_scan()\n{\n  int size = 5;\n  Tensor<Type, 4, DataLayout> tensor(size, size, size, size);\n  tensor.setRandom();\n\n  Tensor<Type, 4, DataLayout> result(size, size, size, size);\n\n  result = tensor.cumsum(0);\n  float accum = 0;\n  for (int i = 0; i < size; i++) {\n    accum += tensor(i, 1, 2, 3);\n    VERIFY_IS_EQUAL(result(i, 1, 2, 3), accum);\n  }\n  result = tensor.cumsum(1);\n  accum = 0;\n  for (int i = 0; i < size; i++) {\n    accum += tensor(1, i, 2, 3);\n    VERIFY_IS_EQUAL(result(1, i, 2, 3), accum);\n  }\n  result = tensor.cumsum(2);\n  accum = 0;\n  for (int i = 0; i < size; i++) {\n    accum += tensor(1, 2, i, 3);\n    VERIFY_IS_EQUAL(result(1, 2, i, 3), accum);\n  }\n  result = tensor.cumsum(3);\n  accum = 0;\n  for (int i = 0; i < size; i++) {\n    accum += tensor(1, 2, 3, i);\n    VERIFY_IS_EQUAL(result(1, 2, 3, i), accum);\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_tensor_maps() {\n  int inputs[20];\n  TensorMap<Tensor<int, 1, DataLayout> > tensor_map(inputs, 20);\n  tensor_map.setRandom();\n\n  Tensor<int, 1, DataLayout> result = tensor_map.cumsum(0);\n\n  int accum = 0;\n  for (int i = 0; i < 20; ++i) {\n    accum += tensor_map(i);\n    VERIFY_IS_EQUAL(result(i), accum);\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_scan) {\n  CALL_SUBTEST((test_1d_scan<ColMajor, float, true>()));\n  CALL_SUBTEST((test_1d_scan<ColMajor, float, false>()));\n  CALL_SUBTEST((test_1d_scan<RowMajor, float, true>()));\n  CALL_SUBTEST((test_1d_scan<RowMajor, float, false>()));\n  CALL_SUBTEST(test_4d_scan<ColMajor>());\n  CALL_SUBTEST(test_4d_scan<RowMajor>());\n  CALL_SUBTEST(test_tensor_maps<ColMajor>());\n  CALL_SUBTEST(test_tensor_maps<RowMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_scan_gpu.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\n#include <Eigen/CXX11/src/Tensor/TensorGpuHipCudaDefines.h>\n\nusing Eigen::Tensor;\ntypedef Tensor<float, 1>::DimensionPair DimPair;\n\ntemplate<int DataLayout>\nvoid test_gpu_cumsum(int m_size, int k_size, int n_size)\n{\n  std::cout << \"Testing for (\" << m_size << \",\" << k_size << \",\" << n_size << \")\" << std::endl;\n  Tensor<float, 3, DataLayout> t_input(m_size, k_size, n_size);\n  Tensor<float, 3, DataLayout> t_result(m_size, k_size, n_size);\n  Tensor<float, 3, DataLayout> t_result_gpu(m_size, k_size, n_size);\n\n  t_input.setRandom();\n\n  std::size_t t_input_bytes = t_input.size()  * sizeof(float);\n  std::size_t t_result_bytes = t_result.size() * sizeof(float);\n\n  float* d_t_input;\n  float* d_t_result;\n\n  gpuMalloc((void**)(&d_t_input), t_input_bytes);\n  gpuMalloc((void**)(&d_t_result), t_result_bytes);\n\n  gpuMemcpy(d_t_input, t_input.data(), t_input_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 3, DataLayout> >\n      gpu_t_input(d_t_input, Eigen::array<int, 3>(m_size, k_size, n_size));\n  Eigen::TensorMap<Eigen::Tensor<float, 3, DataLayout> >\n      gpu_t_result(d_t_result, Eigen::array<int, 3>(m_size, k_size, n_size));\n\n  gpu_t_result.device(gpu_device) = gpu_t_input.cumsum(1);\n  t_result = t_input.cumsum(1);\n\n  gpuMemcpy(t_result_gpu.data(), d_t_result, t_result_bytes, gpuMemcpyDeviceToHost);\n  for (DenseIndex i = 0; i < t_result.size(); i++) {\n    if (fabs(t_result(i) - t_result_gpu(i)) < 1e-4f) {\n      continue;\n    }\n    if (Eigen::internal::isApprox(t_result(i), t_result_gpu(i), 1e-4f)) {\n      continue;\n    }\n    std::cout << \"mismatch detected at index \" << i << \": \" << t_result(i)\n              << \" vs \" <<  t_result_gpu(i) << std::endl;\n    assert(false);\n  }\n\n  gpuFree((void*)d_t_input);\n  gpuFree((void*)d_t_result);\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_scan_gpu)\n{\n  CALL_SUBTEST_1(test_gpu_cumsum<ColMajor>(128, 128, 128));\n  CALL_SUBTEST_2(test_gpu_cumsum<RowMajor>(128, 128, 128));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_scan_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\ntypedef Tensor<float, 1>::DimensionPair DimPair;\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_sycl_cumsum(const Eigen::SyclDevice& sycl_device, IndexType m_size,\n                      IndexType k_size, IndexType n_size, int consume_dim,\n                      bool exclusive) {\n  static const DataType error_threshold = 1e-4f;\n  std::cout << \"Testing for (\" << m_size << \",\" << k_size << \",\" << n_size\n            << \" consume_dim : \" << consume_dim << \")\" << std::endl;\n  Tensor<DataType, 3, DataLayout, IndexType> t_input(m_size, k_size, n_size);\n  Tensor<DataType, 3, DataLayout, IndexType> t_result(m_size, k_size, n_size);\n  Tensor<DataType, 3, DataLayout, IndexType> t_result_gpu(m_size, k_size,\n                                                          n_size);\n\n  t_input.setRandom();\n  std::size_t t_input_bytes = t_input.size() * sizeof(DataType);\n  std::size_t t_result_bytes = t_result.size() * sizeof(DataType);\n\n  DataType* gpu_data_in =\n      static_cast<DataType*>(sycl_device.allocate(t_input_bytes));\n  DataType* gpu_data_out =\n      static_cast<DataType*>(sycl_device.allocate(t_result_bytes));\n\n  array<IndexType, 3> tensorRange = {{m_size, k_size, n_size}};\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu_t_input(\n      gpu_data_in, tensorRange);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu_t_result(\n      gpu_data_out, tensorRange);\n  sycl_device.memcpyHostToDevice(gpu_data_in, t_input.data(), t_input_bytes);\n  sycl_device.memcpyHostToDevice(gpu_data_out, t_input.data(), t_input_bytes);\n\n  gpu_t_result.device(sycl_device) = gpu_t_input.cumsum(consume_dim, exclusive);\n\n  t_result = t_input.cumsum(consume_dim, exclusive);\n\n  sycl_device.memcpyDeviceToHost(t_result_gpu.data(), gpu_data_out,\n                                 t_result_bytes);\n  sycl_device.synchronize();\n\n  for (IndexType i = 0; i < t_result.size(); i++) {\n    if (static_cast<DataType>(std::fabs(static_cast<DataType>(\n            t_result(i) - t_result_gpu(i)))) < error_threshold) {\n      continue;\n    }\n    if (Eigen::internal::isApprox(t_result(i), t_result_gpu(i),\n                                  error_threshold)) {\n      continue;\n    }\n    std::cout << \"mismatch detected at index \" << i << \" CPU : \" << t_result(i)\n              << \" vs SYCL : \" << t_result_gpu(i) << std::endl;\n    assert(false);\n  }\n  sycl_device.deallocate(gpu_data_in);\n  sycl_device.deallocate(gpu_data_out);\n}\n\ntemplate <typename DataType, typename Dev>\nvoid sycl_scan_test_exclusive_dim0_per_device(const Dev& sycl_device) {\n  test_sycl_cumsum<DataType, ColMajor, int64_t>(sycl_device, 2049, 1023, 127, 0,\n                                                true);\n  test_sycl_cumsum<DataType, RowMajor, int64_t>(sycl_device, 2049, 1023, 127, 0,\n                                                true);\n}\ntemplate <typename DataType, typename Dev>\nvoid sycl_scan_test_exclusive_dim1_per_device(const Dev& sycl_device) {\n  test_sycl_cumsum<DataType, ColMajor, int64_t>(sycl_device, 1023, 2049, 127, 1,\n                                                true);\n  test_sycl_cumsum<DataType, RowMajor, int64_t>(sycl_device, 1023, 2049, 127, 1,\n                                                true);\n}\ntemplate <typename DataType, typename Dev>\nvoid sycl_scan_test_exclusive_dim2_per_device(const Dev& sycl_device) {\n  test_sycl_cumsum<DataType, ColMajor, int64_t>(sycl_device, 1023, 127, 2049, 2,\n                                                true);\n  test_sycl_cumsum<DataType, RowMajor, int64_t>(sycl_device, 1023, 127, 2049, 2,\n                                                true);\n}\ntemplate <typename DataType, typename Dev>\nvoid sycl_scan_test_inclusive_dim0_per_device(const Dev& sycl_device) {\n  test_sycl_cumsum<DataType, ColMajor, int64_t>(sycl_device, 2049, 1023, 127, 0,\n                                                false);\n  test_sycl_cumsum<DataType, RowMajor, int64_t>(sycl_device, 2049, 1023, 127, 0,\n                                                false);\n}\ntemplate <typename DataType, typename Dev>\nvoid sycl_scan_test_inclusive_dim1_per_device(const Dev& sycl_device) {\n  test_sycl_cumsum<DataType, ColMajor, int64_t>(sycl_device, 1023, 2049, 127, 1,\n                                                false);\n  test_sycl_cumsum<DataType, RowMajor, int64_t>(sycl_device, 1023, 2049, 127, 1,\n                                                false);\n}\ntemplate <typename DataType, typename Dev>\nvoid sycl_scan_test_inclusive_dim2_per_device(const Dev& sycl_device) {\n  test_sycl_cumsum<DataType, ColMajor, int64_t>(sycl_device, 1023, 127, 2049, 2,\n                                                false);\n  test_sycl_cumsum<DataType, RowMajor, int64_t>(sycl_device, 1023, 127, 2049, 2,\n                                                false);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_scan_sycl) {\n  for (const auto& device : Eigen::get_sycl_supported_devices()) {\n    std::cout << \"Running on \"\n              << device.template get_info<cl::sycl::info::device::name>()\n              << std::endl;\n    QueueInterface queueInterface(device);\n    auto sycl_device = Eigen::SyclDevice(&queueInterface);\n    CALL_SUBTEST_1(\n        sycl_scan_test_exclusive_dim0_per_device<float>(sycl_device));\n    CALL_SUBTEST_2(\n        sycl_scan_test_exclusive_dim1_per_device<float>(sycl_device));\n    CALL_SUBTEST_3(\n        sycl_scan_test_exclusive_dim2_per_device<float>(sycl_device));\n    CALL_SUBTEST_4(\n        sycl_scan_test_inclusive_dim0_per_device<float>(sycl_device));\n    CALL_SUBTEST_5(\n        sycl_scan_test_inclusive_dim1_per_device<float>(sycl_device));\n    CALL_SUBTEST_6(\n        sycl_scan_test_inclusive_dim2_per_device<float>(sycl_device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_shuffling.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::array;\n\ntemplate <int DataLayout>\nstatic void test_simple_shuffling()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> shuffles;\n  shuffles[0] = 0;\n  shuffles[1] = 1;\n  shuffles[2] = 2;\n  shuffles[3] = 3;\n\n  Tensor<float, 4, DataLayout> no_shuffle;\n  no_shuffle = tensor.shuffle(shuffles);\n\n  VERIFY_IS_EQUAL(no_shuffle.dimension(0), 2);\n  VERIFY_IS_EQUAL(no_shuffle.dimension(1), 3);\n  VERIFY_IS_EQUAL(no_shuffle.dimension(2), 5);\n  VERIFY_IS_EQUAL(no_shuffle.dimension(3), 7);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), no_shuffle(i,j,k,l));\n        }\n      }\n    }\n  }\n\n  shuffles[0] = 2;\n  shuffles[1] = 3;\n  shuffles[2] = 1;\n  shuffles[3] = 0;\n  Tensor<float, 4, DataLayout> shuffle;\n  shuffle = tensor.shuffle(shuffles);\n\n  VERIFY_IS_EQUAL(shuffle.dimension(0), 5);\n  VERIFY_IS_EQUAL(shuffle.dimension(1), 7);\n  VERIFY_IS_EQUAL(shuffle.dimension(2), 3);\n  VERIFY_IS_EQUAL(shuffle.dimension(3), 2);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), shuffle(k,l,j,i));\n        }\n      }\n    }\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_expr_shuffling()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n\n  array<ptrdiff_t, 4> shuffles;\n  shuffles[0] = 2;\n  shuffles[1] = 3;\n  shuffles[2] = 1;\n  shuffles[3] = 0;\n  Tensor<float, 4, DataLayout> expected;\n  expected = tensor.shuffle(shuffles);\n\n  Tensor<float, 4, DataLayout> result(5, 7, 3, 2);\n\n  array<ptrdiff_t, 4> src_slice_dim{{2, 3, 1, 7}};\n  array<ptrdiff_t, 4> src_slice_start{{0, 0, 0, 0}};\n  array<ptrdiff_t, 4> dst_slice_dim{{1, 7, 3, 2}};\n  array<ptrdiff_t, 4> dst_slice_start{{0, 0, 0, 0}};\n\n  for (int i = 0; i < 5; ++i) {\n    result.slice(dst_slice_start, dst_slice_dim) =\n        tensor.slice(src_slice_start, src_slice_dim).shuffle(shuffles);\n    src_slice_start[2] += 1;\n    dst_slice_start[0] += 1;\n  }\n\n  VERIFY_IS_EQUAL(result.dimension(0), 5);\n  VERIFY_IS_EQUAL(result.dimension(1), 7);\n  VERIFY_IS_EQUAL(result.dimension(2), 3);\n  VERIFY_IS_EQUAL(result.dimension(3), 2);\n\n  for (int i = 0; i < expected.dimension(0); ++i) {\n    for (int j = 0; j < expected.dimension(1); ++j) {\n      for (int k = 0; k < expected.dimension(2); ++k) {\n        for (int l = 0; l < expected.dimension(3); ++l) {\n          VERIFY_IS_EQUAL(result(i,j,k,l), expected(i,j,k,l));\n        }\n      }\n    }\n  }\n\n  dst_slice_start[0] = 0;\n  result.setRandom();\n  for (int i = 0; i < 5; ++i) {\n    result.slice(dst_slice_start, dst_slice_dim) =\n        tensor.shuffle(shuffles).slice(dst_slice_start, dst_slice_dim);\n    dst_slice_start[0] += 1;\n  }\n\n  for (int i = 0; i < expected.dimension(0); ++i) {\n    for (int j = 0; j < expected.dimension(1); ++j) {\n      for (int k = 0; k < expected.dimension(2); ++k) {\n        for (int l = 0; l < expected.dimension(3); ++l) {\n          VERIFY_IS_EQUAL(result(i,j,k,l), expected(i,j,k,l));\n        }\n      }\n    }\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_shuffling_as_value()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> shuffles;\n  shuffles[2] = 0;\n  shuffles[3] = 1;\n  shuffles[1] = 2;\n  shuffles[0] = 3;\n  Tensor<float, 4, DataLayout> shuffle(5,7,3,2);\n  shuffle.shuffle(shuffles) = tensor;\n\n  VERIFY_IS_EQUAL(shuffle.dimension(0), 5);\n  VERIFY_IS_EQUAL(shuffle.dimension(1), 7);\n  VERIFY_IS_EQUAL(shuffle.dimension(2), 3);\n  VERIFY_IS_EQUAL(shuffle.dimension(3), 2);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), shuffle(k,l,j,i));\n        }\n      }\n    }\n  }\n\n  array<ptrdiff_t, 4> no_shuffle;\n  no_shuffle[0] = 0;\n  no_shuffle[1] = 1;\n  no_shuffle[2] = 2;\n  no_shuffle[3] = 3;\n  Tensor<float, 4, DataLayout> shuffle2(5,7,3,2);\n  shuffle2.shuffle(shuffles) = tensor.shuffle(no_shuffle);\n  for (int i = 0; i < 5; ++i) {\n    for (int j = 0; j < 7; ++j) {\n      for (int k = 0; k < 3; ++k) {\n        for (int l = 0; l < 2; ++l) {\n          VERIFY_IS_EQUAL(shuffle2(i,j,k,l), shuffle(i,j,k,l));\n        }\n      }\n    }\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_shuffle_unshuffle()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n\n  // Choose a random permutation.\n  array<ptrdiff_t, 4> shuffles;\n  for (int i = 0; i < 4; ++i) {\n    shuffles[i] = i;\n  }\n  array<ptrdiff_t, 4> shuffles_inverse;\n  for (int i = 0; i < 4; ++i) {\n    const ptrdiff_t index = internal::random<ptrdiff_t>(i, 3);\n    shuffles_inverse[shuffles[index]] = i;\n    std::swap(shuffles[i], shuffles[index]);\n  }\n\n  Tensor<float, 4, DataLayout> shuffle;\n  shuffle = tensor.shuffle(shuffles).shuffle(shuffles_inverse);\n\n  VERIFY_IS_EQUAL(shuffle.dimension(0), 2);\n  VERIFY_IS_EQUAL(shuffle.dimension(1), 3);\n  VERIFY_IS_EQUAL(shuffle.dimension(2), 5);\n  VERIFY_IS_EQUAL(shuffle.dimension(3), 7);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), shuffle(i,j,k,l));\n        }\n      }\n    }\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_empty_shuffling()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,0,7);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> shuffles;\n  shuffles[0] = 0;\n  shuffles[1] = 1;\n  shuffles[2] = 2;\n  shuffles[3] = 3;\n\n  Tensor<float, 4, DataLayout> no_shuffle;\n  no_shuffle = tensor.shuffle(shuffles);\n\n  VERIFY_IS_EQUAL(no_shuffle.dimension(0), 2);\n  VERIFY_IS_EQUAL(no_shuffle.dimension(1), 3);\n  VERIFY_IS_EQUAL(no_shuffle.dimension(2), 0);\n  VERIFY_IS_EQUAL(no_shuffle.dimension(3), 7);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 0; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), no_shuffle(i,j,k,l));\n        }\n      }\n    }\n  }\n\n  shuffles[0] = 2;\n  shuffles[1] = 3;\n  shuffles[2] = 1;\n  shuffles[3] = 0;\n  Tensor<float, 4, DataLayout> shuffle;\n  shuffle = tensor.shuffle(shuffles);\n\n  VERIFY_IS_EQUAL(shuffle.dimension(0), 0);\n  VERIFY_IS_EQUAL(shuffle.dimension(1), 7);\n  VERIFY_IS_EQUAL(shuffle.dimension(2), 3);\n  VERIFY_IS_EQUAL(shuffle.dimension(3), 2);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 0; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), shuffle(k,l,j,i));\n        }\n      }\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_shuffling)\n{\n  CALL_SUBTEST(test_simple_shuffling<ColMajor>());\n  CALL_SUBTEST(test_simple_shuffling<RowMajor>());\n  CALL_SUBTEST(test_expr_shuffling<ColMajor>());\n  CALL_SUBTEST(test_expr_shuffling<RowMajor>());\n  CALL_SUBTEST(test_shuffling_as_value<ColMajor>());\n  CALL_SUBTEST(test_shuffling_as_value<RowMajor>());\n  CALL_SUBTEST(test_shuffle_unshuffle<ColMajor>());\n  CALL_SUBTEST(test_shuffle_unshuffle<RowMajor>());\n  CALL_SUBTEST(test_empty_shuffling<ColMajor>());\n  CALL_SUBTEST(test_empty_shuffling<RowMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_shuffling_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_simple_shuffling_sycl(const Eigen::SyclDevice& sycl_device) {\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  array<IndexType, 4> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  Tensor<DataType, 4, DataLayout, IndexType> tensor(tensorRange);\n  Tensor<DataType, 4, DataLayout, IndexType> no_shuffle(tensorRange);\n  tensor.setRandom();\n\n  const size_t buffSize = tensor.size() * sizeof(DataType);\n  array<IndexType, 4> shuffles;\n  shuffles[0] = 0;\n  shuffles[1] = 1;\n  shuffles[2] = 2;\n  shuffles[3] = 3;\n  DataType* gpu_data1 = static_cast<DataType*>(sycl_device.allocate(buffSize));\n  DataType* gpu_data2 = static_cast<DataType*>(sycl_device.allocate(buffSize));\n\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType>> gpu1(gpu_data1,\n                                                             tensorRange);\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType>> gpu2(gpu_data2,\n                                                             tensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor.data(), buffSize);\n\n  gpu2.device(sycl_device) = gpu1.shuffle(shuffles);\n  sycl_device.memcpyDeviceToHost(no_shuffle.data(), gpu_data2, buffSize);\n  sycl_device.synchronize();\n\n  VERIFY_IS_EQUAL(no_shuffle.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(no_shuffle.dimension(1), sizeDim2);\n  VERIFY_IS_EQUAL(no_shuffle.dimension(2), sizeDim3);\n  VERIFY_IS_EQUAL(no_shuffle.dimension(3), sizeDim4);\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        for (IndexType l = 0; l < sizeDim4; ++l) {\n          VERIFY_IS_EQUAL(tensor(i, j, k, l), no_shuffle(i, j, k, l));\n        }\n      }\n    }\n  }\n\n  shuffles[0] = 2;\n  shuffles[1] = 3;\n  shuffles[2] = 1;\n  shuffles[3] = 0;\n  array<IndexType, 4> tensorrangeShuffle = {\n      {sizeDim3, sizeDim4, sizeDim2, sizeDim1}};\n  Tensor<DataType, 4, DataLayout, IndexType> shuffle(tensorrangeShuffle);\n  DataType* gpu_data3 = static_cast<DataType*>(sycl_device.allocate(buffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType>> gpu3(\n      gpu_data3, tensorrangeShuffle);\n\n  gpu3.device(sycl_device) = gpu1.shuffle(shuffles);\n  sycl_device.memcpyDeviceToHost(shuffle.data(), gpu_data3, buffSize);\n  sycl_device.synchronize();\n\n  VERIFY_IS_EQUAL(shuffle.dimension(0), sizeDim3);\n  VERIFY_IS_EQUAL(shuffle.dimension(1), sizeDim4);\n  VERIFY_IS_EQUAL(shuffle.dimension(2), sizeDim2);\n  VERIFY_IS_EQUAL(shuffle.dimension(3), sizeDim1);\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        for (IndexType l = 0; l < sizeDim4; ++l) {\n          VERIFY_IS_EQUAL(tensor(i, j, k, l), shuffle(k, l, j, i));\n        }\n      }\n    }\n  }\n}\n\ntemplate <typename DataType, typename dev_Selector>\nvoid sycl_shuffling_test_per_device(dev_Selector s) {\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_simple_shuffling_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_simple_shuffling_sycl<DataType, ColMajor, int64_t>(sycl_device);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_shuffling_sycl) {\n  for (const auto& device : Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_shuffling_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_simple.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\nstatic void test_0d()\n{\n  Tensor<int, 0> scalar1;\n  Tensor<int, 0, RowMajor> scalar2;\n  Tensor<int, 0> scalar3;\n  Tensor<int, 0, RowMajor> scalar4;\n\n  scalar3.resize();\n  scalar4.resize();\n\n  scalar1() = 7;\n  scalar2() = 13;\n  scalar3.setValues(17);\n  scalar4.setZero();\n\n  VERIFY_IS_EQUAL(scalar1.rank(), 0);\n  VERIFY_IS_EQUAL(scalar1.size(), 1);\n\n  VERIFY_IS_EQUAL(scalar1(), 7);\n  VERIFY_IS_EQUAL(scalar2(), 13);\n  VERIFY_IS_EQUAL(scalar3(), 17);\n  VERIFY_IS_EQUAL(scalar4(), 0);\n\n  Tensor<int, 0> scalar5(scalar1);\n\n  VERIFY_IS_EQUAL(scalar5(), 7);\n  VERIFY_IS_EQUAL(scalar5.data()[0], 7);\n}\n\nstatic void test_1d()\n{\n  Tensor<int, 1> vec1(6);\n  Tensor<int, 1, RowMajor> vec2(6);\n  Tensor<int, 1> vec3;\n  Tensor<int, 1, RowMajor> vec4;\n\n  vec3.resize(6);\n  vec4.resize(6);\n\n  vec1(0) = 4;  vec2(0) = 0; vec3(0) = 5;\n  vec1(1) = 8;  vec2(1) = 1; vec3(1) = 4;\n  vec1(2) = 15; vec2(2) = 2; vec3(2) = 3;\n  vec1(3) = 16; vec2(3) = 3; vec3(3) = 2;\n  vec1(4) = 23; vec2(4) = 4; vec3(4) = 1;\n  vec1(5) = 42; vec2(5) = 5; vec3(5) = 0;\n  vec4.setZero();\n\n  VERIFY_IS_EQUAL((vec1.rank()), 1);\n  VERIFY_IS_EQUAL((vec1.size()), 6);\n  VERIFY_IS_EQUAL((vec1.dimensions()[0]), 6);\n\n  VERIFY_IS_EQUAL((vec1[0]), 4);\n  VERIFY_IS_EQUAL((vec1[1]), 8);\n  VERIFY_IS_EQUAL((vec1[2]), 15);\n  VERIFY_IS_EQUAL((vec1[3]), 16);\n  VERIFY_IS_EQUAL((vec1[4]), 23);\n  VERIFY_IS_EQUAL((vec1[5]), 42);\n\n  VERIFY_IS_EQUAL((vec2[0]), 0);\n  VERIFY_IS_EQUAL((vec2[1]), 1);\n  VERIFY_IS_EQUAL((vec2[2]), 2);\n  VERIFY_IS_EQUAL((vec2[3]), 3);\n  VERIFY_IS_EQUAL((vec2[4]), 4);\n  VERIFY_IS_EQUAL((vec2[5]), 5);\n\n  VERIFY_IS_EQUAL((vec3[0]), 5);\n  VERIFY_IS_EQUAL((vec3[1]), 4);\n  VERIFY_IS_EQUAL((vec3[2]), 3);\n  VERIFY_IS_EQUAL((vec3[3]), 2);\n  VERIFY_IS_EQUAL((vec3[4]), 1);\n  VERIFY_IS_EQUAL((vec3[5]), 0);\n\n  VERIFY_IS_EQUAL((vec4[0]), 0);\n  VERIFY_IS_EQUAL((vec4[1]), 0);\n  VERIFY_IS_EQUAL((vec4[2]), 0);\n  VERIFY_IS_EQUAL((vec4[3]), 0);\n  VERIFY_IS_EQUAL((vec4[4]), 0);\n  VERIFY_IS_EQUAL((vec4[5]), 0);\n\n  Tensor<int, 1> vec5(vec1);\n\n  VERIFY_IS_EQUAL((vec5(0)), 4);\n  VERIFY_IS_EQUAL((vec5(1)), 8);\n  VERIFY_IS_EQUAL((vec5(2)), 15);\n  VERIFY_IS_EQUAL((vec5(3)), 16);\n  VERIFY_IS_EQUAL((vec5(4)), 23);\n  VERIFY_IS_EQUAL((vec5(5)), 42);\n\n  VERIFY_IS_EQUAL((vec5.data()[0]), 4);\n  VERIFY_IS_EQUAL((vec5.data()[1]), 8);\n  VERIFY_IS_EQUAL((vec5.data()[2]), 15);\n  VERIFY_IS_EQUAL((vec5.data()[3]), 16);\n  VERIFY_IS_EQUAL((vec5.data()[4]), 23);\n  VERIFY_IS_EQUAL((vec5.data()[5]), 42);\n}\n\nstatic void test_2d()\n{\n  Tensor<int, 2> mat1(2,3);\n  Tensor<int, 2, RowMajor> mat2(2,3);\n\n  mat1(0,0) = 0;\n  mat1(0,1) = 1;\n  mat1(0,2) = 2;\n  mat1(1,0) = 3;\n  mat1(1,1) = 4;\n  mat1(1,2) = 5;\n\n  mat2(0,0) = 0;\n  mat2(0,1) = 1;\n  mat2(0,2) = 2;\n  mat2(1,0) = 3;\n  mat2(1,1) = 4;\n  mat2(1,2) = 5;\n\n  VERIFY_IS_EQUAL((mat1.rank()), 2);\n  VERIFY_IS_EQUAL((mat1.size()), 6);\n  VERIFY_IS_EQUAL((mat1.dimensions()[0]), 2);\n  VERIFY_IS_EQUAL((mat1.dimensions()[1]), 3);\n\n  VERIFY_IS_EQUAL((mat2.rank()), 2);\n  VERIFY_IS_EQUAL((mat2.size()), 6);\n  VERIFY_IS_EQUAL((mat2.dimensions()[0]), 2);\n  VERIFY_IS_EQUAL((mat2.dimensions()[1]), 3);\n\n  VERIFY_IS_EQUAL((mat1.data()[0]), 0);\n  VERIFY_IS_EQUAL((mat1.data()[1]), 3);\n  VERIFY_IS_EQUAL((mat1.data()[2]), 1);\n  VERIFY_IS_EQUAL((mat1.data()[3]), 4);\n  VERIFY_IS_EQUAL((mat1.data()[4]), 2);\n  VERIFY_IS_EQUAL((mat1.data()[5]), 5);\n\n  VERIFY_IS_EQUAL((mat2.data()[0]), 0);\n  VERIFY_IS_EQUAL((mat2.data()[1]), 1);\n  VERIFY_IS_EQUAL((mat2.data()[2]), 2);\n  VERIFY_IS_EQUAL((mat2.data()[3]), 3);\n  VERIFY_IS_EQUAL((mat2.data()[4]), 4);\n  VERIFY_IS_EQUAL((mat2.data()[5]), 5);\n}\n\nstatic void test_3d()\n{\n  Tensor<int, 3> epsilon(3,3,3);\n  epsilon.setZero();\n  epsilon(0,1,2) = epsilon(2,0,1) = epsilon(1,2,0) = 1;\n  epsilon(2,1,0) = epsilon(0,2,1) = epsilon(1,0,2) = -1;\n\n  VERIFY_IS_EQUAL((epsilon.size()), 27);\n  VERIFY_IS_EQUAL((epsilon.dimensions()[0]), 3);\n  VERIFY_IS_EQUAL((epsilon.dimensions()[1]), 3);\n  VERIFY_IS_EQUAL((epsilon.dimensions()[2]), 3);\n\n  VERIFY_IS_EQUAL((epsilon(0,0,0)), 0);\n  VERIFY_IS_EQUAL((epsilon(0,0,1)), 0);\n  VERIFY_IS_EQUAL((epsilon(0,0,2)), 0);\n  VERIFY_IS_EQUAL((epsilon(0,1,0)), 0);\n  VERIFY_IS_EQUAL((epsilon(0,1,1)), 0);\n  VERIFY_IS_EQUAL((epsilon(0,2,0)), 0);\n  VERIFY_IS_EQUAL((epsilon(0,2,2)), 0);\n  VERIFY_IS_EQUAL((epsilon(1,0,0)), 0);\n  VERIFY_IS_EQUAL((epsilon(1,0,1)), 0);\n  VERIFY_IS_EQUAL((epsilon(1,1,0)), 0);\n  VERIFY_IS_EQUAL((epsilon(1,1,1)), 0);\n  VERIFY_IS_EQUAL((epsilon(1,1,2)), 0);\n  VERIFY_IS_EQUAL((epsilon(1,2,1)), 0);\n  VERIFY_IS_EQUAL((epsilon(1,2,2)), 0);\n  VERIFY_IS_EQUAL((epsilon(2,0,0)), 0);\n  VERIFY_IS_EQUAL((epsilon(2,0,2)), 0);\n  VERIFY_IS_EQUAL((epsilon(2,1,1)), 0);\n  VERIFY_IS_EQUAL((epsilon(2,1,2)), 0);\n  VERIFY_IS_EQUAL((epsilon(2,2,0)), 0);\n  VERIFY_IS_EQUAL((epsilon(2,2,1)), 0);\n  VERIFY_IS_EQUAL((epsilon(2,2,2)), 0);\n\n  VERIFY_IS_EQUAL((epsilon(0,1,2)), 1);\n  VERIFY_IS_EQUAL((epsilon(2,0,1)), 1);\n  VERIFY_IS_EQUAL((epsilon(1,2,0)), 1);\n  VERIFY_IS_EQUAL((epsilon(2,1,0)), -1);\n  VERIFY_IS_EQUAL((epsilon(0,2,1)), -1);\n  VERIFY_IS_EQUAL((epsilon(1,0,2)), -1);\n\n  array<Eigen::DenseIndex, 3> dims;\n  dims[0] = 2;\n  dims[1] = 3;\n  dims[2] = 4;\n  Tensor<int, 3> t1(dims);\n  Tensor<int, 3, RowMajor> t2(dims);\n\n  VERIFY_IS_EQUAL((t1.size()), 24);\n  VERIFY_IS_EQUAL((t1.dimensions()[0]), 2);\n  VERIFY_IS_EQUAL((t1.dimensions()[1]), 3);\n  VERIFY_IS_EQUAL((t1.dimensions()[2]), 4);\n\n  VERIFY_IS_EQUAL((t2.size()), 24);\n  VERIFY_IS_EQUAL((t2.dimensions()[0]), 2);\n  VERIFY_IS_EQUAL((t2.dimensions()[1]), 3);\n  VERIFY_IS_EQUAL((t2.dimensions()[2]), 4);\n\n  for (int i = 0; i < 2; i++) {\n    for (int j = 0; j < 3; j++) {\n      for (int k = 0; k < 4; k++) {\n        t1(i, j, k) = 100 * i + 10 * j + k;\n        t2(i, j, k) = 100 * i + 10 * j + k;\n      }\n    }\n  }\n\n  VERIFY_IS_EQUAL((t1.data()[0]),    0);\n  VERIFY_IS_EQUAL((t1.data()[1]),  100);\n  VERIFY_IS_EQUAL((t1.data()[2]),   10);\n  VERIFY_IS_EQUAL((t1.data()[3]),  110);\n  VERIFY_IS_EQUAL((t1.data()[4]),   20);\n  VERIFY_IS_EQUAL((t1.data()[5]),  120);\n  VERIFY_IS_EQUAL((t1.data()[6]),    1);\n  VERIFY_IS_EQUAL((t1.data()[7]),  101);\n  VERIFY_IS_EQUAL((t1.data()[8]),   11);\n  VERIFY_IS_EQUAL((t1.data()[9]),  111);\n  VERIFY_IS_EQUAL((t1.data()[10]),  21);\n  VERIFY_IS_EQUAL((t1.data()[11]), 121);\n  VERIFY_IS_EQUAL((t1.data()[12]),   2);\n  VERIFY_IS_EQUAL((t1.data()[13]), 102);\n  VERIFY_IS_EQUAL((t1.data()[14]),  12);\n  VERIFY_IS_EQUAL((t1.data()[15]), 112);\n  VERIFY_IS_EQUAL((t1.data()[16]),  22);\n  VERIFY_IS_EQUAL((t1.data()[17]), 122);\n  VERIFY_IS_EQUAL((t1.data()[18]),   3);\n  VERIFY_IS_EQUAL((t1.data()[19]), 103);\n  VERIFY_IS_EQUAL((t1.data()[20]),  13);\n  VERIFY_IS_EQUAL((t1.data()[21]), 113);\n  VERIFY_IS_EQUAL((t1.data()[22]),  23);\n  VERIFY_IS_EQUAL((t1.data()[23]), 123);\n\n  VERIFY_IS_EQUAL((t2.data()[0]),    0);\n  VERIFY_IS_EQUAL((t2.data()[1]),    1);\n  VERIFY_IS_EQUAL((t2.data()[2]),    2);\n  VERIFY_IS_EQUAL((t2.data()[3]),    3);\n  VERIFY_IS_EQUAL((t2.data()[4]),   10);\n  VERIFY_IS_EQUAL((t2.data()[5]),   11);\n  VERIFY_IS_EQUAL((t2.data()[6]),   12);\n  VERIFY_IS_EQUAL((t2.data()[7]),   13);\n  VERIFY_IS_EQUAL((t2.data()[8]),   20);\n  VERIFY_IS_EQUAL((t2.data()[9]),   21);\n  VERIFY_IS_EQUAL((t2.data()[10]),  22);\n  VERIFY_IS_EQUAL((t2.data()[11]),  23);\n  VERIFY_IS_EQUAL((t2.data()[12]), 100);\n  VERIFY_IS_EQUAL((t2.data()[13]), 101);\n  VERIFY_IS_EQUAL((t2.data()[14]), 102);\n  VERIFY_IS_EQUAL((t2.data()[15]), 103);\n  VERIFY_IS_EQUAL((t2.data()[16]), 110);\n  VERIFY_IS_EQUAL((t2.data()[17]), 111);\n  VERIFY_IS_EQUAL((t2.data()[18]), 112);\n  VERIFY_IS_EQUAL((t2.data()[19]), 113);\n  VERIFY_IS_EQUAL((t2.data()[20]), 120);\n  VERIFY_IS_EQUAL((t2.data()[21]), 121);\n  VERIFY_IS_EQUAL((t2.data()[22]), 122);\n  VERIFY_IS_EQUAL((t2.data()[23]), 123);\n}\n\nstatic void test_simple_assign()\n{\n  Tensor<int, 3> epsilon(3,3,3);\n  epsilon.setZero();\n  epsilon(0,1,2) = epsilon(2,0,1) = epsilon(1,2,0) = 1;\n  epsilon(2,1,0) = epsilon(0,2,1) = epsilon(1,0,2) = -1;\n\n  Tensor<int, 3> e2(3,3,3);\n  e2.setZero();\n  VERIFY_IS_EQUAL((e2(1,2,0)), 0);\n\n  e2 = epsilon;\n  VERIFY_IS_EQUAL((e2(1,2,0)), 1);\n  VERIFY_IS_EQUAL((e2(0,1,2)), 1);\n  VERIFY_IS_EQUAL((e2(2,0,1)), 1);\n  VERIFY_IS_EQUAL((e2(2,1,0)), -1);\n  VERIFY_IS_EQUAL((e2(0,2,1)), -1);\n  VERIFY_IS_EQUAL((e2(1,0,2)), -1);\n}\n\nstatic void test_resize()\n{\n  Tensor<int, 3> epsilon;\n  epsilon.resize(2,3,7);\n  VERIFY_IS_EQUAL(epsilon.dimension(0), 2);\n  VERIFY_IS_EQUAL(epsilon.dimension(1), 3);\n  VERIFY_IS_EQUAL(epsilon.dimension(2), 7);\n  VERIFY_IS_EQUAL(epsilon.size(), 2*3*7);\n\n  const int* old_data = epsilon.data();\n  epsilon.resize(3,2,7);\n  VERIFY_IS_EQUAL(epsilon.dimension(0), 3);\n  VERIFY_IS_EQUAL(epsilon.dimension(1), 2);\n  VERIFY_IS_EQUAL(epsilon.dimension(2), 7);\n  VERIFY_IS_EQUAL(epsilon.size(), 2*3*7);\n  VERIFY_IS_EQUAL(epsilon.data(), old_data);\n\n  epsilon.resize(3,5,7);\n  VERIFY_IS_EQUAL(epsilon.dimension(0), 3);\n  VERIFY_IS_EQUAL(epsilon.dimension(1), 5);\n  VERIFY_IS_EQUAL(epsilon.dimension(2), 7);\n  VERIFY_IS_EQUAL(epsilon.size(), 3*5*7);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_simple)\n{\n  CALL_SUBTEST(test_0d());\n  CALL_SUBTEST(test_1d());\n  CALL_SUBTEST(test_2d());\n  CALL_SUBTEST(test_3d());\n  CALL_SUBTEST(test_simple_assign());\n  CALL_SUBTEST(test_resize());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_striding.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate<int DataLayout>\nstatic void test_simple_striding()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> strides;\n  strides[0] = 1;\n  strides[1] = 1;\n  strides[2] = 1;\n  strides[3] = 1;\n\n  Tensor<float, 4, DataLayout> no_stride;\n  no_stride = tensor.stride(strides);\n\n  VERIFY_IS_EQUAL(no_stride.dimension(0), 2);\n  VERIFY_IS_EQUAL(no_stride.dimension(1), 3);\n  VERIFY_IS_EQUAL(no_stride.dimension(2), 5);\n  VERIFY_IS_EQUAL(no_stride.dimension(3), 7);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), no_stride(i,j,k,l));\n        }\n      }\n    }\n  }\n\n  strides[0] = 2;\n  strides[1] = 4;\n  strides[2] = 2;\n  strides[3] = 3;\n  Tensor<float, 4, DataLayout> stride;\n  stride = tensor.stride(strides);\n\n  VERIFY_IS_EQUAL(stride.dimension(0), 1);\n  VERIFY_IS_EQUAL(stride.dimension(1), 1);\n  VERIFY_IS_EQUAL(stride.dimension(2), 3);\n  VERIFY_IS_EQUAL(stride.dimension(3), 3);\n\n  for (int i = 0; i < 1; ++i) {\n    for (int j = 0; j < 1; ++j) {\n      for (int k = 0; k < 3; ++k) {\n        for (int l = 0; l < 3; ++l) {\n          VERIFY_IS_EQUAL(tensor(2*i,4*j,2*k,3*l), stride(i,j,k,l));\n        }\n      }\n    }\n  }\n}\n\n\ntemplate<int DataLayout>\nstatic void test_striding_as_lvalue()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> strides;\n  strides[0] = 2;\n  strides[1] = 4;\n  strides[2] = 2;\n  strides[3] = 3;\n\n  Tensor<float, 4, DataLayout> result(3, 12, 10, 21);\n  result.stride(strides) = tensor;\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), result(2*i,4*j,2*k,3*l));\n        }\n      }\n    }\n  }\n\n  array<ptrdiff_t, 4> no_strides;\n  no_strides[0] = 1;\n  no_strides[1] = 1;\n  no_strides[2] = 1;\n  no_strides[3] = 1;\n  Tensor<float, 4, DataLayout> result2(3, 12, 10, 21);\n  result2.stride(strides) = tensor.stride(no_strides);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), result2(2*i,4*j,2*k,3*l));\n        }\n      }\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_striding)\n{\n  CALL_SUBTEST(test_simple_striding<ColMajor>());\n  CALL_SUBTEST(test_simple_striding<RowMajor>());\n  CALL_SUBTEST(test_striding_as_lvalue<ColMajor>());\n  CALL_SUBTEST(test_striding_as_lvalue<RowMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_striding_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include <iostream>\n#include <chrono>\n#include <ctime>\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_simple_striding(const Eigen::SyclDevice& sycl_device)\n{\n\n  Eigen::array<IndexType, 4> tensor_dims = {{2,3,5,7}};\n  Eigen::array<IndexType, 4> stride_dims = {{1,1,3,3}};\n\n\n  Tensor<DataType, 4, DataLayout, IndexType> tensor(tensor_dims);\n  Tensor<DataType, 4, DataLayout,IndexType> no_stride(tensor_dims);\n  Tensor<DataType, 4, DataLayout,IndexType> stride(stride_dims);\n\n\n  std::size_t tensor_bytes = tensor.size()  * sizeof(DataType);\n  std::size_t no_stride_bytes = no_stride.size() * sizeof(DataType);\n  std::size_t stride_bytes = stride.size() * sizeof(DataType);\n  DataType * d_tensor = static_cast<DataType*>(sycl_device.allocate(tensor_bytes));\n  DataType * d_no_stride = static_cast<DataType*>(sycl_device.allocate(no_stride_bytes));\n  DataType * d_stride = static_cast<DataType*>(sycl_device.allocate(stride_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 4, DataLayout, IndexType> > gpu_tensor(d_tensor, tensor_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 4, DataLayout, IndexType> > gpu_no_stride(d_no_stride, tensor_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 4, DataLayout, IndexType> > gpu_stride(d_stride, stride_dims);\n\n\n  tensor.setRandom();\n  array<IndexType, 4> strides;\n  strides[0] = 1;\n  strides[1] = 1;\n  strides[2] = 1;\n  strides[3] = 1;\n  sycl_device.memcpyHostToDevice(d_tensor, tensor.data(), tensor_bytes);\n  gpu_no_stride.device(sycl_device)=gpu_tensor.stride(strides);\n  sycl_device.memcpyDeviceToHost(no_stride.data(), d_no_stride, no_stride_bytes);\n\n  //no_stride = tensor.stride(strides);\n\n  VERIFY_IS_EQUAL(no_stride.dimension(0), 2);\n  VERIFY_IS_EQUAL(no_stride.dimension(1), 3);\n  VERIFY_IS_EQUAL(no_stride.dimension(2), 5);\n  VERIFY_IS_EQUAL(no_stride.dimension(3), 7);\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      for (IndexType k = 0; k < 5; ++k) {\n        for (IndexType l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), no_stride(i,j,k,l));\n        }\n      }\n    }\n  }\n\n  strides[0] = 2;\n  strides[1] = 4;\n  strides[2] = 2;\n  strides[3] = 3;\n//Tensor<float, 4, DataLayout> stride;\n//  stride = tensor.stride(strides);\n\n  gpu_stride.device(sycl_device)=gpu_tensor.stride(strides);\n  sycl_device.memcpyDeviceToHost(stride.data(), d_stride, stride_bytes);\n\n  VERIFY_IS_EQUAL(stride.dimension(0), 1);\n  VERIFY_IS_EQUAL(stride.dimension(1), 1);\n  VERIFY_IS_EQUAL(stride.dimension(2), 3);\n  VERIFY_IS_EQUAL(stride.dimension(3), 3);\n\n  for (IndexType i = 0; i < 1; ++i) {\n    for (IndexType j = 0; j < 1; ++j) {\n      for (IndexType k = 0; k < 3; ++k) {\n        for (IndexType l = 0; l < 3; ++l) {\n          VERIFY_IS_EQUAL(tensor(2*i,4*j,2*k,3*l), stride(i,j,k,l));\n        }\n      }\n    }\n  }\n\n  sycl_device.deallocate(d_tensor);\n  sycl_device.deallocate(d_no_stride);\n  sycl_device.deallocate(d_stride);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_striding_as_lvalue(const Eigen::SyclDevice& sycl_device)\n{\n\n  Eigen::array<IndexType, 4> tensor_dims = {{2,3,5,7}};\n  Eigen::array<IndexType, 4> stride_dims = {{3,12,10,21}};\n\n\n  Tensor<DataType, 4, DataLayout, IndexType> tensor(tensor_dims);\n  Tensor<DataType, 4, DataLayout,IndexType> no_stride(stride_dims);\n  Tensor<DataType, 4, DataLayout,IndexType> stride(stride_dims);\n\n\n  std::size_t tensor_bytes = tensor.size()  * sizeof(DataType);\n  std::size_t no_stride_bytes = no_stride.size() * sizeof(DataType);\n  std::size_t stride_bytes = stride.size() * sizeof(DataType);\n\n  DataType * d_tensor = static_cast<DataType*>(sycl_device.allocate(tensor_bytes));\n  DataType * d_no_stride = static_cast<DataType*>(sycl_device.allocate(no_stride_bytes));\n  DataType * d_stride = static_cast<DataType*>(sycl_device.allocate(stride_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 4, DataLayout, IndexType> > gpu_tensor(d_tensor, tensor_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 4, DataLayout, IndexType> > gpu_no_stride(d_no_stride, stride_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 4, DataLayout, IndexType> > gpu_stride(d_stride, stride_dims);\n\n  //Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  array<IndexType, 4> strides;\n  strides[0] = 2;\n  strides[1] = 4;\n  strides[2] = 2;\n  strides[3] = 3;\n\n//  Tensor<float, 4, DataLayout> result(3, 12, 10, 21);\n//  result.stride(strides) = tensor;\n  sycl_device.memcpyHostToDevice(d_tensor, tensor.data(), tensor_bytes);\n  gpu_stride.stride(strides).device(sycl_device)=gpu_tensor;\n  sycl_device.memcpyDeviceToHost(stride.data(), d_stride, stride_bytes);\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      for (IndexType k = 0; k < 5; ++k) {\n        for (IndexType l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), stride(2*i,4*j,2*k,3*l));\n        }\n      }\n    }\n  }\n\n  array<IndexType, 4> no_strides;\n  no_strides[0] = 1;\n  no_strides[1] = 1;\n  no_strides[2] = 1;\n  no_strides[3] = 1;\n//  Tensor<float, 4, DataLayout> result2(3, 12, 10, 21);\n//  result2.stride(strides) = tensor.stride(no_strides);\n\n  gpu_no_stride.stride(strides).device(sycl_device)=gpu_tensor.stride(no_strides);\n  sycl_device.memcpyDeviceToHost(no_stride.data(), d_no_stride, no_stride_bytes);\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      for (IndexType k = 0; k < 5; ++k) {\n        for (IndexType l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), no_stride(2*i,4*j,2*k,3*l));\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(d_tensor);\n  sycl_device.deallocate(d_no_stride);\n  sycl_device.deallocate(d_stride);\n}\n\n\ntemplate <typename Dev_selector> void tensorStridingPerDevice(Dev_selector& s){\n  QueueInterface queueInterface(s);\n  auto sycl_device=Eigen::SyclDevice(&queueInterface);\n  test_simple_striding<float, ColMajor, int64_t>(sycl_device);\n  test_simple_striding<float, RowMajor, int64_t>(sycl_device);\n  test_striding_as_lvalue<float, ColMajor, int64_t>(sycl_device);\n  test_striding_as_lvalue<float, RowMajor, int64_t>(sycl_device);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_striding_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(tensorStridingPerDevice(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_sugar.cpp",
    "content": "#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\nstatic void test_comparison_sugar() {\n  // we already trust comparisons between tensors, we're simply checking that\n  // the sugared versions are doing the same thing\n  Tensor<int, 3> t(6, 7, 5);\n\n  t.setRandom();\n  // make sure we have at least one value == 0\n  t(0,0,0) = 0;\n\n  Tensor<bool,0> b;\n\n#define TEST_TENSOR_EQUAL(e1, e2) \\\n  b = ((e1) == (e2)).all();       \\\n  VERIFY(b())\n\n#define TEST_OP(op) TEST_TENSOR_EQUAL(t op 0, t op t.constant(0))\n\n  TEST_OP(==);\n  TEST_OP(!=);\n  TEST_OP(<=);\n  TEST_OP(>=);\n  TEST_OP(<);\n  TEST_OP(>);\n#undef TEST_OP\n#undef TEST_TENSOR_EQUAL\n}\n\n\nstatic void test_scalar_sugar_add_mul() {\n  Tensor<float, 3> A(6, 7, 5);\n  Tensor<float, 3> B(6, 7, 5);\n  A.setRandom();\n  B.setRandom();\n\n  const float alpha = 0.43f;\n  const float beta = 0.21f;\n  const float gamma = 0.14f;\n\n  Tensor<float, 3> R = A.constant(gamma) + A * A.constant(alpha) + B * B.constant(beta);\n  Tensor<float, 3> S = A * alpha + B * beta + gamma;\n  Tensor<float, 3> T = gamma + alpha * A + beta * B;\n\n  for (int i = 0; i < 6*7*5; ++i) {\n    VERIFY_IS_APPROX(R(i), S(i));\n    VERIFY_IS_APPROX(R(i), T(i));\n  }\n}\n\nstatic void test_scalar_sugar_sub_div() {\n  Tensor<float, 3> A(6, 7, 5);\n  Tensor<float, 3> B(6, 7, 5);\n  A.setRandom();\n  B.setRandom();\n\n  const float alpha = 0.43f;\n  const float beta = 0.21f;\n  const float gamma = 0.14f;\n  const float delta = 0.32f;\n\n  Tensor<float, 3> R = A.constant(gamma) - A / A.constant(alpha)\n      - B.constant(beta) / B - A.constant(delta);\n  Tensor<float, 3> S = gamma - A / alpha - beta / B - delta;\n\n  for (int i = 0; i < 6*7*5; ++i) {\n    VERIFY_IS_APPROX(R(i), S(i));\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_sugar)\n{\n  CALL_SUBTEST(test_comparison_sugar());\n  CALL_SUBTEST(test_scalar_sugar_add_mul());\n  CALL_SUBTEST(test_scalar_sugar_sub_div());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_sycl_mem_transfers(const Eigen::SyclDevice &sycl_device) {\n  IndexType sizeDim1 = 5;\n  IndexType sizeDim2 = 5;\n  IndexType sizeDim3 = 1;\n  array<IndexType, 3> tensorRange = {{sizeDim1, sizeDim2, sizeDim3}};\n  Tensor<DataType, 3, DataLayout, IndexType> in1(tensorRange);\n  Tensor<DataType, 3, DataLayout, IndexType> out1(tensorRange);\n  Tensor<DataType, 3, DataLayout, IndexType> out2(tensorRange);\n  Tensor<DataType, 3, DataLayout, IndexType> out3(tensorRange);\n\n  in1 = in1.random();\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(in1.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(out1.size()*sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu1(gpu_data1, tensorRange);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu2(gpu_data2, tensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data1, in1.data(),(in1.size())*sizeof(DataType));\n  sycl_device.memcpyHostToDevice(gpu_data2, in1.data(),(in1.size())*sizeof(DataType));\n  gpu1.device(sycl_device) = gpu1 * 3.14f;\n  gpu2.device(sycl_device) = gpu2 * 2.7f;\n  sycl_device.memcpyDeviceToHost(out1.data(), gpu_data1,(out1.size())*sizeof(DataType));\n  sycl_device.memcpyDeviceToHost(out2.data(), gpu_data1,(out2.size())*sizeof(DataType));\n  sycl_device.memcpyDeviceToHost(out3.data(), gpu_data2,(out3.size())*sizeof(DataType));\n  sycl_device.synchronize();\n\n  for (IndexType i = 0; i < in1.size(); ++i) {\n  //  std::cout << \"SYCL DATA : \" << out1(i) << \"  vs  CPU DATA : \" << in1(i) * 3.14f << \"\\n\";\n    VERIFY_IS_APPROX(out1(i), in1(i) * 3.14f);\n    VERIFY_IS_APPROX(out2(i), in1(i) * 3.14f);\n    VERIFY_IS_APPROX(out3(i), in1(i) * 2.7f);\n  }\n\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_sycl_mem_sync(const Eigen::SyclDevice &sycl_device) {\n  IndexType size = 20;\n  array<IndexType, 1> tensorRange = {{size}};\n  Tensor<DataType, 1, DataLayout, IndexType> in1(tensorRange);\n  Tensor<DataType, 1, DataLayout, IndexType> in2(tensorRange);\n  Tensor<DataType, 1, DataLayout, IndexType> out(tensorRange);\n\n  in1 = in1.random();\n  in2 = in1;\n\n  DataType* gpu_data  = static_cast<DataType*>(sycl_device.allocate(in1.size()*sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 1, DataLayout, IndexType>> gpu1(gpu_data, tensorRange);\n  sycl_device.memcpyHostToDevice(gpu_data, in1.data(),(in1.size())*sizeof(DataType));\n  sycl_device.synchronize();\n  in1.setZero();\n\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_data, out.size()*sizeof(DataType));\n  sycl_device.synchronize();\n\n  for (IndexType i = 0; i < in1.size(); ++i) {\n    VERIFY_IS_APPROX(out(i), in2(i));\n  }\n\n  sycl_device.deallocate(gpu_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_sycl_mem_sync_offsets(const Eigen::SyclDevice &sycl_device) {\n  using tensor_type = Tensor<DataType, 1, DataLayout, IndexType>;\n  IndexType full_size = 32;\n  IndexType half_size = full_size / 2;\n  array<IndexType, 1> tensorRange = {{full_size}};\n  tensor_type in1(tensorRange);\n  tensor_type out(tensorRange);\n\n  DataType* gpu_data  = static_cast<DataType*>(sycl_device.allocate(full_size * sizeof(DataType)));\n  TensorMap<tensor_type> gpu1(gpu_data, tensorRange);\n\n  in1 = in1.random();\n  // Copy all data to device, then permute on copy back to host\n  sycl_device.memcpyHostToDevice(gpu_data, in1.data(), full_size * sizeof(DataType));\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_data + half_size, half_size * sizeof(DataType));\n  sycl_device.memcpyDeviceToHost(out.data() + half_size, gpu_data, half_size * sizeof(DataType));\n\n  for (IndexType i = 0; i < half_size; ++i) {\n    VERIFY_IS_APPROX(out(i), in1(i + half_size));\n    VERIFY_IS_APPROX(out(i + half_size), in1(i));\n  }\n\n  in1 = in1.random();\n  out.setZero();\n  // Permute copies to device, then copy all back to host\n  sycl_device.memcpyHostToDevice(gpu_data + half_size, in1.data(), half_size * sizeof(DataType));\n  sycl_device.memcpyHostToDevice(gpu_data, in1.data() + half_size, half_size * sizeof(DataType));\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_data, full_size * sizeof(DataType));\n\n  for (IndexType i = 0; i < half_size; ++i) {\n    VERIFY_IS_APPROX(out(i), in1(i + half_size));\n    VERIFY_IS_APPROX(out(i + half_size), in1(i));\n  }\n\n  in1 = in1.random();\n  out.setZero();\n  DataType* gpu_data_out  = static_cast<DataType*>(sycl_device.allocate(full_size * sizeof(DataType)));\n  TensorMap<tensor_type> gpu2(gpu_data_out, tensorRange);\n  // Copy all to device, permute copies on device, then copy all back to host\n  sycl_device.memcpyHostToDevice(gpu_data, in1.data(), full_size * sizeof(DataType));\n  sycl_device.memcpy(gpu_data_out + half_size, gpu_data, half_size * sizeof(DataType));\n  sycl_device.memcpy(gpu_data_out, gpu_data + half_size, half_size * sizeof(DataType));\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_data_out, full_size * sizeof(DataType));\n\n  for (IndexType i = 0; i < half_size; ++i) {\n    VERIFY_IS_APPROX(out(i), in1(i + half_size));\n    VERIFY_IS_APPROX(out(i + half_size), in1(i));\n  }\n\n  sycl_device.deallocate(gpu_data_out);\n  sycl_device.deallocate(gpu_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_sycl_memset_offsets(const Eigen::SyclDevice &sycl_device) {\n  using tensor_type = Tensor<DataType, 1, DataLayout, IndexType>;\n  IndexType full_size = 32;\n  IndexType half_size = full_size / 2;\n  array<IndexType, 1> tensorRange = {{full_size}};\n  tensor_type cpu_out(tensorRange);\n  tensor_type out(tensorRange);\n\n  cpu_out.setZero();\n\n  std::memset(cpu_out.data(), 0, half_size * sizeof(DataType));\n  std::memset(cpu_out.data() + half_size, 1, half_size * sizeof(DataType));\n\n  DataType* gpu_data  = static_cast<DataType*>(sycl_device.allocate(full_size * sizeof(DataType)));\n  TensorMap<tensor_type> gpu1(gpu_data, tensorRange);\n\n  sycl_device.memset(gpu_data, 0, half_size * sizeof(DataType));\n  sycl_device.memset(gpu_data + half_size, 1, half_size * sizeof(DataType));\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_data, full_size * sizeof(DataType));\n\n  for (IndexType i = 0; i < full_size; ++i) {\n    VERIFY_IS_APPROX(out(i), cpu_out(i));\n  }\n\n  sycl_device.deallocate(gpu_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_sycl_computations(const Eigen::SyclDevice &sycl_device) {\n\n  IndexType sizeDim1 = 100;\n  IndexType sizeDim2 = 10;\n  IndexType sizeDim3 = 20;\n  array<IndexType, 3> tensorRange = {{sizeDim1, sizeDim2, sizeDim3}};\n  Tensor<DataType, 3,DataLayout, IndexType> in1(tensorRange);\n  Tensor<DataType, 3,DataLayout, IndexType> in2(tensorRange);\n  Tensor<DataType, 3,DataLayout, IndexType> in3(tensorRange);\n  Tensor<DataType, 3,DataLayout, IndexType> out(tensorRange);\n\n  in2 = in2.random();\n  in3 = in3.random();\n\n  DataType * gpu_in1_data  = static_cast<DataType*>(sycl_device.allocate(in1.size()*sizeof(DataType)));\n  DataType * gpu_in2_data  = static_cast<DataType*>(sycl_device.allocate(in2.size()*sizeof(DataType)));\n  DataType * gpu_in3_data  = static_cast<DataType*>(sycl_device.allocate(in3.size()*sizeof(DataType)));\n  DataType * gpu_out_data =  static_cast<DataType*>(sycl_device.allocate(out.size()*sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu_in1(gpu_in1_data, tensorRange);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu_in2(gpu_in2_data, tensorRange);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu_in3(gpu_in3_data, tensorRange);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu_out(gpu_out_data, tensorRange);\n\n  /// a=1.2f\n  gpu_in1.device(sycl_device) = gpu_in1.constant(1.2f);\n  sycl_device.memcpyDeviceToHost(in1.data(), gpu_in1_data ,(in1.size())*sizeof(DataType));\n  sycl_device.synchronize();\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        VERIFY_IS_APPROX(in1(i,j,k), 1.2f);\n      }\n    }\n  }\n  printf(\"a=1.2f Test passed\\n\");\n\n  /// a=b*1.2f\n  gpu_out.device(sycl_device) = gpu_in1 * 1.2f;\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data ,(out.size())*sizeof(DataType));\n  sycl_device.synchronize();\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k),\n                         in1(i,j,k) * 1.2f);\n      }\n    }\n  }\n  printf(\"a=b*1.2f Test Passed\\n\");\n\n  /// c=a*b\n  sycl_device.memcpyHostToDevice(gpu_in2_data, in2.data(),(in2.size())*sizeof(DataType));\n  gpu_out.device(sycl_device) = gpu_in1 * gpu_in2;\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data,(out.size())*sizeof(DataType));\n  sycl_device.synchronize();\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k),\n                         in1(i,j,k) *\n                             in2(i,j,k));\n      }\n    }\n  }\n  printf(\"c=a*b Test Passed\\n\");\n\n  /// c=a+b\n  gpu_out.device(sycl_device) = gpu_in1 + gpu_in2;\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data,(out.size())*sizeof(DataType));\n  sycl_device.synchronize();\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k),\n                         in1(i,j,k) +\n                             in2(i,j,k));\n      }\n    }\n  }\n  printf(\"c=a+b Test Passed\\n\");\n\n  /// c=a*a\n  gpu_out.device(sycl_device) = gpu_in1 * gpu_in1;\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data,(out.size())*sizeof(DataType));\n  sycl_device.synchronize();\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k),\n                         in1(i,j,k) *\n                             in1(i,j,k));\n      }\n    }\n  }\n  printf(\"c= a*a Test Passed\\n\");\n\n  //a*3.14f + b*2.7f\n  gpu_out.device(sycl_device) =  gpu_in1 * gpu_in1.constant(3.14f) + gpu_in2 * gpu_in2.constant(2.7f);\n  sycl_device.memcpyDeviceToHost(out.data(),gpu_out_data,(out.size())*sizeof(DataType));\n  sycl_device.synchronize();\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k),\n                         in1(i,j,k) * 3.14f\n                       + in2(i,j,k) * 2.7f);\n      }\n    }\n  }\n  printf(\"a*3.14f + b*2.7f Test Passed\\n\");\n\n  ///d= (a>0.5? b:c)\n  sycl_device.memcpyHostToDevice(gpu_in3_data, in3.data(),(in3.size())*sizeof(DataType));\n  gpu_out.device(sycl_device) =(gpu_in1 > gpu_in1.constant(0.5f)).select(gpu_in2, gpu_in3);\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data,(out.size())*sizeof(DataType));\n  sycl_device.synchronize();\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        VERIFY_IS_APPROX(out(i, j, k), (in1(i, j, k) > 0.5f)\n                                                ? in2(i, j, k)\n                                                : in3(i, j, k));\n      }\n    }\n  }\n  printf(\"d= (a>0.5? b:c) Test Passed\\n\");\n  sycl_device.deallocate(gpu_in1_data);\n  sycl_device.deallocate(gpu_in2_data);\n  sycl_device.deallocate(gpu_in3_data);\n  sycl_device.deallocate(gpu_out_data);\n}\ntemplate<typename Scalar1, typename Scalar2,  int DataLayout, typename IndexType>\nstatic void test_sycl_cast(const Eigen::SyclDevice& sycl_device){\n    IndexType size = 20;\n    array<IndexType, 1> tensorRange = {{size}};\n    Tensor<Scalar1, 1, DataLayout, IndexType> in(tensorRange);\n    Tensor<Scalar2, 1, DataLayout, IndexType> out(tensorRange);\n    Tensor<Scalar2, 1, DataLayout, IndexType> out_host(tensorRange);\n\n    in = in.random();\n\n    Scalar1* gpu_in_data  = static_cast<Scalar1*>(sycl_device.allocate(in.size()*sizeof(Scalar1)));\n    Scalar2 * gpu_out_data =  static_cast<Scalar2*>(sycl_device.allocate(out.size()*sizeof(Scalar2)));\n\n    TensorMap<Tensor<Scalar1, 1, DataLayout, IndexType>> gpu_in(gpu_in_data, tensorRange);\n    TensorMap<Tensor<Scalar2, 1, DataLayout, IndexType>> gpu_out(gpu_out_data, tensorRange);\n    sycl_device.memcpyHostToDevice(gpu_in_data, in.data(),(in.size())*sizeof(Scalar1));\n    gpu_out.device(sycl_device) = gpu_in. template cast<Scalar2>();\n    sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data, out.size()*sizeof(Scalar2));\n    out_host = in. template cast<Scalar2>();\n    for(IndexType i=0; i< size; i++)\n    {\n      VERIFY_IS_APPROX(out(i), out_host(i));\n    }\n    printf(\"cast Test Passed\\n\");\n    sycl_device.deallocate(gpu_in_data);\n    sycl_device.deallocate(gpu_out_data);\n}\ntemplate<typename DataType, typename dev_Selector> void sycl_computing_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_sycl_mem_transfers<DataType, RowMajor, int64_t>(sycl_device);\n  test_sycl_computations<DataType, RowMajor, int64_t>(sycl_device);\n  test_sycl_mem_sync<DataType, RowMajor, int64_t>(sycl_device);\n  test_sycl_mem_sync_offsets<DataType, RowMajor, int64_t>(sycl_device);\n  test_sycl_memset_offsets<DataType, RowMajor, int64_t>(sycl_device);\n  test_sycl_mem_transfers<DataType, ColMajor, int64_t>(sycl_device);\n  test_sycl_computations<DataType, ColMajor, int64_t>(sycl_device);\n  test_sycl_mem_sync<DataType, ColMajor, int64_t>(sycl_device);\n  test_sycl_cast<DataType, int, RowMajor, int64_t>(sycl_device);\n  test_sycl_cast<DataType, int, ColMajor, int64_t>(sycl_device);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_computing_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_symmetry.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n#include <Eigen/CXX11/TensorSymmetry>\n\n#include <map>\n#include <set>\n\nusing Eigen::Tensor;\nusing Eigen::SGroup;\nusing Eigen::DynamicSGroup;\nusing Eigen::StaticSGroup;\nusing Eigen::Symmetry;\nusing Eigen::AntiSymmetry;\nusing Eigen::Hermiticity;\nusing Eigen::AntiHermiticity;\n\nusing Eigen::NegationFlag;\nusing Eigen::ConjugationFlag;\nusing Eigen::GlobalZeroFlag;\nusing Eigen::GlobalRealFlag;\nusing Eigen::GlobalImagFlag;\n\n// helper function to determine if the compiler intantiated a static\n// or dynamic symmetry group\ntemplate<typename... Sym>\nbool isDynGroup(StaticSGroup<Sym...> const& dummy)\n{\n  (void)dummy;\n  return false;\n}\n\nbool isDynGroup(DynamicSGroup const& dummy)\n{\n  (void)dummy;\n  return true;\n}\n\n// helper class for checking that the symmetry groups are correct\nstruct checkIdx {\n  template<typename ArrType>\n  static inline int doCheck_(ArrType e, int flags, int dummy, std::set<uint64_t>& found, std::map<uint64_t, int> const& expected)\n  {\n    // use decimal representation of value\n    uint64_t value = e[0];\n    for (std::size_t i = 1; i < e.size(); i++)\n      value = value * 10 + e[i];\n\n    // we want to make sure that we find each element\n    auto it = expected.find(value);\n    VERIFY((it != expected.end()));\n    VERIFY_IS_EQUAL(it->second, flags);\n\n    // we want to make sure we only have each element once;\n    // set::insert returns true for the second part of the pair\n    // if the element was really inserted and not already there\n    auto p = found.insert(value);\n    VERIFY((p.second));\n\n    return dummy;\n  }\n\n  static inline int run(std::vector<int> e, int flags, int dummy, std::set<uint64_t>& found, std::map<uint64_t, int> const& expected)\n  {\n    return doCheck_(e, flags, dummy, found, expected);\n  }\n\n  template<std::size_t N>\n  static inline int run(std::array<int, N> e, int flags, int dummy, std::set<uint64_t>& found, std::map<uint64_t, int> const& expected)\n  {\n    return doCheck_(e, flags, dummy, found, expected);\n  }\n};\n\nstatic void test_symgroups_static()\n{\n  std::array<int, 7> identity{{0,1,2,3,4,5,6}};\n\n  // Simple static symmetry group\n  StaticSGroup<\n    AntiSymmetry<0,1>,\n    Hermiticity<0,2>\n  > group;\n\n  std::set<uint64_t> found;\n  std::map<uint64_t, int> expected;\n  expected[ 123456] = 0;\n  expected[1023456] = NegationFlag;\n  expected[2103456] = ConjugationFlag;\n  expected[1203456] = ConjugationFlag | NegationFlag;\n  expected[2013456] = ConjugationFlag | NegationFlag;\n  expected[ 213456] = ConjugationFlag;\n\n  VERIFY_IS_EQUAL(group.size(), 6u);\n  VERIFY_IS_EQUAL(group.globalFlags(), GlobalImagFlag);\n  group.apply<checkIdx, int>(identity, 0, found, expected);\n  VERIFY_IS_EQUAL(found.size(), 6u);\n}\n\nstatic void test_symgroups_dynamic()\n{\n  std::vector<int> identity;\n  for (int i = 0; i <= 6; i++)\n    identity.push_back(i);\n\n  // Simple dynamic symmetry group\n  DynamicSGroup group;\n  group.add(0,1,NegationFlag);\n  group.add(0,2,ConjugationFlag);\n\n  VERIFY_IS_EQUAL(group.size(), 6u);\n  VERIFY_IS_EQUAL(group.globalFlags(), GlobalImagFlag);\n\n  std::set<uint64_t> found;\n  std::map<uint64_t, int> expected;\n  expected[ 123456] = 0;\n  expected[1023456] = NegationFlag;\n  expected[2103456] = ConjugationFlag;\n  expected[1203456] = ConjugationFlag | NegationFlag;\n  expected[2013456] = ConjugationFlag | NegationFlag;\n  expected[ 213456] = ConjugationFlag;\n\n  VERIFY_IS_EQUAL(group.size(), 6u);\n  VERIFY_IS_EQUAL(group.globalFlags(), GlobalImagFlag);\n  group.apply<checkIdx, int>(identity, 0, found, expected);\n  VERIFY_IS_EQUAL(found.size(), 6u);\n}\n\nstatic void test_symgroups_selection()\n{\n  std::array<int, 7> identity7{{0,1,2,3,4,5,6}};\n  std::array<int, 10> identity10{{0,1,2,3,4,5,6,7,8,9}};\n\n  {\n    // Do the same test as in test_symgroups_static but\n    // require selection via SGroup\n    SGroup<\n      AntiSymmetry<0,1>,\n      Hermiticity<0,2>\n    > group;\n\n    std::set<uint64_t> found;\n    std::map<uint64_t, int> expected;\n    expected[ 123456] = 0;\n    expected[1023456] = NegationFlag;\n    expected[2103456] = ConjugationFlag;\n    expected[1203456] = ConjugationFlag | NegationFlag;\n    expected[2013456] = ConjugationFlag | NegationFlag;\n    expected[ 213456] = ConjugationFlag;\n\n    VERIFY(!isDynGroup(group));\n    VERIFY_IS_EQUAL(group.size(), 6u);\n    VERIFY_IS_EQUAL(group.globalFlags(), GlobalImagFlag);\n    group.apply<checkIdx, int>(identity7, 0, found, expected);\n    VERIFY_IS_EQUAL(found.size(), 6u);\n  }\n\n  {\n    // simple factorizing group: 5 generators, 2^5 = 32 elements\n    // selection should make this dynamic, although static group\n    // can still be reasonably generated\n    SGroup<\n      Symmetry<0,1>,\n      Symmetry<2,3>,\n      Symmetry<4,5>,\n      Symmetry<6,7>,\n      Symmetry<8,9>\n    > group;\n\n    std::set<uint64_t> found;\n    std::map<uint64_t, int> expected;\n    expected[ 123456789] = 0; expected[ 123456798] = 0; expected[ 123457689] = 0; expected[ 123457698] = 0;\n    expected[ 123546789] = 0; expected[ 123546798] = 0; expected[ 123547689] = 0; expected[ 123547698] = 0;\n    expected[ 132456789] = 0; expected[ 132456798] = 0; expected[ 132457689] = 0; expected[ 132457698] = 0;\n    expected[ 132546789] = 0; expected[ 132546798] = 0; expected[ 132547689] = 0; expected[ 132547698] = 0;\n    expected[1023456789] = 0; expected[1023456798] = 0; expected[1023457689] = 0; expected[1023457698] = 0;\n    expected[1023546789] = 0; expected[1023546798] = 0; expected[1023547689] = 0; expected[1023547698] = 0;\n    expected[1032456789] = 0; expected[1032456798] = 0; expected[1032457689] = 0; expected[1032457698] = 0;\n    expected[1032546789] = 0; expected[1032546798] = 0; expected[1032547689] = 0; expected[1032547698] = 0;\n\n    VERIFY(isDynGroup(group));\n    VERIFY_IS_EQUAL(group.size(), 32u);\n    VERIFY_IS_EQUAL(group.globalFlags(), 0);\n    group.apply<checkIdx, int>(identity10, 0, found, expected);\n    VERIFY_IS_EQUAL(found.size(), 32u);\n\n    // no verify that we could also generate a static group\n    // with these generators\n    found.clear();\n    StaticSGroup<\n      Symmetry<0,1>,\n      Symmetry<2,3>,\n      Symmetry<4,5>,\n      Symmetry<6,7>,\n      Symmetry<8,9>\n    > group_static;\n    VERIFY_IS_EQUAL(group_static.size(), 32u);\n    VERIFY_IS_EQUAL(group_static.globalFlags(), 0);\n    group_static.apply<checkIdx, int>(identity10, 0, found, expected);\n    VERIFY_IS_EQUAL(found.size(), 32u);\n  }\n\n  {\n    // try to create a HUGE group\n    SGroup<\n      Symmetry<0,1>,\n      Symmetry<1,2>,\n      Symmetry<2,3>,\n      Symmetry<3,4>,\n      Symmetry<4,5>,\n      Symmetry<5,6>\n    > group;\n\n    std::set<uint64_t> found;\n    uint64_t pre_expected[5040] = {\n       123456, 1023456,  213456, 2013456, 1203456, 2103456,  132456, 1032456,  312456, 3012456, 1302456, 3102456,\n       231456, 2031456,  321456, 3021456, 2301456, 3201456, 1230456, 2130456, 1320456, 3120456, 2310456, 3210456,\n       124356, 1024356,  214356, 2014356, 1204356, 2104356,  142356, 1042356,  412356, 4012356, 1402356, 4102356,\n       241356, 2041356,  421356, 4021356, 2401356, 4201356, 1240356, 2140356, 1420356, 4120356, 2410356, 4210356,\n       134256, 1034256,  314256, 3014256, 1304256, 3104256,  143256, 1043256,  413256, 4013256, 1403256, 4103256,\n       341256, 3041256,  431256, 4031256, 3401256, 4301256, 1340256, 3140256, 1430256, 4130256, 3410256, 4310256,\n       234156, 2034156,  324156, 3024156, 2304156, 3204156,  243156, 2043156,  423156, 4023156, 2403156, 4203156,\n       342156, 3042156,  432156, 4032156, 3402156, 4302156, 2340156, 3240156, 2430156, 4230156, 3420156, 4320156,\n      1234056, 2134056, 1324056, 3124056, 2314056, 3214056, 1243056, 2143056, 1423056, 4123056, 2413056, 4213056,\n      1342056, 3142056, 1432056, 4132056, 3412056, 4312056, 2341056, 3241056, 2431056, 4231056, 3421056, 4321056,\n       123546, 1023546,  213546, 2013546, 1203546, 2103546,  132546, 1032546,  312546, 3012546, 1302546, 3102546,\n       231546, 2031546,  321546, 3021546, 2301546, 3201546, 1230546, 2130546, 1320546, 3120546, 2310546, 3210546,\n       125346, 1025346,  215346, 2015346, 1205346, 2105346,  152346, 1052346,  512346, 5012346, 1502346, 5102346,\n       251346, 2051346,  521346, 5021346, 2501346, 5201346, 1250346, 2150346, 1520346, 5120346, 2510346, 5210346,\n       135246, 1035246,  315246, 3015246, 1305246, 3105246,  153246, 1053246,  513246, 5013246, 1503246, 5103246,\n       351246, 3051246,  531246, 5031246, 3501246, 5301246, 1350246, 3150246, 1530246, 5130246, 3510246, 5310246,\n       235146, 2035146,  325146, 3025146, 2305146, 3205146,  253146, 2053146,  523146, 5023146, 2503146, 5203146,\n       352146, 3052146,  532146, 5032146, 3502146, 5302146, 2350146, 3250146, 2530146, 5230146, 3520146, 5320146,\n      1235046, 2135046, 1325046, 3125046, 2315046, 3215046, 1253046, 2153046, 1523046, 5123046, 2513046, 5213046,\n      1352046, 3152046, 1532046, 5132046, 3512046, 5312046, 2351046, 3251046, 2531046, 5231046, 3521046, 5321046,\n       124536, 1024536,  214536, 2014536, 1204536, 2104536,  142536, 1042536,  412536, 4012536, 1402536, 4102536,\n       241536, 2041536,  421536, 4021536, 2401536, 4201536, 1240536, 2140536, 1420536, 4120536, 2410536, 4210536,\n       125436, 1025436,  215436, 2015436, 1205436, 2105436,  152436, 1052436,  512436, 5012436, 1502436, 5102436,\n       251436, 2051436,  521436, 5021436, 2501436, 5201436, 1250436, 2150436, 1520436, 5120436, 2510436, 5210436,\n       145236, 1045236,  415236, 4015236, 1405236, 4105236,  154236, 1054236,  514236, 5014236, 1504236, 5104236,\n       451236, 4051236,  541236, 5041236, 4501236, 5401236, 1450236, 4150236, 1540236, 5140236, 4510236, 5410236,\n       245136, 2045136,  425136, 4025136, 2405136, 4205136,  254136, 2054136,  524136, 5024136, 2504136, 5204136,\n       452136, 4052136,  542136, 5042136, 4502136, 5402136, 2450136, 4250136, 2540136, 5240136, 4520136, 5420136,\n      1245036, 2145036, 1425036, 4125036, 2415036, 4215036, 1254036, 2154036, 1524036, 5124036, 2514036, 5214036,\n      1452036, 4152036, 1542036, 5142036, 4512036, 5412036, 2451036, 4251036, 2541036, 5241036, 4521036, 5421036,\n       134526, 1034526,  314526, 3014526, 1304526, 3104526,  143526, 1043526,  413526, 4013526, 1403526, 4103526,\n       341526, 3041526,  431526, 4031526, 3401526, 4301526, 1340526, 3140526, 1430526, 4130526, 3410526, 4310526,\n       135426, 1035426,  315426, 3015426, 1305426, 3105426,  153426, 1053426,  513426, 5013426, 1503426, 5103426,\n       351426, 3051426,  531426, 5031426, 3501426, 5301426, 1350426, 3150426, 1530426, 5130426, 3510426, 5310426,\n       145326, 1045326,  415326, 4015326, 1405326, 4105326,  154326, 1054326,  514326, 5014326, 1504326, 5104326,\n       451326, 4051326,  541326, 5041326, 4501326, 5401326, 1450326, 4150326, 1540326, 5140326, 4510326, 5410326,\n       345126, 3045126,  435126, 4035126, 3405126, 4305126,  354126, 3054126,  534126, 5034126, 3504126, 5304126,\n       453126, 4053126,  543126, 5043126, 4503126, 5403126, 3450126, 4350126, 3540126, 5340126, 4530126, 5430126,\n      1345026, 3145026, 1435026, 4135026, 3415026, 4315026, 1354026, 3154026, 1534026, 5134026, 3514026, 5314026,\n      1453026, 4153026, 1543026, 5143026, 4513026, 5413026, 3451026, 4351026, 3541026, 5341026, 4531026, 5431026,\n       234516, 2034516,  324516, 3024516, 2304516, 3204516,  243516, 2043516,  423516, 4023516, 2403516, 4203516,\n       342516, 3042516,  432516, 4032516, 3402516, 4302516, 2340516, 3240516, 2430516, 4230516, 3420516, 4320516,\n       235416, 2035416,  325416, 3025416, 2305416, 3205416,  253416, 2053416,  523416, 5023416, 2503416, 5203416,\n       352416, 3052416,  532416, 5032416, 3502416, 5302416, 2350416, 3250416, 2530416, 5230416, 3520416, 5320416,\n       245316, 2045316,  425316, 4025316, 2405316, 4205316,  254316, 2054316,  524316, 5024316, 2504316, 5204316,\n       452316, 4052316,  542316, 5042316, 4502316, 5402316, 2450316, 4250316, 2540316, 5240316, 4520316, 5420316,\n       345216, 3045216,  435216, 4035216, 3405216, 4305216,  354216, 3054216,  534216, 5034216, 3504216, 5304216,\n       453216, 4053216,  543216, 5043216, 4503216, 5403216, 3450216, 4350216, 3540216, 5340216, 4530216, 5430216,\n      2345016, 3245016, 2435016, 4235016, 3425016, 4325016, 2354016, 3254016, 2534016, 5234016, 3524016, 5324016,\n      2453016, 4253016, 2543016, 5243016, 4523016, 5423016, 3452016, 4352016, 3542016, 5342016, 4532016, 5432016,\n      1234506, 2134506, 1324506, 3124506, 2314506, 3214506, 1243506, 2143506, 1423506, 4123506, 2413506, 4213506,\n      1342506, 3142506, 1432506, 4132506, 3412506, 4312506, 2341506, 3241506, 2431506, 4231506, 3421506, 4321506,\n      1235406, 2135406, 1325406, 3125406, 2315406, 3215406, 1253406, 2153406, 1523406, 5123406, 2513406, 5213406,\n      1352406, 3152406, 1532406, 5132406, 3512406, 5312406, 2351406, 3251406, 2531406, 5231406, 3521406, 5321406,\n      1245306, 2145306, 1425306, 4125306, 2415306, 4215306, 1254306, 2154306, 1524306, 5124306, 2514306, 5214306,\n      1452306, 4152306, 1542306, 5142306, 4512306, 5412306, 2451306, 4251306, 2541306, 5241306, 4521306, 5421306,\n      1345206, 3145206, 1435206, 4135206, 3415206, 4315206, 1354206, 3154206, 1534206, 5134206, 3514206, 5314206,\n      1453206, 4153206, 1543206, 5143206, 4513206, 5413206, 3451206, 4351206, 3541206, 5341206, 4531206, 5431206,\n      2345106, 3245106, 2435106, 4235106, 3425106, 4325106, 2354106, 3254106, 2534106, 5234106, 3524106, 5324106,\n      2453106, 4253106, 2543106, 5243106, 4523106, 5423106, 3452106, 4352106, 3542106, 5342106, 4532106, 5432106,\n       123465, 1023465,  213465, 2013465, 1203465, 2103465,  132465, 1032465,  312465, 3012465, 1302465, 3102465,\n       231465, 2031465,  321465, 3021465, 2301465, 3201465, 1230465, 2130465, 1320465, 3120465, 2310465, 3210465,\n       124365, 1024365,  214365, 2014365, 1204365, 2104365,  142365, 1042365,  412365, 4012365, 1402365, 4102365,\n       241365, 2041365,  421365, 4021365, 2401365, 4201365, 1240365, 2140365, 1420365, 4120365, 2410365, 4210365,\n       134265, 1034265,  314265, 3014265, 1304265, 3104265,  143265, 1043265,  413265, 4013265, 1403265, 4103265,\n       341265, 3041265,  431265, 4031265, 3401265, 4301265, 1340265, 3140265, 1430265, 4130265, 3410265, 4310265,\n       234165, 2034165,  324165, 3024165, 2304165, 3204165,  243165, 2043165,  423165, 4023165, 2403165, 4203165,\n       342165, 3042165,  432165, 4032165, 3402165, 4302165, 2340165, 3240165, 2430165, 4230165, 3420165, 4320165,\n      1234065, 2134065, 1324065, 3124065, 2314065, 3214065, 1243065, 2143065, 1423065, 4123065, 2413065, 4213065,\n      1342065, 3142065, 1432065, 4132065, 3412065, 4312065, 2341065, 3241065, 2431065, 4231065, 3421065, 4321065,\n       123645, 1023645,  213645, 2013645, 1203645, 2103645,  132645, 1032645,  312645, 3012645, 1302645, 3102645,\n       231645, 2031645,  321645, 3021645, 2301645, 3201645, 1230645, 2130645, 1320645, 3120645, 2310645, 3210645,\n       126345, 1026345,  216345, 2016345, 1206345, 2106345,  162345, 1062345,  612345, 6012345, 1602345, 6102345,\n       261345, 2061345,  621345, 6021345, 2601345, 6201345, 1260345, 2160345, 1620345, 6120345, 2610345, 6210345,\n       136245, 1036245,  316245, 3016245, 1306245, 3106245,  163245, 1063245,  613245, 6013245, 1603245, 6103245,\n       361245, 3061245,  631245, 6031245, 3601245, 6301245, 1360245, 3160245, 1630245, 6130245, 3610245, 6310245,\n       236145, 2036145,  326145, 3026145, 2306145, 3206145,  263145, 2063145,  623145, 6023145, 2603145, 6203145,\n       362145, 3062145,  632145, 6032145, 3602145, 6302145, 2360145, 3260145, 2630145, 6230145, 3620145, 6320145,\n      1236045, 2136045, 1326045, 3126045, 2316045, 3216045, 1263045, 2163045, 1623045, 6123045, 2613045, 6213045,\n      1362045, 3162045, 1632045, 6132045, 3612045, 6312045, 2361045, 3261045, 2631045, 6231045, 3621045, 6321045,\n       124635, 1024635,  214635, 2014635, 1204635, 2104635,  142635, 1042635,  412635, 4012635, 1402635, 4102635,\n       241635, 2041635,  421635, 4021635, 2401635, 4201635, 1240635, 2140635, 1420635, 4120635, 2410635, 4210635,\n       126435, 1026435,  216435, 2016435, 1206435, 2106435,  162435, 1062435,  612435, 6012435, 1602435, 6102435,\n       261435, 2061435,  621435, 6021435, 2601435, 6201435, 1260435, 2160435, 1620435, 6120435, 2610435, 6210435,\n       146235, 1046235,  416235, 4016235, 1406235, 4106235,  164235, 1064235,  614235, 6014235, 1604235, 6104235,\n       461235, 4061235,  641235, 6041235, 4601235, 6401235, 1460235, 4160235, 1640235, 6140235, 4610235, 6410235,\n       246135, 2046135,  426135, 4026135, 2406135, 4206135,  264135, 2064135,  624135, 6024135, 2604135, 6204135,\n       462135, 4062135,  642135, 6042135, 4602135, 6402135, 2460135, 4260135, 2640135, 6240135, 4620135, 6420135,\n      1246035, 2146035, 1426035, 4126035, 2416035, 4216035, 1264035, 2164035, 1624035, 6124035, 2614035, 6214035,\n      1462035, 4162035, 1642035, 6142035, 4612035, 6412035, 2461035, 4261035, 2641035, 6241035, 4621035, 6421035,\n       134625, 1034625,  314625, 3014625, 1304625, 3104625,  143625, 1043625,  413625, 4013625, 1403625, 4103625,\n       341625, 3041625,  431625, 4031625, 3401625, 4301625, 1340625, 3140625, 1430625, 4130625, 3410625, 4310625,\n       136425, 1036425,  316425, 3016425, 1306425, 3106425,  163425, 1063425,  613425, 6013425, 1603425, 6103425,\n       361425, 3061425,  631425, 6031425, 3601425, 6301425, 1360425, 3160425, 1630425, 6130425, 3610425, 6310425,\n       146325, 1046325,  416325, 4016325, 1406325, 4106325,  164325, 1064325,  614325, 6014325, 1604325, 6104325,\n       461325, 4061325,  641325, 6041325, 4601325, 6401325, 1460325, 4160325, 1640325, 6140325, 4610325, 6410325,\n       346125, 3046125,  436125, 4036125, 3406125, 4306125,  364125, 3064125,  634125, 6034125, 3604125, 6304125,\n       463125, 4063125,  643125, 6043125, 4603125, 6403125, 3460125, 4360125, 3640125, 6340125, 4630125, 6430125,\n      1346025, 3146025, 1436025, 4136025, 3416025, 4316025, 1364025, 3164025, 1634025, 6134025, 3614025, 6314025,\n      1463025, 4163025, 1643025, 6143025, 4613025, 6413025, 3461025, 4361025, 3641025, 6341025, 4631025, 6431025,\n       234615, 2034615,  324615, 3024615, 2304615, 3204615,  243615, 2043615,  423615, 4023615, 2403615, 4203615,\n       342615, 3042615,  432615, 4032615, 3402615, 4302615, 2340615, 3240615, 2430615, 4230615, 3420615, 4320615,\n       236415, 2036415,  326415, 3026415, 2306415, 3206415,  263415, 2063415,  623415, 6023415, 2603415, 6203415,\n       362415, 3062415,  632415, 6032415, 3602415, 6302415, 2360415, 3260415, 2630415, 6230415, 3620415, 6320415,\n       246315, 2046315,  426315, 4026315, 2406315, 4206315,  264315, 2064315,  624315, 6024315, 2604315, 6204315,\n       462315, 4062315,  642315, 6042315, 4602315, 6402315, 2460315, 4260315, 2640315, 6240315, 4620315, 6420315,\n       346215, 3046215,  436215, 4036215, 3406215, 4306215,  364215, 3064215,  634215, 6034215, 3604215, 6304215,\n       463215, 4063215,  643215, 6043215, 4603215, 6403215, 3460215, 4360215, 3640215, 6340215, 4630215, 6430215,\n      2346015, 3246015, 2436015, 4236015, 3426015, 4326015, 2364015, 3264015, 2634015, 6234015, 3624015, 6324015,\n      2463015, 4263015, 2643015, 6243015, 4623015, 6423015, 3462015, 4362015, 3642015, 6342015, 4632015, 6432015,\n      1234605, 2134605, 1324605, 3124605, 2314605, 3214605, 1243605, 2143605, 1423605, 4123605, 2413605, 4213605,\n      1342605, 3142605, 1432605, 4132605, 3412605, 4312605, 2341605, 3241605, 2431605, 4231605, 3421605, 4321605,\n      1236405, 2136405, 1326405, 3126405, 2316405, 3216405, 1263405, 2163405, 1623405, 6123405, 2613405, 6213405,\n      1362405, 3162405, 1632405, 6132405, 3612405, 6312405, 2361405, 3261405, 2631405, 6231405, 3621405, 6321405,\n      1246305, 2146305, 1426305, 4126305, 2416305, 4216305, 1264305, 2164305, 1624305, 6124305, 2614305, 6214305,\n      1462305, 4162305, 1642305, 6142305, 4612305, 6412305, 2461305, 4261305, 2641305, 6241305, 4621305, 6421305,\n      1346205, 3146205, 1436205, 4136205, 3416205, 4316205, 1364205, 3164205, 1634205, 6134205, 3614205, 6314205,\n      1463205, 4163205, 1643205, 6143205, 4613205, 6413205, 3461205, 4361205, 3641205, 6341205, 4631205, 6431205,\n      2346105, 3246105, 2436105, 4236105, 3426105, 4326105, 2364105, 3264105, 2634105, 6234105, 3624105, 6324105,\n      2463105, 4263105, 2643105, 6243105, 4623105, 6423105, 3462105, 4362105, 3642105, 6342105, 4632105, 6432105,\n       123564, 1023564,  213564, 2013564, 1203564, 2103564,  132564, 1032564,  312564, 3012564, 1302564, 3102564,\n       231564, 2031564,  321564, 3021564, 2301564, 3201564, 1230564, 2130564, 1320564, 3120564, 2310564, 3210564,\n       125364, 1025364,  215364, 2015364, 1205364, 2105364,  152364, 1052364,  512364, 5012364, 1502364, 5102364,\n       251364, 2051364,  521364, 5021364, 2501364, 5201364, 1250364, 2150364, 1520364, 5120364, 2510364, 5210364,\n       135264, 1035264,  315264, 3015264, 1305264, 3105264,  153264, 1053264,  513264, 5013264, 1503264, 5103264,\n       351264, 3051264,  531264, 5031264, 3501264, 5301264, 1350264, 3150264, 1530264, 5130264, 3510264, 5310264,\n       235164, 2035164,  325164, 3025164, 2305164, 3205164,  253164, 2053164,  523164, 5023164, 2503164, 5203164,\n       352164, 3052164,  532164, 5032164, 3502164, 5302164, 2350164, 3250164, 2530164, 5230164, 3520164, 5320164,\n      1235064, 2135064, 1325064, 3125064, 2315064, 3215064, 1253064, 2153064, 1523064, 5123064, 2513064, 5213064,\n      1352064, 3152064, 1532064, 5132064, 3512064, 5312064, 2351064, 3251064, 2531064, 5231064, 3521064, 5321064,\n       123654, 1023654,  213654, 2013654, 1203654, 2103654,  132654, 1032654,  312654, 3012654, 1302654, 3102654,\n       231654, 2031654,  321654, 3021654, 2301654, 3201654, 1230654, 2130654, 1320654, 3120654, 2310654, 3210654,\n       126354, 1026354,  216354, 2016354, 1206354, 2106354,  162354, 1062354,  612354, 6012354, 1602354, 6102354,\n       261354, 2061354,  621354, 6021354, 2601354, 6201354, 1260354, 2160354, 1620354, 6120354, 2610354, 6210354,\n       136254, 1036254,  316254, 3016254, 1306254, 3106254,  163254, 1063254,  613254, 6013254, 1603254, 6103254,\n       361254, 3061254,  631254, 6031254, 3601254, 6301254, 1360254, 3160254, 1630254, 6130254, 3610254, 6310254,\n       236154, 2036154,  326154, 3026154, 2306154, 3206154,  263154, 2063154,  623154, 6023154, 2603154, 6203154,\n       362154, 3062154,  632154, 6032154, 3602154, 6302154, 2360154, 3260154, 2630154, 6230154, 3620154, 6320154,\n      1236054, 2136054, 1326054, 3126054, 2316054, 3216054, 1263054, 2163054, 1623054, 6123054, 2613054, 6213054,\n      1362054, 3162054, 1632054, 6132054, 3612054, 6312054, 2361054, 3261054, 2631054, 6231054, 3621054, 6321054,\n       125634, 1025634,  215634, 2015634, 1205634, 2105634,  152634, 1052634,  512634, 5012634, 1502634, 5102634,\n       251634, 2051634,  521634, 5021634, 2501634, 5201634, 1250634, 2150634, 1520634, 5120634, 2510634, 5210634,\n       126534, 1026534,  216534, 2016534, 1206534, 2106534,  162534, 1062534,  612534, 6012534, 1602534, 6102534,\n       261534, 2061534,  621534, 6021534, 2601534, 6201534, 1260534, 2160534, 1620534, 6120534, 2610534, 6210534,\n       156234, 1056234,  516234, 5016234, 1506234, 5106234,  165234, 1065234,  615234, 6015234, 1605234, 6105234,\n       561234, 5061234,  651234, 6051234, 5601234, 6501234, 1560234, 5160234, 1650234, 6150234, 5610234, 6510234,\n       256134, 2056134,  526134, 5026134, 2506134, 5206134,  265134, 2065134,  625134, 6025134, 2605134, 6205134,\n       562134, 5062134,  652134, 6052134, 5602134, 6502134, 2560134, 5260134, 2650134, 6250134, 5620134, 6520134,\n      1256034, 2156034, 1526034, 5126034, 2516034, 5216034, 1265034, 2165034, 1625034, 6125034, 2615034, 6215034,\n      1562034, 5162034, 1652034, 6152034, 5612034, 6512034, 2561034, 5261034, 2651034, 6251034, 5621034, 6521034,\n       135624, 1035624,  315624, 3015624, 1305624, 3105624,  153624, 1053624,  513624, 5013624, 1503624, 5103624,\n       351624, 3051624,  531624, 5031624, 3501624, 5301624, 1350624, 3150624, 1530624, 5130624, 3510624, 5310624,\n       136524, 1036524,  316524, 3016524, 1306524, 3106524,  163524, 1063524,  613524, 6013524, 1603524, 6103524,\n       361524, 3061524,  631524, 6031524, 3601524, 6301524, 1360524, 3160524, 1630524, 6130524, 3610524, 6310524,\n       156324, 1056324,  516324, 5016324, 1506324, 5106324,  165324, 1065324,  615324, 6015324, 1605324, 6105324,\n       561324, 5061324,  651324, 6051324, 5601324, 6501324, 1560324, 5160324, 1650324, 6150324, 5610324, 6510324,\n       356124, 3056124,  536124, 5036124, 3506124, 5306124,  365124, 3065124,  635124, 6035124, 3605124, 6305124,\n       563124, 5063124,  653124, 6053124, 5603124, 6503124, 3560124, 5360124, 3650124, 6350124, 5630124, 6530124,\n      1356024, 3156024, 1536024, 5136024, 3516024, 5316024, 1365024, 3165024, 1635024, 6135024, 3615024, 6315024,\n      1563024, 5163024, 1653024, 6153024, 5613024, 6513024, 3561024, 5361024, 3651024, 6351024, 5631024, 6531024,\n       235614, 2035614,  325614, 3025614, 2305614, 3205614,  253614, 2053614,  523614, 5023614, 2503614, 5203614,\n       352614, 3052614,  532614, 5032614, 3502614, 5302614, 2350614, 3250614, 2530614, 5230614, 3520614, 5320614,\n       236514, 2036514,  326514, 3026514, 2306514, 3206514,  263514, 2063514,  623514, 6023514, 2603514, 6203514,\n       362514, 3062514,  632514, 6032514, 3602514, 6302514, 2360514, 3260514, 2630514, 6230514, 3620514, 6320514,\n       256314, 2056314,  526314, 5026314, 2506314, 5206314,  265314, 2065314,  625314, 6025314, 2605314, 6205314,\n       562314, 5062314,  652314, 6052314, 5602314, 6502314, 2560314, 5260314, 2650314, 6250314, 5620314, 6520314,\n       356214, 3056214,  536214, 5036214, 3506214, 5306214,  365214, 3065214,  635214, 6035214, 3605214, 6305214,\n       563214, 5063214,  653214, 6053214, 5603214, 6503214, 3560214, 5360214, 3650214, 6350214, 5630214, 6530214,\n      2356014, 3256014, 2536014, 5236014, 3526014, 5326014, 2365014, 3265014, 2635014, 6235014, 3625014, 6325014,\n      2563014, 5263014, 2653014, 6253014, 5623014, 6523014, 3562014, 5362014, 3652014, 6352014, 5632014, 6532014,\n      1235604, 2135604, 1325604, 3125604, 2315604, 3215604, 1253604, 2153604, 1523604, 5123604, 2513604, 5213604,\n      1352604, 3152604, 1532604, 5132604, 3512604, 5312604, 2351604, 3251604, 2531604, 5231604, 3521604, 5321604,\n      1236504, 2136504, 1326504, 3126504, 2316504, 3216504, 1263504, 2163504, 1623504, 6123504, 2613504, 6213504,\n      1362504, 3162504, 1632504, 6132504, 3612504, 6312504, 2361504, 3261504, 2631504, 6231504, 3621504, 6321504,\n      1256304, 2156304, 1526304, 5126304, 2516304, 5216304, 1265304, 2165304, 1625304, 6125304, 2615304, 6215304,\n      1562304, 5162304, 1652304, 6152304, 5612304, 6512304, 2561304, 5261304, 2651304, 6251304, 5621304, 6521304,\n      1356204, 3156204, 1536204, 5136204, 3516204, 5316204, 1365204, 3165204, 1635204, 6135204, 3615204, 6315204,\n      1563204, 5163204, 1653204, 6153204, 5613204, 6513204, 3561204, 5361204, 3651204, 6351204, 5631204, 6531204,\n      2356104, 3256104, 2536104, 5236104, 3526104, 5326104, 2365104, 3265104, 2635104, 6235104, 3625104, 6325104,\n      2563104, 5263104, 2653104, 6253104, 5623104, 6523104, 3562104, 5362104, 3652104, 6352104, 5632104, 6532104,\n       124563, 1024563,  214563, 2014563, 1204563, 2104563,  142563, 1042563,  412563, 4012563, 1402563, 4102563,\n       241563, 2041563,  421563, 4021563, 2401563, 4201563, 1240563, 2140563, 1420563, 4120563, 2410563, 4210563,\n       125463, 1025463,  215463, 2015463, 1205463, 2105463,  152463, 1052463,  512463, 5012463, 1502463, 5102463,\n       251463, 2051463,  521463, 5021463, 2501463, 5201463, 1250463, 2150463, 1520463, 5120463, 2510463, 5210463,\n       145263, 1045263,  415263, 4015263, 1405263, 4105263,  154263, 1054263,  514263, 5014263, 1504263, 5104263,\n       451263, 4051263,  541263, 5041263, 4501263, 5401263, 1450263, 4150263, 1540263, 5140263, 4510263, 5410263,\n       245163, 2045163,  425163, 4025163, 2405163, 4205163,  254163, 2054163,  524163, 5024163, 2504163, 5204163,\n       452163, 4052163,  542163, 5042163, 4502163, 5402163, 2450163, 4250163, 2540163, 5240163, 4520163, 5420163,\n      1245063, 2145063, 1425063, 4125063, 2415063, 4215063, 1254063, 2154063, 1524063, 5124063, 2514063, 5214063,\n      1452063, 4152063, 1542063, 5142063, 4512063, 5412063, 2451063, 4251063, 2541063, 5241063, 4521063, 5421063,\n       124653, 1024653,  214653, 2014653, 1204653, 2104653,  142653, 1042653,  412653, 4012653, 1402653, 4102653,\n       241653, 2041653,  421653, 4021653, 2401653, 4201653, 1240653, 2140653, 1420653, 4120653, 2410653, 4210653,\n       126453, 1026453,  216453, 2016453, 1206453, 2106453,  162453, 1062453,  612453, 6012453, 1602453, 6102453,\n       261453, 2061453,  621453, 6021453, 2601453, 6201453, 1260453, 2160453, 1620453, 6120453, 2610453, 6210453,\n       146253, 1046253,  416253, 4016253, 1406253, 4106253,  164253, 1064253,  614253, 6014253, 1604253, 6104253,\n       461253, 4061253,  641253, 6041253, 4601253, 6401253, 1460253, 4160253, 1640253, 6140253, 4610253, 6410253,\n       246153, 2046153,  426153, 4026153, 2406153, 4206153,  264153, 2064153,  624153, 6024153, 2604153, 6204153,\n       462153, 4062153,  642153, 6042153, 4602153, 6402153, 2460153, 4260153, 2640153, 6240153, 4620153, 6420153,\n      1246053, 2146053, 1426053, 4126053, 2416053, 4216053, 1264053, 2164053, 1624053, 6124053, 2614053, 6214053,\n      1462053, 4162053, 1642053, 6142053, 4612053, 6412053, 2461053, 4261053, 2641053, 6241053, 4621053, 6421053,\n       125643, 1025643,  215643, 2015643, 1205643, 2105643,  152643, 1052643,  512643, 5012643, 1502643, 5102643,\n       251643, 2051643,  521643, 5021643, 2501643, 5201643, 1250643, 2150643, 1520643, 5120643, 2510643, 5210643,\n       126543, 1026543,  216543, 2016543, 1206543, 2106543,  162543, 1062543,  612543, 6012543, 1602543, 6102543,\n       261543, 2061543,  621543, 6021543, 2601543, 6201543, 1260543, 2160543, 1620543, 6120543, 2610543, 6210543,\n       156243, 1056243,  516243, 5016243, 1506243, 5106243,  165243, 1065243,  615243, 6015243, 1605243, 6105243,\n       561243, 5061243,  651243, 6051243, 5601243, 6501243, 1560243, 5160243, 1650243, 6150243, 5610243, 6510243,\n       256143, 2056143,  526143, 5026143, 2506143, 5206143,  265143, 2065143,  625143, 6025143, 2605143, 6205143,\n       562143, 5062143,  652143, 6052143, 5602143, 6502143, 2560143, 5260143, 2650143, 6250143, 5620143, 6520143,\n      1256043, 2156043, 1526043, 5126043, 2516043, 5216043, 1265043, 2165043, 1625043, 6125043, 2615043, 6215043,\n      1562043, 5162043, 1652043, 6152043, 5612043, 6512043, 2561043, 5261043, 2651043, 6251043, 5621043, 6521043,\n       145623, 1045623,  415623, 4015623, 1405623, 4105623,  154623, 1054623,  514623, 5014623, 1504623, 5104623,\n       451623, 4051623,  541623, 5041623, 4501623, 5401623, 1450623, 4150623, 1540623, 5140623, 4510623, 5410623,\n       146523, 1046523,  416523, 4016523, 1406523, 4106523,  164523, 1064523,  614523, 6014523, 1604523, 6104523,\n       461523, 4061523,  641523, 6041523, 4601523, 6401523, 1460523, 4160523, 1640523, 6140523, 4610523, 6410523,\n       156423, 1056423,  516423, 5016423, 1506423, 5106423,  165423, 1065423,  615423, 6015423, 1605423, 6105423,\n       561423, 5061423,  651423, 6051423, 5601423, 6501423, 1560423, 5160423, 1650423, 6150423, 5610423, 6510423,\n       456123, 4056123,  546123, 5046123, 4506123, 5406123,  465123, 4065123,  645123, 6045123, 4605123, 6405123,\n       564123, 5064123,  654123, 6054123, 5604123, 6504123, 4560123, 5460123, 4650123, 6450123, 5640123, 6540123,\n      1456023, 4156023, 1546023, 5146023, 4516023, 5416023, 1465023, 4165023, 1645023, 6145023, 4615023, 6415023,\n      1564023, 5164023, 1654023, 6154023, 5614023, 6514023, 4561023, 5461023, 4651023, 6451023, 5641023, 6541023,\n       245613, 2045613,  425613, 4025613, 2405613, 4205613,  254613, 2054613,  524613, 5024613, 2504613, 5204613,\n       452613, 4052613,  542613, 5042613, 4502613, 5402613, 2450613, 4250613, 2540613, 5240613, 4520613, 5420613,\n       246513, 2046513,  426513, 4026513, 2406513, 4206513,  264513, 2064513,  624513, 6024513, 2604513, 6204513,\n       462513, 4062513,  642513, 6042513, 4602513, 6402513, 2460513, 4260513, 2640513, 6240513, 4620513, 6420513,\n       256413, 2056413,  526413, 5026413, 2506413, 5206413,  265413, 2065413,  625413, 6025413, 2605413, 6205413,\n       562413, 5062413,  652413, 6052413, 5602413, 6502413, 2560413, 5260413, 2650413, 6250413, 5620413, 6520413,\n       456213, 4056213,  546213, 5046213, 4506213, 5406213,  465213, 4065213,  645213, 6045213, 4605213, 6405213,\n       564213, 5064213,  654213, 6054213, 5604213, 6504213, 4560213, 5460213, 4650213, 6450213, 5640213, 6540213,\n      2456013, 4256013, 2546013, 5246013, 4526013, 5426013, 2465013, 4265013, 2645013, 6245013, 4625013, 6425013,\n      2564013, 5264013, 2654013, 6254013, 5624013, 6524013, 4562013, 5462013, 4652013, 6452013, 5642013, 6542013,\n      1245603, 2145603, 1425603, 4125603, 2415603, 4215603, 1254603, 2154603, 1524603, 5124603, 2514603, 5214603,\n      1452603, 4152603, 1542603, 5142603, 4512603, 5412603, 2451603, 4251603, 2541603, 5241603, 4521603, 5421603,\n      1246503, 2146503, 1426503, 4126503, 2416503, 4216503, 1264503, 2164503, 1624503, 6124503, 2614503, 6214503,\n      1462503, 4162503, 1642503, 6142503, 4612503, 6412503, 2461503, 4261503, 2641503, 6241503, 4621503, 6421503,\n      1256403, 2156403, 1526403, 5126403, 2516403, 5216403, 1265403, 2165403, 1625403, 6125403, 2615403, 6215403,\n      1562403, 5162403, 1652403, 6152403, 5612403, 6512403, 2561403, 5261403, 2651403, 6251403, 5621403, 6521403,\n      1456203, 4156203, 1546203, 5146203, 4516203, 5416203, 1465203, 4165203, 1645203, 6145203, 4615203, 6415203,\n      1564203, 5164203, 1654203, 6154203, 5614203, 6514203, 4561203, 5461203, 4651203, 6451203, 5641203, 6541203,\n      2456103, 4256103, 2546103, 5246103, 4526103, 5426103, 2465103, 4265103, 2645103, 6245103, 4625103, 6425103,\n      2564103, 5264103, 2654103, 6254103, 5624103, 6524103, 4562103, 5462103, 4652103, 6452103, 5642103, 6542103,\n       134562, 1034562,  314562, 3014562, 1304562, 3104562,  143562, 1043562,  413562, 4013562, 1403562, 4103562,\n       341562, 3041562,  431562, 4031562, 3401562, 4301562, 1340562, 3140562, 1430562, 4130562, 3410562, 4310562,\n       135462, 1035462,  315462, 3015462, 1305462, 3105462,  153462, 1053462,  513462, 5013462, 1503462, 5103462,\n       351462, 3051462,  531462, 5031462, 3501462, 5301462, 1350462, 3150462, 1530462, 5130462, 3510462, 5310462,\n       145362, 1045362,  415362, 4015362, 1405362, 4105362,  154362, 1054362,  514362, 5014362, 1504362, 5104362,\n       451362, 4051362,  541362, 5041362, 4501362, 5401362, 1450362, 4150362, 1540362, 5140362, 4510362, 5410362,\n       345162, 3045162,  435162, 4035162, 3405162, 4305162,  354162, 3054162,  534162, 5034162, 3504162, 5304162,\n       453162, 4053162,  543162, 5043162, 4503162, 5403162, 3450162, 4350162, 3540162, 5340162, 4530162, 5430162,\n      1345062, 3145062, 1435062, 4135062, 3415062, 4315062, 1354062, 3154062, 1534062, 5134062, 3514062, 5314062,\n      1453062, 4153062, 1543062, 5143062, 4513062, 5413062, 3451062, 4351062, 3541062, 5341062, 4531062, 5431062,\n       134652, 1034652,  314652, 3014652, 1304652, 3104652,  143652, 1043652,  413652, 4013652, 1403652, 4103652,\n       341652, 3041652,  431652, 4031652, 3401652, 4301652, 1340652, 3140652, 1430652, 4130652, 3410652, 4310652,\n       136452, 1036452,  316452, 3016452, 1306452, 3106452,  163452, 1063452,  613452, 6013452, 1603452, 6103452,\n       361452, 3061452,  631452, 6031452, 3601452, 6301452, 1360452, 3160452, 1630452, 6130452, 3610452, 6310452,\n       146352, 1046352,  416352, 4016352, 1406352, 4106352,  164352, 1064352,  614352, 6014352, 1604352, 6104352,\n       461352, 4061352,  641352, 6041352, 4601352, 6401352, 1460352, 4160352, 1640352, 6140352, 4610352, 6410352,\n       346152, 3046152,  436152, 4036152, 3406152, 4306152,  364152, 3064152,  634152, 6034152, 3604152, 6304152,\n       463152, 4063152,  643152, 6043152, 4603152, 6403152, 3460152, 4360152, 3640152, 6340152, 4630152, 6430152,\n      1346052, 3146052, 1436052, 4136052, 3416052, 4316052, 1364052, 3164052, 1634052, 6134052, 3614052, 6314052,\n      1463052, 4163052, 1643052, 6143052, 4613052, 6413052, 3461052, 4361052, 3641052, 6341052, 4631052, 6431052,\n       135642, 1035642,  315642, 3015642, 1305642, 3105642,  153642, 1053642,  513642, 5013642, 1503642, 5103642,\n       351642, 3051642,  531642, 5031642, 3501642, 5301642, 1350642, 3150642, 1530642, 5130642, 3510642, 5310642,\n       136542, 1036542,  316542, 3016542, 1306542, 3106542,  163542, 1063542,  613542, 6013542, 1603542, 6103542,\n       361542, 3061542,  631542, 6031542, 3601542, 6301542, 1360542, 3160542, 1630542, 6130542, 3610542, 6310542,\n       156342, 1056342,  516342, 5016342, 1506342, 5106342,  165342, 1065342,  615342, 6015342, 1605342, 6105342,\n       561342, 5061342,  651342, 6051342, 5601342, 6501342, 1560342, 5160342, 1650342, 6150342, 5610342, 6510342,\n       356142, 3056142,  536142, 5036142, 3506142, 5306142,  365142, 3065142,  635142, 6035142, 3605142, 6305142,\n       563142, 5063142,  653142, 6053142, 5603142, 6503142, 3560142, 5360142, 3650142, 6350142, 5630142, 6530142,\n      1356042, 3156042, 1536042, 5136042, 3516042, 5316042, 1365042, 3165042, 1635042, 6135042, 3615042, 6315042,\n      1563042, 5163042, 1653042, 6153042, 5613042, 6513042, 3561042, 5361042, 3651042, 6351042, 5631042, 6531042,\n       145632, 1045632,  415632, 4015632, 1405632, 4105632,  154632, 1054632,  514632, 5014632, 1504632, 5104632,\n       451632, 4051632,  541632, 5041632, 4501632, 5401632, 1450632, 4150632, 1540632, 5140632, 4510632, 5410632,\n       146532, 1046532,  416532, 4016532, 1406532, 4106532,  164532, 1064532,  614532, 6014532, 1604532, 6104532,\n       461532, 4061532,  641532, 6041532, 4601532, 6401532, 1460532, 4160532, 1640532, 6140532, 4610532, 6410532,\n       156432, 1056432,  516432, 5016432, 1506432, 5106432,  165432, 1065432,  615432, 6015432, 1605432, 6105432,\n       561432, 5061432,  651432, 6051432, 5601432, 6501432, 1560432, 5160432, 1650432, 6150432, 5610432, 6510432,\n       456132, 4056132,  546132, 5046132, 4506132, 5406132,  465132, 4065132,  645132, 6045132, 4605132, 6405132,\n       564132, 5064132,  654132, 6054132, 5604132, 6504132, 4560132, 5460132, 4650132, 6450132, 5640132, 6540132,\n      1456032, 4156032, 1546032, 5146032, 4516032, 5416032, 1465032, 4165032, 1645032, 6145032, 4615032, 6415032,\n      1564032, 5164032, 1654032, 6154032, 5614032, 6514032, 4561032, 5461032, 4651032, 6451032, 5641032, 6541032,\n       345612, 3045612,  435612, 4035612, 3405612, 4305612,  354612, 3054612,  534612, 5034612, 3504612, 5304612,\n       453612, 4053612,  543612, 5043612, 4503612, 5403612, 3450612, 4350612, 3540612, 5340612, 4530612, 5430612,\n       346512, 3046512,  436512, 4036512, 3406512, 4306512,  364512, 3064512,  634512, 6034512, 3604512, 6304512,\n       463512, 4063512,  643512, 6043512, 4603512, 6403512, 3460512, 4360512, 3640512, 6340512, 4630512, 6430512,\n       356412, 3056412,  536412, 5036412, 3506412, 5306412,  365412, 3065412,  635412, 6035412, 3605412, 6305412,\n       563412, 5063412,  653412, 6053412, 5603412, 6503412, 3560412, 5360412, 3650412, 6350412, 5630412, 6530412,\n       456312, 4056312,  546312, 5046312, 4506312, 5406312,  465312, 4065312,  645312, 6045312, 4605312, 6405312,\n       564312, 5064312,  654312, 6054312, 5604312, 6504312, 4560312, 5460312, 4650312, 6450312, 5640312, 6540312,\n      3456012, 4356012, 3546012, 5346012, 4536012, 5436012, 3465012, 4365012, 3645012, 6345012, 4635012, 6435012,\n      3564012, 5364012, 3654012, 6354012, 5634012, 6534012, 4563012, 5463012, 4653012, 6453012, 5643012, 6543012,\n      1345602, 3145602, 1435602, 4135602, 3415602, 4315602, 1354602, 3154602, 1534602, 5134602, 3514602, 5314602,\n      1453602, 4153602, 1543602, 5143602, 4513602, 5413602, 3451602, 4351602, 3541602, 5341602, 4531602, 5431602,\n      1346502, 3146502, 1436502, 4136502, 3416502, 4316502, 1364502, 3164502, 1634502, 6134502, 3614502, 6314502,\n      1463502, 4163502, 1643502, 6143502, 4613502, 6413502, 3461502, 4361502, 3641502, 6341502, 4631502, 6431502,\n      1356402, 3156402, 1536402, 5136402, 3516402, 5316402, 1365402, 3165402, 1635402, 6135402, 3615402, 6315402,\n      1563402, 5163402, 1653402, 6153402, 5613402, 6513402, 3561402, 5361402, 3651402, 6351402, 5631402, 6531402,\n      1456302, 4156302, 1546302, 5146302, 4516302, 5416302, 1465302, 4165302, 1645302, 6145302, 4615302, 6415302,\n      1564302, 5164302, 1654302, 6154302, 5614302, 6514302, 4561302, 5461302, 4651302, 6451302, 5641302, 6541302,\n      3456102, 4356102, 3546102, 5346102, 4536102, 5436102, 3465102, 4365102, 3645102, 6345102, 4635102, 6435102,\n      3564102, 5364102, 3654102, 6354102, 5634102, 6534102, 4563102, 5463102, 4653102, 6453102, 5643102, 6543102,\n       234561, 2034561,  324561, 3024561, 2304561, 3204561,  243561, 2043561,  423561, 4023561, 2403561, 4203561,\n       342561, 3042561,  432561, 4032561, 3402561, 4302561, 2340561, 3240561, 2430561, 4230561, 3420561, 4320561,\n       235461, 2035461,  325461, 3025461, 2305461, 3205461,  253461, 2053461,  523461, 5023461, 2503461, 5203461,\n       352461, 3052461,  532461, 5032461, 3502461, 5302461, 2350461, 3250461, 2530461, 5230461, 3520461, 5320461,\n       245361, 2045361,  425361, 4025361, 2405361, 4205361,  254361, 2054361,  524361, 5024361, 2504361, 5204361,\n       452361, 4052361,  542361, 5042361, 4502361, 5402361, 2450361, 4250361, 2540361, 5240361, 4520361, 5420361,\n       345261, 3045261,  435261, 4035261, 3405261, 4305261,  354261, 3054261,  534261, 5034261, 3504261, 5304261,\n       453261, 4053261,  543261, 5043261, 4503261, 5403261, 3450261, 4350261, 3540261, 5340261, 4530261, 5430261,\n      2345061, 3245061, 2435061, 4235061, 3425061, 4325061, 2354061, 3254061, 2534061, 5234061, 3524061, 5324061,\n      2453061, 4253061, 2543061, 5243061, 4523061, 5423061, 3452061, 4352061, 3542061, 5342061, 4532061, 5432061,\n       234651, 2034651,  324651, 3024651, 2304651, 3204651,  243651, 2043651,  423651, 4023651, 2403651, 4203651,\n       342651, 3042651,  432651, 4032651, 3402651, 4302651, 2340651, 3240651, 2430651, 4230651, 3420651, 4320651,\n       236451, 2036451,  326451, 3026451, 2306451, 3206451,  263451, 2063451,  623451, 6023451, 2603451, 6203451,\n       362451, 3062451,  632451, 6032451, 3602451, 6302451, 2360451, 3260451, 2630451, 6230451, 3620451, 6320451,\n       246351, 2046351,  426351, 4026351, 2406351, 4206351,  264351, 2064351,  624351, 6024351, 2604351, 6204351,\n       462351, 4062351,  642351, 6042351, 4602351, 6402351, 2460351, 4260351, 2640351, 6240351, 4620351, 6420351,\n       346251, 3046251,  436251, 4036251, 3406251, 4306251,  364251, 3064251,  634251, 6034251, 3604251, 6304251,\n       463251, 4063251,  643251, 6043251, 4603251, 6403251, 3460251, 4360251, 3640251, 6340251, 4630251, 6430251,\n      2346051, 3246051, 2436051, 4236051, 3426051, 4326051, 2364051, 3264051, 2634051, 6234051, 3624051, 6324051,\n      2463051, 4263051, 2643051, 6243051, 4623051, 6423051, 3462051, 4362051, 3642051, 6342051, 4632051, 6432051,\n       235641, 2035641,  325641, 3025641, 2305641, 3205641,  253641, 2053641,  523641, 5023641, 2503641, 5203641,\n       352641, 3052641,  532641, 5032641, 3502641, 5302641, 2350641, 3250641, 2530641, 5230641, 3520641, 5320641,\n       236541, 2036541,  326541, 3026541, 2306541, 3206541,  263541, 2063541,  623541, 6023541, 2603541, 6203541,\n       362541, 3062541,  632541, 6032541, 3602541, 6302541, 2360541, 3260541, 2630541, 6230541, 3620541, 6320541,\n       256341, 2056341,  526341, 5026341, 2506341, 5206341,  265341, 2065341,  625341, 6025341, 2605341, 6205341,\n       562341, 5062341,  652341, 6052341, 5602341, 6502341, 2560341, 5260341, 2650341, 6250341, 5620341, 6520341,\n       356241, 3056241,  536241, 5036241, 3506241, 5306241,  365241, 3065241,  635241, 6035241, 3605241, 6305241,\n       563241, 5063241,  653241, 6053241, 5603241, 6503241, 3560241, 5360241, 3650241, 6350241, 5630241, 6530241,\n      2356041, 3256041, 2536041, 5236041, 3526041, 5326041, 2365041, 3265041, 2635041, 6235041, 3625041, 6325041,\n      2563041, 5263041, 2653041, 6253041, 5623041, 6523041, 3562041, 5362041, 3652041, 6352041, 5632041, 6532041,\n       245631, 2045631,  425631, 4025631, 2405631, 4205631,  254631, 2054631,  524631, 5024631, 2504631, 5204631,\n       452631, 4052631,  542631, 5042631, 4502631, 5402631, 2450631, 4250631, 2540631, 5240631, 4520631, 5420631,\n       246531, 2046531,  426531, 4026531, 2406531, 4206531,  264531, 2064531,  624531, 6024531, 2604531, 6204531,\n       462531, 4062531,  642531, 6042531, 4602531, 6402531, 2460531, 4260531, 2640531, 6240531, 4620531, 6420531,\n       256431, 2056431,  526431, 5026431, 2506431, 5206431,  265431, 2065431,  625431, 6025431, 2605431, 6205431,\n       562431, 5062431,  652431, 6052431, 5602431, 6502431, 2560431, 5260431, 2650431, 6250431, 5620431, 6520431,\n       456231, 4056231,  546231, 5046231, 4506231, 5406231,  465231, 4065231,  645231, 6045231, 4605231, 6405231,\n       564231, 5064231,  654231, 6054231, 5604231, 6504231, 4560231, 5460231, 4650231, 6450231, 5640231, 6540231,\n      2456031, 4256031, 2546031, 5246031, 4526031, 5426031, 2465031, 4265031, 2645031, 6245031, 4625031, 6425031,\n      2564031, 5264031, 2654031, 6254031, 5624031, 6524031, 4562031, 5462031, 4652031, 6452031, 5642031, 6542031,\n       345621, 3045621,  435621, 4035621, 3405621, 4305621,  354621, 3054621,  534621, 5034621, 3504621, 5304621,\n       453621, 4053621,  543621, 5043621, 4503621, 5403621, 3450621, 4350621, 3540621, 5340621, 4530621, 5430621,\n       346521, 3046521,  436521, 4036521, 3406521, 4306521,  364521, 3064521,  634521, 6034521, 3604521, 6304521,\n       463521, 4063521,  643521, 6043521, 4603521, 6403521, 3460521, 4360521, 3640521, 6340521, 4630521, 6430521,\n       356421, 3056421,  536421, 5036421, 3506421, 5306421,  365421, 3065421,  635421, 6035421, 3605421, 6305421,\n       563421, 5063421,  653421, 6053421, 5603421, 6503421, 3560421, 5360421, 3650421, 6350421, 5630421, 6530421,\n       456321, 4056321,  546321, 5046321, 4506321, 5406321,  465321, 4065321,  645321, 6045321, 4605321, 6405321,\n       564321, 5064321,  654321, 6054321, 5604321, 6504321, 4560321, 5460321, 4650321, 6450321, 5640321, 6540321,\n      3456021, 4356021, 3546021, 5346021, 4536021, 5436021, 3465021, 4365021, 3645021, 6345021, 4635021, 6435021,\n      3564021, 5364021, 3654021, 6354021, 5634021, 6534021, 4563021, 5463021, 4653021, 6453021, 5643021, 6543021,\n      2345601, 3245601, 2435601, 4235601, 3425601, 4325601, 2354601, 3254601, 2534601, 5234601, 3524601, 5324601,\n      2453601, 4253601, 2543601, 5243601, 4523601, 5423601, 3452601, 4352601, 3542601, 5342601, 4532601, 5432601,\n      2346501, 3246501, 2436501, 4236501, 3426501, 4326501, 2364501, 3264501, 2634501, 6234501, 3624501, 6324501,\n      2463501, 4263501, 2643501, 6243501, 4623501, 6423501, 3462501, 4362501, 3642501, 6342501, 4632501, 6432501,\n      2356401, 3256401, 2536401, 5236401, 3526401, 5326401, 2365401, 3265401, 2635401, 6235401, 3625401, 6325401,\n      2563401, 5263401, 2653401, 6253401, 5623401, 6523401, 3562401, 5362401, 3652401, 6352401, 5632401, 6532401,\n      2456301, 4256301, 2546301, 5246301, 4526301, 5426301, 2465301, 4265301, 2645301, 6245301, 4625301, 6425301,\n      2564301, 5264301, 2654301, 6254301, 5624301, 6524301, 4562301, 5462301, 4652301, 6452301, 5642301, 6542301,\n      3456201, 4356201, 3546201, 5346201, 4536201, 5436201, 3465201, 4365201, 3645201, 6345201, 4635201, 6435201,\n      3564201, 5364201, 3654201, 6354201, 5634201, 6534201, 4563201, 5463201, 4653201, 6453201, 5643201, 6543201,\n      1234560, 2134560, 1324560, 3124560, 2314560, 3214560, 1243560, 2143560, 1423560, 4123560, 2413560, 4213560,\n      1342560, 3142560, 1432560, 4132560, 3412560, 4312560, 2341560, 3241560, 2431560, 4231560, 3421560, 4321560,\n      1235460, 2135460, 1325460, 3125460, 2315460, 3215460, 1253460, 2153460, 1523460, 5123460, 2513460, 5213460,\n      1352460, 3152460, 1532460, 5132460, 3512460, 5312460, 2351460, 3251460, 2531460, 5231460, 3521460, 5321460,\n      1245360, 2145360, 1425360, 4125360, 2415360, 4215360, 1254360, 2154360, 1524360, 5124360, 2514360, 5214360,\n      1452360, 4152360, 1542360, 5142360, 4512360, 5412360, 2451360, 4251360, 2541360, 5241360, 4521360, 5421360,\n      1345260, 3145260, 1435260, 4135260, 3415260, 4315260, 1354260, 3154260, 1534260, 5134260, 3514260, 5314260,\n      1453260, 4153260, 1543260, 5143260, 4513260, 5413260, 3451260, 4351260, 3541260, 5341260, 4531260, 5431260,\n      2345160, 3245160, 2435160, 4235160, 3425160, 4325160, 2354160, 3254160, 2534160, 5234160, 3524160, 5324160,\n      2453160, 4253160, 2543160, 5243160, 4523160, 5423160, 3452160, 4352160, 3542160, 5342160, 4532160, 5432160,\n      1234650, 2134650, 1324650, 3124650, 2314650, 3214650, 1243650, 2143650, 1423650, 4123650, 2413650, 4213650,\n      1342650, 3142650, 1432650, 4132650, 3412650, 4312650, 2341650, 3241650, 2431650, 4231650, 3421650, 4321650,\n      1236450, 2136450, 1326450, 3126450, 2316450, 3216450, 1263450, 2163450, 1623450, 6123450, 2613450, 6213450,\n      1362450, 3162450, 1632450, 6132450, 3612450, 6312450, 2361450, 3261450, 2631450, 6231450, 3621450, 6321450,\n      1246350, 2146350, 1426350, 4126350, 2416350, 4216350, 1264350, 2164350, 1624350, 6124350, 2614350, 6214350,\n      1462350, 4162350, 1642350, 6142350, 4612350, 6412350, 2461350, 4261350, 2641350, 6241350, 4621350, 6421350,\n      1346250, 3146250, 1436250, 4136250, 3416250, 4316250, 1364250, 3164250, 1634250, 6134250, 3614250, 6314250,\n      1463250, 4163250, 1643250, 6143250, 4613250, 6413250, 3461250, 4361250, 3641250, 6341250, 4631250, 6431250,\n      2346150, 3246150, 2436150, 4236150, 3426150, 4326150, 2364150, 3264150, 2634150, 6234150, 3624150, 6324150,\n      2463150, 4263150, 2643150, 6243150, 4623150, 6423150, 3462150, 4362150, 3642150, 6342150, 4632150, 6432150,\n      1235640, 2135640, 1325640, 3125640, 2315640, 3215640, 1253640, 2153640, 1523640, 5123640, 2513640, 5213640,\n      1352640, 3152640, 1532640, 5132640, 3512640, 5312640, 2351640, 3251640, 2531640, 5231640, 3521640, 5321640,\n      1236540, 2136540, 1326540, 3126540, 2316540, 3216540, 1263540, 2163540, 1623540, 6123540, 2613540, 6213540,\n      1362540, 3162540, 1632540, 6132540, 3612540, 6312540, 2361540, 3261540, 2631540, 6231540, 3621540, 6321540,\n      1256340, 2156340, 1526340, 5126340, 2516340, 5216340, 1265340, 2165340, 1625340, 6125340, 2615340, 6215340,\n      1562340, 5162340, 1652340, 6152340, 5612340, 6512340, 2561340, 5261340, 2651340, 6251340, 5621340, 6521340,\n      1356240, 3156240, 1536240, 5136240, 3516240, 5316240, 1365240, 3165240, 1635240, 6135240, 3615240, 6315240,\n      1563240, 5163240, 1653240, 6153240, 5613240, 6513240, 3561240, 5361240, 3651240, 6351240, 5631240, 6531240,\n      2356140, 3256140, 2536140, 5236140, 3526140, 5326140, 2365140, 3265140, 2635140, 6235140, 3625140, 6325140,\n      2563140, 5263140, 2653140, 6253140, 5623140, 6523140, 3562140, 5362140, 3652140, 6352140, 5632140, 6532140,\n      1245630, 2145630, 1425630, 4125630, 2415630, 4215630, 1254630, 2154630, 1524630, 5124630, 2514630, 5214630,\n      1452630, 4152630, 1542630, 5142630, 4512630, 5412630, 2451630, 4251630, 2541630, 5241630, 4521630, 5421630,\n      1246530, 2146530, 1426530, 4126530, 2416530, 4216530, 1264530, 2164530, 1624530, 6124530, 2614530, 6214530,\n      1462530, 4162530, 1642530, 6142530, 4612530, 6412530, 2461530, 4261530, 2641530, 6241530, 4621530, 6421530,\n      1256430, 2156430, 1526430, 5126430, 2516430, 5216430, 1265430, 2165430, 1625430, 6125430, 2615430, 6215430,\n      1562430, 5162430, 1652430, 6152430, 5612430, 6512430, 2561430, 5261430, 2651430, 6251430, 5621430, 6521430,\n      1456230, 4156230, 1546230, 5146230, 4516230, 5416230, 1465230, 4165230, 1645230, 6145230, 4615230, 6415230,\n      1564230, 5164230, 1654230, 6154230, 5614230, 6514230, 4561230, 5461230, 4651230, 6451230, 5641230, 6541230,\n      2456130, 4256130, 2546130, 5246130, 4526130, 5426130, 2465130, 4265130, 2645130, 6245130, 4625130, 6425130,\n      2564130, 5264130, 2654130, 6254130, 5624130, 6524130, 4562130, 5462130, 4652130, 6452130, 5642130, 6542130,\n      1345620, 3145620, 1435620, 4135620, 3415620, 4315620, 1354620, 3154620, 1534620, 5134620, 3514620, 5314620,\n      1453620, 4153620, 1543620, 5143620, 4513620, 5413620, 3451620, 4351620, 3541620, 5341620, 4531620, 5431620,\n      1346520, 3146520, 1436520, 4136520, 3416520, 4316520, 1364520, 3164520, 1634520, 6134520, 3614520, 6314520,\n      1463520, 4163520, 1643520, 6143520, 4613520, 6413520, 3461520, 4361520, 3641520, 6341520, 4631520, 6431520,\n      1356420, 3156420, 1536420, 5136420, 3516420, 5316420, 1365420, 3165420, 1635420, 6135420, 3615420, 6315420,\n      1563420, 5163420, 1653420, 6153420, 5613420, 6513420, 3561420, 5361420, 3651420, 6351420, 5631420, 6531420,\n      1456320, 4156320, 1546320, 5146320, 4516320, 5416320, 1465320, 4165320, 1645320, 6145320, 4615320, 6415320,\n      1564320, 5164320, 1654320, 6154320, 5614320, 6514320, 4561320, 5461320, 4651320, 6451320, 5641320, 6541320,\n      3456120, 4356120, 3546120, 5346120, 4536120, 5436120, 3465120, 4365120, 3645120, 6345120, 4635120, 6435120,\n      3564120, 5364120, 3654120, 6354120, 5634120, 6534120, 4563120, 5463120, 4653120, 6453120, 5643120, 6543120,\n      2345610, 3245610, 2435610, 4235610, 3425610, 4325610, 2354610, 3254610, 2534610, 5234610, 3524610, 5324610,\n      2453610, 4253610, 2543610, 5243610, 4523610, 5423610, 3452610, 4352610, 3542610, 5342610, 4532610, 5432610,\n      2346510, 3246510, 2436510, 4236510, 3426510, 4326510, 2364510, 3264510, 2634510, 6234510, 3624510, 6324510,\n      2463510, 4263510, 2643510, 6243510, 4623510, 6423510, 3462510, 4362510, 3642510, 6342510, 4632510, 6432510,\n      2356410, 3256410, 2536410, 5236410, 3526410, 5326410, 2365410, 3265410, 2635410, 6235410, 3625410, 6325410,\n      2563410, 5263410, 2653410, 6253410, 5623410, 6523410, 3562410, 5362410, 3652410, 6352410, 5632410, 6532410,\n      2456310, 4256310, 2546310, 5246310, 4526310, 5426310, 2465310, 4265310, 2645310, 6245310, 4625310, 6425310,\n      2564310, 5264310, 2654310, 6254310, 5624310, 6524310, 4562310, 5462310, 4652310, 6452310, 5642310, 6542310,\n      3456210, 4356210, 3546210, 5346210, 4536210, 5436210, 3465210, 4365210, 3645210, 6345210, 4635210, 6435210,\n      3564210, 5364210, 3654210, 6354210, 5634210, 6534210, 4563210, 5463210, 4653210, 6453210, 5643210, 6543210\n    };\n    std::map<uint64_t, int> expected;\n    for (std::size_t i = 0; i < 5040; i++)\n      expected[pre_expected[i]] = 0; // flags are 0, everything is symmetric here\n\n    VERIFY(isDynGroup(group));\n    VERIFY_IS_EQUAL(group.size(), 5040u);\n    VERIFY_IS_EQUAL(group.globalFlags(), 0);\n    group.apply<checkIdx, int>(identity7, 0, found, expected);\n    VERIFY_IS_EQUAL(found.size(), 5040u);\n  }\n}\n\nstatic void test_tensor_epsilon()\n{\n  SGroup<AntiSymmetry<0,1>, AntiSymmetry<1,2>> sym;\n  Tensor<int, 3> epsilon(3,3,3);\n\n  epsilon.setZero();\n  sym(epsilon, 0, 1, 2) = 1;\n\n  for (int i = 0; i < 3; i++) {\n    for (int j = 0; j < 3; j++) {\n      for (int k = 0; k < 3; k++) {\n        VERIFY_IS_EQUAL((epsilon(i,j,k)), (- (j - i) * (k - j) * (i - k) / 2) );\n      }\n    }\n  }\n}\n\nstatic void test_tensor_sym()\n{\n  SGroup<Symmetry<0,1>, Symmetry<2,3>> sym;\n  Tensor<int, 4> t(10,10,10,10);\n\n  t.setZero();\n\n  for (int l = 0; l < 10; l++) {\n    for (int k = l; k < 10; k++) {\n      for (int j = 0; j < 10; j++) {\n        for (int i = j; i < 10; i++) {\n          sym(t, i, j, k, l) = (i + j) * (k + l);\n        }\n      }\n    }\n  }\n\n  for (int l = 0; l < 10; l++) {\n    for (int k = 0; k < 10; k++) {\n      for (int j = 0; j < 10; j++) {\n        for (int i = 0; i < 10; i++) {\n          VERIFY_IS_EQUAL((t(i, j, k, l)), ((i + j) * (k + l)));\n        }\n      }\n    }\n  }\n\n}\n\nstatic void test_tensor_asym()\n{\n  SGroup<AntiSymmetry<0,1>, AntiSymmetry<2,3>> sym;\n  Tensor<int, 4> t(10,10,10,10);\n\n  t.setZero();\n\n  for (int l = 0; l < 10; l++) {\n    for (int k = l + 1; k < 10; k++) {\n      for (int j = 0; j < 10; j++) {\n        for (int i = j + 1; i < 10; i++) {\n          sym(t, i, j, k, l) = ((i * j) + (k * l));\n        }\n      }\n    }\n  }\n\n  for (int l = 0; l < 10; l++) {\n    for (int k = 0; k < 10; k++) {\n      for (int j = 0; j < 10; j++) {\n        for (int i = 0; i < 10; i++) {\n          if (i < j && k < l)\n            VERIFY_IS_EQUAL((t(i, j, k, l)), (((i * j) + (k * l))));\n          else if (i > j && k > l)\n            VERIFY_IS_EQUAL((t(i, j, k, l)), (((i * j) + (k * l))));\n          else if (i < j && k > l)\n            VERIFY_IS_EQUAL((t(i, j, k, l)), (- ((i * j) + (k * l))));\n          else if (i > j && k < l)\n            VERIFY_IS_EQUAL((t(i, j, k, l)), (- ((i * j) + (k * l))));\n          else\n            VERIFY_IS_EQUAL((t(i, j, k, l)), 0);\n        }\n      }\n    }\n  }\n}\n\nstatic void test_tensor_dynsym()\n{\n  DynamicSGroup sym;\n  sym.addSymmetry(0,1);\n  sym.addSymmetry(2,3);\n  Tensor<int, 4> t(10,10,10,10);\n\n  t.setZero();\n\n  for (int l = 0; l < 10; l++) {\n    for (int k = l; k < 10; k++) {\n      for (int j = 0; j < 10; j++) {\n        for (int i = j; i < 10; i++) {\n          sym(t, i, j, k, l) = (i + j) * (k + l);\n        }\n      }\n    }\n  }\n\n  for (int l = 0; l < 10; l++) {\n    for (int k = 0; k < 10; k++) {\n      for (int j = 0; j < 10; j++) {\n        for (int i = 0; i < 10; i++) {\n          VERIFY_IS_EQUAL((t(i, j, k, l)), ((i + j) * (k + l)));\n        }\n      }\n    }\n  }\n}\n\nstatic void test_tensor_randacc()\n{\n  SGroup<Symmetry<0,1>, Symmetry<2,3>> sym;\n  Tensor<int, 4> t(10,10,10,10);\n\n  t.setZero();\n\n  // set elements 1 million times, that way we access the\n  // entire matrix\n  for (int n = 0; n < 1000000; n++) {\n    int i = rand() % 10;\n    int j = rand() % 10;\n    int k = rand() % 10;\n    int l = rand() % 10;\n    // only access those indices in a given order\n    if (i < j)\n      std::swap(i, j);\n    if (k < l)\n      std::swap(k, l);\n    sym(t, i, j, k, l) = (i + j) * (k + l);\n  }\n\n  for (int l = 0; l < 10; l++) {\n    for (int k = 0; k < 10; k++) {\n      for (int j = 0; j < 10; j++) {\n        for (int i = 0; i < 10; i++) {\n          VERIFY_IS_EQUAL((t(i, j, k, l)), ((i + j) * (k + l)));\n        }\n      }\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_symmetry)\n{\n  CALL_SUBTEST(test_symgroups_static());\n  CALL_SUBTEST(test_symgroups_dynamic());\n  CALL_SUBTEST(test_symgroups_selection());\n  CALL_SUBTEST(test_tensor_epsilon());\n  CALL_SUBTEST(test_tensor_sym());\n  CALL_SUBTEST(test_tensor_asym());\n  CALL_SUBTEST(test_tensor_dynsym());\n  CALL_SUBTEST(test_tensor_randacc());\n}\n\n/*\n * kate: space-indent on; indent-width 2; mixedindent off; indent-mode cstyle;\n */\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_thread_local.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_USE_THREADS\n\n#include <iostream>\n#include <unordered_set>\n\n#include \"main.h\"\n#include <Eigen/CXX11/ThreadPool>\n\nstruct Counter {\n  Counter() = default;\n\n  void inc() {\n    // Check that mutation happens only in a thread that created this counter.\n    VERIFY_IS_EQUAL(std::this_thread::get_id(), created_by);\n    counter_value++;\n  }\n  int value() { return counter_value; }\n\n  std::thread::id created_by;\n  int counter_value = 0;\n};\n\nstruct InitCounter {\n  void operator()(Counter& counter) {\n    counter.created_by = std::this_thread::get_id();\n  }\n};\n\nvoid test_simple_thread_local() {\n  int num_threads = internal::random<int>(4, 32);\n  Eigen::ThreadPool thread_pool(num_threads);\n  Eigen::ThreadLocal<Counter, InitCounter> counter(num_threads, InitCounter());\n\n  int num_tasks = 3 * num_threads;\n  Eigen::Barrier barrier(num_tasks);\n\n  for (int i = 0; i < num_tasks; ++i) {\n    thread_pool.Schedule([&counter, &barrier]() {\n      Counter& local = counter.local();\n      local.inc();\n\n      std::this_thread::sleep_for(std::chrono::milliseconds(100));\n      barrier.Notify();\n    });\n  }\n\n  barrier.Wait();\n\n  counter.ForEach(\n      [](std::thread::id, Counter& cnt) { VERIFY_IS_EQUAL(cnt.value(), 3); });\n}\n\nvoid test_zero_sized_thread_local() {\n  Eigen::ThreadLocal<Counter, InitCounter> counter(0, InitCounter());\n\n  Counter& local = counter.local();\n  local.inc();\n\n  int total = 0;\n  counter.ForEach([&total](std::thread::id, Counter& cnt) {\n    total += cnt.value();\n    VERIFY_IS_EQUAL(cnt.value(), 1);\n  });\n\n  VERIFY_IS_EQUAL(total, 1);\n}\n\n// All thread local values fits into the lock-free storage.\nvoid test_large_number_of_tasks_no_spill() {\n  int num_threads = internal::random<int>(4, 32);\n  Eigen::ThreadPool thread_pool(num_threads);\n  Eigen::ThreadLocal<Counter, InitCounter> counter(num_threads, InitCounter());\n\n  int num_tasks = 10000;\n  Eigen::Barrier barrier(num_tasks);\n\n  for (int i = 0; i < num_tasks; ++i) {\n    thread_pool.Schedule([&counter, &barrier]() {\n      Counter& local = counter.local();\n      local.inc();\n      barrier.Notify();\n    });\n  }\n\n  barrier.Wait();\n\n  int total = 0;\n  std::unordered_set<std::thread::id> unique_threads;\n\n  counter.ForEach([&](std::thread::id id, Counter& cnt) {\n    total += cnt.value();\n    unique_threads.insert(id);\n  });\n\n  VERIFY_IS_EQUAL(total, num_tasks);\n  // Not all threads in a pool might be woken up to execute submitted tasks.\n  // Also thread_pool.Schedule() might use current thread if queue is full.\n  VERIFY_IS_EQUAL(\n      unique_threads.size() <= (static_cast<size_t>(num_threads + 1)), true);\n}\n\n// Lock free thread local storage is too small to fit all the unique threads,\n// and it spills to a map guarded by a mutex.\nvoid test_large_number_of_tasks_with_spill() {\n  int num_threads = internal::random<int>(4, 32);\n  Eigen::ThreadPool thread_pool(num_threads);\n  Eigen::ThreadLocal<Counter, InitCounter> counter(1, InitCounter());\n\n  int num_tasks = 10000;\n  Eigen::Barrier barrier(num_tasks);\n\n  for (int i = 0; i < num_tasks; ++i) {\n    thread_pool.Schedule([&counter, &barrier]() {\n      Counter& local = counter.local();\n      local.inc();\n      barrier.Notify();\n    });\n  }\n\n  barrier.Wait();\n\n  int total = 0;\n  std::unordered_set<std::thread::id> unique_threads;\n\n  counter.ForEach([&](std::thread::id id, Counter& cnt) {\n    total += cnt.value();\n    unique_threads.insert(id);\n  });\n\n  VERIFY_IS_EQUAL(total, num_tasks);\n  // Not all threads in a pool might be woken up to execute submitted tasks.\n  // Also thread_pool.Schedule() might use current thread if queue is full.\n  VERIFY_IS_EQUAL(\n      unique_threads.size() <= (static_cast<size_t>(num_threads + 1)), true);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_thread_local) {\n  CALL_SUBTEST(test_simple_thread_local());\n  CALL_SUBTEST(test_zero_sized_thread_local());\n  CALL_SUBTEST(test_large_number_of_tasks_no_spill());\n  CALL_SUBTEST(test_large_number_of_tasks_with_spill());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_thread_pool.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_USE_THREADS\n\n\n#include \"main.h\"\n#include <iostream>\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\nclass TestAllocator : public Allocator {\n public:\n  ~TestAllocator() EIGEN_OVERRIDE {}\n  EIGEN_DEVICE_FUNC void* allocate(size_t num_bytes) const EIGEN_OVERRIDE {\n    const_cast<TestAllocator*>(this)->alloc_count_++;\n    return internal::aligned_malloc(num_bytes);\n  }\n  EIGEN_DEVICE_FUNC void deallocate(void* buffer) const EIGEN_OVERRIDE {\n    const_cast<TestAllocator*>(this)->dealloc_count_++;\n    internal::aligned_free(buffer);\n  }\n\n  int alloc_count() const { return alloc_count_; }\n  int dealloc_count() const { return dealloc_count_; }\n\n private:\n  int alloc_count_ = 0;\n  int dealloc_count_ = 0;\n};\n\nvoid test_multithread_elementwise()\n{\n  Tensor<float, 3> in1(200, 30, 70);\n  Tensor<float, 3> in2(200, 30, 70);\n  Tensor<double, 3> out(200, 30, 70);\n\n  in1.setRandom();\n  in2.setRandom();\n\n  Eigen::ThreadPool tp(internal::random<int>(3, 11));\n  Eigen::ThreadPoolDevice thread_pool_device(&tp, internal::random<int>(3, 11));\n  out.device(thread_pool_device) = (in1 + in2 * 3.14f).cast<double>();\n\n  for (int i = 0; i < 200; ++i) {\n    for (int j = 0; j < 30; ++j) {\n      for (int k = 0; k < 70; ++k) {\n        VERIFY_IS_APPROX(out(i, j, k), static_cast<double>(in1(i, j, k) + in2(i, j, k) * 3.14f));\n      }\n    }\n  }\n}\n\nvoid test_async_multithread_elementwise()\n{\n  Tensor<float, 3> in1(200, 30, 70);\n  Tensor<float, 3> in2(200, 30, 70);\n  Tensor<double, 3> out(200, 30, 70);\n\n  in1.setRandom();\n  in2.setRandom();\n\n  Eigen::ThreadPool tp(internal::random<int>(3, 11));\n  Eigen::ThreadPoolDevice thread_pool_device(&tp, internal::random<int>(3, 11));\n\n  Eigen::Barrier b(1);\n  out.device(thread_pool_device, [&b]() { b.Notify(); }) = (in1 + in2 * 3.14f).cast<double>();\n  b.Wait();\n\n  for (int i = 0; i < 200; ++i) {\n    for (int j = 0; j < 30; ++j) {\n      for (int k = 0; k < 70; ++k) {\n        VERIFY_IS_APPROX(out(i, j, k), static_cast<double>(in1(i, j, k) + in2(i, j, k) * 3.14f));\n      }\n    }\n  }\n}\n\nvoid test_multithread_compound_assignment()\n{\n  Tensor<float, 3> in1(2,3,7);\n  Tensor<float, 3> in2(2,3,7);\n  Tensor<float, 3> out(2,3,7);\n\n  in1.setRandom();\n  in2.setRandom();\n\n  Eigen::ThreadPool tp(internal::random<int>(3, 11));\n  Eigen::ThreadPoolDevice thread_pool_device(&tp, internal::random<int>(3, 11));\n  out.device(thread_pool_device) = in1;\n  out.device(thread_pool_device) += in2 * 3.14f;\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k), in1(i,j,k) + in2(i,j,k) * 3.14f);\n      }\n    }\n  }\n}\n\ntemplate<int DataLayout>\nvoid test_multithread_contraction()\n{\n  Tensor<float, 4, DataLayout> t_left(30, 50, 37, 31);\n  Tensor<float, 5, DataLayout> t_right(37, 31, 70, 2, 10);\n  Tensor<float, 5, DataLayout> t_result(30, 50, 70, 2, 10);\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  // this contraction should be equivalent to a single matrix multiplication\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n  Eigen::array<DimPair, 2> dims({{DimPair(2, 0), DimPair(3, 1)}});\n\n  typedef Map<Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 1500, 1147);\n  MapXf m_right(t_right.data(), 1147, 1400);\n  Matrix<float, Dynamic, Dynamic, DataLayout> m_result(1500, 1400);\n\n  Eigen::ThreadPool tp(4);\n  Eigen::ThreadPoolDevice thread_pool_device(&tp, 4);\n\n  // compute results by separate methods\n  t_result.device(thread_pool_device) = t_left.contract(t_right, dims);\n  m_result = m_left * m_right;\n\n for (ptrdiff_t i = 0; i < t_result.size(); i++) {\n    VERIFY(&t_result.data()[i] != &m_result.data()[i]);\n    if (fabsf(t_result(i) - m_result(i)) < 1e-4f) {\n      continue;\n    }\n    if (Eigen::internal::isApprox(t_result(i), m_result(i), 1e-4f)) {\n      continue;\n    }\n    std::cout << \"mismatch detected at index \" << i << \": \" << t_result(i)\n              << \" vs \" <<  m_result(i) << std::endl;\n    assert(false);\n  }\n}\n\ntemplate<int DataLayout>\nvoid test_contraction_corner_cases()\n{\n  Tensor<float, 2, DataLayout> t_left(32, 500);\n  Tensor<float, 2, DataLayout> t_right(32, 28*28);\n  Tensor<float, 2, DataLayout> t_result(500, 28*28);\n\n  t_left = (t_left.constant(-0.5f) + t_left.random()) * 2.0f;\n  t_right = (t_right.constant(-0.6f) + t_right.random()) * 2.0f;\n  t_result = t_result.constant(NAN);\n\n  // this contraction should be equivalent to a single matrix multiplication\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n  Eigen::array<DimPair, 1> dims{{DimPair(0, 0)}};\n\n  typedef Map<Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 32, 500);\n  MapXf m_right(t_right.data(), 32, 28*28);\n  Matrix<float, Dynamic, Dynamic, DataLayout> m_result(500, 28*28);\n\n  Eigen::ThreadPool tp(12);\n  Eigen::ThreadPoolDevice thread_pool_device(&tp, 12);\n\n  // compute results by separate methods\n  t_result.device(thread_pool_device) = t_left.contract(t_right, dims);\n  m_result = m_left.transpose() * m_right;\n\n  for (ptrdiff_t i = 0; i < t_result.size(); i++) {\n    assert(!(numext::isnan)(t_result.data()[i]));\n    if (fabsf(t_result.data()[i] - m_result.data()[i]) >= 1e-4f) {\n      std::cout << \"mismatch detected at index \" << i << \" : \" << t_result.data()[i] << \" vs \" <<  m_result.data()[i] << std::endl;\n      assert(false);\n    }\n  }\n\n  t_left.resize(32, 1);\n  t_left = (t_left.constant(-0.5f) + t_left.random()) * 2.0f;\n  t_result.resize (1, 28*28);\n  t_result = t_result.constant(NAN);\n  t_result.device(thread_pool_device) = t_left.contract(t_right, dims);\n  new(&m_left) MapXf(t_left.data(), 32, 1);\n  m_result = m_left.transpose() * m_right;\n  for (ptrdiff_t i = 0; i < t_result.size(); i++) {\n    assert(!(numext::isnan)(t_result.data()[i]));\n    if (fabsf(t_result.data()[i] - m_result.data()[i]) >= 1e-4f) {\n      std::cout << \"mismatch detected: \" << t_result.data()[i] << \" vs \" <<  m_result.data()[i] << std::endl;\n      assert(false);\n    }\n  }\n\n  t_left.resize(32, 500);\n  t_right.resize(32, 4);\n  t_left = (t_left.constant(-0.5f) + t_left.random()) * 2.0f;\n  t_right = (t_right.constant(-0.6f) + t_right.random()) * 2.0f;\n  t_result.resize (500, 4);\n  t_result = t_result.constant(NAN);\n  t_result.device(thread_pool_device) = t_left.contract(t_right, dims);\n  new(&m_left) MapXf(t_left.data(), 32, 500);\n  new(&m_right) MapXf(t_right.data(), 32, 4);\n  m_result = m_left.transpose() * m_right;\n  for (ptrdiff_t i = 0; i < t_result.size(); i++) {\n    assert(!(numext::isnan)(t_result.data()[i]));\n    if (fabsf(t_result.data()[i] - m_result.data()[i]) >= 1e-4f) {\n      std::cout << \"mismatch detected: \" << t_result.data()[i] << \" vs \" <<  m_result.data()[i] << std::endl;\n      assert(false);\n    }\n  }\n\n  t_left.resize(32, 1);\n  t_right.resize(32, 4);\n  t_left = (t_left.constant(-0.5f) + t_left.random()) * 2.0f;\n  t_right = (t_right.constant(-0.6f) + t_right.random()) * 2.0f;\n  t_result.resize (1, 4);\n  t_result = t_result.constant(NAN);\n  t_result.device(thread_pool_device) = t_left.contract(t_right, dims);\n  new(&m_left) MapXf(t_left.data(), 32, 1);\n  new(&m_right) MapXf(t_right.data(), 32, 4);\n  m_result = m_left.transpose() * m_right;\n  for (ptrdiff_t i = 0; i < t_result.size(); i++) {\n    assert(!(numext::isnan)(t_result.data()[i]));\n    if (fabsf(t_result.data()[i] - m_result.data()[i]) >= 1e-4f) {\n      std::cout << \"mismatch detected: \" << t_result.data()[i] << \" vs \" <<  m_result.data()[i] << std::endl;\n      assert(false);\n    }\n  }\n}\n\ntemplate<int DataLayout>\nvoid test_multithread_contraction_agrees_with_singlethread() {\n  int contract_size = internal::random<int>(1, 5000);\n\n  Tensor<float, 3, DataLayout> left(internal::random<int>(1, 80),\n                                    contract_size,\n                                    internal::random<int>(1, 100));\n\n  Tensor<float, 4, DataLayout> right(internal::random<int>(1, 25),\n                                     internal::random<int>(1, 37),\n                                     contract_size,\n                                     internal::random<int>(1, 51));\n\n  left.setRandom();\n  right.setRandom();\n\n  // add constants to shift values away from 0 for more precision\n  left += left.constant(1.5f);\n  right += right.constant(1.5f);\n\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n  Eigen::array<DimPair, 1> dims({{DimPair(1, 2)}});\n\n  Eigen::ThreadPool tp(internal::random<int>(2, 11));\n  Eigen::ThreadPoolDevice thread_pool_device(&tp, internal::random<int>(2, 11));\n\n  Tensor<float, 5, DataLayout> st_result;\n  st_result = left.contract(right, dims);\n\n  Tensor<float, 5, DataLayout> tp_result(st_result.dimensions());\n  tp_result.device(thread_pool_device) = left.contract(right, dims);\n\n  VERIFY(dimensions_match(st_result.dimensions(), tp_result.dimensions()));\n  for (ptrdiff_t i = 0; i < st_result.size(); i++) {\n    // if both of the values are very small, then do nothing (because the test will fail\n    // due to numerical precision issues when values are small)\n    if (numext::abs(st_result.data()[i] - tp_result.data()[i]) >= 1e-4f) {\n      VERIFY_IS_APPROX(st_result.data()[i], tp_result.data()[i]);\n    }\n  }\n}\n\n// Apply Sqrt to all output elements.\nstruct SqrtOutputKernel {\n  template <typename Index, typename Scalar>\n  EIGEN_ALWAYS_INLINE void operator()(\n      const internal::blas_data_mapper<Scalar, Index, ColMajor>& output_mapper,\n      const TensorContractionParams&, Index, Index, Index num_rows,\n      Index num_cols) const {\n    for (int i = 0; i < num_rows; ++i) {\n      for (int j = 0; j < num_cols; ++j) {\n        output_mapper(i, j) = std::sqrt(output_mapper(i, j));\n      }\n    }\n  }\n};\n\ntemplate <int DataLayout>\nstatic void test_multithread_contraction_with_output_kernel() {\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n\n  const int num_threads = internal::random<int>(2, 11);\n  ThreadPool threads(num_threads);\n  Eigen::ThreadPoolDevice device(&threads, num_threads);\n\n  Tensor<float, 4, DataLayout> t_left(30, 50, 8, 31);\n  Tensor<float, 5, DataLayout> t_right(8, 31, 7, 20, 10);\n  Tensor<float, 5, DataLayout> t_result(30, 50, 7, 20, 10);\n\n  t_left.setRandom();\n  t_right.setRandom();\n  // Put trash in mat4 to verify contraction clears output memory.\n  t_result.setRandom();\n\n  // Add a little offset so that the results won't be close to zero.\n  t_left += t_left.constant(1.0f);\n  t_right += t_right.constant(1.0f);\n\n  typedef Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 1500, 248);\n  MapXf m_right(t_right.data(), 248, 1400);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result(1500, 1400);\n\n  // this contraction should be equivalent to a single matrix multiplication\n  Eigen::array<DimPair, 2> dims({{DimPair(2, 0), DimPair(3, 1)}});\n\n  // compute results by separate methods\n  t_result.device(device) = t_left.contract(t_right, dims, SqrtOutputKernel());\n\n  m_result = m_left * m_right;\n\n  for (Index i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY(&t_result.data()[i] != &m_result.data()[i]);\n    VERIFY_IS_APPROX(t_result.data()[i], std::sqrt(m_result.data()[i]));\n  }\n}\n\ntemplate<int DataLayout>\nvoid test_async_multithread_contraction_agrees_with_singlethread()\n{\n  int contract_size = internal::random<int>(100, 500);\n\n  Tensor<float, 3, DataLayout> left(internal::random<int>(10, 40),\n                                    contract_size,\n                                    internal::random<int>(10, 40));\n\n  Tensor<float, 4, DataLayout> right(\n      internal::random<int>(1, 20), internal::random<int>(1, 20), contract_size,\n      internal::random<int>(1, 20));\n\n  left.setRandom();\n  right.setRandom();\n\n  // add constants to shift values away from 0 for more precision\n  left += left.constant(1.5f);\n  right += right.constant(1.5f);\n\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n  Eigen::array<DimPair, 1> dims({{DimPair(1, 2)}});\n\n  Eigen::ThreadPool tp(internal::random<int>(2, 11));\n  Eigen::ThreadPoolDevice thread_pool_device(&tp, internal::random<int>(8, 32));\n\n  Tensor<float, 5, DataLayout> st_result;\n  st_result = left.contract(right, dims);\n\n  Tensor<float, 5, DataLayout> tp_result(st_result.dimensions());\n\n  Eigen::Barrier barrier(1);\n  tp_result.device(thread_pool_device, [&barrier]() { barrier.Notify(); }) =\n      left.contract(right, dims);\n  barrier.Wait();\n\n  VERIFY(dimensions_match(st_result.dimensions(), tp_result.dimensions()));\n  for (ptrdiff_t i = 0; i < st_result.size(); i++) {\n    // if both of the values are very small, then do nothing (because the test\n    // will fail due to numerical precision issues when values are small)\n    if (numext::abs(st_result.data()[i] - tp_result.data()[i]) >= 1e-4f) {\n      VERIFY_IS_APPROX(st_result.data()[i], tp_result.data()[i]);\n    }\n  }\n}\n\n// We are triggering 'evalShardedByInnerDim' optimization.\ntemplate <int DataLayout>\nstatic void test_sharded_by_inner_dim_contraction()\n{\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n\n  const int num_threads = internal::random<int>(4, 16);\n  ThreadPool threads(num_threads);\n  Eigen::ThreadPoolDevice device(&threads, num_threads);\n\n  Tensor<float, 2, DataLayout> t_left(2, 10000);\n  Tensor<float, 2, DataLayout> t_right(10000, 10);\n  Tensor<float, 2, DataLayout> t_result(2, 10);\n\n  t_left.setRandom();\n  t_right.setRandom();\n  // Put trash in t_result to verify contraction clears output memory.\n  t_result.setRandom();\n\n  // Add a little offset so that the results won't be close to zero.\n  t_left += t_left.constant(1.0f);\n  t_right += t_right.constant(1.0f);\n\n  typedef Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 2, 10000);\n  MapXf m_right(t_right.data(), 10000, 10);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result(2, 10);\n\n  // this contraction should be equivalent to a single matrix multiplication\n  Eigen::array<DimPair, 1> dims({{DimPair(1, 0)}});\n\n  // compute results by separate methods\n  t_result.device(device) = t_left.contract(t_right, dims);\n  m_result = m_left * m_right;\n\n  for (Index i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY_IS_APPROX(t_result.data()[i], m_result.data()[i]);\n  }\n}\n\n// We are triggering 'evalShardedByInnerDim' optimization with output kernel.\ntemplate <int DataLayout>\nstatic void test_sharded_by_inner_dim_contraction_with_output_kernel()\n{\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n\n  const int num_threads = internal::random<int>(4, 16);\n  ThreadPool threads(num_threads);\n  Eigen::ThreadPoolDevice device(&threads, num_threads);\n\n  Tensor<float, 2, DataLayout> t_left(2, 10000);\n  Tensor<float, 2, DataLayout> t_right(10000, 10);\n  Tensor<float, 2, DataLayout> t_result(2, 10);\n\n  t_left.setRandom();\n  t_right.setRandom();\n  // Put trash in t_result to verify contraction clears output memory.\n  t_result.setRandom();\n\n  // Add a little offset so that the results won't be close to zero.\n  t_left += t_left.constant(1.0f);\n  t_right += t_right.constant(1.0f);\n\n  typedef Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 2, 10000);\n  MapXf m_right(t_right.data(), 10000, 10);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result(2, 10);\n\n  // this contraction should be equivalent to a single matrix multiplication\n  Eigen::array<DimPair, 1> dims({{DimPair(1, 0)}});\n\n  // compute results by separate methods\n  t_result.device(device) = t_left.contract(t_right, dims, SqrtOutputKernel());\n  m_result = m_left * m_right;\n\n  for (Index i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY_IS_APPROX(t_result.data()[i], std::sqrt(m_result.data()[i]));\n  }\n}\n\n// We are triggering 'evalShardedByInnerDim' optimization.\ntemplate <int DataLayout>\nstatic void test_async_sharded_by_inner_dim_contraction()\n{\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n\n  const int num_threads = internal::random<int>(4, 16);\n  ThreadPool threads(num_threads);\n  Eigen::ThreadPoolDevice device(&threads, num_threads);\n\n  Tensor<float, 2, DataLayout> t_left(2, 10000);\n  Tensor<float, 2, DataLayout> t_right(10000, 10);\n  Tensor<float, 2, DataLayout> t_result(2, 10);\n\n  t_left.setRandom();\n  t_right.setRandom();\n  // Put trash in t_result to verify contraction clears output memory.\n  t_result.setRandom();\n\n  // Add a little offset so that the results won't be close to zero.\n  t_left += t_left.constant(1.0f);\n  t_right += t_right.constant(1.0f);\n\n  typedef Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 2, 10000);\n  MapXf m_right(t_right.data(), 10000, 10);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result(2, 10);\n\n  // this contraction should be equivalent to a single matrix multiplication\n  Eigen::array<DimPair, 1> dims({{DimPair(1, 0)}});\n\n  // compute results by separate methods\n  Eigen::Barrier barrier(1);\n  t_result.device(device, [&barrier]() { barrier.Notify(); }) =\n      t_left.contract(t_right, dims);\n  barrier.Wait();\n\n  m_result = m_left * m_right;\n\n  for (Index i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY_IS_APPROX(t_result.data()[i], m_result.data()[i]);\n  }\n}\n\n// We are triggering 'evalShardedByInnerDim' optimization with output kernel.\ntemplate <int DataLayout>\nstatic void test_async_sharded_by_inner_dim_contraction_with_output_kernel()\n{\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n\n  const int num_threads = internal::random<int>(4, 16);\n  ThreadPool threads(num_threads);\n  Eigen::ThreadPoolDevice device(&threads, num_threads);\n\n  Tensor<float, 2, DataLayout> t_left(2, 10000);\n  Tensor<float, 2, DataLayout> t_right(10000, 10);\n  Tensor<float, 2, DataLayout> t_result(2, 10);\n\n  t_left.setRandom();\n  t_right.setRandom();\n  // Put trash in t_result to verify contraction clears output memory.\n  t_result.setRandom();\n\n  // Add a little offset so that the results won't be close to zero.\n  t_left += t_left.constant(1.0f);\n  t_right += t_right.constant(1.0f);\n\n  typedef Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 2, 10000);\n  MapXf m_right(t_right.data(), 10000, 10);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result(2, 10);\n\n  // this contraction should be equivalent to a single matrix multiplication\n  Eigen::array<DimPair, 1> dims({{DimPair(1, 0)}});\n\n  // compute results by separate methods\n  Eigen::Barrier barrier(1);\n  t_result.device(device, [&barrier]() { barrier.Notify(); }) =\n      t_left.contract(t_right, dims, SqrtOutputKernel());\n  barrier.Wait();\n  m_result = m_left * m_right;\n\n  for (Index i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY_IS_APPROX(t_result.data()[i], std::sqrt(m_result.data()[i]));\n  }\n}\n\ntemplate<int DataLayout>\nvoid test_full_contraction() {\n  int contract_size1 = internal::random<int>(1, 500);\n  int contract_size2 = internal::random<int>(1, 500);\n\n  Tensor<float, 2, DataLayout> left(contract_size1,\n                                    contract_size2);\n  Tensor<float, 2, DataLayout> right(contract_size1,\n                                    contract_size2);\n  left.setRandom();\n  right.setRandom();\n\n  // add constants to shift values away from 0 for more precision\n  left += left.constant(1.5f);\n  right += right.constant(1.5f);\n\n  typedef Tensor<float, 2>::DimensionPair DimPair;\n  Eigen::array<DimPair, 2> dims({{DimPair(0, 0), DimPair(1, 1)}});\n\n  Eigen::ThreadPool tp(internal::random<int>(2, 11));\n  Eigen::ThreadPoolDevice thread_pool_device(&tp, internal::random<int>(2, 11));\n\n  Tensor<float, 0, DataLayout> st_result;\n  st_result = left.contract(right, dims);\n\n  Tensor<float, 0, DataLayout> tp_result;\n  tp_result.device(thread_pool_device) = left.contract(right, dims);\n\n  VERIFY(dimensions_match(st_result.dimensions(), tp_result.dimensions()));\n  // if both of the values are very small, then do nothing (because the test will fail\n  // due to numerical precision issues when values are small)\n  if (numext::abs(st_result() - tp_result()) >= 1e-4f) {\n    VERIFY_IS_APPROX(st_result(), tp_result());\n  }\n}\n\ntemplate<int DataLayout>\nvoid test_multithreaded_reductions() {\n  const int num_threads = internal::random<int>(3, 11);\n  ThreadPool thread_pool(num_threads);\n  Eigen::ThreadPoolDevice thread_pool_device(&thread_pool, num_threads);\n\n  const int num_rows = internal::random<int>(13, 732);\n  const int num_cols = internal::random<int>(13, 732);\n  Tensor<float, 2, DataLayout> t1(num_rows, num_cols);\n  t1.setRandom();\n\n  Tensor<float, 0, DataLayout> full_redux;\n  full_redux = t1.sum();\n\n  Tensor<float, 0, DataLayout> full_redux_tp;\n  full_redux_tp.device(thread_pool_device) = t1.sum();\n\n  // Check that the single threaded and the multi threaded reductions return\n  // the same result.\n  VERIFY_IS_APPROX(full_redux(), full_redux_tp());\n}\n\n\nvoid test_memcpy() {\n\n  for (int i = 0; i < 5; ++i) {\n    const int num_threads = internal::random<int>(3, 11);\n    Eigen::ThreadPool tp(num_threads);\n    Eigen::ThreadPoolDevice thread_pool_device(&tp, num_threads);\n\n    const int size = internal::random<int>(13, 7632);\n    Tensor<float, 1> t1(size);\n    t1.setRandom();\n    std::vector<float> result(size);\n    thread_pool_device.memcpy(&result[0], t1.data(), size*sizeof(float));\n    for (int j = 0; j < size; j++) {\n      VERIFY_IS_EQUAL(t1(j), result[j]);\n    }\n  }\n}\n\n\nvoid test_multithread_random()\n{\n  Eigen::ThreadPool tp(2);\n  Eigen::ThreadPoolDevice device(&tp, 2);\n  Tensor<float, 1> t(1 << 20);\n  t.device(device) = t.random<Eigen::internal::NormalRandomGenerator<float>>();\n}\n\ntemplate<int DataLayout>\nvoid test_multithread_shuffle(Allocator* allocator)\n{\n  Tensor<float, 4, DataLayout> tensor(17,5,7,11);\n  tensor.setRandom();\n\n  const int num_threads = internal::random<int>(2, 11);\n  ThreadPool threads(num_threads);\n  Eigen::ThreadPoolDevice device(&threads, num_threads, allocator);\n\n  Tensor<float, 4, DataLayout> shuffle(7,5,11,17);\n  array<ptrdiff_t, 4> shuffles = {{2,1,3,0}};\n  shuffle.device(device) = tensor.shuffle(shuffles);\n\n  for (int i = 0; i < 17; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        for (int l = 0; l < 11; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), shuffle(k,j,l,i));\n        }\n      }\n    }\n  }\n}\n\nvoid test_threadpool_allocate(TestAllocator* allocator)\n{\n  const int num_threads = internal::random<int>(2, 11);\n  const int num_allocs = internal::random<int>(2, 11);\n  ThreadPool threads(num_threads);\n  Eigen::ThreadPoolDevice device(&threads, num_threads, allocator);\n\n  for (int a = 0; a < num_allocs; ++a) {\n    void* ptr = device.allocate(512);\n    device.deallocate(ptr);\n  }\n  VERIFY(allocator != NULL);\n  VERIFY_IS_EQUAL(allocator->alloc_count(), num_allocs);\n  VERIFY_IS_EQUAL(allocator->dealloc_count(), num_allocs);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_thread_pool)\n{\n  CALL_SUBTEST_1(test_multithread_elementwise());\n  CALL_SUBTEST_1(test_async_multithread_elementwise());\n  CALL_SUBTEST_1(test_multithread_compound_assignment());\n\n  CALL_SUBTEST_2(test_multithread_contraction<ColMajor>());\n  CALL_SUBTEST_2(test_multithread_contraction<RowMajor>());\n\n  CALL_SUBTEST_3(test_multithread_contraction_agrees_with_singlethread<ColMajor>());\n  CALL_SUBTEST_3(test_multithread_contraction_agrees_with_singlethread<RowMajor>());\n  CALL_SUBTEST_3(test_multithread_contraction_with_output_kernel<ColMajor>());\n  CALL_SUBTEST_3(test_multithread_contraction_with_output_kernel<RowMajor>());\n\n  CALL_SUBTEST_4(test_async_multithread_contraction_agrees_with_singlethread<ColMajor>());\n  CALL_SUBTEST_4(test_async_multithread_contraction_agrees_with_singlethread<RowMajor>());\n\n  // Test EvalShardedByInnerDimContext parallelization strategy.\n  CALL_SUBTEST_5(test_sharded_by_inner_dim_contraction<ColMajor>());\n  CALL_SUBTEST_5(test_sharded_by_inner_dim_contraction<RowMajor>());\n  CALL_SUBTEST_5(test_sharded_by_inner_dim_contraction_with_output_kernel<ColMajor>());\n  CALL_SUBTEST_5(test_sharded_by_inner_dim_contraction_with_output_kernel<RowMajor>());\n\n  CALL_SUBTEST_6(test_async_sharded_by_inner_dim_contraction<ColMajor>());\n  CALL_SUBTEST_6(test_async_sharded_by_inner_dim_contraction<RowMajor>());\n  CALL_SUBTEST_6(test_async_sharded_by_inner_dim_contraction_with_output_kernel<ColMajor>());\n  CALL_SUBTEST_6(test_async_sharded_by_inner_dim_contraction_with_output_kernel<RowMajor>());\n\n  // Exercise various cases that have been problematic in the past.\n  CALL_SUBTEST_7(test_contraction_corner_cases<ColMajor>());\n  CALL_SUBTEST_7(test_contraction_corner_cases<RowMajor>());\n\n  CALL_SUBTEST_8(test_full_contraction<ColMajor>());\n  CALL_SUBTEST_8(test_full_contraction<RowMajor>());\n\n  CALL_SUBTEST_9(test_multithreaded_reductions<ColMajor>());\n  CALL_SUBTEST_9(test_multithreaded_reductions<RowMajor>());\n\n  CALL_SUBTEST_10(test_memcpy());\n  CALL_SUBTEST_10(test_multithread_random());\n\n  TestAllocator test_allocator;\n  CALL_SUBTEST_11(test_multithread_shuffle<ColMajor>(NULL));\n  CALL_SUBTEST_11(test_multithread_shuffle<RowMajor>(&test_allocator));\n  CALL_SUBTEST_11(test_threadpool_allocate(&test_allocator));\n\n  // Force CMake to split this test.\n  // EIGEN_SUFFIXES;1;2;3;4;5;6;7;8;9;10;11\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_trace.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2017 Gagan Goel <gagan.nith@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::array;\n\ntemplate <int DataLayout>\nstatic void test_0D_trace() {\n  Tensor<float, 0, DataLayout> tensor;\n  tensor.setRandom();\n  array<ptrdiff_t, 0> dims;\n  Tensor<float, 0, DataLayout> result = tensor.trace(dims);\n  VERIFY_IS_EQUAL(result(), tensor());\n}\n\n\ntemplate <int DataLayout>\nstatic void test_all_dimensions_trace() {\n  Tensor<float, 3, DataLayout> tensor1(5, 5, 5);\n  tensor1.setRandom();\n  Tensor<float, 0, DataLayout> result1 = tensor1.trace();\n  VERIFY_IS_EQUAL(result1.rank(), 0);\n  float sum = 0.0f;\n  for (int i = 0; i < 5; ++i) {\n    sum += tensor1(i, i, i);\n  }\n  VERIFY_IS_EQUAL(result1(), sum);\n\n  Tensor<float, 5, DataLayout> tensor2(7, 7, 7, 7, 7);\n  tensor2.setRandom();\n  array<ptrdiff_t, 5> dims = { { 2, 1, 0, 3, 4 } };\n  Tensor<float, 0, DataLayout> result2 = tensor2.trace(dims);\n  VERIFY_IS_EQUAL(result2.rank(), 0);\n  sum = 0.0f;\n  for (int i = 0; i < 7; ++i) {\n    sum += tensor2(i, i, i, i, i);\n  }\n  VERIFY_IS_EQUAL(result2(), sum);\n}\n\n\ntemplate <int DataLayout>\nstatic void test_simple_trace() {\n  Tensor<float, 3, DataLayout> tensor1(3, 5, 3);\n  tensor1.setRandom();\n  array<ptrdiff_t, 2> dims1 = { { 0, 2 } };\n  Tensor<float, 1, DataLayout> result1 = tensor1.trace(dims1);\n  VERIFY_IS_EQUAL(result1.rank(), 1);\n  VERIFY_IS_EQUAL(result1.dimension(0), 5);\n  float sum = 0.0f;\n  for (int i = 0; i < 5; ++i) {\n    sum = 0.0f;\n    for (int j = 0; j < 3; ++j) {\n      sum += tensor1(j, i, j);\n    }\n    VERIFY_IS_EQUAL(result1(i), sum);\n  }\n\n  Tensor<float, 4, DataLayout> tensor2(5, 5, 7, 7);\n  tensor2.setRandom();\n  array<ptrdiff_t, 2> dims2 = { { 2, 3 } };\n  Tensor<float, 2, DataLayout> result2 = tensor2.trace(dims2);\n  VERIFY_IS_EQUAL(result2.rank(), 2);\n  VERIFY_IS_EQUAL(result2.dimension(0), 5);\n  VERIFY_IS_EQUAL(result2.dimension(1), 5);\n  for (int i = 0; i < 5; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      sum = 0.0f;\n      for (int k = 0; k < 7; ++k) {\n        sum += tensor2(i, j, k, k);\n      }\n      VERIFY_IS_EQUAL(result2(i, j), sum);\n    }\n  }\n\n  array<ptrdiff_t, 2> dims3 = { { 1, 0 } };\n  Tensor<float, 2, DataLayout> result3 = tensor2.trace(dims3);\n  VERIFY_IS_EQUAL(result3.rank(), 2);\n  VERIFY_IS_EQUAL(result3.dimension(0), 7);\n  VERIFY_IS_EQUAL(result3.dimension(1), 7);\n  for (int i = 0; i < 7; ++i) {\n    for (int j = 0; j < 7; ++j) {\n      sum = 0.0f;\n      for (int k = 0; k < 5; ++k) {\n        sum += tensor2(k, k, i, j);\n      }\n      VERIFY_IS_EQUAL(result3(i, j), sum);\n    }\n  }\n\n  Tensor<float, 5, DataLayout> tensor3(3, 7, 3, 7, 3);\n  tensor3.setRandom();\n  array<ptrdiff_t, 3> dims4 = { { 0, 2, 4 } };\n  Tensor<float, 2, DataLayout> result4 = tensor3.trace(dims4);\n  VERIFY_IS_EQUAL(result4.rank(), 2);\n  VERIFY_IS_EQUAL(result4.dimension(0), 7);\n  VERIFY_IS_EQUAL(result4.dimension(1), 7);\n  for (int i = 0; i < 7; ++i) {\n    for (int j = 0; j < 7; ++j) {\n      sum = 0.0f;\n      for (int k = 0; k < 3; ++k) {\n        sum += tensor3(k, i, k, j, k);\n      }\n      VERIFY_IS_EQUAL(result4(i, j), sum);\n    }\n  }\n\n  Tensor<float, 5, DataLayout> tensor4(3, 7, 4, 7, 5);\n  tensor4.setRandom();\n  array<ptrdiff_t, 2> dims5 = { { 1, 3 } };\n  Tensor<float, 3, DataLayout> result5 = tensor4.trace(dims5);\n  VERIFY_IS_EQUAL(result5.rank(), 3);\n  VERIFY_IS_EQUAL(result5.dimension(0), 3);\n  VERIFY_IS_EQUAL(result5.dimension(1), 4);\n  VERIFY_IS_EQUAL(result5.dimension(2), 5);\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 4; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        sum = 0.0f;\n        for (int l = 0; l < 7; ++l) {\n          sum += tensor4(i, l, j, l, k);\n        }\n        VERIFY_IS_EQUAL(result5(i, j, k), sum);\n      }\n    }\n  }\n}\n\n\ntemplate<int DataLayout>\nstatic void test_trace_in_expr() {\n  Tensor<float, 4, DataLayout> tensor(2, 3, 5, 3);\n  tensor.setRandom();\n  array<ptrdiff_t, 2> dims = { { 1, 3 } };\n  Tensor<float, 2, DataLayout> result(2, 5);\n  result = result.constant(1.0f) - tensor.trace(dims);\n  VERIFY_IS_EQUAL(result.rank(), 2);\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_EQUAL(result.dimension(1), 5);\n  float sum = 0.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      sum = 0.0f;\n      for (int k = 0; k < 3; ++k) {\n        sum += tensor(i, k, j, k);\n      }\n      VERIFY_IS_EQUAL(result(i, j), 1.0f - sum);\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_trace) {\n  CALL_SUBTEST(test_0D_trace<ColMajor>());\n  CALL_SUBTEST(test_0D_trace<RowMajor>());\n  CALL_SUBTEST(test_all_dimensions_trace<ColMajor>());\n  CALL_SUBTEST(test_all_dimensions_trace<RowMajor>());\n  CALL_SUBTEST(test_simple_trace<ColMajor>());\n  CALL_SUBTEST(test_simple_trace<RowMajor>());\n  CALL_SUBTEST(test_trace_in_expr<ColMajor>());\n  CALL_SUBTEST(test_trace_in_expr<RowMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_uint128.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\n\n#if EIGEN_COMP_MSVC || !defined(__SIZEOF_INT128__)\n#define EIGEN_NO_INT128\n#else\ntypedef __uint128_t uint128_t;\n#endif\n\n// Only run the test on compilers that support 128bit integers natively\n#ifndef EIGEN_NO_INT128\n\nusing Eigen::internal::TensorUInt128;\nusing Eigen::internal::static_val;\n\nvoid VERIFY_EQUAL(TensorUInt128<uint64_t, uint64_t> actual, uint128_t expected) {\n  bool matchl = actual.lower() == static_cast<uint64_t>(expected);\n  bool matchh = actual.upper() == static_cast<uint64_t>(expected >> 64);\n  if (!matchl || !matchh) {\n    const char* testname = g_test_stack.back().c_str();\n    std::cerr << \"Test \" << testname << \" failed in \" << __FILE__\n              << \" (\" << __LINE__ << \")\"\n              << std::endl;\n    abort();\n  }\n}\n\n\nvoid test_add() {\n  uint64_t incr = internal::random<uint64_t>(1, 9999999999);\n  for (uint64_t i1 = 0; i1 < 100; ++i1) {\n    for (uint64_t i2 = 1; i2 < 100 * incr; i2 += incr) {\n      TensorUInt128<uint64_t, uint64_t> i(i1, i2);\n      uint128_t a = (static_cast<uint128_t>(i1) << 64) + static_cast<uint128_t>(i2);\n      for (uint64_t j1 = 0; j1 < 100; ++j1) {\n        for (uint64_t j2 = 1; j2 < 100 * incr; j2 += incr) {\n          TensorUInt128<uint64_t, uint64_t> j(j1, j2);\n          uint128_t b = (static_cast<uint128_t>(j1) << 64) + static_cast<uint128_t>(j2);\n          TensorUInt128<uint64_t, uint64_t> actual = i + j;\n          uint128_t expected = a + b;\n          VERIFY_EQUAL(actual, expected);\n        }\n      }\n    }\n  }\n}\n\nvoid test_sub() {\n  uint64_t incr = internal::random<uint64_t>(1, 9999999999);\n  for (uint64_t i1 = 0; i1 < 100; ++i1) {\n    for (uint64_t i2 = 1; i2 < 100 * incr; i2 += incr) {\n      TensorUInt128<uint64_t, uint64_t> i(i1, i2);\n      uint128_t a = (static_cast<uint128_t>(i1) << 64) + static_cast<uint128_t>(i2);\n      for (uint64_t j1 = 0; j1 < 100; ++j1) {\n        for (uint64_t j2 = 1; j2 < 100 * incr; j2 += incr) {\n          TensorUInt128<uint64_t, uint64_t> j(j1, j2);\n          uint128_t b = (static_cast<uint128_t>(j1) << 64) + static_cast<uint128_t>(j2);\n          TensorUInt128<uint64_t, uint64_t> actual = i - j;\n          uint128_t expected = a - b;\n          VERIFY_EQUAL(actual, expected);\n        }\n      }\n    }\n  }\n}\n\nvoid test_mul() {\n  uint64_t incr = internal::random<uint64_t>(1, 9999999999);\n  for (uint64_t i1 = 0; i1 < 100; ++i1) {\n    for (uint64_t i2 = 1; i2 < 100 * incr; i2 += incr) {\n      TensorUInt128<uint64_t, uint64_t> i(i1, i2);\n      uint128_t a = (static_cast<uint128_t>(i1) << 64) + static_cast<uint128_t>(i2);\n      for (uint64_t j1 = 0; j1 < 100; ++j1) {\n        for (uint64_t j2 = 1; j2 < 100 * incr; j2 += incr) {\n          TensorUInt128<uint64_t, uint64_t> j(j1, j2);\n          uint128_t b = (static_cast<uint128_t>(j1) << 64) + static_cast<uint128_t>(j2);\n          TensorUInt128<uint64_t, uint64_t> actual = i * j;\n          uint128_t expected = a * b;\n          VERIFY_EQUAL(actual, expected);\n        }\n      }\n    }\n  }\n}\n\nvoid test_div() {\n  uint64_t incr = internal::random<uint64_t>(1, 9999999999);\n  for (uint64_t i1 = 0; i1 < 100; ++i1) {\n    for (uint64_t i2 = 1; i2 < 100 * incr; i2 += incr) {\n      TensorUInt128<uint64_t, uint64_t> i(i1, i2);\n      uint128_t a = (static_cast<uint128_t>(i1) << 64) + static_cast<uint128_t>(i2);\n      for (uint64_t j1 = 0; j1 < 100; ++j1) {\n        for (uint64_t j2 = 1; j2 < 100 * incr; j2 += incr) {\n          TensorUInt128<uint64_t, uint64_t> j(j1, j2);\n          uint128_t b = (static_cast<uint128_t>(j1) << 64) + static_cast<uint128_t>(j2);\n          TensorUInt128<uint64_t, uint64_t> actual = i / j;\n          uint128_t expected = a / b;\n          VERIFY_EQUAL(actual, expected);\n        }\n      }\n    }\n  }\n}\n\nvoid test_misc1() {\n  uint64_t incr = internal::random<uint64_t>(1, 9999999999);\n  for (uint64_t i2 = 1; i2 < 100 * incr; i2 += incr) {\n    TensorUInt128<static_val<0>, uint64_t> i(0, i2);\n    uint128_t a = static_cast<uint128_t>(i2);\n    for (uint64_t j2 = 1; j2 < 100 * incr; j2 += incr) {\n      TensorUInt128<static_val<0>, uint64_t> j(0, j2);\n      uint128_t b = static_cast<uint128_t>(j2);\n      uint64_t actual = (i * j).upper();\n      uint64_t expected = (a * b) >> 64;\n      VERIFY_IS_EQUAL(actual, expected);\n    }\n  }\n}\n\nvoid test_misc2() {\n  int64_t incr = internal::random<int64_t>(1, 100);\n  for (int64_t log_div = 0; log_div < 63; ++log_div) {\n    for (int64_t divider = 1; divider <= 1000000 * incr; divider += incr) {\n      uint64_t expected = (static_cast<uint128_t>(1) << (64+log_div)) / static_cast<uint128_t>(divider) - (static_cast<uint128_t>(1) << 64) + 1;\n      uint64_t shift = 1ULL << log_div;\n\n      TensorUInt128<uint64_t, uint64_t> result = (TensorUInt128<uint64_t, static_val<0> >(shift, 0) / TensorUInt128<static_val<0>, uint64_t>(divider) - TensorUInt128<static_val<1>, static_val<0> >(1, 0) + TensorUInt128<static_val<0>, static_val<1> >(1));\n      uint64_t actual = static_cast<uint64_t>(result);\n      VERIFY_IS_EQUAL(actual, expected);\n    }\n  }\n}\n#endif\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_uint128)\n{\n#ifdef EIGEN_NO_INT128\n  // Skip the test on compilers that don't support 128bit integers natively\n  return;\n#else\n  CALL_SUBTEST_1(test_add());\n  CALL_SUBTEST_2(test_sub());\n  CALL_SUBTEST_3(test_mul());\n  CALL_SUBTEST_4(test_div());\n  CALL_SUBTEST_5(test_misc1());\n  CALL_SUBTEST_6(test_misc2());\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_volume_patch.cpp",
    "content": "#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\nstatic void test_single_voxel_patch()\n{\n  Tensor<float, 5> tensor(4,2,3,5,7);\n  tensor.setRandom();\n  Tensor<float, 5, RowMajor> tensor_row_major = tensor.swap_layout();\n\n  Tensor<float, 6> single_voxel_patch;\n  single_voxel_patch = tensor.extract_volume_patches(1, 1, 1);\n  VERIFY_IS_EQUAL(single_voxel_patch.dimension(0), 4);\n  VERIFY_IS_EQUAL(single_voxel_patch.dimension(1), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch.dimension(3), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch.dimension(4), 2 * 3 * 5);\n  VERIFY_IS_EQUAL(single_voxel_patch.dimension(5), 7);\n\n  Tensor<float, 6, RowMajor> single_voxel_patch_row_major;\n  single_voxel_patch_row_major = tensor_row_major.extract_volume_patches(1, 1, 1);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(0), 7);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(1), 2 * 3 * 5);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(3), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(4), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(5), 4);\n\n  for (int i = 0; i < tensor.size(); ++i) {\n    VERIFY_IS_EQUAL(tensor.data()[i], single_voxel_patch.data()[i]);\n    VERIFY_IS_EQUAL(tensor_row_major.data()[i], single_voxel_patch_row_major.data()[i]);\n    VERIFY_IS_EQUAL(tensor.data()[i], tensor_row_major.data()[i]);\n  }\n}\n\n\nstatic void test_entire_volume_patch()\n{\n  const int depth = 4;\n  const int patch_z = 2;\n  const int patch_y = 3;\n  const int patch_x = 5;\n  const int batch = 7;\n\n  Tensor<float, 5> tensor(depth, patch_z, patch_y, patch_x, batch);\n  tensor.setRandom();\n  Tensor<float, 5, RowMajor> tensor_row_major = tensor.swap_layout();\n\n  Tensor<float, 6> entire_volume_patch;\n  entire_volume_patch = tensor.extract_volume_patches(patch_z, patch_y, patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch.dimension(0), depth);\n  VERIFY_IS_EQUAL(entire_volume_patch.dimension(1), patch_z);\n  VERIFY_IS_EQUAL(entire_volume_patch.dimension(2), patch_y);\n  VERIFY_IS_EQUAL(entire_volume_patch.dimension(3), patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch.dimension(4), patch_z * patch_y * patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch.dimension(5), batch);\n\n  Tensor<float, 6, RowMajor> entire_volume_patch_row_major;\n  entire_volume_patch_row_major = tensor_row_major.extract_volume_patches(patch_z, patch_y, patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(0), batch);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(1), patch_z * patch_y * patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(2), patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(3), patch_y);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(4), patch_z);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(5), depth);\n\n  const int dz = patch_z - 1;\n  const int dy = patch_y - 1;\n  const int dx = patch_x - 1;\n\n  const int forward_pad_z = dz / 2;\n  const int forward_pad_y = dy / 2;\n  const int forward_pad_x = dx / 2;\n\n  for (int pz = 0; pz < patch_z; pz++) {\n    for (int py = 0; py < patch_y; py++) {\n      for (int px = 0; px < patch_x; px++) {\n        const int patchId = pz + patch_z * (py + px * patch_y);\n        for (int z = 0; z < patch_z; z++) {\n          for (int y = 0; y < patch_y; y++) {\n            for (int x = 0; x < patch_x; x++) {\n              for (int b = 0; b < batch; b++) {\n                for (int d = 0; d < depth; d++) {\n                  float expected = 0.0f;\n                  float expected_row_major = 0.0f;\n                  const int eff_z = z - forward_pad_z + pz;\n                  const int eff_y = y - forward_pad_y + py;\n                  const int eff_x = x - forward_pad_x + px;\n                  if (eff_z >= 0 && eff_y >= 0 && eff_x >= 0 &&\n                      eff_z < patch_z && eff_y < patch_y && eff_x < patch_x) {\n                    expected = tensor(d, eff_z, eff_y, eff_x, b);\n                    expected_row_major = tensor_row_major(b, eff_x, eff_y, eff_z, d);\n                  }\n                  VERIFY_IS_EQUAL(entire_volume_patch(d, z, y, x, patchId, b), expected);\n                  VERIFY_IS_EQUAL(entire_volume_patch_row_major(b, patchId, x, y, z, d), expected_row_major);\n                }\n              }\n            }\n          }\n        }\n      }\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_volume_patch)\n{\n  CALL_SUBTEST(test_single_voxel_patch());\n  CALL_SUBTEST(test_entire_volume_patch());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/cxx11_tensor_volume_patch_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nstatic const int DataLayout = ColMajor;\n\ntemplate <typename DataType, typename IndexType>\nstatic void test_single_voxel_patch_sycl(const Eigen::SyclDevice& sycl_device)\n{\n\nIndexType sizeDim0 = 4;\nIndexType sizeDim1 = 2;\nIndexType sizeDim2 = 3;\nIndexType sizeDim3 = 5;\nIndexType sizeDim4 = 7;\narray<IndexType, 5> tensorColMajorRange = {{sizeDim0, sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\narray<IndexType, 5> tensorRowMajorRange = {{sizeDim4, sizeDim3, sizeDim2, sizeDim1, sizeDim0}};\nTensor<DataType, 5, DataLayout,IndexType> tensor_col_major(tensorColMajorRange);\nTensor<DataType, 5, RowMajor,IndexType> tensor_row_major(tensorRowMajorRange);\ntensor_col_major.setRandom();\n\n\n  DataType* gpu_data_col_major  = static_cast<DataType*>(sycl_device.allocate(tensor_col_major.size()*sizeof(DataType)));\n  DataType* gpu_data_row_major  = static_cast<DataType*>(sycl_device.allocate(tensor_row_major.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 5, ColMajor, IndexType>> gpu_col_major(gpu_data_col_major, tensorColMajorRange);\n  TensorMap<Tensor<DataType, 5, RowMajor, IndexType>> gpu_row_major(gpu_data_row_major, tensorRowMajorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_col_major, tensor_col_major.data(),(tensor_col_major.size())*sizeof(DataType));\n  gpu_row_major.device(sycl_device)=gpu_col_major.swap_layout();\n\n\n  // single volume patch: ColMajor\n  array<IndexType, 6> patchColMajorTensorRange={{sizeDim0,1, 1, 1, sizeDim1*sizeDim2*sizeDim3, sizeDim4}};\n  Tensor<DataType, 6, DataLayout,IndexType> single_voxel_patch_col_major(patchColMajorTensorRange);\n  size_t patchTensorBuffSize =single_voxel_patch_col_major.size()*sizeof(DataType);\n  DataType* gpu_data_single_voxel_patch_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 6, DataLayout,IndexType>> gpu_single_voxel_patch_col_major(gpu_data_single_voxel_patch_col_major, patchColMajorTensorRange);\n  gpu_single_voxel_patch_col_major.device(sycl_device)=gpu_col_major.extract_volume_patches(1, 1, 1);\n  sycl_device.memcpyDeviceToHost(single_voxel_patch_col_major.data(), gpu_data_single_voxel_patch_col_major, patchTensorBuffSize);\n\n\n  VERIFY_IS_EQUAL(single_voxel_patch_col_major.dimension(0), 4);\n  VERIFY_IS_EQUAL(single_voxel_patch_col_major.dimension(1), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch_col_major.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch_col_major.dimension(3), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch_col_major.dimension(4), 2 * 3 * 5);\n  VERIFY_IS_EQUAL(single_voxel_patch_col_major.dimension(5), 7);\n\n  array<IndexType, 6> patchRowMajorTensorRange={{sizeDim4, sizeDim1*sizeDim2*sizeDim3, 1, 1, 1, sizeDim0}};\n  Tensor<DataType, 6, RowMajor,IndexType> single_voxel_patch_row_major(patchRowMajorTensorRange);\n  patchTensorBuffSize =single_voxel_patch_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_single_voxel_patch_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 6, RowMajor,IndexType>> gpu_single_voxel_patch_row_major(gpu_data_single_voxel_patch_row_major, patchRowMajorTensorRange);\n  gpu_single_voxel_patch_row_major.device(sycl_device)=gpu_row_major.extract_volume_patches(1, 1, 1);\n  sycl_device.memcpyDeviceToHost(single_voxel_patch_row_major.data(), gpu_data_single_voxel_patch_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(0), 7);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(1), 2 * 3 * 5);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(3), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(4), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(5), 4);\n\n sycl_device.memcpyDeviceToHost(tensor_row_major.data(), gpu_data_row_major, (tensor_col_major.size())*sizeof(DataType));\n for (IndexType i = 0; i < tensor_col_major.size(); ++i) {\n       VERIFY_IS_EQUAL(tensor_col_major.data()[i], single_voxel_patch_col_major.data()[i]);\n    VERIFY_IS_EQUAL(tensor_row_major.data()[i], single_voxel_patch_row_major.data()[i]);\n    VERIFY_IS_EQUAL(tensor_col_major.data()[i], tensor_row_major.data()[i]);\n  }\n\n\n  sycl_device.deallocate(gpu_data_col_major);\n  sycl_device.deallocate(gpu_data_row_major);\n  sycl_device.deallocate(gpu_data_single_voxel_patch_col_major);\n  sycl_device.deallocate(gpu_data_single_voxel_patch_row_major);\n}\n\ntemplate <typename DataType, typename IndexType>\nstatic void test_entire_volume_patch_sycl(const Eigen::SyclDevice& sycl_device)\n{\n  const int depth = 4;\n  const int patch_z = 2;\n  const int patch_y = 3;\n  const int patch_x = 5;\n  const int batch = 7;\n\n  array<IndexType, 5> tensorColMajorRange = {{depth, patch_z, patch_y, patch_x, batch}};\n  array<IndexType, 5> tensorRowMajorRange = {{batch, patch_x, patch_y, patch_z, depth}};\n  Tensor<DataType, 5, DataLayout,IndexType> tensor_col_major(tensorColMajorRange);\n  Tensor<DataType, 5, RowMajor,IndexType> tensor_row_major(tensorRowMajorRange);\n  tensor_col_major.setRandom();\n\n\n    DataType* gpu_data_col_major  = static_cast<DataType*>(sycl_device.allocate(tensor_col_major.size()*sizeof(DataType)));\n    DataType* gpu_data_row_major  = static_cast<DataType*>(sycl_device.allocate(tensor_row_major.size()*sizeof(DataType)));\n    TensorMap<Tensor<DataType, 5, ColMajor, IndexType>> gpu_col_major(gpu_data_col_major, tensorColMajorRange);\n    TensorMap<Tensor<DataType, 5, RowMajor, IndexType>> gpu_row_major(gpu_data_row_major, tensorRowMajorRange);\n\n    sycl_device.memcpyHostToDevice(gpu_data_col_major, tensor_col_major.data(),(tensor_col_major.size())*sizeof(DataType));\n    gpu_row_major.device(sycl_device)=gpu_col_major.swap_layout();\n    sycl_device.memcpyDeviceToHost(tensor_row_major.data(), gpu_data_row_major, (tensor_col_major.size())*sizeof(DataType));\n\n\n    // single volume patch: ColMajor\n    array<IndexType, 6> patchColMajorTensorRange={{depth,patch_z, patch_y, patch_x, patch_z*patch_y*patch_x, batch}};\n    Tensor<DataType, 6, DataLayout,IndexType> entire_volume_patch_col_major(patchColMajorTensorRange);\n    size_t patchTensorBuffSize =entire_volume_patch_col_major.size()*sizeof(DataType);\n    DataType* gpu_data_entire_volume_patch_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n    TensorMap<Tensor<DataType, 6, DataLayout,IndexType>> gpu_entire_volume_patch_col_major(gpu_data_entire_volume_patch_col_major, patchColMajorTensorRange);\n    gpu_entire_volume_patch_col_major.device(sycl_device)=gpu_col_major.extract_volume_patches(patch_z, patch_y, patch_x);\n    sycl_device.memcpyDeviceToHost(entire_volume_patch_col_major.data(), gpu_data_entire_volume_patch_col_major, patchTensorBuffSize);\n\n\n//  Tensor<float, 5> tensor(depth, patch_z, patch_y, patch_x, batch);\n//  tensor.setRandom();\n//  Tensor<float, 5, RowMajor> tensor_row_major = tensor.swap_layout();\n\n  //Tensor<float, 6> entire_volume_patch;\n  //entire_volume_patch = tensor.extract_volume_patches(patch_z, patch_y, patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch_col_major.dimension(0), depth);\n  VERIFY_IS_EQUAL(entire_volume_patch_col_major.dimension(1), patch_z);\n  VERIFY_IS_EQUAL(entire_volume_patch_col_major.dimension(2), patch_y);\n  VERIFY_IS_EQUAL(entire_volume_patch_col_major.dimension(3), patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch_col_major.dimension(4), patch_z * patch_y * patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch_col_major.dimension(5), batch);\n\n//  Tensor<float, 6, RowMajor> entire_volume_patch_row_major;\n  //entire_volume_patch_row_major = tensor_row_major.extract_volume_patches(patch_z, patch_y, patch_x);\n\n  array<IndexType, 6> patchRowMajorTensorRange={{batch,patch_z*patch_y*patch_x, patch_x, patch_y, patch_z, depth}};\n  Tensor<DataType, 6, RowMajor,IndexType> entire_volume_patch_row_major(patchRowMajorTensorRange);\n  patchTensorBuffSize =entire_volume_patch_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_entire_volume_patch_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 6, RowMajor,IndexType>> gpu_entire_volume_patch_row_major(gpu_data_entire_volume_patch_row_major, patchRowMajorTensorRange);\n  gpu_entire_volume_patch_row_major.device(sycl_device)=gpu_row_major.extract_volume_patches(patch_z, patch_y, patch_x);\n  sycl_device.memcpyDeviceToHost(entire_volume_patch_row_major.data(), gpu_data_entire_volume_patch_row_major, patchTensorBuffSize);\n\n\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(0), batch);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(1), patch_z * patch_y * patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(2), patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(3), patch_y);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(4), patch_z);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(5), depth);\n\n  const int dz = patch_z - 1;\n  const int dy = patch_y - 1;\n  const int dx = patch_x - 1;\n\n  const int forward_pad_z = dz / 2;\n  const int forward_pad_y = dy / 2;\n  const int forward_pad_x = dx / 2;\n\n  for (int pz = 0; pz < patch_z; pz++) {\n    for (int py = 0; py < patch_y; py++) {\n      for (int px = 0; px < patch_x; px++) {\n        const int patchId = pz + patch_z * (py + px * patch_y);\n        for (int z = 0; z < patch_z; z++) {\n          for (int y = 0; y < patch_y; y++) {\n            for (int x = 0; x < patch_x; x++) {\n              for (int b = 0; b < batch; b++) {\n                for (int d = 0; d < depth; d++) {\n                  float expected = 0.0f;\n                  float expected_row_major = 0.0f;\n                  const int eff_z = z - forward_pad_z + pz;\n                  const int eff_y = y - forward_pad_y + py;\n                  const int eff_x = x - forward_pad_x + px;\n                  if (eff_z >= 0 && eff_y >= 0 && eff_x >= 0 &&\n                      eff_z < patch_z && eff_y < patch_y && eff_x < patch_x) {\n                    expected = tensor_col_major(d, eff_z, eff_y, eff_x, b);\n                    expected_row_major = tensor_row_major(b, eff_x, eff_y, eff_z, d);\n                  }\n                  VERIFY_IS_EQUAL(entire_volume_patch_col_major(d, z, y, x, patchId, b), expected);\n                  VERIFY_IS_EQUAL(entire_volume_patch_row_major(b, patchId, x, y, z, d), expected_row_major);\n                }\n              }\n            }\n          }\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data_col_major);\n  sycl_device.deallocate(gpu_data_row_major);\n  sycl_device.deallocate(gpu_data_entire_volume_patch_col_major);\n  sycl_device.deallocate(gpu_data_entire_volume_patch_row_major);\n}\n\n\n\ntemplate<typename DataType, typename dev_Selector> void sycl_tensor_volume_patch_test_per_device(dev_Selector s){\nQueueInterface queueInterface(s);\nauto sycl_device = Eigen::SyclDevice(&queueInterface);\nstd::cout << \"Running on \" << s.template get_info<cl::sycl::info::device::name>() << std::endl;\ntest_single_voxel_patch_sycl<DataType, int64_t>(sycl_device);\ntest_entire_volume_patch_sycl<DataType, int64_t>(sycl_device);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_volume_patch_sycl)\n{\nfor (const auto& device :Eigen::get_sycl_supported_devices()) {\n  CALL_SUBTEST(sycl_tensor_volume_patch_test_per_device<float>(device));\n}\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/dgmres.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n// Copyright (C) 2012 desire Nuentsa <desire.nuentsa_wakam@inria.fr\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"../../test/sparse_solver.h\"\n#include <unsupported/Eigen/IterativeSolvers>\n\ntemplate<typename T> void test_dgmres_T()\n{\n  DGMRES<SparseMatrix<T>, DiagonalPreconditioner<T> > dgmres_colmajor_diag;\n  DGMRES<SparseMatrix<T>, IdentityPreconditioner    > dgmres_colmajor_I;\n  DGMRES<SparseMatrix<T>, IncompleteLUT<T> >           dgmres_colmajor_ilut;\n  //GMRES<SparseMatrix<T>, SSORPreconditioner<T> >     dgmres_colmajor_ssor;\n\n  CALL_SUBTEST( check_sparse_square_solving(dgmres_colmajor_diag)  );\n//   CALL_SUBTEST( check_sparse_square_solving(dgmres_colmajor_I)     );\n  CALL_SUBTEST( check_sparse_square_solving(dgmres_colmajor_ilut)     );\n  //CALL_SUBTEST( check_sparse_square_solving(dgmres_colmajor_ssor)     );\n}\n\nEIGEN_DECLARE_TEST(dgmres)\n{\n  CALL_SUBTEST_1(test_dgmres_T<double>());\n  CALL_SUBTEST_2(test_dgmres_T<std::complex<double> >());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/forward_adolc.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/Dense>\n\n#define NUMBER_DIRECTIONS 16\n#include <unsupported/Eigen/AdolcForward>\n\ntemplate<typename Vector>\nEIGEN_DONT_INLINE typename Vector::Scalar foo(const Vector& p)\n{\n  typedef typename Vector::Scalar Scalar;\n  return (p-Vector(Scalar(-1),Scalar(1.))).norm() + (p.array().sqrt().abs() * p.array().sin()).sum() + p.dot(p);\n}\n\ntemplate<typename Scalar_, int NX=Dynamic, int NY=Dynamic>\nstruct TestFunc1\n{\n  typedef Scalar_ Scalar;\n  enum {\n    InputsAtCompileTime = NX,\n    ValuesAtCompileTime = NY\n  };\n  typedef Matrix<Scalar,InputsAtCompileTime,1> InputType;\n  typedef Matrix<Scalar,ValuesAtCompileTime,1> ValueType;\n  typedef Matrix<Scalar,ValuesAtCompileTime,InputsAtCompileTime> JacobianType;\n\n  int m_inputs, m_values;\n\n  TestFunc1() : m_inputs(InputsAtCompileTime), m_values(ValuesAtCompileTime) {}\n  TestFunc1(int inputs_, int values_) : m_inputs(inputs_), m_values(values_) {}\n\n  int inputs() const { return m_inputs; }\n  int values() const { return m_values; }\n\n  template<typename T>\n  void operator() (const Matrix<T,InputsAtCompileTime,1>& x, Matrix<T,ValuesAtCompileTime,1>* _v) const\n  {\n    Matrix<T,ValuesAtCompileTime,1>& v = *_v;\n\n    v[0] = 2 * x[0] * x[0] + x[0] * x[1];\n    v[1] = 3 * x[1] * x[0] + 0.5 * x[1] * x[1];\n    if(inputs()>2)\n    {\n      v[0] += 0.5 * x[2];\n      v[1] += x[2];\n    }\n    if(values()>2)\n    {\n      v[2] = 3 * x[1] * x[0] * x[0];\n    }\n    if (inputs()>2 && values()>2)\n      v[2] *= x[2];\n  }\n\n  void operator() (const InputType& x, ValueType* v, JacobianType* _j) const\n  {\n    (*this)(x, v);\n\n    if(_j)\n    {\n      JacobianType& j = *_j;\n\n      j(0,0) = 4 * x[0] + x[1];\n      j(1,0) = 3 * x[1];\n\n      j(0,1) = x[0];\n      j(1,1) = 3 * x[0] + 2 * 0.5 * x[1];\n\n      if (inputs()>2)\n      {\n        j(0,2) = 0.5;\n        j(1,2) = 1;\n      }\n      if(values()>2)\n      {\n        j(2,0) = 3 * x[1] * 2 * x[0];\n        j(2,1) = 3 * x[0] * x[0];\n      }\n      if (inputs()>2 && values()>2)\n      {\n        j(2,0) *= x[2];\n        j(2,1) *= x[2];\n\n        j(2,2) = 3 * x[1] * x[0] * x[0];\n        j(2,2) = 3 * x[1] * x[0] * x[0];\n      }\n    }\n  }\n};\n\ntemplate<typename Func> void adolc_forward_jacobian(const Func& f)\n{\n    typename Func::InputType x = Func::InputType::Random(f.inputs());\n    typename Func::ValueType y(f.values()), yref(f.values());\n    typename Func::JacobianType j(f.values(),f.inputs()), jref(f.values(),f.inputs());\n\n    jref.setZero();\n    yref.setZero();\n    f(x,&yref,&jref);\n//     std::cerr << y.transpose() << \"\\n\\n\";;\n//     std::cerr << j << \"\\n\\n\";;\n\n    j.setZero();\n    y.setZero();\n    AdolcForwardJacobian<Func> autoj(f);\n    autoj(x, &y, &j);\n//     std::cerr << y.transpose() << \"\\n\\n\";;\n//     std::cerr << j << \"\\n\\n\";;\n\n    VERIFY_IS_APPROX(y, yref);\n    VERIFY_IS_APPROX(j, jref);\n}\n\nEIGEN_DECLARE_TEST(forward_adolc)\n{\n  adtl::setNumDir(NUMBER_DIRECTIONS);\n\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST(( adolc_forward_jacobian(TestFunc1<double,2,2>()) ));\n    CALL_SUBTEST(( adolc_forward_jacobian(TestFunc1<double,2,3>()) ));\n    CALL_SUBTEST(( adolc_forward_jacobian(TestFunc1<double,3,2>()) ));\n    CALL_SUBTEST(( adolc_forward_jacobian(TestFunc1<double,3,3>()) ));\n    CALL_SUBTEST(( adolc_forward_jacobian(TestFunc1<double>(3,3)) ));\n  }\n\n  {\n    // simple instantiation tests\n    Matrix<adtl::adouble,2,1> x;\n    foo(x);\n    Matrix<adtl::adouble,Dynamic,Dynamic> A(4,4);;\n    A.selfadjointView<Lower>().eigenvalues();\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/gmres.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n// Copyright (C) 2012 Kolja Brix <brix@igpm.rwth-aaachen.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"../../test/sparse_solver.h\"\n#include <Eigen/IterativeSolvers>\n\ntemplate<typename T> void test_gmres_T()\n{\n  GMRES<SparseMatrix<T>, DiagonalPreconditioner<T> > gmres_colmajor_diag;\n  GMRES<SparseMatrix<T>, IdentityPreconditioner    > gmres_colmajor_I;\n  GMRES<SparseMatrix<T>, IncompleteLUT<T> >           gmres_colmajor_ilut;\n  //GMRES<SparseMatrix<T>, SSORPreconditioner<T> >     gmres_colmajor_ssor;\n\n  CALL_SUBTEST( check_sparse_square_solving(gmres_colmajor_diag)  );\n//   CALL_SUBTEST( check_sparse_square_solving(gmres_colmajor_I)     );\n  CALL_SUBTEST( check_sparse_square_solving(gmres_colmajor_ilut)     );\n  //CALL_SUBTEST( check_sparse_square_solving(gmres_colmajor_ssor)     );\n}\n\nEIGEN_DECLARE_TEST(gmres)\n{\n  CALL_SUBTEST_1(test_gmres_T<double>());\n  CALL_SUBTEST_2(test_gmres_T<std::complex<double> >());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/idrs.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n// Copyright (C) 2012 Kolja Brix <brix@igpm.rwth-aaachen.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"../../test/sparse_solver.h\"\n#include <Eigen/IterativeSolvers>\n\ntemplate<typename T> void test_idrs_T()\n{\n  IDRS<SparseMatrix<T>, DiagonalPreconditioner<T> > idrs_colmajor_diag;\n  IDRS<SparseMatrix<T>, IncompleteLUT<T> >           idrs_colmajor_ilut;\n\n  CALL_SUBTEST( check_sparse_square_solving(idrs_colmajor_diag)  );\n  CALL_SUBTEST( check_sparse_square_solving(idrs_colmajor_ilut)     );\n}\n\nEIGEN_DECLARE_TEST(idrs)\n{\n  CALL_SUBTEST_1(test_idrs_T<double>());\n  CALL_SUBTEST_2(test_idrs_T<std::complex<double> >());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/kronecker_product.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Kolja Brix <brix@igpm.rwth-aachen.de>\n// Copyright (C) 2011 Andreas Platen <andiplaten@gmx.de>\n// Copyright (C) 2012 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#ifdef EIGEN_TEST_PART_1\n\n#include \"sparse.h\"\n#include <Eigen/SparseExtra>\n#include <Eigen/KroneckerProduct>\n\ntemplate<typename MatrixType>\nvoid check_dimension(const MatrixType& ab, const int rows,  const int cols)\n{\n  VERIFY_IS_EQUAL(ab.rows(), rows);\n  VERIFY_IS_EQUAL(ab.cols(), cols);\n}\n\n\ntemplate<typename MatrixType>\nvoid check_kronecker_product(const MatrixType& ab)\n{\n  VERIFY_IS_EQUAL(ab.rows(), 6);\n  VERIFY_IS_EQUAL(ab.cols(), 6);\n  VERIFY_IS_EQUAL(ab.nonZeros(),  36);\n  VERIFY_IS_APPROX(ab.coeff(0,0), -0.4017367630386106);\n  VERIFY_IS_APPROX(ab.coeff(0,1),  0.1056863433932735);\n  VERIFY_IS_APPROX(ab.coeff(0,2), -0.7255206194554212);\n  VERIFY_IS_APPROX(ab.coeff(0,3),  0.1908653336744706);\n  VERIFY_IS_APPROX(ab.coeff(0,4),  0.350864567234111);\n  VERIFY_IS_APPROX(ab.coeff(0,5), -0.0923032108308013);\n  VERIFY_IS_APPROX(ab.coeff(1,0),  0.415417514804677);\n  VERIFY_IS_APPROX(ab.coeff(1,1), -0.2369227701722048);\n  VERIFY_IS_APPROX(ab.coeff(1,2),  0.7502275131458511);\n  VERIFY_IS_APPROX(ab.coeff(1,3), -0.4278731019742696);\n  VERIFY_IS_APPROX(ab.coeff(1,4), -0.3628129162264507);\n  VERIFY_IS_APPROX(ab.coeff(1,5),  0.2069210808481275);\n  VERIFY_IS_APPROX(ab.coeff(2,0),  0.05465890160863986);\n  VERIFY_IS_APPROX(ab.coeff(2,1), -0.2634092511419858);\n  VERIFY_IS_APPROX(ab.coeff(2,2),  0.09871180285793758);\n  VERIFY_IS_APPROX(ab.coeff(2,3), -0.4757066334017702);\n  VERIFY_IS_APPROX(ab.coeff(2,4), -0.04773740823058334);\n  VERIFY_IS_APPROX(ab.coeff(2,5),  0.2300535609645254);\n  VERIFY_IS_APPROX(ab.coeff(3,0), -0.8172945853260133);\n  VERIFY_IS_APPROX(ab.coeff(3,1),  0.2150086428359221);\n  VERIFY_IS_APPROX(ab.coeff(3,2),  0.5825113847292743);\n  VERIFY_IS_APPROX(ab.coeff(3,3), -0.1532433770097174);\n  VERIFY_IS_APPROX(ab.coeff(3,4), -0.329383387282399);\n  VERIFY_IS_APPROX(ab.coeff(3,5),  0.08665207912033064);\n  VERIFY_IS_APPROX(ab.coeff(4,0),  0.8451267514863225);\n  VERIFY_IS_APPROX(ab.coeff(4,1), -0.481996458918977);\n  VERIFY_IS_APPROX(ab.coeff(4,2), -0.6023482390791535);\n  VERIFY_IS_APPROX(ab.coeff(4,3),  0.3435339347164565);\n  VERIFY_IS_APPROX(ab.coeff(4,4),  0.3406002157428891);\n  VERIFY_IS_APPROX(ab.coeff(4,5), -0.1942526344200915);\n  VERIFY_IS_APPROX(ab.coeff(5,0),  0.1111982482925399);\n  VERIFY_IS_APPROX(ab.coeff(5,1), -0.5358806424754169);\n  VERIFY_IS_APPROX(ab.coeff(5,2), -0.07925446559335647);\n  VERIFY_IS_APPROX(ab.coeff(5,3),  0.3819388757769038);\n  VERIFY_IS_APPROX(ab.coeff(5,4),  0.04481475387219876);\n  VERIFY_IS_APPROX(ab.coeff(5,5), -0.2159688616158057);\n}\n\n\ntemplate<typename MatrixType>\nvoid check_sparse_kronecker_product(const MatrixType& ab)\n{\n  VERIFY_IS_EQUAL(ab.rows(), 12);\n  VERIFY_IS_EQUAL(ab.cols(), 10);\n  VERIFY_IS_EQUAL(ab.nonZeros(), 3*2);\n  VERIFY_IS_APPROX(ab.coeff(3,0), -0.04);\n  VERIFY_IS_APPROX(ab.coeff(5,1),  0.05);\n  VERIFY_IS_APPROX(ab.coeff(0,6), -0.08);\n  VERIFY_IS_APPROX(ab.coeff(2,7),  0.10);\n  VERIFY_IS_APPROX(ab.coeff(6,8),  0.12);\n  VERIFY_IS_APPROX(ab.coeff(8,9), -0.15);\n}\n\n\nEIGEN_DECLARE_TEST(kronecker_product)\n{\n  // DM = dense matrix; SM = sparse matrix\n\n  Matrix<double, 2, 3> DM_a;\n  SparseMatrix<double> SM_a(2,3);\n  SM_a.insert(0,0) = DM_a.coeffRef(0,0) = -0.4461540300782201;\n  SM_a.insert(0,1) = DM_a.coeffRef(0,1) = -0.8057364375283049;\n  SM_a.insert(0,2) = DM_a.coeffRef(0,2) =  0.3896572459516341;\n  SM_a.insert(1,0) = DM_a.coeffRef(1,0) = -0.9076572187376921;\n  SM_a.insert(1,1) = DM_a.coeffRef(1,1) =  0.6469156566545853;\n  SM_a.insert(1,2) = DM_a.coeffRef(1,2) = -0.3658010398782789;\n\n  MatrixXd             DM_b(3,2);\n  SparseMatrix<double> SM_b(3,2);\n  SM_b.insert(0,0) = DM_b.coeffRef(0,0) =  0.9004440976767099;\n  SM_b.insert(0,1) = DM_b.coeffRef(0,1) = -0.2368830858139832;\n  SM_b.insert(1,0) = DM_b.coeffRef(1,0) = -0.9311078389941825;\n  SM_b.insert(1,1) = DM_b.coeffRef(1,1) =  0.5310335762980047;\n  SM_b.insert(2,0) = DM_b.coeffRef(2,0) = -0.1225112806872035;\n  SM_b.insert(2,1) = DM_b.coeffRef(2,1) =  0.5903998022741264;\n\n  SparseMatrix<double,RowMajor> SM_row_a(SM_a), SM_row_b(SM_b);\n\n  // test DM_fixedSize = kroneckerProduct(DM_block,DM)\n  Matrix<double, 6, 6> DM_fix_ab = kroneckerProduct(DM_a.topLeftCorner<2,3>(),DM_b);\n\n  CALL_SUBTEST(check_kronecker_product(DM_fix_ab));\n  CALL_SUBTEST(check_kronecker_product(kroneckerProduct(DM_a.topLeftCorner<2,3>(),DM_b)));\n\n  for(int i=0;i<DM_fix_ab.rows();++i)\n    for(int j=0;j<DM_fix_ab.cols();++j)\n       VERIFY_IS_APPROX(kroneckerProduct(DM_a,DM_b).coeff(i,j), DM_fix_ab(i,j));\n\n  // test DM_block = kroneckerProduct(DM,DM)\n  MatrixXd DM_block_ab(10,15);\n  DM_block_ab.block<6,6>(2,5) = kroneckerProduct(DM_a,DM_b);\n  CALL_SUBTEST(check_kronecker_product(DM_block_ab.block<6,6>(2,5)));\n\n  // test DM = kroneckerProduct(DM,DM)\n  MatrixXd DM_ab = kroneckerProduct(DM_a,DM_b);\n  CALL_SUBTEST(check_kronecker_product(DM_ab));\n  CALL_SUBTEST(check_kronecker_product(kroneckerProduct(DM_a,DM_b)));\n\n  // test SM = kroneckerProduct(SM,DM)\n  SparseMatrix<double> SM_ab = kroneckerProduct(SM_a,DM_b);\n  CALL_SUBTEST(check_kronecker_product(SM_ab));\n  SparseMatrix<double,RowMajor> SM_ab2 = kroneckerProduct(SM_a,DM_b);\n  CALL_SUBTEST(check_kronecker_product(SM_ab2));\n  CALL_SUBTEST(check_kronecker_product(kroneckerProduct(SM_a,DM_b)));\n\n  // test SM = kroneckerProduct(DM,SM)\n  SM_ab.setZero();\n  SM_ab.insert(0,0)=37.0;\n  SM_ab = kroneckerProduct(DM_a,SM_b);\n  CALL_SUBTEST(check_kronecker_product(SM_ab));\n  SM_ab2.setZero();\n  SM_ab2.insert(0,0)=37.0;\n  SM_ab2 = kroneckerProduct(DM_a,SM_b);\n  CALL_SUBTEST(check_kronecker_product(SM_ab2));\n  CALL_SUBTEST(check_kronecker_product(kroneckerProduct(DM_a,SM_b)));\n\n  // test SM = kroneckerProduct(SM,SM)\n  SM_ab.resize(2,33);\n  SM_ab.insert(0,0)=37.0;\n  SM_ab = kroneckerProduct(SM_a,SM_b);\n  CALL_SUBTEST(check_kronecker_product(SM_ab));\n  SM_ab2.resize(5,11);\n  SM_ab2.insert(0,0)=37.0;\n  SM_ab2 = kroneckerProduct(SM_a,SM_b);\n  CALL_SUBTEST(check_kronecker_product(SM_ab2));\n  CALL_SUBTEST(check_kronecker_product(kroneckerProduct(SM_a,SM_b)));\n\n  // test SM = kroneckerProduct(SM,SM) with sparse pattern\n  SM_a.resize(4,5);\n  SM_b.resize(3,2);\n  SM_a.resizeNonZeros(0);\n  SM_b.resizeNonZeros(0);\n  SM_a.insert(1,0) = -0.1;\n  SM_a.insert(0,3) = -0.2;\n  SM_a.insert(2,4) =  0.3;\n  SM_a.finalize();\n\n  SM_b.insert(0,0) =  0.4;\n  SM_b.insert(2,1) = -0.5;\n  SM_b.finalize();\n  SM_ab.resize(1,1);\n  SM_ab.insert(0,0)=37.0;\n  SM_ab = kroneckerProduct(SM_a,SM_b);\n  CALL_SUBTEST(check_sparse_kronecker_product(SM_ab));\n\n  // test dimension of result of DM = kroneckerProduct(DM,DM)\n  MatrixXd DM_a2(2,1);\n  MatrixXd DM_b2(5,4);\n  MatrixXd DM_ab2 = kroneckerProduct(DM_a2,DM_b2);\n  CALL_SUBTEST(check_dimension(DM_ab2,2*5,1*4));\n  DM_a2.resize(10,9);\n  DM_b2.resize(4,8);\n  DM_ab2 = kroneckerProduct(DM_a2,DM_b2);\n  CALL_SUBTEST(check_dimension(DM_ab2,10*4,9*8));\n\n  for(int i = 0; i < g_repeat; i++)\n  {\n    double density = Eigen::internal::random<double>(0.01,0.5);\n    int ra = Eigen::internal::random<int>(1,50);\n    int ca = Eigen::internal::random<int>(1,50);\n    int rb = Eigen::internal::random<int>(1,50);\n    int cb = Eigen::internal::random<int>(1,50);\n    SparseMatrix<float,ColMajor> sA(ra,ca), sB(rb,cb), sC;\n    SparseMatrix<float,RowMajor> sC2;\n    MatrixXf dA(ra,ca), dB(rb,cb), dC;\n    initSparse(density, dA, sA);\n    initSparse(density, dB, sB);\n\n    sC = kroneckerProduct(sA,sB);\n    dC = kroneckerProduct(dA,dB);\n    VERIFY_IS_APPROX(MatrixXf(sC),dC);\n\n    sC = kroneckerProduct(sA.transpose(),sB);\n    dC = kroneckerProduct(dA.transpose(),dB);\n    VERIFY_IS_APPROX(MatrixXf(sC),dC);\n\n    sC = kroneckerProduct(sA.transpose(),sB.transpose());\n    dC = kroneckerProduct(dA.transpose(),dB.transpose());\n    VERIFY_IS_APPROX(MatrixXf(sC),dC);\n\n    sC = kroneckerProduct(sA,sB.transpose());\n    dC = kroneckerProduct(dA,dB.transpose());\n    VERIFY_IS_APPROX(MatrixXf(sC),dC);\n\n    sC2 = kroneckerProduct(sA,sB);\n    dC = kroneckerProduct(dA,dB);\n    VERIFY_IS_APPROX(MatrixXf(sC2),dC);\n\n    sC2 = kroneckerProduct(dA,sB);\n    dC = kroneckerProduct(dA,dB);\n    VERIFY_IS_APPROX(MatrixXf(sC2),dC);\n\n    sC2 = kroneckerProduct(sA,dB);\n    dC = kroneckerProduct(dA,dB);\n    VERIFY_IS_APPROX(MatrixXf(sC2),dC);\n\n    sC2 = kroneckerProduct(2*sA,sB);\n    dC = kroneckerProduct(2*dA,dB);\n    VERIFY_IS_APPROX(MatrixXf(sC2),dC);\n  }\n}\n\n#endif\n\n#ifdef EIGEN_TEST_PART_2\n\n// simply check that for a dense kronecker product, sparse module is not needed\n#include \"main.h\"\n#include <Eigen/KroneckerProduct>\n\nEIGEN_DECLARE_TEST(kronecker_product)\n{\n  MatrixXd a(2,2), b(3,3), c;\n  a.setRandom();\n  b.setRandom();\n  c = kroneckerProduct(a,b);\n  VERIFY_IS_APPROX(c.block(3,3,3,3), a(1,1)*b);\n}\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/levenberg_marquardt.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n// Copyright (C) 2012 desire Nuentsa <desire.nuentsa_wakam@inria.fr\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n// FIXME: These tests all check for hard-coded values. Ideally, parameters and start estimates should be randomized.\n\n\n#include <stdio.h>\n\n#include \"main.h\"\n#include <unsupported/Eigen/LevenbergMarquardt>\n\n// This disables some useless Warnings on MSVC.\n// It is intended to be done for this test only.\n#include <Eigen/src/Core/util/DisableStupidWarnings.h>\n\nusing std::sqrt;\n\n// tolerance for chekcing number of iterations\n#define LM_EVAL_COUNT_TOL 4/3\n\nstruct lmder_functor : DenseFunctor<double>\n{\n    lmder_functor(void): DenseFunctor<double>(3,15) {}\n    int operator()(const VectorXd &x, VectorXd &fvec) const\n    {\n        double tmp1, tmp2, tmp3;\n        static const double y[15] = {1.4e-1, 1.8e-1, 2.2e-1, 2.5e-1, 2.9e-1, 3.2e-1, 3.5e-1,\n            3.9e-1, 3.7e-1, 5.8e-1, 7.3e-1, 9.6e-1, 1.34, 2.1, 4.39};\n\n        for (int i = 0; i < values(); i++)\n        {\n            tmp1 = i+1;\n            tmp2 = 16 - i - 1;\n            tmp3 = (i>=8)? tmp2 : tmp1;\n            fvec[i] = y[i] - (x[0] + tmp1/(x[1]*tmp2 + x[2]*tmp3));\n        }\n        return 0;\n    }\n\n    int df(const VectorXd &x, MatrixXd &fjac) const\n    {\n        double tmp1, tmp2, tmp3, tmp4;\n        for (int i = 0; i < values(); i++)\n        {\n            tmp1 = i+1;\n            tmp2 = 16 - i - 1;\n            tmp3 = (i>=8)? tmp2 : tmp1;\n            tmp4 = (x[1]*tmp2 + x[2]*tmp3); tmp4 = tmp4*tmp4;\n            fjac(i,0) = -1;\n            fjac(i,1) = tmp1*tmp2/tmp4;\n            fjac(i,2) = tmp1*tmp3/tmp4;\n        }\n        return 0;\n    }\n};\n\nvoid testLmder1()\n{\n  int n=3, info;\n\n  VectorXd x;\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, 1.);\n\n  // do the computation\n  lmder_functor functor;\n  LevenbergMarquardt<lmder_functor> lm(functor);\n  info = lm.lmder1(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 6);\n  VERIFY_IS_EQUAL(lm.njev(), 5);\n\n  // check norm\n  VERIFY_IS_APPROX(lm.fvec().blueNorm(), 0.09063596);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << 0.08241058, 1.133037, 2.343695;\n  VERIFY_IS_APPROX(x, x_ref);\n}\n\nvoid testLmder()\n{\n  const int m=15, n=3;\n  int info;\n  double fnorm, covfac;\n  VectorXd x;\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, 1.);\n\n  // do the computation\n  lmder_functor functor;\n  LevenbergMarquardt<lmder_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return values\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 6);\n  VERIFY_IS_EQUAL(lm.njev(), 5);\n\n  // check norm\n  fnorm = lm.fvec().blueNorm();\n  VERIFY_IS_APPROX(fnorm, 0.09063596);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << 0.08241058, 1.133037, 2.343695;\n  VERIFY_IS_APPROX(x, x_ref);\n\n  // check covariance\n  covfac = fnorm*fnorm/(m-n);\n  internal::covar(lm.matrixR(), lm.permutation().indices()); // TODO : move this as a function of lm\n\n  MatrixXd cov_ref(n,n);\n  cov_ref <<\n      0.0001531202,   0.002869941,  -0.002656662,\n      0.002869941,    0.09480935,   -0.09098995,\n      -0.002656662,   -0.09098995,    0.08778727;\n\n//  std::cout << fjac*covfac << std::endl;\n\n  MatrixXd cov;\n  cov =  covfac*lm.matrixR().topLeftCorner<n,n>();\n  VERIFY_IS_APPROX( cov, cov_ref);\n  // TODO: why isn't this allowed ? :\n  // VERIFY_IS_APPROX( covfac*fjac.topLeftCorner<n,n>() , cov_ref);\n}\n\nstruct lmdif_functor : DenseFunctor<double>\n{\n    lmdif_functor(void) : DenseFunctor<double>(3,15) {}\n    int operator()(const VectorXd &x, VectorXd &fvec) const\n    {\n        int i;\n        double tmp1,tmp2,tmp3;\n        static const double y[15]={1.4e-1,1.8e-1,2.2e-1,2.5e-1,2.9e-1,3.2e-1,3.5e-1,3.9e-1,\n            3.7e-1,5.8e-1,7.3e-1,9.6e-1,1.34e0,2.1e0,4.39e0};\n\n        assert(x.size()==3);\n        assert(fvec.size()==15);\n        for (i=0; i<15; i++)\n        {\n            tmp1 = i+1;\n            tmp2 = 15 - i;\n            tmp3 = tmp1;\n\n            if (i >= 8) tmp3 = tmp2;\n            fvec[i] = y[i] - (x[0] + tmp1/(x[1]*tmp2 + x[2]*tmp3));\n        }\n        return 0;\n    }\n};\n\nvoid testLmdif1()\n{\n  const int n=3;\n  int info;\n\n  VectorXd x(n), fvec(15);\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, 1.);\n\n  // do the computation\n  lmdif_functor functor;\n  DenseIndex nfev;\n  info = LevenbergMarquardt<lmdif_functor>::lmdif1(functor, x, &nfev);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n//   VERIFY_IS_EQUAL(nfev, 26);\n\n  // check norm\n  functor(x, fvec);\n  VERIFY_IS_APPROX(fvec.blueNorm(), 0.09063596);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << 0.0824106, 1.1330366, 2.3436947;\n  VERIFY_IS_APPROX(x, x_ref);\n\n}\n\nvoid testLmdif()\n{\n  const int m=15, n=3;\n  int info;\n  double fnorm, covfac;\n  VectorXd x(n);\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, 1.);\n\n  // do the computation\n  lmdif_functor functor;\n  NumericalDiff<lmdif_functor> numDiff(functor);\n  LevenbergMarquardt<NumericalDiff<lmdif_functor> > lm(numDiff);\n  info = lm.minimize(x);\n\n  // check return values\n  VERIFY_IS_EQUAL(info, 1);\n//   VERIFY_IS_EQUAL(lm.nfev(), 26);\n\n  // check norm\n  fnorm = lm.fvec().blueNorm();\n  VERIFY_IS_APPROX(fnorm, 0.09063596);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << 0.08241058, 1.133037, 2.343695;\n  VERIFY_IS_APPROX(x, x_ref);\n\n  // check covariance\n  covfac = fnorm*fnorm/(m-n);\n  internal::covar(lm.matrixR(), lm.permutation().indices()); // TODO : move this as a function of lm\n\n  MatrixXd cov_ref(n,n);\n  cov_ref <<\n      0.0001531202,   0.002869942,  -0.002656662,\n      0.002869942,    0.09480937,   -0.09098997,\n      -0.002656662,   -0.09098997,    0.08778729;\n\n//  std::cout << fjac*covfac << std::endl;\n\n  MatrixXd cov;\n  cov =  covfac*lm.matrixR().topLeftCorner<n,n>();\n  VERIFY_IS_APPROX( cov, cov_ref);\n  // TODO: why isn't this allowed ? :\n  // VERIFY_IS_APPROX( covfac*fjac.topLeftCorner<n,n>() , cov_ref);\n}\n\nstruct chwirut2_functor : DenseFunctor<double>\n{\n    chwirut2_functor(void) : DenseFunctor<double>(3,54) {}\n    static const double m_x[54];\n    static const double m_y[54];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        int i;\n\n        assert(b.size()==3);\n        assert(fvec.size()==54);\n        for(i=0; i<54; i++) {\n            double x = m_x[i];\n            fvec[i] = exp(-b[0]*x)/(b[1]+b[2]*x) - m_y[i];\n        }\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==3);\n        assert(fjac.rows()==54);\n        assert(fjac.cols()==3);\n        for(int i=0; i<54; i++) {\n            double x = m_x[i];\n            double factor = 1./(b[1]+b[2]*x);\n            double e = exp(-b[0]*x);\n            fjac(i,0) = -x*e*factor;\n            fjac(i,1) = -e*factor*factor;\n            fjac(i,2) = -x*e*factor*factor;\n        }\n        return 0;\n    }\n};\nconst double chwirut2_functor::m_x[54] = { 0.500E0, 1.000E0, 1.750E0, 3.750E0, 5.750E0, 0.875E0, 2.250E0, 3.250E0, 5.250E0, 0.750E0, 1.750E0, 2.750E0, 4.750E0, 0.625E0, 1.250E0, 2.250E0, 4.250E0, .500E0, 3.000E0, .750E0, 3.000E0, 1.500E0, 6.000E0, 3.000E0, 6.000E0, 1.500E0, 3.000E0, .500E0, 2.000E0, 4.000E0, .750E0, 2.000E0, 5.000E0, .750E0, 2.250E0, 3.750E0, 5.750E0, 3.000E0, .750E0, 2.500E0, 4.000E0, .750E0, 2.500E0, 4.000E0, .750E0, 2.500E0, 4.000E0, .500E0, 6.000E0, 3.000E0, .500E0, 2.750E0, .500E0, 1.750E0};\nconst double chwirut2_functor::m_y[54] = { 92.9000E0 ,57.1000E0 ,31.0500E0 ,11.5875E0 ,8.0250E0 ,63.6000E0 ,21.4000E0 ,14.2500E0 ,8.4750E0 ,63.8000E0 ,26.8000E0 ,16.4625E0 ,7.1250E0 ,67.3000E0 ,41.0000E0 ,21.1500E0 ,8.1750E0 ,81.5000E0 ,13.1200E0 ,59.9000E0 ,14.6200E0 ,32.9000E0 ,5.4400E0 ,12.5600E0 ,5.4400E0 ,32.0000E0 ,13.9500E0 ,75.8000E0 ,20.0000E0 ,10.4200E0 ,59.5000E0 ,21.6700E0 ,8.5500E0 ,62.0000E0 ,20.2000E0 ,7.7600E0 ,3.7500E0 ,11.8100E0 ,54.7000E0 ,23.7000E0 ,11.5500E0 ,61.3000E0 ,17.7000E0 ,8.7400E0 ,59.2000E0 ,16.3000E0 ,8.6200E0 ,81.0000E0 ,4.8700E0 ,14.6200E0 ,81.7000E0 ,17.1700E0 ,81.3000E0 ,28.9000E0  };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/chwirut2.shtml\nvoid testNistChwirut2(void)\n{\n  const int n=3;\n  LevenbergMarquardtSpace::Status info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 0.1, 0.01, 0.02;\n  // do the computation\n  chwirut2_functor functor;\n  LevenbergMarquardt<chwirut2_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n//   VERIFY_IS_EQUAL(lm.nfev(), 10);\n  VERIFY_IS_EQUAL(lm.njev(), 8);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 5.1304802941E+02);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.6657666537E-01);\n  VERIFY_IS_APPROX(x[1], 5.1653291286E-03);\n  VERIFY_IS_APPROX(x[2], 1.2150007096E-02);\n\n  /*\n   * Second try\n   */\n  x<< 0.15, 0.008, 0.010;\n  // do the computation\n  lm.resetParameters();\n  lm.setFtol(1.E6*NumTraits<double>::epsilon());\n  lm.setXtol(1.E6*NumTraits<double>::epsilon());\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n//   VERIFY_IS_EQUAL(lm.nfev(), 7);\n  VERIFY_IS_EQUAL(lm.njev(), 6);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 5.1304802941E+02);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.6657666537E-01);\n  VERIFY_IS_APPROX(x[1], 5.1653291286E-03);\n  VERIFY_IS_APPROX(x[2], 1.2150007096E-02);\n}\n\n\nstruct misra1a_functor : DenseFunctor<double>\n{\n    misra1a_functor(void) : DenseFunctor<double>(2,14) {}\n    static const double m_x[14];\n    static const double m_y[14];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==2);\n        assert(fvec.size()==14);\n        for(int i=0; i<14; i++) {\n            fvec[i] = b[0]*(1.-exp(-b[1]*m_x[i])) - m_y[i] ;\n        }\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==2);\n        assert(fjac.rows()==14);\n        assert(fjac.cols()==2);\n        for(int i=0; i<14; i++) {\n            fjac(i,0) = (1.-exp(-b[1]*m_x[i]));\n            fjac(i,1) = (b[0]*m_x[i]*exp(-b[1]*m_x[i]));\n        }\n        return 0;\n    }\n};\nconst double misra1a_functor::m_x[14] = { 77.6E0, 114.9E0, 141.1E0, 190.8E0, 239.9E0, 289.0E0, 332.8E0, 378.4E0, 434.8E0, 477.3E0, 536.8E0, 593.1E0, 689.1E0, 760.0E0};\nconst double misra1a_functor::m_y[14] = { 10.07E0, 14.73E0, 17.94E0, 23.93E0, 29.61E0, 35.18E0, 40.02E0, 44.82E0, 50.76E0, 55.05E0, 61.01E0, 66.40E0, 75.47E0, 81.78E0};\n\n// http://www.itl.nist.gov/div898/strd/nls/data/misra1a.shtml\nvoid testNistMisra1a(void)\n{\n  const int n=2;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 500., 0.0001;\n  // do the computation\n  misra1a_functor functor;\n  LevenbergMarquardt<misra1a_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 19);\n  VERIFY_IS_EQUAL(lm.njev(), 15);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 1.2455138894E-01);\n  // check x\n  VERIFY_IS_APPROX(x[0], 2.3894212918E+02);\n  VERIFY_IS_APPROX(x[1], 5.5015643181E-04);\n\n  /*\n   * Second try\n   */\n  x<< 250., 0.0005;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 5);\n  VERIFY_IS_EQUAL(lm.njev(), 4);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 1.2455138894E-01);\n  // check x\n  VERIFY_IS_APPROX(x[0], 2.3894212918E+02);\n  VERIFY_IS_APPROX(x[1], 5.5015643181E-04);\n}\n\nstruct hahn1_functor : DenseFunctor<double>\n{\n    hahn1_functor(void) : DenseFunctor<double>(7,236) {}\n    static const double m_x[236];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        static const double m_y[236] = { .591E0 , 1.547E0 , 2.902E0 , 2.894E0 , 4.703E0 , 6.307E0 , 7.03E0  , 7.898E0 , 9.470E0 , 9.484E0 , 10.072E0 , 10.163E0 , 11.615E0 , 12.005E0 , 12.478E0 , 12.982E0 , 12.970E0 , 13.926E0 , 14.452E0 , 14.404E0 , 15.190E0 , 15.550E0 , 15.528E0 , 15.499E0 , 16.131E0 , 16.438E0 , 16.387E0 , 16.549E0 , 16.872E0 , 16.830E0 , 16.926E0 , 16.907E0 , 16.966E0 , 17.060E0 , 17.122E0 , 17.311E0 , 17.355E0 , 17.668E0 , 17.767E0 , 17.803E0 , 17.765E0 , 17.768E0 , 17.736E0 , 17.858E0 , 17.877E0 , 17.912E0 , 18.046E0 , 18.085E0 , 18.291E0 , 18.357E0 , 18.426E0 , 18.584E0 , 18.610E0 , 18.870E0 , 18.795E0 , 19.111E0 , .367E0 , .796E0 , 0.892E0 , 1.903E0 , 2.150E0 , 3.697E0 , 5.870E0 , 6.421E0 , 7.422E0 , 9.944E0 , 11.023E0 , 11.87E0  , 12.786E0 , 14.067E0 , 13.974E0 , 14.462E0 , 14.464E0 , 15.381E0 , 15.483E0 , 15.59E0  , 16.075E0 , 16.347E0 , 16.181E0 , 16.915E0 , 17.003E0 , 16.978E0 , 17.756E0 , 17.808E0 , 17.868E0 , 18.481E0 , 18.486E0 , 19.090E0 , 16.062E0 , 16.337E0 , 16.345E0 ,\n        16.388E0 , 17.159E0 , 17.116E0 , 17.164E0 , 17.123E0 , 17.979E0 , 17.974E0 , 18.007E0 , 17.993E0 , 18.523E0 , 18.669E0 , 18.617E0 , 19.371E0 , 19.330E0 , 0.080E0 , 0.248E0 , 1.089E0 , 1.418E0 , 2.278E0 , 3.624E0 , 4.574E0 , 5.556E0 , 7.267E0 , 7.695E0 , 9.136E0 , 9.959E0 , 9.957E0 , 11.600E0 , 13.138E0 , 13.564E0 , 13.871E0 , 13.994E0 , 14.947E0 , 15.473E0 , 15.379E0 , 15.455E0 , 15.908E0 , 16.114E0 , 17.071E0 , 17.135E0 , 17.282E0 , 17.368E0 , 17.483E0 , 17.764E0 , 18.185E0 , 18.271E0 , 18.236E0 , 18.237E0 , 18.523E0 , 18.627E0 , 18.665E0 , 19.086E0 , 0.214E0 , 0.943E0 , 1.429E0 , 2.241E0 , 2.951E0 , 3.782E0 , 4.757E0 , 5.602E0 , 7.169E0 , 8.920E0 , 10.055E0 , 12.035E0 , 12.861E0 , 13.436E0 , 14.167E0 , 14.755E0 , 15.168E0 , 15.651E0 , 15.746E0 , 16.216E0 , 16.445E0 , 16.965E0 , 17.121E0 , 17.206E0 , 17.250E0 , 17.339E0 , 17.793E0 , 18.123E0 , 18.49E0  , 18.566E0 , 18.645E0 , 18.706E0 , 18.924E0 , 19.1E0   , 0.375E0 , 0.471E0 , 1.504E0 , 2.204E0 , 2.813E0 , 4.765E0 , 9.835E0 , 10.040E0 , 11.946E0 , \n12.596E0 , \n13.303E0 , 13.922E0 , 14.440E0 , 14.951E0 , 15.627E0 , 15.639E0 , 15.814E0 , 16.315E0 , 16.334E0 , 16.430E0 , 16.423E0 , 17.024E0 , 17.009E0 , 17.165E0 , 17.134E0 , 17.349E0 , 17.576E0 , 17.848E0 , 18.090E0 , 18.276E0 , 18.404E0 , 18.519E0 , 19.133E0 , 19.074E0 , 19.239E0 , 19.280E0 , 19.101E0 , 19.398E0 , 19.252E0 , 19.89E0  , 20.007E0 , 19.929E0 , 19.268E0 , 19.324E0 , 20.049E0 , 20.107E0 , 20.062E0 , 20.065E0 , 19.286E0 , 19.972E0 , 20.088E0 , 20.743E0 , 20.83E0  , 20.935E0 , 21.035E0 , 20.93E0  , 21.074E0 , 21.085E0 , 20.935E0 };\n\n        //        int called=0; printf(\"call hahn1_functor with  iflag=%d, called=%d\\n\", iflag, called); if (iflag==1) called++;\n\n        assert(b.size()==7);\n        assert(fvec.size()==236);\n        for(int i=0; i<236; i++) {\n            double x=m_x[i], xx=x*x, xxx=xx*x;\n            fvec[i] = (b[0]+b[1]*x+b[2]*xx+b[3]*xxx) / (1.+b[4]*x+b[5]*xx+b[6]*xxx) - m_y[i];\n        }\n        return 0;\n    }\n\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==7);\n        assert(fjac.rows()==236);\n        assert(fjac.cols()==7);\n        for(int i=0; i<236; i++) {\n            double x=m_x[i], xx=x*x, xxx=xx*x;\n            double fact = 1./(1.+b[4]*x+b[5]*xx+b[6]*xxx);\n            fjac(i,0) = 1.*fact;\n            fjac(i,1) = x*fact;\n            fjac(i,2) = xx*fact;\n            fjac(i,3) = xxx*fact;\n            fact = - (b[0]+b[1]*x+b[2]*xx+b[3]*xxx) * fact * fact;\n            fjac(i,4) = x*fact;\n            fjac(i,5) = xx*fact;\n            fjac(i,6) = xxx*fact;\n        }\n        return 0;\n    }\n};\nconst double hahn1_functor::m_x[236] = { 24.41E0 , 34.82E0 , 44.09E0 , 45.07E0 , 54.98E0 , 65.51E0 , 70.53E0 , 75.70E0 , 89.57E0 , 91.14E0 , 96.40E0 , 97.19E0 , 114.26E0 , 120.25E0 , 127.08E0 , 133.55E0 , 133.61E0 , 158.67E0 , 172.74E0 , 171.31E0 , 202.14E0 , 220.55E0 , 221.05E0 , 221.39E0 , 250.99E0 , 268.99E0 , 271.80E0 , 271.97E0 , 321.31E0 , 321.69E0 , 330.14E0 , 333.03E0 , 333.47E0 , 340.77E0 , 345.65E0 , 373.11E0 , 373.79E0 , 411.82E0 , 419.51E0 , 421.59E0 , 422.02E0 , 422.47E0 , 422.61E0 , 441.75E0 , 447.41E0 , 448.7E0  , 472.89E0 , 476.69E0 , 522.47E0 , 522.62E0 , 524.43E0 , 546.75E0 , 549.53E0 , 575.29E0 , 576.00E0 , 625.55E0 , 20.15E0 , 28.78E0 , 29.57E0 , 37.41E0 , 39.12E0 , 50.24E0 , 61.38E0 , 66.25E0 , 73.42E0 , 95.52E0 , 107.32E0 , 122.04E0 , 134.03E0 , 163.19E0 , 163.48E0 , 175.70E0 , 179.86E0 , 211.27E0 , 217.78E0 , 219.14E0 , 262.52E0 , 268.01E0 , 268.62E0 , 336.25E0 , 337.23E0 , 339.33E0 , 427.38E0 , 428.58E0 , 432.68E0 , 528.99E0 , 531.08E0 , 628.34E0 , 253.24E0 , 273.13E0 , 273.66E0 ,\n282.10E0 , 346.62E0 , 347.19E0 , 348.78E0 , 351.18E0 , 450.10E0 , 450.35E0 , 451.92E0 , 455.56E0 , 552.22E0 , 553.56E0 , 555.74E0 , 652.59E0 , 656.20E0 , 14.13E0 , 20.41E0 , 31.30E0 , 33.84E0 , 39.70E0 , 48.83E0 , 54.50E0 , 60.41E0 , 72.77E0 , 75.25E0 , 86.84E0 , 94.88E0 , 96.40E0 , 117.37E0 , 139.08E0 , 147.73E0 , 158.63E0 , 161.84E0 , 192.11E0 , 206.76E0 , 209.07E0 , 213.32E0 , 226.44E0 , 237.12E0 , 330.90E0 , 358.72E0 , 370.77E0 , 372.72E0 , 396.24E0 , 416.59E0 , 484.02E0 , 495.47E0 , 514.78E0 , 515.65E0 , 519.47E0 , 544.47E0 , 560.11E0 , 620.77E0 , 18.97E0 , 28.93E0 , 33.91E0 , 40.03E0 , 44.66E0 , 49.87E0 , 55.16E0 , 60.90E0 , 72.08E0 , 85.15E0 , 97.06E0 , 119.63E0 , 133.27E0 , 143.84E0 , 161.91E0 , 180.67E0 , 198.44E0 , 226.86E0 , 229.65E0 , 258.27E0 , 273.77E0 , 339.15E0 , 350.13E0 , 362.75E0 , 371.03E0 , 393.32E0 , 448.53E0 , 473.78E0 , 511.12E0 , 524.70E0 , 548.75E0 , 551.64E0 , 574.02E0 , 623.86E0 , 21.46E0 , 24.33E0 , 33.43E0 , 39.22E0 , 44.18E0 , 55.02E0 , 94.33E0 , 96.44E0 , 118.82E0 , 128.48E0 ,\n141.94E0 , 156.92E0 , 171.65E0 , 190.00E0 , 223.26E0 , 223.88E0 , 231.50E0 , 265.05E0 , 269.44E0 , 271.78E0 , 273.46E0 , 334.61E0 , 339.79E0 , 349.52E0 , 358.18E0 , 377.98E0 , 394.77E0 , 429.66E0 , 468.22E0 , 487.27E0 , 519.54E0 , 523.03E0 , 612.99E0 , 638.59E0 , 641.36E0 , 622.05E0 , 631.50E0 , 663.97E0 , 646.9E0  , 748.29E0 , 749.21E0 , 750.14E0 , 647.04E0 , 646.89E0 , 746.9E0  , 748.43E0 , 747.35E0 , 749.27E0 , 647.61E0 , 747.78E0 , 750.51E0 , 851.37E0 , 845.97E0 , 847.54E0 , 849.93E0 , 851.61E0 , 849.75E0 , 850.98E0 , 848.23E0};\n\n// http://www.itl.nist.gov/div898/strd/nls/data/hahn1.shtml\nvoid testNistHahn1(void)\n{\n  const int  n=7;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 10., -1., .05, -.00001, -.05, .001, -.000001;\n  // do the computation\n  hahn1_functor functor;\n  LevenbergMarquardt<hahn1_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 11);\n  VERIFY_IS_EQUAL(lm.njev(), 10);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 1.5324382854E+00);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.0776351733E+00);\n  VERIFY_IS_APPROX(x[1],-1.2269296921E-01);\n  VERIFY_IS_APPROX(x[2], 4.0863750610E-03);\n  VERIFY_IS_APPROX(x[3],-1.426264e-06); // shoulde be : -1.4262662514E-06\n  VERIFY_IS_APPROX(x[4],-5.7609940901E-03);\n  VERIFY_IS_APPROX(x[5], 2.4053735503E-04);\n  VERIFY_IS_APPROX(x[6],-1.2314450199E-07);\n\n  /*\n   * Second try\n   */\n  x<< .1, -.1, .005, -.000001, -.005, .0001, -.0000001;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n//   VERIFY_IS_EQUAL(lm.nfev(), 11);\n  VERIFY_IS_EQUAL(lm.njev(), 10);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 1.5324382854E+00);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.077640); // should be :  1.0776351733E+00\n  VERIFY_IS_APPROX(x[1], -0.1226933); // should be : -1.2269296921E-01\n  VERIFY_IS_APPROX(x[2], 0.004086383); // should be : 4.0863750610E-03\n  VERIFY_IS_APPROX(x[3], -1.426277e-06); // shoulde be : -1.4262662514E-06\n  VERIFY_IS_APPROX(x[4],-5.7609940901E-03);\n  VERIFY_IS_APPROX(x[5], 0.00024053772); // should be : 2.4053735503E-04\n  VERIFY_IS_APPROX(x[6], -1.231450e-07); // should be : -1.2314450199E-07\n\n}\n\nstruct misra1d_functor : DenseFunctor<double>\n{\n    misra1d_functor(void) : DenseFunctor<double>(2,14) {}\n    static const double x[14];\n    static const double y[14];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==2);\n        assert(fvec.size()==14);\n        for(int i=0; i<14; i++) {\n            fvec[i] = b[0]*b[1]*x[i]/(1.+b[1]*x[i]) - y[i];\n        }\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==2);\n        assert(fjac.rows()==14);\n        assert(fjac.cols()==2);\n        for(int i=0; i<14; i++) {\n            double den = 1.+b[1]*x[i];\n            fjac(i,0) = b[1]*x[i] / den;\n            fjac(i,1) = b[0]*x[i]*(den-b[1]*x[i])/den/den;\n        }\n        return 0;\n    }\n};\nconst double misra1d_functor::x[14] = { 77.6E0, 114.9E0, 141.1E0, 190.8E0, 239.9E0, 289.0E0, 332.8E0, 378.4E0, 434.8E0, 477.3E0, 536.8E0, 593.1E0, 689.1E0, 760.0E0};\nconst double misra1d_functor::y[14] = { 10.07E0, 14.73E0, 17.94E0, 23.93E0, 29.61E0, 35.18E0, 40.02E0, 44.82E0, 50.76E0, 55.05E0, 61.01E0, 66.40E0, 75.47E0, 81.78E0};\n\n// http://www.itl.nist.gov/div898/strd/nls/data/misra1d.shtml\nvoid testNistMisra1d(void)\n{\n  const int n=2;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 500., 0.0001;\n  // do the computation\n  misra1d_functor functor;\n  LevenbergMarquardt<misra1d_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 9);\n  VERIFY_IS_EQUAL(lm.njev(), 7);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 5.6419295283E-02);\n  // check x\n  VERIFY_IS_APPROX(x[0], 4.3736970754E+02);\n  VERIFY_IS_APPROX(x[1], 3.0227324449E-04);\n\n  /*\n   * Second try\n   */\n  x<< 450., 0.0003;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 4);\n  VERIFY_IS_EQUAL(lm.njev(), 3);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 5.6419295283E-02);\n  // check x\n  VERIFY_IS_APPROX(x[0], 4.3736970754E+02);\n  VERIFY_IS_APPROX(x[1], 3.0227324449E-04);\n}\n\n\nstruct lanczos1_functor : DenseFunctor<double>\n{\n    lanczos1_functor(void) : DenseFunctor<double>(6,24) {}\n    static const double x[24];\n    static const double y[24];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==6);\n        assert(fvec.size()==24);\n        for(int i=0; i<24; i++)\n            fvec[i] = b[0]*exp(-b[1]*x[i]) + b[2]*exp(-b[3]*x[i]) + b[4]*exp(-b[5]*x[i])  - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==6);\n        assert(fjac.rows()==24);\n        assert(fjac.cols()==6);\n        for(int i=0; i<24; i++) {\n            fjac(i,0) = exp(-b[1]*x[i]);\n            fjac(i,1) = -b[0]*x[i]*exp(-b[1]*x[i]);\n            fjac(i,2) = exp(-b[3]*x[i]);\n            fjac(i,3) = -b[2]*x[i]*exp(-b[3]*x[i]);\n            fjac(i,4) = exp(-b[5]*x[i]);\n            fjac(i,5) = -b[4]*x[i]*exp(-b[5]*x[i]);\n        }\n        return 0;\n    }\n};\nconst double lanczos1_functor::x[24] = { 0.000000000000E+00, 5.000000000000E-02, 1.000000000000E-01, 1.500000000000E-01, 2.000000000000E-01, 2.500000000000E-01, 3.000000000000E-01, 3.500000000000E-01, 4.000000000000E-01, 4.500000000000E-01, 5.000000000000E-01, 5.500000000000E-01, 6.000000000000E-01, 6.500000000000E-01, 7.000000000000E-01, 7.500000000000E-01, 8.000000000000E-01, 8.500000000000E-01, 9.000000000000E-01, 9.500000000000E-01, 1.000000000000E+00, 1.050000000000E+00, 1.100000000000E+00, 1.150000000000E+00 };\nconst double lanczos1_functor::y[24] = { 2.513400000000E+00 ,2.044333373291E+00 ,1.668404436564E+00 ,1.366418021208E+00 ,1.123232487372E+00 ,9.268897180037E-01 ,7.679338563728E-01 ,6.388775523106E-01 ,5.337835317402E-01 ,4.479363617347E-01 ,3.775847884350E-01 ,3.197393199326E-01 ,2.720130773746E-01 ,2.324965529032E-01 ,1.996589546065E-01 ,1.722704126914E-01 ,1.493405660168E-01 ,1.300700206922E-01 ,1.138119324644E-01 ,1.000415587559E-01 ,8.833209084540E-02 ,7.833544019350E-02 ,6.976693743449E-02 ,6.239312536719E-02 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/lanczos1.shtml\nvoid testNistLanczos1(void)\n{\n  const int n=6;\n  LevenbergMarquardtSpace::Status info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 1.2, 0.3, 5.6, 5.5, 6.5, 7.6;\n  // do the computation\n  lanczos1_functor functor;\n  LevenbergMarquardt<lanczos1_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, LevenbergMarquardtSpace::RelativeErrorTooSmall);\n  VERIFY_IS_EQUAL(lm.nfev(), 79);\n  VERIFY_IS_EQUAL(lm.njev(), 72);\n  // check norm^2\n  VERIFY(lm.fvec().squaredNorm() <= 1.4307867721E-25);\n  // check x\n  VERIFY_IS_APPROX(x[0], 9.5100000027E-02);\n  VERIFY_IS_APPROX(x[1], 1.0000000001E+00);\n  VERIFY_IS_APPROX(x[2], 8.6070000013E-01);\n  VERIFY_IS_APPROX(x[3], 3.0000000002E+00);\n  VERIFY_IS_APPROX(x[4], 1.5575999998E+00);\n  VERIFY_IS_APPROX(x[5], 5.0000000001E+00);\n\n  /*\n   * Second try\n   */\n  x<< 0.5, 0.7, 3.6, 4.2, 4., 6.3;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, LevenbergMarquardtSpace::RelativeErrorTooSmall);\n  VERIFY_IS_EQUAL(lm.nfev(), 9);\n  VERIFY_IS_EQUAL(lm.njev(), 8);\n  // check norm^2\n  VERIFY(lm.fvec().squaredNorm() <= 1.4307867721E-25);\n  // check x\n  VERIFY_IS_APPROX(x[0], 9.5100000027E-02);\n  VERIFY_IS_APPROX(x[1], 1.0000000001E+00);\n  VERIFY_IS_APPROX(x[2], 8.6070000013E-01);\n  VERIFY_IS_APPROX(x[3], 3.0000000002E+00);\n  VERIFY_IS_APPROX(x[4], 1.5575999998E+00);\n  VERIFY_IS_APPROX(x[5], 5.0000000001E+00);\n\n}\n\nstruct rat42_functor : DenseFunctor<double>\n{\n    rat42_functor(void) : DenseFunctor<double>(3,9) {}\n    static const double x[9];\n    static const double y[9];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==3);\n        assert(fvec.size()==9);\n        for(int i=0; i<9; i++) {\n            fvec[i] = b[0] / (1.+exp(b[1]-b[2]*x[i])) - y[i];\n        }\n        return 0;\n    }\n\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==3);\n        assert(fjac.rows()==9);\n        assert(fjac.cols()==3);\n        for(int i=0; i<9; i++) {\n            double e = exp(b[1]-b[2]*x[i]);\n            fjac(i,0) = 1./(1.+e);\n            fjac(i,1) = -b[0]*e/(1.+e)/(1.+e);\n            fjac(i,2) = +b[0]*e*x[i]/(1.+e)/(1.+e);\n        }\n        return 0;\n    }\n};\nconst double rat42_functor::x[9] = { 9.000E0, 14.000E0, 21.000E0, 28.000E0, 42.000E0, 57.000E0, 63.000E0, 70.000E0, 79.000E0 };\nconst double rat42_functor::y[9] = { 8.930E0 ,10.800E0 ,18.590E0 ,22.330E0 ,39.350E0 ,56.110E0 ,61.730E0 ,64.620E0 ,67.080E0 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/ratkowsky2.shtml\nvoid testNistRat42(void)\n{\n  const int n=3;\n  LevenbergMarquardtSpace::Status info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 100., 1., 0.1;\n  // do the computation\n  rat42_functor functor;\n  LevenbergMarquardt<rat42_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, LevenbergMarquardtSpace::RelativeReductionTooSmall);\n  VERIFY_IS_EQUAL(lm.nfev(), 10);\n  VERIFY_IS_EQUAL(lm.njev(), 8);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 8.0565229338E+00);\n  // check x\n  VERIFY_IS_APPROX(x[0], 7.2462237576E+01);\n  VERIFY_IS_APPROX(x[1], 2.6180768402E+00);\n  VERIFY_IS_APPROX(x[2], 6.7359200066E-02);\n\n  /*\n   * Second try\n   */\n  x<< 75., 2.5, 0.07;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, LevenbergMarquardtSpace::RelativeReductionTooSmall);\n  VERIFY_IS_EQUAL(lm.nfev(), 6);\n  VERIFY_IS_EQUAL(lm.njev(), 5);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 8.0565229338E+00);\n  // check x\n  VERIFY_IS_APPROX(x[0], 7.2462237576E+01);\n  VERIFY_IS_APPROX(x[1], 2.6180768402E+00);\n  VERIFY_IS_APPROX(x[2], 6.7359200066E-02);\n}\n\nstruct MGH10_functor : DenseFunctor<double>\n{\n    MGH10_functor(void) : DenseFunctor<double>(3,16) {}\n    static const double x[16];\n    static const double y[16];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==3);\n        assert(fvec.size()==16);\n        for(int i=0; i<16; i++)\n            fvec[i] =  b[0] * exp(b[1]/(x[i]+b[2])) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==3);\n        assert(fjac.rows()==16);\n        assert(fjac.cols()==3);\n        for(int i=0; i<16; i++) {\n            double factor = 1./(x[i]+b[2]);\n            double e = exp(b[1]*factor);\n            fjac(i,0) = e;\n            fjac(i,1) = b[0]*factor*e;\n            fjac(i,2) = -b[1]*b[0]*factor*factor*e;\n        }\n        return 0;\n    }\n};\nconst double MGH10_functor::x[16] = { 5.000000E+01, 5.500000E+01, 6.000000E+01, 6.500000E+01, 7.000000E+01, 7.500000E+01, 8.000000E+01, 8.500000E+01, 9.000000E+01, 9.500000E+01, 1.000000E+02, 1.050000E+02, 1.100000E+02, 1.150000E+02, 1.200000E+02, 1.250000E+02 };\nconst double MGH10_functor::y[16] = { 3.478000E+04, 2.861000E+04, 2.365000E+04, 1.963000E+04, 1.637000E+04, 1.372000E+04, 1.154000E+04, 9.744000E+03, 8.261000E+03, 7.030000E+03, 6.005000E+03, 5.147000E+03, 4.427000E+03, 3.820000E+03, 3.307000E+03, 2.872000E+03 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/mgh10.shtml\nvoid testNistMGH10(void)\n{\n  const int n=3;\n  LevenbergMarquardtSpace::Status info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 2., 400000., 25000.;\n  // do the computation\n  MGH10_functor functor;\n  LevenbergMarquardt<MGH10_functor> lm(functor);\n  info = lm.minimize(x);\n  ++g_test_level;\n  VERIFY_IS_EQUAL(info, LevenbergMarquardtSpace::RelativeReductionTooSmall);\n  --g_test_level;\n  // was: VERIFY_IS_EQUAL(info, 1);\n\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 8.7945855171E+01);\n  // check x\n  VERIFY_IS_APPROX(x[0], 5.6096364710E-03);\n  VERIFY_IS_APPROX(x[1], 6.1813463463E+03);\n  VERIFY_IS_APPROX(x[2], 3.4522363462E+02);\n  \n  // check return value\n\n  ++g_test_level;\n  VERIFY_IS_EQUAL(lm.nfev(), 284 );\n  VERIFY_IS_EQUAL(lm.njev(), 249 );\n  --g_test_level;\n  VERIFY(lm.nfev() < 284 * LM_EVAL_COUNT_TOL);\n  VERIFY(lm.njev() < 249 * LM_EVAL_COUNT_TOL);\n\n  /*\n   * Second try\n   */\n  x<< 0.02, 4000., 250.;\n  // do the computation\n  info = lm.minimize(x);\n  ++g_test_level;\n  VERIFY_IS_EQUAL(info, LevenbergMarquardtSpace::RelativeReductionTooSmall);\n  // was: VERIFY_IS_EQUAL(info, 1);\n  --g_test_level;\n\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 8.7945855171E+01);\n  // check x\n  VERIFY_IS_APPROX(x[0], 5.6096364710E-03);\n  VERIFY_IS_APPROX(x[1], 6.1813463463E+03);\n  VERIFY_IS_APPROX(x[2], 3.4522363462E+02);\n  \n  // check return value\n  ++g_test_level;\n  VERIFY_IS_EQUAL(lm.nfev(), 126);\n  VERIFY_IS_EQUAL(lm.njev(), 116);\n  --g_test_level;\n  VERIFY(lm.nfev() < 126 * LM_EVAL_COUNT_TOL);\n  VERIFY(lm.njev() < 116 * LM_EVAL_COUNT_TOL);\n}\n\n\nstruct BoxBOD_functor : DenseFunctor<double>\n{\n    BoxBOD_functor(void) : DenseFunctor<double>(2,6) {}\n    static const double x[6];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        static const double y[6] = { 109., 149., 149., 191., 213., 224. };\n        assert(b.size()==2);\n        assert(fvec.size()==6);\n        for(int i=0; i<6; i++)\n            fvec[i] =  b[0]*(1.-exp(-b[1]*x[i])) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==2);\n        assert(fjac.rows()==6);\n        assert(fjac.cols()==2);\n        for(int i=0; i<6; i++) {\n            double e = exp(-b[1]*x[i]);\n            fjac(i,0) = 1.-e;\n            fjac(i,1) = b[0]*x[i]*e;\n        }\n        return 0;\n    }\n};\nconst double BoxBOD_functor::x[6] = { 1., 2., 3., 5., 7., 10. };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/boxbod.shtml\nvoid testNistBoxBOD(void)\n{\n  const int n=2;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 1., 1.;\n  // do the computation\n  BoxBOD_functor functor;\n  LevenbergMarquardt<BoxBOD_functor> lm(functor);\n  lm.setFtol(1.E6*NumTraits<double>::epsilon());\n  lm.setXtol(1.E6*NumTraits<double>::epsilon());\n  lm.setFactor(10);\n  info = lm.minimize(x);\n\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 1.1680088766E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 2.1380940889E+02);\n  VERIFY_IS_APPROX(x[1], 5.4723748542E-01);\n  \n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY(lm.nfev() < 31); // 31\n  VERIFY(lm.njev() < 25); // 25\n\n  /*\n   * Second try\n   */\n  x<< 100., 0.75;\n  // do the computation\n  lm.resetParameters();\n  lm.setFtol(NumTraits<double>::epsilon());\n  lm.setXtol( NumTraits<double>::epsilon());\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1); \n  ++g_test_level;\n  VERIFY_IS_EQUAL(lm.nfev(), 16 );\n  VERIFY_IS_EQUAL(lm.njev(), 15 );\n  --g_test_level;\n  VERIFY(lm.nfev() < 16 * LM_EVAL_COUNT_TOL);\n  VERIFY(lm.njev() < 15 * LM_EVAL_COUNT_TOL);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 1.1680088766E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 2.1380940889E+02);\n  VERIFY_IS_APPROX(x[1], 5.4723748542E-01);\n}\n\nstruct MGH17_functor : DenseFunctor<double>\n{\n    MGH17_functor(void) : DenseFunctor<double>(5,33) {}\n    static const double x[33];\n    static const double y[33];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==5);\n        assert(fvec.size()==33);\n        for(int i=0; i<33; i++)\n            fvec[i] =  b[0] + b[1]*exp(-b[3]*x[i]) +  b[2]*exp(-b[4]*x[i]) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==5);\n        assert(fjac.rows()==33);\n        assert(fjac.cols()==5);\n        for(int i=0; i<33; i++) {\n            fjac(i,0) = 1.;\n            fjac(i,1) = exp(-b[3]*x[i]);\n            fjac(i,2) = exp(-b[4]*x[i]);\n            fjac(i,3) = -x[i]*b[1]*exp(-b[3]*x[i]);\n            fjac(i,4) = -x[i]*b[2]*exp(-b[4]*x[i]);\n        }\n        return 0;\n    }\n};\nconst double MGH17_functor::x[33] = { 0.000000E+00, 1.000000E+01, 2.000000E+01, 3.000000E+01, 4.000000E+01, 5.000000E+01, 6.000000E+01, 7.000000E+01, 8.000000E+01, 9.000000E+01, 1.000000E+02, 1.100000E+02, 1.200000E+02, 1.300000E+02, 1.400000E+02, 1.500000E+02, 1.600000E+02, 1.700000E+02, 1.800000E+02, 1.900000E+02, 2.000000E+02, 2.100000E+02, 2.200000E+02, 2.300000E+02, 2.400000E+02, 2.500000E+02, 2.600000E+02, 2.700000E+02, 2.800000E+02, 2.900000E+02, 3.000000E+02, 3.100000E+02, 3.200000E+02 };\nconst double MGH17_functor::y[33] = { 8.440000E-01, 9.080000E-01, 9.320000E-01, 9.360000E-01, 9.250000E-01, 9.080000E-01, 8.810000E-01, 8.500000E-01, 8.180000E-01, 7.840000E-01, 7.510000E-01, 7.180000E-01, 6.850000E-01, 6.580000E-01, 6.280000E-01, 6.030000E-01, 5.800000E-01, 5.580000E-01, 5.380000E-01, 5.220000E-01, 5.060000E-01, 4.900000E-01, 4.780000E-01, 4.670000E-01, 4.570000E-01, 4.480000E-01, 4.380000E-01, 4.310000E-01, 4.240000E-01, 4.200000E-01, 4.140000E-01, 4.110000E-01, 4.060000E-01 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/mgh17.shtml\nvoid testNistMGH17(void)\n{\n  const int n=5;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 50., 150., -100., 1., 2.;\n  // do the computation\n  MGH17_functor functor;\n  LevenbergMarquardt<MGH17_functor> lm(functor);\n  lm.setFtol(NumTraits<double>::epsilon());\n  lm.setXtol(NumTraits<double>::epsilon());\n  lm.setMaxfev(1000);\n  info = lm.minimize(x);\n\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 5.4648946975E-05);\n  // check x\n  VERIFY_IS_APPROX(x[0], 3.7541005211E-01);\n  VERIFY_IS_APPROX(x[1], 1.9358469127E+00);\n  VERIFY_IS_APPROX(x[2], -1.4646871366E+00);\n  VERIFY_IS_APPROX(x[3], 1.2867534640E-02);\n  VERIFY_IS_APPROX(x[4], 2.2122699662E-02);\n  \n    // check return value\n//   VERIFY_IS_EQUAL(info, 2);  //FIXME Use (lm.info() == Success)\n  VERIFY(lm.nfev() < 700 ); // 602\n  VERIFY(lm.njev() < 600 ); // 545\n\n  /*\n   * Second try\n   */\n  x<< 0.5  ,1.5  ,-1   ,0.01 ,0.02;\n  // do the computation\n  lm.resetParameters();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 18);\n  VERIFY_IS_EQUAL(lm.njev(), 15);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 5.4648946975E-05);\n  // check x\n  VERIFY_IS_APPROX(x[0], 3.7541005211E-01);\n  VERIFY_IS_APPROX(x[1], 1.9358469127E+00);\n  VERIFY_IS_APPROX(x[2], -1.4646871366E+00);\n  VERIFY_IS_APPROX(x[3], 1.2867534640E-02);\n  VERIFY_IS_APPROX(x[4], 2.2122699662E-02);\n}\n\nstruct MGH09_functor : DenseFunctor<double>\n{\n    MGH09_functor(void) : DenseFunctor<double>(4,11) {}\n    static const double _x[11];\n    static const double y[11];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==4);\n        assert(fvec.size()==11);\n        for(int i=0; i<11; i++) {\n            double x = _x[i], xx=x*x;\n            fvec[i] = b[0]*(xx+x*b[1])/(xx+x*b[2]+b[3]) - y[i];\n        }\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==4);\n        assert(fjac.rows()==11);\n        assert(fjac.cols()==4);\n        for(int i=0; i<11; i++) {\n            double x = _x[i], xx=x*x;\n            double factor = 1./(xx+x*b[2]+b[3]);\n            fjac(i,0) = (xx+x*b[1]) * factor;\n            fjac(i,1) = b[0]*x* factor;\n            fjac(i,2) = - b[0]*(xx+x*b[1]) * x * factor * factor;\n            fjac(i,3) = - b[0]*(xx+x*b[1]) * factor * factor;\n        }\n        return 0;\n    }\n};\nconst double MGH09_functor::_x[11] = { 4., 2., 1., 5.E-1 , 2.5E-01, 1.670000E-01, 1.250000E-01,  1.E-01, 8.330000E-02, 7.140000E-02, 6.250000E-02 };\nconst double MGH09_functor::y[11] = { 1.957000E-01, 1.947000E-01, 1.735000E-01, 1.600000E-01, 8.440000E-02, 6.270000E-02, 4.560000E-02, 3.420000E-02, 3.230000E-02, 2.350000E-02, 2.460000E-02 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/mgh09.shtml\nvoid testNistMGH09(void)\n{\n  const int n=4;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 25., 39, 41.5, 39.;\n  // do the computation\n  MGH09_functor functor;\n  LevenbergMarquardt<MGH09_functor> lm(functor);\n  lm.setMaxfev(1000);\n  info = lm.minimize(x);\n\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 3.0750560385E-04);\n  // check x\n  VERIFY_IS_APPROX(x[0], 0.1928077089); // should be 1.9280693458E-01\n  VERIFY_IS_APPROX(x[1], 0.19126423573); // should be 1.9128232873E-01\n  VERIFY_IS_APPROX(x[2], 0.12305309914); // should be 1.2305650693E-01\n  VERIFY_IS_APPROX(x[3], 0.13605395375); // should be 1.3606233068E-01\n  // check return value\n  VERIFY_IS_EQUAL(info, 1); \n  VERIFY(lm.nfev() < 510 ); // 490\n  VERIFY(lm.njev() < 400 ); // 376\n\n  /*\n   * Second try\n   */\n  x<< 0.25, 0.39, 0.415, 0.39;\n  // do the computation\n  lm.resetParameters();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 18);\n  VERIFY_IS_EQUAL(lm.njev(), 16);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 3.0750560385E-04);\n  // check x\n  VERIFY_IS_APPROX(x[0], 0.19280781); // should be 1.9280693458E-01\n  VERIFY_IS_APPROX(x[1], 0.19126265); // should be 1.9128232873E-01\n  VERIFY_IS_APPROX(x[2], 0.12305280); // should be 1.2305650693E-01\n  VERIFY_IS_APPROX(x[3], 0.13605322); // should be 1.3606233068E-01\n}\n\n\n\nstruct Bennett5_functor : DenseFunctor<double>\n{\n    Bennett5_functor(void) : DenseFunctor<double>(3,154) {}\n    static const double x[154];\n    static const double y[154];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==3);\n        assert(fvec.size()==154);\n        for(int i=0; i<154; i++)\n            fvec[i] = b[0]* pow(b[1]+x[i],-1./b[2]) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==3);\n        assert(fjac.rows()==154);\n        assert(fjac.cols()==3);\n        for(int i=0; i<154; i++) {\n            double e = pow(b[1]+x[i],-1./b[2]);\n            fjac(i,0) = e;\n            fjac(i,1) = - b[0]*e/b[2]/(b[1]+x[i]);\n            fjac(i,2) = b[0]*e*log(b[1]+x[i])/b[2]/b[2];\n        }\n        return 0;\n    }\n};\nconst double Bennett5_functor::x[154] = { 7.447168E0, 8.102586E0, 8.452547E0, 8.711278E0, 8.916774E0, 9.087155E0, 9.232590E0, 9.359535E0, 9.472166E0, 9.573384E0, 9.665293E0, 9.749461E0, 9.827092E0, 9.899128E0, 9.966321E0, 10.029280E0, 10.088510E0, 10.144430E0, 10.197380E0, 10.247670E0, 10.295560E0, 10.341250E0, 10.384950E0, 10.426820E0, 10.467000E0, 10.505640E0, 10.542830E0, 10.578690E0, 10.613310E0, 10.646780E0, 10.679150E0, 10.710520E0, 10.740920E0, 10.770440E0, 10.799100E0, 10.826970E0, 10.854080E0, 10.880470E0, 10.906190E0, 10.931260E0, 10.955720E0, 10.979590E0, 11.002910E0, 11.025700E0, 11.047980E0, 11.069770E0, 11.091100E0, 11.111980E0, 11.132440E0, 11.152480E0, 11.172130E0, 11.191410E0, 11.210310E0, 11.228870E0, 11.247090E0, 11.264980E0, 11.282560E0, 11.299840E0, 11.316820E0, 11.333520E0, 11.349940E0, 11.366100E0, 11.382000E0, 11.397660E0, 11.413070E0, 11.428240E0, 11.443200E0, 11.457930E0, 11.472440E0, 11.486750E0, 11.500860E0, 11.514770E0, 11.528490E0, 11.542020E0, 11.555380E0, 11.568550E0,\n11.581560E0, 11.594420E0, 11.607121E0, 11.619640E0, 11.632000E0, 11.644210E0, 11.656280E0, 11.668200E0, 11.679980E0, 11.691620E0, 11.703130E0, 11.714510E0, 11.725760E0, 11.736880E0, 11.747890E0, 11.758780E0, 11.769550E0, 11.780200E0, 11.790730E0, 11.801160E0, 11.811480E0, 11.821700E0, 11.831810E0, 11.841820E0, 11.851730E0, 11.861550E0, 11.871270E0, 11.880890E0, 11.890420E0, 11.899870E0, 11.909220E0, 11.918490E0, 11.927680E0, 11.936780E0, 11.945790E0, 11.954730E0, 11.963590E0, 11.972370E0, 11.981070E0, 11.989700E0, 11.998260E0, 12.006740E0, 12.015150E0, 12.023490E0, 12.031760E0, 12.039970E0, 12.048100E0, 12.056170E0, 12.064180E0, 12.072120E0, 12.080010E0, 12.087820E0, 12.095580E0, 12.103280E0, 12.110920E0, 12.118500E0, 12.126030E0, 12.133500E0, 12.140910E0, 12.148270E0, 12.155570E0, 12.162830E0, 12.170030E0, 12.177170E0, 12.184270E0, 12.191320E0, 12.198320E0, 12.205270E0, 12.212170E0, 12.219030E0, 12.225840E0, 12.232600E0, 12.239320E0, 12.245990E0, 12.252620E0, 12.259200E0, 12.265750E0, 12.272240E0 };\nconst double Bennett5_functor::y[154] = { -34.834702E0 ,-34.393200E0 ,-34.152901E0 ,-33.979099E0 ,-33.845901E0 ,-33.732899E0 ,-33.640301E0 ,-33.559200E0 ,-33.486801E0 ,-33.423100E0 ,-33.365101E0 ,-33.313000E0 ,-33.260899E0 ,-33.217400E0 ,-33.176899E0 ,-33.139198E0 ,-33.101601E0 ,-33.066799E0 ,-33.035000E0 ,-33.003101E0 ,-32.971298E0 ,-32.942299E0 ,-32.916302E0 ,-32.890202E0 ,-32.864101E0 ,-32.841000E0 ,-32.817799E0 ,-32.797501E0 ,-32.774300E0 ,-32.757000E0 ,-32.733799E0 ,-32.716400E0 ,-32.699100E0 ,-32.678799E0 ,-32.661400E0 ,-32.644001E0 ,-32.626701E0 ,-32.612202E0 ,-32.597698E0 ,-32.583199E0 ,-32.568699E0 ,-32.554298E0 ,-32.539799E0 ,-32.525299E0 ,-32.510799E0 ,-32.499199E0 ,-32.487598E0 ,-32.473202E0 ,-32.461601E0 ,-32.435501E0 ,-32.435501E0 ,-32.426800E0 ,-32.412300E0 ,-32.400799E0 ,-32.392101E0 ,-32.380501E0 ,-32.366001E0 ,-32.357300E0 ,-32.348598E0 ,-32.339901E0 ,-32.328400E0 ,-32.319698E0 ,-32.311001E0 ,-32.299400E0 ,-32.290699E0 ,-32.282001E0 ,-32.273300E0 ,-32.264599E0 ,-32.256001E0 ,-32.247299E0\n,-32.238602E0 ,-32.229900E0 ,-32.224098E0 ,-32.215401E0 ,-32.203800E0 ,-32.198002E0 ,-32.189400E0 ,-32.183601E0 ,-32.174900E0 ,-32.169102E0 ,-32.163300E0 ,-32.154598E0 ,-32.145901E0 ,-32.140099E0 ,-32.131401E0 ,-32.125599E0 ,-32.119801E0 ,-32.111198E0 ,-32.105400E0 ,-32.096699E0 ,-32.090900E0 ,-32.088001E0 ,-32.079300E0 ,-32.073502E0 ,-32.067699E0 ,-32.061901E0 ,-32.056099E0 ,-32.050301E0 ,-32.044498E0 ,-32.038799E0 ,-32.033001E0 ,-32.027199E0 ,-32.024300E0 ,-32.018501E0 ,-32.012699E0 ,-32.004002E0 ,-32.001099E0 ,-31.995300E0 ,-31.989500E0 ,-31.983700E0 ,-31.977900E0 ,-31.972099E0 ,-31.969299E0 ,-31.963501E0 ,-31.957701E0 ,-31.951900E0 ,-31.946100E0 ,-31.940300E0 ,-31.937401E0 ,-31.931601E0 ,-31.925800E0 ,-31.922899E0 ,-31.917101E0 ,-31.911301E0 ,-31.908400E0 ,-31.902599E0 ,-31.896900E0 ,-31.893999E0 ,-31.888201E0 ,-31.885300E0 ,-31.882401E0 ,-31.876600E0 ,-31.873699E0 ,-31.867901E0 ,-31.862101E0 ,-31.859200E0 ,-31.856300E0 ,-31.850500E0 ,-31.844700E0 ,-31.841801E0 ,-31.838900E0 ,-31.833099E0 ,-31.830200E0 ,\n-31.827299E0 ,-31.821600E0 ,-31.818701E0 ,-31.812901E0 ,-31.809999E0 ,-31.807100E0 ,-31.801300E0 ,-31.798401E0 ,-31.795500E0 ,-31.789700E0 ,-31.786800E0 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/bennett5.shtml\nvoid testNistBennett5(void)\n{\n  const int  n=3;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< -2000., 50., 0.8;\n  // do the computation\n  Bennett5_functor functor;\n  LevenbergMarquardt<Bennett5_functor> lm(functor);\n  lm.setMaxfev(1000);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 758);\n  VERIFY_IS_EQUAL(lm.njev(), 744);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 5.2404744073E-04);\n  // check x\n  VERIFY_IS_APPROX(x[0], -2.5235058043E+03);\n  VERIFY_IS_APPROX(x[1], 4.6736564644E+01);\n  VERIFY_IS_APPROX(x[2], 9.3218483193E-01);\n  /*\n   * Second try\n   */\n  x<< -1500., 45., 0.85;\n  // do the computation\n  lm.resetParameters();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 203);\n  VERIFY_IS_EQUAL(lm.njev(), 192);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 5.2404744073E-04);\n  // check x\n  VERIFY_IS_APPROX(x[0], -2523.3007865); // should be -2.5235058043E+03\n  VERIFY_IS_APPROX(x[1], 46.735705771); // should be 4.6736564644E+01);\n  VERIFY_IS_APPROX(x[2], 0.93219881891); // should be 9.3218483193E-01);\n}\n\nstruct thurber_functor : DenseFunctor<double>\n{\n    thurber_functor(void) : DenseFunctor<double>(7,37) {}\n    static const double _x[37];\n    static const double _y[37];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        //        int called=0; printf(\"call hahn1_functor with  iflag=%d, called=%d\\n\", iflag, called); if (iflag==1) called++;\n        assert(b.size()==7);\n        assert(fvec.size()==37);\n        for(int i=0; i<37; i++) {\n            double x=_x[i], xx=x*x, xxx=xx*x;\n            fvec[i] = (b[0]+b[1]*x+b[2]*xx+b[3]*xxx) / (1.+b[4]*x+b[5]*xx+b[6]*xxx) - _y[i];\n        }\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==7);\n        assert(fjac.rows()==37);\n        assert(fjac.cols()==7);\n        for(int i=0; i<37; i++) {\n            double x=_x[i], xx=x*x, xxx=xx*x;\n            double fact = 1./(1.+b[4]*x+b[5]*xx+b[6]*xxx);\n            fjac(i,0) = 1.*fact;\n            fjac(i,1) = x*fact;\n            fjac(i,2) = xx*fact;\n            fjac(i,3) = xxx*fact;\n            fact = - (b[0]+b[1]*x+b[2]*xx+b[3]*xxx) * fact * fact;\n            fjac(i,4) = x*fact;\n            fjac(i,5) = xx*fact;\n            fjac(i,6) = xxx*fact;\n        }\n        return 0;\n    }\n};\nconst double thurber_functor::_x[37] = { -3.067E0, -2.981E0, -2.921E0, -2.912E0, -2.840E0, -2.797E0, -2.702E0, -2.699E0, -2.633E0, -2.481E0, -2.363E0, -2.322E0, -1.501E0, -1.460E0, -1.274E0, -1.212E0, -1.100E0, -1.046E0, -0.915E0, -0.714E0, -0.566E0, -0.545E0, -0.400E0, -0.309E0, -0.109E0, -0.103E0, 0.010E0, 0.119E0, 0.377E0, 0.790E0, 0.963E0, 1.006E0, 1.115E0, 1.572E0, 1.841E0, 2.047E0, 2.200E0 };\nconst double thurber_functor::_y[37] = { 80.574E0, 84.248E0, 87.264E0, 87.195E0, 89.076E0, 89.608E0, 89.868E0, 90.101E0, 92.405E0, 95.854E0, 100.696E0, 101.060E0, 401.672E0, 390.724E0, 567.534E0, 635.316E0, 733.054E0, 759.087E0, 894.206E0, 990.785E0, 1090.109E0, 1080.914E0, 1122.643E0, 1178.351E0, 1260.531E0, 1273.514E0, 1288.339E0, 1327.543E0, 1353.863E0, 1414.509E0, 1425.208E0, 1421.384E0, 1442.962E0, 1464.350E0, 1468.705E0, 1447.894E0, 1457.628E0};\n\n// http://www.itl.nist.gov/div898/strd/nls/data/thurber.shtml\nvoid testNistThurber(void)\n{\n  const int n=7;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 1000 ,1000 ,400 ,40 ,0.7,0.3,0.0 ;\n  // do the computation\n  thurber_functor functor;\n  LevenbergMarquardt<thurber_functor> lm(functor);\n  lm.setFtol(1.E4*NumTraits<double>::epsilon());\n  lm.setXtol(1.E4*NumTraits<double>::epsilon());\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 39);\n  VERIFY_IS_EQUAL(lm.njev(), 36);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 5.6427082397E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.2881396800E+03);\n  VERIFY_IS_APPROX(x[1], 1.4910792535E+03);\n  VERIFY_IS_APPROX(x[2], 5.8323836877E+02);\n  VERIFY_IS_APPROX(x[3], 7.5416644291E+01);\n  VERIFY_IS_APPROX(x[4], 9.6629502864E-01);\n  VERIFY_IS_APPROX(x[5], 3.9797285797E-01);\n  VERIFY_IS_APPROX(x[6], 4.9727297349E-02);\n\n  /*\n   * Second try\n   */\n  x<< 1300 ,1500 ,500  ,75   ,1    ,0.4  ,0.05  ;\n  // do the computation\n  lm.resetParameters();\n  lm.setFtol(1.E4*NumTraits<double>::epsilon());\n  lm.setXtol(1.E4*NumTraits<double>::epsilon());\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 29);\n  VERIFY_IS_EQUAL(lm.njev(), 28);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 5.6427082397E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.2881396800E+03);\n  VERIFY_IS_APPROX(x[1], 1.4910792535E+03);\n  VERIFY_IS_APPROX(x[2], 5.8323836877E+02);\n  VERIFY_IS_APPROX(x[3], 7.5416644291E+01);\n  VERIFY_IS_APPROX(x[4], 9.6629502864E-01);\n  VERIFY_IS_APPROX(x[5], 3.9797285797E-01);\n  VERIFY_IS_APPROX(x[6], 4.9727297349E-02);\n}\n\nstruct rat43_functor : DenseFunctor<double>\n{\n    rat43_functor(void) : DenseFunctor<double>(4,15) {}\n    static const double x[15];\n    static const double y[15];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==4);\n        assert(fvec.size()==15);\n        for(int i=0; i<15; i++)\n            fvec[i] = b[0] * pow(1.+exp(b[1]-b[2]*x[i]),-1./b[3]) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==4);\n        assert(fjac.rows()==15);\n        assert(fjac.cols()==4);\n        for(int i=0; i<15; i++) {\n            double e = exp(b[1]-b[2]*x[i]);\n            double power = -1./b[3];\n            fjac(i,0) = pow(1.+e, power);\n            fjac(i,1) = power*b[0]*e*pow(1.+e, power-1.);\n            fjac(i,2) = -power*b[0]*e*x[i]*pow(1.+e, power-1.);\n            fjac(i,3) = b[0]*power*power*log(1.+e)*pow(1.+e, power);\n        }\n        return 0;\n    }\n};\nconst double rat43_functor::x[15] = { 1., 2., 3., 4., 5., 6., 7., 8., 9., 10., 11., 12., 13., 14., 15. };\nconst double rat43_functor::y[15] = { 16.08, 33.83, 65.80, 97.20, 191.55, 326.20, 386.87, 520.53, 590.03, 651.92, 724.93, 699.56, 689.96, 637.56, 717.41 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/ratkowsky3.shtml\nvoid testNistRat43(void)\n{\n  const int n=4;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 100., 10., 1., 1.;\n  // do the computation\n  rat43_functor functor;\n  LevenbergMarquardt<rat43_functor> lm(functor);\n  lm.setFtol(1.E6*NumTraits<double>::epsilon());\n  lm.setXtol(1.E6*NumTraits<double>::epsilon());\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 27);\n  VERIFY_IS_EQUAL(lm.njev(), 20);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 8.7864049080E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 6.9964151270E+02);\n  VERIFY_IS_APPROX(x[1], 5.2771253025E+00);\n  VERIFY_IS_APPROX(x[2], 7.5962938329E-01);\n  VERIFY_IS_APPROX(x[3], 1.2792483859E+00);\n\n  /*\n   * Second try\n   */\n  x<< 700., 5., 0.75, 1.3;\n  // do the computation\n  lm.resetParameters();\n  lm.setFtol(1.E5*NumTraits<double>::epsilon());\n  lm.setXtol(1.E5*NumTraits<double>::epsilon());\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 9);\n  VERIFY_IS_EQUAL(lm.njev(), 8);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 8.7864049080E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 6.9964151270E+02);\n  VERIFY_IS_APPROX(x[1], 5.2771253025E+00);\n  VERIFY_IS_APPROX(x[2], 7.5962938329E-01);\n  VERIFY_IS_APPROX(x[3], 1.2792483859E+00);\n}\n\n\n\nstruct eckerle4_functor : DenseFunctor<double>\n{\n    eckerle4_functor(void) : DenseFunctor<double>(3,35) {}\n    static const double x[35];\n    static const double y[35];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==3);\n        assert(fvec.size()==35);\n        for(int i=0; i<35; i++)\n            fvec[i] = b[0]/b[1] * exp(-0.5*(x[i]-b[2])*(x[i]-b[2])/(b[1]*b[1])) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==3);\n        assert(fjac.rows()==35);\n        assert(fjac.cols()==3);\n        for(int i=0; i<35; i++) {\n            double b12 = b[1]*b[1];\n            double e = exp(-0.5*(x[i]-b[2])*(x[i]-b[2])/b12);\n            fjac(i,0) = e / b[1];\n            fjac(i,1) = ((x[i]-b[2])*(x[i]-b[2])/b12-1.) * b[0]*e/b12;\n            fjac(i,2) = (x[i]-b[2])*e*b[0]/b[1]/b12;\n        }\n        return 0;\n    }\n};\nconst double eckerle4_functor::x[35] = { 400.0, 405.0, 410.0, 415.0, 420.0, 425.0, 430.0, 435.0, 436.5, 438.0, 439.5, 441.0, 442.5, 444.0, 445.5, 447.0, 448.5, 450.0, 451.5, 453.0, 454.5, 456.0, 457.5, 459.0, 460.5, 462.0, 463.5, 465.0, 470.0, 475.0, 480.0, 485.0, 490.0, 495.0, 500.0};\nconst double eckerle4_functor::y[35] = { 0.0001575, 0.0001699, 0.0002350, 0.0003102, 0.0004917, 0.0008710, 0.0017418, 0.0046400, 0.0065895, 0.0097302, 0.0149002, 0.0237310, 0.0401683, 0.0712559, 0.1264458, 0.2073413, 0.2902366, 0.3445623, 0.3698049, 0.3668534, 0.3106727, 0.2078154, 0.1164354, 0.0616764, 0.0337200, 0.0194023, 0.0117831, 0.0074357, 0.0022732, 0.0008800, 0.0004579, 0.0002345, 0.0001586, 0.0001143, 0.0000710 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/eckerle4.shtml\nvoid testNistEckerle4(void)\n{\n  const int n=3;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 1., 10., 500.;\n  // do the computation\n  eckerle4_functor functor;\n  LevenbergMarquardt<eckerle4_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 18);\n  VERIFY_IS_EQUAL(lm.njev(), 15);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 1.4635887487E-03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.5543827178);\n  VERIFY_IS_APPROX(x[1], 4.0888321754);\n  VERIFY_IS_APPROX(x[2], 4.5154121844E+02);\n\n  /*\n   * Second try\n   */\n  x<< 1.5, 5., 450.;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 7);\n  VERIFY_IS_EQUAL(lm.njev(), 6);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 1.4635887487E-03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.5543827178);\n  VERIFY_IS_APPROX(x[1], 4.0888321754);\n  VERIFY_IS_APPROX(x[2], 4.5154121844E+02);\n}\n\nEIGEN_DECLARE_TEST(levenberg_marquardt)\n{\n    // Tests using the examples provided by (c)minpack\n    CALL_SUBTEST(testLmder1());\n    CALL_SUBTEST(testLmder());\n    CALL_SUBTEST(testLmdif1());\n//     CALL_SUBTEST(testLmstr1());\n//     CALL_SUBTEST(testLmstr());\n    CALL_SUBTEST(testLmdif());\n\n    // NIST tests, level of difficulty = \"Lower\"\n    CALL_SUBTEST(testNistMisra1a());\n    CALL_SUBTEST(testNistChwirut2());\n\n    // NIST tests, level of difficulty = \"Average\"\n    CALL_SUBTEST(testNistHahn1());\n    CALL_SUBTEST(testNistMisra1d());\n    CALL_SUBTEST(testNistMGH17());\n    CALL_SUBTEST(testNistLanczos1());\n\n//     // NIST tests, level of difficulty = \"Higher\"\n    CALL_SUBTEST(testNistRat42());\n    CALL_SUBTEST(testNistMGH10());\n    CALL_SUBTEST(testNistBoxBOD());\n//     CALL_SUBTEST(testNistMGH09());\n    CALL_SUBTEST(testNistBennett5());\n    CALL_SUBTEST(testNistThurber());\n    CALL_SUBTEST(testNistRat43());\n    CALL_SUBTEST(testNistEckerle4());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/matrix_exponential.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"matrix_functions.h\"\n\ndouble binom(int n, int k)\n{\n  double res = 1;\n  for (int i=0; i<k; i++)\n    res = res * (n-k+i+1) / (i+1);\n  return res;\n}\n\ntemplate <typename T>\nT expfn(T x, int)\n{\n  return std::exp(x);\n}\n\ntemplate <typename T>\nvoid test2dRotation(double tol)\n{\n  Matrix<T,2,2> A, B, C;\n  T angle;\n\n  A << 0, 1, -1, 0;\n  for (int i=0; i<=20; i++)\n  {\n    angle = static_cast<T>(pow(10, i / 5. - 2));\n    B << std::cos(angle), std::sin(angle), -std::sin(angle), std::cos(angle);\n\n    C = (angle*A).matrixFunction(expfn);\n    std::cout << \"test2dRotation: i = \" << i << \"   error funm = \" << relerr(C, B);\n    VERIFY(C.isApprox(B, static_cast<T>(tol)));\n\n    C = (angle*A).exp();\n    std::cout << \"   error expm = \" << relerr(C, B) << \"\\n\";\n    VERIFY(C.isApprox(B, static_cast<T>(tol)));\n  }\n}\n\ntemplate <typename T>\nvoid test2dHyperbolicRotation(double tol)\n{\n  Matrix<std::complex<T>,2,2> A, B, C;\n  std::complex<T> imagUnit(0,1);\n  T angle, ch, sh;\n\n  for (int i=0; i<=20; i++)\n  {\n    angle = static_cast<T>((i-10) / 2.0);\n    ch = std::cosh(angle);\n    sh = std::sinh(angle);\n    A << 0, angle*imagUnit, -angle*imagUnit, 0;\n    B << ch, sh*imagUnit, -sh*imagUnit, ch;\n\n    C = A.matrixFunction(expfn);\n    std::cout << \"test2dHyperbolicRotation: i = \" << i << \"   error funm = \" << relerr(C, B);\n    VERIFY(C.isApprox(B, static_cast<T>(tol)));\n\n    C = A.exp();\n    std::cout << \"   error expm = \" << relerr(C, B) << \"\\n\";\n    VERIFY(C.isApprox(B, static_cast<T>(tol)));\n  }\n}\n\ntemplate <typename T>\nvoid testPascal(double tol)\n{\n  for (int size=1; size<20; size++)\n  {\n    Matrix<T,Dynamic,Dynamic> A(size,size), B(size,size), C(size,size);\n    A.setZero();\n    for (int i=0; i<size-1; i++)\n      A(i+1,i) = static_cast<T>(i+1);\n    B.setZero();\n    for (int i=0; i<size; i++)\n      for (int j=0; j<=i; j++)\n    B(i,j) = static_cast<T>(binom(i,j));\n\n    C = A.matrixFunction(expfn);\n    std::cout << \"testPascal: size = \" << size << \"   error funm = \" << relerr(C, B);\n    VERIFY(C.isApprox(B, static_cast<T>(tol)));\n\n    C = A.exp();\n    std::cout << \"   error expm = \" << relerr(C, B) << \"\\n\";\n    VERIFY(C.isApprox(B, static_cast<T>(tol)));\n  }\n}\n\ntemplate<typename MatrixType>\nvoid randomTest(const MatrixType& m, double tol)\n{\n  /* this test covers the following files:\n     Inverse.h\n  */\n  typename MatrixType::Index rows = m.rows();\n  typename MatrixType::Index cols = m.cols();\n  MatrixType m1(rows, cols), m2(rows, cols), identity = MatrixType::Identity(rows, cols);\n\n  typedef typename NumTraits<typename internal::traits<MatrixType>::Scalar>::Real RealScalar;\n\n  for(int i = 0; i < g_repeat; i++) {\n    m1 = MatrixType::Random(rows, cols);\n\n    m2 = m1.matrixFunction(expfn) * (-m1).matrixFunction(expfn);\n    std::cout << \"randomTest: error funm = \" << relerr(identity, m2);\n    VERIFY(identity.isApprox(m2, static_cast<RealScalar>(tol)));\n\n    m2 = m1.exp() * (-m1).exp();\n    std::cout << \"   error expm = \" << relerr(identity, m2) << \"\\n\";\n    VERIFY(identity.isApprox(m2, static_cast<RealScalar>(tol)));\n  }\n}\n\nEIGEN_DECLARE_TEST(matrix_exponential)\n{\n  CALL_SUBTEST_2(test2dRotation<double>(1e-13));\n  CALL_SUBTEST_1(test2dRotation<float>(2e-5));  // was 1e-5, relaxed for clang 2.8 / linux / x86-64\n  CALL_SUBTEST_8(test2dRotation<long double>(1e-13)); \n  CALL_SUBTEST_2(test2dHyperbolicRotation<double>(1e-14));\n  CALL_SUBTEST_1(test2dHyperbolicRotation<float>(1e-5));\n  CALL_SUBTEST_8(test2dHyperbolicRotation<long double>(1e-14));\n  CALL_SUBTEST_6(testPascal<float>(1e-6));\n  CALL_SUBTEST_5(testPascal<double>(1e-15));\n  CALL_SUBTEST_2(randomTest(Matrix2d(), 1e-13));\n  CALL_SUBTEST_7(randomTest(Matrix<double,3,3,RowMajor>(), 1e-13));\n  CALL_SUBTEST_3(randomTest(Matrix4cd(), 1e-13));\n  CALL_SUBTEST_4(randomTest(MatrixXd(8,8), 1e-13));\n  CALL_SUBTEST_1(randomTest(Matrix2f(), 1e-4));\n  CALL_SUBTEST_5(randomTest(Matrix3cf(), 1e-4));\n  CALL_SUBTEST_1(randomTest(Matrix4f(), 1e-4));\n  CALL_SUBTEST_6(randomTest(MatrixXf(8,8), 1e-4));\n  CALL_SUBTEST_9(randomTest(Matrix<long double,Dynamic,Dynamic>(7,7), 1e-13));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/matrix_function.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <unsupported/Eigen/MatrixFunctions>\n\n// Variant of VERIFY_IS_APPROX which uses absolute error instead of\n// relative error.\n#define VERIFY_IS_APPROX_ABS(a, b) VERIFY(test_isApprox_abs(a, b))\n\ntemplate<typename Type1, typename Type2>\ninline bool test_isApprox_abs(const Type1& a, const Type2& b)\n{\n  return ((a-b).array().abs() < test_precision<typename Type1::RealScalar>()).all();\n}\n\n\n// Returns a matrix with eigenvalues clustered around 0, 1 and 2.\ntemplate<typename MatrixType>\nMatrixType randomMatrixWithRealEivals(const Index size)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  MatrixType diag = MatrixType::Zero(size, size);\n  for (Index i = 0; i < size; ++i) {\n    diag(i, i) = Scalar(RealScalar(internal::random<int>(0,2)))\n      + internal::random<Scalar>() * Scalar(RealScalar(0.01));\n  }\n  MatrixType A = MatrixType::Random(size, size);\n  HouseholderQR<MatrixType> QRofA(A);\n  return QRofA.householderQ().inverse() * diag * QRofA.householderQ();\n}\n\ntemplate <typename MatrixType, int IsComplex = NumTraits<typename internal::traits<MatrixType>::Scalar>::IsComplex>\nstruct randomMatrixWithImagEivals\n{\n  // Returns a matrix with eigenvalues clustered around 0 and +/- i.\n  static MatrixType run(const Index size);\n};\n\n// Partial specialization for real matrices\ntemplate<typename MatrixType>\nstruct randomMatrixWithImagEivals<MatrixType, 0>\n{\n  static MatrixType run(const Index size)\n  {\n    typedef typename MatrixType::Scalar Scalar;\n    MatrixType diag = MatrixType::Zero(size, size);\n    Index i = 0;\n    while (i < size) {\n      Index randomInt = internal::random<Index>(-1, 1);\n      if (randomInt == 0 || i == size-1) {\n        diag(i, i) = internal::random<Scalar>() * Scalar(0.01);\n        ++i;\n      } else {\n        Scalar alpha = Scalar(randomInt) + internal::random<Scalar>() * Scalar(0.01);\n        diag(i, i+1) = alpha;\n        diag(i+1, i) = -alpha;\n        i += 2;\n      }\n    }\n    MatrixType A = MatrixType::Random(size, size);\n    HouseholderQR<MatrixType> QRofA(A);\n    return QRofA.householderQ().inverse() * diag * QRofA.householderQ();\n  }\n};\n\n// Partial specialization for complex matrices\ntemplate<typename MatrixType>\nstruct randomMatrixWithImagEivals<MatrixType, 1>\n{\n  static MatrixType run(const Index size)\n  {\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    const Scalar imagUnit(0, 1);\n    MatrixType diag = MatrixType::Zero(size, size);\n    for (Index i = 0; i < size; ++i) {\n      diag(i, i) = Scalar(RealScalar(internal::random<Index>(-1, 1))) * imagUnit\n        + internal::random<Scalar>() * Scalar(RealScalar(0.01));\n    }\n    MatrixType A = MatrixType::Random(size, size);\n    HouseholderQR<MatrixType> QRofA(A);\n    return QRofA.householderQ().inverse() * diag * QRofA.householderQ();\n  }\n};\n\n\ntemplate<typename MatrixType>\nvoid testMatrixExponential(const MatrixType& A)\n{\n  typedef typename internal::traits<MatrixType>::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef std::complex<RealScalar> ComplexScalar;\n\n  VERIFY_IS_APPROX(A.exp(), A.matrixFunction(internal::stem_function_exp<ComplexScalar>));\n}\n\ntemplate<typename MatrixType>\nvoid testMatrixLogarithm(const MatrixType& A)\n{\n  typedef typename internal::traits<MatrixType>::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  MatrixType scaledA;\n  RealScalar maxImagPartOfSpectrum = A.eigenvalues().imag().cwiseAbs().maxCoeff();\n  if (maxImagPartOfSpectrum >= RealScalar(0.9L * EIGEN_PI))\n    scaledA = A * RealScalar(0.9L * EIGEN_PI) / maxImagPartOfSpectrum;\n  else\n    scaledA = A;\n\n  // identity X.exp().log() = X only holds if Im(lambda) < pi for all eigenvalues of X\n  MatrixType expA = scaledA.exp();\n  MatrixType logExpA = expA.log();\n  VERIFY_IS_APPROX(logExpA, scaledA);\n}\n\ntemplate<typename MatrixType>\nvoid testHyperbolicFunctions(const MatrixType& A)\n{\n  // Need to use absolute error because of possible cancellation when\n  // adding/subtracting expA and expmA.\n  VERIFY_IS_APPROX_ABS(A.sinh(), (A.exp() - (-A).exp()) / 2);\n  VERIFY_IS_APPROX_ABS(A.cosh(), (A.exp() + (-A).exp()) / 2);\n}\n\ntemplate<typename MatrixType>\nvoid testGonioFunctions(const MatrixType& A)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef std::complex<RealScalar> ComplexScalar;\n  typedef Matrix<ComplexScalar, MatrixType::RowsAtCompileTime, \n                 MatrixType::ColsAtCompileTime, MatrixType::Options> ComplexMatrix;\n\n  ComplexScalar imagUnit(0,1);\n  ComplexScalar two(2,0);\n\n  ComplexMatrix Ac = A.template cast<ComplexScalar>();\n  \n  ComplexMatrix exp_iA = (imagUnit * Ac).exp();\n  ComplexMatrix exp_miA = (-imagUnit * Ac).exp();\n  \n  ComplexMatrix sinAc = A.sin().template cast<ComplexScalar>();\n  VERIFY_IS_APPROX_ABS(sinAc, (exp_iA - exp_miA) / (two*imagUnit));\n  \n  ComplexMatrix cosAc = A.cos().template cast<ComplexScalar>();\n  VERIFY_IS_APPROX_ABS(cosAc, (exp_iA + exp_miA) / 2);\n}\n\ntemplate<typename MatrixType>\nvoid testMatrix(const MatrixType& A)\n{\n  testMatrixExponential(A);\n  testMatrixLogarithm(A);\n  testHyperbolicFunctions(A);\n  testGonioFunctions(A);\n}\n\ntemplate<typename MatrixType>\nvoid testMatrixType(const MatrixType& m)\n{\n  // Matrices with clustered eigenvalue lead to different code paths\n  // in MatrixFunction.h and are thus useful for testing.\n\n  const Index size = m.rows();\n  for (int i = 0; i < g_repeat; i++) {\n    testMatrix(MatrixType::Random(size, size).eval());\n    testMatrix(randomMatrixWithRealEivals<MatrixType>(size));\n    testMatrix(randomMatrixWithImagEivals<MatrixType>::run(size));\n  }\n}\n\ntemplate<typename MatrixType>\nvoid testMapRef(const MatrixType& A)\n{\n  // Test if passing Ref and Map objects is possible\n  // (Regression test for Bug #1796)\n  Index size = A.rows();\n  MatrixType X; X.setRandom(size, size);\n  MatrixType Y(size,size);\n  Ref<      MatrixType> R(Y);\n  Ref<const MatrixType> Rc(X);\n  Map<      MatrixType> M(Y.data(), size, size);\n  Map<const MatrixType> Mc(X.data(), size, size);\n\n  X = X*X; // make sure sqrt is possible\n  Y = X.sqrt();\n  R = Rc.sqrt();\n  M = Mc.sqrt();\n  Y = X.exp();\n  R = Rc.exp();\n  M = Mc.exp();\n  X = Y; // make sure log is possible\n  Y = X.log();\n  R = Rc.log();\n  M = Mc.log();\n\n  Y = X.cos() + Rc.cos() + Mc.cos();\n  Y = X.sin() + Rc.sin() + Mc.sin();\n\n  Y = X.cosh() + Rc.cosh() + Mc.cosh();\n  Y = X.sinh() + Rc.sinh() + Mc.sinh();\n}\n\n\nEIGEN_DECLARE_TEST(matrix_function)\n{\n  CALL_SUBTEST_1(testMatrixType(Matrix<float,1,1>()));\n  CALL_SUBTEST_2(testMatrixType(Matrix3cf()));\n  CALL_SUBTEST_3(testMatrixType(MatrixXf(8,8)));\n  CALL_SUBTEST_4(testMatrixType(Matrix2d()));\n  CALL_SUBTEST_5(testMatrixType(Matrix<double,5,5,RowMajor>()));\n  CALL_SUBTEST_6(testMatrixType(Matrix4cd()));\n  CALL_SUBTEST_7(testMatrixType(MatrixXd(13,13)));\n\n  CALL_SUBTEST_1(testMapRef(Matrix<float,1,1>()));\n  CALL_SUBTEST_2(testMapRef(Matrix3cf()));\n  CALL_SUBTEST_3(testMapRef(MatrixXf(8,8)));\n  CALL_SUBTEST_7(testMapRef(MatrixXd(13,13)));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/matrix_functions.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2011 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <unsupported/Eigen/MatrixFunctions>\n\n// For complex matrices, any matrix is fine.\ntemplate<typename MatrixType, int IsComplex = NumTraits<typename internal::traits<MatrixType>::Scalar>::IsComplex>\nstruct processTriangularMatrix\n{\n  static void run(MatrixType&, MatrixType&, const MatrixType&)\n  { }\n};\n\n// For real matrices, make sure none of the eigenvalues are negative.\ntemplate<typename MatrixType>\nstruct processTriangularMatrix<MatrixType,0>\n{\n  static void run(MatrixType& m, MatrixType& T, const MatrixType& U)\n  {\n    const Index size = m.cols();\n\n    for (Index i=0; i < size; ++i) {\n      if (i == size - 1 || T.coeff(i+1,i) == 0)\n        T.coeffRef(i,i) = std::abs(T.coeff(i,i));\n      else\n        ++i;\n    }\n    m = U * T * U.transpose();\n  }\n};\n\ntemplate <typename MatrixType, int IsComplex = NumTraits<typename internal::traits<MatrixType>::Scalar>::IsComplex>\nstruct generateTestMatrix;\n\ntemplate <typename MatrixType>\nstruct generateTestMatrix<MatrixType,0>\n{\n  static void run(MatrixType& result, typename MatrixType::Index size)\n  {\n    result = MatrixType::Random(size, size);\n    RealSchur<MatrixType> schur(result);\n    MatrixType T = schur.matrixT();\n    processTriangularMatrix<MatrixType>::run(result, T, schur.matrixU());\n  }\n};\n\ntemplate <typename MatrixType>\nstruct generateTestMatrix<MatrixType,1>\n{\n  static void run(MatrixType& result, typename MatrixType::Index size)\n  {\n    result = MatrixType::Random(size, size);\n  }\n};\n\ntemplate <typename Derived, typename OtherDerived>\ntypename Derived::RealScalar relerr(const MatrixBase<Derived>& A, const MatrixBase<OtherDerived>& B)\n{\n  return std::sqrt((A - B).cwiseAbs2().sum() / (std::min)(A.cwiseAbs2().sum(), B.cwiseAbs2().sum()));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/matrix_power.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012, 2013 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"matrix_functions.h\"\n\ntemplate<typename T>\nvoid test2dRotation(const T& tol)\n{\n  Matrix<T,2,2> A, B, C;\n  T angle, c, s;\n\n  A << 0, 1, -1, 0;\n  MatrixPower<Matrix<T,2,2> > Apow(A);\n\n  for (int i=0; i<=20; ++i) {\n    angle = std::pow(T(10), T(i-10) / T(5.));\n    c = std::cos(angle);\n    s = std::sin(angle);\n    B << c, s, -s, c;\n\n    C = Apow(std::ldexp(angle,1) / T(EIGEN_PI));\n    std::cout << \"test2dRotation: i = \" << i << \"   error powerm = \" << relerr(C,B) << '\\n';\n    VERIFY(C.isApprox(B, tol));\n  }\n}\n\ntemplate<typename T>\nvoid test2dHyperbolicRotation(const T& tol)\n{\n  Matrix<std::complex<T>,2,2> A, B, C;\n  T angle, ch = std::cosh((T)1);\n  std::complex<T> ish(0, std::sinh((T)1));\n\n  A << ch, ish, -ish, ch;\n  MatrixPower<Matrix<std::complex<T>,2,2> > Apow(A);\n\n  for (int i=0; i<=20; ++i) {\n    angle = std::ldexp(static_cast<T>(i-10), -1);\n    ch = std::cosh(angle);\n    ish = std::complex<T>(0, std::sinh(angle));\n    B << ch, ish, -ish, ch;\n\n    C = Apow(angle);\n    std::cout << \"test2dHyperbolicRotation: i = \" << i << \"   error powerm = \" << relerr(C,B) << '\\n';\n    VERIFY(C.isApprox(B, tol));\n  }\n}\n\ntemplate<typename T>\nvoid test3dRotation(const T& tol)\n{\n  Matrix<T,3,1> v;\n  T angle;\n\n  for (int i=0; i<=20; ++i) {\n    v = Matrix<T,3,1>::Random();\n    v.normalize();\n    angle = std::pow(T(10), T(i-10) / T(5.));\n    VERIFY(AngleAxis<T>(angle, v).matrix().isApprox(AngleAxis<T>(1,v).matrix().pow(angle), tol));\n  }\n}\n\ntemplate<typename MatrixType>\nvoid testGeneral(const MatrixType& m, const typename MatrixType::RealScalar& tol)\n{\n  typedef typename MatrixType::RealScalar RealScalar;\n  MatrixType m1, m2, m3, m4, m5;\n  RealScalar x, y;\n\n  for (int i=0; i < g_repeat; ++i) {\n    generateTestMatrix<MatrixType>::run(m1, m.rows());\n    MatrixPower<MatrixType> mpow(m1);\n\n    x = internal::random<RealScalar>();\n    y = internal::random<RealScalar>();\n    m2 = mpow(x);\n    m3 = mpow(y);\n\n    m4 = mpow(x+y);\n    m5.noalias() = m2 * m3;\n    VERIFY(m4.isApprox(m5, tol));\n\n    m4 = mpow(x*y);\n    m5 = m2.pow(y);\n    VERIFY(m4.isApprox(m5, tol));\n\n    m4 = (std::abs(x) * m1).pow(y);\n    m5 = std::pow(std::abs(x), y) * m3;\n    VERIFY(m4.isApprox(m5, tol));\n  }\n}\n\ntemplate<typename MatrixType>\nvoid testSingular(const MatrixType& m_const, const typename MatrixType::RealScalar& tol)\n{\n  // we need to pass by reference in order to prevent errors with\n  // MSVC for aligned data types ...\n  MatrixType& m = const_cast<MatrixType&>(m_const);\n\n  const int IsComplex = NumTraits<typename internal::traits<MatrixType>::Scalar>::IsComplex;\n  typedef typename internal::conditional<IsComplex, TriangularView<MatrixType,Upper>, const MatrixType&>::type TriangularType;\n  typename internal::conditional< IsComplex, ComplexSchur<MatrixType>, RealSchur<MatrixType> >::type schur;\n  MatrixType T;\n\n  for (int i=0; i < g_repeat; ++i) {\n    m.setRandom();\n    m.col(0).fill(0);\n\n    schur.compute(m);\n    T = schur.matrixT();\n    const MatrixType& U = schur.matrixU();\n    processTriangularMatrix<MatrixType>::run(m, T, U);\n    MatrixPower<MatrixType> mpow(m);\n\n    T = T.sqrt();\n    VERIFY(mpow(0.5L).isApprox(U * (TriangularType(T) * U.adjoint()), tol));\n\n    T = T.sqrt();\n    VERIFY(mpow(0.25L).isApprox(U * (TriangularType(T) * U.adjoint()), tol));\n\n    T = T.sqrt();\n    VERIFY(mpow(0.125L).isApprox(U * (TriangularType(T) * U.adjoint()), tol));\n  }\n}\n\ntemplate<typename MatrixType>\nvoid testLogThenExp(const MatrixType& m_const, const typename MatrixType::RealScalar& tol)\n{\n  // we need to pass by reference in order to prevent errors with\n  // MSVC for aligned data types ...\n  MatrixType& m = const_cast<MatrixType&>(m_const);\n\n  typedef typename MatrixType::Scalar Scalar;\n  Scalar x;\n\n  for (int i=0; i < g_repeat; ++i) {\n    generateTestMatrix<MatrixType>::run(m, m.rows());\n    x = internal::random<Scalar>();\n    VERIFY(m.pow(x).isApprox((x * m.log()).exp(), tol));\n  }\n}\n\ntypedef Matrix<double,3,3,RowMajor>         Matrix3dRowMajor;\ntypedef Matrix<long double,3,3>             Matrix3e;\ntypedef Matrix<long double,Dynamic,Dynamic> MatrixXe;\n \nEIGEN_DECLARE_TEST(matrix_power)\n{\n  CALL_SUBTEST_2(test2dRotation<double>(1e-13));\n  CALL_SUBTEST_1(test2dRotation<float>(2e-5f));  // was 1e-5, relaxed for clang 2.8 / linux / x86-64\n  CALL_SUBTEST_9(test2dRotation<long double>(1e-13L));\n  CALL_SUBTEST_2(test2dHyperbolicRotation<double>(1e-14));\n  CALL_SUBTEST_1(test2dHyperbolicRotation<float>(1e-5f));\n  CALL_SUBTEST_9(test2dHyperbolicRotation<long double>(1e-14L));\n\n  CALL_SUBTEST_10(test3dRotation<double>(1e-13));\n  CALL_SUBTEST_11(test3dRotation<float>(1e-5f));\n  CALL_SUBTEST_12(test3dRotation<long double>(1e-13L));\n\n  CALL_SUBTEST_2(testGeneral(Matrix2d(),         1e-13));\n  CALL_SUBTEST_7(testGeneral(Matrix3dRowMajor(), 1e-13));\n  CALL_SUBTEST_3(testGeneral(Matrix4cd(),        1e-13));\n  CALL_SUBTEST_4(testGeneral(MatrixXd(8,8),      2e-12));\n  CALL_SUBTEST_1(testGeneral(Matrix2f(),         1e-4f));\n  CALL_SUBTEST_5(testGeneral(Matrix3cf(),        1e-4f));\n  CALL_SUBTEST_8(testGeneral(Matrix4f(),         1e-4f));\n  CALL_SUBTEST_6(testGeneral(MatrixXf(2,2),      1e-3f)); // see bug 614\n  CALL_SUBTEST_9(testGeneral(MatrixXe(7,7),      1e-13L));\n  CALL_SUBTEST_10(testGeneral(Matrix3d(),        1e-13));\n  CALL_SUBTEST_11(testGeneral(Matrix3f(),        1e-4f));\n  CALL_SUBTEST_12(testGeneral(Matrix3e(),        1e-13L));\n\n  CALL_SUBTEST_2(testSingular(Matrix2d(),         1e-13));\n  CALL_SUBTEST_7(testSingular(Matrix3dRowMajor(), 1e-13));\n  CALL_SUBTEST_3(testSingular(Matrix4cd(),        1e-13));\n  CALL_SUBTEST_4(testSingular(MatrixXd(8,8),      2e-12));\n  CALL_SUBTEST_1(testSingular(Matrix2f(),         1e-4f));\n  CALL_SUBTEST_5(testSingular(Matrix3cf(),        1e-4f));\n  CALL_SUBTEST_8(testSingular(Matrix4f(),         1e-4f));\n  CALL_SUBTEST_6(testSingular(MatrixXf(2,2),      1e-3f));\n  CALL_SUBTEST_9(testSingular(MatrixXe(7,7),      1e-13L));\n  CALL_SUBTEST_10(testSingular(Matrix3d(),        1e-13));\n  CALL_SUBTEST_11(testSingular(Matrix3f(),        1e-4f));\n  CALL_SUBTEST_12(testSingular(Matrix3e(),        1e-13L));\n\n  CALL_SUBTEST_2(testLogThenExp(Matrix2d(),         1e-13));\n  CALL_SUBTEST_7(testLogThenExp(Matrix3dRowMajor(), 1e-13));\n  CALL_SUBTEST_3(testLogThenExp(Matrix4cd(),        1e-13));\n  CALL_SUBTEST_4(testLogThenExp(MatrixXd(8,8),      2e-12));\n  CALL_SUBTEST_1(testLogThenExp(Matrix2f(),         1e-4f));\n  CALL_SUBTEST_5(testLogThenExp(Matrix3cf(),        1e-4f));\n  CALL_SUBTEST_8(testLogThenExp(Matrix4f(),         1e-4f));\n  CALL_SUBTEST_6(testLogThenExp(MatrixXf(2,2),      1e-3f));\n  CALL_SUBTEST_9(testLogThenExp(MatrixXe(7,7),      1e-13L));\n  CALL_SUBTEST_10(testLogThenExp(Matrix3d(),        1e-13));\n  CALL_SUBTEST_11(testLogThenExp(Matrix3f(),        1e-4f));\n  CALL_SUBTEST_12(testLogThenExp(Matrix3e(),        1e-13L));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/matrix_square_root.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"matrix_functions.h\"\n\ntemplate<typename MatrixType>\nvoid testMatrixSqrt(const MatrixType& m)\n{\n  MatrixType A;\n  generateTestMatrix<MatrixType>::run(A, m.rows());\n  MatrixType sqrtA = A.sqrt();\n  VERIFY_IS_APPROX(sqrtA * sqrtA, A);\n}\n\nEIGEN_DECLARE_TEST(matrix_square_root)\n{\n  for (int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(testMatrixSqrt(Matrix3cf()));\n    CALL_SUBTEST_2(testMatrixSqrt(MatrixXcd(12,12)));\n    CALL_SUBTEST_3(testMatrixSqrt(Matrix4f()));\n    CALL_SUBTEST_4(testMatrixSqrt(Matrix<double,Dynamic,Dynamic,RowMajor>(9, 9)));\n    CALL_SUBTEST_5(testMatrixSqrt(Matrix<float,1,1>()));\n    CALL_SUBTEST_5(testMatrixSqrt(Matrix<std::complex<float>,1,1>()));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/minres.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Giacomo Po <gpo@ucla.edu>\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n#include <cmath>\n\n#include \"../../test/sparse_solver.h\"\n#include <Eigen/IterativeSolvers>\n\ntemplate<typename T> void test_minres_T()\n{\n  // Identity preconditioner\n  MINRES<SparseMatrix<T>, Lower, IdentityPreconditioner    > minres_colmajor_lower_I;\n  MINRES<SparseMatrix<T>, Upper, IdentityPreconditioner    > minres_colmajor_upper_I;\n\n  // Diagonal preconditioner\n  MINRES<SparseMatrix<T>, Lower, DiagonalPreconditioner<T> > minres_colmajor_lower_diag;\n  MINRES<SparseMatrix<T>, Upper, DiagonalPreconditioner<T> > minres_colmajor_upper_diag;\n  MINRES<SparseMatrix<T>, Lower|Upper, DiagonalPreconditioner<T> > minres_colmajor_uplo_diag;\n  \n  // call tests for SPD matrix\n  CALL_SUBTEST( check_sparse_spd_solving(minres_colmajor_lower_I) );\n  CALL_SUBTEST( check_sparse_spd_solving(minres_colmajor_upper_I) );\n    \n  CALL_SUBTEST( check_sparse_spd_solving(minres_colmajor_lower_diag)  );\n  CALL_SUBTEST( check_sparse_spd_solving(minres_colmajor_upper_diag)  );\n  CALL_SUBTEST( check_sparse_spd_solving(minres_colmajor_uplo_diag)  );\n    \n  // TO DO: symmetric semi-definite matrix\n  // TO DO: symmetric indefinite matrix\n\n}\n\nEIGEN_DECLARE_TEST(minres)\n{\n  CALL_SUBTEST_1(test_minres_T<double>());\n//  CALL_SUBTEST_2(test_minres_T<std::compex<double> >());\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/mpreal_support.cpp",
    "content": "#include <mpreal.h>  // Must be included before main.h.\n#include \"main.h\"\n#include <Eigen/MPRealSupport>\n#include <Eigen/LU>\n#include <Eigen/Eigenvalues>\n#include <sstream>\n\nusing namespace mpfr;\nusing namespace Eigen;\n\nEIGEN_DECLARE_TEST(mpreal_support)\n{\n  // set precision to 256 bits (double has only 53 bits)\n  mpreal::set_default_prec(256);\n  typedef Matrix<mpreal,Eigen::Dynamic,Eigen::Dynamic> MatrixXmp;\n  typedef Matrix<std::complex<mpreal>,Eigen::Dynamic,Eigen::Dynamic> MatrixXcmp;\n\n  std::cerr << \"epsilon =         \" << NumTraits<mpreal>::epsilon() << \"\\n\";\n  std::cerr << \"dummy_precision = \" << NumTraits<mpreal>::dummy_precision() << \"\\n\";\n  std::cerr << \"highest =         \" << NumTraits<mpreal>::highest() << \"\\n\";\n  std::cerr << \"lowest =          \" << NumTraits<mpreal>::lowest() << \"\\n\";\n  std::cerr << \"digits10 =        \" << NumTraits<mpreal>::digits10() << \"\\n\";\n\n  for(int i = 0; i < g_repeat; i++) {\n    int s = Eigen::internal::random<int>(1,100);\n    MatrixXmp A = MatrixXmp::Random(s,s);\n    MatrixXmp B = MatrixXmp::Random(s,s);\n    MatrixXmp S = A.adjoint() * A;\n    MatrixXmp X;\n    MatrixXcmp Ac = MatrixXcmp::Random(s,s);\n    MatrixXcmp Bc = MatrixXcmp::Random(s,s);\n    MatrixXcmp Sc = Ac.adjoint() * Ac;\n    MatrixXcmp Xc;\n    \n    // Basic stuffs\n    VERIFY_IS_APPROX(A.real(), A);\n    VERIFY(Eigen::internal::isApprox(A.array().abs2().sum(), A.squaredNorm()));\n    VERIFY_IS_APPROX(A.array().exp(),         exp(A.array()));\n    VERIFY_IS_APPROX(A.array().abs2().sqrt(), A.array().abs());\n    VERIFY_IS_APPROX(A.array().sin(),         sin(A.array()));\n    VERIFY_IS_APPROX(A.array().cos(),         cos(A.array()));\n\n    // Cholesky\n    X = S.selfadjointView<Lower>().llt().solve(B);\n    VERIFY_IS_APPROX((S.selfadjointView<Lower>()*X).eval(),B);\n\n    Xc = Sc.selfadjointView<Lower>().llt().solve(Bc);\n    VERIFY_IS_APPROX((Sc.selfadjointView<Lower>()*Xc).eval(),Bc);\n    \n    // partial LU\n    X = A.lu().solve(B);\n    VERIFY_IS_APPROX((A*X).eval(),B);\n\n    // symmetric eigenvalues\n    SelfAdjointEigenSolver<MatrixXmp> eig(S);\n    VERIFY_IS_EQUAL(eig.info(), Success);\n    VERIFY( (S.selfadjointView<Lower>() * eig.eigenvectors()).isApprox(eig.eigenvectors() * eig.eigenvalues().asDiagonal(), NumTraits<mpreal>::dummy_precision()*1e3) );\n  }\n  \n  {\n    MatrixXmp A(8,3); A.setRandom();\n    // test output (interesting things happen in this code)\n    std::stringstream stream;\n    stream << A;\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/openglsupport.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <main.h>\n#include <iostream>\n#include <string>\n\n#if defined(__APPLE_CC__)\n  // Prevent deprecation warnings caused by GLEW on MacOS.\n  #define GL_SILENCE_DEPRECATION 1\n#endif\n#include <GL/glew.h>\n#include <Eigen/OpenGLSupport>\n#if defined(__APPLE_CC__)\n  #include <GLUT/glut.h>\n#else\n  #include <GL/freeglut.h>\n#endif\n\nusing namespace Eigen;\n\n#define VERIFY_MATRIX(CODE,REF) { \\\n    glMatrixMode(GL_MODELVIEW); \\\n    glLoadIdentity(); \\\n    CODE; \\\n    Matrix<float,4,4,ColMajor> m; m.setZero(); \\\n    glGet(GL_MODELVIEW_MATRIX, m); \\\n    if(!(REF).cast<float>().isApprox(m)) { \\\n      std::cerr << \"Expected:\\n\" << ((REF).cast<float>()) << \"\\n\" << \"got\\n\" << m << \"\\n\\n\"; \\\n    } \\\n    VERIFY_IS_APPROX((REF).cast<float>(), m); \\\n  }\n\n#define VERIFY_UNIFORM(SUFFIX,NAME,TYPE) { \\\n    TYPE value; value.setRandom(); \\\n    TYPE data; \\\n    int loc = glGetUniformLocation(prg_id, #NAME); \\\n    VERIFY((loc!=-1) && \"uniform not found\"); \\\n    glUniform(loc,value); \\\n    EIGEN_CAT(glGetUniform,SUFFIX)(prg_id,loc,data.data()); \\\n    if(!value.isApprox(data)) { \\\n      std::cerr << \"Expected:\\n\" << value << \"\\n\" << \"got\\n\" << data << \"\\n\\n\"; \\\n    } \\\n    VERIFY_IS_APPROX(value, data); \\\n  }\n\n#define VERIFY_UNIFORMi(NAME,TYPE) { \\\n    TYPE value = TYPE::Random().eval().cast<float>().cast<TYPE::Scalar>(); \\\n    TYPE data; \\\n    int loc = glGetUniformLocation(prg_id, #NAME); \\\n    VERIFY((loc!=-1) && \"uniform not found\"); \\\n    glUniform(loc,value); \\\n    glGetUniformiv(prg_id,loc,(GLint*)data.data()); \\\n    if(!value.isApprox(data)) { \\\n      std::cerr << \"Expected:\\n\" << value << \"\\n\" << \"got\\n\" << data << \"\\n\\n\"; \\\n    } \\\n    VERIFY_IS_APPROX(value, data); \\\n  }\n\nvoid printProgramInfoLog(GLuint objectID)\n{\n    int infologLength, charsWritten;\n    GLchar *infoLog;\n    glGetProgramiv(objectID, GL_INFO_LOG_LENGTH, &infologLength);\n    if(infologLength > 0)\n    {\n        infoLog = new GLchar[infologLength];\n        glGetProgramInfoLog(objectID, infologLength, &charsWritten, infoLog);\n        if (charsWritten > 0)\n          std::cerr << \"Program info : \\n\" << infoLog << std::endl;\n        delete[] infoLog;\n    }\n}\n\nvoid printShaderInfoLog(GLuint objectID)\n{\n    int infologLength, charsWritten;\n    GLchar *infoLog;\n    glGetShaderiv(objectID, GL_INFO_LOG_LENGTH, &infologLength);\n    if(infologLength > 0)\n    {\n        infoLog = new GLchar[infologLength];\n        glGetShaderInfoLog(objectID, infologLength, &charsWritten, infoLog);\n        if (charsWritten > 0)\n          std::cerr << \"Shader info : \\n\" << infoLog << std::endl;\n        delete[] infoLog;\n    }\n}\n\nGLint createProgram(const char* vtx, const char* frg, bool print_errors = true)\n{\n  GLint prg_id = glCreateProgram();\n  GLint vtx_id = glCreateShader(GL_VERTEX_SHADER);\n  GLint frg_id = glCreateShader(GL_FRAGMENT_SHADER);\n  GLint ok;\n\n  glShaderSource(vtx_id, 1, &vtx, 0);\n  glCompileShader(vtx_id);\n  glGetShaderiv(vtx_id, GL_COMPILE_STATUS, &ok);\n  if(!ok)\n  {\n    if (print_errors)\n    {\n      std::cerr << \"vtx compilation failed\\n\";\n      std::cerr << \"Source:\\n\" << vtx << \"\\n\";\n      printShaderInfoLog(vtx_id);\n    }\n    glDeleteShader(vtx_id);\n    return GL_ZERO;\n  }\n\n  glShaderSource(frg_id, 1, &frg, 0);\n  glCompileShader(frg_id);\n  glGetShaderiv(frg_id, GL_COMPILE_STATUS, &ok);\n  if(!ok)\n  {\n    if (print_errors)\n    {\n      std::cerr << \"frg compilation failed.\\n\";\n      std::cerr << \"Source:\\n\" << frg << \"\\n\";\n      printShaderInfoLog(frg_id);\n    }\n    glDeleteShader(vtx_id);\n    glDeleteShader(frg_id);\n    return GL_ZERO;\n  }\n\n  glAttachShader(prg_id, vtx_id);\n  glAttachShader(prg_id, frg_id);\n  glLinkProgram(prg_id);\n\n  // Delete shaders once linked.\n  glDeleteShader(vtx_id);\n  glDeleteShader(frg_id);\n  glGetProgramiv(prg_id, GL_LINK_STATUS, &ok);\n  if(!ok)\n  {\n    if (print_errors)\n    {\n      std::cerr << \"linking failed.\\n\";\n      printProgramInfoLog(prg_id);\n    }\n    glDeleteProgram(prg_id);\n    return GL_ZERO;\n  }\n\n  glUseProgram(prg_id);\n  return prg_id;\n}\n\nGLint createProgram(const std::string& vtx, const std::string& frg, bool print_errors = true)\n{\n  return createProgram(vtx.c_str(), frg.c_str(), print_errors);\n}\n\nstd::string getGlslVersionString(int gl_major_version, int gl_minor_version)\n{\n  switch (gl_major_version)\n  {\n    case 2:\n      switch (gl_minor_version)\n      {\n        case 0:\n          return \"#version 110\";\n        case 1:\n          return \"#version 120\";\n      }\n      break;\n    case 3:\n      switch (gl_minor_version)\n      {\n        case 0:\n          return \"#version 130\";\n        case 1:\n          return \"#version 140\";\n        case 2:\n          return \"#version 150\";\n        case 3:\n          return \"#version 330\";\n      }\n      break;\n    case 4:\n      switch (gl_minor_version)\n      {\n        case 0:\n          return \"#version 400\";\n        case 1:\n          return \"#version 410\";\n        case 2:\n          return \"#version 420\";\n        case 3:\n          return \"#version 430\";\n        case 4:\n          return \"#version 440\";\n        case 5:\n          return \"#version 450\";\n        case 6:\n          return \"#version 460\";\n      }\n      break;\n  }\n  return \"\";\n}\n\nvoid find_and_replace(\n  std::string& str,\n  const std::string& find,\n  const std::string& replace)\n{\n  size_t loc = 0;\n  size_t flen = find.length();\n  size_t rlen = replace.length();\n  while ( (loc = str.find(find, loc)) != std::string::npos) {\n    str.replace(loc, flen, replace);\n    loc += rlen;\n  }\n}\n\n// Finds and replaces a set of substrings in a string.\nstd::string format(\n  const std::string& str,\n  const std::vector<std::string>& find,\n  const std::vector<std::string>& replace)\n{\n  std::string out = str;\n  for (std::size_t i=0; i<find.size(); ++i) {\n    find_and_replace(out, find[i], replace[i]);\n  }\n  return out;\n}\n\n// GLUT display function that runs test.  Must be run within the display loop\n// in order to properly destroy resources.\nvoid openglsupport_test_loop()\n{\n  // Get context info.\n  const GLubyte* gl_version_string = glGetString(GL_VERSION);\n  std::cerr << \"GL version: \" << gl_version_string << std::endl;\n  std::cerr << \"GLSL version: \" << glGetString(GL_SHADING_LANGUAGE_VERSION) << std::endl;\n  // Parse version from string since GL_MAJOR_VERSION is only supported in GL 3.0+.\n  // Version string guaranteed to be <major>.<minor><vender extension>.\n  GLint gl_major_version = gl_version_string[0] - '0';\n  GLint gl_minor_version = gl_version_string[2] - '0';\n  bool legacy_gl = gl_major_version < 3 || (gl_major_version == 3 && gl_minor_version < 2);\n\n  // Fixed-function pipeline removed in OpenGL 3.2.\n  if (legacy_gl)\n  {\n    // Draw a basic triangle.\n    Vector3f v3f;\n    Matrix3f rot;\n    glBegin(GL_POINTS);\n    {\n      glVertex(v3f);\n      glVertex(2*v3f+v3f);\n      glVertex(rot*v3f);\n    }\n    glEnd();\n\n    // 4x4 matrices\n    Matrix4f mf44; mf44.setRandom();\n    VERIFY_MATRIX(glLoadMatrix(mf44), mf44);\n    VERIFY_MATRIX(glMultMatrix(mf44), mf44);\n    Matrix4d md44; md44.setRandom();\n    VERIFY_MATRIX(glLoadMatrix(md44), md44);\n    VERIFY_MATRIX(glMultMatrix(md44), md44);\n\n    // Quaternion\n    Quaterniond qd(AngleAxisd(internal::random<double>(), Vector3d::Random()));\n    VERIFY_MATRIX(glRotate(qd), Projective3d(qd).matrix());\n\n    Quaternionf qf(AngleAxisf(internal::random<double>(), Vector3f::Random()));\n    VERIFY_MATRIX(glRotate(qf), Projective3f(qf).matrix());\n\n    // 3D Transform\n    Transform<float,3,AffineCompact> acf3; acf3.matrix().setRandom();\n    VERIFY_MATRIX(glLoadMatrix(acf3), Projective3f(acf3).matrix());\n    VERIFY_MATRIX(glMultMatrix(acf3), Projective3f(acf3).matrix());\n\n    Transform<float,3,Affine> af3(acf3);\n    VERIFY_MATRIX(glLoadMatrix(af3), Projective3f(af3).matrix());\n    VERIFY_MATRIX(glMultMatrix(af3), Projective3f(af3).matrix());\n\n    Transform<float,3,Projective> pf3; pf3.matrix().setRandom();\n    VERIFY_MATRIX(glLoadMatrix(pf3), Projective3f(pf3).matrix());\n    VERIFY_MATRIX(glMultMatrix(pf3), Projective3f(pf3).matrix());\n\n    Transform<double,3,AffineCompact> acd3; acd3.matrix().setRandom();\n    VERIFY_MATRIX(glLoadMatrix(acd3), Projective3d(acd3).matrix());\n    VERIFY_MATRIX(glMultMatrix(acd3), Projective3d(acd3).matrix());\n\n    Transform<double,3,Affine> ad3(acd3);\n    VERIFY_MATRIX(glLoadMatrix(ad3), Projective3d(ad3).matrix());\n    VERIFY_MATRIX(glMultMatrix(ad3), Projective3d(ad3).matrix());\n\n    Transform<double,3,Projective> pd3; pd3.matrix().setRandom();\n    VERIFY_MATRIX(glLoadMatrix(pd3), Projective3d(pd3).matrix());\n    VERIFY_MATRIX(glMultMatrix(pd3), Projective3d(pd3).matrix());\n\n    // translations (2D and 3D)\n    {\n      Vector2f vf2; vf2.setRandom(); Vector3f vf23; vf23 << vf2, 0;\n      VERIFY_MATRIX(glTranslate(vf2), Projective3f(Translation3f(vf23)).matrix());\n      Vector2d vd2; vd2.setRandom(); Vector3d vd23; vd23 << vd2, 0;\n      VERIFY_MATRIX(glTranslate(vd2), Projective3d(Translation3d(vd23)).matrix());\n\n      Vector3f vf3; vf3.setRandom();\n      VERIFY_MATRIX(glTranslate(vf3), Projective3f(Translation3f(vf3)).matrix());\n      Vector3d vd3; vd3.setRandom();\n      VERIFY_MATRIX(glTranslate(vd3), Projective3d(Translation3d(vd3)).matrix());\n\n      Translation<float,3> tf3; tf3.vector().setRandom();\n      VERIFY_MATRIX(glTranslate(tf3), Projective3f(tf3).matrix());\n\n      Translation<double,3> td3;  td3.vector().setRandom();\n      VERIFY_MATRIX(glTranslate(td3), Projective3d(td3).matrix());\n    }\n\n    // scaling (2D and 3D)\n    {\n      Vector2f vf2; vf2.setRandom(); Vector3f vf23; vf23 << vf2, 1;\n      VERIFY_MATRIX(glScale(vf2), Projective3f(Scaling(vf23)).matrix());\n      Vector2d vd2; vd2.setRandom(); Vector3d vd23; vd23 << vd2, 1;\n      VERIFY_MATRIX(glScale(vd2), Projective3d(Scaling(vd23)).matrix());\n\n      Vector3f vf3; vf3.setRandom();\n      VERIFY_MATRIX(glScale(vf3), Projective3f(Scaling(vf3)).matrix());\n      Vector3d vd3; vd3.setRandom();\n      VERIFY_MATRIX(glScale(vd3), Projective3d(Scaling(vd3)).matrix());\n\n      UniformScaling<float> usf(internal::random<float>());\n      VERIFY_MATRIX(glScale(usf), Projective3f(usf).matrix());\n\n      UniformScaling<double> usd(internal::random<double>());\n      VERIFY_MATRIX(glScale(usd), Projective3d(usd).matrix());\n    }\n  } else {\n    std::cerr << \"Warning: fixed-function pipeline was not tested.\\n\";\n  }\n\n  // Dynamic shader substitution variables.\n  // Modern shaders require a version string, and newer runtimes fail to\n  // compile old GLSL versions. Thus, we dynamically set the GLSL version\n  // string based on runtime. Also, pre OpenGL 3.0, the output gl_FragColor was\n  // built-in. This was deprecated in OpenGL 3.0, requiring us to explicitly\n  // define the output variable.\n  std::vector<std::string> glsl_vars;\n  glsl_vars.push_back(\"${GLSL_VERSION}\");\n  glsl_vars.push_back(\"${FRAG_OUTPUT_DECLARATION}\");\n  glsl_vars.push_back(\"${FRAG_OUTPUT_VARIABLE}\");\n\n  std::vector<std::string> glsl_vals;\n  glsl_vals.push_back(getGlslVersionString(gl_major_version, gl_minor_version));\n  if (gl_major_version >= 3) {\n    glsl_vals.push_back(\"out vec4 fragColor;\");\n    glsl_vals.push_back(\"fragColor\");\n  } else {\n    glsl_vals.push_back(\"\");\n    glsl_vals.push_back(\"gl_FragColor\");\n  }\n\n  // uniform\n  {\n    // vertex shader.\n    std::string vtx = format(\n      \"${GLSL_VERSION}\\n\"\n      \"void main(void) {\\n\"\n      \"  gl_Position = vec4(0,0,0,1);\\n\"\n      \"}\\n\",\n      glsl_vars, glsl_vals);\n\n#ifdef GL_VERSION_2_0\n    if(GLEW_VERSION_2_0 && GL_VERSION_2_0)\n    {\n      std::string frg = format(\n        \"${GLSL_VERSION}\\n\"\n        \"uniform vec2 v2f;\\n\"\n        \"uniform vec3 v3f;\\n\"\n        \"uniform vec4 v4f;\\n\"\n        \"uniform ivec2 v2i;\\n\"\n        \"uniform ivec3 v3i;\\n\"\n        \"uniform ivec4 v4i;\\n\"\n        \"uniform mat2 m2f;\\n\"\n        \"uniform mat3 m3f;\\n\"\n        \"uniform mat4 m4f;\\n\"\n        \"${FRAG_OUTPUT_DECLARATION}\\n\"\n        \"void main(void) { \\n\"\n        \"  ${FRAG_OUTPUT_VARIABLE} = vec4(v2f[0]+v3f[0]+v4f[0])+vec4(v2i[0]+v3i[0]+v4i[0])+vec4(m2f[0][0]+m3f[0][0]+m4f[0][0]);\\n\"\n        \"}\\n\",\n        glsl_vars, glsl_vals);\n\n      GLint prg_id = createProgram(vtx, frg);\n      VERIFY(prg_id > 0 && \"Failed to create program.\");\n      VERIFY_UNIFORM(fv, v2f, Vector2f);\n      VERIFY_UNIFORM(fv, v3f, Vector3f);\n      VERIFY_UNIFORM(fv, v4f, Vector4f);\n      VERIFY_UNIFORMi(v2i, Vector2i);\n      VERIFY_UNIFORMi(v3i, Vector3i);\n      VERIFY_UNIFORMi(v4i, Vector4i);\n      VERIFY_UNIFORM(fv, m2f, Matrix2f);\n      VERIFY_UNIFORM(fv, m3f, Matrix3f);\n      VERIFY_UNIFORM(fv, m4f, Matrix4f);\n      glDeleteProgram(prg_id);\n    }\n    else\n#endif\n      std::cerr << \"Warning: opengl 2.0 was not tested.\\n\";\n\n#ifdef GL_VERSION_2_1\n    if(GLEW_VERSION_2_1 && GL_VERSION_2_1 &&\n        (gl_major_version > 2 || (gl_major_version == 2 && gl_minor_version >= 1)))\n    {\n      std::string frg = format(\n        \"${GLSL_VERSION}\\n\"\n        \"uniform mat2x3 m23f;\\n\"\n        \"uniform mat3x2 m32f;\\n\"\n        \"uniform mat2x4 m24f;\\n\"\n        \"uniform mat4x2 m42f;\\n\"\n        \"uniform mat3x4 m34f;\\n\"\n        \"uniform mat4x3 m43f;\\n\"\n        \"${FRAG_OUTPUT_DECLARATION}\\n\"\n        \"void main(void) {\\n\"\n        \"  ${FRAG_OUTPUT_VARIABLE} = vec4(m23f[0][0]+m32f[0][0]+m24f[0][0]+m42f[0][0]+m34f[0][0]+m43f[0][0]);\\n\"\n        \"}\\n\",\n        glsl_vars, glsl_vals);\n\n      GLint prg_id = createProgram(vtx, frg);\n      VERIFY(prg_id > 0 && \"Failed to create program.\");\n      typedef Matrix<float,2,3> Matrix23f;\n      typedef Matrix<float,3,2> Matrix32f;\n      typedef Matrix<float,2,4> Matrix24f;\n      typedef Matrix<float,4,2> Matrix42f;\n      typedef Matrix<float,3,4> Matrix34f;\n      typedef Matrix<float,4,3> Matrix43f;\n\n      VERIFY_UNIFORM(fv, m23f, Matrix23f);\n      VERIFY_UNIFORM(fv, m32f, Matrix32f);\n      VERIFY_UNIFORM(fv, m24f, Matrix24f);\n      VERIFY_UNIFORM(fv, m42f, Matrix42f);\n      VERIFY_UNIFORM(fv, m34f, Matrix34f);\n      VERIFY_UNIFORM(fv, m43f, Matrix43f);\n      glDeleteProgram(prg_id);\n    }\n    else\n#endif\n      std::cerr << \"Warning: opengl 2.1 was not tested.\\n\";\n\n#ifdef GL_VERSION_3_0\n    if(GLEW_VERSION_3_0 && GL_VERSION_3_0 && gl_major_version >= 3)\n    {\n      std::string frg = format(\n        \"${GLSL_VERSION}\\n\"\n        \"uniform uvec2 v2ui;\\n\"\n        \"uniform uvec3 v3ui;\\n\"\n        \"uniform uvec4 v4ui;\\n\"\n        \"${FRAG_OUTPUT_DECLARATION}\\n\"\n        \"void main(void) {\\n\"\n        \"  ${FRAG_OUTPUT_VARIABLE} = vec4(v2ui[0]+v3ui[0]+v4ui[0]);\\n\"\n        \"}\\n\",\n        glsl_vars, glsl_vals);\n\n      GLint prg_id = createProgram(vtx, frg);\n      VERIFY(prg_id > 0 && \"Failed to create program.\");\n      typedef Matrix<unsigned int,2,1> Vector2ui;\n      typedef Matrix<unsigned int,3,1> Vector3ui;\n      typedef Matrix<unsigned int,4,1> Vector4ui;\n\n      VERIFY_UNIFORMi(v2ui, Vector2ui);\n      VERIFY_UNIFORMi(v3ui, Vector3ui);\n      VERIFY_UNIFORMi(v4ui, Vector4ui);\n      glDeleteProgram(prg_id);\n    }\n    else\n#endif\n      std::cerr << \"Warning: opengl 3.0 was not tested.\\n\";\n\n    // dvecn supported if >= 4.1 or ARB_vertex_attrib_64bit\n    bool has_fp64_native = (gl_major_version == 4 && gl_minor_version >= 1);\n    bool has_fp64_extension = false;\n#ifdef GLEW_ARB_gpu_shader_fp64\n    if(GLEW_ARB_gpu_shader_fp64)\n    {\n      // Check that extension can actually be compiled.\n      if (has_fp64_extension)\n      {\n        std::string frg = format(\n          \"${GLSL_VERSION}\\n\"\n          \"#extension GL_ARB_gpu_shader_fp64 : enable\\n\"\n          \"uniform dvec2 dv2;\\n\"\n          \"${FRAG_OUTPUT_DECLARATION}\\n\"\n          \"void main(void) {\\n\"\n          \"  ${FRAG_OUTPUT_VARIABLE} = vec4(dv2.x, dv2.y, dv2.x, dv2.y);\\n\"\n          \"}\\n\",\n          glsl_vars, glsl_vals);\n        GLint prg_id = createProgram(vtx, frg, /*print_errors=*/false);\n        if (prg_id)\n        {\n          has_fp64_extension = true;\n          glDeleteProgram(prg_id);\n        }\n      }\n    }\n#endif\n\n    if( has_fp64_native || has_fp64_extension )\n    {\n      std::vector<std::string> glsl_vars_with_extension = glsl_vars;\n      glsl_vars_with_extension.push_back(\"${GLSL_EXTENSIONS}\");\n      std::vector<std::string> glsl_vals_with_extension = glsl_vals;\n      if (has_fp64_extension)\n      {\n        glsl_vals_with_extension.push_back(\"#extension GL_ARB_gpu_shader_fp64 : enable\");\n      }\n      else\n      {\n        glsl_vals_with_extension.push_back(\"\");\n      }\n\n      std::string frg = format(\n        \"${GLSL_VERSION}\\n\"\n        \"${GLSL_EXTENSIONS}\\n\"\n        \"uniform dvec2 v2d;\\n\"\n        \"uniform dvec3 v3d;\\n\"\n        \"uniform dvec4 v4d;\\n\"\n        \"${FRAG_OUTPUT_DECLARATION}\\n\"\n        \"void main(void) {\\n\"\n        \"  ${FRAG_OUTPUT_VARIABLE} = vec4(v2d[0]+v3d[0]+v4d[0]);\\n\"\n        \"}\\n\",\n        glsl_vars_with_extension, glsl_vals_with_extension);\n\n      GLint prg_id = createProgram(vtx,frg);\n      VERIFY(prg_id > 0 && \"Failed to create program.\");\n      VERIFY_UNIFORM(dv, v2d, Vector2d);\n      VERIFY_UNIFORM(dv, v3d, Vector3d);\n      VERIFY_UNIFORM(dv, v4d, Vector4d);\n      glDeleteProgram(prg_id);\n    }\n    else\n      std::cerr << \"Warning: dvec (fp64) was not tested.\\n\";\n  }\n\n  // Exit loop - Leaving main loop is supported by freeglut, otherwise we\n  // are forced to exit.\n#ifdef FREEGLUT\n  glutLeaveMainLoop();\n  // Trigger another display loop iteration. Otherwise, it just hangs.\n  glutPostRedisplay();\n#else\n  exit(0);\n#endif\n}\n\nEIGEN_DECLARE_TEST(openglsupport)\n{\n  int argc = 0;\n  glutInit(&argc, 0);\n\n  GLint glut_display_mode = GLUT_DOUBLE | GLUT_RGB | GLUT_DEPTH;\n\n#ifndef EIGEN_LEGACY_OPENGL\n  // Initialize 3.2+ OpenGL context.\n#if defined(__APPLE_CC__)\n  glut_display_mode |= GLUT_3_2_CORE_PROFILE;\n#elif defined(FREEGLUT)\n  glutInitContextVersion(3, 2);\n  glutInitContextFlags(GLUT_FORWARD_COMPATIBLE);\n  glutInitContextProfile(GLUT_CORE_PROFILE);\n#endif\n#endif\n\n  glutInitDisplayMode(glut_display_mode);\n  glutInitWindowPosition(0, 0);\n  glutInitWindowSize(10, 10);\n\n  int window = glutCreateWindow(\"Eigen\");\n  if(window <= 0)\n  {\n    std::cerr << \"Error: Unable to create GLUT Window.\\n\";\n    exit(1);\n  }\n\n  glewExperimental = GL_TRUE;\n  if(glewInit() != GLEW_OK)\n  {\n    std::cerr << \"Warning: Failed to initialize GLEW.\\n\";\n    exit(1);\n  }\n\n  // Run test in display, otherwise GLUT fails to clean up and leads to memory\n  // access errors on exit.\n  glutDisplayFunc(openglsupport_test_loop);\n  glutMainLoop();\n  glutDestroyWindow(window);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/polynomialsolver.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Manuel Yguel <manuel.yguel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <unsupported/Eigen/Polynomials>\n#include <iostream>\n#include <algorithm>\n\nusing namespace std;\n\nnamespace Eigen {\nnamespace internal {\ntemplate<int Size>\nstruct increment_if_fixed_size\n{\n  enum {\n    ret = (Size == Dynamic) ? Dynamic : Size+1\n  };\n};\n}\n}\n\ntemplate<typename PolynomialType>\nPolynomialType polyder(const PolynomialType& p)\n{\n  typedef typename PolynomialType::Scalar Scalar;\n  PolynomialType res(p.size());\n  for(Index i=1; i<p.size(); ++i)\n    res[i-1] = p[i]*Scalar(i);\n  res[p.size()-1] = 0.;\n  return res;\n}\n\ntemplate<int Deg, typename POLYNOMIAL, typename SOLVER>\nbool aux_evalSolver( const POLYNOMIAL& pols, SOLVER& psolve )\n{\n  typedef typename POLYNOMIAL::Scalar Scalar;\n  typedef typename POLYNOMIAL::RealScalar RealScalar;\n\n  typedef typename SOLVER::RootsType    RootsType;\n  typedef Matrix<RealScalar,Deg,1>      EvalRootsType;\n\n  const Index deg = pols.size()-1;\n\n  // Test template constructor from coefficient vector\n  SOLVER solve_constr (pols);\n\n  psolve.compute( pols );\n  const RootsType& roots( psolve.roots() );\n  EvalRootsType evr( deg );\n  POLYNOMIAL pols_der = polyder(pols);\n  EvalRootsType der( deg );\n  for( int i=0; i<roots.size(); ++i ){\n    evr[i] = std::abs( poly_eval( pols, roots[i] ) );\n    der[i] = numext::maxi(RealScalar(1.), std::abs( poly_eval( pols_der, roots[i] ) ));\n  }\n\n  // we need to divide by the magnitude of the derivative because\n  // with a high derivative is very small error in the value of the root\n  // yiels a very large error in the polynomial evaluation.\n  bool evalToZero = (evr.cwiseQuotient(der)).isZero( test_precision<Scalar>() );\n  if( !evalToZero )\n  {\n    cerr << \"WRONG root: \" << endl;\n    cerr << \"Polynomial: \" << pols.transpose() << endl;\n    cerr << \"Roots found: \" << roots.transpose() << endl;\n    cerr << \"Abs value of the polynomial at the roots: \" << evr.transpose() << endl;\n    cerr << endl;\n  }\n\n  std::vector<RealScalar> rootModuli( roots.size() );\n  Map< EvalRootsType > aux( &rootModuli[0], roots.size() );\n  aux = roots.array().abs();\n  std::sort( rootModuli.begin(), rootModuli.end() );\n  bool distinctModuli=true;\n  for( size_t i=1; i<rootModuli.size() && distinctModuli; ++i )\n  {\n    if( internal::isApprox( rootModuli[i], rootModuli[i-1] ) ){\n      distinctModuli = false; }\n  }\n  VERIFY( evalToZero || !distinctModuli );\n\n  return distinctModuli;\n}\n\n\n\n\n\n\n\ntemplate<int Deg, typename POLYNOMIAL>\nvoid evalSolver( const POLYNOMIAL& pols )\n{\n  typedef typename POLYNOMIAL::Scalar Scalar;\n\n  typedef PolynomialSolver<Scalar, Deg > PolynomialSolverType;\n\n  PolynomialSolverType psolve;\n  aux_evalSolver<Deg, POLYNOMIAL, PolynomialSolverType>( pols, psolve );\n}\n\n\n\n\ntemplate< int Deg, typename POLYNOMIAL, typename ROOTS, typename REAL_ROOTS >\nvoid evalSolverSugarFunction( const POLYNOMIAL& pols, const ROOTS& roots, const REAL_ROOTS& real_roots )\n{\n  using std::sqrt;\n  typedef typename POLYNOMIAL::Scalar Scalar;\n  typedef typename POLYNOMIAL::RealScalar RealScalar;\n\n  typedef PolynomialSolver<Scalar, Deg >              PolynomialSolverType;\n\n  PolynomialSolverType psolve;\n  if( aux_evalSolver<Deg, POLYNOMIAL, PolynomialSolverType>( pols, psolve ) )\n  {\n    //It is supposed that\n    // 1) the roots found are correct\n    // 2) the roots have distinct moduli\n\n    //Test realRoots\n    std::vector< RealScalar > calc_realRoots;\n    psolve.realRoots( calc_realRoots,  test_precision<RealScalar>());\n    VERIFY_IS_EQUAL( calc_realRoots.size() , (size_t)real_roots.size() );\n\n    const RealScalar psPrec = sqrt( test_precision<RealScalar>() );\n\n    for( size_t i=0; i<calc_realRoots.size(); ++i )\n    {\n      bool found = false;\n      for( size_t j=0; j<calc_realRoots.size()&& !found; ++j )\n      {\n        if( internal::isApprox( calc_realRoots[i], real_roots[j], psPrec ) ){\n          found = true; }\n      }\n      VERIFY( found );\n    }\n\n    //Test greatestRoot\n    VERIFY( internal::isApprox( roots.array().abs().maxCoeff(),\n          abs( psolve.greatestRoot() ), psPrec ) );\n\n    //Test smallestRoot\n    VERIFY( internal::isApprox( roots.array().abs().minCoeff(),\n          abs( psolve.smallestRoot() ), psPrec ) );\n\n    bool hasRealRoot;\n    //Test absGreatestRealRoot\n    RealScalar r = psolve.absGreatestRealRoot( hasRealRoot );\n    VERIFY( hasRealRoot == (real_roots.size() > 0 ) );\n    if( hasRealRoot ){\n      VERIFY( internal::isApprox( real_roots.array().abs().maxCoeff(), abs(r), psPrec ) );  }\n\n    //Test absSmallestRealRoot\n    r = psolve.absSmallestRealRoot( hasRealRoot );\n    VERIFY( hasRealRoot == (real_roots.size() > 0 ) );\n    if( hasRealRoot ){\n      VERIFY( internal::isApprox( real_roots.array().abs().minCoeff(), abs( r ), psPrec ) ); }\n\n    //Test greatestRealRoot\n    r = psolve.greatestRealRoot( hasRealRoot );\n    VERIFY( hasRealRoot == (real_roots.size() > 0 ) );\n    if( hasRealRoot ){\n      VERIFY( internal::isApprox( real_roots.array().maxCoeff(), r, psPrec ) ); }\n\n    //Test smallestRealRoot\n    r = psolve.smallestRealRoot( hasRealRoot );\n    VERIFY( hasRealRoot == (real_roots.size() > 0 ) );\n    if( hasRealRoot ){\n    VERIFY( internal::isApprox( real_roots.array().minCoeff(), r, psPrec ) ); }\n  }\n}\n\n\ntemplate<typename Scalar_, int _Deg>\nvoid polynomialsolver(int deg)\n{\n  typedef typename NumTraits<Scalar_>::Real RealScalar;\n  typedef internal::increment_if_fixed_size<_Deg>     Dim;\n  typedef Matrix<Scalar_,Dim::ret,1>                  PolynomialType;\n  typedef Matrix<Scalar_,_Deg,1>                      EvalRootsType;\n  typedef Matrix<RealScalar,_Deg,1>                   RealRootsType;\n\n  cout << \"Standard cases\" << endl;\n  PolynomialType pols = PolynomialType::Random(deg+1);\n  evalSolver<_Deg,PolynomialType>( pols );\n\n  cout << \"Hard cases\" << endl;\n  Scalar_ multipleRoot = internal::random<Scalar_>();\n  EvalRootsType allRoots = EvalRootsType::Constant(deg,multipleRoot);\n  roots_to_monicPolynomial( allRoots, pols );\n  evalSolver<_Deg,PolynomialType>( pols );\n\n  cout << \"Test sugar\" << endl;\n  RealRootsType realRoots = RealRootsType::Random(deg);\n  roots_to_monicPolynomial( realRoots, pols );\n  evalSolverSugarFunction<_Deg>(\n      pols,\n      realRoots.template cast <std::complex<RealScalar> >().eval(),\n      realRoots );\n}\n\nEIGEN_DECLARE_TEST(polynomialsolver)\n{\n  for(int i = 0; i < g_repeat; i++)\n  {\n    CALL_SUBTEST_1( (polynomialsolver<float,1>(1)) );\n    CALL_SUBTEST_2( (polynomialsolver<double,2>(2)) );\n    CALL_SUBTEST_3( (polynomialsolver<double,3>(3)) );\n    CALL_SUBTEST_4( (polynomialsolver<float,4>(4)) );\n    CALL_SUBTEST_5( (polynomialsolver<double,5>(5)) );\n    CALL_SUBTEST_6( (polynomialsolver<float,6>(6)) );\n    CALL_SUBTEST_7( (polynomialsolver<float,7>(7)) );\n    CALL_SUBTEST_8( (polynomialsolver<double,8>(8)) );\n\n    CALL_SUBTEST_9( (polynomialsolver<float,Dynamic>(\n            internal::random<int>(9,13)\n            )) );\n    CALL_SUBTEST_10((polynomialsolver<double,Dynamic>(\n            internal::random<int>(9,13)\n            )) );\n    CALL_SUBTEST_11((polynomialsolver<float,Dynamic>(1)) );\n    CALL_SUBTEST_12((polynomialsolver<std::complex<double>,Dynamic>(internal::random<int>(2,13))) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/polynomialutils.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Manuel Yguel <manuel.yguel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <unsupported/Eigen/Polynomials>\n#include <iostream>\n\nusing namespace std;\n\nnamespace Eigen {\nnamespace internal {\ntemplate<int Size>\nstruct increment_if_fixed_size\n{\n  enum {\n    ret = (Size == Dynamic) ? Dynamic : Size+1\n  };\n};\n}\n}\n\ntemplate<typename Scalar_, int _Deg>\nvoid realRoots_to_monicPolynomial_test(int deg)\n{\n  typedef internal::increment_if_fixed_size<_Deg>            Dim;\n  typedef Matrix<Scalar_,Dim::ret,1>                  PolynomialType;\n  typedef Matrix<Scalar_,_Deg,1>                      EvalRootsType;\n\n  PolynomialType pols(deg+1);\n  EvalRootsType roots = EvalRootsType::Random(deg);\n  roots_to_monicPolynomial( roots, pols );\n\n  EvalRootsType evr( deg );\n  for( int i=0; i<roots.size(); ++i ){\n    evr[i] = std::abs( poly_eval( pols, roots[i] ) ); }\n\n  bool evalToZero = evr.isZero( test_precision<Scalar_>() );\n  if( !evalToZero ){\n    cerr << evr.transpose() << endl; }\n  VERIFY( evalToZero );\n}\n\ntemplate<typename Scalar_> void realRoots_to_monicPolynomial_scalar()\n{\n  CALL_SUBTEST_2( (realRoots_to_monicPolynomial_test<Scalar_,2>(2)) );\n  CALL_SUBTEST_3( (realRoots_to_monicPolynomial_test<Scalar_,3>(3)) );\n  CALL_SUBTEST_4( (realRoots_to_monicPolynomial_test<Scalar_,4>(4)) );\n  CALL_SUBTEST_5( (realRoots_to_monicPolynomial_test<Scalar_,5>(5)) );\n  CALL_SUBTEST_6( (realRoots_to_monicPolynomial_test<Scalar_,6>(6)) );\n  CALL_SUBTEST_7( (realRoots_to_monicPolynomial_test<Scalar_,7>(7)) );\n  CALL_SUBTEST_8( (realRoots_to_monicPolynomial_test<Scalar_,17>(17)) );\n\n  CALL_SUBTEST_9( (realRoots_to_monicPolynomial_test<Scalar_,Dynamic>(\n          internal::random<int>(18,26) )) );\n}\n\n\n\n\ntemplate<typename Scalar_, int _Deg>\nvoid CauchyBounds(int deg)\n{\n  typedef internal::increment_if_fixed_size<_Deg>            Dim;\n  typedef Matrix<Scalar_,Dim::ret,1>                  PolynomialType;\n  typedef Matrix<Scalar_,_Deg,1>                      EvalRootsType;\n\n  PolynomialType pols(deg+1);\n  EvalRootsType roots = EvalRootsType::Random(deg);\n  roots_to_monicPolynomial( roots, pols );\n  Scalar_ M = cauchy_max_bound( pols );\n  Scalar_ m = cauchy_min_bound( pols );\n  Scalar_ Max = roots.array().abs().maxCoeff();\n  Scalar_ min = roots.array().abs().minCoeff();\n  bool eval = (M >= Max) && (m <= min);\n  if( !eval )\n  {\n    cerr << \"Roots: \" << roots << endl;\n    cerr << \"Bounds: (\" << m << \", \" << M << \")\" << endl;\n    cerr << \"Min,Max: (\" << min << \", \" << Max << \")\" << endl;\n  }\n  VERIFY( eval );\n}\n\ntemplate<typename Scalar_> void CauchyBounds_scalar()\n{\n  CALL_SUBTEST_2( (CauchyBounds<Scalar_,2>(2)) );\n  CALL_SUBTEST_3( (CauchyBounds<Scalar_,3>(3)) );\n  CALL_SUBTEST_4( (CauchyBounds<Scalar_,4>(4)) );\n  CALL_SUBTEST_5( (CauchyBounds<Scalar_,5>(5)) );\n  CALL_SUBTEST_6( (CauchyBounds<Scalar_,6>(6)) );\n  CALL_SUBTEST_7( (CauchyBounds<Scalar_,7>(7)) );\n  CALL_SUBTEST_8( (CauchyBounds<Scalar_,17>(17)) );\n\n  CALL_SUBTEST_9( (CauchyBounds<Scalar_,Dynamic>(\n          internal::random<int>(18,26) )) );\n}\n\nEIGEN_DECLARE_TEST(polynomialutils)\n{\n  for(int i = 0; i < g_repeat; i++)\n  {\n    realRoots_to_monicPolynomial_scalar<double>();\n    realRoots_to_monicPolynomial_scalar<float>();\n    CauchyBounds_scalar<double>();\n    CauchyBounds_scalar<float>();\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/sparse_extra.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2010 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n// import basic and product tests for deprecated DynamicSparseMatrix\n#if 0 // sparse_basic(DynamicSparseMatrix) does not compile at all -> disabled\nstatic long g_realloc_count = 0;\n#define EIGEN_SPARSE_COMPRESSED_STORAGE_REALLOCATE_PLUGIN g_realloc_count++;\n\nstatic long g_dense_op_sparse_count = 0;\n#define EIGEN_SPARSE_ASSIGNMENT_FROM_DENSE_OP_SPARSE_PLUGIN g_dense_op_sparse_count++;\n#define EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_ADD_DENSE_PLUGIN g_dense_op_sparse_count+=10;\n#define EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_SUB_DENSE_PLUGIN g_dense_op_sparse_count+=20;\n\n#define EIGEN_SPARSE_TEST_INCLUDED_FROM_SPARSE_EXTRA 1\n#endif\n\n#define EIGEN_NO_DEPRECATED_WARNING\n// Disable counting of temporaries, since sparse_product(DynamicSparseMatrix)\n// has an extra copy-assignment.\n#define EIGEN_SPARSE_PRODUCT_IGNORE_TEMPORARY_COUNT\n#include \"sparse_product.cpp\"\n\n#ifdef min\n#undef min\n#endif\n\n#ifdef max\n#undef max\n#endif\n\n#include <Eigen/SparseExtra>\n\ntemplate<typename SetterType,typename DenseType, typename Scalar, int Options>\nbool test_random_setter(SparseMatrix<Scalar,Options>& sm, const DenseType& ref, const std::vector<Vector2i>& nonzeroCoords)\n{\n  {\n    sm.setZero();\n    SetterType w(sm);\n    std::vector<Vector2i> remaining = nonzeroCoords;\n    while(!remaining.empty())\n    {\n      int i = internal::random<int>(0,static_cast<int>(remaining.size())-1);\n      w(remaining[i].x(),remaining[i].y()) = ref.coeff(remaining[i].x(),remaining[i].y());\n      remaining[i] = remaining.back();\n      remaining.pop_back();\n    }\n  }\n  return sm.isApprox(ref);\n}\n\ntemplate<typename SetterType,typename DenseType, typename T>\nbool test_random_setter(DynamicSparseMatrix<T>& sm, const DenseType& ref, const std::vector<Vector2i>& nonzeroCoords)\n{\n  sm.setZero();\n  std::vector<Vector2i> remaining = nonzeroCoords;\n  while(!remaining.empty())\n  {\n    int i = internal::random<int>(0,static_cast<int>(remaining.size())-1);\n    sm.coeffRef(remaining[i].x(),remaining[i].y()) = ref.coeff(remaining[i].x(),remaining[i].y());\n    remaining[i] = remaining.back();\n    remaining.pop_back();\n  }\n  return sm.isApprox(ref);\n}\n\ntemplate<typename SparseMatrixType> void sparse_extra(const SparseMatrixType& ref)\n{\n  const Index rows = ref.rows();\n  const Index cols = ref.cols();\n  typedef typename SparseMatrixType::Scalar Scalar;\n  enum { Flags = SparseMatrixType::Flags };\n\n  double density = (std::max)(8./(rows*cols), 0.01);\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n  Scalar eps = 1e-6;\n\n  SparseMatrixType m(rows, cols);\n  DenseMatrix refMat = DenseMatrix::Zero(rows, cols);\n  DenseVector vec1 = DenseVector::Random(rows);\n\n  std::vector<Vector2i> zeroCoords;\n  std::vector<Vector2i> nonzeroCoords;\n  initSparse<Scalar>(density, refMat, m, 0, &zeroCoords, &nonzeroCoords);\n\n  if (zeroCoords.size()==0 || nonzeroCoords.size()==0)\n    return;\n\n  // test coeff and coeffRef\n  for (int i=0; i<(int)zeroCoords.size(); ++i)\n  {\n    VERIFY_IS_MUCH_SMALLER_THAN( m.coeff(zeroCoords[i].x(),zeroCoords[i].y()), eps );\n    if(internal::is_same<SparseMatrixType,SparseMatrix<Scalar,Flags> >::value)\n      VERIFY_RAISES_ASSERT( m.coeffRef(zeroCoords[0].x(),zeroCoords[0].y()) = 5 );\n  }\n  VERIFY_IS_APPROX(m, refMat);\n\n  m.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5);\n  refMat.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5);\n\n  VERIFY_IS_APPROX(m, refMat);\n\n  // random setter\n//   {\n//     m.setZero();\n//     VERIFY_IS_NOT_APPROX(m, refMat);\n//     SparseSetter<SparseMatrixType, RandomAccessPattern> w(m);\n//     std::vector<Vector2i> remaining = nonzeroCoords;\n//     while(!remaining.empty())\n//     {\n//       int i = internal::random<int>(0,remaining.size()-1);\n//       w->coeffRef(remaining[i].x(),remaining[i].y()) = refMat.coeff(remaining[i].x(),remaining[i].y());\n//       remaining[i] = remaining.back();\n//       remaining.pop_back();\n//     }\n//   }\n//   VERIFY_IS_APPROX(m, refMat);\n\n    VERIFY(( test_random_setter<RandomSetter<SparseMatrixType, StdMapTraits> >(m,refMat,nonzeroCoords) ));\n    VERIFY(( test_random_setter<RandomSetter<SparseMatrixType, StdUnorderedMapTraits> >(m,refMat,nonzeroCoords) ));\n    #ifdef EIGEN_GOOGLEHASH_SUPPORT\n    VERIFY(( test_random_setter<RandomSetter<SparseMatrixType, GoogleDenseHashMapTraits> >(m,refMat,nonzeroCoords) ));\n    VERIFY(( test_random_setter<RandomSetter<SparseMatrixType, GoogleSparseHashMapTraits> >(m,refMat,nonzeroCoords) ));\n    #endif\n\n\n  // test RandomSetter\n  /*{\n    SparseMatrixType m1(rows,cols), m2(rows,cols);\n    DenseMatrix refM1 = DenseMatrix::Zero(rows, rows);\n    initSparse<Scalar>(density, refM1, m1);\n    {\n      Eigen::RandomSetter<SparseMatrixType > setter(m2);\n      for (int j=0; j<m1.outerSize(); ++j)\n        for (typename SparseMatrixType::InnerIterator i(m1,j); i; ++i)\n          setter(i.index(), j) = i.value();\n    }\n    VERIFY_IS_APPROX(m1, m2);\n  }*/\n\n\n}\n\n\ntemplate<typename SparseMatrixType>\nvoid check_marketio()\n{\n  typedef Matrix<typename SparseMatrixType::Scalar, Dynamic, Dynamic> DenseMatrix;\n  Index rows = internal::random<Index>(1,100);\n  Index cols = internal::random<Index>(1,100);\n  SparseMatrixType m1, m2;\n  m1 = DenseMatrix::Random(rows, cols).sparseView();\n  saveMarket(m1, \"sparse_extra.mtx\");\n  loadMarket(m2, \"sparse_extra.mtx\");\n  VERIFY_IS_EQUAL(DenseMatrix(m1),DenseMatrix(m2));\n}\n\ntemplate<typename VectorType>\nvoid check_marketio_vector()\n{\n  Index size = internal::random<Index>(1,100);\n  VectorType v1, v2;\n  v1 = VectorType::Random(size);\n  saveMarketVector(v1, \"vector_extra.mtx\");\n  loadMarketVector(v2, \"vector_extra.mtx\");\n  VERIFY_IS_EQUAL(v1,v2);\n}\n\nEIGEN_DECLARE_TEST(sparse_extra)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    int s = Eigen::internal::random<int>(1,50);\n    CALL_SUBTEST_1( sparse_extra(SparseMatrix<double>(8, 8)) );\n    CALL_SUBTEST_2( sparse_extra(SparseMatrix<std::complex<double> >(s, s)) );\n    CALL_SUBTEST_1( sparse_extra(SparseMatrix<double>(s, s)) );\n\n    CALL_SUBTEST_4( (check_marketio<SparseMatrix<float,ColMajor,int> >()) );\n    CALL_SUBTEST_4( (check_marketio<SparseMatrix<double,ColMajor,int> >()) );\n    CALL_SUBTEST_4( (check_marketio<SparseMatrix<std::complex<float>,ColMajor,int> >()) );\n    CALL_SUBTEST_4( (check_marketio<SparseMatrix<std::complex<double>,ColMajor,int> >()) );\n    CALL_SUBTEST_4( (check_marketio<SparseMatrix<float,ColMajor,long int> >()) );\n    CALL_SUBTEST_4( (check_marketio<SparseMatrix<double,ColMajor,long int> >()) );\n    CALL_SUBTEST_4( (check_marketio<SparseMatrix<std::complex<float>,ColMajor,long int> >()) );\n    CALL_SUBTEST_4( (check_marketio<SparseMatrix<std::complex<double>,ColMajor,long int> >()) );\n\n\n    CALL_SUBTEST_5( (check_marketio_vector<Matrix<float,1,Dynamic> >()) );\n    CALL_SUBTEST_5( (check_marketio_vector<Matrix<double,1,Dynamic> >()) );\n    CALL_SUBTEST_5( (check_marketio_vector<Matrix<std::complex<float>,1,Dynamic> >()) );\n    CALL_SUBTEST_5( (check_marketio_vector<Matrix<std::complex<double>,1,Dynamic> >()) );\n    CALL_SUBTEST_5( (check_marketio_vector<Matrix<float,Dynamic,1> >()) );\n    CALL_SUBTEST_5( (check_marketio_vector<Matrix<double,Dynamic,1> >()) );\n    CALL_SUBTEST_5( (check_marketio_vector<Matrix<std::complex<float>,Dynamic,1> >()) );\n    CALL_SUBTEST_5( (check_marketio_vector<Matrix<std::complex<double>,Dynamic,1> >()) );\n\n    TEST_SET_BUT_UNUSED_VARIABLE(s);\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/special_functions.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <limits.h>\n#include \"main.h\"\n#include \"../Eigen/SpecialFunctions\"\n\n// Hack to allow \"implicit\" conversions from double to Scalar via comma-initialization.\ntemplate<typename Derived>\nEigen::CommaInitializer<Derived> operator<<(Eigen::DenseBase<Derived>& dense, double v) {\n  return (dense << static_cast<typename Derived::Scalar>(v));\n}\n\ntemplate<typename XprType>\nEigen::CommaInitializer<XprType>& operator,(Eigen::CommaInitializer<XprType>& ci, double v) {\n  return (ci, static_cast<typename XprType::Scalar>(v));\n}\n\ntemplate<typename X, typename Y>\nvoid verify_component_wise(const X& x, const Y& y)\n{\n  for(Index i=0; i<x.size(); ++i)\n  {\n    if((numext::isfinite)(y(i)))\n      VERIFY_IS_APPROX( x(i), y(i) );\n    else if((numext::isnan)(y(i)))\n      VERIFY((numext::isnan)(x(i)));\n    else\n      VERIFY_IS_EQUAL( x(i), y(i) );\n  }\n}\n\ntemplate<typename ArrayType> void array_special_functions()\n{\n  using std::abs;\n  using std::sqrt;\n  typedef typename ArrayType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  Scalar plusinf = std::numeric_limits<Scalar>::infinity();\n  Scalar nan = std::numeric_limits<Scalar>::quiet_NaN();\n\n  Index rows = internal::random<Index>(1,30);\n  Index cols = 1;\n\n  // API\n  {\n    ArrayType m1 = ArrayType::Random(rows,cols);\n#if EIGEN_HAS_C99_MATH\n    VERIFY_IS_APPROX(m1.lgamma(), lgamma(m1));\n    VERIFY_IS_APPROX(m1.digamma(), digamma(m1));\n    VERIFY_IS_APPROX(m1.erf(), erf(m1));\n    VERIFY_IS_APPROX(m1.erfc(), erfc(m1));\n#endif  // EIGEN_HAS_C99_MATH\n  }\n\n\n#if EIGEN_HAS_C99_MATH\n  // check special functions (comparing against numpy implementation)\n  if (!NumTraits<Scalar>::IsComplex)\n  {\n\n    {\n      ArrayType m1 = ArrayType::Random(rows,cols);\n      ArrayType m2 = ArrayType::Random(rows,cols);\n\n      // Test various propreties of igamma & igammac.  These are normalized\n      // gamma integrals where\n      //   igammac(a, x) = Gamma(a, x) / Gamma(a)\n      //   igamma(a, x) = gamma(a, x) / Gamma(a)\n      // where Gamma and gamma are considered the standard unnormalized\n      // upper and lower incomplete gamma functions, respectively.\n      ArrayType a = m1.abs() + Scalar(2);\n      ArrayType x = m2.abs() + Scalar(2);\n      ArrayType zero = ArrayType::Zero(rows, cols);\n      ArrayType one = ArrayType::Constant(rows, cols, Scalar(1.0));\n      ArrayType a_m1 = a - one;\n      ArrayType Gamma_a_x = Eigen::igammac(a, x) * a.lgamma().exp();\n      ArrayType Gamma_a_m1_x = Eigen::igammac(a_m1, x) * a_m1.lgamma().exp();\n      ArrayType gamma_a_x = Eigen::igamma(a, x) * a.lgamma().exp();\n      ArrayType gamma_a_m1_x = Eigen::igamma(a_m1, x) * a_m1.lgamma().exp();\n\n\n      // Gamma(a, 0) == Gamma(a)\n      VERIFY_IS_APPROX(Eigen::igammac(a, zero), one);\n\n      // Gamma(a, x) + gamma(a, x) == Gamma(a)\n      VERIFY_IS_APPROX(Gamma_a_x + gamma_a_x, a.lgamma().exp());\n\n      // Gamma(a, x) == (a - 1) * Gamma(a-1, x) + x^(a-1) * exp(-x)\n      VERIFY_IS_APPROX(Gamma_a_x, (a - Scalar(1)) * Gamma_a_m1_x + x.pow(a-Scalar(1)) * (-x).exp());\n\n      // gamma(a, x) == (a - 1) * gamma(a-1, x) - x^(a-1) * exp(-x)\n      VERIFY_IS_APPROX(gamma_a_x, (a - Scalar(1)) * gamma_a_m1_x - x.pow(a-Scalar(1)) * (-x).exp());\n    }\n    {\n      // Verify for large a and x that values are between 0 and 1.\n      ArrayType m1 = ArrayType::Random(rows,cols);\n      ArrayType m2 = ArrayType::Random(rows,cols);\n      int max_exponent = std::numeric_limits<Scalar>::max_exponent10;\n      ArrayType a = m1.abs() *  Scalar(pow(10., max_exponent - 1));\n      ArrayType x = m2.abs() *  Scalar(pow(10., max_exponent - 1));\n      for (int i = 0; i < a.size(); ++i) {\n        Scalar igam = numext::igamma(a(i), x(i));\n        VERIFY(0 <= igam);\n        VERIFY(igam <= 1);\n      }\n    }\n\n    {\n      // Check exact values of igamma and igammac against a third party calculation.\n      Scalar a_s[] = {Scalar(0), Scalar(1), Scalar(1.5), Scalar(4), Scalar(0.0001), Scalar(1000.5)};\n      Scalar x_s[] = {Scalar(0), Scalar(1), Scalar(1.5), Scalar(4), Scalar(0.0001), Scalar(1000.5)};\n\n      // location i*6+j corresponds to a_s[i], x_s[j].\n      Scalar igamma_s[][6] = {\n          {Scalar(0.0), nan, nan, nan, nan, nan},\n          {Scalar(0.0), Scalar(0.6321205588285578), Scalar(0.7768698398515702),\n           Scalar(0.9816843611112658), Scalar(9.999500016666262e-05),\n           Scalar(1.0)},\n          {Scalar(0.0), Scalar(0.4275932955291202), Scalar(0.608374823728911),\n           Scalar(0.9539882943107686), Scalar(7.522076445089201e-07),\n           Scalar(1.0)},\n          {Scalar(0.0), Scalar(0.01898815687615381),\n           Scalar(0.06564245437845008), Scalar(0.5665298796332909),\n           Scalar(4.166333347221828e-18), Scalar(1.0)},\n          {Scalar(0.0), Scalar(0.9999780593618628), Scalar(0.9999899967080838),\n           Scalar(0.9999996219837988), Scalar(0.9991370418689945), Scalar(1.0)},\n          {Scalar(0.0), Scalar(0.0), Scalar(0.0), Scalar(0.0), Scalar(0.0),\n           Scalar(0.5042041932513908)}};\n      Scalar igammac_s[][6] = {\n          {nan, nan, nan, nan, nan, nan},\n          {Scalar(1.0), Scalar(0.36787944117144233),\n           Scalar(0.22313016014842982), Scalar(0.018315638888734182),\n           Scalar(0.9999000049998333), Scalar(0.0)},\n          {Scalar(1.0), Scalar(0.5724067044708798), Scalar(0.3916251762710878),\n           Scalar(0.04601170568923136), Scalar(0.9999992477923555),\n           Scalar(0.0)},\n          {Scalar(1.0), Scalar(0.9810118431238462), Scalar(0.9343575456215499),\n           Scalar(0.4334701203667089), Scalar(1.0), Scalar(0.0)},\n          {Scalar(1.0), Scalar(2.1940638138146658e-05),\n           Scalar(1.0003291916285e-05), Scalar(3.7801620118431334e-07),\n           Scalar(0.0008629581310054535), Scalar(0.0)},\n          {Scalar(1.0), Scalar(1.0), Scalar(1.0), Scalar(1.0), Scalar(1.0),\n           Scalar(0.49579580674813944)}};\n\n      for (int i = 0; i < 6; ++i) {\n        for (int j = 0; j < 6; ++j) {\n          if ((std::isnan)(igamma_s[i][j])) {\n            VERIFY((std::isnan)(numext::igamma(a_s[i], x_s[j])));\n          } else {\n            VERIFY_IS_APPROX(numext::igamma(a_s[i], x_s[j]), igamma_s[i][j]);\n          }\n\n          if ((std::isnan)(igammac_s[i][j])) {\n            VERIFY((std::isnan)(numext::igammac(a_s[i], x_s[j])));\n          } else {\n            VERIFY_IS_APPROX(numext::igammac(a_s[i], x_s[j]), igammac_s[i][j]);\n          }\n        }\n      }\n    }\n  }\n#endif  // EIGEN_HAS_C99_MATH\n\n  // Check the ndtri function against scipy.special.ndtri\n  {\n    ArrayType x(7), res(7), ref(7);\n    x << 0.5, 0.2, 0.8, 0.9, 0.1, 0.99, 0.01;\n    ref << 0., -0.8416212335729142, 0.8416212335729142, 1.2815515655446004, -1.2815515655446004, 2.3263478740408408, -2.3263478740408408;\n    CALL_SUBTEST( verify_component_wise(ref, ref); );\n    CALL_SUBTEST( res = x.ndtri(); verify_component_wise(res, ref); );\n    CALL_SUBTEST( res = ndtri(x); verify_component_wise(res, ref); );\n\n    // ndtri(normal_cdf(x)) ~= x\n    CALL_SUBTEST(\n        ArrayType m1 = ArrayType::Random(32);\n        using std::sqrt;\n\n        ArrayType cdf_val = (m1 / Scalar(sqrt(2.))).erf();\n        cdf_val = (cdf_val + Scalar(1)) / Scalar(2);\n        verify_component_wise(cdf_val.ndtri(), m1););\n\n  }\n\n  // Check the zeta function against scipy.special.zeta\n  {\n    ArrayType x(10), q(10), res(10), ref(10);\n    x << 1.5,   4, 10.5, 10000.5,    3,      1,    0.9,  2,  3,  4;\n    q <<   2, 1.5,    3,  1.0001, -2.5, 1.2345, 1.2345, -1, -2, -3;\n    ref << 1.61237534869, 0.234848505667, 1.03086757337e-5, 0.367879440865, 0.054102025820864097, plusinf, nan, plusinf, nan, plusinf;\n    CALL_SUBTEST( verify_component_wise(ref, ref); );\n    CALL_SUBTEST( res = x.zeta(q); verify_component_wise(res, ref); );\n    CALL_SUBTEST( res = zeta(x,q); verify_component_wise(res, ref); );\n  }\n\n  // digamma\n  {\n    ArrayType x(9), res(9), ref(9);\n    x << 1, 1.5, 4, -10.5, 10000.5, 0, -1, -2, -3;\n    ref << -0.5772156649015329, 0.03648997397857645, 1.2561176684318, 2.398239129535781, 9.210340372392849, nan, nan, nan, nan;\n    CALL_SUBTEST( verify_component_wise(ref, ref); );\n\n    CALL_SUBTEST( res = x.digamma(); verify_component_wise(res, ref); );\n    CALL_SUBTEST( res = digamma(x);  verify_component_wise(res, ref); );\n  }\n\n#if EIGEN_HAS_C99_MATH\n  {\n    ArrayType n(16), x(16), res(16), ref(16);\n    n << 1, 1,    1, 1.5,   17,   31,   28,    8,   42,  147, 170, -1,  0,  1,  2,  3;\n    x << 2, 3, 25.5, 1.5,  4.7, 11.8, 17.7, 30.2, 15.8, 54.1,  64, -1, -2, -3, -4, -5;\n    ref << 0.644934066848, 0.394934066848, 0.0399946696496, nan, 293.334565435, 0.445487887616, -2.47810300902e-07, -8.29668781082e-09, -0.434562276666, 0.567742190178, -0.0108615497927, nan, nan, plusinf, nan, plusinf;\n    CALL_SUBTEST( verify_component_wise(ref, ref); );\n\n    if(sizeof(RealScalar)>=8) {  // double\n      // Reason for commented line: http://eigen.tuxfamily.org/bz/show_bug.cgi?id=1232\n      //       CALL_SUBTEST( res = x.polygamma(n); verify_component_wise(res, ref); );\n      CALL_SUBTEST( res = polygamma(n,x);  verify_component_wise(res, ref); );\n    }\n    else {\n      //       CALL_SUBTEST( res = x.polygamma(n); verify_component_wise(res.head(8), ref.head(8)); );\n      CALL_SUBTEST( res = polygamma(n,x); verify_component_wise(res.head(8), ref.head(8)); );\n    }\n  }\n#endif\n\n#if EIGEN_HAS_C99_MATH\n  {\n    // Inputs and ground truth generated with scipy via:\n    //   a = np.logspace(-3, 3, 5) - 1e-3\n    //   b = np.logspace(-3, 3, 5) - 1e-3\n    //   x = np.linspace(-0.1, 1.1, 5)\n    //   (full_a, full_b, full_x) = np.vectorize(lambda a, b, x: (a, b, x))(*np.ix_(a, b, x))\n    //   full_a = full_a.flatten().tolist()  # same for full_b, full_x\n    //   v = scipy.special.betainc(full_a, full_b, full_x).flatten().tolist()\n    //\n    // Note in Eigen, we call betainc with arguments in the order (x, a, b).\n    ArrayType a(125);\n    ArrayType b(125);\n    ArrayType x(125);\n    ArrayType v(125);\n    ArrayType res(125);\n\n    a << 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,\n        0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999,\n        0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999,\n        0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 999.999, 999.999, 999.999, 999.999, 999.999, 999.999,\n        999.999, 999.999, 999.999, 999.999, 999.999, 999.999, 999.999, 999.999,\n        999.999, 999.999, 999.999, 999.999, 999.999, 999.999, 999.999, 999.999,\n        999.999, 999.999, 999.999;\n\n    b << 0.0, 0.0, 0.0, 0.0, 0.0, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379, 0.999,\n        0.999, 0.999, 0.999, 0.999, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 31.62177660168379, 999.999,\n        999.999, 999.999, 999.999, 999.999, 0.0, 0.0, 0.0, 0.0, 0.0,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.999, 0.999, 0.999, 0.999,\n        0.999, 31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 999.999, 999.999, 999.999,\n        999.999, 999.999, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.999, 0.999, 0.999, 0.999, 0.999,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 999.999, 999.999, 999.999,\n        999.999, 999.999, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.999, 0.999, 0.999, 0.999, 0.999,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 999.999, 999.999, 999.999,\n        999.999, 999.999, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.999, 0.999, 0.999, 0.999, 0.999,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 999.999, 999.999, 999.999,\n        999.999, 999.999;\n\n    x << -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5,\n        0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2,\n        0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1,\n        0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1,\n        -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8,\n        1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5,\n        0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2,\n        0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1,\n        0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5,\n        0.8, 1.1;\n\n    v << nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan,\n        nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan,\n        nan, nan, nan, 0.47972119876364683, 0.5, 0.5202788012363533, nan, nan,\n        0.9518683957740043, 0.9789663010413743, 0.9931729188073435, nan, nan,\n        0.999995949033062, 0.9999999999993698, 0.9999999999999999, nan, nan,\n        0.9999999999999999, 0.9999999999999999, 0.9999999999999999, nan, nan,\n        nan, nan, nan, nan, nan, 0.006827081192655869, 0.0210336989586256,\n        0.04813160422599567, nan, nan, 0.20014344256217678, 0.5000000000000001,\n        0.7998565574378232, nan, nan, 0.9991401428435834, 0.999999999698403,\n        0.9999999999999999, nan, nan, 0.9999999999999999, 0.9999999999999999,\n        0.9999999999999999, nan, nan, nan, nan, nan, nan, nan,\n        1.0646600232370887e-25, 6.301722877826246e-13, 4.050966937974938e-06,\n        nan, nan, 7.864342668429763e-23, 3.015969667594166e-10,\n        0.0008598571564165444, nan, nan, 6.031987710123844e-08,\n        0.5000000000000007, 0.9999999396801229, nan, nan, 0.9999999999999999,\n        0.9999999999999999, 0.9999999999999999, nan, nan, nan, nan, nan, nan,\n        nan, 0.0, 7.029920380986636e-306, 2.2450728208591345e-101, nan, nan,\n        0.0, 9.275871147869727e-302, 1.2232913026152827e-97, nan, nan, 0.0,\n        3.0891393081932924e-252, 2.9303043666183996e-60, nan, nan,\n        2.248913486879199e-196, 0.5000000000004947, 0.9999999999999999, nan;\n\n    CALL_SUBTEST(res = betainc(a, b, x);\n                 verify_component_wise(res, v););\n  }\n\n  // Test various properties of betainc\n  {\n    ArrayType m1 = ArrayType::Random(32);\n    ArrayType m2 = ArrayType::Random(32);\n    ArrayType m3 = ArrayType::Random(32);\n    ArrayType one = ArrayType::Constant(32, Scalar(1.0));\n    const Scalar eps = std::numeric_limits<Scalar>::epsilon();\n    ArrayType a = (m1 * Scalar(4)).exp();\n    ArrayType b = (m2 * Scalar(4)).exp();\n    ArrayType x = m3.abs();\n\n    // betainc(a, 1, x) == x**a\n    CALL_SUBTEST(\n        ArrayType test = betainc(a, one, x);\n        ArrayType expected = x.pow(a);\n        verify_component_wise(test, expected););\n\n    // betainc(1, b, x) == 1 - (1 - x)**b\n    CALL_SUBTEST(\n        ArrayType test = betainc(one, b, x);\n        ArrayType expected = one - (one - x).pow(b);\n        verify_component_wise(test, expected););\n\n    // betainc(a, b, x) == 1 - betainc(b, a, 1-x)\n    CALL_SUBTEST(\n        ArrayType test = betainc(a, b, x) + betainc(b, a, one - x);\n        ArrayType expected = one;\n        verify_component_wise(test, expected););\n\n    // betainc(a+1, b, x) = betainc(a, b, x) - x**a * (1 - x)**b / (a * beta(a, b))\n    CALL_SUBTEST(\n        ArrayType num = x.pow(a) * (one - x).pow(b);\n        ArrayType denom = a * (a.lgamma() + b.lgamma() - (a + b).lgamma()).exp();\n        // Add eps to rhs and lhs so that component-wise test doesn't result in\n        // nans when both outputs are zeros.\n        ArrayType expected = betainc(a, b, x) - num / denom + eps;\n        ArrayType test = betainc(a + one, b, x) + eps;\n        if (sizeof(Scalar) >= 8) { // double\n          verify_component_wise(test, expected);\n        } else {\n          // Reason for limited test: http://eigen.tuxfamily.org/bz/show_bug.cgi?id=1232\n          verify_component_wise(test.head(8), expected.head(8));\n        });\n\n    // betainc(a, b+1, x) = betainc(a, b, x) + x**a * (1 - x)**b / (b * beta(a, b))\n    CALL_SUBTEST(\n        // Add eps to rhs and lhs so that component-wise test doesn't result in\n        // nans when both outputs are zeros.\n        ArrayType num = x.pow(a) * (one - x).pow(b);\n        ArrayType denom = b * (a.lgamma() + b.lgamma() - (a + b).lgamma()).exp();\n        ArrayType expected = betainc(a, b, x) + num / denom + eps;\n        ArrayType test = betainc(a, b + one, x) + eps;\n        verify_component_wise(test, expected););\n  }\n#endif  // EIGEN_HAS_C99_MATH\n\n    /* Code to generate the data for the following two test cases.\n    N = 5\n    np.random.seed(3)\n\n    a = np.logspace(-2, 3, 6)\n    a = np.ravel(np.tile(np.reshape(a, [-1, 1]), [1, N]))\n    x = np.random.gamma(a, 1.0)\n    x = np.maximum(x, np.finfo(np.float32).tiny)\n\n    def igamma(a, x):\n      return mpmath.gammainc(a, 0, x, regularized=True)\n\n    def igamma_der_a(a, x):\n      res = mpmath.diff(lambda a_prime: igamma(a_prime, x), a)\n      return np.float64(res)\n\n    def gamma_sample_der_alpha(a, x):\n      igamma_x = igamma(a, x)\n      def igammainv_of_igamma(a_prime):\n        return mpmath.findroot(lambda x_prime: igamma(a_prime, x_prime) -\n            igamma_x, x, solver='newton')\n      return np.float64(mpmath.diff(igammainv_of_igamma, a))\n\n    v_igamma_der_a = np.vectorize(igamma_der_a)(a, x)\n    v_gamma_sample_der_alpha = np.vectorize(gamma_sample_der_alpha)(a, x)\n  */\n\n#if EIGEN_HAS_C99_MATH\n  // Test igamma_der_a\n  {\n    ArrayType a(30);\n    ArrayType x(30);\n    ArrayType res(30);\n    ArrayType v(30);\n\n    a << 0.01, 0.01, 0.01, 0.01, 0.01, 0.1, 0.1, 0.1, 0.1, 0.1, 1.0, 1.0, 1.0,\n        1.0, 1.0, 10.0, 10.0, 10.0, 10.0, 10.0, 100.0, 100.0, 100.0, 100.0,\n        100.0, 1000.0, 1000.0, 1000.0, 1000.0, 1000.0;\n\n    x << 1.25668890405e-26, 1.17549435082e-38, 1.20938905072e-05,\n        1.17549435082e-38, 1.17549435082e-38, 5.66572070696e-16,\n        0.0132865061065, 0.0200034203853, 6.29263709118e-17, 1.37160367764e-06,\n        0.333412038288, 1.18135687766, 0.580629033777, 0.170631439426,\n        0.786686768458, 7.63873279537, 13.1944344379, 11.896042354,\n        10.5830172417, 10.5020942233, 92.8918587747, 95.003720371,\n        86.3715926467, 96.0330217672, 82.6389930677, 968.702906754,\n        969.463546828, 1001.79726022, 955.047416547, 1044.27458568;\n\n    v << -32.7256441441, -36.4394150514, -9.66467612263, -36.4394150514,\n        -36.4394150514, -1.0891900302, -2.66351229645, -2.48666868596,\n        -0.929700494428, -3.56327722764, -0.455320135314, -0.391437214323,\n        -0.491352055991, -0.350454834292, -0.471773162921, -0.104084440522,\n        -0.0723646747909, -0.0992828975532, -0.121638215446, -0.122619605294,\n        -0.0317670267286, -0.0359974812869, -0.0154359225363, -0.0375775365921,\n        -0.00794899153653, -0.00777303219211, -0.00796085782042,\n        -0.0125850719397, -0.00455500206958, -0.00476436993148;\n\n    CALL_SUBTEST(res = igamma_der_a(a, x); verify_component_wise(res, v););\n  }\n\n  // Test gamma_sample_der_alpha\n  {\n    ArrayType alpha(30);\n    ArrayType sample(30);\n    ArrayType res(30);\n    ArrayType v(30);\n\n    alpha << 0.01, 0.01, 0.01, 0.01, 0.01, 0.1, 0.1, 0.1, 0.1, 0.1, 1.0, 1.0,\n        1.0, 1.0, 1.0, 10.0, 10.0, 10.0, 10.0, 10.0, 100.0, 100.0, 100.0, 100.0,\n        100.0, 1000.0, 1000.0, 1000.0, 1000.0, 1000.0;\n\n    sample << 1.25668890405e-26, 1.17549435082e-38, 1.20938905072e-05,\n        1.17549435082e-38, 1.17549435082e-38, 5.66572070696e-16,\n        0.0132865061065, 0.0200034203853, 6.29263709118e-17, 1.37160367764e-06,\n        0.333412038288, 1.18135687766, 0.580629033777, 0.170631439426,\n        0.786686768458, 7.63873279537, 13.1944344379, 11.896042354,\n        10.5830172417, 10.5020942233, 92.8918587747, 95.003720371,\n        86.3715926467, 96.0330217672, 82.6389930677, 968.702906754,\n        969.463546828, 1001.79726022, 955.047416547, 1044.27458568;\n\n    v << 7.42424742367e-23, 1.02004297287e-34, 0.0130155240738,\n        1.02004297287e-34, 1.02004297287e-34, 1.96505168277e-13, 0.525575786243,\n        0.713903991771, 2.32077561808e-14, 0.000179348049886, 0.635500453302,\n        1.27561284917, 0.878125852156, 0.41565819538, 1.03606488534,\n        0.885964824887, 1.16424049334, 1.10764479598, 1.04590810812,\n        1.04193666963, 0.965193152414, 0.976217589464, 0.93008035061,\n        0.98153216096, 0.909196397698, 0.98434963993, 0.984738050206,\n        1.00106492525, 0.97734200649, 1.02198794179;\n\n    CALL_SUBTEST(res = gamma_sample_der_alpha(alpha, sample);\n                 verify_component_wise(res, v););\n  }\n#endif  // EIGEN_HAS_C99_MATH\n}\n\nEIGEN_DECLARE_TEST(special_functions)\n{\n  CALL_SUBTEST_1(array_special_functions<ArrayXf>());\n  CALL_SUBTEST_2(array_special_functions<ArrayXd>());\n  // TODO(cantonios): half/bfloat16 don't have enough precision to reproduce results above.\n  // CALL_SUBTEST_3(array_special_functions<ArrayX<Eigen::half>>());\n  // CALL_SUBTEST_4(array_special_functions<ArrayX<Eigen::bfloat16>>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/special_packetmath.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <limits>\n#include \"packetmath_test_shared.h\"\n#include \"../Eigen/SpecialFunctions\"\n\ntemplate<typename Scalar,typename Packet> void packetmath_real()\n{\n  using std::abs;\n  typedef internal::packet_traits<Scalar> PacketTraits;\n  const int PacketSize = internal::unpacket_traits<Packet>::size;\n\n  const int size = PacketSize*4;\n  EIGEN_ALIGN_MAX Scalar data1[PacketSize*4];\n  EIGEN_ALIGN_MAX Scalar data2[PacketSize*4];\n  EIGEN_ALIGN_MAX Scalar ref[PacketSize*4];\n\n#if EIGEN_HAS_C99_MATH\n  {\n    data1[0] = std::numeric_limits<Scalar>::quiet_NaN();\n    test::packet_helper<internal::packet_traits<Scalar>::HasLGamma,Packet> h;\n    h.store(data2, internal::plgamma(h.load(data1)));\n    VERIFY((numext::isnan)(data2[0]));\n  }\n  if (internal::packet_traits<Scalar>::HasErf) {\n    data1[0] = std::numeric_limits<Scalar>::quiet_NaN();\n    test::packet_helper<internal::packet_traits<Scalar>::HasErf,Packet> h;\n    h.store(data2, internal::perf(h.load(data1)));\n    VERIFY((numext::isnan)(data2[0]));\n  }\n  {\n    data1[0] = std::numeric_limits<Scalar>::quiet_NaN();\n    test::packet_helper<internal::packet_traits<Scalar>::HasErfc,Packet> h;\n    h.store(data2, internal::perfc(h.load(data1)));\n    VERIFY((numext::isnan)(data2[0]));\n  }\n  {\n    for (int i=0; i<size; ++i) {\n      data1[i] = internal::random<Scalar>(Scalar(0),Scalar(1));\n    }\n    CHECK_CWISE1_IF(internal::packet_traits<Scalar>::HasNdtri, numext::ndtri, internal::pndtri);\n  }\n#endif  // EIGEN_HAS_C99_MATH\n\n  // For bessel_i*e and bessel_j*, the valid range is negative reals.\n  {\n    const int max_exponent = numext::mini(std::numeric_limits<Scalar>::max_exponent10-1, 6);\n    for (int i=0; i<size; ++i)\n    {\n      data1[i] = internal::random<Scalar>(Scalar(-1),Scalar(1)) * Scalar(std::pow(Scalar(10), internal::random<Scalar>(Scalar(-max_exponent),Scalar(max_exponent))));\n      data2[i] = internal::random<Scalar>(Scalar(-1),Scalar(1)) * Scalar(std::pow(Scalar(10), internal::random<Scalar>(Scalar(-max_exponent),Scalar(max_exponent))));\n    }\n\n    CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_i0e, internal::pbessel_i0e);\n    CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_i1e, internal::pbessel_i1e);\n    CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_j0, internal::pbessel_j0);\n    CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_j1, internal::pbessel_j1);\n  }\n\n  // Use a smaller data range for the bessel_i* as these can become very large.\n  // Following #1693, we also restrict this range further to avoid inf's due to\n  // differences in pexp and exp.\n  for (int i=0; i<size; ++i) {\n      data1[i] = internal::random<Scalar>(Scalar(0.01),Scalar(1)) *\n                  Scalar(std::pow(Scalar(9), internal::random<Scalar>(Scalar(-1),Scalar(2))));\n      data2[i] = internal::random<Scalar>(Scalar(0.01),Scalar(1)) *\n                  Scalar(std::pow(Scalar(9), internal::random<Scalar>(Scalar(-1),Scalar(2))));\n  }\n  CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_i0, internal::pbessel_i0);\n  CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_i1, internal::pbessel_i1);\n\n\n  // y_i, and k_i are valid for x > 0.\n  {\n    const int max_exponent = numext::mini(std::numeric_limits<Scalar>::max_exponent10-1, 5);\n    for (int i=0; i<size; ++i)\n    {\n      data1[i] = internal::random<Scalar>(Scalar(0.01),Scalar(1)) * Scalar(std::pow(Scalar(10), internal::random<Scalar>(Scalar(-2),Scalar(max_exponent))));\n      data2[i] = internal::random<Scalar>(Scalar(0.01),Scalar(1)) * Scalar(std::pow(Scalar(10), internal::random<Scalar>(Scalar(-2),Scalar(max_exponent))));\n    }\n  }\n\n  // TODO(srvasude): Re-enable this test once properly investigated why the\n  // scalar and vector paths differ.\n  // CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_y0, internal::pbessel_y0);\n  CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_y1, internal::pbessel_y1);\n  CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_k0e, internal::pbessel_k0e);\n  CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_k1e, internal::pbessel_k1e);\n\n  // Following #1693, we restrict the range for exp to avoid zeroing out too\n  // fast.\n  for (int i=0; i<size; ++i) {\n      data1[i] = internal::random<Scalar>(Scalar(0.01),Scalar(1)) *\n                  Scalar(std::pow(Scalar(9), internal::random<Scalar>(Scalar(-1),Scalar(2))));\n      data2[i] = internal::random<Scalar>(Scalar(0.01),Scalar(1)) *\n                  Scalar(std::pow(Scalar(9), internal::random<Scalar>(Scalar(-1),Scalar(2))));\n  }\n  CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_k0, internal::pbessel_k0);\n  CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_k1, internal::pbessel_k1);\n\n\n  for (int i=0; i<size; ++i) {\n      data1[i] = internal::random<Scalar>(Scalar(0.01),Scalar(1)) *\n                  Scalar(std::pow(Scalar(10), internal::random<Scalar>(Scalar(-1),Scalar(2))));\n      data2[i] = internal::random<Scalar>(Scalar(0.01),Scalar(1)) *\n                  Scalar(std::pow(Scalar(10), internal::random<Scalar>(Scalar(-1),Scalar(2))));\n  }\n\n#if EIGEN_HAS_C99_MATH && (EIGEN_COMP_CXXVER >= 11)\n  CHECK_CWISE1_IF(internal::packet_traits<Scalar>::HasLGamma, std::lgamma, internal::plgamma);\n  CHECK_CWISE1_IF(internal::packet_traits<Scalar>::HasErf, std::erf, internal::perf);\n  CHECK_CWISE1_IF(internal::packet_traits<Scalar>::HasErfc, std::erfc, internal::perfc);\n#endif\n\n}\n\nnamespace Eigen {\nnamespace test {\n\ntemplate<typename Scalar,typename PacketType, bool IsComplex, bool IsInteger>\nstruct runall {\n  static void run() {\n    packetmath_real<Scalar,PacketType>();\n  }\n};\n\n}\n}\n\nEIGEN_DECLARE_TEST(special_packetmath)\n{\n  g_first_pass = true;\n  for(int i = 0; i < g_repeat; i++) {\n\n    CALL_SUBTEST_1( test::runner<float>::run() );\n    CALL_SUBTEST_2( test::runner<double>::run() );\n    CALL_SUBTEST_3( test::runner<Eigen::half>::run() );\n    CALL_SUBTEST_4( test::runner<Eigen::bfloat16>::run() );\n    g_first_pass = false;\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/eigen/unsupported/test/splines.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010-2011 Hauke Heibel <heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <unsupported/Eigen/Splines>\n\nnamespace Eigen {\n  \n  // lets do some explicit instantiations and thus\n  // force the compilation of all spline functions...\n  template class Spline<double, 2, Dynamic>;\n  template class Spline<double, 3, Dynamic>;\n\n  template class Spline<double, 2, 2>;\n  template class Spline<double, 2, 3>;\n  template class Spline<double, 2, 4>;\n  template class Spline<double, 2, 5>;\n\n  template class Spline<float, 2, Dynamic>;\n  template class Spline<float, 3, Dynamic>;\n\n  template class Spline<float, 3, 2>;\n  template class Spline<float, 3, 3>;\n  template class Spline<float, 3, 4>;\n  template class Spline<float, 3, 5>;\n\n}\n\nSpline<double, 2, Dynamic> closed_spline2d()\n{\n  RowVectorXd knots(12);\n  knots << 0,\n    0,\n    0,\n    0,\n    0.867193179093898,\n    1.660330955342408,\n    2.605084834823134,\n    3.484154586374428,\n    4.252699478956276,\n    4.252699478956276,\n    4.252699478956276,\n    4.252699478956276;\n\n  MatrixXd ctrls(8,2);\n  ctrls << -0.370967741935484,   0.236842105263158,\n    -0.231401860693277,   0.442245185027632,\n    0.344361228532831,   0.773369994120753,\n    0.828990216203802,   0.106550882647595,\n    0.407270163678382,  -1.043452922172848,\n    -0.488467813584053,  -0.390098582530090,\n    -0.494657189446427,   0.054804824897884,\n    -0.370967741935484,   0.236842105263158;\n  ctrls.transposeInPlace();\n\n  return Spline<double, 2, Dynamic>(knots, ctrls);\n}\n\n/* create a reference spline */\nSpline<double, 3, Dynamic> spline3d()\n{\n  RowVectorXd knots(11);\n  knots << 0,\n    0,\n    0,\n    0.118997681558377,\n    0.162611735194631,\n    0.498364051982143,\n    0.655098003973841,\n    0.679702676853675,\n    1.000000000000000,\n    1.000000000000000,\n    1.000000000000000;\n\n  MatrixXd ctrls(8,3);\n  ctrls <<    0.959743958516081,   0.340385726666133,   0.585267750979777,\n    0.223811939491137,   0.751267059305653,   0.255095115459269,\n    0.505957051665142,   0.699076722656686,   0.890903252535799,\n    0.959291425205444,   0.547215529963803,   0.138624442828679,\n    0.149294005559057,   0.257508254123736,   0.840717255983663,\n    0.254282178971531,   0.814284826068816,   0.243524968724989,\n    0.929263623187228,   0.349983765984809,   0.196595250431208,\n    0.251083857976031,   0.616044676146639,   0.473288848902729;\n  ctrls.transposeInPlace();\n\n  return Spline<double, 3, Dynamic>(knots, ctrls);\n}\n\n/* compares evaluations against known results */\nvoid eval_spline3d()\n{\n  Spline3d spline = spline3d();\n\n  RowVectorXd u(10);\n  u << 0.351659507062997,\n    0.830828627896291,\n    0.585264091152724,\n    0.549723608291140,\n    0.917193663829810,\n    0.285839018820374,\n    0.757200229110721,\n    0.753729094278495,\n    0.380445846975357,\n    0.567821640725221;\n\n  MatrixXd pts(10,3);\n  pts << 0.707620811535916,   0.510258911240815,   0.417485437023409,\n    0.603422256426978,   0.529498282727551,   0.270351549348981,\n    0.228364197569334,   0.423745615677815,   0.637687289287490,\n    0.275556796335168,   0.350856706427970,   0.684295784598905,\n    0.514519311047655,   0.525077224890754,   0.351628308305896,\n    0.724152914315666,   0.574461155457304,   0.469860285484058,\n    0.529365063753288,   0.613328702656816,   0.237837040141739,\n    0.522469395136878,   0.619099658652895,   0.237139665242069,\n    0.677357023849552,   0.480655768435853,   0.422227610314397,\n    0.247046593173758,   0.380604672404750,   0.670065791405019;\n  pts.transposeInPlace();\n\n  for (int i=0; i<u.size(); ++i)\n  {\n    Vector3d pt = spline(u(i));\n    VERIFY( (pt - pts.col(i)).norm() < 1e-14 );\n  }\n}\n\n/* compares evaluations on corner cases */\nvoid eval_spline3d_onbrks()\n{\n  Spline3d spline = spline3d();\n\n  RowVectorXd u = spline.knots();\n\n  MatrixXd pts(11,3);\n  pts <<    0.959743958516081,   0.340385726666133,   0.585267750979777,\n    0.959743958516081,   0.340385726666133,   0.585267750979777,\n    0.959743958516081,   0.340385726666133,   0.585267750979777,\n    0.430282980289940,   0.713074680056118,   0.720373307943349,\n    0.558074875553060,   0.681617921034459,   0.804417124839942,\n    0.407076008291750,   0.349707710518163,   0.617275937419545,\n    0.240037008286602,   0.738739390398014,   0.324554153129411,\n    0.302434111480572,   0.781162443963899,   0.240177089094644,\n    0.251083857976031,   0.616044676146639,   0.473288848902729,\n    0.251083857976031,   0.616044676146639,   0.473288848902729,\n    0.251083857976031,   0.616044676146639,   0.473288848902729;\n  pts.transposeInPlace();\n\n  for (int i=0; i<u.size(); ++i)\n  {\n    Vector3d pt = spline(u(i));\n    VERIFY( (pt - pts.col(i)).norm() < 1e-14 );\n  }\n}\n\nvoid eval_closed_spline2d()\n{\n  Spline2d spline = closed_spline2d();\n\n  RowVectorXd u(12);\n  u << 0,\n    0.332457030395796,\n    0.356467130532952,\n    0.453562180176215,\n    0.648017921874804,\n    0.973770235555003,\n    1.882577647219307,\n    2.289408593930498,\n    3.511951429883045,\n    3.884149321369450,\n    4.236261590369414,\n    4.252699478956276;\n\n  MatrixXd pts(12,2);\n  pts << -0.370967741935484,   0.236842105263158,\n    -0.152576775123250,   0.448975001279334,\n    -0.133417538277668,   0.461615613865667,\n    -0.053199060826740,   0.507630360006299,\n    0.114249591147281,   0.570414135097409,\n    0.377810316891987,   0.560497102875315,\n    0.665052120135908,  -0.157557441109611,\n    0.516006487053228,  -0.559763292174825,\n    -0.379486035348887,  -0.331959640488223,\n    -0.462034726249078,  -0.039105670080824,\n    -0.378730600917982,   0.225127015099919,\n    -0.370967741935484,   0.236842105263158;\n  pts.transposeInPlace();\n\n  for (int i=0; i<u.size(); ++i)\n  {\n    Vector2d pt = spline(u(i));\n    VERIFY( (pt - pts.col(i)).norm() < 1e-14 );\n  }\n}\n\nvoid check_global_interpolation2d()\n{\n  typedef Spline2d::PointType PointType;\n  typedef Spline2d::KnotVectorType KnotVectorType;\n  typedef Spline2d::ControlPointVectorType ControlPointVectorType;\n\n  ControlPointVectorType points = ControlPointVectorType::Random(2,100);\n\n  KnotVectorType chord_lengths; // knot parameters\n  Eigen::ChordLengths(points, chord_lengths);\n\n  // interpolation without knot parameters\n  {\n    const Spline2d spline = SplineFitting<Spline2d>::Interpolate(points,3);  \n\n    for (Eigen::DenseIndex i=0; i<points.cols(); ++i)\n    {\n      PointType pt = spline( chord_lengths(i) );\n      PointType ref = points.col(i);\n      VERIFY( (pt - ref).matrix().norm() < 1e-14 );\n    }\n  }\n\n  // interpolation with given knot parameters\n  {\n    const Spline2d spline = SplineFitting<Spline2d>::Interpolate(points,3,chord_lengths);  \n\n    for (Eigen::DenseIndex i=0; i<points.cols(); ++i)\n    {\n      PointType pt = spline( chord_lengths(i) );\n      PointType ref = points.col(i);\n      VERIFY( (pt - ref).matrix().norm() < 1e-14 );\n    }\n  }\n}\n\nvoid check_global_interpolation_with_derivatives2d()\n{\n  typedef Spline2d::PointType PointType;\n  typedef Spline2d::KnotVectorType KnotVectorType;\n\n  const Eigen::DenseIndex numPoints = 100;\n  const unsigned int dimension = 2;\n  const unsigned int degree = 3;\n\n  ArrayXXd points = ArrayXXd::Random(dimension, numPoints);\n\n  KnotVectorType knots;\n  Eigen::ChordLengths(points, knots);\n\n  ArrayXXd derivatives = ArrayXXd::Random(dimension, numPoints);\n  VectorXd derivativeIndices(numPoints);\n\n  for (Eigen::DenseIndex i = 0; i < numPoints; ++i)\n      derivativeIndices(i) = static_cast<double>(i);\n\n  const Spline2d spline = SplineFitting<Spline2d>::InterpolateWithDerivatives(\n    points, derivatives, derivativeIndices, degree);  \n    \n  for (Eigen::DenseIndex i = 0; i < points.cols(); ++i)\n  {\n    PointType point = spline(knots(i));\n    PointType referencePoint = points.col(i);\n    VERIFY_IS_APPROX(point, referencePoint);\n    PointType derivative = spline.derivatives(knots(i), 1).col(1);\n    PointType referenceDerivative = derivatives.col(i);\n    VERIFY_IS_APPROX(derivative, referenceDerivative);\n  }\n}\n\nEIGEN_DECLARE_TEST(splines)\n{\n  for (int i = 0; i < g_repeat; ++i)\n  {\n    CALL_SUBTEST( eval_spline3d() );\n    CALL_SUBTEST( eval_spline3d_onbrks() );\n    CALL_SUBTEST( eval_closed_spline2d() );\n    CALL_SUBTEST( check_global_interpolation2d() );\n    CALL_SUBTEST( check_global_interpolation_with_derivatives2d() );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/.gitignore",
    "content": "__pycache__\nbuild\ndist\n*.egg-info\n*.vscode/\n*.pth\ntests\ncheckpoints\ndatasets\nruns\na.out\ncache\n*.g2o\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/.gitmodules",
    "content": "[submodule \"eigen\"]\n\tpath = eigen\n\turl = https://gitlab.com/libeigen/eigen.git\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/LICENSE",
    "content": "BSD 3-Clause License\n\nCopyright (c) 2021, princeton-vl\nAll rights reserved.\n\nRedistribution and use in source and binary forms, with or without\nmodification, are permitted provided that the following conditions are met:\n\n* Redistributions of source code must retain the above copyright notice, this\n  list of conditions and the following disclaimer.\n\n* Redistributions in binary form must reproduce the above copyright notice,\n  this list of conditions and the following disclaimer in the documentation\n  and/or other materials provided with the distribution.\n\n* Neither the name of the copyright holder nor the names of its\n  contributors may be used to endorse or promote products derived from\n  this software without specific prior written permission.\n\nTHIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\"\nAND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\nIMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\nDISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE\nFOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL\nDAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR\nSERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\nCAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,\nOR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE\nOF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/README.md",
    "content": "# LieTorch: Tangent Space Backpropagation\n\n\n## Introduction\n\nThe LieTorch library generalizes PyTorch to 3D transformation groups. Just as `torch.Tensor` is a multi-dimensional matrix of scalar elements, `lietorch.SE3` is a multi-dimensional matrix of SE3 elements. We support common tensor manipulations such as indexing, reshaping, and broadcasting. Group operations can be composed into computation graphs and backpropagation is automatically peformed in the tangent space of each element. For more details, please see our paper:\n\n<center><img src=\"lietorch.png\" width=\"480\" style=\"center\"></center>\n\n[Tangent Space Backpropagation for 3D Transformation Groups](https://arxiv.org/pdf/2103.12032.pdf)  \nZachary Teed and Jia Deng, CVPR 2021\n\n```\n@inproceedings{teed2021tangent,\n  title={Tangent Space Backpropagation for 3D Transformation Groups},\n  author={Teed, Zachary and Deng, Jia},\n  booktitle={Proceedings of the IEEE/CVF Conference on Computer Vision and Pattern Recognition (CVPR)},\n  year={2021},\n}\n```\n\n\n## Installation\n\n\n### Requirements: \n * Cuda >= 10.1 (with nvcc compiler)\n * PyTorch >= 1.8\n\nWe recommend installing within a virtual enviornment. Make sure you clone using the `--recursive` flag. If you are using Anaconda, the following command can be used to install all dependencies\n```\ngit clone --recursive https://github.com/princeton-vl/lietorch.git\ncd lietorch\n\nconda create -n lie_env\nconda activate lie_env\nconda install scipy pyyaml pytorch torchvision torchaudio cudatoolkit=10.2 -c pytorch\n```\n\nTo run the examples, you will need OpenCV and Open3D. Depending on your operating system, OpenCV and Open3D can either be installed with pip or may need to be built from source\n```\npip install opencv-python open3d\n```\n\n### Installing (from source)\n\nClone the repo using the `--recursive` flag and install using `setup.py` (may take up to 10 minutes)\n```\ngit clone --recursive https://github.com/princeton-vl/lietorch.git\npython setup.py install\n./run_tests.sh\n```\n\n### Installing (pip)\nYou can install the library directly using pip\n```bash\npip install git+https://github.com/princeton-vl/lietorch.git\n```\n\n\n\n## Overview\n\nLieTorch currently supports the 3D transformation groups. \n\n| Group  | Dimension | Action |\n| -------| --------- | ------------- |\n| SO3    | 3  | rotation |\n| RxSO3  | 4  | rotation + scaling |\n| SE3    | 6  | rotation + translation |\n| Sim3   | 7  | rotation + translation + scaling |\n\nEach group supports the following differentiable operations:\n\n| Operation | Map | Description |\n| -------| --------| ------------- |\n| exp    | g -> G | exponential map |\n| log    | G -> g | logarithm map |\n| inv    | G -> G | group inverse |\n| mul   | G x G -> G | group multiplication |\n| adj    | G x g -> g | adjoint |\n| adjT   | G x g*-> g* | dual adjoint |\n| act    | G x R^3 -> R^3 | action on point (set) |\n| act4   | G x P^3 -> P^3 | action on homogeneous point (set) |\n| matrix | G -> R^{4x4} | convert to 4x4 matrix\n| vec    | G -> R^D | map to Euclidean embedding vector |\n| InitFromVec | R^D -> G | initialize group from Euclidean embedding\n\n\n\n&nbsp;\n### Simple Example:\nCompute the angles between all pairs of rotation matrices\n\n```python\nimport torch\nfrom lietorch import SO3\n\nphi = torch.randn(8000, 3, device='cuda', requires_grad=True)\nR = SO3.exp(phi)\n\n# relative rotation matrix, SO3 ^ {8000 x 8000}\ndR = R[:,None].inv() * R[None,:]\n\n# 8000x8000 matrix of angles\nang = dR.log().norm(dim=-1)\n\n# backpropogation in tangent space\nloss = ang.sum()\nloss.backward()\n```\n\n\n### Converting between Groups Elements and Euclidean Embeddings\nWe provide differentiable `FromVec` and `ToVec` functions which can be used to convert between LieGroup elements and their vector embeddings. Additional, the `.matrix` function returns a 4x4 transformation matrix.\n```python\n\n# random quaternion\nq = torch.randn(1, 4, requires_grad=True)\nq = q / q.norm(dim=-1, keepdim=True)\n\n# create SO3 object from quaternion (differentiable w.r.t q)\nR = SO3.InitFromVec(q)\n\n# 4x4 transformation matrix (differentiable w.r.t R)\nT = R.matrix()\n\n# map back to quaterion (differentiable w.r.t R)\nq = R.vec()\n\n```\n\n\n## Examples\nWe provide real use cases in the examples directory\n1. Pose Graph Optimization\n2. Deep SE3/Sim3 Registrtion\n3. RGB-D SLAM / VO\n\n### Acknowledgements\nMany of the Lie Group implementations are adapted from [Sophus](https://github.com/strasdat/Sophus). \n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/.gitignore",
    "content": "qrc_*cxx\n*.orig\n*.pyc\n*.diff\ndiff\n*.save\nsave\n*.old\n*.gmo\n*.qm\ncore\ncore.*\n*.bak\n*~\n*build*\n*.moc.*\n*.moc\nui_*\nCMakeCache.txt\ntags\n.*.swp\nactivity.png\n*.out\n*.php*\n*.log\n*.orig\n*.rej\nlog\npatch\n*.patch\na\na.*\nlapack/testing\nlapack/reference\n.*project\n.settings\nMakefile\n!ci/build.gitlab-ci.yml\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/.gitlab-ci.yml",
    "content": "# This file is part of Eigen, a lightweight C++ template library\n# for linear algebra.\n#\n# Copyright (C) 2020 Arm Ltd. and Contributors\n#\n# This Source Code Form is subject to the terms of the Mozilla\n# Public License v. 2.0. If a copy of the MPL was not distributed\n# with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\nstages:\n  - build\n  - test\n\nvariables:\n  BUILDDIR: builddir\n  EIGEN_CI_CMAKE_GENEATOR: \"Ninja\"\n\ninclude:\n  - \"/ci/build.gitlab-ci.yml\"\n  - \"/ci/test.gitlab-ci.yml\"\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/.hgeol",
    "content": "[patterns]\n*.sh = LF\n*.MINPACK = CRLF\nscripts/*.in = LF\ndebug/msvc/*.dat = CRLF\ndebug/msvc/*.natvis = CRLF\nunsupported/test/mpreal/*.* = CRLF\n** = native\n\n[repository]\nnative = LF\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/CMakeLists.txt",
    "content": "# cmake_minimum_require must be the first command of the file\ncmake_minimum_required(VERSION 3.5.0)\n\nproject(Eigen3)\n\n# guard against in-source builds\n\nif(${CMAKE_SOURCE_DIR} STREQUAL ${CMAKE_BINARY_DIR})\n  message(FATAL_ERROR \"In-source builds not allowed. Please make a new directory (called a build directory) and run CMake from there. You may need to remove CMakeCache.txt. \")\nendif()\n\n\n# Alias Eigen_*_DIR to Eigen3_*_DIR:\n\nset(Eigen_SOURCE_DIR ${Eigen3_SOURCE_DIR})\nset(Eigen_BINARY_DIR ${Eigen3_BINARY_DIR})\n\n# guard against bad build-type strings\n\nif (NOT CMAKE_BUILD_TYPE)\n  set(CMAKE_BUILD_TYPE \"Release\")\nendif()\n\n\n#############################################################################\n# retrieve version information                                               #\n#############################################################################\n\n# automatically parse the version number\nfile(READ \"${PROJECT_SOURCE_DIR}/Eigen/src/Core/util/Macros.h\" _eigen_version_header)\nstring(REGEX MATCH \"define[ \\t]+EIGEN_WORLD_VERSION[ \\t]+([0-9]+)\" _eigen_world_version_match \"${_eigen_version_header}\")\nset(EIGEN_WORLD_VERSION \"${CMAKE_MATCH_1}\")\nstring(REGEX MATCH \"define[ \\t]+EIGEN_MAJOR_VERSION[ \\t]+([0-9]+)\" _eigen_major_version_match \"${_eigen_version_header}\")\nset(EIGEN_MAJOR_VERSION \"${CMAKE_MATCH_1}\")\nstring(REGEX MATCH \"define[ \\t]+EIGEN_MINOR_VERSION[ \\t]+([0-9]+)\" _eigen_minor_version_match \"${_eigen_version_header}\")\nset(EIGEN_MINOR_VERSION \"${CMAKE_MATCH_1}\")\nset(EIGEN_VERSION_NUMBER ${EIGEN_WORLD_VERSION}.${EIGEN_MAJOR_VERSION}.${EIGEN_MINOR_VERSION})\n\n# if we are not in a git clone\nif(IS_DIRECTORY ${CMAKE_SOURCE_DIR}/.git)\n  # if the git program is absent or this will leave the EIGEN_GIT_REVNUM string empty,\n  # but won't stop CMake.\n  execute_process(COMMAND git ls-remote --refs -q ${CMAKE_SOURCE_DIR} HEAD OUTPUT_VARIABLE EIGEN_GIT_OUTPUT)\nendif()\n\n# extract the git rev number from the git output...\nif(EIGEN_GIT_OUTPUT)\nstring(REGEX MATCH \"^([0-9;a-f]+).*\" EIGEN_GIT_CHANGESET_MATCH \"${EIGEN_GIT_OUTPUT}\")\nset(EIGEN_GIT_REVNUM \"${CMAKE_MATCH_1}\")\nendif()\n#...and show it next to the version number\nif(EIGEN_GIT_REVNUM)\n  set(EIGEN_VERSION \"${EIGEN_VERSION_NUMBER} (git rev ${EIGEN_GIT_REVNUM})\")\nelse()\n  set(EIGEN_VERSION \"${EIGEN_VERSION_NUMBER}\")\nendif()\n\ninclude(CheckCXXCompilerFlag)\ninclude(GNUInstallDirs)\ninclude(CMakeDependentOption)\n\nset(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake)\n\n\noption(EIGEN_TEST_CXX11 \"Enable testing with C++11 and C++11 features (e.g. Tensor module).\" OFF)\n\n\nmacro(ei_add_cxx_compiler_flag FLAG)\n  string(REGEX REPLACE \"-\" \"\" SFLAG1 ${FLAG})\n  string(REGEX REPLACE \"\\\\+\" \"p\" SFLAG ${SFLAG1})\n  check_cxx_compiler_flag(${FLAG} COMPILER_SUPPORT_${SFLAG})\n  if(COMPILER_SUPPORT_${SFLAG})\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} ${FLAG}\")\n  endif()\nendmacro()\n\ncheck_cxx_compiler_flag(\"-std=c++11\" EIGEN_COMPILER_SUPPORT_CPP11)\n\nif(EIGEN_TEST_CXX11)\n  set(CMAKE_CXX_STANDARD 11)\n  set(CMAKE_CXX_EXTENSIONS OFF)\n  if(EIGEN_COMPILER_SUPPORT_CPP11)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -std=c++11\")\n  endif()\nelse()\n  #set(CMAKE_CXX_STANDARD 03)\n  #set(CMAKE_CXX_EXTENSIONS OFF)\n  ei_add_cxx_compiler_flag(\"-std=c++03\")\nendif()\n\n#############################################################################\n# find how to link to the standard libraries                                #\n#############################################################################\n\nfind_package(StandardMathLibrary)\n\n\nset(EIGEN_TEST_CUSTOM_LINKER_FLAGS  \"\" CACHE STRING \"Additional linker flags when linking unit tests.\")\nset(EIGEN_TEST_CUSTOM_CXX_FLAGS     \"\" CACHE STRING \"Additional compiler flags when compiling unit tests.\")\n\nset(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO \"\")\n\nif(NOT STANDARD_MATH_LIBRARY_FOUND)\n\n  message(FATAL_ERROR\n    \"Can't link to the standard math library. Please report to the Eigen developers, telling them about your platform.\")\n\nelse()\n\n  if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO)\n    set(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO \"${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO} ${STANDARD_MATH_LIBRARY}\")\n  else()\n    set(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO \"${STANDARD_MATH_LIBRARY}\")\n  endif()\n\nendif()\n\nif(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO)\n  message(STATUS \"Standard libraries to link to explicitly: ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO}\")\nelse()\n  message(STATUS \"Standard libraries to link to explicitly: none\")\nendif()\n\noption(EIGEN_BUILD_BTL \"Build benchmark suite\" OFF)\n\n# Disable pkgconfig only for native Windows builds\nif(NOT WIN32 OR NOT CMAKE_HOST_SYSTEM_NAME MATCHES Windows)\n  option(EIGEN_BUILD_PKGCONFIG \"Build pkg-config .pc file for Eigen\" ON)\nendif()\n\nset(CMAKE_INCLUDE_CURRENT_DIR OFF)\n\noption(EIGEN_SPLIT_LARGE_TESTS \"Split large tests into smaller executables\" ON)\n\noption(EIGEN_DEFAULT_TO_ROW_MAJOR \"Use row-major as default matrix storage order\" OFF)\nif(EIGEN_DEFAULT_TO_ROW_MAJOR)\n  add_definitions(\"-DEIGEN_DEFAULT_TO_ROW_MAJOR\")\nendif()\n\nset(EIGEN_TEST_MAX_SIZE \"320\" CACHE STRING \"Maximal matrix/vector size, default is 320\")\n\nif(NOT MSVC)\n  # We assume that other compilers are partly compatible with GNUCC\n\n  # clang outputs some warnings for unknown flags that are not caught by check_cxx_compiler_flag\n  # adding -Werror turns such warnings into errors\n  check_cxx_compiler_flag(\"-Werror\" COMPILER_SUPPORT_WERROR)\n  if(COMPILER_SUPPORT_WERROR)\n    set(CMAKE_REQUIRED_FLAGS \"-Werror\")\n  endif()\n  ei_add_cxx_compiler_flag(\"-pedantic\")\n  ei_add_cxx_compiler_flag(\"-Wall\")\n  ei_add_cxx_compiler_flag(\"-Wextra\")\n  #ei_add_cxx_compiler_flag(\"-Weverything\")              # clang\n\n  ei_add_cxx_compiler_flag(\"-Wundef\")\n  ei_add_cxx_compiler_flag(\"-Wcast-align\")\n  ei_add_cxx_compiler_flag(\"-Wchar-subscripts\")\n  ei_add_cxx_compiler_flag(\"-Wnon-virtual-dtor\")\n  ei_add_cxx_compiler_flag(\"-Wunused-local-typedefs\")\n  ei_add_cxx_compiler_flag(\"-Wpointer-arith\")\n  ei_add_cxx_compiler_flag(\"-Wwrite-strings\")\n  ei_add_cxx_compiler_flag(\"-Wformat-security\")\n  ei_add_cxx_compiler_flag(\"-Wshorten-64-to-32\")\n  ei_add_cxx_compiler_flag(\"-Wlogical-op\")\n  ei_add_cxx_compiler_flag(\"-Wenum-conversion\")\n  ei_add_cxx_compiler_flag(\"-Wc++11-extensions\")\n  ei_add_cxx_compiler_flag(\"-Wdouble-promotion\")\n#  ei_add_cxx_compiler_flag(\"-Wconversion\")\n\n  ei_add_cxx_compiler_flag(\"-Wshadow\")\n\n  ei_add_cxx_compiler_flag(\"-Wno-psabi\")\n  ei_add_cxx_compiler_flag(\"-Wno-variadic-macros\")\n  ei_add_cxx_compiler_flag(\"-Wno-long-long\")\n\n  ei_add_cxx_compiler_flag(\"-fno-check-new\")\n  ei_add_cxx_compiler_flag(\"-fno-common\")\n  ei_add_cxx_compiler_flag(\"-fstrict-aliasing\")\n  ei_add_cxx_compiler_flag(\"-wd981\")                    # disable ICC's \"operands are evaluated in unspecified order\" remark\n  ei_add_cxx_compiler_flag(\"-wd2304\")                   # disable ICC's \"warning #2304: non-explicit constructor with single argument may cause implicit type conversion\" produced by -Wnon-virtual-dtor\n\n\n  # The -ansi flag must be added last, otherwise it is also used as a linker flag by check_cxx_compiler_flag making it fails\n  # Moreover we should not set both -strict-ansi and -ansi\n  check_cxx_compiler_flag(\"-strict-ansi\" COMPILER_SUPPORT_STRICTANSI)\n  ei_add_cxx_compiler_flag(\"-Qunused-arguments\")        # disable clang warning: argument unused during compilation: '-ansi'\n\n  if(COMPILER_SUPPORT_STRICTANSI)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -strict-ansi\")\n  else()\n    ei_add_cxx_compiler_flag(\"-ansi\")\n  endif()\n\n  if(ANDROID_NDK)\n    ei_add_cxx_compiler_flag(\"-pie\")\n    ei_add_cxx_compiler_flag(\"-fPIE\")\n  endif()\n\n  set(CMAKE_REQUIRED_FLAGS \"\")\n\n  option(EIGEN_TEST_SSE2 \"Enable/Disable SSE2 in tests/examples\" OFF)\n  if(EIGEN_TEST_SSE2)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -msse2\")\n    message(STATUS \"Enabling SSE2 in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_SSE3 \"Enable/Disable SSE3 in tests/examples\" OFF)\n  if(EIGEN_TEST_SSE3)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -msse3\")\n    message(STATUS \"Enabling SSE3 in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_SSSE3 \"Enable/Disable SSSE3 in tests/examples\" OFF)\n  if(EIGEN_TEST_SSSE3)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mssse3\")\n    message(STATUS \"Enabling SSSE3 in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_SSE4_1 \"Enable/Disable SSE4.1 in tests/examples\" OFF)\n  if(EIGEN_TEST_SSE4_1)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -msse4.1\")\n    message(STATUS \"Enabling SSE4.1 in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_SSE4_2 \"Enable/Disable SSE4.2 in tests/examples\" OFF)\n  if(EIGEN_TEST_SSE4_2)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -msse4.2\")\n    message(STATUS \"Enabling SSE4.2 in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_AVX \"Enable/Disable AVX in tests/examples\" OFF)\n  if(EIGEN_TEST_AVX)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mavx\")\n    message(STATUS \"Enabling AVX in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_FMA \"Enable/Disable FMA in tests/examples\" OFF)\n  if(EIGEN_TEST_FMA AND NOT EIGEN_TEST_NEON)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mfma\")\n    message(STATUS \"Enabling FMA in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_AVX2 \"Enable/Disable AVX2 in tests/examples\" OFF)\n  if(EIGEN_TEST_AVX2)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mavx2 -mfma\")\n    message(STATUS \"Enabling AVX2 in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_AVX512 \"Enable/Disable AVX512 in tests/examples\" OFF)\n  if(EIGEN_TEST_AVX512)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mavx512f -mfma\")\n    if (NOT \"${CMAKE_CXX_COMPILER_ID}\" STREQUAL \"Clang\")\n      set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -fabi-version=6\")\n    endif()\n    message(STATUS \"Enabling AVX512 in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_AVX512DQ \"Enable/Disable AVX512DQ in tests/examples\" OFF)\n  if(EIGEN_TEST_AVX512DQ)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mavx512dq\")\n    if (NOT \"${CMAKE_CXX_COMPILER_ID}\" STREQUAL \"Clang\")\n      set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -fabi-version=6\")\n    endif()\n    message(STATUS \"Enabling AVX512DQ in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_F16C \"Enable/Disable F16C in tests/examples\" OFF)\n  if(EIGEN_TEST_F16C)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mf16c\")\n    message(STATUS \"Enabling F16C in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_ALTIVEC \"Enable/Disable AltiVec in tests/examples\" OFF)\n  if(EIGEN_TEST_ALTIVEC)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -maltivec -mabi=altivec\")\n    message(STATUS \"Enabling AltiVec in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_VSX \"Enable/Disable VSX in tests/examples\" OFF)\n  if(EIGEN_TEST_VSX)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -m64 -mvsx\")\n    message(STATUS \"Enabling VSX in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_MSA \"Enable/Disable MSA in tests/examples\" OFF)\n  if(EIGEN_TEST_MSA)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mmsa\")\n    message(STATUS \"Enabling MSA in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_NEON \"Enable/Disable Neon in tests/examples\" OFF)\n  if(EIGEN_TEST_NEON)\n    if(EIGEN_TEST_FMA)\n      set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mfpu=neon-vfpv4\")\n    else()\n      set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mfpu=neon\")\n    endif()\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mfloat-abi=hard\")\n    message(STATUS \"Enabling NEON in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_NEON64 \"Enable/Disable Neon in tests/examples\" OFF)\n  if(EIGEN_TEST_NEON64)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS}\")\n    message(STATUS \"Enabling NEON in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_Z13 \"Enable/Disable S390X(zEC13) ZVECTOR in tests/examples\" OFF)\n  if(EIGEN_TEST_Z13)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -march=z13 -mzvector\")\n    message(STATUS \"Enabling S390X(zEC13) ZVECTOR in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_Z14 \"Enable/Disable S390X(zEC14) ZVECTOR in tests/examples\" OFF)\n  if(EIGEN_TEST_Z14)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -march=z14 -mzvector\")\n    message(STATUS \"Enabling S390X(zEC13) ZVECTOR in tests/examples\")\n  endif()\n\n  check_cxx_compiler_flag(\"-fopenmp\" COMPILER_SUPPORT_OPENMP)\n  if(COMPILER_SUPPORT_OPENMP)\n    option(EIGEN_TEST_OPENMP \"Enable/Disable OpenMP in tests/examples\" OFF)\n    if(EIGEN_TEST_OPENMP)\n      set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -fopenmp\")\n      message(STATUS \"Enabling OpenMP in tests/examples\")\n    endif()\n  endif()\n\nelse()\n\n  # C4127 - conditional expression is constant\n  # C4714 - marked as __forceinline not inlined (I failed to deactivate it selectively)\n  #         We can disable this warning in the unit tests since it is clear that it occurs\n  #         because we are oftentimes returning objects that have a destructor or may\n  #         throw exceptions - in particular in the unit tests we are throwing extra many\n  #         exceptions to cover indexing errors.\n  # C4505 - unreferenced local function has been removed (impossible to deactivate selectively)\n  set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} /EHsc /wd4127 /wd4505 /wd4714\")\n\n  # replace all /Wx by /W4\n  string(REGEX REPLACE \"/W[0-9]\" \"/W4\" CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS}\")\n\n  check_cxx_compiler_flag(\"/openmp\" COMPILER_SUPPORT_OPENMP)\n  if(COMPILER_SUPPORT_OPENMP)\n    option(EIGEN_TEST_OPENMP \"Enable/Disable OpenMP in tests/examples\" OFF)\n    if(EIGEN_TEST_OPENMP)\n      set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} /openmp\")\n      message(STATUS \"Enabling OpenMP in tests/examples\")\n    endif()\n  endif()\n\n  option(EIGEN_TEST_SSE2 \"Enable/Disable SSE2 in tests/examples\" OFF)\n  if(EIGEN_TEST_SSE2)\n    if(NOT CMAKE_CL_64)\n      # arch is not supported on 64 bit systems, SSE is enabled automatically.\n      set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} /arch:SSE2\")\n    endif()\n    message(STATUS \"Enabling SSE2 in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_AVX \"Enable/Disable AVX in tests/examples\" OFF)\n  if(EIGEN_TEST_AVX)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} /arch:AVX\")\n    message(STATUS \"Enabling AVX in tests/examples\")\n  endif()\n\n  option(EIGEN_TEST_FMA \"Enable/Disable FMA/AVX2 in tests/examples\" OFF)\n  if(EIGEN_TEST_FMA AND NOT EIGEN_TEST_NEON)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} /arch:AVX2\")\n    message(STATUS \"Enabling FMA/AVX2 in tests/examples\")\n  endif()\n\nendif()\n\noption(EIGEN_TEST_NO_EXPLICIT_VECTORIZATION \"Disable explicit vectorization in tests/examples\" OFF)\noption(EIGEN_TEST_X87 \"Force using X87 instructions. Implies no vectorization.\" OFF)\noption(EIGEN_TEST_32BIT \"Force generating 32bit code.\" OFF)\n\nif(EIGEN_TEST_X87)\n  set(EIGEN_TEST_NO_EXPLICIT_VECTORIZATION ON)\n  if(CMAKE_COMPILER_IS_GNUCXX)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -mfpmath=387\")\n    message(STATUS \"Forcing use of x87 instructions in tests/examples\")\n  else()\n    message(STATUS \"EIGEN_TEST_X87 ignored on your compiler\")\n  endif()\nendif()\n\nif(EIGEN_TEST_32BIT)\n  if(CMAKE_COMPILER_IS_GNUCXX)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -m32\")\n    message(STATUS \"Forcing generation of 32-bit code in tests/examples\")\n  else()\n    message(STATUS \"EIGEN_TEST_32BIT ignored on your compiler\")\n  endif()\nendif()\n\nif(EIGEN_TEST_NO_EXPLICIT_VECTORIZATION)\n  add_definitions(-DEIGEN_DONT_VECTORIZE=1)\n  message(STATUS \"Disabling vectorization in tests/examples\")\nendif()\n\noption(EIGEN_TEST_NO_EXPLICIT_ALIGNMENT \"Disable explicit alignment (hence vectorization) in tests/examples\" OFF)\nif(EIGEN_TEST_NO_EXPLICIT_ALIGNMENT)\n  add_definitions(-DEIGEN_DONT_ALIGN=1)\n  message(STATUS \"Disabling alignment in tests/examples\")\nendif()\n\noption(EIGEN_TEST_NO_EXCEPTIONS \"Disables C++ exceptions\" OFF)\nif(EIGEN_TEST_NO_EXCEPTIONS)\n  ei_add_cxx_compiler_flag(\"-fno-exceptions\")\n  message(STATUS \"Disabling exceptions in tests/examples\")\nendif()\n\nset(EIGEN_CUDA_COMPUTE_ARCH 30 CACHE STRING \"The CUDA compute architecture level to target when compiling CUDA code\")\n\ninclude_directories(${CMAKE_CURRENT_SOURCE_DIR})\n\n# Backward compatibility support for EIGEN_INCLUDE_INSTALL_DIR\nif(EIGEN_INCLUDE_INSTALL_DIR)\n  message(WARNING \"EIGEN_INCLUDE_INSTALL_DIR is deprecated. Use INCLUDE_INSTALL_DIR instead.\")\nendif()\n\nif(EIGEN_INCLUDE_INSTALL_DIR AND NOT INCLUDE_INSTALL_DIR)\n  set(INCLUDE_INSTALL_DIR ${EIGEN_INCLUDE_INSTALL_DIR}\n      CACHE STRING \"The directory relative to CMAKE_PREFIX_PATH where Eigen header files are installed\")\nelse()\n  set(INCLUDE_INSTALL_DIR\n      \"${CMAKE_INSTALL_INCLUDEDIR}/eigen3\"\n      CACHE STRING \"The directory relative to CMAKE_PREFIX_PATH where Eigen header files are installed\"\n      )\nendif()\nset(CMAKEPACKAGE_INSTALL_DIR\n    \"${CMAKE_INSTALL_DATADIR}/eigen3/cmake\"\n    CACHE STRING \"The directory relative to CMAKE_PREFIX_PATH where Eigen3Config.cmake is installed\"\n    )\nset(PKGCONFIG_INSTALL_DIR\n    \"${CMAKE_INSTALL_DATADIR}/pkgconfig\"\n    CACHE STRING \"The directory relative to CMAKE_PREFIX_PATH where eigen3.pc is installed\"\n    )\n\nforeach(var INCLUDE_INSTALL_DIR CMAKEPACKAGE_INSTALL_DIR PKGCONFIG_INSTALL_DIR)\n  if(IS_ABSOLUTE \"${${var}}\")\n    message(FATAL_ERROR \"${var} must be relative to CMAKE_PREFIX_PATH. Got: ${${var}}\")\n  endif()\nendforeach()\n\n# similar to set_target_properties but append the property instead of overwriting it\nmacro(ei_add_target_property target prop value)\n\n  get_target_property(previous ${target} ${prop})\n  # if the property wasn't previously set, ${previous} is now \"previous-NOTFOUND\" which cmake allows catching with plain if()\n  if(NOT previous)\n    set(previous \"\")\n  endif()\n  set_target_properties(${target} PROPERTIES ${prop} \"${previous} ${value}\")\nendmacro()\n\ninstall(FILES\n  signature_of_eigen3_matrix_library\n  DESTINATION ${INCLUDE_INSTALL_DIR} COMPONENT Devel\n  )\n\nif(EIGEN_BUILD_PKGCONFIG)\n    configure_file(eigen3.pc.in eigen3.pc @ONLY)\n    install(FILES ${CMAKE_CURRENT_BINARY_DIR}/eigen3.pc\n        DESTINATION ${PKGCONFIG_INSTALL_DIR}\n        )\nendif()\n\ninstall(DIRECTORY Eigen DESTINATION ${INCLUDE_INSTALL_DIR} COMPONENT Devel)\n\n\noption(EIGEN_BUILD_DOC \"Enable creation of Eigen documentation\" ON)\nif(EIGEN_BUILD_DOC)\n  add_subdirectory(doc EXCLUDE_FROM_ALL)\nendif()\n\n\noption(BUILD_TESTING \"Enable creation of Eigen tests.\" ON)\nif(BUILD_TESTING)\n  include(EigenConfigureTesting)\n\n  if(EIGEN_LEAVE_TEST_IN_ALL_TARGET)\n    add_subdirectory(test) # can't do EXCLUDE_FROM_ALL here, breaks CTest\n  else()\n    add_subdirectory(test EXCLUDE_FROM_ALL)\n  endif()\n\n  add_subdirectory(failtest)\nendif()\n\nif(EIGEN_LEAVE_TEST_IN_ALL_TARGET)\n  add_subdirectory(blas)\n  add_subdirectory(lapack)\nelse()\n  add_subdirectory(blas EXCLUDE_FROM_ALL)\n  add_subdirectory(lapack EXCLUDE_FROM_ALL)\nendif()\n\n# add SYCL\noption(EIGEN_TEST_SYCL \"Add Sycl support.\" OFF)\noption(EIGEN_SYCL_TRISYCL \"Use the triSYCL Sycl implementation (ComputeCPP by default).\" OFF)\nif(EIGEN_TEST_SYCL)\n  set (CMAKE_MODULE_PATH \"${CMAKE_ROOT}/Modules\" \"cmake/Modules/\" \"${CMAKE_MODULE_PATH}\")\n  find_package(Threads REQUIRED)\n  if(EIGEN_SYCL_TRISYCL)\n    message(STATUS \"Using triSYCL\")\n    include(FindTriSYCL)\n  else()\n    message(STATUS \"Using ComputeCPP SYCL\")\n    include(FindComputeCpp)\n    set(COMPUTECPP_DRIVER_DEFAULT_VALUE OFF)\n    if (NOT MSVC)\n      set(COMPUTECPP_DRIVER_DEFAULT_VALUE ON)\n    endif()\n    option(COMPUTECPP_USE_COMPILER_DRIVER\n      \"Use ComputeCpp driver instead of a 2 steps compilation\"\n      ${COMPUTECPP_DRIVER_DEFAULT_VALUE}\n    )\n  endif(EIGEN_SYCL_TRISYCL)\n  option(EIGEN_DONT_VECTORIZE_SYCL \"Don't use vectorisation in the SYCL tests.\" OFF)\n  if(EIGEN_DONT_VECTORIZE_SYCL)\n    message(STATUS \"Disabling SYCL vectorization in tests/examples\")\n    # When disabling SYCL vectorization, also disable Eigen default vectorization\n    add_definitions(-DEIGEN_DONT_VECTORIZE=1)\n    add_definitions(-DEIGEN_DONT_VECTORIZE_SYCL=1)\n  endif()\nendif()\n\nadd_subdirectory(unsupported)\n\nadd_subdirectory(demos EXCLUDE_FROM_ALL)\n\n# must be after test and unsupported, for configuring buildtests.in\nadd_subdirectory(scripts EXCLUDE_FROM_ALL)\n\n# TODO: consider also replacing EIGEN_BUILD_BTL by a custom target \"make btl\"?\nif(EIGEN_BUILD_BTL)\n  add_subdirectory(bench/btl EXCLUDE_FROM_ALL)\nendif()\n\nif(NOT WIN32)\n  add_subdirectory(bench/spbench EXCLUDE_FROM_ALL)\nendif()\n\nconfigure_file(scripts/cdashtesting.cmake.in cdashtesting.cmake @ONLY)\n\nif(BUILD_TESTING)\n  ei_testing_print_summary()\nendif()\n\nmessage(STATUS \"\")\nmessage(STATUS \"Configured Eigen ${EIGEN_VERSION_NUMBER}\")\nmessage(STATUS \"\")\n\nstring(TOLOWER \"${CMAKE_GENERATOR}\" cmake_generator_tolower)\nif(cmake_generator_tolower MATCHES \"makefile\")\n  message(STATUS \"Available targets (use: make TARGET):\")\nelse()\n  message(STATUS \"Available targets (use: cmake --build . --target TARGET):\")\nendif()\nmessage(STATUS \"---------+--------------------------------------------------------------\")\nmessage(STATUS \"Target   |   Description\")\nmessage(STATUS \"---------+--------------------------------------------------------------\")\nmessage(STATUS \"install  | Install Eigen. Headers will be installed to:\")\nmessage(STATUS \"         |     <CMAKE_INSTALL_PREFIX>/<INCLUDE_INSTALL_DIR>\")\nmessage(STATUS \"         |   Using the following values:\")\nmessage(STATUS \"         |     CMAKE_INSTALL_PREFIX: ${CMAKE_INSTALL_PREFIX}\")\nmessage(STATUS \"         |     INCLUDE_INSTALL_DIR:  ${INCLUDE_INSTALL_DIR}\")\nmessage(STATUS \"         |   Change the install location of Eigen headers using:\")\nmessage(STATUS \"         |     cmake . -DCMAKE_INSTALL_PREFIX=yourprefix\")\nmessage(STATUS \"         |   Or:\")\nmessage(STATUS \"         |     cmake . -DINCLUDE_INSTALL_DIR=yourdir\")\nmessage(STATUS \"doc      | Generate the API documentation, requires Doxygen & LaTeX\")\nif(BUILD_TESTING)\n  message(STATUS \"check    | Build and run the unit-tests. Read this page:\")\n  message(STATUS \"         |   http://eigen.tuxfamily.org/index.php?title=Tests\")\nendif()\nmessage(STATUS \"blas     | Build BLAS library (not the same thing as Eigen)\")\nmessage(STATUS \"uninstall| Remove files installed by the install target\")\nmessage(STATUS \"---------+--------------------------------------------------------------\")\nmessage(STATUS \"\")\n\n\nset ( EIGEN_VERSION_STRING ${EIGEN_VERSION_NUMBER} )\nset ( EIGEN_VERSION_MAJOR  ${EIGEN_WORLD_VERSION} )\nset ( EIGEN_VERSION_MINOR  ${EIGEN_MAJOR_VERSION} )\nset ( EIGEN_VERSION_PATCH  ${EIGEN_MINOR_VERSION} )\nset ( EIGEN_DEFINITIONS \"\")\nset ( EIGEN_INCLUDE_DIR \"${CMAKE_INSTALL_PREFIX}/${INCLUDE_INSTALL_DIR}\" )\nset ( EIGEN_ROOT_DIR ${CMAKE_INSTALL_PREFIX} )\n\ninclude (CMakePackageConfigHelpers)\n\n# Imported target support\nadd_library (eigen INTERFACE)\nadd_library (Eigen3::Eigen ALIAS eigen)\ntarget_compile_definitions (eigen INTERFACE ${EIGEN_DEFINITIONS})\ntarget_include_directories (eigen INTERFACE\n  $<BUILD_INTERFACE:${CMAKE_CURRENT_SOURCE_DIR}>\n  $<INSTALL_INTERFACE:${INCLUDE_INSTALL_DIR}>\n)\n\n# Export as title case Eigen\nset_target_properties (eigen PROPERTIES EXPORT_NAME Eigen)\n\ninstall (TARGETS eigen EXPORT Eigen3Targets)\n\nconfigure_package_config_file (\n  ${CMAKE_CURRENT_SOURCE_DIR}/cmake/Eigen3Config.cmake.in\n  ${CMAKE_CURRENT_BINARY_DIR}/Eigen3Config.cmake\n  PATH_VARS EIGEN_INCLUDE_DIR EIGEN_ROOT_DIR\n  INSTALL_DESTINATION ${CMAKEPACKAGE_INSTALL_DIR}\n  NO_CHECK_REQUIRED_COMPONENTS_MACRO # Eigen does not provide components\n)\n# Remove CMAKE_SIZEOF_VOID_P from Eigen3ConfigVersion.cmake since Eigen does\n# not depend on architecture specific settings or libraries. More\n# specifically, an Eigen3Config.cmake generated from a 64 bit target can be\n# used for 32 bit targets as well (and vice versa).\nset (_Eigen3_CMAKE_SIZEOF_VOID_P ${CMAKE_SIZEOF_VOID_P})\nunset (CMAKE_SIZEOF_VOID_P)\nwrite_basic_package_version_file (Eigen3ConfigVersion.cmake\n                                  VERSION ${EIGEN_VERSION_NUMBER}\n                                  COMPATIBILITY SameMajorVersion)\nset (CMAKE_SIZEOF_VOID_P ${_Eigen3_CMAKE_SIZEOF_VOID_P})\n\n# The Eigen target will be located in the Eigen3 namespace. Other CMake\n# targets can refer to it using Eigen3::Eigen.\nexport (TARGETS eigen NAMESPACE Eigen3:: FILE Eigen3Targets.cmake)\n# Export Eigen3 package to CMake registry such that it can be easily found by\n# CMake even if it has not been installed to a standard directory.\nexport (PACKAGE Eigen3)\n\ninstall (EXPORT Eigen3Targets NAMESPACE Eigen3:: DESTINATION ${CMAKEPACKAGE_INSTALL_DIR})\n\ninstall ( FILES ${CMAKE_CURRENT_SOURCE_DIR}/cmake/UseEigen3.cmake\n                ${CMAKE_CURRENT_BINARY_DIR}/Eigen3Config.cmake\n                ${CMAKE_CURRENT_BINARY_DIR}/Eigen3ConfigVersion.cmake\n          DESTINATION ${CMAKEPACKAGE_INSTALL_DIR} )\n\n# Add uninstall target\nadd_custom_target ( uninstall\n    COMMAND ${CMAKE_COMMAND} -P ${CMAKE_CURRENT_SOURCE_DIR}/cmake/EigenUninstall.cmake)\n\nif (EIGEN_SPLIT_TESTSUITE)\n  ei_split_testsuite(\"${EIGEN_SPLIT_TESTSUITE}\")\nendif()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/COPYING.APACHE",
    "content": "/*\n                                 Apache License\n                           Version 2.0, January 2004\n                        http://www.apache.org/licenses/\n\n   TERMS AND CONDITIONS FOR USE, REPRODUCTION, AND DISTRIBUTION\n\n   1. Definitions.\n\n      \"License\" shall mean the terms and conditions for use, reproduction,\n      and distribution as defined by Sections 1 through 9 of this document.\n\n      \"Licensor\" shall mean the copyright owner or entity authorized by\n      the copyright owner that is granting the License.\n\n      \"Legal Entity\" shall mean the union of the acting entity and all\n      other entities that control, are controlled by, or are under common\n      control with that entity. For the purposes of this definition,\n      \"control\" means (i) the power, direct or indirect, to cause the\n      direction or management of such entity, whether by contract or\n      otherwise, or (ii) ownership of fifty percent (50%) or more of the\n      outstanding shares, or (iii) beneficial ownership of such entity.\n\n      \"You\" (or \"Your\") shall mean an individual or Legal Entity\n      exercising permissions granted by this License.\n\n      \"Source\" form shall mean the preferred form for making modifications,\n      including but not limited to software source code, documentation\n      source, and configuration files.\n\n      \"Object\" form shall mean any form resulting from mechanical\n      transformation or translation of a Source form, including but\n      not limited to compiled object code, generated documentation,\n      and conversions to other media types.\n\n      \"Work\" shall mean the work of authorship, whether in Source or\n      Object form, made available under the License, as indicated by a\n      copyright notice that is included in or attached to the work\n      (an example is provided in the Appendix below).\n\n      \"Derivative Works\" shall mean any work, whether in Source or Object\n      form, that is based on (or derived from) the Work and for which the\n      editorial revisions, annotations, elaborations, or other modifications\n      represent, as a whole, an original work of authorship. For the purposes\n      of this License, Derivative Works shall not include works that remain\n      separable from, or merely link (or bind by name) to the interfaces of,\n      the Work and Derivative Works thereof.\n\n      \"Contribution\" shall mean any work of authorship, including\n      the original version of the Work and any modifications or additions\n      to that Work or Derivative Works thereof, that is intentionally\n      submitted to Licensor for inclusion in the Work by the copyright owner\n      or by an individual or Legal Entity authorized to submit on behalf of\n      the copyright owner. For the purposes of this definition, \"submitted\"\n      means any form of electronic, verbal, or written communication sent\n      to the Licensor or its representatives, including but not limited to\n      communication on electronic mailing lists, source code control systems,\n      and issue tracking systems that are managed by, or on behalf of, the\n      Licensor for the purpose of discussing and improving the Work, but\n      excluding communication that is conspicuously marked or otherwise\n      designated in writing by the copyright owner as \"Not a Contribution.\"\n\n      \"Contributor\" shall mean Licensor and any individual or Legal Entity\n      on behalf of whom a Contribution has been received by Licensor and\n      subsequently incorporated within the Work.\n\n   2. Grant of Copyright License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      copyright license to reproduce, prepare Derivative Works of,\n      publicly display, publicly perform, sublicense, and distribute the\n      Work and such Derivative Works in Source or Object form.\n\n   3. Grant of Patent License. Subject to the terms and conditions of\n      this License, each Contributor hereby grants to You a perpetual,\n      worldwide, non-exclusive, no-charge, royalty-free, irrevocable\n      (except as stated in this section) patent license to make, have made,\n      use, offer to sell, sell, import, and otherwise transfer the Work,\n      where such license applies only to those patent claims licensable\n      by such Contributor that are necessarily infringed by their\n      Contribution(s) alone or by combination of their Contribution(s)\n      with the Work to which such Contribution(s) was submitted. If You\n      institute patent litigation against any entity (including a\n      cross-claim or counterclaim in a lawsuit) alleging that the Work\n      or a Contribution incorporated within the Work constitutes direct\n      or contributory patent infringement, then any patent licenses\n      granted to You under this License for that Work shall terminate\n      as of the date such litigation is filed.\n\n   4. Redistribution. You may reproduce and distribute copies of the\n      Work or Derivative Works thereof in any medium, with or without\n      modifications, and in Source or Object form, provided that You\n      meet the following conditions:\n\n      (a) You must give any other recipients of the Work or\n          Derivative Works a copy of this License; and\n\n      (b) You must cause any modified files to carry prominent notices\n          stating that You changed the files; and\n\n      (c) You must retain, in the Source form of any Derivative Works\n          that You distribute, all copyright, patent, trademark, and\n          attribution notices from the Source form of the Work,\n          excluding those notices that do not pertain to any part of\n          the Derivative Works; and\n\n      (d) If the Work includes a \"NOTICE\" text file as part of its\n          distribution, then any Derivative Works that You distribute must\n          include a readable copy of the attribution notices contained\n          within such NOTICE file, excluding those notices that do not\n          pertain to any part of the Derivative Works, in at least one\n          of the following places: within a NOTICE text file distributed\n          as part of the Derivative Works; within the Source form or\n          documentation, if provided along with the Derivative Works; or,\n          within a display generated by the Derivative Works, if and\n          wherever such third-party notices normally appear. The contents\n          of the NOTICE file are for informational purposes only and\n          do not modify the License. You may add Your own attribution\n          notices within Derivative Works that You distribute, alongside\n          or as an addendum to the NOTICE text from the Work, provided\n          that such additional attribution notices cannot be construed\n          as modifying the License.\n\n      You may add Your own copyright statement to Your modifications and\n      may provide additional or different license terms and conditions\n      for use, reproduction, or distribution of Your modifications, or\n      for any such Derivative Works as a whole, provided Your use,\n      reproduction, and distribution of the Work otherwise complies with\n      the conditions stated in this License.\n\n   5. Submission of Contributions. Unless You explicitly state otherwise,\n      any Contribution intentionally submitted for inclusion in the Work\n      by You to the Licensor shall be under the terms and conditions of\n      this License, without any additional terms or conditions.\n      Notwithstanding the above, nothing herein shall supersede or modify\n      the terms of any separate license agreement you may have executed\n      with Licensor regarding such Contributions.\n\n   6. Trademarks. This License does not grant permission to use the trade\n      names, trademarks, service marks, or product names of the Licensor,\n      except as required for reasonable and customary use in describing the\n      origin of the Work and reproducing the content of the NOTICE file.\n\n   7. Disclaimer of Warranty. Unless required by applicable law or\n      agreed to in writing, Licensor provides the Work (and each\n      Contributor provides its Contributions) on an \"AS IS\" BASIS,\n      WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or\n      implied, including, without limitation, any warranties or conditions\n      of TITLE, NON-INFRINGEMENT, MERCHANTABILITY, or FITNESS FOR A\n      PARTICULAR PURPOSE. You are solely responsible for determining the\n      appropriateness of using or redistributing the Work and assume any\n      risks associated with Your exercise of permissions under this License.\n\n   8. Limitation of Liability. In no event and under no legal theory,\n      whether in tort (including negligence), contract, or otherwise,\n      unless required by applicable law (such as deliberate and grossly\n      negligent acts) or agreed to in writing, shall any Contributor be\n      liable to You for damages, including any direct, indirect, special,\n      incidental, or consequential damages of any character arising as a\n      result of this License or out of the use or inability to use the\n      Work (including but not limited to damages for loss of goodwill,\n      work stoppage, computer failure or malfunction, or any and all\n      other commercial damages or losses), even if such Contributor\n      has been advised of the possibility of such damages.\n\n   9. Accepting Warranty or Additional Liability. While redistributing\n      the Work or Derivative Works thereof, You may choose to offer,\n      and charge a fee for, acceptance of support, warranty, indemnity,\n      or other liability obligations and/or rights consistent with this\n      License. However, in accepting such obligations, You may act only\n      on Your own behalf and on Your sole responsibility, not on behalf\n      of any other Contributor, and only if You agree to indemnify,\n      defend, and hold each Contributor harmless for any liability\n      incurred by, or claims asserted against, such Contributor by reason\n      of your accepting any such warranty or additional liability.\n\n   END OF TERMS AND CONDITIONS\n\n   APPENDIX: How to apply the Apache License to your work.\n\n      To apply the Apache License to your work, attach the following\n      boilerplate notice, with the fields enclosed by brackets \"[]\"\n      replaced with your own identifying information. (Don't include\n      the brackets!)  The text should be enclosed in the appropriate\n      comment syntax for the file format. We also recommend that a\n      file or class name and description of purpose be included on the\n      same \"printed page\" as the copyright notice for easier\n      identification within third-party archives.\n\n   Copyright [yyyy] [name of copyright owner]\n\n   Licensed under the Apache License, Version 2.0 (the \"License\");\n   you may not use this file except in compliance with the License.\n   You may obtain a copy of the License at\n\n       http://www.apache.org/licenses/LICENSE-2.0\n\n   Unless required by applicable law or agreed to in writing, software\n   distributed under the License is distributed on an \"AS IS\" BASIS,\n   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n   See the License for the specific language governing permissions and\n   limitations under the License.\n*/"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/COPYING.BSD",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n*/\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/COPYING.GPL",
    "content": "                    GNU GENERAL PUBLIC LICENSE\n                       Version 3, 29 June 2007\n\n Copyright (C) 2007 Free Software Foundation, Inc. <http://fsf.org/>\n Everyone is permitted to copy and distribute verbatim copies\n of this license document, but changing it is not allowed.\n\n                            Preamble\n\n  The GNU General Public License is a free, copyleft license for\nsoftware and other kinds of works.\n\n  The licenses for most software and other practical works are designed\nto take away your freedom to share and change the works.  By contrast,\nthe GNU General Public License is intended to guarantee your freedom to\nshare and change all versions of a program--to make sure it remains free\nsoftware for all its users.  We, the Free Software Foundation, use the\nGNU General Public License for most of our software; it applies also to\nany other work released this way by its authors.  You can apply it to\nyour programs, too.\n\n  When we speak of free software, we are referring to freedom, not\nprice.  Our General Public Licenses are designed to make sure that you\nhave the freedom to distribute copies of free software (and charge for\nthem if you wish), that you receive source code or can get it if you\nwant it, that you can change the software or use pieces of it in new\nfree programs, and that you know you can do these things.\n\n  To protect your rights, we need to prevent others from denying you\nthese rights or asking you to surrender the rights.  Therefore, you have\ncertain responsibilities if you distribute copies of the software, or if\nyou modify it: responsibilities to respect the freedom of others.\n\n  For example, if you distribute copies of such a program, whether\ngratis or for a fee, you must pass on to the recipients the same\nfreedoms that you received.  You must make sure that they, too, receive\nor can get the source code.  And you must show them these terms so they\nknow their rights.\n\n  Developers that use the GNU GPL protect your rights with two steps:\n(1) assert copyright on the software, and (2) offer you this License\ngiving you legal permission to copy, distribute and/or modify it.\n\n  For the developers' and authors' protection, the GPL clearly explains\nthat there is no warranty for this free software.  For both users' and\nauthors' sake, the GPL requires that modified versions be marked as\nchanged, so that their problems will not be attributed erroneously to\nauthors of previous versions.\n\n  Some devices are designed to deny users access to install or run\nmodified versions of the software inside them, although the manufacturer\ncan do so.  This is fundamentally incompatible with the aim of\nprotecting users' freedom to change the software.  The systematic\npattern of such abuse occurs in the area of products for individuals to\nuse, which is precisely where it is most unacceptable.  Therefore, we\nhave designed this version of the GPL to prohibit the practice for those\nproducts.  If such problems arise substantially in other domains, we\nstand ready to extend this provision to those domains in future versions\nof the GPL, as needed to protect the freedom of users.\n\n  Finally, every program is threatened constantly by software patents.\nStates should not allow patents to restrict development and use of\nsoftware on general-purpose computers, but in those that do, we wish to\navoid the special danger that patents applied to a free program could\nmake it effectively proprietary.  To prevent this, the GPL assures that\npatents cannot be used to render the program non-free.\n\n  The precise terms and conditions for copying, distribution and\nmodification follow.\n\n                       TERMS AND CONDITIONS\n\n  0. Definitions.\n\n  \"This License\" refers to version 3 of the GNU General Public License.\n\n  \"Copyright\" also means copyright-like laws that apply to other kinds of\nworks, such as semiconductor masks.\n\n  \"The Program\" refers to any copyrightable work licensed under this\nLicense.  Each licensee is addressed as \"you\".  \"Licensees\" and\n\"recipients\" may be individuals or organizations.\n\n  To \"modify\" a work means to copy from or adapt all or part of the work\nin a fashion requiring copyright permission, other than the making of an\nexact copy.  The resulting work is called a \"modified version\" of the\nearlier work or a work \"based on\" the earlier work.\n\n  A \"covered work\" means either the unmodified Program or a work based\non the Program.\n\n  To \"propagate\" a work means to do anything with it that, without\npermission, would make you directly or secondarily liable for\ninfringement under applicable copyright law, except executing it on a\ncomputer or modifying a private copy.  Propagation includes copying,\ndistribution (with or without modification), making available to the\npublic, and in some countries other activities as well.\n\n  To \"convey\" a work means any kind of propagation that enables other\nparties to make or receive copies.  Mere interaction with a user through\na computer network, with no transfer of a copy, is not conveying.\n\n  An interactive user interface displays \"Appropriate Legal Notices\"\nto the extent that it includes a convenient and prominently visible\nfeature that (1) displays an appropriate copyright notice, and (2)\ntells the user that there is no warranty for the work (except to the\nextent that warranties are provided), that licensees may convey the\nwork under this License, and how to view a copy of this License.  If\nthe interface presents a list of user commands or options, such as a\nmenu, a prominent item in the list meets this criterion.\n\n  1. Source Code.\n\n  The \"source code\" for a work means the preferred form of the work\nfor making modifications to it.  \"Object code\" means any non-source\nform of a work.\n\n  A \"Standard Interface\" means an interface that either is an official\nstandard defined by a recognized standards body, or, in the case of\ninterfaces specified for a particular programming language, one that\nis widely used among developers working in that language.\n\n  The \"System Libraries\" of an executable work include anything, other\nthan the work as a whole, that (a) is included in the normal form of\npackaging a Major Component, but which is not part of that Major\nComponent, and (b) serves only to enable use of the work with that\nMajor Component, or to implement a Standard Interface for which an\nimplementation is available to the public in source code form.  A\n\"Major Component\", in this context, means a major essential component\n(kernel, window system, and so on) of the specific operating system\n(if any) on which the executable work runs, or a compiler used to\nproduce the work, or an object code interpreter used to run it.\n\n  The \"Corresponding Source\" for a work in object code form means all\nthe source code needed to generate, install, and (for an executable\nwork) run the object code and to modify the work, including scripts to\ncontrol those activities.  However, it does not include the work's\nSystem Libraries, or general-purpose tools or generally available free\nprograms which are used unmodified in performing those activities but\nwhich are not part of the work.  For example, Corresponding Source\nincludes interface definition files associated with source files for\nthe work, and the source code for shared libraries and dynamically\nlinked subprograms that the work is specifically designed to require,\nsuch as by intimate data communication or control flow between those\nsubprograms and other parts of the work.\n\n  The Corresponding Source need not include anything that users\ncan regenerate automatically from other parts of the Corresponding\nSource.\n\n  The Corresponding Source for a work in source code form is that\nsame work.\n\n  2. Basic Permissions.\n\n  All rights granted under this License are granted for the term of\ncopyright on the Program, and are irrevocable provided the stated\nconditions are met.  This License explicitly affirms your unlimited\npermission to run the unmodified Program.  The output from running a\ncovered work is covered by this License only if the output, given its\ncontent, constitutes a covered work.  This License acknowledges your\nrights of fair use or other equivalent, as provided by copyright law.\n\n  You may make, run and propagate covered works that you do not\nconvey, without conditions so long as your license otherwise remains\nin force.  You may convey covered works to others for the sole purpose\nof having them make modifications exclusively for you, or provide you\nwith facilities for running those works, provided that you comply with\nthe terms of this License in conveying all material for which you do\nnot control copyright.  Those thus making or running the covered works\nfor you must do so exclusively on your behalf, under your direction\nand control, on terms that prohibit them from making any copies of\nyour copyrighted material outside their relationship with you.\n\n  Conveying under any other circumstances is permitted solely under\nthe conditions stated below.  Sublicensing is not allowed; section 10\nmakes it unnecessary.\n\n  3. Protecting Users' Legal Rights From Anti-Circumvention Law.\n\n  No covered work shall be deemed part of an effective technological\nmeasure under any applicable law fulfilling obligations under article\n11 of the WIPO copyright treaty adopted on 20 December 1996, or\nsimilar laws prohibiting or restricting circumvention of such\nmeasures.\n\n  When you convey a covered work, you waive any legal power to forbid\ncircumvention of technological measures to the extent such circumvention\nis effected by exercising rights under this License with respect to\nthe covered work, and you disclaim any intention to limit operation or\nmodification of the work as a means of enforcing, against the work's\nusers, your or third parties' legal rights to forbid circumvention of\ntechnological measures.\n\n  4. Conveying Verbatim Copies.\n\n  You may convey verbatim copies of the Program's source code as you\nreceive it, in any medium, provided that you conspicuously and\nappropriately publish on each copy an appropriate copyright notice;\nkeep intact all notices stating that this License and any\nnon-permissive terms added in accord with section 7 apply to the code;\nkeep intact all notices of the absence of any warranty; and give all\nrecipients a copy of this License along with the Program.\n\n  You may charge any price or no price for each copy that you convey,\nand you may offer support or warranty protection for a fee.\n\n  5. Conveying Modified Source Versions.\n\n  You may convey a work based on the Program, or the modifications to\nproduce it from the Program, in the form of source code under the\nterms of section 4, provided that you also meet all of these conditions:\n\n    a) The work must carry prominent notices stating that you modified\n    it, and giving a relevant date.\n\n    b) The work must carry prominent notices stating that it is\n    released under this License and any conditions added under section\n    7.  This requirement modifies the requirement in section 4 to\n    \"keep intact all notices\".\n\n    c) You must license the entire work, as a whole, under this\n    License to anyone who comes into possession of a copy.  This\n    License will therefore apply, along with any applicable section 7\n    additional terms, to the whole of the work, and all its parts,\n    regardless of how they are packaged.  This License gives no\n    permission to license the work in any other way, but it does not\n    invalidate such permission if you have separately received it.\n\n    d) If the work has interactive user interfaces, each must display\n    Appropriate Legal Notices; however, if the Program has interactive\n    interfaces that do not display Appropriate Legal Notices, your\n    work need not make them do so.\n\n  A compilation of a covered work with other separate and independent\nworks, which are not by their nature extensions of the covered work,\nand which are not combined with it such as to form a larger program,\nin or on a volume of a storage or distribution medium, is called an\n\"aggregate\" if the compilation and its resulting copyright are not\nused to limit the access or legal rights of the compilation's users\nbeyond what the individual works permit.  Inclusion of a covered work\nin an aggregate does not cause this License to apply to the other\nparts of the aggregate.\n\n  6. Conveying Non-Source Forms.\n\n  You may convey a covered work in object code form under the terms\nof sections 4 and 5, provided that you also convey the\nmachine-readable Corresponding Source under the terms of this License,\nin one of these ways:\n\n    a) Convey the object code in, or embodied in, a physical product\n    (including a physical distribution medium), accompanied by the\n    Corresponding Source fixed on a durable physical medium\n    customarily used for software interchange.\n\n    b) Convey the object code in, or embodied in, a physical product\n    (including a physical distribution medium), accompanied by a\n    written offer, valid for at least three years and valid for as\n    long as you offer spare parts or customer support for that product\n    model, to give anyone who possesses the object code either (1) a\n    copy of the Corresponding Source for all the software in the\n    product that is covered by this License, on a durable physical\n    medium customarily used for software interchange, for a price no\n    more than your reasonable cost of physically performing this\n    conveying of source, or (2) access to copy the\n    Corresponding Source from a network server at no charge.\n\n    c) Convey individual copies of the object code with a copy of the\n    written offer to provide the Corresponding Source.  This\n    alternative is allowed only occasionally and noncommercially, and\n    only if you received the object code with such an offer, in accord\n    with subsection 6b.\n\n    d) Convey the object code by offering access from a designated\n    place (gratis or for a charge), and offer equivalent access to the\n    Corresponding Source in the same way through the same place at no\n    further charge.  You need not require recipients to copy the\n    Corresponding Source along with the object code.  If the place to\n    copy the object code is a network server, the Corresponding Source\n    may be on a different server (operated by you or a third party)\n    that supports equivalent copying facilities, provided you maintain\n    clear directions next to the object code saying where to find the\n    Corresponding Source.  Regardless of what server hosts the\n    Corresponding Source, you remain obligated to ensure that it is\n    available for as long as needed to satisfy these requirements.\n\n    e) Convey the object code using peer-to-peer transmission, provided\n    you inform other peers where the object code and Corresponding\n    Source of the work are being offered to the general public at no\n    charge under subsection 6d.\n\n  A separable portion of the object code, whose source code is excluded\nfrom the Corresponding Source as a System Library, need not be\nincluded in conveying the object code work.\n\n  A \"User Product\" is either (1) a \"consumer product\", which means any\ntangible personal property which is normally used for personal, family,\nor household purposes, or (2) anything designed or sold for incorporation\ninto a dwelling.  In determining whether a product is a consumer product,\ndoubtful cases shall be resolved in favor of coverage.  For a particular\nproduct received by a particular user, \"normally used\" refers to a\ntypical or common use of that class of product, regardless of the status\nof the particular user or of the way in which the particular user\nactually uses, or expects or is expected to use, the product.  A product\nis a consumer product regardless of whether the product has substantial\ncommercial, industrial or non-consumer uses, unless such uses represent\nthe only significant mode of use of the product.\n\n  \"Installation Information\" for a User Product means any methods,\nprocedures, authorization keys, or other information required to install\nand execute modified versions of a covered work in that User Product from\na modified version of its Corresponding Source.  The information must\nsuffice to ensure that the continued functioning of the modified object\ncode is in no case prevented or interfered with solely because\nmodification has been made.\n\n  If you convey an object code work under this section in, or with, or\nspecifically for use in, a User Product, and the conveying occurs as\npart of a transaction in which the right of possession and use of the\nUser Product is transferred to the recipient in perpetuity or for a\nfixed term (regardless of how the transaction is characterized), the\nCorresponding Source conveyed under this section must be accompanied\nby the Installation Information.  But this requirement does not apply\nif neither you nor any third party retains the ability to install\nmodified object code on the User Product (for example, the work has\nbeen installed in ROM).\n\n  The requirement to provide Installation Information does not include a\nrequirement to continue to provide support service, warranty, or updates\nfor a work that has been modified or installed by the recipient, or for\nthe User Product in which it has been modified or installed.  Access to a\nnetwork may be denied when the modification itself materially and\nadversely affects the operation of the network or violates the rules and\nprotocols for communication across the network.\n\n  Corresponding Source conveyed, and Installation Information provided,\nin accord with this section must be in a format that is publicly\ndocumented (and with an implementation available to the public in\nsource code form), and must require no special password or key for\nunpacking, reading or copying.\n\n  7. Additional Terms.\n\n  \"Additional permissions\" are terms that supplement the terms of this\nLicense by making exceptions from one or more of its conditions.\nAdditional permissions that are applicable to the entire Program shall\nbe treated as though they were included in this License, to the extent\nthat they are valid under applicable law.  If additional permissions\napply only to part of the Program, that part may be used separately\nunder those permissions, but the entire Program remains governed by\nthis License without regard to the additional permissions.\n\n  When you convey a copy of a covered work, you may at your option\nremove any additional permissions from that copy, or from any part of\nit.  (Additional permissions may be written to require their own\nremoval in certain cases when you modify the work.)  You may place\nadditional permissions on material, added by you to a covered work,\nfor which you have or can give appropriate copyright permission.\n\n  Notwithstanding any other provision of this License, for material you\nadd to a covered work, you may (if authorized by the copyright holders of\nthat material) supplement the terms of this License with terms:\n\n    a) Disclaiming warranty or limiting liability differently from the\n    terms of sections 15 and 16 of this License; or\n\n    b) Requiring preservation of specified reasonable legal notices or\n    author attributions in that material or in the Appropriate Legal\n    Notices displayed by works containing it; or\n\n    c) Prohibiting misrepresentation of the origin of that material, or\n    requiring that modified versions of such material be marked in\n    reasonable ways as different from the original version; or\n\n    d) Limiting the use for publicity purposes of names of licensors or\n    authors of the material; or\n\n    e) Declining to grant rights under trademark law for use of some\n    trade names, trademarks, or service marks; or\n\n    f) Requiring indemnification of licensors and authors of that\n    material by anyone who conveys the material (or modified versions of\n    it) with contractual assumptions of liability to the recipient, for\n    any liability that these contractual assumptions directly impose on\n    those licensors and authors.\n\n  All other non-permissive additional terms are considered \"further\nrestrictions\" within the meaning of section 10.  If the Program as you\nreceived it, or any part of it, contains a notice stating that it is\ngoverned by this License along with a term that is a further\nrestriction, you may remove that term.  If a license document contains\na further restriction but permits relicensing or conveying under this\nLicense, you may add to a covered work material governed by the terms\nof that license document, provided that the further restriction does\nnot survive such relicensing or conveying.\n\n  If you add terms to a covered work in accord with this section, you\nmust place, in the relevant source files, a statement of the\nadditional terms that apply to those files, or a notice indicating\nwhere to find the applicable terms.\n\n  Additional terms, permissive or non-permissive, may be stated in the\nform of a separately written license, or stated as exceptions;\nthe above requirements apply either way.\n\n  8. Termination.\n\n  You may not propagate or modify a covered work except as expressly\nprovided under this License.  Any attempt otherwise to propagate or\nmodify it is void, and will automatically terminate your rights under\nthis License (including any patent licenses granted under the third\nparagraph of section 11).\n\n  However, if you cease all violation of this License, then your\nlicense from a particular copyright holder is reinstated (a)\nprovisionally, unless and until the copyright holder explicitly and\nfinally terminates your license, and (b) permanently, if the copyright\nholder fails to notify you of the violation by some reasonable means\nprior to 60 days after the cessation.\n\n  Moreover, your license from a particular copyright holder is\nreinstated permanently if the copyright holder notifies you of the\nviolation by some reasonable means, this is the first time you have\nreceived notice of violation of this License (for any work) from that\ncopyright holder, and you cure the violation prior to 30 days after\nyour receipt of the notice.\n\n  Termination of your rights under this section does not terminate the\nlicenses of parties who have received copies or rights from you under\nthis License.  If your rights have been terminated and not permanently\nreinstated, you do not qualify to receive new licenses for the same\nmaterial under section 10.\n\n  9. Acceptance Not Required for Having Copies.\n\n  You are not required to accept this License in order to receive or\nrun a copy of the Program.  Ancillary propagation of a covered work\noccurring solely as a consequence of using peer-to-peer transmission\nto receive a copy likewise does not require acceptance.  However,\nnothing other than this License grants you permission to propagate or\nmodify any covered work.  These actions infringe copyright if you do\nnot accept this License.  Therefore, by modifying or propagating a\ncovered work, you indicate your acceptance of this License to do so.\n\n  10. Automatic Licensing of Downstream Recipients.\n\n  Each time you convey a covered work, the recipient automatically\nreceives a license from the original licensors, to run, modify and\npropagate that work, subject to this License.  You are not responsible\nfor enforcing compliance by third parties with this License.\n\n  An \"entity transaction\" is a transaction transferring control of an\norganization, or substantially all assets of one, or subdividing an\norganization, or merging organizations.  If propagation of a covered\nwork results from an entity transaction, each party to that\ntransaction who receives a copy of the work also receives whatever\nlicenses to the work the party's predecessor in interest had or could\ngive under the previous paragraph, plus a right to possession of the\nCorresponding Source of the work from the predecessor in interest, if\nthe predecessor has it or can get it with reasonable efforts.\n\n  You may not impose any further restrictions on the exercise of the\nrights granted or affirmed under this License.  For example, you may\nnot impose a license fee, royalty, or other charge for exercise of\nrights granted under this License, and you may not initiate litigation\n(including a cross-claim or counterclaim in a lawsuit) alleging that\nany patent claim is infringed by making, using, selling, offering for\nsale, or importing the Program or any portion of it.\n\n  11. Patents.\n\n  A \"contributor\" is a copyright holder who authorizes use under this\nLicense of the Program or a work on which the Program is based.  The\nwork thus licensed is called the contributor's \"contributor version\".\n\n  A contributor's \"essential patent claims\" are all patent claims\nowned or controlled by the contributor, whether already acquired or\nhereafter acquired, that would be infringed by some manner, permitted\nby this License, of making, using, or selling its contributor version,\nbut do not include claims that would be infringed only as a\nconsequence of further modification of the contributor version.  For\npurposes of this definition, \"control\" includes the right to grant\npatent sublicenses in a manner consistent with the requirements of\nthis License.\n\n  Each contributor grants you a non-exclusive, worldwide, royalty-free\npatent license under the contributor's essential patent claims, to\nmake, use, sell, offer for sale, import and otherwise run, modify and\npropagate the contents of its contributor version.\n\n  In the following three paragraphs, a \"patent license\" is any express\nagreement or commitment, however denominated, not to enforce a patent\n(such as an express permission to practice a patent or covenant not to\nsue for patent infringement).  To \"grant\" such a patent license to a\nparty means to make such an agreement or commitment not to enforce a\npatent against the party.\n\n  If you convey a covered work, knowingly relying on a patent license,\nand the Corresponding Source of the work is not available for anyone\nto copy, free of charge and under the terms of this License, through a\npublicly available network server or other readily accessible means,\nthen you must either (1) cause the Corresponding Source to be so\navailable, or (2) arrange to deprive yourself of the benefit of the\npatent license for this particular work, or (3) arrange, in a manner\nconsistent with the requirements of this License, to extend the patent\nlicense to downstream recipients.  \"Knowingly relying\" means you have\nactual knowledge that, but for the patent license, your conveying the\ncovered work in a country, or your recipient's use of the covered work\nin a country, would infringe one or more identifiable patents in that\ncountry that you have reason to believe are valid.\n\n  If, pursuant to or in connection with a single transaction or\narrangement, you convey, or propagate by procuring conveyance of, a\ncovered work, and grant a patent license to some of the parties\nreceiving the covered work authorizing them to use, propagate, modify\nor convey a specific copy of the covered work, then the patent license\nyou grant is automatically extended to all recipients of the covered\nwork and works based on it.\n\n  A patent license is \"discriminatory\" if it does not include within\nthe scope of its coverage, prohibits the exercise of, or is\nconditioned on the non-exercise of one or more of the rights that are\nspecifically granted under this License.  You may not convey a covered\nwork if you are a party to an arrangement with a third party that is\nin the business of distributing software, under which you make payment\nto the third party based on the extent of your activity of conveying\nthe work, and under which the third party grants, to any of the\nparties who would receive the covered work from you, a discriminatory\npatent license (a) in connection with copies of the covered work\nconveyed by you (or copies made from those copies), or (b) primarily\nfor and in connection with specific products or compilations that\ncontain the covered work, unless you entered into that arrangement,\nor that patent license was granted, prior to 28 March 2007.\n\n  Nothing in this License shall be construed as excluding or limiting\nany implied license or other defenses to infringement that may\notherwise be available to you under applicable patent law.\n\n  12. No Surrender of Others' Freedom.\n\n  If conditions are imposed on you (whether by court order, agreement or\notherwise) that contradict the conditions of this License, they do not\nexcuse you from the conditions of this License.  If you cannot convey a\ncovered work so as to satisfy simultaneously your obligations under this\nLicense and any other pertinent obligations, then as a consequence you may\nnot convey it at all.  For example, if you agree to terms that obligate you\nto collect a royalty for further conveying from those to whom you convey\nthe Program, the only way you could satisfy both those terms and this\nLicense would be to refrain entirely from conveying the Program.\n\n  13. Use with the GNU Affero General Public License.\n\n  Notwithstanding any other provision of this License, you have\npermission to link or combine any covered work with a work licensed\nunder version 3 of the GNU Affero General Public License into a single\ncombined work, and to convey the resulting work.  The terms of this\nLicense will continue to apply to the part which is the covered work,\nbut the special requirements of the GNU Affero General Public License,\nsection 13, concerning interaction through a network will apply to the\ncombination as such.\n\n  14. Revised Versions of this License.\n\n  The Free Software Foundation may publish revised and/or new versions of\nthe GNU General Public License from time to time.  Such new versions will\nbe similar in spirit to the present version, but may differ in detail to\naddress new problems or concerns.\n\n  Each version is given a distinguishing version number.  If the\nProgram specifies that a certain numbered version of the GNU General\nPublic License \"or any later version\" applies to it, you have the\noption of following the terms and conditions either of that numbered\nversion or of any later version published by the Free Software\nFoundation.  If the Program does not specify a version number of the\nGNU General Public License, you may choose any version ever published\nby the Free Software Foundation.\n\n  If the Program specifies that a proxy can decide which future\nversions of the GNU General Public License can be used, that proxy's\npublic statement of acceptance of a version permanently authorizes you\nto choose that version for the Program.\n\n  Later license versions may give you additional or different\npermissions.  However, no additional obligations are imposed on any\nauthor or copyright holder as a result of your choosing to follow a\nlater version.\n\n  15. Disclaimer of Warranty.\n\n  THERE IS NO WARRANTY FOR THE PROGRAM, TO THE EXTENT PERMITTED BY\nAPPLICABLE LAW.  EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT\nHOLDERS AND/OR OTHER PARTIES PROVIDE THE PROGRAM \"AS IS\" WITHOUT WARRANTY\nOF ANY KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO,\nTHE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR\nPURPOSE.  THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE PROGRAM\nIS WITH YOU.  SHOULD THE PROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF\nALL NECESSARY SERVICING, REPAIR OR CORRECTION.\n\n  16. Limitation of Liability.\n\n  IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING\nWILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MODIFIES AND/OR CONVEYS\nTHE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES, INCLUDING ANY\nGENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING OUT OF THE\nUSE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED TO LOSS OF\nDATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD\nPARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER PROGRAMS),\nEVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF\nSUCH DAMAGES.\n\n  17. Interpretation of Sections 15 and 16.\n\n  If the disclaimer of warranty and limitation of liability provided\nabove cannot be given local legal effect according to their terms,\nreviewing courts shall apply local law that most closely approximates\nan absolute waiver of all civil liability in connection with the\nProgram, unless a warranty or assumption of liability accompanies a\ncopy of the Program in return for a fee.\n\n                     END OF TERMS AND CONDITIONS\n\n            How to Apply These Terms to Your New Programs\n\n  If you develop a new program, and you want it to be of the greatest\npossible use to the public, the best way to achieve this is to make it\nfree software which everyone can redistribute and change under these terms.\n\n  To do so, attach the following notices to the program.  It is safest\nto attach them to the start of each source file to most effectively\nstate the exclusion of warranty; and each file should have at least\nthe \"copyright\" line and a pointer to where the full notice is found.\n\n    <one line to give the program's name and a brief idea of what it does.>\n    Copyright (C) <year>  <name of author>\n\n    This program is free software: you can redistribute it and/or modify\n    it under the terms of the GNU General Public License as published by\n    the Free Software Foundation, either version 3 of the License, or\n    (at your option) any later version.\n\n    This program is distributed in the hope that it will be useful,\n    but WITHOUT ANY WARRANTY; without even the implied warranty of\n    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n    GNU General Public License for more details.\n\n    You should have received a copy of the GNU General Public License\n    along with this program.  If not, see <http://www.gnu.org/licenses/>.\n\nAlso add information on how to contact you by electronic and paper mail.\n\n  If the program does terminal interaction, make it output a short\nnotice like this when it starts in an interactive mode:\n\n    <program>  Copyright (C) <year>  <name of author>\n    This program comes with ABSOLUTELY NO WARRANTY; for details type `show w'.\n    This is free software, and you are welcome to redistribute it\n    under certain conditions; type `show c' for details.\n\nThe hypothetical commands `show w' and `show c' should show the appropriate\nparts of the General Public License.  Of course, your program's commands\nmight be different; for a GUI interface, you would use an \"about box\".\n\n  You should also get your employer (if you work as a programmer) or school,\nif any, to sign a \"copyright disclaimer\" for the program, if necessary.\nFor more information on this, and how to apply and follow the GNU GPL, see\n<http://www.gnu.org/licenses/>.\n\n  The GNU General Public License does not permit incorporating your program\ninto proprietary programs.  If your program is a subroutine library, you\nmay consider it more useful to permit linking proprietary applications with\nthe library.  If this is what you want to do, use the GNU Lesser General\nPublic License instead of this License.  But first, please read\n<http://www.gnu.org/philosophy/why-not-lgpl.html>.\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/COPYING.LGPL",
    "content": "                  GNU LESSER GENERAL PUBLIC LICENSE\n                       Version 2.1, February 1999\n\n Copyright (C) 1991, 1999 Free Software Foundation, Inc.\n 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA\n Everyone is permitted to copy and distribute verbatim copies\n of this license document, but changing it is not allowed.\n\n[This is the first released version of the Lesser GPL.  It also counts\n as the successor of the GNU Library Public License, version 2, hence\n the version number 2.1.]\n\n                            Preamble\n\n  The licenses for most software are designed to take away your\nfreedom to share and change it.  By contrast, the GNU General Public\nLicenses are intended to guarantee your freedom to share and change\nfree software--to make sure the software is free for all its users.\n\n  This license, the Lesser General Public License, applies to some\nspecially designated software packages--typically libraries--of the\nFree Software Foundation and other authors who decide to use it.  You\ncan use it too, but we suggest you first think carefully about whether\nthis license or the ordinary General Public License is the better\nstrategy to use in any particular case, based on the explanations below.\n\n  When we speak of free software, we are referring to freedom of use,\nnot price.  Our General Public Licenses are designed to make sure that\nyou have the freedom to distribute copies of free software (and charge\nfor this service if you wish); that you receive source code or can get\nit if you want it; that you can change the software and use pieces of\nit in new free programs; and that you are informed that you can do\nthese things.\n\n  To protect your rights, we need to make restrictions that forbid\ndistributors to deny you these rights or to ask you to surrender these\nrights.  These restrictions translate to certain responsibilities for\nyou if you distribute copies of the library or if you modify it.\n\n  For example, if you distribute copies of the library, whether gratis\nor for a fee, you must give the recipients all the rights that we gave\nyou.  You must make sure that they, too, receive or can get the source\ncode.  If you link other code with the library, you must provide\ncomplete object files to the recipients, so that they can relink them\nwith the library after making changes to the library and recompiling\nit.  And you must show them these terms so they know their rights.\n\n  We protect your rights with a two-step method: (1) we copyright the\nlibrary, and (2) we offer you this license, which gives you legal\npermission to copy, distribute and/or modify the library.\n\n  To protect each distributor, we want to make it very clear that\nthere is no warranty for the free library.  Also, if the library is\nmodified by someone else and passed on, the recipients should know\nthat what they have is not the original version, so that the original\nauthor's reputation will not be affected by problems that might be\nintroduced by others.\n\f\n  Finally, software patents pose a constant threat to the existence of\nany free program.  We wish to make sure that a company cannot\neffectively restrict the users of a free program by obtaining a\nrestrictive license from a patent holder.  Therefore, we insist that\nany patent license obtained for a version of the library must be\nconsistent with the full freedom of use specified in this license.\n\n  Most GNU software, including some libraries, is covered by the\nordinary GNU General Public License.  This license, the GNU Lesser\nGeneral Public License, applies to certain designated libraries, and\nis quite different from the ordinary General Public License.  We use\nthis license for certain libraries in order to permit linking those\nlibraries into non-free programs.\n\n  When a program is linked with a library, whether statically or using\na shared library, the combination of the two is legally speaking a\ncombined work, a derivative of the original library.  The ordinary\nGeneral Public License therefore permits such linking only if the\nentire combination fits its criteria of freedom.  The Lesser General\nPublic License permits more lax criteria for linking other code with\nthe library.\n\n  We call this license the \"Lesser\" General Public License because it\ndoes Less to protect the user's freedom than the ordinary General\nPublic License.  It also provides other free software developers Less\nof an advantage over competing non-free programs.  These disadvantages\nare the reason we use the ordinary General Public License for many\nlibraries.  However, the Lesser license provides advantages in certain\nspecial circumstances.\n\n  For example, on rare occasions, there may be a special need to\nencourage the widest possible use of a certain library, so that it becomes\na de-facto standard.  To achieve this, non-free programs must be\nallowed to use the library.  A more frequent case is that a free\nlibrary does the same job as widely used non-free libraries.  In this\ncase, there is little to gain by limiting the free library to free\nsoftware only, so we use the Lesser General Public License.\n\n  In other cases, permission to use a particular library in non-free\nprograms enables a greater number of people to use a large body of\nfree software.  For example, permission to use the GNU C Library in\nnon-free programs enables many more people to use the whole GNU\noperating system, as well as its variant, the GNU/Linux operating\nsystem.\n\n  Although the Lesser General Public License is Less protective of the\nusers' freedom, it does ensure that the user of a program that is\nlinked with the Library has the freedom and the wherewithal to run\nthat program using a modified version of the Library.\n\n  The precise terms and conditions for copying, distribution and\nmodification follow.  Pay close attention to the difference between a\n\"work based on the library\" and a \"work that uses the library\".  The\nformer contains code derived from the library, whereas the latter must\nbe combined with the library in order to run.\n\f\n                  GNU LESSER GENERAL PUBLIC LICENSE\n   TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION\n\n  0. This License Agreement applies to any software library or other\nprogram which contains a notice placed by the copyright holder or\nother authorized party saying it may be distributed under the terms of\nthis Lesser General Public License (also called \"this License\").\nEach licensee is addressed as \"you\".\n\n  A \"library\" means a collection of software functions and/or data\nprepared so as to be conveniently linked with application programs\n(which use some of those functions and data) to form executables.\n\n  The \"Library\", below, refers to any such software library or work\nwhich has been distributed under these terms.  A \"work based on the\nLibrary\" means either the Library or any derivative work under\ncopyright law: that is to say, a work containing the Library or a\nportion of it, either verbatim or with modifications and/or translated\nstraightforwardly into another language.  (Hereinafter, translation is\nincluded without limitation in the term \"modification\".)\n\n  \"Source code\" for a work means the preferred form of the work for\nmaking modifications to it.  For a library, complete source code means\nall the source code for all modules it contains, plus any associated\ninterface definition files, plus the scripts used to control compilation\nand installation of the library.\n\n  Activities other than copying, distribution and modification are not\ncovered by this License; they are outside its scope.  The act of\nrunning a program using the Library is not restricted, and output from\nsuch a program is covered only if its contents constitute a work based\non the Library (independent of the use of the Library in a tool for\nwriting it).  Whether that is true depends on what the Library does\nand what the program that uses the Library does.\n\n  1. You may copy and distribute verbatim copies of the Library's\ncomplete source code as you receive it, in any medium, provided that\nyou conspicuously and appropriately publish on each copy an\nappropriate copyright notice and disclaimer of warranty; keep intact\nall the notices that refer to this License and to the absence of any\nwarranty; and distribute a copy of this License along with the\nLibrary.\n\n  You may charge a fee for the physical act of transferring a copy,\nand you may at your option offer warranty protection in exchange for a\nfee.\n\f\n  2. You may modify your copy or copies of the Library or any portion\nof it, thus forming a work based on the Library, and copy and\ndistribute such modifications or work under the terms of Section 1\nabove, provided that you also meet all of these conditions:\n\n    a) The modified work must itself be a software library.\n\n    b) You must cause the files modified to carry prominent notices\n    stating that you changed the files and the date of any change.\n\n    c) You must cause the whole of the work to be licensed at no\n    charge to all third parties under the terms of this License.\n\n    d) If a facility in the modified Library refers to a function or a\n    table of data to be supplied by an application program that uses\n    the facility, other than as an argument passed when the facility\n    is invoked, then you must make a good faith effort to ensure that,\n    in the event an application does not supply such function or\n    table, the facility still operates, and performs whatever part of\n    its purpose remains meaningful.\n\n    (For example, a function in a library to compute square roots has\n    a purpose that is entirely well-defined independent of the\n    application.  Therefore, Subsection 2d requires that any\n    application-supplied function or table used by this function must\n    be optional: if the application does not supply it, the square\n    root function must still compute square roots.)\n\nThese requirements apply to the modified work as a whole.  If\nidentifiable sections of that work are not derived from the Library,\nand can be reasonably considered independent and separate works in\nthemselves, then this License, and its terms, do not apply to those\nsections when you distribute them as separate works.  But when you\ndistribute the same sections as part of a whole which is a work based\non the Library, the distribution of the whole must be on the terms of\nthis License, whose permissions for other licensees extend to the\nentire whole, and thus to each and every part regardless of who wrote\nit.\n\nThus, it is not the intent of this section to claim rights or contest\nyour rights to work written entirely by you; rather, the intent is to\nexercise the right to control the distribution of derivative or\ncollective works based on the Library.\n\nIn addition, mere aggregation of another work not based on the Library\nwith the Library (or with a work based on the Library) on a volume of\na storage or distribution medium does not bring the other work under\nthe scope of this License.\n\n  3. You may opt to apply the terms of the ordinary GNU General Public\nLicense instead of this License to a given copy of the Library.  To do\nthis, you must alter all the notices that refer to this License, so\nthat they refer to the ordinary GNU General Public License, version 2,\ninstead of to this License.  (If a newer version than version 2 of the\nordinary GNU General Public License has appeared, then you can specify\nthat version instead if you wish.)  Do not make any other change in\nthese notices.\n\f\n  Once this change is made in a given copy, it is irreversible for\nthat copy, so the ordinary GNU General Public License applies to all\nsubsequent copies and derivative works made from that copy.\n\n  This option is useful when you wish to copy part of the code of\nthe Library into a program that is not a library.\n\n  4. You may copy and distribute the Library (or a portion or\nderivative of it, under Section 2) in object code or executable form\nunder the terms of Sections 1 and 2 above provided that you accompany\nit with the complete corresponding machine-readable source code, which\nmust be distributed under the terms of Sections 1 and 2 above on a\nmedium customarily used for software interchange.\n\n  If distribution of object code is made by offering access to copy\nfrom a designated place, then offering equivalent access to copy the\nsource code from the same place satisfies the requirement to\ndistribute the source code, even though third parties are not\ncompelled to copy the source along with the object code.\n\n  5. A program that contains no derivative of any portion of the\nLibrary, but is designed to work with the Library by being compiled or\nlinked with it, is called a \"work that uses the Library\".  Such a\nwork, in isolation, is not a derivative work of the Library, and\ntherefore falls outside the scope of this License.\n\n  However, linking a \"work that uses the Library\" with the Library\ncreates an executable that is a derivative of the Library (because it\ncontains portions of the Library), rather than a \"work that uses the\nlibrary\".  The executable is therefore covered by this License.\nSection 6 states terms for distribution of such executables.\n\n  When a \"work that uses the Library\" uses material from a header file\nthat is part of the Library, the object code for the work may be a\nderivative work of the Library even though the source code is not.\nWhether this is true is especially significant if the work can be\nlinked without the Library, or if the work is itself a library.  The\nthreshold for this to be true is not precisely defined by law.\n\n  If such an object file uses only numerical parameters, data\nstructure layouts and accessors, and small macros and small inline\nfunctions (ten lines or less in length), then the use of the object\nfile is unrestricted, regardless of whether it is legally a derivative\nwork.  (Executables containing this object code plus portions of the\nLibrary will still fall under Section 6.)\n\n  Otherwise, if the work is a derivative of the Library, you may\ndistribute the object code for the work under the terms of Section 6.\nAny executables containing that work also fall under Section 6,\nwhether or not they are linked directly with the Library itself.\n\f\n  6. As an exception to the Sections above, you may also combine or\nlink a \"work that uses the Library\" with the Library to produce a\nwork containing portions of the Library, and distribute that work\nunder terms of your choice, provided that the terms permit\nmodification of the work for the customer's own use and reverse\nengineering for debugging such modifications.\n\n  You must give prominent notice with each copy of the work that the\nLibrary is used in it and that the Library and its use are covered by\nthis License.  You must supply a copy of this License.  If the work\nduring execution displays copyright notices, you must include the\ncopyright notice for the Library among them, as well as a reference\ndirecting the user to the copy of this License.  Also, you must do one\nof these things:\n\n    a) Accompany the work with the complete corresponding\n    machine-readable source code for the Library including whatever\n    changes were used in the work (which must be distributed under\n    Sections 1 and 2 above); and, if the work is an executable linked\n    with the Library, with the complete machine-readable \"work that\n    uses the Library\", as object code and/or source code, so that the\n    user can modify the Library and then relink to produce a modified\n    executable containing the modified Library.  (It is understood\n    that the user who changes the contents of definitions files in the\n    Library will not necessarily be able to recompile the application\n    to use the modified definitions.)\n\n    b) Use a suitable shared library mechanism for linking with the\n    Library.  A suitable mechanism is one that (1) uses at run time a\n    copy of the library already present on the user's computer system,\n    rather than copying library functions into the executable, and (2)\n    will operate properly with a modified version of the library, if\n    the user installs one, as long as the modified version is\n    interface-compatible with the version that the work was made with.\n\n    c) Accompany the work with a written offer, valid for at\n    least three years, to give the same user the materials\n    specified in Subsection 6a, above, for a charge no more\n    than the cost of performing this distribution.\n\n    d) If distribution of the work is made by offering access to copy\n    from a designated place, offer equivalent access to copy the above\n    specified materials from the same place.\n\n    e) Verify that the user has already received a copy of these\n    materials or that you have already sent this user a copy.\n\n  For an executable, the required form of the \"work that uses the\nLibrary\" must include any data and utility programs needed for\nreproducing the executable from it.  However, as a special exception,\nthe materials to be distributed need not include anything that is\nnormally distributed (in either source or binary form) with the major\ncomponents (compiler, kernel, and so on) of the operating system on\nwhich the executable runs, unless that component itself accompanies\nthe executable.\n\n  It may happen that this requirement contradicts the license\nrestrictions of other proprietary libraries that do not normally\naccompany the operating system.  Such a contradiction means you cannot\nuse both them and the Library together in an executable that you\ndistribute.\n\f\n  7. You may place library facilities that are a work based on the\nLibrary side-by-side in a single library together with other library\nfacilities not covered by this License, and distribute such a combined\nlibrary, provided that the separate distribution of the work based on\nthe Library and of the other library facilities is otherwise\npermitted, and provided that you do these two things:\n\n    a) Accompany the combined library with a copy of the same work\n    based on the Library, uncombined with any other library\n    facilities.  This must be distributed under the terms of the\n    Sections above.\n\n    b) Give prominent notice with the combined library of the fact\n    that part of it is a work based on the Library, and explaining\n    where to find the accompanying uncombined form of the same work.\n\n  8. You may not copy, modify, sublicense, link with, or distribute\nthe Library except as expressly provided under this License.  Any\nattempt otherwise to copy, modify, sublicense, link with, or\ndistribute the Library is void, and will automatically terminate your\nrights under this License.  However, parties who have received copies,\nor rights, from you under this License will not have their licenses\nterminated so long as such parties remain in full compliance.\n\n  9. You are not required to accept this License, since you have not\nsigned it.  However, nothing else grants you permission to modify or\ndistribute the Library or its derivative works.  These actions are\nprohibited by law if you do not accept this License.  Therefore, by\nmodifying or distributing the Library (or any work based on the\nLibrary), you indicate your acceptance of this License to do so, and\nall its terms and conditions for copying, distributing or modifying\nthe Library or works based on it.\n\n  10. Each time you redistribute the Library (or any work based on the\nLibrary), the recipient automatically receives a license from the\noriginal licensor to copy, distribute, link with or modify the Library\nsubject to these terms and conditions.  You may not impose any further\nrestrictions on the recipients' exercise of the rights granted herein.\nYou are not responsible for enforcing compliance by third parties with\nthis License.\n\f\n  11. If, as a consequence of a court judgment or allegation of patent\ninfringement or for any other reason (not limited to patent issues),\nconditions are imposed on you (whether by court order, agreement or\notherwise) that contradict the conditions of this License, they do not\nexcuse you from the conditions of this License.  If you cannot\ndistribute so as to satisfy simultaneously your obligations under this\nLicense and any other pertinent obligations, then as a consequence you\nmay not distribute the Library at all.  For example, if a patent\nlicense would not permit royalty-free redistribution of the Library by\nall those who receive copies directly or indirectly through you, then\nthe only way you could satisfy both it and this License would be to\nrefrain entirely from distribution of the Library.\n\nIf any portion of this section is held invalid or unenforceable under any\nparticular circumstance, the balance of the section is intended to apply,\nand the section as a whole is intended to apply in other circumstances.\n\nIt is not the purpose of this section to induce you to infringe any\npatents or other property right claims or to contest validity of any\nsuch claims; this section has the sole purpose of protecting the\nintegrity of the free software distribution system which is\nimplemented by public license practices.  Many people have made\ngenerous contributions to the wide range of software distributed\nthrough that system in reliance on consistent application of that\nsystem; it is up to the author/donor to decide if he or she is willing\nto distribute software through any other system and a licensee cannot\nimpose that choice.\n\nThis section is intended to make thoroughly clear what is believed to\nbe a consequence of the rest of this License.\n\n  12. If the distribution and/or use of the Library is restricted in\ncertain countries either by patents or by copyrighted interfaces, the\noriginal copyright holder who places the Library under this License may add\nan explicit geographical distribution limitation excluding those countries,\nso that distribution is permitted only in or among countries not thus\nexcluded.  In such case, this License incorporates the limitation as if\nwritten in the body of this License.\n\n  13. The Free Software Foundation may publish revised and/or new\nversions of the Lesser General Public License from time to time.\nSuch new versions will be similar in spirit to the present version,\nbut may differ in detail to address new problems or concerns.\n\nEach version is given a distinguishing version number.  If the Library\nspecifies a version number of this License which applies to it and\n\"any later version\", you have the option of following the terms and\nconditions either of that version or of any later version published by\nthe Free Software Foundation.  If the Library does not specify a\nlicense version number, you may choose any version ever published by\nthe Free Software Foundation.\n\f\n  14. If you wish to incorporate parts of the Library into other free\nprograms whose distribution conditions are incompatible with these,\nwrite to the author to ask for permission.  For software which is\ncopyrighted by the Free Software Foundation, write to the Free\nSoftware Foundation; we sometimes make exceptions for this.  Our\ndecision will be guided by the two goals of preserving the free status\nof all derivatives of our free software and of promoting the sharing\nand reuse of software generally.\n\n                            NO WARRANTY\n\n  15. BECAUSE THE LIBRARY IS LICENSED FREE OF CHARGE, THERE IS NO\nWARRANTY FOR THE LIBRARY, TO THE EXTENT PERMITTED BY APPLICABLE LAW.\nEXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR\nOTHER PARTIES PROVIDE THE LIBRARY \"AS IS\" WITHOUT WARRANTY OF ANY\nKIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE\nIMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR\nPURPOSE.  THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE\nLIBRARY IS WITH YOU.  SHOULD THE LIBRARY PROVE DEFECTIVE, YOU ASSUME\nTHE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION.\n\n  16. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN\nWRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY\nAND/OR REDISTRIBUTE THE LIBRARY AS PERMITTED ABOVE, BE LIABLE TO YOU\nFOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR\nCONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE\nLIBRARY (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING\nRENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A\nFAILURE OF THE LIBRARY TO OPERATE WITH ANY OTHER SOFTWARE), EVEN IF\nSUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH\nDAMAGES.\n\n                     END OF TERMS AND CONDITIONS\n\f\n           How to Apply These Terms to Your New Libraries\n\n  If you develop a new library, and you want it to be of the greatest\npossible use to the public, we recommend making it free software that\neveryone can redistribute and change.  You can do so by permitting\nredistribution under these terms (or, alternatively, under the terms of the\nordinary General Public License).\n\n  To apply these terms, attach the following notices to the library.  It is\nsafest to attach them to the start of each source file to most effectively\nconvey the exclusion of warranty; and each file should have at least the\n\"copyright\" line and a pointer to where the full notice is found.\n\n    <one line to give the library's name and a brief idea of what it does.>\n    Copyright (C) <year>  <name of author>\n\n    This library is free software; you can redistribute it and/or\n    modify it under the terms of the GNU Lesser General Public\n    License as published by the Free Software Foundation; either\n    version 2.1 of the License, or (at your option) any later version.\n\n    This library is distributed in the hope that it will be useful,\n    but WITHOUT ANY WARRANTY; without even the implied warranty of\n    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the GNU\n    Lesser General Public License for more details.\n\n    You should have received a copy of the GNU Lesser General Public\n    License along with this library; if not, write to the Free Software\n    Foundation, Inc., 51 Franklin Street, Fifth Floor, Boston, MA  02110-1301  USA\n\nAlso add information on how to contact you by electronic and paper mail.\n\nYou should also get your employer (if you work as a programmer) or your\nschool, if any, to sign a \"copyright disclaimer\" for the library, if\nnecessary.  Here is a sample; alter the names:\n\n  Yoyodyne, Inc., hereby disclaims all copyright interest in the\n  library `Frob' (a library for tweaking knobs) written by James Random Hacker.\n\n  <signature of Ty Coon>, 1 April 1990\n  Ty Coon, President of Vice\n\nThat's all there is to it!\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/COPYING.MINPACK",
    "content": "Minpack Copyright Notice (1999) University of Chicago.  All rights reserved\n\nRedistribution and use in source and binary forms, with or\nwithout modification, are permitted provided that the\nfollowing conditions are met:\n\n1. Redistributions of source code must retain the above\ncopyright notice, this list of conditions and the following\ndisclaimer.\n\n2. Redistributions in binary form must reproduce the above\ncopyright notice, this list of conditions and the following\ndisclaimer in the documentation and/or other materials\nprovided with the distribution.\n\n3. The end-user documentation included with the\nredistribution, if any, must include the following\nacknowledgment:\n\n   \"This product includes software developed by the\n   University of Chicago, as Operator of Argonne National\n   Laboratory.\n\nAlternately, this acknowledgment may appear in the software\nitself, if and wherever such third-party acknowledgments\nnormally appear.\n\n4. WARRANTY DISCLAIMER. THE SOFTWARE IS SUPPLIED \"AS IS\"\nWITHOUT WARRANTY OF ANY KIND. THE COPYRIGHT HOLDER, THE\nUNITED STATES, THE UNITED STATES DEPARTMENT OF ENERGY, AND\nTHEIR EMPLOYEES: (1) DISCLAIM ANY WARRANTIES, EXPRESS OR\nIMPLIED, INCLUDING BUT NOT LIMITED TO ANY IMPLIED WARRANTIES\nOF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, TITLE\nOR NON-INFRINGEMENT, (2) DO NOT ASSUME ANY LEGAL LIABILITY\nOR RESPONSIBILITY FOR THE ACCURACY, COMPLETENESS, OR\nUSEFULNESS OF THE SOFTWARE, (3) DO NOT REPRESENT THAT USE OF\nTHE SOFTWARE WOULD NOT INFRINGE PRIVATELY OWNED RIGHTS, (4)\nDO NOT WARRANT THAT THE SOFTWARE WILL FUNCTION\nUNINTERRUPTED, THAT IT IS ERROR-FREE OR THAT ANY ERRORS WILL\nBE CORRECTED.\n\n5. LIMITATION OF LIABILITY. IN NO EVENT WILL THE COPYRIGHT\nHOLDER, THE UNITED STATES, THE UNITED STATES DEPARTMENT OF\nENERGY, OR THEIR EMPLOYEES: BE LIABLE FOR ANY INDIRECT,\nINCIDENTAL, CONSEQUENTIAL, SPECIAL OR PUNITIVE DAMAGES OF\nANY KIND OR NATURE, INCLUDING BUT NOT LIMITED TO LOSS OF\nPROFITS OR LOSS OF DATA, FOR ANY REASON WHATSOEVER, WHETHER\nSUCH LIABILITY IS ASSERTED ON THE BASIS OF CONTRACT, TORT\n(INCLUDING NEGLIGENCE OR STRICT LIABILITY), OR OTHERWISE,\nEVEN IF ANY OF SAID PARTIES HAS BEEN WARNED OF THE\nPOSSIBILITY OF SUCH LOSS OR DAMAGES.\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/COPYING.MPL2",
    "content": "Mozilla Public License Version 2.0\n==================================\n\n1. Definitions\n--------------\n\n1.1. \"Contributor\"\n    means each individual or legal entity that creates, contributes to\n    the creation of, or owns Covered Software.\n\n1.2. \"Contributor Version\"\n    means the combination of the Contributions of others (if any) used\n    by a Contributor and that particular Contributor's Contribution.\n\n1.3. \"Contribution\"\n    means Covered Software of a particular Contributor.\n\n1.4. \"Covered Software\"\n    means Source Code Form to which the initial Contributor has attached\n    the notice in Exhibit A, the Executable Form of such Source Code\n    Form, and Modifications of such Source Code Form, in each case\n    including portions thereof.\n\n1.5. \"Incompatible With Secondary Licenses\"\n    means\n\n    (a) that the initial Contributor has attached the notice described\n        in Exhibit B to the Covered Software; or\n\n    (b) that the Covered Software was made available under the terms of\n        version 1.1 or earlier of the License, but not also under the\n        terms of a Secondary License.\n\n1.6. \"Executable Form\"\n    means any form of the work other than Source Code Form.\n\n1.7. \"Larger Work\"\n    means a work that combines Covered Software with other material, in \n    a separate file or files, that is not Covered Software.\n\n1.8. \"License\"\n    means this document.\n\n1.9. \"Licensable\"\n    means having the right to grant, to the maximum extent possible,\n    whether at the time of the initial grant or subsequently, any and\n    all of the rights conveyed by this License.\n\n1.10. \"Modifications\"\n    means any of the following:\n\n    (a) any file in Source Code Form that results from an addition to,\n        deletion from, or modification of the contents of Covered\n        Software; or\n\n    (b) any new file in Source Code Form that contains any Covered\n        Software.\n\n1.11. \"Patent Claims\" of a Contributor\n    means any patent claim(s), including without limitation, method,\n    process, and apparatus claims, in any patent Licensable by such\n    Contributor that would be infringed, but for the grant of the\n    License, by the making, using, selling, offering for sale, having\n    made, import, or transfer of either its Contributions or its\n    Contributor Version.\n\n1.12. \"Secondary License\"\n    means either the GNU General Public License, Version 2.0, the GNU\n    Lesser General Public License, Version 2.1, the GNU Affero General\n    Public License, Version 3.0, or any later versions of those\n    licenses.\n\n1.13. \"Source Code Form\"\n    means the form of the work preferred for making modifications.\n\n1.14. \"You\" (or \"Your\")\n    means an individual or a legal entity exercising rights under this\n    License. For legal entities, \"You\" includes any entity that\n    controls, is controlled by, or is under common control with You. For\n    purposes of this definition, \"control\" means (a) the power, direct\n    or indirect, to cause the direction or management of such entity,\n    whether by contract or otherwise, or (b) ownership of more than\n    fifty percent (50%) of the outstanding shares or beneficial\n    ownership of such entity.\n\n2. License Grants and Conditions\n--------------------------------\n\n2.1. Grants\n\nEach Contributor hereby grants You a world-wide, royalty-free,\nnon-exclusive license:\n\n(a) under intellectual property rights (other than patent or trademark)\n    Licensable by such Contributor to use, reproduce, make available,\n    modify, display, perform, distribute, and otherwise exploit its\n    Contributions, either on an unmodified basis, with Modifications, or\n    as part of a Larger Work; and\n\n(b) under Patent Claims of such Contributor to make, use, sell, offer\n    for sale, have made, import, and otherwise transfer either its\n    Contributions or its Contributor Version.\n\n2.2. Effective Date\n\nThe licenses granted in Section 2.1 with respect to any Contribution\nbecome effective for each Contribution on the date the Contributor first\ndistributes such Contribution.\n\n2.3. Limitations on Grant Scope\n\nThe licenses granted in this Section 2 are the only rights granted under\nthis License. No additional rights or licenses will be implied from the\ndistribution or licensing of Covered Software under this License.\nNotwithstanding Section 2.1(b) above, no patent license is granted by a\nContributor:\n\n(a) for any code that a Contributor has removed from Covered Software;\n    or\n\n(b) for infringements caused by: (i) Your and any other third party's\n    modifications of Covered Software, or (ii) the combination of its\n    Contributions with other software (except as part of its Contributor\n    Version); or\n\n(c) under Patent Claims infringed by Covered Software in the absence of\n    its Contributions.\n\nThis License does not grant any rights in the trademarks, service marks,\nor logos of any Contributor (except as may be necessary to comply with\nthe notice requirements in Section 3.4).\n\n2.4. Subsequent Licenses\n\nNo Contributor makes additional grants as a result of Your choice to\ndistribute the Covered Software under a subsequent version of this\nLicense (see Section 10.2) or under the terms of a Secondary License (if\npermitted under the terms of Section 3.3).\n\n2.5. Representation\n\nEach Contributor represents that the Contributor believes its\nContributions are its original creation(s) or it has sufficient rights\nto grant the rights to its Contributions conveyed by this License.\n\n2.6. Fair Use\n\nThis License is not intended to limit any rights You have under\napplicable copyright doctrines of fair use, fair dealing, or other\nequivalents.\n\n2.7. Conditions\n\nSections 3.1, 3.2, 3.3, and 3.4 are conditions of the licenses granted\nin Section 2.1.\n\n3. Responsibilities\n-------------------\n\n3.1. Distribution of Source Form\n\nAll distribution of Covered Software in Source Code Form, including any\nModifications that You create or to which You contribute, must be under\nthe terms of this License. You must inform recipients that the Source\nCode Form of the Covered Software is governed by the terms of this\nLicense, and how they can obtain a copy of this License. You may not\nattempt to alter or restrict the recipients' rights in the Source Code\nForm.\n\n3.2. Distribution of Executable Form\n\nIf You distribute Covered Software in Executable Form then:\n\n(a) such Covered Software must also be made available in Source Code\n    Form, as described in Section 3.1, and You must inform recipients of\n    the Executable Form how they can obtain a copy of such Source Code\n    Form by reasonable means in a timely manner, at a charge no more\n    than the cost of distribution to the recipient; and\n\n(b) You may distribute such Executable Form under the terms of this\n    License, or sublicense it under different terms, provided that the\n    license for the Executable Form does not attempt to limit or alter\n    the recipients' rights in the Source Code Form under this License.\n\n3.3. Distribution of a Larger Work\n\nYou may create and distribute a Larger Work under terms of Your choice,\nprovided that You also comply with the requirements of this License for\nthe Covered Software. If the Larger Work is a combination of Covered\nSoftware with a work governed by one or more Secondary Licenses, and the\nCovered Software is not Incompatible With Secondary Licenses, this\nLicense permits You to additionally distribute such Covered Software\nunder the terms of such Secondary License(s), so that the recipient of\nthe Larger Work may, at their option, further distribute the Covered\nSoftware under the terms of either this License or such Secondary\nLicense(s).\n\n3.4. Notices\n\nYou may not remove or alter the substance of any license notices\n(including copyright notices, patent notices, disclaimers of warranty,\nor limitations of liability) contained within the Source Code Form of\nthe Covered Software, except that You may alter any license notices to\nthe extent required to remedy known factual inaccuracies.\n\n3.5. Application of Additional Terms\n\nYou may choose to offer, and to charge a fee for, warranty, support,\nindemnity or liability obligations to one or more recipients of Covered\nSoftware. However, You may do so only on Your own behalf, and not on\nbehalf of any Contributor. You must make it absolutely clear that any\nsuch warranty, support, indemnity, or liability obligation is offered by\nYou alone, and You hereby agree to indemnify every Contributor for any\nliability incurred by such Contributor as a result of warranty, support,\nindemnity or liability terms You offer. You may include additional\ndisclaimers of warranty and limitations of liability specific to any\njurisdiction.\n\n4. Inability to Comply Due to Statute or Regulation\n---------------------------------------------------\n\nIf it is impossible for You to comply with any of the terms of this\nLicense with respect to some or all of the Covered Software due to\nstatute, judicial order, or regulation then You must: (a) comply with\nthe terms of this License to the maximum extent possible; and (b)\ndescribe the limitations and the code they affect. Such description must\nbe placed in a text file included with all distributions of the Covered\nSoftware under this License. Except to the extent prohibited by statute\nor regulation, such description must be sufficiently detailed for a\nrecipient of ordinary skill to be able to understand it.\n\n5. Termination\n--------------\n\n5.1. The rights granted under this License will terminate automatically\nif You fail to comply with any of its terms. However, if You become\ncompliant, then the rights granted under this License from a particular\nContributor are reinstated (a) provisionally, unless and until such\nContributor explicitly and finally terminates Your grants, and (b) on an\nongoing basis, if such Contributor fails to notify You of the\nnon-compliance by some reasonable means prior to 60 days after You have\ncome back into compliance. Moreover, Your grants from a particular\nContributor are reinstated on an ongoing basis if such Contributor\nnotifies You of the non-compliance by some reasonable means, this is the\nfirst time You have received notice of non-compliance with this License\nfrom such Contributor, and You become compliant prior to 30 days after\nYour receipt of the notice.\n\n5.2. If You initiate litigation against any entity by asserting a patent\ninfringement claim (excluding declaratory judgment actions,\ncounter-claims, and cross-claims) alleging that a Contributor Version\ndirectly or indirectly infringes any patent, then the rights granted to\nYou by any and all Contributors for the Covered Software under Section\n2.1 of this License shall terminate.\n\n5.3. In the event of termination under Sections 5.1 or 5.2 above, all\nend user license agreements (excluding distributors and resellers) which\nhave been validly granted by You or Your distributors under this License\nprior to termination shall survive termination.\n\n************************************************************************\n*                                                                      *\n*  6. Disclaimer of Warranty                                           *\n*  -------------------------                                           *\n*                                                                      *\n*  Covered Software is provided under this License on an \"as is\"       *\n*  basis, without warranty of any kind, either expressed, implied, or  *\n*  statutory, including, without limitation, warranties that the       *\n*  Covered Software is free of defects, merchantable, fit for a        *\n*  particular purpose or non-infringing. The entire risk as to the     *\n*  quality and performance of the Covered Software is with You.        *\n*  Should any Covered Software prove defective in any respect, You     *\n*  (not any Contributor) assume the cost of any necessary servicing,   *\n*  repair, or correction. This disclaimer of warranty constitutes an   *\n*  essential part of this License. No use of any Covered Software is   *\n*  authorized under this License except under this disclaimer.         *\n*                                                                      *\n************************************************************************\n\n************************************************************************\n*                                                                      *\n*  7. Limitation of Liability                                          *\n*  --------------------------                                          *\n*                                                                      *\n*  Under no circumstances and under no legal theory, whether tort      *\n*  (including negligence), contract, or otherwise, shall any           *\n*  Contributor, or anyone who distributes Covered Software as          *\n*  permitted above, be liable to You for any direct, indirect,         *\n*  special, incidental, or consequential damages of any character      *\n*  including, without limitation, damages for lost profits, loss of    *\n*  goodwill, work stoppage, computer failure or malfunction, or any    *\n*  and all other commercial damages or losses, even if such party      *\n*  shall have been informed of the possibility of such damages. This   *\n*  limitation of liability shall not apply to liability for death or   *\n*  personal injury resulting from such party's negligence to the       *\n*  extent applicable law prohibits such limitation. Some               *\n*  jurisdictions do not allow the exclusion or limitation of           *\n*  incidental or consequential damages, so this exclusion and          *\n*  limitation may not apply to You.                                    *\n*                                                                      *\n************************************************************************\n\n8. Litigation\n-------------\n\nAny litigation relating to this License may be brought only in the\ncourts of a jurisdiction where the defendant maintains its principal\nplace of business and such litigation shall be governed by laws of that\njurisdiction, without reference to its conflict-of-law provisions.\nNothing in this Section shall prevent a party's ability to bring\ncross-claims or counter-claims.\n\n9. Miscellaneous\n----------------\n\nThis License represents the complete agreement concerning the subject\nmatter hereof. If any provision of this License is held to be\nunenforceable, such provision shall be reformed only to the extent\nnecessary to make it enforceable. Any law or regulation which provides\nthat the language of a contract shall be construed against the drafter\nshall not be used to construe this License against a Contributor.\n\n10. Versions of the License\n---------------------------\n\n10.1. New Versions\n\nMozilla Foundation is the license steward. Except as provided in Section\n10.3, no one other than the license steward has the right to modify or\npublish new versions of this License. Each version will be given a\ndistinguishing version number.\n\n10.2. Effect of New Versions\n\nYou may distribute the Covered Software under the terms of the version\nof the License under which You originally received the Covered Software,\nor under the terms of any subsequent version published by the license\nsteward.\n\n10.3. Modified Versions\n\nIf you create software not governed by this License, and you want to\ncreate a new license for such software, you may create and use a\nmodified version of this License if you rename the license and remove\nany references to the name of the license steward (except to note that\nsuch modified license differs from this License).\n\n10.4. Distributing Source Code Form that is Incompatible With Secondary\nLicenses\n\nIf You choose to distribute Source Code Form that is Incompatible With\nSecondary Licenses under the terms of this version of the License, the\nnotice described in Exhibit B of this License must be attached.\n\nExhibit A - Source Code Form License Notice\n-------------------------------------------\n\n  This Source Code Form is subject to the terms of the Mozilla Public\n  License, v. 2.0. If a copy of the MPL was not distributed with this\n  file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\nIf it is not possible or desirable to put the notice in a particular\nfile, then You may include the notice in a location (such as a LICENSE\nfile in a relevant directory) where a recipient would be likely to look\nfor such a notice.\n\nYou may add additional accurate notices of copyright ownership.\n\nExhibit B - \"Incompatible With Secondary Licenses\" Notice\n---------------------------------------------------------\n\n  This Source Code Form is \"Incompatible With Secondary Licenses\", as\n  defined by the Mozilla Public License, v. 2.0.\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/COPYING.README",
    "content": "Eigen is primarily MPL2 licensed. See COPYING.MPL2 and these links:\n  http://www.mozilla.org/MPL/2.0/\n  http://www.mozilla.org/MPL/2.0/FAQ.html\n\nSome files contain third-party code under BSD or LGPL licenses, whence the other\nCOPYING.* files here.\n\nAll the LGPL code is either LGPL 2.1-only, or LGPL 2.1-or-later.\nFor this reason, the COPYING.LGPL file contains the LGPL 2.1 text.\n\nIf you want to guarantee that the Eigen code that you are #including is licensed\nunder the MPL2 and possibly more permissive licenses (like BSD), #define this\npreprocessor symbol:\n  EIGEN_MPL2_ONLY\nFor example, with most compilers, you could add this to your project CXXFLAGS:\n  -DEIGEN_MPL2_ONLY\nThis will cause a compilation error to be generated if you #include any code that is\nLGPL licensed.\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/CTestConfig.cmake",
    "content": "## This file should be placed in the root directory of your project.\n## Then modify the CMakeLists.txt file in the root directory of your\n## project to incorporate the testing dashboard.\n## # The following are required to uses Dart and the Cdash dashboard\n##   enable_testing()\n##   include(CTest)\nset(CTEST_PROJECT_NAME \"Eigen\")\nset(CTEST_NIGHTLY_START_TIME \"00:00:00 UTC\")\n\nset(CTEST_DROP_METHOD \"http\")\nset(CTEST_DROP_SITE \"my.cdash.org\")\nset(CTEST_DROP_LOCATION \"/submit.php?project=Eigen\")\nset(CTEST_DROP_SITE_CDASH TRUE)\n#set(CTEST_PROJECT_SUBPROJECTS\n#Official\n#Unsupported\n#)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/CTestCustom.cmake.in",
    "content": "\nset(CTEST_CUSTOM_MAXIMUM_NUMBER_OF_WARNINGS \"2000\")\nset(CTEST_CUSTOM_MAXIMUM_NUMBER_OF_ERRORS   \"2000\")\nlist(APPEND CTEST_CUSTOM_ERROR_EXCEPTION    @EIGEN_CTEST_ERROR_EXCEPTION@)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/Cholesky",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CHOLESKY_MODULE_H\n#define EIGEN_CHOLESKY_MODULE_H\n\n#include \"Core\"\n#include \"Jacobi\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \\defgroup Cholesky_Module Cholesky module\n  *\n  *\n  *\n  * This module provides two variants of the Cholesky decomposition for selfadjoint (hermitian) matrices.\n  * Those decompositions are also accessible via the following methods:\n  *  - MatrixBase::llt()\n  *  - MatrixBase::ldlt()\n  *  - SelfAdjointView::llt()\n  *  - SelfAdjointView::ldlt()\n  *\n  * \\code\n  * #include <Eigen/Cholesky>\n  * \\endcode\n  */\n\n#include \"src/Cholesky/LLT.h\"\n#include \"src/Cholesky/LDLT.h\"\n#ifdef EIGEN_USE_LAPACKE\n#ifdef EIGEN_USE_MKL\n#include \"mkl_lapacke.h\"\n#else\n#include \"src/misc/lapacke.h\"\n#endif\n#include \"src/Cholesky/LLT_LAPACKE.h\"\n#endif\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_CHOLESKY_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/CholmodSupport",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CHOLMODSUPPORT_MODULE_H\n#define EIGEN_CHOLMODSUPPORT_MODULE_H\n\n#include \"SparseCore\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\nextern \"C\" {\n  #include <cholmod.h>\n}\n\n/** \\ingroup Support_modules\n  * \\defgroup CholmodSupport_Module CholmodSupport module\n  *\n  * This module provides an interface to the Cholmod library which is part of the <a href=\"http://www.suitesparse.com\">suitesparse</a> package.\n  * It provides the two following main factorization classes:\n  * - class CholmodSupernodalLLT: a supernodal LLT Cholesky factorization.\n  * - class CholmodDecomposiiton: a general L(D)LT Cholesky factorization with automatic or explicit runtime selection of the underlying factorization method (supernodal or simplicial).\n  *\n  * For the sake of completeness, this module also propose the two following classes:\n  * - class CholmodSimplicialLLT\n  * - class CholmodSimplicialLDLT\n  * Note that these classes does not bring any particular advantage compared to the built-in\n  * SimplicialLLT and SimplicialLDLT factorization classes.\n  *\n  * \\code\n  * #include <Eigen/CholmodSupport>\n  * \\endcode\n  *\n  * In order to use this module, the cholmod headers must be accessible from the include paths, and your binary must be linked to the cholmod library and its dependencies.\n  * The dependencies depend on how cholmod has been compiled.\n  * For a cmake based project, you can use our FindCholmod.cmake module to help you in this task.\n  *\n  */\n\n#include \"src/CholmodSupport/CholmodSupport.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_CHOLMODSUPPORT_MODULE_H\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/Dense",
    "content": "#include \"Core\"\n#include \"LU\"\n#include \"Cholesky\"\n#include \"QR\"\n#include \"SVD\"\n#include \"Geometry\"\n#include \"Eigenvalues\"\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/Eigen",
    "content": "#include \"Dense\"\n#include \"Sparse\"\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/Eigenvalues",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_EIGENVALUES_MODULE_H\n#define EIGEN_EIGENVALUES_MODULE_H\n\n#include \"Core\"\n\n#include \"Cholesky\"\n#include \"Jacobi\"\n#include \"Householder\"\n#include \"LU\"\n#include \"Geometry\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \\defgroup Eigenvalues_Module Eigenvalues module\n  *\n  *\n  *\n  * This module mainly provides various eigenvalue solvers.\n  * This module also provides some MatrixBase methods, including:\n  *  - MatrixBase::eigenvalues(),\n  *  - MatrixBase::operatorNorm()\n  *\n  * \\code\n  * #include <Eigen/Eigenvalues>\n  * \\endcode\n  */\n\n#include \"src/misc/RealSvd2x2.h\"\n#include \"src/Eigenvalues/Tridiagonalization.h\"\n#include \"src/Eigenvalues/RealSchur.h\"\n#include \"src/Eigenvalues/EigenSolver.h\"\n#include \"src/Eigenvalues/SelfAdjointEigenSolver.h\"\n#include \"src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h\"\n#include \"src/Eigenvalues/HessenbergDecomposition.h\"\n#include \"src/Eigenvalues/ComplexSchur.h\"\n#include \"src/Eigenvalues/ComplexEigenSolver.h\"\n#include \"src/Eigenvalues/RealQZ.h\"\n#include \"src/Eigenvalues/GeneralizedEigenSolver.h\"\n#include \"src/Eigenvalues/MatrixBaseEigenvalues.h\"\n#ifdef EIGEN_USE_LAPACKE\n#ifdef EIGEN_USE_MKL\n#include \"mkl_lapacke.h\"\n#else\n#include \"src/misc/lapacke.h\"\n#endif\n#include \"src/Eigenvalues/RealSchur_LAPACKE.h\"\n#include \"src/Eigenvalues/ComplexSchur_LAPACKE.h\"\n#include \"src/Eigenvalues/SelfAdjointEigenSolver_LAPACKE.h\"\n#endif\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_EIGENVALUES_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/Geometry",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_GEOMETRY_MODULE_H\n#define EIGEN_GEOMETRY_MODULE_H\n\n#include \"Core\"\n\n#include \"SVD\"\n#include \"LU\"\n#include <limits>\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \\defgroup Geometry_Module Geometry module\n  *\n  * This module provides support for:\n  *  - fixed-size homogeneous transformations\n  *  - translation, scaling, 2D and 3D rotations\n  *  - \\link Quaternion quaternions \\endlink\n  *  - cross products (\\ref MatrixBase::cross, \\ref MatrixBase::cross3)\n  *  - orthognal vector generation (\\ref MatrixBase::unitOrthogonal)\n  *  - some linear components: \\link ParametrizedLine parametrized-lines \\endlink and \\link Hyperplane hyperplanes \\endlink\n  *  - \\link AlignedBox axis aligned bounding boxes \\endlink\n  *  - \\link umeyama least-square transformation fitting \\endlink\n  *\n  * \\code\n  * #include <Eigen/Geometry>\n  * \\endcode\n  */\n\n#include \"src/Geometry/OrthoMethods.h\"\n#include \"src/Geometry/EulerAngles.h\"\n\n#include \"src/Geometry/Homogeneous.h\"\n#include \"src/Geometry/RotationBase.h\"\n#include \"src/Geometry/Rotation2D.h\"\n#include \"src/Geometry/Quaternion.h\"\n#include \"src/Geometry/AngleAxis.h\"\n#include \"src/Geometry/Transform.h\"\n#include \"src/Geometry/Translation.h\"\n#include \"src/Geometry/Scaling.h\"\n#include \"src/Geometry/Hyperplane.h\"\n#include \"src/Geometry/ParametrizedLine.h\"\n#include \"src/Geometry/AlignedBox.h\"\n#include \"src/Geometry/Umeyama.h\"\n\n// Use the SSE optimized version whenever possible.\n#if (defined EIGEN_VECTORIZE_SSE) || (defined EIGEN_VECTORIZE_NEON)\n#include \"src/Geometry/arch/Geometry_SIMD.h\"\n#endif\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_GEOMETRY_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/Householder",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_HOUSEHOLDER_MODULE_H\n#define EIGEN_HOUSEHOLDER_MODULE_H\n\n#include \"Core\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \\defgroup Householder_Module Householder module\n  * This module provides Householder transformations.\n  *\n  * \\code\n  * #include <Eigen/Householder>\n  * \\endcode\n  */\n\n#include \"src/Householder/Householder.h\"\n#include \"src/Householder/HouseholderSequence.h\"\n#include \"src/Householder/BlockHouseholder.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_HOUSEHOLDER_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/IterativeLinearSolvers",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ITERATIVELINEARSOLVERS_MODULE_H\n#define EIGEN_ITERATIVELINEARSOLVERS_MODULE_H\n\n#include \"SparseCore\"\n#include \"OrderingMethods\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \n  * \\defgroup IterativeLinearSolvers_Module IterativeLinearSolvers module\n  *\n  * This module currently provides iterative methods to solve problems of the form \\c A \\c x = \\c b, where \\c A is a squared matrix, usually very large and sparse.\n  * Those solvers are accessible via the following classes:\n  *  - ConjugateGradient for selfadjoint (hermitian) matrices,\n  *  - LeastSquaresConjugateGradient for rectangular least-square problems,\n  *  - BiCGSTAB for general square matrices.\n  *\n  * These iterative solvers are associated with some preconditioners:\n  *  - IdentityPreconditioner - not really useful\n  *  - DiagonalPreconditioner - also called Jacobi preconditioner, work very well on diagonal dominant matrices.\n  *  - IncompleteLUT - incomplete LU factorization with dual thresholding\n  *\n  * Such problems can also be solved using the direct sparse decomposition modules: SparseCholesky, CholmodSupport, UmfPackSupport, SuperLUSupport.\n  *\n    \\code\n    #include <Eigen/IterativeLinearSolvers>\n    \\endcode\n  */\n\n#include \"src/IterativeLinearSolvers/SolveWithGuess.h\"\n#include \"src/IterativeLinearSolvers/IterativeSolverBase.h\"\n#include \"src/IterativeLinearSolvers/BasicPreconditioners.h\"\n#include \"src/IterativeLinearSolvers/ConjugateGradient.h\"\n#include \"src/IterativeLinearSolvers/LeastSquareConjugateGradient.h\"\n#include \"src/IterativeLinearSolvers/BiCGSTAB.h\"\n#include \"src/IterativeLinearSolvers/IncompleteLUT.h\"\n#include \"src/IterativeLinearSolvers/IncompleteCholesky.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_ITERATIVELINEARSOLVERS_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/Jacobi",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_JACOBI_MODULE_H\n#define EIGEN_JACOBI_MODULE_H\n\n#include \"Core\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \\defgroup Jacobi_Module Jacobi module\n  * This module provides Jacobi and Givens rotations.\n  *\n  * \\code\n  * #include <Eigen/Jacobi>\n  * \\endcode\n  *\n  * In addition to listed classes, it defines the two following MatrixBase methods to apply a Jacobi or Givens rotation:\n  *  - MatrixBase::applyOnTheLeft()\n  *  - MatrixBase::applyOnTheRight().\n  */\n\n#include \"src/Jacobi/Jacobi.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_JACOBI_MODULE_H\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/KLUSupport",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_KLUSUPPORT_MODULE_H\n#define EIGEN_KLUSUPPORT_MODULE_H\n\n#include <Eigen/SparseCore>\n\n#include <Eigen/src/Core/util/DisableStupidWarnings.h>\n\nextern \"C\" {\n#include <btf.h>\n#include <klu.h>\n   }\n\n/** \\ingroup Support_modules\n  * \\defgroup KLUSupport_Module KLUSupport module\n  *\n  * This module provides an interface to the KLU library which is part of the <a href=\"http://www.suitesparse.com\">suitesparse</a> package.\n  * It provides the following factorization class:\n  * - class KLU: a sparse LU factorization, well-suited for circuit simulation.\n  *\n  * \\code\n  * #include <Eigen/KLUSupport>\n  * \\endcode\n  *\n  * In order to use this module, the klu and btf headers must be accessible from the include paths, and your binary must be linked to the klu library and its dependencies.\n  * The dependencies depend on how umfpack has been compiled.\n  * For a cmake based project, you can use our FindKLU.cmake module to help you in this task.\n  *\n  */\n\n#include \"src/KLUSupport/KLUSupport.h\"\n\n#include <Eigen/src/Core/util/ReenableStupidWarnings.h>\n\n#endif // EIGEN_KLUSUPPORT_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/LU",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_LU_MODULE_H\n#define EIGEN_LU_MODULE_H\n\n#include \"Core\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \\defgroup LU_Module LU module\n  * This module includes %LU decomposition and related notions such as matrix inversion and determinant.\n  * This module defines the following MatrixBase methods:\n  *  - MatrixBase::inverse()\n  *  - MatrixBase::determinant()\n  *\n  * \\code\n  * #include <Eigen/LU>\n  * \\endcode\n  */\n\n#include \"src/misc/Kernel.h\"\n#include \"src/misc/Image.h\"\n#include \"src/LU/FullPivLU.h\"\n#include \"src/LU/PartialPivLU.h\"\n#ifdef EIGEN_USE_LAPACKE\n#ifdef EIGEN_USE_MKL\n#include \"mkl_lapacke.h\"\n#else\n#include \"src/misc/lapacke.h\"\n#endif\n#include \"src/LU/PartialPivLU_LAPACKE.h\"\n#endif\n#include \"src/LU/Determinant.h\"\n#include \"src/LU/InverseImpl.h\"\n\n// Use the SSE optimized version whenever possible. At the moment the\n// SSE version doesn't compile when AVX is enabled\n#if (defined EIGEN_VECTORIZE_SSE && !defined EIGEN_VECTORIZE_AVX) || defined EIGEN_VECTORIZE_NEON\n  #include \"src/LU/arch/InverseSize4.h\"\n#endif\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_LU_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/MetisSupport",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_METISSUPPORT_MODULE_H\n#define EIGEN_METISSUPPORT_MODULE_H\n\n#include \"SparseCore\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\nextern \"C\" {\n#include <metis.h>\n}\n\n\n/** \\ingroup Support_modules\n  * \\defgroup MetisSupport_Module MetisSupport module\n  *\n  * \\code\n  * #include <Eigen/MetisSupport>\n  * \\endcode\n  * This module defines an interface to the METIS reordering package (http://glaros.dtc.umn.edu/gkhome/views/metis). \n  * It can be used just as any other built-in method as explained in \\link OrderingMethods_Module here. \\endlink\n  */\n\n\n#include \"src/MetisSupport/MetisSupport.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_METISSUPPORT_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/OrderingMethods",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ORDERINGMETHODS_MODULE_H\n#define EIGEN_ORDERINGMETHODS_MODULE_H\n\n#include \"SparseCore\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \n  * \\defgroup OrderingMethods_Module OrderingMethods module\n  *\n  * This module is currently for internal use only\n  * \n  * It defines various built-in and external ordering methods for sparse matrices. \n  * They are typically used to reduce the number of elements during \n  * the sparse matrix decomposition (LLT, LU, QR).\n  * Precisely, in a preprocessing step, a permutation matrix P is computed using \n  * those ordering methods and applied to the columns of the matrix. \n  * Using for instance the sparse Cholesky decomposition, it is expected that \n  * the nonzeros elements in LLT(A*P) will be much smaller than that in LLT(A).\n  * \n  * \n  * Usage : \n  * \\code\n  * #include <Eigen/OrderingMethods>\n  * \\endcode\n  * \n  * A simple usage is as a template parameter in the sparse decomposition classes : \n  * \n  * \\code \n  * SparseLU<MatrixType, COLAMDOrdering<int> > solver;\n  * \\endcode \n  * \n  * \\code \n  * SparseQR<MatrixType, COLAMDOrdering<int> > solver;\n  * \\endcode\n  * \n  * It is possible as well to call directly a particular ordering method for your own purpose, \n  * \\code \n  * AMDOrdering<int> ordering;\n  * PermutationMatrix<Dynamic, Dynamic, int> perm;\n  * SparseMatrix<double> A; \n  * //Fill the matrix ...\n  * \n  * ordering(A, perm); // Call AMD\n  * \\endcode\n  * \n  * \\note Some of these methods (like AMD or METIS), need the sparsity pattern \n  * of the input matrix to be symmetric. When the matrix is structurally unsymmetric, \n  * Eigen computes internally the pattern of \\f$A^T*A\\f$ before calling the method.\n  * If your matrix is already symmetric (at leat in structure), you can avoid that\n  * by calling the method with a SelfAdjointView type.\n  * \n  * \\code\n  *  // Call the ordering on the pattern of the lower triangular matrix A\n  * ordering(A.selfadjointView<Lower>(), perm);\n  * \\endcode\n  */\n\n#include \"src/OrderingMethods/Amd.h\"\n#include \"src/OrderingMethods/Ordering.h\"\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_ORDERINGMETHODS_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/PaStiXSupport",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_PASTIXSUPPORT_MODULE_H\n#define EIGEN_PASTIXSUPPORT_MODULE_H\n\n#include \"SparseCore\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\nextern \"C\" {\n#include <pastix_nompi.h>\n#include <pastix.h>\n}\n\n#ifdef complex\n#undef complex\n#endif\n\n/** \\ingroup Support_modules\n  * \\defgroup PaStiXSupport_Module PaStiXSupport module\n  * \n  * This module provides an interface to the <a href=\"http://pastix.gforge.inria.fr/\">PaSTiX</a> library.\n  * PaSTiX is a general \\b supernodal, \\b parallel and \\b opensource sparse solver.\n  * It provides the two following main factorization classes:\n  * - class PastixLLT : a supernodal, parallel LLt Cholesky factorization.\n  * - class PastixLDLT: a supernodal, parallel LDLt Cholesky factorization.\n  * - class PastixLU : a supernodal, parallel LU factorization (optimized for a symmetric pattern).\n  * \n  * \\code\n  * #include <Eigen/PaStiXSupport>\n  * \\endcode\n  *\n  * In order to use this module, the PaSTiX headers must be accessible from the include paths, and your binary must be linked to the PaSTiX library and its dependencies.\n  * This wrapper resuires PaStiX version 5.x compiled without MPI support.\n  * The dependencies depend on how PaSTiX has been compiled.\n  * For a cmake based project, you can use our FindPaSTiX.cmake module to help you in this task.\n  *\n  */\n\n#include \"src/PaStiXSupport/PaStiXSupport.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_PASTIXSUPPORT_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/PardisoSupport",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_PARDISOSUPPORT_MODULE_H\n#define EIGEN_PARDISOSUPPORT_MODULE_H\n\n#include \"SparseCore\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n#include <mkl_pardiso.h>\n\n/** \\ingroup Support_modules\n  * \\defgroup PardisoSupport_Module PardisoSupport module\n  *\n  * This module brings support for the Intel(R) MKL PARDISO direct sparse solvers.\n  *\n  * \\code\n  * #include <Eigen/PardisoSupport>\n  * \\endcode\n  *\n  * In order to use this module, the MKL headers must be accessible from the include paths, and your binary must be linked to the MKL library and its dependencies.\n  * See this \\ref TopicUsingIntelMKL \"page\" for more information on MKL-Eigen integration.\n  * \n  */\n\n#include \"src/PardisoSupport/PardisoSupport.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_PARDISOSUPPORT_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/QR",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_QR_MODULE_H\n#define EIGEN_QR_MODULE_H\n\n#include \"Core\"\n\n#include \"Cholesky\"\n#include \"Jacobi\"\n#include \"Householder\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \\defgroup QR_Module QR module\n  *\n  *\n  *\n  * This module provides various QR decompositions\n  * This module also provides some MatrixBase methods, including:\n  *  - MatrixBase::householderQr()\n  *  - MatrixBase::colPivHouseholderQr()\n  *  - MatrixBase::fullPivHouseholderQr()\n  *\n  * \\code\n  * #include <Eigen/QR>\n  * \\endcode\n  */\n\n#include \"src/QR/HouseholderQR.h\"\n#include \"src/QR/FullPivHouseholderQR.h\"\n#include \"src/QR/ColPivHouseholderQR.h\"\n#include \"src/QR/CompleteOrthogonalDecomposition.h\"\n#ifdef EIGEN_USE_LAPACKE\n#ifdef EIGEN_USE_MKL\n#include \"mkl_lapacke.h\"\n#else\n#include \"src/misc/lapacke.h\"\n#endif\n#include \"src/QR/HouseholderQR_LAPACKE.h\"\n#include \"src/QR/ColPivHouseholderQR_LAPACKE.h\"\n#endif\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_QR_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/QtAlignedMalloc",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_QTMALLOC_MODULE_H\n#define EIGEN_QTMALLOC_MODULE_H\n\n#include \"Core\"\n\n#if (!EIGEN_MALLOC_ALREADY_ALIGNED)\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\nvoid *qMalloc(std::size_t size)\n{\n  return Eigen::internal::aligned_malloc(size);\n}\n\nvoid qFree(void *ptr)\n{\n  Eigen::internal::aligned_free(ptr);\n}\n\nvoid *qRealloc(void *ptr, std::size_t size)\n{\n  void* newPtr = Eigen::internal::aligned_malloc(size);\n  std::memcpy(newPtr, ptr, size);\n  Eigen::internal::aligned_free(ptr);\n  return newPtr;\n}\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif\n\n#endif // EIGEN_QTMALLOC_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/SPQRSupport",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPQRSUPPORT_MODULE_H\n#define EIGEN_SPQRSUPPORT_MODULE_H\n\n#include \"SparseCore\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n#include \"SuiteSparseQR.hpp\"\n\n/** \\ingroup Support_modules\n  * \\defgroup SPQRSupport_Module SuiteSparseQR module\n  * \n  * This module provides an interface to the SPQR library, which is part of the <a href=\"http://www.suitesparse.com\">suitesparse</a> package.\n  *\n  * \\code\n  * #include <Eigen/SPQRSupport>\n  * \\endcode\n  *\n  * In order to use this module, the SPQR headers must be accessible from the include paths, and your binary must be linked to the SPQR library and its dependencies (Cholmod, AMD, COLAMD,...).\n  * For a cmake based project, you can use our FindSPQR.cmake and FindCholmod.Cmake modules\n  *\n  */\n\n#include \"src/CholmodSupport/CholmodSupport.h\"\n#include \"src/SPQRSupport/SuiteSparseQRSupport.h\"\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/SVD",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SVD_MODULE_H\n#define EIGEN_SVD_MODULE_H\n\n#include \"QR\"\n#include \"Householder\"\n#include \"Jacobi\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \\defgroup SVD_Module SVD module\n  *\n  *\n  *\n  * This module provides SVD decomposition for matrices (both real and complex).\n  * Two decomposition algorithms are provided:\n  *  - JacobiSVD implementing two-sided Jacobi iterations is numerically very accurate, fast for small matrices, but very slow for larger ones.\n  *  - BDCSVD implementing a recursive divide & conquer strategy on top of an upper-bidiagonalization which remains fast for large problems.\n  * These decompositions are accessible via the respective classes and following MatrixBase methods:\n  *  - MatrixBase::jacobiSvd()\n  *  - MatrixBase::bdcSvd()\n  *\n  * \\code\n  * #include <Eigen/SVD>\n  * \\endcode\n  */\n\n#include \"src/misc/RealSvd2x2.h\"\n#include \"src/SVD/UpperBidiagonalization.h\"\n#include \"src/SVD/SVDBase.h\"\n#include \"src/SVD/JacobiSVD.h\"\n#include \"src/SVD/BDCSVD.h\"\n#if defined(EIGEN_USE_LAPACKE) && !defined(EIGEN_USE_LAPACKE_STRICT)\n#ifdef EIGEN_USE_MKL\n#include \"mkl_lapacke.h\"\n#else\n#include \"src/misc/lapacke.h\"\n#endif\n#include \"src/SVD/JacobiSVD_LAPACKE.h\"\n#endif\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_SVD_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/Sparse",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_MODULE_H\n#define EIGEN_SPARSE_MODULE_H\n\n/** \\defgroup Sparse_Module Sparse meta-module\n  *\n  * Meta-module including all related modules:\n  * - \\ref SparseCore_Module\n  * - \\ref OrderingMethods_Module\n  * - \\ref SparseCholesky_Module\n  * - \\ref SparseLU_Module\n  * - \\ref SparseQR_Module\n  * - \\ref IterativeLinearSolvers_Module\n  *\n    \\code\n    #include <Eigen/Sparse>\n    \\endcode\n  */\n\n#include \"SparseCore\"\n#include \"OrderingMethods\"\n#include \"SparseCholesky\"\n#include \"SparseLU\"\n#include \"SparseQR\"\n#include \"IterativeLinearSolvers\"\n\n#endif // EIGEN_SPARSE_MODULE_H\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/SparseCholesky",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2013 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSECHOLESKY_MODULE_H\n#define EIGEN_SPARSECHOLESKY_MODULE_H\n\n#include \"SparseCore\"\n#include \"OrderingMethods\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \n  * \\defgroup SparseCholesky_Module SparseCholesky module\n  *\n  * This module currently provides two variants of the direct sparse Cholesky decomposition for selfadjoint (hermitian) matrices.\n  * Those decompositions are accessible via the following classes:\n  *  - SimplicialLLt,\n  *  - SimplicialLDLt\n  *\n  * Such problems can also be solved using the ConjugateGradient solver from the IterativeLinearSolvers module.\n  *\n  * \\code\n  * #include <Eigen/SparseCholesky>\n  * \\endcode\n  */\n\n#include \"src/SparseCholesky/SimplicialCholesky.h\"\n#include \"src/SparseCholesky/SimplicialCholesky_impl.h\"\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_SPARSECHOLESKY_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/SparseCore",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSECORE_MODULE_H\n#define EIGEN_SPARSECORE_MODULE_H\n\n#include \"Core\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n#include <vector>\n#include <map>\n#include <cstdlib>\n#include <cstring>\n#include <algorithm>\n\n/** \n  * \\defgroup SparseCore_Module SparseCore module\n  *\n  * This module provides a sparse matrix representation, and basic associated matrix manipulations\n  * and operations.\n  *\n  * See the \\ref TutorialSparse \"Sparse tutorial\"\n  *\n  * \\code\n  * #include <Eigen/SparseCore>\n  * \\endcode\n  *\n  * This module depends on: Core.\n  */\n\n#include \"src/SparseCore/SparseUtil.h\"\n#include \"src/SparseCore/SparseMatrixBase.h\"\n#include \"src/SparseCore/SparseAssign.h\"\n#include \"src/SparseCore/CompressedStorage.h\"\n#include \"src/SparseCore/AmbiVector.h\"\n#include \"src/SparseCore/SparseCompressedBase.h\"\n#include \"src/SparseCore/SparseMatrix.h\"\n#include \"src/SparseCore/SparseMap.h\"\n#include \"src/SparseCore/MappedSparseMatrix.h\"\n#include \"src/SparseCore/SparseVector.h\"\n#include \"src/SparseCore/SparseRef.h\"\n#include \"src/SparseCore/SparseCwiseUnaryOp.h\"\n#include \"src/SparseCore/SparseCwiseBinaryOp.h\"\n#include \"src/SparseCore/SparseTranspose.h\"\n#include \"src/SparseCore/SparseBlock.h\"\n#include \"src/SparseCore/SparseDot.h\"\n#include \"src/SparseCore/SparseRedux.h\"\n#include \"src/SparseCore/SparseView.h\"\n#include \"src/SparseCore/SparseDiagonalProduct.h\"\n#include \"src/SparseCore/ConservativeSparseSparseProduct.h\"\n#include \"src/SparseCore/SparseSparseProductWithPruning.h\"\n#include \"src/SparseCore/SparseProduct.h\"\n#include \"src/SparseCore/SparseDenseProduct.h\"\n#include \"src/SparseCore/SparseSelfAdjointView.h\"\n#include \"src/SparseCore/SparseTriangularView.h\"\n#include \"src/SparseCore/TriangularSolver.h\"\n#include \"src/SparseCore/SparsePermutation.h\"\n#include \"src/SparseCore/SparseFuzzy.h\"\n#include \"src/SparseCore/SparseSolverBase.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_SPARSECORE_MODULE_H\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/SparseLU",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSELU_MODULE_H\n#define EIGEN_SPARSELU_MODULE_H\n\n#include \"SparseCore\"\n\n/** \n  * \\defgroup SparseLU_Module SparseLU module\n  * This module defines a supernodal factorization of general sparse matrices.\n  * The code is fully optimized for supernode-panel updates with specialized kernels.\n  * Please, see the documentation of the SparseLU class for more details.\n  */\n\n// Ordering interface\n#include \"OrderingMethods\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n#include \"src/SparseLU/SparseLU_gemm_kernel.h\"\n\n#include \"src/SparseLU/SparseLU_Structs.h\"\n#include \"src/SparseLU/SparseLU_SupernodalMatrix.h\"\n#include \"src/SparseLU/SparseLUImpl.h\"\n#include \"src/SparseCore/SparseColEtree.h\"\n#include \"src/SparseLU/SparseLU_Memory.h\"\n#include \"src/SparseLU/SparseLU_heap_relax_snode.h\"\n#include \"src/SparseLU/SparseLU_relax_snode.h\"\n#include \"src/SparseLU/SparseLU_pivotL.h\"\n#include \"src/SparseLU/SparseLU_panel_dfs.h\"\n#include \"src/SparseLU/SparseLU_kernel_bmod.h\"\n#include \"src/SparseLU/SparseLU_panel_bmod.h\"\n#include \"src/SparseLU/SparseLU_column_dfs.h\"\n#include \"src/SparseLU/SparseLU_column_bmod.h\"\n#include \"src/SparseLU/SparseLU_copy_to_ucol.h\"\n#include \"src/SparseLU/SparseLU_pruneL.h\"\n#include \"src/SparseLU/SparseLU_Utils.h\"\n#include \"src/SparseLU/SparseLU.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_SPARSELU_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/SparseQR",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEQR_MODULE_H\n#define EIGEN_SPARSEQR_MODULE_H\n\n#include \"SparseCore\"\n#include \"OrderingMethods\"\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n/** \\defgroup SparseQR_Module SparseQR module\n  * \\brief Provides QR decomposition for sparse matrices\n  * \n  * This module provides a simplicial version of the left-looking Sparse QR decomposition. \n  * The columns of the input matrix should be reordered to limit the fill-in during the \n  * decomposition. Built-in methods (COLAMD, AMD) or external  methods (METIS) can be used to this end.\n  * See the \\link OrderingMethods_Module OrderingMethods\\endlink module for the list \n  * of built-in and external ordering methods.\n  * \n  * \\code\n  * #include <Eigen/SparseQR>\n  * \\endcode\n  * \n  * \n  */\n\n#include \"src/SparseCore/SparseColEtree.h\"\n#include \"src/SparseQR/SparseQR.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/StdDeque",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Hauke Heibel <hauke.heibel@googlemail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_STDDEQUE_MODULE_H\n#define EIGEN_STDDEQUE_MODULE_H\n\n#include \"Core\"\n#include <deque>\n\n#if EIGEN_COMP_MSVC && EIGEN_OS_WIN64 && (EIGEN_MAX_STATIC_ALIGN_BYTES<=16) /* MSVC auto aligns up to 16 bytes in 64 bit builds */\n\n#define EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(...)\n\n#else\n\n#include \"src/StlSupport/StdDeque.h\"\n\n#endif\n\n#endif // EIGEN_STDDEQUE_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/StdList",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Hauke Heibel <hauke.heibel@googlemail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_STDLIST_MODULE_H\n#define EIGEN_STDLIST_MODULE_H\n\n#include \"Core\"\n#include <list>\n\n#if EIGEN_COMP_MSVC && EIGEN_OS_WIN64 && (EIGEN_MAX_STATIC_ALIGN_BYTES<=16) /* MSVC auto aligns up to 16 bytes in 64 bit builds */\n\n#define EIGEN_DEFINE_STL_LIST_SPECIALIZATION(...)\n\n#else\n\n#include \"src/StlSupport/StdList.h\"\n\n#endif\n\n#endif // EIGEN_STDLIST_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/StdVector",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Hauke Heibel <hauke.heibel@googlemail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_STDVECTOR_MODULE_H\n#define EIGEN_STDVECTOR_MODULE_H\n\n#include \"Core\"\n#include <vector>\n\n#if EIGEN_COMP_MSVC && EIGEN_OS_WIN64 && (EIGEN_MAX_STATIC_ALIGN_BYTES<=16) /* MSVC auto aligns up to 16 bytes in 64 bit builds */\n\n#define EIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(...)\n\n#else\n\n#include \"src/StlSupport/StdVector.h\"\n\n#endif\n\n#endif // EIGEN_STDVECTOR_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/SuperLUSupport",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SUPERLUSUPPORT_MODULE_H\n#define EIGEN_SUPERLUSUPPORT_MODULE_H\n\n#include \"SparseCore\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\n#ifdef EMPTY\n#define EIGEN_EMPTY_WAS_ALREADY_DEFINED\n#endif\n\ntypedef int int_t;\n#include <slu_Cnames.h>\n#include <supermatrix.h>\n#include <slu_util.h>\n\n// slu_util.h defines a preprocessor token named EMPTY which is really polluting,\n// so we remove it in favor of a SUPERLU_EMPTY token.\n// If EMPTY was already defined then we don't undef it.\n\n#if defined(EIGEN_EMPTY_WAS_ALREADY_DEFINED)\n# undef EIGEN_EMPTY_WAS_ALREADY_DEFINED\n#elif defined(EMPTY)\n# undef EMPTY\n#endif\n\n#define SUPERLU_EMPTY (-1)\n\nnamespace Eigen { struct SluMatrix; }\n\n/** \\ingroup Support_modules\n  * \\defgroup SuperLUSupport_Module SuperLUSupport module\n  *\n  * This module provides an interface to the <a href=\"http://crd-legacy.lbl.gov/~xiaoye/SuperLU/\">SuperLU</a> library.\n  * It provides the following factorization class:\n  * - class SuperLU: a supernodal sequential LU factorization.\n  * - class SuperILU: a supernodal sequential incomplete LU factorization (to be used as a preconditioner for iterative methods).\n  *\n  * \\warning This wrapper requires at least versions 4.0 of SuperLU. The 3.x versions are not supported.\n  *\n  * \\warning When including this module, you have to use SUPERLU_EMPTY instead of EMPTY which is no longer defined because it is too polluting.\n  *\n  * \\code\n  * #include <Eigen/SuperLUSupport>\n  * \\endcode\n  *\n  * In order to use this module, the superlu headers must be accessible from the include paths, and your binary must be linked to the superlu library and its dependencies.\n  * The dependencies depend on how superlu has been compiled.\n  * For a cmake based project, you can use our FindSuperLU.cmake module to help you in this task.\n  *\n  */\n\n#include \"src/SuperLUSupport/SuperLUSupport.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_SUPERLUSUPPORT_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/UmfPackSupport",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_UMFPACKSUPPORT_MODULE_H\n#define EIGEN_UMFPACKSUPPORT_MODULE_H\n\n#include \"SparseCore\"\n\n#include \"src/Core/util/DisableStupidWarnings.h\"\n\nextern \"C\" {\n#include <umfpack.h>\n}\n\n/** \\ingroup Support_modules\n  * \\defgroup UmfPackSupport_Module UmfPackSupport module\n  *\n  * This module provides an interface to the UmfPack library which is part of the <a href=\"http://www.suitesparse.com\">suitesparse</a> package.\n  * It provides the following factorization class:\n  * - class UmfPackLU: a multifrontal sequential LU factorization.\n  *\n  * \\code\n  * #include <Eigen/UmfPackSupport>\n  * \\endcode\n  *\n  * In order to use this module, the umfpack headers must be accessible from the include paths, and your binary must be linked to the umfpack library and its dependencies.\n  * The dependencies depend on how umfpack has been compiled.\n  * For a cmake based project, you can use our FindUmfPack.cmake module to help you in this task.\n  *\n  */\n\n#include \"src/UmfPackSupport/UmfPackSupport.h\"\n\n#include \"src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_UMFPACKSUPPORT_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Cholesky/LDLT.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Keir Mierle <mierle@gmail.com>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2011 Timothy E. Holy <tim.holy@gmail.com >\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_LDLT_H\n#define EIGEN_LDLT_H\n\nnamespace Eigen {\n\nnamespace internal {\n  template<typename _MatrixType, int _UpLo> struct traits<LDLT<_MatrixType, _UpLo> >\n   : traits<_MatrixType>\n  {\n    typedef MatrixXpr XprKind;\n    typedef SolverStorage StorageKind;\n    typedef int StorageIndex;\n    enum { Flags = 0 };\n  };\n\n  template<typename MatrixType, int UpLo> struct LDLT_Traits;\n\n  // PositiveSemiDef means positive semi-definite and non-zero; same for NegativeSemiDef\n  enum SignMatrix { PositiveSemiDef, NegativeSemiDef, ZeroSign, Indefinite };\n}\n\n/** \\ingroup Cholesky_Module\n  *\n  * \\class LDLT\n  *\n  * \\brief Robust Cholesky decomposition of a matrix with pivoting\n  *\n  * \\tparam _MatrixType the type of the matrix of which to compute the LDL^T Cholesky decomposition\n  * \\tparam _UpLo the triangular part that will be used for the decompositon: Lower (default) or Upper.\n  *             The other triangular part won't be read.\n  *\n  * Perform a robust Cholesky decomposition of a positive semidefinite or negative semidefinite\n  * matrix \\f$ A \\f$ such that \\f$ A =  P^TLDL^*P \\f$, where P is a permutation matrix, L\n  * is lower triangular with a unit diagonal and D is a diagonal matrix.\n  *\n  * The decomposition uses pivoting to ensure stability, so that D will have\n  * zeros in the bottom right rank(A) - n submatrix. Avoiding the square root\n  * on D also stabilizes the computation.\n  *\n  * Remember that Cholesky decompositions are not rank-revealing. Also, do not use a Cholesky\n  * decomposition to determine whether a system of equations has a solution.\n  *\n  * This class supports the \\link InplaceDecomposition inplace decomposition \\endlink mechanism.\n  *\n  * \\sa MatrixBase::ldlt(), SelfAdjointView::ldlt(), class LLT\n  */\ntemplate<typename _MatrixType, int _UpLo> class LDLT\n        : public SolverBase<LDLT<_MatrixType, _UpLo> >\n{\n  public:\n    typedef _MatrixType MatrixType;\n    typedef SolverBase<LDLT> Base;\n    friend class SolverBase<LDLT>;\n\n    EIGEN_GENERIC_PUBLIC_INTERFACE(LDLT)\n    enum {\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime,\n      UpLo = _UpLo\n    };\n    typedef Matrix<Scalar, RowsAtCompileTime, 1, 0, MaxRowsAtCompileTime, 1> TmpMatrixType;\n\n    typedef Transpositions<RowsAtCompileTime, MaxRowsAtCompileTime> TranspositionType;\n    typedef PermutationMatrix<RowsAtCompileTime, MaxRowsAtCompileTime> PermutationType;\n\n    typedef internal::LDLT_Traits<MatrixType,UpLo> Traits;\n\n    /** \\brief Default Constructor.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via LDLT::compute(const MatrixType&).\n      */\n    LDLT()\n      : m_matrix(),\n        m_transpositions(),\n        m_sign(internal::ZeroSign),\n        m_isInitialized(false)\n    {}\n\n    /** \\brief Default Constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem \\a size.\n      * \\sa LDLT()\n      */\n    explicit LDLT(Index size)\n      : m_matrix(size, size),\n        m_transpositions(size),\n        m_temporary(size),\n        m_sign(internal::ZeroSign),\n        m_isInitialized(false)\n    {}\n\n    /** \\brief Constructor with decomposition\n      *\n      * This calculates the decomposition for the input \\a matrix.\n      *\n      * \\sa LDLT(Index size)\n      */\n    template<typename InputType>\n    explicit LDLT(const EigenBase<InputType>& matrix)\n      : m_matrix(matrix.rows(), matrix.cols()),\n        m_transpositions(matrix.rows()),\n        m_temporary(matrix.rows()),\n        m_sign(internal::ZeroSign),\n        m_isInitialized(false)\n    {\n      compute(matrix.derived());\n    }\n\n    /** \\brief Constructs a LDLT factorization from a given matrix\n      *\n      * This overloaded constructor is provided for \\link InplaceDecomposition inplace decomposition \\endlink when \\c MatrixType is a Eigen::Ref.\n      *\n      * \\sa LDLT(const EigenBase&)\n      */\n    template<typename InputType>\n    explicit LDLT(EigenBase<InputType>& matrix)\n      : m_matrix(matrix.derived()),\n        m_transpositions(matrix.rows()),\n        m_temporary(matrix.rows()),\n        m_sign(internal::ZeroSign),\n        m_isInitialized(false)\n    {\n      compute(matrix.derived());\n    }\n\n    /** Clear any existing decomposition\n     * \\sa rankUpdate(w,sigma)\n     */\n    void setZero()\n    {\n      m_isInitialized = false;\n    }\n\n    /** \\returns a view of the upper triangular matrix U */\n    inline typename Traits::MatrixU matrixU() const\n    {\n      eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n      return Traits::getU(m_matrix);\n    }\n\n    /** \\returns a view of the lower triangular matrix L */\n    inline typename Traits::MatrixL matrixL() const\n    {\n      eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n      return Traits::getL(m_matrix);\n    }\n\n    /** \\returns the permutation matrix P as a transposition sequence.\n      */\n    inline const TranspositionType& transpositionsP() const\n    {\n      eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n      return m_transpositions;\n    }\n\n    /** \\returns the coefficients of the diagonal matrix D */\n    inline Diagonal<const MatrixType> vectorD() const\n    {\n      eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n      return m_matrix.diagonal();\n    }\n\n    /** \\returns true if the matrix is positive (semidefinite) */\n    inline bool isPositive() const\n    {\n      eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n      return m_sign == internal::PositiveSemiDef || m_sign == internal::ZeroSign;\n    }\n\n    /** \\returns true if the matrix is negative (semidefinite) */\n    inline bool isNegative(void) const\n    {\n      eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n      return m_sign == internal::NegativeSemiDef || m_sign == internal::ZeroSign;\n    }\n\n    #ifdef EIGEN_PARSED_BY_DOXYGEN\n    /** \\returns a solution x of \\f$ A x = b \\f$ using the current decomposition of A.\n      *\n      * This function also supports in-place solves using the syntax <tt>x = decompositionObject.solve(x)</tt> .\n      *\n      * \\note_about_checking_solutions\n      *\n      * More precisely, this method solves \\f$ A x = b \\f$ using the decomposition \\f$ A = P^T L D L^* P \\f$\n      * by solving the systems \\f$ P^T y_1 = b \\f$, \\f$ L y_2 = y_1 \\f$, \\f$ D y_3 = y_2 \\f$,\n      * \\f$ L^* y_4 = y_3 \\f$ and \\f$ P x = y_4 \\f$ in succession. If the matrix \\f$ A \\f$ is singular, then\n      * \\f$ D \\f$ will also be singular (all the other matrices are invertible). In that case, the\n      * least-square solution of \\f$ D y_3 = y_2 \\f$ is computed. This does not mean that this function\n      * computes the least-square solution of \\f$ A x = b \\f$ if \\f$ A \\f$ is singular.\n      *\n      * \\sa MatrixBase::ldlt(), SelfAdjointView::ldlt()\n      */\n    template<typename Rhs>\n    inline const Solve<LDLT, Rhs>\n    solve(const MatrixBase<Rhs>& b) const;\n    #endif\n\n    template<typename Derived>\n    bool solveInPlace(MatrixBase<Derived> &bAndX) const;\n\n    template<typename InputType>\n    LDLT& compute(const EigenBase<InputType>& matrix);\n\n    /** \\returns an estimate of the reciprocal condition number of the matrix of\n     *  which \\c *this is the LDLT decomposition.\n     */\n    RealScalar rcond() const\n    {\n      eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n      return internal::rcond_estimate_helper(m_l1_norm, *this);\n    }\n\n    template <typename Derived>\n    LDLT& rankUpdate(const MatrixBase<Derived>& w, const RealScalar& alpha=1);\n\n    /** \\returns the internal LDLT decomposition matrix\n      *\n      * TODO: document the storage layout\n      */\n    inline const MatrixType& matrixLDLT() const\n    {\n      eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n      return m_matrix;\n    }\n\n    MatrixType reconstructedMatrix() const;\n\n    /** \\returns the adjoint of \\c *this, that is, a const reference to the decomposition itself as the underlying matrix is self-adjoint.\n      *\n      * This method is provided for compatibility with other matrix decompositions, thus enabling generic code such as:\n      * \\code x = decomposition.adjoint().solve(b) \\endcode\n      */\n    const LDLT& adjoint() const { return *this; };\n\n    EIGEN_DEVICE_FUNC inline Index rows() const { return m_matrix.rows(); }\n    EIGEN_DEVICE_FUNC inline Index cols() const { return m_matrix.cols(); }\n\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the factorization failed because of a zero pivot.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n      return m_info;\n    }\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<typename RhsType, typename DstType>\n    void _solve_impl(const RhsType &rhs, DstType &dst) const;\n\n    template<bool Conjugate, typename RhsType, typename DstType>\n    void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const;\n    #endif\n\n  protected:\n\n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n    }\n\n    /** \\internal\n      * Used to compute and store the Cholesky decomposition A = L D L^* = U^* D U.\n      * The strict upper part is used during the decomposition, the strict lower\n      * part correspond to the coefficients of L (its diagonal is equal to 1 and\n      * is not stored), and the diagonal entries correspond to D.\n      */\n    MatrixType m_matrix;\n    RealScalar m_l1_norm;\n    TranspositionType m_transpositions;\n    TmpMatrixType m_temporary;\n    internal::SignMatrix m_sign;\n    bool m_isInitialized;\n    ComputationInfo m_info;\n};\n\nnamespace internal {\n\ntemplate<int UpLo> struct ldlt_inplace;\n\ntemplate<> struct ldlt_inplace<Lower>\n{\n  template<typename MatrixType, typename TranspositionType, typename Workspace>\n  static bool unblocked(MatrixType& mat, TranspositionType& transpositions, Workspace& temp, SignMatrix& sign)\n  {\n    using std::abs;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef typename TranspositionType::StorageIndex IndexType;\n    eigen_assert(mat.rows()==mat.cols());\n    const Index size = mat.rows();\n    bool found_zero_pivot = false;\n    bool ret = true;\n\n    if (size <= 1)\n    {\n      transpositions.setIdentity();\n      if(size==0) sign = ZeroSign;\n      else if (numext::real(mat.coeff(0,0)) > static_cast<RealScalar>(0) ) sign = PositiveSemiDef;\n      else if (numext::real(mat.coeff(0,0)) < static_cast<RealScalar>(0)) sign = NegativeSemiDef;\n      else sign = ZeroSign;\n      return true;\n    }\n\n    for (Index k = 0; k < size; ++k)\n    {\n      // Find largest diagonal element\n      Index index_of_biggest_in_corner;\n      mat.diagonal().tail(size-k).cwiseAbs().maxCoeff(&index_of_biggest_in_corner);\n      index_of_biggest_in_corner += k;\n\n      transpositions.coeffRef(k) = IndexType(index_of_biggest_in_corner);\n      if(k != index_of_biggest_in_corner)\n      {\n        // apply the transposition while taking care to consider only\n        // the lower triangular part\n        Index s = size-index_of_biggest_in_corner-1; // trailing size after the biggest element\n        mat.row(k).head(k).swap(mat.row(index_of_biggest_in_corner).head(k));\n        mat.col(k).tail(s).swap(mat.col(index_of_biggest_in_corner).tail(s));\n        std::swap(mat.coeffRef(k,k),mat.coeffRef(index_of_biggest_in_corner,index_of_biggest_in_corner));\n        for(Index i=k+1;i<index_of_biggest_in_corner;++i)\n        {\n          Scalar tmp = mat.coeffRef(i,k);\n          mat.coeffRef(i,k) = numext::conj(mat.coeffRef(index_of_biggest_in_corner,i));\n          mat.coeffRef(index_of_biggest_in_corner,i) = numext::conj(tmp);\n        }\n        if(NumTraits<Scalar>::IsComplex)\n          mat.coeffRef(index_of_biggest_in_corner,k) = numext::conj(mat.coeff(index_of_biggest_in_corner,k));\n      }\n\n      // partition the matrix:\n      //       A00 |  -  |  -\n      // lu  = A10 | A11 |  -\n      //       A20 | A21 | A22\n      Index rs = size - k - 1;\n      Block<MatrixType,Dynamic,1> A21(mat,k+1,k,rs,1);\n      Block<MatrixType,1,Dynamic> A10(mat,k,0,1,k);\n      Block<MatrixType,Dynamic,Dynamic> A20(mat,k+1,0,rs,k);\n\n      if(k>0)\n      {\n        temp.head(k) = mat.diagonal().real().head(k).asDiagonal() * A10.adjoint();\n        mat.coeffRef(k,k) -= (A10 * temp.head(k)).value();\n        if(rs>0)\n          A21.noalias() -= A20 * temp.head(k);\n      }\n\n      // In some previous versions of Eigen (e.g., 3.2.1), the scaling was omitted if the pivot\n      // was smaller than the cutoff value. However, since LDLT is not rank-revealing\n      // we should only make sure that we do not introduce INF or NaN values.\n      // Remark that LAPACK also uses 0 as the cutoff value.\n      RealScalar realAkk = numext::real(mat.coeffRef(k,k));\n      bool pivot_is_valid = (abs(realAkk) > RealScalar(0));\n\n      if(k==0 && !pivot_is_valid)\n      {\n        // The entire diagonal is zero, there is nothing more to do\n        // except filling the transpositions, and checking whether the matrix is zero.\n        sign = ZeroSign;\n        for(Index j = 0; j<size; ++j)\n        {\n          transpositions.coeffRef(j) = IndexType(j);\n          ret = ret && (mat.col(j).tail(size-j-1).array()==Scalar(0)).all();\n        }\n        return ret;\n      }\n\n      if((rs>0) && pivot_is_valid)\n        A21 /= realAkk;\n      else if(rs>0)\n        ret = ret && (A21.array()==Scalar(0)).all();\n\n      if(found_zero_pivot && pivot_is_valid) ret = false; // factorization failed\n      else if(!pivot_is_valid) found_zero_pivot = true;\n\n      if (sign == PositiveSemiDef) {\n        if (realAkk < static_cast<RealScalar>(0)) sign = Indefinite;\n      } else if (sign == NegativeSemiDef) {\n        if (realAkk > static_cast<RealScalar>(0)) sign = Indefinite;\n      } else if (sign == ZeroSign) {\n        if (realAkk > static_cast<RealScalar>(0)) sign = PositiveSemiDef;\n        else if (realAkk < static_cast<RealScalar>(0)) sign = NegativeSemiDef;\n      }\n    }\n\n    return ret;\n  }\n\n  // Reference for the algorithm: Davis and Hager, \"Multiple Rank\n  // Modifications of a Sparse Cholesky Factorization\" (Algorithm 1)\n  // Trivial rearrangements of their computations (Timothy E. Holy)\n  // allow their algorithm to work for rank-1 updates even if the\n  // original matrix is not of full rank.\n  // Here only rank-1 updates are implemented, to reduce the\n  // requirement for intermediate storage and improve accuracy\n  template<typename MatrixType, typename WDerived>\n  static bool updateInPlace(MatrixType& mat, MatrixBase<WDerived>& w, const typename MatrixType::RealScalar& sigma=1)\n  {\n    using numext::isfinite;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n\n    const Index size = mat.rows();\n    eigen_assert(mat.cols() == size && w.size()==size);\n\n    RealScalar alpha = 1;\n\n    // Apply the update\n    for (Index j = 0; j < size; j++)\n    {\n      // Check for termination due to an original decomposition of low-rank\n      if (!(isfinite)(alpha))\n        break;\n\n      // Update the diagonal terms\n      RealScalar dj = numext::real(mat.coeff(j,j));\n      Scalar wj = w.coeff(j);\n      RealScalar swj2 = sigma*numext::abs2(wj);\n      RealScalar gamma = dj*alpha + swj2;\n\n      mat.coeffRef(j,j) += swj2/alpha;\n      alpha += swj2/dj;\n\n\n      // Update the terms of L\n      Index rs = size-j-1;\n      w.tail(rs) -= wj * mat.col(j).tail(rs);\n      if(gamma != 0)\n        mat.col(j).tail(rs) += (sigma*numext::conj(wj)/gamma)*w.tail(rs);\n    }\n    return true;\n  }\n\n  template<typename MatrixType, typename TranspositionType, typename Workspace, typename WType>\n  static bool update(MatrixType& mat, const TranspositionType& transpositions, Workspace& tmp, const WType& w, const typename MatrixType::RealScalar& sigma=1)\n  {\n    // Apply the permutation to the input w\n    tmp = transpositions * w;\n\n    return ldlt_inplace<Lower>::updateInPlace(mat,tmp,sigma);\n  }\n};\n\ntemplate<> struct ldlt_inplace<Upper>\n{\n  template<typename MatrixType, typename TranspositionType, typename Workspace>\n  static EIGEN_STRONG_INLINE bool unblocked(MatrixType& mat, TranspositionType& transpositions, Workspace& temp, SignMatrix& sign)\n  {\n    Transpose<MatrixType> matt(mat);\n    return ldlt_inplace<Lower>::unblocked(matt, transpositions, temp, sign);\n  }\n\n  template<typename MatrixType, typename TranspositionType, typename Workspace, typename WType>\n  static EIGEN_STRONG_INLINE bool update(MatrixType& mat, TranspositionType& transpositions, Workspace& tmp, WType& w, const typename MatrixType::RealScalar& sigma=1)\n  {\n    Transpose<MatrixType> matt(mat);\n    return ldlt_inplace<Lower>::update(matt, transpositions, tmp, w.conjugate(), sigma);\n  }\n};\n\ntemplate<typename MatrixType> struct LDLT_Traits<MatrixType,Lower>\n{\n  typedef const TriangularView<const MatrixType, UnitLower> MatrixL;\n  typedef const TriangularView<const typename MatrixType::AdjointReturnType, UnitUpper> MatrixU;\n  static inline MatrixL getL(const MatrixType& m) { return MatrixL(m); }\n  static inline MatrixU getU(const MatrixType& m) { return MatrixU(m.adjoint()); }\n};\n\ntemplate<typename MatrixType> struct LDLT_Traits<MatrixType,Upper>\n{\n  typedef const TriangularView<const typename MatrixType::AdjointReturnType, UnitLower> MatrixL;\n  typedef const TriangularView<const MatrixType, UnitUpper> MatrixU;\n  static inline MatrixL getL(const MatrixType& m) { return MatrixL(m.adjoint()); }\n  static inline MatrixU getU(const MatrixType& m) { return MatrixU(m); }\n};\n\n} // end namespace internal\n\n/** Compute / recompute the LDLT decomposition A = L D L^* = U^* D U of \\a matrix\n  */\ntemplate<typename MatrixType, int _UpLo>\ntemplate<typename InputType>\nLDLT<MatrixType,_UpLo>& LDLT<MatrixType,_UpLo>::compute(const EigenBase<InputType>& a)\n{\n  check_template_parameters();\n\n  eigen_assert(a.rows()==a.cols());\n  const Index size = a.rows();\n\n  m_matrix = a.derived();\n\n  // Compute matrix L1 norm = max abs column sum.\n  m_l1_norm = RealScalar(0);\n  // TODO move this code to SelfAdjointView\n  for (Index col = 0; col < size; ++col) {\n    RealScalar abs_col_sum;\n    if (_UpLo == Lower)\n      abs_col_sum = m_matrix.col(col).tail(size - col).template lpNorm<1>() + m_matrix.row(col).head(col).template lpNorm<1>();\n    else\n      abs_col_sum = m_matrix.col(col).head(col).template lpNorm<1>() + m_matrix.row(col).tail(size - col).template lpNorm<1>();\n    if (abs_col_sum > m_l1_norm)\n      m_l1_norm = abs_col_sum;\n  }\n\n  m_transpositions.resize(size);\n  m_isInitialized = false;\n  m_temporary.resize(size);\n  m_sign = internal::ZeroSign;\n\n  m_info = internal::ldlt_inplace<UpLo>::unblocked(m_matrix, m_transpositions, m_temporary, m_sign) ? Success : NumericalIssue;\n\n  m_isInitialized = true;\n  return *this;\n}\n\n/** Update the LDLT decomposition:  given A = L D L^T, efficiently compute the decomposition of A + sigma w w^T.\n * \\param w a vector to be incorporated into the decomposition.\n * \\param sigma a scalar, +1 for updates and -1 for \"downdates,\" which correspond to removing previously-added column vectors. Optional; default value is +1.\n * \\sa setZero()\n  */\ntemplate<typename MatrixType, int _UpLo>\ntemplate<typename Derived>\nLDLT<MatrixType,_UpLo>& LDLT<MatrixType,_UpLo>::rankUpdate(const MatrixBase<Derived>& w, const typename LDLT<MatrixType,_UpLo>::RealScalar& sigma)\n{\n  typedef typename TranspositionType::StorageIndex IndexType;\n  const Index size = w.rows();\n  if (m_isInitialized)\n  {\n    eigen_assert(m_matrix.rows()==size);\n  }\n  else\n  {\n    m_matrix.resize(size,size);\n    m_matrix.setZero();\n    m_transpositions.resize(size);\n    for (Index i = 0; i < size; i++)\n      m_transpositions.coeffRef(i) = IndexType(i);\n    m_temporary.resize(size);\n    m_sign = sigma>=0 ? internal::PositiveSemiDef : internal::NegativeSemiDef;\n    m_isInitialized = true;\n  }\n\n  internal::ldlt_inplace<UpLo>::update(m_matrix, m_transpositions, m_temporary, w, sigma);\n\n  return *this;\n}\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename _MatrixType, int _UpLo>\ntemplate<typename RhsType, typename DstType>\nvoid LDLT<_MatrixType,_UpLo>::_solve_impl(const RhsType &rhs, DstType &dst) const\n{\n  _solve_impl_transposed<true>(rhs, dst);\n}\n\ntemplate<typename _MatrixType,int _UpLo>\ntemplate<bool Conjugate, typename RhsType, typename DstType>\nvoid LDLT<_MatrixType,_UpLo>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const\n{\n  // dst = P b\n  dst = m_transpositions * rhs;\n\n  // dst = L^-1 (P b)\n  // dst = L^-*T (P b)\n  matrixL().template conjugateIf<!Conjugate>().solveInPlace(dst);\n\n  // dst = D^-* (L^-1 P b)\n  // dst = D^-1 (L^-*T P b)\n  // more precisely, use pseudo-inverse of D (see bug 241)\n  using std::abs;\n  const typename Diagonal<const MatrixType>::RealReturnType vecD(vectorD());\n  // In some previous versions, tolerance was set to the max of 1/highest (or rather numeric_limits::min())\n  // and the maximal diagonal entry * epsilon as motivated by LAPACK's xGELSS:\n  // RealScalar tolerance = numext::maxi(vecD.array().abs().maxCoeff() * NumTraits<RealScalar>::epsilon(),RealScalar(1) / NumTraits<RealScalar>::highest());\n  // However, LDLT is not rank revealing, and so adjusting the tolerance wrt to the highest\n  // diagonal element is not well justified and leads to numerical issues in some cases.\n  // Moreover, Lapack's xSYTRS routines use 0 for the tolerance.\n  // Using numeric_limits::min() gives us more robustness to denormals.\n  RealScalar tolerance = (std::numeric_limits<RealScalar>::min)();\n  for (Index i = 0; i < vecD.size(); ++i)\n  {\n    if(abs(vecD(i)) > tolerance)\n      dst.row(i) /= vecD(i);\n    else\n      dst.row(i).setZero();\n  }\n\n  // dst = L^-* (D^-* L^-1 P b)\n  // dst = L^-T (D^-1 L^-*T P b)\n  matrixL().transpose().template conjugateIf<Conjugate>().solveInPlace(dst);\n\n  // dst = P^T (L^-* D^-* L^-1 P b) = A^-1 b\n  // dst = P^-T (L^-T D^-1 L^-*T P b) = A^-1 b\n  dst = m_transpositions.transpose() * dst;\n}\n#endif\n\n/** \\internal use x = ldlt_object.solve(x);\n  *\n  * This is the \\em in-place version of solve().\n  *\n  * \\param bAndX represents both the right-hand side matrix b and result x.\n  *\n  * \\returns true always! If you need to check for existence of solutions, use another decomposition like LU, QR, or SVD.\n  *\n  * This version avoids a copy when the right hand side matrix b is not\n  * needed anymore.\n  *\n  * \\sa LDLT::solve(), MatrixBase::ldlt()\n  */\ntemplate<typename MatrixType,int _UpLo>\ntemplate<typename Derived>\nbool LDLT<MatrixType,_UpLo>::solveInPlace(MatrixBase<Derived> &bAndX) const\n{\n  eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n  eigen_assert(m_matrix.rows() == bAndX.rows());\n\n  bAndX = this->solve(bAndX);\n\n  return true;\n}\n\n/** \\returns the matrix represented by the decomposition,\n * i.e., it returns the product: P^T L D L^* P.\n * This function is provided for debug purpose. */\ntemplate<typename MatrixType, int _UpLo>\nMatrixType LDLT<MatrixType,_UpLo>::reconstructedMatrix() const\n{\n  eigen_assert(m_isInitialized && \"LDLT is not initialized.\");\n  const Index size = m_matrix.rows();\n  MatrixType res(size,size);\n\n  // P\n  res.setIdentity();\n  res = transpositionsP() * res;\n  // L^* P\n  res = matrixU() * res;\n  // D(L^*P)\n  res = vectorD().real().asDiagonal() * res;\n  // L(DL^*P)\n  res = matrixL() * res;\n  // P^T (LDL^*P)\n  res = transpositionsP().transpose() * res;\n\n  return res;\n}\n\n/** \\cholesky_module\n  * \\returns the Cholesky decomposition with full pivoting without square root of \\c *this\n  * \\sa MatrixBase::ldlt()\n  */\ntemplate<typename MatrixType, unsigned int UpLo>\ninline const LDLT<typename SelfAdjointView<MatrixType, UpLo>::PlainObject, UpLo>\nSelfAdjointView<MatrixType, UpLo>::ldlt() const\n{\n  return LDLT<PlainObject,UpLo>(m_matrix);\n}\n\n/** \\cholesky_module\n  * \\returns the Cholesky decomposition with full pivoting without square root of \\c *this\n  * \\sa SelfAdjointView::ldlt()\n  */\ntemplate<typename Derived>\ninline const LDLT<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::ldlt() const\n{\n  return LDLT<PlainObject>(derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_LDLT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Cholesky/LLT.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_LLT_H\n#define EIGEN_LLT_H\n\nnamespace Eigen {\n\nnamespace internal{\n\ntemplate<typename _MatrixType, int _UpLo> struct traits<LLT<_MatrixType, _UpLo> >\n : traits<_MatrixType>\n{\n  typedef MatrixXpr XprKind;\n  typedef SolverStorage StorageKind;\n  typedef int StorageIndex;\n  enum { Flags = 0 };\n};\n\ntemplate<typename MatrixType, int UpLo> struct LLT_Traits;\n}\n\n/** \\ingroup Cholesky_Module\n  *\n  * \\class LLT\n  *\n  * \\brief Standard Cholesky decomposition (LL^T) of a matrix and associated features\n  *\n  * \\tparam _MatrixType the type of the matrix of which we are computing the LL^T Cholesky decomposition\n  * \\tparam _UpLo the triangular part that will be used for the decompositon: Lower (default) or Upper.\n  *               The other triangular part won't be read.\n  *\n  * This class performs a LL^T Cholesky decomposition of a symmetric, positive definite\n  * matrix A such that A = LL^* = U^*U, where L is lower triangular.\n  *\n  * While the Cholesky decomposition is particularly useful to solve selfadjoint problems like  D^*D x = b,\n  * for that purpose, we recommend the Cholesky decomposition without square root which is more stable\n  * and even faster. Nevertheless, this standard Cholesky decomposition remains useful in many other\n  * situations like generalised eigen problems with hermitian matrices.\n  *\n  * Remember that Cholesky decompositions are not rank-revealing. This LLT decomposition is only stable on positive definite matrices,\n  * use LDLT instead for the semidefinite case. Also, do not use a Cholesky decomposition to determine whether a system of equations\n  * has a solution.\n  *\n  * Example: \\include LLT_example.cpp\n  * Output: \\verbinclude LLT_example.out\n  *\n  * \\b Performance: for best performance, it is recommended to use a column-major storage format\n  * with the Lower triangular part (the default), or, equivalently, a row-major storage format\n  * with the Upper triangular part. Otherwise, you might get a 20% slowdown for the full factorization\n  * step, and rank-updates can be up to 3 times slower.\n  *\n  * This class supports the \\link InplaceDecomposition inplace decomposition \\endlink mechanism.\n  *\n  * Note that during the decomposition, only the lower (or upper, as defined by _UpLo) triangular part of A is considered.\n  * Therefore, the strict lower part does not have to store correct values.\n  *\n  * \\sa MatrixBase::llt(), SelfAdjointView::llt(), class LDLT\n  */\ntemplate<typename _MatrixType, int _UpLo> class LLT\n        : public SolverBase<LLT<_MatrixType, _UpLo> >\n{\n  public:\n    typedef _MatrixType MatrixType;\n    typedef SolverBase<LLT> Base;\n    friend class SolverBase<LLT>;\n\n    EIGEN_GENERIC_PUBLIC_INTERFACE(LLT)\n    enum {\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n\n    enum {\n      PacketSize = internal::packet_traits<Scalar>::size,\n      AlignmentMask = int(PacketSize)-1,\n      UpLo = _UpLo\n    };\n\n    typedef internal::LLT_Traits<MatrixType,UpLo> Traits;\n\n    /**\n      * \\brief Default Constructor.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via LLT::compute(const MatrixType&).\n      */\n    LLT() : m_matrix(), m_isInitialized(false) {}\n\n    /** \\brief Default Constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem \\a size.\n      * \\sa LLT()\n      */\n    explicit LLT(Index size) : m_matrix(size, size),\n                    m_isInitialized(false) {}\n\n    template<typename InputType>\n    explicit LLT(const EigenBase<InputType>& matrix)\n      : m_matrix(matrix.rows(), matrix.cols()),\n        m_isInitialized(false)\n    {\n      compute(matrix.derived());\n    }\n\n    /** \\brief Constructs a LLT factorization from a given matrix\n      *\n      * This overloaded constructor is provided for \\link InplaceDecomposition inplace decomposition \\endlink when\n      * \\c MatrixType is a Eigen::Ref.\n      *\n      * \\sa LLT(const EigenBase&)\n      */\n    template<typename InputType>\n    explicit LLT(EigenBase<InputType>& matrix)\n      : m_matrix(matrix.derived()),\n        m_isInitialized(false)\n    {\n      compute(matrix.derived());\n    }\n\n    /** \\returns a view of the upper triangular matrix U */\n    inline typename Traits::MatrixU matrixU() const\n    {\n      eigen_assert(m_isInitialized && \"LLT is not initialized.\");\n      return Traits::getU(m_matrix);\n    }\n\n    /** \\returns a view of the lower triangular matrix L */\n    inline typename Traits::MatrixL matrixL() const\n    {\n      eigen_assert(m_isInitialized && \"LLT is not initialized.\");\n      return Traits::getL(m_matrix);\n    }\n\n    #ifdef EIGEN_PARSED_BY_DOXYGEN\n    /** \\returns the solution x of \\f$ A x = b \\f$ using the current decomposition of A.\n      *\n      * Since this LLT class assumes anyway that the matrix A is invertible, the solution\n      * theoretically exists and is unique regardless of b.\n      *\n      * Example: \\include LLT_solve.cpp\n      * Output: \\verbinclude LLT_solve.out\n      *\n      * \\sa solveInPlace(), MatrixBase::llt(), SelfAdjointView::llt()\n      */\n    template<typename Rhs>\n    inline const Solve<LLT, Rhs>\n    solve(const MatrixBase<Rhs>& b) const;\n    #endif\n\n    template<typename Derived>\n    void solveInPlace(const MatrixBase<Derived> &bAndX) const;\n\n    template<typename InputType>\n    LLT& compute(const EigenBase<InputType>& matrix);\n\n    /** \\returns an estimate of the reciprocal condition number of the matrix of\n      *  which \\c *this is the Cholesky decomposition.\n      */\n    RealScalar rcond() const\n    {\n      eigen_assert(m_isInitialized && \"LLT is not initialized.\");\n      eigen_assert(m_info == Success && \"LLT failed because matrix appears to be negative\");\n      return internal::rcond_estimate_helper(m_l1_norm, *this);\n    }\n\n    /** \\returns the LLT decomposition matrix\n      *\n      * TODO: document the storage layout\n      */\n    inline const MatrixType& matrixLLT() const\n    {\n      eigen_assert(m_isInitialized && \"LLT is not initialized.\");\n      return m_matrix;\n    }\n\n    MatrixType reconstructedMatrix() const;\n\n\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the matrix.appears not to be positive definite.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"LLT is not initialized.\");\n      return m_info;\n    }\n\n    /** \\returns the adjoint of \\c *this, that is, a const reference to the decomposition itself as the underlying matrix is self-adjoint.\n      *\n      * This method is provided for compatibility with other matrix decompositions, thus enabling generic code such as:\n      * \\code x = decomposition.adjoint().solve(b) \\endcode\n      */\n    const LLT& adjoint() const { return *this; };\n\n    inline Index rows() const { return m_matrix.rows(); }\n    inline Index cols() const { return m_matrix.cols(); }\n\n    template<typename VectorType>\n    LLT & rankUpdate(const VectorType& vec, const RealScalar& sigma = 1);\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<typename RhsType, typename DstType>\n    void _solve_impl(const RhsType &rhs, DstType &dst) const;\n\n    template<bool Conjugate, typename RhsType, typename DstType>\n    void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const;\n    #endif\n\n  protected:\n\n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n    }\n\n    /** \\internal\n      * Used to compute and store L\n      * The strict upper part is not used and even not initialized.\n      */\n    MatrixType m_matrix;\n    RealScalar m_l1_norm;\n    bool m_isInitialized;\n    ComputationInfo m_info;\n};\n\nnamespace internal {\n\ntemplate<typename Scalar, int UpLo> struct llt_inplace;\n\ntemplate<typename MatrixType, typename VectorType>\nstatic Index llt_rank_update_lower(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma)\n{\n  using std::sqrt;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef typename MatrixType::ColXpr ColXpr;\n  typedef typename internal::remove_all<ColXpr>::type ColXprCleaned;\n  typedef typename ColXprCleaned::SegmentReturnType ColXprSegment;\n  typedef Matrix<Scalar,Dynamic,1> TempVectorType;\n  typedef typename TempVectorType::SegmentReturnType TempVecSegment;\n\n  Index n = mat.cols();\n  eigen_assert(mat.rows()==n && vec.size()==n);\n\n  TempVectorType temp;\n\n  if(sigma>0)\n  {\n    // This version is based on Givens rotations.\n    // It is faster than the other one below, but only works for updates,\n    // i.e., for sigma > 0\n    temp = sqrt(sigma) * vec;\n\n    for(Index i=0; i<n; ++i)\n    {\n      JacobiRotation<Scalar> g;\n      g.makeGivens(mat(i,i), -temp(i), &mat(i,i));\n\n      Index rs = n-i-1;\n      if(rs>0)\n      {\n        ColXprSegment x(mat.col(i).tail(rs));\n        TempVecSegment y(temp.tail(rs));\n        apply_rotation_in_the_plane(x, y, g);\n      }\n    }\n  }\n  else\n  {\n    temp = vec;\n    RealScalar beta = 1;\n    for(Index j=0; j<n; ++j)\n    {\n      RealScalar Ljj = numext::real(mat.coeff(j,j));\n      RealScalar dj = numext::abs2(Ljj);\n      Scalar wj = temp.coeff(j);\n      RealScalar swj2 = sigma*numext::abs2(wj);\n      RealScalar gamma = dj*beta + swj2;\n\n      RealScalar x = dj + swj2/beta;\n      if (x<=RealScalar(0))\n        return j;\n      RealScalar nLjj = sqrt(x);\n      mat.coeffRef(j,j) = nLjj;\n      beta += swj2/dj;\n\n      // Update the terms of L\n      Index rs = n-j-1;\n      if(rs)\n      {\n        temp.tail(rs) -= (wj/Ljj) * mat.col(j).tail(rs);\n        if(gamma != 0)\n          mat.col(j).tail(rs) = (nLjj/Ljj) * mat.col(j).tail(rs) + (nLjj * sigma*numext::conj(wj)/gamma)*temp.tail(rs);\n      }\n    }\n  }\n  return -1;\n}\n\ntemplate<typename Scalar> struct llt_inplace<Scalar, Lower>\n{\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  template<typename MatrixType>\n  static Index unblocked(MatrixType& mat)\n  {\n    using std::sqrt;\n\n    eigen_assert(mat.rows()==mat.cols());\n    const Index size = mat.rows();\n    for(Index k = 0; k < size; ++k)\n    {\n      Index rs = size-k-1; // remaining size\n\n      Block<MatrixType,Dynamic,1> A21(mat,k+1,k,rs,1);\n      Block<MatrixType,1,Dynamic> A10(mat,k,0,1,k);\n      Block<MatrixType,Dynamic,Dynamic> A20(mat,k+1,0,rs,k);\n\n      RealScalar x = numext::real(mat.coeff(k,k));\n      if (k>0) x -= A10.squaredNorm();\n      if (x<=RealScalar(0))\n        return k;\n      mat.coeffRef(k,k) = x = sqrt(x);\n      if (k>0 && rs>0) A21.noalias() -= A20 * A10.adjoint();\n      if (rs>0) A21 /= x;\n    }\n    return -1;\n  }\n\n  template<typename MatrixType>\n  static Index blocked(MatrixType& m)\n  {\n    eigen_assert(m.rows()==m.cols());\n    Index size = m.rows();\n    if(size<32)\n      return unblocked(m);\n\n    Index blockSize = size/8;\n    blockSize = (blockSize/16)*16;\n    blockSize = (std::min)((std::max)(blockSize,Index(8)), Index(128));\n\n    for (Index k=0; k<size; k+=blockSize)\n    {\n      // partition the matrix:\n      //       A00 |  -  |  -\n      // lu  = A10 | A11 |  -\n      //       A20 | A21 | A22\n      Index bs = (std::min)(blockSize, size-k);\n      Index rs = size - k - bs;\n      Block<MatrixType,Dynamic,Dynamic> A11(m,k,   k,   bs,bs);\n      Block<MatrixType,Dynamic,Dynamic> A21(m,k+bs,k,   rs,bs);\n      Block<MatrixType,Dynamic,Dynamic> A22(m,k+bs,k+bs,rs,rs);\n\n      Index ret;\n      if((ret=unblocked(A11))>=0) return k+ret;\n      if(rs>0) A11.adjoint().template triangularView<Upper>().template solveInPlace<OnTheRight>(A21);\n      if(rs>0) A22.template selfadjointView<Lower>().rankUpdate(A21,typename NumTraits<RealScalar>::Literal(-1)); // bottleneck\n    }\n    return -1;\n  }\n\n  template<typename MatrixType, typename VectorType>\n  static Index rankUpdate(MatrixType& mat, const VectorType& vec, const RealScalar& sigma)\n  {\n    return Eigen::internal::llt_rank_update_lower(mat, vec, sigma);\n  }\n};\n\ntemplate<typename Scalar> struct llt_inplace<Scalar, Upper>\n{\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  template<typename MatrixType>\n  static EIGEN_STRONG_INLINE Index unblocked(MatrixType& mat)\n  {\n    Transpose<MatrixType> matt(mat);\n    return llt_inplace<Scalar, Lower>::unblocked(matt);\n  }\n  template<typename MatrixType>\n  static EIGEN_STRONG_INLINE Index blocked(MatrixType& mat)\n  {\n    Transpose<MatrixType> matt(mat);\n    return llt_inplace<Scalar, Lower>::blocked(matt);\n  }\n  template<typename MatrixType, typename VectorType>\n  static Index rankUpdate(MatrixType& mat, const VectorType& vec, const RealScalar& sigma)\n  {\n    Transpose<MatrixType> matt(mat);\n    return llt_inplace<Scalar, Lower>::rankUpdate(matt, vec.conjugate(), sigma);\n  }\n};\n\ntemplate<typename MatrixType> struct LLT_Traits<MatrixType,Lower>\n{\n  typedef const TriangularView<const MatrixType, Lower> MatrixL;\n  typedef const TriangularView<const typename MatrixType::AdjointReturnType, Upper> MatrixU;\n  static inline MatrixL getL(const MatrixType& m) { return MatrixL(m); }\n  static inline MatrixU getU(const MatrixType& m) { return MatrixU(m.adjoint()); }\n  static bool inplace_decomposition(MatrixType& m)\n  { return llt_inplace<typename MatrixType::Scalar, Lower>::blocked(m)==-1; }\n};\n\ntemplate<typename MatrixType> struct LLT_Traits<MatrixType,Upper>\n{\n  typedef const TriangularView<const typename MatrixType::AdjointReturnType, Lower> MatrixL;\n  typedef const TriangularView<const MatrixType, Upper> MatrixU;\n  static inline MatrixL getL(const MatrixType& m) { return MatrixL(m.adjoint()); }\n  static inline MatrixU getU(const MatrixType& m) { return MatrixU(m); }\n  static bool inplace_decomposition(MatrixType& m)\n  { return llt_inplace<typename MatrixType::Scalar, Upper>::blocked(m)==-1; }\n};\n\n} // end namespace internal\n\n/** Computes / recomputes the Cholesky decomposition A = LL^* = U^*U of \\a matrix\n  *\n  * \\returns a reference to *this\n  *\n  * Example: \\include TutorialLinAlgComputeTwice.cpp\n  * Output: \\verbinclude TutorialLinAlgComputeTwice.out\n  */\ntemplate<typename MatrixType, int _UpLo>\ntemplate<typename InputType>\nLLT<MatrixType,_UpLo>& LLT<MatrixType,_UpLo>::compute(const EigenBase<InputType>& a)\n{\n  check_template_parameters();\n\n  eigen_assert(a.rows()==a.cols());\n  const Index size = a.rows();\n  m_matrix.resize(size, size);\n  if (!internal::is_same_dense(m_matrix, a.derived()))\n    m_matrix = a.derived();\n\n  // Compute matrix L1 norm = max abs column sum.\n  m_l1_norm = RealScalar(0);\n  // TODO move this code to SelfAdjointView\n  for (Index col = 0; col < size; ++col) {\n    RealScalar abs_col_sum;\n    if (_UpLo == Lower)\n      abs_col_sum = m_matrix.col(col).tail(size - col).template lpNorm<1>() + m_matrix.row(col).head(col).template lpNorm<1>();\n    else\n      abs_col_sum = m_matrix.col(col).head(col).template lpNorm<1>() + m_matrix.row(col).tail(size - col).template lpNorm<1>();\n    if (abs_col_sum > m_l1_norm)\n      m_l1_norm = abs_col_sum;\n  }\n\n  m_isInitialized = true;\n  bool ok = Traits::inplace_decomposition(m_matrix);\n  m_info = ok ? Success : NumericalIssue;\n\n  return *this;\n}\n\n/** Performs a rank one update (or dowdate) of the current decomposition.\n  * If A = LL^* before the rank one update,\n  * then after it we have LL^* = A + sigma * v v^* where \\a v must be a vector\n  * of same dimension.\n  */\ntemplate<typename _MatrixType, int _UpLo>\ntemplate<typename VectorType>\nLLT<_MatrixType,_UpLo> & LLT<_MatrixType,_UpLo>::rankUpdate(const VectorType& v, const RealScalar& sigma)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(VectorType);\n  eigen_assert(v.size()==m_matrix.cols());\n  eigen_assert(m_isInitialized);\n  if(internal::llt_inplace<typename MatrixType::Scalar, UpLo>::rankUpdate(m_matrix,v,sigma)>=0)\n    m_info = NumericalIssue;\n  else\n    m_info = Success;\n\n  return *this;\n}\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename _MatrixType,int _UpLo>\ntemplate<typename RhsType, typename DstType>\nvoid LLT<_MatrixType,_UpLo>::_solve_impl(const RhsType &rhs, DstType &dst) const\n{\n  _solve_impl_transposed<true>(rhs, dst);\n}\n\ntemplate<typename _MatrixType,int _UpLo>\ntemplate<bool Conjugate, typename RhsType, typename DstType>\nvoid LLT<_MatrixType,_UpLo>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const\n{\n    dst = rhs;\n\n    matrixL().template conjugateIf<!Conjugate>().solveInPlace(dst);\n    matrixU().template conjugateIf<!Conjugate>().solveInPlace(dst);\n}\n#endif\n\n/** \\internal use x = llt_object.solve(x);\n  *\n  * This is the \\em in-place version of solve().\n  *\n  * \\param bAndX represents both the right-hand side matrix b and result x.\n  *\n  * This version avoids a copy when the right hand side matrix b is not needed anymore.\n  *\n  * \\warning The parameter is only marked 'const' to make the C++ compiler accept a temporary expression here.\n  * This function will const_cast it, so constness isn't honored here.\n  *\n  * \\sa LLT::solve(), MatrixBase::llt()\n  */\ntemplate<typename MatrixType, int _UpLo>\ntemplate<typename Derived>\nvoid LLT<MatrixType,_UpLo>::solveInPlace(const MatrixBase<Derived> &bAndX) const\n{\n  eigen_assert(m_isInitialized && \"LLT is not initialized.\");\n  eigen_assert(m_matrix.rows()==bAndX.rows());\n  matrixL().solveInPlace(bAndX);\n  matrixU().solveInPlace(bAndX);\n}\n\n/** \\returns the matrix represented by the decomposition,\n * i.e., it returns the product: L L^*.\n * This function is provided for debug purpose. */\ntemplate<typename MatrixType, int _UpLo>\nMatrixType LLT<MatrixType,_UpLo>::reconstructedMatrix() const\n{\n  eigen_assert(m_isInitialized && \"LLT is not initialized.\");\n  return matrixL() * matrixL().adjoint().toDenseMatrix();\n}\n\n/** \\cholesky_module\n  * \\returns the LLT decomposition of \\c *this\n  * \\sa SelfAdjointView::llt()\n  */\ntemplate<typename Derived>\ninline const LLT<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::llt() const\n{\n  return LLT<PlainObject>(derived());\n}\n\n/** \\cholesky_module\n  * \\returns the LLT decomposition of \\c *this\n  * \\sa SelfAdjointView::llt()\n  */\ntemplate<typename MatrixType, unsigned int UpLo>\ninline const LLT<typename SelfAdjointView<MatrixType, UpLo>::PlainObject, UpLo>\nSelfAdjointView<MatrixType, UpLo>::llt() const\n{\n  return LLT<PlainObject,UpLo>(m_matrix);\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_LLT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Cholesky/LLT_LAPACKE.h",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Eigen bindings to LAPACKe\n *     LLt decomposition based on LAPACKE_?potrf function.\n ********************************************************************************\n*/\n\n#ifndef EIGEN_LLT_LAPACKE_H\n#define EIGEN_LLT_LAPACKE_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate<typename Scalar> struct lapacke_llt;\n\n#define EIGEN_LAPACKE_LLT(EIGTYPE, BLASTYPE, LAPACKE_PREFIX) \\\ntemplate<> struct lapacke_llt<EIGTYPE> \\\n{ \\\n  template<typename MatrixType> \\\n  static inline Index potrf(MatrixType& m, char uplo) \\\n  { \\\n    lapack_int matrix_order; \\\n    lapack_int size, lda, info, StorageOrder; \\\n    EIGTYPE* a; \\\n    eigen_assert(m.rows()==m.cols()); \\\n    /* Set up parameters for ?potrf */ \\\n    size = convert_index<lapack_int>(m.rows()); \\\n    StorageOrder = MatrixType::Flags&RowMajorBit?RowMajor:ColMajor; \\\n    matrix_order = StorageOrder==RowMajor ? LAPACK_ROW_MAJOR : LAPACK_COL_MAJOR; \\\n    a = &(m.coeffRef(0,0)); \\\n    lda = convert_index<lapack_int>(m.outerStride()); \\\n\\\n    info = LAPACKE_##LAPACKE_PREFIX##potrf( matrix_order, uplo, size, (BLASTYPE*)a, lda ); \\\n    info = (info==0) ? -1 : info>0 ? info-1 : size; \\\n    return info; \\\n  } \\\n}; \\\ntemplate<> struct llt_inplace<EIGTYPE, Lower> \\\n{ \\\n  template<typename MatrixType> \\\n  static Index blocked(MatrixType& m) \\\n  { \\\n    return lapacke_llt<EIGTYPE>::potrf(m, 'L'); \\\n  } \\\n  template<typename MatrixType, typename VectorType> \\\n  static Index rankUpdate(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma) \\\n  { return Eigen::internal::llt_rank_update_lower(mat, vec, sigma); } \\\n}; \\\ntemplate<> struct llt_inplace<EIGTYPE, Upper> \\\n{ \\\n  template<typename MatrixType> \\\n  static Index blocked(MatrixType& m) \\\n  { \\\n    return lapacke_llt<EIGTYPE>::potrf(m, 'U'); \\\n  } \\\n  template<typename MatrixType, typename VectorType> \\\n  static Index rankUpdate(MatrixType& mat, const VectorType& vec, const typename MatrixType::RealScalar& sigma) \\\n  { \\\n    Transpose<MatrixType> matt(mat); \\\n    return llt_inplace<EIGTYPE, Lower>::rankUpdate(matt, vec.conjugate(), sigma); \\\n  } \\\n};\n\nEIGEN_LAPACKE_LLT(double, double, d)\nEIGEN_LAPACKE_LLT(float, float, s)\nEIGEN_LAPACKE_LLT(dcomplex, lapack_complex_double, z)\nEIGEN_LAPACKE_LLT(scomplex, lapack_complex_float, c)\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_LLT_LAPACKE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/CholmodSupport/CholmodSupport.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CHOLMODSUPPORT_H\n#define EIGEN_CHOLMODSUPPORT_H\n\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate<typename Scalar> struct cholmod_configure_matrix;\n\ntemplate<> struct cholmod_configure_matrix<double> {\n  template<typename CholmodType>\n  static void run(CholmodType& mat) {\n    mat.xtype = CHOLMOD_REAL;\n    mat.dtype = CHOLMOD_DOUBLE;\n  }\n};\n\ntemplate<> struct cholmod_configure_matrix<std::complex<double> > {\n  template<typename CholmodType>\n  static void run(CholmodType& mat) {\n    mat.xtype = CHOLMOD_COMPLEX;\n    mat.dtype = CHOLMOD_DOUBLE;\n  }\n};\n\n// Other scalar types are not yet supported by Cholmod\n// template<> struct cholmod_configure_matrix<float> {\n//   template<typename CholmodType>\n//   static void run(CholmodType& mat) {\n//     mat.xtype = CHOLMOD_REAL;\n//     mat.dtype = CHOLMOD_SINGLE;\n//   }\n// };\n//\n// template<> struct cholmod_configure_matrix<std::complex<float> > {\n//   template<typename CholmodType>\n//   static void run(CholmodType& mat) {\n//     mat.xtype = CHOLMOD_COMPLEX;\n//     mat.dtype = CHOLMOD_SINGLE;\n//   }\n// };\n\n} // namespace internal\n\n/** Wraps the Eigen sparse matrix \\a mat into a Cholmod sparse matrix object.\n  * Note that the data are shared.\n  */\ntemplate<typename _Scalar, int _Options, typename _StorageIndex>\ncholmod_sparse viewAsCholmod(Ref<SparseMatrix<_Scalar,_Options,_StorageIndex> > mat)\n{\n  cholmod_sparse res;\n  res.nzmax   = mat.nonZeros();\n  res.nrow    = mat.rows();\n  res.ncol    = mat.cols();\n  res.p       = mat.outerIndexPtr();\n  res.i       = mat.innerIndexPtr();\n  res.x       = mat.valuePtr();\n  res.z       = 0;\n  res.sorted  = 1;\n  if(mat.isCompressed())\n  {\n    res.packed  = 1;\n    res.nz = 0;\n  }\n  else\n  {\n    res.packed  = 0;\n    res.nz = mat.innerNonZeroPtr();\n  }\n\n  res.dtype   = 0;\n  res.stype   = -1;\n\n  if (internal::is_same<_StorageIndex,int>::value)\n  {\n    res.itype = CHOLMOD_INT;\n  }\n  else if (internal::is_same<_StorageIndex,SuiteSparse_long>::value)\n  {\n    res.itype = CHOLMOD_LONG;\n  }\n  else\n  {\n    eigen_assert(false && \"Index type not supported yet\");\n  }\n\n  // setup res.xtype\n  internal::cholmod_configure_matrix<_Scalar>::run(res);\n\n  res.stype = 0;\n\n  return res;\n}\n\ntemplate<typename _Scalar, int _Options, typename _Index>\nconst cholmod_sparse viewAsCholmod(const SparseMatrix<_Scalar,_Options,_Index>& mat)\n{\n  cholmod_sparse res = viewAsCholmod(Ref<SparseMatrix<_Scalar,_Options,_Index> >(mat.const_cast_derived()));\n  return res;\n}\n\ntemplate<typename _Scalar, int _Options, typename _Index>\nconst cholmod_sparse viewAsCholmod(const SparseVector<_Scalar,_Options,_Index>& mat)\n{\n  cholmod_sparse res = viewAsCholmod(Ref<SparseMatrix<_Scalar,_Options,_Index> >(mat.const_cast_derived()));\n  return res;\n}\n\n/** Returns a view of the Eigen sparse matrix \\a mat as Cholmod sparse matrix.\n  * The data are not copied but shared. */\ntemplate<typename _Scalar, int _Options, typename _Index, unsigned int UpLo>\ncholmod_sparse viewAsCholmod(const SparseSelfAdjointView<const SparseMatrix<_Scalar,_Options,_Index>, UpLo>& mat)\n{\n  cholmod_sparse res = viewAsCholmod(Ref<SparseMatrix<_Scalar,_Options,_Index> >(mat.matrix().const_cast_derived()));\n\n  if(UpLo==Upper) res.stype =  1;\n  if(UpLo==Lower) res.stype = -1;\n  // swap stype for rowmajor matrices (only works for real matrices)\n  EIGEN_STATIC_ASSERT((_Options & RowMajorBit) == 0 || NumTraits<_Scalar>::IsComplex == 0, THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES);\n  if(_Options & RowMajorBit) res.stype *=-1;\n\n  return res;\n}\n\n/** Returns a view of the Eigen \\b dense matrix \\a mat as Cholmod dense matrix.\n  * The data are not copied but shared. */\ntemplate<typename Derived>\ncholmod_dense viewAsCholmod(MatrixBase<Derived>& mat)\n{\n  EIGEN_STATIC_ASSERT((internal::traits<Derived>::Flags&RowMajorBit)==0,THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES);\n  typedef typename Derived::Scalar Scalar;\n\n  cholmod_dense res;\n  res.nrow   = mat.rows();\n  res.ncol   = mat.cols();\n  res.nzmax  = res.nrow * res.ncol;\n  res.d      = Derived::IsVectorAtCompileTime ? mat.derived().size() : mat.derived().outerStride();\n  res.x      = (void*)(mat.derived().data());\n  res.z      = 0;\n\n  internal::cholmod_configure_matrix<Scalar>::run(res);\n\n  return res;\n}\n\n/** Returns a view of the Cholmod sparse matrix \\a cm as an Eigen sparse matrix.\n  * The data are not copied but shared. */\ntemplate<typename Scalar, int Flags, typename StorageIndex>\nMappedSparseMatrix<Scalar,Flags,StorageIndex> viewAsEigen(cholmod_sparse& cm)\n{\n  return MappedSparseMatrix<Scalar,Flags,StorageIndex>\n         (cm.nrow, cm.ncol, static_cast<StorageIndex*>(cm.p)[cm.ncol],\n          static_cast<StorageIndex*>(cm.p), static_cast<StorageIndex*>(cm.i),static_cast<Scalar*>(cm.x) );\n}\n\nnamespace internal {\n\n// template specializations for int and long that call the correct cholmod method\n\n#define EIGEN_CHOLMOD_SPECIALIZE0(ret, name) \\\n    template<typename _StorageIndex> inline ret cm_ ## name       (cholmod_common &Common) { return cholmod_ ## name   (&Common); } \\\n    template<>                       inline ret cm_ ## name<SuiteSparse_long> (cholmod_common &Common) { return cholmod_l_ ## name (&Common); }\n\n#define EIGEN_CHOLMOD_SPECIALIZE1(ret, name, t1, a1) \\\n    template<typename _StorageIndex> inline ret cm_ ## name       (t1& a1, cholmod_common &Common) { return cholmod_ ## name   (&a1, &Common); } \\\n    template<>                       inline ret cm_ ## name<SuiteSparse_long> (t1& a1, cholmod_common &Common) { return cholmod_l_ ## name (&a1, &Common); }\n\nEIGEN_CHOLMOD_SPECIALIZE0(int, start)\nEIGEN_CHOLMOD_SPECIALIZE0(int, finish)\n\nEIGEN_CHOLMOD_SPECIALIZE1(int, free_factor, cholmod_factor*, L)\nEIGEN_CHOLMOD_SPECIALIZE1(int, free_dense,  cholmod_dense*,  X)\nEIGEN_CHOLMOD_SPECIALIZE1(int, free_sparse, cholmod_sparse*, A)\n\nEIGEN_CHOLMOD_SPECIALIZE1(cholmod_factor*, analyze, cholmod_sparse, A)\n\ntemplate<typename _StorageIndex> inline cholmod_dense*  cm_solve         (int sys, cholmod_factor& L, cholmod_dense&  B, cholmod_common &Common) { return cholmod_solve     (sys, &L, &B, &Common); }\ntemplate<>                       inline cholmod_dense*  cm_solve<SuiteSparse_long>   (int sys, cholmod_factor& L, cholmod_dense&  B, cholmod_common &Common) { return cholmod_l_solve   (sys, &L, &B, &Common); }\n\ntemplate<typename _StorageIndex> inline cholmod_sparse* cm_spsolve       (int sys, cholmod_factor& L, cholmod_sparse& B, cholmod_common &Common) { return cholmod_spsolve   (sys, &L, &B, &Common); }\ntemplate<>                       inline cholmod_sparse* cm_spsolve<SuiteSparse_long> (int sys, cholmod_factor& L, cholmod_sparse& B, cholmod_common &Common) { return cholmod_l_spsolve (sys, &L, &B, &Common); }\n\ntemplate<typename _StorageIndex>\ninline int  cm_factorize_p       (cholmod_sparse*  A, double beta[2], _StorageIndex* fset, std::size_t fsize, cholmod_factor* L, cholmod_common &Common) { return cholmod_factorize_p   (A, beta, fset, fsize, L, &Common); }\ntemplate<>\ninline int  cm_factorize_p<SuiteSparse_long> (cholmod_sparse*  A, double beta[2], SuiteSparse_long* fset,          std::size_t fsize, cholmod_factor* L, cholmod_common &Common) { return cholmod_l_factorize_p (A, beta, fset, fsize, L, &Common); }\n\n#undef EIGEN_CHOLMOD_SPECIALIZE0\n#undef EIGEN_CHOLMOD_SPECIALIZE1\n\n}  // namespace internal\n\n\nenum CholmodMode {\n  CholmodAuto, CholmodSimplicialLLt, CholmodSupernodalLLt, CholmodLDLt\n};\n\n\n/** \\ingroup CholmodSupport_Module\n  * \\class CholmodBase\n  * \\brief The base class for the direct Cholesky factorization of Cholmod\n  * \\sa class CholmodSupernodalLLT, class CholmodSimplicialLDLT, class CholmodSimplicialLLT\n  */\ntemplate<typename _MatrixType, int _UpLo, typename Derived>\nclass CholmodBase : public SparseSolverBase<Derived>\n{\n  protected:\n    typedef SparseSolverBase<Derived> Base;\n    using Base::derived;\n    using Base::m_isInitialized;\n  public:\n    typedef _MatrixType MatrixType;\n    enum { UpLo = _UpLo };\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef MatrixType CholMatrixType;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    enum {\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n\n  public:\n\n    CholmodBase()\n      : m_cholmodFactor(0), m_info(Success), m_factorizationIsOk(false), m_analysisIsOk(false)\n    {\n      EIGEN_STATIC_ASSERT((internal::is_same<double,RealScalar>::value), CHOLMOD_SUPPORTS_DOUBLE_PRECISION_ONLY);\n      m_shiftOffset[0] = m_shiftOffset[1] = 0.0;\n      internal::cm_start<StorageIndex>(m_cholmod);\n    }\n\n    explicit CholmodBase(const MatrixType& matrix)\n      : m_cholmodFactor(0), m_info(Success), m_factorizationIsOk(false), m_analysisIsOk(false)\n    {\n      EIGEN_STATIC_ASSERT((internal::is_same<double,RealScalar>::value), CHOLMOD_SUPPORTS_DOUBLE_PRECISION_ONLY);\n      m_shiftOffset[0] = m_shiftOffset[1] = 0.0;\n      internal::cm_start<StorageIndex>(m_cholmod);\n      compute(matrix);\n    }\n\n    ~CholmodBase()\n    {\n      if(m_cholmodFactor)\n        internal::cm_free_factor<StorageIndex>(m_cholmodFactor, m_cholmod);\n      internal::cm_finish<StorageIndex>(m_cholmod);\n    }\n\n    inline StorageIndex cols() const { return internal::convert_index<StorageIndex, Index>(m_cholmodFactor->n); }\n    inline StorageIndex rows() const { return internal::convert_index<StorageIndex, Index>(m_cholmodFactor->n); }\n\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the matrix.appears to be negative.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_info;\n    }\n\n    /** Computes the sparse Cholesky decomposition of \\a matrix */\n    Derived& compute(const MatrixType& matrix)\n    {\n      analyzePattern(matrix);\n      factorize(matrix);\n      return derived();\n    }\n\n    /** Performs a symbolic decomposition on the sparsity pattern of \\a matrix.\n      *\n      * This function is particularly useful when solving for several problems having the same structure.\n      *\n      * \\sa factorize()\n      */\n    void analyzePattern(const MatrixType& matrix)\n    {\n      if(m_cholmodFactor)\n      {\n        internal::cm_free_factor<StorageIndex>(m_cholmodFactor, m_cholmod);\n        m_cholmodFactor = 0;\n      }\n      cholmod_sparse A = viewAsCholmod(matrix.template selfadjointView<UpLo>());\n      m_cholmodFactor = internal::cm_analyze<StorageIndex>(A, m_cholmod);\n\n      this->m_isInitialized = true;\n      this->m_info = Success;\n      m_analysisIsOk = true;\n      m_factorizationIsOk = false;\n    }\n\n    /** Performs a numeric decomposition of \\a matrix\n      *\n      * The given matrix must have the same sparsity pattern as the matrix on which the symbolic decomposition has been performed.\n      *\n      * \\sa analyzePattern()\n      */\n    void factorize(const MatrixType& matrix)\n    {\n      eigen_assert(m_analysisIsOk && \"You must first call analyzePattern()\");\n      cholmod_sparse A = viewAsCholmod(matrix.template selfadjointView<UpLo>());\n      internal::cm_factorize_p<StorageIndex>(&A, m_shiftOffset, 0, 0, m_cholmodFactor, m_cholmod);\n\n      // If the factorization failed, minor is the column at which it did. On success minor == n.\n      this->m_info = (m_cholmodFactor->minor == m_cholmodFactor->n ? Success : NumericalIssue);\n      m_factorizationIsOk = true;\n    }\n\n    /** Returns a reference to the Cholmod's configuration structure to get a full control over the performed operations.\n     *  See the Cholmod user guide for details. */\n    cholmod_common& cholmod() { return m_cholmod; }\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    /** \\internal */\n    template<typename Rhs,typename Dest>\n    void _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const\n    {\n      eigen_assert(m_factorizationIsOk && \"The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()\");\n      const Index size = m_cholmodFactor->n;\n      EIGEN_UNUSED_VARIABLE(size);\n      eigen_assert(size==b.rows());\n\n      // Cholmod needs column-major storage without inner-stride, which corresponds to the default behavior of Ref.\n      Ref<const Matrix<typename Rhs::Scalar,Dynamic,Dynamic,ColMajor> > b_ref(b.derived());\n\n      cholmod_dense b_cd = viewAsCholmod(b_ref);\n      cholmod_dense* x_cd = internal::cm_solve<StorageIndex>(CHOLMOD_A, *m_cholmodFactor, b_cd, m_cholmod);\n      if(!x_cd)\n      {\n        this->m_info = NumericalIssue;\n        return;\n      }\n      // TODO optimize this copy by swapping when possible (be careful with alignment, etc.)\n      // NOTE Actually, the copy can be avoided by calling cholmod_solve2 instead of cholmod_solve\n      dest = Matrix<Scalar,Dest::RowsAtCompileTime,Dest::ColsAtCompileTime>::Map(reinterpret_cast<Scalar*>(x_cd->x),b.rows(),b.cols());\n      internal::cm_free_dense<StorageIndex>(x_cd, m_cholmod);\n    }\n\n    /** \\internal */\n    template<typename RhsDerived, typename DestDerived>\n    void _solve_impl(const SparseMatrixBase<RhsDerived> &b, SparseMatrixBase<DestDerived> &dest) const\n    {\n      eigen_assert(m_factorizationIsOk && \"The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()\");\n      const Index size = m_cholmodFactor->n;\n      EIGEN_UNUSED_VARIABLE(size);\n      eigen_assert(size==b.rows());\n\n      // note: cs stands for Cholmod Sparse\n      Ref<SparseMatrix<typename RhsDerived::Scalar,ColMajor,typename RhsDerived::StorageIndex> > b_ref(b.const_cast_derived());\n      cholmod_sparse b_cs = viewAsCholmod(b_ref);\n      cholmod_sparse* x_cs = internal::cm_spsolve<StorageIndex>(CHOLMOD_A, *m_cholmodFactor, b_cs, m_cholmod);\n      if(!x_cs)\n      {\n        this->m_info = NumericalIssue;\n        return;\n      }\n      // TODO optimize this copy by swapping when possible (be careful with alignment, etc.)\n      // NOTE cholmod_spsolve in fact just calls the dense solver for blocks of 4 columns at a time (similar to Eigen's sparse solver)\n      dest.derived() = viewAsEigen<typename DestDerived::Scalar,ColMajor,typename DestDerived::StorageIndex>(*x_cs);\n      internal::cm_free_sparse<StorageIndex>(x_cs, m_cholmod);\n    }\n    #endif // EIGEN_PARSED_BY_DOXYGEN\n\n\n    /** Sets the shift parameter that will be used to adjust the diagonal coefficients during the numerical factorization.\n      *\n      * During the numerical factorization, an offset term is added to the diagonal coefficients:\\n\n      * \\c d_ii = \\a offset + \\c d_ii\n      *\n      * The default is \\a offset=0.\n      *\n      * \\returns a reference to \\c *this.\n      */\n    Derived& setShift(const RealScalar& offset)\n    {\n      m_shiftOffset[0] = double(offset);\n      return derived();\n    }\n\n    /** \\returns the determinant of the underlying matrix from the current factorization */\n    Scalar determinant() const\n    {\n      using std::exp;\n      return exp(logDeterminant());\n    }\n\n    /** \\returns the log determinant of the underlying matrix from the current factorization */\n    Scalar logDeterminant() const\n    {\n      using std::log;\n      using numext::real;\n      eigen_assert(m_factorizationIsOk && \"The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()\");\n\n      RealScalar logDet = 0;\n      Scalar *x = static_cast<Scalar*>(m_cholmodFactor->x);\n      if (m_cholmodFactor->is_super)\n      {\n        // Supernodal factorization stored as a packed list of dense column-major blocs,\n        // as described by the following structure:\n\n        // super[k] == index of the first column of the j-th super node\n        StorageIndex *super = static_cast<StorageIndex*>(m_cholmodFactor->super);\n        // pi[k] == offset to the description of row indices\n        StorageIndex *pi = static_cast<StorageIndex*>(m_cholmodFactor->pi);\n        // px[k] == offset to the respective dense block\n        StorageIndex *px = static_cast<StorageIndex*>(m_cholmodFactor->px);\n\n        Index nb_super_nodes = m_cholmodFactor->nsuper;\n        for (Index k=0; k < nb_super_nodes; ++k)\n        {\n          StorageIndex ncols = super[k + 1] - super[k];\n          StorageIndex nrows = pi[k + 1] - pi[k];\n\n          Map<const Array<Scalar,1,Dynamic>, 0, InnerStride<> > sk(x + px[k], ncols, InnerStride<>(nrows+1));\n          logDet += sk.real().log().sum();\n        }\n      }\n      else\n      {\n        // Simplicial factorization stored as standard CSC matrix.\n        StorageIndex *p = static_cast<StorageIndex*>(m_cholmodFactor->p);\n        Index size = m_cholmodFactor->n;\n        for (Index k=0; k<size; ++k)\n          logDet += log(real( x[p[k]] ));\n      }\n      if (m_cholmodFactor->is_ll)\n        logDet *= 2.0;\n      return logDet;\n    };\n\n    template<typename Stream>\n    void dumpMemory(Stream& /*s*/)\n    {}\n\n  protected:\n    mutable cholmod_common m_cholmod;\n    cholmod_factor* m_cholmodFactor;\n    double m_shiftOffset[2];\n    mutable ComputationInfo m_info;\n    int m_factorizationIsOk;\n    int m_analysisIsOk;\n};\n\n/** \\ingroup CholmodSupport_Module\n  * \\class CholmodSimplicialLLT\n  * \\brief A simplicial direct Cholesky (LLT) factorization and solver based on Cholmod\n  *\n  * This class allows to solve for A.X = B sparse linear problems via a simplicial LL^T Cholesky factorization\n  * using the Cholmod library.\n  * This simplicial variant is equivalent to Eigen's built-in SimplicialLLT class. Therefore, it has little practical interest.\n  * The sparse matrix A must be selfadjoint and positive definite. The vectors or matrices\n  * X and B can be either dense or sparse.\n  *\n  * \\tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam _UpLo the triangular part that will be used for the computations. It can be Lower\n  *               or Upper. Default is Lower.\n  *\n  * \\implsparsesolverconcept\n  *\n  * This class supports all kind of SparseMatrix<>: row or column major; upper, lower, or both; compressed or non compressed.\n  *\n  * \\warning Only double precision real and complex scalar types are supported by Cholmod.\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class CholmodSupernodalLLT, class SimplicialLLT\n  */\ntemplate<typename _MatrixType, int _UpLo = Lower>\nclass CholmodSimplicialLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimplicialLLT<_MatrixType, _UpLo> >\n{\n    typedef CholmodBase<_MatrixType, _UpLo, CholmodSimplicialLLT> Base;\n    using Base::m_cholmod;\n\n  public:\n\n    typedef _MatrixType MatrixType;\n\n    CholmodSimplicialLLT() : Base() { init(); }\n\n    CholmodSimplicialLLT(const MatrixType& matrix) : Base()\n    {\n      init();\n      this->compute(matrix);\n    }\n\n    ~CholmodSimplicialLLT() {}\n  protected:\n    void init()\n    {\n      m_cholmod.final_asis = 0;\n      m_cholmod.supernodal = CHOLMOD_SIMPLICIAL;\n      m_cholmod.final_ll = 1;\n    }\n};\n\n\n/** \\ingroup CholmodSupport_Module\n  * \\class CholmodSimplicialLDLT\n  * \\brief A simplicial direct Cholesky (LDLT) factorization and solver based on Cholmod\n  *\n  * This class allows to solve for A.X = B sparse linear problems via a simplicial LDL^T Cholesky factorization\n  * using the Cholmod library.\n  * This simplicial variant is equivalent to Eigen's built-in SimplicialLDLT class. Therefore, it has little practical interest.\n  * The sparse matrix A must be selfadjoint and positive definite. The vectors or matrices\n  * X and B can be either dense or sparse.\n  *\n  * \\tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam _UpLo the triangular part that will be used for the computations. It can be Lower\n  *               or Upper. Default is Lower.\n  *\n  * \\implsparsesolverconcept\n  *\n  * This class supports all kind of SparseMatrix<>: row or column major; upper, lower, or both; compressed or non compressed.\n  *\n  * \\warning Only double precision real and complex scalar types are supported by Cholmod.\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class CholmodSupernodalLLT, class SimplicialLDLT\n  */\ntemplate<typename _MatrixType, int _UpLo = Lower>\nclass CholmodSimplicialLDLT : public CholmodBase<_MatrixType, _UpLo, CholmodSimplicialLDLT<_MatrixType, _UpLo> >\n{\n    typedef CholmodBase<_MatrixType, _UpLo, CholmodSimplicialLDLT> Base;\n    using Base::m_cholmod;\n\n  public:\n\n    typedef _MatrixType MatrixType;\n\n    CholmodSimplicialLDLT() : Base() { init(); }\n\n    CholmodSimplicialLDLT(const MatrixType& matrix) : Base()\n    {\n      init();\n      this->compute(matrix);\n    }\n\n    ~CholmodSimplicialLDLT() {}\n  protected:\n    void init()\n    {\n      m_cholmod.final_asis = 1;\n      m_cholmod.supernodal = CHOLMOD_SIMPLICIAL;\n    }\n};\n\n/** \\ingroup CholmodSupport_Module\n  * \\class CholmodSupernodalLLT\n  * \\brief A supernodal Cholesky (LLT) factorization and solver based on Cholmod\n  *\n  * This class allows to solve for A.X = B sparse linear problems via a supernodal LL^T Cholesky factorization\n  * using the Cholmod library.\n  * This supernodal variant performs best on dense enough problems, e.g., 3D FEM, or very high order 2D FEM.\n  * The sparse matrix A must be selfadjoint and positive definite. The vectors or matrices\n  * X and B can be either dense or sparse.\n  *\n  * \\tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam _UpLo the triangular part that will be used for the computations. It can be Lower\n  *               or Upper. Default is Lower.\n  *\n  * \\implsparsesolverconcept\n  *\n  * This class supports all kind of SparseMatrix<>: row or column major; upper, lower, or both; compressed or non compressed.\n  *\n  * \\warning Only double precision real and complex scalar types are supported by Cholmod.\n  *\n  * \\sa \\ref TutorialSparseSolverConcept\n  */\ntemplate<typename _MatrixType, int _UpLo = Lower>\nclass CholmodSupernodalLLT : public CholmodBase<_MatrixType, _UpLo, CholmodSupernodalLLT<_MatrixType, _UpLo> >\n{\n    typedef CholmodBase<_MatrixType, _UpLo, CholmodSupernodalLLT> Base;\n    using Base::m_cholmod;\n\n  public:\n\n    typedef _MatrixType MatrixType;\n\n    CholmodSupernodalLLT() : Base() { init(); }\n\n    CholmodSupernodalLLT(const MatrixType& matrix) : Base()\n    {\n      init();\n      this->compute(matrix);\n    }\n\n    ~CholmodSupernodalLLT() {}\n  protected:\n    void init()\n    {\n      m_cholmod.final_asis = 1;\n      m_cholmod.supernodal = CHOLMOD_SUPERNODAL;\n    }\n};\n\n/** \\ingroup CholmodSupport_Module\n  * \\class CholmodDecomposition\n  * \\brief A general Cholesky factorization and solver based on Cholmod\n  *\n  * This class allows to solve for A.X = B sparse linear problems via a LL^T or LDL^T Cholesky factorization\n  * using the Cholmod library. The sparse matrix A must be selfadjoint and positive definite. The vectors or matrices\n  * X and B can be either dense or sparse.\n  *\n  * This variant permits to change the underlying Cholesky method at runtime.\n  * On the other hand, it does not provide access to the result of the factorization.\n  * The default is to let Cholmod automatically choose between a simplicial and supernodal factorization.\n  *\n  * \\tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam _UpLo the triangular part that will be used for the computations. It can be Lower\n  *               or Upper. Default is Lower.\n  *\n  * \\implsparsesolverconcept\n  *\n  * This class supports all kind of SparseMatrix<>: row or column major; upper, lower, or both; compressed or non compressed.\n  *\n  * \\warning Only double precision real and complex scalar types are supported by Cholmod.\n  *\n  * \\sa \\ref TutorialSparseSolverConcept\n  */\ntemplate<typename _MatrixType, int _UpLo = Lower>\nclass CholmodDecomposition : public CholmodBase<_MatrixType, _UpLo, CholmodDecomposition<_MatrixType, _UpLo> >\n{\n    typedef CholmodBase<_MatrixType, _UpLo, CholmodDecomposition> Base;\n    using Base::m_cholmod;\n\n  public:\n\n    typedef _MatrixType MatrixType;\n\n    CholmodDecomposition() : Base() { init(); }\n\n    CholmodDecomposition(const MatrixType& matrix) : Base()\n    {\n      init();\n      this->compute(matrix);\n    }\n\n    ~CholmodDecomposition() {}\n\n    void setMode(CholmodMode mode)\n    {\n      switch(mode)\n      {\n        case CholmodAuto:\n          m_cholmod.final_asis = 1;\n          m_cholmod.supernodal = CHOLMOD_AUTO;\n          break;\n        case CholmodSimplicialLLt:\n          m_cholmod.final_asis = 0;\n          m_cholmod.supernodal = CHOLMOD_SIMPLICIAL;\n          m_cholmod.final_ll = 1;\n          break;\n        case CholmodSupernodalLLt:\n          m_cholmod.final_asis = 1;\n          m_cholmod.supernodal = CHOLMOD_SUPERNODAL;\n          break;\n        case CholmodLDLt:\n          m_cholmod.final_asis = 1;\n          m_cholmod.supernodal = CHOLMOD_SIMPLICIAL;\n          break;\n        default:\n          break;\n      }\n    }\n  protected:\n    void init()\n    {\n      m_cholmod.final_asis = 1;\n      m_cholmod.supernodal = CHOLMOD_AUTO;\n    }\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CHOLMODSUPPORT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Eigenvalues/ComplexEigenSolver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Claire Maurice\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010,2012 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_COMPLEX_EIGEN_SOLVER_H\n#define EIGEN_COMPLEX_EIGEN_SOLVER_H\n\n#include \"./ComplexSchur.h\"\n\nnamespace Eigen { \n\n/** \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  *\n  * \\class ComplexEigenSolver\n  *\n  * \\brief Computes eigenvalues and eigenvectors of general complex matrices\n  *\n  * \\tparam _MatrixType the type of the matrix of which we are\n  * computing the eigendecomposition; this is expected to be an\n  * instantiation of the Matrix class template.\n  *\n  * The eigenvalues and eigenvectors of a matrix \\f$ A \\f$ are scalars\n  * \\f$ \\lambda \\f$ and vectors \\f$ v \\f$ such that \\f$ Av = \\lambda v\n  * \\f$.  If \\f$ D \\f$ is a diagonal matrix with the eigenvalues on\n  * the diagonal, and \\f$ V \\f$ is a matrix with the eigenvectors as\n  * its columns, then \\f$ A V = V D \\f$. The matrix \\f$ V \\f$ is\n  * almost always invertible, in which case we have \\f$ A = V D V^{-1}\n  * \\f$. This is called the eigendecomposition.\n  *\n  * The main function in this class is compute(), which computes the\n  * eigenvalues and eigenvectors of a given function. The\n  * documentation for that function contains an example showing the\n  * main features of the class.\n  *\n  * \\sa class EigenSolver, class SelfAdjointEigenSolver\n  */\ntemplate<typename _MatrixType> class ComplexEigenSolver\n{\n  public:\n\n    /** \\brief Synonym for the template parameter \\p _MatrixType. */\n    typedef _MatrixType MatrixType;\n\n    enum {\n      RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      Options = MatrixType::Options,\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n\n    /** \\brief Scalar type for matrices of type #MatrixType. */\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n\n    /** \\brief Complex scalar type for #MatrixType.\n      *\n      * This is \\c std::complex<Scalar> if #Scalar is real (e.g.,\n      * \\c float or \\c double) and just \\c Scalar if #Scalar is\n      * complex.\n      */\n    typedef std::complex<RealScalar> ComplexScalar;\n\n    /** \\brief Type for vector of eigenvalues as returned by eigenvalues().\n      *\n      * This is a column vector with entries of type #ComplexScalar.\n      * The length of the vector is the size of #MatrixType.\n      */\n    typedef Matrix<ComplexScalar, ColsAtCompileTime, 1, Options&(~RowMajor), MaxColsAtCompileTime, 1> EigenvalueType;\n\n    /** \\brief Type for matrix of eigenvectors as returned by eigenvectors().\n      *\n      * This is a square matrix with entries of type #ComplexScalar.\n      * The size is the same as the size of #MatrixType.\n      */\n    typedef Matrix<ComplexScalar, RowsAtCompileTime, ColsAtCompileTime, Options, MaxRowsAtCompileTime, MaxColsAtCompileTime> EigenvectorType;\n\n    /** \\brief Default constructor.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via compute().\n      */\n    ComplexEigenSolver()\n            : m_eivec(),\n              m_eivalues(),\n              m_schur(),\n              m_isInitialized(false),\n              m_eigenvectorsOk(false),\n              m_matX()\n    {}\n\n    /** \\brief Default Constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem \\a size.\n      * \\sa ComplexEigenSolver()\n      */\n    explicit ComplexEigenSolver(Index size)\n            : m_eivec(size, size),\n              m_eivalues(size),\n              m_schur(size),\n              m_isInitialized(false),\n              m_eigenvectorsOk(false),\n              m_matX(size, size)\n    {}\n\n    /** \\brief Constructor; computes eigendecomposition of given matrix.\n      *\n      * \\param[in]  matrix  Square matrix whose eigendecomposition is to be computed.\n      * \\param[in]  computeEigenvectors  If true, both the eigenvectors and the\n      *    eigenvalues are computed; if false, only the eigenvalues are\n      *    computed.\n      *\n      * This constructor calls compute() to compute the eigendecomposition.\n      */\n    template<typename InputType>\n    explicit ComplexEigenSolver(const EigenBase<InputType>& matrix, bool computeEigenvectors = true)\n            : m_eivec(matrix.rows(),matrix.cols()),\n              m_eivalues(matrix.cols()),\n              m_schur(matrix.rows()),\n              m_isInitialized(false),\n              m_eigenvectorsOk(false),\n              m_matX(matrix.rows(),matrix.cols())\n    {\n      compute(matrix.derived(), computeEigenvectors);\n    }\n\n    /** \\brief Returns the eigenvectors of given matrix.\n      *\n      * \\returns  A const reference to the matrix whose columns are the eigenvectors.\n      *\n      * \\pre Either the constructor\n      * ComplexEigenSolver(const MatrixType& matrix, bool) or the member\n      * function compute(const MatrixType& matrix, bool) has been called before\n      * to compute the eigendecomposition of a matrix, and\n      * \\p computeEigenvectors was set to true (the default).\n      *\n      * This function returns a matrix whose columns are the eigenvectors. Column\n      * \\f$ k \\f$ is an eigenvector corresponding to eigenvalue number \\f$ k\n      * \\f$ as returned by eigenvalues().  The eigenvectors are normalized to\n      * have (Euclidean) norm equal to one. The matrix returned by this\n      * function is the matrix \\f$ V \\f$ in the eigendecomposition \\f$ A = V D\n      * V^{-1} \\f$, if it exists.\n      *\n      * Example: \\include ComplexEigenSolver_eigenvectors.cpp\n      * Output: \\verbinclude ComplexEigenSolver_eigenvectors.out\n      */\n    const EigenvectorType& eigenvectors() const\n    {\n      eigen_assert(m_isInitialized && \"ComplexEigenSolver is not initialized.\");\n      eigen_assert(m_eigenvectorsOk && \"The eigenvectors have not been computed together with the eigenvalues.\");\n      return m_eivec;\n    }\n\n    /** \\brief Returns the eigenvalues of given matrix.\n      *\n      * \\returns A const reference to the column vector containing the eigenvalues.\n      *\n      * \\pre Either the constructor\n      * ComplexEigenSolver(const MatrixType& matrix, bool) or the member\n      * function compute(const MatrixType& matrix, bool) has been called before\n      * to compute the eigendecomposition of a matrix.\n      *\n      * This function returns a column vector containing the\n      * eigenvalues. Eigenvalues are repeated according to their\n      * algebraic multiplicity, so there are as many eigenvalues as\n      * rows in the matrix. The eigenvalues are not sorted in any particular\n      * order.\n      *\n      * Example: \\include ComplexEigenSolver_eigenvalues.cpp\n      * Output: \\verbinclude ComplexEigenSolver_eigenvalues.out\n      */\n    const EigenvalueType& eigenvalues() const\n    {\n      eigen_assert(m_isInitialized && \"ComplexEigenSolver is not initialized.\");\n      return m_eivalues;\n    }\n\n    /** \\brief Computes eigendecomposition of given matrix.\n      *\n      * \\param[in]  matrix  Square matrix whose eigendecomposition is to be computed.\n      * \\param[in]  computeEigenvectors  If true, both the eigenvectors and the\n      *    eigenvalues are computed; if false, only the eigenvalues are\n      *    computed.\n      * \\returns    Reference to \\c *this\n      *\n      * This function computes the eigenvalues of the complex matrix \\p matrix.\n      * The eigenvalues() function can be used to retrieve them.  If\n      * \\p computeEigenvectors is true, then the eigenvectors are also computed\n      * and can be retrieved by calling eigenvectors().\n      *\n      * The matrix is first reduced to Schur form using the\n      * ComplexSchur class. The Schur decomposition is then used to\n      * compute the eigenvalues and eigenvectors.\n      *\n      * The cost of the computation is dominated by the cost of the\n      * Schur decomposition, which is \\f$ O(n^3) \\f$ where \\f$ n \\f$\n      * is the size of the matrix.\n      *\n      * Example: \\include ComplexEigenSolver_compute.cpp\n      * Output: \\verbinclude ComplexEigenSolver_compute.out\n      */\n    template<typename InputType>\n    ComplexEigenSolver& compute(const EigenBase<InputType>& matrix, bool computeEigenvectors = true);\n\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful, \\c NoConvergence otherwise.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"ComplexEigenSolver is not initialized.\");\n      return m_schur.info();\n    }\n\n    /** \\brief Sets the maximum number of iterations allowed. */\n    ComplexEigenSolver& setMaxIterations(Index maxIters)\n    {\n      m_schur.setMaxIterations(maxIters);\n      return *this;\n    }\n\n    /** \\brief Returns the maximum number of iterations. */\n    Index getMaxIterations()\n    {\n      return m_schur.getMaxIterations();\n    }\n\n  protected:\n    \n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n    }\n    \n    EigenvectorType m_eivec;\n    EigenvalueType m_eivalues;\n    ComplexSchur<MatrixType> m_schur;\n    bool m_isInitialized;\n    bool m_eigenvectorsOk;\n    EigenvectorType m_matX;\n\n  private:\n    void doComputeEigenvectors(RealScalar matrixnorm);\n    void sortEigenvalues(bool computeEigenvectors);\n};\n\n\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nComplexEigenSolver<MatrixType>& \nComplexEigenSolver<MatrixType>::compute(const EigenBase<InputType>& matrix, bool computeEigenvectors)\n{\n  check_template_parameters();\n  \n  // this code is inspired from Jampack\n  eigen_assert(matrix.cols() == matrix.rows());\n\n  // Do a complex Schur decomposition, A = U T U^*\n  // The eigenvalues are on the diagonal of T.\n  m_schur.compute(matrix.derived(), computeEigenvectors);\n\n  if(m_schur.info() == Success)\n  {\n    m_eivalues = m_schur.matrixT().diagonal();\n    if(computeEigenvectors)\n      doComputeEigenvectors(m_schur.matrixT().norm());\n    sortEigenvalues(computeEigenvectors);\n  }\n\n  m_isInitialized = true;\n  m_eigenvectorsOk = computeEigenvectors;\n  return *this;\n}\n\n\ntemplate<typename MatrixType>\nvoid ComplexEigenSolver<MatrixType>::doComputeEigenvectors(RealScalar matrixnorm)\n{\n  const Index n = m_eivalues.size();\n\n  matrixnorm = numext::maxi(matrixnorm,(std::numeric_limits<RealScalar>::min)());\n\n  // Compute X such that T = X D X^(-1), where D is the diagonal of T.\n  // The matrix X is unit triangular.\n  m_matX = EigenvectorType::Zero(n, n);\n  for(Index k=n-1 ; k>=0 ; k--)\n  {\n    m_matX.coeffRef(k,k) = ComplexScalar(1.0,0.0);\n    // Compute X(i,k) using the (i,k) entry of the equation X T = D X\n    for(Index i=k-1 ; i>=0 ; i--)\n    {\n      m_matX.coeffRef(i,k) = -m_schur.matrixT().coeff(i,k);\n      if(k-i-1>0)\n        m_matX.coeffRef(i,k) -= (m_schur.matrixT().row(i).segment(i+1,k-i-1) * m_matX.col(k).segment(i+1,k-i-1)).value();\n      ComplexScalar z = m_schur.matrixT().coeff(i,i) - m_schur.matrixT().coeff(k,k);\n      if(z==ComplexScalar(0))\n      {\n        // If the i-th and k-th eigenvalue are equal, then z equals 0.\n        // Use a small value instead, to prevent division by zero.\n        numext::real_ref(z) = NumTraits<RealScalar>::epsilon() * matrixnorm;\n      }\n      m_matX.coeffRef(i,k) = m_matX.coeff(i,k) / z;\n    }\n  }\n\n  // Compute V as V = U X; now A = U T U^* = U X D X^(-1) U^* = V D V^(-1)\n  m_eivec.noalias() = m_schur.matrixU() * m_matX;\n  // .. and normalize the eigenvectors\n  for(Index k=0 ; k<n ; k++)\n  {\n    m_eivec.col(k).normalize();\n  }\n}\n\n\ntemplate<typename MatrixType>\nvoid ComplexEigenSolver<MatrixType>::sortEigenvalues(bool computeEigenvectors)\n{\n  const Index n =  m_eivalues.size();\n  for (Index i=0; i<n; i++)\n  {\n    Index k;\n    m_eivalues.cwiseAbs().tail(n-i).minCoeff(&k);\n    if (k != 0)\n    {\n      k += i;\n      std::swap(m_eivalues[k],m_eivalues[i]);\n      if(computeEigenvectors)\n\tm_eivec.col(i).swap(m_eivec.col(k));\n    }\n  }\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_COMPLEX_EIGEN_SOLVER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Eigenvalues/ComplexSchur.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Claire Maurice\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010,2012 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_COMPLEX_SCHUR_H\n#define EIGEN_COMPLEX_SCHUR_H\n\n#include \"./HessenbergDecomposition.h\"\n\nnamespace Eigen { \n\nnamespace internal {\ntemplate<typename MatrixType, bool IsComplex> struct complex_schur_reduce_to_hessenberg;\n}\n\n/** \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  *\n  * \\class ComplexSchur\n  *\n  * \\brief Performs a complex Schur decomposition of a real or complex square matrix\n  *\n  * \\tparam _MatrixType the type of the matrix of which we are\n  * computing the Schur decomposition; this is expected to be an\n  * instantiation of the Matrix class template.\n  *\n  * Given a real or complex square matrix A, this class computes the\n  * Schur decomposition: \\f$ A = U T U^*\\f$ where U is a unitary\n  * complex matrix, and T is a complex upper triangular matrix.  The\n  * diagonal of the matrix T corresponds to the eigenvalues of the\n  * matrix A.\n  *\n  * Call the function compute() to compute the Schur decomposition of\n  * a given matrix. Alternatively, you can use the \n  * ComplexSchur(const MatrixType&, bool) constructor which computes\n  * the Schur decomposition at construction time. Once the\n  * decomposition is computed, you can use the matrixU() and matrixT()\n  * functions to retrieve the matrices U and V in the decomposition.\n  *\n  * \\note This code is inspired from Jampack\n  *\n  * \\sa class RealSchur, class EigenSolver, class ComplexEigenSolver\n  */\ntemplate<typename _MatrixType> class ComplexSchur\n{\n  public:\n    typedef _MatrixType MatrixType;\n    enum {\n      RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      Options = MatrixType::Options,\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n\n    /** \\brief Scalar type for matrices of type \\p _MatrixType. */\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n\n    /** \\brief Complex scalar type for \\p _MatrixType. \n      *\n      * This is \\c std::complex<Scalar> if #Scalar is real (e.g.,\n      * \\c float or \\c double) and just \\c Scalar if #Scalar is\n      * complex.\n      */\n    typedef std::complex<RealScalar> ComplexScalar;\n\n    /** \\brief Type for the matrices in the Schur decomposition.\n      *\n      * This is a square matrix with entries of type #ComplexScalar. \n      * The size is the same as the size of \\p _MatrixType.\n      */\n    typedef Matrix<ComplexScalar, RowsAtCompileTime, ColsAtCompileTime, Options, MaxRowsAtCompileTime, MaxColsAtCompileTime> ComplexMatrixType;\n\n    /** \\brief Default constructor.\n      *\n      * \\param [in] size  Positive integer, size of the matrix whose Schur decomposition will be computed.\n      *\n      * The default constructor is useful in cases in which the user\n      * intends to perform decompositions via compute().  The \\p size\n      * parameter is only used as a hint. It is not an error to give a\n      * wrong \\p size, but it may impair performance.\n      *\n      * \\sa compute() for an example.\n      */\n    explicit ComplexSchur(Index size = RowsAtCompileTime==Dynamic ? 1 : RowsAtCompileTime)\n      : m_matT(size,size),\n        m_matU(size,size),\n        m_hess(size),\n        m_isInitialized(false),\n        m_matUisUptodate(false),\n        m_maxIters(-1)\n    {}\n\n    /** \\brief Constructor; computes Schur decomposition of given matrix. \n      * \n      * \\param[in]  matrix    Square matrix whose Schur decomposition is to be computed.\n      * \\param[in]  computeU  If true, both T and U are computed; if false, only T is computed.\n      *\n      * This constructor calls compute() to compute the Schur decomposition.\n      *\n      * \\sa matrixT() and matrixU() for examples.\n      */\n    template<typename InputType>\n    explicit ComplexSchur(const EigenBase<InputType>& matrix, bool computeU = true)\n      : m_matT(matrix.rows(),matrix.cols()),\n        m_matU(matrix.rows(),matrix.cols()),\n        m_hess(matrix.rows()),\n        m_isInitialized(false),\n        m_matUisUptodate(false),\n        m_maxIters(-1)\n    {\n      compute(matrix.derived(), computeU);\n    }\n\n    /** \\brief Returns the unitary matrix in the Schur decomposition. \n      *\n      * \\returns A const reference to the matrix U.\n      *\n      * It is assumed that either the constructor\n      * ComplexSchur(const MatrixType& matrix, bool computeU) or the\n      * member function compute(const MatrixType& matrix, bool computeU)\n      * has been called before to compute the Schur decomposition of a\n      * matrix, and that \\p computeU was set to true (the default\n      * value).\n      *\n      * Example: \\include ComplexSchur_matrixU.cpp\n      * Output: \\verbinclude ComplexSchur_matrixU.out\n      */\n    const ComplexMatrixType& matrixU() const\n    {\n      eigen_assert(m_isInitialized && \"ComplexSchur is not initialized.\");\n      eigen_assert(m_matUisUptodate && \"The matrix U has not been computed during the ComplexSchur decomposition.\");\n      return m_matU;\n    }\n\n    /** \\brief Returns the triangular matrix in the Schur decomposition. \n      *\n      * \\returns A const reference to the matrix T.\n      *\n      * It is assumed that either the constructor\n      * ComplexSchur(const MatrixType& matrix, bool computeU) or the\n      * member function compute(const MatrixType& matrix, bool computeU)\n      * has been called before to compute the Schur decomposition of a\n      * matrix.\n      *\n      * Note that this function returns a plain square matrix. If you want to reference\n      * only the upper triangular part, use:\n      * \\code schur.matrixT().triangularView<Upper>() \\endcode \n      *\n      * Example: \\include ComplexSchur_matrixT.cpp\n      * Output: \\verbinclude ComplexSchur_matrixT.out\n      */\n    const ComplexMatrixType& matrixT() const\n    {\n      eigen_assert(m_isInitialized && \"ComplexSchur is not initialized.\");\n      return m_matT;\n    }\n\n    /** \\brief Computes Schur decomposition of given matrix. \n      * \n      * \\param[in]  matrix  Square matrix whose Schur decomposition is to be computed.\n      * \\param[in]  computeU  If true, both T and U are computed; if false, only T is computed.\n\n      * \\returns    Reference to \\c *this\n      *\n      * The Schur decomposition is computed by first reducing the\n      * matrix to Hessenberg form using the class\n      * HessenbergDecomposition. The Hessenberg matrix is then reduced\n      * to triangular form by performing QR iterations with a single\n      * shift. The cost of computing the Schur decomposition depends\n      * on the number of iterations; as a rough guide, it may be taken\n      * on the number of iterations; as a rough guide, it may be taken\n      * to be \\f$25n^3\\f$ complex flops, or \\f$10n^3\\f$ complex flops\n      * if \\a computeU is false.\n      *\n      * Example: \\include ComplexSchur_compute.cpp\n      * Output: \\verbinclude ComplexSchur_compute.out\n      *\n      * \\sa compute(const MatrixType&, bool, Index)\n      */\n    template<typename InputType>\n    ComplexSchur& compute(const EigenBase<InputType>& matrix, bool computeU = true);\n    \n    /** \\brief Compute Schur decomposition from a given Hessenberg matrix\n     *  \\param[in] matrixH Matrix in Hessenberg form H\n     *  \\param[in] matrixQ orthogonal matrix Q that transform a matrix A to H : A = Q H Q^T\n     *  \\param computeU Computes the matriX U of the Schur vectors\n     * \\return Reference to \\c *this\n     * \n     *  This routine assumes that the matrix is already reduced in Hessenberg form matrixH\n     *  using either the class HessenbergDecomposition or another mean. \n     *  It computes the upper quasi-triangular matrix T of the Schur decomposition of H\n     *  When computeU is true, this routine computes the matrix U such that \n     *  A = U T U^T =  (QZ) T (QZ)^T = Q H Q^T where A is the initial matrix\n     * \n     * NOTE Q is referenced if computeU is true; so, if the initial orthogonal matrix\n     * is not available, the user should give an identity matrix (Q.setIdentity())\n     * \n     * \\sa compute(const MatrixType&, bool)\n     */\n    template<typename HessMatrixType, typename OrthMatrixType>\n    ComplexSchur& computeFromHessenberg(const HessMatrixType& matrixH, const OrthMatrixType& matrixQ,  bool computeU=true);\n\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful, \\c NoConvergence otherwise.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"ComplexSchur is not initialized.\");\n      return m_info;\n    }\n\n    /** \\brief Sets the maximum number of iterations allowed. \n      *\n      * If not specified by the user, the maximum number of iterations is m_maxIterationsPerRow times the size\n      * of the matrix.\n      */\n    ComplexSchur& setMaxIterations(Index maxIters)\n    {\n      m_maxIters = maxIters;\n      return *this;\n    }\n\n    /** \\brief Returns the maximum number of iterations. */\n    Index getMaxIterations()\n    {\n      return m_maxIters;\n    }\n\n    /** \\brief Maximum number of iterations per row.\n      *\n      * If not otherwise specified, the maximum number of iterations is this number times the size of the\n      * matrix. It is currently set to 30.\n      */\n    static const int m_maxIterationsPerRow = 30;\n\n  protected:\n    ComplexMatrixType m_matT, m_matU;\n    HessenbergDecomposition<MatrixType> m_hess;\n    ComputationInfo m_info;\n    bool m_isInitialized;\n    bool m_matUisUptodate;\n    Index m_maxIters;\n\n  private:  \n    bool subdiagonalEntryIsNeglegible(Index i);\n    ComplexScalar computeShift(Index iu, Index iter);\n    void reduceToTriangularForm(bool computeU);\n    friend struct internal::complex_schur_reduce_to_hessenberg<MatrixType, NumTraits<Scalar>::IsComplex>;\n};\n\n/** If m_matT(i+1,i) is neglegible in floating point arithmetic\n  * compared to m_matT(i,i) and m_matT(j,j), then set it to zero and\n  * return true, else return false. */\ntemplate<typename MatrixType>\ninline bool ComplexSchur<MatrixType>::subdiagonalEntryIsNeglegible(Index i)\n{\n  RealScalar d = numext::norm1(m_matT.coeff(i,i)) + numext::norm1(m_matT.coeff(i+1,i+1));\n  RealScalar sd = numext::norm1(m_matT.coeff(i+1,i));\n  if (internal::isMuchSmallerThan(sd, d, NumTraits<RealScalar>::epsilon()))\n  {\n    m_matT.coeffRef(i+1,i) = ComplexScalar(0);\n    return true;\n  }\n  return false;\n}\n\n\n/** Compute the shift in the current QR iteration. */\ntemplate<typename MatrixType>\ntypename ComplexSchur<MatrixType>::ComplexScalar ComplexSchur<MatrixType>::computeShift(Index iu, Index iter)\n{\n  using std::abs;\n  if (iter == 10 || iter == 20) \n  {\n    // exceptional shift, taken from http://www.netlib.org/eispack/comqr.f\n    return abs(numext::real(m_matT.coeff(iu,iu-1))) + abs(numext::real(m_matT.coeff(iu-1,iu-2)));\n  }\n\n  // compute the shift as one of the eigenvalues of t, the 2x2\n  // diagonal block on the bottom of the active submatrix\n  Matrix<ComplexScalar,2,2> t = m_matT.template block<2,2>(iu-1,iu-1);\n  RealScalar normt = t.cwiseAbs().sum();\n  t /= normt;     // the normalization by sf is to avoid under/overflow\n\n  ComplexScalar b = t.coeff(0,1) * t.coeff(1,0);\n  ComplexScalar c = t.coeff(0,0) - t.coeff(1,1);\n  ComplexScalar disc = sqrt(c*c + RealScalar(4)*b);\n  ComplexScalar det = t.coeff(0,0) * t.coeff(1,1) - b;\n  ComplexScalar trace = t.coeff(0,0) + t.coeff(1,1);\n  ComplexScalar eival1 = (trace + disc) / RealScalar(2);\n  ComplexScalar eival2 = (trace - disc) / RealScalar(2);\n  RealScalar eival1_norm = numext::norm1(eival1);\n  RealScalar eival2_norm = numext::norm1(eival2);\n  // A division by zero can only occur if eival1==eival2==0.\n  // In this case, det==0, and all we have to do is checking that eival2_norm!=0\n  if(eival1_norm > eival2_norm)\n    eival2 = det / eival1;\n  else if(eival2_norm!=RealScalar(0))\n    eival1 = det / eival2;\n\n  // choose the eigenvalue closest to the bottom entry of the diagonal\n  if(numext::norm1(eival1-t.coeff(1,1)) < numext::norm1(eival2-t.coeff(1,1)))\n    return normt * eival1;\n  else\n    return normt * eival2;\n}\n\n\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nComplexSchur<MatrixType>& ComplexSchur<MatrixType>::compute(const EigenBase<InputType>& matrix, bool computeU)\n{\n  m_matUisUptodate = false;\n  eigen_assert(matrix.cols() == matrix.rows());\n\n  if(matrix.cols() == 1)\n  {\n    m_matT = matrix.derived().template cast<ComplexScalar>();\n    if(computeU)  m_matU = ComplexMatrixType::Identity(1,1);\n    m_info = Success;\n    m_isInitialized = true;\n    m_matUisUptodate = computeU;\n    return *this;\n  }\n\n  internal::complex_schur_reduce_to_hessenberg<MatrixType, NumTraits<Scalar>::IsComplex>::run(*this, matrix.derived(), computeU);\n  computeFromHessenberg(m_matT, m_matU, computeU);\n  return *this;\n}\n\ntemplate<typename MatrixType>\ntemplate<typename HessMatrixType, typename OrthMatrixType>\nComplexSchur<MatrixType>& ComplexSchur<MatrixType>::computeFromHessenberg(const HessMatrixType& matrixH, const OrthMatrixType& matrixQ, bool computeU)\n{\n  m_matT = matrixH;\n  if(computeU)\n    m_matU = matrixQ;\n  reduceToTriangularForm(computeU);\n  return *this;\n}\nnamespace internal {\n\n/* Reduce given matrix to Hessenberg form */\ntemplate<typename MatrixType, bool IsComplex>\nstruct complex_schur_reduce_to_hessenberg\n{\n  // this is the implementation for the case IsComplex = true\n  static void run(ComplexSchur<MatrixType>& _this, const MatrixType& matrix, bool computeU)\n  {\n    _this.m_hess.compute(matrix);\n    _this.m_matT = _this.m_hess.matrixH();\n    if(computeU)  _this.m_matU = _this.m_hess.matrixQ();\n  }\n};\n\ntemplate<typename MatrixType>\nstruct complex_schur_reduce_to_hessenberg<MatrixType, false>\n{\n  static void run(ComplexSchur<MatrixType>& _this, const MatrixType& matrix, bool computeU)\n  {\n    typedef typename ComplexSchur<MatrixType>::ComplexScalar ComplexScalar;\n\n    // Note: m_hess is over RealScalar; m_matT and m_matU is over ComplexScalar\n    _this.m_hess.compute(matrix);\n    _this.m_matT = _this.m_hess.matrixH().template cast<ComplexScalar>();\n    if(computeU)  \n    {\n      // This may cause an allocation which seems to be avoidable\n      MatrixType Q = _this.m_hess.matrixQ(); \n      _this.m_matU = Q.template cast<ComplexScalar>();\n    }\n  }\n};\n\n} // end namespace internal\n\n// Reduce the Hessenberg matrix m_matT to triangular form by QR iteration.\ntemplate<typename MatrixType>\nvoid ComplexSchur<MatrixType>::reduceToTriangularForm(bool computeU)\n{  \n  Index maxIters = m_maxIters;\n  if (maxIters == -1)\n    maxIters = m_maxIterationsPerRow * m_matT.rows();\n\n  // The matrix m_matT is divided in three parts. \n  // Rows 0,...,il-1 are decoupled from the rest because m_matT(il,il-1) is zero. \n  // Rows il,...,iu is the part we are working on (the active submatrix).\n  // Rows iu+1,...,end are already brought in triangular form.\n  Index iu = m_matT.cols() - 1;\n  Index il;\n  Index iter = 0; // number of iterations we are working on the (iu,iu) element\n  Index totalIter = 0; // number of iterations for whole matrix\n\n  while(true)\n  {\n    // find iu, the bottom row of the active submatrix\n    while(iu > 0)\n    {\n      if(!subdiagonalEntryIsNeglegible(iu-1)) break;\n      iter = 0;\n      --iu;\n    }\n\n    // if iu is zero then we are done; the whole matrix is triangularized\n    if(iu==0) break;\n\n    // if we spent too many iterations, we give up\n    iter++;\n    totalIter++;\n    if(totalIter > maxIters) break;\n\n    // find il, the top row of the active submatrix\n    il = iu-1;\n    while(il > 0 && !subdiagonalEntryIsNeglegible(il-1))\n    {\n      --il;\n    }\n\n    /* perform the QR step using Givens rotations. The first rotation\n       creates a bulge; the (il+2,il) element becomes nonzero. This\n       bulge is chased down to the bottom of the active submatrix. */\n\n    ComplexScalar shift = computeShift(iu, iter);\n    JacobiRotation<ComplexScalar> rot;\n    rot.makeGivens(m_matT.coeff(il,il) - shift, m_matT.coeff(il+1,il));\n    m_matT.rightCols(m_matT.cols()-il).applyOnTheLeft(il, il+1, rot.adjoint());\n    m_matT.topRows((std::min)(il+2,iu)+1).applyOnTheRight(il, il+1, rot);\n    if(computeU) m_matU.applyOnTheRight(il, il+1, rot);\n\n    for(Index i=il+1 ; i<iu ; i++)\n    {\n      rot.makeGivens(m_matT.coeffRef(i,i-1), m_matT.coeffRef(i+1,i-1), &m_matT.coeffRef(i,i-1));\n      m_matT.coeffRef(i+1,i-1) = ComplexScalar(0);\n      m_matT.rightCols(m_matT.cols()-i).applyOnTheLeft(i, i+1, rot.adjoint());\n      m_matT.topRows((std::min)(i+2,iu)+1).applyOnTheRight(i, i+1, rot);\n      if(computeU) m_matU.applyOnTheRight(i, i+1, rot);\n    }\n  }\n\n  if(totalIter <= maxIters)\n    m_info = Success;\n  else\n    m_info = NoConvergence;\n\n  m_isInitialized = true;\n  m_matUisUptodate = computeU;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_COMPLEX_SCHUR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Eigenvalues/ComplexSchur_LAPACKE.h",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Eigen bindings to LAPACKe\n *    Complex Schur needed to complex unsymmetrical eigenvalues/eigenvectors.\n ********************************************************************************\n*/\n\n#ifndef EIGEN_COMPLEX_SCHUR_LAPACKE_H\n#define EIGEN_COMPLEX_SCHUR_LAPACKE_H\n\nnamespace Eigen { \n\n/** \\internal Specialization for the data types supported by LAPACKe */\n\n#define EIGEN_LAPACKE_SCHUR_COMPLEX(EIGTYPE, LAPACKE_TYPE, LAPACKE_PREFIX, LAPACKE_PREFIX_U, EIGCOLROW, LAPACKE_COLROW) \\\ntemplate<> template<typename InputType> inline \\\nComplexSchur<Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW> >& \\\nComplexSchur<Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW> >::compute(const EigenBase<InputType>& matrix, bool computeU) \\\n{ \\\n  typedef Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW> MatrixType; \\\n  typedef MatrixType::RealScalar RealScalar; \\\n  typedef std::complex<RealScalar> ComplexScalar; \\\n\\\n  eigen_assert(matrix.cols() == matrix.rows()); \\\n\\\n  m_matUisUptodate = false; \\\n  if(matrix.cols() == 1) \\\n  { \\\n    m_matT = matrix.derived().template cast<ComplexScalar>(); \\\n    if(computeU)  m_matU = ComplexMatrixType::Identity(1,1); \\\n      m_info = Success; \\\n      m_isInitialized = true; \\\n      m_matUisUptodate = computeU; \\\n      return *this; \\\n  } \\\n  lapack_int n = internal::convert_index<lapack_int>(matrix.cols()), sdim, info; \\\n  lapack_int matrix_order = LAPACKE_COLROW; \\\n  char jobvs, sort='N'; \\\n  LAPACK_##LAPACKE_PREFIX_U##_SELECT1 select = 0; \\\n  jobvs = (computeU) ? 'V' : 'N'; \\\n  m_matU.resize(n, n); \\\n  lapack_int ldvs  = internal::convert_index<lapack_int>(m_matU.outerStride()); \\\n  m_matT = matrix; \\\n  lapack_int lda = internal::convert_index<lapack_int>(m_matT.outerStride()); \\\n  Matrix<EIGTYPE, Dynamic, Dynamic> w; \\\n  w.resize(n, 1);\\\n  info = LAPACKE_##LAPACKE_PREFIX##gees( matrix_order, jobvs, sort, select, n, (LAPACKE_TYPE*)m_matT.data(), lda, &sdim, (LAPACKE_TYPE*)w.data(), (LAPACKE_TYPE*)m_matU.data(), ldvs ); \\\n  if(info == 0) \\\n    m_info = Success; \\\n  else \\\n    m_info = NoConvergence; \\\n\\\n  m_isInitialized = true; \\\n  m_matUisUptodate = computeU; \\\n  return *this; \\\n\\\n}\n\nEIGEN_LAPACKE_SCHUR_COMPLEX(dcomplex, lapack_complex_double, z, Z, ColMajor, LAPACK_COL_MAJOR)\nEIGEN_LAPACKE_SCHUR_COMPLEX(scomplex, lapack_complex_float,  c, C, ColMajor, LAPACK_COL_MAJOR)\nEIGEN_LAPACKE_SCHUR_COMPLEX(dcomplex, lapack_complex_double, z, Z, RowMajor, LAPACK_ROW_MAJOR)\nEIGEN_LAPACKE_SCHUR_COMPLEX(scomplex, lapack_complex_float,  c, C, RowMajor, LAPACK_ROW_MAJOR)\n\n} // end namespace Eigen\n\n#endif // EIGEN_COMPLEX_SCHUR_LAPACKE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Eigenvalues/EigenSolver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010,2012 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_EIGENSOLVER_H\n#define EIGEN_EIGENSOLVER_H\n\n#include \"./RealSchur.h\"\n\nnamespace Eigen { \n\n/** \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  *\n  * \\class EigenSolver\n  *\n  * \\brief Computes eigenvalues and eigenvectors of general matrices\n  *\n  * \\tparam _MatrixType the type of the matrix of which we are computing the\n  * eigendecomposition; this is expected to be an instantiation of the Matrix\n  * class template. Currently, only real matrices are supported.\n  *\n  * The eigenvalues and eigenvectors of a matrix \\f$ A \\f$ are scalars\n  * \\f$ \\lambda \\f$ and vectors \\f$ v \\f$ such that \\f$ Av = \\lambda v \\f$.  If\n  * \\f$ D \\f$ is a diagonal matrix with the eigenvalues on the diagonal, and\n  * \\f$ V \\f$ is a matrix with the eigenvectors as its columns, then \\f$ A V =\n  * V D \\f$. The matrix \\f$ V \\f$ is almost always invertible, in which case we\n  * have \\f$ A = V D V^{-1} \\f$. This is called the eigendecomposition.\n  *\n  * The eigenvalues and eigenvectors of a matrix may be complex, even when the\n  * matrix is real. However, we can choose real matrices \\f$ V \\f$ and \\f$ D\n  * \\f$ satisfying \\f$ A V = V D \\f$, just like the eigendecomposition, if the\n  * matrix \\f$ D \\f$ is not required to be diagonal, but if it is allowed to\n  * have blocks of the form\n  * \\f[ \\begin{bmatrix} u & v \\\\ -v & u \\end{bmatrix} \\f]\n  * (where \\f$ u \\f$ and \\f$ v \\f$ are real numbers) on the diagonal.  These\n  * blocks correspond to complex eigenvalue pairs \\f$ u \\pm iv \\f$. We call\n  * this variant of the eigendecomposition the pseudo-eigendecomposition.\n  *\n  * Call the function compute() to compute the eigenvalues and eigenvectors of\n  * a given matrix. Alternatively, you can use the \n  * EigenSolver(const MatrixType&, bool) constructor which computes the\n  * eigenvalues and eigenvectors at construction time. Once the eigenvalue and\n  * eigenvectors are computed, they can be retrieved with the eigenvalues() and\n  * eigenvectors() functions. The pseudoEigenvalueMatrix() and\n  * pseudoEigenvectors() methods allow the construction of the\n  * pseudo-eigendecomposition.\n  *\n  * The documentation for EigenSolver(const MatrixType&, bool) contains an\n  * example of the typical use of this class.\n  *\n  * \\note The implementation is adapted from\n  * <a href=\"http://math.nist.gov/javanumerics/jama/\">JAMA</a> (public domain).\n  * Their code is based on EISPACK.\n  *\n  * \\sa MatrixBase::eigenvalues(), class ComplexEigenSolver, class SelfAdjointEigenSolver\n  */\ntemplate<typename _MatrixType> class EigenSolver\n{\n  public:\n\n    /** \\brief Synonym for the template parameter \\p _MatrixType. */\n    typedef _MatrixType MatrixType;\n\n    enum {\n      RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      Options = MatrixType::Options,\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n\n    /** \\brief Scalar type for matrices of type #MatrixType. */\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n\n    /** \\brief Complex scalar type for #MatrixType. \n      *\n      * This is \\c std::complex<Scalar> if #Scalar is real (e.g.,\n      * \\c float or \\c double) and just \\c Scalar if #Scalar is\n      * complex.\n      */\n    typedef std::complex<RealScalar> ComplexScalar;\n\n    /** \\brief Type for vector of eigenvalues as returned by eigenvalues(). \n      *\n      * This is a column vector with entries of type #ComplexScalar.\n      * The length of the vector is the size of #MatrixType.\n      */\n    typedef Matrix<ComplexScalar, ColsAtCompileTime, 1, Options & ~RowMajor, MaxColsAtCompileTime, 1> EigenvalueType;\n\n    /** \\brief Type for matrix of eigenvectors as returned by eigenvectors(). \n      *\n      * This is a square matrix with entries of type #ComplexScalar. \n      * The size is the same as the size of #MatrixType.\n      */\n    typedef Matrix<ComplexScalar, RowsAtCompileTime, ColsAtCompileTime, Options, MaxRowsAtCompileTime, MaxColsAtCompileTime> EigenvectorsType;\n\n    /** \\brief Default constructor.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via EigenSolver::compute(const MatrixType&, bool).\n      *\n      * \\sa compute() for an example.\n      */\n    EigenSolver() : m_eivec(), m_eivalues(), m_isInitialized(false), m_eigenvectorsOk(false), m_realSchur(), m_matT(), m_tmp() {}\n\n    /** \\brief Default constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem \\a size.\n      * \\sa EigenSolver()\n      */\n    explicit EigenSolver(Index size)\n      : m_eivec(size, size),\n        m_eivalues(size),\n        m_isInitialized(false),\n        m_eigenvectorsOk(false),\n        m_realSchur(size),\n        m_matT(size, size), \n        m_tmp(size)\n    {}\n\n    /** \\brief Constructor; computes eigendecomposition of given matrix. \n      * \n      * \\param[in]  matrix  Square matrix whose eigendecomposition is to be computed.\n      * \\param[in]  computeEigenvectors  If true, both the eigenvectors and the\n      *    eigenvalues are computed; if false, only the eigenvalues are\n      *    computed. \n      *\n      * This constructor calls compute() to compute the eigenvalues\n      * and eigenvectors.\n      *\n      * Example: \\include EigenSolver_EigenSolver_MatrixType.cpp\n      * Output: \\verbinclude EigenSolver_EigenSolver_MatrixType.out\n      *\n      * \\sa compute()\n      */\n    template<typename InputType>\n    explicit EigenSolver(const EigenBase<InputType>& matrix, bool computeEigenvectors = true)\n      : m_eivec(matrix.rows(), matrix.cols()),\n        m_eivalues(matrix.cols()),\n        m_isInitialized(false),\n        m_eigenvectorsOk(false),\n        m_realSchur(matrix.cols()),\n        m_matT(matrix.rows(), matrix.cols()), \n        m_tmp(matrix.cols())\n    {\n      compute(matrix.derived(), computeEigenvectors);\n    }\n\n    /** \\brief Returns the eigenvectors of given matrix. \n      *\n      * \\returns  %Matrix whose columns are the (possibly complex) eigenvectors.\n      *\n      * \\pre Either the constructor \n      * EigenSolver(const MatrixType&,bool) or the member function\n      * compute(const MatrixType&, bool) has been called before, and\n      * \\p computeEigenvectors was set to true (the default).\n      *\n      * Column \\f$ k \\f$ of the returned matrix is an eigenvector corresponding\n      * to eigenvalue number \\f$ k \\f$ as returned by eigenvalues().  The\n      * eigenvectors are normalized to have (Euclidean) norm equal to one. The\n      * matrix returned by this function is the matrix \\f$ V \\f$ in the\n      * eigendecomposition \\f$ A = V D V^{-1} \\f$, if it exists.\n      *\n      * Example: \\include EigenSolver_eigenvectors.cpp\n      * Output: \\verbinclude EigenSolver_eigenvectors.out\n      *\n      * \\sa eigenvalues(), pseudoEigenvectors()\n      */\n    EigenvectorsType eigenvectors() const;\n\n    /** \\brief Returns the pseudo-eigenvectors of given matrix. \n      *\n      * \\returns  Const reference to matrix whose columns are the pseudo-eigenvectors.\n      *\n      * \\pre Either the constructor \n      * EigenSolver(const MatrixType&,bool) or the member function\n      * compute(const MatrixType&, bool) has been called before, and\n      * \\p computeEigenvectors was set to true (the default).\n      *\n      * The real matrix \\f$ V \\f$ returned by this function and the\n      * block-diagonal matrix \\f$ D \\f$ returned by pseudoEigenvalueMatrix()\n      * satisfy \\f$ AV = VD \\f$.\n      *\n      * Example: \\include EigenSolver_pseudoEigenvectors.cpp\n      * Output: \\verbinclude EigenSolver_pseudoEigenvectors.out\n      *\n      * \\sa pseudoEigenvalueMatrix(), eigenvectors()\n      */\n    const MatrixType& pseudoEigenvectors() const\n    {\n      eigen_assert(m_isInitialized && \"EigenSolver is not initialized.\");\n      eigen_assert(m_eigenvectorsOk && \"The eigenvectors have not been computed together with the eigenvalues.\");\n      return m_eivec;\n    }\n\n    /** \\brief Returns the block-diagonal matrix in the pseudo-eigendecomposition.\n      *\n      * \\returns  A block-diagonal matrix.\n      *\n      * \\pre Either the constructor \n      * EigenSolver(const MatrixType&,bool) or the member function\n      * compute(const MatrixType&, bool) has been called before.\n      *\n      * The matrix \\f$ D \\f$ returned by this function is real and\n      * block-diagonal. The blocks on the diagonal are either 1-by-1 or 2-by-2\n      * blocks of the form\n      * \\f$ \\begin{bmatrix} u & v \\\\ -v & u \\end{bmatrix} \\f$.\n      * These blocks are not sorted in any particular order.\n      * The matrix \\f$ D \\f$ and the matrix \\f$ V \\f$ returned by\n      * pseudoEigenvectors() satisfy \\f$ AV = VD \\f$.\n      *\n      * \\sa pseudoEigenvectors() for an example, eigenvalues()\n      */\n    MatrixType pseudoEigenvalueMatrix() const;\n\n    /** \\brief Returns the eigenvalues of given matrix. \n      *\n      * \\returns A const reference to the column vector containing the eigenvalues.\n      *\n      * \\pre Either the constructor \n      * EigenSolver(const MatrixType&,bool) or the member function\n      * compute(const MatrixType&, bool) has been called before.\n      *\n      * The eigenvalues are repeated according to their algebraic multiplicity,\n      * so there are as many eigenvalues as rows in the matrix. The eigenvalues \n      * are not sorted in any particular order.\n      *\n      * Example: \\include EigenSolver_eigenvalues.cpp\n      * Output: \\verbinclude EigenSolver_eigenvalues.out\n      *\n      * \\sa eigenvectors(), pseudoEigenvalueMatrix(),\n      *     MatrixBase::eigenvalues()\n      */\n    const EigenvalueType& eigenvalues() const\n    {\n      eigen_assert(m_isInitialized && \"EigenSolver is not initialized.\");\n      return m_eivalues;\n    }\n\n    /** \\brief Computes eigendecomposition of given matrix. \n      * \n      * \\param[in]  matrix  Square matrix whose eigendecomposition is to be computed.\n      * \\param[in]  computeEigenvectors  If true, both the eigenvectors and the\n      *    eigenvalues are computed; if false, only the eigenvalues are\n      *    computed. \n      * \\returns    Reference to \\c *this\n      *\n      * This function computes the eigenvalues of the real matrix \\p matrix.\n      * The eigenvalues() function can be used to retrieve them.  If \n      * \\p computeEigenvectors is true, then the eigenvectors are also computed\n      * and can be retrieved by calling eigenvectors().\n      *\n      * The matrix is first reduced to real Schur form using the RealSchur\n      * class. The Schur decomposition is then used to compute the eigenvalues\n      * and eigenvectors.\n      *\n      * The cost of the computation is dominated by the cost of the\n      * Schur decomposition, which is very approximately \\f$ 25n^3 \\f$\n      * (where \\f$ n \\f$ is the size of the matrix) if \\p computeEigenvectors \n      * is true, and \\f$ 10n^3 \\f$ if \\p computeEigenvectors is false.\n      *\n      * This method reuses of the allocated data in the EigenSolver object.\n      *\n      * Example: \\include EigenSolver_compute.cpp\n      * Output: \\verbinclude EigenSolver_compute.out\n      */\n    template<typename InputType>\n    EigenSolver& compute(const EigenBase<InputType>& matrix, bool computeEigenvectors = true);\n\n    /** \\returns NumericalIssue if the input contains INF or NaN values or overflow occurred. Returns Success otherwise. */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"EigenSolver is not initialized.\");\n      return m_info;\n    }\n\n    /** \\brief Sets the maximum number of iterations allowed. */\n    EigenSolver& setMaxIterations(Index maxIters)\n    {\n      m_realSchur.setMaxIterations(maxIters);\n      return *this;\n    }\n\n    /** \\brief Returns the maximum number of iterations. */\n    Index getMaxIterations()\n    {\n      return m_realSchur.getMaxIterations();\n    }\n\n  private:\n    void doComputeEigenvectors();\n\n  protected:\n    \n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n      EIGEN_STATIC_ASSERT(!NumTraits<Scalar>::IsComplex, NUMERIC_TYPE_MUST_BE_REAL);\n    }\n    \n    MatrixType m_eivec;\n    EigenvalueType m_eivalues;\n    bool m_isInitialized;\n    bool m_eigenvectorsOk;\n    ComputationInfo m_info;\n    RealSchur<MatrixType> m_realSchur;\n    MatrixType m_matT;\n\n    typedef Matrix<Scalar, ColsAtCompileTime, 1, Options & ~RowMajor, MaxColsAtCompileTime, 1> ColumnVectorType;\n    ColumnVectorType m_tmp;\n};\n\ntemplate<typename MatrixType>\nMatrixType EigenSolver<MatrixType>::pseudoEigenvalueMatrix() const\n{\n  eigen_assert(m_isInitialized && \"EigenSolver is not initialized.\");\n  const RealScalar precision = RealScalar(2)*NumTraits<RealScalar>::epsilon();\n  Index n = m_eivalues.rows();\n  MatrixType matD = MatrixType::Zero(n,n);\n  for (Index i=0; i<n; ++i)\n  {\n    if (internal::isMuchSmallerThan(numext::imag(m_eivalues.coeff(i)), numext::real(m_eivalues.coeff(i)), precision))\n      matD.coeffRef(i,i) = numext::real(m_eivalues.coeff(i));\n    else\n    {\n      matD.template block<2,2>(i,i) <<  numext::real(m_eivalues.coeff(i)), numext::imag(m_eivalues.coeff(i)),\n                                       -numext::imag(m_eivalues.coeff(i)), numext::real(m_eivalues.coeff(i));\n      ++i;\n    }\n  }\n  return matD;\n}\n\ntemplate<typename MatrixType>\ntypename EigenSolver<MatrixType>::EigenvectorsType EigenSolver<MatrixType>::eigenvectors() const\n{\n  eigen_assert(m_isInitialized && \"EigenSolver is not initialized.\");\n  eigen_assert(m_eigenvectorsOk && \"The eigenvectors have not been computed together with the eigenvalues.\");\n  const RealScalar precision = RealScalar(2)*NumTraits<RealScalar>::epsilon();\n  Index n = m_eivec.cols();\n  EigenvectorsType matV(n,n);\n  for (Index j=0; j<n; ++j)\n  {\n    if (internal::isMuchSmallerThan(numext::imag(m_eivalues.coeff(j)), numext::real(m_eivalues.coeff(j)), precision) || j+1==n)\n    {\n      // we have a real eigen value\n      matV.col(j) = m_eivec.col(j).template cast<ComplexScalar>();\n      matV.col(j).normalize();\n    }\n    else\n    {\n      // we have a pair of complex eigen values\n      for (Index i=0; i<n; ++i)\n      {\n        matV.coeffRef(i,j)   = ComplexScalar(m_eivec.coeff(i,j),  m_eivec.coeff(i,j+1));\n        matV.coeffRef(i,j+1) = ComplexScalar(m_eivec.coeff(i,j), -m_eivec.coeff(i,j+1));\n      }\n      matV.col(j).normalize();\n      matV.col(j+1).normalize();\n      ++j;\n    }\n  }\n  return matV;\n}\n\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nEigenSolver<MatrixType>& \nEigenSolver<MatrixType>::compute(const EigenBase<InputType>& matrix, bool computeEigenvectors)\n{\n  check_template_parameters();\n  \n  using std::sqrt;\n  using std::abs;\n  using numext::isfinite;\n  eigen_assert(matrix.cols() == matrix.rows());\n\n  // Reduce to real Schur form.\n  m_realSchur.compute(matrix.derived(), computeEigenvectors);\n  \n  m_info = m_realSchur.info();\n\n  if (m_info == Success)\n  {\n    m_matT = m_realSchur.matrixT();\n    if (computeEigenvectors)\n      m_eivec = m_realSchur.matrixU();\n  \n    // Compute eigenvalues from matT\n    m_eivalues.resize(matrix.cols());\n    Index i = 0;\n    while (i < matrix.cols()) \n    {\n      if (i == matrix.cols() - 1 || m_matT.coeff(i+1, i) == Scalar(0)) \n      {\n        m_eivalues.coeffRef(i) = m_matT.coeff(i, i);\n        if(!(isfinite)(m_eivalues.coeffRef(i)))\n        {\n          m_isInitialized = true;\n          m_eigenvectorsOk = false;\n          m_info = NumericalIssue;\n          return *this;\n        }\n        ++i;\n      }\n      else\n      {\n        Scalar p = Scalar(0.5) * (m_matT.coeff(i, i) - m_matT.coeff(i+1, i+1));\n        Scalar z;\n        // Compute z = sqrt(abs(p * p + m_matT.coeff(i+1, i) * m_matT.coeff(i, i+1)));\n        // without overflow\n        {\n          Scalar t0 = m_matT.coeff(i+1, i);\n          Scalar t1 = m_matT.coeff(i, i+1);\n          Scalar maxval = numext::maxi<Scalar>(abs(p),numext::maxi<Scalar>(abs(t0),abs(t1)));\n          t0 /= maxval;\n          t1 /= maxval;\n          Scalar p0 = p/maxval;\n          z = maxval * sqrt(abs(p0 * p0 + t0 * t1));\n        }\n        \n        m_eivalues.coeffRef(i)   = ComplexScalar(m_matT.coeff(i+1, i+1) + p, z);\n        m_eivalues.coeffRef(i+1) = ComplexScalar(m_matT.coeff(i+1, i+1) + p, -z);\n        if(!((isfinite)(m_eivalues.coeffRef(i)) && (isfinite)(m_eivalues.coeffRef(i+1))))\n        {\n          m_isInitialized = true;\n          m_eigenvectorsOk = false;\n          m_info = NumericalIssue;\n          return *this;\n        }\n        i += 2;\n      }\n    }\n    \n    // Compute eigenvectors.\n    if (computeEigenvectors)\n      doComputeEigenvectors();\n  }\n\n  m_isInitialized = true;\n  m_eigenvectorsOk = computeEigenvectors;\n\n  return *this;\n}\n\n\ntemplate<typename MatrixType>\nvoid EigenSolver<MatrixType>::doComputeEigenvectors()\n{\n  using std::abs;\n  const Index size = m_eivec.cols();\n  const Scalar eps = NumTraits<Scalar>::epsilon();\n\n  // inefficient! this is already computed in RealSchur\n  Scalar norm(0);\n  for (Index j = 0; j < size; ++j)\n  {\n    norm += m_matT.row(j).segment((std::max)(j-1,Index(0)), size-(std::max)(j-1,Index(0))).cwiseAbs().sum();\n  }\n  \n  // Backsubstitute to find vectors of upper triangular form\n  if (norm == Scalar(0))\n  {\n    return;\n  }\n\n  for (Index n = size-1; n >= 0; n--)\n  {\n    Scalar p = m_eivalues.coeff(n).real();\n    Scalar q = m_eivalues.coeff(n).imag();\n\n    // Scalar vector\n    if (q == Scalar(0))\n    {\n      Scalar lastr(0), lastw(0);\n      Index l = n;\n\n      m_matT.coeffRef(n,n) = Scalar(1);\n      for (Index i = n-1; i >= 0; i--)\n      {\n        Scalar w = m_matT.coeff(i,i) - p;\n        Scalar r = m_matT.row(i).segment(l,n-l+1).dot(m_matT.col(n).segment(l, n-l+1));\n\n        if (m_eivalues.coeff(i).imag() < Scalar(0))\n        {\n          lastw = w;\n          lastr = r;\n        }\n        else\n        {\n          l = i;\n          if (m_eivalues.coeff(i).imag() == Scalar(0))\n          {\n            if (w != Scalar(0))\n              m_matT.coeffRef(i,n) = -r / w;\n            else\n              m_matT.coeffRef(i,n) = -r / (eps * norm);\n          }\n          else // Solve real equations\n          {\n            Scalar x = m_matT.coeff(i,i+1);\n            Scalar y = m_matT.coeff(i+1,i);\n            Scalar denom = (m_eivalues.coeff(i).real() - p) * (m_eivalues.coeff(i).real() - p) + m_eivalues.coeff(i).imag() * m_eivalues.coeff(i).imag();\n            Scalar t = (x * lastr - lastw * r) / denom;\n            m_matT.coeffRef(i,n) = t;\n            if (abs(x) > abs(lastw))\n              m_matT.coeffRef(i+1,n) = (-r - w * t) / x;\n            else\n              m_matT.coeffRef(i+1,n) = (-lastr - y * t) / lastw;\n          }\n\n          // Overflow control\n          Scalar t = abs(m_matT.coeff(i,n));\n          if ((eps * t) * t > Scalar(1))\n            m_matT.col(n).tail(size-i) /= t;\n        }\n      }\n    }\n    else if (q < Scalar(0) && n > 0) // Complex vector\n    {\n      Scalar lastra(0), lastsa(0), lastw(0);\n      Index l = n-1;\n\n      // Last vector component imaginary so matrix is triangular\n      if (abs(m_matT.coeff(n,n-1)) > abs(m_matT.coeff(n-1,n)))\n      {\n        m_matT.coeffRef(n-1,n-1) = q / m_matT.coeff(n,n-1);\n        m_matT.coeffRef(n-1,n) = -(m_matT.coeff(n,n) - p) / m_matT.coeff(n,n-1);\n      }\n      else\n      {\n        ComplexScalar cc = ComplexScalar(Scalar(0),-m_matT.coeff(n-1,n)) / ComplexScalar(m_matT.coeff(n-1,n-1)-p,q);\n        m_matT.coeffRef(n-1,n-1) = numext::real(cc);\n        m_matT.coeffRef(n-1,n) = numext::imag(cc);\n      }\n      m_matT.coeffRef(n,n-1) = Scalar(0);\n      m_matT.coeffRef(n,n) = Scalar(1);\n      for (Index i = n-2; i >= 0; i--)\n      {\n        Scalar ra = m_matT.row(i).segment(l, n-l+1).dot(m_matT.col(n-1).segment(l, n-l+1));\n        Scalar sa = m_matT.row(i).segment(l, n-l+1).dot(m_matT.col(n).segment(l, n-l+1));\n        Scalar w = m_matT.coeff(i,i) - p;\n\n        if (m_eivalues.coeff(i).imag() < Scalar(0))\n        {\n          lastw = w;\n          lastra = ra;\n          lastsa = sa;\n        }\n        else\n        {\n          l = i;\n          if (m_eivalues.coeff(i).imag() == RealScalar(0))\n          {\n            ComplexScalar cc = ComplexScalar(-ra,-sa) / ComplexScalar(w,q);\n            m_matT.coeffRef(i,n-1) = numext::real(cc);\n            m_matT.coeffRef(i,n) = numext::imag(cc);\n          }\n          else\n          {\n            // Solve complex equations\n            Scalar x = m_matT.coeff(i,i+1);\n            Scalar y = m_matT.coeff(i+1,i);\n            Scalar vr = (m_eivalues.coeff(i).real() - p) * (m_eivalues.coeff(i).real() - p) + m_eivalues.coeff(i).imag() * m_eivalues.coeff(i).imag() - q * q;\n            Scalar vi = (m_eivalues.coeff(i).real() - p) * Scalar(2) * q;\n            if ((vr == Scalar(0)) && (vi == Scalar(0)))\n              vr = eps * norm * (abs(w) + abs(q) + abs(x) + abs(y) + abs(lastw));\n\n            ComplexScalar cc = ComplexScalar(x*lastra-lastw*ra+q*sa,x*lastsa-lastw*sa-q*ra) / ComplexScalar(vr,vi);\n            m_matT.coeffRef(i,n-1) = numext::real(cc);\n            m_matT.coeffRef(i,n) = numext::imag(cc);\n            if (abs(x) > (abs(lastw) + abs(q)))\n            {\n              m_matT.coeffRef(i+1,n-1) = (-ra - w * m_matT.coeff(i,n-1) + q * m_matT.coeff(i,n)) / x;\n              m_matT.coeffRef(i+1,n) = (-sa - w * m_matT.coeff(i,n) - q * m_matT.coeff(i,n-1)) / x;\n            }\n            else\n            {\n              cc = ComplexScalar(-lastra-y*m_matT.coeff(i,n-1),-lastsa-y*m_matT.coeff(i,n)) / ComplexScalar(lastw,q);\n              m_matT.coeffRef(i+1,n-1) = numext::real(cc);\n              m_matT.coeffRef(i+1,n) = numext::imag(cc);\n            }\n          }\n\n          // Overflow control\n          Scalar t = numext::maxi<Scalar>(abs(m_matT.coeff(i,n-1)),abs(m_matT.coeff(i,n)));\n          if ((eps * t) * t > Scalar(1))\n            m_matT.block(i, n-1, size-i, 2) /= t;\n\n        }\n      }\n      \n      // We handled a pair of complex conjugate eigenvalues, so need to skip them both\n      n--;\n    }\n    else\n    {\n      eigen_assert(0 && \"Internal bug in EigenSolver (INF or NaN has not been detected)\"); // this should not happen\n    }\n  }\n\n  // Back transformation to get eigenvectors of original matrix\n  for (Index j = size-1; j >= 0; j--)\n  {\n    m_tmp.noalias() = m_eivec.leftCols(j+1) * m_matT.col(j).segment(0, j+1);\n    m_eivec.col(j) = m_tmp;\n  }\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_EIGENSOLVER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Eigenvalues/GeneralizedEigenSolver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012-2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010,2012 Jitse Niesen <jitse@maths.leeds.ac.uk>\n// Copyright (C) 2016 Tobias Wood <tobias@spinicist.org.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_GENERALIZEDEIGENSOLVER_H\n#define EIGEN_GENERALIZEDEIGENSOLVER_H\n\n#include \"./RealQZ.h\"\n\nnamespace Eigen { \n\n/** \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  *\n  * \\class GeneralizedEigenSolver\n  *\n  * \\brief Computes the generalized eigenvalues and eigenvectors of a pair of general matrices\n  *\n  * \\tparam _MatrixType the type of the matrices of which we are computing the\n  * eigen-decomposition; this is expected to be an instantiation of the Matrix\n  * class template. Currently, only real matrices are supported.\n  *\n  * The generalized eigenvalues and eigenvectors of a matrix pair \\f$ A \\f$ and \\f$ B \\f$ are scalars\n  * \\f$ \\lambda \\f$ and vectors \\f$ v \\f$ such that \\f$ Av = \\lambda Bv \\f$.  If\n  * \\f$ D \\f$ is a diagonal matrix with the eigenvalues on the diagonal, and\n  * \\f$ V \\f$ is a matrix with the eigenvectors as its columns, then \\f$ A V =\n  * B V D \\f$. The matrix \\f$ V \\f$ is almost always invertible, in which case we\n  * have \\f$ A = B V D V^{-1} \\f$. This is called the generalized eigen-decomposition.\n  *\n  * The generalized eigenvalues and eigenvectors of a matrix pair may be complex, even when the\n  * matrices are real. Moreover, the generalized eigenvalue might be infinite if the matrix B is\n  * singular. To workaround this difficulty, the eigenvalues are provided as a pair of complex \\f$ \\alpha \\f$\n  * and real \\f$ \\beta \\f$ such that: \\f$ \\lambda_i = \\alpha_i / \\beta_i \\f$. If \\f$ \\beta_i \\f$ is (nearly) zero,\n  * then one can consider the well defined left eigenvalue \\f$ \\mu = \\beta_i / \\alpha_i\\f$ such that:\n  * \\f$ \\mu_i A v_i = B v_i \\f$, or even \\f$ \\mu_i u_i^T A  = u_i^T B \\f$ where \\f$ u_i \\f$ is\n  * called the left eigenvector.\n  *\n  * Call the function compute() to compute the generalized eigenvalues and eigenvectors of\n  * a given matrix pair. Alternatively, you can use the\n  * GeneralizedEigenSolver(const MatrixType&, const MatrixType&, bool) constructor which computes the\n  * eigenvalues and eigenvectors at construction time. Once the eigenvalue and\n  * eigenvectors are computed, they can be retrieved with the eigenvalues() and\n  * eigenvectors() functions.\n  *\n  * Here is an usage example of this class:\n  * Example: \\include GeneralizedEigenSolver.cpp\n  * Output: \\verbinclude GeneralizedEigenSolver.out\n  *\n  * \\sa MatrixBase::eigenvalues(), class ComplexEigenSolver, class SelfAdjointEigenSolver\n  */\ntemplate<typename _MatrixType> class GeneralizedEigenSolver\n{\n  public:\n\n    /** \\brief Synonym for the template parameter \\p _MatrixType. */\n    typedef _MatrixType MatrixType;\n\n    enum {\n      RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      Options = MatrixType::Options,\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n\n    /** \\brief Scalar type for matrices of type #MatrixType. */\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n\n    /** \\brief Complex scalar type for #MatrixType. \n      *\n      * This is \\c std::complex<Scalar> if #Scalar is real (e.g.,\n      * \\c float or \\c double) and just \\c Scalar if #Scalar is\n      * complex.\n      */\n    typedef std::complex<RealScalar> ComplexScalar;\n\n    /** \\brief Type for vector of real scalar values eigenvalues as returned by betas().\n      *\n      * This is a column vector with entries of type #Scalar.\n      * The length of the vector is the size of #MatrixType.\n      */\n    typedef Matrix<Scalar, ColsAtCompileTime, 1, Options & ~RowMajor, MaxColsAtCompileTime, 1> VectorType;\n\n    /** \\brief Type for vector of complex scalar values eigenvalues as returned by alphas().\n      *\n      * This is a column vector with entries of type #ComplexScalar.\n      * The length of the vector is the size of #MatrixType.\n      */\n    typedef Matrix<ComplexScalar, ColsAtCompileTime, 1, Options & ~RowMajor, MaxColsAtCompileTime, 1> ComplexVectorType;\n\n    /** \\brief Expression type for the eigenvalues as returned by eigenvalues().\n      */\n    typedef CwiseBinaryOp<internal::scalar_quotient_op<ComplexScalar,Scalar>,ComplexVectorType,VectorType> EigenvalueType;\n\n    /** \\brief Type for matrix of eigenvectors as returned by eigenvectors(). \n      *\n      * This is a square matrix with entries of type #ComplexScalar. \n      * The size is the same as the size of #MatrixType.\n      */\n    typedef Matrix<ComplexScalar, RowsAtCompileTime, ColsAtCompileTime, Options, MaxRowsAtCompileTime, MaxColsAtCompileTime> EigenvectorsType;\n\n    /** \\brief Default constructor.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via EigenSolver::compute(const MatrixType&, bool).\n      *\n      * \\sa compute() for an example.\n      */\n    GeneralizedEigenSolver()\n      : m_eivec(),\n        m_alphas(),\n        m_betas(),\n        m_valuesOkay(false),\n        m_vectorsOkay(false),\n        m_realQZ()\n    {}\n\n    /** \\brief Default constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem \\a size.\n      * \\sa GeneralizedEigenSolver()\n      */\n    explicit GeneralizedEigenSolver(Index size)\n      : m_eivec(size, size),\n        m_alphas(size),\n        m_betas(size),\n        m_valuesOkay(false),\n        m_vectorsOkay(false),\n        m_realQZ(size),\n        m_tmp(size)\n    {}\n\n    /** \\brief Constructor; computes the generalized eigendecomposition of given matrix pair.\n      * \n      * \\param[in]  A  Square matrix whose eigendecomposition is to be computed.\n      * \\param[in]  B  Square matrix whose eigendecomposition is to be computed.\n      * \\param[in]  computeEigenvectors  If true, both the eigenvectors and the\n      *    eigenvalues are computed; if false, only the eigenvalues are computed.\n      *\n      * This constructor calls compute() to compute the generalized eigenvalues\n      * and eigenvectors.\n      *\n      * \\sa compute()\n      */\n    GeneralizedEigenSolver(const MatrixType& A, const MatrixType& B, bool computeEigenvectors = true)\n      : m_eivec(A.rows(), A.cols()),\n        m_alphas(A.cols()),\n        m_betas(A.cols()),\n        m_valuesOkay(false),\n        m_vectorsOkay(false),\n        m_realQZ(A.cols()),\n        m_tmp(A.cols())\n    {\n      compute(A, B, computeEigenvectors);\n    }\n\n    /* \\brief Returns the computed generalized eigenvectors.\n      *\n      * \\returns  %Matrix whose columns are the (possibly complex) right eigenvectors.\n      * i.e. the eigenvectors that solve (A - l*B)x = 0. The ordering matches the eigenvalues.\n      *\n      * \\pre Either the constructor \n      * GeneralizedEigenSolver(const MatrixType&,const MatrixType&, bool) or the member function\n      * compute(const MatrixType&, const MatrixType& bool) has been called before, and\n      * \\p computeEigenvectors was set to true (the default).\n      *\n      * \\sa eigenvalues()\n      */\n    EigenvectorsType eigenvectors() const {\n      eigen_assert(m_vectorsOkay && \"Eigenvectors for GeneralizedEigenSolver were not calculated.\");\n      return m_eivec;\n    }\n\n    /** \\brief Returns an expression of the computed generalized eigenvalues.\n      *\n      * \\returns An expression of the column vector containing the eigenvalues.\n      *\n      * It is a shortcut for \\code this->alphas().cwiseQuotient(this->betas()); \\endcode\n      * Not that betas might contain zeros. It is therefore not recommended to use this function,\n      * but rather directly deal with the alphas and betas vectors.\n      *\n      * \\pre Either the constructor \n      * GeneralizedEigenSolver(const MatrixType&,const MatrixType&,bool) or the member function\n      * compute(const MatrixType&,const MatrixType&,bool) has been called before.\n      *\n      * The eigenvalues are repeated according to their algebraic multiplicity,\n      * so there are as many eigenvalues as rows in the matrix. The eigenvalues \n      * are not sorted in any particular order.\n      *\n      * \\sa alphas(), betas(), eigenvectors()\n      */\n    EigenvalueType eigenvalues() const\n    {\n      eigen_assert(m_valuesOkay && \"GeneralizedEigenSolver is not initialized.\");\n      return EigenvalueType(m_alphas,m_betas);\n    }\n\n    /** \\returns A const reference to the vectors containing the alpha values\n      *\n      * This vector permits to reconstruct the j-th eigenvalues as alphas(i)/betas(j).\n      *\n      * \\sa betas(), eigenvalues() */\n    ComplexVectorType alphas() const\n    {\n      eigen_assert(m_valuesOkay && \"GeneralizedEigenSolver is not initialized.\");\n      return m_alphas;\n    }\n\n    /** \\returns A const reference to the vectors containing the beta values\n      *\n      * This vector permits to reconstruct the j-th eigenvalues as alphas(i)/betas(j).\n      *\n      * \\sa alphas(), eigenvalues() */\n    VectorType betas() const\n    {\n      eigen_assert(m_valuesOkay && \"GeneralizedEigenSolver is not initialized.\");\n      return m_betas;\n    }\n\n    /** \\brief Computes generalized eigendecomposition of given matrix.\n      * \n      * \\param[in]  A  Square matrix whose eigendecomposition is to be computed.\n      * \\param[in]  B  Square matrix whose eigendecomposition is to be computed.\n      * \\param[in]  computeEigenvectors  If true, both the eigenvectors and the\n      *    eigenvalues are computed; if false, only the eigenvalues are\n      *    computed. \n      * \\returns    Reference to \\c *this\n      *\n      * This function computes the eigenvalues of the real matrix \\p matrix.\n      * The eigenvalues() function can be used to retrieve them.  If \n      * \\p computeEigenvectors is true, then the eigenvectors are also computed\n      * and can be retrieved by calling eigenvectors().\n      *\n      * The matrix is first reduced to real generalized Schur form using the RealQZ\n      * class. The generalized Schur decomposition is then used to compute the eigenvalues\n      * and eigenvectors.\n      *\n      * The cost of the computation is dominated by the cost of the\n      * generalized Schur decomposition.\n      *\n      * This method reuses of the allocated data in the GeneralizedEigenSolver object.\n      */\n    GeneralizedEigenSolver& compute(const MatrixType& A, const MatrixType& B, bool computeEigenvectors = true);\n\n    ComputationInfo info() const\n    {\n      eigen_assert(m_valuesOkay && \"EigenSolver is not initialized.\");\n      return m_realQZ.info();\n    }\n\n    /** Sets the maximal number of iterations allowed.\n    */\n    GeneralizedEigenSolver& setMaxIterations(Index maxIters)\n    {\n      m_realQZ.setMaxIterations(maxIters);\n      return *this;\n    }\n\n  protected:\n    \n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n      EIGEN_STATIC_ASSERT(!NumTraits<Scalar>::IsComplex, NUMERIC_TYPE_MUST_BE_REAL);\n    }\n    \n    EigenvectorsType m_eivec;\n    ComplexVectorType m_alphas;\n    VectorType m_betas;\n    bool m_valuesOkay, m_vectorsOkay;\n    RealQZ<MatrixType> m_realQZ;\n    ComplexVectorType m_tmp;\n};\n\ntemplate<typename MatrixType>\nGeneralizedEigenSolver<MatrixType>&\nGeneralizedEigenSolver<MatrixType>::compute(const MatrixType& A, const MatrixType& B, bool computeEigenvectors)\n{\n  check_template_parameters();\n  \n  using std::sqrt;\n  using std::abs;\n  eigen_assert(A.cols() == A.rows() && B.cols() == A.rows() && B.cols() == B.rows());\n  Index size = A.cols();\n  m_valuesOkay = false;\n  m_vectorsOkay = false;\n  // Reduce to generalized real Schur form:\n  // A = Q S Z and B = Q T Z\n  m_realQZ.compute(A, B, computeEigenvectors);\n  if (m_realQZ.info() == Success)\n  {\n    // Resize storage\n    m_alphas.resize(size);\n    m_betas.resize(size);\n    if (computeEigenvectors)\n    {\n      m_eivec.resize(size,size);\n      m_tmp.resize(size);\n    }\n\n    // Aliases:\n    Map<VectorType> v(reinterpret_cast<Scalar*>(m_tmp.data()), size);\n    ComplexVectorType &cv = m_tmp;\n    const MatrixType &mS = m_realQZ.matrixS();\n    const MatrixType &mT = m_realQZ.matrixT();\n\n    Index i = 0;\n    while (i < size)\n    {\n      if (i == size - 1 || mS.coeff(i+1, i) == Scalar(0))\n      {\n        // Real eigenvalue\n        m_alphas.coeffRef(i) = mS.diagonal().coeff(i);\n        m_betas.coeffRef(i)  = mT.diagonal().coeff(i);\n        if (computeEigenvectors)\n        {\n          v.setConstant(Scalar(0.0));\n          v.coeffRef(i) = Scalar(1.0);\n          // For singular eigenvalues do nothing more\n          if(abs(m_betas.coeffRef(i)) >= (std::numeric_limits<RealScalar>::min)())\n          {\n            // Non-singular eigenvalue\n            const Scalar alpha = real(m_alphas.coeffRef(i));\n            const Scalar beta = m_betas.coeffRef(i);\n            for (Index j = i-1; j >= 0; j--)\n            {\n              const Index st = j+1;\n              const Index sz = i-j;\n              if (j > 0 && mS.coeff(j, j-1) != Scalar(0))\n              {\n                // 2x2 block\n                Matrix<Scalar, 2, 1> rhs = (alpha*mT.template block<2,Dynamic>(j-1,st,2,sz) - beta*mS.template block<2,Dynamic>(j-1,st,2,sz)) .lazyProduct( v.segment(st,sz) );\n                Matrix<Scalar, 2, 2> lhs = beta * mS.template block<2,2>(j-1,j-1) - alpha * mT.template block<2,2>(j-1,j-1);\n                v.template segment<2>(j-1) = lhs.partialPivLu().solve(rhs);\n                j--;\n              }\n              else\n              {\n                v.coeffRef(j) = -v.segment(st,sz).transpose().cwiseProduct(beta*mS.block(j,st,1,sz) - alpha*mT.block(j,st,1,sz)).sum() / (beta*mS.coeffRef(j,j) - alpha*mT.coeffRef(j,j));\n              }\n            }\n          }\n          m_eivec.col(i).real().noalias() = m_realQZ.matrixZ().transpose() * v;\n          m_eivec.col(i).real().normalize();\n          m_eivec.col(i).imag().setConstant(0);\n        }\n        ++i;\n      }\n      else\n      {\n        // We need to extract the generalized eigenvalues of the pair of a general 2x2 block S and a positive diagonal 2x2 block T\n        // Then taking beta=T_00*T_11, we can avoid any division, and alpha is the eigenvalues of A = (U^-1 * S * U) * diag(T_11,T_00):\n\n        // T =  [a 0]\n        //      [0 b]\n        RealScalar a = mT.diagonal().coeff(i),\n                   b = mT.diagonal().coeff(i+1);\n        const RealScalar beta = m_betas.coeffRef(i) = m_betas.coeffRef(i+1) = a*b;\n\n        // ^^ NOTE: using diagonal()(i) instead of coeff(i,i) workarounds a MSVC bug.\n        Matrix<RealScalar,2,2> S2 = mS.template block<2,2>(i,i) * Matrix<Scalar,2,1>(b,a).asDiagonal();\n\n        Scalar p = Scalar(0.5) * (S2.coeff(0,0) - S2.coeff(1,1));\n        Scalar z = sqrt(abs(p * p + S2.coeff(1,0) * S2.coeff(0,1)));\n        const ComplexScalar alpha = ComplexScalar(S2.coeff(1,1) + p, (beta > 0) ? z : -z);\n        m_alphas.coeffRef(i)   = conj(alpha);\n        m_alphas.coeffRef(i+1) = alpha;\n\n        if (computeEigenvectors) {\n          // Compute eigenvector in position (i+1) and then position (i) is just the conjugate\n          cv.setZero();\n          cv.coeffRef(i+1) = Scalar(1.0);\n          // here, the \"static_cast\" workaound expression template issues.\n          cv.coeffRef(i) = -(static_cast<Scalar>(beta*mS.coeffRef(i,i+1)) - alpha*mT.coeffRef(i,i+1))\n                          / (static_cast<Scalar>(beta*mS.coeffRef(i,i))   - alpha*mT.coeffRef(i,i));\n          for (Index j = i-1; j >= 0; j--)\n          {\n            const Index st = j+1;\n            const Index sz = i+1-j;\n            if (j > 0 && mS.coeff(j, j-1) != Scalar(0))\n            {\n              // 2x2 block\n              Matrix<ComplexScalar, 2, 1> rhs = (alpha*mT.template block<2,Dynamic>(j-1,st,2,sz) - beta*mS.template block<2,Dynamic>(j-1,st,2,sz)) .lazyProduct( cv.segment(st,sz) );\n              Matrix<ComplexScalar, 2, 2> lhs = beta * mS.template block<2,2>(j-1,j-1) - alpha * mT.template block<2,2>(j-1,j-1);\n              cv.template segment<2>(j-1) = lhs.partialPivLu().solve(rhs);\n              j--;\n            } else {\n              cv.coeffRef(j) =  cv.segment(st,sz).transpose().cwiseProduct(beta*mS.block(j,st,1,sz) - alpha*mT.block(j,st,1,sz)).sum()\n                              / (alpha*mT.coeffRef(j,j) - static_cast<Scalar>(beta*mS.coeffRef(j,j)));\n            }\n          }\n          m_eivec.col(i+1).noalias() = (m_realQZ.matrixZ().transpose() * cv);\n          m_eivec.col(i+1).normalize();\n          m_eivec.col(i) = m_eivec.col(i+1).conjugate();\n        }\n        i += 2;\n      }\n    }\n\n    m_valuesOkay = true;\n    m_vectorsOkay = computeEigenvectors;\n  }\n  return *this;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_GENERALIZEDEIGENSOLVER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Eigenvalues/GeneralizedSelfAdjointEigenSolver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_GENERALIZEDSELFADJOINTEIGENSOLVER_H\n#define EIGEN_GENERALIZEDSELFADJOINTEIGENSOLVER_H\n\n#include \"./Tridiagonalization.h\"\n\nnamespace Eigen { \n\n/** \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  *\n  * \\class GeneralizedSelfAdjointEigenSolver\n  *\n  * \\brief Computes eigenvalues and eigenvectors of the generalized selfadjoint eigen problem\n  *\n  * \\tparam _MatrixType the type of the matrix of which we are computing the\n  * eigendecomposition; this is expected to be an instantiation of the Matrix\n  * class template.\n  *\n  * This class solves the generalized eigenvalue problem\n  * \\f$ Av = \\lambda Bv \\f$. In this case, the matrix \\f$ A \\f$ should be\n  * selfadjoint and the matrix \\f$ B \\f$ should be positive definite.\n  *\n  * Only the \\b lower \\b triangular \\b part of the input matrix is referenced.\n  *\n  * Call the function compute() to compute the eigenvalues and eigenvectors of\n  * a given matrix. Alternatively, you can use the\n  * GeneralizedSelfAdjointEigenSolver(const MatrixType&, const MatrixType&, int)\n  * constructor which computes the eigenvalues and eigenvectors at construction time.\n  * Once the eigenvalue and eigenvectors are computed, they can be retrieved with the eigenvalues()\n  * and eigenvectors() functions.\n  *\n  * The documentation for GeneralizedSelfAdjointEigenSolver(const MatrixType&, const MatrixType&, int)\n  * contains an example of the typical use of this class.\n  *\n  * \\sa class SelfAdjointEigenSolver, class EigenSolver, class ComplexEigenSolver\n  */\ntemplate<typename _MatrixType>\nclass GeneralizedSelfAdjointEigenSolver : public SelfAdjointEigenSolver<_MatrixType>\n{\n    typedef SelfAdjointEigenSolver<_MatrixType> Base;\n  public:\n\n    typedef _MatrixType MatrixType;\n\n    /** \\brief Default constructor for fixed-size matrices.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via compute(). This constructor\n      * can only be used if \\p _MatrixType is a fixed-size matrix; use\n      * GeneralizedSelfAdjointEigenSolver(Index) for dynamic-size matrices.\n      */\n    GeneralizedSelfAdjointEigenSolver() : Base() {}\n\n    /** \\brief Constructor, pre-allocates memory for dynamic-size matrices.\n      *\n      * \\param [in]  size  Positive integer, size of the matrix whose\n      * eigenvalues and eigenvectors will be computed.\n      *\n      * This constructor is useful for dynamic-size matrices, when the user\n      * intends to perform decompositions via compute(). The \\p size\n      * parameter is only used as a hint. It is not an error to give a wrong\n      * \\p size, but it may impair performance.\n      *\n      * \\sa compute() for an example\n      */\n    explicit GeneralizedSelfAdjointEigenSolver(Index size)\n        : Base(size)\n    {}\n\n    /** \\brief Constructor; computes generalized eigendecomposition of given matrix pencil.\n      *\n      * \\param[in]  matA  Selfadjoint matrix in matrix pencil.\n      *                   Only the lower triangular part of the matrix is referenced.\n      * \\param[in]  matB  Positive-definite matrix in matrix pencil.\n      *                   Only the lower triangular part of the matrix is referenced.\n      * \\param[in]  options A or-ed set of flags {#ComputeEigenvectors,#EigenvaluesOnly} | {#Ax_lBx,#ABx_lx,#BAx_lx}.\n      *                     Default is #ComputeEigenvectors|#Ax_lBx.\n      *\n      * This constructor calls compute(const MatrixType&, const MatrixType&, int)\n      * to compute the eigenvalues and (if requested) the eigenvectors of the\n      * generalized eigenproblem \\f$ Ax = \\lambda B x \\f$ with \\a matA the\n      * selfadjoint matrix \\f$ A \\f$ and \\a matB the positive definite matrix\n      * \\f$ B \\f$. Each eigenvector \\f$ x \\f$ satisfies the property\n      * \\f$ x^* B x = 1 \\f$. The eigenvectors are computed if\n      * \\a options contains ComputeEigenvectors.\n      *\n      * In addition, the two following variants can be solved via \\p options:\n      * - \\c ABx_lx: \\f$ ABx = \\lambda x \\f$\n      * - \\c BAx_lx: \\f$ BAx = \\lambda x \\f$\n      *\n      * Example: \\include SelfAdjointEigenSolver_SelfAdjointEigenSolver_MatrixType2.cpp\n      * Output: \\verbinclude SelfAdjointEigenSolver_SelfAdjointEigenSolver_MatrixType2.out\n      *\n      * \\sa compute(const MatrixType&, const MatrixType&, int)\n      */\n    GeneralizedSelfAdjointEigenSolver(const MatrixType& matA, const MatrixType& matB,\n                                      int options = ComputeEigenvectors|Ax_lBx)\n      : Base(matA.cols())\n    {\n      compute(matA, matB, options);\n    }\n\n    /** \\brief Computes generalized eigendecomposition of given matrix pencil.\n      *\n      * \\param[in]  matA  Selfadjoint matrix in matrix pencil.\n      *                   Only the lower triangular part of the matrix is referenced.\n      * \\param[in]  matB  Positive-definite matrix in matrix pencil.\n      *                   Only the lower triangular part of the matrix is referenced.\n      * \\param[in]  options A or-ed set of flags {#ComputeEigenvectors,#EigenvaluesOnly} | {#Ax_lBx,#ABx_lx,#BAx_lx}.\n      *                     Default is #ComputeEigenvectors|#Ax_lBx.\n      *\n      * \\returns    Reference to \\c *this\n      *\n      * According to \\p options, this function computes eigenvalues and (if requested)\n      * the eigenvectors of one of the following three generalized eigenproblems:\n      * - \\c Ax_lBx: \\f$ Ax = \\lambda B x \\f$\n      * - \\c ABx_lx: \\f$ ABx = \\lambda x \\f$\n      * - \\c BAx_lx: \\f$ BAx = \\lambda x \\f$\n      * with \\a matA the selfadjoint matrix \\f$ A \\f$ and \\a matB the positive definite\n      * matrix \\f$ B \\f$.\n      * In addition, each eigenvector \\f$ x \\f$ satisfies the property \\f$ x^* B x = 1 \\f$.\n      *\n      * The eigenvalues() function can be used to retrieve\n      * the eigenvalues. If \\p options contains ComputeEigenvectors, then the\n      * eigenvectors are also computed and can be retrieved by calling\n      * eigenvectors().\n      *\n      * The implementation uses LLT to compute the Cholesky decomposition\n      * \\f$ B = LL^* \\f$ and computes the classical eigendecomposition\n      * of the selfadjoint matrix \\f$ L^{-1} A (L^*)^{-1} \\f$ if \\p options contains Ax_lBx\n      * and of \\f$ L^{*} A L \\f$ otherwise. This solves the\n      * generalized eigenproblem, because any solution of the generalized\n      * eigenproblem \\f$ Ax = \\lambda B x \\f$ corresponds to a solution\n      * \\f$ L^{-1} A (L^*)^{-1} (L^* x) = \\lambda (L^* x) \\f$ of the\n      * eigenproblem for \\f$ L^{-1} A (L^*)^{-1} \\f$. Similar statements\n      * can be made for the two other variants.\n      *\n      * Example: \\include SelfAdjointEigenSolver_compute_MatrixType2.cpp\n      * Output: \\verbinclude SelfAdjointEigenSolver_compute_MatrixType2.out\n      *\n      * \\sa GeneralizedSelfAdjointEigenSolver(const MatrixType&, const MatrixType&, int)\n      */\n    GeneralizedSelfAdjointEigenSolver& compute(const MatrixType& matA, const MatrixType& matB,\n                                               int options = ComputeEigenvectors|Ax_lBx);\n\n  protected:\n\n};\n\n\ntemplate<typename MatrixType>\nGeneralizedSelfAdjointEigenSolver<MatrixType>& GeneralizedSelfAdjointEigenSolver<MatrixType>::\ncompute(const MatrixType& matA, const MatrixType& matB, int options)\n{\n  eigen_assert(matA.cols()==matA.rows() && matB.rows()==matA.rows() && matB.cols()==matB.rows());\n  eigen_assert((options&~(EigVecMask|GenEigMask))==0\n          && (options&EigVecMask)!=EigVecMask\n          && ((options&GenEigMask)==0 || (options&GenEigMask)==Ax_lBx\n           || (options&GenEigMask)==ABx_lx || (options&GenEigMask)==BAx_lx)\n          && \"invalid option parameter\");\n\n  bool computeEigVecs = ((options&EigVecMask)==0) || ((options&EigVecMask)==ComputeEigenvectors);\n\n  // Compute the cholesky decomposition of matB = L L' = U'U\n  LLT<MatrixType> cholB(matB);\n\n  int type = (options&GenEigMask);\n  if(type==0)\n    type = Ax_lBx;\n\n  if(type==Ax_lBx)\n  {\n    // compute C = inv(L) A inv(L')\n    MatrixType matC = matA.template selfadjointView<Lower>();\n    cholB.matrixL().template solveInPlace<OnTheLeft>(matC);\n    cholB.matrixU().template solveInPlace<OnTheRight>(matC);\n\n    Base::compute(matC, computeEigVecs ? ComputeEigenvectors : EigenvaluesOnly );\n\n    // transform back the eigen vectors: evecs = inv(U) * evecs\n    if(computeEigVecs)\n      cholB.matrixU().solveInPlace(Base::m_eivec);\n  }\n  else if(type==ABx_lx)\n  {\n    // compute C = L' A L\n    MatrixType matC = matA.template selfadjointView<Lower>();\n    matC = matC * cholB.matrixL();\n    matC = cholB.matrixU() * matC;\n\n    Base::compute(matC, computeEigVecs ? ComputeEigenvectors : EigenvaluesOnly);\n\n    // transform back the eigen vectors: evecs = inv(U) * evecs\n    if(computeEigVecs)\n      cholB.matrixU().solveInPlace(Base::m_eivec);\n  }\n  else if(type==BAx_lx)\n  {\n    // compute C = L' A L\n    MatrixType matC = matA.template selfadjointView<Lower>();\n    matC = matC * cholB.matrixL();\n    matC = cholB.matrixU() * matC;\n\n    Base::compute(matC, computeEigVecs ? ComputeEigenvectors : EigenvaluesOnly);\n\n    // transform back the eigen vectors: evecs = L * evecs\n    if(computeEigVecs)\n      Base::m_eivec = cholB.matrixL() * Base::m_eivec;\n  }\n\n  return *this;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_GENERALIZEDSELFADJOINTEIGENSOLVER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Eigenvalues/HessenbergDecomposition.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_HESSENBERGDECOMPOSITION_H\n#define EIGEN_HESSENBERGDECOMPOSITION_H\n\nnamespace Eigen { \n\nnamespace internal {\n  \ntemplate<typename MatrixType> struct HessenbergDecompositionMatrixHReturnType;\ntemplate<typename MatrixType>\nstruct traits<HessenbergDecompositionMatrixHReturnType<MatrixType> >\n{\n  typedef MatrixType ReturnType;\n};\n\n}\n\n/** \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  *\n  * \\class HessenbergDecomposition\n  *\n  * \\brief Reduces a square matrix to Hessenberg form by an orthogonal similarity transformation\n  *\n  * \\tparam _MatrixType the type of the matrix of which we are computing the Hessenberg decomposition\n  *\n  * This class performs an Hessenberg decomposition of a matrix \\f$ A \\f$. In\n  * the real case, the Hessenberg decomposition consists of an orthogonal\n  * matrix \\f$ Q \\f$ and a Hessenberg matrix \\f$ H \\f$ such that \\f$ A = Q H\n  * Q^T \\f$. An orthogonal matrix is a matrix whose inverse equals its\n  * transpose (\\f$ Q^{-1} = Q^T \\f$). A Hessenberg matrix has zeros below the\n  * subdiagonal, so it is almost upper triangular. The Hessenberg decomposition\n  * of a complex matrix is \\f$ A = Q H Q^* \\f$ with \\f$ Q \\f$ unitary (that is,\n  * \\f$ Q^{-1} = Q^* \\f$).\n  *\n  * Call the function compute() to compute the Hessenberg decomposition of a\n  * given matrix. Alternatively, you can use the\n  * HessenbergDecomposition(const MatrixType&) constructor which computes the\n  * Hessenberg decomposition at construction time. Once the decomposition is\n  * computed, you can use the matrixH() and matrixQ() functions to construct\n  * the matrices H and Q in the decomposition.\n  *\n  * The documentation for matrixH() contains an example of the typical use of\n  * this class.\n  *\n  * \\sa class ComplexSchur, class Tridiagonalization, \\ref QR_Module \"QR Module\"\n  */\ntemplate<typename _MatrixType> class HessenbergDecomposition\n{\n  public:\n\n    /** \\brief Synonym for the template parameter \\p _MatrixType. */\n    typedef _MatrixType MatrixType;\n\n    enum {\n      Size = MatrixType::RowsAtCompileTime,\n      SizeMinusOne = Size == Dynamic ? Dynamic : Size - 1,\n      Options = MatrixType::Options,\n      MaxSize = MatrixType::MaxRowsAtCompileTime,\n      MaxSizeMinusOne = MaxSize == Dynamic ? Dynamic : MaxSize - 1\n    };\n\n    /** \\brief Scalar type for matrices of type #MatrixType. */\n    typedef typename MatrixType::Scalar Scalar;\n    typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n\n    /** \\brief Type for vector of Householder coefficients.\n      *\n      * This is column vector with entries of type #Scalar. The length of the\n      * vector is one less than the size of #MatrixType, if it is a fixed-side\n      * type.\n      */\n    typedef Matrix<Scalar, SizeMinusOne, 1, Options & ~RowMajor, MaxSizeMinusOne, 1> CoeffVectorType;\n\n    /** \\brief Return type of matrixQ() */\n    typedef HouseholderSequence<MatrixType,typename internal::remove_all<typename CoeffVectorType::ConjugateReturnType>::type> HouseholderSequenceType;\n    \n    typedef internal::HessenbergDecompositionMatrixHReturnType<MatrixType> MatrixHReturnType;\n\n    /** \\brief Default constructor; the decomposition will be computed later.\n      *\n      * \\param [in] size  The size of the matrix whose Hessenberg decomposition will be computed.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via compute().  The \\p size parameter is only\n      * used as a hint. It is not an error to give a wrong \\p size, but it may\n      * impair performance.\n      *\n      * \\sa compute() for an example.\n      */\n    explicit HessenbergDecomposition(Index size = Size==Dynamic ? 2 : Size)\n      : m_matrix(size,size),\n        m_temp(size),\n        m_isInitialized(false)\n    {\n      if(size>1)\n        m_hCoeffs.resize(size-1);\n    }\n\n    /** \\brief Constructor; computes Hessenberg decomposition of given matrix.\n      *\n      * \\param[in]  matrix  Square matrix whose Hessenberg decomposition is to be computed.\n      *\n      * This constructor calls compute() to compute the Hessenberg\n      * decomposition.\n      *\n      * \\sa matrixH() for an example.\n      */\n    template<typename InputType>\n    explicit HessenbergDecomposition(const EigenBase<InputType>& matrix)\n      : m_matrix(matrix.derived()),\n        m_temp(matrix.rows()),\n        m_isInitialized(false)\n    {\n      if(matrix.rows()<2)\n      {\n        m_isInitialized = true;\n        return;\n      }\n      m_hCoeffs.resize(matrix.rows()-1,1);\n      _compute(m_matrix, m_hCoeffs, m_temp);\n      m_isInitialized = true;\n    }\n\n    /** \\brief Computes Hessenberg decomposition of given matrix.\n      *\n      * \\param[in]  matrix  Square matrix whose Hessenberg decomposition is to be computed.\n      * \\returns    Reference to \\c *this\n      *\n      * The Hessenberg decomposition is computed by bringing the columns of the\n      * matrix successively in the required form using Householder reflections\n      * (see, e.g., Algorithm 7.4.2 in Golub \\& Van Loan, <i>%Matrix\n      * Computations</i>). The cost is \\f$ 10n^3/3 \\f$ flops, where \\f$ n \\f$\n      * denotes the size of the given matrix.\n      *\n      * This method reuses of the allocated data in the HessenbergDecomposition\n      * object.\n      *\n      * Example: \\include HessenbergDecomposition_compute.cpp\n      * Output: \\verbinclude HessenbergDecomposition_compute.out\n      */\n    template<typename InputType>\n    HessenbergDecomposition& compute(const EigenBase<InputType>& matrix)\n    {\n      m_matrix = matrix.derived();\n      if(matrix.rows()<2)\n      {\n        m_isInitialized = true;\n        return *this;\n      }\n      m_hCoeffs.resize(matrix.rows()-1,1);\n      _compute(m_matrix, m_hCoeffs, m_temp);\n      m_isInitialized = true;\n      return *this;\n    }\n\n    /** \\brief Returns the Householder coefficients.\n      *\n      * \\returns a const reference to the vector of Householder coefficients\n      *\n      * \\pre Either the constructor HessenbergDecomposition(const MatrixType&)\n      * or the member function compute(const MatrixType&) has been called\n      * before to compute the Hessenberg decomposition of a matrix.\n      *\n      * The Householder coefficients allow the reconstruction of the matrix\n      * \\f$ Q \\f$ in the Hessenberg decomposition from the packed data.\n      *\n      * \\sa packedMatrix(), \\ref Householder_Module \"Householder module\"\n      */\n    const CoeffVectorType& householderCoefficients() const\n    {\n      eigen_assert(m_isInitialized && \"HessenbergDecomposition is not initialized.\");\n      return m_hCoeffs;\n    }\n\n    /** \\brief Returns the internal representation of the decomposition\n      *\n      *\t\\returns a const reference to a matrix with the internal representation\n      *\t         of the decomposition.\n      *\n      * \\pre Either the constructor HessenbergDecomposition(const MatrixType&)\n      * or the member function compute(const MatrixType&) has been called\n      * before to compute the Hessenberg decomposition of a matrix.\n      *\n      * The returned matrix contains the following information:\n      *  - the upper part and lower sub-diagonal represent the Hessenberg matrix H\n      *  - the rest of the lower part contains the Householder vectors that, combined with\n      *    Householder coefficients returned by householderCoefficients(),\n      *    allows to reconstruct the matrix Q as\n      *       \\f$ Q = H_{N-1} \\ldots H_1 H_0 \\f$.\n      *    Here, the matrices \\f$ H_i \\f$ are the Householder transformations\n      *       \\f$ H_i = (I - h_i v_i v_i^T) \\f$\n      *    where \\f$ h_i \\f$ is the \\f$ i \\f$th Householder coefficient and\n      *    \\f$ v_i \\f$ is the Householder vector defined by\n      *       \\f$ v_i = [ 0, \\ldots, 0, 1, M(i+2,i), \\ldots, M(N-1,i) ]^T \\f$\n      *    with M the matrix returned by this function.\n      *\n      * See LAPACK for further details on this packed storage.\n      *\n      * Example: \\include HessenbergDecomposition_packedMatrix.cpp\n      * Output: \\verbinclude HessenbergDecomposition_packedMatrix.out\n      *\n      * \\sa householderCoefficients()\n      */\n    const MatrixType& packedMatrix() const\n    {\n      eigen_assert(m_isInitialized && \"HessenbergDecomposition is not initialized.\");\n      return m_matrix;\n    }\n\n    /** \\brief Reconstructs the orthogonal matrix Q in the decomposition\n      *\n      * \\returns object representing the matrix Q\n      *\n      * \\pre Either the constructor HessenbergDecomposition(const MatrixType&)\n      * or the member function compute(const MatrixType&) has been called\n      * before to compute the Hessenberg decomposition of a matrix.\n      *\n      * This function returns a light-weight object of template class\n      * HouseholderSequence. You can either apply it directly to a matrix or\n      * you can convert it to a matrix of type #MatrixType.\n      *\n      * \\sa matrixH() for an example, class HouseholderSequence\n      */\n    HouseholderSequenceType matrixQ() const\n    {\n      eigen_assert(m_isInitialized && \"HessenbergDecomposition is not initialized.\");\n      return HouseholderSequenceType(m_matrix, m_hCoeffs.conjugate())\n             .setLength(m_matrix.rows() - 1)\n             .setShift(1);\n    }\n\n    /** \\brief Constructs the Hessenberg matrix H in the decomposition\n      *\n      * \\returns expression object representing the matrix H\n      *\n      * \\pre Either the constructor HessenbergDecomposition(const MatrixType&)\n      * or the member function compute(const MatrixType&) has been called\n      * before to compute the Hessenberg decomposition of a matrix.\n      *\n      * The object returned by this function constructs the Hessenberg matrix H\n      * when it is assigned to a matrix or otherwise evaluated. The matrix H is\n      * constructed from the packed matrix as returned by packedMatrix(): The\n      * upper part (including the subdiagonal) of the packed matrix contains\n      * the matrix H. It may sometimes be better to directly use the packed\n      * matrix instead of constructing the matrix H.\n      *\n      * Example: \\include HessenbergDecomposition_matrixH.cpp\n      * Output: \\verbinclude HessenbergDecomposition_matrixH.out\n      *\n      * \\sa matrixQ(), packedMatrix()\n      */\n    MatrixHReturnType matrixH() const\n    {\n      eigen_assert(m_isInitialized && \"HessenbergDecomposition is not initialized.\");\n      return MatrixHReturnType(*this);\n    }\n\n  private:\n\n    typedef Matrix<Scalar, 1, Size, Options | RowMajor, 1, MaxSize> VectorType;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    static void _compute(MatrixType& matA, CoeffVectorType& hCoeffs, VectorType& temp);\n\n  protected:\n    MatrixType m_matrix;\n    CoeffVectorType m_hCoeffs;\n    VectorType m_temp;\n    bool m_isInitialized;\n};\n\n/** \\internal\n  * Performs a tridiagonal decomposition of \\a matA in place.\n  *\n  * \\param matA the input selfadjoint matrix\n  * \\param hCoeffs returned Householder coefficients\n  *\n  * The result is written in the lower triangular part of \\a matA.\n  *\n  * Implemented from Golub's \"%Matrix Computations\", algorithm 8.3.1.\n  *\n  * \\sa packedMatrix()\n  */\ntemplate<typename MatrixType>\nvoid HessenbergDecomposition<MatrixType>::_compute(MatrixType& matA, CoeffVectorType& hCoeffs, VectorType& temp)\n{\n  eigen_assert(matA.rows()==matA.cols());\n  Index n = matA.rows();\n  temp.resize(n);\n  for (Index i = 0; i<n-1; ++i)\n  {\n    // let's consider the vector v = i-th column starting at position i+1\n    Index remainingSize = n-i-1;\n    RealScalar beta;\n    Scalar h;\n    matA.col(i).tail(remainingSize).makeHouseholderInPlace(h, beta);\n    matA.col(i).coeffRef(i+1) = beta;\n    hCoeffs.coeffRef(i) = h;\n\n    // Apply similarity transformation to remaining columns,\n    // i.e., compute A = H A H'\n\n    // A = H A\n    matA.bottomRightCorner(remainingSize, remainingSize)\n        .applyHouseholderOnTheLeft(matA.col(i).tail(remainingSize-1), h, &temp.coeffRef(0));\n\n    // A = A H'\n    matA.rightCols(remainingSize)\n        .applyHouseholderOnTheRight(matA.col(i).tail(remainingSize-1), numext::conj(h), &temp.coeffRef(0));\n  }\n}\n\nnamespace internal {\n\n/** \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  *\n  * \\brief Expression type for return value of HessenbergDecomposition::matrixH()\n  *\n  * \\tparam MatrixType type of matrix in the Hessenberg decomposition\n  *\n  * Objects of this type represent the Hessenberg matrix in the Hessenberg\n  * decomposition of some matrix. The object holds a reference to the\n  * HessenbergDecomposition class until the it is assigned or evaluated for\n  * some other reason (the reference should remain valid during the life time\n  * of this object). This class is the return type of\n  * HessenbergDecomposition::matrixH(); there is probably no other use for this\n  * class.\n  */\ntemplate<typename MatrixType> struct HessenbergDecompositionMatrixHReturnType\n: public ReturnByValue<HessenbergDecompositionMatrixHReturnType<MatrixType> >\n{\n  public:\n    /** \\brief Constructor.\n      *\n      * \\param[in] hess  Hessenberg decomposition\n      */\n    HessenbergDecompositionMatrixHReturnType(const HessenbergDecomposition<MatrixType>& hess) : m_hess(hess) { }\n\n    /** \\brief Hessenberg matrix in decomposition.\n      *\n      * \\param[out] result  Hessenberg matrix in decomposition \\p hess which\n      *                     was passed to the constructor\n      */\n    template <typename ResultType>\n    inline void evalTo(ResultType& result) const\n    {\n      result = m_hess.packedMatrix();\n      Index n = result.rows();\n      if (n>2)\n        result.bottomLeftCorner(n-2, n-2).template triangularView<Lower>().setZero();\n    }\n\n    Index rows() const { return m_hess.packedMatrix().rows(); }\n    Index cols() const { return m_hess.packedMatrix().cols(); }\n\n  protected:\n    const HessenbergDecomposition<MatrixType>& m_hess;\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_HESSENBERGDECOMPOSITION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Eigenvalues/MatrixBaseEigenvalues.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MATRIXBASEEIGENVALUES_H\n#define EIGEN_MATRIXBASEEIGENVALUES_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate<typename Derived, bool IsComplex>\nstruct eigenvalues_selector\n{\n  // this is the implementation for the case IsComplex = true\n  static inline typename MatrixBase<Derived>::EigenvaluesReturnType const\n  run(const MatrixBase<Derived>& m)\n  {\n    typedef typename Derived::PlainObject PlainObject;\n    PlainObject m_eval(m);\n    return ComplexEigenSolver<PlainObject>(m_eval, false).eigenvalues();\n  }\n};\n\ntemplate<typename Derived>\nstruct eigenvalues_selector<Derived, false>\n{\n  static inline typename MatrixBase<Derived>::EigenvaluesReturnType const\n  run(const MatrixBase<Derived>& m)\n  {\n    typedef typename Derived::PlainObject PlainObject;\n    PlainObject m_eval(m);\n    return EigenSolver<PlainObject>(m_eval, false).eigenvalues();\n  }\n};\n\n} // end namespace internal\n\n/** \\brief Computes the eigenvalues of a matrix \n  * \\returns Column vector containing the eigenvalues.\n  *\n  * \\eigenvalues_module\n  * This function computes the eigenvalues with the help of the EigenSolver\n  * class (for real matrices) or the ComplexEigenSolver class (for complex\n  * matrices). \n  *\n  * The eigenvalues are repeated according to their algebraic multiplicity,\n  * so there are as many eigenvalues as rows in the matrix.\n  *\n  * The SelfAdjointView class provides a better algorithm for selfadjoint\n  * matrices.\n  *\n  * Example: \\include MatrixBase_eigenvalues.cpp\n  * Output: \\verbinclude MatrixBase_eigenvalues.out\n  *\n  * \\sa EigenSolver::eigenvalues(), ComplexEigenSolver::eigenvalues(),\n  *     SelfAdjointView::eigenvalues()\n  */\ntemplate<typename Derived>\ninline typename MatrixBase<Derived>::EigenvaluesReturnType\nMatrixBase<Derived>::eigenvalues() const\n{\n  return internal::eigenvalues_selector<Derived, NumTraits<Scalar>::IsComplex>::run(derived());\n}\n\n/** \\brief Computes the eigenvalues of a matrix\n  * \\returns Column vector containing the eigenvalues.\n  *\n  * \\eigenvalues_module\n  * This function computes the eigenvalues with the help of the\n  * SelfAdjointEigenSolver class.  The eigenvalues are repeated according to\n  * their algebraic multiplicity, so there are as many eigenvalues as rows in\n  * the matrix.\n  *\n  * Example: \\include SelfAdjointView_eigenvalues.cpp\n  * Output: \\verbinclude SelfAdjointView_eigenvalues.out\n  *\n  * \\sa SelfAdjointEigenSolver::eigenvalues(), MatrixBase::eigenvalues()\n  */\ntemplate<typename MatrixType, unsigned int UpLo> \nEIGEN_DEVICE_FUNC inline typename SelfAdjointView<MatrixType, UpLo>::EigenvaluesReturnType\nSelfAdjointView<MatrixType, UpLo>::eigenvalues() const\n{\n  PlainObject thisAsMatrix(*this);\n  return SelfAdjointEigenSolver<PlainObject>(thisAsMatrix, false).eigenvalues();\n}\n\n\n\n/** \\brief Computes the L2 operator norm\n  * \\returns Operator norm of the matrix.\n  *\n  * \\eigenvalues_module\n  * This function computes the L2 operator norm of a matrix, which is also\n  * known as the spectral norm. The norm of a matrix \\f$ A \\f$ is defined to be\n  * \\f[ \\|A\\|_2 = \\max_x \\frac{\\|Ax\\|_2}{\\|x\\|_2} \\f]\n  * where the maximum is over all vectors and the norm on the right is the\n  * Euclidean vector norm. The norm equals the largest singular value, which is\n  * the square root of the largest eigenvalue of the positive semi-definite\n  * matrix \\f$ A^*A \\f$.\n  *\n  * The current implementation uses the eigenvalues of \\f$ A^*A \\f$, as computed\n  * by SelfAdjointView::eigenvalues(), to compute the operator norm of a\n  * matrix.  The SelfAdjointView class provides a better algorithm for\n  * selfadjoint matrices.\n  *\n  * Example: \\include MatrixBase_operatorNorm.cpp\n  * Output: \\verbinclude MatrixBase_operatorNorm.out\n  *\n  * \\sa SelfAdjointView::eigenvalues(), SelfAdjointView::operatorNorm()\n  */\ntemplate<typename Derived>\ninline typename MatrixBase<Derived>::RealScalar\nMatrixBase<Derived>::operatorNorm() const\n{\n  using std::sqrt;\n  typename Derived::PlainObject m_eval(derived());\n  // FIXME if it is really guaranteed that the eigenvalues are already sorted,\n  // then we don't need to compute a maxCoeff() here, comparing the 1st and last ones is enough.\n  return sqrt((m_eval*m_eval.adjoint())\n                 .eval()\n\t\t .template selfadjointView<Lower>()\n\t\t .eigenvalues()\n\t\t .maxCoeff()\n\t\t );\n}\n\n/** \\brief Computes the L2 operator norm\n  * \\returns Operator norm of the matrix.\n  *\n  * \\eigenvalues_module\n  * This function computes the L2 operator norm of a self-adjoint matrix. For a\n  * self-adjoint matrix, the operator norm is the largest eigenvalue.\n  *\n  * The current implementation uses the eigenvalues of the matrix, as computed\n  * by eigenvalues(), to compute the operator norm of the matrix.\n  *\n  * Example: \\include SelfAdjointView_operatorNorm.cpp\n  * Output: \\verbinclude SelfAdjointView_operatorNorm.out\n  *\n  * \\sa eigenvalues(), MatrixBase::operatorNorm()\n  */\ntemplate<typename MatrixType, unsigned int UpLo>\nEIGEN_DEVICE_FUNC inline typename SelfAdjointView<MatrixType, UpLo>::RealScalar\nSelfAdjointView<MatrixType, UpLo>::operatorNorm() const\n{\n  return eigenvalues().cwiseAbs().maxCoeff();\n}\n\n} // end namespace Eigen\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Eigenvalues/RealQZ.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Alexey Korepanov <kaikaikai@yandex.ru>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_REAL_QZ_H\n#define EIGEN_REAL_QZ_H\n\nnamespace Eigen {\n\n  /** \\eigenvalues_module \\ingroup Eigenvalues_Module\n   *\n   *\n   * \\class RealQZ\n   *\n   * \\brief Performs a real QZ decomposition of a pair of square matrices\n   *\n   * \\tparam _MatrixType the type of the matrix of which we are computing the\n   * real QZ decomposition; this is expected to be an instantiation of the\n   * Matrix class template.\n   *\n   * Given a real square matrices A and B, this class computes the real QZ\n   * decomposition: \\f$ A = Q S Z \\f$, \\f$ B = Q T Z \\f$ where Q and Z are\n   * real orthogonal matrixes, T is upper-triangular matrix, and S is upper\n   * quasi-triangular matrix. An orthogonal matrix is a matrix whose\n   * inverse is equal to its transpose, \\f$ U^{-1} = U^T \\f$. A quasi-triangular\n   * matrix is a block-triangular matrix whose diagonal consists of 1-by-1\n   * blocks and 2-by-2 blocks where further reduction is impossible due to\n   * complex eigenvalues. \n   *\n   * The eigenvalues of the pencil \\f$ A - z B \\f$ can be obtained from\n   * 1x1 and 2x2 blocks on the diagonals of S and T.\n   *\n   * Call the function compute() to compute the real QZ decomposition of a\n   * given pair of matrices. Alternatively, you can use the \n   * RealQZ(const MatrixType& B, const MatrixType& B, bool computeQZ)\n   * constructor which computes the real QZ decomposition at construction\n   * time. Once the decomposition is computed, you can use the matrixS(),\n   * matrixT(), matrixQ() and matrixZ() functions to retrieve the matrices\n   * S, T, Q and Z in the decomposition. If computeQZ==false, some time\n   * is saved by not computing matrices Q and Z.\n   *\n   * Example: \\include RealQZ_compute.cpp\n   * Output: \\include RealQZ_compute.out\n   *\n   * \\note The implementation is based on the algorithm in \"Matrix Computations\"\n   * by Gene H. Golub and Charles F. Van Loan, and a paper \"An algorithm for\n   * generalized eigenvalue problems\" by C.B.Moler and G.W.Stewart.\n   *\n   * \\sa class RealSchur, class ComplexSchur, class EigenSolver, class ComplexEigenSolver\n   */\n\n  template<typename _MatrixType> class RealQZ\n  {\n    public:\n      typedef _MatrixType MatrixType;\n      enum {\n        RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n        ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n        Options = MatrixType::Options,\n        MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n        MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n      };\n      typedef typename MatrixType::Scalar Scalar;\n      typedef std::complex<typename NumTraits<Scalar>::Real> ComplexScalar;\n      typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n\n      typedef Matrix<ComplexScalar, ColsAtCompileTime, 1, Options & ~RowMajor, MaxColsAtCompileTime, 1> EigenvalueType;\n      typedef Matrix<Scalar, ColsAtCompileTime, 1, Options & ~RowMajor, MaxColsAtCompileTime, 1> ColumnVectorType;\n\n      /** \\brief Default constructor.\n       *\n       * \\param [in] size  Positive integer, size of the matrix whose QZ decomposition will be computed.\n       *\n       * The default constructor is useful in cases in which the user intends to\n       * perform decompositions via compute().  The \\p size parameter is only\n       * used as a hint. It is not an error to give a wrong \\p size, but it may\n       * impair performance.\n       *\n       * \\sa compute() for an example.\n       */\n      explicit RealQZ(Index size = RowsAtCompileTime==Dynamic ? 1 : RowsAtCompileTime) :\n        m_S(size, size),\n        m_T(size, size),\n        m_Q(size, size),\n        m_Z(size, size),\n        m_workspace(size*2),\n        m_maxIters(400),\n        m_isInitialized(false),\n        m_computeQZ(true)\n      {}\n\n      /** \\brief Constructor; computes real QZ decomposition of given matrices\n       * \n       * \\param[in]  A          Matrix A.\n       * \\param[in]  B          Matrix B.\n       * \\param[in]  computeQZ  If false, A and Z are not computed.\n       *\n       * This constructor calls compute() to compute the QZ decomposition.\n       */\n      RealQZ(const MatrixType& A, const MatrixType& B, bool computeQZ = true) :\n        m_S(A.rows(),A.cols()),\n        m_T(A.rows(),A.cols()),\n        m_Q(A.rows(),A.cols()),\n        m_Z(A.rows(),A.cols()),\n        m_workspace(A.rows()*2),\n        m_maxIters(400),\n        m_isInitialized(false),\n        m_computeQZ(true)\n      {\n        compute(A, B, computeQZ);\n      }\n\n      /** \\brief Returns matrix Q in the QZ decomposition. \n       *\n       * \\returns A const reference to the matrix Q.\n       */\n      const MatrixType& matrixQ() const {\n        eigen_assert(m_isInitialized && \"RealQZ is not initialized.\");\n        eigen_assert(m_computeQZ && \"The matrices Q and Z have not been computed during the QZ decomposition.\");\n        return m_Q;\n      }\n\n      /** \\brief Returns matrix Z in the QZ decomposition. \n       *\n       * \\returns A const reference to the matrix Z.\n       */\n      const MatrixType& matrixZ() const {\n        eigen_assert(m_isInitialized && \"RealQZ is not initialized.\");\n        eigen_assert(m_computeQZ && \"The matrices Q and Z have not been computed during the QZ decomposition.\");\n        return m_Z;\n      }\n\n      /** \\brief Returns matrix S in the QZ decomposition. \n       *\n       * \\returns A const reference to the matrix S.\n       */\n      const MatrixType& matrixS() const {\n        eigen_assert(m_isInitialized && \"RealQZ is not initialized.\");\n        return m_S;\n      }\n\n      /** \\brief Returns matrix S in the QZ decomposition. \n       *\n       * \\returns A const reference to the matrix S.\n       */\n      const MatrixType& matrixT() const {\n        eigen_assert(m_isInitialized && \"RealQZ is not initialized.\");\n        return m_T;\n      }\n\n      /** \\brief Computes QZ decomposition of given matrix. \n       * \n       * \\param[in]  A          Matrix A.\n       * \\param[in]  B          Matrix B.\n       * \\param[in]  computeQZ  If false, A and Z are not computed.\n       * \\returns    Reference to \\c *this\n       */\n      RealQZ& compute(const MatrixType& A, const MatrixType& B, bool computeQZ = true);\n\n      /** \\brief Reports whether previous computation was successful.\n       *\n       * \\returns \\c Success if computation was successful, \\c NoConvergence otherwise.\n       */\n      ComputationInfo info() const\n      {\n        eigen_assert(m_isInitialized && \"RealQZ is not initialized.\");\n        return m_info;\n      }\n\n      /** \\brief Returns number of performed QR-like iterations.\n      */\n      Index iterations() const\n      {\n        eigen_assert(m_isInitialized && \"RealQZ is not initialized.\");\n        return m_global_iter;\n      }\n\n      /** Sets the maximal number of iterations allowed to converge to one eigenvalue\n       * or decouple the problem.\n      */\n      RealQZ& setMaxIterations(Index maxIters)\n      {\n        m_maxIters = maxIters;\n        return *this;\n      }\n\n    private:\n\n      MatrixType m_S, m_T, m_Q, m_Z;\n      Matrix<Scalar,Dynamic,1> m_workspace;\n      ComputationInfo m_info;\n      Index m_maxIters;\n      bool m_isInitialized;\n      bool m_computeQZ;\n      Scalar m_normOfT, m_normOfS;\n      Index m_global_iter;\n\n      typedef Matrix<Scalar,3,1> Vector3s;\n      typedef Matrix<Scalar,2,1> Vector2s;\n      typedef Matrix<Scalar,2,2> Matrix2s;\n      typedef JacobiRotation<Scalar> JRs;\n\n      void hessenbergTriangular();\n      void computeNorms();\n      Index findSmallSubdiagEntry(Index iu);\n      Index findSmallDiagEntry(Index f, Index l);\n      void splitOffTwoRows(Index i);\n      void pushDownZero(Index z, Index f, Index l);\n      void step(Index f, Index l, Index iter);\n\n  }; // RealQZ\n\n  /** \\internal Reduces S and T to upper Hessenberg - triangular form */\n  template<typename MatrixType>\n    void RealQZ<MatrixType>::hessenbergTriangular()\n    {\n\n      const Index dim = m_S.cols();\n\n      // perform QR decomposition of T, overwrite T with R, save Q\n      HouseholderQR<MatrixType> qrT(m_T);\n      m_T = qrT.matrixQR();\n      m_T.template triangularView<StrictlyLower>().setZero();\n      m_Q = qrT.householderQ();\n      // overwrite S with Q* S\n      m_S.applyOnTheLeft(m_Q.adjoint());\n      // init Z as Identity\n      if (m_computeQZ)\n        m_Z = MatrixType::Identity(dim,dim);\n      // reduce S to upper Hessenberg with Givens rotations\n      for (Index j=0; j<=dim-3; j++) {\n        for (Index i=dim-1; i>=j+2; i--) {\n          JRs G;\n          // kill S(i,j)\n          if(m_S.coeff(i,j) != 0)\n          {\n            G.makeGivens(m_S.coeff(i-1,j), m_S.coeff(i,j), &m_S.coeffRef(i-1, j));\n            m_S.coeffRef(i,j) = Scalar(0.0);\n            m_S.rightCols(dim-j-1).applyOnTheLeft(i-1,i,G.adjoint());\n            m_T.rightCols(dim-i+1).applyOnTheLeft(i-1,i,G.adjoint());\n            // update Q\n            if (m_computeQZ)\n              m_Q.applyOnTheRight(i-1,i,G);\n          }\n          // kill T(i,i-1)\n          if(m_T.coeff(i,i-1)!=Scalar(0))\n          {\n            G.makeGivens(m_T.coeff(i,i), m_T.coeff(i,i-1), &m_T.coeffRef(i,i));\n            m_T.coeffRef(i,i-1) = Scalar(0.0);\n            m_S.applyOnTheRight(i,i-1,G);\n            m_T.topRows(i).applyOnTheRight(i,i-1,G);\n            // update Z\n            if (m_computeQZ)\n              m_Z.applyOnTheLeft(i,i-1,G.adjoint());\n          }\n        }\n      }\n    }\n\n  /** \\internal Computes vector L1 norms of S and T when in Hessenberg-Triangular form already */\n  template<typename MatrixType>\n    inline void RealQZ<MatrixType>::computeNorms()\n    {\n      const Index size = m_S.cols();\n      m_normOfS = Scalar(0.0);\n      m_normOfT = Scalar(0.0);\n      for (Index j = 0; j < size; ++j)\n      {\n        m_normOfS += m_S.col(j).segment(0, (std::min)(size,j+2)).cwiseAbs().sum();\n        m_normOfT += m_T.row(j).segment(j, size - j).cwiseAbs().sum();\n      }\n    }\n\n\n  /** \\internal Look for single small sub-diagonal element S(res, res-1) and return res (or 0) */\n  template<typename MatrixType>\n    inline Index RealQZ<MatrixType>::findSmallSubdiagEntry(Index iu)\n    {\n      using std::abs;\n      Index res = iu;\n      while (res > 0)\n      {\n        Scalar s = abs(m_S.coeff(res-1,res-1)) + abs(m_S.coeff(res,res));\n        if (s == Scalar(0.0))\n          s = m_normOfS;\n        if (abs(m_S.coeff(res,res-1)) < NumTraits<Scalar>::epsilon() * s)\n          break;\n        res--;\n      }\n      return res;\n    }\n\n  /** \\internal Look for single small diagonal element T(res, res) for res between f and l, and return res (or f-1)  */\n  template<typename MatrixType>\n    inline Index RealQZ<MatrixType>::findSmallDiagEntry(Index f, Index l)\n    {\n      using std::abs;\n      Index res = l;\n      while (res >= f) {\n        if (abs(m_T.coeff(res,res)) <= NumTraits<Scalar>::epsilon() * m_normOfT)\n          break;\n        res--;\n      }\n      return res;\n    }\n\n  /** \\internal decouple 2x2 diagonal block in rows i, i+1 if eigenvalues are real */\n  template<typename MatrixType>\n    inline void RealQZ<MatrixType>::splitOffTwoRows(Index i)\n    {\n      using std::abs;\n      using std::sqrt;\n      const Index dim=m_S.cols();\n      if (abs(m_S.coeff(i+1,i))==Scalar(0))\n        return;\n      Index j = findSmallDiagEntry(i,i+1);\n      if (j==i-1)\n      {\n        // block of (S T^{-1})\n        Matrix2s STi = m_T.template block<2,2>(i,i).template triangularView<Upper>().\n          template solve<OnTheRight>(m_S.template block<2,2>(i,i));\n        Scalar p = Scalar(0.5)*(STi(0,0)-STi(1,1));\n        Scalar q = p*p + STi(1,0)*STi(0,1);\n        if (q>=0) {\n          Scalar z = sqrt(q);\n          // one QR-like iteration for ABi - lambda I\n          // is enough - when we know exact eigenvalue in advance,\n          // convergence is immediate\n          JRs G;\n          if (p>=0)\n            G.makeGivens(p + z, STi(1,0));\n          else\n            G.makeGivens(p - z, STi(1,0));\n          m_S.rightCols(dim-i).applyOnTheLeft(i,i+1,G.adjoint());\n          m_T.rightCols(dim-i).applyOnTheLeft(i,i+1,G.adjoint());\n          // update Q\n          if (m_computeQZ)\n            m_Q.applyOnTheRight(i,i+1,G);\n\n          G.makeGivens(m_T.coeff(i+1,i+1), m_T.coeff(i+1,i));\n          m_S.topRows(i+2).applyOnTheRight(i+1,i,G);\n          m_T.topRows(i+2).applyOnTheRight(i+1,i,G);\n          // update Z\n          if (m_computeQZ)\n            m_Z.applyOnTheLeft(i+1,i,G.adjoint());\n\n          m_S.coeffRef(i+1,i) = Scalar(0.0);\n          m_T.coeffRef(i+1,i) = Scalar(0.0);\n        }\n      }\n      else\n      {\n        pushDownZero(j,i,i+1);\n      }\n    }\n\n  /** \\internal use zero in T(z,z) to zero S(l,l-1), working in block f..l */\n  template<typename MatrixType>\n    inline void RealQZ<MatrixType>::pushDownZero(Index z, Index f, Index l)\n    {\n      JRs G;\n      const Index dim = m_S.cols();\n      for (Index zz=z; zz<l; zz++)\n      {\n        // push 0 down\n        Index firstColS = zz>f ? (zz-1) : zz;\n        G.makeGivens(m_T.coeff(zz, zz+1), m_T.coeff(zz+1, zz+1));\n        m_S.rightCols(dim-firstColS).applyOnTheLeft(zz,zz+1,G.adjoint());\n        m_T.rightCols(dim-zz).applyOnTheLeft(zz,zz+1,G.adjoint());\n        m_T.coeffRef(zz+1,zz+1) = Scalar(0.0);\n        // update Q\n        if (m_computeQZ)\n          m_Q.applyOnTheRight(zz,zz+1,G);\n        // kill S(zz+1, zz-1)\n        if (zz>f)\n        {\n          G.makeGivens(m_S.coeff(zz+1, zz), m_S.coeff(zz+1,zz-1));\n          m_S.topRows(zz+2).applyOnTheRight(zz, zz-1,G);\n          m_T.topRows(zz+1).applyOnTheRight(zz, zz-1,G);\n          m_S.coeffRef(zz+1,zz-1) = Scalar(0.0);\n          // update Z\n          if (m_computeQZ)\n            m_Z.applyOnTheLeft(zz,zz-1,G.adjoint());\n        }\n      }\n      // finally kill S(l,l-1)\n      G.makeGivens(m_S.coeff(l,l), m_S.coeff(l,l-1));\n      m_S.applyOnTheRight(l,l-1,G);\n      m_T.applyOnTheRight(l,l-1,G);\n      m_S.coeffRef(l,l-1)=Scalar(0.0);\n      // update Z\n      if (m_computeQZ)\n        m_Z.applyOnTheLeft(l,l-1,G.adjoint());\n    }\n\n  /** \\internal QR-like iterative step for block f..l */\n  template<typename MatrixType>\n    inline void RealQZ<MatrixType>::step(Index f, Index l, Index iter)\n    {\n      using std::abs;\n      const Index dim = m_S.cols();\n\n      // x, y, z\n      Scalar x, y, z;\n      if (iter==10)\n      {\n        // Wilkinson ad hoc shift\n        const Scalar\n          a11=m_S.coeff(f+0,f+0), a12=m_S.coeff(f+0,f+1),\n          a21=m_S.coeff(f+1,f+0), a22=m_S.coeff(f+1,f+1), a32=m_S.coeff(f+2,f+1),\n          b12=m_T.coeff(f+0,f+1),\n          b11i=Scalar(1.0)/m_T.coeff(f+0,f+0),\n          b22i=Scalar(1.0)/m_T.coeff(f+1,f+1),\n          a87=m_S.coeff(l-1,l-2),\n          a98=m_S.coeff(l-0,l-1),\n          b77i=Scalar(1.0)/m_T.coeff(l-2,l-2),\n          b88i=Scalar(1.0)/m_T.coeff(l-1,l-1);\n        Scalar ss = abs(a87*b77i) + abs(a98*b88i),\n               lpl = Scalar(1.5)*ss,\n               ll = ss*ss;\n        x = ll + a11*a11*b11i*b11i - lpl*a11*b11i + a12*a21*b11i*b22i\n          - a11*a21*b12*b11i*b11i*b22i;\n        y = a11*a21*b11i*b11i - lpl*a21*b11i + a21*a22*b11i*b22i \n          - a21*a21*b12*b11i*b11i*b22i;\n        z = a21*a32*b11i*b22i;\n      }\n      else if (iter==16)\n      {\n        // another exceptional shift\n        x = m_S.coeff(f,f)/m_T.coeff(f,f)-m_S.coeff(l,l)/m_T.coeff(l,l) + m_S.coeff(l,l-1)*m_T.coeff(l-1,l) /\n          (m_T.coeff(l-1,l-1)*m_T.coeff(l,l));\n        y = m_S.coeff(f+1,f)/m_T.coeff(f,f);\n        z = 0;\n      }\n      else if (iter>23 && !(iter%8))\n      {\n        // extremely exceptional shift\n        x = internal::random<Scalar>(-1.0,1.0);\n        y = internal::random<Scalar>(-1.0,1.0);\n        z = internal::random<Scalar>(-1.0,1.0);\n      }\n      else\n      {\n        // Compute the shifts: (x,y,z,0...) = (AB^-1 - l1 I) (AB^-1 - l2 I) e1\n        // where l1 and l2 are the eigenvalues of the 2x2 matrix C = U V^-1 where\n        // U and V are 2x2 bottom right sub matrices of A and B. Thus:\n        //  = AB^-1AB^-1 + l1 l2 I - (l1+l2)(AB^-1)\n        //  = AB^-1AB^-1 + det(M) - tr(M)(AB^-1)\n        // Since we are only interested in having x, y, z with a correct ratio, we have:\n        const Scalar\n          a11 = m_S.coeff(f,f),     a12 = m_S.coeff(f,f+1),\n          a21 = m_S.coeff(f+1,f),   a22 = m_S.coeff(f+1,f+1),\n                                    a32 = m_S.coeff(f+2,f+1),\n\n          a88 = m_S.coeff(l-1,l-1), a89 = m_S.coeff(l-1,l),\n          a98 = m_S.coeff(l,l-1),   a99 = m_S.coeff(l,l),\n\n          b11 = m_T.coeff(f,f),     b12 = m_T.coeff(f,f+1),\n                                    b22 = m_T.coeff(f+1,f+1),\n\n          b88 = m_T.coeff(l-1,l-1), b89 = m_T.coeff(l-1,l),\n                                    b99 = m_T.coeff(l,l);\n\n        x = ( (a88/b88 - a11/b11)*(a99/b99 - a11/b11) - (a89/b99)*(a98/b88) + (a98/b88)*(b89/b99)*(a11/b11) ) * (b11/a21)\n          + a12/b22 - (a11/b11)*(b12/b22);\n        y = (a22/b22-a11/b11) - (a21/b11)*(b12/b22) - (a88/b88-a11/b11) - (a99/b99-a11/b11) + (a98/b88)*(b89/b99);\n        z = a32/b22;\n      }\n\n      JRs G;\n\n      for (Index k=f; k<=l-2; k++)\n      {\n        // variables for Householder reflections\n        Vector2s essential2;\n        Scalar tau, beta;\n\n        Vector3s hr(x,y,z);\n\n        // Q_k to annihilate S(k+1,k-1) and S(k+2,k-1)\n        hr.makeHouseholderInPlace(tau, beta);\n        essential2 = hr.template bottomRows<2>();\n        Index fc=(std::max)(k-1,Index(0));  // first col to update\n        m_S.template middleRows<3>(k).rightCols(dim-fc).applyHouseholderOnTheLeft(essential2, tau, m_workspace.data());\n        m_T.template middleRows<3>(k).rightCols(dim-fc).applyHouseholderOnTheLeft(essential2, tau, m_workspace.data());\n        if (m_computeQZ)\n          m_Q.template middleCols<3>(k).applyHouseholderOnTheRight(essential2, tau, m_workspace.data());\n        if (k>f)\n          m_S.coeffRef(k+2,k-1) = m_S.coeffRef(k+1,k-1) = Scalar(0.0);\n\n        // Z_{k1} to annihilate T(k+2,k+1) and T(k+2,k)\n        hr << m_T.coeff(k+2,k+2),m_T.coeff(k+2,k),m_T.coeff(k+2,k+1);\n        hr.makeHouseholderInPlace(tau, beta);\n        essential2 = hr.template bottomRows<2>();\n        {\n          Index lr = (std::min)(k+4,dim); // last row to update\n          Map<Matrix<Scalar,Dynamic,1> > tmp(m_workspace.data(),lr);\n          // S\n          tmp = m_S.template middleCols<2>(k).topRows(lr) * essential2;\n          tmp += m_S.col(k+2).head(lr);\n          m_S.col(k+2).head(lr) -= tau*tmp;\n          m_S.template middleCols<2>(k).topRows(lr) -= (tau*tmp) * essential2.adjoint();\n          // T\n          tmp = m_T.template middleCols<2>(k).topRows(lr) * essential2;\n          tmp += m_T.col(k+2).head(lr);\n          m_T.col(k+2).head(lr) -= tau*tmp;\n          m_T.template middleCols<2>(k).topRows(lr) -= (tau*tmp) * essential2.adjoint();\n        }\n        if (m_computeQZ)\n        {\n          // Z\n          Map<Matrix<Scalar,1,Dynamic> > tmp(m_workspace.data(),dim);\n          tmp = essential2.adjoint()*(m_Z.template middleRows<2>(k));\n          tmp += m_Z.row(k+2);\n          m_Z.row(k+2) -= tau*tmp;\n          m_Z.template middleRows<2>(k) -= essential2 * (tau*tmp);\n        }\n        m_T.coeffRef(k+2,k) = m_T.coeffRef(k+2,k+1) = Scalar(0.0);\n\n        // Z_{k2} to annihilate T(k+1,k)\n        G.makeGivens(m_T.coeff(k+1,k+1), m_T.coeff(k+1,k));\n        m_S.applyOnTheRight(k+1,k,G);\n        m_T.applyOnTheRight(k+1,k,G);\n        // update Z\n        if (m_computeQZ)\n          m_Z.applyOnTheLeft(k+1,k,G.adjoint());\n        m_T.coeffRef(k+1,k) = Scalar(0.0);\n\n        // update x,y,z\n        x = m_S.coeff(k+1,k);\n        y = m_S.coeff(k+2,k);\n        if (k < l-2)\n          z = m_S.coeff(k+3,k);\n      } // loop over k\n\n      // Q_{n-1} to annihilate y = S(l,l-2)\n      G.makeGivens(x,y);\n      m_S.applyOnTheLeft(l-1,l,G.adjoint());\n      m_T.applyOnTheLeft(l-1,l,G.adjoint());\n      if (m_computeQZ)\n        m_Q.applyOnTheRight(l-1,l,G);\n      m_S.coeffRef(l,l-2) = Scalar(0.0);\n\n      // Z_{n-1} to annihilate T(l,l-1)\n      G.makeGivens(m_T.coeff(l,l),m_T.coeff(l,l-1));\n      m_S.applyOnTheRight(l,l-1,G);\n      m_T.applyOnTheRight(l,l-1,G);\n      if (m_computeQZ)\n        m_Z.applyOnTheLeft(l,l-1,G.adjoint());\n      m_T.coeffRef(l,l-1) = Scalar(0.0);\n    }\n\n  template<typename MatrixType>\n    RealQZ<MatrixType>& RealQZ<MatrixType>::compute(const MatrixType& A_in, const MatrixType& B_in, bool computeQZ)\n    {\n\n      const Index dim = A_in.cols();\n\n      eigen_assert (A_in.rows()==dim && A_in.cols()==dim \n          && B_in.rows()==dim && B_in.cols()==dim \n          && \"Need square matrices of the same dimension\");\n\n      m_isInitialized = true;\n      m_computeQZ = computeQZ;\n      m_S = A_in; m_T = B_in;\n      m_workspace.resize(dim*2);\n      m_global_iter = 0;\n\n      // entrance point: hessenberg triangular decomposition\n      hessenbergTriangular();\n      // compute L1 vector norms of T, S into m_normOfS, m_normOfT\n      computeNorms();\n\n      Index l = dim-1, \n            f, \n            local_iter = 0;\n\n      while (l>0 && local_iter<m_maxIters)\n      {\n        f = findSmallSubdiagEntry(l);\n        // now rows and columns f..l (including) decouple from the rest of the problem\n        if (f>0) m_S.coeffRef(f,f-1) = Scalar(0.0);\n        if (f == l) // One root found\n        {\n          l--;\n          local_iter = 0;\n        }\n        else if (f == l-1) // Two roots found\n        {\n          splitOffTwoRows(f);\n          l -= 2;\n          local_iter = 0;\n        }\n        else // No convergence yet\n        {\n          // if there's zero on diagonal of T, we can isolate an eigenvalue with Givens rotations\n          Index z = findSmallDiagEntry(f,l);\n          if (z>=f)\n          {\n            // zero found\n            pushDownZero(z,f,l);\n          }\n          else\n          {\n            // We are sure now that S.block(f,f, l-f+1,l-f+1) is underuced upper-Hessenberg \n            // and T.block(f,f, l-f+1,l-f+1) is invertible uper-triangular, which allows to\n            // apply a QR-like iteration to rows and columns f..l.\n            step(f,l, local_iter);\n            local_iter++;\n            m_global_iter++;\n          }\n        }\n      }\n      // check if we converged before reaching iterations limit\n      m_info = (local_iter<m_maxIters) ? Success : NoConvergence;\n\n      // For each non triangular 2x2 diagonal block of S,\n      //    reduce the respective 2x2 diagonal block of T to positive diagonal form using 2x2 SVD.\n      // This step is not mandatory for QZ, but it does help further extraction of eigenvalues/eigenvectors,\n      // and is in par with Lapack/Matlab QZ.\n      if(m_info==Success)\n      {\n        for(Index i=0; i<dim-1; ++i)\n        {\n          if(m_S.coeff(i+1, i) != Scalar(0))\n          {\n            JacobiRotation<Scalar> j_left, j_right;\n            internal::real_2x2_jacobi_svd(m_T, i, i+1, &j_left, &j_right);\n\n            // Apply resulting Jacobi rotations\n            m_S.applyOnTheLeft(i,i+1,j_left);\n            m_S.applyOnTheRight(i,i+1,j_right);\n            m_T.applyOnTheLeft(i,i+1,j_left);\n            m_T.applyOnTheRight(i,i+1,j_right);\n            m_T(i+1,i) = m_T(i,i+1) = Scalar(0);\n\n            if(m_computeQZ) {\n              m_Q.applyOnTheRight(i,i+1,j_left.transpose());\n              m_Z.applyOnTheLeft(i,i+1,j_right.transpose());\n            }\n\n            i++;\n          }\n        }\n      }\n\n      return *this;\n    } // end compute\n\n} // end namespace Eigen\n\n#endif //EIGEN_REAL_QZ\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Eigenvalues/RealSchur.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010,2012 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_REAL_SCHUR_H\n#define EIGEN_REAL_SCHUR_H\n\n#include \"./HessenbergDecomposition.h\"\n\nnamespace Eigen { \n\n/** \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  *\n  * \\class RealSchur\n  *\n  * \\brief Performs a real Schur decomposition of a square matrix\n  *\n  * \\tparam _MatrixType the type of the matrix of which we are computing the\n  * real Schur decomposition; this is expected to be an instantiation of the\n  * Matrix class template.\n  *\n  * Given a real square matrix A, this class computes the real Schur\n  * decomposition: \\f$ A = U T U^T \\f$ where U is a real orthogonal matrix and\n  * T is a real quasi-triangular matrix. An orthogonal matrix is a matrix whose\n  * inverse is equal to its transpose, \\f$ U^{-1} = U^T \\f$. A quasi-triangular\n  * matrix is a block-triangular matrix whose diagonal consists of 1-by-1\n  * blocks and 2-by-2 blocks with complex eigenvalues. The eigenvalues of the\n  * blocks on the diagonal of T are the same as the eigenvalues of the matrix\n  * A, and thus the real Schur decomposition is used in EigenSolver to compute\n  * the eigendecomposition of a matrix.\n  *\n  * Call the function compute() to compute the real Schur decomposition of a\n  * given matrix. Alternatively, you can use the RealSchur(const MatrixType&, bool)\n  * constructor which computes the real Schur decomposition at construction\n  * time. Once the decomposition is computed, you can use the matrixU() and\n  * matrixT() functions to retrieve the matrices U and T in the decomposition.\n  *\n  * The documentation of RealSchur(const MatrixType&, bool) contains an example\n  * of the typical use of this class.\n  *\n  * \\note The implementation is adapted from\n  * <a href=\"http://math.nist.gov/javanumerics/jama/\">JAMA</a> (public domain).\n  * Their code is based on EISPACK.\n  *\n  * \\sa class ComplexSchur, class EigenSolver, class ComplexEigenSolver\n  */\ntemplate<typename _MatrixType> class RealSchur\n{\n  public:\n    typedef _MatrixType MatrixType;\n    enum {\n      RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      Options = MatrixType::Options,\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n    typedef typename MatrixType::Scalar Scalar;\n    typedef std::complex<typename NumTraits<Scalar>::Real> ComplexScalar;\n    typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n\n    typedef Matrix<ComplexScalar, ColsAtCompileTime, 1, Options & ~RowMajor, MaxColsAtCompileTime, 1> EigenvalueType;\n    typedef Matrix<Scalar, ColsAtCompileTime, 1, Options & ~RowMajor, MaxColsAtCompileTime, 1> ColumnVectorType;\n\n    /** \\brief Default constructor.\n      *\n      * \\param [in] size  Positive integer, size of the matrix whose Schur decomposition will be computed.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via compute().  The \\p size parameter is only\n      * used as a hint. It is not an error to give a wrong \\p size, but it may\n      * impair performance.\n      *\n      * \\sa compute() for an example.\n      */\n    explicit RealSchur(Index size = RowsAtCompileTime==Dynamic ? 1 : RowsAtCompileTime)\n            : m_matT(size, size),\n              m_matU(size, size),\n              m_workspaceVector(size),\n              m_hess(size),\n              m_isInitialized(false),\n              m_matUisUptodate(false),\n              m_maxIters(-1)\n    { }\n\n    /** \\brief Constructor; computes real Schur decomposition of given matrix. \n      * \n      * \\param[in]  matrix    Square matrix whose Schur decomposition is to be computed.\n      * \\param[in]  computeU  If true, both T and U are computed; if false, only T is computed.\n      *\n      * This constructor calls compute() to compute the Schur decomposition.\n      *\n      * Example: \\include RealSchur_RealSchur_MatrixType.cpp\n      * Output: \\verbinclude RealSchur_RealSchur_MatrixType.out\n      */\n    template<typename InputType>\n    explicit RealSchur(const EigenBase<InputType>& matrix, bool computeU = true)\n            : m_matT(matrix.rows(),matrix.cols()),\n              m_matU(matrix.rows(),matrix.cols()),\n              m_workspaceVector(matrix.rows()),\n              m_hess(matrix.rows()),\n              m_isInitialized(false),\n              m_matUisUptodate(false),\n              m_maxIters(-1)\n    {\n      compute(matrix.derived(), computeU);\n    }\n\n    /** \\brief Returns the orthogonal matrix in the Schur decomposition. \n      *\n      * \\returns A const reference to the matrix U.\n      *\n      * \\pre Either the constructor RealSchur(const MatrixType&, bool) or the\n      * member function compute(const MatrixType&, bool) has been called before\n      * to compute the Schur decomposition of a matrix, and \\p computeU was set\n      * to true (the default value).\n      *\n      * \\sa RealSchur(const MatrixType&, bool) for an example\n      */\n    const MatrixType& matrixU() const\n    {\n      eigen_assert(m_isInitialized && \"RealSchur is not initialized.\");\n      eigen_assert(m_matUisUptodate && \"The matrix U has not been computed during the RealSchur decomposition.\");\n      return m_matU;\n    }\n\n    /** \\brief Returns the quasi-triangular matrix in the Schur decomposition. \n      *\n      * \\returns A const reference to the matrix T.\n      *\n      * \\pre Either the constructor RealSchur(const MatrixType&, bool) or the\n      * member function compute(const MatrixType&, bool) has been called before\n      * to compute the Schur decomposition of a matrix.\n      *\n      * \\sa RealSchur(const MatrixType&, bool) for an example\n      */\n    const MatrixType& matrixT() const\n    {\n      eigen_assert(m_isInitialized && \"RealSchur is not initialized.\");\n      return m_matT;\n    }\n  \n    /** \\brief Computes Schur decomposition of given matrix. \n      * \n      * \\param[in]  matrix    Square matrix whose Schur decomposition is to be computed.\n      * \\param[in]  computeU  If true, both T and U are computed; if false, only T is computed.\n      * \\returns    Reference to \\c *this\n      *\n      * The Schur decomposition is computed by first reducing the matrix to\n      * Hessenberg form using the class HessenbergDecomposition. The Hessenberg\n      * matrix is then reduced to triangular form by performing Francis QR\n      * iterations with implicit double shift. The cost of computing the Schur\n      * decomposition depends on the number of iterations; as a rough guide, it\n      * may be taken to be \\f$25n^3\\f$ flops if \\a computeU is true and\n      * \\f$10n^3\\f$ flops if \\a computeU is false.\n      *\n      * Example: \\include RealSchur_compute.cpp\n      * Output: \\verbinclude RealSchur_compute.out\n      *\n      * \\sa compute(const MatrixType&, bool, Index)\n      */\n    template<typename InputType>\n    RealSchur& compute(const EigenBase<InputType>& matrix, bool computeU = true);\n\n    /** \\brief Computes Schur decomposition of a Hessenberg matrix H = Z T Z^T\n     *  \\param[in] matrixH Matrix in Hessenberg form H\n     *  \\param[in] matrixQ orthogonal matrix Q that transform a matrix A to H : A = Q H Q^T\n     *  \\param computeU Computes the matriX U of the Schur vectors\n     * \\return Reference to \\c *this\n     * \n     *  This routine assumes that the matrix is already reduced in Hessenberg form matrixH\n     *  using either the class HessenbergDecomposition or another mean. \n     *  It computes the upper quasi-triangular matrix T of the Schur decomposition of H\n     *  When computeU is true, this routine computes the matrix U such that \n     *  A = U T U^T =  (QZ) T (QZ)^T = Q H Q^T where A is the initial matrix\n     * \n     * NOTE Q is referenced if computeU is true; so, if the initial orthogonal matrix\n     * is not available, the user should give an identity matrix (Q.setIdentity())\n     * \n     * \\sa compute(const MatrixType&, bool)\n     */\n    template<typename HessMatrixType, typename OrthMatrixType>\n    RealSchur& computeFromHessenberg(const HessMatrixType& matrixH, const OrthMatrixType& matrixQ,  bool computeU);\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful, \\c NoConvergence otherwise.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"RealSchur is not initialized.\");\n      return m_info;\n    }\n\n    /** \\brief Sets the maximum number of iterations allowed. \n      *\n      * If not specified by the user, the maximum number of iterations is m_maxIterationsPerRow times the size\n      * of the matrix.\n      */\n    RealSchur& setMaxIterations(Index maxIters)\n    {\n      m_maxIters = maxIters;\n      return *this;\n    }\n\n    /** \\brief Returns the maximum number of iterations. */\n    Index getMaxIterations()\n    {\n      return m_maxIters;\n    }\n\n    /** \\brief Maximum number of iterations per row.\n      *\n      * If not otherwise specified, the maximum number of iterations is this number times the size of the\n      * matrix. It is currently set to 40.\n      */\n    static const int m_maxIterationsPerRow = 40;\n\n  private:\n    \n    MatrixType m_matT;\n    MatrixType m_matU;\n    ColumnVectorType m_workspaceVector;\n    HessenbergDecomposition<MatrixType> m_hess;\n    ComputationInfo m_info;\n    bool m_isInitialized;\n    bool m_matUisUptodate;\n    Index m_maxIters;\n\n    typedef Matrix<Scalar,3,1> Vector3s;\n\n    Scalar computeNormOfT();\n    Index findSmallSubdiagEntry(Index iu, const Scalar& considerAsZero);\n    void splitOffTwoRows(Index iu, bool computeU, const Scalar& exshift);\n    void computeShift(Index iu, Index iter, Scalar& exshift, Vector3s& shiftInfo);\n    void initFrancisQRStep(Index il, Index iu, const Vector3s& shiftInfo, Index& im, Vector3s& firstHouseholderVector);\n    void performFrancisQRStep(Index il, Index im, Index iu, bool computeU, const Vector3s& firstHouseholderVector, Scalar* workspace);\n};\n\n\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nRealSchur<MatrixType>& RealSchur<MatrixType>::compute(const EigenBase<InputType>& matrix, bool computeU)\n{\n  const Scalar considerAsZero = (std::numeric_limits<Scalar>::min)();\n\n  eigen_assert(matrix.cols() == matrix.rows());\n  Index maxIters = m_maxIters;\n  if (maxIters == -1)\n    maxIters = m_maxIterationsPerRow * matrix.rows();\n\n  Scalar scale = matrix.derived().cwiseAbs().maxCoeff();\n  if(scale<considerAsZero)\n  {\n    m_matT.setZero(matrix.rows(),matrix.cols());\n    if(computeU)\n      m_matU.setIdentity(matrix.rows(),matrix.cols());\n    m_info = Success;\n    m_isInitialized = true;\n    m_matUisUptodate = computeU;\n    return *this;\n  }\n\n  // Step 1. Reduce to Hessenberg form\n  m_hess.compute(matrix.derived()/scale);\n\n  // Step 2. Reduce to real Schur form\n  // Note: we copy m_hess.matrixQ() into m_matU here and not in computeFromHessenberg\n  //       to be able to pass our working-space buffer for the Householder to Dense evaluation.\n  m_workspaceVector.resize(matrix.cols());\n  if(computeU)\n    m_hess.matrixQ().evalTo(m_matU, m_workspaceVector);\n  computeFromHessenberg(m_hess.matrixH(), m_matU, computeU);\n\n  m_matT *= scale;\n  \n  return *this;\n}\ntemplate<typename MatrixType>\ntemplate<typename HessMatrixType, typename OrthMatrixType>\nRealSchur<MatrixType>& RealSchur<MatrixType>::computeFromHessenberg(const HessMatrixType& matrixH, const OrthMatrixType& matrixQ,  bool computeU)\n{\n  using std::abs;\n\n  m_matT = matrixH;\n  m_workspaceVector.resize(m_matT.cols());\n  if(computeU && !internal::is_same_dense(m_matU,matrixQ))\n    m_matU = matrixQ;\n  \n  Index maxIters = m_maxIters;\n  if (maxIters == -1)\n    maxIters = m_maxIterationsPerRow * matrixH.rows();\n  Scalar* workspace = &m_workspaceVector.coeffRef(0);\n\n  // The matrix m_matT is divided in three parts. \n  // Rows 0,...,il-1 are decoupled from the rest because m_matT(il,il-1) is zero. \n  // Rows il,...,iu is the part we are working on (the active window).\n  // Rows iu+1,...,end are already brought in triangular form.\n  Index iu = m_matT.cols() - 1;\n  Index iter = 0;      // iteration count for current eigenvalue\n  Index totalIter = 0; // iteration count for whole matrix\n  Scalar exshift(0);   // sum of exceptional shifts\n  Scalar norm = computeNormOfT();\n  // sub-diagonal entries smaller than considerAsZero will be treated as zero.\n  // We use eps^2 to enable more precision in small eigenvalues.\n  Scalar considerAsZero = numext::maxi<Scalar>( norm * numext::abs2(NumTraits<Scalar>::epsilon()),\n                                                (std::numeric_limits<Scalar>::min)() );\n\n  if(norm!=Scalar(0))\n  {\n    while (iu >= 0)\n    {\n      Index il = findSmallSubdiagEntry(iu,considerAsZero);\n\n      // Check for convergence\n      if (il == iu) // One root found\n      {\n        m_matT.coeffRef(iu,iu) = m_matT.coeff(iu,iu) + exshift;\n        if (iu > 0)\n          m_matT.coeffRef(iu, iu-1) = Scalar(0);\n        iu--;\n        iter = 0;\n      }\n      else if (il == iu-1) // Two roots found\n      {\n        splitOffTwoRows(iu, computeU, exshift);\n        iu -= 2;\n        iter = 0;\n      }\n      else // No convergence yet\n      {\n        // The firstHouseholderVector vector has to be initialized to something to get rid of a silly GCC warning (-O1 -Wall -DNDEBUG )\n        Vector3s firstHouseholderVector = Vector3s::Zero(), shiftInfo;\n        computeShift(iu, iter, exshift, shiftInfo);\n        iter = iter + 1;\n        totalIter = totalIter + 1;\n        if (totalIter > maxIters) break;\n        Index im;\n        initFrancisQRStep(il, iu, shiftInfo, im, firstHouseholderVector);\n        performFrancisQRStep(il, im, iu, computeU, firstHouseholderVector, workspace);\n      }\n    }\n  }\n  if(totalIter <= maxIters)\n    m_info = Success;\n  else\n    m_info = NoConvergence;\n\n  m_isInitialized = true;\n  m_matUisUptodate = computeU;\n  return *this;\n}\n\n/** \\internal Computes and returns vector L1 norm of T */\ntemplate<typename MatrixType>\ninline typename MatrixType::Scalar RealSchur<MatrixType>::computeNormOfT()\n{\n  const Index size = m_matT.cols();\n  // FIXME to be efficient the following would requires a triangular reduxion code\n  // Scalar norm = m_matT.upper().cwiseAbs().sum() \n  //               + m_matT.bottomLeftCorner(size-1,size-1).diagonal().cwiseAbs().sum();\n  Scalar norm(0);\n  for (Index j = 0; j < size; ++j)\n    norm += m_matT.col(j).segment(0, (std::min)(size,j+2)).cwiseAbs().sum();\n  return norm;\n}\n\n/** \\internal Look for single small sub-diagonal element and returns its index */\ntemplate<typename MatrixType>\ninline Index RealSchur<MatrixType>::findSmallSubdiagEntry(Index iu, const Scalar& considerAsZero)\n{\n  using std::abs;\n  Index res = iu;\n  while (res > 0)\n  {\n    Scalar s = abs(m_matT.coeff(res-1,res-1)) + abs(m_matT.coeff(res,res));\n\n    s = numext::maxi<Scalar>(s * NumTraits<Scalar>::epsilon(), considerAsZero);\n    \n    if (abs(m_matT.coeff(res,res-1)) <= s)\n      break;\n    res--;\n  }\n  return res;\n}\n\n/** \\internal Update T given that rows iu-1 and iu decouple from the rest. */\ntemplate<typename MatrixType>\ninline void RealSchur<MatrixType>::splitOffTwoRows(Index iu, bool computeU, const Scalar& exshift)\n{\n  using std::sqrt;\n  using std::abs;\n  const Index size = m_matT.cols();\n\n  // The eigenvalues of the 2x2 matrix [a b; c d] are \n  // trace +/- sqrt(discr/4) where discr = tr^2 - 4*det, tr = a + d, det = ad - bc\n  Scalar p = Scalar(0.5) * (m_matT.coeff(iu-1,iu-1) - m_matT.coeff(iu,iu));\n  Scalar q = p * p + m_matT.coeff(iu,iu-1) * m_matT.coeff(iu-1,iu);   // q = tr^2 / 4 - det = discr/4\n  m_matT.coeffRef(iu,iu) += exshift;\n  m_matT.coeffRef(iu-1,iu-1) += exshift;\n\n  if (q >= Scalar(0)) // Two real eigenvalues\n  {\n    Scalar z = sqrt(abs(q));\n    JacobiRotation<Scalar> rot;\n    if (p >= Scalar(0))\n      rot.makeGivens(p + z, m_matT.coeff(iu, iu-1));\n    else\n      rot.makeGivens(p - z, m_matT.coeff(iu, iu-1));\n\n    m_matT.rightCols(size-iu+1).applyOnTheLeft(iu-1, iu, rot.adjoint());\n    m_matT.topRows(iu+1).applyOnTheRight(iu-1, iu, rot);\n    m_matT.coeffRef(iu, iu-1) = Scalar(0); \n    if (computeU)\n      m_matU.applyOnTheRight(iu-1, iu, rot);\n  }\n\n  if (iu > 1) \n    m_matT.coeffRef(iu-1, iu-2) = Scalar(0);\n}\n\n/** \\internal Form shift in shiftInfo, and update exshift if an exceptional shift is performed. */\ntemplate<typename MatrixType>\ninline void RealSchur<MatrixType>::computeShift(Index iu, Index iter, Scalar& exshift, Vector3s& shiftInfo)\n{\n  using std::sqrt;\n  using std::abs;\n  shiftInfo.coeffRef(0) = m_matT.coeff(iu,iu);\n  shiftInfo.coeffRef(1) = m_matT.coeff(iu-1,iu-1);\n  shiftInfo.coeffRef(2) = m_matT.coeff(iu,iu-1) * m_matT.coeff(iu-1,iu);\n\n  // Wilkinson's original ad hoc shift\n  if (iter == 10)\n  {\n    exshift += shiftInfo.coeff(0);\n    for (Index i = 0; i <= iu; ++i)\n      m_matT.coeffRef(i,i) -= shiftInfo.coeff(0);\n    Scalar s = abs(m_matT.coeff(iu,iu-1)) + abs(m_matT.coeff(iu-1,iu-2));\n    shiftInfo.coeffRef(0) = Scalar(0.75) * s;\n    shiftInfo.coeffRef(1) = Scalar(0.75) * s;\n    shiftInfo.coeffRef(2) = Scalar(-0.4375) * s * s;\n  }\n\n  // MATLAB's new ad hoc shift\n  if (iter == 30)\n  {\n    Scalar s = (shiftInfo.coeff(1) - shiftInfo.coeff(0)) / Scalar(2.0);\n    s = s * s + shiftInfo.coeff(2);\n    if (s > Scalar(0))\n    {\n      s = sqrt(s);\n      if (shiftInfo.coeff(1) < shiftInfo.coeff(0))\n        s = -s;\n      s = s + (shiftInfo.coeff(1) - shiftInfo.coeff(0)) / Scalar(2.0);\n      s = shiftInfo.coeff(0) - shiftInfo.coeff(2) / s;\n      exshift += s;\n      for (Index i = 0; i <= iu; ++i)\n        m_matT.coeffRef(i,i) -= s;\n      shiftInfo.setConstant(Scalar(0.964));\n    }\n  }\n}\n\n/** \\internal Compute index im at which Francis QR step starts and the first Householder vector. */\ntemplate<typename MatrixType>\ninline void RealSchur<MatrixType>::initFrancisQRStep(Index il, Index iu, const Vector3s& shiftInfo, Index& im, Vector3s& firstHouseholderVector)\n{\n  using std::abs;\n  Vector3s& v = firstHouseholderVector; // alias to save typing\n\n  for (im = iu-2; im >= il; --im)\n  {\n    const Scalar Tmm = m_matT.coeff(im,im);\n    const Scalar r = shiftInfo.coeff(0) - Tmm;\n    const Scalar s = shiftInfo.coeff(1) - Tmm;\n    v.coeffRef(0) = (r * s - shiftInfo.coeff(2)) / m_matT.coeff(im+1,im) + m_matT.coeff(im,im+1);\n    v.coeffRef(1) = m_matT.coeff(im+1,im+1) - Tmm - r - s;\n    v.coeffRef(2) = m_matT.coeff(im+2,im+1);\n    if (im == il) {\n      break;\n    }\n    const Scalar lhs = m_matT.coeff(im,im-1) * (abs(v.coeff(1)) + abs(v.coeff(2)));\n    const Scalar rhs = v.coeff(0) * (abs(m_matT.coeff(im-1,im-1)) + abs(Tmm) + abs(m_matT.coeff(im+1,im+1)));\n    if (abs(lhs) < NumTraits<Scalar>::epsilon() * rhs)\n      break;\n  }\n}\n\n/** \\internal Perform a Francis QR step involving rows il:iu and columns im:iu. */\ntemplate<typename MatrixType>\ninline void RealSchur<MatrixType>::performFrancisQRStep(Index il, Index im, Index iu, bool computeU, const Vector3s& firstHouseholderVector, Scalar* workspace)\n{\n  eigen_assert(im >= il);\n  eigen_assert(im <= iu-2);\n\n  const Index size = m_matT.cols();\n\n  for (Index k = im; k <= iu-2; ++k)\n  {\n    bool firstIteration = (k == im);\n\n    Vector3s v;\n    if (firstIteration)\n      v = firstHouseholderVector;\n    else\n      v = m_matT.template block<3,1>(k,k-1);\n\n    Scalar tau, beta;\n    Matrix<Scalar, 2, 1> ess;\n    v.makeHouseholder(ess, tau, beta);\n    \n    if (beta != Scalar(0)) // if v is not zero\n    {\n      if (firstIteration && k > il)\n        m_matT.coeffRef(k,k-1) = -m_matT.coeff(k,k-1);\n      else if (!firstIteration)\n        m_matT.coeffRef(k,k-1) = beta;\n\n      // These Householder transformations form the O(n^3) part of the algorithm\n      m_matT.block(k, k, 3, size-k).applyHouseholderOnTheLeft(ess, tau, workspace);\n      m_matT.block(0, k, (std::min)(iu,k+3) + 1, 3).applyHouseholderOnTheRight(ess, tau, workspace);\n      if (computeU)\n        m_matU.block(0, k, size, 3).applyHouseholderOnTheRight(ess, tau, workspace);\n    }\n  }\n\n  Matrix<Scalar, 2, 1> v = m_matT.template block<2,1>(iu-1, iu-2);\n  Scalar tau, beta;\n  Matrix<Scalar, 1, 1> ess;\n  v.makeHouseholder(ess, tau, beta);\n\n  if (beta != Scalar(0)) // if v is not zero\n  {\n    m_matT.coeffRef(iu-1, iu-2) = beta;\n    m_matT.block(iu-1, iu-1, 2, size-iu+1).applyHouseholderOnTheLeft(ess, tau, workspace);\n    m_matT.block(0, iu-1, iu+1, 2).applyHouseholderOnTheRight(ess, tau, workspace);\n    if (computeU)\n      m_matU.block(0, iu-1, size, 2).applyHouseholderOnTheRight(ess, tau, workspace);\n  }\n\n  // clean up pollution due to round-off errors\n  for (Index i = im+2; i <= iu; ++i)\n  {\n    m_matT.coeffRef(i,i-2) = Scalar(0);\n    if (i > im+2)\n      m_matT.coeffRef(i,i-3) = Scalar(0);\n  }\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_REAL_SCHUR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Eigenvalues/RealSchur_LAPACKE.h",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Eigen bindings to LAPACKe\n *    Real Schur needed to real unsymmetrical eigenvalues/eigenvectors.\n ********************************************************************************\n*/\n\n#ifndef EIGEN_REAL_SCHUR_LAPACKE_H\n#define EIGEN_REAL_SCHUR_LAPACKE_H\n\nnamespace Eigen { \n\n/** \\internal Specialization for the data types supported by LAPACKe */\n\n#define EIGEN_LAPACKE_SCHUR_REAL(EIGTYPE, LAPACKE_TYPE, LAPACKE_PREFIX, LAPACKE_PREFIX_U, EIGCOLROW, LAPACKE_COLROW) \\\ntemplate<> template<typename InputType> inline \\\nRealSchur<Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW> >& \\\nRealSchur<Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW> >::compute(const EigenBase<InputType>& matrix, bool computeU) \\\n{ \\\n  eigen_assert(matrix.cols() == matrix.rows()); \\\n\\\n  lapack_int n = internal::convert_index<lapack_int>(matrix.cols()), sdim, info; \\\n  lapack_int matrix_order = LAPACKE_COLROW; \\\n  char jobvs, sort='N'; \\\n  LAPACK_##LAPACKE_PREFIX_U##_SELECT2 select = 0; \\\n  jobvs = (computeU) ? 'V' : 'N'; \\\n  m_matU.resize(n, n); \\\n  lapack_int ldvs  = internal::convert_index<lapack_int>(m_matU.outerStride()); \\\n  m_matT = matrix; \\\n  lapack_int lda = internal::convert_index<lapack_int>(m_matT.outerStride()); \\\n  Matrix<EIGTYPE, Dynamic, Dynamic> wr, wi; \\\n  wr.resize(n, 1); wi.resize(n, 1); \\\n  info = LAPACKE_##LAPACKE_PREFIX##gees( matrix_order, jobvs, sort, select, n, (LAPACKE_TYPE*)m_matT.data(), lda, &sdim, (LAPACKE_TYPE*)wr.data(), (LAPACKE_TYPE*)wi.data(), (LAPACKE_TYPE*)m_matU.data(), ldvs ); \\\n  if(info == 0) \\\n    m_info = Success; \\\n  else \\\n    m_info = NoConvergence; \\\n\\\n  m_isInitialized = true; \\\n  m_matUisUptodate = computeU; \\\n  return *this; \\\n\\\n}\n\nEIGEN_LAPACKE_SCHUR_REAL(double,   double, d, D, ColMajor, LAPACK_COL_MAJOR)\nEIGEN_LAPACKE_SCHUR_REAL(float,    float,  s, S, ColMajor, LAPACK_COL_MAJOR)\nEIGEN_LAPACKE_SCHUR_REAL(double,   double, d, D, RowMajor, LAPACK_ROW_MAJOR)\nEIGEN_LAPACKE_SCHUR_REAL(float,    float,  s, S, RowMajor, LAPACK_ROW_MAJOR)\n\n} // end namespace Eigen\n\n#endif // EIGEN_REAL_SCHUR_LAPACKE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Eigenvalues/SelfAdjointEigenSolver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SELFADJOINTEIGENSOLVER_H\n#define EIGEN_SELFADJOINTEIGENSOLVER_H\n\n#include \"./Tridiagonalization.h\"\n\nnamespace Eigen { \n\ntemplate<typename _MatrixType>\nclass GeneralizedSelfAdjointEigenSolver;\n\nnamespace internal {\ntemplate<typename SolverType,int Size,bool IsComplex> struct direct_selfadjoint_eigenvalues;\n\ntemplate<typename MatrixType, typename DiagType, typename SubDiagType>\nEIGEN_DEVICE_FUNC\nComputationInfo computeFromTridiagonal_impl(DiagType& diag, SubDiagType& subdiag, const Index maxIterations, bool computeEigenvectors, MatrixType& eivec);\n}\n\n/** \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  *\n  * \\class SelfAdjointEigenSolver\n  *\n  * \\brief Computes eigenvalues and eigenvectors of selfadjoint matrices\n  *\n  * \\tparam _MatrixType the type of the matrix of which we are computing the\n  * eigendecomposition; this is expected to be an instantiation of the Matrix\n  * class template.\n  *\n  * A matrix \\f$ A \\f$ is selfadjoint if it equals its adjoint. For real\n  * matrices, this means that the matrix is symmetric: it equals its\n  * transpose. This class computes the eigenvalues and eigenvectors of a\n  * selfadjoint matrix. These are the scalars \\f$ \\lambda \\f$ and vectors\n  * \\f$ v \\f$ such that \\f$ Av = \\lambda v \\f$.  The eigenvalues of a\n  * selfadjoint matrix are always real. If \\f$ D \\f$ is a diagonal matrix with\n  * the eigenvalues on the diagonal, and \\f$ V \\f$ is a matrix with the\n  * eigenvectors as its columns, then \\f$ A = V D V^{-1} \\f$. This is called the\n  * eigendecomposition.\n  *\n  * For a selfadjoint matrix, \\f$ V \\f$ is unitary, meaning its inverse is equal\n  * to its adjoint, \\f$ V^{-1} = V^{\\dagger} \\f$. If \\f$ A \\f$ is real, then\n  * \\f$ V \\f$ is also real and therefore orthogonal, meaning its inverse is\n  * equal to its transpose, \\f$ V^{-1} = V^T \\f$.\n  *\n  * The algorithm exploits the fact that the matrix is selfadjoint, making it\n  * faster and more accurate than the general purpose eigenvalue algorithms\n  * implemented in EigenSolver and ComplexEigenSolver.\n  *\n  * Only the \\b lower \\b triangular \\b part of the input matrix is referenced.\n  *\n  * Call the function compute() to compute the eigenvalues and eigenvectors of\n  * a given matrix. Alternatively, you can use the\n  * SelfAdjointEigenSolver(const MatrixType&, int) constructor which computes\n  * the eigenvalues and eigenvectors at construction time. Once the eigenvalue\n  * and eigenvectors are computed, they can be retrieved with the eigenvalues()\n  * and eigenvectors() functions.\n  *\n  * The documentation for SelfAdjointEigenSolver(const MatrixType&, int)\n  * contains an example of the typical use of this class.\n  *\n  * To solve the \\em generalized eigenvalue problem \\f$ Av = \\lambda Bv \\f$ and\n  * the likes, see the class GeneralizedSelfAdjointEigenSolver.\n  *\n  * \\sa MatrixBase::eigenvalues(), class EigenSolver, class ComplexEigenSolver\n  */\ntemplate<typename _MatrixType> class SelfAdjointEigenSolver\n{\n  public:\n\n    typedef _MatrixType MatrixType;\n    enum {\n      Size = MatrixType::RowsAtCompileTime,\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      Options = MatrixType::Options,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n    \n    /** \\brief Scalar type for matrices of type \\p _MatrixType. */\n    typedef typename MatrixType::Scalar Scalar;\n    typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n    \n    typedef Matrix<Scalar,Size,Size,ColMajor,MaxColsAtCompileTime,MaxColsAtCompileTime> EigenvectorsType;\n\n    /** \\brief Real scalar type for \\p _MatrixType.\n      *\n      * This is just \\c Scalar if #Scalar is real (e.g., \\c float or\n      * \\c double), and the type of the real part of \\c Scalar if #Scalar is\n      * complex.\n      */\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    \n    friend struct internal::direct_selfadjoint_eigenvalues<SelfAdjointEigenSolver,Size,NumTraits<Scalar>::IsComplex>;\n\n    /** \\brief Type for vector of eigenvalues as returned by eigenvalues().\n      *\n      * This is a column vector with entries of type #RealScalar.\n      * The length of the vector is the size of \\p _MatrixType.\n      */\n    typedef typename internal::plain_col_type<MatrixType, RealScalar>::type RealVectorType;\n    typedef Tridiagonalization<MatrixType> TridiagonalizationType;\n    typedef typename TridiagonalizationType::SubDiagonalType SubDiagonalType;\n\n    /** \\brief Default constructor for fixed-size matrices.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via compute(). This constructor\n      * can only be used if \\p _MatrixType is a fixed-size matrix; use\n      * SelfAdjointEigenSolver(Index) for dynamic-size matrices.\n      *\n      * Example: \\include SelfAdjointEigenSolver_SelfAdjointEigenSolver.cpp\n      * Output: \\verbinclude SelfAdjointEigenSolver_SelfAdjointEigenSolver.out\n      */\n    EIGEN_DEVICE_FUNC\n    SelfAdjointEigenSolver()\n        : m_eivec(),\n          m_eivalues(),\n          m_subdiag(),\n          m_info(InvalidInput),\n          m_isInitialized(false),\n          m_eigenvectorsOk(false)\n    { }\n\n    /** \\brief Constructor, pre-allocates memory for dynamic-size matrices.\n      *\n      * \\param [in]  size  Positive integer, size of the matrix whose\n      * eigenvalues and eigenvectors will be computed.\n      *\n      * This constructor is useful for dynamic-size matrices, when the user\n      * intends to perform decompositions via compute(). The \\p size\n      * parameter is only used as a hint. It is not an error to give a wrong\n      * \\p size, but it may impair performance.\n      *\n      * \\sa compute() for an example\n      */\n    EIGEN_DEVICE_FUNC\n    explicit SelfAdjointEigenSolver(Index size)\n        : m_eivec(size, size),\n          m_eivalues(size),\n          m_subdiag(size > 1 ? size - 1 : 1),\n          m_isInitialized(false),\n          m_eigenvectorsOk(false)\n    {}\n\n    /** \\brief Constructor; computes eigendecomposition of given matrix.\n      *\n      * \\param[in]  matrix  Selfadjoint matrix whose eigendecomposition is to\n      *    be computed. Only the lower triangular part of the matrix is referenced.\n      * \\param[in]  options Can be #ComputeEigenvectors (default) or #EigenvaluesOnly.\n      *\n      * This constructor calls compute(const MatrixType&, int) to compute the\n      * eigenvalues of the matrix \\p matrix. The eigenvectors are computed if\n      * \\p options equals #ComputeEigenvectors.\n      *\n      * Example: \\include SelfAdjointEigenSolver_SelfAdjointEigenSolver_MatrixType.cpp\n      * Output: \\verbinclude SelfAdjointEigenSolver_SelfAdjointEigenSolver_MatrixType.out\n      *\n      * \\sa compute(const MatrixType&, int)\n      */\n    template<typename InputType>\n    EIGEN_DEVICE_FUNC\n    explicit SelfAdjointEigenSolver(const EigenBase<InputType>& matrix, int options = ComputeEigenvectors)\n      : m_eivec(matrix.rows(), matrix.cols()),\n        m_eivalues(matrix.cols()),\n        m_subdiag(matrix.rows() > 1 ? matrix.rows() - 1 : 1),\n        m_isInitialized(false),\n        m_eigenvectorsOk(false)\n    {\n      compute(matrix.derived(), options);\n    }\n\n    /** \\brief Computes eigendecomposition of given matrix.\n      *\n      * \\param[in]  matrix  Selfadjoint matrix whose eigendecomposition is to\n      *    be computed. Only the lower triangular part of the matrix is referenced.\n      * \\param[in]  options Can be #ComputeEigenvectors (default) or #EigenvaluesOnly.\n      * \\returns    Reference to \\c *this\n      *\n      * This function computes the eigenvalues of \\p matrix.  The eigenvalues()\n      * function can be used to retrieve them.  If \\p options equals #ComputeEigenvectors,\n      * then the eigenvectors are also computed and can be retrieved by\n      * calling eigenvectors().\n      *\n      * This implementation uses a symmetric QR algorithm. The matrix is first\n      * reduced to tridiagonal form using the Tridiagonalization class. The\n      * tridiagonal matrix is then brought to diagonal form with implicit\n      * symmetric QR steps with Wilkinson shift. Details can be found in\n      * Section 8.3 of Golub \\& Van Loan, <i>%Matrix Computations</i>.\n      *\n      * The cost of the computation is about \\f$ 9n^3 \\f$ if the eigenvectors\n      * are required and \\f$ 4n^3/3 \\f$ if they are not required.\n      *\n      * This method reuses the memory in the SelfAdjointEigenSolver object that\n      * was allocated when the object was constructed, if the size of the\n      * matrix does not change.\n      *\n      * Example: \\include SelfAdjointEigenSolver_compute_MatrixType.cpp\n      * Output: \\verbinclude SelfAdjointEigenSolver_compute_MatrixType.out\n      *\n      * \\sa SelfAdjointEigenSolver(const MatrixType&, int)\n      */\n    template<typename InputType>\n    EIGEN_DEVICE_FUNC\n    SelfAdjointEigenSolver& compute(const EigenBase<InputType>& matrix, int options = ComputeEigenvectors);\n    \n    /** \\brief Computes eigendecomposition of given matrix using a closed-form algorithm\n      *\n      * This is a variant of compute(const MatrixType&, int options) which\n      * directly solves the underlying polynomial equation.\n      * \n      * Currently only 2x2 and 3x3 matrices for which the sizes are known at compile time are supported (e.g., Matrix3d).\n      * \n      * This method is usually significantly faster than the QR iterative algorithm\n      * but it might also be less accurate. It is also worth noting that\n      * for 3x3 matrices it involves trigonometric operations which are\n      * not necessarily available for all scalar types.\n      * \n      * For the 3x3 case, we observed the following worst case relative error regarding the eigenvalues:\n      *   - double: 1e-8\n      *   - float:  1e-3\n      *\n      * \\sa compute(const MatrixType&, int options)\n      */\n    EIGEN_DEVICE_FUNC\n    SelfAdjointEigenSolver& computeDirect(const MatrixType& matrix, int options = ComputeEigenvectors);\n\n    /**\n      *\\brief Computes the eigen decomposition from a tridiagonal symmetric matrix\n      *\n      * \\param[in] diag The vector containing the diagonal of the matrix.\n      * \\param[in] subdiag The subdiagonal of the matrix.\n      * \\param[in] options Can be #ComputeEigenvectors (default) or #EigenvaluesOnly.\n      * \\returns Reference to \\c *this\n      *\n      * This function assumes that the matrix has been reduced to tridiagonal form.\n      *\n      * \\sa compute(const MatrixType&, int) for more information\n      */\n    SelfAdjointEigenSolver& computeFromTridiagonal(const RealVectorType& diag, const SubDiagonalType& subdiag , int options=ComputeEigenvectors);\n\n    /** \\brief Returns the eigenvectors of given matrix.\n      *\n      * \\returns  A const reference to the matrix whose columns are the eigenvectors.\n      *\n      * \\pre The eigenvectors have been computed before.\n      *\n      * Column \\f$ k \\f$ of the returned matrix is an eigenvector corresponding\n      * to eigenvalue number \\f$ k \\f$ as returned by eigenvalues().  The\n      * eigenvectors are normalized to have (Euclidean) norm equal to one. If\n      * this object was used to solve the eigenproblem for the selfadjoint\n      * matrix \\f$ A \\f$, then the matrix returned by this function is the\n      * matrix \\f$ V \\f$ in the eigendecomposition \\f$ A = V D V^{-1} \\f$.\n      *\n      * For a selfadjoint matrix, \\f$ V \\f$ is unitary, meaning its inverse is equal\n      * to its adjoint, \\f$ V^{-1} = V^{\\dagger} \\f$. If \\f$ A \\f$ is real, then\n      * \\f$ V \\f$ is also real and therefore orthogonal, meaning its inverse is\n      * equal to its transpose, \\f$ V^{-1} = V^T \\f$.\n      *\n      * Example: \\include SelfAdjointEigenSolver_eigenvectors.cpp\n      * Output: \\verbinclude SelfAdjointEigenSolver_eigenvectors.out\n      *\n      * \\sa eigenvalues()\n      */\n    EIGEN_DEVICE_FUNC\n    const EigenvectorsType& eigenvectors() const\n    {\n      eigen_assert(m_isInitialized && \"SelfAdjointEigenSolver is not initialized.\");\n      eigen_assert(m_eigenvectorsOk && \"The eigenvectors have not been computed together with the eigenvalues.\");\n      return m_eivec;\n    }\n\n    /** \\brief Returns the eigenvalues of given matrix.\n      *\n      * \\returns A const reference to the column vector containing the eigenvalues.\n      *\n      * \\pre The eigenvalues have been computed before.\n      *\n      * The eigenvalues are repeated according to their algebraic multiplicity,\n      * so there are as many eigenvalues as rows in the matrix. The eigenvalues\n      * are sorted in increasing order.\n      *\n      * Example: \\include SelfAdjointEigenSolver_eigenvalues.cpp\n      * Output: \\verbinclude SelfAdjointEigenSolver_eigenvalues.out\n      *\n      * \\sa eigenvectors(), MatrixBase::eigenvalues()\n      */\n    EIGEN_DEVICE_FUNC\n    const RealVectorType& eigenvalues() const\n    {\n      eigen_assert(m_isInitialized && \"SelfAdjointEigenSolver is not initialized.\");\n      return m_eivalues;\n    }\n\n    /** \\brief Computes the positive-definite square root of the matrix.\n      *\n      * \\returns the positive-definite square root of the matrix\n      *\n      * \\pre The eigenvalues and eigenvectors of a positive-definite matrix\n      * have been computed before.\n      *\n      * The square root of a positive-definite matrix \\f$ A \\f$ is the\n      * positive-definite matrix whose square equals \\f$ A \\f$. This function\n      * uses the eigendecomposition \\f$ A = V D V^{-1} \\f$ to compute the\n      * square root as \\f$ A^{1/2} = V D^{1/2} V^{-1} \\f$.\n      *\n      * Example: \\include SelfAdjointEigenSolver_operatorSqrt.cpp\n      * Output: \\verbinclude SelfAdjointEigenSolver_operatorSqrt.out\n      *\n      * \\sa operatorInverseSqrt(), <a href=\"unsupported/group__MatrixFunctions__Module.html\">MatrixFunctions Module</a>\n      */\n    EIGEN_DEVICE_FUNC\n    MatrixType operatorSqrt() const\n    {\n      eigen_assert(m_isInitialized && \"SelfAdjointEigenSolver is not initialized.\");\n      eigen_assert(m_eigenvectorsOk && \"The eigenvectors have not been computed together with the eigenvalues.\");\n      return m_eivec * m_eivalues.cwiseSqrt().asDiagonal() * m_eivec.adjoint();\n    }\n\n    /** \\brief Computes the inverse square root of the matrix.\n      *\n      * \\returns the inverse positive-definite square root of the matrix\n      *\n      * \\pre The eigenvalues and eigenvectors of a positive-definite matrix\n      * have been computed before.\n      *\n      * This function uses the eigendecomposition \\f$ A = V D V^{-1} \\f$ to\n      * compute the inverse square root as \\f$ V D^{-1/2} V^{-1} \\f$. This is\n      * cheaper than first computing the square root with operatorSqrt() and\n      * then its inverse with MatrixBase::inverse().\n      *\n      * Example: \\include SelfAdjointEigenSolver_operatorInverseSqrt.cpp\n      * Output: \\verbinclude SelfAdjointEigenSolver_operatorInverseSqrt.out\n      *\n      * \\sa operatorSqrt(), MatrixBase::inverse(), <a href=\"unsupported/group__MatrixFunctions__Module.html\">MatrixFunctions Module</a>\n      */\n    EIGEN_DEVICE_FUNC\n    MatrixType operatorInverseSqrt() const\n    {\n      eigen_assert(m_isInitialized && \"SelfAdjointEigenSolver is not initialized.\");\n      eigen_assert(m_eigenvectorsOk && \"The eigenvectors have not been computed together with the eigenvalues.\");\n      return m_eivec * m_eivalues.cwiseInverse().cwiseSqrt().asDiagonal() * m_eivec.adjoint();\n    }\n\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful, \\c NoConvergence otherwise.\n      */\n    EIGEN_DEVICE_FUNC\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"SelfAdjointEigenSolver is not initialized.\");\n      return m_info;\n    }\n\n    /** \\brief Maximum number of iterations.\n      *\n      * The algorithm terminates if it does not converge within m_maxIterations * n iterations, where n\n      * denotes the size of the matrix. This value is currently set to 30 (copied from LAPACK).\n      */\n    static const int m_maxIterations = 30;\n\n  protected:\n    static EIGEN_DEVICE_FUNC\n    void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n    }\n    \n    EigenvectorsType m_eivec;\n    RealVectorType m_eivalues;\n    typename TridiagonalizationType::SubDiagonalType m_subdiag;\n    ComputationInfo m_info;\n    bool m_isInitialized;\n    bool m_eigenvectorsOk;\n};\n\nnamespace internal {\n/** \\internal\n  *\n  * \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  * Performs a QR step on a tridiagonal symmetric matrix represented as a\n  * pair of two vectors \\a diag and \\a subdiag.\n  *\n  * \\param diag the diagonal part of the input selfadjoint tridiagonal matrix\n  * \\param subdiag the sub-diagonal part of the input selfadjoint tridiagonal matrix\n  * \\param start starting index of the submatrix to work on\n  * \\param end last+1 index of the submatrix to work on\n  * \\param matrixQ pointer to the column-major matrix holding the eigenvectors, can be 0\n  * \\param n size of the input matrix\n  *\n  * For compilation efficiency reasons, this procedure does not use eigen expression\n  * for its arguments.\n  *\n  * Implemented from Golub's \"Matrix Computations\", algorithm 8.3.2:\n  * \"implicit symmetric QR step with Wilkinson shift\"\n  */\ntemplate<int StorageOrder,typename RealScalar, typename Scalar, typename Index>\nEIGEN_DEVICE_FUNC\nstatic void tridiagonal_qr_step(RealScalar* diag, RealScalar* subdiag, Index start, Index end, Scalar* matrixQ, Index n);\n}\n\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nEIGEN_DEVICE_FUNC\nSelfAdjointEigenSolver<MatrixType>& SelfAdjointEigenSolver<MatrixType>\n::compute(const EigenBase<InputType>& a_matrix, int options)\n{\n  check_template_parameters();\n  \n  const InputType &matrix(a_matrix.derived());\n  \n  EIGEN_USING_STD(abs);\n  eigen_assert(matrix.cols() == matrix.rows());\n  eigen_assert((options&~(EigVecMask|GenEigMask))==0\n          && (options&EigVecMask)!=EigVecMask\n          && \"invalid option parameter\");\n  bool computeEigenvectors = (options&ComputeEigenvectors)==ComputeEigenvectors;\n  Index n = matrix.cols();\n  m_eivalues.resize(n,1);\n\n  if(n==1)\n  {\n    m_eivec = matrix;\n    m_eivalues.coeffRef(0,0) = numext::real(m_eivec.coeff(0,0));\n    if(computeEigenvectors)\n      m_eivec.setOnes(n,n);\n    m_info = Success;\n    m_isInitialized = true;\n    m_eigenvectorsOk = computeEigenvectors;\n    return *this;\n  }\n\n  // declare some aliases\n  RealVectorType& diag = m_eivalues;\n  EigenvectorsType& mat = m_eivec;\n\n  // map the matrix coefficients to [-1:1] to avoid over- and underflow.\n  mat = matrix.template triangularView<Lower>();\n  RealScalar scale = mat.cwiseAbs().maxCoeff();\n  if(scale==RealScalar(0)) scale = RealScalar(1);\n  mat.template triangularView<Lower>() /= scale;\n  m_subdiag.resize(n-1);\n  internal::tridiagonalization_inplace(mat, diag, m_subdiag, computeEigenvectors);\n\n  m_info = internal::computeFromTridiagonal_impl(diag, m_subdiag, m_maxIterations, computeEigenvectors, m_eivec);\n  \n  // scale back the eigen values\n  m_eivalues *= scale;\n\n  m_isInitialized = true;\n  m_eigenvectorsOk = computeEigenvectors;\n  return *this;\n}\n\ntemplate<typename MatrixType>\nSelfAdjointEigenSolver<MatrixType>& SelfAdjointEigenSolver<MatrixType>\n::computeFromTridiagonal(const RealVectorType& diag, const SubDiagonalType& subdiag , int options)\n{\n  //TODO : Add an option to scale the values beforehand\n  bool computeEigenvectors = (options&ComputeEigenvectors)==ComputeEigenvectors;\n\n  m_eivalues = diag;\n  m_subdiag = subdiag;\n  if (computeEigenvectors)\n  {\n    m_eivec.setIdentity(diag.size(), diag.size());\n  }\n  m_info = internal::computeFromTridiagonal_impl(m_eivalues, m_subdiag, m_maxIterations, computeEigenvectors, m_eivec);\n\n  m_isInitialized = true;\n  m_eigenvectorsOk = computeEigenvectors;\n  return *this;\n}\n\nnamespace internal {\n/**\n  * \\internal\n  * \\brief Compute the eigendecomposition from a tridiagonal matrix\n  *\n  * \\param[in,out] diag : On input, the diagonal of the matrix, on output the eigenvalues\n  * \\param[in,out] subdiag : The subdiagonal part of the matrix (entries are modified during the decomposition)\n  * \\param[in] maxIterations : the maximum number of iterations\n  * \\param[in] computeEigenvectors : whether the eigenvectors have to be computed or not\n  * \\param[out] eivec : The matrix to store the eigenvectors if computeEigenvectors==true. Must be allocated on input.\n  * \\returns \\c Success or \\c NoConvergence\n  */\ntemplate<typename MatrixType, typename DiagType, typename SubDiagType>\nEIGEN_DEVICE_FUNC\nComputationInfo computeFromTridiagonal_impl(DiagType& diag, SubDiagType& subdiag, const Index maxIterations, bool computeEigenvectors, MatrixType& eivec)\n{\n  EIGEN_USING_STD(abs);\n\n  ComputationInfo info;\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index n = diag.size();\n  Index end = n-1;\n  Index start = 0;\n  Index iter = 0; // total number of iterations\n  \n  typedef typename DiagType::RealScalar RealScalar;\n  const RealScalar considerAsZero = (std::numeric_limits<RealScalar>::min)();\n  const RealScalar precision = RealScalar(2)*NumTraits<RealScalar>::epsilon();\n  \n  while (end>0)\n  {\n    for (Index i = start; i<end; ++i)\n      if (internal::isMuchSmallerThan(abs(subdiag[i]),(abs(diag[i])+abs(diag[i+1])),precision) || abs(subdiag[i]) <= considerAsZero)\n        subdiag[i] = 0;\n\n    // find the largest unreduced block\n    while (end>0 && subdiag[end-1]==RealScalar(0))\n    {\n      end--;\n    }\n    if (end<=0)\n      break;\n\n    // if we spent too many iterations, we give up\n    iter++;\n    if(iter > maxIterations * n) break;\n\n    start = end - 1;\n    while (start>0 && subdiag[start-1]!=0)\n      start--;\n\n    internal::tridiagonal_qr_step<MatrixType::Flags&RowMajorBit ? RowMajor : ColMajor>(diag.data(), subdiag.data(), start, end, computeEigenvectors ? eivec.data() : (Scalar*)0, n);\n  }\n  if (iter <= maxIterations * n)\n    info = Success;\n  else\n    info = NoConvergence;\n\n  // Sort eigenvalues and corresponding vectors.\n  // TODO make the sort optional ?\n  // TODO use a better sort algorithm !!\n  if (info == Success)\n  {\n    for (Index i = 0; i < n-1; ++i)\n    {\n      Index k;\n      diag.segment(i,n-i).minCoeff(&k);\n      if (k > 0)\n      {\n        numext::swap(diag[i], diag[k+i]);\n        if(computeEigenvectors)\n          eivec.col(i).swap(eivec.col(k+i));\n      }\n    }\n  }\n  return info;\n}\n  \ntemplate<typename SolverType,int Size,bool IsComplex> struct direct_selfadjoint_eigenvalues\n{\n  EIGEN_DEVICE_FUNC\n  static inline void run(SolverType& eig, const typename SolverType::MatrixType& A, int options)\n  { eig.compute(A,options); }\n};\n\ntemplate<typename SolverType> struct direct_selfadjoint_eigenvalues<SolverType,3,false>\n{\n  typedef typename SolverType::MatrixType MatrixType;\n  typedef typename SolverType::RealVectorType VectorType;\n  typedef typename SolverType::Scalar Scalar;\n  typedef typename SolverType::EigenvectorsType EigenvectorsType;\n  \n\n  /** \\internal\n   * Computes the roots of the characteristic polynomial of \\a m.\n   * For numerical stability m.trace() should be near zero and to avoid over- or underflow m should be normalized.\n   */\n  EIGEN_DEVICE_FUNC\n  static inline void computeRoots(const MatrixType& m, VectorType& roots)\n  {\n    EIGEN_USING_STD(sqrt)\n    EIGEN_USING_STD(atan2)\n    EIGEN_USING_STD(cos)\n    EIGEN_USING_STD(sin)\n    const Scalar s_inv3 = Scalar(1)/Scalar(3);\n    const Scalar s_sqrt3 = sqrt(Scalar(3));\n\n    // The characteristic equation is x^3 - c2*x^2 + c1*x - c0 = 0.  The\n    // eigenvalues are the roots to this equation, all guaranteed to be\n    // real-valued, because the matrix is symmetric.\n    Scalar c0 = m(0,0)*m(1,1)*m(2,2) + Scalar(2)*m(1,0)*m(2,0)*m(2,1) - m(0,0)*m(2,1)*m(2,1) - m(1,1)*m(2,0)*m(2,0) - m(2,2)*m(1,0)*m(1,0);\n    Scalar c1 = m(0,0)*m(1,1) - m(1,0)*m(1,0) + m(0,0)*m(2,2) - m(2,0)*m(2,0) + m(1,1)*m(2,2) - m(2,1)*m(2,1);\n    Scalar c2 = m(0,0) + m(1,1) + m(2,2);\n\n    // Construct the parameters used in classifying the roots of the equation\n    // and in solving the equation for the roots in closed form.\n    Scalar c2_over_3 = c2*s_inv3;\n    Scalar a_over_3 = (c2*c2_over_3 - c1)*s_inv3;\n    a_over_3 = numext::maxi(a_over_3, Scalar(0));\n\n    Scalar half_b = Scalar(0.5)*(c0 + c2_over_3*(Scalar(2)*c2_over_3*c2_over_3 - c1));\n\n    Scalar q = a_over_3*a_over_3*a_over_3 - half_b*half_b;\n    q = numext::maxi(q, Scalar(0));\n\n    // Compute the eigenvalues by solving for the roots of the polynomial.\n    Scalar rho = sqrt(a_over_3);\n    Scalar theta = atan2(sqrt(q),half_b)*s_inv3;  // since sqrt(q) > 0, atan2 is in [0, pi] and theta is in [0, pi/3]\n    Scalar cos_theta = cos(theta);\n    Scalar sin_theta = sin(theta);\n    // roots are already sorted, since cos is monotonically decreasing on [0, pi]\n    roots(0) = c2_over_3 - rho*(cos_theta + s_sqrt3*sin_theta); // == 2*rho*cos(theta+2pi/3)\n    roots(1) = c2_over_3 - rho*(cos_theta - s_sqrt3*sin_theta); // == 2*rho*cos(theta+ pi/3)\n    roots(2) = c2_over_3 + Scalar(2)*rho*cos_theta;\n  }\n\n  EIGEN_DEVICE_FUNC\n  static inline bool extract_kernel(MatrixType& mat, Ref<VectorType> res, Ref<VectorType> representative)\n  {\n    EIGEN_USING_STD(abs);\n    EIGEN_USING_STD(sqrt);\n    Index i0;\n    // Find non-zero column i0 (by construction, there must exist a non zero coefficient on the diagonal):\n    mat.diagonal().cwiseAbs().maxCoeff(&i0);\n    // mat.col(i0) is a good candidate for an orthogonal vector to the current eigenvector,\n    // so let's save it:\n    representative = mat.col(i0);\n    Scalar n0, n1;\n    VectorType c0, c1;\n    n0 = (c0 = representative.cross(mat.col((i0+1)%3))).squaredNorm();\n    n1 = (c1 = representative.cross(mat.col((i0+2)%3))).squaredNorm();\n    if(n0>n1) res = c0/sqrt(n0);\n    else      res = c1/sqrt(n1);\n\n    return true;\n  }\n\n  EIGEN_DEVICE_FUNC\n  static inline void run(SolverType& solver, const MatrixType& mat, int options)\n  {\n    eigen_assert(mat.cols() == 3 && mat.cols() == mat.rows());\n    eigen_assert((options&~(EigVecMask|GenEigMask))==0\n            && (options&EigVecMask)!=EigVecMask\n            && \"invalid option parameter\");\n    bool computeEigenvectors = (options&ComputeEigenvectors)==ComputeEigenvectors;\n    \n    EigenvectorsType& eivecs = solver.m_eivec;\n    VectorType& eivals = solver.m_eivalues;\n  \n    // Shift the matrix to the mean eigenvalue and map the matrix coefficients to [-1:1] to avoid over- and underflow.\n    Scalar shift = mat.trace() / Scalar(3);\n    // TODO Avoid this copy. Currently it is necessary to suppress bogus values when determining maxCoeff and for computing the eigenvectors later\n    MatrixType scaledMat = mat.template selfadjointView<Lower>();\n    scaledMat.diagonal().array() -= shift;\n    Scalar scale = scaledMat.cwiseAbs().maxCoeff();\n    if(scale > 0) scaledMat /= scale;   // TODO for scale==0 we could save the remaining operations\n\n    // compute the eigenvalues\n    computeRoots(scaledMat,eivals);\n\n    // compute the eigenvectors\n    if(computeEigenvectors)\n    {\n      if((eivals(2)-eivals(0))<=Eigen::NumTraits<Scalar>::epsilon())\n      {\n        // All three eigenvalues are numerically the same\n        eivecs.setIdentity();\n      }\n      else\n      {\n        MatrixType tmp;\n        tmp = scaledMat;\n\n        // Compute the eigenvector of the most distinct eigenvalue\n        Scalar d0 = eivals(2) - eivals(1);\n        Scalar d1 = eivals(1) - eivals(0);\n        Index k(0), l(2);\n        if(d0 > d1)\n        {\n          numext::swap(k,l);\n          d0 = d1;\n        }\n\n        // Compute the eigenvector of index k\n        {\n          tmp.diagonal().array () -= eivals(k);\n          // By construction, 'tmp' is of rank 2, and its kernel corresponds to the respective eigenvector.\n          extract_kernel(tmp, eivecs.col(k), eivecs.col(l));\n        }\n\n        // Compute eigenvector of index l\n        if(d0<=2*Eigen::NumTraits<Scalar>::epsilon()*d1)\n        {\n          // If d0 is too small, then the two other eigenvalues are numerically the same,\n          // and thus we only have to ortho-normalize the near orthogonal vector we saved above.\n          eivecs.col(l) -= eivecs.col(k).dot(eivecs.col(l))*eivecs.col(l);\n          eivecs.col(l).normalize();\n        }\n        else\n        {\n          tmp = scaledMat;\n          tmp.diagonal().array () -= eivals(l);\n\n          VectorType dummy;\n          extract_kernel(tmp, eivecs.col(l), dummy);\n        }\n\n        // Compute last eigenvector from the other two\n        eivecs.col(1) = eivecs.col(2).cross(eivecs.col(0)).normalized();\n      }\n    }\n\n    // Rescale back to the original size.\n    eivals *= scale;\n    eivals.array() += shift;\n    \n    solver.m_info = Success;\n    solver.m_isInitialized = true;\n    solver.m_eigenvectorsOk = computeEigenvectors;\n  }\n};\n\n// 2x2 direct eigenvalues decomposition, code from Hauke Heibel\ntemplate<typename SolverType> \nstruct direct_selfadjoint_eigenvalues<SolverType,2,false>\n{\n  typedef typename SolverType::MatrixType MatrixType;\n  typedef typename SolverType::RealVectorType VectorType;\n  typedef typename SolverType::Scalar Scalar;\n  typedef typename SolverType::EigenvectorsType EigenvectorsType;\n  \n  EIGEN_DEVICE_FUNC\n  static inline void computeRoots(const MatrixType& m, VectorType& roots)\n  {\n    EIGEN_USING_STD(sqrt);\n    const Scalar t0 = Scalar(0.5) * sqrt( numext::abs2(m(0,0)-m(1,1)) + Scalar(4)*numext::abs2(m(1,0)));\n    const Scalar t1 = Scalar(0.5) * (m(0,0) + m(1,1));\n    roots(0) = t1 - t0;\n    roots(1) = t1 + t0;\n  }\n  \n  EIGEN_DEVICE_FUNC\n  static inline void run(SolverType& solver, const MatrixType& mat, int options)\n  {\n    EIGEN_USING_STD(sqrt);\n    EIGEN_USING_STD(abs);\n    \n    eigen_assert(mat.cols() == 2 && mat.cols() == mat.rows());\n    eigen_assert((options&~(EigVecMask|GenEigMask))==0\n            && (options&EigVecMask)!=EigVecMask\n            && \"invalid option parameter\");\n    bool computeEigenvectors = (options&ComputeEigenvectors)==ComputeEigenvectors;\n    \n    EigenvectorsType& eivecs = solver.m_eivec;\n    VectorType& eivals = solver.m_eivalues;\n  \n    // Shift the matrix to the mean eigenvalue and map the matrix coefficients to [-1:1] to avoid over- and underflow.\n    Scalar shift = mat.trace() / Scalar(2);\n    MatrixType scaledMat = mat;\n    scaledMat.coeffRef(0,1) = mat.coeff(1,0);\n    scaledMat.diagonal().array() -= shift;\n    Scalar scale = scaledMat.cwiseAbs().maxCoeff();\n    if(scale > Scalar(0))\n      scaledMat /= scale;\n\n    // Compute the eigenvalues\n    computeRoots(scaledMat,eivals);\n\n    // compute the eigen vectors\n    if(computeEigenvectors)\n    {\n      if((eivals(1)-eivals(0))<=abs(eivals(1))*Eigen::NumTraits<Scalar>::epsilon())\n      {\n        eivecs.setIdentity();\n      }\n      else\n      {\n        scaledMat.diagonal().array () -= eivals(1);\n        Scalar a2 = numext::abs2(scaledMat(0,0));\n        Scalar c2 = numext::abs2(scaledMat(1,1));\n        Scalar b2 = numext::abs2(scaledMat(1,0));\n        if(a2>c2)\n        {\n          eivecs.col(1) << -scaledMat(1,0), scaledMat(0,0);\n          eivecs.col(1) /= sqrt(a2+b2);\n        }\n        else\n        {\n          eivecs.col(1) << -scaledMat(1,1), scaledMat(1,0);\n          eivecs.col(1) /= sqrt(c2+b2);\n        }\n\n        eivecs.col(0) << eivecs.col(1).unitOrthogonal();\n      }\n    }\n\n    // Rescale back to the original size.\n    eivals *= scale;\n    eivals.array() += shift;\n\n    solver.m_info = Success;\n    solver.m_isInitialized = true;\n    solver.m_eigenvectorsOk = computeEigenvectors;\n  }\n};\n\n}\n\ntemplate<typename MatrixType>\nEIGEN_DEVICE_FUNC\nSelfAdjointEigenSolver<MatrixType>& SelfAdjointEigenSolver<MatrixType>\n::computeDirect(const MatrixType& matrix, int options)\n{\n  internal::direct_selfadjoint_eigenvalues<SelfAdjointEigenSolver,Size,NumTraits<Scalar>::IsComplex>::run(*this,matrix,options);\n  return *this;\n}\n\nnamespace internal {\ntemplate<int StorageOrder,typename RealScalar, typename Scalar, typename Index>\nEIGEN_DEVICE_FUNC\nstatic void tridiagonal_qr_step(RealScalar* diag, RealScalar* subdiag, Index start, Index end, Scalar* matrixQ, Index n)\n{\n  EIGEN_USING_STD(abs);\n  RealScalar td = (diag[end-1] - diag[end])*RealScalar(0.5);\n  RealScalar e = subdiag[end-1];\n  // Note that thanks to scaling, e^2 or td^2 cannot overflow, however they can still\n  // underflow thus leading to inf/NaN values when using the following commented code:\n//   RealScalar e2 = numext::abs2(subdiag[end-1]);\n//   RealScalar mu = diag[end] - e2 / (td + (td>0 ? 1 : -1) * sqrt(td*td + e2));\n  // This explain the following, somewhat more complicated, version:\n  RealScalar mu = diag[end];\n  if(td==RealScalar(0))\n    mu -= abs(e);\n  else\n  {\n    RealScalar e2 = numext::abs2(subdiag[end-1]);\n    RealScalar h = numext::hypot(td,e);\n    if(e2==RealScalar(0)) mu -= (e / (td + (td>RealScalar(0) ? RealScalar(1) : RealScalar(-1)))) * (e / h);\n    else                  mu -= e2 / (td + (td>RealScalar(0) ? h : -h));\n  }\n  \n  RealScalar x = diag[start] - mu;\n  RealScalar z = subdiag[start];\n  for (Index k = start; k < end; ++k)\n  {\n    JacobiRotation<RealScalar> rot;\n    rot.makeGivens(x, z);\n\n    // do T = G' T G\n    RealScalar sdk = rot.s() * diag[k] + rot.c() * subdiag[k];\n    RealScalar dkp1 = rot.s() * subdiag[k] + rot.c() * diag[k+1];\n\n    diag[k] = rot.c() * (rot.c() * diag[k] - rot.s() * subdiag[k]) - rot.s() * (rot.c() * subdiag[k] - rot.s() * diag[k+1]);\n    diag[k+1] = rot.s() * sdk + rot.c() * dkp1;\n    subdiag[k] = rot.c() * sdk - rot.s() * dkp1;\n    \n\n    if (k > start)\n      subdiag[k - 1] = rot.c() * subdiag[k-1] - rot.s() * z;\n\n    x = subdiag[k];\n\n    if (k < end - 1)\n    {\n      z = -rot.s() * subdiag[k+1];\n      subdiag[k + 1] = rot.c() * subdiag[k+1];\n    }\n    \n    // apply the givens rotation to the unit matrix Q = Q * G\n    if (matrixQ)\n    {\n      // FIXME if StorageOrder == RowMajor this operation is not very efficient\n      Map<Matrix<Scalar,Dynamic,Dynamic,StorageOrder> > q(matrixQ,n,n);\n      q.applyOnTheRight(k,k+1,rot);\n    }\n  }\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SELFADJOINTEIGENSOLVER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Eigenvalues/SelfAdjointEigenSolver_LAPACKE.h",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Eigen bindings to LAPACKe\n *    Self-adjoint eigenvalues/eigenvectors.\n ********************************************************************************\n*/\n\n#ifndef EIGEN_SAEIGENSOLVER_LAPACKE_H\n#define EIGEN_SAEIGENSOLVER_LAPACKE_H\n\nnamespace Eigen { \n\n/** \\internal Specialization for the data types supported by LAPACKe */\n\n#define EIGEN_LAPACKE_EIG_SELFADJ_2(EIGTYPE, LAPACKE_TYPE, LAPACKE_RTYPE, LAPACKE_NAME, EIGCOLROW ) \\\ntemplate<> template<typename InputType> inline \\\nSelfAdjointEigenSolver<Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW> >& \\\nSelfAdjointEigenSolver<Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW> >::compute(const EigenBase<InputType>& matrix, int options) \\\n{ \\\n  eigen_assert(matrix.cols() == matrix.rows()); \\\n  eigen_assert((options&~(EigVecMask|GenEigMask))==0 \\\n          && (options&EigVecMask)!=EigVecMask \\\n          && \"invalid option parameter\"); \\\n  bool computeEigenvectors = (options&ComputeEigenvectors)==ComputeEigenvectors; \\\n  lapack_int n = internal::convert_index<lapack_int>(matrix.cols()), lda, info; \\\n  m_eivalues.resize(n,1); \\\n  m_subdiag.resize(n-1); \\\n  m_eivec = matrix; \\\n\\\n  if(n==1) \\\n  { \\\n    m_eivalues.coeffRef(0,0) = numext::real(m_eivec.coeff(0,0)); \\\n    if(computeEigenvectors) m_eivec.setOnes(n,n); \\\n    m_info = Success; \\\n    m_isInitialized = true; \\\n    m_eigenvectorsOk = computeEigenvectors; \\\n    return *this; \\\n  } \\\n\\\n  lda = internal::convert_index<lapack_int>(m_eivec.outerStride()); \\\n  char jobz, uplo='L'/*, range='A'*/; \\\n  jobz = computeEigenvectors ? 'V' : 'N'; \\\n\\\n  info = LAPACKE_##LAPACKE_NAME( LAPACK_COL_MAJOR, jobz, uplo, n, (LAPACKE_TYPE*)m_eivec.data(), lda, (LAPACKE_RTYPE*)m_eivalues.data() ); \\\n  m_info = (info==0) ? Success : NoConvergence; \\\n  m_isInitialized = true; \\\n  m_eigenvectorsOk = computeEigenvectors; \\\n  return *this; \\\n}\n\n#define EIGEN_LAPACKE_EIG_SELFADJ(EIGTYPE, LAPACKE_TYPE, LAPACKE_RTYPE, LAPACKE_NAME )              \\\n        EIGEN_LAPACKE_EIG_SELFADJ_2(EIGTYPE, LAPACKE_TYPE, LAPACKE_RTYPE, LAPACKE_NAME, ColMajor )  \\\n        EIGEN_LAPACKE_EIG_SELFADJ_2(EIGTYPE, LAPACKE_TYPE, LAPACKE_RTYPE, LAPACKE_NAME, RowMajor ) \n\nEIGEN_LAPACKE_EIG_SELFADJ(double,   double,                double, dsyev)\nEIGEN_LAPACKE_EIG_SELFADJ(float,    float,                 float,  ssyev)\nEIGEN_LAPACKE_EIG_SELFADJ(dcomplex, lapack_complex_double, double, zheev)\nEIGEN_LAPACKE_EIG_SELFADJ(scomplex, lapack_complex_float,  float,  cheev)\n\n} // end namespace Eigen\n\n#endif // EIGEN_SAEIGENSOLVER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Eigenvalues/Tridiagonalization.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_TRIDIAGONALIZATION_H\n#define EIGEN_TRIDIAGONALIZATION_H\n\nnamespace Eigen { \n\nnamespace internal {\n  \ntemplate<typename MatrixType> struct TridiagonalizationMatrixTReturnType;\ntemplate<typename MatrixType>\nstruct traits<TridiagonalizationMatrixTReturnType<MatrixType> >\n  : public traits<typename MatrixType::PlainObject>\n{\n  typedef typename MatrixType::PlainObject ReturnType; // FIXME shall it be a BandMatrix?\n  enum { Flags = 0 };\n};\n\ntemplate<typename MatrixType, typename CoeffVectorType>\nEIGEN_DEVICE_FUNC\nvoid tridiagonalization_inplace(MatrixType& matA, CoeffVectorType& hCoeffs);\n}\n\n/** \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  *\n  * \\class Tridiagonalization\n  *\n  * \\brief Tridiagonal decomposition of a selfadjoint matrix\n  *\n  * \\tparam _MatrixType the type of the matrix of which we are computing the\n  * tridiagonal decomposition; this is expected to be an instantiation of the\n  * Matrix class template.\n  *\n  * This class performs a tridiagonal decomposition of a selfadjoint matrix \\f$ A \\f$ such that:\n  * \\f$ A = Q T Q^* \\f$ where \\f$ Q \\f$ is unitary and \\f$ T \\f$ a real symmetric tridiagonal matrix.\n  *\n  * A tridiagonal matrix is a matrix which has nonzero elements only on the\n  * main diagonal and the first diagonal below and above it. The Hessenberg\n  * decomposition of a selfadjoint matrix is in fact a tridiagonal\n  * decomposition. This class is used in SelfAdjointEigenSolver to compute the\n  * eigenvalues and eigenvectors of a selfadjoint matrix.\n  *\n  * Call the function compute() to compute the tridiagonal decomposition of a\n  * given matrix. Alternatively, you can use the Tridiagonalization(const MatrixType&)\n  * constructor which computes the tridiagonal Schur decomposition at\n  * construction time. Once the decomposition is computed, you can use the\n  * matrixQ() and matrixT() functions to retrieve the matrices Q and T in the\n  * decomposition.\n  *\n  * The documentation of Tridiagonalization(const MatrixType&) contains an\n  * example of the typical use of this class.\n  *\n  * \\sa class HessenbergDecomposition, class SelfAdjointEigenSolver\n  */\ntemplate<typename _MatrixType> class Tridiagonalization\n{\n  public:\n\n    /** \\brief Synonym for the template parameter \\p _MatrixType. */\n    typedef _MatrixType MatrixType;\n\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n\n    enum {\n      Size = MatrixType::RowsAtCompileTime,\n      SizeMinusOne = Size == Dynamic ? Dynamic : (Size > 1 ? Size - 1 : 1),\n      Options = MatrixType::Options,\n      MaxSize = MatrixType::MaxRowsAtCompileTime,\n      MaxSizeMinusOne = MaxSize == Dynamic ? Dynamic : (MaxSize > 1 ? MaxSize - 1 : 1)\n    };\n\n    typedef Matrix<Scalar, SizeMinusOne, 1, Options & ~RowMajor, MaxSizeMinusOne, 1> CoeffVectorType;\n    typedef typename internal::plain_col_type<MatrixType, RealScalar>::type DiagonalType;\n    typedef Matrix<RealScalar, SizeMinusOne, 1, Options & ~RowMajor, MaxSizeMinusOne, 1> SubDiagonalType;\n    typedef typename internal::remove_all<typename MatrixType::RealReturnType>::type MatrixTypeRealView;\n    typedef internal::TridiagonalizationMatrixTReturnType<MatrixTypeRealView> MatrixTReturnType;\n\n    typedef typename internal::conditional<NumTraits<Scalar>::IsComplex,\n              typename internal::add_const_on_value_type<typename Diagonal<const MatrixType>::RealReturnType>::type,\n              const Diagonal<const MatrixType>\n            >::type DiagonalReturnType;\n\n    typedef typename internal::conditional<NumTraits<Scalar>::IsComplex,\n              typename internal::add_const_on_value_type<typename Diagonal<const MatrixType, -1>::RealReturnType>::type,\n              const Diagonal<const MatrixType, -1>\n            >::type SubDiagonalReturnType;\n\n    /** \\brief Return type of matrixQ() */\n    typedef HouseholderSequence<MatrixType,typename internal::remove_all<typename CoeffVectorType::ConjugateReturnType>::type> HouseholderSequenceType;\n\n    /** \\brief Default constructor.\n      *\n      * \\param [in]  size  Positive integer, size of the matrix whose tridiagonal\n      * decomposition will be computed.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via compute().  The \\p size parameter is only\n      * used as a hint. It is not an error to give a wrong \\p size, but it may\n      * impair performance.\n      *\n      * \\sa compute() for an example.\n      */\n    explicit Tridiagonalization(Index size = Size==Dynamic ? 2 : Size)\n      : m_matrix(size,size),\n        m_hCoeffs(size > 1 ? size-1 : 1),\n        m_isInitialized(false)\n    {}\n\n    /** \\brief Constructor; computes tridiagonal decomposition of given matrix.\n      *\n      * \\param[in]  matrix  Selfadjoint matrix whose tridiagonal decomposition\n      * is to be computed.\n      *\n      * This constructor calls compute() to compute the tridiagonal decomposition.\n      *\n      * Example: \\include Tridiagonalization_Tridiagonalization_MatrixType.cpp\n      * Output: \\verbinclude Tridiagonalization_Tridiagonalization_MatrixType.out\n      */\n    template<typename InputType>\n    explicit Tridiagonalization(const EigenBase<InputType>& matrix)\n      : m_matrix(matrix.derived()),\n        m_hCoeffs(matrix.cols() > 1 ? matrix.cols()-1 : 1),\n        m_isInitialized(false)\n    {\n      internal::tridiagonalization_inplace(m_matrix, m_hCoeffs);\n      m_isInitialized = true;\n    }\n\n    /** \\brief Computes tridiagonal decomposition of given matrix.\n      *\n      * \\param[in]  matrix  Selfadjoint matrix whose tridiagonal decomposition\n      * is to be computed.\n      * \\returns    Reference to \\c *this\n      *\n      * The tridiagonal decomposition is computed by bringing the columns of\n      * the matrix successively in the required form using Householder\n      * reflections. The cost is \\f$ 4n^3/3 \\f$ flops, where \\f$ n \\f$ denotes\n      * the size of the given matrix.\n      *\n      * This method reuses of the allocated data in the Tridiagonalization\n      * object, if the size of the matrix does not change.\n      *\n      * Example: \\include Tridiagonalization_compute.cpp\n      * Output: \\verbinclude Tridiagonalization_compute.out\n      */\n    template<typename InputType>\n    Tridiagonalization& compute(const EigenBase<InputType>& matrix)\n    {\n      m_matrix = matrix.derived();\n      m_hCoeffs.resize(matrix.rows()-1, 1);\n      internal::tridiagonalization_inplace(m_matrix, m_hCoeffs);\n      m_isInitialized = true;\n      return *this;\n    }\n\n    /** \\brief Returns the Householder coefficients.\n      *\n      * \\returns a const reference to the vector of Householder coefficients\n      *\n      * \\pre Either the constructor Tridiagonalization(const MatrixType&) or\n      * the member function compute(const MatrixType&) has been called before\n      * to compute the tridiagonal decomposition of a matrix.\n      *\n      * The Householder coefficients allow the reconstruction of the matrix\n      * \\f$ Q \\f$ in the tridiagonal decomposition from the packed data.\n      *\n      * Example: \\include Tridiagonalization_householderCoefficients.cpp\n      * Output: \\verbinclude Tridiagonalization_householderCoefficients.out\n      *\n      * \\sa packedMatrix(), \\ref Householder_Module \"Householder module\"\n      */\n    inline CoeffVectorType householderCoefficients() const\n    {\n      eigen_assert(m_isInitialized && \"Tridiagonalization is not initialized.\");\n      return m_hCoeffs;\n    }\n\n    /** \\brief Returns the internal representation of the decomposition\n      *\n      *\t\\returns a const reference to a matrix with the internal representation\n      *\t         of the decomposition.\n      *\n      * \\pre Either the constructor Tridiagonalization(const MatrixType&) or\n      * the member function compute(const MatrixType&) has been called before\n      * to compute the tridiagonal decomposition of a matrix.\n      *\n      * The returned matrix contains the following information:\n      *  - the strict upper triangular part is equal to the input matrix A.\n      *  - the diagonal and lower sub-diagonal represent the real tridiagonal\n      *    symmetric matrix T.\n      *  - the rest of the lower part contains the Householder vectors that,\n      *    combined with Householder coefficients returned by\n      *    householderCoefficients(), allows to reconstruct the matrix Q as\n      *       \\f$ Q = H_{N-1} \\ldots H_1 H_0 \\f$.\n      *    Here, the matrices \\f$ H_i \\f$ are the Householder transformations\n      *       \\f$ H_i = (I - h_i v_i v_i^T) \\f$\n      *    where \\f$ h_i \\f$ is the \\f$ i \\f$th Householder coefficient and\n      *    \\f$ v_i \\f$ is the Householder vector defined by\n      *       \\f$ v_i = [ 0, \\ldots, 0, 1, M(i+2,i), \\ldots, M(N-1,i) ]^T \\f$\n      *    with M the matrix returned by this function.\n      *\n      * See LAPACK for further details on this packed storage.\n      *\n      * Example: \\include Tridiagonalization_packedMatrix.cpp\n      * Output: \\verbinclude Tridiagonalization_packedMatrix.out\n      *\n      * \\sa householderCoefficients()\n      */\n    inline const MatrixType& packedMatrix() const\n    {\n      eigen_assert(m_isInitialized && \"Tridiagonalization is not initialized.\");\n      return m_matrix;\n    }\n\n    /** \\brief Returns the unitary matrix Q in the decomposition\n      *\n      * \\returns object representing the matrix Q\n      *\n      * \\pre Either the constructor Tridiagonalization(const MatrixType&) or\n      * the member function compute(const MatrixType&) has been called before\n      * to compute the tridiagonal decomposition of a matrix.\n      *\n      * This function returns a light-weight object of template class\n      * HouseholderSequence. You can either apply it directly to a matrix or\n      * you can convert it to a matrix of type #MatrixType.\n      *\n      * \\sa Tridiagonalization(const MatrixType&) for an example,\n      *     matrixT(), class HouseholderSequence\n      */\n    HouseholderSequenceType matrixQ() const\n    {\n      eigen_assert(m_isInitialized && \"Tridiagonalization is not initialized.\");\n      return HouseholderSequenceType(m_matrix, m_hCoeffs.conjugate())\n             .setLength(m_matrix.rows() - 1)\n             .setShift(1);\n    }\n\n    /** \\brief Returns an expression of the tridiagonal matrix T in the decomposition\n      *\n      * \\returns expression object representing the matrix T\n      *\n      * \\pre Either the constructor Tridiagonalization(const MatrixType&) or\n      * the member function compute(const MatrixType&) has been called before\n      * to compute the tridiagonal decomposition of a matrix.\n      *\n      * Currently, this function can be used to extract the matrix T from internal\n      * data and copy it to a dense matrix object. In most cases, it may be\n      * sufficient to directly use the packed matrix or the vector expressions\n      * returned by diagonal() and subDiagonal() instead of creating a new\n      * dense copy matrix with this function.\n      *\n      * \\sa Tridiagonalization(const MatrixType&) for an example,\n      * matrixQ(), packedMatrix(), diagonal(), subDiagonal()\n      */\n    MatrixTReturnType matrixT() const\n    {\n      eigen_assert(m_isInitialized && \"Tridiagonalization is not initialized.\");\n      return MatrixTReturnType(m_matrix.real());\n    }\n\n    /** \\brief Returns the diagonal of the tridiagonal matrix T in the decomposition.\n      *\n      * \\returns expression representing the diagonal of T\n      *\n      * \\pre Either the constructor Tridiagonalization(const MatrixType&) or\n      * the member function compute(const MatrixType&) has been called before\n      * to compute the tridiagonal decomposition of a matrix.\n      *\n      * Example: \\include Tridiagonalization_diagonal.cpp\n      * Output: \\verbinclude Tridiagonalization_diagonal.out\n      *\n      * \\sa matrixT(), subDiagonal()\n      */\n    DiagonalReturnType diagonal() const;\n\n    /** \\brief Returns the subdiagonal of the tridiagonal matrix T in the decomposition.\n      *\n      * \\returns expression representing the subdiagonal of T\n      *\n      * \\pre Either the constructor Tridiagonalization(const MatrixType&) or\n      * the member function compute(const MatrixType&) has been called before\n      * to compute the tridiagonal decomposition of a matrix.\n      *\n      * \\sa diagonal() for an example, matrixT()\n      */\n    SubDiagonalReturnType subDiagonal() const;\n\n  protected:\n\n    MatrixType m_matrix;\n    CoeffVectorType m_hCoeffs;\n    bool m_isInitialized;\n};\n\ntemplate<typename MatrixType>\ntypename Tridiagonalization<MatrixType>::DiagonalReturnType\nTridiagonalization<MatrixType>::diagonal() const\n{\n  eigen_assert(m_isInitialized && \"Tridiagonalization is not initialized.\");\n  return m_matrix.diagonal().real();\n}\n\ntemplate<typename MatrixType>\ntypename Tridiagonalization<MatrixType>::SubDiagonalReturnType\nTridiagonalization<MatrixType>::subDiagonal() const\n{\n  eigen_assert(m_isInitialized && \"Tridiagonalization is not initialized.\");\n  return m_matrix.template diagonal<-1>().real();\n}\n\nnamespace internal {\n\n/** \\internal\n  * Performs a tridiagonal decomposition of the selfadjoint matrix \\a matA in-place.\n  *\n  * \\param[in,out] matA On input the selfadjoint matrix. Only the \\b lower triangular part is referenced.\n  *                     On output, the strict upper part is left unchanged, and the lower triangular part\n  *                     represents the T and Q matrices in packed format has detailed below.\n  * \\param[out]    hCoeffs returned Householder coefficients (see below)\n  *\n  * On output, the tridiagonal selfadjoint matrix T is stored in the diagonal\n  * and lower sub-diagonal of the matrix \\a matA.\n  * The unitary matrix Q is represented in a compact way as a product of\n  * Householder reflectors \\f$ H_i \\f$ such that:\n  *       \\f$ Q = H_{N-1} \\ldots H_1 H_0 \\f$.\n  * The Householder reflectors are defined as\n  *       \\f$ H_i = (I - h_i v_i v_i^T) \\f$\n  * where \\f$ h_i = hCoeffs[i]\\f$ is the \\f$ i \\f$th Householder coefficient and\n  * \\f$ v_i \\f$ is the Householder vector defined by\n  *       \\f$ v_i = [ 0, \\ldots, 0, 1, matA(i+2,i), \\ldots, matA(N-1,i) ]^T \\f$.\n  *\n  * Implemented from Golub's \"Matrix Computations\", algorithm 8.3.1.\n  *\n  * \\sa Tridiagonalization::packedMatrix()\n  */\ntemplate<typename MatrixType, typename CoeffVectorType>\nEIGEN_DEVICE_FUNC\nvoid tridiagonalization_inplace(MatrixType& matA, CoeffVectorType& hCoeffs)\n{\n  using numext::conj;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  Index n = matA.rows();\n  eigen_assert(n==matA.cols());\n  eigen_assert(n==hCoeffs.size()+1 || n==1);\n  \n  for (Index i = 0; i<n-1; ++i)\n  {\n    Index remainingSize = n-i-1;\n    RealScalar beta;\n    Scalar h;\n    matA.col(i).tail(remainingSize).makeHouseholderInPlace(h, beta);\n\n    // Apply similarity transformation to remaining columns,\n    // i.e., A = H A H' where H = I - h v v' and v = matA.col(i).tail(n-i-1)\n    matA.col(i).coeffRef(i+1) = 1;\n\n    hCoeffs.tail(n-i-1).noalias() = (matA.bottomRightCorner(remainingSize,remainingSize).template selfadjointView<Lower>()\n                                  * (conj(h) * matA.col(i).tail(remainingSize)));\n\n    hCoeffs.tail(n-i-1) += (conj(h)*RealScalar(-0.5)*(hCoeffs.tail(remainingSize).dot(matA.col(i).tail(remainingSize)))) * matA.col(i).tail(n-i-1);\n\n    matA.bottomRightCorner(remainingSize, remainingSize).template selfadjointView<Lower>()\n      .rankUpdate(matA.col(i).tail(remainingSize), hCoeffs.tail(remainingSize), Scalar(-1));\n\n    matA.col(i).coeffRef(i+1) = beta;\n    hCoeffs.coeffRef(i) = h;\n  }\n}\n\n// forward declaration, implementation at the end of this file\ntemplate<typename MatrixType,\n         int Size=MatrixType::ColsAtCompileTime,\n         bool IsComplex=NumTraits<typename MatrixType::Scalar>::IsComplex>\nstruct tridiagonalization_inplace_selector;\n\n/** \\brief Performs a full tridiagonalization in place\n  *\n  * \\param[in,out]  mat  On input, the selfadjoint matrix whose tridiagonal\n  *    decomposition is to be computed. Only the lower triangular part referenced.\n  *    The rest is left unchanged. On output, the orthogonal matrix Q\n  *    in the decomposition if \\p extractQ is true.\n  * \\param[out]  diag  The diagonal of the tridiagonal matrix T in the\n  *    decomposition.\n  * \\param[out]  subdiag  The subdiagonal of the tridiagonal matrix T in\n  *    the decomposition.\n  * \\param[in]  extractQ  If true, the orthogonal matrix Q in the\n  *    decomposition is computed and stored in \\p mat.\n  *\n  * Computes the tridiagonal decomposition of the selfadjoint matrix \\p mat in place\n  * such that \\f$ mat = Q T Q^* \\f$ where \\f$ Q \\f$ is unitary and \\f$ T \\f$ a real\n  * symmetric tridiagonal matrix.\n  *\n  * The tridiagonal matrix T is passed to the output parameters \\p diag and \\p subdiag. If\n  * \\p extractQ is true, then the orthogonal matrix Q is passed to \\p mat. Otherwise the lower\n  * part of the matrix \\p mat is destroyed.\n  *\n  * The vectors \\p diag and \\p subdiag are not resized. The function\n  * assumes that they are already of the correct size. The length of the\n  * vector \\p diag should equal the number of rows in \\p mat, and the\n  * length of the vector \\p subdiag should be one left.\n  *\n  * This implementation contains an optimized path for 3-by-3 matrices\n  * which is especially useful for plane fitting.\n  *\n  * \\note Currently, it requires two temporary vectors to hold the intermediate\n  * Householder coefficients, and to reconstruct the matrix Q from the Householder\n  * reflectors.\n  *\n  * Example (this uses the same matrix as the example in\n  *    Tridiagonalization::Tridiagonalization(const MatrixType&)):\n  *    \\include Tridiagonalization_decomposeInPlace.cpp\n  * Output: \\verbinclude Tridiagonalization_decomposeInPlace.out\n  *\n  * \\sa class Tridiagonalization\n  */\ntemplate<typename MatrixType, typename DiagonalType, typename SubDiagonalType>\nEIGEN_DEVICE_FUNC\nvoid tridiagonalization_inplace(MatrixType& mat, DiagonalType& diag, SubDiagonalType& subdiag, bool extractQ)\n{\n  eigen_assert(mat.cols()==mat.rows() && diag.size()==mat.rows() && subdiag.size()==mat.rows()-1);\n  tridiagonalization_inplace_selector<MatrixType>::run(mat, diag, subdiag, extractQ);\n}\n\n/** \\internal\n  * General full tridiagonalization\n  */\ntemplate<typename MatrixType, int Size, bool IsComplex>\nstruct tridiagonalization_inplace_selector\n{\n  typedef typename Tridiagonalization<MatrixType>::CoeffVectorType CoeffVectorType;\n  typedef typename Tridiagonalization<MatrixType>::HouseholderSequenceType HouseholderSequenceType;\n  template<typename DiagonalType, typename SubDiagonalType>\n  static EIGEN_DEVICE_FUNC\n  void run(MatrixType& mat, DiagonalType& diag, SubDiagonalType& subdiag, bool extractQ)\n  {\n    CoeffVectorType hCoeffs(mat.cols()-1);\n    tridiagonalization_inplace(mat,hCoeffs);\n    diag = mat.diagonal().real();\n    subdiag = mat.template diagonal<-1>().real();\n    if(extractQ)\n      mat = HouseholderSequenceType(mat, hCoeffs.conjugate())\n            .setLength(mat.rows() - 1)\n            .setShift(1);\n  }\n};\n\n/** \\internal\n  * Specialization for 3x3 real matrices.\n  * Especially useful for plane fitting.\n  */\ntemplate<typename MatrixType>\nstruct tridiagonalization_inplace_selector<MatrixType,3,false>\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n\n  template<typename DiagonalType, typename SubDiagonalType>\n  static void run(MatrixType& mat, DiagonalType& diag, SubDiagonalType& subdiag, bool extractQ)\n  {\n    using std::sqrt;\n    const RealScalar tol = (std::numeric_limits<RealScalar>::min)();\n    diag[0] = mat(0,0);\n    RealScalar v1norm2 = numext::abs2(mat(2,0));\n    if(v1norm2 <= tol)\n    {\n      diag[1] = mat(1,1);\n      diag[2] = mat(2,2);\n      subdiag[0] = mat(1,0);\n      subdiag[1] = mat(2,1);\n      if (extractQ)\n        mat.setIdentity();\n    }\n    else\n    {\n      RealScalar beta = sqrt(numext::abs2(mat(1,0)) + v1norm2);\n      RealScalar invBeta = RealScalar(1)/beta;\n      Scalar m01 = mat(1,0) * invBeta;\n      Scalar m02 = mat(2,0) * invBeta;\n      Scalar q = RealScalar(2)*m01*mat(2,1) + m02*(mat(2,2) - mat(1,1));\n      diag[1] = mat(1,1) + m02*q;\n      diag[2] = mat(2,2) - m02*q;\n      subdiag[0] = beta;\n      subdiag[1] = mat(2,1) - m01 * q;\n      if (extractQ)\n      {\n        mat << 1,   0,    0,\n               0, m01,  m02,\n               0, m02, -m01;\n      }\n    }\n  }\n};\n\n/** \\internal\n  * Trivial specialization for 1x1 matrices\n  */\ntemplate<typename MatrixType, bool IsComplex>\nstruct tridiagonalization_inplace_selector<MatrixType,1,IsComplex>\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  template<typename DiagonalType, typename SubDiagonalType>\n  static EIGEN_DEVICE_FUNC\n  void run(MatrixType& mat, DiagonalType& diag, SubDiagonalType&, bool extractQ)\n  {\n    diag(0,0) = numext::real(mat(0,0));\n    if(extractQ)\n      mat(0,0) = Scalar(1);\n  }\n};\n\n/** \\internal\n  * \\eigenvalues_module \\ingroup Eigenvalues_Module\n  *\n  * \\brief Expression type for return value of Tridiagonalization::matrixT()\n  *\n  * \\tparam MatrixType type of underlying dense matrix\n  */\ntemplate<typename MatrixType> struct TridiagonalizationMatrixTReturnType\n: public ReturnByValue<TridiagonalizationMatrixTReturnType<MatrixType> >\n{\n  public:\n    /** \\brief Constructor.\n      *\n      * \\param[in] mat The underlying dense matrix\n      */\n    TridiagonalizationMatrixTReturnType(const MatrixType& mat) : m_matrix(mat) { }\n\n    template <typename ResultType>\n    inline void evalTo(ResultType& result) const\n    {\n      result.setZero();\n      result.template diagonal<1>() = m_matrix.template diagonal<-1>().conjugate();\n      result.diagonal() = m_matrix.diagonal();\n      result.template diagonal<-1>() = m_matrix.template diagonal<-1>();\n    }\n\n    Index rows() const { return m_matrix.rows(); }\n    Index cols() const { return m_matrix.cols(); }\n\n  protected:\n    typename MatrixType::Nested m_matrix;\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_TRIDIAGONALIZATION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Geometry/AlignedBox.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// Function void Eigen::AlignedBox::transform(const Transform& transform)\n// is provided under the following license agreement:\n//\n// Software License Agreement (BSD License)\n//\n// Copyright (c) 2011-2014, Willow Garage, Inc.\n// Copyright (c) 2014-2015, Open Source Robotics Foundation\n// All rights reserved.\n//\n// Redistribution and use in source and binary forms, with or without\n// modification, are permitted provided that the following conditions\n// are met:\n//\n//  * Redistributions of source code must retain the above copyright\n//    notice, this list of conditions and the following disclaimer.\n//  * Redistributions in binary form must reproduce the above\n//    copyright notice, this list of conditions and the following\n//    disclaimer in the documentation and/or other materials provided\n//    with the distribution.\n//  * Neither the name of Open Source Robotics Foundation nor the names of its\n//    contributors may be used to endorse or promote products derived\n//    from this software without specific prior written permission.\n//\n// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n// \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n// FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n// COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n// INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n// BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n// LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n// CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n// LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n// ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n// POSSIBILITY OF SUCH DAMAGE.\n\n#ifndef EIGEN_ALIGNEDBOX_H\n#define EIGEN_ALIGNEDBOX_H\n\nnamespace Eigen {\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  *\n  * \\class AlignedBox\n  *\n  * \\brief An axis aligned box\n  *\n  * \\tparam _Scalar the type of the scalar coefficients\n  * \\tparam _AmbientDim the dimension of the ambient space, can be a compile time value or Dynamic.\n  *\n  * This class represents an axis aligned box as a pair of the minimal and maximal corners.\n  * \\warning The result of most methods is undefined when applied to an empty box. You can check for empty boxes using isEmpty().\n  * \\sa alignedboxtypedefs\n  */\ntemplate <typename _Scalar, int _AmbientDim>\nclass AlignedBox\n{\npublic:\nEIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_AmbientDim)\n  enum { AmbientDimAtCompileTime = _AmbientDim };\n  typedef _Scalar                                   Scalar;\n  typedef NumTraits<Scalar>                         ScalarTraits;\n  typedef Eigen::Index                              Index; ///< \\deprecated since Eigen 3.3\n  typedef typename ScalarTraits::Real               RealScalar;\n  typedef typename ScalarTraits::NonInteger         NonInteger;\n  typedef Matrix<Scalar,AmbientDimAtCompileTime,1>  VectorType;\n  typedef CwiseBinaryOp<internal::scalar_sum_op<Scalar>, const VectorType, const VectorType> VectorTypeSum;\n\n  /** Define constants to name the corners of a 1D, 2D or 3D axis aligned bounding box */\n  enum CornerType\n  {\n    /** 1D names @{ */\n    Min=0, Max=1,\n    /** @} */\n\n    /** Identifier for 2D corner @{ */\n    BottomLeft=0, BottomRight=1,\n    TopLeft=2, TopRight=3,\n    /** @} */\n\n    /** Identifier for 3D corner  @{ */\n    BottomLeftFloor=0, BottomRightFloor=1,\n    TopLeftFloor=2, TopRightFloor=3,\n    BottomLeftCeil=4, BottomRightCeil=5,\n    TopLeftCeil=6, TopRightCeil=7\n    /** @} */\n  };\n\n\n  /** Default constructor initializing a null box. */\n  EIGEN_DEVICE_FUNC inline AlignedBox()\n  { if (EIGEN_CONST_CONDITIONAL(AmbientDimAtCompileTime!=Dynamic)) setEmpty(); }\n\n  /** Constructs a null box with \\a _dim the dimension of the ambient space. */\n  EIGEN_DEVICE_FUNC inline explicit AlignedBox(Index _dim) : m_min(_dim), m_max(_dim)\n  { setEmpty(); }\n\n  /** Constructs a box with extremities \\a _min and \\a _max.\n   * \\warning If either component of \\a _min is larger than the same component of \\a _max, the constructed box is empty. */\n  template<typename OtherVectorType1, typename OtherVectorType2>\n  EIGEN_DEVICE_FUNC inline AlignedBox(const OtherVectorType1& _min, const OtherVectorType2& _max) : m_min(_min), m_max(_max) {}\n\n  /** Constructs a box containing a single point \\a p. */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline explicit AlignedBox(const MatrixBase<Derived>& p) : m_min(p), m_max(m_min)\n  { }\n\n  EIGEN_DEVICE_FUNC ~AlignedBox() {}\n\n  /** \\returns the dimension in which the box holds */\n  EIGEN_DEVICE_FUNC inline Index dim() const { return AmbientDimAtCompileTime==Dynamic ? m_min.size() : Index(AmbientDimAtCompileTime); }\n\n  /** \\deprecated use isEmpty() */\n  EIGEN_DEVICE_FUNC inline bool isNull() const { return isEmpty(); }\n\n  /** \\deprecated use setEmpty() */\n  EIGEN_DEVICE_FUNC inline void setNull() { setEmpty(); }\n\n  /** \\returns true if the box is empty.\n   * \\sa setEmpty */\n  EIGEN_DEVICE_FUNC inline bool isEmpty() const { return (m_min.array() > m_max.array()).any(); }\n\n  /** Makes \\c *this an empty box.\n   * \\sa isEmpty */\n  EIGEN_DEVICE_FUNC inline void setEmpty()\n  {\n    m_min.setConstant( ScalarTraits::highest() );\n    m_max.setConstant( ScalarTraits::lowest() );\n  }\n\n  /** \\returns the minimal corner */\n  EIGEN_DEVICE_FUNC inline const VectorType& (min)() const { return m_min; }\n  /** \\returns a non const reference to the minimal corner */\n  EIGEN_DEVICE_FUNC inline VectorType& (min)() { return m_min; }\n  /** \\returns the maximal corner */\n  EIGEN_DEVICE_FUNC inline const VectorType& (max)() const { return m_max; }\n  /** \\returns a non const reference to the maximal corner */\n  EIGEN_DEVICE_FUNC inline VectorType& (max)() { return m_max; }\n\n  /** \\returns the center of the box */\n  EIGEN_DEVICE_FUNC inline const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(VectorTypeSum, RealScalar, quotient)\n  center() const\n  { return (m_min+m_max)/RealScalar(2); }\n\n  /** \\returns the lengths of the sides of the bounding box.\n    * Note that this function does not get the same\n    * result for integral or floating scalar types: see\n    */\n  EIGEN_DEVICE_FUNC inline const CwiseBinaryOp< internal::scalar_difference_op<Scalar,Scalar>, const VectorType, const VectorType> sizes() const\n  { return m_max - m_min; }\n\n  /** \\returns the volume of the bounding box */\n  EIGEN_DEVICE_FUNC inline Scalar volume() const\n  { return sizes().prod(); }\n\n  /** \\returns an expression for the bounding box diagonal vector\n    * if the length of the diagonal is needed: diagonal().norm()\n    * will provide it.\n    */\n  EIGEN_DEVICE_FUNC inline CwiseBinaryOp< internal::scalar_difference_op<Scalar,Scalar>, const VectorType, const VectorType> diagonal() const\n  { return sizes(); }\n\n  /** \\returns the vertex of the bounding box at the corner defined by\n    * the corner-id corner. It works only for a 1D, 2D or 3D bounding box.\n    * For 1D bounding boxes corners are named by 2 enum constants:\n    * BottomLeft and BottomRight.\n    * For 2D bounding boxes, corners are named by 4 enum constants:\n    * BottomLeft, BottomRight, TopLeft, TopRight.\n    * For 3D bounding boxes, the following names are added:\n    * BottomLeftCeil, BottomRightCeil, TopLeftCeil, TopRightCeil.\n    */\n  EIGEN_DEVICE_FUNC inline VectorType corner(CornerType corner) const\n  {\n    EIGEN_STATIC_ASSERT(_AmbientDim <= 3, THIS_METHOD_IS_ONLY_FOR_VECTORS_OF_A_SPECIFIC_SIZE);\n\n    VectorType res;\n\n    Index mult = 1;\n    for(Index d=0; d<dim(); ++d)\n    {\n      if( mult & corner ) res[d] = m_max[d];\n      else                res[d] = m_min[d];\n      mult *= 2;\n    }\n    return res;\n  }\n\n  /** \\returns a random point inside the bounding box sampled with\n   * a uniform distribution */\n  EIGEN_DEVICE_FUNC inline VectorType sample() const\n  {\n    VectorType r(dim());\n    for(Index d=0; d<dim(); ++d)\n    {\n      if(!ScalarTraits::IsInteger)\n      {\n        r[d] = m_min[d] + (m_max[d]-m_min[d])\n             * internal::random<Scalar>(Scalar(0), Scalar(1));\n      }\n      else\n        r[d] = internal::random(m_min[d], m_max[d]);\n    }\n    return r;\n  }\n\n  /** \\returns true if the point \\a p is inside the box \\c *this. */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline bool contains(const MatrixBase<Derived>& p) const\n  {\n    typename internal::nested_eval<Derived,2>::type p_n(p.derived());\n    return (m_min.array()<=p_n.array()).all() && (p_n.array()<=m_max.array()).all();\n  }\n\n  /** \\returns true if the box \\a b is entirely inside the box \\c *this. */\n  EIGEN_DEVICE_FUNC inline bool contains(const AlignedBox& b) const\n  { return (m_min.array()<=(b.min)().array()).all() && ((b.max)().array()<=m_max.array()).all(); }\n\n  /** \\returns true if the box \\a b is intersecting the box \\c *this.\n   * \\sa intersection, clamp */\n  EIGEN_DEVICE_FUNC inline bool intersects(const AlignedBox& b) const\n  { return (m_min.array()<=(b.max)().array()).all() && ((b.min)().array()<=m_max.array()).all(); }\n\n  /** Extends \\c *this such that it contains the point \\a p and returns a reference to \\c *this.\n   * \\sa extend(const AlignedBox&) */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline AlignedBox& extend(const MatrixBase<Derived>& p)\n  {\n    typename internal::nested_eval<Derived,2>::type p_n(p.derived());\n    m_min = m_min.cwiseMin(p_n);\n    m_max = m_max.cwiseMax(p_n);\n    return *this;\n  }\n\n  /** Extends \\c *this such that it contains the box \\a b and returns a reference to \\c *this.\n   * \\sa merged, extend(const MatrixBase&) */\n  EIGEN_DEVICE_FUNC inline AlignedBox& extend(const AlignedBox& b)\n  {\n    m_min = m_min.cwiseMin(b.m_min);\n    m_max = m_max.cwiseMax(b.m_max);\n    return *this;\n  }\n\n  /** Clamps \\c *this by the box \\a b and returns a reference to \\c *this.\n   * \\note If the boxes don't intersect, the resulting box is empty.\n   * \\sa intersection(), intersects() */\n  EIGEN_DEVICE_FUNC inline AlignedBox& clamp(const AlignedBox& b)\n  {\n    m_min = m_min.cwiseMax(b.m_min);\n    m_max = m_max.cwiseMin(b.m_max);\n    return *this;\n  }\n\n  /** Returns an AlignedBox that is the intersection of \\a b and \\c *this\n   * \\note If the boxes don't intersect, the resulting box is empty.\n   * \\sa intersects(), clamp, contains()  */\n  EIGEN_DEVICE_FUNC inline AlignedBox intersection(const AlignedBox& b) const\n  {return AlignedBox(m_min.cwiseMax(b.m_min), m_max.cwiseMin(b.m_max)); }\n\n  /** Returns an AlignedBox that is the union of \\a b and \\c *this.\n   * \\note Merging with an empty box may result in a box bigger than \\c *this.\n   * \\sa extend(const AlignedBox&) */\n  EIGEN_DEVICE_FUNC inline AlignedBox merged(const AlignedBox& b) const\n  { return AlignedBox(m_min.cwiseMin(b.m_min), m_max.cwiseMax(b.m_max)); }\n\n  /** Translate \\c *this by the vector \\a t and returns a reference to \\c *this. */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline AlignedBox& translate(const MatrixBase<Derived>& a_t)\n  {\n    const typename internal::nested_eval<Derived,2>::type t(a_t.derived());\n    m_min += t;\n    m_max += t;\n    return *this;\n  }\n\n  /** \\returns a copy of \\c *this translated by the vector \\a t. */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline AlignedBox translated(const MatrixBase<Derived>& a_t) const\n  {\n    AlignedBox result(m_min, m_max);\n    result.translate(a_t);\n    return result;\n  }\n\n  /** \\returns the squared distance between the point \\a p and the box \\c *this,\n    * and zero if \\a p is inside the box.\n    * \\sa exteriorDistance(const MatrixBase&), squaredExteriorDistance(const AlignedBox&)\n    */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline Scalar squaredExteriorDistance(const MatrixBase<Derived>& p) const;\n\n  /** \\returns the squared distance between the boxes \\a b and \\c *this,\n    * and zero if the boxes intersect.\n    * \\sa exteriorDistance(const AlignedBox&), squaredExteriorDistance(const MatrixBase&)\n    */\n  EIGEN_DEVICE_FUNC inline Scalar squaredExteriorDistance(const AlignedBox& b) const;\n\n  /** \\returns the distance between the point \\a p and the box \\c *this,\n    * and zero if \\a p is inside the box.\n    * \\sa squaredExteriorDistance(const MatrixBase&), exteriorDistance(const AlignedBox&)\n    */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline NonInteger exteriorDistance(const MatrixBase<Derived>& p) const\n  { EIGEN_USING_STD(sqrt) return sqrt(NonInteger(squaredExteriorDistance(p))); }\n\n  /** \\returns the distance between the boxes \\a b and \\c *this,\n    * and zero if the boxes intersect.\n    * \\sa squaredExteriorDistance(const AlignedBox&), exteriorDistance(const MatrixBase&)\n    */\n  EIGEN_DEVICE_FUNC inline NonInteger exteriorDistance(const AlignedBox& b) const\n  { EIGEN_USING_STD(sqrt) return sqrt(NonInteger(squaredExteriorDistance(b))); }\n\n  /**\n   * Specialization of transform for pure translation.\n   */\n  template<int Mode, int Options>\n  EIGEN_DEVICE_FUNC inline void transform(\n      const typename Transform<Scalar, AmbientDimAtCompileTime, Mode, Options>::TranslationType& translation)\n  {\n    this->translate(translation);\n  }\n\n  /**\n   * Transforms this box by \\a transform and recomputes it to\n   * still be an axis-aligned box.\n   *\n   * \\note This method is provided under BSD license (see the top of this file).\n   */\n  template<int Mode, int Options>\n  EIGEN_DEVICE_FUNC inline void transform(const Transform<Scalar, AmbientDimAtCompileTime, Mode, Options>& transform)\n  {\n    // Only Affine and Isometry transforms are currently supported.\n    EIGEN_STATIC_ASSERT(Mode == Affine || Mode == AffineCompact || Mode == Isometry, THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS);\n\n    // Method adapted from FCL src/shape/geometric_shapes_utility.cpp#computeBV<AABB, Box>(...)\n    // https://github.com/flexible-collision-library/fcl/blob/fcl-0.4/src/shape/geometric_shapes_utility.cpp#L292\n    //\n    // Here's a nice explanation why it works: https://zeuxcg.org/2010/10/17/aabb-from-obb-with-component-wise-abs/\n\n    // two times rotated extent\n    const VectorType rotated_extent_2 = transform.linear().cwiseAbs() * sizes();\n    // two times new center\n    const VectorType rotated_center_2 = transform.linear() * (this->m_max + this->m_min) +\n        Scalar(2) * transform.translation();\n\n    this->m_max = (rotated_center_2 + rotated_extent_2) / Scalar(2);\n    this->m_min = (rotated_center_2 - rotated_extent_2) / Scalar(2);\n  }\n\n  /**\n   * \\returns a copy of \\c *this transformed by \\a transform and recomputed to\n   * still be an axis-aligned box.\n   */\n  template<int Mode, int Options>\n  EIGEN_DEVICE_FUNC AlignedBox transformed(const Transform<Scalar, AmbientDimAtCompileTime, Mode, Options>& transform) const\n  {\n    AlignedBox result(m_min, m_max);\n    result.transform(transform);\n    return result;\n  }\n\n  /** \\returns \\c *this with scalar type casted to \\a NewScalarType\n    *\n    * Note that if \\a NewScalarType is equal to the current scalar type of \\c *this\n    * then this function smartly returns a const reference to \\c *this.\n    */\n  template<typename NewScalarType>\n  EIGEN_DEVICE_FUNC inline typename internal::cast_return_type<AlignedBox,\n           AlignedBox<NewScalarType,AmbientDimAtCompileTime> >::type cast() const\n  {\n    return typename internal::cast_return_type<AlignedBox,\n                    AlignedBox<NewScalarType,AmbientDimAtCompileTime> >::type(*this);\n  }\n\n  /** Copy constructor with scalar type conversion */\n  template<typename OtherScalarType>\n  EIGEN_DEVICE_FUNC inline explicit AlignedBox(const AlignedBox<OtherScalarType,AmbientDimAtCompileTime>& other)\n  {\n    m_min = (other.min)().template cast<Scalar>();\n    m_max = (other.max)().template cast<Scalar>();\n  }\n\n  /** \\returns \\c true if \\c *this is approximately equal to \\a other, within the precision\n    * determined by \\a prec.\n    *\n    * \\sa MatrixBase::isApprox() */\n  EIGEN_DEVICE_FUNC bool isApprox(const AlignedBox& other, const RealScalar& prec = ScalarTraits::dummy_precision()) const\n  { return m_min.isApprox(other.m_min, prec) && m_max.isApprox(other.m_max, prec); }\n\nprotected:\n\n  VectorType m_min, m_max;\n};\n\n\n\ntemplate<typename Scalar,int AmbientDim>\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC inline Scalar AlignedBox<Scalar,AmbientDim>::squaredExteriorDistance(const MatrixBase<Derived>& a_p) const\n{\n  typename internal::nested_eval<Derived,2*AmbientDim>::type p(a_p.derived());\n  Scalar dist2(0);\n  Scalar aux;\n  for (Index k=0; k<dim(); ++k)\n  {\n    if( m_min[k] > p[k] )\n    {\n      aux = m_min[k] - p[k];\n      dist2 += aux*aux;\n    }\n    else if( p[k] > m_max[k] )\n    {\n      aux = p[k] - m_max[k];\n      dist2 += aux*aux;\n    }\n  }\n  return dist2;\n}\n\ntemplate<typename Scalar,int AmbientDim>\nEIGEN_DEVICE_FUNC inline Scalar AlignedBox<Scalar,AmbientDim>::squaredExteriorDistance(const AlignedBox& b) const\n{\n  Scalar dist2(0);\n  Scalar aux;\n  for (Index k=0; k<dim(); ++k)\n  {\n    if( m_min[k] > b.m_max[k] )\n    {\n      aux = m_min[k] - b.m_max[k];\n      dist2 += aux*aux;\n    }\n    else if( b.m_min[k] > m_max[k] )\n    {\n      aux = b.m_min[k] - m_max[k];\n      dist2 += aux*aux;\n    }\n  }\n  return dist2;\n}\n\n/** \\defgroup alignedboxtypedefs Global aligned box typedefs\n  *\n  * \\ingroup Geometry_Module\n  *\n  * Eigen defines several typedef shortcuts for most common aligned box types.\n  *\n  * The general patterns are the following:\n  *\n  * \\c AlignedBoxSizeType where \\c Size can be \\c 1, \\c 2,\\c 3,\\c 4 for fixed size boxes or \\c X for dynamic size,\n  * and where \\c Type can be \\c i for integer, \\c f for float, \\c d for double.\n  *\n  * For example, \\c AlignedBox3d is a fixed-size 3x3 aligned box type of doubles, and \\c AlignedBoxXf is a dynamic-size aligned box of floats.\n  *\n  * \\sa class AlignedBox\n  */\n\n#define EIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, Size, SizeSuffix)    \\\n/** \\ingroup alignedboxtypedefs */                                 \\\ntypedef AlignedBox<Type, Size>   AlignedBox##SizeSuffix##TypeSuffix;\n\n#define EIGEN_MAKE_TYPEDEFS_ALL_SIZES(Type, TypeSuffix) \\\nEIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, 1, 1) \\\nEIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, 2, 2) \\\nEIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, 3, 3) \\\nEIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, 4, 4) \\\nEIGEN_MAKE_TYPEDEFS(Type, TypeSuffix, Dynamic, X)\n\nEIGEN_MAKE_TYPEDEFS_ALL_SIZES(int,                  i)\nEIGEN_MAKE_TYPEDEFS_ALL_SIZES(float,                f)\nEIGEN_MAKE_TYPEDEFS_ALL_SIZES(double,               d)\n\n#undef EIGEN_MAKE_TYPEDEFS_ALL_SIZES\n#undef EIGEN_MAKE_TYPEDEFS\n\n} // end namespace Eigen\n\n#endif // EIGEN_ALIGNEDBOX_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Geometry/AngleAxis.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ANGLEAXIS_H\n#define EIGEN_ANGLEAXIS_H\n\nnamespace Eigen { \n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\class AngleAxis\n  *\n  * \\brief Represents a 3D rotation as a rotation angle around an arbitrary 3D axis\n  *\n  * \\param _Scalar the scalar type, i.e., the type of the coefficients.\n  *\n  * \\warning When setting up an AngleAxis object, the axis vector \\b must \\b be \\b normalized.\n  *\n  * The following two typedefs are provided for convenience:\n  * \\li \\c AngleAxisf for \\c float\n  * \\li \\c AngleAxisd for \\c double\n  *\n  * Combined with MatrixBase::Unit{X,Y,Z}, AngleAxis can be used to easily\n  * mimic Euler-angles. Here is an example:\n  * \\include AngleAxis_mimic_euler.cpp\n  * Output: \\verbinclude AngleAxis_mimic_euler.out\n  *\n  * \\note This class is not aimed to be used to store a rotation transformation,\n  * but rather to make easier the creation of other rotation (Quaternion, rotation Matrix)\n  * and transformation objects.\n  *\n  * \\sa class Quaternion, class Transform, MatrixBase::UnitX()\n  */\n\nnamespace internal {\ntemplate<typename _Scalar> struct traits<AngleAxis<_Scalar> >\n{\n  typedef _Scalar Scalar;\n};\n}\n\ntemplate<typename _Scalar>\nclass AngleAxis : public RotationBase<AngleAxis<_Scalar>,3>\n{\n  typedef RotationBase<AngleAxis<_Scalar>,3> Base;\n\npublic:\n\n  using Base::operator*;\n\n  enum { Dim = 3 };\n  /** the scalar type of the coefficients */\n  typedef _Scalar Scalar;\n  typedef Matrix<Scalar,3,3> Matrix3;\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef Quaternion<Scalar> QuaternionType;\n\nprotected:\n\n  Vector3 m_axis;\n  Scalar m_angle;\n\npublic:\n\n  /** Default constructor without initialization. */\n  EIGEN_DEVICE_FUNC AngleAxis() {}\n  /** Constructs and initialize the angle-axis rotation from an \\a angle in radian\n    * and an \\a axis which \\b must \\b be \\b normalized.\n    *\n    * \\warning If the \\a axis vector is not normalized, then the angle-axis object\n    *          represents an invalid rotation. */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC \n  inline AngleAxis(const Scalar& angle, const MatrixBase<Derived>& axis) : m_axis(axis), m_angle(angle) {}\n  /** Constructs and initialize the angle-axis rotation from a quaternion \\a q.\n    * This function implicitly normalizes the quaternion \\a q.\n    */\n  template<typename QuatDerived> \n  EIGEN_DEVICE_FUNC inline explicit AngleAxis(const QuaternionBase<QuatDerived>& q) { *this = q; }\n  /** Constructs and initialize the angle-axis rotation from a 3x3 rotation matrix. */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline explicit AngleAxis(const MatrixBase<Derived>& m) { *this = m; }\n\n  /** \\returns the value of the rotation angle in radian */\n  EIGEN_DEVICE_FUNC Scalar angle() const { return m_angle; }\n  /** \\returns a read-write reference to the stored angle in radian */\n  EIGEN_DEVICE_FUNC Scalar& angle() { return m_angle; }\n\n  /** \\returns the rotation axis */\n  EIGEN_DEVICE_FUNC const Vector3& axis() const { return m_axis; }\n  /** \\returns a read-write reference to the stored rotation axis.\n    *\n    * \\warning The rotation axis must remain a \\b unit vector.\n    */\n  EIGEN_DEVICE_FUNC Vector3& axis() { return m_axis; }\n\n  /** Concatenates two rotations */\n  EIGEN_DEVICE_FUNC inline QuaternionType operator* (const AngleAxis& other) const\n  { return QuaternionType(*this) * QuaternionType(other); }\n\n  /** Concatenates two rotations */\n  EIGEN_DEVICE_FUNC inline QuaternionType operator* (const QuaternionType& other) const\n  { return QuaternionType(*this) * other; }\n\n  /** Concatenates two rotations */\n  friend EIGEN_DEVICE_FUNC inline QuaternionType operator* (const QuaternionType& a, const AngleAxis& b)\n  { return a * QuaternionType(b); }\n\n  /** \\returns the inverse rotation, i.e., an angle-axis with opposite rotation angle */\n  EIGEN_DEVICE_FUNC AngleAxis inverse() const\n  { return AngleAxis(-m_angle, m_axis); }\n\n  template<class QuatDerived>\n  EIGEN_DEVICE_FUNC AngleAxis& operator=(const QuaternionBase<QuatDerived>& q);\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC AngleAxis& operator=(const MatrixBase<Derived>& m);\n\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC AngleAxis& fromRotationMatrix(const MatrixBase<Derived>& m);\n  EIGEN_DEVICE_FUNC Matrix3 toRotationMatrix(void) const;\n\n  /** \\returns \\c *this with scalar type casted to \\a NewScalarType\n    *\n    * Note that if \\a NewScalarType is equal to the current scalar type of \\c *this\n    * then this function smartly returns a const reference to \\c *this.\n    */\n  template<typename NewScalarType>\n  EIGEN_DEVICE_FUNC inline typename internal::cast_return_type<AngleAxis,AngleAxis<NewScalarType> >::type cast() const\n  { return typename internal::cast_return_type<AngleAxis,AngleAxis<NewScalarType> >::type(*this); }\n\n  /** Copy constructor with scalar type conversion */\n  template<typename OtherScalarType>\n  EIGEN_DEVICE_FUNC inline explicit AngleAxis(const AngleAxis<OtherScalarType>& other)\n  {\n    m_axis = other.axis().template cast<Scalar>();\n    m_angle = Scalar(other.angle());\n  }\n\n  EIGEN_DEVICE_FUNC static inline const AngleAxis Identity() { return AngleAxis(Scalar(0), Vector3::UnitX()); }\n\n  /** \\returns \\c true if \\c *this is approximately equal to \\a other, within the precision\n    * determined by \\a prec.\n    *\n    * \\sa MatrixBase::isApprox() */\n  EIGEN_DEVICE_FUNC bool isApprox(const AngleAxis& other, const typename NumTraits<Scalar>::Real& prec = NumTraits<Scalar>::dummy_precision()) const\n  { return m_axis.isApprox(other.m_axis, prec) && internal::isApprox(m_angle,other.m_angle, prec); }\n};\n\n/** \\ingroup Geometry_Module\n  * single precision angle-axis type */\ntypedef AngleAxis<float> AngleAxisf;\n/** \\ingroup Geometry_Module\n  * double precision angle-axis type */\ntypedef AngleAxis<double> AngleAxisd;\n\n/** Set \\c *this from a \\b unit quaternion.\n  *\n  * The resulting axis is normalized, and the computed angle is in the [0,pi] range.\n  * \n  * This function implicitly normalizes the quaternion \\a q.\n  */\ntemplate<typename Scalar>\ntemplate<typename QuatDerived>\nEIGEN_DEVICE_FUNC AngleAxis<Scalar>& AngleAxis<Scalar>::operator=(const QuaternionBase<QuatDerived>& q)\n{\n  EIGEN_USING_STD(atan2)\n  EIGEN_USING_STD(abs)\n  Scalar n = q.vec().norm();\n  if(n<NumTraits<Scalar>::epsilon())\n    n = q.vec().stableNorm();\n\n  if (n != Scalar(0))\n  {\n    m_angle = Scalar(2)*atan2(n, abs(q.w()));\n    if(q.w() < Scalar(0))\n      n = -n;\n    m_axis  = q.vec() / n;\n  }\n  else\n  {\n    m_angle = Scalar(0);\n    m_axis << Scalar(1), Scalar(0), Scalar(0);\n  }\n  return *this;\n}\n\n/** Set \\c *this from a 3x3 rotation matrix \\a mat.\n  */\ntemplate<typename Scalar>\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC AngleAxis<Scalar>& AngleAxis<Scalar>::operator=(const MatrixBase<Derived>& mat)\n{\n  // Since a direct conversion would not be really faster,\n  // let's use the robust Quaternion implementation:\n  return *this = QuaternionType(mat);\n}\n\n/**\n* \\brief Sets \\c *this from a 3x3 rotation matrix.\n**/\ntemplate<typename Scalar>\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC AngleAxis<Scalar>& AngleAxis<Scalar>::fromRotationMatrix(const MatrixBase<Derived>& mat)\n{\n  return *this = QuaternionType(mat);\n}\n\n/** Constructs and \\returns an equivalent 3x3 rotation matrix.\n  */\ntemplate<typename Scalar>\ntypename AngleAxis<Scalar>::Matrix3\nEIGEN_DEVICE_FUNC AngleAxis<Scalar>::toRotationMatrix(void) const\n{\n  EIGEN_USING_STD(sin)\n  EIGEN_USING_STD(cos)\n  Matrix3 res;\n  Vector3 sin_axis  = sin(m_angle) * m_axis;\n  Scalar c = cos(m_angle);\n  Vector3 cos1_axis = (Scalar(1)-c) * m_axis;\n\n  Scalar tmp;\n  tmp = cos1_axis.x() * m_axis.y();\n  res.coeffRef(0,1) = tmp - sin_axis.z();\n  res.coeffRef(1,0) = tmp + sin_axis.z();\n\n  tmp = cos1_axis.x() * m_axis.z();\n  res.coeffRef(0,2) = tmp + sin_axis.y();\n  res.coeffRef(2,0) = tmp - sin_axis.y();\n\n  tmp = cos1_axis.y() * m_axis.z();\n  res.coeffRef(1,2) = tmp - sin_axis.x();\n  res.coeffRef(2,1) = tmp + sin_axis.x();\n\n  res.diagonal() = (cos1_axis.cwiseProduct(m_axis)).array() + c;\n\n  return res;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_ANGLEAXIS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Geometry/EulerAngles.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_EULERANGLES_H\n#define EIGEN_EULERANGLES_H\n\nnamespace Eigen { \n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  *\n  * \\returns the Euler-angles of the rotation matrix \\c *this using the convention defined by the triplet (\\a a0,\\a a1,\\a a2)\n  *\n  * Each of the three parameters \\a a0,\\a a1,\\a a2 represents the respective rotation axis as an integer in {0,1,2}.\n  * For instance, in:\n  * \\code Vector3f ea = mat.eulerAngles(2, 0, 2); \\endcode\n  * \"2\" represents the z axis and \"0\" the x axis, etc. The returned angles are such that\n  * we have the following equality:\n  * \\code\n  * mat == AngleAxisf(ea[0], Vector3f::UnitZ())\n  *      * AngleAxisf(ea[1], Vector3f::UnitX())\n  *      * AngleAxisf(ea[2], Vector3f::UnitZ()); \\endcode\n  * This corresponds to the right-multiply conventions (with right hand side frames).\n  * \n  * The returned angles are in the ranges [0:pi]x[-pi:pi]x[-pi:pi].\n  * \n  * \\sa class AngleAxis\n  */\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC inline Matrix<typename MatrixBase<Derived>::Scalar,3,1>\nMatrixBase<Derived>::eulerAngles(Index a0, Index a1, Index a2) const\n{\n  EIGEN_USING_STD(atan2)\n  EIGEN_USING_STD(sin)\n  EIGEN_USING_STD(cos)\n  /* Implemented from Graphics Gems IV */\n  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Derived,3,3)\n\n  Matrix<Scalar,3,1> res;\n  typedef Matrix<typename Derived::Scalar,2,1> Vector2;\n\n  const Index odd = ((a0+1)%3 == a1) ? 0 : 1;\n  const Index i = a0;\n  const Index j = (a0 + 1 + odd)%3;\n  const Index k = (a0 + 2 - odd)%3;\n  \n  if (a0==a2)\n  {\n    res[0] = atan2(coeff(j,i), coeff(k,i));\n    if((odd && res[0]<Scalar(0)) || ((!odd) && res[0]>Scalar(0)))\n    {\n      if(res[0] > Scalar(0)) {\n        res[0] -= Scalar(EIGEN_PI);\n      }\n      else {\n        res[0] += Scalar(EIGEN_PI);\n      }\n      Scalar s2 = Vector2(coeff(j,i), coeff(k,i)).norm();\n      res[1] = -atan2(s2, coeff(i,i));\n    }\n    else\n    {\n      Scalar s2 = Vector2(coeff(j,i), coeff(k,i)).norm();\n      res[1] = atan2(s2, coeff(i,i));\n    }\n    \n    // With a=(0,1,0), we have i=0; j=1; k=2, and after computing the first two angles,\n    // we can compute their respective rotation, and apply its inverse to M. Since the result must\n    // be a rotation around x, we have:\n    //\n    //  c2  s1.s2 c1.s2                   1  0   0 \n    //  0   c1    -s1       *    M    =   0  c3  s3\n    //  -s2 s1.c2 c1.c2                   0 -s3  c3\n    //\n    //  Thus:  m11.c1 - m21.s1 = c3  &   m12.c1 - m22.s1 = s3\n    \n    Scalar s1 = sin(res[0]);\n    Scalar c1 = cos(res[0]);\n    res[2] = atan2(c1*coeff(j,k)-s1*coeff(k,k), c1*coeff(j,j) - s1 * coeff(k,j));\n  } \n  else\n  {\n    res[0] = atan2(coeff(j,k), coeff(k,k));\n    Scalar c2 = Vector2(coeff(i,i), coeff(i,j)).norm();\n    if((odd && res[0]<Scalar(0)) || ((!odd) && res[0]>Scalar(0))) {\n      if(res[0] > Scalar(0)) {\n        res[0] -= Scalar(EIGEN_PI);\n      }\n      else {\n        res[0] += Scalar(EIGEN_PI);\n      }\n      res[1] = atan2(-coeff(i,k), -c2);\n    }\n    else\n      res[1] = atan2(-coeff(i,k), c2);\n    Scalar s1 = sin(res[0]);\n    Scalar c1 = cos(res[0]);\n    res[2] = atan2(s1*coeff(k,i)-c1*coeff(j,i), c1*coeff(j,j) - s1 * coeff(k,j));\n  }\n  if (!odd)\n    res = -res;\n  \n  return res;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_EULERANGLES_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Geometry/Homogeneous.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_HOMOGENEOUS_H\n#define EIGEN_HOMOGENEOUS_H\n\nnamespace Eigen { \n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\class Homogeneous\n  *\n  * \\brief Expression of one (or a set of) homogeneous vector(s)\n  *\n  * \\param MatrixType the type of the object in which we are making homogeneous\n  *\n  * This class represents an expression of one (or a set of) homogeneous vector(s).\n  * It is the return type of MatrixBase::homogeneous() and most of the time\n  * this is the only way it is used.\n  *\n  * \\sa MatrixBase::homogeneous()\n  */\n\nnamespace internal {\n\ntemplate<typename MatrixType,int Direction>\nstruct traits<Homogeneous<MatrixType,Direction> >\n : traits<MatrixType>\n{\n  typedef typename traits<MatrixType>::StorageKind StorageKind;\n  typedef typename ref_selector<MatrixType>::type MatrixTypeNested;\n  typedef typename remove_reference<MatrixTypeNested>::type _MatrixTypeNested;\n  enum {\n    RowsPlusOne = (MatrixType::RowsAtCompileTime != Dynamic) ?\n                  int(MatrixType::RowsAtCompileTime) + 1 : Dynamic,\n    ColsPlusOne = (MatrixType::ColsAtCompileTime != Dynamic) ?\n                  int(MatrixType::ColsAtCompileTime) + 1 : Dynamic,\n    RowsAtCompileTime = Direction==Vertical  ?  RowsPlusOne : MatrixType::RowsAtCompileTime,\n    ColsAtCompileTime = Direction==Horizontal ? ColsPlusOne : MatrixType::ColsAtCompileTime,\n    MaxRowsAtCompileTime = RowsAtCompileTime,\n    MaxColsAtCompileTime = ColsAtCompileTime,\n    TmpFlags = _MatrixTypeNested::Flags & HereditaryBits,\n    Flags = ColsAtCompileTime==1 ? (TmpFlags & ~RowMajorBit)\n          : RowsAtCompileTime==1 ? (TmpFlags | RowMajorBit)\n          : TmpFlags\n  };\n};\n\ntemplate<typename MatrixType,typename Lhs> struct homogeneous_left_product_impl;\ntemplate<typename MatrixType,typename Rhs> struct homogeneous_right_product_impl;\n\n} // end namespace internal\n\ntemplate<typename MatrixType,int _Direction> class Homogeneous\n  : public MatrixBase<Homogeneous<MatrixType,_Direction> >, internal::no_assignment_operator\n{\n  public:\n\n    typedef MatrixType NestedExpression;\n    enum { Direction = _Direction };\n\n    typedef MatrixBase<Homogeneous> Base;\n    EIGEN_DENSE_PUBLIC_INTERFACE(Homogeneous)\n\n    EIGEN_DEVICE_FUNC explicit inline Homogeneous(const MatrixType& matrix)\n      : m_matrix(matrix)\n    {}\n\n    EIGEN_DEVICE_FUNC inline Index rows() const { return m_matrix.rows() + (int(Direction)==Vertical   ? 1 : 0); }\n    EIGEN_DEVICE_FUNC inline Index cols() const { return m_matrix.cols() + (int(Direction)==Horizontal ? 1 : 0); }\n    \n    EIGEN_DEVICE_FUNC const NestedExpression& nestedExpression() const { return m_matrix; }\n\n    template<typename Rhs>\n    EIGEN_DEVICE_FUNC inline const Product<Homogeneous,Rhs>\n    operator* (const MatrixBase<Rhs>& rhs) const\n    {\n      eigen_assert(int(Direction)==Horizontal);\n      return Product<Homogeneous,Rhs>(*this,rhs.derived());\n    }\n\n    template<typename Lhs> friend\n    EIGEN_DEVICE_FUNC inline const Product<Lhs,Homogeneous>\n    operator* (const MatrixBase<Lhs>& lhs, const Homogeneous& rhs)\n    {\n      eigen_assert(int(Direction)==Vertical);\n      return Product<Lhs,Homogeneous>(lhs.derived(),rhs);\n    }\n\n    template<typename Scalar, int Dim, int Mode, int Options> friend\n    EIGEN_DEVICE_FUNC inline const Product<Transform<Scalar,Dim,Mode,Options>, Homogeneous >\n    operator* (const Transform<Scalar,Dim,Mode,Options>& lhs, const Homogeneous& rhs)\n    {\n      eigen_assert(int(Direction)==Vertical);\n      return Product<Transform<Scalar,Dim,Mode,Options>, Homogeneous>(lhs,rhs);\n    }\n\n    template<typename Func>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename internal::result_of<Func(Scalar,Scalar)>::type\n    redux(const Func& func) const\n    {\n      return func(m_matrix.redux(func), Scalar(1));\n    }\n\n  protected:\n    typename MatrixType::Nested m_matrix;\n};\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\returns a vector expression that is one longer than the vector argument, with the value 1 symbolically appended as the last coefficient.\n  *\n  * This can be used to convert affine coordinates to homogeneous coordinates.\n  *\n  * \\only_for_vectors\n  *\n  * Example: \\include MatrixBase_homogeneous.cpp\n  * Output: \\verbinclude MatrixBase_homogeneous.out\n  *\n  * \\sa VectorwiseOp::homogeneous(), class Homogeneous\n  */\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC inline typename MatrixBase<Derived>::HomogeneousReturnType\nMatrixBase<Derived>::homogeneous() const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived);\n  return HomogeneousReturnType(derived());\n}\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\returns an expression where the value 1 is symbolically appended as the final coefficient to each column (or row) of the matrix.\n  *\n  * This can be used to convert affine coordinates to homogeneous coordinates.\n  *\n  * Example: \\include VectorwiseOp_homogeneous.cpp\n  * Output: \\verbinclude VectorwiseOp_homogeneous.out\n  *\n  * \\sa MatrixBase::homogeneous(), class Homogeneous */\ntemplate<typename ExpressionType, int Direction>\nEIGEN_DEVICE_FUNC inline Homogeneous<ExpressionType,Direction>\nVectorwiseOp<ExpressionType,Direction>::homogeneous() const\n{\n  return HomogeneousReturnType(_expression());\n}\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\brief homogeneous normalization\n  *\n  * \\returns a vector expression of the N-1 first coefficients of \\c *this divided by that last coefficient.\n  *\n  * This can be used to convert homogeneous coordinates to affine coordinates.\n  *\n  * It is essentially a shortcut for:\n  * \\code\n    this->head(this->size()-1)/this->coeff(this->size()-1);\n    \\endcode\n  *\n  * Example: \\include MatrixBase_hnormalized.cpp\n  * Output: \\verbinclude MatrixBase_hnormalized.out\n  *\n  * \\sa VectorwiseOp::hnormalized() */\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC inline const typename MatrixBase<Derived>::HNormalizedReturnType\nMatrixBase<Derived>::hnormalized() const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived);\n  return ConstStartMinusOne(derived(),0,0,\n    ColsAtCompileTime==1?size()-1:1,\n    ColsAtCompileTime==1?1:size()-1) / coeff(size()-1);\n}\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\brief column or row-wise homogeneous normalization\n  *\n  * \\returns an expression of the first N-1 coefficients of each column (or row) of \\c *this divided by the last coefficient of each column (or row).\n  *\n  * This can be used to convert homogeneous coordinates to affine coordinates.\n  *\n  * It is conceptually equivalent to calling MatrixBase::hnormalized() to each column (or row) of \\c *this.\n  *\n  * Example: \\include DirectionWise_hnormalized.cpp\n  * Output: \\verbinclude DirectionWise_hnormalized.out\n  *\n  * \\sa MatrixBase::hnormalized() */\ntemplate<typename ExpressionType, int Direction>\nEIGEN_DEVICE_FUNC inline const typename VectorwiseOp<ExpressionType,Direction>::HNormalizedReturnType\nVectorwiseOp<ExpressionType,Direction>::hnormalized() const\n{\n  return HNormalized_Block(_expression(),0,0,\n      Direction==Vertical   ? _expression().rows()-1 : _expression().rows(),\n      Direction==Horizontal ? _expression().cols()-1 : _expression().cols()).cwiseQuotient(\n      Replicate<HNormalized_Factors,\n                Direction==Vertical   ? HNormalized_SizeMinusOne : 1,\n                Direction==Horizontal ? HNormalized_SizeMinusOne : 1>\n        (HNormalized_Factors(_expression(),\n          Direction==Vertical    ? _expression().rows()-1:0,\n          Direction==Horizontal  ? _expression().cols()-1:0,\n          Direction==Vertical    ? 1 : _expression().rows(),\n          Direction==Horizontal  ? 1 : _expression().cols()),\n         Direction==Vertical   ? _expression().rows()-1 : 1,\n         Direction==Horizontal ? _expression().cols()-1 : 1));\n}\n\nnamespace internal {\n\ntemplate<typename MatrixOrTransformType>\nstruct take_matrix_for_product\n{\n  typedef MatrixOrTransformType type;\n  EIGEN_DEVICE_FUNC static const type& run(const type &x) { return x; }\n};\n\ntemplate<typename Scalar, int Dim, int Mode,int Options>\nstruct take_matrix_for_product<Transform<Scalar, Dim, Mode, Options> >\n{\n  typedef Transform<Scalar, Dim, Mode, Options> TransformType;\n  typedef typename internal::add_const<typename TransformType::ConstAffinePart>::type type;\n  EIGEN_DEVICE_FUNC static type run (const TransformType& x) { return x.affine(); }\n};\n\ntemplate<typename Scalar, int Dim, int Options>\nstruct take_matrix_for_product<Transform<Scalar, Dim, Projective, Options> >\n{\n  typedef Transform<Scalar, Dim, Projective, Options> TransformType;\n  typedef typename TransformType::MatrixType type;\n  EIGEN_DEVICE_FUNC static const type& run (const TransformType& x) { return x.matrix(); }\n};\n\ntemplate<typename MatrixType,typename Lhs>\nstruct traits<homogeneous_left_product_impl<Homogeneous<MatrixType,Vertical>,Lhs> >\n{\n  typedef typename take_matrix_for_product<Lhs>::type LhsMatrixType;\n  typedef typename remove_all<MatrixType>::type MatrixTypeCleaned;\n  typedef typename remove_all<LhsMatrixType>::type LhsMatrixTypeCleaned;\n  typedef typename make_proper_matrix_type<\n                 typename traits<MatrixTypeCleaned>::Scalar,\n                 LhsMatrixTypeCleaned::RowsAtCompileTime,\n                 MatrixTypeCleaned::ColsAtCompileTime,\n                 MatrixTypeCleaned::PlainObject::Options,\n                 LhsMatrixTypeCleaned::MaxRowsAtCompileTime,\n                 MatrixTypeCleaned::MaxColsAtCompileTime>::type ReturnType;\n};\n\ntemplate<typename MatrixType,typename Lhs>\nstruct homogeneous_left_product_impl<Homogeneous<MatrixType,Vertical>,Lhs>\n  : public ReturnByValue<homogeneous_left_product_impl<Homogeneous<MatrixType,Vertical>,Lhs> >\n{\n  typedef typename traits<homogeneous_left_product_impl>::LhsMatrixType LhsMatrixType;\n  typedef typename remove_all<LhsMatrixType>::type LhsMatrixTypeCleaned;\n  typedef typename remove_all<typename LhsMatrixTypeCleaned::Nested>::type LhsMatrixTypeNested;\n  EIGEN_DEVICE_FUNC homogeneous_left_product_impl(const Lhs& lhs, const MatrixType& rhs)\n    : m_lhs(take_matrix_for_product<Lhs>::run(lhs)),\n      m_rhs(rhs)\n  {}\n\n  EIGEN_DEVICE_FUNC inline Index rows() const { return m_lhs.rows(); }\n  EIGEN_DEVICE_FUNC inline Index cols() const { return m_rhs.cols(); }\n\n  template<typename Dest> EIGEN_DEVICE_FUNC void evalTo(Dest& dst) const\n  {\n    // FIXME investigate how to allow lazy evaluation of this product when possible\n    dst = Block<const LhsMatrixTypeNested,\n              LhsMatrixTypeNested::RowsAtCompileTime,\n              LhsMatrixTypeNested::ColsAtCompileTime==Dynamic?Dynamic:LhsMatrixTypeNested::ColsAtCompileTime-1>\n            (m_lhs,0,0,m_lhs.rows(),m_lhs.cols()-1) * m_rhs;\n    dst += m_lhs.col(m_lhs.cols()-1).rowwise()\n            .template replicate<MatrixType::ColsAtCompileTime>(m_rhs.cols());\n  }\n\n  typename LhsMatrixTypeCleaned::Nested m_lhs;\n  typename MatrixType::Nested m_rhs;\n};\n\ntemplate<typename MatrixType,typename Rhs>\nstruct traits<homogeneous_right_product_impl<Homogeneous<MatrixType,Horizontal>,Rhs> >\n{\n  typedef typename make_proper_matrix_type<typename traits<MatrixType>::Scalar,\n                 MatrixType::RowsAtCompileTime,\n                 Rhs::ColsAtCompileTime,\n                 MatrixType::PlainObject::Options,\n                 MatrixType::MaxRowsAtCompileTime,\n                 Rhs::MaxColsAtCompileTime>::type ReturnType;\n};\n\ntemplate<typename MatrixType,typename Rhs>\nstruct homogeneous_right_product_impl<Homogeneous<MatrixType,Horizontal>,Rhs>\n  : public ReturnByValue<homogeneous_right_product_impl<Homogeneous<MatrixType,Horizontal>,Rhs> >\n{\n  typedef typename remove_all<typename Rhs::Nested>::type RhsNested;\n  EIGEN_DEVICE_FUNC homogeneous_right_product_impl(const MatrixType& lhs, const Rhs& rhs)\n    : m_lhs(lhs), m_rhs(rhs)\n  {}\n\n  EIGEN_DEVICE_FUNC inline Index rows() const { return m_lhs.rows(); }\n  EIGEN_DEVICE_FUNC inline Index cols() const { return m_rhs.cols(); }\n\n  template<typename Dest> EIGEN_DEVICE_FUNC void evalTo(Dest& dst) const\n  {\n    // FIXME investigate how to allow lazy evaluation of this product when possible\n    dst = m_lhs * Block<const RhsNested,\n                        RhsNested::RowsAtCompileTime==Dynamic?Dynamic:RhsNested::RowsAtCompileTime-1,\n                        RhsNested::ColsAtCompileTime>\n            (m_rhs,0,0,m_rhs.rows()-1,m_rhs.cols());\n    dst += m_rhs.row(m_rhs.rows()-1).colwise()\n            .template replicate<MatrixType::RowsAtCompileTime>(m_lhs.rows());\n  }\n\n  typename MatrixType::Nested m_lhs;\n  typename Rhs::Nested m_rhs;\n};\n\ntemplate<typename ArgType,int Direction>\nstruct evaluator_traits<Homogeneous<ArgType,Direction> >\n{\n  typedef typename storage_kind_to_evaluator_kind<typename ArgType::StorageKind>::Kind Kind;\n  typedef HomogeneousShape Shape;  \n};\n\ntemplate<> struct AssignmentKind<DenseShape,HomogeneousShape> { typedef Dense2Dense Kind; };\n\n\ntemplate<typename ArgType,int Direction>\nstruct unary_evaluator<Homogeneous<ArgType,Direction>, IndexBased>\n  : evaluator<typename Homogeneous<ArgType,Direction>::PlainObject >\n{\n  typedef Homogeneous<ArgType,Direction> XprType;\n  typedef typename XprType::PlainObject PlainObject;\n  typedef evaluator<PlainObject> Base;\n\n  EIGEN_DEVICE_FUNC explicit unary_evaluator(const XprType& op)\n    : Base(), m_temp(op)\n  {\n    ::new (static_cast<Base*>(this)) Base(m_temp);\n  }\n\nprotected:\n  PlainObject m_temp;\n};\n\n// dense = homogeneous\ntemplate< typename DstXprType, typename ArgType, typename Scalar>\nstruct Assignment<DstXprType, Homogeneous<ArgType,Vertical>, internal::assign_op<Scalar,typename ArgType::Scalar>, Dense2Dense>\n{\n  typedef Homogeneous<ArgType,Vertical> SrcXprType;\n  EIGEN_DEVICE_FUNC static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<Scalar,typename ArgType::Scalar> &)\n  {\n    Index dstRows = src.rows();\n    Index dstCols = src.cols();\n    if((dst.rows()!=dstRows) || (dst.cols()!=dstCols))\n      dst.resize(dstRows, dstCols);\n\n    dst.template topRows<ArgType::RowsAtCompileTime>(src.nestedExpression().rows()) = src.nestedExpression();\n    dst.row(dst.rows()-1).setOnes();\n  }\n};\n\n// dense = homogeneous\ntemplate< typename DstXprType, typename ArgType, typename Scalar>\nstruct Assignment<DstXprType, Homogeneous<ArgType,Horizontal>, internal::assign_op<Scalar,typename ArgType::Scalar>, Dense2Dense>\n{\n  typedef Homogeneous<ArgType,Horizontal> SrcXprType;\n  EIGEN_DEVICE_FUNC static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<Scalar,typename ArgType::Scalar> &)\n  {\n    Index dstRows = src.rows();\n    Index dstCols = src.cols();\n    if((dst.rows()!=dstRows) || (dst.cols()!=dstCols))\n      dst.resize(dstRows, dstCols);\n\n    dst.template leftCols<ArgType::ColsAtCompileTime>(src.nestedExpression().cols()) = src.nestedExpression();\n    dst.col(dst.cols()-1).setOnes();\n  }\n};\n\ntemplate<typename LhsArg, typename Rhs, int ProductTag>\nstruct generic_product_impl<Homogeneous<LhsArg,Horizontal>, Rhs, HomogeneousShape, DenseShape, ProductTag>\n{\n  template<typename Dest>\n  EIGEN_DEVICE_FUNC static void evalTo(Dest& dst, const Homogeneous<LhsArg,Horizontal>& lhs, const Rhs& rhs)\n  {\n    homogeneous_right_product_impl<Homogeneous<LhsArg,Horizontal>, Rhs>(lhs.nestedExpression(), rhs).evalTo(dst);\n  }\n};\n\ntemplate<typename Lhs,typename Rhs>\nstruct homogeneous_right_product_refactoring_helper\n{\n  enum {\n    Dim  = Lhs::ColsAtCompileTime,\n    Rows = Lhs::RowsAtCompileTime\n  };\n  typedef typename Rhs::template ConstNRowsBlockXpr<Dim>::Type          LinearBlockConst;\n  typedef typename remove_const<LinearBlockConst>::type                 LinearBlock;\n  typedef typename Rhs::ConstRowXpr                                     ConstantColumn;\n  typedef Replicate<const ConstantColumn,Rows,1>                        ConstantBlock;\n  typedef Product<Lhs,LinearBlock,LazyProduct>                          LinearProduct;\n  typedef CwiseBinaryOp<internal::scalar_sum_op<typename Lhs::Scalar,typename Rhs::Scalar>, const LinearProduct, const ConstantBlock> Xpr;\n};\n\ntemplate<typename Lhs, typename Rhs, int ProductTag>\nstruct product_evaluator<Product<Lhs, Rhs, LazyProduct>, ProductTag, HomogeneousShape, DenseShape>\n : public evaluator<typename homogeneous_right_product_refactoring_helper<typename Lhs::NestedExpression,Rhs>::Xpr>\n{\n  typedef Product<Lhs, Rhs, LazyProduct> XprType;\n  typedef homogeneous_right_product_refactoring_helper<typename Lhs::NestedExpression,Rhs> helper;\n  typedef typename helper::ConstantBlock ConstantBlock;\n  typedef typename helper::Xpr RefactoredXpr;\n  typedef evaluator<RefactoredXpr> Base;\n  \n  EIGEN_DEVICE_FUNC explicit product_evaluator(const XprType& xpr)\n    : Base(  xpr.lhs().nestedExpression() .lazyProduct(  xpr.rhs().template topRows<helper::Dim>(xpr.lhs().nestedExpression().cols()) )\n            + ConstantBlock(xpr.rhs().row(xpr.rhs().rows()-1),xpr.lhs().rows(), 1) )\n  {}\n};\n\ntemplate<typename Lhs, typename RhsArg, int ProductTag>\nstruct generic_product_impl<Lhs, Homogeneous<RhsArg,Vertical>, DenseShape, HomogeneousShape, ProductTag>\n{\n  template<typename Dest>\n  EIGEN_DEVICE_FUNC static void evalTo(Dest& dst, const Lhs& lhs, const Homogeneous<RhsArg,Vertical>& rhs)\n  {\n    homogeneous_left_product_impl<Homogeneous<RhsArg,Vertical>, Lhs>(lhs, rhs.nestedExpression()).evalTo(dst);\n  }\n};\n\n// TODO: the following specialization is to address a regression from 3.2 to 3.3\n// In the future, this path should be optimized.\ntemplate<typename Lhs, typename RhsArg, int ProductTag>\nstruct generic_product_impl<Lhs, Homogeneous<RhsArg,Vertical>, TriangularShape, HomogeneousShape, ProductTag>\n{\n  template<typename Dest>\n  static void evalTo(Dest& dst, const Lhs& lhs, const Homogeneous<RhsArg,Vertical>& rhs)\n  {\n    dst.noalias() = lhs * rhs.eval();\n  }\n};\n\ntemplate<typename Lhs,typename Rhs>\nstruct homogeneous_left_product_refactoring_helper\n{\n  enum {\n    Dim = Rhs::RowsAtCompileTime,\n    Cols = Rhs::ColsAtCompileTime\n  };\n  typedef typename Lhs::template ConstNColsBlockXpr<Dim>::Type          LinearBlockConst;\n  typedef typename remove_const<LinearBlockConst>::type                 LinearBlock;\n  typedef typename Lhs::ConstColXpr                                     ConstantColumn;\n  typedef Replicate<const ConstantColumn,1,Cols>                        ConstantBlock;\n  typedef Product<LinearBlock,Rhs,LazyProduct>                          LinearProduct;\n  typedef CwiseBinaryOp<internal::scalar_sum_op<typename Lhs::Scalar,typename Rhs::Scalar>, const LinearProduct, const ConstantBlock> Xpr;\n};\n\ntemplate<typename Lhs, typename Rhs, int ProductTag>\nstruct product_evaluator<Product<Lhs, Rhs, LazyProduct>, ProductTag, DenseShape, HomogeneousShape>\n : public evaluator<typename homogeneous_left_product_refactoring_helper<Lhs,typename Rhs::NestedExpression>::Xpr>\n{\n  typedef Product<Lhs, Rhs, LazyProduct> XprType;\n  typedef homogeneous_left_product_refactoring_helper<Lhs,typename Rhs::NestedExpression> helper;\n  typedef typename helper::ConstantBlock ConstantBlock;\n  typedef typename helper::Xpr RefactoredXpr;\n  typedef evaluator<RefactoredXpr> Base;\n  \n  EIGEN_DEVICE_FUNC explicit product_evaluator(const XprType& xpr)\n    : Base(   xpr.lhs().template leftCols<helper::Dim>(xpr.rhs().nestedExpression().rows()) .lazyProduct( xpr.rhs().nestedExpression() )\n            + ConstantBlock(xpr.lhs().col(xpr.lhs().cols()-1),1,xpr.rhs().cols()) )\n  {}\n};\n\ntemplate<typename Scalar, int Dim, int Mode,int Options, typename RhsArg, int ProductTag>\nstruct generic_product_impl<Transform<Scalar,Dim,Mode,Options>, Homogeneous<RhsArg,Vertical>, DenseShape, HomogeneousShape, ProductTag>\n{\n  typedef Transform<Scalar,Dim,Mode,Options> TransformType;\n  template<typename Dest>\n  EIGEN_DEVICE_FUNC static void evalTo(Dest& dst, const TransformType& lhs, const Homogeneous<RhsArg,Vertical>& rhs)\n  {\n    homogeneous_left_product_impl<Homogeneous<RhsArg,Vertical>, TransformType>(lhs, rhs.nestedExpression()).evalTo(dst);\n  }\n};\n\ntemplate<typename ExpressionType, int Side, bool Transposed>\nstruct permutation_matrix_product<ExpressionType, Side, Transposed, HomogeneousShape>\n  : public permutation_matrix_product<ExpressionType, Side, Transposed, DenseShape>\n{};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_HOMOGENEOUS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Geometry/Hyperplane.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_HYPERPLANE_H\n#define EIGEN_HYPERPLANE_H\n\nnamespace Eigen { \n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\class Hyperplane\n  *\n  * \\brief A hyperplane\n  *\n  * A hyperplane is an affine subspace of dimension n-1 in a space of dimension n.\n  * For example, a hyperplane in a plane is a line; a hyperplane in 3-space is a plane.\n  *\n  * \\tparam _Scalar the scalar type, i.e., the type of the coefficients\n  * \\tparam _AmbientDim the dimension of the ambient space, can be a compile time value or Dynamic.\n  *             Notice that the dimension of the hyperplane is _AmbientDim-1.\n  *\n  * This class represents an hyperplane as the zero set of the implicit equation\n  * \\f$ n \\cdot x + d = 0 \\f$ where \\f$ n \\f$ is a unit normal vector of the plane (linear part)\n  * and \\f$ d \\f$ is the distance (offset) to the origin.\n  */\ntemplate <typename _Scalar, int _AmbientDim, int _Options>\nclass Hyperplane\n{\npublic:\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_AmbientDim==Dynamic ? Dynamic : _AmbientDim+1)\n  enum {\n    AmbientDimAtCompileTime = _AmbientDim,\n    Options = _Options\n  };\n  typedef _Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n  typedef Matrix<Scalar,AmbientDimAtCompileTime,1> VectorType;\n  typedef Matrix<Scalar,Index(AmbientDimAtCompileTime)==Dynamic\n                        ? Dynamic\n                        : Index(AmbientDimAtCompileTime)+1,1,Options> Coefficients;\n  typedef Block<Coefficients,AmbientDimAtCompileTime,1> NormalReturnType;\n  typedef const Block<const Coefficients,AmbientDimAtCompileTime,1> ConstNormalReturnType;\n\n  /** Default constructor without initialization */\n  EIGEN_DEVICE_FUNC inline Hyperplane() {}\n  \n  template<int OtherOptions>\n  EIGEN_DEVICE_FUNC Hyperplane(const Hyperplane<Scalar,AmbientDimAtCompileTime,OtherOptions>& other)\n   : m_coeffs(other.coeffs())\n  {}\n\n  /** Constructs a dynamic-size hyperplane with \\a _dim the dimension\n    * of the ambient space */\n  EIGEN_DEVICE_FUNC inline explicit Hyperplane(Index _dim) : m_coeffs(_dim+1) {}\n\n  /** Construct a plane from its normal \\a n and a point \\a e onto the plane.\n    * \\warning the vector normal is assumed to be normalized.\n    */\n  EIGEN_DEVICE_FUNC inline Hyperplane(const VectorType& n, const VectorType& e)\n    : m_coeffs(n.size()+1)\n  {\n    normal() = n;\n    offset() = -n.dot(e);\n  }\n\n  /** Constructs a plane from its normal \\a n and distance to the origin \\a d\n    * such that the algebraic equation of the plane is \\f$ n \\cdot x + d = 0 \\f$.\n    * \\warning the vector normal is assumed to be normalized.\n    */\n  EIGEN_DEVICE_FUNC inline Hyperplane(const VectorType& n, const Scalar& d)\n    : m_coeffs(n.size()+1)\n  {\n    normal() = n;\n    offset() = d;\n  }\n\n  /** Constructs a hyperplane passing through the two points. If the dimension of the ambient space\n    * is greater than 2, then there isn't uniqueness, so an arbitrary choice is made.\n    */\n  EIGEN_DEVICE_FUNC static inline Hyperplane Through(const VectorType& p0, const VectorType& p1)\n  {\n    Hyperplane result(p0.size());\n    result.normal() = (p1 - p0).unitOrthogonal();\n    result.offset() = -p0.dot(result.normal());\n    return result;\n  }\n\n  /** Constructs a hyperplane passing through the three points. The dimension of the ambient space\n    * is required to be exactly 3.\n    */\n  EIGEN_DEVICE_FUNC static inline Hyperplane Through(const VectorType& p0, const VectorType& p1, const VectorType& p2)\n  {\n    EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(VectorType, 3)\n    Hyperplane result(p0.size());\n    VectorType v0(p2 - p0), v1(p1 - p0);\n    result.normal() = v0.cross(v1);\n    RealScalar norm = result.normal().norm();\n    if(norm <= v0.norm() * v1.norm() * NumTraits<RealScalar>::epsilon())\n    {\n      Matrix<Scalar,2,3> m; m << v0.transpose(), v1.transpose();\n      JacobiSVD<Matrix<Scalar,2,3> > svd(m, ComputeFullV);\n      result.normal() = svd.matrixV().col(2);\n    }\n    else\n      result.normal() /= norm;\n    result.offset() = -p0.dot(result.normal());\n    return result;\n  }\n\n  /** Constructs a hyperplane passing through the parametrized line \\a parametrized.\n    * If the dimension of the ambient space is greater than 2, then there isn't uniqueness,\n    * so an arbitrary choice is made.\n    */\n  // FIXME to be consistent with the rest this could be implemented as a static Through function ??\n  EIGEN_DEVICE_FUNC explicit Hyperplane(const ParametrizedLine<Scalar, AmbientDimAtCompileTime>& parametrized)\n  {\n    normal() = parametrized.direction().unitOrthogonal();\n    offset() = -parametrized.origin().dot(normal());\n  }\n\n  EIGEN_DEVICE_FUNC ~Hyperplane() {}\n\n  /** \\returns the dimension in which the plane holds */\n  EIGEN_DEVICE_FUNC inline Index dim() const { return AmbientDimAtCompileTime==Dynamic ? m_coeffs.size()-1 : Index(AmbientDimAtCompileTime); }\n\n  /** normalizes \\c *this */\n  EIGEN_DEVICE_FUNC void normalize(void)\n  {\n    m_coeffs /= normal().norm();\n  }\n\n  /** \\returns the signed distance between the plane \\c *this and a point \\a p.\n    * \\sa absDistance()\n    */\n  EIGEN_DEVICE_FUNC inline Scalar signedDistance(const VectorType& p) const { return normal().dot(p) + offset(); }\n\n  /** \\returns the absolute distance between the plane \\c *this and a point \\a p.\n    * \\sa signedDistance()\n    */\n  EIGEN_DEVICE_FUNC inline Scalar absDistance(const VectorType& p) const { return numext::abs(signedDistance(p)); }\n\n  /** \\returns the projection of a point \\a p onto the plane \\c *this.\n    */\n  EIGEN_DEVICE_FUNC inline VectorType projection(const VectorType& p) const { return p - signedDistance(p) * normal(); }\n\n  /** \\returns a constant reference to the unit normal vector of the plane, which corresponds\n    * to the linear part of the implicit equation.\n    */\n  EIGEN_DEVICE_FUNC inline ConstNormalReturnType normal() const { return ConstNormalReturnType(m_coeffs,0,0,dim(),1); }\n\n  /** \\returns a non-constant reference to the unit normal vector of the plane, which corresponds\n    * to the linear part of the implicit equation.\n    */\n  EIGEN_DEVICE_FUNC inline NormalReturnType normal() { return NormalReturnType(m_coeffs,0,0,dim(),1); }\n\n  /** \\returns the distance to the origin, which is also the \"constant term\" of the implicit equation\n    * \\warning the vector normal is assumed to be normalized.\n    */\n  EIGEN_DEVICE_FUNC inline const Scalar& offset() const { return m_coeffs.coeff(dim()); }\n\n  /** \\returns a non-constant reference to the distance to the origin, which is also the constant part\n    * of the implicit equation */\n  EIGEN_DEVICE_FUNC inline Scalar& offset() { return m_coeffs(dim()); }\n\n  /** \\returns a constant reference to the coefficients c_i of the plane equation:\n    * \\f$ c_0*x_0 + ... + c_{d-1}*x_{d-1} + c_d = 0 \\f$\n    */\n  EIGEN_DEVICE_FUNC inline const Coefficients& coeffs() const { return m_coeffs; }\n\n  /** \\returns a non-constant reference to the coefficients c_i of the plane equation:\n    * \\f$ c_0*x_0 + ... + c_{d-1}*x_{d-1} + c_d = 0 \\f$\n    */\n  EIGEN_DEVICE_FUNC inline Coefficients& coeffs() { return m_coeffs; }\n\n  /** \\returns the intersection of *this with \\a other.\n    *\n    * \\warning The ambient space must be a plane, i.e. have dimension 2, so that \\c *this and \\a other are lines.\n    *\n    * \\note If \\a other is approximately parallel to *this, this method will return any point on *this.\n    */\n  EIGEN_DEVICE_FUNC VectorType intersection(const Hyperplane& other) const\n  {\n    EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(VectorType, 2)\n    Scalar det = coeffs().coeff(0) * other.coeffs().coeff(1) - coeffs().coeff(1) * other.coeffs().coeff(0);\n    // since the line equations ax+by=c are normalized with a^2+b^2=1, the following tests\n    // whether the two lines are approximately parallel.\n    if(internal::isMuchSmallerThan(det, Scalar(1)))\n    {   // special case where the two lines are approximately parallel. Pick any point on the first line.\n        if(numext::abs(coeffs().coeff(1))>numext::abs(coeffs().coeff(0)))\n            return VectorType(coeffs().coeff(1), -coeffs().coeff(2)/coeffs().coeff(1)-coeffs().coeff(0));\n        else\n            return VectorType(-coeffs().coeff(2)/coeffs().coeff(0)-coeffs().coeff(1), coeffs().coeff(0));\n    }\n    else\n    {   // general case\n        Scalar invdet = Scalar(1) / det;\n        return VectorType(invdet*(coeffs().coeff(1)*other.coeffs().coeff(2)-other.coeffs().coeff(1)*coeffs().coeff(2)),\n                          invdet*(other.coeffs().coeff(0)*coeffs().coeff(2)-coeffs().coeff(0)*other.coeffs().coeff(2)));\n    }\n  }\n\n  /** Applies the transformation matrix \\a mat to \\c *this and returns a reference to \\c *this.\n    *\n    * \\param mat the Dim x Dim transformation matrix\n    * \\param traits specifies whether the matrix \\a mat represents an #Isometry\n    *               or a more generic #Affine transformation. The default is #Affine.\n    */\n  template<typename XprType>\n  EIGEN_DEVICE_FUNC inline Hyperplane& transform(const MatrixBase<XprType>& mat, TransformTraits traits = Affine)\n  {\n    if (traits==Affine)\n    {\n      normal() = mat.inverse().transpose() * normal();\n      m_coeffs /= normal().norm();\n    }\n    else if (traits==Isometry)\n      normal() = mat * normal();\n    else\n    {\n      eigen_assert(0 && \"invalid traits value in Hyperplane::transform()\");\n    }\n    return *this;\n  }\n\n  /** Applies the transformation \\a t to \\c *this and returns a reference to \\c *this.\n    *\n    * \\param t the transformation of dimension Dim\n    * \\param traits specifies whether the transformation \\a t represents an #Isometry\n    *               or a more generic #Affine transformation. The default is #Affine.\n    *               Other kind of transformations are not supported.\n    */\n  template<int TrOptions>\n  EIGEN_DEVICE_FUNC inline Hyperplane& transform(const Transform<Scalar,AmbientDimAtCompileTime,Affine,TrOptions>& t,\n                                TransformTraits traits = Affine)\n  {\n    transform(t.linear(), traits);\n    offset() -= normal().dot(t.translation());\n    return *this;\n  }\n\n  /** \\returns \\c *this with scalar type casted to \\a NewScalarType\n    *\n    * Note that if \\a NewScalarType is equal to the current scalar type of \\c *this\n    * then this function smartly returns a const reference to \\c *this.\n    */\n  template<typename NewScalarType>\n  EIGEN_DEVICE_FUNC inline typename internal::cast_return_type<Hyperplane,\n           Hyperplane<NewScalarType,AmbientDimAtCompileTime,Options> >::type cast() const\n  {\n    return typename internal::cast_return_type<Hyperplane,\n                    Hyperplane<NewScalarType,AmbientDimAtCompileTime,Options> >::type(*this);\n  }\n\n  /** Copy constructor with scalar type conversion */\n  template<typename OtherScalarType,int OtherOptions>\n  EIGEN_DEVICE_FUNC inline explicit Hyperplane(const Hyperplane<OtherScalarType,AmbientDimAtCompileTime,OtherOptions>& other)\n  { m_coeffs = other.coeffs().template cast<Scalar>(); }\n\n  /** \\returns \\c true if \\c *this is approximately equal to \\a other, within the precision\n    * determined by \\a prec.\n    *\n    * \\sa MatrixBase::isApprox() */\n  template<int OtherOptions>\n  EIGEN_DEVICE_FUNC bool isApprox(const Hyperplane<Scalar,AmbientDimAtCompileTime,OtherOptions>& other, const typename NumTraits<Scalar>::Real& prec = NumTraits<Scalar>::dummy_precision()) const\n  { return m_coeffs.isApprox(other.m_coeffs, prec); }\n\nprotected:\n\n  Coefficients m_coeffs;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_HYPERPLANE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Geometry/OrthoMethods.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ORTHOMETHODS_H\n#define EIGEN_ORTHOMETHODS_H\n\nnamespace Eigen { \n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\returns the cross product of \\c *this and \\a other\n  *\n  * Here is a very good explanation of cross-product: http://xkcd.com/199/\n  * \n  * With complex numbers, the cross product is implemented as\n  * \\f$ (\\mathbf{a}+i\\mathbf{b}) \\times (\\mathbf{c}+i\\mathbf{d}) = (\\mathbf{a} \\times \\mathbf{c} - \\mathbf{b} \\times \\mathbf{d}) - i(\\mathbf{a} \\times \\mathbf{d} - \\mathbf{b} \\times \\mathbf{c})\\f$\n  * \n  * \\sa MatrixBase::cross3()\n  */\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename MatrixBase<Derived>::template cross_product_return_type<OtherDerived>::type\n#else\ntypename MatrixBase<Derived>::PlainObject\n#endif\nMatrixBase<Derived>::cross(const MatrixBase<OtherDerived>& other) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Derived,3)\n  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(OtherDerived,3)\n\n  // Note that there is no need for an expression here since the compiler\n  // optimize such a small temporary very well (even within a complex expression)\n  typename internal::nested_eval<Derived,2>::type lhs(derived());\n  typename internal::nested_eval<OtherDerived,2>::type rhs(other.derived());\n  return typename cross_product_return_type<OtherDerived>::type(\n    numext::conj(lhs.coeff(1) * rhs.coeff(2) - lhs.coeff(2) * rhs.coeff(1)),\n    numext::conj(lhs.coeff(2) * rhs.coeff(0) - lhs.coeff(0) * rhs.coeff(2)),\n    numext::conj(lhs.coeff(0) * rhs.coeff(1) - lhs.coeff(1) * rhs.coeff(0))\n  );\n}\n\nnamespace internal {\n\ntemplate< int Arch,typename VectorLhs,typename VectorRhs,\n          typename Scalar = typename VectorLhs::Scalar,\n          bool Vectorizable = bool((VectorLhs::Flags&VectorRhs::Flags)&PacketAccessBit)>\nstruct cross3_impl {\n  EIGEN_DEVICE_FUNC static inline typename internal::plain_matrix_type<VectorLhs>::type\n  run(const VectorLhs& lhs, const VectorRhs& rhs)\n  {\n    return typename internal::plain_matrix_type<VectorLhs>::type(\n      numext::conj(lhs.coeff(1) * rhs.coeff(2) - lhs.coeff(2) * rhs.coeff(1)),\n      numext::conj(lhs.coeff(2) * rhs.coeff(0) - lhs.coeff(0) * rhs.coeff(2)),\n      numext::conj(lhs.coeff(0) * rhs.coeff(1) - lhs.coeff(1) * rhs.coeff(0)),\n      0\n    );\n  }\n};\n\n}\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\returns the cross product of \\c *this and \\a other using only the x, y, and z coefficients\n  *\n  * The size of \\c *this and \\a other must be four. This function is especially useful\n  * when using 4D vectors instead of 3D ones to get advantage of SSE/AltiVec vectorization.\n  *\n  * \\sa MatrixBase::cross()\n  */\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC inline typename MatrixBase<Derived>::PlainObject\nMatrixBase<Derived>::cross3(const MatrixBase<OtherDerived>& other) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Derived,4)\n  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(OtherDerived,4)\n\n  typedef typename internal::nested_eval<Derived,2>::type DerivedNested;\n  typedef typename internal::nested_eval<OtherDerived,2>::type OtherDerivedNested;\n  DerivedNested lhs(derived());\n  OtherDerivedNested rhs(other.derived());\n\n  return internal::cross3_impl<Architecture::Target,\n                        typename internal::remove_all<DerivedNested>::type,\n                        typename internal::remove_all<OtherDerivedNested>::type>::run(lhs,rhs);\n}\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\returns a matrix expression of the cross product of each column or row\n  * of the referenced expression with the \\a other vector.\n  *\n  * The referenced matrix must have one dimension equal to 3.\n  * The result matrix has the same dimensions than the referenced one.\n  *\n  * \\sa MatrixBase::cross() */\ntemplate<typename ExpressionType, int Direction>\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC \nconst typename VectorwiseOp<ExpressionType,Direction>::CrossReturnType\nVectorwiseOp<ExpressionType,Direction>::cross(const MatrixBase<OtherDerived>& other) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(OtherDerived,3)\n  EIGEN_STATIC_ASSERT((internal::is_same<Scalar, typename OtherDerived::Scalar>::value),\n    YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n  \n  typename internal::nested_eval<ExpressionType,2>::type mat(_expression());\n  typename internal::nested_eval<OtherDerived,2>::type vec(other.derived());\n\n  CrossReturnType res(_expression().rows(),_expression().cols());\n  if(Direction==Vertical)\n  {\n    eigen_assert(CrossReturnType::RowsAtCompileTime==3 && \"the matrix must have exactly 3 rows\");\n    res.row(0) = (mat.row(1) * vec.coeff(2) - mat.row(2) * vec.coeff(1)).conjugate();\n    res.row(1) = (mat.row(2) * vec.coeff(0) - mat.row(0) * vec.coeff(2)).conjugate();\n    res.row(2) = (mat.row(0) * vec.coeff(1) - mat.row(1) * vec.coeff(0)).conjugate();\n  }\n  else\n  {\n    eigen_assert(CrossReturnType::ColsAtCompileTime==3 && \"the matrix must have exactly 3 columns\");\n    res.col(0) = (mat.col(1) * vec.coeff(2) - mat.col(2) * vec.coeff(1)).conjugate();\n    res.col(1) = (mat.col(2) * vec.coeff(0) - mat.col(0) * vec.coeff(2)).conjugate();\n    res.col(2) = (mat.col(0) * vec.coeff(1) - mat.col(1) * vec.coeff(0)).conjugate();\n  }\n  return res;\n}\n\nnamespace internal {\n\ntemplate<typename Derived, int Size = Derived::SizeAtCompileTime>\nstruct unitOrthogonal_selector\n{\n  typedef typename plain_matrix_type<Derived>::type VectorType;\n  typedef typename traits<Derived>::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar,2,1> Vector2;\n  EIGEN_DEVICE_FUNC\n  static inline VectorType run(const Derived& src)\n  {\n    VectorType perp = VectorType::Zero(src.size());\n    Index maxi = 0;\n    Index sndi = 0;\n    src.cwiseAbs().maxCoeff(&maxi);\n    if (maxi==0)\n      sndi = 1;\n    RealScalar invnm = RealScalar(1)/(Vector2() << src.coeff(sndi),src.coeff(maxi)).finished().norm();\n    perp.coeffRef(maxi) = -numext::conj(src.coeff(sndi)) * invnm;\n    perp.coeffRef(sndi) =  numext::conj(src.coeff(maxi)) * invnm;\n\n    return perp;\n   }\n};\n\ntemplate<typename Derived>\nstruct unitOrthogonal_selector<Derived,3>\n{\n  typedef typename plain_matrix_type<Derived>::type VectorType;\n  typedef typename traits<Derived>::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  EIGEN_DEVICE_FUNC\n  static inline VectorType run(const Derived& src)\n  {\n    VectorType perp;\n    /* Let us compute the crossed product of *this with a vector\n     * that is not too close to being colinear to *this.\n     */\n\n    /* unless the x and y coords are both close to zero, we can\n     * simply take ( -y, x, 0 ) and normalize it.\n     */\n    if((!isMuchSmallerThan(src.x(), src.z()))\n    || (!isMuchSmallerThan(src.y(), src.z())))\n    {\n      RealScalar invnm = RealScalar(1)/src.template head<2>().norm();\n      perp.coeffRef(0) = -numext::conj(src.y())*invnm;\n      perp.coeffRef(1) = numext::conj(src.x())*invnm;\n      perp.coeffRef(2) = 0;\n    }\n    /* if both x and y are close to zero, then the vector is close\n     * to the z-axis, so it's far from colinear to the x-axis for instance.\n     * So we take the crossed product with (1,0,0) and normalize it.\n     */\n    else\n    {\n      RealScalar invnm = RealScalar(1)/src.template tail<2>().norm();\n      perp.coeffRef(0) = 0;\n      perp.coeffRef(1) = -numext::conj(src.z())*invnm;\n      perp.coeffRef(2) = numext::conj(src.y())*invnm;\n    }\n\n    return perp;\n   }\n};\n\ntemplate<typename Derived>\nstruct unitOrthogonal_selector<Derived,2>\n{\n  typedef typename plain_matrix_type<Derived>::type VectorType;\n  EIGEN_DEVICE_FUNC\n  static inline VectorType run(const Derived& src)\n  { return VectorType(-numext::conj(src.y()), numext::conj(src.x())).normalized(); }\n};\n\n} // end namespace internal\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\returns a unit vector which is orthogonal to \\c *this\n  *\n  * The size of \\c *this must be at least 2. If the size is exactly 2,\n  * then the returned vector is a counter clock wise rotation of \\c *this, i.e., (-y,x).normalized().\n  *\n  * \\sa cross()\n  */\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC typename MatrixBase<Derived>::PlainObject\nMatrixBase<Derived>::unitOrthogonal() const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return internal::unitOrthogonal_selector<Derived>::run(derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_ORTHOMETHODS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Geometry/ParametrizedLine.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_PARAMETRIZEDLINE_H\n#define EIGEN_PARAMETRIZEDLINE_H\n\nnamespace Eigen { \n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\class ParametrizedLine\n  *\n  * \\brief A parametrized line\n  *\n  * A parametrized line is defined by an origin point \\f$ \\mathbf{o} \\f$ and a unit\n  * direction vector \\f$ \\mathbf{d} \\f$ such that the line corresponds to\n  * the set \\f$ l(t) = \\mathbf{o} + t \\mathbf{d} \\f$, \\f$ t \\in \\mathbf{R} \\f$.\n  *\n  * \\tparam _Scalar the scalar type, i.e., the type of the coefficients\n  * \\tparam _AmbientDim the dimension of the ambient space, can be a compile time value or Dynamic.\n  */\ntemplate <typename _Scalar, int _AmbientDim, int _Options>\nclass ParametrizedLine\n{\npublic:\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_AmbientDim)\n  enum {\n    AmbientDimAtCompileTime = _AmbientDim,\n    Options = _Options\n  };\n  typedef _Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n  typedef Matrix<Scalar,AmbientDimAtCompileTime,1,Options> VectorType;\n\n  /** Default constructor without initialization */\n  EIGEN_DEVICE_FUNC inline ParametrizedLine() {}\n  \n  template<int OtherOptions>\n  EIGEN_DEVICE_FUNC ParametrizedLine(const ParametrizedLine<Scalar,AmbientDimAtCompileTime,OtherOptions>& other)\n   : m_origin(other.origin()), m_direction(other.direction())\n  {}\n\n  /** Constructs a dynamic-size line with \\a _dim the dimension\n    * of the ambient space */\n  EIGEN_DEVICE_FUNC inline explicit ParametrizedLine(Index _dim) : m_origin(_dim), m_direction(_dim) {}\n\n  /** Initializes a parametrized line of direction \\a direction and origin \\a origin.\n    * \\warning the vector direction is assumed to be normalized.\n    */\n  EIGEN_DEVICE_FUNC ParametrizedLine(const VectorType& origin, const VectorType& direction)\n    : m_origin(origin), m_direction(direction) {}\n\n  template <int OtherOptions>\n  EIGEN_DEVICE_FUNC explicit ParametrizedLine(const Hyperplane<_Scalar, _AmbientDim, OtherOptions>& hyperplane);\n\n  /** Constructs a parametrized line going from \\a p0 to \\a p1. */\n  EIGEN_DEVICE_FUNC static inline ParametrizedLine Through(const VectorType& p0, const VectorType& p1)\n  { return ParametrizedLine(p0, (p1-p0).normalized()); }\n\n  EIGEN_DEVICE_FUNC ~ParametrizedLine() {}\n\n  /** \\returns the dimension in which the line holds */\n  EIGEN_DEVICE_FUNC inline Index dim() const { return m_direction.size(); }\n\n  EIGEN_DEVICE_FUNC const VectorType& origin() const { return m_origin; }\n  EIGEN_DEVICE_FUNC VectorType& origin() { return m_origin; }\n\n  EIGEN_DEVICE_FUNC const VectorType& direction() const { return m_direction; }\n  EIGEN_DEVICE_FUNC VectorType& direction() { return m_direction; }\n\n  /** \\returns the squared distance of a point \\a p to its projection onto the line \\c *this.\n    * \\sa distance()\n    */\n  EIGEN_DEVICE_FUNC RealScalar squaredDistance(const VectorType& p) const\n  {\n    VectorType diff = p - origin();\n    return (diff - direction().dot(diff) * direction()).squaredNorm();\n  }\n  /** \\returns the distance of a point \\a p to its projection onto the line \\c *this.\n    * \\sa squaredDistance()\n    */\n  EIGEN_DEVICE_FUNC RealScalar distance(const VectorType& p) const { EIGEN_USING_STD(sqrt) return sqrt(squaredDistance(p)); }\n\n  /** \\returns the projection of a point \\a p onto the line \\c *this. */\n  EIGEN_DEVICE_FUNC VectorType projection(const VectorType& p) const\n  { return origin() + direction().dot(p-origin()) * direction(); }\n\n  EIGEN_DEVICE_FUNC VectorType pointAt(const Scalar& t) const;\n  \n  template <int OtherOptions>\n  EIGEN_DEVICE_FUNC Scalar intersectionParameter(const Hyperplane<_Scalar, _AmbientDim, OtherOptions>& hyperplane) const;\n \n  template <int OtherOptions>\n  EIGEN_DEVICE_FUNC Scalar intersection(const Hyperplane<_Scalar, _AmbientDim, OtherOptions>& hyperplane) const;\n  \n  template <int OtherOptions>\n  EIGEN_DEVICE_FUNC VectorType intersectionPoint(const Hyperplane<_Scalar, _AmbientDim, OtherOptions>& hyperplane) const;\n\n  /** Applies the transformation matrix \\a mat to \\c *this and returns a reference to \\c *this.\n    *\n    * \\param mat the Dim x Dim transformation matrix\n    * \\param traits specifies whether the matrix \\a mat represents an #Isometry\n    *               or a more generic #Affine transformation. The default is #Affine.\n    */\n  template<typename XprType>\n  EIGEN_DEVICE_FUNC inline ParametrizedLine& transform(const MatrixBase<XprType>& mat, TransformTraits traits = Affine)\n  {\n    if (traits==Affine)\n      direction() = (mat * direction()).normalized();\n    else if (traits==Isometry)\n      direction() = mat * direction();\n    else\n    {\n      eigen_assert(0 && \"invalid traits value in ParametrizedLine::transform()\");\n    }\n    origin() = mat * origin();\n    return *this;\n  }\n\n  /** Applies the transformation \\a t to \\c *this and returns a reference to \\c *this.\n    *\n    * \\param t the transformation of dimension Dim\n    * \\param traits specifies whether the transformation \\a t represents an #Isometry\n    *               or a more generic #Affine transformation. The default is #Affine.\n    *               Other kind of transformations are not supported.\n    */\n  template<int TrOptions>\n  EIGEN_DEVICE_FUNC inline ParametrizedLine& transform(const Transform<Scalar,AmbientDimAtCompileTime,Affine,TrOptions>& t,\n                                                       TransformTraits traits = Affine)\n  {\n    transform(t.linear(), traits);\n    origin() += t.translation();\n    return *this;\n  }\n\n/** \\returns \\c *this with scalar type casted to \\a NewScalarType\n    *\n    * Note that if \\a NewScalarType is equal to the current scalar type of \\c *this\n    * then this function smartly returns a const reference to \\c *this.\n    */\n  template<typename NewScalarType>\n  EIGEN_DEVICE_FUNC inline typename internal::cast_return_type<ParametrizedLine,\n           ParametrizedLine<NewScalarType,AmbientDimAtCompileTime,Options> >::type cast() const\n  {\n    return typename internal::cast_return_type<ParametrizedLine,\n                    ParametrizedLine<NewScalarType,AmbientDimAtCompileTime,Options> >::type(*this);\n  }\n\n  /** Copy constructor with scalar type conversion */\n  template<typename OtherScalarType,int OtherOptions>\n  EIGEN_DEVICE_FUNC inline explicit ParametrizedLine(const ParametrizedLine<OtherScalarType,AmbientDimAtCompileTime,OtherOptions>& other)\n  {\n    m_origin = other.origin().template cast<Scalar>();\n    m_direction = other.direction().template cast<Scalar>();\n  }\n\n  /** \\returns \\c true if \\c *this is approximately equal to \\a other, within the precision\n    * determined by \\a prec.\n    *\n    * \\sa MatrixBase::isApprox() */\n  EIGEN_DEVICE_FUNC bool isApprox(const ParametrizedLine& other, const typename NumTraits<Scalar>::Real& prec = NumTraits<Scalar>::dummy_precision()) const\n  { return m_origin.isApprox(other.m_origin, prec) && m_direction.isApprox(other.m_direction, prec); }\n\nprotected:\n\n  VectorType m_origin, m_direction;\n};\n\n/** Constructs a parametrized line from a 2D hyperplane\n  *\n  * \\warning the ambient space must have dimension 2 such that the hyperplane actually describes a line\n  */\ntemplate <typename _Scalar, int _AmbientDim, int _Options>\ntemplate <int OtherOptions>\nEIGEN_DEVICE_FUNC inline ParametrizedLine<_Scalar, _AmbientDim,_Options>::ParametrizedLine(const Hyperplane<_Scalar, _AmbientDim,OtherOptions>& hyperplane)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(VectorType, 2)\n  direction() = hyperplane.normal().unitOrthogonal();\n  origin() = -hyperplane.normal()*hyperplane.offset();\n}\n\n/** \\returns the point at \\a t along this line\n  */\ntemplate <typename _Scalar, int _AmbientDim, int _Options>\nEIGEN_DEVICE_FUNC inline typename ParametrizedLine<_Scalar, _AmbientDim,_Options>::VectorType\nParametrizedLine<_Scalar, _AmbientDim,_Options>::pointAt(const _Scalar& t) const\n{\n  return origin() + (direction()*t); \n}\n\n/** \\returns the parameter value of the intersection between \\c *this and the given \\a hyperplane\n  */\ntemplate <typename _Scalar, int _AmbientDim, int _Options>\ntemplate <int OtherOptions>\nEIGEN_DEVICE_FUNC inline _Scalar ParametrizedLine<_Scalar, _AmbientDim,_Options>::intersectionParameter(const Hyperplane<_Scalar, _AmbientDim, OtherOptions>& hyperplane) const\n{\n  return -(hyperplane.offset()+hyperplane.normal().dot(origin()))\n          / hyperplane.normal().dot(direction());\n}\n\n\n/** \\deprecated use intersectionParameter()\n  * \\returns the parameter value of the intersection between \\c *this and the given \\a hyperplane\n  */\ntemplate <typename _Scalar, int _AmbientDim, int _Options>\ntemplate <int OtherOptions>\nEIGEN_DEVICE_FUNC inline _Scalar ParametrizedLine<_Scalar, _AmbientDim,_Options>::intersection(const Hyperplane<_Scalar, _AmbientDim, OtherOptions>& hyperplane) const\n{\n  return intersectionParameter(hyperplane);\n}\n\n/** \\returns the point of the intersection between \\c *this and the given hyperplane\n  */\ntemplate <typename _Scalar, int _AmbientDim, int _Options>\ntemplate <int OtherOptions>\nEIGEN_DEVICE_FUNC inline typename ParametrizedLine<_Scalar, _AmbientDim,_Options>::VectorType\nParametrizedLine<_Scalar, _AmbientDim,_Options>::intersectionPoint(const Hyperplane<_Scalar, _AmbientDim, OtherOptions>& hyperplane) const\n{\n  return pointAt(intersectionParameter(hyperplane));\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_PARAMETRIZEDLINE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Geometry/Quaternion.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Mathieu Gautier <mathieu.gautier@cea.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_QUATERNION_H\n#define EIGEN_QUATERNION_H\nnamespace Eigen { \n\n\n/***************************************************************************\n* Definition of QuaternionBase<Derived>\n* The implementation is at the end of the file\n***************************************************************************/\n\nnamespace internal {\ntemplate<typename Other,\n         int OtherRows=Other::RowsAtCompileTime,\n         int OtherCols=Other::ColsAtCompileTime>\nstruct quaternionbase_assign_impl;\n}\n\n/** \\geometry_module \\ingroup Geometry_Module\n  * \\class QuaternionBase\n  * \\brief Base class for quaternion expressions\n  * \\tparam Derived derived type (CRTP)\n  * \\sa class Quaternion\n  */\ntemplate<class Derived>\nclass QuaternionBase : public RotationBase<Derived, 3>\n{\n public:\n  typedef RotationBase<Derived, 3> Base;\n\n  using Base::operator*;\n  using Base::derived;\n\n  typedef typename internal::traits<Derived>::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef typename internal::traits<Derived>::Coefficients Coefficients;\n  typedef typename Coefficients::CoeffReturnType CoeffReturnType;\n  typedef typename internal::conditional<bool(internal::traits<Derived>::Flags&LvalueBit),\n                                        Scalar&, CoeffReturnType>::type NonConstCoeffReturnType;\n\n\n  enum {\n    Flags = Eigen::internal::traits<Derived>::Flags\n  };\n\n // typedef typename Matrix<Scalar,4,1> Coefficients;\n  /** the type of a 3D vector */\n  typedef Matrix<Scalar,3,1> Vector3;\n  /** the equivalent rotation matrix type */\n  typedef Matrix<Scalar,3,3> Matrix3;\n  /** the equivalent angle-axis type */\n  typedef AngleAxis<Scalar> AngleAxisType;\n\n\n\n  /** \\returns the \\c x coefficient */\n  EIGEN_DEVICE_FUNC inline CoeffReturnType x() const { return this->derived().coeffs().coeff(0); }\n  /** \\returns the \\c y coefficient */\n  EIGEN_DEVICE_FUNC inline CoeffReturnType y() const { return this->derived().coeffs().coeff(1); }\n  /** \\returns the \\c z coefficient */\n  EIGEN_DEVICE_FUNC inline CoeffReturnType z() const { return this->derived().coeffs().coeff(2); }\n  /** \\returns the \\c w coefficient */\n  EIGEN_DEVICE_FUNC inline CoeffReturnType w() const { return this->derived().coeffs().coeff(3); }\n\n  /** \\returns a reference to the \\c x coefficient (if Derived is a non-const lvalue) */\n  EIGEN_DEVICE_FUNC inline NonConstCoeffReturnType x() { return this->derived().coeffs().x(); }\n  /** \\returns a reference to the \\c y coefficient (if Derived is a non-const lvalue) */\n  EIGEN_DEVICE_FUNC inline NonConstCoeffReturnType y() { return this->derived().coeffs().y(); }\n  /** \\returns a reference to the \\c z coefficient (if Derived is a non-const lvalue) */\n  EIGEN_DEVICE_FUNC inline NonConstCoeffReturnType z() { return this->derived().coeffs().z(); }\n  /** \\returns a reference to the \\c w coefficient (if Derived is a non-const lvalue) */\n  EIGEN_DEVICE_FUNC inline NonConstCoeffReturnType w() { return this->derived().coeffs().w(); }\n\n  /** \\returns a read-only vector expression of the imaginary part (x,y,z) */\n  EIGEN_DEVICE_FUNC inline const VectorBlock<const Coefficients,3> vec() const { return coeffs().template head<3>(); }\n\n  /** \\returns a vector expression of the imaginary part (x,y,z) */\n  EIGEN_DEVICE_FUNC inline VectorBlock<Coefficients,3> vec() { return coeffs().template head<3>(); }\n\n  /** \\returns a read-only vector expression of the coefficients (x,y,z,w) */\n  EIGEN_DEVICE_FUNC inline const typename internal::traits<Derived>::Coefficients& coeffs() const { return derived().coeffs(); }\n\n  /** \\returns a vector expression of the coefficients (x,y,z,w) */\n  EIGEN_DEVICE_FUNC inline typename internal::traits<Derived>::Coefficients& coeffs() { return derived().coeffs(); }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE QuaternionBase<Derived>& operator=(const QuaternionBase<Derived>& other);\n  template<class OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const QuaternionBase<OtherDerived>& other);\n\n// disabled this copy operator as it is giving very strange compilation errors when compiling\n// test_stdvector with GCC 4.4.2. This looks like a GCC bug though, so feel free to re-enable it if it's\n// useful; however notice that we already have the templated operator= above and e.g. in MatrixBase\n// we didn't have to add, in addition to templated operator=, such a non-templated copy operator.\n//  Derived& operator=(const QuaternionBase& other)\n//  { return operator=<Derived>(other); }\n\n  EIGEN_DEVICE_FUNC Derived& operator=(const AngleAxisType& aa);\n  template<class OtherDerived> EIGEN_DEVICE_FUNC Derived& operator=(const MatrixBase<OtherDerived>& m);\n\n  /** \\returns a quaternion representing an identity rotation\n    * \\sa MatrixBase::Identity()\n    */\n  EIGEN_DEVICE_FUNC static inline Quaternion<Scalar> Identity() { return Quaternion<Scalar>(Scalar(1), Scalar(0), Scalar(0), Scalar(0)); }\n\n  /** \\sa QuaternionBase::Identity(), MatrixBase::setIdentity()\n    */\n  EIGEN_DEVICE_FUNC inline QuaternionBase& setIdentity() { coeffs() << Scalar(0), Scalar(0), Scalar(0), Scalar(1); return *this; }\n\n  /** \\returns the squared norm of the quaternion's coefficients\n    * \\sa QuaternionBase::norm(), MatrixBase::squaredNorm()\n    */\n  EIGEN_DEVICE_FUNC inline Scalar squaredNorm() const { return coeffs().squaredNorm(); }\n\n  /** \\returns the norm of the quaternion's coefficients\n    * \\sa QuaternionBase::squaredNorm(), MatrixBase::norm()\n    */\n  EIGEN_DEVICE_FUNC inline Scalar norm() const { return coeffs().norm(); }\n\n  /** Normalizes the quaternion \\c *this\n    * \\sa normalized(), MatrixBase::normalize() */\n  EIGEN_DEVICE_FUNC inline void normalize() { coeffs().normalize(); }\n  /** \\returns a normalized copy of \\c *this\n    * \\sa normalize(), MatrixBase::normalized() */\n  EIGEN_DEVICE_FUNC inline Quaternion<Scalar> normalized() const { return Quaternion<Scalar>(coeffs().normalized()); }\n\n    /** \\returns the dot product of \\c *this and \\a other\n    * Geometrically speaking, the dot product of two unit quaternions\n    * corresponds to the cosine of half the angle between the two rotations.\n    * \\sa angularDistance()\n    */\n  template<class OtherDerived> EIGEN_DEVICE_FUNC inline Scalar dot(const QuaternionBase<OtherDerived>& other) const { return coeffs().dot(other.coeffs()); }\n\n  template<class OtherDerived> EIGEN_DEVICE_FUNC Scalar angularDistance(const QuaternionBase<OtherDerived>& other) const;\n\n  /** \\returns an equivalent 3x3 rotation matrix */\n  EIGEN_DEVICE_FUNC inline Matrix3 toRotationMatrix() const;\n\n  /** \\returns the quaternion which transform \\a a into \\a b through a rotation */\n  template<typename Derived1, typename Derived2>\n  EIGEN_DEVICE_FUNC Derived& setFromTwoVectors(const MatrixBase<Derived1>& a, const MatrixBase<Derived2>& b);\n\n  template<class OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Quaternion<Scalar> operator* (const QuaternionBase<OtherDerived>& q) const;\n  template<class OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator*= (const QuaternionBase<OtherDerived>& q);\n\n  /** \\returns the quaternion describing the inverse rotation */\n  EIGEN_DEVICE_FUNC Quaternion<Scalar> inverse() const;\n\n  /** \\returns the conjugated quaternion */\n  EIGEN_DEVICE_FUNC Quaternion<Scalar> conjugate() const;\n\n  template<class OtherDerived> EIGEN_DEVICE_FUNC Quaternion<Scalar> slerp(const Scalar& t, const QuaternionBase<OtherDerived>& other) const;\n\n  /** \\returns true if each coefficients of \\c *this and \\a other are all exactly equal.\n    * \\warning When using floating point scalar values you probably should rather use a\n    *          fuzzy comparison such as isApprox()\n    * \\sa isApprox(), operator!= */\n  template<class OtherDerived>\n  EIGEN_DEVICE_FUNC inline bool operator==(const QuaternionBase<OtherDerived>& other) const\n  { return coeffs() == other.coeffs(); }\n\n  /** \\returns true if at least one pair of coefficients of \\c *this and \\a other are not exactly equal to each other.\n    * \\warning When using floating point scalar values you probably should rather use a\n    *          fuzzy comparison such as isApprox()\n    * \\sa isApprox(), operator== */\n  template<class OtherDerived>\n  EIGEN_DEVICE_FUNC inline bool operator!=(const QuaternionBase<OtherDerived>& other) const\n  { return coeffs() != other.coeffs(); }\n\n  /** \\returns \\c true if \\c *this is approximately equal to \\a other, within the precision\n    * determined by \\a prec.\n    *\n    * \\sa MatrixBase::isApprox() */\n  template<class OtherDerived>\n  EIGEN_DEVICE_FUNC bool isApprox(const QuaternionBase<OtherDerived>& other, const RealScalar& prec = NumTraits<Scalar>::dummy_precision()) const\n  { return coeffs().isApprox(other.coeffs(), prec); }\n\n  /** return the result vector of \\a v through the rotation*/\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Vector3 _transformVector(const Vector3& v) const;\n\n  #ifdef EIGEN_PARSED_BY_DOXYGEN\n  /** \\returns \\c *this with scalar type casted to \\a NewScalarType\n    *\n    * Note that if \\a NewScalarType is equal to the current scalar type of \\c *this\n    * then this function smartly returns a const reference to \\c *this.\n    */\n  template<typename NewScalarType>\n  EIGEN_DEVICE_FUNC inline typename internal::cast_return_type<Derived,Quaternion<NewScalarType> >::type cast() const;\n\n  #else\n\n  template<typename NewScalarType>\n  EIGEN_DEVICE_FUNC inline\n  typename internal::enable_if<internal::is_same<Scalar,NewScalarType>::value,const Derived&>::type cast() const\n  {\n    return derived();\n  }\n\n  template<typename NewScalarType>\n  EIGEN_DEVICE_FUNC inline\n  typename internal::enable_if<!internal::is_same<Scalar,NewScalarType>::value,Quaternion<NewScalarType> >::type cast() const\n  {\n    return Quaternion<NewScalarType>(coeffs().template cast<NewScalarType>());\n  }\n  #endif\n\n#ifndef EIGEN_NO_IO\n  friend std::ostream& operator<<(std::ostream& s, const QuaternionBase<Derived>& q) {\n    s << q.x() << \"i + \" << q.y() << \"j + \" << q.z() << \"k\" << \" + \" << q.w();\n    return s;\n  }\n#endif\n\n#ifdef EIGEN_QUATERNIONBASE_PLUGIN\n# include EIGEN_QUATERNIONBASE_PLUGIN\n#endif\nprotected:\n  EIGEN_DEFAULT_COPY_CONSTRUCTOR(QuaternionBase)\n  EIGEN_DEFAULT_EMPTY_CONSTRUCTOR_AND_DESTRUCTOR(QuaternionBase)\n};\n\n/***************************************************************************\n* Definition/implementation of Quaternion<Scalar>\n***************************************************************************/\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\class Quaternion\n  *\n  * \\brief The quaternion class used to represent 3D orientations and rotations\n  *\n  * \\tparam _Scalar the scalar type, i.e., the type of the coefficients\n  * \\tparam _Options controls the memory alignment of the coefficients. Can be \\# AutoAlign or \\# DontAlign. Default is AutoAlign.\n  *\n  * This class represents a quaternion \\f$ w+xi+yj+zk \\f$ that is a convenient representation of\n  * orientations and rotations of objects in three dimensions. Compared to other representations\n  * like Euler angles or 3x3 matrices, quaternions offer the following advantages:\n  * \\li \\b compact storage (4 scalars)\n  * \\li \\b efficient to compose (28 flops),\n  * \\li \\b stable spherical interpolation\n  *\n  * The following two typedefs are provided for convenience:\n  * \\li \\c Quaternionf for \\c float\n  * \\li \\c Quaterniond for \\c double\n  *\n  * \\warning Operations interpreting the quaternion as rotation have undefined behavior if the quaternion is not normalized.\n  *\n  * \\sa  class AngleAxis, class Transform\n  */\n\nnamespace internal {\ntemplate<typename _Scalar,int _Options>\nstruct traits<Quaternion<_Scalar,_Options> >\n{\n  typedef Quaternion<_Scalar,_Options> PlainObject;\n  typedef _Scalar Scalar;\n  typedef Matrix<_Scalar,4,1,_Options> Coefficients;\n  enum{\n    Alignment = internal::traits<Coefficients>::Alignment,\n    Flags = LvalueBit\n  };\n};\n}\n\ntemplate<typename _Scalar, int _Options>\nclass Quaternion : public QuaternionBase<Quaternion<_Scalar,_Options> >\n{\npublic:\n  typedef QuaternionBase<Quaternion<_Scalar,_Options> > Base;\n  enum { NeedsAlignment = internal::traits<Quaternion>::Alignment>0 };\n\n  typedef _Scalar Scalar;\n\n  EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Quaternion)\n  using Base::operator*=;\n\n  typedef typename internal::traits<Quaternion>::Coefficients Coefficients;\n  typedef typename Base::AngleAxisType AngleAxisType;\n\n  /** Default constructor leaving the quaternion uninitialized. */\n  EIGEN_DEVICE_FUNC inline Quaternion() {}\n\n  /** Constructs and initializes the quaternion \\f$ w+xi+yj+zk \\f$ from\n    * its four coefficients \\a w, \\a x, \\a y and \\a z.\n    *\n    * \\warning Note the order of the arguments: the real \\a w coefficient first,\n    * while internally the coefficients are stored in the following order:\n    * [\\c x, \\c y, \\c z, \\c w]\n    */\n  EIGEN_DEVICE_FUNC inline Quaternion(const Scalar& w, const Scalar& x, const Scalar& y, const Scalar& z) : m_coeffs(x, y, z, w){}\n\n  /** Constructs and initialize a quaternion from the array data */\n  EIGEN_DEVICE_FUNC explicit inline Quaternion(const Scalar* data) : m_coeffs(data) {}\n\n  /** Copy constructor */\n  template<class Derived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Quaternion(const QuaternionBase<Derived>& other) { this->Base::operator=(other); }\n\n  /** Constructs and initializes a quaternion from the angle-axis \\a aa */\n  EIGEN_DEVICE_FUNC explicit inline Quaternion(const AngleAxisType& aa) { *this = aa; }\n\n  /** Constructs and initializes a quaternion from either:\n    *  - a rotation matrix expression,\n    *  - a 4D vector expression representing quaternion coefficients.\n    */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC explicit inline Quaternion(const MatrixBase<Derived>& other) { *this = other; }\n\n  /** Explicit copy constructor with scalar conversion */\n  template<typename OtherScalar, int OtherOptions>\n  EIGEN_DEVICE_FUNC explicit inline Quaternion(const Quaternion<OtherScalar, OtherOptions>& other)\n  { m_coeffs = other.coeffs().template cast<Scalar>(); }\n\n#if EIGEN_HAS_RVALUE_REFERENCES\n  // We define a copy constructor, which means we don't get an implicit move constructor or assignment operator.\n  /** Default move constructor */\n  EIGEN_DEVICE_FUNC inline Quaternion(Quaternion&& other) EIGEN_NOEXCEPT_IF(std::is_nothrow_move_constructible<Scalar>::value)\n    : m_coeffs(std::move(other.coeffs()))\n  {}\n\n  /** Default move assignment operator */\n  EIGEN_DEVICE_FUNC Quaternion& operator=(Quaternion&& other) EIGEN_NOEXCEPT_IF(std::is_nothrow_move_assignable<Scalar>::value)\n  {\n    m_coeffs = std::move(other.coeffs());\n    return *this;\n  }\n#endif\n\n  EIGEN_DEVICE_FUNC static Quaternion UnitRandom();\n\n  template<typename Derived1, typename Derived2>\n  EIGEN_DEVICE_FUNC static Quaternion FromTwoVectors(const MatrixBase<Derived1>& a, const MatrixBase<Derived2>& b);\n\n  EIGEN_DEVICE_FUNC inline Coefficients& coeffs() { return m_coeffs;}\n  EIGEN_DEVICE_FUNC inline const Coefficients& coeffs() const { return m_coeffs;}\n\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(bool(NeedsAlignment))\n  \n#ifdef EIGEN_QUATERNION_PLUGIN\n# include EIGEN_QUATERNION_PLUGIN\n#endif\n\nprotected:\n  Coefficients m_coeffs;\n  \n#ifndef EIGEN_PARSED_BY_DOXYGEN\n    static EIGEN_STRONG_INLINE void _check_template_params()\n    {\n      EIGEN_STATIC_ASSERT( (_Options & DontAlign) == _Options,\n        INVALID_MATRIX_TEMPLATE_PARAMETERS)\n    }\n#endif\n};\n\n/** \\ingroup Geometry_Module\n  * single precision quaternion type */\ntypedef Quaternion<float> Quaternionf;\n/** \\ingroup Geometry_Module\n  * double precision quaternion type */\ntypedef Quaternion<double> Quaterniond;\n\n/***************************************************************************\n* Specialization of Map<Quaternion<Scalar>>\n***************************************************************************/\n\nnamespace internal {\n  template<typename _Scalar, int _Options>\n  struct traits<Map<Quaternion<_Scalar>, _Options> > : traits<Quaternion<_Scalar, (int(_Options)&Aligned)==Aligned ? AutoAlign : DontAlign> >\n  {\n    typedef Map<Matrix<_Scalar,4,1>, _Options> Coefficients;\n  };\n}\n\nnamespace internal {\n  template<typename _Scalar, int _Options>\n  struct traits<Map<const Quaternion<_Scalar>, _Options> > : traits<Quaternion<_Scalar, (int(_Options)&Aligned)==Aligned ? AutoAlign : DontAlign> >\n  {\n    typedef Map<const Matrix<_Scalar,4,1>, _Options> Coefficients;\n    typedef traits<Quaternion<_Scalar, (int(_Options)&Aligned)==Aligned ? AutoAlign : DontAlign> > TraitsBase;\n    enum {\n      Flags = TraitsBase::Flags & ~LvalueBit\n    };\n  };\n}\n\n/** \\ingroup Geometry_Module\n  * \\brief Quaternion expression mapping a constant memory buffer\n  *\n  * \\tparam _Scalar the type of the Quaternion coefficients\n  * \\tparam _Options see class Map\n  *\n  * This is a specialization of class Map for Quaternion. This class allows to view\n  * a 4 scalar memory buffer as an Eigen's Quaternion object.\n  *\n  * \\sa class Map, class Quaternion, class QuaternionBase\n  */\ntemplate<typename _Scalar, int _Options>\nclass Map<const Quaternion<_Scalar>, _Options >\n  : public QuaternionBase<Map<const Quaternion<_Scalar>, _Options> >\n{\n  public:\n    typedef QuaternionBase<Map<const Quaternion<_Scalar>, _Options> > Base;\n\n    typedef _Scalar Scalar;\n    typedef typename internal::traits<Map>::Coefficients Coefficients;\n    EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Map)\n    using Base::operator*=;\n\n    /** Constructs a Mapped Quaternion object from the pointer \\a coeffs\n      *\n      * The pointer \\a coeffs must reference the four coefficients of Quaternion in the following order:\n      * \\code *coeffs == {x, y, z, w} \\endcode\n      *\n      * If the template parameter _Options is set to #Aligned, then the pointer coeffs must be aligned. */\n    EIGEN_DEVICE_FUNC explicit EIGEN_STRONG_INLINE Map(const Scalar* coeffs) : m_coeffs(coeffs) {}\n\n    EIGEN_DEVICE_FUNC inline const Coefficients& coeffs() const { return m_coeffs;}\n\n  protected:\n    const Coefficients m_coeffs;\n};\n\n/** \\ingroup Geometry_Module\n  * \\brief Expression of a quaternion from a memory buffer\n  *\n  * \\tparam _Scalar the type of the Quaternion coefficients\n  * \\tparam _Options see class Map\n  *\n  * This is a specialization of class Map for Quaternion. This class allows to view\n  * a 4 scalar memory buffer as an Eigen's  Quaternion object.\n  *\n  * \\sa class Map, class Quaternion, class QuaternionBase\n  */\ntemplate<typename _Scalar, int _Options>\nclass Map<Quaternion<_Scalar>, _Options >\n  : public QuaternionBase<Map<Quaternion<_Scalar>, _Options> >\n{\n  public:\n    typedef QuaternionBase<Map<Quaternion<_Scalar>, _Options> > Base;\n\n    typedef _Scalar Scalar;\n    typedef typename internal::traits<Map>::Coefficients Coefficients;\n    EIGEN_INHERIT_ASSIGNMENT_OPERATORS(Map)\n    using Base::operator*=;\n\n    /** Constructs a Mapped Quaternion object from the pointer \\a coeffs\n      *\n      * The pointer \\a coeffs must reference the four coefficients of Quaternion in the following order:\n      * \\code *coeffs == {x, y, z, w} \\endcode\n      *\n      * If the template parameter _Options is set to #Aligned, then the pointer coeffs must be aligned. */\n    EIGEN_DEVICE_FUNC explicit EIGEN_STRONG_INLINE Map(Scalar* coeffs) : m_coeffs(coeffs) {}\n\n    EIGEN_DEVICE_FUNC inline Coefficients& coeffs() { return m_coeffs; }\n    EIGEN_DEVICE_FUNC inline const Coefficients& coeffs() const { return m_coeffs; }\n\n  protected:\n    Coefficients m_coeffs;\n};\n\n/** \\ingroup Geometry_Module\n  * Map an unaligned array of single precision scalars as a quaternion */\ntypedef Map<Quaternion<float>, 0>         QuaternionMapf;\n/** \\ingroup Geometry_Module\n  * Map an unaligned array of double precision scalars as a quaternion */\ntypedef Map<Quaternion<double>, 0>        QuaternionMapd;\n/** \\ingroup Geometry_Module\n  * Map a 16-byte aligned array of single precision scalars as a quaternion */\ntypedef Map<Quaternion<float>, Aligned>   QuaternionMapAlignedf;\n/** \\ingroup Geometry_Module\n  * Map a 16-byte aligned array of double precision scalars as a quaternion */\ntypedef Map<Quaternion<double>, Aligned>  QuaternionMapAlignedd;\n\n/***************************************************************************\n* Implementation of QuaternionBase methods\n***************************************************************************/\n\n// Generic Quaternion * Quaternion product\n// This product can be specialized for a given architecture via the Arch template argument.\nnamespace internal {\ntemplate<int Arch, class Derived1, class Derived2, typename Scalar> struct quat_product\n{\n  EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Quaternion<Scalar> run(const QuaternionBase<Derived1>& a, const QuaternionBase<Derived2>& b){\n    return Quaternion<Scalar>\n    (\n      a.w() * b.w() - a.x() * b.x() - a.y() * b.y() - a.z() * b.z(),\n      a.w() * b.x() + a.x() * b.w() + a.y() * b.z() - a.z() * b.y(),\n      a.w() * b.y() + a.y() * b.w() + a.z() * b.x() - a.x() * b.z(),\n      a.w() * b.z() + a.z() * b.w() + a.x() * b.y() - a.y() * b.x()\n    );\n  }\n};\n}\n\n/** \\returns the concatenation of two rotations as a quaternion-quaternion product */\ntemplate <class Derived>\ntemplate <class OtherDerived>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Quaternion<typename internal::traits<Derived>::Scalar>\nQuaternionBase<Derived>::operator* (const QuaternionBase<OtherDerived>& other) const\n{\n  EIGEN_STATIC_ASSERT((internal::is_same<typename Derived::Scalar, typename OtherDerived::Scalar>::value),\n   YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n  return internal::quat_product<Architecture::Target, Derived, OtherDerived,\n                         typename internal::traits<Derived>::Scalar>::run(*this, other);\n}\n\n/** \\sa operator*(Quaternion) */\ntemplate <class Derived>\ntemplate <class OtherDerived>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& QuaternionBase<Derived>::operator*= (const QuaternionBase<OtherDerived>& other)\n{\n  derived() = derived() * other.derived();\n  return derived();\n}\n\n/** Rotation of a vector by a quaternion.\n  * \\remarks If the quaternion is used to rotate several points (>1)\n  * then it is much more efficient to first convert it to a 3x3 Matrix.\n  * Comparison of the operation cost for n transformations:\n  *   - Quaternion2:    30n\n  *   - Via a Matrix3: 24 + 15n\n  */\ntemplate <class Derived>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename QuaternionBase<Derived>::Vector3\nQuaternionBase<Derived>::_transformVector(const Vector3& v) const\n{\n    // Note that this algorithm comes from the optimization by hand\n    // of the conversion to a Matrix followed by a Matrix/Vector product.\n    // It appears to be much faster than the common algorithm found\n    // in the literature (30 versus 39 flops). It also requires two\n    // Vector3 as temporaries.\n    Vector3 uv = this->vec().cross(v);\n    uv += uv;\n    return v + this->w() * uv + this->vec().cross(uv);\n}\n\ntemplate<class Derived>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE QuaternionBase<Derived>& QuaternionBase<Derived>::operator=(const QuaternionBase<Derived>& other)\n{\n  coeffs() = other.coeffs();\n  return derived();\n}\n\ntemplate<class Derived>\ntemplate<class OtherDerived>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& QuaternionBase<Derived>::operator=(const QuaternionBase<OtherDerived>& other)\n{\n  coeffs() = other.coeffs();\n  return derived();\n}\n\n/** Set \\c *this from an angle-axis \\a aa and returns a reference to \\c *this\n  */\ntemplate<class Derived>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& QuaternionBase<Derived>::operator=(const AngleAxisType& aa)\n{\n  EIGEN_USING_STD(cos)\n  EIGEN_USING_STD(sin)\n  Scalar ha = Scalar(0.5)*aa.angle(); // Scalar(0.5) to suppress precision loss warnings\n  this->w() = cos(ha);\n  this->vec() = sin(ha) * aa.axis();\n  return derived();\n}\n\n/** Set \\c *this from the expression \\a xpr:\n  *   - if \\a xpr is a 4x1 vector, then \\a xpr is assumed to be a quaternion\n  *   - if \\a xpr is a 3x3 matrix, then \\a xpr is assumed to be rotation matrix\n  *     and \\a xpr is converted to a quaternion\n  */\n\ntemplate<class Derived>\ntemplate<class MatrixDerived>\nEIGEN_DEVICE_FUNC inline Derived& QuaternionBase<Derived>::operator=(const MatrixBase<MatrixDerived>& xpr)\n{\n  EIGEN_STATIC_ASSERT((internal::is_same<typename Derived::Scalar, typename MatrixDerived::Scalar>::value),\n   YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n  internal::quaternionbase_assign_impl<MatrixDerived>::run(*this, xpr.derived());\n  return derived();\n}\n\n/** Convert the quaternion to a 3x3 rotation matrix. The quaternion is required to\n  * be normalized, otherwise the result is undefined.\n  */\ntemplate<class Derived>\nEIGEN_DEVICE_FUNC inline typename QuaternionBase<Derived>::Matrix3\nQuaternionBase<Derived>::toRotationMatrix(void) const\n{\n  // NOTE if inlined, then gcc 4.2 and 4.4 get rid of the temporary (not gcc 4.3 !!)\n  // if not inlined then the cost of the return by value is huge ~ +35%,\n  // however, not inlining this function is an order of magnitude slower, so\n  // it has to be inlined, and so the return by value is not an issue\n  Matrix3 res;\n\n  const Scalar tx  = Scalar(2)*this->x();\n  const Scalar ty  = Scalar(2)*this->y();\n  const Scalar tz  = Scalar(2)*this->z();\n  const Scalar twx = tx*this->w();\n  const Scalar twy = ty*this->w();\n  const Scalar twz = tz*this->w();\n  const Scalar txx = tx*this->x();\n  const Scalar txy = ty*this->x();\n  const Scalar txz = tz*this->x();\n  const Scalar tyy = ty*this->y();\n  const Scalar tyz = tz*this->y();\n  const Scalar tzz = tz*this->z();\n\n  res.coeffRef(0,0) = Scalar(1)-(tyy+tzz);\n  res.coeffRef(0,1) = txy-twz;\n  res.coeffRef(0,2) = txz+twy;\n  res.coeffRef(1,0) = txy+twz;\n  res.coeffRef(1,1) = Scalar(1)-(txx+tzz);\n  res.coeffRef(1,2) = tyz-twx;\n  res.coeffRef(2,0) = txz-twy;\n  res.coeffRef(2,1) = tyz+twx;\n  res.coeffRef(2,2) = Scalar(1)-(txx+tyy);\n\n  return res;\n}\n\n/** Sets \\c *this to be a quaternion representing a rotation between\n  * the two arbitrary vectors \\a a and \\a b. In other words, the built\n  * rotation represent a rotation sending the line of direction \\a a\n  * to the line of direction \\a b, both lines passing through the origin.\n  *\n  * \\returns a reference to \\c *this.\n  *\n  * Note that the two input vectors do \\b not have to be normalized, and\n  * do not need to have the same norm.\n  */\ntemplate<class Derived>\ntemplate<typename Derived1, typename Derived2>\nEIGEN_DEVICE_FUNC inline Derived& QuaternionBase<Derived>::setFromTwoVectors(const MatrixBase<Derived1>& a, const MatrixBase<Derived2>& b)\n{\n  EIGEN_USING_STD(sqrt)\n  Vector3 v0 = a.normalized();\n  Vector3 v1 = b.normalized();\n  Scalar c = v1.dot(v0);\n\n  // if dot == -1, vectors are nearly opposites\n  // => accurately compute the rotation axis by computing the\n  //    intersection of the two planes. This is done by solving:\n  //       x^T v0 = 0\n  //       x^T v1 = 0\n  //    under the constraint:\n  //       ||x|| = 1\n  //    which yields a singular value problem\n  if (c < Scalar(-1)+NumTraits<Scalar>::dummy_precision())\n  {\n    c = numext::maxi(c,Scalar(-1));\n    Matrix<Scalar,2,3> m; m << v0.transpose(), v1.transpose();\n    JacobiSVD<Matrix<Scalar,2,3> > svd(m, ComputeFullV);\n    Vector3 axis = svd.matrixV().col(2);\n\n    Scalar w2 = (Scalar(1)+c)*Scalar(0.5);\n    this->w() = sqrt(w2);\n    this->vec() = axis * sqrt(Scalar(1) - w2);\n    return derived();\n  }\n  Vector3 axis = v0.cross(v1);\n  Scalar s = sqrt((Scalar(1)+c)*Scalar(2));\n  Scalar invs = Scalar(1)/s;\n  this->vec() = axis * invs;\n  this->w() = s * Scalar(0.5);\n\n  return derived();\n}\n\n/** \\returns a random unit quaternion following a uniform distribution law on SO(3)\n  *\n  * \\note The implementation is based on http://planning.cs.uiuc.edu/node198.html\n  */\ntemplate<typename Scalar, int Options>\nEIGEN_DEVICE_FUNC Quaternion<Scalar,Options> Quaternion<Scalar,Options>::UnitRandom()\n{\n  EIGEN_USING_STD(sqrt)\n  EIGEN_USING_STD(sin)\n  EIGEN_USING_STD(cos)\n  const Scalar u1 = internal::random<Scalar>(0, 1),\n               u2 = internal::random<Scalar>(0, 2*EIGEN_PI),\n               u3 = internal::random<Scalar>(0, 2*EIGEN_PI);\n  const Scalar a = sqrt(Scalar(1) - u1),\n               b = sqrt(u1);\n  return Quaternion (a * sin(u2), a * cos(u2), b * sin(u3), b * cos(u3));\n}\n\n\n/** Returns a quaternion representing a rotation between\n  * the two arbitrary vectors \\a a and \\a b. In other words, the built\n  * rotation represent a rotation sending the line of direction \\a a\n  * to the line of direction \\a b, both lines passing through the origin.\n  *\n  * \\returns resulting quaternion\n  *\n  * Note that the two input vectors do \\b not have to be normalized, and\n  * do not need to have the same norm.\n  */\ntemplate<typename Scalar, int Options>\ntemplate<typename Derived1, typename Derived2>\nEIGEN_DEVICE_FUNC Quaternion<Scalar,Options> Quaternion<Scalar,Options>::FromTwoVectors(const MatrixBase<Derived1>& a, const MatrixBase<Derived2>& b)\n{\n    Quaternion quat;\n    quat.setFromTwoVectors(a, b);\n    return quat;\n}\n\n\n/** \\returns the multiplicative inverse of \\c *this\n  * Note that in most cases, i.e., if you simply want the opposite rotation,\n  * and/or the quaternion is normalized, then it is enough to use the conjugate.\n  *\n  * \\sa QuaternionBase::conjugate()\n  */\ntemplate <class Derived>\nEIGEN_DEVICE_FUNC inline Quaternion<typename internal::traits<Derived>::Scalar> QuaternionBase<Derived>::inverse() const\n{\n  // FIXME should this function be called multiplicativeInverse and conjugate() be called inverse() or opposite()  ??\n  Scalar n2 = this->squaredNorm();\n  if (n2 > Scalar(0))\n    return Quaternion<Scalar>(conjugate().coeffs() / n2);\n  else\n  {\n    // return an invalid result to flag the error\n    return Quaternion<Scalar>(Coefficients::Zero());\n  }\n}\n\n// Generic conjugate of a Quaternion\nnamespace internal {\ntemplate<int Arch, class Derived, typename Scalar> struct quat_conj\n{\n  EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE Quaternion<Scalar> run(const QuaternionBase<Derived>& q){\n    return Quaternion<Scalar>(q.w(),-q.x(),-q.y(),-q.z());\n  }\n};\n}\n                         \n/** \\returns the conjugate of the \\c *this which is equal to the multiplicative inverse\n  * if the quaternion is normalized.\n  * The conjugate of a quaternion represents the opposite rotation.\n  *\n  * \\sa Quaternion2::inverse()\n  */\ntemplate <class Derived>\nEIGEN_DEVICE_FUNC inline Quaternion<typename internal::traits<Derived>::Scalar>\nQuaternionBase<Derived>::conjugate() const\n{\n  return internal::quat_conj<Architecture::Target, Derived,\n                         typename internal::traits<Derived>::Scalar>::run(*this);\n                         \n}\n\n/** \\returns the angle (in radian) between two rotations\n  * \\sa dot()\n  */\ntemplate <class Derived>\ntemplate <class OtherDerived>\nEIGEN_DEVICE_FUNC inline typename internal::traits<Derived>::Scalar\nQuaternionBase<Derived>::angularDistance(const QuaternionBase<OtherDerived>& other) const\n{\n  EIGEN_USING_STD(atan2)\n  Quaternion<Scalar> d = (*this) * other.conjugate();\n  return Scalar(2) * atan2( d.vec().norm(), numext::abs(d.w()) );\n}\n\n \n    \n/** \\returns the spherical linear interpolation between the two quaternions\n  * \\c *this and \\a other at the parameter \\a t in [0;1].\n  * \n  * This represents an interpolation for a constant motion between \\c *this and \\a other,\n  * see also http://en.wikipedia.org/wiki/Slerp.\n  */\ntemplate <class Derived>\ntemplate <class OtherDerived>\nEIGEN_DEVICE_FUNC Quaternion<typename internal::traits<Derived>::Scalar>\nQuaternionBase<Derived>::slerp(const Scalar& t, const QuaternionBase<OtherDerived>& other) const\n{\n  EIGEN_USING_STD(acos)\n  EIGEN_USING_STD(sin)\n  const Scalar one = Scalar(1) - NumTraits<Scalar>::epsilon();\n  Scalar d = this->dot(other);\n  Scalar absD = numext::abs(d);\n\n  Scalar scale0;\n  Scalar scale1;\n\n  if(absD>=one)\n  {\n    scale0 = Scalar(1) - t;\n    scale1 = t;\n  }\n  else\n  {\n    // theta is the angle between the 2 quaternions\n    Scalar theta = acos(absD);\n    Scalar sinTheta = sin(theta);\n\n    scale0 = sin( ( Scalar(1) - t ) * theta) / sinTheta;\n    scale1 = sin( ( t * theta) ) / sinTheta;\n  }\n  if(d<Scalar(0)) scale1 = -scale1;\n\n  return Quaternion<Scalar>(scale0 * coeffs() + scale1 * other.coeffs());\n}\n\nnamespace internal {\n\n// set from a rotation matrix\ntemplate<typename Other>\nstruct quaternionbase_assign_impl<Other,3,3>\n{\n  typedef typename Other::Scalar Scalar;\n  template<class Derived> EIGEN_DEVICE_FUNC static inline void run(QuaternionBase<Derived>& q, const Other& a_mat)\n  {\n    const typename internal::nested_eval<Other,2>::type mat(a_mat);\n    EIGEN_USING_STD(sqrt)\n    // This algorithm comes from  \"Quaternion Calculus and Fast Animation\",\n    // Ken Shoemake, 1987 SIGGRAPH course notes\n    Scalar t = mat.trace();\n    if (t > Scalar(0))\n    {\n      t = sqrt(t + Scalar(1.0));\n      q.w() = Scalar(0.5)*t;\n      t = Scalar(0.5)/t;\n      q.x() = (mat.coeff(2,1) - mat.coeff(1,2)) * t;\n      q.y() = (mat.coeff(0,2) - mat.coeff(2,0)) * t;\n      q.z() = (mat.coeff(1,0) - mat.coeff(0,1)) * t;\n    }\n    else\n    {\n      Index i = 0;\n      if (mat.coeff(1,1) > mat.coeff(0,0))\n        i = 1;\n      if (mat.coeff(2,2) > mat.coeff(i,i))\n        i = 2;\n      Index j = (i+1)%3;\n      Index k = (j+1)%3;\n\n      t = sqrt(mat.coeff(i,i)-mat.coeff(j,j)-mat.coeff(k,k) + Scalar(1.0));\n      q.coeffs().coeffRef(i) = Scalar(0.5) * t;\n      t = Scalar(0.5)/t;\n      q.w() = (mat.coeff(k,j)-mat.coeff(j,k))*t;\n      q.coeffs().coeffRef(j) = (mat.coeff(j,i)+mat.coeff(i,j))*t;\n      q.coeffs().coeffRef(k) = (mat.coeff(k,i)+mat.coeff(i,k))*t;\n    }\n  }\n};\n\n// set from a vector of coefficients assumed to be a quaternion\ntemplate<typename Other>\nstruct quaternionbase_assign_impl<Other,4,1>\n{\n  typedef typename Other::Scalar Scalar;\n  template<class Derived> EIGEN_DEVICE_FUNC static inline void run(QuaternionBase<Derived>& q, const Other& vec)\n  {\n    q.coeffs() = vec;\n  }\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_QUATERNION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Geometry/Rotation2D.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ROTATION2D_H\n#define EIGEN_ROTATION2D_H\n\nnamespace Eigen { \n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\class Rotation2D\n  *\n  * \\brief Represents a rotation/orientation in a 2 dimensional space.\n  *\n  * \\tparam _Scalar the scalar type, i.e., the type of the coefficients\n  *\n  * This class is equivalent to a single scalar representing a counter clock wise rotation\n  * as a single angle in radian. It provides some additional features such as the automatic\n  * conversion from/to a 2x2 rotation matrix. Moreover this class aims to provide a similar\n  * interface to Quaternion in order to facilitate the writing of generic algorithms\n  * dealing with rotations.\n  *\n  * \\sa class Quaternion, class Transform\n  */\n\nnamespace internal {\n\ntemplate<typename _Scalar> struct traits<Rotation2D<_Scalar> >\n{\n  typedef _Scalar Scalar;\n};\n} // end namespace internal\n\ntemplate<typename _Scalar>\nclass Rotation2D : public RotationBase<Rotation2D<_Scalar>,2>\n{\n  typedef RotationBase<Rotation2D<_Scalar>,2> Base;\n\npublic:\n\n  using Base::operator*;\n\n  enum { Dim = 2 };\n  /** the scalar type of the coefficients */\n  typedef _Scalar Scalar;\n  typedef Matrix<Scalar,2,1> Vector2;\n  typedef Matrix<Scalar,2,2> Matrix2;\n\nprotected:\n\n  Scalar m_angle;\n\npublic:\n\n  /** Construct a 2D counter clock wise rotation from the angle \\a a in radian. */\n  EIGEN_DEVICE_FUNC explicit inline Rotation2D(const Scalar& a) : m_angle(a) {}\n  \n  /** Default constructor wihtout initialization. The represented rotation is undefined. */\n  EIGEN_DEVICE_FUNC Rotation2D() {}\n\n  /** Construct a 2D rotation from a 2x2 rotation matrix \\a mat.\n    *\n    * \\sa fromRotationMatrix()\n    */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC explicit Rotation2D(const MatrixBase<Derived>& m)\n  {\n    fromRotationMatrix(m.derived());\n  }\n\n  /** \\returns the rotation angle */\n  EIGEN_DEVICE_FUNC inline Scalar angle() const { return m_angle; }\n\n  /** \\returns a read-write reference to the rotation angle */\n  EIGEN_DEVICE_FUNC inline Scalar& angle() { return m_angle; }\n  \n  /** \\returns the rotation angle in [0,2pi] */\n  EIGEN_DEVICE_FUNC inline Scalar smallestPositiveAngle() const {\n    Scalar tmp = numext::fmod(m_angle,Scalar(2*EIGEN_PI));\n    return tmp<Scalar(0) ? tmp + Scalar(2*EIGEN_PI) : tmp;\n  }\n  \n  /** \\returns the rotation angle in [-pi,pi] */\n  EIGEN_DEVICE_FUNC inline Scalar smallestAngle() const {\n    Scalar tmp = numext::fmod(m_angle,Scalar(2*EIGEN_PI));\n    if(tmp>Scalar(EIGEN_PI))       tmp -= Scalar(2*EIGEN_PI);\n    else if(tmp<-Scalar(EIGEN_PI)) tmp += Scalar(2*EIGEN_PI);\n    return tmp;\n  }\n\n  /** \\returns the inverse rotation */\n  EIGEN_DEVICE_FUNC inline Rotation2D inverse() const { return Rotation2D(-m_angle); }\n\n  /** Concatenates two rotations */\n  EIGEN_DEVICE_FUNC inline Rotation2D operator*(const Rotation2D& other) const\n  { return Rotation2D(m_angle + other.m_angle); }\n\n  /** Concatenates two rotations */\n  EIGEN_DEVICE_FUNC inline Rotation2D& operator*=(const Rotation2D& other)\n  { m_angle += other.m_angle; return *this; }\n\n  /** Applies the rotation to a 2D vector */\n  EIGEN_DEVICE_FUNC Vector2 operator* (const Vector2& vec) const\n  { return toRotationMatrix() * vec; }\n  \n  template<typename Derived>\n  EIGEN_DEVICE_FUNC Rotation2D& fromRotationMatrix(const MatrixBase<Derived>& m);\n  EIGEN_DEVICE_FUNC Matrix2 toRotationMatrix() const;\n\n  /** Set \\c *this from a 2x2 rotation matrix \\a mat.\n    * In other words, this function extract the rotation angle from the rotation matrix.\n    *\n    * This method is an alias for fromRotationMatrix()\n    *\n    * \\sa fromRotationMatrix()\n    */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC Rotation2D& operator=(const  MatrixBase<Derived>& m)\n  { return fromRotationMatrix(m.derived()); }\n\n  /** \\returns the spherical interpolation between \\c *this and \\a other using\n    * parameter \\a t. It is in fact equivalent to a linear interpolation.\n    */\n  EIGEN_DEVICE_FUNC inline Rotation2D slerp(const Scalar& t, const Rotation2D& other) const\n  {\n    Scalar dist = Rotation2D(other.m_angle-m_angle).smallestAngle();\n    return Rotation2D(m_angle + dist*t);\n  }\n\n  /** \\returns \\c *this with scalar type casted to \\a NewScalarType\n    *\n    * Note that if \\a NewScalarType is equal to the current scalar type of \\c *this\n    * then this function smartly returns a const reference to \\c *this.\n    */\n  template<typename NewScalarType>\n  EIGEN_DEVICE_FUNC inline typename internal::cast_return_type<Rotation2D,Rotation2D<NewScalarType> >::type cast() const\n  { return typename internal::cast_return_type<Rotation2D,Rotation2D<NewScalarType> >::type(*this); }\n\n  /** Copy constructor with scalar type conversion */\n  template<typename OtherScalarType>\n  EIGEN_DEVICE_FUNC inline explicit Rotation2D(const Rotation2D<OtherScalarType>& other)\n  {\n    m_angle = Scalar(other.angle());\n  }\n\n  EIGEN_DEVICE_FUNC static inline Rotation2D Identity() { return Rotation2D(0); }\n\n  /** \\returns \\c true if \\c *this is approximately equal to \\a other, within the precision\n    * determined by \\a prec.\n    *\n    * \\sa MatrixBase::isApprox() */\n  EIGEN_DEVICE_FUNC bool isApprox(const Rotation2D& other, const typename NumTraits<Scalar>::Real& prec = NumTraits<Scalar>::dummy_precision()) const\n  { return internal::isApprox(m_angle,other.m_angle, prec); }\n  \n};\n\n/** \\ingroup Geometry_Module\n  * single precision 2D rotation type */\ntypedef Rotation2D<float> Rotation2Df;\n/** \\ingroup Geometry_Module\n  * double precision 2D rotation type */\ntypedef Rotation2D<double> Rotation2Dd;\n\n/** Set \\c *this from a 2x2 rotation matrix \\a mat.\n  * In other words, this function extract the rotation angle\n  * from the rotation matrix.\n  */\ntemplate<typename Scalar>\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC Rotation2D<Scalar>& Rotation2D<Scalar>::fromRotationMatrix(const MatrixBase<Derived>& mat)\n{\n  EIGEN_USING_STD(atan2)\n  EIGEN_STATIC_ASSERT(Derived::RowsAtCompileTime==2 && Derived::ColsAtCompileTime==2,YOU_MADE_A_PROGRAMMING_MISTAKE)\n  m_angle = atan2(mat.coeff(1,0), mat.coeff(0,0));\n  return *this;\n}\n\n/** Constructs and \\returns an equivalent 2x2 rotation matrix.\n  */\ntemplate<typename Scalar>\ntypename Rotation2D<Scalar>::Matrix2\nEIGEN_DEVICE_FUNC Rotation2D<Scalar>::toRotationMatrix(void) const\n{\n  EIGEN_USING_STD(sin)\n  EIGEN_USING_STD(cos)\n  Scalar sinA = sin(m_angle);\n  Scalar cosA = cos(m_angle);\n  return (Matrix2() << cosA, -sinA, sinA, cosA).finished();\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_ROTATION2D_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Geometry/RotationBase.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ROTATIONBASE_H\n#define EIGEN_ROTATIONBASE_H\n\nnamespace Eigen { \n\n// forward declaration\nnamespace internal {\ntemplate<typename RotationDerived, typename MatrixType, bool IsVector=MatrixType::IsVectorAtCompileTime>\nstruct rotation_base_generic_product_selector;\n}\n\n/** \\class RotationBase\n  *\n  * \\brief Common base class for compact rotation representations\n  *\n  * \\tparam Derived is the derived type, i.e., a rotation type\n  * \\tparam _Dim the dimension of the space\n  */\ntemplate<typename Derived, int _Dim>\nclass RotationBase\n{\n  public:\n    enum { Dim = _Dim };\n    /** the scalar type of the coefficients */\n    typedef typename internal::traits<Derived>::Scalar Scalar;\n\n    /** corresponding linear transformation matrix type */\n    typedef Matrix<Scalar,Dim,Dim> RotationMatrixType;\n    typedef Matrix<Scalar,Dim,1> VectorType;\n\n  public:\n    EIGEN_DEVICE_FUNC inline const Derived& derived() const { return *static_cast<const Derived*>(this); }\n    EIGEN_DEVICE_FUNC inline Derived& derived() { return *static_cast<Derived*>(this); }\n\n    /** \\returns an equivalent rotation matrix */\n    EIGEN_DEVICE_FUNC inline RotationMatrixType toRotationMatrix() const { return derived().toRotationMatrix(); }\n\n    /** \\returns an equivalent rotation matrix \n      * This function is added to be conform with the Transform class' naming scheme.\n      */\n    EIGEN_DEVICE_FUNC inline RotationMatrixType matrix() const { return derived().toRotationMatrix(); }\n\n    /** \\returns the inverse rotation */\n    EIGEN_DEVICE_FUNC inline Derived inverse() const { return derived().inverse(); }\n\n    /** \\returns the concatenation of the rotation \\c *this with a translation \\a t */\n    EIGEN_DEVICE_FUNC inline Transform<Scalar,Dim,Isometry> operator*(const Translation<Scalar,Dim>& t) const\n    { return Transform<Scalar,Dim,Isometry>(*this) * t; }\n\n    /** \\returns the concatenation of the rotation \\c *this with a uniform scaling \\a s */\n    EIGEN_DEVICE_FUNC inline RotationMatrixType operator*(const UniformScaling<Scalar>& s) const\n    { return toRotationMatrix() * s.factor(); }\n\n    /** \\returns the concatenation of the rotation \\c *this with a generic expression \\a e\n      * \\a e can be:\n      *  - a DimxDim linear transformation matrix\n      *  - a DimxDim diagonal matrix (axis aligned scaling)\n      *  - a vector of size Dim\n      */\n    template<typename OtherDerived>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename internal::rotation_base_generic_product_selector<Derived,OtherDerived,OtherDerived::IsVectorAtCompileTime>::ReturnType\n    operator*(const EigenBase<OtherDerived>& e) const\n    { return internal::rotation_base_generic_product_selector<Derived,OtherDerived>::run(derived(), e.derived()); }\n\n    /** \\returns the concatenation of a linear transformation \\a l with the rotation \\a r */\n    template<typename OtherDerived> friend\n    EIGEN_DEVICE_FUNC inline RotationMatrixType operator*(const EigenBase<OtherDerived>& l, const Derived& r)\n    { return l.derived() * r.toRotationMatrix(); }\n\n    /** \\returns the concatenation of a scaling \\a l with the rotation \\a r */\n    EIGEN_DEVICE_FUNC friend inline Transform<Scalar,Dim,Affine> operator*(const DiagonalMatrix<Scalar,Dim>& l, const Derived& r)\n    { \n      Transform<Scalar,Dim,Affine> res(r);\n      res.linear().applyOnTheLeft(l);\n      return res;\n    }\n\n    /** \\returns the concatenation of the rotation \\c *this with a transformation \\a t */\n    template<int Mode, int Options>\n    EIGEN_DEVICE_FUNC inline Transform<Scalar,Dim,Mode> operator*(const Transform<Scalar,Dim,Mode,Options>& t) const\n    { return toRotationMatrix() * t; }\n\n    template<typename OtherVectorType>\n    EIGEN_DEVICE_FUNC inline VectorType _transformVector(const OtherVectorType& v) const\n    { return toRotationMatrix() * v; }\n};\n\nnamespace internal {\n\n// implementation of the generic product rotation * matrix\ntemplate<typename RotationDerived, typename MatrixType>\nstruct rotation_base_generic_product_selector<RotationDerived,MatrixType,false>\n{\n  enum { Dim = RotationDerived::Dim };\n  typedef Matrix<typename RotationDerived::Scalar,Dim,Dim> ReturnType;\n  EIGEN_DEVICE_FUNC static inline ReturnType run(const RotationDerived& r, const MatrixType& m)\n  { return r.toRotationMatrix() * m; }\n};\n\ntemplate<typename RotationDerived, typename Scalar, int Dim, int MaxDim>\nstruct rotation_base_generic_product_selector< RotationDerived, DiagonalMatrix<Scalar,Dim,MaxDim>, false >\n{\n  typedef Transform<Scalar,Dim,Affine> ReturnType;\n  EIGEN_DEVICE_FUNC static inline ReturnType run(const RotationDerived& r, const DiagonalMatrix<Scalar,Dim,MaxDim>& m)\n  {\n    ReturnType res(r);\n    res.linear() *= m;\n    return res;\n  }\n};\n\ntemplate<typename RotationDerived,typename OtherVectorType>\nstruct rotation_base_generic_product_selector<RotationDerived,OtherVectorType,true>\n{\n  enum { Dim = RotationDerived::Dim };\n  typedef Matrix<typename RotationDerived::Scalar,Dim,1> ReturnType;\n  EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE ReturnType run(const RotationDerived& r, const OtherVectorType& v)\n  {\n    return r._transformVector(v);\n  }\n};\n\n} // end namespace internal\n\n/** \\geometry_module\n  *\n  * \\brief Constructs a Dim x Dim rotation matrix from the rotation \\a r\n  */\ntemplate<typename _Scalar, int _Rows, int _Cols, int _Storage, int _MaxRows, int _MaxCols>\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC Matrix<_Scalar, _Rows, _Cols, _Storage, _MaxRows, _MaxCols>\n::Matrix(const RotationBase<OtherDerived,ColsAtCompileTime>& r)\n{\n  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix,int(OtherDerived::Dim),int(OtherDerived::Dim))\n  *this = r.toRotationMatrix();\n}\n\n/** \\geometry_module\n  *\n  * \\brief Set a Dim x Dim rotation matrix from the rotation \\a r\n  */\ntemplate<typename _Scalar, int _Rows, int _Cols, int _Storage, int _MaxRows, int _MaxCols>\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC Matrix<_Scalar, _Rows, _Cols, _Storage, _MaxRows, _MaxCols>&\nMatrix<_Scalar, _Rows, _Cols, _Storage, _MaxRows, _MaxCols>\n::operator=(const RotationBase<OtherDerived,ColsAtCompileTime>& r)\n{\n  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix,int(OtherDerived::Dim),int(OtherDerived::Dim))\n  return *this = r.toRotationMatrix();\n}\n\nnamespace internal {\n\n/** \\internal\n  *\n  * Helper function to return an arbitrary rotation object to a rotation matrix.\n  *\n  * \\tparam Scalar the numeric type of the matrix coefficients\n  * \\tparam Dim the dimension of the current space\n  *\n  * It returns a Dim x Dim fixed size matrix.\n  *\n  * Default specializations are provided for:\n  *   - any scalar type (2D),\n  *   - any matrix expression,\n  *   - any type based on RotationBase (e.g., Quaternion, AngleAxis, Rotation2D)\n  *\n  * Currently toRotationMatrix is only used by Transform.\n  *\n  * \\sa class Transform, class Rotation2D, class Quaternion, class AngleAxis\n  */\ntemplate<typename Scalar, int Dim>\nEIGEN_DEVICE_FUNC static inline Matrix<Scalar,2,2> toRotationMatrix(const Scalar& s)\n{\n  EIGEN_STATIC_ASSERT(Dim==2,YOU_MADE_A_PROGRAMMING_MISTAKE)\n  return Rotation2D<Scalar>(s).toRotationMatrix();\n}\n\ntemplate<typename Scalar, int Dim, typename OtherDerived>\nEIGEN_DEVICE_FUNC static inline Matrix<Scalar,Dim,Dim> toRotationMatrix(const RotationBase<OtherDerived,Dim>& r)\n{\n  return r.toRotationMatrix();\n}\n\ntemplate<typename Scalar, int Dim, typename OtherDerived>\nEIGEN_DEVICE_FUNC static inline const MatrixBase<OtherDerived>& toRotationMatrix(const MatrixBase<OtherDerived>& mat)\n{\n  EIGEN_STATIC_ASSERT(OtherDerived::RowsAtCompileTime==Dim && OtherDerived::ColsAtCompileTime==Dim,\n    YOU_MADE_A_PROGRAMMING_MISTAKE)\n  return mat;\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_ROTATIONBASE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Geometry/Scaling.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SCALING_H\n#define EIGEN_SCALING_H\n\nnamespace Eigen { \n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\class UniformScaling\n  *\n  * \\brief Represents a generic uniform scaling transformation\n  *\n  * \\tparam _Scalar the scalar type, i.e., the type of the coefficients.\n  *\n  * This class represent a uniform scaling transformation. It is the return\n  * type of Scaling(Scalar), and most of the time this is the only way it\n  * is used. In particular, this class is not aimed to be used to store a scaling transformation,\n  * but rather to make easier the constructions and updates of Transform objects.\n  *\n  * To represent an axis aligned scaling, use the DiagonalMatrix class.\n  *\n  * \\sa Scaling(), class DiagonalMatrix, MatrixBase::asDiagonal(), class Translation, class Transform\n  */\n\nnamespace internal\n{\n  // This helper helps nvcc+MSVC to properly parse this file.\n  // See bug 1412.\n  template <typename Scalar, int Dim, int Mode>\n  struct uniformscaling_times_affine_returntype\n  {\n    enum\n    {\n      NewMode = int(Mode) == int(Isometry) ? Affine : Mode\n    };\n    typedef Transform <Scalar, Dim, NewMode> type;\n  };\n}\n\ntemplate<typename _Scalar>\nclass UniformScaling\n{\npublic:\n  /** the scalar type of the coefficients */\n  typedef _Scalar Scalar;\n\nprotected:\n\n  Scalar m_factor;\n\npublic:\n\n  /** Default constructor without initialization. */\n  UniformScaling() {}\n  /** Constructs and initialize a uniform scaling transformation */\n  explicit inline UniformScaling(const Scalar& s) : m_factor(s) {}\n\n  inline const Scalar& factor() const { return m_factor; }\n  inline Scalar& factor() { return m_factor; }\n\n  /** Concatenates two uniform scaling */\n  inline UniformScaling operator* (const UniformScaling& other) const\n  { return UniformScaling(m_factor * other.factor()); }\n\n  /** Concatenates a uniform scaling and a translation */\n  template<int Dim>\n  inline Transform<Scalar,Dim,Affine> operator* (const Translation<Scalar,Dim>& t) const;\n\n  /** Concatenates a uniform scaling and an affine transformation */\n  template<int Dim, int Mode, int Options>\n  inline typename\n\tinternal::uniformscaling_times_affine_returntype<Scalar,Dim,Mode>::type\n\toperator* (const Transform<Scalar, Dim, Mode, Options>& t) const\n  {\n    typename internal::uniformscaling_times_affine_returntype<Scalar,Dim,Mode>::type res = t;\n    res.prescale(factor());\n    return res;\n  }\n\n  /** Concatenates a uniform scaling and a linear transformation matrix */\n  // TODO returns an expression\n  template<typename Derived>\n  inline typename Eigen::internal::plain_matrix_type<Derived>::type operator* (const MatrixBase<Derived>& other) const\n  { return other * m_factor; }\n\n  template<typename Derived,int Dim>\n  inline Matrix<Scalar,Dim,Dim> operator*(const RotationBase<Derived,Dim>& r) const\n  { return r.toRotationMatrix() * m_factor; }\n\n  /** \\returns the inverse scaling */\n  inline UniformScaling inverse() const\n  { return UniformScaling(Scalar(1)/m_factor); }\n\n  /** \\returns \\c *this with scalar type casted to \\a NewScalarType\n    *\n    * Note that if \\a NewScalarType is equal to the current scalar type of \\c *this\n    * then this function smartly returns a const reference to \\c *this.\n    */\n  template<typename NewScalarType>\n  inline UniformScaling<NewScalarType> cast() const\n  { return UniformScaling<NewScalarType>(NewScalarType(m_factor)); }\n\n  /** Copy constructor with scalar type conversion */\n  template<typename OtherScalarType>\n  inline explicit UniformScaling(const UniformScaling<OtherScalarType>& other)\n  { m_factor = Scalar(other.factor()); }\n\n  /** \\returns \\c true if \\c *this is approximately equal to \\a other, within the precision\n    * determined by \\a prec.\n    *\n    * \\sa MatrixBase::isApprox() */\n  bool isApprox(const UniformScaling& other, const typename NumTraits<Scalar>::Real& prec = NumTraits<Scalar>::dummy_precision()) const\n  { return internal::isApprox(m_factor, other.factor(), prec); }\n\n};\n\n/** \\addtogroup Geometry_Module */\n//@{\n\n/** Concatenates a linear transformation matrix and a uniform scaling\n  * \\relates UniformScaling\n  */\n// NOTE this operator is defined in MatrixBase and not as a friend function\n// of UniformScaling to fix an internal crash of Intel's ICC\ntemplate<typename Derived,typename Scalar>\nEIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(Derived,Scalar,product)\noperator*(const MatrixBase<Derived>& matrix, const UniformScaling<Scalar>& s)\n{ return matrix.derived() * s.factor(); }\n\n/** Constructs a uniform scaling from scale factor \\a s */\ninline UniformScaling<float> Scaling(float s) { return UniformScaling<float>(s); }\n/** Constructs a uniform scaling from scale factor \\a s */\ninline UniformScaling<double> Scaling(double s) { return UniformScaling<double>(s); }\n/** Constructs a uniform scaling from scale factor \\a s */\ntemplate<typename RealScalar>\ninline UniformScaling<std::complex<RealScalar> > Scaling(const std::complex<RealScalar>& s)\n{ return UniformScaling<std::complex<RealScalar> >(s); }\n\n/** Constructs a 2D axis aligned scaling */\ntemplate<typename Scalar>\ninline DiagonalMatrix<Scalar,2> Scaling(const Scalar& sx, const Scalar& sy)\n{ return DiagonalMatrix<Scalar,2>(sx, sy); }\n/** Constructs a 3D axis aligned scaling */\ntemplate<typename Scalar>\ninline DiagonalMatrix<Scalar,3> Scaling(const Scalar& sx, const Scalar& sy, const Scalar& sz)\n{ return DiagonalMatrix<Scalar,3>(sx, sy, sz); }\n\n/** Constructs an axis aligned scaling expression from vector expression \\a coeffs\n  * This is an alias for coeffs.asDiagonal()\n  */\ntemplate<typename Derived>\ninline const DiagonalWrapper<const Derived> Scaling(const MatrixBase<Derived>& coeffs)\n{ return coeffs.asDiagonal(); }\n\n/** \\deprecated */\ntypedef DiagonalMatrix<float, 2> AlignedScaling2f;\n/** \\deprecated */\ntypedef DiagonalMatrix<double,2> AlignedScaling2d;\n/** \\deprecated */\ntypedef DiagonalMatrix<float, 3> AlignedScaling3f;\n/** \\deprecated */\ntypedef DiagonalMatrix<double,3> AlignedScaling3d;\n//@}\n\ntemplate<typename Scalar>\ntemplate<int Dim>\ninline Transform<Scalar,Dim,Affine>\nUniformScaling<Scalar>::operator* (const Translation<Scalar,Dim>& t) const\n{\n  Transform<Scalar,Dim,Affine> res;\n  res.matrix().setZero();\n  res.linear().diagonal().fill(factor());\n  res.translation() = factor() * t.vector();\n  res(Dim,Dim) = Scalar(1);\n  return res;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SCALING_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Geometry/Transform.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2010 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_TRANSFORM_H\n#define EIGEN_TRANSFORM_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate<typename Transform>\nstruct transform_traits\n{\n  enum\n  {\n    Dim = Transform::Dim,\n    HDim = Transform::HDim,\n    Mode = Transform::Mode,\n    IsProjective = (int(Mode)==int(Projective))\n  };\n};\n\ntemplate< typename TransformType,\n          typename MatrixType,\n          int Case = transform_traits<TransformType>::IsProjective ? 0\n                   : int(MatrixType::RowsAtCompileTime) == int(transform_traits<TransformType>::HDim) ? 1\n                   : 2,\n          int RhsCols = MatrixType::ColsAtCompileTime>\nstruct transform_right_product_impl;\n\ntemplate< typename Other,\n          int Mode,\n          int Options,\n          int Dim,\n          int HDim,\n          int OtherRows=Other::RowsAtCompileTime,\n          int OtherCols=Other::ColsAtCompileTime>\nstruct transform_left_product_impl;\n\ntemplate< typename Lhs,\n          typename Rhs,\n          bool AnyProjective = \n            transform_traits<Lhs>::IsProjective ||\n            transform_traits<Rhs>::IsProjective>\nstruct transform_transform_product_impl;\n\ntemplate< typename Other,\n          int Mode,\n          int Options,\n          int Dim,\n          int HDim,\n          int OtherRows=Other::RowsAtCompileTime,\n          int OtherCols=Other::ColsAtCompileTime>\nstruct transform_construct_from_matrix;\n\ntemplate<typename TransformType> struct transform_take_affine_part;\n\ntemplate<typename _Scalar, int _Dim, int _Mode, int _Options>\nstruct traits<Transform<_Scalar,_Dim,_Mode,_Options> >\n{\n  typedef _Scalar Scalar;\n  typedef Eigen::Index StorageIndex;\n  typedef Dense StorageKind;\n  enum {\n    Dim1 = _Dim==Dynamic ? _Dim : _Dim + 1,\n    RowsAtCompileTime = _Mode==Projective ? Dim1 : _Dim,\n    ColsAtCompileTime = Dim1,\n    MaxRowsAtCompileTime = RowsAtCompileTime,\n    MaxColsAtCompileTime = ColsAtCompileTime,\n    Flags = 0\n  };\n};\n\ntemplate<int Mode> struct transform_make_affine;\n\n} // end namespace internal\n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\class Transform\n  *\n  * \\brief Represents an homogeneous transformation in a N dimensional space\n  *\n  * \\tparam _Scalar the scalar type, i.e., the type of the coefficients\n  * \\tparam _Dim the dimension of the space\n  * \\tparam _Mode the type of the transformation. Can be:\n  *              - #Affine: the transformation is stored as a (Dim+1)^2 matrix,\n  *                         where the last row is assumed to be [0 ... 0 1].\n  *              - #AffineCompact: the transformation is stored as a (Dim)x(Dim+1) matrix.\n  *              - #Projective: the transformation is stored as a (Dim+1)^2 matrix\n  *                             without any assumption.\n  *              - #Isometry: same as #Affine with the additional assumption that\n  *                           the linear part represents a rotation. This assumption is exploited\n  *                           to speed up some functions such as inverse() and rotation().\n  * \\tparam _Options has the same meaning as in class Matrix. It allows to specify DontAlign and/or RowMajor.\n  *                  These Options are passed directly to the underlying matrix type.\n  *\n  * The homography is internally represented and stored by a matrix which\n  * is available through the matrix() method. To understand the behavior of\n  * this class you have to think a Transform object as its internal\n  * matrix representation. The chosen convention is right multiply:\n  *\n  * \\code v' = T * v \\endcode\n  *\n  * Therefore, an affine transformation matrix M is shaped like this:\n  *\n  * \\f$ \\left( \\begin{array}{cc}\n  * linear & translation\\\\\n  * 0 ... 0 & 1\n  * \\end{array} \\right) \\f$\n  *\n  * Note that for a projective transformation the last row can be anything,\n  * and then the interpretation of different parts might be slightly different.\n  *\n  * However, unlike a plain matrix, the Transform class provides many features\n  * simplifying both its assembly and usage. In particular, it can be composed\n  * with any other transformations (Transform,Translation,RotationBase,DiagonalMatrix)\n  * and can be directly used to transform implicit homogeneous vectors. All these\n  * operations are handled via the operator*. For the composition of transformations,\n  * its principle consists to first convert the right/left hand sides of the product\n  * to a compatible (Dim+1)^2 matrix and then perform a pure matrix product.\n  * Of course, internally, operator* tries to perform the minimal number of operations\n  * according to the nature of each terms. Likewise, when applying the transform\n  * to points, the latters are automatically promoted to homogeneous vectors\n  * before doing the matrix product. The conventions to homogeneous representations\n  * are performed as follow:\n  *\n  * \\b Translation t (Dim)x(1):\n  * \\f$ \\left( \\begin{array}{cc}\n  * I & t \\\\\n  * 0\\,...\\,0 & 1\n  * \\end{array} \\right) \\f$\n  *\n  * \\b Rotation R (Dim)x(Dim):\n  * \\f$ \\left( \\begin{array}{cc}\n  * R & 0\\\\\n  * 0\\,...\\,0 & 1\n  * \\end{array} \\right) \\f$\n  *<!--\n  * \\b Linear \\b Matrix L (Dim)x(Dim):\n  * \\f$ \\left( \\begin{array}{cc}\n  * L & 0\\\\\n  * 0\\,...\\,0 & 1\n  * \\end{array} \\right) \\f$\n  *\n  * \\b Affine \\b Matrix A (Dim)x(Dim+1):\n  * \\f$ \\left( \\begin{array}{c}\n  * A\\\\\n  * 0\\,...\\,0\\,1\n  * \\end{array} \\right) \\f$\n  *-->\n  * \\b Scaling \\b DiagonalMatrix S (Dim)x(Dim):\n  * \\f$ \\left( \\begin{array}{cc}\n  * S & 0\\\\\n  * 0\\,...\\,0 & 1\n  * \\end{array} \\right) \\f$\n  *\n  * \\b Column \\b point v (Dim)x(1):\n  * \\f$ \\left( \\begin{array}{c}\n  * v\\\\\n  * 1\n  * \\end{array} \\right) \\f$\n  *\n  * \\b Set \\b of \\b column \\b points V1...Vn (Dim)x(n):\n  * \\f$ \\left( \\begin{array}{ccc}\n  * v_1 & ... & v_n\\\\\n  * 1 & ... & 1\n  * \\end{array} \\right) \\f$\n  *\n  * The concatenation of a Transform object with any kind of other transformation\n  * always returns a Transform object.\n  *\n  * A little exception to the \"as pure matrix product\" rule is the case of the\n  * transformation of non homogeneous vectors by an affine transformation. In\n  * that case the last matrix row can be ignored, and the product returns non\n  * homogeneous vectors.\n  *\n  * Since, for instance, a Dim x Dim matrix is interpreted as a linear transformation,\n  * it is not possible to directly transform Dim vectors stored in a Dim x Dim matrix.\n  * The solution is either to use a Dim x Dynamic matrix or explicitly request a\n  * vector transformation by making the vector homogeneous:\n  * \\code\n  * m' = T * m.colwise().homogeneous();\n  * \\endcode\n  * Note that there is zero overhead.\n  *\n  * Conversion methods from/to Qt's QMatrix and QTransform are available if the\n  * preprocessor token EIGEN_QT_SUPPORT is defined.\n  *\n  * This class can be extended with the help of the plugin mechanism described on the page\n  * \\ref TopicCustomizing_Plugins by defining the preprocessor symbol \\c EIGEN_TRANSFORM_PLUGIN.\n  *\n  * \\sa class Matrix, class Quaternion\n  */\ntemplate<typename _Scalar, int _Dim, int _Mode, int _Options>\nclass Transform\n{\npublic:\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_Dim==Dynamic ? Dynamic : (_Dim+1)*(_Dim+1))\n  enum {\n    Mode = _Mode,\n    Options = _Options,\n    Dim = _Dim,     ///< space dimension in which the transformation holds\n    HDim = _Dim+1,  ///< size of a respective homogeneous vector\n    Rows = int(Mode)==(AffineCompact) ? Dim : HDim\n  };\n  /** the scalar type of the coefficients */\n  typedef _Scalar Scalar;\n  typedef Eigen::Index StorageIndex;\n  typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n  /** type of the matrix used to represent the transformation */\n  typedef typename internal::make_proper_matrix_type<Scalar,Rows,HDim,Options>::type MatrixType;\n  /** constified MatrixType */\n  typedef const MatrixType ConstMatrixType;\n  /** type of the matrix used to represent the linear part of the transformation */\n  typedef Matrix<Scalar,Dim,Dim,Options> LinearMatrixType;\n  /** type of read/write reference to the linear part of the transformation */\n  typedef Block<MatrixType,Dim,Dim,int(Mode)==(AffineCompact) && (int(Options)&RowMajor)==0> LinearPart;\n  /** type of read reference to the linear part of the transformation */\n  typedef const Block<ConstMatrixType,Dim,Dim,int(Mode)==(AffineCompact) && (int(Options)&RowMajor)==0> ConstLinearPart;\n  /** type of read/write reference to the affine part of the transformation */\n  typedef typename internal::conditional<int(Mode)==int(AffineCompact),\n                              MatrixType&,\n                              Block<MatrixType,Dim,HDim> >::type AffinePart;\n  /** type of read reference to the affine part of the transformation */\n  typedef typename internal::conditional<int(Mode)==int(AffineCompact),\n                              const MatrixType&,\n                              const Block<const MatrixType,Dim,HDim> >::type ConstAffinePart;\n  /** type of a vector */\n  typedef Matrix<Scalar,Dim,1> VectorType;\n  /** type of a read/write reference to the translation part of the rotation */\n  typedef Block<MatrixType,Dim,1,!(internal::traits<MatrixType>::Flags & RowMajorBit)> TranslationPart;\n  /** type of a read reference to the translation part of the rotation */\n  typedef const Block<ConstMatrixType,Dim,1,!(internal::traits<MatrixType>::Flags & RowMajorBit)> ConstTranslationPart;\n  /** corresponding translation type */\n  typedef Translation<Scalar,Dim> TranslationType;\n  \n  // this intermediate enum is needed to avoid an ICE with gcc 3.4 and 4.0\n  enum { TransformTimeDiagonalMode = ((Mode==int(Isometry))?Affine:int(Mode)) };\n  /** The return type of the product between a diagonal matrix and a transform */\n  typedef Transform<Scalar,Dim,TransformTimeDiagonalMode> TransformTimeDiagonalReturnType;\n\nprotected:\n\n  MatrixType m_matrix;\n\npublic:\n\n  /** Default constructor without initialization of the meaningful coefficients.\n    * If Mode==Affine or Mode==Isometry, then the last row is set to [0 ... 0 1] */\n  EIGEN_DEVICE_FUNC inline Transform()\n  {\n    check_template_params();\n    internal::transform_make_affine<(int(Mode)==Affine || int(Mode)==Isometry) ? Affine : AffineCompact>::run(m_matrix);\n  }\n\n  EIGEN_DEVICE_FUNC inline explicit Transform(const TranslationType& t)\n  {\n    check_template_params();\n    *this = t;\n  }\n  EIGEN_DEVICE_FUNC inline explicit Transform(const UniformScaling<Scalar>& s)\n  {\n    check_template_params();\n    *this = s;\n  }\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline explicit Transform(const RotationBase<Derived, Dim>& r)\n  {\n    check_template_params();\n    *this = r;\n  }\n\n  typedef internal::transform_take_affine_part<Transform> take_affine_part;\n\n  /** Constructs and initializes a transformation from a Dim^2 or a (Dim+1)^2 matrix. */\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC inline explicit Transform(const EigenBase<OtherDerived>& other)\n  {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar,typename OtherDerived::Scalar>::value),\n      YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY);\n\n    check_template_params();\n    internal::transform_construct_from_matrix<OtherDerived,Mode,Options,Dim,HDim>::run(this, other.derived());\n  }\n\n  /** Set \\c *this from a Dim^2 or (Dim+1)^2 matrix. */\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC inline Transform& operator=(const EigenBase<OtherDerived>& other)\n  {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar,typename OtherDerived::Scalar>::value),\n      YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY);\n\n    internal::transform_construct_from_matrix<OtherDerived,Mode,Options,Dim,HDim>::run(this, other.derived());\n    return *this;\n  }\n  \n  template<int OtherOptions>\n  EIGEN_DEVICE_FUNC inline Transform(const Transform<Scalar,Dim,Mode,OtherOptions>& other)\n  {\n    check_template_params();\n    // only the options change, we can directly copy the matrices\n    m_matrix = other.matrix();\n  }\n\n  template<int OtherMode,int OtherOptions>\n  EIGEN_DEVICE_FUNC inline Transform(const Transform<Scalar,Dim,OtherMode,OtherOptions>& other)\n  {\n    check_template_params();\n    // prevent conversions as:\n    // Affine | AffineCompact | Isometry = Projective\n    EIGEN_STATIC_ASSERT(EIGEN_IMPLIES(OtherMode==int(Projective), Mode==int(Projective)),\n                        YOU_PERFORMED_AN_INVALID_TRANSFORMATION_CONVERSION)\n\n    // prevent conversions as:\n    // Isometry = Affine | AffineCompact\n    EIGEN_STATIC_ASSERT(EIGEN_IMPLIES(OtherMode==int(Affine)||OtherMode==int(AffineCompact), Mode!=int(Isometry)),\n                        YOU_PERFORMED_AN_INVALID_TRANSFORMATION_CONVERSION)\n\n    enum { ModeIsAffineCompact = Mode == int(AffineCompact),\n           OtherModeIsAffineCompact = OtherMode == int(AffineCompact)\n    };\n\n    if(EIGEN_CONST_CONDITIONAL(ModeIsAffineCompact == OtherModeIsAffineCompact))\n    {\n      // We need the block expression because the code is compiled for all\n      // combinations of transformations and will trigger a compile time error\n      // if one tries to assign the matrices directly\n      m_matrix.template block<Dim,Dim+1>(0,0) = other.matrix().template block<Dim,Dim+1>(0,0);\n      makeAffine();\n    }\n    else if(EIGEN_CONST_CONDITIONAL(OtherModeIsAffineCompact))\n    {\n      typedef typename Transform<Scalar,Dim,OtherMode,OtherOptions>::MatrixType OtherMatrixType;\n      internal::transform_construct_from_matrix<OtherMatrixType,Mode,Options,Dim,HDim>::run(this, other.matrix());\n    }\n    else\n    {\n      // here we know that Mode == AffineCompact and OtherMode != AffineCompact.\n      // if OtherMode were Projective, the static assert above would already have caught it.\n      // So the only possibility is that OtherMode == Affine\n      linear() = other.linear();\n      translation() = other.translation();\n    }\n  }\n\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC Transform(const ReturnByValue<OtherDerived>& other)\n  {\n    check_template_params();\n    other.evalTo(*this);\n  }\n\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC Transform& operator=(const ReturnByValue<OtherDerived>& other)\n  {\n    other.evalTo(*this);\n    return *this;\n  }\n\n  #ifdef EIGEN_QT_SUPPORT\n  inline Transform(const QMatrix& other);\n  inline Transform& operator=(const QMatrix& other);\n  inline QMatrix toQMatrix(void) const;\n  inline Transform(const QTransform& other);\n  inline Transform& operator=(const QTransform& other);\n  inline QTransform toQTransform(void) const;\n  #endif\n  \n  EIGEN_DEVICE_FUNC Index rows() const { return int(Mode)==int(Projective) ? m_matrix.cols() : (m_matrix.cols()-1); }\n  EIGEN_DEVICE_FUNC Index cols() const { return m_matrix.cols(); }\n\n  /** shortcut for m_matrix(row,col);\n    * \\sa MatrixBase::operator(Index,Index) const */\n  EIGEN_DEVICE_FUNC inline Scalar operator() (Index row, Index col) const { return m_matrix(row,col); }\n  /** shortcut for m_matrix(row,col);\n    * \\sa MatrixBase::operator(Index,Index) */\n  EIGEN_DEVICE_FUNC inline Scalar& operator() (Index row, Index col) { return m_matrix(row,col); }\n\n  /** \\returns a read-only expression of the transformation matrix */\n  EIGEN_DEVICE_FUNC inline const MatrixType& matrix() const { return m_matrix; }\n  /** \\returns a writable expression of the transformation matrix */\n  EIGEN_DEVICE_FUNC inline MatrixType& matrix() { return m_matrix; }\n\n  /** \\returns a read-only expression of the linear part of the transformation */\n  EIGEN_DEVICE_FUNC inline ConstLinearPart linear() const { return ConstLinearPart(m_matrix,0,0); }\n  /** \\returns a writable expression of the linear part of the transformation */\n  EIGEN_DEVICE_FUNC inline LinearPart linear() { return LinearPart(m_matrix,0,0); }\n\n  /** \\returns a read-only expression of the Dim x HDim affine part of the transformation */\n  EIGEN_DEVICE_FUNC inline ConstAffinePart affine() const { return take_affine_part::run(m_matrix); }\n  /** \\returns a writable expression of the Dim x HDim affine part of the transformation */\n  EIGEN_DEVICE_FUNC inline AffinePart affine() { return take_affine_part::run(m_matrix); }\n\n  /** \\returns a read-only expression of the translation vector of the transformation */\n  EIGEN_DEVICE_FUNC inline ConstTranslationPart translation() const { return ConstTranslationPart(m_matrix,0,Dim); }\n  /** \\returns a writable expression of the translation vector of the transformation */\n  EIGEN_DEVICE_FUNC inline TranslationPart translation() { return TranslationPart(m_matrix,0,Dim); }\n\n  /** \\returns an expression of the product between the transform \\c *this and a matrix expression \\a other.\n    *\n    * The right-hand-side \\a other can be either:\n    * \\li an homogeneous vector of size Dim+1,\n    * \\li a set of homogeneous vectors of size Dim+1 x N,\n    * \\li a transformation matrix of size Dim+1 x Dim+1.\n    *\n    * Moreover, if \\c *this represents an affine transformation (i.e., Mode!=Projective), then \\a other can also be:\n    * \\li a point of size Dim (computes: \\code this->linear() * other + this->translation()\\endcode),\n    * \\li a set of N points as a Dim x N matrix (computes: \\code (this->linear() * other).colwise() + this->translation()\\endcode),\n    *\n    * In all cases, the return type is a matrix or vector of same sizes as the right-hand-side \\a other.\n    *\n    * If you want to interpret \\a other as a linear or affine transformation, then first convert it to a Transform<> type,\n    * or do your own cooking.\n    *\n    * Finally, if you want to apply Affine transformations to vectors, then explicitly apply the linear part only:\n    * \\code\n    * Affine3f A;\n    * Vector3f v1, v2;\n    * v2 = A.linear() * v1;\n    * \\endcode\n    *\n    */\n  // note: this function is defined here because some compilers cannot find the respective declaration\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const typename internal::transform_right_product_impl<Transform, OtherDerived>::ResultType\n  operator * (const EigenBase<OtherDerived> &other) const\n  { return internal::transform_right_product_impl<Transform, OtherDerived>::run(*this,other.derived()); }\n\n  /** \\returns the product expression of a transformation matrix \\a a times a transform \\a b\n    *\n    * The left hand side \\a other can be either:\n    * \\li a linear transformation matrix of size Dim x Dim,\n    * \\li an affine transformation matrix of size Dim x Dim+1,\n    * \\li a general transformation matrix of size Dim+1 x Dim+1.\n    */\n  template<typename OtherDerived> friend\n  EIGEN_DEVICE_FUNC inline const typename internal::transform_left_product_impl<OtherDerived,Mode,Options,_Dim,_Dim+1>::ResultType\n    operator * (const EigenBase<OtherDerived> &a, const Transform &b)\n  { return internal::transform_left_product_impl<OtherDerived,Mode,Options,Dim,HDim>::run(a.derived(),b); }\n\n  /** \\returns The product expression of a transform \\a a times a diagonal matrix \\a b\n    *\n    * The rhs diagonal matrix is interpreted as an affine scaling transformation. The\n    * product results in a Transform of the same type (mode) as the lhs only if the lhs \n    * mode is no isometry. In that case, the returned transform is an affinity.\n    */\n  template<typename DiagonalDerived>\n  EIGEN_DEVICE_FUNC inline const TransformTimeDiagonalReturnType\n    operator * (const DiagonalBase<DiagonalDerived> &b) const\n  {\n    TransformTimeDiagonalReturnType res(*this);\n    res.linearExt() *= b;\n    return res;\n  }\n\n  /** \\returns The product expression of a diagonal matrix \\a a times a transform \\a b\n    *\n    * The lhs diagonal matrix is interpreted as an affine scaling transformation. The\n    * product results in a Transform of the same type (mode) as the lhs only if the lhs \n    * mode is no isometry. In that case, the returned transform is an affinity.\n    */\n  template<typename DiagonalDerived>\n  EIGEN_DEVICE_FUNC friend inline TransformTimeDiagonalReturnType\n    operator * (const DiagonalBase<DiagonalDerived> &a, const Transform &b)\n  {\n    TransformTimeDiagonalReturnType res;\n    res.linear().noalias() = a*b.linear();\n    res.translation().noalias() = a*b.translation();\n    if (EIGEN_CONST_CONDITIONAL(Mode!=int(AffineCompact)))\n      res.matrix().row(Dim) = b.matrix().row(Dim);\n    return res;\n  }\n\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC inline Transform& operator*=(const EigenBase<OtherDerived>& other) { return *this = *this * other; }\n\n  /** Concatenates two transformations */\n  EIGEN_DEVICE_FUNC inline const Transform operator * (const Transform& other) const\n  {\n    return internal::transform_transform_product_impl<Transform,Transform>::run(*this,other);\n  }\n  \n  #if EIGEN_COMP_ICC\nprivate:\n  // this intermediate structure permits to workaround a bug in ICC 11:\n  //   error: template instantiation resulted in unexpected function type of \"Eigen::Transform<double, 3, 32, 0>\n  //             (const Eigen::Transform<double, 3, 2, 0> &) const\"\n  //  (the meaning of a name may have changed since the template declaration -- the type of the template is:\n  // \"Eigen::internal::transform_transform_product_impl<Eigen::Transform<double, 3, 32, 0>,\n  //     Eigen::Transform<double, 3, Mode, Options>, <expression>>::ResultType (const Eigen::Transform<double, 3, Mode, Options> &) const\")\n  // \n  template<int OtherMode,int OtherOptions> struct icc_11_workaround\n  {\n    typedef internal::transform_transform_product_impl<Transform,Transform<Scalar,Dim,OtherMode,OtherOptions> > ProductType;\n    typedef typename ProductType::ResultType ResultType;\n  };\n  \npublic:\n  /** Concatenates two different transformations */\n  template<int OtherMode,int OtherOptions>\n  inline typename icc_11_workaround<OtherMode,OtherOptions>::ResultType\n    operator * (const Transform<Scalar,Dim,OtherMode,OtherOptions>& other) const\n  {\n    typedef typename icc_11_workaround<OtherMode,OtherOptions>::ProductType ProductType;\n    return ProductType::run(*this,other);\n  }\n  #else\n  /** Concatenates two different transformations */\n  template<int OtherMode,int OtherOptions>\n  EIGEN_DEVICE_FUNC inline typename internal::transform_transform_product_impl<Transform,Transform<Scalar,Dim,OtherMode,OtherOptions> >::ResultType\n    operator * (const Transform<Scalar,Dim,OtherMode,OtherOptions>& other) const\n  {\n    return internal::transform_transform_product_impl<Transform,Transform<Scalar,Dim,OtherMode,OtherOptions> >::run(*this,other);\n  }\n  #endif\n\n  /** \\sa MatrixBase::setIdentity() */\n  EIGEN_DEVICE_FUNC void setIdentity() { m_matrix.setIdentity(); }\n\n  /**\n   * \\brief Returns an identity transformation.\n   * \\todo In the future this function should be returning a Transform expression.\n   */\n  EIGEN_DEVICE_FUNC static const Transform Identity()\n  {\n    return Transform(MatrixType::Identity());\n  }\n\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC \n  inline Transform& scale(const MatrixBase<OtherDerived> &other);\n\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC\n  inline Transform& prescale(const MatrixBase<OtherDerived> &other);\n\n  EIGEN_DEVICE_FUNC inline Transform& scale(const Scalar& s);\n  EIGEN_DEVICE_FUNC inline Transform& prescale(const Scalar& s);\n\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC\n  inline Transform& translate(const MatrixBase<OtherDerived> &other);\n\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC\n  inline Transform& pretranslate(const MatrixBase<OtherDerived> &other);\n\n  template<typename RotationType>\n  EIGEN_DEVICE_FUNC\n  inline Transform& rotate(const RotationType& rotation);\n\n  template<typename RotationType>\n  EIGEN_DEVICE_FUNC\n  inline Transform& prerotate(const RotationType& rotation);\n\n  EIGEN_DEVICE_FUNC Transform& shear(const Scalar& sx, const Scalar& sy);\n  EIGEN_DEVICE_FUNC Transform& preshear(const Scalar& sx, const Scalar& sy);\n\n  EIGEN_DEVICE_FUNC inline Transform& operator=(const TranslationType& t);\n  \n  EIGEN_DEVICE_FUNC\n  inline Transform& operator*=(const TranslationType& t) { return translate(t.vector()); }\n  \n  EIGEN_DEVICE_FUNC inline Transform operator*(const TranslationType& t) const;\n\n  EIGEN_DEVICE_FUNC \n  inline Transform& operator=(const UniformScaling<Scalar>& t);\n  \n  EIGEN_DEVICE_FUNC\n  inline Transform& operator*=(const UniformScaling<Scalar>& s) { return scale(s.factor()); }\n  \n  EIGEN_DEVICE_FUNC\n  inline TransformTimeDiagonalReturnType operator*(const UniformScaling<Scalar>& s) const\n  {\n    TransformTimeDiagonalReturnType res = *this;\n    res.scale(s.factor());\n    return res;\n  }\n\n  EIGEN_DEVICE_FUNC\n  inline Transform& operator*=(const DiagonalMatrix<Scalar,Dim>& s) { linearExt() *= s; return *this; }\n\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline Transform& operator=(const RotationBase<Derived,Dim>& r);\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline Transform& operator*=(const RotationBase<Derived,Dim>& r) { return rotate(r.toRotationMatrix()); }\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline Transform operator*(const RotationBase<Derived,Dim>& r) const;\n\n  typedef typename internal::conditional<int(Mode)==Isometry,ConstLinearPart,const LinearMatrixType>::type RotationReturnType;\n  EIGEN_DEVICE_FUNC RotationReturnType rotation() const;\n\n  template<typename RotationMatrixType, typename ScalingMatrixType>\n  EIGEN_DEVICE_FUNC\n  void computeRotationScaling(RotationMatrixType *rotation, ScalingMatrixType *scaling) const;\n  template<typename ScalingMatrixType, typename RotationMatrixType>\n  EIGEN_DEVICE_FUNC\n  void computeScalingRotation(ScalingMatrixType *scaling, RotationMatrixType *rotation) const;\n\n  template<typename PositionDerived, typename OrientationType, typename ScaleDerived>\n  EIGEN_DEVICE_FUNC\n  Transform& fromPositionOrientationScale(const MatrixBase<PositionDerived> &position,\n    const OrientationType& orientation, const MatrixBase<ScaleDerived> &scale);\n\n  EIGEN_DEVICE_FUNC\n  inline Transform inverse(TransformTraits traits = (TransformTraits)Mode) const;\n\n  /** \\returns a const pointer to the column major internal matrix */\n  EIGEN_DEVICE_FUNC const Scalar* data() const { return m_matrix.data(); }\n  /** \\returns a non-const pointer to the column major internal matrix */\n  EIGEN_DEVICE_FUNC Scalar* data() { return m_matrix.data(); }\n\n  /** \\returns \\c *this with scalar type casted to \\a NewScalarType\n    *\n    * Note that if \\a NewScalarType is equal to the current scalar type of \\c *this\n    * then this function smartly returns a const reference to \\c *this.\n    */\n  template<typename NewScalarType>\n  EIGEN_DEVICE_FUNC inline typename internal::cast_return_type<Transform,Transform<NewScalarType,Dim,Mode,Options> >::type cast() const\n  { return typename internal::cast_return_type<Transform,Transform<NewScalarType,Dim,Mode,Options> >::type(*this); }\n\n  /** Copy constructor with scalar type conversion */\n  template<typename OtherScalarType>\n  EIGEN_DEVICE_FUNC inline explicit Transform(const Transform<OtherScalarType,Dim,Mode,Options>& other)\n  {\n    check_template_params();\n    m_matrix = other.matrix().template cast<Scalar>();\n  }\n\n  /** \\returns \\c true if \\c *this is approximately equal to \\a other, within the precision\n    * determined by \\a prec.\n    *\n    * \\sa MatrixBase::isApprox() */\n  EIGEN_DEVICE_FUNC bool isApprox(const Transform& other, const typename NumTraits<Scalar>::Real& prec = NumTraits<Scalar>::dummy_precision()) const\n  { return m_matrix.isApprox(other.m_matrix, prec); }\n\n  /** Sets the last row to [0 ... 0 1]\n    */\n  EIGEN_DEVICE_FUNC void makeAffine()\n  {\n    internal::transform_make_affine<int(Mode)>::run(m_matrix);\n  }\n\n  /** \\internal\n    * \\returns the Dim x Dim linear part if the transformation is affine,\n    *          and the HDim x Dim part for projective transformations.\n    */\n  EIGEN_DEVICE_FUNC inline Block<MatrixType,int(Mode)==int(Projective)?HDim:Dim,Dim> linearExt()\n  { return m_matrix.template block<int(Mode)==int(Projective)?HDim:Dim,Dim>(0,0); }\n  /** \\internal\n    * \\returns the Dim x Dim linear part if the transformation is affine,\n    *          and the HDim x Dim part for projective transformations.\n    */\n  EIGEN_DEVICE_FUNC inline const Block<MatrixType,int(Mode)==int(Projective)?HDim:Dim,Dim> linearExt() const\n  { return m_matrix.template block<int(Mode)==int(Projective)?HDim:Dim,Dim>(0,0); }\n\n  /** \\internal\n    * \\returns the translation part if the transformation is affine,\n    *          and the last column for projective transformations.\n    */\n  EIGEN_DEVICE_FUNC inline Block<MatrixType,int(Mode)==int(Projective)?HDim:Dim,1> translationExt()\n  { return m_matrix.template block<int(Mode)==int(Projective)?HDim:Dim,1>(0,Dim); }\n  /** \\internal\n    * \\returns the translation part if the transformation is affine,\n    *          and the last column for projective transformations.\n    */\n  EIGEN_DEVICE_FUNC inline const Block<MatrixType,int(Mode)==int(Projective)?HDim:Dim,1> translationExt() const\n  { return m_matrix.template block<int(Mode)==int(Projective)?HDim:Dim,1>(0,Dim); }\n\n\n  #ifdef EIGEN_TRANSFORM_PLUGIN\n  #include EIGEN_TRANSFORM_PLUGIN\n  #endif\n  \nprotected:\n  #ifndef EIGEN_PARSED_BY_DOXYGEN\n    EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE void check_template_params()\n    {\n      EIGEN_STATIC_ASSERT((Options & (DontAlign|RowMajor)) == Options, INVALID_MATRIX_TEMPLATE_PARAMETERS)\n    }\n  #endif\n\n};\n\n/** \\ingroup Geometry_Module */\ntypedef Transform<float,2,Isometry> Isometry2f;\n/** \\ingroup Geometry_Module */\ntypedef Transform<float,3,Isometry> Isometry3f;\n/** \\ingroup Geometry_Module */\ntypedef Transform<double,2,Isometry> Isometry2d;\n/** \\ingroup Geometry_Module */\ntypedef Transform<double,3,Isometry> Isometry3d;\n\n/** \\ingroup Geometry_Module */\ntypedef Transform<float,2,Affine> Affine2f;\n/** \\ingroup Geometry_Module */\ntypedef Transform<float,3,Affine> Affine3f;\n/** \\ingroup Geometry_Module */\ntypedef Transform<double,2,Affine> Affine2d;\n/** \\ingroup Geometry_Module */\ntypedef Transform<double,3,Affine> Affine3d;\n\n/** \\ingroup Geometry_Module */\ntypedef Transform<float,2,AffineCompact> AffineCompact2f;\n/** \\ingroup Geometry_Module */\ntypedef Transform<float,3,AffineCompact> AffineCompact3f;\n/** \\ingroup Geometry_Module */\ntypedef Transform<double,2,AffineCompact> AffineCompact2d;\n/** \\ingroup Geometry_Module */\ntypedef Transform<double,3,AffineCompact> AffineCompact3d;\n\n/** \\ingroup Geometry_Module */\ntypedef Transform<float,2,Projective> Projective2f;\n/** \\ingroup Geometry_Module */\ntypedef Transform<float,3,Projective> Projective3f;\n/** \\ingroup Geometry_Module */\ntypedef Transform<double,2,Projective> Projective2d;\n/** \\ingroup Geometry_Module */\ntypedef Transform<double,3,Projective> Projective3d;\n\n/**************************\n*** Optional QT support ***\n**************************/\n\n#ifdef EIGEN_QT_SUPPORT\n/** Initializes \\c *this from a QMatrix assuming the dimension is 2.\n  *\n  * This function is available only if the token EIGEN_QT_SUPPORT is defined.\n  */\ntemplate<typename Scalar, int Dim, int Mode,int Options>\nTransform<Scalar,Dim,Mode,Options>::Transform(const QMatrix& other)\n{\n  check_template_params();\n  *this = other;\n}\n\n/** Set \\c *this from a QMatrix assuming the dimension is 2.\n  *\n  * This function is available only if the token EIGEN_QT_SUPPORT is defined.\n  */\ntemplate<typename Scalar, int Dim, int Mode,int Options>\nTransform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::operator=(const QMatrix& other)\n{\n  EIGEN_STATIC_ASSERT(Dim==2, YOU_MADE_A_PROGRAMMING_MISTAKE)\n  if (EIGEN_CONST_CONDITIONAL(Mode == int(AffineCompact)))\n    m_matrix << other.m11(), other.m21(), other.dx(),\n                other.m12(), other.m22(), other.dy();\n  else\n    m_matrix << other.m11(), other.m21(), other.dx(),\n                other.m12(), other.m22(), other.dy(),\n                0, 0, 1;\n  return *this;\n}\n\n/** \\returns a QMatrix from \\c *this assuming the dimension is 2.\n  *\n  * \\warning this conversion might loss data if \\c *this is not affine\n  *\n  * This function is available only if the token EIGEN_QT_SUPPORT is defined.\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nQMatrix Transform<Scalar,Dim,Mode,Options>::toQMatrix(void) const\n{\n  check_template_params();\n  EIGEN_STATIC_ASSERT(Dim==2, YOU_MADE_A_PROGRAMMING_MISTAKE)\n  return QMatrix(m_matrix.coeff(0,0), m_matrix.coeff(1,0),\n                 m_matrix.coeff(0,1), m_matrix.coeff(1,1),\n                 m_matrix.coeff(0,2), m_matrix.coeff(1,2));\n}\n\n/** Initializes \\c *this from a QTransform assuming the dimension is 2.\n  *\n  * This function is available only if the token EIGEN_QT_SUPPORT is defined.\n  */\ntemplate<typename Scalar, int Dim, int Mode,int Options>\nTransform<Scalar,Dim,Mode,Options>::Transform(const QTransform& other)\n{\n  check_template_params();\n  *this = other;\n}\n\n/** Set \\c *this from a QTransform assuming the dimension is 2.\n  *\n  * This function is available only if the token EIGEN_QT_SUPPORT is defined.\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nTransform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::operator=(const QTransform& other)\n{\n  check_template_params();\n  EIGEN_STATIC_ASSERT(Dim==2, YOU_MADE_A_PROGRAMMING_MISTAKE)\n  if (EIGEN_CONST_CONDITIONAL(Mode == int(AffineCompact)))\n    m_matrix << other.m11(), other.m21(), other.dx(),\n                other.m12(), other.m22(), other.dy();\n  else\n    m_matrix << other.m11(), other.m21(), other.dx(),\n                other.m12(), other.m22(), other.dy(),\n                other.m13(), other.m23(), other.m33();\n  return *this;\n}\n\n/** \\returns a QTransform from \\c *this assuming the dimension is 2.\n  *\n  * This function is available only if the token EIGEN_QT_SUPPORT is defined.\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nQTransform Transform<Scalar,Dim,Mode,Options>::toQTransform(void) const\n{\n  EIGEN_STATIC_ASSERT(Dim==2, YOU_MADE_A_PROGRAMMING_MISTAKE)\n  if (EIGEN_CONST_CONDITIONAL(Mode == int(AffineCompact)))\n    return QTransform(m_matrix.coeff(0,0), m_matrix.coeff(1,0),\n                      m_matrix.coeff(0,1), m_matrix.coeff(1,1),\n                      m_matrix.coeff(0,2), m_matrix.coeff(1,2));\n  else\n    return QTransform(m_matrix.coeff(0,0), m_matrix.coeff(1,0), m_matrix.coeff(2,0),\n                      m_matrix.coeff(0,1), m_matrix.coeff(1,1), m_matrix.coeff(2,1),\n                      m_matrix.coeff(0,2), m_matrix.coeff(1,2), m_matrix.coeff(2,2));\n}\n#endif\n\n/*********************\n*** Procedural API ***\n*********************/\n\n/** Applies on the right the non uniform scale transformation represented\n  * by the vector \\a other to \\c *this and returns a reference to \\c *this.\n  * \\sa prescale()\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode,Options>&\nTransform<Scalar,Dim,Mode,Options>::scale(const MatrixBase<OtherDerived> &other)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(OtherDerived,int(Dim))\n  EIGEN_STATIC_ASSERT(Mode!=int(Isometry), THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS)\n  linearExt().noalias() = (linearExt() * other.asDiagonal());\n  return *this;\n}\n\n/** Applies on the right a uniform scale of a factor \\a c to \\c *this\n  * and returns a reference to \\c *this.\n  * \\sa prescale(Scalar)\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nEIGEN_DEVICE_FUNC inline Transform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::scale(const Scalar& s)\n{\n  EIGEN_STATIC_ASSERT(Mode!=int(Isometry), THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS)\n  linearExt() *= s;\n  return *this;\n}\n\n/** Applies on the left the non uniform scale transformation represented\n  * by the vector \\a other to \\c *this and returns a reference to \\c *this.\n  * \\sa scale()\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode,Options>&\nTransform<Scalar,Dim,Mode,Options>::prescale(const MatrixBase<OtherDerived> &other)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(OtherDerived,int(Dim))\n  EIGEN_STATIC_ASSERT(Mode!=int(Isometry), THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS)\n  affine().noalias() = (other.asDiagonal() * affine());\n  return *this;\n}\n\n/** Applies on the left a uniform scale of a factor \\a c to \\c *this\n  * and returns a reference to \\c *this.\n  * \\sa scale(Scalar)\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nEIGEN_DEVICE_FUNC inline Transform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::prescale(const Scalar& s)\n{\n  EIGEN_STATIC_ASSERT(Mode!=int(Isometry), THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS)\n  m_matrix.template topRows<Dim>() *= s;\n  return *this;\n}\n\n/** Applies on the right the translation matrix represented by the vector \\a other\n  * to \\c *this and returns a reference to \\c *this.\n  * \\sa pretranslate()\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode,Options>&\nTransform<Scalar,Dim,Mode,Options>::translate(const MatrixBase<OtherDerived> &other)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(OtherDerived,int(Dim))\n  translationExt() += linearExt() * other;\n  return *this;\n}\n\n/** Applies on the left the translation matrix represented by the vector \\a other\n  * to \\c *this and returns a reference to \\c *this.\n  * \\sa translate()\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode,Options>&\nTransform<Scalar,Dim,Mode,Options>::pretranslate(const MatrixBase<OtherDerived> &other)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(OtherDerived,int(Dim))\n  if(EIGEN_CONST_CONDITIONAL(int(Mode)==int(Projective)))\n    affine() += other * m_matrix.row(Dim);\n  else\n    translation() += other;\n  return *this;\n}\n\n/** Applies on the right the rotation represented by the rotation \\a rotation\n  * to \\c *this and returns a reference to \\c *this.\n  *\n  * The template parameter \\a RotationType is the type of the rotation which\n  * must be known by internal::toRotationMatrix<>.\n  *\n  * Natively supported types includes:\n  *   - any scalar (2D),\n  *   - a Dim x Dim matrix expression,\n  *   - a Quaternion (3D),\n  *   - a AngleAxis (3D)\n  *\n  * This mechanism is easily extendable to support user types such as Euler angles,\n  * or a pair of Quaternion for 4D rotations.\n  *\n  * \\sa rotate(Scalar), class Quaternion, class AngleAxis, prerotate(RotationType)\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename RotationType>\nEIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode,Options>&\nTransform<Scalar,Dim,Mode,Options>::rotate(const RotationType& rotation)\n{\n  linearExt() *= internal::toRotationMatrix<Scalar,Dim>(rotation);\n  return *this;\n}\n\n/** Applies on the left the rotation represented by the rotation \\a rotation\n  * to \\c *this and returns a reference to \\c *this.\n  *\n  * See rotate() for further details.\n  *\n  * \\sa rotate()\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename RotationType>\nEIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode,Options>&\nTransform<Scalar,Dim,Mode,Options>::prerotate(const RotationType& rotation)\n{\n  m_matrix.template block<Dim,HDim>(0,0) = internal::toRotationMatrix<Scalar,Dim>(rotation)\n                                         * m_matrix.template block<Dim,HDim>(0,0);\n  return *this;\n}\n\n/** Applies on the right the shear transformation represented\n  * by the vector \\a other to \\c *this and returns a reference to \\c *this.\n  * \\warning 2D only.\n  * \\sa preshear()\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nEIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode,Options>&\nTransform<Scalar,Dim,Mode,Options>::shear(const Scalar& sx, const Scalar& sy)\n{\n  EIGEN_STATIC_ASSERT(int(Dim)==2, YOU_MADE_A_PROGRAMMING_MISTAKE)\n  EIGEN_STATIC_ASSERT(Mode!=int(Isometry), THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS)\n  VectorType tmp = linear().col(0)*sy + linear().col(1);\n  linear() << linear().col(0) + linear().col(1)*sx, tmp;\n  return *this;\n}\n\n/** Applies on the left the shear transformation represented\n  * by the vector \\a other to \\c *this and returns a reference to \\c *this.\n  * \\warning 2D only.\n  * \\sa shear()\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nEIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode,Options>&\nTransform<Scalar,Dim,Mode,Options>::preshear(const Scalar& sx, const Scalar& sy)\n{\n  EIGEN_STATIC_ASSERT(int(Dim)==2, YOU_MADE_A_PROGRAMMING_MISTAKE)\n  EIGEN_STATIC_ASSERT(Mode!=int(Isometry), THIS_METHOD_IS_ONLY_FOR_SPECIFIC_TRANSFORMATIONS)\n  m_matrix.template block<Dim,HDim>(0,0) = LinearMatrixType(1, sx, sy, 1) * m_matrix.template block<Dim,HDim>(0,0);\n  return *this;\n}\n\n/******************************************************\n*** Scaling, Translation and Rotation compatibility ***\n******************************************************/\n\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nEIGEN_DEVICE_FUNC inline Transform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::operator=(const TranslationType& t)\n{\n  linear().setIdentity();\n  translation() = t.vector();\n  makeAffine();\n  return *this;\n}\n\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nEIGEN_DEVICE_FUNC inline Transform<Scalar,Dim,Mode,Options> Transform<Scalar,Dim,Mode,Options>::operator*(const TranslationType& t) const\n{\n  Transform res = *this;\n  res.translate(t.vector());\n  return res;\n}\n\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nEIGEN_DEVICE_FUNC inline Transform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::operator=(const UniformScaling<Scalar>& s)\n{\n  m_matrix.setZero();\n  linear().diagonal().fill(s.factor());\n  makeAffine();\n  return *this;\n}\n\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC inline Transform<Scalar,Dim,Mode,Options>& Transform<Scalar,Dim,Mode,Options>::operator=(const RotationBase<Derived,Dim>& r)\n{\n  linear() = internal::toRotationMatrix<Scalar,Dim>(r);\n  translation().setZero();\n  makeAffine();\n  return *this;\n}\n\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC inline Transform<Scalar,Dim,Mode,Options> Transform<Scalar,Dim,Mode,Options>::operator*(const RotationBase<Derived,Dim>& r) const\n{\n  Transform res = *this;\n  res.rotate(r.derived());\n  return res;\n}\n\n/************************\n*** Special functions ***\n************************/\n\nnamespace internal {\ntemplate<int Mode> struct transform_rotation_impl {\n  template<typename TransformType>\n  EIGEN_DEVICE_FUNC static inline\n  const typename TransformType::LinearMatrixType run(const TransformType& t)\n  {\n    typedef typename TransformType::LinearMatrixType LinearMatrixType; \n    LinearMatrixType result;\n    t.computeRotationScaling(&result, (LinearMatrixType*)0);\n    return result;\n  }\n};\ntemplate<> struct transform_rotation_impl<Isometry> {\n  template<typename TransformType>\n  EIGEN_DEVICE_FUNC static inline\n  typename TransformType::ConstLinearPart run(const TransformType& t)\n  {\n    return t.linear();\n  }\n};\n}\n/** \\returns the rotation part of the transformation\n  *\n  * If Mode==Isometry, then this method is an alias for linear(),\n  * otherwise it calls computeRotationScaling() to extract the rotation\n  * through a SVD decomposition.\n  *\n  * \\svd_module\n  *\n  * \\sa computeRotationScaling(), computeScalingRotation(), class SVD\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nEIGEN_DEVICE_FUNC\ntypename Transform<Scalar,Dim,Mode,Options>::RotationReturnType\nTransform<Scalar,Dim,Mode,Options>::rotation() const\n{\n  return internal::transform_rotation_impl<Mode>::run(*this);\n}\n\n\n/** decomposes the linear part of the transformation as a product rotation x scaling, the scaling being\n  * not necessarily positive.\n  *\n  * If either pointer is zero, the corresponding computation is skipped.\n  *\n  *\n  *\n  * \\svd_module\n  *\n  * \\sa computeScalingRotation(), rotation(), class SVD\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename RotationMatrixType, typename ScalingMatrixType>\nEIGEN_DEVICE_FUNC void Transform<Scalar,Dim,Mode,Options>::computeRotationScaling(RotationMatrixType *rotation, ScalingMatrixType *scaling) const\n{\n  // Note that JacobiSVD is faster than BDCSVD for small matrices.\n  JacobiSVD<LinearMatrixType> svd(linear(), ComputeFullU | ComputeFullV);\n\n  Scalar x = (svd.matrixU() * svd.matrixV().adjoint()).determinant() < Scalar(0) ? Scalar(-1) : Scalar(1); // so x has absolute value 1\n  VectorType sv(svd.singularValues());\n  sv.coeffRef(Dim-1) *= x;\n  if(scaling) *scaling = svd.matrixV() * sv.asDiagonal() * svd.matrixV().adjoint();\n  if(rotation)\n  {\n    LinearMatrixType m(svd.matrixU());\n    m.col(Dim-1) *= x;\n    *rotation = m * svd.matrixV().adjoint();\n  }\n}\n\n/** decomposes the linear part of the transformation as a product scaling x rotation, the scaling being\n  * not necessarily positive.\n  *\n  * If either pointer is zero, the corresponding computation is skipped.\n  *\n  *\n  *\n  * \\svd_module\n  *\n  * \\sa computeRotationScaling(), rotation(), class SVD\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename ScalingMatrixType, typename RotationMatrixType>\nEIGEN_DEVICE_FUNC void Transform<Scalar,Dim,Mode,Options>::computeScalingRotation(ScalingMatrixType *scaling, RotationMatrixType *rotation) const\n{\n  // Note that JacobiSVD is faster than BDCSVD for small matrices.\n  JacobiSVD<LinearMatrixType> svd(linear(), ComputeFullU | ComputeFullV);\n\n  Scalar x = (svd.matrixU() * svd.matrixV().adjoint()).determinant() < Scalar(0) ? Scalar(-1) : Scalar(1); // so x has absolute value 1\n  VectorType sv(svd.singularValues());\n  sv.coeffRef(Dim-1) *= x;\n  if(scaling) *scaling = svd.matrixU() * sv.asDiagonal() * svd.matrixU().adjoint();\n  if(rotation)\n  {\n    LinearMatrixType m(svd.matrixU());\n    m.col(Dim-1) *= x;\n    *rotation = m * svd.matrixV().adjoint();\n  }\n}\n\n/** Convenient method to set \\c *this from a position, orientation and scale\n  * of a 3D object.\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\ntemplate<typename PositionDerived, typename OrientationType, typename ScaleDerived>\nEIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode,Options>&\nTransform<Scalar,Dim,Mode,Options>::fromPositionOrientationScale(const MatrixBase<PositionDerived> &position,\n  const OrientationType& orientation, const MatrixBase<ScaleDerived> &scale)\n{\n  linear() = internal::toRotationMatrix<Scalar,Dim>(orientation);\n  linear() *= scale.asDiagonal();\n  translation() = position;\n  makeAffine();\n  return *this;\n}\n\nnamespace internal {\n\ntemplate<int Mode>\nstruct transform_make_affine\n{\n  template<typename MatrixType>\n  EIGEN_DEVICE_FUNC static void run(MatrixType &mat)\n  {\n    static const int Dim = MatrixType::ColsAtCompileTime-1;\n    mat.template block<1,Dim>(Dim,0).setZero();\n    mat.coeffRef(Dim,Dim) = typename MatrixType::Scalar(1);\n  }\n};\n\ntemplate<>\nstruct transform_make_affine<AffineCompact>\n{\n  template<typename MatrixType> EIGEN_DEVICE_FUNC static void run(MatrixType &) { }\n};\n    \n// selector needed to avoid taking the inverse of a 3x4 matrix\ntemplate<typename TransformType, int Mode=TransformType::Mode>\nstruct projective_transform_inverse\n{\n  EIGEN_DEVICE_FUNC static inline void run(const TransformType&, TransformType&)\n  {}\n};\n\ntemplate<typename TransformType>\nstruct projective_transform_inverse<TransformType, Projective>\n{\n  EIGEN_DEVICE_FUNC static inline void run(const TransformType& m, TransformType& res)\n  {\n    res.matrix() = m.matrix().inverse();\n  }\n};\n\n} // end namespace internal\n\n\n/**\n  *\n  * \\returns the inverse transformation according to some given knowledge\n  * on \\c *this.\n  *\n  * \\param hint allows to optimize the inversion process when the transformation\n  * is known to be not a general transformation (optional). The possible values are:\n  *  - #Projective if the transformation is not necessarily affine, i.e., if the\n  *    last row is not guaranteed to be [0 ... 0 1]\n  *  - #Affine if the last row can be assumed to be [0 ... 0 1]\n  *  - #Isometry if the transformation is only a concatenations of translations\n  *    and rotations.\n  *  The default is the template class parameter \\c Mode.\n  *\n  * \\warning unless \\a traits is always set to NoShear or NoScaling, this function\n  * requires the generic inverse method of MatrixBase defined in the LU module. If\n  * you forget to include this module, then you will get hard to debug linking errors.\n  *\n  * \\sa MatrixBase::inverse()\n  */\ntemplate<typename Scalar, int Dim, int Mode, int Options>\nEIGEN_DEVICE_FUNC Transform<Scalar,Dim,Mode,Options>\nTransform<Scalar,Dim,Mode,Options>::inverse(TransformTraits hint) const\n{\n  Transform res;\n  if (hint == Projective)\n  {\n    internal::projective_transform_inverse<Transform>::run(*this, res);\n  }\n  else\n  {\n    if (hint == Isometry)\n    {\n      res.matrix().template topLeftCorner<Dim,Dim>() = linear().transpose();\n    }\n    else if(hint&Affine)\n    {\n      res.matrix().template topLeftCorner<Dim,Dim>() = linear().inverse();\n    }\n    else\n    {\n      eigen_assert(false && \"Invalid transform traits in Transform::Inverse\");\n    }\n    // translation and remaining parts\n    res.matrix().template topRightCorner<Dim,1>()\n      = - res.matrix().template topLeftCorner<Dim,Dim>() * translation();\n    res.makeAffine(); // we do need this, because in the beginning res is uninitialized\n  }\n  return res;\n}\n\nnamespace internal {\n\n/*****************************************************\n*** Specializations of take affine part            ***\n*****************************************************/\n\ntemplate<typename TransformType> struct transform_take_affine_part {\n  typedef typename TransformType::MatrixType MatrixType;\n  typedef typename TransformType::AffinePart AffinePart;\n  typedef typename TransformType::ConstAffinePart ConstAffinePart;\n  static inline AffinePart run(MatrixType& m)\n  { return m.template block<TransformType::Dim,TransformType::HDim>(0,0); }\n  static inline ConstAffinePart run(const MatrixType& m)\n  { return m.template block<TransformType::Dim,TransformType::HDim>(0,0); }\n};\n\ntemplate<typename Scalar, int Dim, int Options>\nstruct transform_take_affine_part<Transform<Scalar,Dim,AffineCompact, Options> > {\n  typedef typename Transform<Scalar,Dim,AffineCompact,Options>::MatrixType MatrixType;\n  static inline MatrixType& run(MatrixType& m) { return m; }\n  static inline const MatrixType& run(const MatrixType& m) { return m; }\n};\n\n/*****************************************************\n*** Specializations of construct from matrix       ***\n*****************************************************/\n\ntemplate<typename Other, int Mode, int Options, int Dim, int HDim>\nstruct transform_construct_from_matrix<Other, Mode,Options,Dim,HDim, Dim,Dim>\n{\n  static inline void run(Transform<typename Other::Scalar,Dim,Mode,Options> *transform, const Other& other)\n  {\n    transform->linear() = other;\n    transform->translation().setZero();\n    transform->makeAffine();\n  }\n};\n\ntemplate<typename Other, int Mode, int Options, int Dim, int HDim>\nstruct transform_construct_from_matrix<Other, Mode,Options,Dim,HDim, Dim,HDim>\n{\n  static inline void run(Transform<typename Other::Scalar,Dim,Mode,Options> *transform, const Other& other)\n  {\n    transform->affine() = other;\n    transform->makeAffine();\n  }\n};\n\ntemplate<typename Other, int Mode, int Options, int Dim, int HDim>\nstruct transform_construct_from_matrix<Other, Mode,Options,Dim,HDim, HDim,HDim>\n{\n  static inline void run(Transform<typename Other::Scalar,Dim,Mode,Options> *transform, const Other& other)\n  { transform->matrix() = other; }\n};\n\ntemplate<typename Other, int Options, int Dim, int HDim>\nstruct transform_construct_from_matrix<Other, AffineCompact,Options,Dim,HDim, HDim,HDim>\n{\n  static inline void run(Transform<typename Other::Scalar,Dim,AffineCompact,Options> *transform, const Other& other)\n  { transform->matrix() = other.template block<Dim,HDim>(0,0); }\n};\n\n/**********************************************************\n***   Specializations of operator* with rhs EigenBase   ***\n**********************************************************/\n\ntemplate<int LhsMode,int RhsMode>\nstruct transform_product_result\n{\n  enum \n  { \n    Mode =\n      (LhsMode == (int)Projective    || RhsMode == (int)Projective    ) ? Projective :\n      (LhsMode == (int)Affine        || RhsMode == (int)Affine        ) ? Affine :\n      (LhsMode == (int)AffineCompact || RhsMode == (int)AffineCompact ) ? AffineCompact :\n      (LhsMode == (int)Isometry      || RhsMode == (int)Isometry      ) ? Isometry : Projective\n  };\n};\n\ntemplate< typename TransformType, typename MatrixType, int RhsCols>\nstruct transform_right_product_impl< TransformType, MatrixType, 0, RhsCols>\n{\n  typedef typename MatrixType::PlainObject ResultType;\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other)\n  {\n    return T.matrix() * other;\n  }\n};\n\ntemplate< typename TransformType, typename MatrixType, int RhsCols>\nstruct transform_right_product_impl< TransformType, MatrixType, 1, RhsCols>\n{\n  enum { \n    Dim = TransformType::Dim, \n    HDim = TransformType::HDim,\n    OtherRows = MatrixType::RowsAtCompileTime,\n    OtherCols = MatrixType::ColsAtCompileTime\n  };\n\n  typedef typename MatrixType::PlainObject ResultType;\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other)\n  {\n    EIGEN_STATIC_ASSERT(OtherRows==HDim, YOU_MIXED_MATRICES_OF_DIFFERENT_SIZES);\n\n    typedef Block<ResultType, Dim, OtherCols, int(MatrixType::RowsAtCompileTime)==Dim> TopLeftLhs;\n\n    ResultType res(other.rows(),other.cols());\n    TopLeftLhs(res, 0, 0, Dim, other.cols()).noalias() = T.affine() * other;\n    res.row(OtherRows-1) = other.row(OtherRows-1);\n    \n    return res;\n  }\n};\n\ntemplate< typename TransformType, typename MatrixType, int RhsCols>\nstruct transform_right_product_impl< TransformType, MatrixType, 2, RhsCols>\n{\n  enum { \n    Dim = TransformType::Dim, \n    HDim = TransformType::HDim,\n    OtherRows = MatrixType::RowsAtCompileTime,\n    OtherCols = MatrixType::ColsAtCompileTime\n  };\n\n  typedef typename MatrixType::PlainObject ResultType;\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other)\n  {\n    EIGEN_STATIC_ASSERT(OtherRows==Dim, YOU_MIXED_MATRICES_OF_DIFFERENT_SIZES);\n\n    typedef Block<ResultType, Dim, OtherCols, true> TopLeftLhs;\n    ResultType res(Replicate<typename TransformType::ConstTranslationPart, 1, OtherCols>(T.translation(),1,other.cols()));\n    TopLeftLhs(res, 0, 0, Dim, other.cols()).noalias() += T.linear() * other;\n\n    return res;\n  }\n};\n\ntemplate< typename TransformType, typename MatrixType >\nstruct transform_right_product_impl< TransformType, MatrixType, 2, 1> // rhs is a vector of size Dim\n{\n  typedef typename TransformType::MatrixType TransformMatrix;\n  enum {\n    Dim = TransformType::Dim,\n    HDim = TransformType::HDim,\n    OtherRows = MatrixType::RowsAtCompileTime,\n    WorkingRows = EIGEN_PLAIN_ENUM_MIN(TransformMatrix::RowsAtCompileTime,HDim)\n  };\n\n  typedef typename MatrixType::PlainObject ResultType;\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ResultType run(const TransformType& T, const MatrixType& other)\n  {\n    EIGEN_STATIC_ASSERT(OtherRows==Dim, YOU_MIXED_MATRICES_OF_DIFFERENT_SIZES);\n\n    Matrix<typename ResultType::Scalar, Dim+1, 1> rhs;\n    rhs.template head<Dim>() = other; rhs[Dim] = typename ResultType::Scalar(1);\n    Matrix<typename ResultType::Scalar, WorkingRows, 1> res(T.matrix() * rhs);\n    return res.template head<Dim>();\n  }\n};\n\n/**********************************************************\n***   Specializations of operator* with lhs EigenBase   ***\n**********************************************************/\n\n// generic HDim x HDim matrix * T => Projective\ntemplate<typename Other,int Mode, int Options, int Dim, int HDim>\nstruct transform_left_product_impl<Other,Mode,Options,Dim,HDim, HDim,HDim>\n{\n  typedef Transform<typename Other::Scalar,Dim,Mode,Options> TransformType;\n  typedef typename TransformType::MatrixType MatrixType;\n  typedef Transform<typename Other::Scalar,Dim,Projective,Options> ResultType;\n  static ResultType run(const Other& other,const TransformType& tr)\n  { return ResultType(other * tr.matrix()); }\n};\n\n// generic HDim x HDim matrix * AffineCompact => Projective\ntemplate<typename Other, int Options, int Dim, int HDim>\nstruct transform_left_product_impl<Other,AffineCompact,Options,Dim,HDim, HDim,HDim>\n{\n  typedef Transform<typename Other::Scalar,Dim,AffineCompact,Options> TransformType;\n  typedef typename TransformType::MatrixType MatrixType;\n  typedef Transform<typename Other::Scalar,Dim,Projective,Options> ResultType;\n  static ResultType run(const Other& other,const TransformType& tr)\n  {\n    ResultType res;\n    res.matrix().noalias() = other.template block<HDim,Dim>(0,0) * tr.matrix();\n    res.matrix().col(Dim) += other.col(Dim);\n    return res;\n  }\n};\n\n// affine matrix * T\ntemplate<typename Other,int Mode, int Options, int Dim, int HDim>\nstruct transform_left_product_impl<Other,Mode,Options,Dim,HDim, Dim,HDim>\n{\n  typedef Transform<typename Other::Scalar,Dim,Mode,Options> TransformType;\n  typedef typename TransformType::MatrixType MatrixType;\n  typedef TransformType ResultType;\n  static ResultType run(const Other& other,const TransformType& tr)\n  {\n    ResultType res;\n    res.affine().noalias() = other * tr.matrix();\n    res.matrix().row(Dim) = tr.matrix().row(Dim);\n    return res;\n  }\n};\n\n// affine matrix * AffineCompact\ntemplate<typename Other, int Options, int Dim, int HDim>\nstruct transform_left_product_impl<Other,AffineCompact,Options,Dim,HDim, Dim,HDim>\n{\n  typedef Transform<typename Other::Scalar,Dim,AffineCompact,Options> TransformType;\n  typedef typename TransformType::MatrixType MatrixType;\n  typedef TransformType ResultType;\n  static ResultType run(const Other& other,const TransformType& tr)\n  {\n    ResultType res;\n    res.matrix().noalias() = other.template block<Dim,Dim>(0,0) * tr.matrix();\n    res.translation() += other.col(Dim);\n    return res;\n  }\n};\n\n// linear matrix * T\ntemplate<typename Other,int Mode, int Options, int Dim, int HDim>\nstruct transform_left_product_impl<Other,Mode,Options,Dim,HDim, Dim,Dim>\n{\n  typedef Transform<typename Other::Scalar,Dim,Mode,Options> TransformType;\n  typedef typename TransformType::MatrixType MatrixType;\n  typedef TransformType ResultType;\n  static ResultType run(const Other& other, const TransformType& tr)\n  {\n    TransformType res;\n    if(Mode!=int(AffineCompact))\n      res.matrix().row(Dim) = tr.matrix().row(Dim);\n    res.matrix().template topRows<Dim>().noalias()\n      = other * tr.matrix().template topRows<Dim>();\n    return res;\n  }\n};\n\n/**********************************************************\n*** Specializations of operator* with another Transform ***\n**********************************************************/\n\ntemplate<typename Scalar, int Dim, int LhsMode, int LhsOptions, int RhsMode, int RhsOptions>\nstruct transform_transform_product_impl<Transform<Scalar,Dim,LhsMode,LhsOptions>,Transform<Scalar,Dim,RhsMode,RhsOptions>,false >\n{\n  enum { ResultMode = transform_product_result<LhsMode,RhsMode>::Mode };\n  typedef Transform<Scalar,Dim,LhsMode,LhsOptions> Lhs;\n  typedef Transform<Scalar,Dim,RhsMode,RhsOptions> Rhs;\n  typedef Transform<Scalar,Dim,ResultMode,LhsOptions> ResultType;\n  static ResultType run(const Lhs& lhs, const Rhs& rhs)\n  {\n    ResultType res;\n    res.linear() = lhs.linear() * rhs.linear();\n    res.translation() = lhs.linear() * rhs.translation() + lhs.translation();\n    res.makeAffine();\n    return res;\n  }\n};\n\ntemplate<typename Scalar, int Dim, int LhsMode, int LhsOptions, int RhsMode, int RhsOptions>\nstruct transform_transform_product_impl<Transform<Scalar,Dim,LhsMode,LhsOptions>,Transform<Scalar,Dim,RhsMode,RhsOptions>,true >\n{\n  typedef Transform<Scalar,Dim,LhsMode,LhsOptions> Lhs;\n  typedef Transform<Scalar,Dim,RhsMode,RhsOptions> Rhs;\n  typedef Transform<Scalar,Dim,Projective> ResultType;\n  static ResultType run(const Lhs& lhs, const Rhs& rhs)\n  {\n    return ResultType( lhs.matrix() * rhs.matrix() );\n  }\n};\n\ntemplate<typename Scalar, int Dim, int LhsOptions, int RhsOptions>\nstruct transform_transform_product_impl<Transform<Scalar,Dim,AffineCompact,LhsOptions>,Transform<Scalar,Dim,Projective,RhsOptions>,true >\n{\n  typedef Transform<Scalar,Dim,AffineCompact,LhsOptions> Lhs;\n  typedef Transform<Scalar,Dim,Projective,RhsOptions> Rhs;\n  typedef Transform<Scalar,Dim,Projective> ResultType;\n  static ResultType run(const Lhs& lhs, const Rhs& rhs)\n  {\n    ResultType res;\n    res.matrix().template topRows<Dim>() = lhs.matrix() * rhs.matrix();\n    res.matrix().row(Dim) = rhs.matrix().row(Dim);\n    return res;\n  }\n};\n\ntemplate<typename Scalar, int Dim, int LhsOptions, int RhsOptions>\nstruct transform_transform_product_impl<Transform<Scalar,Dim,Projective,LhsOptions>,Transform<Scalar,Dim,AffineCompact,RhsOptions>,true >\n{\n  typedef Transform<Scalar,Dim,Projective,LhsOptions> Lhs;\n  typedef Transform<Scalar,Dim,AffineCompact,RhsOptions> Rhs;\n  typedef Transform<Scalar,Dim,Projective> ResultType;\n  static ResultType run(const Lhs& lhs, const Rhs& rhs)\n  {\n    ResultType res(lhs.matrix().template leftCols<Dim>() * rhs.matrix());\n    res.matrix().col(Dim) += lhs.matrix().col(Dim);\n    return res;\n  }\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_TRANSFORM_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Geometry/Translation.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_TRANSLATION_H\n#define EIGEN_TRANSLATION_H\n\nnamespace Eigen { \n\n/** \\geometry_module \\ingroup Geometry_Module\n  *\n  * \\class Translation\n  *\n  * \\brief Represents a translation transformation\n  *\n  * \\tparam _Scalar the scalar type, i.e., the type of the coefficients.\n  * \\tparam _Dim the  dimension of the space, can be a compile time value or Dynamic\n  *\n  * \\note This class is not aimed to be used to store a translation transformation,\n  * but rather to make easier the constructions and updates of Transform objects.\n  *\n  * \\sa class Scaling, class Transform\n  */\ntemplate<typename _Scalar, int _Dim>\nclass Translation\n{\npublic:\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_Dim)\n  /** dimension of the space */\n  enum { Dim = _Dim };\n  /** the scalar type of the coefficients */\n  typedef _Scalar Scalar;\n  /** corresponding vector type */\n  typedef Matrix<Scalar,Dim,1> VectorType;\n  /** corresponding linear transformation matrix type */\n  typedef Matrix<Scalar,Dim,Dim> LinearMatrixType;\n  /** corresponding affine transformation type */\n  typedef Transform<Scalar,Dim,Affine> AffineTransformType;\n  /** corresponding isometric transformation type */\n  typedef Transform<Scalar,Dim,Isometry> IsometryTransformType;\n\nprotected:\n\n  VectorType m_coeffs;\n\npublic:\n\n  /** Default constructor without initialization. */\n  EIGEN_DEVICE_FUNC Translation() {}\n  /**  */\n  EIGEN_DEVICE_FUNC inline Translation(const Scalar& sx, const Scalar& sy)\n  {\n    eigen_assert(Dim==2);\n    m_coeffs.x() = sx;\n    m_coeffs.y() = sy;\n  }\n  /**  */\n  EIGEN_DEVICE_FUNC inline Translation(const Scalar& sx, const Scalar& sy, const Scalar& sz)\n  {\n    eigen_assert(Dim==3);\n    m_coeffs.x() = sx;\n    m_coeffs.y() = sy;\n    m_coeffs.z() = sz;\n  }\n  /** Constructs and initialize the translation transformation from a vector of translation coefficients */\n  EIGEN_DEVICE_FUNC explicit inline Translation(const VectorType& vector) : m_coeffs(vector) {}\n\n  /** \\brief Returns the x-translation by value. **/\n  EIGEN_DEVICE_FUNC inline Scalar x() const { return m_coeffs.x(); }\n  /** \\brief Returns the y-translation by value. **/\n  EIGEN_DEVICE_FUNC inline Scalar y() const { return m_coeffs.y(); }\n  /** \\brief Returns the z-translation by value. **/\n  EIGEN_DEVICE_FUNC inline Scalar z() const { return m_coeffs.z(); }\n\n  /** \\brief Returns the x-translation as a reference. **/\n  EIGEN_DEVICE_FUNC inline Scalar& x() { return m_coeffs.x(); }\n  /** \\brief Returns the y-translation as a reference. **/\n  EIGEN_DEVICE_FUNC inline Scalar& y() { return m_coeffs.y(); }\n  /** \\brief Returns the z-translation as a reference. **/\n  EIGEN_DEVICE_FUNC inline Scalar& z() { return m_coeffs.z(); }\n\n  EIGEN_DEVICE_FUNC const VectorType& vector() const { return m_coeffs; }\n  EIGEN_DEVICE_FUNC VectorType& vector() { return m_coeffs; }\n\n  EIGEN_DEVICE_FUNC const VectorType& translation() const { return m_coeffs; }\n  EIGEN_DEVICE_FUNC VectorType& translation() { return m_coeffs; }\n\n  /** Concatenates two translation */\n  EIGEN_DEVICE_FUNC inline Translation operator* (const Translation& other) const\n  { return Translation(m_coeffs + other.m_coeffs); }\n\n  /** Concatenates a translation and a uniform scaling */\n  EIGEN_DEVICE_FUNC inline AffineTransformType operator* (const UniformScaling<Scalar>& other) const;\n\n  /** Concatenates a translation and a linear transformation */\n  template<typename OtherDerived>\n  EIGEN_DEVICE_FUNC inline AffineTransformType operator* (const EigenBase<OtherDerived>& linear) const;\n\n  /** Concatenates a translation and a rotation */\n  template<typename Derived>\n  EIGEN_DEVICE_FUNC inline IsometryTransformType operator*(const RotationBase<Derived,Dim>& r) const\n  { return *this * IsometryTransformType(r); }\n\n  /** \\returns the concatenation of a linear transformation \\a l with the translation \\a t */\n  // its a nightmare to define a templated friend function outside its declaration\n  template<typename OtherDerived> friend\n  EIGEN_DEVICE_FUNC inline AffineTransformType operator*(const EigenBase<OtherDerived>& linear, const Translation& t)\n  {\n    AffineTransformType res;\n    res.matrix().setZero();\n    res.linear() = linear.derived();\n    res.translation() = linear.derived() * t.m_coeffs;\n    res.matrix().row(Dim).setZero();\n    res(Dim,Dim) = Scalar(1);\n    return res;\n  }\n\n  /** Concatenates a translation and a transformation */\n  template<int Mode, int Options>\n  EIGEN_DEVICE_FUNC inline Transform<Scalar,Dim,Mode> operator* (const Transform<Scalar,Dim,Mode,Options>& t) const\n  {\n    Transform<Scalar,Dim,Mode> res = t;\n    res.pretranslate(m_coeffs);\n    return res;\n  }\n\n  /** Applies translation to vector */\n  template<typename Derived>\n  inline typename internal::enable_if<Derived::IsVectorAtCompileTime,VectorType>::type\n  operator* (const MatrixBase<Derived>& vec) const\n  { return m_coeffs + vec.derived(); }\n\n  /** \\returns the inverse translation (opposite) */\n  Translation inverse() const { return Translation(-m_coeffs); }\n\n  static const Translation Identity() { return Translation(VectorType::Zero()); }\n\n  /** \\returns \\c *this with scalar type casted to \\a NewScalarType\n    *\n    * Note that if \\a NewScalarType is equal to the current scalar type of \\c *this\n    * then this function smartly returns a const reference to \\c *this.\n    */\n  template<typename NewScalarType>\n  EIGEN_DEVICE_FUNC inline typename internal::cast_return_type<Translation,Translation<NewScalarType,Dim> >::type cast() const\n  { return typename internal::cast_return_type<Translation,Translation<NewScalarType,Dim> >::type(*this); }\n\n  /** Copy constructor with scalar type conversion */\n  template<typename OtherScalarType>\n  EIGEN_DEVICE_FUNC inline explicit Translation(const Translation<OtherScalarType,Dim>& other)\n  { m_coeffs = other.vector().template cast<Scalar>(); }\n\n  /** \\returns \\c true if \\c *this is approximately equal to \\a other, within the precision\n    * determined by \\a prec.\n    *\n    * \\sa MatrixBase::isApprox() */\n  EIGEN_DEVICE_FUNC bool isApprox(const Translation& other, const typename NumTraits<Scalar>::Real& prec = NumTraits<Scalar>::dummy_precision()) const\n  { return m_coeffs.isApprox(other.m_coeffs, prec); }\n\n};\n\n/** \\addtogroup Geometry_Module */\n//@{\ntypedef Translation<float, 2> Translation2f;\ntypedef Translation<double,2> Translation2d;\ntypedef Translation<float, 3> Translation3f;\ntypedef Translation<double,3> Translation3d;\n//@}\n\ntemplate<typename Scalar, int Dim>\nEIGEN_DEVICE_FUNC inline typename Translation<Scalar,Dim>::AffineTransformType\nTranslation<Scalar,Dim>::operator* (const UniformScaling<Scalar>& other) const\n{\n  AffineTransformType res;\n  res.matrix().setZero();\n  res.linear().diagonal().fill(other.factor());\n  res.translation() = m_coeffs;\n  res(Dim,Dim) = Scalar(1);\n  return res;\n}\n\ntemplate<typename Scalar, int Dim>\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC inline typename Translation<Scalar,Dim>::AffineTransformType\nTranslation<Scalar,Dim>::operator* (const EigenBase<OtherDerived>& linear) const\n{\n  AffineTransformType res;\n  res.matrix().setZero();\n  res.linear() = linear.derived();\n  res.translation() = m_coeffs;\n  res.matrix().row(Dim).setZero();\n  res(Dim,Dim) = Scalar(1);\n  return res;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_TRANSLATION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Geometry/Umeyama.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_UMEYAMA_H\n#define EIGEN_UMEYAMA_H\n\n// This file requires the user to include \n// * Eigen/Core\n// * Eigen/LU \n// * Eigen/SVD\n// * Eigen/Array\n\nnamespace Eigen { \n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n\n// These helpers are required since it allows to use mixed types as parameters\n// for the Umeyama. The problem with mixed parameters is that the return type\n// cannot trivially be deduced when float and double types are mixed.\nnamespace internal {\n\n// Compile time return type deduction for different MatrixBase types.\n// Different means here different alignment and parameters but the same underlying\n// real scalar type.\ntemplate<typename MatrixType, typename OtherMatrixType>\nstruct umeyama_transform_matrix_type\n{\n  enum {\n    MinRowsAtCompileTime = EIGEN_SIZE_MIN_PREFER_DYNAMIC(MatrixType::RowsAtCompileTime, OtherMatrixType::RowsAtCompileTime),\n\n    // When possible we want to choose some small fixed size value since the result\n    // is likely to fit on the stack. So here, EIGEN_SIZE_MIN_PREFER_DYNAMIC is not what we want.\n    HomogeneousDimension = int(MinRowsAtCompileTime) == Dynamic ? Dynamic : int(MinRowsAtCompileTime)+1\n  };\n\n  typedef Matrix<typename traits<MatrixType>::Scalar,\n    HomogeneousDimension,\n    HomogeneousDimension,\n    AutoAlign | (traits<MatrixType>::Flags & RowMajorBit ? RowMajor : ColMajor),\n    HomogeneousDimension,\n    HomogeneousDimension\n  > type;\n};\n\n}\n\n#endif\n\n/**\n* \\geometry_module \\ingroup Geometry_Module\n*\n* \\brief Returns the transformation between two point sets.\n*\n* The algorithm is based on:\n* \"Least-squares estimation of transformation parameters between two point patterns\",\n* Shinji Umeyama, PAMI 1991, DOI: 10.1109/34.88573\n*\n* It estimates parameters \\f$ c, \\mathbf{R}, \\f$ and \\f$ \\mathbf{t} \\f$ such that\n* \\f{align*}\n*   \\frac{1}{n} \\sum_{i=1}^n \\vert\\vert y_i - (c\\mathbf{R}x_i + \\mathbf{t}) \\vert\\vert_2^2\n* \\f}\n* is minimized.\n*\n* The algorithm is based on the analysis of the covariance matrix\n* \\f$ \\Sigma_{\\mathbf{x}\\mathbf{y}} \\in \\mathbb{R}^{d \\times d} \\f$\n* of the input point sets \\f$ \\mathbf{x} \\f$ and \\f$ \\mathbf{y} \\f$ where \n* \\f$d\\f$ is corresponding to the dimension (which is typically small).\n* The analysis is involving the SVD having a complexity of \\f$O(d^3)\\f$\n* though the actual computational effort lies in the covariance\n* matrix computation which has an asymptotic lower bound of \\f$O(dm)\\f$ when \n* the input point sets have dimension \\f$d \\times m\\f$.\n*\n* Currently the method is working only for floating point matrices.\n*\n* \\todo Should the return type of umeyama() become a Transform?\n*\n* \\param src Source points \\f$ \\mathbf{x} = \\left( x_1, \\hdots, x_n \\right) \\f$.\n* \\param dst Destination points \\f$ \\mathbf{y} = \\left( y_1, \\hdots, y_n \\right) \\f$.\n* \\param with_scaling Sets \\f$ c=1 \\f$ when <code>false</code> is passed.\n* \\return The homogeneous transformation \n* \\f{align*}\n*   T = \\begin{bmatrix} c\\mathbf{R} & \\mathbf{t} \\\\ \\mathbf{0} & 1 \\end{bmatrix}\n* \\f}\n* minimizing the residual above. This transformation is always returned as an \n* Eigen::Matrix.\n*/\ntemplate <typename Derived, typename OtherDerived>\ntypename internal::umeyama_transform_matrix_type<Derived, OtherDerived>::type\numeyama(const MatrixBase<Derived>& src, const MatrixBase<OtherDerived>& dst, bool with_scaling = true)\n{\n  typedef typename internal::umeyama_transform_matrix_type<Derived, OtherDerived>::type TransformationMatrixType;\n  typedef typename internal::traits<TransformationMatrixType>::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  EIGEN_STATIC_ASSERT(!NumTraits<Scalar>::IsComplex, NUMERIC_TYPE_MUST_BE_REAL)\n  EIGEN_STATIC_ASSERT((internal::is_same<Scalar, typename internal::traits<OtherDerived>::Scalar>::value),\n    YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n\n  enum { Dimension = EIGEN_SIZE_MIN_PREFER_DYNAMIC(Derived::RowsAtCompileTime, OtherDerived::RowsAtCompileTime) };\n\n  typedef Matrix<Scalar, Dimension, 1> VectorType;\n  typedef Matrix<Scalar, Dimension, Dimension> MatrixType;\n  typedef typename internal::plain_matrix_type_row_major<Derived>::type RowMajorMatrixType;\n\n  const Index m = src.rows(); // dimension\n  const Index n = src.cols(); // number of measurements\n\n  // required for demeaning ...\n  const RealScalar one_over_n = RealScalar(1) / static_cast<RealScalar>(n);\n\n  // computation of mean\n  const VectorType src_mean = src.rowwise().sum() * one_over_n;\n  const VectorType dst_mean = dst.rowwise().sum() * one_over_n;\n\n  // demeaning of src and dst points\n  const RowMajorMatrixType src_demean = src.colwise() - src_mean;\n  const RowMajorMatrixType dst_demean = dst.colwise() - dst_mean;\n\n  // Eq. (36)-(37)\n  const Scalar src_var = src_demean.rowwise().squaredNorm().sum() * one_over_n;\n\n  // Eq. (38)\n  const MatrixType sigma = one_over_n * dst_demean * src_demean.transpose();\n\n  JacobiSVD<MatrixType> svd(sigma, ComputeFullU | ComputeFullV);\n\n  // Initialize the resulting transformation with an identity matrix...\n  TransformationMatrixType Rt = TransformationMatrixType::Identity(m+1,m+1);\n\n  // Eq. (39)\n  VectorType S = VectorType::Ones(m);\n\n  if  ( svd.matrixU().determinant() * svd.matrixV().determinant() < 0 )\n    S(m-1) = -1;\n\n  // Eq. (40) and (43)\n  Rt.block(0,0,m,m).noalias() = svd.matrixU() * S.asDiagonal() * svd.matrixV().transpose();\n\n  if (with_scaling)\n  {\n    // Eq. (42)\n    const Scalar c = Scalar(1)/src_var * svd.singularValues().dot(S);\n\n    // Eq. (41)\n    Rt.col(m).head(m) = dst_mean;\n    Rt.col(m).head(m).noalias() -= c*Rt.topLeftCorner(m,m)*src_mean;\n    Rt.block(0,0,m,m) *= c;\n  }\n  else\n  {\n    Rt.col(m).head(m) = dst_mean;\n    Rt.col(m).head(m).noalias() -= Rt.topLeftCorner(m,m)*src_mean;\n  }\n\n  return Rt;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_UMEYAMA_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Geometry/arch/Geometry_SIMD.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Rohit Garg <rpg.314@gmail.com>\n// Copyright (C) 2009-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_GEOMETRY_SIMD_H\n#define EIGEN_GEOMETRY_SIMD_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate<class Derived, class OtherDerived>\nstruct quat_product<Architecture::Target, Derived, OtherDerived, float>\n{\n  enum {\n    AAlignment = traits<Derived>::Alignment,\n    BAlignment = traits<OtherDerived>::Alignment,\n    ResAlignment = traits<Quaternion<float> >::Alignment\n  };\n  static inline Quaternion<float> run(const QuaternionBase<Derived>& _a, const QuaternionBase<OtherDerived>& _b)\n  {\n    evaluator<typename Derived::Coefficients> ae(_a.coeffs());\n    evaluator<typename OtherDerived::Coefficients> be(_b.coeffs());\n    Quaternion<float> res;\n    float arr[4] = {0.f, 0.f, 0.f, -0.f};\n    const Packet4f mask = pset<Packet4f>(arr);\n    Packet4f a = ae.template packet<AAlignment,Packet4f>(0);\n    Packet4f b = be.template packet<BAlignment,Packet4f>(0);\n    Packet4f s1 = pmul(vec4f_swizzle1(a,1,2,0,2),vec4f_swizzle1(b,2,0,1,2));\n    Packet4f s2 = pmul(vec4f_swizzle1(a,3,3,3,1),vec4f_swizzle1(b,0,1,2,1));\n    pstoret<float,Packet4f,ResAlignment>(\n              &res.x(),\n              padd(psub(pmul(a,vec4f_swizzle1(b,3,3,3,3)),\n                                    pmul(vec4f_swizzle1(a,2,0,1,0),\n                                               vec4f_swizzle1(b,1,2,0,0))),\n                         pxor(mask,padd(s1,s2))));\n    \n    return res;\n  }\n};\n\ntemplate<class Derived>\nstruct quat_conj<Architecture::Target, Derived, float>\n{\n  enum {\n    ResAlignment = traits<Quaternion<float> >::Alignment\n  };\n  static inline Quaternion<float> run(const QuaternionBase<Derived>& q)\n  {\n    evaluator<typename Derived::Coefficients> qe(q.coeffs());\n    Quaternion<float> res;\n    float arr[4] = {-0.f,-0.f,-0.f,0.f};\n    const Packet4f mask = pset<Packet4f>(arr);\n    pstoret<float,Packet4f,ResAlignment>(&res.x(), pxor(mask, qe.template packet<traits<Derived>::Alignment,Packet4f>(0)));\n    return res;\n  }\n};\n\n\ntemplate<typename VectorLhs,typename VectorRhs>\nstruct cross3_impl<Architecture::Target,VectorLhs,VectorRhs,float,true>\n{\n  enum {\n    ResAlignment = traits<typename plain_matrix_type<VectorLhs>::type>::Alignment\n  };\n  static inline typename plain_matrix_type<VectorLhs>::type\n  run(const VectorLhs& lhs, const VectorRhs& rhs)\n  {\n    evaluator<VectorLhs> lhs_eval(lhs);\n    evaluator<VectorRhs> rhs_eval(rhs);\n    Packet4f a = lhs_eval.template packet<traits<VectorLhs>::Alignment,Packet4f>(0);\n    Packet4f b = rhs_eval.template packet<traits<VectorRhs>::Alignment,Packet4f>(0);\n    Packet4f mul1 = pmul(vec4f_swizzle1(a,1,2,0,3),vec4f_swizzle1(b,2,0,1,3));\n    Packet4f mul2 = pmul(vec4f_swizzle1(a,2,0,1,3),vec4f_swizzle1(b,1,2,0,3));\n    typename plain_matrix_type<VectorLhs>::type res;\n    pstoret<float,Packet4f,ResAlignment>(&res.x(),psub(mul1,mul2));\n    return res;\n  }\n};\n\n\n\n#if (defined EIGEN_VECTORIZE_SSE) || (EIGEN_ARCH_ARM64)\n\ntemplate<class Derived, class OtherDerived>\nstruct quat_product<Architecture::Target, Derived, OtherDerived, double>\n{\n  enum {\n    BAlignment = traits<OtherDerived>::Alignment,\n    ResAlignment = traits<Quaternion<double> >::Alignment\n  };\n\n  static inline Quaternion<double> run(const QuaternionBase<Derived>& _a, const QuaternionBase<OtherDerived>& _b)\n  {\n  Quaternion<double> res;\n\n  evaluator<typename Derived::Coefficients> ae(_a.coeffs());\n  evaluator<typename OtherDerived::Coefficients> be(_b.coeffs());\n\n  const double* a = _a.coeffs().data();\n  Packet2d b_xy = be.template packet<BAlignment,Packet2d>(0);\n  Packet2d b_zw = be.template packet<BAlignment,Packet2d>(2);\n  Packet2d a_xx = pset1<Packet2d>(a[0]);\n  Packet2d a_yy = pset1<Packet2d>(a[1]);\n  Packet2d a_zz = pset1<Packet2d>(a[2]);\n  Packet2d a_ww = pset1<Packet2d>(a[3]);\n\n  // two temporaries:\n  Packet2d t1, t2;\n\n  /*\n   * t1 = ww*xy + yy*zw\n   * t2 = zz*xy - xx*zw\n   * res.xy = t1 +/- swap(t2)\n   */\n  t1 = padd(pmul(a_ww, b_xy), pmul(a_yy, b_zw));\n  t2 = psub(pmul(a_zz, b_xy), pmul(a_xx, b_zw));\n  pstoret<double,Packet2d,ResAlignment>(&res.x(), paddsub(t1, preverse(t2)));\n  \n  /*\n   * t1 = ww*zw - yy*xy\n   * t2 = zz*zw + xx*xy\n   * res.zw = t1 -/+ swap(t2) = swap( swap(t1) +/- t2)\n   */\n  t1 = psub(pmul(a_ww, b_zw), pmul(a_yy, b_xy));\n  t2 = padd(pmul(a_zz, b_zw), pmul(a_xx, b_xy));\n  pstoret<double,Packet2d,ResAlignment>(&res.z(), preverse(paddsub(preverse(t1), t2)));\n\n  return res;\n}\n};\n\ntemplate<class Derived>\nstruct quat_conj<Architecture::Target, Derived, double>\n{\n  enum {\n    ResAlignment = traits<Quaternion<double> >::Alignment\n  };\n  static inline Quaternion<double> run(const QuaternionBase<Derived>& q)\n  {\n    evaluator<typename Derived::Coefficients> qe(q.coeffs());\n    Quaternion<double> res;\n    double arr1[2] = {-0.0, -0.0};\n    double arr2[2] = {-0.0,  0.0};\n    const Packet2d mask0 = pset<Packet2d>(arr1);\n    const Packet2d mask2 = pset<Packet2d>(arr2);\n    pstoret<double,Packet2d,ResAlignment>(&res.x(), pxor(mask0, qe.template packet<traits<Derived>::Alignment,Packet2d>(0)));\n    pstoret<double,Packet2d,ResAlignment>(&res.z(), pxor(mask2, qe.template packet<traits<Derived>::Alignment,Packet2d>(2)));\n    return res;\n  }\n};\n\n#endif // end EIGEN_VECTORIZE_SSE_OR_EIGEN_ARCH_ARM64\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_GEOMETRY_SIMD_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Householder/BlockHouseholder.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Vincent Lejeune\n// Copyright (C) 2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BLOCK_HOUSEHOLDER_H\n#define EIGEN_BLOCK_HOUSEHOLDER_H\n\n// This file contains some helper function to deal with block householder reflectors\n\nnamespace Eigen { \n\nnamespace internal {\n  \n/** \\internal */\n// template<typename TriangularFactorType,typename VectorsType,typename CoeffsType>\n// void make_block_householder_triangular_factor(TriangularFactorType& triFactor, const VectorsType& vectors, const CoeffsType& hCoeffs)\n// {\n//   typedef typename VectorsType::Scalar Scalar;\n//   const Index nbVecs = vectors.cols();\n//   eigen_assert(triFactor.rows() == nbVecs && triFactor.cols() == nbVecs && vectors.rows()>=nbVecs);\n// \n//   for(Index i = 0; i < nbVecs; i++)\n//   {\n//     Index rs = vectors.rows() - i;\n//     // Warning, note that hCoeffs may alias with vectors.\n//     // It is then necessary to copy it before modifying vectors(i,i). \n//     typename CoeffsType::Scalar h = hCoeffs(i);\n//     // This hack permits to pass trough nested Block<> and Transpose<> expressions.\n//     Scalar *Vii_ptr = const_cast<Scalar*>(vectors.data() + vectors.outerStride()*i + vectors.innerStride()*i);\n//     Scalar Vii = *Vii_ptr;\n//     *Vii_ptr = Scalar(1);\n//     triFactor.col(i).head(i).noalias() = -h * vectors.block(i, 0, rs, i).adjoint()\n//                                        * vectors.col(i).tail(rs);\n//     *Vii_ptr = Vii;\n//     // FIXME add .noalias() once the triangular product can work inplace\n//     triFactor.col(i).head(i) = triFactor.block(0,0,i,i).template triangularView<Upper>()\n//                              * triFactor.col(i).head(i);\n//     triFactor(i,i) = hCoeffs(i);\n//   }\n// }\n\n/** \\internal */\n// This variant avoid modifications in vectors\ntemplate<typename TriangularFactorType,typename VectorsType,typename CoeffsType>\nvoid make_block_householder_triangular_factor(TriangularFactorType& triFactor, const VectorsType& vectors, const CoeffsType& hCoeffs)\n{\n  const Index nbVecs = vectors.cols();\n  eigen_assert(triFactor.rows() == nbVecs && triFactor.cols() == nbVecs && vectors.rows()>=nbVecs);\n\n  for(Index i = nbVecs-1; i >=0 ; --i)\n  {\n    Index rs = vectors.rows() - i - 1;\n    Index rt = nbVecs-i-1;\n\n    if(rt>0)\n    {\n      triFactor.row(i).tail(rt).noalias() = -hCoeffs(i) * vectors.col(i).tail(rs).adjoint()\n                                                        * vectors.bottomRightCorner(rs, rt).template triangularView<UnitLower>();\n            \n      // FIXME use the following line with .noalias() once the triangular product can work inplace\n      // triFactor.row(i).tail(rt) = triFactor.row(i).tail(rt) * triFactor.bottomRightCorner(rt,rt).template triangularView<Upper>();\n      for(Index j=nbVecs-1; j>i; --j)\n      {\n        typename TriangularFactorType::Scalar z = triFactor(i,j);\n        triFactor(i,j) = z * triFactor(j,j);\n        if(nbVecs-j-1>0)\n          triFactor.row(i).tail(nbVecs-j-1) += z * triFactor.row(j).tail(nbVecs-j-1);\n      }\n      \n    }\n    triFactor(i,i) = hCoeffs(i);\n  }\n}\n\n/** \\internal\n  * if forward then perform   mat = H0 * H1 * H2 * mat\n  * otherwise perform         mat = H2 * H1 * H0 * mat\n  */\ntemplate<typename MatrixType,typename VectorsType,typename CoeffsType>\nvoid apply_block_householder_on_the_left(MatrixType& mat, const VectorsType& vectors, const CoeffsType& hCoeffs, bool forward)\n{\n  enum { TFactorSize = MatrixType::ColsAtCompileTime };\n  Index nbVecs = vectors.cols();\n  Matrix<typename MatrixType::Scalar, TFactorSize, TFactorSize, RowMajor> T(nbVecs,nbVecs);\n  \n  if(forward) make_block_householder_triangular_factor(T, vectors, hCoeffs);\n  else        make_block_householder_triangular_factor(T, vectors, hCoeffs.conjugate());  \n  const TriangularView<const VectorsType, UnitLower> V(vectors);\n\n  // A -= V T V^* A\n  Matrix<typename MatrixType::Scalar,VectorsType::ColsAtCompileTime,MatrixType::ColsAtCompileTime,\n         (VectorsType::MaxColsAtCompileTime==1 && MatrixType::MaxColsAtCompileTime!=1)?RowMajor:ColMajor,\n         VectorsType::MaxColsAtCompileTime,MatrixType::MaxColsAtCompileTime> tmp = V.adjoint() * mat;\n  // FIXME add .noalias() once the triangular product can work inplace\n  if(forward) tmp = T.template triangularView<Upper>()           * tmp;\n  else        tmp = T.template triangularView<Upper>().adjoint() * tmp;\n  mat.noalias() -= V * tmp;\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_BLOCK_HOUSEHOLDER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Householder/Householder.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_HOUSEHOLDER_H\n#define EIGEN_HOUSEHOLDER_H\n\nnamespace Eigen { \n\nnamespace internal {\ntemplate<int n> struct decrement_size\n{\n  enum {\n    ret = n==Dynamic ? n : n-1\n  };\n};\n}\n\n/** Computes the elementary reflector H such that:\n  * \\f$ H *this = [ beta 0 ... 0]^T \\f$\n  * where the transformation H is:\n  * \\f$ H = I - tau v v^*\\f$\n  * and the vector v is:\n  * \\f$ v^T = [1 essential^T] \\f$\n  *\n  * The essential part of the vector \\c v is stored in *this.\n  * \n  * On output:\n  * \\param tau the scaling factor of the Householder transformation\n  * \\param beta the result of H * \\c *this\n  *\n  * \\sa MatrixBase::makeHouseholder(), MatrixBase::applyHouseholderOnTheLeft(),\n  *     MatrixBase::applyHouseholderOnTheRight()\n  */\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC\nvoid MatrixBase<Derived>::makeHouseholderInPlace(Scalar& tau, RealScalar& beta)\n{\n  VectorBlock<Derived, internal::decrement_size<Base::SizeAtCompileTime>::ret> essentialPart(derived(), 1, size()-1);\n  makeHouseholder(essentialPart, tau, beta);\n}\n\n/** Computes the elementary reflector H such that:\n  * \\f$ H *this = [ beta 0 ... 0]^T \\f$\n  * where the transformation H is:\n  * \\f$ H = I - tau v v^*\\f$\n  * and the vector v is:\n  * \\f$ v^T = [1 essential^T] \\f$\n  *\n  * On output:\n  * \\param essential the essential part of the vector \\c v\n  * \\param tau the scaling factor of the Householder transformation\n  * \\param beta the result of H * \\c *this\n  *\n  * \\sa MatrixBase::makeHouseholderInPlace(), MatrixBase::applyHouseholderOnTheLeft(),\n  *     MatrixBase::applyHouseholderOnTheRight()\n  */\ntemplate<typename Derived>\ntemplate<typename EssentialPart>\nEIGEN_DEVICE_FUNC\nvoid MatrixBase<Derived>::makeHouseholder(\n  EssentialPart& essential,\n  Scalar& tau,\n  RealScalar& beta) const\n{\n  using std::sqrt;\n  using numext::conj;\n  \n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(EssentialPart)\n  VectorBlock<const Derived, EssentialPart::SizeAtCompileTime> tail(derived(), 1, size()-1);\n  \n  RealScalar tailSqNorm = size()==1 ? RealScalar(0) : tail.squaredNorm();\n  Scalar c0 = coeff(0);\n  const RealScalar tol = (std::numeric_limits<RealScalar>::min)();\n\n  if(tailSqNorm <= tol && numext::abs2(numext::imag(c0))<=tol)\n  {\n    tau = RealScalar(0);\n    beta = numext::real(c0);\n    essential.setZero();\n  }\n  else\n  {\n    beta = sqrt(numext::abs2(c0) + tailSqNorm);\n    if (numext::real(c0)>=RealScalar(0))\n      beta = -beta;\n    essential = tail / (c0 - beta);\n    tau = conj((beta - c0) / beta);\n  }\n}\n\n/** Apply the elementary reflector H given by\n  * \\f$ H = I - tau v v^*\\f$\n  * with\n  * \\f$ v^T = [1 essential^T] \\f$\n  * from the left to a vector or matrix.\n  *\n  * On input:\n  * \\param essential the essential part of the vector \\c v\n  * \\param tau the scaling factor of the Householder transformation\n  * \\param workspace a pointer to working space with at least\n  *                  this->cols() entries\n  *\n  * \\sa MatrixBase::makeHouseholder(), MatrixBase::makeHouseholderInPlace(), \n  *     MatrixBase::applyHouseholderOnTheRight()\n  */\ntemplate<typename Derived>\ntemplate<typename EssentialPart>\nEIGEN_DEVICE_FUNC\nvoid MatrixBase<Derived>::applyHouseholderOnTheLeft(\n  const EssentialPart& essential,\n  const Scalar& tau,\n  Scalar* workspace)\n{\n  if(rows() == 1)\n  {\n    *this *= Scalar(1)-tau;\n  }\n  else if(tau!=Scalar(0))\n  {\n    Map<typename internal::plain_row_type<PlainObject>::type> tmp(workspace,cols());\n    Block<Derived, EssentialPart::SizeAtCompileTime, Derived::ColsAtCompileTime> bottom(derived(), 1, 0, rows()-1, cols());\n    tmp.noalias() = essential.adjoint() * bottom;\n    tmp += this->row(0);\n    this->row(0) -= tau * tmp;\n    bottom.noalias() -= tau * essential * tmp;\n  }\n}\n\n/** Apply the elementary reflector H given by\n  * \\f$ H = I - tau v v^*\\f$\n  * with\n  * \\f$ v^T = [1 essential^T] \\f$\n  * from the right to a vector or matrix.\n  *\n  * On input:\n  * \\param essential the essential part of the vector \\c v\n  * \\param tau the scaling factor of the Householder transformation\n  * \\param workspace a pointer to working space with at least\n  *                  this->rows() entries\n  *\n  * \\sa MatrixBase::makeHouseholder(), MatrixBase::makeHouseholderInPlace(), \n  *     MatrixBase::applyHouseholderOnTheLeft()\n  */\ntemplate<typename Derived>\ntemplate<typename EssentialPart>\nEIGEN_DEVICE_FUNC\nvoid MatrixBase<Derived>::applyHouseholderOnTheRight(\n  const EssentialPart& essential,\n  const Scalar& tau,\n  Scalar* workspace)\n{\n  if(cols() == 1)\n  {\n    *this *= Scalar(1)-tau;\n  }\n  else if(tau!=Scalar(0))\n  {\n    Map<typename internal::plain_col_type<PlainObject>::type> tmp(workspace,rows());\n    Block<Derived, Derived::RowsAtCompileTime, EssentialPart::SizeAtCompileTime> right(derived(), 0, 1, rows(), cols()-1);\n    tmp.noalias() = right * essential;\n    tmp += this->col(0);\n    this->col(0) -= tau * tmp;\n    right.noalias() -= tau * tmp * essential.adjoint();\n  }\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_HOUSEHOLDER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Householder/HouseholderSequence.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_HOUSEHOLDER_SEQUENCE_H\n#define EIGEN_HOUSEHOLDER_SEQUENCE_H\n\nnamespace Eigen { \n\n/** \\ingroup Householder_Module\n  * \\householder_module\n  * \\class HouseholderSequence\n  * \\brief Sequence of Householder reflections acting on subspaces with decreasing size\n  * \\tparam VectorsType type of matrix containing the Householder vectors\n  * \\tparam CoeffsType  type of vector containing the Householder coefficients\n  * \\tparam Side        either OnTheLeft (the default) or OnTheRight\n  *\n  * This class represents a product sequence of Householder reflections where the first Householder reflection\n  * acts on the whole space, the second Householder reflection leaves the one-dimensional subspace spanned by\n  * the first unit vector invariant, the third Householder reflection leaves the two-dimensional subspace\n  * spanned by the first two unit vectors invariant, and so on up to the last reflection which leaves all but\n  * one dimensions invariant and acts only on the last dimension. Such sequences of Householder reflections\n  * are used in several algorithms to zero out certain parts of a matrix. Indeed, the methods\n  * HessenbergDecomposition::matrixQ(), Tridiagonalization::matrixQ(), HouseholderQR::householderQ(),\n  * and ColPivHouseholderQR::householderQ() all return a %HouseholderSequence.\n  *\n  * More precisely, the class %HouseholderSequence represents an \\f$ n \\times n \\f$ matrix \\f$ H \\f$ of the\n  * form \\f$ H = \\prod_{i=0}^{n-1} H_i \\f$ where the i-th Householder reflection is \\f$ H_i = I - h_i v_i\n  * v_i^* \\f$. The i-th Householder coefficient \\f$ h_i \\f$ is a scalar and the i-th Householder vector \\f$\n  * v_i \\f$ is a vector of the form\n  * \\f[ \n  * v_i = [\\underbrace{0, \\ldots, 0}_{i-1\\mbox{ zeros}}, 1, \\underbrace{*, \\ldots,*}_{n-i\\mbox{ arbitrary entries}} ]. \n  * \\f]\n  * The last \\f$ n-i \\f$ entries of \\f$ v_i \\f$ are called the essential part of the Householder vector.\n  *\n  * Typical usages are listed below, where H is a HouseholderSequence:\n  * \\code\n  * A.applyOnTheRight(H);             // A = A * H\n  * A.applyOnTheLeft(H);              // A = H * A\n  * A.applyOnTheRight(H.adjoint());   // A = A * H^*\n  * A.applyOnTheLeft(H.adjoint());    // A = H^* * A\n  * MatrixXd Q = H;                   // conversion to a dense matrix\n  * \\endcode\n  * In addition to the adjoint, you can also apply the inverse (=adjoint), the transpose, and the conjugate operators.\n  *\n  * See the documentation for HouseholderSequence(const VectorsType&, const CoeffsType&) for an example.\n  *\n  * \\sa MatrixBase::applyOnTheLeft(), MatrixBase::applyOnTheRight()\n  */\n\nnamespace internal {\n\ntemplate<typename VectorsType, typename CoeffsType, int Side>\nstruct traits<HouseholderSequence<VectorsType,CoeffsType,Side> >\n{\n  typedef typename VectorsType::Scalar Scalar;\n  typedef typename VectorsType::StorageIndex StorageIndex;\n  typedef typename VectorsType::StorageKind StorageKind;\n  enum {\n    RowsAtCompileTime = Side==OnTheLeft ? traits<VectorsType>::RowsAtCompileTime\n                                        : traits<VectorsType>::ColsAtCompileTime,\n    ColsAtCompileTime = RowsAtCompileTime,\n    MaxRowsAtCompileTime = Side==OnTheLeft ? traits<VectorsType>::MaxRowsAtCompileTime\n                                           : traits<VectorsType>::MaxColsAtCompileTime,\n    MaxColsAtCompileTime = MaxRowsAtCompileTime,\n    Flags = 0\n  };\n};\n\nstruct HouseholderSequenceShape {};\n\ntemplate<typename VectorsType, typename CoeffsType, int Side>\nstruct evaluator_traits<HouseholderSequence<VectorsType,CoeffsType,Side> >\n  : public evaluator_traits_base<HouseholderSequence<VectorsType,CoeffsType,Side> >\n{\n  typedef HouseholderSequenceShape Shape;\n};\n\ntemplate<typename VectorsType, typename CoeffsType, int Side>\nstruct hseq_side_dependent_impl\n{\n  typedef Block<const VectorsType, Dynamic, 1> EssentialVectorType;\n  typedef HouseholderSequence<VectorsType, CoeffsType, OnTheLeft> HouseholderSequenceType;\n  static EIGEN_DEVICE_FUNC inline const EssentialVectorType essentialVector(const HouseholderSequenceType& h, Index k)\n  {\n    Index start = k+1+h.m_shift;\n    return Block<const VectorsType,Dynamic,1>(h.m_vectors, start, k, h.rows()-start, 1);\n  }\n};\n\ntemplate<typename VectorsType, typename CoeffsType>\nstruct hseq_side_dependent_impl<VectorsType, CoeffsType, OnTheRight>\n{\n  typedef Transpose<Block<const VectorsType, 1, Dynamic> > EssentialVectorType;\n  typedef HouseholderSequence<VectorsType, CoeffsType, OnTheRight> HouseholderSequenceType;\n  static inline const EssentialVectorType essentialVector(const HouseholderSequenceType& h, Index k)\n  {\n    Index start = k+1+h.m_shift;\n    return Block<const VectorsType,1,Dynamic>(h.m_vectors, k, start, 1, h.rows()-start).transpose();\n  }\n};\n\ntemplate<typename OtherScalarType, typename MatrixType> struct matrix_type_times_scalar_type\n{\n  typedef typename ScalarBinaryOpTraits<OtherScalarType, typename MatrixType::Scalar>::ReturnType\n    ResultScalar;\n  typedef Matrix<ResultScalar, MatrixType::RowsAtCompileTime, MatrixType::ColsAtCompileTime,\n                 0, MatrixType::MaxRowsAtCompileTime, MatrixType::MaxColsAtCompileTime> Type;\n};\n\n} // end namespace internal\n\ntemplate<typename VectorsType, typename CoeffsType, int Side> class HouseholderSequence\n  : public EigenBase<HouseholderSequence<VectorsType,CoeffsType,Side> >\n{\n    typedef typename internal::hseq_side_dependent_impl<VectorsType,CoeffsType,Side>::EssentialVectorType EssentialVectorType;\n  \n  public:\n    enum {\n      RowsAtCompileTime = internal::traits<HouseholderSequence>::RowsAtCompileTime,\n      ColsAtCompileTime = internal::traits<HouseholderSequence>::ColsAtCompileTime,\n      MaxRowsAtCompileTime = internal::traits<HouseholderSequence>::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = internal::traits<HouseholderSequence>::MaxColsAtCompileTime\n    };\n    typedef typename internal::traits<HouseholderSequence>::Scalar Scalar;\n\n    typedef HouseholderSequence<\n      typename internal::conditional<NumTraits<Scalar>::IsComplex,\n        typename internal::remove_all<typename VectorsType::ConjugateReturnType>::type,\n        VectorsType>::type,\n      typename internal::conditional<NumTraits<Scalar>::IsComplex,\n        typename internal::remove_all<typename CoeffsType::ConjugateReturnType>::type,\n        CoeffsType>::type,\n      Side\n    > ConjugateReturnType;\n\n    typedef HouseholderSequence<\n      VectorsType,\n      typename internal::conditional<NumTraits<Scalar>::IsComplex,\n        typename internal::remove_all<typename CoeffsType::ConjugateReturnType>::type,\n        CoeffsType>::type,\n      Side\n    > AdjointReturnType;\n\n    typedef HouseholderSequence<\n      typename internal::conditional<NumTraits<Scalar>::IsComplex,\n        typename internal::remove_all<typename VectorsType::ConjugateReturnType>::type,\n        VectorsType>::type,\n      CoeffsType,\n      Side\n    > TransposeReturnType;\n\n    typedef HouseholderSequence<\n      typename internal::add_const<VectorsType>::type,\n      typename internal::add_const<CoeffsType>::type,\n      Side\n    > ConstHouseholderSequence;\n\n    /** \\brief Constructor.\n      * \\param[in]  v      %Matrix containing the essential parts of the Householder vectors\n      * \\param[in]  h      Vector containing the Householder coefficients\n      *\n      * Constructs the Householder sequence with coefficients given by \\p h and vectors given by \\p v. The\n      * i-th Householder coefficient \\f$ h_i \\f$ is given by \\p h(i) and the essential part of the i-th\n      * Householder vector \\f$ v_i \\f$ is given by \\p v(k,i) with \\p k > \\p i (the subdiagonal part of the\n      * i-th column). If \\p v has fewer columns than rows, then the Householder sequence contains as many\n      * Householder reflections as there are columns.\n      *\n      * \\note The %HouseholderSequence object stores \\p v and \\p h by reference.\n      *\n      * Example: \\include HouseholderSequence_HouseholderSequence.cpp\n      * Output: \\verbinclude HouseholderSequence_HouseholderSequence.out\n      *\n      * \\sa setLength(), setShift()\n      */\n    EIGEN_DEVICE_FUNC\n    HouseholderSequence(const VectorsType& v, const CoeffsType& h)\n      : m_vectors(v), m_coeffs(h), m_reverse(false), m_length(v.diagonalSize()),\n        m_shift(0)\n    {\n    }\n\n    /** \\brief Copy constructor. */\n    EIGEN_DEVICE_FUNC\n    HouseholderSequence(const HouseholderSequence& other)\n      : m_vectors(other.m_vectors),\n        m_coeffs(other.m_coeffs),\n        m_reverse(other.m_reverse),\n        m_length(other.m_length),\n        m_shift(other.m_shift)\n    {\n    }\n\n    /** \\brief Number of rows of transformation viewed as a matrix.\n      * \\returns Number of rows \n      * \\details This equals the dimension of the space that the transformation acts on.\n      */\n    EIGEN_DEVICE_FUNC\n    Index rows() const { return Side==OnTheLeft ? m_vectors.rows() : m_vectors.cols(); }\n\n    /** \\brief Number of columns of transformation viewed as a matrix.\n      * \\returns Number of columns\n      * \\details This equals the dimension of the space that the transformation acts on.\n      */\n    EIGEN_DEVICE_FUNC\n    Index cols() const { return rows(); }\n\n    /** \\brief Essential part of a Householder vector.\n      * \\param[in]  k  Index of Householder reflection\n      * \\returns    Vector containing non-trivial entries of k-th Householder vector\n      *\n      * This function returns the essential part of the Householder vector \\f$ v_i \\f$. This is a vector of\n      * length \\f$ n-i \\f$ containing the last \\f$ n-i \\f$ entries of the vector\n      * \\f[ \n      * v_i = [\\underbrace{0, \\ldots, 0}_{i-1\\mbox{ zeros}}, 1, \\underbrace{*, \\ldots,*}_{n-i\\mbox{ arbitrary entries}} ]. \n      * \\f]\n      * The index \\f$ i \\f$ equals \\p k + shift(), corresponding to the k-th column of the matrix \\p v\n      * passed to the constructor.\n      *\n      * \\sa setShift(), shift()\n      */\n    EIGEN_DEVICE_FUNC\n    const EssentialVectorType essentialVector(Index k) const\n    {\n      eigen_assert(k >= 0 && k < m_length);\n      return internal::hseq_side_dependent_impl<VectorsType,CoeffsType,Side>::essentialVector(*this, k);\n    }\n\n    /** \\brief %Transpose of the Householder sequence. */\n    TransposeReturnType transpose() const\n    {\n      return TransposeReturnType(m_vectors.conjugate(), m_coeffs)\n              .setReverseFlag(!m_reverse)\n              .setLength(m_length)\n              .setShift(m_shift);\n    }\n\n    /** \\brief Complex conjugate of the Householder sequence. */\n    ConjugateReturnType conjugate() const\n    {\n      return ConjugateReturnType(m_vectors.conjugate(), m_coeffs.conjugate())\n             .setReverseFlag(m_reverse)\n             .setLength(m_length)\n             .setShift(m_shift);\n    }\n\n    /** \\returns an expression of the complex conjugate of \\c *this if Cond==true,\n     *           returns \\c *this otherwise.\n     */\n    template<bool Cond>\n    EIGEN_DEVICE_FUNC\n    inline typename internal::conditional<Cond,ConjugateReturnType,ConstHouseholderSequence>::type\n    conjugateIf() const\n    {\n      typedef typename internal::conditional<Cond,ConjugateReturnType,ConstHouseholderSequence>::type ReturnType;\n      return ReturnType(m_vectors.template conjugateIf<Cond>(), m_coeffs.template conjugateIf<Cond>());\n    }\n\n    /** \\brief Adjoint (conjugate transpose) of the Householder sequence. */\n    AdjointReturnType adjoint() const\n    {\n      return AdjointReturnType(m_vectors, m_coeffs.conjugate())\n              .setReverseFlag(!m_reverse)\n              .setLength(m_length)\n              .setShift(m_shift);\n    }\n\n    /** \\brief Inverse of the Householder sequence (equals the adjoint). */\n    AdjointReturnType inverse() const { return adjoint(); }\n\n    /** \\internal */\n    template<typename DestType>\n    inline EIGEN_DEVICE_FUNC\n    void evalTo(DestType& dst) const\n    {\n      Matrix<Scalar, DestType::RowsAtCompileTime, 1,\n             AutoAlign|ColMajor, DestType::MaxRowsAtCompileTime, 1> workspace(rows());\n      evalTo(dst, workspace);\n    }\n\n    /** \\internal */\n    template<typename Dest, typename Workspace>\n    EIGEN_DEVICE_FUNC\n    void evalTo(Dest& dst, Workspace& workspace) const\n    {\n      workspace.resize(rows());\n      Index vecs = m_length;\n      if(internal::is_same_dense(dst,m_vectors))\n      {\n        // in-place\n        dst.diagonal().setOnes();\n        dst.template triangularView<StrictlyUpper>().setZero();\n        for(Index k = vecs-1; k >= 0; --k)\n        {\n          Index cornerSize = rows() - k - m_shift;\n          if(m_reverse)\n            dst.bottomRightCorner(cornerSize, cornerSize)\n               .applyHouseholderOnTheRight(essentialVector(k), m_coeffs.coeff(k), workspace.data());\n          else\n            dst.bottomRightCorner(cornerSize, cornerSize)\n               .applyHouseholderOnTheLeft(essentialVector(k), m_coeffs.coeff(k), workspace.data());\n\n          // clear the off diagonal vector\n          dst.col(k).tail(rows()-k-1).setZero();\n        }\n        // clear the remaining columns if needed\n        for(Index k = 0; k<cols()-vecs ; ++k)\n          dst.col(k).tail(rows()-k-1).setZero();\n      }\n      else if(m_length>BlockSize)\n      {\n        dst.setIdentity(rows(), rows());\n        if(m_reverse)\n          applyThisOnTheLeft(dst,workspace,true);\n        else\n          applyThisOnTheLeft(dst,workspace,true);\n      }\n      else\n      {\n        dst.setIdentity(rows(), rows());\n        for(Index k = vecs-1; k >= 0; --k)\n        {\n          Index cornerSize = rows() - k - m_shift;\n          if(m_reverse)\n            dst.bottomRightCorner(cornerSize, cornerSize)\n               .applyHouseholderOnTheRight(essentialVector(k), m_coeffs.coeff(k), workspace.data());\n          else\n            dst.bottomRightCorner(cornerSize, cornerSize)\n               .applyHouseholderOnTheLeft(essentialVector(k), m_coeffs.coeff(k), workspace.data());\n        }\n      }\n    }\n\n    /** \\internal */\n    template<typename Dest> inline void applyThisOnTheRight(Dest& dst) const\n    {\n      Matrix<Scalar,1,Dest::RowsAtCompileTime,RowMajor,1,Dest::MaxRowsAtCompileTime> workspace(dst.rows());\n      applyThisOnTheRight(dst, workspace);\n    }\n\n    /** \\internal */\n    template<typename Dest, typename Workspace>\n    inline void applyThisOnTheRight(Dest& dst, Workspace& workspace) const\n    {\n      workspace.resize(dst.rows());\n      for(Index k = 0; k < m_length; ++k)\n      {\n        Index actual_k = m_reverse ? m_length-k-1 : k;\n        dst.rightCols(rows()-m_shift-actual_k)\n           .applyHouseholderOnTheRight(essentialVector(actual_k), m_coeffs.coeff(actual_k), workspace.data());\n      }\n    }\n\n    /** \\internal */\n    template<typename Dest> inline void applyThisOnTheLeft(Dest& dst, bool inputIsIdentity = false) const\n    {\n      Matrix<Scalar,1,Dest::ColsAtCompileTime,RowMajor,1,Dest::MaxColsAtCompileTime> workspace;\n      applyThisOnTheLeft(dst, workspace, inputIsIdentity);\n    }\n\n    /** \\internal */\n    template<typename Dest, typename Workspace>\n    inline void applyThisOnTheLeft(Dest& dst, Workspace& workspace, bool inputIsIdentity = false) const\n    {\n      if(inputIsIdentity && m_reverse)\n        inputIsIdentity = false;\n      // if the entries are large enough, then apply the reflectors by block\n      if(m_length>=BlockSize && dst.cols()>1)\n      {\n        // Make sure we have at least 2 useful blocks, otherwise it is point-less:\n        Index blockSize = m_length<Index(2*BlockSize) ? (m_length+1)/2 : Index(BlockSize);\n        for(Index i = 0; i < m_length; i+=blockSize)\n        {\n          Index end = m_reverse ? (std::min)(m_length,i+blockSize) : m_length-i;\n          Index k = m_reverse ? i : (std::max)(Index(0),end-blockSize);\n          Index bs = end-k;\n          Index start = k + m_shift;\n          \n          typedef Block<typename internal::remove_all<VectorsType>::type,Dynamic,Dynamic> SubVectorsType;\n          SubVectorsType sub_vecs1(m_vectors.const_cast_derived(), Side==OnTheRight ? k : start,\n                                                                   Side==OnTheRight ? start : k,\n                                                                   Side==OnTheRight ? bs : m_vectors.rows()-start,\n                                                                   Side==OnTheRight ? m_vectors.cols()-start : bs);\n          typename internal::conditional<Side==OnTheRight, Transpose<SubVectorsType>, SubVectorsType&>::type sub_vecs(sub_vecs1);\n\n          Index dstStart = dst.rows()-rows()+m_shift+k;\n          Index dstRows  = rows()-m_shift-k;\n          Block<Dest,Dynamic,Dynamic> sub_dst(dst,\n                                              dstStart,\n                                              inputIsIdentity ? dstStart : 0,\n                                              dstRows,\n                                              inputIsIdentity ? dstRows : dst.cols());\n          apply_block_householder_on_the_left(sub_dst, sub_vecs, m_coeffs.segment(k, bs), !m_reverse);\n        }\n      }\n      else\n      {\n        workspace.resize(dst.cols());\n        for(Index k = 0; k < m_length; ++k)\n        {\n          Index actual_k = m_reverse ? k : m_length-k-1;\n          Index dstStart = rows()-m_shift-actual_k;\n          dst.bottomRightCorner(dstStart, inputIsIdentity ? dstStart : dst.cols())\n            .applyHouseholderOnTheLeft(essentialVector(actual_k), m_coeffs.coeff(actual_k), workspace.data());\n        }\n      }\n    }\n\n    /** \\brief Computes the product of a Householder sequence with a matrix.\n      * \\param[in]  other  %Matrix being multiplied.\n      * \\returns    Expression object representing the product.\n      *\n      * This function computes \\f$ HM \\f$ where \\f$ H \\f$ is the Householder sequence represented by \\p *this\n      * and \\f$ M \\f$ is the matrix \\p other.\n      */\n    template<typename OtherDerived>\n    typename internal::matrix_type_times_scalar_type<Scalar, OtherDerived>::Type operator*(const MatrixBase<OtherDerived>& other) const\n    {\n      typename internal::matrix_type_times_scalar_type<Scalar, OtherDerived>::Type\n        res(other.template cast<typename internal::matrix_type_times_scalar_type<Scalar,OtherDerived>::ResultScalar>());\n      applyThisOnTheLeft(res, internal::is_identity<OtherDerived>::value && res.rows()==res.cols());\n      return res;\n    }\n\n    template<typename _VectorsType, typename _CoeffsType, int _Side> friend struct internal::hseq_side_dependent_impl;\n\n    /** \\brief Sets the length of the Householder sequence.\n      * \\param [in]  length  New value for the length.\n      *\n      * By default, the length \\f$ n \\f$ of the Householder sequence \\f$ H = H_0 H_1 \\ldots H_{n-1} \\f$ is set\n      * to the number of columns of the matrix \\p v passed to the constructor, or the number of rows if that\n      * is smaller. After this function is called, the length equals \\p length.\n      *\n      * \\sa length()\n      */\n    EIGEN_DEVICE_FUNC\n    HouseholderSequence& setLength(Index length)\n    {\n      m_length = length;\n      return *this;\n    }\n\n    /** \\brief Sets the shift of the Householder sequence.\n      * \\param [in]  shift  New value for the shift.\n      *\n      * By default, a %HouseholderSequence object represents \\f$ H = H_0 H_1 \\ldots H_{n-1} \\f$ and the i-th\n      * column of the matrix \\p v passed to the constructor corresponds to the i-th Householder\n      * reflection. After this function is called, the object represents \\f$ H = H_{\\mathrm{shift}}\n      * H_{\\mathrm{shift}+1} \\ldots H_{n-1} \\f$ and the i-th column of \\p v corresponds to the (shift+i)-th\n      * Householder reflection.\n      *\n      * \\sa shift()\n      */\n    EIGEN_DEVICE_FUNC\n    HouseholderSequence& setShift(Index shift)\n    {\n      m_shift = shift;\n      return *this;\n    }\n\n    EIGEN_DEVICE_FUNC\n    Index length() const { return m_length; }  /**< \\brief Returns the length of the Householder sequence. */\n\n    EIGEN_DEVICE_FUNC\n    Index shift() const { return m_shift; }    /**< \\brief Returns the shift of the Householder sequence. */\n\n    /* Necessary for .adjoint() and .conjugate() */\n    template <typename VectorsType2, typename CoeffsType2, int Side2> friend class HouseholderSequence;\n\n  protected:\n\n    /** \\internal\n      * \\brief Sets the reverse flag.\n      * \\param [in]  reverse  New value of the reverse flag.\n      *\n      * By default, the reverse flag is not set. If the reverse flag is set, then this object represents\n      * \\f$ H^r = H_{n-1} \\ldots H_1 H_0 \\f$ instead of \\f$ H = H_0 H_1 \\ldots H_{n-1} \\f$.\n      * \\note For real valued HouseholderSequence this is equivalent to transposing \\f$ H \\f$.\n      *\n      * \\sa reverseFlag(), transpose(), adjoint()\n      */\n    HouseholderSequence& setReverseFlag(bool reverse)\n    {\n      m_reverse = reverse;\n      return *this;\n    }\n\n    bool reverseFlag() const { return m_reverse; }     /**< \\internal \\brief Returns the reverse flag. */\n\n    typename VectorsType::Nested m_vectors;\n    typename CoeffsType::Nested m_coeffs;\n    bool m_reverse;\n    Index m_length;\n    Index m_shift;\n    enum { BlockSize = 48 };\n};\n\n/** \\brief Computes the product of a matrix with a Householder sequence.\n  * \\param[in]  other  %Matrix being multiplied.\n  * \\param[in]  h      %HouseholderSequence being multiplied.\n  * \\returns    Expression object representing the product.\n  *\n  * This function computes \\f$ MH \\f$ where \\f$ M \\f$ is the matrix \\p other and \\f$ H \\f$ is the\n  * Householder sequence represented by \\p h.\n  */\ntemplate<typename OtherDerived, typename VectorsType, typename CoeffsType, int Side>\ntypename internal::matrix_type_times_scalar_type<typename VectorsType::Scalar,OtherDerived>::Type operator*(const MatrixBase<OtherDerived>& other, const HouseholderSequence<VectorsType,CoeffsType,Side>& h)\n{\n  typename internal::matrix_type_times_scalar_type<typename VectorsType::Scalar,OtherDerived>::Type\n    res(other.template cast<typename internal::matrix_type_times_scalar_type<typename VectorsType::Scalar,OtherDerived>::ResultScalar>());\n  h.applyThisOnTheRight(res);\n  return res;\n}\n\n/** \\ingroup Householder_Module \\householder_module\n  * \\brief Convenience function for constructing a Householder sequence. \n  * \\returns A HouseholderSequence constructed from the specified arguments.\n  */\ntemplate<typename VectorsType, typename CoeffsType>\nHouseholderSequence<VectorsType,CoeffsType> householderSequence(const VectorsType& v, const CoeffsType& h)\n{\n  return HouseholderSequence<VectorsType,CoeffsType,OnTheLeft>(v, h);\n}\n\n/** \\ingroup Householder_Module \\householder_module\n  * \\brief Convenience function for constructing a Householder sequence. \n  * \\returns A HouseholderSequence constructed from the specified arguments.\n  * \\details This function differs from householderSequence() in that the template argument \\p OnTheSide of\n  * the constructed HouseholderSequence is set to OnTheRight, instead of the default OnTheLeft.\n  */\ntemplate<typename VectorsType, typename CoeffsType>\nHouseholderSequence<VectorsType,CoeffsType,OnTheRight> rightHouseholderSequence(const VectorsType& v, const CoeffsType& h)\n{\n  return HouseholderSequence<VectorsType,CoeffsType,OnTheRight>(v, h);\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_HOUSEHOLDER_SEQUENCE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/IterativeLinearSolvers/BasicPreconditioners.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BASIC_PRECONDITIONERS_H\n#define EIGEN_BASIC_PRECONDITIONERS_H\n\nnamespace Eigen { \n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\brief A preconditioner based on the digonal entries\n  *\n  * This class allows to approximately solve for A.x = b problems assuming A is a diagonal matrix.\n  * In other words, this preconditioner neglects all off diagonal entries and, in Eigen's language, solves for:\n    \\code\n    A.diagonal().asDiagonal() . x = b\n    \\endcode\n  *\n  * \\tparam _Scalar the type of the scalar.\n  *\n  * \\implsparsesolverconcept\n  *\n  * This preconditioner is suitable for both selfadjoint and general problems.\n  * The diagonal entries are pre-inverted and stored into a dense vector.\n  *\n  * \\note A variant that has yet to be implemented would attempt to preserve the norm of each column.\n  *\n  * \\sa class LeastSquareDiagonalPreconditioner, class ConjugateGradient\n  */\ntemplate <typename _Scalar>\nclass DiagonalPreconditioner\n{\n    typedef _Scalar Scalar;\n    typedef Matrix<Scalar,Dynamic,1> Vector;\n  public:\n    typedef typename Vector::StorageIndex StorageIndex;\n    enum {\n      ColsAtCompileTime = Dynamic,\n      MaxColsAtCompileTime = Dynamic\n    };\n\n    DiagonalPreconditioner() : m_isInitialized(false) {}\n\n    template<typename MatType>\n    explicit DiagonalPreconditioner(const MatType& mat) : m_invdiag(mat.cols())\n    {\n      compute(mat);\n    }\n\n    Index rows() const { return m_invdiag.size(); }\n    Index cols() const { return m_invdiag.size(); }\n    \n    template<typename MatType>\n    DiagonalPreconditioner& analyzePattern(const MatType& )\n    {\n      return *this;\n    }\n    \n    template<typename MatType>\n    DiagonalPreconditioner& factorize(const MatType& mat)\n    {\n      m_invdiag.resize(mat.cols());\n      for(int j=0; j<mat.outerSize(); ++j)\n      {\n        typename MatType::InnerIterator it(mat,j);\n        while(it && it.index()!=j) ++it;\n        if(it && it.index()==j && it.value()!=Scalar(0))\n          m_invdiag(j) = Scalar(1)/it.value();\n        else\n          m_invdiag(j) = Scalar(1);\n      }\n      m_isInitialized = true;\n      return *this;\n    }\n    \n    template<typename MatType>\n    DiagonalPreconditioner& compute(const MatType& mat)\n    {\n      return factorize(mat);\n    }\n\n    /** \\internal */\n    template<typename Rhs, typename Dest>\n    void _solve_impl(const Rhs& b, Dest& x) const\n    {\n      x = m_invdiag.array() * b.array() ;\n    }\n\n    template<typename Rhs> inline const Solve<DiagonalPreconditioner, Rhs>\n    solve(const MatrixBase<Rhs>& b) const\n    {\n      eigen_assert(m_isInitialized && \"DiagonalPreconditioner is not initialized.\");\n      eigen_assert(m_invdiag.size()==b.rows()\n                && \"DiagonalPreconditioner::solve(): invalid number of rows of the right hand side matrix b\");\n      return Solve<DiagonalPreconditioner, Rhs>(*this, b.derived());\n    }\n    \n    ComputationInfo info() { return Success; }\n\n  protected:\n    Vector m_invdiag;\n    bool m_isInitialized;\n};\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\brief Jacobi preconditioner for LeastSquaresConjugateGradient\n  *\n  * This class allows to approximately solve for A' A x  = A' b problems assuming A' A is a diagonal matrix.\n  * In other words, this preconditioner neglects all off diagonal entries and, in Eigen's language, solves for:\n    \\code\n    (A.adjoint() * A).diagonal().asDiagonal() * x = b\n    \\endcode\n  *\n  * \\tparam _Scalar the type of the scalar.\n  *\n  * \\implsparsesolverconcept\n  *\n  * The diagonal entries are pre-inverted and stored into a dense vector.\n  * \n  * \\sa class LeastSquaresConjugateGradient, class DiagonalPreconditioner\n  */\ntemplate <typename _Scalar>\nclass LeastSquareDiagonalPreconditioner : public DiagonalPreconditioner<_Scalar>\n{\n    typedef _Scalar Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef DiagonalPreconditioner<_Scalar> Base;\n    using Base::m_invdiag;\n  public:\n\n    LeastSquareDiagonalPreconditioner() : Base() {}\n\n    template<typename MatType>\n    explicit LeastSquareDiagonalPreconditioner(const MatType& mat) : Base()\n    {\n      compute(mat);\n    }\n\n    template<typename MatType>\n    LeastSquareDiagonalPreconditioner& analyzePattern(const MatType& )\n    {\n      return *this;\n    }\n    \n    template<typename MatType>\n    LeastSquareDiagonalPreconditioner& factorize(const MatType& mat)\n    {\n      // Compute the inverse squared-norm of each column of mat\n      m_invdiag.resize(mat.cols());\n      if(MatType::IsRowMajor)\n      {\n        m_invdiag.setZero();\n        for(Index j=0; j<mat.outerSize(); ++j)\n        {\n          for(typename MatType::InnerIterator it(mat,j); it; ++it)\n            m_invdiag(it.index()) += numext::abs2(it.value());\n        }\n        for(Index j=0; j<mat.cols(); ++j)\n          if(numext::real(m_invdiag(j))>RealScalar(0))\n            m_invdiag(j) = RealScalar(1)/numext::real(m_invdiag(j));\n      }\n      else\n      {\n        for(Index j=0; j<mat.outerSize(); ++j)\n        {\n          RealScalar sum = mat.col(j).squaredNorm();\n          if(sum>RealScalar(0))\n            m_invdiag(j) = RealScalar(1)/sum;\n          else\n            m_invdiag(j) = RealScalar(1);\n        }\n      }\n      Base::m_isInitialized = true;\n      return *this;\n    }\n    \n    template<typename MatType>\n    LeastSquareDiagonalPreconditioner& compute(const MatType& mat)\n    {\n      return factorize(mat);\n    }\n    \n    ComputationInfo info() { return Success; }\n\n  protected:\n};\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\brief A naive preconditioner which approximates any matrix as the identity matrix\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa class DiagonalPreconditioner\n  */\nclass IdentityPreconditioner\n{\n  public:\n\n    IdentityPreconditioner() {}\n\n    template<typename MatrixType>\n    explicit IdentityPreconditioner(const MatrixType& ) {}\n    \n    template<typename MatrixType>\n    IdentityPreconditioner& analyzePattern(const MatrixType& ) { return *this; }\n    \n    template<typename MatrixType>\n    IdentityPreconditioner& factorize(const MatrixType& ) { return *this; }\n\n    template<typename MatrixType>\n    IdentityPreconditioner& compute(const MatrixType& ) { return *this; }\n    \n    template<typename Rhs>\n    inline const Rhs& solve(const Rhs& b) const { return b; }\n    \n    ComputationInfo info() { return Success; }\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_BASIC_PRECONDITIONERS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/IterativeLinearSolvers/BiCGSTAB.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BICGSTAB_H\n#define EIGEN_BICGSTAB_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\internal Low-level bi conjugate gradient stabilized algorithm\n  * \\param mat The matrix A\n  * \\param rhs The right hand side vector b\n  * \\param x On input and initial solution, on output the computed solution.\n  * \\param precond A preconditioner being able to efficiently solve for an\n  *                approximation of Ax=b (regardless of b)\n  * \\param iters On input the max number of iteration, on output the number of performed iterations.\n  * \\param tol_error On input the tolerance error, on output an estimation of the relative error.\n  * \\return false in the case of numerical issue, for example a break down of BiCGSTAB. \n  */\ntemplate<typename MatrixType, typename Rhs, typename Dest, typename Preconditioner>\nbool bicgstab(const MatrixType& mat, const Rhs& rhs, Dest& x,\n              const Preconditioner& precond, Index& iters,\n              typename Dest::RealScalar& tol_error)\n{\n  using std::sqrt;\n  using std::abs;\n  typedef typename Dest::RealScalar RealScalar;\n  typedef typename Dest::Scalar Scalar;\n  typedef Matrix<Scalar,Dynamic,1> VectorType;\n  RealScalar tol = tol_error;\n  Index maxIters = iters;\n\n  Index n = mat.cols();\n  VectorType r  = rhs - mat * x;\n  VectorType r0 = r;\n  \n  RealScalar r0_sqnorm = r0.squaredNorm();\n  RealScalar rhs_sqnorm = rhs.squaredNorm();\n  if(rhs_sqnorm == 0)\n  {\n    x.setZero();\n    return true;\n  }\n  Scalar rho    = 1;\n  Scalar alpha  = 1;\n  Scalar w      = 1;\n  \n  VectorType v = VectorType::Zero(n), p = VectorType::Zero(n);\n  VectorType y(n),  z(n);\n  VectorType kt(n), ks(n);\n\n  VectorType s(n), t(n);\n\n  RealScalar tol2 = tol*tol*rhs_sqnorm;\n  RealScalar eps2 = NumTraits<Scalar>::epsilon()*NumTraits<Scalar>::epsilon();\n  Index i = 0;\n  Index restarts = 0;\n\n  while ( r.squaredNorm() > tol2 && i<maxIters )\n  {\n    Scalar rho_old = rho;\n\n    rho = r0.dot(r);\n    if (abs(rho) < eps2*r0_sqnorm)\n    {\n      // The new residual vector became too orthogonal to the arbitrarily chosen direction r0\n      // Let's restart with a new r0:\n      r  = rhs - mat * x;\n      r0 = r;\n      rho = r0_sqnorm = r.squaredNorm();\n      if(restarts++ == 0)\n        i = 0;\n    }\n    Scalar beta = (rho/rho_old) * (alpha / w);\n    p = r + beta * (p - w * v);\n    \n    y = precond.solve(p);\n    \n    v.noalias() = mat * y;\n\n    alpha = rho / r0.dot(v);\n    s = r - alpha * v;\n\n    z = precond.solve(s);\n    t.noalias() = mat * z;\n\n    RealScalar tmp = t.squaredNorm();\n    if(tmp>RealScalar(0))\n      w = t.dot(s) / tmp;\n    else\n      w = Scalar(0);\n    x += alpha * y + w * z;\n    r = s - w * t;\n    ++i;\n  }\n  tol_error = sqrt(r.squaredNorm()/rhs_sqnorm);\n  iters = i;\n  return true; \n}\n\n}\n\ntemplate< typename _MatrixType,\n          typename _Preconditioner = DiagonalPreconditioner<typename _MatrixType::Scalar> >\nclass BiCGSTAB;\n\nnamespace internal {\n\ntemplate< typename _MatrixType, typename _Preconditioner>\nstruct traits<BiCGSTAB<_MatrixType,_Preconditioner> >\n{\n  typedef _MatrixType MatrixType;\n  typedef _Preconditioner Preconditioner;\n};\n\n}\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\brief A bi conjugate gradient stabilized solver for sparse square problems\n  *\n  * This class allows to solve for A.x = b sparse linear problems using a bi conjugate gradient\n  * stabilized algorithm. The vectors x and b can be either dense or sparse.\n  *\n  * \\tparam _MatrixType the type of the sparse matrix A, can be a dense or a sparse matrix.\n  * \\tparam _Preconditioner the type of the preconditioner. Default is DiagonalPreconditioner\n  *\n  * \\implsparsesolverconcept\n  *\n  * The maximal number of iterations and tolerance value can be controlled via the setMaxIterations()\n  * and setTolerance() methods. The defaults are the size of the problem for the maximal number of iterations\n  * and NumTraits<Scalar>::epsilon() for the tolerance.\n  * \n  * The tolerance corresponds to the relative residual error: |Ax-b|/|b|\n  * \n  * \\b Performance: when using sparse matrices, best performance is achied for a row-major sparse matrix format.\n  * Moreover, in this case multi-threading can be exploited if the user code is compiled with OpenMP enabled.\n  * See \\ref TopicMultiThreading for details.\n  * \n  * This class can be used as the direct solver classes. Here is a typical usage example:\n  * \\include BiCGSTAB_simple.cpp\n  * \n  * By default the iterations start with x=0 as an initial guess of the solution.\n  * One can control the start using the solveWithGuess() method.\n  * \n  * BiCGSTAB can also be used in a matrix-free context, see the following \\link MatrixfreeSolverExample example \\endlink.\n  *\n  * \\sa class SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner\n  */\ntemplate< typename _MatrixType, typename _Preconditioner>\nclass BiCGSTAB : public IterativeSolverBase<BiCGSTAB<_MatrixType,_Preconditioner> >\n{\n  typedef IterativeSolverBase<BiCGSTAB> Base;\n  using Base::matrix;\n  using Base::m_error;\n  using Base::m_iterations;\n  using Base::m_info;\n  using Base::m_isInitialized;\npublic:\n  typedef _MatrixType MatrixType;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef _Preconditioner Preconditioner;\n\npublic:\n\n  /** Default constructor. */\n  BiCGSTAB() : Base() {}\n\n  /** Initialize the solver with matrix \\a A for further \\c Ax=b solving.\n    * \n    * This constructor is a shortcut for the default constructor followed\n    * by a call to compute().\n    * \n    * \\warning this class stores a reference to the matrix A as well as some\n    * precomputed values that depend on it. Therefore, if \\a A is changed\n    * this class becomes invalid. Call compute() to update it with the new\n    * matrix A, or modify a copy of A.\n    */\n  template<typename MatrixDerived>\n  explicit BiCGSTAB(const EigenBase<MatrixDerived>& A) : Base(A.derived()) {}\n\n  ~BiCGSTAB() {}\n\n  /** \\internal */\n  template<typename Rhs,typename Dest>\n  void _solve_vector_with_guess_impl(const Rhs& b, Dest& x) const\n  {    \n    m_iterations = Base::maxIterations();\n    m_error = Base::m_tolerance;\n    \n    bool ret = internal::bicgstab(matrix(), b, x, Base::m_preconditioner, m_iterations, m_error);\n\n    m_info = (!ret) ? NumericalIssue\n           : m_error <= Base::m_tolerance ? Success\n           : NoConvergence;\n  }\n\nprotected:\n\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_BICGSTAB_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/IterativeLinearSolvers/ConjugateGradient.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CONJUGATE_GRADIENT_H\n#define EIGEN_CONJUGATE_GRADIENT_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\internal Low-level conjugate gradient algorithm\n  * \\param mat The matrix A\n  * \\param rhs The right hand side vector b\n  * \\param x On input and initial solution, on output the computed solution.\n  * \\param precond A preconditioner being able to efficiently solve for an\n  *                approximation of Ax=b (regardless of b)\n  * \\param iters On input the max number of iteration, on output the number of performed iterations.\n  * \\param tol_error On input the tolerance error, on output an estimation of the relative error.\n  */\ntemplate<typename MatrixType, typename Rhs, typename Dest, typename Preconditioner>\nEIGEN_DONT_INLINE\nvoid conjugate_gradient(const MatrixType& mat, const Rhs& rhs, Dest& x,\n                        const Preconditioner& precond, Index& iters,\n                        typename Dest::RealScalar& tol_error)\n{\n  using std::sqrt;\n  using std::abs;\n  typedef typename Dest::RealScalar RealScalar;\n  typedef typename Dest::Scalar Scalar;\n  typedef Matrix<Scalar,Dynamic,1> VectorType;\n  \n  RealScalar tol = tol_error;\n  Index maxIters = iters;\n  \n  Index n = mat.cols();\n\n  VectorType residual = rhs - mat * x; //initial residual\n\n  RealScalar rhsNorm2 = rhs.squaredNorm();\n  if(rhsNorm2 == 0) \n  {\n    x.setZero();\n    iters = 0;\n    tol_error = 0;\n    return;\n  }\n  const RealScalar considerAsZero = (std::numeric_limits<RealScalar>::min)();\n  RealScalar threshold = numext::maxi(RealScalar(tol*tol*rhsNorm2),considerAsZero);\n  RealScalar residualNorm2 = residual.squaredNorm();\n  if (residualNorm2 < threshold)\n  {\n    iters = 0;\n    tol_error = sqrt(residualNorm2 / rhsNorm2);\n    return;\n  }\n\n  VectorType p(n);\n  p = precond.solve(residual);      // initial search direction\n\n  VectorType z(n), tmp(n);\n  RealScalar absNew = numext::real(residual.dot(p));  // the square of the absolute value of r scaled by invM\n  Index i = 0;\n  while(i < maxIters)\n  {\n    tmp.noalias() = mat * p;                    // the bottleneck of the algorithm\n\n    Scalar alpha = absNew / p.dot(tmp);         // the amount we travel on dir\n    x += alpha * p;                             // update solution\n    residual -= alpha * tmp;                    // update residual\n    \n    residualNorm2 = residual.squaredNorm();\n    if(residualNorm2 < threshold)\n      break;\n    \n    z = precond.solve(residual);                // approximately solve for \"A z = residual\"\n\n    RealScalar absOld = absNew;\n    absNew = numext::real(residual.dot(z));     // update the absolute value of r\n    RealScalar beta = absNew / absOld;          // calculate the Gram-Schmidt value used to create the new search direction\n    p = z + beta * p;                           // update search direction\n    i++;\n  }\n  tol_error = sqrt(residualNorm2 / rhsNorm2);\n  iters = i;\n}\n\n}\n\ntemplate< typename _MatrixType, int _UpLo=Lower,\n          typename _Preconditioner = DiagonalPreconditioner<typename _MatrixType::Scalar> >\nclass ConjugateGradient;\n\nnamespace internal {\n\ntemplate< typename _MatrixType, int _UpLo, typename _Preconditioner>\nstruct traits<ConjugateGradient<_MatrixType,_UpLo,_Preconditioner> >\n{\n  typedef _MatrixType MatrixType;\n  typedef _Preconditioner Preconditioner;\n};\n\n}\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\brief A conjugate gradient solver for sparse (or dense) self-adjoint problems\n  *\n  * This class allows to solve for A.x = b linear problems using an iterative conjugate gradient algorithm.\n  * The matrix A must be selfadjoint. The matrix A and the vectors x and b can be either dense or sparse.\n  *\n  * \\tparam _MatrixType the type of the matrix A, can be a dense or a sparse matrix.\n  * \\tparam _UpLo the triangular part that will be used for the computations. It can be Lower,\n  *               \\c Upper, or \\c Lower|Upper in which the full matrix entries will be considered.\n  *               Default is \\c Lower, best performance is \\c Lower|Upper.\n  * \\tparam _Preconditioner the type of the preconditioner. Default is DiagonalPreconditioner\n  *\n  * \\implsparsesolverconcept\n  *\n  * The maximal number of iterations and tolerance value can be controlled via the setMaxIterations()\n  * and setTolerance() methods. The defaults are the size of the problem for the maximal number of iterations\n  * and NumTraits<Scalar>::epsilon() for the tolerance.\n  * \n  * The tolerance corresponds to the relative residual error: |Ax-b|/|b|\n  * \n  * \\b Performance: Even though the default value of \\c _UpLo is \\c Lower, significantly higher performance is\n  * achieved when using a complete matrix and \\b Lower|Upper as the \\a _UpLo template parameter. Moreover, in this\n  * case multi-threading can be exploited if the user code is compiled with OpenMP enabled.\n  * See \\ref TopicMultiThreading for details.\n  * \n  * This class can be used as the direct solver classes. Here is a typical usage example:\n    \\code\n    int n = 10000;\n    VectorXd x(n), b(n);\n    SparseMatrix<double> A(n,n);\n    // fill A and b\n    ConjugateGradient<SparseMatrix<double>, Lower|Upper> cg;\n    cg.compute(A);\n    x = cg.solve(b);\n    std::cout << \"#iterations:     \" << cg.iterations() << std::endl;\n    std::cout << \"estimated error: \" << cg.error()      << std::endl;\n    // update b, and solve again\n    x = cg.solve(b);\n    \\endcode\n  * \n  * By default the iterations start with x=0 as an initial guess of the solution.\n  * One can control the start using the solveWithGuess() method.\n  * \n  * ConjugateGradient can also be used in a matrix-free context, see the following \\link MatrixfreeSolverExample example \\endlink.\n  *\n  * \\sa class LeastSquaresConjugateGradient, class SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner\n  */\ntemplate< typename _MatrixType, int _UpLo, typename _Preconditioner>\nclass ConjugateGradient : public IterativeSolverBase<ConjugateGradient<_MatrixType,_UpLo,_Preconditioner> >\n{\n  typedef IterativeSolverBase<ConjugateGradient> Base;\n  using Base::matrix;\n  using Base::m_error;\n  using Base::m_iterations;\n  using Base::m_info;\n  using Base::m_isInitialized;\npublic:\n  typedef _MatrixType MatrixType;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef _Preconditioner Preconditioner;\n\n  enum {\n    UpLo = _UpLo\n  };\n\npublic:\n\n  /** Default constructor. */\n  ConjugateGradient() : Base() {}\n\n  /** Initialize the solver with matrix \\a A for further \\c Ax=b solving.\n    * \n    * This constructor is a shortcut for the default constructor followed\n    * by a call to compute().\n    * \n    * \\warning this class stores a reference to the matrix A as well as some\n    * precomputed values that depend on it. Therefore, if \\a A is changed\n    * this class becomes invalid. Call compute() to update it with the new\n    * matrix A, or modify a copy of A.\n    */\n  template<typename MatrixDerived>\n  explicit ConjugateGradient(const EigenBase<MatrixDerived>& A) : Base(A.derived()) {}\n\n  ~ConjugateGradient() {}\n\n  /** \\internal */\n  template<typename Rhs,typename Dest>\n  void _solve_vector_with_guess_impl(const Rhs& b, Dest& x) const\n  {\n    typedef typename Base::MatrixWrapper MatrixWrapper;\n    typedef typename Base::ActualMatrixType ActualMatrixType;\n    enum {\n      TransposeInput  =   (!MatrixWrapper::MatrixFree)\n                      &&  (UpLo==(Lower|Upper))\n                      &&  (!MatrixType::IsRowMajor)\n                      &&  (!NumTraits<Scalar>::IsComplex)\n    };\n    typedef typename internal::conditional<TransposeInput,Transpose<const ActualMatrixType>, ActualMatrixType const&>::type RowMajorWrapper;\n    EIGEN_STATIC_ASSERT(EIGEN_IMPLIES(MatrixWrapper::MatrixFree,UpLo==(Lower|Upper)),MATRIX_FREE_CONJUGATE_GRADIENT_IS_COMPATIBLE_WITH_UPPER_UNION_LOWER_MODE_ONLY);\n    typedef typename internal::conditional<UpLo==(Lower|Upper),\n                                           RowMajorWrapper,\n                                           typename MatrixWrapper::template ConstSelfAdjointViewReturnType<UpLo>::Type\n                                          >::type SelfAdjointWrapper;\n\n    m_iterations = Base::maxIterations();\n    m_error = Base::m_tolerance;\n\n    RowMajorWrapper row_mat(matrix());\n    internal::conjugate_gradient(SelfAdjointWrapper(row_mat), b, x, Base::m_preconditioner, m_iterations, m_error);\n    m_info = m_error <= Base::m_tolerance ? Success : NoConvergence;\n  }\n\nprotected:\n\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CONJUGATE_GRADIENT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/IterativeLinearSolvers/IncompleteCholesky.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_INCOMPLETE_CHOlESKY_H\n#define EIGEN_INCOMPLETE_CHOlESKY_H\n\n#include <vector>\n#include <list>\n\nnamespace Eigen {  \n/** \n  * \\brief Modified Incomplete Cholesky with dual threshold\n  *\n  * References : C-J. Lin and J. J. Moré, Incomplete Cholesky Factorizations with\n  *              Limited memory, SIAM J. Sci. Comput.  21(1), pp. 24-45, 1999\n  *\n  * \\tparam Scalar the scalar type of the input matrices\n  * \\tparam _UpLo The triangular part that will be used for the computations. It can be Lower\n    *               or Upper. Default is Lower.\n  * \\tparam _OrderingType The ordering method to use, either AMDOrdering<> or NaturalOrdering<>. Default is AMDOrdering<int>,\n  *                       unless EIGEN_MPL2_ONLY is defined, in which case the default is NaturalOrdering<int>.\n  *\n  * \\implsparsesolverconcept\n  *\n  * It performs the following incomplete factorization: \\f$ S P A P' S \\approx L L' \\f$\n  * where L is a lower triangular factor, S is a diagonal scaling matrix, and P is a\n  * fill-in reducing permutation as computed by the ordering method.\n  *\n  * \\b Shifting \\b strategy: Let \\f$ B = S P A P' S \\f$  be the scaled matrix on which the factorization is carried out,\n  * and \\f$ \\beta \\f$ be the minimum value of the diagonal. If \\f$ \\beta > 0 \\f$ then, the factorization is directly performed\n  * on the matrix B. Otherwise, the factorization is performed on the shifted matrix \\f$ B + (\\sigma+|\\beta| I \\f$ where\n  * \\f$ \\sigma \\f$ is the initial shift value as returned and set by setInitialShift() method. The default value is \\f$ \\sigma = 10^{-3} \\f$.\n  * If the factorization fails, then the shift in doubled until it succeed or a maximum of ten attempts. If it still fails, as returned by\n  * the info() method, then you can either increase the initial shift, or better use another preconditioning technique.\n  *\n  */\ntemplate <typename Scalar, int _UpLo = Lower, typename _OrderingType = AMDOrdering<int> >\nclass IncompleteCholesky : public SparseSolverBase<IncompleteCholesky<Scalar,_UpLo,_OrderingType> >\n{\n  protected:\n    typedef SparseSolverBase<IncompleteCholesky<Scalar,_UpLo,_OrderingType> > Base;\n    using Base::m_isInitialized;\n  public:\n    typedef typename NumTraits<Scalar>::Real RealScalar; \n    typedef _OrderingType OrderingType;\n    typedef typename OrderingType::PermutationType PermutationType;\n    typedef typename PermutationType::StorageIndex StorageIndex; \n    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> FactorType;\n    typedef Matrix<Scalar,Dynamic,1> VectorSx;\n    typedef Matrix<RealScalar,Dynamic,1> VectorRx;\n    typedef Matrix<StorageIndex,Dynamic, 1> VectorIx;\n    typedef std::vector<std::list<StorageIndex> > VectorList; \n    enum { UpLo = _UpLo };\n    enum {\n      ColsAtCompileTime = Dynamic,\n      MaxColsAtCompileTime = Dynamic\n    };\n  public:\n\n    /** Default constructor leaving the object in a partly non-initialized stage.\n      *\n      * You must call compute() or the pair analyzePattern()/factorize() to make it valid.\n      *\n      * \\sa IncompleteCholesky(const MatrixType&)\n      */\n    IncompleteCholesky() : m_initialShift(1e-3),m_analysisIsOk(false),m_factorizationIsOk(false) {}\n    \n    /** Constructor computing the incomplete factorization for the given matrix \\a matrix.\n      */\n    template<typename MatrixType>\n    IncompleteCholesky(const MatrixType& matrix) : m_initialShift(1e-3),m_analysisIsOk(false),m_factorizationIsOk(false)\n    {\n      compute(matrix);\n    }\n    \n    /** \\returns number of rows of the factored matrix */\n    Index rows() const { return m_L.rows(); }\n    \n    /** \\returns number of columns of the factored matrix */\n    Index cols() const { return m_L.cols(); }\n    \n\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * It triggers an assertion if \\c *this has not been initialized through the respective constructor,\n      * or a call to compute() or analyzePattern().\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the matrix appears to be negative.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"IncompleteCholesky is not initialized.\");\n      return m_info;\n    }\n    \n    /** \\brief Set the initial shift parameter \\f$ \\sigma \\f$.\n      */\n    void setInitialShift(RealScalar shift) { m_initialShift = shift; }\n    \n    /** \\brief Computes the fill reducing permutation vector using the sparsity pattern of \\a mat\n      */\n    template<typename MatrixType>\n    void analyzePattern(const MatrixType& mat)\n    {\n      OrderingType ord; \n      PermutationType pinv;\n      ord(mat.template selfadjointView<UpLo>(), pinv); \n      if(pinv.size()>0) m_perm = pinv.inverse();\n      else              m_perm.resize(0);\n      m_L.resize(mat.rows(), mat.cols());\n      m_analysisIsOk = true;\n      m_isInitialized = true;\n      m_info = Success;\n    }\n    \n    /** \\brief Performs the numerical factorization of the input matrix \\a mat\n      *\n      * The method analyzePattern() or compute() must have been called beforehand\n      * with a matrix having the same pattern.\n      *\n      * \\sa compute(), analyzePattern()\n      */\n    template<typename MatrixType>\n    void factorize(const MatrixType& mat);\n    \n    /** Computes or re-computes the incomplete Cholesky factorization of the input matrix \\a mat\n      *\n      * It is a shortcut for a sequential call to the analyzePattern() and factorize() methods.\n      *\n      * \\sa analyzePattern(), factorize()\n      */\n    template<typename MatrixType>\n    void compute(const MatrixType& mat)\n    {\n      analyzePattern(mat);\n      factorize(mat);\n    }\n    \n    // internal\n    template<typename Rhs, typename Dest>\n    void _solve_impl(const Rhs& b, Dest& x) const\n    {\n      eigen_assert(m_factorizationIsOk && \"factorize() should be called first\");\n      if (m_perm.rows() == b.rows())  x = m_perm * b;\n      else                            x = b;\n      x = m_scale.asDiagonal() * x;\n      x = m_L.template triangularView<Lower>().solve(x);\n      x = m_L.adjoint().template triangularView<Upper>().solve(x);\n      x = m_scale.asDiagonal() * x;\n      if (m_perm.rows() == b.rows())\n        x = m_perm.inverse() * x;\n    }\n\n    /** \\returns the sparse lower triangular factor L */\n    const FactorType& matrixL() const { eigen_assert(\"m_factorizationIsOk\"); return m_L; }\n\n    /** \\returns a vector representing the scaling factor S */\n    const VectorRx& scalingS() const { eigen_assert(\"m_factorizationIsOk\"); return m_scale; }\n\n    /** \\returns the fill-in reducing permutation P (can be empty for a natural ordering) */\n    const PermutationType& permutationP() const { eigen_assert(\"m_analysisIsOk\"); return m_perm; }\n\n  protected:\n    FactorType m_L;              // The lower part stored in CSC\n    VectorRx m_scale;            // The vector for scaling the matrix \n    RealScalar m_initialShift;   // The initial shift parameter\n    bool m_analysisIsOk; \n    bool m_factorizationIsOk; \n    ComputationInfo m_info;\n    PermutationType m_perm; \n\n  private:\n    inline void updateList(Ref<const VectorIx> colPtr, Ref<VectorIx> rowIdx, Ref<VectorSx> vals, const Index& col, const Index& jk, VectorIx& firstElt, VectorList& listCol); \n}; \n\n// Based on the following paper:\n//   C-J. Lin and J. J. Moré, Incomplete Cholesky Factorizations with\n//   Limited memory, SIAM J. Sci. Comput.  21(1), pp. 24-45, 1999\n//   http://ftp.mcs.anl.gov/pub/tech_reports/reports/P682.pdf\ntemplate<typename Scalar, int _UpLo, typename OrderingType>\ntemplate<typename _MatrixType>\nvoid IncompleteCholesky<Scalar,_UpLo, OrderingType>::factorize(const _MatrixType& mat)\n{\n  using std::sqrt;\n  eigen_assert(m_analysisIsOk && \"analyzePattern() should be called first\"); \n    \n  // Dropping strategy : Keep only the p largest elements per column, where p is the number of elements in the column of the original matrix. Other strategies will be added\n  \n  // Apply the fill-reducing permutation computed in analyzePattern()\n  if (m_perm.rows() == mat.rows() ) // To detect the null permutation\n  {\n    // The temporary is needed to make sure that the diagonal entry is properly sorted\n    FactorType tmp(mat.rows(), mat.cols());\n    tmp = mat.template selfadjointView<_UpLo>().twistedBy(m_perm);\n    m_L.template selfadjointView<Lower>() = tmp.template selfadjointView<Lower>();\n  }\n  else\n  {\n    m_L.template selfadjointView<Lower>() = mat.template selfadjointView<_UpLo>();\n  }\n  \n  Index n = m_L.cols(); \n  Index nnz = m_L.nonZeros();\n  Map<VectorSx> vals(m_L.valuePtr(), nnz);         //values\n  Map<VectorIx> rowIdx(m_L.innerIndexPtr(), nnz);  //Row indices\n  Map<VectorIx> colPtr( m_L.outerIndexPtr(), n+1); // Pointer to the beginning of each row\n  VectorIx firstElt(n-1); // for each j, points to the next entry in vals that will be used in the factorization\n  VectorList listCol(n);  // listCol(j) is a linked list of columns to update column j\n  VectorSx col_vals(n);   // Store a  nonzero values in each column\n  VectorIx col_irow(n);   // Row indices of nonzero elements in each column\n  VectorIx col_pattern(n);\n  col_pattern.fill(-1);\n  StorageIndex col_nnz;\n  \n  \n  // Computes the scaling factors \n  m_scale.resize(n);\n  m_scale.setZero();\n  for (Index j = 0; j < n; j++)\n    for (Index k = colPtr[j]; k < colPtr[j+1]; k++)\n    {\n      m_scale(j) += numext::abs2(vals(k));\n      if(rowIdx[k]!=j)\n        m_scale(rowIdx[k]) += numext::abs2(vals(k));\n    }\n  \n  m_scale = m_scale.cwiseSqrt().cwiseSqrt();\n\n  for (Index j = 0; j < n; ++j)\n    if(m_scale(j)>(std::numeric_limits<RealScalar>::min)())\n      m_scale(j) = RealScalar(1)/m_scale(j);\n    else\n      m_scale(j) = 1;\n\n  // TODO disable scaling if not needed, i.e., if it is roughly uniform? (this will make solve() faster)\n  \n  // Scale and compute the shift for the matrix \n  RealScalar mindiag = NumTraits<RealScalar>::highest();\n  for (Index j = 0; j < n; j++)\n  {\n    for (Index k = colPtr[j]; k < colPtr[j+1]; k++)\n      vals[k] *= (m_scale(j)*m_scale(rowIdx[k]));\n    eigen_internal_assert(rowIdx[colPtr[j]]==j && \"IncompleteCholesky: only the lower triangular part must be stored\");\n    mindiag = numext::mini(numext::real(vals[colPtr[j]]), mindiag);\n  }\n\n  FactorType L_save = m_L;\n  \n  RealScalar shift = 0;\n  if(mindiag <= RealScalar(0.))\n    shift = m_initialShift - mindiag;\n\n  m_info = NumericalIssue;\n\n  // Try to perform the incomplete factorization using the current shift\n  int iter = 0;\n  do\n  {\n    // Apply the shift to the diagonal elements of the matrix\n    for (Index j = 0; j < n; j++)\n      vals[colPtr[j]] += shift;\n\n    // jki version of the Cholesky factorization\n    Index j=0;\n    for (; j < n; ++j)\n    {\n      // Left-looking factorization of the j-th column\n      // First, load the j-th column into col_vals\n      Scalar diag = vals[colPtr[j]];  // It is assumed that only the lower part is stored\n      col_nnz = 0;\n      for (Index i = colPtr[j] + 1; i < colPtr[j+1]; i++)\n      {\n        StorageIndex l = rowIdx[i];\n        col_vals(col_nnz) = vals[i];\n        col_irow(col_nnz) = l;\n        col_pattern(l) = col_nnz;\n        col_nnz++;\n      }\n      {\n        typename std::list<StorageIndex>::iterator k;\n        // Browse all previous columns that will update column j\n        for(k = listCol[j].begin(); k != listCol[j].end(); k++)\n        {\n          Index jk = firstElt(*k); // First element to use in the column\n          eigen_internal_assert(rowIdx[jk]==j);\n          Scalar v_j_jk = numext::conj(vals[jk]);\n\n          jk += 1;\n          for (Index i = jk; i < colPtr[*k+1]; i++)\n          {\n            StorageIndex l = rowIdx[i];\n            if(col_pattern[l]<0)\n            {\n              col_vals(col_nnz) = vals[i] * v_j_jk;\n              col_irow[col_nnz] = l;\n              col_pattern(l) = col_nnz;\n              col_nnz++;\n            }\n            else\n              col_vals(col_pattern[l]) -= vals[i] * v_j_jk;\n          }\n          updateList(colPtr,rowIdx,vals, *k, jk, firstElt, listCol);\n        }\n      }\n\n      // Scale the current column\n      if(numext::real(diag) <= 0)\n      {\n        if(++iter>=10)\n          return;\n\n        // increase shift\n        shift = numext::maxi(m_initialShift,RealScalar(2)*shift);\n        // restore m_L, col_pattern, and listCol\n        vals = Map<const VectorSx>(L_save.valuePtr(), nnz);\n        rowIdx = Map<const VectorIx>(L_save.innerIndexPtr(), nnz);\n        colPtr = Map<const VectorIx>(L_save.outerIndexPtr(), n+1);\n        col_pattern.fill(-1);\n        for(Index i=0; i<n; ++i)\n          listCol[i].clear();\n\n        break;\n      }\n\n      RealScalar rdiag = sqrt(numext::real(diag));\n      vals[colPtr[j]] = rdiag;\n      for (Index k = 0; k<col_nnz; ++k)\n      {\n        Index i = col_irow[k];\n        //Scale\n        col_vals(k) /= rdiag;\n        //Update the remaining diagonals with col_vals\n        vals[colPtr[i]] -= numext::abs2(col_vals(k));\n      }\n      // Select the largest p elements\n      // p is the original number of elements in the column (without the diagonal)\n      Index p = colPtr[j+1] - colPtr[j] - 1 ;\n      Ref<VectorSx> cvals = col_vals.head(col_nnz);\n      Ref<VectorIx> cirow = col_irow.head(col_nnz);\n      internal::QuickSplit(cvals,cirow, p);\n      // Insert the largest p elements in the matrix\n      Index cpt = 0;\n      for (Index i = colPtr[j]+1; i < colPtr[j+1]; i++)\n      {\n        vals[i] = col_vals(cpt);\n        rowIdx[i] = col_irow(cpt);\n        // restore col_pattern:\n        col_pattern(col_irow(cpt)) = -1;\n        cpt++;\n      }\n      // Get the first smallest row index and put it after the diagonal element\n      Index jk = colPtr(j)+1;\n      updateList(colPtr,rowIdx,vals,j,jk,firstElt,listCol);\n    }\n\n    if(j==n)\n    {\n      m_factorizationIsOk = true;\n      m_info = Success;\n    }\n  } while(m_info!=Success);\n}\n\ntemplate<typename Scalar, int _UpLo, typename OrderingType>\ninline void IncompleteCholesky<Scalar,_UpLo, OrderingType>::updateList(Ref<const VectorIx> colPtr, Ref<VectorIx> rowIdx, Ref<VectorSx> vals, const Index& col, const Index& jk, VectorIx& firstElt, VectorList& listCol)\n{\n  if (jk < colPtr(col+1) )\n  {\n    Index p = colPtr(col+1) - jk;\n    Index minpos; \n    rowIdx.segment(jk,p).minCoeff(&minpos);\n    minpos += jk;\n    if (rowIdx(minpos) != rowIdx(jk))\n    {\n      //Swap\n      std::swap(rowIdx(jk),rowIdx(minpos));\n      std::swap(vals(jk),vals(minpos));\n    }\n    firstElt(col) = internal::convert_index<StorageIndex,Index>(jk);\n    listCol[rowIdx(jk)].push_back(internal::convert_index<StorageIndex,Index>(col));\n  }\n}\n\n} // end namespace Eigen \n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/IterativeLinearSolvers/IncompleteLUT.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_INCOMPLETE_LUT_H\n#define EIGEN_INCOMPLETE_LUT_H\n\n\nnamespace Eigen { \n\nnamespace internal {\n    \n/** \\internal\n  * Compute a quick-sort split of a vector \n  * On output, the vector row is permuted such that its elements satisfy\n  * abs(row(i)) >= abs(row(ncut)) if i<ncut\n  * abs(row(i)) <= abs(row(ncut)) if i>ncut \n  * \\param row The vector of values\n  * \\param ind The array of index for the elements in @p row\n  * \\param ncut  The number of largest elements to keep\n  **/ \ntemplate <typename VectorV, typename VectorI>\nIndex QuickSplit(VectorV &row, VectorI &ind, Index ncut)\n{\n  typedef typename VectorV::RealScalar RealScalar;\n  using std::swap;\n  using std::abs;\n  Index mid;\n  Index n = row.size(); /* length of the vector */\n  Index first, last ;\n  \n  ncut--; /* to fit the zero-based indices */\n  first = 0; \n  last = n-1; \n  if (ncut < first || ncut > last ) return 0;\n  \n  do {\n    mid = first; \n    RealScalar abskey = abs(row(mid)); \n    for (Index j = first + 1; j <= last; j++) {\n      if ( abs(row(j)) > abskey) {\n        ++mid;\n        swap(row(mid), row(j));\n        swap(ind(mid), ind(j));\n      }\n    }\n    /* Interchange for the pivot element */\n    swap(row(mid), row(first));\n    swap(ind(mid), ind(first));\n    \n    if (mid > ncut) last = mid - 1;\n    else if (mid < ncut ) first = mid + 1; \n  } while (mid != ncut );\n  \n  return 0; /* mid is equal to ncut */ \n}\n\n}// end namespace internal\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\class IncompleteLUT\n  * \\brief Incomplete LU factorization with dual-threshold strategy\n  *\n  * \\implsparsesolverconcept\n  *\n  * During the numerical factorization, two dropping rules are used :\n  *  1) any element whose magnitude is less than some tolerance is dropped.\n  *    This tolerance is obtained by multiplying the input tolerance @p droptol \n  *    by the average magnitude of all the original elements in the current row.\n  *  2) After the elimination of the row, only the @p fill largest elements in \n  *    the L part and the @p fill largest elements in the U part are kept \n  *    (in addition to the diagonal element ). Note that @p fill is computed from \n  *    the input parameter @p fillfactor which is used the ratio to control the fill_in \n  *    relatively to the initial number of nonzero elements.\n  * \n  * The two extreme cases are when @p droptol=0 (to keep all the @p fill*2 largest elements)\n  * and when @p fill=n/2 with @p droptol being different to zero. \n  * \n  * References : Yousef Saad, ILUT: A dual threshold incomplete LU factorization, \n  *              Numerical Linear Algebra with Applications, 1(4), pp 387-402, 1994.\n  * \n  * NOTE : The following implementation is derived from the ILUT implementation\n  * in the SPARSKIT package, Copyright (C) 2005, the Regents of the University of Minnesota \n  *  released under the terms of the GNU LGPL: \n  *    http://www-users.cs.umn.edu/~saad/software/SPARSKIT/README\n  * However, Yousef Saad gave us permission to relicense his ILUT code to MPL2.\n  * See the Eigen mailing list archive, thread: ILUT, date: July 8, 2012:\n  *   http://listengine.tuxfamily.org/lists.tuxfamily.org/eigen/2012/07/msg00064.html\n  * alternatively, on GMANE:\n  *   http://comments.gmane.org/gmane.comp.lib.eigen/3302\n  */\ntemplate <typename _Scalar, typename _StorageIndex = int>\nclass IncompleteLUT : public SparseSolverBase<IncompleteLUT<_Scalar, _StorageIndex> >\n{\n  protected:\n    typedef SparseSolverBase<IncompleteLUT> Base;\n    using Base::m_isInitialized;\n  public:\n    typedef _Scalar Scalar;\n    typedef _StorageIndex StorageIndex;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef Matrix<Scalar,Dynamic,1> Vector;\n    typedef Matrix<StorageIndex,Dynamic,1> VectorI;\n    typedef SparseMatrix<Scalar,RowMajor,StorageIndex> FactorType;\n\n    enum {\n      ColsAtCompileTime = Dynamic,\n      MaxColsAtCompileTime = Dynamic\n    };\n\n  public:\n    \n    IncompleteLUT()\n      : m_droptol(NumTraits<Scalar>::dummy_precision()), m_fillfactor(10),\n        m_analysisIsOk(false), m_factorizationIsOk(false)\n    {}\n    \n    template<typename MatrixType>\n    explicit IncompleteLUT(const MatrixType& mat, const RealScalar& droptol=NumTraits<Scalar>::dummy_precision(), int fillfactor = 10)\n      : m_droptol(droptol),m_fillfactor(fillfactor),\n        m_analysisIsOk(false),m_factorizationIsOk(false)\n    {\n      eigen_assert(fillfactor != 0);\n      compute(mat); \n    }\n    \n    Index rows() const { return m_lu.rows(); }\n    \n    Index cols() const { return m_lu.cols(); }\n\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the matrix.appears to be negative.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"IncompleteLUT is not initialized.\");\n      return m_info;\n    }\n    \n    template<typename MatrixType>\n    void analyzePattern(const MatrixType& amat);\n    \n    template<typename MatrixType>\n    void factorize(const MatrixType& amat);\n    \n    /**\n      * Compute an incomplete LU factorization with dual threshold on the matrix mat\n      * No pivoting is done in this version\n      * \n      **/\n    template<typename MatrixType>\n    IncompleteLUT& compute(const MatrixType& amat)\n    {\n      analyzePattern(amat); \n      factorize(amat);\n      return *this;\n    }\n\n    void setDroptol(const RealScalar& droptol); \n    void setFillfactor(int fillfactor); \n    \n    template<typename Rhs, typename Dest>\n    void _solve_impl(const Rhs& b, Dest& x) const\n    {\n      x = m_Pinv * b;\n      x = m_lu.template triangularView<UnitLower>().solve(x);\n      x = m_lu.template triangularView<Upper>().solve(x);\n      x = m_P * x; \n    }\n\nprotected:\n\n    /** keeps off-diagonal entries; drops diagonal entries */\n    struct keep_diag {\n      inline bool operator() (const Index& row, const Index& col, const Scalar&) const\n      {\n        return row!=col;\n      }\n    };\n\nprotected:\n\n    FactorType m_lu;\n    RealScalar m_droptol;\n    int m_fillfactor;\n    bool m_analysisIsOk;\n    bool m_factorizationIsOk;\n    ComputationInfo m_info;\n    PermutationMatrix<Dynamic,Dynamic,StorageIndex> m_P;     // Fill-reducing permutation\n    PermutationMatrix<Dynamic,Dynamic,StorageIndex> m_Pinv;  // Inverse permutation\n};\n\n/**\n * Set control parameter droptol\n *  \\param droptol   Drop any element whose magnitude is less than this tolerance \n **/ \ntemplate<typename Scalar, typename StorageIndex>\nvoid IncompleteLUT<Scalar,StorageIndex>::setDroptol(const RealScalar& droptol)\n{\n  this->m_droptol = droptol;   \n}\n\n/**\n * Set control parameter fillfactor\n * \\param fillfactor  This is used to compute the  number @p fill_in of largest elements to keep on each row. \n **/ \ntemplate<typename Scalar, typename StorageIndex>\nvoid IncompleteLUT<Scalar,StorageIndex>::setFillfactor(int fillfactor)\n{\n  this->m_fillfactor = fillfactor;   \n}\n\ntemplate <typename Scalar, typename StorageIndex>\ntemplate<typename _MatrixType>\nvoid IncompleteLUT<Scalar,StorageIndex>::analyzePattern(const _MatrixType& amat)\n{\n  // Compute the Fill-reducing permutation\n  // Since ILUT does not perform any numerical pivoting,\n  // it is highly preferable to keep the diagonal through symmetric permutations.\n  // To this end, let's symmetrize the pattern and perform AMD on it.\n  SparseMatrix<Scalar,ColMajor, StorageIndex> mat1 = amat;\n  SparseMatrix<Scalar,ColMajor, StorageIndex> mat2 = amat.transpose();\n  // FIXME for a matrix with nearly symmetric pattern, mat2+mat1 is the appropriate choice.\n  //       on the other hand for a really non-symmetric pattern, mat2*mat1 should be preferred...\n  SparseMatrix<Scalar,ColMajor, StorageIndex> AtA = mat2 + mat1;\n  AMDOrdering<StorageIndex> ordering;\n  ordering(AtA,m_P);\n  m_Pinv  = m_P.inverse(); // cache the inverse permutation\n  m_analysisIsOk = true;\n  m_factorizationIsOk = false;\n  m_isInitialized = true;\n}\n\ntemplate <typename Scalar, typename StorageIndex>\ntemplate<typename _MatrixType>\nvoid IncompleteLUT<Scalar,StorageIndex>::factorize(const _MatrixType& amat)\n{\n  using std::sqrt;\n  using std::swap;\n  using std::abs;\n  using internal::convert_index;\n\n  eigen_assert((amat.rows() == amat.cols()) && \"The factorization should be done on a square matrix\");\n  Index n = amat.cols();  // Size of the matrix\n  m_lu.resize(n,n);\n  // Declare Working vectors and variables\n  Vector u(n) ;     // real values of the row -- maximum size is n --\n  VectorI ju(n);   // column position of the values in u -- maximum size  is n\n  VectorI jr(n);   // Indicate the position of the nonzero elements in the vector u -- A zero location is indicated by -1\n\n  // Apply the fill-reducing permutation\n  eigen_assert(m_analysisIsOk && \"You must first call analyzePattern()\");\n  SparseMatrix<Scalar,RowMajor, StorageIndex> mat;\n  mat = amat.twistedBy(m_Pinv);\n\n  // Initialization\n  jr.fill(-1);\n  ju.fill(0);\n  u.fill(0);\n\n  // number of largest elements to keep in each row:\n  Index fill_in = (amat.nonZeros()*m_fillfactor)/n + 1;\n  if (fill_in > n) fill_in = n;\n\n  // number of largest nonzero elements to keep in the L and the U part of the current row:\n  Index nnzL = fill_in/2;\n  Index nnzU = nnzL;\n  m_lu.reserve(n * (nnzL + nnzU + 1));\n\n  // global loop over the rows of the sparse matrix\n  for (Index ii = 0; ii < n; ii++)\n  {\n    // 1 - copy the lower and the upper part of the row i of mat in the working vector u\n\n    Index sizeu = 1; // number of nonzero elements in the upper part of the current row\n    Index sizel = 0; // number of nonzero elements in the lower part of the current row\n    ju(ii)    = convert_index<StorageIndex>(ii);\n    u(ii)     = 0;\n    jr(ii)    = convert_index<StorageIndex>(ii);\n    RealScalar rownorm = 0;\n\n    typename FactorType::InnerIterator j_it(mat, ii); // Iterate through the current row ii\n    for (; j_it; ++j_it)\n    {\n      Index k = j_it.index();\n      if (k < ii)\n      {\n        // copy the lower part\n        ju(sizel) = convert_index<StorageIndex>(k);\n        u(sizel) = j_it.value();\n        jr(k) = convert_index<StorageIndex>(sizel);\n        ++sizel;\n      }\n      else if (k == ii)\n      {\n        u(ii) = j_it.value();\n      }\n      else\n      {\n        // copy the upper part\n        Index jpos = ii + sizeu;\n        ju(jpos) = convert_index<StorageIndex>(k);\n        u(jpos) = j_it.value();\n        jr(k) = convert_index<StorageIndex>(jpos);\n        ++sizeu;\n      }\n      rownorm += numext::abs2(j_it.value());\n    }\n\n    // 2 - detect possible zero row\n    if(rownorm==0)\n    {\n      m_info = NumericalIssue;\n      return;\n    }\n    // Take the 2-norm of the current row as a relative tolerance\n    rownorm = sqrt(rownorm);\n\n    // 3 - eliminate the previous nonzero rows\n    Index jj = 0;\n    Index len = 0;\n    while (jj < sizel)\n    {\n      // In order to eliminate in the correct order,\n      // we must select first the smallest column index among  ju(jj:sizel)\n      Index k;\n      Index minrow = ju.segment(jj,sizel-jj).minCoeff(&k); // k is relative to the segment\n      k += jj;\n      if (minrow != ju(jj))\n      {\n        // swap the two locations\n        Index j = ju(jj);\n        swap(ju(jj), ju(k));\n        jr(minrow) = convert_index<StorageIndex>(jj);\n        jr(j) = convert_index<StorageIndex>(k);\n        swap(u(jj), u(k));\n      }\n      // Reset this location\n      jr(minrow) = -1;\n\n      // Start elimination\n      typename FactorType::InnerIterator ki_it(m_lu, minrow);\n      while (ki_it && ki_it.index() < minrow) ++ki_it;\n      eigen_internal_assert(ki_it && ki_it.col()==minrow);\n      Scalar fact = u(jj) / ki_it.value();\n\n      // drop too small elements\n      if(abs(fact) <= m_droptol)\n      {\n        jj++;\n        continue;\n      }\n\n      // linear combination of the current row ii and the row minrow\n      ++ki_it;\n      for (; ki_it; ++ki_it)\n      {\n        Scalar prod = fact * ki_it.value();\n        Index j     = ki_it.index();\n        Index jpos  = jr(j);\n        if (jpos == -1) // fill-in element\n        {\n          Index newpos;\n          if (j >= ii) // dealing with the upper part\n          {\n            newpos = ii + sizeu;\n            sizeu++;\n            eigen_internal_assert(sizeu<=n);\n          }\n          else // dealing with the lower part\n          {\n            newpos = sizel;\n            sizel++;\n            eigen_internal_assert(sizel<=ii);\n          }\n          ju(newpos) = convert_index<StorageIndex>(j);\n          u(newpos) = -prod;\n          jr(j) = convert_index<StorageIndex>(newpos);\n        }\n        else\n          u(jpos) -= prod;\n      }\n      // store the pivot element\n      u(len)  = fact;\n      ju(len) = convert_index<StorageIndex>(minrow);\n      ++len;\n\n      jj++;\n    } // end of the elimination on the row ii\n\n    // reset the upper part of the pointer jr to zero\n    for(Index k = 0; k <sizeu; k++) jr(ju(ii+k)) = -1;\n\n    // 4 - partially sort and insert the elements in the m_lu matrix\n\n    // sort the L-part of the row\n    sizel = len;\n    len = (std::min)(sizel, nnzL);\n    typename Vector::SegmentReturnType ul(u.segment(0, sizel));\n    typename VectorI::SegmentReturnType jul(ju.segment(0, sizel));\n    internal::QuickSplit(ul, jul, len);\n\n    // store the largest m_fill elements of the L part\n    m_lu.startVec(ii);\n    for(Index k = 0; k < len; k++)\n      m_lu.insertBackByOuterInnerUnordered(ii,ju(k)) = u(k);\n\n    // store the diagonal element\n    // apply a shifting rule to avoid zero pivots (we are doing an incomplete factorization)\n    if (u(ii) == Scalar(0))\n      u(ii) = sqrt(m_droptol) * rownorm;\n    m_lu.insertBackByOuterInnerUnordered(ii, ii) = u(ii);\n\n    // sort the U-part of the row\n    // apply the dropping rule first\n    len = 0;\n    for(Index k = 1; k < sizeu; k++)\n    {\n      if(abs(u(ii+k)) > m_droptol * rownorm )\n      {\n        ++len;\n        u(ii + len)  = u(ii + k);\n        ju(ii + len) = ju(ii + k);\n      }\n    }\n    sizeu = len + 1; // +1 to take into account the diagonal element\n    len = (std::min)(sizeu, nnzU);\n    typename Vector::SegmentReturnType uu(u.segment(ii+1, sizeu-1));\n    typename VectorI::SegmentReturnType juu(ju.segment(ii+1, sizeu-1));\n    internal::QuickSplit(uu, juu, len);\n\n    // store the largest elements of the U part\n    for(Index k = ii + 1; k < ii + len; k++)\n      m_lu.insertBackByOuterInnerUnordered(ii,ju(k)) = u(k);\n  }\n  m_lu.finalize();\n  m_lu.makeCompressed();\n\n  m_factorizationIsOk = true;\n  m_info = Success;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_INCOMPLETE_LUT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/IterativeLinearSolvers/IterativeSolverBase.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ITERATIVE_SOLVER_BASE_H\n#define EIGEN_ITERATIVE_SOLVER_BASE_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate<typename MatrixType>\nstruct is_ref_compatible_impl\n{\nprivate:\n  template <typename T0>\n  struct any_conversion\n  {\n    template <typename T> any_conversion(const volatile T&);\n    template <typename T> any_conversion(T&);\n  };\n  struct yes {int a[1];};\n  struct no  {int a[2];};\n\n  template<typename T>\n  static yes test(const Ref<const T>&, int);\n  template<typename T>\n  static no  test(any_conversion<T>, ...);\n\npublic:\n  static MatrixType ms_from;\n  enum { value = sizeof(test<MatrixType>(ms_from, 0))==sizeof(yes) };\n};\n\ntemplate<typename MatrixType>\nstruct is_ref_compatible\n{\n  enum { value = is_ref_compatible_impl<typename remove_all<MatrixType>::type>::value };\n};\n\ntemplate<typename MatrixType, bool MatrixFree = !internal::is_ref_compatible<MatrixType>::value>\nclass generic_matrix_wrapper;\n\n// We have an explicit matrix at hand, compatible with Ref<>\ntemplate<typename MatrixType>\nclass generic_matrix_wrapper<MatrixType,false>\n{\npublic:\n  typedef Ref<const MatrixType> ActualMatrixType;\n  template<int UpLo> struct ConstSelfAdjointViewReturnType {\n    typedef typename ActualMatrixType::template ConstSelfAdjointViewReturnType<UpLo>::Type Type;\n  };\n\n  enum {\n    MatrixFree = false\n  };\n\n  generic_matrix_wrapper()\n    : m_dummy(0,0), m_matrix(m_dummy)\n  {}\n\n  template<typename InputType>\n  generic_matrix_wrapper(const InputType &mat)\n    : m_matrix(mat)\n  {}\n\n  const ActualMatrixType& matrix() const\n  {\n    return m_matrix;\n  }\n\n  template<typename MatrixDerived>\n  void grab(const EigenBase<MatrixDerived> &mat)\n  {\n    m_matrix.~Ref<const MatrixType>();\n    ::new (&m_matrix) Ref<const MatrixType>(mat.derived());\n  }\n\n  void grab(const Ref<const MatrixType> &mat)\n  {\n    if(&(mat.derived()) != &m_matrix)\n    {\n      m_matrix.~Ref<const MatrixType>();\n      ::new (&m_matrix) Ref<const MatrixType>(mat);\n    }\n  }\n\nprotected:\n  MatrixType m_dummy; // used to default initialize the Ref<> object\n  ActualMatrixType m_matrix;\n};\n\n// MatrixType is not compatible with Ref<> -> matrix-free wrapper\ntemplate<typename MatrixType>\nclass generic_matrix_wrapper<MatrixType,true>\n{\npublic:\n  typedef MatrixType ActualMatrixType;\n  template<int UpLo> struct ConstSelfAdjointViewReturnType\n  {\n    typedef ActualMatrixType Type;\n  };\n\n  enum {\n    MatrixFree = true\n  };\n\n  generic_matrix_wrapper()\n    : mp_matrix(0)\n  {}\n\n  generic_matrix_wrapper(const MatrixType &mat)\n    : mp_matrix(&mat)\n  {}\n\n  const ActualMatrixType& matrix() const\n  {\n    return *mp_matrix;\n  }\n\n  void grab(const MatrixType &mat)\n  {\n    mp_matrix = &mat;\n  }\n\nprotected:\n  const ActualMatrixType *mp_matrix;\n};\n\n}\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\brief Base class for linear iterative solvers\n  *\n  * \\sa class SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner\n  */\ntemplate< typename Derived>\nclass IterativeSolverBase : public SparseSolverBase<Derived>\n{\nprotected:\n  typedef SparseSolverBase<Derived> Base;\n  using Base::m_isInitialized;\n  \npublic:\n  typedef typename internal::traits<Derived>::MatrixType MatrixType;\n  typedef typename internal::traits<Derived>::Preconditioner Preconditioner;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::StorageIndex StorageIndex;\n  typedef typename MatrixType::RealScalar RealScalar;\n\n  enum {\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n    MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n  };\n\npublic:\n\n  using Base::derived;\n\n  /** Default constructor. */\n  IterativeSolverBase()\n  {\n    init();\n  }\n\n  /** Initialize the solver with matrix \\a A for further \\c Ax=b solving.\n    * \n    * This constructor is a shortcut for the default constructor followed\n    * by a call to compute().\n    * \n    * \\warning this class stores a reference to the matrix A as well as some\n    * precomputed values that depend on it. Therefore, if \\a A is changed\n    * this class becomes invalid. Call compute() to update it with the new\n    * matrix A, or modify a copy of A.\n    */\n  template<typename MatrixDerived>\n  explicit IterativeSolverBase(const EigenBase<MatrixDerived>& A)\n    : m_matrixWrapper(A.derived())\n  {\n    init();\n    compute(matrix());\n  }\n\n  ~IterativeSolverBase() {}\n  \n  /** Initializes the iterative solver for the sparsity pattern of the matrix \\a A for further solving \\c Ax=b problems.\n    *\n    * Currently, this function mostly calls analyzePattern on the preconditioner. In the future\n    * we might, for instance, implement column reordering for faster matrix vector products.\n    */\n  template<typename MatrixDerived>\n  Derived& analyzePattern(const EigenBase<MatrixDerived>& A)\n  {\n    grab(A.derived());\n    m_preconditioner.analyzePattern(matrix());\n    m_isInitialized = true;\n    m_analysisIsOk = true;\n    m_info = m_preconditioner.info();\n    return derived();\n  }\n  \n  /** Initializes the iterative solver with the numerical values of the matrix \\a A for further solving \\c Ax=b problems.\n    *\n    * Currently, this function mostly calls factorize on the preconditioner.\n    *\n    * \\warning this class stores a reference to the matrix A as well as some\n    * precomputed values that depend on it. Therefore, if \\a A is changed\n    * this class becomes invalid. Call compute() to update it with the new\n    * matrix A, or modify a copy of A.\n    */\n  template<typename MatrixDerived>\n  Derived& factorize(const EigenBase<MatrixDerived>& A)\n  {\n    eigen_assert(m_analysisIsOk && \"You must first call analyzePattern()\"); \n    grab(A.derived());\n    m_preconditioner.factorize(matrix());\n    m_factorizationIsOk = true;\n    m_info = m_preconditioner.info();\n    return derived();\n  }\n\n  /** Initializes the iterative solver with the matrix \\a A for further solving \\c Ax=b problems.\n    *\n    * Currently, this function mostly initializes/computes the preconditioner. In the future\n    * we might, for instance, implement column reordering for faster matrix vector products.\n    *\n    * \\warning this class stores a reference to the matrix A as well as some\n    * precomputed values that depend on it. Therefore, if \\a A is changed\n    * this class becomes invalid. Call compute() to update it with the new\n    * matrix A, or modify a copy of A.\n    */\n  template<typename MatrixDerived>\n  Derived& compute(const EigenBase<MatrixDerived>& A)\n  {\n    grab(A.derived());\n    m_preconditioner.compute(matrix());\n    m_isInitialized = true;\n    m_analysisIsOk = true;\n    m_factorizationIsOk = true;\n    m_info = m_preconditioner.info();\n    return derived();\n  }\n\n  /** \\internal */\n  Index rows() const { return matrix().rows(); }\n\n  /** \\internal */\n  Index cols() const { return matrix().cols(); }\n\n  /** \\returns the tolerance threshold used by the stopping criteria.\n    * \\sa setTolerance()\n    */\n  RealScalar tolerance() const { return m_tolerance; }\n  \n  /** Sets the tolerance threshold used by the stopping criteria.\n    *\n    * This value is used as an upper bound to the relative residual error: |Ax-b|/|b|.\n    * The default value is the machine precision given by NumTraits<Scalar>::epsilon()\n    */\n  Derived& setTolerance(const RealScalar& tolerance)\n  {\n    m_tolerance = tolerance;\n    return derived();\n  }\n\n  /** \\returns a read-write reference to the preconditioner for custom configuration. */\n  Preconditioner& preconditioner() { return m_preconditioner; }\n  \n  /** \\returns a read-only reference to the preconditioner. */\n  const Preconditioner& preconditioner() const { return m_preconditioner; }\n\n  /** \\returns the max number of iterations.\n    * It is either the value set by setMaxIterations or, by default,\n    * twice the number of columns of the matrix.\n    */\n  Index maxIterations() const\n  {\n    return (m_maxIterations<0) ? 2*matrix().cols() : m_maxIterations;\n  }\n  \n  /** Sets the max number of iterations.\n    * Default is twice the number of columns of the matrix.\n    */\n  Derived& setMaxIterations(Index maxIters)\n  {\n    m_maxIterations = maxIters;\n    return derived();\n  }\n\n  /** \\returns the number of iterations performed during the last solve */\n  Index iterations() const\n  {\n    eigen_assert(m_isInitialized && \"ConjugateGradient is not initialized.\");\n    return m_iterations;\n  }\n\n  /** \\returns the tolerance error reached during the last solve.\n    * It is a close approximation of the true relative residual error |Ax-b|/|b|.\n    */\n  RealScalar error() const\n  {\n    eigen_assert(m_isInitialized && \"ConjugateGradient is not initialized.\");\n    return m_error;\n  }\n\n  /** \\returns the solution x of \\f$ A x = b \\f$ using the current decomposition of A\n    * and \\a x0 as an initial solution.\n    *\n    * \\sa solve(), compute()\n    */\n  template<typename Rhs,typename Guess>\n  inline const SolveWithGuess<Derived, Rhs, Guess>\n  solveWithGuess(const MatrixBase<Rhs>& b, const Guess& x0) const\n  {\n    eigen_assert(m_isInitialized && \"Solver is not initialized.\");\n    eigen_assert(derived().rows()==b.rows() && \"solve(): invalid number of rows of the right hand side matrix b\");\n    return SolveWithGuess<Derived, Rhs, Guess>(derived(), b.derived(), x0);\n  }\n\n  /** \\returns Success if the iterations converged, and NoConvergence otherwise. */\n  ComputationInfo info() const\n  {\n    eigen_assert(m_isInitialized && \"IterativeSolverBase is not initialized.\");\n    return m_info;\n  }\n  \n  /** \\internal */\n  template<typename Rhs, typename DestDerived>\n  void _solve_with_guess_impl(const Rhs& b, SparseMatrixBase<DestDerived> &aDest) const\n  {\n    eigen_assert(rows()==b.rows());\n    \n    Index rhsCols = b.cols();\n    Index size = b.rows();\n    DestDerived& dest(aDest.derived());\n    typedef typename DestDerived::Scalar DestScalar;\n    Eigen::Matrix<DestScalar,Dynamic,1> tb(size);\n    Eigen::Matrix<DestScalar,Dynamic,1> tx(cols());\n    // We do not directly fill dest because sparse expressions have to be free of aliasing issue.\n    // For non square least-square problems, b and dest might not have the same size whereas they might alias each-other.\n    typename DestDerived::PlainObject tmp(cols(),rhsCols);\n    ComputationInfo global_info = Success;\n    for(Index k=0; k<rhsCols; ++k)\n    {\n      tb = b.col(k);\n      tx = dest.col(k);\n      derived()._solve_vector_with_guess_impl(tb,tx);\n      tmp.col(k) = tx.sparseView(0);\n\n      // The call to _solve_vector_with_guess_impl updates m_info, so if it failed for a previous column\n      // we need to restore it to the worst value.\n      if(m_info==NumericalIssue)\n        global_info = NumericalIssue;\n      else if(m_info==NoConvergence)\n        global_info = NoConvergence;\n    }\n    m_info = global_info;\n    dest.swap(tmp);\n  }\n\n  template<typename Rhs, typename DestDerived>\n  typename internal::enable_if<Rhs::ColsAtCompileTime!=1 && DestDerived::ColsAtCompileTime!=1>::type\n  _solve_with_guess_impl(const Rhs& b, MatrixBase<DestDerived> &aDest) const\n  {\n    eigen_assert(rows()==b.rows());\n    \n    Index rhsCols = b.cols();\n    DestDerived& dest(aDest.derived());\n    ComputationInfo global_info = Success;\n    for(Index k=0; k<rhsCols; ++k)\n    {\n      typename DestDerived::ColXpr xk(dest,k);\n      typename Rhs::ConstColXpr bk(b,k);\n      derived()._solve_vector_with_guess_impl(bk,xk);\n\n      // The call to _solve_vector_with_guess updates m_info, so if it failed for a previous column\n      // we need to restore it to the worst value.\n      if(m_info==NumericalIssue)\n        global_info = NumericalIssue;\n      else if(m_info==NoConvergence)\n        global_info = NoConvergence;\n    }\n    m_info = global_info;\n  }\n\n  template<typename Rhs, typename DestDerived>\n  typename internal::enable_if<Rhs::ColsAtCompileTime==1 || DestDerived::ColsAtCompileTime==1>::type\n  _solve_with_guess_impl(const Rhs& b, MatrixBase<DestDerived> &dest) const\n  {\n    derived()._solve_vector_with_guess_impl(b,dest.derived());\n  }\n\n  /** \\internal default initial guess = 0 */\n  template<typename Rhs,typename Dest>\n  void _solve_impl(const Rhs& b, Dest& x) const\n  {\n    x.setZero();\n    derived()._solve_with_guess_impl(b,x);\n  }\n\nprotected:\n  void init()\n  {\n    m_isInitialized = false;\n    m_analysisIsOk = false;\n    m_factorizationIsOk = false;\n    m_maxIterations = -1;\n    m_tolerance = NumTraits<Scalar>::epsilon();\n  }\n\n  typedef internal::generic_matrix_wrapper<MatrixType> MatrixWrapper;\n  typedef typename MatrixWrapper::ActualMatrixType ActualMatrixType;\n\n  const ActualMatrixType& matrix() const\n  {\n    return m_matrixWrapper.matrix();\n  }\n  \n  template<typename InputType>\n  void grab(const InputType &A)\n  {\n    m_matrixWrapper.grab(A);\n  }\n  \n  MatrixWrapper m_matrixWrapper;\n  Preconditioner m_preconditioner;\n\n  Index m_maxIterations;\n  RealScalar m_tolerance;\n  \n  mutable RealScalar m_error;\n  mutable Index m_iterations;\n  mutable ComputationInfo m_info;\n  mutable bool m_analysisIsOk, m_factorizationIsOk;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_ITERATIVE_SOLVER_BASE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/IterativeLinearSolvers/LeastSquareConjugateGradient.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_LEAST_SQUARE_CONJUGATE_GRADIENT_H\n#define EIGEN_LEAST_SQUARE_CONJUGATE_GRADIENT_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\internal Low-level conjugate gradient algorithm for least-square problems\n  * \\param mat The matrix A\n  * \\param rhs The right hand side vector b\n  * \\param x On input and initial solution, on output the computed solution.\n  * \\param precond A preconditioner being able to efficiently solve for an\n  *                approximation of A'Ax=b (regardless of b)\n  * \\param iters On input the max number of iteration, on output the number of performed iterations.\n  * \\param tol_error On input the tolerance error, on output an estimation of the relative error.\n  */\ntemplate<typename MatrixType, typename Rhs, typename Dest, typename Preconditioner>\nEIGEN_DONT_INLINE\nvoid least_square_conjugate_gradient(const MatrixType& mat, const Rhs& rhs, Dest& x,\n                                     const Preconditioner& precond, Index& iters,\n                                     typename Dest::RealScalar& tol_error)\n{\n  using std::sqrt;\n  using std::abs;\n  typedef typename Dest::RealScalar RealScalar;\n  typedef typename Dest::Scalar Scalar;\n  typedef Matrix<Scalar,Dynamic,1> VectorType;\n  \n  RealScalar tol = tol_error;\n  Index maxIters = iters;\n  \n  Index m = mat.rows(), n = mat.cols();\n\n  VectorType residual        = rhs - mat * x;\n  VectorType normal_residual = mat.adjoint() * residual;\n\n  RealScalar rhsNorm2 = (mat.adjoint()*rhs).squaredNorm();\n  if(rhsNorm2 == 0) \n  {\n    x.setZero();\n    iters = 0;\n    tol_error = 0;\n    return;\n  }\n  RealScalar threshold = tol*tol*rhsNorm2;\n  RealScalar residualNorm2 = normal_residual.squaredNorm();\n  if (residualNorm2 < threshold)\n  {\n    iters = 0;\n    tol_error = sqrt(residualNorm2 / rhsNorm2);\n    return;\n  }\n  \n  VectorType p(n);\n  p = precond.solve(normal_residual);                         // initial search direction\n\n  VectorType z(n), tmp(m);\n  RealScalar absNew = numext::real(normal_residual.dot(p));  // the square of the absolute value of r scaled by invM\n  Index i = 0;\n  while(i < maxIters)\n  {\n    tmp.noalias() = mat * p;\n\n    Scalar alpha = absNew / tmp.squaredNorm();      // the amount we travel on dir\n    x += alpha * p;                                 // update solution\n    residual -= alpha * tmp;                        // update residual\n    normal_residual = mat.adjoint() * residual;     // update residual of the normal equation\n    \n    residualNorm2 = normal_residual.squaredNorm();\n    if(residualNorm2 < threshold)\n      break;\n    \n    z = precond.solve(normal_residual);             // approximately solve for \"A'A z = normal_residual\"\n\n    RealScalar absOld = absNew;\n    absNew = numext::real(normal_residual.dot(z));  // update the absolute value of r\n    RealScalar beta = absNew / absOld;              // calculate the Gram-Schmidt value used to create the new search direction\n    p = z + beta * p;                               // update search direction\n    i++;\n  }\n  tol_error = sqrt(residualNorm2 / rhsNorm2);\n  iters = i;\n}\n\n}\n\ntemplate< typename _MatrixType,\n          typename _Preconditioner = LeastSquareDiagonalPreconditioner<typename _MatrixType::Scalar> >\nclass LeastSquaresConjugateGradient;\n\nnamespace internal {\n\ntemplate< typename _MatrixType, typename _Preconditioner>\nstruct traits<LeastSquaresConjugateGradient<_MatrixType,_Preconditioner> >\n{\n  typedef _MatrixType MatrixType;\n  typedef _Preconditioner Preconditioner;\n};\n\n}\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\brief A conjugate gradient solver for sparse (or dense) least-square problems\n  *\n  * This class allows to solve for A x = b linear problems using an iterative conjugate gradient algorithm.\n  * The matrix A can be non symmetric and rectangular, but the matrix A' A should be positive-definite to guaranty stability.\n  * Otherwise, the SparseLU or SparseQR classes might be preferable.\n  * The matrix A and the vectors x and b can be either dense or sparse.\n  *\n  * \\tparam _MatrixType the type of the matrix A, can be a dense or a sparse matrix.\n  * \\tparam _Preconditioner the type of the preconditioner. Default is LeastSquareDiagonalPreconditioner\n  *\n  * \\implsparsesolverconcept\n  * \n  * The maximal number of iterations and tolerance value can be controlled via the setMaxIterations()\n  * and setTolerance() methods. The defaults are the size of the problem for the maximal number of iterations\n  * and NumTraits<Scalar>::epsilon() for the tolerance.\n  * \n  * This class can be used as the direct solver classes. Here is a typical usage example:\n    \\code\n    int m=1000000, n = 10000;\n    VectorXd x(n), b(m);\n    SparseMatrix<double> A(m,n);\n    // fill A and b\n    LeastSquaresConjugateGradient<SparseMatrix<double> > lscg;\n    lscg.compute(A);\n    x = lscg.solve(b);\n    std::cout << \"#iterations:     \" << lscg.iterations() << std::endl;\n    std::cout << \"estimated error: \" << lscg.error()      << std::endl;\n    // update b, and solve again\n    x = lscg.solve(b);\n    \\endcode\n  * \n  * By default the iterations start with x=0 as an initial guess of the solution.\n  * One can control the start using the solveWithGuess() method.\n  * \n  * \\sa class ConjugateGradient, SparseLU, SparseQR\n  */\ntemplate< typename _MatrixType, typename _Preconditioner>\nclass LeastSquaresConjugateGradient : public IterativeSolverBase<LeastSquaresConjugateGradient<_MatrixType,_Preconditioner> >\n{\n  typedef IterativeSolverBase<LeastSquaresConjugateGradient> Base;\n  using Base::matrix;\n  using Base::m_error;\n  using Base::m_iterations;\n  using Base::m_info;\n  using Base::m_isInitialized;\npublic:\n  typedef _MatrixType MatrixType;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef _Preconditioner Preconditioner;\n\npublic:\n\n  /** Default constructor. */\n  LeastSquaresConjugateGradient() : Base() {}\n\n  /** Initialize the solver with matrix \\a A for further \\c Ax=b solving.\n    * \n    * This constructor is a shortcut for the default constructor followed\n    * by a call to compute().\n    * \n    * \\warning this class stores a reference to the matrix A as well as some\n    * precomputed values that depend on it. Therefore, if \\a A is changed\n    * this class becomes invalid. Call compute() to update it with the new\n    * matrix A, or modify a copy of A.\n    */\n  template<typename MatrixDerived>\n  explicit LeastSquaresConjugateGradient(const EigenBase<MatrixDerived>& A) : Base(A.derived()) {}\n\n  ~LeastSquaresConjugateGradient() {}\n\n  /** \\internal */\n  template<typename Rhs,typename Dest>\n  void _solve_vector_with_guess_impl(const Rhs& b, Dest& x) const\n  {\n    m_iterations = Base::maxIterations();\n    m_error = Base::m_tolerance;\n\n    internal::least_square_conjugate_gradient(matrix(), b, x, Base::m_preconditioner, m_iterations, m_error);\n    m_info = m_error <= Base::m_tolerance ? Success : NoConvergence;\n  }\n\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_LEAST_SQUARE_CONJUGATE_GRADIENT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/IterativeLinearSolvers/SolveWithGuess.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SOLVEWITHGUESS_H\n#define EIGEN_SOLVEWITHGUESS_H\n\nnamespace Eigen {\n\ntemplate<typename Decomposition, typename RhsType, typename GuessType> class SolveWithGuess;\n  \n/** \\class SolveWithGuess\n  * \\ingroup IterativeLinearSolvers_Module\n  *\n  * \\brief Pseudo expression representing a solving operation\n  *\n  * \\tparam Decomposition the type of the matrix or decomposion object\n  * \\tparam Rhstype the type of the right-hand side\n  *\n  * This class represents an expression of A.solve(B)\n  * and most of the time this is the only way it is used.\n  *\n  */\nnamespace internal {\n\n\ntemplate<typename Decomposition, typename RhsType, typename GuessType>\nstruct traits<SolveWithGuess<Decomposition, RhsType, GuessType> >\n  : traits<Solve<Decomposition,RhsType> >\n{};\n\n}\n\n\ntemplate<typename Decomposition, typename RhsType, typename GuessType>\nclass SolveWithGuess : public internal::generic_xpr_base<SolveWithGuess<Decomposition,RhsType,GuessType>, MatrixXpr, typename internal::traits<RhsType>::StorageKind>::type\n{\npublic:\n  typedef typename internal::traits<SolveWithGuess>::Scalar Scalar;\n  typedef typename internal::traits<SolveWithGuess>::PlainObject PlainObject;\n  typedef typename internal::generic_xpr_base<SolveWithGuess<Decomposition,RhsType,GuessType>, MatrixXpr, typename internal::traits<RhsType>::StorageKind>::type Base;\n  typedef typename internal::ref_selector<SolveWithGuess>::type Nested;\n  \n  SolveWithGuess(const Decomposition &dec, const RhsType &rhs, const GuessType &guess)\n    : m_dec(dec), m_rhs(rhs), m_guess(guess)\n  {}\n  \n  EIGEN_DEVICE_FUNC Index rows() const { return m_dec.cols(); }\n  EIGEN_DEVICE_FUNC Index cols() const { return m_rhs.cols(); }\n\n  EIGEN_DEVICE_FUNC const Decomposition& dec()   const { return m_dec; }\n  EIGEN_DEVICE_FUNC const RhsType&       rhs()   const { return m_rhs; }\n  EIGEN_DEVICE_FUNC const GuessType&     guess() const { return m_guess; }\n\nprotected:\n  const Decomposition &m_dec;\n  const RhsType       &m_rhs;\n  const GuessType     &m_guess;\n  \nprivate:\n  Scalar coeff(Index row, Index col) const;\n  Scalar coeff(Index i) const;\n};\n\nnamespace internal {\n\n// Evaluator of SolveWithGuess -> eval into a temporary\ntemplate<typename Decomposition, typename RhsType, typename GuessType>\nstruct evaluator<SolveWithGuess<Decomposition,RhsType, GuessType> >\n  : public evaluator<typename SolveWithGuess<Decomposition,RhsType,GuessType>::PlainObject>\n{\n  typedef SolveWithGuess<Decomposition,RhsType,GuessType> SolveType;\n  typedef typename SolveType::PlainObject PlainObject;\n  typedef evaluator<PlainObject> Base;\n\n  evaluator(const SolveType& solve)\n    : m_result(solve.rows(), solve.cols())\n  {\n    ::new (static_cast<Base*>(this)) Base(m_result);\n    m_result = solve.guess();\n    solve.dec()._solve_with_guess_impl(solve.rhs(), m_result);\n  }\n  \nprotected:  \n  PlainObject m_result;\n};\n\n// Specialization for \"dst = dec.solveWithGuess(rhs)\"\n// NOTE we need to specialize it for Dense2Dense to avoid ambiguous specialization error and a Sparse2Sparse specialization must exist somewhere\ntemplate<typename DstXprType, typename DecType, typename RhsType, typename GuessType, typename Scalar>\nstruct Assignment<DstXprType, SolveWithGuess<DecType,RhsType,GuessType>, internal::assign_op<Scalar,Scalar>, Dense2Dense>\n{\n  typedef SolveWithGuess<DecType,RhsType,GuessType> SrcXprType;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<Scalar,Scalar> &)\n  {\n    Index dstRows = src.rows();\n    Index dstCols = src.cols();\n    if((dst.rows()!=dstRows) || (dst.cols()!=dstCols))\n      dst.resize(dstRows, dstCols);\n\n    dst = src.guess();\n    src.dec()._solve_with_guess_impl(src.rhs(), dst/*, src.guess()*/);\n  }\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SOLVEWITHGUESS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/Jacobi/Jacobi.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_JACOBI_H\n#define EIGEN_JACOBI_H\n\nnamespace Eigen {\n\n/** \\ingroup Jacobi_Module\n  * \\jacobi_module\n  * \\class JacobiRotation\n  * \\brief Rotation given by a cosine-sine pair.\n  *\n  * This class represents a Jacobi or Givens rotation.\n  * This is a 2D rotation in the plane \\c J of angle \\f$ \\theta \\f$ defined by\n  * its cosine \\c c and sine \\c s as follow:\n  * \\f$ J = \\left ( \\begin{array}{cc} c & \\overline s \\\\ -s  & \\overline c \\end{array} \\right ) \\f$\n  *\n  * You can apply the respective counter-clockwise rotation to a column vector \\c v by\n  * applying its adjoint on the left: \\f$ v = J^* v \\f$ that translates to the following Eigen code:\n  * \\code\n  * v.applyOnTheLeft(J.adjoint());\n  * \\endcode\n  *\n  * \\sa MatrixBase::applyOnTheLeft(), MatrixBase::applyOnTheRight()\n  */\ntemplate<typename Scalar> class JacobiRotation\n{\n  public:\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n\n    /** Default constructor without any initialization. */\n    EIGEN_DEVICE_FUNC\n    JacobiRotation() {}\n\n    /** Construct a planar rotation from a cosine-sine pair (\\a c, \\c s). */\n    EIGEN_DEVICE_FUNC\n    JacobiRotation(const Scalar& c, const Scalar& s) : m_c(c), m_s(s) {}\n\n    EIGEN_DEVICE_FUNC Scalar& c() { return m_c; }\n    EIGEN_DEVICE_FUNC Scalar c() const { return m_c; }\n    EIGEN_DEVICE_FUNC Scalar& s() { return m_s; }\n    EIGEN_DEVICE_FUNC Scalar s() const { return m_s; }\n\n    /** Concatenates two planar rotation */\n    EIGEN_DEVICE_FUNC\n    JacobiRotation operator*(const JacobiRotation& other)\n    {\n      using numext::conj;\n      return JacobiRotation(m_c * other.m_c - conj(m_s) * other.m_s,\n                            conj(m_c * conj(other.m_s) + conj(m_s) * conj(other.m_c)));\n    }\n\n    /** Returns the transposed transformation */\n    EIGEN_DEVICE_FUNC\n    JacobiRotation transpose() const { using numext::conj; return JacobiRotation(m_c, -conj(m_s)); }\n\n    /** Returns the adjoint transformation */\n    EIGEN_DEVICE_FUNC\n    JacobiRotation adjoint() const { using numext::conj; return JacobiRotation(conj(m_c), -m_s); }\n\n    template<typename Derived>\n    EIGEN_DEVICE_FUNC\n    bool makeJacobi(const MatrixBase<Derived>&, Index p, Index q);\n    EIGEN_DEVICE_FUNC\n    bool makeJacobi(const RealScalar& x, const Scalar& y, const RealScalar& z);\n\n    EIGEN_DEVICE_FUNC\n    void makeGivens(const Scalar& p, const Scalar& q, Scalar* r=0);\n\n  protected:\n    EIGEN_DEVICE_FUNC\n    void makeGivens(const Scalar& p, const Scalar& q, Scalar* r, internal::true_type);\n    EIGEN_DEVICE_FUNC\n    void makeGivens(const Scalar& p, const Scalar& q, Scalar* r, internal::false_type);\n\n    Scalar m_c, m_s;\n};\n\n/** Makes \\c *this as a Jacobi rotation \\a J such that applying \\a J on both the right and left sides of the selfadjoint 2x2 matrix\n  * \\f$ B = \\left ( \\begin{array}{cc} x & y \\\\ \\overline y & z \\end{array} \\right )\\f$ yields a diagonal matrix \\f$ A = J^* B J \\f$\n  *\n  * \\sa MatrixBase::makeJacobi(const MatrixBase<Derived>&, Index, Index), MatrixBase::applyOnTheLeft(), MatrixBase::applyOnTheRight()\n  */\ntemplate<typename Scalar>\nEIGEN_DEVICE_FUNC\nbool JacobiRotation<Scalar>::makeJacobi(const RealScalar& x, const Scalar& y, const RealScalar& z)\n{\n  using std::sqrt;\n  using std::abs;\n\n  RealScalar deno = RealScalar(2)*abs(y);\n  if(deno < (std::numeric_limits<RealScalar>::min)())\n  {\n    m_c = Scalar(1);\n    m_s = Scalar(0);\n    return false;\n  }\n  else\n  {\n    RealScalar tau = (x-z)/deno;\n    RealScalar w = sqrt(numext::abs2(tau) + RealScalar(1));\n    RealScalar t;\n    if(tau>RealScalar(0))\n    {\n      t = RealScalar(1) / (tau + w);\n    }\n    else\n    {\n      t = RealScalar(1) / (tau - w);\n    }\n    RealScalar sign_t = t > RealScalar(0) ? RealScalar(1) : RealScalar(-1);\n    RealScalar n = RealScalar(1) / sqrt(numext::abs2(t)+RealScalar(1));\n    m_s = - sign_t * (numext::conj(y) / abs(y)) * abs(t) * n;\n    m_c = n;\n    return true;\n  }\n}\n\n/** Makes \\c *this as a Jacobi rotation \\c J such that applying \\a J on both the right and left sides of the 2x2 selfadjoint matrix\n  * \\f$ B = \\left ( \\begin{array}{cc} \\text{this}_{pp} & \\text{this}_{pq} \\\\ (\\text{this}_{pq})^* & \\text{this}_{qq} \\end{array} \\right )\\f$ yields\n  * a diagonal matrix \\f$ A = J^* B J \\f$\n  *\n  * Example: \\include Jacobi_makeJacobi.cpp\n  * Output: \\verbinclude Jacobi_makeJacobi.out\n  *\n  * \\sa JacobiRotation::makeJacobi(RealScalar, Scalar, RealScalar), MatrixBase::applyOnTheLeft(), MatrixBase::applyOnTheRight()\n  */\ntemplate<typename Scalar>\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC\ninline bool JacobiRotation<Scalar>::makeJacobi(const MatrixBase<Derived>& m, Index p, Index q)\n{\n  return makeJacobi(numext::real(m.coeff(p,p)), m.coeff(p,q), numext::real(m.coeff(q,q)));\n}\n\n/** Makes \\c *this as a Givens rotation \\c G such that applying \\f$ G^* \\f$ to the left of the vector\n  * \\f$ V = \\left ( \\begin{array}{c} p \\\\ q \\end{array} \\right )\\f$ yields:\n  * \\f$ G^* V = \\left ( \\begin{array}{c} r \\\\ 0 \\end{array} \\right )\\f$.\n  *\n  * The value of \\a r is returned if \\a r is not null (the default is null).\n  * Also note that G is built such that the cosine is always real.\n  *\n  * Example: \\include Jacobi_makeGivens.cpp\n  * Output: \\verbinclude Jacobi_makeGivens.out\n  *\n  * This function implements the continuous Givens rotation generation algorithm\n  * found in Anderson (2000), Discontinuous Plane Rotations and the Symmetric Eigenvalue Problem.\n  * LAPACK Working Note 150, University of Tennessee, UT-CS-00-454, December 4, 2000.\n  *\n  * \\sa MatrixBase::applyOnTheLeft(), MatrixBase::applyOnTheRight()\n  */\ntemplate<typename Scalar>\nEIGEN_DEVICE_FUNC\nvoid JacobiRotation<Scalar>::makeGivens(const Scalar& p, const Scalar& q, Scalar* r)\n{\n  makeGivens(p, q, r, typename internal::conditional<NumTraits<Scalar>::IsComplex, internal::true_type, internal::false_type>::type());\n}\n\n\n// specialization for complexes\ntemplate<typename Scalar>\nEIGEN_DEVICE_FUNC\nvoid JacobiRotation<Scalar>::makeGivens(const Scalar& p, const Scalar& q, Scalar* r, internal::true_type)\n{\n  using std::sqrt;\n  using std::abs;\n  using numext::conj;\n\n  if(q==Scalar(0))\n  {\n    m_c = numext::real(p)<0 ? Scalar(-1) : Scalar(1);\n    m_s = 0;\n    if(r) *r = m_c * p;\n  }\n  else if(p==Scalar(0))\n  {\n    m_c = 0;\n    m_s = -q/abs(q);\n    if(r) *r = abs(q);\n  }\n  else\n  {\n    RealScalar p1 = numext::norm1(p);\n    RealScalar q1 = numext::norm1(q);\n    if(p1>=q1)\n    {\n      Scalar ps = p / p1;\n      RealScalar p2 = numext::abs2(ps);\n      Scalar qs = q / p1;\n      RealScalar q2 = numext::abs2(qs);\n\n      RealScalar u = sqrt(RealScalar(1) + q2/p2);\n      if(numext::real(p)<RealScalar(0))\n        u = -u;\n\n      m_c = Scalar(1)/u;\n      m_s = -qs*conj(ps)*(m_c/p2);\n      if(r) *r = p * u;\n    }\n    else\n    {\n      Scalar ps = p / q1;\n      RealScalar p2 = numext::abs2(ps);\n      Scalar qs = q / q1;\n      RealScalar q2 = numext::abs2(qs);\n\n      RealScalar u = q1 * sqrt(p2 + q2);\n      if(numext::real(p)<RealScalar(0))\n        u = -u;\n\n      p1 = abs(p);\n      ps = p/p1;\n      m_c = p1/u;\n      m_s = -conj(ps) * (q/u);\n      if(r) *r = ps * u;\n    }\n  }\n}\n\n// specialization for reals\ntemplate<typename Scalar>\nEIGEN_DEVICE_FUNC\nvoid JacobiRotation<Scalar>::makeGivens(const Scalar& p, const Scalar& q, Scalar* r, internal::false_type)\n{\n  using std::sqrt;\n  using std::abs;\n  if(q==Scalar(0))\n  {\n    m_c = p<Scalar(0) ? Scalar(-1) : Scalar(1);\n    m_s = Scalar(0);\n    if(r) *r = abs(p);\n  }\n  else if(p==Scalar(0))\n  {\n    m_c = Scalar(0);\n    m_s = q<Scalar(0) ? Scalar(1) : Scalar(-1);\n    if(r) *r = abs(q);\n  }\n  else if(abs(p) > abs(q))\n  {\n    Scalar t = q/p;\n    Scalar u = sqrt(Scalar(1) + numext::abs2(t));\n    if(p<Scalar(0))\n      u = -u;\n    m_c = Scalar(1)/u;\n    m_s = -t * m_c;\n    if(r) *r = p * u;\n  }\n  else\n  {\n    Scalar t = p/q;\n    Scalar u = sqrt(Scalar(1) + numext::abs2(t));\n    if(q<Scalar(0))\n      u = -u;\n    m_s = -Scalar(1)/u;\n    m_c = -t * m_s;\n    if(r) *r = q * u;\n  }\n\n}\n\n/****************************************************************************************\n*   Implementation of MatrixBase methods\n****************************************************************************************/\n\nnamespace internal {\n/** \\jacobi_module\n  * Applies the clock wise 2D rotation \\a j to the set of 2D vectors of coordinates \\a x and \\a y:\n  * \\f$ \\left ( \\begin{array}{cc} x \\\\ y \\end{array} \\right )  =  J \\left ( \\begin{array}{cc} x \\\\ y \\end{array} \\right ) \\f$\n  *\n  * \\sa MatrixBase::applyOnTheLeft(), MatrixBase::applyOnTheRight()\n  */\ntemplate<typename VectorX, typename VectorY, typename OtherScalar>\nEIGEN_DEVICE_FUNC\nvoid apply_rotation_in_the_plane(DenseBase<VectorX>& xpr_x, DenseBase<VectorY>& xpr_y, const JacobiRotation<OtherScalar>& j);\n}\n\n/** \\jacobi_module\n  * Applies the rotation in the plane \\a j to the rows \\a p and \\a q of \\c *this, i.e., it computes B = J * B,\n  * with \\f$ B = \\left ( \\begin{array}{cc} \\text{*this.row}(p) \\\\ \\text{*this.row}(q) \\end{array} \\right ) \\f$.\n  *\n  * \\sa class JacobiRotation, MatrixBase::applyOnTheRight(), internal::apply_rotation_in_the_plane()\n  */\ntemplate<typename Derived>\ntemplate<typename OtherScalar>\nEIGEN_DEVICE_FUNC\ninline void MatrixBase<Derived>::applyOnTheLeft(Index p, Index q, const JacobiRotation<OtherScalar>& j)\n{\n  RowXpr x(this->row(p));\n  RowXpr y(this->row(q));\n  internal::apply_rotation_in_the_plane(x, y, j);\n}\n\n/** \\ingroup Jacobi_Module\n  * Applies the rotation in the plane \\a j to the columns \\a p and \\a q of \\c *this, i.e., it computes B = B * J\n  * with \\f$ B = \\left ( \\begin{array}{cc} \\text{*this.col}(p) & \\text{*this.col}(q) \\end{array} \\right ) \\f$.\n  *\n  * \\sa class JacobiRotation, MatrixBase::applyOnTheLeft(), internal::apply_rotation_in_the_plane()\n  */\ntemplate<typename Derived>\ntemplate<typename OtherScalar>\nEIGEN_DEVICE_FUNC\ninline void MatrixBase<Derived>::applyOnTheRight(Index p, Index q, const JacobiRotation<OtherScalar>& j)\n{\n  ColXpr x(this->col(p));\n  ColXpr y(this->col(q));\n  internal::apply_rotation_in_the_plane(x, y, j.transpose());\n}\n\nnamespace internal {\n\ntemplate<typename Scalar, typename OtherScalar,\n         int SizeAtCompileTime, int MinAlignment, bool Vectorizable>\nstruct apply_rotation_in_the_plane_selector\n{\n  static EIGEN_DEVICE_FUNC\n  inline void run(Scalar *x, Index incrx, Scalar *y, Index incry, Index size, OtherScalar c, OtherScalar s)\n  {\n    for(Index i=0; i<size; ++i)\n    {\n      Scalar xi = *x;\n      Scalar yi = *y;\n      *x =  c * xi + numext::conj(s) * yi;\n      *y = -s * xi + numext::conj(c) * yi;\n      x += incrx;\n      y += incry;\n    }\n  }\n};\n\ntemplate<typename Scalar, typename OtherScalar,\n         int SizeAtCompileTime, int MinAlignment>\nstruct apply_rotation_in_the_plane_selector<Scalar,OtherScalar,SizeAtCompileTime,MinAlignment,true /* vectorizable */>\n{\n  static inline void run(Scalar *x, Index incrx, Scalar *y, Index incry, Index size, OtherScalar c, OtherScalar s)\n  {\n    enum {\n      PacketSize = packet_traits<Scalar>::size,\n      OtherPacketSize = packet_traits<OtherScalar>::size\n    };\n    typedef typename packet_traits<Scalar>::type Packet;\n    typedef typename packet_traits<OtherScalar>::type OtherPacket;\n\n    /*** dynamic-size vectorized paths ***/\n    if(SizeAtCompileTime == Dynamic && ((incrx==1 && incry==1) || PacketSize == 1))\n    {\n      // both vectors are sequentially stored in memory => vectorization\n      enum { Peeling = 2 };\n\n      Index alignedStart = internal::first_default_aligned(y, size);\n      Index alignedEnd = alignedStart + ((size-alignedStart)/PacketSize)*PacketSize;\n\n      const OtherPacket pc = pset1<OtherPacket>(c);\n      const OtherPacket ps = pset1<OtherPacket>(s);\n      conj_helper<OtherPacket,Packet,NumTraits<OtherScalar>::IsComplex,false> pcj;\n      conj_helper<OtherPacket,Packet,false,false> pm;\n\n      for(Index i=0; i<alignedStart; ++i)\n      {\n        Scalar xi = x[i];\n        Scalar yi = y[i];\n        x[i] =  c * xi + numext::conj(s) * yi;\n        y[i] = -s * xi + numext::conj(c) * yi;\n      }\n\n      Scalar* EIGEN_RESTRICT px = x + alignedStart;\n      Scalar* EIGEN_RESTRICT py = y + alignedStart;\n\n      if(internal::first_default_aligned(x, size)==alignedStart)\n      {\n        for(Index i=alignedStart; i<alignedEnd; i+=PacketSize)\n        {\n          Packet xi = pload<Packet>(px);\n          Packet yi = pload<Packet>(py);\n          pstore(px, padd(pm.pmul(pc,xi),pcj.pmul(ps,yi)));\n          pstore(py, psub(pcj.pmul(pc,yi),pm.pmul(ps,xi)));\n          px += PacketSize;\n          py += PacketSize;\n        }\n      }\n      else\n      {\n        Index peelingEnd = alignedStart + ((size-alignedStart)/(Peeling*PacketSize))*(Peeling*PacketSize);\n        for(Index i=alignedStart; i<peelingEnd; i+=Peeling*PacketSize)\n        {\n          Packet xi   = ploadu<Packet>(px);\n          Packet xi1  = ploadu<Packet>(px+PacketSize);\n          Packet yi   = pload <Packet>(py);\n          Packet yi1  = pload <Packet>(py+PacketSize);\n          pstoreu(px, padd(pm.pmul(pc,xi),pcj.pmul(ps,yi)));\n          pstoreu(px+PacketSize, padd(pm.pmul(pc,xi1),pcj.pmul(ps,yi1)));\n          pstore (py, psub(pcj.pmul(pc,yi),pm.pmul(ps,xi)));\n          pstore (py+PacketSize, psub(pcj.pmul(pc,yi1),pm.pmul(ps,xi1)));\n          px += Peeling*PacketSize;\n          py += Peeling*PacketSize;\n        }\n        if(alignedEnd!=peelingEnd)\n        {\n          Packet xi = ploadu<Packet>(x+peelingEnd);\n          Packet yi = pload <Packet>(y+peelingEnd);\n          pstoreu(x+peelingEnd, padd(pm.pmul(pc,xi),pcj.pmul(ps,yi)));\n          pstore (y+peelingEnd, psub(pcj.pmul(pc,yi),pm.pmul(ps,xi)));\n        }\n      }\n\n      for(Index i=alignedEnd; i<size; ++i)\n      {\n        Scalar xi = x[i];\n        Scalar yi = y[i];\n        x[i] =  c * xi + numext::conj(s) * yi;\n        y[i] = -s * xi + numext::conj(c) * yi;\n      }\n    }\n\n    /*** fixed-size vectorized path ***/\n    else if(SizeAtCompileTime != Dynamic && MinAlignment>0) // FIXME should be compared to the required alignment\n    {\n      const OtherPacket pc = pset1<OtherPacket>(c);\n      const OtherPacket ps = pset1<OtherPacket>(s);\n      conj_helper<OtherPacket,Packet,NumTraits<OtherPacket>::IsComplex,false> pcj;\n      conj_helper<OtherPacket,Packet,false,false> pm;\n      Scalar* EIGEN_RESTRICT px = x;\n      Scalar* EIGEN_RESTRICT py = y;\n      for(Index i=0; i<size; i+=PacketSize)\n      {\n        Packet xi = pload<Packet>(px);\n        Packet yi = pload<Packet>(py);\n        pstore(px, padd(pm.pmul(pc,xi),pcj.pmul(ps,yi)));\n        pstore(py, psub(pcj.pmul(pc,yi),pm.pmul(ps,xi)));\n        px += PacketSize;\n        py += PacketSize;\n      }\n    }\n\n    /*** non-vectorized path ***/\n    else\n    {\n      apply_rotation_in_the_plane_selector<Scalar,OtherScalar,SizeAtCompileTime,MinAlignment,false>::run(x,incrx,y,incry,size,c,s);\n    }\n  }\n};\n\ntemplate<typename VectorX, typename VectorY, typename OtherScalar>\nEIGEN_DEVICE_FUNC\nvoid /*EIGEN_DONT_INLINE*/ apply_rotation_in_the_plane(DenseBase<VectorX>& xpr_x, DenseBase<VectorY>& xpr_y, const JacobiRotation<OtherScalar>& j)\n{\n  typedef typename VectorX::Scalar Scalar;\n  const bool Vectorizable =    (int(VectorX::Flags) & int(VectorY::Flags) & PacketAccessBit)\n                            && (int(packet_traits<Scalar>::size) == int(packet_traits<OtherScalar>::size));\n\n  eigen_assert(xpr_x.size() == xpr_y.size());\n  Index size = xpr_x.size();\n  Index incrx = xpr_x.derived().innerStride();\n  Index incry = xpr_y.derived().innerStride();\n\n  Scalar* EIGEN_RESTRICT x = &xpr_x.derived().coeffRef(0);\n  Scalar* EIGEN_RESTRICT y = &xpr_y.derived().coeffRef(0);\n\n  OtherScalar c = j.c();\n  OtherScalar s = j.s();\n  if (c==OtherScalar(1) && s==OtherScalar(0))\n    return;\n\n  apply_rotation_in_the_plane_selector<\n    Scalar,OtherScalar,\n    VectorX::SizeAtCompileTime,\n    EIGEN_PLAIN_ENUM_MIN(evaluator<VectorX>::Alignment, evaluator<VectorY>::Alignment),\n    Vectorizable>::run(x,incrx,y,incry,size,c,s);\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_JACOBI_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/KLUSupport/KLUSupport.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2017 Kyle Macfarlan <kyle.macfarlan@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_KLUSUPPORT_H\n#define EIGEN_KLUSUPPORT_H\n\nnamespace Eigen {\n\n/* TODO extract L, extract U, compute det, etc... */\n\n/** \\ingroup KLUSupport_Module\n  * \\brief A sparse LU factorization and solver based on KLU\n  *\n  * This class allows to solve for A.X = B sparse linear problems via a LU factorization\n  * using the KLU library. The sparse matrix A must be squared and full rank.\n  * The vectors or matrices X and B can be either dense or sparse.\n  *\n  * \\warning The input matrix A should be in a \\b compressed and \\b column-major form.\n  * Otherwise an expensive copy will be made. You can call the inexpensive makeCompressed() to get a compressed matrix.\n  * \\tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class UmfPackLU, class SparseLU\n  */\n\n\ninline int klu_solve(klu_symbolic *Symbolic, klu_numeric *Numeric, Index ldim, Index nrhs, double B [ ], klu_common *Common, double) {\n   return klu_solve(Symbolic, Numeric, internal::convert_index<int>(ldim), internal::convert_index<int>(nrhs), B, Common);\n}\n\ninline int klu_solve(klu_symbolic *Symbolic, klu_numeric *Numeric, Index ldim, Index nrhs, std::complex<double>B[], klu_common *Common, std::complex<double>) {\n   return klu_z_solve(Symbolic, Numeric, internal::convert_index<int>(ldim), internal::convert_index<int>(nrhs), &numext::real_ref(B[0]), Common);\n}\n\ninline int klu_tsolve(klu_symbolic *Symbolic, klu_numeric *Numeric, Index ldim, Index nrhs, double B[], klu_common *Common, double) {\n   return klu_tsolve(Symbolic, Numeric, internal::convert_index<int>(ldim), internal::convert_index<int>(nrhs), B, Common);\n}\n\ninline int klu_tsolve(klu_symbolic *Symbolic, klu_numeric *Numeric, Index ldim, Index nrhs, std::complex<double>B[], klu_common *Common, std::complex<double>) {\n   return klu_z_tsolve(Symbolic, Numeric, internal::convert_index<int>(ldim), internal::convert_index<int>(nrhs), &numext::real_ref(B[0]), 0, Common);\n}\n\ninline klu_numeric* klu_factor(int Ap [ ], int Ai [ ], double Ax [ ], klu_symbolic *Symbolic, klu_common *Common, double) {\n   return klu_factor(Ap, Ai, Ax, Symbolic, Common);\n}\n\ninline klu_numeric* klu_factor(int Ap[], int Ai[], std::complex<double> Ax[], klu_symbolic *Symbolic, klu_common *Common, std::complex<double>) {\n   return klu_z_factor(Ap, Ai, &numext::real_ref(Ax[0]), Symbolic, Common);\n}\n\n\ntemplate<typename _MatrixType>\nclass KLU : public SparseSolverBase<KLU<_MatrixType> >\n{\n  protected:\n    typedef SparseSolverBase<KLU<_MatrixType> > Base;\n    using Base::m_isInitialized;\n  public:\n    using Base::_solve_impl;\n    typedef _MatrixType MatrixType;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef Matrix<Scalar,Dynamic,1> Vector;\n    typedef Matrix<int, 1, MatrixType::ColsAtCompileTime> IntRowVectorType;\n    typedef Matrix<int, MatrixType::RowsAtCompileTime, 1> IntColVectorType;\n    typedef SparseMatrix<Scalar> LUMatrixType;\n    typedef SparseMatrix<Scalar,ColMajor,int> KLUMatrixType;\n    typedef Ref<const KLUMatrixType, StandardCompressedFormat> KLUMatrixRef;\n    enum {\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n\n  public:\n\n    KLU()\n      : m_dummy(0,0), mp_matrix(m_dummy)\n    {\n      init();\n    }\n\n    template<typename InputMatrixType>\n    explicit KLU(const InputMatrixType& matrix)\n      : mp_matrix(matrix)\n    {\n      init();\n      compute(matrix);\n    }\n\n    ~KLU()\n    {\n      if(m_symbolic) klu_free_symbolic(&m_symbolic,&m_common);\n      if(m_numeric)  klu_free_numeric(&m_numeric,&m_common);\n    }\n\n    inline Index rows() const { return mp_matrix.rows(); }\n    inline Index cols() const { return mp_matrix.cols(); }\n\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the matrix.appears to be negative.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_info;\n    }\n#if 0 // not implemented yet\n    inline const LUMatrixType& matrixL() const\n    {\n      if (m_extractedDataAreDirty) extractData();\n      return m_l;\n    }\n\n    inline const LUMatrixType& matrixU() const\n    {\n      if (m_extractedDataAreDirty) extractData();\n      return m_u;\n    }\n\n    inline const IntColVectorType& permutationP() const\n    {\n      if (m_extractedDataAreDirty) extractData();\n      return m_p;\n    }\n\n    inline const IntRowVectorType& permutationQ() const\n    {\n      if (m_extractedDataAreDirty) extractData();\n      return m_q;\n    }\n#endif\n    /** Computes the sparse Cholesky decomposition of \\a matrix\n     *  Note that the matrix should be column-major, and in compressed format for best performance.\n     *  \\sa SparseMatrix::makeCompressed().\n     */\n    template<typename InputMatrixType>\n    void compute(const InputMatrixType& matrix)\n    {\n      if(m_symbolic) klu_free_symbolic(&m_symbolic, &m_common);\n      if(m_numeric)  klu_free_numeric(&m_numeric, &m_common);\n      grab(matrix.derived());\n      analyzePattern_impl();\n      factorize_impl();\n    }\n\n    /** Performs a symbolic decomposition on the sparcity of \\a matrix.\n      *\n      * This function is particularly useful when solving for several problems having the same structure.\n      *\n      * \\sa factorize(), compute()\n      */\n    template<typename InputMatrixType>\n    void analyzePattern(const InputMatrixType& matrix)\n    {\n      if(m_symbolic) klu_free_symbolic(&m_symbolic, &m_common);\n      if(m_numeric)  klu_free_numeric(&m_numeric, &m_common);\n\n      grab(matrix.derived());\n\n      analyzePattern_impl();\n    }\n\n\n    /** Provides access to the control settings array used by KLU.\n      *\n      * See KLU documentation for details.\n      */\n    inline const klu_common& kluCommon() const\n    {\n      return m_common;\n    }\n\n    /** Provides access to the control settings array used by UmfPack.\n      *\n      * If this array contains NaN's, the default values are used.\n      *\n      * See KLU documentation for details.\n      */\n    inline klu_common& kluCommon()\n    {\n      return m_common;\n    }\n\n    /** Performs a numeric decomposition of \\a matrix\n      *\n      * The given matrix must has the same sparcity than the matrix on which the pattern anylysis has been performed.\n      *\n      * \\sa analyzePattern(), compute()\n      */\n    template<typename InputMatrixType>\n    void factorize(const InputMatrixType& matrix)\n    {\n      eigen_assert(m_analysisIsOk && \"KLU: you must first call analyzePattern()\");\n      if(m_numeric)\n        klu_free_numeric(&m_numeric,&m_common);\n\n      grab(matrix.derived());\n\n      factorize_impl();\n    }\n\n    /** \\internal */\n    template<typename BDerived,typename XDerived>\n    bool _solve_impl(const MatrixBase<BDerived> &b, MatrixBase<XDerived> &x) const;\n\n#if 0 // not implemented yet\n    Scalar determinant() const;\n\n    void extractData() const;\n#endif\n\n  protected:\n\n    void init()\n    {\n      m_info                  = InvalidInput;\n      m_isInitialized         = false;\n      m_numeric               = 0;\n      m_symbolic              = 0;\n      m_extractedDataAreDirty = true;\n\n      klu_defaults(&m_common);\n    }\n\n    void analyzePattern_impl()\n    {\n      m_info = InvalidInput;\n      m_analysisIsOk = false;\n      m_factorizationIsOk = false;\n      m_symbolic = klu_analyze(internal::convert_index<int>(mp_matrix.rows()),\n                                     const_cast<StorageIndex*>(mp_matrix.outerIndexPtr()), const_cast<StorageIndex*>(mp_matrix.innerIndexPtr()),\n                                     &m_common);\n      if (m_symbolic) {\n         m_isInitialized = true;\n         m_info = Success;\n         m_analysisIsOk = true;\n         m_extractedDataAreDirty = true;\n      }\n    }\n\n    void factorize_impl()\n    {\n\n      m_numeric = klu_factor(const_cast<StorageIndex*>(mp_matrix.outerIndexPtr()), const_cast<StorageIndex*>(mp_matrix.innerIndexPtr()), const_cast<Scalar*>(mp_matrix.valuePtr()),\n                                    m_symbolic, &m_common, Scalar());\n                                         \n\n      m_info = m_numeric ? Success : NumericalIssue;\n      m_factorizationIsOk = m_numeric ? 1 : 0;\n      m_extractedDataAreDirty = true;\n    }\n\n    template<typename MatrixDerived>\n    void grab(const EigenBase<MatrixDerived> &A)\n    {\n      mp_matrix.~KLUMatrixRef();\n      ::new (&mp_matrix) KLUMatrixRef(A.derived());\n    }\n\n    void grab(const KLUMatrixRef &A)\n    {\n      if(&(A.derived()) != &mp_matrix)\n      {\n        mp_matrix.~KLUMatrixRef();\n        ::new (&mp_matrix) KLUMatrixRef(A);\n      }\n    }\n\n    // cached data to reduce reallocation, etc.\n#if 0 // not implemented yet\n    mutable LUMatrixType m_l;\n    mutable LUMatrixType m_u;\n    mutable IntColVectorType m_p;\n    mutable IntRowVectorType m_q;\n#endif\n\n    KLUMatrixType m_dummy;\n    KLUMatrixRef mp_matrix;\n\n    klu_numeric* m_numeric;\n    klu_symbolic* m_symbolic;\n    klu_common m_common;\n    mutable ComputationInfo m_info;\n    int m_factorizationIsOk;\n    int m_analysisIsOk;\n    mutable bool m_extractedDataAreDirty;\n\n  private:\n    KLU(const KLU& ) { }\n};\n\n#if 0 // not implemented yet\ntemplate<typename MatrixType>\nvoid KLU<MatrixType>::extractData() const\n{\n  if (m_extractedDataAreDirty)\n  {\n     eigen_assert(false && \"KLU: extractData Not Yet Implemented\");\n\n    // get size of the data\n    int lnz, unz, rows, cols, nz_udiag;\n    umfpack_get_lunz(&lnz, &unz, &rows, &cols, &nz_udiag, m_numeric, Scalar());\n\n    // allocate data\n    m_l.resize(rows,(std::min)(rows,cols));\n    m_l.resizeNonZeros(lnz);\n\n    m_u.resize((std::min)(rows,cols),cols);\n    m_u.resizeNonZeros(unz);\n\n    m_p.resize(rows);\n    m_q.resize(cols);\n\n    // extract\n    umfpack_get_numeric(m_l.outerIndexPtr(), m_l.innerIndexPtr(), m_l.valuePtr(),\n                        m_u.outerIndexPtr(), m_u.innerIndexPtr(), m_u.valuePtr(),\n                        m_p.data(), m_q.data(), 0, 0, 0, m_numeric);\n\n    m_extractedDataAreDirty = false;\n  }\n}\n\ntemplate<typename MatrixType>\ntypename KLU<MatrixType>::Scalar KLU<MatrixType>::determinant() const\n{\n  eigen_assert(false && \"KLU: extractData Not Yet Implemented\");\n  return Scalar();\n}\n#endif\n\ntemplate<typename MatrixType>\ntemplate<typename BDerived,typename XDerived>\nbool KLU<MatrixType>::_solve_impl(const MatrixBase<BDerived> &b, MatrixBase<XDerived> &x) const\n{\n  Index rhsCols = b.cols();\n  EIGEN_STATIC_ASSERT((XDerived::Flags&RowMajorBit)==0, THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES);\n  eigen_assert(m_factorizationIsOk && \"The decomposition is not in a valid state for solving, you must first call either compute() or analyzePattern()/factorize()\");\n\n  x = b;\n  int info = klu_solve(m_symbolic, m_numeric, b.rows(), rhsCols, x.const_cast_derived().data(), const_cast<klu_common*>(&m_common), Scalar());\n\n  m_info = info!=0 ? Success : NumericalIssue;\n  return true;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_KLUSUPPORT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/LU/Determinant.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_DETERMINANT_H\n#define EIGEN_DETERMINANT_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC\ninline const typename Derived::Scalar bruteforce_det3_helper\n(const MatrixBase<Derived>& matrix, int a, int b, int c)\n{\n  return matrix.coeff(0,a)\n         * (matrix.coeff(1,b) * matrix.coeff(2,c) - matrix.coeff(1,c) * matrix.coeff(2,b));\n}\n\ntemplate<typename Derived,\n         int DeterminantType = Derived::RowsAtCompileTime\n> struct determinant_impl\n{\n  static inline typename traits<Derived>::Scalar run(const Derived& m)\n  {\n    if(Derived::ColsAtCompileTime==Dynamic && m.rows()==0)\n      return typename traits<Derived>::Scalar(1);\n    return m.partialPivLu().determinant();\n  }\n};\n\ntemplate<typename Derived> struct determinant_impl<Derived, 1>\n{\n  static inline EIGEN_DEVICE_FUNC\n  typename traits<Derived>::Scalar run(const Derived& m)\n  {\n    return m.coeff(0,0);\n  }\n};\n\ntemplate<typename Derived> struct determinant_impl<Derived, 2>\n{\n  static inline EIGEN_DEVICE_FUNC\n  typename traits<Derived>::Scalar run(const Derived& m)\n  {\n    return m.coeff(0,0) * m.coeff(1,1) - m.coeff(1,0) * m.coeff(0,1);\n  }\n};\n\ntemplate<typename Derived> struct determinant_impl<Derived, 3>\n{\n  static inline EIGEN_DEVICE_FUNC\n  typename traits<Derived>::Scalar run(const Derived& m)\n  {\n    return bruteforce_det3_helper(m,0,1,2)\n          - bruteforce_det3_helper(m,1,0,2)\n          + bruteforce_det3_helper(m,2,0,1);\n  }\n};\n\ntemplate<typename Derived> struct determinant_impl<Derived, 4>\n{\n  typedef typename traits<Derived>::Scalar Scalar;\n  static EIGEN_DEVICE_FUNC\n  Scalar run(const Derived& m)\n  {\n    Scalar d2_01 = det2(m, 0, 1);\n    Scalar d2_02 = det2(m, 0, 2);\n    Scalar d2_03 = det2(m, 0, 3);\n    Scalar d2_12 = det2(m, 1, 2);\n    Scalar d2_13 = det2(m, 1, 3);\n    Scalar d2_23 = det2(m, 2, 3);\n    Scalar d3_0 = det3(m, 1,d2_23, 2,d2_13, 3,d2_12);\n    Scalar d3_1 = det3(m, 0,d2_23, 2,d2_03, 3,d2_02);\n    Scalar d3_2 = det3(m, 0,d2_13, 1,d2_03, 3,d2_01);\n    Scalar d3_3 = det3(m, 0,d2_12, 1,d2_02, 2,d2_01);\n    return internal::pmadd(-m(0,3),d3_0, m(1,3)*d3_1) +\n           internal::pmadd(-m(2,3),d3_2, m(3,3)*d3_3);\n  }\nprotected:\n  static EIGEN_DEVICE_FUNC\n  Scalar det2(const Derived& m, Index i0, Index i1)\n  {\n    return m(i0,0) * m(i1,1) - m(i1,0) * m(i0,1);\n  }\n\n  static EIGEN_DEVICE_FUNC\n  Scalar det3(const Derived& m, Index i0, const Scalar& d0, Index i1, const Scalar& d1, Index i2, const Scalar& d2)\n  {\n    return internal::pmadd(m(i0,2), d0, internal::pmadd(-m(i1,2), d1, m(i2,2)*d2));\n  }\n};\n\n} // end namespace internal\n\n/** \\lu_module\n  *\n  * \\returns the determinant of this matrix\n  */\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC\ninline typename internal::traits<Derived>::Scalar MatrixBase<Derived>::determinant() const\n{\n  eigen_assert(rows() == cols());\n  typedef typename internal::nested_eval<Derived,Base::RowsAtCompileTime>::type Nested;\n  return internal::determinant_impl<typename internal::remove_all<Nested>::type>::run(derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_DETERMINANT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/LU/FullPivLU.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_LU_H\n#define EIGEN_LU_H\n\nnamespace Eigen {\n\nnamespace internal {\ntemplate<typename _MatrixType> struct traits<FullPivLU<_MatrixType> >\n : traits<_MatrixType>\n{\n  typedef MatrixXpr XprKind;\n  typedef SolverStorage StorageKind;\n  typedef int StorageIndex;\n  enum { Flags = 0 };\n};\n\n} // end namespace internal\n\n/** \\ingroup LU_Module\n  *\n  * \\class FullPivLU\n  *\n  * \\brief LU decomposition of a matrix with complete pivoting, and related features\n  *\n  * \\tparam _MatrixType the type of the matrix of which we are computing the LU decomposition\n  *\n  * This class represents a LU decomposition of any matrix, with complete pivoting: the matrix A is\n  * decomposed as \\f$ A = P^{-1} L U Q^{-1} \\f$ where L is unit-lower-triangular, U is\n  * upper-triangular, and P and Q are permutation matrices. This is a rank-revealing LU\n  * decomposition. The eigenvalues (diagonal coefficients) of U are sorted in such a way that any\n  * zeros are at the end.\n  *\n  * This decomposition provides the generic approach to solving systems of linear equations, computing\n  * the rank, invertibility, inverse, kernel, and determinant.\n  *\n  * This LU decomposition is very stable and well tested with large matrices. However there are use cases where the SVD\n  * decomposition is inherently more stable and/or flexible. For example, when computing the kernel of a matrix,\n  * working with the SVD allows to select the smallest singular values of the matrix, something that\n  * the LU decomposition doesn't see.\n  *\n  * The data of the LU decomposition can be directly accessed through the methods matrixLU(),\n  * permutationP(), permutationQ().\n  *\n  * As an example, here is how the original matrix can be retrieved:\n  * \\include class_FullPivLU.cpp\n  * Output: \\verbinclude class_FullPivLU.out\n  *\n  * This class supports the \\link InplaceDecomposition inplace decomposition \\endlink mechanism.\n  *\n  * \\sa MatrixBase::fullPivLu(), MatrixBase::determinant(), MatrixBase::inverse()\n  */\ntemplate<typename _MatrixType> class FullPivLU\n  : public SolverBase<FullPivLU<_MatrixType> >\n{\n  public:\n    typedef _MatrixType MatrixType;\n    typedef SolverBase<FullPivLU> Base;\n    friend class SolverBase<FullPivLU>;\n\n    EIGEN_GENERIC_PUBLIC_INTERFACE(FullPivLU)\n    enum {\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n    typedef typename internal::plain_row_type<MatrixType, StorageIndex>::type IntRowVectorType;\n    typedef typename internal::plain_col_type<MatrixType, StorageIndex>::type IntColVectorType;\n    typedef PermutationMatrix<ColsAtCompileTime, MaxColsAtCompileTime> PermutationQType;\n    typedef PermutationMatrix<RowsAtCompileTime, MaxRowsAtCompileTime> PermutationPType;\n    typedef typename MatrixType::PlainObject PlainObject;\n\n    /**\n      * \\brief Default Constructor.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via LU::compute(const MatrixType&).\n      */\n    FullPivLU();\n\n    /** \\brief Default Constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem \\a size.\n      * \\sa FullPivLU()\n      */\n    FullPivLU(Index rows, Index cols);\n\n    /** Constructor.\n      *\n      * \\param matrix the matrix of which to compute the LU decomposition.\n      *               It is required to be nonzero.\n      */\n    template<typename InputType>\n    explicit FullPivLU(const EigenBase<InputType>& matrix);\n\n    /** \\brief Constructs a LU factorization from a given matrix\n      *\n      * This overloaded constructor is provided for \\link InplaceDecomposition inplace decomposition \\endlink when \\c MatrixType is a Eigen::Ref.\n      *\n      * \\sa FullPivLU(const EigenBase&)\n      */\n    template<typename InputType>\n    explicit FullPivLU(EigenBase<InputType>& matrix);\n\n    /** Computes the LU decomposition of the given matrix.\n      *\n      * \\param matrix the matrix of which to compute the LU decomposition.\n      *               It is required to be nonzero.\n      *\n      * \\returns a reference to *this\n      */\n    template<typename InputType>\n    FullPivLU& compute(const EigenBase<InputType>& matrix) {\n      m_lu = matrix.derived();\n      computeInPlace();\n      return *this;\n    }\n\n    /** \\returns the LU decomposition matrix: the upper-triangular part is U, the\n      * unit-lower-triangular part is L (at least for square matrices; in the non-square\n      * case, special care is needed, see the documentation of class FullPivLU).\n      *\n      * \\sa matrixL(), matrixU()\n      */\n    inline const MatrixType& matrixLU() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return m_lu;\n    }\n\n    /** \\returns the number of nonzero pivots in the LU decomposition.\n      * Here nonzero is meant in the exact sense, not in a fuzzy sense.\n      * So that notion isn't really intrinsically interesting, but it is\n      * still useful when implementing algorithms.\n      *\n      * \\sa rank()\n      */\n    inline Index nonzeroPivots() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return m_nonzero_pivots;\n    }\n\n    /** \\returns the absolute value of the biggest pivot, i.e. the biggest\n      *          diagonal coefficient of U.\n      */\n    RealScalar maxPivot() const { return m_maxpivot; }\n\n    /** \\returns the permutation matrix P\n      *\n      * \\sa permutationQ()\n      */\n    EIGEN_DEVICE_FUNC inline const PermutationPType& permutationP() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return m_p;\n    }\n\n    /** \\returns the permutation matrix Q\n      *\n      * \\sa permutationP()\n      */\n    inline const PermutationQType& permutationQ() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return m_q;\n    }\n\n    /** \\returns the kernel of the matrix, also called its null-space. The columns of the returned matrix\n      * will form a basis of the kernel.\n      *\n      * \\note If the kernel has dimension zero, then the returned matrix is a column-vector filled with zeros.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      *\n      * Example: \\include FullPivLU_kernel.cpp\n      * Output: \\verbinclude FullPivLU_kernel.out\n      *\n      * \\sa image()\n      */\n    inline const internal::kernel_retval<FullPivLU> kernel() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return internal::kernel_retval<FullPivLU>(*this);\n    }\n\n    /** \\returns the image of the matrix, also called its column-space. The columns of the returned matrix\n      * will form a basis of the image (column-space).\n      *\n      * \\param originalMatrix the original matrix, of which *this is the LU decomposition.\n      *                       The reason why it is needed to pass it here, is that this allows\n      *                       a large optimization, as otherwise this method would need to reconstruct it\n      *                       from the LU decomposition.\n      *\n      * \\note If the image has dimension zero, then the returned matrix is a column-vector filled with zeros.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      *\n      * Example: \\include FullPivLU_image.cpp\n      * Output: \\verbinclude FullPivLU_image.out\n      *\n      * \\sa kernel()\n      */\n    inline const internal::image_retval<FullPivLU>\n      image(const MatrixType& originalMatrix) const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return internal::image_retval<FullPivLU>(*this, originalMatrix);\n    }\n\n    #ifdef EIGEN_PARSED_BY_DOXYGEN\n    /** \\return a solution x to the equation Ax=b, where A is the matrix of which\n      * *this is the LU decomposition.\n      *\n      * \\param b the right-hand-side of the equation to solve. Can be a vector or a matrix,\n      *          the only requirement in order for the equation to make sense is that\n      *          b.rows()==A.rows(), where A is the matrix of which *this is the LU decomposition.\n      *\n      * \\returns a solution.\n      *\n      * \\note_about_checking_solutions\n      *\n      * \\note_about_arbitrary_choice_of_solution\n      * \\note_about_using_kernel_to_study_multiple_solutions\n      *\n      * Example: \\include FullPivLU_solve.cpp\n      * Output: \\verbinclude FullPivLU_solve.out\n      *\n      * \\sa TriangularView::solve(), kernel(), inverse()\n      */\n    template<typename Rhs>\n    inline const Solve<FullPivLU, Rhs>\n    solve(const MatrixBase<Rhs>& b) const;\n    #endif\n\n    /** \\returns an estimate of the reciprocal condition number of the matrix of which \\c *this is\n        the LU decomposition.\n      */\n    inline RealScalar rcond() const\n    {\n      eigen_assert(m_isInitialized && \"PartialPivLU is not initialized.\");\n      return internal::rcond_estimate_helper(m_l1_norm, *this);\n    }\n\n    /** \\returns the determinant of the matrix of which\n      * *this is the LU decomposition. It has only linear complexity\n      * (that is, O(n) where n is the dimension of the square matrix)\n      * as the LU decomposition has already been computed.\n      *\n      * \\note This is only for square matrices.\n      *\n      * \\note For fixed-size matrices of size up to 4, MatrixBase::determinant() offers\n      *       optimized paths.\n      *\n      * \\warning a determinant can be very big or small, so for matrices\n      * of large enough dimension, there is a risk of overflow/underflow.\n      *\n      * \\sa MatrixBase::determinant()\n      */\n    typename internal::traits<MatrixType>::Scalar determinant() const;\n\n    /** Allows to prescribe a threshold to be used by certain methods, such as rank(),\n      * who need to determine when pivots are to be considered nonzero. This is not used for the\n      * LU decomposition itself.\n      *\n      * When it needs to get the threshold value, Eigen calls threshold(). By default, this\n      * uses a formula to automatically determine a reasonable threshold.\n      * Once you have called the present method setThreshold(const RealScalar&),\n      * your value is used instead.\n      *\n      * \\param threshold The new value to use as the threshold.\n      *\n      * A pivot will be considered nonzero if its absolute value is strictly greater than\n      *  \\f$ \\vert pivot \\vert \\leqslant threshold \\times \\vert maxpivot \\vert \\f$\n      * where maxpivot is the biggest pivot.\n      *\n      * If you want to come back to the default behavior, call setThreshold(Default_t)\n      */\n    FullPivLU& setThreshold(const RealScalar& threshold)\n    {\n      m_usePrescribedThreshold = true;\n      m_prescribedThreshold = threshold;\n      return *this;\n    }\n\n    /** Allows to come back to the default behavior, letting Eigen use its default formula for\n      * determining the threshold.\n      *\n      * You should pass the special object Eigen::Default as parameter here.\n      * \\code lu.setThreshold(Eigen::Default); \\endcode\n      *\n      * See the documentation of setThreshold(const RealScalar&).\n      */\n    FullPivLU& setThreshold(Default_t)\n    {\n      m_usePrescribedThreshold = false;\n      return *this;\n    }\n\n    /** Returns the threshold that will be used by certain methods such as rank().\n      *\n      * See the documentation of setThreshold(const RealScalar&).\n      */\n    RealScalar threshold() const\n    {\n      eigen_assert(m_isInitialized || m_usePrescribedThreshold);\n      return m_usePrescribedThreshold ? m_prescribedThreshold\n      // this formula comes from experimenting (see \"LU precision tuning\" thread on the list)\n      // and turns out to be identical to Higham's formula used already in LDLt.\n          : NumTraits<Scalar>::epsilon() * RealScalar(m_lu.diagonalSize());\n    }\n\n    /** \\returns the rank of the matrix of which *this is the LU decomposition.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline Index rank() const\n    {\n      using std::abs;\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      RealScalar premultiplied_threshold = abs(m_maxpivot) * threshold();\n      Index result = 0;\n      for(Index i = 0; i < m_nonzero_pivots; ++i)\n        result += (abs(m_lu.coeff(i,i)) > premultiplied_threshold);\n      return result;\n    }\n\n    /** \\returns the dimension of the kernel of the matrix of which *this is the LU decomposition.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline Index dimensionOfKernel() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return cols() - rank();\n    }\n\n    /** \\returns true if the matrix of which *this is the LU decomposition represents an injective\n      *          linear map, i.e. has trivial kernel; false otherwise.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline bool isInjective() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return rank() == cols();\n    }\n\n    /** \\returns true if the matrix of which *this is the LU decomposition represents a surjective\n      *          linear map; false otherwise.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline bool isSurjective() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return rank() == rows();\n    }\n\n    /** \\returns true if the matrix of which *this is the LU decomposition is invertible.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline bool isInvertible() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return isInjective() && (m_lu.rows() == m_lu.cols());\n    }\n\n    /** \\returns the inverse of the matrix of which *this is the LU decomposition.\n      *\n      * \\note If this matrix is not invertible, the returned matrix has undefined coefficients.\n      *       Use isInvertible() to first determine whether this matrix is invertible.\n      *\n      * \\sa MatrixBase::inverse()\n      */\n    inline const Inverse<FullPivLU> inverse() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      eigen_assert(m_lu.rows() == m_lu.cols() && \"You can't take the inverse of a non-square matrix!\");\n      return Inverse<FullPivLU>(*this);\n    }\n\n    MatrixType reconstructedMatrix() const;\n\n    EIGEN_DEVICE_FUNC inline Index rows() const { return m_lu.rows(); }\n    EIGEN_DEVICE_FUNC inline Index cols() const { return m_lu.cols(); }\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<typename RhsType, typename DstType>\n    void _solve_impl(const RhsType &rhs, DstType &dst) const;\n\n    template<bool Conjugate, typename RhsType, typename DstType>\n    void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const;\n    #endif\n\n  protected:\n\n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n    }\n\n    void computeInPlace();\n\n    MatrixType m_lu;\n    PermutationPType m_p;\n    PermutationQType m_q;\n    IntColVectorType m_rowsTranspositions;\n    IntRowVectorType m_colsTranspositions;\n    Index m_nonzero_pivots;\n    RealScalar m_l1_norm;\n    RealScalar m_maxpivot, m_prescribedThreshold;\n    signed char m_det_pq;\n    bool m_isInitialized, m_usePrescribedThreshold;\n};\n\ntemplate<typename MatrixType>\nFullPivLU<MatrixType>::FullPivLU()\n  : m_isInitialized(false), m_usePrescribedThreshold(false)\n{\n}\n\ntemplate<typename MatrixType>\nFullPivLU<MatrixType>::FullPivLU(Index rows, Index cols)\n  : m_lu(rows, cols),\n    m_p(rows),\n    m_q(cols),\n    m_rowsTranspositions(rows),\n    m_colsTranspositions(cols),\n    m_isInitialized(false),\n    m_usePrescribedThreshold(false)\n{\n}\n\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nFullPivLU<MatrixType>::FullPivLU(const EigenBase<InputType>& matrix)\n  : m_lu(matrix.rows(), matrix.cols()),\n    m_p(matrix.rows()),\n    m_q(matrix.cols()),\n    m_rowsTranspositions(matrix.rows()),\n    m_colsTranspositions(matrix.cols()),\n    m_isInitialized(false),\n    m_usePrescribedThreshold(false)\n{\n  compute(matrix.derived());\n}\n\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nFullPivLU<MatrixType>::FullPivLU(EigenBase<InputType>& matrix)\n  : m_lu(matrix.derived()),\n    m_p(matrix.rows()),\n    m_q(matrix.cols()),\n    m_rowsTranspositions(matrix.rows()),\n    m_colsTranspositions(matrix.cols()),\n    m_isInitialized(false),\n    m_usePrescribedThreshold(false)\n{\n  computeInPlace();\n}\n\ntemplate<typename MatrixType>\nvoid FullPivLU<MatrixType>::computeInPlace()\n{\n  check_template_parameters();\n\n  // the permutations are stored as int indices, so just to be sure:\n  eigen_assert(m_lu.rows()<=NumTraits<int>::highest() && m_lu.cols()<=NumTraits<int>::highest());\n\n  m_l1_norm = m_lu.cwiseAbs().colwise().sum().maxCoeff();\n\n  const Index size = m_lu.diagonalSize();\n  const Index rows = m_lu.rows();\n  const Index cols = m_lu.cols();\n\n  // will store the transpositions, before we accumulate them at the end.\n  // can't accumulate on-the-fly because that will be done in reverse order for the rows.\n  m_rowsTranspositions.resize(m_lu.rows());\n  m_colsTranspositions.resize(m_lu.cols());\n  Index number_of_transpositions = 0; // number of NONTRIVIAL transpositions, i.e. m_rowsTranspositions[i]!=i\n\n  m_nonzero_pivots = size; // the generic case is that in which all pivots are nonzero (invertible case)\n  m_maxpivot = RealScalar(0);\n\n  for(Index k = 0; k < size; ++k)\n  {\n    // First, we need to find the pivot.\n\n    // biggest coefficient in the remaining bottom-right corner (starting at row k, col k)\n    Index row_of_biggest_in_corner, col_of_biggest_in_corner;\n    typedef internal::scalar_score_coeff_op<Scalar> Scoring;\n    typedef typename Scoring::result_type Score;\n    Score biggest_in_corner;\n    biggest_in_corner = m_lu.bottomRightCorner(rows-k, cols-k)\n                        .unaryExpr(Scoring())\n                        .maxCoeff(&row_of_biggest_in_corner, &col_of_biggest_in_corner);\n    row_of_biggest_in_corner += k; // correct the values! since they were computed in the corner,\n    col_of_biggest_in_corner += k; // need to add k to them.\n\n    if(biggest_in_corner==Score(0))\n    {\n      // before exiting, make sure to initialize the still uninitialized transpositions\n      // in a sane state without destroying what we already have.\n      m_nonzero_pivots = k;\n      for(Index i = k; i < size; ++i)\n      {\n        m_rowsTranspositions.coeffRef(i) = internal::convert_index<StorageIndex>(i);\n        m_colsTranspositions.coeffRef(i) = internal::convert_index<StorageIndex>(i);\n      }\n      break;\n    }\n\n    RealScalar abs_pivot = internal::abs_knowing_score<Scalar>()(m_lu(row_of_biggest_in_corner, col_of_biggest_in_corner), biggest_in_corner);\n    if(abs_pivot > m_maxpivot) m_maxpivot = abs_pivot;\n\n    // Now that we've found the pivot, we need to apply the row/col swaps to\n    // bring it to the location (k,k).\n\n    m_rowsTranspositions.coeffRef(k) = internal::convert_index<StorageIndex>(row_of_biggest_in_corner);\n    m_colsTranspositions.coeffRef(k) = internal::convert_index<StorageIndex>(col_of_biggest_in_corner);\n    if(k != row_of_biggest_in_corner) {\n      m_lu.row(k).swap(m_lu.row(row_of_biggest_in_corner));\n      ++number_of_transpositions;\n    }\n    if(k != col_of_biggest_in_corner) {\n      m_lu.col(k).swap(m_lu.col(col_of_biggest_in_corner));\n      ++number_of_transpositions;\n    }\n\n    // Now that the pivot is at the right location, we update the remaining\n    // bottom-right corner by Gaussian elimination.\n\n    if(k<rows-1)\n      m_lu.col(k).tail(rows-k-1) /= m_lu.coeff(k,k);\n    if(k<size-1)\n      m_lu.block(k+1,k+1,rows-k-1,cols-k-1).noalias() -= m_lu.col(k).tail(rows-k-1) * m_lu.row(k).tail(cols-k-1);\n  }\n\n  // the main loop is over, we still have to accumulate the transpositions to find the\n  // permutations P and Q\n\n  m_p.setIdentity(rows);\n  for(Index k = size-1; k >= 0; --k)\n    m_p.applyTranspositionOnTheRight(k, m_rowsTranspositions.coeff(k));\n\n  m_q.setIdentity(cols);\n  for(Index k = 0; k < size; ++k)\n    m_q.applyTranspositionOnTheRight(k, m_colsTranspositions.coeff(k));\n\n  m_det_pq = (number_of_transpositions%2) ? -1 : 1;\n\n  m_isInitialized = true;\n}\n\ntemplate<typename MatrixType>\ntypename internal::traits<MatrixType>::Scalar FullPivLU<MatrixType>::determinant() const\n{\n  eigen_assert(m_isInitialized && \"LU is not initialized.\");\n  eigen_assert(m_lu.rows() == m_lu.cols() && \"You can't take the determinant of a non-square matrix!\");\n  return Scalar(m_det_pq) * Scalar(m_lu.diagonal().prod());\n}\n\n/** \\returns the matrix represented by the decomposition,\n * i.e., it returns the product: \\f$ P^{-1} L U Q^{-1} \\f$.\n * This function is provided for debug purposes. */\ntemplate<typename MatrixType>\nMatrixType FullPivLU<MatrixType>::reconstructedMatrix() const\n{\n  eigen_assert(m_isInitialized && \"LU is not initialized.\");\n  const Index smalldim = (std::min)(m_lu.rows(), m_lu.cols());\n  // LU\n  MatrixType res(m_lu.rows(),m_lu.cols());\n  // FIXME the .toDenseMatrix() should not be needed...\n  res = m_lu.leftCols(smalldim)\n            .template triangularView<UnitLower>().toDenseMatrix()\n      * m_lu.topRows(smalldim)\n            .template triangularView<Upper>().toDenseMatrix();\n\n  // P^{-1}(LU)\n  res = m_p.inverse() * res;\n\n  // (P^{-1}LU)Q^{-1}\n  res = res * m_q.inverse();\n\n  return res;\n}\n\n/********* Implementation of kernel() **************************************************/\n\nnamespace internal {\ntemplate<typename _MatrixType>\nstruct kernel_retval<FullPivLU<_MatrixType> >\n  : kernel_retval_base<FullPivLU<_MatrixType> >\n{\n  EIGEN_MAKE_KERNEL_HELPERS(FullPivLU<_MatrixType>)\n\n  enum { MaxSmallDimAtCompileTime = EIGEN_SIZE_MIN_PREFER_FIXED(\n            MatrixType::MaxColsAtCompileTime,\n            MatrixType::MaxRowsAtCompileTime)\n  };\n\n  template<typename Dest> void evalTo(Dest& dst) const\n  {\n    using std::abs;\n    const Index cols = dec().matrixLU().cols(), dimker = cols - rank();\n    if(dimker == 0)\n    {\n      // The Kernel is just {0}, so it doesn't have a basis properly speaking, but let's\n      // avoid crashing/asserting as that depends on floating point calculations. Let's\n      // just return a single column vector filled with zeros.\n      dst.setZero();\n      return;\n    }\n\n    /* Let us use the following lemma:\n      *\n      * Lemma: If the matrix A has the LU decomposition PAQ = LU,\n      * then Ker A = Q(Ker U).\n      *\n      * Proof: trivial: just keep in mind that P, Q, L are invertible.\n      */\n\n    /* Thus, all we need to do is to compute Ker U, and then apply Q.\n      *\n      * U is upper triangular, with eigenvalues sorted so that any zeros appear at the end.\n      * Thus, the diagonal of U ends with exactly\n      * dimKer zero's. Let us use that to construct dimKer linearly\n      * independent vectors in Ker U.\n      */\n\n    Matrix<Index, Dynamic, 1, 0, MaxSmallDimAtCompileTime, 1> pivots(rank());\n    RealScalar premultiplied_threshold = dec().maxPivot() * dec().threshold();\n    Index p = 0;\n    for(Index i = 0; i < dec().nonzeroPivots(); ++i)\n      if(abs(dec().matrixLU().coeff(i,i)) > premultiplied_threshold)\n        pivots.coeffRef(p++) = i;\n    eigen_internal_assert(p == rank());\n\n    // we construct a temporaty trapezoid matrix m, by taking the U matrix and\n    // permuting the rows and cols to bring the nonnegligible pivots to the top of\n    // the main diagonal. We need that to be able to apply our triangular solvers.\n    // FIXME when we get triangularView-for-rectangular-matrices, this can be simplified\n    Matrix<typename MatrixType::Scalar, Dynamic, Dynamic, MatrixType::Options,\n           MaxSmallDimAtCompileTime, MatrixType::MaxColsAtCompileTime>\n      m(dec().matrixLU().block(0, 0, rank(), cols));\n    for(Index i = 0; i < rank(); ++i)\n    {\n      if(i) m.row(i).head(i).setZero();\n      m.row(i).tail(cols-i) = dec().matrixLU().row(pivots.coeff(i)).tail(cols-i);\n    }\n    m.block(0, 0, rank(), rank());\n    m.block(0, 0, rank(), rank()).template triangularView<StrictlyLower>().setZero();\n    for(Index i = 0; i < rank(); ++i)\n      m.col(i).swap(m.col(pivots.coeff(i)));\n\n    // ok, we have our trapezoid matrix, we can apply the triangular solver.\n    // notice that the math behind this suggests that we should apply this to the\n    // negative of the RHS, but for performance we just put the negative sign elsewhere, see below.\n    m.topLeftCorner(rank(), rank())\n     .template triangularView<Upper>().solveInPlace(\n        m.topRightCorner(rank(), dimker)\n      );\n\n    // now we must undo the column permutation that we had applied!\n    for(Index i = rank()-1; i >= 0; --i)\n      m.col(i).swap(m.col(pivots.coeff(i)));\n\n    // see the negative sign in the next line, that's what we were talking about above.\n    for(Index i = 0; i < rank(); ++i) dst.row(dec().permutationQ().indices().coeff(i)) = -m.row(i).tail(dimker);\n    for(Index i = rank(); i < cols; ++i) dst.row(dec().permutationQ().indices().coeff(i)).setZero();\n    for(Index k = 0; k < dimker; ++k) dst.coeffRef(dec().permutationQ().indices().coeff(rank()+k), k) = Scalar(1);\n  }\n};\n\n/***** Implementation of image() *****************************************************/\n\ntemplate<typename _MatrixType>\nstruct image_retval<FullPivLU<_MatrixType> >\n  : image_retval_base<FullPivLU<_MatrixType> >\n{\n  EIGEN_MAKE_IMAGE_HELPERS(FullPivLU<_MatrixType>)\n\n  enum { MaxSmallDimAtCompileTime = EIGEN_SIZE_MIN_PREFER_FIXED(\n            MatrixType::MaxColsAtCompileTime,\n            MatrixType::MaxRowsAtCompileTime)\n  };\n\n  template<typename Dest> void evalTo(Dest& dst) const\n  {\n    using std::abs;\n    if(rank() == 0)\n    {\n      // The Image is just {0}, so it doesn't have a basis properly speaking, but let's\n      // avoid crashing/asserting as that depends on floating point calculations. Let's\n      // just return a single column vector filled with zeros.\n      dst.setZero();\n      return;\n    }\n\n    Matrix<Index, Dynamic, 1, 0, MaxSmallDimAtCompileTime, 1> pivots(rank());\n    RealScalar premultiplied_threshold = dec().maxPivot() * dec().threshold();\n    Index p = 0;\n    for(Index i = 0; i < dec().nonzeroPivots(); ++i)\n      if(abs(dec().matrixLU().coeff(i,i)) > premultiplied_threshold)\n        pivots.coeffRef(p++) = i;\n    eigen_internal_assert(p == rank());\n\n    for(Index i = 0; i < rank(); ++i)\n      dst.col(i) = originalMatrix().col(dec().permutationQ().indices().coeff(pivots.coeff(i)));\n  }\n};\n\n/***** Implementation of solve() *****************************************************/\n\n} // end namespace internal\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename _MatrixType>\ntemplate<typename RhsType, typename DstType>\nvoid FullPivLU<_MatrixType>::_solve_impl(const RhsType &rhs, DstType &dst) const\n{\n  /* The decomposition PAQ = LU can be rewritten as A = P^{-1} L U Q^{-1}.\n  * So we proceed as follows:\n  * Step 1: compute c = P * rhs.\n  * Step 2: replace c by the solution x to Lx = c. Exists because L is invertible.\n  * Step 3: replace c by the solution x to Ux = c. May or may not exist.\n  * Step 4: result = Q * c;\n  */\n\n  const Index rows = this->rows(),\n              cols = this->cols(),\n              nonzero_pivots = this->rank();\n  const Index smalldim = (std::min)(rows, cols);\n\n  if(nonzero_pivots == 0)\n  {\n    dst.setZero();\n    return;\n  }\n\n  typename RhsType::PlainObject c(rhs.rows(), rhs.cols());\n\n  // Step 1\n  c = permutationP() * rhs;\n\n  // Step 2\n  m_lu.topLeftCorner(smalldim,smalldim)\n      .template triangularView<UnitLower>()\n      .solveInPlace(c.topRows(smalldim));\n  if(rows>cols)\n    c.bottomRows(rows-cols) -= m_lu.bottomRows(rows-cols) * c.topRows(cols);\n\n  // Step 3\n  m_lu.topLeftCorner(nonzero_pivots, nonzero_pivots)\n      .template triangularView<Upper>()\n      .solveInPlace(c.topRows(nonzero_pivots));\n\n  // Step 4\n  for(Index i = 0; i < nonzero_pivots; ++i)\n    dst.row(permutationQ().indices().coeff(i)) = c.row(i);\n  for(Index i = nonzero_pivots; i < m_lu.cols(); ++i)\n    dst.row(permutationQ().indices().coeff(i)).setZero();\n}\n\ntemplate<typename _MatrixType>\ntemplate<bool Conjugate, typename RhsType, typename DstType>\nvoid FullPivLU<_MatrixType>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const\n{\n  /* The decomposition PAQ = LU can be rewritten as A = P^{-1} L U Q^{-1},\n   * and since permutations are real and unitary, we can write this\n   * as   A^T = Q U^T L^T P,\n   * So we proceed as follows:\n   * Step 1: compute c = Q^T rhs.\n   * Step 2: replace c by the solution x to U^T x = c. May or may not exist.\n   * Step 3: replace c by the solution x to L^T x = c.\n   * Step 4: result = P^T c.\n   * If Conjugate is true, replace \"^T\" by \"^*\" above.\n   */\n\n  const Index rows = this->rows(), cols = this->cols(),\n    nonzero_pivots = this->rank();\n  const Index smalldim = (std::min)(rows, cols);\n\n  if(nonzero_pivots == 0)\n  {\n    dst.setZero();\n    return;\n  }\n\n  typename RhsType::PlainObject c(rhs.rows(), rhs.cols());\n\n  // Step 1\n  c = permutationQ().inverse() * rhs;\n\n  // Step 2\n  m_lu.topLeftCorner(nonzero_pivots, nonzero_pivots)\n      .template triangularView<Upper>()\n      .transpose()\n      .template conjugateIf<Conjugate>()\n      .solveInPlace(c.topRows(nonzero_pivots));\n\n  // Step 3\n  m_lu.topLeftCorner(smalldim, smalldim)\n      .template triangularView<UnitLower>()\n      .transpose()\n      .template conjugateIf<Conjugate>()\n      .solveInPlace(c.topRows(smalldim));\n\n  // Step 4\n  PermutationPType invp = permutationP().inverse().eval();\n  for(Index i = 0; i < smalldim; ++i)\n    dst.row(invp.indices().coeff(i)) = c.row(i);\n  for(Index i = smalldim; i < rows; ++i)\n    dst.row(invp.indices().coeff(i)).setZero();\n}\n\n#endif\n\nnamespace internal {\n\n\n/***** Implementation of inverse() *****************************************************/\ntemplate<typename DstXprType, typename MatrixType>\nstruct Assignment<DstXprType, Inverse<FullPivLU<MatrixType> >, internal::assign_op<typename DstXprType::Scalar,typename FullPivLU<MatrixType>::Scalar>, Dense2Dense>\n{\n  typedef FullPivLU<MatrixType> LuType;\n  typedef Inverse<LuType> SrcXprType;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename MatrixType::Scalar> &)\n  {\n    dst = src.nestedExpression().solve(MatrixType::Identity(src.rows(), src.cols()));\n  }\n};\n} // end namespace internal\n\n/******* MatrixBase methods *****************************************************************/\n\n/** \\lu_module\n  *\n  * \\return the full-pivoting LU decomposition of \\c *this.\n  *\n  * \\sa class FullPivLU\n  */\ntemplate<typename Derived>\ninline const FullPivLU<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::fullPivLu() const\n{\n  return FullPivLU<PlainObject>(eval());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_LU_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/LU/InverseImpl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_INVERSE_IMPL_H\n#define EIGEN_INVERSE_IMPL_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/**********************************\n*** General case implementation ***\n**********************************/\n\ntemplate<typename MatrixType, typename ResultType, int Size = MatrixType::RowsAtCompileTime>\nstruct compute_inverse\n{\n  EIGEN_DEVICE_FUNC\n  static inline void run(const MatrixType& matrix, ResultType& result)\n  {\n    result = matrix.partialPivLu().inverse();\n  }\n};\n\ntemplate<typename MatrixType, typename ResultType, int Size = MatrixType::RowsAtCompileTime>\nstruct compute_inverse_and_det_with_check { /* nothing! general case not supported. */ };\n\n/****************************\n*** Size 1 implementation ***\n****************************/\n\ntemplate<typename MatrixType, typename ResultType>\nstruct compute_inverse<MatrixType, ResultType, 1>\n{\n  EIGEN_DEVICE_FUNC\n  static inline void run(const MatrixType& matrix, ResultType& result)\n  {\n    typedef typename MatrixType::Scalar Scalar;\n    internal::evaluator<MatrixType> matrixEval(matrix);\n    result.coeffRef(0,0) = Scalar(1) / matrixEval.coeff(0,0);\n  }\n};\n\ntemplate<typename MatrixType, typename ResultType>\nstruct compute_inverse_and_det_with_check<MatrixType, ResultType, 1>\n{\n  EIGEN_DEVICE_FUNC\n  static inline void run(\n    const MatrixType& matrix,\n    const typename MatrixType::RealScalar& absDeterminantThreshold,\n    ResultType& result,\n    typename ResultType::Scalar& determinant,\n    bool& invertible\n  )\n  {\n    using std::abs;\n    determinant = matrix.coeff(0,0);\n    invertible = abs(determinant) > absDeterminantThreshold;\n    if(invertible) result.coeffRef(0,0) = typename ResultType::Scalar(1) / determinant;\n  }\n};\n\n/****************************\n*** Size 2 implementation ***\n****************************/\n\ntemplate<typename MatrixType, typename ResultType>\nEIGEN_DEVICE_FUNC \ninline void compute_inverse_size2_helper(\n    const MatrixType& matrix, const typename ResultType::Scalar& invdet,\n    ResultType& result)\n{\n  result.coeffRef(0,0) =  matrix.coeff(1,1) * invdet;\n  result.coeffRef(1,0) = -matrix.coeff(1,0) * invdet;\n  result.coeffRef(0,1) = -matrix.coeff(0,1) * invdet;\n  result.coeffRef(1,1) =  matrix.coeff(0,0) * invdet;\n}\n\ntemplate<typename MatrixType, typename ResultType>\nstruct compute_inverse<MatrixType, ResultType, 2>\n{\n  EIGEN_DEVICE_FUNC\n  static inline void run(const MatrixType& matrix, ResultType& result)\n  {\n    typedef typename ResultType::Scalar Scalar;\n    const Scalar invdet = typename MatrixType::Scalar(1) / matrix.determinant();\n    compute_inverse_size2_helper(matrix, invdet, result);\n  }\n};\n\ntemplate<typename MatrixType, typename ResultType>\nstruct compute_inverse_and_det_with_check<MatrixType, ResultType, 2>\n{\n  EIGEN_DEVICE_FUNC\n  static inline void run(\n    const MatrixType& matrix,\n    const typename MatrixType::RealScalar& absDeterminantThreshold,\n    ResultType& inverse,\n    typename ResultType::Scalar& determinant,\n    bool& invertible\n  )\n  {\n    using std::abs;\n    typedef typename ResultType::Scalar Scalar;\n    determinant = matrix.determinant();\n    invertible = abs(determinant) > absDeterminantThreshold;\n    if(!invertible) return;\n    const Scalar invdet = Scalar(1) / determinant;\n    compute_inverse_size2_helper(matrix, invdet, inverse);\n  }\n};\n\n/****************************\n*** Size 3 implementation ***\n****************************/\n\ntemplate<typename MatrixType, int i, int j>\nEIGEN_DEVICE_FUNC \ninline typename MatrixType::Scalar cofactor_3x3(const MatrixType& m)\n{\n  enum {\n    i1 = (i+1) % 3,\n    i2 = (i+2) % 3,\n    j1 = (j+1) % 3,\n    j2 = (j+2) % 3\n  };\n  return m.coeff(i1, j1) * m.coeff(i2, j2)\n       - m.coeff(i1, j2) * m.coeff(i2, j1);\n}\n\ntemplate<typename MatrixType, typename ResultType>\nEIGEN_DEVICE_FUNC\ninline void compute_inverse_size3_helper(\n    const MatrixType& matrix,\n    const typename ResultType::Scalar& invdet,\n    const Matrix<typename ResultType::Scalar,3,1>& cofactors_col0,\n    ResultType& result)\n{\n  result.row(0) = cofactors_col0 * invdet;\n  result.coeffRef(1,0) =  cofactor_3x3<MatrixType,0,1>(matrix) * invdet;\n  result.coeffRef(1,1) =  cofactor_3x3<MatrixType,1,1>(matrix) * invdet;\n  result.coeffRef(1,2) =  cofactor_3x3<MatrixType,2,1>(matrix) * invdet;\n  result.coeffRef(2,0) =  cofactor_3x3<MatrixType,0,2>(matrix) * invdet;\n  result.coeffRef(2,1) =  cofactor_3x3<MatrixType,1,2>(matrix) * invdet;\n  result.coeffRef(2,2) =  cofactor_3x3<MatrixType,2,2>(matrix) * invdet;\n}\n\ntemplate<typename MatrixType, typename ResultType>\nstruct compute_inverse<MatrixType, ResultType, 3>\n{\n  EIGEN_DEVICE_FUNC\n  static inline void run(const MatrixType& matrix, ResultType& result)\n  {\n    typedef typename ResultType::Scalar Scalar;\n    Matrix<typename MatrixType::Scalar,3,1> cofactors_col0;\n    cofactors_col0.coeffRef(0) =  cofactor_3x3<MatrixType,0,0>(matrix);\n    cofactors_col0.coeffRef(1) =  cofactor_3x3<MatrixType,1,0>(matrix);\n    cofactors_col0.coeffRef(2) =  cofactor_3x3<MatrixType,2,0>(matrix);\n    const Scalar det = (cofactors_col0.cwiseProduct(matrix.col(0))).sum();\n    const Scalar invdet = Scalar(1) / det;\n    compute_inverse_size3_helper(matrix, invdet, cofactors_col0, result);\n  }\n};\n\ntemplate<typename MatrixType, typename ResultType>\nstruct compute_inverse_and_det_with_check<MatrixType, ResultType, 3>\n{\n  EIGEN_DEVICE_FUNC\n  static inline void run(\n    const MatrixType& matrix,\n    const typename MatrixType::RealScalar& absDeterminantThreshold,\n    ResultType& inverse,\n    typename ResultType::Scalar& determinant,\n    bool& invertible\n  )\n  {\n    using std::abs;\n    typedef typename ResultType::Scalar Scalar;\n    Matrix<Scalar,3,1> cofactors_col0;\n    cofactors_col0.coeffRef(0) =  cofactor_3x3<MatrixType,0,0>(matrix);\n    cofactors_col0.coeffRef(1) =  cofactor_3x3<MatrixType,1,0>(matrix);\n    cofactors_col0.coeffRef(2) =  cofactor_3x3<MatrixType,2,0>(matrix);\n    determinant = (cofactors_col0.cwiseProduct(matrix.col(0))).sum();\n    invertible = abs(determinant) > absDeterminantThreshold;\n    if(!invertible) return;\n    const Scalar invdet = Scalar(1) / determinant;\n    compute_inverse_size3_helper(matrix, invdet, cofactors_col0, inverse);\n  }\n};\n\n/****************************\n*** Size 4 implementation ***\n****************************/\n\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC \ninline const typename Derived::Scalar general_det3_helper\n(const MatrixBase<Derived>& matrix, int i1, int i2, int i3, int j1, int j2, int j3)\n{\n  return matrix.coeff(i1,j1)\n         * (matrix.coeff(i2,j2) * matrix.coeff(i3,j3) - matrix.coeff(i2,j3) * matrix.coeff(i3,j2));\n}\n\ntemplate<typename MatrixType, int i, int j>\nEIGEN_DEVICE_FUNC \ninline typename MatrixType::Scalar cofactor_4x4(const MatrixType& matrix)\n{\n  enum {\n    i1 = (i+1) % 4,\n    i2 = (i+2) % 4,\n    i3 = (i+3) % 4,\n    j1 = (j+1) % 4,\n    j2 = (j+2) % 4,\n    j3 = (j+3) % 4\n  };\n  return general_det3_helper(matrix, i1, i2, i3, j1, j2, j3)\n       + general_det3_helper(matrix, i2, i3, i1, j1, j2, j3)\n       + general_det3_helper(matrix, i3, i1, i2, j1, j2, j3);\n}\n\ntemplate<int Arch, typename Scalar, typename MatrixType, typename ResultType>\nstruct compute_inverse_size4\n{\n  EIGEN_DEVICE_FUNC\n  static void run(const MatrixType& matrix, ResultType& result)\n  {\n    result.coeffRef(0,0) =  cofactor_4x4<MatrixType,0,0>(matrix);\n    result.coeffRef(1,0) = -cofactor_4x4<MatrixType,0,1>(matrix);\n    result.coeffRef(2,0) =  cofactor_4x4<MatrixType,0,2>(matrix);\n    result.coeffRef(3,0) = -cofactor_4x4<MatrixType,0,3>(matrix);\n    result.coeffRef(0,2) =  cofactor_4x4<MatrixType,2,0>(matrix);\n    result.coeffRef(1,2) = -cofactor_4x4<MatrixType,2,1>(matrix);\n    result.coeffRef(2,2) =  cofactor_4x4<MatrixType,2,2>(matrix);\n    result.coeffRef(3,2) = -cofactor_4x4<MatrixType,2,3>(matrix);\n    result.coeffRef(0,1) = -cofactor_4x4<MatrixType,1,0>(matrix);\n    result.coeffRef(1,1) =  cofactor_4x4<MatrixType,1,1>(matrix);\n    result.coeffRef(2,1) = -cofactor_4x4<MatrixType,1,2>(matrix);\n    result.coeffRef(3,1) =  cofactor_4x4<MatrixType,1,3>(matrix);\n    result.coeffRef(0,3) = -cofactor_4x4<MatrixType,3,0>(matrix);\n    result.coeffRef(1,3) =  cofactor_4x4<MatrixType,3,1>(matrix);\n    result.coeffRef(2,3) = -cofactor_4x4<MatrixType,3,2>(matrix);\n    result.coeffRef(3,3) =  cofactor_4x4<MatrixType,3,3>(matrix);\n    result /= (matrix.col(0).cwiseProduct(result.row(0).transpose())).sum();\n  }\n};\n\ntemplate<typename MatrixType, typename ResultType>\nstruct compute_inverse<MatrixType, ResultType, 4>\n : compute_inverse_size4<Architecture::Target, typename MatrixType::Scalar,\n                            MatrixType, ResultType>\n{\n};\n\ntemplate<typename MatrixType, typename ResultType>\nstruct compute_inverse_and_det_with_check<MatrixType, ResultType, 4>\n{\n  EIGEN_DEVICE_FUNC\n  static inline void run(\n    const MatrixType& matrix,\n    const typename MatrixType::RealScalar& absDeterminantThreshold,\n    ResultType& inverse,\n    typename ResultType::Scalar& determinant,\n    bool& invertible\n  )\n  {\n    using std::abs;\n    determinant = matrix.determinant();\n    invertible = abs(determinant) > absDeterminantThreshold;\n    if(invertible) compute_inverse<MatrixType, ResultType>::run(matrix, inverse);\n  }\n};\n\n/*************************\n*** MatrixBase methods ***\n*************************/\n\n} // end namespace internal\n\nnamespace internal {\n\n// Specialization for \"dense = dense_xpr.inverse()\"\ntemplate<typename DstXprType, typename XprType>\nstruct Assignment<DstXprType, Inverse<XprType>, internal::assign_op<typename DstXprType::Scalar,typename XprType::Scalar>, Dense2Dense>\n{\n  typedef Inverse<XprType> SrcXprType;\n  EIGEN_DEVICE_FUNC\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename XprType::Scalar> &)\n  {\n    Index dstRows = src.rows();\n    Index dstCols = src.cols();\n    if((dst.rows()!=dstRows) || (dst.cols()!=dstCols))\n      dst.resize(dstRows, dstCols);\n    \n    const int Size = EIGEN_PLAIN_ENUM_MIN(XprType::ColsAtCompileTime,DstXprType::ColsAtCompileTime);\n    EIGEN_ONLY_USED_FOR_DEBUG(Size);\n    eigen_assert(( (Size<=1) || (Size>4) || (extract_data(src.nestedExpression())!=extract_data(dst)))\n              && \"Aliasing problem detected in inverse(), you need to do inverse().eval() here.\");\n\n    typedef typename internal::nested_eval<XprType,XprType::ColsAtCompileTime>::type  ActualXprType;\n    typedef typename internal::remove_all<ActualXprType>::type                        ActualXprTypeCleanded;\n    \n    ActualXprType actual_xpr(src.nestedExpression());\n    \n    compute_inverse<ActualXprTypeCleanded, DstXprType>::run(actual_xpr, dst);\n  }\n};\n\n  \n} // end namespace internal\n\n/** \\lu_module\n  *\n  * \\returns the matrix inverse of this matrix.\n  *\n  * For small fixed sizes up to 4x4, this method uses cofactors.\n  * In the general case, this method uses class PartialPivLU.\n  *\n  * \\note This matrix must be invertible, otherwise the result is undefined. If you need an\n  * invertibility check, do the following:\n  * \\li for fixed sizes up to 4x4, use computeInverseAndDetWithCheck().\n  * \\li for the general case, use class FullPivLU.\n  *\n  * Example: \\include MatrixBase_inverse.cpp\n  * Output: \\verbinclude MatrixBase_inverse.out\n  *\n  * \\sa computeInverseAndDetWithCheck()\n  */\ntemplate<typename Derived>\nEIGEN_DEVICE_FUNC\ninline const Inverse<Derived> MatrixBase<Derived>::inverse() const\n{\n  EIGEN_STATIC_ASSERT(!NumTraits<Scalar>::IsInteger,THIS_FUNCTION_IS_NOT_FOR_INTEGER_NUMERIC_TYPES)\n  eigen_assert(rows() == cols());\n  return Inverse<Derived>(derived());\n}\n\n/** \\lu_module\n  *\n  * Computation of matrix inverse and determinant, with invertibility check.\n  *\n  * This is only for fixed-size square matrices of size up to 4x4.\n  *\n  * \\param inverse Reference to the matrix in which to store the inverse.\n  * \\param determinant Reference to the variable in which to store the determinant.\n  * \\param invertible Reference to the bool variable in which to store whether the matrix is invertible.\n  * \\param absDeterminantThreshold Optional parameter controlling the invertibility check.\n  *                                The matrix will be declared invertible if the absolute value of its\n  *                                determinant is greater than this threshold.\n  *\n  * Example: \\include MatrixBase_computeInverseAndDetWithCheck.cpp\n  * Output: \\verbinclude MatrixBase_computeInverseAndDetWithCheck.out\n  *\n  * \\sa inverse(), computeInverseWithCheck()\n  */\ntemplate<typename Derived>\ntemplate<typename ResultType>\ninline void MatrixBase<Derived>::computeInverseAndDetWithCheck(\n    ResultType& inverse,\n    typename ResultType::Scalar& determinant,\n    bool& invertible,\n    const RealScalar& absDeterminantThreshold\n  ) const\n{\n  // i'd love to put some static assertions there, but SFINAE means that they have no effect...\n  eigen_assert(rows() == cols());\n  // for 2x2, it's worth giving a chance to avoid evaluating.\n  // for larger sizes, evaluating has negligible cost and limits code size.\n  typedef typename internal::conditional<\n    RowsAtCompileTime == 2,\n    typename internal::remove_all<typename internal::nested_eval<Derived, 2>::type>::type,\n    PlainObject\n  >::type MatrixType;\n  internal::compute_inverse_and_det_with_check<MatrixType, ResultType>::run\n    (derived(), absDeterminantThreshold, inverse, determinant, invertible);\n}\n\n/** \\lu_module\n  *\n  * Computation of matrix inverse, with invertibility check.\n  *\n  * This is only for fixed-size square matrices of size up to 4x4.\n  *\n  * \\param inverse Reference to the matrix in which to store the inverse.\n  * \\param invertible Reference to the bool variable in which to store whether the matrix is invertible.\n  * \\param absDeterminantThreshold Optional parameter controlling the invertibility check.\n  *                                The matrix will be declared invertible if the absolute value of its\n  *                                determinant is greater than this threshold.\n  *\n  * Example: \\include MatrixBase_computeInverseWithCheck.cpp\n  * Output: \\verbinclude MatrixBase_computeInverseWithCheck.out\n  *\n  * \\sa inverse(), computeInverseAndDetWithCheck()\n  */\ntemplate<typename Derived>\ntemplate<typename ResultType>\ninline void MatrixBase<Derived>::computeInverseWithCheck(\n    ResultType& inverse,\n    bool& invertible,\n    const RealScalar& absDeterminantThreshold\n  ) const\n{\n  Scalar determinant;\n  // i'd love to put some static assertions there, but SFINAE means that they have no effect...\n  eigen_assert(rows() == cols());\n  computeInverseAndDetWithCheck(inverse,determinant,invertible,absDeterminantThreshold);\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_INVERSE_IMPL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/LU/PartialPivLU.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_PARTIALLU_H\n#define EIGEN_PARTIALLU_H\n\nnamespace Eigen {\n\nnamespace internal {\ntemplate<typename _MatrixType> struct traits<PartialPivLU<_MatrixType> >\n : traits<_MatrixType>\n{\n  typedef MatrixXpr XprKind;\n  typedef SolverStorage StorageKind;\n  typedef int StorageIndex;\n  typedef traits<_MatrixType> BaseTraits;\n  enum {\n    Flags = BaseTraits::Flags & RowMajorBit,\n    CoeffReadCost = Dynamic\n  };\n};\n\ntemplate<typename T,typename Derived>\nstruct enable_if_ref;\n// {\n//   typedef Derived type;\n// };\n\ntemplate<typename T,typename Derived>\nstruct enable_if_ref<Ref<T>,Derived> {\n  typedef Derived type;\n};\n\n} // end namespace internal\n\n/** \\ingroup LU_Module\n  *\n  * \\class PartialPivLU\n  *\n  * \\brief LU decomposition of a matrix with partial pivoting, and related features\n  *\n  * \\tparam _MatrixType the type of the matrix of which we are computing the LU decomposition\n  *\n  * This class represents a LU decomposition of a \\b square \\b invertible matrix, with partial pivoting: the matrix A\n  * is decomposed as A = PLU where L is unit-lower-triangular, U is upper-triangular, and P\n  * is a permutation matrix.\n  *\n  * Typically, partial pivoting LU decomposition is only considered numerically stable for square invertible\n  * matrices. Thus LAPACK's dgesv and dgesvx require the matrix to be square and invertible. The present class\n  * does the same. It will assert that the matrix is square, but it won't (actually it can't) check that the\n  * matrix is invertible: it is your task to check that you only use this decomposition on invertible matrices.\n  *\n  * The guaranteed safe alternative, working for all matrices, is the full pivoting LU decomposition, provided\n  * by class FullPivLU.\n  *\n  * This is \\b not a rank-revealing LU decomposition. Many features are intentionally absent from this class,\n  * such as rank computation. If you need these features, use class FullPivLU.\n  *\n  * This LU decomposition is suitable to invert invertible matrices. It is what MatrixBase::inverse() uses\n  * in the general case.\n  * On the other hand, it is \\b not suitable to determine whether a given matrix is invertible.\n  *\n  * The data of the LU decomposition can be directly accessed through the methods matrixLU(), permutationP().\n  *\n  * This class supports the \\link InplaceDecomposition inplace decomposition \\endlink mechanism.\n  * \n  * \\sa MatrixBase::partialPivLu(), MatrixBase::determinant(), MatrixBase::inverse(), MatrixBase::computeInverse(), class FullPivLU\n  */\ntemplate<typename _MatrixType> class PartialPivLU\n  : public SolverBase<PartialPivLU<_MatrixType> >\n{\n  public:\n\n    typedef _MatrixType MatrixType;\n    typedef SolverBase<PartialPivLU> Base;\n    friend class SolverBase<PartialPivLU>;\n\n    EIGEN_GENERIC_PUBLIC_INTERFACE(PartialPivLU)\n    enum {\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n    typedef PermutationMatrix<RowsAtCompileTime, MaxRowsAtCompileTime> PermutationType;\n    typedef Transpositions<RowsAtCompileTime, MaxRowsAtCompileTime> TranspositionType;\n    typedef typename MatrixType::PlainObject PlainObject;\n\n    /**\n      * \\brief Default Constructor.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via PartialPivLU::compute(const MatrixType&).\n      */\n    PartialPivLU();\n\n    /** \\brief Default Constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem \\a size.\n      * \\sa PartialPivLU()\n      */\n    explicit PartialPivLU(Index size);\n\n    /** Constructor.\n      *\n      * \\param matrix the matrix of which to compute the LU decomposition.\n      *\n      * \\warning The matrix should have full rank (e.g. if it's square, it should be invertible).\n      * If you need to deal with non-full rank, use class FullPivLU instead.\n      */\n    template<typename InputType>\n    explicit PartialPivLU(const EigenBase<InputType>& matrix);\n\n    /** Constructor for \\link InplaceDecomposition inplace decomposition \\endlink\n      *\n      * \\param matrix the matrix of which to compute the LU decomposition.\n      *\n      * \\warning The matrix should have full rank (e.g. if it's square, it should be invertible).\n      * If you need to deal with non-full rank, use class FullPivLU instead.\n      */\n    template<typename InputType>\n    explicit PartialPivLU(EigenBase<InputType>& matrix);\n\n    template<typename InputType>\n    PartialPivLU& compute(const EigenBase<InputType>& matrix) {\n      m_lu = matrix.derived();\n      compute();\n      return *this;\n    }\n\n    /** \\returns the LU decomposition matrix: the upper-triangular part is U, the\n      * unit-lower-triangular part is L (at least for square matrices; in the non-square\n      * case, special care is needed, see the documentation of class FullPivLU).\n      *\n      * \\sa matrixL(), matrixU()\n      */\n    inline const MatrixType& matrixLU() const\n    {\n      eigen_assert(m_isInitialized && \"PartialPivLU is not initialized.\");\n      return m_lu;\n    }\n\n    /** \\returns the permutation matrix P.\n      */\n    inline const PermutationType& permutationP() const\n    {\n      eigen_assert(m_isInitialized && \"PartialPivLU is not initialized.\");\n      return m_p;\n    }\n\n    #ifdef EIGEN_PARSED_BY_DOXYGEN\n    /** This method returns the solution x to the equation Ax=b, where A is the matrix of which\n      * *this is the LU decomposition.\n      *\n      * \\param b the right-hand-side of the equation to solve. Can be a vector or a matrix,\n      *          the only requirement in order for the equation to make sense is that\n      *          b.rows()==A.rows(), where A is the matrix of which *this is the LU decomposition.\n      *\n      * \\returns the solution.\n      *\n      * Example: \\include PartialPivLU_solve.cpp\n      * Output: \\verbinclude PartialPivLU_solve.out\n      *\n      * Since this PartialPivLU class assumes anyway that the matrix A is invertible, the solution\n      * theoretically exists and is unique regardless of b.\n      *\n      * \\sa TriangularView::solve(), inverse(), computeInverse()\n      */\n    template<typename Rhs>\n    inline const Solve<PartialPivLU, Rhs>\n    solve(const MatrixBase<Rhs>& b) const;\n    #endif\n\n    /** \\returns an estimate of the reciprocal condition number of the matrix of which \\c *this is\n        the LU decomposition.\n      */\n    inline RealScalar rcond() const\n    {\n      eigen_assert(m_isInitialized && \"PartialPivLU is not initialized.\");\n      return internal::rcond_estimate_helper(m_l1_norm, *this);\n    }\n\n    /** \\returns the inverse of the matrix of which *this is the LU decomposition.\n      *\n      * \\warning The matrix being decomposed here is assumed to be invertible. If you need to check for\n      *          invertibility, use class FullPivLU instead.\n      *\n      * \\sa MatrixBase::inverse(), LU::inverse()\n      */\n    inline const Inverse<PartialPivLU> inverse() const\n    {\n      eigen_assert(m_isInitialized && \"PartialPivLU is not initialized.\");\n      return Inverse<PartialPivLU>(*this);\n    }\n\n    /** \\returns the determinant of the matrix of which\n      * *this is the LU decomposition. It has only linear complexity\n      * (that is, O(n) where n is the dimension of the square matrix)\n      * as the LU decomposition has already been computed.\n      *\n      * \\note For fixed-size matrices of size up to 4, MatrixBase::determinant() offers\n      *       optimized paths.\n      *\n      * \\warning a determinant can be very big or small, so for matrices\n      * of large enough dimension, there is a risk of overflow/underflow.\n      *\n      * \\sa MatrixBase::determinant()\n      */\n    Scalar determinant() const;\n\n    MatrixType reconstructedMatrix() const;\n\n    inline Index rows() const { return m_lu.rows(); }\n    inline Index cols() const { return m_lu.cols(); }\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<typename RhsType, typename DstType>\n    EIGEN_DEVICE_FUNC\n    void _solve_impl(const RhsType &rhs, DstType &dst) const {\n     /* The decomposition PA = LU can be rewritten as A = P^{-1} L U.\n      * So we proceed as follows:\n      * Step 1: compute c = Pb.\n      * Step 2: replace c by the solution x to Lx = c.\n      * Step 3: replace c by the solution x to Ux = c.\n      */\n\n      // Step 1\n      dst = permutationP() * rhs;\n\n      // Step 2\n      m_lu.template triangularView<UnitLower>().solveInPlace(dst);\n\n      // Step 3\n      m_lu.template triangularView<Upper>().solveInPlace(dst);\n    }\n\n    template<bool Conjugate, typename RhsType, typename DstType>\n    EIGEN_DEVICE_FUNC\n    void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const {\n     /* The decomposition PA = LU can be rewritten as A^T = U^T L^T P.\n      * So we proceed as follows:\n      * Step 1: compute c as the solution to L^T c = b\n      * Step 2: replace c by the solution x to U^T x = c.\n      * Step 3: update  c = P^-1 c.\n      */\n\n      eigen_assert(rhs.rows() == m_lu.cols());\n\n      // Step 1\n      dst = m_lu.template triangularView<Upper>().transpose()\n                .template conjugateIf<Conjugate>().solve(rhs);\n      // Step 2\n      m_lu.template triangularView<UnitLower>().transpose()\n          .template conjugateIf<Conjugate>().solveInPlace(dst);\n      // Step 3\n      dst = permutationP().transpose() * dst;\n    }\n    #endif\n\n  protected:\n\n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n    }\n\n    void compute();\n\n    MatrixType m_lu;\n    PermutationType m_p;\n    TranspositionType m_rowsTranspositions;\n    RealScalar m_l1_norm;\n    signed char m_det_p;\n    bool m_isInitialized;\n};\n\ntemplate<typename MatrixType>\nPartialPivLU<MatrixType>::PartialPivLU()\n  : m_lu(),\n    m_p(),\n    m_rowsTranspositions(),\n    m_l1_norm(0),\n    m_det_p(0),\n    m_isInitialized(false)\n{\n}\n\ntemplate<typename MatrixType>\nPartialPivLU<MatrixType>::PartialPivLU(Index size)\n  : m_lu(size, size),\n    m_p(size),\n    m_rowsTranspositions(size),\n    m_l1_norm(0),\n    m_det_p(0),\n    m_isInitialized(false)\n{\n}\n\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nPartialPivLU<MatrixType>::PartialPivLU(const EigenBase<InputType>& matrix)\n  : m_lu(matrix.rows(),matrix.cols()),\n    m_p(matrix.rows()),\n    m_rowsTranspositions(matrix.rows()),\n    m_l1_norm(0),\n    m_det_p(0),\n    m_isInitialized(false)\n{\n  compute(matrix.derived());\n}\n\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nPartialPivLU<MatrixType>::PartialPivLU(EigenBase<InputType>& matrix)\n  : m_lu(matrix.derived()),\n    m_p(matrix.rows()),\n    m_rowsTranspositions(matrix.rows()),\n    m_l1_norm(0),\n    m_det_p(0),\n    m_isInitialized(false)\n{\n  compute();\n}\n\nnamespace internal {\n\n/** \\internal This is the blocked version of fullpivlu_unblocked() */\ntemplate<typename Scalar, int StorageOrder, typename PivIndex, int SizeAtCompileTime=Dynamic>\nstruct partial_lu_impl\n{\n  static const int UnBlockedBound = 16;\n  static const bool UnBlockedAtCompileTime = SizeAtCompileTime!=Dynamic && SizeAtCompileTime<=UnBlockedBound;\n  static const int ActualSizeAtCompileTime = UnBlockedAtCompileTime ? SizeAtCompileTime : Dynamic;\n  // Remaining rows and columns at compile-time:\n  static const int RRows = SizeAtCompileTime==2 ? 1 : Dynamic;\n  static const int RCols = SizeAtCompileTime==2 ? 1 : Dynamic;\n  typedef Matrix<Scalar, ActualSizeAtCompileTime, ActualSizeAtCompileTime, StorageOrder> MatrixType;\n  typedef Ref<MatrixType> MatrixTypeRef;\n  typedef Ref<Matrix<Scalar, Dynamic, Dynamic, StorageOrder> > BlockType;\n  typedef typename MatrixType::RealScalar RealScalar;\n\n  /** \\internal performs the LU decomposition in-place of the matrix \\a lu\n    * using an unblocked algorithm.\n    *\n    * In addition, this function returns the row transpositions in the\n    * vector \\a row_transpositions which must have a size equal to the number\n    * of columns of the matrix \\a lu, and an integer \\a nb_transpositions\n    * which returns the actual number of transpositions.\n    *\n    * \\returns The index of the first pivot which is exactly zero if any, or a negative number otherwise.\n    */\n  static Index unblocked_lu(MatrixTypeRef& lu, PivIndex* row_transpositions, PivIndex& nb_transpositions)\n  {\n    typedef scalar_score_coeff_op<Scalar> Scoring;\n    typedef typename Scoring::result_type Score;\n    const Index rows = lu.rows();\n    const Index cols = lu.cols();\n    const Index size = (std::min)(rows,cols);\n    // For small compile-time matrices it is worth processing the last row separately:\n    //  speedup: +100% for 2x2, +10% for others.\n    const Index endk = UnBlockedAtCompileTime ? size-1 : size;\n    nb_transpositions = 0;\n    Index first_zero_pivot = -1;\n    for(Index k = 0; k < endk; ++k)\n    {\n      int rrows = internal::convert_index<int>(rows-k-1);\n      int rcols = internal::convert_index<int>(cols-k-1);\n\n      Index row_of_biggest_in_col;\n      Score biggest_in_corner\n        = lu.col(k).tail(rows-k).unaryExpr(Scoring()).maxCoeff(&row_of_biggest_in_col);\n      row_of_biggest_in_col += k;\n\n      row_transpositions[k] = PivIndex(row_of_biggest_in_col);\n\n      if(biggest_in_corner != Score(0))\n      {\n        if(k != row_of_biggest_in_col)\n        {\n          lu.row(k).swap(lu.row(row_of_biggest_in_col));\n          ++nb_transpositions;\n        }\n\n        lu.col(k).tail(fix<RRows>(rrows)) /= lu.coeff(k,k);\n      }\n      else if(first_zero_pivot==-1)\n      {\n        // the pivot is exactly zero, we record the index of the first pivot which is exactly 0,\n        // and continue the factorization such we still have A = PLU\n        first_zero_pivot = k;\n      }\n\n      if(k<rows-1)\n        lu.bottomRightCorner(fix<RRows>(rrows),fix<RCols>(rcols)).noalias() -= lu.col(k).tail(fix<RRows>(rrows)) * lu.row(k).tail(fix<RCols>(rcols));\n    }\n\n    // special handling of the last entry\n    if(UnBlockedAtCompileTime)\n    {\n      Index k = endk;\n      row_transpositions[k] = PivIndex(k);\n      if (Scoring()(lu(k, k)) == Score(0) && first_zero_pivot == -1)\n        first_zero_pivot = k;\n    }\n\n    return first_zero_pivot;\n  }\n\n  /** \\internal performs the LU decomposition in-place of the matrix represented\n    * by the variables \\a rows, \\a cols, \\a lu_data, and \\a lu_stride using a\n    * recursive, blocked algorithm.\n    *\n    * In addition, this function returns the row transpositions in the\n    * vector \\a row_transpositions which must have a size equal to the number\n    * of columns of the matrix \\a lu, and an integer \\a nb_transpositions\n    * which returns the actual number of transpositions.\n    *\n    * \\returns The index of the first pivot which is exactly zero if any, or a negative number otherwise.\n    *\n    * \\note This very low level interface using pointers, etc. is to:\n    *   1 - reduce the number of instantiations to the strict minimum\n    *   2 - avoid infinite recursion of the instantiations with Block<Block<Block<...> > >\n    */\n  static Index blocked_lu(Index rows, Index cols, Scalar* lu_data, Index luStride, PivIndex* row_transpositions, PivIndex& nb_transpositions, Index maxBlockSize=256)\n  {\n    MatrixTypeRef lu = MatrixType::Map(lu_data,rows, cols, OuterStride<>(luStride));\n\n    const Index size = (std::min)(rows,cols);\n\n    // if the matrix is too small, no blocking:\n    if(UnBlockedAtCompileTime || size<=UnBlockedBound)\n    {\n      return unblocked_lu(lu, row_transpositions, nb_transpositions);\n    }\n\n    // automatically adjust the number of subdivisions to the size\n    // of the matrix so that there is enough sub blocks:\n    Index blockSize;\n    {\n      blockSize = size/8;\n      blockSize = (blockSize/16)*16;\n      blockSize = (std::min)((std::max)(blockSize,Index(8)), maxBlockSize);\n    }\n\n    nb_transpositions = 0;\n    Index first_zero_pivot = -1;\n    for(Index k = 0; k < size; k+=blockSize)\n    {\n      Index bs = (std::min)(size-k,blockSize); // actual size of the block\n      Index trows = rows - k - bs; // trailing rows\n      Index tsize = size - k - bs; // trailing size\n\n      // partition the matrix:\n      //                          A00 | A01 | A02\n      // lu  = A_0 | A_1 | A_2 =  A10 | A11 | A12\n      //                          A20 | A21 | A22\n      BlockType A_0 = lu.block(0,0,rows,k);\n      BlockType A_2 = lu.block(0,k+bs,rows,tsize);\n      BlockType A11 = lu.block(k,k,bs,bs);\n      BlockType A12 = lu.block(k,k+bs,bs,tsize);\n      BlockType A21 = lu.block(k+bs,k,trows,bs);\n      BlockType A22 = lu.block(k+bs,k+bs,trows,tsize);\n\n      PivIndex nb_transpositions_in_panel;\n      // recursively call the blocked LU algorithm on [A11^T A21^T]^T\n      // with a very small blocking size:\n      Index ret = blocked_lu(trows+bs, bs, &lu.coeffRef(k,k), luStride,\n                   row_transpositions+k, nb_transpositions_in_panel, 16);\n      if(ret>=0 && first_zero_pivot==-1)\n        first_zero_pivot = k+ret;\n\n      nb_transpositions += nb_transpositions_in_panel;\n      // update permutations and apply them to A_0\n      for(Index i=k; i<k+bs; ++i)\n      {\n        Index piv = (row_transpositions[i] += internal::convert_index<PivIndex>(k));\n        A_0.row(i).swap(A_0.row(piv));\n      }\n\n      if(trows)\n      {\n        // apply permutations to A_2\n        for(Index i=k;i<k+bs; ++i)\n          A_2.row(i).swap(A_2.row(row_transpositions[i]));\n\n        // A12 = A11^-1 A12\n        A11.template triangularView<UnitLower>().solveInPlace(A12);\n\n        A22.noalias() -= A21 * A12;\n      }\n    }\n    return first_zero_pivot;\n  }\n};\n\n/** \\internal performs the LU decomposition with partial pivoting in-place.\n  */\ntemplate<typename MatrixType, typename TranspositionType>\nvoid partial_lu_inplace(MatrixType& lu, TranspositionType& row_transpositions, typename TranspositionType::StorageIndex& nb_transpositions)\n{\n  eigen_assert(lu.cols() == row_transpositions.size());\n  eigen_assert((&row_transpositions.coeffRef(1)-&row_transpositions.coeffRef(0)) == 1);\n\n  partial_lu_impl\n    < typename MatrixType::Scalar, MatrixType::Flags&RowMajorBit?RowMajor:ColMajor,\n      typename TranspositionType::StorageIndex,\n      EIGEN_SIZE_MIN_PREFER_FIXED(MatrixType::RowsAtCompileTime,MatrixType::ColsAtCompileTime)>\n    ::blocked_lu(lu.rows(), lu.cols(), &lu.coeffRef(0,0), lu.outerStride(), &row_transpositions.coeffRef(0), nb_transpositions);\n}\n\n} // end namespace internal\n\ntemplate<typename MatrixType>\nvoid PartialPivLU<MatrixType>::compute()\n{\n  check_template_parameters();\n\n  // the row permutation is stored as int indices, so just to be sure:\n  eigen_assert(m_lu.rows()<NumTraits<int>::highest());\n\n  if(m_lu.cols()>0)\n    m_l1_norm = m_lu.cwiseAbs().colwise().sum().maxCoeff();\n  else\n    m_l1_norm = RealScalar(0);\n\n  eigen_assert(m_lu.rows() == m_lu.cols() && \"PartialPivLU is only for square (and moreover invertible) matrices\");\n  const Index size = m_lu.rows();\n\n  m_rowsTranspositions.resize(size);\n\n  typename TranspositionType::StorageIndex nb_transpositions;\n  internal::partial_lu_inplace(m_lu, m_rowsTranspositions, nb_transpositions);\n  m_det_p = (nb_transpositions%2) ? -1 : 1;\n\n  m_p = m_rowsTranspositions;\n\n  m_isInitialized = true;\n}\n\ntemplate<typename MatrixType>\ntypename PartialPivLU<MatrixType>::Scalar PartialPivLU<MatrixType>::determinant() const\n{\n  eigen_assert(m_isInitialized && \"PartialPivLU is not initialized.\");\n  return Scalar(m_det_p) * m_lu.diagonal().prod();\n}\n\n/** \\returns the matrix represented by the decomposition,\n * i.e., it returns the product: P^{-1} L U.\n * This function is provided for debug purpose. */\ntemplate<typename MatrixType>\nMatrixType PartialPivLU<MatrixType>::reconstructedMatrix() const\n{\n  eigen_assert(m_isInitialized && \"LU is not initialized.\");\n  // LU\n  MatrixType res = m_lu.template triangularView<UnitLower>().toDenseMatrix()\n                 * m_lu.template triangularView<Upper>();\n\n  // P^{-1}(LU)\n  res = m_p.inverse() * res;\n\n  return res;\n}\n\n/***** Implementation details *****************************************************/\n\nnamespace internal {\n\n/***** Implementation of inverse() *****************************************************/\ntemplate<typename DstXprType, typename MatrixType>\nstruct Assignment<DstXprType, Inverse<PartialPivLU<MatrixType> >, internal::assign_op<typename DstXprType::Scalar,typename PartialPivLU<MatrixType>::Scalar>, Dense2Dense>\n{\n  typedef PartialPivLU<MatrixType> LuType;\n  typedef Inverse<LuType> SrcXprType;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename LuType::Scalar> &)\n  {\n    dst = src.nestedExpression().solve(MatrixType::Identity(src.rows(), src.cols()));\n  }\n};\n} // end namespace internal\n\n/******** MatrixBase methods *******/\n\n/** \\lu_module\n  *\n  * \\return the partial-pivoting LU decomposition of \\c *this.\n  *\n  * \\sa class PartialPivLU\n  */\ntemplate<typename Derived>\ninline const PartialPivLU<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::partialPivLu() const\n{\n  return PartialPivLU<PlainObject>(eval());\n}\n\n/** \\lu_module\n  *\n  * Synonym of partialPivLu().\n  *\n  * \\return the partial-pivoting LU decomposition of \\c *this.\n  *\n  * \\sa class PartialPivLU\n  */\ntemplate<typename Derived>\ninline const PartialPivLU<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::lu() const\n{\n  return PartialPivLU<PlainObject>(eval());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_PARTIALLU_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/LU/PartialPivLU_LAPACKE.h",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Eigen bindings to LAPACKe\n *     LU decomposition with partial pivoting based on LAPACKE_?getrf function.\n ********************************************************************************\n*/\n\n#ifndef EIGEN_PARTIALLU_LAPACK_H\n#define EIGEN_PARTIALLU_LAPACK_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\internal Specialization for the data types supported by LAPACKe */\n\n#define EIGEN_LAPACKE_LU_PARTPIV(EIGTYPE, LAPACKE_TYPE, LAPACKE_PREFIX) \\\ntemplate<int StorageOrder> \\\nstruct partial_lu_impl<EIGTYPE, StorageOrder, lapack_int> \\\n{ \\\n  /* \\internal performs the LU decomposition in-place of the matrix represented */ \\\n  static lapack_int blocked_lu(Index rows, Index cols, EIGTYPE* lu_data, Index luStride, lapack_int* row_transpositions, lapack_int& nb_transpositions, lapack_int maxBlockSize=256) \\\n  { \\\n    EIGEN_UNUSED_VARIABLE(maxBlockSize);\\\n    lapack_int matrix_order, first_zero_pivot; \\\n    lapack_int m, n, lda, *ipiv, info; \\\n    EIGTYPE* a; \\\n/* Set up parameters for ?getrf */ \\\n    matrix_order = StorageOrder==RowMajor ? LAPACK_ROW_MAJOR : LAPACK_COL_MAJOR; \\\n    lda = convert_index<lapack_int>(luStride); \\\n    a = lu_data; \\\n    ipiv = row_transpositions; \\\n    m = convert_index<lapack_int>(rows); \\\n    n = convert_index<lapack_int>(cols); \\\n    nb_transpositions = 0; \\\n\\\n    info = LAPACKE_##LAPACKE_PREFIX##getrf( matrix_order, m, n, (LAPACKE_TYPE*)a, lda, ipiv ); \\\n\\\n    for(int i=0;i<m;i++) { ipiv[i]--; if (ipiv[i]!=i) nb_transpositions++; } \\\n\\\n    eigen_assert(info >= 0); \\\n/* something should be done with nb_transpositions */ \\\n\\\n    first_zero_pivot = info; \\\n    return first_zero_pivot; \\\n  } \\\n};\n\nEIGEN_LAPACKE_LU_PARTPIV(double, double, d)\nEIGEN_LAPACKE_LU_PARTPIV(float, float, s)\nEIGEN_LAPACKE_LU_PARTPIV(dcomplex, lapack_complex_double, z)\nEIGEN_LAPACKE_LU_PARTPIV(scomplex, lapack_complex_float,  c)\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_PARTIALLU_LAPACK_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/LU/arch/InverseSize4.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2001 Intel Corporation\n// Copyright (C) 2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n//\n// The algorithm below is a reimplementation of former \\src\\LU\\Inverse_SSE.h using PacketMath.\n// inv(M) = M#/|M|, where inv(M), M# and |M| denote the inverse of M,\n// adjugate of M and determinant of M respectively. M# is computed block-wise\n// using specific formulae. For proof, see:\n// https://lxjk.github.io/2017/09/03/Fast-4x4-Matrix-Inverse-with-SSE-SIMD-Explained.html\n// Variable names are adopted from \\src\\LU\\Inverse_SSE.h.\n//\n// The SSE code for the 4x4 float and double matrix inverse in former (deprecated) \\src\\LU\\Inverse_SSE.h\n// comes from the following Intel's library:\n// http://software.intel.com/en-us/articles/optimized-matrix-library-for-use-with-the-intel-pentiumr-4-processors-sse2-instructions/\n//\n// Here is the respective copyright and license statement:\n//\n//   Copyright (c) 2001 Intel Corporation.\n//\n// Permition is granted to use, copy, distribute and prepare derivative works\n// of this library for any purpose and without fee, provided, that the above\n// copyright notice and this statement appear in all copies.\n// Intel makes no representations about the suitability of this software for\n// any purpose, and specifically disclaims all warranties.\n// See LEGAL.TXT for all the legal information.\n//\n// TODO: Unify implementations of different data types (i.e. float and double).\n#ifndef EIGEN_INVERSE_SIZE_4_H\n#define EIGEN_INVERSE_SIZE_4_H\n\nnamespace Eigen\n{\nnamespace internal\n{\ntemplate <typename MatrixType, typename ResultType>\nstruct compute_inverse_size4<Architecture::Target, float, MatrixType, ResultType>\n{\n  enum\n  {\n    MatrixAlignment = traits<MatrixType>::Alignment,\n    ResultAlignment = traits<ResultType>::Alignment,\n    StorageOrdersMatch = (MatrixType::Flags & RowMajorBit) == (ResultType::Flags & RowMajorBit)\n  };\n  typedef typename conditional<(MatrixType::Flags & LinearAccessBit), MatrixType const &, typename MatrixType::PlainObject>::type ActualMatrixType;\n\n  static void run(const MatrixType &mat, ResultType &result)\n  {\n    ActualMatrixType matrix(mat);\n\n    Packet4f _L1 = matrix.template packet<MatrixAlignment>(0);\n    Packet4f _L2 = matrix.template packet<MatrixAlignment>(4);\n    Packet4f _L3 = matrix.template packet<MatrixAlignment>(8);\n    Packet4f _L4 = matrix.template packet<MatrixAlignment>(12);\n\n    // Four 2x2 sub-matrices of the input matrix\n    // input = [[A, B],\n    //          [C, D]]\n    Packet4f A, B, C, D;\n\n    if (!StorageOrdersMatch)\n    {\n      A = vec4f_unpacklo(_L1, _L2);\n      B = vec4f_unpacklo(_L3, _L4);\n      C = vec4f_unpackhi(_L1, _L2);\n      D = vec4f_unpackhi(_L3, _L4);\n    }\n    else\n    {\n      A = vec4f_movelh(_L1, _L2);\n      B = vec4f_movehl(_L2, _L1);\n      C = vec4f_movelh(_L3, _L4);\n      D = vec4f_movehl(_L4, _L3);\n    }\n\n    Packet4f AB, DC;\n\n    // AB = A# * B, where A# denotes the adjugate of A, and * denotes matrix product.\n    AB = pmul(vec4f_swizzle2(A, A, 3, 3, 0, 0), B);\n    AB = psub(AB, pmul(vec4f_swizzle2(A, A, 1, 1, 2, 2), vec4f_swizzle2(B, B, 2, 3, 0, 1)));\n\n    // DC = D#*C\n    DC = pmul(vec4f_swizzle2(D, D, 3, 3, 0, 0), C);\n    DC = psub(DC, pmul(vec4f_swizzle2(D, D, 1, 1, 2, 2), vec4f_swizzle2(C, C, 2, 3, 0, 1)));\n\n    // determinants of the sub-matrices\n    Packet4f dA, dB, dC, dD;\n\n    dA = pmul(vec4f_swizzle2(A, A, 3, 3, 1, 1), A);\n    dA = psub(dA, vec4f_movehl(dA, dA));\n\n    dB = pmul(vec4f_swizzle2(B, B, 3, 3, 1, 1), B);\n    dB = psub(dB, vec4f_movehl(dB, dB));\n\n    dC = pmul(vec4f_swizzle2(C, C, 3, 3, 1, 1), C);\n    dC = psub(dC, vec4f_movehl(dC, dC));\n\n    dD = pmul(vec4f_swizzle2(D, D, 3, 3, 1, 1), D);\n    dD = psub(dD, vec4f_movehl(dD, dD));\n\n    Packet4f d, d1, d2;\n\n    d = pmul(vec4f_swizzle2(DC, DC, 0, 2, 1, 3), AB);\n    d = padd(d, vec4f_movehl(d, d));\n    d = padd(d, vec4f_swizzle2(d, d, 1, 0, 0, 0));\n    d1 = pmul(dA, dD);\n    d2 = pmul(dB, dC);\n\n    // determinant of the input matrix, det = |A||D| + |B||C| - trace(A#*B*D#*C)\n    Packet4f det = vec4f_duplane(psub(padd(d1, d2), d), 0);\n\n    // reciprocal of the determinant of the input matrix, rd = 1/det\n    Packet4f rd = pdiv(pset1<Packet4f>(1.0f), det);\n\n    // Four sub-matrices of the inverse\n    Packet4f iA, iB, iC, iD;\n\n    // iD = D*|A| - C*A#*B\n    iD = pmul(vec4f_swizzle2(C, C, 0, 0, 2, 2), vec4f_movelh(AB, AB));\n    iD = padd(iD, pmul(vec4f_swizzle2(C, C, 1, 1, 3, 3), vec4f_movehl(AB, AB)));\n    iD = psub(pmul(D, vec4f_duplane(dA, 0)), iD);\n\n    // iA = A*|D| - B*D#*C\n    iA = pmul(vec4f_swizzle2(B, B, 0, 0, 2, 2), vec4f_movelh(DC, DC));\n    iA = padd(iA, pmul(vec4f_swizzle2(B, B, 1, 1, 3, 3), vec4f_movehl(DC, DC)));\n    iA = psub(pmul(A, vec4f_duplane(dD, 0)), iA);\n\n    // iB = C*|B| - D * (A#B)# = C*|B| - D*B#*A\n    iB = pmul(D, vec4f_swizzle2(AB, AB, 3, 0, 3, 0));\n    iB = psub(iB, pmul(vec4f_swizzle2(D, D, 1, 0, 3, 2), vec4f_swizzle2(AB, AB, 2, 1, 2, 1)));\n    iB = psub(pmul(C, vec4f_duplane(dB, 0)), iB);\n\n    // iC = B*|C| - A * (D#C)# = B*|C| - A*C#*D\n    iC = pmul(A, vec4f_swizzle2(DC, DC, 3, 0, 3, 0));\n    iC = psub(iC, pmul(vec4f_swizzle2(A, A, 1, 0, 3, 2), vec4f_swizzle2(DC, DC, 2, 1, 2, 1)));\n    iC = psub(pmul(B, vec4f_duplane(dC, 0)), iC);\n\n    const int bits[4] = {0, -2147483648, -2147483648, 0};\n    const Packet4f p4f_sign_PNNP = preinterpret<Packet4f, Packet4i>(pgather<int, Packet4i>(bits, static_cast<Eigen::Index>(1)));\n    rd = pxor(rd, p4f_sign_PNNP);\n    iA = pmul(iA, rd);\n    iB = pmul(iB, rd);\n    iC = pmul(iC, rd);\n    iD = pmul(iD, rd);\n\n    Index res_stride = result.outerStride();\n    float *res = result.data();\n\n    pstoret<float, Packet4f, ResultAlignment>(res + 0, vec4f_swizzle2(iA, iB, 3, 1, 3, 1));\n    pstoret<float, Packet4f, ResultAlignment>(res + res_stride, vec4f_swizzle2(iA, iB, 2, 0, 2, 0));\n    pstoret<float, Packet4f, ResultAlignment>(res + 2 * res_stride, vec4f_swizzle2(iC, iD, 3, 1, 3, 1));\n    pstoret<float, Packet4f, ResultAlignment>(res + 3 * res_stride, vec4f_swizzle2(iC, iD, 2, 0, 2, 0));\n  }\n};\n\n#if !(defined EIGEN_VECTORIZE_NEON && !(EIGEN_ARCH_ARM64 && !EIGEN_APPLE_DOUBLE_NEON_BUG))\n// same algorithm as above, except that each operand is split into\n// halves for two registers to hold.\ntemplate <typename MatrixType, typename ResultType>\nstruct compute_inverse_size4<Architecture::Target, double, MatrixType, ResultType>\n{\n  enum\n  {\n    MatrixAlignment = traits<MatrixType>::Alignment,\n    ResultAlignment = traits<ResultType>::Alignment,\n    StorageOrdersMatch = (MatrixType::Flags & RowMajorBit) == (ResultType::Flags & RowMajorBit)\n  };\n  typedef typename conditional<(MatrixType::Flags & LinearAccessBit),\n                               MatrixType const &,\n                               typename MatrixType::PlainObject>::type\n      ActualMatrixType;\n\n  static void run(const MatrixType &mat, ResultType &result)\n  {\n    ActualMatrixType matrix(mat);\n\n    // Four 2x2 sub-matrices of the input matrix, each is further divided into upper and lower\n    // row e.g. A1, upper row of A, A2, lower row of A\n    // input = [[A, B],  =  [[[A1, [B1,\n    //          [C, D]]        A2], B2]],\n    //                       [[C1, [D1,\n    //                         C2], D2]]]\n\n    Packet2d A1, A2, B1, B2, C1, C2, D1, D2;\n\n    if (StorageOrdersMatch)\n    {\n      A1 = matrix.template packet<MatrixAlignment>(0);\n      B1 = matrix.template packet<MatrixAlignment>(2);\n      A2 = matrix.template packet<MatrixAlignment>(4);\n      B2 = matrix.template packet<MatrixAlignment>(6);\n      C1 = matrix.template packet<MatrixAlignment>(8);\n      D1 = matrix.template packet<MatrixAlignment>(10);\n      C2 = matrix.template packet<MatrixAlignment>(12);\n      D2 = matrix.template packet<MatrixAlignment>(14);\n    }\n    else\n    {\n      Packet2d temp;\n      A1 = matrix.template packet<MatrixAlignment>(0);\n      C1 = matrix.template packet<MatrixAlignment>(2);\n      A2 = matrix.template packet<MatrixAlignment>(4);\n      C2 = matrix.template packet<MatrixAlignment>(6);\n\n      temp = A1;\n      A1 = vec2d_unpacklo(A1, A2);\n      A2 = vec2d_unpackhi(temp, A2);\n\n      temp = C1;\n      C1 = vec2d_unpacklo(C1, C2);\n      C2 = vec2d_unpackhi(temp, C2);\n\n      B1 = matrix.template packet<MatrixAlignment>(8);\n      D1 = matrix.template packet<MatrixAlignment>(10);\n      B2 = matrix.template packet<MatrixAlignment>(12);\n      D2 = matrix.template packet<MatrixAlignment>(14);\n\n      temp = B1;\n      B1 = vec2d_unpacklo(B1, B2);\n      B2 = vec2d_unpackhi(temp, B2);\n\n      temp = D1;\n      D1 = vec2d_unpacklo(D1, D2);\n      D2 = vec2d_unpackhi(temp, D2);\n    }\n\n    // determinants of the sub-matrices\n    Packet2d dA, dB, dC, dD;\n\n    dA = vec2d_swizzle2(A2, A2, 1);\n    dA = pmul(A1, dA);\n    dA = psub(dA, vec2d_duplane(dA, 1));\n\n    dB = vec2d_swizzle2(B2, B2, 1);\n    dB = pmul(B1, dB);\n    dB = psub(dB, vec2d_duplane(dB, 1));\n\n    dC = vec2d_swizzle2(C2, C2, 1);\n    dC = pmul(C1, dC);\n    dC = psub(dC, vec2d_duplane(dC, 1));\n\n    dD = vec2d_swizzle2(D2, D2, 1);\n    dD = pmul(D1, dD);\n    dD = psub(dD, vec2d_duplane(dD, 1));\n\n    Packet2d DC1, DC2, AB1, AB2;\n\n    // AB = A# * B, where A# denotes the adjugate of A, and * denotes matrix product.\n    AB1 = pmul(B1, vec2d_duplane(A2, 1));\n    AB2 = pmul(B2, vec2d_duplane(A1, 0));\n    AB1 = psub(AB1, pmul(B2, vec2d_duplane(A1, 1)));\n    AB2 = psub(AB2, pmul(B1, vec2d_duplane(A2, 0)));\n\n    // DC = D#*C\n    DC1 = pmul(C1, vec2d_duplane(D2, 1));\n    DC2 = pmul(C2, vec2d_duplane(D1, 0));\n    DC1 = psub(DC1, pmul(C2, vec2d_duplane(D1, 1)));\n    DC2 = psub(DC2, pmul(C1, vec2d_duplane(D2, 0)));\n\n    Packet2d d1, d2;\n\n    // determinant of the input matrix, det = |A||D| + |B||C| - trace(A#*B*D#*C)\n    Packet2d det;\n\n    // reciprocal of the determinant of the input matrix, rd = 1/det\n    Packet2d rd;\n\n    d1 = pmul(AB1, vec2d_swizzle2(DC1, DC2, 0));\n    d2 = pmul(AB2, vec2d_swizzle2(DC1, DC2, 3));\n    rd = padd(d1, d2);\n    rd = padd(rd, vec2d_duplane(rd, 1));\n\n    d1 = pmul(dA, dD);\n    d2 = pmul(dB, dC);\n\n    det = padd(d1, d2);\n    det = psub(det, rd);\n    det = vec2d_duplane(det, 0);\n    rd = pdiv(pset1<Packet2d>(1.0), det);\n\n    // rows of four sub-matrices of the inverse\n    Packet2d iA1, iA2, iB1, iB2, iC1, iC2, iD1, iD2;\n\n    // iD = D*|A| - C*A#*B\n    iD1 = pmul(AB1, vec2d_duplane(C1, 0));\n    iD2 = pmul(AB1, vec2d_duplane(C2, 0));\n    iD1 = padd(iD1, pmul(AB2, vec2d_duplane(C1, 1)));\n    iD2 = padd(iD2, pmul(AB2, vec2d_duplane(C2, 1)));\n    dA = vec2d_duplane(dA, 0);\n    iD1 = psub(pmul(D1, dA), iD1);\n    iD2 = psub(pmul(D2, dA), iD2);\n\n    // iA = A*|D| - B*D#*C\n    iA1 = pmul(DC1, vec2d_duplane(B1, 0));\n    iA2 = pmul(DC1, vec2d_duplane(B2, 0));\n    iA1 = padd(iA1, pmul(DC2, vec2d_duplane(B1, 1)));\n    iA2 = padd(iA2, pmul(DC2, vec2d_duplane(B2, 1)));\n    dD = vec2d_duplane(dD, 0);\n    iA1 = psub(pmul(A1, dD), iA1);\n    iA2 = psub(pmul(A2, dD), iA2);\n\n    // iB = C*|B| - D * (A#B)# = C*|B| - D*B#*A\n    iB1 = pmul(D1, vec2d_swizzle2(AB2, AB1, 1));\n    iB2 = pmul(D2, vec2d_swizzle2(AB2, AB1, 1));\n    iB1 = psub(iB1, pmul(vec2d_swizzle2(D1, D1, 1), vec2d_swizzle2(AB2, AB1, 2)));\n    iB2 = psub(iB2, pmul(vec2d_swizzle2(D2, D2, 1), vec2d_swizzle2(AB2, AB1, 2)));\n    dB = vec2d_duplane(dB, 0);\n    iB1 = psub(pmul(C1, dB), iB1);\n    iB2 = psub(pmul(C2, dB), iB2);\n\n    // iC = B*|C| - A * (D#C)# = B*|C| - A*C#*D\n    iC1 = pmul(A1, vec2d_swizzle2(DC2, DC1, 1));\n    iC2 = pmul(A2, vec2d_swizzle2(DC2, DC1, 1));\n    iC1 = psub(iC1, pmul(vec2d_swizzle2(A1, A1, 1), vec2d_swizzle2(DC2, DC1, 2)));\n    iC2 = psub(iC2, pmul(vec2d_swizzle2(A2, A2, 1), vec2d_swizzle2(DC2, DC1, 2)));\n    dC = vec2d_duplane(dC, 0);\n    iC1 = psub(pmul(B1, dC), iC1);\n    iC2 = psub(pmul(B2, dC), iC2);\n\n    const int bits1[4] = {0, -2147483648, 0, 0};\n    const int bits2[4] = {0, 0, 0, -2147483648};\n    const Packet2d _Sign_NP = preinterpret<Packet2d, Packet4i>(pgather<int, Packet4i>(bits1, static_cast<Eigen::Index>(1)));\n    const Packet2d _Sign_PN = preinterpret<Packet2d, Packet4i>(pgather<int, Packet4i>(bits2, static_cast<Eigen::Index>(1)));\n    d1 = pxor(rd, _Sign_PN);\n    d2 = pxor(rd, _Sign_NP);\n\n    Index res_stride = result.outerStride();\n    double *res = result.data();\n    pstoret<double, Packet2d, ResultAlignment>(res + 0, pmul(vec2d_swizzle2(iA2, iA1, 3), d1));\n    pstoret<double, Packet2d, ResultAlignment>(res + res_stride, pmul(vec2d_swizzle2(iA2, iA1, 0), d2));\n    pstoret<double, Packet2d, ResultAlignment>(res + 2, pmul(vec2d_swizzle2(iB2, iB1, 3), d1));\n    pstoret<double, Packet2d, ResultAlignment>(res + res_stride + 2, pmul(vec2d_swizzle2(iB2, iB1, 0), d2));\n    pstoret<double, Packet2d, ResultAlignment>(res + 2 * res_stride, pmul(vec2d_swizzle2(iC2, iC1, 3), d1));\n    pstoret<double, Packet2d, ResultAlignment>(res + 3 * res_stride, pmul(vec2d_swizzle2(iC2, iC1, 0), d2));\n    pstoret<double, Packet2d, ResultAlignment>(res + 2 * res_stride + 2, pmul(vec2d_swizzle2(iD2, iD1, 3), d1));\n    pstoret<double, Packet2d, ResultAlignment>(res + 3 * res_stride + 2, pmul(vec2d_swizzle2(iD2, iD1, 0), d2));\n  }\n};\n#endif\n} // namespace internal\n} // namespace Eigen\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/MetisSupport/MetisSupport.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n#ifndef METIS_SUPPORT_H\n#define METIS_SUPPORT_H\n\nnamespace Eigen {\n/**\n * Get the fill-reducing ordering from the METIS package\n * \n * If A is the original matrix and Ap is the permuted matrix, \n * the fill-reducing permutation is defined as follows :\n * Row (column) i of A is the matperm(i) row (column) of Ap. \n * WARNING: As computed by METIS, this corresponds to the vector iperm (instead of perm)\n */\ntemplate <typename StorageIndex>\nclass MetisOrdering\n{\npublic:\n  typedef PermutationMatrix<Dynamic,Dynamic,StorageIndex> PermutationType;\n  typedef Matrix<StorageIndex,Dynamic,1> IndexVector; \n  \n  template <typename MatrixType>\n  void get_symmetrized_graph(const MatrixType& A)\n  {\n    Index m = A.cols(); \n    eigen_assert((A.rows() == A.cols()) && \"ONLY FOR SQUARED MATRICES\");\n    // Get the transpose of the input matrix \n    MatrixType At = A.transpose(); \n    // Get the number of nonzeros elements in each row/col of At+A\n    Index TotNz = 0; \n    IndexVector visited(m); \n    visited.setConstant(-1); \n    for (StorageIndex j = 0; j < m; j++)\n    {\n      // Compute the union structure of of A(j,:) and At(j,:)\n      visited(j) = j; // Do not include the diagonal element\n      // Get the nonzeros in row/column j of A\n      for (typename MatrixType::InnerIterator it(A, j); it; ++it)\n      {\n        Index idx = it.index(); // Get the row index (for column major) or column index (for row major)\n        if (visited(idx) != j ) \n        {\n          visited(idx) = j; \n          ++TotNz; \n        }\n      }\n      //Get the nonzeros in row/column j of At\n      for (typename MatrixType::InnerIterator it(At, j); it; ++it)\n      {\n        Index idx = it.index(); \n        if(visited(idx) != j)\n        {\n          visited(idx) = j; \n          ++TotNz; \n        }\n      }\n    }\n    // Reserve place for A + At\n    m_indexPtr.resize(m+1);\n    m_innerIndices.resize(TotNz); \n\n    // Now compute the real adjacency list of each column/row \n    visited.setConstant(-1); \n    StorageIndex CurNz = 0; \n    for (StorageIndex j = 0; j < m; j++)\n    {\n      m_indexPtr(j) = CurNz; \n      \n      visited(j) = j; // Do not include the diagonal element\n      // Add the pattern of row/column j of A to A+At\n      for (typename MatrixType::InnerIterator it(A,j); it; ++it)\n      {\n        StorageIndex idx = it.index(); // Get the row index (for column major) or column index (for row major)\n        if (visited(idx) != j ) \n        {\n          visited(idx) = j; \n          m_innerIndices(CurNz) = idx; \n          CurNz++; \n        }\n      }\n      //Add the pattern of row/column j of At to A+At\n      for (typename MatrixType::InnerIterator it(At, j); it; ++it)\n      {\n        StorageIndex idx = it.index(); \n        if(visited(idx) != j)\n        {\n          visited(idx) = j; \n          m_innerIndices(CurNz) = idx; \n          ++CurNz; \n        }\n      }\n    }\n    m_indexPtr(m) = CurNz;    \n  }\n  \n  template <typename MatrixType>\n  void operator() (const MatrixType& A, PermutationType& matperm)\n  {\n     StorageIndex m = internal::convert_index<StorageIndex>(A.cols()); // must be StorageIndex, because it is passed by address to METIS\n     IndexVector perm(m),iperm(m); \n    // First, symmetrize the matrix graph. \n     get_symmetrized_graph(A); \n     int output_error;\n     \n     // Call the fill-reducing routine from METIS \n     output_error = METIS_NodeND(&m, m_indexPtr.data(), m_innerIndices.data(), NULL, NULL, perm.data(), iperm.data());\n     \n    if(output_error != METIS_OK) \n    {\n      //FIXME The ordering interface should define a class of possible errors \n     std::cerr << \"ERROR WHILE CALLING THE METIS PACKAGE \\n\"; \n     return; \n    }\n    \n    // Get the fill-reducing permutation \n    //NOTE:  If Ap is the permuted matrix then perm and iperm vectors are defined as follows \n    // Row (column) i of Ap is the perm(i) row(column) of A, and row (column) i of A is the iperm(i) row(column) of Ap\n    \n     matperm.resize(m);\n     for (int j = 0; j < m; j++)\n       matperm.indices()(iperm(j)) = j;\n   \n  }\n  \n  protected:\n    IndexVector m_indexPtr; // Pointer to the adjacenccy list of each row/column\n    IndexVector m_innerIndices; // Adjacency list \n};\n\n}// end namespace eigen \n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/OrderingMethods/Amd.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/*\nNOTE: this routine has been adapted from the CSparse library:\n\nCopyright (c) 2006, Timothy A. Davis.\nhttp://www.suitesparse.com\n\nThe author of CSparse, Timothy A. Davis., has executed a license with Google LLC\nto permit distribution of this code and derivative works as part of Eigen under\nthe Mozilla Public License v. 2.0, as stated at the top of this file.\n*/\n\n#ifndef EIGEN_SPARSE_AMD_H\n#define EIGEN_SPARSE_AMD_H\n\nnamespace Eigen { \n\nnamespace internal {\n  \ntemplate<typename T> inline T amd_flip(const T& i) { return -i-2; }\ntemplate<typename T> inline T amd_unflip(const T& i) { return i<0 ? amd_flip(i) : i; }\ntemplate<typename T0, typename T1> inline bool amd_marked(const T0* w, const T1& j) { return w[j]<0; }\ntemplate<typename T0, typename T1> inline void amd_mark(const T0* w, const T1& j) { return w[j] = amd_flip(w[j]); }\n\n/* clear w */\ntemplate<typename StorageIndex>\nstatic StorageIndex cs_wclear (StorageIndex mark, StorageIndex lemax, StorageIndex *w, StorageIndex n)\n{\n  StorageIndex k;\n  if(mark < 2 || (mark + lemax < 0))\n  {\n    for(k = 0; k < n; k++)\n      if(w[k] != 0)\n        w[k] = 1;\n    mark = 2;\n  }\n  return (mark);     /* at this point, w[0..n-1] < mark holds */\n}\n\n/* depth-first search and postorder of a tree rooted at node j */\ntemplate<typename StorageIndex>\nStorageIndex cs_tdfs(StorageIndex j, StorageIndex k, StorageIndex *head, const StorageIndex *next, StorageIndex *post, StorageIndex *stack)\n{\n  StorageIndex i, p, top = 0;\n  if(!head || !next || !post || !stack) return (-1);    /* check inputs */\n  stack[0] = j;                 /* place j on the stack */\n  while (top >= 0)                /* while (stack is not empty) */\n  {\n    p = stack[top];           /* p = top of stack */\n    i = head[p];              /* i = youngest child of p */\n    if(i == -1)\n    {\n      top--;                 /* p has no unordered children left */\n      post[k++] = p;        /* node p is the kth postordered node */\n    }\n    else\n    {\n      head[p] = next[i];   /* remove i from children of p */\n      stack[++top] = i;     /* start dfs on child node i */\n    }\n  }\n  return k;\n}\n\n\n/** \\internal\n  * \\ingroup OrderingMethods_Module \n  * Approximate minimum degree ordering algorithm.\n  *\n  * \\param[in] C the input selfadjoint matrix stored in compressed column major format.\n  * \\param[out] perm the permutation P reducing the fill-in of the input matrix \\a C\n  *\n  * Note that the input matrix \\a C must be complete, that is both the upper and lower parts have to be stored, as well as the diagonal entries.\n  * On exit the values of C are destroyed */\ntemplate<typename Scalar, typename StorageIndex>\nvoid minimum_degree_ordering(SparseMatrix<Scalar,ColMajor,StorageIndex>& C, PermutationMatrix<Dynamic,Dynamic,StorageIndex>& perm)\n{\n  using std::sqrt;\n  \n  StorageIndex d, dk, dext, lemax = 0, e, elenk, eln, i, j, k, k1,\n                k2, k3, jlast, ln, dense, nzmax, mindeg = 0, nvi, nvj, nvk, mark, wnvi,\n                ok, nel = 0, p, p1, p2, p3, p4, pj, pk, pk1, pk2, pn, q, t, h;\n  \n  StorageIndex n = StorageIndex(C.cols());\n  dense = std::max<StorageIndex> (16, StorageIndex(10 * sqrt(double(n))));   /* find dense threshold */\n  dense = (std::min)(n-2, dense);\n  \n  StorageIndex cnz = StorageIndex(C.nonZeros());\n  perm.resize(n+1);\n  t = cnz + cnz/5 + 2*n;                 /* add elbow room to C */\n  C.resizeNonZeros(t);\n  \n  // get workspace\n  ei_declare_aligned_stack_constructed_variable(StorageIndex,W,8*(n+1),0);\n  StorageIndex* len     = W;\n  StorageIndex* nv      = W +   (n+1);\n  StorageIndex* next    = W + 2*(n+1);\n  StorageIndex* head    = W + 3*(n+1);\n  StorageIndex* elen    = W + 4*(n+1);\n  StorageIndex* degree  = W + 5*(n+1);\n  StorageIndex* w       = W + 6*(n+1);\n  StorageIndex* hhead   = W + 7*(n+1);\n  StorageIndex* last    = perm.indices().data();                              /* use P as workspace for last */\n  \n  /* --- Initialize quotient graph ---------------------------------------- */\n  StorageIndex* Cp = C.outerIndexPtr();\n  StorageIndex* Ci = C.innerIndexPtr();\n  for(k = 0; k < n; k++)\n    len[k] = Cp[k+1] - Cp[k];\n  len[n] = 0;\n  nzmax = t;\n  \n  for(i = 0; i <= n; i++)\n  {\n    head[i]   = -1;                     // degree list i is empty\n    last[i]   = -1;\n    next[i]   = -1;\n    hhead[i]  = -1;                     // hash list i is empty \n    nv[i]     = 1;                      // node i is just one node\n    w[i]      = 1;                      // node i is alive\n    elen[i]   = 0;                      // Ek of node i is empty\n    degree[i] = len[i];                 // degree of node i\n  }\n  mark = internal::cs_wclear<StorageIndex>(0, 0, w, n);         /* clear w */\n  \n  /* --- Initialize degree lists ------------------------------------------ */\n  for(i = 0; i < n; i++)\n  {\n    bool has_diag = false;\n    for(p = Cp[i]; p<Cp[i+1]; ++p)\n      if(Ci[p]==i)\n      {\n        has_diag = true;\n        break;\n      }\n   \n    d = degree[i];\n    if(d == 1 && has_diag)           /* node i is empty */\n    {\n      elen[i] = -2;                 /* element i is dead */\n      nel++;\n      Cp[i] = -1;                   /* i is a root of assembly tree */\n      w[i] = 0;\n    }\n    else if(d > dense || !has_diag)  /* node i is dense or has no structural diagonal element */\n    {\n      nv[i] = 0;                    /* absorb i into element n */\n      elen[i] = -1;                 /* node i is dead */\n      nel++;\n      Cp[i] = amd_flip (n);\n      nv[n]++;\n    }\n    else\n    {\n      if(head[d] != -1) last[head[d]] = i;\n      next[i] = head[d];           /* put node i in degree list d */\n      head[d] = i;\n    }\n  }\n  \n  elen[n] = -2;                         /* n is a dead element */\n  Cp[n] = -1;                           /* n is a root of assembly tree */\n  w[n] = 0;                             /* n is a dead element */\n  \n  while (nel < n)                         /* while (selecting pivots) do */\n  {\n    /* --- Select node of minimum approximate degree -------------------- */\n    for(k = -1; mindeg < n && (k = head[mindeg]) == -1; mindeg++) {}\n    if(next[k] != -1) last[next[k]] = -1;\n    head[mindeg] = next[k];          /* remove k from degree list */\n    elenk = elen[k];                  /* elenk = |Ek| */\n    nvk = nv[k];                      /* # of nodes k represents */\n    nel += nvk;                        /* nv[k] nodes of A eliminated */\n    \n    /* --- Garbage collection ------------------------------------------- */\n    if(elenk > 0 && cnz + mindeg >= nzmax)\n    {\n      for(j = 0; j < n; j++)\n      {\n        if((p = Cp[j]) >= 0)      /* j is a live node or element */\n        {\n          Cp[j] = Ci[p];          /* save first entry of object */\n          Ci[p] = amd_flip (j);    /* first entry is now amd_flip(j) */\n        }\n      }\n      for(q = 0, p = 0; p < cnz; ) /* scan all of memory */\n      {\n        if((j = amd_flip (Ci[p++])) >= 0)  /* found object j */\n        {\n          Ci[q] = Cp[j];       /* restore first entry of object */\n          Cp[j] = q++;          /* new pointer to object j */\n          for(k3 = 0; k3 < len[j]-1; k3++) Ci[q++] = Ci[p++];\n        }\n      }\n      cnz = q;                       /* Ci[cnz...nzmax-1] now free */\n    }\n    \n    /* --- Construct new element ---------------------------------------- */\n    dk = 0;\n    nv[k] = -nvk;                     /* flag k as in Lk */\n    p = Cp[k];\n    pk1 = (elenk == 0) ? p : cnz;      /* do in place if elen[k] == 0 */\n    pk2 = pk1;\n    for(k1 = 1; k1 <= elenk + 1; k1++)\n    {\n      if(k1 > elenk)\n      {\n        e = k;                     /* search the nodes in k */\n        pj = p;                    /* list of nodes starts at Ci[pj]*/\n        ln = len[k] - elenk;      /* length of list of nodes in k */\n      }\n      else\n      {\n        e = Ci[p++];              /* search the nodes in e */\n        pj = Cp[e];\n        ln = len[e];              /* length of list of nodes in e */\n      }\n      for(k2 = 1; k2 <= ln; k2++)\n      {\n        i = Ci[pj++];\n        if((nvi = nv[i]) <= 0) continue; /* node i dead, or seen */\n        dk += nvi;                 /* degree[Lk] += size of node i */\n        nv[i] = -nvi;             /* negate nv[i] to denote i in Lk*/\n        Ci[pk2++] = i;            /* place i in Lk */\n        if(next[i] != -1) last[next[i]] = last[i];\n        if(last[i] != -1)         /* remove i from degree list */\n        {\n          next[last[i]] = next[i];\n        }\n        else\n        {\n          head[degree[i]] = next[i];\n        }\n      }\n      if(e != k)\n      {\n        Cp[e] = amd_flip (k);      /* absorb e into k */\n        w[e] = 0;                 /* e is now a dead element */\n      }\n    }\n    if(elenk != 0) cnz = pk2;         /* Ci[cnz...nzmax] is free */\n    degree[k] = dk;                   /* external degree of k - |Lk\\i| */\n    Cp[k] = pk1;                      /* element k is in Ci[pk1..pk2-1] */\n    len[k] = pk2 - pk1;\n    elen[k] = -2;                     /* k is now an element */\n    \n    /* --- Find set differences ----------------------------------------- */\n    mark = internal::cs_wclear<StorageIndex>(mark, lemax, w, n);  /* clear w if necessary */\n    for(pk = pk1; pk < pk2; pk++)    /* scan 1: find |Le\\Lk| */\n    {\n      i = Ci[pk];\n      if((eln = elen[i]) <= 0) continue;/* skip if elen[i] empty */\n      nvi = -nv[i];                      /* nv[i] was negated */\n      wnvi = mark - nvi;\n      for(p = Cp[i]; p <= Cp[i] + eln - 1; p++)  /* scan Ei */\n      {\n        e = Ci[p];\n        if(w[e] >= mark)\n        {\n          w[e] -= nvi;          /* decrement |Le\\Lk| */\n        }\n        else if(w[e] != 0)        /* ensure e is a live element */\n        {\n          w[e] = degree[e] + wnvi; /* 1st time e seen in scan 1 */\n        }\n      }\n    }\n    \n    /* --- Degree update ------------------------------------------------ */\n    for(pk = pk1; pk < pk2; pk++)    /* scan2: degree update */\n    {\n      i = Ci[pk];                   /* consider node i in Lk */\n      p1 = Cp[i];\n      p2 = p1 + elen[i] - 1;\n      pn = p1;\n      for(h = 0, d = 0, p = p1; p <= p2; p++)    /* scan Ei */\n      {\n        e = Ci[p];\n        if(w[e] != 0)             /* e is an unabsorbed element */\n        {\n          dext = w[e] - mark;   /* dext = |Le\\Lk| */\n          if(dext > 0)\n          {\n            d += dext;         /* sum up the set differences */\n            Ci[pn++] = e;     /* keep e in Ei */\n            h += e;            /* compute the hash of node i */\n          }\n          else\n          {\n            Cp[e] = amd_flip (k);  /* aggressive absorb. e->k */\n            w[e] = 0;             /* e is a dead element */\n          }\n        }\n      }\n      elen[i] = pn - p1 + 1;        /* elen[i] = |Ei| */\n      p3 = pn;\n      p4 = p1 + len[i];\n      for(p = p2 + 1; p < p4; p++) /* prune edges in Ai */\n      {\n        j = Ci[p];\n        if((nvj = nv[j]) <= 0) continue; /* node j dead or in Lk */\n        d += nvj;                  /* degree(i) += |j| */\n        Ci[pn++] = j;             /* place j in node list of i */\n        h += j;                    /* compute hash for node i */\n      }\n      if(d == 0)                     /* check for mass elimination */\n      {\n        Cp[i] = amd_flip (k);      /* absorb i into k */\n        nvi = -nv[i];\n        dk -= nvi;                 /* |Lk| -= |i| */\n        nvk += nvi;                /* |k| += nv[i] */\n        nel += nvi;\n        nv[i] = 0;\n        elen[i] = -1;             /* node i is dead */\n      }\n      else\n      {\n        degree[i] = std::min<StorageIndex> (degree[i], d);   /* update degree(i) */\n        Ci[pn] = Ci[p3];         /* move first node to end */\n        Ci[p3] = Ci[p1];         /* move 1st el. to end of Ei */\n        Ci[p1] = k;               /* add k as 1st element in of Ei */\n        len[i] = pn - p1 + 1;     /* new len of adj. list of node i */\n        h %= n;                    /* finalize hash of i */\n        next[i] = hhead[h];      /* place i in hash bucket */\n        hhead[h] = i;\n        last[i] = h;      /* save hash of i in last[i] */\n      }\n    }                                   /* scan2 is done */\n    degree[k] = dk;                   /* finalize |Lk| */\n    lemax = std::max<StorageIndex>(lemax, dk);\n    mark = internal::cs_wclear<StorageIndex>(mark+lemax, lemax, w, n);    /* clear w */\n    \n    /* --- Supernode detection ------------------------------------------ */\n    for(pk = pk1; pk < pk2; pk++)\n    {\n      i = Ci[pk];\n      if(nv[i] >= 0) continue;         /* skip if i is dead */\n      h = last[i];                      /* scan hash bucket of node i */\n      i = hhead[h];\n      hhead[h] = -1;                    /* hash bucket will be empty */\n      for(; i != -1 && next[i] != -1; i = next[i], mark++)\n      {\n        ln = len[i];\n        eln = elen[i];\n        for(p = Cp[i]+1; p <= Cp[i] + ln-1; p++) w[Ci[p]] = mark;\n        jlast = i;\n        for(j = next[i]; j != -1; ) /* compare i with all j */\n        {\n          ok = (len[j] == ln) && (elen[j] == eln);\n          for(p = Cp[j] + 1; ok && p <= Cp[j] + ln - 1; p++)\n          {\n            if(w[Ci[p]] != mark) ok = 0;    /* compare i and j*/\n          }\n          if(ok)                     /* i and j are identical */\n          {\n            Cp[j] = amd_flip (i);  /* absorb j into i */\n            nv[i] += nv[j];\n            nv[j] = 0;\n            elen[j] = -1;         /* node j is dead */\n            j = next[j];          /* delete j from hash bucket */\n            next[jlast] = j;\n          }\n          else\n          {\n            jlast = j;             /* j and i are different */\n            j = next[j];\n          }\n        }\n      }\n    }\n    \n    /* --- Finalize new element------------------------------------------ */\n    for(p = pk1, pk = pk1; pk < pk2; pk++)   /* finalize Lk */\n    {\n      i = Ci[pk];\n      if((nvi = -nv[i]) <= 0) continue;/* skip if i is dead */\n      nv[i] = nvi;                      /* restore nv[i] */\n      d = degree[i] + dk - nvi;         /* compute external degree(i) */\n      d = std::min<StorageIndex> (d, n - nel - nvi);\n      if(head[d] != -1) last[head[d]] = i;\n      next[i] = head[d];               /* put i back in degree list */\n      last[i] = -1;\n      head[d] = i;\n      mindeg = std::min<StorageIndex> (mindeg, d);       /* find new minimum degree */\n      degree[i] = d;\n      Ci[p++] = i;                      /* place i in Lk */\n    }\n    nv[k] = nvk;                      /* # nodes absorbed into k */\n    if((len[k] = p-pk1) == 0)         /* length of adj list of element k*/\n    {\n      Cp[k] = -1;                   /* k is a root of the tree */\n      w[k] = 0;                     /* k is now a dead element */\n    }\n    if(elenk != 0) cnz = p;           /* free unused space in Lk */\n  }\n  \n  /* --- Postordering ----------------------------------------------------- */\n  for(i = 0; i < n; i++) Cp[i] = amd_flip (Cp[i]);/* fix assembly tree */\n  for(j = 0; j <= n; j++) head[j] = -1;\n  for(j = n; j >= 0; j--)              /* place unordered nodes in lists */\n  {\n    if(nv[j] > 0) continue;          /* skip if j is an element */\n    next[j] = head[Cp[j]];          /* place j in list of its parent */\n    head[Cp[j]] = j;\n  }\n  for(e = n; e >= 0; e--)              /* place elements in lists */\n  {\n    if(nv[e] <= 0) continue;         /* skip unless e is an element */\n    if(Cp[e] != -1)\n    {\n      next[e] = head[Cp[e]];      /* place e in list of its parent */\n      head[Cp[e]] = e;\n    }\n  }\n  for(k = 0, i = 0; i <= n; i++)       /* postorder the assembly tree */\n  {\n    if(Cp[i] == -1) k = internal::cs_tdfs<StorageIndex>(i, k, head, next, perm.indices().data(), w);\n  }\n  \n  perm.indices().conservativeResize(n);\n}\n\n} // namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_AMD_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/OrderingMethods/Eigen_Colamd.h",
    "content": "// // This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Desire Nuentsa Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// This file is modified from the colamd/symamd library. The copyright is below\n\n//   The authors of the code itself are Stefan I. Larimore and Timothy A.\n//   Davis (davis@cise.ufl.edu), University of Florida.  The algorithm was\n//   developed in collaboration with John Gilbert, Xerox PARC, and Esmond\n//   Ng, Oak Ridge National Laboratory.\n//\n//     Date:\n//\n//   September 8, 2003.  Version 2.3.\n//\n//     Acknowledgements:\n//\n//   This work was supported by the National Science Foundation, under\n//   grants DMS-9504974 and DMS-9803599.\n//\n//     Notice:\n//\n//   Copyright (c) 1998-2003 by the University of Florida.\n//   All Rights Reserved.\n//\n//   THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n//   EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n//\n//   Permission is hereby granted to use, copy, modify, and/or distribute\n//   this program, provided that the Copyright, this License, and the\n//   Availability of the original version is retained on all copies and made\n//   accessible to the end-user of any code or package that includes COLAMD\n//   or any modified version of COLAMD.\n//\n//     Availability:\n//\n//   The colamd/symamd library is available at\n//\n//       http://www.suitesparse.com\n\n\n#ifndef EIGEN_COLAMD_H\n#define EIGEN_COLAMD_H\n\nnamespace internal {\n\nnamespace Colamd {\n\n/* Ensure that debugging is turned off: */\n#ifndef COLAMD_NDEBUG\n#define COLAMD_NDEBUG\n#endif /* NDEBUG */\n\n\n/* ========================================================================== */\n/* === Knob and statistics definitions ====================================== */\n/* ========================================================================== */\n\n/* size of the knobs [ ] array.  Only knobs [0..1] are currently used. */\nconst int NKnobs = 20;\n\n/* number of output statistics.  Only stats [0..6] are currently used. */\nconst int NStats = 20;\n\n/* Indices into knobs and stats array. */\nenum KnobsStatsIndex {\n  /* knobs [0] and stats [0]: dense row knob and output statistic. */\n  DenseRow = 0,\n\n  /* knobs [1] and stats [1]: dense column knob and output statistic. */\n  DenseCol = 1,\n\n  /* stats [2]: memory defragmentation count output statistic */\n  DefragCount = 2,\n\n  /* stats [3]: colamd status:  zero OK, > 0 warning or notice, < 0 error */\n  Status = 3,\n\n  /* stats [4..6]: error info, or info on jumbled columns */\n  Info1 = 4,\n  Info2 = 5,\n  Info3 = 6\n};\n\n/* error codes returned in stats [3]: */\nenum Status {\n  Ok = 0,\n  OkButJumbled = 1,\n  ErrorANotPresent = -1,\n  ErrorPNotPresent = -2,\n  ErrorNrowNegative = -3,\n  ErrorNcolNegative = -4,\n  ErrorNnzNegative = -5,\n  ErrorP0Nonzero = -6,\n  ErrorATooSmall = -7,\n  ErrorColLengthNegative = -8,\n  ErrorRowIndexOutOfBounds = -9,\n  ErrorOutOfMemory = -10,\n  ErrorInternalError = -999\n};\n/* ========================================================================== */\n/* === Definitions ========================================================== */\n/* ========================================================================== */\n\ntemplate <typename IndexType>\nIndexType ones_complement(const IndexType r) {\n  return (-(r)-1);\n}\n\n/* -------------------------------------------------------------------------- */\nconst int Empty = -1;\n\n/* Row and column status */\nenum RowColumnStatus {\n  Alive = 0,\n  Dead = -1\n};\n\n/* Column status */\nenum ColumnStatus {\n  DeadPrincipal = -1,\n  DeadNonPrincipal = -2\n};\n\n/* ========================================================================== */\n/* === Colamd reporting mechanism =========================================== */\n/* ========================================================================== */\n\n// == Row and Column structures ==\ntemplate <typename IndexType>\nstruct ColStructure\n{\n  IndexType start ;   /* index for A of first row in this column, or Dead */\n  /* if column is dead */\n  IndexType length ;  /* number of rows in this column */\n  union\n  {\n    IndexType thickness ; /* number of original columns represented by this */\n    /* col, if the column is alive */\n    IndexType parent ;  /* parent in parent tree super-column structure, if */\n    /* the column is dead */\n  } shared1 ;\n  union\n  {\n    IndexType score ; /* the score used to maintain heap, if col is alive */\n    IndexType order ; /* pivot ordering of this column, if col is dead */\n  } shared2 ;\n  union\n  {\n    IndexType headhash ;  /* head of a hash bucket, if col is at the head of */\n    /* a degree list */\n    IndexType hash ;  /* hash value, if col is not in a degree list */\n    IndexType prev ;  /* previous column in degree list, if col is in a */\n    /* degree list (but not at the head of a degree list) */\n  } shared3 ;\n  union\n  {\n    IndexType degree_next ; /* next column, if col is in a degree list */\n    IndexType hash_next ;   /* next column, if col is in a hash list */\n  } shared4 ;\n\n  inline bool is_dead() const { return start < Alive; }\n\n  inline bool is_alive() const { return start >= Alive; }\n\n  inline bool is_dead_principal() const { return start == DeadPrincipal; }\n\n  inline void kill_principal() { start = DeadPrincipal; }\n\n  inline void kill_non_principal() { start = DeadNonPrincipal; }\n\n};\n\ntemplate <typename IndexType>\nstruct RowStructure\n{\n  IndexType start ;   /* index for A of first col in this row */\n  IndexType length ;  /* number of principal columns in this row */\n  union\n  {\n    IndexType degree ;  /* number of principal & non-principal columns in row */\n    IndexType p ;   /* used as a row pointer in init_rows_cols () */\n  } shared1 ;\n  union\n  {\n    IndexType mark ;  /* for computing set differences and marking dead rows*/\n    IndexType first_column ;/* first column in row (used in garbage collection) */\n  } shared2 ;\n\n  inline bool is_dead() const { return shared2.mark < Alive; }\n\n  inline bool is_alive() const { return shared2.mark >= Alive; }\n\n  inline void kill() { shared2.mark = Dead; }\n\n};\n\n/* ========================================================================== */\n/* === Colamd recommended memory size ======================================= */\n/* ========================================================================== */\n\n/*\n  The recommended length Alen of the array A passed to colamd is given by\n  the COLAMD_RECOMMENDED (nnz, n_row, n_col) macro.  It returns -1 if any\n  argument is negative.  2*nnz space is required for the row and column\n  indices of the matrix. colamd_c (n_col) + colamd_r (n_row) space is\n  required for the Col and Row arrays, respectively, which are internal to\n  colamd.  An additional n_col space is the minimal amount of \"elbow room\",\n  and nnz/5 more space is recommended for run time efficiency.\n\n  This macro is not needed when using symamd.\n\n  Explicit typecast to IndexType added Sept. 23, 2002, COLAMD version 2.2, to avoid\n  gcc -pedantic warning messages.\n*/\ntemplate <typename IndexType>\ninline IndexType colamd_c(IndexType n_col)\n{ return IndexType( ((n_col) + 1) * sizeof (ColStructure<IndexType>) / sizeof (IndexType) ) ; }\n\ntemplate <typename IndexType>\ninline IndexType  colamd_r(IndexType n_row)\n{ return IndexType(((n_row) + 1) * sizeof (RowStructure<IndexType>) / sizeof (IndexType)); }\n\n// Prototypes of non-user callable routines\ntemplate <typename IndexType>\nstatic IndexType init_rows_cols (IndexType n_row, IndexType n_col, RowStructure<IndexType> Row [], ColStructure<IndexType> col [], IndexType A [], IndexType p [], IndexType stats[NStats] );\n\ntemplate <typename IndexType>\nstatic void init_scoring (IndexType n_row, IndexType n_col, RowStructure<IndexType> Row [], ColStructure<IndexType> Col [], IndexType A [], IndexType head [], double knobs[NKnobs], IndexType *p_n_row2, IndexType *p_n_col2, IndexType *p_max_deg);\n\ntemplate <typename IndexType>\nstatic IndexType find_ordering (IndexType n_row, IndexType n_col, IndexType Alen, RowStructure<IndexType> Row [], ColStructure<IndexType> Col [], IndexType A [], IndexType head [], IndexType n_col2, IndexType max_deg, IndexType pfree);\n\ntemplate <typename IndexType>\nstatic void order_children (IndexType n_col, ColStructure<IndexType> Col [], IndexType p []);\n\ntemplate <typename IndexType>\nstatic void detect_super_cols (ColStructure<IndexType> Col [], IndexType A [], IndexType head [], IndexType row_start, IndexType row_length ) ;\n\ntemplate <typename IndexType>\nstatic IndexType garbage_collection (IndexType n_row, IndexType n_col, RowStructure<IndexType> Row [], ColStructure<IndexType> Col [], IndexType A [], IndexType *pfree) ;\n\ntemplate <typename IndexType>\nstatic inline  IndexType clear_mark (IndexType n_row, RowStructure<IndexType> Row [] ) ;\n\n/* === No debugging ========================================================= */\n\n#define COLAMD_DEBUG0(params) ;\n#define COLAMD_DEBUG1(params) ;\n#define COLAMD_DEBUG2(params) ;\n#define COLAMD_DEBUG3(params) ;\n#define COLAMD_DEBUG4(params) ;\n\n#define COLAMD_ASSERT(expression) ((void) 0)\n\n\n/**\n * \\brief Returns the recommended value of Alen\n *\n * Returns recommended value of Alen for use by colamd.\n * Returns -1 if any input argument is negative.\n * The use of this routine or macro is optional.\n * Note that the macro uses its arguments   more than once,\n * so be careful for side effects, if you pass expressions as arguments to COLAMD_RECOMMENDED.\n *\n * \\param nnz nonzeros in A\n * \\param n_row number of rows in A\n * \\param n_col number of columns in A\n * \\return recommended value of Alen for use by colamd\n */\ntemplate <typename IndexType>\ninline IndexType recommended ( IndexType nnz, IndexType n_row, IndexType n_col)\n{\n  if ((nnz) < 0 || (n_row) < 0 || (n_col) < 0)\n    return (-1);\n  else\n    return (2 * (nnz) + colamd_c (n_col) + colamd_r (n_row) + (n_col) + ((nnz) / 5));\n}\n\n/**\n * \\brief set default parameters  The use of this routine is optional.\n *\n * Colamd: rows with more than (knobs [DenseRow] * n_col)\n * entries are removed prior to ordering.  Columns with more than\n * (knobs [DenseCol] * n_row) entries are removed prior to\n * ordering, and placed last in the output column ordering.\n *\n * DenseRow and DenseCol are defined as 0 and 1,\n * respectively, in colamd.h.  Default values of these two knobs\n * are both 0.5.  Currently, only knobs [0] and knobs [1] are\n * used, but future versions may use more knobs.  If so, they will\n * be properly set to their defaults by the future version of\n * colamd_set_defaults, so that the code that calls colamd will\n * not need to change, assuming that you either use\n * colamd_set_defaults, or pass a (double *) NULL pointer as the\n * knobs array to colamd or symamd.\n *\n * \\param knobs parameter settings for colamd\n */\n\nstatic inline void set_defaults(double knobs[NKnobs])\n{\n  /* === Local variables ================================================== */\n\n  int i ;\n\n  if (!knobs)\n  {\n    return ;      /* no knobs to initialize */\n  }\n  for (i = 0 ; i < NKnobs ; i++)\n  {\n    knobs [i] = 0 ;\n  }\n  knobs [Colamd::DenseRow] = 0.5 ;  /* ignore rows over 50% dense */\n  knobs [Colamd::DenseCol] = 0.5 ;  /* ignore columns over 50% dense */\n}\n\n/**\n * \\brief  Computes a column ordering using the column approximate minimum degree ordering\n *\n * Computes a column ordering (Q) of A such that P(AQ)=LU or\n * (AQ)'AQ=LL' have less fill-in and require fewer floating point\n * operations than factorizing the unpermuted matrix A or A'A,\n * respectively.\n *\n *\n * \\param n_row number of rows in A\n * \\param n_col number of columns in A\n * \\param Alen, size of the array A\n * \\param A row indices of the matrix, of size ALen\n * \\param p column pointers of A, of size n_col+1\n * \\param knobs parameter settings for colamd\n * \\param stats colamd output statistics and error codes\n */\ntemplate <typename IndexType>\nstatic bool compute_ordering(IndexType n_row, IndexType n_col, IndexType Alen, IndexType *A, IndexType *p, double knobs[NKnobs], IndexType stats[NStats])\n{\n  /* === Local variables ================================================== */\n\n  IndexType i ;     /* loop index */\n  IndexType nnz ;     /* nonzeros in A */\n  IndexType Row_size ;    /* size of Row [], in integers */\n  IndexType Col_size ;    /* size of Col [], in integers */\n  IndexType need ;      /* minimum required length of A */\n  Colamd::RowStructure<IndexType> *Row ;   /* pointer into A of Row [0..n_row] array */\n  Colamd::ColStructure<IndexType> *Col ;   /* pointer into A of Col [0..n_col] array */\n  IndexType n_col2 ;    /* number of non-dense, non-empty columns */\n  IndexType n_row2 ;    /* number of non-dense, non-empty rows */\n  IndexType ngarbage ;    /* number of garbage collections performed */\n  IndexType max_deg ;   /* maximum row degree */\n  double default_knobs [NKnobs] ; /* default knobs array */\n\n\n  /* === Check the input arguments ======================================== */\n\n  if (!stats)\n  {\n    COLAMD_DEBUG0 ((\"colamd: stats not present\\n\")) ;\n    return (false) ;\n  }\n  for (i = 0 ; i < NStats ; i++)\n  {\n    stats [i] = 0 ;\n  }\n  stats [Colamd::Status] = Colamd::Ok ;\n  stats [Colamd::Info1] = -1 ;\n  stats [Colamd::Info2] = -1 ;\n\n  if (!A)   /* A is not present */\n  {\n    stats [Colamd::Status] = Colamd::ErrorANotPresent ;\n    COLAMD_DEBUG0 ((\"colamd: A not present\\n\")) ;\n    return (false) ;\n  }\n\n  if (!p)   /* p is not present */\n  {\n    stats [Colamd::Status] = Colamd::ErrorPNotPresent ;\n    COLAMD_DEBUG0 ((\"colamd: p not present\\n\")) ;\n    return (false) ;\n  }\n\n  if (n_row < 0)  /* n_row must be >= 0 */\n  {\n    stats [Colamd::Status] = Colamd::ErrorNrowNegative ;\n    stats [Colamd::Info1] = n_row ;\n    COLAMD_DEBUG0 ((\"colamd: nrow negative %d\\n\", n_row)) ;\n    return (false) ;\n  }\n\n  if (n_col < 0)  /* n_col must be >= 0 */\n  {\n    stats [Colamd::Status] = Colamd::ErrorNcolNegative ;\n    stats [Colamd::Info1] = n_col ;\n    COLAMD_DEBUG0 ((\"colamd: ncol negative %d\\n\", n_col)) ;\n    return (false) ;\n  }\n\n  nnz = p [n_col] ;\n  if (nnz < 0)  /* nnz must be >= 0 */\n  {\n    stats [Colamd::Status] = Colamd::ErrorNnzNegative ;\n    stats [Colamd::Info1] = nnz ;\n    COLAMD_DEBUG0 ((\"colamd: number of entries negative %d\\n\", nnz)) ;\n    return (false) ;\n  }\n\n  if (p [0] != 0)\n  {\n    stats [Colamd::Status] = Colamd::ErrorP0Nonzero ;\n    stats [Colamd::Info1] = p [0] ;\n    COLAMD_DEBUG0 ((\"colamd: p[0] not zero %d\\n\", p [0])) ;\n    return (false) ;\n  }\n\n  /* === If no knobs, set default knobs =================================== */\n\n  if (!knobs)\n  {\n    set_defaults (default_knobs) ;\n    knobs = default_knobs ;\n  }\n\n  /* === Allocate the Row and Col arrays from array A ===================== */\n\n  Col_size = colamd_c (n_col) ;\n  Row_size = colamd_r (n_row) ;\n  need = 2*nnz + n_col + Col_size + Row_size ;\n\n  if (need > Alen)\n  {\n    /* not enough space in array A to perform the ordering */\n    stats [Colamd::Status] = Colamd::ErrorATooSmall ;\n    stats [Colamd::Info1] = need ;\n    stats [Colamd::Info2] = Alen ;\n    COLAMD_DEBUG0 ((\"colamd: Need Alen >= %d, given only Alen = %d\\n\", need,Alen));\n    return (false) ;\n  }\n\n  Alen -= Col_size + Row_size ;\n  Col = (ColStructure<IndexType> *) &A [Alen] ;\n  Row = (RowStructure<IndexType> *) &A [Alen + Col_size] ;\n\n  /* === Construct the row and column data structures ===================== */\n\n  if (!Colamd::init_rows_cols (n_row, n_col, Row, Col, A, p, stats))\n  {\n    /* input matrix is invalid */\n    COLAMD_DEBUG0 ((\"colamd: Matrix invalid\\n\")) ;\n    return (false) ;\n  }\n\n  /* === Initialize scores, kill dense rows/columns ======================= */\n\n  Colamd::init_scoring (n_row, n_col, Row, Col, A, p, knobs,\n\t\t&n_row2, &n_col2, &max_deg) ;\n\n  /* === Order the supercolumns =========================================== */\n\n  ngarbage = Colamd::find_ordering (n_row, n_col, Alen, Row, Col, A, p,\n\t\t\t    n_col2, max_deg, 2*nnz) ;\n\n  /* === Order the non-principal columns ================================== */\n\n  Colamd::order_children (n_col, Col, p) ;\n\n  /* === Return statistics in stats ======================================= */\n\n  stats [Colamd::DenseRow] = n_row - n_row2 ;\n  stats [Colamd::DenseCol] = n_col - n_col2 ;\n  stats [Colamd::DefragCount] = ngarbage ;\n  COLAMD_DEBUG0 ((\"colamd: done.\\n\")) ;\n  return (true) ;\n}\n\n/* ========================================================================== */\n/* === NON-USER-CALLABLE ROUTINES: ========================================== */\n/* ========================================================================== */\n\n/* There are no user-callable routines beyond this point in the file */\n\n/* ========================================================================== */\n/* === init_rows_cols ======================================================= */\n/* ========================================================================== */\n\n/*\n  Takes the column form of the matrix in A and creates the row form of the\n  matrix.  Also, row and column attributes are stored in the Col and Row\n  structs.  If the columns are un-sorted or contain duplicate row indices,\n  this routine will also sort and remove duplicate row indices from the\n  column form of the matrix.  Returns false if the matrix is invalid,\n  true otherwise.  Not user-callable.\n*/\ntemplate <typename IndexType>\nstatic IndexType init_rows_cols  /* returns true if OK, or false otherwise */\n  (\n    /* === Parameters ======================================================= */\n\n    IndexType n_row,      /* number of rows of A */\n    IndexType n_col,      /* number of columns of A */\n    RowStructure<IndexType> Row [],    /* of size n_row+1 */\n    ColStructure<IndexType> Col [],    /* of size n_col+1 */\n    IndexType A [],     /* row indices of A, of size Alen */\n    IndexType p [],     /* pointers to columns in A, of size n_col+1 */\n    IndexType stats [NStats]  /* colamd statistics */\n    )\n{\n  /* === Local variables ================================================== */\n\n  IndexType col ;     /* a column index */\n  IndexType row ;     /* a row index */\n  IndexType *cp ;     /* a column pointer */\n  IndexType *cp_end ;   /* a pointer to the end of a column */\n  IndexType *rp ;     /* a row pointer */\n  IndexType *rp_end ;   /* a pointer to the end of a row */\n  IndexType last_row ;    /* previous row */\n\n  /* === Initialize columns, and check column pointers ==================== */\n\n  for (col = 0 ; col < n_col ; col++)\n  {\n    Col [col].start = p [col] ;\n    Col [col].length = p [col+1] - p [col] ;\n\n    if ((Col [col].length) < 0) // extra parentheses to work-around gcc bug 10200\n    {\n      /* column pointers must be non-decreasing */\n      stats [Colamd::Status] = Colamd::ErrorColLengthNegative ;\n      stats [Colamd::Info1] = col ;\n      stats [Colamd::Info2] = Col [col].length ;\n      COLAMD_DEBUG0 ((\"colamd: col %d length %d < 0\\n\", col, Col [col].length)) ;\n      return (false) ;\n    }\n\n    Col [col].shared1.thickness = 1 ;\n    Col [col].shared2.score = 0 ;\n    Col [col].shared3.prev = Empty ;\n    Col [col].shared4.degree_next = Empty ;\n  }\n\n  /* p [0..n_col] no longer needed, used as \"head\" in subsequent routines */\n\n  /* === Scan columns, compute row degrees, and check row indices ========= */\n\n  stats [Info3] = 0 ;  /* number of duplicate or unsorted row indices*/\n\n  for (row = 0 ; row < n_row ; row++)\n  {\n    Row [row].length = 0 ;\n    Row [row].shared2.mark = -1 ;\n  }\n\n  for (col = 0 ; col < n_col ; col++)\n  {\n    last_row = -1 ;\n\n    cp = &A [p [col]] ;\n    cp_end = &A [p [col+1]] ;\n\n    while (cp < cp_end)\n    {\n      row = *cp++ ;\n\n      /* make sure row indices within range */\n      if (row < 0 || row >= n_row)\n      {\n\tstats [Colamd::Status] = Colamd::ErrorRowIndexOutOfBounds ;\n\tstats [Colamd::Info1] = col ;\n\tstats [Colamd::Info2] = row ;\n\tstats [Colamd::Info3] = n_row ;\n\tCOLAMD_DEBUG0 ((\"colamd: row %d col %d out of bounds\\n\", row, col)) ;\n\treturn (false) ;\n      }\n\n      if (row <= last_row || Row [row].shared2.mark == col)\n      {\n\t/* row index are unsorted or repeated (or both), thus col */\n\t/* is jumbled.  This is a notice, not an error condition. */\n\tstats [Colamd::Status] = Colamd::OkButJumbled ;\n\tstats [Colamd::Info1] = col ;\n\tstats [Colamd::Info2] = row ;\n\t(stats [Colamd::Info3]) ++ ;\n\tCOLAMD_DEBUG1 ((\"colamd: row %d col %d unsorted/duplicate\\n\",row,col));\n      }\n\n      if (Row [row].shared2.mark != col)\n      {\n\tRow [row].length++ ;\n      }\n      else\n      {\n\t/* this is a repeated entry in the column, */\n\t/* it will be removed */\n\tCol [col].length-- ;\n      }\n\n      /* mark the row as having been seen in this column */\n      Row [row].shared2.mark = col ;\n\n      last_row = row ;\n    }\n  }\n\n  /* === Compute row pointers ============================================= */\n\n  /* row form of the matrix starts directly after the column */\n  /* form of matrix in A */\n  Row [0].start = p [n_col] ;\n  Row [0].shared1.p = Row [0].start ;\n  Row [0].shared2.mark = -1 ;\n  for (row = 1 ; row < n_row ; row++)\n  {\n    Row [row].start = Row [row-1].start + Row [row-1].length ;\n    Row [row].shared1.p = Row [row].start ;\n    Row [row].shared2.mark = -1 ;\n  }\n\n  /* === Create row form ================================================== */\n\n  if (stats [Status] == OkButJumbled)\n  {\n    /* if cols jumbled, watch for repeated row indices */\n    for (col = 0 ; col < n_col ; col++)\n    {\n      cp = &A [p [col]] ;\n      cp_end = &A [p [col+1]] ;\n      while (cp < cp_end)\n      {\n\trow = *cp++ ;\n\tif (Row [row].shared2.mark != col)\n\t{\n\t  A [(Row [row].shared1.p)++] = col ;\n\t  Row [row].shared2.mark = col ;\n\t}\n      }\n    }\n  }\n  else\n  {\n    /* if cols not jumbled, we don't need the mark (this is faster) */\n    for (col = 0 ; col < n_col ; col++)\n    {\n      cp = &A [p [col]] ;\n      cp_end = &A [p [col+1]] ;\n      while (cp < cp_end)\n      {\n\tA [(Row [*cp++].shared1.p)++] = col ;\n      }\n    }\n  }\n\n  /* === Clear the row marks and set row degrees ========================== */\n\n  for (row = 0 ; row < n_row ; row++)\n  {\n    Row [row].shared2.mark = 0 ;\n    Row [row].shared1.degree = Row [row].length ;\n  }\n\n  /* === See if we need to re-create columns ============================== */\n\n  if (stats [Status] == OkButJumbled)\n  {\n    COLAMD_DEBUG0 ((\"colamd: reconstructing column form, matrix jumbled\\n\")) ;\n\n\n    /* === Compute col pointers ========================================= */\n\n    /* col form of the matrix starts at A [0]. */\n    /* Note, we may have a gap between the col form and the row */\n    /* form if there were duplicate entries, if so, it will be */\n    /* removed upon the first garbage collection */\n    Col [0].start = 0 ;\n    p [0] = Col [0].start ;\n    for (col = 1 ; col < n_col ; col++)\n    {\n      /* note that the lengths here are for pruned columns, i.e. */\n      /* no duplicate row indices will exist for these columns */\n      Col [col].start = Col [col-1].start + Col [col-1].length ;\n      p [col] = Col [col].start ;\n    }\n\n    /* === Re-create col form =========================================== */\n\n    for (row = 0 ; row < n_row ; row++)\n    {\n      rp = &A [Row [row].start] ;\n      rp_end = rp + Row [row].length ;\n      while (rp < rp_end)\n      {\n\tA [(p [*rp++])++] = row ;\n      }\n    }\n  }\n\n  /* === Done.  Matrix is not (or no longer) jumbled ====================== */\n\n  return (true) ;\n}\n\n\n/* ========================================================================== */\n/* === init_scoring ========================================================= */\n/* ========================================================================== */\n\n/*\n  Kills dense or empty columns and rows, calculates an initial score for\n  each column, and places all columns in the degree lists.  Not user-callable.\n*/\ntemplate <typename IndexType>\nstatic void init_scoring\n  (\n    /* === Parameters ======================================================= */\n\n    IndexType n_row,      /* number of rows of A */\n    IndexType n_col,      /* number of columns of A */\n    RowStructure<IndexType> Row [],    /* of size n_row+1 */\n    ColStructure<IndexType> Col [],    /* of size n_col+1 */\n    IndexType A [],     /* column form and row form of A */\n    IndexType head [],    /* of size n_col+1 */\n    double knobs [NKnobs],/* parameters */\n    IndexType *p_n_row2,    /* number of non-dense, non-empty rows */\n    IndexType *p_n_col2,    /* number of non-dense, non-empty columns */\n    IndexType *p_max_deg    /* maximum row degree */\n    )\n{\n  /* === Local variables ================================================== */\n\n  IndexType c ;     /* a column index */\n  IndexType r, row ;    /* a row index */\n  IndexType *cp ;     /* a column pointer */\n  IndexType deg ;     /* degree of a row or column */\n  IndexType *cp_end ;   /* a pointer to the end of a column */\n  IndexType *new_cp ;   /* new column pointer */\n  IndexType col_length ;    /* length of pruned column */\n  IndexType score ;     /* current column score */\n  IndexType n_col2 ;    /* number of non-dense, non-empty columns */\n  IndexType n_row2 ;    /* number of non-dense, non-empty rows */\n  IndexType dense_row_count ; /* remove rows with more entries than this */\n  IndexType dense_col_count ; /* remove cols with more entries than this */\n  IndexType min_score ;   /* smallest column score */\n  IndexType max_deg ;   /* maximum row degree */\n  IndexType next_col ;    /* Used to add to degree list.*/\n\n\n  /* === Extract knobs ==================================================== */\n\n  dense_row_count = numext::maxi(IndexType(0), numext::mini(IndexType(knobs [Colamd::DenseRow] * n_col), n_col)) ;\n  dense_col_count = numext::maxi(IndexType(0), numext::mini(IndexType(knobs [Colamd::DenseCol] * n_row), n_row)) ;\n  COLAMD_DEBUG1 ((\"colamd: densecount: %d %d\\n\", dense_row_count, dense_col_count)) ;\n  max_deg = 0 ;\n  n_col2 = n_col ;\n  n_row2 = n_row ;\n\n  /* === Kill empty columns =============================================== */\n\n  /* Put the empty columns at the end in their natural order, so that LU */\n  /* factorization can proceed as far as possible. */\n  for (c = n_col-1 ; c >= 0 ; c--)\n  {\n    deg = Col [c].length ;\n    if (deg == 0)\n    {\n      /* this is a empty column, kill and order it last */\n      Col [c].shared2.order = --n_col2 ;\n      Col[c].kill_principal() ;\n    }\n  }\n  COLAMD_DEBUG1 ((\"colamd: null columns killed: %d\\n\", n_col - n_col2)) ;\n\n  /* === Kill dense columns =============================================== */\n\n  /* Put the dense columns at the end, in their natural order */\n  for (c = n_col-1 ; c >= 0 ; c--)\n  {\n    /* skip any dead columns */\n    if (Col[c].is_dead())\n    {\n      continue ;\n    }\n    deg = Col [c].length ;\n    if (deg > dense_col_count)\n    {\n      /* this is a dense column, kill and order it last */\n      Col [c].shared2.order = --n_col2 ;\n      /* decrement the row degrees */\n      cp = &A [Col [c].start] ;\n      cp_end = cp + Col [c].length ;\n      while (cp < cp_end)\n      {\n\tRow [*cp++].shared1.degree-- ;\n      }\n      Col[c].kill_principal() ;\n    }\n  }\n  COLAMD_DEBUG1 ((\"colamd: Dense and null columns killed: %d\\n\", n_col - n_col2)) ;\n\n  /* === Kill dense and empty rows ======================================== */\n\n  for (r = 0 ; r < n_row ; r++)\n  {\n    deg = Row [r].shared1.degree ;\n    COLAMD_ASSERT (deg >= 0 && deg <= n_col) ;\n    if (deg > dense_row_count || deg == 0)\n    {\n      /* kill a dense or empty row */\n      Row[r].kill() ;\n      --n_row2 ;\n    }\n    else\n    {\n      /* keep track of max degree of remaining rows */\n      max_deg = numext::maxi(max_deg, deg) ;\n    }\n  }\n  COLAMD_DEBUG1 ((\"colamd: Dense and null rows killed: %d\\n\", n_row - n_row2)) ;\n\n  /* === Compute initial column scores ==================================== */\n\n  /* At this point the row degrees are accurate.  They reflect the number */\n  /* of \"live\" (non-dense) columns in each row.  No empty rows exist. */\n  /* Some \"live\" columns may contain only dead rows, however.  These are */\n  /* pruned in the code below. */\n\n  /* now find the initial matlab score for each column */\n  for (c = n_col-1 ; c >= 0 ; c--)\n  {\n    /* skip dead column */\n    if (Col[c].is_dead())\n    {\n      continue ;\n    }\n    score = 0 ;\n    cp = &A [Col [c].start] ;\n    new_cp = cp ;\n    cp_end = cp + Col [c].length ;\n    while (cp < cp_end)\n    {\n      /* get a row */\n      row = *cp++ ;\n      /* skip if dead */\n      if (Row[row].is_dead())\n      {\n\tcontinue ;\n      }\n      /* compact the column */\n      *new_cp++ = row ;\n      /* add row's external degree */\n      score += Row [row].shared1.degree - 1 ;\n      /* guard against integer overflow */\n      score = numext::mini(score, n_col) ;\n    }\n    /* determine pruned column length */\n    col_length = (IndexType) (new_cp - &A [Col [c].start]) ;\n    if (col_length == 0)\n    {\n      /* a newly-made null column (all rows in this col are \"dense\" */\n      /* and have already been killed) */\n      COLAMD_DEBUG2 ((\"Newly null killed: %d\\n\", c)) ;\n      Col [c].shared2.order = --n_col2 ;\n      Col[c].kill_principal() ;\n    }\n    else\n    {\n      /* set column length and set score */\n      COLAMD_ASSERT (score >= 0) ;\n      COLAMD_ASSERT (score <= n_col) ;\n      Col [c].length = col_length ;\n      Col [c].shared2.score = score ;\n    }\n  }\n  COLAMD_DEBUG1 ((\"colamd: Dense, null, and newly-null columns killed: %d\\n\",\n\t\t  n_col-n_col2)) ;\n\n  /* At this point, all empty rows and columns are dead.  All live columns */\n  /* are \"clean\" (containing no dead rows) and simplicial (no supercolumns */\n  /* yet).  Rows may contain dead columns, but all live rows contain at */\n  /* least one live column. */\n\n  /* === Initialize degree lists ========================================== */\n\n\n  /* clear the hash buckets */\n  for (c = 0 ; c <= n_col ; c++)\n  {\n    head [c] = Empty ;\n  }\n  min_score = n_col ;\n  /* place in reverse order, so low column indices are at the front */\n  /* of the lists.  This is to encourage natural tie-breaking */\n  for (c = n_col-1 ; c >= 0 ; c--)\n  {\n    /* only add principal columns to degree lists */\n    if (Col[c].is_alive())\n    {\n      COLAMD_DEBUG4 ((\"place %d score %d minscore %d ncol %d\\n\",\n\t\t      c, Col [c].shared2.score, min_score, n_col)) ;\n\n      /* === Add columns score to DList =============================== */\n\n      score = Col [c].shared2.score ;\n\n      COLAMD_ASSERT (min_score >= 0) ;\n      COLAMD_ASSERT (min_score <= n_col) ;\n      COLAMD_ASSERT (score >= 0) ;\n      COLAMD_ASSERT (score <= n_col) ;\n      COLAMD_ASSERT (head [score] >= Empty) ;\n\n      /* now add this column to dList at proper score location */\n      next_col = head [score] ;\n      Col [c].shared3.prev = Empty ;\n      Col [c].shared4.degree_next = next_col ;\n\n      /* if there already was a column with the same score, set its */\n      /* previous pointer to this new column */\n      if (next_col != Empty)\n      {\n\tCol [next_col].shared3.prev = c ;\n      }\n      head [score] = c ;\n\n      /* see if this score is less than current min */\n      min_score = numext::mini(min_score, score) ;\n\n\n    }\n  }\n\n\n  /* === Return number of remaining columns, and max row degree =========== */\n\n  *p_n_col2 = n_col2 ;\n  *p_n_row2 = n_row2 ;\n  *p_max_deg = max_deg ;\n}\n\n\n/* ========================================================================== */\n/* === find_ordering ======================================================== */\n/* ========================================================================== */\n\n/*\n  Order the principal columns of the supercolumn form of the matrix\n  (no supercolumns on input).  Uses a minimum approximate column minimum\n  degree ordering method.  Not user-callable.\n*/\ntemplate <typename IndexType>\nstatic IndexType find_ordering /* return the number of garbage collections */\n  (\n    /* === Parameters ======================================================= */\n\n    IndexType n_row,      /* number of rows of A */\n    IndexType n_col,      /* number of columns of A */\n    IndexType Alen,     /* size of A, 2*nnz + n_col or larger */\n    RowStructure<IndexType> Row [],    /* of size n_row+1 */\n    ColStructure<IndexType> Col [],    /* of size n_col+1 */\n    IndexType A [],     /* column form and row form of A */\n    IndexType head [],    /* of size n_col+1 */\n    IndexType n_col2,     /* Remaining columns to order */\n    IndexType max_deg,    /* Maximum row degree */\n    IndexType pfree     /* index of first free slot (2*nnz on entry) */\n    )\n{\n  /* === Local variables ================================================== */\n\n  IndexType k ;     /* current pivot ordering step */\n  IndexType pivot_col ;   /* current pivot column */\n  IndexType *cp ;     /* a column pointer */\n  IndexType *rp ;     /* a row pointer */\n  IndexType pivot_row ;   /* current pivot row */\n  IndexType *new_cp ;   /* modified column pointer */\n  IndexType *new_rp ;   /* modified row pointer */\n  IndexType pivot_row_start ; /* pointer to start of pivot row */\n  IndexType pivot_row_degree ;  /* number of columns in pivot row */\n  IndexType pivot_row_length ;  /* number of supercolumns in pivot row */\n  IndexType pivot_col_score ; /* score of pivot column */\n  IndexType needed_memory ;   /* free space needed for pivot row */\n  IndexType *cp_end ;   /* pointer to the end of a column */\n  IndexType *rp_end ;   /* pointer to the end of a row */\n  IndexType row ;     /* a row index */\n  IndexType col ;     /* a column index */\n  IndexType max_score ;   /* maximum possible score */\n  IndexType cur_score ;   /* score of current column */\n  unsigned int hash ;   /* hash value for supernode detection */\n  IndexType head_column ;   /* head of hash bucket */\n  IndexType first_col ;   /* first column in hash bucket */\n  IndexType tag_mark ;    /* marker value for mark array */\n  IndexType row_mark ;    /* Row [row].shared2.mark */\n  IndexType set_difference ;  /* set difference size of row with pivot row */\n  IndexType min_score ;   /* smallest column score */\n  IndexType col_thickness ;   /* \"thickness\" (no. of columns in a supercol) */\n  IndexType max_mark ;    /* maximum value of tag_mark */\n  IndexType pivot_col_thickness ; /* number of columns represented by pivot col */\n  IndexType prev_col ;    /* Used by Dlist operations. */\n  IndexType next_col ;    /* Used by Dlist operations. */\n  IndexType ngarbage ;    /* number of garbage collections performed */\n\n\n  /* === Initialization and clear mark ==================================== */\n\n  max_mark = INT_MAX - n_col ;  /* INT_MAX defined in <limits.h> */\n  tag_mark = Colamd::clear_mark (n_row, Row) ;\n  min_score = 0 ;\n  ngarbage = 0 ;\n  COLAMD_DEBUG1 ((\"colamd: Ordering, n_col2=%d\\n\", n_col2)) ;\n\n  /* === Order the columns ================================================ */\n\n  for (k = 0 ; k < n_col2 ; /* 'k' is incremented below */)\n  {\n\n    /* === Select pivot column, and order it ============================ */\n\n    /* make sure degree list isn't empty */\n    COLAMD_ASSERT (min_score >= 0) ;\n    COLAMD_ASSERT (min_score <= n_col) ;\n    COLAMD_ASSERT (head [min_score] >= Empty) ;\n\n    /* get pivot column from head of minimum degree list */\n    while (min_score < n_col && head [min_score] == Empty)\n    {\n      min_score++ ;\n    }\n    pivot_col = head [min_score] ;\n    COLAMD_ASSERT (pivot_col >= 0 && pivot_col <= n_col) ;\n    next_col = Col [pivot_col].shared4.degree_next ;\n    head [min_score] = next_col ;\n    if (next_col != Empty)\n    {\n      Col [next_col].shared3.prev = Empty ;\n    }\n\n    COLAMD_ASSERT (Col[pivot_col].is_alive()) ;\n    COLAMD_DEBUG3 ((\"Pivot col: %d\\n\", pivot_col)) ;\n\n    /* remember score for defrag check */\n    pivot_col_score = Col [pivot_col].shared2.score ;\n\n    /* the pivot column is the kth column in the pivot order */\n    Col [pivot_col].shared2.order = k ;\n\n    /* increment order count by column thickness */\n    pivot_col_thickness = Col [pivot_col].shared1.thickness ;\n    k += pivot_col_thickness ;\n    COLAMD_ASSERT (pivot_col_thickness > 0) ;\n\n    /* === Garbage_collection, if necessary ============================= */\n\n    needed_memory = numext::mini(pivot_col_score, n_col - k) ;\n    if (pfree + needed_memory >= Alen)\n    {\n      pfree = Colamd::garbage_collection (n_row, n_col, Row, Col, A, &A [pfree]) ;\n      ngarbage++ ;\n      /* after garbage collection we will have enough */\n      COLAMD_ASSERT (pfree + needed_memory < Alen) ;\n      /* garbage collection has wiped out the Row[].shared2.mark array */\n      tag_mark = Colamd::clear_mark (n_row, Row) ;\n\n    }\n\n    /* === Compute pivot row pattern ==================================== */\n\n    /* get starting location for this new merged row */\n    pivot_row_start = pfree ;\n\n    /* initialize new row counts to zero */\n    pivot_row_degree = 0 ;\n\n    /* tag pivot column as having been visited so it isn't included */\n    /* in merged pivot row */\n    Col [pivot_col].shared1.thickness = -pivot_col_thickness ;\n\n    /* pivot row is the union of all rows in the pivot column pattern */\n    cp = &A [Col [pivot_col].start] ;\n    cp_end = cp + Col [pivot_col].length ;\n    while (cp < cp_end)\n    {\n      /* get a row */\n      row = *cp++ ;\n      COLAMD_DEBUG4 ((\"Pivot col pattern %d %d\\n\", Row[row].is_alive(), row)) ;\n      /* skip if row is dead */\n      if (Row[row].is_dead())\n      {\n\tcontinue ;\n      }\n      rp = &A [Row [row].start] ;\n      rp_end = rp + Row [row].length ;\n      while (rp < rp_end)\n      {\n\t/* get a column */\n\tcol = *rp++ ;\n\t/* add the column, if alive and untagged */\n\tcol_thickness = Col [col].shared1.thickness ;\n\tif (col_thickness > 0 && Col[col].is_alive())\n\t{\n\t  /* tag column in pivot row */\n\t  Col [col].shared1.thickness = -col_thickness ;\n\t  COLAMD_ASSERT (pfree < Alen) ;\n\t  /* place column in pivot row */\n\t  A [pfree++] = col ;\n\t  pivot_row_degree += col_thickness ;\n\t}\n      }\n    }\n\n    /* clear tag on pivot column */\n    Col [pivot_col].shared1.thickness = pivot_col_thickness ;\n    max_deg = numext::maxi(max_deg, pivot_row_degree) ;\n\n\n    /* === Kill all rows used to construct pivot row ==================== */\n\n    /* also kill pivot row, temporarily */\n    cp = &A [Col [pivot_col].start] ;\n    cp_end = cp + Col [pivot_col].length ;\n    while (cp < cp_end)\n    {\n      /* may be killing an already dead row */\n      row = *cp++ ;\n      COLAMD_DEBUG3 ((\"Kill row in pivot col: %d\\n\", row)) ;\n      Row[row].kill() ;\n    }\n\n    /* === Select a row index to use as the new pivot row =============== */\n\n    pivot_row_length = pfree - pivot_row_start ;\n    if (pivot_row_length > 0)\n    {\n      /* pick the \"pivot\" row arbitrarily (first row in col) */\n      pivot_row = A [Col [pivot_col].start] ;\n      COLAMD_DEBUG3 ((\"Pivotal row is %d\\n\", pivot_row)) ;\n    }\n    else\n    {\n      /* there is no pivot row, since it is of zero length */\n      pivot_row = Empty ;\n      COLAMD_ASSERT (pivot_row_length == 0) ;\n    }\n    COLAMD_ASSERT (Col [pivot_col].length > 0 || pivot_row_length == 0) ;\n\n    /* === Approximate degree computation =============================== */\n\n    /* Here begins the computation of the approximate degree.  The column */\n    /* score is the sum of the pivot row \"length\", plus the size of the */\n    /* set differences of each row in the column minus the pattern of the */\n    /* pivot row itself.  The column (\"thickness\") itself is also */\n    /* excluded from the column score (we thus use an approximate */\n    /* external degree). */\n\n    /* The time taken by the following code (compute set differences, and */\n    /* add them up) is proportional to the size of the data structure */\n    /* being scanned - that is, the sum of the sizes of each column in */\n    /* the pivot row.  Thus, the amortized time to compute a column score */\n    /* is proportional to the size of that column (where size, in this */\n    /* context, is the column \"length\", or the number of row indices */\n    /* in that column).  The number of row indices in a column is */\n    /* monotonically non-decreasing, from the length of the original */\n    /* column on input to colamd. */\n\n    /* === Compute set differences ====================================== */\n\n    COLAMD_DEBUG3 ((\"** Computing set differences phase. **\\n\")) ;\n\n    /* pivot row is currently dead - it will be revived later. */\n\n    COLAMD_DEBUG3 ((\"Pivot row: \")) ;\n    /* for each column in pivot row */\n    rp = &A [pivot_row_start] ;\n    rp_end = rp + pivot_row_length ;\n    while (rp < rp_end)\n    {\n      col = *rp++ ;\n      COLAMD_ASSERT (Col[col].is_alive() && col != pivot_col) ;\n      COLAMD_DEBUG3 ((\"Col: %d\\n\", col)) ;\n\n      /* clear tags used to construct pivot row pattern */\n      col_thickness = -Col [col].shared1.thickness ;\n      COLAMD_ASSERT (col_thickness > 0) ;\n      Col [col].shared1.thickness = col_thickness ;\n\n      /* === Remove column from degree list =========================== */\n\n      cur_score = Col [col].shared2.score ;\n      prev_col = Col [col].shared3.prev ;\n      next_col = Col [col].shared4.degree_next ;\n      COLAMD_ASSERT (cur_score >= 0) ;\n      COLAMD_ASSERT (cur_score <= n_col) ;\n      COLAMD_ASSERT (cur_score >= Empty) ;\n      if (prev_col == Empty)\n      {\n\thead [cur_score] = next_col ;\n      }\n      else\n      {\n\tCol [prev_col].shared4.degree_next = next_col ;\n      }\n      if (next_col != Empty)\n      {\n\tCol [next_col].shared3.prev = prev_col ;\n      }\n\n      /* === Scan the column ========================================== */\n\n      cp = &A [Col [col].start] ;\n      cp_end = cp + Col [col].length ;\n      while (cp < cp_end)\n      {\n\t/* get a row */\n\trow = *cp++ ;\n\t/* skip if dead */\n\tif (Row[row].is_dead())\n\t{\n\t  continue ;\n\t}\n  row_mark = Row [row].shared2.mark ;\n\tCOLAMD_ASSERT (row != pivot_row) ;\n\tset_difference = row_mark - tag_mark ;\n\t/* check if the row has been seen yet */\n\tif (set_difference < 0)\n\t{\n\t  COLAMD_ASSERT (Row [row].shared1.degree <= max_deg) ;\n\t  set_difference = Row [row].shared1.degree ;\n\t}\n\t/* subtract column thickness from this row's set difference */\n\tset_difference -= col_thickness ;\n\tCOLAMD_ASSERT (set_difference >= 0) ;\n\t/* absorb this row if the set difference becomes zero */\n\tif (set_difference == 0)\n\t{\n\t  COLAMD_DEBUG3 ((\"aggressive absorption. Row: %d\\n\", row)) ;\n\t  Row[row].kill() ;\n\t}\n\telse\n\t{\n\t  /* save the new mark */\n\t  Row [row].shared2.mark = set_difference + tag_mark ;\n\t}\n      }\n    }\n\n\n    /* === Add up set differences for each column ======================= */\n\n    COLAMD_DEBUG3 ((\"** Adding set differences phase. **\\n\")) ;\n\n    /* for each column in pivot row */\n    rp = &A [pivot_row_start] ;\n    rp_end = rp + pivot_row_length ;\n    while (rp < rp_end)\n    {\n      /* get a column */\n      col = *rp++ ;\n      COLAMD_ASSERT (Col[col].is_alive() && col != pivot_col) ;\n      hash = 0 ;\n      cur_score = 0 ;\n      cp = &A [Col [col].start] ;\n      /* compact the column */\n      new_cp = cp ;\n      cp_end = cp + Col [col].length ;\n\n      COLAMD_DEBUG4 ((\"Adding set diffs for Col: %d.\\n\", col)) ;\n\n      while (cp < cp_end)\n      {\n\t/* get a row */\n\trow = *cp++ ;\n\tCOLAMD_ASSERT(row >= 0 && row < n_row) ;\n\t/* skip if dead */\n\tif (Row [row].is_dead())\n\t{\n\t  continue ;\n\t}\n  row_mark = Row [row].shared2.mark ;\n\tCOLAMD_ASSERT (row_mark > tag_mark) ;\n\t/* compact the column */\n\t*new_cp++ = row ;\n\t/* compute hash function */\n\thash += row ;\n\t/* add set difference */\n\tcur_score += row_mark - tag_mark ;\n\t/* integer overflow... */\n\tcur_score = numext::mini(cur_score, n_col) ;\n      }\n\n      /* recompute the column's length */\n      Col [col].length = (IndexType) (new_cp - &A [Col [col].start]) ;\n\n      /* === Further mass elimination ================================= */\n\n      if (Col [col].length == 0)\n      {\n\tCOLAMD_DEBUG4 ((\"further mass elimination. Col: %d\\n\", col)) ;\n\t/* nothing left but the pivot row in this column */\n\tCol[col].kill_principal() ;\n\tpivot_row_degree -= Col [col].shared1.thickness ;\n\tCOLAMD_ASSERT (pivot_row_degree >= 0) ;\n\t/* order it */\n\tCol [col].shared2.order = k ;\n\t/* increment order count by column thickness */\n\tk += Col [col].shared1.thickness ;\n      }\n      else\n      {\n\t/* === Prepare for supercolumn detection ==================== */\n\n\tCOLAMD_DEBUG4 ((\"Preparing supercol detection for Col: %d.\\n\", col)) ;\n\n\t/* save score so far */\n\tCol [col].shared2.score = cur_score ;\n\n\t/* add column to hash table, for supercolumn detection */\n\thash %= n_col + 1 ;\n\n\tCOLAMD_DEBUG4 ((\" Hash = %d, n_col = %d.\\n\", hash, n_col)) ;\n\tCOLAMD_ASSERT (hash <= n_col) ;\n\n\thead_column = head [hash] ;\n\tif (head_column > Empty)\n\t{\n\t  /* degree list \"hash\" is non-empty, use prev (shared3) of */\n\t  /* first column in degree list as head of hash bucket */\n\t  first_col = Col [head_column].shared3.headhash ;\n\t  Col [head_column].shared3.headhash = col ;\n\t}\n\telse\n\t{\n\t  /* degree list \"hash\" is empty, use head as hash bucket */\n\t  first_col = - (head_column + 2) ;\n\t  head [hash] = - (col + 2) ;\n\t}\n\tCol [col].shared4.hash_next = first_col ;\n\n\t/* save hash function in Col [col].shared3.hash */\n\tCol [col].shared3.hash = (IndexType) hash ;\n\tCOLAMD_ASSERT (Col[col].is_alive()) ;\n      }\n    }\n\n    /* The approximate external column degree is now computed.  */\n\n    /* === Supercolumn detection ======================================== */\n\n    COLAMD_DEBUG3 ((\"** Supercolumn detection phase. **\\n\")) ;\n\n    Colamd::detect_super_cols (Col, A, head, pivot_row_start, pivot_row_length) ;\n\n    /* === Kill the pivotal column ====================================== */\n\n    Col[pivot_col].kill_principal() ;\n\n    /* === Clear mark =================================================== */\n\n    tag_mark += (max_deg + 1) ;\n    if (tag_mark >= max_mark)\n    {\n      COLAMD_DEBUG2 ((\"clearing tag_mark\\n\")) ;\n      tag_mark = Colamd::clear_mark (n_row, Row) ;\n    }\n\n    /* === Finalize the new pivot row, and column scores ================ */\n\n    COLAMD_DEBUG3 ((\"** Finalize scores phase. **\\n\")) ;\n\n    /* for each column in pivot row */\n    rp = &A [pivot_row_start] ;\n    /* compact the pivot row */\n    new_rp = rp ;\n    rp_end = rp + pivot_row_length ;\n    while (rp < rp_end)\n    {\n      col = *rp++ ;\n      /* skip dead columns */\n      if (Col[col].is_dead())\n      {\n\tcontinue ;\n      }\n      *new_rp++ = col ;\n      /* add new pivot row to column */\n      A [Col [col].start + (Col [col].length++)] = pivot_row ;\n\n      /* retrieve score so far and add on pivot row's degree. */\n      /* (we wait until here for this in case the pivot */\n      /* row's degree was reduced due to mass elimination). */\n      cur_score = Col [col].shared2.score + pivot_row_degree ;\n\n      /* calculate the max possible score as the number of */\n      /* external columns minus the 'k' value minus the */\n      /* columns thickness */\n      max_score = n_col - k - Col [col].shared1.thickness ;\n\n      /* make the score the external degree of the union-of-rows */\n      cur_score -= Col [col].shared1.thickness ;\n\n      /* make sure score is less or equal than the max score */\n      cur_score = numext::mini(cur_score, max_score) ;\n      COLAMD_ASSERT (cur_score >= 0) ;\n\n      /* store updated score */\n      Col [col].shared2.score = cur_score ;\n\n      /* === Place column back in degree list ========================= */\n\n      COLAMD_ASSERT (min_score >= 0) ;\n      COLAMD_ASSERT (min_score <= n_col) ;\n      COLAMD_ASSERT (cur_score >= 0) ;\n      COLAMD_ASSERT (cur_score <= n_col) ;\n      COLAMD_ASSERT (head [cur_score] >= Empty) ;\n      next_col = head [cur_score] ;\n      Col [col].shared4.degree_next = next_col ;\n      Col [col].shared3.prev = Empty ;\n      if (next_col != Empty)\n      {\n\tCol [next_col].shared3.prev = col ;\n      }\n      head [cur_score] = col ;\n\n      /* see if this score is less than current min */\n      min_score = numext::mini(min_score, cur_score) ;\n\n    }\n\n    /* === Resurrect the new pivot row ================================== */\n\n    if (pivot_row_degree > 0)\n    {\n      /* update pivot row length to reflect any cols that were killed */\n      /* during super-col detection and mass elimination */\n      Row [pivot_row].start  = pivot_row_start ;\n      Row [pivot_row].length = (IndexType) (new_rp - &A[pivot_row_start]) ;\n      Row [pivot_row].shared1.degree = pivot_row_degree ;\n      Row [pivot_row].shared2.mark = 0 ;\n      /* pivot row is no longer dead */\n    }\n  }\n\n  /* === All principal columns have now been ordered ====================== */\n\n  return (ngarbage) ;\n}\n\n\n/* ========================================================================== */\n/* === order_children ======================================================= */\n/* ========================================================================== */\n\n/*\n  The find_ordering routine has ordered all of the principal columns (the\n  representatives of the supercolumns).  The non-principal columns have not\n  yet been ordered.  This routine orders those columns by walking up the\n  parent tree (a column is a child of the column which absorbed it).  The\n  final permutation vector is then placed in p [0 ... n_col-1], with p [0]\n  being the first column, and p [n_col-1] being the last.  It doesn't look\n  like it at first glance, but be assured that this routine takes time linear\n  in the number of columns.  Although not immediately obvious, the time\n  taken by this routine is O (n_col), that is, linear in the number of\n  columns.  Not user-callable.\n*/\ntemplate <typename IndexType>\nstatic inline  void order_children\n(\n  /* === Parameters ======================================================= */\n\n  IndexType n_col,      /* number of columns of A */\n  ColStructure<IndexType> Col [],    /* of size n_col+1 */\n  IndexType p []      /* p [0 ... n_col-1] is the column permutation*/\n  )\n{\n  /* === Local variables ================================================== */\n\n  IndexType i ;     /* loop counter for all columns */\n  IndexType c ;     /* column index */\n  IndexType parent ;    /* index of column's parent */\n  IndexType order ;     /* column's order */\n\n  /* === Order each non-principal column ================================== */\n\n  for (i = 0 ; i < n_col ; i++)\n  {\n    /* find an un-ordered non-principal column */\n    COLAMD_ASSERT (col_is_dead(Col, i)) ;\n    if (!Col[i].is_dead_principal() && Col [i].shared2.order == Empty)\n    {\n      parent = i ;\n      /* once found, find its principal parent */\n      do\n      {\n\tparent = Col [parent].shared1.parent ;\n      } while (!Col[parent].is_dead_principal()) ;\n\n      /* now, order all un-ordered non-principal columns along path */\n      /* to this parent.  collapse tree at the same time */\n      c = i ;\n      /* get order of parent */\n      order = Col [parent].shared2.order ;\n\n      do\n      {\n\tCOLAMD_ASSERT (Col [c].shared2.order == Empty) ;\n\n\t/* order this column */\n\tCol [c].shared2.order = order++ ;\n\t/* collaps tree */\n\tCol [c].shared1.parent = parent ;\n\n\t/* get immediate parent of this column */\n\tc = Col [c].shared1.parent ;\n\n\t/* continue until we hit an ordered column.  There are */\n\t/* guaranteed not to be anymore unordered columns */\n\t/* above an ordered column */\n      } while (Col [c].shared2.order == Empty) ;\n\n      /* re-order the super_col parent to largest order for this group */\n      Col [parent].shared2.order = order ;\n    }\n  }\n\n  /* === Generate the permutation ========================================= */\n\n  for (c = 0 ; c < n_col ; c++)\n  {\n    p [Col [c].shared2.order] = c ;\n  }\n}\n\n\n/* ========================================================================== */\n/* === detect_super_cols ==================================================== */\n/* ========================================================================== */\n\n/*\n  Detects supercolumns by finding matches between columns in the hash buckets.\n  Check amongst columns in the set A [row_start ... row_start + row_length-1].\n  The columns under consideration are currently *not* in the degree lists,\n  and have already been placed in the hash buckets.\n\n  The hash bucket for columns whose hash function is equal to h is stored\n  as follows:\n\n  if head [h] is >= 0, then head [h] contains a degree list, so:\n\n  head [h] is the first column in degree bucket h.\n  Col [head [h]].headhash gives the first column in hash bucket h.\n\n  otherwise, the degree list is empty, and:\n\n  -(head [h] + 2) is the first column in hash bucket h.\n\n  For a column c in a hash bucket, Col [c].shared3.prev is NOT a \"previous\n  column\" pointer.  Col [c].shared3.hash is used instead as the hash number\n  for that column.  The value of Col [c].shared4.hash_next is the next column\n  in the same hash bucket.\n\n  Assuming no, or \"few\" hash collisions, the time taken by this routine is\n  linear in the sum of the sizes (lengths) of each column whose score has\n  just been computed in the approximate degree computation.\n  Not user-callable.\n*/\ntemplate <typename IndexType>\nstatic void detect_super_cols\n(\n  /* === Parameters ======================================================= */\n\n  ColStructure<IndexType> Col [],    /* of size n_col+1 */\n  IndexType A [],     /* row indices of A */\n  IndexType head [],    /* head of degree lists and hash buckets */\n  IndexType row_start,    /* pointer to set of columns to check */\n  IndexType row_length    /* number of columns to check */\n)\n{\n  /* === Local variables ================================================== */\n\n  IndexType hash ;      /* hash value for a column */\n  IndexType *rp ;     /* pointer to a row */\n  IndexType c ;     /* a column index */\n  IndexType super_c ;   /* column index of the column to absorb into */\n  IndexType *cp1 ;      /* column pointer for column super_c */\n  IndexType *cp2 ;      /* column pointer for column c */\n  IndexType length ;    /* length of column super_c */\n  IndexType prev_c ;    /* column preceding c in hash bucket */\n  IndexType i ;     /* loop counter */\n  IndexType *rp_end ;   /* pointer to the end of the row */\n  IndexType col ;     /* a column index in the row to check */\n  IndexType head_column ;   /* first column in hash bucket or degree list */\n  IndexType first_col ;   /* first column in hash bucket */\n\n  /* === Consider each column in the row ================================== */\n\n  rp = &A [row_start] ;\n  rp_end = rp + row_length ;\n  while (rp < rp_end)\n  {\n    col = *rp++ ;\n    if (Col[col].is_dead())\n    {\n      continue ;\n    }\n\n    /* get hash number for this column */\n    hash = Col [col].shared3.hash ;\n    COLAMD_ASSERT (hash <= n_col) ;\n\n    /* === Get the first column in this hash bucket ===================== */\n\n    head_column = head [hash] ;\n    if (head_column > Empty)\n    {\n      first_col = Col [head_column].shared3.headhash ;\n    }\n    else\n    {\n      first_col = - (head_column + 2) ;\n    }\n\n    /* === Consider each column in the hash bucket ====================== */\n\n    for (super_c = first_col ; super_c != Empty ;\n\t super_c = Col [super_c].shared4.hash_next)\n    {\n      COLAMD_ASSERT (Col [super_c].is_alive()) ;\n      COLAMD_ASSERT (Col [super_c].shared3.hash == hash) ;\n      length = Col [super_c].length ;\n\n      /* prev_c is the column preceding column c in the hash bucket */\n      prev_c = super_c ;\n\n      /* === Compare super_c with all columns after it ================ */\n\n      for (c = Col [super_c].shared4.hash_next ;\n\t   c != Empty ; c = Col [c].shared4.hash_next)\n      {\n\tCOLAMD_ASSERT (c != super_c) ;\n\tCOLAMD_ASSERT (Col[c].is_alive()) ;\n\tCOLAMD_ASSERT (Col [c].shared3.hash == hash) ;\n\n\t/* not identical if lengths or scores are different */\n\tif (Col [c].length != length ||\n\t    Col [c].shared2.score != Col [super_c].shared2.score)\n\t{\n\t  prev_c = c ;\n\t  continue ;\n\t}\n\n\t/* compare the two columns */\n\tcp1 = &A [Col [super_c].start] ;\n\tcp2 = &A [Col [c].start] ;\n\n\tfor (i = 0 ; i < length ; i++)\n\t{\n\t  /* the columns are \"clean\" (no dead rows) */\n\t  COLAMD_ASSERT ( cp1->is_alive() );\n\t  COLAMD_ASSERT ( cp2->is_alive() );\n\t  /* row indices will same order for both supercols, */\n\t  /* no gather scatter necessary */\n\t  if (*cp1++ != *cp2++)\n\t  {\n\t    break ;\n\t  }\n\t}\n\n\t/* the two columns are different if the for-loop \"broke\" */\n\tif (i != length)\n\t{\n\t  prev_c = c ;\n\t  continue ;\n\t}\n\n\t/* === Got it!  two columns are identical =================== */\n\n\tCOLAMD_ASSERT (Col [c].shared2.score == Col [super_c].shared2.score) ;\n\n\tCol [super_c].shared1.thickness += Col [c].shared1.thickness ;\n\tCol [c].shared1.parent = super_c ;\n\tCol[c].kill_non_principal() ;\n\t/* order c later, in order_children() */\n\tCol [c].shared2.order = Empty ;\n\t/* remove c from hash bucket */\n\tCol [prev_c].shared4.hash_next = Col [c].shared4.hash_next ;\n      }\n    }\n\n    /* === Empty this hash bucket ======================================= */\n\n    if (head_column > Empty)\n    {\n      /* corresponding degree list \"hash\" is not empty */\n      Col [head_column].shared3.headhash = Empty ;\n    }\n    else\n    {\n      /* corresponding degree list \"hash\" is empty */\n      head [hash] = Empty ;\n    }\n  }\n}\n\n\n/* ========================================================================== */\n/* === garbage_collection =================================================== */\n/* ========================================================================== */\n\n/*\n  Defragments and compacts columns and rows in the workspace A.  Used when\n  all available memory has been used while performing row merging.  Returns\n  the index of the first free position in A, after garbage collection.  The\n  time taken by this routine is linear is the size of the array A, which is\n  itself linear in the number of nonzeros in the input matrix.\n  Not user-callable.\n*/\ntemplate <typename IndexType>\nstatic IndexType garbage_collection  /* returns the new value of pfree */\n  (\n    /* === Parameters ======================================================= */\n\n    IndexType n_row,      /* number of rows */\n    IndexType n_col,      /* number of columns */\n    RowStructure<IndexType> Row [],    /* row info */\n    ColStructure<IndexType> Col [],    /* column info */\n    IndexType A [],     /* A [0 ... Alen-1] holds the matrix */\n    IndexType *pfree      /* &A [0] ... pfree is in use */\n    )\n{\n  /* === Local variables ================================================== */\n\n  IndexType *psrc ;     /* source pointer */\n  IndexType *pdest ;    /* destination pointer */\n  IndexType j ;     /* counter */\n  IndexType r ;     /* a row index */\n  IndexType c ;     /* a column index */\n  IndexType length ;    /* length of a row or column */\n\n  /* === Defragment the columns =========================================== */\n\n  pdest = &A[0] ;\n  for (c = 0 ; c < n_col ; c++)\n  {\n    if (Col[c].is_alive())\n    {\n      psrc = &A [Col [c].start] ;\n\n      /* move and compact the column */\n      COLAMD_ASSERT (pdest <= psrc) ;\n      Col [c].start = (IndexType) (pdest - &A [0]) ;\n      length = Col [c].length ;\n      for (j = 0 ; j < length ; j++)\n      {\n\tr = *psrc++ ;\n\tif (Row[r].is_alive())\n\t{\n\t  *pdest++ = r ;\n\t}\n      }\n      Col [c].length = (IndexType) (pdest - &A [Col [c].start]) ;\n    }\n  }\n\n  /* === Prepare to defragment the rows =================================== */\n\n  for (r = 0 ; r < n_row ; r++)\n  {\n    if (Row[r].is_alive())\n    {\n      if (Row [r].length == 0)\n      {\n        /* this row is of zero length.  cannot compact it, so kill it */\n        COLAMD_DEBUG3 ((\"Defrag row kill\\n\")) ;\n        Row[r].kill() ;\n      }\n      else\n      {\n        /* save first column index in Row [r].shared2.first_column */\n        psrc = &A [Row [r].start] ;\n        Row [r].shared2.first_column = *psrc ;\n        COLAMD_ASSERT (Row[r].is_alive()) ;\n        /* flag the start of the row with the one's complement of row */\n        *psrc = ones_complement(r) ;\n\n      }\n    }\n  }\n\n  /* === Defragment the rows ============================================== */\n\n  psrc = pdest ;\n  while (psrc < pfree)\n  {\n    /* find a negative number ... the start of a row */\n    if (*psrc++ < 0)\n    {\n      psrc-- ;\n      /* get the row index */\n      r = ones_complement(*psrc) ;\n      COLAMD_ASSERT (r >= 0 && r < n_row) ;\n      /* restore first column index */\n      *psrc = Row [r].shared2.first_column ;\n      COLAMD_ASSERT (Row[r].is_alive()) ;\n\n      /* move and compact the row */\n      COLAMD_ASSERT (pdest <= psrc) ;\n      Row [r].start = (IndexType) (pdest - &A [0]) ;\n      length = Row [r].length ;\n      for (j = 0 ; j < length ; j++)\n      {\n\tc = *psrc++ ;\n\tif (Col[c].is_alive())\n\t{\n\t  *pdest++ = c ;\n\t}\n      }\n      Row [r].length = (IndexType) (pdest - &A [Row [r].start]) ;\n\n    }\n  }\n  /* ensure we found all the rows */\n  COLAMD_ASSERT (debug_rows == 0) ;\n\n  /* === Return the new value of pfree ==================================== */\n\n  return ((IndexType) (pdest - &A [0])) ;\n}\n\n\n/* ========================================================================== */\n/* === clear_mark =========================================================== */\n/* ========================================================================== */\n\n/*\n  Clears the Row [].shared2.mark array, and returns the new tag_mark.\n  Return value is the new tag_mark.  Not user-callable.\n*/\ntemplate <typename IndexType>\nstatic inline  IndexType clear_mark  /* return the new value for tag_mark */\n  (\n      /* === Parameters ======================================================= */\n\n    IndexType n_row,    /* number of rows in A */\n    RowStructure<IndexType> Row [] /* Row [0 ... n_row-1].shared2.mark is set to zero */\n    )\n{\n  /* === Local variables ================================================== */\n\n  IndexType r ;\n\n  for (r = 0 ; r < n_row ; r++)\n  {\n    if (Row[r].is_alive())\n    {\n      Row [r].shared2.mark = 0 ;\n    }\n  }\n  return (1) ;\n}\n\n} // namespace Colamd\n\n} // namespace internal\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/OrderingMethods/Ordering.h",
    "content": " \n// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012  Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ORDERING_H\n#define EIGEN_ORDERING_H\n\nnamespace Eigen {\n  \n#include \"Eigen_Colamd.h\"\n\nnamespace internal {\n    \n/** \\internal\n  * \\ingroup OrderingMethods_Module\n  * \\param[in] A the input non-symmetric matrix\n  * \\param[out] symmat the symmetric pattern A^T+A from the input matrix \\a A.\n  * FIXME: The values should not be considered here\n  */\ntemplate<typename MatrixType> \nvoid ordering_helper_at_plus_a(const MatrixType& A, MatrixType& symmat)\n{\n  MatrixType C;\n  C = A.transpose(); // NOTE: Could be  costly\n  for (int i = 0; i < C.rows(); i++) \n  {\n      for (typename MatrixType::InnerIterator it(C, i); it; ++it)\n        it.valueRef() = typename MatrixType::Scalar(0);\n  }\n  symmat = C + A;\n}\n    \n}\n\n/** \\ingroup OrderingMethods_Module\n  * \\class AMDOrdering\n  *\n  * Functor computing the \\em approximate \\em minimum \\em degree ordering\n  * If the matrix is not structurally symmetric, an ordering of A^T+A is computed\n  * \\tparam  StorageIndex The type of indices of the matrix \n  * \\sa COLAMDOrdering\n  */\ntemplate <typename StorageIndex>\nclass AMDOrdering\n{\n  public:\n    typedef PermutationMatrix<Dynamic, Dynamic, StorageIndex> PermutationType;\n    \n    /** Compute the permutation vector from a sparse matrix\n     * This routine is much faster if the input matrix is column-major     \n     */\n    template <typename MatrixType>\n    void operator()(const MatrixType& mat, PermutationType& perm)\n    {\n      // Compute the symmetric pattern\n      SparseMatrix<typename MatrixType::Scalar, ColMajor, StorageIndex> symm;\n      internal::ordering_helper_at_plus_a(mat,symm); \n    \n      // Call the AMD routine \n      //m_mat.prune(keep_diag());\n      internal::minimum_degree_ordering(symm, perm);\n    }\n    \n    /** Compute the permutation with a selfadjoint matrix */\n    template <typename SrcType, unsigned int SrcUpLo> \n    void operator()(const SparseSelfAdjointView<SrcType, SrcUpLo>& mat, PermutationType& perm)\n    { \n      SparseMatrix<typename SrcType::Scalar, ColMajor, StorageIndex> C; C = mat;\n      \n      // Call the AMD routine \n      // m_mat.prune(keep_diag()); //Remove the diagonal elements \n      internal::minimum_degree_ordering(C, perm);\n    }\n};\n\n/** \\ingroup OrderingMethods_Module\n  * \\class NaturalOrdering\n  *\n  * Functor computing the natural ordering (identity)\n  * \n  * \\note Returns an empty permutation matrix\n  * \\tparam  StorageIndex The type of indices of the matrix \n  */\ntemplate <typename StorageIndex>\nclass NaturalOrdering\n{\n  public:\n    typedef PermutationMatrix<Dynamic, Dynamic, StorageIndex> PermutationType;\n    \n    /** Compute the permutation vector from a column-major sparse matrix */\n    template <typename MatrixType>\n    void operator()(const MatrixType& /*mat*/, PermutationType& perm)\n    {\n      perm.resize(0); \n    }\n    \n};\n\n/** \\ingroup OrderingMethods_Module\n  * \\class COLAMDOrdering\n  *\n  * \\tparam  StorageIndex The type of indices of the matrix \n  * \n  * Functor computing the \\em column \\em approximate \\em minimum \\em degree ordering \n  * The matrix should be in column-major and \\b compressed format (see SparseMatrix::makeCompressed()).\n  */\ntemplate<typename StorageIndex>\nclass COLAMDOrdering\n{\n  public:\n    typedef PermutationMatrix<Dynamic, Dynamic, StorageIndex> PermutationType; \n    typedef Matrix<StorageIndex, Dynamic, 1> IndexVector;\n    \n    /** Compute the permutation vector \\a perm form the sparse matrix \\a mat\n      * \\warning The input sparse matrix \\a mat must be in compressed mode (see SparseMatrix::makeCompressed()).\n      */\n    template <typename MatrixType>\n    void operator() (const MatrixType& mat, PermutationType& perm)\n    {\n      eigen_assert(mat.isCompressed() && \"COLAMDOrdering requires a sparse matrix in compressed mode. Call .makeCompressed() before passing it to COLAMDOrdering\");\n      \n      StorageIndex m = StorageIndex(mat.rows());\n      StorageIndex n = StorageIndex(mat.cols());\n      StorageIndex nnz = StorageIndex(mat.nonZeros());\n      // Get the recommended value of Alen to be used by colamd\n      StorageIndex Alen = internal::Colamd::recommended(nnz, m, n); \n      // Set the default parameters\n      double knobs [internal::Colamd::NKnobs]; \n      StorageIndex stats [internal::Colamd::NStats];\n      internal::Colamd::set_defaults(knobs);\n      \n      IndexVector p(n+1), A(Alen); \n      for(StorageIndex i=0; i <= n; i++)   p(i) = mat.outerIndexPtr()[i];\n      for(StorageIndex i=0; i < nnz; i++)  A(i) = mat.innerIndexPtr()[i];\n      // Call Colamd routine to compute the ordering \n      StorageIndex info = internal::Colamd::compute_ordering(m, n, Alen, A.data(), p.data(), knobs, stats); \n      EIGEN_UNUSED_VARIABLE(info);\n      eigen_assert( info && \"COLAMD failed \" );\n      \n      perm.resize(n);\n      for (StorageIndex i = 0; i < n; i++) perm.indices()(p(i)) = i;\n    }\n};\n\n} // end namespace Eigen\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/PaStiXSupport/PaStiXSupport.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_PASTIXSUPPORT_H\n#define EIGEN_PASTIXSUPPORT_H\n\nnamespace Eigen { \n\n#if defined(DCOMPLEX)\n  #define PASTIX_COMPLEX  COMPLEX\n  #define PASTIX_DCOMPLEX DCOMPLEX\n#else\n  #define PASTIX_COMPLEX  std::complex<float>\n  #define PASTIX_DCOMPLEX std::complex<double>\n#endif\n\n/** \\ingroup PaStiXSupport_Module\n  * \\brief Interface to the PaStix solver\n  * \n  * This class is used to solve the linear systems A.X = B via the PaStix library. \n  * The matrix can be either real or complex, symmetric or not.\n  *\n  * \\sa TutorialSparseDirectSolvers\n  */\ntemplate<typename _MatrixType, bool IsStrSym = false> class PastixLU;\ntemplate<typename _MatrixType, int Options> class PastixLLT;\ntemplate<typename _MatrixType, int Options> class PastixLDLT;\n\nnamespace internal\n{\n    \n  template<class Pastix> struct pastix_traits;\n\n  template<typename _MatrixType>\n  struct pastix_traits< PastixLU<_MatrixType> >\n  {\n    typedef _MatrixType MatrixType;\n    typedef typename _MatrixType::Scalar Scalar;\n    typedef typename _MatrixType::RealScalar RealScalar;\n    typedef typename _MatrixType::StorageIndex StorageIndex;\n  };\n\n  template<typename _MatrixType, int Options>\n  struct pastix_traits< PastixLLT<_MatrixType,Options> >\n  {\n    typedef _MatrixType MatrixType;\n    typedef typename _MatrixType::Scalar Scalar;\n    typedef typename _MatrixType::RealScalar RealScalar;\n    typedef typename _MatrixType::StorageIndex StorageIndex;\n  };\n\n  template<typename _MatrixType, int Options>\n  struct pastix_traits< PastixLDLT<_MatrixType,Options> >\n  {\n    typedef _MatrixType MatrixType;\n    typedef typename _MatrixType::Scalar Scalar;\n    typedef typename _MatrixType::RealScalar RealScalar;\n    typedef typename _MatrixType::StorageIndex StorageIndex;\n  };\n  \n  inline void eigen_pastix(pastix_data_t **pastix_data, int pastix_comm, int n, int *ptr, int *idx, float *vals, int *perm, int * invp, float *x, int nbrhs, int *iparm, double *dparm)\n  {\n    if (n == 0) { ptr = NULL; idx = NULL; vals = NULL; }\n    if (nbrhs == 0) {x = NULL; nbrhs=1;}\n    s_pastix(pastix_data, pastix_comm, n, ptr, idx, vals, perm, invp, x, nbrhs, iparm, dparm); \n  }\n  \n  inline void eigen_pastix(pastix_data_t **pastix_data, int pastix_comm, int n, int *ptr, int *idx, double *vals, int *perm, int * invp, double *x, int nbrhs, int *iparm, double *dparm)\n  {\n    if (n == 0) { ptr = NULL; idx = NULL; vals = NULL; }\n    if (nbrhs == 0) {x = NULL; nbrhs=1;}\n    d_pastix(pastix_data, pastix_comm, n, ptr, idx, vals, perm, invp, x, nbrhs, iparm, dparm); \n  }\n  \n  inline void eigen_pastix(pastix_data_t **pastix_data, int pastix_comm, int n, int *ptr, int *idx, std::complex<float> *vals, int *perm, int * invp, std::complex<float> *x, int nbrhs, int *iparm, double *dparm)\n  {\n    if (n == 0) { ptr = NULL; idx = NULL; vals = NULL; }\n    if (nbrhs == 0) {x = NULL; nbrhs=1;}\n    c_pastix(pastix_data, pastix_comm, n, ptr, idx, reinterpret_cast<PASTIX_COMPLEX*>(vals), perm, invp, reinterpret_cast<PASTIX_COMPLEX*>(x), nbrhs, iparm, dparm); \n  }\n  \n  inline void eigen_pastix(pastix_data_t **pastix_data, int pastix_comm, int n, int *ptr, int *idx, std::complex<double> *vals, int *perm, int * invp, std::complex<double> *x, int nbrhs, int *iparm, double *dparm)\n  {\n    if (n == 0) { ptr = NULL; idx = NULL; vals = NULL; }\n    if (nbrhs == 0) {x = NULL; nbrhs=1;}\n    z_pastix(pastix_data, pastix_comm, n, ptr, idx, reinterpret_cast<PASTIX_DCOMPLEX*>(vals), perm, invp, reinterpret_cast<PASTIX_DCOMPLEX*>(x), nbrhs, iparm, dparm); \n  }\n\n  // Convert the matrix  to Fortran-style Numbering\n  template <typename MatrixType>\n  void c_to_fortran_numbering (MatrixType& mat)\n  {\n    if ( !(mat.outerIndexPtr()[0]) ) \n    { \n      int i;\n      for(i = 0; i <= mat.rows(); ++i)\n        ++mat.outerIndexPtr()[i];\n      for(i = 0; i < mat.nonZeros(); ++i)\n        ++mat.innerIndexPtr()[i];\n    }\n  }\n  \n  // Convert to C-style Numbering\n  template <typename MatrixType>\n  void fortran_to_c_numbering (MatrixType& mat)\n  {\n    // Check the Numbering\n    if ( mat.outerIndexPtr()[0] == 1 ) \n    { // Convert to C-style numbering\n      int i;\n      for(i = 0; i <= mat.rows(); ++i)\n        --mat.outerIndexPtr()[i];\n      for(i = 0; i < mat.nonZeros(); ++i)\n        --mat.innerIndexPtr()[i];\n    }\n  }\n}\n\n// This is the base class to interface with PaStiX functions. \n// Users should not used this class directly. \ntemplate <class Derived>\nclass PastixBase : public SparseSolverBase<Derived>\n{\n  protected:\n    typedef SparseSolverBase<Derived> Base;\n    using Base::derived;\n    using Base::m_isInitialized;\n  public:\n    using Base::_solve_impl;\n    \n    typedef typename internal::pastix_traits<Derived>::MatrixType _MatrixType;\n    typedef _MatrixType MatrixType;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef Matrix<Scalar,Dynamic,1> Vector;\n    typedef SparseMatrix<Scalar, ColMajor> ColSpMatrix;\n    enum {\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n    \n  public:\n    \n    PastixBase() : m_initisOk(false), m_analysisIsOk(false), m_factorizationIsOk(false), m_pastixdata(0), m_size(0)\n    {\n      init();\n    }\n    \n    ~PastixBase() \n    {\n      clean();\n    }\n    \n    template<typename Rhs,typename Dest>\n    bool _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &x) const;\n    \n    /** Returns a reference to the integer vector IPARM of PaStiX parameters\n      * to modify the default parameters. \n      * The statistics related to the different phases of factorization and solve are saved here as well\n      * \\sa analyzePattern() factorize()\n      */\n    Array<StorageIndex,IPARM_SIZE,1>& iparm()\n    {\n      return m_iparm; \n    }\n    \n    /** Return a reference to a particular index parameter of the IPARM vector \n     * \\sa iparm()\n     */\n    \n    int& iparm(int idxparam)\n    {\n      return m_iparm(idxparam);\n    }\n    \n     /** Returns a reference to the double vector DPARM of PaStiX parameters \n      * The statistics related to the different phases of factorization and solve are saved here as well\n      * \\sa analyzePattern() factorize()\n      */\n    Array<double,DPARM_SIZE,1>& dparm()\n    {\n      return m_dparm; \n    }\n    \n    \n    /** Return a reference to a particular index parameter of the DPARM vector \n     * \\sa dparm()\n     */\n    double& dparm(int idxparam)\n    {\n      return m_dparm(idxparam);\n    }\n    \n    inline Index cols() const { return m_size; }\n    inline Index rows() const { return m_size; }\n    \n     /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the PaStiX reports a problem\n      *          \\c InvalidInput if the input matrix is invalid\n      *\n      * \\sa iparm()          \n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_info;\n    }\n    \n  protected:\n\n    // Initialize the Pastix data structure, check the matrix\n    void init(); \n    \n    // Compute the ordering and the symbolic factorization\n    void analyzePattern(ColSpMatrix& mat);\n    \n    // Compute the numerical factorization\n    void factorize(ColSpMatrix& mat);\n    \n    // Free all the data allocated by Pastix\n    void clean()\n    {\n      eigen_assert(m_initisOk && \"The Pastix structure should be allocated first\"); \n      m_iparm(IPARM_START_TASK) = API_TASK_CLEAN;\n      m_iparm(IPARM_END_TASK) = API_TASK_CLEAN;\n      internal::eigen_pastix(&m_pastixdata, MPI_COMM_WORLD, 0, 0, 0, (Scalar*)0,\n                             m_perm.data(), m_invp.data(), 0, 0, m_iparm.data(), m_dparm.data());\n    }\n    \n    void compute(ColSpMatrix& mat);\n    \n    int m_initisOk; \n    int m_analysisIsOk;\n    int m_factorizationIsOk;\n    mutable ComputationInfo m_info; \n    mutable pastix_data_t *m_pastixdata; // Data structure for pastix\n    mutable int m_comm; // The MPI communicator identifier\n    mutable Array<int,IPARM_SIZE,1> m_iparm; // integer vector for the input parameters\n    mutable Array<double,DPARM_SIZE,1> m_dparm; // Scalar vector for the input parameters\n    mutable Matrix<StorageIndex,Dynamic,1> m_perm;  // Permutation vector\n    mutable Matrix<StorageIndex,Dynamic,1> m_invp;  // Inverse permutation vector\n    mutable int m_size; // Size of the matrix \n}; \n\n /** Initialize the PaStiX data structure. \n   *A first call to this function fills iparm and dparm with the default PaStiX parameters\n   * \\sa iparm() dparm()\n   */\ntemplate <class Derived>\nvoid PastixBase<Derived>::init()\n{\n  m_size = 0; \n  m_iparm.setZero(IPARM_SIZE);\n  m_dparm.setZero(DPARM_SIZE);\n  \n  m_iparm(IPARM_MODIFY_PARAMETER) = API_NO;\n  pastix(&m_pastixdata, MPI_COMM_WORLD,\n         0, 0, 0, 0,\n         0, 0, 0, 1, m_iparm.data(), m_dparm.data());\n  \n  m_iparm[IPARM_MATRIX_VERIFICATION] = API_NO;\n  m_iparm[IPARM_VERBOSE]             = API_VERBOSE_NOT;\n  m_iparm[IPARM_ORDERING]            = API_ORDER_SCOTCH;\n  m_iparm[IPARM_INCOMPLETE]          = API_NO;\n  m_iparm[IPARM_OOC_LIMIT]           = 2000;\n  m_iparm[IPARM_RHS_MAKING]          = API_RHS_B;\n  m_iparm(IPARM_MATRIX_VERIFICATION) = API_NO;\n  \n  m_iparm(IPARM_START_TASK) = API_TASK_INIT;\n  m_iparm(IPARM_END_TASK) = API_TASK_INIT;\n  internal::eigen_pastix(&m_pastixdata, MPI_COMM_WORLD, 0, 0, 0, (Scalar*)0,\n                         0, 0, 0, 0, m_iparm.data(), m_dparm.data());\n  \n  // Check the returned error\n  if(m_iparm(IPARM_ERROR_NUMBER)) {\n    m_info = InvalidInput;\n    m_initisOk = false;\n  }\n  else { \n    m_info = Success;\n    m_initisOk = true;\n  }\n}\n\ntemplate <class Derived>\nvoid PastixBase<Derived>::compute(ColSpMatrix& mat)\n{\n  eigen_assert(mat.rows() == mat.cols() && \"The input matrix should be squared\");\n  \n  analyzePattern(mat);  \n  factorize(mat);\n  \n  m_iparm(IPARM_MATRIX_VERIFICATION) = API_NO;\n}\n\n\ntemplate <class Derived>\nvoid PastixBase<Derived>::analyzePattern(ColSpMatrix& mat)\n{                         \n  eigen_assert(m_initisOk && \"The initialization of PaSTiX failed\");\n  \n  // clean previous calls\n  if(m_size>0)\n    clean();\n  \n  m_size = internal::convert_index<int>(mat.rows());\n  m_perm.resize(m_size);\n  m_invp.resize(m_size);\n  \n  m_iparm(IPARM_START_TASK) = API_TASK_ORDERING;\n  m_iparm(IPARM_END_TASK) = API_TASK_ANALYSE;\n  internal::eigen_pastix(&m_pastixdata, MPI_COMM_WORLD, m_size, mat.outerIndexPtr(), mat.innerIndexPtr(),\n               mat.valuePtr(), m_perm.data(), m_invp.data(), 0, 0, m_iparm.data(), m_dparm.data());\n  \n  // Check the returned error\n  if(m_iparm(IPARM_ERROR_NUMBER))\n  {\n    m_info = NumericalIssue;\n    m_analysisIsOk = false;\n  }\n  else\n  { \n    m_info = Success;\n    m_analysisIsOk = true;\n  }\n}\n\ntemplate <class Derived>\nvoid PastixBase<Derived>::factorize(ColSpMatrix& mat)\n{\n//   if(&m_cpyMat != &mat) m_cpyMat = mat;\n  eigen_assert(m_analysisIsOk && \"The analysis phase should be called before the factorization phase\");\n  m_iparm(IPARM_START_TASK) = API_TASK_NUMFACT;\n  m_iparm(IPARM_END_TASK) = API_TASK_NUMFACT;\n  m_size = internal::convert_index<int>(mat.rows());\n  \n  internal::eigen_pastix(&m_pastixdata, MPI_COMM_WORLD, m_size, mat.outerIndexPtr(), mat.innerIndexPtr(),\n               mat.valuePtr(), m_perm.data(), m_invp.data(), 0, 0, m_iparm.data(), m_dparm.data());\n  \n  // Check the returned error\n  if(m_iparm(IPARM_ERROR_NUMBER))\n  {\n    m_info = NumericalIssue;\n    m_factorizationIsOk = false;\n    m_isInitialized = false;\n  }\n  else\n  {\n    m_info = Success;\n    m_factorizationIsOk = true;\n    m_isInitialized = true;\n  }\n}\n\n/* Solve the system */\ntemplate<typename Base>\ntemplate<typename Rhs,typename Dest>\nbool PastixBase<Base>::_solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &x) const\n{\n  eigen_assert(m_isInitialized && \"The matrix should be factorized first\");\n  EIGEN_STATIC_ASSERT((Dest::Flags&RowMajorBit)==0,\n                     THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES);\n  int rhs = 1;\n  \n  x = b; /* on return, x is overwritten by the computed solution */\n  \n  for (int i = 0; i < b.cols(); i++){\n    m_iparm[IPARM_START_TASK]          = API_TASK_SOLVE;\n    m_iparm[IPARM_END_TASK]            = API_TASK_REFINE;\n  \n    internal::eigen_pastix(&m_pastixdata, MPI_COMM_WORLD, internal::convert_index<int>(x.rows()), 0, 0, 0,\n                           m_perm.data(), m_invp.data(), &x(0, i), rhs, m_iparm.data(), m_dparm.data());\n  }\n  \n  // Check the returned error\n  m_info = m_iparm(IPARM_ERROR_NUMBER)==0 ? Success : NumericalIssue;\n  \n  return m_iparm(IPARM_ERROR_NUMBER)==0;\n}\n\n/** \\ingroup PaStiXSupport_Module\n  * \\class PastixLU\n  * \\brief Sparse direct LU solver based on PaStiX library\n  * \n  * This class is used to solve the linear systems A.X = B with a supernodal LU \n  * factorization in the PaStiX library. The matrix A should be squared and nonsingular\n  * PaStiX requires that the matrix A has a symmetric structural pattern. \n  * This interface can symmetrize the input matrix otherwise. \n  * The vectors or matrices X and B can be either dense or sparse.\n  * \n  * \\tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam IsStrSym Indicates if the input matrix has a symmetric pattern, default is false\n  * NOTE : Note that if the analysis and factorization phase are called separately, \n  * the input matrix will be symmetrized at each call, hence it is advised to \n  * symmetrize the matrix in a end-user program and set \\p IsStrSym to true\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class SparseLU\n  * \n  */\ntemplate<typename _MatrixType, bool IsStrSym>\nclass PastixLU : public PastixBase< PastixLU<_MatrixType> >\n{\n  public:\n    typedef _MatrixType MatrixType;\n    typedef PastixBase<PastixLU<MatrixType> > Base;\n    typedef typename Base::ColSpMatrix ColSpMatrix;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    \n  public:\n    PastixLU() : Base()\n    {\n      init();\n    }\n    \n    explicit PastixLU(const MatrixType& matrix):Base()\n    {\n      init();\n      compute(matrix);\n    }\n    /** Compute the LU supernodal factorization of \\p matrix. \n      * iparm and dparm can be used to tune the PaStiX parameters. \n      * see the PaStiX user's manual\n      * \\sa analyzePattern() factorize()\n      */\n    void compute (const MatrixType& matrix)\n    {\n      m_structureIsUptodate = false;\n      ColSpMatrix temp;\n      grabMatrix(matrix, temp);\n      Base::compute(temp);\n    }\n    /** Compute the LU symbolic factorization of \\p matrix using its sparsity pattern. \n      * Several ordering methods can be used at this step. See the PaStiX user's manual. \n      * The result of this operation can be used with successive matrices having the same pattern as \\p matrix\n      * \\sa factorize()\n      */\n    void analyzePattern(const MatrixType& matrix)\n    {\n      m_structureIsUptodate = false;\n      ColSpMatrix temp;\n      grabMatrix(matrix, temp);\n      Base::analyzePattern(temp);\n    }\n\n    /** Compute the LU supernodal factorization of \\p matrix\n      * WARNING The matrix \\p matrix should have the same structural pattern \n      * as the same used in the analysis phase.\n      * \\sa analyzePattern()\n      */ \n    void factorize(const MatrixType& matrix)\n    {\n      ColSpMatrix temp;\n      grabMatrix(matrix, temp);\n      Base::factorize(temp);\n    }\n  protected:\n    \n    void init()\n    {\n      m_structureIsUptodate = false;\n      m_iparm(IPARM_SYM) = API_SYM_NO;\n      m_iparm(IPARM_FACTORIZATION) = API_FACT_LU;\n    }\n    \n    void grabMatrix(const MatrixType& matrix, ColSpMatrix& out)\n    {\n      if(IsStrSym)\n        out = matrix;\n      else\n      {\n        if(!m_structureIsUptodate)\n        {\n          // update the transposed structure\n          m_transposedStructure = matrix.transpose();\n          \n          // Set the elements of the matrix to zero \n          for (Index j=0; j<m_transposedStructure.outerSize(); ++j) \n            for(typename ColSpMatrix::InnerIterator it(m_transposedStructure, j); it; ++it)\n              it.valueRef() = 0.0;\n\n          m_structureIsUptodate = true;\n        }\n        \n        out = m_transposedStructure + matrix;\n      }\n      internal::c_to_fortran_numbering(out);\n    }\n    \n    using Base::m_iparm;\n    using Base::m_dparm;\n    \n    ColSpMatrix m_transposedStructure;\n    bool m_structureIsUptodate;\n};\n\n/** \\ingroup PaStiXSupport_Module\n  * \\class PastixLLT\n  * \\brief A sparse direct supernodal Cholesky (LLT) factorization and solver based on the PaStiX library\n  * \n  * This class is used to solve the linear systems A.X = B via a LL^T supernodal Cholesky factorization\n  * available in the PaStiX library. The matrix A should be symmetric and positive definite\n  * WARNING Selfadjoint complex matrices are not supported in the current version of PaStiX\n  * The vectors or matrices X and B can be either dense or sparse\n  * \n  * \\tparam MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam UpLo The part of the matrix to use : Lower or Upper. The default is Lower as required by PaStiX\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class SimplicialLLT\n  */\ntemplate<typename _MatrixType, int _UpLo>\nclass PastixLLT : public PastixBase< PastixLLT<_MatrixType, _UpLo> >\n{\n  public:\n    typedef _MatrixType MatrixType;\n    typedef PastixBase<PastixLLT<MatrixType, _UpLo> > Base;\n    typedef typename Base::ColSpMatrix ColSpMatrix;\n    \n  public:\n    enum { UpLo = _UpLo };\n    PastixLLT() : Base()\n    {\n      init();\n    }\n    \n    explicit PastixLLT(const MatrixType& matrix):Base()\n    {\n      init();\n      compute(matrix);\n    }\n\n    /** Compute the L factor of the LL^T supernodal factorization of \\p matrix \n      * \\sa analyzePattern() factorize()\n      */\n    void compute (const MatrixType& matrix)\n    {\n      ColSpMatrix temp;\n      grabMatrix(matrix, temp);\n      Base::compute(temp);\n    }\n\n     /** Compute the LL^T symbolic factorization of \\p matrix using its sparsity pattern\n      * The result of this operation can be used with successive matrices having the same pattern as \\p matrix\n      * \\sa factorize()\n      */\n    void analyzePattern(const MatrixType& matrix)\n    {\n      ColSpMatrix temp;\n      grabMatrix(matrix, temp);\n      Base::analyzePattern(temp);\n    }\n      /** Compute the LL^T supernodal numerical factorization of \\p matrix \n        * \\sa analyzePattern()\n        */\n    void factorize(const MatrixType& matrix)\n    {\n      ColSpMatrix temp;\n      grabMatrix(matrix, temp);\n      Base::factorize(temp);\n    }\n  protected:\n    using Base::m_iparm;\n    \n    void init()\n    {\n      m_iparm(IPARM_SYM) = API_SYM_YES;\n      m_iparm(IPARM_FACTORIZATION) = API_FACT_LLT;\n    }\n    \n    void grabMatrix(const MatrixType& matrix, ColSpMatrix& out)\n    {\n      out.resize(matrix.rows(), matrix.cols());\n      // Pastix supports only lower, column-major matrices \n      out.template selfadjointView<Lower>() = matrix.template selfadjointView<UpLo>();\n      internal::c_to_fortran_numbering(out);\n    }\n};\n\n/** \\ingroup PaStiXSupport_Module\n  * \\class PastixLDLT\n  * \\brief A sparse direct supernodal Cholesky (LLT) factorization and solver based on the PaStiX library\n  * \n  * This class is used to solve the linear systems A.X = B via a LDL^T supernodal Cholesky factorization\n  * available in the PaStiX library. The matrix A should be symmetric and positive definite\n  * WARNING Selfadjoint complex matrices are not supported in the current version of PaStiX\n  * The vectors or matrices X and B can be either dense or sparse\n  * \n  * \\tparam MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam UpLo The part of the matrix to use : Lower or Upper. The default is Lower as required by PaStiX\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class SimplicialLDLT\n  */\ntemplate<typename _MatrixType, int _UpLo>\nclass PastixLDLT : public PastixBase< PastixLDLT<_MatrixType, _UpLo> >\n{\n  public:\n    typedef _MatrixType MatrixType;\n    typedef PastixBase<PastixLDLT<MatrixType, _UpLo> > Base; \n    typedef typename Base::ColSpMatrix ColSpMatrix;\n    \n  public:\n    enum { UpLo = _UpLo };\n    PastixLDLT():Base()\n    {\n      init();\n    }\n    \n    explicit PastixLDLT(const MatrixType& matrix):Base()\n    {\n      init();\n      compute(matrix);\n    }\n\n    /** Compute the L and D factors of the LDL^T factorization of \\p matrix \n      * \\sa analyzePattern() factorize()\n      */\n    void compute (const MatrixType& matrix)\n    {\n      ColSpMatrix temp;\n      grabMatrix(matrix, temp);\n      Base::compute(temp);\n    }\n\n    /** Compute the LDL^T symbolic factorization of \\p matrix using its sparsity pattern\n      * The result of this operation can be used with successive matrices having the same pattern as \\p matrix\n      * \\sa factorize()\n      */\n    void analyzePattern(const MatrixType& matrix)\n    { \n      ColSpMatrix temp;\n      grabMatrix(matrix, temp);\n      Base::analyzePattern(temp);\n    }\n    /** Compute the LDL^T supernodal numerical factorization of \\p matrix \n      * \n      */\n    void factorize(const MatrixType& matrix)\n    {\n      ColSpMatrix temp;\n      grabMatrix(matrix, temp);\n      Base::factorize(temp);\n    }\n\n  protected:\n    using Base::m_iparm;\n    \n    void init()\n    {\n      m_iparm(IPARM_SYM) = API_SYM_YES;\n      m_iparm(IPARM_FACTORIZATION) = API_FACT_LDLT;\n    }\n    \n    void grabMatrix(const MatrixType& matrix, ColSpMatrix& out)\n    {\n      // Pastix supports only lower, column-major matrices \n      out.resize(matrix.rows(), matrix.cols());\n      out.template selfadjointView<Lower>() = matrix.template selfadjointView<UpLo>();\n      internal::c_to_fortran_numbering(out);\n    }\n};\n\n} // end namespace Eigen\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/PardisoSupport/PardisoSupport.h",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Eigen bindings to Intel(R) MKL PARDISO\n ********************************************************************************\n*/\n\n#ifndef EIGEN_PARDISOSUPPORT_H\n#define EIGEN_PARDISOSUPPORT_H\n\nnamespace Eigen { \n\ntemplate<typename _MatrixType> class PardisoLU;\ntemplate<typename _MatrixType, int Options=Upper> class PardisoLLT;\ntemplate<typename _MatrixType, int Options=Upper> class PardisoLDLT;\n\nnamespace internal\n{\n  template<typename IndexType>\n  struct pardiso_run_selector\n  {\n    static IndexType run( _MKL_DSS_HANDLE_t pt, IndexType maxfct, IndexType mnum, IndexType type, IndexType phase, IndexType n, void *a,\n                      IndexType *ia, IndexType *ja, IndexType *perm, IndexType nrhs, IndexType *iparm, IndexType msglvl, void *b, void *x)\n    {\n      IndexType error = 0;\n      ::pardiso(pt, &maxfct, &mnum, &type, &phase, &n, a, ia, ja, perm, &nrhs, iparm, &msglvl, b, x, &error);\n      return error;\n    }\n  };\n  template<>\n  struct pardiso_run_selector<long long int>\n  {\n    typedef long long int IndexType;\n    static IndexType run( _MKL_DSS_HANDLE_t pt, IndexType maxfct, IndexType mnum, IndexType type, IndexType phase, IndexType n, void *a,\n                      IndexType *ia, IndexType *ja, IndexType *perm, IndexType nrhs, IndexType *iparm, IndexType msglvl, void *b, void *x)\n    {\n      IndexType error = 0;\n      ::pardiso_64(pt, &maxfct, &mnum, &type, &phase, &n, a, ia, ja, perm, &nrhs, iparm, &msglvl, b, x, &error);\n      return error;\n    }\n  };\n\n  template<class Pardiso> struct pardiso_traits;\n\n  template<typename _MatrixType>\n  struct pardiso_traits< PardisoLU<_MatrixType> >\n  {\n    typedef _MatrixType MatrixType;\n    typedef typename _MatrixType::Scalar Scalar;\n    typedef typename _MatrixType::RealScalar RealScalar;\n    typedef typename _MatrixType::StorageIndex StorageIndex;\n  };\n\n  template<typename _MatrixType, int Options>\n  struct pardiso_traits< PardisoLLT<_MatrixType, Options> >\n  {\n    typedef _MatrixType MatrixType;\n    typedef typename _MatrixType::Scalar Scalar;\n    typedef typename _MatrixType::RealScalar RealScalar;\n    typedef typename _MatrixType::StorageIndex StorageIndex;\n  };\n\n  template<typename _MatrixType, int Options>\n  struct pardiso_traits< PardisoLDLT<_MatrixType, Options> >\n  {\n    typedef _MatrixType MatrixType;\n    typedef typename _MatrixType::Scalar Scalar;\n    typedef typename _MatrixType::RealScalar RealScalar;\n    typedef typename _MatrixType::StorageIndex StorageIndex;    \n  };\n\n} // end namespace internal\n\ntemplate<class Derived>\nclass PardisoImpl : public SparseSolverBase<Derived>\n{\n  protected:\n    typedef SparseSolverBase<Derived> Base;\n    using Base::derived;\n    using Base::m_isInitialized;\n    \n    typedef internal::pardiso_traits<Derived> Traits;\n  public:\n    using Base::_solve_impl;\n    \n    typedef typename Traits::MatrixType MatrixType;\n    typedef typename Traits::Scalar Scalar;\n    typedef typename Traits::RealScalar RealScalar;\n    typedef typename Traits::StorageIndex StorageIndex;\n    typedef SparseMatrix<Scalar,RowMajor,StorageIndex> SparseMatrixType;\n    typedef Matrix<Scalar,Dynamic,1> VectorType;\n    typedef Matrix<StorageIndex, 1, MatrixType::ColsAtCompileTime> IntRowVectorType;\n    typedef Matrix<StorageIndex, MatrixType::RowsAtCompileTime, 1> IntColVectorType;\n    typedef Array<StorageIndex,64,1,DontAlign> ParameterType;\n    enum {\n      ScalarIsComplex = NumTraits<Scalar>::IsComplex,\n      ColsAtCompileTime = Dynamic,\n      MaxColsAtCompileTime = Dynamic\n    };\n\n    PardisoImpl()\n      : m_analysisIsOk(false), m_factorizationIsOk(false)\n    {\n      eigen_assert((sizeof(StorageIndex) >= sizeof(_INTEGER_t) && sizeof(StorageIndex) <= 8) && \"Non-supported index type\");\n      m_iparm.setZero();\n      m_msglvl = 0; // No output\n      m_isInitialized = false;\n    }\n\n    ~PardisoImpl()\n    {\n      pardisoRelease();\n    }\n\n    inline Index cols() const { return m_size; }\n    inline Index rows() const { return m_size; }\n  \n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the matrix appears to be negative.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_info;\n    }\n\n    /** \\warning for advanced usage only.\n      * \\returns a reference to the parameter array controlling PARDISO.\n      * See the PARDISO manual to know how to use it. */\n    ParameterType& pardisoParameterArray()\n    {\n      return m_iparm;\n    }\n    \n    /** Performs a symbolic decomposition on the sparcity of \\a matrix.\n      *\n      * This function is particularly useful when solving for several problems having the same structure.\n      * \n      * \\sa factorize()\n      */\n    Derived& analyzePattern(const MatrixType& matrix);\n    \n    /** Performs a numeric decomposition of \\a matrix\n      *\n      * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed.\n      *\n      * \\sa analyzePattern()\n      */\n    Derived& factorize(const MatrixType& matrix);\n\n    Derived& compute(const MatrixType& matrix);\n\n    template<typename Rhs,typename Dest>\n    void _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const;\n\n  protected:\n    void pardisoRelease()\n    {\n      if(m_isInitialized) // Factorization ran at least once\n      {\n        internal::pardiso_run_selector<StorageIndex>::run(m_pt, 1, 1, m_type, -1, internal::convert_index<StorageIndex>(m_size),0, 0, 0, m_perm.data(), 0,\n                                                          m_iparm.data(), m_msglvl, NULL, NULL);\n        m_isInitialized = false;\n      }\n    }\n\n    void pardisoInit(int type)\n    {\n      m_type = type;\n      bool symmetric = std::abs(m_type) < 10;\n      m_iparm[0] = 1;   // No solver default\n      m_iparm[1] = 2;   // use Metis for the ordering\n      m_iparm[2] = 0;   // Reserved. Set to zero. (??Numbers of processors, value of OMP_NUM_THREADS??)\n      m_iparm[3] = 0;   // No iterative-direct algorithm\n      m_iparm[4] = 0;   // No user fill-in reducing permutation\n      m_iparm[5] = 0;   // Write solution into x, b is left unchanged\n      m_iparm[6] = 0;   // Not in use\n      m_iparm[7] = 2;   // Max numbers of iterative refinement steps\n      m_iparm[8] = 0;   // Not in use\n      m_iparm[9] = 13;  // Perturb the pivot elements with 1E-13\n      m_iparm[10] = symmetric ? 0 : 1; // Use nonsymmetric permutation and scaling MPS\n      m_iparm[11] = 0;  // Not in use\n      m_iparm[12] = symmetric ? 0 : 1;  // Maximum weighted matching algorithm is switched-off (default for symmetric).\n                                        // Try m_iparm[12] = 1 in case of inappropriate accuracy\n      m_iparm[13] = 0;  // Output: Number of perturbed pivots\n      m_iparm[14] = 0;  // Not in use\n      m_iparm[15] = 0;  // Not in use\n      m_iparm[16] = 0;  // Not in use\n      m_iparm[17] = -1; // Output: Number of nonzeros in the factor LU\n      m_iparm[18] = -1; // Output: Mflops for LU factorization\n      m_iparm[19] = 0;  // Output: Numbers of CG Iterations\n      \n      m_iparm[20] = 0;  // 1x1 pivoting\n      m_iparm[26] = 0;  // No matrix checker\n      m_iparm[27] = (sizeof(RealScalar) == 4) ? 1 : 0;\n      m_iparm[34] = 1;  // C indexing\n      m_iparm[36] = 0;  // CSR\n      m_iparm[59] = 0;  // 0 - In-Core ; 1 - Automatic switch between In-Core and Out-of-Core modes ; 2 - Out-of-Core\n      \n      memset(m_pt, 0, sizeof(m_pt));\n    }\n\n  protected:\n    // cached data to reduce reallocation, etc.\n    \n    void manageErrorCode(Index error) const\n    {\n      switch(error)\n      {\n        case 0:\n          m_info = Success;\n          break;\n        case -4:\n        case -7:\n          m_info = NumericalIssue;\n          break;\n        default:\n          m_info = InvalidInput;\n      }\n    }\n\n    mutable SparseMatrixType m_matrix;\n    mutable ComputationInfo m_info;\n    bool m_analysisIsOk, m_factorizationIsOk;\n    StorageIndex m_type, m_msglvl;\n    mutable void *m_pt[64];\n    mutable ParameterType m_iparm;\n    mutable IntColVectorType m_perm;\n    Index m_size;\n    \n};\n\ntemplate<class Derived>\nDerived& PardisoImpl<Derived>::compute(const MatrixType& a)\n{\n  m_size = a.rows();\n  eigen_assert(a.rows() == a.cols());\n\n  pardisoRelease();\n  m_perm.setZero(m_size);\n  derived().getMatrix(a);\n  \n  Index error;\n  error = internal::pardiso_run_selector<StorageIndex>::run(m_pt, 1, 1, m_type, 12, internal::convert_index<StorageIndex>(m_size),\n                                                            m_matrix.valuePtr(), m_matrix.outerIndexPtr(), m_matrix.innerIndexPtr(),\n                                                            m_perm.data(), 0, m_iparm.data(), m_msglvl, NULL, NULL);\n  manageErrorCode(error);\n  m_analysisIsOk = true;\n  m_factorizationIsOk = true;\n  m_isInitialized = true;\n  return derived();\n}\n\ntemplate<class Derived>\nDerived& PardisoImpl<Derived>::analyzePattern(const MatrixType& a)\n{\n  m_size = a.rows();\n  eigen_assert(m_size == a.cols());\n\n  pardisoRelease();\n  m_perm.setZero(m_size);\n  derived().getMatrix(a);\n  \n  Index error;\n  error = internal::pardiso_run_selector<StorageIndex>::run(m_pt, 1, 1, m_type, 11, internal::convert_index<StorageIndex>(m_size),\n                                                            m_matrix.valuePtr(), m_matrix.outerIndexPtr(), m_matrix.innerIndexPtr(),\n                                                            m_perm.data(), 0, m_iparm.data(), m_msglvl, NULL, NULL);\n  \n  manageErrorCode(error);\n  m_analysisIsOk = true;\n  m_factorizationIsOk = false;\n  m_isInitialized = true;\n  return derived();\n}\n\ntemplate<class Derived>\nDerived& PardisoImpl<Derived>::factorize(const MatrixType& a)\n{\n  eigen_assert(m_analysisIsOk && \"You must first call analyzePattern()\");\n  eigen_assert(m_size == a.rows() && m_size == a.cols());\n  \n  derived().getMatrix(a);\n\n  Index error;\n  error = internal::pardiso_run_selector<StorageIndex>::run(m_pt, 1, 1, m_type, 22, internal::convert_index<StorageIndex>(m_size),\n                                                            m_matrix.valuePtr(), m_matrix.outerIndexPtr(), m_matrix.innerIndexPtr(),\n                                                            m_perm.data(), 0, m_iparm.data(), m_msglvl, NULL, NULL);\n  \n  manageErrorCode(error);\n  m_factorizationIsOk = true;\n  return derived();\n}\n\ntemplate<class Derived>\ntemplate<typename BDerived,typename XDerived>\nvoid PardisoImpl<Derived>::_solve_impl(const MatrixBase<BDerived> &b, MatrixBase<XDerived>& x) const\n{\n  if(m_iparm[0] == 0) // Factorization was not computed\n  {\n    m_info = InvalidInput;\n    return;\n  }\n\n  //Index n = m_matrix.rows();\n  Index nrhs = Index(b.cols());\n  eigen_assert(m_size==b.rows());\n  eigen_assert(((MatrixBase<BDerived>::Flags & RowMajorBit) == 0 || nrhs == 1) && \"Row-major right hand sides are not supported\");\n  eigen_assert(((MatrixBase<XDerived>::Flags & RowMajorBit) == 0 || nrhs == 1) && \"Row-major matrices of unknowns are not supported\");\n  eigen_assert(((nrhs == 1) || b.outerStride() == b.rows()));\n\n\n//  switch (transposed) {\n//    case SvNoTrans    : m_iparm[11] = 0 ; break;\n//    case SvTranspose  : m_iparm[11] = 2 ; break;\n//    case SvAdjoint    : m_iparm[11] = 1 ; break;\n//    default:\n//      //std::cerr << \"Eigen: transposition  option \\\"\" << transposed << \"\\\" not supported by the PARDISO backend\\n\";\n//      m_iparm[11] = 0;\n//  }\n\n  Scalar* rhs_ptr = const_cast<Scalar*>(b.derived().data());\n  Matrix<Scalar,Dynamic,Dynamic,ColMajor> tmp;\n  \n  // Pardiso cannot solve in-place\n  if(rhs_ptr == x.derived().data())\n  {\n    tmp = b;\n    rhs_ptr = tmp.data();\n  }\n  \n  Index error;\n  error = internal::pardiso_run_selector<StorageIndex>::run(m_pt, 1, 1, m_type, 33, internal::convert_index<StorageIndex>(m_size),\n                                                            m_matrix.valuePtr(), m_matrix.outerIndexPtr(), m_matrix.innerIndexPtr(),\n                                                            m_perm.data(), internal::convert_index<StorageIndex>(nrhs), m_iparm.data(), m_msglvl,\n                                                            rhs_ptr, x.derived().data());\n\n  manageErrorCode(error);\n}\n\n\n/** \\ingroup PardisoSupport_Module\n  * \\class PardisoLU\n  * \\brief A sparse direct LU factorization and solver based on the PARDISO library\n  *\n  * This class allows to solve for A.X = B sparse linear problems via a direct LU factorization\n  * using the Intel MKL PARDISO library. The sparse matrix A must be squared and invertible.\n  * The vectors or matrices X and B can be either dense or sparse.\n  *\n  * By default, it runs in in-core mode. To enable PARDISO's out-of-core feature, set:\n  * \\code solver.pardisoParameterArray()[59] = 1; \\endcode\n  *\n  * \\tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class SparseLU\n  */\ntemplate<typename MatrixType>\nclass PardisoLU : public PardisoImpl< PardisoLU<MatrixType> >\n{\n  protected:\n    typedef PardisoImpl<PardisoLU> Base;\n    using Base::pardisoInit;\n    using Base::m_matrix;\n    friend class PardisoImpl< PardisoLU<MatrixType> >;\n\n  public:\n\n    typedef typename Base::Scalar Scalar;\n    typedef typename Base::RealScalar RealScalar;\n\n    using Base::compute;\n    using Base::solve;\n\n    PardisoLU()\n      : Base()\n    {\n      pardisoInit(Base::ScalarIsComplex ? 13 : 11);\n    }\n\n    explicit PardisoLU(const MatrixType& matrix)\n      : Base()\n    {\n      pardisoInit(Base::ScalarIsComplex ? 13 : 11);\n      compute(matrix);\n    }\n  protected:\n    void getMatrix(const MatrixType& matrix)\n    {\n      m_matrix = matrix;\n      m_matrix.makeCompressed();\n    }\n};\n\n/** \\ingroup PardisoSupport_Module\n  * \\class PardisoLLT\n  * \\brief A sparse direct Cholesky (LLT) factorization and solver based on the PARDISO library\n  *\n  * This class allows to solve for A.X = B sparse linear problems via a LL^T Cholesky factorization\n  * using the Intel MKL PARDISO library. The sparse matrix A must be selfajoint and positive definite.\n  * The vectors or matrices X and B can be either dense or sparse.\n  *\n  * By default, it runs in in-core mode. To enable PARDISO's out-of-core feature, set:\n  * \\code solver.pardisoParameterArray()[59] = 1; \\endcode\n  *\n  * \\tparam MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam UpLo can be any bitwise combination of Upper, Lower. The default is Upper, meaning only the upper triangular part has to be used.\n  *         Upper|Lower can be used to tell both triangular parts can be used as input.\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class SimplicialLLT\n  */\ntemplate<typename MatrixType, int _UpLo>\nclass PardisoLLT : public PardisoImpl< PardisoLLT<MatrixType,_UpLo> >\n{\n  protected:\n    typedef PardisoImpl< PardisoLLT<MatrixType,_UpLo> > Base;\n    using Base::pardisoInit;\n    using Base::m_matrix;\n    friend class PardisoImpl< PardisoLLT<MatrixType,_UpLo> >;\n\n  public:\n\n    typedef typename Base::Scalar Scalar;\n    typedef typename Base::RealScalar RealScalar;\n    typedef typename Base::StorageIndex StorageIndex;\n    enum { UpLo = _UpLo };\n    using Base::compute;\n\n    PardisoLLT()\n      : Base()\n    {\n      pardisoInit(Base::ScalarIsComplex ? 4 : 2);\n    }\n\n    explicit PardisoLLT(const MatrixType& matrix)\n      : Base()\n    {\n      pardisoInit(Base::ScalarIsComplex ? 4 : 2);\n      compute(matrix);\n    }\n    \n  protected:\n    \n    void getMatrix(const MatrixType& matrix)\n    {\n      // PARDISO supports only upper, row-major matrices\n      PermutationMatrix<Dynamic,Dynamic,StorageIndex> p_null;\n      m_matrix.resize(matrix.rows(), matrix.cols());\n      m_matrix.template selfadjointView<Upper>() = matrix.template selfadjointView<UpLo>().twistedBy(p_null);\n      m_matrix.makeCompressed();\n    }\n};\n\n/** \\ingroup PardisoSupport_Module\n  * \\class PardisoLDLT\n  * \\brief A sparse direct Cholesky (LDLT) factorization and solver based on the PARDISO library\n  *\n  * This class allows to solve for A.X = B sparse linear problems via a LDL^T Cholesky factorization\n  * using the Intel MKL PARDISO library. The sparse matrix A is assumed to be selfajoint and positive definite.\n  * For complex matrices, A can also be symmetric only, see the \\a Options template parameter.\n  * The vectors or matrices X and B can be either dense or sparse.\n  *\n  * By default, it runs in in-core mode. To enable PARDISO's out-of-core feature, set:\n  * \\code solver.pardisoParameterArray()[59] = 1; \\endcode\n  *\n  * \\tparam MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam Options can be any bitwise combination of Upper, Lower, and Symmetric. The default is Upper, meaning only the upper triangular part has to be used.\n  *         Symmetric can be used for symmetric, non-selfadjoint complex matrices, the default being to assume a selfadjoint matrix.\n  *         Upper|Lower can be used to tell both triangular parts can be used as input.\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class SimplicialLDLT\n  */\ntemplate<typename MatrixType, int Options>\nclass PardisoLDLT : public PardisoImpl< PardisoLDLT<MatrixType,Options> >\n{\n  protected:\n    typedef PardisoImpl< PardisoLDLT<MatrixType,Options> > Base;\n    using Base::pardisoInit;\n    using Base::m_matrix;\n    friend class PardisoImpl< PardisoLDLT<MatrixType,Options> >;\n\n  public:\n\n    typedef typename Base::Scalar Scalar;\n    typedef typename Base::RealScalar RealScalar;\n    typedef typename Base::StorageIndex StorageIndex;\n    using Base::compute;\n    enum { UpLo = Options&(Upper|Lower) };\n\n    PardisoLDLT()\n      : Base()\n    {\n      pardisoInit(Base::ScalarIsComplex ? ( bool(Options&Symmetric) ? 6 : -4 ) : -2);\n    }\n\n    explicit PardisoLDLT(const MatrixType& matrix)\n      : Base()\n    {\n      pardisoInit(Base::ScalarIsComplex ? ( bool(Options&Symmetric) ? 6 : -4 ) : -2);\n      compute(matrix);\n    }\n    \n    void getMatrix(const MatrixType& matrix)\n    {\n      // PARDISO supports only upper, row-major matrices\n      PermutationMatrix<Dynamic,Dynamic,StorageIndex> p_null;\n      m_matrix.resize(matrix.rows(), matrix.cols());\n      m_matrix.template selfadjointView<Upper>() = matrix.template selfadjointView<UpLo>().twistedBy(p_null);\n      m_matrix.makeCompressed();\n    }\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_PARDISOSUPPORT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/QR/ColPivHouseholderQR.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_COLPIVOTINGHOUSEHOLDERQR_H\n#define EIGEN_COLPIVOTINGHOUSEHOLDERQR_H\n\nnamespace Eigen {\n\nnamespace internal {\ntemplate<typename _MatrixType> struct traits<ColPivHouseholderQR<_MatrixType> >\n : traits<_MatrixType>\n{\n  typedef MatrixXpr XprKind;\n  typedef SolverStorage StorageKind;\n  typedef int StorageIndex;\n  enum { Flags = 0 };\n};\n\n} // end namespace internal\n\n/** \\ingroup QR_Module\n  *\n  * \\class ColPivHouseholderQR\n  *\n  * \\brief Householder rank-revealing QR decomposition of a matrix with column-pivoting\n  *\n  * \\tparam _MatrixType the type of the matrix of which we are computing the QR decomposition\n  *\n  * This class performs a rank-revealing QR decomposition of a matrix \\b A into matrices \\b P, \\b Q and \\b R\n  * such that\n  * \\f[\n  *  \\mathbf{A} \\, \\mathbf{P} = \\mathbf{Q} \\, \\mathbf{R}\n  * \\f]\n  * by using Householder transformations. Here, \\b P is a permutation matrix, \\b Q a unitary matrix and \\b R an\n  * upper triangular matrix.\n  *\n  * This decomposition performs column pivoting in order to be rank-revealing and improve\n  * numerical stability. It is slower than HouseholderQR, and faster than FullPivHouseholderQR.\n  *\n  * This class supports the \\link InplaceDecomposition inplace decomposition \\endlink mechanism.\n  * \n  * \\sa MatrixBase::colPivHouseholderQr()\n  */\ntemplate<typename _MatrixType> class ColPivHouseholderQR\n        : public SolverBase<ColPivHouseholderQR<_MatrixType> >\n{\n  public:\n\n    typedef _MatrixType MatrixType;\n    typedef SolverBase<ColPivHouseholderQR> Base;\n    friend class SolverBase<ColPivHouseholderQR>;\n\n    EIGEN_GENERIC_PUBLIC_INTERFACE(ColPivHouseholderQR)\n    enum {\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n    typedef typename internal::plain_diag_type<MatrixType>::type HCoeffsType;\n    typedef PermutationMatrix<ColsAtCompileTime, MaxColsAtCompileTime> PermutationType;\n    typedef typename internal::plain_row_type<MatrixType, Index>::type IntRowVectorType;\n    typedef typename internal::plain_row_type<MatrixType>::type RowVectorType;\n    typedef typename internal::plain_row_type<MatrixType, RealScalar>::type RealRowVectorType;\n    typedef HouseholderSequence<MatrixType,typename internal::remove_all<typename HCoeffsType::ConjugateReturnType>::type> HouseholderSequenceType;\n    typedef typename MatrixType::PlainObject PlainObject;\n\n  private:\n\n    typedef typename PermutationType::StorageIndex PermIndexType;\n\n  public:\n\n    /**\n    * \\brief Default Constructor.\n    *\n    * The default constructor is useful in cases in which the user intends to\n    * perform decompositions via ColPivHouseholderQR::compute(const MatrixType&).\n    */\n    ColPivHouseholderQR()\n      : m_qr(),\n        m_hCoeffs(),\n        m_colsPermutation(),\n        m_colsTranspositions(),\n        m_temp(),\n        m_colNormsUpdated(),\n        m_colNormsDirect(),\n        m_isInitialized(false),\n        m_usePrescribedThreshold(false) {}\n\n    /** \\brief Default Constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem \\a size.\n      * \\sa ColPivHouseholderQR()\n      */\n    ColPivHouseholderQR(Index rows, Index cols)\n      : m_qr(rows, cols),\n        m_hCoeffs((std::min)(rows,cols)),\n        m_colsPermutation(PermIndexType(cols)),\n        m_colsTranspositions(cols),\n        m_temp(cols),\n        m_colNormsUpdated(cols),\n        m_colNormsDirect(cols),\n        m_isInitialized(false),\n        m_usePrescribedThreshold(false) {}\n\n    /** \\brief Constructs a QR factorization from a given matrix\n      *\n      * This constructor computes the QR factorization of the matrix \\a matrix by calling\n      * the method compute(). It is a short cut for:\n      *\n      * \\code\n      * ColPivHouseholderQR<MatrixType> qr(matrix.rows(), matrix.cols());\n      * qr.compute(matrix);\n      * \\endcode\n      *\n      * \\sa compute()\n      */\n    template<typename InputType>\n    explicit ColPivHouseholderQR(const EigenBase<InputType>& matrix)\n      : m_qr(matrix.rows(), matrix.cols()),\n        m_hCoeffs((std::min)(matrix.rows(),matrix.cols())),\n        m_colsPermutation(PermIndexType(matrix.cols())),\n        m_colsTranspositions(matrix.cols()),\n        m_temp(matrix.cols()),\n        m_colNormsUpdated(matrix.cols()),\n        m_colNormsDirect(matrix.cols()),\n        m_isInitialized(false),\n        m_usePrescribedThreshold(false)\n    {\n      compute(matrix.derived());\n    }\n\n    /** \\brief Constructs a QR factorization from a given matrix\n      *\n      * This overloaded constructor is provided for \\link InplaceDecomposition inplace decomposition \\endlink when \\c MatrixType is a Eigen::Ref.\n      *\n      * \\sa ColPivHouseholderQR(const EigenBase&)\n      */\n    template<typename InputType>\n    explicit ColPivHouseholderQR(EigenBase<InputType>& matrix)\n      : m_qr(matrix.derived()),\n        m_hCoeffs((std::min)(matrix.rows(),matrix.cols())),\n        m_colsPermutation(PermIndexType(matrix.cols())),\n        m_colsTranspositions(matrix.cols()),\n        m_temp(matrix.cols()),\n        m_colNormsUpdated(matrix.cols()),\n        m_colNormsDirect(matrix.cols()),\n        m_isInitialized(false),\n        m_usePrescribedThreshold(false)\n    {\n      computeInPlace();\n    }\n\n    #ifdef EIGEN_PARSED_BY_DOXYGEN\n    /** This method finds a solution x to the equation Ax=b, where A is the matrix of which\n      * *this is the QR decomposition, if any exists.\n      *\n      * \\param b the right-hand-side of the equation to solve.\n      *\n      * \\returns a solution.\n      *\n      * \\note_about_checking_solutions\n      *\n      * \\note_about_arbitrary_choice_of_solution\n      *\n      * Example: \\include ColPivHouseholderQR_solve.cpp\n      * Output: \\verbinclude ColPivHouseholderQR_solve.out\n      */\n    template<typename Rhs>\n    inline const Solve<ColPivHouseholderQR, Rhs>\n    solve(const MatrixBase<Rhs>& b) const;\n    #endif\n\n    HouseholderSequenceType householderQ() const;\n    HouseholderSequenceType matrixQ() const\n    {\n      return householderQ();\n    }\n\n    /** \\returns a reference to the matrix where the Householder QR decomposition is stored\n      */\n    const MatrixType& matrixQR() const\n    {\n      eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n      return m_qr;\n    }\n\n    /** \\returns a reference to the matrix where the result Householder QR is stored\n     * \\warning The strict lower part of this matrix contains internal values.\n     * Only the upper triangular part should be referenced. To get it, use\n     * \\code matrixR().template triangularView<Upper>() \\endcode\n     * For rank-deficient matrices, use\n     * \\code\n     * matrixR().topLeftCorner(rank(), rank()).template triangularView<Upper>()\n     * \\endcode\n     */\n    const MatrixType& matrixR() const\n    {\n      eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n      return m_qr;\n    }\n\n    template<typename InputType>\n    ColPivHouseholderQR& compute(const EigenBase<InputType>& matrix);\n\n    /** \\returns a const reference to the column permutation matrix */\n    const PermutationType& colsPermutation() const\n    {\n      eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n      return m_colsPermutation;\n    }\n\n    /** \\returns the absolute value of the determinant of the matrix of which\n      * *this is the QR decomposition. It has only linear complexity\n      * (that is, O(n) where n is the dimension of the square matrix)\n      * as the QR decomposition has already been computed.\n      *\n      * \\note This is only for square matrices.\n      *\n      * \\warning a determinant can be very big or small, so for matrices\n      * of large enough dimension, there is a risk of overflow/underflow.\n      * One way to work around that is to use logAbsDeterminant() instead.\n      *\n      * \\sa logAbsDeterminant(), MatrixBase::determinant()\n      */\n    typename MatrixType::RealScalar absDeterminant() const;\n\n    /** \\returns the natural log of the absolute value of the determinant of the matrix of which\n      * *this is the QR decomposition. It has only linear complexity\n      * (that is, O(n) where n is the dimension of the square matrix)\n      * as the QR decomposition has already been computed.\n      *\n      * \\note This is only for square matrices.\n      *\n      * \\note This method is useful to work around the risk of overflow/underflow that's inherent\n      * to determinant computation.\n      *\n      * \\sa absDeterminant(), MatrixBase::determinant()\n      */\n    typename MatrixType::RealScalar logAbsDeterminant() const;\n\n    /** \\returns the rank of the matrix of which *this is the QR decomposition.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline Index rank() const\n    {\n      using std::abs;\n      eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n      RealScalar premultiplied_threshold = abs(m_maxpivot) * threshold();\n      Index result = 0;\n      for(Index i = 0; i < m_nonzero_pivots; ++i)\n        result += (abs(m_qr.coeff(i,i)) > premultiplied_threshold);\n      return result;\n    }\n\n    /** \\returns the dimension of the kernel of the matrix of which *this is the QR decomposition.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline Index dimensionOfKernel() const\n    {\n      eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n      return cols() - rank();\n    }\n\n    /** \\returns true if the matrix of which *this is the QR decomposition represents an injective\n      *          linear map, i.e. has trivial kernel; false otherwise.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline bool isInjective() const\n    {\n      eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n      return rank() == cols();\n    }\n\n    /** \\returns true if the matrix of which *this is the QR decomposition represents a surjective\n      *          linear map; false otherwise.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline bool isSurjective() const\n    {\n      eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n      return rank() == rows();\n    }\n\n    /** \\returns true if the matrix of which *this is the QR decomposition is invertible.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline bool isInvertible() const\n    {\n      eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n      return isInjective() && isSurjective();\n    }\n\n    /** \\returns the inverse of the matrix of which *this is the QR decomposition.\n      *\n      * \\note If this matrix is not invertible, the returned matrix has undefined coefficients.\n      *       Use isInvertible() to first determine whether this matrix is invertible.\n      */\n    inline const Inverse<ColPivHouseholderQR> inverse() const\n    {\n      eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n      return Inverse<ColPivHouseholderQR>(*this);\n    }\n\n    inline Index rows() const { return m_qr.rows(); }\n    inline Index cols() const { return m_qr.cols(); }\n\n    /** \\returns a const reference to the vector of Householder coefficients used to represent the factor \\c Q.\n      *\n      * For advanced uses only.\n      */\n    const HCoeffsType& hCoeffs() const { return m_hCoeffs; }\n\n    /** Allows to prescribe a threshold to be used by certain methods, such as rank(),\n      * who need to determine when pivots are to be considered nonzero. This is not used for the\n      * QR decomposition itself.\n      *\n      * When it needs to get the threshold value, Eigen calls threshold(). By default, this\n      * uses a formula to automatically determine a reasonable threshold.\n      * Once you have called the present method setThreshold(const RealScalar&),\n      * your value is used instead.\n      *\n      * \\param threshold The new value to use as the threshold.\n      *\n      * A pivot will be considered nonzero if its absolute value is strictly greater than\n      *  \\f$ \\vert pivot \\vert \\leqslant threshold \\times \\vert maxpivot \\vert \\f$\n      * where maxpivot is the biggest pivot.\n      *\n      * If you want to come back to the default behavior, call setThreshold(Default_t)\n      */\n    ColPivHouseholderQR& setThreshold(const RealScalar& threshold)\n    {\n      m_usePrescribedThreshold = true;\n      m_prescribedThreshold = threshold;\n      return *this;\n    }\n\n    /** Allows to come back to the default behavior, letting Eigen use its default formula for\n      * determining the threshold.\n      *\n      * You should pass the special object Eigen::Default as parameter here.\n      * \\code qr.setThreshold(Eigen::Default); \\endcode\n      *\n      * See the documentation of setThreshold(const RealScalar&).\n      */\n    ColPivHouseholderQR& setThreshold(Default_t)\n    {\n      m_usePrescribedThreshold = false;\n      return *this;\n    }\n\n    /** Returns the threshold that will be used by certain methods such as rank().\n      *\n      * See the documentation of setThreshold(const RealScalar&).\n      */\n    RealScalar threshold() const\n    {\n      eigen_assert(m_isInitialized || m_usePrescribedThreshold);\n      return m_usePrescribedThreshold ? m_prescribedThreshold\n      // this formula comes from experimenting (see \"LU precision tuning\" thread on the list)\n      // and turns out to be identical to Higham's formula used already in LDLt.\n                                      : NumTraits<Scalar>::epsilon() * RealScalar(m_qr.diagonalSize());\n    }\n\n    /** \\returns the number of nonzero pivots in the QR decomposition.\n      * Here nonzero is meant in the exact sense, not in a fuzzy sense.\n      * So that notion isn't really intrinsically interesting, but it is\n      * still useful when implementing algorithms.\n      *\n      * \\sa rank()\n      */\n    inline Index nonzeroPivots() const\n    {\n      eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n      return m_nonzero_pivots;\n    }\n\n    /** \\returns the absolute value of the biggest pivot, i.e. the biggest\n      *          diagonal coefficient of R.\n      */\n    RealScalar maxPivot() const { return m_maxpivot; }\n\n    /** \\brief Reports whether the QR factorization was successful.\n      *\n      * \\note This function always returns \\c Success. It is provided for compatibility\n      * with other factorization routines.\n      * \\returns \\c Success\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return Success;\n    }\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<typename RhsType, typename DstType>\n    void _solve_impl(const RhsType &rhs, DstType &dst) const;\n\n    template<bool Conjugate, typename RhsType, typename DstType>\n    void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const;\n    #endif\n\n  protected:\n\n    friend class CompleteOrthogonalDecomposition<MatrixType>;\n\n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n    }\n\n    void computeInPlace();\n\n    MatrixType m_qr;\n    HCoeffsType m_hCoeffs;\n    PermutationType m_colsPermutation;\n    IntRowVectorType m_colsTranspositions;\n    RowVectorType m_temp;\n    RealRowVectorType m_colNormsUpdated;\n    RealRowVectorType m_colNormsDirect;\n    bool m_isInitialized, m_usePrescribedThreshold;\n    RealScalar m_prescribedThreshold, m_maxpivot;\n    Index m_nonzero_pivots;\n    Index m_det_pq;\n};\n\ntemplate<typename MatrixType>\ntypename MatrixType::RealScalar ColPivHouseholderQR<MatrixType>::absDeterminant() const\n{\n  using std::abs;\n  eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n  eigen_assert(m_qr.rows() == m_qr.cols() && \"You can't take the determinant of a non-square matrix!\");\n  return abs(m_qr.diagonal().prod());\n}\n\ntemplate<typename MatrixType>\ntypename MatrixType::RealScalar ColPivHouseholderQR<MatrixType>::logAbsDeterminant() const\n{\n  eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n  eigen_assert(m_qr.rows() == m_qr.cols() && \"You can't take the determinant of a non-square matrix!\");\n  return m_qr.diagonal().cwiseAbs().array().log().sum();\n}\n\n/** Performs the QR factorization of the given matrix \\a matrix. The result of\n  * the factorization is stored into \\c *this, and a reference to \\c *this\n  * is returned.\n  *\n  * \\sa class ColPivHouseholderQR, ColPivHouseholderQR(const MatrixType&)\n  */\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nColPivHouseholderQR<MatrixType>& ColPivHouseholderQR<MatrixType>::compute(const EigenBase<InputType>& matrix)\n{\n  m_qr = matrix.derived();\n  computeInPlace();\n  return *this;\n}\n\ntemplate<typename MatrixType>\nvoid ColPivHouseholderQR<MatrixType>::computeInPlace()\n{\n  check_template_parameters();\n\n  // the column permutation is stored as int indices, so just to be sure:\n  eigen_assert(m_qr.cols()<=NumTraits<int>::highest());\n\n  using std::abs;\n\n  Index rows = m_qr.rows();\n  Index cols = m_qr.cols();\n  Index size = m_qr.diagonalSize();\n\n  m_hCoeffs.resize(size);\n\n  m_temp.resize(cols);\n\n  m_colsTranspositions.resize(m_qr.cols());\n  Index number_of_transpositions = 0;\n\n  m_colNormsUpdated.resize(cols);\n  m_colNormsDirect.resize(cols);\n  for (Index k = 0; k < cols; ++k) {\n    // colNormsDirect(k) caches the most recent directly computed norm of\n    // column k.\n    m_colNormsDirect.coeffRef(k) = m_qr.col(k).norm();\n    m_colNormsUpdated.coeffRef(k) = m_colNormsDirect.coeffRef(k);\n  }\n\n  RealScalar threshold_helper =  numext::abs2<RealScalar>(m_colNormsUpdated.maxCoeff() * NumTraits<RealScalar>::epsilon()) / RealScalar(rows);\n  RealScalar norm_downdate_threshold = numext::sqrt(NumTraits<RealScalar>::epsilon());\n\n  m_nonzero_pivots = size; // the generic case is that in which all pivots are nonzero (invertible case)\n  m_maxpivot = RealScalar(0);\n\n  for(Index k = 0; k < size; ++k)\n  {\n    // first, we look up in our table m_colNormsUpdated which column has the biggest norm\n    Index biggest_col_index;\n    RealScalar biggest_col_sq_norm = numext::abs2(m_colNormsUpdated.tail(cols-k).maxCoeff(&biggest_col_index));\n    biggest_col_index += k;\n\n    // Track the number of meaningful pivots but do not stop the decomposition to make\n    // sure that the initial matrix is properly reproduced. See bug 941.\n    if(m_nonzero_pivots==size && biggest_col_sq_norm < threshold_helper * RealScalar(rows-k))\n      m_nonzero_pivots = k;\n\n    // apply the transposition to the columns\n    m_colsTranspositions.coeffRef(k) = biggest_col_index;\n    if(k != biggest_col_index) {\n      m_qr.col(k).swap(m_qr.col(biggest_col_index));\n      std::swap(m_colNormsUpdated.coeffRef(k), m_colNormsUpdated.coeffRef(biggest_col_index));\n      std::swap(m_colNormsDirect.coeffRef(k), m_colNormsDirect.coeffRef(biggest_col_index));\n      ++number_of_transpositions;\n    }\n\n    // generate the householder vector, store it below the diagonal\n    RealScalar beta;\n    m_qr.col(k).tail(rows-k).makeHouseholderInPlace(m_hCoeffs.coeffRef(k), beta);\n\n    // apply the householder transformation to the diagonal coefficient\n    m_qr.coeffRef(k,k) = beta;\n\n    // remember the maximum absolute value of diagonal coefficients\n    if(abs(beta) > m_maxpivot) m_maxpivot = abs(beta);\n\n    // apply the householder transformation\n    m_qr.bottomRightCorner(rows-k, cols-k-1)\n        .applyHouseholderOnTheLeft(m_qr.col(k).tail(rows-k-1), m_hCoeffs.coeffRef(k), &m_temp.coeffRef(k+1));\n\n    // update our table of norms of the columns\n    for (Index j = k + 1; j < cols; ++j) {\n      // The following implements the stable norm downgrade step discussed in\n      // http://www.netlib.org/lapack/lawnspdf/lawn176.pdf\n      // and used in LAPACK routines xGEQPF and xGEQP3.\n      // See lines 278-297 in http://www.netlib.org/lapack/explore-html/dc/df4/sgeqpf_8f_source.html\n      if (m_colNormsUpdated.coeffRef(j) != RealScalar(0)) {\n        RealScalar temp = abs(m_qr.coeffRef(k, j)) / m_colNormsUpdated.coeffRef(j);\n        temp = (RealScalar(1) + temp) * (RealScalar(1) - temp);\n        temp = temp <  RealScalar(0) ? RealScalar(0) : temp;\n        RealScalar temp2 = temp * numext::abs2<RealScalar>(m_colNormsUpdated.coeffRef(j) /\n                                                           m_colNormsDirect.coeffRef(j));\n        if (temp2 <= norm_downdate_threshold) {\n          // The updated norm has become too inaccurate so re-compute the column\n          // norm directly.\n          m_colNormsDirect.coeffRef(j) = m_qr.col(j).tail(rows - k - 1).norm();\n          m_colNormsUpdated.coeffRef(j) = m_colNormsDirect.coeffRef(j);\n        } else {\n          m_colNormsUpdated.coeffRef(j) *= numext::sqrt(temp);\n        }\n      }\n    }\n  }\n\n  m_colsPermutation.setIdentity(PermIndexType(cols));\n  for(PermIndexType k = 0; k < size/*m_nonzero_pivots*/; ++k)\n    m_colsPermutation.applyTranspositionOnTheRight(k, PermIndexType(m_colsTranspositions.coeff(k)));\n\n  m_det_pq = (number_of_transpositions%2) ? -1 : 1;\n  m_isInitialized = true;\n}\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename _MatrixType>\ntemplate<typename RhsType, typename DstType>\nvoid ColPivHouseholderQR<_MatrixType>::_solve_impl(const RhsType &rhs, DstType &dst) const\n{\n  const Index nonzero_pivots = nonzeroPivots();\n\n  if(nonzero_pivots == 0)\n  {\n    dst.setZero();\n    return;\n  }\n\n  typename RhsType::PlainObject c(rhs);\n\n  c.applyOnTheLeft(householderQ().setLength(nonzero_pivots).adjoint() );\n\n  m_qr.topLeftCorner(nonzero_pivots, nonzero_pivots)\n      .template triangularView<Upper>()\n      .solveInPlace(c.topRows(nonzero_pivots));\n\n  for(Index i = 0; i < nonzero_pivots; ++i) dst.row(m_colsPermutation.indices().coeff(i)) = c.row(i);\n  for(Index i = nonzero_pivots; i < cols(); ++i) dst.row(m_colsPermutation.indices().coeff(i)).setZero();\n}\n\ntemplate<typename _MatrixType>\ntemplate<bool Conjugate, typename RhsType, typename DstType>\nvoid ColPivHouseholderQR<_MatrixType>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const\n{\n  const Index nonzero_pivots = nonzeroPivots();\n\n  if(nonzero_pivots == 0)\n  {\n    dst.setZero();\n    return;\n  }\n\n  typename RhsType::PlainObject c(m_colsPermutation.transpose()*rhs);\n\n  m_qr.topLeftCorner(nonzero_pivots, nonzero_pivots)\n        .template triangularView<Upper>()\n        .transpose().template conjugateIf<Conjugate>()\n        .solveInPlace(c.topRows(nonzero_pivots));\n\n  dst.topRows(nonzero_pivots) = c.topRows(nonzero_pivots);\n  dst.bottomRows(rows()-nonzero_pivots).setZero();\n\n  dst.applyOnTheLeft(householderQ().setLength(nonzero_pivots).template conjugateIf<!Conjugate>() );\n}\n#endif\n\nnamespace internal {\n\ntemplate<typename DstXprType, typename MatrixType>\nstruct Assignment<DstXprType, Inverse<ColPivHouseholderQR<MatrixType> >, internal::assign_op<typename DstXprType::Scalar,typename ColPivHouseholderQR<MatrixType>::Scalar>, Dense2Dense>\n{\n  typedef ColPivHouseholderQR<MatrixType> QrType;\n  typedef Inverse<QrType> SrcXprType;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename QrType::Scalar> &)\n  {\n    dst = src.nestedExpression().solve(MatrixType::Identity(src.rows(), src.cols()));\n  }\n};\n\n} // end namespace internal\n\n/** \\returns the matrix Q as a sequence of householder transformations.\n  * You can extract the meaningful part only by using:\n  * \\code qr.householderQ().setLength(qr.nonzeroPivots()) \\endcode*/\ntemplate<typename MatrixType>\ntypename ColPivHouseholderQR<MatrixType>::HouseholderSequenceType ColPivHouseholderQR<MatrixType>\n  ::householderQ() const\n{\n  eigen_assert(m_isInitialized && \"ColPivHouseholderQR is not initialized.\");\n  return HouseholderSequenceType(m_qr, m_hCoeffs.conjugate());\n}\n\n/** \\return the column-pivoting Householder QR decomposition of \\c *this.\n  *\n  * \\sa class ColPivHouseholderQR\n  */\ntemplate<typename Derived>\nconst ColPivHouseholderQR<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::colPivHouseholderQr() const\n{\n  return ColPivHouseholderQR<PlainObject>(eval());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_COLPIVOTINGHOUSEHOLDERQR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/QR/ColPivHouseholderQR_LAPACKE.h",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Eigen bindings to LAPACKe\n *    Householder QR decomposition of a matrix with column pivoting based on\n *    LAPACKE_?geqp3 function.\n ********************************************************************************\n*/\n\n#ifndef EIGEN_COLPIVOTINGHOUSEHOLDERQR_LAPACKE_H\n#define EIGEN_COLPIVOTINGHOUSEHOLDERQR_LAPACKE_H\n\nnamespace Eigen { \n\n/** \\internal Specialization for the data types supported by LAPACKe */\n\n#define EIGEN_LAPACKE_QR_COLPIV(EIGTYPE, LAPACKE_TYPE, LAPACKE_PREFIX, EIGCOLROW, LAPACKE_COLROW) \\\ntemplate<> template<typename InputType> inline \\\nColPivHouseholderQR<Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW, Dynamic, Dynamic> >& \\\nColPivHouseholderQR<Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW, Dynamic, Dynamic> >::compute( \\\n              const EigenBase<InputType>& matrix) \\\n\\\n{ \\\n  using std::abs; \\\n  typedef Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW, Dynamic, Dynamic> MatrixType; \\\n  typedef MatrixType::RealScalar RealScalar; \\\n  Index rows = matrix.rows();\\\n  Index cols = matrix.cols();\\\n\\\n  m_qr = matrix;\\\n  Index size = m_qr.diagonalSize();\\\n  m_hCoeffs.resize(size);\\\n\\\n  m_colsTranspositions.resize(cols);\\\n  /*Index number_of_transpositions = 0;*/ \\\n\\\n  m_nonzero_pivots = 0; \\\n  m_maxpivot = RealScalar(0);\\\n  m_colsPermutation.resize(cols); \\\n  m_colsPermutation.indices().setZero(); \\\n\\\n  lapack_int lda = internal::convert_index<lapack_int,Index>(m_qr.outerStride()); \\\n  lapack_int matrix_order = LAPACKE_COLROW; \\\n  LAPACKE_##LAPACKE_PREFIX##geqp3( matrix_order, internal::convert_index<lapack_int,Index>(rows), internal::convert_index<lapack_int,Index>(cols), \\\n                              (LAPACKE_TYPE*)m_qr.data(), lda, (lapack_int*)m_colsPermutation.indices().data(), (LAPACKE_TYPE*)m_hCoeffs.data()); \\\n  m_isInitialized = true; \\\n  m_maxpivot=m_qr.diagonal().cwiseAbs().maxCoeff(); \\\n  m_hCoeffs.adjointInPlace(); \\\n  RealScalar premultiplied_threshold = abs(m_maxpivot) * threshold(); \\\n  lapack_int *perm = m_colsPermutation.indices().data(); \\\n  for(Index i=0;i<size;i++) { \\\n    m_nonzero_pivots += (abs(m_qr.coeff(i,i)) > premultiplied_threshold);\\\n  } \\\n  for(Index i=0;i<cols;i++) perm[i]--;\\\n\\\n  /*m_det_pq = (number_of_transpositions%2) ? -1 : 1;  // TODO: It's not needed now; fix upon availability in Eigen */ \\\n\\\n  return *this; \\\n}\n\nEIGEN_LAPACKE_QR_COLPIV(double,   double,        d, ColMajor, LAPACK_COL_MAJOR)\nEIGEN_LAPACKE_QR_COLPIV(float,    float,         s, ColMajor, LAPACK_COL_MAJOR)\nEIGEN_LAPACKE_QR_COLPIV(dcomplex, lapack_complex_double, z, ColMajor, LAPACK_COL_MAJOR)\nEIGEN_LAPACKE_QR_COLPIV(scomplex, lapack_complex_float,  c, ColMajor, LAPACK_COL_MAJOR)\n\nEIGEN_LAPACKE_QR_COLPIV(double,   double,        d, RowMajor, LAPACK_ROW_MAJOR)\nEIGEN_LAPACKE_QR_COLPIV(float,    float,         s, RowMajor, LAPACK_ROW_MAJOR)\nEIGEN_LAPACKE_QR_COLPIV(dcomplex, lapack_complex_double, z, RowMajor, LAPACK_ROW_MAJOR)\nEIGEN_LAPACKE_QR_COLPIV(scomplex, lapack_complex_float,  c, RowMajor, LAPACK_ROW_MAJOR)\n\n} // end namespace Eigen\n\n#endif // EIGEN_COLPIVOTINGHOUSEHOLDERQR_LAPACKE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/QR/CompleteOrthogonalDecomposition.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Rasmus Munk Larsen <rmlarsen@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_COMPLETEORTHOGONALDECOMPOSITION_H\n#define EIGEN_COMPLETEORTHOGONALDECOMPOSITION_H\n\nnamespace Eigen {\n\nnamespace internal {\ntemplate <typename _MatrixType>\nstruct traits<CompleteOrthogonalDecomposition<_MatrixType> >\n    : traits<_MatrixType> {\n  typedef MatrixXpr XprKind;\n  typedef SolverStorage StorageKind;\n  typedef int StorageIndex;\n  enum { Flags = 0 };\n};\n\n}  // end namespace internal\n\n/** \\ingroup QR_Module\n  *\n  * \\class CompleteOrthogonalDecomposition\n  *\n  * \\brief Complete orthogonal decomposition (COD) of a matrix.\n  *\n  * \\param MatrixType the type of the matrix of which we are computing the COD.\n  *\n  * This class performs a rank-revealing complete orthogonal decomposition of a\n  * matrix  \\b A into matrices \\b P, \\b Q, \\b T, and \\b Z such that\n  * \\f[\n  *  \\mathbf{A} \\, \\mathbf{P} = \\mathbf{Q} \\,\n  *                     \\begin{bmatrix} \\mathbf{T} &  \\mathbf{0} \\\\\n  *                                     \\mathbf{0} & \\mathbf{0} \\end{bmatrix} \\, \\mathbf{Z}\n  * \\f]\n  * by using Householder transformations. Here, \\b P is a permutation matrix,\n  * \\b Q and \\b Z are unitary matrices and \\b T an upper triangular matrix of\n  * size rank-by-rank. \\b A may be rank deficient.\n  *\n  * This class supports the \\link InplaceDecomposition inplace decomposition \\endlink mechanism.\n  * \n  * \\sa MatrixBase::completeOrthogonalDecomposition()\n  */\ntemplate <typename _MatrixType> class CompleteOrthogonalDecomposition\n          : public SolverBase<CompleteOrthogonalDecomposition<_MatrixType> >\n{\n public:\n  typedef _MatrixType MatrixType;\n  typedef SolverBase<CompleteOrthogonalDecomposition> Base;\n\n  template<typename Derived>\n  friend struct internal::solve_assertion;\n\n  EIGEN_GENERIC_PUBLIC_INTERFACE(CompleteOrthogonalDecomposition)\n  enum {\n    MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n    MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n  };\n  typedef typename internal::plain_diag_type<MatrixType>::type HCoeffsType;\n  typedef PermutationMatrix<ColsAtCompileTime, MaxColsAtCompileTime>\n      PermutationType;\n  typedef typename internal::plain_row_type<MatrixType, Index>::type\n      IntRowVectorType;\n  typedef typename internal::plain_row_type<MatrixType>::type RowVectorType;\n  typedef typename internal::plain_row_type<MatrixType, RealScalar>::type\n      RealRowVectorType;\n  typedef HouseholderSequence<\n      MatrixType, typename internal::remove_all<\n                      typename HCoeffsType::ConjugateReturnType>::type>\n      HouseholderSequenceType;\n  typedef typename MatrixType::PlainObject PlainObject;\n\n private:\n  typedef typename PermutationType::Index PermIndexType;\n\n public:\n  /**\n   * \\brief Default Constructor.\n   *\n   * The default constructor is useful in cases in which the user intends to\n   * perform decompositions via\n   * \\c CompleteOrthogonalDecomposition::compute(const* MatrixType&).\n   */\n  CompleteOrthogonalDecomposition() : m_cpqr(), m_zCoeffs(), m_temp() {}\n\n  /** \\brief Default Constructor with memory preallocation\n   *\n   * Like the default constructor but with preallocation of the internal data\n   * according to the specified problem \\a size.\n   * \\sa CompleteOrthogonalDecomposition()\n   */\n  CompleteOrthogonalDecomposition(Index rows, Index cols)\n      : m_cpqr(rows, cols), m_zCoeffs((std::min)(rows, cols)), m_temp(cols) {}\n\n  /** \\brief Constructs a complete orthogonal decomposition from a given\n   * matrix.\n   *\n   * This constructor computes the complete orthogonal decomposition of the\n   * matrix \\a matrix by calling the method compute(). The default\n   * threshold for rank determination will be used. It is a short cut for:\n   *\n   * \\code\n   * CompleteOrthogonalDecomposition<MatrixType> cod(matrix.rows(),\n   *                                                 matrix.cols());\n   * cod.setThreshold(Default);\n   * cod.compute(matrix);\n   * \\endcode\n   *\n   * \\sa compute()\n   */\n  template <typename InputType>\n  explicit CompleteOrthogonalDecomposition(const EigenBase<InputType>& matrix)\n      : m_cpqr(matrix.rows(), matrix.cols()),\n        m_zCoeffs((std::min)(matrix.rows(), matrix.cols())),\n        m_temp(matrix.cols())\n  {\n    compute(matrix.derived());\n  }\n\n  /** \\brief Constructs a complete orthogonal decomposition from a given matrix\n    *\n    * This overloaded constructor is provided for \\link InplaceDecomposition inplace decomposition \\endlink when \\c MatrixType is a Eigen::Ref.\n    *\n    * \\sa CompleteOrthogonalDecomposition(const EigenBase&)\n    */\n  template<typename InputType>\n  explicit CompleteOrthogonalDecomposition(EigenBase<InputType>& matrix)\n    : m_cpqr(matrix.derived()),\n      m_zCoeffs((std::min)(matrix.rows(), matrix.cols())),\n      m_temp(matrix.cols())\n  {\n    computeInPlace();\n  } \n\n  #ifdef EIGEN_PARSED_BY_DOXYGEN\n  /** This method computes the minimum-norm solution X to a least squares\n   * problem \\f[\\mathrm{minimize} \\|A X - B\\|, \\f] where \\b A is the matrix of\n   * which \\c *this is the complete orthogonal decomposition.\n   *\n   * \\param b the right-hand sides of the problem to solve.\n   *\n   * \\returns a solution.\n   *\n   */\n  template <typename Rhs>\n  inline const Solve<CompleteOrthogonalDecomposition, Rhs> solve(\n      const MatrixBase<Rhs>& b) const;\n  #endif\n\n  HouseholderSequenceType householderQ(void) const;\n  HouseholderSequenceType matrixQ(void) const { return m_cpqr.householderQ(); }\n\n  /** \\returns the matrix \\b Z.\n   */\n  MatrixType matrixZ() const {\n    MatrixType Z = MatrixType::Identity(m_cpqr.cols(), m_cpqr.cols());\n    applyZOnTheLeftInPlace<false>(Z);\n    return Z;\n  }\n\n  /** \\returns a reference to the matrix where the complete orthogonal\n   * decomposition is stored\n   */\n  const MatrixType& matrixQTZ() const { return m_cpqr.matrixQR(); }\n\n  /** \\returns a reference to the matrix where the complete orthogonal\n   * decomposition is stored.\n   * \\warning The strict lower part and \\code cols() - rank() \\endcode right\n   * columns of this matrix contains internal values.\n   * Only the upper triangular part should be referenced. To get it, use\n   * \\code matrixT().template triangularView<Upper>() \\endcode\n   * For rank-deficient matrices, use\n   * \\code\n   * matrixR().topLeftCorner(rank(), rank()).template triangularView<Upper>()\n   * \\endcode\n   */\n  const MatrixType& matrixT() const { return m_cpqr.matrixQR(); }\n\n  template <typename InputType>\n  CompleteOrthogonalDecomposition& compute(const EigenBase<InputType>& matrix) {\n    // Compute the column pivoted QR factorization A P = Q R.\n    m_cpqr.compute(matrix);\n    computeInPlace();\n    return *this;\n  }\n\n  /** \\returns a const reference to the column permutation matrix */\n  const PermutationType& colsPermutation() const {\n    return m_cpqr.colsPermutation();\n  }\n\n  /** \\returns the absolute value of the determinant of the matrix of which\n   * *this is the complete orthogonal decomposition. It has only linear\n   * complexity (that is, O(n) where n is the dimension of the square matrix)\n   * as the complete orthogonal decomposition has already been computed.\n   *\n   * \\note This is only for square matrices.\n   *\n   * \\warning a determinant can be very big or small, so for matrices\n   * of large enough dimension, there is a risk of overflow/underflow.\n   * One way to work around that is to use logAbsDeterminant() instead.\n   *\n   * \\sa logAbsDeterminant(), MatrixBase::determinant()\n   */\n  typename MatrixType::RealScalar absDeterminant() const;\n\n  /** \\returns the natural log of the absolute value of the determinant of the\n   * matrix of which *this is the complete orthogonal decomposition. It has\n   * only linear complexity (that is, O(n) where n is the dimension of the\n   * square matrix) as the complete orthogonal decomposition has already been\n   * computed.\n   *\n   * \\note This is only for square matrices.\n   *\n   * \\note This method is useful to work around the risk of overflow/underflow\n   * that's inherent to determinant computation.\n   *\n   * \\sa absDeterminant(), MatrixBase::determinant()\n   */\n  typename MatrixType::RealScalar logAbsDeterminant() const;\n\n  /** \\returns the rank of the matrix of which *this is the complete orthogonal\n   * decomposition.\n   *\n   * \\note This method has to determine which pivots should be considered\n   * nonzero. For that, it uses the threshold value that you can control by\n   * calling setThreshold(const RealScalar&).\n   */\n  inline Index rank() const { return m_cpqr.rank(); }\n\n  /** \\returns the dimension of the kernel of the matrix of which *this is the\n   * complete orthogonal decomposition.\n   *\n   * \\note This method has to determine which pivots should be considered\n   * nonzero. For that, it uses the threshold value that you can control by\n   * calling setThreshold(const RealScalar&).\n   */\n  inline Index dimensionOfKernel() const { return m_cpqr.dimensionOfKernel(); }\n\n  /** \\returns true if the matrix of which *this is the decomposition represents\n   * an injective linear map, i.e. has trivial kernel; false otherwise.\n   *\n   * \\note This method has to determine which pivots should be considered\n   * nonzero. For that, it uses the threshold value that you can control by\n   * calling setThreshold(const RealScalar&).\n   */\n  inline bool isInjective() const { return m_cpqr.isInjective(); }\n\n  /** \\returns true if the matrix of which *this is the decomposition represents\n   * a surjective linear map; false otherwise.\n   *\n   * \\note This method has to determine which pivots should be considered\n   * nonzero. For that, it uses the threshold value that you can control by\n   * calling setThreshold(const RealScalar&).\n   */\n  inline bool isSurjective() const { return m_cpqr.isSurjective(); }\n\n  /** \\returns true if the matrix of which *this is the complete orthogonal\n   * decomposition is invertible.\n   *\n   * \\note This method has to determine which pivots should be considered\n   * nonzero. For that, it uses the threshold value that you can control by\n   * calling setThreshold(const RealScalar&).\n   */\n  inline bool isInvertible() const { return m_cpqr.isInvertible(); }\n\n  /** \\returns the pseudo-inverse of the matrix of which *this is the complete\n   * orthogonal decomposition.\n   * \\warning: Do not compute \\c this->pseudoInverse()*rhs to solve a linear systems.\n   * It is more efficient and numerically stable to call \\c this->solve(rhs).\n   */\n  inline const Inverse<CompleteOrthogonalDecomposition> pseudoInverse() const\n  {\n    eigen_assert(m_cpqr.m_isInitialized && \"CompleteOrthogonalDecomposition is not initialized.\");\n    return Inverse<CompleteOrthogonalDecomposition>(*this);\n  }\n\n  inline Index rows() const { return m_cpqr.rows(); }\n  inline Index cols() const { return m_cpqr.cols(); }\n\n  /** \\returns a const reference to the vector of Householder coefficients used\n   * to represent the factor \\c Q.\n   *\n   * For advanced uses only.\n   */\n  inline const HCoeffsType& hCoeffs() const { return m_cpqr.hCoeffs(); }\n\n  /** \\returns a const reference to the vector of Householder coefficients\n   * used to represent the factor \\c Z.\n   *\n   * For advanced uses only.\n   */\n  const HCoeffsType& zCoeffs() const { return m_zCoeffs; }\n\n  /** Allows to prescribe a threshold to be used by certain methods, such as\n   * rank(), who need to determine when pivots are to be considered nonzero.\n   * Most be called before calling compute().\n   *\n   * When it needs to get the threshold value, Eigen calls threshold(). By\n   * default, this uses a formula to automatically determine a reasonable\n   * threshold. Once you have called the present method\n   * setThreshold(const RealScalar&), your value is used instead.\n   *\n   * \\param threshold The new value to use as the threshold.\n   *\n   * A pivot will be considered nonzero if its absolute value is strictly\n   * greater than\n   *  \\f$ \\vert pivot \\vert \\leqslant threshold \\times \\vert maxpivot \\vert \\f$\n   * where maxpivot is the biggest pivot.\n   *\n   * If you want to come back to the default behavior, call\n   * setThreshold(Default_t)\n   */\n  CompleteOrthogonalDecomposition& setThreshold(const RealScalar& threshold) {\n    m_cpqr.setThreshold(threshold);\n    return *this;\n  }\n\n  /** Allows to come back to the default behavior, letting Eigen use its default\n   * formula for determining the threshold.\n   *\n   * You should pass the special object Eigen::Default as parameter here.\n   * \\code qr.setThreshold(Eigen::Default); \\endcode\n   *\n   * See the documentation of setThreshold(const RealScalar&).\n   */\n  CompleteOrthogonalDecomposition& setThreshold(Default_t) {\n    m_cpqr.setThreshold(Default);\n    return *this;\n  }\n\n  /** Returns the threshold that will be used by certain methods such as rank().\n   *\n   * See the documentation of setThreshold(const RealScalar&).\n   */\n  RealScalar threshold() const { return m_cpqr.threshold(); }\n\n  /** \\returns the number of nonzero pivots in the complete orthogonal\n   * decomposition. Here nonzero is meant in the exact sense, not in a\n   * fuzzy sense. So that notion isn't really intrinsically interesting,\n   * but it is still useful when implementing algorithms.\n   *\n   * \\sa rank()\n   */\n  inline Index nonzeroPivots() const { return m_cpqr.nonzeroPivots(); }\n\n  /** \\returns the absolute value of the biggest pivot, i.e. the biggest\n   *          diagonal coefficient of R.\n   */\n  inline RealScalar maxPivot() const { return m_cpqr.maxPivot(); }\n\n  /** \\brief Reports whether the complete orthogonal decomposition was\n   * successful.\n   *\n   * \\note This function always returns \\c Success. It is provided for\n   * compatibility\n   * with other factorization routines.\n   * \\returns \\c Success\n   */\n  ComputationInfo info() const {\n    eigen_assert(m_cpqr.m_isInitialized && \"Decomposition is not initialized.\");\n    return Success;\n  }\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n  template <typename RhsType, typename DstType>\n  void _solve_impl(const RhsType& rhs, DstType& dst) const;\n\n  template<bool Conjugate, typename RhsType, typename DstType>\n  void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const;\n#endif\n\n protected:\n  static void check_template_parameters() {\n    EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n  }\n\n  template<bool Transpose_, typename Rhs>\n  void _check_solve_assertion(const Rhs& b) const {\n      EIGEN_ONLY_USED_FOR_DEBUG(b);\n      eigen_assert(m_cpqr.m_isInitialized && \"CompleteOrthogonalDecomposition is not initialized.\");\n      eigen_assert((Transpose_?derived().cols():derived().rows())==b.rows() && \"CompleteOrthogonalDecomposition::solve(): invalid number of rows of the right hand side matrix b\");\n  }\n\n  void computeInPlace();\n\n  /** Overwrites \\b rhs with \\f$ \\mathbf{Z} * \\mathbf{rhs} \\f$ or\n   *  \\f$ \\mathbf{\\overline Z} * \\mathbf{rhs} \\f$ if \\c Conjugate \n   *  is set to \\c true.\n   */\n  template <bool Conjugate, typename Rhs>\n  void applyZOnTheLeftInPlace(Rhs& rhs) const;\n\n  /** Overwrites \\b rhs with \\f$ \\mathbf{Z}^* * \\mathbf{rhs} \\f$.\n   */\n  template <typename Rhs>\n  void applyZAdjointOnTheLeftInPlace(Rhs& rhs) const;\n\n  ColPivHouseholderQR<MatrixType> m_cpqr;\n  HCoeffsType m_zCoeffs;\n  RowVectorType m_temp;\n};\n\ntemplate <typename MatrixType>\ntypename MatrixType::RealScalar\nCompleteOrthogonalDecomposition<MatrixType>::absDeterminant() const {\n  return m_cpqr.absDeterminant();\n}\n\ntemplate <typename MatrixType>\ntypename MatrixType::RealScalar\nCompleteOrthogonalDecomposition<MatrixType>::logAbsDeterminant() const {\n  return m_cpqr.logAbsDeterminant();\n}\n\n/** Performs the complete orthogonal decomposition of the given matrix \\a\n * matrix. The result of the factorization is stored into \\c *this, and a\n * reference to \\c *this is returned.\n *\n * \\sa class CompleteOrthogonalDecomposition,\n * CompleteOrthogonalDecomposition(const MatrixType&)\n */\ntemplate <typename MatrixType>\nvoid CompleteOrthogonalDecomposition<MatrixType>::computeInPlace()\n{\n  check_template_parameters();\n\n  // the column permutation is stored as int indices, so just to be sure:\n  eigen_assert(m_cpqr.cols() <= NumTraits<int>::highest());\n\n  const Index rank = m_cpqr.rank();\n  const Index cols = m_cpqr.cols();\n  const Index rows = m_cpqr.rows();\n  m_zCoeffs.resize((std::min)(rows, cols));\n  m_temp.resize(cols);\n\n  if (rank < cols) {\n    // We have reduced the (permuted) matrix to the form\n    //   [R11 R12]\n    //   [ 0  R22]\n    // where R11 is r-by-r (r = rank) upper triangular, R12 is\n    // r-by-(n-r), and R22 is empty or the norm of R22 is negligible.\n    // We now compute the complete orthogonal decomposition by applying\n    // Householder transformations from the right to the upper trapezoidal\n    // matrix X = [R11 R12] to zero out R12 and obtain the factorization\n    // [R11 R12] = [T11 0] * Z, where T11 is r-by-r upper triangular and\n    // Z = Z(0) * Z(1) ... Z(r-1) is an n-by-n orthogonal matrix.\n    // We store the data representing Z in R12 and m_zCoeffs.\n    for (Index k = rank - 1; k >= 0; --k) {\n      if (k != rank - 1) {\n        // Given the API for Householder reflectors, it is more convenient if\n        // we swap the leading parts of columns k and r-1 (zero-based) to form\n        // the matrix X_k = [X(0:k, k), X(0:k, r:n)]\n        m_cpqr.m_qr.col(k).head(k + 1).swap(\n            m_cpqr.m_qr.col(rank - 1).head(k + 1));\n      }\n      // Construct Householder reflector Z(k) to zero out the last row of X_k,\n      // i.e. choose Z(k) such that\n      // [X(k, k), X(k, r:n)] * Z(k) = [beta, 0, .., 0].\n      RealScalar beta;\n      m_cpqr.m_qr.row(k)\n          .tail(cols - rank + 1)\n          .makeHouseholderInPlace(m_zCoeffs(k), beta);\n      m_cpqr.m_qr(k, rank - 1) = beta;\n      if (k > 0) {\n        // Apply Z(k) to the first k rows of X_k\n        m_cpqr.m_qr.topRightCorner(k, cols - rank + 1)\n            .applyHouseholderOnTheRight(\n                m_cpqr.m_qr.row(k).tail(cols - rank).adjoint(), m_zCoeffs(k),\n                &m_temp(0));\n      }\n      if (k != rank - 1) {\n        // Swap X(0:k,k) back to its proper location.\n        m_cpqr.m_qr.col(k).head(k + 1).swap(\n            m_cpqr.m_qr.col(rank - 1).head(k + 1));\n      }\n    }\n  }\n}\n\ntemplate <typename MatrixType>\ntemplate <bool Conjugate, typename Rhs>\nvoid CompleteOrthogonalDecomposition<MatrixType>::applyZOnTheLeftInPlace(\n    Rhs& rhs) const {\n  const Index cols = this->cols();\n  const Index nrhs = rhs.cols();\n  const Index rank = this->rank();\n  Matrix<typename Rhs::Scalar, Dynamic, 1> temp((std::max)(cols, nrhs));\n  for (Index k = rank-1; k >= 0; --k) {\n    if (k != rank - 1) {\n      rhs.row(k).swap(rhs.row(rank - 1));\n    }\n    rhs.middleRows(rank - 1, cols - rank + 1)\n        .applyHouseholderOnTheLeft(\n            matrixQTZ().row(k).tail(cols - rank).transpose().template conjugateIf<!Conjugate>(), zCoeffs().template conjugateIf<Conjugate>()(k),\n            &temp(0));\n    if (k != rank - 1) {\n      rhs.row(k).swap(rhs.row(rank - 1));\n    }\n  }\n}\n\ntemplate <typename MatrixType>\ntemplate <typename Rhs>\nvoid CompleteOrthogonalDecomposition<MatrixType>::applyZAdjointOnTheLeftInPlace(\n    Rhs& rhs) const {\n  const Index cols = this->cols();\n  const Index nrhs = rhs.cols();\n  const Index rank = this->rank();\n  Matrix<typename Rhs::Scalar, Dynamic, 1> temp((std::max)(cols, nrhs));\n  for (Index k = 0; k < rank; ++k) {\n    if (k != rank - 1) {\n      rhs.row(k).swap(rhs.row(rank - 1));\n    }\n    rhs.middleRows(rank - 1, cols - rank + 1)\n        .applyHouseholderOnTheLeft(\n            matrixQTZ().row(k).tail(cols - rank).adjoint(), zCoeffs()(k),\n            &temp(0));\n    if (k != rank - 1) {\n      rhs.row(k).swap(rhs.row(rank - 1));\n    }\n  }\n}\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate <typename _MatrixType>\ntemplate <typename RhsType, typename DstType>\nvoid CompleteOrthogonalDecomposition<_MatrixType>::_solve_impl(\n    const RhsType& rhs, DstType& dst) const {\n  const Index rank = this->rank();\n  if (rank == 0) {\n    dst.setZero();\n    return;\n  }\n\n  // Compute c = Q^* * rhs\n  typename RhsType::PlainObject c(rhs);\n  c.applyOnTheLeft(matrixQ().setLength(rank).adjoint());\n\n  // Solve T z = c(1:rank, :)\n  dst.topRows(rank) = matrixT()\n                          .topLeftCorner(rank, rank)\n                          .template triangularView<Upper>()\n                          .solve(c.topRows(rank));\n\n  const Index cols = this->cols();\n  if (rank < cols) {\n    // Compute y = Z^* * [ z ]\n    //                   [ 0 ]\n    dst.bottomRows(cols - rank).setZero();\n    applyZAdjointOnTheLeftInPlace(dst);\n  }\n\n  // Undo permutation to get x = P^{-1} * y.\n  dst = colsPermutation() * dst;\n}\n\ntemplate<typename _MatrixType>\ntemplate<bool Conjugate, typename RhsType, typename DstType>\nvoid CompleteOrthogonalDecomposition<_MatrixType>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const\n{\n  const Index rank = this->rank();\n\n  if (rank == 0) {\n    dst.setZero();\n    return;\n  }\n\n  typename RhsType::PlainObject c(colsPermutation().transpose()*rhs);\n\n  if (rank < cols()) {\n    applyZOnTheLeftInPlace<!Conjugate>(c);\n  }\n\n  matrixT().topLeftCorner(rank, rank)\n           .template triangularView<Upper>()\n           .transpose().template conjugateIf<Conjugate>()\n           .solveInPlace(c.topRows(rank));\n\n  dst.topRows(rank) = c.topRows(rank);\n  dst.bottomRows(rows()-rank).setZero();\n\n  dst.applyOnTheLeft(householderQ().setLength(rank).template conjugateIf<!Conjugate>() );\n}\n#endif\n\nnamespace internal {\n\ntemplate<typename MatrixType>\nstruct traits<Inverse<CompleteOrthogonalDecomposition<MatrixType> > >\n  : traits<typename Transpose<typename MatrixType::PlainObject>::PlainObject>\n{\n  enum { Flags = 0 };\n};\n\ntemplate<typename DstXprType, typename MatrixType>\nstruct Assignment<DstXprType, Inverse<CompleteOrthogonalDecomposition<MatrixType> >, internal::assign_op<typename DstXprType::Scalar,typename CompleteOrthogonalDecomposition<MatrixType>::Scalar>, Dense2Dense>\n{\n  typedef CompleteOrthogonalDecomposition<MatrixType> CodType;\n  typedef Inverse<CodType> SrcXprType;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename CodType::Scalar> &)\n  {\n    typedef Matrix<typename CodType::Scalar, CodType::RowsAtCompileTime, CodType::RowsAtCompileTime, 0, CodType::MaxRowsAtCompileTime, CodType::MaxRowsAtCompileTime> IdentityMatrixType;\n    dst = src.nestedExpression().solve(IdentityMatrixType::Identity(src.cols(), src.cols()));\n  }\n};\n\n} // end namespace internal\n\n/** \\returns the matrix Q as a sequence of householder transformations */\ntemplate <typename MatrixType>\ntypename CompleteOrthogonalDecomposition<MatrixType>::HouseholderSequenceType\nCompleteOrthogonalDecomposition<MatrixType>::householderQ() const {\n  return m_cpqr.householderQ();\n}\n\n/** \\return the complete orthogonal decomposition of \\c *this.\n  *\n  * \\sa class CompleteOrthogonalDecomposition\n  */\ntemplate <typename Derived>\nconst CompleteOrthogonalDecomposition<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::completeOrthogonalDecomposition() const {\n  return CompleteOrthogonalDecomposition<PlainObject>(eval());\n}\n\n}  // end namespace Eigen\n\n#endif  // EIGEN_COMPLETEORTHOGONALDECOMPOSITION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/QR/FullPivHouseholderQR.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_FULLPIVOTINGHOUSEHOLDERQR_H\n#define EIGEN_FULLPIVOTINGHOUSEHOLDERQR_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate<typename _MatrixType> struct traits<FullPivHouseholderQR<_MatrixType> >\n : traits<_MatrixType>\n{\n  typedef MatrixXpr XprKind;\n  typedef SolverStorage StorageKind;\n  typedef int StorageIndex;\n  enum { Flags = 0 };\n};\n\ntemplate<typename MatrixType> struct FullPivHouseholderQRMatrixQReturnType;\n\ntemplate<typename MatrixType>\nstruct traits<FullPivHouseholderQRMatrixQReturnType<MatrixType> >\n{\n  typedef typename MatrixType::PlainObject ReturnType;\n};\n\n} // end namespace internal\n\n/** \\ingroup QR_Module\n  *\n  * \\class FullPivHouseholderQR\n  *\n  * \\brief Householder rank-revealing QR decomposition of a matrix with full pivoting\n  *\n  * \\tparam _MatrixType the type of the matrix of which we are computing the QR decomposition\n  *\n  * This class performs a rank-revealing QR decomposition of a matrix \\b A into matrices \\b P, \\b P', \\b Q and \\b R\n  * such that \n  * \\f[\n  *  \\mathbf{P} \\, \\mathbf{A} \\, \\mathbf{P}' = \\mathbf{Q} \\, \\mathbf{R}\n  * \\f]\n  * by using Householder transformations. Here, \\b P and \\b P' are permutation matrices, \\b Q a unitary matrix \n  * and \\b R an upper triangular matrix.\n  *\n  * This decomposition performs a very prudent full pivoting in order to be rank-revealing and achieve optimal\n  * numerical stability. The trade-off is that it is slower than HouseholderQR and ColPivHouseholderQR.\n  *\n  * This class supports the \\link InplaceDecomposition inplace decomposition \\endlink mechanism.\n  * \n  * \\sa MatrixBase::fullPivHouseholderQr()\n  */\ntemplate<typename _MatrixType> class FullPivHouseholderQR\n        : public SolverBase<FullPivHouseholderQR<_MatrixType> >\n{\n  public:\n\n    typedef _MatrixType MatrixType;\n    typedef SolverBase<FullPivHouseholderQR> Base;\n    friend class SolverBase<FullPivHouseholderQR>;\n\n    EIGEN_GENERIC_PUBLIC_INTERFACE(FullPivHouseholderQR)\n    enum {\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n    typedef internal::FullPivHouseholderQRMatrixQReturnType<MatrixType> MatrixQReturnType;\n    typedef typename internal::plain_diag_type<MatrixType>::type HCoeffsType;\n    typedef Matrix<StorageIndex, 1,\n                   EIGEN_SIZE_MIN_PREFER_DYNAMIC(ColsAtCompileTime,RowsAtCompileTime), RowMajor, 1,\n                   EIGEN_SIZE_MIN_PREFER_FIXED(MaxColsAtCompileTime,MaxRowsAtCompileTime)> IntDiagSizeVectorType;\n    typedef PermutationMatrix<ColsAtCompileTime, MaxColsAtCompileTime> PermutationType;\n    typedef typename internal::plain_row_type<MatrixType>::type RowVectorType;\n    typedef typename internal::plain_col_type<MatrixType>::type ColVectorType;\n    typedef typename MatrixType::PlainObject PlainObject;\n\n    /** \\brief Default Constructor.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via FullPivHouseholderQR::compute(const MatrixType&).\n      */\n    FullPivHouseholderQR()\n      : m_qr(),\n        m_hCoeffs(),\n        m_rows_transpositions(),\n        m_cols_transpositions(),\n        m_cols_permutation(),\n        m_temp(),\n        m_isInitialized(false),\n        m_usePrescribedThreshold(false) {}\n\n    /** \\brief Default Constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem \\a size.\n      * \\sa FullPivHouseholderQR()\n      */\n    FullPivHouseholderQR(Index rows, Index cols)\n      : m_qr(rows, cols),\n        m_hCoeffs((std::min)(rows,cols)),\n        m_rows_transpositions((std::min)(rows,cols)),\n        m_cols_transpositions((std::min)(rows,cols)),\n        m_cols_permutation(cols),\n        m_temp(cols),\n        m_isInitialized(false),\n        m_usePrescribedThreshold(false) {}\n\n    /** \\brief Constructs a QR factorization from a given matrix\n      *\n      * This constructor computes the QR factorization of the matrix \\a matrix by calling\n      * the method compute(). It is a short cut for:\n      * \n      * \\code\n      * FullPivHouseholderQR<MatrixType> qr(matrix.rows(), matrix.cols());\n      * qr.compute(matrix);\n      * \\endcode\n      * \n      * \\sa compute()\n      */\n    template<typename InputType>\n    explicit FullPivHouseholderQR(const EigenBase<InputType>& matrix)\n      : m_qr(matrix.rows(), matrix.cols()),\n        m_hCoeffs((std::min)(matrix.rows(), matrix.cols())),\n        m_rows_transpositions((std::min)(matrix.rows(), matrix.cols())),\n        m_cols_transpositions((std::min)(matrix.rows(), matrix.cols())),\n        m_cols_permutation(matrix.cols()),\n        m_temp(matrix.cols()),\n        m_isInitialized(false),\n        m_usePrescribedThreshold(false)\n    {\n      compute(matrix.derived());\n    }\n\n    /** \\brief Constructs a QR factorization from a given matrix\n      *\n      * This overloaded constructor is provided for \\link InplaceDecomposition inplace decomposition \\endlink when \\c MatrixType is a Eigen::Ref.\n      *\n      * \\sa FullPivHouseholderQR(const EigenBase&)\n      */\n    template<typename InputType>\n    explicit FullPivHouseholderQR(EigenBase<InputType>& matrix)\n      : m_qr(matrix.derived()),\n        m_hCoeffs((std::min)(matrix.rows(), matrix.cols())),\n        m_rows_transpositions((std::min)(matrix.rows(), matrix.cols())),\n        m_cols_transpositions((std::min)(matrix.rows(), matrix.cols())),\n        m_cols_permutation(matrix.cols()),\n        m_temp(matrix.cols()),\n        m_isInitialized(false),\n        m_usePrescribedThreshold(false)\n    {\n      computeInPlace();\n    }\n\n    #ifdef EIGEN_PARSED_BY_DOXYGEN\n    /** This method finds a solution x to the equation Ax=b, where A is the matrix of which\n      * \\c *this is the QR decomposition.\n      *\n      * \\param b the right-hand-side of the equation to solve.\n      *\n      * \\returns the exact or least-square solution if the rank is greater or equal to the number of columns of A,\n      * and an arbitrary solution otherwise.\n      *\n      * \\note_about_checking_solutions\n      *\n      * \\note_about_arbitrary_choice_of_solution\n      *\n      * Example: \\include FullPivHouseholderQR_solve.cpp\n      * Output: \\verbinclude FullPivHouseholderQR_solve.out\n      */\n    template<typename Rhs>\n    inline const Solve<FullPivHouseholderQR, Rhs>\n    solve(const MatrixBase<Rhs>& b) const;\n    #endif\n\n    /** \\returns Expression object representing the matrix Q\n      */\n    MatrixQReturnType matrixQ(void) const;\n\n    /** \\returns a reference to the matrix where the Householder QR decomposition is stored\n      */\n    const MatrixType& matrixQR() const\n    {\n      eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n      return m_qr;\n    }\n\n    template<typename InputType>\n    FullPivHouseholderQR& compute(const EigenBase<InputType>& matrix);\n\n    /** \\returns a const reference to the column permutation matrix */\n    const PermutationType& colsPermutation() const\n    {\n      eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n      return m_cols_permutation;\n    }\n\n    /** \\returns a const reference to the vector of indices representing the rows transpositions */\n    const IntDiagSizeVectorType& rowsTranspositions() const\n    {\n      eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n      return m_rows_transpositions;\n    }\n\n    /** \\returns the absolute value of the determinant of the matrix of which\n      * *this is the QR decomposition. It has only linear complexity\n      * (that is, O(n) where n is the dimension of the square matrix)\n      * as the QR decomposition has already been computed.\n      *\n      * \\note This is only for square matrices.\n      *\n      * \\warning a determinant can be very big or small, so for matrices\n      * of large enough dimension, there is a risk of overflow/underflow.\n      * One way to work around that is to use logAbsDeterminant() instead.\n      *\n      * \\sa logAbsDeterminant(), MatrixBase::determinant()\n      */\n    typename MatrixType::RealScalar absDeterminant() const;\n\n    /** \\returns the natural log of the absolute value of the determinant of the matrix of which\n      * *this is the QR decomposition. It has only linear complexity\n      * (that is, O(n) where n is the dimension of the square matrix)\n      * as the QR decomposition has already been computed.\n      *\n      * \\note This is only for square matrices.\n      *\n      * \\note This method is useful to work around the risk of overflow/underflow that's inherent\n      * to determinant computation.\n      *\n      * \\sa absDeterminant(), MatrixBase::determinant()\n      */\n    typename MatrixType::RealScalar logAbsDeterminant() const;\n\n    /** \\returns the rank of the matrix of which *this is the QR decomposition.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline Index rank() const\n    {\n      using std::abs;\n      eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n      RealScalar premultiplied_threshold = abs(m_maxpivot) * threshold();\n      Index result = 0;\n      for(Index i = 0; i < m_nonzero_pivots; ++i)\n        result += (abs(m_qr.coeff(i,i)) > premultiplied_threshold);\n      return result;\n    }\n\n    /** \\returns the dimension of the kernel of the matrix of which *this is the QR decomposition.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline Index dimensionOfKernel() const\n    {\n      eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n      return cols() - rank();\n    }\n\n    /** \\returns true if the matrix of which *this is the QR decomposition represents an injective\n      *          linear map, i.e. has trivial kernel; false otherwise.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline bool isInjective() const\n    {\n      eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n      return rank() == cols();\n    }\n\n    /** \\returns true if the matrix of which *this is the QR decomposition represents a surjective\n      *          linear map; false otherwise.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline bool isSurjective() const\n    {\n      eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n      return rank() == rows();\n    }\n\n    /** \\returns true if the matrix of which *this is the QR decomposition is invertible.\n      *\n      * \\note This method has to determine which pivots should be considered nonzero.\n      *       For that, it uses the threshold value that you can control by calling\n      *       setThreshold(const RealScalar&).\n      */\n    inline bool isInvertible() const\n    {\n      eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n      return isInjective() && isSurjective();\n    }\n\n    /** \\returns the inverse of the matrix of which *this is the QR decomposition.\n      *\n      * \\note If this matrix is not invertible, the returned matrix has undefined coefficients.\n      *       Use isInvertible() to first determine whether this matrix is invertible.\n      */\n    inline const Inverse<FullPivHouseholderQR> inverse() const\n    {\n      eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n      return Inverse<FullPivHouseholderQR>(*this);\n    }\n\n    inline Index rows() const { return m_qr.rows(); }\n    inline Index cols() const { return m_qr.cols(); }\n    \n    /** \\returns a const reference to the vector of Householder coefficients used to represent the factor \\c Q.\n      * \n      * For advanced uses only.\n      */\n    const HCoeffsType& hCoeffs() const { return m_hCoeffs; }\n\n    /** Allows to prescribe a threshold to be used by certain methods, such as rank(),\n      * who need to determine when pivots are to be considered nonzero. This is not used for the\n      * QR decomposition itself.\n      *\n      * When it needs to get the threshold value, Eigen calls threshold(). By default, this\n      * uses a formula to automatically determine a reasonable threshold.\n      * Once you have called the present method setThreshold(const RealScalar&),\n      * your value is used instead.\n      *\n      * \\param threshold The new value to use as the threshold.\n      *\n      * A pivot will be considered nonzero if its absolute value is strictly greater than\n      *  \\f$ \\vert pivot \\vert \\leqslant threshold \\times \\vert maxpivot \\vert \\f$\n      * where maxpivot is the biggest pivot.\n      *\n      * If you want to come back to the default behavior, call setThreshold(Default_t)\n      */\n    FullPivHouseholderQR& setThreshold(const RealScalar& threshold)\n    {\n      m_usePrescribedThreshold = true;\n      m_prescribedThreshold = threshold;\n      return *this;\n    }\n\n    /** Allows to come back to the default behavior, letting Eigen use its default formula for\n      * determining the threshold.\n      *\n      * You should pass the special object Eigen::Default as parameter here.\n      * \\code qr.setThreshold(Eigen::Default); \\endcode\n      *\n      * See the documentation of setThreshold(const RealScalar&).\n      */\n    FullPivHouseholderQR& setThreshold(Default_t)\n    {\n      m_usePrescribedThreshold = false;\n      return *this;\n    }\n\n    /** Returns the threshold that will be used by certain methods such as rank().\n      *\n      * See the documentation of setThreshold(const RealScalar&).\n      */\n    RealScalar threshold() const\n    {\n      eigen_assert(m_isInitialized || m_usePrescribedThreshold);\n      return m_usePrescribedThreshold ? m_prescribedThreshold\n      // this formula comes from experimenting (see \"LU precision tuning\" thread on the list)\n      // and turns out to be identical to Higham's formula used already in LDLt.\n                                      : NumTraits<Scalar>::epsilon() * RealScalar(m_qr.diagonalSize());\n    }\n\n    /** \\returns the number of nonzero pivots in the QR decomposition.\n      * Here nonzero is meant in the exact sense, not in a fuzzy sense.\n      * So that notion isn't really intrinsically interesting, but it is\n      * still useful when implementing algorithms.\n      *\n      * \\sa rank()\n      */\n    inline Index nonzeroPivots() const\n    {\n      eigen_assert(m_isInitialized && \"LU is not initialized.\");\n      return m_nonzero_pivots;\n    }\n\n    /** \\returns the absolute value of the biggest pivot, i.e. the biggest\n      *          diagonal coefficient of U.\n      */\n    RealScalar maxPivot() const { return m_maxpivot; }\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<typename RhsType, typename DstType>\n    void _solve_impl(const RhsType &rhs, DstType &dst) const;\n\n    template<bool Conjugate, typename RhsType, typename DstType>\n    void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const;\n    #endif\n\n  protected:\n\n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n    }\n\n    void computeInPlace();\n\n    MatrixType m_qr;\n    HCoeffsType m_hCoeffs;\n    IntDiagSizeVectorType m_rows_transpositions;\n    IntDiagSizeVectorType m_cols_transpositions;\n    PermutationType m_cols_permutation;\n    RowVectorType m_temp;\n    bool m_isInitialized, m_usePrescribedThreshold;\n    RealScalar m_prescribedThreshold, m_maxpivot;\n    Index m_nonzero_pivots;\n    RealScalar m_precision;\n    Index m_det_pq;\n};\n\ntemplate<typename MatrixType>\ntypename MatrixType::RealScalar FullPivHouseholderQR<MatrixType>::absDeterminant() const\n{\n  using std::abs;\n  eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n  eigen_assert(m_qr.rows() == m_qr.cols() && \"You can't take the determinant of a non-square matrix!\");\n  return abs(m_qr.diagonal().prod());\n}\n\ntemplate<typename MatrixType>\ntypename MatrixType::RealScalar FullPivHouseholderQR<MatrixType>::logAbsDeterminant() const\n{\n  eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n  eigen_assert(m_qr.rows() == m_qr.cols() && \"You can't take the determinant of a non-square matrix!\");\n  return m_qr.diagonal().cwiseAbs().array().log().sum();\n}\n\n/** Performs the QR factorization of the given matrix \\a matrix. The result of\n  * the factorization is stored into \\c *this, and a reference to \\c *this\n  * is returned.\n  *\n  * \\sa class FullPivHouseholderQR, FullPivHouseholderQR(const MatrixType&)\n  */\ntemplate<typename MatrixType>\ntemplate<typename InputType>\nFullPivHouseholderQR<MatrixType>& FullPivHouseholderQR<MatrixType>::compute(const EigenBase<InputType>& matrix)\n{\n  m_qr = matrix.derived();\n  computeInPlace();\n  return *this;\n}\n\ntemplate<typename MatrixType>\nvoid FullPivHouseholderQR<MatrixType>::computeInPlace()\n{\n  check_template_parameters();\n\n  using std::abs;\n  Index rows = m_qr.rows();\n  Index cols = m_qr.cols();\n  Index size = (std::min)(rows,cols);\n\n  \n  m_hCoeffs.resize(size);\n\n  m_temp.resize(cols);\n\n  m_precision = NumTraits<Scalar>::epsilon() * RealScalar(size);\n\n  m_rows_transpositions.resize(size);\n  m_cols_transpositions.resize(size);\n  Index number_of_transpositions = 0;\n\n  RealScalar biggest(0);\n\n  m_nonzero_pivots = size; // the generic case is that in which all pivots are nonzero (invertible case)\n  m_maxpivot = RealScalar(0);\n\n  for (Index k = 0; k < size; ++k)\n  {\n    Index row_of_biggest_in_corner, col_of_biggest_in_corner;\n    typedef internal::scalar_score_coeff_op<Scalar> Scoring;\n    typedef typename Scoring::result_type Score;\n\n    Score score = m_qr.bottomRightCorner(rows-k, cols-k)\n                      .unaryExpr(Scoring())\n                      .maxCoeff(&row_of_biggest_in_corner, &col_of_biggest_in_corner);\n    row_of_biggest_in_corner += k;\n    col_of_biggest_in_corner += k;\n    RealScalar biggest_in_corner = internal::abs_knowing_score<Scalar>()(m_qr(row_of_biggest_in_corner, col_of_biggest_in_corner), score);\n    if(k==0) biggest = biggest_in_corner;\n\n    // if the corner is negligible, then we have less than full rank, and we can finish early\n    if(internal::isMuchSmallerThan(biggest_in_corner, biggest, m_precision))\n    {\n      m_nonzero_pivots = k;\n      for(Index i = k; i < size; i++)\n      {\n        m_rows_transpositions.coeffRef(i) = internal::convert_index<StorageIndex>(i);\n        m_cols_transpositions.coeffRef(i) = internal::convert_index<StorageIndex>(i);\n        m_hCoeffs.coeffRef(i) = Scalar(0);\n      }\n      break;\n    }\n\n    m_rows_transpositions.coeffRef(k) = internal::convert_index<StorageIndex>(row_of_biggest_in_corner);\n    m_cols_transpositions.coeffRef(k) = internal::convert_index<StorageIndex>(col_of_biggest_in_corner);\n    if(k != row_of_biggest_in_corner) {\n      m_qr.row(k).tail(cols-k).swap(m_qr.row(row_of_biggest_in_corner).tail(cols-k));\n      ++number_of_transpositions;\n    }\n    if(k != col_of_biggest_in_corner) {\n      m_qr.col(k).swap(m_qr.col(col_of_biggest_in_corner));\n      ++number_of_transpositions;\n    }\n\n    RealScalar beta;\n    m_qr.col(k).tail(rows-k).makeHouseholderInPlace(m_hCoeffs.coeffRef(k), beta);\n    m_qr.coeffRef(k,k) = beta;\n\n    // remember the maximum absolute value of diagonal coefficients\n    if(abs(beta) > m_maxpivot) m_maxpivot = abs(beta);\n\n    m_qr.bottomRightCorner(rows-k, cols-k-1)\n        .applyHouseholderOnTheLeft(m_qr.col(k).tail(rows-k-1), m_hCoeffs.coeffRef(k), &m_temp.coeffRef(k+1));\n  }\n\n  m_cols_permutation.setIdentity(cols);\n  for(Index k = 0; k < size; ++k)\n    m_cols_permutation.applyTranspositionOnTheRight(k, m_cols_transpositions.coeff(k));\n\n  m_det_pq = (number_of_transpositions%2) ? -1 : 1;\n  m_isInitialized = true;\n}\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename _MatrixType>\ntemplate<typename RhsType, typename DstType>\nvoid FullPivHouseholderQR<_MatrixType>::_solve_impl(const RhsType &rhs, DstType &dst) const\n{\n  const Index l_rank = rank();\n\n  // FIXME introduce nonzeroPivots() and use it here. and more generally,\n  // make the same improvements in this dec as in FullPivLU.\n  if(l_rank==0)\n  {\n    dst.setZero();\n    return;\n  }\n\n  typename RhsType::PlainObject c(rhs);\n\n  Matrix<typename RhsType::Scalar,1,RhsType::ColsAtCompileTime> temp(rhs.cols());\n  for (Index k = 0; k < l_rank; ++k)\n  {\n    Index remainingSize = rows()-k;\n    c.row(k).swap(c.row(m_rows_transpositions.coeff(k)));\n    c.bottomRightCorner(remainingSize, rhs.cols())\n      .applyHouseholderOnTheLeft(m_qr.col(k).tail(remainingSize-1),\n                               m_hCoeffs.coeff(k), &temp.coeffRef(0));\n  }\n\n  m_qr.topLeftCorner(l_rank, l_rank)\n      .template triangularView<Upper>()\n      .solveInPlace(c.topRows(l_rank));\n\n  for(Index i = 0; i < l_rank; ++i) dst.row(m_cols_permutation.indices().coeff(i)) = c.row(i);\n  for(Index i = l_rank; i < cols(); ++i) dst.row(m_cols_permutation.indices().coeff(i)).setZero();\n}\n\ntemplate<typename _MatrixType>\ntemplate<bool Conjugate, typename RhsType, typename DstType>\nvoid FullPivHouseholderQR<_MatrixType>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const\n{\n  const Index l_rank = rank();\n\n  if(l_rank == 0)\n  {\n    dst.setZero();\n    return;\n  }\n\n  typename RhsType::PlainObject c(m_cols_permutation.transpose()*rhs);\n\n  m_qr.topLeftCorner(l_rank, l_rank)\n         .template triangularView<Upper>()\n         .transpose().template conjugateIf<Conjugate>()\n         .solveInPlace(c.topRows(l_rank));\n\n  dst.topRows(l_rank) = c.topRows(l_rank);\n  dst.bottomRows(rows()-l_rank).setZero();\n\n  Matrix<Scalar, 1, DstType::ColsAtCompileTime> temp(dst.cols());\n  const Index size = (std::min)(rows(), cols());\n  for (Index k = size-1; k >= 0; --k)\n  {\n    Index remainingSize = rows()-k;\n\n    dst.bottomRightCorner(remainingSize, dst.cols())\n       .applyHouseholderOnTheLeft(m_qr.col(k).tail(remainingSize-1).template conjugateIf<!Conjugate>(),\n                                  m_hCoeffs.template conjugateIf<Conjugate>().coeff(k), &temp.coeffRef(0));\n\n    dst.row(k).swap(dst.row(m_rows_transpositions.coeff(k)));\n  }\n}\n#endif\n\nnamespace internal {\n  \ntemplate<typename DstXprType, typename MatrixType>\nstruct Assignment<DstXprType, Inverse<FullPivHouseholderQR<MatrixType> >, internal::assign_op<typename DstXprType::Scalar,typename FullPivHouseholderQR<MatrixType>::Scalar>, Dense2Dense>\n{\n  typedef FullPivHouseholderQR<MatrixType> QrType;\n  typedef Inverse<QrType> SrcXprType;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename QrType::Scalar> &)\n  {    \n    dst = src.nestedExpression().solve(MatrixType::Identity(src.rows(), src.cols()));\n  }\n};\n\n/** \\ingroup QR_Module\n  *\n  * \\brief Expression type for return value of FullPivHouseholderQR::matrixQ()\n  *\n  * \\tparam MatrixType type of underlying dense matrix\n  */\ntemplate<typename MatrixType> struct FullPivHouseholderQRMatrixQReturnType\n  : public ReturnByValue<FullPivHouseholderQRMatrixQReturnType<MatrixType> >\n{\npublic:\n  typedef typename FullPivHouseholderQR<MatrixType>::IntDiagSizeVectorType IntDiagSizeVectorType;\n  typedef typename internal::plain_diag_type<MatrixType>::type HCoeffsType;\n  typedef Matrix<typename MatrixType::Scalar, 1, MatrixType::RowsAtCompileTime, RowMajor, 1,\n                 MatrixType::MaxRowsAtCompileTime> WorkVectorType;\n\n  FullPivHouseholderQRMatrixQReturnType(const MatrixType&       qr,\n                                        const HCoeffsType&      hCoeffs,\n                                        const IntDiagSizeVectorType& rowsTranspositions)\n    : m_qr(qr),\n      m_hCoeffs(hCoeffs),\n      m_rowsTranspositions(rowsTranspositions)\n  {}\n\n  template <typename ResultType>\n  void evalTo(ResultType& result) const\n  {\n    const Index rows = m_qr.rows();\n    WorkVectorType workspace(rows);\n    evalTo(result, workspace);\n  }\n\n  template <typename ResultType>\n  void evalTo(ResultType& result, WorkVectorType& workspace) const\n  {\n    using numext::conj;\n    // compute the product H'_0 H'_1 ... H'_n-1,\n    // where H_k is the k-th Householder transformation I - h_k v_k v_k'\n    // and v_k is the k-th Householder vector [1,m_qr(k+1,k), m_qr(k+2,k), ...]\n    const Index rows = m_qr.rows();\n    const Index cols = m_qr.cols();\n    const Index size = (std::min)(rows, cols);\n    workspace.resize(rows);\n    result.setIdentity(rows, rows);\n    for (Index k = size-1; k >= 0; k--)\n    {\n      result.block(k, k, rows-k, rows-k)\n            .applyHouseholderOnTheLeft(m_qr.col(k).tail(rows-k-1), conj(m_hCoeffs.coeff(k)), &workspace.coeffRef(k));\n      result.row(k).swap(result.row(m_rowsTranspositions.coeff(k)));\n    }\n  }\n\n  Index rows() const { return m_qr.rows(); }\n  Index cols() const { return m_qr.rows(); }\n\nprotected:\n  typename MatrixType::Nested m_qr;\n  typename HCoeffsType::Nested m_hCoeffs;\n  typename IntDiagSizeVectorType::Nested m_rowsTranspositions;\n};\n\n// template<typename MatrixType>\n// struct evaluator<FullPivHouseholderQRMatrixQReturnType<MatrixType> >\n//  : public evaluator<ReturnByValue<FullPivHouseholderQRMatrixQReturnType<MatrixType> > >\n// {};\n\n} // end namespace internal\n\ntemplate<typename MatrixType>\ninline typename FullPivHouseholderQR<MatrixType>::MatrixQReturnType FullPivHouseholderQR<MatrixType>::matrixQ() const\n{\n  eigen_assert(m_isInitialized && \"FullPivHouseholderQR is not initialized.\");\n  return MatrixQReturnType(m_qr, m_hCoeffs, m_rows_transpositions);\n}\n\n/** \\return the full-pivoting Householder QR decomposition of \\c *this.\n  *\n  * \\sa class FullPivHouseholderQR\n  */\ntemplate<typename Derived>\nconst FullPivHouseholderQR<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::fullPivHouseholderQr() const\n{\n  return FullPivHouseholderQR<PlainObject>(eval());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_FULLPIVOTINGHOUSEHOLDERQR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/QR/HouseholderQR.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2010 Vincent Lejeune\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_QR_H\n#define EIGEN_QR_H\n\nnamespace Eigen { \n\nnamespace internal {\ntemplate<typename _MatrixType> struct traits<HouseholderQR<_MatrixType> >\n : traits<_MatrixType>\n{\n  typedef MatrixXpr XprKind;\n  typedef SolverStorage StorageKind;\n  typedef int StorageIndex;\n  enum { Flags = 0 };\n};\n\n} // end namespace internal\n\n/** \\ingroup QR_Module\n  *\n  *\n  * \\class HouseholderQR\n  *\n  * \\brief Householder QR decomposition of a matrix\n  *\n  * \\tparam _MatrixType the type of the matrix of which we are computing the QR decomposition\n  *\n  * This class performs a QR decomposition of a matrix \\b A into matrices \\b Q and \\b R\n  * such that \n  * \\f[\n  *  \\mathbf{A} = \\mathbf{Q} \\, \\mathbf{R}\n  * \\f]\n  * by using Householder transformations. Here, \\b Q a unitary matrix and \\b R an upper triangular matrix.\n  * The result is stored in a compact way compatible with LAPACK.\n  *\n  * Note that no pivoting is performed. This is \\b not a rank-revealing decomposition.\n  * If you want that feature, use FullPivHouseholderQR or ColPivHouseholderQR instead.\n  *\n  * This Householder QR decomposition is faster, but less numerically stable and less feature-full than\n  * FullPivHouseholderQR or ColPivHouseholderQR.\n  *\n  * This class supports the \\link InplaceDecomposition inplace decomposition \\endlink mechanism.\n  *\n  * \\sa MatrixBase::householderQr()\n  */\ntemplate<typename _MatrixType> class HouseholderQR\n        : public SolverBase<HouseholderQR<_MatrixType> >\n{\n  public:\n\n    typedef _MatrixType MatrixType;\n    typedef SolverBase<HouseholderQR> Base;\n    friend class SolverBase<HouseholderQR>;\n\n    EIGEN_GENERIC_PUBLIC_INTERFACE(HouseholderQR)\n    enum {\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n    typedef Matrix<Scalar, RowsAtCompileTime, RowsAtCompileTime, (MatrixType::Flags&RowMajorBit) ? RowMajor : ColMajor, MaxRowsAtCompileTime, MaxRowsAtCompileTime> MatrixQType;\n    typedef typename internal::plain_diag_type<MatrixType>::type HCoeffsType;\n    typedef typename internal::plain_row_type<MatrixType>::type RowVectorType;\n    typedef HouseholderSequence<MatrixType,typename internal::remove_all<typename HCoeffsType::ConjugateReturnType>::type> HouseholderSequenceType;\n\n    /**\n      * \\brief Default Constructor.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via HouseholderQR::compute(const MatrixType&).\n      */\n    HouseholderQR() : m_qr(), m_hCoeffs(), m_temp(), m_isInitialized(false) {}\n\n    /** \\brief Default Constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem \\a size.\n      * \\sa HouseholderQR()\n      */\n    HouseholderQR(Index rows, Index cols)\n      : m_qr(rows, cols),\n        m_hCoeffs((std::min)(rows,cols)),\n        m_temp(cols),\n        m_isInitialized(false) {}\n\n    /** \\brief Constructs a QR factorization from a given matrix\n      *\n      * This constructor computes the QR factorization of the matrix \\a matrix by calling\n      * the method compute(). It is a short cut for:\n      * \n      * \\code\n      * HouseholderQR<MatrixType> qr(matrix.rows(), matrix.cols());\n      * qr.compute(matrix);\n      * \\endcode\n      * \n      * \\sa compute()\n      */\n    template<typename InputType>\n    explicit HouseholderQR(const EigenBase<InputType>& matrix)\n      : m_qr(matrix.rows(), matrix.cols()),\n        m_hCoeffs((std::min)(matrix.rows(),matrix.cols())),\n        m_temp(matrix.cols()),\n        m_isInitialized(false)\n    {\n      compute(matrix.derived());\n    }\n\n\n    /** \\brief Constructs a QR factorization from a given matrix\n      *\n      * This overloaded constructor is provided for \\link InplaceDecomposition inplace decomposition \\endlink when\n      * \\c MatrixType is a Eigen::Ref.\n      *\n      * \\sa HouseholderQR(const EigenBase&)\n      */\n    template<typename InputType>\n    explicit HouseholderQR(EigenBase<InputType>& matrix)\n      : m_qr(matrix.derived()),\n        m_hCoeffs((std::min)(matrix.rows(),matrix.cols())),\n        m_temp(matrix.cols()),\n        m_isInitialized(false)\n    {\n      computeInPlace();\n    }\n\n    #ifdef EIGEN_PARSED_BY_DOXYGEN\n    /** This method finds a solution x to the equation Ax=b, where A is the matrix of which\n      * *this is the QR decomposition, if any exists.\n      *\n      * \\param b the right-hand-side of the equation to solve.\n      *\n      * \\returns a solution.\n      *\n      * \\note_about_checking_solutions\n      *\n      * \\note_about_arbitrary_choice_of_solution\n      *\n      * Example: \\include HouseholderQR_solve.cpp\n      * Output: \\verbinclude HouseholderQR_solve.out\n      */\n    template<typename Rhs>\n    inline const Solve<HouseholderQR, Rhs>\n    solve(const MatrixBase<Rhs>& b) const;\n    #endif\n\n    /** This method returns an expression of the unitary matrix Q as a sequence of Householder transformations.\n      *\n      * The returned expression can directly be used to perform matrix products. It can also be assigned to a dense Matrix object.\n      * Here is an example showing how to recover the full or thin matrix Q, as well as how to perform matrix products using operator*:\n      *\n      * Example: \\include HouseholderQR_householderQ.cpp\n      * Output: \\verbinclude HouseholderQR_householderQ.out\n      */\n    HouseholderSequenceType householderQ() const\n    {\n      eigen_assert(m_isInitialized && \"HouseholderQR is not initialized.\");\n      return HouseholderSequenceType(m_qr, m_hCoeffs.conjugate());\n    }\n\n    /** \\returns a reference to the matrix where the Householder QR decomposition is stored\n      * in a LAPACK-compatible way.\n      */\n    const MatrixType& matrixQR() const\n    {\n        eigen_assert(m_isInitialized && \"HouseholderQR is not initialized.\");\n        return m_qr;\n    }\n\n    template<typename InputType>\n    HouseholderQR& compute(const EigenBase<InputType>& matrix) {\n      m_qr = matrix.derived();\n      computeInPlace();\n      return *this;\n    }\n\n    /** \\returns the absolute value of the determinant of the matrix of which\n      * *this is the QR decomposition. It has only linear complexity\n      * (that is, O(n) where n is the dimension of the square matrix)\n      * as the QR decomposition has already been computed.\n      *\n      * \\note This is only for square matrices.\n      *\n      * \\warning a determinant can be very big or small, so for matrices\n      * of large enough dimension, there is a risk of overflow/underflow.\n      * One way to work around that is to use logAbsDeterminant() instead.\n      *\n      * \\sa logAbsDeterminant(), MatrixBase::determinant()\n      */\n    typename MatrixType::RealScalar absDeterminant() const;\n\n    /** \\returns the natural log of the absolute value of the determinant of the matrix of which\n      * *this is the QR decomposition. It has only linear complexity\n      * (that is, O(n) where n is the dimension of the square matrix)\n      * as the QR decomposition has already been computed.\n      *\n      * \\note This is only for square matrices.\n      *\n      * \\note This method is useful to work around the risk of overflow/underflow that's inherent\n      * to determinant computation.\n      *\n      * \\sa absDeterminant(), MatrixBase::determinant()\n      */\n    typename MatrixType::RealScalar logAbsDeterminant() const;\n\n    inline Index rows() const { return m_qr.rows(); }\n    inline Index cols() const { return m_qr.cols(); }\n\n    /** \\returns a const reference to the vector of Householder coefficients used to represent the factor \\c Q.\n      * \n      * For advanced uses only.\n      */\n    const HCoeffsType& hCoeffs() const { return m_hCoeffs; }\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<typename RhsType, typename DstType>\n    void _solve_impl(const RhsType &rhs, DstType &dst) const;\n\n    template<bool Conjugate, typename RhsType, typename DstType>\n    void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const;\n    #endif\n\n  protected:\n\n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n    }\n\n    void computeInPlace();\n\n    MatrixType m_qr;\n    HCoeffsType m_hCoeffs;\n    RowVectorType m_temp;\n    bool m_isInitialized;\n};\n\ntemplate<typename MatrixType>\ntypename MatrixType::RealScalar HouseholderQR<MatrixType>::absDeterminant() const\n{\n  using std::abs;\n  eigen_assert(m_isInitialized && \"HouseholderQR is not initialized.\");\n  eigen_assert(m_qr.rows() == m_qr.cols() && \"You can't take the determinant of a non-square matrix!\");\n  return abs(m_qr.diagonal().prod());\n}\n\ntemplate<typename MatrixType>\ntypename MatrixType::RealScalar HouseholderQR<MatrixType>::logAbsDeterminant() const\n{\n  eigen_assert(m_isInitialized && \"HouseholderQR is not initialized.\");\n  eigen_assert(m_qr.rows() == m_qr.cols() && \"You can't take the determinant of a non-square matrix!\");\n  return m_qr.diagonal().cwiseAbs().array().log().sum();\n}\n\nnamespace internal {\n\n/** \\internal */\ntemplate<typename MatrixQR, typename HCoeffs>\nvoid householder_qr_inplace_unblocked(MatrixQR& mat, HCoeffs& hCoeffs, typename MatrixQR::Scalar* tempData = 0)\n{\n  typedef typename MatrixQR::Scalar Scalar;\n  typedef typename MatrixQR::RealScalar RealScalar;\n  Index rows = mat.rows();\n  Index cols = mat.cols();\n  Index size = (std::min)(rows,cols);\n\n  eigen_assert(hCoeffs.size() == size);\n\n  typedef Matrix<Scalar,MatrixQR::ColsAtCompileTime,1> TempType;\n  TempType tempVector;\n  if(tempData==0)\n  {\n    tempVector.resize(cols);\n    tempData = tempVector.data();\n  }\n\n  for(Index k = 0; k < size; ++k)\n  {\n    Index remainingRows = rows - k;\n    Index remainingCols = cols - k - 1;\n\n    RealScalar beta;\n    mat.col(k).tail(remainingRows).makeHouseholderInPlace(hCoeffs.coeffRef(k), beta);\n    mat.coeffRef(k,k) = beta;\n\n    // apply H to remaining part of m_qr from the left\n    mat.bottomRightCorner(remainingRows, remainingCols)\n        .applyHouseholderOnTheLeft(mat.col(k).tail(remainingRows-1), hCoeffs.coeffRef(k), tempData+k+1);\n  }\n}\n\n/** \\internal */\ntemplate<typename MatrixQR, typename HCoeffs,\n  typename MatrixQRScalar = typename MatrixQR::Scalar,\n  bool InnerStrideIsOne = (MatrixQR::InnerStrideAtCompileTime == 1 && HCoeffs::InnerStrideAtCompileTime == 1)>\nstruct householder_qr_inplace_blocked\n{\n  // This is specialized for LAPACK-supported Scalar types in HouseholderQR_LAPACKE.h\n  static void run(MatrixQR& mat, HCoeffs& hCoeffs, Index maxBlockSize=32,\n      typename MatrixQR::Scalar* tempData = 0)\n  {\n    typedef typename MatrixQR::Scalar Scalar;\n    typedef Block<MatrixQR,Dynamic,Dynamic> BlockType;\n\n    Index rows = mat.rows();\n    Index cols = mat.cols();\n    Index size = (std::min)(rows, cols);\n\n    typedef Matrix<Scalar,Dynamic,1,ColMajor,MatrixQR::MaxColsAtCompileTime,1> TempType;\n    TempType tempVector;\n    if(tempData==0)\n    {\n      tempVector.resize(cols);\n      tempData = tempVector.data();\n    }\n\n    Index blockSize = (std::min)(maxBlockSize,size);\n\n    Index k = 0;\n    for (k = 0; k < size; k += blockSize)\n    {\n      Index bs = (std::min)(size-k,blockSize);  // actual size of the block\n      Index tcols = cols - k - bs;              // trailing columns\n      Index brows = rows-k;                     // rows of the block\n\n      // partition the matrix:\n      //        A00 | A01 | A02\n      // mat  = A10 | A11 | A12\n      //        A20 | A21 | A22\n      // and performs the qr dec of [A11^T A12^T]^T\n      // and update [A21^T A22^T]^T using level 3 operations.\n      // Finally, the algorithm continue on A22\n\n      BlockType A11_21 = mat.block(k,k,brows,bs);\n      Block<HCoeffs,Dynamic,1> hCoeffsSegment = hCoeffs.segment(k,bs);\n\n      householder_qr_inplace_unblocked(A11_21, hCoeffsSegment, tempData);\n\n      if(tcols)\n      {\n        BlockType A21_22 = mat.block(k,k+bs,brows,tcols);\n        apply_block_householder_on_the_left(A21_22,A11_21,hCoeffsSegment, false); // false == backward\n      }\n    }\n  }\n};\n\n} // end namespace internal\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename _MatrixType>\ntemplate<typename RhsType, typename DstType>\nvoid HouseholderQR<_MatrixType>::_solve_impl(const RhsType &rhs, DstType &dst) const\n{\n  const Index rank = (std::min)(rows(), cols());\n\n  typename RhsType::PlainObject c(rhs);\n\n  c.applyOnTheLeft(householderQ().setLength(rank).adjoint() );\n\n  m_qr.topLeftCorner(rank, rank)\n      .template triangularView<Upper>()\n      .solveInPlace(c.topRows(rank));\n\n  dst.topRows(rank) = c.topRows(rank);\n  dst.bottomRows(cols()-rank).setZero();\n}\n\ntemplate<typename _MatrixType>\ntemplate<bool Conjugate, typename RhsType, typename DstType>\nvoid HouseholderQR<_MatrixType>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const\n{\n  const Index rank = (std::min)(rows(), cols());\n\n  typename RhsType::PlainObject c(rhs);\n\n  m_qr.topLeftCorner(rank, rank)\n      .template triangularView<Upper>()\n      .transpose().template conjugateIf<Conjugate>()\n      .solveInPlace(c.topRows(rank));\n\n  dst.topRows(rank) = c.topRows(rank);\n  dst.bottomRows(rows()-rank).setZero();\n\n  dst.applyOnTheLeft(householderQ().setLength(rank).template conjugateIf<!Conjugate>() );\n}\n#endif\n\n/** Performs the QR factorization of the given matrix \\a matrix. The result of\n  * the factorization is stored into \\c *this, and a reference to \\c *this\n  * is returned.\n  *\n  * \\sa class HouseholderQR, HouseholderQR(const MatrixType&)\n  */\ntemplate<typename MatrixType>\nvoid HouseholderQR<MatrixType>::computeInPlace()\n{\n  check_template_parameters();\n  \n  Index rows = m_qr.rows();\n  Index cols = m_qr.cols();\n  Index size = (std::min)(rows,cols);\n\n  m_hCoeffs.resize(size);\n\n  m_temp.resize(cols);\n\n  internal::householder_qr_inplace_blocked<MatrixType, HCoeffsType>::run(m_qr, m_hCoeffs, 48, m_temp.data());\n\n  m_isInitialized = true;\n}\n\n/** \\return the Householder QR decomposition of \\c *this.\n  *\n  * \\sa class HouseholderQR\n  */\ntemplate<typename Derived>\nconst HouseholderQR<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::householderQr() const\n{\n  return HouseholderQR<PlainObject>(eval());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_QR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/QR/HouseholderQR_LAPACKE.h",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Eigen bindings to LAPACKe\n *    Householder QR decomposition of a matrix w/o pivoting based on\n *    LAPACKE_?geqrf function.\n ********************************************************************************\n*/\n\n#ifndef EIGEN_QR_LAPACKE_H\n#define EIGEN_QR_LAPACKE_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\internal Specialization for the data types supported by LAPACKe */\n\n#define EIGEN_LAPACKE_QR_NOPIV(EIGTYPE, LAPACKE_TYPE, LAPACKE_PREFIX) \\\ntemplate<typename MatrixQR, typename HCoeffs> \\\nstruct householder_qr_inplace_blocked<MatrixQR, HCoeffs, EIGTYPE, true> \\\n{ \\\n  static void run(MatrixQR& mat, HCoeffs& hCoeffs, Index = 32, \\\n      typename MatrixQR::Scalar* = 0) \\\n  { \\\n    lapack_int m = (lapack_int) mat.rows(); \\\n    lapack_int n = (lapack_int) mat.cols(); \\\n    lapack_int lda = (lapack_int) mat.outerStride(); \\\n    lapack_int matrix_order = (MatrixQR::IsRowMajor) ? LAPACK_ROW_MAJOR : LAPACK_COL_MAJOR; \\\n    LAPACKE_##LAPACKE_PREFIX##geqrf( matrix_order, m, n, (LAPACKE_TYPE*)mat.data(), lda, (LAPACKE_TYPE*)hCoeffs.data()); \\\n    hCoeffs.adjointInPlace(); \\\n  } \\\n};\n\nEIGEN_LAPACKE_QR_NOPIV(double, double, d)\nEIGEN_LAPACKE_QR_NOPIV(float, float, s)\nEIGEN_LAPACKE_QR_NOPIV(dcomplex, lapack_complex_double, z)\nEIGEN_LAPACKE_QR_NOPIV(scomplex, lapack_complex_float, c)\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_QR_LAPACKE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SPQRSupport/SuiteSparseQRSupport.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Desire Nuentsa <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SUITESPARSEQRSUPPORT_H\n#define EIGEN_SUITESPARSEQRSUPPORT_H\n\nnamespace Eigen {\n  \n  template<typename MatrixType> class SPQR; \n  template<typename SPQRType> struct SPQRMatrixQReturnType; \n  template<typename SPQRType> struct SPQRMatrixQTransposeReturnType; \n  template <typename SPQRType, typename Derived> struct SPQR_QProduct;\n  namespace internal {\n    template <typename SPQRType> struct traits<SPQRMatrixQReturnType<SPQRType> >\n    {\n      typedef typename SPQRType::MatrixType ReturnType;\n    };\n    template <typename SPQRType> struct traits<SPQRMatrixQTransposeReturnType<SPQRType> >\n    {\n      typedef typename SPQRType::MatrixType ReturnType;\n    };\n    template <typename SPQRType, typename Derived> struct traits<SPQR_QProduct<SPQRType, Derived> >\n    {\n      typedef typename Derived::PlainObject ReturnType;\n    };\n  } // End namespace internal\n  \n/**\n  * \\ingroup SPQRSupport_Module\n  * \\class SPQR\n  * \\brief Sparse QR factorization based on SuiteSparseQR library\n  *\n  * This class is used to perform a multithreaded and multifrontal rank-revealing QR decomposition\n  * of sparse matrices. The result is then used to solve linear leasts_square systems.\n  * Clearly, a QR factorization is returned such that A*P = Q*R where :\n  *\n  * P is the column permutation. Use colsPermutation() to get it.\n  *\n  * Q is the orthogonal matrix represented as Householder reflectors.\n  * Use matrixQ() to get an expression and matrixQ().transpose() to get the transpose.\n  * You can then apply it to a vector.\n  *\n  * R is the sparse triangular factor. Use matrixQR() to get it as SparseMatrix.\n  * NOTE : The Index type of R is always SuiteSparse_long. You can get it with SPQR::Index\n  *\n  * \\tparam _MatrixType The type of the sparse matrix A, must be a column-major SparseMatrix<>\n  *\n  * \\implsparsesolverconcept\n  *\n  *\n  */\ntemplate<typename _MatrixType>\nclass SPQR : public SparseSolverBase<SPQR<_MatrixType> >\n{\n  protected:\n    typedef SparseSolverBase<SPQR<_MatrixType> > Base;\n    using Base::m_isInitialized;\n  public:\n    typedef typename _MatrixType::Scalar Scalar;\n    typedef typename _MatrixType::RealScalar RealScalar;\n    typedef SuiteSparse_long StorageIndex ;\n    typedef SparseMatrix<Scalar, ColMajor, StorageIndex> MatrixType;\n    typedef Map<PermutationMatrix<Dynamic, Dynamic, StorageIndex> > PermutationType;\n    enum {\n      ColsAtCompileTime = Dynamic,\n      MaxColsAtCompileTime = Dynamic\n    };\n  public:\n    SPQR() \n      : m_analysisIsOk(false),\n        m_factorizationIsOk(false),\n        m_isRUpToDate(false),\n        m_ordering(SPQR_ORDERING_DEFAULT),\n        m_allow_tol(SPQR_DEFAULT_TOL),\n        m_tolerance (NumTraits<Scalar>::epsilon()),\n        m_cR(0),\n        m_E(0),\n        m_H(0),\n        m_HPinv(0),\n        m_HTau(0),\n        m_useDefaultThreshold(true)\n    { \n      cholmod_l_start(&m_cc);\n    }\n    \n    explicit SPQR(const _MatrixType& matrix)\n      : m_analysisIsOk(false),\n        m_factorizationIsOk(false),\n        m_isRUpToDate(false),\n        m_ordering(SPQR_ORDERING_DEFAULT),\n        m_allow_tol(SPQR_DEFAULT_TOL),\n        m_tolerance (NumTraits<Scalar>::epsilon()),\n        m_cR(0),\n        m_E(0),\n        m_H(0),\n        m_HPinv(0),\n        m_HTau(0),\n        m_useDefaultThreshold(true)\n    {\n      cholmod_l_start(&m_cc);\n      compute(matrix);\n    }\n    \n    ~SPQR()\n    {\n      SPQR_free();\n      cholmod_l_finish(&m_cc);\n    }\n    void SPQR_free()\n    {\n      cholmod_l_free_sparse(&m_H, &m_cc);\n      cholmod_l_free_sparse(&m_cR, &m_cc);\n      cholmod_l_free_dense(&m_HTau, &m_cc);\n      std::free(m_E);\n      std::free(m_HPinv);\n    }\n\n    void compute(const _MatrixType& matrix)\n    {\n      if(m_isInitialized) SPQR_free();\n\n      MatrixType mat(matrix);\n      \n      /* Compute the default threshold as in MatLab, see:\n       * Tim Davis, \"Algorithm 915, SuiteSparseQR: Multifrontal Multithreaded Rank-Revealing\n       * Sparse QR Factorization, ACM Trans. on Math. Soft. 38(1), 2011, Page 8:3 \n       */\n      RealScalar pivotThreshold = m_tolerance;\n      if(m_useDefaultThreshold) \n      {\n        RealScalar max2Norm = 0.0;\n        for (int j = 0; j < mat.cols(); j++) max2Norm = numext::maxi(max2Norm, mat.col(j).norm());\n        if(max2Norm==RealScalar(0))\n          max2Norm = RealScalar(1);\n        pivotThreshold = 20 * (mat.rows() + mat.cols()) * max2Norm * NumTraits<RealScalar>::epsilon();\n      }\n      cholmod_sparse A; \n      A = viewAsCholmod(mat);\n      m_rows = matrix.rows();\n      Index col = matrix.cols();\n      m_rank = SuiteSparseQR<Scalar>(m_ordering, pivotThreshold, col, &A, \n                             &m_cR, &m_E, &m_H, &m_HPinv, &m_HTau, &m_cc);\n\n      if (!m_cR)\n      {\n        m_info = NumericalIssue;\n        m_isInitialized = false;\n        return;\n      }\n      m_info = Success;\n      m_isInitialized = true;\n      m_isRUpToDate = false;\n    }\n    /** \n     * Get the number of rows of the input matrix and the Q matrix\n     */\n    inline Index rows() const {return m_rows; }\n    \n    /** \n     * Get the number of columns of the input matrix. \n     */\n    inline Index cols() const { return m_cR->ncol; }\n    \n    template<typename Rhs, typename Dest>\n    void _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const\n    {\n      eigen_assert(m_isInitialized && \" The QR factorization should be computed first, call compute()\");\n      eigen_assert(b.cols()==1 && \"This method is for vectors only\");\n\n      //Compute Q^T * b\n      typename Dest::PlainObject y, y2;\n      y = matrixQ().transpose() * b;\n      \n      // Solves with the triangular matrix R\n      Index rk = this->rank();\n      y2 = y;\n      y.resize((std::max)(cols(),Index(y.rows())),y.cols());\n      y.topRows(rk) = this->matrixR().topLeftCorner(rk, rk).template triangularView<Upper>().solve(y2.topRows(rk));\n\n      // Apply the column permutation \n      // colsPermutation() performs a copy of the permutation,\n      // so let's apply it manually:\n      for(Index i = 0; i < rk; ++i) dest.row(m_E[i]) = y.row(i);\n      for(Index i = rk; i < cols(); ++i) dest.row(m_E[i]).setZero();\n      \n//       y.bottomRows(y.rows()-rk).setZero();\n//       dest = colsPermutation() * y.topRows(cols());\n      \n      m_info = Success;\n    }\n    \n    /** \\returns the sparse triangular factor R. It is a sparse matrix\n     */\n    const MatrixType matrixR() const\n    {\n      eigen_assert(m_isInitialized && \" The QR factorization should be computed first, call compute()\");\n      if(!m_isRUpToDate) {\n        m_R = viewAsEigen<Scalar,ColMajor, typename MatrixType::StorageIndex>(*m_cR);\n        m_isRUpToDate = true;\n      }\n      return m_R;\n    }\n    /// Get an expression of the matrix Q\n    SPQRMatrixQReturnType<SPQR> matrixQ() const\n    {\n      return SPQRMatrixQReturnType<SPQR>(*this);\n    }\n    /// Get the permutation that was applied to columns of A\n    PermutationType colsPermutation() const\n    { \n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return PermutationType(m_E, m_cR->ncol);\n    }\n    /**\n     * Gets the rank of the matrix. \n     * It should be equal to matrixQR().cols if the matrix is full-rank\n     */\n    Index rank() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_cc.SPQR_istat[4];\n    }\n    /// Set the fill-reducing ordering method to be used\n    void setSPQROrdering(int ord) { m_ordering = ord;}\n    /// Set the tolerance tol to treat columns with 2-norm < =tol as zero\n    void setPivotThreshold(const RealScalar& tol)\n    {\n      m_useDefaultThreshold = false;\n      m_tolerance = tol;\n    }\n    \n    /** \\returns a pointer to the SPQR workspace */\n    cholmod_common *cholmodCommon() const { return &m_cc; }\n    \n    \n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the sparse QR can not be computed\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_info;\n    }\n  protected:\n    bool m_analysisIsOk;\n    bool m_factorizationIsOk;\n    mutable bool m_isRUpToDate;\n    mutable ComputationInfo m_info;\n    int m_ordering; // Ordering method to use, see SPQR's manual\n    int m_allow_tol; // Allow to use some tolerance during numerical factorization.\n    RealScalar m_tolerance; // treat columns with 2-norm below this tolerance as zero\n    mutable cholmod_sparse *m_cR; // The sparse R factor in cholmod format\n    mutable MatrixType m_R; // The sparse matrix R in Eigen format\n    mutable StorageIndex *m_E; // The permutation applied to columns\n    mutable cholmod_sparse *m_H;  //The householder vectors\n    mutable StorageIndex *m_HPinv; // The row permutation of H\n    mutable cholmod_dense *m_HTau; // The Householder coefficients\n    mutable Index m_rank; // The rank of the matrix\n    mutable cholmod_common m_cc; // Workspace and parameters\n    bool m_useDefaultThreshold;     // Use default threshold\n    Index m_rows;\n    template<typename ,typename > friend struct SPQR_QProduct;\n};\n\ntemplate <typename SPQRType, typename Derived>\nstruct SPQR_QProduct : ReturnByValue<SPQR_QProduct<SPQRType,Derived> >\n{\n  typedef typename SPQRType::Scalar Scalar;\n  typedef typename SPQRType::StorageIndex StorageIndex;\n  //Define the constructor to get reference to argument types\n  SPQR_QProduct(const SPQRType& spqr, const Derived& other, bool transpose) : m_spqr(spqr),m_other(other),m_transpose(transpose) {}\n  \n  inline Index rows() const { return m_transpose ? m_spqr.rows() : m_spqr.cols(); }\n  inline Index cols() const { return m_other.cols(); }\n  // Assign to a vector\n  template<typename ResType>\n  void evalTo(ResType& res) const\n  {\n    cholmod_dense y_cd;\n    cholmod_dense *x_cd; \n    int method = m_transpose ? SPQR_QTX : SPQR_QX; \n    cholmod_common *cc = m_spqr.cholmodCommon();\n    y_cd = viewAsCholmod(m_other.const_cast_derived());\n    x_cd = SuiteSparseQR_qmult<Scalar>(method, m_spqr.m_H, m_spqr.m_HTau, m_spqr.m_HPinv, &y_cd, cc);\n    res = Matrix<Scalar,ResType::RowsAtCompileTime,ResType::ColsAtCompileTime>::Map(reinterpret_cast<Scalar*>(x_cd->x), x_cd->nrow, x_cd->ncol);\n    cholmod_l_free_dense(&x_cd, cc);\n  }\n  const SPQRType& m_spqr; \n  const Derived& m_other; \n  bool m_transpose; \n  \n};\ntemplate<typename SPQRType>\nstruct SPQRMatrixQReturnType{\n  \n  SPQRMatrixQReturnType(const SPQRType& spqr) : m_spqr(spqr) {}\n  template<typename Derived>\n  SPQR_QProduct<SPQRType, Derived> operator*(const MatrixBase<Derived>& other)\n  {\n    return SPQR_QProduct<SPQRType,Derived>(m_spqr,other.derived(),false);\n  }\n  SPQRMatrixQTransposeReturnType<SPQRType> adjoint() const\n  {\n    return SPQRMatrixQTransposeReturnType<SPQRType>(m_spqr);\n  }\n  // To use for operations with the transpose of Q\n  SPQRMatrixQTransposeReturnType<SPQRType> transpose() const\n  {\n    return SPQRMatrixQTransposeReturnType<SPQRType>(m_spqr);\n  }\n  const SPQRType& m_spqr;\n};\n\ntemplate<typename SPQRType>\nstruct SPQRMatrixQTransposeReturnType{\n  SPQRMatrixQTransposeReturnType(const SPQRType& spqr) : m_spqr(spqr) {}\n  template<typename Derived>\n  SPQR_QProduct<SPQRType,Derived> operator*(const MatrixBase<Derived>& other)\n  {\n    return SPQR_QProduct<SPQRType,Derived>(m_spqr,other.derived(), true);\n  }\n  const SPQRType& m_spqr;\n};\n\n}// End namespace Eigen\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SVD/BDCSVD.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n// \n// We used the \"A Divide-And-Conquer Algorithm for the Bidiagonal SVD\"\n// research report written by Ming Gu and Stanley C.Eisenstat\n// The code variable names correspond to the names they used in their \n// report\n//\n// Copyright (C) 2013 Gauthier Brun <brun.gauthier@gmail.com>\n// Copyright (C) 2013 Nicolas Carre <nicolas.carre@ensimag.fr>\n// Copyright (C) 2013 Jean Ceccato <jean.ceccato@ensimag.fr>\n// Copyright (C) 2013 Pierre Zoppitelli <pierre.zoppitelli@ensimag.fr>\n// Copyright (C) 2013 Jitse Niesen <jitse@maths.leeds.ac.uk>\n// Copyright (C) 2014-2017 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BDCSVD_H\n#define EIGEN_BDCSVD_H\n// #define EIGEN_BDCSVD_DEBUG_VERBOSE\n// #define EIGEN_BDCSVD_SANITY_CHECKS\n\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n#undef eigen_internal_assert\n#define eigen_internal_assert(X) assert(X);\n#endif\n\nnamespace Eigen {\n\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\nIOFormat bdcsvdfmt(8, 0, \", \", \"\\n\", \"  [\", \"]\");\n#endif\n  \ntemplate<typename _MatrixType> class BDCSVD;\n\nnamespace internal {\n\ntemplate<typename _MatrixType> \nstruct traits<BDCSVD<_MatrixType> >\n        : traits<_MatrixType>\n{\n  typedef _MatrixType MatrixType;\n};  \n\n} // end namespace internal\n  \n  \n/** \\ingroup SVD_Module\n *\n *\n * \\class BDCSVD\n *\n * \\brief class Bidiagonal Divide and Conquer SVD\n *\n * \\tparam _MatrixType the type of the matrix of which we are computing the SVD decomposition\n *\n * This class first reduces the input matrix to bi-diagonal form using class UpperBidiagonalization,\n * and then performs a divide-and-conquer diagonalization. Small blocks are diagonalized using class JacobiSVD.\n * You can control the switching size with the setSwitchSize() method, default is 16.\n * For small matrice (<16), it is thus preferable to directly use JacobiSVD. For larger ones, BDCSVD is highly\n * recommended and can several order of magnitude faster.\n *\n * \\warning this algorithm is unlikely to provide accurate result when compiled with unsafe math optimizations.\n * For instance, this concerns Intel's compiler (ICC), which performs such optimization by default unless\n * you compile with the \\c -fp-model \\c precise option. Likewise, the \\c -ffast-math option of GCC or clang will\n * significantly degrade the accuracy.\n *\n * \\sa class JacobiSVD\n */\ntemplate<typename _MatrixType> \nclass BDCSVD : public SVDBase<BDCSVD<_MatrixType> >\n{\n  typedef SVDBase<BDCSVD> Base;\n    \npublic:\n  using Base::rows;\n  using Base::cols;\n  using Base::computeU;\n  using Base::computeV;\n  \n  typedef _MatrixType MatrixType;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<typename MatrixType::Scalar>::Real RealScalar;\n  typedef typename NumTraits<RealScalar>::Literal Literal;\n  enum {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime, \n    ColsAtCompileTime = MatrixType::ColsAtCompileTime, \n    DiagSizeAtCompileTime = EIGEN_SIZE_MIN_PREFER_DYNAMIC(RowsAtCompileTime, ColsAtCompileTime), \n    MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime, \n    MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime, \n    MaxDiagSizeAtCompileTime = EIGEN_SIZE_MIN_PREFER_FIXED(MaxRowsAtCompileTime, MaxColsAtCompileTime), \n    MatrixOptions = MatrixType::Options\n  };\n\n  typedef typename Base::MatrixUType MatrixUType;\n  typedef typename Base::MatrixVType MatrixVType;\n  typedef typename Base::SingularValuesType SingularValuesType;\n  \n  typedef Matrix<Scalar, Dynamic, Dynamic, ColMajor> MatrixX;\n  typedef Matrix<RealScalar, Dynamic, Dynamic, ColMajor> MatrixXr;\n  typedef Matrix<RealScalar, Dynamic, 1> VectorType;\n  typedef Array<RealScalar, Dynamic, 1> ArrayXr;\n  typedef Array<Index,1,Dynamic> ArrayXi;\n  typedef Ref<ArrayXr> ArrayRef;\n  typedef Ref<ArrayXi> IndicesRef;\n\n  /** \\brief Default Constructor.\n   *\n   * The default constructor is useful in cases in which the user intends to\n   * perform decompositions via BDCSVD::compute(const MatrixType&).\n   */\n  BDCSVD() : m_algoswap(16), m_isTranspose(false), m_compU(false), m_compV(false), m_numIters(0)\n  {}\n\n\n  /** \\brief Default Constructor with memory preallocation\n   *\n   * Like the default constructor but with preallocation of the internal data\n   * according to the specified problem size.\n   * \\sa BDCSVD()\n   */\n  BDCSVD(Index rows, Index cols, unsigned int computationOptions = 0)\n    : m_algoswap(16), m_numIters(0)\n  {\n    allocate(rows, cols, computationOptions);\n  }\n\n  /** \\brief Constructor performing the decomposition of given matrix.\n   *\n   * \\param matrix the matrix to decompose\n   * \\param computationOptions optional parameter allowing to specify if you want full or thin U or V unitaries to be computed.\n   *                           By default, none is computed. This is a bit - field, the possible bits are #ComputeFullU, #ComputeThinU, \n   *                           #ComputeFullV, #ComputeThinV.\n   *\n   * Thin unitaries are only available if your matrix type has a Dynamic number of columns (for example MatrixXf). They also are not\n   * available with the (non - default) FullPivHouseholderQR preconditioner.\n   */\n  BDCSVD(const MatrixType& matrix, unsigned int computationOptions = 0)\n    : m_algoswap(16), m_numIters(0)\n  {\n    compute(matrix, computationOptions);\n  }\n\n  ~BDCSVD() \n  {\n  }\n  \n  /** \\brief Method performing the decomposition of given matrix using custom options.\n   *\n   * \\param matrix the matrix to decompose\n   * \\param computationOptions optional parameter allowing to specify if you want full or thin U or V unitaries to be computed.\n   *                           By default, none is computed. This is a bit - field, the possible bits are #ComputeFullU, #ComputeThinU, \n   *                           #ComputeFullV, #ComputeThinV.\n   *\n   * Thin unitaries are only available if your matrix type has a Dynamic number of columns (for example MatrixXf). They also are not\n   * available with the (non - default) FullPivHouseholderQR preconditioner.\n   */\n  BDCSVD& compute(const MatrixType& matrix, unsigned int computationOptions);\n\n  /** \\brief Method performing the decomposition of given matrix using current options.\n   *\n   * \\param matrix the matrix to decompose\n   *\n   * This method uses the current \\a computationOptions, as already passed to the constructor or to compute(const MatrixType&, unsigned int).\n   */\n  BDCSVD& compute(const MatrixType& matrix)\n  {\n    return compute(matrix, this->m_computationOptions);\n  }\n\n  void setSwitchSize(int s) \n  {\n    eigen_assert(s>3 && \"BDCSVD the size of the algo switch has to be greater than 3\");\n    m_algoswap = s;\n  }\n \nprivate:\n  void allocate(Index rows, Index cols, unsigned int computationOptions);\n  void divide(Index firstCol, Index lastCol, Index firstRowW, Index firstColW, Index shift);\n  void computeSVDofM(Index firstCol, Index n, MatrixXr& U, VectorType& singVals, MatrixXr& V);\n  void computeSingVals(const ArrayRef& col0, const ArrayRef& diag, const IndicesRef& perm, VectorType& singVals, ArrayRef shifts, ArrayRef mus);\n  void perturbCol0(const ArrayRef& col0, const ArrayRef& diag, const IndicesRef& perm, const VectorType& singVals, const ArrayRef& shifts, const ArrayRef& mus, ArrayRef zhat);\n  void computeSingVecs(const ArrayRef& zhat, const ArrayRef& diag, const IndicesRef& perm, const VectorType& singVals, const ArrayRef& shifts, const ArrayRef& mus, MatrixXr& U, MatrixXr& V);\n  void deflation43(Index firstCol, Index shift, Index i, Index size);\n  void deflation44(Index firstColu , Index firstColm, Index firstRowW, Index firstColW, Index i, Index j, Index size);\n  void deflation(Index firstCol, Index lastCol, Index k, Index firstRowW, Index firstColW, Index shift);\n  template<typename HouseholderU, typename HouseholderV, typename NaiveU, typename NaiveV>\n  void copyUV(const HouseholderU &householderU, const HouseholderV &householderV, const NaiveU &naiveU, const NaiveV &naivev);\n  void structured_update(Block<MatrixXr,Dynamic,Dynamic> A, const MatrixXr &B, Index n1);\n  static RealScalar secularEq(RealScalar x, const ArrayRef& col0, const ArrayRef& diag, const IndicesRef &perm, const ArrayRef& diagShifted, RealScalar shift);\n\nprotected:\n  MatrixXr m_naiveU, m_naiveV;\n  MatrixXr m_computed;\n  Index m_nRec;\n  ArrayXr m_workspace;\n  ArrayXi m_workspaceI;\n  int m_algoswap;\n  bool m_isTranspose, m_compU, m_compV;\n  \n  using Base::m_singularValues;\n  using Base::m_diagSize;\n  using Base::m_computeFullU;\n  using Base::m_computeFullV;\n  using Base::m_computeThinU;\n  using Base::m_computeThinV;\n  using Base::m_matrixU;\n  using Base::m_matrixV;\n  using Base::m_isInitialized;\n  using Base::m_nonzeroSingularValues;\n\npublic:  \n  int m_numIters;\n}; //end class BDCSVD\n\n\n// Method to allocate and initialize matrix and attributes\ntemplate<typename MatrixType>\nvoid BDCSVD<MatrixType>::allocate(Eigen::Index rows, Eigen::Index cols, unsigned int computationOptions)\n{\n  m_isTranspose = (cols > rows);\n\n  if (Base::allocate(rows, cols, computationOptions))\n    return;\n  \n  m_computed = MatrixXr::Zero(m_diagSize + 1, m_diagSize );\n  m_compU = computeV();\n  m_compV = computeU();\n  if (m_isTranspose)\n    std::swap(m_compU, m_compV);\n  \n  if (m_compU) m_naiveU = MatrixXr::Zero(m_diagSize + 1, m_diagSize + 1 );\n  else         m_naiveU = MatrixXr::Zero(2, m_diagSize + 1 );\n  \n  if (m_compV) m_naiveV = MatrixXr::Zero(m_diagSize, m_diagSize);\n  \n  m_workspace.resize((m_diagSize+1)*(m_diagSize+1)*3);\n  m_workspaceI.resize(3*m_diagSize);\n}// end allocate\n\ntemplate<typename MatrixType>\nBDCSVD<MatrixType>& BDCSVD<MatrixType>::compute(const MatrixType& matrix, unsigned int computationOptions) \n{\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n  std::cout << \"\\n\\n\\n======================================================================================================================\\n\\n\\n\";\n#endif\n  allocate(matrix.rows(), matrix.cols(), computationOptions);\n  using std::abs;\n\n  const RealScalar considerZero = (std::numeric_limits<RealScalar>::min)();\n  \n  //**** step -1 - If the problem is too small, directly falls back to JacobiSVD and return\n  if(matrix.cols() < m_algoswap)\n  {\n    // FIXME this line involves temporaries\n    JacobiSVD<MatrixType> jsvd(matrix,computationOptions);\n    if(computeU()) m_matrixU = jsvd.matrixU();\n    if(computeV()) m_matrixV = jsvd.matrixV();\n    m_singularValues = jsvd.singularValues();\n    m_nonzeroSingularValues = jsvd.nonzeroSingularValues();\n    m_isInitialized = true;\n    return *this;\n  }\n  \n  //**** step 0 - Copy the input matrix and apply scaling to reduce over/under-flows\n  RealScalar scale = matrix.cwiseAbs().maxCoeff();\n  if(scale==Literal(0)) scale = Literal(1);\n  MatrixX copy;\n  if (m_isTranspose) copy = matrix.adjoint()/scale;\n  else               copy = matrix/scale;\n  \n  //**** step 1 - Bidiagonalization\n  // FIXME this line involves temporaries\n  internal::UpperBidiagonalization<MatrixX> bid(copy);\n\n  //**** step 2 - Divide & Conquer\n  m_naiveU.setZero();\n  m_naiveV.setZero();\n  // FIXME this line involves a temporary matrix\n  m_computed.topRows(m_diagSize) = bid.bidiagonal().toDenseMatrix().transpose();\n  m_computed.template bottomRows<1>().setZero();\n  divide(0, m_diagSize - 1, 0, 0, 0);\n\n  //**** step 3 - Copy singular values and vectors\n  for (int i=0; i<m_diagSize; i++)\n  {\n    RealScalar a = abs(m_computed.coeff(i, i));\n    m_singularValues.coeffRef(i) = a * scale;\n    if (a<considerZero)\n    {\n      m_nonzeroSingularValues = i;\n      m_singularValues.tail(m_diagSize - i - 1).setZero();\n      break;\n    }\n    else if (i == m_diagSize - 1)\n    {\n      m_nonzeroSingularValues = i + 1;\n      break;\n    }\n  }\n\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n//   std::cout << \"m_naiveU\\n\" << m_naiveU << \"\\n\\n\";\n//   std::cout << \"m_naiveV\\n\" << m_naiveV << \"\\n\\n\";\n#endif\n  if(m_isTranspose) copyUV(bid.householderV(), bid.householderU(), m_naiveV, m_naiveU);\n  else              copyUV(bid.householderU(), bid.householderV(), m_naiveU, m_naiveV);\n\n  m_isInitialized = true;\n  return *this;\n}// end compute\n\n\ntemplate<typename MatrixType>\ntemplate<typename HouseholderU, typename HouseholderV, typename NaiveU, typename NaiveV>\nvoid BDCSVD<MatrixType>::copyUV(const HouseholderU &householderU, const HouseholderV &householderV, const NaiveU &naiveU, const NaiveV &naiveV)\n{\n  // Note exchange of U and V: m_matrixU is set from m_naiveV and vice versa\n  if (computeU())\n  {\n    Index Ucols = m_computeThinU ? m_diagSize : householderU.cols();\n    m_matrixU = MatrixX::Identity(householderU.cols(), Ucols);\n    m_matrixU.topLeftCorner(m_diagSize, m_diagSize) = naiveV.template cast<Scalar>().topLeftCorner(m_diagSize, m_diagSize);\n    householderU.applyThisOnTheLeft(m_matrixU); // FIXME this line involves a temporary buffer\n  }\n  if (computeV())\n  {\n    Index Vcols = m_computeThinV ? m_diagSize : householderV.cols();\n    m_matrixV = MatrixX::Identity(householderV.cols(), Vcols);\n    m_matrixV.topLeftCorner(m_diagSize, m_diagSize) = naiveU.template cast<Scalar>().topLeftCorner(m_diagSize, m_diagSize);\n    householderV.applyThisOnTheLeft(m_matrixV); // FIXME this line involves a temporary buffer\n  }\n}\n\n/** \\internal\n  * Performs A = A * B exploiting the special structure of the matrix A. Splitting A as:\n  *  A = [A1]\n  *      [A2]\n  * such that A1.rows()==n1, then we assume that at least half of the columns of A1 and A2 are zeros.\n  * We can thus pack them prior to the the matrix product. However, this is only worth the effort if the matrix is large\n  * enough.\n  */\ntemplate<typename MatrixType>\nvoid BDCSVD<MatrixType>::structured_update(Block<MatrixXr,Dynamic,Dynamic> A, const MatrixXr &B, Index n1)\n{\n  Index n = A.rows();\n  if(n>100)\n  {\n    // If the matrices are large enough, let's exploit the sparse structure of A by\n    // splitting it in half (wrt n1), and packing the non-zero columns.\n    Index n2 = n - n1;\n    Map<MatrixXr> A1(m_workspace.data()      , n1, n);\n    Map<MatrixXr> A2(m_workspace.data()+ n1*n, n2, n);\n    Map<MatrixXr> B1(m_workspace.data()+  n*n, n,  n);\n    Map<MatrixXr> B2(m_workspace.data()+2*n*n, n,  n);\n    Index k1=0, k2=0;\n    for(Index j=0; j<n; ++j)\n    {\n      if( (A.col(j).head(n1).array()!=Literal(0)).any() )\n      {\n        A1.col(k1) = A.col(j).head(n1);\n        B1.row(k1) = B.row(j);\n        ++k1;\n      }\n      if( (A.col(j).tail(n2).array()!=Literal(0)).any() )\n      {\n        A2.col(k2) = A.col(j).tail(n2);\n        B2.row(k2) = B.row(j);\n        ++k2;\n      }\n    }\n  \n    A.topRows(n1).noalias()    = A1.leftCols(k1) * B1.topRows(k1);\n    A.bottomRows(n2).noalias() = A2.leftCols(k2) * B2.topRows(k2);\n  }\n  else\n  {\n    Map<MatrixXr,Aligned> tmp(m_workspace.data(),n,n);\n    tmp.noalias() = A*B;\n    A = tmp;\n  }\n}\n\n// The divide algorithm is done \"in place\", we are always working on subsets of the same matrix. The divide methods takes as argument the \n// place of the submatrix we are currently working on.\n\n//@param firstCol : The Index of the first column of the submatrix of m_computed and for m_naiveU;\n//@param lastCol : The Index of the last column of the submatrix of m_computed and for m_naiveU; \n// lastCol + 1 - firstCol is the size of the submatrix.\n//@param firstRowW : The Index of the first row of the matrix W that we are to change. (see the reference paper section 1 for more information on W)\n//@param firstRowW : Same as firstRowW with the column.\n//@param shift : Each time one takes the left submatrix, one must add 1 to the shift. Why? Because! We actually want the last column of the U submatrix \n// to become the first column (*coeff) and to shift all the other columns to the right. There are more details on the reference paper.\ntemplate<typename MatrixType>\nvoid BDCSVD<MatrixType>::divide (Eigen::Index firstCol, Eigen::Index lastCol, Eigen::Index firstRowW, Eigen::Index firstColW, Eigen::Index shift)\n{\n  // requires rows = cols + 1;\n  using std::pow;\n  using std::sqrt;\n  using std::abs;\n  const Index n = lastCol - firstCol + 1;\n  const Index k = n/2;\n  const RealScalar considerZero = (std::numeric_limits<RealScalar>::min)();\n  RealScalar alphaK;\n  RealScalar betaK; \n  RealScalar r0; \n  RealScalar lambda, phi, c0, s0;\n  VectorType l, f;\n  // We use the other algorithm which is more efficient for small \n  // matrices.\n  if (n < m_algoswap)\n  {\n    // FIXME this line involves temporaries\n    JacobiSVD<MatrixXr> b(m_computed.block(firstCol, firstCol, n + 1, n), ComputeFullU | (m_compV ? ComputeFullV : 0));\n    if (m_compU)\n      m_naiveU.block(firstCol, firstCol, n + 1, n + 1).real() = b.matrixU();\n    else \n    {\n      m_naiveU.row(0).segment(firstCol, n + 1).real() = b.matrixU().row(0);\n      m_naiveU.row(1).segment(firstCol, n + 1).real() = b.matrixU().row(n);\n    }\n    if (m_compV) m_naiveV.block(firstRowW, firstColW, n, n).real() = b.matrixV();\n    m_computed.block(firstCol + shift, firstCol + shift, n + 1, n).setZero();\n    m_computed.diagonal().segment(firstCol + shift, n) = b.singularValues().head(n);\n    return;\n  }\n  // We use the divide and conquer algorithm\n  alphaK =  m_computed(firstCol + k, firstCol + k);\n  betaK = m_computed(firstCol + k + 1, firstCol + k);\n  // The divide must be done in that order in order to have good results. Divide change the data inside the submatrices\n  // and the divide of the right submatrice reads one column of the left submatrice. That's why we need to treat the \n  // right submatrix before the left one. \n  divide(k + 1 + firstCol, lastCol, k + 1 + firstRowW, k + 1 + firstColW, shift);\n  divide(firstCol, k - 1 + firstCol, firstRowW, firstColW + 1, shift + 1);\n\n  if (m_compU)\n  {\n    lambda = m_naiveU(firstCol + k, firstCol + k);\n    phi = m_naiveU(firstCol + k + 1, lastCol + 1);\n  } \n  else \n  {\n    lambda = m_naiveU(1, firstCol + k);\n    phi = m_naiveU(0, lastCol + 1);\n  }\n  r0 = sqrt((abs(alphaK * lambda) * abs(alphaK * lambda)) + abs(betaK * phi) * abs(betaK * phi));\n  if (m_compU)\n  {\n    l = m_naiveU.row(firstCol + k).segment(firstCol, k);\n    f = m_naiveU.row(firstCol + k + 1).segment(firstCol + k + 1, n - k - 1);\n  } \n  else \n  {\n    l = m_naiveU.row(1).segment(firstCol, k);\n    f = m_naiveU.row(0).segment(firstCol + k + 1, n - k - 1);\n  }\n  if (m_compV) m_naiveV(firstRowW+k, firstColW) = Literal(1);\n  if (r0<considerZero)\n  {\n    c0 = Literal(1);\n    s0 = Literal(0);\n  }\n  else\n  {\n    c0 = alphaK * lambda / r0;\n    s0 = betaK * phi / r0;\n  }\n  \n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  assert(m_naiveU.allFinite());\n  assert(m_naiveV.allFinite());\n  assert(m_computed.allFinite());\n#endif\n  \n  if (m_compU)\n  {\n    MatrixXr q1 (m_naiveU.col(firstCol + k).segment(firstCol, k + 1));     \n    // we shiftW Q1 to the right\n    for (Index i = firstCol + k - 1; i >= firstCol; i--) \n      m_naiveU.col(i + 1).segment(firstCol, k + 1) = m_naiveU.col(i).segment(firstCol, k + 1);\n    // we shift q1 at the left with a factor c0\n    m_naiveU.col(firstCol).segment( firstCol, k + 1) = (q1 * c0);\n    // last column = q1 * - s0\n    m_naiveU.col(lastCol + 1).segment(firstCol, k + 1) = (q1 * ( - s0));\n    // first column = q2 * s0\n    m_naiveU.col(firstCol).segment(firstCol + k + 1, n - k) = m_naiveU.col(lastCol + 1).segment(firstCol + k + 1, n - k) * s0; \n    // q2 *= c0\n    m_naiveU.col(lastCol + 1).segment(firstCol + k + 1, n - k) *= c0;\n  } \n  else \n  {\n    RealScalar q1 = m_naiveU(0, firstCol + k);\n    // we shift Q1 to the right\n    for (Index i = firstCol + k - 1; i >= firstCol; i--) \n      m_naiveU(0, i + 1) = m_naiveU(0, i);\n    // we shift q1 at the left with a factor c0\n    m_naiveU(0, firstCol) = (q1 * c0);\n    // last column = q1 * - s0\n    m_naiveU(0, lastCol + 1) = (q1 * ( - s0));\n    // first column = q2 * s0\n    m_naiveU(1, firstCol) = m_naiveU(1, lastCol + 1) *s0; \n    // q2 *= c0\n    m_naiveU(1, lastCol + 1) *= c0;\n    m_naiveU.row(1).segment(firstCol + 1, k).setZero();\n    m_naiveU.row(0).segment(firstCol + k + 1, n - k - 1).setZero();\n  }\n  \n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  assert(m_naiveU.allFinite());\n  assert(m_naiveV.allFinite());\n  assert(m_computed.allFinite());\n#endif\n  \n  m_computed(firstCol + shift, firstCol + shift) = r0;\n  m_computed.col(firstCol + shift).segment(firstCol + shift + 1, k) = alphaK * l.transpose().real();\n  m_computed.col(firstCol + shift).segment(firstCol + shift + k + 1, n - k - 1) = betaK * f.transpose().real();\n\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n  ArrayXr tmp1 = (m_computed.block(firstCol+shift, firstCol+shift, n, n)).jacobiSvd().singularValues();\n#endif\n  // Second part: try to deflate singular values in combined matrix\n  deflation(firstCol, lastCol, k, firstRowW, firstColW, shift);\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n  ArrayXr tmp2 = (m_computed.block(firstCol+shift, firstCol+shift, n, n)).jacobiSvd().singularValues();\n  std::cout << \"\\n\\nj1 = \" << tmp1.transpose().format(bdcsvdfmt) << \"\\n\";\n  std::cout << \"j2 = \" << tmp2.transpose().format(bdcsvdfmt) << \"\\n\\n\";\n  std::cout << \"err:      \" << ((tmp1-tmp2).abs()>1e-12*tmp2.abs()).transpose() << \"\\n\";\n  static int count = 0;\n  std::cout << \"# \" << ++count << \"\\n\\n\";\n  assert((tmp1-tmp2).matrix().norm() < 1e-14*tmp2.matrix().norm());\n//   assert(count<681);\n//   assert(((tmp1-tmp2).abs()<1e-13*tmp2.abs()).all());\n#endif\n  \n  // Third part: compute SVD of combined matrix\n  MatrixXr UofSVD, VofSVD;\n  VectorType singVals;\n  computeSVDofM(firstCol + shift, n, UofSVD, singVals, VofSVD);\n  \n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  assert(UofSVD.allFinite());\n  assert(VofSVD.allFinite());\n#endif\n  \n  if (m_compU)\n    structured_update(m_naiveU.block(firstCol, firstCol, n + 1, n + 1), UofSVD, (n+2)/2);\n  else\n  {\n    Map<Matrix<RealScalar,2,Dynamic>,Aligned> tmp(m_workspace.data(),2,n+1);\n    tmp.noalias() = m_naiveU.middleCols(firstCol, n+1) * UofSVD;\n    m_naiveU.middleCols(firstCol, n + 1) = tmp;\n  }\n  \n  if (m_compV)  structured_update(m_naiveV.block(firstRowW, firstColW, n, n), VofSVD, (n+1)/2);\n  \n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  assert(m_naiveU.allFinite());\n  assert(m_naiveV.allFinite());\n  assert(m_computed.allFinite());\n#endif\n  \n  m_computed.block(firstCol + shift, firstCol + shift, n, n).setZero();\n  m_computed.block(firstCol + shift, firstCol + shift, n, n).diagonal() = singVals;\n}// end divide\n\n// Compute SVD of m_computed.block(firstCol, firstCol, n + 1, n); this block only has non-zeros in\n// the first column and on the diagonal and has undergone deflation, so diagonal is in increasing\n// order except for possibly the (0,0) entry. The computed SVD is stored U, singVals and V, except\n// that if m_compV is false, then V is not computed. Singular values are sorted in decreasing order.\n//\n// TODO Opportunities for optimization: better root finding algo, better stopping criterion, better\n// handling of round-off errors, be consistent in ordering\n// For instance, to solve the secular equation using FMM, see http://www.stat.uchicago.edu/~lekheng/courses/302/classics/greengard-rokhlin.pdf\ntemplate <typename MatrixType>\nvoid BDCSVD<MatrixType>::computeSVDofM(Eigen::Index firstCol, Eigen::Index n, MatrixXr& U, VectorType& singVals, MatrixXr& V)\n{\n  const RealScalar considerZero = (std::numeric_limits<RealScalar>::min)();\n  using std::abs;\n  ArrayRef col0 = m_computed.col(firstCol).segment(firstCol, n);\n  m_workspace.head(n) =  m_computed.block(firstCol, firstCol, n, n).diagonal();\n  ArrayRef diag = m_workspace.head(n);\n  diag(0) = Literal(0);\n\n  // Allocate space for singular values and vectors\n  singVals.resize(n);\n  U.resize(n+1, n+1);\n  if (m_compV) V.resize(n, n);\n\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n  if (col0.hasNaN() || diag.hasNaN())\n    std::cout << \"\\n\\nHAS NAN\\n\\n\";\n#endif\n  \n  // Many singular values might have been deflated, the zero ones have been moved to the end,\n  // but others are interleaved and we must ignore them at this stage.\n  // To this end, let's compute a permutation skipping them:\n  Index actual_n = n;\n  while(actual_n>1 && diag(actual_n-1)==Literal(0)) {--actual_n; eigen_internal_assert(col0(actual_n)==Literal(0)); }\n  Index m = 0; // size of the deflated problem\n  for(Index k=0;k<actual_n;++k)\n    if(abs(col0(k))>considerZero)\n      m_workspaceI(m++) = k;\n  Map<ArrayXi> perm(m_workspaceI.data(),m);\n  \n  Map<ArrayXr> shifts(m_workspace.data()+1*n, n);\n  Map<ArrayXr> mus(m_workspace.data()+2*n, n);\n  Map<ArrayXr> zhat(m_workspace.data()+3*n, n);\n\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n  std::cout << \"computeSVDofM using:\\n\";\n  std::cout << \"  z: \" << col0.transpose() << \"\\n\";\n  std::cout << \"  d: \" << diag.transpose() << \"\\n\";\n#endif\n  \n  // Compute singVals, shifts, and mus\n  computeSingVals(col0, diag, perm, singVals, shifts, mus);\n  \n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n  std::cout << \"  j:        \" << (m_computed.block(firstCol, firstCol, n, n)).jacobiSvd().singularValues().transpose().reverse() << \"\\n\\n\";\n  std::cout << \"  sing-val: \" << singVals.transpose() << \"\\n\";\n  std::cout << \"  mu:       \" << mus.transpose() << \"\\n\";\n  std::cout << \"  shift:    \" << shifts.transpose() << \"\\n\";\n  \n  {\n    std::cout << \"\\n\\n    mus:    \" << mus.head(actual_n).transpose() << \"\\n\\n\";\n    std::cout << \"    check1 (expect0) : \" << ((singVals.array()-(shifts+mus)) / singVals.array()).head(actual_n).transpose() << \"\\n\\n\";\n    assert((((singVals.array()-(shifts+mus)) / singVals.array()).head(actual_n) >= 0).all());\n    std::cout << \"    check2 (>0)      : \" << ((singVals.array()-diag) / singVals.array()).head(actual_n).transpose() << \"\\n\\n\";\n    assert((((singVals.array()-diag) / singVals.array()).head(actual_n) >= 0).all());\n  }\n#endif\n  \n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  assert(singVals.allFinite());\n  assert(mus.allFinite());\n  assert(shifts.allFinite());\n#endif\n  \n  // Compute zhat\n  perturbCol0(col0, diag, perm, singVals, shifts, mus, zhat);\n#ifdef  EIGEN_BDCSVD_DEBUG_VERBOSE\n  std::cout << \"  zhat: \" << zhat.transpose() << \"\\n\";\n#endif\n  \n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  assert(zhat.allFinite());\n#endif\n  \n  computeSingVecs(zhat, diag, perm, singVals, shifts, mus, U, V);\n  \n#ifdef  EIGEN_BDCSVD_DEBUG_VERBOSE\n  std::cout << \"U^T U: \" << (U.transpose() * U - MatrixXr(MatrixXr::Identity(U.cols(),U.cols()))).norm() << \"\\n\";\n  std::cout << \"V^T V: \" << (V.transpose() * V - MatrixXr(MatrixXr::Identity(V.cols(),V.cols()))).norm() << \"\\n\";\n#endif\n  \n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  assert(m_naiveU.allFinite());\n  assert(m_naiveV.allFinite());\n  assert(m_computed.allFinite());\n  assert(U.allFinite());\n  assert(V.allFinite());\n//   assert((U.transpose() * U - MatrixXr(MatrixXr::Identity(U.cols(),U.cols()))).norm() < 100*NumTraits<RealScalar>::epsilon() * n);\n//   assert((V.transpose() * V - MatrixXr(MatrixXr::Identity(V.cols(),V.cols()))).norm() < 100*NumTraits<RealScalar>::epsilon() * n);\n#endif\n  \n  // Because of deflation, the singular values might not be completely sorted.\n  // Fortunately, reordering them is a O(n) problem\n  for(Index i=0; i<actual_n-1; ++i)\n  {\n    if(singVals(i)>singVals(i+1))\n    {\n      using std::swap;\n      swap(singVals(i),singVals(i+1));\n      U.col(i).swap(U.col(i+1));\n      if(m_compV) V.col(i).swap(V.col(i+1));\n    }\n  }\n\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  {\n    bool singular_values_sorted = (((singVals.segment(1,actual_n-1)-singVals.head(actual_n-1))).array() >= 0).all();\n    if(!singular_values_sorted)\n      std::cout << \"Singular values are not sorted: \" << singVals.segment(1,actual_n).transpose() << \"\\n\";\n    assert(singular_values_sorted);\n  }\n#endif\n  \n  // Reverse order so that singular values in increased order\n  // Because of deflation, the zeros singular-values are already at the end\n  singVals.head(actual_n).reverseInPlace();\n  U.leftCols(actual_n).rowwise().reverseInPlace();\n  if (m_compV) V.leftCols(actual_n).rowwise().reverseInPlace();\n  \n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n  JacobiSVD<MatrixXr> jsvd(m_computed.block(firstCol, firstCol, n, n) );\n  std::cout << \"  * j:        \" << jsvd.singularValues().transpose() << \"\\n\\n\";\n  std::cout << \"  * sing-val: \" << singVals.transpose() << \"\\n\";\n//   std::cout << \"  * err:      \" << ((jsvd.singularValues()-singVals)>1e-13*singVals.norm()).transpose() << \"\\n\";\n#endif\n}\n\ntemplate <typename MatrixType>\ntypename BDCSVD<MatrixType>::RealScalar BDCSVD<MatrixType>::secularEq(RealScalar mu, const ArrayRef& col0, const ArrayRef& diag, const IndicesRef &perm, const ArrayRef& diagShifted, RealScalar shift)\n{\n  Index m = perm.size();\n  RealScalar res = Literal(1);\n  for(Index i=0; i<m; ++i)\n  {\n    Index j = perm(i);\n    // The following expression could be rewritten to involve only a single division,\n    // but this would make the expression more sensitive to overflow.\n    res += (col0(j) / (diagShifted(j) - mu)) * (col0(j) / (diag(j) + shift + mu));\n  }\n  return res;\n\n}\n\ntemplate <typename MatrixType>\nvoid BDCSVD<MatrixType>::computeSingVals(const ArrayRef& col0, const ArrayRef& diag, const IndicesRef &perm,\n                                         VectorType& singVals, ArrayRef shifts, ArrayRef mus)\n{\n  using std::abs;\n  using std::swap;\n  using std::sqrt;\n\n  Index n = col0.size();\n  Index actual_n = n;\n  // Note that here actual_n is computed based on col0(i)==0 instead of diag(i)==0 as above\n  // because 1) we have diag(i)==0 => col0(i)==0 and 2) if col0(i)==0, then diag(i) is already a singular value.\n  while(actual_n>1 && col0(actual_n-1)==Literal(0)) --actual_n;\n\n  for (Index k = 0; k < n; ++k)\n  {\n    if (col0(k) == Literal(0) || actual_n==1)\n    {\n      // if col0(k) == 0, then entry is deflated, so singular value is on diagonal\n      // if actual_n==1, then the deflated problem is already diagonalized\n      singVals(k) = k==0 ? col0(0) : diag(k);\n      mus(k) = Literal(0);\n      shifts(k) = k==0 ? col0(0) : diag(k);\n      continue;\n    } \n\n    // otherwise, use secular equation to find singular value\n    RealScalar left = diag(k);\n    RealScalar right; // was: = (k != actual_n-1) ? diag(k+1) : (diag(actual_n-1) + col0.matrix().norm());\n    if(k==actual_n-1)\n      right = (diag(actual_n-1) + col0.matrix().norm());\n    else\n    {\n      // Skip deflated singular values,\n      // recall that at this stage we assume that z[j]!=0 and all entries for which z[j]==0 have been put aside.\n      // This should be equivalent to using perm[]\n      Index l = k+1;\n      while(col0(l)==Literal(0)) { ++l; eigen_internal_assert(l<actual_n); }\n      right = diag(l);\n    }\n\n    // first decide whether it's closer to the left end or the right end\n    RealScalar mid = left + (right-left) / Literal(2);\n    RealScalar fMid = secularEq(mid, col0, diag, perm, diag, Literal(0));\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n    std::cout << \"right-left = \" << right-left << \"\\n\";\n//     std::cout << \"fMid = \" << fMid << \" \" << secularEq(mid-left, col0, diag, perm, ArrayXr(diag-left), left)\n//                            << \" \" << secularEq(mid-right, col0, diag, perm, ArrayXr(diag-right), right)   << \"\\n\";\n    std::cout << \"     = \" << secularEq(left+RealScalar(0.000001)*(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.1)     *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.2)     *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.3)     *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.4)     *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.49)    *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.5)     *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.51)    *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.6)     *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.7)     *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.8)     *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.9)     *(right-left), col0, diag, perm, diag, 0)\n              << \" \"       << secularEq(left+RealScalar(0.999999)*(right-left), col0, diag, perm, diag, 0) << \"\\n\";\n#endif\n    RealScalar shift = (k == actual_n-1 || fMid > Literal(0)) ? left : right;\n    \n    // measure everything relative to shift\n    Map<ArrayXr> diagShifted(m_workspace.data()+4*n, n);\n    diagShifted = diag - shift;\n\n    if(k!=actual_n-1)\n    {\n      // check that after the shift, f(mid) is still negative:\n      RealScalar midShifted = (right - left) / RealScalar(2);\n      if(shift==right)\n        midShifted = -midShifted;\n      RealScalar fMidShifted = secularEq(midShifted, col0, diag, perm, diagShifted, shift);\n      if(fMidShifted>0)\n      {\n        // fMid was erroneous, fix it:\n        shift =  fMidShifted > Literal(0) ? left : right;\n        diagShifted = diag - shift;\n      }\n    }\n    \n    // initial guess\n    RealScalar muPrev, muCur;\n    if (shift == left)\n    {\n      muPrev = (right - left) * RealScalar(0.1);\n      if (k == actual_n-1) muCur = right - left;\n      else                 muCur = (right - left) * RealScalar(0.5);\n    }\n    else\n    {\n      muPrev = -(right - left) * RealScalar(0.1);\n      muCur = -(right - left) * RealScalar(0.5);\n    }\n\n    RealScalar fPrev = secularEq(muPrev, col0, diag, perm, diagShifted, shift);\n    RealScalar fCur = secularEq(muCur, col0, diag, perm, diagShifted, shift);\n    if (abs(fPrev) < abs(fCur))\n    {\n      swap(fPrev, fCur);\n      swap(muPrev, muCur);\n    }\n\n    // rational interpolation: fit a function of the form a / mu + b through the two previous\n    // iterates and use its zero to compute the next iterate\n    bool useBisection = fPrev*fCur>Literal(0);\n    while (fCur!=Literal(0) && abs(muCur - muPrev) > Literal(8) * NumTraits<RealScalar>::epsilon() * numext::maxi<RealScalar>(abs(muCur), abs(muPrev)) && abs(fCur - fPrev)>NumTraits<RealScalar>::epsilon() && !useBisection)\n    {\n      ++m_numIters;\n\n      // Find a and b such that the function f(mu) = a / mu + b matches the current and previous samples.\n      RealScalar a = (fCur - fPrev) / (Literal(1)/muCur - Literal(1)/muPrev);\n      RealScalar b = fCur - a / muCur;\n      // And find mu such that f(mu)==0:\n      RealScalar muZero = -a/b;\n      RealScalar fZero = secularEq(muZero, col0, diag, perm, diagShifted, shift);\n\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n      assert((numext::isfinite)(fZero));\n#endif\n      \n      muPrev = muCur;\n      fPrev = fCur;\n      muCur = muZero;\n      fCur = fZero;\n      \n      if (shift == left  && (muCur < Literal(0) || muCur > right - left)) useBisection = true;\n      if (shift == right && (muCur < -(right - left) || muCur > Literal(0))) useBisection = true;\n      if (abs(fCur)>abs(fPrev)) useBisection = true;\n    }\n\n    // fall back on bisection method if rational interpolation did not work\n    if (useBisection)\n    {\n#ifdef  EIGEN_BDCSVD_DEBUG_VERBOSE\n      std::cout << \"useBisection for k = \" << k << \", actual_n = \" << actual_n << \"\\n\";\n#endif\n      RealScalar leftShifted, rightShifted;\n      if (shift == left)\n      {\n        // to avoid overflow, we must have mu > max(real_min, |z(k)|/sqrt(real_max)),\n        // the factor 2 is to be more conservative\n        leftShifted = numext::maxi<RealScalar>( (std::numeric_limits<RealScalar>::min)(), Literal(2) * abs(col0(k)) / sqrt((std::numeric_limits<RealScalar>::max)()) );\n\n        // check that we did it right:\n        eigen_internal_assert( (numext::isfinite)( (col0(k)/leftShifted)*(col0(k)/(diag(k)+shift+leftShifted)) ) );\n        // I don't understand why the case k==0 would be special there:\n        // if (k == 0) rightShifted = right - left; else\n        rightShifted = (k==actual_n-1) ? right : ((right - left) * RealScalar(0.51)); // theoretically we can take 0.5, but let's be safe\n      }\n      else\n      {\n        leftShifted = -(right - left) * RealScalar(0.51);\n        if(k+1<n)\n          rightShifted = -numext::maxi<RealScalar>( (std::numeric_limits<RealScalar>::min)(), abs(col0(k+1)) / sqrt((std::numeric_limits<RealScalar>::max)()) );\n        else\n          rightShifted = -(std::numeric_limits<RealScalar>::min)();\n      }\n\n      RealScalar fLeft = secularEq(leftShifted, col0, diag, perm, diagShifted, shift);\n      eigen_internal_assert(fLeft<Literal(0));\n\n#if defined EIGEN_INTERNAL_DEBUGGING || defined EIGEN_BDCSVD_SANITY_CHECKS\n      RealScalar fRight = secularEq(rightShifted, col0, diag, perm, diagShifted, shift);\n#endif\n\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n      if(!(numext::isfinite)(fLeft))\n        std::cout << \"f(\" << leftShifted << \") =\" << fLeft << \" ; \" << left << \" \" << shift << \" \" << right << \"\\n\";\n      assert((numext::isfinite)(fLeft));\n\n      if(!(numext::isfinite)(fRight))\n        std::cout << \"f(\" << rightShifted << \") =\" << fRight << \" ; \" << left << \" \" << shift << \" \" << right << \"\\n\";\n      // assert((numext::isfinite)(fRight));\n#endif\n    \n#ifdef  EIGEN_BDCSVD_DEBUG_VERBOSE\n      if(!(fLeft * fRight<0))\n      {\n        std::cout << \"f(leftShifted) using  leftShifted=\" << leftShifted << \" ;  diagShifted(1:10):\" << diagShifted.head(10).transpose()  << \"\\n ; \"\n                  << \"left==shift=\" << bool(left==shift) << \" ; left-shift = \" << (left-shift) << \"\\n\";\n        std::cout << \"k=\" << k << \", \" <<  fLeft << \" * \" << fRight << \" == \" << fLeft * fRight << \"  ;  \"\n                  << \"[\" << left << \" .. \" << right << \"] -> [\" << leftShifted << \" \" << rightShifted << \"], shift=\" << shift\n                  << \" ,  f(right)=\" << secularEq(0,     col0, diag, perm, diagShifted, shift)\n                           << \" == \" << secularEq(right, col0, diag, perm, diag, 0) << \" == \" << fRight << \"\\n\";\n      }\n#endif\n      eigen_internal_assert(fLeft * fRight < Literal(0));\n\n      if(fLeft<Literal(0))\n      {\n        while (rightShifted - leftShifted > Literal(2) * NumTraits<RealScalar>::epsilon() * numext::maxi<RealScalar>(abs(leftShifted), abs(rightShifted)))\n        {\n          RealScalar midShifted = (leftShifted + rightShifted) / Literal(2);\n          fMid = secularEq(midShifted, col0, diag, perm, diagShifted, shift);\n          eigen_internal_assert((numext::isfinite)(fMid));\n\n          if (fLeft * fMid < Literal(0))\n          {\n            rightShifted = midShifted;\n          }\n          else\n          {\n            leftShifted = midShifted;\n            fLeft = fMid;\n          }\n        }\n        muCur = (leftShifted + rightShifted) / Literal(2);\n      }\n      else \n      {\n        // We have a problem as shifting on the left or right give either a positive or negative value\n        // at the middle of [left,right]...\n        // Instead fo abbording or entering an infinite loop,\n        // let's just use the middle as the estimated zero-crossing:\n        muCur = (right - left) * RealScalar(0.5);\n        if(shift == right)\n          muCur = -muCur;\n      }\n    }\n      \n    singVals[k] = shift + muCur;\n    shifts[k] = shift;\n    mus[k] = muCur;\n\n#ifdef  EIGEN_BDCSVD_DEBUG_VERBOSE\n    if(k+1<n)\n      std::cout << \"found \" << singVals[k] << \" == \" << shift << \" + \" << muCur << \" from \" << diag(k) << \" .. \"  << diag(k+1) << \"\\n\";\n#endif\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n    assert(k==0 || singVals[k]>=singVals[k-1]);\n    assert(singVals[k]>=diag(k));\n#endif\n\n    // perturb singular value slightly if it equals diagonal entry to avoid division by zero later\n    // (deflation is supposed to avoid this from happening)\n    // - this does no seem to be necessary anymore -\n//     if (singVals[k] == left) singVals[k] *= 1 + NumTraits<RealScalar>::epsilon();\n//     if (singVals[k] == right) singVals[k] *= 1 - NumTraits<RealScalar>::epsilon();\n  }\n}\n\n\n// zhat is perturbation of col0 for which singular vectors can be computed stably (see Section 3.1)\ntemplate <typename MatrixType>\nvoid BDCSVD<MatrixType>::perturbCol0\n   (const ArrayRef& col0, const ArrayRef& diag, const IndicesRef &perm, const VectorType& singVals,\n    const ArrayRef& shifts, const ArrayRef& mus, ArrayRef zhat)\n{\n  using std::sqrt;\n  Index n = col0.size();\n  Index m = perm.size();\n  if(m==0)\n  {\n    zhat.setZero();\n    return;\n  }\n  Index lastIdx = perm(m-1);\n  // The offset permits to skip deflated entries while computing zhat\n  for (Index k = 0; k < n; ++k)\n  {\n    if (col0(k) == Literal(0)) // deflated\n      zhat(k) = Literal(0);\n    else\n    {\n      // see equation (3.6)\n      RealScalar dk = diag(k);\n      RealScalar prod = (singVals(lastIdx) + dk) * (mus(lastIdx) + (shifts(lastIdx) - dk));\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n      if(prod<0) {\n        std::cout << \"k = \" << k << \" ;  z(k)=\" << col0(k) << \", diag(k)=\" << dk << \"\\n\";\n        std::cout << \"prod = \" << \"(\" << singVals(lastIdx) << \" + \" << dk << \") * (\" << mus(lastIdx) << \" + (\" << shifts(lastIdx) << \" - \" << dk << \"))\" << \"\\n\";\n        std::cout << \"     = \" << singVals(lastIdx) + dk << \" * \" << mus(lastIdx) + (shifts(lastIdx) - dk) <<  \"\\n\";\n      }\n      assert(prod>=0);\n#endif\n\n      for(Index l = 0; l<m; ++l)\n      {\n        Index i = perm(l);\n        if(i!=k)\n        {\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n          if(i>=k && (l==0 || l-1>=m))\n          {\n            std::cout << \"Error in perturbCol0\\n\";\n            std::cout << \"  \" << k << \"/\" << n << \" \"  << l << \"/\" << m << \" \" << i << \"/\" << n << \" ; \" << col0(k) << \" \" << diag(k) << \" \"  <<  \"\\n\";\n            std::cout << \"  \" <<diag(i) << \"\\n\";\n            Index j = (i<k /*|| l==0*/) ? i : perm(l-1);\n            std::cout << \"  \" << \"j=\" << j << \"\\n\";\n          }\n#endif\n          Index j = i<k ? i : perm(l-1);\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n          if(!(dk!=Literal(0) || diag(i)!=Literal(0)))\n          {\n            std::cout << \"k=\" << k << \", i=\" << i << \", l=\" << l << \", perm.size()=\" << perm.size() << \"\\n\";\n          }\n          assert(dk!=Literal(0) || diag(i)!=Literal(0));\n#endif\n          prod *= ((singVals(j)+dk) / ((diag(i)+dk))) * ((mus(j)+(shifts(j)-dk)) / ((diag(i)-dk)));\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n          assert(prod>=0);\n#endif\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n          if(i!=k && numext::abs(((singVals(j)+dk)*(mus(j)+(shifts(j)-dk)))/((diag(i)+dk)*(diag(i)-dk)) - 1) > 0.9 )\n            std::cout << \"     \" << ((singVals(j)+dk)*(mus(j)+(shifts(j)-dk)))/((diag(i)+dk)*(diag(i)-dk)) << \" == (\" << (singVals(j)+dk) << \" * \" << (mus(j)+(shifts(j)-dk))\n                       << \") / (\" << (diag(i)+dk) << \" * \" << (diag(i)-dk) << \")\\n\";\n#endif\n        }\n      }\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n      std::cout << \"zhat(\" << k << \") =  sqrt( \" << prod << \")  ;  \" << (singVals(lastIdx) + dk) << \" * \" << mus(lastIdx) + shifts(lastIdx) << \" - \" << dk << \"\\n\";\n#endif\n      RealScalar tmp = sqrt(prod);\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n      assert((numext::isfinite)(tmp));\n#endif\n      zhat(k) = col0(k) > Literal(0) ? RealScalar(tmp) : RealScalar(-tmp);\n    }\n  }\n}\n\n// compute singular vectors\ntemplate <typename MatrixType>\nvoid BDCSVD<MatrixType>::computeSingVecs\n   (const ArrayRef& zhat, const ArrayRef& diag, const IndicesRef &perm, const VectorType& singVals,\n    const ArrayRef& shifts, const ArrayRef& mus, MatrixXr& U, MatrixXr& V)\n{\n  Index n = zhat.size();\n  Index m = perm.size();\n  \n  for (Index k = 0; k < n; ++k)\n  {\n    if (zhat(k) == Literal(0))\n    {\n      U.col(k) = VectorType::Unit(n+1, k);\n      if (m_compV) V.col(k) = VectorType::Unit(n, k);\n    }\n    else\n    {\n      U.col(k).setZero();\n      for(Index l=0;l<m;++l)\n      {\n        Index i = perm(l);\n        U(i,k) = zhat(i)/(((diag(i) - shifts(k)) - mus(k)) )/( (diag(i) + singVals[k]));\n      }\n      U(n,k) = Literal(0);\n      U.col(k).normalize();\n    \n      if (m_compV)\n      {\n        V.col(k).setZero();\n        for(Index l=1;l<m;++l)\n        {\n          Index i = perm(l);\n          V(i,k) = diag(i) * zhat(i) / (((diag(i) - shifts(k)) - mus(k)) )/( (diag(i) + singVals[k]));\n        }\n        V(0,k) = Literal(-1);\n        V.col(k).normalize();\n      }\n    }\n  }\n  U.col(n) = VectorType::Unit(n+1, n);\n}\n\n\n// page 12_13\n// i >= 1, di almost null and zi non null.\n// We use a rotation to zero out zi applied to the left of M\ntemplate <typename MatrixType>\nvoid BDCSVD<MatrixType>::deflation43(Eigen::Index firstCol, Eigen::Index shift, Eigen::Index i, Eigen::Index size)\n{\n  using std::abs;\n  using std::sqrt;\n  using std::pow;\n  Index start = firstCol + shift;\n  RealScalar c = m_computed(start, start);\n  RealScalar s = m_computed(start+i, start);\n  RealScalar r = numext::hypot(c,s);\n  if (r == Literal(0))\n  {\n    m_computed(start+i, start+i) = Literal(0);\n    return;\n  }\n  m_computed(start,start) = r;  \n  m_computed(start+i, start) = Literal(0);\n  m_computed(start+i, start+i) = Literal(0);\n  \n  JacobiRotation<RealScalar> J(c/r,-s/r);\n  if (m_compU)  m_naiveU.middleRows(firstCol, size+1).applyOnTheRight(firstCol, firstCol+i, J);\n  else          m_naiveU.applyOnTheRight(firstCol, firstCol+i, J);\n}// end deflation 43\n\n\n// page 13\n// i,j >= 1, i!=j and |di - dj| < epsilon * norm2(M)\n// We apply two rotations to have zj = 0;\n// TODO deflation44 is still broken and not properly tested\ntemplate <typename MatrixType>\nvoid BDCSVD<MatrixType>::deflation44(Eigen::Index firstColu , Eigen::Index firstColm, Eigen::Index firstRowW, Eigen::Index firstColW, Eigen::Index i, Eigen::Index j, Eigen::Index size)\n{\n  using std::abs;\n  using std::sqrt;\n  using std::conj;\n  using std::pow;\n  RealScalar c = m_computed(firstColm+i, firstColm);\n  RealScalar s = m_computed(firstColm+j, firstColm);\n  RealScalar r = sqrt(numext::abs2(c) + numext::abs2(s));\n#ifdef  EIGEN_BDCSVD_DEBUG_VERBOSE\n  std::cout << \"deflation 4.4: \" << i << \",\" << j << \" -> \" << c << \" \" << s << \" \" << r << \" ; \"\n    << m_computed(firstColm + i-1, firstColm)  << \" \"\n    << m_computed(firstColm + i, firstColm)  << \" \"\n    << m_computed(firstColm + i+1, firstColm) << \" \"\n    << m_computed(firstColm + i+2, firstColm) << \"\\n\";\n  std::cout << m_computed(firstColm + i-1, firstColm + i-1)  << \" \"\n    << m_computed(firstColm + i, firstColm+i)  << \" \"\n    << m_computed(firstColm + i+1, firstColm+i+1) << \" \"\n    << m_computed(firstColm + i+2, firstColm+i+2) << \"\\n\";\n#endif\n  if (r==Literal(0))\n  {\n    m_computed(firstColm + i, firstColm + i) = m_computed(firstColm + j, firstColm + j);\n    return;\n  }\n  c/=r;\n  s/=r;\n  m_computed(firstColm + i, firstColm) = r;\n  m_computed(firstColm + j, firstColm + j) = m_computed(firstColm + i, firstColm + i);\n  m_computed(firstColm + j, firstColm) = Literal(0);\n\n  JacobiRotation<RealScalar> J(c,-s);\n  if (m_compU)  m_naiveU.middleRows(firstColu, size+1).applyOnTheRight(firstColu + i, firstColu + j, J);\n  else          m_naiveU.applyOnTheRight(firstColu+i, firstColu+j, J);\n  if (m_compV)  m_naiveV.middleRows(firstRowW, size).applyOnTheRight(firstColW + i, firstColW + j, J);\n}// end deflation 44\n\n\n// acts on block from (firstCol+shift, firstCol+shift) to (lastCol+shift, lastCol+shift) [inclusive]\ntemplate <typename MatrixType>\nvoid BDCSVD<MatrixType>::deflation(Eigen::Index firstCol, Eigen::Index lastCol, Eigen::Index k, Eigen::Index firstRowW, Eigen::Index firstColW, Eigen::Index shift)\n{\n  using std::sqrt;\n  using std::abs;\n  const Index length = lastCol + 1 - firstCol;\n  \n  Block<MatrixXr,Dynamic,1> col0(m_computed, firstCol+shift, firstCol+shift, length, 1);\n  Diagonal<MatrixXr> fulldiag(m_computed);\n  VectorBlock<Diagonal<MatrixXr>,Dynamic> diag(fulldiag, firstCol+shift, length);\n  \n  const RealScalar considerZero = (std::numeric_limits<RealScalar>::min)();\n  RealScalar maxDiag = diag.tail((std::max)(Index(1),length-1)).cwiseAbs().maxCoeff();\n  RealScalar epsilon_strict = numext::maxi<RealScalar>(considerZero,NumTraits<RealScalar>::epsilon() * maxDiag);\n  RealScalar epsilon_coarse = Literal(8) * NumTraits<RealScalar>::epsilon() * numext::maxi<RealScalar>(col0.cwiseAbs().maxCoeff(), maxDiag);\n  \n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  assert(m_naiveU.allFinite());\n  assert(m_naiveV.allFinite());\n  assert(m_computed.allFinite());\n#endif\n\n#ifdef  EIGEN_BDCSVD_DEBUG_VERBOSE  \n  std::cout << \"\\ndeflate:\" << diag.head(k+1).transpose() << \"  |  \" << diag.segment(k+1,length-k-1).transpose() << \"\\n\";\n#endif\n  \n  //condition 4.1\n  if (diag(0) < epsilon_coarse)\n  { \n#ifdef  EIGEN_BDCSVD_DEBUG_VERBOSE\n    std::cout << \"deflation 4.1, because \" << diag(0) << \" < \" << epsilon_coarse << \"\\n\";\n#endif\n    diag(0) = epsilon_coarse;\n  }\n\n  //condition 4.2\n  for (Index i=1;i<length;++i)\n    if (abs(col0(i)) < epsilon_strict)\n    {\n#ifdef  EIGEN_BDCSVD_DEBUG_VERBOSE\n      std::cout << \"deflation 4.2, set z(\" << i << \") to zero because \" << abs(col0(i)) << \" < \" << epsilon_strict << \"  (diag(\" << i << \")=\" << diag(i) << \")\\n\";\n#endif\n      col0(i) = Literal(0);\n    }\n\n  //condition 4.3\n  for (Index i=1;i<length; i++)\n    if (diag(i) < epsilon_coarse)\n    {\n#ifdef  EIGEN_BDCSVD_DEBUG_VERBOSE\n      std::cout << \"deflation 4.3, cancel z(\" << i << \")=\" << col0(i) << \" because diag(\" << i << \")=\" << diag(i) << \" < \" << epsilon_coarse << \"\\n\";\n#endif\n      deflation43(firstCol, shift, i, length);\n    }\n\n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  assert(m_naiveU.allFinite());\n  assert(m_naiveV.allFinite());\n  assert(m_computed.allFinite());\n#endif\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n  std::cout << \"to be sorted: \" << diag.transpose() << \"\\n\\n\";\n  std::cout << \"            : \" << col0.transpose() << \"\\n\\n\";\n#endif\n  {\n    // Check for total deflation\n    // If we have a total deflation, then we have to consider col0(0)==diag(0) as a singular value during sorting\n    bool total_deflation = (col0.tail(length-1).array()<considerZero).all();\n    \n    // Sort the diagonal entries, since diag(1:k-1) and diag(k:length) are already sorted, let's do a sorted merge.\n    // First, compute the respective permutation.\n    Index *permutation = m_workspaceI.data();\n    {\n      permutation[0] = 0;\n      Index p = 1;\n      \n      // Move deflated diagonal entries at the end.\n      for(Index i=1; i<length; ++i)\n        if(abs(diag(i))<considerZero)\n          permutation[p++] = i;\n        \n      Index i=1, j=k+1;\n      for( ; p < length; ++p)\n      {\n             if (i > k)             permutation[p] = j++;\n        else if (j >= length)       permutation[p] = i++;\n        else if (diag(i) < diag(j)) permutation[p] = j++;\n        else                        permutation[p] = i++;\n      }\n    }\n    \n    // If we have a total deflation, then we have to insert diag(0) at the right place\n    if(total_deflation)\n    {\n      for(Index i=1; i<length; ++i)\n      {\n        Index pi = permutation[i];\n        if(abs(diag(pi))<considerZero || diag(0)<diag(pi))\n          permutation[i-1] = permutation[i];\n        else\n        {\n          permutation[i-1] = 0;\n          break;\n        }\n      }\n    }\n    \n    // Current index of each col, and current column of each index\n    Index *realInd = m_workspaceI.data()+length;\n    Index *realCol = m_workspaceI.data()+2*length;\n    \n    for(int pos = 0; pos< length; pos++)\n    {\n      realCol[pos] = pos;\n      realInd[pos] = pos;\n    }\n    \n    for(Index i = total_deflation?0:1; i < length; i++)\n    {\n      const Index pi = permutation[length - (total_deflation ? i+1 : i)];\n      const Index J = realCol[pi];\n      \n      using std::swap;\n      // swap diagonal and first column entries:\n      swap(diag(i), diag(J));\n      if(i!=0 && J!=0) swap(col0(i), col0(J));\n\n      // change columns\n      if (m_compU) m_naiveU.col(firstCol+i).segment(firstCol, length + 1).swap(m_naiveU.col(firstCol+J).segment(firstCol, length + 1));\n      else         m_naiveU.col(firstCol+i).segment(0, 2)                .swap(m_naiveU.col(firstCol+J).segment(0, 2));\n      if (m_compV) m_naiveV.col(firstColW + i).segment(firstRowW, length).swap(m_naiveV.col(firstColW + J).segment(firstRowW, length));\n\n      //update real pos\n      const Index realI = realInd[i];\n      realCol[realI] = J;\n      realCol[pi] = i;\n      realInd[J] = realI;\n      realInd[i] = pi;\n    }\n  }\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n  std::cout << \"sorted: \" << diag.transpose().format(bdcsvdfmt) << \"\\n\";\n  std::cout << \"      : \" << col0.transpose() << \"\\n\\n\";\n#endif\n    \n  //condition 4.4\n  {\n    Index i = length-1;\n    while(i>0 && (abs(diag(i))<considerZero || abs(col0(i))<considerZero)) --i;\n    for(; i>1;--i)\n       if( (diag(i) - diag(i-1)) < NumTraits<RealScalar>::epsilon()*maxDiag )\n      {\n#ifdef EIGEN_BDCSVD_DEBUG_VERBOSE\n        std::cout << \"deflation 4.4 with i = \" << i << \" because \" << diag(i) << \" - \" << diag(i-1) << \" == \" << (diag(i) - diag(i-1)) << \" < \" << NumTraits<RealScalar>::epsilon()*/*diag(i)*/maxDiag << \"\\n\";\n#endif\n        eigen_internal_assert(abs(diag(i) - diag(i-1))<epsilon_coarse && \" diagonal entries are not properly sorted\");\n        deflation44(firstCol, firstCol + shift, firstRowW, firstColW, i-1, i, length);\n      }\n  }\n  \n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  for(Index j=2;j<length;++j)\n    assert(diag(j-1)<=diag(j) || abs(diag(j))<considerZero);\n#endif\n  \n#ifdef EIGEN_BDCSVD_SANITY_CHECKS\n  assert(m_naiveU.allFinite());\n  assert(m_naiveV.allFinite());\n  assert(m_computed.allFinite());\n#endif\n}//end deflation\n\n/** \\svd_module\n  *\n  * \\return the singular value decomposition of \\c *this computed by Divide & Conquer algorithm\n  *\n  * \\sa class BDCSVD\n  */\ntemplate<typename Derived>\nBDCSVD<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::bdcSvd(unsigned int computationOptions) const\n{\n  return BDCSVD<PlainObject>(*this, computationOptions);\n}\n\n} // end namespace Eigen\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SVD/JacobiSVD.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2013-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_JACOBISVD_H\n#define EIGEN_JACOBISVD_H\n\nnamespace Eigen { \n\nnamespace internal {\n// forward declaration (needed by ICC)\n// the empty body is required by MSVC\ntemplate<typename MatrixType, int QRPreconditioner,\n         bool IsComplex = NumTraits<typename MatrixType::Scalar>::IsComplex>\nstruct svd_precondition_2x2_block_to_be_real {};\n\n/*** QR preconditioners (R-SVD)\n ***\n *** Their role is to reduce the problem of computing the SVD to the case of a square matrix.\n *** This approach, known as R-SVD, is an optimization for rectangular-enough matrices, and is a requirement for\n *** JacobiSVD which by itself is only able to work on square matrices.\n ***/\n\nenum { PreconditionIfMoreColsThanRows, PreconditionIfMoreRowsThanCols };\n\ntemplate<typename MatrixType, int QRPreconditioner, int Case>\nstruct qr_preconditioner_should_do_anything\n{\n  enum { a = MatrixType::RowsAtCompileTime != Dynamic &&\n             MatrixType::ColsAtCompileTime != Dynamic &&\n             MatrixType::ColsAtCompileTime <= MatrixType::RowsAtCompileTime,\n         b = MatrixType::RowsAtCompileTime != Dynamic &&\n             MatrixType::ColsAtCompileTime != Dynamic &&\n             MatrixType::RowsAtCompileTime <= MatrixType::ColsAtCompileTime,\n         ret = !( (QRPreconditioner == NoQRPreconditioner) ||\n                  (Case == PreconditionIfMoreColsThanRows && bool(a)) ||\n                  (Case == PreconditionIfMoreRowsThanCols && bool(b)) )\n  };\n};\n\ntemplate<typename MatrixType, int QRPreconditioner, int Case,\n         bool DoAnything = qr_preconditioner_should_do_anything<MatrixType, QRPreconditioner, Case>::ret\n> struct qr_preconditioner_impl {};\n\ntemplate<typename MatrixType, int QRPreconditioner, int Case>\nclass qr_preconditioner_impl<MatrixType, QRPreconditioner, Case, false>\n{\npublic:\n  void allocate(const JacobiSVD<MatrixType, QRPreconditioner>&) {}\n  bool run(JacobiSVD<MatrixType, QRPreconditioner>&, const MatrixType&)\n  {\n    return false;\n  }\n};\n\n/*** preconditioner using FullPivHouseholderQR ***/\n\ntemplate<typename MatrixType>\nclass qr_preconditioner_impl<MatrixType, FullPivHouseholderQRPreconditioner, PreconditionIfMoreRowsThanCols, true>\n{\npublic:\n  typedef typename MatrixType::Scalar Scalar;\n  enum\n  {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n    MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime\n  };\n  typedef Matrix<Scalar, 1, RowsAtCompileTime, RowMajor, 1, MaxRowsAtCompileTime> WorkspaceType;\n\n  void allocate(const JacobiSVD<MatrixType, FullPivHouseholderQRPreconditioner>& svd)\n  {\n    if (svd.rows() != m_qr.rows() || svd.cols() != m_qr.cols())\n    {\n      m_qr.~QRType();\n      ::new (&m_qr) QRType(svd.rows(), svd.cols());\n    }\n    if (svd.m_computeFullU) m_workspace.resize(svd.rows());\n  }\n\n  bool run(JacobiSVD<MatrixType, FullPivHouseholderQRPreconditioner>& svd, const MatrixType& matrix)\n  {\n    if(matrix.rows() > matrix.cols())\n    {\n      m_qr.compute(matrix);\n      svd.m_workMatrix = m_qr.matrixQR().block(0,0,matrix.cols(),matrix.cols()).template triangularView<Upper>();\n      if(svd.m_computeFullU) m_qr.matrixQ().evalTo(svd.m_matrixU, m_workspace);\n      if(svd.computeV()) svd.m_matrixV = m_qr.colsPermutation();\n      return true;\n    }\n    return false;\n  }\nprivate:\n  typedef FullPivHouseholderQR<MatrixType> QRType;\n  QRType m_qr;\n  WorkspaceType m_workspace;\n};\n\ntemplate<typename MatrixType>\nclass qr_preconditioner_impl<MatrixType, FullPivHouseholderQRPreconditioner, PreconditionIfMoreColsThanRows, true>\n{\npublic:\n  typedef typename MatrixType::Scalar Scalar;\n  enum\n  {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n    MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n    MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime,\n    TrOptions = RowsAtCompileTime==1 ? (MatrixType::Options & ~(RowMajor))\n              : ColsAtCompileTime==1 ? (MatrixType::Options |   RowMajor)\n              : MatrixType::Options\n  };\n  typedef Matrix<Scalar, ColsAtCompileTime, RowsAtCompileTime, TrOptions, MaxColsAtCompileTime, MaxRowsAtCompileTime>\n          TransposeTypeWithSameStorageOrder;\n\n  void allocate(const JacobiSVD<MatrixType, FullPivHouseholderQRPreconditioner>& svd)\n  {\n    if (svd.cols() != m_qr.rows() || svd.rows() != m_qr.cols())\n    {\n      m_qr.~QRType();\n      ::new (&m_qr) QRType(svd.cols(), svd.rows());\n    }\n    m_adjoint.resize(svd.cols(), svd.rows());\n    if (svd.m_computeFullV) m_workspace.resize(svd.cols());\n  }\n\n  bool run(JacobiSVD<MatrixType, FullPivHouseholderQRPreconditioner>& svd, const MatrixType& matrix)\n  {\n    if(matrix.cols() > matrix.rows())\n    {\n      m_adjoint = matrix.adjoint();\n      m_qr.compute(m_adjoint);\n      svd.m_workMatrix = m_qr.matrixQR().block(0,0,matrix.rows(),matrix.rows()).template triangularView<Upper>().adjoint();\n      if(svd.m_computeFullV) m_qr.matrixQ().evalTo(svd.m_matrixV, m_workspace);\n      if(svd.computeU()) svd.m_matrixU = m_qr.colsPermutation();\n      return true;\n    }\n    else return false;\n  }\nprivate:\n  typedef FullPivHouseholderQR<TransposeTypeWithSameStorageOrder> QRType;\n  QRType m_qr;\n  TransposeTypeWithSameStorageOrder m_adjoint;\n  typename internal::plain_row_type<MatrixType>::type m_workspace;\n};\n\n/*** preconditioner using ColPivHouseholderQR ***/\n\ntemplate<typename MatrixType>\nclass qr_preconditioner_impl<MatrixType, ColPivHouseholderQRPreconditioner, PreconditionIfMoreRowsThanCols, true>\n{\npublic:\n  void allocate(const JacobiSVD<MatrixType, ColPivHouseholderQRPreconditioner>& svd)\n  {\n    if (svd.rows() != m_qr.rows() || svd.cols() != m_qr.cols())\n    {\n      m_qr.~QRType();\n      ::new (&m_qr) QRType(svd.rows(), svd.cols());\n    }\n    if (svd.m_computeFullU) m_workspace.resize(svd.rows());\n    else if (svd.m_computeThinU) m_workspace.resize(svd.cols());\n  }\n\n  bool run(JacobiSVD<MatrixType, ColPivHouseholderQRPreconditioner>& svd, const MatrixType& matrix)\n  {\n    if(matrix.rows() > matrix.cols())\n    {\n      m_qr.compute(matrix);\n      svd.m_workMatrix = m_qr.matrixQR().block(0,0,matrix.cols(),matrix.cols()).template triangularView<Upper>();\n      if(svd.m_computeFullU) m_qr.householderQ().evalTo(svd.m_matrixU, m_workspace);\n      else if(svd.m_computeThinU)\n      {\n        svd.m_matrixU.setIdentity(matrix.rows(), matrix.cols());\n        m_qr.householderQ().applyThisOnTheLeft(svd.m_matrixU, m_workspace);\n      }\n      if(svd.computeV()) svd.m_matrixV = m_qr.colsPermutation();\n      return true;\n    }\n    return false;\n  }\n\nprivate:\n  typedef ColPivHouseholderQR<MatrixType> QRType;\n  QRType m_qr;\n  typename internal::plain_col_type<MatrixType>::type m_workspace;\n};\n\ntemplate<typename MatrixType>\nclass qr_preconditioner_impl<MatrixType, ColPivHouseholderQRPreconditioner, PreconditionIfMoreColsThanRows, true>\n{\npublic:\n  typedef typename MatrixType::Scalar Scalar;\n  enum\n  {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n    MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n    MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime,\n    TrOptions = RowsAtCompileTime==1 ? (MatrixType::Options & ~(RowMajor))\n              : ColsAtCompileTime==1 ? (MatrixType::Options |   RowMajor)\n              : MatrixType::Options\n  };\n\n  typedef Matrix<Scalar, ColsAtCompileTime, RowsAtCompileTime, TrOptions, MaxColsAtCompileTime, MaxRowsAtCompileTime>\n          TransposeTypeWithSameStorageOrder;\n\n  void allocate(const JacobiSVD<MatrixType, ColPivHouseholderQRPreconditioner>& svd)\n  {\n    if (svd.cols() != m_qr.rows() || svd.rows() != m_qr.cols())\n    {\n      m_qr.~QRType();\n      ::new (&m_qr) QRType(svd.cols(), svd.rows());\n    }\n    if (svd.m_computeFullV) m_workspace.resize(svd.cols());\n    else if (svd.m_computeThinV) m_workspace.resize(svd.rows());\n    m_adjoint.resize(svd.cols(), svd.rows());\n  }\n\n  bool run(JacobiSVD<MatrixType, ColPivHouseholderQRPreconditioner>& svd, const MatrixType& matrix)\n  {\n    if(matrix.cols() > matrix.rows())\n    {\n      m_adjoint = matrix.adjoint();\n      m_qr.compute(m_adjoint);\n\n      svd.m_workMatrix = m_qr.matrixQR().block(0,0,matrix.rows(),matrix.rows()).template triangularView<Upper>().adjoint();\n      if(svd.m_computeFullV) m_qr.householderQ().evalTo(svd.m_matrixV, m_workspace);\n      else if(svd.m_computeThinV)\n      {\n        svd.m_matrixV.setIdentity(matrix.cols(), matrix.rows());\n        m_qr.householderQ().applyThisOnTheLeft(svd.m_matrixV, m_workspace);\n      }\n      if(svd.computeU()) svd.m_matrixU = m_qr.colsPermutation();\n      return true;\n    }\n    else return false;\n  }\n\nprivate:\n  typedef ColPivHouseholderQR<TransposeTypeWithSameStorageOrder> QRType;\n  QRType m_qr;\n  TransposeTypeWithSameStorageOrder m_adjoint;\n  typename internal::plain_row_type<MatrixType>::type m_workspace;\n};\n\n/*** preconditioner using HouseholderQR ***/\n\ntemplate<typename MatrixType>\nclass qr_preconditioner_impl<MatrixType, HouseholderQRPreconditioner, PreconditionIfMoreRowsThanCols, true>\n{\npublic:\n  void allocate(const JacobiSVD<MatrixType, HouseholderQRPreconditioner>& svd)\n  {\n    if (svd.rows() != m_qr.rows() || svd.cols() != m_qr.cols())\n    {\n      m_qr.~QRType();\n      ::new (&m_qr) QRType(svd.rows(), svd.cols());\n    }\n    if (svd.m_computeFullU) m_workspace.resize(svd.rows());\n    else if (svd.m_computeThinU) m_workspace.resize(svd.cols());\n  }\n\n  bool run(JacobiSVD<MatrixType, HouseholderQRPreconditioner>& svd, const MatrixType& matrix)\n  {\n    if(matrix.rows() > matrix.cols())\n    {\n      m_qr.compute(matrix);\n      svd.m_workMatrix = m_qr.matrixQR().block(0,0,matrix.cols(),matrix.cols()).template triangularView<Upper>();\n      if(svd.m_computeFullU) m_qr.householderQ().evalTo(svd.m_matrixU, m_workspace);\n      else if(svd.m_computeThinU)\n      {\n        svd.m_matrixU.setIdentity(matrix.rows(), matrix.cols());\n        m_qr.householderQ().applyThisOnTheLeft(svd.m_matrixU, m_workspace);\n      }\n      if(svd.computeV()) svd.m_matrixV.setIdentity(matrix.cols(), matrix.cols());\n      return true;\n    }\n    return false;\n  }\nprivate:\n  typedef HouseholderQR<MatrixType> QRType;\n  QRType m_qr;\n  typename internal::plain_col_type<MatrixType>::type m_workspace;\n};\n\ntemplate<typename MatrixType>\nclass qr_preconditioner_impl<MatrixType, HouseholderQRPreconditioner, PreconditionIfMoreColsThanRows, true>\n{\npublic:\n  typedef typename MatrixType::Scalar Scalar;\n  enum\n  {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n    MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n    MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime,\n    Options = MatrixType::Options\n  };\n\n  typedef Matrix<Scalar, ColsAtCompileTime, RowsAtCompileTime, Options, MaxColsAtCompileTime, MaxRowsAtCompileTime>\n          TransposeTypeWithSameStorageOrder;\n\n  void allocate(const JacobiSVD<MatrixType, HouseholderQRPreconditioner>& svd)\n  {\n    if (svd.cols() != m_qr.rows() || svd.rows() != m_qr.cols())\n    {\n      m_qr.~QRType();\n      ::new (&m_qr) QRType(svd.cols(), svd.rows());\n    }\n    if (svd.m_computeFullV) m_workspace.resize(svd.cols());\n    else if (svd.m_computeThinV) m_workspace.resize(svd.rows());\n    m_adjoint.resize(svd.cols(), svd.rows());\n  }\n\n  bool run(JacobiSVD<MatrixType, HouseholderQRPreconditioner>& svd, const MatrixType& matrix)\n  {\n    if(matrix.cols() > matrix.rows())\n    {\n      m_adjoint = matrix.adjoint();\n      m_qr.compute(m_adjoint);\n\n      svd.m_workMatrix = m_qr.matrixQR().block(0,0,matrix.rows(),matrix.rows()).template triangularView<Upper>().adjoint();\n      if(svd.m_computeFullV) m_qr.householderQ().evalTo(svd.m_matrixV, m_workspace);\n      else if(svd.m_computeThinV)\n      {\n        svd.m_matrixV.setIdentity(matrix.cols(), matrix.rows());\n        m_qr.householderQ().applyThisOnTheLeft(svd.m_matrixV, m_workspace);\n      }\n      if(svd.computeU()) svd.m_matrixU.setIdentity(matrix.rows(), matrix.rows());\n      return true;\n    }\n    else return false;\n  }\n\nprivate:\n  typedef HouseholderQR<TransposeTypeWithSameStorageOrder> QRType;\n  QRType m_qr;\n  TransposeTypeWithSameStorageOrder m_adjoint;\n  typename internal::plain_row_type<MatrixType>::type m_workspace;\n};\n\n/*** 2x2 SVD implementation\n ***\n *** JacobiSVD consists in performing a series of 2x2 SVD subproblems\n ***/\n\ntemplate<typename MatrixType, int QRPreconditioner>\nstruct svd_precondition_2x2_block_to_be_real<MatrixType, QRPreconditioner, false>\n{\n  typedef JacobiSVD<MatrixType, QRPreconditioner> SVD;\n  typedef typename MatrixType::RealScalar RealScalar;\n  static bool run(typename SVD::WorkMatrixType&, SVD&, Index, Index, RealScalar&) { return true; }\n};\n\ntemplate<typename MatrixType, int QRPreconditioner>\nstruct svd_precondition_2x2_block_to_be_real<MatrixType, QRPreconditioner, true>\n{\n  typedef JacobiSVD<MatrixType, QRPreconditioner> SVD;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  static bool run(typename SVD::WorkMatrixType& work_matrix, SVD& svd, Index p, Index q, RealScalar& maxDiagEntry)\n  {\n    using std::sqrt;\n    using std::abs;\n    Scalar z;\n    JacobiRotation<Scalar> rot;\n    RealScalar n = sqrt(numext::abs2(work_matrix.coeff(p,p)) + numext::abs2(work_matrix.coeff(q,p)));\n\n    const RealScalar considerAsZero = (std::numeric_limits<RealScalar>::min)();\n    const RealScalar precision = NumTraits<Scalar>::epsilon();\n\n    if(n==0)\n    {\n      // make sure first column is zero\n      work_matrix.coeffRef(p,p) = work_matrix.coeffRef(q,p) = Scalar(0);\n\n      if(abs(numext::imag(work_matrix.coeff(p,q)))>considerAsZero)\n      {\n        // work_matrix.coeff(p,q) can be zero if work_matrix.coeff(q,p) is not zero but small enough to underflow when computing n\n        z = abs(work_matrix.coeff(p,q)) / work_matrix.coeff(p,q);\n        work_matrix.row(p) *= z;\n        if(svd.computeU()) svd.m_matrixU.col(p) *= conj(z);\n      }\n      if(abs(numext::imag(work_matrix.coeff(q,q)))>considerAsZero)\n      {\n        z = abs(work_matrix.coeff(q,q)) / work_matrix.coeff(q,q);\n        work_matrix.row(q) *= z;\n        if(svd.computeU()) svd.m_matrixU.col(q) *= conj(z);\n      }\n      // otherwise the second row is already zero, so we have nothing to do.\n    }\n    else\n    {\n      rot.c() = conj(work_matrix.coeff(p,p)) / n;\n      rot.s() = work_matrix.coeff(q,p) / n;\n      work_matrix.applyOnTheLeft(p,q,rot);\n      if(svd.computeU()) svd.m_matrixU.applyOnTheRight(p,q,rot.adjoint());\n      if(abs(numext::imag(work_matrix.coeff(p,q)))>considerAsZero)\n      {\n        z = abs(work_matrix.coeff(p,q)) / work_matrix.coeff(p,q);\n        work_matrix.col(q) *= z;\n        if(svd.computeV()) svd.m_matrixV.col(q) *= z;\n      }\n      if(abs(numext::imag(work_matrix.coeff(q,q)))>considerAsZero)\n      {\n        z = abs(work_matrix.coeff(q,q)) / work_matrix.coeff(q,q);\n        work_matrix.row(q) *= z;\n        if(svd.computeU()) svd.m_matrixU.col(q) *= conj(z);\n      }\n    }\n\n    // update largest diagonal entry\n    maxDiagEntry = numext::maxi<RealScalar>(maxDiagEntry,numext::maxi<RealScalar>(abs(work_matrix.coeff(p,p)), abs(work_matrix.coeff(q,q))));\n    // and check whether the 2x2 block is already diagonal\n    RealScalar threshold = numext::maxi<RealScalar>(considerAsZero, precision * maxDiagEntry);\n    return abs(work_matrix.coeff(p,q))>threshold || abs(work_matrix.coeff(q,p)) > threshold;\n  }\n};\n\ntemplate<typename _MatrixType, int QRPreconditioner> \nstruct traits<JacobiSVD<_MatrixType,QRPreconditioner> >\n        : traits<_MatrixType>\n{\n  typedef _MatrixType MatrixType;\n};\n\n} // end namespace internal\n\n/** \\ingroup SVD_Module\n  *\n  *\n  * \\class JacobiSVD\n  *\n  * \\brief Two-sided Jacobi SVD decomposition of a rectangular matrix\n  *\n  * \\tparam _MatrixType the type of the matrix of which we are computing the SVD decomposition\n  * \\tparam QRPreconditioner this optional parameter allows to specify the type of QR decomposition that will be used internally\n  *                        for the R-SVD step for non-square matrices. See discussion of possible values below.\n  *\n  * SVD decomposition consists in decomposing any n-by-p matrix \\a A as a product\n  *   \\f[ A = U S V^* \\f]\n  * where \\a U is a n-by-n unitary, \\a V is a p-by-p unitary, and \\a S is a n-by-p real positive matrix which is zero outside of its main diagonal;\n  * the diagonal entries of S are known as the \\em singular \\em values of \\a A and the columns of \\a U and \\a V are known as the left\n  * and right \\em singular \\em vectors of \\a A respectively.\n  *\n  * Singular values are always sorted in decreasing order.\n  *\n  * This JacobiSVD decomposition computes only the singular values by default. If you want \\a U or \\a V, you need to ask for them explicitly.\n  *\n  * You can ask for only \\em thin \\a U or \\a V to be computed, meaning the following. In case of a rectangular n-by-p matrix, letting \\a m be the\n  * smaller value among \\a n and \\a p, there are only \\a m singular vectors; the remaining columns of \\a U and \\a V do not correspond to actual\n  * singular vectors. Asking for \\em thin \\a U or \\a V means asking for only their \\a m first columns to be formed. So \\a U is then a n-by-m matrix,\n  * and \\a V is then a p-by-m matrix. Notice that thin \\a U and \\a V are all you need for (least squares) solving.\n  *\n  * Here's an example demonstrating basic usage:\n  * \\include JacobiSVD_basic.cpp\n  * Output: \\verbinclude JacobiSVD_basic.out\n  *\n  * This JacobiSVD class is a two-sided Jacobi R-SVD decomposition, ensuring optimal reliability and accuracy. The downside is that it's slower than\n  * bidiagonalizing SVD algorithms for large square matrices; however its complexity is still \\f$ O(n^2p) \\f$ where \\a n is the smaller dimension and\n  * \\a p is the greater dimension, meaning that it is still of the same order of complexity as the faster bidiagonalizing R-SVD algorithms.\n  * In particular, like any R-SVD, it takes advantage of non-squareness in that its complexity is only linear in the greater dimension.\n  *\n  * If the input matrix has inf or nan coefficients, the result of the computation is undefined, but the computation is guaranteed to\n  * terminate in finite (and reasonable) time.\n  *\n  * The possible values for QRPreconditioner are:\n  * \\li ColPivHouseholderQRPreconditioner is the default. In practice it's very safe. It uses column-pivoting QR.\n  * \\li FullPivHouseholderQRPreconditioner, is the safest and slowest. It uses full-pivoting QR.\n  *     Contrary to other QRs, it doesn't allow computing thin unitaries.\n  * \\li HouseholderQRPreconditioner is the fastest, and less safe and accurate than the pivoting variants. It uses non-pivoting QR.\n  *     This is very similar in safety and accuracy to the bidiagonalization process used by bidiagonalizing SVD algorithms (since bidiagonalization\n  *     is inherently non-pivoting). However the resulting SVD is still more reliable than bidiagonalizing SVDs because the Jacobi-based iterarive\n  *     process is more reliable than the optimized bidiagonal SVD iterations.\n  * \\li NoQRPreconditioner allows not to use a QR preconditioner at all. This is useful if you know that you will only be computing\n  *     JacobiSVD decompositions of square matrices. Non-square matrices require a QR preconditioner. Using this option will result in\n  *     faster compilation and smaller executable code. It won't significantly speed up computation, since JacobiSVD is always checking\n  *     if QR preconditioning is needed before applying it anyway.\n  *\n  * \\sa MatrixBase::jacobiSvd()\n  */\ntemplate<typename _MatrixType, int QRPreconditioner> class JacobiSVD\n : public SVDBase<JacobiSVD<_MatrixType,QRPreconditioner> >\n{\n    typedef SVDBase<JacobiSVD> Base;\n  public:\n\n    typedef _MatrixType MatrixType;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename NumTraits<typename MatrixType::Scalar>::Real RealScalar;\n    enum {\n      RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      DiagSizeAtCompileTime = EIGEN_SIZE_MIN_PREFER_DYNAMIC(RowsAtCompileTime,ColsAtCompileTime),\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime,\n      MaxDiagSizeAtCompileTime = EIGEN_SIZE_MIN_PREFER_FIXED(MaxRowsAtCompileTime,MaxColsAtCompileTime),\n      MatrixOptions = MatrixType::Options\n    };\n\n    typedef typename Base::MatrixUType MatrixUType;\n    typedef typename Base::MatrixVType MatrixVType;\n    typedef typename Base::SingularValuesType SingularValuesType;\n    \n    typedef typename internal::plain_row_type<MatrixType>::type RowType;\n    typedef typename internal::plain_col_type<MatrixType>::type ColType;\n    typedef Matrix<Scalar, DiagSizeAtCompileTime, DiagSizeAtCompileTime,\n                   MatrixOptions, MaxDiagSizeAtCompileTime, MaxDiagSizeAtCompileTime>\n            WorkMatrixType;\n\n    /** \\brief Default Constructor.\n      *\n      * The default constructor is useful in cases in which the user intends to\n      * perform decompositions via JacobiSVD::compute(const MatrixType&).\n      */\n    JacobiSVD()\n    {}\n\n\n    /** \\brief Default Constructor with memory preallocation\n      *\n      * Like the default constructor but with preallocation of the internal data\n      * according to the specified problem size.\n      * \\sa JacobiSVD()\n      */\n    JacobiSVD(Index rows, Index cols, unsigned int computationOptions = 0)\n    {\n      allocate(rows, cols, computationOptions);\n    }\n\n    /** \\brief Constructor performing the decomposition of given matrix.\n     *\n     * \\param matrix the matrix to decompose\n     * \\param computationOptions optional parameter allowing to specify if you want full or thin U or V unitaries to be computed.\n     *                           By default, none is computed. This is a bit-field, the possible bits are #ComputeFullU, #ComputeThinU,\n     *                           #ComputeFullV, #ComputeThinV.\n     *\n     * Thin unitaries are only available if your matrix type has a Dynamic number of columns (for example MatrixXf). They also are not\n     * available with the (non-default) FullPivHouseholderQR preconditioner.\n     */\n    explicit JacobiSVD(const MatrixType& matrix, unsigned int computationOptions = 0)\n    {\n      compute(matrix, computationOptions);\n    }\n\n    /** \\brief Method performing the decomposition of given matrix using custom options.\n     *\n     * \\param matrix the matrix to decompose\n     * \\param computationOptions optional parameter allowing to specify if you want full or thin U or V unitaries to be computed.\n     *                           By default, none is computed. This is a bit-field, the possible bits are #ComputeFullU, #ComputeThinU,\n     *                           #ComputeFullV, #ComputeThinV.\n     *\n     * Thin unitaries are only available if your matrix type has a Dynamic number of columns (for example MatrixXf). They also are not\n     * available with the (non-default) FullPivHouseholderQR preconditioner.\n     */\n    JacobiSVD& compute(const MatrixType& matrix, unsigned int computationOptions);\n\n    /** \\brief Method performing the decomposition of given matrix using current options.\n     *\n     * \\param matrix the matrix to decompose\n     *\n     * This method uses the current \\a computationOptions, as already passed to the constructor or to compute(const MatrixType&, unsigned int).\n     */\n    JacobiSVD& compute(const MatrixType& matrix)\n    {\n      return compute(matrix, m_computationOptions);\n    }\n\n    using Base::computeU;\n    using Base::computeV;\n    using Base::rows;\n    using Base::cols;\n    using Base::rank;\n\n  private:\n    void allocate(Index rows, Index cols, unsigned int computationOptions);\n\n  protected:\n    using Base::m_matrixU;\n    using Base::m_matrixV;\n    using Base::m_singularValues;\n    using Base::m_isInitialized;\n    using Base::m_isAllocated;\n    using Base::m_usePrescribedThreshold;\n    using Base::m_computeFullU;\n    using Base::m_computeThinU;\n    using Base::m_computeFullV;\n    using Base::m_computeThinV;\n    using Base::m_computationOptions;\n    using Base::m_nonzeroSingularValues;\n    using Base::m_rows;\n    using Base::m_cols;\n    using Base::m_diagSize;\n    using Base::m_prescribedThreshold;\n    WorkMatrixType m_workMatrix;\n\n    template<typename __MatrixType, int _QRPreconditioner, bool _IsComplex>\n    friend struct internal::svd_precondition_2x2_block_to_be_real;\n    template<typename __MatrixType, int _QRPreconditioner, int _Case, bool _DoAnything>\n    friend struct internal::qr_preconditioner_impl;\n\n    internal::qr_preconditioner_impl<MatrixType, QRPreconditioner, internal::PreconditionIfMoreColsThanRows> m_qr_precond_morecols;\n    internal::qr_preconditioner_impl<MatrixType, QRPreconditioner, internal::PreconditionIfMoreRowsThanCols> m_qr_precond_morerows;\n    MatrixType m_scaledMatrix;\n};\n\ntemplate<typename MatrixType, int QRPreconditioner>\nvoid JacobiSVD<MatrixType, QRPreconditioner>::allocate(Eigen::Index rows, Eigen::Index cols, unsigned int computationOptions)\n{\n  eigen_assert(rows >= 0 && cols >= 0);\n\n  if (m_isAllocated &&\n      rows == m_rows &&\n      cols == m_cols &&\n      computationOptions == m_computationOptions)\n  {\n    return;\n  }\n\n  m_rows = rows;\n  m_cols = cols;\n  m_isInitialized = false;\n  m_isAllocated = true;\n  m_computationOptions = computationOptions;\n  m_computeFullU = (computationOptions & ComputeFullU) != 0;\n  m_computeThinU = (computationOptions & ComputeThinU) != 0;\n  m_computeFullV = (computationOptions & ComputeFullV) != 0;\n  m_computeThinV = (computationOptions & ComputeThinV) != 0;\n  eigen_assert(!(m_computeFullU && m_computeThinU) && \"JacobiSVD: you can't ask for both full and thin U\");\n  eigen_assert(!(m_computeFullV && m_computeThinV) && \"JacobiSVD: you can't ask for both full and thin V\");\n  eigen_assert(EIGEN_IMPLIES(m_computeThinU || m_computeThinV, MatrixType::ColsAtCompileTime==Dynamic) &&\n              \"JacobiSVD: thin U and V are only available when your matrix has a dynamic number of columns.\");\n  if (QRPreconditioner == FullPivHouseholderQRPreconditioner)\n  {\n      eigen_assert(!(m_computeThinU || m_computeThinV) &&\n              \"JacobiSVD: can't compute thin U or thin V with the FullPivHouseholderQR preconditioner. \"\n              \"Use the ColPivHouseholderQR preconditioner instead.\");\n  }\n  m_diagSize = (std::min)(m_rows, m_cols);\n  m_singularValues.resize(m_diagSize);\n  if(RowsAtCompileTime==Dynamic)\n    m_matrixU.resize(m_rows, m_computeFullU ? m_rows\n                            : m_computeThinU ? m_diagSize\n                            : 0);\n  if(ColsAtCompileTime==Dynamic)\n    m_matrixV.resize(m_cols, m_computeFullV ? m_cols\n                            : m_computeThinV ? m_diagSize\n                            : 0);\n  m_workMatrix.resize(m_diagSize, m_diagSize);\n  \n  if(m_cols>m_rows)   m_qr_precond_morecols.allocate(*this);\n  if(m_rows>m_cols)   m_qr_precond_morerows.allocate(*this);\n  if(m_rows!=m_cols)  m_scaledMatrix.resize(rows,cols);\n}\n\ntemplate<typename MatrixType, int QRPreconditioner>\nJacobiSVD<MatrixType, QRPreconditioner>&\nJacobiSVD<MatrixType, QRPreconditioner>::compute(const MatrixType& matrix, unsigned int computationOptions)\n{\n  using std::abs;\n  allocate(matrix.rows(), matrix.cols(), computationOptions);\n\n  // currently we stop when we reach precision 2*epsilon as the last bit of precision can require an unreasonable number of iterations,\n  // only worsening the precision of U and V as we accumulate more rotations\n  const RealScalar precision = RealScalar(2) * NumTraits<Scalar>::epsilon();\n\n  // limit for denormal numbers to be considered zero in order to avoid infinite loops (see bug 286)\n  const RealScalar considerAsZero = (std::numeric_limits<RealScalar>::min)();\n\n  // Scaling factor to reduce over/under-flows\n  RealScalar scale = matrix.cwiseAbs().maxCoeff();\n  if(scale==RealScalar(0)) scale = RealScalar(1);\n  \n  /*** step 1. The R-SVD step: we use a QR decomposition to reduce to the case of a square matrix */\n\n  if(m_rows!=m_cols)\n  {\n    m_scaledMatrix = matrix / scale;\n    m_qr_precond_morecols.run(*this, m_scaledMatrix);\n    m_qr_precond_morerows.run(*this, m_scaledMatrix);\n  }\n  else\n  {\n    m_workMatrix = matrix.block(0,0,m_diagSize,m_diagSize) / scale;\n    if(m_computeFullU) m_matrixU.setIdentity(m_rows,m_rows);\n    if(m_computeThinU) m_matrixU.setIdentity(m_rows,m_diagSize);\n    if(m_computeFullV) m_matrixV.setIdentity(m_cols,m_cols);\n    if(m_computeThinV) m_matrixV.setIdentity(m_cols, m_diagSize);\n  }\n\n  /*** step 2. The main Jacobi SVD iteration. ***/\n  RealScalar maxDiagEntry = m_workMatrix.cwiseAbs().diagonal().maxCoeff();\n\n  bool finished = false;\n  while(!finished)\n  {\n    finished = true;\n\n    // do a sweep: for all index pairs (p,q), perform SVD of the corresponding 2x2 sub-matrix\n\n    for(Index p = 1; p < m_diagSize; ++p)\n    {\n      for(Index q = 0; q < p; ++q)\n      {\n        // if this 2x2 sub-matrix is not diagonal already...\n        // notice that this comparison will evaluate to false if any NaN is involved, ensuring that NaN's don't\n        // keep us iterating forever. Similarly, small denormal numbers are considered zero.\n        RealScalar threshold = numext::maxi<RealScalar>(considerAsZero, precision * maxDiagEntry);\n        if(abs(m_workMatrix.coeff(p,q))>threshold || abs(m_workMatrix.coeff(q,p)) > threshold)\n        {\n          finished = false;\n          // perform SVD decomposition of 2x2 sub-matrix corresponding to indices p,q to make it diagonal\n          // the complex to real operation returns true if the updated 2x2 block is not already diagonal\n          if(internal::svd_precondition_2x2_block_to_be_real<MatrixType, QRPreconditioner>::run(m_workMatrix, *this, p, q, maxDiagEntry))\n          {\n            JacobiRotation<RealScalar> j_left, j_right;\n            internal::real_2x2_jacobi_svd(m_workMatrix, p, q, &j_left, &j_right);\n\n            // accumulate resulting Jacobi rotations\n            m_workMatrix.applyOnTheLeft(p,q,j_left);\n            if(computeU()) m_matrixU.applyOnTheRight(p,q,j_left.transpose());\n\n            m_workMatrix.applyOnTheRight(p,q,j_right);\n            if(computeV()) m_matrixV.applyOnTheRight(p,q,j_right);\n\n            // keep track of the largest diagonal coefficient\n            maxDiagEntry = numext::maxi<RealScalar>(maxDiagEntry,numext::maxi<RealScalar>(abs(m_workMatrix.coeff(p,p)), abs(m_workMatrix.coeff(q,q))));\n          }\n        }\n      }\n    }\n  }\n\n  /*** step 3. The work matrix is now diagonal, so ensure it's positive so its diagonal entries are the singular values ***/\n\n  for(Index i = 0; i < m_diagSize; ++i)\n  {\n    // For a complex matrix, some diagonal coefficients might note have been\n    // treated by svd_precondition_2x2_block_to_be_real, and the imaginary part\n    // of some diagonal entry might not be null.\n    if(NumTraits<Scalar>::IsComplex && abs(numext::imag(m_workMatrix.coeff(i,i)))>considerAsZero)\n    {\n      RealScalar a = abs(m_workMatrix.coeff(i,i));\n      m_singularValues.coeffRef(i) = abs(a);\n      if(computeU()) m_matrixU.col(i) *= m_workMatrix.coeff(i,i)/a;\n    }\n    else\n    {\n      // m_workMatrix.coeff(i,i) is already real, no difficulty:\n      RealScalar a = numext::real(m_workMatrix.coeff(i,i));\n      m_singularValues.coeffRef(i) = abs(a);\n      if(computeU() && (a<RealScalar(0))) m_matrixU.col(i) = -m_matrixU.col(i);\n    }\n  }\n  \n  m_singularValues *= scale;\n\n  /*** step 4. Sort singular values in descending order and compute the number of nonzero singular values ***/\n\n  m_nonzeroSingularValues = m_diagSize;\n  for(Index i = 0; i < m_diagSize; i++)\n  {\n    Index pos;\n    RealScalar maxRemainingSingularValue = m_singularValues.tail(m_diagSize-i).maxCoeff(&pos);\n    if(maxRemainingSingularValue == RealScalar(0))\n    {\n      m_nonzeroSingularValues = i;\n      break;\n    }\n    if(pos)\n    {\n      pos += i;\n      std::swap(m_singularValues.coeffRef(i), m_singularValues.coeffRef(pos));\n      if(computeU()) m_matrixU.col(pos).swap(m_matrixU.col(i));\n      if(computeV()) m_matrixV.col(pos).swap(m_matrixV.col(i));\n    }\n  }\n\n  m_isInitialized = true;\n  return *this;\n}\n\n/** \\svd_module\n  *\n  * \\return the singular value decomposition of \\c *this computed by two-sided\n  * Jacobi transformations.\n  *\n  * \\sa class JacobiSVD\n  */\ntemplate<typename Derived>\nJacobiSVD<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::jacobiSvd(unsigned int computationOptions) const\n{\n  return JacobiSVD<PlainObject>(*this, computationOptions);\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_JACOBISVD_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SVD/JacobiSVD_LAPACKE.h",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Eigen bindings to LAPACKe\n *    Singular Value Decomposition - SVD.\n ********************************************************************************\n*/\n\n#ifndef EIGEN_JACOBISVD_LAPACKE_H\n#define EIGEN_JACOBISVD_LAPACKE_H\n\nnamespace Eigen { \n\n/** \\internal Specialization for the data types supported by LAPACKe */\n\n#define EIGEN_LAPACKE_SVD(EIGTYPE, LAPACKE_TYPE, LAPACKE_RTYPE, LAPACKE_PREFIX, EIGCOLROW, LAPACKE_COLROW) \\\ntemplate<> inline \\\nJacobiSVD<Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW, Dynamic, Dynamic>, ColPivHouseholderQRPreconditioner>& \\\nJacobiSVD<Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW, Dynamic, Dynamic>, ColPivHouseholderQRPreconditioner>::compute(const Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW, Dynamic, Dynamic>& matrix, unsigned int computationOptions) \\\n{ \\\n  typedef Matrix<EIGTYPE, Dynamic, Dynamic, EIGCOLROW, Dynamic, Dynamic> MatrixType; \\\n  /*typedef MatrixType::Scalar Scalar;*/ \\\n  /*typedef MatrixType::RealScalar RealScalar;*/ \\\n  allocate(matrix.rows(), matrix.cols(), computationOptions); \\\n\\\n  /*const RealScalar precision = RealScalar(2) * NumTraits<Scalar>::epsilon();*/ \\\n  m_nonzeroSingularValues = m_diagSize; \\\n\\\n  lapack_int lda = internal::convert_index<lapack_int>(matrix.outerStride()), ldu, ldvt; \\\n  lapack_int matrix_order = LAPACKE_COLROW; \\\n  char jobu, jobvt; \\\n  LAPACKE_TYPE *u, *vt, dummy; \\\n  jobu  = (m_computeFullU) ? 'A' : (m_computeThinU) ? 'S' : 'N'; \\\n  jobvt = (m_computeFullV) ? 'A' : (m_computeThinV) ? 'S' : 'N'; \\\n  if (computeU()) { \\\n    ldu  = internal::convert_index<lapack_int>(m_matrixU.outerStride()); \\\n    u    = (LAPACKE_TYPE*)m_matrixU.data(); \\\n  } else { ldu=1; u=&dummy; }\\\n  MatrixType localV; \\\n  lapack_int vt_rows = (m_computeFullV) ? internal::convert_index<lapack_int>(m_cols) : (m_computeThinV) ? internal::convert_index<lapack_int>(m_diagSize) : 1; \\\n  if (computeV()) { \\\n    localV.resize(vt_rows, m_cols); \\\n    ldvt  = internal::convert_index<lapack_int>(localV.outerStride()); \\\n    vt   = (LAPACKE_TYPE*)localV.data(); \\\n  } else { ldvt=1; vt=&dummy; }\\\n  Matrix<LAPACKE_RTYPE, Dynamic, Dynamic> superb; superb.resize(m_diagSize, 1); \\\n  MatrixType m_temp; m_temp = matrix; \\\n  LAPACKE_##LAPACKE_PREFIX##gesvd( matrix_order, jobu, jobvt, internal::convert_index<lapack_int>(m_rows), internal::convert_index<lapack_int>(m_cols), (LAPACKE_TYPE*)m_temp.data(), lda, (LAPACKE_RTYPE*)m_singularValues.data(), u, ldu, vt, ldvt, superb.data()); \\\n  if (computeV()) m_matrixV = localV.adjoint(); \\\n /* for(int i=0;i<m_diagSize;i++) if (m_singularValues.coeffRef(i) < precision) { m_nonzeroSingularValues--; m_singularValues.coeffRef(i)=RealScalar(0);}*/ \\\n  m_isInitialized = true; \\\n  return *this; \\\n}\n\nEIGEN_LAPACKE_SVD(double,   double,                double, d, ColMajor, LAPACK_COL_MAJOR)\nEIGEN_LAPACKE_SVD(float,    float,                 float , s, ColMajor, LAPACK_COL_MAJOR)\nEIGEN_LAPACKE_SVD(dcomplex, lapack_complex_double, double, z, ColMajor, LAPACK_COL_MAJOR)\nEIGEN_LAPACKE_SVD(scomplex, lapack_complex_float,  float , c, ColMajor, LAPACK_COL_MAJOR)\n\nEIGEN_LAPACKE_SVD(double,   double,                double, d, RowMajor, LAPACK_ROW_MAJOR)\nEIGEN_LAPACKE_SVD(float,    float,                 float , s, RowMajor, LAPACK_ROW_MAJOR)\nEIGEN_LAPACKE_SVD(dcomplex, lapack_complex_double, double, z, RowMajor, LAPACK_ROW_MAJOR)\nEIGEN_LAPACKE_SVD(scomplex, lapack_complex_float,  float , c, RowMajor, LAPACK_ROW_MAJOR)\n\n} // end namespace Eigen\n\n#endif // EIGEN_JACOBISVD_LAPACKE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SVD/SVDBase.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// Copyright (C) 2013 Gauthier Brun <brun.gauthier@gmail.com>\n// Copyright (C) 2013 Nicolas Carre <nicolas.carre@ensimag.fr>\n// Copyright (C) 2013 Jean Ceccato <jean.ceccato@ensimag.fr>\n// Copyright (C) 2013 Pierre Zoppitelli <pierre.zoppitelli@ensimag.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SVDBASE_H\n#define EIGEN_SVDBASE_H\n\nnamespace Eigen {\n\nnamespace internal {\ntemplate<typename Derived> struct traits<SVDBase<Derived> >\n : traits<Derived>\n{\n  typedef MatrixXpr XprKind;\n  typedef SolverStorage StorageKind;\n  typedef int StorageIndex;\n  enum { Flags = 0 };\n};\n}\n\n/** \\ingroup SVD_Module\n *\n *\n * \\class SVDBase\n *\n * \\brief Base class of SVD algorithms\n *\n * \\tparam Derived the type of the actual SVD decomposition\n *\n * SVD decomposition consists in decomposing any n-by-p matrix \\a A as a product\n *   \\f[ A = U S V^* \\f]\n * where \\a U is a n-by-n unitary, \\a V is a p-by-p unitary, and \\a S is a n-by-p real positive matrix which is zero outside of its main diagonal;\n * the diagonal entries of S are known as the \\em singular \\em values of \\a A and the columns of \\a U and \\a V are known as the left\n * and right \\em singular \\em vectors of \\a A respectively.\n *\n * Singular values are always sorted in decreasing order.\n *\n * \n * You can ask for only \\em thin \\a U or \\a V to be computed, meaning the following. In case of a rectangular n-by-p matrix, letting \\a m be the\n * smaller value among \\a n and \\a p, there are only \\a m singular vectors; the remaining columns of \\a U and \\a V do not correspond to actual\n * singular vectors. Asking for \\em thin \\a U or \\a V means asking for only their \\a m first columns to be formed. So \\a U is then a n-by-m matrix,\n * and \\a V is then a p-by-m matrix. Notice that thin \\a U and \\a V are all you need for (least squares) solving.\n *  \n * If the input matrix has inf or nan coefficients, the result of the computation is undefined, but the computation is guaranteed to\n * terminate in finite (and reasonable) time.\n * \\sa class BDCSVD, class JacobiSVD\n */\ntemplate<typename Derived> class SVDBase\n : public SolverBase<SVDBase<Derived> >\n{\npublic: \n   \n  template<typename Derived_>\n  friend struct internal::solve_assertion;\n\n  typedef typename internal::traits<Derived>::MatrixType MatrixType;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<typename MatrixType::Scalar>::Real RealScalar;\n  typedef typename Eigen::internal::traits<SVDBase>::StorageIndex StorageIndex;\n  typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n  enum {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n    DiagSizeAtCompileTime = EIGEN_SIZE_MIN_PREFER_DYNAMIC(RowsAtCompileTime,ColsAtCompileTime),\n    MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime,\n    MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime,\n    MaxDiagSizeAtCompileTime = EIGEN_SIZE_MIN_PREFER_FIXED(MaxRowsAtCompileTime,MaxColsAtCompileTime),\n    MatrixOptions = MatrixType::Options\n  };\n\n  typedef Matrix<Scalar, RowsAtCompileTime, RowsAtCompileTime, MatrixOptions, MaxRowsAtCompileTime, MaxRowsAtCompileTime> MatrixUType;\n  typedef Matrix<Scalar, ColsAtCompileTime, ColsAtCompileTime, MatrixOptions, MaxColsAtCompileTime, MaxColsAtCompileTime> MatrixVType;\n  typedef typename internal::plain_diag_type<MatrixType, RealScalar>::type SingularValuesType;\n  \n  Derived& derived() { return *static_cast<Derived*>(this); }\n  const Derived& derived() const { return *static_cast<const Derived*>(this); }\n\n  /** \\returns the \\a U matrix.\n   *\n   * For the SVD decomposition of a n-by-p matrix, letting \\a m be the minimum of \\a n and \\a p,\n   * the U matrix is n-by-n if you asked for \\link Eigen::ComputeFullU ComputeFullU \\endlink, and is n-by-m if you asked for \\link Eigen::ComputeThinU ComputeThinU \\endlink.\n   *\n   * The \\a m first columns of \\a U are the left singular vectors of the matrix being decomposed.\n   *\n   * This method asserts that you asked for \\a U to be computed.\n   */\n  const MatrixUType& matrixU() const\n  {\n    eigen_assert(m_isInitialized && \"SVD is not initialized.\");\n    eigen_assert(computeU() && \"This SVD decomposition didn't compute U. Did you ask for it?\");\n    return m_matrixU;\n  }\n\n  /** \\returns the \\a V matrix.\n   *\n   * For the SVD decomposition of a n-by-p matrix, letting \\a m be the minimum of \\a n and \\a p,\n   * the V matrix is p-by-p if you asked for \\link Eigen::ComputeFullV ComputeFullV \\endlink, and is p-by-m if you asked for \\link Eigen::ComputeThinV ComputeThinV \\endlink.\n   *\n   * The \\a m first columns of \\a V are the right singular vectors of the matrix being decomposed.\n   *\n   * This method asserts that you asked for \\a V to be computed.\n   */\n  const MatrixVType& matrixV() const\n  {\n    eigen_assert(m_isInitialized && \"SVD is not initialized.\");\n    eigen_assert(computeV() && \"This SVD decomposition didn't compute V. Did you ask for it?\");\n    return m_matrixV;\n  }\n\n  /** \\returns the vector of singular values.\n   *\n   * For the SVD decomposition of a n-by-p matrix, letting \\a m be the minimum of \\a n and \\a p, the\n   * returned vector has size \\a m.  Singular values are always sorted in decreasing order.\n   */\n  const SingularValuesType& singularValues() const\n  {\n    eigen_assert(m_isInitialized && \"SVD is not initialized.\");\n    return m_singularValues;\n  }\n\n  /** \\returns the number of singular values that are not exactly 0 */\n  Index nonzeroSingularValues() const\n  {\n    eigen_assert(m_isInitialized && \"SVD is not initialized.\");\n    return m_nonzeroSingularValues;\n  }\n  \n  /** \\returns the rank of the matrix of which \\c *this is the SVD.\n    *\n    * \\note This method has to determine which singular values should be considered nonzero.\n    *       For that, it uses the threshold value that you can control by calling\n    *       setThreshold(const RealScalar&).\n    */\n  inline Index rank() const\n  {\n    using std::abs;\n    eigen_assert(m_isInitialized && \"JacobiSVD is not initialized.\");\n    if(m_singularValues.size()==0) return 0;\n    RealScalar premultiplied_threshold = numext::maxi<RealScalar>(m_singularValues.coeff(0) * threshold(), (std::numeric_limits<RealScalar>::min)());\n    Index i = m_nonzeroSingularValues-1;\n    while(i>=0 && m_singularValues.coeff(i) < premultiplied_threshold) --i;\n    return i+1;\n  }\n  \n  /** Allows to prescribe a threshold to be used by certain methods, such as rank() and solve(),\n    * which need to determine when singular values are to be considered nonzero.\n    * This is not used for the SVD decomposition itself.\n    *\n    * When it needs to get the threshold value, Eigen calls threshold().\n    * The default is \\c NumTraits<Scalar>::epsilon()\n    *\n    * \\param threshold The new value to use as the threshold.\n    *\n    * A singular value will be considered nonzero if its value is strictly greater than\n    *  \\f$ \\vert singular value \\vert \\leqslant threshold \\times \\vert max singular value \\vert \\f$.\n    *\n    * If you want to come back to the default behavior, call setThreshold(Default_t)\n    */\n  Derived& setThreshold(const RealScalar& threshold)\n  {\n    m_usePrescribedThreshold = true;\n    m_prescribedThreshold = threshold;\n    return derived();\n  }\n\n  /** Allows to come back to the default behavior, letting Eigen use its default formula for\n    * determining the threshold.\n    *\n    * You should pass the special object Eigen::Default as parameter here.\n    * \\code svd.setThreshold(Eigen::Default); \\endcode\n    *\n    * See the documentation of setThreshold(const RealScalar&).\n    */\n  Derived& setThreshold(Default_t)\n  {\n    m_usePrescribedThreshold = false;\n    return derived();\n  }\n\n  /** Returns the threshold that will be used by certain methods such as rank().\n    *\n    * See the documentation of setThreshold(const RealScalar&).\n    */\n  RealScalar threshold() const\n  {\n    eigen_assert(m_isInitialized || m_usePrescribedThreshold);\n    // this temporary is needed to workaround a MSVC issue\n    Index diagSize = (std::max<Index>)(1,m_diagSize);\n    return m_usePrescribedThreshold ? m_prescribedThreshold\n                                    : RealScalar(diagSize)*NumTraits<Scalar>::epsilon();\n  }\n\n  /** \\returns true if \\a U (full or thin) is asked for in this SVD decomposition */\n  inline bool computeU() const { return m_computeFullU || m_computeThinU; }\n  /** \\returns true if \\a V (full or thin) is asked for in this SVD decomposition */\n  inline bool computeV() const { return m_computeFullV || m_computeThinV; }\n\n  inline Index rows() const { return m_rows; }\n  inline Index cols() const { return m_cols; }\n  \n  #ifdef EIGEN_PARSED_BY_DOXYGEN\n  /** \\returns a (least squares) solution of \\f$ A x = b \\f$ using the current SVD decomposition of A.\n    *\n    * \\param b the right-hand-side of the equation to solve.\n    *\n    * \\note Solving requires both U and V to be computed. Thin U and V are enough, there is no need for full U or V.\n    *\n    * \\note SVD solving is implicitly least-squares. Thus, this method serves both purposes of exact solving and least-squares solving.\n    * In other words, the returned solution is guaranteed to minimize the Euclidean norm \\f$ \\Vert A x - b \\Vert \\f$.\n    */\n  template<typename Rhs>\n  inline const Solve<Derived, Rhs>\n  solve(const MatrixBase<Rhs>& b) const;\n  #endif\n\n  #ifndef EIGEN_PARSED_BY_DOXYGEN\n  template<typename RhsType, typename DstType>\n  void _solve_impl(const RhsType &rhs, DstType &dst) const;\n\n  template<bool Conjugate, typename RhsType, typename DstType>\n  void _solve_impl_transposed(const RhsType &rhs, DstType &dst) const;\n  #endif\n\nprotected:\n  \n  static void check_template_parameters()\n  {\n    EIGEN_STATIC_ASSERT_NON_INTEGER(Scalar);\n  }\n\n  template<bool Transpose_, typename Rhs>\n  void _check_solve_assertion(const Rhs& b) const {\n      EIGEN_ONLY_USED_FOR_DEBUG(b);\n      eigen_assert(m_isInitialized && \"SVD is not initialized.\");\n      eigen_assert(computeU() && computeV() && \"SVDBase::solve(): Both unitaries U and V are required to be computed (thin unitaries suffice).\");\n      eigen_assert((Transpose_?cols():rows())==b.rows() && \"SVDBase::solve(): invalid number of rows of the right hand side matrix b\");\n  }\n  \n  // return true if already allocated\n  bool allocate(Index rows, Index cols, unsigned int computationOptions) ;\n\n  MatrixUType m_matrixU;\n  MatrixVType m_matrixV;\n  SingularValuesType m_singularValues;\n  bool m_isInitialized, m_isAllocated, m_usePrescribedThreshold;\n  bool m_computeFullU, m_computeThinU;\n  bool m_computeFullV, m_computeThinV;\n  unsigned int m_computationOptions;\n  Index m_nonzeroSingularValues, m_rows, m_cols, m_diagSize;\n  RealScalar m_prescribedThreshold;\n\n  /** \\brief Default Constructor.\n   *\n   * Default constructor of SVDBase\n   */\n  SVDBase()\n    : m_isInitialized(false),\n      m_isAllocated(false),\n      m_usePrescribedThreshold(false),\n      m_computeFullU(false),\n      m_computeThinU(false),\n      m_computeFullV(false),\n      m_computeThinV(false),\n      m_computationOptions(0),\n      m_rows(-1), m_cols(-1), m_diagSize(0)\n  {\n    check_template_parameters();\n  }\n\n\n};\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename Derived>\ntemplate<typename RhsType, typename DstType>\nvoid SVDBase<Derived>::_solve_impl(const RhsType &rhs, DstType &dst) const\n{\n  // A = U S V^*\n  // So A^{-1} = V S^{-1} U^*\n\n  Matrix<typename RhsType::Scalar, Dynamic, RhsType::ColsAtCompileTime, 0, MatrixType::MaxRowsAtCompileTime, RhsType::MaxColsAtCompileTime> tmp;\n  Index l_rank = rank();\n  tmp.noalias() =  m_matrixU.leftCols(l_rank).adjoint() * rhs;\n  tmp = m_singularValues.head(l_rank).asDiagonal().inverse() * tmp;\n  dst = m_matrixV.leftCols(l_rank) * tmp;\n}\n\ntemplate<typename Derived>\ntemplate<bool Conjugate, typename RhsType, typename DstType>\nvoid SVDBase<Derived>::_solve_impl_transposed(const RhsType &rhs, DstType &dst) const\n{\n  // A = U S V^*\n  // So  A^{-*} = U S^{-1} V^*\n  // And A^{-T} = U_conj S^{-1} V^T\n  Matrix<typename RhsType::Scalar, Dynamic, RhsType::ColsAtCompileTime, 0, MatrixType::MaxRowsAtCompileTime, RhsType::MaxColsAtCompileTime> tmp;\n  Index l_rank = rank();\n\n  tmp.noalias() =  m_matrixV.leftCols(l_rank).transpose().template conjugateIf<Conjugate>() * rhs;\n  tmp = m_singularValues.head(l_rank).asDiagonal().inverse() * tmp;\n  dst = m_matrixU.template conjugateIf<!Conjugate>().leftCols(l_rank) * tmp;\n}\n#endif\n\ntemplate<typename MatrixType>\nbool SVDBase<MatrixType>::allocate(Index rows, Index cols, unsigned int computationOptions)\n{\n  eigen_assert(rows >= 0 && cols >= 0);\n\n  if (m_isAllocated &&\n      rows == m_rows &&\n      cols == m_cols &&\n      computationOptions == m_computationOptions)\n  {\n    return true;\n  }\n\n  m_rows = rows;\n  m_cols = cols;\n  m_isInitialized = false;\n  m_isAllocated = true;\n  m_computationOptions = computationOptions;\n  m_computeFullU = (computationOptions & ComputeFullU) != 0;\n  m_computeThinU = (computationOptions & ComputeThinU) != 0;\n  m_computeFullV = (computationOptions & ComputeFullV) != 0;\n  m_computeThinV = (computationOptions & ComputeThinV) != 0;\n  eigen_assert(!(m_computeFullU && m_computeThinU) && \"SVDBase: you can't ask for both full and thin U\");\n  eigen_assert(!(m_computeFullV && m_computeThinV) && \"SVDBase: you can't ask for both full and thin V\");\n  eigen_assert(EIGEN_IMPLIES(m_computeThinU || m_computeThinV, MatrixType::ColsAtCompileTime==Dynamic) &&\n\t       \"SVDBase: thin U and V are only available when your matrix has a dynamic number of columns.\");\n\n  m_diagSize = (std::min)(m_rows, m_cols);\n  m_singularValues.resize(m_diagSize);\n  if(RowsAtCompileTime==Dynamic)\n    m_matrixU.resize(m_rows, m_computeFullU ? m_rows : m_computeThinU ? m_diagSize : 0);\n  if(ColsAtCompileTime==Dynamic)\n    m_matrixV.resize(m_cols, m_computeFullV ? m_cols : m_computeThinV ? m_diagSize : 0);\n\n  return false;\n}\n\n}// end namespace\n\n#endif // EIGEN_SVDBASE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SVD/UpperBidiagonalization.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2013-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BIDIAGONALIZATION_H\n#define EIGEN_BIDIAGONALIZATION_H\n\nnamespace Eigen { \n\nnamespace internal {\n// UpperBidiagonalization will probably be replaced by a Bidiagonalization class, don't want to make it stable API.\n// At the same time, it's useful to keep for now as it's about the only thing that is testing the BandMatrix class.\n\ntemplate<typename _MatrixType> class UpperBidiagonalization\n{\n  public:\n\n    typedef _MatrixType MatrixType;\n    enum {\n      RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      ColsAtCompileTimeMinusOne = internal::decrement_size<ColsAtCompileTime>::ret\n    };\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef Eigen::Index Index; ///< \\deprecated since Eigen 3.3\n    typedef Matrix<Scalar, 1, ColsAtCompileTime> RowVectorType;\n    typedef Matrix<Scalar, RowsAtCompileTime, 1> ColVectorType;\n    typedef BandMatrix<RealScalar, ColsAtCompileTime, ColsAtCompileTime, 1, 0, RowMajor> BidiagonalType;\n    typedef Matrix<Scalar, ColsAtCompileTime, 1> DiagVectorType;\n    typedef Matrix<Scalar, ColsAtCompileTimeMinusOne, 1> SuperDiagVectorType;\n    typedef HouseholderSequence<\n              const MatrixType,\n              const typename internal::remove_all<typename Diagonal<const MatrixType,0>::ConjugateReturnType>::type\n            > HouseholderUSequenceType;\n    typedef HouseholderSequence<\n              const typename internal::remove_all<typename MatrixType::ConjugateReturnType>::type,\n              Diagonal<const MatrixType,1>,\n              OnTheRight\n            > HouseholderVSequenceType;\n    \n    /**\n    * \\brief Default Constructor.\n    *\n    * The default constructor is useful in cases in which the user intends to\n    * perform decompositions via Bidiagonalization::compute(const MatrixType&).\n    */\n    UpperBidiagonalization() : m_householder(), m_bidiagonal(), m_isInitialized(false) {}\n\n    explicit UpperBidiagonalization(const MatrixType& matrix)\n      : m_householder(matrix.rows(), matrix.cols()),\n        m_bidiagonal(matrix.cols(), matrix.cols()),\n        m_isInitialized(false)\n    {\n      compute(matrix);\n    }\n    \n    UpperBidiagonalization& compute(const MatrixType& matrix);\n    UpperBidiagonalization& computeUnblocked(const MatrixType& matrix);\n    \n    const MatrixType& householder() const { return m_householder; }\n    const BidiagonalType& bidiagonal() const { return m_bidiagonal; }\n    \n    const HouseholderUSequenceType householderU() const\n    {\n      eigen_assert(m_isInitialized && \"UpperBidiagonalization is not initialized.\");\n      return HouseholderUSequenceType(m_householder, m_householder.diagonal().conjugate());\n    }\n\n    const HouseholderVSequenceType householderV() // const here gives nasty errors and i'm lazy\n    {\n      eigen_assert(m_isInitialized && \"UpperBidiagonalization is not initialized.\");\n      return HouseholderVSequenceType(m_householder.conjugate(), m_householder.const_derived().template diagonal<1>())\n             .setLength(m_householder.cols()-1)\n             .setShift(1);\n    }\n    \n  protected:\n    MatrixType m_householder;\n    BidiagonalType m_bidiagonal;\n    bool m_isInitialized;\n};\n\n// Standard upper bidiagonalization without fancy optimizations\n// This version should be faster for small matrix size\ntemplate<typename MatrixType>\nvoid upperbidiagonalization_inplace_unblocked(MatrixType& mat,\n                                              typename MatrixType::RealScalar *diagonal,\n                                              typename MatrixType::RealScalar *upper_diagonal,\n                                              typename MatrixType::Scalar* tempData = 0)\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index rows = mat.rows();\n  Index cols = mat.cols();\n\n  typedef Matrix<Scalar,Dynamic,1,ColMajor,MatrixType::MaxRowsAtCompileTime,1> TempType;\n  TempType tempVector;\n  if(tempData==0)\n  {\n    tempVector.resize(rows);\n    tempData = tempVector.data();\n  }\n\n  for (Index k = 0; /* breaks at k==cols-1 below */ ; ++k)\n  {\n    Index remainingRows = rows - k;\n    Index remainingCols = cols - k - 1;\n\n    // construct left householder transform in-place in A\n    mat.col(k).tail(remainingRows)\n       .makeHouseholderInPlace(mat.coeffRef(k,k), diagonal[k]);\n    // apply householder transform to remaining part of A on the left\n    mat.bottomRightCorner(remainingRows, remainingCols)\n       .applyHouseholderOnTheLeft(mat.col(k).tail(remainingRows-1), mat.coeff(k,k), tempData);\n\n    if(k == cols-1) break;\n\n    // construct right householder transform in-place in mat\n    mat.row(k).tail(remainingCols)\n       .makeHouseholderInPlace(mat.coeffRef(k,k+1), upper_diagonal[k]);\n    // apply householder transform to remaining part of mat on the left\n    mat.bottomRightCorner(remainingRows-1, remainingCols)\n       .applyHouseholderOnTheRight(mat.row(k).tail(remainingCols-1).adjoint(), mat.coeff(k,k+1), tempData);\n  }\n}\n\n/** \\internal\n  * Helper routine for the block reduction to upper bidiagonal form.\n  *\n  * Let's partition the matrix A:\n  * \n  *      | A00 A01 |\n  *  A = |         |\n  *      | A10 A11 |\n  *\n  * This function reduces to bidiagonal form the left \\c rows x \\a blockSize vertical panel [A00/A10]\n  * and the \\a blockSize x \\c cols horizontal panel [A00 A01] of the matrix \\a A. The bottom-right block A11\n  * is updated using matrix-matrix products:\n  *   A22 -= V * Y^T - X * U^T\n  * where V and U contains the left and right Householder vectors. U and V are stored in A10, and A01\n  * respectively, and the update matrices X and Y are computed during the reduction.\n  * \n  */\ntemplate<typename MatrixType>\nvoid upperbidiagonalization_blocked_helper(MatrixType& A,\n                                           typename MatrixType::RealScalar *diagonal,\n                                           typename MatrixType::RealScalar *upper_diagonal,\n                                           Index bs,\n                                           Ref<Matrix<typename MatrixType::Scalar, Dynamic, Dynamic,\n                                                      traits<MatrixType>::Flags & RowMajorBit> > X,\n                                           Ref<Matrix<typename MatrixType::Scalar, Dynamic, Dynamic,\n                                                      traits<MatrixType>::Flags & RowMajorBit> > Y)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef typename NumTraits<RealScalar>::Literal Literal;\n  enum { StorageOrder = traits<MatrixType>::Flags & RowMajorBit };\n  typedef InnerStride<int(StorageOrder) == int(ColMajor) ? 1 : Dynamic> ColInnerStride;\n  typedef InnerStride<int(StorageOrder) == int(ColMajor) ? Dynamic : 1> RowInnerStride;\n  typedef Ref<Matrix<Scalar, Dynamic, 1>, 0, ColInnerStride>    SubColumnType;\n  typedef Ref<Matrix<Scalar, 1, Dynamic>, 0, RowInnerStride>    SubRowType;\n  typedef Ref<Matrix<Scalar, Dynamic, Dynamic, StorageOrder > > SubMatType;\n  \n  Index brows = A.rows();\n  Index bcols = A.cols();\n\n  Scalar tau_u, tau_u_prev(0), tau_v;\n\n  for(Index k = 0; k < bs; ++k)\n  {\n    Index remainingRows = brows - k;\n    Index remainingCols = bcols - k - 1;\n\n    SubMatType X_k1( X.block(k,0, remainingRows,k) );\n    SubMatType V_k1( A.block(k,0, remainingRows,k) );\n\n    // 1 - update the k-th column of A\n    SubColumnType v_k = A.col(k).tail(remainingRows);\n          v_k -= V_k1 * Y.row(k).head(k).adjoint();\n    if(k) v_k -= X_k1 * A.col(k).head(k);\n    \n    // 2 - construct left Householder transform in-place\n    v_k.makeHouseholderInPlace(tau_v, diagonal[k]);\n       \n    if(k+1<bcols)\n    {\n      SubMatType Y_k  ( Y.block(k+1,0, remainingCols, k+1) );\n      SubMatType U_k1 ( A.block(0,k+1, k,remainingCols) );\n      \n      // this eases the application of Householder transforAions\n      // A(k,k) will store tau_v later\n      A(k,k) = Scalar(1);\n\n      // 3 - Compute y_k^T = tau_v * ( A^T*v_k - Y_k-1*V_k-1^T*v_k - U_k-1*X_k-1^T*v_k )\n      {\n        SubColumnType y_k( Y.col(k).tail(remainingCols) );\n        \n        // let's use the beginning of column k of Y as a temporary vector\n        SubColumnType tmp( Y.col(k).head(k) );\n        y_k.noalias()  = A.block(k,k+1, remainingRows,remainingCols).adjoint() * v_k; // bottleneck\n        tmp.noalias()  = V_k1.adjoint()  * v_k;\n        y_k.noalias() -= Y_k.leftCols(k) * tmp;\n        tmp.noalias()  = X_k1.adjoint()  * v_k;\n        y_k.noalias() -= U_k1.adjoint()  * tmp;\n        y_k *= numext::conj(tau_v);\n      }\n\n      // 4 - update k-th row of A (it will become u_k)\n      SubRowType u_k( A.row(k).tail(remainingCols) );\n      u_k = u_k.conjugate();\n      {\n        u_k -= Y_k * A.row(k).head(k+1).adjoint();\n        if(k) u_k -= U_k1.adjoint() * X.row(k).head(k).adjoint();\n      }\n\n      // 5 - construct right Householder transform in-place\n      u_k.makeHouseholderInPlace(tau_u, upper_diagonal[k]);\n\n      // this eases the application of Householder transformations\n      // A(k,k+1) will store tau_u later\n      A(k,k+1) = Scalar(1);\n\n      // 6 - Compute x_k = tau_u * ( A*u_k - X_k-1*U_k-1^T*u_k - V_k*Y_k^T*u_k )\n      {\n        SubColumnType x_k ( X.col(k).tail(remainingRows-1) );\n        \n        // let's use the beginning of column k of X as a temporary vectors\n        // note that tmp0 and tmp1 overlaps\n        SubColumnType tmp0 ( X.col(k).head(k) ),\n                      tmp1 ( X.col(k).head(k+1) );\n                    \n        x_k.noalias()   = A.block(k+1,k+1, remainingRows-1,remainingCols) * u_k.transpose(); // bottleneck\n        tmp0.noalias()  = U_k1 * u_k.transpose();\n        x_k.noalias()  -= X_k1.bottomRows(remainingRows-1) * tmp0;\n        tmp1.noalias()  = Y_k.adjoint() * u_k.transpose();\n        x_k.noalias()  -= A.block(k+1,0, remainingRows-1,k+1) * tmp1;\n        x_k *= numext::conj(tau_u);\n        tau_u = numext::conj(tau_u);\n        u_k = u_k.conjugate();\n      }\n\n      if(k>0) A.coeffRef(k-1,k) = tau_u_prev;\n      tau_u_prev = tau_u;\n    }\n    else\n      A.coeffRef(k-1,k) = tau_u_prev;\n\n    A.coeffRef(k,k) = tau_v;\n  }\n  \n  if(bs<bcols)\n    A.coeffRef(bs-1,bs) = tau_u_prev;\n\n  // update A22\n  if(bcols>bs && brows>bs)\n  {\n    SubMatType A11( A.bottomRightCorner(brows-bs,bcols-bs) );\n    SubMatType A10( A.block(bs,0, brows-bs,bs) );\n    SubMatType A01( A.block(0,bs, bs,bcols-bs) );\n    Scalar tmp = A01(bs-1,0);\n    A01(bs-1,0) = Literal(1);\n    A11.noalias() -= A10 * Y.topLeftCorner(bcols,bs).bottomRows(bcols-bs).adjoint();\n    A11.noalias() -= X.topLeftCorner(brows,bs).bottomRows(brows-bs) * A01;\n    A01(bs-1,0) = tmp;\n  }\n}\n\n/** \\internal\n  *\n  * Implementation of a block-bidiagonal reduction.\n  * It is based on the following paper:\n  *   The Design of a Parallel Dense Linear Algebra Software Library: Reduction to Hessenberg, Tridiagonal, and Bidiagonal Form.\n  *   by Jaeyoung Choi, Jack J. Dongarra, David W. Walker. (1995)\n  *   section 3.3\n  */\ntemplate<typename MatrixType, typename BidiagType>\nvoid upperbidiagonalization_inplace_blocked(MatrixType& A, BidiagType& bidiagonal,\n                                            Index maxBlockSize=32,\n                                            typename MatrixType::Scalar* /*tempData*/ = 0)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Block<MatrixType,Dynamic,Dynamic> BlockType;\n\n  Index rows = A.rows();\n  Index cols = A.cols();\n  Index size = (std::min)(rows, cols);\n\n  // X and Y are work space\n  enum { StorageOrder = traits<MatrixType>::Flags & RowMajorBit };\n  Matrix<Scalar,\n         MatrixType::RowsAtCompileTime,\n         Dynamic,\n         StorageOrder,\n         MatrixType::MaxRowsAtCompileTime> X(rows,maxBlockSize);\n  Matrix<Scalar,\n         MatrixType::ColsAtCompileTime,\n         Dynamic,\n         StorageOrder,\n         MatrixType::MaxColsAtCompileTime> Y(cols,maxBlockSize);\n  Index blockSize = (std::min)(maxBlockSize,size);\n\n  Index k = 0;\n  for(k = 0; k < size; k += blockSize)\n  {\n    Index bs = (std::min)(size-k,blockSize);  // actual size of the block\n    Index brows = rows - k;                   // rows of the block\n    Index bcols = cols - k;                   // columns of the block\n\n    // partition the matrix A:\n    // \n    //      | A00 A01 A02 |\n    //      |             |\n    // A  = | A10 A11 A12 |\n    //      |             |\n    //      | A20 A21 A22 |\n    //\n    // where A11 is a bs x bs diagonal block,\n    // and let:\n    //      | A11 A12 |\n    //  B = |         |\n    //      | A21 A22 |\n\n    BlockType B = A.block(k,k,brows,bcols);\n    \n    // This stage performs the bidiagonalization of A11, A21, A12, and updating of A22.\n    // Finally, the algorithm continue on the updated A22.\n    //\n    // However, if B is too small, or A22 empty, then let's use an unblocked strategy\n    if(k+bs==cols || bcols<48) // somewhat arbitrary threshold\n    {\n      upperbidiagonalization_inplace_unblocked(B,\n                                               &(bidiagonal.template diagonal<0>().coeffRef(k)),\n                                               &(bidiagonal.template diagonal<1>().coeffRef(k)),\n                                               X.data()\n                                              );\n      break; // We're done\n    }\n    else\n    {\n      upperbidiagonalization_blocked_helper<BlockType>( B,\n                                                        &(bidiagonal.template diagonal<0>().coeffRef(k)),\n                                                        &(bidiagonal.template diagonal<1>().coeffRef(k)),\n                                                        bs,\n                                                        X.topLeftCorner(brows,bs),\n                                                        Y.topLeftCorner(bcols,bs)\n                                                      );\n    }\n  }\n}\n\ntemplate<typename _MatrixType>\nUpperBidiagonalization<_MatrixType>& UpperBidiagonalization<_MatrixType>::computeUnblocked(const _MatrixType& matrix)\n{\n  Index rows = matrix.rows();\n  Index cols = matrix.cols();\n  EIGEN_ONLY_USED_FOR_DEBUG(cols);\n\n  eigen_assert(rows >= cols && \"UpperBidiagonalization is only for Arices satisfying rows>=cols.\");\n\n  m_householder = matrix;\n\n  ColVectorType temp(rows);\n\n  upperbidiagonalization_inplace_unblocked(m_householder,\n                                           &(m_bidiagonal.template diagonal<0>().coeffRef(0)),\n                                           &(m_bidiagonal.template diagonal<1>().coeffRef(0)),\n                                           temp.data());\n\n  m_isInitialized = true;\n  return *this;\n}\n\ntemplate<typename _MatrixType>\nUpperBidiagonalization<_MatrixType>& UpperBidiagonalization<_MatrixType>::compute(const _MatrixType& matrix)\n{\n  Index rows = matrix.rows();\n  Index cols = matrix.cols();\n  EIGEN_ONLY_USED_FOR_DEBUG(rows);\n  EIGEN_ONLY_USED_FOR_DEBUG(cols);\n\n  eigen_assert(rows >= cols && \"UpperBidiagonalization is only for Arices satisfying rows>=cols.\");\n\n  m_householder = matrix;\n  upperbidiagonalization_inplace_blocked(m_householder, m_bidiagonal);\n            \n  m_isInitialized = true;\n  return *this;\n}\n\n#if 0\n/** \\return the Householder QR decomposition of \\c *this.\n  *\n  * \\sa class Bidiagonalization\n  */\ntemplate<typename Derived>\nconst UpperBidiagonalization<typename MatrixBase<Derived>::PlainObject>\nMatrixBase<Derived>::bidiagonalization() const\n{\n  return UpperBidiagonalization<PlainObject>(eval());\n}\n#endif\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_BIDIAGONALIZATION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCholesky/SimplicialCholesky.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SIMPLICIAL_CHOLESKY_H\n#define EIGEN_SIMPLICIAL_CHOLESKY_H\n\nnamespace Eigen { \n\nenum SimplicialCholeskyMode {\n  SimplicialCholeskyLLT,\n  SimplicialCholeskyLDLT\n};\n\nnamespace internal {\n  template<typename CholMatrixType, typename InputMatrixType>\n  struct simplicial_cholesky_grab_input {\n    typedef CholMatrixType const * ConstCholMatrixPtr;\n    static void run(const InputMatrixType& input, ConstCholMatrixPtr &pmat, CholMatrixType &tmp)\n    {\n      tmp = input;\n      pmat = &tmp;\n    }\n  };\n  \n  template<typename MatrixType>\n  struct simplicial_cholesky_grab_input<MatrixType,MatrixType> {\n    typedef MatrixType const * ConstMatrixPtr;\n    static void run(const MatrixType& input, ConstMatrixPtr &pmat, MatrixType &/*tmp*/)\n    {\n      pmat = &input;\n    }\n  };\n} // end namespace internal\n\n/** \\ingroup SparseCholesky_Module\n  * \\brief A base class for direct sparse Cholesky factorizations\n  *\n  * This is a base class for LL^T and LDL^T Cholesky factorizations of sparse matrices that are\n  * selfadjoint and positive definite. These factorizations allow for solving A.X = B where\n  * X and B can be either dense or sparse.\n  * \n  * In order to reduce the fill-in, a symmetric permutation P is applied prior to the factorization\n  * such that the factorized matrix is P A P^-1.\n  *\n  * \\tparam Derived the type of the derived class, that is the actual factorization type.\n  *\n  */\ntemplate<typename Derived>\nclass SimplicialCholeskyBase : public SparseSolverBase<Derived>\n{\n    typedef SparseSolverBase<Derived> Base;\n    using Base::m_isInitialized;\n    \n  public:\n    typedef typename internal::traits<Derived>::MatrixType MatrixType;\n    typedef typename internal::traits<Derived>::OrderingType OrderingType;\n    enum { UpLo = internal::traits<Derived>::UpLo };\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> CholMatrixType;\n    typedef CholMatrixType const * ConstCholMatrixPtr;\n    typedef Matrix<Scalar,Dynamic,1> VectorType;\n    typedef Matrix<StorageIndex,Dynamic,1> VectorI;\n\n    enum {\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n\n  public:\n    \n    using Base::derived;\n\n    /** Default constructor */\n    SimplicialCholeskyBase()\n      : m_info(Success),\n        m_factorizationIsOk(false),\n        m_analysisIsOk(false),\n        m_shiftOffset(0),\n        m_shiftScale(1)\n    {}\n\n    explicit SimplicialCholeskyBase(const MatrixType& matrix)\n      : m_info(Success),\n        m_factorizationIsOk(false),\n        m_analysisIsOk(false),\n        m_shiftOffset(0),\n        m_shiftScale(1)\n    {\n      derived().compute(matrix);\n    }\n\n    ~SimplicialCholeskyBase()\n    {\n    }\n\n    Derived& derived() { return *static_cast<Derived*>(this); }\n    const Derived& derived() const { return *static_cast<const Derived*>(this); }\n    \n    inline Index cols() const { return m_matrix.cols(); }\n    inline Index rows() const { return m_matrix.rows(); }\n    \n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the matrix.appears to be negative.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_info;\n    }\n    \n    /** \\returns the permutation P\n      * \\sa permutationPinv() */\n    const PermutationMatrix<Dynamic,Dynamic,StorageIndex>& permutationP() const\n    { return m_P; }\n    \n    /** \\returns the inverse P^-1 of the permutation P\n      * \\sa permutationP() */\n    const PermutationMatrix<Dynamic,Dynamic,StorageIndex>& permutationPinv() const\n    { return m_Pinv; }\n\n    /** Sets the shift parameters that will be used to adjust the diagonal coefficients during the numerical factorization.\n      *\n      * During the numerical factorization, the diagonal coefficients are transformed by the following linear model:\\n\n      * \\c d_ii = \\a offset + \\a scale * \\c d_ii\n      *\n      * The default is the identity transformation with \\a offset=0, and \\a scale=1.\n      *\n      * \\returns a reference to \\c *this.\n      */\n    Derived& setShift(const RealScalar& offset, const RealScalar& scale = 1)\n    {\n      m_shiftOffset = offset;\n      m_shiftScale = scale;\n      return derived();\n    }\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n    /** \\internal */\n    template<typename Stream>\n    void dumpMemory(Stream& s)\n    {\n      int total = 0;\n      s << \"  L:        \" << ((total+=(m_matrix.cols()+1) * sizeof(int) + m_matrix.nonZeros()*(sizeof(int)+sizeof(Scalar))) >> 20) << \"Mb\" << \"\\n\";\n      s << \"  diag:     \" << ((total+=m_diag.size() * sizeof(Scalar)) >> 20) << \"Mb\" << \"\\n\";\n      s << \"  tree:     \" << ((total+=m_parent.size() * sizeof(int)) >> 20) << \"Mb\" << \"\\n\";\n      s << \"  nonzeros: \" << ((total+=m_nonZerosPerCol.size() * sizeof(int)) >> 20) << \"Mb\" << \"\\n\";\n      s << \"  perm:     \" << ((total+=m_P.size() * sizeof(int)) >> 20) << \"Mb\" << \"\\n\";\n      s << \"  perm^-1:  \" << ((total+=m_Pinv.size() * sizeof(int)) >> 20) << \"Mb\" << \"\\n\";\n      s << \"  TOTAL:    \" << (total>> 20) << \"Mb\" << \"\\n\";\n    }\n\n    /** \\internal */\n    template<typename Rhs,typename Dest>\n    void _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const\n    {\n      eigen_assert(m_factorizationIsOk && \"The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()\");\n      eigen_assert(m_matrix.rows()==b.rows());\n\n      if(m_info!=Success)\n        return;\n\n      if(m_P.size()>0)\n        dest = m_P * b;\n      else\n        dest = b;\n\n      if(m_matrix.nonZeros()>0) // otherwise L==I\n        derived().matrixL().solveInPlace(dest);\n\n      if(m_diag.size()>0)\n        dest = m_diag.asDiagonal().inverse() * dest;\n\n      if (m_matrix.nonZeros()>0) // otherwise U==I\n        derived().matrixU().solveInPlace(dest);\n\n      if(m_P.size()>0)\n        dest = m_Pinv * dest;\n    }\n    \n    template<typename Rhs,typename Dest>\n    void _solve_impl(const SparseMatrixBase<Rhs> &b, SparseMatrixBase<Dest> &dest) const\n    {\n      internal::solve_sparse_through_dense_panels(derived(), b, dest);\n    }\n\n#endif // EIGEN_PARSED_BY_DOXYGEN\n\n  protected:\n    \n    /** Computes the sparse Cholesky decomposition of \\a matrix */\n    template<bool DoLDLT>\n    void compute(const MatrixType& matrix)\n    {\n      eigen_assert(matrix.rows()==matrix.cols());\n      Index size = matrix.cols();\n      CholMatrixType tmp(size,size);\n      ConstCholMatrixPtr pmat;\n      ordering(matrix, pmat, tmp);\n      analyzePattern_preordered(*pmat, DoLDLT);\n      factorize_preordered<DoLDLT>(*pmat);\n    }\n    \n    template<bool DoLDLT>\n    void factorize(const MatrixType& a)\n    {\n      eigen_assert(a.rows()==a.cols());\n      Index size = a.cols();\n      CholMatrixType tmp(size,size);\n      ConstCholMatrixPtr pmat;\n      \n      if(m_P.size()==0 && (UpLo&Upper)==Upper)\n      {\n        // If there is no ordering, try to directly use the input matrix without any copy\n        internal::simplicial_cholesky_grab_input<CholMatrixType,MatrixType>::run(a, pmat, tmp);\n      }\n      else\n      {\n        tmp.template selfadjointView<Upper>() = a.template selfadjointView<UpLo>().twistedBy(m_P);\n        pmat = &tmp;\n      }\n      \n      factorize_preordered<DoLDLT>(*pmat);\n    }\n\n    template<bool DoLDLT>\n    void factorize_preordered(const CholMatrixType& a);\n\n    void analyzePattern(const MatrixType& a, bool doLDLT)\n    {\n      eigen_assert(a.rows()==a.cols());\n      Index size = a.cols();\n      CholMatrixType tmp(size,size);\n      ConstCholMatrixPtr pmat;\n      ordering(a, pmat, tmp);\n      analyzePattern_preordered(*pmat,doLDLT);\n    }\n    void analyzePattern_preordered(const CholMatrixType& a, bool doLDLT);\n    \n    void ordering(const MatrixType& a, ConstCholMatrixPtr &pmat, CholMatrixType& ap);\n\n    /** keeps off-diagonal entries; drops diagonal entries */\n    struct keep_diag {\n      inline bool operator() (const Index& row, const Index& col, const Scalar&) const\n      {\n        return row!=col;\n      }\n    };\n\n    mutable ComputationInfo m_info;\n    bool m_factorizationIsOk;\n    bool m_analysisIsOk;\n    \n    CholMatrixType m_matrix;\n    VectorType m_diag;                                // the diagonal coefficients (LDLT mode)\n    VectorI m_parent;                                 // elimination tree\n    VectorI m_nonZerosPerCol;\n    PermutationMatrix<Dynamic,Dynamic,StorageIndex> m_P;     // the permutation\n    PermutationMatrix<Dynamic,Dynamic,StorageIndex> m_Pinv;  // the inverse permutation\n\n    RealScalar m_shiftOffset;\n    RealScalar m_shiftScale;\n};\n\ntemplate<typename _MatrixType, int _UpLo = Lower, typename _Ordering = AMDOrdering<typename _MatrixType::StorageIndex> > class SimplicialLLT;\ntemplate<typename _MatrixType, int _UpLo = Lower, typename _Ordering = AMDOrdering<typename _MatrixType::StorageIndex> > class SimplicialLDLT;\ntemplate<typename _MatrixType, int _UpLo = Lower, typename _Ordering = AMDOrdering<typename _MatrixType::StorageIndex> > class SimplicialCholesky;\n\nnamespace internal {\n\ntemplate<typename _MatrixType, int _UpLo, typename _Ordering> struct traits<SimplicialLLT<_MatrixType,_UpLo,_Ordering> >\n{\n  typedef _MatrixType MatrixType;\n  typedef _Ordering OrderingType;\n  enum { UpLo = _UpLo };\n  typedef typename MatrixType::Scalar                         Scalar;\n  typedef typename MatrixType::StorageIndex                   StorageIndex;\n  typedef SparseMatrix<Scalar, ColMajor, StorageIndex>        CholMatrixType;\n  typedef TriangularView<const CholMatrixType, Eigen::Lower>  MatrixL;\n  typedef TriangularView<const typename CholMatrixType::AdjointReturnType, Eigen::Upper>   MatrixU;\n  static inline MatrixL getL(const CholMatrixType& m) { return MatrixL(m); }\n  static inline MatrixU getU(const CholMatrixType& m) { return MatrixU(m.adjoint()); }\n};\n\ntemplate<typename _MatrixType,int _UpLo, typename _Ordering> struct traits<SimplicialLDLT<_MatrixType,_UpLo,_Ordering> >\n{\n  typedef _MatrixType MatrixType;\n  typedef _Ordering OrderingType;\n  enum { UpLo = _UpLo };\n  typedef typename MatrixType::Scalar                             Scalar;\n  typedef typename MatrixType::StorageIndex                       StorageIndex;\n  typedef SparseMatrix<Scalar, ColMajor, StorageIndex>            CholMatrixType;\n  typedef TriangularView<const CholMatrixType, Eigen::UnitLower>  MatrixL;\n  typedef TriangularView<const typename CholMatrixType::AdjointReturnType, Eigen::UnitUpper> MatrixU;\n  static inline MatrixL getL(const CholMatrixType& m) { return MatrixL(m); }\n  static inline MatrixU getU(const CholMatrixType& m) { return MatrixU(m.adjoint()); }\n};\n\ntemplate<typename _MatrixType, int _UpLo, typename _Ordering> struct traits<SimplicialCholesky<_MatrixType,_UpLo,_Ordering> >\n{\n  typedef _MatrixType MatrixType;\n  typedef _Ordering OrderingType;\n  enum { UpLo = _UpLo };\n};\n\n}\n\n/** \\ingroup SparseCholesky_Module\n  * \\class SimplicialLLT\n  * \\brief A direct sparse LLT Cholesky factorizations\n  *\n  * This class provides a LL^T Cholesky factorizations of sparse matrices that are\n  * selfadjoint and positive definite. The factorization allows for solving A.X = B where\n  * X and B can be either dense or sparse.\n  * \n  * In order to reduce the fill-in, a symmetric permutation P is applied prior to the factorization\n  * such that the factorized matrix is P A P^-1.\n  *\n  * \\tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam _UpLo the triangular part that will be used for the computations. It can be Lower\n  *               or Upper. Default is Lower.\n  * \\tparam _Ordering The ordering method to use, either AMDOrdering<> or NaturalOrdering<>. Default is AMDOrdering<>\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa class SimplicialLDLT, class AMDOrdering, class NaturalOrdering\n  */\ntemplate<typename _MatrixType, int _UpLo, typename _Ordering>\n    class SimplicialLLT : public SimplicialCholeskyBase<SimplicialLLT<_MatrixType,_UpLo,_Ordering> >\n{\npublic:\n    typedef _MatrixType MatrixType;\n    enum { UpLo = _UpLo };\n    typedef SimplicialCholeskyBase<SimplicialLLT> Base;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef SparseMatrix<Scalar,ColMajor,Index> CholMatrixType;\n    typedef Matrix<Scalar,Dynamic,1> VectorType;\n    typedef internal::traits<SimplicialLLT> Traits;\n    typedef typename Traits::MatrixL  MatrixL;\n    typedef typename Traits::MatrixU  MatrixU;\npublic:\n    /** Default constructor */\n    SimplicialLLT() : Base() {}\n    /** Constructs and performs the LLT factorization of \\a matrix */\n    explicit SimplicialLLT(const MatrixType& matrix)\n        : Base(matrix) {}\n\n    /** \\returns an expression of the factor L */\n    inline const MatrixL matrixL() const {\n        eigen_assert(Base::m_factorizationIsOk && \"Simplicial LLT not factorized\");\n        return Traits::getL(Base::m_matrix);\n    }\n\n    /** \\returns an expression of the factor U (= L^*) */\n    inline const MatrixU matrixU() const {\n        eigen_assert(Base::m_factorizationIsOk && \"Simplicial LLT not factorized\");\n        return Traits::getU(Base::m_matrix);\n    }\n    \n    /** Computes the sparse Cholesky decomposition of \\a matrix */\n    SimplicialLLT& compute(const MatrixType& matrix)\n    {\n      Base::template compute<false>(matrix);\n      return *this;\n    }\n\n    /** Performs a symbolic decomposition on the sparcity of \\a matrix.\n      *\n      * This function is particularly useful when solving for several problems having the same structure.\n      *\n      * \\sa factorize()\n      */\n    void analyzePattern(const MatrixType& a)\n    {\n      Base::analyzePattern(a, false);\n    }\n\n    /** Performs a numeric decomposition of \\a matrix\n      *\n      * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed.\n      *\n      * \\sa analyzePattern()\n      */\n    void factorize(const MatrixType& a)\n    {\n      Base::template factorize<false>(a);\n    }\n\n    /** \\returns the determinant of the underlying matrix from the current factorization */\n    Scalar determinant() const\n    {\n      Scalar detL = Base::m_matrix.diagonal().prod();\n      return numext::abs2(detL);\n    }\n};\n\n/** \\ingroup SparseCholesky_Module\n  * \\class SimplicialLDLT\n  * \\brief A direct sparse LDLT Cholesky factorizations without square root.\n  *\n  * This class provides a LDL^T Cholesky factorizations without square root of sparse matrices that are\n  * selfadjoint and positive definite. The factorization allows for solving A.X = B where\n  * X and B can be either dense or sparse.\n  * \n  * In order to reduce the fill-in, a symmetric permutation P is applied prior to the factorization\n  * such that the factorized matrix is P A P^-1.\n  *\n  * \\tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>\n  * \\tparam _UpLo the triangular part that will be used for the computations. It can be Lower\n  *               or Upper. Default is Lower.\n  * \\tparam _Ordering The ordering method to use, either AMDOrdering<> or NaturalOrdering<>. Default is AMDOrdering<>\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa class SimplicialLLT, class AMDOrdering, class NaturalOrdering\n  */\ntemplate<typename _MatrixType, int _UpLo, typename _Ordering>\n    class SimplicialLDLT : public SimplicialCholeskyBase<SimplicialLDLT<_MatrixType,_UpLo,_Ordering> >\n{\npublic:\n    typedef _MatrixType MatrixType;\n    enum { UpLo = _UpLo };\n    typedef SimplicialCholeskyBase<SimplicialLDLT> Base;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> CholMatrixType;\n    typedef Matrix<Scalar,Dynamic,1> VectorType;\n    typedef internal::traits<SimplicialLDLT> Traits;\n    typedef typename Traits::MatrixL  MatrixL;\n    typedef typename Traits::MatrixU  MatrixU;\npublic:\n    /** Default constructor */\n    SimplicialLDLT() : Base() {}\n\n    /** Constructs and performs the LLT factorization of \\a matrix */\n    explicit SimplicialLDLT(const MatrixType& matrix)\n        : Base(matrix) {}\n\n    /** \\returns a vector expression of the diagonal D */\n    inline const VectorType vectorD() const {\n        eigen_assert(Base::m_factorizationIsOk && \"Simplicial LDLT not factorized\");\n        return Base::m_diag;\n    }\n    /** \\returns an expression of the factor L */\n    inline const MatrixL matrixL() const {\n        eigen_assert(Base::m_factorizationIsOk && \"Simplicial LDLT not factorized\");\n        return Traits::getL(Base::m_matrix);\n    }\n\n    /** \\returns an expression of the factor U (= L^*) */\n    inline const MatrixU matrixU() const {\n        eigen_assert(Base::m_factorizationIsOk && \"Simplicial LDLT not factorized\");\n        return Traits::getU(Base::m_matrix);\n    }\n\n    /** Computes the sparse Cholesky decomposition of \\a matrix */\n    SimplicialLDLT& compute(const MatrixType& matrix)\n    {\n      Base::template compute<true>(matrix);\n      return *this;\n    }\n    \n    /** Performs a symbolic decomposition on the sparcity of \\a matrix.\n      *\n      * This function is particularly useful when solving for several problems having the same structure.\n      *\n      * \\sa factorize()\n      */\n    void analyzePattern(const MatrixType& a)\n    {\n      Base::analyzePattern(a, true);\n    }\n\n    /** Performs a numeric decomposition of \\a matrix\n      *\n      * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed.\n      *\n      * \\sa analyzePattern()\n      */\n    void factorize(const MatrixType& a)\n    {\n      Base::template factorize<true>(a);\n    }\n\n    /** \\returns the determinant of the underlying matrix from the current factorization */\n    Scalar determinant() const\n    {\n      return Base::m_diag.prod();\n    }\n};\n\n/** \\deprecated use SimplicialLDLT or class SimplicialLLT\n  * \\ingroup SparseCholesky_Module\n  * \\class SimplicialCholesky\n  *\n  * \\sa class SimplicialLDLT, class SimplicialLLT\n  */\ntemplate<typename _MatrixType, int _UpLo, typename _Ordering>\n    class SimplicialCholesky : public SimplicialCholeskyBase<SimplicialCholesky<_MatrixType,_UpLo,_Ordering> >\n{\npublic:\n    typedef _MatrixType MatrixType;\n    enum { UpLo = _UpLo };\n    typedef SimplicialCholeskyBase<SimplicialCholesky> Base;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> CholMatrixType;\n    typedef Matrix<Scalar,Dynamic,1> VectorType;\n    typedef internal::traits<SimplicialCholesky> Traits;\n    typedef internal::traits<SimplicialLDLT<MatrixType,UpLo> > LDLTTraits;\n    typedef internal::traits<SimplicialLLT<MatrixType,UpLo>  > LLTTraits;\n  public:\n    SimplicialCholesky() : Base(), m_LDLT(true) {}\n\n    explicit SimplicialCholesky(const MatrixType& matrix)\n      : Base(), m_LDLT(true)\n    {\n      compute(matrix);\n    }\n\n    SimplicialCholesky& setMode(SimplicialCholeskyMode mode)\n    {\n      switch(mode)\n      {\n      case SimplicialCholeskyLLT:\n        m_LDLT = false;\n        break;\n      case SimplicialCholeskyLDLT:\n        m_LDLT = true;\n        break;\n      default:\n        break;\n      }\n\n      return *this;\n    }\n\n    inline const VectorType vectorD() const {\n        eigen_assert(Base::m_factorizationIsOk && \"Simplicial Cholesky not factorized\");\n        return Base::m_diag;\n    }\n    inline const CholMatrixType rawMatrix() const {\n        eigen_assert(Base::m_factorizationIsOk && \"Simplicial Cholesky not factorized\");\n        return Base::m_matrix;\n    }\n    \n    /** Computes the sparse Cholesky decomposition of \\a matrix */\n    SimplicialCholesky& compute(const MatrixType& matrix)\n    {\n      if(m_LDLT)\n        Base::template compute<true>(matrix);\n      else\n        Base::template compute<false>(matrix);\n      return *this;\n    }\n\n    /** Performs a symbolic decomposition on the sparcity of \\a matrix.\n      *\n      * This function is particularly useful when solving for several problems having the same structure.\n      *\n      * \\sa factorize()\n      */\n    void analyzePattern(const MatrixType& a)\n    {\n      Base::analyzePattern(a, m_LDLT);\n    }\n\n    /** Performs a numeric decomposition of \\a matrix\n      *\n      * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed.\n      *\n      * \\sa analyzePattern()\n      */\n    void factorize(const MatrixType& a)\n    {\n      if(m_LDLT)\n        Base::template factorize<true>(a);\n      else\n        Base::template factorize<false>(a);\n    }\n\n    /** \\internal */\n    template<typename Rhs,typename Dest>\n    void _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const\n    {\n      eigen_assert(Base::m_factorizationIsOk && \"The decomposition is not in a valid state for solving, you must first call either compute() or symbolic()/numeric()\");\n      eigen_assert(Base::m_matrix.rows()==b.rows());\n\n      if(Base::m_info!=Success)\n        return;\n\n      if(Base::m_P.size()>0)\n        dest = Base::m_P * b;\n      else\n        dest = b;\n\n      if(Base::m_matrix.nonZeros()>0) // otherwise L==I\n      {\n        if(m_LDLT)\n          LDLTTraits::getL(Base::m_matrix).solveInPlace(dest);\n        else\n          LLTTraits::getL(Base::m_matrix).solveInPlace(dest);\n      }\n\n      if(Base::m_diag.size()>0)\n        dest = Base::m_diag.real().asDiagonal().inverse() * dest;\n\n      if (Base::m_matrix.nonZeros()>0) // otherwise I==I\n      {\n        if(m_LDLT)\n          LDLTTraits::getU(Base::m_matrix).solveInPlace(dest);\n        else\n          LLTTraits::getU(Base::m_matrix).solveInPlace(dest);\n      }\n\n      if(Base::m_P.size()>0)\n        dest = Base::m_Pinv * dest;\n    }\n    \n    /** \\internal */\n    template<typename Rhs,typename Dest>\n    void _solve_impl(const SparseMatrixBase<Rhs> &b, SparseMatrixBase<Dest> &dest) const\n    {\n      internal::solve_sparse_through_dense_panels(*this, b, dest);\n    }\n    \n    Scalar determinant() const\n    {\n      if(m_LDLT)\n      {\n        return Base::m_diag.prod();\n      }\n      else\n      {\n        Scalar detL = Diagonal<const CholMatrixType>(Base::m_matrix).prod();\n        return numext::abs2(detL);\n      }\n    }\n    \n  protected:\n    bool m_LDLT;\n};\n\ntemplate<typename Derived>\nvoid SimplicialCholeskyBase<Derived>::ordering(const MatrixType& a, ConstCholMatrixPtr &pmat, CholMatrixType& ap)\n{\n  eigen_assert(a.rows()==a.cols());\n  const Index size = a.rows();\n  pmat = &ap;\n  // Note that ordering methods compute the inverse permutation\n  if(!internal::is_same<OrderingType,NaturalOrdering<Index> >::value)\n  {\n    {\n      CholMatrixType C;\n      C = a.template selfadjointView<UpLo>();\n      \n      OrderingType ordering;\n      ordering(C,m_Pinv);\n    }\n\n    if(m_Pinv.size()>0) m_P = m_Pinv.inverse();\n    else                m_P.resize(0);\n    \n    ap.resize(size,size);\n    ap.template selfadjointView<Upper>() = a.template selfadjointView<UpLo>().twistedBy(m_P);\n  }\n  else\n  {\n    m_Pinv.resize(0);\n    m_P.resize(0);\n    if(int(UpLo)==int(Lower) || MatrixType::IsRowMajor)\n    {\n      // we have to transpose the lower part to to the upper one\n      ap.resize(size,size);\n      ap.template selfadjointView<Upper>() = a.template selfadjointView<UpLo>();\n    }\n    else\n      internal::simplicial_cholesky_grab_input<CholMatrixType,MatrixType>::run(a, pmat, ap);\n  }  \n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SIMPLICIAL_CHOLESKY_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCholesky/SimplicialCholesky_impl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/*\nNOTE: these functions have been adapted from the LDL library:\n\nLDL Copyright (c) 2005 by Timothy A. Davis.  All Rights Reserved.\n\nThe author of LDL, Timothy A. Davis., has executed a license with Google LLC\nto permit distribution of this code and derivative works as part of Eigen under\nthe Mozilla Public License v. 2.0, as stated at the top of this file.\n */\n\n#ifndef EIGEN_SIMPLICIAL_CHOLESKY_IMPL_H\n#define EIGEN_SIMPLICIAL_CHOLESKY_IMPL_H\n\nnamespace Eigen {\n\ntemplate<typename Derived>\nvoid SimplicialCholeskyBase<Derived>::analyzePattern_preordered(const CholMatrixType& ap, bool doLDLT)\n{\n  const StorageIndex size = StorageIndex(ap.rows());\n  m_matrix.resize(size, size);\n  m_parent.resize(size);\n  m_nonZerosPerCol.resize(size);\n\n  ei_declare_aligned_stack_constructed_variable(StorageIndex, tags, size, 0);\n\n  for(StorageIndex k = 0; k < size; ++k)\n  {\n    /* L(k,:) pattern: all nodes reachable in etree from nz in A(0:k-1,k) */\n    m_parent[k] = -1;             /* parent of k is not yet known */\n    tags[k] = k;                  /* mark node k as visited */\n    m_nonZerosPerCol[k] = 0;      /* count of nonzeros in column k of L */\n    for(typename CholMatrixType::InnerIterator it(ap,k); it; ++it)\n    {\n      StorageIndex i = it.index();\n      if(i < k)\n      {\n        /* follow path from i to root of etree, stop at flagged node */\n        for(; tags[i] != k; i = m_parent[i])\n        {\n          /* find parent of i if not yet determined */\n          if (m_parent[i] == -1)\n            m_parent[i] = k;\n          m_nonZerosPerCol[i]++;        /* L (k,i) is nonzero */\n          tags[i] = k;                  /* mark i as visited */\n        }\n      }\n    }\n  }\n\n  /* construct Lp index array from m_nonZerosPerCol column counts */\n  StorageIndex* Lp = m_matrix.outerIndexPtr();\n  Lp[0] = 0;\n  for(StorageIndex k = 0; k < size; ++k)\n    Lp[k+1] = Lp[k] + m_nonZerosPerCol[k] + (doLDLT ? 0 : 1);\n\n  m_matrix.resizeNonZeros(Lp[size]);\n\n  m_isInitialized     = true;\n  m_info              = Success;\n  m_analysisIsOk      = true;\n  m_factorizationIsOk = false;\n}\n\n\ntemplate<typename Derived>\ntemplate<bool DoLDLT>\nvoid SimplicialCholeskyBase<Derived>::factorize_preordered(const CholMatrixType& ap)\n{\n  using std::sqrt;\n\n  eigen_assert(m_analysisIsOk && \"You must first call analyzePattern()\");\n  eigen_assert(ap.rows()==ap.cols());\n  eigen_assert(m_parent.size()==ap.rows());\n  eigen_assert(m_nonZerosPerCol.size()==ap.rows());\n\n  const StorageIndex size = StorageIndex(ap.rows());\n  const StorageIndex* Lp = m_matrix.outerIndexPtr();\n  StorageIndex* Li = m_matrix.innerIndexPtr();\n  Scalar* Lx = m_matrix.valuePtr();\n\n  ei_declare_aligned_stack_constructed_variable(Scalar, y, size, 0);\n  ei_declare_aligned_stack_constructed_variable(StorageIndex,  pattern, size, 0);\n  ei_declare_aligned_stack_constructed_variable(StorageIndex,  tags, size, 0);\n\n  bool ok = true;\n  m_diag.resize(DoLDLT ? size : 0);\n\n  for(StorageIndex k = 0; k < size; ++k)\n  {\n    // compute nonzero pattern of kth row of L, in topological order\n    y[k] = Scalar(0);                     // Y(0:k) is now all zero\n    StorageIndex top = size;               // stack for pattern is empty\n    tags[k] = k;                    // mark node k as visited\n    m_nonZerosPerCol[k] = 0;        // count of nonzeros in column k of L\n    for(typename CholMatrixType::InnerIterator it(ap,k); it; ++it)\n    {\n      StorageIndex i = it.index();\n      if(i <= k)\n      {\n        y[i] += numext::conj(it.value());            /* scatter A(i,k) into Y (sum duplicates) */\n        Index len;\n        for(len = 0; tags[i] != k; i = m_parent[i])\n        {\n          pattern[len++] = i;     /* L(k,i) is nonzero */\n          tags[i] = k;            /* mark i as visited */\n        }\n        while(len > 0)\n          pattern[--top] = pattern[--len];\n      }\n    }\n\n    /* compute numerical values kth row of L (a sparse triangular solve) */\n\n    RealScalar d = numext::real(y[k]) * m_shiftScale + m_shiftOffset;    // get D(k,k), apply the shift function, and clear Y(k)\n    y[k] = Scalar(0);\n    for(; top < size; ++top)\n    {\n      Index i = pattern[top];       /* pattern[top:n-1] is pattern of L(:,k) */\n      Scalar yi = y[i];             /* get and clear Y(i) */\n      y[i] = Scalar(0);\n\n      /* the nonzero entry L(k,i) */\n      Scalar l_ki;\n      if(DoLDLT)\n        l_ki = yi / numext::real(m_diag[i]);\n      else\n        yi = l_ki = yi / Lx[Lp[i]];\n\n      Index p2 = Lp[i] + m_nonZerosPerCol[i];\n      Index p;\n      for(p = Lp[i] + (DoLDLT ? 0 : 1); p < p2; ++p)\n        y[Li[p]] -= numext::conj(Lx[p]) * yi;\n      d -= numext::real(l_ki * numext::conj(yi));\n      Li[p] = k;                          /* store L(k,i) in column form of L */\n      Lx[p] = l_ki;\n      ++m_nonZerosPerCol[i];              /* increment count of nonzeros in col i */\n    }\n    if(DoLDLT)\n    {\n      m_diag[k] = d;\n      if(d == RealScalar(0))\n      {\n        ok = false;                         /* failure, D(k,k) is zero */\n        break;\n      }\n    }\n    else\n    {\n      Index p = Lp[k] + m_nonZerosPerCol[k]++;\n      Li[p] = k ;                /* store L(k,k) = sqrt (d) in column k */\n      if(d <= RealScalar(0)) {\n        ok = false;              /* failure, matrix is not positive definite */\n        break;\n      }\n      Lx[p] = sqrt(d) ;\n    }\n  }\n\n  m_info = ok ? Success : NumericalIssue;\n  m_factorizationIsOk = true;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SIMPLICIAL_CHOLESKY_IMPL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/AmbiVector.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_AMBIVECTOR_H\n#define EIGEN_AMBIVECTOR_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\internal\n  * Hybrid sparse/dense vector class designed for intensive read-write operations.\n  *\n  * See BasicSparseLLT and SparseProduct for usage examples.\n  */\ntemplate<typename _Scalar, typename _StorageIndex>\nclass AmbiVector\n{\n  public:\n    typedef _Scalar Scalar;\n    typedef _StorageIndex StorageIndex;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n\n    explicit AmbiVector(Index size)\n      : m_buffer(0), m_zero(0), m_size(0), m_end(0), m_allocatedSize(0), m_allocatedElements(0), m_mode(-1)\n    {\n      resize(size);\n    }\n\n    void init(double estimatedDensity);\n    void init(int mode);\n\n    Index nonZeros() const;\n\n    /** Specifies a sub-vector to work on */\n    void setBounds(Index start, Index end) { m_start = convert_index(start); m_end = convert_index(end); }\n\n    void setZero();\n\n    void restart();\n    Scalar& coeffRef(Index i);\n    Scalar& coeff(Index i);\n\n    class Iterator;\n\n    ~AmbiVector() { delete[] m_buffer; }\n\n    void resize(Index size)\n    {\n      if (m_allocatedSize < size)\n        reallocate(size);\n      m_size = convert_index(size);\n    }\n\n    StorageIndex size() const { return m_size; }\n\n  protected:\n    StorageIndex convert_index(Index idx)\n    {\n      return internal::convert_index<StorageIndex>(idx);\n    }\n\n    void reallocate(Index size)\n    {\n      // if the size of the matrix is not too large, let's allocate a bit more than needed such\n      // that we can handle dense vector even in sparse mode.\n      delete[] m_buffer;\n      if (size<1000)\n      {\n        Index allocSize = (size * sizeof(ListEl) + sizeof(Scalar) - 1)/sizeof(Scalar);\n        m_allocatedElements = convert_index((allocSize*sizeof(Scalar))/sizeof(ListEl));\n        m_buffer = new Scalar[allocSize];\n      }\n      else\n      {\n        m_allocatedElements = convert_index((size*sizeof(Scalar))/sizeof(ListEl));\n        m_buffer = new Scalar[size];\n      }\n      m_size = convert_index(size);\n      m_start = 0;\n      m_end = m_size;\n    }\n\n    void reallocateSparse()\n    {\n      Index copyElements = m_allocatedElements;\n      m_allocatedElements = (std::min)(StorageIndex(m_allocatedElements*1.5),m_size);\n      Index allocSize = m_allocatedElements * sizeof(ListEl);\n      allocSize = (allocSize + sizeof(Scalar) - 1)/sizeof(Scalar);\n      Scalar* newBuffer = new Scalar[allocSize];\n      std::memcpy(newBuffer,  m_buffer,  copyElements * sizeof(ListEl));\n      delete[] m_buffer;\n      m_buffer = newBuffer;\n    }\n\n  protected:\n    // element type of the linked list\n    struct ListEl\n    {\n      StorageIndex next;\n      StorageIndex index;\n      Scalar value;\n    };\n\n    // used to store data in both mode\n    Scalar* m_buffer;\n    Scalar m_zero;\n    StorageIndex m_size;\n    StorageIndex m_start;\n    StorageIndex m_end;\n    StorageIndex m_allocatedSize;\n    StorageIndex m_allocatedElements;\n    StorageIndex m_mode;\n\n    // linked list mode\n    StorageIndex m_llStart;\n    StorageIndex m_llCurrent;\n    StorageIndex m_llSize;\n};\n\n/** \\returns the number of non zeros in the current sub vector */\ntemplate<typename _Scalar,typename _StorageIndex>\nIndex AmbiVector<_Scalar,_StorageIndex>::nonZeros() const\n{\n  if (m_mode==IsSparse)\n    return m_llSize;\n  else\n    return m_end - m_start;\n}\n\ntemplate<typename _Scalar,typename _StorageIndex>\nvoid AmbiVector<_Scalar,_StorageIndex>::init(double estimatedDensity)\n{\n  if (estimatedDensity>0.1)\n    init(IsDense);\n  else\n    init(IsSparse);\n}\n\ntemplate<typename _Scalar,typename _StorageIndex>\nvoid AmbiVector<_Scalar,_StorageIndex>::init(int mode)\n{\n  m_mode = mode;\n  // This is only necessary in sparse mode, but we set these unconditionally to avoid some maybe-uninitialized warnings\n  // if (m_mode==IsSparse)\n  {\n    m_llSize = 0;\n    m_llStart = -1;\n  }\n}\n\n/** Must be called whenever we might perform a write access\n  * with an index smaller than the previous one.\n  *\n  * Don't worry, this function is extremely cheap.\n  */\ntemplate<typename _Scalar,typename _StorageIndex>\nvoid AmbiVector<_Scalar,_StorageIndex>::restart()\n{\n  m_llCurrent = m_llStart;\n}\n\n/** Set all coefficients of current subvector to zero */\ntemplate<typename _Scalar,typename _StorageIndex>\nvoid AmbiVector<_Scalar,_StorageIndex>::setZero()\n{\n  if (m_mode==IsDense)\n  {\n    for (Index i=m_start; i<m_end; ++i)\n      m_buffer[i] = Scalar(0);\n  }\n  else\n  {\n    eigen_assert(m_mode==IsSparse);\n    m_llSize = 0;\n    m_llStart = -1;\n  }\n}\n\ntemplate<typename _Scalar,typename _StorageIndex>\n_Scalar& AmbiVector<_Scalar,_StorageIndex>::coeffRef(Index i)\n{\n  if (m_mode==IsDense)\n    return m_buffer[i];\n  else\n  {\n    ListEl* EIGEN_RESTRICT llElements = reinterpret_cast<ListEl*>(m_buffer);\n    // TODO factorize the following code to reduce code generation\n    eigen_assert(m_mode==IsSparse);\n    if (m_llSize==0)\n    {\n      // this is the first element\n      m_llStart = 0;\n      m_llCurrent = 0;\n      ++m_llSize;\n      llElements[0].value = Scalar(0);\n      llElements[0].index = convert_index(i);\n      llElements[0].next = -1;\n      return llElements[0].value;\n    }\n    else if (i<llElements[m_llStart].index)\n    {\n      // this is going to be the new first element of the list\n      ListEl& el = llElements[m_llSize];\n      el.value = Scalar(0);\n      el.index = convert_index(i);\n      el.next = m_llStart;\n      m_llStart = m_llSize;\n      ++m_llSize;\n      m_llCurrent = m_llStart;\n      return el.value;\n    }\n    else\n    {\n      StorageIndex nextel = llElements[m_llCurrent].next;\n      eigen_assert(i>=llElements[m_llCurrent].index && \"you must call restart() before inserting an element with lower or equal index\");\n      while (nextel >= 0 && llElements[nextel].index<=i)\n      {\n        m_llCurrent = nextel;\n        nextel = llElements[nextel].next;\n      }\n\n      if (llElements[m_llCurrent].index==i)\n      {\n        // the coefficient already exists and we found it !\n        return llElements[m_llCurrent].value;\n      }\n      else\n      {\n        if (m_llSize>=m_allocatedElements)\n        {\n          reallocateSparse();\n          llElements = reinterpret_cast<ListEl*>(m_buffer);\n        }\n        eigen_internal_assert(m_llSize<m_allocatedElements && \"internal error: overflow in sparse mode\");\n        // let's insert a new coefficient\n        ListEl& el = llElements[m_llSize];\n        el.value = Scalar(0);\n        el.index = convert_index(i);\n        el.next = llElements[m_llCurrent].next;\n        llElements[m_llCurrent].next = m_llSize;\n        ++m_llSize;\n        return el.value;\n      }\n    }\n  }\n}\n\ntemplate<typename _Scalar,typename _StorageIndex>\n_Scalar& AmbiVector<_Scalar,_StorageIndex>::coeff(Index i)\n{\n  if (m_mode==IsDense)\n    return m_buffer[i];\n  else\n  {\n    ListEl* EIGEN_RESTRICT llElements = reinterpret_cast<ListEl*>(m_buffer);\n    eigen_assert(m_mode==IsSparse);\n    if ((m_llSize==0) || (i<llElements[m_llStart].index))\n    {\n      return m_zero;\n    }\n    else\n    {\n      Index elid = m_llStart;\n      while (elid >= 0 && llElements[elid].index<i)\n        elid = llElements[elid].next;\n\n      if (llElements[elid].index==i)\n        return llElements[m_llCurrent].value;\n      else\n        return m_zero;\n    }\n  }\n}\n\n/** Iterator over the nonzero coefficients */\ntemplate<typename _Scalar,typename _StorageIndex>\nclass AmbiVector<_Scalar,_StorageIndex>::Iterator\n{\n  public:\n    typedef _Scalar Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n\n    /** Default constructor\n      * \\param vec the vector on which we iterate\n      * \\param epsilon the minimal value used to prune zero coefficients.\n      * In practice, all coefficients having a magnitude smaller than \\a epsilon\n      * are skipped.\n      */\n    explicit Iterator(const AmbiVector& vec, const RealScalar& epsilon = 0)\n      : m_vector(vec)\n    {\n      using std::abs;\n      m_epsilon = epsilon;\n      m_isDense = m_vector.m_mode==IsDense;\n      if (m_isDense)\n      {\n        m_currentEl = 0;   // this is to avoid a compilation warning\n        m_cachedValue = 0; // this is to avoid a compilation warning\n        m_cachedIndex = m_vector.m_start-1;\n        ++(*this);\n      }\n      else\n      {\n        ListEl* EIGEN_RESTRICT llElements = reinterpret_cast<ListEl*>(m_vector.m_buffer);\n        m_currentEl = m_vector.m_llStart;\n        while (m_currentEl>=0 && abs(llElements[m_currentEl].value)<=m_epsilon)\n          m_currentEl = llElements[m_currentEl].next;\n        if (m_currentEl<0)\n        {\n          m_cachedValue = 0; // this is to avoid a compilation warning\n          m_cachedIndex = -1;\n        }\n        else\n        {\n          m_cachedIndex = llElements[m_currentEl].index;\n          m_cachedValue = llElements[m_currentEl].value;\n        }\n      }\n    }\n\n    StorageIndex index() const { return m_cachedIndex; }\n    Scalar value() const { return m_cachedValue; }\n\n    operator bool() const { return m_cachedIndex>=0; }\n\n    Iterator& operator++()\n    {\n      using std::abs;\n      if (m_isDense)\n      {\n        do {\n          ++m_cachedIndex;\n        } while (m_cachedIndex<m_vector.m_end && abs(m_vector.m_buffer[m_cachedIndex])<=m_epsilon);\n        if (m_cachedIndex<m_vector.m_end)\n          m_cachedValue = m_vector.m_buffer[m_cachedIndex];\n        else\n          m_cachedIndex=-1;\n      }\n      else\n      {\n        ListEl* EIGEN_RESTRICT llElements = reinterpret_cast<ListEl*>(m_vector.m_buffer);\n        do {\n          m_currentEl = llElements[m_currentEl].next;\n        } while (m_currentEl>=0 && abs(llElements[m_currentEl].value)<=m_epsilon);\n        if (m_currentEl<0)\n        {\n          m_cachedIndex = -1;\n        }\n        else\n        {\n          m_cachedIndex = llElements[m_currentEl].index;\n          m_cachedValue = llElements[m_currentEl].value;\n        }\n      }\n      return *this;\n    }\n\n  protected:\n    const AmbiVector& m_vector; // the target vector\n    StorageIndex m_currentEl;   // the current element in sparse/linked-list mode\n    RealScalar m_epsilon;       // epsilon used to prune zero coefficients\n    StorageIndex m_cachedIndex; // current coordinate\n    Scalar m_cachedValue;       // current value\n    bool m_isDense;             // mode of the vector\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_AMBIVECTOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/CompressedStorage.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_COMPRESSED_STORAGE_H\n#define EIGEN_COMPRESSED_STORAGE_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\internal\n  * Stores a sparse set of values as a list of values and a list of indices.\n  *\n  */\ntemplate<typename _Scalar,typename _StorageIndex>\nclass CompressedStorage\n{\n  public:\n\n    typedef _Scalar Scalar;\n    typedef _StorageIndex StorageIndex;\n\n  protected:\n\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  public:\n\n    CompressedStorage()\n      : m_values(0), m_indices(0), m_size(0), m_allocatedSize(0)\n    {}\n\n    explicit CompressedStorage(Index size)\n      : m_values(0), m_indices(0), m_size(0), m_allocatedSize(0)\n    {\n      resize(size);\n    }\n\n    CompressedStorage(const CompressedStorage& other)\n      : m_values(0), m_indices(0), m_size(0), m_allocatedSize(0)\n    {\n      *this = other;\n    }\n\n    CompressedStorage& operator=(const CompressedStorage& other)\n    {\n      resize(other.size());\n      if(other.size()>0)\n      {\n        internal::smart_copy(other.m_values,  other.m_values  + m_size, m_values);\n        internal::smart_copy(other.m_indices, other.m_indices + m_size, m_indices);\n      }\n      return *this;\n    }\n\n    void swap(CompressedStorage& other)\n    {\n      std::swap(m_values, other.m_values);\n      std::swap(m_indices, other.m_indices);\n      std::swap(m_size, other.m_size);\n      std::swap(m_allocatedSize, other.m_allocatedSize);\n    }\n\n    ~CompressedStorage()\n    {\n      delete[] m_values;\n      delete[] m_indices;\n    }\n\n    void reserve(Index size)\n    {\n      Index newAllocatedSize = m_size + size;\n      if (newAllocatedSize > m_allocatedSize)\n        reallocate(newAllocatedSize);\n    }\n\n    void squeeze()\n    {\n      if (m_allocatedSize>m_size)\n        reallocate(m_size);\n    }\n\n    void resize(Index size, double reserveSizeFactor = 0)\n    {\n      if (m_allocatedSize<size)\n      {\n        Index realloc_size = (std::min<Index>)(NumTraits<StorageIndex>::highest(),  size + Index(reserveSizeFactor*double(size)));\n        if(realloc_size<size)\n          internal::throw_std_bad_alloc();\n        reallocate(realloc_size);\n      }\n      m_size = size;\n    }\n\n    void append(const Scalar& v, Index i)\n    {\n      Index id = m_size;\n      resize(m_size+1, 1);\n      m_values[id] = v;\n      m_indices[id] = internal::convert_index<StorageIndex>(i);\n    }\n\n    inline Index size() const { return m_size; }\n    inline Index allocatedSize() const { return m_allocatedSize; }\n    inline void clear() { m_size = 0; }\n\n    const Scalar* valuePtr() const { return m_values; }\n    Scalar* valuePtr() { return m_values; }\n    const StorageIndex* indexPtr() const { return m_indices; }\n    StorageIndex* indexPtr() { return m_indices; }\n\n    inline Scalar& value(Index i) { eigen_internal_assert(m_values!=0); return m_values[i]; }\n    inline const Scalar& value(Index i) const { eigen_internal_assert(m_values!=0); return m_values[i]; }\n\n    inline StorageIndex& index(Index i) { eigen_internal_assert(m_indices!=0); return m_indices[i]; }\n    inline const StorageIndex& index(Index i) const { eigen_internal_assert(m_indices!=0); return m_indices[i]; }\n\n    /** \\returns the largest \\c k such that for all \\c j in [0,k) index[\\c j]\\<\\a key */\n    inline Index searchLowerIndex(Index key) const\n    {\n      return searchLowerIndex(0, m_size, key);\n    }\n\n    /** \\returns the largest \\c k in [start,end) such that for all \\c j in [start,k) index[\\c j]\\<\\a key */\n    inline Index searchLowerIndex(Index start, Index end, Index key) const\n    {\n      while(end>start)\n      {\n        Index mid = (end+start)>>1;\n        if (m_indices[mid]<key)\n          start = mid+1;\n        else\n          end = mid;\n      }\n      return start;\n    }\n\n    /** \\returns the stored value at index \\a key\n      * If the value does not exist, then the value \\a defaultValue is returned without any insertion. */\n    inline Scalar at(Index key, const Scalar& defaultValue = Scalar(0)) const\n    {\n      if (m_size==0)\n        return defaultValue;\n      else if (key==m_indices[m_size-1])\n        return m_values[m_size-1];\n      // ^^  optimization: let's first check if it is the last coefficient\n      // (very common in high level algorithms)\n      const Index id = searchLowerIndex(0,m_size-1,key);\n      return ((id<m_size) && (m_indices[id]==key)) ? m_values[id] : defaultValue;\n    }\n\n    /** Like at(), but the search is performed in the range [start,end) */\n    inline Scalar atInRange(Index start, Index end, Index key, const Scalar &defaultValue = Scalar(0)) const\n    {\n      if (start>=end)\n        return defaultValue;\n      else if (end>start && key==m_indices[end-1])\n        return m_values[end-1];\n      // ^^  optimization: let's first check if it is the last coefficient\n      // (very common in high level algorithms)\n      const Index id = searchLowerIndex(start,end-1,key);\n      return ((id<end) && (m_indices[id]==key)) ? m_values[id] : defaultValue;\n    }\n\n    /** \\returns a reference to the value at index \\a key\n      * If the value does not exist, then the value \\a defaultValue is inserted\n      * such that the keys are sorted. */\n    inline Scalar& atWithInsertion(Index key, const Scalar& defaultValue = Scalar(0))\n    {\n      Index id = searchLowerIndex(0,m_size,key);\n      if (id>=m_size || m_indices[id]!=key)\n      {\n        if (m_allocatedSize<m_size+1)\n        {\n          m_allocatedSize = 2*(m_size+1);\n          internal::scoped_array<Scalar> newValues(m_allocatedSize);\n          internal::scoped_array<StorageIndex> newIndices(m_allocatedSize);\n\n          // copy first chunk\n          internal::smart_copy(m_values,  m_values +id, newValues.ptr());\n          internal::smart_copy(m_indices, m_indices+id, newIndices.ptr());\n\n          // copy the rest\n          if(m_size>id)\n          {\n            internal::smart_copy(m_values +id,  m_values +m_size, newValues.ptr() +id+1);\n            internal::smart_copy(m_indices+id,  m_indices+m_size, newIndices.ptr()+id+1);\n          }\n          std::swap(m_values,newValues.ptr());\n          std::swap(m_indices,newIndices.ptr());\n        }\n        else if(m_size>id)\n        {\n          internal::smart_memmove(m_values +id, m_values +m_size, m_values +id+1);\n          internal::smart_memmove(m_indices+id, m_indices+m_size, m_indices+id+1);\n        }\n        m_size++;\n        m_indices[id] = internal::convert_index<StorageIndex>(key);\n        m_values[id] = defaultValue;\n      }\n      return m_values[id];\n    }\n\n    void moveChunk(Index from, Index to, Index chunkSize)\n    {\n      eigen_internal_assert(to+chunkSize <= m_size);\n      if(to>from && from+chunkSize>to)\n      {\n        // move backward\n        internal::smart_memmove(m_values+from,  m_values+from+chunkSize,  m_values+to);\n        internal::smart_memmove(m_indices+from, m_indices+from+chunkSize, m_indices+to);\n      }\n      else\n      {\n        internal::smart_copy(m_values+from,  m_values+from+chunkSize,  m_values+to);\n        internal::smart_copy(m_indices+from, m_indices+from+chunkSize, m_indices+to);\n      }\n    }\n\n    void prune(const Scalar& reference, const RealScalar& epsilon = NumTraits<RealScalar>::dummy_precision())\n    {\n      Index k = 0;\n      Index n = size();\n      for (Index i=0; i<n; ++i)\n      {\n        if (!internal::isMuchSmallerThan(value(i), reference, epsilon))\n        {\n          value(k) = value(i);\n          index(k) = index(i);\n          ++k;\n        }\n      }\n      resize(k,0);\n    }\n\n  protected:\n\n    inline void reallocate(Index size)\n    {\n      #ifdef EIGEN_SPARSE_COMPRESSED_STORAGE_REALLOCATE_PLUGIN\n        EIGEN_SPARSE_COMPRESSED_STORAGE_REALLOCATE_PLUGIN\n      #endif\n      eigen_internal_assert(size!=m_allocatedSize);\n      internal::scoped_array<Scalar> newValues(size);\n      internal::scoped_array<StorageIndex> newIndices(size);\n      Index copySize = (std::min)(size, m_size);\n      if (copySize>0) {\n        internal::smart_copy(m_values, m_values+copySize, newValues.ptr());\n        internal::smart_copy(m_indices, m_indices+copySize, newIndices.ptr());\n      }\n      std::swap(m_values,newValues.ptr());\n      std::swap(m_indices,newIndices.ptr());\n      m_allocatedSize = size;\n    }\n\n  protected:\n    Scalar* m_values;\n    StorageIndex* m_indices;\n    Index m_size;\n    Index m_allocatedSize;\n\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_COMPRESSED_STORAGE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/ConservativeSparseSparseProduct.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CONSERVATIVESPARSESPARSEPRODUCT_H\n#define EIGEN_CONSERVATIVESPARSESPARSEPRODUCT_H\n\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstatic void conservative_sparse_sparse_product_impl(const Lhs& lhs, const Rhs& rhs, ResultType& res, bool sortedInsertion = false)\n{\n  typedef typename remove_all<Lhs>::type::Scalar LhsScalar;\n  typedef typename remove_all<Rhs>::type::Scalar RhsScalar;\n  typedef typename remove_all<ResultType>::type::Scalar ResScalar;\n\n  // make sure to call innerSize/outerSize since we fake the storage order.\n  Index rows = lhs.innerSize();\n  Index cols = rhs.outerSize();\n  eigen_assert(lhs.outerSize() == rhs.innerSize());\n\n  ei_declare_aligned_stack_constructed_variable(bool,   mask,     rows, 0);\n  ei_declare_aligned_stack_constructed_variable(ResScalar, values,   rows, 0);\n  ei_declare_aligned_stack_constructed_variable(Index,  indices,  rows, 0);\n\n  std::memset(mask,0,sizeof(bool)*rows);\n\n  evaluator<Lhs> lhsEval(lhs);\n  evaluator<Rhs> rhsEval(rhs);\n\n  // estimate the number of non zero entries\n  // given a rhs column containing Y non zeros, we assume that the respective Y columns\n  // of the lhs differs in average of one non zeros, thus the number of non zeros for\n  // the product of a rhs column with the lhs is X+Y where X is the average number of non zero\n  // per column of the lhs.\n  // Therefore, we have nnz(lhs*rhs) = nnz(lhs) + nnz(rhs)\n  Index estimated_nnz_prod = lhsEval.nonZerosEstimate() + rhsEval.nonZerosEstimate();\n\n  res.setZero();\n  res.reserve(Index(estimated_nnz_prod));\n  // we compute each column of the result, one after the other\n  for (Index j=0; j<cols; ++j)\n  {\n\n    res.startVec(j);\n    Index nnz = 0;\n    for (typename evaluator<Rhs>::InnerIterator rhsIt(rhsEval, j); rhsIt; ++rhsIt)\n    {\n      RhsScalar y = rhsIt.value();\n      Index k = rhsIt.index();\n      for (typename evaluator<Lhs>::InnerIterator lhsIt(lhsEval, k); lhsIt; ++lhsIt)\n      {\n        Index i = lhsIt.index();\n        LhsScalar x = lhsIt.value();\n        if(!mask[i])\n        {\n          mask[i] = true;\n          values[i] = x * y;\n          indices[nnz] = i;\n          ++nnz;\n        }\n        else\n          values[i] += x * y;\n      }\n    }\n    if(!sortedInsertion)\n    {\n      // unordered insertion\n      for(Index k=0; k<nnz; ++k)\n      {\n        Index i = indices[k];\n        res.insertBackByOuterInnerUnordered(j,i) = values[i];\n        mask[i] = false;\n      }\n    }\n    else\n    {\n      // alternative ordered insertion code:\n      const Index t200 = rows/11; // 11 == (log2(200)*1.39)\n      const Index t = (rows*100)/139;\n\n      // FIXME reserve nnz non zeros\n      // FIXME implement faster sorting algorithms for very small nnz\n      // if the result is sparse enough => use a quick sort\n      // otherwise => loop through the entire vector\n      // In order to avoid to perform an expensive log2 when the\n      // result is clearly very sparse we use a linear bound up to 200.\n      if((nnz<200 && nnz<t200) || nnz * numext::log2(int(nnz)) < t)\n      {\n        if(nnz>1) std::sort(indices,indices+nnz);\n        for(Index k=0; k<nnz; ++k)\n        {\n          Index i = indices[k];\n          res.insertBackByOuterInner(j,i) = values[i];\n          mask[i] = false;\n        }\n      }\n      else\n      {\n        // dense path\n        for(Index i=0; i<rows; ++i)\n        {\n          if(mask[i])\n          {\n            mask[i] = false;\n            res.insertBackByOuterInner(j,i) = values[i];\n          }\n        }\n      }\n    }\n  }\n  res.finalize();\n}\n\n\n} // end namespace internal\n\nnamespace internal {\n\ntemplate<typename Lhs, typename Rhs, typename ResultType,\n  int LhsStorageOrder = (traits<Lhs>::Flags&RowMajorBit) ? RowMajor : ColMajor,\n  int RhsStorageOrder = (traits<Rhs>::Flags&RowMajorBit) ? RowMajor : ColMajor,\n  int ResStorageOrder = (traits<ResultType>::Flags&RowMajorBit) ? RowMajor : ColMajor>\nstruct conservative_sparse_sparse_product_selector;\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,ColMajor,ColMajor,ColMajor>\n{\n  typedef typename remove_all<Lhs>::type LhsCleaned;\n  typedef typename LhsCleaned::Scalar Scalar;\n\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    typedef SparseMatrix<typename ResultType::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorMatrix;\n    typedef SparseMatrix<typename ResultType::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorMatrixAux;\n    typedef typename sparse_eval<ColMajorMatrixAux,ResultType::RowsAtCompileTime,ResultType::ColsAtCompileTime,ColMajorMatrixAux::Flags>::type ColMajorMatrix;\n\n    // If the result is tall and thin (in the extreme case a column vector)\n    // then it is faster to sort the coefficients inplace instead of transposing twice.\n    // FIXME, the following heuristic is probably not very good.\n    if(lhs.rows()>rhs.cols())\n    {\n      ColMajorMatrix resCol(lhs.rows(),rhs.cols());\n      // perform sorted insertion\n      internal::conservative_sparse_sparse_product_impl<Lhs,Rhs,ColMajorMatrix>(lhs, rhs, resCol, true);\n      res = resCol.markAsRValue();\n    }\n    else\n    {\n      ColMajorMatrixAux resCol(lhs.rows(),rhs.cols());\n      // resort to transpose to sort the entries\n      internal::conservative_sparse_sparse_product_impl<Lhs,Rhs,ColMajorMatrixAux>(lhs, rhs, resCol, false);\n      RowMajorMatrix resRow(resCol);\n      res = resRow.markAsRValue();\n    }\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,RowMajor,ColMajor,ColMajor>\n{\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    typedef SparseMatrix<typename Rhs::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorRhs;\n    typedef SparseMatrix<typename ResultType::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorRes;\n    RowMajorRhs rhsRow = rhs;\n    RowMajorRes resRow(lhs.rows(), rhs.cols());\n    internal::conservative_sparse_sparse_product_impl<RowMajorRhs,Lhs,RowMajorRes>(rhsRow, lhs, resRow);\n    res = resRow;\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,ColMajor,RowMajor,ColMajor>\n{\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    typedef SparseMatrix<typename Lhs::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorLhs;\n    typedef SparseMatrix<typename ResultType::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorRes;\n    RowMajorLhs lhsRow = lhs;\n    RowMajorRes resRow(lhs.rows(), rhs.cols());\n    internal::conservative_sparse_sparse_product_impl<Rhs,RowMajorLhs,RowMajorRes>(rhs, lhsRow, resRow);\n    res = resRow;\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,RowMajor,RowMajor,ColMajor>\n{\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    typedef SparseMatrix<typename ResultType::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorMatrix;\n    RowMajorMatrix resRow(lhs.rows(), rhs.cols());\n    internal::conservative_sparse_sparse_product_impl<Rhs,Lhs,RowMajorMatrix>(rhs, lhs, resRow);\n    res = resRow;\n  }\n};\n\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,ColMajor,ColMajor,RowMajor>\n{\n  typedef typename traits<typename remove_all<Lhs>::type>::Scalar Scalar;\n\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    typedef SparseMatrix<typename ResultType::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorMatrix;\n    ColMajorMatrix resCol(lhs.rows(), rhs.cols());\n    internal::conservative_sparse_sparse_product_impl<Lhs,Rhs,ColMajorMatrix>(lhs, rhs, resCol);\n    res = resCol;\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,RowMajor,ColMajor,RowMajor>\n{\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    typedef SparseMatrix<typename Lhs::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorLhs;\n    typedef SparseMatrix<typename ResultType::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorRes;\n    ColMajorLhs lhsCol = lhs;\n    ColMajorRes resCol(lhs.rows(), rhs.cols());\n    internal::conservative_sparse_sparse_product_impl<ColMajorLhs,Rhs,ColMajorRes>(lhsCol, rhs, resCol);\n    res = resCol;\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,ColMajor,RowMajor,RowMajor>\n{\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    typedef SparseMatrix<typename Rhs::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorRhs;\n    typedef SparseMatrix<typename ResultType::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorRes;\n    ColMajorRhs rhsCol = rhs;\n    ColMajorRes resCol(lhs.rows(), rhs.cols());\n    internal::conservative_sparse_sparse_product_impl<Lhs,ColMajorRhs,ColMajorRes>(lhs, rhsCol, resCol);\n    res = resCol;\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct conservative_sparse_sparse_product_selector<Lhs,Rhs,ResultType,RowMajor,RowMajor,RowMajor>\n{\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    typedef SparseMatrix<typename ResultType::Scalar,RowMajor,typename ResultType::StorageIndex> RowMajorMatrix;\n    typedef SparseMatrix<typename ResultType::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorMatrix;\n    RowMajorMatrix resRow(lhs.rows(),rhs.cols());\n    internal::conservative_sparse_sparse_product_impl<Rhs,Lhs,RowMajorMatrix>(rhs, lhs, resRow);\n    // sort the non zeros:\n    ColMajorMatrix resCol(resRow);\n    res = resCol;\n  }\n};\n\n} // end namespace internal\n\n\nnamespace internal {\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstatic void sparse_sparse_to_dense_product_impl(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n{\n  typedef typename remove_all<Lhs>::type::Scalar LhsScalar;\n  typedef typename remove_all<Rhs>::type::Scalar RhsScalar;\n  Index cols = rhs.outerSize();\n  eigen_assert(lhs.outerSize() == rhs.innerSize());\n\n  evaluator<Lhs> lhsEval(lhs);\n  evaluator<Rhs> rhsEval(rhs);\n\n  for (Index j=0; j<cols; ++j)\n  {\n    for (typename evaluator<Rhs>::InnerIterator rhsIt(rhsEval, j); rhsIt; ++rhsIt)\n    {\n      RhsScalar y = rhsIt.value();\n      Index k = rhsIt.index();\n      for (typename evaluator<Lhs>::InnerIterator lhsIt(lhsEval, k); lhsIt; ++lhsIt)\n      {\n        Index i = lhsIt.index();\n        LhsScalar x = lhsIt.value();\n        res.coeffRef(i,j) += x * y;\n      }\n    }\n  }\n}\n\n\n} // end namespace internal\n\nnamespace internal {\n\ntemplate<typename Lhs, typename Rhs, typename ResultType,\n  int LhsStorageOrder = (traits<Lhs>::Flags&RowMajorBit) ? RowMajor : ColMajor,\n  int RhsStorageOrder = (traits<Rhs>::Flags&RowMajorBit) ? RowMajor : ColMajor>\nstruct sparse_sparse_to_dense_product_selector;\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_to_dense_product_selector<Lhs,Rhs,ResultType,ColMajor,ColMajor>\n{\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    internal::sparse_sparse_to_dense_product_impl<Lhs,Rhs,ResultType>(lhs, rhs, res);\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_to_dense_product_selector<Lhs,Rhs,ResultType,RowMajor,ColMajor>\n{\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    typedef SparseMatrix<typename Lhs::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorLhs;\n    ColMajorLhs lhsCol(lhs);\n    internal::sparse_sparse_to_dense_product_impl<ColMajorLhs,Rhs,ResultType>(lhsCol, rhs, res);\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_to_dense_product_selector<Lhs,Rhs,ResultType,ColMajor,RowMajor>\n{\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    typedef SparseMatrix<typename Rhs::Scalar,ColMajor,typename ResultType::StorageIndex> ColMajorRhs;\n    ColMajorRhs rhsCol(rhs);\n    internal::sparse_sparse_to_dense_product_impl<Lhs,ColMajorRhs,ResultType>(lhs, rhsCol, res);\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_to_dense_product_selector<Lhs,Rhs,ResultType,RowMajor,RowMajor>\n{\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res)\n  {\n    Transpose<ResultType> trRes(res);\n    internal::sparse_sparse_to_dense_product_impl<Rhs,Lhs,Transpose<ResultType> >(rhs, lhs, trRes);\n  }\n};\n\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_CONSERVATIVESPARSESPARSEPRODUCT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/MappedSparseMatrix.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MAPPED_SPARSEMATRIX_H\n#define EIGEN_MAPPED_SPARSEMATRIX_H\n\nnamespace Eigen {\n\n/** \\deprecated Use Map<SparseMatrix<> >\n  * \\class MappedSparseMatrix\n  *\n  * \\brief Sparse matrix\n  *\n  * \\param _Scalar the scalar type, i.e. the type of the coefficients\n  *\n  * See http://www.netlib.org/linalg/html_templates/node91.html for details on the storage scheme.\n  *\n  */\nnamespace internal {\ntemplate<typename _Scalar, int _Flags, typename _StorageIndex>\nstruct traits<MappedSparseMatrix<_Scalar, _Flags, _StorageIndex> > : traits<SparseMatrix<_Scalar, _Flags, _StorageIndex> >\n{};\n} // end namespace internal\n\ntemplate<typename _Scalar, int _Flags, typename _StorageIndex>\nclass MappedSparseMatrix\n  : public Map<SparseMatrix<_Scalar, _Flags, _StorageIndex> >\n{\n    typedef Map<SparseMatrix<_Scalar, _Flags, _StorageIndex> > Base;\n\n  public:\n    \n    typedef typename Base::StorageIndex StorageIndex;\n    typedef typename Base::Scalar Scalar;\n\n    inline MappedSparseMatrix(Index rows, Index cols, Index nnz, StorageIndex* outerIndexPtr, StorageIndex* innerIndexPtr, Scalar* valuePtr, StorageIndex* innerNonZeroPtr = 0)\n      : Base(rows, cols, nnz, outerIndexPtr, innerIndexPtr, valuePtr, innerNonZeroPtr)\n    {}\n\n    /** Empty destructor */\n    inline ~MappedSparseMatrix() {}\n};\n\nnamespace internal {\n\ntemplate<typename _Scalar, int _Options, typename _StorageIndex>\nstruct evaluator<MappedSparseMatrix<_Scalar,_Options,_StorageIndex> >\n  : evaluator<SparseCompressedBase<MappedSparseMatrix<_Scalar,_Options,_StorageIndex> > >\n{\n  typedef MappedSparseMatrix<_Scalar,_Options,_StorageIndex> XprType;\n  typedef evaluator<SparseCompressedBase<XprType> > Base;\n  \n  evaluator() : Base() {}\n  explicit evaluator(const XprType &mat) : Base(mat) {}\n};\n\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_MAPPED_SPARSEMATRIX_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseAssign.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEASSIGN_H\n#define EIGEN_SPARSEASSIGN_H\n\nnamespace Eigen { \n\ntemplate<typename Derived>    \ntemplate<typename OtherDerived>\nDerived& SparseMatrixBase<Derived>::operator=(const EigenBase<OtherDerived> &other)\n{\n  internal::call_assignment_no_alias(derived(), other.derived());\n  return derived();\n}\n\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\nDerived& SparseMatrixBase<Derived>::operator=(const ReturnByValue<OtherDerived>& other)\n{\n  // TODO use the evaluator mechanism\n  other.evalTo(derived());\n  return derived();\n}\n\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\ninline Derived& SparseMatrixBase<Derived>::operator=(const SparseMatrixBase<OtherDerived>& other)\n{\n  // by default sparse evaluation do not alias, so we can safely bypass the generic call_assignment routine\n  internal::Assignment<Derived,OtherDerived,internal::assign_op<Scalar,typename OtherDerived::Scalar> >\n          ::run(derived(), other.derived(), internal::assign_op<Scalar,typename OtherDerived::Scalar>());\n  return derived();\n}\n\ntemplate<typename Derived>\ninline Derived& SparseMatrixBase<Derived>::operator=(const Derived& other)\n{\n  internal::call_assignment_no_alias(derived(), other.derived());\n  return derived();\n}\n\nnamespace internal {\n\ntemplate<>\nstruct storage_kind_to_evaluator_kind<Sparse> {\n  typedef IteratorBased Kind;\n};\n\ntemplate<>\nstruct storage_kind_to_shape<Sparse> {\n  typedef SparseShape Shape;\n};\n\nstruct Sparse2Sparse {};\nstruct Sparse2Dense  {};\n\ntemplate<> struct AssignmentKind<SparseShape, SparseShape>           { typedef Sparse2Sparse Kind; };\ntemplate<> struct AssignmentKind<SparseShape, SparseTriangularShape> { typedef Sparse2Sparse Kind; };\ntemplate<> struct AssignmentKind<DenseShape,  SparseShape>           { typedef Sparse2Dense  Kind; };\ntemplate<> struct AssignmentKind<DenseShape,  SparseTriangularShape> { typedef Sparse2Dense  Kind; };\n\n\ntemplate<typename DstXprType, typename SrcXprType>\nvoid assign_sparse_to_sparse(DstXprType &dst, const SrcXprType &src)\n{\n  typedef typename DstXprType::Scalar Scalar;\n  typedef internal::evaluator<DstXprType> DstEvaluatorType;\n  typedef internal::evaluator<SrcXprType> SrcEvaluatorType;\n\n  SrcEvaluatorType srcEvaluator(src);\n\n  const bool transpose = (DstEvaluatorType::Flags & RowMajorBit) != (SrcEvaluatorType::Flags & RowMajorBit);\n  const Index outerEvaluationSize = (SrcEvaluatorType::Flags&RowMajorBit) ? src.rows() : src.cols();\n  if ((!transpose) && src.isRValue())\n  {\n    // eval without temporary\n    dst.resize(src.rows(), src.cols());\n    dst.setZero();\n    dst.reserve((std::min)(src.rows()*src.cols(), (std::max)(src.rows(),src.cols())*2));\n    for (Index j=0; j<outerEvaluationSize; ++j)\n    {\n      dst.startVec(j);\n      for (typename SrcEvaluatorType::InnerIterator it(srcEvaluator, j); it; ++it)\n      {\n        Scalar v = it.value();\n        dst.insertBackByOuterInner(j,it.index()) = v;\n      }\n    }\n    dst.finalize();\n  }\n  else\n  {\n    // eval through a temporary\n    eigen_assert(( ((internal::traits<DstXprType>::SupportedAccessPatterns & OuterRandomAccessPattern)==OuterRandomAccessPattern) ||\n              (!((DstEvaluatorType::Flags & RowMajorBit) != (SrcEvaluatorType::Flags & RowMajorBit)))) &&\n              \"the transpose operation is supposed to be handled in SparseMatrix::operator=\");\n\n    enum { Flip = (DstEvaluatorType::Flags & RowMajorBit) != (SrcEvaluatorType::Flags & RowMajorBit) };\n\n    \n    DstXprType temp(src.rows(), src.cols());\n\n    temp.reserve((std::min)(src.rows()*src.cols(), (std::max)(src.rows(),src.cols())*2));\n    for (Index j=0; j<outerEvaluationSize; ++j)\n    {\n      temp.startVec(j);\n      for (typename SrcEvaluatorType::InnerIterator it(srcEvaluator, j); it; ++it)\n      {\n        Scalar v = it.value();\n        temp.insertBackByOuterInner(Flip?it.index():j,Flip?j:it.index()) = v;\n      }\n    }\n    temp.finalize();\n\n    dst = temp.markAsRValue();\n  }\n}\n\n// Generic Sparse to Sparse assignment\ntemplate< typename DstXprType, typename SrcXprType, typename Functor>\nstruct Assignment<DstXprType, SrcXprType, Functor, Sparse2Sparse>\n{\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &/*func*/)\n  {\n    assign_sparse_to_sparse(dst.derived(), src.derived());\n  }\n};\n\n// Generic Sparse to Dense assignment\ntemplate< typename DstXprType, typename SrcXprType, typename Functor, typename Weak>\nstruct Assignment<DstXprType, SrcXprType, Functor, Sparse2Dense, Weak>\n{\n  static void run(DstXprType &dst, const SrcXprType &src, const Functor &func)\n  {\n    if(internal::is_same<Functor,internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> >::value)\n      dst.setZero();\n    \n    internal::evaluator<SrcXprType> srcEval(src);\n    resize_if_allowed(dst, src, func);\n    internal::evaluator<DstXprType> dstEval(dst);\n    \n    const Index outerEvaluationSize = (internal::evaluator<SrcXprType>::Flags&RowMajorBit) ? src.rows() : src.cols();\n    for (Index j=0; j<outerEvaluationSize; ++j)\n      for (typename internal::evaluator<SrcXprType>::InnerIterator i(srcEval,j); i; ++i)\n        func.assignCoeff(dstEval.coeffRef(i.row(),i.col()), i.value());\n  }\n};\n\n// Specialization for dense ?= dense +/- sparse and dense ?= sparse +/- dense\ntemplate<typename DstXprType, typename Func1, typename Func2>\nstruct assignment_from_dense_op_sparse\n{\n  template<typename SrcXprType, typename InitialFunc>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void run(DstXprType &dst, const SrcXprType &src, const InitialFunc& /*func*/)\n  {\n    #ifdef EIGEN_SPARSE_ASSIGNMENT_FROM_DENSE_OP_SPARSE_PLUGIN\n    EIGEN_SPARSE_ASSIGNMENT_FROM_DENSE_OP_SPARSE_PLUGIN\n    #endif\n\n    call_assignment_no_alias(dst, src.lhs(), Func1());\n    call_assignment_no_alias(dst, src.rhs(), Func2());\n  }\n\n  // Specialization for dense1 = sparse + dense2; -> dense1 = dense2; dense1 += sparse;\n  template<typename Lhs, typename Rhs, typename Scalar>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  typename internal::enable_if<internal::is_same<typename internal::evaluator_traits<Rhs>::Shape,DenseShape>::value>::type\n  run(DstXprType &dst, const CwiseBinaryOp<internal::scalar_sum_op<Scalar,Scalar>, const Lhs, const Rhs> &src,\n      const internal::assign_op<typename DstXprType::Scalar,Scalar>& /*func*/)\n  {\n    #ifdef EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_ADD_DENSE_PLUGIN\n    EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_ADD_DENSE_PLUGIN\n    #endif\n\n    // Apply the dense matrix first, then the sparse one.\n    call_assignment_no_alias(dst, src.rhs(), Func1());\n    call_assignment_no_alias(dst, src.lhs(), Func2());\n  }\n\n  // Specialization for dense1 = sparse - dense2; -> dense1 = -dense2; dense1 += sparse;\n  template<typename Lhs, typename Rhs, typename Scalar>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  typename internal::enable_if<internal::is_same<typename internal::evaluator_traits<Rhs>::Shape,DenseShape>::value>::type\n  run(DstXprType &dst, const CwiseBinaryOp<internal::scalar_difference_op<Scalar,Scalar>, const Lhs, const Rhs> &src,\n      const internal::assign_op<typename DstXprType::Scalar,Scalar>& /*func*/)\n  {\n    #ifdef EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_SUB_DENSE_PLUGIN\n    EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_SUB_DENSE_PLUGIN\n    #endif\n\n    // Apply the dense matrix first, then the sparse one.\n    call_assignment_no_alias(dst, -src.rhs(), Func1());\n    call_assignment_no_alias(dst,  src.lhs(), add_assign_op<typename DstXprType::Scalar,typename Lhs::Scalar>());\n  }\n};\n\n#define EIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(ASSIGN_OP,BINOP,ASSIGN_OP2) \\\n  template< typename DstXprType, typename Lhs, typename Rhs, typename Scalar> \\\n  struct Assignment<DstXprType, CwiseBinaryOp<internal::BINOP<Scalar,Scalar>, const Lhs, const Rhs>, internal::ASSIGN_OP<typename DstXprType::Scalar,Scalar>, \\\n                    Sparse2Dense, \\\n                    typename internal::enable_if<   internal::is_same<typename internal::evaluator_traits<Lhs>::Shape,DenseShape>::value \\\n                                                 || internal::is_same<typename internal::evaluator_traits<Rhs>::Shape,DenseShape>::value>::type> \\\n    : assignment_from_dense_op_sparse<DstXprType, internal::ASSIGN_OP<typename DstXprType::Scalar,typename Lhs::Scalar>, internal::ASSIGN_OP2<typename DstXprType::Scalar,typename Rhs::Scalar> > \\\n  {}\n\nEIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(assign_op,    scalar_sum_op,add_assign_op);\nEIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(add_assign_op,scalar_sum_op,add_assign_op);\nEIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(sub_assign_op,scalar_sum_op,sub_assign_op);\n\nEIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(assign_op,    scalar_difference_op,sub_assign_op);\nEIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(add_assign_op,scalar_difference_op,sub_assign_op);\nEIGEN_CATCH_ASSIGN_DENSE_OP_SPARSE(sub_assign_op,scalar_difference_op,add_assign_op);\n\n\n// Specialization for \"dst = dec.solve(rhs)\"\n// NOTE we need to specialize it for Sparse2Sparse to avoid ambiguous specialization error\ntemplate<typename DstXprType, typename DecType, typename RhsType, typename Scalar>\nstruct Assignment<DstXprType, Solve<DecType,RhsType>, internal::assign_op<Scalar,Scalar>, Sparse2Sparse>\n{\n  typedef Solve<DecType,RhsType> SrcXprType;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<Scalar,Scalar> &)\n  {\n    Index dstRows = src.rows();\n    Index dstCols = src.cols();\n    if((dst.rows()!=dstRows) || (dst.cols()!=dstCols))\n      dst.resize(dstRows, dstCols);\n\n    src.dec()._solve_impl(src.rhs(), dst);\n  }\n};\n\nstruct Diagonal2Sparse {};\n\ntemplate<> struct AssignmentKind<SparseShape,DiagonalShape> { typedef Diagonal2Sparse Kind; };\n\ntemplate< typename DstXprType, typename SrcXprType, typename Functor>\nstruct Assignment<DstXprType, SrcXprType, Functor, Diagonal2Sparse>\n{\n  typedef typename DstXprType::StorageIndex StorageIndex;\n  typedef typename DstXprType::Scalar Scalar;\n\n  template<int Options, typename AssignFunc>\n  static void run(SparseMatrix<Scalar,Options,StorageIndex> &dst, const SrcXprType &src, const AssignFunc &func)\n  { dst.assignDiagonal(src.diagonal(), func); }\n  \n  template<typename DstDerived>\n  static void run(SparseMatrixBase<DstDerived> &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &/*func*/)\n  { dst.derived().diagonal() = src.diagonal(); }\n  \n  template<typename DstDerived>\n  static void run(SparseMatrixBase<DstDerived> &dst, const SrcXprType &src, const internal::add_assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &/*func*/)\n  { dst.derived().diagonal() += src.diagonal(); }\n  \n  template<typename DstDerived>\n  static void run(SparseMatrixBase<DstDerived> &dst, const SrcXprType &src, const internal::sub_assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &/*func*/)\n  { dst.derived().diagonal() -= src.diagonal(); }\n};\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSEASSIGN_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseBlock.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_BLOCK_H\n#define EIGEN_SPARSE_BLOCK_H\n\nnamespace Eigen {\n\n// Subset of columns or rows\ntemplate<typename XprType, int BlockRows, int BlockCols>\nclass BlockImpl<XprType,BlockRows,BlockCols,true,Sparse>\n  : public SparseMatrixBase<Block<XprType,BlockRows,BlockCols,true> >\n{\n    typedef typename internal::remove_all<typename XprType::Nested>::type _MatrixTypeNested;\n    typedef Block<XprType, BlockRows, BlockCols, true> BlockType;\npublic:\n    enum { IsRowMajor = internal::traits<BlockType>::IsRowMajor };\nprotected:\n    enum { OuterSize = IsRowMajor ? BlockRows : BlockCols };\n    typedef SparseMatrixBase<BlockType> Base;\n    using Base::convert_index;\npublic:\n    EIGEN_SPARSE_PUBLIC_INTERFACE(BlockType)\n\n    inline BlockImpl(XprType& xpr, Index i)\n      : m_matrix(xpr), m_outerStart(convert_index(i)), m_outerSize(OuterSize)\n    {}\n\n    inline BlockImpl(XprType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols)\n      : m_matrix(xpr), m_outerStart(convert_index(IsRowMajor ? startRow : startCol)), m_outerSize(convert_index(IsRowMajor ? blockRows : blockCols))\n    {}\n\n    EIGEN_STRONG_INLINE Index rows() const { return IsRowMajor ? m_outerSize.value() : m_matrix.rows(); }\n    EIGEN_STRONG_INLINE Index cols() const { return IsRowMajor ? m_matrix.cols() : m_outerSize.value(); }\n\n    Index nonZeros() const\n    {\n      typedef internal::evaluator<XprType> EvaluatorType;\n      EvaluatorType matEval(m_matrix);\n      Index nnz = 0;\n      Index end = m_outerStart + m_outerSize.value();\n      for(Index j=m_outerStart; j<end; ++j)\n        for(typename EvaluatorType::InnerIterator it(matEval, j); it; ++it)\n          ++nnz;\n      return nnz;\n    }\n\n    inline const Scalar coeff(Index row, Index col) const\n    {\n      return m_matrix.coeff(row + (IsRowMajor ? m_outerStart : 0), col + (IsRowMajor ? 0 :  m_outerStart));\n    }\n\n    inline const Scalar coeff(Index index) const\n    {\n      return m_matrix.coeff(IsRowMajor ? m_outerStart : index, IsRowMajor ? index :  m_outerStart);\n    }\n\n    inline const XprType& nestedExpression() const { return m_matrix; }\n    inline XprType& nestedExpression() { return m_matrix; }\n    Index startRow() const { return IsRowMajor ? m_outerStart : 0; }\n    Index startCol() const { return IsRowMajor ? 0 : m_outerStart; }\n    Index blockRows() const { return IsRowMajor ? m_outerSize.value() : m_matrix.rows(); }\n    Index blockCols() const { return IsRowMajor ? m_matrix.cols() : m_outerSize.value(); }\n\n  protected:\n\n    typename internal::ref_selector<XprType>::non_const_type m_matrix;\n    Index m_outerStart;\n    const internal::variable_if_dynamic<Index, OuterSize> m_outerSize;\n\n  protected:\n    // Disable assignment with clear error message.\n    // Note that simply removing operator= yields compilation errors with ICC+MSVC\n    template<typename T>\n    BlockImpl& operator=(const T&)\n    {\n      EIGEN_STATIC_ASSERT(sizeof(T)==0, THIS_SPARSE_BLOCK_SUBEXPRESSION_IS_READ_ONLY);\n      return *this;\n    }\n};\n\n\n/***************************************************************************\n* specialization for SparseMatrix\n***************************************************************************/\n\nnamespace internal {\n\ntemplate<typename SparseMatrixType, int BlockRows, int BlockCols>\nclass sparse_matrix_block_impl\n  : public SparseCompressedBase<Block<SparseMatrixType,BlockRows,BlockCols,true> >\n{\n    typedef typename internal::remove_all<typename SparseMatrixType::Nested>::type _MatrixTypeNested;\n    typedef Block<SparseMatrixType, BlockRows, BlockCols, true> BlockType;\n    typedef SparseCompressedBase<Block<SparseMatrixType,BlockRows,BlockCols,true> > Base;\n    using Base::convert_index;\npublic:\n    enum { IsRowMajor = internal::traits<BlockType>::IsRowMajor };\n    EIGEN_SPARSE_PUBLIC_INTERFACE(BlockType)\nprotected:\n    typedef typename Base::IndexVector IndexVector;\n    enum { OuterSize = IsRowMajor ? BlockRows : BlockCols };\npublic:\n\n    inline sparse_matrix_block_impl(SparseMatrixType& xpr, Index i)\n      : m_matrix(xpr), m_outerStart(convert_index(i)), m_outerSize(OuterSize)\n    {}\n\n    inline sparse_matrix_block_impl(SparseMatrixType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols)\n      : m_matrix(xpr), m_outerStart(convert_index(IsRowMajor ? startRow : startCol)), m_outerSize(convert_index(IsRowMajor ? blockRows : blockCols))\n    {}\n\n    template<typename OtherDerived>\n    inline BlockType& operator=(const SparseMatrixBase<OtherDerived>& other)\n    {\n      typedef typename internal::remove_all<typename SparseMatrixType::Nested>::type _NestedMatrixType;\n      _NestedMatrixType& matrix = m_matrix;\n      // This assignment is slow if this vector set is not empty\n      // and/or it is not at the end of the nonzeros of the underlying matrix.\n\n      // 1 - eval to a temporary to avoid transposition and/or aliasing issues\n      Ref<const SparseMatrix<Scalar, IsRowMajor ? RowMajor : ColMajor, StorageIndex> > tmp(other.derived());\n      eigen_internal_assert(tmp.outerSize()==m_outerSize.value());\n\n      // 2 - let's check whether there is enough allocated memory\n      Index nnz           = tmp.nonZeros();\n      Index start         = m_outerStart==0 ? 0 : m_matrix.outerIndexPtr()[m_outerStart]; // starting position of the current block\n      Index end           = m_matrix.outerIndexPtr()[m_outerStart+m_outerSize.value()]; // ending position of the current block\n      Index block_size    = end - start;                                                // available room in the current block\n      Index tail_size     = m_matrix.outerIndexPtr()[m_matrix.outerSize()] - end;\n\n      Index free_size     = m_matrix.isCompressed()\n                          ? Index(matrix.data().allocatedSize()) + block_size\n                          : block_size;\n\n      Index tmp_start = tmp.outerIndexPtr()[0];\n\n      bool update_trailing_pointers = false;\n      if(nnz>free_size)\n      {\n        // realloc manually to reduce copies\n        typename SparseMatrixType::Storage newdata(m_matrix.data().allocatedSize() - block_size + nnz);\n\n        internal::smart_copy(m_matrix.valuePtr(),       m_matrix.valuePtr() + start,      newdata.valuePtr());\n        internal::smart_copy(m_matrix.innerIndexPtr(),  m_matrix.innerIndexPtr() + start, newdata.indexPtr());\n\n        internal::smart_copy(tmp.valuePtr() + tmp_start,      tmp.valuePtr() + tmp_start + nnz,       newdata.valuePtr() + start);\n        internal::smart_copy(tmp.innerIndexPtr() + tmp_start, tmp.innerIndexPtr() + tmp_start + nnz,  newdata.indexPtr() + start);\n\n        internal::smart_copy(matrix.valuePtr()+end,       matrix.valuePtr()+end + tail_size,      newdata.valuePtr()+start+nnz);\n        internal::smart_copy(matrix.innerIndexPtr()+end,  matrix.innerIndexPtr()+end + tail_size, newdata.indexPtr()+start+nnz);\n\n        newdata.resize(m_matrix.outerIndexPtr()[m_matrix.outerSize()] - block_size + nnz);\n\n        matrix.data().swap(newdata);\n\n        update_trailing_pointers = true;\n      }\n      else\n      {\n        if(m_matrix.isCompressed() && nnz!=block_size)\n        {\n          // no need to realloc, simply copy the tail at its respective position and insert tmp\n          matrix.data().resize(start + nnz + tail_size);\n\n          internal::smart_memmove(matrix.valuePtr()+end,      matrix.valuePtr() + end+tail_size,      matrix.valuePtr() + start+nnz);\n          internal::smart_memmove(matrix.innerIndexPtr()+end, matrix.innerIndexPtr() + end+tail_size, matrix.innerIndexPtr() + start+nnz);\n\n          update_trailing_pointers = true;\n        }\n\n        internal::smart_copy(tmp.valuePtr() + tmp_start,      tmp.valuePtr() + tmp_start + nnz,       matrix.valuePtr() + start);\n        internal::smart_copy(tmp.innerIndexPtr() + tmp_start, tmp.innerIndexPtr() + tmp_start + nnz,  matrix.innerIndexPtr() + start);\n      }\n\n      // update outer index pointers and innerNonZeros\n      if(IsVectorAtCompileTime)\n      {\n        if(!m_matrix.isCompressed())\n          matrix.innerNonZeroPtr()[m_outerStart] = StorageIndex(nnz);\n        matrix.outerIndexPtr()[m_outerStart] = StorageIndex(start);\n      }\n      else\n      {\n        StorageIndex p = StorageIndex(start);\n        for(Index k=0; k<m_outerSize.value(); ++k)\n        {\n          StorageIndex nnz_k = internal::convert_index<StorageIndex>(tmp.innerVector(k).nonZeros());\n          if(!m_matrix.isCompressed())\n            matrix.innerNonZeroPtr()[m_outerStart+k] = nnz_k;\n          matrix.outerIndexPtr()[m_outerStart+k] = p;\n          p += nnz_k;\n        }\n      }\n\n      if(update_trailing_pointers)\n      {\n        StorageIndex offset = internal::convert_index<StorageIndex>(nnz - block_size);\n        for(Index k = m_outerStart + m_outerSize.value(); k<=matrix.outerSize(); ++k)\n        {\n          matrix.outerIndexPtr()[k] += offset;\n        }\n      }\n\n      return derived();\n    }\n\n    inline BlockType& operator=(const BlockType& other)\n    {\n      return operator=<BlockType>(other);\n    }\n\n    inline const Scalar* valuePtr() const\n    { return m_matrix.valuePtr(); }\n    inline Scalar* valuePtr()\n    { return m_matrix.valuePtr(); }\n\n    inline const StorageIndex* innerIndexPtr() const\n    { return m_matrix.innerIndexPtr(); }\n    inline StorageIndex* innerIndexPtr()\n    { return m_matrix.innerIndexPtr(); }\n\n    inline const StorageIndex* outerIndexPtr() const\n    { return m_matrix.outerIndexPtr() + m_outerStart; }\n    inline StorageIndex* outerIndexPtr()\n    { return m_matrix.outerIndexPtr() + m_outerStart; }\n\n    inline const StorageIndex* innerNonZeroPtr() const\n    { return isCompressed() ? 0 : (m_matrix.innerNonZeroPtr()+m_outerStart); }\n    inline StorageIndex* innerNonZeroPtr()\n    { return isCompressed() ? 0 : (m_matrix.innerNonZeroPtr()+m_outerStart); }\n\n    bool isCompressed() const { return m_matrix.innerNonZeroPtr()==0; }\n\n    inline Scalar& coeffRef(Index row, Index col)\n    {\n      return m_matrix.coeffRef(row + (IsRowMajor ? m_outerStart : 0), col + (IsRowMajor ? 0 :  m_outerStart));\n    }\n\n    inline const Scalar coeff(Index row, Index col) const\n    {\n      return m_matrix.coeff(row + (IsRowMajor ? m_outerStart : 0), col + (IsRowMajor ? 0 :  m_outerStart));\n    }\n\n    inline const Scalar coeff(Index index) const\n    {\n      return m_matrix.coeff(IsRowMajor ? m_outerStart : index, IsRowMajor ? index :  m_outerStart);\n    }\n\n    const Scalar& lastCoeff() const\n    {\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(sparse_matrix_block_impl);\n      eigen_assert(Base::nonZeros()>0);\n      if(m_matrix.isCompressed())\n        return m_matrix.valuePtr()[m_matrix.outerIndexPtr()[m_outerStart+1]-1];\n      else\n        return m_matrix.valuePtr()[m_matrix.outerIndexPtr()[m_outerStart]+m_matrix.innerNonZeroPtr()[m_outerStart]-1];\n    }\n\n    EIGEN_STRONG_INLINE Index rows() const { return IsRowMajor ? m_outerSize.value() : m_matrix.rows(); }\n    EIGEN_STRONG_INLINE Index cols() const { return IsRowMajor ? m_matrix.cols() : m_outerSize.value(); }\n\n    inline const SparseMatrixType& nestedExpression() const { return m_matrix; }\n    inline SparseMatrixType& nestedExpression() { return m_matrix; }\n    Index startRow() const { return IsRowMajor ? m_outerStart : 0; }\n    Index startCol() const { return IsRowMajor ? 0 : m_outerStart; }\n    Index blockRows() const { return IsRowMajor ? m_outerSize.value() : m_matrix.rows(); }\n    Index blockCols() const { return IsRowMajor ? m_matrix.cols() : m_outerSize.value(); }\n\n  protected:\n\n    typename internal::ref_selector<SparseMatrixType>::non_const_type m_matrix;\n    Index m_outerStart;\n    const internal::variable_if_dynamic<Index, OuterSize> m_outerSize;\n\n};\n\n} // namespace internal\n\ntemplate<typename _Scalar, int _Options, typename _StorageIndex, int BlockRows, int BlockCols>\nclass BlockImpl<SparseMatrix<_Scalar, _Options, _StorageIndex>,BlockRows,BlockCols,true,Sparse>\n  : public internal::sparse_matrix_block_impl<SparseMatrix<_Scalar, _Options, _StorageIndex>,BlockRows,BlockCols>\n{\npublic:\n  typedef _StorageIndex StorageIndex;\n  typedef SparseMatrix<_Scalar, _Options, _StorageIndex> SparseMatrixType;\n  typedef internal::sparse_matrix_block_impl<SparseMatrixType,BlockRows,BlockCols> Base;\n  inline BlockImpl(SparseMatrixType& xpr, Index i)\n    : Base(xpr, i)\n  {}\n\n  inline BlockImpl(SparseMatrixType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols)\n    : Base(xpr, startRow, startCol, blockRows, blockCols)\n  {}\n\n  using Base::operator=;\n};\n\ntemplate<typename _Scalar, int _Options, typename _StorageIndex, int BlockRows, int BlockCols>\nclass BlockImpl<const SparseMatrix<_Scalar, _Options, _StorageIndex>,BlockRows,BlockCols,true,Sparse>\n  : public internal::sparse_matrix_block_impl<const SparseMatrix<_Scalar, _Options, _StorageIndex>,BlockRows,BlockCols>\n{\npublic:\n  typedef _StorageIndex StorageIndex;\n  typedef const SparseMatrix<_Scalar, _Options, _StorageIndex> SparseMatrixType;\n  typedef internal::sparse_matrix_block_impl<SparseMatrixType,BlockRows,BlockCols> Base;\n  inline BlockImpl(SparseMatrixType& xpr, Index i)\n    : Base(xpr, i)\n  {}\n\n  inline BlockImpl(SparseMatrixType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols)\n    : Base(xpr, startRow, startCol, blockRows, blockCols)\n  {}\n\n  using Base::operator=;\nprivate:\n  template<typename Derived> BlockImpl(const SparseMatrixBase<Derived>& xpr, Index i);\n  template<typename Derived> BlockImpl(const SparseMatrixBase<Derived>& xpr);\n};\n\n//----------\n\n/** Generic implementation of sparse Block expression.\n  * Real-only.\n  */\ntemplate<typename XprType, int BlockRows, int BlockCols, bool InnerPanel>\nclass BlockImpl<XprType,BlockRows,BlockCols,InnerPanel,Sparse>\n  : public SparseMatrixBase<Block<XprType,BlockRows,BlockCols,InnerPanel> >, internal::no_assignment_operator\n{\n    typedef Block<XprType, BlockRows, BlockCols, InnerPanel> BlockType;\n    typedef SparseMatrixBase<BlockType> Base;\n    using Base::convert_index;\npublic:\n    enum { IsRowMajor = internal::traits<BlockType>::IsRowMajor };\n    EIGEN_SPARSE_PUBLIC_INTERFACE(BlockType)\n\n    typedef typename internal::remove_all<typename XprType::Nested>::type _MatrixTypeNested;\n\n    /** Column or Row constructor\n      */\n    inline BlockImpl(XprType& xpr, Index i)\n      : m_matrix(xpr),\n        m_startRow( (BlockRows==1) && (BlockCols==XprType::ColsAtCompileTime) ? convert_index(i) : 0),\n        m_startCol( (BlockRows==XprType::RowsAtCompileTime) && (BlockCols==1) ? convert_index(i) : 0),\n        m_blockRows(BlockRows==1 ? 1 : xpr.rows()),\n        m_blockCols(BlockCols==1 ? 1 : xpr.cols())\n    {}\n\n    /** Dynamic-size constructor\n      */\n    inline BlockImpl(XprType& xpr, Index startRow, Index startCol, Index blockRows, Index blockCols)\n      : m_matrix(xpr), m_startRow(convert_index(startRow)), m_startCol(convert_index(startCol)), m_blockRows(convert_index(blockRows)), m_blockCols(convert_index(blockCols))\n    {}\n\n    inline Index rows() const { return m_blockRows.value(); }\n    inline Index cols() const { return m_blockCols.value(); }\n\n    inline Scalar& coeffRef(Index row, Index col)\n    {\n      return m_matrix.coeffRef(row + m_startRow.value(), col + m_startCol.value());\n    }\n\n    inline const Scalar coeff(Index row, Index col) const\n    {\n      return m_matrix.coeff(row + m_startRow.value(), col + m_startCol.value());\n    }\n\n    inline Scalar& coeffRef(Index index)\n    {\n      return m_matrix.coeffRef(m_startRow.value() + (RowsAtCompileTime == 1 ? 0 : index),\n                               m_startCol.value() + (RowsAtCompileTime == 1 ? index : 0));\n    }\n\n    inline const Scalar coeff(Index index) const\n    {\n      return m_matrix.coeff(m_startRow.value() + (RowsAtCompileTime == 1 ? 0 : index),\n                            m_startCol.value() + (RowsAtCompileTime == 1 ? index : 0));\n    }\n\n    inline const XprType& nestedExpression() const { return m_matrix; }\n    inline XprType& nestedExpression() { return m_matrix; }\n    Index startRow() const { return m_startRow.value(); }\n    Index startCol() const { return m_startCol.value(); }\n    Index blockRows() const { return m_blockRows.value(); }\n    Index blockCols() const { return m_blockCols.value(); }\n\n  protected:\n//     friend class internal::GenericSparseBlockInnerIteratorImpl<XprType,BlockRows,BlockCols,InnerPanel>;\n    friend struct internal::unary_evaluator<Block<XprType,BlockRows,BlockCols,InnerPanel>, internal::IteratorBased, Scalar >;\n\n    Index nonZeros() const { return Dynamic; }\n\n    typename internal::ref_selector<XprType>::non_const_type m_matrix;\n    const internal::variable_if_dynamic<Index, XprType::RowsAtCompileTime == 1 ? 0 : Dynamic> m_startRow;\n    const internal::variable_if_dynamic<Index, XprType::ColsAtCompileTime == 1 ? 0 : Dynamic> m_startCol;\n    const internal::variable_if_dynamic<Index, RowsAtCompileTime> m_blockRows;\n    const internal::variable_if_dynamic<Index, ColsAtCompileTime> m_blockCols;\n\n  protected:\n    // Disable assignment with clear error message.\n    // Note that simply removing operator= yields compilation errors with ICC+MSVC\n    template<typename T>\n    BlockImpl& operator=(const T&)\n    {\n      EIGEN_STATIC_ASSERT(sizeof(T)==0, THIS_SPARSE_BLOCK_SUBEXPRESSION_IS_READ_ONLY);\n      return *this;\n    }\n\n};\n\nnamespace internal {\n\ntemplate<typename ArgType, int BlockRows, int BlockCols, bool InnerPanel>\nstruct unary_evaluator<Block<ArgType,BlockRows,BlockCols,InnerPanel>, IteratorBased >\n : public evaluator_base<Block<ArgType,BlockRows,BlockCols,InnerPanel> >\n{\n    class InnerVectorInnerIterator;\n    class OuterVectorInnerIterator;\n  public:\n    typedef Block<ArgType,BlockRows,BlockCols,InnerPanel> XprType;\n    typedef typename XprType::StorageIndex StorageIndex;\n    typedef typename XprType::Scalar Scalar;\n\n    enum {\n      IsRowMajor = XprType::IsRowMajor,\n\n      OuterVector =  (BlockCols==1 && ArgType::IsRowMajor)\n                    | // FIXME | instead of || to please GCC 4.4.0 stupid warning \"suggest parentheses around &&\".\n                      // revert to || as soon as not needed anymore.\n                     (BlockRows==1 && !ArgType::IsRowMajor),\n\n      CoeffReadCost = evaluator<ArgType>::CoeffReadCost,\n      Flags = XprType::Flags\n    };\n\n    typedef typename internal::conditional<OuterVector,OuterVectorInnerIterator,InnerVectorInnerIterator>::type InnerIterator;\n\n    explicit unary_evaluator(const XprType& op)\n      : m_argImpl(op.nestedExpression()), m_block(op)\n    {}\n\n    inline Index nonZerosEstimate() const {\n      const Index nnz = m_block.nonZeros();\n      if(nnz < 0) {\n        // Scale the non-zero estimate for the underlying expression linearly with block size.\n        // Return zero if the underlying block is empty.\n        const Index nested_sz = m_block.nestedExpression().size();        \n        return nested_sz == 0 ? 0 : m_argImpl.nonZerosEstimate() * m_block.size() / nested_sz;\n      }\n      return nnz;\n    }\n\n  protected:\n    typedef typename evaluator<ArgType>::InnerIterator EvalIterator;\n\n    evaluator<ArgType> m_argImpl;\n    const XprType &m_block;\n};\n\ntemplate<typename ArgType, int BlockRows, int BlockCols, bool InnerPanel>\nclass unary_evaluator<Block<ArgType,BlockRows,BlockCols,InnerPanel>, IteratorBased>::InnerVectorInnerIterator\n : public EvalIterator\n{\n  // NOTE MSVC fails to compile if we don't explicitely \"import\" IsRowMajor from unary_evaluator\n  //      because the base class EvalIterator has a private IsRowMajor enum too. (bug #1786)\n  // NOTE We cannot call it IsRowMajor because it would shadow unary_evaluator::IsRowMajor\n  enum { XprIsRowMajor = unary_evaluator::IsRowMajor };\n  const XprType& m_block;\n  Index m_end;\npublic:\n\n  EIGEN_STRONG_INLINE InnerVectorInnerIterator(const unary_evaluator& aEval, Index outer)\n    : EvalIterator(aEval.m_argImpl, outer + (XprIsRowMajor ? aEval.m_block.startRow() : aEval.m_block.startCol())),\n      m_block(aEval.m_block),\n      m_end(XprIsRowMajor ? aEval.m_block.startCol()+aEval.m_block.blockCols() : aEval.m_block.startRow()+aEval.m_block.blockRows())\n  {\n    while( (EvalIterator::operator bool()) && (EvalIterator::index() < (XprIsRowMajor ? m_block.startCol() : m_block.startRow())) )\n      EvalIterator::operator++();\n  }\n\n  inline StorageIndex index() const { return EvalIterator::index() - convert_index<StorageIndex>(XprIsRowMajor ? m_block.startCol() : m_block.startRow()); }\n  inline Index outer()  const { return EvalIterator::outer() - (XprIsRowMajor ? m_block.startRow() : m_block.startCol()); }\n  inline Index row()    const { return EvalIterator::row()   - m_block.startRow(); }\n  inline Index col()    const { return EvalIterator::col()   - m_block.startCol(); }\n\n  inline operator bool() const { return EvalIterator::operator bool() && EvalIterator::index() < m_end; }\n};\n\ntemplate<typename ArgType, int BlockRows, int BlockCols, bool InnerPanel>\nclass unary_evaluator<Block<ArgType,BlockRows,BlockCols,InnerPanel>, IteratorBased>::OuterVectorInnerIterator\n{\n  // NOTE see above\n  enum { XprIsRowMajor = unary_evaluator::IsRowMajor };\n  const unary_evaluator& m_eval;\n  Index m_outerPos;\n  const Index m_innerIndex;\n  Index m_end;\n  EvalIterator m_it;\npublic:\n\n  EIGEN_STRONG_INLINE OuterVectorInnerIterator(const unary_evaluator& aEval, Index outer)\n    : m_eval(aEval),\n      m_outerPos( (XprIsRowMajor ? aEval.m_block.startCol() : aEval.m_block.startRow()) ),\n      m_innerIndex(XprIsRowMajor ? aEval.m_block.startRow() : aEval.m_block.startCol()),\n      m_end(XprIsRowMajor ? aEval.m_block.startCol()+aEval.m_block.blockCols() : aEval.m_block.startRow()+aEval.m_block.blockRows()),\n      m_it(m_eval.m_argImpl, m_outerPos)\n  {\n    EIGEN_UNUSED_VARIABLE(outer);\n    eigen_assert(outer==0);\n\n    while(m_it && m_it.index() < m_innerIndex) ++m_it;\n    if((!m_it) || (m_it.index()!=m_innerIndex))\n      ++(*this);\n  }\n\n  inline StorageIndex index() const { return convert_index<StorageIndex>(m_outerPos - (XprIsRowMajor ? m_eval.m_block.startCol() : m_eval.m_block.startRow())); }\n  inline Index outer()  const { return 0; }\n  inline Index row()    const { return XprIsRowMajor ? 0 : index(); }\n  inline Index col()    const { return XprIsRowMajor ? index() : 0; }\n\n  inline Scalar value() const { return m_it.value(); }\n  inline Scalar& valueRef() { return m_it.valueRef(); }\n\n  inline OuterVectorInnerIterator& operator++()\n  {\n    // search next non-zero entry\n    while(++m_outerPos<m_end)\n    {\n      // Restart iterator at the next inner-vector:\n      m_it.~EvalIterator();\n      ::new (&m_it) EvalIterator(m_eval.m_argImpl, m_outerPos);\n      // search for the key m_innerIndex in the current outer-vector\n      while(m_it && m_it.index() < m_innerIndex) ++m_it;\n      if(m_it && m_it.index()==m_innerIndex) break;\n    }\n    return *this;\n  }\n\n  inline operator bool() const { return m_outerPos < m_end; }\n};\n\ntemplate<typename _Scalar, int _Options, typename _StorageIndex, int BlockRows, int BlockCols>\nstruct unary_evaluator<Block<SparseMatrix<_Scalar, _Options, _StorageIndex>,BlockRows,BlockCols,true>, IteratorBased>\n  : evaluator<SparseCompressedBase<Block<SparseMatrix<_Scalar, _Options, _StorageIndex>,BlockRows,BlockCols,true> > >\n{\n  typedef Block<SparseMatrix<_Scalar, _Options, _StorageIndex>,BlockRows,BlockCols,true> XprType;\n  typedef evaluator<SparseCompressedBase<XprType> > Base;\n  explicit unary_evaluator(const XprType &xpr) : Base(xpr) {}\n};\n\ntemplate<typename _Scalar, int _Options, typename _StorageIndex, int BlockRows, int BlockCols>\nstruct unary_evaluator<Block<const SparseMatrix<_Scalar, _Options, _StorageIndex>,BlockRows,BlockCols,true>, IteratorBased>\n  : evaluator<SparseCompressedBase<Block<const SparseMatrix<_Scalar, _Options, _StorageIndex>,BlockRows,BlockCols,true> > >\n{\n  typedef Block<const SparseMatrix<_Scalar, _Options, _StorageIndex>,BlockRows,BlockCols,true> XprType;\n  typedef evaluator<SparseCompressedBase<XprType> > Base;\n  explicit unary_evaluator(const XprType &xpr) : Base(xpr) {}\n};\n\n} // end namespace internal\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_BLOCK_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseColEtree.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n/* \n \n * NOTE: This file is the modified version of sp_coletree.c file in SuperLU \n \n * -- SuperLU routine (version 3.1) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * August 1, 2008\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n#ifndef SPARSE_COLETREE_H\n#define SPARSE_COLETREE_H\n\nnamespace Eigen {\n\nnamespace internal {\n\n/** Find the root of the tree/set containing the vertex i : Use Path halving */ \ntemplate<typename Index, typename IndexVector>\nIndex etree_find (Index i, IndexVector& pp)\n{\n  Index p = pp(i); // Parent \n  Index gp = pp(p); // Grand parent \n  while (gp != p) \n  {\n    pp(i) = gp; // Parent pointer on find path is changed to former grand parent\n    i = gp; \n    p = pp(i);\n    gp = pp(p);\n  }\n  return p; \n}\n\n/** Compute the column elimination tree of a sparse matrix\n  * \\param mat The matrix in column-major format. \n  * \\param parent The elimination tree\n  * \\param firstRowElt The column index of the first element in each row\n  * \\param perm The permutation to apply to the column of \\b mat\n  */\ntemplate <typename MatrixType, typename IndexVector>\nint coletree(const MatrixType& mat, IndexVector& parent, IndexVector& firstRowElt, typename MatrixType::StorageIndex *perm=0)\n{\n  typedef typename MatrixType::StorageIndex StorageIndex;\n  StorageIndex nc = convert_index<StorageIndex>(mat.cols()); // Number of columns\n  StorageIndex m = convert_index<StorageIndex>(mat.rows());\n  StorageIndex diagSize = (std::min)(nc,m);\n  IndexVector root(nc); // root of subtree of etree \n  root.setZero();\n  IndexVector pp(nc); // disjoint sets \n  pp.setZero(); // Initialize disjoint sets \n  parent.resize(mat.cols());\n  //Compute first nonzero column in each row \n  firstRowElt.resize(m);\n  firstRowElt.setConstant(nc);\n  firstRowElt.segment(0, diagSize).setLinSpaced(diagSize, 0, diagSize-1);\n  bool found_diag;\n  for (StorageIndex col = 0; col < nc; col++)\n  {\n    StorageIndex pcol = col;\n    if(perm) pcol  = perm[col];\n    for (typename MatrixType::InnerIterator it(mat, pcol); it; ++it)\n    { \n      Index row = it.row();\n      firstRowElt(row) = (std::min)(firstRowElt(row), col);\n    }\n  }\n  /* Compute etree by Liu's algorithm for symmetric matrices,\n          except use (firstRowElt[r],c) in place of an edge (r,c) of A.\n    Thus each row clique in A'*A is replaced by a star\n    centered at its first vertex, which has the same fill. */\n  StorageIndex rset, cset, rroot;\n  for (StorageIndex col = 0; col < nc; col++) \n  {\n    found_diag = col>=m;\n    pp(col) = col; \n    cset = col; \n    root(cset) = col; \n    parent(col) = nc; \n    /* The diagonal element is treated here even if it does not exist in the matrix\n     * hence the loop is executed once more */ \n    StorageIndex pcol = col;\n    if(perm) pcol  = perm[col];\n    for (typename MatrixType::InnerIterator it(mat, pcol); it||!found_diag; ++it)\n    { //  A sequence of interleaved find and union is performed \n      Index i = col;\n      if(it) i = it.index();\n      if (i == col) found_diag = true;\n      \n      StorageIndex row = firstRowElt(i);\n      if (row >= col) continue; \n      rset = internal::etree_find(row, pp); // Find the name of the set containing row\n      rroot = root(rset);\n      if (rroot != col) \n      {\n        parent(rroot) = col; \n        pp(cset) = rset; \n        cset = rset; \n        root(cset) = col; \n      }\n    }\n  }\n  return 0;  \n}\n\n/** \n  * Depth-first search from vertex n.  No recursion.\n  * This routine was contributed by Cédric Doucet, CEDRAT Group, Meylan, France.\n*/\ntemplate <typename IndexVector>\nvoid nr_etdfs (typename IndexVector::Scalar n, IndexVector& parent, IndexVector& first_kid, IndexVector& next_kid, IndexVector& post, typename IndexVector::Scalar postnum)\n{\n  typedef typename IndexVector::Scalar StorageIndex;\n  StorageIndex current = n, first, next;\n  while (postnum != n) \n  {\n    // No kid for the current node\n    first = first_kid(current);\n    \n    // no kid for the current node\n    if (first == -1) \n    {\n      // Numbering this node because it has no kid \n      post(current) = postnum++;\n      \n      // looking for the next kid \n      next = next_kid(current); \n      while (next == -1) \n      {\n        // No more kids : back to the parent node\n        current = parent(current); \n        // numbering the parent node \n        post(current) = postnum++;\n        \n        // Get the next kid \n        next = next_kid(current); \n      }\n      // stopping criterion \n      if (postnum == n+1) return; \n      \n      // Updating current node \n      current = next; \n    }\n    else \n    {\n      current = first; \n    }\n  }\n}\n\n\n/**\n  * \\brief Post order a tree \n  * \\param n the number of nodes\n  * \\param parent Input tree\n  * \\param post postordered tree\n  */\ntemplate <typename IndexVector>\nvoid treePostorder(typename IndexVector::Scalar n, IndexVector& parent, IndexVector& post)\n{\n  typedef typename IndexVector::Scalar StorageIndex;\n  IndexVector first_kid, next_kid; // Linked list of children \n  StorageIndex postnum; \n  // Allocate storage for working arrays and results \n  first_kid.resize(n+1); \n  next_kid.setZero(n+1);\n  post.setZero(n+1);\n  \n  // Set up structure describing children\n  first_kid.setConstant(-1); \n  for (StorageIndex v = n-1; v >= 0; v--) \n  {\n    StorageIndex dad = parent(v);\n    next_kid(v) = first_kid(dad); \n    first_kid(dad) = v; \n  }\n  \n  // Depth-first search from dummy root vertex #n\n  postnum = 0; \n  internal::nr_etdfs(n, parent, first_kid, next_kid, post, postnum);\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // SPARSE_COLETREE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseCompressedBase.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_COMPRESSED_BASE_H\n#define EIGEN_SPARSE_COMPRESSED_BASE_H\n\nnamespace Eigen { \n\ntemplate<typename Derived> class SparseCompressedBase;\n  \nnamespace internal {\n\ntemplate<typename Derived>\nstruct traits<SparseCompressedBase<Derived> > : traits<Derived>\n{};\n\n} // end namespace internal\n\n/** \\ingroup SparseCore_Module\n  * \\class SparseCompressedBase\n  * \\brief Common base class for sparse [compressed]-{row|column}-storage format.\n  *\n  * This class defines the common interface for all derived classes implementing the compressed sparse storage format, such as:\n  *  - SparseMatrix\n  *  - Ref<SparseMatrixType,Options>\n  *  - Map<SparseMatrixType>\n  *\n  */\ntemplate<typename Derived>\nclass SparseCompressedBase\n  : public SparseMatrixBase<Derived>\n{\n  public:\n    typedef SparseMatrixBase<Derived> Base;\n    EIGEN_SPARSE_PUBLIC_INTERFACE(SparseCompressedBase)\n    using Base::operator=;\n    using Base::IsRowMajor;\n    \n    class InnerIterator;\n    class ReverseInnerIterator;\n    \n  protected:\n    typedef typename Base::IndexVector IndexVector;\n    Eigen::Map<IndexVector> innerNonZeros() { return Eigen::Map<IndexVector>(innerNonZeroPtr(), isCompressed()?0:derived().outerSize()); }\n    const  Eigen::Map<const IndexVector> innerNonZeros() const { return Eigen::Map<const IndexVector>(innerNonZeroPtr(), isCompressed()?0:derived().outerSize()); }\n        \n  public:\n    \n    /** \\returns the number of non zero coefficients */\n    inline Index nonZeros() const\n    {\n      if(Derived::IsVectorAtCompileTime && outerIndexPtr()==0)\n        return derived().nonZeros();\n      else if(isCompressed())\n        return outerIndexPtr()[derived().outerSize()]-outerIndexPtr()[0];\n      else if(derived().outerSize()==0)\n        return 0;\n      else\n        return innerNonZeros().sum();\n    }\n    \n    /** \\returns a const pointer to the array of values.\n      * This function is aimed at interoperability with other libraries.\n      * \\sa innerIndexPtr(), outerIndexPtr() */\n    inline const Scalar* valuePtr() const { return derived().valuePtr(); }\n    /** \\returns a non-const pointer to the array of values.\n      * This function is aimed at interoperability with other libraries.\n      * \\sa innerIndexPtr(), outerIndexPtr() */\n    inline Scalar* valuePtr() { return derived().valuePtr(); }\n\n    /** \\returns a const pointer to the array of inner indices.\n      * This function is aimed at interoperability with other libraries.\n      * \\sa valuePtr(), outerIndexPtr() */\n    inline const StorageIndex* innerIndexPtr() const { return derived().innerIndexPtr(); }\n    /** \\returns a non-const pointer to the array of inner indices.\n      * This function is aimed at interoperability with other libraries.\n      * \\sa valuePtr(), outerIndexPtr() */\n    inline StorageIndex* innerIndexPtr() { return derived().innerIndexPtr(); }\n\n    /** \\returns a const pointer to the array of the starting positions of the inner vectors.\n      * This function is aimed at interoperability with other libraries.\n      * \\warning it returns the null pointer 0 for SparseVector\n      * \\sa valuePtr(), innerIndexPtr() */\n    inline const StorageIndex* outerIndexPtr() const { return derived().outerIndexPtr(); }\n    /** \\returns a non-const pointer to the array of the starting positions of the inner vectors.\n      * This function is aimed at interoperability with other libraries.\n      * \\warning it returns the null pointer 0 for SparseVector\n      * \\sa valuePtr(), innerIndexPtr() */\n    inline StorageIndex* outerIndexPtr() { return derived().outerIndexPtr(); }\n\n    /** \\returns a const pointer to the array of the number of non zeros of the inner vectors.\n      * This function is aimed at interoperability with other libraries.\n      * \\warning it returns the null pointer 0 in compressed mode */\n    inline const StorageIndex* innerNonZeroPtr() const { return derived().innerNonZeroPtr(); }\n    /** \\returns a non-const pointer to the array of the number of non zeros of the inner vectors.\n      * This function is aimed at interoperability with other libraries.\n      * \\warning it returns the null pointer 0 in compressed mode */\n    inline StorageIndex* innerNonZeroPtr() { return derived().innerNonZeroPtr(); }\n    \n    /** \\returns whether \\c *this is in compressed form. */\n    inline bool isCompressed() const { return innerNonZeroPtr()==0; }\n\n    /** \\returns a read-only view of the stored coefficients as a 1D array expression.\n      *\n      * \\warning this method is for \\b compressed \\b storage \\b only, and it will trigger an assertion otherwise.\n      *\n      * \\sa valuePtr(), isCompressed() */\n    const Map<const Array<Scalar,Dynamic,1> > coeffs() const { eigen_assert(isCompressed()); return Array<Scalar,Dynamic,1>::Map(valuePtr(),nonZeros()); }\n\n    /** \\returns a read-write view of the stored coefficients as a 1D array expression\n      *\n      * \\warning this method is for \\b compressed \\b storage \\b only, and it will trigger an assertion otherwise.\n      *\n      * Here is an example:\n      * \\include SparseMatrix_coeffs.cpp\n      * and the output is:\n      * \\include SparseMatrix_coeffs.out\n      *\n      * \\sa valuePtr(), isCompressed() */\n    Map<Array<Scalar,Dynamic,1> > coeffs() { eigen_assert(isCompressed()); return Array<Scalar,Dynamic,1>::Map(valuePtr(),nonZeros()); }\n\n  protected:\n    /** Default constructor. Do nothing. */\n    SparseCompressedBase() {}\n\n    /** \\internal return the index of the coeff at (row,col) or just before if it does not exist.\n      * This is an analogue of std::lower_bound.\n      */\n    internal::LowerBoundIndex lower_bound(Index row, Index col) const\n    {\n      eigen_internal_assert(row>=0 && row<this->rows() && col>=0 && col<this->cols());\n\n      const Index outer = Derived::IsRowMajor ? row : col;\n      const Index inner = Derived::IsRowMajor ? col : row;\n\n      Index start = this->outerIndexPtr()[outer];\n      Index end = this->isCompressed() ? this->outerIndexPtr()[outer+1] : this->outerIndexPtr()[outer] + this->innerNonZeroPtr()[outer];\n      eigen_assert(end>=start && \"you are using a non finalized sparse matrix or written coefficient does not exist\");\n      internal::LowerBoundIndex p;\n      p.value = std::lower_bound(this->innerIndexPtr()+start, this->innerIndexPtr()+end,inner) - this->innerIndexPtr();\n      p.found = (p.value<end) && (this->innerIndexPtr()[p.value]==inner);\n      return p;\n    }\n\n    friend struct internal::evaluator<SparseCompressedBase<Derived> >;\n\n  private:\n    template<typename OtherDerived> explicit SparseCompressedBase(const SparseCompressedBase<OtherDerived>&);\n};\n\ntemplate<typename Derived>\nclass SparseCompressedBase<Derived>::InnerIterator\n{\n  public:\n    InnerIterator()\n      : m_values(0), m_indices(0), m_outer(0), m_id(0), m_end(0)\n    {}\n\n    InnerIterator(const InnerIterator& other)\n      : m_values(other.m_values), m_indices(other.m_indices), m_outer(other.m_outer), m_id(other.m_id), m_end(other.m_end)\n    {}\n\n    InnerIterator& operator=(const InnerIterator& other)\n    {\n      m_values = other.m_values;\n      m_indices = other.m_indices;\n      const_cast<OuterType&>(m_outer).setValue(other.m_outer.value());\n      m_id = other.m_id;\n      m_end = other.m_end;\n      return *this;\n    }\n\n    InnerIterator(const SparseCompressedBase& mat, Index outer)\n      : m_values(mat.valuePtr()), m_indices(mat.innerIndexPtr()), m_outer(outer)\n    {\n      if(Derived::IsVectorAtCompileTime && mat.outerIndexPtr()==0)\n      {\n        m_id = 0;\n        m_end = mat.nonZeros();\n      }\n      else\n      {\n        m_id = mat.outerIndexPtr()[outer];\n        if(mat.isCompressed())\n          m_end = mat.outerIndexPtr()[outer+1];\n        else\n          m_end = m_id + mat.innerNonZeroPtr()[outer];\n      }\n    }\n\n    explicit InnerIterator(const SparseCompressedBase& mat)\n      : m_values(mat.valuePtr()), m_indices(mat.innerIndexPtr()), m_outer(0), m_id(0), m_end(mat.nonZeros())\n    {\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived);\n    }\n\n    explicit InnerIterator(const internal::CompressedStorage<Scalar,StorageIndex>& data)\n      : m_values(data.valuePtr()), m_indices(data.indexPtr()), m_outer(0), m_id(0), m_end(data.size())\n    {\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived);\n    }\n\n    inline InnerIterator& operator++() { m_id++; return *this; }\n    inline InnerIterator& operator+=(Index i) { m_id += i ; return *this; }\n\n    inline InnerIterator operator+(Index i) \n    { \n        InnerIterator result = *this;\n        result += i;\n        return result;\n    }\n\n    inline const Scalar& value() const { return m_values[m_id]; }\n    inline Scalar& valueRef() { return const_cast<Scalar&>(m_values[m_id]); }\n\n    inline StorageIndex index() const { return m_indices[m_id]; }\n    inline Index outer() const { return m_outer.value(); }\n    inline Index row() const { return IsRowMajor ? m_outer.value() : index(); }\n    inline Index col() const { return IsRowMajor ? index() : m_outer.value(); }\n\n    inline operator bool() const { return (m_id < m_end); }\n\n  protected:\n    const Scalar* m_values;\n    const StorageIndex* m_indices;\n    typedef internal::variable_if_dynamic<Index,Derived::IsVectorAtCompileTime?0:Dynamic> OuterType;\n    const OuterType m_outer;\n    Index m_id;\n    Index m_end;\n  private:\n    // If you get here, then you're not using the right InnerIterator type, e.g.:\n    //   SparseMatrix<double,RowMajor> A;\n    //   SparseMatrix<double>::InnerIterator it(A,0);\n    template<typename T> InnerIterator(const SparseMatrixBase<T>&, Index outer);\n};\n\ntemplate<typename Derived>\nclass SparseCompressedBase<Derived>::ReverseInnerIterator\n{\n  public:\n    ReverseInnerIterator(const SparseCompressedBase& mat, Index outer)\n      : m_values(mat.valuePtr()), m_indices(mat.innerIndexPtr()), m_outer(outer)\n    {\n      if(Derived::IsVectorAtCompileTime && mat.outerIndexPtr()==0)\n      {\n        m_start = 0;\n        m_id = mat.nonZeros();\n      }\n      else\n      {\n        m_start = mat.outerIndexPtr()[outer];\n        if(mat.isCompressed())\n          m_id = mat.outerIndexPtr()[outer+1];\n        else\n          m_id = m_start + mat.innerNonZeroPtr()[outer];\n      }\n    }\n\n    explicit ReverseInnerIterator(const SparseCompressedBase& mat)\n      : m_values(mat.valuePtr()), m_indices(mat.innerIndexPtr()), m_outer(0), m_start(0), m_id(mat.nonZeros())\n    {\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived);\n    }\n\n    explicit ReverseInnerIterator(const internal::CompressedStorage<Scalar,StorageIndex>& data)\n      : m_values(data.valuePtr()), m_indices(data.indexPtr()), m_outer(0), m_start(0), m_id(data.size())\n    {\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived);\n    }\n\n    inline ReverseInnerIterator& operator--() { --m_id; return *this; }\n    inline ReverseInnerIterator& operator-=(Index i) { m_id -= i; return *this; }\n\n    inline ReverseInnerIterator operator-(Index i) \n    {\n        ReverseInnerIterator result = *this;\n        result -= i;\n        return result;\n    }\n\n    inline const Scalar& value() const { return m_values[m_id-1]; }\n    inline Scalar& valueRef() { return const_cast<Scalar&>(m_values[m_id-1]); }\n\n    inline StorageIndex index() const { return m_indices[m_id-1]; }\n    inline Index outer() const { return m_outer.value(); }\n    inline Index row() const { return IsRowMajor ? m_outer.value() : index(); }\n    inline Index col() const { return IsRowMajor ? index() : m_outer.value(); }\n\n    inline operator bool() const { return (m_id > m_start); }\n\n  protected:\n    const Scalar* m_values;\n    const StorageIndex* m_indices;\n    typedef internal::variable_if_dynamic<Index,Derived::IsVectorAtCompileTime?0:Dynamic> OuterType;\n    const OuterType m_outer;\n    Index m_start;\n    Index m_id;\n};\n\nnamespace internal {\n\ntemplate<typename Derived>\nstruct evaluator<SparseCompressedBase<Derived> >\n  : evaluator_base<Derived>\n{\n  typedef typename Derived::Scalar Scalar;\n  typedef typename Derived::InnerIterator InnerIterator;\n  \n  enum {\n    CoeffReadCost = NumTraits<Scalar>::ReadCost,\n    Flags = Derived::Flags\n  };\n  \n  evaluator() : m_matrix(0), m_zero(0)\n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n  explicit evaluator(const Derived &mat) : m_matrix(&mat), m_zero(0)\n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n  \n  inline Index nonZerosEstimate() const {\n    return m_matrix->nonZeros();\n  }\n  \n  operator Derived&() { return m_matrix->const_cast_derived(); }\n  operator const Derived&() const { return *m_matrix; }\n  \n  typedef typename DenseCoeffsBase<Derived,ReadOnlyAccessors>::CoeffReturnType CoeffReturnType;\n  const Scalar& coeff(Index row, Index col) const\n  {\n    Index p = find(row,col);\n\n    if(p==Dynamic)\n      return m_zero;\n    else\n      return m_matrix->const_cast_derived().valuePtr()[p];\n  }\n\n  Scalar& coeffRef(Index row, Index col)\n  {\n    Index p = find(row,col);\n    eigen_assert(p!=Dynamic && \"written coefficient does not exist\");\n    return m_matrix->const_cast_derived().valuePtr()[p];\n  }\n\nprotected:\n\n  Index find(Index row, Index col) const\n  {\n    internal::LowerBoundIndex p = m_matrix->lower_bound(row,col);\n    return p.found ? p.value : Dynamic;\n  }\n\n  const Derived *m_matrix;\n  const Scalar m_zero;\n};\n\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_COMPRESSED_BASE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseCwiseBinaryOp.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_CWISE_BINARY_OP_H\n#define EIGEN_SPARSE_CWISE_BINARY_OP_H\n\nnamespace Eigen { \n\n// Here we have to handle 3 cases:\n//  1 - sparse op dense\n//  2 - dense op sparse\n//  3 - sparse op sparse\n// We also need to implement a 4th iterator for:\n//  4 - dense op dense\n// Finally, we also need to distinguish between the product and other operations :\n//                configuration      returned mode\n//  1 - sparse op dense    product      sparse\n//                         generic      dense\n//  2 - dense op sparse    product      sparse\n//                         generic      dense\n//  3 - sparse op sparse   product      sparse\n//                         generic      sparse\n//  4 - dense op dense     product      dense\n//                         generic      dense\n//\n// TODO to ease compiler job, we could specialize product/quotient with a scalar\n//      and fallback to cwise-unary evaluator using bind1st_op and bind2nd_op.\n\ntemplate<typename BinaryOp, typename Lhs, typename Rhs>\nclass CwiseBinaryOpImpl<BinaryOp, Lhs, Rhs, Sparse>\n  : public SparseMatrixBase<CwiseBinaryOp<BinaryOp, Lhs, Rhs> >\n{\n  public:\n    typedef CwiseBinaryOp<BinaryOp, Lhs, Rhs> Derived;\n    typedef SparseMatrixBase<Derived> Base;\n    EIGEN_SPARSE_PUBLIC_INTERFACE(Derived)\n    CwiseBinaryOpImpl()\n    {\n      EIGEN_STATIC_ASSERT((\n                (!internal::is_same<typename internal::traits<Lhs>::StorageKind,\n                                    typename internal::traits<Rhs>::StorageKind>::value)\n            ||  ((internal::evaluator<Lhs>::Flags&RowMajorBit) == (internal::evaluator<Rhs>::Flags&RowMajorBit))),\n            THE_STORAGE_ORDER_OF_BOTH_SIDES_MUST_MATCH);\n    }\n};\n\nnamespace internal {\n\n  \n// Generic \"sparse OP sparse\"\ntemplate<typename XprType> struct binary_sparse_evaluator;\n\ntemplate<typename BinaryOp, typename Lhs, typename Rhs>\nstruct binary_evaluator<CwiseBinaryOp<BinaryOp, Lhs, Rhs>, IteratorBased, IteratorBased>\n  : evaluator_base<CwiseBinaryOp<BinaryOp, Lhs, Rhs> >\n{\nprotected:\n  typedef typename evaluator<Lhs>::InnerIterator  LhsIterator;\n  typedef typename evaluator<Rhs>::InnerIterator  RhsIterator;\n  typedef CwiseBinaryOp<BinaryOp, Lhs, Rhs> XprType;\n  typedef typename traits<XprType>::Scalar Scalar;\n  typedef typename XprType::StorageIndex StorageIndex;\npublic:\n\n  class InnerIterator\n  {\n  public:\n    \n    EIGEN_STRONG_INLINE InnerIterator(const binary_evaluator& aEval, Index outer)\n      : m_lhsIter(aEval.m_lhsImpl,outer), m_rhsIter(aEval.m_rhsImpl,outer), m_functor(aEval.m_functor)\n    {\n      this->operator++();\n    }\n\n    EIGEN_STRONG_INLINE InnerIterator& operator++()\n    {\n      if (m_lhsIter && m_rhsIter && (m_lhsIter.index() == m_rhsIter.index()))\n      {\n        m_id = m_lhsIter.index();\n        m_value = m_functor(m_lhsIter.value(), m_rhsIter.value());\n        ++m_lhsIter;\n        ++m_rhsIter;\n      }\n      else if (m_lhsIter && (!m_rhsIter || (m_lhsIter.index() < m_rhsIter.index())))\n      {\n        m_id = m_lhsIter.index();\n        m_value = m_functor(m_lhsIter.value(), Scalar(0));\n        ++m_lhsIter;\n      }\n      else if (m_rhsIter && (!m_lhsIter || (m_lhsIter.index() > m_rhsIter.index())))\n      {\n        m_id = m_rhsIter.index();\n        m_value = m_functor(Scalar(0), m_rhsIter.value());\n        ++m_rhsIter;\n      }\n      else\n      {\n        m_value = Scalar(0); // this is to avoid a compilation warning\n        m_id = -1;\n      }\n      return *this;\n    }\n\n    EIGEN_STRONG_INLINE Scalar value() const { return m_value; }\n\n    EIGEN_STRONG_INLINE StorageIndex index() const { return m_id; }\n    EIGEN_STRONG_INLINE Index outer() const { return m_lhsIter.outer(); }\n    EIGEN_STRONG_INLINE Index row() const { return Lhs::IsRowMajor ? m_lhsIter.row() : index(); }\n    EIGEN_STRONG_INLINE Index col() const { return Lhs::IsRowMajor ? index() : m_lhsIter.col(); }\n\n    EIGEN_STRONG_INLINE operator bool() const { return m_id>=0; }\n\n  protected:\n    LhsIterator m_lhsIter;\n    RhsIterator m_rhsIter;\n    const BinaryOp& m_functor;\n    Scalar m_value;\n    StorageIndex m_id;\n  };\n  \n  \n  enum {\n    CoeffReadCost = evaluator<Lhs>::CoeffReadCost + evaluator<Rhs>::CoeffReadCost + functor_traits<BinaryOp>::Cost,\n    Flags = XprType::Flags\n  };\n  \n  explicit binary_evaluator(const XprType& xpr)\n    : m_functor(xpr.functor()),\n      m_lhsImpl(xpr.lhs()), \n      m_rhsImpl(xpr.rhs())  \n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<BinaryOp>::Cost);\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n  \n  inline Index nonZerosEstimate() const {\n    return m_lhsImpl.nonZerosEstimate() + m_rhsImpl.nonZerosEstimate();\n  }\n\nprotected:\n  const BinaryOp m_functor;\n  evaluator<Lhs> m_lhsImpl;\n  evaluator<Rhs> m_rhsImpl;\n};\n\n// dense op sparse\ntemplate<typename BinaryOp, typename Lhs, typename Rhs>\nstruct binary_evaluator<CwiseBinaryOp<BinaryOp, Lhs, Rhs>, IndexBased, IteratorBased>\n  : evaluator_base<CwiseBinaryOp<BinaryOp, Lhs, Rhs> >\n{\nprotected:\n  typedef typename evaluator<Rhs>::InnerIterator  RhsIterator;\n  typedef CwiseBinaryOp<BinaryOp, Lhs, Rhs> XprType;\n  typedef typename traits<XprType>::Scalar Scalar;\n  typedef typename XprType::StorageIndex StorageIndex;\npublic:\n\n  class InnerIterator\n  {\n    enum { IsRowMajor = (int(Rhs::Flags)&RowMajorBit)==RowMajorBit };\n  public:\n\n    EIGEN_STRONG_INLINE InnerIterator(const binary_evaluator& aEval, Index outer)\n      : m_lhsEval(aEval.m_lhsImpl), m_rhsIter(aEval.m_rhsImpl,outer), m_functor(aEval.m_functor), m_value(0), m_id(-1), m_innerSize(aEval.m_expr.rhs().innerSize())\n    {\n      this->operator++();\n    }\n\n    EIGEN_STRONG_INLINE InnerIterator& operator++()\n    {\n      ++m_id;\n      if(m_id<m_innerSize)\n      {\n        Scalar lhsVal = m_lhsEval.coeff(IsRowMajor?m_rhsIter.outer():m_id,\n                                        IsRowMajor?m_id:m_rhsIter.outer());\n        if(m_rhsIter && m_rhsIter.index()==m_id)\n        {\n          m_value = m_functor(lhsVal, m_rhsIter.value());\n          ++m_rhsIter;\n        }\n        else\n          m_value = m_functor(lhsVal, Scalar(0));\n      }\n\n      return *this;\n    }\n\n    EIGEN_STRONG_INLINE Scalar value() const { eigen_internal_assert(m_id<m_innerSize); return m_value; }\n\n    EIGEN_STRONG_INLINE StorageIndex index() const { return m_id; }\n    EIGEN_STRONG_INLINE Index outer() const { return m_rhsIter.outer(); }\n    EIGEN_STRONG_INLINE Index row() const { return IsRowMajor ? m_rhsIter.outer() : m_id; }\n    EIGEN_STRONG_INLINE Index col() const { return IsRowMajor ? m_id : m_rhsIter.outer(); }\n\n    EIGEN_STRONG_INLINE operator bool() const { return m_id<m_innerSize; }\n\n  protected:\n    const evaluator<Lhs> &m_lhsEval;\n    RhsIterator m_rhsIter;\n    const BinaryOp& m_functor;\n    Scalar m_value;\n    StorageIndex m_id;\n    StorageIndex m_innerSize;\n  };\n\n\n  enum {\n    CoeffReadCost = evaluator<Lhs>::CoeffReadCost + evaluator<Rhs>::CoeffReadCost + functor_traits<BinaryOp>::Cost,\n    Flags = XprType::Flags\n  };\n\n  explicit binary_evaluator(const XprType& xpr)\n    : m_functor(xpr.functor()),\n      m_lhsImpl(xpr.lhs()),\n      m_rhsImpl(xpr.rhs()),\n      m_expr(xpr)\n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<BinaryOp>::Cost);\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n\n  inline Index nonZerosEstimate() const {\n    return m_expr.size();\n  }\n\nprotected:\n  const BinaryOp m_functor;\n  evaluator<Lhs> m_lhsImpl;\n  evaluator<Rhs> m_rhsImpl;\n  const XprType &m_expr;\n};\n\n// sparse op dense\ntemplate<typename BinaryOp, typename Lhs, typename Rhs>\nstruct binary_evaluator<CwiseBinaryOp<BinaryOp, Lhs, Rhs>, IteratorBased, IndexBased>\n  : evaluator_base<CwiseBinaryOp<BinaryOp, Lhs, Rhs> >\n{\nprotected:\n  typedef typename evaluator<Lhs>::InnerIterator  LhsIterator;\n  typedef CwiseBinaryOp<BinaryOp, Lhs, Rhs> XprType;\n  typedef typename traits<XprType>::Scalar Scalar;\n  typedef typename XprType::StorageIndex StorageIndex;\npublic:\n\n  class InnerIterator\n  {\n    enum { IsRowMajor = (int(Lhs::Flags)&RowMajorBit)==RowMajorBit };\n  public:\n\n    EIGEN_STRONG_INLINE InnerIterator(const binary_evaluator& aEval, Index outer)\n      : m_lhsIter(aEval.m_lhsImpl,outer), m_rhsEval(aEval.m_rhsImpl), m_functor(aEval.m_functor), m_value(0), m_id(-1), m_innerSize(aEval.m_expr.lhs().innerSize())\n    {\n      this->operator++();\n    }\n\n    EIGEN_STRONG_INLINE InnerIterator& operator++()\n    {\n      ++m_id;\n      if(m_id<m_innerSize)\n      {\n        Scalar rhsVal = m_rhsEval.coeff(IsRowMajor?m_lhsIter.outer():m_id,\n                                        IsRowMajor?m_id:m_lhsIter.outer());\n        if(m_lhsIter && m_lhsIter.index()==m_id)\n        {\n          m_value = m_functor(m_lhsIter.value(), rhsVal);\n          ++m_lhsIter;\n        }\n        else\n          m_value = m_functor(Scalar(0),rhsVal);\n      }\n\n      return *this;\n    }\n\n    EIGEN_STRONG_INLINE Scalar value() const { eigen_internal_assert(m_id<m_innerSize); return m_value; }\n\n    EIGEN_STRONG_INLINE StorageIndex index() const { return m_id; }\n    EIGEN_STRONG_INLINE Index outer() const { return m_lhsIter.outer(); }\n    EIGEN_STRONG_INLINE Index row() const { return IsRowMajor ? m_lhsIter.outer() : m_id; }\n    EIGEN_STRONG_INLINE Index col() const { return IsRowMajor ? m_id : m_lhsIter.outer(); }\n\n    EIGEN_STRONG_INLINE operator bool() const { return m_id<m_innerSize; }\n\n  protected:\n    LhsIterator m_lhsIter;\n    const evaluator<Rhs> &m_rhsEval;\n    const BinaryOp& m_functor;\n    Scalar m_value;\n    StorageIndex m_id;\n    StorageIndex m_innerSize;\n  };\n\n\n  enum {\n    CoeffReadCost = evaluator<Lhs>::CoeffReadCost + evaluator<Rhs>::CoeffReadCost + functor_traits<BinaryOp>::Cost,\n    Flags = XprType::Flags\n  };\n\n  explicit binary_evaluator(const XprType& xpr)\n    : m_functor(xpr.functor()),\n      m_lhsImpl(xpr.lhs()),\n      m_rhsImpl(xpr.rhs()),\n      m_expr(xpr)\n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<BinaryOp>::Cost);\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n\n  inline Index nonZerosEstimate() const {\n    return m_expr.size();\n  }\n\nprotected:\n  const BinaryOp m_functor;\n  evaluator<Lhs> m_lhsImpl;\n  evaluator<Rhs> m_rhsImpl;\n  const XprType &m_expr;\n};\n\ntemplate<typename T,\n         typename LhsKind   = typename evaluator_traits<typename T::Lhs>::Kind,\n         typename RhsKind   = typename evaluator_traits<typename T::Rhs>::Kind,\n         typename LhsScalar = typename traits<typename T::Lhs>::Scalar,\n         typename RhsScalar = typename traits<typename T::Rhs>::Scalar> struct sparse_conjunction_evaluator;\n\n// \"sparse .* sparse\"\ntemplate<typename T1, typename T2, typename Lhs, typename Rhs>\nstruct binary_evaluator<CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs>, IteratorBased, IteratorBased>\n  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs> >\n{\n  typedef CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs> XprType;\n  typedef sparse_conjunction_evaluator<XprType> Base;\n  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}\n};\n// \"dense .* sparse\"\ntemplate<typename T1, typename T2, typename Lhs, typename Rhs>\nstruct binary_evaluator<CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs>, IndexBased, IteratorBased>\n  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs> >\n{\n  typedef CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs> XprType;\n  typedef sparse_conjunction_evaluator<XprType> Base;\n  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}\n};\n// \"sparse .* dense\"\ntemplate<typename T1, typename T2, typename Lhs, typename Rhs>\nstruct binary_evaluator<CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs>, IteratorBased, IndexBased>\n  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs> >\n{\n  typedef CwiseBinaryOp<scalar_product_op<T1,T2>, Lhs, Rhs> XprType;\n  typedef sparse_conjunction_evaluator<XprType> Base;\n  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}\n};\n\n// \"sparse ./ dense\"\ntemplate<typename T1, typename T2, typename Lhs, typename Rhs>\nstruct binary_evaluator<CwiseBinaryOp<scalar_quotient_op<T1,T2>, Lhs, Rhs>, IteratorBased, IndexBased>\n  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_quotient_op<T1,T2>, Lhs, Rhs> >\n{\n  typedef CwiseBinaryOp<scalar_quotient_op<T1,T2>, Lhs, Rhs> XprType;\n  typedef sparse_conjunction_evaluator<XprType> Base;\n  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}\n};\n\n// \"sparse && sparse\"\ntemplate<typename Lhs, typename Rhs>\nstruct binary_evaluator<CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs>, IteratorBased, IteratorBased>\n  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs> >\n{\n  typedef CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs> XprType;\n  typedef sparse_conjunction_evaluator<XprType> Base;\n  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}\n};\n// \"dense && sparse\"\ntemplate<typename Lhs, typename Rhs>\nstruct binary_evaluator<CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs>, IndexBased, IteratorBased>\n  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs> >\n{\n  typedef CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs> XprType;\n  typedef sparse_conjunction_evaluator<XprType> Base;\n  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}\n};\n// \"sparse && dense\"\ntemplate<typename Lhs, typename Rhs>\nstruct binary_evaluator<CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs>, IteratorBased, IndexBased>\n  : sparse_conjunction_evaluator<CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs> >\n{\n  typedef CwiseBinaryOp<scalar_boolean_and_op, Lhs, Rhs> XprType;\n  typedef sparse_conjunction_evaluator<XprType> Base;\n  explicit binary_evaluator(const XprType& xpr) : Base(xpr) {}\n};\n\n// \"sparse ^ sparse\"\ntemplate<typename XprType>\nstruct sparse_conjunction_evaluator<XprType, IteratorBased, IteratorBased>\n  : evaluator_base<XprType>\n{\nprotected:\n  typedef typename XprType::Functor BinaryOp;\n  typedef typename XprType::Lhs LhsArg;\n  typedef typename XprType::Rhs RhsArg;\n  typedef typename evaluator<LhsArg>::InnerIterator  LhsIterator;\n  typedef typename evaluator<RhsArg>::InnerIterator  RhsIterator;\n  typedef typename XprType::StorageIndex StorageIndex;\n  typedef typename traits<XprType>::Scalar Scalar;\npublic:\n\n  class InnerIterator\n  {\n  public:\n    \n    EIGEN_STRONG_INLINE InnerIterator(const sparse_conjunction_evaluator& aEval, Index outer)\n      : m_lhsIter(aEval.m_lhsImpl,outer), m_rhsIter(aEval.m_rhsImpl,outer), m_functor(aEval.m_functor)\n    {\n      while (m_lhsIter && m_rhsIter && (m_lhsIter.index() != m_rhsIter.index()))\n      {\n        if (m_lhsIter.index() < m_rhsIter.index())\n          ++m_lhsIter;\n        else\n          ++m_rhsIter;\n      }\n    }\n\n    EIGEN_STRONG_INLINE InnerIterator& operator++()\n    {\n      ++m_lhsIter;\n      ++m_rhsIter;\n      while (m_lhsIter && m_rhsIter && (m_lhsIter.index() != m_rhsIter.index()))\n      {\n        if (m_lhsIter.index() < m_rhsIter.index())\n          ++m_lhsIter;\n        else\n          ++m_rhsIter;\n      }\n      return *this;\n    }\n    \n    EIGEN_STRONG_INLINE Scalar value() const { return m_functor(m_lhsIter.value(), m_rhsIter.value()); }\n\n    EIGEN_STRONG_INLINE StorageIndex index() const { return m_lhsIter.index(); }\n    EIGEN_STRONG_INLINE Index outer() const { return m_lhsIter.outer(); }\n    EIGEN_STRONG_INLINE Index row() const { return m_lhsIter.row(); }\n    EIGEN_STRONG_INLINE Index col() const { return m_lhsIter.col(); }\n\n    EIGEN_STRONG_INLINE operator bool() const { return (m_lhsIter && m_rhsIter); }\n\n  protected:\n    LhsIterator m_lhsIter;\n    RhsIterator m_rhsIter;\n    const BinaryOp& m_functor;\n  };\n  \n  \n  enum {\n    CoeffReadCost = evaluator<LhsArg>::CoeffReadCost + evaluator<RhsArg>::CoeffReadCost + functor_traits<BinaryOp>::Cost,\n    Flags = XprType::Flags\n  };\n  \n  explicit sparse_conjunction_evaluator(const XprType& xpr)\n    : m_functor(xpr.functor()),\n      m_lhsImpl(xpr.lhs()), \n      m_rhsImpl(xpr.rhs())  \n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<BinaryOp>::Cost);\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n  \n  inline Index nonZerosEstimate() const {\n    return (std::min)(m_lhsImpl.nonZerosEstimate(), m_rhsImpl.nonZerosEstimate());\n  }\n\nprotected:\n  const BinaryOp m_functor;\n  evaluator<LhsArg> m_lhsImpl;\n  evaluator<RhsArg> m_rhsImpl;\n};\n\n// \"dense ^ sparse\"\ntemplate<typename XprType>\nstruct sparse_conjunction_evaluator<XprType, IndexBased, IteratorBased>\n  : evaluator_base<XprType>\n{\nprotected:\n  typedef typename XprType::Functor BinaryOp;\n  typedef typename XprType::Lhs LhsArg;\n  typedef typename XprType::Rhs RhsArg;\n  typedef evaluator<LhsArg> LhsEvaluator;\n  typedef typename evaluator<RhsArg>::InnerIterator  RhsIterator;\n  typedef typename XprType::StorageIndex StorageIndex;\n  typedef typename traits<XprType>::Scalar Scalar;\npublic:\n\n  class InnerIterator\n  {\n    enum { IsRowMajor = (int(RhsArg::Flags)&RowMajorBit)==RowMajorBit };\n\n  public:\n    \n    EIGEN_STRONG_INLINE InnerIterator(const sparse_conjunction_evaluator& aEval, Index outer)\n      : m_lhsEval(aEval.m_lhsImpl), m_rhsIter(aEval.m_rhsImpl,outer), m_functor(aEval.m_functor), m_outer(outer)\n    {}\n\n    EIGEN_STRONG_INLINE InnerIterator& operator++()\n    {\n      ++m_rhsIter;\n      return *this;\n    }\n\n    EIGEN_STRONG_INLINE Scalar value() const\n    { return m_functor(m_lhsEval.coeff(IsRowMajor?m_outer:m_rhsIter.index(),IsRowMajor?m_rhsIter.index():m_outer), m_rhsIter.value()); }\n\n    EIGEN_STRONG_INLINE StorageIndex index() const { return m_rhsIter.index(); }\n    EIGEN_STRONG_INLINE Index outer() const { return m_rhsIter.outer(); }\n    EIGEN_STRONG_INLINE Index row() const { return m_rhsIter.row(); }\n    EIGEN_STRONG_INLINE Index col() const { return m_rhsIter.col(); }\n\n    EIGEN_STRONG_INLINE operator bool() const { return m_rhsIter; }\n    \n  protected:\n    const LhsEvaluator &m_lhsEval;\n    RhsIterator m_rhsIter;\n    const BinaryOp& m_functor;\n    const Index m_outer;\n  };\n  \n  \n  enum {\n    CoeffReadCost = evaluator<LhsArg>::CoeffReadCost + evaluator<RhsArg>::CoeffReadCost + functor_traits<BinaryOp>::Cost,\n    Flags = XprType::Flags\n  };\n  \n  explicit sparse_conjunction_evaluator(const XprType& xpr)\n    : m_functor(xpr.functor()),\n      m_lhsImpl(xpr.lhs()), \n      m_rhsImpl(xpr.rhs())  \n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<BinaryOp>::Cost);\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n  \n  inline Index nonZerosEstimate() const {\n    return m_rhsImpl.nonZerosEstimate();\n  }\n\nprotected:\n  const BinaryOp m_functor;\n  evaluator<LhsArg> m_lhsImpl;\n  evaluator<RhsArg> m_rhsImpl;\n};\n\n// \"sparse ^ dense\"\ntemplate<typename XprType>\nstruct sparse_conjunction_evaluator<XprType, IteratorBased, IndexBased>\n  : evaluator_base<XprType>\n{\nprotected:\n  typedef typename XprType::Functor BinaryOp;\n  typedef typename XprType::Lhs LhsArg;\n  typedef typename XprType::Rhs RhsArg;\n  typedef typename evaluator<LhsArg>::InnerIterator LhsIterator;\n  typedef evaluator<RhsArg> RhsEvaluator;\n  typedef typename XprType::StorageIndex StorageIndex;\n  typedef typename traits<XprType>::Scalar Scalar;\npublic:\n\n  class InnerIterator\n  {\n    enum { IsRowMajor = (int(LhsArg::Flags)&RowMajorBit)==RowMajorBit };\n\n  public:\n    \n    EIGEN_STRONG_INLINE InnerIterator(const sparse_conjunction_evaluator& aEval, Index outer)\n      : m_lhsIter(aEval.m_lhsImpl,outer), m_rhsEval(aEval.m_rhsImpl), m_functor(aEval.m_functor), m_outer(outer)\n    {}\n\n    EIGEN_STRONG_INLINE InnerIterator& operator++()\n    {\n      ++m_lhsIter;\n      return *this;\n    }\n\n    EIGEN_STRONG_INLINE Scalar value() const\n    { return m_functor(m_lhsIter.value(),\n                       m_rhsEval.coeff(IsRowMajor?m_outer:m_lhsIter.index(),IsRowMajor?m_lhsIter.index():m_outer)); }\n\n    EIGEN_STRONG_INLINE StorageIndex index() const { return m_lhsIter.index(); }\n    EIGEN_STRONG_INLINE Index outer() const { return m_lhsIter.outer(); }\n    EIGEN_STRONG_INLINE Index row() const { return m_lhsIter.row(); }\n    EIGEN_STRONG_INLINE Index col() const { return m_lhsIter.col(); }\n\n    EIGEN_STRONG_INLINE operator bool() const { return m_lhsIter; }\n    \n  protected:\n    LhsIterator m_lhsIter;\n    const evaluator<RhsArg> &m_rhsEval;\n    const BinaryOp& m_functor;\n    const Index m_outer;\n  };\n  \n  \n  enum {\n    CoeffReadCost = evaluator<LhsArg>::CoeffReadCost + evaluator<RhsArg>::CoeffReadCost + functor_traits<BinaryOp>::Cost,\n    Flags = XprType::Flags\n  };\n  \n  explicit sparse_conjunction_evaluator(const XprType& xpr)\n    : m_functor(xpr.functor()),\n      m_lhsImpl(xpr.lhs()), \n      m_rhsImpl(xpr.rhs())  \n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<BinaryOp>::Cost);\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n  \n  inline Index nonZerosEstimate() const {\n    return m_lhsImpl.nonZerosEstimate();\n  }\n\nprotected:\n  const BinaryOp m_functor;\n  evaluator<LhsArg> m_lhsImpl;\n  evaluator<RhsArg> m_rhsImpl;\n};\n\n}\n\n/***************************************************************************\n* Implementation of SparseMatrixBase and SparseCwise functions/operators\n***************************************************************************/\n\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\nDerived& SparseMatrixBase<Derived>::operator+=(const EigenBase<OtherDerived> &other)\n{\n  call_assignment(derived(), other.derived(), internal::add_assign_op<Scalar,typename OtherDerived::Scalar>());\n  return derived();\n}\n\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\nDerived& SparseMatrixBase<Derived>::operator-=(const EigenBase<OtherDerived> &other)\n{\n  call_assignment(derived(), other.derived(), internal::assign_op<Scalar,typename OtherDerived::Scalar>());\n  return derived();\n}\n\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\nEIGEN_STRONG_INLINE Derived &\nSparseMatrixBase<Derived>::operator-=(const SparseMatrixBase<OtherDerived> &other)\n{\n  return derived() = derived() - other.derived();\n}\n\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\nEIGEN_STRONG_INLINE Derived &\nSparseMatrixBase<Derived>::operator+=(const SparseMatrixBase<OtherDerived>& other)\n{\n  return derived() = derived() + other.derived();\n}\n\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\nDerived& SparseMatrixBase<Derived>::operator+=(const DiagonalBase<OtherDerived>& other)\n{\n  call_assignment_no_alias(derived(), other.derived(), internal::add_assign_op<Scalar,typename OtherDerived::Scalar>());\n  return derived();\n}\n\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\nDerived& SparseMatrixBase<Derived>::operator-=(const DiagonalBase<OtherDerived>& other)\n{\n  call_assignment_no_alias(derived(), other.derived(), internal::sub_assign_op<Scalar,typename OtherDerived::Scalar>());\n  return derived();\n}\n    \ntemplate<typename Derived>\ntemplate<typename OtherDerived>\nEIGEN_STRONG_INLINE const typename SparseMatrixBase<Derived>::template CwiseProductDenseReturnType<OtherDerived>::Type\nSparseMatrixBase<Derived>::cwiseProduct(const MatrixBase<OtherDerived> &other) const\n{\n  return typename CwiseProductDenseReturnType<OtherDerived>::Type(derived(), other.derived());\n}\n\ntemplate<typename DenseDerived, typename SparseDerived>\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_sum_op<typename DenseDerived::Scalar,typename SparseDerived::Scalar>, const DenseDerived, const SparseDerived>\noperator+(const MatrixBase<DenseDerived> &a, const SparseMatrixBase<SparseDerived> &b)\n{\n  return CwiseBinaryOp<internal::scalar_sum_op<typename DenseDerived::Scalar,typename SparseDerived::Scalar>, const DenseDerived, const SparseDerived>(a.derived(), b.derived());\n}\n\ntemplate<typename SparseDerived, typename DenseDerived>\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_sum_op<typename SparseDerived::Scalar,typename DenseDerived::Scalar>, const SparseDerived, const DenseDerived>\noperator+(const SparseMatrixBase<SparseDerived> &a, const MatrixBase<DenseDerived> &b)\n{\n  return CwiseBinaryOp<internal::scalar_sum_op<typename SparseDerived::Scalar,typename DenseDerived::Scalar>, const SparseDerived, const DenseDerived>(a.derived(), b.derived());\n}\n\ntemplate<typename DenseDerived, typename SparseDerived>\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_difference_op<typename DenseDerived::Scalar,typename SparseDerived::Scalar>, const DenseDerived, const SparseDerived>\noperator-(const MatrixBase<DenseDerived> &a, const SparseMatrixBase<SparseDerived> &b)\n{\n  return CwiseBinaryOp<internal::scalar_difference_op<typename DenseDerived::Scalar,typename SparseDerived::Scalar>, const DenseDerived, const SparseDerived>(a.derived(), b.derived());\n}\n\ntemplate<typename SparseDerived, typename DenseDerived>\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_difference_op<typename SparseDerived::Scalar,typename DenseDerived::Scalar>, const SparseDerived, const DenseDerived>\noperator-(const SparseMatrixBase<SparseDerived> &a, const MatrixBase<DenseDerived> &b)\n{\n  return CwiseBinaryOp<internal::scalar_difference_op<typename SparseDerived::Scalar,typename DenseDerived::Scalar>, const SparseDerived, const DenseDerived>(a.derived(), b.derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_CWISE_BINARY_OP_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseCwiseUnaryOp.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_CWISE_UNARY_OP_H\n#define EIGEN_SPARSE_CWISE_UNARY_OP_H\n\nnamespace Eigen { \n\nnamespace internal {\n  \ntemplate<typename UnaryOp, typename ArgType>\nstruct unary_evaluator<CwiseUnaryOp<UnaryOp,ArgType>, IteratorBased>\n  : public evaluator_base<CwiseUnaryOp<UnaryOp,ArgType> >\n{\n  public:\n    typedef CwiseUnaryOp<UnaryOp, ArgType> XprType;\n\n    class InnerIterator;\n    \n    enum {\n      CoeffReadCost = evaluator<ArgType>::CoeffReadCost + functor_traits<UnaryOp>::Cost,\n      Flags = XprType::Flags\n    };\n    \n    explicit unary_evaluator(const XprType& op) : m_functor(op.functor()), m_argImpl(op.nestedExpression())\n    {\n      EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<UnaryOp>::Cost);\n      EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n    }\n    \n    inline Index nonZerosEstimate() const {\n      return m_argImpl.nonZerosEstimate();\n    }\n\n  protected:\n    typedef typename evaluator<ArgType>::InnerIterator        EvalIterator;\n    \n    const UnaryOp m_functor;\n    evaluator<ArgType> m_argImpl;\n};\n\ntemplate<typename UnaryOp, typename ArgType>\nclass unary_evaluator<CwiseUnaryOp<UnaryOp,ArgType>, IteratorBased>::InnerIterator\n    : public unary_evaluator<CwiseUnaryOp<UnaryOp,ArgType>, IteratorBased>::EvalIterator\n{\n  protected:\n    typedef typename XprType::Scalar Scalar;\n    typedef typename unary_evaluator<CwiseUnaryOp<UnaryOp,ArgType>, IteratorBased>::EvalIterator Base;\n  public:\n\n    EIGEN_STRONG_INLINE InnerIterator(const unary_evaluator& unaryOp, Index outer)\n      : Base(unaryOp.m_argImpl,outer), m_functor(unaryOp.m_functor)\n    {}\n\n    EIGEN_STRONG_INLINE InnerIterator& operator++()\n    { Base::operator++(); return *this; }\n\n    EIGEN_STRONG_INLINE Scalar value() const { return m_functor(Base::value()); }\n\n  protected:\n    const UnaryOp m_functor;\n  private:\n    Scalar& valueRef();\n};\n\ntemplate<typename ViewOp, typename ArgType>\nstruct unary_evaluator<CwiseUnaryView<ViewOp,ArgType>, IteratorBased>\n  : public evaluator_base<CwiseUnaryView<ViewOp,ArgType> >\n{\n  public:\n    typedef CwiseUnaryView<ViewOp, ArgType> XprType;\n\n    class InnerIterator;\n    \n    enum {\n      CoeffReadCost = evaluator<ArgType>::CoeffReadCost + functor_traits<ViewOp>::Cost,\n      Flags = XprType::Flags\n    };\n    \n    explicit unary_evaluator(const XprType& op) : m_functor(op.functor()), m_argImpl(op.nestedExpression())\n    {\n      EIGEN_INTERNAL_CHECK_COST_VALUE(functor_traits<ViewOp>::Cost);\n      EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n    }\n\n  protected:\n    typedef typename evaluator<ArgType>::InnerIterator        EvalIterator;\n    \n    const ViewOp m_functor;\n    evaluator<ArgType> m_argImpl;\n};\n\ntemplate<typename ViewOp, typename ArgType>\nclass unary_evaluator<CwiseUnaryView<ViewOp,ArgType>, IteratorBased>::InnerIterator\n    : public unary_evaluator<CwiseUnaryView<ViewOp,ArgType>, IteratorBased>::EvalIterator\n{\n  protected:\n    typedef typename XprType::Scalar Scalar;\n    typedef typename unary_evaluator<CwiseUnaryView<ViewOp,ArgType>, IteratorBased>::EvalIterator Base;\n  public:\n\n    EIGEN_STRONG_INLINE InnerIterator(const unary_evaluator& unaryOp, Index outer)\n      : Base(unaryOp.m_argImpl,outer), m_functor(unaryOp.m_functor)\n    {}\n\n    EIGEN_STRONG_INLINE InnerIterator& operator++()\n    { Base::operator++(); return *this; }\n\n    EIGEN_STRONG_INLINE Scalar value() const { return m_functor(Base::value()); }\n    EIGEN_STRONG_INLINE Scalar& valueRef() { return m_functor(Base::valueRef()); }\n\n  protected:\n    const ViewOp m_functor;\n};\n\n} // end namespace internal\n\ntemplate<typename Derived>\nEIGEN_STRONG_INLINE Derived&\nSparseMatrixBase<Derived>::operator*=(const Scalar& other)\n{\n  typedef typename internal::evaluator<Derived>::InnerIterator EvalIterator;\n  internal::evaluator<Derived> thisEval(derived());\n  for (Index j=0; j<outerSize(); ++j)\n    for (EvalIterator i(thisEval,j); i; ++i)\n      i.valueRef() *= other;\n  return derived();\n}\n\ntemplate<typename Derived>\nEIGEN_STRONG_INLINE Derived&\nSparseMatrixBase<Derived>::operator/=(const Scalar& other)\n{\n  typedef typename internal::evaluator<Derived>::InnerIterator EvalIterator;\n  internal::evaluator<Derived> thisEval(derived());\n  for (Index j=0; j<outerSize(); ++j)\n    for (EvalIterator i(thisEval,j); i; ++i)\n      i.valueRef() /= other;\n  return derived();\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_CWISE_UNARY_OP_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseDenseProduct.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEDENSEPRODUCT_H\n#define EIGEN_SPARSEDENSEPRODUCT_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate <> struct product_promote_storage_type<Sparse,Dense, OuterProduct> { typedef Sparse ret; };\ntemplate <> struct product_promote_storage_type<Dense,Sparse, OuterProduct> { typedef Sparse ret; };\n\ntemplate<typename SparseLhsType, typename DenseRhsType, typename DenseResType,\n         typename AlphaType,\n         int LhsStorageOrder = ((SparseLhsType::Flags&RowMajorBit)==RowMajorBit) ? RowMajor : ColMajor,\n         bool ColPerCol = ((DenseRhsType::Flags&RowMajorBit)==0) || DenseRhsType::ColsAtCompileTime==1>\nstruct sparse_time_dense_product_impl;\n\ntemplate<typename SparseLhsType, typename DenseRhsType, typename DenseResType>\nstruct sparse_time_dense_product_impl<SparseLhsType,DenseRhsType,DenseResType, typename DenseResType::Scalar, RowMajor, true>\n{\n  typedef typename internal::remove_all<SparseLhsType>::type Lhs;\n  typedef typename internal::remove_all<DenseRhsType>::type Rhs;\n  typedef typename internal::remove_all<DenseResType>::type Res;\n  typedef typename evaluator<Lhs>::InnerIterator LhsInnerIterator;\n  typedef evaluator<Lhs> LhsEval;\n  static void run(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const typename Res::Scalar& alpha)\n  {\n    LhsEval lhsEval(lhs);\n    \n    Index n = lhs.outerSize();\n#ifdef EIGEN_HAS_OPENMP\n    Eigen::initParallel();\n    Index threads = Eigen::nbThreads();\n#endif\n    \n    for(Index c=0; c<rhs.cols(); ++c)\n    {\n#ifdef EIGEN_HAS_OPENMP\n      // This 20000 threshold has been found experimentally on 2D and 3D Poisson problems.\n      // It basically represents the minimal amount of work to be done to be worth it.\n      if(threads>1 && lhsEval.nonZerosEstimate() > 20000)\n      {\n        #pragma omp parallel for schedule(dynamic,(n+threads*4-1)/(threads*4)) num_threads(threads)\n        for(Index i=0; i<n; ++i)\n          processRow(lhsEval,rhs,res,alpha,i,c);\n      }\n      else\n#endif\n      {\n        for(Index i=0; i<n; ++i)\n          processRow(lhsEval,rhs,res,alpha,i,c);\n      }\n    }\n  }\n  \n  static void processRow(const LhsEval& lhsEval, const DenseRhsType& rhs, DenseResType& res, const typename Res::Scalar& alpha, Index i, Index col)\n  {\n    typename Res::Scalar tmp(0);\n    for(LhsInnerIterator it(lhsEval,i); it ;++it)\n      tmp += it.value() * rhs.coeff(it.index(),col);\n    res.coeffRef(i,col) += alpha * tmp;\n  }\n  \n};\n\n// FIXME: what is the purpose of the following specialization? Is it for the BlockedSparse format?\n// -> let's disable it for now as it is conflicting with generic scalar*matrix and matrix*scalar operators\n// template<typename T1, typename T2/*, int _Options, typename _StrideType*/>\n// struct ScalarBinaryOpTraits<T1, Ref<T2/*, _Options, _StrideType*/> >\n// {\n//   enum {\n//     Defined = 1\n//   };\n//   typedef typename CwiseUnaryOp<scalar_multiple2_op<T1, typename T2::Scalar>, T2>::PlainObject ReturnType;\n// };\n\ntemplate<typename SparseLhsType, typename DenseRhsType, typename DenseResType, typename AlphaType>\nstruct sparse_time_dense_product_impl<SparseLhsType,DenseRhsType,DenseResType, AlphaType, ColMajor, true>\n{\n  typedef typename internal::remove_all<SparseLhsType>::type Lhs;\n  typedef typename internal::remove_all<DenseRhsType>::type Rhs;\n  typedef typename internal::remove_all<DenseResType>::type Res;\n  typedef evaluator<Lhs> LhsEval;\n  typedef typename LhsEval::InnerIterator LhsInnerIterator;\n  static void run(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const AlphaType& alpha)\n  {\n    LhsEval lhsEval(lhs);\n    for(Index c=0; c<rhs.cols(); ++c)\n    {\n      for(Index j=0; j<lhs.outerSize(); ++j)\n      {\n//        typename Res::Scalar rhs_j = alpha * rhs.coeff(j,c);\n        typename ScalarBinaryOpTraits<AlphaType, typename Rhs::Scalar>::ReturnType rhs_j(alpha * rhs.coeff(j,c));\n        for(LhsInnerIterator it(lhsEval,j); it ;++it)\n          res.coeffRef(it.index(),c) += it.value() * rhs_j;\n      }\n    }\n  }\n};\n\ntemplate<typename SparseLhsType, typename DenseRhsType, typename DenseResType>\nstruct sparse_time_dense_product_impl<SparseLhsType,DenseRhsType,DenseResType, typename DenseResType::Scalar, RowMajor, false>\n{\n  typedef typename internal::remove_all<SparseLhsType>::type Lhs;\n  typedef typename internal::remove_all<DenseRhsType>::type Rhs;\n  typedef typename internal::remove_all<DenseResType>::type Res;\n  typedef evaluator<Lhs> LhsEval;\n  typedef typename LhsEval::InnerIterator LhsInnerIterator;\n  static void run(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const typename Res::Scalar& alpha)\n  {\n    Index n = lhs.rows();\n    LhsEval lhsEval(lhs);\n\n#ifdef EIGEN_HAS_OPENMP\n    Eigen::initParallel();\n    Index threads = Eigen::nbThreads();\n    // This 20000 threshold has been found experimentally on 2D and 3D Poisson problems.\n    // It basically represents the minimal amount of work to be done to be worth it.\n    if(threads>1 && lhsEval.nonZerosEstimate()*rhs.cols() > 20000)\n    {\n      #pragma omp parallel for schedule(dynamic,(n+threads*4-1)/(threads*4)) num_threads(threads)\n      for(Index i=0; i<n; ++i)\n        processRow(lhsEval,rhs,res,alpha,i);\n    }\n    else\n#endif\n    {\n      for(Index i=0; i<n; ++i)\n        processRow(lhsEval, rhs, res, alpha, i);\n    }\n  }\n\n  static void processRow(const LhsEval& lhsEval, const DenseRhsType& rhs, Res& res, const typename Res::Scalar& alpha, Index i)\n  {\n    typename Res::RowXpr res_i(res.row(i));\n    for(LhsInnerIterator it(lhsEval,i); it ;++it)\n      res_i += (alpha*it.value()) * rhs.row(it.index());\n  }\n};\n\ntemplate<typename SparseLhsType, typename DenseRhsType, typename DenseResType>\nstruct sparse_time_dense_product_impl<SparseLhsType,DenseRhsType,DenseResType, typename DenseResType::Scalar, ColMajor, false>\n{\n  typedef typename internal::remove_all<SparseLhsType>::type Lhs;\n  typedef typename internal::remove_all<DenseRhsType>::type Rhs;\n  typedef typename internal::remove_all<DenseResType>::type Res;\n  typedef typename evaluator<Lhs>::InnerIterator LhsInnerIterator;\n  static void run(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const typename Res::Scalar& alpha)\n  {\n    evaluator<Lhs> lhsEval(lhs);\n    for(Index j=0; j<lhs.outerSize(); ++j)\n    {\n      typename Rhs::ConstRowXpr rhs_j(rhs.row(j));\n      for(LhsInnerIterator it(lhsEval,j); it ;++it)\n        res.row(it.index()) += (alpha*it.value()) * rhs_j;\n    }\n  }\n};\n\ntemplate<typename SparseLhsType, typename DenseRhsType, typename DenseResType,typename AlphaType>\ninline void sparse_time_dense_product(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const AlphaType& alpha)\n{\n  sparse_time_dense_product_impl<SparseLhsType,DenseRhsType,DenseResType, AlphaType>::run(lhs, rhs, res, alpha);\n}\n\n} // end namespace internal\n\nnamespace internal {\n\ntemplate<typename Lhs, typename Rhs, int ProductType>\nstruct generic_product_impl<Lhs, Rhs, SparseShape, DenseShape, ProductType>\n : generic_product_impl_base<Lhs,Rhs,generic_product_impl<Lhs,Rhs,SparseShape,DenseShape,ProductType> >\n{\n  typedef typename Product<Lhs,Rhs>::Scalar Scalar;\n  \n  template<typename Dest>\n  static void scaleAndAddTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha)\n  {\n    typedef typename nested_eval<Lhs,((Rhs::Flags&RowMajorBit)==0) ? 1 : Rhs::ColsAtCompileTime>::type LhsNested;\n    typedef typename nested_eval<Rhs,((Lhs::Flags&RowMajorBit)==0) ? 1 : Dynamic>::type RhsNested;\n    LhsNested lhsNested(lhs);\n    RhsNested rhsNested(rhs);\n    internal::sparse_time_dense_product(lhsNested, rhsNested, dst, alpha);\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, int ProductType>\nstruct generic_product_impl<Lhs, Rhs, SparseTriangularShape, DenseShape, ProductType>\n  : generic_product_impl<Lhs, Rhs, SparseShape, DenseShape, ProductType>\n{};\n\ntemplate<typename Lhs, typename Rhs, int ProductType>\nstruct generic_product_impl<Lhs, Rhs, DenseShape, SparseShape, ProductType>\n  : generic_product_impl_base<Lhs,Rhs,generic_product_impl<Lhs,Rhs,DenseShape,SparseShape,ProductType> >\n{\n  typedef typename Product<Lhs,Rhs>::Scalar Scalar;\n  \n  template<typename Dst>\n  static void scaleAndAddTo(Dst& dst, const Lhs& lhs, const Rhs& rhs, const Scalar& alpha)\n  {\n    typedef typename nested_eval<Lhs,((Rhs::Flags&RowMajorBit)==0) ? Dynamic : 1>::type LhsNested;\n    typedef typename nested_eval<Rhs,((Lhs::Flags&RowMajorBit)==RowMajorBit) ? 1 : Lhs::RowsAtCompileTime>::type RhsNested;\n    LhsNested lhsNested(lhs);\n    RhsNested rhsNested(rhs);\n    \n    // transpose everything\n    Transpose<Dst> dstT(dst);\n    internal::sparse_time_dense_product(rhsNested.transpose(), lhsNested.transpose(), dstT, alpha);\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, int ProductType>\nstruct generic_product_impl<Lhs, Rhs, DenseShape, SparseTriangularShape, ProductType>\n  : generic_product_impl<Lhs, Rhs, DenseShape, SparseShape, ProductType>\n{};\n\ntemplate<typename LhsT, typename RhsT, bool NeedToTranspose>\nstruct sparse_dense_outer_product_evaluator\n{\nprotected:\n  typedef typename conditional<NeedToTranspose,RhsT,LhsT>::type Lhs1;\n  typedef typename conditional<NeedToTranspose,LhsT,RhsT>::type ActualRhs;\n  typedef Product<LhsT,RhsT,DefaultProduct> ProdXprType;\n  \n  // if the actual left-hand side is a dense vector,\n  // then build a sparse-view so that we can seamlessly iterate over it.\n  typedef typename conditional<is_same<typename internal::traits<Lhs1>::StorageKind,Sparse>::value,\n            Lhs1, SparseView<Lhs1> >::type ActualLhs;\n  typedef typename conditional<is_same<typename internal::traits<Lhs1>::StorageKind,Sparse>::value,\n            Lhs1 const&, SparseView<Lhs1> >::type LhsArg;\n            \n  typedef evaluator<ActualLhs> LhsEval;\n  typedef evaluator<ActualRhs> RhsEval;\n  typedef typename evaluator<ActualLhs>::InnerIterator LhsIterator;\n  typedef typename ProdXprType::Scalar Scalar;\n  \npublic:\n  enum {\n    Flags = NeedToTranspose ? RowMajorBit : 0,\n    CoeffReadCost = HugeCost\n  };\n  \n  class InnerIterator : public LhsIterator\n  {\n  public:\n    InnerIterator(const sparse_dense_outer_product_evaluator &xprEval, Index outer)\n      : LhsIterator(xprEval.m_lhsXprImpl, 0),\n        m_outer(outer),\n        m_empty(false),\n        m_factor(get(xprEval.m_rhsXprImpl, outer, typename internal::traits<ActualRhs>::StorageKind() ))\n    {}\n    \n    EIGEN_STRONG_INLINE Index outer() const { return m_outer; }\n    EIGEN_STRONG_INLINE Index row()   const { return NeedToTranspose ? m_outer : LhsIterator::index(); }\n    EIGEN_STRONG_INLINE Index col()   const { return NeedToTranspose ? LhsIterator::index() : m_outer; }\n\n    EIGEN_STRONG_INLINE Scalar value() const { return LhsIterator::value() * m_factor; }\n    EIGEN_STRONG_INLINE operator bool() const { return LhsIterator::operator bool() && (!m_empty); }\n    \n  protected:\n    Scalar get(const RhsEval &rhs, Index outer, Dense = Dense()) const\n    {\n      return rhs.coeff(outer);\n    }\n    \n    Scalar get(const RhsEval &rhs, Index outer, Sparse = Sparse())\n    {\n      typename RhsEval::InnerIterator it(rhs, outer);\n      if (it && it.index()==0 && it.value()!=Scalar(0))\n        return it.value();\n      m_empty = true;\n      return Scalar(0);\n    }\n    \n    Index m_outer;\n    bool m_empty;\n    Scalar m_factor;\n  };\n  \n  sparse_dense_outer_product_evaluator(const Lhs1 &lhs, const ActualRhs &rhs)\n     : m_lhs(lhs), m_lhsXprImpl(m_lhs), m_rhsXprImpl(rhs)\n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n  \n  // transpose case\n  sparse_dense_outer_product_evaluator(const ActualRhs &rhs, const Lhs1 &lhs)\n     : m_lhs(lhs), m_lhsXprImpl(m_lhs), m_rhsXprImpl(rhs)\n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n    \nprotected:\n  const LhsArg m_lhs;\n  evaluator<ActualLhs> m_lhsXprImpl;\n  evaluator<ActualRhs> m_rhsXprImpl;\n};\n\n// sparse * dense outer product\ntemplate<typename Lhs, typename Rhs>\nstruct product_evaluator<Product<Lhs, Rhs, DefaultProduct>, OuterProduct, SparseShape, DenseShape>\n  : sparse_dense_outer_product_evaluator<Lhs,Rhs, Lhs::IsRowMajor>\n{\n  typedef sparse_dense_outer_product_evaluator<Lhs,Rhs, Lhs::IsRowMajor> Base;\n  \n  typedef Product<Lhs, Rhs> XprType;\n  typedef typename XprType::PlainObject PlainObject;\n\n  explicit product_evaluator(const XprType& xpr)\n    : Base(xpr.lhs(), xpr.rhs())\n  {}\n  \n};\n\ntemplate<typename Lhs, typename Rhs>\nstruct product_evaluator<Product<Lhs, Rhs, DefaultProduct>, OuterProduct, DenseShape, SparseShape>\n  : sparse_dense_outer_product_evaluator<Lhs,Rhs, Rhs::IsRowMajor>\n{\n  typedef sparse_dense_outer_product_evaluator<Lhs,Rhs, Rhs::IsRowMajor> Base;\n  \n  typedef Product<Lhs, Rhs> XprType;\n  typedef typename XprType::PlainObject PlainObject;\n\n  explicit product_evaluator(const XprType& xpr)\n    : Base(xpr.lhs(), xpr.rhs())\n  {}\n  \n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSEDENSEPRODUCT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseDiagonalProduct.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_DIAGONAL_PRODUCT_H\n#define EIGEN_SPARSE_DIAGONAL_PRODUCT_H\n\nnamespace Eigen { \n\n// The product of a diagonal matrix with a sparse matrix can be easily\n// implemented using expression template.\n// We have two consider very different cases:\n// 1 - diag * row-major sparse\n//     => each inner vector <=> scalar * sparse vector product\n//     => so we can reuse CwiseUnaryOp::InnerIterator\n// 2 - diag * col-major sparse\n//     => each inner vector <=> densevector * sparse vector cwise product\n//     => again, we can reuse specialization of CwiseBinaryOp::InnerIterator\n//        for that particular case\n// The two other cases are symmetric.\n\nnamespace internal {\n\nenum {\n  SDP_AsScalarProduct,\n  SDP_AsCwiseProduct\n};\n  \ntemplate<typename SparseXprType, typename DiagonalCoeffType, int SDP_Tag>\nstruct sparse_diagonal_product_evaluator;\n\ntemplate<typename Lhs, typename Rhs, int ProductTag>\nstruct product_evaluator<Product<Lhs, Rhs, DefaultProduct>, ProductTag, DiagonalShape, SparseShape>\n  : public sparse_diagonal_product_evaluator<Rhs, typename Lhs::DiagonalVectorType, Rhs::Flags&RowMajorBit?SDP_AsScalarProduct:SDP_AsCwiseProduct>\n{\n  typedef Product<Lhs, Rhs, DefaultProduct> XprType;\n  enum { CoeffReadCost = HugeCost, Flags = Rhs::Flags&RowMajorBit, Alignment = 0 }; // FIXME CoeffReadCost & Flags\n  \n  typedef sparse_diagonal_product_evaluator<Rhs, typename Lhs::DiagonalVectorType, Rhs::Flags&RowMajorBit?SDP_AsScalarProduct:SDP_AsCwiseProduct> Base;\n  explicit product_evaluator(const XprType& xpr) : Base(xpr.rhs(), xpr.lhs().diagonal()) {}\n};\n\ntemplate<typename Lhs, typename Rhs, int ProductTag>\nstruct product_evaluator<Product<Lhs, Rhs, DefaultProduct>, ProductTag, SparseShape, DiagonalShape>\n  : public sparse_diagonal_product_evaluator<Lhs, Transpose<const typename Rhs::DiagonalVectorType>, Lhs::Flags&RowMajorBit?SDP_AsCwiseProduct:SDP_AsScalarProduct>\n{\n  typedef Product<Lhs, Rhs, DefaultProduct> XprType;\n  enum { CoeffReadCost = HugeCost, Flags = Lhs::Flags&RowMajorBit, Alignment = 0 }; // FIXME CoeffReadCost & Flags\n  \n  typedef sparse_diagonal_product_evaluator<Lhs, Transpose<const typename Rhs::DiagonalVectorType>, Lhs::Flags&RowMajorBit?SDP_AsCwiseProduct:SDP_AsScalarProduct> Base;\n  explicit product_evaluator(const XprType& xpr) : Base(xpr.lhs(), xpr.rhs().diagonal().transpose()) {}\n};\n\ntemplate<typename SparseXprType, typename DiagonalCoeffType>\nstruct sparse_diagonal_product_evaluator<SparseXprType, DiagonalCoeffType, SDP_AsScalarProduct>\n{\nprotected:\n  typedef typename evaluator<SparseXprType>::InnerIterator SparseXprInnerIterator;\n  typedef typename SparseXprType::Scalar Scalar;\n  \npublic:\n  class InnerIterator : public SparseXprInnerIterator\n  {\n  public:\n    InnerIterator(const sparse_diagonal_product_evaluator &xprEval, Index outer)\n      : SparseXprInnerIterator(xprEval.m_sparseXprImpl, outer),\n        m_coeff(xprEval.m_diagCoeffImpl.coeff(outer))\n    {}\n    \n    EIGEN_STRONG_INLINE Scalar value() const { return m_coeff * SparseXprInnerIterator::value(); }\n  protected:\n    typename DiagonalCoeffType::Scalar m_coeff;\n  };\n  \n  sparse_diagonal_product_evaluator(const SparseXprType &sparseXpr, const DiagonalCoeffType &diagCoeff)\n    : m_sparseXprImpl(sparseXpr), m_diagCoeffImpl(diagCoeff)\n  {}\n\n  Index nonZerosEstimate() const { return m_sparseXprImpl.nonZerosEstimate(); }\n    \nprotected:\n  evaluator<SparseXprType> m_sparseXprImpl;\n  evaluator<DiagonalCoeffType> m_diagCoeffImpl;\n};\n\n\ntemplate<typename SparseXprType, typename DiagCoeffType>\nstruct sparse_diagonal_product_evaluator<SparseXprType, DiagCoeffType, SDP_AsCwiseProduct>\n{\n  typedef typename SparseXprType::Scalar Scalar;\n  typedef typename SparseXprType::StorageIndex StorageIndex;\n  \n  typedef typename nested_eval<DiagCoeffType,SparseXprType::IsRowMajor ? SparseXprType::RowsAtCompileTime\n                                                                       : SparseXprType::ColsAtCompileTime>::type DiagCoeffNested;\n  \n  class InnerIterator\n  {\n    typedef typename evaluator<SparseXprType>::InnerIterator SparseXprIter;\n  public:\n    InnerIterator(const sparse_diagonal_product_evaluator &xprEval, Index outer)\n      : m_sparseIter(xprEval.m_sparseXprEval, outer), m_diagCoeffNested(xprEval.m_diagCoeffNested)\n    {}\n    \n    inline Scalar value() const { return m_sparseIter.value() * m_diagCoeffNested.coeff(index()); }\n    inline StorageIndex index() const  { return m_sparseIter.index(); }\n    inline Index outer() const  { return m_sparseIter.outer(); }\n    inline Index col() const    { return SparseXprType::IsRowMajor ? m_sparseIter.index() : m_sparseIter.outer(); }\n    inline Index row() const    { return SparseXprType::IsRowMajor ? m_sparseIter.outer() : m_sparseIter.index(); }\n    \n    EIGEN_STRONG_INLINE InnerIterator& operator++() { ++m_sparseIter; return *this; }\n    inline operator bool() const  { return m_sparseIter; }\n    \n  protected:\n    SparseXprIter m_sparseIter;\n    DiagCoeffNested m_diagCoeffNested;\n  };\n  \n  sparse_diagonal_product_evaluator(const SparseXprType &sparseXpr, const DiagCoeffType &diagCoeff)\n    : m_sparseXprEval(sparseXpr), m_diagCoeffNested(diagCoeff)\n  {}\n\n  Index nonZerosEstimate() const { return m_sparseXprEval.nonZerosEstimate(); }\n    \nprotected:\n  evaluator<SparseXprType> m_sparseXprEval;\n  DiagCoeffNested m_diagCoeffNested;\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_DIAGONAL_PRODUCT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseDot.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_DOT_H\n#define EIGEN_SPARSE_DOT_H\n\nnamespace Eigen { \n\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\ntypename internal::traits<Derived>::Scalar\nSparseMatrixBase<Derived>::dot(const MatrixBase<OtherDerived>& other) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived)\n  EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Derived,OtherDerived)\n  EIGEN_STATIC_ASSERT((internal::is_same<Scalar, typename OtherDerived::Scalar>::value),\n    YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n\n  eigen_assert(size() == other.size());\n  eigen_assert(other.size()>0 && \"you are using a non initialized vector\");\n\n  internal::evaluator<Derived> thisEval(derived());\n  typename internal::evaluator<Derived>::InnerIterator i(thisEval, 0);\n  Scalar res(0);\n  while (i)\n  {\n    res += numext::conj(i.value()) * other.coeff(i.index());\n    ++i;\n  }\n  return res;\n}\n\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\ntypename internal::traits<Derived>::Scalar\nSparseMatrixBase<Derived>::dot(const SparseMatrixBase<OtherDerived>& other) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(OtherDerived)\n  EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(Derived,OtherDerived)\n  EIGEN_STATIC_ASSERT((internal::is_same<Scalar, typename OtherDerived::Scalar>::value),\n    YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n\n  eigen_assert(size() == other.size());\n\n  internal::evaluator<Derived> thisEval(derived());\n  typename internal::evaluator<Derived>::InnerIterator i(thisEval, 0);\n  \n  internal::evaluator<OtherDerived>  otherEval(other.derived());\n  typename internal::evaluator<OtherDerived>::InnerIterator j(otherEval, 0);\n\n  Scalar res(0);\n  while (i && j)\n  {\n    if (i.index()==j.index())\n    {\n      res += numext::conj(i.value()) * j.value();\n      ++i; ++j;\n    }\n    else if (i.index()<j.index())\n      ++i;\n    else\n      ++j;\n  }\n  return res;\n}\n\ntemplate<typename Derived>\ninline typename NumTraits<typename internal::traits<Derived>::Scalar>::Real\nSparseMatrixBase<Derived>::squaredNorm() const\n{\n  return numext::real((*this).cwiseAbs2().sum());\n}\n\ntemplate<typename Derived>\ninline typename NumTraits<typename internal::traits<Derived>::Scalar>::Real\nSparseMatrixBase<Derived>::norm() const\n{\n  using std::sqrt;\n  return sqrt(squaredNorm());\n}\n\ntemplate<typename Derived>\ninline typename NumTraits<typename internal::traits<Derived>::Scalar>::Real\nSparseMatrixBase<Derived>::blueNorm() const\n{\n  return internal::blueNorm_impl(*this);\n}\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_DOT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseFuzzy.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_FUZZY_H\n#define EIGEN_SPARSE_FUZZY_H\n\nnamespace Eigen {\n  \ntemplate<typename Derived>\ntemplate<typename OtherDerived>\nbool SparseMatrixBase<Derived>::isApprox(const SparseMatrixBase<OtherDerived>& other, const RealScalar &prec) const\n{\n  const typename internal::nested_eval<Derived,2,PlainObject>::type actualA(derived());\n  typename internal::conditional<bool(IsRowMajor)==bool(OtherDerived::IsRowMajor),\n    const typename internal::nested_eval<OtherDerived,2,PlainObject>::type,\n    const PlainObject>::type actualB(other.derived());\n\n  return (actualA - actualB).squaredNorm() <= prec * prec * numext::mini(actualA.squaredNorm(), actualB.squaredNorm());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_FUZZY_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseMap.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_MAP_H\n#define EIGEN_SPARSE_MAP_H\n\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nstruct traits<Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n  : public traits<SparseMatrix<MatScalar,MatOptions,MatIndex> >\n{\n  typedef SparseMatrix<MatScalar,MatOptions,MatIndex> PlainObjectType;\n  typedef traits<PlainObjectType> TraitsBase;\n  enum {\n    Flags = TraitsBase::Flags & (~NestByRefBit)\n  };\n};\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nstruct traits<Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n  : public traits<SparseMatrix<MatScalar,MatOptions,MatIndex> >\n{\n  typedef SparseMatrix<MatScalar,MatOptions,MatIndex> PlainObjectType;\n  typedef traits<PlainObjectType> TraitsBase;\n  enum {\n    Flags = TraitsBase::Flags & (~ (NestByRefBit | LvalueBit))\n  };\n};\n\n} // end namespace internal\n\ntemplate<typename Derived,\n         int Level = internal::accessors_level<Derived>::has_write_access ? WriteAccessors : ReadOnlyAccessors\n> class SparseMapBase;\n\n/** \\ingroup SparseCore_Module\n  * class SparseMapBase\n  * \\brief Common base class for Map and Ref instance of sparse matrix and vector.\n  */\ntemplate<typename Derived>\nclass SparseMapBase<Derived,ReadOnlyAccessors>\n  : public SparseCompressedBase<Derived>\n{\n  public:\n    typedef SparseCompressedBase<Derived> Base;\n    typedef typename Base::Scalar Scalar;\n    typedef typename Base::StorageIndex StorageIndex;\n    enum { IsRowMajor = Base::IsRowMajor };\n    using Base::operator=;\n  protected:\n    \n    typedef typename internal::conditional<\n                         bool(internal::is_lvalue<Derived>::value),\n                         Scalar *, const Scalar *>::type ScalarPointer;\n    typedef typename internal::conditional<\n                         bool(internal::is_lvalue<Derived>::value),\n                         StorageIndex *, const StorageIndex *>::type IndexPointer;\n\n    Index   m_outerSize;\n    Index   m_innerSize;\n    Array<StorageIndex,2,1>  m_zero_nnz;\n    IndexPointer  m_outerIndex;\n    IndexPointer  m_innerIndices;\n    ScalarPointer m_values;\n    IndexPointer  m_innerNonZeros;\n\n  public:\n\n    /** \\copydoc SparseMatrixBase::rows() */\n    inline Index rows() const { return IsRowMajor ? m_outerSize : m_innerSize; }\n    /** \\copydoc SparseMatrixBase::cols() */\n    inline Index cols() const { return IsRowMajor ? m_innerSize : m_outerSize; }\n    /** \\copydoc SparseMatrixBase::innerSize() */\n    inline Index innerSize() const { return m_innerSize; }\n    /** \\copydoc SparseMatrixBase::outerSize() */\n    inline Index outerSize() const { return m_outerSize; }\n    /** \\copydoc SparseCompressedBase::nonZeros */\n    inline Index nonZeros() const { return m_zero_nnz[1]; }\n    \n    /** \\copydoc SparseCompressedBase::isCompressed */\n    bool isCompressed() const { return m_innerNonZeros==0; }\n\n    //----------------------------------------\n    // direct access interface\n    /** \\copydoc SparseMatrix::valuePtr */\n    inline const Scalar* valuePtr() const { return m_values; }\n    /** \\copydoc SparseMatrix::innerIndexPtr */\n    inline const StorageIndex* innerIndexPtr() const { return m_innerIndices; }\n    /** \\copydoc SparseMatrix::outerIndexPtr */\n    inline const StorageIndex* outerIndexPtr() const { return m_outerIndex; }\n    /** \\copydoc SparseMatrix::innerNonZeroPtr */\n    inline const StorageIndex* innerNonZeroPtr() const { return m_innerNonZeros; }\n    //----------------------------------------\n\n    /** \\copydoc SparseMatrix::coeff */\n    inline Scalar coeff(Index row, Index col) const\n    {\n      const Index outer = IsRowMajor ? row : col;\n      const Index inner = IsRowMajor ? col : row;\n\n      Index start = m_outerIndex[outer];\n      Index end = isCompressed() ? m_outerIndex[outer+1] : start + m_innerNonZeros[outer];\n      if (start==end)\n        return Scalar(0);\n      else if (end>0 && inner==m_innerIndices[end-1])\n        return m_values[end-1];\n      // ^^  optimization: let's first check if it is the last coefficient\n      // (very common in high level algorithms)\n\n      const StorageIndex* r = std::lower_bound(&m_innerIndices[start],&m_innerIndices[end-1],inner);\n      const Index id = r-&m_innerIndices[0];\n      return ((*r==inner) && (id<end)) ? m_values[id] : Scalar(0);\n    }\n\n    inline SparseMapBase(Index rows, Index cols, Index nnz, IndexPointer outerIndexPtr, IndexPointer innerIndexPtr,\n                              ScalarPointer valuePtr, IndexPointer innerNonZerosPtr = 0)\n      : m_outerSize(IsRowMajor?rows:cols), m_innerSize(IsRowMajor?cols:rows), m_zero_nnz(0,internal::convert_index<StorageIndex>(nnz)), m_outerIndex(outerIndexPtr),\n        m_innerIndices(innerIndexPtr), m_values(valuePtr), m_innerNonZeros(innerNonZerosPtr)\n    {}\n\n    // for vectors\n    inline SparseMapBase(Index size, Index nnz, IndexPointer innerIndexPtr, ScalarPointer valuePtr)\n      : m_outerSize(1), m_innerSize(size), m_zero_nnz(0,internal::convert_index<StorageIndex>(nnz)), m_outerIndex(m_zero_nnz.data()),\n        m_innerIndices(innerIndexPtr), m_values(valuePtr), m_innerNonZeros(0)\n    {}\n\n    /** Empty destructor */\n    inline ~SparseMapBase() {}\n\n  protected:\n    inline SparseMapBase() {}\n};\n\n/** \\ingroup SparseCore_Module\n  * class SparseMapBase\n  * \\brief Common base class for writable Map and Ref instance of sparse matrix and vector.\n  */\ntemplate<typename Derived>\nclass SparseMapBase<Derived,WriteAccessors>\n  : public SparseMapBase<Derived,ReadOnlyAccessors>\n{\n    typedef MapBase<Derived, ReadOnlyAccessors> ReadOnlyMapBase;\n    \n  public:\n    typedef SparseMapBase<Derived, ReadOnlyAccessors> Base;\n    typedef typename Base::Scalar Scalar;\n    typedef typename Base::StorageIndex StorageIndex;\n    enum { IsRowMajor = Base::IsRowMajor };\n    \n    using Base::operator=;\n\n  public:\n    \n    //----------------------------------------\n    // direct access interface\n    using Base::valuePtr;\n    using Base::innerIndexPtr;\n    using Base::outerIndexPtr;\n    using Base::innerNonZeroPtr;\n    /** \\copydoc SparseMatrix::valuePtr */\n    inline Scalar* valuePtr()              { return Base::m_values; }\n    /** \\copydoc SparseMatrix::innerIndexPtr */\n    inline StorageIndex* innerIndexPtr()   { return Base::m_innerIndices; }\n    /** \\copydoc SparseMatrix::outerIndexPtr */\n    inline StorageIndex* outerIndexPtr()   { return Base::m_outerIndex; }\n    /** \\copydoc SparseMatrix::innerNonZeroPtr */\n    inline StorageIndex* innerNonZeroPtr() { return Base::m_innerNonZeros; }\n    //----------------------------------------\n\n    /** \\copydoc SparseMatrix::coeffRef */\n    inline Scalar& coeffRef(Index row, Index col)\n    {\n      const Index outer = IsRowMajor ? row : col;\n      const Index inner = IsRowMajor ? col : row;\n\n      Index start = Base::m_outerIndex[outer];\n      Index end = Base::isCompressed() ? Base::m_outerIndex[outer+1] : start + Base::m_innerNonZeros[outer];\n      eigen_assert(end>=start && \"you probably called coeffRef on a non finalized matrix\");\n      eigen_assert(end>start && \"coeffRef cannot be called on a zero coefficient\");\n      StorageIndex* r = std::lower_bound(&Base::m_innerIndices[start],&Base::m_innerIndices[end],inner);\n      const Index id = r - &Base::m_innerIndices[0];\n      eigen_assert((*r==inner) && (id<end) && \"coeffRef cannot be called on a zero coefficient\");\n      return const_cast<Scalar*>(Base::m_values)[id];\n    }\n    \n    inline SparseMapBase(Index rows, Index cols, Index nnz, StorageIndex* outerIndexPtr, StorageIndex* innerIndexPtr,\n                         Scalar* valuePtr, StorageIndex* innerNonZerosPtr = 0)\n      : Base(rows, cols, nnz, outerIndexPtr, innerIndexPtr, valuePtr, innerNonZerosPtr)\n    {}\n\n    // for vectors\n    inline SparseMapBase(Index size, Index nnz, StorageIndex* innerIndexPtr, Scalar* valuePtr)\n      : Base(size, nnz, innerIndexPtr, valuePtr)\n    {}\n\n    /** Empty destructor */\n    inline ~SparseMapBase() {}\n\n  protected:\n    inline SparseMapBase() {}\n};\n\n/** \\ingroup SparseCore_Module\n  *\n  * \\brief Specialization of class Map for SparseMatrix-like storage.\n  *\n  * \\tparam SparseMatrixType the equivalent sparse matrix type of the referenced data, it must be a template instance of class SparseMatrix.\n  *\n  * \\sa class Map, class SparseMatrix, class Ref<SparseMatrixType,Options>\n  */\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nclass Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType>\n  : public SparseMapBase<Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n#else\ntemplate<typename SparseMatrixType>\nclass Map<SparseMatrixType>\n  : public SparseMapBase<Derived,WriteAccessors>\n#endif\n{\n  public:\n    typedef SparseMapBase<Map> Base;\n    EIGEN_SPARSE_PUBLIC_INTERFACE(Map)\n    enum { IsRowMajor = Base::IsRowMajor };\n\n  public:\n\n    /** Constructs a read-write Map to a sparse matrix of size \\a rows x \\a cols, containing \\a nnz non-zero coefficients,\n      * stored as a sparse format as defined by the pointers \\a outerIndexPtr, \\a innerIndexPtr, and \\a valuePtr.\n      * If the optional parameter \\a innerNonZerosPtr is the null pointer, then a standard compressed format is assumed.\n      *\n      * This constructor is available only if \\c SparseMatrixType is non-const.\n      *\n      * More details on the expected storage schemes are given in the \\ref TutorialSparse \"manual pages\".\n      */\n    inline Map(Index rows, Index cols, Index nnz, StorageIndex* outerIndexPtr,\n               StorageIndex* innerIndexPtr, Scalar* valuePtr, StorageIndex* innerNonZerosPtr = 0)\n      : Base(rows, cols, nnz, outerIndexPtr, innerIndexPtr, valuePtr, innerNonZerosPtr)\n    {}\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n    /** Empty destructor */\n    inline ~Map() {}\n};\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nclass Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType>\n  : public SparseMapBase<Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n{\n  public:\n    typedef SparseMapBase<Map> Base;\n    EIGEN_SPARSE_PUBLIC_INTERFACE(Map)\n    enum { IsRowMajor = Base::IsRowMajor };\n\n  public:\n#endif\n    /** This is the const version of the above constructor.\n      *\n      * This constructor is available only if \\c SparseMatrixType is const, e.g.:\n      * \\code Map<const SparseMatrix<double> >  \\endcode\n      */\n    inline Map(Index rows, Index cols, Index nnz, const StorageIndex* outerIndexPtr,\n               const StorageIndex* innerIndexPtr, const Scalar* valuePtr, const StorageIndex* innerNonZerosPtr = 0)\n      : Base(rows, cols, nnz, outerIndexPtr, innerIndexPtr, valuePtr, innerNonZerosPtr)\n    {}\n\n    /** Empty destructor */\n    inline ~Map() {}\n};\n\nnamespace internal {\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nstruct evaluator<Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n  : evaluator<SparseCompressedBase<Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > >\n{\n  typedef evaluator<SparseCompressedBase<Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > > Base;\n  typedef Map<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> XprType;  \n  evaluator() : Base() {}\n  explicit evaluator(const XprType &mat) : Base(mat) {}\n};\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nstruct evaluator<Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n  : evaluator<SparseCompressedBase<Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > >\n{\n  typedef evaluator<SparseCompressedBase<Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > > Base;\n  typedef Map<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> XprType;  \n  evaluator() : Base() {}\n  explicit evaluator(const XprType &mat) : Base(mat) {}\n};\n\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_MAP_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseMatrix.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEMATRIX_H\n#define EIGEN_SPARSEMATRIX_H\n\nnamespace Eigen { \n\n/** \\ingroup SparseCore_Module\n  *\n  * \\class SparseMatrix\n  *\n  * \\brief A versatible sparse matrix representation\n  *\n  * This class implements a more versatile variants of the common \\em compressed row/column storage format.\n  * Each colmun's (resp. row) non zeros are stored as a pair of value with associated row (resp. colmiun) index.\n  * All the non zeros are stored in a single large buffer. Unlike the \\em compressed format, there might be extra\n  * space in between the nonzeros of two successive colmuns (resp. rows) such that insertion of new non-zero\n  * can be done with limited memory reallocation and copies.\n  *\n  * A call to the function makeCompressed() turns the matrix into the standard \\em compressed format\n  * compatible with many library.\n  *\n  * More details on this storage sceheme are given in the \\ref TutorialSparse \"manual pages\".\n  *\n  * \\tparam _Scalar the scalar type, i.e. the type of the coefficients\n  * \\tparam _Options Union of bit flags controlling the storage scheme. Currently the only possibility\n  *                 is ColMajor or RowMajor. The default is 0 which means column-major.\n  * \\tparam _StorageIndex the type of the indices. It has to be a \\b signed type (e.g., short, int, std::ptrdiff_t). Default is \\c int.\n  *\n  * \\warning In %Eigen 3.2, the undocumented type \\c SparseMatrix::Index was improperly defined as the storage index type (e.g., int),\n  *          whereas it is now (starting from %Eigen 3.3) deprecated and always defined as Eigen::Index.\n  *          Codes making use of \\c SparseMatrix::Index, might thus likely have to be changed to use \\c SparseMatrix::StorageIndex instead.\n  *\n  * This class can be extended with the help of the plugin mechanism described on the page\n  * \\ref TopicCustomizing_Plugins by defining the preprocessor symbol \\c EIGEN_SPARSEMATRIX_PLUGIN.\n  */\n\nnamespace internal {\ntemplate<typename _Scalar, int _Options, typename _StorageIndex>\nstruct traits<SparseMatrix<_Scalar, _Options, _StorageIndex> >\n{\n  typedef _Scalar Scalar;\n  typedef _StorageIndex StorageIndex;\n  typedef Sparse StorageKind;\n  typedef MatrixXpr XprKind;\n  enum {\n    RowsAtCompileTime = Dynamic,\n    ColsAtCompileTime = Dynamic,\n    MaxRowsAtCompileTime = Dynamic,\n    MaxColsAtCompileTime = Dynamic,\n    Flags = _Options | NestByRefBit | LvalueBit | CompressedAccessBit,\n    SupportedAccessPatterns = InnerRandomAccessPattern\n  };\n};\n\ntemplate<typename _Scalar, int _Options, typename _StorageIndex, int DiagIndex>\nstruct traits<Diagonal<SparseMatrix<_Scalar, _Options, _StorageIndex>, DiagIndex> >\n{\n  typedef SparseMatrix<_Scalar, _Options, _StorageIndex> MatrixType;\n  typedef typename ref_selector<MatrixType>::type MatrixTypeNested;\n  typedef typename remove_reference<MatrixTypeNested>::type _MatrixTypeNested;\n\n  typedef _Scalar Scalar;\n  typedef Dense StorageKind;\n  typedef _StorageIndex StorageIndex;\n  typedef MatrixXpr XprKind;\n\n  enum {\n    RowsAtCompileTime = Dynamic,\n    ColsAtCompileTime = 1,\n    MaxRowsAtCompileTime = Dynamic,\n    MaxColsAtCompileTime = 1,\n    Flags = LvalueBit\n  };\n};\n\ntemplate<typename _Scalar, int _Options, typename _StorageIndex, int DiagIndex>\nstruct traits<Diagonal<const SparseMatrix<_Scalar, _Options, _StorageIndex>, DiagIndex> >\n : public traits<Diagonal<SparseMatrix<_Scalar, _Options, _StorageIndex>, DiagIndex> >\n{\n  enum {\n    Flags = 0\n  };\n};\n\n} // end namespace internal\n\ntemplate<typename _Scalar, int _Options, typename _StorageIndex>\nclass SparseMatrix\n  : public SparseCompressedBase<SparseMatrix<_Scalar, _Options, _StorageIndex> >\n{\n    typedef SparseCompressedBase<SparseMatrix> Base;\n    using Base::convert_index;\n    friend class SparseVector<_Scalar,0,_StorageIndex>;\n    template<typename, typename, typename, typename, typename>\n    friend struct internal::Assignment;\n  public:\n    using Base::isCompressed;\n    using Base::nonZeros;\n    EIGEN_SPARSE_PUBLIC_INTERFACE(SparseMatrix)\n    using Base::operator+=;\n    using Base::operator-=;\n\n    typedef MappedSparseMatrix<Scalar,Flags> Map;\n    typedef Diagonal<SparseMatrix> DiagonalReturnType;\n    typedef Diagonal<const SparseMatrix> ConstDiagonalReturnType;\n    typedef typename Base::InnerIterator InnerIterator;\n    typedef typename Base::ReverseInnerIterator ReverseInnerIterator;\n    \n\n    using Base::IsRowMajor;\n    typedef internal::CompressedStorage<Scalar,StorageIndex> Storage;\n    enum {\n      Options = _Options\n    };\n\n    typedef typename Base::IndexVector IndexVector;\n    typedef typename Base::ScalarVector ScalarVector;\n  protected:\n    typedef SparseMatrix<Scalar,(Flags&~RowMajorBit)|(IsRowMajor?RowMajorBit:0)> TransposedSparseMatrix;\n\n    Index m_outerSize;\n    Index m_innerSize;\n    StorageIndex* m_outerIndex;\n    StorageIndex* m_innerNonZeros;     // optional, if null then the data is compressed\n    Storage m_data;\n\n  public:\n    \n    /** \\returns the number of rows of the matrix */\n    inline Index rows() const { return IsRowMajor ? m_outerSize : m_innerSize; }\n    /** \\returns the number of columns of the matrix */\n    inline Index cols() const { return IsRowMajor ? m_innerSize : m_outerSize; }\n\n    /** \\returns the number of rows (resp. columns) of the matrix if the storage order column major (resp. row major) */\n    inline Index innerSize() const { return m_innerSize; }\n    /** \\returns the number of columns (resp. rows) of the matrix if the storage order column major (resp. row major) */\n    inline Index outerSize() const { return m_outerSize; }\n    \n    /** \\returns a const pointer to the array of values.\n      * This function is aimed at interoperability with other libraries.\n      * \\sa innerIndexPtr(), outerIndexPtr() */\n    inline const Scalar* valuePtr() const { return m_data.valuePtr(); }\n    /** \\returns a non-const pointer to the array of values.\n      * This function is aimed at interoperability with other libraries.\n      * \\sa innerIndexPtr(), outerIndexPtr() */\n    inline Scalar* valuePtr() { return m_data.valuePtr(); }\n\n    /** \\returns a const pointer to the array of inner indices.\n      * This function is aimed at interoperability with other libraries.\n      * \\sa valuePtr(), outerIndexPtr() */\n    inline const StorageIndex* innerIndexPtr() const { return m_data.indexPtr(); }\n    /** \\returns a non-const pointer to the array of inner indices.\n      * This function is aimed at interoperability with other libraries.\n      * \\sa valuePtr(), outerIndexPtr() */\n    inline StorageIndex* innerIndexPtr() { return m_data.indexPtr(); }\n\n    /** \\returns a const pointer to the array of the starting positions of the inner vectors.\n      * This function is aimed at interoperability with other libraries.\n      * \\sa valuePtr(), innerIndexPtr() */\n    inline const StorageIndex* outerIndexPtr() const { return m_outerIndex; }\n    /** \\returns a non-const pointer to the array of the starting positions of the inner vectors.\n      * This function is aimed at interoperability with other libraries.\n      * \\sa valuePtr(), innerIndexPtr() */\n    inline StorageIndex* outerIndexPtr() { return m_outerIndex; }\n\n    /** \\returns a const pointer to the array of the number of non zeros of the inner vectors.\n      * This function is aimed at interoperability with other libraries.\n      * \\warning it returns the null pointer 0 in compressed mode */\n    inline const StorageIndex* innerNonZeroPtr() const { return m_innerNonZeros; }\n    /** \\returns a non-const pointer to the array of the number of non zeros of the inner vectors.\n      * This function is aimed at interoperability with other libraries.\n      * \\warning it returns the null pointer 0 in compressed mode */\n    inline StorageIndex* innerNonZeroPtr() { return m_innerNonZeros; }\n\n    /** \\internal */\n    inline Storage& data() { return m_data; }\n    /** \\internal */\n    inline const Storage& data() const { return m_data; }\n\n    /** \\returns the value of the matrix at position \\a i, \\a j\n      * This function returns Scalar(0) if the element is an explicit \\em zero */\n    inline Scalar coeff(Index row, Index col) const\n    {\n      eigen_assert(row>=0 && row<rows() && col>=0 && col<cols());\n      \n      const Index outer = IsRowMajor ? row : col;\n      const Index inner = IsRowMajor ? col : row;\n      Index end = m_innerNonZeros ? m_outerIndex[outer] + m_innerNonZeros[outer] : m_outerIndex[outer+1];\n      return m_data.atInRange(m_outerIndex[outer], end, StorageIndex(inner));\n    }\n\n    /** \\returns a non-const reference to the value of the matrix at position \\a i, \\a j\n      *\n      * If the element does not exist then it is inserted via the insert(Index,Index) function\n      * which itself turns the matrix into a non compressed form if that was not the case.\n      *\n      * This is a O(log(nnz_j)) operation (binary search) plus the cost of insert(Index,Index)\n      * function if the element does not already exist.\n      */\n    inline Scalar& coeffRef(Index row, Index col)\n    {\n      eigen_assert(row>=0 && row<rows() && col>=0 && col<cols());\n      \n      const Index outer = IsRowMajor ? row : col;\n      const Index inner = IsRowMajor ? col : row;\n\n      Index start = m_outerIndex[outer];\n      Index end = m_innerNonZeros ? m_outerIndex[outer] + m_innerNonZeros[outer] : m_outerIndex[outer+1];\n      eigen_assert(end>=start && \"you probably called coeffRef on a non finalized matrix\");\n      if(end<=start)\n        return insert(row,col);\n      const Index p = m_data.searchLowerIndex(start,end-1,StorageIndex(inner));\n      if((p<end) && (m_data.index(p)==inner))\n        return m_data.value(p);\n      else\n        return insert(row,col);\n    }\n\n    /** \\returns a reference to a novel non zero coefficient with coordinates \\a row x \\a col.\n      * The non zero coefficient must \\b not already exist.\n      *\n      * If the matrix \\c *this is in compressed mode, then \\c *this is turned into uncompressed\n      * mode while reserving room for 2 x this->innerSize() non zeros if reserve(Index) has not been called earlier.\n      * In this case, the insertion procedure is optimized for a \\e sequential insertion mode where elements are assumed to be\n      * inserted by increasing outer-indices.\n      * \n      * If that's not the case, then it is strongly recommended to either use a triplet-list to assemble the matrix, or to first\n      * call reserve(const SizesType &) to reserve the appropriate number of non-zero elements per inner vector.\n      *\n      * Assuming memory has been appropriately reserved, this function performs a sorted insertion in O(1)\n      * if the elements of each inner vector are inserted in increasing inner index order, and in O(nnz_j) for a random insertion.\n      *\n      */\n    Scalar& insert(Index row, Index col);\n\n  public:\n\n    /** Removes all non zeros but keep allocated memory\n      *\n      * This function does not free the currently allocated memory. To release as much as memory as possible,\n      * call \\code mat.data().squeeze(); \\endcode after resizing it.\n      * \n      * \\sa resize(Index,Index), data()\n      */\n    inline void setZero()\n    {\n      m_data.clear();\n      memset(m_outerIndex, 0, (m_outerSize+1)*sizeof(StorageIndex));\n      if(m_innerNonZeros)\n        memset(m_innerNonZeros, 0, (m_outerSize)*sizeof(StorageIndex));\n    }\n\n    /** Preallocates \\a reserveSize non zeros.\n      *\n      * Precondition: the matrix must be in compressed mode. */\n    inline void reserve(Index reserveSize)\n    {\n      eigen_assert(isCompressed() && \"This function does not make sense in non compressed mode.\");\n      m_data.reserve(reserveSize);\n    }\n    \n    #ifdef EIGEN_PARSED_BY_DOXYGEN\n    /** Preallocates \\a reserveSize[\\c j] non zeros for each column (resp. row) \\c j.\n      *\n      * This function turns the matrix in non-compressed mode.\n      * \n      * The type \\c SizesType must expose the following interface:\n        \\code\n        typedef value_type;\n        const value_type& operator[](i) const;\n        \\endcode\n      * for \\c i in the [0,this->outerSize()[ range.\n      * Typical choices include std::vector<int>, Eigen::VectorXi, Eigen::VectorXi::Constant, etc.\n      */\n    template<class SizesType>\n    inline void reserve(const SizesType& reserveSizes);\n    #else\n    template<class SizesType>\n    inline void reserve(const SizesType& reserveSizes, const typename SizesType::value_type& enableif =\n    #if (!EIGEN_COMP_MSVC) || (EIGEN_COMP_MSVC>=1500) // MSVC 2005 fails to compile with this typename\n        typename\n    #endif\n        SizesType::value_type())\n    {\n      EIGEN_UNUSED_VARIABLE(enableif);\n      reserveInnerVectors(reserveSizes);\n    }\n    #endif // EIGEN_PARSED_BY_DOXYGEN\n  protected:\n    template<class SizesType>\n    inline void reserveInnerVectors(const SizesType& reserveSizes)\n    {\n      if(isCompressed())\n      {\n        Index totalReserveSize = 0;\n        // turn the matrix into non-compressed mode\n        m_innerNonZeros = static_cast<StorageIndex*>(std::malloc(m_outerSize * sizeof(StorageIndex)));\n        if (!m_innerNonZeros) internal::throw_std_bad_alloc();\n        \n        // temporarily use m_innerSizes to hold the new starting points.\n        StorageIndex* newOuterIndex = m_innerNonZeros;\n        \n        StorageIndex count = 0;\n        for(Index j=0; j<m_outerSize; ++j)\n        {\n          newOuterIndex[j] = count;\n          count += reserveSizes[j] + (m_outerIndex[j+1]-m_outerIndex[j]);\n          totalReserveSize += reserveSizes[j];\n        }\n        m_data.reserve(totalReserveSize);\n        StorageIndex previousOuterIndex = m_outerIndex[m_outerSize];\n        for(Index j=m_outerSize-1; j>=0; --j)\n        {\n          StorageIndex innerNNZ = previousOuterIndex - m_outerIndex[j];\n          for(Index i=innerNNZ-1; i>=0; --i)\n          {\n            m_data.index(newOuterIndex[j]+i) = m_data.index(m_outerIndex[j]+i);\n            m_data.value(newOuterIndex[j]+i) = m_data.value(m_outerIndex[j]+i);\n          }\n          previousOuterIndex = m_outerIndex[j];\n          m_outerIndex[j] = newOuterIndex[j];\n          m_innerNonZeros[j] = innerNNZ;\n        }\n        if(m_outerSize>0)\n          m_outerIndex[m_outerSize] = m_outerIndex[m_outerSize-1] + m_innerNonZeros[m_outerSize-1] + reserveSizes[m_outerSize-1];\n        \n        m_data.resize(m_outerIndex[m_outerSize]);\n      }\n      else\n      {\n        StorageIndex* newOuterIndex = static_cast<StorageIndex*>(std::malloc((m_outerSize+1)*sizeof(StorageIndex)));\n        if (!newOuterIndex) internal::throw_std_bad_alloc();\n        \n        StorageIndex count = 0;\n        for(Index j=0; j<m_outerSize; ++j)\n        {\n          newOuterIndex[j] = count;\n          StorageIndex alreadyReserved = (m_outerIndex[j+1]-m_outerIndex[j]) - m_innerNonZeros[j];\n          StorageIndex toReserve = std::max<StorageIndex>(reserveSizes[j], alreadyReserved);\n          count += toReserve + m_innerNonZeros[j];\n        }\n        newOuterIndex[m_outerSize] = count;\n        \n        m_data.resize(count);\n        for(Index j=m_outerSize-1; j>=0; --j)\n        {\n          Index offset = newOuterIndex[j] - m_outerIndex[j];\n          if(offset>0)\n          {\n            StorageIndex innerNNZ = m_innerNonZeros[j];\n            for(Index i=innerNNZ-1; i>=0; --i)\n            {\n              m_data.index(newOuterIndex[j]+i) = m_data.index(m_outerIndex[j]+i);\n              m_data.value(newOuterIndex[j]+i) = m_data.value(m_outerIndex[j]+i);\n            }\n          }\n        }\n        \n        std::swap(m_outerIndex, newOuterIndex);\n        std::free(newOuterIndex);\n      }\n      \n    }\n  public:\n\n    //--- low level purely coherent filling ---\n\n    /** \\internal\n      * \\returns a reference to the non zero coefficient at position \\a row, \\a col assuming that:\n      * - the nonzero does not already exist\n      * - the new coefficient is the last one according to the storage order\n      *\n      * Before filling a given inner vector you must call the statVec(Index) function.\n      *\n      * After an insertion session, you should call the finalize() function.\n      *\n      * \\sa insert, insertBackByOuterInner, startVec */\n    inline Scalar& insertBack(Index row, Index col)\n    {\n      return insertBackByOuterInner(IsRowMajor?row:col, IsRowMajor?col:row);\n    }\n\n    /** \\internal\n      * \\sa insertBack, startVec */\n    inline Scalar& insertBackByOuterInner(Index outer, Index inner)\n    {\n      eigen_assert(Index(m_outerIndex[outer+1]) == m_data.size() && \"Invalid ordered insertion (invalid outer index)\");\n      eigen_assert( (m_outerIndex[outer+1]-m_outerIndex[outer]==0 || m_data.index(m_data.size()-1)<inner) && \"Invalid ordered insertion (invalid inner index)\");\n      Index p = m_outerIndex[outer+1];\n      ++m_outerIndex[outer+1];\n      m_data.append(Scalar(0), inner);\n      return m_data.value(p);\n    }\n\n    /** \\internal\n      * \\warning use it only if you know what you are doing */\n    inline Scalar& insertBackByOuterInnerUnordered(Index outer, Index inner)\n    {\n      Index p = m_outerIndex[outer+1];\n      ++m_outerIndex[outer+1];\n      m_data.append(Scalar(0), inner);\n      return m_data.value(p);\n    }\n\n    /** \\internal\n      * \\sa insertBack, insertBackByOuterInner */\n    inline void startVec(Index outer)\n    {\n      eigen_assert(m_outerIndex[outer]==Index(m_data.size()) && \"You must call startVec for each inner vector sequentially\");\n      eigen_assert(m_outerIndex[outer+1]==0 && \"You must call startVec for each inner vector sequentially\");\n      m_outerIndex[outer+1] = m_outerIndex[outer];\n    }\n\n    /** \\internal\n      * Must be called after inserting a set of non zero entries using the low level compressed API.\n      */\n    inline void finalize()\n    {\n      if(isCompressed())\n      {\n        StorageIndex size = internal::convert_index<StorageIndex>(m_data.size());\n        Index i = m_outerSize;\n        // find the last filled column\n        while (i>=0 && m_outerIndex[i]==0)\n          --i;\n        ++i;\n        while (i<=m_outerSize)\n        {\n          m_outerIndex[i] = size;\n          ++i;\n        }\n      }\n    }\n\n    //---\n\n    template<typename InputIterators>\n    void setFromTriplets(const InputIterators& begin, const InputIterators& end);\n\n    template<typename InputIterators,typename DupFunctor>\n    void setFromTriplets(const InputIterators& begin, const InputIterators& end, DupFunctor dup_func);\n\n    void sumupDuplicates() { collapseDuplicates(internal::scalar_sum_op<Scalar,Scalar>()); }\n\n    template<typename DupFunctor>\n    void collapseDuplicates(DupFunctor dup_func = DupFunctor());\n\n    //---\n    \n    /** \\internal\n      * same as insert(Index,Index) except that the indices are given relative to the storage order */\n    Scalar& insertByOuterInner(Index j, Index i)\n    {\n      return insert(IsRowMajor ? j : i, IsRowMajor ? i : j);\n    }\n\n    /** Turns the matrix into the \\em compressed format.\n      */\n    void makeCompressed()\n    {\n      if(isCompressed())\n        return;\n      \n      eigen_internal_assert(m_outerIndex!=0 && m_outerSize>0);\n      \n      Index oldStart = m_outerIndex[1];\n      m_outerIndex[1] = m_innerNonZeros[0];\n      for(Index j=1; j<m_outerSize; ++j)\n      {\n        Index nextOldStart = m_outerIndex[j+1];\n        Index offset = oldStart - m_outerIndex[j];\n        if(offset>0)\n        {\n          for(Index k=0; k<m_innerNonZeros[j]; ++k)\n          {\n            m_data.index(m_outerIndex[j]+k) = m_data.index(oldStart+k);\n            m_data.value(m_outerIndex[j]+k) = m_data.value(oldStart+k);\n          }\n        }\n        m_outerIndex[j+1] = m_outerIndex[j] + m_innerNonZeros[j];\n        oldStart = nextOldStart;\n      }\n      std::free(m_innerNonZeros);\n      m_innerNonZeros = 0;\n      m_data.resize(m_outerIndex[m_outerSize]);\n      m_data.squeeze();\n    }\n\n    /** Turns the matrix into the uncompressed mode */\n    void uncompress()\n    {\n      if(m_innerNonZeros != 0)\n        return; \n      m_innerNonZeros = static_cast<StorageIndex*>(std::malloc(m_outerSize * sizeof(StorageIndex)));\n      for (Index i = 0; i < m_outerSize; i++)\n      {\n        m_innerNonZeros[i] = m_outerIndex[i+1] - m_outerIndex[i]; \n      }\n    }\n\n    /** Suppresses all nonzeros which are \\b much \\b smaller \\b than \\a reference under the tolerance \\a epsilon */\n    void prune(const Scalar& reference, const RealScalar& epsilon = NumTraits<RealScalar>::dummy_precision())\n    {\n      prune(default_prunning_func(reference,epsilon));\n    }\n    \n    /** Turns the matrix into compressed format, and suppresses all nonzeros which do not satisfy the predicate \\a keep.\n      * The functor type \\a KeepFunc must implement the following function:\n      * \\code\n      * bool operator() (const Index& row, const Index& col, const Scalar& value) const;\n      * \\endcode\n      * \\sa prune(Scalar,RealScalar)\n      */\n    template<typename KeepFunc>\n    void prune(const KeepFunc& keep = KeepFunc())\n    {\n      // TODO optimize the uncompressed mode to avoid moving and allocating the data twice\n      makeCompressed();\n\n      StorageIndex k = 0;\n      for(Index j=0; j<m_outerSize; ++j)\n      {\n        Index previousStart = m_outerIndex[j];\n        m_outerIndex[j] = k;\n        Index end = m_outerIndex[j+1];\n        for(Index i=previousStart; i<end; ++i)\n        {\n          if(keep(IsRowMajor?j:m_data.index(i), IsRowMajor?m_data.index(i):j, m_data.value(i)))\n          {\n            m_data.value(k) = m_data.value(i);\n            m_data.index(k) = m_data.index(i);\n            ++k;\n          }\n        }\n      }\n      m_outerIndex[m_outerSize] = k;\n      m_data.resize(k,0);\n    }\n\n    /** Resizes the matrix to a \\a rows x \\a cols matrix leaving old values untouched.\n      *\n      * If the sizes of the matrix are decreased, then the matrix is turned to \\b uncompressed-mode\n      * and the storage of the out of bounds coefficients is kept and reserved.\n      * Call makeCompressed() to pack the entries and squeeze extra memory.\n      *\n      * \\sa reserve(), setZero(), makeCompressed()\n      */\n    void conservativeResize(Index rows, Index cols) \n    {\n      // No change\n      if (this->rows() == rows && this->cols() == cols) return;\n      \n      // If one dimension is null, then there is nothing to be preserved\n      if(rows==0 || cols==0) return resize(rows,cols);\n\n      Index innerChange = IsRowMajor ? cols - this->cols() : rows - this->rows();\n      Index outerChange = IsRowMajor ? rows - this->rows() : cols - this->cols();\n      StorageIndex newInnerSize = convert_index(IsRowMajor ? cols : rows);\n\n      // Deals with inner non zeros\n      if (m_innerNonZeros)\n      {\n        // Resize m_innerNonZeros\n        StorageIndex *newInnerNonZeros = static_cast<StorageIndex*>(std::realloc(m_innerNonZeros, (m_outerSize + outerChange) * sizeof(StorageIndex)));\n        if (!newInnerNonZeros) internal::throw_std_bad_alloc();\n        m_innerNonZeros = newInnerNonZeros;\n        \n        for(Index i=m_outerSize; i<m_outerSize+outerChange; i++)          \n          m_innerNonZeros[i] = 0;\n      } \n      else if (innerChange < 0) \n      {\n        // Inner size decreased: allocate a new m_innerNonZeros\n        m_innerNonZeros = static_cast<StorageIndex*>(std::malloc((m_outerSize + outerChange) * sizeof(StorageIndex)));\n        if (!m_innerNonZeros) internal::throw_std_bad_alloc();\n        for(Index i = 0; i < m_outerSize + (std::min)(outerChange, Index(0)); i++)\n          m_innerNonZeros[i] = m_outerIndex[i+1] - m_outerIndex[i];\n        for(Index i = m_outerSize; i < m_outerSize + outerChange; i++)\n          m_innerNonZeros[i] = 0;\n      }\n      \n      // Change the m_innerNonZeros in case of a decrease of inner size\n      if (m_innerNonZeros && innerChange < 0)\n      {\n        for(Index i = 0; i < m_outerSize + (std::min)(outerChange, Index(0)); i++)\n        {\n          StorageIndex &n = m_innerNonZeros[i];\n          StorageIndex start = m_outerIndex[i];\n          while (n > 0 && m_data.index(start+n-1) >= newInnerSize) --n; \n        }\n      }\n      \n      m_innerSize = newInnerSize;\n\n      // Re-allocate outer index structure if necessary\n      if (outerChange == 0)\n        return;\n          \n      StorageIndex *newOuterIndex = static_cast<StorageIndex*>(std::realloc(m_outerIndex, (m_outerSize + outerChange + 1) * sizeof(StorageIndex)));\n      if (!newOuterIndex) internal::throw_std_bad_alloc();\n      m_outerIndex = newOuterIndex;\n      if (outerChange > 0)\n      {\n        StorageIndex lastIdx = m_outerSize == 0 ? 0 : m_outerIndex[m_outerSize];\n        for(Index i=m_outerSize; i<m_outerSize+outerChange+1; i++)          \n          m_outerIndex[i] = lastIdx; \n      }\n      m_outerSize += outerChange;\n    }\n    \n    /** Resizes the matrix to a \\a rows x \\a cols matrix and initializes it to zero.\n      * \n      * This function does not free the currently allocated memory. To release as much as memory as possible,\n      * call \\code mat.data().squeeze(); \\endcode after resizing it.\n      * \n      * \\sa reserve(), setZero()\n      */\n    void resize(Index rows, Index cols)\n    {\n      const Index outerSize = IsRowMajor ? rows : cols;\n      m_innerSize = IsRowMajor ? cols : rows;\n      m_data.clear();\n      if (m_outerSize != outerSize || m_outerSize==0)\n      {\n        std::free(m_outerIndex);\n        m_outerIndex = static_cast<StorageIndex*>(std::malloc((outerSize + 1) * sizeof(StorageIndex)));\n        if (!m_outerIndex) internal::throw_std_bad_alloc();\n        \n        m_outerSize = outerSize;\n      }\n      if(m_innerNonZeros)\n      {\n        std::free(m_innerNonZeros);\n        m_innerNonZeros = 0;\n      }\n      memset(m_outerIndex, 0, (m_outerSize+1)*sizeof(StorageIndex));\n    }\n\n    /** \\internal\n      * Resize the nonzero vector to \\a size */\n    void resizeNonZeros(Index size)\n    {\n      m_data.resize(size);\n    }\n\n    /** \\returns a const expression of the diagonal coefficients. */\n    const ConstDiagonalReturnType diagonal() const { return ConstDiagonalReturnType(*this); }\n    \n    /** \\returns a read-write expression of the diagonal coefficients.\n      * \\warning If the diagonal entries are written, then all diagonal\n      * entries \\b must already exist, otherwise an assertion will be raised.\n      */\n    DiagonalReturnType diagonal() { return DiagonalReturnType(*this); }\n\n    /** Default constructor yielding an empty \\c 0 \\c x \\c 0 matrix */\n    inline SparseMatrix()\n      : m_outerSize(-1), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)\n    {\n      check_template_parameters();\n      resize(0, 0);\n    }\n\n    /** Constructs a \\a rows \\c x \\a cols empty matrix */\n    inline SparseMatrix(Index rows, Index cols)\n      : m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)\n    {\n      check_template_parameters();\n      resize(rows, cols);\n    }\n\n    /** Constructs a sparse matrix from the sparse expression \\a other */\n    template<typename OtherDerived>\n    inline SparseMatrix(const SparseMatrixBase<OtherDerived>& other)\n      : m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)\n    {\n      EIGEN_STATIC_ASSERT((internal::is_same<Scalar, typename OtherDerived::Scalar>::value),\n        YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n      check_template_parameters();\n      const bool needToTranspose = (Flags & RowMajorBit) != (internal::evaluator<OtherDerived>::Flags & RowMajorBit);\n      if (needToTranspose)\n        *this = other.derived();\n      else\n      {\n        #ifdef EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n          EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n        #endif\n        internal::call_assignment_no_alias(*this, other.derived());\n      }\n    }\n    \n    /** Constructs a sparse matrix from the sparse selfadjoint view \\a other */\n    template<typename OtherDerived, unsigned int UpLo>\n    inline SparseMatrix(const SparseSelfAdjointView<OtherDerived, UpLo>& other)\n      : m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)\n    {\n      check_template_parameters();\n      Base::operator=(other);\n    }\n\n    /** Copy constructor (it performs a deep copy) */\n    inline SparseMatrix(const SparseMatrix& other)\n      : Base(), m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)\n    {\n      check_template_parameters();\n      *this = other.derived();\n    }\n\n    /** \\brief Copy constructor with in-place evaluation */\n    template<typename OtherDerived>\n    SparseMatrix(const ReturnByValue<OtherDerived>& other)\n      : Base(), m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)\n    {\n      check_template_parameters();\n      initAssignment(other);\n      other.evalTo(*this);\n    }\n    \n    /** \\brief Copy constructor with in-place evaluation */\n    template<typename OtherDerived>\n    explicit SparseMatrix(const DiagonalBase<OtherDerived>& other)\n      : Base(), m_outerSize(0), m_innerSize(0), m_outerIndex(0), m_innerNonZeros(0)\n    {\n      check_template_parameters();\n      *this = other.derived();\n    }\n\n    /** Swaps the content of two sparse matrices of the same type.\n      * This is a fast operation that simply swaps the underlying pointers and parameters. */\n    inline void swap(SparseMatrix& other)\n    {\n      //EIGEN_DBG_SPARSE(std::cout << \"SparseMatrix:: swap\\n\");\n      std::swap(m_outerIndex, other.m_outerIndex);\n      std::swap(m_innerSize, other.m_innerSize);\n      std::swap(m_outerSize, other.m_outerSize);\n      std::swap(m_innerNonZeros, other.m_innerNonZeros);\n      m_data.swap(other.m_data);\n    }\n\n    /** Sets *this to the identity matrix.\n      * This function also turns the matrix into compressed mode, and drop any reserved memory. */\n    inline void setIdentity()\n    {\n      eigen_assert(rows() == cols() && \"ONLY FOR SQUARED MATRICES\");\n      this->m_data.resize(rows());\n      Eigen::Map<IndexVector>(this->m_data.indexPtr(), rows()).setLinSpaced(0, StorageIndex(rows()-1));\n      Eigen::Map<ScalarVector>(this->m_data.valuePtr(), rows()).setOnes();\n      Eigen::Map<IndexVector>(this->m_outerIndex, rows()+1).setLinSpaced(0, StorageIndex(rows()));\n      std::free(m_innerNonZeros);\n      m_innerNonZeros = 0;\n    }\n    inline SparseMatrix& operator=(const SparseMatrix& other)\n    {\n      if (other.isRValue())\n      {\n        swap(other.const_cast_derived());\n      }\n      else if(this!=&other)\n      {\n        #ifdef EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n          EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n        #endif\n        initAssignment(other);\n        if(other.isCompressed())\n        {\n          internal::smart_copy(other.m_outerIndex, other.m_outerIndex + m_outerSize + 1, m_outerIndex);\n          m_data = other.m_data;\n        }\n        else\n        {\n          Base::operator=(other);\n        }\n      }\n      return *this;\n    }\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<typename OtherDerived>\n    inline SparseMatrix& operator=(const EigenBase<OtherDerived>& other)\n    { return Base::operator=(other.derived()); }\n\n    template<typename Lhs, typename Rhs>\n    inline SparseMatrix& operator=(const Product<Lhs,Rhs,AliasFreeProduct>& other);\n#endif // EIGEN_PARSED_BY_DOXYGEN\n\n    template<typename OtherDerived>\n    EIGEN_DONT_INLINE SparseMatrix& operator=(const SparseMatrixBase<OtherDerived>& other);\n\n    friend std::ostream & operator << (std::ostream & s, const SparseMatrix& m)\n    {\n      EIGEN_DBG_SPARSE(\n        s << \"Nonzero entries:\\n\";\n        if(m.isCompressed())\n        {\n          for (Index i=0; i<m.nonZeros(); ++i)\n            s << \"(\" << m.m_data.value(i) << \",\" << m.m_data.index(i) << \") \";\n        }\n        else\n        {\n          for (Index i=0; i<m.outerSize(); ++i)\n          {\n            Index p = m.m_outerIndex[i];\n            Index pe = m.m_outerIndex[i]+m.m_innerNonZeros[i];\n            Index k=p;\n            for (; k<pe; ++k) {\n              s << \"(\" << m.m_data.value(k) << \",\" << m.m_data.index(k) << \") \";\n            }\n            for (; k<m.m_outerIndex[i+1]; ++k) {\n              s << \"(_,_) \";\n            }\n          }\n        }\n        s << std::endl;\n        s << std::endl;\n        s << \"Outer pointers:\\n\";\n        for (Index i=0; i<m.outerSize(); ++i) {\n          s << m.m_outerIndex[i] << \" \";\n        }\n        s << \" $\" << std::endl;\n        if(!m.isCompressed())\n        {\n          s << \"Inner non zeros:\\n\";\n          for (Index i=0; i<m.outerSize(); ++i) {\n            s << m.m_innerNonZeros[i] << \" \";\n          }\n          s << \" $\" << std::endl;\n        }\n        s << std::endl;\n      );\n      s << static_cast<const SparseMatrixBase<SparseMatrix>&>(m);\n      return s;\n    }\n\n    /** Destructor */\n    inline ~SparseMatrix()\n    {\n      std::free(m_outerIndex);\n      std::free(m_innerNonZeros);\n    }\n\n    /** Overloaded for performance */\n    Scalar sum() const;\n    \n#   ifdef EIGEN_SPARSEMATRIX_PLUGIN\n#     include EIGEN_SPARSEMATRIX_PLUGIN\n#   endif\n\nprotected:\n\n    template<typename Other>\n    void initAssignment(const Other& other)\n    {\n      resize(other.rows(), other.cols());\n      if(m_innerNonZeros)\n      {\n        std::free(m_innerNonZeros);\n        m_innerNonZeros = 0;\n      }\n    }\n\n    /** \\internal\n      * \\sa insert(Index,Index) */\n    EIGEN_DONT_INLINE Scalar& insertCompressed(Index row, Index col);\n\n    /** \\internal\n      * A vector object that is equal to 0 everywhere but v at the position i */\n    class SingletonVector\n    {\n        StorageIndex m_index;\n        StorageIndex m_value;\n      public:\n        typedef StorageIndex value_type;\n        SingletonVector(Index i, Index v)\n          : m_index(convert_index(i)), m_value(convert_index(v))\n        {}\n\n        StorageIndex operator[](Index i) const { return i==m_index ? m_value : 0; }\n    };\n\n    /** \\internal\n      * \\sa insert(Index,Index) */\n    EIGEN_DONT_INLINE Scalar& insertUncompressed(Index row, Index col);\n\npublic:\n    /** \\internal\n      * \\sa insert(Index,Index) */\n    EIGEN_STRONG_INLINE Scalar& insertBackUncompressed(Index row, Index col)\n    {\n      const Index outer = IsRowMajor ? row : col;\n      const Index inner = IsRowMajor ? col : row;\n\n      eigen_assert(!isCompressed());\n      eigen_assert(m_innerNonZeros[outer]<=(m_outerIndex[outer+1] - m_outerIndex[outer]));\n\n      Index p = m_outerIndex[outer] + m_innerNonZeros[outer]++;\n      m_data.index(p) = convert_index(inner);\n      return (m_data.value(p) = Scalar(0));\n    }\nprotected:\n    struct IndexPosPair {\n      IndexPosPair(Index a_i, Index a_p) : i(a_i), p(a_p) {}\n      Index i;\n      Index p;\n    };\n\n    /** \\internal assign \\a diagXpr to the diagonal of \\c *this\n      * There are different strategies:\n      *   1 - if *this is overwritten (Func==assign_op) or *this is empty, then we can work treat *this as a dense vector expression.\n      *   2 - otherwise, for each diagonal coeff,\n      *     2.a - if it already exists, then we update it,\n      *     2.b - otherwise, if *this is uncompressed and that the current inner-vector has empty room for at least 1 element, then we perform an in-place insertion.\n      *     2.c - otherwise, we'll have to reallocate and copy everything, so instead of doing so for each new element, it is recorded in a std::vector.\n      *   3 - at the end, if some entries failed to be inserted in-place, then we alloc a new buffer, copy each chunk at the right position, and insert the new elements.\n      * \n      * TODO: some piece of code could be isolated and reused for a general in-place update strategy.\n      * TODO: if we start to defer the insertion of some elements (i.e., case 2.c executed once),\n      *       then it *might* be better to disable case 2.b since they will have to be copied anyway.\n      */\n    template<typename DiagXpr, typename Func>\n    void assignDiagonal(const DiagXpr diagXpr, const Func& assignFunc)\n    {\n      Index n = diagXpr.size();\n\n      const bool overwrite = internal::is_same<Func, internal::assign_op<Scalar,Scalar> >::value;\n      if(overwrite)\n      {\n        if((this->rows()!=n) || (this->cols()!=n))\n          this->resize(n, n);\n      }\n\n      if(m_data.size()==0 || overwrite)\n      {\n        typedef Array<StorageIndex,Dynamic,1> ArrayXI;  \n        this->makeCompressed();\n        this->resizeNonZeros(n);\n        Eigen::Map<ArrayXI>(this->innerIndexPtr(), n).setLinSpaced(0,StorageIndex(n)-1);\n        Eigen::Map<ArrayXI>(this->outerIndexPtr(), n+1).setLinSpaced(0,StorageIndex(n));\n        Eigen::Map<Array<Scalar,Dynamic,1> > values = this->coeffs();\n        values.setZero();\n        internal::call_assignment_no_alias(values, diagXpr, assignFunc);\n      }\n      else\n      {\n        bool isComp = isCompressed();\n        internal::evaluator<DiagXpr> diaEval(diagXpr);\n        std::vector<IndexPosPair> newEntries;\n\n        // 1 - try in-place update and record insertion failures\n        for(Index i = 0; i<n; ++i)\n        {\n          internal::LowerBoundIndex lb = this->lower_bound(i,i);\n          Index p = lb.value;\n          if(lb.found)\n          {\n            // the coeff already exists\n            assignFunc.assignCoeff(m_data.value(p), diaEval.coeff(i));\n          }\n          else if((!isComp) && m_innerNonZeros[i] < (m_outerIndex[i+1]-m_outerIndex[i]))\n          {\n            // non compressed mode with local room for inserting one element\n            m_data.moveChunk(p, p+1, m_outerIndex[i]+m_innerNonZeros[i]-p);\n            m_innerNonZeros[i]++;\n            m_data.value(p) = Scalar(0);\n            m_data.index(p) = StorageIndex(i);\n            assignFunc.assignCoeff(m_data.value(p), diaEval.coeff(i));\n          }\n          else\n          {\n            // defer insertion\n            newEntries.push_back(IndexPosPair(i,p));\n          }\n        }\n        // 2 - insert deferred entries\n        Index n_entries = Index(newEntries.size());\n        if(n_entries>0)\n        {\n          Storage newData(m_data.size()+n_entries);\n          Index prev_p = 0;\n          Index prev_i = 0;\n          for(Index k=0; k<n_entries;++k)\n          {\n            Index i = newEntries[k].i;\n            Index p = newEntries[k].p;\n            internal::smart_copy(m_data.valuePtr()+prev_p, m_data.valuePtr()+p, newData.valuePtr()+prev_p+k);\n            internal::smart_copy(m_data.indexPtr()+prev_p, m_data.indexPtr()+p, newData.indexPtr()+prev_p+k);\n            for(Index j=prev_i;j<i;++j)\n              m_outerIndex[j+1] += k;\n            if(!isComp)\n              m_innerNonZeros[i]++;\n            prev_p = p;\n            prev_i = i;\n            newData.value(p+k) = Scalar(0);\n            newData.index(p+k) = StorageIndex(i);\n            assignFunc.assignCoeff(newData.value(p+k), diaEval.coeff(i));\n          }\n          {\n            internal::smart_copy(m_data.valuePtr()+prev_p, m_data.valuePtr()+m_data.size(), newData.valuePtr()+prev_p+n_entries);\n            internal::smart_copy(m_data.indexPtr()+prev_p, m_data.indexPtr()+m_data.size(), newData.indexPtr()+prev_p+n_entries);\n            for(Index j=prev_i+1;j<=m_outerSize;++j)\n              m_outerIndex[j] += n_entries;\n          }\n          m_data.swap(newData);\n        }\n      }\n    }\n\nprivate:\n  static void check_template_parameters()\n  {\n    EIGEN_STATIC_ASSERT(NumTraits<StorageIndex>::IsSigned,THE_INDEX_TYPE_MUST_BE_A_SIGNED_TYPE);\n    EIGEN_STATIC_ASSERT((Options&(ColMajor|RowMajor))==Options,INVALID_MATRIX_TEMPLATE_PARAMETERS);\n  }\n\n  struct default_prunning_func {\n    default_prunning_func(const Scalar& ref, const RealScalar& eps) : reference(ref), epsilon(eps) {}\n    inline bool operator() (const Index&, const Index&, const Scalar& value) const\n    {\n      return !internal::isMuchSmallerThan(value, reference, epsilon);\n    }\n    Scalar reference;\n    RealScalar epsilon;\n  };\n};\n\nnamespace internal {\n\ntemplate<typename InputIterator, typename SparseMatrixType, typename DupFunctor>\nvoid set_from_triplets(const InputIterator& begin, const InputIterator& end, SparseMatrixType& mat, DupFunctor dup_func)\n{\n  enum { IsRowMajor = SparseMatrixType::IsRowMajor };\n  typedef typename SparseMatrixType::Scalar Scalar;\n  typedef typename SparseMatrixType::StorageIndex StorageIndex;\n  SparseMatrix<Scalar,IsRowMajor?ColMajor:RowMajor,StorageIndex> trMat(mat.rows(),mat.cols());\n\n  if(begin!=end)\n  {\n    // pass 1: count the nnz per inner-vector\n    typename SparseMatrixType::IndexVector wi(trMat.outerSize());\n    wi.setZero();\n    for(InputIterator it(begin); it!=end; ++it)\n    {\n      eigen_assert(it->row()>=0 && it->row()<mat.rows() && it->col()>=0 && it->col()<mat.cols());\n      wi(IsRowMajor ? it->col() : it->row())++;\n    }\n\n    // pass 2: insert all the elements into trMat\n    trMat.reserve(wi);\n    for(InputIterator it(begin); it!=end; ++it)\n      trMat.insertBackUncompressed(it->row(),it->col()) = it->value();\n\n    // pass 3:\n    trMat.collapseDuplicates(dup_func);\n  }\n\n  // pass 4: transposed copy -> implicit sorting\n  mat = trMat;\n}\n\n}\n\n\n/** Fill the matrix \\c *this with the list of \\em triplets defined by the iterator range \\a begin - \\a end.\n  *\n  * A \\em triplet is a tuple (i,j,value) defining a non-zero element.\n  * The input list of triplets does not have to be sorted, and can contains duplicated elements.\n  * In any case, the result is a \\b sorted and \\b compressed sparse matrix where the duplicates have been summed up.\n  * This is a \\em O(n) operation, with \\em n the number of triplet elements.\n  * The initial contents of \\c *this is destroyed.\n  * The matrix \\c *this must be properly resized beforehand using the SparseMatrix(Index,Index) constructor,\n  * or the resize(Index,Index) method. The sizes are not extracted from the triplet list.\n  *\n  * The \\a InputIterators value_type must provide the following interface:\n  * \\code\n  * Scalar value() const; // the value\n  * Scalar row() const;   // the row index i\n  * Scalar col() const;   // the column index j\n  * \\endcode\n  * See for instance the Eigen::Triplet template class.\n  *\n  * Here is a typical usage example:\n  * \\code\n    typedef Triplet<double> T;\n    std::vector<T> tripletList;\n    tripletList.reserve(estimation_of_entries);\n    for(...)\n    {\n      // ...\n      tripletList.push_back(T(i,j,v_ij));\n    }\n    SparseMatrixType m(rows,cols);\n    m.setFromTriplets(tripletList.begin(), tripletList.end());\n    // m is ready to go!\n  * \\endcode\n  *\n  * \\warning The list of triplets is read multiple times (at least twice). Therefore, it is not recommended to define\n  * an abstract iterator over a complex data-structure that would be expensive to evaluate. The triplets should rather\n  * be explicitly stored into a std::vector for instance.\n  */\ntemplate<typename Scalar, int _Options, typename _StorageIndex>\ntemplate<typename InputIterators>\nvoid SparseMatrix<Scalar,_Options,_StorageIndex>::setFromTriplets(const InputIterators& begin, const InputIterators& end)\n{\n  internal::set_from_triplets<InputIterators, SparseMatrix<Scalar,_Options,_StorageIndex> >(begin, end, *this, internal::scalar_sum_op<Scalar,Scalar>());\n}\n\n/** The same as setFromTriplets but when duplicates are met the functor \\a dup_func is applied:\n  * \\code\n  * value = dup_func(OldValue, NewValue)\n  * \\endcode \n  * Here is a C++11 example keeping the latest entry only:\n  * \\code\n  * mat.setFromTriplets(triplets.begin(), triplets.end(), [] (const Scalar&,const Scalar &b) { return b; });\n  * \\endcode\n  */\ntemplate<typename Scalar, int _Options, typename _StorageIndex>\ntemplate<typename InputIterators,typename DupFunctor>\nvoid SparseMatrix<Scalar,_Options,_StorageIndex>::setFromTriplets(const InputIterators& begin, const InputIterators& end, DupFunctor dup_func)\n{\n  internal::set_from_triplets<InputIterators, SparseMatrix<Scalar,_Options,_StorageIndex>, DupFunctor>(begin, end, *this, dup_func);\n}\n\n/** \\internal */\ntemplate<typename Scalar, int _Options, typename _StorageIndex>\ntemplate<typename DupFunctor>\nvoid SparseMatrix<Scalar,_Options,_StorageIndex>::collapseDuplicates(DupFunctor dup_func)\n{\n  eigen_assert(!isCompressed());\n  // TODO, in practice we should be able to use m_innerNonZeros for that task\n  IndexVector wi(innerSize());\n  wi.fill(-1);\n  StorageIndex count = 0;\n  // for each inner-vector, wi[inner_index] will hold the position of first element into the index/value buffers\n  for(Index j=0; j<outerSize(); ++j)\n  {\n    StorageIndex start   = count;\n    Index oldEnd  = m_outerIndex[j]+m_innerNonZeros[j];\n    for(Index k=m_outerIndex[j]; k<oldEnd; ++k)\n    {\n      Index i = m_data.index(k);\n      if(wi(i)>=start)\n      {\n        // we already meet this entry => accumulate it\n        m_data.value(wi(i)) = dup_func(m_data.value(wi(i)), m_data.value(k));\n      }\n      else\n      {\n        m_data.value(count) = m_data.value(k);\n        m_data.index(count) = m_data.index(k);\n        wi(i) = count;\n        ++count;\n      }\n    }\n    m_outerIndex[j] = start;\n  }\n  m_outerIndex[m_outerSize] = count;\n\n  // turn the matrix into compressed form\n  std::free(m_innerNonZeros);\n  m_innerNonZeros = 0;\n  m_data.resize(m_outerIndex[m_outerSize]);\n}\n\ntemplate<typename Scalar, int _Options, typename _StorageIndex>\ntemplate<typename OtherDerived>\nEIGEN_DONT_INLINE SparseMatrix<Scalar,_Options,_StorageIndex>& SparseMatrix<Scalar,_Options,_StorageIndex>::operator=(const SparseMatrixBase<OtherDerived>& other)\n{\n  EIGEN_STATIC_ASSERT((internal::is_same<Scalar, typename OtherDerived::Scalar>::value),\n        YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n\n  #ifdef EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n    EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n  #endif\n      \n  const bool needToTranspose = (Flags & RowMajorBit) != (internal::evaluator<OtherDerived>::Flags & RowMajorBit);\n  if (needToTranspose)\n  {\n    #ifdef EIGEN_SPARSE_TRANSPOSED_COPY_PLUGIN\n      EIGEN_SPARSE_TRANSPOSED_COPY_PLUGIN\n    #endif\n    // two passes algorithm:\n    //  1 - compute the number of coeffs per dest inner vector\n    //  2 - do the actual copy/eval\n    // Since each coeff of the rhs has to be evaluated twice, let's evaluate it if needed\n    typedef typename internal::nested_eval<OtherDerived,2,typename internal::plain_matrix_type<OtherDerived>::type >::type OtherCopy;\n    typedef typename internal::remove_all<OtherCopy>::type _OtherCopy;\n    typedef internal::evaluator<_OtherCopy> OtherCopyEval;\n    OtherCopy otherCopy(other.derived());\n    OtherCopyEval otherCopyEval(otherCopy);\n\n    SparseMatrix dest(other.rows(),other.cols());\n    Eigen::Map<IndexVector> (dest.m_outerIndex,dest.outerSize()).setZero();\n\n    // pass 1\n    // FIXME the above copy could be merged with that pass\n    for (Index j=0; j<otherCopy.outerSize(); ++j)\n      for (typename OtherCopyEval::InnerIterator it(otherCopyEval, j); it; ++it)\n        ++dest.m_outerIndex[it.index()];\n\n    // prefix sum\n    StorageIndex count = 0;\n    IndexVector positions(dest.outerSize());\n    for (Index j=0; j<dest.outerSize(); ++j)\n    {\n      StorageIndex tmp = dest.m_outerIndex[j];\n      dest.m_outerIndex[j] = count;\n      positions[j] = count;\n      count += tmp;\n    }\n    dest.m_outerIndex[dest.outerSize()] = count;\n    // alloc\n    dest.m_data.resize(count);\n    // pass 2\n    for (StorageIndex j=0; j<otherCopy.outerSize(); ++j)\n    {\n      for (typename OtherCopyEval::InnerIterator it(otherCopyEval, j); it; ++it)\n      {\n        Index pos = positions[it.index()]++;\n        dest.m_data.index(pos) = j;\n        dest.m_data.value(pos) = it.value();\n      }\n    }\n    this->swap(dest);\n    return *this;\n  }\n  else\n  {\n    if(other.isRValue())\n    {\n      initAssignment(other.derived());\n    }\n    // there is no special optimization\n    return Base::operator=(other.derived());\n  }\n}\n\ntemplate<typename _Scalar, int _Options, typename _StorageIndex>\ntypename SparseMatrix<_Scalar,_Options,_StorageIndex>::Scalar& SparseMatrix<_Scalar,_Options,_StorageIndex>::insert(Index row, Index col)\n{\n  eigen_assert(row>=0 && row<rows() && col>=0 && col<cols());\n  \n  const Index outer = IsRowMajor ? row : col;\n  const Index inner = IsRowMajor ? col : row;\n  \n  if(isCompressed())\n  {\n    if(nonZeros()==0)\n    {\n      // reserve space if not already done\n      if(m_data.allocatedSize()==0)\n        m_data.reserve(2*m_innerSize);\n      \n      // turn the matrix into non-compressed mode\n      m_innerNonZeros = static_cast<StorageIndex*>(std::malloc(m_outerSize * sizeof(StorageIndex)));\n      if(!m_innerNonZeros) internal::throw_std_bad_alloc();\n      \n      memset(m_innerNonZeros, 0, (m_outerSize)*sizeof(StorageIndex));\n      \n      // pack all inner-vectors to the end of the pre-allocated space\n      // and allocate the entire free-space to the first inner-vector\n      StorageIndex end = convert_index(m_data.allocatedSize());\n      for(Index j=1; j<=m_outerSize; ++j)\n        m_outerIndex[j] = end;\n    }\n    else\n    {\n      // turn the matrix into non-compressed mode\n      m_innerNonZeros = static_cast<StorageIndex*>(std::malloc(m_outerSize * sizeof(StorageIndex)));\n      if(!m_innerNonZeros) internal::throw_std_bad_alloc();\n      for(Index j=0; j<m_outerSize; ++j)\n        m_innerNonZeros[j] = m_outerIndex[j+1]-m_outerIndex[j];\n    }\n  }\n  \n  // check whether we can do a fast \"push back\" insertion\n  Index data_end = m_data.allocatedSize();\n  \n  // First case: we are filling a new inner vector which is packed at the end.\n  // We assume that all remaining inner-vectors are also empty and packed to the end.\n  if(m_outerIndex[outer]==data_end)\n  {\n    eigen_internal_assert(m_innerNonZeros[outer]==0);\n    \n    // pack previous empty inner-vectors to end of the used-space\n    // and allocate the entire free-space to the current inner-vector.\n    StorageIndex p = convert_index(m_data.size());\n    Index j = outer;\n    while(j>=0 && m_innerNonZeros[j]==0)\n      m_outerIndex[j--] = p;\n    \n    // push back the new element\n    ++m_innerNonZeros[outer];\n    m_data.append(Scalar(0), inner);\n    \n    // check for reallocation\n    if(data_end != m_data.allocatedSize())\n    {\n      // m_data has been reallocated\n      //  -> move remaining inner-vectors back to the end of the free-space\n      //     so that the entire free-space is allocated to the current inner-vector.\n      eigen_internal_assert(data_end < m_data.allocatedSize());\n      StorageIndex new_end = convert_index(m_data.allocatedSize());\n      for(Index k=outer+1; k<=m_outerSize; ++k)\n        if(m_outerIndex[k]==data_end)\n          m_outerIndex[k] = new_end;\n    }\n    return m_data.value(p);\n  }\n  \n  // Second case: the next inner-vector is packed to the end\n  // and the current inner-vector end match the used-space.\n  if(m_outerIndex[outer+1]==data_end && m_outerIndex[outer]+m_innerNonZeros[outer]==m_data.size())\n  {\n    eigen_internal_assert(outer+1==m_outerSize || m_innerNonZeros[outer+1]==0);\n    \n    // add space for the new element\n    ++m_innerNonZeros[outer];\n    m_data.resize(m_data.size()+1);\n    \n    // check for reallocation\n    if(data_end != m_data.allocatedSize())\n    {\n      // m_data has been reallocated\n      //  -> move remaining inner-vectors back to the end of the free-space\n      //     so that the entire free-space is allocated to the current inner-vector.\n      eigen_internal_assert(data_end < m_data.allocatedSize());\n      StorageIndex new_end = convert_index(m_data.allocatedSize());\n      for(Index k=outer+1; k<=m_outerSize; ++k)\n        if(m_outerIndex[k]==data_end)\n          m_outerIndex[k] = new_end;\n    }\n    \n    // and insert it at the right position (sorted insertion)\n    Index startId = m_outerIndex[outer];\n    Index p = m_outerIndex[outer]+m_innerNonZeros[outer]-1;\n    while ( (p > startId) && (m_data.index(p-1) > inner) )\n    {\n      m_data.index(p) = m_data.index(p-1);\n      m_data.value(p) = m_data.value(p-1);\n      --p;\n    }\n    \n    m_data.index(p) = convert_index(inner);\n    return (m_data.value(p) = Scalar(0));\n  }\n  \n  if(m_data.size() != m_data.allocatedSize())\n  {\n    // make sure the matrix is compatible to random un-compressed insertion:\n    m_data.resize(m_data.allocatedSize());\n    this->reserveInnerVectors(Array<StorageIndex,Dynamic,1>::Constant(m_outerSize, 2));\n  }\n  \n  return insertUncompressed(row,col);\n}\n    \ntemplate<typename _Scalar, int _Options, typename _StorageIndex>\nEIGEN_DONT_INLINE typename SparseMatrix<_Scalar,_Options,_StorageIndex>::Scalar& SparseMatrix<_Scalar,_Options,_StorageIndex>::insertUncompressed(Index row, Index col)\n{\n  eigen_assert(!isCompressed());\n\n  const Index outer = IsRowMajor ? row : col;\n  const StorageIndex inner = convert_index(IsRowMajor ? col : row);\n\n  Index room = m_outerIndex[outer+1] - m_outerIndex[outer];\n  StorageIndex innerNNZ = m_innerNonZeros[outer];\n  if(innerNNZ>=room)\n  {\n    // this inner vector is full, we need to reallocate the whole buffer :(\n    reserve(SingletonVector(outer,std::max<StorageIndex>(2,innerNNZ)));\n  }\n\n  Index startId = m_outerIndex[outer];\n  Index p = startId + m_innerNonZeros[outer];\n  while ( (p > startId) && (m_data.index(p-1) > inner) )\n  {\n    m_data.index(p) = m_data.index(p-1);\n    m_data.value(p) = m_data.value(p-1);\n    --p;\n  }\n  eigen_assert((p<=startId || m_data.index(p-1)!=inner) && \"you cannot insert an element that already exists, you must call coeffRef to this end\");\n\n  m_innerNonZeros[outer]++;\n\n  m_data.index(p) = inner;\n  return (m_data.value(p) = Scalar(0));\n}\n\ntemplate<typename _Scalar, int _Options, typename _StorageIndex>\nEIGEN_DONT_INLINE typename SparseMatrix<_Scalar,_Options,_StorageIndex>::Scalar& SparseMatrix<_Scalar,_Options,_StorageIndex>::insertCompressed(Index row, Index col)\n{\n  eigen_assert(isCompressed());\n\n  const Index outer = IsRowMajor ? row : col;\n  const Index inner = IsRowMajor ? col : row;\n\n  Index previousOuter = outer;\n  if (m_outerIndex[outer+1]==0)\n  {\n    // we start a new inner vector\n    while (previousOuter>=0 && m_outerIndex[previousOuter]==0)\n    {\n      m_outerIndex[previousOuter] = convert_index(m_data.size());\n      --previousOuter;\n    }\n    m_outerIndex[outer+1] = m_outerIndex[outer];\n  }\n\n  // here we have to handle the tricky case where the outerIndex array\n  // starts with: [ 0 0 0 0 0 1 ...] and we are inserted in, e.g.,\n  // the 2nd inner vector...\n  bool isLastVec = (!(previousOuter==-1 && m_data.size()!=0))\n                && (std::size_t(m_outerIndex[outer+1]) == m_data.size());\n\n  std::size_t startId = m_outerIndex[outer];\n  // FIXME let's make sure sizeof(long int) == sizeof(std::size_t)\n  std::size_t p = m_outerIndex[outer+1];\n  ++m_outerIndex[outer+1];\n\n  double reallocRatio = 1;\n  if (m_data.allocatedSize()<=m_data.size())\n  {\n    // if there is no preallocated memory, let's reserve a minimum of 32 elements\n    if (m_data.size()==0)\n    {\n      m_data.reserve(32);\n    }\n    else\n    {\n      // we need to reallocate the data, to reduce multiple reallocations\n      // we use a smart resize algorithm based on the current filling ratio\n      // in addition, we use double to avoid integers overflows\n      double nnzEstimate = double(m_outerIndex[outer])*double(m_outerSize)/double(outer+1);\n      reallocRatio = (nnzEstimate-double(m_data.size()))/double(m_data.size());\n      // furthermore we bound the realloc ratio to:\n      //   1) reduce multiple minor realloc when the matrix is almost filled\n      //   2) avoid to allocate too much memory when the matrix is almost empty\n      reallocRatio = (std::min)((std::max)(reallocRatio,1.5),8.);\n    }\n  }\n  m_data.resize(m_data.size()+1,reallocRatio);\n\n  if (!isLastVec)\n  {\n    if (previousOuter==-1)\n    {\n      // oops wrong guess.\n      // let's correct the outer offsets\n      for (Index k=0; k<=(outer+1); ++k)\n        m_outerIndex[k] = 0;\n      Index k=outer+1;\n      while(m_outerIndex[k]==0)\n        m_outerIndex[k++] = 1;\n      while (k<=m_outerSize && m_outerIndex[k]!=0)\n        m_outerIndex[k++]++;\n      p = 0;\n      --k;\n      k = m_outerIndex[k]-1;\n      while (k>0)\n      {\n        m_data.index(k) = m_data.index(k-1);\n        m_data.value(k) = m_data.value(k-1);\n        k--;\n      }\n    }\n    else\n    {\n      // we are not inserting into the last inner vec\n      // update outer indices:\n      Index j = outer+2;\n      while (j<=m_outerSize && m_outerIndex[j]!=0)\n        m_outerIndex[j++]++;\n      --j;\n      // shift data of last vecs:\n      Index k = m_outerIndex[j]-1;\n      while (k>=Index(p))\n      {\n        m_data.index(k) = m_data.index(k-1);\n        m_data.value(k) = m_data.value(k-1);\n        k--;\n      }\n    }\n  }\n\n  while ( (p > startId) && (m_data.index(p-1) > inner) )\n  {\n    m_data.index(p) = m_data.index(p-1);\n    m_data.value(p) = m_data.value(p-1);\n    --p;\n  }\n\n  m_data.index(p) = inner;\n  return (m_data.value(p) = Scalar(0));\n}\n\nnamespace internal {\n\ntemplate<typename _Scalar, int _Options, typename _StorageIndex>\nstruct evaluator<SparseMatrix<_Scalar,_Options,_StorageIndex> >\n  : evaluator<SparseCompressedBase<SparseMatrix<_Scalar,_Options,_StorageIndex> > >\n{\n  typedef evaluator<SparseCompressedBase<SparseMatrix<_Scalar,_Options,_StorageIndex> > > Base;\n  typedef SparseMatrix<_Scalar,_Options,_StorageIndex> SparseMatrixType;\n  evaluator() : Base() {}\n  explicit evaluator(const SparseMatrixType &mat) : Base(mat) {}\n};\n\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSEMATRIX_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseMatrixBase.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEMATRIXBASE_H\n#define EIGEN_SPARSEMATRIXBASE_H\n\nnamespace Eigen { \n\n/** \\ingroup SparseCore_Module\n  *\n  * \\class SparseMatrixBase\n  *\n  * \\brief Base class of any sparse matrices or sparse expressions\n  *\n  * \\tparam Derived is the derived type, e.g. a sparse matrix type, or an expression, etc.\n  *\n  * This class can be extended with the help of the plugin mechanism described on the page\n  * \\ref TopicCustomizing_Plugins by defining the preprocessor symbol \\c EIGEN_SPARSEMATRIXBASE_PLUGIN.\n  */\ntemplate<typename Derived> class SparseMatrixBase\n  : public EigenBase<Derived>\n{\n  public:\n\n    typedef typename internal::traits<Derived>::Scalar Scalar;\n    \n    /** The numeric type of the expression' coefficients, e.g. float, double, int or std::complex<float>, etc.\n      *\n      * It is an alias for the Scalar type */\n    typedef Scalar value_type;\n    \n    typedef typename internal::packet_traits<Scalar>::type PacketScalar;\n    typedef typename internal::traits<Derived>::StorageKind StorageKind;\n\n    /** The integer type used to \\b store indices within a SparseMatrix.\n      * For a \\c SparseMatrix<Scalar,Options,IndexType> it an alias of the third template parameter \\c IndexType. */\n    typedef typename internal::traits<Derived>::StorageIndex StorageIndex;\n\n    typedef typename internal::add_const_on_value_type_if_arithmetic<\n                         typename internal::packet_traits<Scalar>::type\n                     >::type PacketReturnType;\n\n    typedef SparseMatrixBase StorageBaseType;\n\n    typedef Matrix<StorageIndex,Dynamic,1> IndexVector;\n    typedef Matrix<Scalar,Dynamic,1> ScalarVector;\n    \n    template<typename OtherDerived>\n    Derived& operator=(const EigenBase<OtherDerived> &other);\n\n    enum {\n\n      RowsAtCompileTime = internal::traits<Derived>::RowsAtCompileTime,\n        /**< The number of rows at compile-time. This is just a copy of the value provided\n          * by the \\a Derived type. If a value is not known at compile-time,\n          * it is set to the \\a Dynamic constant.\n          * \\sa MatrixBase::rows(), MatrixBase::cols(), ColsAtCompileTime, SizeAtCompileTime */\n\n      ColsAtCompileTime = internal::traits<Derived>::ColsAtCompileTime,\n        /**< The number of columns at compile-time. This is just a copy of the value provided\n          * by the \\a Derived type. If a value is not known at compile-time,\n          * it is set to the \\a Dynamic constant.\n          * \\sa MatrixBase::rows(), MatrixBase::cols(), RowsAtCompileTime, SizeAtCompileTime */\n\n\n      SizeAtCompileTime = (internal::size_at_compile_time<internal::traits<Derived>::RowsAtCompileTime,\n                                                   internal::traits<Derived>::ColsAtCompileTime>::ret),\n        /**< This is equal to the number of coefficients, i.e. the number of\n          * rows times the number of columns, or to \\a Dynamic if this is not\n          * known at compile-time. \\sa RowsAtCompileTime, ColsAtCompileTime */\n\n      MaxRowsAtCompileTime = RowsAtCompileTime,\n      MaxColsAtCompileTime = ColsAtCompileTime,\n\n      MaxSizeAtCompileTime = (internal::size_at_compile_time<MaxRowsAtCompileTime,\n                                                      MaxColsAtCompileTime>::ret),\n\n      IsVectorAtCompileTime = RowsAtCompileTime == 1 || ColsAtCompileTime == 1,\n        /**< This is set to true if either the number of rows or the number of\n          * columns is known at compile-time to be equal to 1. Indeed, in that case,\n          * we are dealing with a column-vector (if there is only one column) or with\n          * a row-vector (if there is only one row). */\n\n      NumDimensions = int(MaxSizeAtCompileTime) == 1 ? 0 : bool(IsVectorAtCompileTime) ? 1 : 2,\n        /**< This value is equal to Tensor::NumDimensions, i.e. 0 for scalars, 1 for vectors,\n         * and 2 for matrices.\n         */\n\n      Flags = internal::traits<Derived>::Flags,\n        /**< This stores expression \\ref flags flags which may or may not be inherited by new expressions\n          * constructed from this one. See the \\ref flags \"list of flags\".\n          */\n\n      IsRowMajor = Flags&RowMajorBit ? 1 : 0,\n      \n      InnerSizeAtCompileTime = int(IsVectorAtCompileTime) ? int(SizeAtCompileTime)\n                             : int(IsRowMajor) ? int(ColsAtCompileTime) : int(RowsAtCompileTime),\n\n      #ifndef EIGEN_PARSED_BY_DOXYGEN\n      _HasDirectAccess = (int(Flags)&DirectAccessBit) ? 1 : 0 // workaround sunCC\n      #endif\n    };\n\n    /** \\internal the return type of MatrixBase::adjoint() */\n    typedef typename internal::conditional<NumTraits<Scalar>::IsComplex,\n                        CwiseUnaryOp<internal::scalar_conjugate_op<Scalar>, Eigen::Transpose<const Derived> >,\n                        Transpose<const Derived>\n                     >::type AdjointReturnType;\n    typedef Transpose<Derived> TransposeReturnType;\n    typedef typename internal::add_const<Transpose<const Derived> >::type ConstTransposeReturnType;\n\n    // FIXME storage order do not match evaluator storage order\n    typedef SparseMatrix<Scalar, Flags&RowMajorBit ? RowMajor : ColMajor, StorageIndex> PlainObject;\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n    /** This is the \"real scalar\" type; if the \\a Scalar type is already real numbers\n      * (e.g. int, float or double) then \\a RealScalar is just the same as \\a Scalar. If\n      * \\a Scalar is \\a std::complex<T> then RealScalar is \\a T.\n      *\n      * \\sa class NumTraits\n      */\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n\n    /** \\internal the return type of coeff()\n      */\n    typedef typename internal::conditional<_HasDirectAccess, const Scalar&, Scalar>::type CoeffReturnType;\n\n    /** \\internal Represents a matrix with all coefficients equal to one another*/\n    typedef CwiseNullaryOp<internal::scalar_constant_op<Scalar>,Matrix<Scalar,Dynamic,Dynamic> > ConstantReturnType;\n\n    /** type of the equivalent dense matrix */\n    typedef Matrix<Scalar,RowsAtCompileTime,ColsAtCompileTime> DenseMatrixType;\n    /** type of the equivalent square matrix */\n    typedef Matrix<Scalar,EIGEN_SIZE_MAX(RowsAtCompileTime,ColsAtCompileTime),\n                          EIGEN_SIZE_MAX(RowsAtCompileTime,ColsAtCompileTime)> SquareMatrixType;\n\n    inline const Derived& derived() const { return *static_cast<const Derived*>(this); }\n    inline Derived& derived() { return *static_cast<Derived*>(this); }\n    inline Derived& const_cast_derived() const\n    { return *static_cast<Derived*>(const_cast<SparseMatrixBase*>(this)); }\n\n    typedef EigenBase<Derived> Base;\n\n#endif // not EIGEN_PARSED_BY_DOXYGEN\n\n#define EIGEN_CURRENT_STORAGE_BASE_CLASS Eigen::SparseMatrixBase\n#ifdef EIGEN_PARSED_BY_DOXYGEN\n#define EIGEN_DOC_UNARY_ADDONS(METHOD,OP)           /** <p>This method does not change the sparsity of \\c *this: the OP is applied to explicitly stored coefficients only. \\sa SparseCompressedBase::coeffs() </p> */\n#define EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL      /** <p> \\warning This method returns a read-only expression for any sparse matrices. \\sa \\ref TutorialSparse_SubMatrices \"Sparse block operations\" </p> */\n#define EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(COND) /** <p> \\warning This method returns a read-write expression for COND sparse matrices only. Otherwise, the returned expression is read-only. \\sa \\ref TutorialSparse_SubMatrices \"Sparse block operations\" </p> */\n#else\n#define EIGEN_DOC_UNARY_ADDONS(X,Y)\n#define EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n#define EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(COND)\n#endif\n#   include \"../plugins/CommonCwiseUnaryOps.h\"\n#   include \"../plugins/CommonCwiseBinaryOps.h\"\n#   include \"../plugins/MatrixCwiseUnaryOps.h\"\n#   include \"../plugins/MatrixCwiseBinaryOps.h\"\n#   include \"../plugins/BlockMethods.h\"\n#   ifdef EIGEN_SPARSEMATRIXBASE_PLUGIN\n#     include EIGEN_SPARSEMATRIXBASE_PLUGIN\n#   endif\n#undef EIGEN_CURRENT_STORAGE_BASE_CLASS\n#undef EIGEN_DOC_UNARY_ADDONS\n#undef EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n#undef EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF\n\n    /** \\returns the number of rows. \\sa cols() */\n    inline Index rows() const { return derived().rows(); }\n    /** \\returns the number of columns. \\sa rows() */\n    inline Index cols() const { return derived().cols(); }\n    /** \\returns the number of coefficients, which is \\a rows()*cols().\n      * \\sa rows(), cols(). */\n    inline Index size() const { return rows() * cols(); }\n    /** \\returns true if either the number of rows or the number of columns is equal to 1.\n      * In other words, this function returns\n      * \\code rows()==1 || cols()==1 \\endcode\n      * \\sa rows(), cols(), IsVectorAtCompileTime. */\n    inline bool isVector() const { return rows()==1 || cols()==1; }\n    /** \\returns the size of the storage major dimension,\n      * i.e., the number of columns for a columns major matrix, and the number of rows otherwise */\n    Index outerSize() const { return (int(Flags)&RowMajorBit) ? this->rows() : this->cols(); }\n    /** \\returns the size of the inner dimension according to the storage order,\n      * i.e., the number of rows for a columns major matrix, and the number of cols otherwise */\n    Index innerSize() const { return (int(Flags)&RowMajorBit) ? this->cols() : this->rows(); }\n\n    bool isRValue() const { return m_isRValue; }\n    Derived& markAsRValue() { m_isRValue = true; return derived(); }\n\n    SparseMatrixBase() : m_isRValue(false) { /* TODO check flags */ }\n\n    \n    template<typename OtherDerived>\n    Derived& operator=(const ReturnByValue<OtherDerived>& other);\n\n    template<typename OtherDerived>\n    inline Derived& operator=(const SparseMatrixBase<OtherDerived>& other);\n\n    inline Derived& operator=(const Derived& other);\n\n  protected:\n\n    template<typename OtherDerived>\n    inline Derived& assign(const OtherDerived& other);\n\n    template<typename OtherDerived>\n    inline void assignGeneric(const OtherDerived& other);\n\n  public:\n\n    friend std::ostream & operator << (std::ostream & s, const SparseMatrixBase& m)\n    {\n      typedef typename Derived::Nested Nested;\n      typedef typename internal::remove_all<Nested>::type NestedCleaned;\n\n      if (Flags&RowMajorBit)\n      {\n        Nested nm(m.derived());\n        internal::evaluator<NestedCleaned> thisEval(nm);\n        for (Index row=0; row<nm.outerSize(); ++row)\n        {\n          Index col = 0;\n          for (typename internal::evaluator<NestedCleaned>::InnerIterator it(thisEval, row); it; ++it)\n          {\n            for ( ; col<it.index(); ++col)\n              s << \"0 \";\n            s << it.value() << \" \";\n            ++col;\n          }\n          for ( ; col<m.cols(); ++col)\n            s << \"0 \";\n          s << std::endl;\n        }\n      }\n      else\n      {\n        Nested nm(m.derived());\n        internal::evaluator<NestedCleaned> thisEval(nm);\n        if (m.cols() == 1) {\n          Index row = 0;\n          for (typename internal::evaluator<NestedCleaned>::InnerIterator it(thisEval, 0); it; ++it)\n          {\n            for ( ; row<it.index(); ++row)\n              s << \"0\" << std::endl;\n            s << it.value() << std::endl;\n            ++row;\n          }\n          for ( ; row<m.rows(); ++row)\n            s << \"0\" << std::endl;\n        }\n        else\n        {\n          SparseMatrix<Scalar, RowMajorBit, StorageIndex> trans = m;\n          s << static_cast<const SparseMatrixBase<SparseMatrix<Scalar, RowMajorBit, StorageIndex> >&>(trans);\n        }\n      }\n      return s;\n    }\n\n    template<typename OtherDerived>\n    Derived& operator+=(const SparseMatrixBase<OtherDerived>& other);\n    template<typename OtherDerived>\n    Derived& operator-=(const SparseMatrixBase<OtherDerived>& other);\n    \n    template<typename OtherDerived>\n    Derived& operator+=(const DiagonalBase<OtherDerived>& other);\n    template<typename OtherDerived>\n    Derived& operator-=(const DiagonalBase<OtherDerived>& other);\n\n    template<typename OtherDerived>\n    Derived& operator+=(const EigenBase<OtherDerived> &other);\n    template<typename OtherDerived>\n    Derived& operator-=(const EigenBase<OtherDerived> &other);\n\n    Derived& operator*=(const Scalar& other);\n    Derived& operator/=(const Scalar& other);\n\n    template<typename OtherDerived> struct CwiseProductDenseReturnType {\n      typedef CwiseBinaryOp<internal::scalar_product_op<typename ScalarBinaryOpTraits<\n                                                          typename internal::traits<Derived>::Scalar,\n                                                          typename internal::traits<OtherDerived>::Scalar\n                                                        >::ReturnType>,\n                            const Derived,\n                            const OtherDerived\n                          > Type;\n    };\n\n    template<typename OtherDerived>\n    EIGEN_STRONG_INLINE const typename CwiseProductDenseReturnType<OtherDerived>::Type\n    cwiseProduct(const MatrixBase<OtherDerived> &other) const;\n\n    // sparse * diagonal\n    template<typename OtherDerived>\n    const Product<Derived,OtherDerived>\n    operator*(const DiagonalBase<OtherDerived> &other) const\n    { return Product<Derived,OtherDerived>(derived(), other.derived()); }\n\n    // diagonal * sparse\n    template<typename OtherDerived> friend\n    const Product<OtherDerived,Derived>\n    operator*(const DiagonalBase<OtherDerived> &lhs, const SparseMatrixBase& rhs)\n    { return Product<OtherDerived,Derived>(lhs.derived(), rhs.derived()); }\n    \n    // sparse * sparse\n    template<typename OtherDerived>\n    const Product<Derived,OtherDerived,AliasFreeProduct>\n    operator*(const SparseMatrixBase<OtherDerived> &other) const;\n    \n    // sparse * dense\n    template<typename OtherDerived>\n    const Product<Derived,OtherDerived>\n    operator*(const MatrixBase<OtherDerived> &other) const\n    { return Product<Derived,OtherDerived>(derived(), other.derived()); }\n    \n    // dense * sparse\n    template<typename OtherDerived> friend\n    const Product<OtherDerived,Derived>\n    operator*(const MatrixBase<OtherDerived> &lhs, const SparseMatrixBase& rhs)\n    { return Product<OtherDerived,Derived>(lhs.derived(), rhs.derived()); }\n    \n     /** \\returns an expression of P H P^-1 where H is the matrix represented by \\c *this */\n    SparseSymmetricPermutationProduct<Derived,Upper|Lower> twistedBy(const PermutationMatrix<Dynamic,Dynamic,StorageIndex>& perm) const\n    {\n      return SparseSymmetricPermutationProduct<Derived,Upper|Lower>(derived(), perm);\n    }\n\n    template<typename OtherDerived>\n    Derived& operator*=(const SparseMatrixBase<OtherDerived>& other);\n\n    template<int Mode>\n    inline const TriangularView<const Derived, Mode> triangularView() const;\n    \n    template<unsigned int UpLo> struct SelfAdjointViewReturnType { typedef SparseSelfAdjointView<Derived, UpLo> Type; };\n    template<unsigned int UpLo> struct ConstSelfAdjointViewReturnType { typedef const SparseSelfAdjointView<const Derived, UpLo> Type; };\n\n    template<unsigned int UpLo> inline \n    typename ConstSelfAdjointViewReturnType<UpLo>::Type selfadjointView() const;\n    template<unsigned int UpLo> inline\n    typename SelfAdjointViewReturnType<UpLo>::Type selfadjointView();\n\n    template<typename OtherDerived> Scalar dot(const MatrixBase<OtherDerived>& other) const;\n    template<typename OtherDerived> Scalar dot(const SparseMatrixBase<OtherDerived>& other) const;\n    RealScalar squaredNorm() const;\n    RealScalar norm()  const;\n    RealScalar blueNorm() const;\n\n    TransposeReturnType transpose() { return TransposeReturnType(derived()); }\n    const ConstTransposeReturnType transpose() const { return ConstTransposeReturnType(derived()); }\n    const AdjointReturnType adjoint() const { return AdjointReturnType(transpose()); }\n\n    DenseMatrixType toDense() const\n    {\n      return DenseMatrixType(derived());\n    }\n\n    template<typename OtherDerived>\n    bool isApprox(const SparseMatrixBase<OtherDerived>& other,\n                  const RealScalar& prec = NumTraits<Scalar>::dummy_precision()) const;\n\n    template<typename OtherDerived>\n    bool isApprox(const MatrixBase<OtherDerived>& other,\n                  const RealScalar& prec = NumTraits<Scalar>::dummy_precision()) const\n    { return toDense().isApprox(other,prec); }\n\n    /** \\returns the matrix or vector obtained by evaluating this expression.\n      *\n      * Notice that in the case of a plain matrix or vector (not an expression) this function just returns\n      * a const reference, in order to avoid a useless copy.\n      */\n    inline const typename internal::eval<Derived>::type eval() const\n    { return typename internal::eval<Derived>::type(derived()); }\n\n    Scalar sum() const;\n    \n    inline const SparseView<Derived>\n    pruned(const Scalar& reference = Scalar(0), const RealScalar& epsilon = NumTraits<Scalar>::dummy_precision()) const;\n\n  protected:\n\n    bool m_isRValue;\n\n    static inline StorageIndex convert_index(const Index idx) {\n      return internal::convert_index<StorageIndex>(idx);\n    }\n  private:\n    template<typename Dest> void evalTo(Dest &) const;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSEMATRIXBASE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparsePermutation.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_PERMUTATION_H\n#define EIGEN_SPARSE_PERMUTATION_H\n\n// This file implements sparse * permutation products\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate<typename ExpressionType, int Side, bool Transposed>\nstruct permutation_matrix_product<ExpressionType, Side, Transposed, SparseShape>\n{\n    typedef typename nested_eval<ExpressionType, 1>::type MatrixType;\n    typedef typename remove_all<MatrixType>::type MatrixTypeCleaned;\n\n    typedef typename MatrixTypeCleaned::Scalar Scalar;\n    typedef typename MatrixTypeCleaned::StorageIndex StorageIndex;\n\n    enum {\n      SrcStorageOrder = MatrixTypeCleaned::Flags&RowMajorBit ? RowMajor : ColMajor,\n      MoveOuter = SrcStorageOrder==RowMajor ? Side==OnTheLeft : Side==OnTheRight\n    };\n    \n    typedef typename internal::conditional<MoveOuter,\n        SparseMatrix<Scalar,SrcStorageOrder,StorageIndex>,\n        SparseMatrix<Scalar,int(SrcStorageOrder)==RowMajor?ColMajor:RowMajor,StorageIndex> >::type ReturnType;\n\n    template<typename Dest,typename PermutationType>\n    static inline void run(Dest& dst, const PermutationType& perm, const ExpressionType& xpr)\n    {\n      MatrixType mat(xpr);\n      if(MoveOuter)\n      {\n        SparseMatrix<Scalar,SrcStorageOrder,StorageIndex> tmp(mat.rows(), mat.cols());\n        Matrix<StorageIndex,Dynamic,1> sizes(mat.outerSize());\n        for(Index j=0; j<mat.outerSize(); ++j)\n        {\n          Index jp = perm.indices().coeff(j);\n          sizes[((Side==OnTheLeft) ^ Transposed) ? jp : j] = StorageIndex(mat.innerVector(((Side==OnTheRight) ^ Transposed) ? jp : j).nonZeros());\n        }\n        tmp.reserve(sizes);\n        for(Index j=0; j<mat.outerSize(); ++j)\n        {\n          Index jp = perm.indices().coeff(j);\n          Index jsrc = ((Side==OnTheRight) ^ Transposed) ? jp : j;\n          Index jdst = ((Side==OnTheLeft) ^ Transposed) ? jp : j;\n          for(typename MatrixTypeCleaned::InnerIterator it(mat,jsrc); it; ++it)\n            tmp.insertByOuterInner(jdst,it.index()) = it.value();\n        }\n        dst = tmp;\n      }\n      else\n      {\n        SparseMatrix<Scalar,int(SrcStorageOrder)==RowMajor?ColMajor:RowMajor,StorageIndex> tmp(mat.rows(), mat.cols());\n        Matrix<StorageIndex,Dynamic,1> sizes(tmp.outerSize());\n        sizes.setZero();\n        PermutationMatrix<Dynamic,Dynamic,StorageIndex> perm_cpy;\n        if((Side==OnTheLeft) ^ Transposed)\n          perm_cpy = perm;\n        else\n          perm_cpy = perm.transpose();\n\n        for(Index j=0; j<mat.outerSize(); ++j)\n          for(typename MatrixTypeCleaned::InnerIterator it(mat,j); it; ++it)\n            sizes[perm_cpy.indices().coeff(it.index())]++;\n        tmp.reserve(sizes);\n        for(Index j=0; j<mat.outerSize(); ++j)\n          for(typename MatrixTypeCleaned::InnerIterator it(mat,j); it; ++it)\n            tmp.insertByOuterInner(perm_cpy.indices().coeff(it.index()),j) = it.value();\n        dst = tmp;\n      }\n    }\n};\n\n}\n\nnamespace internal {\n\ntemplate <int ProductTag> struct product_promote_storage_type<Sparse,             PermutationStorage, ProductTag> { typedef Sparse ret; };\ntemplate <int ProductTag> struct product_promote_storage_type<PermutationStorage, Sparse,             ProductTag> { typedef Sparse ret; };\n\n// TODO, the following two overloads are only needed to define the right temporary type through \n// typename traits<permutation_sparse_matrix_product<Rhs,Lhs,OnTheRight,false> >::ReturnType\n// whereas it should be correctly handled by traits<Product<> >::PlainObject\n\ntemplate<typename Lhs, typename Rhs, int ProductTag>\nstruct product_evaluator<Product<Lhs, Rhs, AliasFreeProduct>, ProductTag, PermutationShape, SparseShape>\n  : public evaluator<typename permutation_matrix_product<Rhs,OnTheLeft,false,SparseShape>::ReturnType>\n{\n  typedef Product<Lhs, Rhs, AliasFreeProduct> XprType;\n  typedef typename permutation_matrix_product<Rhs,OnTheLeft,false,SparseShape>::ReturnType PlainObject;\n  typedef evaluator<PlainObject> Base;\n\n  enum {\n    Flags = Base::Flags | EvalBeforeNestingBit\n  };\n\n  explicit product_evaluator(const XprType& xpr)\n    : m_result(xpr.rows(), xpr.cols())\n  {\n    ::new (static_cast<Base*>(this)) Base(m_result);\n    generic_product_impl<Lhs, Rhs, PermutationShape, SparseShape, ProductTag>::evalTo(m_result, xpr.lhs(), xpr.rhs());\n  }\n\nprotected:\n  PlainObject m_result;\n};\n\ntemplate<typename Lhs, typename Rhs, int ProductTag>\nstruct product_evaluator<Product<Lhs, Rhs, AliasFreeProduct>, ProductTag, SparseShape, PermutationShape >\n  : public evaluator<typename permutation_matrix_product<Lhs,OnTheRight,false,SparseShape>::ReturnType>\n{\n  typedef Product<Lhs, Rhs, AliasFreeProduct> XprType;\n  typedef typename permutation_matrix_product<Lhs,OnTheRight,false,SparseShape>::ReturnType PlainObject;\n  typedef evaluator<PlainObject> Base;\n\n  enum {\n    Flags = Base::Flags | EvalBeforeNestingBit\n  };\n\n  explicit product_evaluator(const XprType& xpr)\n    : m_result(xpr.rows(), xpr.cols())\n  {\n    ::new (static_cast<Base*>(this)) Base(m_result);\n    generic_product_impl<Lhs, Rhs, SparseShape, PermutationShape, ProductTag>::evalTo(m_result, xpr.lhs(), xpr.rhs());\n  }\n\nprotected:\n  PlainObject m_result;\n};\n\n} // end namespace internal\n\n/** \\returns the matrix with the permutation applied to the columns\n  */\ntemplate<typename SparseDerived, typename PermDerived>\ninline const Product<SparseDerived, PermDerived, AliasFreeProduct>\noperator*(const SparseMatrixBase<SparseDerived>& matrix, const PermutationBase<PermDerived>& perm)\n{ return Product<SparseDerived, PermDerived, AliasFreeProduct>(matrix.derived(), perm.derived()); }\n\n/** \\returns the matrix with the permutation applied to the rows\n  */\ntemplate<typename SparseDerived, typename PermDerived>\ninline const Product<PermDerived, SparseDerived, AliasFreeProduct>\noperator*( const PermutationBase<PermDerived>& perm, const SparseMatrixBase<SparseDerived>& matrix)\n{ return  Product<PermDerived, SparseDerived, AliasFreeProduct>(perm.derived(), matrix.derived()); }\n\n\n/** \\returns the matrix with the inverse permutation applied to the columns.\n  */\ntemplate<typename SparseDerived, typename PermutationType>\ninline const Product<SparseDerived, Inverse<PermutationType>, AliasFreeProduct>\noperator*(const SparseMatrixBase<SparseDerived>& matrix, const InverseImpl<PermutationType, PermutationStorage>& tperm)\n{\n  return Product<SparseDerived, Inverse<PermutationType>, AliasFreeProduct>(matrix.derived(), tperm.derived());\n}\n\n/** \\returns the matrix with the inverse permutation applied to the rows.\n  */\ntemplate<typename SparseDerived, typename PermutationType>\ninline const Product<Inverse<PermutationType>, SparseDerived, AliasFreeProduct>\noperator*(const InverseImpl<PermutationType,PermutationStorage>& tperm, const SparseMatrixBase<SparseDerived>& matrix)\n{\n  return Product<Inverse<PermutationType>, SparseDerived, AliasFreeProduct>(tperm.derived(), matrix.derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_SELFADJOINTVIEW_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseProduct.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEPRODUCT_H\n#define EIGEN_SPARSEPRODUCT_H\n\nnamespace Eigen { \n\n/** \\returns an expression of the product of two sparse matrices.\n  * By default a conservative product preserving the symbolic non zeros is performed.\n  * The automatic pruning of the small values can be achieved by calling the pruned() function\n  * in which case a totally different product algorithm is employed:\n  * \\code\n  * C = (A*B).pruned();             // suppress numerical zeros (exact)\n  * C = (A*B).pruned(ref);\n  * C = (A*B).pruned(ref,epsilon);\n  * \\endcode\n  * where \\c ref is a meaningful non zero reference value.\n  * */\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\ninline const Product<Derived,OtherDerived,AliasFreeProduct>\nSparseMatrixBase<Derived>::operator*(const SparseMatrixBase<OtherDerived> &other) const\n{\n  return Product<Derived,OtherDerived,AliasFreeProduct>(derived(), other.derived());\n}\n\nnamespace internal {\n\n// sparse * sparse\ntemplate<typename Lhs, typename Rhs, int ProductType>\nstruct generic_product_impl<Lhs, Rhs, SparseShape, SparseShape, ProductType>\n{\n  template<typename Dest>\n  static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs)\n  {\n    evalTo(dst, lhs, rhs, typename evaluator_traits<Dest>::Shape());\n  }\n\n  // dense += sparse * sparse\n  template<typename Dest,typename ActualLhs>\n  static void addTo(Dest& dst, const ActualLhs& lhs, const Rhs& rhs, typename enable_if<is_same<typename evaluator_traits<Dest>::Shape,DenseShape>::value,int*>::type* = 0)\n  {\n    typedef typename nested_eval<ActualLhs,Dynamic>::type LhsNested;\n    typedef typename nested_eval<Rhs,Dynamic>::type RhsNested;\n    LhsNested lhsNested(lhs);\n    RhsNested rhsNested(rhs);\n    internal::sparse_sparse_to_dense_product_selector<typename remove_all<LhsNested>::type,\n                                                      typename remove_all<RhsNested>::type, Dest>::run(lhsNested,rhsNested,dst);\n  }\n\n  // dense -= sparse * sparse\n  template<typename Dest>\n  static void subTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, typename enable_if<is_same<typename evaluator_traits<Dest>::Shape,DenseShape>::value,int*>::type* = 0)\n  {\n    addTo(dst, -lhs, rhs);\n  }\n\nprotected:\n\n  // sparse = sparse * sparse\n  template<typename Dest>\n  static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, SparseShape)\n  {\n    typedef typename nested_eval<Lhs,Dynamic>::type LhsNested;\n    typedef typename nested_eval<Rhs,Dynamic>::type RhsNested;\n    LhsNested lhsNested(lhs);\n    RhsNested rhsNested(rhs);\n    internal::conservative_sparse_sparse_product_selector<typename remove_all<LhsNested>::type,\n                                                          typename remove_all<RhsNested>::type, Dest>::run(lhsNested,rhsNested,dst);\n  }\n\n  // dense = sparse * sparse\n  template<typename Dest>\n  static void evalTo(Dest& dst, const Lhs& lhs, const Rhs& rhs, DenseShape)\n  {\n    dst.setZero();\n    addTo(dst, lhs, rhs);\n  }\n};\n\n// sparse * sparse-triangular\ntemplate<typename Lhs, typename Rhs, int ProductType>\nstruct generic_product_impl<Lhs, Rhs, SparseShape, SparseTriangularShape, ProductType>\n : public generic_product_impl<Lhs, Rhs, SparseShape, SparseShape, ProductType>\n{};\n\n// sparse-triangular * sparse\ntemplate<typename Lhs, typename Rhs, int ProductType>\nstruct generic_product_impl<Lhs, Rhs, SparseTriangularShape, SparseShape, ProductType>\n : public generic_product_impl<Lhs, Rhs, SparseShape, SparseShape, ProductType>\n{};\n\n// dense = sparse-product (can be sparse*sparse, sparse*perm, etc.)\ntemplate< typename DstXprType, typename Lhs, typename Rhs>\nstruct Assignment<DstXprType, Product<Lhs,Rhs,AliasFreeProduct>, internal::assign_op<typename DstXprType::Scalar,typename Product<Lhs,Rhs,AliasFreeProduct>::Scalar>, Sparse2Dense>\n{\n  typedef Product<Lhs,Rhs,AliasFreeProduct> SrcXprType;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &)\n  {\n    Index dstRows = src.rows();\n    Index dstCols = src.cols();\n    if((dst.rows()!=dstRows) || (dst.cols()!=dstCols))\n      dst.resize(dstRows, dstCols);\n    \n    generic_product_impl<Lhs, Rhs>::evalTo(dst,src.lhs(),src.rhs());\n  }\n};\n\n// dense += sparse-product (can be sparse*sparse, sparse*perm, etc.)\ntemplate< typename DstXprType, typename Lhs, typename Rhs>\nstruct Assignment<DstXprType, Product<Lhs,Rhs,AliasFreeProduct>, internal::add_assign_op<typename DstXprType::Scalar,typename Product<Lhs,Rhs,AliasFreeProduct>::Scalar>, Sparse2Dense>\n{\n  typedef Product<Lhs,Rhs,AliasFreeProduct> SrcXprType;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::add_assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &)\n  {\n    generic_product_impl<Lhs, Rhs>::addTo(dst,src.lhs(),src.rhs());\n  }\n};\n\n// dense -= sparse-product (can be sparse*sparse, sparse*perm, etc.)\ntemplate< typename DstXprType, typename Lhs, typename Rhs>\nstruct Assignment<DstXprType, Product<Lhs,Rhs,AliasFreeProduct>, internal::sub_assign_op<typename DstXprType::Scalar,typename Product<Lhs,Rhs,AliasFreeProduct>::Scalar>, Sparse2Dense>\n{\n  typedef Product<Lhs,Rhs,AliasFreeProduct> SrcXprType;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::sub_assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> &)\n  {\n    generic_product_impl<Lhs, Rhs>::subTo(dst,src.lhs(),src.rhs());\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, int Options>\nstruct unary_evaluator<SparseView<Product<Lhs, Rhs, Options> >, IteratorBased>\n : public evaluator<typename Product<Lhs, Rhs, DefaultProduct>::PlainObject>\n{\n  typedef SparseView<Product<Lhs, Rhs, Options> > XprType;\n  typedef typename XprType::PlainObject PlainObject;\n  typedef evaluator<PlainObject> Base;\n\n  explicit unary_evaluator(const XprType& xpr)\n    : m_result(xpr.rows(), xpr.cols())\n  {\n    using std::abs;\n    ::new (static_cast<Base*>(this)) Base(m_result);\n    typedef typename nested_eval<Lhs,Dynamic>::type LhsNested;\n    typedef typename nested_eval<Rhs,Dynamic>::type RhsNested;\n    LhsNested lhsNested(xpr.nestedExpression().lhs());\n    RhsNested rhsNested(xpr.nestedExpression().rhs());\n\n    internal::sparse_sparse_product_with_pruning_selector<typename remove_all<LhsNested>::type,\n                                                          typename remove_all<RhsNested>::type, PlainObject>::run(lhsNested,rhsNested,m_result,\n                                                                                                                  abs(xpr.reference())*xpr.epsilon());\n  }\n\nprotected:\n  PlainObject m_result;\n};\n\n} // end namespace internal\n\n// sparse matrix = sparse-product (can be sparse*sparse, sparse*perm, etc.)\ntemplate<typename Scalar, int _Options, typename _StorageIndex>\ntemplate<typename Lhs, typename Rhs>\nSparseMatrix<Scalar,_Options,_StorageIndex>& SparseMatrix<Scalar,_Options,_StorageIndex>::operator=(const Product<Lhs,Rhs,AliasFreeProduct>& src)\n{\n  // std::cout << \"in Assignment : \" << DstOptions << \"\\n\";\n  SparseMatrix dst(src.rows(),src.cols());\n  internal::generic_product_impl<Lhs, Rhs>::evalTo(dst,src.lhs(),src.rhs());\n  this->swap(dst);\n  return *this;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSEPRODUCT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseRedux.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEREDUX_H\n#define EIGEN_SPARSEREDUX_H\n\nnamespace Eigen { \n\ntemplate<typename Derived>\ntypename internal::traits<Derived>::Scalar\nSparseMatrixBase<Derived>::sum() const\n{\n  eigen_assert(rows()>0 && cols()>0 && \"you are using a non initialized matrix\");\n  Scalar res(0);\n  internal::evaluator<Derived> thisEval(derived());\n  for (Index j=0; j<outerSize(); ++j)\n    for (typename internal::evaluator<Derived>::InnerIterator iter(thisEval,j); iter; ++iter)\n      res += iter.value();\n  return res;\n}\n\ntemplate<typename _Scalar, int _Options, typename _Index>\ntypename internal::traits<SparseMatrix<_Scalar,_Options,_Index> >::Scalar\nSparseMatrix<_Scalar,_Options,_Index>::sum() const\n{\n  eigen_assert(rows()>0 && cols()>0 && \"you are using a non initialized matrix\");\n  if(this->isCompressed())\n    return Matrix<Scalar,1,Dynamic>::Map(m_data.valuePtr(), m_data.size()).sum();\n  else\n    return Base::sum();\n}\n\ntemplate<typename _Scalar, int _Options, typename _Index>\ntypename internal::traits<SparseVector<_Scalar,_Options, _Index> >::Scalar\nSparseVector<_Scalar,_Options,_Index>::sum() const\n{\n  eigen_assert(rows()>0 && cols()>0 && \"you are using a non initialized matrix\");\n  return Matrix<Scalar,1,Dynamic>::Map(m_data.valuePtr(), m_data.size()).sum();\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSEREDUX_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseRef.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_REF_H\n#define EIGEN_SPARSE_REF_H\n\nnamespace Eigen {\n\nenum {\n  StandardCompressedFormat = 2 /**< used by Ref<SparseMatrix> to specify whether the input storage must be in standard compressed form */\n};\n  \nnamespace internal {\n\ntemplate<typename Derived> class SparseRefBase;\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int _Options, typename _StrideType>\nstruct traits<Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, _Options, _StrideType> >\n  : public traits<SparseMatrix<MatScalar,MatOptions,MatIndex> >\n{\n  typedef SparseMatrix<MatScalar,MatOptions,MatIndex> PlainObjectType;\n  enum {\n    Options = _Options,\n    Flags = traits<PlainObjectType>::Flags | CompressedAccessBit | NestByRefBit\n  };\n\n  template<typename Derived> struct match {\n    enum {\n      StorageOrderMatch = PlainObjectType::IsVectorAtCompileTime || Derived::IsVectorAtCompileTime || ((PlainObjectType::Flags&RowMajorBit)==(Derived::Flags&RowMajorBit)),\n      MatchAtCompileTime = (Derived::Flags&CompressedAccessBit) && StorageOrderMatch\n    };\n    typedef typename internal::conditional<MatchAtCompileTime,internal::true_type,internal::false_type>::type type;\n  };\n  \n};\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int _Options, typename _StrideType>\nstruct traits<Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, _Options, _StrideType> >\n  : public traits<Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, _Options, _StrideType> >\n{\n  enum {\n    Flags = (traits<SparseMatrix<MatScalar,MatOptions,MatIndex> >::Flags | CompressedAccessBit | NestByRefBit) & ~LvalueBit\n  };\n};\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int _Options, typename _StrideType>\nstruct traits<Ref<SparseVector<MatScalar,MatOptions,MatIndex>, _Options, _StrideType> >\n  : public traits<SparseVector<MatScalar,MatOptions,MatIndex> >\n{\n  typedef SparseVector<MatScalar,MatOptions,MatIndex> PlainObjectType;\n  enum {\n    Options = _Options,\n    Flags = traits<PlainObjectType>::Flags | CompressedAccessBit | NestByRefBit\n  };\n\n  template<typename Derived> struct match {\n    enum {\n      MatchAtCompileTime = (Derived::Flags&CompressedAccessBit) && Derived::IsVectorAtCompileTime\n    };\n    typedef typename internal::conditional<MatchAtCompileTime,internal::true_type,internal::false_type>::type type;\n  };\n\n};\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int _Options, typename _StrideType>\nstruct traits<Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, _Options, _StrideType> >\n  : public traits<Ref<SparseVector<MatScalar,MatOptions,MatIndex>, _Options, _StrideType> >\n{\n  enum {\n    Flags = (traits<SparseVector<MatScalar,MatOptions,MatIndex> >::Flags | CompressedAccessBit | NestByRefBit) & ~LvalueBit\n  };\n};\n\ntemplate<typename Derived>\nstruct traits<SparseRefBase<Derived> > : public traits<Derived> {};\n\ntemplate<typename Derived> class SparseRefBase\n  : public SparseMapBase<Derived>\n{\npublic:\n\n  typedef SparseMapBase<Derived> Base;\n  EIGEN_SPARSE_PUBLIC_INTERFACE(SparseRefBase)\n\n  SparseRefBase()\n    : Base(RowsAtCompileTime==Dynamic?0:RowsAtCompileTime,ColsAtCompileTime==Dynamic?0:ColsAtCompileTime, 0, 0, 0, 0, 0)\n  {}\n  \nprotected:\n\n  template<typename Expression>\n  void construct(Expression& expr)\n  {\n    if(expr.outerIndexPtr()==0)\n      ::new (static_cast<Base*>(this)) Base(expr.size(), expr.nonZeros(), expr.innerIndexPtr(), expr.valuePtr());\n    else\n      ::new (static_cast<Base*>(this)) Base(expr.rows(), expr.cols(), expr.nonZeros(), expr.outerIndexPtr(), expr.innerIndexPtr(), expr.valuePtr(), expr.innerNonZeroPtr());\n  }\n};\n\n} // namespace internal\n\n\n/** \n  * \\ingroup SparseCore_Module\n  *\n  * \\brief A sparse matrix expression referencing an existing sparse expression\n  *\n  * \\tparam SparseMatrixType the equivalent sparse matrix type of the referenced data, it must be a template instance of class SparseMatrix.\n  * \\tparam Options specifies whether the a standard compressed format is required \\c Options is  \\c #StandardCompressedFormat, or \\c 0.\n  *                The default is \\c 0.\n  *\n  * \\sa class Ref\n  */\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nclass Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType >\n  : public internal::SparseRefBase<Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType > >\n#else\ntemplate<typename SparseMatrixType, int Options>\nclass Ref<SparseMatrixType, Options>\n  : public SparseMapBase<Derived,WriteAccessors> // yes, that's weird to use Derived here, but that works!\n#endif\n{\n    typedef SparseMatrix<MatScalar,MatOptions,MatIndex> PlainObjectType;\n    typedef internal::traits<Ref> Traits;\n    template<int OtherOptions>\n    inline Ref(const SparseMatrix<MatScalar,OtherOptions,MatIndex>& expr);\n    template<int OtherOptions>\n    inline Ref(const MappedSparseMatrix<MatScalar,OtherOptions,MatIndex>& expr);\n  public:\n\n    typedef internal::SparseRefBase<Ref> Base;\n    EIGEN_SPARSE_PUBLIC_INTERFACE(Ref)\n\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<int OtherOptions>\n    inline Ref(SparseMatrix<MatScalar,OtherOptions,MatIndex>& expr)\n    {\n      EIGEN_STATIC_ASSERT(bool(Traits::template match<SparseMatrix<MatScalar,OtherOptions,MatIndex> >::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH);\n      eigen_assert( ((Options & int(StandardCompressedFormat))==0) || (expr.isCompressed()) );\n      Base::construct(expr.derived());\n    }\n    \n    template<int OtherOptions>\n    inline Ref(MappedSparseMatrix<MatScalar,OtherOptions,MatIndex>& expr)\n    {\n      EIGEN_STATIC_ASSERT(bool(Traits::template match<SparseMatrix<MatScalar,OtherOptions,MatIndex> >::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH);\n      eigen_assert( ((Options & int(StandardCompressedFormat))==0) || (expr.isCompressed()) );\n      Base::construct(expr.derived());\n    }\n    \n    template<typename Derived>\n    inline Ref(const SparseCompressedBase<Derived>& expr)\n    #else\n    /** Implicit constructor from any sparse expression (2D matrix or 1D vector) */\n    template<typename Derived>\n    inline Ref(SparseCompressedBase<Derived>& expr)\n    #endif\n    {\n      EIGEN_STATIC_ASSERT(bool(internal::is_lvalue<Derived>::value), THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY);\n      EIGEN_STATIC_ASSERT(bool(Traits::template match<Derived>::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH);\n      eigen_assert( ((Options & int(StandardCompressedFormat))==0) || (expr.isCompressed()) );\n      Base::construct(expr.const_cast_derived());\n    }\n};\n\n// this is the const ref version\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nclass Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType>\n  : public internal::SparseRefBase<Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n{\n    typedef SparseMatrix<MatScalar,MatOptions,MatIndex> TPlainObjectType;\n    typedef internal::traits<Ref> Traits;\n  public:\n\n    typedef internal::SparseRefBase<Ref> Base;\n    EIGEN_SPARSE_PUBLIC_INTERFACE(Ref)\n\n    template<typename Derived>\n    inline Ref(const SparseMatrixBase<Derived>& expr) : m_hasCopy(false)\n    {\n      construct(expr.derived(), typename Traits::template match<Derived>::type());\n    }\n\n    inline Ref(const Ref& other) : Base(other), m_hasCopy(false) {\n      // copy constructor shall not copy the m_object, to avoid unnecessary malloc and copy\n    }\n\n    template<typename OtherRef>\n    inline Ref(const RefBase<OtherRef>& other) : m_hasCopy(false) {\n      construct(other.derived(), typename Traits::template match<OtherRef>::type());\n    }\n\n    ~Ref() {\n      if(m_hasCopy) {\n        TPlainObjectType* obj = reinterpret_cast<TPlainObjectType*>(&m_storage);\n        obj->~TPlainObjectType();\n      }\n    }\n\n  protected:\n\n    template<typename Expression>\n    void construct(const Expression& expr,internal::true_type)\n    {\n      if((Options & int(StandardCompressedFormat)) && (!expr.isCompressed()))\n      {\n        TPlainObjectType* obj = reinterpret_cast<TPlainObjectType*>(&m_storage);\n        ::new (obj) TPlainObjectType(expr);\n        m_hasCopy = true;\n        Base::construct(*obj);\n      }\n      else\n      {\n        Base::construct(expr);\n      }\n    }\n\n    template<typename Expression>\n    void construct(const Expression& expr, internal::false_type)\n    {\n      TPlainObjectType* obj = reinterpret_cast<TPlainObjectType*>(&m_storage);\n      ::new (obj) TPlainObjectType(expr);\n      m_hasCopy = true;\n      Base::construct(*obj);\n    }\n\n  protected:\n    typename internal::aligned_storage<sizeof(TPlainObjectType), EIGEN_ALIGNOF(TPlainObjectType)>::type m_storage;\n    bool m_hasCopy;\n};\n\n\n\n/**\n  * \\ingroup SparseCore_Module\n  *\n  * \\brief A sparse vector expression referencing an existing sparse vector expression\n  *\n  * \\tparam SparseVectorType the equivalent sparse vector type of the referenced data, it must be a template instance of class SparseVector.\n  *\n  * \\sa class Ref\n  */\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nclass Ref<SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType >\n  : public internal::SparseRefBase<Ref<SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType > >\n#else\ntemplate<typename SparseVectorType>\nclass Ref<SparseVectorType>\n  : public SparseMapBase<Derived,WriteAccessors>\n#endif\n{\n    typedef SparseVector<MatScalar,MatOptions,MatIndex> PlainObjectType;\n    typedef internal::traits<Ref> Traits;\n    template<int OtherOptions>\n    inline Ref(const SparseVector<MatScalar,OtherOptions,MatIndex>& expr);\n  public:\n\n    typedef internal::SparseRefBase<Ref> Base;\n    EIGEN_SPARSE_PUBLIC_INTERFACE(Ref)\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<int OtherOptions>\n    inline Ref(SparseVector<MatScalar,OtherOptions,MatIndex>& expr)\n    {\n      EIGEN_STATIC_ASSERT(bool(Traits::template match<SparseVector<MatScalar,OtherOptions,MatIndex> >::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH);\n      Base::construct(expr.derived());\n    }\n\n    template<typename Derived>\n    inline Ref(const SparseCompressedBase<Derived>& expr)\n    #else\n    /** Implicit constructor from any 1D sparse vector expression */\n    template<typename Derived>\n    inline Ref(SparseCompressedBase<Derived>& expr)\n    #endif\n    {\n      EIGEN_STATIC_ASSERT(bool(internal::is_lvalue<Derived>::value), THIS_EXPRESSION_IS_NOT_A_LVALUE__IT_IS_READ_ONLY);\n      EIGEN_STATIC_ASSERT(bool(Traits::template match<Derived>::MatchAtCompileTime), STORAGE_LAYOUT_DOES_NOT_MATCH);\n      Base::construct(expr.const_cast_derived());\n    }\n};\n\n// this is the const ref version\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nclass Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType>\n  : public internal::SparseRefBase<Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n{\n    typedef SparseVector<MatScalar,MatOptions,MatIndex> TPlainObjectType;\n    typedef internal::traits<Ref> Traits;\n  public:\n\n    typedef internal::SparseRefBase<Ref> Base;\n    EIGEN_SPARSE_PUBLIC_INTERFACE(Ref)\n\n    template<typename Derived>\n    inline Ref(const SparseMatrixBase<Derived>& expr) : m_hasCopy(false)\n    {\n      construct(expr.derived(), typename Traits::template match<Derived>::type());\n    }\n\n    inline Ref(const Ref& other) : Base(other), m_hasCopy(false) {\n      // copy constructor shall not copy the m_object, to avoid unnecessary malloc and copy\n    }\n\n    template<typename OtherRef>\n    inline Ref(const RefBase<OtherRef>& other) : m_hasCopy(false) {\n      construct(other.derived(), typename Traits::template match<OtherRef>::type());\n    }\n\n    ~Ref() {\n      if(m_hasCopy) {\n        TPlainObjectType* obj = reinterpret_cast<TPlainObjectType*>(&m_storage);\n        obj->~TPlainObjectType();\n      }\n    }\n\n  protected:\n\n    template<typename Expression>\n    void construct(const Expression& expr,internal::true_type)\n    {\n      Base::construct(expr);\n    }\n\n    template<typename Expression>\n    void construct(const Expression& expr, internal::false_type)\n    {\n      TPlainObjectType* obj = reinterpret_cast<TPlainObjectType*>(&m_storage);\n      ::new (obj) TPlainObjectType(expr);\n      m_hasCopy = true;\n      Base::construct(*obj);\n    }\n\n  protected:\n    typename internal::aligned_storage<sizeof(TPlainObjectType), EIGEN_ALIGNOF(TPlainObjectType)>::type m_storage;\n    bool m_hasCopy;\n};\n\nnamespace internal {\n\n// FIXME shall we introduce a general evaluatior_ref that we can specialize for any sparse object once, and thus remove this copy-pasta thing...\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nstruct evaluator<Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n  : evaluator<SparseCompressedBase<Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > >\n{\n  typedef evaluator<SparseCompressedBase<Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > > Base;\n  typedef Ref<SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> XprType;  \n  evaluator() : Base() {}\n  explicit evaluator(const XprType &mat) : Base(mat) {}\n};\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nstruct evaluator<Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n  : evaluator<SparseCompressedBase<Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > >\n{\n  typedef evaluator<SparseCompressedBase<Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> > > Base;\n  typedef Ref<const SparseMatrix<MatScalar,MatOptions,MatIndex>, Options, StrideType> XprType;  \n  evaluator() : Base() {}\n  explicit evaluator(const XprType &mat) : Base(mat) {}\n};\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nstruct evaluator<Ref<SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n  : evaluator<SparseCompressedBase<Ref<SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> > >\n{\n  typedef evaluator<SparseCompressedBase<Ref<SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> > > Base;\n  typedef Ref<SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> XprType;\n  evaluator() : Base() {}\n  explicit evaluator(const XprType &mat) : Base(mat) {}\n};\n\ntemplate<typename MatScalar, int MatOptions, typename MatIndex, int Options, typename StrideType>\nstruct evaluator<Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> >\n  : evaluator<SparseCompressedBase<Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> > >\n{\n  typedef evaluator<SparseCompressedBase<Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> > > Base;\n  typedef Ref<const SparseVector<MatScalar,MatOptions,MatIndex>, Options, StrideType> XprType;\n  evaluator() : Base() {}\n  explicit evaluator(const XprType &mat) : Base(mat) {}\n};\n\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_REF_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseSelfAdjointView.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_SELFADJOINTVIEW_H\n#define EIGEN_SPARSE_SELFADJOINTVIEW_H\n\nnamespace Eigen { \n  \n/** \\ingroup SparseCore_Module\n  * \\class SparseSelfAdjointView\n  *\n  * \\brief Pseudo expression to manipulate a triangular sparse matrix as a selfadjoint matrix.\n  *\n  * \\param MatrixType the type of the dense matrix storing the coefficients\n  * \\param Mode can be either \\c #Lower or \\c #Upper\n  *\n  * This class is an expression of a sefladjoint matrix from a triangular part of a matrix\n  * with given dense storage of the coefficients. It is the return type of MatrixBase::selfadjointView()\n  * and most of the time this is the only way that it is used.\n  *\n  * \\sa SparseMatrixBase::selfadjointView()\n  */\nnamespace internal {\n  \ntemplate<typename MatrixType, unsigned int Mode>\nstruct traits<SparseSelfAdjointView<MatrixType,Mode> > : traits<MatrixType> {\n};\n\ntemplate<int SrcMode,int DstMode,typename MatrixType,int DestOrder>\nvoid permute_symm_to_symm(const MatrixType& mat, SparseMatrix<typename MatrixType::Scalar,DestOrder,typename MatrixType::StorageIndex>& _dest, const typename MatrixType::StorageIndex* perm = 0);\n\ntemplate<int Mode,typename MatrixType,int DestOrder>\nvoid permute_symm_to_fullsymm(const MatrixType& mat, SparseMatrix<typename MatrixType::Scalar,DestOrder,typename MatrixType::StorageIndex>& _dest, const typename MatrixType::StorageIndex* perm = 0);\n\n}\n\ntemplate<typename MatrixType, unsigned int _Mode> class SparseSelfAdjointView\n  : public EigenBase<SparseSelfAdjointView<MatrixType,_Mode> >\n{\n  public:\n    \n    enum {\n      Mode = _Mode,\n      TransposeMode = ((Mode & Upper) ? Lower : 0) | ((Mode & Lower) ? Upper : 0),\n      RowsAtCompileTime = internal::traits<SparseSelfAdjointView>::RowsAtCompileTime,\n      ColsAtCompileTime = internal::traits<SparseSelfAdjointView>::ColsAtCompileTime\n    };\n\n    typedef EigenBase<SparseSelfAdjointView> Base;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef Matrix<StorageIndex,Dynamic,1> VectorI;\n    typedef typename internal::ref_selector<MatrixType>::non_const_type MatrixTypeNested;\n    typedef typename internal::remove_all<MatrixTypeNested>::type _MatrixTypeNested;\n    \n    explicit inline SparseSelfAdjointView(MatrixType& matrix) : m_matrix(matrix)\n    {\n      eigen_assert(rows()==cols() && \"SelfAdjointView is only for squared matrices\");\n    }\n\n    inline Index rows() const { return m_matrix.rows(); }\n    inline Index cols() const { return m_matrix.cols(); }\n\n    /** \\internal \\returns a reference to the nested matrix */\n    const _MatrixTypeNested& matrix() const { return m_matrix; }\n    typename internal::remove_reference<MatrixTypeNested>::type& matrix() { return m_matrix; }\n\n    /** \\returns an expression of the matrix product between a sparse self-adjoint matrix \\c *this and a sparse matrix \\a rhs.\n      *\n      * Note that there is no algorithmic advantage of performing such a product compared to a general sparse-sparse matrix product.\n      * Indeed, the SparseSelfadjointView operand is first copied into a temporary SparseMatrix before computing the product.\n      */\n    template<typename OtherDerived>\n    Product<SparseSelfAdjointView, OtherDerived>\n    operator*(const SparseMatrixBase<OtherDerived>& rhs) const\n    {\n      return Product<SparseSelfAdjointView, OtherDerived>(*this, rhs.derived());\n    }\n\n    /** \\returns an expression of the matrix product between a sparse matrix \\a lhs and a sparse self-adjoint matrix \\a rhs.\n      *\n      * Note that there is no algorithmic advantage of performing such a product compared to a general sparse-sparse matrix product.\n      * Indeed, the SparseSelfadjointView operand is first copied into a temporary SparseMatrix before computing the product.\n      */\n    template<typename OtherDerived> friend\n    Product<OtherDerived, SparseSelfAdjointView>\n    operator*(const SparseMatrixBase<OtherDerived>& lhs, const SparseSelfAdjointView& rhs)\n    {\n      return Product<OtherDerived, SparseSelfAdjointView>(lhs.derived(), rhs);\n    }\n    \n    /** Efficient sparse self-adjoint matrix times dense vector/matrix product */\n    template<typename OtherDerived>\n    Product<SparseSelfAdjointView,OtherDerived>\n    operator*(const MatrixBase<OtherDerived>& rhs) const\n    {\n      return Product<SparseSelfAdjointView,OtherDerived>(*this, rhs.derived());\n    }\n\n    /** Efficient dense vector/matrix times sparse self-adjoint matrix product */\n    template<typename OtherDerived> friend\n    Product<OtherDerived,SparseSelfAdjointView>\n    operator*(const MatrixBase<OtherDerived>& lhs, const SparseSelfAdjointView& rhs)\n    {\n      return Product<OtherDerived,SparseSelfAdjointView>(lhs.derived(), rhs);\n    }\n\n    /** Perform a symmetric rank K update of the selfadjoint matrix \\c *this:\n      * \\f$ this = this + \\alpha ( u u^* ) \\f$ where \\a u is a vector or matrix.\n      *\n      * \\returns a reference to \\c *this\n      *\n      * To perform \\f$ this = this + \\alpha ( u^* u ) \\f$ you can simply\n      * call this function with u.adjoint().\n      */\n    template<typename DerivedU>\n    SparseSelfAdjointView& rankUpdate(const SparseMatrixBase<DerivedU>& u, const Scalar& alpha = Scalar(1));\n    \n    /** \\returns an expression of P H P^-1 */\n    // TODO implement twists in a more evaluator friendly fashion\n    SparseSymmetricPermutationProduct<_MatrixTypeNested,Mode> twistedBy(const PermutationMatrix<Dynamic,Dynamic,StorageIndex>& perm) const\n    {\n      return SparseSymmetricPermutationProduct<_MatrixTypeNested,Mode>(m_matrix, perm);\n    }\n\n    template<typename SrcMatrixType,int SrcMode>\n    SparseSelfAdjointView& operator=(const SparseSymmetricPermutationProduct<SrcMatrixType,SrcMode>& permutedMatrix)\n    {\n      internal::call_assignment_no_alias_no_transpose(*this, permutedMatrix);\n      return *this;\n    }\n\n    SparseSelfAdjointView& operator=(const SparseSelfAdjointView& src)\n    {\n      PermutationMatrix<Dynamic,Dynamic,StorageIndex> pnull;\n      return *this = src.twistedBy(pnull);\n    }\n\n    // Since we override the copy-assignment operator, we need to explicitly re-declare the copy-constructor\n    EIGEN_DEFAULT_COPY_CONSTRUCTOR(SparseSelfAdjointView)\n\n    template<typename SrcMatrixType,unsigned int SrcMode>\n    SparseSelfAdjointView& operator=(const SparseSelfAdjointView<SrcMatrixType,SrcMode>& src)\n    {\n      PermutationMatrix<Dynamic,Dynamic,StorageIndex> pnull;\n      return *this = src.twistedBy(pnull);\n    }\n    \n    void resize(Index rows, Index cols)\n    {\n      EIGEN_ONLY_USED_FOR_DEBUG(rows);\n      EIGEN_ONLY_USED_FOR_DEBUG(cols);\n      eigen_assert(rows == this->rows() && cols == this->cols()\n                && \"SparseSelfadjointView::resize() does not actually allow to resize.\");\n    }\n    \n  protected:\n\n    MatrixTypeNested m_matrix;\n    //mutable VectorI m_countPerRow;\n    //mutable VectorI m_countPerCol;\n  private:\n    template<typename Dest> void evalTo(Dest &) const;\n};\n\n/***************************************************************************\n* Implementation of SparseMatrixBase methods\n***************************************************************************/\n\ntemplate<typename Derived>\ntemplate<unsigned int UpLo>\ntypename SparseMatrixBase<Derived>::template ConstSelfAdjointViewReturnType<UpLo>::Type SparseMatrixBase<Derived>::selfadjointView() const\n{\n  return SparseSelfAdjointView<const Derived, UpLo>(derived());\n}\n\ntemplate<typename Derived>\ntemplate<unsigned int UpLo>\ntypename SparseMatrixBase<Derived>::template SelfAdjointViewReturnType<UpLo>::Type SparseMatrixBase<Derived>::selfadjointView()\n{\n  return SparseSelfAdjointView<Derived, UpLo>(derived());\n}\n\n/***************************************************************************\n* Implementation of SparseSelfAdjointView methods\n***************************************************************************/\n\ntemplate<typename MatrixType, unsigned int Mode>\ntemplate<typename DerivedU>\nSparseSelfAdjointView<MatrixType,Mode>&\nSparseSelfAdjointView<MatrixType,Mode>::rankUpdate(const SparseMatrixBase<DerivedU>& u, const Scalar& alpha)\n{\n  SparseMatrix<Scalar,(MatrixType::Flags&RowMajorBit)?RowMajor:ColMajor> tmp = u * u.adjoint();\n  if(alpha==Scalar(0))\n    m_matrix = tmp.template triangularView<Mode>();\n  else\n    m_matrix += alpha * tmp.template triangularView<Mode>();\n\n  return *this;\n}\n\nnamespace internal {\n  \n// TODO currently a selfadjoint expression has the form SelfAdjointView<.,.>\n//      in the future selfadjoint-ness should be defined by the expression traits\n//      such that Transpose<SelfAdjointView<.,.> > is valid. (currently TriangularBase::transpose() is overloaded to make it work)\ntemplate<typename MatrixType, unsigned int Mode>\nstruct evaluator_traits<SparseSelfAdjointView<MatrixType,Mode> >\n{\n  typedef typename storage_kind_to_evaluator_kind<typename MatrixType::StorageKind>::Kind Kind;\n  typedef SparseSelfAdjointShape Shape;\n};\n\nstruct SparseSelfAdjoint2Sparse {};\n\ntemplate<> struct AssignmentKind<SparseShape,SparseSelfAdjointShape> { typedef SparseSelfAdjoint2Sparse Kind; };\ntemplate<> struct AssignmentKind<SparseSelfAdjointShape,SparseShape> { typedef Sparse2Sparse Kind; };\n\ntemplate< typename DstXprType, typename SrcXprType, typename Functor>\nstruct Assignment<DstXprType, SrcXprType, Functor, SparseSelfAdjoint2Sparse>\n{\n  typedef typename DstXprType::StorageIndex StorageIndex;\n  typedef internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar> AssignOpType;\n\n  template<typename DestScalar,int StorageOrder>\n  static void run(SparseMatrix<DestScalar,StorageOrder,StorageIndex> &dst, const SrcXprType &src, const AssignOpType&/*func*/)\n  {\n    internal::permute_symm_to_fullsymm<SrcXprType::Mode>(src.matrix(), dst);\n  }\n\n  // FIXME: the handling of += and -= in sparse matrices should be cleanup so that next two overloads could be reduced to:\n  template<typename DestScalar,int StorageOrder,typename AssignFunc>\n  static void run(SparseMatrix<DestScalar,StorageOrder,StorageIndex> &dst, const SrcXprType &src, const AssignFunc& func)\n  {\n    SparseMatrix<DestScalar,StorageOrder,StorageIndex> tmp(src.rows(),src.cols());\n    run(tmp, src, AssignOpType());\n    call_assignment_no_alias_no_transpose(dst, tmp, func);\n  }\n\n  template<typename DestScalar,int StorageOrder>\n  static void run(SparseMatrix<DestScalar,StorageOrder,StorageIndex> &dst, const SrcXprType &src,\n                  const internal::add_assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar>& /* func */)\n  {\n    SparseMatrix<DestScalar,StorageOrder,StorageIndex> tmp(src.rows(),src.cols());\n    run(tmp, src, AssignOpType());\n    dst += tmp;\n  }\n\n  template<typename DestScalar,int StorageOrder>\n  static void run(SparseMatrix<DestScalar,StorageOrder,StorageIndex> &dst, const SrcXprType &src,\n                  const internal::sub_assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar>& /* func */)\n  {\n    SparseMatrix<DestScalar,StorageOrder,StorageIndex> tmp(src.rows(),src.cols());\n    run(tmp, src, AssignOpType());\n    dst -= tmp;\n  }\n  \n  template<typename DestScalar>\n  static void run(DynamicSparseMatrix<DestScalar,ColMajor,StorageIndex>& dst, const SrcXprType &src, const AssignOpType&/*func*/)\n  {\n    // TODO directly evaluate into dst;\n    SparseMatrix<DestScalar,ColMajor,StorageIndex> tmp(dst.rows(),dst.cols());\n    internal::permute_symm_to_fullsymm<SrcXprType::Mode>(src.matrix(), tmp);\n    dst = tmp;\n  }\n};\n\n} // end namespace internal\n\n/***************************************************************************\n* Implementation of sparse self-adjoint time dense matrix\n***************************************************************************/\n\nnamespace internal {\n\ntemplate<int Mode, typename SparseLhsType, typename DenseRhsType, typename DenseResType, typename AlphaType>\ninline void sparse_selfadjoint_time_dense_product(const SparseLhsType& lhs, const DenseRhsType& rhs, DenseResType& res, const AlphaType& alpha)\n{\n  EIGEN_ONLY_USED_FOR_DEBUG(alpha);\n  \n  typedef typename internal::nested_eval<SparseLhsType,DenseRhsType::MaxColsAtCompileTime>::type SparseLhsTypeNested;\n  typedef typename internal::remove_all<SparseLhsTypeNested>::type SparseLhsTypeNestedCleaned;\n  typedef evaluator<SparseLhsTypeNestedCleaned> LhsEval;\n  typedef typename LhsEval::InnerIterator LhsIterator;\n  typedef typename SparseLhsType::Scalar LhsScalar;\n  \n  enum {\n    LhsIsRowMajor = (LhsEval::Flags&RowMajorBit)==RowMajorBit,\n    ProcessFirstHalf =\n              ((Mode&(Upper|Lower))==(Upper|Lower))\n          || ( (Mode&Upper) && !LhsIsRowMajor)\n          || ( (Mode&Lower) && LhsIsRowMajor),\n    ProcessSecondHalf = !ProcessFirstHalf\n  };\n  \n  SparseLhsTypeNested lhs_nested(lhs);\n  LhsEval lhsEval(lhs_nested);\n\n  // work on one column at once\n  for (Index k=0; k<rhs.cols(); ++k)\n  {\n    for (Index j=0; j<lhs.outerSize(); ++j)\n    {\n      LhsIterator i(lhsEval,j);\n      // handle diagonal coeff\n      if (ProcessSecondHalf)\n      {\n        while (i && i.index()<j) ++i;\n        if(i && i.index()==j)\n        {\n          res.coeffRef(j,k) += alpha * i.value() * rhs.coeff(j,k);\n          ++i;\n        }\n      }\n\n      // premultiplied rhs for scatters\n      typename ScalarBinaryOpTraits<AlphaType, typename DenseRhsType::Scalar>::ReturnType rhs_j(alpha*rhs(j,k));\n      // accumulator for partial scalar product\n      typename DenseResType::Scalar res_j(0);\n      for(; (ProcessFirstHalf ? i && i.index() < j : i) ; ++i)\n      {\n        LhsScalar lhs_ij = i.value();\n        if(!LhsIsRowMajor) lhs_ij = numext::conj(lhs_ij);\n        res_j += lhs_ij * rhs.coeff(i.index(),k);\n        res(i.index(),k) += numext::conj(lhs_ij) * rhs_j;\n      }\n      res.coeffRef(j,k) += alpha * res_j;\n\n      // handle diagonal coeff\n      if (ProcessFirstHalf && i && (i.index()==j))\n        res.coeffRef(j,k) += alpha * i.value() * rhs.coeff(j,k);\n    }\n  }\n}\n\n\ntemplate<typename LhsView, typename Rhs, int ProductType>\nstruct generic_product_impl<LhsView, Rhs, SparseSelfAdjointShape, DenseShape, ProductType>\n: generic_product_impl_base<LhsView, Rhs, generic_product_impl<LhsView, Rhs, SparseSelfAdjointShape, DenseShape, ProductType> >\n{\n  template<typename Dest>\n  static void scaleAndAddTo(Dest& dst, const LhsView& lhsView, const Rhs& rhs, const typename Dest::Scalar& alpha)\n  {\n    typedef typename LhsView::_MatrixTypeNested Lhs;\n    typedef typename nested_eval<Lhs,Dynamic>::type LhsNested;\n    typedef typename nested_eval<Rhs,Dynamic>::type RhsNested;\n    LhsNested lhsNested(lhsView.matrix());\n    RhsNested rhsNested(rhs);\n    \n    internal::sparse_selfadjoint_time_dense_product<LhsView::Mode>(lhsNested, rhsNested, dst, alpha);\n  }\n};\n\ntemplate<typename Lhs, typename RhsView, int ProductType>\nstruct generic_product_impl<Lhs, RhsView, DenseShape, SparseSelfAdjointShape, ProductType>\n: generic_product_impl_base<Lhs, RhsView, generic_product_impl<Lhs, RhsView, DenseShape, SparseSelfAdjointShape, ProductType> >\n{\n  template<typename Dest>\n  static void scaleAndAddTo(Dest& dst, const Lhs& lhs, const RhsView& rhsView, const typename Dest::Scalar& alpha)\n  {\n    typedef typename RhsView::_MatrixTypeNested Rhs;\n    typedef typename nested_eval<Lhs,Dynamic>::type LhsNested;\n    typedef typename nested_eval<Rhs,Dynamic>::type RhsNested;\n    LhsNested lhsNested(lhs);\n    RhsNested rhsNested(rhsView.matrix());\n    \n    // transpose everything\n    Transpose<Dest> dstT(dst);\n    internal::sparse_selfadjoint_time_dense_product<RhsView::TransposeMode>(rhsNested.transpose(), lhsNested.transpose(), dstT, alpha);\n  }\n};\n\n// NOTE: these two overloads are needed to evaluate the sparse selfadjoint view into a full sparse matrix\n// TODO: maybe the copy could be handled by generic_product_impl so that these overloads would not be needed anymore\n\ntemplate<typename LhsView, typename Rhs, int ProductTag>\nstruct product_evaluator<Product<LhsView, Rhs, DefaultProduct>, ProductTag, SparseSelfAdjointShape, SparseShape>\n  : public evaluator<typename Product<typename Rhs::PlainObject, Rhs, DefaultProduct>::PlainObject>\n{\n  typedef Product<LhsView, Rhs, DefaultProduct> XprType;\n  typedef typename XprType::PlainObject PlainObject;\n  typedef evaluator<PlainObject> Base;\n\n  product_evaluator(const XprType& xpr)\n    : m_lhs(xpr.lhs()), m_result(xpr.rows(), xpr.cols())\n  {\n    ::new (static_cast<Base*>(this)) Base(m_result);\n    generic_product_impl<typename Rhs::PlainObject, Rhs, SparseShape, SparseShape, ProductTag>::evalTo(m_result, m_lhs, xpr.rhs());\n  }\n  \nprotected:\n  typename Rhs::PlainObject m_lhs;\n  PlainObject m_result;\n};\n\ntemplate<typename Lhs, typename RhsView, int ProductTag>\nstruct product_evaluator<Product<Lhs, RhsView, DefaultProduct>, ProductTag, SparseShape, SparseSelfAdjointShape>\n  : public evaluator<typename Product<Lhs, typename Lhs::PlainObject, DefaultProduct>::PlainObject>\n{\n  typedef Product<Lhs, RhsView, DefaultProduct> XprType;\n  typedef typename XprType::PlainObject PlainObject;\n  typedef evaluator<PlainObject> Base;\n\n  product_evaluator(const XprType& xpr)\n    : m_rhs(xpr.rhs()), m_result(xpr.rows(), xpr.cols())\n  {\n    ::new (static_cast<Base*>(this)) Base(m_result);\n    generic_product_impl<Lhs, typename Lhs::PlainObject, SparseShape, SparseShape, ProductTag>::evalTo(m_result, xpr.lhs(), m_rhs);\n  }\n  \nprotected:\n  typename Lhs::PlainObject m_rhs;\n  PlainObject m_result;\n};\n\n} // namespace internal\n\n/***************************************************************************\n* Implementation of symmetric copies and permutations\n***************************************************************************/\nnamespace internal {\n\ntemplate<int Mode,typename MatrixType,int DestOrder>\nvoid permute_symm_to_fullsymm(const MatrixType& mat, SparseMatrix<typename MatrixType::Scalar,DestOrder,typename MatrixType::StorageIndex>& _dest, const typename MatrixType::StorageIndex* perm)\n{\n  typedef typename MatrixType::StorageIndex StorageIndex;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef SparseMatrix<Scalar,DestOrder,StorageIndex> Dest;\n  typedef Matrix<StorageIndex,Dynamic,1> VectorI;\n  typedef evaluator<MatrixType> MatEval;\n  typedef typename evaluator<MatrixType>::InnerIterator MatIterator;\n  \n  MatEval matEval(mat);\n  Dest& dest(_dest.derived());\n  enum {\n    StorageOrderMatch = int(Dest::IsRowMajor) == int(MatrixType::IsRowMajor)\n  };\n  \n  Index size = mat.rows();\n  VectorI count;\n  count.resize(size);\n  count.setZero();\n  dest.resize(size,size);\n  for(Index j = 0; j<size; ++j)\n  {\n    Index jp = perm ? perm[j] : j;\n    for(MatIterator it(matEval,j); it; ++it)\n    {\n      Index i = it.index();\n      Index r = it.row();\n      Index c = it.col();\n      Index ip = perm ? perm[i] : i;\n      if(Mode==int(Upper|Lower))\n        count[StorageOrderMatch ? jp : ip]++;\n      else if(r==c)\n        count[ip]++;\n      else if(( Mode==Lower && r>c) || ( Mode==Upper && r<c))\n      {\n        count[ip]++;\n        count[jp]++;\n      }\n    }\n  }\n  Index nnz = count.sum();\n  \n  // reserve space\n  dest.resizeNonZeros(nnz);\n  dest.outerIndexPtr()[0] = 0;\n  for(Index j=0; j<size; ++j)\n    dest.outerIndexPtr()[j+1] = dest.outerIndexPtr()[j] + count[j];\n  for(Index j=0; j<size; ++j)\n    count[j] = dest.outerIndexPtr()[j];\n  \n  // copy data\n  for(StorageIndex j = 0; j<size; ++j)\n  {\n    for(MatIterator it(matEval,j); it; ++it)\n    {\n      StorageIndex i = internal::convert_index<StorageIndex>(it.index());\n      Index r = it.row();\n      Index c = it.col();\n      \n      StorageIndex jp = perm ? perm[j] : j;\n      StorageIndex ip = perm ? perm[i] : i;\n      \n      if(Mode==int(Upper|Lower))\n      {\n        Index k = count[StorageOrderMatch ? jp : ip]++;\n        dest.innerIndexPtr()[k] = StorageOrderMatch ? ip : jp;\n        dest.valuePtr()[k] = it.value();\n      }\n      else if(r==c)\n      {\n        Index k = count[ip]++;\n        dest.innerIndexPtr()[k] = ip;\n        dest.valuePtr()[k] = it.value();\n      }\n      else if(( (Mode&Lower)==Lower && r>c) || ( (Mode&Upper)==Upper && r<c))\n      {\n        if(!StorageOrderMatch)\n          std::swap(ip,jp);\n        Index k = count[jp]++;\n        dest.innerIndexPtr()[k] = ip;\n        dest.valuePtr()[k] = it.value();\n        k = count[ip]++;\n        dest.innerIndexPtr()[k] = jp;\n        dest.valuePtr()[k] = numext::conj(it.value());\n      }\n    }\n  }\n}\n\ntemplate<int _SrcMode,int _DstMode,typename MatrixType,int DstOrder>\nvoid permute_symm_to_symm(const MatrixType& mat, SparseMatrix<typename MatrixType::Scalar,DstOrder,typename MatrixType::StorageIndex>& _dest, const typename MatrixType::StorageIndex* perm)\n{\n  typedef typename MatrixType::StorageIndex StorageIndex;\n  typedef typename MatrixType::Scalar Scalar;\n  SparseMatrix<Scalar,DstOrder,StorageIndex>& dest(_dest.derived());\n  typedef Matrix<StorageIndex,Dynamic,1> VectorI;\n  typedef evaluator<MatrixType> MatEval;\n  typedef typename evaluator<MatrixType>::InnerIterator MatIterator;\n\n  enum {\n    SrcOrder = MatrixType::IsRowMajor ? RowMajor : ColMajor,\n    StorageOrderMatch = int(SrcOrder) == int(DstOrder),\n    DstMode = DstOrder==RowMajor ? (_DstMode==Upper ? Lower : Upper) : _DstMode,\n    SrcMode = SrcOrder==RowMajor ? (_SrcMode==Upper ? Lower : Upper) : _SrcMode\n  };\n\n  MatEval matEval(mat);\n  \n  Index size = mat.rows();\n  VectorI count(size);\n  count.setZero();\n  dest.resize(size,size);\n  for(StorageIndex j = 0; j<size; ++j)\n  {\n    StorageIndex jp = perm ? perm[j] : j;\n    for(MatIterator it(matEval,j); it; ++it)\n    {\n      StorageIndex i = it.index();\n      if((int(SrcMode)==int(Lower) && i<j) || (int(SrcMode)==int(Upper) && i>j))\n        continue;\n                  \n      StorageIndex ip = perm ? perm[i] : i;\n      count[int(DstMode)==int(Lower) ? (std::min)(ip,jp) : (std::max)(ip,jp)]++;\n    }\n  }\n  dest.outerIndexPtr()[0] = 0;\n  for(Index j=0; j<size; ++j)\n    dest.outerIndexPtr()[j+1] = dest.outerIndexPtr()[j] + count[j];\n  dest.resizeNonZeros(dest.outerIndexPtr()[size]);\n  for(Index j=0; j<size; ++j)\n    count[j] = dest.outerIndexPtr()[j];\n  \n  for(StorageIndex j = 0; j<size; ++j)\n  {\n    \n    for(MatIterator it(matEval,j); it; ++it)\n    {\n      StorageIndex i = it.index();\n      if((int(SrcMode)==int(Lower) && i<j) || (int(SrcMode)==int(Upper) && i>j))\n        continue;\n                  \n      StorageIndex jp = perm ? perm[j] : j;\n      StorageIndex ip = perm? perm[i] : i;\n      \n      Index k = count[int(DstMode)==int(Lower) ? (std::min)(ip,jp) : (std::max)(ip,jp)]++;\n      dest.innerIndexPtr()[k] = int(DstMode)==int(Lower) ? (std::max)(ip,jp) : (std::min)(ip,jp);\n      \n      if(!StorageOrderMatch) std::swap(ip,jp);\n      if( ((int(DstMode)==int(Lower) && ip<jp) || (int(DstMode)==int(Upper) && ip>jp)))\n        dest.valuePtr()[k] = numext::conj(it.value());\n      else\n        dest.valuePtr()[k] = it.value();\n    }\n  }\n}\n\n}\n\n// TODO implement twists in a more evaluator friendly fashion\n\nnamespace internal {\n\ntemplate<typename MatrixType, int Mode>\nstruct traits<SparseSymmetricPermutationProduct<MatrixType,Mode> > : traits<MatrixType> {\n};\n\n}\n\ntemplate<typename MatrixType,int Mode>\nclass SparseSymmetricPermutationProduct\n  : public EigenBase<SparseSymmetricPermutationProduct<MatrixType,Mode> >\n{\n  public:\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    enum {\n      RowsAtCompileTime = internal::traits<SparseSymmetricPermutationProduct>::RowsAtCompileTime,\n      ColsAtCompileTime = internal::traits<SparseSymmetricPermutationProduct>::ColsAtCompileTime\n    };\n  protected:\n    typedef PermutationMatrix<Dynamic,Dynamic,StorageIndex> Perm;\n  public:\n    typedef Matrix<StorageIndex,Dynamic,1> VectorI;\n    typedef typename MatrixType::Nested MatrixTypeNested;\n    typedef typename internal::remove_all<MatrixTypeNested>::type NestedExpression;\n    \n    SparseSymmetricPermutationProduct(const MatrixType& mat, const Perm& perm)\n      : m_matrix(mat), m_perm(perm)\n    {}\n    \n    inline Index rows() const { return m_matrix.rows(); }\n    inline Index cols() const { return m_matrix.cols(); }\n        \n    const NestedExpression& matrix() const { return m_matrix; }\n    const Perm& perm() const { return m_perm; }\n    \n  protected:\n    MatrixTypeNested m_matrix;\n    const Perm& m_perm;\n\n};\n\nnamespace internal {\n  \ntemplate<typename DstXprType, typename MatrixType, int Mode, typename Scalar>\nstruct Assignment<DstXprType, SparseSymmetricPermutationProduct<MatrixType,Mode>, internal::assign_op<Scalar,typename MatrixType::Scalar>, Sparse2Sparse>\n{\n  typedef SparseSymmetricPermutationProduct<MatrixType,Mode> SrcXprType;\n  typedef typename DstXprType::StorageIndex DstIndex;\n  template<int Options>\n  static void run(SparseMatrix<Scalar,Options,DstIndex> &dst, const SrcXprType &src, const internal::assign_op<Scalar,typename MatrixType::Scalar> &)\n  {\n    // internal::permute_symm_to_fullsymm<Mode>(m_matrix,_dest,m_perm.indices().data());\n    SparseMatrix<Scalar,(Options&RowMajor)==RowMajor ? ColMajor : RowMajor, DstIndex> tmp;\n    internal::permute_symm_to_fullsymm<Mode>(src.matrix(),tmp,src.perm().indices().data());\n    dst = tmp;\n  }\n  \n  template<typename DestType,unsigned int DestMode>\n  static void run(SparseSelfAdjointView<DestType,DestMode>& dst, const SrcXprType &src, const internal::assign_op<Scalar,typename MatrixType::Scalar> &)\n  {\n    internal::permute_symm_to_symm<Mode,DestMode>(src.matrix(),dst.matrix(),src.perm().indices().data());\n  }\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_SELFADJOINTVIEW_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseSolverBase.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSESOLVERBASE_H\n#define EIGEN_SPARSESOLVERBASE_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n  /** \\internal\n  * Helper functions to solve with a sparse right-hand-side and result.\n  * The rhs is decomposed into small vertical panels which are solved through dense temporaries.\n  */\ntemplate<typename Decomposition, typename Rhs, typename Dest>\ntypename enable_if<Rhs::ColsAtCompileTime!=1 && Dest::ColsAtCompileTime!=1>::type\nsolve_sparse_through_dense_panels(const Decomposition &dec, const Rhs& rhs, Dest &dest)\n{\n  EIGEN_STATIC_ASSERT((Dest::Flags&RowMajorBit)==0,THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES);\n  typedef typename Dest::Scalar DestScalar;\n  // we process the sparse rhs per block of NbColsAtOnce columns temporarily stored into a dense matrix.\n  static const Index NbColsAtOnce = 4;\n  Index rhsCols = rhs.cols();\n  Index size = rhs.rows();\n  // the temporary matrices do not need more columns than NbColsAtOnce:\n  Index tmpCols = (std::min)(rhsCols, NbColsAtOnce); \n  Eigen::Matrix<DestScalar,Dynamic,Dynamic> tmp(size,tmpCols);\n  Eigen::Matrix<DestScalar,Dynamic,Dynamic> tmpX(size,tmpCols);\n  for(Index k=0; k<rhsCols; k+=NbColsAtOnce)\n  {\n    Index actualCols = std::min<Index>(rhsCols-k, NbColsAtOnce);\n    tmp.leftCols(actualCols) = rhs.middleCols(k,actualCols);\n    tmpX.leftCols(actualCols) = dec.solve(tmp.leftCols(actualCols));\n    dest.middleCols(k,actualCols) = tmpX.leftCols(actualCols).sparseView();\n  }\n}\n\n// Overload for vector as rhs\ntemplate<typename Decomposition, typename Rhs, typename Dest>\ntypename enable_if<Rhs::ColsAtCompileTime==1 || Dest::ColsAtCompileTime==1>::type\nsolve_sparse_through_dense_panels(const Decomposition &dec, const Rhs& rhs, Dest &dest)\n{\n  typedef typename Dest::Scalar DestScalar;\n  Index size = rhs.rows();\n  Eigen::Matrix<DestScalar,Dynamic,1> rhs_dense(rhs);\n  Eigen::Matrix<DestScalar,Dynamic,1> dest_dense(size);\n  dest_dense = dec.solve(rhs_dense);\n  dest = dest_dense.sparseView();\n}\n\n} // end namespace internal\n\n/** \\class SparseSolverBase\n  * \\ingroup SparseCore_Module\n  * \\brief A base class for sparse solvers\n  *\n  * \\tparam Derived the actual type of the solver.\n  *\n  */\ntemplate<typename Derived>\nclass SparseSolverBase : internal::noncopyable\n{\n  public:\n\n    /** Default constructor */\n    SparseSolverBase()\n      : m_isInitialized(false)\n    {}\n\n    ~SparseSolverBase()\n    {}\n\n    Derived& derived() { return *static_cast<Derived*>(this); }\n    const Derived& derived() const { return *static_cast<const Derived*>(this); }\n    \n    /** \\returns an expression of the solution x of \\f$ A x = b \\f$ using the current decomposition of A.\n      *\n      * \\sa compute()\n      */\n    template<typename Rhs>\n    inline const Solve<Derived, Rhs>\n    solve(const MatrixBase<Rhs>& b) const\n    {\n      eigen_assert(m_isInitialized && \"Solver is not initialized.\");\n      eigen_assert(derived().rows()==b.rows() && \"solve(): invalid number of rows of the right hand side matrix b\");\n      return Solve<Derived, Rhs>(derived(), b.derived());\n    }\n    \n    /** \\returns an expression of the solution x of \\f$ A x = b \\f$ using the current decomposition of A.\n      *\n      * \\sa compute()\n      */\n    template<typename Rhs>\n    inline const Solve<Derived, Rhs>\n    solve(const SparseMatrixBase<Rhs>& b) const\n    {\n      eigen_assert(m_isInitialized && \"Solver is not initialized.\");\n      eigen_assert(derived().rows()==b.rows() && \"solve(): invalid number of rows of the right hand side matrix b\");\n      return Solve<Derived, Rhs>(derived(), b.derived());\n    }\n    \n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    /** \\internal default implementation of solving with a sparse rhs */\n    template<typename Rhs,typename Dest>\n    void _solve_impl(const SparseMatrixBase<Rhs> &b, SparseMatrixBase<Dest> &dest) const\n    {\n      internal::solve_sparse_through_dense_panels(derived(), b.derived(), dest.derived());\n    }\n    #endif // EIGEN_PARSED_BY_DOXYGEN\n\n  protected:\n    \n    mutable bool m_isInitialized;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSESOLVERBASE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseSparseProductWithPruning.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSESPARSEPRODUCTWITHPRUNING_H\n#define EIGEN_SPARSESPARSEPRODUCTWITHPRUNING_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n\n// perform a pseudo in-place sparse * sparse product assuming all matrices are col major\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstatic void sparse_sparse_product_with_pruning_impl(const Lhs& lhs, const Rhs& rhs, ResultType& res, const typename ResultType::RealScalar& tolerance)\n{\n  // return sparse_sparse_product_with_pruning_impl2(lhs,rhs,res);\n\n  typedef typename remove_all<Rhs>::type::Scalar RhsScalar;\n  typedef typename remove_all<ResultType>::type::Scalar ResScalar;\n  typedef typename remove_all<Lhs>::type::StorageIndex StorageIndex;\n\n  // make sure to call innerSize/outerSize since we fake the storage order.\n  Index rows = lhs.innerSize();\n  Index cols = rhs.outerSize();\n  //Index size = lhs.outerSize();\n  eigen_assert(lhs.outerSize() == rhs.innerSize());\n\n  // allocate a temporary buffer\n  AmbiVector<ResScalar,StorageIndex> tempVector(rows);\n\n  // mimics a resizeByInnerOuter:\n  if(ResultType::IsRowMajor)\n    res.resize(cols, rows);\n  else\n    res.resize(rows, cols);\n  \n  evaluator<Lhs> lhsEval(lhs);\n  evaluator<Rhs> rhsEval(rhs);\n  \n  // estimate the number of non zero entries\n  // given a rhs column containing Y non zeros, we assume that the respective Y columns\n  // of the lhs differs in average of one non zeros, thus the number of non zeros for\n  // the product of a rhs column with the lhs is X+Y where X is the average number of non zero\n  // per column of the lhs.\n  // Therefore, we have nnz(lhs*rhs) = nnz(lhs) + nnz(rhs)\n  Index estimated_nnz_prod = lhsEval.nonZerosEstimate() + rhsEval.nonZerosEstimate();\n\n  res.reserve(estimated_nnz_prod);\n  double ratioColRes = double(estimated_nnz_prod)/(double(lhs.rows())*double(rhs.cols()));\n  for (Index j=0; j<cols; ++j)\n  {\n    // FIXME:\n    //double ratioColRes = (double(rhs.innerVector(j).nonZeros()) + double(lhs.nonZeros())/double(lhs.cols()))/double(lhs.rows());\n    // let's do a more accurate determination of the nnz ratio for the current column j of res\n    tempVector.init(ratioColRes);\n    tempVector.setZero();\n    for (typename evaluator<Rhs>::InnerIterator rhsIt(rhsEval, j); rhsIt; ++rhsIt)\n    {\n      // FIXME should be written like this: tmp += rhsIt.value() * lhs.col(rhsIt.index())\n      tempVector.restart();\n      RhsScalar x = rhsIt.value();\n      for (typename evaluator<Lhs>::InnerIterator lhsIt(lhsEval, rhsIt.index()); lhsIt; ++lhsIt)\n      {\n        tempVector.coeffRef(lhsIt.index()) += lhsIt.value() * x;\n      }\n    }\n    res.startVec(j);\n    for (typename AmbiVector<ResScalar,StorageIndex>::Iterator it(tempVector,tolerance); it; ++it)\n      res.insertBackByOuterInner(j,it.index()) = it.value();\n  }\n  res.finalize();\n}\n\ntemplate<typename Lhs, typename Rhs, typename ResultType,\n  int LhsStorageOrder = traits<Lhs>::Flags&RowMajorBit,\n  int RhsStorageOrder = traits<Rhs>::Flags&RowMajorBit,\n  int ResStorageOrder = traits<ResultType>::Flags&RowMajorBit>\nstruct sparse_sparse_product_with_pruning_selector;\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,ColMajor,ColMajor,ColMajor>\n{\n  typedef typename ResultType::RealScalar RealScalar;\n\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)\n  {\n    typename remove_all<ResultType>::type _res(res.rows(), res.cols());\n    internal::sparse_sparse_product_with_pruning_impl<Lhs,Rhs,ResultType>(lhs, rhs, _res, tolerance);\n    res.swap(_res);\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,ColMajor,ColMajor,RowMajor>\n{\n  typedef typename ResultType::RealScalar RealScalar;\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)\n  {\n    // we need a col-major matrix to hold the result\n    typedef SparseMatrix<typename ResultType::Scalar,ColMajor,typename ResultType::StorageIndex> SparseTemporaryType;\n    SparseTemporaryType _res(res.rows(), res.cols());\n    internal::sparse_sparse_product_with_pruning_impl<Lhs,Rhs,SparseTemporaryType>(lhs, rhs, _res, tolerance);\n    res = _res;\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,RowMajor,RowMajor,RowMajor>\n{\n  typedef typename ResultType::RealScalar RealScalar;\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)\n  {\n    // let's transpose the product to get a column x column product\n    typename remove_all<ResultType>::type _res(res.rows(), res.cols());\n    internal::sparse_sparse_product_with_pruning_impl<Rhs,Lhs,ResultType>(rhs, lhs, _res, tolerance);\n    res.swap(_res);\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,RowMajor,RowMajor,ColMajor>\n{\n  typedef typename ResultType::RealScalar RealScalar;\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)\n  {\n    typedef SparseMatrix<typename Lhs::Scalar,ColMajor,typename Lhs::StorageIndex> ColMajorMatrixLhs;\n    typedef SparseMatrix<typename Rhs::Scalar,ColMajor,typename Lhs::StorageIndex> ColMajorMatrixRhs;\n    ColMajorMatrixLhs colLhs(lhs);\n    ColMajorMatrixRhs colRhs(rhs);\n    internal::sparse_sparse_product_with_pruning_impl<ColMajorMatrixLhs,ColMajorMatrixRhs,ResultType>(colLhs, colRhs, res, tolerance);\n\n    // let's transpose the product to get a column x column product\n//     typedef SparseMatrix<typename ResultType::Scalar> SparseTemporaryType;\n//     SparseTemporaryType _res(res.cols(), res.rows());\n//     sparse_sparse_product_with_pruning_impl<Rhs,Lhs,SparseTemporaryType>(rhs, lhs, _res);\n//     res = _res.transpose();\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,ColMajor,RowMajor,RowMajor>\n{\n  typedef typename ResultType::RealScalar RealScalar;\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)\n  {\n    typedef SparseMatrix<typename Lhs::Scalar,RowMajor,typename Lhs::StorageIndex> RowMajorMatrixLhs;\n    RowMajorMatrixLhs rowLhs(lhs);\n    sparse_sparse_product_with_pruning_selector<RowMajorMatrixLhs,Rhs,ResultType,RowMajor,RowMajor>(rowLhs,rhs,res,tolerance);\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,RowMajor,ColMajor,RowMajor>\n{\n  typedef typename ResultType::RealScalar RealScalar;\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)\n  {\n    typedef SparseMatrix<typename Rhs::Scalar,RowMajor,typename Lhs::StorageIndex> RowMajorMatrixRhs;\n    RowMajorMatrixRhs rowRhs(rhs);\n    sparse_sparse_product_with_pruning_selector<Lhs,RowMajorMatrixRhs,ResultType,RowMajor,RowMajor,RowMajor>(lhs,rowRhs,res,tolerance);\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,ColMajor,RowMajor,ColMajor>\n{\n  typedef typename ResultType::RealScalar RealScalar;\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)\n  {\n    typedef SparseMatrix<typename Rhs::Scalar,ColMajor,typename Lhs::StorageIndex> ColMajorMatrixRhs;\n    ColMajorMatrixRhs colRhs(rhs);\n    internal::sparse_sparse_product_with_pruning_impl<Lhs,ColMajorMatrixRhs,ResultType>(lhs, colRhs, res, tolerance);\n  }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct sparse_sparse_product_with_pruning_selector<Lhs,Rhs,ResultType,RowMajor,ColMajor,ColMajor>\n{\n  typedef typename ResultType::RealScalar RealScalar;\n  static void run(const Lhs& lhs, const Rhs& rhs, ResultType& res, const RealScalar& tolerance)\n  {\n    typedef SparseMatrix<typename Lhs::Scalar,ColMajor,typename Lhs::StorageIndex> ColMajorMatrixLhs;\n    ColMajorMatrixLhs colLhs(lhs);\n    internal::sparse_sparse_product_with_pruning_impl<ColMajorMatrixLhs,Rhs,ResultType>(colLhs, rhs, res, tolerance);\n  }\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSESPARSEPRODUCTWITHPRUNING_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseTranspose.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSETRANSPOSE_H\n#define EIGEN_SPARSETRANSPOSE_H\n\nnamespace Eigen { \n\nnamespace internal {\n  template<typename MatrixType,int CompressedAccess=int(MatrixType::Flags&CompressedAccessBit)>\n  class SparseTransposeImpl\n    : public SparseMatrixBase<Transpose<MatrixType> >\n  {};\n  \n  template<typename MatrixType>\n  class SparseTransposeImpl<MatrixType,CompressedAccessBit>\n    : public SparseCompressedBase<Transpose<MatrixType> >\n  {\n    typedef SparseCompressedBase<Transpose<MatrixType> > Base;\n  public:\n    using Base::derived;\n    typedef typename Base::Scalar Scalar;\n    typedef typename Base::StorageIndex StorageIndex;\n\n    inline Index nonZeros() const { return derived().nestedExpression().nonZeros(); }\n    \n    inline const Scalar* valuePtr() const { return derived().nestedExpression().valuePtr(); }\n    inline const StorageIndex* innerIndexPtr() const { return derived().nestedExpression().innerIndexPtr(); }\n    inline const StorageIndex* outerIndexPtr() const { return derived().nestedExpression().outerIndexPtr(); }\n    inline const StorageIndex* innerNonZeroPtr() const { return derived().nestedExpression().innerNonZeroPtr(); }\n\n    inline Scalar* valuePtr() { return derived().nestedExpression().valuePtr(); }\n    inline StorageIndex* innerIndexPtr() { return derived().nestedExpression().innerIndexPtr(); }\n    inline StorageIndex* outerIndexPtr() { return derived().nestedExpression().outerIndexPtr(); }\n    inline StorageIndex* innerNonZeroPtr() { return derived().nestedExpression().innerNonZeroPtr(); }\n  };\n}\n  \ntemplate<typename MatrixType> class TransposeImpl<MatrixType,Sparse>\n  : public internal::SparseTransposeImpl<MatrixType>\n{\n  protected:\n    typedef internal::SparseTransposeImpl<MatrixType> Base;\n};\n\nnamespace internal {\n  \ntemplate<typename ArgType>\nstruct unary_evaluator<Transpose<ArgType>, IteratorBased>\n  : public evaluator_base<Transpose<ArgType> >\n{\n    typedef typename evaluator<ArgType>::InnerIterator        EvalIterator;\n  public:\n    typedef Transpose<ArgType> XprType;\n    \n    inline Index nonZerosEstimate() const {\n      return m_argImpl.nonZerosEstimate();\n    }\n\n    class InnerIterator : public EvalIterator\n    {\n    public:\n      EIGEN_STRONG_INLINE InnerIterator(const unary_evaluator& unaryOp, Index outer)\n        : EvalIterator(unaryOp.m_argImpl,outer)\n      {}\n      \n      Index row() const { return EvalIterator::col(); }\n      Index col() const { return EvalIterator::row(); }\n    };\n    \n    enum {\n      CoeffReadCost = evaluator<ArgType>::CoeffReadCost,\n      Flags = XprType::Flags\n    };\n    \n    explicit unary_evaluator(const XprType& op) :m_argImpl(op.nestedExpression()) {}\n\n  protected:\n    evaluator<ArgType> m_argImpl;\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSETRANSPOSE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseTriangularView.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_TRIANGULARVIEW_H\n#define EIGEN_SPARSE_TRIANGULARVIEW_H\n\nnamespace Eigen {\n\n/** \\ingroup SparseCore_Module\n  *\n  * \\brief Base class for a triangular part in a \\b sparse matrix\n  *\n  * This class is an abstract base class of class TriangularView, and objects of type TriangularViewImpl cannot be instantiated.\n  * It extends class TriangularView with additional methods which are available for sparse expressions only.\n  *\n  * \\sa class TriangularView, SparseMatrixBase::triangularView()\n  */\ntemplate<typename MatrixType, unsigned int Mode> class TriangularViewImpl<MatrixType,Mode,Sparse>\n  : public SparseMatrixBase<TriangularView<MatrixType,Mode> >\n{\n    enum { SkipFirst = ((Mode&Lower) && !(MatrixType::Flags&RowMajorBit))\n                    || ((Mode&Upper) &&  (MatrixType::Flags&RowMajorBit)),\n           SkipLast = !SkipFirst,\n           SkipDiag = (Mode&ZeroDiag) ? 1 : 0,\n           HasUnitDiag = (Mode&UnitDiag) ? 1 : 0\n    };\n    \n    typedef TriangularView<MatrixType,Mode> TriangularViewType;\n    \n  protected:\n    // dummy solve function to make TriangularView happy.\n    void solve() const;\n\n    typedef SparseMatrixBase<TriangularViewType> Base;\n  public:\n    \n    EIGEN_SPARSE_PUBLIC_INTERFACE(TriangularViewType)\n    \n    typedef typename MatrixType::Nested MatrixTypeNested;\n    typedef typename internal::remove_reference<MatrixTypeNested>::type MatrixTypeNestedNonRef;\n    typedef typename internal::remove_all<MatrixTypeNested>::type MatrixTypeNestedCleaned;\n\n    template<typename RhsType, typename DstType>\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE void _solve_impl(const RhsType &rhs, DstType &dst) const {\n      if(!(internal::is_same<RhsType,DstType>::value && internal::extract_data(dst) == internal::extract_data(rhs)))\n        dst = rhs;\n      this->solveInPlace(dst);\n    }\n\n    /** Applies the inverse of \\c *this to the dense vector or matrix \\a other, \"in-place\" */\n    template<typename OtherDerived> void solveInPlace(MatrixBase<OtherDerived>& other) const;\n\n    /** Applies the inverse of \\c *this to the sparse vector or matrix \\a other, \"in-place\" */\n    template<typename OtherDerived> void solveInPlace(SparseMatrixBase<OtherDerived>& other) const;\n  \n};\n\nnamespace internal {\n\ntemplate<typename ArgType, unsigned int Mode>\nstruct unary_evaluator<TriangularView<ArgType,Mode>, IteratorBased>\n : evaluator_base<TriangularView<ArgType,Mode> >\n{\n  typedef TriangularView<ArgType,Mode> XprType;\n  \nprotected:\n  \n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::StorageIndex StorageIndex;\n  typedef typename evaluator<ArgType>::InnerIterator EvalIterator;\n  \n  enum { SkipFirst = ((Mode&Lower) && !(ArgType::Flags&RowMajorBit))\n                    || ((Mode&Upper) &&  (ArgType::Flags&RowMajorBit)),\n         SkipLast = !SkipFirst,\n         SkipDiag = (Mode&ZeroDiag) ? 1 : 0,\n         HasUnitDiag = (Mode&UnitDiag) ? 1 : 0\n  };\n  \npublic:\n  \n  enum {\n    CoeffReadCost = evaluator<ArgType>::CoeffReadCost,\n    Flags = XprType::Flags\n  };\n    \n  explicit unary_evaluator(const XprType &xpr) : m_argImpl(xpr.nestedExpression()), m_arg(xpr.nestedExpression()) {}\n  \n  inline Index nonZerosEstimate() const {\n    return m_argImpl.nonZerosEstimate();\n  }\n  \n  class InnerIterator : public EvalIterator\n  {\n      typedef EvalIterator Base;\n    public:\n\n      EIGEN_STRONG_INLINE InnerIterator(const unary_evaluator& xprEval, Index outer)\n        : Base(xprEval.m_argImpl,outer), m_returnOne(false), m_containsDiag(Base::outer()<xprEval.m_arg.innerSize())\n      {\n        if(SkipFirst)\n        {\n          while((*this) && ((HasUnitDiag||SkipDiag)  ? this->index()<=outer : this->index()<outer))\n            Base::operator++();\n          if(HasUnitDiag)\n            m_returnOne = m_containsDiag;\n        }\n        else if(HasUnitDiag && ((!Base::operator bool()) || Base::index()>=Base::outer()))\n        {\n          if((!SkipFirst) && Base::operator bool())\n            Base::operator++();\n          m_returnOne = m_containsDiag;\n        }\n      }\n\n      EIGEN_STRONG_INLINE InnerIterator& operator++()\n      {\n        if(HasUnitDiag && m_returnOne)\n          m_returnOne = false;\n        else\n        {\n          Base::operator++();\n          if(HasUnitDiag && (!SkipFirst) && ((!Base::operator bool()) || Base::index()>=Base::outer()))\n          {\n            if((!SkipFirst) && Base::operator bool())\n              Base::operator++();\n            m_returnOne = m_containsDiag;\n          }\n        }\n        return *this;\n      }\n      \n      EIGEN_STRONG_INLINE operator bool() const\n      {\n        if(HasUnitDiag && m_returnOne)\n          return true;\n        if(SkipFirst) return  Base::operator bool();\n        else\n        {\n          if (SkipDiag) return (Base::operator bool() && this->index() < this->outer());\n          else return (Base::operator bool() && this->index() <= this->outer());\n        }\n      }\n\n//       inline Index row() const { return (ArgType::Flags&RowMajorBit ? Base::outer() : this->index()); }\n//       inline Index col() const { return (ArgType::Flags&RowMajorBit ? this->index() : Base::outer()); }\n      inline StorageIndex index() const\n      {\n        if(HasUnitDiag && m_returnOne)  return internal::convert_index<StorageIndex>(Base::outer());\n        else                            return Base::index();\n      }\n      inline Scalar value() const\n      {\n        if(HasUnitDiag && m_returnOne)  return Scalar(1);\n        else                            return Base::value();\n      }\n\n    protected:\n      bool m_returnOne;\n      bool m_containsDiag;\n    private:\n      Scalar& valueRef();\n  };\n  \nprotected:\n  evaluator<ArgType> m_argImpl;\n  const ArgType& m_arg;\n};\n\n} // end namespace internal\n\ntemplate<typename Derived>\ntemplate<int Mode>\ninline const TriangularView<const Derived, Mode>\nSparseMatrixBase<Derived>::triangularView() const\n{\n  return TriangularView<const Derived, Mode>(derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_TRIANGULARVIEW_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseUtil.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEUTIL_H\n#define EIGEN_SPARSEUTIL_H\n\nnamespace Eigen { \n\n#ifdef NDEBUG\n#define EIGEN_DBG_SPARSE(X)\n#else\n#define EIGEN_DBG_SPARSE(X) X\n#endif\n\n#define EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(Derived, Op) \\\ntemplate<typename OtherDerived> \\\nEIGEN_STRONG_INLINE Derived& operator Op(const Eigen::SparseMatrixBase<OtherDerived>& other) \\\n{ \\\n  return Base::operator Op(other.derived()); \\\n} \\\nEIGEN_STRONG_INLINE Derived& operator Op(const Derived& other) \\\n{ \\\n  return Base::operator Op(other); \\\n}\n\n#define EIGEN_SPARSE_INHERIT_SCALAR_ASSIGNMENT_OPERATOR(Derived, Op) \\\ntemplate<typename Other> \\\nEIGEN_STRONG_INLINE Derived& operator Op(const Other& scalar) \\\n{ \\\n  return Base::operator Op(scalar); \\\n}\n\n#define EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATORS(Derived) \\\nEIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(Derived, =)\n\n\n#define EIGEN_SPARSE_PUBLIC_INTERFACE(Derived) \\\n  EIGEN_GENERIC_PUBLIC_INTERFACE(Derived)\n\n  \nconst int CoherentAccessPattern     = 0x1;\nconst int InnerRandomAccessPattern  = 0x2 | CoherentAccessPattern;\nconst int OuterRandomAccessPattern  = 0x4 | CoherentAccessPattern;\nconst int RandomAccessPattern       = 0x8 | OuterRandomAccessPattern | InnerRandomAccessPattern;\n\ntemplate<typename _Scalar, int _Flags = 0, typename _StorageIndex = int>  class SparseMatrix;\ntemplate<typename _Scalar, int _Flags = 0, typename _StorageIndex = int>  class DynamicSparseMatrix;\ntemplate<typename _Scalar, int _Flags = 0, typename _StorageIndex = int>  class SparseVector;\ntemplate<typename _Scalar, int _Flags = 0, typename _StorageIndex = int>  class MappedSparseMatrix;\n\ntemplate<typename MatrixType, unsigned int UpLo>  class SparseSelfAdjointView;\ntemplate<typename Lhs, typename Rhs>              class SparseDiagonalProduct;\ntemplate<typename MatrixType> class SparseView;\n\ntemplate<typename Lhs, typename Rhs>        class SparseSparseProduct;\ntemplate<typename Lhs, typename Rhs>        class SparseTimeDenseProduct;\ntemplate<typename Lhs, typename Rhs>        class DenseTimeSparseProduct;\ntemplate<typename Lhs, typename Rhs, bool Transpose> class SparseDenseOuterProduct;\n\ntemplate<typename Lhs, typename Rhs> struct SparseSparseProductReturnType;\ntemplate<typename Lhs, typename Rhs,\n         int InnerSize = EIGEN_SIZE_MIN_PREFER_FIXED(internal::traits<Lhs>::ColsAtCompileTime,internal::traits<Rhs>::RowsAtCompileTime)> struct DenseSparseProductReturnType;\n         \ntemplate<typename Lhs, typename Rhs,\n         int InnerSize = EIGEN_SIZE_MIN_PREFER_FIXED(internal::traits<Lhs>::ColsAtCompileTime,internal::traits<Rhs>::RowsAtCompileTime)> struct SparseDenseProductReturnType;\ntemplate<typename MatrixType,int UpLo> class SparseSymmetricPermutationProduct;\n\nnamespace internal {\n\ntemplate<typename T,int Rows,int Cols,int Flags> struct sparse_eval;\n\ntemplate<typename T> struct eval<T,Sparse>\n  : sparse_eval<T, traits<T>::RowsAtCompileTime,traits<T>::ColsAtCompileTime,traits<T>::Flags>\n{};\n\ntemplate<typename T,int Cols,int Flags> struct sparse_eval<T,1,Cols,Flags> {\n    typedef typename traits<T>::Scalar _Scalar;\n    typedef typename traits<T>::StorageIndex _StorageIndex;\n  public:\n    typedef SparseVector<_Scalar, RowMajor, _StorageIndex> type;\n};\n\ntemplate<typename T,int Rows,int Flags> struct sparse_eval<T,Rows,1,Flags> {\n    typedef typename traits<T>::Scalar _Scalar;\n    typedef typename traits<T>::StorageIndex _StorageIndex;\n  public:\n    typedef SparseVector<_Scalar, ColMajor, _StorageIndex> type;\n};\n\n// TODO this seems almost identical to plain_matrix_type<T, Sparse>\ntemplate<typename T,int Rows,int Cols,int Flags> struct sparse_eval {\n    typedef typename traits<T>::Scalar _Scalar;\n    typedef typename traits<T>::StorageIndex _StorageIndex;\n    enum { _Options = ((Flags&RowMajorBit)==RowMajorBit) ? RowMajor : ColMajor };\n  public:\n    typedef SparseMatrix<_Scalar, _Options, _StorageIndex> type;\n};\n\ntemplate<typename T,int Flags> struct sparse_eval<T,1,1,Flags> {\n    typedef typename traits<T>::Scalar _Scalar;\n  public:\n    typedef Matrix<_Scalar, 1, 1> type;\n};\n\ntemplate<typename T> struct plain_matrix_type<T,Sparse>\n{\n  typedef typename traits<T>::Scalar _Scalar;\n  typedef typename traits<T>::StorageIndex _StorageIndex;\n  enum { _Options = ((evaluator<T>::Flags&RowMajorBit)==RowMajorBit) ? RowMajor : ColMajor };\n  public:\n    typedef SparseMatrix<_Scalar, _Options, _StorageIndex> type;\n};\n\ntemplate<typename T>\nstruct plain_object_eval<T,Sparse>\n  : sparse_eval<T, traits<T>::RowsAtCompileTime,traits<T>::ColsAtCompileTime, evaluator<T>::Flags>\n{};\n\ntemplate<typename Decomposition, typename RhsType>\nstruct solve_traits<Decomposition,RhsType,Sparse>\n{\n  typedef typename sparse_eval<RhsType, RhsType::RowsAtCompileTime, RhsType::ColsAtCompileTime,traits<RhsType>::Flags>::type PlainObject;\n};\n\ntemplate<typename Derived>\nstruct generic_xpr_base<Derived, MatrixXpr, Sparse>\n{\n  typedef SparseMatrixBase<Derived> type;\n};\n\nstruct SparseTriangularShape  { static std::string debugName() { return \"SparseTriangularShape\"; } };\nstruct SparseSelfAdjointShape { static std::string debugName() { return \"SparseSelfAdjointShape\"; } };\n\ntemplate<> struct glue_shapes<SparseShape,SelfAdjointShape> { typedef SparseSelfAdjointShape type;  };\ntemplate<> struct glue_shapes<SparseShape,TriangularShape > { typedef SparseTriangularShape  type;  };\n\n// return type of SparseCompressedBase::lower_bound;\nstruct LowerBoundIndex {\n  LowerBoundIndex() : value(-1), found(false) {}\n  LowerBoundIndex(Index val, bool ok) : value(val), found(ok) {}\n  Index value;\n  bool found;\n};\n\n} // end namespace internal\n\n/** \\ingroup SparseCore_Module\n  *\n  * \\class Triplet\n  *\n  * \\brief A small structure to hold a non zero as a triplet (i,j,value).\n  *\n  * \\sa SparseMatrix::setFromTriplets()\n  */\ntemplate<typename Scalar, typename StorageIndex=typename SparseMatrix<Scalar>::StorageIndex >\nclass Triplet\n{\npublic:\n  Triplet() : m_row(0), m_col(0), m_value(0) {}\n\n  Triplet(const StorageIndex& i, const StorageIndex& j, const Scalar& v = Scalar(0))\n    : m_row(i), m_col(j), m_value(v)\n  {}\n\n  /** \\returns the row index of the element */\n  const StorageIndex& row() const { return m_row; }\n\n  /** \\returns the column index of the element */\n  const StorageIndex& col() const { return m_col; }\n\n  /** \\returns the value of the element */\n  const Scalar& value() const { return m_value; }\nprotected:\n  StorageIndex m_row, m_col;\n  Scalar m_value;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSEUTIL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseVector.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEVECTOR_H\n#define EIGEN_SPARSEVECTOR_H\n\nnamespace Eigen { \n\n/** \\ingroup SparseCore_Module\n  * \\class SparseVector\n  *\n  * \\brief a sparse vector class\n  *\n  * \\tparam _Scalar the scalar type, i.e. the type of the coefficients\n  *\n  * See http://www.netlib.org/linalg/html_templates/node91.html for details on the storage scheme.\n  *\n  * This class can be extended with the help of the plugin mechanism described on the page\n  * \\ref TopicCustomizing_Plugins by defining the preprocessor symbol \\c EIGEN_SPARSEVECTOR_PLUGIN.\n  */\n\nnamespace internal {\ntemplate<typename _Scalar, int _Options, typename _StorageIndex>\nstruct traits<SparseVector<_Scalar, _Options, _StorageIndex> >\n{\n  typedef _Scalar Scalar;\n  typedef _StorageIndex StorageIndex;\n  typedef Sparse StorageKind;\n  typedef MatrixXpr XprKind;\n  enum {\n    IsColVector = (_Options & RowMajorBit) ? 0 : 1,\n\n    RowsAtCompileTime = IsColVector ? Dynamic : 1,\n    ColsAtCompileTime = IsColVector ? 1 : Dynamic,\n    MaxRowsAtCompileTime = RowsAtCompileTime,\n    MaxColsAtCompileTime = ColsAtCompileTime,\n    Flags = _Options | NestByRefBit | LvalueBit | (IsColVector ? 0 : RowMajorBit) | CompressedAccessBit,\n    SupportedAccessPatterns = InnerRandomAccessPattern\n  };\n};\n\n// Sparse-Vector-Assignment kinds:\nenum {\n  SVA_RuntimeSwitch,\n  SVA_Inner,\n  SVA_Outer\n};\n\ntemplate< typename Dest, typename Src,\n          int AssignmentKind = !bool(Src::IsVectorAtCompileTime) ? SVA_RuntimeSwitch\n                             : Src::InnerSizeAtCompileTime==1 ? SVA_Outer\n                             : SVA_Inner>\nstruct sparse_vector_assign_selector;\n\n}\n\ntemplate<typename _Scalar, int _Options, typename _StorageIndex>\nclass SparseVector\n  : public SparseCompressedBase<SparseVector<_Scalar, _Options, _StorageIndex> >\n{\n    typedef SparseCompressedBase<SparseVector> Base;\n    using Base::convert_index;\n  public:\n    EIGEN_SPARSE_PUBLIC_INTERFACE(SparseVector)\n    EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(SparseVector, +=)\n    EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(SparseVector, -=)\n    \n    typedef internal::CompressedStorage<Scalar,StorageIndex> Storage;\n    enum { IsColVector = internal::traits<SparseVector>::IsColVector };\n    \n    enum {\n      Options = _Options\n    };\n    \n    EIGEN_STRONG_INLINE Index rows() const { return IsColVector ? m_size : 1; }\n    EIGEN_STRONG_INLINE Index cols() const { return IsColVector ? 1 : m_size; }\n    EIGEN_STRONG_INLINE Index innerSize() const { return m_size; }\n    EIGEN_STRONG_INLINE Index outerSize() const { return 1; }\n\n    EIGEN_STRONG_INLINE const Scalar* valuePtr() const { return m_data.valuePtr(); }\n    EIGEN_STRONG_INLINE Scalar* valuePtr() { return m_data.valuePtr(); }\n\n    EIGEN_STRONG_INLINE const StorageIndex* innerIndexPtr() const { return m_data.indexPtr(); }\n    EIGEN_STRONG_INLINE StorageIndex* innerIndexPtr() { return m_data.indexPtr(); }\n\n    inline const StorageIndex* outerIndexPtr() const { return 0; }\n    inline StorageIndex* outerIndexPtr() { return 0; }\n    inline const StorageIndex* innerNonZeroPtr() const { return 0; }\n    inline StorageIndex* innerNonZeroPtr() { return 0; }\n    \n    /** \\internal */\n    inline Storage& data() { return m_data; }\n    /** \\internal */\n    inline const Storage& data() const { return m_data; }\n\n    inline Scalar coeff(Index row, Index col) const\n    {\n      eigen_assert(IsColVector ? (col==0 && row>=0 && row<m_size) : (row==0 && col>=0 && col<m_size));\n      return coeff(IsColVector ? row : col);\n    }\n    inline Scalar coeff(Index i) const\n    {\n      eigen_assert(i>=0 && i<m_size);\n      return m_data.at(StorageIndex(i));\n    }\n\n    inline Scalar& coeffRef(Index row, Index col)\n    {\n      eigen_assert(IsColVector ? (col==0 && row>=0 && row<m_size) : (row==0 && col>=0 && col<m_size));\n      return coeffRef(IsColVector ? row : col);\n    }\n\n    /** \\returns a reference to the coefficient value at given index \\a i\n      * This operation involes a log(rho*size) binary search. If the coefficient does not\n      * exist yet, then a sorted insertion into a sequential buffer is performed.\n      *\n      * This insertion might be very costly if the number of nonzeros above \\a i is large.\n      */\n    inline Scalar& coeffRef(Index i)\n    {\n      eigen_assert(i>=0 && i<m_size);\n\n      return m_data.atWithInsertion(StorageIndex(i));\n    }\n\n  public:\n\n    typedef typename Base::InnerIterator InnerIterator;\n    typedef typename Base::ReverseInnerIterator ReverseInnerIterator;\n\n    inline void setZero() { m_data.clear(); }\n\n    /** \\returns the number of non zero coefficients */\n    inline Index nonZeros() const  { return m_data.size(); }\n\n    inline void startVec(Index outer)\n    {\n      EIGEN_UNUSED_VARIABLE(outer);\n      eigen_assert(outer==0);\n    }\n\n    inline Scalar& insertBackByOuterInner(Index outer, Index inner)\n    {\n      EIGEN_UNUSED_VARIABLE(outer);\n      eigen_assert(outer==0);\n      return insertBack(inner);\n    }\n    inline Scalar& insertBack(Index i)\n    {\n      m_data.append(0, i);\n      return m_data.value(m_data.size()-1);\n    }\n    \n    Scalar& insertBackByOuterInnerUnordered(Index outer, Index inner)\n    {\n      EIGEN_UNUSED_VARIABLE(outer);\n      eigen_assert(outer==0);\n      return insertBackUnordered(inner);\n    }\n    inline Scalar& insertBackUnordered(Index i)\n    {\n      m_data.append(0, i);\n      return m_data.value(m_data.size()-1);\n    }\n\n    inline Scalar& insert(Index row, Index col)\n    {\n      eigen_assert(IsColVector ? (col==0 && row>=0 && row<m_size) : (row==0 && col>=0 && col<m_size));\n      \n      Index inner = IsColVector ? row : col;\n      Index outer = IsColVector ? col : row;\n      EIGEN_ONLY_USED_FOR_DEBUG(outer);\n      eigen_assert(outer==0);\n      return insert(inner);\n    }\n    Scalar& insert(Index i)\n    {\n      eigen_assert(i>=0 && i<m_size);\n      \n      Index startId = 0;\n      Index p = Index(m_data.size()) - 1;\n      // TODO smart realloc\n      m_data.resize(p+2,1);\n\n      while ( (p >= startId) && (m_data.index(p) > i) )\n      {\n        m_data.index(p+1) = m_data.index(p);\n        m_data.value(p+1) = m_data.value(p);\n        --p;\n      }\n      m_data.index(p+1) = convert_index(i);\n      m_data.value(p+1) = 0;\n      return m_data.value(p+1);\n    }\n\n    /**\n      */\n    inline void reserve(Index reserveSize) { m_data.reserve(reserveSize); }\n\n\n    inline void finalize() {}\n\n    /** \\copydoc SparseMatrix::prune(const Scalar&,const RealScalar&) */\n    void prune(const Scalar& reference, const RealScalar& epsilon = NumTraits<RealScalar>::dummy_precision())\n    {\n      m_data.prune(reference,epsilon);\n    }\n\n    /** Resizes the sparse vector to \\a rows x \\a cols\n      *\n      * This method is provided for compatibility with matrices.\n      * For a column vector, \\a cols must be equal to 1.\n      * For a row vector, \\a rows must be equal to 1.\n      *\n      * \\sa resize(Index)\n      */\n    void resize(Index rows, Index cols)\n    {\n      eigen_assert((IsColVector ? cols : rows)==1 && \"Outer dimension must equal 1\");\n      resize(IsColVector ? rows : cols);\n    }\n\n    /** Resizes the sparse vector to \\a newSize\n      * This method deletes all entries, thus leaving an empty sparse vector\n      *\n      * \\sa  conservativeResize(), setZero() */\n    void resize(Index newSize)\n    {\n      m_size = newSize;\n      m_data.clear();\n    }\n\n    /** Resizes the sparse vector to \\a newSize, while leaving old values untouched.\n      *\n      * If the size of the vector is decreased, then the storage of the out-of bounds coefficients is kept and reserved.\n      * Call .data().squeeze() to free extra memory.\n      *\n      * \\sa reserve(), setZero()\n      */\n    void conservativeResize(Index newSize)\n    {\n      if (newSize < m_size)\n      {\n        Index i = 0;\n        while (i<m_data.size() && m_data.index(i)<newSize) ++i;\n        m_data.resize(i);\n      }\n      m_size = newSize;\n    }\n\n    void resizeNonZeros(Index size) { m_data.resize(size); }\n\n    inline SparseVector() : m_size(0) { check_template_parameters(); resize(0); }\n\n    explicit inline SparseVector(Index size) : m_size(0) { check_template_parameters(); resize(size); }\n\n    inline SparseVector(Index rows, Index cols) : m_size(0) { check_template_parameters(); resize(rows,cols); }\n\n    template<typename OtherDerived>\n    inline SparseVector(const SparseMatrixBase<OtherDerived>& other)\n      : m_size(0)\n    {\n      #ifdef EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n        EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n      #endif\n      check_template_parameters();\n      *this = other.derived();\n    }\n\n    inline SparseVector(const SparseVector& other)\n      : Base(other), m_size(0)\n    {\n      check_template_parameters();\n      *this = other.derived();\n    }\n\n    /** Swaps the values of \\c *this and \\a other.\n      * Overloaded for performance: this version performs a \\em shallow swap by swapping pointers and attributes only.\n      * \\sa SparseMatrixBase::swap()\n      */\n    inline void swap(SparseVector& other)\n    {\n      std::swap(m_size, other.m_size);\n      m_data.swap(other.m_data);\n    }\n\n    template<int OtherOptions>\n    inline void swap(SparseMatrix<Scalar,OtherOptions,StorageIndex>& other)\n    {\n      eigen_assert(other.outerSize()==1);\n      std::swap(m_size, other.m_innerSize);\n      m_data.swap(other.m_data);\n    }\n\n    inline SparseVector& operator=(const SparseVector& other)\n    {\n      if (other.isRValue())\n      {\n        swap(other.const_cast_derived());\n      }\n      else\n      {\n        resize(other.size());\n        m_data = other.m_data;\n      }\n      return *this;\n    }\n\n    template<typename OtherDerived>\n    inline SparseVector& operator=(const SparseMatrixBase<OtherDerived>& other)\n    {\n      SparseVector tmp(other.size());\n      internal::sparse_vector_assign_selector<SparseVector,OtherDerived>::run(tmp,other.derived());\n      this->swap(tmp);\n      return *this;\n    }\n\n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    template<typename Lhs, typename Rhs>\n    inline SparseVector& operator=(const SparseSparseProduct<Lhs,Rhs>& product)\n    {\n      return Base::operator=(product);\n    }\n    #endif\n\n    friend std::ostream & operator << (std::ostream & s, const SparseVector& m)\n    {\n      for (Index i=0; i<m.nonZeros(); ++i)\n        s << \"(\" << m.m_data.value(i) << \",\" << m.m_data.index(i) << \") \";\n      s << std::endl;\n      return s;\n    }\n\n    /** Destructor */\n    inline ~SparseVector() {}\n\n    /** Overloaded for performance */\n    Scalar sum() const;\n\n  public:\n\n    /** \\internal \\deprecated use setZero() and reserve() */\n    EIGEN_DEPRECATED void startFill(Index reserve)\n    {\n      setZero();\n      m_data.reserve(reserve);\n    }\n\n    /** \\internal \\deprecated use insertBack(Index,Index) */\n    EIGEN_DEPRECATED Scalar& fill(Index r, Index c)\n    {\n      eigen_assert(r==0 || c==0);\n      return fill(IsColVector ? r : c);\n    }\n\n    /** \\internal \\deprecated use insertBack(Index) */\n    EIGEN_DEPRECATED Scalar& fill(Index i)\n    {\n      m_data.append(0, i);\n      return m_data.value(m_data.size()-1);\n    }\n\n    /** \\internal \\deprecated use insert(Index,Index) */\n    EIGEN_DEPRECATED Scalar& fillrand(Index r, Index c)\n    {\n      eigen_assert(r==0 || c==0);\n      return fillrand(IsColVector ? r : c);\n    }\n\n    /** \\internal \\deprecated use insert(Index) */\n    EIGEN_DEPRECATED Scalar& fillrand(Index i)\n    {\n      return insert(i);\n    }\n\n    /** \\internal \\deprecated use finalize() */\n    EIGEN_DEPRECATED void endFill() {}\n    \n    // These two functions were here in the 3.1 release, so let's keep them in case some code rely on them.\n    /** \\internal \\deprecated use data() */\n    EIGEN_DEPRECATED Storage& _data() { return m_data; }\n    /** \\internal \\deprecated use data() */\n    EIGEN_DEPRECATED const Storage& _data() const { return m_data; }\n    \n#   ifdef EIGEN_SPARSEVECTOR_PLUGIN\n#     include EIGEN_SPARSEVECTOR_PLUGIN\n#   endif\n\nprotected:\n  \n    static void check_template_parameters()\n    {\n      EIGEN_STATIC_ASSERT(NumTraits<StorageIndex>::IsSigned,THE_INDEX_TYPE_MUST_BE_A_SIGNED_TYPE);\n      EIGEN_STATIC_ASSERT((_Options&(ColMajor|RowMajor))==Options,INVALID_MATRIX_TEMPLATE_PARAMETERS);\n    }\n    \n    Storage m_data;\n    Index m_size;\n};\n\nnamespace internal {\n\ntemplate<typename _Scalar, int _Options, typename _Index>\nstruct evaluator<SparseVector<_Scalar,_Options,_Index> >\n  : evaluator_base<SparseVector<_Scalar,_Options,_Index> >\n{\n  typedef SparseVector<_Scalar,_Options,_Index> SparseVectorType;\n  typedef evaluator_base<SparseVectorType> Base;\n  typedef typename SparseVectorType::InnerIterator InnerIterator;\n  typedef typename SparseVectorType::ReverseInnerIterator ReverseInnerIterator;\n  \n  enum {\n    CoeffReadCost = NumTraits<_Scalar>::ReadCost,\n    Flags = SparseVectorType::Flags\n  };\n\n  evaluator() : Base() {}\n  \n  explicit evaluator(const SparseVectorType &mat) : m_matrix(&mat)\n  {\n    EIGEN_INTERNAL_CHECK_COST_VALUE(CoeffReadCost);\n  }\n  \n  inline Index nonZerosEstimate() const {\n    return m_matrix->nonZeros();\n  }\n  \n  operator SparseVectorType&() { return m_matrix->const_cast_derived(); }\n  operator const SparseVectorType&() const { return *m_matrix; }\n  \n  const SparseVectorType *m_matrix;\n};\n\ntemplate< typename Dest, typename Src>\nstruct sparse_vector_assign_selector<Dest,Src,SVA_Inner> {\n  static void run(Dest& dst, const Src& src) {\n    eigen_internal_assert(src.innerSize()==src.size());\n    typedef internal::evaluator<Src> SrcEvaluatorType;\n    SrcEvaluatorType srcEval(src);\n    for(typename SrcEvaluatorType::InnerIterator it(srcEval, 0); it; ++it)\n      dst.insert(it.index()) = it.value();\n  }\n};\n\ntemplate< typename Dest, typename Src>\nstruct sparse_vector_assign_selector<Dest,Src,SVA_Outer> {\n  static void run(Dest& dst, const Src& src) {\n    eigen_internal_assert(src.outerSize()==src.size());\n    typedef internal::evaluator<Src> SrcEvaluatorType;\n    SrcEvaluatorType srcEval(src);\n    for(Index i=0; i<src.size(); ++i)\n    {\n      typename SrcEvaluatorType::InnerIterator it(srcEval, i);\n      if(it)\n        dst.insert(i) = it.value();\n    }\n  }\n};\n\ntemplate< typename Dest, typename Src>\nstruct sparse_vector_assign_selector<Dest,Src,SVA_RuntimeSwitch> {\n  static void run(Dest& dst, const Src& src) {\n    if(src.outerSize()==1)  sparse_vector_assign_selector<Dest,Src,SVA_Inner>::run(dst, src);\n    else                    sparse_vector_assign_selector<Dest,Src,SVA_Outer>::run(dst, src);\n  }\n};\n\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSEVECTOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/SparseView.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010 Daniel Lowengrub <lowdanie@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEVIEW_H\n#define EIGEN_SPARSEVIEW_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate<typename MatrixType>\nstruct traits<SparseView<MatrixType> > : traits<MatrixType>\n{\n  typedef typename MatrixType::StorageIndex StorageIndex;\n  typedef Sparse StorageKind;\n  enum {\n    Flags = int(traits<MatrixType>::Flags) & (RowMajorBit)\n  };\n};\n\n} // end namespace internal\n\n/** \\ingroup SparseCore_Module\n  * \\class SparseView\n  *\n  * \\brief Expression of a dense or sparse matrix with zero or too small values removed\n  *\n  * \\tparam MatrixType the type of the object of which we are removing the small entries\n  *\n  * This class represents an expression of a given dense or sparse matrix with\n  * entries smaller than \\c reference * \\c epsilon are removed.\n  * It is the return type of MatrixBase::sparseView() and SparseMatrixBase::pruned()\n  * and most of the time this is the only way it is used.\n  *\n  * \\sa MatrixBase::sparseView(), SparseMatrixBase::pruned()\n  */\ntemplate<typename MatrixType>\nclass SparseView : public SparseMatrixBase<SparseView<MatrixType> >\n{\n  typedef typename MatrixType::Nested MatrixTypeNested;\n  typedef typename internal::remove_all<MatrixTypeNested>::type _MatrixTypeNested;\n  typedef SparseMatrixBase<SparseView > Base;\npublic:\n  EIGEN_SPARSE_PUBLIC_INTERFACE(SparseView)\n  typedef typename internal::remove_all<MatrixType>::type NestedExpression;\n\n  explicit SparseView(const MatrixType& mat, const Scalar& reference = Scalar(0),\n                      const RealScalar &epsilon = NumTraits<Scalar>::dummy_precision())\n    : m_matrix(mat), m_reference(reference), m_epsilon(epsilon) {}\n\n  inline Index rows() const { return m_matrix.rows(); }\n  inline Index cols() const { return m_matrix.cols(); }\n\n  inline Index innerSize() const { return m_matrix.innerSize(); }\n  inline Index outerSize() const { return m_matrix.outerSize(); }\n  \n  /** \\returns the nested expression */\n  const typename internal::remove_all<MatrixTypeNested>::type&\n  nestedExpression() const { return m_matrix; }\n  \n  Scalar reference() const { return m_reference; }\n  RealScalar epsilon() const { return m_epsilon; }\n  \nprotected:\n  MatrixTypeNested m_matrix;\n  Scalar m_reference;\n  RealScalar m_epsilon;\n};\n\nnamespace internal {\n\n// TODO find a way to unify the two following variants\n// This is tricky because implementing an inner iterator on top of an IndexBased evaluator is\n// not easy because the evaluators do not expose the sizes of the underlying expression.\n  \ntemplate<typename ArgType>\nstruct unary_evaluator<SparseView<ArgType>, IteratorBased>\n  : public evaluator_base<SparseView<ArgType> >\n{\n    typedef typename evaluator<ArgType>::InnerIterator EvalIterator;\n  public:\n    typedef SparseView<ArgType> XprType;\n    \n    class InnerIterator : public EvalIterator\n    {\n      protected:\n        typedef typename XprType::Scalar Scalar;\n      public:\n\n        EIGEN_STRONG_INLINE InnerIterator(const unary_evaluator& sve, Index outer)\n          : EvalIterator(sve.m_argImpl,outer), m_view(sve.m_view)\n        {\n          incrementToNonZero();\n        }\n\n        EIGEN_STRONG_INLINE InnerIterator& operator++()\n        {\n          EvalIterator::operator++();\n          incrementToNonZero();\n          return *this;\n        }\n\n        using EvalIterator::value;\n\n      protected:\n        const XprType &m_view;\n\n      private:\n        void incrementToNonZero()\n        {\n          while((bool(*this)) && internal::isMuchSmallerThan(value(), m_view.reference(), m_view.epsilon()))\n          {\n            EvalIterator::operator++();\n          }\n        }\n    };\n    \n    enum {\n      CoeffReadCost = evaluator<ArgType>::CoeffReadCost,\n      Flags = XprType::Flags\n    };\n    \n    explicit unary_evaluator(const XprType& xpr) : m_argImpl(xpr.nestedExpression()), m_view(xpr) {}\n\n  protected:\n    evaluator<ArgType> m_argImpl;\n    const XprType &m_view;\n};\n\ntemplate<typename ArgType>\nstruct unary_evaluator<SparseView<ArgType>, IndexBased>\n  : public evaluator_base<SparseView<ArgType> >\n{\n  public:\n    typedef SparseView<ArgType> XprType;\n  protected:\n    enum { IsRowMajor = (XprType::Flags&RowMajorBit)==RowMajorBit };\n    typedef typename XprType::Scalar Scalar;\n    typedef typename XprType::StorageIndex StorageIndex;\n  public:\n    \n    class InnerIterator\n    {\n      public:\n\n        EIGEN_STRONG_INLINE InnerIterator(const unary_evaluator& sve, Index outer)\n          : m_sve(sve), m_inner(0), m_outer(outer), m_end(sve.m_view.innerSize())\n        {\n          incrementToNonZero();\n        }\n\n        EIGEN_STRONG_INLINE InnerIterator& operator++()\n        {\n          m_inner++;\n          incrementToNonZero();\n          return *this;\n        }\n\n        EIGEN_STRONG_INLINE Scalar value() const\n        {\n          return (IsRowMajor) ? m_sve.m_argImpl.coeff(m_outer, m_inner)\n                              : m_sve.m_argImpl.coeff(m_inner, m_outer);\n        }\n\n        EIGEN_STRONG_INLINE StorageIndex index() const { return m_inner; }\n        inline Index row() const { return IsRowMajor ? m_outer : index(); }\n        inline Index col() const { return IsRowMajor ? index() : m_outer; }\n\n        EIGEN_STRONG_INLINE operator bool() const { return m_inner < m_end && m_inner>=0; }\n\n      protected:\n        const unary_evaluator &m_sve;\n        Index m_inner;\n        const Index m_outer;\n        const Index m_end;\n\n      private:\n        void incrementToNonZero()\n        {\n          while((bool(*this)) && internal::isMuchSmallerThan(value(), m_sve.m_view.reference(), m_sve.m_view.epsilon()))\n          {\n            m_inner++;\n          }\n        }\n    };\n    \n    enum {\n      CoeffReadCost = evaluator<ArgType>::CoeffReadCost,\n      Flags = XprType::Flags\n    };\n    \n    explicit unary_evaluator(const XprType& xpr) : m_argImpl(xpr.nestedExpression()), m_view(xpr) {}\n\n  protected:\n    evaluator<ArgType> m_argImpl;\n    const XprType &m_view;\n};\n\n} // end namespace internal\n\n/** \\ingroup SparseCore_Module\n  *\n  * \\returns a sparse expression of the dense expression \\c *this with values smaller than\n  * \\a reference * \\a epsilon removed.\n  *\n  * This method is typically used when prototyping to convert a quickly assembled dense Matrix \\c D to a SparseMatrix \\c S:\n  * \\code\n  * MatrixXd D(n,m);\n  * SparseMatrix<double> S;\n  * S = D.sparseView();             // suppress numerical zeros (exact)\n  * S = D.sparseView(reference);\n  * S = D.sparseView(reference,epsilon);\n  * \\endcode\n  * where \\a reference is a meaningful non zero reference value,\n  * and \\a epsilon is a tolerance factor defaulting to NumTraits<Scalar>::dummy_precision().\n  *\n  * \\sa SparseMatrixBase::pruned(), class SparseView */\ntemplate<typename Derived>\nconst SparseView<Derived> MatrixBase<Derived>::sparseView(const Scalar& reference,\n                                                          const typename NumTraits<Scalar>::Real& epsilon) const\n{\n  return SparseView<Derived>(derived(), reference, epsilon);\n}\n\n/** \\returns an expression of \\c *this with values smaller than\n  * \\a reference * \\a epsilon removed.\n  *\n  * This method is typically used in conjunction with the product of two sparse matrices\n  * to automatically prune the smallest values as follows:\n  * \\code\n  * C = (A*B).pruned();             // suppress numerical zeros (exact)\n  * C = (A*B).pruned(ref);\n  * C = (A*B).pruned(ref,epsilon);\n  * \\endcode\n  * where \\c ref is a meaningful non zero reference value.\n  * */\ntemplate<typename Derived>\nconst SparseView<Derived>\nSparseMatrixBase<Derived>::pruned(const Scalar& reference,\n                                  const RealScalar& epsilon) const\n{\n  return SparseView<Derived>(derived(), reference, epsilon);\n}\n\n} // end namespace Eigen\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseCore/TriangularSolver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSETRIANGULARSOLVER_H\n#define EIGEN_SPARSETRIANGULARSOLVER_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate<typename Lhs, typename Rhs, int Mode,\n  int UpLo = (Mode & Lower)\n           ? Lower\n           : (Mode & Upper)\n           ? Upper\n           : -1,\n  int StorageOrder = int(traits<Lhs>::Flags) & RowMajorBit>\nstruct sparse_solve_triangular_selector;\n\n// forward substitution, row-major\ntemplate<typename Lhs, typename Rhs, int Mode>\nstruct sparse_solve_triangular_selector<Lhs,Rhs,Mode,Lower,RowMajor>\n{\n  typedef typename Rhs::Scalar Scalar;\n  typedef evaluator<Lhs> LhsEval;\n  typedef typename evaluator<Lhs>::InnerIterator LhsIterator;\n  static void run(const Lhs& lhs, Rhs& other)\n  {\n    LhsEval lhsEval(lhs);\n    for(Index col=0 ; col<other.cols() ; ++col)\n    {\n      for(Index i=0; i<lhs.rows(); ++i)\n      {\n        Scalar tmp = other.coeff(i,col);\n        Scalar lastVal(0);\n        Index lastIndex = 0;\n        for(LhsIterator it(lhsEval, i); it; ++it)\n        {\n          lastVal = it.value();\n          lastIndex = it.index();\n          if(lastIndex==i)\n            break;\n          tmp -= lastVal * other.coeff(lastIndex,col);\n        }\n        if (Mode & UnitDiag)\n          other.coeffRef(i,col) = tmp;\n        else\n        {\n          eigen_assert(lastIndex==i);\n          other.coeffRef(i,col) = tmp/lastVal;\n        }\n      }\n    }\n  }\n};\n\n// backward substitution, row-major\ntemplate<typename Lhs, typename Rhs, int Mode>\nstruct sparse_solve_triangular_selector<Lhs,Rhs,Mode,Upper,RowMajor>\n{\n  typedef typename Rhs::Scalar Scalar;\n  typedef evaluator<Lhs> LhsEval;\n  typedef typename evaluator<Lhs>::InnerIterator LhsIterator;\n  static void run(const Lhs& lhs, Rhs& other)\n  {\n    LhsEval lhsEval(lhs);\n    for(Index col=0 ; col<other.cols() ; ++col)\n    {\n      for(Index i=lhs.rows()-1 ; i>=0 ; --i)\n      {\n        Scalar tmp = other.coeff(i,col);\n        Scalar l_ii(0);\n        LhsIterator it(lhsEval, i);\n        while(it && it.index()<i)\n          ++it;\n        if(!(Mode & UnitDiag))\n        {\n          eigen_assert(it && it.index()==i);\n          l_ii = it.value();\n          ++it;\n        }\n        else if (it && it.index() == i)\n          ++it;\n        for(; it; ++it)\n        {\n          tmp -= it.value() * other.coeff(it.index(),col);\n        }\n\n        if (Mode & UnitDiag)  other.coeffRef(i,col) = tmp;\n        else                  other.coeffRef(i,col) = tmp/l_ii;\n      }\n    }\n  }\n};\n\n// forward substitution, col-major\ntemplate<typename Lhs, typename Rhs, int Mode>\nstruct sparse_solve_triangular_selector<Lhs,Rhs,Mode,Lower,ColMajor>\n{\n  typedef typename Rhs::Scalar Scalar;\n  typedef evaluator<Lhs> LhsEval;\n  typedef typename evaluator<Lhs>::InnerIterator LhsIterator;\n  static void run(const Lhs& lhs, Rhs& other)\n  {\n    LhsEval lhsEval(lhs);\n    for(Index col=0 ; col<other.cols() ; ++col)\n    {\n      for(Index i=0; i<lhs.cols(); ++i)\n      {\n        Scalar& tmp = other.coeffRef(i,col);\n        if (tmp!=Scalar(0)) // optimization when other is actually sparse\n        {\n          LhsIterator it(lhsEval, i);\n          while(it && it.index()<i)\n            ++it;\n          if(!(Mode & UnitDiag))\n          {\n            eigen_assert(it && it.index()==i);\n            tmp /= it.value();\n          }\n          if (it && it.index()==i)\n            ++it;\n          for(; it; ++it)\n            other.coeffRef(it.index(), col) -= tmp * it.value();\n        }\n      }\n    }\n  }\n};\n\n// backward substitution, col-major\ntemplate<typename Lhs, typename Rhs, int Mode>\nstruct sparse_solve_triangular_selector<Lhs,Rhs,Mode,Upper,ColMajor>\n{\n  typedef typename Rhs::Scalar Scalar;\n  typedef evaluator<Lhs> LhsEval;\n  typedef typename evaluator<Lhs>::InnerIterator LhsIterator;\n  static void run(const Lhs& lhs, Rhs& other)\n  {\n    LhsEval lhsEval(lhs);\n    for(Index col=0 ; col<other.cols() ; ++col)\n    {\n      for(Index i=lhs.cols()-1; i>=0; --i)\n      {\n        Scalar& tmp = other.coeffRef(i,col);\n        if (tmp!=Scalar(0)) // optimization when other is actually sparse\n        {\n          if(!(Mode & UnitDiag))\n          {\n            // TODO replace this by a binary search. make sure the binary search is safe for partially sorted elements\n            LhsIterator it(lhsEval, i);\n            while(it && it.index()!=i)\n              ++it;\n            eigen_assert(it && it.index()==i);\n            other.coeffRef(i,col) /= it.value();\n          }\n          LhsIterator it(lhsEval, i);\n          for(; it && it.index()<i; ++it)\n            other.coeffRef(it.index(), col) -= tmp * it.value();\n        }\n      }\n    }\n  }\n};\n\n} // end namespace internal\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n\ntemplate<typename ExpressionType,unsigned int Mode>\ntemplate<typename OtherDerived>\nvoid TriangularViewImpl<ExpressionType,Mode,Sparse>::solveInPlace(MatrixBase<OtherDerived>& other) const\n{\n  eigen_assert(derived().cols() == derived().rows() && derived().cols() == other.rows());\n  eigen_assert((!(Mode & ZeroDiag)) && bool(Mode & (Upper|Lower)));\n\n  enum { copy = internal::traits<OtherDerived>::Flags & RowMajorBit };\n\n  typedef typename internal::conditional<copy,\n    typename internal::plain_matrix_type_column_major<OtherDerived>::type, OtherDerived&>::type OtherCopy;\n  OtherCopy otherCopy(other.derived());\n\n  internal::sparse_solve_triangular_selector<ExpressionType, typename internal::remove_reference<OtherCopy>::type, Mode>::run(derived().nestedExpression(), otherCopy);\n\n  if (copy)\n    other = otherCopy;\n}\n#endif\n\n// pure sparse path\n\nnamespace internal {\n\ntemplate<typename Lhs, typename Rhs, int Mode,\n  int UpLo = (Mode & Lower)\n           ? Lower\n           : (Mode & Upper)\n           ? Upper\n           : -1,\n  int StorageOrder = int(Lhs::Flags) & (RowMajorBit)>\nstruct sparse_solve_triangular_sparse_selector;\n\n// forward substitution, col-major\ntemplate<typename Lhs, typename Rhs, int Mode, int UpLo>\nstruct sparse_solve_triangular_sparse_selector<Lhs,Rhs,Mode,UpLo,ColMajor>\n{\n  typedef typename Rhs::Scalar Scalar;\n  typedef typename promote_index_type<typename traits<Lhs>::StorageIndex,\n                                      typename traits<Rhs>::StorageIndex>::type StorageIndex;\n  static void run(const Lhs& lhs, Rhs& other)\n  {\n    const bool IsLower = (UpLo==Lower);\n    AmbiVector<Scalar,StorageIndex> tempVector(other.rows()*2);\n    tempVector.setBounds(0,other.rows());\n\n    Rhs res(other.rows(), other.cols());\n    res.reserve(other.nonZeros());\n\n    for(Index col=0 ; col<other.cols() ; ++col)\n    {\n      // FIXME estimate number of non zeros\n      tempVector.init(.99/*float(other.col(col).nonZeros())/float(other.rows())*/);\n      tempVector.setZero();\n      tempVector.restart();\n      for (typename Rhs::InnerIterator rhsIt(other, col); rhsIt; ++rhsIt)\n      {\n        tempVector.coeffRef(rhsIt.index()) = rhsIt.value();\n      }\n\n      for(Index i=IsLower?0:lhs.cols()-1;\n          IsLower?i<lhs.cols():i>=0;\n          i+=IsLower?1:-1)\n      {\n        tempVector.restart();\n        Scalar& ci = tempVector.coeffRef(i);\n        if (ci!=Scalar(0))\n        {\n          // find\n          typename Lhs::InnerIterator it(lhs, i);\n          if(!(Mode & UnitDiag))\n          {\n            if (IsLower)\n            {\n              eigen_assert(it.index()==i);\n              ci /= it.value();\n            }\n            else\n              ci /= lhs.coeff(i,i);\n          }\n          tempVector.restart();\n          if (IsLower)\n          {\n            if (it.index()==i)\n              ++it;\n            for(; it; ++it)\n              tempVector.coeffRef(it.index()) -= ci * it.value();\n          }\n          else\n          {\n            for(; it && it.index()<i; ++it)\n              tempVector.coeffRef(it.index()) -= ci * it.value();\n          }\n        }\n      }\n\n\n      Index count = 0;\n      // FIXME compute a reference value to filter zeros\n      for (typename AmbiVector<Scalar,StorageIndex>::Iterator it(tempVector/*,1e-12*/); it; ++it)\n      {\n        ++ count;\n//         std::cerr << \"fill \" << it.index() << \", \" << col << \"\\n\";\n//         std::cout << it.value() << \"  \";\n        // FIXME use insertBack\n        res.insert(it.index(), col) = it.value();\n      }\n//       std::cout << \"tempVector.nonZeros() == \" << int(count) << \" / \" << (other.rows()) << \"\\n\";\n    }\n    res.finalize();\n    other = res.markAsRValue();\n  }\n};\n\n} // end namespace internal\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename ExpressionType,unsigned int Mode>\ntemplate<typename OtherDerived>\nvoid TriangularViewImpl<ExpressionType,Mode,Sparse>::solveInPlace(SparseMatrixBase<OtherDerived>& other) const\n{\n  eigen_assert(derived().cols() == derived().rows() && derived().cols() == other.rows());\n  eigen_assert( (!(Mode & ZeroDiag)) && bool(Mode & (Upper|Lower)));\n\n//   enum { copy = internal::traits<OtherDerived>::Flags & RowMajorBit };\n\n//   typedef typename internal::conditional<copy,\n//     typename internal::plain_matrix_type_column_major<OtherDerived>::type, OtherDerived&>::type OtherCopy;\n//   OtherCopy otherCopy(other.derived());\n\n  internal::sparse_solve_triangular_sparse_selector<ExpressionType, OtherDerived, Mode>::run(derived().nestedExpression(), other.derived());\n\n//   if (copy)\n//     other = otherCopy;\n}\n#endif\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSETRIANGULARSOLVER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseLU/SparseLU.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2012-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#ifndef EIGEN_SPARSE_LU_H\n#define EIGEN_SPARSE_LU_H\n\nnamespace Eigen {\n\ntemplate <typename _MatrixType, typename _OrderingType = COLAMDOrdering<typename _MatrixType::StorageIndex> > class SparseLU;\ntemplate <typename MappedSparseMatrixType> struct SparseLUMatrixLReturnType;\ntemplate <typename MatrixLType, typename MatrixUType> struct SparseLUMatrixUReturnType;\n\ntemplate <bool Conjugate,class SparseLUType>\nclass SparseLUTransposeView : public SparseSolverBase<SparseLUTransposeView<Conjugate,SparseLUType> >\n{\nprotected:\n  typedef SparseSolverBase<SparseLUTransposeView<Conjugate,SparseLUType> > APIBase;\n  using APIBase::m_isInitialized;\npublic:\n  typedef typename SparseLUType::Scalar Scalar;\n  typedef typename SparseLUType::StorageIndex StorageIndex;\n  typedef typename SparseLUType::MatrixType MatrixType;\n  typedef typename SparseLUType::OrderingType OrderingType;\n\n  enum {\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n    MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n  };\n\n  SparseLUTransposeView() : m_sparseLU(NULL) {}\n  SparseLUTransposeView(const SparseLUTransposeView& view) {\n    this->m_sparseLU = view.m_sparseLU;\n  }\n  void setIsInitialized(const bool isInitialized) {this->m_isInitialized = isInitialized;}\n  void setSparseLU(SparseLUType* sparseLU) {m_sparseLU = sparseLU;}\n  using APIBase::_solve_impl;\n  template<typename Rhs, typename Dest>\n  bool _solve_impl(const MatrixBase<Rhs> &B, MatrixBase<Dest> &X_base) const\n  {\n    Dest& X(X_base.derived());\n    eigen_assert(m_sparseLU->info() == Success && \"The matrix should be factorized first\");\n    EIGEN_STATIC_ASSERT((Dest::Flags&RowMajorBit)==0,\n                        THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES);\n\n\n    // this ugly const_cast_derived() helps to detect aliasing when applying the permutations\n    for(Index j = 0; j < B.cols(); ++j){\n      X.col(j) = m_sparseLU->colsPermutation() * B.const_cast_derived().col(j);\n    }\n    //Forward substitution with transposed or adjoint of U\n    m_sparseLU->matrixU().template solveTransposedInPlace<Conjugate>(X);\n\n    //Backward substitution with transposed or adjoint of L\n    m_sparseLU->matrixL().template solveTransposedInPlace<Conjugate>(X);\n\n    // Permute back the solution\n    for (Index j = 0; j < B.cols(); ++j)\n      X.col(j) = m_sparseLU->rowsPermutation().transpose() * X.col(j);\n    return true;\n  }\n  inline Index rows() const { return m_sparseLU->rows(); }\n  inline Index cols() const { return m_sparseLU->cols(); }\n\nprivate:\n  SparseLUType *m_sparseLU;\n  SparseLUTransposeView& operator=(const SparseLUTransposeView&);\n};\n\n\n/** \\ingroup SparseLU_Module\n  * \\class SparseLU\n  * \n  * \\brief Sparse supernodal LU factorization for general matrices\n  * \n  * This class implements the supernodal LU factorization for general matrices.\n  * It uses the main techniques from the sequential SuperLU package \n  * (http://crd-legacy.lbl.gov/~xiaoye/SuperLU/). It handles transparently real \n  * and complex arithmetic with single and double precision, depending on the \n  * scalar type of your input matrix. \n  * The code has been optimized to provide BLAS-3 operations during supernode-panel updates. \n  * It benefits directly from the built-in high-performant Eigen BLAS routines. \n  * Moreover, when the size of a supernode is very small, the BLAS calls are avoided to \n  * enable a better optimization from the compiler. For best performance, \n  * you should compile it with NDEBUG flag to avoid the numerous bounds checking on vectors. \n  * \n  * An important parameter of this class is the ordering method. It is used to reorder the columns \n  * (and eventually the rows) of the matrix to reduce the number of new elements that are created during \n  * numerical factorization. The cheapest method available is COLAMD. \n  * See  \\link OrderingMethods_Module the OrderingMethods module \\endlink for the list of \n  * built-in and external ordering methods. \n  *\n  * Simple example with key steps \n  * \\code\n  * VectorXd x(n), b(n);\n  * SparseMatrix<double> A;\n  * SparseLU<SparseMatrix<double>, COLAMDOrdering<int> >   solver;\n  * // fill A and b;\n  * // Compute the ordering permutation vector from the structural pattern of A\n  * solver.analyzePattern(A); \n  * // Compute the numerical factorization \n  * solver.factorize(A); \n  * //Use the factors to solve the linear system \n  * x = solver.solve(b); \n  * \\endcode\n  * \n  * \\warning The input matrix A should be in a \\b compressed and \\b column-major form.\n  * Otherwise an expensive copy will be made. You can call the inexpensive makeCompressed() to get a compressed matrix.\n  * \n  * \\note Unlike the initial SuperLU implementation, there is no step to equilibrate the matrix. \n  * For badly scaled matrices, this step can be useful to reduce the pivoting during factorization. \n  * If this is the case for your matrices, you can try the basic scaling method at\n  *  \"unsupported/Eigen/src/IterativeSolvers/Scaling.h\"\n  * \n  * \\tparam _MatrixType The type of the sparse matrix. It must be a column-major SparseMatrix<>\n  * \\tparam _OrderingType The ordering method to use, either AMD, COLAMD or METIS. Default is COLMAD\n  *\n  * \\implsparsesolverconcept\n  * \n  * \\sa \\ref TutorialSparseSolverConcept\n  * \\sa \\ref OrderingMethods_Module\n  */\ntemplate <typename _MatrixType, typename _OrderingType>\nclass SparseLU : public SparseSolverBase<SparseLU<_MatrixType,_OrderingType> >, public internal::SparseLUImpl<typename _MatrixType::Scalar, typename _MatrixType::StorageIndex>\n{\n  protected:\n    typedef SparseSolverBase<SparseLU<_MatrixType,_OrderingType> > APIBase;\n    using APIBase::m_isInitialized;\n  public:\n    using APIBase::_solve_impl;\n    \n    typedef _MatrixType MatrixType; \n    typedef _OrderingType OrderingType;\n    typedef typename MatrixType::Scalar Scalar; \n    typedef typename MatrixType::RealScalar RealScalar; \n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> NCMatrix;\n    typedef internal::MappedSuperNodalMatrix<Scalar, StorageIndex> SCMatrix;\n    typedef Matrix<Scalar,Dynamic,1> ScalarVector;\n    typedef Matrix<StorageIndex,Dynamic,1> IndexVector;\n    typedef PermutationMatrix<Dynamic, Dynamic, StorageIndex> PermutationType;\n    typedef internal::SparseLUImpl<Scalar, StorageIndex> Base;\n\n    enum {\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n    \n  public:\n\n    SparseLU():m_lastError(\"\"),m_Ustore(0,0,0,0,0,0),m_symmetricmode(false),m_diagpivotthresh(1.0),m_detPermR(1)\n    {\n      initperfvalues(); \n    }\n    explicit SparseLU(const MatrixType& matrix)\n      : m_lastError(\"\"),m_Ustore(0,0,0,0,0,0),m_symmetricmode(false),m_diagpivotthresh(1.0),m_detPermR(1)\n    {\n      initperfvalues(); \n      compute(matrix);\n    }\n    \n    ~SparseLU()\n    {\n      // Free all explicit dynamic pointers \n    }\n    \n    void analyzePattern (const MatrixType& matrix);\n    void factorize (const MatrixType& matrix);\n    void simplicialfactorize(const MatrixType& matrix);\n    \n    /**\n      * Compute the symbolic and numeric factorization of the input sparse matrix.\n      * The input matrix should be in column-major storage. \n      */\n    void compute (const MatrixType& matrix)\n    {\n      // Analyze \n      analyzePattern(matrix); \n      //Factorize\n      factorize(matrix);\n    } \n\n    /** \\returns an expression of the transposed of the factored matrix.\n      *\n      * A typical usage is to solve for the transposed problem A^T x = b:\n      * \\code\n      * solver.compute(A);\n      * x = solver.transpose().solve(b);\n      * \\endcode\n      *\n      * \\sa adjoint(), solve()\n      */\n    const SparseLUTransposeView<false,SparseLU<_MatrixType,_OrderingType> > transpose()\n    {\n      SparseLUTransposeView<false,  SparseLU<_MatrixType,_OrderingType> > transposeView;\n      transposeView.setSparseLU(this);\n      transposeView.setIsInitialized(this->m_isInitialized);\n      return transposeView;\n    }\n\n\n    /** \\returns an expression of the adjoint of the factored matrix\n      *\n      * A typical usage is to solve for the adjoint problem A' x = b:\n      * \\code\n      * solver.compute(A);\n      * x = solver.adjoint().solve(b);\n      * \\endcode\n      *\n      * For real scalar types, this function is equivalent to transpose().\n      *\n      * \\sa transpose(), solve()\n      */\n    const SparseLUTransposeView<true, SparseLU<_MatrixType,_OrderingType> > adjoint()\n    {\n      SparseLUTransposeView<true,  SparseLU<_MatrixType,_OrderingType> > adjointView;\n      adjointView.setSparseLU(this);\n      adjointView.setIsInitialized(this->m_isInitialized);\n      return adjointView;\n    }\n    \n    inline Index rows() const { return m_mat.rows(); }\n    inline Index cols() const { return m_mat.cols(); }\n    /** Indicate that the pattern of the input matrix is symmetric */\n    void isSymmetric(bool sym)\n    {\n      m_symmetricmode = sym;\n    }\n    \n    /** \\returns an expression of the matrix L, internally stored as supernodes\n      * The only operation available with this expression is the triangular solve\n      * \\code\n      * y = b; matrixL().solveInPlace(y);\n      * \\endcode\n      */\n    SparseLUMatrixLReturnType<SCMatrix> matrixL() const\n    {\n      return SparseLUMatrixLReturnType<SCMatrix>(m_Lstore);\n    }\n    /** \\returns an expression of the matrix U,\n      * The only operation available with this expression is the triangular solve\n      * \\code\n      * y = b; matrixU().solveInPlace(y);\n      * \\endcode\n      */\n    SparseLUMatrixUReturnType<SCMatrix,MappedSparseMatrix<Scalar,ColMajor,StorageIndex> > matrixU() const\n    {\n      return SparseLUMatrixUReturnType<SCMatrix, MappedSparseMatrix<Scalar,ColMajor,StorageIndex> >(m_Lstore, m_Ustore);\n    }\n\n    /**\n      * \\returns a reference to the row matrix permutation \\f$ P_r \\f$ such that \\f$P_r A P_c^T = L U\\f$\n      * \\sa colsPermutation()\n      */\n    inline const PermutationType& rowsPermutation() const\n    {\n      return m_perm_r;\n    }\n    /**\n      * \\returns a reference to the column matrix permutation\\f$ P_c^T \\f$ such that \\f$P_r A P_c^T = L U\\f$\n      * \\sa rowsPermutation()\n      */\n    inline const PermutationType& colsPermutation() const\n    {\n      return m_perm_c;\n    }\n    /** Set the threshold used for a diagonal entry to be an acceptable pivot. */\n    void setPivotThreshold(const RealScalar& thresh)\n    {\n      m_diagpivotthresh = thresh; \n    }\n\n#ifdef EIGEN_PARSED_BY_DOXYGEN\n    /** \\returns the solution X of \\f$ A X = B \\f$ using the current decomposition of A.\n      *\n      * \\warning the destination matrix X in X = this->solve(B) must be colmun-major.\n      *\n      * \\sa compute()\n      */\n    template<typename Rhs>\n    inline const Solve<SparseLU, Rhs> solve(const MatrixBase<Rhs>& B) const;\n#endif // EIGEN_PARSED_BY_DOXYGEN\n    \n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the LU factorization reports a problem, zero diagonal for instance\n      *          \\c InvalidInput if the input matrix is invalid\n      *\n      * \\sa iparm()          \n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_info;\n    }\n    \n    /**\n      * \\returns A string describing the type of error\n      */\n    std::string lastErrorMessage() const\n    {\n      return m_lastError; \n    }\n\n    template<typename Rhs, typename Dest>\n    bool _solve_impl(const MatrixBase<Rhs> &B, MatrixBase<Dest> &X_base) const\n    {\n      Dest& X(X_base.derived());\n      eigen_assert(m_factorizationIsOk && \"The matrix should be factorized first\");\n      EIGEN_STATIC_ASSERT((Dest::Flags&RowMajorBit)==0,\n                        THIS_METHOD_IS_ONLY_FOR_COLUMN_MAJOR_MATRICES);\n      \n      // Permute the right hand side to form X = Pr*B\n      // on return, X is overwritten by the computed solution\n      X.resize(B.rows(),B.cols());\n\n      // this ugly const_cast_derived() helps to detect aliasing when applying the permutations\n      for(Index j = 0; j < B.cols(); ++j)\n        X.col(j) = rowsPermutation() * B.const_cast_derived().col(j);\n      \n      //Forward substitution with L\n      this->matrixL().solveInPlace(X);\n      this->matrixU().solveInPlace(X);\n      \n      // Permute back the solution \n      for (Index j = 0; j < B.cols(); ++j)\n        X.col(j) = colsPermutation().inverse() * X.col(j);\n      \n      return true; \n    }\n    \n    /**\n      * \\returns the absolute value of the determinant of the matrix of which\n      * *this is the QR decomposition.\n      *\n      * \\warning a determinant can be very big or small, so for matrices\n      * of large enough dimension, there is a risk of overflow/underflow.\n      * One way to work around that is to use logAbsDeterminant() instead.\n      *\n      * \\sa logAbsDeterminant(), signDeterminant()\n      */\n    Scalar absDeterminant()\n    {\n      using std::abs;\n      eigen_assert(m_factorizationIsOk && \"The matrix should be factorized first.\");\n      // Initialize with the determinant of the row matrix\n      Scalar det = Scalar(1.);\n      // Note that the diagonal blocks of U are stored in supernodes,\n      // which are available in the  L part :)\n      for (Index j = 0; j < this->cols(); ++j)\n      {\n        for (typename SCMatrix::InnerIterator it(m_Lstore, j); it; ++it)\n        {\n          if(it.index() == j)\n          {\n            det *= abs(it.value());\n            break;\n          }\n        }\n      }\n      return det;\n    }\n\n    /** \\returns the natural log of the absolute value of the determinant of the matrix\n      * of which **this is the QR decomposition\n      *\n      * \\note This method is useful to work around the risk of overflow/underflow that's\n      * inherent to the determinant computation.\n      *\n      * \\sa absDeterminant(), signDeterminant()\n      */\n    Scalar logAbsDeterminant() const\n    {\n      using std::log;\n      using std::abs;\n\n      eigen_assert(m_factorizationIsOk && \"The matrix should be factorized first.\");\n      Scalar det = Scalar(0.);\n      for (Index j = 0; j < this->cols(); ++j)\n      {\n        for (typename SCMatrix::InnerIterator it(m_Lstore, j); it; ++it)\n        {\n          if(it.row() < j) continue;\n          if(it.row() == j)\n          {\n            det += log(abs(it.value()));\n            break;\n          }\n        }\n      }\n      return det;\n    }\n\n    /** \\returns A number representing the sign of the determinant\n      *\n      * \\sa absDeterminant(), logAbsDeterminant()\n      */\n    Scalar signDeterminant()\n    {\n      eigen_assert(m_factorizationIsOk && \"The matrix should be factorized first.\");\n      // Initialize with the determinant of the row matrix\n      Index det = 1;\n      // Note that the diagonal blocks of U are stored in supernodes,\n      // which are available in the  L part :)\n      for (Index j = 0; j < this->cols(); ++j)\n      {\n        for (typename SCMatrix::InnerIterator it(m_Lstore, j); it; ++it)\n        {\n          if(it.index() == j)\n          {\n            if(it.value()<0)\n              det = -det;\n            else if(it.value()==0)\n              return 0;\n            break;\n          }\n        }\n      }\n      return det * m_detPermR * m_detPermC;\n    }\n    \n    /** \\returns The determinant of the matrix.\n      *\n      * \\sa absDeterminant(), logAbsDeterminant()\n      */\n    Scalar determinant()\n    {\n      eigen_assert(m_factorizationIsOk && \"The matrix should be factorized first.\");\n      // Initialize with the determinant of the row matrix\n      Scalar det = Scalar(1.);\n      // Note that the diagonal blocks of U are stored in supernodes,\n      // which are available in the  L part :)\n      for (Index j = 0; j < this->cols(); ++j)\n      {\n        for (typename SCMatrix::InnerIterator it(m_Lstore, j); it; ++it)\n        {\n          if(it.index() == j)\n          {\n            det *= it.value();\n            break;\n          }\n        }\n      }\n      return (m_detPermR * m_detPermC) > 0 ? det : -det;\n    }\n\n    Index nnzL() const { return m_nnzL; };\n    Index nnzU() const { return m_nnzU; };\n\n  protected:\n    // Functions \n    void initperfvalues()\n    {\n      m_perfv.panel_size = 16;\n      m_perfv.relax = 1; \n      m_perfv.maxsuper = 128; \n      m_perfv.rowblk = 16; \n      m_perfv.colblk = 8; \n      m_perfv.fillfactor = 20;  \n    }\n      \n    // Variables \n    mutable ComputationInfo m_info;\n    bool m_factorizationIsOk;\n    bool m_analysisIsOk;\n    std::string m_lastError;\n    NCMatrix m_mat; // The input (permuted ) matrix \n    SCMatrix m_Lstore; // The lower triangular matrix (supernodal)\n    MappedSparseMatrix<Scalar,ColMajor,StorageIndex> m_Ustore; // The upper triangular matrix\n    PermutationType m_perm_c; // Column permutation \n    PermutationType m_perm_r ; // Row permutation\n    IndexVector m_etree; // Column elimination tree \n    \n    typename Base::GlobalLU_t m_glu; \n                               \n    // SparseLU options \n    bool m_symmetricmode;\n    // values for performance \n    internal::perfvalues m_perfv;\n    RealScalar m_diagpivotthresh; // Specifies the threshold used for a diagonal entry to be an acceptable pivot\n    Index m_nnzL, m_nnzU; // Nonzeros in L and U factors\n    Index m_detPermR, m_detPermC; // Determinants of the permutation matrices\n  private:\n    // Disable copy constructor \n    SparseLU (const SparseLU& );\n}; // End class SparseLU\n\n\n\n// Functions needed by the anaysis phase\n/** \n  * Compute the column permutation to minimize the fill-in\n  * \n  *  - Apply this permutation to the input matrix - \n  * \n  *  - Compute the column elimination tree on the permuted matrix \n  * \n  *  - Postorder the elimination tree and the column permutation\n  * \n  */\ntemplate <typename MatrixType, typename OrderingType>\nvoid SparseLU<MatrixType, OrderingType>::analyzePattern(const MatrixType& mat)\n{\n  \n  //TODO  It is possible as in SuperLU to compute row and columns scaling vectors to equilibrate the matrix mat.\n  \n  // Firstly, copy the whole input matrix. \n  m_mat = mat;\n  \n  // Compute fill-in ordering\n  OrderingType ord; \n  ord(m_mat,m_perm_c);\n  \n  // Apply the permutation to the column of the input  matrix\n  if (m_perm_c.size())\n  {\n    m_mat.uncompress(); //NOTE: The effect of this command is only to create the InnerNonzeros pointers. FIXME : This vector is filled but not subsequently used.  \n    // Then, permute only the column pointers\n    ei_declare_aligned_stack_constructed_variable(StorageIndex,outerIndexPtr,mat.cols()+1,mat.isCompressed()?const_cast<StorageIndex*>(mat.outerIndexPtr()):0);\n    \n    // If the input matrix 'mat' is uncompressed, then the outer-indices do not match the ones of m_mat, and a copy is thus needed.\n    if(!mat.isCompressed()) \n      IndexVector::Map(outerIndexPtr, mat.cols()+1) = IndexVector::Map(m_mat.outerIndexPtr(),mat.cols()+1);\n    \n    // Apply the permutation and compute the nnz per column.\n    for (Index i = 0; i < mat.cols(); i++)\n    {\n      m_mat.outerIndexPtr()[m_perm_c.indices()(i)] = outerIndexPtr[i];\n      m_mat.innerNonZeroPtr()[m_perm_c.indices()(i)] = outerIndexPtr[i+1] - outerIndexPtr[i];\n    }\n  }\n  \n  // Compute the column elimination tree of the permuted matrix \n  IndexVector firstRowElt;\n  internal::coletree(m_mat, m_etree,firstRowElt); \n     \n  // In symmetric mode, do not do postorder here\n  if (!m_symmetricmode) {\n    IndexVector post, iwork; \n    // Post order etree\n    internal::treePostorder(StorageIndex(m_mat.cols()), m_etree, post); \n      \n   \n    // Renumber etree in postorder \n    Index m = m_mat.cols(); \n    iwork.resize(m+1);\n    for (Index i = 0; i < m; ++i) iwork(post(i)) = post(m_etree(i));\n    m_etree = iwork;\n    \n    // Postmultiply A*Pc by post, i.e reorder the matrix according to the postorder of the etree\n    PermutationType post_perm(m); \n    for (Index i = 0; i < m; i++) \n      post_perm.indices()(i) = post(i); \n        \n    // Combine the two permutations : postorder the permutation for future use\n    if(m_perm_c.size()) {\n      m_perm_c = post_perm * m_perm_c;\n    }\n    \n  } // end postordering \n  \n  m_analysisIsOk = true; \n}\n\n// Functions needed by the numerical factorization phase\n\n\n/** \n  *  - Numerical factorization \n  *  - Interleaved with the symbolic factorization \n  * On exit,  info is \n  * \n  *    = 0: successful factorization\n  * \n  *    > 0: if info = i, and i is\n  * \n  *       <= A->ncol: U(i,i) is exactly zero. The factorization has\n  *          been completed, but the factor U is exactly singular,\n  *          and division by zero will occur if it is used to solve a\n  *          system of equations.\n  * \n  *       > A->ncol: number of bytes allocated when memory allocation\n  *         failure occurred, plus A->ncol. If lwork = -1, it is\n  *         the estimated amount of space needed, plus A->ncol.  \n  */\ntemplate <typename MatrixType, typename OrderingType>\nvoid SparseLU<MatrixType, OrderingType>::factorize(const MatrixType& matrix)\n{\n  using internal::emptyIdxLU;\n  eigen_assert(m_analysisIsOk && \"analyzePattern() should be called first\"); \n  eigen_assert((matrix.rows() == matrix.cols()) && \"Only for squared matrices\");\n  \n  m_isInitialized = true;\n  \n  // Apply the column permutation computed in analyzepattern()\n  //   m_mat = matrix * m_perm_c.inverse(); \n  m_mat = matrix;\n  if (m_perm_c.size()) \n  {\n    m_mat.uncompress(); //NOTE: The effect of this command is only to create the InnerNonzeros pointers.\n    //Then, permute only the column pointers\n    const StorageIndex * outerIndexPtr;\n    if (matrix.isCompressed()) outerIndexPtr = matrix.outerIndexPtr();\n    else\n    {\n      StorageIndex* outerIndexPtr_t = new StorageIndex[matrix.cols()+1];\n      for(Index i = 0; i <= matrix.cols(); i++) outerIndexPtr_t[i] = m_mat.outerIndexPtr()[i];\n      outerIndexPtr = outerIndexPtr_t;\n    }\n    for (Index i = 0; i < matrix.cols(); i++)\n    {\n      m_mat.outerIndexPtr()[m_perm_c.indices()(i)] = outerIndexPtr[i];\n      m_mat.innerNonZeroPtr()[m_perm_c.indices()(i)] = outerIndexPtr[i+1] - outerIndexPtr[i];\n    }\n    if(!matrix.isCompressed()) delete[] outerIndexPtr;\n  } \n  else \n  { //FIXME This should not be needed if the empty permutation is handled transparently\n    m_perm_c.resize(matrix.cols());\n    for(StorageIndex i = 0; i < matrix.cols(); ++i) m_perm_c.indices()(i) = i;\n  }\n  \n  Index m = m_mat.rows();\n  Index n = m_mat.cols();\n  Index nnz = m_mat.nonZeros();\n  Index maxpanel = m_perfv.panel_size * m;\n  // Allocate working storage common to the factor routines\n  Index lwork = 0;\n  Index info = Base::memInit(m, n, nnz, lwork, m_perfv.fillfactor, m_perfv.panel_size, m_glu); \n  if (info) \n  {\n    m_lastError = \"UNABLE TO ALLOCATE WORKING MEMORY\\n\\n\" ;\n    m_factorizationIsOk = false;\n    return ; \n  }\n  \n  // Set up pointers for integer working arrays \n  IndexVector segrep(m); segrep.setZero();\n  IndexVector parent(m); parent.setZero();\n  IndexVector xplore(m); xplore.setZero();\n  IndexVector repfnz(maxpanel);\n  IndexVector panel_lsub(maxpanel);\n  IndexVector xprune(n); xprune.setZero();\n  IndexVector marker(m*internal::LUNoMarker); marker.setZero();\n  \n  repfnz.setConstant(-1); \n  panel_lsub.setConstant(-1);\n  \n  // Set up pointers for scalar working arrays \n  ScalarVector dense; \n  dense.setZero(maxpanel);\n  ScalarVector tempv; \n  tempv.setZero(internal::LUnumTempV(m, m_perfv.panel_size, m_perfv.maxsuper, /*m_perfv.rowblk*/m) );\n  \n  // Compute the inverse of perm_c\n  PermutationType iperm_c(m_perm_c.inverse()); \n  \n  // Identify initial relaxed snodes\n  IndexVector relax_end(n);\n  if ( m_symmetricmode == true ) \n    Base::heap_relax_snode(n, m_etree, m_perfv.relax, marker, relax_end);\n  else\n    Base::relax_snode(n, m_etree, m_perfv.relax, marker, relax_end);\n  \n  \n  m_perm_r.resize(m); \n  m_perm_r.indices().setConstant(-1);\n  marker.setConstant(-1);\n  m_detPermR = 1; // Record the determinant of the row permutation\n  \n  m_glu.supno(0) = emptyIdxLU; m_glu.xsup.setConstant(0);\n  m_glu.xsup(0) = m_glu.xlsub(0) = m_glu.xusub(0) = m_glu.xlusup(0) = Index(0);\n  \n  // Work on one 'panel' at a time. A panel is one of the following :\n  //  (a) a relaxed supernode at the bottom of the etree, or\n  //  (b) panel_size contiguous columns, <panel_size> defined by the user\n  Index jcol; \n  Index pivrow; // Pivotal row number in the original row matrix\n  Index nseg1; // Number of segments in U-column above panel row jcol\n  Index nseg; // Number of segments in each U-column \n  Index irep; \n  Index i, k, jj; \n  for (jcol = 0; jcol < n; )\n  {\n    // Adjust panel size so that a panel won't overlap with the next relaxed snode. \n    Index panel_size = m_perfv.panel_size; // upper bound on panel width\n    for (k = jcol + 1; k < (std::min)(jcol+panel_size, n); k++)\n    {\n      if (relax_end(k) != emptyIdxLU) \n      {\n        panel_size = k - jcol; \n        break; \n      }\n    }\n    if (k == n) \n      panel_size = n - jcol; \n      \n    // Symbolic outer factorization on a panel of columns \n    Base::panel_dfs(m, panel_size, jcol, m_mat, m_perm_r.indices(), nseg1, dense, panel_lsub, segrep, repfnz, xprune, marker, parent, xplore, m_glu); \n    \n    // Numeric sup-panel updates in topological order \n    Base::panel_bmod(m, panel_size, jcol, nseg1, dense, tempv, segrep, repfnz, m_glu); \n    \n    // Sparse LU within the panel, and below the panel diagonal \n    for ( jj = jcol; jj< jcol + panel_size; jj++) \n    {\n      k = (jj - jcol) * m; // Column index for w-wide arrays \n      \n      nseg = nseg1; // begin after all the panel segments\n      //Depth-first-search for the current column\n      VectorBlock<IndexVector> panel_lsubk(panel_lsub, k, m);\n      VectorBlock<IndexVector> repfnz_k(repfnz, k, m); \n      info = Base::column_dfs(m, jj, m_perm_r.indices(), m_perfv.maxsuper, nseg, panel_lsubk, segrep, repfnz_k, xprune, marker, parent, xplore, m_glu); \n      if ( info ) \n      {\n        m_lastError =  \"UNABLE TO EXPAND MEMORY IN COLUMN_DFS() \";\n        m_info = NumericalIssue; \n        m_factorizationIsOk = false; \n        return; \n      }\n      // Numeric updates to this column \n      VectorBlock<ScalarVector> dense_k(dense, k, m); \n      VectorBlock<IndexVector> segrep_k(segrep, nseg1, m-nseg1); \n      info = Base::column_bmod(jj, (nseg - nseg1), dense_k, tempv, segrep_k, repfnz_k, jcol, m_glu); \n      if ( info ) \n      {\n        m_lastError = \"UNABLE TO EXPAND MEMORY IN COLUMN_BMOD() \";\n        m_info = NumericalIssue; \n        m_factorizationIsOk = false; \n        return; \n      }\n      \n      // Copy the U-segments to ucol(*)\n      info = Base::copy_to_ucol(jj, nseg, segrep, repfnz_k ,m_perm_r.indices(), dense_k, m_glu); \n      if ( info ) \n      {\n        m_lastError = \"UNABLE TO EXPAND MEMORY IN COPY_TO_UCOL() \";\n        m_info = NumericalIssue; \n        m_factorizationIsOk = false; \n        return; \n      }\n      \n      // Form the L-segment \n      info = Base::pivotL(jj, m_diagpivotthresh, m_perm_r.indices(), iperm_c.indices(), pivrow, m_glu);\n      if ( info ) \n      {\n        m_lastError = \"THE MATRIX IS STRUCTURALLY SINGULAR ... ZERO COLUMN AT \";\n        std::ostringstream returnInfo;\n        returnInfo << info; \n        m_lastError += returnInfo.str();\n        m_info = NumericalIssue; \n        m_factorizationIsOk = false; \n        return; \n      }\n      \n      // Update the determinant of the row permutation matrix\n      // FIXME: the following test is not correct, we should probably take iperm_c into account and pivrow is not directly the row pivot.\n      if (pivrow != jj) m_detPermR = -m_detPermR;\n\n      // Prune columns (0:jj-1) using column jj\n      Base::pruneL(jj, m_perm_r.indices(), pivrow, nseg, segrep, repfnz_k, xprune, m_glu); \n      \n      // Reset repfnz for this column \n      for (i = 0; i < nseg; i++)\n      {\n        irep = segrep(i); \n        repfnz_k(irep) = emptyIdxLU; \n      }\n    } // end SparseLU within the panel  \n    jcol += panel_size;  // Move to the next panel\n  } // end for -- end elimination \n  \n  m_detPermR = m_perm_r.determinant();\n  m_detPermC = m_perm_c.determinant();\n  \n  // Count the number of nonzeros in factors \n  Base::countnz(n, m_nnzL, m_nnzU, m_glu); \n  // Apply permutation  to the L subscripts \n  Base::fixupL(n, m_perm_r.indices(), m_glu);\n  \n  // Create supernode matrix L \n  m_Lstore.setInfos(m, n, m_glu.lusup, m_glu.xlusup, m_glu.lsub, m_glu.xlsub, m_glu.supno, m_glu.xsup); \n  // Create the column major upper sparse matrix  U; \n  new (&m_Ustore) MappedSparseMatrix<Scalar, ColMajor, StorageIndex> ( m, n, m_nnzU, m_glu.xusub.data(), m_glu.usub.data(), m_glu.ucol.data() );\n  \n  m_info = Success;\n  m_factorizationIsOk = true;\n}\n\ntemplate<typename MappedSupernodalType>\nstruct SparseLUMatrixLReturnType : internal::no_assignment_operator\n{\n  typedef typename MappedSupernodalType::Scalar Scalar;\n  explicit SparseLUMatrixLReturnType(const MappedSupernodalType& mapL) : m_mapL(mapL)\n  { }\n  Index rows() const { return m_mapL.rows(); }\n  Index cols() const { return m_mapL.cols(); }\n  template<typename Dest>\n  void solveInPlace( MatrixBase<Dest> &X) const\n  {\n    m_mapL.solveInPlace(X);\n  }\n  template<bool Conjugate, typename Dest>\n  void solveTransposedInPlace( MatrixBase<Dest> &X) const\n  {\n    m_mapL.template solveTransposedInPlace<Conjugate>(X);\n  }\n\n  const MappedSupernodalType& m_mapL;\n};\n\ntemplate<typename MatrixLType, typename MatrixUType>\nstruct SparseLUMatrixUReturnType : internal::no_assignment_operator\n{\n  typedef typename MatrixLType::Scalar Scalar;\n  SparseLUMatrixUReturnType(const MatrixLType& mapL, const MatrixUType& mapU)\n  : m_mapL(mapL),m_mapU(mapU)\n  { }\n  Index rows() const { return m_mapL.rows(); }\n  Index cols() const { return m_mapL.cols(); }\n\n  template<typename Dest>   void solveInPlace(MatrixBase<Dest> &X) const\n  {\n    Index nrhs = X.cols();\n    Index n    = X.rows();\n    // Backward solve with U\n    for (Index k = m_mapL.nsuper(); k >= 0; k--)\n    {\n      Index fsupc = m_mapL.supToCol()[k];\n      Index lda = m_mapL.colIndexPtr()[fsupc+1] - m_mapL.colIndexPtr()[fsupc]; // leading dimension\n      Index nsupc = m_mapL.supToCol()[k+1] - fsupc;\n      Index luptr = m_mapL.colIndexPtr()[fsupc];\n\n      if (nsupc == 1)\n      {\n        for (Index j = 0; j < nrhs; j++)\n        {\n          X(fsupc, j) /= m_mapL.valuePtr()[luptr];\n        }\n      }\n      else\n      {\n        // FIXME: the following lines should use Block expressions and not Map!\n        Map<const Matrix<Scalar,Dynamic,Dynamic, ColMajor>, 0, OuterStride<> > A( &(m_mapL.valuePtr()[luptr]), nsupc, nsupc, OuterStride<>(lda) );\n        Map< Matrix<Scalar,Dynamic,Dest::ColsAtCompileTime, ColMajor>, 0, OuterStride<> > U (&(X.coeffRef(fsupc,0)), nsupc, nrhs, OuterStride<>(n) );\n        U = A.template triangularView<Upper>().solve(U);\n      }\n\n      for (Index j = 0; j < nrhs; ++j)\n      {\n        for (Index jcol = fsupc; jcol < fsupc + nsupc; jcol++)\n        {\n          typename MatrixUType::InnerIterator it(m_mapU, jcol);\n          for ( ; it; ++it)\n          {\n            Index irow = it.index();\n            X(irow, j) -= X(jcol, j) * it.value();\n          }\n        }\n      }\n    } // End For U-solve\n  }\n\n  template<bool Conjugate, typename Dest>   void solveTransposedInPlace(MatrixBase<Dest> &X) const\n  {\n    using numext::conj;\n    Index nrhs = X.cols();\n    Index n    = X.rows();\n    // Forward solve with U\n    for (Index k = 0; k <=  m_mapL.nsuper(); k++)\n    {\n      Index fsupc = m_mapL.supToCol()[k];\n      Index lda = m_mapL.colIndexPtr()[fsupc+1] - m_mapL.colIndexPtr()[fsupc]; // leading dimension\n      Index nsupc = m_mapL.supToCol()[k+1] - fsupc;\n      Index luptr = m_mapL.colIndexPtr()[fsupc];\n\n      for (Index j = 0; j < nrhs; ++j)\n      {\n        for (Index jcol = fsupc; jcol < fsupc + nsupc; jcol++)\n        {\n          typename MatrixUType::InnerIterator it(m_mapU, jcol);\n          for ( ; it; ++it)\n          {\n            Index irow = it.index();\n            X(jcol, j) -= X(irow, j) * (Conjugate? conj(it.value()): it.value());\n          }\n        }\n      }\n      if (nsupc == 1)\n      {\n        for (Index j = 0; j < nrhs; j++)\n        {\n          X(fsupc, j) /= (Conjugate? conj(m_mapL.valuePtr()[luptr]) : m_mapL.valuePtr()[luptr]);\n        }\n      }\n      else\n      {\n        Map<const Matrix<Scalar,Dynamic,Dynamic, ColMajor>, 0, OuterStride<> > A( &(m_mapL.valuePtr()[luptr]), nsupc, nsupc, OuterStride<>(lda) );\n        Map< Matrix<Scalar,Dynamic,Dest::ColsAtCompileTime, ColMajor>, 0, OuterStride<> > U (&(X(fsupc,0)), nsupc, nrhs, OuterStride<>(n) );\n        if(Conjugate)\n          U = A.adjoint().template triangularView<Lower>().solve(U);\n        else\n          U = A.transpose().template triangularView<Lower>().solve(U);\n      }\n    }// End For U-solve\n  }\n\n\n  const MatrixLType& m_mapL;\n  const MatrixUType& m_mapU;\n};\n\n} // End namespace Eigen \n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseLU/SparseLUImpl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n#ifndef SPARSELU_IMPL_H\n#define SPARSELU_IMPL_H\n\nnamespace Eigen {\nnamespace internal {\n  \n/** \\ingroup SparseLU_Module\n  * \\class SparseLUImpl\n  * Base class for sparseLU\n  */\ntemplate <typename Scalar, typename StorageIndex>\nclass SparseLUImpl\n{\n  public:\n    typedef Matrix<Scalar,Dynamic,1> ScalarVector;\n    typedef Matrix<StorageIndex,Dynamic,1> IndexVector; \n    typedef Matrix<Scalar,Dynamic,Dynamic,ColMajor> ScalarMatrix;\n    typedef Map<ScalarMatrix, 0,  OuterStride<> > MappedMatrixBlock;\n    typedef typename ScalarVector::RealScalar RealScalar; \n    typedef Ref<Matrix<Scalar,Dynamic,1> > BlockScalarVector;\n    typedef Ref<Matrix<StorageIndex,Dynamic,1> > BlockIndexVector;\n    typedef LU_GlobalLU_t<IndexVector, ScalarVector> GlobalLU_t; \n    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> MatrixType; \n    \n  protected:\n     template <typename VectorType>\n     Index expand(VectorType& vec, Index& length, Index nbElts, Index keep_prev, Index& num_expansions);\n     Index memInit(Index m, Index n, Index annz, Index lwork, Index fillratio, Index panel_size,  GlobalLU_t& glu); \n     template <typename VectorType>\n     Index memXpand(VectorType& vec, Index& maxlen, Index nbElts, MemType memtype, Index& num_expansions);\n     void heap_relax_snode (const Index n, IndexVector& et, const Index relax_columns, IndexVector& descendants, IndexVector& relax_end); \n     void relax_snode (const Index n, IndexVector& et, const Index relax_columns, IndexVector& descendants, IndexVector& relax_end); \n     Index snode_dfs(const Index jcol, const Index kcol,const MatrixType& mat,  IndexVector& xprune, IndexVector& marker, GlobalLU_t& glu); \n     Index snode_bmod (const Index jcol, const Index fsupc, ScalarVector& dense, GlobalLU_t& glu);\n     Index pivotL(const Index jcol, const RealScalar& diagpivotthresh, IndexVector& perm_r, IndexVector& iperm_c, Index& pivrow, GlobalLU_t& glu);\n     template <typename Traits>\n     void dfs_kernel(const StorageIndex jj, IndexVector& perm_r,\n                    Index& nseg, IndexVector& panel_lsub, IndexVector& segrep,\n                    Ref<IndexVector> repfnz_col, IndexVector& xprune, Ref<IndexVector> marker, IndexVector& parent,\n                    IndexVector& xplore, GlobalLU_t& glu, Index& nextl_col, Index krow, Traits& traits);\n     void panel_dfs(const Index m, const Index w, const Index jcol, MatrixType& A, IndexVector& perm_r, Index& nseg, ScalarVector& dense, IndexVector& panel_lsub, IndexVector& segrep, IndexVector& repfnz, IndexVector& xprune, IndexVector& marker, IndexVector& parent, IndexVector& xplore, GlobalLU_t& glu);\n    \n     void panel_bmod(const Index m, const Index w, const Index jcol, const Index nseg, ScalarVector& dense, ScalarVector& tempv, IndexVector& segrep, IndexVector& repfnz, GlobalLU_t& glu);\n     Index column_dfs(const Index m, const Index jcol, IndexVector& perm_r, Index maxsuper, Index& nseg,  BlockIndexVector lsub_col, IndexVector& segrep, BlockIndexVector repfnz, IndexVector& xprune, IndexVector& marker, IndexVector& parent, IndexVector& xplore, GlobalLU_t& glu);\n     Index column_bmod(const Index jcol, const Index nseg, BlockScalarVector dense, ScalarVector& tempv, BlockIndexVector segrep, BlockIndexVector repfnz, Index fpanelc, GlobalLU_t& glu); \n     Index copy_to_ucol(const Index jcol, const Index nseg, IndexVector& segrep, BlockIndexVector repfnz ,IndexVector& perm_r, BlockScalarVector dense, GlobalLU_t& glu); \n     void pruneL(const Index jcol, const IndexVector& perm_r, const Index pivrow, const Index nseg, const IndexVector& segrep, BlockIndexVector repfnz, IndexVector& xprune, GlobalLU_t& glu);\n     void countnz(const Index n, Index& nnzL, Index& nnzU, GlobalLU_t& glu); \n     void fixupL(const Index n, const IndexVector& perm_r, GlobalLU_t& glu); \n     \n     template<typename , typename >\n     friend struct column_dfs_traits;\n}; \n\n} // end namespace internal\n} // namespace Eigen\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseLU/SparseLU_Memory.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/* \n \n * NOTE: This file is the modified version of [s,d,c,z]memory.c files in SuperLU \n \n * -- SuperLU routine (version 3.1) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * August 1, 2008\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n\n#ifndef EIGEN_SPARSELU_MEMORY\n#define EIGEN_SPARSELU_MEMORY\n\nnamespace Eigen {\nnamespace internal {\n  \nenum { LUNoMarker = 3 };\nenum {emptyIdxLU = -1};\ninline Index LUnumTempV(Index& m, Index& w, Index& t, Index& b)\n{\n  return (std::max)(m, (t+b)*w);\n}\n\ntemplate< typename Scalar>\ninline Index LUTempSpace(Index&m, Index& w)\n{\n  return (2*w + 4 + LUNoMarker) * m * sizeof(Index) + (w + 1) * m * sizeof(Scalar);\n}\n\n\n\n\n/** \n  * Expand the existing storage to accommodate more fill-ins\n  * \\param vec Valid pointer to the vector to allocate or expand\n  * \\param[in,out] length  At input, contain the current length of the vector that is to be increased. At output, length of the newly allocated vector\n  * \\param[in] nbElts Current number of elements in the factors\n  * \\param keep_prev  1: use length  and do not expand the vector; 0: compute new_len and expand\n  * \\param[in,out] num_expansions Number of times the memory has been expanded\n  */\ntemplate <typename Scalar, typename StorageIndex>\ntemplate <typename VectorType>\nIndex  SparseLUImpl<Scalar,StorageIndex>::expand(VectorType& vec, Index& length, Index nbElts, Index keep_prev, Index& num_expansions) \n{\n  \n  float alpha = 1.5; // Ratio of the memory increase \n  Index new_len; // New size of the allocated memory\n  \n  if(num_expansions == 0 || keep_prev) \n    new_len = length ; // First time allocate requested\n  else \n    new_len = (std::max)(length+1,Index(alpha * length));\n  \n  VectorType old_vec; // Temporary vector to hold the previous values   \n  if (nbElts > 0 )\n    old_vec = vec.segment(0,nbElts); \n  \n  //Allocate or expand the current vector\n#ifdef EIGEN_EXCEPTIONS\n  try\n#endif\n  {\n    vec.resize(new_len); \n  }\n#ifdef EIGEN_EXCEPTIONS\n  catch(std::bad_alloc& )\n#else\n  if(!vec.size())\n#endif\n  {\n    if (!num_expansions)\n    {\n      // First time to allocate from LUMemInit()\n      // Let LUMemInit() deals with it.\n      return -1;\n    }\n    if (keep_prev)\n    {\n      // In this case, the memory length should not not be reduced\n      return new_len;\n    }\n    else \n    {\n      // Reduce the size and increase again \n      Index tries = 0; // Number of attempts\n      do \n      {\n        alpha = (alpha + 1)/2;\n        new_len = (std::max)(length+1,Index(alpha * length));\n#ifdef EIGEN_EXCEPTIONS\n        try\n#endif\n        {\n          vec.resize(new_len); \n        }\n#ifdef EIGEN_EXCEPTIONS\n        catch(std::bad_alloc& )\n#else\n        if (!vec.size())\n#endif\n        {\n          tries += 1; \n          if ( tries > 10) return new_len; \n        }\n      } while (!vec.size());\n    }\n  }\n  //Copy the previous values to the newly allocated space \n  if (nbElts > 0)\n    vec.segment(0, nbElts) = old_vec;   \n   \n  \n  length  = new_len;\n  if(num_expansions) ++num_expansions;\n  return 0; \n}\n\n/**\n * \\brief  Allocate various working space for the numerical factorization phase.\n * \\param m number of rows of the input matrix \n * \\param n number of columns \n * \\param annz number of initial nonzeros in the matrix \n * \\param lwork  if lwork=-1, this routine returns an estimated size of the required memory\n * \\param glu persistent data to facilitate multiple factors : will be deleted later ??\n * \\param fillratio estimated ratio of fill in the factors\n * \\param panel_size Size of a panel\n * \\return an estimated size of the required memory if lwork = -1; otherwise, return the size of actually allocated memory when allocation failed, and 0 on success\n * \\note Unlike SuperLU, this routine does not support successive factorization with the same pattern and the same row permutation\n */\ntemplate <typename Scalar, typename StorageIndex>\nIndex SparseLUImpl<Scalar,StorageIndex>::memInit(Index m, Index n, Index annz, Index lwork, Index fillratio, Index panel_size,  GlobalLU_t& glu)\n{\n  Index& num_expansions = glu.num_expansions; //No memory expansions so far\n  num_expansions = 0;\n  glu.nzumax = glu.nzlumax = (std::min)(fillratio * (annz+1) / n, m) * n; // estimated number of nonzeros in U \n  glu.nzlmax = (std::max)(Index(4), fillratio) * (annz+1) / 4; // estimated  nnz in L factor\n  // Return the estimated size to the user if necessary\n  Index tempSpace;\n  tempSpace = (2*panel_size + 4 + LUNoMarker) * m * sizeof(Index) + (panel_size + 1) * m * sizeof(Scalar);\n  if (lwork == emptyIdxLU) \n  {\n    Index estimated_size;\n    estimated_size = (5 * n + 5) * sizeof(Index)  + tempSpace\n                    + (glu.nzlmax + glu.nzumax) * sizeof(Index) + (glu.nzlumax+glu.nzumax) *  sizeof(Scalar) + n; \n    return estimated_size;\n  }\n  \n  // Setup the required space \n  \n  // First allocate Integer pointers for L\\U factors\n  glu.xsup.resize(n+1);\n  glu.supno.resize(n+1);\n  glu.xlsub.resize(n+1);\n  glu.xlusup.resize(n+1);\n  glu.xusub.resize(n+1);\n\n  // Reserve memory for L/U factors\n  do \n  {\n    if(     (expand<ScalarVector>(glu.lusup, glu.nzlumax, 0, 0, num_expansions)<0)\n        ||  (expand<ScalarVector>(glu.ucol,  glu.nzumax,  0, 0, num_expansions)<0)\n        ||  (expand<IndexVector> (glu.lsub,  glu.nzlmax,  0, 0, num_expansions)<0)\n        ||  (expand<IndexVector> (glu.usub,  glu.nzumax,  0, 1, num_expansions)<0) )\n    {\n      //Reduce the estimated size and retry\n      glu.nzlumax /= 2;\n      glu.nzumax /= 2;\n      glu.nzlmax /= 2;\n      if (glu.nzlumax < annz ) return glu.nzlumax; \n    }\n  } while (!glu.lusup.size() || !glu.ucol.size() || !glu.lsub.size() || !glu.usub.size());\n  \n  ++num_expansions;\n  return 0;\n  \n} // end LuMemInit\n\n/** \n * \\brief Expand the existing storage \n * \\param vec vector to expand \n * \\param[in,out] maxlen On input, previous size of vec (Number of elements to copy ). on output, new size\n * \\param nbElts current number of elements in the vector.\n * \\param memtype Type of the element to expand\n * \\param num_expansions Number of expansions \n * \\return 0 on success, > 0 size of the memory allocated so far\n */\ntemplate <typename Scalar, typename StorageIndex>\ntemplate <typename VectorType>\nIndex SparseLUImpl<Scalar,StorageIndex>::memXpand(VectorType& vec, Index& maxlen, Index nbElts, MemType memtype, Index& num_expansions)\n{\n  Index failed_size; \n  if (memtype == USUB)\n     failed_size = this->expand<VectorType>(vec, maxlen, nbElts, 1, num_expansions);\n  else\n    failed_size = this->expand<VectorType>(vec, maxlen, nbElts, 0, num_expansions);\n\n  if (failed_size)\n    return failed_size; \n  \n  return 0 ;  \n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n#endif // EIGEN_SPARSELU_MEMORY\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseLU/SparseLU_Structs.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/* \n * NOTE: This file comes from a partly modified version of files slu_[s,d,c,z]defs.h\n * -- SuperLU routine (version 4.1) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * November, 2010\n * \n * Global data structures used in LU factorization -\n * \n *   nsuper: #supernodes = nsuper + 1, numbered [0, nsuper].\n *   (xsup,supno): supno[i] is the supernode no to which i belongs;\n *  xsup(s) points to the beginning of the s-th supernode.\n *  e.g.   supno 0 1 2 2 3 3 3 4 4 4 4 4   (n=12)\n *          xsup 0 1 2 4 7 12\n *  Note: dfs will be performed on supernode rep. relative to the new \n *        row pivoting ordering\n *\n *   (xlsub,lsub): lsub[*] contains the compressed subscript of\n *  rectangular supernodes; xlsub[j] points to the starting\n *  location of the j-th column in lsub[*]. Note that xlsub \n *  is indexed by column.\n *  Storage: original row subscripts\n *\n *      During the course of sparse LU factorization, we also use\n *  (xlsub,lsub) for the purpose of symmetric pruning. For each\n *  supernode {s,s+1,...,t=s+r} with first column s and last\n *  column t, the subscript set\n *    lsub[j], j=xlsub[s], .., xlsub[s+1]-1\n *  is the structure of column s (i.e. structure of this supernode).\n *  It is used for the storage of numerical values.\n *  Furthermore,\n *    lsub[j], j=xlsub[t], .., xlsub[t+1]-1\n *  is the structure of the last column t of this supernode.\n *  It is for the purpose of symmetric pruning. Therefore, the\n *  structural subscripts can be rearranged without making physical\n *  interchanges among the numerical values.\n *\n *  However, if the supernode has only one column, then we\n *  only keep one set of subscripts. For any subscript interchange\n *  performed, similar interchange must be done on the numerical\n *  values.\n *\n *  The last column structures (for pruning) will be removed\n *  after the numercial LU factorization phase.\n *\n *   (xlusup,lusup): lusup[*] contains the numerical values of the\n *  rectangular supernodes; xlusup[j] points to the starting\n *  location of the j-th column in storage vector lusup[*]\n *  Note: xlusup is indexed by column.\n *  Each rectangular supernode is stored by column-major\n *  scheme, consistent with Fortran 2-dim array storage.\n *\n *   (xusub,ucol,usub): ucol[*] stores the numerical values of\n *  U-columns outside the rectangular supernodes. The row\n *  subscript of nonzero ucol[k] is stored in usub[k].\n *  xusub[i] points to the starting location of column i in ucol.\n *  Storage: new row subscripts; that is subscripts of PA.\n */\n\n#ifndef EIGEN_LU_STRUCTS\n#define EIGEN_LU_STRUCTS\nnamespace Eigen {\nnamespace internal {\n  \ntypedef enum {LUSUP, UCOL, LSUB, USUB, LLVL, ULVL} MemType; \n\ntemplate <typename IndexVector, typename ScalarVector>\nstruct LU_GlobalLU_t {\n  typedef typename IndexVector::Scalar StorageIndex; \n  IndexVector xsup; //First supernode column ... xsup(s) points to the beginning of the s-th supernode\n  IndexVector supno; // Supernode number corresponding to this column (column to supernode mapping)\n  ScalarVector  lusup; // nonzero values of L ordered by columns \n  IndexVector lsub; // Compressed row indices of L rectangular supernodes. \n  IndexVector xlusup; // pointers to the beginning of each column in lusup\n  IndexVector xlsub; // pointers to the beginning of each column in lsub\n  Index   nzlmax; // Current max size of lsub\n  Index   nzlumax; // Current max size of lusup\n  ScalarVector  ucol; // nonzero values of U ordered by columns \n  IndexVector usub; // row indices of U columns in ucol\n  IndexVector xusub; // Pointers to the beginning of each column of U in ucol \n  Index   nzumax; // Current max size of ucol\n  Index   n; // Number of columns in the matrix  \n  Index   num_expansions; \n};\n\n// Values to set for performance\nstruct perfvalues {\n  Index panel_size; // a panel consists of at most <panel_size> consecutive columns\n  Index relax; // To control degree of relaxing supernodes. If the number of nodes (columns) \n                // in a subtree of the elimination tree is less than relax, this subtree is considered \n                // as one supernode regardless of the row structures of those columns\n  Index maxsuper; // The maximum size for a supernode in complete LU\n  Index rowblk; // The minimum row dimension for 2-D blocking to be used;\n  Index colblk; // The minimum column dimension for 2-D blocking to be used;\n  Index fillfactor; // The estimated fills factors for L and U, compared with A\n}; \n\n} // end namespace internal\n\n} // end namespace Eigen\n#endif // EIGEN_LU_STRUCTS\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseLU/SparseLU_SupernodalMatrix.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSELU_SUPERNODAL_MATRIX_H\n#define EIGEN_SPARSELU_SUPERNODAL_MATRIX_H\n\nnamespace Eigen {\nnamespace internal {\n\n/** \\ingroup SparseLU_Module\n * \\brief a class to manipulate the L supernodal factor from the SparseLU factorization\n * \n * This class  contain the data to easily store \n * and manipulate the supernodes during the factorization and solution phase of Sparse LU. \n * Only the lower triangular matrix has supernodes.\n * \n * NOTE : This class corresponds to the SCformat structure in SuperLU\n * \n */\n/* TODO\n * InnerIterator as for sparsematrix \n * SuperInnerIterator to iterate through all supernodes \n * Function for triangular solve\n */\ntemplate <typename _Scalar, typename _StorageIndex>\nclass MappedSuperNodalMatrix\n{\n  public:\n    typedef _Scalar Scalar; \n    typedef _StorageIndex StorageIndex;\n    typedef Matrix<StorageIndex,Dynamic,1> IndexVector;\n    typedef Matrix<Scalar,Dynamic,1> ScalarVector;\n  public:\n    MappedSuperNodalMatrix()\n    {\n      \n    }\n    MappedSuperNodalMatrix(Index m, Index n,  ScalarVector& nzval, IndexVector& nzval_colptr, IndexVector& rowind,\n             IndexVector& rowind_colptr, IndexVector& col_to_sup, IndexVector& sup_to_col )\n    {\n      setInfos(m, n, nzval, nzval_colptr, rowind, rowind_colptr, col_to_sup, sup_to_col);\n    }\n    \n    ~MappedSuperNodalMatrix()\n    {\n      \n    }\n    /**\n     * Set appropriate pointers for the lower triangular supernodal matrix\n     * These infos are available at the end of the numerical factorization\n     * FIXME This class will be modified such that it can be use in the course \n     * of the factorization.\n     */\n    void setInfos(Index m, Index n, ScalarVector& nzval, IndexVector& nzval_colptr, IndexVector& rowind,\n             IndexVector& rowind_colptr, IndexVector& col_to_sup, IndexVector& sup_to_col )\n    {\n      m_row = m;\n      m_col = n; \n      m_nzval = nzval.data(); \n      m_nzval_colptr = nzval_colptr.data(); \n      m_rowind = rowind.data(); \n      m_rowind_colptr = rowind_colptr.data(); \n      m_nsuper = col_to_sup(n); \n      m_col_to_sup = col_to_sup.data(); \n      m_sup_to_col = sup_to_col.data(); \n    }\n    \n    /**\n     * Number of rows\n     */\n    Index rows() const { return m_row; }\n    \n    /**\n     * Number of columns\n     */\n    Index cols() const { return m_col; }\n    \n    /**\n     * Return the array of nonzero values packed by column\n     * \n     * The size is nnz\n     */\n    Scalar* valuePtr() {  return m_nzval; }\n    \n    const Scalar* valuePtr() const \n    {\n      return m_nzval; \n    }\n    /**\n     * Return the pointers to the beginning of each column in \\ref valuePtr()\n     */\n    StorageIndex* colIndexPtr()\n    {\n      return m_nzval_colptr; \n    }\n    \n    const StorageIndex* colIndexPtr() const\n    {\n      return m_nzval_colptr; \n    }\n    \n    /**\n     * Return the array of compressed row indices of all supernodes\n     */\n    StorageIndex* rowIndex()  { return m_rowind; }\n    \n    const StorageIndex* rowIndex() const\n    {\n      return m_rowind; \n    }\n    \n    /**\n     * Return the location in \\em rowvaluePtr() which starts each column\n     */\n    StorageIndex* rowIndexPtr() { return m_rowind_colptr; }\n    \n    const StorageIndex* rowIndexPtr() const\n    {\n      return m_rowind_colptr; \n    }\n    \n    /** \n     * Return the array of column-to-supernode mapping \n     */\n    StorageIndex* colToSup()  { return m_col_to_sup; }\n    \n    const StorageIndex* colToSup() const\n    {\n      return m_col_to_sup;       \n    }\n    /**\n     * Return the array of supernode-to-column mapping\n     */\n    StorageIndex* supToCol() { return m_sup_to_col; }\n    \n    const StorageIndex* supToCol() const\n    {\n      return m_sup_to_col;\n    }\n    \n    /**\n     * Return the number of supernodes\n     */\n    Index nsuper() const\n    {\n      return m_nsuper; \n    }\n    \n    class InnerIterator; \n    template<typename Dest>\n    void solveInPlace( MatrixBase<Dest>&X) const;\n    template<bool Conjugate, typename Dest>\n    void solveTransposedInPlace( MatrixBase<Dest>&X) const;\n\n    \n      \n      \n    \n  protected:\n    Index m_row; // Number of rows\n    Index m_col; // Number of columns\n    Index m_nsuper; // Number of supernodes\n    Scalar* m_nzval; //array of nonzero values packed by column\n    StorageIndex* m_nzval_colptr; //nzval_colptr[j] Stores the location in nzval[] which starts column j\n    StorageIndex* m_rowind; // Array of compressed row indices of rectangular supernodes\n    StorageIndex* m_rowind_colptr; //rowind_colptr[j] stores the location in rowind[] which starts column j\n    StorageIndex* m_col_to_sup; // col_to_sup[j] is the supernode number to which column j belongs\n    StorageIndex* m_sup_to_col; //sup_to_col[s] points to the starting column of the s-th supernode\n    \n  private :\n};\n\n/**\n  * \\brief InnerIterator class to iterate over nonzero values of the current column in the supernodal matrix L\n  * \n  */\ntemplate<typename Scalar, typename StorageIndex>\nclass MappedSuperNodalMatrix<Scalar,StorageIndex>::InnerIterator\n{\n  public:\n     InnerIterator(const MappedSuperNodalMatrix& mat, Index outer)\n      : m_matrix(mat),\n        m_outer(outer),\n        m_supno(mat.colToSup()[outer]),\n        m_idval(mat.colIndexPtr()[outer]),\n        m_startidval(m_idval),\n        m_endidval(mat.colIndexPtr()[outer+1]),\n        m_idrow(mat.rowIndexPtr()[mat.supToCol()[mat.colToSup()[outer]]]),\n        m_endidrow(mat.rowIndexPtr()[mat.supToCol()[mat.colToSup()[outer]]+1])\n    {}\n    inline InnerIterator& operator++()\n    { \n      m_idval++; \n      m_idrow++;\n      return *this;\n    }\n    inline Scalar value() const { return m_matrix.valuePtr()[m_idval]; }\n    \n    inline Scalar& valueRef() { return const_cast<Scalar&>(m_matrix.valuePtr()[m_idval]); }\n    \n    inline Index index() const { return m_matrix.rowIndex()[m_idrow]; }\n    inline Index row() const { return index(); }\n    inline Index col() const { return m_outer; }\n    \n    inline Index supIndex() const { return m_supno; }\n    \n    inline operator bool() const \n    { \n      return ( (m_idval < m_endidval) && (m_idval >= m_startidval)\n                && (m_idrow < m_endidrow) );\n    }\n    \n  protected:\n    const MappedSuperNodalMatrix& m_matrix; // Supernodal lower triangular matrix \n    const Index m_outer;                    // Current column \n    const Index m_supno;                    // Current SuperNode number\n    Index m_idval;                          // Index to browse the values in the current column\n    const Index m_startidval;               // Start of the column value\n    const Index m_endidval;                 // End of the column value\n    Index m_idrow;                          // Index to browse the row indices \n    Index m_endidrow;                       // End index of row indices of the current column\n};\n\n/**\n * \\brief Solve with the supernode triangular matrix\n * \n */\ntemplate<typename Scalar, typename Index_>\ntemplate<typename Dest>\nvoid MappedSuperNodalMatrix<Scalar,Index_>::solveInPlace( MatrixBase<Dest>&X) const\n{\n    /* Explicit type conversion as the Index type of MatrixBase<Dest> may be wider than Index */\n//    eigen_assert(X.rows() <= NumTraits<Index>::highest());\n//    eigen_assert(X.cols() <= NumTraits<Index>::highest());\n    Index n    = int(X.rows());\n    Index nrhs = Index(X.cols());\n    const Scalar * Lval = valuePtr();                 // Nonzero values \n    Matrix<Scalar,Dynamic,Dest::ColsAtCompileTime, ColMajor> work(n, nrhs);     // working vector\n    work.setZero();\n    for (Index k = 0; k <= nsuper(); k ++)\n    {\n      Index fsupc = supToCol()[k];                    // First column of the current supernode \n      Index istart = rowIndexPtr()[fsupc];            // Pointer index to the subscript of the current column\n      Index nsupr = rowIndexPtr()[fsupc+1] - istart;  // Number of rows in the current supernode\n      Index nsupc = supToCol()[k+1] - fsupc;          // Number of columns in the current supernode\n      Index nrow = nsupr - nsupc;                     // Number of rows in the non-diagonal part of the supernode\n      Index irow;                                     //Current index row\n      \n      if (nsupc == 1 )\n      {\n        for (Index j = 0; j < nrhs; j++)\n        {\n          InnerIterator it(*this, fsupc);\n          ++it; // Skip the diagonal element\n          for (; it; ++it)\n          {\n            irow = it.row();\n            X(irow, j) -= X(fsupc, j) * it.value();\n          }\n        }\n      }\n      else\n      {\n        // The supernode has more than one column \n        Index luptr = colIndexPtr()[fsupc]; \n        Index lda = colIndexPtr()[fsupc+1] - luptr;\n        \n        // Triangular solve \n        Map<const Matrix<Scalar,Dynamic,Dynamic, ColMajor>, 0, OuterStride<> > A( &(Lval[luptr]), nsupc, nsupc, OuterStride<>(lda) );\n        Map< Matrix<Scalar,Dynamic,Dest::ColsAtCompileTime, ColMajor>, 0, OuterStride<> > U (&(X(fsupc,0)), nsupc, nrhs, OuterStride<>(n) );\n        U = A.template triangularView<UnitLower>().solve(U); \n        \n        // Matrix-vector product \n        new (&A) Map<const Matrix<Scalar,Dynamic,Dynamic, ColMajor>, 0, OuterStride<> > ( &(Lval[luptr+nsupc]), nrow, nsupc, OuterStride<>(lda) );\n        work.topRows(nrow).noalias() = A * U;\n        \n        //Begin Scatter \n        for (Index j = 0; j < nrhs; j++)\n        {\n          Index iptr = istart + nsupc; \n          for (Index i = 0; i < nrow; i++)\n          {\n            irow = rowIndex()[iptr]; \n            X(irow, j) -= work(i, j); // Scatter operation\n            work(i, j) = Scalar(0); \n            iptr++;\n          }\n        }\n      }\n    } \n}\n\ntemplate<typename Scalar, typename Index_>\ntemplate<bool Conjugate, typename Dest>\nvoid MappedSuperNodalMatrix<Scalar,Index_>::solveTransposedInPlace( MatrixBase<Dest>&X) const\n{\n    using numext::conj;\n  Index n    = int(X.rows());\n  Index nrhs = Index(X.cols());\n  const Scalar * Lval = valuePtr();                 // Nonzero values\n  Matrix<Scalar,Dynamic,Dest::ColsAtCompileTime, ColMajor> work(n, nrhs);     // working vector\n  work.setZero();\n  for (Index k = nsuper(); k >= 0; k--)\n  {\n    Index fsupc = supToCol()[k];                    // First column of the current supernode\n    Index istart = rowIndexPtr()[fsupc];            // Pointer index to the subscript of the current column\n    Index nsupr = rowIndexPtr()[fsupc+1] - istart;  // Number of rows in the current supernode\n    Index nsupc = supToCol()[k+1] - fsupc;          // Number of columns in the current supernode\n    Index nrow = nsupr - nsupc;                     // Number of rows in the non-diagonal part of the supernode\n    Index irow;                                     //Current index row\n\n    if (nsupc == 1 )\n    {\n      for (Index j = 0; j < nrhs; j++)\n      {\n        InnerIterator it(*this, fsupc);\n        ++it; // Skip the diagonal element\n        for (; it; ++it)\n        {\n          irow = it.row();\n          X(fsupc,j) -= X(irow, j) * (Conjugate?conj(it.value()):it.value());\n        }\n      }\n    }\n    else\n    {\n      // The supernode has more than one column\n      Index luptr = colIndexPtr()[fsupc];\n      Index lda = colIndexPtr()[fsupc+1] - luptr;\n\n      //Begin Gather\n      for (Index j = 0; j < nrhs; j++)\n      {\n        Index iptr = istart + nsupc;\n        for (Index i = 0; i < nrow; i++)\n        {\n          irow = rowIndex()[iptr];\n          work.topRows(nrow)(i,j)= X(irow,j); // Gather operation\n          iptr++;\n        }\n      }\n\n      // Matrix-vector product with transposed submatrix\n      Map<const Matrix<Scalar,Dynamic,Dynamic, ColMajor>, 0, OuterStride<> > A( &(Lval[luptr+nsupc]), nrow, nsupc, OuterStride<>(lda) );\n      Map< Matrix<Scalar,Dynamic,Dest::ColsAtCompileTime, ColMajor>, 0, OuterStride<> > U (&(X(fsupc,0)), nsupc, nrhs, OuterStride<>(n) );\n      if(Conjugate)\n        U = U - A.adjoint() * work.topRows(nrow);\n      else\n        U = U - A.transpose() * work.topRows(nrow);\n\n      // Triangular solve (of transposed diagonal block)\n      new (&A) Map<const Matrix<Scalar,Dynamic,Dynamic, ColMajor>, 0, OuterStride<> > ( &(Lval[luptr]), nsupc, nsupc, OuterStride<>(lda) );\n      if(Conjugate)\n        U = A.adjoint().template triangularView<UnitUpper>().solve(U);\n      else\n        U = A.transpose().template triangularView<UnitUpper>().solve(U);\n\n    }\n\n  }\n}\n\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSELU_MATRIX_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseLU/SparseLU_Utils.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#ifndef EIGEN_SPARSELU_UTILS_H\n#define EIGEN_SPARSELU_UTILS_H\n\nnamespace Eigen {\nnamespace internal {\n\n/**\n * \\brief Count Nonzero elements in the factors\n */\ntemplate <typename Scalar, typename StorageIndex>\nvoid SparseLUImpl<Scalar,StorageIndex>::countnz(const Index n, Index& nnzL, Index& nnzU, GlobalLU_t& glu)\n{\n nnzL = 0; \n nnzU = (glu.xusub)(n); \n Index nsuper = (glu.supno)(n); \n Index jlen; \n Index i, j, fsupc;\n if (n <= 0 ) return; \n // For each supernode\n for (i = 0; i <= nsuper; i++)\n {\n   fsupc = glu.xsup(i); \n   jlen = glu.xlsub(fsupc+1) - glu.xlsub(fsupc); \n   \n   for (j = fsupc; j < glu.xsup(i+1); j++)\n   {\n     nnzL += jlen; \n     nnzU += j - fsupc + 1; \n     jlen--; \n   }\n }\n}\n\n/**\n * \\brief Fix up the data storage lsub for L-subscripts. \n * \n * It removes the subscripts sets for structural pruning, \n * and applies permutation to the remaining subscripts\n * \n */\ntemplate <typename Scalar, typename StorageIndex>\nvoid SparseLUImpl<Scalar,StorageIndex>::fixupL(const Index n, const IndexVector& perm_r, GlobalLU_t& glu)\n{\n  Index fsupc, i, j, k, jstart; \n  \n  StorageIndex nextl = 0; \n  Index nsuper = (glu.supno)(n); \n  \n  // For each supernode \n  for (i = 0; i <= nsuper; i++)\n  {\n    fsupc = glu.xsup(i); \n    jstart = glu.xlsub(fsupc); \n    glu.xlsub(fsupc) = nextl; \n    for (j = jstart; j < glu.xlsub(fsupc + 1); j++)\n    {\n      glu.lsub(nextl) = perm_r(glu.lsub(j)); // Now indexed into P*A\n      nextl++;\n    }\n    for (k = fsupc+1; k < glu.xsup(i+1); k++)\n      glu.xlsub(k) = nextl; // other columns in supernode i\n  }\n  \n  glu.xlsub(n) = nextl; \n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n#endif // EIGEN_SPARSELU_UTILS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseLU/SparseLU_column_bmod.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/* \n \n * NOTE: This file is the modified version of xcolumn_bmod.c file in SuperLU \n \n * -- SuperLU routine (version 3.0) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * October 15, 2003\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n#ifndef SPARSELU_COLUMN_BMOD_H\n#define SPARSELU_COLUMN_BMOD_H\n\nnamespace Eigen {\n\nnamespace internal {\n/**\n * \\brief Performs numeric block updates (sup-col) in topological order\n * \n * \\param jcol current column to update\n * \\param nseg Number of segments in the U part\n * \\param dense Store the full representation of the column\n * \\param tempv working array \n * \\param segrep segment representative ...\n * \\param repfnz ??? First nonzero column in each row ???  ...\n * \\param fpanelc First column in the current panel\n * \\param glu Global LU data. \n * \\return 0 - successful return \n *         > 0 - number of bytes allocated when run out of space\n * \n */\ntemplate <typename Scalar, typename StorageIndex>\nIndex SparseLUImpl<Scalar,StorageIndex>::column_bmod(const Index jcol, const Index nseg, BlockScalarVector dense, ScalarVector& tempv,\n                                                     BlockIndexVector segrep, BlockIndexVector repfnz, Index fpanelc, GlobalLU_t& glu)\n{\n  Index  jsupno, k, ksub, krep, ksupno; \n  Index lptr, nrow, isub, irow, nextlu, new_next, ufirst; \n  Index fsupc, nsupc, nsupr, luptr, kfnz, no_zeros; \n  /* krep = representative of current k-th supernode\n    * fsupc =  first supernodal column\n    * nsupc = number of columns in a supernode\n    * nsupr = number of rows in a supernode\n    * luptr = location of supernodal LU-block in storage\n    * kfnz = first nonz in the k-th supernodal segment\n    * no_zeros = no lf leading zeros in a supernodal U-segment\n    */\n  \n  jsupno = glu.supno(jcol);\n  // For each nonzero supernode segment of U[*,j] in topological order \n  k = nseg - 1; \n  Index d_fsupc; // distance between the first column of the current panel and the \n               // first column of the current snode\n  Index fst_col; // First column within small LU update\n  Index segsize; \n  for (ksub = 0; ksub < nseg; ksub++)\n  {\n    krep = segrep(k); k--; \n    ksupno = glu.supno(krep); \n    if (jsupno != ksupno )\n    {\n      // outside the rectangular supernode \n      fsupc = glu.xsup(ksupno); \n      fst_col = (std::max)(fsupc, fpanelc); \n      \n      // Distance from the current supernode to the current panel; \n      // d_fsupc = 0 if fsupc > fpanelc\n      d_fsupc = fst_col - fsupc; \n      \n      luptr = glu.xlusup(fst_col) + d_fsupc; \n      lptr = glu.xlsub(fsupc) + d_fsupc; \n      \n      kfnz = repfnz(krep); \n      kfnz = (std::max)(kfnz, fpanelc); \n      \n      segsize = krep - kfnz + 1; \n      nsupc = krep - fst_col + 1; \n      nsupr = glu.xlsub(fsupc+1) - glu.xlsub(fsupc); \n      nrow = nsupr - d_fsupc - nsupc;\n      Index lda = glu.xlusup(fst_col+1) - glu.xlusup(fst_col);\n      \n      \n      // Perform a triangular solver and block update, \n      // then scatter the result of sup-col update to dense\n      no_zeros = kfnz - fst_col; \n      if(segsize==1)\n        LU_kernel_bmod<1>::run(segsize, dense, tempv, glu.lusup, luptr, lda, nrow, glu.lsub, lptr, no_zeros);\n      else\n        LU_kernel_bmod<Dynamic>::run(segsize, dense, tempv, glu.lusup, luptr, lda, nrow, glu.lsub, lptr, no_zeros);\n    } // end if jsupno \n  } // end for each segment\n  \n  // Process the supernodal portion of  L\\U[*,j]\n  nextlu = glu.xlusup(jcol); \n  fsupc = glu.xsup(jsupno);\n  \n  // copy the SPA dense into L\\U[*,j]\n  Index mem; \n  new_next = nextlu + glu.xlsub(fsupc + 1) - glu.xlsub(fsupc); \n  Index offset = internal::first_multiple<Index>(new_next, internal::packet_traits<Scalar>::size) - new_next;\n  if(offset)\n    new_next += offset;\n  while (new_next > glu.nzlumax )\n  {\n    mem = memXpand<ScalarVector>(glu.lusup, glu.nzlumax, nextlu, LUSUP, glu.num_expansions);  \n    if (mem) return mem; \n  }\n  \n  for (isub = glu.xlsub(fsupc); isub < glu.xlsub(fsupc+1); isub++)\n  {\n    irow = glu.lsub(isub);\n    glu.lusup(nextlu) = dense(irow);\n    dense(irow) = Scalar(0.0); \n    ++nextlu; \n  }\n  \n  if(offset)\n  {\n    glu.lusup.segment(nextlu,offset).setZero();\n    nextlu += offset;\n  }\n  glu.xlusup(jcol + 1) = StorageIndex(nextlu);  // close L\\U(*,jcol); \n  \n  /* For more updates within the panel (also within the current supernode),\n   * should start from the first column of the panel, or the first column\n   * of the supernode, whichever is bigger. There are two cases:\n   *  1) fsupc < fpanelc, then fst_col <-- fpanelc\n   *  2) fsupc >= fpanelc, then fst_col <-- fsupc\n   */\n  fst_col = (std::max)(fsupc, fpanelc); \n  \n  if (fst_col  < jcol)\n  {\n    // Distance between the current supernode and the current panel\n    // d_fsupc = 0 if fsupc >= fpanelc\n    d_fsupc = fst_col - fsupc; \n    \n    lptr = glu.xlsub(fsupc) + d_fsupc; \n    luptr = glu.xlusup(fst_col) + d_fsupc; \n    nsupr = glu.xlsub(fsupc+1) - glu.xlsub(fsupc); // leading dimension\n    nsupc = jcol - fst_col; // excluding jcol \n    nrow = nsupr - d_fsupc - nsupc; \n    \n    // points to the beginning of jcol in snode L\\U(jsupno) \n    ufirst = glu.xlusup(jcol) + d_fsupc; \n    Index lda = glu.xlusup(jcol+1) - glu.xlusup(jcol);\n    MappedMatrixBlock A( &(glu.lusup.data()[luptr]), nsupc, nsupc, OuterStride<>(lda) );\n    VectorBlock<ScalarVector> u(glu.lusup, ufirst, nsupc); \n    u = A.template triangularView<UnitLower>().solve(u); \n    \n    new (&A) MappedMatrixBlock ( &(glu.lusup.data()[luptr+nsupc]), nrow, nsupc, OuterStride<>(lda) );\n    VectorBlock<ScalarVector> l(glu.lusup, ufirst+nsupc, nrow); \n    l.noalias() -= A * u;\n    \n  } // End if fst_col\n  return 0; \n}\n\n} // end namespace internal\n} // end namespace Eigen\n\n#endif // SPARSELU_COLUMN_BMOD_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseLU/SparseLU_column_dfs.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/* \n \n * NOTE: This file is the modified version of [s,d,c,z]column_dfs.c file in SuperLU \n \n * -- SuperLU routine (version 2.0) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * November 15, 1997\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n#ifndef SPARSELU_COLUMN_DFS_H\n#define SPARSELU_COLUMN_DFS_H\n\ntemplate <typename Scalar, typename StorageIndex> class SparseLUImpl;\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate<typename IndexVector, typename ScalarVector>\nstruct column_dfs_traits : no_assignment_operator\n{\n  typedef typename ScalarVector::Scalar Scalar;\n  typedef typename IndexVector::Scalar StorageIndex;\n  column_dfs_traits(Index jcol, Index& jsuper, typename SparseLUImpl<Scalar, StorageIndex>::GlobalLU_t& glu, SparseLUImpl<Scalar, StorageIndex>& luImpl)\n   : m_jcol(jcol), m_jsuper_ref(jsuper), m_glu(glu), m_luImpl(luImpl)\n {}\n  bool update_segrep(Index /*krep*/, Index /*jj*/)\n  {\n    return true;\n  }\n  void mem_expand(IndexVector& lsub, Index& nextl, Index chmark)\n  {\n    if (nextl >= m_glu.nzlmax)\n      m_luImpl.memXpand(lsub, m_glu.nzlmax, nextl, LSUB, m_glu.num_expansions); \n    if (chmark != (m_jcol-1)) m_jsuper_ref = emptyIdxLU;\n  }\n  enum { ExpandMem = true };\n  \n  Index m_jcol;\n  Index& m_jsuper_ref;\n  typename SparseLUImpl<Scalar, StorageIndex>::GlobalLU_t& m_glu;\n  SparseLUImpl<Scalar, StorageIndex>& m_luImpl;\n};\n\n\n/**\n * \\brief Performs a symbolic factorization on column jcol and decide the supernode boundary\n * \n * A supernode representative is the last column of a supernode.\n * The nonzeros in U[*,j] are segments that end at supernodes representatives. \n * The routine returns a list of the supernodal representatives \n * in topological order of the dfs that generates them. \n * The location of the first nonzero in each supernodal segment \n * (supernodal entry location) is also returned. \n * \n * \\param m number of rows in the matrix\n * \\param jcol Current column \n * \\param perm_r Row permutation\n * \\param maxsuper  Maximum number of column allowed in a supernode\n * \\param [in,out] nseg Number of segments in current U[*,j] - new segments appended\n * \\param lsub_col defines the rhs vector to start the dfs\n * \\param [in,out] segrep Segment representatives - new segments appended \n * \\param repfnz  First nonzero location in each row\n * \\param xprune \n * \\param marker  marker[i] == jj, if i was visited during dfs of current column jj;\n * \\param parent\n * \\param xplore working array\n * \\param glu global LU data \n * \\return 0 success\n *         > 0 number of bytes allocated when run out of space\n * \n */\ntemplate <typename Scalar, typename StorageIndex>\nIndex SparseLUImpl<Scalar,StorageIndex>::column_dfs(const Index m, const Index jcol, IndexVector& perm_r, Index maxsuper, Index& nseg,\n                                                    BlockIndexVector lsub_col, IndexVector& segrep, BlockIndexVector repfnz, IndexVector& xprune,\n                                                    IndexVector& marker, IndexVector& parent, IndexVector& xplore, GlobalLU_t& glu)\n{\n  \n  Index jsuper = glu.supno(jcol); \n  Index nextl = glu.xlsub(jcol); \n  VectorBlock<IndexVector> marker2(marker, 2*m, m); \n  \n  \n  column_dfs_traits<IndexVector, ScalarVector> traits(jcol, jsuper, glu, *this);\n  \n  // For each nonzero in A(*,jcol) do dfs \n  for (Index k = 0; ((k < m) ? lsub_col[k] != emptyIdxLU : false) ; k++)\n  {\n    Index krow = lsub_col(k); \n    lsub_col(k) = emptyIdxLU; \n    Index kmark = marker2(krow); \n    \n    // krow was visited before, go to the next nonz; \n    if (kmark == jcol) continue;\n    \n    dfs_kernel(StorageIndex(jcol), perm_r, nseg, glu.lsub, segrep, repfnz, xprune, marker2, parent,\n                   xplore, glu, nextl, krow, traits);\n  } // for each nonzero ... \n  \n  Index fsupc;\n  StorageIndex nsuper = glu.supno(jcol);\n  StorageIndex jcolp1 = StorageIndex(jcol) + 1;\n  Index jcolm1 = jcol - 1;\n  \n  // check to see if j belongs in the same supernode as j-1\n  if ( jcol == 0 )\n  { // Do nothing for column 0 \n    nsuper = glu.supno(0) = 0 ;\n  }\n  else \n  {\n    fsupc = glu.xsup(nsuper); \n    StorageIndex jptr = glu.xlsub(jcol); // Not yet compressed\n    StorageIndex jm1ptr = glu.xlsub(jcolm1); \n    \n    // Use supernodes of type T2 : see SuperLU paper\n    if ( (nextl-jptr != jptr-jm1ptr-1) ) jsuper = emptyIdxLU;\n    \n    // Make sure the number of columns in a supernode doesn't\n    // exceed threshold\n    if ( (jcol - fsupc) >= maxsuper) jsuper = emptyIdxLU; \n    \n    /* If jcol starts a new supernode, reclaim storage space in\n     * glu.lsub from previous supernode. Note we only store \n     * the subscript set of the first and last columns of \n     * a supernode. (first for num values, last for pruning)\n     */\n    if (jsuper == emptyIdxLU)\n    { // starts a new supernode \n      if ( (fsupc < jcolm1-1) ) \n      { // >= 3 columns in nsuper\n        StorageIndex ito = glu.xlsub(fsupc+1);\n        glu.xlsub(jcolm1) = ito; \n        StorageIndex istop = ito + jptr - jm1ptr; \n        xprune(jcolm1) = istop; // initialize xprune(jcol-1)\n        glu.xlsub(jcol) = istop; \n        \n        for (StorageIndex ifrom = jm1ptr; ifrom < nextl; ++ifrom, ++ito)\n          glu.lsub(ito) = glu.lsub(ifrom); \n        nextl = ito;  // = istop + length(jcol)\n      }\n      nsuper++; \n      glu.supno(jcol) = nsuper; \n    } // if a new supernode \n  } // end else:  jcol > 0\n  \n  // Tidy up the pointers before exit\n  glu.xsup(nsuper+1) = jcolp1; \n  glu.supno(jcolp1) = nsuper; \n  xprune(jcol) = StorageIndex(nextl);  // Initialize upper bound for pruning\n  glu.xlsub(jcolp1) = StorageIndex(nextl); \n  \n  return 0; \n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseLU/SparseLU_copy_to_ucol.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n/* \n \n * NOTE: This file is the modified version of [s,d,c,z]copy_to_ucol.c file in SuperLU \n \n * -- SuperLU routine (version 2.0) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * November 15, 1997\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n#ifndef SPARSELU_COPY_TO_UCOL_H\n#define SPARSELU_COPY_TO_UCOL_H\n\nnamespace Eigen {\nnamespace internal {\n\n/**\n * \\brief Performs numeric block updates (sup-col) in topological order\n * \n * \\param jcol current column to update\n * \\param nseg Number of segments in the U part\n * \\param segrep segment representative ...\n * \\param repfnz First nonzero column in each row  ...\n * \\param perm_r Row permutation \n * \\param dense Store the full representation of the column\n * \\param glu Global LU data. \n * \\return 0 - successful return \n *         > 0 - number of bytes allocated when run out of space\n * \n */\ntemplate <typename Scalar, typename StorageIndex>\nIndex SparseLUImpl<Scalar,StorageIndex>::copy_to_ucol(const Index jcol, const Index nseg, IndexVector& segrep,\n                                                      BlockIndexVector repfnz ,IndexVector& perm_r, BlockScalarVector dense, GlobalLU_t& glu)\n{  \n  Index ksub, krep, ksupno; \n    \n  Index jsupno = glu.supno(jcol);\n  \n  // For each nonzero supernode segment of U[*,j] in topological order \n  Index k = nseg - 1, i; \n  StorageIndex nextu = glu.xusub(jcol); \n  Index kfnz, isub, segsize; \n  Index new_next,irow; \n  Index fsupc, mem; \n  for (ksub = 0; ksub < nseg; ksub++)\n  {\n    krep = segrep(k); k--; \n    ksupno = glu.supno(krep); \n    if (jsupno != ksupno ) // should go into ucol(); \n    {\n      kfnz = repfnz(krep); \n      if (kfnz != emptyIdxLU)\n      { // Nonzero U-segment \n        fsupc = glu.xsup(ksupno); \n        isub = glu.xlsub(fsupc) + kfnz - fsupc; \n        segsize = krep - kfnz + 1; \n        new_next = nextu + segsize; \n        while (new_next > glu.nzumax) \n        {\n          mem = memXpand<ScalarVector>(glu.ucol, glu.nzumax, nextu, UCOL, glu.num_expansions); \n          if (mem) return mem; \n          mem = memXpand<IndexVector>(glu.usub, glu.nzumax, nextu, USUB, glu.num_expansions); \n          if (mem) return mem; \n          \n        }\n        \n        for (i = 0; i < segsize; i++)\n        {\n          irow = glu.lsub(isub); \n          glu.usub(nextu) = perm_r(irow); // Unlike the L part, the U part is stored in its final order\n          glu.ucol(nextu) = dense(irow); \n          dense(irow) = Scalar(0.0); \n          nextu++;\n          isub++;\n        }\n        \n      } // end nonzero U-segment \n      \n    } // end if jsupno \n    \n  } // end for each segment\n  glu.xusub(jcol + 1) = nextu; // close U(*,jcol)\n  return 0; \n}\n\n} // namespace internal\n} // end namespace Eigen\n\n#endif // SPARSELU_COPY_TO_UCOL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseLU/SparseLU_gemm_kernel.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSELU_GEMM_KERNEL_H\n#define EIGEN_SPARSELU_GEMM_KERNEL_H\n\nnamespace Eigen {\n\nnamespace internal {\n\n\n/** \\internal\n  * A general matrix-matrix product kernel optimized for the SparseLU factorization.\n  *  - A, B, and C must be column major\n  *  - lda and ldc must be multiples of the respective packet size\n  *  - C must have the same alignment as A\n  */\ntemplate<typename Scalar>\nEIGEN_DONT_INLINE\nvoid sparselu_gemm(Index m, Index n, Index d, const Scalar* A, Index lda, const Scalar* B, Index ldb, Scalar* C, Index ldc)\n{\n  using namespace Eigen::internal;\n  \n  typedef typename packet_traits<Scalar>::type Packet;\n  enum {\n    NumberOfRegisters = EIGEN_ARCH_DEFAULT_NUMBER_OF_REGISTERS,\n    PacketSize = packet_traits<Scalar>::size,\n    PM = 8,                             // peeling in M\n    RN = 2,                             // register blocking\n    RK = NumberOfRegisters>=16 ? 4 : 2, // register blocking\n    BM = 4096/sizeof(Scalar),           // number of rows of A-C per chunk\n    SM = PM*PacketSize                  // step along M\n  };\n  Index d_end = (d/RK)*RK;    // number of columns of A (rows of B) suitable for full register blocking\n  Index n_end = (n/RN)*RN;    // number of columns of B-C suitable for processing RN columns at once\n  Index i0 = internal::first_default_aligned(A,m);\n  \n  eigen_internal_assert(((lda%PacketSize)==0) && ((ldc%PacketSize)==0) && (i0==internal::first_default_aligned(C,m)));\n  \n  // handle the non aligned rows of A and C without any optimization:\n  for(Index i=0; i<i0; ++i)\n  {\n    for(Index j=0; j<n; ++j)\n    {\n      Scalar c = C[i+j*ldc];\n      for(Index k=0; k<d; ++k)\n        c += B[k+j*ldb] * A[i+k*lda];\n      C[i+j*ldc] = c;\n    }\n  }\n  // process the remaining rows per chunk of BM rows\n  for(Index ib=i0; ib<m; ib+=BM)\n  {\n    Index actual_b = std::min<Index>(BM, m-ib);                 // actual number of rows\n    Index actual_b_end1 = (actual_b/SM)*SM;                   // actual number of rows suitable for peeling\n    Index actual_b_end2 = (actual_b/PacketSize)*PacketSize;   // actual number of rows suitable for vectorization\n    \n    // Let's process two columns of B-C at once\n    for(Index j=0; j<n_end; j+=RN)\n    {\n      const Scalar* Bc0 = B+(j+0)*ldb;\n      const Scalar* Bc1 = B+(j+1)*ldb;\n      \n      for(Index k=0; k<d_end; k+=RK)\n      {\n        \n        // load and expand a RN x RK block of B\n        Packet b00, b10, b20, b30, b01, b11, b21, b31;\n                  { b00 = pset1<Packet>(Bc0[0]); }\n                  { b10 = pset1<Packet>(Bc0[1]); }\n        if(RK==4) { b20 = pset1<Packet>(Bc0[2]); }\n        if(RK==4) { b30 = pset1<Packet>(Bc0[3]); }\n                  { b01 = pset1<Packet>(Bc1[0]); }\n                  { b11 = pset1<Packet>(Bc1[1]); }\n        if(RK==4) { b21 = pset1<Packet>(Bc1[2]); }\n        if(RK==4) { b31 = pset1<Packet>(Bc1[3]); }\n        \n        Packet a0, a1, a2, a3, c0, c1, t0, t1;\n        \n        const Scalar* A0 = A+ib+(k+0)*lda;\n        const Scalar* A1 = A+ib+(k+1)*lda;\n        const Scalar* A2 = A+ib+(k+2)*lda;\n        const Scalar* A3 = A+ib+(k+3)*lda;\n        \n        Scalar* C0 = C+ib+(j+0)*ldc;\n        Scalar* C1 = C+ib+(j+1)*ldc;\n        \n                  a0 = pload<Packet>(A0);\n                  a1 = pload<Packet>(A1);\n        if(RK==4)\n        {\n          a2 = pload<Packet>(A2);\n          a3 = pload<Packet>(A3);\n        }\n        else\n        {\n          // workaround \"may be used uninitialized in this function\" warning\n          a2 = a3 = a0;\n        }\n        \n#define KMADD(c, a, b, tmp) {tmp = b; tmp = pmul(a,tmp); c = padd(c,tmp);}\n#define WORK(I)  \\\n                     c0 = pload<Packet>(C0+i+(I)*PacketSize);    \\\n                     c1 = pload<Packet>(C1+i+(I)*PacketSize);    \\\n                     KMADD(c0, a0, b00, t0)                      \\\n                     KMADD(c1, a0, b01, t1)                      \\\n                     a0 = pload<Packet>(A0+i+(I+1)*PacketSize);  \\\n                     KMADD(c0, a1, b10, t0)                      \\\n                     KMADD(c1, a1, b11, t1)                      \\\n                     a1 = pload<Packet>(A1+i+(I+1)*PacketSize);  \\\n          if(RK==4){ KMADD(c0, a2, b20, t0)                     }\\\n          if(RK==4){ KMADD(c1, a2, b21, t1)                     }\\\n          if(RK==4){ a2 = pload<Packet>(A2+i+(I+1)*PacketSize); }\\\n          if(RK==4){ KMADD(c0, a3, b30, t0)                     }\\\n          if(RK==4){ KMADD(c1, a3, b31, t1)                     }\\\n          if(RK==4){ a3 = pload<Packet>(A3+i+(I+1)*PacketSize); }\\\n                     pstore(C0+i+(I)*PacketSize, c0);            \\\n                     pstore(C1+i+(I)*PacketSize, c1)\n        \n        // process rows of A' - C' with aggressive vectorization and peeling \n        for(Index i=0; i<actual_b_end1; i+=PacketSize*8)\n        {\n          EIGEN_ASM_COMMENT(\"SPARSELU_GEMML_KERNEL1\");\n                    prefetch((A0+i+(5)*PacketSize));\n                    prefetch((A1+i+(5)*PacketSize));\n          if(RK==4) prefetch((A2+i+(5)*PacketSize));\n          if(RK==4) prefetch((A3+i+(5)*PacketSize));\n\n          WORK(0);\n          WORK(1);\n          WORK(2);\n          WORK(3);\n          WORK(4);\n          WORK(5);\n          WORK(6);\n          WORK(7);\n        }\n        // process the remaining rows with vectorization only\n        for(Index i=actual_b_end1; i<actual_b_end2; i+=PacketSize)\n        {\n          WORK(0);\n        }\n#undef WORK\n        // process the remaining rows without vectorization\n        for(Index i=actual_b_end2; i<actual_b; ++i)\n        {\n          if(RK==4)\n          {\n            C0[i] += A0[i]*Bc0[0]+A1[i]*Bc0[1]+A2[i]*Bc0[2]+A3[i]*Bc0[3];\n            C1[i] += A0[i]*Bc1[0]+A1[i]*Bc1[1]+A2[i]*Bc1[2]+A3[i]*Bc1[3];\n          }\n          else\n          {\n            C0[i] += A0[i]*Bc0[0]+A1[i]*Bc0[1];\n            C1[i] += A0[i]*Bc1[0]+A1[i]*Bc1[1];\n          }\n        }\n        \n        Bc0 += RK;\n        Bc1 += RK;\n      } // peeled loop on k\n    } // peeled loop on the columns j\n    // process the last column (we now perform a matrix-vector product)\n    if((n-n_end)>0)\n    {\n      const Scalar* Bc0 = B+(n-1)*ldb;\n      \n      for(Index k=0; k<d_end; k+=RK)\n      {\n        \n        // load and expand a 1 x RK block of B\n        Packet b00, b10, b20, b30;\n                  b00 = pset1<Packet>(Bc0[0]);\n                  b10 = pset1<Packet>(Bc0[1]);\n        if(RK==4) b20 = pset1<Packet>(Bc0[2]);\n        if(RK==4) b30 = pset1<Packet>(Bc0[3]);\n        \n        Packet a0, a1, a2, a3, c0, t0/*, t1*/;\n        \n        const Scalar* A0 = A+ib+(k+0)*lda;\n        const Scalar* A1 = A+ib+(k+1)*lda;\n        const Scalar* A2 = A+ib+(k+2)*lda;\n        const Scalar* A3 = A+ib+(k+3)*lda;\n        \n        Scalar* C0 = C+ib+(n_end)*ldc;\n        \n                  a0 = pload<Packet>(A0);\n                  a1 = pload<Packet>(A1);\n        if(RK==4)\n        {\n          a2 = pload<Packet>(A2);\n          a3 = pload<Packet>(A3);\n        }\n        else\n        {\n          // workaround \"may be used uninitialized in this function\" warning\n          a2 = a3 = a0;\n        }\n        \n#define WORK(I) \\\n                   c0 = pload<Packet>(C0+i+(I)*PacketSize);     \\\n                   KMADD(c0, a0, b00, t0)                       \\\n                   a0 = pload<Packet>(A0+i+(I+1)*PacketSize);   \\\n                   KMADD(c0, a1, b10, t0)                       \\\n                   a1 = pload<Packet>(A1+i+(I+1)*PacketSize);   \\\n        if(RK==4){ KMADD(c0, a2, b20, t0)                      }\\\n        if(RK==4){ a2 = pload<Packet>(A2+i+(I+1)*PacketSize);  }\\\n        if(RK==4){ KMADD(c0, a3, b30, t0)                      }\\\n        if(RK==4){ a3 = pload<Packet>(A3+i+(I+1)*PacketSize);  }\\\n                   pstore(C0+i+(I)*PacketSize, c0);\n        \n        // aggressive vectorization and peeling\n        for(Index i=0; i<actual_b_end1; i+=PacketSize*8)\n        {\n          EIGEN_ASM_COMMENT(\"SPARSELU_GEMML_KERNEL2\");\n          WORK(0);\n          WORK(1);\n          WORK(2);\n          WORK(3);\n          WORK(4);\n          WORK(5);\n          WORK(6);\n          WORK(7);\n        }\n        // vectorization only\n        for(Index i=actual_b_end1; i<actual_b_end2; i+=PacketSize)\n        {\n          WORK(0);\n        }\n        // remaining scalars\n        for(Index i=actual_b_end2; i<actual_b; ++i)\n        {\n          if(RK==4) \n            C0[i] += A0[i]*Bc0[0]+A1[i]*Bc0[1]+A2[i]*Bc0[2]+A3[i]*Bc0[3];\n          else\n            C0[i] += A0[i]*Bc0[0]+A1[i]*Bc0[1];\n        }\n        \n        Bc0 += RK;\n#undef WORK\n      }\n    }\n    \n    // process the last columns of A, corresponding to the last rows of B\n    Index rd = d-d_end;\n    if(rd>0)\n    {\n      for(Index j=0; j<n; ++j)\n      {\n        enum {\n          Alignment = PacketSize>1 ? Aligned : 0\n        };\n        typedef Map<Matrix<Scalar,Dynamic,1>, Alignment > MapVector;\n        typedef Map<const Matrix<Scalar,Dynamic,1>, Alignment > ConstMapVector;\n        if(rd==1)       MapVector(C+j*ldc+ib,actual_b) += B[0+d_end+j*ldb] * ConstMapVector(A+(d_end+0)*lda+ib, actual_b);\n        \n        else if(rd==2)  MapVector(C+j*ldc+ib,actual_b) += B[0+d_end+j*ldb] * ConstMapVector(A+(d_end+0)*lda+ib, actual_b)\n                                                        + B[1+d_end+j*ldb] * ConstMapVector(A+(d_end+1)*lda+ib, actual_b);\n        \n        else            MapVector(C+j*ldc+ib,actual_b) += B[0+d_end+j*ldb] * ConstMapVector(A+(d_end+0)*lda+ib, actual_b)\n                                                        + B[1+d_end+j*ldb] * ConstMapVector(A+(d_end+1)*lda+ib, actual_b)\n                                                        + B[2+d_end+j*ldb] * ConstMapVector(A+(d_end+2)*lda+ib, actual_b);\n      }\n    }\n  \n  } // blocking on the rows of A and C\n}\n#undef KMADD\n\n} // namespace internal\n\n} // namespace Eigen\n\n#endif // EIGEN_SPARSELU_GEMM_KERNEL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseLU/SparseLU_heap_relax_snode.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/* This file is a modified version of heap_relax_snode.c file in SuperLU\n * -- SuperLU routine (version 3.0) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * October 15, 2003\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n\n#ifndef SPARSELU_HEAP_RELAX_SNODE_H\n#define SPARSELU_HEAP_RELAX_SNODE_H\n\nnamespace Eigen {\nnamespace internal {\n\n/** \n * \\brief Identify the initial relaxed supernodes\n * \n * This routine applied to a symmetric elimination tree. \n * It assumes that the matrix has been reordered according to the postorder of the etree\n * \\param n The number of columns\n * \\param et elimination tree \n * \\param relax_columns Maximum number of columns allowed in a relaxed snode \n * \\param descendants Number of descendants of each node in the etree\n * \\param relax_end last column in a supernode\n */\ntemplate <typename Scalar, typename StorageIndex>\nvoid SparseLUImpl<Scalar,StorageIndex>::heap_relax_snode (const Index n, IndexVector& et, const Index relax_columns, IndexVector& descendants, IndexVector& relax_end)\n{\n  \n  // The etree may not be postordered, but its heap ordered  \n  IndexVector post;\n  internal::treePostorder(StorageIndex(n), et, post); // Post order etree\n  IndexVector inv_post(n+1); \n  for (StorageIndex i = 0; i < n+1; ++i) inv_post(post(i)) = i; // inv_post = post.inverse()???\n  \n  // Renumber etree in postorder \n  IndexVector iwork(n);\n  IndexVector et_save(n+1);\n  for (Index i = 0; i < n; ++i)\n  {\n    iwork(post(i)) = post(et(i));\n  }\n  et_save = et; // Save the original etree\n  et = iwork; \n  \n  // compute the number of descendants of each node in the etree\n  relax_end.setConstant(emptyIdxLU);\n  Index j, parent; \n  descendants.setZero();\n  for (j = 0; j < n; j++) \n  {\n    parent = et(j);\n    if (parent != n) // not the dummy root\n      descendants(parent) += descendants(j) + 1;\n  }\n  // Identify the relaxed supernodes by postorder traversal of the etree\n  Index snode_start; // beginning of a snode \n  StorageIndex k;\n  Index nsuper_et_post = 0; // Number of relaxed snodes in postordered etree \n  Index nsuper_et = 0; // Number of relaxed snodes in the original etree \n  StorageIndex l; \n  for (j = 0; j < n; )\n  {\n    parent = et(j);\n    snode_start = j; \n    while ( parent != n && descendants(parent) < relax_columns ) \n    {\n      j = parent; \n      parent = et(j);\n    }\n    // Found a supernode in postordered etree, j is the last column \n    ++nsuper_et_post;\n    k = StorageIndex(n);\n    for (Index i = snode_start; i <= j; ++i)\n      k = (std::min)(k, inv_post(i));\n    l = inv_post(j);\n    if ( (l - k) == (j - snode_start) )  // Same number of columns in the snode\n    {\n      // This is also a supernode in the original etree\n      relax_end(k) = l; // Record last column \n      ++nsuper_et; \n    }\n    else \n    {\n      for (Index i = snode_start; i <= j; ++i) \n      {\n        l = inv_post(i);\n        if (descendants(i) == 0) \n        {\n          relax_end(l) = l;\n          ++nsuper_et;\n        }\n      }\n    }\n    j++;\n    // Search for a new leaf\n    while (descendants(j) != 0 && j < n) j++;\n  } // End postorder traversal of the etree\n  \n  // Recover the original etree\n  et = et_save; \n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n#endif // SPARSELU_HEAP_RELAX_SNODE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseLU/SparseLU_kernel_bmod.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef SPARSELU_KERNEL_BMOD_H\n#define SPARSELU_KERNEL_BMOD_H\n\nnamespace Eigen {\nnamespace internal {\n  \ntemplate <int SegSizeAtCompileTime> struct LU_kernel_bmod\n{\n  /** \\internal\n    * \\brief Performs numeric block updates from a given supernode to a single column\n    *\n    * \\param segsize Size of the segment (and blocks ) to use for updates\n    * \\param[in,out] dense Packed values of the original matrix\n    * \\param tempv temporary vector to use for updates\n    * \\param lusup array containing the supernodes\n    * \\param lda Leading dimension in the supernode\n    * \\param nrow Number of rows in the rectangular part of the supernode\n    * \\param lsub compressed row subscripts of supernodes\n    * \\param lptr pointer to the first column of the current supernode in lsub\n    * \\param no_zeros Number of nonzeros elements before the diagonal part of the supernode\n    */\n  template <typename BlockScalarVector, typename ScalarVector, typename IndexVector>\n  static EIGEN_DONT_INLINE void run(const Index segsize, BlockScalarVector& dense, ScalarVector& tempv, ScalarVector& lusup, Index& luptr, const Index lda,\n                                    const Index nrow, IndexVector& lsub, const Index lptr, const Index no_zeros);\n};\n\ntemplate <int SegSizeAtCompileTime>\ntemplate <typename BlockScalarVector, typename ScalarVector, typename IndexVector>\nEIGEN_DONT_INLINE void LU_kernel_bmod<SegSizeAtCompileTime>::run(const Index segsize, BlockScalarVector& dense, ScalarVector& tempv, ScalarVector& lusup, Index& luptr, const Index lda,\n                                                                  const Index nrow, IndexVector& lsub, const Index lptr, const Index no_zeros)\n{\n  typedef typename ScalarVector::Scalar Scalar;\n  // First, copy U[*,j] segment from dense(*) to tempv(*)\n  // The result of triangular solve is in tempv[*]; \n    // The result of matric-vector update is in dense[*]\n  Index isub = lptr + no_zeros; \n  Index i;\n  Index irow;\n  for (i = 0; i < ((SegSizeAtCompileTime==Dynamic)?segsize:SegSizeAtCompileTime); i++)\n  {\n    irow = lsub(isub); \n    tempv(i) = dense(irow); \n    ++isub; \n  }\n  // Dense triangular solve -- start effective triangle\n  luptr += lda * no_zeros + no_zeros; \n  // Form Eigen matrix and vector \n  Map<Matrix<Scalar,SegSizeAtCompileTime,SegSizeAtCompileTime, ColMajor>, 0, OuterStride<> > A( &(lusup.data()[luptr]), segsize, segsize, OuterStride<>(lda) );\n  Map<Matrix<Scalar,SegSizeAtCompileTime,1> > u(tempv.data(), segsize);\n  \n  u = A.template triangularView<UnitLower>().solve(u); \n  \n  // Dense matrix-vector product y <-- B*x \n  luptr += segsize;\n  const Index PacketSize = internal::packet_traits<Scalar>::size;\n  Index ldl = internal::first_multiple(nrow, PacketSize);\n  Map<Matrix<Scalar,Dynamic,SegSizeAtCompileTime, ColMajor>, 0, OuterStride<> > B( &(lusup.data()[luptr]), nrow, segsize, OuterStride<>(lda) );\n  Index aligned_offset = internal::first_default_aligned(tempv.data()+segsize, PacketSize);\n  Index aligned_with_B_offset = (PacketSize-internal::first_default_aligned(B.data(), PacketSize))%PacketSize;\n  Map<Matrix<Scalar,Dynamic,1>, 0, OuterStride<> > l(tempv.data()+segsize+aligned_offset+aligned_with_B_offset, nrow, OuterStride<>(ldl) );\n  \n  l.setZero();\n  internal::sparselu_gemm<Scalar>(l.rows(), l.cols(), B.cols(), B.data(), B.outerStride(), u.data(), u.outerStride(), l.data(), l.outerStride());\n  \n  // Scatter tempv[] into SPA dense[] as a temporary storage \n  isub = lptr + no_zeros;\n  for (i = 0; i < ((SegSizeAtCompileTime==Dynamic)?segsize:SegSizeAtCompileTime); i++)\n  {\n    irow = lsub(isub++); \n    dense(irow) = tempv(i);\n  }\n  \n  // Scatter l into SPA dense[]\n  for (i = 0; i < nrow; i++)\n  {\n    irow = lsub(isub++); \n    dense(irow) -= l(i);\n  } \n}\n\ntemplate <> struct LU_kernel_bmod<1>\n{\n  template <typename BlockScalarVector, typename ScalarVector, typename IndexVector>\n  static EIGEN_DONT_INLINE void run(const Index /*segsize*/, BlockScalarVector& dense, ScalarVector& /*tempv*/, ScalarVector& lusup, Index& luptr,\n                                    const Index lda, const Index nrow, IndexVector& lsub, const Index lptr, const Index no_zeros);\n};\n\n\ntemplate <typename BlockScalarVector, typename ScalarVector, typename IndexVector>\nEIGEN_DONT_INLINE void LU_kernel_bmod<1>::run(const Index /*segsize*/, BlockScalarVector& dense, ScalarVector& /*tempv*/, ScalarVector& lusup, Index& luptr,\n                                              const Index lda, const Index nrow, IndexVector& lsub, const Index lptr, const Index no_zeros)\n{\n  typedef typename ScalarVector::Scalar Scalar;\n  typedef typename IndexVector::Scalar StorageIndex;\n  Scalar f = dense(lsub(lptr + no_zeros));\n  luptr += lda * no_zeros + no_zeros + 1;\n  const Scalar* a(lusup.data() + luptr);\n  const StorageIndex*  irow(lsub.data()+lptr + no_zeros + 1);\n  Index i = 0;\n  for (; i+1 < nrow; i+=2)\n  {\n    Index i0 = *(irow++);\n    Index i1 = *(irow++);\n    Scalar a0 = *(a++);\n    Scalar a1 = *(a++);\n    Scalar d0 = dense.coeff(i0);\n    Scalar d1 = dense.coeff(i1);\n    d0 -= f*a0;\n    d1 -= f*a1;\n    dense.coeffRef(i0) = d0;\n    dense.coeffRef(i1) = d1;\n  }\n  if(i<nrow)\n    dense.coeffRef(*(irow++)) -= f * *(a++);\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n#endif // SPARSELU_KERNEL_BMOD_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseLU/SparseLU_panel_bmod.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/* \n \n * NOTE: This file is the modified version of [s,d,c,z]panel_bmod.c file in SuperLU \n \n * -- SuperLU routine (version 3.0) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * October 15, 2003\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n#ifndef SPARSELU_PANEL_BMOD_H\n#define SPARSELU_PANEL_BMOD_H\n\nnamespace Eigen {\nnamespace internal {\n\n/**\n * \\brief Performs numeric block updates (sup-panel) in topological order.\n * \n * Before entering this routine, the original nonzeros in the panel\n * were already copied into the spa[m,w]\n * \n * \\param m number of rows in the matrix\n * \\param w Panel size\n * \\param jcol Starting  column of the panel\n * \\param nseg Number of segments in the U part\n * \\param dense Store the full representation of the panel \n * \\param tempv working array \n * \\param segrep segment representative... first row in the segment\n * \\param repfnz First nonzero rows\n * \\param glu Global LU data. \n * \n * \n */\ntemplate <typename Scalar, typename StorageIndex>\nvoid SparseLUImpl<Scalar,StorageIndex>::panel_bmod(const Index m, const Index w, const Index jcol, \n                                            const Index nseg, ScalarVector& dense, ScalarVector& tempv,\n                                            IndexVector& segrep, IndexVector& repfnz, GlobalLU_t& glu)\n{\n  \n  Index ksub,jj,nextl_col; \n  Index fsupc, nsupc, nsupr, nrow; \n  Index krep, kfnz; \n  Index lptr; // points to the row subscripts of a supernode \n  Index luptr; // ...\n  Index segsize,no_zeros ; \n  // For each nonz supernode segment of U[*,j] in topological order\n  Index k = nseg - 1; \n  const Index PacketSize = internal::packet_traits<Scalar>::size;\n  \n  for (ksub = 0; ksub < nseg; ksub++)\n  { // For each updating supernode\n    /* krep = representative of current k-th supernode\n     * fsupc =  first supernodal column\n     * nsupc = number of columns in a supernode\n     * nsupr = number of rows in a supernode\n     */\n    krep = segrep(k); k--; \n    fsupc = glu.xsup(glu.supno(krep)); \n    nsupc = krep - fsupc + 1; \n    nsupr = glu.xlsub(fsupc+1) - glu.xlsub(fsupc); \n    nrow = nsupr - nsupc; \n    lptr = glu.xlsub(fsupc); \n    \n    // loop over the panel columns to detect the actual number of columns and rows\n    Index u_rows = 0;\n    Index u_cols = 0;\n    for (jj = jcol; jj < jcol + w; jj++)\n    {\n      nextl_col = (jj-jcol) * m; \n      VectorBlock<IndexVector> repfnz_col(repfnz, nextl_col, m); // First nonzero column index for each row\n      \n      kfnz = repfnz_col(krep); \n      if ( kfnz == emptyIdxLU ) \n        continue; // skip any zero segment\n      \n      segsize = krep - kfnz + 1;\n      u_cols++;\n      u_rows = (std::max)(segsize,u_rows);\n    }\n    \n    if(nsupc >= 2)\n    { \n      Index ldu = internal::first_multiple<Index>(u_rows, PacketSize);\n      Map<ScalarMatrix, Aligned,  OuterStride<> > U(tempv.data(), u_rows, u_cols, OuterStride<>(ldu));\n      \n      // gather U\n      Index u_col = 0;\n      for (jj = jcol; jj < jcol + w; jj++)\n      {\n        nextl_col = (jj-jcol) * m; \n        VectorBlock<IndexVector> repfnz_col(repfnz, nextl_col, m); // First nonzero column index for each row\n        VectorBlock<ScalarVector> dense_col(dense, nextl_col, m); // Scatter/gather entire matrix column from/to here\n        \n        kfnz = repfnz_col(krep); \n        if ( kfnz == emptyIdxLU ) \n          continue; // skip any zero segment\n        \n        segsize = krep - kfnz + 1;\n        luptr = glu.xlusup(fsupc);    \n        no_zeros = kfnz - fsupc; \n        \n        Index isub = lptr + no_zeros;\n        Index off = u_rows-segsize;\n        for (Index i = 0; i < off; i++) U(i,u_col) = 0;\n        for (Index i = 0; i < segsize; i++)\n        {\n          Index irow = glu.lsub(isub); \n          U(i+off,u_col) = dense_col(irow); \n          ++isub; \n        }\n        u_col++;\n      }\n      // solve U = A^-1 U\n      luptr = glu.xlusup(fsupc);\n      Index lda = glu.xlusup(fsupc+1) - glu.xlusup(fsupc);\n      no_zeros = (krep - u_rows + 1) - fsupc;\n      luptr += lda * no_zeros + no_zeros;\n      MappedMatrixBlock A(glu.lusup.data()+luptr, u_rows, u_rows, OuterStride<>(lda) );\n      U = A.template triangularView<UnitLower>().solve(U);\n      \n      // update\n      luptr += u_rows;\n      MappedMatrixBlock B(glu.lusup.data()+luptr, nrow, u_rows, OuterStride<>(lda) );\n      eigen_assert(tempv.size()>w*ldu + nrow*w + 1);\n      \n      Index ldl = internal::first_multiple<Index>(nrow, PacketSize);\n      Index offset = (PacketSize-internal::first_default_aligned(B.data(), PacketSize)) % PacketSize;\n      MappedMatrixBlock L(tempv.data()+w*ldu+offset, nrow, u_cols, OuterStride<>(ldl));\n      \n      L.setZero();\n      internal::sparselu_gemm<Scalar>(L.rows(), L.cols(), B.cols(), B.data(), B.outerStride(), U.data(), U.outerStride(), L.data(), L.outerStride());\n      \n      // scatter U and L\n      u_col = 0;\n      for (jj = jcol; jj < jcol + w; jj++)\n      {\n        nextl_col = (jj-jcol) * m; \n        VectorBlock<IndexVector> repfnz_col(repfnz, nextl_col, m); // First nonzero column index for each row\n        VectorBlock<ScalarVector> dense_col(dense, nextl_col, m); // Scatter/gather entire matrix column from/to here\n        \n        kfnz = repfnz_col(krep); \n        if ( kfnz == emptyIdxLU ) \n          continue; // skip any zero segment\n        \n        segsize = krep - kfnz + 1;\n        no_zeros = kfnz - fsupc; \n        Index isub = lptr + no_zeros;\n        \n        Index off = u_rows-segsize;\n        for (Index i = 0; i < segsize; i++)\n        {\n          Index irow = glu.lsub(isub++); \n          dense_col(irow) = U.coeff(i+off,u_col);\n          U.coeffRef(i+off,u_col) = 0;\n        }\n        \n        // Scatter l into SPA dense[]\n        for (Index i = 0; i < nrow; i++)\n        {\n          Index irow = glu.lsub(isub++); \n          dense_col(irow) -= L.coeff(i,u_col);\n          L.coeffRef(i,u_col) = 0;\n        }\n        u_col++;\n      }\n    }\n    else // level 2 only\n    {\n      // Sequence through each column in the panel\n      for (jj = jcol; jj < jcol + w; jj++)\n      {\n        nextl_col = (jj-jcol) * m; \n        VectorBlock<IndexVector> repfnz_col(repfnz, nextl_col, m); // First nonzero column index for each row\n        VectorBlock<ScalarVector> dense_col(dense, nextl_col, m); // Scatter/gather entire matrix column from/to here\n        \n        kfnz = repfnz_col(krep); \n        if ( kfnz == emptyIdxLU ) \n          continue; // skip any zero segment\n        \n        segsize = krep - kfnz + 1;\n        luptr = glu.xlusup(fsupc);\n        \n        Index lda = glu.xlusup(fsupc+1)-glu.xlusup(fsupc);// nsupr\n        \n        // Perform a trianglar solve and block update, \n        // then scatter the result of sup-col update to dense[]\n        no_zeros = kfnz - fsupc; \n              if(segsize==1)  LU_kernel_bmod<1>::run(segsize, dense_col, tempv, glu.lusup, luptr, lda, nrow, glu.lsub, lptr, no_zeros);\n        else  if(segsize==2)  LU_kernel_bmod<2>::run(segsize, dense_col, tempv, glu.lusup, luptr, lda, nrow, glu.lsub, lptr, no_zeros);\n        else  if(segsize==3)  LU_kernel_bmod<3>::run(segsize, dense_col, tempv, glu.lusup, luptr, lda, nrow, glu.lsub, lptr, no_zeros);\n        else                  LU_kernel_bmod<Dynamic>::run(segsize, dense_col, tempv, glu.lusup, luptr, lda, nrow, glu.lsub, lptr, no_zeros); \n      } // End for each column in the panel \n    }\n    \n  } // End for each updating supernode\n} // end panel bmod\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // SPARSELU_PANEL_BMOD_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseLU/SparseLU_panel_dfs.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/* \n \n * NOTE: This file is the modified version of [s,d,c,z]panel_dfs.c file in SuperLU \n \n * -- SuperLU routine (version 2.0) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * November 15, 1997\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n#ifndef SPARSELU_PANEL_DFS_H\n#define SPARSELU_PANEL_DFS_H\n\nnamespace Eigen {\n\nnamespace internal {\n  \ntemplate<typename IndexVector>\nstruct panel_dfs_traits\n{\n  typedef typename IndexVector::Scalar StorageIndex;\n  panel_dfs_traits(Index jcol, StorageIndex* marker)\n    : m_jcol(jcol), m_marker(marker)\n  {}\n  bool update_segrep(Index krep, StorageIndex jj)\n  {\n    if(m_marker[krep]<m_jcol)\n    {\n      m_marker[krep] = jj; \n      return true;\n    }\n    return false;\n  }\n  void mem_expand(IndexVector& /*glu.lsub*/, Index /*nextl*/, Index /*chmark*/) {}\n  enum { ExpandMem = false };\n  Index m_jcol;\n  StorageIndex* m_marker;\n};\n\n\ntemplate <typename Scalar, typename StorageIndex>\ntemplate <typename Traits>\nvoid SparseLUImpl<Scalar,StorageIndex>::dfs_kernel(const StorageIndex jj, IndexVector& perm_r,\n                   Index& nseg, IndexVector& panel_lsub, IndexVector& segrep,\n                   Ref<IndexVector> repfnz_col, IndexVector& xprune, Ref<IndexVector> marker, IndexVector& parent,\n                   IndexVector& xplore, GlobalLU_t& glu,\n                   Index& nextl_col, Index krow, Traits& traits\n                  )\n{\n  \n  StorageIndex kmark = marker(krow);\n      \n  // For each unmarked krow of jj\n  marker(krow) = jj; \n  StorageIndex kperm = perm_r(krow); \n  if (kperm == emptyIdxLU ) {\n    // krow is in L : place it in structure of L(*, jj)\n    panel_lsub(nextl_col++) = StorageIndex(krow);  // krow is indexed into A\n    \n    traits.mem_expand(panel_lsub, nextl_col, kmark);\n  }\n  else \n  {\n    // krow is in U : if its supernode-representative krep\n    // has been explored, update repfnz(*)\n    // krep = supernode representative of the current row\n    StorageIndex krep = glu.xsup(glu.supno(kperm)+1) - 1; \n    // First nonzero element in the current column:\n    StorageIndex myfnz = repfnz_col(krep); \n    \n    if (myfnz != emptyIdxLU )\n    {\n      // Representative visited before\n      if (myfnz > kperm ) repfnz_col(krep) = kperm; \n      \n    }\n    else \n    {\n      // Otherwise, perform dfs starting at krep\n      StorageIndex oldrep = emptyIdxLU; \n      parent(krep) = oldrep; \n      repfnz_col(krep) = kperm; \n      StorageIndex xdfs =  glu.xlsub(krep); \n      Index maxdfs = xprune(krep); \n      \n      StorageIndex kpar;\n      do \n      {\n        // For each unmarked kchild of krep\n        while (xdfs < maxdfs) \n        {\n          StorageIndex kchild = glu.lsub(xdfs); \n          xdfs++; \n          StorageIndex chmark = marker(kchild); \n          \n          if (chmark != jj ) \n          {\n            marker(kchild) = jj; \n            StorageIndex chperm = perm_r(kchild); \n            \n            if (chperm == emptyIdxLU) \n            {\n              // case kchild is in L: place it in L(*, j)\n              panel_lsub(nextl_col++) = kchild;\n              traits.mem_expand(panel_lsub, nextl_col, chmark);\n            }\n            else\n            {\n              // case kchild is in U :\n              // chrep = its supernode-rep. If its rep has been explored, \n              // update its repfnz(*)\n              StorageIndex chrep = glu.xsup(glu.supno(chperm)+1) - 1; \n              myfnz = repfnz_col(chrep); \n              \n              if (myfnz != emptyIdxLU) \n              { // Visited before \n                if (myfnz > chperm) \n                  repfnz_col(chrep) = chperm; \n              }\n              else \n              { // Cont. dfs at snode-rep of kchild\n                xplore(krep) = xdfs; \n                oldrep = krep; \n                krep = chrep; // Go deeper down G(L)\n                parent(krep) = oldrep; \n                repfnz_col(krep) = chperm; \n                xdfs = glu.xlsub(krep); \n                maxdfs = xprune(krep); \n                \n              } // end if myfnz != -1\n            } // end if chperm == -1 \n                \n          } // end if chmark !=jj\n        } // end while xdfs < maxdfs\n        \n        // krow has no more unexplored nbrs :\n        //    Place snode-rep krep in postorder DFS, if this \n        //    segment is seen for the first time. (Note that \n        //    \"repfnz(krep)\" may change later.)\n        //    Baktrack dfs to its parent\n        if(traits.update_segrep(krep,jj))\n        //if (marker1(krep) < jcol )\n        {\n          segrep(nseg) = krep; \n          ++nseg; \n          //marker1(krep) = jj; \n        }\n        \n        kpar = parent(krep); // Pop recursion, mimic recursion \n        if (kpar == emptyIdxLU) \n          break; // dfs done \n        krep = kpar; \n        xdfs = xplore(krep); \n        maxdfs = xprune(krep); \n\n      } while (kpar != emptyIdxLU); // Do until empty stack \n      \n    } // end if (myfnz = -1)\n\n  } // end if (kperm == -1)   \n}\n\n/**\n * \\brief Performs a symbolic factorization on a panel of columns [jcol, jcol+w)\n * \n * A supernode representative is the last column of a supernode.\n * The nonzeros in U[*,j] are segments that end at supernodes representatives\n * \n * The routine returns a list of the supernodal representatives \n * in topological order of the dfs that generates them. This list is \n * a superset of the topological order of each individual column within \n * the panel.\n * The location of the first nonzero in each supernodal segment \n * (supernodal entry location) is also returned. Each column has \n * a separate list for this purpose. \n * \n * Two markers arrays are used for dfs :\n *    marker[i] == jj, if i was visited during dfs of current column jj;\n *    marker1[i] >= jcol, if i was visited by earlier columns in this panel; \n * \n * \\param[in] m number of rows in the matrix\n * \\param[in] w Panel size\n * \\param[in] jcol Starting  column of the panel\n * \\param[in] A Input matrix in column-major storage\n * \\param[in] perm_r Row permutation\n * \\param[out] nseg Number of U segments\n * \\param[out] dense Accumulate the column vectors of the panel\n * \\param[out] panel_lsub Subscripts of the row in the panel \n * \\param[out] segrep Segment representative i.e first nonzero row of each segment\n * \\param[out] repfnz First nonzero location in each row\n * \\param[out] xprune The pruned elimination tree\n * \\param[out] marker work vector\n * \\param  parent The elimination tree\n * \\param xplore work vector\n * \\param glu The global data structure\n * \n */\n\ntemplate <typename Scalar, typename StorageIndex>\nvoid SparseLUImpl<Scalar,StorageIndex>::panel_dfs(const Index m, const Index w, const Index jcol, MatrixType& A, IndexVector& perm_r, Index& nseg, ScalarVector& dense, IndexVector& panel_lsub, IndexVector& segrep, IndexVector& repfnz, IndexVector& xprune, IndexVector& marker, IndexVector& parent, IndexVector& xplore, GlobalLU_t& glu)\n{\n  Index nextl_col; // Next available position in panel_lsub[*,jj] \n  \n  // Initialize pointers \n  VectorBlock<IndexVector> marker1(marker, m, m); \n  nseg = 0; \n  \n  panel_dfs_traits<IndexVector> traits(jcol, marker1.data());\n  \n  // For each column in the panel \n  for (StorageIndex jj = StorageIndex(jcol); jj < jcol + w; jj++) \n  {\n    nextl_col = (jj - jcol) * m; \n    \n    VectorBlock<IndexVector> repfnz_col(repfnz, nextl_col, m); // First nonzero location in each row\n    VectorBlock<ScalarVector> dense_col(dense,nextl_col, m); // Accumulate a column vector here\n    \n    \n    // For each nnz in A[*, jj] do depth first search\n    for (typename MatrixType::InnerIterator it(A, jj); it; ++it)\n    {\n      Index krow = it.row(); \n      dense_col(krow) = it.value();\n      \n      StorageIndex kmark = marker(krow); \n      if (kmark == jj) \n        continue; // krow visited before, go to the next nonzero\n      \n      dfs_kernel(jj, perm_r, nseg, panel_lsub, segrep, repfnz_col, xprune, marker, parent,\n                   xplore, glu, nextl_col, krow, traits);\n    }// end for nonzeros in column jj\n    \n  } // end for column jj\n}\n\n} // end namespace internal\n} // end namespace Eigen\n\n#endif // SPARSELU_PANEL_DFS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseLU/SparseLU_pivotL.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/* \n \n * NOTE: This file is the modified version of xpivotL.c file in SuperLU \n \n * -- SuperLU routine (version 3.0) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * October 15, 2003\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n#ifndef SPARSELU_PIVOTL_H\n#define SPARSELU_PIVOTL_H\n\nnamespace Eigen {\nnamespace internal {\n  \n/**\n * \\brief Performs the numerical pivotin on the current column of L, and the CDIV operation.\n * \n * Pivot policy :\n * (1) Compute thresh = u * max_(i>=j) abs(A_ij);\n * (2) IF user specifies pivot row k and abs(A_kj) >= thresh THEN\n *           pivot row = k;\n *       ELSE IF abs(A_jj) >= thresh THEN\n *           pivot row = j;\n *       ELSE\n *           pivot row = m;\n * \n *   Note: If you absolutely want to use a given pivot order, then set u=0.0.\n * \n * \\param jcol The current column of L\n * \\param diagpivotthresh diagonal pivoting threshold\n * \\param[in,out] perm_r Row permutation (threshold pivoting)\n * \\param[in] iperm_c column permutation - used to finf diagonal of Pc*A*Pc'\n * \\param[out] pivrow  The pivot row\n * \\param glu Global LU data\n * \\return 0 if success, i > 0 if U(i,i) is exactly zero \n * \n */\ntemplate <typename Scalar, typename StorageIndex>\nIndex SparseLUImpl<Scalar,StorageIndex>::pivotL(const Index jcol, const RealScalar& diagpivotthresh, IndexVector& perm_r, IndexVector& iperm_c, Index& pivrow, GlobalLU_t& glu)\n{\n  \n  Index fsupc = (glu.xsup)((glu.supno)(jcol)); // First column in the supernode containing the column jcol\n  Index nsupc = jcol - fsupc; // Number of columns in the supernode portion, excluding jcol; nsupc >=0\n  Index lptr = glu.xlsub(fsupc); // pointer to the starting location of the row subscripts for this supernode portion\n  Index nsupr = glu.xlsub(fsupc+1) - lptr; // Number of rows in the supernode\n  Index lda = glu.xlusup(fsupc+1) - glu.xlusup(fsupc); // leading dimension\n  Scalar* lu_sup_ptr = &(glu.lusup.data()[glu.xlusup(fsupc)]); // Start of the current supernode\n  Scalar* lu_col_ptr = &(glu.lusup.data()[glu.xlusup(jcol)]); // Start of jcol in the supernode\n  StorageIndex* lsub_ptr = &(glu.lsub.data()[lptr]); // Start of row indices of the supernode\n  \n  // Determine the largest abs numerical value for partial pivoting \n  Index diagind = iperm_c(jcol); // diagonal index \n  RealScalar pivmax(-1.0);\n  Index pivptr = nsupc; \n  Index diag = emptyIdxLU; \n  RealScalar rtemp;\n  Index isub, icol, itemp, k; \n  for (isub = nsupc; isub < nsupr; ++isub) {\n    using std::abs;\n    rtemp = abs(lu_col_ptr[isub]);\n    if (rtemp > pivmax) {\n      pivmax = rtemp; \n      pivptr = isub;\n    } \n    if (lsub_ptr[isub] == diagind) diag = isub;\n  }\n  \n  // Test for singularity\n  if ( pivmax <= RealScalar(0.0) ) {\n    // if pivmax == -1, the column is structurally empty, otherwise it is only numerically zero\n    pivrow = pivmax < RealScalar(0.0) ? diagind : lsub_ptr[pivptr];\n    perm_r(pivrow) = StorageIndex(jcol);\n    return (jcol+1);\n  }\n  \n  RealScalar thresh = diagpivotthresh * pivmax; \n  \n  // Choose appropriate pivotal element \n  \n  {\n    // Test if the diagonal element can be used as a pivot (given the threshold value)\n    if (diag >= 0 ) \n    {\n      // Diagonal element exists\n      using std::abs;\n      rtemp = abs(lu_col_ptr[diag]);\n      if (rtemp != RealScalar(0.0) && rtemp >= thresh) pivptr = diag;\n    }\n    pivrow = lsub_ptr[pivptr];\n  }\n  \n  // Record pivot row\n  perm_r(pivrow) = StorageIndex(jcol);\n  // Interchange row subscripts\n  if (pivptr != nsupc )\n  {\n    std::swap( lsub_ptr[pivptr], lsub_ptr[nsupc] );\n    // Interchange numerical values as well, for the two rows in the whole snode\n    // such that L is indexed the same way as A\n    for (icol = 0; icol <= nsupc; icol++)\n    {\n      itemp = pivptr + icol * lda; \n      std::swap(lu_sup_ptr[itemp], lu_sup_ptr[nsupc + icol * lda]);\n    }\n  }\n  // cdiv operations\n  Scalar temp = Scalar(1.0) / lu_col_ptr[nsupc];\n  for (k = nsupc+1; k < nsupr; k++)\n    lu_col_ptr[k] *= temp; \n  return 0;\n}\n\n} // end namespace internal\n} // end namespace Eigen\n\n#endif // SPARSELU_PIVOTL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseLU/SparseLU_pruneL.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/* \n \n * NOTE: This file is the modified version of [s,d,c,z]pruneL.c file in SuperLU \n \n * -- SuperLU routine (version 2.0) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * November 15, 1997\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n#ifndef SPARSELU_PRUNEL_H\n#define SPARSELU_PRUNEL_H\n\nnamespace Eigen {\nnamespace internal {\n\n/**\n * \\brief Prunes the L-structure.\n *\n * It prunes the L-structure  of supernodes whose L-structure contains the current pivot row \"pivrow\"\n * \n * \n * \\param jcol The current column of L\n * \\param[in] perm_r Row permutation\n * \\param[out] pivrow  The pivot row\n * \\param nseg Number of segments\n * \\param segrep \n * \\param repfnz\n * \\param[out] xprune \n * \\param glu Global LU data\n * \n */\ntemplate <typename Scalar, typename StorageIndex>\nvoid SparseLUImpl<Scalar,StorageIndex>::pruneL(const Index jcol, const IndexVector& perm_r, const Index pivrow, const Index nseg,\n                                               const IndexVector& segrep, BlockIndexVector repfnz, IndexVector& xprune, GlobalLU_t& glu)\n{\n  // For each supernode-rep irep in U(*,j]\n  Index jsupno = glu.supno(jcol); \n  Index i,irep,irep1; \n  bool movnum, do_prune = false; \n  Index kmin = 0, kmax = 0, minloc, maxloc,krow; \n  for (i = 0; i < nseg; i++)\n  {\n    irep = segrep(i); \n    irep1 = irep + 1; \n    do_prune = false; \n    \n    // Don't prune with a zero U-segment \n    if (repfnz(irep) == emptyIdxLU) continue; \n    \n    // If a snode overlaps with the next panel, then the U-segment\n    // is fragmented into two parts -- irep and irep1. We should let \n    // pruning occur at the rep-column in irep1s snode. \n    if (glu.supno(irep) == glu.supno(irep1) ) continue; // don't prune \n    \n    // If it has not been pruned & it has a nonz in row L(pivrow,i)\n    if (glu.supno(irep) != jsupno )\n    {\n      if ( xprune (irep) >= glu.xlsub(irep1) )\n      {\n        kmin = glu.xlsub(irep);\n        kmax = glu.xlsub(irep1) - 1; \n        for (krow = kmin; krow <= kmax; krow++)\n        {\n          if (glu.lsub(krow) == pivrow) \n          {\n            do_prune = true; \n            break; \n          }\n        }\n      }\n      \n      if (do_prune) \n      {\n        // do a quicksort-type partition\n        // movnum=true means that the num values have to be exchanged\n        movnum = false; \n        if (irep == glu.xsup(glu.supno(irep)) ) // Snode of size 1 \n          movnum = true; \n        \n        while (kmin <= kmax)\n        {\n          if (perm_r(glu.lsub(kmax)) == emptyIdxLU)\n            kmax--; \n          else if ( perm_r(glu.lsub(kmin)) != emptyIdxLU)\n            kmin++;\n          else \n          {\n            // kmin below pivrow (not yet pivoted), and kmax\n            // above pivrow: interchange the two suscripts\n            std::swap(glu.lsub(kmin), glu.lsub(kmax)); \n            \n            // If the supernode has only one column, then we \n            // only keep one set of subscripts. For any subscript\n            // intercnahge performed, similar interchange must be \n            // done on the numerical values. \n            if (movnum) \n            {\n              minloc = glu.xlusup(irep) + ( kmin - glu.xlsub(irep) ); \n              maxloc = glu.xlusup(irep) + ( kmax - glu.xlsub(irep) ); \n              std::swap(glu.lusup(minloc), glu.lusup(maxloc)); \n            }\n            kmin++;\n            kmax--;\n          }\n        } // end while \n        \n        xprune(irep) = StorageIndex(kmin);  //Pruning \n      } // end if do_prune \n    } // end pruning \n  } // End for each U-segment\n}\n\n} // end namespace internal\n} // end namespace Eigen\n\n#endif // SPARSELU_PRUNEL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseLU/SparseLU_relax_snode.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/* This file is a modified version of heap_relax_snode.c file in SuperLU\n * -- SuperLU routine (version 3.0) --\n * Univ. of California Berkeley, Xerox Palo Alto Research Center,\n * and Lawrence Berkeley National Lab.\n * October 15, 2003\n *\n * Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n *\n * THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n * EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n *\n * Permission is hereby granted to use or copy this program for any\n * purpose, provided the above notices are retained on all copies.\n * Permission to modify the code and to distribute modified code is\n * granted, provided the above notices are retained, and a notice that\n * the code was modified is included with the above copyright notice.\n */\n\n#ifndef SPARSELU_RELAX_SNODE_H\n#define SPARSELU_RELAX_SNODE_H\n\nnamespace Eigen {\n\nnamespace internal {\n \n/** \n * \\brief Identify the initial relaxed supernodes\n * \n * This routine is applied to a column elimination tree. \n * It assumes that the matrix has been reordered according to the postorder of the etree\n * \\param n  the number of columns\n * \\param et elimination tree \n * \\param relax_columns Maximum number of columns allowed in a relaxed snode \n * \\param descendants Number of descendants of each node in the etree\n * \\param relax_end last column in a supernode\n */\ntemplate <typename Scalar, typename StorageIndex>\nvoid SparseLUImpl<Scalar,StorageIndex>::relax_snode (const Index n, IndexVector& et, const Index relax_columns, IndexVector& descendants, IndexVector& relax_end)\n{\n  \n  // compute the number of descendants of each node in the etree\n  Index parent; \n  relax_end.setConstant(emptyIdxLU);\n  descendants.setZero();\n  for (Index j = 0; j < n; j++) \n  {\n    parent = et(j);\n    if (parent != n) // not the dummy root\n      descendants(parent) += descendants(j) + 1;\n  }\n  // Identify the relaxed supernodes by postorder traversal of the etree\n  Index snode_start; // beginning of a snode \n  for (Index j = 0; j < n; )\n  {\n    parent = et(j);\n    snode_start = j; \n    while ( parent != n && descendants(parent) < relax_columns ) \n    {\n      j = parent; \n      parent = et(j);\n    }\n    // Found a supernode in postordered etree, j is the last column \n    relax_end(snode_start) = StorageIndex(j); // Record last column\n    j++;\n    // Search for a new leaf\n    while (descendants(j) != 0 && j < n) j++;\n  } // End postorder traversal of the etree\n  \n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SparseQR/SparseQR.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012-2013 Desire Nuentsa <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2012-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_QR_H\n#define EIGEN_SPARSE_QR_H\n\nnamespace Eigen {\n\ntemplate<typename MatrixType, typename OrderingType> class SparseQR;\ntemplate<typename SparseQRType> struct SparseQRMatrixQReturnType;\ntemplate<typename SparseQRType> struct SparseQRMatrixQTransposeReturnType;\ntemplate<typename SparseQRType, typename Derived> struct SparseQR_QProduct;\nnamespace internal {\n  template <typename SparseQRType> struct traits<SparseQRMatrixQReturnType<SparseQRType> >\n  {\n    typedef typename SparseQRType::MatrixType ReturnType;\n    typedef typename ReturnType::StorageIndex StorageIndex;\n    typedef typename ReturnType::StorageKind StorageKind;\n    enum {\n      RowsAtCompileTime = Dynamic,\n      ColsAtCompileTime = Dynamic\n    };\n  };\n  template <typename SparseQRType> struct traits<SparseQRMatrixQTransposeReturnType<SparseQRType> >\n  {\n    typedef typename SparseQRType::MatrixType ReturnType;\n  };\n  template <typename SparseQRType, typename Derived> struct traits<SparseQR_QProduct<SparseQRType, Derived> >\n  {\n    typedef typename Derived::PlainObject ReturnType;\n  };\n} // End namespace internal\n\n/**\n  * \\ingroup SparseQR_Module\n  * \\class SparseQR\n  * \\brief Sparse left-looking QR factorization with numerical column pivoting\n  * \n  * This class implements a left-looking QR decomposition of sparse matrices\n  * with numerical column pivoting.\n  * When a column has a norm less than a given tolerance\n  * it is implicitly permuted to the end. The QR factorization thus obtained is \n  * given by A*P = Q*R where R is upper triangular or trapezoidal. \n  * \n  * P is the column permutation which is the product of the fill-reducing and the\n  * numerical permutations. Use colsPermutation() to get it.\n  * \n  * Q is the orthogonal matrix represented as products of Householder reflectors. \n  * Use matrixQ() to get an expression and matrixQ().adjoint() to get the adjoint.\n  * You can then apply it to a vector.\n  * \n  * R is the sparse triangular or trapezoidal matrix. The later occurs when A is rank-deficient.\n  * matrixR().topLeftCorner(rank(), rank()) always returns a triangular factor of full rank.\n  * \n  * \\tparam _MatrixType The type of the sparse matrix A, must be a column-major SparseMatrix<>\n  * \\tparam _OrderingType The fill-reducing ordering method. See the \\link OrderingMethods_Module \n  *  OrderingMethods \\endlink module for the list of built-in and external ordering methods.\n  * \n  * \\implsparsesolverconcept\n  *\n  * The numerical pivoting strategy and default threshold are the same as in SuiteSparse QR, and\n  * detailed in the following paper:\n  * <i>\n  * Tim Davis, \"Algorithm 915, SuiteSparseQR: Multifrontal Multithreaded Rank-Revealing\n  * Sparse QR Factorization, ACM Trans. on Math. Soft. 38(1), 2011.\n  * </i>\n  * Even though it is qualified as \"rank-revealing\", this strategy might fail for some \n  * rank deficient problems. When this class is used to solve linear or least-square problems\n  * it is thus strongly recommended to check the accuracy of the computed solution. If it\n  * failed, it usually helps to increase the threshold with setPivotThreshold.\n  * \n  * \\warning The input sparse matrix A must be in compressed mode (see SparseMatrix::makeCompressed()).\n  * \\warning For complex matrices matrixQ().transpose() will actually return the adjoint matrix.\n  * \n  */\ntemplate<typename _MatrixType, typename _OrderingType>\nclass SparseQR : public SparseSolverBase<SparseQR<_MatrixType,_OrderingType> >\n{\n  protected:\n    typedef SparseSolverBase<SparseQR<_MatrixType,_OrderingType> > Base;\n    using Base::m_isInitialized;\n  public:\n    using Base::_solve_impl;\n    typedef _MatrixType MatrixType;\n    typedef _OrderingType OrderingType;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> QRMatrixType;\n    typedef Matrix<StorageIndex, Dynamic, 1> IndexVector;\n    typedef Matrix<Scalar, Dynamic, 1> ScalarVector;\n    typedef PermutationMatrix<Dynamic, Dynamic, StorageIndex> PermutationType;\n\n    enum {\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n    \n  public:\n    SparseQR () :  m_analysisIsok(false), m_lastError(\"\"), m_useDefaultThreshold(true),m_isQSorted(false),m_isEtreeOk(false)\n    { }\n    \n    /** Construct a QR factorization of the matrix \\a mat.\n      * \n      * \\warning The matrix \\a mat must be in compressed mode (see SparseMatrix::makeCompressed()).\n      * \n      * \\sa compute()\n      */\n    explicit SparseQR(const MatrixType& mat) : m_analysisIsok(false), m_lastError(\"\"), m_useDefaultThreshold(true),m_isQSorted(false),m_isEtreeOk(false)\n    {\n      compute(mat);\n    }\n    \n    /** Computes the QR factorization of the sparse matrix \\a mat.\n      * \n      * \\warning The matrix \\a mat must be in compressed mode (see SparseMatrix::makeCompressed()).\n      * \n      * \\sa analyzePattern(), factorize()\n      */\n    void compute(const MatrixType& mat)\n    {\n      analyzePattern(mat);\n      factorize(mat);\n    }\n    void analyzePattern(const MatrixType& mat);\n    void factorize(const MatrixType& mat);\n    \n    /** \\returns the number of rows of the represented matrix. \n      */\n    inline Index rows() const { return m_pmat.rows(); }\n    \n    /** \\returns the number of columns of the represented matrix. \n      */\n    inline Index cols() const { return m_pmat.cols();}\n    \n    /** \\returns a const reference to the \\b sparse upper triangular matrix R of the QR factorization.\n      * \\warning The entries of the returned matrix are not sorted. This means that using it in algorithms\n      *          expecting sorted entries will fail. This include random coefficient accesses (SpaseMatrix::coeff()),\n      *          and coefficient-wise operations. Matrix products and triangular solves are fine though.\n      *\n      * To sort the entries, you can assign it to a row-major matrix, and if a column-major matrix\n      * is required, you can copy it again:\n      * \\code\n      * SparseMatrix<double>          R  = qr.matrixR();  // column-major, not sorted!\n      * SparseMatrix<double,RowMajor> Rr = qr.matrixR();  // row-major, sorted\n      * SparseMatrix<double>          Rc = Rr;            // column-major, sorted\n      * \\endcode\n      */\n    const QRMatrixType& matrixR() const { return m_R; }\n    \n    /** \\returns the number of non linearly dependent columns as determined by the pivoting threshold.\n      *\n      * \\sa setPivotThreshold()\n      */\n    Index rank() const\n    {\n      eigen_assert(m_isInitialized && \"The factorization should be called first, use compute()\");\n      return m_nonzeropivots; \n    }\n    \n    /** \\returns an expression of the matrix Q as products of sparse Householder reflectors.\n    * The common usage of this function is to apply it to a dense matrix or vector\n    * \\code\n    * VectorXd B1, B2;\n    * // Initialize B1\n    * B2 = matrixQ() * B1;\n    * \\endcode\n    *\n    * To get a plain SparseMatrix representation of Q:\n    * \\code\n    * SparseMatrix<double> Q;\n    * Q = SparseQR<SparseMatrix<double> >(A).matrixQ();\n    * \\endcode\n    * Internally, this call simply performs a sparse product between the matrix Q\n    * and a sparse identity matrix. However, due to the fact that the sparse\n    * reflectors are stored unsorted, two transpositions are needed to sort\n    * them before performing the product.\n    */\n    SparseQRMatrixQReturnType<SparseQR> matrixQ() const \n    { return SparseQRMatrixQReturnType<SparseQR>(*this); }\n    \n    /** \\returns a const reference to the column permutation P that was applied to A such that A*P = Q*R\n      * It is the combination of the fill-in reducing permutation and numerical column pivoting.\n      */\n    const PermutationType& colsPermutation() const\n    { \n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_outputPerm_c;\n    }\n    \n    /** \\returns A string describing the type of error.\n      * This method is provided to ease debugging, not to handle errors.\n      */\n    std::string lastErrorMessage() const { return m_lastError; }\n    \n    /** \\internal */\n    template<typename Rhs, typename Dest>\n    bool _solve_impl(const MatrixBase<Rhs> &B, MatrixBase<Dest> &dest) const\n    {\n      eigen_assert(m_isInitialized && \"The factorization should be called first, use compute()\");\n      eigen_assert(this->rows() == B.rows() && \"SparseQR::solve() : invalid number of rows in the right hand side matrix\");\n\n      Index rank = this->rank();\n      \n      // Compute Q^* * b;\n      typename Dest::PlainObject y, b;\n      y = this->matrixQ().adjoint() * B;\n      b = y;\n      \n      // Solve with the triangular matrix R\n      y.resize((std::max<Index>)(cols(),y.rows()),y.cols());\n      y.topRows(rank) = this->matrixR().topLeftCorner(rank, rank).template triangularView<Upper>().solve(b.topRows(rank));\n      y.bottomRows(y.rows()-rank).setZero();\n      \n      // Apply the column permutation\n      if (m_perm_c.size())  dest = colsPermutation() * y.topRows(cols());\n      else                  dest = y.topRows(cols());\n      \n      m_info = Success;\n      return true;\n    }\n\n    /** Sets the threshold that is used to determine linearly dependent columns during the factorization.\n      *\n      * In practice, if during the factorization the norm of the column that has to be eliminated is below\n      * this threshold, then the entire column is treated as zero, and it is moved at the end.\n      */\n    void setPivotThreshold(const RealScalar& threshold)\n    {\n      m_useDefaultThreshold = false;\n      m_threshold = threshold;\n    }\n    \n    /** \\returns the solution X of \\f$ A X = B \\f$ using the current decomposition of A.\n      *\n      * \\sa compute()\n      */\n    template<typename Rhs>\n    inline const Solve<SparseQR, Rhs> solve(const MatrixBase<Rhs>& B) const \n    {\n      eigen_assert(m_isInitialized && \"The factorization should be called first, use compute()\");\n      eigen_assert(this->rows() == B.rows() && \"SparseQR::solve() : invalid number of rows in the right hand side matrix\");\n      return Solve<SparseQR, Rhs>(*this, B.derived());\n    }\n    template<typename Rhs>\n    inline const Solve<SparseQR, Rhs> solve(const SparseMatrixBase<Rhs>& B) const\n    {\n          eigen_assert(m_isInitialized && \"The factorization should be called first, use compute()\");\n          eigen_assert(this->rows() == B.rows() && \"SparseQR::solve() : invalid number of rows in the right hand side matrix\");\n          return Solve<SparseQR, Rhs>(*this, B.derived());\n    }\n    \n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the QR factorization reports a numerical problem\n      *          \\c InvalidInput if the input matrix is invalid\n      *\n      * \\sa iparm()          \n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_info;\n    }\n\n\n    /** \\internal */\n    inline void _sort_matrix_Q()\n    {\n      if(this->m_isQSorted) return;\n      // The matrix Q is sorted during the transposition\n      SparseMatrix<Scalar, RowMajor, Index> mQrm(this->m_Q);\n      this->m_Q = mQrm;\n      this->m_isQSorted = true;\n    }\n\n    \n  protected:\n    bool m_analysisIsok;\n    bool m_factorizationIsok;\n    mutable ComputationInfo m_info;\n    std::string m_lastError;\n    QRMatrixType m_pmat;            // Temporary matrix\n    QRMatrixType m_R;               // The triangular factor matrix\n    QRMatrixType m_Q;               // The orthogonal reflectors\n    ScalarVector m_hcoeffs;         // The Householder coefficients\n    PermutationType m_perm_c;       // Fill-reducing  Column  permutation\n    PermutationType m_pivotperm;    // The permutation for rank revealing\n    PermutationType m_outputPerm_c; // The final column permutation\n    RealScalar m_threshold;         // Threshold to determine null Householder reflections\n    bool m_useDefaultThreshold;     // Use default threshold\n    Index m_nonzeropivots;          // Number of non zero pivots found\n    IndexVector m_etree;            // Column elimination tree\n    IndexVector m_firstRowElt;      // First element in each row\n    bool m_isQSorted;               // whether Q is sorted or not\n    bool m_isEtreeOk;               // whether the elimination tree match the initial input matrix\n    \n    template <typename, typename > friend struct SparseQR_QProduct;\n    \n};\n\n/** \\brief Preprocessing step of a QR factorization \n  * \n  * \\warning The matrix \\a mat must be in compressed mode (see SparseMatrix::makeCompressed()).\n  * \n  * In this step, the fill-reducing permutation is computed and applied to the columns of A\n  * and the column elimination tree is computed as well. Only the sparsity pattern of \\a mat is exploited.\n  * \n  * \\note In this step it is assumed that there is no empty row in the matrix \\a mat.\n  */\ntemplate <typename MatrixType, typename OrderingType>\nvoid SparseQR<MatrixType,OrderingType>::analyzePattern(const MatrixType& mat)\n{\n  eigen_assert(mat.isCompressed() && \"SparseQR requires a sparse matrix in compressed mode. Call .makeCompressed() before passing it to SparseQR\");\n  // Copy to a column major matrix if the input is rowmajor\n  typename internal::conditional<MatrixType::IsRowMajor,QRMatrixType,const MatrixType&>::type matCpy(mat);\n  // Compute the column fill reducing ordering\n  OrderingType ord; \n  ord(matCpy, m_perm_c); \n  Index n = mat.cols();\n  Index m = mat.rows();\n  Index diagSize = (std::min)(m,n);\n  \n  if (!m_perm_c.size())\n  {\n    m_perm_c.resize(n);\n    m_perm_c.indices().setLinSpaced(n, 0,StorageIndex(n-1));\n  }\n  \n  // Compute the column elimination tree of the permuted matrix\n  m_outputPerm_c = m_perm_c.inverse();\n  internal::coletree(matCpy, m_etree, m_firstRowElt, m_outputPerm_c.indices().data());\n  m_isEtreeOk = true;\n  \n  m_R.resize(m, n);\n  m_Q.resize(m, diagSize);\n  \n  // Allocate space for nonzero elements: rough estimation\n  m_R.reserve(2*mat.nonZeros()); //FIXME Get a more accurate estimation through symbolic factorization with the etree\n  m_Q.reserve(2*mat.nonZeros());\n  m_hcoeffs.resize(diagSize);\n  m_analysisIsok = true;\n}\n\n/** \\brief Performs the numerical QR factorization of the input matrix\n  * \n  * The function SparseQR::analyzePattern(const MatrixType&) must have been called beforehand with\n  * a matrix having the same sparsity pattern than \\a mat.\n  * \n  * \\param mat The sparse column-major matrix\n  */\ntemplate <typename MatrixType, typename OrderingType>\nvoid SparseQR<MatrixType,OrderingType>::factorize(const MatrixType& mat)\n{\n  using std::abs;\n  \n  eigen_assert(m_analysisIsok && \"analyzePattern() should be called before this step\");\n  StorageIndex m = StorageIndex(mat.rows());\n  StorageIndex n = StorageIndex(mat.cols());\n  StorageIndex diagSize = (std::min)(m,n);\n  IndexVector mark((std::max)(m,n)); mark.setConstant(-1);  // Record the visited nodes\n  IndexVector Ridx(n), Qidx(m);                             // Store temporarily the row indexes for the current column of R and Q\n  Index nzcolR, nzcolQ;                                     // Number of nonzero for the current column of R and Q\n  ScalarVector tval(m);                                     // The dense vector used to compute the current column\n  RealScalar pivotThreshold = m_threshold;\n  \n  m_R.setZero();\n  m_Q.setZero();\n  m_pmat = mat;\n  if(!m_isEtreeOk)\n  {\n    m_outputPerm_c = m_perm_c.inverse();\n    internal::coletree(m_pmat, m_etree, m_firstRowElt, m_outputPerm_c.indices().data());\n    m_isEtreeOk = true;\n  }\n\n  m_pmat.uncompress(); // To have the innerNonZeroPtr allocated\n  \n  // Apply the fill-in reducing permutation lazily:\n  {\n    // If the input is row major, copy the original column indices,\n    // otherwise directly use the input matrix\n    // \n    IndexVector originalOuterIndicesCpy;\n    const StorageIndex *originalOuterIndices = mat.outerIndexPtr();\n    if(MatrixType::IsRowMajor)\n    {\n      originalOuterIndicesCpy = IndexVector::Map(m_pmat.outerIndexPtr(),n+1);\n      originalOuterIndices = originalOuterIndicesCpy.data();\n    }\n    \n    for (int i = 0; i < n; i++)\n    {\n      Index p = m_perm_c.size() ? m_perm_c.indices()(i) : i;\n      m_pmat.outerIndexPtr()[p] = originalOuterIndices[i]; \n      m_pmat.innerNonZeroPtr()[p] = originalOuterIndices[i+1] - originalOuterIndices[i]; \n    }\n  }\n  \n  /* Compute the default threshold as in MatLab, see:\n   * Tim Davis, \"Algorithm 915, SuiteSparseQR: Multifrontal Multithreaded Rank-Revealing\n   * Sparse QR Factorization, ACM Trans. on Math. Soft. 38(1), 2011, Page 8:3 \n   */\n  if(m_useDefaultThreshold) \n  {\n    RealScalar max2Norm = 0.0;\n    for (int j = 0; j < n; j++) max2Norm = numext::maxi(max2Norm, m_pmat.col(j).norm());\n    if(max2Norm==RealScalar(0))\n      max2Norm = RealScalar(1);\n    pivotThreshold = 20 * (m + n) * max2Norm * NumTraits<RealScalar>::epsilon();\n  }\n  \n  // Initialize the numerical permutation\n  m_pivotperm.setIdentity(n);\n  \n  StorageIndex nonzeroCol = 0; // Record the number of valid pivots\n  m_Q.startVec(0);\n\n  // Left looking rank-revealing QR factorization: compute a column of R and Q at a time\n  for (StorageIndex col = 0; col < n; ++col)\n  {\n    mark.setConstant(-1);\n    m_R.startVec(col);\n    mark(nonzeroCol) = col;\n    Qidx(0) = nonzeroCol;\n    nzcolR = 0; nzcolQ = 1;\n    bool found_diag = nonzeroCol>=m;\n    tval.setZero(); \n    \n    // Symbolic factorization: find the nonzero locations of the column k of the factors R and Q, i.e.,\n    // all the nodes (with indexes lower than rank) reachable through the column elimination tree (etree) rooted at node k.\n    // Note: if the diagonal entry does not exist, then its contribution must be explicitly added,\n    // thus the trick with found_diag that permits to do one more iteration on the diagonal element if this one has not been found.\n    for (typename QRMatrixType::InnerIterator itp(m_pmat, col); itp || !found_diag; ++itp)\n    {\n      StorageIndex curIdx = nonzeroCol;\n      if(itp) curIdx = StorageIndex(itp.row());\n      if(curIdx == nonzeroCol) found_diag = true;\n      \n      // Get the nonzeros indexes of the current column of R\n      StorageIndex st = m_firstRowElt(curIdx); // The traversal of the etree starts here\n      if (st < 0 )\n      {\n        m_lastError = \"Empty row found during numerical factorization\";\n        m_info = InvalidInput;\n        return;\n      }\n\n      // Traverse the etree \n      Index bi = nzcolR;\n      for (; mark(st) != col; st = m_etree(st))\n      {\n        Ridx(nzcolR) = st;  // Add this row to the list,\n        mark(st) = col;     // and mark this row as visited\n        nzcolR++;\n      }\n\n      // Reverse the list to get the topological ordering\n      Index nt = nzcolR-bi;\n      for(Index i = 0; i < nt/2; i++) std::swap(Ridx(bi+i), Ridx(nzcolR-i-1));\n       \n      // Copy the current (curIdx,pcol) value of the input matrix\n      if(itp) tval(curIdx) = itp.value();\n      else    tval(curIdx) = Scalar(0);\n      \n      // Compute the pattern of Q(:,k)\n      if(curIdx > nonzeroCol && mark(curIdx) != col ) \n      {\n        Qidx(nzcolQ) = curIdx;  // Add this row to the pattern of Q,\n        mark(curIdx) = col;     // and mark it as visited\n        nzcolQ++;\n      }\n    }\n\n    // Browse all the indexes of R(:,col) in reverse order\n    for (Index i = nzcolR-1; i >= 0; i--)\n    {\n      Index curIdx = Ridx(i);\n      \n      // Apply the curIdx-th householder vector to the current column (temporarily stored into tval)\n      Scalar tdot(0);\n      \n      // First compute q' * tval\n      tdot = m_Q.col(curIdx).dot(tval);\n\n      tdot *= m_hcoeffs(curIdx);\n      \n      // Then update tval = tval - q * tau\n      // FIXME: tval -= tdot * m_Q.col(curIdx) should amount to the same (need to check/add support for efficient \"dense ?= sparse\")\n      for (typename QRMatrixType::InnerIterator itq(m_Q, curIdx); itq; ++itq)\n        tval(itq.row()) -= itq.value() * tdot;\n\n      // Detect fill-in for the current column of Q\n      if(m_etree(Ridx(i)) == nonzeroCol)\n      {\n        for (typename QRMatrixType::InnerIterator itq(m_Q, curIdx); itq; ++itq)\n        {\n          StorageIndex iQ = StorageIndex(itq.row());\n          if (mark(iQ) != col)\n          {\n            Qidx(nzcolQ++) = iQ;  // Add this row to the pattern of Q,\n            mark(iQ) = col;       // and mark it as visited\n          }\n        }\n      }\n    } // End update current column\n    \n    Scalar tau = RealScalar(0);\n    RealScalar beta = 0;\n    \n    if(nonzeroCol < diagSize)\n    {\n      // Compute the Householder reflection that eliminate the current column\n      // FIXME this step should call the Householder module.\n      Scalar c0 = nzcolQ ? tval(Qidx(0)) : Scalar(0);\n      \n      // First, the squared norm of Q((col+1):m, col)\n      RealScalar sqrNorm = 0.;\n      for (Index itq = 1; itq < nzcolQ; ++itq) sqrNorm += numext::abs2(tval(Qidx(itq)));\n      if(sqrNorm == RealScalar(0) && numext::imag(c0) == RealScalar(0))\n      {\n        beta = numext::real(c0);\n        tval(Qidx(0)) = 1;\n      }\n      else\n      {\n        using std::sqrt;\n        beta = sqrt(numext::abs2(c0) + sqrNorm);\n        if(numext::real(c0) >= RealScalar(0))\n          beta = -beta;\n        tval(Qidx(0)) = 1;\n        for (Index itq = 1; itq < nzcolQ; ++itq)\n          tval(Qidx(itq)) /= (c0 - beta);\n        tau = numext::conj((beta-c0) / beta);\n          \n      }\n    }\n\n    // Insert values in R\n    for (Index  i = nzcolR-1; i >= 0; i--)\n    {\n      Index curIdx = Ridx(i);\n      if(curIdx < nonzeroCol) \n      {\n        m_R.insertBackByOuterInnerUnordered(col, curIdx) = tval(curIdx);\n        tval(curIdx) = Scalar(0.);\n      }\n    }\n\n    if(nonzeroCol < diagSize && abs(beta) >= pivotThreshold)\n    {\n      m_R.insertBackByOuterInner(col, nonzeroCol) = beta;\n      // The householder coefficient\n      m_hcoeffs(nonzeroCol) = tau;\n      // Record the householder reflections\n      for (Index itq = 0; itq < nzcolQ; ++itq)\n      {\n        Index iQ = Qidx(itq);\n        m_Q.insertBackByOuterInnerUnordered(nonzeroCol,iQ) = tval(iQ);\n        tval(iQ) = Scalar(0.);\n      }\n      nonzeroCol++;\n      if(nonzeroCol<diagSize)\n        m_Q.startVec(nonzeroCol);\n    }\n    else\n    {\n      // Zero pivot found: move implicitly this column to the end\n      for (Index j = nonzeroCol; j < n-1; j++) \n        std::swap(m_pivotperm.indices()(j), m_pivotperm.indices()[j+1]);\n      \n      // Recompute the column elimination tree\n      internal::coletree(m_pmat, m_etree, m_firstRowElt, m_pivotperm.indices().data());\n      m_isEtreeOk = false;\n    }\n  }\n  \n  m_hcoeffs.tail(diagSize-nonzeroCol).setZero();\n  \n  // Finalize the column pointers of the sparse matrices R and Q\n  m_Q.finalize();\n  m_Q.makeCompressed();\n  m_R.finalize();\n  m_R.makeCompressed();\n  m_isQSorted = false;\n\n  m_nonzeropivots = nonzeroCol;\n  \n  if(nonzeroCol<n)\n  {\n    // Permute the triangular factor to put the 'dead' columns to the end\n    QRMatrixType tempR(m_R);\n    m_R = tempR * m_pivotperm;\n    \n    // Update the column permutation\n    m_outputPerm_c = m_outputPerm_c * m_pivotperm;\n  }\n  \n  m_isInitialized = true; \n  m_factorizationIsok = true;\n  m_info = Success;\n}\n\ntemplate <typename SparseQRType, typename Derived>\nstruct SparseQR_QProduct : ReturnByValue<SparseQR_QProduct<SparseQRType, Derived> >\n{\n  typedef typename SparseQRType::QRMatrixType MatrixType;\n  typedef typename SparseQRType::Scalar Scalar;\n  // Get the references \n  SparseQR_QProduct(const SparseQRType& qr, const Derived& other, bool transpose) : \n  m_qr(qr),m_other(other),m_transpose(transpose) {}\n  inline Index rows() const { return m_qr.matrixQ().rows(); }\n  inline Index cols() const { return m_other.cols(); }\n  \n  // Assign to a vector\n  template<typename DesType>\n  void evalTo(DesType& res) const\n  {\n    Index m = m_qr.rows();\n    Index n = m_qr.cols();\n    Index diagSize = (std::min)(m,n);\n    res = m_other;\n    if (m_transpose)\n    {\n      eigen_assert(m_qr.m_Q.rows() == m_other.rows() && \"Non conforming object sizes\");\n      //Compute res = Q' * other column by column\n      for(Index j = 0; j < res.cols(); j++){\n        for (Index k = 0; k < diagSize; k++)\n        {\n          Scalar tau = Scalar(0);\n          tau = m_qr.m_Q.col(k).dot(res.col(j));\n          if(tau==Scalar(0)) continue;\n          tau = tau * m_qr.m_hcoeffs(k);\n          res.col(j) -= tau * m_qr.m_Q.col(k);\n        }\n      }\n    }\n    else\n    {\n      eigen_assert(m_qr.matrixQ().cols() == m_other.rows() && \"Non conforming object sizes\");\n\n      res.conservativeResize(rows(), cols());\n\n      // Compute res = Q * other column by column\n      for(Index j = 0; j < res.cols(); j++)\n      {\n        Index start_k = internal::is_identity<Derived>::value ? numext::mini(j,diagSize-1) : diagSize-1;\n        for (Index k = start_k; k >=0; k--)\n        {\n          Scalar tau = Scalar(0);\n          tau = m_qr.m_Q.col(k).dot(res.col(j));\n          if(tau==Scalar(0)) continue;\n          tau = tau * numext::conj(m_qr.m_hcoeffs(k));\n          res.col(j) -= tau * m_qr.m_Q.col(k);\n        }\n      }\n    }\n  }\n  \n  const SparseQRType& m_qr;\n  const Derived& m_other;\n  bool m_transpose; // TODO this actually means adjoint\n};\n\ntemplate<typename SparseQRType>\nstruct SparseQRMatrixQReturnType : public EigenBase<SparseQRMatrixQReturnType<SparseQRType> >\n{  \n  typedef typename SparseQRType::Scalar Scalar;\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  enum {\n    RowsAtCompileTime = Dynamic,\n    ColsAtCompileTime = Dynamic\n  };\n  explicit SparseQRMatrixQReturnType(const SparseQRType& qr) : m_qr(qr) {}\n  template<typename Derived>\n  SparseQR_QProduct<SparseQRType, Derived> operator*(const MatrixBase<Derived>& other)\n  {\n    return SparseQR_QProduct<SparseQRType,Derived>(m_qr,other.derived(),false);\n  }\n  // To use for operations with the adjoint of Q\n  SparseQRMatrixQTransposeReturnType<SparseQRType> adjoint() const\n  {\n    return SparseQRMatrixQTransposeReturnType<SparseQRType>(m_qr);\n  }\n  inline Index rows() const { return m_qr.rows(); }\n  inline Index cols() const { return m_qr.rows(); }\n  // To use for operations with the transpose of Q FIXME this is the same as adjoint at the moment\n  SparseQRMatrixQTransposeReturnType<SparseQRType> transpose() const\n  {\n    return SparseQRMatrixQTransposeReturnType<SparseQRType>(m_qr);\n  }\n  const SparseQRType& m_qr;\n};\n\n// TODO this actually represents the adjoint of Q\ntemplate<typename SparseQRType>\nstruct SparseQRMatrixQTransposeReturnType\n{\n  explicit SparseQRMatrixQTransposeReturnType(const SparseQRType& qr) : m_qr(qr) {}\n  template<typename Derived>\n  SparseQR_QProduct<SparseQRType,Derived> operator*(const MatrixBase<Derived>& other)\n  {\n    return SparseQR_QProduct<SparseQRType,Derived>(m_qr,other.derived(), true);\n  }\n  const SparseQRType& m_qr;\n};\n\nnamespace internal {\n  \ntemplate<typename SparseQRType>\nstruct evaluator_traits<SparseQRMatrixQReturnType<SparseQRType> >\n{\n  typedef typename SparseQRType::MatrixType MatrixType;\n  typedef typename storage_kind_to_evaluator_kind<typename MatrixType::StorageKind>::Kind Kind;\n  typedef SparseShape Shape;\n};\n\ntemplate< typename DstXprType, typename SparseQRType>\nstruct Assignment<DstXprType, SparseQRMatrixQReturnType<SparseQRType>, internal::assign_op<typename DstXprType::Scalar,typename DstXprType::Scalar>, Sparse2Sparse>\n{\n  typedef SparseQRMatrixQReturnType<SparseQRType> SrcXprType;\n  typedef typename DstXprType::Scalar Scalar;\n  typedef typename DstXprType::StorageIndex StorageIndex;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<Scalar,Scalar> &/*func*/)\n  {\n    typename DstXprType::PlainObject idMat(src.rows(), src.cols());\n    idMat.setIdentity();\n    // Sort the sparse householder reflectors if needed\n    const_cast<SparseQRType *>(&src.m_qr)->_sort_matrix_Q();\n    dst = SparseQR_QProduct<SparseQRType, DstXprType>(src.m_qr, idMat, false);\n  }\n};\n\ntemplate< typename DstXprType, typename SparseQRType>\nstruct Assignment<DstXprType, SparseQRMatrixQReturnType<SparseQRType>, internal::assign_op<typename DstXprType::Scalar,typename DstXprType::Scalar>, Sparse2Dense>\n{\n  typedef SparseQRMatrixQReturnType<SparseQRType> SrcXprType;\n  typedef typename DstXprType::Scalar Scalar;\n  typedef typename DstXprType::StorageIndex StorageIndex;\n  static void run(DstXprType &dst, const SrcXprType &src, const internal::assign_op<Scalar,Scalar> &/*func*/)\n  {\n    dst = src.m_qr.matrixQ() * DstXprType::Identity(src.m_qr.rows(), src.m_qr.rows());\n  }\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/StlSupport/StdDeque.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Hauke Heibel <hauke.heibel@googlemail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_STDDEQUE_H\n#define EIGEN_STDDEQUE_H\n\n#include \"details.h\"\n\n/**\n * This section contains a convenience MACRO which allows an easy specialization of\n * std::deque such that for data types with alignment issues the correct allocator\n * is used automatically.\n */\n#define EIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(...) \\\nnamespace std \\\n{ \\\n  template<> \\\n  class deque<__VA_ARGS__, std::allocator<__VA_ARGS__> >           \\\n    : public deque<__VA_ARGS__, EIGEN_ALIGNED_ALLOCATOR<__VA_ARGS__> > \\\n  { \\\n    typedef deque<__VA_ARGS__, EIGEN_ALIGNED_ALLOCATOR<__VA_ARGS__> > deque_base; \\\n  public: \\\n    typedef __VA_ARGS__ value_type; \\\n    typedef deque_base::allocator_type allocator_type; \\\n    typedef deque_base::size_type size_type;  \\\n    typedef deque_base::iterator iterator;  \\\n    explicit deque(const allocator_type& a = allocator_type()) : deque_base(a) {}  \\\n    template<typename InputIterator> \\\n    deque(InputIterator first, InputIterator last, const allocator_type& a = allocator_type()) : deque_base(first, last, a) {} \\\n    deque(const deque& c) : deque_base(c) {}  \\\n    explicit deque(size_type num, const value_type& val = value_type()) : deque_base(num, val) {} \\\n    deque(iterator start_, iterator end_) : deque_base(start_, end_) {}  \\\n    deque& operator=(const deque& x) {  \\\n      deque_base::operator=(x);  \\\n      return *this;  \\\n    } \\\n  }; \\\n}\n\n// check whether we really need the std::deque specialization\n#if !EIGEN_HAS_CXX11_CONTAINERS && !(defined(_GLIBCXX_DEQUE) && (!EIGEN_GNUC_AT_LEAST(4,1))) /* Note that before gcc-4.1 we already have: std::deque::resize(size_type,const T&). */\n\nnamespace std {\n\n#define EIGEN_STD_DEQUE_SPECIALIZATION_BODY \\\n  public:  \\\n    typedef T value_type; \\\n    typedef typename deque_base::allocator_type allocator_type; \\\n    typedef typename deque_base::size_type size_type;  \\\n    typedef typename deque_base::iterator iterator;  \\\n    typedef typename deque_base::const_iterator const_iterator;  \\\n    explicit deque(const allocator_type& a = allocator_type()) : deque_base(a) {}  \\\n    template<typename InputIterator> \\\n    deque(InputIterator first, InputIterator last, const allocator_type& a = allocator_type()) \\\n    : deque_base(first, last, a) {} \\\n    deque(const deque& c) : deque_base(c) {}  \\\n    explicit deque(size_type num, const value_type& val = value_type()) : deque_base(num, val) {} \\\n    deque(iterator start_, iterator end_) : deque_base(start_, end_) {}  \\\n    deque& operator=(const deque& x) {  \\\n      deque_base::operator=(x);  \\\n      return *this;  \\\n    }\n\n  template<typename T>\n  class deque<T,EIGEN_ALIGNED_ALLOCATOR<T> >\n    : public deque<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T),\n                   Eigen::aligned_allocator_indirection<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T)> >\n{\n  typedef deque<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T),\n                Eigen::aligned_allocator_indirection<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T)> > deque_base;\n  EIGEN_STD_DEQUE_SPECIALIZATION_BODY\n\n  void resize(size_type new_size)\n  { resize(new_size, T()); }\n\n#if defined(_DEQUE_)\n  // workaround MSVC std::deque implementation\n  void resize(size_type new_size, const value_type& x)\n  {\n    if (deque_base::size() < new_size)\n      deque_base::_Insert_n(deque_base::end(), new_size - deque_base::size(), x);\n    else if (new_size < deque_base::size())\n      deque_base::erase(deque_base::begin() + new_size, deque_base::end());\n  }\n  void push_back(const value_type& x)\n  { deque_base::push_back(x); } \n  void push_front(const value_type& x)\n  { deque_base::push_front(x); }\n  using deque_base::insert;  \n  iterator insert(const_iterator position, const value_type& x)\n  { return deque_base::insert(position,x); }\n  void insert(const_iterator position, size_type new_size, const value_type& x)\n  { deque_base::insert(position, new_size, x); }\n#else\n  // default implementation which should always work.\n  void resize(size_type new_size, const value_type& x)\n  {\n    if (new_size < deque_base::size())\n      deque_base::erase(deque_base::begin() + new_size, deque_base::end());\n    else if (new_size > deque_base::size())\n      deque_base::insert(deque_base::end(), new_size - deque_base::size(), x);\n  }\n#endif\n  };\n}\n\n#endif // check whether specialization is actually required\n\n#endif // EIGEN_STDDEQUE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/StlSupport/StdList.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Hauke Heibel <hauke.heibel@googlemail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_STDLIST_H\n#define EIGEN_STDLIST_H\n\n#include \"details.h\"\n\n/**\n * This section contains a convenience MACRO which allows an easy specialization of\n * std::list such that for data types with alignment issues the correct allocator\n * is used automatically.\n */\n#define EIGEN_DEFINE_STL_LIST_SPECIALIZATION(...) \\\nnamespace std \\\n{ \\\n  template<> \\\n  class list<__VA_ARGS__, std::allocator<__VA_ARGS__> >           \\\n    : public list<__VA_ARGS__, EIGEN_ALIGNED_ALLOCATOR<__VA_ARGS__> > \\\n  { \\\n    typedef list<__VA_ARGS__, EIGEN_ALIGNED_ALLOCATOR<__VA_ARGS__> > list_base; \\\n  public: \\\n    typedef __VA_ARGS__ value_type; \\\n    typedef list_base::allocator_type allocator_type; \\\n    typedef list_base::size_type size_type;  \\\n    typedef list_base::iterator iterator;  \\\n    explicit list(const allocator_type& a = allocator_type()) : list_base(a) {}  \\\n    template<typename InputIterator> \\\n    list(InputIterator first, InputIterator last, const allocator_type& a = allocator_type()) : list_base(first, last, a) {} \\\n    list(const list& c) : list_base(c) {}  \\\n    explicit list(size_type num, const value_type& val = value_type()) : list_base(num, val) {} \\\n    list(iterator start_, iterator end_) : list_base(start_, end_) {}  \\\n    list& operator=(const list& x) {  \\\n      list_base::operator=(x);  \\\n      return *this;  \\\n    } \\\n  }; \\\n}\n\n// check whether we really need the std::list specialization\n#if !EIGEN_HAS_CXX11_CONTAINERS && !(defined(_GLIBCXX_LIST) && (!EIGEN_GNUC_AT_LEAST(4,1))) /* Note that before gcc-4.1 we already have: std::list::resize(size_type,const T&). */\n\nnamespace std\n{\n\n#define EIGEN_STD_LIST_SPECIALIZATION_BODY \\\n  public:  \\\n    typedef T value_type; \\\n    typedef typename list_base::allocator_type allocator_type; \\\n    typedef typename list_base::size_type size_type;  \\\n    typedef typename list_base::iterator iterator;  \\\n    typedef typename list_base::const_iterator const_iterator;  \\\n    explicit list(const allocator_type& a = allocator_type()) : list_base(a) {}  \\\n    template<typename InputIterator> \\\n    list(InputIterator first, InputIterator last, const allocator_type& a = allocator_type()) \\\n    : list_base(first, last, a) {} \\\n    list(const list& c) : list_base(c) {}  \\\n    explicit list(size_type num, const value_type& val = value_type()) : list_base(num, val) {} \\\n    list(iterator start_, iterator end_) : list_base(start_, end_) {}  \\\n    list& operator=(const list& x) {  \\\n    list_base::operator=(x);  \\\n    return *this; \\\n  }\n\n  template<typename T>\n  class list<T,EIGEN_ALIGNED_ALLOCATOR<T> >\n    : public list<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T),\n                  Eigen::aligned_allocator_indirection<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T)> >\n  {\n    typedef list<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T),\n                 Eigen::aligned_allocator_indirection<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T)> > list_base;\n    EIGEN_STD_LIST_SPECIALIZATION_BODY\n\n    void resize(size_type new_size)\n    { resize(new_size, T()); }\n\n    void resize(size_type new_size, const value_type& x)\n    {\n      if (list_base::size() < new_size)\n        list_base::insert(list_base::end(), new_size - list_base::size(), x);\n      else\n        while (new_size < list_base::size()) list_base::pop_back();\n    }\n\n#if defined(_LIST_)\n    // workaround MSVC std::list implementation\n    void push_back(const value_type& x)\n    { list_base::push_back(x); } \n    using list_base::insert;  \n    iterator insert(const_iterator position, const value_type& x)\n    { return list_base::insert(position,x); }\n    void insert(const_iterator position, size_type new_size, const value_type& x)\n    { list_base::insert(position, new_size, x); }\n#endif\n  };\n}\n\n#endif // check whether specialization is actually required\n\n#endif // EIGEN_STDLIST_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/StlSupport/StdVector.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Hauke Heibel <hauke.heibel@googlemail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_STDVECTOR_H\n#define EIGEN_STDVECTOR_H\n\n#include \"details.h\"\n\n/**\n * This section contains a convenience MACRO which allows an easy specialization of\n * std::vector such that for data types with alignment issues the correct allocator\n * is used automatically.\n */\n#define EIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(...) \\\nnamespace std \\\n{ \\\n  template<> \\\n  class vector<__VA_ARGS__, std::allocator<__VA_ARGS__> >  \\\n    : public vector<__VA_ARGS__, EIGEN_ALIGNED_ALLOCATOR<__VA_ARGS__> > \\\n  { \\\n    typedef vector<__VA_ARGS__, EIGEN_ALIGNED_ALLOCATOR<__VA_ARGS__> > vector_base; \\\n  public: \\\n    typedef __VA_ARGS__ value_type; \\\n    typedef vector_base::allocator_type allocator_type; \\\n    typedef vector_base::size_type size_type;  \\\n    typedef vector_base::iterator iterator;  \\\n    explicit vector(const allocator_type& a = allocator_type()) : vector_base(a) {}  \\\n    template<typename InputIterator> \\\n    vector(InputIterator first, InputIterator last, const allocator_type& a = allocator_type()) : vector_base(first, last, a) {} \\\n    vector(const vector& c) : vector_base(c) {}  \\\n    explicit vector(size_type num, const value_type& val = value_type()) : vector_base(num, val) {} \\\n    vector(iterator start_, iterator end_) : vector_base(start_, end_) {}  \\\n    vector& operator=(const vector& x) {  \\\n      vector_base::operator=(x);  \\\n      return *this;  \\\n    } \\\n  }; \\\n}\n\n// Don't specialize if containers are implemented according to C++11\n#if !EIGEN_HAS_CXX11_CONTAINERS\n\nnamespace std {\n\n#define EIGEN_STD_VECTOR_SPECIALIZATION_BODY \\\n  public:  \\\n    typedef T value_type; \\\n    typedef typename vector_base::allocator_type allocator_type; \\\n    typedef typename vector_base::size_type size_type;  \\\n    typedef typename vector_base::iterator iterator;  \\\n    typedef typename vector_base::const_iterator const_iterator;  \\\n    explicit vector(const allocator_type& a = allocator_type()) : vector_base(a) {}  \\\n    template<typename InputIterator> \\\n    vector(InputIterator first, InputIterator last, const allocator_type& a = allocator_type()) \\\n    : vector_base(first, last, a) {} \\\n    vector(const vector& c) : vector_base(c) {}  \\\n    explicit vector(size_type num, const value_type& val = value_type()) : vector_base(num, val) {} \\\n    vector(iterator start_, iterator end_) : vector_base(start_, end_) {}  \\\n    vector& operator=(const vector& x) {  \\\n      vector_base::operator=(x);  \\\n      return *this;  \\\n    }\n\n  template<typename T>\n  class vector<T,EIGEN_ALIGNED_ALLOCATOR<T> >\n    : public vector<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T),\n                    Eigen::aligned_allocator_indirection<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T)> >\n{\n  typedef vector<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T),\n                 Eigen::aligned_allocator_indirection<EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T)> > vector_base;\n  EIGEN_STD_VECTOR_SPECIALIZATION_BODY\n\n  void resize(size_type new_size)\n  { resize(new_size, T()); }\n\n#if defined(_VECTOR_)\n  // workaround MSVC std::vector implementation\n  void resize(size_type new_size, const value_type& x)\n  {\n    if (vector_base::size() < new_size)\n      vector_base::_Insert_n(vector_base::end(), new_size - vector_base::size(), x);\n    else if (new_size < vector_base::size())\n      vector_base::erase(vector_base::begin() + new_size, vector_base::end());\n  }\n  void push_back(const value_type& x)\n  { vector_base::push_back(x); } \n  using vector_base::insert;  \n  iterator insert(const_iterator position, const value_type& x)\n  { return vector_base::insert(position,x); }\n  void insert(const_iterator position, size_type new_size, const value_type& x)\n  { vector_base::insert(position, new_size, x); }\n#elif defined(_GLIBCXX_VECTOR) && (!(EIGEN_GNUC_AT_LEAST(4,1)))\n  /* Note that before gcc-4.1 we already have: std::vector::resize(size_type,const T&).\n   * However, this specialization is still needed to make the above EIGEN_DEFINE_STL_VECTOR_SPECIALIZATION trick to work. */\n  void resize(size_type new_size, const value_type& x)\n  {\n    vector_base::resize(new_size,x);\n  }\n#elif defined(_GLIBCXX_VECTOR) && EIGEN_GNUC_AT_LEAST(4,2)\n  // workaround GCC std::vector implementation\n  void resize(size_type new_size, const value_type& x)\n  {\n    if (new_size < vector_base::size())\n      vector_base::_M_erase_at_end(this->_M_impl._M_start + new_size);\n    else\n      vector_base::insert(vector_base::end(), new_size - vector_base::size(), x);\n  }\n#else\n  // either GCC 4.1 or non-GCC\n  // default implementation which should always work.\n  void resize(size_type new_size, const value_type& x)\n  {\n    if (new_size < vector_base::size())\n      vector_base::erase(vector_base::begin() + new_size, vector_base::end());\n    else if (new_size > vector_base::size())\n      vector_base::insert(vector_base::end(), new_size - vector_base::size(), x);\n  }\n#endif\n  };\n}\n#endif // !EIGEN_HAS_CXX11_CONTAINERS\n\n\n#endif // EIGEN_STDVECTOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/StlSupport/details.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Hauke Heibel <hauke.heibel@googlemail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_STL_DETAILS_H\n#define EIGEN_STL_DETAILS_H\n\n#ifndef EIGEN_ALIGNED_ALLOCATOR\n  #define EIGEN_ALIGNED_ALLOCATOR Eigen::aligned_allocator\n#endif\n\nnamespace Eigen {\n\n  // This one is needed to prevent reimplementing the whole std::vector.\n  template <class T>\n  class aligned_allocator_indirection : public EIGEN_ALIGNED_ALLOCATOR<T>\n  {\n  public:\n    typedef std::size_t     size_type;\n    typedef std::ptrdiff_t  difference_type;\n    typedef T*              pointer;\n    typedef const T*        const_pointer;\n    typedef T&              reference;\n    typedef const T&        const_reference;\n    typedef T               value_type;\n\n    template<class U>\n    struct rebind\n    {\n      typedef aligned_allocator_indirection<U> other;\n    };\n\n    aligned_allocator_indirection() {}\n    aligned_allocator_indirection(const aligned_allocator_indirection& ) : EIGEN_ALIGNED_ALLOCATOR<T>() {}\n    aligned_allocator_indirection(const EIGEN_ALIGNED_ALLOCATOR<T>& ) {}\n    template<class U>\n    aligned_allocator_indirection(const aligned_allocator_indirection<U>& ) {}\n    template<class U>\n    aligned_allocator_indirection(const EIGEN_ALIGNED_ALLOCATOR<U>& ) {}\n    ~aligned_allocator_indirection() {}\n  };\n\n#if EIGEN_COMP_MSVC\n\n  // sometimes, MSVC detects, at compile time, that the argument x\n  // in std::vector::resize(size_t s,T x) won't be aligned and generate an error\n  // even if this function is never called. Whence this little wrapper.\n#define EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T) \\\n  typename Eigen::internal::conditional< \\\n    Eigen::internal::is_arithmetic<T>::value, \\\n    T, \\\n    Eigen::internal::workaround_msvc_stl_support<T> \\\n  >::type\n\n  namespace internal {\n  template<typename T> struct workaround_msvc_stl_support : public T\n  {\n    inline workaround_msvc_stl_support() : T() {}\n    inline workaround_msvc_stl_support(const T& other) : T(other) {}\n    inline operator T& () { return *static_cast<T*>(this); }\n    inline operator const T& () const { return *static_cast<const T*>(this); }\n    template<typename OtherT>\n    inline T& operator=(const OtherT& other)\n    { T::operator=(other); return *this; }\n    inline workaround_msvc_stl_support& operator=(const workaround_msvc_stl_support& other)\n    { T::operator=(other); return *this; }\n  };\n  }\n\n#else\n\n#define EIGEN_WORKAROUND_MSVC_STL_SUPPORT(T) T\n\n#endif\n\n}\n\n#endif // EIGEN_STL_DETAILS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/SuperLUSupport/SuperLUSupport.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SUPERLUSUPPORT_H\n#define EIGEN_SUPERLUSUPPORT_H\n\nnamespace Eigen {\n\n#if defined(SUPERLU_MAJOR_VERSION) && (SUPERLU_MAJOR_VERSION >= 5)\n#define DECL_GSSVX(PREFIX,FLOATTYPE,KEYTYPE)\t\t\\\n    extern \"C\" {                                                                                          \\\n      extern void PREFIX##gssvx(superlu_options_t *, SuperMatrix *, int *, int *, int *,                  \\\n                                char *, FLOATTYPE *, FLOATTYPE *, SuperMatrix *, SuperMatrix *,           \\\n                                void *, int, SuperMatrix *, SuperMatrix *,                                \\\n                                FLOATTYPE *, FLOATTYPE *, FLOATTYPE *, FLOATTYPE *,                       \\\n                                GlobalLU_t *, mem_usage_t *, SuperLUStat_t *, int *);                     \\\n    }                                                                                                     \\\n    inline float SuperLU_gssvx(superlu_options_t *options, SuperMatrix *A,                                \\\n         int *perm_c, int *perm_r, int *etree, char *equed,                                               \\\n         FLOATTYPE *R, FLOATTYPE *C, SuperMatrix *L,                                                      \\\n         SuperMatrix *U, void *work, int lwork,                                                           \\\n         SuperMatrix *B, SuperMatrix *X,                                                                  \\\n         FLOATTYPE *recip_pivot_growth,                                                                   \\\n         FLOATTYPE *rcond, FLOATTYPE *ferr, FLOATTYPE *berr,                                              \\\n         SuperLUStat_t *stats, int *info, KEYTYPE) {                                                      \\\n    mem_usage_t mem_usage;                                                                                \\\n    GlobalLU_t gLU;                                                                                       \\\n    PREFIX##gssvx(options, A, perm_c, perm_r, etree, equed, R, C, L,                                      \\\n         U, work, lwork, B, X, recip_pivot_growth, rcond,                                                 \\\n         ferr, berr, &gLU, &mem_usage, stats, info);                                                      \\\n    return mem_usage.for_lu; /* bytes used by the factor storage */                                       \\\n  }\n#else // version < 5.0\n#define DECL_GSSVX(PREFIX,FLOATTYPE,KEYTYPE)\t\t\\\n    extern \"C\" {                                                                                          \\\n      extern void PREFIX##gssvx(superlu_options_t *, SuperMatrix *, int *, int *, int *,                  \\\n                                char *, FLOATTYPE *, FLOATTYPE *, SuperMatrix *, SuperMatrix *,           \\\n                                void *, int, SuperMatrix *, SuperMatrix *,                                \\\n                                FLOATTYPE *, FLOATTYPE *, FLOATTYPE *, FLOATTYPE *,                       \\\n                                mem_usage_t *, SuperLUStat_t *, int *);                                   \\\n    }                                                                                                     \\\n    inline float SuperLU_gssvx(superlu_options_t *options, SuperMatrix *A,                                \\\n         int *perm_c, int *perm_r, int *etree, char *equed,                                               \\\n         FLOATTYPE *R, FLOATTYPE *C, SuperMatrix *L,                                                      \\\n         SuperMatrix *U, void *work, int lwork,                                                           \\\n         SuperMatrix *B, SuperMatrix *X,                                                                  \\\n         FLOATTYPE *recip_pivot_growth,                                                                   \\\n         FLOATTYPE *rcond, FLOATTYPE *ferr, FLOATTYPE *berr,                                              \\\n         SuperLUStat_t *stats, int *info, KEYTYPE) {                                                      \\\n    mem_usage_t mem_usage;                                                                                \\\n    PREFIX##gssvx(options, A, perm_c, perm_r, etree, equed, R, C, L,                                      \\\n         U, work, lwork, B, X, recip_pivot_growth, rcond,                                                 \\\n         ferr, berr, &mem_usage, stats, info);                                                            \\\n    return mem_usage.for_lu; /* bytes used by the factor storage */                                       \\\n  }\n#endif\n\nDECL_GSSVX(s,float,float)\nDECL_GSSVX(c,float,std::complex<float>)\nDECL_GSSVX(d,double,double)\nDECL_GSSVX(z,double,std::complex<double>)\n\n#ifdef MILU_ALPHA\n#define EIGEN_SUPERLU_HAS_ILU\n#endif\n\n#ifdef EIGEN_SUPERLU_HAS_ILU\n\n// similarly for the incomplete factorization using gsisx\n#define DECL_GSISX(PREFIX,FLOATTYPE,KEYTYPE)                                                    \\\n    extern \"C\" {                                                                                \\\n      extern void PREFIX##gsisx(superlu_options_t *, SuperMatrix *, int *, int *, int *,        \\\n                         char *, FLOATTYPE *, FLOATTYPE *, SuperMatrix *, SuperMatrix *,        \\\n                         void *, int, SuperMatrix *, SuperMatrix *, FLOATTYPE *, FLOATTYPE *,   \\\n                         mem_usage_t *, SuperLUStat_t *, int *);                        \\\n    }                                                                                           \\\n    inline float SuperLU_gsisx(superlu_options_t *options, SuperMatrix *A,                      \\\n         int *perm_c, int *perm_r, int *etree, char *equed,                                     \\\n         FLOATTYPE *R, FLOATTYPE *C, SuperMatrix *L,                                            \\\n         SuperMatrix *U, void *work, int lwork,                                                 \\\n         SuperMatrix *B, SuperMatrix *X,                                                        \\\n         FLOATTYPE *recip_pivot_growth,                                                         \\\n         FLOATTYPE *rcond,                                                                      \\\n         SuperLUStat_t *stats, int *info, KEYTYPE) {                                            \\\n    mem_usage_t mem_usage;                                                              \\\n    PREFIX##gsisx(options, A, perm_c, perm_r, etree, equed, R, C, L,                            \\\n         U, work, lwork, B, X, recip_pivot_growth, rcond,                                       \\\n         &mem_usage, stats, info);                                                              \\\n    return mem_usage.for_lu; /* bytes used by the factor storage */                             \\\n  }\n\nDECL_GSISX(s,float,float)\nDECL_GSISX(c,float,std::complex<float>)\nDECL_GSISX(d,double,double)\nDECL_GSISX(z,double,std::complex<double>)\n\n#endif\n\ntemplate<typename MatrixType>\nstruct SluMatrixMapHelper;\n\n/** \\internal\n  *\n  * A wrapper class for SuperLU matrices. It supports only compressed sparse matrices\n  * and dense matrices. Supernodal and other fancy format are not supported by this wrapper.\n  *\n  * This wrapper class mainly aims to avoids the need of dynamic allocation of the storage structure.\n  */\nstruct SluMatrix : SuperMatrix\n{\n  SluMatrix()\n  {\n    Store = &storage;\n  }\n\n  SluMatrix(const SluMatrix& other)\n    : SuperMatrix(other)\n  {\n    Store = &storage;\n    storage = other.storage;\n  }\n\n  SluMatrix& operator=(const SluMatrix& other)\n  {\n    SuperMatrix::operator=(static_cast<const SuperMatrix&>(other));\n    Store = &storage;\n    storage = other.storage;\n    return *this;\n  }\n\n  struct\n  {\n    union {int nnz;int lda;};\n    void *values;\n    int *innerInd;\n    int *outerInd;\n  } storage;\n\n  void setStorageType(Stype_t t)\n  {\n    Stype = t;\n    if (t==SLU_NC || t==SLU_NR || t==SLU_DN)\n      Store = &storage;\n    else\n    {\n      eigen_assert(false && \"storage type not supported\");\n      Store = 0;\n    }\n  }\n\n  template<typename Scalar>\n  void setScalarType()\n  {\n    if (internal::is_same<Scalar,float>::value)\n      Dtype = SLU_S;\n    else if (internal::is_same<Scalar,double>::value)\n      Dtype = SLU_D;\n    else if (internal::is_same<Scalar,std::complex<float> >::value)\n      Dtype = SLU_C;\n    else if (internal::is_same<Scalar,std::complex<double> >::value)\n      Dtype = SLU_Z;\n    else\n    {\n      eigen_assert(false && \"Scalar type not supported by SuperLU\");\n    }\n  }\n\n  template<typename MatrixType>\n  static SluMatrix Map(MatrixBase<MatrixType>& _mat)\n  {\n    MatrixType& mat(_mat.derived());\n    eigen_assert( ((MatrixType::Flags&RowMajorBit)!=RowMajorBit) && \"row-major dense matrices are not supported by SuperLU\");\n    SluMatrix res;\n    res.setStorageType(SLU_DN);\n    res.setScalarType<typename MatrixType::Scalar>();\n    res.Mtype     = SLU_GE;\n\n    res.nrow      = internal::convert_index<int>(mat.rows());\n    res.ncol      = internal::convert_index<int>(mat.cols());\n\n    res.storage.lda       = internal::convert_index<int>(MatrixType::IsVectorAtCompileTime ? mat.size() : mat.outerStride());\n    res.storage.values    = (void*)(mat.data());\n    return res;\n  }\n\n  template<typename MatrixType>\n  static SluMatrix Map(SparseMatrixBase<MatrixType>& a_mat)\n  {\n    MatrixType &mat(a_mat.derived());\n    SluMatrix res;\n    if ((MatrixType::Flags&RowMajorBit)==RowMajorBit)\n    {\n      res.setStorageType(SLU_NR);\n      res.nrow      = internal::convert_index<int>(mat.cols());\n      res.ncol      = internal::convert_index<int>(mat.rows());\n    }\n    else\n    {\n      res.setStorageType(SLU_NC);\n      res.nrow      = internal::convert_index<int>(mat.rows());\n      res.ncol      = internal::convert_index<int>(mat.cols());\n    }\n\n    res.Mtype       = SLU_GE;\n\n    res.storage.nnz       = internal::convert_index<int>(mat.nonZeros());\n    res.storage.values    = mat.valuePtr();\n    res.storage.innerInd  = mat.innerIndexPtr();\n    res.storage.outerInd  = mat.outerIndexPtr();\n\n    res.setScalarType<typename MatrixType::Scalar>();\n\n    // FIXME the following is not very accurate\n    if (int(MatrixType::Flags) & int(Upper))\n      res.Mtype = SLU_TRU;\n    if (int(MatrixType::Flags) & int(Lower))\n      res.Mtype = SLU_TRL;\n\n    eigen_assert(((int(MatrixType::Flags) & int(SelfAdjoint))==0) && \"SelfAdjoint matrix shape not supported by SuperLU\");\n\n    return res;\n  }\n};\n\ntemplate<typename Scalar, int Rows, int Cols, int Options, int MRows, int MCols>\nstruct SluMatrixMapHelper<Matrix<Scalar,Rows,Cols,Options,MRows,MCols> >\n{\n  typedef Matrix<Scalar,Rows,Cols,Options,MRows,MCols> MatrixType;\n  static void run(MatrixType& mat, SluMatrix& res)\n  {\n    eigen_assert( ((Options&RowMajor)!=RowMajor) && \"row-major dense matrices is not supported by SuperLU\");\n    res.setStorageType(SLU_DN);\n    res.setScalarType<Scalar>();\n    res.Mtype     = SLU_GE;\n\n    res.nrow      = mat.rows();\n    res.ncol      = mat.cols();\n\n    res.storage.lda       = mat.outerStride();\n    res.storage.values    = mat.data();\n  }\n};\n\ntemplate<typename Derived>\nstruct SluMatrixMapHelper<SparseMatrixBase<Derived> >\n{\n  typedef Derived MatrixType;\n  static void run(MatrixType& mat, SluMatrix& res)\n  {\n    if ((MatrixType::Flags&RowMajorBit)==RowMajorBit)\n    {\n      res.setStorageType(SLU_NR);\n      res.nrow      = mat.cols();\n      res.ncol      = mat.rows();\n    }\n    else\n    {\n      res.setStorageType(SLU_NC);\n      res.nrow      = mat.rows();\n      res.ncol      = mat.cols();\n    }\n\n    res.Mtype       = SLU_GE;\n\n    res.storage.nnz       = mat.nonZeros();\n    res.storage.values    = mat.valuePtr();\n    res.storage.innerInd  = mat.innerIndexPtr();\n    res.storage.outerInd  = mat.outerIndexPtr();\n\n    res.setScalarType<typename MatrixType::Scalar>();\n\n    // FIXME the following is not very accurate\n    if (MatrixType::Flags & Upper)\n      res.Mtype = SLU_TRU;\n    if (MatrixType::Flags & Lower)\n      res.Mtype = SLU_TRL;\n\n    eigen_assert(((MatrixType::Flags & SelfAdjoint)==0) && \"SelfAdjoint matrix shape not supported by SuperLU\");\n  }\n};\n\nnamespace internal {\n\ntemplate<typename MatrixType>\nSluMatrix asSluMatrix(MatrixType& mat)\n{\n  return SluMatrix::Map(mat);\n}\n\n/** View a Super LU matrix as an Eigen expression */\ntemplate<typename Scalar, int Flags, typename Index>\nMappedSparseMatrix<Scalar,Flags,Index> map_superlu(SluMatrix& sluMat)\n{\n  eigen_assert(((Flags&RowMajor)==RowMajor && sluMat.Stype == SLU_NR)\n         || ((Flags&ColMajor)==ColMajor && sluMat.Stype == SLU_NC));\n\n  Index outerSize = (Flags&RowMajor)==RowMajor ? sluMat.ncol : sluMat.nrow;\n\n  return MappedSparseMatrix<Scalar,Flags,Index>(\n    sluMat.nrow, sluMat.ncol, sluMat.storage.outerInd[outerSize],\n    sluMat.storage.outerInd, sluMat.storage.innerInd, reinterpret_cast<Scalar*>(sluMat.storage.values) );\n}\n\n} // end namespace internal\n\n/** \\ingroup SuperLUSupport_Module\n  * \\class SuperLUBase\n  * \\brief The base class for the direct and incomplete LU factorization of SuperLU\n  */\ntemplate<typename _MatrixType, typename Derived>\nclass SuperLUBase : public SparseSolverBase<Derived>\n{\n  protected:\n    typedef SparseSolverBase<Derived> Base;\n    using Base::derived;\n    using Base::m_isInitialized;\n  public:\n    typedef _MatrixType MatrixType;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef Matrix<Scalar,Dynamic,1> Vector;\n    typedef Matrix<int, 1, MatrixType::ColsAtCompileTime> IntRowVectorType;\n    typedef Matrix<int, MatrixType::RowsAtCompileTime, 1> IntColVectorType;    \n    typedef Map<PermutationMatrix<Dynamic,Dynamic,int> > PermutationMap;\n    typedef SparseMatrix<Scalar> LUMatrixType;\n    enum {\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n\n  public:\n\n    SuperLUBase() {}\n\n    ~SuperLUBase()\n    {\n      clearFactors();\n    }\n    \n    inline Index rows() const { return m_matrix.rows(); }\n    inline Index cols() const { return m_matrix.cols(); }\n    \n    /** \\returns a reference to the Super LU option object to configure the  Super LU algorithms. */\n    inline superlu_options_t& options() { return m_sluOptions; }\n    \n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the matrix.appears to be negative.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_info;\n    }\n\n    /** Computes the sparse Cholesky decomposition of \\a matrix */\n    void compute(const MatrixType& matrix)\n    {\n      derived().analyzePattern(matrix);\n      derived().factorize(matrix);\n    }\n\n    /** Performs a symbolic decomposition on the sparcity of \\a matrix.\n      *\n      * This function is particularly useful when solving for several problems having the same structure.\n      * \n      * \\sa factorize()\n      */\n    void analyzePattern(const MatrixType& /*matrix*/)\n    {\n      m_isInitialized = true;\n      m_info = Success;\n      m_analysisIsOk = true;\n      m_factorizationIsOk = false;\n    }\n    \n    template<typename Stream>\n    void dumpMemory(Stream& /*s*/)\n    {}\n    \n  protected:\n    \n    void initFactorization(const MatrixType& a)\n    {\n      set_default_options(&this->m_sluOptions);\n      \n      const Index size = a.rows();\n      m_matrix = a;\n\n      m_sluA = internal::asSluMatrix(m_matrix);\n      clearFactors();\n\n      m_p.resize(size);\n      m_q.resize(size);\n      m_sluRscale.resize(size);\n      m_sluCscale.resize(size);\n      m_sluEtree.resize(size);\n\n      // set empty B and X\n      m_sluB.setStorageType(SLU_DN);\n      m_sluB.setScalarType<Scalar>();\n      m_sluB.Mtype          = SLU_GE;\n      m_sluB.storage.values = 0;\n      m_sluB.nrow           = 0;\n      m_sluB.ncol           = 0;\n      m_sluB.storage.lda    = internal::convert_index<int>(size);\n      m_sluX                = m_sluB;\n      \n      m_extractedDataAreDirty = true;\n    }\n    \n    void init()\n    {\n      m_info = InvalidInput;\n      m_isInitialized = false;\n      m_sluL.Store = 0;\n      m_sluU.Store = 0;\n    }\n    \n    void extractData() const;\n\n    void clearFactors()\n    {\n      if(m_sluL.Store)\n        Destroy_SuperNode_Matrix(&m_sluL);\n      if(m_sluU.Store)\n        Destroy_CompCol_Matrix(&m_sluU);\n\n      m_sluL.Store = 0;\n      m_sluU.Store = 0;\n\n      memset(&m_sluL,0,sizeof m_sluL);\n      memset(&m_sluU,0,sizeof m_sluU);\n    }\n\n    // cached data to reduce reallocation, etc.\n    mutable LUMatrixType m_l;\n    mutable LUMatrixType m_u;\n    mutable IntColVectorType m_p;\n    mutable IntRowVectorType m_q;\n\n    mutable LUMatrixType m_matrix;  // copy of the factorized matrix\n    mutable SluMatrix m_sluA;\n    mutable SuperMatrix m_sluL, m_sluU;\n    mutable SluMatrix m_sluB, m_sluX;\n    mutable SuperLUStat_t m_sluStat;\n    mutable superlu_options_t m_sluOptions;\n    mutable std::vector<int> m_sluEtree;\n    mutable Matrix<RealScalar,Dynamic,1> m_sluRscale, m_sluCscale;\n    mutable Matrix<RealScalar,Dynamic,1> m_sluFerr, m_sluBerr;\n    mutable char m_sluEqued;\n\n    mutable ComputationInfo m_info;\n    int m_factorizationIsOk;\n    int m_analysisIsOk;\n    mutable bool m_extractedDataAreDirty;\n    \n  private:\n    SuperLUBase(SuperLUBase& ) { }\n};\n\n\n/** \\ingroup SuperLUSupport_Module\n  * \\class SuperLU\n  * \\brief A sparse direct LU factorization and solver based on the SuperLU library\n  *\n  * This class allows to solve for A.X = B sparse linear problems via a direct LU factorization\n  * using the SuperLU library. The sparse matrix A must be squared and invertible. The vectors or matrices\n  * X and B can be either dense or sparse.\n  *\n  * \\tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>\n  *\n  * \\warning This class is only for the 4.x versions of SuperLU. The 3.x and 5.x versions are not supported.\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class SparseLU\n  */\ntemplate<typename _MatrixType>\nclass SuperLU : public SuperLUBase<_MatrixType,SuperLU<_MatrixType> >\n{\n  public:\n    typedef SuperLUBase<_MatrixType,SuperLU> Base;\n    typedef _MatrixType MatrixType;\n    typedef typename Base::Scalar Scalar;\n    typedef typename Base::RealScalar RealScalar;\n    typedef typename Base::StorageIndex StorageIndex;\n    typedef typename Base::IntRowVectorType IntRowVectorType;\n    typedef typename Base::IntColVectorType IntColVectorType;   \n    typedef typename Base::PermutationMap PermutationMap;\n    typedef typename Base::LUMatrixType LUMatrixType;\n    typedef TriangularView<LUMatrixType, Lower|UnitDiag>  LMatrixType;\n    typedef TriangularView<LUMatrixType,  Upper>          UMatrixType;\n\n  public:\n    using Base::_solve_impl;\n\n    SuperLU() : Base() { init(); }\n\n    explicit SuperLU(const MatrixType& matrix) : Base()\n    {\n      init();\n      Base::compute(matrix);\n    }\n\n    ~SuperLU()\n    {\n    }\n    \n    /** Performs a symbolic decomposition on the sparcity of \\a matrix.\n      *\n      * This function is particularly useful when solving for several problems having the same structure.\n      * \n      * \\sa factorize()\n      */\n    void analyzePattern(const MatrixType& matrix)\n    {\n      m_info = InvalidInput;\n      m_isInitialized = false;\n      Base::analyzePattern(matrix);\n    }\n    \n    /** Performs a numeric decomposition of \\a matrix\n      *\n      * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed.\n      *\n      * \\sa analyzePattern()\n      */\n    void factorize(const MatrixType& matrix);\n    \n    /** \\internal */\n    template<typename Rhs,typename Dest>\n    void _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const;\n    \n    inline const LMatrixType& matrixL() const\n    {\n      if (m_extractedDataAreDirty) this->extractData();\n      return m_l;\n    }\n\n    inline const UMatrixType& matrixU() const\n    {\n      if (m_extractedDataAreDirty) this->extractData();\n      return m_u;\n    }\n\n    inline const IntColVectorType& permutationP() const\n    {\n      if (m_extractedDataAreDirty) this->extractData();\n      return m_p;\n    }\n\n    inline const IntRowVectorType& permutationQ() const\n    {\n      if (m_extractedDataAreDirty) this->extractData();\n      return m_q;\n    }\n    \n    Scalar determinant() const;\n    \n  protected:\n    \n    using Base::m_matrix;\n    using Base::m_sluOptions;\n    using Base::m_sluA;\n    using Base::m_sluB;\n    using Base::m_sluX;\n    using Base::m_p;\n    using Base::m_q;\n    using Base::m_sluEtree;\n    using Base::m_sluEqued;\n    using Base::m_sluRscale;\n    using Base::m_sluCscale;\n    using Base::m_sluL;\n    using Base::m_sluU;\n    using Base::m_sluStat;\n    using Base::m_sluFerr;\n    using Base::m_sluBerr;\n    using Base::m_l;\n    using Base::m_u;\n    \n    using Base::m_analysisIsOk;\n    using Base::m_factorizationIsOk;\n    using Base::m_extractedDataAreDirty;\n    using Base::m_isInitialized;\n    using Base::m_info;\n    \n    void init()\n    {\n      Base::init();\n      \n      set_default_options(&this->m_sluOptions);\n      m_sluOptions.PrintStat        = NO;\n      m_sluOptions.ConditionNumber  = NO;\n      m_sluOptions.Trans            = NOTRANS;\n      m_sluOptions.ColPerm          = COLAMD;\n    }\n    \n    \n  private:\n    SuperLU(SuperLU& ) { }\n};\n\ntemplate<typename MatrixType>\nvoid SuperLU<MatrixType>::factorize(const MatrixType& a)\n{\n  eigen_assert(m_analysisIsOk && \"You must first call analyzePattern()\");\n  if(!m_analysisIsOk)\n  {\n    m_info = InvalidInput;\n    return;\n  }\n  \n  this->initFactorization(a);\n  \n  m_sluOptions.ColPerm = COLAMD;\n  int info = 0;\n  RealScalar recip_pivot_growth, rcond;\n  RealScalar ferr, berr;\n\n  StatInit(&m_sluStat);\n  SuperLU_gssvx(&m_sluOptions, &m_sluA, m_q.data(), m_p.data(), &m_sluEtree[0],\n                &m_sluEqued, &m_sluRscale[0], &m_sluCscale[0],\n                &m_sluL, &m_sluU,\n                NULL, 0,\n                &m_sluB, &m_sluX,\n                &recip_pivot_growth, &rcond,\n                &ferr, &berr,\n                &m_sluStat, &info, Scalar());\n  StatFree(&m_sluStat);\n\n  m_extractedDataAreDirty = true;\n\n  // FIXME how to better check for errors ???\n  m_info = info == 0 ? Success : NumericalIssue;\n  m_factorizationIsOk = true;\n}\n\ntemplate<typename MatrixType>\ntemplate<typename Rhs,typename Dest>\nvoid SuperLU<MatrixType>::_solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest>& x) const\n{\n  eigen_assert(m_factorizationIsOk && \"The decomposition is not in a valid state for solving, you must first call either compute() or analyzePattern()/factorize()\");\n\n  const Index rhsCols = b.cols();\n  eigen_assert(m_matrix.rows()==b.rows());\n\n  m_sluOptions.Trans = NOTRANS;\n  m_sluOptions.Fact = FACTORED;\n  m_sluOptions.IterRefine = NOREFINE;\n  \n\n  m_sluFerr.resize(rhsCols);\n  m_sluBerr.resize(rhsCols);\n  \n  Ref<const Matrix<typename Rhs::Scalar,Dynamic,Dynamic,ColMajor> > b_ref(b);\n  Ref<const Matrix<typename Dest::Scalar,Dynamic,Dynamic,ColMajor> > x_ref(x);\n  \n  m_sluB = SluMatrix::Map(b_ref.const_cast_derived());\n  m_sluX = SluMatrix::Map(x_ref.const_cast_derived());\n  \n  typename Rhs::PlainObject b_cpy;\n  if(m_sluEqued!='N')\n  {\n    b_cpy = b;\n    m_sluB = SluMatrix::Map(b_cpy.const_cast_derived());  \n  }\n\n  StatInit(&m_sluStat);\n  int info = 0;\n  RealScalar recip_pivot_growth, rcond;\n  SuperLU_gssvx(&m_sluOptions, &m_sluA,\n                m_q.data(), m_p.data(),\n                &m_sluEtree[0], &m_sluEqued,\n                &m_sluRscale[0], &m_sluCscale[0],\n                &m_sluL, &m_sluU,\n                NULL, 0,\n                &m_sluB, &m_sluX,\n                &recip_pivot_growth, &rcond,\n                &m_sluFerr[0], &m_sluBerr[0],\n                &m_sluStat, &info, Scalar());\n  StatFree(&m_sluStat);\n  \n  if(x.derived().data() != x_ref.data())\n    x = x_ref;\n  \n  m_info = info==0 ? Success : NumericalIssue;\n}\n\n// the code of this extractData() function has been adapted from the SuperLU's Matlab support code,\n//\n//  Copyright (c) 1994 by Xerox Corporation.  All rights reserved.\n//\n//  THIS MATERIAL IS PROVIDED AS IS, WITH ABSOLUTELY NO WARRANTY\n//  EXPRESSED OR IMPLIED.  ANY USE IS AT YOUR OWN RISK.\n//\ntemplate<typename MatrixType, typename Derived>\nvoid SuperLUBase<MatrixType,Derived>::extractData() const\n{\n  eigen_assert(m_factorizationIsOk && \"The decomposition is not in a valid state for extracting factors, you must first call either compute() or analyzePattern()/factorize()\");\n  if (m_extractedDataAreDirty)\n  {\n    int         upper;\n    int         fsupc, istart, nsupr;\n    int         lastl = 0, lastu = 0;\n    SCformat    *Lstore = static_cast<SCformat*>(m_sluL.Store);\n    NCformat    *Ustore = static_cast<NCformat*>(m_sluU.Store);\n    Scalar      *SNptr;\n\n    const Index size = m_matrix.rows();\n    m_l.resize(size,size);\n    m_l.resizeNonZeros(Lstore->nnz);\n    m_u.resize(size,size);\n    m_u.resizeNonZeros(Ustore->nnz);\n\n    int* Lcol = m_l.outerIndexPtr();\n    int* Lrow = m_l.innerIndexPtr();\n    Scalar* Lval = m_l.valuePtr();\n\n    int* Ucol = m_u.outerIndexPtr();\n    int* Urow = m_u.innerIndexPtr();\n    Scalar* Uval = m_u.valuePtr();\n\n    Ucol[0] = 0;\n    Ucol[0] = 0;\n\n    /* for each supernode */\n    for (int k = 0; k <= Lstore->nsuper; ++k)\n    {\n      fsupc   = L_FST_SUPC(k);\n      istart  = L_SUB_START(fsupc);\n      nsupr   = L_SUB_START(fsupc+1) - istart;\n      upper   = 1;\n\n      /* for each column in the supernode */\n      for (int j = fsupc; j < L_FST_SUPC(k+1); ++j)\n      {\n        SNptr = &((Scalar*)Lstore->nzval)[L_NZ_START(j)];\n\n        /* Extract U */\n        for (int i = U_NZ_START(j); i < U_NZ_START(j+1); ++i)\n        {\n          Uval[lastu] = ((Scalar*)Ustore->nzval)[i];\n          /* Matlab doesn't like explicit zero. */\n          if (Uval[lastu] != 0.0)\n            Urow[lastu++] = U_SUB(i);\n        }\n        for (int i = 0; i < upper; ++i)\n        {\n          /* upper triangle in the supernode */\n          Uval[lastu] = SNptr[i];\n          /* Matlab doesn't like explicit zero. */\n          if (Uval[lastu] != 0.0)\n            Urow[lastu++] = L_SUB(istart+i);\n        }\n        Ucol[j+1] = lastu;\n\n        /* Extract L */\n        Lval[lastl] = 1.0; /* unit diagonal */\n        Lrow[lastl++] = L_SUB(istart + upper - 1);\n        for (int i = upper; i < nsupr; ++i)\n        {\n          Lval[lastl] = SNptr[i];\n          /* Matlab doesn't like explicit zero. */\n          if (Lval[lastl] != 0.0)\n            Lrow[lastl++] = L_SUB(istart+i);\n        }\n        Lcol[j+1] = lastl;\n\n        ++upper;\n      } /* for j ... */\n\n    } /* for k ... */\n\n    // squeeze the matrices :\n    m_l.resizeNonZeros(lastl);\n    m_u.resizeNonZeros(lastu);\n\n    m_extractedDataAreDirty = false;\n  }\n}\n\ntemplate<typename MatrixType>\ntypename SuperLU<MatrixType>::Scalar SuperLU<MatrixType>::determinant() const\n{\n  eigen_assert(m_factorizationIsOk && \"The decomposition is not in a valid state for computing the determinant, you must first call either compute() or analyzePattern()/factorize()\");\n  \n  if (m_extractedDataAreDirty)\n    this->extractData();\n\n  Scalar det = Scalar(1);\n  for (int j=0; j<m_u.cols(); ++j)\n  {\n    if (m_u.outerIndexPtr()[j+1]-m_u.outerIndexPtr()[j] > 0)\n    {\n      int lastId = m_u.outerIndexPtr()[j+1]-1;\n      eigen_assert(m_u.innerIndexPtr()[lastId]<=j);\n      if (m_u.innerIndexPtr()[lastId]==j)\n        det *= m_u.valuePtr()[lastId];\n    }\n  }\n  if(PermutationMap(m_p.data(),m_p.size()).determinant()*PermutationMap(m_q.data(),m_q.size()).determinant()<0)\n    det = -det;\n  if(m_sluEqued!='N')\n    return det/m_sluRscale.prod()/m_sluCscale.prod();\n  else\n    return det;\n}\n\n#ifdef EIGEN_PARSED_BY_DOXYGEN\n#define EIGEN_SUPERLU_HAS_ILU\n#endif\n\n#ifdef EIGEN_SUPERLU_HAS_ILU\n\n/** \\ingroup SuperLUSupport_Module\n  * \\class SuperILU\n  * \\brief A sparse direct \\b incomplete LU factorization and solver based on the SuperLU library\n  *\n  * This class allows to solve for an approximate solution of A.X = B sparse linear problems via an incomplete LU factorization\n  * using the SuperLU library. This class is aimed to be used as a preconditioner of the iterative linear solvers.\n  *\n  * \\warning This class is only for the 4.x versions of SuperLU. The 3.x and 5.x versions are not supported.\n  *\n  * \\tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class IncompleteLUT, class ConjugateGradient, class BiCGSTAB\n  */\n\ntemplate<typename _MatrixType>\nclass SuperILU : public SuperLUBase<_MatrixType,SuperILU<_MatrixType> >\n{\n  public:\n    typedef SuperLUBase<_MatrixType,SuperILU> Base;\n    typedef _MatrixType MatrixType;\n    typedef typename Base::Scalar Scalar;\n    typedef typename Base::RealScalar RealScalar;\n\n  public:\n    using Base::_solve_impl;\n\n    SuperILU() : Base() { init(); }\n\n    SuperILU(const MatrixType& matrix) : Base()\n    {\n      init();\n      Base::compute(matrix);\n    }\n\n    ~SuperILU()\n    {\n    }\n    \n    /** Performs a symbolic decomposition on the sparcity of \\a matrix.\n      *\n      * This function is particularly useful when solving for several problems having the same structure.\n      * \n      * \\sa factorize()\n      */\n    void analyzePattern(const MatrixType& matrix)\n    {\n      Base::analyzePattern(matrix);\n    }\n    \n    /** Performs a numeric decomposition of \\a matrix\n      *\n      * The given matrix must has the same sparcity than the matrix on which the symbolic decomposition has been performed.\n      *\n      * \\sa analyzePattern()\n      */\n    void factorize(const MatrixType& matrix);\n    \n    #ifndef EIGEN_PARSED_BY_DOXYGEN\n    /** \\internal */\n    template<typename Rhs,typename Dest>\n    void _solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest> &dest) const;\n    #endif // EIGEN_PARSED_BY_DOXYGEN\n    \n  protected:\n    \n    using Base::m_matrix;\n    using Base::m_sluOptions;\n    using Base::m_sluA;\n    using Base::m_sluB;\n    using Base::m_sluX;\n    using Base::m_p;\n    using Base::m_q;\n    using Base::m_sluEtree;\n    using Base::m_sluEqued;\n    using Base::m_sluRscale;\n    using Base::m_sluCscale;\n    using Base::m_sluL;\n    using Base::m_sluU;\n    using Base::m_sluStat;\n    using Base::m_sluFerr;\n    using Base::m_sluBerr;\n    using Base::m_l;\n    using Base::m_u;\n    \n    using Base::m_analysisIsOk;\n    using Base::m_factorizationIsOk;\n    using Base::m_extractedDataAreDirty;\n    using Base::m_isInitialized;\n    using Base::m_info;\n\n    void init()\n    {\n      Base::init();\n      \n      ilu_set_default_options(&m_sluOptions);\n      m_sluOptions.PrintStat        = NO;\n      m_sluOptions.ConditionNumber  = NO;\n      m_sluOptions.Trans            = NOTRANS;\n      m_sluOptions.ColPerm          = MMD_AT_PLUS_A;\n      \n      // no attempt to preserve column sum\n      m_sluOptions.ILU_MILU = SILU;\n      // only basic ILU(k) support -- no direct control over memory consumption\n      // better to use ILU_DropRule = DROP_BASIC | DROP_AREA\n      // and set ILU_FillFactor to max memory growth\n      m_sluOptions.ILU_DropRule = DROP_BASIC;\n      m_sluOptions.ILU_DropTol = NumTraits<Scalar>::dummy_precision()*10;\n    }\n    \n  private:\n    SuperILU(SuperILU& ) { }\n};\n\ntemplate<typename MatrixType>\nvoid SuperILU<MatrixType>::factorize(const MatrixType& a)\n{\n  eigen_assert(m_analysisIsOk && \"You must first call analyzePattern()\");\n  if(!m_analysisIsOk)\n  {\n    m_info = InvalidInput;\n    return;\n  }\n  \n  this->initFactorization(a);\n\n  int info = 0;\n  RealScalar recip_pivot_growth, rcond;\n\n  StatInit(&m_sluStat);\n  SuperLU_gsisx(&m_sluOptions, &m_sluA, m_q.data(), m_p.data(), &m_sluEtree[0],\n                &m_sluEqued, &m_sluRscale[0], &m_sluCscale[0],\n                &m_sluL, &m_sluU,\n                NULL, 0,\n                &m_sluB, &m_sluX,\n                &recip_pivot_growth, &rcond,\n                &m_sluStat, &info, Scalar());\n  StatFree(&m_sluStat);\n\n  // FIXME how to better check for errors ???\n  m_info = info == 0 ? Success : NumericalIssue;\n  m_factorizationIsOk = true;\n}\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename MatrixType>\ntemplate<typename Rhs,typename Dest>\nvoid SuperILU<MatrixType>::_solve_impl(const MatrixBase<Rhs> &b, MatrixBase<Dest>& x) const\n{\n  eigen_assert(m_factorizationIsOk && \"The decomposition is not in a valid state for solving, you must first call either compute() or analyzePattern()/factorize()\");\n\n  const int rhsCols = b.cols();\n  eigen_assert(m_matrix.rows()==b.rows());\n\n  m_sluOptions.Trans = NOTRANS;\n  m_sluOptions.Fact = FACTORED;\n  m_sluOptions.IterRefine = NOREFINE;\n\n  m_sluFerr.resize(rhsCols);\n  m_sluBerr.resize(rhsCols);\n  \n  Ref<const Matrix<typename Rhs::Scalar,Dynamic,Dynamic,ColMajor> > b_ref(b);\n  Ref<const Matrix<typename Dest::Scalar,Dynamic,Dynamic,ColMajor> > x_ref(x);\n  \n  m_sluB = SluMatrix::Map(b_ref.const_cast_derived());\n  m_sluX = SluMatrix::Map(x_ref.const_cast_derived());\n\n  typename Rhs::PlainObject b_cpy;\n  if(m_sluEqued!='N')\n  {\n    b_cpy = b;\n    m_sluB = SluMatrix::Map(b_cpy.const_cast_derived());  \n  }\n  \n  int info = 0;\n  RealScalar recip_pivot_growth, rcond;\n\n  StatInit(&m_sluStat);\n  SuperLU_gsisx(&m_sluOptions, &m_sluA,\n                m_q.data(), m_p.data(),\n                &m_sluEtree[0], &m_sluEqued,\n                &m_sluRscale[0], &m_sluCscale[0],\n                &m_sluL, &m_sluU,\n                NULL, 0,\n                &m_sluB, &m_sluX,\n                &recip_pivot_growth, &rcond,\n                &m_sluStat, &info, Scalar());\n  StatFree(&m_sluStat);\n  \n  if(x.derived().data() != x_ref.data())\n    x = x_ref;\n\n  m_info = info==0 ? Success : NumericalIssue;\n}\n#endif\n\n#endif\n\n} // end namespace Eigen\n\n#endif // EIGEN_SUPERLUSUPPORT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/UmfPackSupport/UmfPackSupport.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_UMFPACKSUPPORT_H\n#define EIGEN_UMFPACKSUPPORT_H\n\n// for compatibility with super old version of umfpack,\n// not sure this is really needed, but this is harmless.\n#ifndef SuiteSparse_long\n#ifdef UF_long\n#define SuiteSparse_long UF_long\n#else\n#error neither SuiteSparse_long nor UF_long are defined\n#endif\n#endif\n\nnamespace Eigen {\n\n/* TODO extract L, extract U, compute det, etc... */\n\n// generic double/complex<double> wrapper functions:\n\n\n // Defaults\ninline void umfpack_defaults(double control[UMFPACK_CONTROL], double, int)\n{ umfpack_di_defaults(control); }\n\ninline void umfpack_defaults(double control[UMFPACK_CONTROL], std::complex<double>, int)\n{ umfpack_zi_defaults(control); }\n\ninline void umfpack_defaults(double control[UMFPACK_CONTROL], double, SuiteSparse_long)\n{ umfpack_dl_defaults(control); }\n\ninline void umfpack_defaults(double control[UMFPACK_CONTROL], std::complex<double>, SuiteSparse_long)\n{ umfpack_zl_defaults(control); }\n\n// Report info\ninline void umfpack_report_info(double control[UMFPACK_CONTROL], double info[UMFPACK_INFO], double, int)\n{ umfpack_di_report_info(control, info);}\n\ninline void umfpack_report_info(double control[UMFPACK_CONTROL], double info[UMFPACK_INFO], std::complex<double>, int)\n{ umfpack_zi_report_info(control, info);}\n\ninline void umfpack_report_info(double control[UMFPACK_CONTROL], double info[UMFPACK_INFO], double, SuiteSparse_long)\n{ umfpack_dl_report_info(control, info);}\n\ninline void umfpack_report_info(double control[UMFPACK_CONTROL], double info[UMFPACK_INFO], std::complex<double>, SuiteSparse_long)\n{ umfpack_zl_report_info(control, info);}\n\n// Report status\ninline void umfpack_report_status(double control[UMFPACK_CONTROL], int status, double, int)\n{ umfpack_di_report_status(control, status);}\n\ninline void umfpack_report_status(double control[UMFPACK_CONTROL], int status, std::complex<double>, int)\n{ umfpack_zi_report_status(control, status);}\n\ninline void umfpack_report_status(double control[UMFPACK_CONTROL], int status, double, SuiteSparse_long)\n{ umfpack_dl_report_status(control, status);}\n\ninline void umfpack_report_status(double control[UMFPACK_CONTROL], int status, std::complex<double>, SuiteSparse_long)\n{ umfpack_zl_report_status(control, status);}\n\n// report control\ninline void umfpack_report_control(double control[UMFPACK_CONTROL], double, int)\n{ umfpack_di_report_control(control);}\n\ninline void umfpack_report_control(double control[UMFPACK_CONTROL], std::complex<double>, int)\n{ umfpack_zi_report_control(control);}\n\ninline void umfpack_report_control(double control[UMFPACK_CONTROL], double, SuiteSparse_long)\n{ umfpack_dl_report_control(control);}\n\ninline void umfpack_report_control(double control[UMFPACK_CONTROL], std::complex<double>, SuiteSparse_long)\n{ umfpack_zl_report_control(control);}\n\n// Free numeric\ninline void umfpack_free_numeric(void **Numeric, double, int)\n{ umfpack_di_free_numeric(Numeric); *Numeric = 0; }\n\ninline void umfpack_free_numeric(void **Numeric, std::complex<double>, int)\n{ umfpack_zi_free_numeric(Numeric); *Numeric = 0; }\n\ninline void umfpack_free_numeric(void **Numeric, double, SuiteSparse_long)\n{ umfpack_dl_free_numeric(Numeric); *Numeric = 0; }\n\ninline void umfpack_free_numeric(void **Numeric, std::complex<double>, SuiteSparse_long)\n{ umfpack_zl_free_numeric(Numeric); *Numeric = 0; }\n\n// Free symbolic\ninline void umfpack_free_symbolic(void **Symbolic, double, int)\n{ umfpack_di_free_symbolic(Symbolic); *Symbolic = 0; }\n\ninline void umfpack_free_symbolic(void **Symbolic, std::complex<double>, int)\n{ umfpack_zi_free_symbolic(Symbolic); *Symbolic = 0; }\n\ninline void umfpack_free_symbolic(void **Symbolic, double, SuiteSparse_long)\n{ umfpack_dl_free_symbolic(Symbolic); *Symbolic = 0; }\n\ninline void umfpack_free_symbolic(void **Symbolic, std::complex<double>, SuiteSparse_long)\n{ umfpack_zl_free_symbolic(Symbolic); *Symbolic = 0; }\n\n// Symbolic\ninline int umfpack_symbolic(int n_row,int n_col,\n                            const int Ap[], const int Ai[], const double Ax[], void **Symbolic,\n                            const double Control [UMFPACK_CONTROL], double Info [UMFPACK_INFO])\n{\n  return umfpack_di_symbolic(n_row,n_col,Ap,Ai,Ax,Symbolic,Control,Info);\n}\n\ninline int umfpack_symbolic(int n_row,int n_col,\n                            const int Ap[], const int Ai[], const std::complex<double> Ax[], void **Symbolic,\n                            const double Control [UMFPACK_CONTROL], double Info [UMFPACK_INFO])\n{\n  return umfpack_zi_symbolic(n_row,n_col,Ap,Ai,&numext::real_ref(Ax[0]),0,Symbolic,Control,Info);\n}\ninline SuiteSparse_long umfpack_symbolic( SuiteSparse_long n_row,SuiteSparse_long n_col,\n                                          const SuiteSparse_long Ap[], const SuiteSparse_long Ai[], const double Ax[], void **Symbolic,\n                                          const double Control [UMFPACK_CONTROL], double Info [UMFPACK_INFO])\n{\n  return umfpack_dl_symbolic(n_row,n_col,Ap,Ai,Ax,Symbolic,Control,Info);\n}\n\ninline SuiteSparse_long umfpack_symbolic( SuiteSparse_long n_row,SuiteSparse_long n_col,\n                                          const SuiteSparse_long Ap[], const SuiteSparse_long Ai[], const std::complex<double> Ax[], void **Symbolic,\n                                          const double Control [UMFPACK_CONTROL], double Info [UMFPACK_INFO])\n{\n  return umfpack_zl_symbolic(n_row,n_col,Ap,Ai,&numext::real_ref(Ax[0]),0,Symbolic,Control,Info);\n}\n\n// Numeric\ninline int umfpack_numeric( const int Ap[], const int Ai[], const double Ax[],\n                            void *Symbolic, void **Numeric,\n                            const double Control[UMFPACK_CONTROL],double Info [UMFPACK_INFO])\n{\n  return umfpack_di_numeric(Ap,Ai,Ax,Symbolic,Numeric,Control,Info);\n}\n\ninline int umfpack_numeric( const int Ap[], const int Ai[], const std::complex<double> Ax[],\n                            void *Symbolic, void **Numeric,\n                            const double Control[UMFPACK_CONTROL],double Info [UMFPACK_INFO])\n{\n  return umfpack_zi_numeric(Ap,Ai,&numext::real_ref(Ax[0]),0,Symbolic,Numeric,Control,Info);\n}\ninline SuiteSparse_long umfpack_numeric(const SuiteSparse_long Ap[], const SuiteSparse_long Ai[], const double Ax[],\n                                        void *Symbolic, void **Numeric,\n                                        const double Control[UMFPACK_CONTROL],double Info [UMFPACK_INFO])\n{\n  return umfpack_dl_numeric(Ap,Ai,Ax,Symbolic,Numeric,Control,Info);\n}\n\ninline SuiteSparse_long umfpack_numeric(const SuiteSparse_long Ap[], const SuiteSparse_long Ai[], const std::complex<double> Ax[],\n                                        void *Symbolic, void **Numeric,\n                                        const double Control[UMFPACK_CONTROL],double Info [UMFPACK_INFO])\n{\n  return umfpack_zl_numeric(Ap,Ai,&numext::real_ref(Ax[0]),0,Symbolic,Numeric,Control,Info);\n}\n\n// solve\ninline int umfpack_solve( int sys, const int Ap[], const int Ai[], const double Ax[],\n                          double X[], const double B[], void *Numeric,\n                          const double Control[UMFPACK_CONTROL], double Info[UMFPACK_INFO])\n{\n  return umfpack_di_solve(sys,Ap,Ai,Ax,X,B,Numeric,Control,Info);\n}\n\ninline int umfpack_solve( int sys, const int Ap[], const int Ai[], const std::complex<double> Ax[],\n                          std::complex<double> X[], const std::complex<double> B[], void *Numeric,\n                          const double Control[UMFPACK_CONTROL], double Info[UMFPACK_INFO])\n{\n  return umfpack_zi_solve(sys,Ap,Ai,&numext::real_ref(Ax[0]),0,&numext::real_ref(X[0]),0,&numext::real_ref(B[0]),0,Numeric,Control,Info);\n}\n\ninline SuiteSparse_long umfpack_solve(int sys, const SuiteSparse_long Ap[], const SuiteSparse_long Ai[], const double Ax[],\n                                      double X[], const double B[], void *Numeric,\n                                      const double Control[UMFPACK_CONTROL], double Info[UMFPACK_INFO])\n{\n  return umfpack_dl_solve(sys,Ap,Ai,Ax,X,B,Numeric,Control,Info);\n}\n\ninline SuiteSparse_long umfpack_solve(int sys, const SuiteSparse_long Ap[], const SuiteSparse_long Ai[], const std::complex<double> Ax[],\n                                      std::complex<double> X[], const std::complex<double> B[], void *Numeric,\n                                      const double Control[UMFPACK_CONTROL], double Info[UMFPACK_INFO])\n{\n  return umfpack_zl_solve(sys,Ap,Ai,&numext::real_ref(Ax[0]),0,&numext::real_ref(X[0]),0,&numext::real_ref(B[0]),0,Numeric,Control,Info);\n}\n\n// Get Lunz\ninline int umfpack_get_lunz(int *lnz, int *unz, int *n_row, int *n_col, int *nz_udiag, void *Numeric, double)\n{\n  return umfpack_di_get_lunz(lnz,unz,n_row,n_col,nz_udiag,Numeric);\n}\n\ninline int umfpack_get_lunz(int *lnz, int *unz, int *n_row, int *n_col, int *nz_udiag, void *Numeric, std::complex<double>)\n{\n  return umfpack_zi_get_lunz(lnz,unz,n_row,n_col,nz_udiag,Numeric);\n}\n\ninline SuiteSparse_long umfpack_get_lunz( SuiteSparse_long *lnz, SuiteSparse_long *unz, SuiteSparse_long *n_row, SuiteSparse_long *n_col,\n                                          SuiteSparse_long *nz_udiag, void *Numeric, double)\n{\n  return umfpack_dl_get_lunz(lnz,unz,n_row,n_col,nz_udiag,Numeric);\n}\n\ninline SuiteSparse_long umfpack_get_lunz( SuiteSparse_long *lnz, SuiteSparse_long *unz, SuiteSparse_long *n_row, SuiteSparse_long *n_col,\n                                          SuiteSparse_long *nz_udiag, void *Numeric, std::complex<double>)\n{\n  return umfpack_zl_get_lunz(lnz,unz,n_row,n_col,nz_udiag,Numeric);\n}\n\n// Get Numeric\ninline int umfpack_get_numeric(int Lp[], int Lj[], double Lx[], int Up[], int Ui[], double Ux[],\n                               int P[], int Q[], double Dx[], int *do_recip, double Rs[], void *Numeric)\n{\n  return umfpack_di_get_numeric(Lp,Lj,Lx,Up,Ui,Ux,P,Q,Dx,do_recip,Rs,Numeric);\n}\n\ninline int umfpack_get_numeric(int Lp[], int Lj[], std::complex<double> Lx[], int Up[], int Ui[], std::complex<double> Ux[],\n                               int P[], int Q[], std::complex<double> Dx[], int *do_recip, double Rs[], void *Numeric)\n{\n  double& lx0_real = numext::real_ref(Lx[0]);\n  double& ux0_real = numext::real_ref(Ux[0]);\n  double& dx0_real = numext::real_ref(Dx[0]);\n  return umfpack_zi_get_numeric(Lp,Lj,Lx?&lx0_real:0,0,Up,Ui,Ux?&ux0_real:0,0,P,Q,\n                                Dx?&dx0_real:0,0,do_recip,Rs,Numeric);\n}\ninline SuiteSparse_long umfpack_get_numeric(SuiteSparse_long Lp[], SuiteSparse_long Lj[], double Lx[], SuiteSparse_long Up[], SuiteSparse_long Ui[], double Ux[],\n                                            SuiteSparse_long P[], SuiteSparse_long Q[], double Dx[], SuiteSparse_long *do_recip, double Rs[], void *Numeric)\n{\n  return umfpack_dl_get_numeric(Lp,Lj,Lx,Up,Ui,Ux,P,Q,Dx,do_recip,Rs,Numeric);\n}\n\ninline SuiteSparse_long umfpack_get_numeric(SuiteSparse_long Lp[], SuiteSparse_long Lj[], std::complex<double> Lx[], SuiteSparse_long Up[], SuiteSparse_long Ui[], std::complex<double> Ux[],\n                                            SuiteSparse_long P[], SuiteSparse_long Q[], std::complex<double> Dx[], SuiteSparse_long *do_recip, double Rs[], void *Numeric)\n{\n  double& lx0_real = numext::real_ref(Lx[0]);\n  double& ux0_real = numext::real_ref(Ux[0]);\n  double& dx0_real = numext::real_ref(Dx[0]);\n  return umfpack_zl_get_numeric(Lp,Lj,Lx?&lx0_real:0,0,Up,Ui,Ux?&ux0_real:0,0,P,Q,\n                                Dx?&dx0_real:0,0,do_recip,Rs,Numeric);\n}\n\n// Get Determinant\ninline int umfpack_get_determinant(double *Mx, double *Ex, void *NumericHandle, double User_Info [UMFPACK_INFO], int)\n{\n  return umfpack_di_get_determinant(Mx,Ex,NumericHandle,User_Info);\n}\n\ninline int umfpack_get_determinant(std::complex<double> *Mx, double *Ex, void *NumericHandle, double User_Info [UMFPACK_INFO], int)\n{\n  double& mx_real = numext::real_ref(*Mx);\n  return umfpack_zi_get_determinant(&mx_real,0,Ex,NumericHandle,User_Info);\n}\n\ninline SuiteSparse_long umfpack_get_determinant(double *Mx, double *Ex, void *NumericHandle, double User_Info [UMFPACK_INFO], SuiteSparse_long)\n{\n  return umfpack_dl_get_determinant(Mx,Ex,NumericHandle,User_Info);\n}\n\ninline SuiteSparse_long umfpack_get_determinant(std::complex<double> *Mx, double *Ex, void *NumericHandle, double User_Info [UMFPACK_INFO], SuiteSparse_long)\n{\n  double& mx_real = numext::real_ref(*Mx);\n  return umfpack_zl_get_determinant(&mx_real,0,Ex,NumericHandle,User_Info);\n}\n\n\n/** \\ingroup UmfPackSupport_Module\n  * \\brief A sparse LU factorization and solver based on UmfPack\n  *\n  * This class allows to solve for A.X = B sparse linear problems via a LU factorization\n  * using the UmfPack library. The sparse matrix A must be squared and full rank.\n  * The vectors or matrices X and B can be either dense or sparse.\n  *\n  * \\warning The input matrix A should be in a \\b compressed and \\b column-major form.\n  * Otherwise an expensive copy will be made. You can call the inexpensive makeCompressed() to get a compressed matrix.\n  * \\tparam _MatrixType the type of the sparse matrix A, it must be a SparseMatrix<>\n  *\n  * \\implsparsesolverconcept\n  *\n  * \\sa \\ref TutorialSparseSolverConcept, class SparseLU\n  */\ntemplate<typename _MatrixType>\nclass UmfPackLU : public SparseSolverBase<UmfPackLU<_MatrixType> >\n{\n  protected:\n    typedef SparseSolverBase<UmfPackLU<_MatrixType> > Base;\n    using Base::m_isInitialized;\n  public:\n    using Base::_solve_impl;\n    typedef _MatrixType MatrixType;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef Matrix<Scalar,Dynamic,1> Vector;\n    typedef Matrix<int, 1, MatrixType::ColsAtCompileTime> IntRowVectorType;\n    typedef Matrix<int, MatrixType::RowsAtCompileTime, 1> IntColVectorType;\n    typedef SparseMatrix<Scalar> LUMatrixType;\n    typedef SparseMatrix<Scalar,ColMajor,StorageIndex> UmfpackMatrixType;\n    typedef Ref<const UmfpackMatrixType, StandardCompressedFormat> UmfpackMatrixRef;\n    enum {\n      ColsAtCompileTime = MatrixType::ColsAtCompileTime,\n      MaxColsAtCompileTime = MatrixType::MaxColsAtCompileTime\n    };\n\n  public:\n\n    typedef Array<double, UMFPACK_CONTROL, 1> UmfpackControl;\n    typedef Array<double, UMFPACK_INFO, 1> UmfpackInfo;\n\n    UmfPackLU()\n      : m_dummy(0,0), mp_matrix(m_dummy)\n    {\n      init();\n    }\n\n    template<typename InputMatrixType>\n    explicit UmfPackLU(const InputMatrixType& matrix)\n      : mp_matrix(matrix)\n    {\n      init();\n      compute(matrix);\n    }\n\n    ~UmfPackLU()\n    {\n      if(m_symbolic) umfpack_free_symbolic(&m_symbolic,Scalar(), StorageIndex());\n      if(m_numeric)  umfpack_free_numeric(&m_numeric,Scalar(), StorageIndex());\n    }\n\n    inline Index rows() const { return mp_matrix.rows(); }\n    inline Index cols() const { return mp_matrix.cols(); }\n\n    /** \\brief Reports whether previous computation was successful.\n      *\n      * \\returns \\c Success if computation was successful,\n      *          \\c NumericalIssue if the matrix.appears to be negative.\n      */\n    ComputationInfo info() const\n    {\n      eigen_assert(m_isInitialized && \"Decomposition is not initialized.\");\n      return m_info;\n    }\n\n    inline const LUMatrixType& matrixL() const\n    {\n      if (m_extractedDataAreDirty) extractData();\n      return m_l;\n    }\n\n    inline const LUMatrixType& matrixU() const\n    {\n      if (m_extractedDataAreDirty) extractData();\n      return m_u;\n    }\n\n    inline const IntColVectorType& permutationP() const\n    {\n      if (m_extractedDataAreDirty) extractData();\n      return m_p;\n    }\n\n    inline const IntRowVectorType& permutationQ() const\n    {\n      if (m_extractedDataAreDirty) extractData();\n      return m_q;\n    }\n\n    /** Computes the sparse Cholesky decomposition of \\a matrix\n     *  Note that the matrix should be column-major, and in compressed format for best performance.\n     *  \\sa SparseMatrix::makeCompressed().\n     */\n    template<typename InputMatrixType>\n    void compute(const InputMatrixType& matrix)\n    {\n      if(m_symbolic) umfpack_free_symbolic(&m_symbolic,Scalar(),StorageIndex());\n      if(m_numeric)  umfpack_free_numeric(&m_numeric,Scalar(),StorageIndex());\n      grab(matrix.derived());\n      analyzePattern_impl();\n      factorize_impl();\n    }\n\n    /** Performs a symbolic decomposition on the sparcity of \\a matrix.\n      *\n      * This function is particularly useful when solving for several problems having the same structure.\n      *\n      * \\sa factorize(), compute()\n      */\n    template<typename InputMatrixType>\n    void analyzePattern(const InputMatrixType& matrix)\n    {\n      if(m_symbolic) umfpack_free_symbolic(&m_symbolic,Scalar(),StorageIndex());\n      if(m_numeric)  umfpack_free_numeric(&m_numeric,Scalar(),StorageIndex());\n\n      grab(matrix.derived());\n\n      analyzePattern_impl();\n    }\n\n    /** Provides the return status code returned by UmfPack during the numeric\n      * factorization.\n      *\n      * \\sa factorize(), compute()\n      */\n    inline int umfpackFactorizeReturncode() const\n    {\n      eigen_assert(m_numeric && \"UmfPackLU: you must first call factorize()\");\n      return m_fact_errorCode;\n    }\n\n    /** Provides access to the control settings array used by UmfPack.\n      *\n      * If this array contains NaN's, the default values are used.\n      *\n      * See UMFPACK documentation for details.\n      */\n    inline const UmfpackControl& umfpackControl() const\n    {\n      return m_control;\n    }\n\n    /** Provides access to the control settings array used by UmfPack.\n      *\n      * If this array contains NaN's, the default values are used.\n      *\n      * See UMFPACK documentation for details.\n      */\n    inline UmfpackControl& umfpackControl()\n    {\n      return m_control;\n    }\n\n    /** Performs a numeric decomposition of \\a matrix\n      *\n      * The given matrix must has the same sparcity than the matrix on which the pattern anylysis has been performed.\n      *\n      * \\sa analyzePattern(), compute()\n      */\n    template<typename InputMatrixType>\n    void factorize(const InputMatrixType& matrix)\n    {\n      eigen_assert(m_analysisIsOk && \"UmfPackLU: you must first call analyzePattern()\");\n      if(m_numeric)\n        umfpack_free_numeric(&m_numeric,Scalar(),StorageIndex());\n\n      grab(matrix.derived());\n\n      factorize_impl();\n    }\n\n    /** Prints the current UmfPack control settings.\n      *\n      * \\sa umfpackControl()\n      */\n    void printUmfpackControl()\n    {\n      umfpack_report_control(m_control.data(), Scalar(),StorageIndex());\n    }\n\n    /** Prints statistics collected by UmfPack.\n      *\n      * \\sa analyzePattern(), compute()\n      */\n    void printUmfpackInfo()\n    {\n      eigen_assert(m_analysisIsOk && \"UmfPackLU: you must first call analyzePattern()\");\n      umfpack_report_info(m_control.data(), m_umfpackInfo.data(), Scalar(),StorageIndex());\n    }\n\n    /** Prints the status of the previous factorization operation performed by UmfPack (symbolic or numerical factorization).\n      *\n      * \\sa analyzePattern(), compute()\n      */\n    void printUmfpackStatus() {\n      eigen_assert(m_analysisIsOk && \"UmfPackLU: you must first call analyzePattern()\");\n      umfpack_report_status(m_control.data(), m_fact_errorCode, Scalar(),StorageIndex());\n    }\n\n    /** \\internal */\n    template<typename BDerived,typename XDerived>\n    bool _solve_impl(const MatrixBase<BDerived> &b, MatrixBase<XDerived> &x) const;\n\n    Scalar determinant() const;\n\n    void extractData() const;\n\n  protected:\n\n    void init()\n    {\n      m_info                  = InvalidInput;\n      m_isInitialized         = false;\n      m_numeric               = 0;\n      m_symbolic              = 0;\n      m_extractedDataAreDirty = true;\n\n      umfpack_defaults(m_control.data(), Scalar(),StorageIndex());\n    }\n\n    void analyzePattern_impl()\n    {\n      m_fact_errorCode = umfpack_symbolic(internal::convert_index<StorageIndex>(mp_matrix.rows()),\n                                          internal::convert_index<StorageIndex>(mp_matrix.cols()),\n                                          mp_matrix.outerIndexPtr(), mp_matrix.innerIndexPtr(), mp_matrix.valuePtr(),\n                                          &m_symbolic, m_control.data(), m_umfpackInfo.data());\n\n      m_isInitialized = true;\n      m_info = m_fact_errorCode ? InvalidInput : Success;\n      m_analysisIsOk = true;\n      m_factorizationIsOk = false;\n      m_extractedDataAreDirty = true;\n    }\n\n    void factorize_impl()\n    {\n\n      m_fact_errorCode = umfpack_numeric(mp_matrix.outerIndexPtr(), mp_matrix.innerIndexPtr(), mp_matrix.valuePtr(),\n                                         m_symbolic, &m_numeric, m_control.data(), m_umfpackInfo.data());\n\n      m_info = m_fact_errorCode == UMFPACK_OK ? Success : NumericalIssue;\n      m_factorizationIsOk = true;\n      m_extractedDataAreDirty = true;\n    }\n\n    template<typename MatrixDerived>\n    void grab(const EigenBase<MatrixDerived> &A)\n    {\n      mp_matrix.~UmfpackMatrixRef();\n      ::new (&mp_matrix) UmfpackMatrixRef(A.derived());\n    }\n\n    void grab(const UmfpackMatrixRef &A)\n    {\n      if(&(A.derived()) != &mp_matrix)\n      {\n        mp_matrix.~UmfpackMatrixRef();\n        ::new (&mp_matrix) UmfpackMatrixRef(A);\n      }\n    }\n\n    // cached data to reduce reallocation, etc.\n    mutable LUMatrixType m_l;\n    StorageIndex m_fact_errorCode;\n    UmfpackControl m_control;\n    mutable UmfpackInfo m_umfpackInfo;\n\n    mutable LUMatrixType m_u;\n    mutable IntColVectorType m_p;\n    mutable IntRowVectorType m_q;\n\n    UmfpackMatrixType m_dummy;\n    UmfpackMatrixRef mp_matrix;\n\n    void* m_numeric;\n    void* m_symbolic;\n\n    mutable ComputationInfo m_info;\n    int m_factorizationIsOk;\n    int m_analysisIsOk;\n    mutable bool m_extractedDataAreDirty;\n\n  private:\n    UmfPackLU(const UmfPackLU& ) { }\n};\n\n\ntemplate<typename MatrixType>\nvoid UmfPackLU<MatrixType>::extractData() const\n{\n  if (m_extractedDataAreDirty)\n  {\n    // get size of the data\n    StorageIndex lnz, unz, rows, cols, nz_udiag;\n    umfpack_get_lunz(&lnz, &unz, &rows, &cols, &nz_udiag, m_numeric, Scalar());\n\n    // allocate data\n    m_l.resize(rows,(std::min)(rows,cols));\n    m_l.resizeNonZeros(lnz);\n\n    m_u.resize((std::min)(rows,cols),cols);\n    m_u.resizeNonZeros(unz);\n\n    m_p.resize(rows);\n    m_q.resize(cols);\n\n    // extract\n    umfpack_get_numeric(m_l.outerIndexPtr(), m_l.innerIndexPtr(), m_l.valuePtr(),\n                        m_u.outerIndexPtr(), m_u.innerIndexPtr(), m_u.valuePtr(),\n                        m_p.data(), m_q.data(), 0, 0, 0, m_numeric);\n\n    m_extractedDataAreDirty = false;\n  }\n}\n\ntemplate<typename MatrixType>\ntypename UmfPackLU<MatrixType>::Scalar UmfPackLU<MatrixType>::determinant() const\n{\n  Scalar det;\n  umfpack_get_determinant(&det, 0, m_numeric, 0, StorageIndex());\n  return det;\n}\n\ntemplate<typename MatrixType>\ntemplate<typename BDerived,typename XDerived>\nbool UmfPackLU<MatrixType>::_solve_impl(const MatrixBase<BDerived> &b, MatrixBase<XDerived> &x) const\n{\n  Index rhsCols = b.cols();\n  eigen_assert((BDerived::Flags&RowMajorBit)==0 && \"UmfPackLU backend does not support non col-major rhs yet\");\n  eigen_assert((XDerived::Flags&RowMajorBit)==0 && \"UmfPackLU backend does not support non col-major result yet\");\n  eigen_assert(b.derived().data() != x.derived().data() && \" Umfpack does not support inplace solve\");\n\n  Scalar* x_ptr = 0;\n  Matrix<Scalar,Dynamic,1> x_tmp;\n  if(x.innerStride()!=1)\n  {\n    x_tmp.resize(x.rows());\n    x_ptr = x_tmp.data();\n  }\n  for (int j=0; j<rhsCols; ++j)\n  {\n    if(x.innerStride()==1)\n      x_ptr = &x.col(j).coeffRef(0);\n    StorageIndex errorCode = umfpack_solve(UMFPACK_A,\n                                mp_matrix.outerIndexPtr(), mp_matrix.innerIndexPtr(), mp_matrix.valuePtr(),\n                                x_ptr, &b.const_cast_derived().col(j).coeffRef(0),\n                                m_numeric, m_control.data(), m_umfpackInfo.data());\n    if(x.innerStride()!=1)\n      x.col(j) = x_tmp;\n    if (errorCode!=0)\n      return false;\n  }\n\n  return true;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_UMFPACKSUPPORT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/misc/Image.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MISC_IMAGE_H\n#define EIGEN_MISC_IMAGE_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\class image_retval_base\n  *\n  */\ntemplate<typename DecompositionType>\nstruct traits<image_retval_base<DecompositionType> >\n{\n  typedef typename DecompositionType::MatrixType MatrixType;\n  typedef Matrix<\n    typename MatrixType::Scalar,\n    MatrixType::RowsAtCompileTime, // the image is a subspace of the destination space, whose\n                                   // dimension is the number of rows of the original matrix\n    Dynamic,                       // we don't know at compile time the dimension of the image (the rank)\n    MatrixType::Options,\n    MatrixType::MaxRowsAtCompileTime, // the image matrix will consist of columns from the original matrix,\n    MatrixType::MaxColsAtCompileTime  // so it has the same number of rows and at most as many columns.\n  > ReturnType;\n};\n\ntemplate<typename _DecompositionType> struct image_retval_base\n : public ReturnByValue<image_retval_base<_DecompositionType> >\n{\n  typedef _DecompositionType DecompositionType;\n  typedef typename DecompositionType::MatrixType MatrixType;\n  typedef ReturnByValue<image_retval_base> Base;\n\n  image_retval_base(const DecompositionType& dec, const MatrixType& originalMatrix)\n    : m_dec(dec), m_rank(dec.rank()),\n      m_cols(m_rank == 0 ? 1 : m_rank),\n      m_originalMatrix(originalMatrix)\n  {}\n\n  inline Index rows() const { return m_dec.rows(); }\n  inline Index cols() const { return m_cols; }\n  inline Index rank() const { return m_rank; }\n  inline const DecompositionType& dec() const { return m_dec; }\n  inline const MatrixType& originalMatrix() const { return m_originalMatrix; }\n\n  template<typename Dest> inline void evalTo(Dest& dst) const\n  {\n    static_cast<const image_retval<DecompositionType>*>(this)->evalTo(dst);\n  }\n\n  protected:\n    const DecompositionType& m_dec;\n    Index m_rank, m_cols;\n    const MatrixType& m_originalMatrix;\n};\n\n} // end namespace internal\n\n#define EIGEN_MAKE_IMAGE_HELPERS(DecompositionType) \\\n  typedef typename DecompositionType::MatrixType MatrixType; \\\n  typedef typename MatrixType::Scalar Scalar; \\\n  typedef typename MatrixType::RealScalar RealScalar; \\\n  typedef Eigen::internal::image_retval_base<DecompositionType> Base; \\\n  using Base::dec; \\\n  using Base::originalMatrix; \\\n  using Base::rank; \\\n  using Base::rows; \\\n  using Base::cols; \\\n  image_retval(const DecompositionType& dec, const MatrixType& originalMatrix) \\\n    : Base(dec, originalMatrix) {}\n\n} // end namespace Eigen\n\n#endif // EIGEN_MISC_IMAGE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/misc/Kernel.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MISC_KERNEL_H\n#define EIGEN_MISC_KERNEL_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\class kernel_retval_base\n  *\n  */\ntemplate<typename DecompositionType>\nstruct traits<kernel_retval_base<DecompositionType> >\n{\n  typedef typename DecompositionType::MatrixType MatrixType;\n  typedef Matrix<\n    typename MatrixType::Scalar,\n    MatrixType::ColsAtCompileTime, // the number of rows in the \"kernel matrix\"\n                                   // is the number of cols of the original matrix\n                                   // so that the product \"matrix * kernel = zero\" makes sense\n    Dynamic,                       // we don't know at compile-time the dimension of the kernel\n    MatrixType::Options,\n    MatrixType::MaxColsAtCompileTime, // see explanation for 2nd template parameter\n    MatrixType::MaxColsAtCompileTime // the kernel is a subspace of the domain space,\n                                     // whose dimension is the number of columns of the original matrix\n  > ReturnType;\n};\n\ntemplate<typename _DecompositionType> struct kernel_retval_base\n : public ReturnByValue<kernel_retval_base<_DecompositionType> >\n{\n  typedef _DecompositionType DecompositionType;\n  typedef ReturnByValue<kernel_retval_base> Base;\n\n  explicit kernel_retval_base(const DecompositionType& dec)\n    : m_dec(dec),\n      m_rank(dec.rank()),\n      m_cols(m_rank==dec.cols() ? 1 : dec.cols() - m_rank)\n  {}\n\n  inline Index rows() const { return m_dec.cols(); }\n  inline Index cols() const { return m_cols; }\n  inline Index rank() const { return m_rank; }\n  inline const DecompositionType& dec() const { return m_dec; }\n\n  template<typename Dest> inline void evalTo(Dest& dst) const\n  {\n    static_cast<const kernel_retval<DecompositionType>*>(this)->evalTo(dst);\n  }\n\n  protected:\n    const DecompositionType& m_dec;\n    Index m_rank, m_cols;\n};\n\n} // end namespace internal\n\n#define EIGEN_MAKE_KERNEL_HELPERS(DecompositionType) \\\n  typedef typename DecompositionType::MatrixType MatrixType; \\\n  typedef typename MatrixType::Scalar Scalar; \\\n  typedef typename MatrixType::RealScalar RealScalar; \\\n  typedef Eigen::internal::kernel_retval_base<DecompositionType> Base; \\\n  using Base::dec; \\\n  using Base::rank; \\\n  using Base::rows; \\\n  using Base::cols; \\\n  kernel_retval(const DecompositionType& dec) : Base(dec) {}\n\n} // end namespace Eigen\n\n#endif // EIGEN_MISC_KERNEL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/misc/RealSvd2x2.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2013-2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_REALSVD2X2_H\n#define EIGEN_REALSVD2X2_H\n\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate<typename MatrixType, typename RealScalar, typename Index>\nvoid real_2x2_jacobi_svd(const MatrixType& matrix, Index p, Index q,\n                         JacobiRotation<RealScalar> *j_left,\n                         JacobiRotation<RealScalar> *j_right)\n{\n  using std::sqrt;\n  using std::abs;\n  Matrix<RealScalar,2,2> m;\n  m << numext::real(matrix.coeff(p,p)), numext::real(matrix.coeff(p,q)),\n       numext::real(matrix.coeff(q,p)), numext::real(matrix.coeff(q,q));\n  JacobiRotation<RealScalar> rot1;\n  RealScalar t = m.coeff(0,0) + m.coeff(1,1);\n  RealScalar d = m.coeff(1,0) - m.coeff(0,1);\n\n  if(abs(d) < (std::numeric_limits<RealScalar>::min)())\n  {\n    rot1.s() = RealScalar(0);\n    rot1.c() = RealScalar(1);\n  }\n  else\n  {\n    // If d!=0, then t/d cannot overflow because the magnitude of the\n    // entries forming d are not too small compared to the ones forming t.\n    RealScalar u = t / d;\n    RealScalar tmp = sqrt(RealScalar(1) + numext::abs2(u));\n    rot1.s() = RealScalar(1) / tmp;\n    rot1.c() = u / tmp;\n  }\n  m.applyOnTheLeft(0,1,rot1);\n  j_right->makeJacobi(m,0,1);\n  *j_left = rot1 * j_right->transpose();\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_REALSVD2X2_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/misc/blas.h",
    "content": "#ifndef BLAS_H\n#define BLAS_H\n\n#ifdef __cplusplus\nextern \"C\"\n{\n#endif\n\n#define BLASFUNC(FUNC) FUNC##_\n\n#ifdef __WIN64__\ntypedef long long BLASLONG;\ntypedef unsigned long long BLASULONG;\n#else\ntypedef long BLASLONG;\ntypedef unsigned long BLASULONG;\n#endif\n\nint    BLASFUNC(xerbla)(const char *, int *info, int);\n\nfloat  BLASFUNC(sdot)  (int *, float  *, int *, float  *, int *);\nfloat  BLASFUNC(sdsdot)(int *, float  *,        float  *, int *, float  *, int *);\n\ndouble BLASFUNC(dsdot) (int *, float  *, int *, float  *, int *);\ndouble BLASFUNC(ddot)  (int *, double *, int *, double *, int *);\ndouble BLASFUNC(qdot)  (int *, double *, int *, double *, int *);\n\nint  BLASFUNC(cdotuw)  (int *, float  *, int *, float  *, int *, float*);\nint  BLASFUNC(cdotcw)  (int *, float  *, int *, float  *, int *, float*);\nint  BLASFUNC(zdotuw)  (int *, double  *, int *, double  *, int *, double*);\nint  BLASFUNC(zdotcw)  (int *, double  *, int *, double  *, int *, double*);\n\nint    BLASFUNC(saxpy) (const int *, const float  *, const float  *, const int *, float  *, const int *);\nint    BLASFUNC(daxpy) (const int *, const double *, const double *, const int *, double *, const int *);\nint    BLASFUNC(qaxpy) (const int *, const double *, const double *, const int *, double *, const int *);\nint    BLASFUNC(caxpy) (const int *, const float  *, const float  *, const int *, float  *, const int *);\nint    BLASFUNC(zaxpy) (const int *, const double *, const double *, const int *, double *, const int *);\nint    BLASFUNC(xaxpy) (const int *, const double *, const double *, const int *, double *, const int *);\nint    BLASFUNC(caxpyc)(const int *, const float  *, const float  *, const int *, float  *, const int *);\nint    BLASFUNC(zaxpyc)(const int *, const double *, const double *, const int *, double *, const int *);\nint    BLASFUNC(xaxpyc)(const int *, const double *, const double *, const int *, double *, const int *);\n\nint    BLASFUNC(scopy) (int *, float  *, int *, float  *, int *);\nint    BLASFUNC(dcopy) (int *, double *, int *, double *, int *);\nint    BLASFUNC(qcopy) (int *, double *, int *, double *, int *);\nint    BLASFUNC(ccopy) (int *, float  *, int *, float  *, int *);\nint    BLASFUNC(zcopy) (int *, double *, int *, double *, int *);\nint    BLASFUNC(xcopy) (int *, double *, int *, double *, int *);\n\nint    BLASFUNC(sswap) (int *, float  *, int *, float  *, int *);\nint    BLASFUNC(dswap) (int *, double *, int *, double *, int *);\nint    BLASFUNC(qswap) (int *, double *, int *, double *, int *);\nint    BLASFUNC(cswap) (int *, float  *, int *, float  *, int *);\nint    BLASFUNC(zswap) (int *, double *, int *, double *, int *);\nint    BLASFUNC(xswap) (int *, double *, int *, double *, int *);\n\nfloat  BLASFUNC(sasum) (int *, float  *, int *);\nfloat  BLASFUNC(scasum)(int *, float  *, int *);\ndouble BLASFUNC(dasum) (int *, double *, int *);\ndouble BLASFUNC(qasum) (int *, double *, int *);\ndouble BLASFUNC(dzasum)(int *, double *, int *);\ndouble BLASFUNC(qxasum)(int *, double *, int *);\n\nint    BLASFUNC(isamax)(int *, float  *, int *);\nint    BLASFUNC(idamax)(int *, double *, int *);\nint    BLASFUNC(iqamax)(int *, double *, int *);\nint    BLASFUNC(icamax)(int *, float  *, int *);\nint    BLASFUNC(izamax)(int *, double *, int *);\nint    BLASFUNC(ixamax)(int *, double *, int *);\n\nint    BLASFUNC(ismax) (int *, float  *, int *);\nint    BLASFUNC(idmax) (int *, double *, int *);\nint    BLASFUNC(iqmax) (int *, double *, int *);\nint    BLASFUNC(icmax) (int *, float  *, int *);\nint    BLASFUNC(izmax) (int *, double *, int *);\nint    BLASFUNC(ixmax) (int *, double *, int *);\n\nint    BLASFUNC(isamin)(int *, float  *, int *);\nint    BLASFUNC(idamin)(int *, double *, int *);\nint    BLASFUNC(iqamin)(int *, double *, int *);\nint    BLASFUNC(icamin)(int *, float  *, int *);\nint    BLASFUNC(izamin)(int *, double *, int *);\nint    BLASFUNC(ixamin)(int *, double *, int *);\n\nint    BLASFUNC(ismin)(int *, float  *, int *);\nint    BLASFUNC(idmin)(int *, double *, int *);\nint    BLASFUNC(iqmin)(int *, double *, int *);\nint    BLASFUNC(icmin)(int *, float  *, int *);\nint    BLASFUNC(izmin)(int *, double *, int *);\nint    BLASFUNC(ixmin)(int *, double *, int *);\n\nfloat  BLASFUNC(samax) (int *, float  *, int *);\ndouble BLASFUNC(damax) (int *, double *, int *);\ndouble BLASFUNC(qamax) (int *, double *, int *);\nfloat  BLASFUNC(scamax)(int *, float  *, int *);\ndouble BLASFUNC(dzamax)(int *, double *, int *);\ndouble BLASFUNC(qxamax)(int *, double *, int *);\n\nfloat  BLASFUNC(samin) (int *, float  *, int *);\ndouble BLASFUNC(damin) (int *, double *, int *);\ndouble BLASFUNC(qamin) (int *, double *, int *);\nfloat  BLASFUNC(scamin)(int *, float  *, int *);\ndouble BLASFUNC(dzamin)(int *, double *, int *);\ndouble BLASFUNC(qxamin)(int *, double *, int *);\n\nfloat  BLASFUNC(smax)  (int *, float  *, int *);\ndouble BLASFUNC(dmax)  (int *, double *, int *);\ndouble BLASFUNC(qmax)  (int *, double *, int *);\nfloat  BLASFUNC(scmax) (int *, float  *, int *);\ndouble BLASFUNC(dzmax) (int *, double *, int *);\ndouble BLASFUNC(qxmax) (int *, double *, int *);\n\nfloat  BLASFUNC(smin)  (int *, float  *, int *);\ndouble BLASFUNC(dmin)  (int *, double *, int *);\ndouble BLASFUNC(qmin)  (int *, double *, int *);\nfloat  BLASFUNC(scmin) (int *, float  *, int *);\ndouble BLASFUNC(dzmin) (int *, double *, int *);\ndouble BLASFUNC(qxmin) (int *, double *, int *);\n\nint    BLASFUNC(sscal) (int *,  float  *, float  *, int *);\nint    BLASFUNC(dscal) (int *,  double *, double *, int *);\nint    BLASFUNC(qscal) (int *,  double *, double *, int *);\nint    BLASFUNC(cscal) (int *,  float  *, float  *, int *);\nint    BLASFUNC(zscal) (int *,  double *, double *, int *);\nint    BLASFUNC(xscal) (int *,  double *, double *, int *);\nint    BLASFUNC(csscal)(int *,  float  *, float  *, int *);\nint    BLASFUNC(zdscal)(int *,  double *, double *, int *);\nint    BLASFUNC(xqscal)(int *,  double *, double *, int *);\n\nfloat  BLASFUNC(snrm2) (int *, float  *, int *);\nfloat  BLASFUNC(scnrm2)(int *, float  *, int *);\n\ndouble BLASFUNC(dnrm2) (int *, double *, int *);\ndouble BLASFUNC(qnrm2) (int *, double *, int *);\ndouble BLASFUNC(dznrm2)(int *, double *, int *);\ndouble BLASFUNC(qxnrm2)(int *, double *, int *);\n\nint    BLASFUNC(srot)  (int *, float  *, int *, float  *, int *, float  *, float  *);\nint    BLASFUNC(drot)  (int *, double *, int *, double *, int *, double *, double *);\nint    BLASFUNC(qrot)  (int *, double *, int *, double *, int *, double *, double *);\nint    BLASFUNC(csrot) (int *, float  *, int *, float  *, int *, float  *, float  *);\nint    BLASFUNC(zdrot) (int *, double *, int *, double *, int *, double *, double *);\nint    BLASFUNC(xqrot) (int *, double *, int *, double *, int *, double *, double *);\n\nint    BLASFUNC(srotg) (float  *, float  *, float  *, float  *);\nint    BLASFUNC(drotg) (double *, double *, double *, double *);\nint    BLASFUNC(qrotg) (double *, double *, double *, double *);\nint    BLASFUNC(crotg) (float  *, float  *, float  *, float  *);\nint    BLASFUNC(zrotg) (double *, double *, double *, double *);\nint    BLASFUNC(xrotg) (double *, double *, double *, double *);\n\nint    BLASFUNC(srotmg)(float  *, float  *, float  *, float  *, float  *);\nint    BLASFUNC(drotmg)(double *, double *, double *, double *, double *);\n\nint    BLASFUNC(srotm) (int *, float  *, int *, float  *, int *, float  *);\nint    BLASFUNC(drotm) (int *, double *, int *, double *, int *, double *);\nint    BLASFUNC(qrotm) (int *, double *, int *, double *, int *, double *);\n\n/* Level 2 routines */\n\nint BLASFUNC(sger)(int *,    int *, float *,  float *, int *,\n\t\t   float *,  int *, float *,  int *);\nint BLASFUNC(dger)(int *,    int *, double *, double *, int *,\n\t\t   double *, int *, double *, int *);\nint BLASFUNC(qger)(int *,    int *, double *, double *, int *,\n\t\t   double *, int *, double *, int *);\nint BLASFUNC(cgeru)(int *,    int *, float *,  float *, int *,\n\t\t    float *,  int *, float *,  int *);\nint BLASFUNC(cgerc)(int *,    int *, float *,  float *, int *,\n\t\t    float *,  int *, float *,  int *);\nint BLASFUNC(zgeru)(int *,    int *, double *, double *, int *,\n\t\t    double *, int *, double *, int *);\nint BLASFUNC(zgerc)(int *,    int *, double *, double *, int *,\n\t\t    double *, int *, double *, int *);\nint BLASFUNC(xgeru)(int *,    int *, double *, double *, int *,\n\t\t    double *, int *, double *, int *);\nint BLASFUNC(xgerc)(int *,    int *, double *, double *, int *,\n\t\t    double *, int *, double *, int *);\n\nint BLASFUNC(sgemv)(const char *, const int *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(dgemv)(const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(qgemv)(const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(cgemv)(const char *, const int *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zgemv)(const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(xgemv)(const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\n\nint BLASFUNC(strsv) (const char *, const char *, const char *, const int *, const float  *, const int *, float  *, const int *);\nint BLASFUNC(dtrsv) (const char *, const char *, const char *, const int *, const double *, const int *, double *, const int *);\nint BLASFUNC(qtrsv) (const char *, const char *, const char *, const int *, const double *, const int *, double *, const int *);\nint BLASFUNC(ctrsv) (const char *, const char *, const char *, const int *, const float  *, const int *, float  *, const int *);\nint BLASFUNC(ztrsv) (const char *, const char *, const char *, const int *, const double *, const int *, double *, const int *);\nint BLASFUNC(xtrsv) (const char *, const char *, const char *, const int *, const double *, const int *, double *, const int *);\n\nint BLASFUNC(stpsv) (char *, char *, char *, int *, float  *, float  *, int *);\nint BLASFUNC(dtpsv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(qtpsv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(ctpsv) (char *, char *, char *, int *, float  *, float  *, int *);\nint BLASFUNC(ztpsv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(xtpsv) (char *, char *, char *, int *, double *, double *, int *);\n\nint BLASFUNC(strmv) (const char *, const char *, const char *, const int *, const float  *, const int *, float  *, const int *);\nint BLASFUNC(dtrmv) (const char *, const char *, const char *, const int *, const double *, const int *, double *, const int *);\nint BLASFUNC(qtrmv) (const char *, const char *, const char *, const int *, const double *, const int *, double *, const int *);\nint BLASFUNC(ctrmv) (const char *, const char *, const char *, const int *, const float  *, const int *, float  *, const int *);\nint BLASFUNC(ztrmv) (const char *, const char *, const char *, const int *, const double *, const int *, double *, const int *);\nint BLASFUNC(xtrmv) (const char *, const char *, const char *, const int *, const double *, const int *, double *, const int *);\n\nint BLASFUNC(stpmv) (char *, char *, char *, int *, float  *, float  *, int *);\nint BLASFUNC(dtpmv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(qtpmv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(ctpmv) (char *, char *, char *, int *, float  *, float  *, int *);\nint BLASFUNC(ztpmv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(xtpmv) (char *, char *, char *, int *, double *, double *, int *);\n\nint BLASFUNC(stbmv) (char *, char *, char *, int *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(dtbmv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(qtbmv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(ctbmv) (char *, char *, char *, int *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(ztbmv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(xtbmv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\n\nint BLASFUNC(stbsv) (char *, char *, char *, int *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(dtbsv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(qtbsv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(ctbsv) (char *, char *, char *, int *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(ztbsv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(xtbsv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\n\nint BLASFUNC(ssymv) (const char *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(dsymv) (const char *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(qsymv) (const char *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\n\nint BLASFUNC(sspmv) (char *, int *, float  *, float *,\n\t\t     float  *, int *, float *, float *, int *);\nint BLASFUNC(dspmv) (char *, int *, double  *, double *,\n\t\t     double  *, int *, double *, double *, int *);\nint BLASFUNC(qspmv) (char *, int *, double  *, double *,\n\t\t     double  *, int *, double *, double *, int *);\n\nint BLASFUNC(ssyr) (const char *, const int *, const float   *, const float  *, const int *, float  *, const int *);\nint BLASFUNC(dsyr) (const char *, const int *, const double  *, const double *, const int *, double *, const int *);\nint BLASFUNC(qsyr) (const char *, const int *, const double  *, const double *, const int *, double *, const int *);\n\nint BLASFUNC(ssyr2) (const char *, const int *, const float   *, const float  *, const int *, const float  *, const int *, float  *, const int *);\nint BLASFUNC(dsyr2) (const char *, const int *, const double  *, const double *, const int *, const double *, const int *, double *, const int *);\nint BLASFUNC(qsyr2) (const char *, const int *, const double  *, const double *, const int *, const double *, const int *, double *, const int *);\nint BLASFUNC(csyr2) (const char *, const int *, const float   *, const float  *, const int *, const float  *, const int *, float  *, const int *);\nint BLASFUNC(zsyr2) (const char *, const int *, const double  *, const double *, const int *, const double *, const int *, double *, const int *);\nint BLASFUNC(xsyr2) (const char *, const int *, const double  *, const double *, const int *, const double *, const int *, double *, const int *);\n\nint BLASFUNC(sspr) (char *, int *, float   *, float  *, int *,\n\t\t    float  *);\nint BLASFUNC(dspr) (char *, int *, double  *, double *, int *,\n\t\t    double *);\nint BLASFUNC(qspr) (char *, int *, double  *, double *, int *,\n\t\t    double *);\n\nint BLASFUNC(sspr2) (char *, int *, float   *,\n\t\t     float  *, int *, float  *, int *, float  *);\nint BLASFUNC(dspr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\nint BLASFUNC(qspr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\nint BLASFUNC(cspr2) (char *, int *, float   *,\n\t\t     float  *, int *, float  *, int *, float  *);\nint BLASFUNC(zspr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\nint BLASFUNC(xspr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\n\nint BLASFUNC(cher) (char *, int *, float   *, float  *, int *,\n\t\t    float  *, int *);\nint BLASFUNC(zher) (char *, int *, double  *, double *, int *,\n\t\t    double *, int *);\nint BLASFUNC(xher) (char *, int *, double  *, double *, int *,\n\t\t    double *, int *);\n\nint BLASFUNC(chpr) (char *, int *, float   *, float  *, int *, float  *);\nint BLASFUNC(zhpr) (char *, int *, double  *, double *, int *, double *);\nint BLASFUNC(xhpr) (char *, int *, double  *, double *, int *, double *);\n\nint BLASFUNC(cher2) (char *, int *, float   *,\n\t\t     float  *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(zher2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *, int *);\nint BLASFUNC(xher2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *, int *);\n\nint BLASFUNC(chpr2) (char *, int *, float   *,\n\t\t     float  *, int *, float  *, int *, float  *);\nint BLASFUNC(zhpr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\nint BLASFUNC(xhpr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\n\nint BLASFUNC(chemv) (const char *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zhemv) (const char *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(xhemv) (const char *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\n\nint BLASFUNC(chpmv) (char *, int *, float  *, float *,\n\t\t     float  *, int *, float *, float *, int *);\nint BLASFUNC(zhpmv) (char *, int *, double  *, double *,\n\t\t     double  *, int *, double *, double *, int *);\nint BLASFUNC(xhpmv) (char *, int *, double  *, double *,\n\t\t     double  *, int *, double *, double *, int *);\n\nint BLASFUNC(snorm)(char *, int *, int *, float  *, int *);\nint BLASFUNC(dnorm)(char *, int *, int *, double *, int *);\nint BLASFUNC(cnorm)(char *, int *, int *, float  *, int *);\nint BLASFUNC(znorm)(char *, int *, int *, double *, int *);\n\nint BLASFUNC(sgbmv)(char *, int *, int *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(dgbmv)(char *, int *, int *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(qgbmv)(char *, int *, int *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(cgbmv)(char *, int *, int *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zgbmv)(char *, int *, int *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(xgbmv)(char *, int *, int *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\n\nint BLASFUNC(ssbmv)(char *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(dsbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(qsbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(csbmv)(char *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zsbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(xsbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\n\nint BLASFUNC(chbmv)(char *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zhbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(xhbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\n\n/* Level 3 routines */\n\nint BLASFUNC(sgemm)(const char *, const char *, const int *, const int *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(dgemm)(const char *, const char *, const int *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(qgemm)(const char *, const char *, const int *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(cgemm)(const char *, const char *, const int *, const int *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zgemm)(const char *, const char *, const int *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(xgemm)(const char *, const char *, const int *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\n\nint BLASFUNC(cgemm3m)(char *, char *, int *, int *, int *, float *,\n\t   float  *, int *, float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zgemm3m)(char *, char *, int *, int *, int *, double *,\n\t   double *, int *, double *, int *, double *, double *, int *);\nint BLASFUNC(xgemm3m)(char *, char *, int *, int *, int *, double *,\n\t   double *, int *, double *, int *, double *, double *, int *);\n\nint BLASFUNC(sge2mm)(char *, char *, char *, int *, int *,\n\t\t     float *, float  *, int *, float  *, int *,\n\t\t     float *, float  *, int *);\nint BLASFUNC(dge2mm)(char *, char *, char *, int *, int *,\n\t\t     double *, double  *, int *, double  *, int *,\n\t\t     double *, double  *, int *);\nint BLASFUNC(cge2mm)(char *, char *, char *, int *, int *,\n\t\t     float *, float  *, int *, float  *, int *,\n\t\t     float *, float  *, int *);\nint BLASFUNC(zge2mm)(char *, char *, char *, int *, int *,\n\t\t     double *, double  *, int *, double  *, int *,\n\t\t     double *, double  *, int *);\n\nint BLASFUNC(strsm)(const char *, const char *, const char *, const char *, const int *, const int *, const float *,  const float *,  const int *, float *,  const int *);\nint BLASFUNC(dtrsm)(const char *, const char *, const char *, const char *, const int *, const int *, const double *, const double *, const int *, double *, const int *);\nint BLASFUNC(qtrsm)(const char *, const char *, const char *, const char *, const int *, const int *, const double *, const double *, const int *, double *, const int *);\nint BLASFUNC(ctrsm)(const char *, const char *, const char *, const char *, const int *, const int *, const float *,  const float *,  const int *, float *,  const int *);\nint BLASFUNC(ztrsm)(const char *, const char *, const char *, const char *, const int *, const int *, const double *, const double *, const int *, double *, const int *);\nint BLASFUNC(xtrsm)(const char *, const char *, const char *, const char *, const int *, const int *, const double *, const double *, const int *, double *, const int *);\n\nint BLASFUNC(strmm)(const char *, const char *, const char *, const char *, const int *, const int *, const float *,  const float *,  const int *, float *,  const int *);\nint BLASFUNC(dtrmm)(const char *, const char *, const char *, const char *, const int *, const int *, const double *, const double *, const int *, double *, const int *);\nint BLASFUNC(qtrmm)(const char *, const char *, const char *, const char *, const int *, const int *, const double *, const double *, const int *, double *, const int *);\nint BLASFUNC(ctrmm)(const char *, const char *, const char *, const char *, const int *, const int *, const float *,  const float *,  const int *, float *,  const int *);\nint BLASFUNC(ztrmm)(const char *, const char *, const char *, const char *, const int *, const int *, const double *, const double *, const int *, double *, const int *);\nint BLASFUNC(xtrmm)(const char *, const char *, const char *, const char *, const int *, const int *, const double *, const double *, const int *, double *, const int *);\n\nint BLASFUNC(ssymm)(const char *, const char *, const int *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(dsymm)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(qsymm)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(csymm)(const char *, const char *, const int *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zsymm)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(xsymm)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\n\nint BLASFUNC(csymm3m)(char *, char *, int *, int *, float  *, float  *, int *, float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zsymm3m)(char *, char *, int *, int *, double *, double *, int *, double *, int *, double *, double *, int *);\nint BLASFUNC(xsymm3m)(char *, char *, int *, int *, double *, double *, int *, double *, int *, double *, double *, int *);\n\nint BLASFUNC(ssyrk)(const char *, const char *, const int *, const int *, const float  *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(dsyrk)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(qsyrk)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(csyrk)(const char *, const char *, const int *, const int *, const float  *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zsyrk)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(xsyrk)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, double *, const int *);\n\nint BLASFUNC(ssyr2k)(const char *, const char *, const int *, const int *, const float  *, const float  *, const int *, const float *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(dsyr2k)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double*, const int *, const double *, double *, const int *);\nint BLASFUNC(qsyr2k)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double*, const int *, const double *, double *, const int *);\nint BLASFUNC(csyr2k)(const char *, const char *, const int *, const int *, const float  *, const float  *, const int *, const float *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zsyr2k)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double*, const int *, const double *, double *, const int *);\nint BLASFUNC(xsyr2k)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double*, const int *, const double *, double *, const int *);\n\nint BLASFUNC(chemm)(const char *, const char *, const int *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zhemm)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(xhemm)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\n\nint BLASFUNC(chemm3m)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zhemm3m)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\nint BLASFUNC(xhemm3m)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\n\nint BLASFUNC(cherk)(const char *, const char *, const int *, const int *, const float  *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zherk)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(xherk)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, double *, const int *);\n\nint BLASFUNC(cher2k)(const char *, const char *, const int *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zher2k)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(xher2k)(const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(cher2m)(const char *, const char *, const char *, const int *, const int *, const float  *, const float  *, const int *, const float *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zher2m)(const char *, const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double*, const int *, const double *, double *, const int *);\nint BLASFUNC(xher2m)(const char *, const char *, const char *, const int *, const int *, const double *, const double *, const int *, const double*, const int *, const double *, double *, const int *);\n\n\n#ifdef __cplusplus\n}\n#endif\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/misc/lapack.h",
    "content": "#ifndef LAPACK_H\n#define LAPACK_H\n\n#include \"blas.h\"\n\n#ifdef __cplusplus\nextern \"C\"\n{\n#endif\n\nint BLASFUNC(csymv) (const char *, const int *, const float  *, const float  *, const int *, const float  *, const int *, const float  *, float  *, const int *);\nint BLASFUNC(zsymv) (const char *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\nint BLASFUNC(xsymv) (const char *, const int *, const double *, const double *, const int *, const double *, const int *, const double *, double *, const int *);\n\n\nint BLASFUNC(cspmv) (char *, int *, float  *, float *,\n         float  *, int *, float *, float *, int *);\nint BLASFUNC(zspmv) (char *, int *, double  *, double *,\n         double  *, int *, double *, double *, int *);\nint BLASFUNC(xspmv) (char *, int *, double  *, double *,\n         double  *, int *, double *, double *, int *);\n\nint BLASFUNC(csyr) (char *, int *, float   *, float  *, int *,\n        float  *, int *);\nint BLASFUNC(zsyr) (char *, int *, double  *, double *, int *,\n        double *, int *);\nint BLASFUNC(xsyr) (char *, int *, double  *, double *, int *,\n        double *, int *);\n\nint BLASFUNC(cspr) (char *, int *, float   *, float  *, int *,\n        float  *);\nint BLASFUNC(zspr) (char *, int *, double  *, double *, int *,\n        double *);\nint BLASFUNC(xspr) (char *, int *, double  *, double *, int *,\n        double *);\n\nint BLASFUNC(sgemt)(char *, int *, int *, float  *, float  *, int *,\n        float  *, int *);\nint BLASFUNC(dgemt)(char *, int *, int *, double *, double *, int *,\n        double *, int *);\nint BLASFUNC(cgemt)(char *, int *, int *, float  *, float  *, int *,\n        float  *, int *);\nint BLASFUNC(zgemt)(char *, int *, int *, double *, double *, int *,\n        double *, int *);\n\nint BLASFUNC(sgema)(char *, char *, int *, int *, float  *,\n        float  *, int *, float *, float  *, int *, float *, int *);\nint BLASFUNC(dgema)(char *, char *, int *, int *, double *,\n        double *, int *, double*, double *, int *, double*, int *);\nint BLASFUNC(cgema)(char *, char *, int *, int *, float  *,\n        float  *, int *, float *, float  *, int *, float *, int *);\nint BLASFUNC(zgema)(char *, char *, int *, int *, double *,\n        double *, int *, double*, double *, int *, double*, int *);\n\nint BLASFUNC(sgems)(char *, char *, int *, int *, float  *,\n        float  *, int *, float *, float  *, int *, float *, int *);\nint BLASFUNC(dgems)(char *, char *, int *, int *, double *,\n        double *, int *, double*, double *, int *, double*, int *);\nint BLASFUNC(cgems)(char *, char *, int *, int *, float  *,\n        float  *, int *, float *, float  *, int *, float *, int *);\nint BLASFUNC(zgems)(char *, char *, int *, int *, double *,\n        double *, int *, double*, double *, int *, double*, int *);\n\nint BLASFUNC(sgetf2)(int *, int *, float  *, int *, int *, int *);\nint BLASFUNC(dgetf2)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(qgetf2)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(cgetf2)(int *, int *, float  *, int *, int *, int *);\nint BLASFUNC(zgetf2)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(xgetf2)(int *, int *, double *, int *, int *, int *);\n\nint BLASFUNC(sgetrf)(int *, int *, float  *, int *, int *, int *);\nint BLASFUNC(dgetrf)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(qgetrf)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(cgetrf)(int *, int *, float  *, int *, int *, int *);\nint BLASFUNC(zgetrf)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(xgetrf)(int *, int *, double *, int *, int *, int *);\n\nint BLASFUNC(slaswp)(int *, float  *, int *, int *, int *, int *, int *);\nint BLASFUNC(dlaswp)(int *, double *, int *, int *, int *, int *, int *);\nint BLASFUNC(qlaswp)(int *, double *, int *, int *, int *, int *, int *);\nint BLASFUNC(claswp)(int *, float  *, int *, int *, int *, int *, int *);\nint BLASFUNC(zlaswp)(int *, double *, int *, int *, int *, int *, int *);\nint BLASFUNC(xlaswp)(int *, double *, int *, int *, int *, int *, int *);\n\nint BLASFUNC(sgetrs)(char *, int *, int *, float  *, int *, int *, float  *, int *, int *);\nint BLASFUNC(dgetrs)(char *, int *, int *, double *, int *, int *, double *, int *, int *);\nint BLASFUNC(qgetrs)(char *, int *, int *, double *, int *, int *, double *, int *, int *);\nint BLASFUNC(cgetrs)(char *, int *, int *, float  *, int *, int *, float  *, int *, int *);\nint BLASFUNC(zgetrs)(char *, int *, int *, double *, int *, int *, double *, int *, int *);\nint BLASFUNC(xgetrs)(char *, int *, int *, double *, int *, int *, double *, int *, int *);\n\nint BLASFUNC(sgesv)(int *, int *, float  *, int *, int *, float *, int *, int *);\nint BLASFUNC(dgesv)(int *, int *, double *, int *, int *, double*, int *, int *);\nint BLASFUNC(qgesv)(int *, int *, double *, int *, int *, double*, int *, int *);\nint BLASFUNC(cgesv)(int *, int *, float  *, int *, int *, float *, int *, int *);\nint BLASFUNC(zgesv)(int *, int *, double *, int *, int *, double*, int *, int *);\nint BLASFUNC(xgesv)(int *, int *, double *, int *, int *, double*, int *, int *);\n\nint BLASFUNC(spotf2)(char *, int *, float  *, int *, int *);\nint BLASFUNC(dpotf2)(char *, int *, double *, int *, int *);\nint BLASFUNC(qpotf2)(char *, int *, double *, int *, int *);\nint BLASFUNC(cpotf2)(char *, int *, float  *, int *, int *);\nint BLASFUNC(zpotf2)(char *, int *, double *, int *, int *);\nint BLASFUNC(xpotf2)(char *, int *, double *, int *, int *);\n\nint BLASFUNC(spotrf)(char *, int *, float  *, int *, int *);\nint BLASFUNC(dpotrf)(char *, int *, double *, int *, int *);\nint BLASFUNC(qpotrf)(char *, int *, double *, int *, int *);\nint BLASFUNC(cpotrf)(char *, int *, float  *, int *, int *);\nint BLASFUNC(zpotrf)(char *, int *, double *, int *, int *);\nint BLASFUNC(xpotrf)(char *, int *, double *, int *, int *);\n\nint BLASFUNC(slauu2)(char *, int *, float  *, int *, int *);\nint BLASFUNC(dlauu2)(char *, int *, double *, int *, int *);\nint BLASFUNC(qlauu2)(char *, int *, double *, int *, int *);\nint BLASFUNC(clauu2)(char *, int *, float  *, int *, int *);\nint BLASFUNC(zlauu2)(char *, int *, double *, int *, int *);\nint BLASFUNC(xlauu2)(char *, int *, double *, int *, int *);\n\nint BLASFUNC(slauum)(char *, int *, float  *, int *, int *);\nint BLASFUNC(dlauum)(char *, int *, double *, int *, int *);\nint BLASFUNC(qlauum)(char *, int *, double *, int *, int *);\nint BLASFUNC(clauum)(char *, int *, float  *, int *, int *);\nint BLASFUNC(zlauum)(char *, int *, double *, int *, int *);\nint BLASFUNC(xlauum)(char *, int *, double *, int *, int *);\n\nint BLASFUNC(strti2)(char *, char *, int *, float  *, int *, int *);\nint BLASFUNC(dtrti2)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(qtrti2)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(ctrti2)(char *, char *, int *, float  *, int *, int *);\nint BLASFUNC(ztrti2)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(xtrti2)(char *, char *, int *, double *, int *, int *);\n\nint BLASFUNC(strtri)(char *, char *, int *, float  *, int *, int *);\nint BLASFUNC(dtrtri)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(qtrtri)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(ctrtri)(char *, char *, int *, float  *, int *, int *);\nint BLASFUNC(ztrtri)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(xtrtri)(char *, char *, int *, double *, int *, int *);\n\nint BLASFUNC(spotri)(char *, int *, float  *, int *, int *);\nint BLASFUNC(dpotri)(char *, int *, double *, int *, int *);\nint BLASFUNC(qpotri)(char *, int *, double *, int *, int *);\nint BLASFUNC(cpotri)(char *, int *, float  *, int *, int *);\nint BLASFUNC(zpotri)(char *, int *, double *, int *, int *);\nint BLASFUNC(xpotri)(char *, int *, double *, int *, int *);\n\n#ifdef __cplusplus\n}\n#endif\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/misc/lapacke.h",
    "content": "/*****************************************************************************\n  Copyright (c) 2010, Intel Corp.\n  All rights reserved.\n\n  Redistribution and use in source and binary forms, with or without\n  modification, are permitted provided that the following conditions are met:\n\n    * Redistributions of source code must retain the above copyright notice,\n      this list of conditions and the following disclaimer.\n    * Redistributions in binary form must reproduce the above copyright\n      notice, this list of conditions and the following disclaimer in the\n      documentation and/or other materials provided with the distribution.\n    * Neither the name of Intel Corporation nor the names of its contributors\n      may be used to endorse or promote products derived from this software\n      without specific prior written permission.\n\n  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\"\n  AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\n  IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE\n  ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE\n  LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR\n  CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF\n  SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS\n  INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN\n  CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)\n  ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF\n  THE POSSIBILITY OF SUCH DAMAGE.\n******************************************************************************\n* Contents: Native C interface to LAPACK\n* Author: Intel Corporation\n* Generated November, 2011\n*****************************************************************************/\n\n#ifndef _MKL_LAPACKE_H_\n\n#ifndef _LAPACKE_H_\n#define _LAPACKE_H_\n\n/*\n*  Turn on HAVE_LAPACK_CONFIG_H to redefine C-LAPACK datatypes\n*/\n#ifdef HAVE_LAPACK_CONFIG_H\n#include \"lapacke_config.h\"\n#endif\n\n#include <stdlib.h>\n\n#ifndef lapack_int\n#define lapack_int     int\n#endif\n\n#ifndef lapack_logical\n#define lapack_logical lapack_int\n#endif\n\n/* Complex types are structures equivalent to the\n* Fortran complex types COMPLEX(4) and COMPLEX(8).\n*\n* One can also redefine the types with his own types\n* for example by including in the code definitions like\n*\n* #define lapack_complex_float std::complex<float>\n* #define lapack_complex_double std::complex<double>\n*\n* or define these types in the command line:\n*\n* -Dlapack_complex_float=\"std::complex<float>\"\n* -Dlapack_complex_double=\"std::complex<double>\"\n*/\n\n#ifndef LAPACK_COMPLEX_CUSTOM\n\n/* Complex type (single precision) */\n#ifndef lapack_complex_float\n#include <complex.h>\n#define lapack_complex_float    float _Complex\n#endif\n\n#ifndef lapack_complex_float_real\n#define lapack_complex_float_real(z)       (creal(z))\n#endif\n\n#ifndef lapack_complex_float_imag\n#define lapack_complex_float_imag(z)       (cimag(z))\n#endif\n\nlapack_complex_float lapack_make_complex_float( float re, float im );\n\n/* Complex type (double precision) */\n#ifndef lapack_complex_double\n#include <complex.h>\n#define lapack_complex_double   double _Complex\n#endif\n\n#ifndef lapack_complex_double_real\n#define lapack_complex_double_real(z)      (creal(z))\n#endif\n\n#ifndef lapack_complex_double_imag\n#define lapack_complex_double_imag(z)       (cimag(z))\n#endif\n\nlapack_complex_double lapack_make_complex_double( double re, double im );\n\n#endif\n\n\n#ifdef __cplusplus\nextern \"C\" {\n#endif /* __cplusplus */\n\n#ifndef LAPACKE_malloc\n#define LAPACKE_malloc( size ) malloc( size )\n#endif\n#ifndef LAPACKE_free\n#define LAPACKE_free( p )      free( p )\n#endif\n\n#define LAPACK_C2INT( x ) (lapack_int)(*((float*)&x ))\n#define LAPACK_Z2INT( x ) (lapack_int)(*((double*)&x ))\n\n#define LAPACK_ROW_MAJOR               101\n#define LAPACK_COL_MAJOR               102\n\n#define LAPACK_WORK_MEMORY_ERROR       -1010\n#define LAPACK_TRANSPOSE_MEMORY_ERROR  -1011\n\n/* Callback logical functions of one, two, or three arguments are used\n*  to select eigenvalues to sort to the top left of the Schur form.\n*  The value is selected if function returns TRUE (non-zero). */\n\ntypedef lapack_logical (*LAPACK_S_SELECT2) ( const float*, const float* );\ntypedef lapack_logical (*LAPACK_S_SELECT3)\n    ( const float*, const float*, const float* );\ntypedef lapack_logical (*LAPACK_D_SELECT2) ( const double*, const double* );\ntypedef lapack_logical (*LAPACK_D_SELECT3)\n    ( const double*, const double*, const double* );\n\ntypedef lapack_logical (*LAPACK_C_SELECT1) ( const lapack_complex_float* );\ntypedef lapack_logical (*LAPACK_C_SELECT2)\n    ( const lapack_complex_float*, const lapack_complex_float* );\ntypedef lapack_logical (*LAPACK_Z_SELECT1) ( const lapack_complex_double* );\ntypedef lapack_logical (*LAPACK_Z_SELECT2)\n    ( const lapack_complex_double*, const lapack_complex_double* );\n\n#include \"lapacke_mangling.h\"\n\n#define LAPACK_lsame LAPACK_GLOBAL(lsame,LSAME)\nlapack_logical LAPACK_lsame( char* ca,  char* cb,\n                              lapack_int lca, lapack_int lcb );\n\n/* C-LAPACK function prototypes */\n\nlapack_int LAPACKE_sbdsdc( int matrix_order, char uplo, char compq,\n                           lapack_int n, float* d, float* e, float* u,\n                           lapack_int ldu, float* vt, lapack_int ldvt, float* q,\n                           lapack_int* iq );\nlapack_int LAPACKE_dbdsdc( int matrix_order, char uplo, char compq,\n                           lapack_int n, double* d, double* e, double* u,\n                           lapack_int ldu, double* vt, lapack_int ldvt,\n                           double* q, lapack_int* iq );\n\nlapack_int LAPACKE_sbdsqr( int matrix_order, char uplo, lapack_int n,\n                           lapack_int ncvt, lapack_int nru, lapack_int ncc,\n                           float* d, float* e, float* vt, lapack_int ldvt,\n                           float* u, lapack_int ldu, float* c, lapack_int ldc );\nlapack_int LAPACKE_dbdsqr( int matrix_order, char uplo, lapack_int n,\n                           lapack_int ncvt, lapack_int nru, lapack_int ncc,\n                           double* d, double* e, double* vt, lapack_int ldvt,\n                           double* u, lapack_int ldu, double* c,\n                           lapack_int ldc );\nlapack_int LAPACKE_cbdsqr( int matrix_order, char uplo, lapack_int n,\n                           lapack_int ncvt, lapack_int nru, lapack_int ncc,\n                           float* d, float* e, lapack_complex_float* vt,\n                           lapack_int ldvt, lapack_complex_float* u,\n                           lapack_int ldu, lapack_complex_float* c,\n                           lapack_int ldc );\nlapack_int LAPACKE_zbdsqr( int matrix_order, char uplo, lapack_int n,\n                           lapack_int ncvt, lapack_int nru, lapack_int ncc,\n                           double* d, double* e, lapack_complex_double* vt,\n                           lapack_int ldvt, lapack_complex_double* u,\n                           lapack_int ldu, lapack_complex_double* c,\n                           lapack_int ldc );\n\nlapack_int LAPACKE_sdisna( char job, lapack_int m, lapack_int n, const float* d,\n                           float* sep );\nlapack_int LAPACKE_ddisna( char job, lapack_int m, lapack_int n,\n                           const double* d, double* sep );\n\nlapack_int LAPACKE_sgbbrd( int matrix_order, char vect, lapack_int m,\n                           lapack_int n, lapack_int ncc, lapack_int kl,\n                           lapack_int ku, float* ab, lapack_int ldab, float* d,\n                           float* e, float* q, lapack_int ldq, float* pt,\n                           lapack_int ldpt, float* c, lapack_int ldc );\nlapack_int LAPACKE_dgbbrd( int matrix_order, char vect, lapack_int m,\n                           lapack_int n, lapack_int ncc, lapack_int kl,\n                           lapack_int ku, double* ab, lapack_int ldab,\n                           double* d, double* e, double* q, lapack_int ldq,\n                           double* pt, lapack_int ldpt, double* c,\n                           lapack_int ldc );\nlapack_int LAPACKE_cgbbrd( int matrix_order, char vect, lapack_int m,\n                           lapack_int n, lapack_int ncc, lapack_int kl,\n                           lapack_int ku, lapack_complex_float* ab,\n                           lapack_int ldab, float* d, float* e,\n                           lapack_complex_float* q, lapack_int ldq,\n                           lapack_complex_float* pt, lapack_int ldpt,\n                           lapack_complex_float* c, lapack_int ldc );\nlapack_int LAPACKE_zgbbrd( int matrix_order, char vect, lapack_int m,\n                           lapack_int n, lapack_int ncc, lapack_int kl,\n                           lapack_int ku, lapack_complex_double* ab,\n                           lapack_int ldab, double* d, double* e,\n                           lapack_complex_double* q, lapack_int ldq,\n                           lapack_complex_double* pt, lapack_int ldpt,\n                           lapack_complex_double* c, lapack_int ldc );\n\nlapack_int LAPACKE_sgbcon( int matrix_order, char norm, lapack_int n,\n                           lapack_int kl, lapack_int ku, const float* ab,\n                           lapack_int ldab, const lapack_int* ipiv, float anorm,\n                           float* rcond );\nlapack_int LAPACKE_dgbcon( int matrix_order, char norm, lapack_int n,\n                           lapack_int kl, lapack_int ku, const double* ab,\n                           lapack_int ldab, const lapack_int* ipiv,\n                           double anorm, double* rcond );\nlapack_int LAPACKE_cgbcon( int matrix_order, char norm, lapack_int n,\n                           lapack_int kl, lapack_int ku,\n                           const lapack_complex_float* ab, lapack_int ldab,\n                           const lapack_int* ipiv, float anorm, float* rcond );\nlapack_int LAPACKE_zgbcon( int matrix_order, char norm, lapack_int n,\n                           lapack_int kl, lapack_int ku,\n                           const lapack_complex_double* ab, lapack_int ldab,\n                           const lapack_int* ipiv, double anorm,\n                           double* rcond );\n\nlapack_int LAPACKE_sgbequ( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku, const float* ab,\n                           lapack_int ldab, float* r, float* c, float* rowcnd,\n                           float* colcnd, float* amax );\nlapack_int LAPACKE_dgbequ( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku, const double* ab,\n                           lapack_int ldab, double* r, double* c,\n                           double* rowcnd, double* colcnd, double* amax );\nlapack_int LAPACKE_cgbequ( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku,\n                           const lapack_complex_float* ab, lapack_int ldab,\n                           float* r, float* c, float* rowcnd, float* colcnd,\n                           float* amax );\nlapack_int LAPACKE_zgbequ( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku,\n                           const lapack_complex_double* ab, lapack_int ldab,\n                           double* r, double* c, double* rowcnd, double* colcnd,\n                           double* amax );\n\nlapack_int LAPACKE_sgbequb( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_int kl, lapack_int ku, const float* ab,\n                            lapack_int ldab, float* r, float* c, float* rowcnd,\n                            float* colcnd, float* amax );\nlapack_int LAPACKE_dgbequb( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_int kl, lapack_int ku, const double* ab,\n                            lapack_int ldab, double* r, double* c,\n                            double* rowcnd, double* colcnd, double* amax );\nlapack_int LAPACKE_cgbequb( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_int kl, lapack_int ku,\n                            const lapack_complex_float* ab, lapack_int ldab,\n                            float* r, float* c, float* rowcnd, float* colcnd,\n                            float* amax );\nlapack_int LAPACKE_zgbequb( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_int kl, lapack_int ku,\n                            const lapack_complex_double* ab, lapack_int ldab,\n                            double* r, double* c, double* rowcnd,\n                            double* colcnd, double* amax );\n\nlapack_int LAPACKE_sgbrfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int kl, lapack_int ku, lapack_int nrhs,\n                           const float* ab, lapack_int ldab, const float* afb,\n                           lapack_int ldafb, const lapack_int* ipiv,\n                           const float* b, lapack_int ldb, float* x,\n                           lapack_int ldx, float* ferr, float* berr );\nlapack_int LAPACKE_dgbrfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int kl, lapack_int ku, lapack_int nrhs,\n                           const double* ab, lapack_int ldab, const double* afb,\n                           lapack_int ldafb, const lapack_int* ipiv,\n                           const double* b, lapack_int ldb, double* x,\n                           lapack_int ldx, double* ferr, double* berr );\nlapack_int LAPACKE_cgbrfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int kl, lapack_int ku, lapack_int nrhs,\n                           const lapack_complex_float* ab, lapack_int ldab,\n                           const lapack_complex_float* afb, lapack_int ldafb,\n                           const lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zgbrfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int kl, lapack_int ku, lapack_int nrhs,\n                           const lapack_complex_double* ab, lapack_int ldab,\n                           const lapack_complex_double* afb, lapack_int ldafb,\n                           const lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_sgbrfsx( int matrix_order, char trans, char equed,\n                            lapack_int n, lapack_int kl, lapack_int ku,\n                            lapack_int nrhs, const float* ab, lapack_int ldab,\n                            const float* afb, lapack_int ldafb,\n                            const lapack_int* ipiv, const float* r,\n                            const float* c, const float* b, lapack_int ldb,\n                            float* x, lapack_int ldx, float* rcond, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_dgbrfsx( int matrix_order, char trans, char equed,\n                            lapack_int n, lapack_int kl, lapack_int ku,\n                            lapack_int nrhs, const double* ab, lapack_int ldab,\n                            const double* afb, lapack_int ldafb,\n                            const lapack_int* ipiv, const double* r,\n                            const double* c, const double* b, lapack_int ldb,\n                            double* x, lapack_int ldx, double* rcond,\n                            double* berr, lapack_int n_err_bnds,\n                            double* err_bnds_norm, double* err_bnds_comp,\n                            lapack_int nparams, double* params );\nlapack_int LAPACKE_cgbrfsx( int matrix_order, char trans, char equed,\n                            lapack_int n, lapack_int kl, lapack_int ku,\n                            lapack_int nrhs, const lapack_complex_float* ab,\n                            lapack_int ldab, const lapack_complex_float* afb,\n                            lapack_int ldafb, const lapack_int* ipiv,\n                            const float* r, const float* c,\n                            const lapack_complex_float* b, lapack_int ldb,\n                            lapack_complex_float* x, lapack_int ldx,\n                            float* rcond, float* berr, lapack_int n_err_bnds,\n                            float* err_bnds_norm, float* err_bnds_comp,\n                            lapack_int nparams, float* params );\nlapack_int LAPACKE_zgbrfsx( int matrix_order, char trans, char equed,\n                            lapack_int n, lapack_int kl, lapack_int ku,\n                            lapack_int nrhs, const lapack_complex_double* ab,\n                            lapack_int ldab, const lapack_complex_double* afb,\n                            lapack_int ldafb, const lapack_int* ipiv,\n                            const double* r, const double* c,\n                            const lapack_complex_double* b, lapack_int ldb,\n                            lapack_complex_double* x, lapack_int ldx,\n                            double* rcond, double* berr, lapack_int n_err_bnds,\n                            double* err_bnds_norm, double* err_bnds_comp,\n                            lapack_int nparams, double* params );\n\nlapack_int LAPACKE_sgbsv( int matrix_order, lapack_int n, lapack_int kl,\n                          lapack_int ku, lapack_int nrhs, float* ab,\n                          lapack_int ldab, lapack_int* ipiv, float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_dgbsv( int matrix_order, lapack_int n, lapack_int kl,\n                          lapack_int ku, lapack_int nrhs, double* ab,\n                          lapack_int ldab, lapack_int* ipiv, double* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_cgbsv( int matrix_order, lapack_int n, lapack_int kl,\n                          lapack_int ku, lapack_int nrhs,\n                          lapack_complex_float* ab, lapack_int ldab,\n                          lapack_int* ipiv, lapack_complex_float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_zgbsv( int matrix_order, lapack_int n, lapack_int kl,\n                          lapack_int ku, lapack_int nrhs,\n                          lapack_complex_double* ab, lapack_int ldab,\n                          lapack_int* ipiv, lapack_complex_double* b,\n                          lapack_int ldb );\n\nlapack_int LAPACKE_sgbsvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int kl, lapack_int ku,\n                           lapack_int nrhs, float* ab, lapack_int ldab,\n                           float* afb, lapack_int ldafb, lapack_int* ipiv,\n                           char* equed, float* r, float* c, float* b,\n                           lapack_int ldb, float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr,\n                           float* rpivot );\nlapack_int LAPACKE_dgbsvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int kl, lapack_int ku,\n                           lapack_int nrhs, double* ab, lapack_int ldab,\n                           double* afb, lapack_int ldafb, lapack_int* ipiv,\n                           char* equed, double* r, double* c, double* b,\n                           lapack_int ldb, double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr,\n                           double* rpivot );\nlapack_int LAPACKE_cgbsvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int kl, lapack_int ku,\n                           lapack_int nrhs, lapack_complex_float* ab,\n                           lapack_int ldab, lapack_complex_float* afb,\n                           lapack_int ldafb, lapack_int* ipiv, char* equed,\n                           float* r, float* c, lapack_complex_float* b,\n                           lapack_int ldb, lapack_complex_float* x,\n                           lapack_int ldx, float* rcond, float* ferr,\n                           float* berr, float* rpivot );\nlapack_int LAPACKE_zgbsvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int kl, lapack_int ku,\n                           lapack_int nrhs, lapack_complex_double* ab,\n                           lapack_int ldab, lapack_complex_double* afb,\n                           lapack_int ldafb, lapack_int* ipiv, char* equed,\n                           double* r, double* c, lapack_complex_double* b,\n                           lapack_int ldb, lapack_complex_double* x,\n                           lapack_int ldx, double* rcond, double* ferr,\n                           double* berr, double* rpivot );\n\nlapack_int LAPACKE_sgbsvxx( int matrix_order, char fact, char trans,\n                            lapack_int n, lapack_int kl, lapack_int ku,\n                            lapack_int nrhs, float* ab, lapack_int ldab,\n                            float* afb, lapack_int ldafb, lapack_int* ipiv,\n                            char* equed, float* r, float* c, float* b,\n                            lapack_int ldb, float* x, lapack_int ldx,\n                            float* rcond, float* rpvgrw, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_dgbsvxx( int matrix_order, char fact, char trans,\n                            lapack_int n, lapack_int kl, lapack_int ku,\n                            lapack_int nrhs, double* ab, lapack_int ldab,\n                            double* afb, lapack_int ldafb, lapack_int* ipiv,\n                            char* equed, double* r, double* c, double* b,\n                            lapack_int ldb, double* x, lapack_int ldx,\n                            double* rcond, double* rpvgrw, double* berr,\n                            lapack_int n_err_bnds, double* err_bnds_norm,\n                            double* err_bnds_comp, lapack_int nparams,\n                            double* params );\nlapack_int LAPACKE_cgbsvxx( int matrix_order, char fact, char trans,\n                            lapack_int n, lapack_int kl, lapack_int ku,\n                            lapack_int nrhs, lapack_complex_float* ab,\n                            lapack_int ldab, lapack_complex_float* afb,\n                            lapack_int ldafb, lapack_int* ipiv, char* equed,\n                            float* r, float* c, lapack_complex_float* b,\n                            lapack_int ldb, lapack_complex_float* x,\n                            lapack_int ldx, float* rcond, float* rpvgrw,\n                            float* berr, lapack_int n_err_bnds,\n                            float* err_bnds_norm, float* err_bnds_comp,\n                            lapack_int nparams, float* params );\nlapack_int LAPACKE_zgbsvxx( int matrix_order, char fact, char trans,\n                            lapack_int n, lapack_int kl, lapack_int ku,\n                            lapack_int nrhs, lapack_complex_double* ab,\n                            lapack_int ldab, lapack_complex_double* afb,\n                            lapack_int ldafb, lapack_int* ipiv, char* equed,\n                            double* r, double* c, lapack_complex_double* b,\n                            lapack_int ldb, lapack_complex_double* x,\n                            lapack_int ldx, double* rcond, double* rpvgrw,\n                            double* berr, lapack_int n_err_bnds,\n                            double* err_bnds_norm, double* err_bnds_comp,\n                            lapack_int nparams, double* params );\n\nlapack_int LAPACKE_sgbtrf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku, float* ab,\n                           lapack_int ldab, lapack_int* ipiv );\nlapack_int LAPACKE_dgbtrf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku, double* ab,\n                           lapack_int ldab, lapack_int* ipiv );\nlapack_int LAPACKE_cgbtrf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku,\n                           lapack_complex_float* ab, lapack_int ldab,\n                           lapack_int* ipiv );\nlapack_int LAPACKE_zgbtrf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku,\n                           lapack_complex_double* ab, lapack_int ldab,\n                           lapack_int* ipiv );\n\nlapack_int LAPACKE_sgbtrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int kl, lapack_int ku, lapack_int nrhs,\n                           const float* ab, lapack_int ldab,\n                           const lapack_int* ipiv, float* b, lapack_int ldb );\nlapack_int LAPACKE_dgbtrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int kl, lapack_int ku, lapack_int nrhs,\n                           const double* ab, lapack_int ldab,\n                           const lapack_int* ipiv, double* b, lapack_int ldb );\nlapack_int LAPACKE_cgbtrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int kl, lapack_int ku, lapack_int nrhs,\n                           const lapack_complex_float* ab, lapack_int ldab,\n                           const lapack_int* ipiv, lapack_complex_float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_zgbtrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int kl, lapack_int ku, lapack_int nrhs,\n                           const lapack_complex_double* ab, lapack_int ldab,\n                           const lapack_int* ipiv, lapack_complex_double* b,\n                           lapack_int ldb );\n\nlapack_int LAPACKE_sgebak( int matrix_order, char job, char side, lapack_int n,\n                           lapack_int ilo, lapack_int ihi, const float* scale,\n                           lapack_int m, float* v, lapack_int ldv );\nlapack_int LAPACKE_dgebak( int matrix_order, char job, char side, lapack_int n,\n                           lapack_int ilo, lapack_int ihi, const double* scale,\n                           lapack_int m, double* v, lapack_int ldv );\nlapack_int LAPACKE_cgebak( int matrix_order, char job, char side, lapack_int n,\n                           lapack_int ilo, lapack_int ihi, const float* scale,\n                           lapack_int m, lapack_complex_float* v,\n                           lapack_int ldv );\nlapack_int LAPACKE_zgebak( int matrix_order, char job, char side, lapack_int n,\n                           lapack_int ilo, lapack_int ihi, const double* scale,\n                           lapack_int m, lapack_complex_double* v,\n                           lapack_int ldv );\n\nlapack_int LAPACKE_sgebal( int matrix_order, char job, lapack_int n, float* a,\n                           lapack_int lda, lapack_int* ilo, lapack_int* ihi,\n                           float* scale );\nlapack_int LAPACKE_dgebal( int matrix_order, char job, lapack_int n, double* a,\n                           lapack_int lda, lapack_int* ilo, lapack_int* ihi,\n                           double* scale );\nlapack_int LAPACKE_cgebal( int matrix_order, char job, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int* ilo, lapack_int* ihi, float* scale );\nlapack_int LAPACKE_zgebal( int matrix_order, char job, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* ilo, lapack_int* ihi, double* scale );\n\nlapack_int LAPACKE_sgebrd( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, float* d, float* e,\n                           float* tauq, float* taup );\nlapack_int LAPACKE_dgebrd( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, double* d, double* e,\n                           double* tauq, double* taup );\nlapack_int LAPACKE_cgebrd( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda, float* d,\n                           float* e, lapack_complex_float* tauq,\n                           lapack_complex_float* taup );\nlapack_int LAPACKE_zgebrd( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda, double* d,\n                           double* e, lapack_complex_double* tauq,\n                           lapack_complex_double* taup );\n\nlapack_int LAPACKE_sgecon( int matrix_order, char norm, lapack_int n,\n                           const float* a, lapack_int lda, float anorm,\n                           float* rcond );\nlapack_int LAPACKE_dgecon( int matrix_order, char norm, lapack_int n,\n                           const double* a, lapack_int lda, double anorm,\n                           double* rcond );\nlapack_int LAPACKE_cgecon( int matrix_order, char norm, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           float anorm, float* rcond );\nlapack_int LAPACKE_zgecon( int matrix_order, char norm, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           double anorm, double* rcond );\n\nlapack_int LAPACKE_sgeequ( int matrix_order, lapack_int m, lapack_int n,\n                           const float* a, lapack_int lda, float* r, float* c,\n                           float* rowcnd, float* colcnd, float* amax );\nlapack_int LAPACKE_dgeequ( int matrix_order, lapack_int m, lapack_int n,\n                           const double* a, lapack_int lda, double* r,\n                           double* c, double* rowcnd, double* colcnd,\n                           double* amax );\nlapack_int LAPACKE_cgeequ( int matrix_order, lapack_int m, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           float* r, float* c, float* rowcnd, float* colcnd,\n                           float* amax );\nlapack_int LAPACKE_zgeequ( int matrix_order, lapack_int m, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           double* r, double* c, double* rowcnd, double* colcnd,\n                           double* amax );\n\nlapack_int LAPACKE_sgeequb( int matrix_order, lapack_int m, lapack_int n,\n                            const float* a, lapack_int lda, float* r, float* c,\n                            float* rowcnd, float* colcnd, float* amax );\nlapack_int LAPACKE_dgeequb( int matrix_order, lapack_int m, lapack_int n,\n                            const double* a, lapack_int lda, double* r,\n                            double* c, double* rowcnd, double* colcnd,\n                            double* amax );\nlapack_int LAPACKE_cgeequb( int matrix_order, lapack_int m, lapack_int n,\n                            const lapack_complex_float* a, lapack_int lda,\n                            float* r, float* c, float* rowcnd, float* colcnd,\n                            float* amax );\nlapack_int LAPACKE_zgeequb( int matrix_order, lapack_int m, lapack_int n,\n                            const lapack_complex_double* a, lapack_int lda,\n                            double* r, double* c, double* rowcnd,\n                            double* colcnd, double* amax );\n\nlapack_int LAPACKE_sgees( int matrix_order, char jobvs, char sort,\n                          LAPACK_S_SELECT2 select, lapack_int n, float* a,\n                          lapack_int lda, lapack_int* sdim, float* wr,\n                          float* wi, float* vs, lapack_int ldvs );\nlapack_int LAPACKE_dgees( int matrix_order, char jobvs, char sort,\n                          LAPACK_D_SELECT2 select, lapack_int n, double* a,\n                          lapack_int lda, lapack_int* sdim, double* wr,\n                          double* wi, double* vs, lapack_int ldvs );\nlapack_int LAPACKE_cgees( int matrix_order, char jobvs, char sort,\n                          LAPACK_C_SELECT1 select, lapack_int n,\n                          lapack_complex_float* a, lapack_int lda,\n                          lapack_int* sdim, lapack_complex_float* w,\n                          lapack_complex_float* vs, lapack_int ldvs );\nlapack_int LAPACKE_zgees( int matrix_order, char jobvs, char sort,\n                          LAPACK_Z_SELECT1 select, lapack_int n,\n                          lapack_complex_double* a, lapack_int lda,\n                          lapack_int* sdim, lapack_complex_double* w,\n                          lapack_complex_double* vs, lapack_int ldvs );\n\nlapack_int LAPACKE_sgeesx( int matrix_order, char jobvs, char sort,\n                           LAPACK_S_SELECT2 select, char sense, lapack_int n,\n                           float* a, lapack_int lda, lapack_int* sdim,\n                           float* wr, float* wi, float* vs, lapack_int ldvs,\n                           float* rconde, float* rcondv );\nlapack_int LAPACKE_dgeesx( int matrix_order, char jobvs, char sort,\n                           LAPACK_D_SELECT2 select, char sense, lapack_int n,\n                           double* a, lapack_int lda, lapack_int* sdim,\n                           double* wr, double* wi, double* vs, lapack_int ldvs,\n                           double* rconde, double* rcondv );\nlapack_int LAPACKE_cgeesx( int matrix_order, char jobvs, char sort,\n                           LAPACK_C_SELECT1 select, char sense, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int* sdim, lapack_complex_float* w,\n                           lapack_complex_float* vs, lapack_int ldvs,\n                           float* rconde, float* rcondv );\nlapack_int LAPACKE_zgeesx( int matrix_order, char jobvs, char sort,\n                           LAPACK_Z_SELECT1 select, char sense, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* sdim, lapack_complex_double* w,\n                           lapack_complex_double* vs, lapack_int ldvs,\n                           double* rconde, double* rcondv );\n\nlapack_int LAPACKE_sgeev( int matrix_order, char jobvl, char jobvr,\n                          lapack_int n, float* a, lapack_int lda, float* wr,\n                          float* wi, float* vl, lapack_int ldvl, float* vr,\n                          lapack_int ldvr );\nlapack_int LAPACKE_dgeev( int matrix_order, char jobvl, char jobvr,\n                          lapack_int n, double* a, lapack_int lda, double* wr,\n                          double* wi, double* vl, lapack_int ldvl, double* vr,\n                          lapack_int ldvr );\nlapack_int LAPACKE_cgeev( int matrix_order, char jobvl, char jobvr,\n                          lapack_int n, lapack_complex_float* a, lapack_int lda,\n                          lapack_complex_float* w, lapack_complex_float* vl,\n                          lapack_int ldvl, lapack_complex_float* vr,\n                          lapack_int ldvr );\nlapack_int LAPACKE_zgeev( int matrix_order, char jobvl, char jobvr,\n                          lapack_int n, lapack_complex_double* a,\n                          lapack_int lda, lapack_complex_double* w,\n                          lapack_complex_double* vl, lapack_int ldvl,\n                          lapack_complex_double* vr, lapack_int ldvr );\n\nlapack_int LAPACKE_sgeevx( int matrix_order, char balanc, char jobvl,\n                           char jobvr, char sense, lapack_int n, float* a,\n                           lapack_int lda, float* wr, float* wi, float* vl,\n                           lapack_int ldvl, float* vr, lapack_int ldvr,\n                           lapack_int* ilo, lapack_int* ihi, float* scale,\n                           float* abnrm, float* rconde, float* rcondv );\nlapack_int LAPACKE_dgeevx( int matrix_order, char balanc, char jobvl,\n                           char jobvr, char sense, lapack_int n, double* a,\n                           lapack_int lda, double* wr, double* wi, double* vl,\n                           lapack_int ldvl, double* vr, lapack_int ldvr,\n                           lapack_int* ilo, lapack_int* ihi, double* scale,\n                           double* abnrm, double* rconde, double* rcondv );\nlapack_int LAPACKE_cgeevx( int matrix_order, char balanc, char jobvl,\n                           char jobvr, char sense, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* w, lapack_complex_float* vl,\n                           lapack_int ldvl, lapack_complex_float* vr,\n                           lapack_int ldvr, lapack_int* ilo, lapack_int* ihi,\n                           float* scale, float* abnrm, float* rconde,\n                           float* rcondv );\nlapack_int LAPACKE_zgeevx( int matrix_order, char balanc, char jobvl,\n                           char jobvr, char sense, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* w, lapack_complex_double* vl,\n                           lapack_int ldvl, lapack_complex_double* vr,\n                           lapack_int ldvr, lapack_int* ilo, lapack_int* ihi,\n                           double* scale, double* abnrm, double* rconde,\n                           double* rcondv );\n\nlapack_int LAPACKE_sgehrd( int matrix_order, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, float* a, lapack_int lda,\n                           float* tau );\nlapack_int LAPACKE_dgehrd( int matrix_order, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, double* a, lapack_int lda,\n                           double* tau );\nlapack_int LAPACKE_cgehrd( int matrix_order, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* tau );\nlapack_int LAPACKE_zgehrd( int matrix_order, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* tau );\n\nlapack_int LAPACKE_sgejsv( int matrix_order, char joba, char jobu, char jobv,\n                           char jobr, char jobt, char jobp, lapack_int m,\n                           lapack_int n, float* a, lapack_int lda, float* sva,\n                           float* u, lapack_int ldu, float* v, lapack_int ldv,\n                           float* stat, lapack_int* istat );\nlapack_int LAPACKE_dgejsv( int matrix_order, char joba, char jobu, char jobv,\n                           char jobr, char jobt, char jobp, lapack_int m,\n                           lapack_int n, double* a, lapack_int lda, double* sva,\n                           double* u, lapack_int ldu, double* v, lapack_int ldv,\n                           double* stat, lapack_int* istat );\n\nlapack_int LAPACKE_sgelq2( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, float* tau );\nlapack_int LAPACKE_dgelq2( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, double* tau );\nlapack_int LAPACKE_cgelq2( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* tau );\nlapack_int LAPACKE_zgelq2( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* tau );\n\nlapack_int LAPACKE_sgelqf( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, float* tau );\nlapack_int LAPACKE_dgelqf( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, double* tau );\nlapack_int LAPACKE_cgelqf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* tau );\nlapack_int LAPACKE_zgelqf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* tau );\n\nlapack_int LAPACKE_sgels( int matrix_order, char trans, lapack_int m,\n                          lapack_int n, lapack_int nrhs, float* a,\n                          lapack_int lda, float* b, lapack_int ldb );\nlapack_int LAPACKE_dgels( int matrix_order, char trans, lapack_int m,\n                          lapack_int n, lapack_int nrhs, double* a,\n                          lapack_int lda, double* b, lapack_int ldb );\nlapack_int LAPACKE_cgels( int matrix_order, char trans, lapack_int m,\n                          lapack_int n, lapack_int nrhs,\n                          lapack_complex_float* a, lapack_int lda,\n                          lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zgels( int matrix_order, char trans, lapack_int m,\n                          lapack_int n, lapack_int nrhs,\n                          lapack_complex_double* a, lapack_int lda,\n                          lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_sgelsd( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, float* a, lapack_int lda, float* b,\n                           lapack_int ldb, float* s, float rcond,\n                           lapack_int* rank );\nlapack_int LAPACKE_dgelsd( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, double* a, lapack_int lda,\n                           double* b, lapack_int ldb, double* s, double rcond,\n                           lapack_int* rank );\nlapack_int LAPACKE_cgelsd( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* b,\n                           lapack_int ldb, float* s, float rcond,\n                           lapack_int* rank );\nlapack_int LAPACKE_zgelsd( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb, double* s, double rcond,\n                           lapack_int* rank );\n\nlapack_int LAPACKE_sgelss( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, float* a, lapack_int lda, float* b,\n                           lapack_int ldb, float* s, float rcond,\n                           lapack_int* rank );\nlapack_int LAPACKE_dgelss( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, double* a, lapack_int lda,\n                           double* b, lapack_int ldb, double* s, double rcond,\n                           lapack_int* rank );\nlapack_int LAPACKE_cgelss( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* b,\n                           lapack_int ldb, float* s, float rcond,\n                           lapack_int* rank );\nlapack_int LAPACKE_zgelss( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb, double* s, double rcond,\n                           lapack_int* rank );\n\nlapack_int LAPACKE_sgelsy( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, float* a, lapack_int lda, float* b,\n                           lapack_int ldb, lapack_int* jpvt, float rcond,\n                           lapack_int* rank );\nlapack_int LAPACKE_dgelsy( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, double* a, lapack_int lda,\n                           double* b, lapack_int ldb, lapack_int* jpvt,\n                           double rcond, lapack_int* rank );\nlapack_int LAPACKE_cgelsy( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* b,\n                           lapack_int ldb, lapack_int* jpvt, float rcond,\n                           lapack_int* rank );\nlapack_int LAPACKE_zgelsy( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nrhs, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb, lapack_int* jpvt, double rcond,\n                           lapack_int* rank );\n\nlapack_int LAPACKE_sgeqlf( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, float* tau );\nlapack_int LAPACKE_dgeqlf( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, double* tau );\nlapack_int LAPACKE_cgeqlf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* tau );\nlapack_int LAPACKE_zgeqlf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* tau );\n\nlapack_int LAPACKE_sgeqp3( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, lapack_int* jpvt,\n                           float* tau );\nlapack_int LAPACKE_dgeqp3( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, lapack_int* jpvt,\n                           double* tau );\nlapack_int LAPACKE_cgeqp3( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int* jpvt, lapack_complex_float* tau );\nlapack_int LAPACKE_zgeqp3( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* jpvt, lapack_complex_double* tau );\n\nlapack_int LAPACKE_sgeqpf( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, lapack_int* jpvt,\n                           float* tau );\nlapack_int LAPACKE_dgeqpf( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, lapack_int* jpvt,\n                           double* tau );\nlapack_int LAPACKE_cgeqpf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int* jpvt, lapack_complex_float* tau );\nlapack_int LAPACKE_zgeqpf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* jpvt, lapack_complex_double* tau );\n\nlapack_int LAPACKE_sgeqr2( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, float* tau );\nlapack_int LAPACKE_dgeqr2( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, double* tau );\nlapack_int LAPACKE_cgeqr2( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* tau );\nlapack_int LAPACKE_zgeqr2( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* tau );\n\nlapack_int LAPACKE_sgeqrf( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, float* tau );\nlapack_int LAPACKE_dgeqrf( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, double* tau );\nlapack_int LAPACKE_cgeqrf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* tau );\nlapack_int LAPACKE_zgeqrf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* tau );\n\nlapack_int LAPACKE_sgeqrfp( int matrix_order, lapack_int m, lapack_int n,\n                            float* a, lapack_int lda, float* tau );\nlapack_int LAPACKE_dgeqrfp( int matrix_order, lapack_int m, lapack_int n,\n                            double* a, lapack_int lda, double* tau );\nlapack_int LAPACKE_cgeqrfp( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_complex_float* a, lapack_int lda,\n                            lapack_complex_float* tau );\nlapack_int LAPACKE_zgeqrfp( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_complex_double* a, lapack_int lda,\n                            lapack_complex_double* tau );\n\nlapack_int LAPACKE_sgerfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const float* a, lapack_int lda,\n                           const float* af, lapack_int ldaf,\n                           const lapack_int* ipiv, const float* b,\n                           lapack_int ldb, float* x, lapack_int ldx,\n                           float* ferr, float* berr );\nlapack_int LAPACKE_dgerfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const double* a, lapack_int lda,\n                           const double* af, lapack_int ldaf,\n                           const lapack_int* ipiv, const double* b,\n                           lapack_int ldb, double* x, lapack_int ldx,\n                           double* ferr, double* berr );\nlapack_int LAPACKE_cgerfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* af,\n                           lapack_int ldaf, const lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zgerfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* af,\n                           lapack_int ldaf, const lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_sgerfsx( int matrix_order, char trans, char equed,\n                            lapack_int n, lapack_int nrhs, const float* a,\n                            lapack_int lda, const float* af, lapack_int ldaf,\n                            const lapack_int* ipiv, const float* r,\n                            const float* c, const float* b, lapack_int ldb,\n                            float* x, lapack_int ldx, float* rcond, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_dgerfsx( int matrix_order, char trans, char equed,\n                            lapack_int n, lapack_int nrhs, const double* a,\n                            lapack_int lda, const double* af, lapack_int ldaf,\n                            const lapack_int* ipiv, const double* r,\n                            const double* c, const double* b, lapack_int ldb,\n                            double* x, lapack_int ldx, double* rcond,\n                            double* berr, lapack_int n_err_bnds,\n                            double* err_bnds_norm, double* err_bnds_comp,\n                            lapack_int nparams, double* params );\nlapack_int LAPACKE_cgerfsx( int matrix_order, char trans, char equed,\n                            lapack_int n, lapack_int nrhs,\n                            const lapack_complex_float* a, lapack_int lda,\n                            const lapack_complex_float* af, lapack_int ldaf,\n                            const lapack_int* ipiv, const float* r,\n                            const float* c, const lapack_complex_float* b,\n                            lapack_int ldb, lapack_complex_float* x,\n                            lapack_int ldx, float* rcond, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_zgerfsx( int matrix_order, char trans, char equed,\n                            lapack_int n, lapack_int nrhs,\n                            const lapack_complex_double* a, lapack_int lda,\n                            const lapack_complex_double* af, lapack_int ldaf,\n                            const lapack_int* ipiv, const double* r,\n                            const double* c, const lapack_complex_double* b,\n                            lapack_int ldb, lapack_complex_double* x,\n                            lapack_int ldx, double* rcond, double* berr,\n                            lapack_int n_err_bnds, double* err_bnds_norm,\n                            double* err_bnds_comp, lapack_int nparams,\n                            double* params );\n\nlapack_int LAPACKE_sgerqf( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, float* tau );\nlapack_int LAPACKE_dgerqf( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, double* tau );\nlapack_int LAPACKE_cgerqf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* tau );\nlapack_int LAPACKE_zgerqf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* tau );\n\nlapack_int LAPACKE_sgesdd( int matrix_order, char jobz, lapack_int m,\n                           lapack_int n, float* a, lapack_int lda, float* s,\n                           float* u, lapack_int ldu, float* vt,\n                           lapack_int ldvt );\nlapack_int LAPACKE_dgesdd( int matrix_order, char jobz, lapack_int m,\n                           lapack_int n, double* a, lapack_int lda, double* s,\n                           double* u, lapack_int ldu, double* vt,\n                           lapack_int ldvt );\nlapack_int LAPACKE_cgesdd( int matrix_order, char jobz, lapack_int m,\n                           lapack_int n, lapack_complex_float* a,\n                           lapack_int lda, float* s, lapack_complex_float* u,\n                           lapack_int ldu, lapack_complex_float* vt,\n                           lapack_int ldvt );\nlapack_int LAPACKE_zgesdd( int matrix_order, char jobz, lapack_int m,\n                           lapack_int n, lapack_complex_double* a,\n                           lapack_int lda, double* s, lapack_complex_double* u,\n                           lapack_int ldu, lapack_complex_double* vt,\n                           lapack_int ldvt );\n\nlapack_int LAPACKE_sgesv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          float* a, lapack_int lda, lapack_int* ipiv, float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_dgesv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          double* a, lapack_int lda, lapack_int* ipiv,\n                          double* b, lapack_int ldb );\nlapack_int LAPACKE_cgesv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          lapack_complex_float* a, lapack_int lda,\n                          lapack_int* ipiv, lapack_complex_float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_zgesv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          lapack_complex_double* a, lapack_int lda,\n                          lapack_int* ipiv, lapack_complex_double* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_dsgesv( int matrix_order, lapack_int n, lapack_int nrhs,\n                           double* a, lapack_int lda, lapack_int* ipiv,\n                           double* b, lapack_int ldb, double* x, lapack_int ldx,\n                           lapack_int* iter );\nlapack_int LAPACKE_zcgesv( int matrix_order, lapack_int n, lapack_int nrhs,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* ipiv, lapack_complex_double* b,\n                           lapack_int ldb, lapack_complex_double* x,\n                           lapack_int ldx, lapack_int* iter );\n\nlapack_int LAPACKE_sgesvd( int matrix_order, char jobu, char jobvt,\n                           lapack_int m, lapack_int n, float* a, lapack_int lda,\n                           float* s, float* u, lapack_int ldu, float* vt,\n                           lapack_int ldvt, float* superb );\nlapack_int LAPACKE_dgesvd( int matrix_order, char jobu, char jobvt,\n                           lapack_int m, lapack_int n, double* a,\n                           lapack_int lda, double* s, double* u, lapack_int ldu,\n                           double* vt, lapack_int ldvt, double* superb );\nlapack_int LAPACKE_cgesvd( int matrix_order, char jobu, char jobvt,\n                           lapack_int m, lapack_int n, lapack_complex_float* a,\n                           lapack_int lda, float* s, lapack_complex_float* u,\n                           lapack_int ldu, lapack_complex_float* vt,\n                           lapack_int ldvt, float* superb );\nlapack_int LAPACKE_zgesvd( int matrix_order, char jobu, char jobvt,\n                           lapack_int m, lapack_int n, lapack_complex_double* a,\n                           lapack_int lda, double* s, lapack_complex_double* u,\n                           lapack_int ldu, lapack_complex_double* vt,\n                           lapack_int ldvt, double* superb );\n\nlapack_int LAPACKE_sgesvj( int matrix_order, char joba, char jobu, char jobv,\n                           lapack_int m, lapack_int n, float* a, lapack_int lda,\n                           float* sva, lapack_int mv, float* v, lapack_int ldv,\n                           float* stat );\nlapack_int LAPACKE_dgesvj( int matrix_order, char joba, char jobu, char jobv,\n                           lapack_int m, lapack_int n, double* a,\n                           lapack_int lda, double* sva, lapack_int mv,\n                           double* v, lapack_int ldv, double* stat );\n\nlapack_int LAPACKE_sgesvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int nrhs, float* a,\n                           lapack_int lda, float* af, lapack_int ldaf,\n                           lapack_int* ipiv, char* equed, float* r, float* c,\n                           float* b, lapack_int ldb, float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr,\n                           float* rpivot );\nlapack_int LAPACKE_dgesvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int nrhs, double* a,\n                           lapack_int lda, double* af, lapack_int ldaf,\n                           lapack_int* ipiv, char* equed, double* r, double* c,\n                           double* b, lapack_int ldb, double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr,\n                           double* rpivot );\nlapack_int LAPACKE_cgesvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int nrhs,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* af, lapack_int ldaf,\n                           lapack_int* ipiv, char* equed, float* r, float* c,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr,\n                           float* rpivot );\nlapack_int LAPACKE_zgesvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int nrhs,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* af, lapack_int ldaf,\n                           lapack_int* ipiv, char* equed, double* r, double* c,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr,\n                           double* rpivot );\n\nlapack_int LAPACKE_sgesvxx( int matrix_order, char fact, char trans,\n                            lapack_int n, lapack_int nrhs, float* a,\n                            lapack_int lda, float* af, lapack_int ldaf,\n                            lapack_int* ipiv, char* equed, float* r, float* c,\n                            float* b, lapack_int ldb, float* x, lapack_int ldx,\n                            float* rcond, float* rpvgrw, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_dgesvxx( int matrix_order, char fact, char trans,\n                            lapack_int n, lapack_int nrhs, double* a,\n                            lapack_int lda, double* af, lapack_int ldaf,\n                            lapack_int* ipiv, char* equed, double* r, double* c,\n                            double* b, lapack_int ldb, double* x,\n                            lapack_int ldx, double* rcond, double* rpvgrw,\n                            double* berr, lapack_int n_err_bnds,\n                            double* err_bnds_norm, double* err_bnds_comp,\n                            lapack_int nparams, double* params );\nlapack_int LAPACKE_cgesvxx( int matrix_order, char fact, char trans,\n                            lapack_int n, lapack_int nrhs,\n                            lapack_complex_float* a, lapack_int lda,\n                            lapack_complex_float* af, lapack_int ldaf,\n                            lapack_int* ipiv, char* equed, float* r, float* c,\n                            lapack_complex_float* b, lapack_int ldb,\n                            lapack_complex_float* x, lapack_int ldx,\n                            float* rcond, float* rpvgrw, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_zgesvxx( int matrix_order, char fact, char trans,\n                            lapack_int n, lapack_int nrhs,\n                            lapack_complex_double* a, lapack_int lda,\n                            lapack_complex_double* af, lapack_int ldaf,\n                            lapack_int* ipiv, char* equed, double* r, double* c,\n                            lapack_complex_double* b, lapack_int ldb,\n                            lapack_complex_double* x, lapack_int ldx,\n                            double* rcond, double* rpvgrw, double* berr,\n                            lapack_int n_err_bnds, double* err_bnds_norm,\n                            double* err_bnds_comp, lapack_int nparams,\n                            double* params );\n\nlapack_int LAPACKE_sgetf2( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, lapack_int* ipiv );\nlapack_int LAPACKE_dgetf2( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, lapack_int* ipiv );\nlapack_int LAPACKE_cgetf2( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int* ipiv );\nlapack_int LAPACKE_zgetf2( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* ipiv );\n\nlapack_int LAPACKE_sgetrf( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, lapack_int* ipiv );\nlapack_int LAPACKE_dgetrf( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, lapack_int* ipiv );\nlapack_int LAPACKE_cgetrf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int* ipiv );\nlapack_int LAPACKE_zgetrf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* ipiv );\n\nlapack_int LAPACKE_sgetri( int matrix_order, lapack_int n, float* a,\n                           lapack_int lda, const lapack_int* ipiv );\nlapack_int LAPACKE_dgetri( int matrix_order, lapack_int n, double* a,\n                           lapack_int lda, const lapack_int* ipiv );\nlapack_int LAPACKE_cgetri( int matrix_order, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           const lapack_int* ipiv );\nlapack_int LAPACKE_zgetri( int matrix_order, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           const lapack_int* ipiv );\n\nlapack_int LAPACKE_sgetrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const float* a, lapack_int lda,\n                           const lapack_int* ipiv, float* b, lapack_int ldb );\nlapack_int LAPACKE_dgetrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const double* a, lapack_int lda,\n                           const lapack_int* ipiv, double* b, lapack_int ldb );\nlapack_int LAPACKE_cgetrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* a,\n                           lapack_int lda, const lapack_int* ipiv,\n                           lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zgetrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* a,\n                           lapack_int lda, const lapack_int* ipiv,\n                           lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_sggbak( int matrix_order, char job, char side, lapack_int n,\n                           lapack_int ilo, lapack_int ihi, const float* lscale,\n                           const float* rscale, lapack_int m, float* v,\n                           lapack_int ldv );\nlapack_int LAPACKE_dggbak( int matrix_order, char job, char side, lapack_int n,\n                           lapack_int ilo, lapack_int ihi, const double* lscale,\n                           const double* rscale, lapack_int m, double* v,\n                           lapack_int ldv );\nlapack_int LAPACKE_cggbak( int matrix_order, char job, char side, lapack_int n,\n                           lapack_int ilo, lapack_int ihi, const float* lscale,\n                           const float* rscale, lapack_int m,\n                           lapack_complex_float* v, lapack_int ldv );\nlapack_int LAPACKE_zggbak( int matrix_order, char job, char side, lapack_int n,\n                           lapack_int ilo, lapack_int ihi, const double* lscale,\n                           const double* rscale, lapack_int m,\n                           lapack_complex_double* v, lapack_int ldv );\n\nlapack_int LAPACKE_sggbal( int matrix_order, char job, lapack_int n, float* a,\n                           lapack_int lda, float* b, lapack_int ldb,\n                           lapack_int* ilo, lapack_int* ihi, float* lscale,\n                           float* rscale );\nlapack_int LAPACKE_dggbal( int matrix_order, char job, lapack_int n, double* a,\n                           lapack_int lda, double* b, lapack_int ldb,\n                           lapack_int* ilo, lapack_int* ihi, double* lscale,\n                           double* rscale );\nlapack_int LAPACKE_cggbal( int matrix_order, char job, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_int* ilo, lapack_int* ihi, float* lscale,\n                           float* rscale );\nlapack_int LAPACKE_zggbal( int matrix_order, char job, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_int* ilo, lapack_int* ihi, double* lscale,\n                           double* rscale );\n\nlapack_int LAPACKE_sgges( int matrix_order, char jobvsl, char jobvsr, char sort,\n                          LAPACK_S_SELECT3 selctg, lapack_int n, float* a,\n                          lapack_int lda, float* b, lapack_int ldb,\n                          lapack_int* sdim, float* alphar, float* alphai,\n                          float* beta, float* vsl, lapack_int ldvsl, float* vsr,\n                          lapack_int ldvsr );\nlapack_int LAPACKE_dgges( int matrix_order, char jobvsl, char jobvsr, char sort,\n                          LAPACK_D_SELECT3 selctg, lapack_int n, double* a,\n                          lapack_int lda, double* b, lapack_int ldb,\n                          lapack_int* sdim, double* alphar, double* alphai,\n                          double* beta, double* vsl, lapack_int ldvsl,\n                          double* vsr, lapack_int ldvsr );\nlapack_int LAPACKE_cgges( int matrix_order, char jobvsl, char jobvsr, char sort,\n                          LAPACK_C_SELECT2 selctg, lapack_int n,\n                          lapack_complex_float* a, lapack_int lda,\n                          lapack_complex_float* b, lapack_int ldb,\n                          lapack_int* sdim, lapack_complex_float* alpha,\n                          lapack_complex_float* beta, lapack_complex_float* vsl,\n                          lapack_int ldvsl, lapack_complex_float* vsr,\n                          lapack_int ldvsr );\nlapack_int LAPACKE_zgges( int matrix_order, char jobvsl, char jobvsr, char sort,\n                          LAPACK_Z_SELECT2 selctg, lapack_int n,\n                          lapack_complex_double* a, lapack_int lda,\n                          lapack_complex_double* b, lapack_int ldb,\n                          lapack_int* sdim, lapack_complex_double* alpha,\n                          lapack_complex_double* beta,\n                          lapack_complex_double* vsl, lapack_int ldvsl,\n                          lapack_complex_double* vsr, lapack_int ldvsr );\n\nlapack_int LAPACKE_sggesx( int matrix_order, char jobvsl, char jobvsr,\n                           char sort, LAPACK_S_SELECT3 selctg, char sense,\n                           lapack_int n, float* a, lapack_int lda, float* b,\n                           lapack_int ldb, lapack_int* sdim, float* alphar,\n                           float* alphai, float* beta, float* vsl,\n                           lapack_int ldvsl, float* vsr, lapack_int ldvsr,\n                           float* rconde, float* rcondv );\nlapack_int LAPACKE_dggesx( int matrix_order, char jobvsl, char jobvsr,\n                           char sort, LAPACK_D_SELECT3 selctg, char sense,\n                           lapack_int n, double* a, lapack_int lda, double* b,\n                           lapack_int ldb, lapack_int* sdim, double* alphar,\n                           double* alphai, double* beta, double* vsl,\n                           lapack_int ldvsl, double* vsr, lapack_int ldvsr,\n                           double* rconde, double* rcondv );\nlapack_int LAPACKE_cggesx( int matrix_order, char jobvsl, char jobvsr,\n                           char sort, LAPACK_C_SELECT2 selctg, char sense,\n                           lapack_int n, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* b,\n                           lapack_int ldb, lapack_int* sdim,\n                           lapack_complex_float* alpha,\n                           lapack_complex_float* beta,\n                           lapack_complex_float* vsl, lapack_int ldvsl,\n                           lapack_complex_float* vsr, lapack_int ldvsr,\n                           float* rconde, float* rcondv );\nlapack_int LAPACKE_zggesx( int matrix_order, char jobvsl, char jobvsr,\n                           char sort, LAPACK_Z_SELECT2 selctg, char sense,\n                           lapack_int n, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb, lapack_int* sdim,\n                           lapack_complex_double* alpha,\n                           lapack_complex_double* beta,\n                           lapack_complex_double* vsl, lapack_int ldvsl,\n                           lapack_complex_double* vsr, lapack_int ldvsr,\n                           double* rconde, double* rcondv );\n\nlapack_int LAPACKE_sggev( int matrix_order, char jobvl, char jobvr,\n                          lapack_int n, float* a, lapack_int lda, float* b,\n                          lapack_int ldb, float* alphar, float* alphai,\n                          float* beta, float* vl, lapack_int ldvl, float* vr,\n                          lapack_int ldvr );\nlapack_int LAPACKE_dggev( int matrix_order, char jobvl, char jobvr,\n                          lapack_int n, double* a, lapack_int lda, double* b,\n                          lapack_int ldb, double* alphar, double* alphai,\n                          double* beta, double* vl, lapack_int ldvl, double* vr,\n                          lapack_int ldvr );\nlapack_int LAPACKE_cggev( int matrix_order, char jobvl, char jobvr,\n                          lapack_int n, lapack_complex_float* a, lapack_int lda,\n                          lapack_complex_float* b, lapack_int ldb,\n                          lapack_complex_float* alpha,\n                          lapack_complex_float* beta, lapack_complex_float* vl,\n                          lapack_int ldvl, lapack_complex_float* vr,\n                          lapack_int ldvr );\nlapack_int LAPACKE_zggev( int matrix_order, char jobvl, char jobvr,\n                          lapack_int n, lapack_complex_double* a,\n                          lapack_int lda, lapack_complex_double* b,\n                          lapack_int ldb, lapack_complex_double* alpha,\n                          lapack_complex_double* beta,\n                          lapack_complex_double* vl, lapack_int ldvl,\n                          lapack_complex_double* vr, lapack_int ldvr );\n\nlapack_int LAPACKE_sggevx( int matrix_order, char balanc, char jobvl,\n                           char jobvr, char sense, lapack_int n, float* a,\n                           lapack_int lda, float* b, lapack_int ldb,\n                           float* alphar, float* alphai, float* beta, float* vl,\n                           lapack_int ldvl, float* vr, lapack_int ldvr,\n                           lapack_int* ilo, lapack_int* ihi, float* lscale,\n                           float* rscale, float* abnrm, float* bbnrm,\n                           float* rconde, float* rcondv );\nlapack_int LAPACKE_dggevx( int matrix_order, char balanc, char jobvl,\n                           char jobvr, char sense, lapack_int n, double* a,\n                           lapack_int lda, double* b, lapack_int ldb,\n                           double* alphar, double* alphai, double* beta,\n                           double* vl, lapack_int ldvl, double* vr,\n                           lapack_int ldvr, lapack_int* ilo, lapack_int* ihi,\n                           double* lscale, double* rscale, double* abnrm,\n                           double* bbnrm, double* rconde, double* rcondv );\nlapack_int LAPACKE_cggevx( int matrix_order, char balanc, char jobvl,\n                           char jobvr, char sense, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* alpha,\n                           lapack_complex_float* beta, lapack_complex_float* vl,\n                           lapack_int ldvl, lapack_complex_float* vr,\n                           lapack_int ldvr, lapack_int* ilo, lapack_int* ihi,\n                           float* lscale, float* rscale, float* abnrm,\n                           float* bbnrm, float* rconde, float* rcondv );\nlapack_int LAPACKE_zggevx( int matrix_order, char balanc, char jobvl,\n                           char jobvr, char sense, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* alpha,\n                           lapack_complex_double* beta,\n                           lapack_complex_double* vl, lapack_int ldvl,\n                           lapack_complex_double* vr, lapack_int ldvr,\n                           lapack_int* ilo, lapack_int* ihi, double* lscale,\n                           double* rscale, double* abnrm, double* bbnrm,\n                           double* rconde, double* rcondv );\n\nlapack_int LAPACKE_sggglm( int matrix_order, lapack_int n, lapack_int m,\n                           lapack_int p, float* a, lapack_int lda, float* b,\n                           lapack_int ldb, float* d, float* x, float* y );\nlapack_int LAPACKE_dggglm( int matrix_order, lapack_int n, lapack_int m,\n                           lapack_int p, double* a, lapack_int lda, double* b,\n                           lapack_int ldb, double* d, double* x, double* y );\nlapack_int LAPACKE_cggglm( int matrix_order, lapack_int n, lapack_int m,\n                           lapack_int p, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* b,\n                           lapack_int ldb, lapack_complex_float* d,\n                           lapack_complex_float* x, lapack_complex_float* y );\nlapack_int LAPACKE_zggglm( int matrix_order, lapack_int n, lapack_int m,\n                           lapack_int p, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb, lapack_complex_double* d,\n                           lapack_complex_double* x, lapack_complex_double* y );\n\nlapack_int LAPACKE_sgghrd( int matrix_order, char compq, char compz,\n                           lapack_int n, lapack_int ilo, lapack_int ihi,\n                           float* a, lapack_int lda, float* b, lapack_int ldb,\n                           float* q, lapack_int ldq, float* z, lapack_int ldz );\nlapack_int LAPACKE_dgghrd( int matrix_order, char compq, char compz,\n                           lapack_int n, lapack_int ilo, lapack_int ihi,\n                           double* a, lapack_int lda, double* b, lapack_int ldb,\n                           double* q, lapack_int ldq, double* z,\n                           lapack_int ldz );\nlapack_int LAPACKE_cgghrd( int matrix_order, char compq, char compz,\n                           lapack_int n, lapack_int ilo, lapack_int ihi,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* q, lapack_int ldq,\n                           lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zgghrd( int matrix_order, char compq, char compz,\n                           lapack_int n, lapack_int ilo, lapack_int ihi,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* q, lapack_int ldq,\n                           lapack_complex_double* z, lapack_int ldz );\n\nlapack_int LAPACKE_sgglse( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int p, float* a, lapack_int lda, float* b,\n                           lapack_int ldb, float* c, float* d, float* x );\nlapack_int LAPACKE_dgglse( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int p, double* a, lapack_int lda, double* b,\n                           lapack_int ldb, double* c, double* d, double* x );\nlapack_int LAPACKE_cgglse( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int p, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* b,\n                           lapack_int ldb, lapack_complex_float* c,\n                           lapack_complex_float* d, lapack_complex_float* x );\nlapack_int LAPACKE_zgglse( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int p, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb, lapack_complex_double* c,\n                           lapack_complex_double* d, lapack_complex_double* x );\n\nlapack_int LAPACKE_sggqrf( int matrix_order, lapack_int n, lapack_int m,\n                           lapack_int p, float* a, lapack_int lda, float* taua,\n                           float* b, lapack_int ldb, float* taub );\nlapack_int LAPACKE_dggqrf( int matrix_order, lapack_int n, lapack_int m,\n                           lapack_int p, double* a, lapack_int lda,\n                           double* taua, double* b, lapack_int ldb,\n                           double* taub );\nlapack_int LAPACKE_cggqrf( int matrix_order, lapack_int n, lapack_int m,\n                           lapack_int p, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* taua,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* taub );\nlapack_int LAPACKE_zggqrf( int matrix_order, lapack_int n, lapack_int m,\n                           lapack_int p, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* taua,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* taub );\n\nlapack_int LAPACKE_sggrqf( int matrix_order, lapack_int m, lapack_int p,\n                           lapack_int n, float* a, lapack_int lda, float* taua,\n                           float* b, lapack_int ldb, float* taub );\nlapack_int LAPACKE_dggrqf( int matrix_order, lapack_int m, lapack_int p,\n                           lapack_int n, double* a, lapack_int lda,\n                           double* taua, double* b, lapack_int ldb,\n                           double* taub );\nlapack_int LAPACKE_cggrqf( int matrix_order, lapack_int m, lapack_int p,\n                           lapack_int n, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* taua,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* taub );\nlapack_int LAPACKE_zggrqf( int matrix_order, lapack_int m, lapack_int p,\n                           lapack_int n, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* taua,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* taub );\n\nlapack_int LAPACKE_sggsvd( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int n, lapack_int p,\n                           lapack_int* k, lapack_int* l, float* a,\n                           lapack_int lda, float* b, lapack_int ldb,\n                           float* alpha, float* beta, float* u, lapack_int ldu,\n                           float* v, lapack_int ldv, float* q, lapack_int ldq,\n                           lapack_int* iwork );\nlapack_int LAPACKE_dggsvd( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int n, lapack_int p,\n                           lapack_int* k, lapack_int* l, double* a,\n                           lapack_int lda, double* b, lapack_int ldb,\n                           double* alpha, double* beta, double* u,\n                           lapack_int ldu, double* v, lapack_int ldv, double* q,\n                           lapack_int ldq, lapack_int* iwork );\nlapack_int LAPACKE_cggsvd( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int n, lapack_int p,\n                           lapack_int* k, lapack_int* l,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* b, lapack_int ldb,\n                           float* alpha, float* beta, lapack_complex_float* u,\n                           lapack_int ldu, lapack_complex_float* v,\n                           lapack_int ldv, lapack_complex_float* q,\n                           lapack_int ldq, lapack_int* iwork );\nlapack_int LAPACKE_zggsvd( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int n, lapack_int p,\n                           lapack_int* k, lapack_int* l,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb,\n                           double* alpha, double* beta,\n                           lapack_complex_double* u, lapack_int ldu,\n                           lapack_complex_double* v, lapack_int ldv,\n                           lapack_complex_double* q, lapack_int ldq,\n                           lapack_int* iwork );\n\nlapack_int LAPACKE_sggsvp( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int p, lapack_int n, float* a,\n                           lapack_int lda, float* b, lapack_int ldb, float tola,\n                           float tolb, lapack_int* k, lapack_int* l, float* u,\n                           lapack_int ldu, float* v, lapack_int ldv, float* q,\n                           lapack_int ldq );\nlapack_int LAPACKE_dggsvp( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int p, lapack_int n, double* a,\n                           lapack_int lda, double* b, lapack_int ldb,\n                           double tola, double tolb, lapack_int* k,\n                           lapack_int* l, double* u, lapack_int ldu, double* v,\n                           lapack_int ldv, double* q, lapack_int ldq );\nlapack_int LAPACKE_cggsvp( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int p, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* b, lapack_int ldb, float tola,\n                           float tolb, lapack_int* k, lapack_int* l,\n                           lapack_complex_float* u, lapack_int ldu,\n                           lapack_complex_float* v, lapack_int ldv,\n                           lapack_complex_float* q, lapack_int ldq );\nlapack_int LAPACKE_zggsvp( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int p, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb,\n                           double tola, double tolb, lapack_int* k,\n                           lapack_int* l, lapack_complex_double* u,\n                           lapack_int ldu, lapack_complex_double* v,\n                           lapack_int ldv, lapack_complex_double* q,\n                           lapack_int ldq );\n\nlapack_int LAPACKE_sgtcon( char norm, lapack_int n, const float* dl,\n                           const float* d, const float* du, const float* du2,\n                           const lapack_int* ipiv, float anorm, float* rcond );\nlapack_int LAPACKE_dgtcon( char norm, lapack_int n, const double* dl,\n                           const double* d, const double* du, const double* du2,\n                           const lapack_int* ipiv, double anorm,\n                           double* rcond );\nlapack_int LAPACKE_cgtcon( char norm, lapack_int n,\n                           const lapack_complex_float* dl,\n                           const lapack_complex_float* d,\n                           const lapack_complex_float* du,\n                           const lapack_complex_float* du2,\n                           const lapack_int* ipiv, float anorm, float* rcond );\nlapack_int LAPACKE_zgtcon( char norm, lapack_int n,\n                           const lapack_complex_double* dl,\n                           const lapack_complex_double* d,\n                           const lapack_complex_double* du,\n                           const lapack_complex_double* du2,\n                           const lapack_int* ipiv, double anorm,\n                           double* rcond );\n\nlapack_int LAPACKE_sgtrfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const float* dl, const float* d,\n                           const float* du, const float* dlf, const float* df,\n                           const float* duf, const float* du2,\n                           const lapack_int* ipiv, const float* b,\n                           lapack_int ldb, float* x, lapack_int ldx,\n                           float* ferr, float* berr );\nlapack_int LAPACKE_dgtrfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const double* dl, const double* d,\n                           const double* du, const double* dlf,\n                           const double* df, const double* duf,\n                           const double* du2, const lapack_int* ipiv,\n                           const double* b, lapack_int ldb, double* x,\n                           lapack_int ldx, double* ferr, double* berr );\nlapack_int LAPACKE_cgtrfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* dl,\n                           const lapack_complex_float* d,\n                           const lapack_complex_float* du,\n                           const lapack_complex_float* dlf,\n                           const lapack_complex_float* df,\n                           const lapack_complex_float* duf,\n                           const lapack_complex_float* du2,\n                           const lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zgtrfs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* dl,\n                           const lapack_complex_double* d,\n                           const lapack_complex_double* du,\n                           const lapack_complex_double* dlf,\n                           const lapack_complex_double* df,\n                           const lapack_complex_double* duf,\n                           const lapack_complex_double* du2,\n                           const lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_sgtsv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          float* dl, float* d, float* du, float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_dgtsv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          double* dl, double* d, double* du, double* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_cgtsv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          lapack_complex_float* dl, lapack_complex_float* d,\n                          lapack_complex_float* du, lapack_complex_float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_zgtsv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          lapack_complex_double* dl, lapack_complex_double* d,\n                          lapack_complex_double* du, lapack_complex_double* b,\n                          lapack_int ldb );\n\nlapack_int LAPACKE_sgtsvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int nrhs, const float* dl,\n                           const float* d, const float* du, float* dlf,\n                           float* df, float* duf, float* du2, lapack_int* ipiv,\n                           const float* b, lapack_int ldb, float* x,\n                           lapack_int ldx, float* rcond, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_dgtsvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int nrhs, const double* dl,\n                           const double* d, const double* du, double* dlf,\n                           double* df, double* duf, double* du2,\n                           lapack_int* ipiv, const double* b, lapack_int ldb,\n                           double* x, lapack_int ldx, double* rcond,\n                           double* ferr, double* berr );\nlapack_int LAPACKE_cgtsvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_float* dl,\n                           const lapack_complex_float* d,\n                           const lapack_complex_float* du,\n                           lapack_complex_float* dlf, lapack_complex_float* df,\n                           lapack_complex_float* duf, lapack_complex_float* du2,\n                           lapack_int* ipiv, const lapack_complex_float* b,\n                           lapack_int ldb, lapack_complex_float* x,\n                           lapack_int ldx, float* rcond, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zgtsvx( int matrix_order, char fact, char trans,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_double* dl,\n                           const lapack_complex_double* d,\n                           const lapack_complex_double* du,\n                           lapack_complex_double* dlf,\n                           lapack_complex_double* df,\n                           lapack_complex_double* duf,\n                           lapack_complex_double* du2, lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr );\n\nlapack_int LAPACKE_sgttrf( lapack_int n, float* dl, float* d, float* du,\n                           float* du2, lapack_int* ipiv );\nlapack_int LAPACKE_dgttrf( lapack_int n, double* dl, double* d, double* du,\n                           double* du2, lapack_int* ipiv );\nlapack_int LAPACKE_cgttrf( lapack_int n, lapack_complex_float* dl,\n                           lapack_complex_float* d, lapack_complex_float* du,\n                           lapack_complex_float* du2, lapack_int* ipiv );\nlapack_int LAPACKE_zgttrf( lapack_int n, lapack_complex_double* dl,\n                           lapack_complex_double* d, lapack_complex_double* du,\n                           lapack_complex_double* du2, lapack_int* ipiv );\n\nlapack_int LAPACKE_sgttrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const float* dl, const float* d,\n                           const float* du, const float* du2,\n                           const lapack_int* ipiv, float* b, lapack_int ldb );\nlapack_int LAPACKE_dgttrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const double* dl, const double* d,\n                           const double* du, const double* du2,\n                           const lapack_int* ipiv, double* b, lapack_int ldb );\nlapack_int LAPACKE_cgttrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* dl,\n                           const lapack_complex_float* d,\n                           const lapack_complex_float* du,\n                           const lapack_complex_float* du2,\n                           const lapack_int* ipiv, lapack_complex_float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_zgttrs( int matrix_order, char trans, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* dl,\n                           const lapack_complex_double* d,\n                           const lapack_complex_double* du,\n                           const lapack_complex_double* du2,\n                           const lapack_int* ipiv, lapack_complex_double* b,\n                           lapack_int ldb );\n\nlapack_int LAPACKE_chbev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_int kd, lapack_complex_float* ab,\n                          lapack_int ldab, float* w, lapack_complex_float* z,\n                          lapack_int ldz );\nlapack_int LAPACKE_zhbev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_int kd, lapack_complex_double* ab,\n                          lapack_int ldab, double* w, lapack_complex_double* z,\n                          lapack_int ldz );\n\nlapack_int LAPACKE_chbevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_int kd, lapack_complex_float* ab,\n                           lapack_int ldab, float* w, lapack_complex_float* z,\n                           lapack_int ldz );\nlapack_int LAPACKE_zhbevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_int kd, lapack_complex_double* ab,\n                           lapack_int ldab, double* w, lapack_complex_double* z,\n                           lapack_int ldz );\n\nlapack_int LAPACKE_chbevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_int kd,\n                           lapack_complex_float* ab, lapack_int ldab,\n                           lapack_complex_float* q, lapack_int ldq, float vl,\n                           float vu, lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, lapack_complex_float* z,\n                           lapack_int ldz, lapack_int* ifail );\nlapack_int LAPACKE_zhbevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_int kd,\n                           lapack_complex_double* ab, lapack_int ldab,\n                           lapack_complex_double* q, lapack_int ldq, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w,\n                           lapack_complex_double* z, lapack_int ldz,\n                           lapack_int* ifail );\n\nlapack_int LAPACKE_chbgst( int matrix_order, char vect, char uplo, lapack_int n,\n                           lapack_int ka, lapack_int kb,\n                           lapack_complex_float* ab, lapack_int ldab,\n                           const lapack_complex_float* bb, lapack_int ldbb,\n                           lapack_complex_float* x, lapack_int ldx );\nlapack_int LAPACKE_zhbgst( int matrix_order, char vect, char uplo, lapack_int n,\n                           lapack_int ka, lapack_int kb,\n                           lapack_complex_double* ab, lapack_int ldab,\n                           const lapack_complex_double* bb, lapack_int ldbb,\n                           lapack_complex_double* x, lapack_int ldx );\n\nlapack_int LAPACKE_chbgv( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_int ka, lapack_int kb,\n                          lapack_complex_float* ab, lapack_int ldab,\n                          lapack_complex_float* bb, lapack_int ldbb, float* w,\n                          lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zhbgv( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_int ka, lapack_int kb,\n                          lapack_complex_double* ab, lapack_int ldab,\n                          lapack_complex_double* bb, lapack_int ldbb, double* w,\n                          lapack_complex_double* z, lapack_int ldz );\n\nlapack_int LAPACKE_chbgvd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_int ka, lapack_int kb,\n                           lapack_complex_float* ab, lapack_int ldab,\n                           lapack_complex_float* bb, lapack_int ldbb, float* w,\n                           lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zhbgvd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_int ka, lapack_int kb,\n                           lapack_complex_double* ab, lapack_int ldab,\n                           lapack_complex_double* bb, lapack_int ldbb,\n                           double* w, lapack_complex_double* z,\n                           lapack_int ldz );\n\nlapack_int LAPACKE_chbgvx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_int ka, lapack_int kb,\n                           lapack_complex_float* ab, lapack_int ldab,\n                           lapack_complex_float* bb, lapack_int ldbb,\n                           lapack_complex_float* q, lapack_int ldq, float vl,\n                           float vu, lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, lapack_complex_float* z,\n                           lapack_int ldz, lapack_int* ifail );\nlapack_int LAPACKE_zhbgvx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_int ka, lapack_int kb,\n                           lapack_complex_double* ab, lapack_int ldab,\n                           lapack_complex_double* bb, lapack_int ldbb,\n                           lapack_complex_double* q, lapack_int ldq, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w,\n                           lapack_complex_double* z, lapack_int ldz,\n                           lapack_int* ifail );\n\nlapack_int LAPACKE_chbtrd( int matrix_order, char vect, char uplo, lapack_int n,\n                           lapack_int kd, lapack_complex_float* ab,\n                           lapack_int ldab, float* d, float* e,\n                           lapack_complex_float* q, lapack_int ldq );\nlapack_int LAPACKE_zhbtrd( int matrix_order, char vect, char uplo, lapack_int n,\n                           lapack_int kd, lapack_complex_double* ab,\n                           lapack_int ldab, double* d, double* e,\n                           lapack_complex_double* q, lapack_int ldq );\n\nlapack_int LAPACKE_checon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_int* ipiv, float anorm, float* rcond );\nlapack_int LAPACKE_zhecon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_int* ipiv, double anorm,\n                           double* rcond );\n\nlapack_int LAPACKE_cheequb( int matrix_order, char uplo, lapack_int n,\n                            const lapack_complex_float* a, lapack_int lda,\n                            float* s, float* scond, float* amax );\nlapack_int LAPACKE_zheequb( int matrix_order, char uplo, lapack_int n,\n                            const lapack_complex_double* a, lapack_int lda,\n                            double* s, double* scond, double* amax );\n\nlapack_int LAPACKE_cheev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_complex_float* a, lapack_int lda, float* w );\nlapack_int LAPACKE_zheev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_complex_double* a, lapack_int lda, double* w );\n\nlapack_int LAPACKE_cheevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda, float* w );\nlapack_int LAPACKE_zheevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           double* w );\n\nlapack_int LAPACKE_cheevr( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_complex_float* a,\n                           lapack_int lda, float vl, float vu, lapack_int il,\n                           lapack_int iu, float abstol, lapack_int* m, float* w,\n                           lapack_complex_float* z, lapack_int ldz,\n                           lapack_int* isuppz );\nlapack_int LAPACKE_zheevr( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_complex_double* a,\n                           lapack_int lda, double vl, double vu, lapack_int il,\n                           lapack_int iu, double abstol, lapack_int* m,\n                           double* w, lapack_complex_double* z, lapack_int ldz,\n                           lapack_int* isuppz );\n\nlapack_int LAPACKE_cheevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_complex_float* a,\n                           lapack_int lda, float vl, float vu, lapack_int il,\n                           lapack_int iu, float abstol, lapack_int* m, float* w,\n                           lapack_complex_float* z, lapack_int ldz,\n                           lapack_int* ifail );\nlapack_int LAPACKE_zheevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_complex_double* a,\n                           lapack_int lda, double vl, double vu, lapack_int il,\n                           lapack_int iu, double abstol, lapack_int* m,\n                           double* w, lapack_complex_double* z, lapack_int ldz,\n                           lapack_int* ifail );\n\nlapack_int LAPACKE_chegst( int matrix_order, lapack_int itype, char uplo,\n                           lapack_int n, lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_zhegst( int matrix_order, lapack_int itype, char uplo,\n                           lapack_int n, lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* b,\n                           lapack_int ldb );\n\nlapack_int LAPACKE_chegv( int matrix_order, lapack_int itype, char jobz,\n                          char uplo, lapack_int n, lapack_complex_float* a,\n                          lapack_int lda, lapack_complex_float* b,\n                          lapack_int ldb, float* w );\nlapack_int LAPACKE_zhegv( int matrix_order, lapack_int itype, char jobz,\n                          char uplo, lapack_int n, lapack_complex_double* a,\n                          lapack_int lda, lapack_complex_double* b,\n                          lapack_int ldb, double* w );\n\nlapack_int LAPACKE_chegvd( int matrix_order, lapack_int itype, char jobz,\n                           char uplo, lapack_int n, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* b,\n                           lapack_int ldb, float* w );\nlapack_int LAPACKE_zhegvd( int matrix_order, lapack_int itype, char jobz,\n                           char uplo, lapack_int n, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb, double* w );\n\nlapack_int LAPACKE_chegvx( int matrix_order, lapack_int itype, char jobz,\n                           char range, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* b, lapack_int ldb, float vl,\n                           float vu, lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, lapack_complex_float* z,\n                           lapack_int ldz, lapack_int* ifail );\nlapack_int LAPACKE_zhegvx( int matrix_order, lapack_int itype, char jobz,\n                           char range, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w,\n                           lapack_complex_double* z, lapack_int ldz,\n                           lapack_int* ifail );\n\nlapack_int LAPACKE_cherfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* af,\n                           lapack_int ldaf, const lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zherfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* af,\n                           lapack_int ldaf, const lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_cherfsx( int matrix_order, char uplo, char equed,\n                            lapack_int n, lapack_int nrhs,\n                            const lapack_complex_float* a, lapack_int lda,\n                            const lapack_complex_float* af, lapack_int ldaf,\n                            const lapack_int* ipiv, const float* s,\n                            const lapack_complex_float* b, lapack_int ldb,\n                            lapack_complex_float* x, lapack_int ldx,\n                            float* rcond, float* berr, lapack_int n_err_bnds,\n                            float* err_bnds_norm, float* err_bnds_comp,\n                            lapack_int nparams, float* params );\nlapack_int LAPACKE_zherfsx( int matrix_order, char uplo, char equed,\n                            lapack_int n, lapack_int nrhs,\n                            const lapack_complex_double* a, lapack_int lda,\n                            const lapack_complex_double* af, lapack_int ldaf,\n                            const lapack_int* ipiv, const double* s,\n                            const lapack_complex_double* b, lapack_int ldb,\n                            lapack_complex_double* x, lapack_int ldx,\n                            double* rcond, double* berr, lapack_int n_err_bnds,\n                            double* err_bnds_norm, double* err_bnds_comp,\n                            lapack_int nparams, double* params );\n\nlapack_int LAPACKE_chesv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_float* a,\n                          lapack_int lda, lapack_int* ipiv,\n                          lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zhesv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_double* a,\n                          lapack_int lda, lapack_int* ipiv,\n                          lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_chesvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* af,\n                           lapack_int ldaf, lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr );\nlapack_int LAPACKE_zhesvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* af,\n                           lapack_int ldaf, lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr );\n\nlapack_int LAPACKE_chesvxx( int matrix_order, char fact, char uplo,\n                            lapack_int n, lapack_int nrhs,\n                            lapack_complex_float* a, lapack_int lda,\n                            lapack_complex_float* af, lapack_int ldaf,\n                            lapack_int* ipiv, char* equed, float* s,\n                            lapack_complex_float* b, lapack_int ldb,\n                            lapack_complex_float* x, lapack_int ldx,\n                            float* rcond, float* rpvgrw, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_zhesvxx( int matrix_order, char fact, char uplo,\n                            lapack_int n, lapack_int nrhs,\n                            lapack_complex_double* a, lapack_int lda,\n                            lapack_complex_double* af, lapack_int ldaf,\n                            lapack_int* ipiv, char* equed, double* s,\n                            lapack_complex_double* b, lapack_int ldb,\n                            lapack_complex_double* x, lapack_int ldx,\n                            double* rcond, double* rpvgrw, double* berr,\n                            lapack_int n_err_bnds, double* err_bnds_norm,\n                            double* err_bnds_comp, lapack_int nparams,\n                            double* params );\n\nlapack_int LAPACKE_chetrd( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda, float* d,\n                           float* e, lapack_complex_float* tau );\nlapack_int LAPACKE_zhetrd( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda, double* d,\n                           double* e, lapack_complex_double* tau );\n\nlapack_int LAPACKE_chetrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int* ipiv );\nlapack_int LAPACKE_zhetrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* ipiv );\n\nlapack_int LAPACKE_chetri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           const lapack_int* ipiv );\nlapack_int LAPACKE_zhetri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           const lapack_int* ipiv );\n\nlapack_int LAPACKE_chetrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* a,\n                           lapack_int lda, const lapack_int* ipiv,\n                           lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zhetrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* a,\n                           lapack_int lda, const lapack_int* ipiv,\n                           lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_chfrk( int matrix_order, char transr, char uplo, char trans,\n                          lapack_int n, lapack_int k, float alpha,\n                          const lapack_complex_float* a, lapack_int lda,\n                          float beta, lapack_complex_float* c );\nlapack_int LAPACKE_zhfrk( int matrix_order, char transr, char uplo, char trans,\n                          lapack_int n, lapack_int k, double alpha,\n                          const lapack_complex_double* a, lapack_int lda,\n                          double beta, lapack_complex_double* c );\n\nlapack_int LAPACKE_shgeqz( int matrix_order, char job, char compq, char compz,\n                           lapack_int n, lapack_int ilo, lapack_int ihi,\n                           float* h, lapack_int ldh, float* t, lapack_int ldt,\n                           float* alphar, float* alphai, float* beta, float* q,\n                           lapack_int ldq, float* z, lapack_int ldz );\nlapack_int LAPACKE_dhgeqz( int matrix_order, char job, char compq, char compz,\n                           lapack_int n, lapack_int ilo, lapack_int ihi,\n                           double* h, lapack_int ldh, double* t, lapack_int ldt,\n                           double* alphar, double* alphai, double* beta,\n                           double* q, lapack_int ldq, double* z,\n                           lapack_int ldz );\nlapack_int LAPACKE_chgeqz( int matrix_order, char job, char compq, char compz,\n                           lapack_int n, lapack_int ilo, lapack_int ihi,\n                           lapack_complex_float* h, lapack_int ldh,\n                           lapack_complex_float* t, lapack_int ldt,\n                           lapack_complex_float* alpha,\n                           lapack_complex_float* beta, lapack_complex_float* q,\n                           lapack_int ldq, lapack_complex_float* z,\n                           lapack_int ldz );\nlapack_int LAPACKE_zhgeqz( int matrix_order, char job, char compq, char compz,\n                           lapack_int n, lapack_int ilo, lapack_int ihi,\n                           lapack_complex_double* h, lapack_int ldh,\n                           lapack_complex_double* t, lapack_int ldt,\n                           lapack_complex_double* alpha,\n                           lapack_complex_double* beta,\n                           lapack_complex_double* q, lapack_int ldq,\n                           lapack_complex_double* z, lapack_int ldz );\n\nlapack_int LAPACKE_chpcon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_float* ap,\n                           const lapack_int* ipiv, float anorm, float* rcond );\nlapack_int LAPACKE_zhpcon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_double* ap,\n                           const lapack_int* ipiv, double anorm,\n                           double* rcond );\n\nlapack_int LAPACKE_chpev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_complex_float* ap, float* w,\n                          lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zhpev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_complex_double* ap, double* w,\n                          lapack_complex_double* z, lapack_int ldz );\n\nlapack_int LAPACKE_chpevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_complex_float* ap, float* w,\n                           lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zhpevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_complex_double* ap, double* w,\n                           lapack_complex_double* z, lapack_int ldz );\n\nlapack_int LAPACKE_chpevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_complex_float* ap, float vl,\n                           float vu, lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, lapack_complex_float* z,\n                           lapack_int ldz, lapack_int* ifail );\nlapack_int LAPACKE_zhpevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_complex_double* ap, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w,\n                           lapack_complex_double* z, lapack_int ldz,\n                           lapack_int* ifail );\n\nlapack_int LAPACKE_chpgst( int matrix_order, lapack_int itype, char uplo,\n                           lapack_int n, lapack_complex_float* ap,\n                           const lapack_complex_float* bp );\nlapack_int LAPACKE_zhpgst( int matrix_order, lapack_int itype, char uplo,\n                           lapack_int n, lapack_complex_double* ap,\n                           const lapack_complex_double* bp );\n\nlapack_int LAPACKE_chpgv( int matrix_order, lapack_int itype, char jobz,\n                          char uplo, lapack_int n, lapack_complex_float* ap,\n                          lapack_complex_float* bp, float* w,\n                          lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zhpgv( int matrix_order, lapack_int itype, char jobz,\n                          char uplo, lapack_int n, lapack_complex_double* ap,\n                          lapack_complex_double* bp, double* w,\n                          lapack_complex_double* z, lapack_int ldz );\n\nlapack_int LAPACKE_chpgvd( int matrix_order, lapack_int itype, char jobz,\n                           char uplo, lapack_int n, lapack_complex_float* ap,\n                           lapack_complex_float* bp, float* w,\n                           lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zhpgvd( int matrix_order, lapack_int itype, char jobz,\n                           char uplo, lapack_int n, lapack_complex_double* ap,\n                           lapack_complex_double* bp, double* w,\n                           lapack_complex_double* z, lapack_int ldz );\n\nlapack_int LAPACKE_chpgvx( int matrix_order, lapack_int itype, char jobz,\n                           char range, char uplo, lapack_int n,\n                           lapack_complex_float* ap, lapack_complex_float* bp,\n                           float vl, float vu, lapack_int il, lapack_int iu,\n                           float abstol, lapack_int* m, float* w,\n                           lapack_complex_float* z, lapack_int ldz,\n                           lapack_int* ifail );\nlapack_int LAPACKE_zhpgvx( int matrix_order, lapack_int itype, char jobz,\n                           char range, char uplo, lapack_int n,\n                           lapack_complex_double* ap, lapack_complex_double* bp,\n                           double vl, double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w,\n                           lapack_complex_double* z, lapack_int ldz,\n                           lapack_int* ifail );\n\nlapack_int LAPACKE_chprfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* ap,\n                           const lapack_complex_float* afp,\n                           const lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zhprfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* ap,\n                           const lapack_complex_double* afp,\n                           const lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_chpsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_float* ap,\n                          lapack_int* ipiv, lapack_complex_float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_zhpsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_double* ap,\n                          lapack_int* ipiv, lapack_complex_double* b,\n                          lapack_int ldb );\n\nlapack_int LAPACKE_chpsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* ap,\n                           lapack_complex_float* afp, lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr );\nlapack_int LAPACKE_zhpsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* ap,\n                           lapack_complex_double* afp, lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr );\n\nlapack_int LAPACKE_chptrd( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* ap, float* d, float* e,\n                           lapack_complex_float* tau );\nlapack_int LAPACKE_zhptrd( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* ap, double* d, double* e,\n                           lapack_complex_double* tau );\n\nlapack_int LAPACKE_chptrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* ap, lapack_int* ipiv );\nlapack_int LAPACKE_zhptrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* ap, lapack_int* ipiv );\n\nlapack_int LAPACKE_chptri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* ap, const lapack_int* ipiv );\nlapack_int LAPACKE_zhptri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* ap, const lapack_int* ipiv );\n\nlapack_int LAPACKE_chptrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* ap,\n                           const lapack_int* ipiv, lapack_complex_float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_zhptrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* ap,\n                           const lapack_int* ipiv, lapack_complex_double* b,\n                           lapack_int ldb );\n\nlapack_int LAPACKE_shsein( int matrix_order, char job, char eigsrc, char initv,\n                           lapack_logical* select, lapack_int n, const float* h,\n                           lapack_int ldh, float* wr, const float* wi,\n                           float* vl, lapack_int ldvl, float* vr,\n                           lapack_int ldvr, lapack_int mm, lapack_int* m,\n                           lapack_int* ifaill, lapack_int* ifailr );\nlapack_int LAPACKE_dhsein( int matrix_order, char job, char eigsrc, char initv,\n                           lapack_logical* select, lapack_int n,\n                           const double* h, lapack_int ldh, double* wr,\n                           const double* wi, double* vl, lapack_int ldvl,\n                           double* vr, lapack_int ldvr, lapack_int mm,\n                           lapack_int* m, lapack_int* ifaill,\n                           lapack_int* ifailr );\nlapack_int LAPACKE_chsein( int matrix_order, char job, char eigsrc, char initv,\n                           const lapack_logical* select, lapack_int n,\n                           const lapack_complex_float* h, lapack_int ldh,\n                           lapack_complex_float* w, lapack_complex_float* vl,\n                           lapack_int ldvl, lapack_complex_float* vr,\n                           lapack_int ldvr, lapack_int mm, lapack_int* m,\n                           lapack_int* ifaill, lapack_int* ifailr );\nlapack_int LAPACKE_zhsein( int matrix_order, char job, char eigsrc, char initv,\n                           const lapack_logical* select, lapack_int n,\n                           const lapack_complex_double* h, lapack_int ldh,\n                           lapack_complex_double* w, lapack_complex_double* vl,\n                           lapack_int ldvl, lapack_complex_double* vr,\n                           lapack_int ldvr, lapack_int mm, lapack_int* m,\n                           lapack_int* ifaill, lapack_int* ifailr );\n\nlapack_int LAPACKE_shseqr( int matrix_order, char job, char compz, lapack_int n,\n                           lapack_int ilo, lapack_int ihi, float* h,\n                           lapack_int ldh, float* wr, float* wi, float* z,\n                           lapack_int ldz );\nlapack_int LAPACKE_dhseqr( int matrix_order, char job, char compz, lapack_int n,\n                           lapack_int ilo, lapack_int ihi, double* h,\n                           lapack_int ldh, double* wr, double* wi, double* z,\n                           lapack_int ldz );\nlapack_int LAPACKE_chseqr( int matrix_order, char job, char compz, lapack_int n,\n                           lapack_int ilo, lapack_int ihi,\n                           lapack_complex_float* h, lapack_int ldh,\n                           lapack_complex_float* w, lapack_complex_float* z,\n                           lapack_int ldz );\nlapack_int LAPACKE_zhseqr( int matrix_order, char job, char compz, lapack_int n,\n                           lapack_int ilo, lapack_int ihi,\n                           lapack_complex_double* h, lapack_int ldh,\n                           lapack_complex_double* w, lapack_complex_double* z,\n                           lapack_int ldz );\n\nlapack_int LAPACKE_clacgv( lapack_int n, lapack_complex_float* x,\n                           lapack_int incx );\nlapack_int LAPACKE_zlacgv( lapack_int n, lapack_complex_double* x,\n                           lapack_int incx );\n\nlapack_int LAPACKE_slacpy( int matrix_order, char uplo, lapack_int m,\n                           lapack_int n, const float* a, lapack_int lda, float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_dlacpy( int matrix_order, char uplo, lapack_int m,\n                           lapack_int n, const double* a, lapack_int lda, double* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_clacpy( int matrix_order, char uplo, lapack_int m,\n                           lapack_int n, const lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_zlacpy( int matrix_order, char uplo, lapack_int m,\n                           lapack_int n, const lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb );\n\nlapack_int LAPACKE_zlag2c( int matrix_order, lapack_int m, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_float* sa, lapack_int ldsa );\n\nlapack_int LAPACKE_slag2d( int matrix_order, lapack_int m, lapack_int n,\n                           const float* sa, lapack_int ldsa, double* a,\n                           lapack_int lda );\n\nlapack_int LAPACKE_dlag2s( int matrix_order, lapack_int m, lapack_int n,\n                           const double* a, lapack_int lda, float* sa,\n                           lapack_int ldsa );\n\nlapack_int LAPACKE_clag2z( int matrix_order, lapack_int m, lapack_int n,\n                           const lapack_complex_float* sa, lapack_int ldsa,\n                           lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_slagge( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku, const float* d,\n                           float* a, lapack_int lda, lapack_int* iseed );\nlapack_int LAPACKE_dlagge( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku, const double* d,\n                           double* a, lapack_int lda, lapack_int* iseed );\nlapack_int LAPACKE_clagge( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku, const float* d,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int* iseed );\nlapack_int LAPACKE_zlagge( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int kl, lapack_int ku, const double* d,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* iseed );\n\nfloat LAPACKE_slamch( char cmach );\ndouble LAPACKE_dlamch( char cmach );\n\nfloat LAPACKE_slange( int matrix_order, char norm, lapack_int m,\n                           lapack_int n, const float* a, lapack_int lda );\ndouble LAPACKE_dlange( int matrix_order, char norm, lapack_int m,\n                           lapack_int n, const double* a, lapack_int lda );\nfloat LAPACKE_clange( int matrix_order, char norm, lapack_int m,\n                           lapack_int n, const lapack_complex_float* a,\n                           lapack_int lda );\ndouble LAPACKE_zlange( int matrix_order, char norm, lapack_int m,\n                           lapack_int n, const lapack_complex_double* a,\n                           lapack_int lda );\n\nfloat LAPACKE_clanhe( int matrix_order, char norm, char uplo, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda );\ndouble LAPACKE_zlanhe( int matrix_order, char norm, char uplo, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda );\n\nfloat LAPACKE_slansy( int matrix_order, char norm, char uplo, lapack_int n,\n                           const float* a, lapack_int lda );\ndouble LAPACKE_dlansy( int matrix_order, char norm, char uplo, lapack_int n,\n                           const double* a, lapack_int lda );\nfloat LAPACKE_clansy( int matrix_order, char norm, char uplo, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda );\ndouble LAPACKE_zlansy( int matrix_order, char norm, char uplo, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda );\n\nfloat LAPACKE_slantr( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int m, lapack_int n, const float* a,\n                           lapack_int lda );\ndouble LAPACKE_dlantr( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int m, lapack_int n, const double* a,\n                           lapack_int lda );\nfloat LAPACKE_clantr( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int m, lapack_int n, const lapack_complex_float* a,\n                           lapack_int lda );\ndouble LAPACKE_zlantr( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int m, lapack_int n, const lapack_complex_double* a,\n                           lapack_int lda );\n\n\nlapack_int LAPACKE_slarfb( int matrix_order, char side, char trans, char direct,\n                           char storev, lapack_int m, lapack_int n,\n                           lapack_int k, const float* v, lapack_int ldv,\n                           const float* t, lapack_int ldt, float* c,\n                           lapack_int ldc );\nlapack_int LAPACKE_dlarfb( int matrix_order, char side, char trans, char direct,\n                           char storev, lapack_int m, lapack_int n,\n                           lapack_int k, const double* v, lapack_int ldv,\n                           const double* t, lapack_int ldt, double* c,\n                           lapack_int ldc );\nlapack_int LAPACKE_clarfb( int matrix_order, char side, char trans, char direct,\n                           char storev, lapack_int m, lapack_int n,\n                           lapack_int k, const lapack_complex_float* v,\n                           lapack_int ldv, const lapack_complex_float* t,\n                           lapack_int ldt, lapack_complex_float* c,\n                           lapack_int ldc );\nlapack_int LAPACKE_zlarfb( int matrix_order, char side, char trans, char direct,\n                           char storev, lapack_int m, lapack_int n,\n                           lapack_int k, const lapack_complex_double* v,\n                           lapack_int ldv, const lapack_complex_double* t,\n                           lapack_int ldt, lapack_complex_double* c,\n                           lapack_int ldc );\n\nlapack_int LAPACKE_slarfg( lapack_int n, float* alpha, float* x,\n                           lapack_int incx, float* tau );\nlapack_int LAPACKE_dlarfg( lapack_int n, double* alpha, double* x,\n                           lapack_int incx, double* tau );\nlapack_int LAPACKE_clarfg( lapack_int n, lapack_complex_float* alpha,\n                           lapack_complex_float* x, lapack_int incx,\n                           lapack_complex_float* tau );\nlapack_int LAPACKE_zlarfg( lapack_int n, lapack_complex_double* alpha,\n                           lapack_complex_double* x, lapack_int incx,\n                           lapack_complex_double* tau );\n\nlapack_int LAPACKE_slarft( int matrix_order, char direct, char storev,\n                           lapack_int n, lapack_int k, const float* v,\n                           lapack_int ldv, const float* tau, float* t,\n                           lapack_int ldt );\nlapack_int LAPACKE_dlarft( int matrix_order, char direct, char storev,\n                           lapack_int n, lapack_int k, const double* v,\n                           lapack_int ldv, const double* tau, double* t,\n                           lapack_int ldt );\nlapack_int LAPACKE_clarft( int matrix_order, char direct, char storev,\n                           lapack_int n, lapack_int k,\n                           const lapack_complex_float* v, lapack_int ldv,\n                           const lapack_complex_float* tau,\n                           lapack_complex_float* t, lapack_int ldt );\nlapack_int LAPACKE_zlarft( int matrix_order, char direct, char storev,\n                           lapack_int n, lapack_int k,\n                           const lapack_complex_double* v, lapack_int ldv,\n                           const lapack_complex_double* tau,\n                           lapack_complex_double* t, lapack_int ldt );\n\nlapack_int LAPACKE_slarfx( int matrix_order, char side, lapack_int m,\n                           lapack_int n, const float* v, float tau, float* c,\n                           lapack_int ldc, float* work );\nlapack_int LAPACKE_dlarfx( int matrix_order, char side, lapack_int m,\n                           lapack_int n, const double* v, double tau, double* c,\n                           lapack_int ldc, double* work );\nlapack_int LAPACKE_clarfx( int matrix_order, char side, lapack_int m,\n                           lapack_int n, const lapack_complex_float* v,\n                           lapack_complex_float tau, lapack_complex_float* c,\n                           lapack_int ldc, lapack_complex_float* work );\nlapack_int LAPACKE_zlarfx( int matrix_order, char side, lapack_int m,\n                           lapack_int n, const lapack_complex_double* v,\n                           lapack_complex_double tau, lapack_complex_double* c,\n                           lapack_int ldc, lapack_complex_double* work );\n\nlapack_int LAPACKE_slarnv( lapack_int idist, lapack_int* iseed, lapack_int n,\n                           float* x );\nlapack_int LAPACKE_dlarnv( lapack_int idist, lapack_int* iseed, lapack_int n,\n                           double* x );\nlapack_int LAPACKE_clarnv( lapack_int idist, lapack_int* iseed, lapack_int n,\n                           lapack_complex_float* x );\nlapack_int LAPACKE_zlarnv( lapack_int idist, lapack_int* iseed, lapack_int n,\n                           lapack_complex_double* x );\n\nlapack_int LAPACKE_slaset( int matrix_order, char uplo, lapack_int m,\n                           lapack_int n, float alpha, float beta, float* a,\n                           lapack_int lda );\nlapack_int LAPACKE_dlaset( int matrix_order, char uplo, lapack_int m,\n                           lapack_int n, double alpha, double beta, double* a,\n                           lapack_int lda );\nlapack_int LAPACKE_claset( int matrix_order, char uplo, lapack_int m,\n                           lapack_int n, lapack_complex_float alpha,\n                           lapack_complex_float beta, lapack_complex_float* a,\n                           lapack_int lda );\nlapack_int LAPACKE_zlaset( int matrix_order, char uplo, lapack_int m,\n                           lapack_int n, lapack_complex_double alpha,\n                           lapack_complex_double beta, lapack_complex_double* a,\n                           lapack_int lda );\n\nlapack_int LAPACKE_slasrt( char id, lapack_int n, float* d );\nlapack_int LAPACKE_dlasrt( char id, lapack_int n, double* d );\n\nlapack_int LAPACKE_slaswp( int matrix_order, lapack_int n, float* a,\n                           lapack_int lda, lapack_int k1, lapack_int k2,\n                           const lapack_int* ipiv, lapack_int incx );\nlapack_int LAPACKE_dlaswp( int matrix_order, lapack_int n, double* a,\n                           lapack_int lda, lapack_int k1, lapack_int k2,\n                           const lapack_int* ipiv, lapack_int incx );\nlapack_int LAPACKE_claswp( int matrix_order, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int k1, lapack_int k2, const lapack_int* ipiv,\n                           lapack_int incx );\nlapack_int LAPACKE_zlaswp( int matrix_order, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int k1, lapack_int k2, const lapack_int* ipiv,\n                           lapack_int incx );\n\nlapack_int LAPACKE_slatms( int matrix_order, lapack_int m, lapack_int n,\n                           char dist, lapack_int* iseed, char sym, float* d,\n                           lapack_int mode, float cond, float dmax,\n                           lapack_int kl, lapack_int ku, char pack, float* a,\n                           lapack_int lda );\nlapack_int LAPACKE_dlatms( int matrix_order, lapack_int m, lapack_int n,\n                           char dist, lapack_int* iseed, char sym, double* d,\n                           lapack_int mode, double cond, double dmax,\n                           lapack_int kl, lapack_int ku, char pack, double* a,\n                           lapack_int lda );\nlapack_int LAPACKE_clatms( int matrix_order, lapack_int m, lapack_int n,\n                           char dist, lapack_int* iseed, char sym, float* d,\n                           lapack_int mode, float cond, float dmax,\n                           lapack_int kl, lapack_int ku, char pack,\n                           lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_zlatms( int matrix_order, lapack_int m, lapack_int n,\n                           char dist, lapack_int* iseed, char sym, double* d,\n                           lapack_int mode, double cond, double dmax,\n                           lapack_int kl, lapack_int ku, char pack,\n                           lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_slauum( int matrix_order, char uplo, lapack_int n, float* a,\n                           lapack_int lda );\nlapack_int LAPACKE_dlauum( int matrix_order, char uplo, lapack_int n, double* a,\n                           lapack_int lda );\nlapack_int LAPACKE_clauum( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_zlauum( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_sopgtr( int matrix_order, char uplo, lapack_int n,\n                           const float* ap, const float* tau, float* q,\n                           lapack_int ldq );\nlapack_int LAPACKE_dopgtr( int matrix_order, char uplo, lapack_int n,\n                           const double* ap, const double* tau, double* q,\n                           lapack_int ldq );\n\nlapack_int LAPACKE_sopmtr( int matrix_order, char side, char uplo, char trans,\n                           lapack_int m, lapack_int n, const float* ap,\n                           const float* tau, float* c, lapack_int ldc );\nlapack_int LAPACKE_dopmtr( int matrix_order, char side, char uplo, char trans,\n                           lapack_int m, lapack_int n, const double* ap,\n                           const double* tau, double* c, lapack_int ldc );\n\nlapack_int LAPACKE_sorgbr( int matrix_order, char vect, lapack_int m,\n                           lapack_int n, lapack_int k, float* a, lapack_int lda,\n                           const float* tau );\nlapack_int LAPACKE_dorgbr( int matrix_order, char vect, lapack_int m,\n                           lapack_int n, lapack_int k, double* a,\n                           lapack_int lda, const double* tau );\n\nlapack_int LAPACKE_sorghr( int matrix_order, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, float* a, lapack_int lda,\n                           const float* tau );\nlapack_int LAPACKE_dorghr( int matrix_order, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, double* a, lapack_int lda,\n                           const double* tau );\n\nlapack_int LAPACKE_sorglq( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, float* a, lapack_int lda,\n                           const float* tau );\nlapack_int LAPACKE_dorglq( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, double* a, lapack_int lda,\n                           const double* tau );\n\nlapack_int LAPACKE_sorgql( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, float* a, lapack_int lda,\n                           const float* tau );\nlapack_int LAPACKE_dorgql( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, double* a, lapack_int lda,\n                           const double* tau );\n\nlapack_int LAPACKE_sorgqr( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, float* a, lapack_int lda,\n                           const float* tau );\nlapack_int LAPACKE_dorgqr( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, double* a, lapack_int lda,\n                           const double* tau );\n\nlapack_int LAPACKE_sorgrq( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, float* a, lapack_int lda,\n                           const float* tau );\nlapack_int LAPACKE_dorgrq( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, double* a, lapack_int lda,\n                           const double* tau );\n\nlapack_int LAPACKE_sorgtr( int matrix_order, char uplo, lapack_int n, float* a,\n                           lapack_int lda, const float* tau );\nlapack_int LAPACKE_dorgtr( int matrix_order, char uplo, lapack_int n, double* a,\n                           lapack_int lda, const double* tau );\n\nlapack_int LAPACKE_sormbr( int matrix_order, char vect, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const float* a, lapack_int lda, const float* tau,\n                           float* c, lapack_int ldc );\nlapack_int LAPACKE_dormbr( int matrix_order, char vect, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const double* a, lapack_int lda, const double* tau,\n                           double* c, lapack_int ldc );\n\nlapack_int LAPACKE_sormhr( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, const float* a, lapack_int lda,\n                           const float* tau, float* c, lapack_int ldc );\nlapack_int LAPACKE_dormhr( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, const double* a, lapack_int lda,\n                           const double* tau, double* c, lapack_int ldc );\n\nlapack_int LAPACKE_sormlq( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const float* a, lapack_int lda, const float* tau,\n                           float* c, lapack_int ldc );\nlapack_int LAPACKE_dormlq( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const double* a, lapack_int lda, const double* tau,\n                           double* c, lapack_int ldc );\n\nlapack_int LAPACKE_sormql( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const float* a, lapack_int lda, const float* tau,\n                           float* c, lapack_int ldc );\nlapack_int LAPACKE_dormql( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const double* a, lapack_int lda, const double* tau,\n                           double* c, lapack_int ldc );\n\nlapack_int LAPACKE_sormqr( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const float* a, lapack_int lda, const float* tau,\n                           float* c, lapack_int ldc );\nlapack_int LAPACKE_dormqr( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const double* a, lapack_int lda, const double* tau,\n                           double* c, lapack_int ldc );\n\nlapack_int LAPACKE_sormrq( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const float* a, lapack_int lda, const float* tau,\n                           float* c, lapack_int ldc );\nlapack_int LAPACKE_dormrq( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const double* a, lapack_int lda, const double* tau,\n                           double* c, lapack_int ldc );\n\nlapack_int LAPACKE_sormrz( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           lapack_int l, const float* a, lapack_int lda,\n                           const float* tau, float* c, lapack_int ldc );\nlapack_int LAPACKE_dormrz( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           lapack_int l, const double* a, lapack_int lda,\n                           const double* tau, double* c, lapack_int ldc );\n\nlapack_int LAPACKE_sormtr( int matrix_order, char side, char uplo, char trans,\n                           lapack_int m, lapack_int n, const float* a,\n                           lapack_int lda, const float* tau, float* c,\n                           lapack_int ldc );\nlapack_int LAPACKE_dormtr( int matrix_order, char side, char uplo, char trans,\n                           lapack_int m, lapack_int n, const double* a,\n                           lapack_int lda, const double* tau, double* c,\n                           lapack_int ldc );\n\nlapack_int LAPACKE_spbcon( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, const float* ab, lapack_int ldab,\n                           float anorm, float* rcond );\nlapack_int LAPACKE_dpbcon( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, const double* ab, lapack_int ldab,\n                           double anorm, double* rcond );\nlapack_int LAPACKE_cpbcon( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, const lapack_complex_float* ab,\n                           lapack_int ldab, float anorm, float* rcond );\nlapack_int LAPACKE_zpbcon( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, const lapack_complex_double* ab,\n                           lapack_int ldab, double anorm, double* rcond );\n\nlapack_int LAPACKE_spbequ( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, const float* ab, lapack_int ldab,\n                           float* s, float* scond, float* amax );\nlapack_int LAPACKE_dpbequ( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, const double* ab, lapack_int ldab,\n                           double* s, double* scond, double* amax );\nlapack_int LAPACKE_cpbequ( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, const lapack_complex_float* ab,\n                           lapack_int ldab, float* s, float* scond,\n                           float* amax );\nlapack_int LAPACKE_zpbequ( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, const lapack_complex_double* ab,\n                           lapack_int ldab, double* s, double* scond,\n                           double* amax );\n\nlapack_int LAPACKE_spbrfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs, const float* ab,\n                           lapack_int ldab, const float* afb, lapack_int ldafb,\n                           const float* b, lapack_int ldb, float* x,\n                           lapack_int ldx, float* ferr, float* berr );\nlapack_int LAPACKE_dpbrfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs, const double* ab,\n                           lapack_int ldab, const double* afb, lapack_int ldafb,\n                           const double* b, lapack_int ldb, double* x,\n                           lapack_int ldx, double* ferr, double* berr );\nlapack_int LAPACKE_cpbrfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs,\n                           const lapack_complex_float* ab, lapack_int ldab,\n                           const lapack_complex_float* afb, lapack_int ldafb,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zpbrfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs,\n                           const lapack_complex_double* ab, lapack_int ldab,\n                           const lapack_complex_double* afb, lapack_int ldafb,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_spbstf( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kb, float* bb, lapack_int ldbb );\nlapack_int LAPACKE_dpbstf( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kb, double* bb, lapack_int ldbb );\nlapack_int LAPACKE_cpbstf( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kb, lapack_complex_float* bb,\n                           lapack_int ldbb );\nlapack_int LAPACKE_zpbstf( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kb, lapack_complex_double* bb,\n                           lapack_int ldbb );\n\nlapack_int LAPACKE_spbsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int kd, lapack_int nrhs, float* ab,\n                          lapack_int ldab, float* b, lapack_int ldb );\nlapack_int LAPACKE_dpbsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int kd, lapack_int nrhs, double* ab,\n                          lapack_int ldab, double* b, lapack_int ldb );\nlapack_int LAPACKE_cpbsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int kd, lapack_int nrhs,\n                          lapack_complex_float* ab, lapack_int ldab,\n                          lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zpbsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int kd, lapack_int nrhs,\n                          lapack_complex_double* ab, lapack_int ldab,\n                          lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_spbsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs, float* ab,\n                           lapack_int ldab, float* afb, lapack_int ldafb,\n                           char* equed, float* s, float* b, lapack_int ldb,\n                           float* x, lapack_int ldx, float* rcond, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_dpbsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs, double* ab,\n                           lapack_int ldab, double* afb, lapack_int ldafb,\n                           char* equed, double* s, double* b, lapack_int ldb,\n                           double* x, lapack_int ldx, double* rcond,\n                           double* ferr, double* berr );\nlapack_int LAPACKE_cpbsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs,\n                           lapack_complex_float* ab, lapack_int ldab,\n                           lapack_complex_float* afb, lapack_int ldafb,\n                           char* equed, float* s, lapack_complex_float* b,\n                           lapack_int ldb, lapack_complex_float* x,\n                           lapack_int ldx, float* rcond, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zpbsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs,\n                           lapack_complex_double* ab, lapack_int ldab,\n                           lapack_complex_double* afb, lapack_int ldafb,\n                           char* equed, double* s, lapack_complex_double* b,\n                           lapack_int ldb, lapack_complex_double* x,\n                           lapack_int ldx, double* rcond, double* ferr,\n                           double* berr );\n\nlapack_int LAPACKE_spbtrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, float* ab, lapack_int ldab );\nlapack_int LAPACKE_dpbtrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, double* ab, lapack_int ldab );\nlapack_int LAPACKE_cpbtrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, lapack_complex_float* ab,\n                           lapack_int ldab );\nlapack_int LAPACKE_zpbtrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, lapack_complex_double* ab,\n                           lapack_int ldab );\n\nlapack_int LAPACKE_spbtrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs, const float* ab,\n                           lapack_int ldab, float* b, lapack_int ldb );\nlapack_int LAPACKE_dpbtrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs, const double* ab,\n                           lapack_int ldab, double* b, lapack_int ldb );\nlapack_int LAPACKE_cpbtrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs,\n                           const lapack_complex_float* ab, lapack_int ldab,\n                           lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zpbtrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int kd, lapack_int nrhs,\n                           const lapack_complex_double* ab, lapack_int ldab,\n                           lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_spftrf( int matrix_order, char transr, char uplo,\n                           lapack_int n, float* a );\nlapack_int LAPACKE_dpftrf( int matrix_order, char transr, char uplo,\n                           lapack_int n, double* a );\nlapack_int LAPACKE_cpftrf( int matrix_order, char transr, char uplo,\n                           lapack_int n, lapack_complex_float* a );\nlapack_int LAPACKE_zpftrf( int matrix_order, char transr, char uplo,\n                           lapack_int n, lapack_complex_double* a );\n\nlapack_int LAPACKE_spftri( int matrix_order, char transr, char uplo,\n                           lapack_int n, float* a );\nlapack_int LAPACKE_dpftri( int matrix_order, char transr, char uplo,\n                           lapack_int n, double* a );\nlapack_int LAPACKE_cpftri( int matrix_order, char transr, char uplo,\n                           lapack_int n, lapack_complex_float* a );\nlapack_int LAPACKE_zpftri( int matrix_order, char transr, char uplo,\n                           lapack_int n, lapack_complex_double* a );\n\nlapack_int LAPACKE_spftrs( int matrix_order, char transr, char uplo,\n                           lapack_int n, lapack_int nrhs, const float* a,\n                           float* b, lapack_int ldb );\nlapack_int LAPACKE_dpftrs( int matrix_order, char transr, char uplo,\n                           lapack_int n, lapack_int nrhs, const double* a,\n                           double* b, lapack_int ldb );\nlapack_int LAPACKE_cpftrs( int matrix_order, char transr, char uplo,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_float* a,\n                           lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zpftrs( int matrix_order, char transr, char uplo,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_double* a,\n                           lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_spocon( int matrix_order, char uplo, lapack_int n,\n                           const float* a, lapack_int lda, float anorm,\n                           float* rcond );\nlapack_int LAPACKE_dpocon( int matrix_order, char uplo, lapack_int n,\n                           const double* a, lapack_int lda, double anorm,\n                           double* rcond );\nlapack_int LAPACKE_cpocon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           float anorm, float* rcond );\nlapack_int LAPACKE_zpocon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           double anorm, double* rcond );\n\nlapack_int LAPACKE_spoequ( int matrix_order, lapack_int n, const float* a,\n                           lapack_int lda, float* s, float* scond,\n                           float* amax );\nlapack_int LAPACKE_dpoequ( int matrix_order, lapack_int n, const double* a,\n                           lapack_int lda, double* s, double* scond,\n                           double* amax );\nlapack_int LAPACKE_cpoequ( int matrix_order, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           float* s, float* scond, float* amax );\nlapack_int LAPACKE_zpoequ( int matrix_order, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           double* s, double* scond, double* amax );\n\nlapack_int LAPACKE_spoequb( int matrix_order, lapack_int n, const float* a,\n                            lapack_int lda, float* s, float* scond,\n                            float* amax );\nlapack_int LAPACKE_dpoequb( int matrix_order, lapack_int n, const double* a,\n                            lapack_int lda, double* s, double* scond,\n                            double* amax );\nlapack_int LAPACKE_cpoequb( int matrix_order, lapack_int n,\n                            const lapack_complex_float* a, lapack_int lda,\n                            float* s, float* scond, float* amax );\nlapack_int LAPACKE_zpoequb( int matrix_order, lapack_int n,\n                            const lapack_complex_double* a, lapack_int lda,\n                            double* s, double* scond, double* amax );\n\nlapack_int LAPACKE_sporfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* a, lapack_int lda,\n                           const float* af, lapack_int ldaf, const float* b,\n                           lapack_int ldb, float* x, lapack_int ldx,\n                           float* ferr, float* berr );\nlapack_int LAPACKE_dporfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* a, lapack_int lda,\n                           const double* af, lapack_int ldaf, const double* b,\n                           lapack_int ldb, double* x, lapack_int ldx,\n                           double* ferr, double* berr );\nlapack_int LAPACKE_cporfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* af,\n                           lapack_int ldaf, const lapack_complex_float* b,\n                           lapack_int ldb, lapack_complex_float* x,\n                           lapack_int ldx, float* ferr, float* berr );\nlapack_int LAPACKE_zporfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* af,\n                           lapack_int ldaf, const lapack_complex_double* b,\n                           lapack_int ldb, lapack_complex_double* x,\n                           lapack_int ldx, double* ferr, double* berr );\n\nlapack_int LAPACKE_sporfsx( int matrix_order, char uplo, char equed,\n                            lapack_int n, lapack_int nrhs, const float* a,\n                            lapack_int lda, const float* af, lapack_int ldaf,\n                            const float* s, const float* b, lapack_int ldb,\n                            float* x, lapack_int ldx, float* rcond, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_dporfsx( int matrix_order, char uplo, char equed,\n                            lapack_int n, lapack_int nrhs, const double* a,\n                            lapack_int lda, const double* af, lapack_int ldaf,\n                            const double* s, const double* b, lapack_int ldb,\n                            double* x, lapack_int ldx, double* rcond,\n                            double* berr, lapack_int n_err_bnds,\n                            double* err_bnds_norm, double* err_bnds_comp,\n                            lapack_int nparams, double* params );\nlapack_int LAPACKE_cporfsx( int matrix_order, char uplo, char equed,\n                            lapack_int n, lapack_int nrhs,\n                            const lapack_complex_float* a, lapack_int lda,\n                            const lapack_complex_float* af, lapack_int ldaf,\n                            const float* s, const lapack_complex_float* b,\n                            lapack_int ldb, lapack_complex_float* x,\n                            lapack_int ldx, float* rcond, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_zporfsx( int matrix_order, char uplo, char equed,\n                            lapack_int n, lapack_int nrhs,\n                            const lapack_complex_double* a, lapack_int lda,\n                            const lapack_complex_double* af, lapack_int ldaf,\n                            const double* s, const lapack_complex_double* b,\n                            lapack_int ldb, lapack_complex_double* x,\n                            lapack_int ldx, double* rcond, double* berr,\n                            lapack_int n_err_bnds, double* err_bnds_norm,\n                            double* err_bnds_comp, lapack_int nparams,\n                            double* params );\n\nlapack_int LAPACKE_sposv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, float* a, lapack_int lda, float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_dposv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, double* a, lapack_int lda, double* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_cposv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_float* a,\n                          lapack_int lda, lapack_complex_float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_zposv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_double* a,\n                          lapack_int lda, lapack_complex_double* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_dsposv( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, double* a, lapack_int lda,\n                           double* b, lapack_int ldb, double* x, lapack_int ldx,\n                           lapack_int* iter );\nlapack_int LAPACKE_zcposv( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb, lapack_complex_double* x,\n                           lapack_int ldx, lapack_int* iter );\n\nlapack_int LAPACKE_sposvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, float* a, lapack_int lda, float* af,\n                           lapack_int ldaf, char* equed, float* s, float* b,\n                           lapack_int ldb, float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr );\nlapack_int LAPACKE_dposvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, double* a, lapack_int lda,\n                           double* af, lapack_int ldaf, char* equed, double* s,\n                           double* b, lapack_int ldb, double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr );\nlapack_int LAPACKE_cposvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* af,\n                           lapack_int ldaf, char* equed, float* s,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr );\nlapack_int LAPACKE_zposvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* af,\n                           lapack_int ldaf, char* equed, double* s,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr );\n\nlapack_int LAPACKE_sposvxx( int matrix_order, char fact, char uplo,\n                            lapack_int n, lapack_int nrhs, float* a,\n                            lapack_int lda, float* af, lapack_int ldaf,\n                            char* equed, float* s, float* b, lapack_int ldb,\n                            float* x, lapack_int ldx, float* rcond,\n                            float* rpvgrw, float* berr, lapack_int n_err_bnds,\n                            float* err_bnds_norm, float* err_bnds_comp,\n                            lapack_int nparams, float* params );\nlapack_int LAPACKE_dposvxx( int matrix_order, char fact, char uplo,\n                            lapack_int n, lapack_int nrhs, double* a,\n                            lapack_int lda, double* af, lapack_int ldaf,\n                            char* equed, double* s, double* b, lapack_int ldb,\n                            double* x, lapack_int ldx, double* rcond,\n                            double* rpvgrw, double* berr, lapack_int n_err_bnds,\n                            double* err_bnds_norm, double* err_bnds_comp,\n                            lapack_int nparams, double* params );\nlapack_int LAPACKE_cposvxx( int matrix_order, char fact, char uplo,\n                            lapack_int n, lapack_int nrhs,\n                            lapack_complex_float* a, lapack_int lda,\n                            lapack_complex_float* af, lapack_int ldaf,\n                            char* equed, float* s, lapack_complex_float* b,\n                            lapack_int ldb, lapack_complex_float* x,\n                            lapack_int ldx, float* rcond, float* rpvgrw,\n                            float* berr, lapack_int n_err_bnds,\n                            float* err_bnds_norm, float* err_bnds_comp,\n                            lapack_int nparams, float* params );\nlapack_int LAPACKE_zposvxx( int matrix_order, char fact, char uplo,\n                            lapack_int n, lapack_int nrhs,\n                            lapack_complex_double* a, lapack_int lda,\n                            lapack_complex_double* af, lapack_int ldaf,\n                            char* equed, double* s, lapack_complex_double* b,\n                            lapack_int ldb, lapack_complex_double* x,\n                            lapack_int ldx, double* rcond, double* rpvgrw,\n                            double* berr, lapack_int n_err_bnds,\n                            double* err_bnds_norm, double* err_bnds_comp,\n                            lapack_int nparams, double* params );\n\nlapack_int LAPACKE_spotrf( int matrix_order, char uplo, lapack_int n, float* a,\n                           lapack_int lda );\nlapack_int LAPACKE_dpotrf( int matrix_order, char uplo, lapack_int n, double* a,\n                           lapack_int lda );\nlapack_int LAPACKE_cpotrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_zpotrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_spotri( int matrix_order, char uplo, lapack_int n, float* a,\n                           lapack_int lda );\nlapack_int LAPACKE_dpotri( int matrix_order, char uplo, lapack_int n, double* a,\n                           lapack_int lda );\nlapack_int LAPACKE_cpotri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_zpotri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_spotrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* a, lapack_int lda,\n                           float* b, lapack_int ldb );\nlapack_int LAPACKE_dpotrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* a, lapack_int lda,\n                           double* b, lapack_int ldb );\nlapack_int LAPACKE_cpotrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_zpotrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb );\n\nlapack_int LAPACKE_sppcon( int matrix_order, char uplo, lapack_int n,\n                           const float* ap, float anorm, float* rcond );\nlapack_int LAPACKE_dppcon( int matrix_order, char uplo, lapack_int n,\n                           const double* ap, double anorm, double* rcond );\nlapack_int LAPACKE_cppcon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_float* ap, float anorm,\n                           float* rcond );\nlapack_int LAPACKE_zppcon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_double* ap, double anorm,\n                           double* rcond );\n\nlapack_int LAPACKE_sppequ( int matrix_order, char uplo, lapack_int n,\n                           const float* ap, float* s, float* scond,\n                           float* amax );\nlapack_int LAPACKE_dppequ( int matrix_order, char uplo, lapack_int n,\n                           const double* ap, double* s, double* scond,\n                           double* amax );\nlapack_int LAPACKE_cppequ( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_float* ap, float* s,\n                           float* scond, float* amax );\nlapack_int LAPACKE_zppequ( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_double* ap, double* s,\n                           double* scond, double* amax );\n\nlapack_int LAPACKE_spprfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* ap, const float* afp,\n                           const float* b, lapack_int ldb, float* x,\n                           lapack_int ldx, float* ferr, float* berr );\nlapack_int LAPACKE_dpprfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* ap, const double* afp,\n                           const double* b, lapack_int ldb, double* x,\n                           lapack_int ldx, double* ferr, double* berr );\nlapack_int LAPACKE_cpprfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* ap,\n                           const lapack_complex_float* afp,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zpprfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* ap,\n                           const lapack_complex_double* afp,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_sppsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, float* ap, float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_dppsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, double* ap, double* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_cppsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_float* ap,\n                          lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zppsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_double* ap,\n                          lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_sppsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, float* ap, float* afp, char* equed,\n                           float* s, float* b, lapack_int ldb, float* x,\n                           lapack_int ldx, float* rcond, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_dppsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, double* ap, double* afp,\n                           char* equed, double* s, double* b, lapack_int ldb,\n                           double* x, lapack_int ldx, double* rcond,\n                           double* ferr, double* berr );\nlapack_int LAPACKE_cppsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, lapack_complex_float* ap,\n                           lapack_complex_float* afp, char* equed, float* s,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr );\nlapack_int LAPACKE_zppsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, lapack_complex_double* ap,\n                           lapack_complex_double* afp, char* equed, double* s,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr );\n\nlapack_int LAPACKE_spptrf( int matrix_order, char uplo, lapack_int n,\n                           float* ap );\nlapack_int LAPACKE_dpptrf( int matrix_order, char uplo, lapack_int n,\n                           double* ap );\nlapack_int LAPACKE_cpptrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* ap );\nlapack_int LAPACKE_zpptrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* ap );\n\nlapack_int LAPACKE_spptri( int matrix_order, char uplo, lapack_int n,\n                           float* ap );\nlapack_int LAPACKE_dpptri( int matrix_order, char uplo, lapack_int n,\n                           double* ap );\nlapack_int LAPACKE_cpptri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* ap );\nlapack_int LAPACKE_zpptri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* ap );\n\nlapack_int LAPACKE_spptrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* ap, float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_dpptrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* ap, double* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_cpptrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* ap,\n                           lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zpptrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* ap,\n                           lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_spstrf( int matrix_order, char uplo, lapack_int n, float* a,\n                           lapack_int lda, lapack_int* piv, lapack_int* rank,\n                           float tol );\nlapack_int LAPACKE_dpstrf( int matrix_order, char uplo, lapack_int n, double* a,\n                           lapack_int lda, lapack_int* piv, lapack_int* rank,\n                           double tol );\nlapack_int LAPACKE_cpstrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int* piv, lapack_int* rank, float tol );\nlapack_int LAPACKE_zpstrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* piv, lapack_int* rank, double tol );\n\nlapack_int LAPACKE_sptcon( lapack_int n, const float* d, const float* e,\n                           float anorm, float* rcond );\nlapack_int LAPACKE_dptcon( lapack_int n, const double* d, const double* e,\n                           double anorm, double* rcond );\nlapack_int LAPACKE_cptcon( lapack_int n, const float* d,\n                           const lapack_complex_float* e, float anorm,\n                           float* rcond );\nlapack_int LAPACKE_zptcon( lapack_int n, const double* d,\n                           const lapack_complex_double* e, double anorm,\n                           double* rcond );\n\nlapack_int LAPACKE_spteqr( int matrix_order, char compz, lapack_int n, float* d,\n                           float* e, float* z, lapack_int ldz );\nlapack_int LAPACKE_dpteqr( int matrix_order, char compz, lapack_int n,\n                           double* d, double* e, double* z, lapack_int ldz );\nlapack_int LAPACKE_cpteqr( int matrix_order, char compz, lapack_int n, float* d,\n                           float* e, lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zpteqr( int matrix_order, char compz, lapack_int n,\n                           double* d, double* e, lapack_complex_double* z,\n                           lapack_int ldz );\n\nlapack_int LAPACKE_sptrfs( int matrix_order, lapack_int n, lapack_int nrhs,\n                           const float* d, const float* e, const float* df,\n                           const float* ef, const float* b, lapack_int ldb,\n                           float* x, lapack_int ldx, float* ferr, float* berr );\nlapack_int LAPACKE_dptrfs( int matrix_order, lapack_int n, lapack_int nrhs,\n                           const double* d, const double* e, const double* df,\n                           const double* ef, const double* b, lapack_int ldb,\n                           double* x, lapack_int ldx, double* ferr,\n                           double* berr );\nlapack_int LAPACKE_cptrfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* d,\n                           const lapack_complex_float* e, const float* df,\n                           const lapack_complex_float* ef,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zptrfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* d,\n                           const lapack_complex_double* e, const double* df,\n                           const lapack_complex_double* ef,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_sptsv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          float* d, float* e, float* b, lapack_int ldb );\nlapack_int LAPACKE_dptsv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          double* d, double* e, double* b, lapack_int ldb );\nlapack_int LAPACKE_cptsv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          float* d, lapack_complex_float* e,\n                          lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zptsv( int matrix_order, lapack_int n, lapack_int nrhs,\n                          double* d, lapack_complex_double* e,\n                          lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_sptsvx( int matrix_order, char fact, lapack_int n,\n                           lapack_int nrhs, const float* d, const float* e,\n                           float* df, float* ef, const float* b, lapack_int ldb,\n                           float* x, lapack_int ldx, float* rcond, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_dptsvx( int matrix_order, char fact, lapack_int n,\n                           lapack_int nrhs, const double* d, const double* e,\n                           double* df, double* ef, const double* b,\n                           lapack_int ldb, double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr );\nlapack_int LAPACKE_cptsvx( int matrix_order, char fact, lapack_int n,\n                           lapack_int nrhs, const float* d,\n                           const lapack_complex_float* e, float* df,\n                           lapack_complex_float* ef,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr );\nlapack_int LAPACKE_zptsvx( int matrix_order, char fact, lapack_int n,\n                           lapack_int nrhs, const double* d,\n                           const lapack_complex_double* e, double* df,\n                           lapack_complex_double* ef,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr );\n\nlapack_int LAPACKE_spttrf( lapack_int n, float* d, float* e );\nlapack_int LAPACKE_dpttrf( lapack_int n, double* d, double* e );\nlapack_int LAPACKE_cpttrf( lapack_int n, float* d, lapack_complex_float* e );\nlapack_int LAPACKE_zpttrf( lapack_int n, double* d, lapack_complex_double* e );\n\nlapack_int LAPACKE_spttrs( int matrix_order, lapack_int n, lapack_int nrhs,\n                           const float* d, const float* e, float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_dpttrs( int matrix_order, lapack_int n, lapack_int nrhs,\n                           const double* d, const double* e, double* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_cpttrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* d,\n                           const lapack_complex_float* e,\n                           lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zpttrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* d,\n                           const lapack_complex_double* e,\n                           lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_ssbev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_int kd, float* ab, lapack_int ldab, float* w,\n                          float* z, lapack_int ldz );\nlapack_int LAPACKE_dsbev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_int kd, double* ab, lapack_int ldab, double* w,\n                          double* z, lapack_int ldz );\n\nlapack_int LAPACKE_ssbevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_int kd, float* ab, lapack_int ldab, float* w,\n                           float* z, lapack_int ldz );\nlapack_int LAPACKE_dsbevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_int kd, double* ab, lapack_int ldab,\n                           double* w, double* z, lapack_int ldz );\n\nlapack_int LAPACKE_ssbevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_int kd, float* ab,\n                           lapack_int ldab, float* q, lapack_int ldq, float vl,\n                           float vu, lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, float* z, lapack_int ldz,\n                           lapack_int* ifail );\nlapack_int LAPACKE_dsbevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_int kd, double* ab,\n                           lapack_int ldab, double* q, lapack_int ldq,\n                           double vl, double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w, double* z,\n                           lapack_int ldz, lapack_int* ifail );\n\nlapack_int LAPACKE_ssbgst( int matrix_order, char vect, char uplo, lapack_int n,\n                           lapack_int ka, lapack_int kb, float* ab,\n                           lapack_int ldab, const float* bb, lapack_int ldbb,\n                           float* x, lapack_int ldx );\nlapack_int LAPACKE_dsbgst( int matrix_order, char vect, char uplo, lapack_int n,\n                           lapack_int ka, lapack_int kb, double* ab,\n                           lapack_int ldab, const double* bb, lapack_int ldbb,\n                           double* x, lapack_int ldx );\n\nlapack_int LAPACKE_ssbgv( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_int ka, lapack_int kb, float* ab,\n                          lapack_int ldab, float* bb, lapack_int ldbb, float* w,\n                          float* z, lapack_int ldz );\nlapack_int LAPACKE_dsbgv( int matrix_order, char jobz, char uplo, lapack_int n,\n                          lapack_int ka, lapack_int kb, double* ab,\n                          lapack_int ldab, double* bb, lapack_int ldbb,\n                          double* w, double* z, lapack_int ldz );\n\nlapack_int LAPACKE_ssbgvd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_int ka, lapack_int kb, float* ab,\n                           lapack_int ldab, float* bb, lapack_int ldbb,\n                           float* w, float* z, lapack_int ldz );\nlapack_int LAPACKE_dsbgvd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           lapack_int ka, lapack_int kb, double* ab,\n                           lapack_int ldab, double* bb, lapack_int ldbb,\n                           double* w, double* z, lapack_int ldz );\n\nlapack_int LAPACKE_ssbgvx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_int ka, lapack_int kb,\n                           float* ab, lapack_int ldab, float* bb,\n                           lapack_int ldbb, float* q, lapack_int ldq, float vl,\n                           float vu, lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, float* z, lapack_int ldz,\n                           lapack_int* ifail );\nlapack_int LAPACKE_dsbgvx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, lapack_int ka, lapack_int kb,\n                           double* ab, lapack_int ldab, double* bb,\n                           lapack_int ldbb, double* q, lapack_int ldq,\n                           double vl, double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w, double* z,\n                           lapack_int ldz, lapack_int* ifail );\n\nlapack_int LAPACKE_ssbtrd( int matrix_order, char vect, char uplo, lapack_int n,\n                           lapack_int kd, float* ab, lapack_int ldab, float* d,\n                           float* e, float* q, lapack_int ldq );\nlapack_int LAPACKE_dsbtrd( int matrix_order, char vect, char uplo, lapack_int n,\n                           lapack_int kd, double* ab, lapack_int ldab,\n                           double* d, double* e, double* q, lapack_int ldq );\n\nlapack_int LAPACKE_ssfrk( int matrix_order, char transr, char uplo, char trans,\n                          lapack_int n, lapack_int k, float alpha,\n                          const float* a, lapack_int lda, float beta,\n                          float* c );\nlapack_int LAPACKE_dsfrk( int matrix_order, char transr, char uplo, char trans,\n                          lapack_int n, lapack_int k, double alpha,\n                          const double* a, lapack_int lda, double beta,\n                          double* c );\n\nlapack_int LAPACKE_sspcon( int matrix_order, char uplo, lapack_int n,\n                           const float* ap, const lapack_int* ipiv, float anorm,\n                           float* rcond );\nlapack_int LAPACKE_dspcon( int matrix_order, char uplo, lapack_int n,\n                           const double* ap, const lapack_int* ipiv,\n                           double anorm, double* rcond );\nlapack_int LAPACKE_cspcon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_float* ap,\n                           const lapack_int* ipiv, float anorm, float* rcond );\nlapack_int LAPACKE_zspcon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_double* ap,\n                           const lapack_int* ipiv, double anorm,\n                           double* rcond );\n\nlapack_int LAPACKE_sspev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          float* ap, float* w, float* z, lapack_int ldz );\nlapack_int LAPACKE_dspev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          double* ap, double* w, double* z, lapack_int ldz );\n\nlapack_int LAPACKE_sspevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           float* ap, float* w, float* z, lapack_int ldz );\nlapack_int LAPACKE_dspevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           double* ap, double* w, double* z, lapack_int ldz );\n\nlapack_int LAPACKE_sspevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, float* ap, float vl, float vu,\n                           lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, float* z, lapack_int ldz,\n                           lapack_int* ifail );\nlapack_int LAPACKE_dspevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, double* ap, double vl, double vu,\n                           lapack_int il, lapack_int iu, double abstol,\n                           lapack_int* m, double* w, double* z, lapack_int ldz,\n                           lapack_int* ifail );\n\nlapack_int LAPACKE_sspgst( int matrix_order, lapack_int itype, char uplo,\n                           lapack_int n, float* ap, const float* bp );\nlapack_int LAPACKE_dspgst( int matrix_order, lapack_int itype, char uplo,\n                           lapack_int n, double* ap, const double* bp );\n\nlapack_int LAPACKE_sspgv( int matrix_order, lapack_int itype, char jobz,\n                          char uplo, lapack_int n, float* ap, float* bp,\n                          float* w, float* z, lapack_int ldz );\nlapack_int LAPACKE_dspgv( int matrix_order, lapack_int itype, char jobz,\n                          char uplo, lapack_int n, double* ap, double* bp,\n                          double* w, double* z, lapack_int ldz );\n\nlapack_int LAPACKE_sspgvd( int matrix_order, lapack_int itype, char jobz,\n                           char uplo, lapack_int n, float* ap, float* bp,\n                           float* w, float* z, lapack_int ldz );\nlapack_int LAPACKE_dspgvd( int matrix_order, lapack_int itype, char jobz,\n                           char uplo, lapack_int n, double* ap, double* bp,\n                           double* w, double* z, lapack_int ldz );\n\nlapack_int LAPACKE_sspgvx( int matrix_order, lapack_int itype, char jobz,\n                           char range, char uplo, lapack_int n, float* ap,\n                           float* bp, float vl, float vu, lapack_int il,\n                           lapack_int iu, float abstol, lapack_int* m, float* w,\n                           float* z, lapack_int ldz, lapack_int* ifail );\nlapack_int LAPACKE_dspgvx( int matrix_order, lapack_int itype, char jobz,\n                           char range, char uplo, lapack_int n, double* ap,\n                           double* bp, double vl, double vu, lapack_int il,\n                           lapack_int iu, double abstol, lapack_int* m,\n                           double* w, double* z, lapack_int ldz,\n                           lapack_int* ifail );\n\nlapack_int LAPACKE_ssprfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* ap, const float* afp,\n                           const lapack_int* ipiv, const float* b,\n                           lapack_int ldb, float* x, lapack_int ldx,\n                           float* ferr, float* berr );\nlapack_int LAPACKE_dsprfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* ap, const double* afp,\n                           const lapack_int* ipiv, const double* b,\n                           lapack_int ldb, double* x, lapack_int ldx,\n                           double* ferr, double* berr );\nlapack_int LAPACKE_csprfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* ap,\n                           const lapack_complex_float* afp,\n                           const lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zsprfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* ap,\n                           const lapack_complex_double* afp,\n                           const lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_sspsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, float* ap, lapack_int* ipiv,\n                          float* b, lapack_int ldb );\nlapack_int LAPACKE_dspsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, double* ap, lapack_int* ipiv,\n                          double* b, lapack_int ldb );\nlapack_int LAPACKE_cspsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_float* ap,\n                          lapack_int* ipiv, lapack_complex_float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_zspsv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_double* ap,\n                          lapack_int* ipiv, lapack_complex_double* b,\n                          lapack_int ldb );\n\nlapack_int LAPACKE_sspsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* ap, float* afp,\n                           lapack_int* ipiv, const float* b, lapack_int ldb,\n                           float* x, lapack_int ldx, float* rcond, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_dspsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* ap, double* afp,\n                           lapack_int* ipiv, const double* b, lapack_int ldb,\n                           double* x, lapack_int ldx, double* rcond,\n                           double* ferr, double* berr );\nlapack_int LAPACKE_cspsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* ap,\n                           lapack_complex_float* afp, lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr );\nlapack_int LAPACKE_zspsvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* ap,\n                           lapack_complex_double* afp, lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr );\n\nlapack_int LAPACKE_ssptrd( int matrix_order, char uplo, lapack_int n, float* ap,\n                           float* d, float* e, float* tau );\nlapack_int LAPACKE_dsptrd( int matrix_order, char uplo, lapack_int n,\n                           double* ap, double* d, double* e, double* tau );\n\nlapack_int LAPACKE_ssptrf( int matrix_order, char uplo, lapack_int n, float* ap,\n                           lapack_int* ipiv );\nlapack_int LAPACKE_dsptrf( int matrix_order, char uplo, lapack_int n,\n                           double* ap, lapack_int* ipiv );\nlapack_int LAPACKE_csptrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* ap, lapack_int* ipiv );\nlapack_int LAPACKE_zsptrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* ap, lapack_int* ipiv );\n\nlapack_int LAPACKE_ssptri( int matrix_order, char uplo, lapack_int n, float* ap,\n                           const lapack_int* ipiv );\nlapack_int LAPACKE_dsptri( int matrix_order, char uplo, lapack_int n,\n                           double* ap, const lapack_int* ipiv );\nlapack_int LAPACKE_csptri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* ap, const lapack_int* ipiv );\nlapack_int LAPACKE_zsptri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* ap, const lapack_int* ipiv );\n\nlapack_int LAPACKE_ssptrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* ap,\n                           const lapack_int* ipiv, float* b, lapack_int ldb );\nlapack_int LAPACKE_dsptrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* ap,\n                           const lapack_int* ipiv, double* b, lapack_int ldb );\nlapack_int LAPACKE_csptrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* ap,\n                           const lapack_int* ipiv, lapack_complex_float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_zsptrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* ap,\n                           const lapack_int* ipiv, lapack_complex_double* b,\n                           lapack_int ldb );\n\nlapack_int LAPACKE_sstebz( char range, char order, lapack_int n, float vl,\n                           float vu, lapack_int il, lapack_int iu, float abstol,\n                           const float* d, const float* e, lapack_int* m,\n                           lapack_int* nsplit, float* w, lapack_int* iblock,\n                           lapack_int* isplit );\nlapack_int LAPACKE_dstebz( char range, char order, lapack_int n, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, const double* d, const double* e,\n                           lapack_int* m, lapack_int* nsplit, double* w,\n                           lapack_int* iblock, lapack_int* isplit );\n\nlapack_int LAPACKE_sstedc( int matrix_order, char compz, lapack_int n, float* d,\n                           float* e, float* z, lapack_int ldz );\nlapack_int LAPACKE_dstedc( int matrix_order, char compz, lapack_int n,\n                           double* d, double* e, double* z, lapack_int ldz );\nlapack_int LAPACKE_cstedc( int matrix_order, char compz, lapack_int n, float* d,\n                           float* e, lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zstedc( int matrix_order, char compz, lapack_int n,\n                           double* d, double* e, lapack_complex_double* z,\n                           lapack_int ldz );\n\nlapack_int LAPACKE_sstegr( int matrix_order, char jobz, char range,\n                           lapack_int n, float* d, float* e, float vl, float vu,\n                           lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, float* z, lapack_int ldz,\n                           lapack_int* isuppz );\nlapack_int LAPACKE_dstegr( int matrix_order, char jobz, char range,\n                           lapack_int n, double* d, double* e, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w, double* z,\n                           lapack_int ldz, lapack_int* isuppz );\nlapack_int LAPACKE_cstegr( int matrix_order, char jobz, char range,\n                           lapack_int n, float* d, float* e, float vl, float vu,\n                           lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, lapack_complex_float* z,\n                           lapack_int ldz, lapack_int* isuppz );\nlapack_int LAPACKE_zstegr( int matrix_order, char jobz, char range,\n                           lapack_int n, double* d, double* e, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w,\n                           lapack_complex_double* z, lapack_int ldz,\n                           lapack_int* isuppz );\n\nlapack_int LAPACKE_sstein( int matrix_order, lapack_int n, const float* d,\n                           const float* e, lapack_int m, const float* w,\n                           const lapack_int* iblock, const lapack_int* isplit,\n                           float* z, lapack_int ldz, lapack_int* ifailv );\nlapack_int LAPACKE_dstein( int matrix_order, lapack_int n, const double* d,\n                           const double* e, lapack_int m, const double* w,\n                           const lapack_int* iblock, const lapack_int* isplit,\n                           double* z, lapack_int ldz, lapack_int* ifailv );\nlapack_int LAPACKE_cstein( int matrix_order, lapack_int n, const float* d,\n                           const float* e, lapack_int m, const float* w,\n                           const lapack_int* iblock, const lapack_int* isplit,\n                           lapack_complex_float* z, lapack_int ldz,\n                           lapack_int* ifailv );\nlapack_int LAPACKE_zstein( int matrix_order, lapack_int n, const double* d,\n                           const double* e, lapack_int m, const double* w,\n                           const lapack_int* iblock, const lapack_int* isplit,\n                           lapack_complex_double* z, lapack_int ldz,\n                           lapack_int* ifailv );\n\nlapack_int LAPACKE_sstemr( int matrix_order, char jobz, char range,\n                           lapack_int n, float* d, float* e, float vl, float vu,\n                           lapack_int il, lapack_int iu, lapack_int* m,\n                           float* w, float* z, lapack_int ldz, lapack_int nzc,\n                           lapack_int* isuppz, lapack_logical* tryrac );\nlapack_int LAPACKE_dstemr( int matrix_order, char jobz, char range,\n                           lapack_int n, double* d, double* e, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           lapack_int* m, double* w, double* z, lapack_int ldz,\n                           lapack_int nzc, lapack_int* isuppz,\n                           lapack_logical* tryrac );\nlapack_int LAPACKE_cstemr( int matrix_order, char jobz, char range,\n                           lapack_int n, float* d, float* e, float vl, float vu,\n                           lapack_int il, lapack_int iu, lapack_int* m,\n                           float* w, lapack_complex_float* z, lapack_int ldz,\n                           lapack_int nzc, lapack_int* isuppz,\n                           lapack_logical* tryrac );\nlapack_int LAPACKE_zstemr( int matrix_order, char jobz, char range,\n                           lapack_int n, double* d, double* e, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           lapack_int* m, double* w, lapack_complex_double* z,\n                           lapack_int ldz, lapack_int nzc, lapack_int* isuppz,\n                           lapack_logical* tryrac );\n\nlapack_int LAPACKE_ssteqr( int matrix_order, char compz, lapack_int n, float* d,\n                           float* e, float* z, lapack_int ldz );\nlapack_int LAPACKE_dsteqr( int matrix_order, char compz, lapack_int n,\n                           double* d, double* e, double* z, lapack_int ldz );\nlapack_int LAPACKE_csteqr( int matrix_order, char compz, lapack_int n, float* d,\n                           float* e, lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zsteqr( int matrix_order, char compz, lapack_int n,\n                           double* d, double* e, lapack_complex_double* z,\n                           lapack_int ldz );\n\nlapack_int LAPACKE_ssterf( lapack_int n, float* d, float* e );\nlapack_int LAPACKE_dsterf( lapack_int n, double* d, double* e );\n\nlapack_int LAPACKE_sstev( int matrix_order, char jobz, lapack_int n, float* d,\n                          float* e, float* z, lapack_int ldz );\nlapack_int LAPACKE_dstev( int matrix_order, char jobz, lapack_int n, double* d,\n                          double* e, double* z, lapack_int ldz );\n\nlapack_int LAPACKE_sstevd( int matrix_order, char jobz, lapack_int n, float* d,\n                           float* e, float* z, lapack_int ldz );\nlapack_int LAPACKE_dstevd( int matrix_order, char jobz, lapack_int n, double* d,\n                           double* e, double* z, lapack_int ldz );\n\nlapack_int LAPACKE_sstevr( int matrix_order, char jobz, char range,\n                           lapack_int n, float* d, float* e, float vl, float vu,\n                           lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, float* z, lapack_int ldz,\n                           lapack_int* isuppz );\nlapack_int LAPACKE_dstevr( int matrix_order, char jobz, char range,\n                           lapack_int n, double* d, double* e, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w, double* z,\n                           lapack_int ldz, lapack_int* isuppz );\n\nlapack_int LAPACKE_sstevx( int matrix_order, char jobz, char range,\n                           lapack_int n, float* d, float* e, float vl, float vu,\n                           lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, float* z, lapack_int ldz,\n                           lapack_int* ifail );\nlapack_int LAPACKE_dstevx( int matrix_order, char jobz, char range,\n                           lapack_int n, double* d, double* e, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w, double* z,\n                           lapack_int ldz, lapack_int* ifail );\n\nlapack_int LAPACKE_ssycon( int matrix_order, char uplo, lapack_int n,\n                           const float* a, lapack_int lda,\n                           const lapack_int* ipiv, float anorm, float* rcond );\nlapack_int LAPACKE_dsycon( int matrix_order, char uplo, lapack_int n,\n                           const double* a, lapack_int lda,\n                           const lapack_int* ipiv, double anorm,\n                           double* rcond );\nlapack_int LAPACKE_csycon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_int* ipiv, float anorm, float* rcond );\nlapack_int LAPACKE_zsycon( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_int* ipiv, double anorm,\n                           double* rcond );\n\nlapack_int LAPACKE_ssyequb( int matrix_order, char uplo, lapack_int n,\n                            const float* a, lapack_int lda, float* s,\n                            float* scond, float* amax );\nlapack_int LAPACKE_dsyequb( int matrix_order, char uplo, lapack_int n,\n                            const double* a, lapack_int lda, double* s,\n                            double* scond, double* amax );\nlapack_int LAPACKE_csyequb( int matrix_order, char uplo, lapack_int n,\n                            const lapack_complex_float* a, lapack_int lda,\n                            float* s, float* scond, float* amax );\nlapack_int LAPACKE_zsyequb( int matrix_order, char uplo, lapack_int n,\n                            const lapack_complex_double* a, lapack_int lda,\n                            double* s, double* scond, double* amax );\n\nlapack_int LAPACKE_ssyev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          float* a, lapack_int lda, float* w );\nlapack_int LAPACKE_dsyev( int matrix_order, char jobz, char uplo, lapack_int n,\n                          double* a, lapack_int lda, double* w );\n\nlapack_int LAPACKE_ssyevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           float* a, lapack_int lda, float* w );\nlapack_int LAPACKE_dsyevd( int matrix_order, char jobz, char uplo, lapack_int n,\n                           double* a, lapack_int lda, double* w );\n\nlapack_int LAPACKE_ssyevr( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, float* a, lapack_int lda, float vl,\n                           float vu, lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, float* z, lapack_int ldz,\n                           lapack_int* isuppz );\nlapack_int LAPACKE_dsyevr( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, double* a, lapack_int lda, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w, double* z,\n                           lapack_int ldz, lapack_int* isuppz );\n\nlapack_int LAPACKE_ssyevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, float* a, lapack_int lda, float vl,\n                           float vu, lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, float* z, lapack_int ldz,\n                           lapack_int* ifail );\nlapack_int LAPACKE_dsyevx( int matrix_order, char jobz, char range, char uplo,\n                           lapack_int n, double* a, lapack_int lda, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w, double* z,\n                           lapack_int ldz, lapack_int* ifail );\n\nlapack_int LAPACKE_ssygst( int matrix_order, lapack_int itype, char uplo,\n                           lapack_int n, float* a, lapack_int lda,\n                           const float* b, lapack_int ldb );\nlapack_int LAPACKE_dsygst( int matrix_order, lapack_int itype, char uplo,\n                           lapack_int n, double* a, lapack_int lda,\n                           const double* b, lapack_int ldb );\n\nlapack_int LAPACKE_ssygv( int matrix_order, lapack_int itype, char jobz,\n                          char uplo, lapack_int n, float* a, lapack_int lda,\n                          float* b, lapack_int ldb, float* w );\nlapack_int LAPACKE_dsygv( int matrix_order, lapack_int itype, char jobz,\n                          char uplo, lapack_int n, double* a, lapack_int lda,\n                          double* b, lapack_int ldb, double* w );\n\nlapack_int LAPACKE_ssygvd( int matrix_order, lapack_int itype, char jobz,\n                           char uplo, lapack_int n, float* a, lapack_int lda,\n                           float* b, lapack_int ldb, float* w );\nlapack_int LAPACKE_dsygvd( int matrix_order, lapack_int itype, char jobz,\n                           char uplo, lapack_int n, double* a, lapack_int lda,\n                           double* b, lapack_int ldb, double* w );\n\nlapack_int LAPACKE_ssygvx( int matrix_order, lapack_int itype, char jobz,\n                           char range, char uplo, lapack_int n, float* a,\n                           lapack_int lda, float* b, lapack_int ldb, float vl,\n                           float vu, lapack_int il, lapack_int iu, float abstol,\n                           lapack_int* m, float* w, float* z, lapack_int ldz,\n                           lapack_int* ifail );\nlapack_int LAPACKE_dsygvx( int matrix_order, lapack_int itype, char jobz,\n                           char range, char uplo, lapack_int n, double* a,\n                           lapack_int lda, double* b, lapack_int ldb, double vl,\n                           double vu, lapack_int il, lapack_int iu,\n                           double abstol, lapack_int* m, double* w, double* z,\n                           lapack_int ldz, lapack_int* ifail );\n\nlapack_int LAPACKE_ssyrfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* a, lapack_int lda,\n                           const float* af, lapack_int ldaf,\n                           const lapack_int* ipiv, const float* b,\n                           lapack_int ldb, float* x, lapack_int ldx,\n                           float* ferr, float* berr );\nlapack_int LAPACKE_dsyrfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* a, lapack_int lda,\n                           const double* af, lapack_int ldaf,\n                           const lapack_int* ipiv, const double* b,\n                           lapack_int ldb, double* x, lapack_int ldx,\n                           double* ferr, double* berr );\nlapack_int LAPACKE_csyrfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* af,\n                           lapack_int ldaf, const lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_zsyrfs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* af,\n                           lapack_int ldaf, const lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_ssyrfsx( int matrix_order, char uplo, char equed,\n                            lapack_int n, lapack_int nrhs, const float* a,\n                            lapack_int lda, const float* af, lapack_int ldaf,\n                            const lapack_int* ipiv, const float* s,\n                            const float* b, lapack_int ldb, float* x,\n                            lapack_int ldx, float* rcond, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_dsyrfsx( int matrix_order, char uplo, char equed,\n                            lapack_int n, lapack_int nrhs, const double* a,\n                            lapack_int lda, const double* af, lapack_int ldaf,\n                            const lapack_int* ipiv, const double* s,\n                            const double* b, lapack_int ldb, double* x,\n                            lapack_int ldx, double* rcond, double* berr,\n                            lapack_int n_err_bnds, double* err_bnds_norm,\n                            double* err_bnds_comp, lapack_int nparams,\n                            double* params );\nlapack_int LAPACKE_csyrfsx( int matrix_order, char uplo, char equed,\n                            lapack_int n, lapack_int nrhs,\n                            const lapack_complex_float* a, lapack_int lda,\n                            const lapack_complex_float* af, lapack_int ldaf,\n                            const lapack_int* ipiv, const float* s,\n                            const lapack_complex_float* b, lapack_int ldb,\n                            lapack_complex_float* x, lapack_int ldx,\n                            float* rcond, float* berr, lapack_int n_err_bnds,\n                            float* err_bnds_norm, float* err_bnds_comp,\n                            lapack_int nparams, float* params );\nlapack_int LAPACKE_zsyrfsx( int matrix_order, char uplo, char equed,\n                            lapack_int n, lapack_int nrhs,\n                            const lapack_complex_double* a, lapack_int lda,\n                            const lapack_complex_double* af, lapack_int ldaf,\n                            const lapack_int* ipiv, const double* s,\n                            const lapack_complex_double* b, lapack_int ldb,\n                            lapack_complex_double* x, lapack_int ldx,\n                            double* rcond, double* berr, lapack_int n_err_bnds,\n                            double* err_bnds_norm, double* err_bnds_comp,\n                            lapack_int nparams, double* params );\n\nlapack_int LAPACKE_ssysv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, float* a, lapack_int lda,\n                          lapack_int* ipiv, float* b, lapack_int ldb );\nlapack_int LAPACKE_dsysv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, double* a, lapack_int lda,\n                          lapack_int* ipiv, double* b, lapack_int ldb );\nlapack_int LAPACKE_csysv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_float* a,\n                          lapack_int lda, lapack_int* ipiv,\n                          lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zsysv( int matrix_order, char uplo, lapack_int n,\n                          lapack_int nrhs, lapack_complex_double* a,\n                          lapack_int lda, lapack_int* ipiv,\n                          lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_ssysvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* a, lapack_int lda,\n                           float* af, lapack_int ldaf, lapack_int* ipiv,\n                           const float* b, lapack_int ldb, float* x,\n                           lapack_int ldx, float* rcond, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_dsysvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* a, lapack_int lda,\n                           double* af, lapack_int ldaf, lapack_int* ipiv,\n                           const double* b, lapack_int ldb, double* x,\n                           lapack_int ldx, double* rcond, double* ferr,\n                           double* berr );\nlapack_int LAPACKE_csysvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* af,\n                           lapack_int ldaf, lapack_int* ipiv,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* x, lapack_int ldx,\n                           float* rcond, float* ferr, float* berr );\nlapack_int LAPACKE_zsysvx( int matrix_order, char fact, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* af,\n                           lapack_int ldaf, lapack_int* ipiv,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* x, lapack_int ldx,\n                           double* rcond, double* ferr, double* berr );\n\nlapack_int LAPACKE_ssysvxx( int matrix_order, char fact, char uplo,\n                            lapack_int n, lapack_int nrhs, float* a,\n                            lapack_int lda, float* af, lapack_int ldaf,\n                            lapack_int* ipiv, char* equed, float* s, float* b,\n                            lapack_int ldb, float* x, lapack_int ldx,\n                            float* rcond, float* rpvgrw, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_dsysvxx( int matrix_order, char fact, char uplo,\n                            lapack_int n, lapack_int nrhs, double* a,\n                            lapack_int lda, double* af, lapack_int ldaf,\n                            lapack_int* ipiv, char* equed, double* s, double* b,\n                            lapack_int ldb, double* x, lapack_int ldx,\n                            double* rcond, double* rpvgrw, double* berr,\n                            lapack_int n_err_bnds, double* err_bnds_norm,\n                            double* err_bnds_comp, lapack_int nparams,\n                            double* params );\nlapack_int LAPACKE_csysvxx( int matrix_order, char fact, char uplo,\n                            lapack_int n, lapack_int nrhs,\n                            lapack_complex_float* a, lapack_int lda,\n                            lapack_complex_float* af, lapack_int ldaf,\n                            lapack_int* ipiv, char* equed, float* s,\n                            lapack_complex_float* b, lapack_int ldb,\n                            lapack_complex_float* x, lapack_int ldx,\n                            float* rcond, float* rpvgrw, float* berr,\n                            lapack_int n_err_bnds, float* err_bnds_norm,\n                            float* err_bnds_comp, lapack_int nparams,\n                            float* params );\nlapack_int LAPACKE_zsysvxx( int matrix_order, char fact, char uplo,\n                            lapack_int n, lapack_int nrhs,\n                            lapack_complex_double* a, lapack_int lda,\n                            lapack_complex_double* af, lapack_int ldaf,\n                            lapack_int* ipiv, char* equed, double* s,\n                            lapack_complex_double* b, lapack_int ldb,\n                            lapack_complex_double* x, lapack_int ldx,\n                            double* rcond, double* rpvgrw, double* berr,\n                            lapack_int n_err_bnds, double* err_bnds_norm,\n                            double* err_bnds_comp, lapack_int nparams,\n                            double* params );\n\nlapack_int LAPACKE_ssytrd( int matrix_order, char uplo, lapack_int n, float* a,\n                           lapack_int lda, float* d, float* e, float* tau );\nlapack_int LAPACKE_dsytrd( int matrix_order, char uplo, lapack_int n, double* a,\n                           lapack_int lda, double* d, double* e, double* tau );\n\nlapack_int LAPACKE_ssytrf( int matrix_order, char uplo, lapack_int n, float* a,\n                           lapack_int lda, lapack_int* ipiv );\nlapack_int LAPACKE_dsytrf( int matrix_order, char uplo, lapack_int n, double* a,\n                           lapack_int lda, lapack_int* ipiv );\nlapack_int LAPACKE_csytrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_int* ipiv );\nlapack_int LAPACKE_zsytrf( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_int* ipiv );\n\nlapack_int LAPACKE_ssytri( int matrix_order, char uplo, lapack_int n, float* a,\n                           lapack_int lda, const lapack_int* ipiv );\nlapack_int LAPACKE_dsytri( int matrix_order, char uplo, lapack_int n, double* a,\n                           lapack_int lda, const lapack_int* ipiv );\nlapack_int LAPACKE_csytri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           const lapack_int* ipiv );\nlapack_int LAPACKE_zsytri( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           const lapack_int* ipiv );\n\nlapack_int LAPACKE_ssytrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const float* a, lapack_int lda,\n                           const lapack_int* ipiv, float* b, lapack_int ldb );\nlapack_int LAPACKE_dsytrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const double* a, lapack_int lda,\n                           const lapack_int* ipiv, double* b, lapack_int ldb );\nlapack_int LAPACKE_csytrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_float* a,\n                           lapack_int lda, const lapack_int* ipiv,\n                           lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zsytrs( int matrix_order, char uplo, lapack_int n,\n                           lapack_int nrhs, const lapack_complex_double* a,\n                           lapack_int lda, const lapack_int* ipiv,\n                           lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_stbcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, lapack_int kd, const float* ab,\n                           lapack_int ldab, float* rcond );\nlapack_int LAPACKE_dtbcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, lapack_int kd, const double* ab,\n                           lapack_int ldab, double* rcond );\nlapack_int LAPACKE_ctbcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, lapack_int kd,\n                           const lapack_complex_float* ab, lapack_int ldab,\n                           float* rcond );\nlapack_int LAPACKE_ztbcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, lapack_int kd,\n                           const lapack_complex_double* ab, lapack_int ldab,\n                           double* rcond );\n\nlapack_int LAPACKE_stbrfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int kd, lapack_int nrhs,\n                           const float* ab, lapack_int ldab, const float* b,\n                           lapack_int ldb, const float* x, lapack_int ldx,\n                           float* ferr, float* berr );\nlapack_int LAPACKE_dtbrfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int kd, lapack_int nrhs,\n                           const double* ab, lapack_int ldab, const double* b,\n                           lapack_int ldb, const double* x, lapack_int ldx,\n                           double* ferr, double* berr );\nlapack_int LAPACKE_ctbrfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int kd, lapack_int nrhs,\n                           const lapack_complex_float* ab, lapack_int ldab,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           const lapack_complex_float* x, lapack_int ldx,\n                           float* ferr, float* berr );\nlapack_int LAPACKE_ztbrfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int kd, lapack_int nrhs,\n                           const lapack_complex_double* ab, lapack_int ldab,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           const lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_stbtrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int kd, lapack_int nrhs,\n                           const float* ab, lapack_int ldab, float* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_dtbtrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int kd, lapack_int nrhs,\n                           const double* ab, lapack_int ldab, double* b,\n                           lapack_int ldb );\nlapack_int LAPACKE_ctbtrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int kd, lapack_int nrhs,\n                           const lapack_complex_float* ab, lapack_int ldab,\n                           lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_ztbtrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int kd, lapack_int nrhs,\n                           const lapack_complex_double* ab, lapack_int ldab,\n                           lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_stfsm( int matrix_order, char transr, char side, char uplo,\n                          char trans, char diag, lapack_int m, lapack_int n,\n                          float alpha, const float* a, float* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_dtfsm( int matrix_order, char transr, char side, char uplo,\n                          char trans, char diag, lapack_int m, lapack_int n,\n                          double alpha, const double* a, double* b,\n                          lapack_int ldb );\nlapack_int LAPACKE_ctfsm( int matrix_order, char transr, char side, char uplo,\n                          char trans, char diag, lapack_int m, lapack_int n,\n                          lapack_complex_float alpha,\n                          const lapack_complex_float* a,\n                          lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_ztfsm( int matrix_order, char transr, char side, char uplo,\n                          char trans, char diag, lapack_int m, lapack_int n,\n                          lapack_complex_double alpha,\n                          const lapack_complex_double* a,\n                          lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_stftri( int matrix_order, char transr, char uplo, char diag,\n                           lapack_int n, float* a );\nlapack_int LAPACKE_dtftri( int matrix_order, char transr, char uplo, char diag,\n                           lapack_int n, double* a );\nlapack_int LAPACKE_ctftri( int matrix_order, char transr, char uplo, char diag,\n                           lapack_int n, lapack_complex_float* a );\nlapack_int LAPACKE_ztftri( int matrix_order, char transr, char uplo, char diag,\n                           lapack_int n, lapack_complex_double* a );\n\nlapack_int LAPACKE_stfttp( int matrix_order, char transr, char uplo,\n                           lapack_int n, const float* arf, float* ap );\nlapack_int LAPACKE_dtfttp( int matrix_order, char transr, char uplo,\n                           lapack_int n, const double* arf, double* ap );\nlapack_int LAPACKE_ctfttp( int matrix_order, char transr, char uplo,\n                           lapack_int n, const lapack_complex_float* arf,\n                           lapack_complex_float* ap );\nlapack_int LAPACKE_ztfttp( int matrix_order, char transr, char uplo,\n                           lapack_int n, const lapack_complex_double* arf,\n                           lapack_complex_double* ap );\n\nlapack_int LAPACKE_stfttr( int matrix_order, char transr, char uplo,\n                           lapack_int n, const float* arf, float* a,\n                           lapack_int lda );\nlapack_int LAPACKE_dtfttr( int matrix_order, char transr, char uplo,\n                           lapack_int n, const double* arf, double* a,\n                           lapack_int lda );\nlapack_int LAPACKE_ctfttr( int matrix_order, char transr, char uplo,\n                           lapack_int n, const lapack_complex_float* arf,\n                           lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_ztfttr( int matrix_order, char transr, char uplo,\n                           lapack_int n, const lapack_complex_double* arf,\n                           lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_stgevc( int matrix_order, char side, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const float* s, lapack_int lds, const float* p,\n                           lapack_int ldp, float* vl, lapack_int ldvl,\n                           float* vr, lapack_int ldvr, lapack_int mm,\n                           lapack_int* m );\nlapack_int LAPACKE_dtgevc( int matrix_order, char side, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const double* s, lapack_int lds, const double* p,\n                           lapack_int ldp, double* vl, lapack_int ldvl,\n                           double* vr, lapack_int ldvr, lapack_int mm,\n                           lapack_int* m );\nlapack_int LAPACKE_ctgevc( int matrix_order, char side, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const lapack_complex_float* s, lapack_int lds,\n                           const lapack_complex_float* p, lapack_int ldp,\n                           lapack_complex_float* vl, lapack_int ldvl,\n                           lapack_complex_float* vr, lapack_int ldvr,\n                           lapack_int mm, lapack_int* m );\nlapack_int LAPACKE_ztgevc( int matrix_order, char side, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const lapack_complex_double* s, lapack_int lds,\n                           const lapack_complex_double* p, lapack_int ldp,\n                           lapack_complex_double* vl, lapack_int ldvl,\n                           lapack_complex_double* vr, lapack_int ldvr,\n                           lapack_int mm, lapack_int* m );\n\nlapack_int LAPACKE_stgexc( int matrix_order, lapack_logical wantq,\n                           lapack_logical wantz, lapack_int n, float* a,\n                           lapack_int lda, float* b, lapack_int ldb, float* q,\n                           lapack_int ldq, float* z, lapack_int ldz,\n                           lapack_int* ifst, lapack_int* ilst );\nlapack_int LAPACKE_dtgexc( int matrix_order, lapack_logical wantq,\n                           lapack_logical wantz, lapack_int n, double* a,\n                           lapack_int lda, double* b, lapack_int ldb, double* q,\n                           lapack_int ldq, double* z, lapack_int ldz,\n                           lapack_int* ifst, lapack_int* ilst );\nlapack_int LAPACKE_ctgexc( int matrix_order, lapack_logical wantq,\n                           lapack_logical wantz, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* q, lapack_int ldq,\n                           lapack_complex_float* z, lapack_int ldz,\n                           lapack_int ifst, lapack_int ilst );\nlapack_int LAPACKE_ztgexc( int matrix_order, lapack_logical wantq,\n                           lapack_logical wantz, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* q, lapack_int ldq,\n                           lapack_complex_double* z, lapack_int ldz,\n                           lapack_int ifst, lapack_int ilst );\n\nlapack_int LAPACKE_stgsen( int matrix_order, lapack_int ijob,\n                           lapack_logical wantq, lapack_logical wantz,\n                           const lapack_logical* select, lapack_int n, float* a,\n                           lapack_int lda, float* b, lapack_int ldb,\n                           float* alphar, float* alphai, float* beta, float* q,\n                           lapack_int ldq, float* z, lapack_int ldz,\n                           lapack_int* m, float* pl, float* pr, float* dif );\nlapack_int LAPACKE_dtgsen( int matrix_order, lapack_int ijob,\n                           lapack_logical wantq, lapack_logical wantz,\n                           const lapack_logical* select, lapack_int n,\n                           double* a, lapack_int lda, double* b, lapack_int ldb,\n                           double* alphar, double* alphai, double* beta,\n                           double* q, lapack_int ldq, double* z, lapack_int ldz,\n                           lapack_int* m, double* pl, double* pr, double* dif );\nlapack_int LAPACKE_ctgsen( int matrix_order, lapack_int ijob,\n                           lapack_logical wantq, lapack_logical wantz,\n                           const lapack_logical* select, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* alpha,\n                           lapack_complex_float* beta, lapack_complex_float* q,\n                           lapack_int ldq, lapack_complex_float* z,\n                           lapack_int ldz, lapack_int* m, float* pl, float* pr,\n                           float* dif );\nlapack_int LAPACKE_ztgsen( int matrix_order, lapack_int ijob,\n                           lapack_logical wantq, lapack_logical wantz,\n                           const lapack_logical* select, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* alpha,\n                           lapack_complex_double* beta,\n                           lapack_complex_double* q, lapack_int ldq,\n                           lapack_complex_double* z, lapack_int ldz,\n                           lapack_int* m, double* pl, double* pr, double* dif );\n\nlapack_int LAPACKE_stgsja( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int p, lapack_int n,\n                           lapack_int k, lapack_int l, float* a, lapack_int lda,\n                           float* b, lapack_int ldb, float tola, float tolb,\n                           float* alpha, float* beta, float* u, lapack_int ldu,\n                           float* v, lapack_int ldv, float* q, lapack_int ldq,\n                           lapack_int* ncycle );\nlapack_int LAPACKE_dtgsja( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int p, lapack_int n,\n                           lapack_int k, lapack_int l, double* a,\n                           lapack_int lda, double* b, lapack_int ldb,\n                           double tola, double tolb, double* alpha,\n                           double* beta, double* u, lapack_int ldu, double* v,\n                           lapack_int ldv, double* q, lapack_int ldq,\n                           lapack_int* ncycle );\nlapack_int LAPACKE_ctgsja( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int p, lapack_int n,\n                           lapack_int k, lapack_int l, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* b,\n                           lapack_int ldb, float tola, float tolb, float* alpha,\n                           float* beta, lapack_complex_float* u, lapack_int ldu,\n                           lapack_complex_float* v, lapack_int ldv,\n                           lapack_complex_float* q, lapack_int ldq,\n                           lapack_int* ncycle );\nlapack_int LAPACKE_ztgsja( int matrix_order, char jobu, char jobv, char jobq,\n                           lapack_int m, lapack_int p, lapack_int n,\n                           lapack_int k, lapack_int l, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* b,\n                           lapack_int ldb, double tola, double tolb,\n                           double* alpha, double* beta,\n                           lapack_complex_double* u, lapack_int ldu,\n                           lapack_complex_double* v, lapack_int ldv,\n                           lapack_complex_double* q, lapack_int ldq,\n                           lapack_int* ncycle );\n\nlapack_int LAPACKE_stgsna( int matrix_order, char job, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const float* a, lapack_int lda, const float* b,\n                           lapack_int ldb, const float* vl, lapack_int ldvl,\n                           const float* vr, lapack_int ldvr, float* s,\n                           float* dif, lapack_int mm, lapack_int* m );\nlapack_int LAPACKE_dtgsna( int matrix_order, char job, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const double* a, lapack_int lda, const double* b,\n                           lapack_int ldb, const double* vl, lapack_int ldvl,\n                           const double* vr, lapack_int ldvr, double* s,\n                           double* dif, lapack_int mm, lapack_int* m );\nlapack_int LAPACKE_ctgsna( int matrix_order, char job, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           const lapack_complex_float* vl, lapack_int ldvl,\n                           const lapack_complex_float* vr, lapack_int ldvr,\n                           float* s, float* dif, lapack_int mm, lapack_int* m );\nlapack_int LAPACKE_ztgsna( int matrix_order, char job, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           const lapack_complex_double* vl, lapack_int ldvl,\n                           const lapack_complex_double* vr, lapack_int ldvr,\n                           double* s, double* dif, lapack_int mm,\n                           lapack_int* m );\n\nlapack_int LAPACKE_stgsyl( int matrix_order, char trans, lapack_int ijob,\n                           lapack_int m, lapack_int n, const float* a,\n                           lapack_int lda, const float* b, lapack_int ldb,\n                           float* c, lapack_int ldc, const float* d,\n                           lapack_int ldd, const float* e, lapack_int lde,\n                           float* f, lapack_int ldf, float* scale, float* dif );\nlapack_int LAPACKE_dtgsyl( int matrix_order, char trans, lapack_int ijob,\n                           lapack_int m, lapack_int n, const double* a,\n                           lapack_int lda, const double* b, lapack_int ldb,\n                           double* c, lapack_int ldc, const double* d,\n                           lapack_int ldd, const double* e, lapack_int lde,\n                           double* f, lapack_int ldf, double* scale,\n                           double* dif );\nlapack_int LAPACKE_ctgsyl( int matrix_order, char trans, lapack_int ijob,\n                           lapack_int m, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* c, lapack_int ldc,\n                           const lapack_complex_float* d, lapack_int ldd,\n                           const lapack_complex_float* e, lapack_int lde,\n                           lapack_complex_float* f, lapack_int ldf,\n                           float* scale, float* dif );\nlapack_int LAPACKE_ztgsyl( int matrix_order, char trans, lapack_int ijob,\n                           lapack_int m, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* c, lapack_int ldc,\n                           const lapack_complex_double* d, lapack_int ldd,\n                           const lapack_complex_double* e, lapack_int lde,\n                           lapack_complex_double* f, lapack_int ldf,\n                           double* scale, double* dif );\n\nlapack_int LAPACKE_stpcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, const float* ap, float* rcond );\nlapack_int LAPACKE_dtpcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, const double* ap, double* rcond );\nlapack_int LAPACKE_ctpcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, const lapack_complex_float* ap,\n                           float* rcond );\nlapack_int LAPACKE_ztpcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, const lapack_complex_double* ap,\n                           double* rcond );\n\nlapack_int LAPACKE_stprfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs, const float* ap,\n                           const float* b, lapack_int ldb, const float* x,\n                           lapack_int ldx, float* ferr, float* berr );\nlapack_int LAPACKE_dtprfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs, const double* ap,\n                           const double* b, lapack_int ldb, const double* x,\n                           lapack_int ldx, double* ferr, double* berr );\nlapack_int LAPACKE_ctprfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_float* ap,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           const lapack_complex_float* x, lapack_int ldx,\n                           float* ferr, float* berr );\nlapack_int LAPACKE_ztprfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_double* ap,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           const lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_stptri( int matrix_order, char uplo, char diag, lapack_int n,\n                           float* ap );\nlapack_int LAPACKE_dtptri( int matrix_order, char uplo, char diag, lapack_int n,\n                           double* ap );\nlapack_int LAPACKE_ctptri( int matrix_order, char uplo, char diag, lapack_int n,\n                           lapack_complex_float* ap );\nlapack_int LAPACKE_ztptri( int matrix_order, char uplo, char diag, lapack_int n,\n                           lapack_complex_double* ap );\n\nlapack_int LAPACKE_stptrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs, const float* ap,\n                           float* b, lapack_int ldb );\nlapack_int LAPACKE_dtptrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs, const double* ap,\n                           double* b, lapack_int ldb );\nlapack_int LAPACKE_ctptrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_float* ap,\n                           lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_ztptrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_double* ap,\n                           lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_stpttf( int matrix_order, char transr, char uplo,\n                           lapack_int n, const float* ap, float* arf );\nlapack_int LAPACKE_dtpttf( int matrix_order, char transr, char uplo,\n                           lapack_int n, const double* ap, double* arf );\nlapack_int LAPACKE_ctpttf( int matrix_order, char transr, char uplo,\n                           lapack_int n, const lapack_complex_float* ap,\n                           lapack_complex_float* arf );\nlapack_int LAPACKE_ztpttf( int matrix_order, char transr, char uplo,\n                           lapack_int n, const lapack_complex_double* ap,\n                           lapack_complex_double* arf );\n\nlapack_int LAPACKE_stpttr( int matrix_order, char uplo, lapack_int n,\n                           const float* ap, float* a, lapack_int lda );\nlapack_int LAPACKE_dtpttr( int matrix_order, char uplo, lapack_int n,\n                           const double* ap, double* a, lapack_int lda );\nlapack_int LAPACKE_ctpttr( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_float* ap,\n                           lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_ztpttr( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_double* ap,\n                           lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_strcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, const float* a, lapack_int lda,\n                           float* rcond );\nlapack_int LAPACKE_dtrcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, const double* a, lapack_int lda,\n                           double* rcond );\nlapack_int LAPACKE_ctrcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, const lapack_complex_float* a,\n                           lapack_int lda, float* rcond );\nlapack_int LAPACKE_ztrcon( int matrix_order, char norm, char uplo, char diag,\n                           lapack_int n, const lapack_complex_double* a,\n                           lapack_int lda, double* rcond );\n\nlapack_int LAPACKE_strevc( int matrix_order, char side, char howmny,\n                           lapack_logical* select, lapack_int n, const float* t,\n                           lapack_int ldt, float* vl, lapack_int ldvl,\n                           float* vr, lapack_int ldvr, lapack_int mm,\n                           lapack_int* m );\nlapack_int LAPACKE_dtrevc( int matrix_order, char side, char howmny,\n                           lapack_logical* select, lapack_int n,\n                           const double* t, lapack_int ldt, double* vl,\n                           lapack_int ldvl, double* vr, lapack_int ldvr,\n                           lapack_int mm, lapack_int* m );\nlapack_int LAPACKE_ctrevc( int matrix_order, char side, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           lapack_complex_float* t, lapack_int ldt,\n                           lapack_complex_float* vl, lapack_int ldvl,\n                           lapack_complex_float* vr, lapack_int ldvr,\n                           lapack_int mm, lapack_int* m );\nlapack_int LAPACKE_ztrevc( int matrix_order, char side, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           lapack_complex_double* t, lapack_int ldt,\n                           lapack_complex_double* vl, lapack_int ldvl,\n                           lapack_complex_double* vr, lapack_int ldvr,\n                           lapack_int mm, lapack_int* m );\n\nlapack_int LAPACKE_strexc( int matrix_order, char compq, lapack_int n, float* t,\n                           lapack_int ldt, float* q, lapack_int ldq,\n                           lapack_int* ifst, lapack_int* ilst );\nlapack_int LAPACKE_dtrexc( int matrix_order, char compq, lapack_int n,\n                           double* t, lapack_int ldt, double* q, lapack_int ldq,\n                           lapack_int* ifst, lapack_int* ilst );\nlapack_int LAPACKE_ctrexc( int matrix_order, char compq, lapack_int n,\n                           lapack_complex_float* t, lapack_int ldt,\n                           lapack_complex_float* q, lapack_int ldq,\n                           lapack_int ifst, lapack_int ilst );\nlapack_int LAPACKE_ztrexc( int matrix_order, char compq, lapack_int n,\n                           lapack_complex_double* t, lapack_int ldt,\n                           lapack_complex_double* q, lapack_int ldq,\n                           lapack_int ifst, lapack_int ilst );\n\nlapack_int LAPACKE_strrfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs, const float* a,\n                           lapack_int lda, const float* b, lapack_int ldb,\n                           const float* x, lapack_int ldx, float* ferr,\n                           float* berr );\nlapack_int LAPACKE_dtrrfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs, const double* a,\n                           lapack_int lda, const double* b, lapack_int ldb,\n                           const double* x, lapack_int ldx, double* ferr,\n                           double* berr );\nlapack_int LAPACKE_ctrrfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           const lapack_complex_float* x, lapack_int ldx,\n                           float* ferr, float* berr );\nlapack_int LAPACKE_ztrrfs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           const lapack_complex_double* x, lapack_int ldx,\n                           double* ferr, double* berr );\n\nlapack_int LAPACKE_strsen( int matrix_order, char job, char compq,\n                           const lapack_logical* select, lapack_int n, float* t,\n                           lapack_int ldt, float* q, lapack_int ldq, float* wr,\n                           float* wi, lapack_int* m, float* s, float* sep );\nlapack_int LAPACKE_dtrsen( int matrix_order, char job, char compq,\n                           const lapack_logical* select, lapack_int n,\n                           double* t, lapack_int ldt, double* q, lapack_int ldq,\n                           double* wr, double* wi, lapack_int* m, double* s,\n                           double* sep );\nlapack_int LAPACKE_ctrsen( int matrix_order, char job, char compq,\n                           const lapack_logical* select, lapack_int n,\n                           lapack_complex_float* t, lapack_int ldt,\n                           lapack_complex_float* q, lapack_int ldq,\n                           lapack_complex_float* w, lapack_int* m, float* s,\n                           float* sep );\nlapack_int LAPACKE_ztrsen( int matrix_order, char job, char compq,\n                           const lapack_logical* select, lapack_int n,\n                           lapack_complex_double* t, lapack_int ldt,\n                           lapack_complex_double* q, lapack_int ldq,\n                           lapack_complex_double* w, lapack_int* m, double* s,\n                           double* sep );\n\nlapack_int LAPACKE_strsna( int matrix_order, char job, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const float* t, lapack_int ldt, const float* vl,\n                           lapack_int ldvl, const float* vr, lapack_int ldvr,\n                           float* s, float* sep, lapack_int mm, lapack_int* m );\nlapack_int LAPACKE_dtrsna( int matrix_order, char job, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const double* t, lapack_int ldt, const double* vl,\n                           lapack_int ldvl, const double* vr, lapack_int ldvr,\n                           double* s, double* sep, lapack_int mm,\n                           lapack_int* m );\nlapack_int LAPACKE_ctrsna( int matrix_order, char job, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const lapack_complex_float* t, lapack_int ldt,\n                           const lapack_complex_float* vl, lapack_int ldvl,\n                           const lapack_complex_float* vr, lapack_int ldvr,\n                           float* s, float* sep, lapack_int mm, lapack_int* m );\nlapack_int LAPACKE_ztrsna( int matrix_order, char job, char howmny,\n                           const lapack_logical* select, lapack_int n,\n                           const lapack_complex_double* t, lapack_int ldt,\n                           const lapack_complex_double* vl, lapack_int ldvl,\n                           const lapack_complex_double* vr, lapack_int ldvr,\n                           double* s, double* sep, lapack_int mm,\n                           lapack_int* m );\n\nlapack_int LAPACKE_strsyl( int matrix_order, char trana, char tranb,\n                           lapack_int isgn, lapack_int m, lapack_int n,\n                           const float* a, lapack_int lda, const float* b,\n                           lapack_int ldb, float* c, lapack_int ldc,\n                           float* scale );\nlapack_int LAPACKE_dtrsyl( int matrix_order, char trana, char tranb,\n                           lapack_int isgn, lapack_int m, lapack_int n,\n                           const double* a, lapack_int lda, const double* b,\n                           lapack_int ldb, double* c, lapack_int ldc,\n                           double* scale );\nlapack_int LAPACKE_ctrsyl( int matrix_order, char trana, char tranb,\n                           lapack_int isgn, lapack_int m, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* b, lapack_int ldb,\n                           lapack_complex_float* c, lapack_int ldc,\n                           float* scale );\nlapack_int LAPACKE_ztrsyl( int matrix_order, char trana, char tranb,\n                           lapack_int isgn, lapack_int m, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* c, lapack_int ldc,\n                           double* scale );\n\nlapack_int LAPACKE_strtri( int matrix_order, char uplo, char diag, lapack_int n,\n                           float* a, lapack_int lda );\nlapack_int LAPACKE_dtrtri( int matrix_order, char uplo, char diag, lapack_int n,\n                           double* a, lapack_int lda );\nlapack_int LAPACKE_ctrtri( int matrix_order, char uplo, char diag, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_ztrtri( int matrix_order, char uplo, char diag, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_strtrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs, const float* a,\n                           lapack_int lda, float* b, lapack_int ldb );\nlapack_int LAPACKE_dtrtrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs, const double* a,\n                           lapack_int lda, double* b, lapack_int ldb );\nlapack_int LAPACKE_ctrtrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_ztrtrs( int matrix_order, char uplo, char trans, char diag,\n                           lapack_int n, lapack_int nrhs,\n                           const lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_strttf( int matrix_order, char transr, char uplo,\n                           lapack_int n, const float* a, lapack_int lda,\n                           float* arf );\nlapack_int LAPACKE_dtrttf( int matrix_order, char transr, char uplo,\n                           lapack_int n, const double* a, lapack_int lda,\n                           double* arf );\nlapack_int LAPACKE_ctrttf( int matrix_order, char transr, char uplo,\n                           lapack_int n, const lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* arf );\nlapack_int LAPACKE_ztrttf( int matrix_order, char transr, char uplo,\n                           lapack_int n, const lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* arf );\n\nlapack_int LAPACKE_strttp( int matrix_order, char uplo, lapack_int n,\n                           const float* a, lapack_int lda, float* ap );\nlapack_int LAPACKE_dtrttp( int matrix_order, char uplo, lapack_int n,\n                           const double* a, lapack_int lda, double* ap );\nlapack_int LAPACKE_ctrttp( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* ap );\nlapack_int LAPACKE_ztrttp( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* ap );\n\nlapack_int LAPACKE_stzrzf( int matrix_order, lapack_int m, lapack_int n,\n                           float* a, lapack_int lda, float* tau );\nlapack_int LAPACKE_dtzrzf( int matrix_order, lapack_int m, lapack_int n,\n                           double* a, lapack_int lda, double* tau );\nlapack_int LAPACKE_ctzrzf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* tau );\nlapack_int LAPACKE_ztzrzf( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* tau );\n\nlapack_int LAPACKE_cungbr( int matrix_order, char vect, lapack_int m,\n                           lapack_int n, lapack_int k, lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* tau );\nlapack_int LAPACKE_zungbr( int matrix_order, char vect, lapack_int m,\n                           lapack_int n, lapack_int k, lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* tau );\n\nlapack_int LAPACKE_cunghr( int matrix_order, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* tau );\nlapack_int LAPACKE_zunghr( int matrix_order, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* tau );\n\nlapack_int LAPACKE_cunglq( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* tau );\nlapack_int LAPACKE_zunglq( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* tau );\n\nlapack_int LAPACKE_cungql( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* tau );\nlapack_int LAPACKE_zungql( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* tau );\n\nlapack_int LAPACKE_cungqr( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* tau );\nlapack_int LAPACKE_zungqr( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* tau );\n\nlapack_int LAPACKE_cungrq( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* tau );\nlapack_int LAPACKE_zungrq( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* tau );\n\nlapack_int LAPACKE_cungtr( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* tau );\nlapack_int LAPACKE_zungtr( int matrix_order, char uplo, lapack_int n,\n                           lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* tau );\n\nlapack_int LAPACKE_cunmbr( int matrix_order, char vect, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* tau,\n                           lapack_complex_float* c, lapack_int ldc );\nlapack_int LAPACKE_zunmbr( int matrix_order, char vect, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* tau,\n                           lapack_complex_double* c, lapack_int ldc );\n\nlapack_int LAPACKE_cunmhr( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, const lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* tau,\n                           lapack_complex_float* c, lapack_int ldc );\nlapack_int LAPACKE_zunmhr( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int ilo,\n                           lapack_int ihi, const lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* tau,\n                           lapack_complex_double* c, lapack_int ldc );\n\nlapack_int LAPACKE_cunmlq( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* tau,\n                           lapack_complex_float* c, lapack_int ldc );\nlapack_int LAPACKE_zunmlq( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* tau,\n                           lapack_complex_double* c, lapack_int ldc );\n\nlapack_int LAPACKE_cunmql( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* tau,\n                           lapack_complex_float* c, lapack_int ldc );\nlapack_int LAPACKE_zunmql( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* tau,\n                           lapack_complex_double* c, lapack_int ldc );\n\nlapack_int LAPACKE_cunmqr( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* tau,\n                           lapack_complex_float* c, lapack_int ldc );\nlapack_int LAPACKE_zunmqr( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* tau,\n                           lapack_complex_double* c, lapack_int ldc );\n\nlapack_int LAPACKE_cunmrq( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* tau,\n                           lapack_complex_float* c, lapack_int ldc );\nlapack_int LAPACKE_zunmrq( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* tau,\n                           lapack_complex_double* c, lapack_int ldc );\n\nlapack_int LAPACKE_cunmrz( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           lapack_int l, const lapack_complex_float* a,\n                           lapack_int lda, const lapack_complex_float* tau,\n                           lapack_complex_float* c, lapack_int ldc );\nlapack_int LAPACKE_zunmrz( int matrix_order, char side, char trans,\n                           lapack_int m, lapack_int n, lapack_int k,\n                           lapack_int l, const lapack_complex_double* a,\n                           lapack_int lda, const lapack_complex_double* tau,\n                           lapack_complex_double* c, lapack_int ldc );\n\nlapack_int LAPACKE_cunmtr( int matrix_order, char side, char uplo, char trans,\n                           lapack_int m, lapack_int n,\n                           const lapack_complex_float* a, lapack_int lda,\n                           const lapack_complex_float* tau,\n                           lapack_complex_float* c, lapack_int ldc );\nlapack_int LAPACKE_zunmtr( int matrix_order, char side, char uplo, char trans,\n                           lapack_int m, lapack_int n,\n                           const lapack_complex_double* a, lapack_int lda,\n                           const lapack_complex_double* tau,\n                           lapack_complex_double* c, lapack_int ldc );\n\nlapack_int LAPACKE_cupgtr( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_float* ap,\n                           const lapack_complex_float* tau,\n                           lapack_complex_float* q, lapack_int ldq );\nlapack_int LAPACKE_zupgtr( int matrix_order, char uplo, lapack_int n,\n                           const lapack_complex_double* ap,\n                           const lapack_complex_double* tau,\n                           lapack_complex_double* q, lapack_int ldq );\n\nlapack_int LAPACKE_cupmtr( int matrix_order, char side, char uplo, char trans,\n                           lapack_int m, lapack_int n,\n                           const lapack_complex_float* ap,\n                           const lapack_complex_float* tau,\n                           lapack_complex_float* c, lapack_int ldc );\nlapack_int LAPACKE_zupmtr( int matrix_order, char side, char uplo, char trans,\n                           lapack_int m, lapack_int n,\n                           const lapack_complex_double* ap,\n                           const lapack_complex_double* tau,\n                           lapack_complex_double* c, lapack_int ldc );\n\nlapack_int LAPACKE_sbdsdc_work( int matrix_order, char uplo, char compq,\n                                lapack_int n, float* d, float* e, float* u,\n                                lapack_int ldu, float* vt, lapack_int ldvt,\n                                float* q, lapack_int* iq, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dbdsdc_work( int matrix_order, char uplo, char compq,\n                                lapack_int n, double* d, double* e, double* u,\n                                lapack_int ldu, double* vt, lapack_int ldvt,\n                                double* q, lapack_int* iq, double* work,\n                                lapack_int* iwork );\n\nlapack_int LAPACKE_sbdsqr_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int ncvt, lapack_int nru, lapack_int ncc,\n                                float* d, float* e, float* vt, lapack_int ldvt,\n                                float* u, lapack_int ldu, float* c,\n                                lapack_int ldc, float* work );\nlapack_int LAPACKE_dbdsqr_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int ncvt, lapack_int nru, lapack_int ncc,\n                                double* d, double* e, double* vt,\n                                lapack_int ldvt, double* u, lapack_int ldu,\n                                double* c, lapack_int ldc, double* work );\nlapack_int LAPACKE_cbdsqr_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int ncvt, lapack_int nru, lapack_int ncc,\n                                float* d, float* e, lapack_complex_float* vt,\n                                lapack_int ldvt, lapack_complex_float* u,\n                                lapack_int ldu, lapack_complex_float* c,\n                                lapack_int ldc, float* work );\nlapack_int LAPACKE_zbdsqr_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int ncvt, lapack_int nru, lapack_int ncc,\n                                double* d, double* e, lapack_complex_double* vt,\n                                lapack_int ldvt, lapack_complex_double* u,\n                                lapack_int ldu, lapack_complex_double* c,\n                                lapack_int ldc, double* work );\n\nlapack_int LAPACKE_sdisna_work( char job, lapack_int m, lapack_int n,\n                                const float* d, float* sep );\nlapack_int LAPACKE_ddisna_work( char job, lapack_int m, lapack_int n,\n                                const double* d, double* sep );\n\nlapack_int LAPACKE_sgbbrd_work( int matrix_order, char vect, lapack_int m,\n                                lapack_int n, lapack_int ncc, lapack_int kl,\n                                lapack_int ku, float* ab, lapack_int ldab,\n                                float* d, float* e, float* q, lapack_int ldq,\n                                float* pt, lapack_int ldpt, float* c,\n                                lapack_int ldc, float* work );\nlapack_int LAPACKE_dgbbrd_work( int matrix_order, char vect, lapack_int m,\n                                lapack_int n, lapack_int ncc, lapack_int kl,\n                                lapack_int ku, double* ab, lapack_int ldab,\n                                double* d, double* e, double* q, lapack_int ldq,\n                                double* pt, lapack_int ldpt, double* c,\n                                lapack_int ldc, double* work );\nlapack_int LAPACKE_cgbbrd_work( int matrix_order, char vect, lapack_int m,\n                                lapack_int n, lapack_int ncc, lapack_int kl,\n                                lapack_int ku, lapack_complex_float* ab,\n                                lapack_int ldab, float* d, float* e,\n                                lapack_complex_float* q, lapack_int ldq,\n                                lapack_complex_float* pt, lapack_int ldpt,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zgbbrd_work( int matrix_order, char vect, lapack_int m,\n                                lapack_int n, lapack_int ncc, lapack_int kl,\n                                lapack_int ku, lapack_complex_double* ab,\n                                lapack_int ldab, double* d, double* e,\n                                lapack_complex_double* q, lapack_int ldq,\n                                lapack_complex_double* pt, lapack_int ldpt,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sgbcon_work( int matrix_order, char norm, lapack_int n,\n                                lapack_int kl, lapack_int ku, const float* ab,\n                                lapack_int ldab, const lapack_int* ipiv,\n                                float anorm, float* rcond, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dgbcon_work( int matrix_order, char norm, lapack_int n,\n                                lapack_int kl, lapack_int ku, const double* ab,\n                                lapack_int ldab, const lapack_int* ipiv,\n                                double anorm, double* rcond, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_cgbcon_work( int matrix_order, char norm, lapack_int n,\n                                lapack_int kl, lapack_int ku,\n                                const lapack_complex_float* ab, lapack_int ldab,\n                                const lapack_int* ipiv, float anorm,\n                                float* rcond, lapack_complex_float* work,\n                                float* rwork );\nlapack_int LAPACKE_zgbcon_work( int matrix_order, char norm, lapack_int n,\n                                lapack_int kl, lapack_int ku,\n                                const lapack_complex_double* ab,\n                                lapack_int ldab, const lapack_int* ipiv,\n                                double anorm, double* rcond,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sgbequ_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku, const float* ab,\n                                lapack_int ldab, float* r, float* c,\n                                float* rowcnd, float* colcnd, float* amax );\nlapack_int LAPACKE_dgbequ_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku, const double* ab,\n                                lapack_int ldab, double* r, double* c,\n                                double* rowcnd, double* colcnd, double* amax );\nlapack_int LAPACKE_cgbequ_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku,\n                                const lapack_complex_float* ab, lapack_int ldab,\n                                float* r, float* c, float* rowcnd,\n                                float* colcnd, float* amax );\nlapack_int LAPACKE_zgbequ_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku,\n                                const lapack_complex_double* ab,\n                                lapack_int ldab, double* r, double* c,\n                                double* rowcnd, double* colcnd, double* amax );\n\nlapack_int LAPACKE_sgbequb_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_int kl, lapack_int ku, const float* ab,\n                                 lapack_int ldab, float* r, float* c,\n                                 float* rowcnd, float* colcnd, float* amax );\nlapack_int LAPACKE_dgbequb_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_int kl, lapack_int ku, const double* ab,\n                                 lapack_int ldab, double* r, double* c,\n                                 double* rowcnd, double* colcnd, double* amax );\nlapack_int LAPACKE_cgbequb_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_int kl, lapack_int ku,\n                                 const lapack_complex_float* ab,\n                                 lapack_int ldab, float* r, float* c,\n                                 float* rowcnd, float* colcnd, float* amax );\nlapack_int LAPACKE_zgbequb_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_int kl, lapack_int ku,\n                                 const lapack_complex_double* ab,\n                                 lapack_int ldab, double* r, double* c,\n                                 double* rowcnd, double* colcnd, double* amax );\n\nlapack_int LAPACKE_sgbrfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int kl, lapack_int ku, lapack_int nrhs,\n                                const float* ab, lapack_int ldab,\n                                const float* afb, lapack_int ldafb,\n                                const lapack_int* ipiv, const float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* ferr, float* berr, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dgbrfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int kl, lapack_int ku, lapack_int nrhs,\n                                const double* ab, lapack_int ldab,\n                                const double* afb, lapack_int ldafb,\n                                const lapack_int* ipiv, const double* b,\n                                lapack_int ldb, double* x, lapack_int ldx,\n                                double* ferr, double* berr, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_cgbrfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int kl, lapack_int ku, lapack_int nrhs,\n                                const lapack_complex_float* ab, lapack_int ldab,\n                                const lapack_complex_float* afb,\n                                lapack_int ldafb, const lapack_int* ipiv,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zgbrfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int kl, lapack_int ku, lapack_int nrhs,\n                                const lapack_complex_double* ab,\n                                lapack_int ldab,\n                                const lapack_complex_double* afb,\n                                lapack_int ldafb, const lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sgbrfsx_work( int matrix_order, char trans, char equed,\n                                 lapack_int n, lapack_int kl, lapack_int ku,\n                                 lapack_int nrhs, const float* ab,\n                                 lapack_int ldab, const float* afb,\n                                 lapack_int ldafb, const lapack_int* ipiv,\n                                 const float* r, const float* c, const float* b,\n                                 lapack_int ldb, float* x, lapack_int ldx,\n                                 float* rcond, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, float* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_dgbrfsx_work( int matrix_order, char trans, char equed,\n                                 lapack_int n, lapack_int kl, lapack_int ku,\n                                 lapack_int nrhs, const double* ab,\n                                 lapack_int ldab, const double* afb,\n                                 lapack_int ldafb, const lapack_int* ipiv,\n                                 const double* r, const double* c,\n                                 const double* b, lapack_int ldb, double* x,\n                                 lapack_int ldx, double* rcond, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, double* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_cgbrfsx_work( int matrix_order, char trans, char equed,\n                                 lapack_int n, lapack_int kl, lapack_int ku,\n                                 lapack_int nrhs,\n                                 const lapack_complex_float* ab,\n                                 lapack_int ldab,\n                                 const lapack_complex_float* afb,\n                                 lapack_int ldafb, const lapack_int* ipiv,\n                                 const float* r, const float* c,\n                                 const lapack_complex_float* b, lapack_int ldb,\n                                 lapack_complex_float* x, lapack_int ldx,\n                                 float* rcond, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, lapack_complex_float* work,\n                                 float* rwork );\nlapack_int LAPACKE_zgbrfsx_work( int matrix_order, char trans, char equed,\n                                 lapack_int n, lapack_int kl, lapack_int ku,\n                                 lapack_int nrhs,\n                                 const lapack_complex_double* ab,\n                                 lapack_int ldab,\n                                 const lapack_complex_double* afb,\n                                 lapack_int ldafb, const lapack_int* ipiv,\n                                 const double* r, const double* c,\n                                 const lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* x, lapack_int ldx,\n                                 double* rcond, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, lapack_complex_double* work,\n                                 double* rwork );\n\nlapack_int LAPACKE_sgbsv_work( int matrix_order, lapack_int n, lapack_int kl,\n                               lapack_int ku, lapack_int nrhs, float* ab,\n                               lapack_int ldab, lapack_int* ipiv, float* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_dgbsv_work( int matrix_order, lapack_int n, lapack_int kl,\n                               lapack_int ku, lapack_int nrhs, double* ab,\n                               lapack_int ldab, lapack_int* ipiv, double* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_cgbsv_work( int matrix_order, lapack_int n, lapack_int kl,\n                               lapack_int ku, lapack_int nrhs,\n                               lapack_complex_float* ab, lapack_int ldab,\n                               lapack_int* ipiv, lapack_complex_float* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_zgbsv_work( int matrix_order, lapack_int n, lapack_int kl,\n                               lapack_int ku, lapack_int nrhs,\n                               lapack_complex_double* ab, lapack_int ldab,\n                               lapack_int* ipiv, lapack_complex_double* b,\n                               lapack_int ldb );\n\nlapack_int LAPACKE_sgbsvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int kl, lapack_int ku,\n                                lapack_int nrhs, float* ab, lapack_int ldab,\n                                float* afb, lapack_int ldafb, lapack_int* ipiv,\n                                char* equed, float* r, float* c, float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* rcond, float* ferr, float* berr,\n                                float* work, lapack_int* iwork );\nlapack_int LAPACKE_dgbsvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int kl, lapack_int ku,\n                                lapack_int nrhs, double* ab, lapack_int ldab,\n                                double* afb, lapack_int ldafb, lapack_int* ipiv,\n                                char* equed, double* r, double* c, double* b,\n                                lapack_int ldb, double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_cgbsvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int kl, lapack_int ku,\n                                lapack_int nrhs, lapack_complex_float* ab,\n                                lapack_int ldab, lapack_complex_float* afb,\n                                lapack_int ldafb, lapack_int* ipiv, char* equed,\n                                float* r, float* c, lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* x,\n                                lapack_int ldx, float* rcond, float* ferr,\n                                float* berr, lapack_complex_float* work,\n                                float* rwork );\nlapack_int LAPACKE_zgbsvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int kl, lapack_int ku,\n                                lapack_int nrhs, lapack_complex_double* ab,\n                                lapack_int ldab, lapack_complex_double* afb,\n                                lapack_int ldafb, lapack_int* ipiv, char* equed,\n                                double* r, double* c, lapack_complex_double* b,\n                                lapack_int ldb, lapack_complex_double* x,\n                                lapack_int ldx, double* rcond, double* ferr,\n                                double* berr, lapack_complex_double* work,\n                                double* rwork );\n\nlapack_int LAPACKE_sgbsvxx_work( int matrix_order, char fact, char trans,\n                                 lapack_int n, lapack_int kl, lapack_int ku,\n                                 lapack_int nrhs, float* ab, lapack_int ldab,\n                                 float* afb, lapack_int ldafb, lapack_int* ipiv,\n                                 char* equed, float* r, float* c, float* b,\n                                 lapack_int ldb, float* x, lapack_int ldx,\n                                 float* rcond, float* rpvgrw, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, float* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_dgbsvxx_work( int matrix_order, char fact, char trans,\n                                 lapack_int n, lapack_int kl, lapack_int ku,\n                                 lapack_int nrhs, double* ab, lapack_int ldab,\n                                 double* afb, lapack_int ldafb,\n                                 lapack_int* ipiv, char* equed, double* r,\n                                 double* c, double* b, lapack_int ldb,\n                                 double* x, lapack_int ldx, double* rcond,\n                                 double* rpvgrw, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, double* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_cgbsvxx_work( int matrix_order, char fact, char trans,\n                                 lapack_int n, lapack_int kl, lapack_int ku,\n                                 lapack_int nrhs, lapack_complex_float* ab,\n                                 lapack_int ldab, lapack_complex_float* afb,\n                                 lapack_int ldafb, lapack_int* ipiv,\n                                 char* equed, float* r, float* c,\n                                 lapack_complex_float* b, lapack_int ldb,\n                                 lapack_complex_float* x, lapack_int ldx,\n                                 float* rcond, float* rpvgrw, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, lapack_complex_float* work,\n                                 float* rwork );\nlapack_int LAPACKE_zgbsvxx_work( int matrix_order, char fact, char trans,\n                                 lapack_int n, lapack_int kl, lapack_int ku,\n                                 lapack_int nrhs, lapack_complex_double* ab,\n                                 lapack_int ldab, lapack_complex_double* afb,\n                                 lapack_int ldafb, lapack_int* ipiv,\n                                 char* equed, double* r, double* c,\n                                 lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* x, lapack_int ldx,\n                                 double* rcond, double* rpvgrw, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, lapack_complex_double* work,\n                                 double* rwork );\n\nlapack_int LAPACKE_sgbtrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku, float* ab,\n                                lapack_int ldab, lapack_int* ipiv );\nlapack_int LAPACKE_dgbtrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku, double* ab,\n                                lapack_int ldab, lapack_int* ipiv );\nlapack_int LAPACKE_cgbtrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku,\n                                lapack_complex_float* ab, lapack_int ldab,\n                                lapack_int* ipiv );\nlapack_int LAPACKE_zgbtrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku,\n                                lapack_complex_double* ab, lapack_int ldab,\n                                lapack_int* ipiv );\n\nlapack_int LAPACKE_sgbtrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int kl, lapack_int ku, lapack_int nrhs,\n                                const float* ab, lapack_int ldab,\n                                const lapack_int* ipiv, float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_dgbtrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int kl, lapack_int ku, lapack_int nrhs,\n                                const double* ab, lapack_int ldab,\n                                const lapack_int* ipiv, double* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_cgbtrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int kl, lapack_int ku, lapack_int nrhs,\n                                const lapack_complex_float* ab, lapack_int ldab,\n                                const lapack_int* ipiv, lapack_complex_float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_zgbtrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int kl, lapack_int ku, lapack_int nrhs,\n                                const lapack_complex_double* ab,\n                                lapack_int ldab, const lapack_int* ipiv,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_sgebak_work( int matrix_order, char job, char side,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                const float* scale, lapack_int m, float* v,\n                                lapack_int ldv );\nlapack_int LAPACKE_dgebak_work( int matrix_order, char job, char side,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                const double* scale, lapack_int m, double* v,\n                                lapack_int ldv );\nlapack_int LAPACKE_cgebak_work( int matrix_order, char job, char side,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                const float* scale, lapack_int m,\n                                lapack_complex_float* v, lapack_int ldv );\nlapack_int LAPACKE_zgebak_work( int matrix_order, char job, char side,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                const double* scale, lapack_int m,\n                                lapack_complex_double* v, lapack_int ldv );\n\nlapack_int LAPACKE_sgebal_work( int matrix_order, char job, lapack_int n,\n                                float* a, lapack_int lda, lapack_int* ilo,\n                                lapack_int* ihi, float* scale );\nlapack_int LAPACKE_dgebal_work( int matrix_order, char job, lapack_int n,\n                                double* a, lapack_int lda, lapack_int* ilo,\n                                lapack_int* ihi, double* scale );\nlapack_int LAPACKE_cgebal_work( int matrix_order, char job, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_int* ilo, lapack_int* ihi,\n                                float* scale );\nlapack_int LAPACKE_zgebal_work( int matrix_order, char job, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int* ilo, lapack_int* ihi,\n                                double* scale );\n\nlapack_int LAPACKE_sgebrd_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, float* d, float* e,\n                                float* tauq, float* taup, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dgebrd_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, double* d, double* e,\n                                double* tauq, double* taup, double* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_cgebrd_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                float* d, float* e, lapack_complex_float* tauq,\n                                lapack_complex_float* taup,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zgebrd_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                double* d, double* e,\n                                lapack_complex_double* tauq,\n                                lapack_complex_double* taup,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sgecon_work( int matrix_order, char norm, lapack_int n,\n                                const float* a, lapack_int lda, float anorm,\n                                float* rcond, float* work, lapack_int* iwork );\nlapack_int LAPACKE_dgecon_work( int matrix_order, char norm, lapack_int n,\n                                const double* a, lapack_int lda, double anorm,\n                                double* rcond, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_cgecon_work( int matrix_order, char norm, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                float anorm, float* rcond,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zgecon_work( int matrix_order, char norm, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                double anorm, double* rcond,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sgeequ_work( int matrix_order, lapack_int m, lapack_int n,\n                                const float* a, lapack_int lda, float* r,\n                                float* c, float* rowcnd, float* colcnd,\n                                float* amax );\nlapack_int LAPACKE_dgeequ_work( int matrix_order, lapack_int m, lapack_int n,\n                                const double* a, lapack_int lda, double* r,\n                                double* c, double* rowcnd, double* colcnd,\n                                double* amax );\nlapack_int LAPACKE_cgeequ_work( int matrix_order, lapack_int m, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                float* r, float* c, float* rowcnd,\n                                float* colcnd, float* amax );\nlapack_int LAPACKE_zgeequ_work( int matrix_order, lapack_int m, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                double* r, double* c, double* rowcnd,\n                                double* colcnd, double* amax );\n\nlapack_int LAPACKE_sgeequb_work( int matrix_order, lapack_int m, lapack_int n,\n                                 const float* a, lapack_int lda, float* r,\n                                 float* c, float* rowcnd, float* colcnd,\n                                 float* amax );\nlapack_int LAPACKE_dgeequb_work( int matrix_order, lapack_int m, lapack_int n,\n                                 const double* a, lapack_int lda, double* r,\n                                 double* c, double* rowcnd, double* colcnd,\n                                 double* amax );\nlapack_int LAPACKE_cgeequb_work( int matrix_order, lapack_int m, lapack_int n,\n                                 const lapack_complex_float* a, lapack_int lda,\n                                 float* r, float* c, float* rowcnd,\n                                 float* colcnd, float* amax );\nlapack_int LAPACKE_zgeequb_work( int matrix_order, lapack_int m, lapack_int n,\n                                 const lapack_complex_double* a, lapack_int lda,\n                                 double* r, double* c, double* rowcnd,\n                                 double* colcnd, double* amax );\n\nlapack_int LAPACKE_sgees_work( int matrix_order, char jobvs, char sort,\n                               LAPACK_S_SELECT2 select, lapack_int n, float* a,\n                               lapack_int lda, lapack_int* sdim, float* wr,\n                               float* wi, float* vs, lapack_int ldvs,\n                               float* work, lapack_int lwork,\n                               lapack_logical* bwork );\nlapack_int LAPACKE_dgees_work( int matrix_order, char jobvs, char sort,\n                               LAPACK_D_SELECT2 select, lapack_int n, double* a,\n                               lapack_int lda, lapack_int* sdim, double* wr,\n                               double* wi, double* vs, lapack_int ldvs,\n                               double* work, lapack_int lwork,\n                               lapack_logical* bwork );\nlapack_int LAPACKE_cgees_work( int matrix_order, char jobvs, char sort,\n                               LAPACK_C_SELECT1 select, lapack_int n,\n                               lapack_complex_float* a, lapack_int lda,\n                               lapack_int* sdim, lapack_complex_float* w,\n                               lapack_complex_float* vs, lapack_int ldvs,\n                               lapack_complex_float* work, lapack_int lwork,\n                               float* rwork, lapack_logical* bwork );\nlapack_int LAPACKE_zgees_work( int matrix_order, char jobvs, char sort,\n                               LAPACK_Z_SELECT1 select, lapack_int n,\n                               lapack_complex_double* a, lapack_int lda,\n                               lapack_int* sdim, lapack_complex_double* w,\n                               lapack_complex_double* vs, lapack_int ldvs,\n                               lapack_complex_double* work, lapack_int lwork,\n                               double* rwork, lapack_logical* bwork );\n\nlapack_int LAPACKE_sgeesx_work( int matrix_order, char jobvs, char sort,\n                                LAPACK_S_SELECT2 select, char sense,\n                                lapack_int n, float* a, lapack_int lda,\n                                lapack_int* sdim, float* wr, float* wi,\n                                float* vs, lapack_int ldvs, float* rconde,\n                                float* rcondv, float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork,\n                                lapack_logical* bwork );\nlapack_int LAPACKE_dgeesx_work( int matrix_order, char jobvs, char sort,\n                                LAPACK_D_SELECT2 select, char sense,\n                                lapack_int n, double* a, lapack_int lda,\n                                lapack_int* sdim, double* wr, double* wi,\n                                double* vs, lapack_int ldvs, double* rconde,\n                                double* rcondv, double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork,\n                                lapack_logical* bwork );\nlapack_int LAPACKE_cgeesx_work( int matrix_order, char jobvs, char sort,\n                                LAPACK_C_SELECT1 select, char sense,\n                                lapack_int n, lapack_complex_float* a,\n                                lapack_int lda, lapack_int* sdim,\n                                lapack_complex_float* w,\n                                lapack_complex_float* vs, lapack_int ldvs,\n                                float* rconde, float* rcondv,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork, lapack_logical* bwork );\nlapack_int LAPACKE_zgeesx_work( int matrix_order, char jobvs, char sort,\n                                LAPACK_Z_SELECT1 select, char sense,\n                                lapack_int n, lapack_complex_double* a,\n                                lapack_int lda, lapack_int* sdim,\n                                lapack_complex_double* w,\n                                lapack_complex_double* vs, lapack_int ldvs,\n                                double* rconde, double* rcondv,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork, lapack_logical* bwork );\n\nlapack_int LAPACKE_sgeev_work( int matrix_order, char jobvl, char jobvr,\n                               lapack_int n, float* a, lapack_int lda,\n                               float* wr, float* wi, float* vl, lapack_int ldvl,\n                               float* vr, lapack_int ldvr, float* work,\n                               lapack_int lwork );\nlapack_int LAPACKE_dgeev_work( int matrix_order, char jobvl, char jobvr,\n                               lapack_int n, double* a, lapack_int lda,\n                               double* wr, double* wi, double* vl,\n                               lapack_int ldvl, double* vr, lapack_int ldvr,\n                               double* work, lapack_int lwork );\nlapack_int LAPACKE_cgeev_work( int matrix_order, char jobvl, char jobvr,\n                               lapack_int n, lapack_complex_float* a,\n                               lapack_int lda, lapack_complex_float* w,\n                               lapack_complex_float* vl, lapack_int ldvl,\n                               lapack_complex_float* vr, lapack_int ldvr,\n                               lapack_complex_float* work, lapack_int lwork,\n                               float* rwork );\nlapack_int LAPACKE_zgeev_work( int matrix_order, char jobvl, char jobvr,\n                               lapack_int n, lapack_complex_double* a,\n                               lapack_int lda, lapack_complex_double* w,\n                               lapack_complex_double* vl, lapack_int ldvl,\n                               lapack_complex_double* vr, lapack_int ldvr,\n                               lapack_complex_double* work, lapack_int lwork,\n                               double* rwork );\n\nlapack_int LAPACKE_sgeevx_work( int matrix_order, char balanc, char jobvl,\n                                char jobvr, char sense, lapack_int n, float* a,\n                                lapack_int lda, float* wr, float* wi, float* vl,\n                                lapack_int ldvl, float* vr, lapack_int ldvr,\n                                lapack_int* ilo, lapack_int* ihi, float* scale,\n                                float* abnrm, float* rconde, float* rcondv,\n                                float* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dgeevx_work( int matrix_order, char balanc, char jobvl,\n                                char jobvr, char sense, lapack_int n, double* a,\n                                lapack_int lda, double* wr, double* wi,\n                                double* vl, lapack_int ldvl, double* vr,\n                                lapack_int ldvr, lapack_int* ilo,\n                                lapack_int* ihi, double* scale, double* abnrm,\n                                double* rconde, double* rcondv, double* work,\n                                lapack_int lwork, lapack_int* iwork );\nlapack_int LAPACKE_cgeevx_work( int matrix_order, char balanc, char jobvl,\n                                char jobvr, char sense, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* w,\n                                lapack_complex_float* vl, lapack_int ldvl,\n                                lapack_complex_float* vr, lapack_int ldvr,\n                                lapack_int* ilo, lapack_int* ihi, float* scale,\n                                float* abnrm, float* rconde, float* rcondv,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork );\nlapack_int LAPACKE_zgeevx_work( int matrix_order, char balanc, char jobvl,\n                                char jobvr, char sense, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* w,\n                                lapack_complex_double* vl, lapack_int ldvl,\n                                lapack_complex_double* vr, lapack_int ldvr,\n                                lapack_int* ilo, lapack_int* ihi, double* scale,\n                                double* abnrm, double* rconde, double* rcondv,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork );\n\nlapack_int LAPACKE_sgehrd_work( int matrix_order, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, float* a, lapack_int lda,\n                                float* tau, float* work, lapack_int lwork );\nlapack_int LAPACKE_dgehrd_work( int matrix_order, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, double* a, lapack_int lda,\n                                double* tau, double* work, lapack_int lwork );\nlapack_int LAPACKE_cgehrd_work( int matrix_order, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zgehrd_work( int matrix_order, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sgejsv_work( int matrix_order, char joba, char jobu,\n                                char jobv, char jobr, char jobt, char jobp,\n                                lapack_int m, lapack_int n, float* a,\n                                lapack_int lda, float* sva, float* u,\n                                lapack_int ldu, float* v, lapack_int ldv,\n                                float* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dgejsv_work( int matrix_order, char joba, char jobu,\n                                char jobv, char jobr, char jobt, char jobp,\n                                lapack_int m, lapack_int n, double* a,\n                                lapack_int lda, double* sva, double* u,\n                                lapack_int ldu, double* v, lapack_int ldv,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork );\n\nlapack_int LAPACKE_sgelq2_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, float* tau,\n                                float* work );\nlapack_int LAPACKE_dgelq2_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, double* tau,\n                                double* work );\nlapack_int LAPACKE_cgelq2_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* tau,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zgelq2_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* tau,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_sgelqf_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, float* tau,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dgelqf_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, double* tau,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_cgelqf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zgelqf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sgels_work( int matrix_order, char trans, lapack_int m,\n                               lapack_int n, lapack_int nrhs, float* a,\n                               lapack_int lda, float* b, lapack_int ldb,\n                               float* work, lapack_int lwork );\nlapack_int LAPACKE_dgels_work( int matrix_order, char trans, lapack_int m,\n                               lapack_int n, lapack_int nrhs, double* a,\n                               lapack_int lda, double* b, lapack_int ldb,\n                               double* work, lapack_int lwork );\nlapack_int LAPACKE_cgels_work( int matrix_order, char trans, lapack_int m,\n                               lapack_int n, lapack_int nrhs,\n                               lapack_complex_float* a, lapack_int lda,\n                               lapack_complex_float* b, lapack_int ldb,\n                               lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zgels_work( int matrix_order, char trans, lapack_int m,\n                               lapack_int n, lapack_int nrhs,\n                               lapack_complex_double* a, lapack_int lda,\n                               lapack_complex_double* b, lapack_int ldb,\n                               lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sgelsd_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, float* a, lapack_int lda,\n                                float* b, lapack_int ldb, float* s, float rcond,\n                                lapack_int* rank, float* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dgelsd_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, double* a, lapack_int lda,\n                                double* b, lapack_int ldb, double* s,\n                                double rcond, lapack_int* rank, double* work,\n                                lapack_int lwork, lapack_int* iwork );\nlapack_int LAPACKE_cgelsd_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* b,\n                                lapack_int ldb, float* s, float rcond,\n                                lapack_int* rank, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_zgelsd_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* b,\n                                lapack_int ldb, double* s, double rcond,\n                                lapack_int* rank, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork,\n                                lapack_int* iwork );\n\nlapack_int LAPACKE_sgelss_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, float* a, lapack_int lda,\n                                float* b, lapack_int ldb, float* s, float rcond,\n                                lapack_int* rank, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dgelss_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, double* a, lapack_int lda,\n                                double* b, lapack_int ldb, double* s,\n                                double rcond, lapack_int* rank, double* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_cgelss_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* b,\n                                lapack_int ldb, float* s, float rcond,\n                                lapack_int* rank, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork );\nlapack_int LAPACKE_zgelss_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* b,\n                                lapack_int ldb, double* s, double rcond,\n                                lapack_int* rank, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork );\n\nlapack_int LAPACKE_sgelsy_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, float* a, lapack_int lda,\n                                float* b, lapack_int ldb, lapack_int* jpvt,\n                                float rcond, lapack_int* rank, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dgelsy_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, double* a, lapack_int lda,\n                                double* b, lapack_int ldb, lapack_int* jpvt,\n                                double rcond, lapack_int* rank, double* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_cgelsy_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* b,\n                                lapack_int ldb, lapack_int* jpvt, float rcond,\n                                lapack_int* rank, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork );\nlapack_int LAPACKE_zgelsy_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nrhs, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* b,\n                                lapack_int ldb, lapack_int* jpvt, double rcond,\n                                lapack_int* rank, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork );\n\nlapack_int LAPACKE_sgeqlf_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, float* tau,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dgeqlf_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, double* tau,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_cgeqlf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zgeqlf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sgeqp3_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, lapack_int* jpvt,\n                                float* tau, float* work, lapack_int lwork );\nlapack_int LAPACKE_dgeqp3_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, lapack_int* jpvt,\n                                double* tau, double* work, lapack_int lwork );\nlapack_int LAPACKE_cgeqp3_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_int* jpvt, lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork );\nlapack_int LAPACKE_zgeqp3_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int* jpvt, lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork );\n\nlapack_int LAPACKE_sgeqpf_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, lapack_int* jpvt,\n                                float* tau, float* work );\nlapack_int LAPACKE_dgeqpf_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, lapack_int* jpvt,\n                                double* tau, double* work );\nlapack_int LAPACKE_cgeqpf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_int* jpvt, lapack_complex_float* tau,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zgeqpf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int* jpvt, lapack_complex_double* tau,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sgeqr2_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, float* tau,\n                                float* work );\nlapack_int LAPACKE_dgeqr2_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, double* tau,\n                                double* work );\nlapack_int LAPACKE_cgeqr2_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* tau,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zgeqr2_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* tau,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_sgeqrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, float* tau,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dgeqrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, double* tau,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_cgeqrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zgeqrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sgeqrfp_work( int matrix_order, lapack_int m, lapack_int n,\n                                 float* a, lapack_int lda, float* tau,\n                                 float* work, lapack_int lwork );\nlapack_int LAPACKE_dgeqrfp_work( int matrix_order, lapack_int m, lapack_int n,\n                                 double* a, lapack_int lda, double* tau,\n                                 double* work, lapack_int lwork );\nlapack_int LAPACKE_cgeqrfp_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 lapack_complex_float* tau,\n                                 lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zgeqrfp_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 lapack_complex_double* tau,\n                                 lapack_complex_double* work,\n                                 lapack_int lwork );\n\nlapack_int LAPACKE_sgerfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const float* a, lapack_int lda,\n                                const float* af, lapack_int ldaf,\n                                const lapack_int* ipiv, const float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* ferr, float* berr, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dgerfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const double* a,\n                                lapack_int lda, const double* af,\n                                lapack_int ldaf, const lapack_int* ipiv,\n                                const double* b, lapack_int ldb, double* x,\n                                lapack_int ldx, double* ferr, double* berr,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_cgerfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* af,\n                                lapack_int ldaf, const lapack_int* ipiv,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zgerfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_double* a,\n                                lapack_int lda, const lapack_complex_double* af,\n                                lapack_int ldaf, const lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sgerfsx_work( int matrix_order, char trans, char equed,\n                                 lapack_int n, lapack_int nrhs, const float* a,\n                                 lapack_int lda, const float* af,\n                                 lapack_int ldaf, const lapack_int* ipiv,\n                                 const float* r, const float* c, const float* b,\n                                 lapack_int ldb, float* x, lapack_int ldx,\n                                 float* rcond, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, float* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_dgerfsx_work( int matrix_order, char trans, char equed,\n                                 lapack_int n, lapack_int nrhs, const double* a,\n                                 lapack_int lda, const double* af,\n                                 lapack_int ldaf, const lapack_int* ipiv,\n                                 const double* r, const double* c,\n                                 const double* b, lapack_int ldb, double* x,\n                                 lapack_int ldx, double* rcond, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, double* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_cgerfsx_work( int matrix_order, char trans, char equed,\n                                 lapack_int n, lapack_int nrhs,\n                                 const lapack_complex_float* a, lapack_int lda,\n                                 const lapack_complex_float* af,\n                                 lapack_int ldaf, const lapack_int* ipiv,\n                                 const float* r, const float* c,\n                                 const lapack_complex_float* b, lapack_int ldb,\n                                 lapack_complex_float* x, lapack_int ldx,\n                                 float* rcond, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, lapack_complex_float* work,\n                                 float* rwork );\nlapack_int LAPACKE_zgerfsx_work( int matrix_order, char trans, char equed,\n                                 lapack_int n, lapack_int nrhs,\n                                 const lapack_complex_double* a, lapack_int lda,\n                                 const lapack_complex_double* af,\n                                 lapack_int ldaf, const lapack_int* ipiv,\n                                 const double* r, const double* c,\n                                 const lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* x, lapack_int ldx,\n                                 double* rcond, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, lapack_complex_double* work,\n                                 double* rwork );\n\nlapack_int LAPACKE_sgerqf_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, float* tau,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dgerqf_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, double* tau,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_cgerqf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zgerqf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sgesdd_work( int matrix_order, char jobz, lapack_int m,\n                                lapack_int n, float* a, lapack_int lda,\n                                float* s, float* u, lapack_int ldu, float* vt,\n                                lapack_int ldvt, float* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dgesdd_work( int matrix_order, char jobz, lapack_int m,\n                                lapack_int n, double* a, lapack_int lda,\n                                double* s, double* u, lapack_int ldu,\n                                double* vt, lapack_int ldvt, double* work,\n                                lapack_int lwork, lapack_int* iwork );\nlapack_int LAPACKE_cgesdd_work( int matrix_order, char jobz, lapack_int m,\n                                lapack_int n, lapack_complex_float* a,\n                                lapack_int lda, float* s,\n                                lapack_complex_float* u, lapack_int ldu,\n                                lapack_complex_float* vt, lapack_int ldvt,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork, lapack_int* iwork );\nlapack_int LAPACKE_zgesdd_work( int matrix_order, char jobz, lapack_int m,\n                                lapack_int n, lapack_complex_double* a,\n                                lapack_int lda, double* s,\n                                lapack_complex_double* u, lapack_int ldu,\n                                lapack_complex_double* vt, lapack_int ldvt,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork, lapack_int* iwork );\n\nlapack_int LAPACKE_sgesv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               float* a, lapack_int lda, lapack_int* ipiv,\n                               float* b, lapack_int ldb );\nlapack_int LAPACKE_dgesv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               double* a, lapack_int lda, lapack_int* ipiv,\n                               double* b, lapack_int ldb );\nlapack_int LAPACKE_cgesv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               lapack_complex_float* a, lapack_int lda,\n                               lapack_int* ipiv, lapack_complex_float* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_zgesv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               lapack_complex_double* a, lapack_int lda,\n                               lapack_int* ipiv, lapack_complex_double* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_dsgesv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                                double* a, lapack_int lda, lapack_int* ipiv,\n                                double* b, lapack_int ldb, double* x,\n                                lapack_int ldx, double* work, float* swork,\n                                lapack_int* iter );\nlapack_int LAPACKE_zcgesv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int* ipiv, lapack_complex_double* b,\n                                lapack_int ldb, lapack_complex_double* x,\n                                lapack_int ldx, lapack_complex_double* work,\n                                lapack_complex_float* swork, double* rwork,\n                                lapack_int* iter );\n\nlapack_int LAPACKE_sgesvd_work( int matrix_order, char jobu, char jobvt,\n                                lapack_int m, lapack_int n, float* a,\n                                lapack_int lda, float* s, float* u,\n                                lapack_int ldu, float* vt, lapack_int ldvt,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dgesvd_work( int matrix_order, char jobu, char jobvt,\n                                lapack_int m, lapack_int n, double* a,\n                                lapack_int lda, double* s, double* u,\n                                lapack_int ldu, double* vt, lapack_int ldvt,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_cgesvd_work( int matrix_order, char jobu, char jobvt,\n                                lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                float* s, lapack_complex_float* u,\n                                lapack_int ldu, lapack_complex_float* vt,\n                                lapack_int ldvt, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork );\nlapack_int LAPACKE_zgesvd_work( int matrix_order, char jobu, char jobvt,\n                                lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                double* s, lapack_complex_double* u,\n                                lapack_int ldu, lapack_complex_double* vt,\n                                lapack_int ldvt, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork );\n\nlapack_int LAPACKE_sgesvj_work( int matrix_order, char joba, char jobu,\n                                char jobv, lapack_int m, lapack_int n, float* a,\n                                lapack_int lda, float* sva, lapack_int mv,\n                                float* v, lapack_int ldv, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dgesvj_work( int matrix_order, char joba, char jobu,\n                                char jobv, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, double* sva,\n                                lapack_int mv, double* v, lapack_int ldv,\n                                double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sgesvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int nrhs, float* a,\n                                lapack_int lda, float* af, lapack_int ldaf,\n                                lapack_int* ipiv, char* equed, float* r,\n                                float* c, float* b, lapack_int ldb, float* x,\n                                lapack_int ldx, float* rcond, float* ferr,\n                                float* berr, float* work, lapack_int* iwork );\nlapack_int LAPACKE_dgesvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int nrhs, double* a,\n                                lapack_int lda, double* af, lapack_int ldaf,\n                                lapack_int* ipiv, char* equed, double* r,\n                                double* c, double* b, lapack_int ldb, double* x,\n                                lapack_int ldx, double* rcond, double* ferr,\n                                double* berr, double* work, lapack_int* iwork );\nlapack_int LAPACKE_cgesvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int nrhs,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* af, lapack_int ldaf,\n                                lapack_int* ipiv, char* equed, float* r,\n                                float* c, lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* x,\n                                lapack_int ldx, float* rcond, float* ferr,\n                                float* berr, lapack_complex_float* work,\n                                float* rwork );\nlapack_int LAPACKE_zgesvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int nrhs,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* af, lapack_int ldaf,\n                                lapack_int* ipiv, char* equed, double* r,\n                                double* c, lapack_complex_double* b,\n                                lapack_int ldb, lapack_complex_double* x,\n                                lapack_int ldx, double* rcond, double* ferr,\n                                double* berr, lapack_complex_double* work,\n                                double* rwork );\n\nlapack_int LAPACKE_sgesvxx_work( int matrix_order, char fact, char trans,\n                                 lapack_int n, lapack_int nrhs, float* a,\n                                 lapack_int lda, float* af, lapack_int ldaf,\n                                 lapack_int* ipiv, char* equed, float* r,\n                                 float* c, float* b, lapack_int ldb, float* x,\n                                 lapack_int ldx, float* rcond, float* rpvgrw,\n                                 float* berr, lapack_int n_err_bnds,\n                                 float* err_bnds_norm, float* err_bnds_comp,\n                                 lapack_int nparams, float* params, float* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_dgesvxx_work( int matrix_order, char fact, char trans,\n                                 lapack_int n, lapack_int nrhs, double* a,\n                                 lapack_int lda, double* af, lapack_int ldaf,\n                                 lapack_int* ipiv, char* equed, double* r,\n                                 double* c, double* b, lapack_int ldb,\n                                 double* x, lapack_int ldx, double* rcond,\n                                 double* rpvgrw, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, double* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_cgesvxx_work( int matrix_order, char fact, char trans,\n                                 lapack_int n, lapack_int nrhs,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 lapack_complex_float* af, lapack_int ldaf,\n                                 lapack_int* ipiv, char* equed, float* r,\n                                 float* c, lapack_complex_float* b,\n                                 lapack_int ldb, lapack_complex_float* x,\n                                 lapack_int ldx, float* rcond, float* rpvgrw,\n                                 float* berr, lapack_int n_err_bnds,\n                                 float* err_bnds_norm, float* err_bnds_comp,\n                                 lapack_int nparams, float* params,\n                                 lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zgesvxx_work( int matrix_order, char fact, char trans,\n                                 lapack_int n, lapack_int nrhs,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 lapack_complex_double* af, lapack_int ldaf,\n                                 lapack_int* ipiv, char* equed, double* r,\n                                 double* c, lapack_complex_double* b,\n                                 lapack_int ldb, lapack_complex_double* x,\n                                 lapack_int ldx, double* rcond, double* rpvgrw,\n                                 double* berr, lapack_int n_err_bnds,\n                                 double* err_bnds_norm, double* err_bnds_comp,\n                                 lapack_int nparams, double* params,\n                                 lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sgetf2_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, lapack_int* ipiv );\nlapack_int LAPACKE_dgetf2_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, lapack_int* ipiv );\nlapack_int LAPACKE_cgetf2_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_int* ipiv );\nlapack_int LAPACKE_zgetf2_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int* ipiv );\n\nlapack_int LAPACKE_sgetrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, lapack_int* ipiv );\nlapack_int LAPACKE_dgetrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, lapack_int* ipiv );\nlapack_int LAPACKE_cgetrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_int* ipiv );\nlapack_int LAPACKE_zgetrf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int* ipiv );\n\nlapack_int LAPACKE_sgetri_work( int matrix_order, lapack_int n, float* a,\n                                lapack_int lda, const lapack_int* ipiv,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dgetri_work( int matrix_order, lapack_int n, double* a,\n                                lapack_int lda, const lapack_int* ipiv,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_cgetri_work( int matrix_order, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                const lapack_int* ipiv,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zgetri_work( int matrix_order, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                const lapack_int* ipiv,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sgetrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const float* a, lapack_int lda,\n                                const lapack_int* ipiv, float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_dgetrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const double* a,\n                                lapack_int lda, const lapack_int* ipiv,\n                                double* b, lapack_int ldb );\nlapack_int LAPACKE_cgetrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* a,\n                                lapack_int lda, const lapack_int* ipiv,\n                                lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zgetrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_double* a,\n                                lapack_int lda, const lapack_int* ipiv,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_sggbak_work( int matrix_order, char job, char side,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                const float* lscale, const float* rscale,\n                                lapack_int m, float* v, lapack_int ldv );\nlapack_int LAPACKE_dggbak_work( int matrix_order, char job, char side,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                const double* lscale, const double* rscale,\n                                lapack_int m, double* v, lapack_int ldv );\nlapack_int LAPACKE_cggbak_work( int matrix_order, char job, char side,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                const float* lscale, const float* rscale,\n                                lapack_int m, lapack_complex_float* v,\n                                lapack_int ldv );\nlapack_int LAPACKE_zggbak_work( int matrix_order, char job, char side,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                const double* lscale, const double* rscale,\n                                lapack_int m, lapack_complex_double* v,\n                                lapack_int ldv );\n\nlapack_int LAPACKE_sggbal_work( int matrix_order, char job, lapack_int n,\n                                float* a, lapack_int lda, float* b,\n                                lapack_int ldb, lapack_int* ilo,\n                                lapack_int* ihi, float* lscale, float* rscale,\n                                float* work );\nlapack_int LAPACKE_dggbal_work( int matrix_order, char job, lapack_int n,\n                                double* a, lapack_int lda, double* b,\n                                lapack_int ldb, lapack_int* ilo,\n                                lapack_int* ihi, double* lscale, double* rscale,\n                                double* work );\nlapack_int LAPACKE_cggbal_work( int matrix_order, char job, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb,\n                                lapack_int* ilo, lapack_int* ihi, float* lscale,\n                                float* rscale, float* work );\nlapack_int LAPACKE_zggbal_work( int matrix_order, char job, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                lapack_int* ilo, lapack_int* ihi,\n                                double* lscale, double* rscale, double* work );\n\nlapack_int LAPACKE_sgges_work( int matrix_order, char jobvsl, char jobvsr,\n                               char sort, LAPACK_S_SELECT3 selctg, lapack_int n,\n                               float* a, lapack_int lda, float* b,\n                               lapack_int ldb, lapack_int* sdim, float* alphar,\n                               float* alphai, float* beta, float* vsl,\n                               lapack_int ldvsl, float* vsr, lapack_int ldvsr,\n                               float* work, lapack_int lwork,\n                               lapack_logical* bwork );\nlapack_int LAPACKE_dgges_work( int matrix_order, char jobvsl, char jobvsr,\n                               char sort, LAPACK_D_SELECT3 selctg, lapack_int n,\n                               double* a, lapack_int lda, double* b,\n                               lapack_int ldb, lapack_int* sdim, double* alphar,\n                               double* alphai, double* beta, double* vsl,\n                               lapack_int ldvsl, double* vsr, lapack_int ldvsr,\n                               double* work, lapack_int lwork,\n                               lapack_logical* bwork );\nlapack_int LAPACKE_cgges_work( int matrix_order, char jobvsl, char jobvsr,\n                               char sort, LAPACK_C_SELECT2 selctg, lapack_int n,\n                               lapack_complex_float* a, lapack_int lda,\n                               lapack_complex_float* b, lapack_int ldb,\n                               lapack_int* sdim, lapack_complex_float* alpha,\n                               lapack_complex_float* beta,\n                               lapack_complex_float* vsl, lapack_int ldvsl,\n                               lapack_complex_float* vsr, lapack_int ldvsr,\n                               lapack_complex_float* work, lapack_int lwork,\n                               float* rwork, lapack_logical* bwork );\nlapack_int LAPACKE_zgges_work( int matrix_order, char jobvsl, char jobvsr,\n                               char sort, LAPACK_Z_SELECT2 selctg, lapack_int n,\n                               lapack_complex_double* a, lapack_int lda,\n                               lapack_complex_double* b, lapack_int ldb,\n                               lapack_int* sdim, lapack_complex_double* alpha,\n                               lapack_complex_double* beta,\n                               lapack_complex_double* vsl, lapack_int ldvsl,\n                               lapack_complex_double* vsr, lapack_int ldvsr,\n                               lapack_complex_double* work, lapack_int lwork,\n                               double* rwork, lapack_logical* bwork );\n\nlapack_int LAPACKE_sggesx_work( int matrix_order, char jobvsl, char jobvsr,\n                                char sort, LAPACK_S_SELECT3 selctg, char sense,\n                                lapack_int n, float* a, lapack_int lda,\n                                float* b, lapack_int ldb, lapack_int* sdim,\n                                float* alphar, float* alphai, float* beta,\n                                float* vsl, lapack_int ldvsl, float* vsr,\n                                lapack_int ldvsr, float* rconde, float* rcondv,\n                                float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork,\n                                lapack_logical* bwork );\nlapack_int LAPACKE_dggesx_work( int matrix_order, char jobvsl, char jobvsr,\n                                char sort, LAPACK_D_SELECT3 selctg, char sense,\n                                lapack_int n, double* a, lapack_int lda,\n                                double* b, lapack_int ldb, lapack_int* sdim,\n                                double* alphar, double* alphai, double* beta,\n                                double* vsl, lapack_int ldvsl, double* vsr,\n                                lapack_int ldvsr, double* rconde,\n                                double* rcondv, double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork,\n                                lapack_logical* bwork );\nlapack_int LAPACKE_cggesx_work( int matrix_order, char jobvsl, char jobvsr,\n                                char sort, LAPACK_C_SELECT2 selctg, char sense,\n                                lapack_int n, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* b,\n                                lapack_int ldb, lapack_int* sdim,\n                                lapack_complex_float* alpha,\n                                lapack_complex_float* beta,\n                                lapack_complex_float* vsl, lapack_int ldvsl,\n                                lapack_complex_float* vsr, lapack_int ldvsr,\n                                float* rconde, float* rcondv,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork, lapack_int* iwork,\n                                lapack_int liwork, lapack_logical* bwork );\nlapack_int LAPACKE_zggesx_work( int matrix_order, char jobvsl, char jobvsr,\n                                char sort, LAPACK_Z_SELECT2 selctg, char sense,\n                                lapack_int n, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* b,\n                                lapack_int ldb, lapack_int* sdim,\n                                lapack_complex_double* alpha,\n                                lapack_complex_double* beta,\n                                lapack_complex_double* vsl, lapack_int ldvsl,\n                                lapack_complex_double* vsr, lapack_int ldvsr,\n                                double* rconde, double* rcondv,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork, lapack_int* iwork,\n                                lapack_int liwork, lapack_logical* bwork );\n\nlapack_int LAPACKE_sggev_work( int matrix_order, char jobvl, char jobvr,\n                               lapack_int n, float* a, lapack_int lda, float* b,\n                               lapack_int ldb, float* alphar, float* alphai,\n                               float* beta, float* vl, lapack_int ldvl,\n                               float* vr, lapack_int ldvr, float* work,\n                               lapack_int lwork );\nlapack_int LAPACKE_dggev_work( int matrix_order, char jobvl, char jobvr,\n                               lapack_int n, double* a, lapack_int lda,\n                               double* b, lapack_int ldb, double* alphar,\n                               double* alphai, double* beta, double* vl,\n                               lapack_int ldvl, double* vr, lapack_int ldvr,\n                               double* work, lapack_int lwork );\nlapack_int LAPACKE_cggev_work( int matrix_order, char jobvl, char jobvr,\n                               lapack_int n, lapack_complex_float* a,\n                               lapack_int lda, lapack_complex_float* b,\n                               lapack_int ldb, lapack_complex_float* alpha,\n                               lapack_complex_float* beta,\n                               lapack_complex_float* vl, lapack_int ldvl,\n                               lapack_complex_float* vr, lapack_int ldvr,\n                               lapack_complex_float* work, lapack_int lwork,\n                               float* rwork );\nlapack_int LAPACKE_zggev_work( int matrix_order, char jobvl, char jobvr,\n                               lapack_int n, lapack_complex_double* a,\n                               lapack_int lda, lapack_complex_double* b,\n                               lapack_int ldb, lapack_complex_double* alpha,\n                               lapack_complex_double* beta,\n                               lapack_complex_double* vl, lapack_int ldvl,\n                               lapack_complex_double* vr, lapack_int ldvr,\n                               lapack_complex_double* work, lapack_int lwork,\n                               double* rwork );\n\nlapack_int LAPACKE_sggevx_work( int matrix_order, char balanc, char jobvl,\n                                char jobvr, char sense, lapack_int n, float* a,\n                                lapack_int lda, float* b, lapack_int ldb,\n                                float* alphar, float* alphai, float* beta,\n                                float* vl, lapack_int ldvl, float* vr,\n                                lapack_int ldvr, lapack_int* ilo,\n                                lapack_int* ihi, float* lscale, float* rscale,\n                                float* abnrm, float* bbnrm, float* rconde,\n                                float* rcondv, float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_logical* bwork );\nlapack_int LAPACKE_dggevx_work( int matrix_order, char balanc, char jobvl,\n                                char jobvr, char sense, lapack_int n, double* a,\n                                lapack_int lda, double* b, lapack_int ldb,\n                                double* alphar, double* alphai, double* beta,\n                                double* vl, lapack_int ldvl, double* vr,\n                                lapack_int ldvr, lapack_int* ilo,\n                                lapack_int* ihi, double* lscale, double* rscale,\n                                double* abnrm, double* bbnrm, double* rconde,\n                                double* rcondv, double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_logical* bwork );\nlapack_int LAPACKE_cggevx_work( int matrix_order, char balanc, char jobvl,\n                                char jobvr, char sense, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* alpha,\n                                lapack_complex_float* beta,\n                                lapack_complex_float* vl, lapack_int ldvl,\n                                lapack_complex_float* vr, lapack_int ldvr,\n                                lapack_int* ilo, lapack_int* ihi, float* lscale,\n                                float* rscale, float* abnrm, float* bbnrm,\n                                float* rconde, float* rcondv,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork, lapack_int* iwork,\n                                lapack_logical* bwork );\nlapack_int LAPACKE_zggevx_work( int matrix_order, char balanc, char jobvl,\n                                char jobvr, char sense, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* alpha,\n                                lapack_complex_double* beta,\n                                lapack_complex_double* vl, lapack_int ldvl,\n                                lapack_complex_double* vr, lapack_int ldvr,\n                                lapack_int* ilo, lapack_int* ihi,\n                                double* lscale, double* rscale, double* abnrm,\n                                double* bbnrm, double* rconde, double* rcondv,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork, lapack_int* iwork,\n                                lapack_logical* bwork );\n\nlapack_int LAPACKE_sggglm_work( int matrix_order, lapack_int n, lapack_int m,\n                                lapack_int p, float* a, lapack_int lda,\n                                float* b, lapack_int ldb, float* d, float* x,\n                                float* y, float* work, lapack_int lwork );\nlapack_int LAPACKE_dggglm_work( int matrix_order, lapack_int n, lapack_int m,\n                                lapack_int p, double* a, lapack_int lda,\n                                double* b, lapack_int ldb, double* d, double* x,\n                                double* y, double* work, lapack_int lwork );\nlapack_int LAPACKE_cggglm_work( int matrix_order, lapack_int n, lapack_int m,\n                                lapack_int p, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* d,\n                                lapack_complex_float* x,\n                                lapack_complex_float* y,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zggglm_work( int matrix_order, lapack_int n, lapack_int m,\n                                lapack_int p, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* b,\n                                lapack_int ldb, lapack_complex_double* d,\n                                lapack_complex_double* x,\n                                lapack_complex_double* y,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sgghrd_work( int matrix_order, char compq, char compz,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                float* a, lapack_int lda, float* b,\n                                lapack_int ldb, float* q, lapack_int ldq,\n                                float* z, lapack_int ldz );\nlapack_int LAPACKE_dgghrd_work( int matrix_order, char compq, char compz,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                double* a, lapack_int lda, double* b,\n                                lapack_int ldb, double* q, lapack_int ldq,\n                                double* z, lapack_int ldz );\nlapack_int LAPACKE_cgghrd_work( int matrix_order, char compq, char compz,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* q, lapack_int ldq,\n                                lapack_complex_float* z, lapack_int ldz );\nlapack_int LAPACKE_zgghrd_work( int matrix_order, char compq, char compz,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* q, lapack_int ldq,\n                                lapack_complex_double* z, lapack_int ldz );\n\nlapack_int LAPACKE_sgglse_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int p, float* a, lapack_int lda,\n                                float* b, lapack_int ldb, float* c, float* d,\n                                float* x, float* work, lapack_int lwork );\nlapack_int LAPACKE_dgglse_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int p, double* a, lapack_int lda,\n                                double* b, lapack_int ldb, double* c, double* d,\n                                double* x, double* work, lapack_int lwork );\nlapack_int LAPACKE_cgglse_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int p, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* c,\n                                lapack_complex_float* d,\n                                lapack_complex_float* x,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zgglse_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int p, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* b,\n                                lapack_int ldb, lapack_complex_double* c,\n                                lapack_complex_double* d,\n                                lapack_complex_double* x,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sggqrf_work( int matrix_order, lapack_int n, lapack_int m,\n                                lapack_int p, float* a, lapack_int lda,\n                                float* taua, float* b, lapack_int ldb,\n                                float* taub, float* work, lapack_int lwork );\nlapack_int LAPACKE_dggqrf_work( int matrix_order, lapack_int n, lapack_int m,\n                                lapack_int p, double* a, lapack_int lda,\n                                double* taua, double* b, lapack_int ldb,\n                                double* taub, double* work, lapack_int lwork );\nlapack_int LAPACKE_cggqrf_work( int matrix_order, lapack_int n, lapack_int m,\n                                lapack_int p, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* taua,\n                                lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* taub,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zggqrf_work( int matrix_order, lapack_int n, lapack_int m,\n                                lapack_int p, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* taua,\n                                lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* taub,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sggrqf_work( int matrix_order, lapack_int m, lapack_int p,\n                                lapack_int n, float* a, lapack_int lda,\n                                float* taua, float* b, lapack_int ldb,\n                                float* taub, float* work, lapack_int lwork );\nlapack_int LAPACKE_dggrqf_work( int matrix_order, lapack_int m, lapack_int p,\n                                lapack_int n, double* a, lapack_int lda,\n                                double* taua, double* b, lapack_int ldb,\n                                double* taub, double* work, lapack_int lwork );\nlapack_int LAPACKE_cggrqf_work( int matrix_order, lapack_int m, lapack_int p,\n                                lapack_int n, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* taua,\n                                lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* taub,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zggrqf_work( int matrix_order, lapack_int m, lapack_int p,\n                                lapack_int n, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* taua,\n                                lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* taub,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sggsvd_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int n,\n                                lapack_int p, lapack_int* k, lapack_int* l,\n                                float* a, lapack_int lda, float* b,\n                                lapack_int ldb, float* alpha, float* beta,\n                                float* u, lapack_int ldu, float* v,\n                                lapack_int ldv, float* q, lapack_int ldq,\n                                float* work, lapack_int* iwork );\nlapack_int LAPACKE_dggsvd_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int n,\n                                lapack_int p, lapack_int* k, lapack_int* l,\n                                double* a, lapack_int lda, double* b,\n                                lapack_int ldb, double* alpha, double* beta,\n                                double* u, lapack_int ldu, double* v,\n                                lapack_int ldv, double* q, lapack_int ldq,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_cggsvd_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int n,\n                                lapack_int p, lapack_int* k, lapack_int* l,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb,\n                                float* alpha, float* beta,\n                                lapack_complex_float* u, lapack_int ldu,\n                                lapack_complex_float* v, lapack_int ldv,\n                                lapack_complex_float* q, lapack_int ldq,\n                                lapack_complex_float* work, float* rwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_zggsvd_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int n,\n                                lapack_int p, lapack_int* k, lapack_int* l,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                double* alpha, double* beta,\n                                lapack_complex_double* u, lapack_int ldu,\n                                lapack_complex_double* v, lapack_int ldv,\n                                lapack_complex_double* q, lapack_int ldq,\n                                lapack_complex_double* work, double* rwork,\n                                lapack_int* iwork );\n\nlapack_int LAPACKE_sggsvp_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int p,\n                                lapack_int n, float* a, lapack_int lda,\n                                float* b, lapack_int ldb, float tola,\n                                float tolb, lapack_int* k, lapack_int* l,\n                                float* u, lapack_int ldu, float* v,\n                                lapack_int ldv, float* q, lapack_int ldq,\n                                lapack_int* iwork, float* tau, float* work );\nlapack_int LAPACKE_dggsvp_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int p,\n                                lapack_int n, double* a, lapack_int lda,\n                                double* b, lapack_int ldb, double tola,\n                                double tolb, lapack_int* k, lapack_int* l,\n                                double* u, lapack_int ldu, double* v,\n                                lapack_int ldv, double* q, lapack_int ldq,\n                                lapack_int* iwork, double* tau, double* work );\nlapack_int LAPACKE_cggsvp_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int p,\n                                lapack_int n, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* b,\n                                lapack_int ldb, float tola, float tolb,\n                                lapack_int* k, lapack_int* l,\n                                lapack_complex_float* u, lapack_int ldu,\n                                lapack_complex_float* v, lapack_int ldv,\n                                lapack_complex_float* q, lapack_int ldq,\n                                lapack_int* iwork, float* rwork,\n                                lapack_complex_float* tau,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zggsvp_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int p,\n                                lapack_int n, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* b,\n                                lapack_int ldb, double tola, double tolb,\n                                lapack_int* k, lapack_int* l,\n                                lapack_complex_double* u, lapack_int ldu,\n                                lapack_complex_double* v, lapack_int ldv,\n                                lapack_complex_double* q, lapack_int ldq,\n                                lapack_int* iwork, double* rwork,\n                                lapack_complex_double* tau,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_sgtcon_work( char norm, lapack_int n, const float* dl,\n                                const float* d, const float* du,\n                                const float* du2, const lapack_int* ipiv,\n                                float anorm, float* rcond, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dgtcon_work( char norm, lapack_int n, const double* dl,\n                                const double* d, const double* du,\n                                const double* du2, const lapack_int* ipiv,\n                                double anorm, double* rcond, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_cgtcon_work( char norm, lapack_int n,\n                                const lapack_complex_float* dl,\n                                const lapack_complex_float* d,\n                                const lapack_complex_float* du,\n                                const lapack_complex_float* du2,\n                                const lapack_int* ipiv, float anorm,\n                                float* rcond, lapack_complex_float* work );\nlapack_int LAPACKE_zgtcon_work( char norm, lapack_int n,\n                                const lapack_complex_double* dl,\n                                const lapack_complex_double* d,\n                                const lapack_complex_double* du,\n                                const lapack_complex_double* du2,\n                                const lapack_int* ipiv, double anorm,\n                                double* rcond, lapack_complex_double* work );\n\nlapack_int LAPACKE_sgtrfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const float* dl,\n                                const float* d, const float* du,\n                                const float* dlf, const float* df,\n                                const float* duf, const float* du2,\n                                const lapack_int* ipiv, const float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* ferr, float* berr, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dgtrfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const double* dl,\n                                const double* d, const double* du,\n                                const double* dlf, const double* df,\n                                const double* duf, const double* du2,\n                                const lapack_int* ipiv, const double* b,\n                                lapack_int ldb, double* x, lapack_int ldx,\n                                double* ferr, double* berr, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_cgtrfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* dl,\n                                const lapack_complex_float* d,\n                                const lapack_complex_float* du,\n                                const lapack_complex_float* dlf,\n                                const lapack_complex_float* df,\n                                const lapack_complex_float* duf,\n                                const lapack_complex_float* du2,\n                                const lapack_int* ipiv,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zgtrfs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs,\n                                const lapack_complex_double* dl,\n                                const lapack_complex_double* d,\n                                const lapack_complex_double* du,\n                                const lapack_complex_double* dlf,\n                                const lapack_complex_double* df,\n                                const lapack_complex_double* duf,\n                                const lapack_complex_double* du2,\n                                const lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sgtsv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               float* dl, float* d, float* du, float* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_dgtsv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               double* dl, double* d, double* du, double* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_cgtsv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               lapack_complex_float* dl,\n                               lapack_complex_float* d,\n                               lapack_complex_float* du,\n                               lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zgtsv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               lapack_complex_double* dl,\n                               lapack_complex_double* d,\n                               lapack_complex_double* du,\n                               lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_sgtsvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int nrhs, const float* dl,\n                                const float* d, const float* du, float* dlf,\n                                float* df, float* duf, float* du2,\n                                lapack_int* ipiv, const float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* rcond, float* ferr, float* berr,\n                                float* work, lapack_int* iwork );\nlapack_int LAPACKE_dgtsvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int nrhs, const double* dl,\n                                const double* d, const double* du, double* dlf,\n                                double* df, double* duf, double* du2,\n                                lapack_int* ipiv, const double* b,\n                                lapack_int ldb, double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_cgtsvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_float* dl,\n                                const lapack_complex_float* d,\n                                const lapack_complex_float* du,\n                                lapack_complex_float* dlf,\n                                lapack_complex_float* df,\n                                lapack_complex_float* duf,\n                                lapack_complex_float* du2, lapack_int* ipiv,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* rcond, float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zgtsvx_work( int matrix_order, char fact, char trans,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_double* dl,\n                                const lapack_complex_double* d,\n                                const lapack_complex_double* du,\n                                lapack_complex_double* dlf,\n                                lapack_complex_double* df,\n                                lapack_complex_double* duf,\n                                lapack_complex_double* du2, lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sgttrf_work( lapack_int n, float* dl, float* d, float* du,\n                                float* du2, lapack_int* ipiv );\nlapack_int LAPACKE_dgttrf_work( lapack_int n, double* dl, double* d, double* du,\n                                double* du2, lapack_int* ipiv );\nlapack_int LAPACKE_cgttrf_work( lapack_int n, lapack_complex_float* dl,\n                                lapack_complex_float* d,\n                                lapack_complex_float* du,\n                                lapack_complex_float* du2, lapack_int* ipiv );\nlapack_int LAPACKE_zgttrf_work( lapack_int n, lapack_complex_double* dl,\n                                lapack_complex_double* d,\n                                lapack_complex_double* du,\n                                lapack_complex_double* du2, lapack_int* ipiv );\n\nlapack_int LAPACKE_sgttrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const float* dl,\n                                const float* d, const float* du,\n                                const float* du2, const lapack_int* ipiv,\n                                float* b, lapack_int ldb );\nlapack_int LAPACKE_dgttrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const double* dl,\n                                const double* d, const double* du,\n                                const double* du2, const lapack_int* ipiv,\n                                double* b, lapack_int ldb );\nlapack_int LAPACKE_cgttrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* dl,\n                                const lapack_complex_float* d,\n                                const lapack_complex_float* du,\n                                const lapack_complex_float* du2,\n                                const lapack_int* ipiv, lapack_complex_float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_zgttrs_work( int matrix_order, char trans, lapack_int n,\n                                lapack_int nrhs,\n                                const lapack_complex_double* dl,\n                                const lapack_complex_double* d,\n                                const lapack_complex_double* du,\n                                const lapack_complex_double* du2,\n                                const lapack_int* ipiv,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_chbev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_int kd,\n                               lapack_complex_float* ab, lapack_int ldab,\n                               float* w, lapack_complex_float* z,\n                               lapack_int ldz, lapack_complex_float* work,\n                               float* rwork );\nlapack_int LAPACKE_zhbev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_int kd,\n                               lapack_complex_double* ab, lapack_int ldab,\n                               double* w, lapack_complex_double* z,\n                               lapack_int ldz, lapack_complex_double* work,\n                               double* rwork );\n\nlapack_int LAPACKE_chbevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_int kd,\n                                lapack_complex_float* ab, lapack_int ldab,\n                                float* w, lapack_complex_float* z,\n                                lapack_int ldz, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork,\n                                lapack_int lrwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_zhbevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_int kd,\n                                lapack_complex_double* ab, lapack_int ldab,\n                                double* w, lapack_complex_double* z,\n                                lapack_int ldz, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork,\n                                lapack_int lrwork, lapack_int* iwork,\n                                lapack_int liwork );\n\nlapack_int LAPACKE_chbevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, lapack_int kd,\n                                lapack_complex_float* ab, lapack_int ldab,\n                                lapack_complex_float* q, lapack_int ldq,\n                                float vl, float vu, lapack_int il,\n                                lapack_int iu, float abstol, lapack_int* m,\n                                float* w, lapack_complex_float* z,\n                                lapack_int ldz, lapack_complex_float* work,\n                                float* rwork, lapack_int* iwork,\n                                lapack_int* ifail );\nlapack_int LAPACKE_zhbevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, lapack_int kd,\n                                lapack_complex_double* ab, lapack_int ldab,\n                                lapack_complex_double* q, lapack_int ldq,\n                                double vl, double vu, lapack_int il,\n                                lapack_int iu, double abstol, lapack_int* m,\n                                double* w, lapack_complex_double* z,\n                                lapack_int ldz, lapack_complex_double* work,\n                                double* rwork, lapack_int* iwork,\n                                lapack_int* ifail );\n\nlapack_int LAPACKE_chbgst_work( int matrix_order, char vect, char uplo,\n                                lapack_int n, lapack_int ka, lapack_int kb,\n                                lapack_complex_float* ab, lapack_int ldab,\n                                const lapack_complex_float* bb, lapack_int ldbb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zhbgst_work( int matrix_order, char vect, char uplo,\n                                lapack_int n, lapack_int ka, lapack_int kb,\n                                lapack_complex_double* ab, lapack_int ldab,\n                                const lapack_complex_double* bb,\n                                lapack_int ldbb, lapack_complex_double* x,\n                                lapack_int ldx, lapack_complex_double* work,\n                                double* rwork );\n\nlapack_int LAPACKE_chbgv_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_int ka, lapack_int kb,\n                               lapack_complex_float* ab, lapack_int ldab,\n                               lapack_complex_float* bb, lapack_int ldbb,\n                               float* w, lapack_complex_float* z,\n                               lapack_int ldz, lapack_complex_float* work,\n                               float* rwork );\nlapack_int LAPACKE_zhbgv_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_int ka, lapack_int kb,\n                               lapack_complex_double* ab, lapack_int ldab,\n                               lapack_complex_double* bb, lapack_int ldbb,\n                               double* w, lapack_complex_double* z,\n                               lapack_int ldz, lapack_complex_double* work,\n                               double* rwork );\n\nlapack_int LAPACKE_chbgvd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_int ka, lapack_int kb,\n                                lapack_complex_float* ab, lapack_int ldab,\n                                lapack_complex_float* bb, lapack_int ldbb,\n                                float* w, lapack_complex_float* z,\n                                lapack_int ldz, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork,\n                                lapack_int lrwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_zhbgvd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_int ka, lapack_int kb,\n                                lapack_complex_double* ab, lapack_int ldab,\n                                lapack_complex_double* bb, lapack_int ldbb,\n                                double* w, lapack_complex_double* z,\n                                lapack_int ldz, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork,\n                                lapack_int lrwork, lapack_int* iwork,\n                                lapack_int liwork );\n\nlapack_int LAPACKE_chbgvx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, lapack_int ka,\n                                lapack_int kb, lapack_complex_float* ab,\n                                lapack_int ldab, lapack_complex_float* bb,\n                                lapack_int ldbb, lapack_complex_float* q,\n                                lapack_int ldq, float vl, float vu,\n                                lapack_int il, lapack_int iu, float abstol,\n                                lapack_int* m, float* w,\n                                lapack_complex_float* z, lapack_int ldz,\n                                lapack_complex_float* work, float* rwork,\n                                lapack_int* iwork, lapack_int* ifail );\nlapack_int LAPACKE_zhbgvx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, lapack_int ka,\n                                lapack_int kb, lapack_complex_double* ab,\n                                lapack_int ldab, lapack_complex_double* bb,\n                                lapack_int ldbb, lapack_complex_double* q,\n                                lapack_int ldq, double vl, double vu,\n                                lapack_int il, lapack_int iu, double abstol,\n                                lapack_int* m, double* w,\n                                lapack_complex_double* z, lapack_int ldz,\n                                lapack_complex_double* work, double* rwork,\n                                lapack_int* iwork, lapack_int* ifail );\n\nlapack_int LAPACKE_chbtrd_work( int matrix_order, char vect, char uplo,\n                                lapack_int n, lapack_int kd,\n                                lapack_complex_float* ab, lapack_int ldab,\n                                float* d, float* e, lapack_complex_float* q,\n                                lapack_int ldq, lapack_complex_float* work );\nlapack_int LAPACKE_zhbtrd_work( int matrix_order, char vect, char uplo,\n                                lapack_int n, lapack_int kd,\n                                lapack_complex_double* ab, lapack_int ldab,\n                                double* d, double* e, lapack_complex_double* q,\n                                lapack_int ldq, lapack_complex_double* work );\n\nlapack_int LAPACKE_checon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_int* ipiv, float anorm,\n                                float* rcond, lapack_complex_float* work );\nlapack_int LAPACKE_zhecon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_int* ipiv, double anorm,\n                                double* rcond, lapack_complex_double* work );\n\nlapack_int LAPACKE_cheequb_work( int matrix_order, char uplo, lapack_int n,\n                                 const lapack_complex_float* a, lapack_int lda,\n                                 float* s, float* scond, float* amax,\n                                 lapack_complex_float* work );\nlapack_int LAPACKE_zheequb_work( int matrix_order, char uplo, lapack_int n,\n                                 const lapack_complex_double* a, lapack_int lda,\n                                 double* s, double* scond, double* amax,\n                                 lapack_complex_double* work );\n\nlapack_int LAPACKE_cheev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_complex_float* a,\n                               lapack_int lda, float* w,\n                               lapack_complex_float* work, lapack_int lwork,\n                               float* rwork );\nlapack_int LAPACKE_zheev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_complex_double* a,\n                               lapack_int lda, double* w,\n                               lapack_complex_double* work, lapack_int lwork,\n                               double* rwork );\n\nlapack_int LAPACKE_cheevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_complex_float* a,\n                                lapack_int lda, float* w,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork, lapack_int lrwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_zheevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_complex_double* a,\n                                lapack_int lda, double* w,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork, lapack_int lrwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_cheevr_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                float vl, float vu, lapack_int il,\n                                lapack_int iu, float abstol, lapack_int* m,\n                                float* w, lapack_complex_float* z,\n                                lapack_int ldz, lapack_int* isuppz,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork, lapack_int lrwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_zheevr_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                double vl, double vu, lapack_int il,\n                                lapack_int iu, double abstol, lapack_int* m,\n                                double* w, lapack_complex_double* z,\n                                lapack_int ldz, lapack_int* isuppz,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork, lapack_int lrwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_cheevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                float vl, float vu, lapack_int il,\n                                lapack_int iu, float abstol, lapack_int* m,\n                                float* w, lapack_complex_float* z,\n                                lapack_int ldz, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork,\n                                lapack_int* iwork, lapack_int* ifail );\nlapack_int LAPACKE_zheevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                double vl, double vu, lapack_int il,\n                                lapack_int iu, double abstol, lapack_int* m,\n                                double* w, lapack_complex_double* z,\n                                lapack_int ldz, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork,\n                                lapack_int* iwork, lapack_int* ifail );\n\nlapack_int LAPACKE_chegst_work( int matrix_order, lapack_int itype, char uplo,\n                                lapack_int n, lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_zhegst_work( int matrix_order, lapack_int itype, char uplo,\n                                lapack_int n, lapack_complex_double* a,\n                                lapack_int lda, const lapack_complex_double* b,\n                                lapack_int ldb );\n\nlapack_int LAPACKE_chegv_work( int matrix_order, lapack_int itype, char jobz,\n                               char uplo, lapack_int n, lapack_complex_float* a,\n                               lapack_int lda, lapack_complex_float* b,\n                               lapack_int ldb, float* w,\n                               lapack_complex_float* work, lapack_int lwork,\n                               float* rwork );\nlapack_int LAPACKE_zhegv_work( int matrix_order, lapack_int itype, char jobz,\n                               char uplo, lapack_int n,\n                               lapack_complex_double* a, lapack_int lda,\n                               lapack_complex_double* b, lapack_int ldb,\n                               double* w, lapack_complex_double* work,\n                               lapack_int lwork, double* rwork );\n\nlapack_int LAPACKE_chegvd_work( int matrix_order, lapack_int itype, char jobz,\n                                char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb,\n                                float* w, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork,\n                                lapack_int lrwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_zhegvd_work( int matrix_order, lapack_int itype, char jobz,\n                                char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                double* w, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork,\n                                lapack_int lrwork, lapack_int* iwork,\n                                lapack_int liwork );\n\nlapack_int LAPACKE_chegvx_work( int matrix_order, lapack_int itype, char jobz,\n                                char range, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb,\n                                float vl, float vu, lapack_int il,\n                                lapack_int iu, float abstol, lapack_int* m,\n                                float* w, lapack_complex_float* z,\n                                lapack_int ldz, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork,\n                                lapack_int* iwork, lapack_int* ifail );\nlapack_int LAPACKE_zhegvx_work( int matrix_order, lapack_int itype, char jobz,\n                                char range, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                double vl, double vu, lapack_int il,\n                                lapack_int iu, double abstol, lapack_int* m,\n                                double* w, lapack_complex_double* z,\n                                lapack_int ldz, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork,\n                                lapack_int* iwork, lapack_int* ifail );\n\nlapack_int LAPACKE_cherfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* af,\n                                lapack_int ldaf, const lapack_int* ipiv,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zherfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_double* a,\n                                lapack_int lda, const lapack_complex_double* af,\n                                lapack_int ldaf, const lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_cherfsx_work( int matrix_order, char uplo, char equed,\n                                 lapack_int n, lapack_int nrhs,\n                                 const lapack_complex_float* a, lapack_int lda,\n                                 const lapack_complex_float* af,\n                                 lapack_int ldaf, const lapack_int* ipiv,\n                                 const float* s, const lapack_complex_float* b,\n                                 lapack_int ldb, lapack_complex_float* x,\n                                 lapack_int ldx, float* rcond, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, lapack_complex_float* work,\n                                 float* rwork );\nlapack_int LAPACKE_zherfsx_work( int matrix_order, char uplo, char equed,\n                                 lapack_int n, lapack_int nrhs,\n                                 const lapack_complex_double* a, lapack_int lda,\n                                 const lapack_complex_double* af,\n                                 lapack_int ldaf, const lapack_int* ipiv,\n                                 const double* s,\n                                 const lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* x, lapack_int ldx,\n                                 double* rcond, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, lapack_complex_double* work,\n                                 double* rwork );\n\nlapack_int LAPACKE_chesv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_float* a,\n                               lapack_int lda, lapack_int* ipiv,\n                               lapack_complex_float* b, lapack_int ldb,\n                               lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zhesv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_double* a,\n                               lapack_int lda, lapack_int* ipiv,\n                               lapack_complex_double* b, lapack_int ldb,\n                               lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_chesvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* af, lapack_int ldaf,\n                                lapack_int* ipiv, const lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* x,\n                                lapack_int ldx, float* rcond, float* ferr,\n                                float* berr, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork );\nlapack_int LAPACKE_zhesvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* af, lapack_int ldaf,\n                                lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork );\n\nlapack_int LAPACKE_chesvxx_work( int matrix_order, char fact, char uplo,\n                                 lapack_int n, lapack_int nrhs,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 lapack_complex_float* af, lapack_int ldaf,\n                                 lapack_int* ipiv, char* equed, float* s,\n                                 lapack_complex_float* b, lapack_int ldb,\n                                 lapack_complex_float* x, lapack_int ldx,\n                                 float* rcond, float* rpvgrw, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, lapack_complex_float* work,\n                                 float* rwork );\nlapack_int LAPACKE_zhesvxx_work( int matrix_order, char fact, char uplo,\n                                 lapack_int n, lapack_int nrhs,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 lapack_complex_double* af, lapack_int ldaf,\n                                 lapack_int* ipiv, char* equed, double* s,\n                                 lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* x, lapack_int ldx,\n                                 double* rcond, double* rpvgrw, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, lapack_complex_double* work,\n                                 double* rwork );\n\nlapack_int LAPACKE_chetrd_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                float* d, float* e, lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zhetrd_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                double* d, double* e,\n                                lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_chetrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_int* ipiv, lapack_complex_float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_zhetrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int* ipiv, lapack_complex_double* work,\n                                lapack_int lwork );\n\nlapack_int LAPACKE_chetri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                const lapack_int* ipiv,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zhetri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                const lapack_int* ipiv,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_chetrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* a,\n                                lapack_int lda, const lapack_int* ipiv,\n                                lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zhetrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_double* a,\n                                lapack_int lda, const lapack_int* ipiv,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_chfrk_work( int matrix_order, char transr, char uplo,\n                               char trans, lapack_int n, lapack_int k,\n                               float alpha, const lapack_complex_float* a,\n                               lapack_int lda, float beta,\n                               lapack_complex_float* c );\nlapack_int LAPACKE_zhfrk_work( int matrix_order, char transr, char uplo,\n                               char trans, lapack_int n, lapack_int k,\n                               double alpha, const lapack_complex_double* a,\n                               lapack_int lda, double beta,\n                               lapack_complex_double* c );\n\nlapack_int LAPACKE_shgeqz_work( int matrix_order, char job, char compq,\n                                char compz, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, float* h, lapack_int ldh,\n                                float* t, lapack_int ldt, float* alphar,\n                                float* alphai, float* beta, float* q,\n                                lapack_int ldq, float* z, lapack_int ldz,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dhgeqz_work( int matrix_order, char job, char compq,\n                                char compz, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, double* h, lapack_int ldh,\n                                double* t, lapack_int ldt, double* alphar,\n                                double* alphai, double* beta, double* q,\n                                lapack_int ldq, double* z, lapack_int ldz,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_chgeqz_work( int matrix_order, char job, char compq,\n                                char compz, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, lapack_complex_float* h,\n                                lapack_int ldh, lapack_complex_float* t,\n                                lapack_int ldt, lapack_complex_float* alpha,\n                                lapack_complex_float* beta,\n                                lapack_complex_float* q, lapack_int ldq,\n                                lapack_complex_float* z, lapack_int ldz,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork );\nlapack_int LAPACKE_zhgeqz_work( int matrix_order, char job, char compq,\n                                char compz, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, lapack_complex_double* h,\n                                lapack_int ldh, lapack_complex_double* t,\n                                lapack_int ldt, lapack_complex_double* alpha,\n                                lapack_complex_double* beta,\n                                lapack_complex_double* q, lapack_int ldq,\n                                lapack_complex_double* z, lapack_int ldz,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork );\n\nlapack_int LAPACKE_chpcon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_float* ap,\n                                const lapack_int* ipiv, float anorm,\n                                float* rcond, lapack_complex_float* work );\nlapack_int LAPACKE_zhpcon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_double* ap,\n                                const lapack_int* ipiv, double anorm,\n                                double* rcond, lapack_complex_double* work );\n\nlapack_int LAPACKE_chpev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_complex_float* ap, float* w,\n                               lapack_complex_float* z, lapack_int ldz,\n                               lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zhpev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_complex_double* ap,\n                               double* w, lapack_complex_double* z,\n                               lapack_int ldz, lapack_complex_double* work,\n                               double* rwork );\n\nlapack_int LAPACKE_chpevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_complex_float* ap,\n                                float* w, lapack_complex_float* z,\n                                lapack_int ldz, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork,\n                                lapack_int lrwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_zhpevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_complex_double* ap,\n                                double* w, lapack_complex_double* z,\n                                lapack_int ldz, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork,\n                                lapack_int lrwork, lapack_int* iwork,\n                                lapack_int liwork );\n\nlapack_int LAPACKE_chpevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n,\n                                lapack_complex_float* ap, float vl, float vu,\n                                lapack_int il, lapack_int iu, float abstol,\n                                lapack_int* m, float* w,\n                                lapack_complex_float* z, lapack_int ldz,\n                                lapack_complex_float* work, float* rwork,\n                                lapack_int* iwork, lapack_int* ifail );\nlapack_int LAPACKE_zhpevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n,\n                                lapack_complex_double* ap, double vl, double vu,\n                                lapack_int il, lapack_int iu, double abstol,\n                                lapack_int* m, double* w,\n                                lapack_complex_double* z, lapack_int ldz,\n                                lapack_complex_double* work, double* rwork,\n                                lapack_int* iwork, lapack_int* ifail );\n\nlapack_int LAPACKE_chpgst_work( int matrix_order, lapack_int itype, char uplo,\n                                lapack_int n, lapack_complex_float* ap,\n                                const lapack_complex_float* bp );\nlapack_int LAPACKE_zhpgst_work( int matrix_order, lapack_int itype, char uplo,\n                                lapack_int n, lapack_complex_double* ap,\n                                const lapack_complex_double* bp );\n\nlapack_int LAPACKE_chpgv_work( int matrix_order, lapack_int itype, char jobz,\n                               char uplo, lapack_int n,\n                               lapack_complex_float* ap,\n                               lapack_complex_float* bp, float* w,\n                               lapack_complex_float* z, lapack_int ldz,\n                               lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zhpgv_work( int matrix_order, lapack_int itype, char jobz,\n                               char uplo, lapack_int n,\n                               lapack_complex_double* ap,\n                               lapack_complex_double* bp, double* w,\n                               lapack_complex_double* z, lapack_int ldz,\n                               lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_chpgvd_work( int matrix_order, lapack_int itype, char jobz,\n                                char uplo, lapack_int n,\n                                lapack_complex_float* ap,\n                                lapack_complex_float* bp, float* w,\n                                lapack_complex_float* z, lapack_int ldz,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork, lapack_int lrwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_zhpgvd_work( int matrix_order, lapack_int itype, char jobz,\n                                char uplo, lapack_int n,\n                                lapack_complex_double* ap,\n                                lapack_complex_double* bp, double* w,\n                                lapack_complex_double* z, lapack_int ldz,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork, lapack_int lrwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_chpgvx_work( int matrix_order, lapack_int itype, char jobz,\n                                char range, char uplo, lapack_int n,\n                                lapack_complex_float* ap,\n                                lapack_complex_float* bp, float vl, float vu,\n                                lapack_int il, lapack_int iu, float abstol,\n                                lapack_int* m, float* w,\n                                lapack_complex_float* z, lapack_int ldz,\n                                lapack_complex_float* work, float* rwork,\n                                lapack_int* iwork, lapack_int* ifail );\nlapack_int LAPACKE_zhpgvx_work( int matrix_order, lapack_int itype, char jobz,\n                                char range, char uplo, lapack_int n,\n                                lapack_complex_double* ap,\n                                lapack_complex_double* bp, double vl, double vu,\n                                lapack_int il, lapack_int iu, double abstol,\n                                lapack_int* m, double* w,\n                                lapack_complex_double* z, lapack_int ldz,\n                                lapack_complex_double* work, double* rwork,\n                                lapack_int* iwork, lapack_int* ifail );\n\nlapack_int LAPACKE_chprfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* ap,\n                                const lapack_complex_float* afp,\n                                const lapack_int* ipiv,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zhprfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs,\n                                const lapack_complex_double* ap,\n                                const lapack_complex_double* afp,\n                                const lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_chpsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_float* ap,\n                               lapack_int* ipiv, lapack_complex_float* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_zhpsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_double* ap,\n                               lapack_int* ipiv, lapack_complex_double* b,\n                               lapack_int ldb );\n\nlapack_int LAPACKE_chpsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_float* ap,\n                                lapack_complex_float* afp, lapack_int* ipiv,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* rcond, float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zhpsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_double* ap,\n                                lapack_complex_double* afp, lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_chptrd_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* ap, float* d, float* e,\n                                lapack_complex_float* tau );\nlapack_int LAPACKE_zhptrd_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* ap, double* d, double* e,\n                                lapack_complex_double* tau );\n\nlapack_int LAPACKE_chptrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* ap, lapack_int* ipiv );\nlapack_int LAPACKE_zhptrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* ap, lapack_int* ipiv );\n\nlapack_int LAPACKE_chptri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* ap,\n                                const lapack_int* ipiv,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zhptri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* ap,\n                                const lapack_int* ipiv,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_chptrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* ap,\n                                const lapack_int* ipiv, lapack_complex_float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_zhptrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs,\n                                const lapack_complex_double* ap,\n                                const lapack_int* ipiv,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_shsein_work( int matrix_order, char job, char eigsrc,\n                                char initv, lapack_logical* select,\n                                lapack_int n, const float* h, lapack_int ldh,\n                                float* wr, const float* wi, float* vl,\n                                lapack_int ldvl, float* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m, float* work,\n                                lapack_int* ifaill, lapack_int* ifailr );\nlapack_int LAPACKE_dhsein_work( int matrix_order, char job, char eigsrc,\n                                char initv, lapack_logical* select,\n                                lapack_int n, const double* h, lapack_int ldh,\n                                double* wr, const double* wi, double* vl,\n                                lapack_int ldvl, double* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m, double* work,\n                                lapack_int* ifaill, lapack_int* ifailr );\nlapack_int LAPACKE_chsein_work( int matrix_order, char job, char eigsrc,\n                                char initv, const lapack_logical* select,\n                                lapack_int n, const lapack_complex_float* h,\n                                lapack_int ldh, lapack_complex_float* w,\n                                lapack_complex_float* vl, lapack_int ldvl,\n                                lapack_complex_float* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m,\n                                lapack_complex_float* work, float* rwork,\n                                lapack_int* ifaill, lapack_int* ifailr );\nlapack_int LAPACKE_zhsein_work( int matrix_order, char job, char eigsrc,\n                                char initv, const lapack_logical* select,\n                                lapack_int n, const lapack_complex_double* h,\n                                lapack_int ldh, lapack_complex_double* w,\n                                lapack_complex_double* vl, lapack_int ldvl,\n                                lapack_complex_double* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m,\n                                lapack_complex_double* work, double* rwork,\n                                lapack_int* ifaill, lapack_int* ifailr );\n\nlapack_int LAPACKE_shseqr_work( int matrix_order, char job, char compz,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                float* h, lapack_int ldh, float* wr, float* wi,\n                                float* z, lapack_int ldz, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dhseqr_work( int matrix_order, char job, char compz,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                double* h, lapack_int ldh, double* wr,\n                                double* wi, double* z, lapack_int ldz,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_chseqr_work( int matrix_order, char job, char compz,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                lapack_complex_float* h, lapack_int ldh,\n                                lapack_complex_float* w,\n                                lapack_complex_float* z, lapack_int ldz,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zhseqr_work( int matrix_order, char job, char compz,\n                                lapack_int n, lapack_int ilo, lapack_int ihi,\n                                lapack_complex_double* h, lapack_int ldh,\n                                lapack_complex_double* w,\n                                lapack_complex_double* z, lapack_int ldz,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_clacgv_work( lapack_int n, lapack_complex_float* x,\n                                lapack_int incx );\nlapack_int LAPACKE_zlacgv_work( lapack_int n, lapack_complex_double* x,\n                                lapack_int incx );\n\nlapack_int LAPACKE_slacpy_work( int matrix_order, char uplo, lapack_int m,\n                                lapack_int n, const float* a, lapack_int lda,\n                                float* b, lapack_int ldb );\nlapack_int LAPACKE_dlacpy_work( int matrix_order, char uplo, lapack_int m,\n                                lapack_int n, const double* a, lapack_int lda,\n                                double* b, lapack_int ldb );\nlapack_int LAPACKE_clacpy_work( int matrix_order, char uplo, lapack_int m,\n                                lapack_int n, const lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_zlacpy_work( int matrix_order, char uplo, lapack_int m,\n                                lapack_int n, const lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* b,\n                                lapack_int ldb );\n\nlapack_int LAPACKE_zlag2c_work( int matrix_order, lapack_int m, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_float* sa, lapack_int ldsa );\n\nlapack_int LAPACKE_slag2d_work( int matrix_order, lapack_int m, lapack_int n,\n                                const float* sa, lapack_int ldsa, double* a,\n                                lapack_int lda );\n\nlapack_int LAPACKE_dlag2s_work( int matrix_order, lapack_int m, lapack_int n,\n                                const double* a, lapack_int lda, float* sa,\n                                lapack_int ldsa );\n\nlapack_int LAPACKE_clag2z_work( int matrix_order, lapack_int m, lapack_int n,\n                                const lapack_complex_float* sa, lapack_int ldsa,\n                                lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_slagge_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku, const float* d,\n                                float* a, lapack_int lda, lapack_int* iseed,\n                                float* work );\nlapack_int LAPACKE_dlagge_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku, const double* d,\n                                double* a, lapack_int lda, lapack_int* iseed,\n                                double* work );\nlapack_int LAPACKE_clagge_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku, const float* d,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_int* iseed, lapack_complex_float* work );\nlapack_int LAPACKE_zlagge_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int kl, lapack_int ku, const double* d,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int* iseed,\n                                lapack_complex_double* work );\n                                \nlapack_int LAPACKE_claghe_work( int matrix_order, lapack_int n, lapack_int k,\n                                const float* d, lapack_complex_float* a,\n                                lapack_int lda, lapack_int* iseed,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zlaghe_work( int matrix_order, lapack_int n, lapack_int k,\n                                const double* d, lapack_complex_double* a,\n                                lapack_int lda, lapack_int* iseed,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_slagsy_work( int matrix_order, lapack_int n, lapack_int k,\n                                const float* d, float* a, lapack_int lda,\n                                lapack_int* iseed, float* work );\nlapack_int LAPACKE_dlagsy_work( int matrix_order, lapack_int n, lapack_int k,\n                                const double* d, double* a, lapack_int lda,\n                                lapack_int* iseed, double* work );\nlapack_int LAPACKE_clagsy_work( int matrix_order, lapack_int n, lapack_int k,\n                                const float* d, lapack_complex_float* a,\n                                lapack_int lda, lapack_int* iseed,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zlagsy_work( int matrix_order, lapack_int n, lapack_int k,\n                                const double* d, lapack_complex_double* a,\n                                lapack_int lda, lapack_int* iseed,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_slapmr_work( int matrix_order, lapack_logical forwrd,\n                                lapack_int m, lapack_int n, float* x,\n                                lapack_int ldx, lapack_int* k );\nlapack_int LAPACKE_dlapmr_work( int matrix_order, lapack_logical forwrd,\n                                lapack_int m, lapack_int n, double* x,\n                                lapack_int ldx, lapack_int* k );\nlapack_int LAPACKE_clapmr_work( int matrix_order, lapack_logical forwrd,\n                                lapack_int m, lapack_int n,\n                                lapack_complex_float* x, lapack_int ldx,\n                                lapack_int* k );\nlapack_int LAPACKE_zlapmr_work( int matrix_order, lapack_logical forwrd,\n                                lapack_int m, lapack_int n,\n                                lapack_complex_double* x, lapack_int ldx,\n                                lapack_int* k );\n\nlapack_int LAPACKE_slartgp_work( float f, float g, float* cs, float* sn,\n                                 float* r );\nlapack_int LAPACKE_dlartgp_work( double f, double g, double* cs, double* sn,\n                                 double* r );\n\nlapack_int LAPACKE_slartgs_work( float x, float y, float sigma, float* cs,\n                                 float* sn );\nlapack_int LAPACKE_dlartgs_work( double x, double y, double sigma, double* cs,\n                                 double* sn );\n                                \nfloat LAPACKE_slapy2_work( float x, float y );\ndouble LAPACKE_dlapy2_work( double x, double y );\n\nfloat LAPACKE_slapy3_work( float x, float y, float z );\ndouble LAPACKE_dlapy3_work( double x, double y, double z );\n\nfloat LAPACKE_slamch_work( char cmach );\ndouble LAPACKE_dlamch_work( char cmach );\n\nfloat LAPACKE_slange_work( int matrix_order, char norm, lapack_int m,\n                                lapack_int n, const float* a, lapack_int lda,\n                                float* work );\ndouble LAPACKE_dlange_work( int matrix_order, char norm, lapack_int m,\n                                lapack_int n, const double* a, lapack_int lda,\n                                double* work );\nfloat LAPACKE_clange_work( int matrix_order, char norm, lapack_int m,\n                                lapack_int n, const lapack_complex_float* a,\n                                lapack_int lda, float* work );\ndouble LAPACKE_zlange_work( int matrix_order, char norm, lapack_int m,\n                                lapack_int n, const lapack_complex_double* a,\n                                lapack_int lda, double* work );\n\nfloat LAPACKE_clanhe_work( int matrix_order, char norm, char uplo,\n                                lapack_int n, const lapack_complex_float* a,\n                                lapack_int lda, float* work );\ndouble LAPACKE_zlanhe_work( int matrix_order, char norm, char uplo,\n                                lapack_int n, const lapack_complex_double* a,\n                                lapack_int lda, double* work );\n\nfloat LAPACKE_slansy_work( int matrix_order, char norm, char uplo,\n                                lapack_int n, const float* a, lapack_int lda,\n                                float* work );\ndouble LAPACKE_dlansy_work( int matrix_order, char norm, char uplo,\n                                lapack_int n, const double* a, lapack_int lda,\n                                double* work );\nfloat LAPACKE_clansy_work( int matrix_order, char norm, char uplo,\n                                lapack_int n, const lapack_complex_float* a,\n                                lapack_int lda, float* work );\ndouble LAPACKE_zlansy_work( int matrix_order, char norm, char uplo,\n                                lapack_int n, const lapack_complex_double* a,\n                                lapack_int lda, double* work );\n\nfloat LAPACKE_slantr_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int m, lapack_int n, const float* a,\n                                lapack_int lda, float* work );\ndouble LAPACKE_dlantr_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int m, lapack_int n,\n                                const double* a, lapack_int lda, double* work );\nfloat LAPACKE_clantr_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int m, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                float* work );\ndouble LAPACKE_zlantr_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int m, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                double* work );\n\nlapack_int LAPACKE_slarfb_work( int matrix_order, char side, char trans,\n                                char direct, char storev, lapack_int m,\n                                lapack_int n, lapack_int k, const float* v,\n                                lapack_int ldv, const float* t, lapack_int ldt,\n                                float* c, lapack_int ldc, float* work,\n                                lapack_int ldwork );\nlapack_int LAPACKE_dlarfb_work( int matrix_order, char side, char trans,\n                                char direct, char storev, lapack_int m,\n                                lapack_int n, lapack_int k, const double* v,\n                                lapack_int ldv, const double* t, lapack_int ldt,\n                                double* c, lapack_int ldc, double* work,\n                                lapack_int ldwork );\nlapack_int LAPACKE_clarfb_work( int matrix_order, char side, char trans,\n                                char direct, char storev, lapack_int m,\n                                lapack_int n, lapack_int k,\n                                const lapack_complex_float* v, lapack_int ldv,\n                                const lapack_complex_float* t, lapack_int ldt,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work, lapack_int ldwork );\nlapack_int LAPACKE_zlarfb_work( int matrix_order, char side, char trans,\n                                char direct, char storev, lapack_int m,\n                                lapack_int n, lapack_int k,\n                                const lapack_complex_double* v, lapack_int ldv,\n                                const lapack_complex_double* t, lapack_int ldt,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work,\n                                lapack_int ldwork );\n\nlapack_int LAPACKE_slarfg_work( lapack_int n, float* alpha, float* x,\n                                lapack_int incx, float* tau );\nlapack_int LAPACKE_dlarfg_work( lapack_int n, double* alpha, double* x,\n                                lapack_int incx, double* tau );\nlapack_int LAPACKE_clarfg_work( lapack_int n, lapack_complex_float* alpha,\n                                lapack_complex_float* x, lapack_int incx,\n                                lapack_complex_float* tau );\nlapack_int LAPACKE_zlarfg_work( lapack_int n, lapack_complex_double* alpha,\n                                lapack_complex_double* x, lapack_int incx,\n                                lapack_complex_double* tau );\n\nlapack_int LAPACKE_slarft_work( int matrix_order, char direct, char storev,\n                                lapack_int n, lapack_int k, const float* v,\n                                lapack_int ldv, const float* tau, float* t,\n                                lapack_int ldt );\nlapack_int LAPACKE_dlarft_work( int matrix_order, char direct, char storev,\n                                lapack_int n, lapack_int k, const double* v,\n                                lapack_int ldv, const double* tau, double* t,\n                                lapack_int ldt );\nlapack_int LAPACKE_clarft_work( int matrix_order, char direct, char storev,\n                                lapack_int n, lapack_int k,\n                                const lapack_complex_float* v, lapack_int ldv,\n                                const lapack_complex_float* tau,\n                                lapack_complex_float* t, lapack_int ldt );\nlapack_int LAPACKE_zlarft_work( int matrix_order, char direct, char storev,\n                                lapack_int n, lapack_int k,\n                                const lapack_complex_double* v, lapack_int ldv,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* t, lapack_int ldt );\n\nlapack_int LAPACKE_slarfx_work( int matrix_order, char side, lapack_int m,\n                                lapack_int n, const float* v, float tau,\n                                float* c, lapack_int ldc, float* work );\nlapack_int LAPACKE_dlarfx_work( int matrix_order, char side, lapack_int m,\n                                lapack_int n, const double* v, double tau,\n                                double* c, lapack_int ldc, double* work );\nlapack_int LAPACKE_clarfx_work( int matrix_order, char side, lapack_int m,\n                                lapack_int n, const lapack_complex_float* v,\n                                lapack_complex_float tau,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zlarfx_work( int matrix_order, char side, lapack_int m,\n                                lapack_int n, const lapack_complex_double* v,\n                                lapack_complex_double tau,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_slarnv_work( lapack_int idist, lapack_int* iseed,\n                                lapack_int n, float* x );\nlapack_int LAPACKE_dlarnv_work( lapack_int idist, lapack_int* iseed,\n                                lapack_int n, double* x );\nlapack_int LAPACKE_clarnv_work( lapack_int idist, lapack_int* iseed,\n                                lapack_int n, lapack_complex_float* x );\nlapack_int LAPACKE_zlarnv_work( lapack_int idist, lapack_int* iseed,\n                                lapack_int n, lapack_complex_double* x );\n\nlapack_int LAPACKE_slaset_work( int matrix_order, char uplo, lapack_int m,\n                                lapack_int n, float alpha, float beta, float* a,\n                                lapack_int lda );\nlapack_int LAPACKE_dlaset_work( int matrix_order, char uplo, lapack_int m,\n                                lapack_int n, double alpha, double beta,\n                                double* a, lapack_int lda );\nlapack_int LAPACKE_claset_work( int matrix_order, char uplo, lapack_int m,\n                                lapack_int n, lapack_complex_float alpha,\n                                lapack_complex_float beta,\n                                lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_zlaset_work( int matrix_order, char uplo, lapack_int m,\n                                lapack_int n, lapack_complex_double alpha,\n                                lapack_complex_double beta,\n                                lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_slasrt_work( char id, lapack_int n, float* d );\nlapack_int LAPACKE_dlasrt_work( char id, lapack_int n, double* d );\n\nlapack_int LAPACKE_slaswp_work( int matrix_order, lapack_int n, float* a,\n                                lapack_int lda, lapack_int k1, lapack_int k2,\n                                const lapack_int* ipiv, lapack_int incx );\nlapack_int LAPACKE_dlaswp_work( int matrix_order, lapack_int n, double* a,\n                                lapack_int lda, lapack_int k1, lapack_int k2,\n                                const lapack_int* ipiv, lapack_int incx );\nlapack_int LAPACKE_claswp_work( int matrix_order, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_int k1, lapack_int k2,\n                                const lapack_int* ipiv, lapack_int incx );\nlapack_int LAPACKE_zlaswp_work( int matrix_order, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int k1, lapack_int k2,\n                                const lapack_int* ipiv, lapack_int incx );\n\nlapack_int LAPACKE_slatms_work( int matrix_order, lapack_int m, lapack_int n,\n                                char dist, lapack_int* iseed, char sym,\n                                float* d, lapack_int mode, float cond,\n                                float dmax, lapack_int kl, lapack_int ku,\n                                char pack, float* a, lapack_int lda,\n                                float* work );\nlapack_int LAPACKE_dlatms_work( int matrix_order, lapack_int m, lapack_int n,\n                                char dist, lapack_int* iseed, char sym,\n                                double* d, lapack_int mode, double cond,\n                                double dmax, lapack_int kl, lapack_int ku,\n                                char pack, double* a, lapack_int lda,\n                                double* work );\nlapack_int LAPACKE_clatms_work( int matrix_order, lapack_int m, lapack_int n,\n                                char dist, lapack_int* iseed, char sym,\n                                float* d, lapack_int mode, float cond,\n                                float dmax, lapack_int kl, lapack_int ku,\n                                char pack, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* work );\nlapack_int LAPACKE_zlatms_work( int matrix_order, lapack_int m, lapack_int n,\n                                char dist, lapack_int* iseed, char sym,\n                                double* d, lapack_int mode, double cond,\n                                double dmax, lapack_int kl, lapack_int ku,\n                                char pack, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* work );\n\nlapack_int LAPACKE_slauum_work( int matrix_order, char uplo, lapack_int n,\n                                float* a, lapack_int lda );\nlapack_int LAPACKE_dlauum_work( int matrix_order, char uplo, lapack_int n,\n                                double* a, lapack_int lda );\nlapack_int LAPACKE_clauum_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_zlauum_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_sopgtr_work( int matrix_order, char uplo, lapack_int n,\n                                const float* ap, const float* tau, float* q,\n                                lapack_int ldq, float* work );\nlapack_int LAPACKE_dopgtr_work( int matrix_order, char uplo, lapack_int n,\n                                const double* ap, const double* tau, double* q,\n                                lapack_int ldq, double* work );\n\nlapack_int LAPACKE_sopmtr_work( int matrix_order, char side, char uplo,\n                                char trans, lapack_int m, lapack_int n,\n                                const float* ap, const float* tau, float* c,\n                                lapack_int ldc, float* work );\nlapack_int LAPACKE_dopmtr_work( int matrix_order, char side, char uplo,\n                                char trans, lapack_int m, lapack_int n,\n                                const double* ap, const double* tau, double* c,\n                                lapack_int ldc, double* work );\n\nlapack_int LAPACKE_sorgbr_work( int matrix_order, char vect, lapack_int m,\n                                lapack_int n, lapack_int k, float* a,\n                                lapack_int lda, const float* tau, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dorgbr_work( int matrix_order, char vect, lapack_int m,\n                                lapack_int n, lapack_int k, double* a,\n                                lapack_int lda, const double* tau, double* work,\n                                lapack_int lwork );\n\nlapack_int LAPACKE_sorghr_work( int matrix_order, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, float* a, lapack_int lda,\n                                const float* tau, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dorghr_work( int matrix_order, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, double* a, lapack_int lda,\n                                const double* tau, double* work,\n                                lapack_int lwork );\n\nlapack_int LAPACKE_sorglq_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, float* a, lapack_int lda,\n                                const float* tau, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dorglq_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, double* a, lapack_int lda,\n                                const double* tau, double* work,\n                                lapack_int lwork );\n\nlapack_int LAPACKE_sorgql_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, float* a, lapack_int lda,\n                                const float* tau, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dorgql_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, double* a, lapack_int lda,\n                                const double* tau, double* work,\n                                lapack_int lwork );\n\nlapack_int LAPACKE_sorgqr_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, float* a, lapack_int lda,\n                                const float* tau, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dorgqr_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, double* a, lapack_int lda,\n                                const double* tau, double* work,\n                                lapack_int lwork );\n\nlapack_int LAPACKE_sorgrq_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, float* a, lapack_int lda,\n                                const float* tau, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dorgrq_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, double* a, lapack_int lda,\n                                const double* tau, double* work,\n                                lapack_int lwork );\n\nlapack_int LAPACKE_sorgtr_work( int matrix_order, char uplo, lapack_int n,\n                                float* a, lapack_int lda, const float* tau,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dorgtr_work( int matrix_order, char uplo, lapack_int n,\n                                double* a, lapack_int lda, const double* tau,\n                                double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sormbr_work( int matrix_order, char vect, char side,\n                                char trans, lapack_int m, lapack_int n,\n                                lapack_int k, const float* a, lapack_int lda,\n                                const float* tau, float* c, lapack_int ldc,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dormbr_work( int matrix_order, char vect, char side,\n                                char trans, lapack_int m, lapack_int n,\n                                lapack_int k, const double* a, lapack_int lda,\n                                const double* tau, double* c, lapack_int ldc,\n                                double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sormhr_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, const float* a, lapack_int lda,\n                                const float* tau, float* c, lapack_int ldc,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dormhr_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, const double* a, lapack_int lda,\n                                const double* tau, double* c, lapack_int ldc,\n                                double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sormlq_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const float* a, lapack_int lda,\n                                const float* tau, float* c, lapack_int ldc,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dormlq_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const double* a, lapack_int lda,\n                                const double* tau, double* c, lapack_int ldc,\n                                double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sormql_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const float* a, lapack_int lda,\n                                const float* tau, float* c, lapack_int ldc,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dormql_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const double* a, lapack_int lda,\n                                const double* tau, double* c, lapack_int ldc,\n                                double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sormqr_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const float* a, lapack_int lda,\n                                const float* tau, float* c, lapack_int ldc,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dormqr_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const double* a, lapack_int lda,\n                                const double* tau, double* c, lapack_int ldc,\n                                double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sormrq_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const float* a, lapack_int lda,\n                                const float* tau, float* c, lapack_int ldc,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dormrq_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const double* a, lapack_int lda,\n                                const double* tau, double* c, lapack_int ldc,\n                                double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sormrz_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                lapack_int l, const float* a, lapack_int lda,\n                                const float* tau, float* c, lapack_int ldc,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dormrz_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                lapack_int l, const double* a, lapack_int lda,\n                                const double* tau, double* c, lapack_int ldc,\n                                double* work, lapack_int lwork );\n\nlapack_int LAPACKE_sormtr_work( int matrix_order, char side, char uplo,\n                                char trans, lapack_int m, lapack_int n,\n                                const float* a, lapack_int lda,\n                                const float* tau, float* c, lapack_int ldc,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dormtr_work( int matrix_order, char side, char uplo,\n                                char trans, lapack_int m, lapack_int n,\n                                const double* a, lapack_int lda,\n                                const double* tau, double* c, lapack_int ldc,\n                                double* work, lapack_int lwork );\n\nlapack_int LAPACKE_spbcon_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, const float* ab, lapack_int ldab,\n                                float anorm, float* rcond, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dpbcon_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, const double* ab,\n                                lapack_int ldab, double anorm, double* rcond,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_cpbcon_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, const lapack_complex_float* ab,\n                                lapack_int ldab, float anorm, float* rcond,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zpbcon_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, const lapack_complex_double* ab,\n                                lapack_int ldab, double anorm, double* rcond,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_spbequ_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, const float* ab, lapack_int ldab,\n                                float* s, float* scond, float* amax );\nlapack_int LAPACKE_dpbequ_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, const double* ab,\n                                lapack_int ldab, double* s, double* scond,\n                                double* amax );\nlapack_int LAPACKE_cpbequ_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, const lapack_complex_float* ab,\n                                lapack_int ldab, float* s, float* scond,\n                                float* amax );\nlapack_int LAPACKE_zpbequ_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, const lapack_complex_double* ab,\n                                lapack_int ldab, double* s, double* scond,\n                                double* amax );\n\nlapack_int LAPACKE_spbrfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, lapack_int nrhs, const float* ab,\n                                lapack_int ldab, const float* afb,\n                                lapack_int ldafb, const float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* ferr, float* berr, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dpbrfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, lapack_int nrhs,\n                                const double* ab, lapack_int ldab,\n                                const double* afb, lapack_int ldafb,\n                                const double* b, lapack_int ldb, double* x,\n                                lapack_int ldx, double* ferr, double* berr,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_cpbrfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, lapack_int nrhs,\n                                const lapack_complex_float* ab, lapack_int ldab,\n                                const lapack_complex_float* afb,\n                                lapack_int ldafb, const lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* x,\n                                lapack_int ldx, float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zpbrfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, lapack_int nrhs,\n                                const lapack_complex_double* ab,\n                                lapack_int ldab,\n                                const lapack_complex_double* afb,\n                                lapack_int ldafb,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_spbstf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kb, float* bb, lapack_int ldbb );\nlapack_int LAPACKE_dpbstf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kb, double* bb, lapack_int ldbb );\nlapack_int LAPACKE_cpbstf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kb, lapack_complex_float* bb,\n                                lapack_int ldbb );\nlapack_int LAPACKE_zpbstf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kb, lapack_complex_double* bb,\n                                lapack_int ldbb );\n\nlapack_int LAPACKE_spbsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int kd, lapack_int nrhs, float* ab,\n                               lapack_int ldab, float* b, lapack_int ldb );\nlapack_int LAPACKE_dpbsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int kd, lapack_int nrhs, double* ab,\n                               lapack_int ldab, double* b, lapack_int ldb );\nlapack_int LAPACKE_cpbsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int kd, lapack_int nrhs,\n                               lapack_complex_float* ab, lapack_int ldab,\n                               lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zpbsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int kd, lapack_int nrhs,\n                               lapack_complex_double* ab, lapack_int ldab,\n                               lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_spbsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int kd, lapack_int nrhs,\n                                float* ab, lapack_int ldab, float* afb,\n                                lapack_int ldafb, char* equed, float* s,\n                                float* b, lapack_int ldb, float* x,\n                                lapack_int ldx, float* rcond, float* ferr,\n                                float* berr, float* work, lapack_int* iwork );\nlapack_int LAPACKE_dpbsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int kd, lapack_int nrhs,\n                                double* ab, lapack_int ldab, double* afb,\n                                lapack_int ldafb, char* equed, double* s,\n                                double* b, lapack_int ldb, double* x,\n                                lapack_int ldx, double* rcond, double* ferr,\n                                double* berr, double* work, lapack_int* iwork );\nlapack_int LAPACKE_cpbsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int kd, lapack_int nrhs,\n                                lapack_complex_float* ab, lapack_int ldab,\n                                lapack_complex_float* afb, lapack_int ldafb,\n                                char* equed, float* s, lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* x,\n                                lapack_int ldx, float* rcond, float* ferr,\n                                float* berr, lapack_complex_float* work,\n                                float* rwork );\nlapack_int LAPACKE_zpbsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int kd, lapack_int nrhs,\n                                lapack_complex_double* ab, lapack_int ldab,\n                                lapack_complex_double* afb, lapack_int ldafb,\n                                char* equed, double* s,\n                                lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_spbtrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, float* ab, lapack_int ldab );\nlapack_int LAPACKE_dpbtrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, double* ab, lapack_int ldab );\nlapack_int LAPACKE_cpbtrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, lapack_complex_float* ab,\n                                lapack_int ldab );\nlapack_int LAPACKE_zpbtrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, lapack_complex_double* ab,\n                                lapack_int ldab );\n\nlapack_int LAPACKE_spbtrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, lapack_int nrhs, const float* ab,\n                                lapack_int ldab, float* b, lapack_int ldb );\nlapack_int LAPACKE_dpbtrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, lapack_int nrhs,\n                                const double* ab, lapack_int ldab, double* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_cpbtrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, lapack_int nrhs,\n                                const lapack_complex_float* ab, lapack_int ldab,\n                                lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zpbtrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int kd, lapack_int nrhs,\n                                const lapack_complex_double* ab,\n                                lapack_int ldab, lapack_complex_double* b,\n                                lapack_int ldb );\n\nlapack_int LAPACKE_spftrf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, float* a );\nlapack_int LAPACKE_dpftrf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, double* a );\nlapack_int LAPACKE_cpftrf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, lapack_complex_float* a );\nlapack_int LAPACKE_zpftrf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, lapack_complex_double* a );\n\nlapack_int LAPACKE_spftri_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, float* a );\nlapack_int LAPACKE_dpftri_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, double* a );\nlapack_int LAPACKE_cpftri_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, lapack_complex_float* a );\nlapack_int LAPACKE_zpftri_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, lapack_complex_double* a );\n\nlapack_int LAPACKE_spftrs_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, lapack_int nrhs, const float* a,\n                                float* b, lapack_int ldb );\nlapack_int LAPACKE_dpftrs_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, lapack_int nrhs, const double* a,\n                                double* b, lapack_int ldb );\nlapack_int LAPACKE_cpftrs_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_float* a,\n                                lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zpftrs_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_double* a,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_spocon_work( int matrix_order, char uplo, lapack_int n,\n                                const float* a, lapack_int lda, float anorm,\n                                float* rcond, float* work, lapack_int* iwork );\nlapack_int LAPACKE_dpocon_work( int matrix_order, char uplo, lapack_int n,\n                                const double* a, lapack_int lda, double anorm,\n                                double* rcond, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_cpocon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                float anorm, float* rcond,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zpocon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                double anorm, double* rcond,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_spoequ_work( int matrix_order, lapack_int n, const float* a,\n                                lapack_int lda, float* s, float* scond,\n                                float* amax );\nlapack_int LAPACKE_dpoequ_work( int matrix_order, lapack_int n, const double* a,\n                                lapack_int lda, double* s, double* scond,\n                                double* amax );\nlapack_int LAPACKE_cpoequ_work( int matrix_order, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                float* s, float* scond, float* amax );\nlapack_int LAPACKE_zpoequ_work( int matrix_order, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                double* s, double* scond, double* amax );\n\nlapack_int LAPACKE_spoequb_work( int matrix_order, lapack_int n, const float* a,\n                                 lapack_int lda, float* s, float* scond,\n                                 float* amax );\nlapack_int LAPACKE_dpoequb_work( int matrix_order, lapack_int n,\n                                 const double* a, lapack_int lda, double* s,\n                                 double* scond, double* amax );\nlapack_int LAPACKE_cpoequb_work( int matrix_order, lapack_int n,\n                                 const lapack_complex_float* a, lapack_int lda,\n                                 float* s, float* scond, float* amax );\nlapack_int LAPACKE_zpoequb_work( int matrix_order, lapack_int n,\n                                 const lapack_complex_double* a, lapack_int lda,\n                                 double* s, double* scond, double* amax );\n\nlapack_int LAPACKE_sporfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const float* a, lapack_int lda,\n                                const float* af, lapack_int ldaf,\n                                const float* b, lapack_int ldb, float* x,\n                                lapack_int ldx, float* ferr, float* berr,\n                                float* work, lapack_int* iwork );\nlapack_int LAPACKE_dporfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const double* a,\n                                lapack_int lda, const double* af,\n                                lapack_int ldaf, const double* b,\n                                lapack_int ldb, double* x, lapack_int ldx,\n                                double* ferr, double* berr, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_cporfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* af,\n                                lapack_int ldaf, const lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* x,\n                                lapack_int ldx, float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zporfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_double* a,\n                                lapack_int lda, const lapack_complex_double* af,\n                                lapack_int ldaf, const lapack_complex_double* b,\n                                lapack_int ldb, lapack_complex_double* x,\n                                lapack_int ldx, double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sporfsx_work( int matrix_order, char uplo, char equed,\n                                 lapack_int n, lapack_int nrhs, const float* a,\n                                 lapack_int lda, const float* af,\n                                 lapack_int ldaf, const float* s,\n                                 const float* b, lapack_int ldb, float* x,\n                                 lapack_int ldx, float* rcond, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, float* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_dporfsx_work( int matrix_order, char uplo, char equed,\n                                 lapack_int n, lapack_int nrhs, const double* a,\n                                 lapack_int lda, const double* af,\n                                 lapack_int ldaf, const double* s,\n                                 const double* b, lapack_int ldb, double* x,\n                                 lapack_int ldx, double* rcond, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, double* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_cporfsx_work( int matrix_order, char uplo, char equed,\n                                 lapack_int n, lapack_int nrhs,\n                                 const lapack_complex_float* a, lapack_int lda,\n                                 const lapack_complex_float* af,\n                                 lapack_int ldaf, const float* s,\n                                 const lapack_complex_float* b, lapack_int ldb,\n                                 lapack_complex_float* x, lapack_int ldx,\n                                 float* rcond, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, lapack_complex_float* work,\n                                 float* rwork );\nlapack_int LAPACKE_zporfsx_work( int matrix_order, char uplo, char equed,\n                                 lapack_int n, lapack_int nrhs,\n                                 const lapack_complex_double* a, lapack_int lda,\n                                 const lapack_complex_double* af,\n                                 lapack_int ldaf, const double* s,\n                                 const lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* x, lapack_int ldx,\n                                 double* rcond, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, lapack_complex_double* work,\n                                 double* rwork );\n\nlapack_int LAPACKE_sposv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, float* a, lapack_int lda,\n                               float* b, lapack_int ldb );\nlapack_int LAPACKE_dposv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, double* a, lapack_int lda,\n                               double* b, lapack_int ldb );\nlapack_int LAPACKE_cposv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_float* a,\n                               lapack_int lda, lapack_complex_float* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_zposv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_double* a,\n                               lapack_int lda, lapack_complex_double* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_dsposv_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, double* a, lapack_int lda,\n                                double* b, lapack_int ldb, double* x,\n                                lapack_int ldx, double* work, float* swork,\n                                lapack_int* iter );\nlapack_int LAPACKE_zcposv_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* b,\n                                lapack_int ldb, lapack_complex_double* x,\n                                lapack_int ldx, lapack_complex_double* work,\n                                lapack_complex_float* swork, double* rwork,\n                                lapack_int* iter );\n\nlapack_int LAPACKE_sposvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs, float* a,\n                                lapack_int lda, float* af, lapack_int ldaf,\n                                char* equed, float* s, float* b, lapack_int ldb,\n                                float* x, lapack_int ldx, float* rcond,\n                                float* ferr, float* berr, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dposvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs, double* a,\n                                lapack_int lda, double* af, lapack_int ldaf,\n                                char* equed, double* s, double* b,\n                                lapack_int ldb, double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_cposvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* af, lapack_int ldaf,\n                                char* equed, float* s, lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* x,\n                                lapack_int ldx, float* rcond, float* ferr,\n                                float* berr, lapack_complex_float* work,\n                                float* rwork );\nlapack_int LAPACKE_zposvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* af, lapack_int ldaf,\n                                char* equed, double* s,\n                                lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sposvxx_work( int matrix_order, char fact, char uplo,\n                                 lapack_int n, lapack_int nrhs, float* a,\n                                 lapack_int lda, float* af, lapack_int ldaf,\n                                 char* equed, float* s, float* b,\n                                 lapack_int ldb, float* x, lapack_int ldx,\n                                 float* rcond, float* rpvgrw, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, float* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_dposvxx_work( int matrix_order, char fact, char uplo,\n                                 lapack_int n, lapack_int nrhs, double* a,\n                                 lapack_int lda, double* af, lapack_int ldaf,\n                                 char* equed, double* s, double* b,\n                                 lapack_int ldb, double* x, lapack_int ldx,\n                                 double* rcond, double* rpvgrw, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, double* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_cposvxx_work( int matrix_order, char fact, char uplo,\n                                 lapack_int n, lapack_int nrhs,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 lapack_complex_float* af, lapack_int ldaf,\n                                 char* equed, float* s, lapack_complex_float* b,\n                                 lapack_int ldb, lapack_complex_float* x,\n                                 lapack_int ldx, float* rcond, float* rpvgrw,\n                                 float* berr, lapack_int n_err_bnds,\n                                 float* err_bnds_norm, float* err_bnds_comp,\n                                 lapack_int nparams, float* params,\n                                 lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zposvxx_work( int matrix_order, char fact, char uplo,\n                                 lapack_int n, lapack_int nrhs,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 lapack_complex_double* af, lapack_int ldaf,\n                                 char* equed, double* s,\n                                 lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* x, lapack_int ldx,\n                                 double* rcond, double* rpvgrw, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, lapack_complex_double* work,\n                                 double* rwork );\n\nlapack_int LAPACKE_spotrf_work( int matrix_order, char uplo, lapack_int n,\n                                float* a, lapack_int lda );\nlapack_int LAPACKE_dpotrf_work( int matrix_order, char uplo, lapack_int n,\n                                double* a, lapack_int lda );\nlapack_int LAPACKE_cpotrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_zpotrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_spotri_work( int matrix_order, char uplo, lapack_int n,\n                                float* a, lapack_int lda );\nlapack_int LAPACKE_dpotri_work( int matrix_order, char uplo, lapack_int n,\n                                double* a, lapack_int lda );\nlapack_int LAPACKE_cpotri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_zpotri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_spotrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const float* a, lapack_int lda,\n                                float* b, lapack_int ldb );\nlapack_int LAPACKE_dpotrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const double* a,\n                                lapack_int lda, double* b, lapack_int ldb );\nlapack_int LAPACKE_cpotrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_zpotrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* b,\n                                lapack_int ldb );\n\nlapack_int LAPACKE_sppcon_work( int matrix_order, char uplo, lapack_int n,\n                                const float* ap, float anorm, float* rcond,\n                                float* work, lapack_int* iwork );\nlapack_int LAPACKE_dppcon_work( int matrix_order, char uplo, lapack_int n,\n                                const double* ap, double anorm, double* rcond,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_cppcon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_float* ap, float anorm,\n                                float* rcond, lapack_complex_float* work,\n                                float* rwork );\nlapack_int LAPACKE_zppcon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_double* ap, double anorm,\n                                double* rcond, lapack_complex_double* work,\n                                double* rwork );\n\nlapack_int LAPACKE_sppequ_work( int matrix_order, char uplo, lapack_int n,\n                                const float* ap, float* s, float* scond,\n                                float* amax );\nlapack_int LAPACKE_dppequ_work( int matrix_order, char uplo, lapack_int n,\n                                const double* ap, double* s, double* scond,\n                                double* amax );\nlapack_int LAPACKE_cppequ_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_float* ap, float* s,\n                                float* scond, float* amax );\nlapack_int LAPACKE_zppequ_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_double* ap, double* s,\n                                double* scond, double* amax );\n\nlapack_int LAPACKE_spprfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const float* ap,\n                                const float* afp, const float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* ferr, float* berr, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dpprfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const double* ap,\n                                const double* afp, const double* b,\n                                lapack_int ldb, double* x, lapack_int ldx,\n                                double* ferr, double* berr, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_cpprfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* ap,\n                                const lapack_complex_float* afp,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zpprfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs,\n                                const lapack_complex_double* ap,\n                                const lapack_complex_double* afp,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sppsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, float* ap, float* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_dppsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, double* ap, double* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_cppsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_float* ap,\n                               lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zppsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_double* ap,\n                               lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_sppsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs, float* ap,\n                                float* afp, char* equed, float* s, float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* rcond, float* ferr, float* berr,\n                                float* work, lapack_int* iwork );\nlapack_int LAPACKE_dppsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs, double* ap,\n                                double* afp, char* equed, double* s, double* b,\n                                lapack_int ldb, double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_cppsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                lapack_complex_float* ap,\n                                lapack_complex_float* afp, char* equed,\n                                float* s, lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* x,\n                                lapack_int ldx, float* rcond, float* ferr,\n                                float* berr, lapack_complex_float* work,\n                                float* rwork );\nlapack_int LAPACKE_zppsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                lapack_complex_double* ap,\n                                lapack_complex_double* afp, char* equed,\n                                double* s, lapack_complex_double* b,\n                                lapack_int ldb, lapack_complex_double* x,\n                                lapack_int ldx, double* rcond, double* ferr,\n                                double* berr, lapack_complex_double* work,\n                                double* rwork );\n\nlapack_int LAPACKE_spptrf_work( int matrix_order, char uplo, lapack_int n,\n                                float* ap );\nlapack_int LAPACKE_dpptrf_work( int matrix_order, char uplo, lapack_int n,\n                                double* ap );\nlapack_int LAPACKE_cpptrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* ap );\nlapack_int LAPACKE_zpptrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* ap );\n\nlapack_int LAPACKE_spptri_work( int matrix_order, char uplo, lapack_int n,\n                                float* ap );\nlapack_int LAPACKE_dpptri_work( int matrix_order, char uplo, lapack_int n,\n                                double* ap );\nlapack_int LAPACKE_cpptri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* ap );\nlapack_int LAPACKE_zpptri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* ap );\n\nlapack_int LAPACKE_spptrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const float* ap, float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_dpptrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const double* ap, double* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_cpptrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* ap,\n                                lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zpptrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs,\n                                const lapack_complex_double* ap,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_spstrf_work( int matrix_order, char uplo, lapack_int n,\n                                float* a, lapack_int lda, lapack_int* piv,\n                                lapack_int* rank, float tol, float* work );\nlapack_int LAPACKE_dpstrf_work( int matrix_order, char uplo, lapack_int n,\n                                double* a, lapack_int lda, lapack_int* piv,\n                                lapack_int* rank, double tol, double* work );\nlapack_int LAPACKE_cpstrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_int* piv, lapack_int* rank, float tol,\n                                float* work );\nlapack_int LAPACKE_zpstrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int* piv, lapack_int* rank, double tol,\n                                double* work );\n\nlapack_int LAPACKE_sptcon_work( lapack_int n, const float* d, const float* e,\n                                float anorm, float* rcond, float* work );\nlapack_int LAPACKE_dptcon_work( lapack_int n, const double* d, const double* e,\n                                double anorm, double* rcond, double* work );\nlapack_int LAPACKE_cptcon_work( lapack_int n, const float* d,\n                                const lapack_complex_float* e, float anorm,\n                                float* rcond, float* work );\nlapack_int LAPACKE_zptcon_work( lapack_int n, const double* d,\n                                const lapack_complex_double* e, double anorm,\n                                double* rcond, double* work );\n\nlapack_int LAPACKE_spteqr_work( int matrix_order, char compz, lapack_int n,\n                                float* d, float* e, float* z, lapack_int ldz,\n                                float* work );\nlapack_int LAPACKE_dpteqr_work( int matrix_order, char compz, lapack_int n,\n                                double* d, double* e, double* z, lapack_int ldz,\n                                double* work );\nlapack_int LAPACKE_cpteqr_work( int matrix_order, char compz, lapack_int n,\n                                float* d, float* e, lapack_complex_float* z,\n                                lapack_int ldz, float* work );\nlapack_int LAPACKE_zpteqr_work( int matrix_order, char compz, lapack_int n,\n                                double* d, double* e, lapack_complex_double* z,\n                                lapack_int ldz, double* work );\n\nlapack_int LAPACKE_sptrfs_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                                const float* d, const float* e, const float* df,\n                                const float* ef, const float* b, lapack_int ldb,\n                                float* x, lapack_int ldx, float* ferr,\n                                float* berr, float* work );\nlapack_int LAPACKE_dptrfs_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                                const double* d, const double* e,\n                                const double* df, const double* ef,\n                                const double* b, lapack_int ldb, double* x,\n                                lapack_int ldx, double* ferr, double* berr,\n                                double* work );\nlapack_int LAPACKE_cptrfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const float* d,\n                                const lapack_complex_float* e, const float* df,\n                                const lapack_complex_float* ef,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zptrfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const double* d,\n                                const lapack_complex_double* e,\n                                const double* df,\n                                const lapack_complex_double* ef,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sptsv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               float* d, float* e, float* b, lapack_int ldb );\nlapack_int LAPACKE_dptsv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               double* d, double* e, double* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_cptsv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               float* d, lapack_complex_float* e,\n                               lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zptsv_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                               double* d, lapack_complex_double* e,\n                               lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_sptsvx_work( int matrix_order, char fact, lapack_int n,\n                                lapack_int nrhs, const float* d, const float* e,\n                                float* df, float* ef, const float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* rcond, float* ferr, float* berr,\n                                float* work );\nlapack_int LAPACKE_dptsvx_work( int matrix_order, char fact, lapack_int n,\n                                lapack_int nrhs, const double* d,\n                                const double* e, double* df, double* ef,\n                                const double* b, lapack_int ldb, double* x,\n                                lapack_int ldx, double* rcond, double* ferr,\n                                double* berr, double* work );\nlapack_int LAPACKE_cptsvx_work( int matrix_order, char fact, lapack_int n,\n                                lapack_int nrhs, const float* d,\n                                const lapack_complex_float* e, float* df,\n                                lapack_complex_float* ef,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* rcond, float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zptsvx_work( int matrix_order, char fact, lapack_int n,\n                                lapack_int nrhs, const double* d,\n                                const lapack_complex_double* e, double* df,\n                                lapack_complex_double* ef,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_spttrf_work( lapack_int n, float* d, float* e );\nlapack_int LAPACKE_dpttrf_work( lapack_int n, double* d, double* e );\nlapack_int LAPACKE_cpttrf_work( lapack_int n, float* d,\n                                lapack_complex_float* e );\nlapack_int LAPACKE_zpttrf_work( lapack_int n, double* d,\n                                lapack_complex_double* e );\n\nlapack_int LAPACKE_spttrs_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                                const float* d, const float* e, float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_dpttrs_work( int matrix_order, lapack_int n, lapack_int nrhs,\n                                const double* d, const double* e, double* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_cpttrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const float* d,\n                                const lapack_complex_float* e,\n                                lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zpttrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const double* d,\n                                const lapack_complex_double* e,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_ssbev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_int kd, float* ab,\n                               lapack_int ldab, float* w, float* z,\n                               lapack_int ldz, float* work );\nlapack_int LAPACKE_dsbev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_int kd, double* ab,\n                               lapack_int ldab, double* w, double* z,\n                               lapack_int ldz, double* work );\n\nlapack_int LAPACKE_ssbevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_int kd, float* ab,\n                                lapack_int ldab, float* w, float* z,\n                                lapack_int ldz, float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_dsbevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_int kd, double* ab,\n                                lapack_int ldab, double* w, double* z,\n                                lapack_int ldz, double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_ssbevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, lapack_int kd,\n                                float* ab, lapack_int ldab, float* q,\n                                lapack_int ldq, float vl, float vu,\n                                lapack_int il, lapack_int iu, float abstol,\n                                lapack_int* m, float* w, float* z,\n                                lapack_int ldz, float* work, lapack_int* iwork,\n                                lapack_int* ifail );\nlapack_int LAPACKE_dsbevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, lapack_int kd,\n                                double* ab, lapack_int ldab, double* q,\n                                lapack_int ldq, double vl, double vu,\n                                lapack_int il, lapack_int iu, double abstol,\n                                lapack_int* m, double* w, double* z,\n                                lapack_int ldz, double* work, lapack_int* iwork,\n                                lapack_int* ifail );\n\nlapack_int LAPACKE_ssbgst_work( int matrix_order, char vect, char uplo,\n                                lapack_int n, lapack_int ka, lapack_int kb,\n                                float* ab, lapack_int ldab, const float* bb,\n                                lapack_int ldbb, float* x, lapack_int ldx,\n                                float* work );\nlapack_int LAPACKE_dsbgst_work( int matrix_order, char vect, char uplo,\n                                lapack_int n, lapack_int ka, lapack_int kb,\n                                double* ab, lapack_int ldab, const double* bb,\n                                lapack_int ldbb, double* x, lapack_int ldx,\n                                double* work );\n\nlapack_int LAPACKE_ssbgv_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_int ka, lapack_int kb,\n                               float* ab, lapack_int ldab, float* bb,\n                               lapack_int ldbb, float* w, float* z,\n                               lapack_int ldz, float* work );\nlapack_int LAPACKE_dsbgv_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, lapack_int ka, lapack_int kb,\n                               double* ab, lapack_int ldab, double* bb,\n                               lapack_int ldbb, double* w, double* z,\n                               lapack_int ldz, double* work );\n\nlapack_int LAPACKE_ssbgvd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_int ka, lapack_int kb,\n                                float* ab, lapack_int ldab, float* bb,\n                                lapack_int ldbb, float* w, float* z,\n                                lapack_int ldz, float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_dsbgvd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, lapack_int ka, lapack_int kb,\n                                double* ab, lapack_int ldab, double* bb,\n                                lapack_int ldbb, double* w, double* z,\n                                lapack_int ldz, double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_ssbgvx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, lapack_int ka,\n                                lapack_int kb, float* ab, lapack_int ldab,\n                                float* bb, lapack_int ldbb, float* q,\n                                lapack_int ldq, float vl, float vu,\n                                lapack_int il, lapack_int iu, float abstol,\n                                lapack_int* m, float* w, float* z,\n                                lapack_int ldz, float* work, lapack_int* iwork,\n                                lapack_int* ifail );\nlapack_int LAPACKE_dsbgvx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, lapack_int ka,\n                                lapack_int kb, double* ab, lapack_int ldab,\n                                double* bb, lapack_int ldbb, double* q,\n                                lapack_int ldq, double vl, double vu,\n                                lapack_int il, lapack_int iu, double abstol,\n                                lapack_int* m, double* w, double* z,\n                                lapack_int ldz, double* work, lapack_int* iwork,\n                                lapack_int* ifail );\n\nlapack_int LAPACKE_ssbtrd_work( int matrix_order, char vect, char uplo,\n                                lapack_int n, lapack_int kd, float* ab,\n                                lapack_int ldab, float* d, float* e, float* q,\n                                lapack_int ldq, float* work );\nlapack_int LAPACKE_dsbtrd_work( int matrix_order, char vect, char uplo,\n                                lapack_int n, lapack_int kd, double* ab,\n                                lapack_int ldab, double* d, double* e,\n                                double* q, lapack_int ldq, double* work );\n\nlapack_int LAPACKE_ssfrk_work( int matrix_order, char transr, char uplo,\n                               char trans, lapack_int n, lapack_int k,\n                               float alpha, const float* a, lapack_int lda,\n                               float beta, float* c );\nlapack_int LAPACKE_dsfrk_work( int matrix_order, char transr, char uplo,\n                               char trans, lapack_int n, lapack_int k,\n                               double alpha, const double* a, lapack_int lda,\n                               double beta, double* c );\n\nlapack_int LAPACKE_sspcon_work( int matrix_order, char uplo, lapack_int n,\n                                const float* ap, const lapack_int* ipiv,\n                                float anorm, float* rcond, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dspcon_work( int matrix_order, char uplo, lapack_int n,\n                                const double* ap, const lapack_int* ipiv,\n                                double anorm, double* rcond, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_cspcon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_float* ap,\n                                const lapack_int* ipiv, float anorm,\n                                float* rcond, lapack_complex_float* work );\nlapack_int LAPACKE_zspcon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_double* ap,\n                                const lapack_int* ipiv, double anorm,\n                                double* rcond, lapack_complex_double* work );\n\nlapack_int LAPACKE_sspev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, float* ap, float* w, float* z,\n                               lapack_int ldz, float* work );\nlapack_int LAPACKE_dspev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, double* ap, double* w, double* z,\n                               lapack_int ldz, double* work );\n\nlapack_int LAPACKE_sspevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, float* ap, float* w, float* z,\n                                lapack_int ldz, float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_dspevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, double* ap, double* w, double* z,\n                                lapack_int ldz, double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_sspevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, float* ap, float vl,\n                                float vu, lapack_int il, lapack_int iu,\n                                float abstol, lapack_int* m, float* w, float* z,\n                                lapack_int ldz, float* work, lapack_int* iwork,\n                                lapack_int* ifail );\nlapack_int LAPACKE_dspevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, double* ap, double vl,\n                                double vu, lapack_int il, lapack_int iu,\n                                double abstol, lapack_int* m, double* w,\n                                double* z, lapack_int ldz, double* work,\n                                lapack_int* iwork, lapack_int* ifail );\n\nlapack_int LAPACKE_sspgst_work( int matrix_order, lapack_int itype, char uplo,\n                                lapack_int n, float* ap, const float* bp );\nlapack_int LAPACKE_dspgst_work( int matrix_order, lapack_int itype, char uplo,\n                                lapack_int n, double* ap, const double* bp );\n\nlapack_int LAPACKE_sspgv_work( int matrix_order, lapack_int itype, char jobz,\n                               char uplo, lapack_int n, float* ap, float* bp,\n                               float* w, float* z, lapack_int ldz,\n                               float* work );\nlapack_int LAPACKE_dspgv_work( int matrix_order, lapack_int itype, char jobz,\n                               char uplo, lapack_int n, double* ap, double* bp,\n                               double* w, double* z, lapack_int ldz,\n                               double* work );\n\nlapack_int LAPACKE_sspgvd_work( int matrix_order, lapack_int itype, char jobz,\n                                char uplo, lapack_int n, float* ap, float* bp,\n                                float* w, float* z, lapack_int ldz, float* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_dspgvd_work( int matrix_order, lapack_int itype, char jobz,\n                                char uplo, lapack_int n, double* ap, double* bp,\n                                double* w, double* z, lapack_int ldz,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_sspgvx_work( int matrix_order, lapack_int itype, char jobz,\n                                char range, char uplo, lapack_int n, float* ap,\n                                float* bp, float vl, float vu, lapack_int il,\n                                lapack_int iu, float abstol, lapack_int* m,\n                                float* w, float* z, lapack_int ldz, float* work,\n                                lapack_int* iwork, lapack_int* ifail );\nlapack_int LAPACKE_dspgvx_work( int matrix_order, lapack_int itype, char jobz,\n                                char range, char uplo, lapack_int n, double* ap,\n                                double* bp, double vl, double vu, lapack_int il,\n                                lapack_int iu, double abstol, lapack_int* m,\n                                double* w, double* z, lapack_int ldz,\n                                double* work, lapack_int* iwork,\n                                lapack_int* ifail );\n\nlapack_int LAPACKE_ssprfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const float* ap,\n                                const float* afp, const lapack_int* ipiv,\n                                const float* b, lapack_int ldb, float* x,\n                                lapack_int ldx, float* ferr, float* berr,\n                                float* work, lapack_int* iwork );\nlapack_int LAPACKE_dsprfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const double* ap,\n                                const double* afp, const lapack_int* ipiv,\n                                const double* b, lapack_int ldb, double* x,\n                                lapack_int ldx, double* ferr, double* berr,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_csprfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* ap,\n                                const lapack_complex_float* afp,\n                                const lapack_int* ipiv,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zsprfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs,\n                                const lapack_complex_double* ap,\n                                const lapack_complex_double* afp,\n                                const lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_sspsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, float* ap, lapack_int* ipiv,\n                               float* b, lapack_int ldb );\nlapack_int LAPACKE_dspsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, double* ap, lapack_int* ipiv,\n                               double* b, lapack_int ldb );\nlapack_int LAPACKE_cspsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_float* ap,\n                               lapack_int* ipiv, lapack_complex_float* b,\n                               lapack_int ldb );\nlapack_int LAPACKE_zspsv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_double* ap,\n                               lapack_int* ipiv, lapack_complex_double* b,\n                               lapack_int ldb );\n\nlapack_int LAPACKE_sspsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs, const float* ap,\n                                float* afp, lapack_int* ipiv, const float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* rcond, float* ferr, float* berr,\n                                float* work, lapack_int* iwork );\nlapack_int LAPACKE_dspsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs, const double* ap,\n                                double* afp, lapack_int* ipiv, const double* b,\n                                lapack_int ldb, double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_cspsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_float* ap,\n                                lapack_complex_float* afp, lapack_int* ipiv,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* rcond, float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zspsvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_double* ap,\n                                lapack_complex_double* afp, lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_ssptrd_work( int matrix_order, char uplo, lapack_int n,\n                                float* ap, float* d, float* e, float* tau );\nlapack_int LAPACKE_dsptrd_work( int matrix_order, char uplo, lapack_int n,\n                                double* ap, double* d, double* e, double* tau );\n\nlapack_int LAPACKE_ssptrf_work( int matrix_order, char uplo, lapack_int n,\n                                float* ap, lapack_int* ipiv );\nlapack_int LAPACKE_dsptrf_work( int matrix_order, char uplo, lapack_int n,\n                                double* ap, lapack_int* ipiv );\nlapack_int LAPACKE_csptrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* ap, lapack_int* ipiv );\nlapack_int LAPACKE_zsptrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* ap, lapack_int* ipiv );\n\nlapack_int LAPACKE_ssptri_work( int matrix_order, char uplo, lapack_int n,\n                                float* ap, const lapack_int* ipiv,\n                                float* work );\nlapack_int LAPACKE_dsptri_work( int matrix_order, char uplo, lapack_int n,\n                                double* ap, const lapack_int* ipiv,\n                                double* work );\nlapack_int LAPACKE_csptri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* ap,\n                                const lapack_int* ipiv,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zsptri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* ap,\n                                const lapack_int* ipiv,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_ssptrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const float* ap,\n                                const lapack_int* ipiv, float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_dsptrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const double* ap,\n                                const lapack_int* ipiv, double* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_csptrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* ap,\n                                const lapack_int* ipiv, lapack_complex_float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_zsptrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs,\n                                const lapack_complex_double* ap,\n                                const lapack_int* ipiv,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_sstebz_work( char range, char order, lapack_int n, float vl,\n                                float vu, lapack_int il, lapack_int iu,\n                                float abstol, const float* d, const float* e,\n                                lapack_int* m, lapack_int* nsplit, float* w,\n                                lapack_int* iblock, lapack_int* isplit,\n                                float* work, lapack_int* iwork );\nlapack_int LAPACKE_dstebz_work( char range, char order, lapack_int n, double vl,\n                                double vu, lapack_int il, lapack_int iu,\n                                double abstol, const double* d, const double* e,\n                                lapack_int* m, lapack_int* nsplit, double* w,\n                                lapack_int* iblock, lapack_int* isplit,\n                                double* work, lapack_int* iwork );\n\nlapack_int LAPACKE_sstedc_work( int matrix_order, char compz, lapack_int n,\n                                float* d, float* e, float* z, lapack_int ldz,\n                                float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_dstedc_work( int matrix_order, char compz, lapack_int n,\n                                double* d, double* e, double* z, lapack_int ldz,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_cstedc_work( int matrix_order, char compz, lapack_int n,\n                                float* d, float* e, lapack_complex_float* z,\n                                lapack_int ldz, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork,\n                                lapack_int lrwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_zstedc_work( int matrix_order, char compz, lapack_int n,\n                                double* d, double* e, lapack_complex_double* z,\n                                lapack_int ldz, lapack_complex_double* work,\n                                lapack_int lwork, double* rwork,\n                                lapack_int lrwork, lapack_int* iwork,\n                                lapack_int liwork );\n\nlapack_int LAPACKE_sstegr_work( int matrix_order, char jobz, char range,\n                                lapack_int n, float* d, float* e, float vl,\n                                float vu, lapack_int il, lapack_int iu,\n                                float abstol, lapack_int* m, float* w, float* z,\n                                lapack_int ldz, lapack_int* isuppz, float* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_dstegr_work( int matrix_order, char jobz, char range,\n                                lapack_int n, double* d, double* e, double vl,\n                                double vu, lapack_int il, lapack_int iu,\n                                double abstol, lapack_int* m, double* w,\n                                double* z, lapack_int ldz, lapack_int* isuppz,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_cstegr_work( int matrix_order, char jobz, char range,\n                                lapack_int n, float* d, float* e, float vl,\n                                float vu, lapack_int il, lapack_int iu,\n                                float abstol, lapack_int* m, float* w,\n                                lapack_complex_float* z, lapack_int ldz,\n                                lapack_int* isuppz, float* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_zstegr_work( int matrix_order, char jobz, char range,\n                                lapack_int n, double* d, double* e, double vl,\n                                double vu, lapack_int il, lapack_int iu,\n                                double abstol, lapack_int* m, double* w,\n                                lapack_complex_double* z, lapack_int ldz,\n                                lapack_int* isuppz, double* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int liwork );\n\nlapack_int LAPACKE_sstein_work( int matrix_order, lapack_int n, const float* d,\n                                const float* e, lapack_int m, const float* w,\n                                const lapack_int* iblock,\n                                const lapack_int* isplit, float* z,\n                                lapack_int ldz, float* work, lapack_int* iwork,\n                                lapack_int* ifailv );\nlapack_int LAPACKE_dstein_work( int matrix_order, lapack_int n, const double* d,\n                                const double* e, lapack_int m, const double* w,\n                                const lapack_int* iblock,\n                                const lapack_int* isplit, double* z,\n                                lapack_int ldz, double* work, lapack_int* iwork,\n                                lapack_int* ifailv );\nlapack_int LAPACKE_cstein_work( int matrix_order, lapack_int n, const float* d,\n                                const float* e, lapack_int m, const float* w,\n                                const lapack_int* iblock,\n                                const lapack_int* isplit,\n                                lapack_complex_float* z, lapack_int ldz,\n                                float* work, lapack_int* iwork,\n                                lapack_int* ifailv );\nlapack_int LAPACKE_zstein_work( int matrix_order, lapack_int n, const double* d,\n                                const double* e, lapack_int m, const double* w,\n                                const lapack_int* iblock,\n                                const lapack_int* isplit,\n                                lapack_complex_double* z, lapack_int ldz,\n                                double* work, lapack_int* iwork,\n                                lapack_int* ifailv );\n\nlapack_int LAPACKE_sstemr_work( int matrix_order, char jobz, char range,\n                                lapack_int n, float* d, float* e, float vl,\n                                float vu, lapack_int il, lapack_int iu,\n                                lapack_int* m, float* w, float* z,\n                                lapack_int ldz, lapack_int nzc,\n                                lapack_int* isuppz, lapack_logical* tryrac,\n                                float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_dstemr_work( int matrix_order, char jobz, char range,\n                                lapack_int n, double* d, double* e, double vl,\n                                double vu, lapack_int il, lapack_int iu,\n                                lapack_int* m, double* w, double* z,\n                                lapack_int ldz, lapack_int nzc,\n                                lapack_int* isuppz, lapack_logical* tryrac,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_cstemr_work( int matrix_order, char jobz, char range,\n                                lapack_int n, float* d, float* e, float vl,\n                                float vu, lapack_int il, lapack_int iu,\n                                lapack_int* m, float* w,\n                                lapack_complex_float* z, lapack_int ldz,\n                                lapack_int nzc, lapack_int* isuppz,\n                                lapack_logical* tryrac, float* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_zstemr_work( int matrix_order, char jobz, char range,\n                                lapack_int n, double* d, double* e, double vl,\n                                double vu, lapack_int il, lapack_int iu,\n                                lapack_int* m, double* w,\n                                lapack_complex_double* z, lapack_int ldz,\n                                lapack_int nzc, lapack_int* isuppz,\n                                lapack_logical* tryrac, double* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int liwork );\n\nlapack_int LAPACKE_ssteqr_work( int matrix_order, char compz, lapack_int n,\n                                float* d, float* e, float* z, lapack_int ldz,\n                                float* work );\nlapack_int LAPACKE_dsteqr_work( int matrix_order, char compz, lapack_int n,\n                                double* d, double* e, double* z, lapack_int ldz,\n                                double* work );\nlapack_int LAPACKE_csteqr_work( int matrix_order, char compz, lapack_int n,\n                                float* d, float* e, lapack_complex_float* z,\n                                lapack_int ldz, float* work );\nlapack_int LAPACKE_zsteqr_work( int matrix_order, char compz, lapack_int n,\n                                double* d, double* e, lapack_complex_double* z,\n                                lapack_int ldz, double* work );\n\nlapack_int LAPACKE_ssterf_work( lapack_int n, float* d, float* e );\nlapack_int LAPACKE_dsterf_work( lapack_int n, double* d, double* e );\n\nlapack_int LAPACKE_sstev_work( int matrix_order, char jobz, lapack_int n,\n                               float* d, float* e, float* z, lapack_int ldz,\n                               float* work );\nlapack_int LAPACKE_dstev_work( int matrix_order, char jobz, lapack_int n,\n                               double* d, double* e, double* z, lapack_int ldz,\n                               double* work );\n\nlapack_int LAPACKE_sstevd_work( int matrix_order, char jobz, lapack_int n,\n                                float* d, float* e, float* z, lapack_int ldz,\n                                float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_dstevd_work( int matrix_order, char jobz, lapack_int n,\n                                double* d, double* e, double* z, lapack_int ldz,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_sstevr_work( int matrix_order, char jobz, char range,\n                                lapack_int n, float* d, float* e, float vl,\n                                float vu, lapack_int il, lapack_int iu,\n                                float abstol, lapack_int* m, float* w, float* z,\n                                lapack_int ldz, lapack_int* isuppz, float* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_dstevr_work( int matrix_order, char jobz, char range,\n                                lapack_int n, double* d, double* e, double vl,\n                                double vu, lapack_int il, lapack_int iu,\n                                double abstol, lapack_int* m, double* w,\n                                double* z, lapack_int ldz, lapack_int* isuppz,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_sstevx_work( int matrix_order, char jobz, char range,\n                                lapack_int n, float* d, float* e, float vl,\n                                float vu, lapack_int il, lapack_int iu,\n                                float abstol, lapack_int* m, float* w, float* z,\n                                lapack_int ldz, float* work, lapack_int* iwork,\n                                lapack_int* ifail );\nlapack_int LAPACKE_dstevx_work( int matrix_order, char jobz, char range,\n                                lapack_int n, double* d, double* e, double vl,\n                                double vu, lapack_int il, lapack_int iu,\n                                double abstol, lapack_int* m, double* w,\n                                double* z, lapack_int ldz, double* work,\n                                lapack_int* iwork, lapack_int* ifail );\n\nlapack_int LAPACKE_ssycon_work( int matrix_order, char uplo, lapack_int n,\n                                const float* a, lapack_int lda,\n                                const lapack_int* ipiv, float anorm,\n                                float* rcond, float* work, lapack_int* iwork );\nlapack_int LAPACKE_dsycon_work( int matrix_order, char uplo, lapack_int n,\n                                const double* a, lapack_int lda,\n                                const lapack_int* ipiv, double anorm,\n                                double* rcond, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_csycon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_int* ipiv, float anorm,\n                                float* rcond, lapack_complex_float* work );\nlapack_int LAPACKE_zsycon_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_int* ipiv, double anorm,\n                                double* rcond, lapack_complex_double* work );\n\nlapack_int LAPACKE_ssyequb_work( int matrix_order, char uplo, lapack_int n,\n                                 const float* a, lapack_int lda, float* s,\n                                 float* scond, float* amax, float* work );\nlapack_int LAPACKE_dsyequb_work( int matrix_order, char uplo, lapack_int n,\n                                 const double* a, lapack_int lda, double* s,\n                                 double* scond, double* amax, double* work );\nlapack_int LAPACKE_csyequb_work( int matrix_order, char uplo, lapack_int n,\n                                 const lapack_complex_float* a, lapack_int lda,\n                                 float* s, float* scond, float* amax,\n                                 lapack_complex_float* work );\nlapack_int LAPACKE_zsyequb_work( int matrix_order, char uplo, lapack_int n,\n                                 const lapack_complex_double* a, lapack_int lda,\n                                 double* s, double* scond, double* amax,\n                                 lapack_complex_double* work );\n\nlapack_int LAPACKE_ssyev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, float* a, lapack_int lda, float* w,\n                               float* work, lapack_int lwork );\nlapack_int LAPACKE_dsyev_work( int matrix_order, char jobz, char uplo,\n                               lapack_int n, double* a, lapack_int lda,\n                               double* w, double* work, lapack_int lwork );\n\nlapack_int LAPACKE_ssyevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, float* a, lapack_int lda,\n                                float* w, float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_dsyevd_work( int matrix_order, char jobz, char uplo,\n                                lapack_int n, double* a, lapack_int lda,\n                                double* w, double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_ssyevr_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, float* a,\n                                lapack_int lda, float vl, float vu,\n                                lapack_int il, lapack_int iu, float abstol,\n                                lapack_int* m, float* w, float* z,\n                                lapack_int ldz, lapack_int* isuppz, float* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_dsyevr_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, double* a,\n                                lapack_int lda, double vl, double vu,\n                                lapack_int il, lapack_int iu, double abstol,\n                                lapack_int* m, double* w, double* z,\n                                lapack_int ldz, lapack_int* isuppz,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_ssyevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, float* a,\n                                lapack_int lda, float vl, float vu,\n                                lapack_int il, lapack_int iu, float abstol,\n                                lapack_int* m, float* w, float* z,\n                                lapack_int ldz, float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int* ifail );\nlapack_int LAPACKE_dsyevx_work( int matrix_order, char jobz, char range,\n                                char uplo, lapack_int n, double* a,\n                                lapack_int lda, double vl, double vu,\n                                lapack_int il, lapack_int iu, double abstol,\n                                lapack_int* m, double* w, double* z,\n                                lapack_int ldz, double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int* ifail );\n\nlapack_int LAPACKE_ssygst_work( int matrix_order, lapack_int itype, char uplo,\n                                lapack_int n, float* a, lapack_int lda,\n                                const float* b, lapack_int ldb );\nlapack_int LAPACKE_dsygst_work( int matrix_order, lapack_int itype, char uplo,\n                                lapack_int n, double* a, lapack_int lda,\n                                const double* b, lapack_int ldb );\n\nlapack_int LAPACKE_ssygv_work( int matrix_order, lapack_int itype, char jobz,\n                               char uplo, lapack_int n, float* a,\n                               lapack_int lda, float* b, lapack_int ldb,\n                               float* w, float* work, lapack_int lwork );\nlapack_int LAPACKE_dsygv_work( int matrix_order, lapack_int itype, char jobz,\n                               char uplo, lapack_int n, double* a,\n                               lapack_int lda, double* b, lapack_int ldb,\n                               double* w, double* work, lapack_int lwork );\n\nlapack_int LAPACKE_ssygvd_work( int matrix_order, lapack_int itype, char jobz,\n                                char uplo, lapack_int n, float* a,\n                                lapack_int lda, float* b, lapack_int ldb,\n                                float* w, float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_dsygvd_work( int matrix_order, lapack_int itype, char jobz,\n                                char uplo, lapack_int n, double* a,\n                                lapack_int lda, double* b, lapack_int ldb,\n                                double* w, double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\n\nlapack_int LAPACKE_ssygvx_work( int matrix_order, lapack_int itype, char jobz,\n                                char range, char uplo, lapack_int n, float* a,\n                                lapack_int lda, float* b, lapack_int ldb,\n                                float vl, float vu, lapack_int il,\n                                lapack_int iu, float abstol, lapack_int* m,\n                                float* w, float* z, lapack_int ldz, float* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int* ifail );\nlapack_int LAPACKE_dsygvx_work( int matrix_order, lapack_int itype, char jobz,\n                                char range, char uplo, lapack_int n, double* a,\n                                lapack_int lda, double* b, lapack_int ldb,\n                                double vl, double vu, lapack_int il,\n                                lapack_int iu, double abstol, lapack_int* m,\n                                double* w, double* z, lapack_int ldz,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int* ifail );\n\nlapack_int LAPACKE_ssyrfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const float* a, lapack_int lda,\n                                const float* af, lapack_int ldaf,\n                                const lapack_int* ipiv, const float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* ferr, float* berr, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dsyrfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const double* a,\n                                lapack_int lda, const double* af,\n                                lapack_int ldaf, const lapack_int* ipiv,\n                                const double* b, lapack_int ldb, double* x,\n                                lapack_int ldx, double* ferr, double* berr,\n                                double* work, lapack_int* iwork );\nlapack_int LAPACKE_csyrfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* af,\n                                lapack_int ldaf, const lapack_int* ipiv,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_zsyrfs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_double* a,\n                                lapack_int lda, const lapack_complex_double* af,\n                                lapack_int ldaf, const lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_ssyrfsx_work( int matrix_order, char uplo, char equed,\n                                 lapack_int n, lapack_int nrhs, const float* a,\n                                 lapack_int lda, const float* af,\n                                 lapack_int ldaf, const lapack_int* ipiv,\n                                 const float* s, const float* b, lapack_int ldb,\n                                 float* x, lapack_int ldx, float* rcond,\n                                 float* berr, lapack_int n_err_bnds,\n                                 float* err_bnds_norm, float* err_bnds_comp,\n                                 lapack_int nparams, float* params, float* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_dsyrfsx_work( int matrix_order, char uplo, char equed,\n                                 lapack_int n, lapack_int nrhs, const double* a,\n                                 lapack_int lda, const double* af,\n                                 lapack_int ldaf, const lapack_int* ipiv,\n                                 const double* s, const double* b,\n                                 lapack_int ldb, double* x, lapack_int ldx,\n                                 double* rcond, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, double* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_csyrfsx_work( int matrix_order, char uplo, char equed,\n                                 lapack_int n, lapack_int nrhs,\n                                 const lapack_complex_float* a, lapack_int lda,\n                                 const lapack_complex_float* af,\n                                 lapack_int ldaf, const lapack_int* ipiv,\n                                 const float* s, const lapack_complex_float* b,\n                                 lapack_int ldb, lapack_complex_float* x,\n                                 lapack_int ldx, float* rcond, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, lapack_complex_float* work,\n                                 float* rwork );\nlapack_int LAPACKE_zsyrfsx_work( int matrix_order, char uplo, char equed,\n                                 lapack_int n, lapack_int nrhs,\n                                 const lapack_complex_double* a, lapack_int lda,\n                                 const lapack_complex_double* af,\n                                 lapack_int ldaf, const lapack_int* ipiv,\n                                 const double* s,\n                                 const lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* x, lapack_int ldx,\n                                 double* rcond, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, lapack_complex_double* work,\n                                 double* rwork );\n\nlapack_int LAPACKE_ssysv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, float* a, lapack_int lda,\n                               lapack_int* ipiv, float* b, lapack_int ldb,\n                               float* work, lapack_int lwork );\nlapack_int LAPACKE_dsysv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, double* a, lapack_int lda,\n                               lapack_int* ipiv, double* b, lapack_int ldb,\n                               double* work, lapack_int lwork );\nlapack_int LAPACKE_csysv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_float* a,\n                               lapack_int lda, lapack_int* ipiv,\n                               lapack_complex_float* b, lapack_int ldb,\n                               lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zsysv_work( int matrix_order, char uplo, lapack_int n,\n                               lapack_int nrhs, lapack_complex_double* a,\n                               lapack_int lda, lapack_int* ipiv,\n                               lapack_complex_double* b, lapack_int ldb,\n                               lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_ssysvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs, const float* a,\n                                lapack_int lda, float* af, lapack_int ldaf,\n                                lapack_int* ipiv, const float* b,\n                                lapack_int ldb, float* x, lapack_int ldx,\n                                float* rcond, float* ferr, float* berr,\n                                float* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dsysvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs, const double* a,\n                                lapack_int lda, double* af, lapack_int ldaf,\n                                lapack_int* ipiv, const double* b,\n                                lapack_int ldb, double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_csysvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* af, lapack_int ldaf,\n                                lapack_int* ipiv, const lapack_complex_float* b,\n                                lapack_int ldb, lapack_complex_float* x,\n                                lapack_int ldx, float* rcond, float* ferr,\n                                float* berr, lapack_complex_float* work,\n                                lapack_int lwork, float* rwork );\nlapack_int LAPACKE_zsysvx_work( int matrix_order, char fact, char uplo,\n                                lapack_int n, lapack_int nrhs,\n                                const lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* af, lapack_int ldaf,\n                                lapack_int* ipiv,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* x, lapack_int ldx,\n                                double* rcond, double* ferr, double* berr,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork );\n\nlapack_int LAPACKE_ssysvxx_work( int matrix_order, char fact, char uplo,\n                                 lapack_int n, lapack_int nrhs, float* a,\n                                 lapack_int lda, float* af, lapack_int ldaf,\n                                 lapack_int* ipiv, char* equed, float* s,\n                                 float* b, lapack_int ldb, float* x,\n                                 lapack_int ldx, float* rcond, float* rpvgrw,\n                                 float* berr, lapack_int n_err_bnds,\n                                 float* err_bnds_norm, float* err_bnds_comp,\n                                 lapack_int nparams, float* params, float* work,\n                                 lapack_int* iwork );\nlapack_int LAPACKE_dsysvxx_work( int matrix_order, char fact, char uplo,\n                                 lapack_int n, lapack_int nrhs, double* a,\n                                 lapack_int lda, double* af, lapack_int ldaf,\n                                 lapack_int* ipiv, char* equed, double* s,\n                                 double* b, lapack_int ldb, double* x,\n                                 lapack_int ldx, double* rcond, double* rpvgrw,\n                                 double* berr, lapack_int n_err_bnds,\n                                 double* err_bnds_norm, double* err_bnds_comp,\n                                 lapack_int nparams, double* params,\n                                 double* work, lapack_int* iwork );\nlapack_int LAPACKE_csysvxx_work( int matrix_order, char fact, char uplo,\n                                 lapack_int n, lapack_int nrhs,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 lapack_complex_float* af, lapack_int ldaf,\n                                 lapack_int* ipiv, char* equed, float* s,\n                                 lapack_complex_float* b, lapack_int ldb,\n                                 lapack_complex_float* x, lapack_int ldx,\n                                 float* rcond, float* rpvgrw, float* berr,\n                                 lapack_int n_err_bnds, float* err_bnds_norm,\n                                 float* err_bnds_comp, lapack_int nparams,\n                                 float* params, lapack_complex_float* work,\n                                 float* rwork );\nlapack_int LAPACKE_zsysvxx_work( int matrix_order, char fact, char uplo,\n                                 lapack_int n, lapack_int nrhs,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 lapack_complex_double* af, lapack_int ldaf,\n                                 lapack_int* ipiv, char* equed, double* s,\n                                 lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* x, lapack_int ldx,\n                                 double* rcond, double* rpvgrw, double* berr,\n                                 lapack_int n_err_bnds, double* err_bnds_norm,\n                                 double* err_bnds_comp, lapack_int nparams,\n                                 double* params, lapack_complex_double* work,\n                                 double* rwork );\n\nlapack_int LAPACKE_ssytrd_work( int matrix_order, char uplo, lapack_int n,\n                                float* a, lapack_int lda, float* d, float* e,\n                                float* tau, float* work, lapack_int lwork );\nlapack_int LAPACKE_dsytrd_work( int matrix_order, char uplo, lapack_int n,\n                                double* a, lapack_int lda, double* d, double* e,\n                                double* tau, double* work, lapack_int lwork );\n\nlapack_int LAPACKE_ssytrf_work( int matrix_order, char uplo, lapack_int n,\n                                float* a, lapack_int lda, lapack_int* ipiv,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dsytrf_work( int matrix_order, char uplo, lapack_int n,\n                                double* a, lapack_int lda, lapack_int* ipiv,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_csytrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_int* ipiv, lapack_complex_float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_zsytrf_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_int* ipiv, lapack_complex_double* work,\n                                lapack_int lwork );\n\nlapack_int LAPACKE_ssytri_work( int matrix_order, char uplo, lapack_int n,\n                                float* a, lapack_int lda,\n                                const lapack_int* ipiv, float* work );\nlapack_int LAPACKE_dsytri_work( int matrix_order, char uplo, lapack_int n,\n                                double* a, lapack_int lda,\n                                const lapack_int* ipiv, double* work );\nlapack_int LAPACKE_csytri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                const lapack_int* ipiv,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zsytri_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                const lapack_int* ipiv,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_ssytrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const float* a, lapack_int lda,\n                                const lapack_int* ipiv, float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_dsytrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const double* a,\n                                lapack_int lda, const lapack_int* ipiv,\n                                double* b, lapack_int ldb );\nlapack_int LAPACKE_csytrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_float* a,\n                                lapack_int lda, const lapack_int* ipiv,\n                                lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_zsytrs_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_int nrhs, const lapack_complex_double* a,\n                                lapack_int lda, const lapack_int* ipiv,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_stbcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n, lapack_int kd,\n                                const float* ab, lapack_int ldab, float* rcond,\n                                float* work, lapack_int* iwork );\nlapack_int LAPACKE_dtbcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n, lapack_int kd,\n                                const double* ab, lapack_int ldab,\n                                double* rcond, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_ctbcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n, lapack_int kd,\n                                const lapack_complex_float* ab, lapack_int ldab,\n                                float* rcond, lapack_complex_float* work,\n                                float* rwork );\nlapack_int LAPACKE_ztbcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n, lapack_int kd,\n                                const lapack_complex_double* ab,\n                                lapack_int ldab, double* rcond,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_stbrfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int kd,\n                                lapack_int nrhs, const float* ab,\n                                lapack_int ldab, const float* b, lapack_int ldb,\n                                const float* x, lapack_int ldx, float* ferr,\n                                float* berr, float* work, lapack_int* iwork );\nlapack_int LAPACKE_dtbrfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int kd,\n                                lapack_int nrhs, const double* ab,\n                                lapack_int ldab, const double* b,\n                                lapack_int ldb, const double* x, lapack_int ldx,\n                                double* ferr, double* berr, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_ctbrfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int kd,\n                                lapack_int nrhs, const lapack_complex_float* ab,\n                                lapack_int ldab, const lapack_complex_float* b,\n                                lapack_int ldb, const lapack_complex_float* x,\n                                lapack_int ldx, float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_ztbrfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int kd,\n                                lapack_int nrhs,\n                                const lapack_complex_double* ab,\n                                lapack_int ldab, const lapack_complex_double* b,\n                                lapack_int ldb, const lapack_complex_double* x,\n                                lapack_int ldx, double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_stbtrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int kd,\n                                lapack_int nrhs, const float* ab,\n                                lapack_int ldab, float* b, lapack_int ldb );\nlapack_int LAPACKE_dtbtrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int kd,\n                                lapack_int nrhs, const double* ab,\n                                lapack_int ldab, double* b, lapack_int ldb );\nlapack_int LAPACKE_ctbtrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int kd,\n                                lapack_int nrhs, const lapack_complex_float* ab,\n                                lapack_int ldab, lapack_complex_float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_ztbtrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int kd,\n                                lapack_int nrhs,\n                                const lapack_complex_double* ab,\n                                lapack_int ldab, lapack_complex_double* b,\n                                lapack_int ldb );\n\nlapack_int LAPACKE_stfsm_work( int matrix_order, char transr, char side,\n                               char uplo, char trans, char diag, lapack_int m,\n                               lapack_int n, float alpha, const float* a,\n                               float* b, lapack_int ldb );\nlapack_int LAPACKE_dtfsm_work( int matrix_order, char transr, char side,\n                               char uplo, char trans, char diag, lapack_int m,\n                               lapack_int n, double alpha, const double* a,\n                               double* b, lapack_int ldb );\nlapack_int LAPACKE_ctfsm_work( int matrix_order, char transr, char side,\n                               char uplo, char trans, char diag, lapack_int m,\n                               lapack_int n, lapack_complex_float alpha,\n                               const lapack_complex_float* a,\n                               lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_ztfsm_work( int matrix_order, char transr, char side,\n                               char uplo, char trans, char diag, lapack_int m,\n                               lapack_int n, lapack_complex_double alpha,\n                               const lapack_complex_double* a,\n                               lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_stftri_work( int matrix_order, char transr, char uplo,\n                                char diag, lapack_int n, float* a );\nlapack_int LAPACKE_dtftri_work( int matrix_order, char transr, char uplo,\n                                char diag, lapack_int n, double* a );\nlapack_int LAPACKE_ctftri_work( int matrix_order, char transr, char uplo,\n                                char diag, lapack_int n,\n                                lapack_complex_float* a );\nlapack_int LAPACKE_ztftri_work( int matrix_order, char transr, char uplo,\n                                char diag, lapack_int n,\n                                lapack_complex_double* a );\n\nlapack_int LAPACKE_stfttp_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const float* arf, float* ap );\nlapack_int LAPACKE_dtfttp_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const double* arf, double* ap );\nlapack_int LAPACKE_ctfttp_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const lapack_complex_float* arf,\n                                lapack_complex_float* ap );\nlapack_int LAPACKE_ztfttp_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const lapack_complex_double* arf,\n                                lapack_complex_double* ap );\n\nlapack_int LAPACKE_stfttr_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const float* arf, float* a,\n                                lapack_int lda );\nlapack_int LAPACKE_dtfttr_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const double* arf, double* a,\n                                lapack_int lda );\nlapack_int LAPACKE_ctfttr_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const lapack_complex_float* arf,\n                                lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_ztfttr_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const lapack_complex_double* arf,\n                                lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_stgevc_work( int matrix_order, char side, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const float* s, lapack_int lds, const float* p,\n                                lapack_int ldp, float* vl, lapack_int ldvl,\n                                float* vr, lapack_int ldvr, lapack_int mm,\n                                lapack_int* m, float* work );\nlapack_int LAPACKE_dtgevc_work( int matrix_order, char side, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const double* s, lapack_int lds,\n                                const double* p, lapack_int ldp, double* vl,\n                                lapack_int ldvl, double* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m, double* work );\nlapack_int LAPACKE_ctgevc_work( int matrix_order, char side, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const lapack_complex_float* s, lapack_int lds,\n                                const lapack_complex_float* p, lapack_int ldp,\n                                lapack_complex_float* vl, lapack_int ldvl,\n                                lapack_complex_float* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_ztgevc_work( int matrix_order, char side, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const lapack_complex_double* s, lapack_int lds,\n                                const lapack_complex_double* p, lapack_int ldp,\n                                lapack_complex_double* vl, lapack_int ldvl,\n                                lapack_complex_double* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_stgexc_work( int matrix_order, lapack_logical wantq,\n                                lapack_logical wantz, lapack_int n, float* a,\n                                lapack_int lda, float* b, lapack_int ldb,\n                                float* q, lapack_int ldq, float* z,\n                                lapack_int ldz, lapack_int* ifst,\n                                lapack_int* ilst, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dtgexc_work( int matrix_order, lapack_logical wantq,\n                                lapack_logical wantz, lapack_int n, double* a,\n                                lapack_int lda, double* b, lapack_int ldb,\n                                double* q, lapack_int ldq, double* z,\n                                lapack_int ldz, lapack_int* ifst,\n                                lapack_int* ilst, double* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_ctgexc_work( int matrix_order, lapack_logical wantq,\n                                lapack_logical wantz, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* q, lapack_int ldq,\n                                lapack_complex_float* z, lapack_int ldz,\n                                lapack_int ifst, lapack_int ilst );\nlapack_int LAPACKE_ztgexc_work( int matrix_order, lapack_logical wantq,\n                                lapack_logical wantz, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* q, lapack_int ldq,\n                                lapack_complex_double* z, lapack_int ldz,\n                                lapack_int ifst, lapack_int ilst );\n\nlapack_int LAPACKE_stgsen_work( int matrix_order, lapack_int ijob,\n                                lapack_logical wantq, lapack_logical wantz,\n                                const lapack_logical* select, lapack_int n,\n                                float* a, lapack_int lda, float* b,\n                                lapack_int ldb, float* alphar, float* alphai,\n                                float* beta, float* q, lapack_int ldq, float* z,\n                                lapack_int ldz, lapack_int* m, float* pl,\n                                float* pr, float* dif, float* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int liwork );\nlapack_int LAPACKE_dtgsen_work( int matrix_order, lapack_int ijob,\n                                lapack_logical wantq, lapack_logical wantz,\n                                const lapack_logical* select, lapack_int n,\n                                double* a, lapack_int lda, double* b,\n                                lapack_int ldb, double* alphar, double* alphai,\n                                double* beta, double* q, lapack_int ldq,\n                                double* z, lapack_int ldz, lapack_int* m,\n                                double* pl, double* pr, double* dif,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_ctgsen_work( int matrix_order, lapack_int ijob,\n                                lapack_logical wantq, lapack_logical wantz,\n                                const lapack_logical* select, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* alpha,\n                                lapack_complex_float* beta,\n                                lapack_complex_float* q, lapack_int ldq,\n                                lapack_complex_float* z, lapack_int ldz,\n                                lapack_int* m, float* pl, float* pr, float* dif,\n                                lapack_complex_float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_ztgsen_work( int matrix_order, lapack_int ijob,\n                                lapack_logical wantq, lapack_logical wantz,\n                                const lapack_logical* select, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* alpha,\n                                lapack_complex_double* beta,\n                                lapack_complex_double* q, lapack_int ldq,\n                                lapack_complex_double* z, lapack_int ldz,\n                                lapack_int* m, double* pl, double* pr,\n                                double* dif, lapack_complex_double* work,\n                                lapack_int lwork, lapack_int* iwork,\n                                lapack_int liwork );\n\nlapack_int LAPACKE_stgsja_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int p,\n                                lapack_int n, lapack_int k, lapack_int l,\n                                float* a, lapack_int lda, float* b,\n                                lapack_int ldb, float tola, float tolb,\n                                float* alpha, float* beta, float* u,\n                                lapack_int ldu, float* v, lapack_int ldv,\n                                float* q, lapack_int ldq, float* work,\n                                lapack_int* ncycle );\nlapack_int LAPACKE_dtgsja_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int p,\n                                lapack_int n, lapack_int k, lapack_int l,\n                                double* a, lapack_int lda, double* b,\n                                lapack_int ldb, double tola, double tolb,\n                                double* alpha, double* beta, double* u,\n                                lapack_int ldu, double* v, lapack_int ldv,\n                                double* q, lapack_int ldq, double* work,\n                                lapack_int* ncycle );\nlapack_int LAPACKE_ctgsja_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int p,\n                                lapack_int n, lapack_int k, lapack_int l,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb,\n                                float tola, float tolb, float* alpha,\n                                float* beta, lapack_complex_float* u,\n                                lapack_int ldu, lapack_complex_float* v,\n                                lapack_int ldv, lapack_complex_float* q,\n                                lapack_int ldq, lapack_complex_float* work,\n                                lapack_int* ncycle );\nlapack_int LAPACKE_ztgsja_work( int matrix_order, char jobu, char jobv,\n                                char jobq, lapack_int m, lapack_int p,\n                                lapack_int n, lapack_int k, lapack_int l,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                double tola, double tolb, double* alpha,\n                                double* beta, lapack_complex_double* u,\n                                lapack_int ldu, lapack_complex_double* v,\n                                lapack_int ldv, lapack_complex_double* q,\n                                lapack_int ldq, lapack_complex_double* work,\n                                lapack_int* ncycle );\n\nlapack_int LAPACKE_stgsna_work( int matrix_order, char job, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const float* a, lapack_int lda, const float* b,\n                                lapack_int ldb, const float* vl,\n                                lapack_int ldvl, const float* vr,\n                                lapack_int ldvr, float* s, float* dif,\n                                lapack_int mm, lapack_int* m, float* work,\n                                lapack_int lwork, lapack_int* iwork );\nlapack_int LAPACKE_dtgsna_work( int matrix_order, char job, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const double* a, lapack_int lda,\n                                const double* b, lapack_int ldb,\n                                const double* vl, lapack_int ldvl,\n                                const double* vr, lapack_int ldvr, double* s,\n                                double* dif, lapack_int mm, lapack_int* m,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_ctgsna_work( int matrix_order, char job, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                const lapack_complex_float* vl, lapack_int ldvl,\n                                const lapack_complex_float* vr, lapack_int ldvr,\n                                float* s, float* dif, lapack_int mm,\n                                lapack_int* m, lapack_complex_float* work,\n                                lapack_int lwork, lapack_int* iwork );\nlapack_int LAPACKE_ztgsna_work( int matrix_order, char job, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                const lapack_complex_double* vl,\n                                lapack_int ldvl,\n                                const lapack_complex_double* vr,\n                                lapack_int ldvr, double* s, double* dif,\n                                lapack_int mm, lapack_int* m,\n                                lapack_complex_double* work, lapack_int lwork,\n                                lapack_int* iwork );\n\nlapack_int LAPACKE_stgsyl_work( int matrix_order, char trans, lapack_int ijob,\n                                lapack_int m, lapack_int n, const float* a,\n                                lapack_int lda, const float* b, lapack_int ldb,\n                                float* c, lapack_int ldc, const float* d,\n                                lapack_int ldd, const float* e, lapack_int lde,\n                                float* f, lapack_int ldf, float* scale,\n                                float* dif, float* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dtgsyl_work( int matrix_order, char trans, lapack_int ijob,\n                                lapack_int m, lapack_int n, const double* a,\n                                lapack_int lda, const double* b, lapack_int ldb,\n                                double* c, lapack_int ldc, const double* d,\n                                lapack_int ldd, const double* e, lapack_int lde,\n                                double* f, lapack_int ldf, double* scale,\n                                double* dif, double* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_ctgsyl_work( int matrix_order, char trans, lapack_int ijob,\n                                lapack_int m, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* c, lapack_int ldc,\n                                const lapack_complex_float* d, lapack_int ldd,\n                                const lapack_complex_float* e, lapack_int lde,\n                                lapack_complex_float* f, lapack_int ldf,\n                                float* scale, float* dif,\n                                lapack_complex_float* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_ztgsyl_work( int matrix_order, char trans, lapack_int ijob,\n                                lapack_int m, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* c, lapack_int ldc,\n                                const lapack_complex_double* d, lapack_int ldd,\n                                const lapack_complex_double* e, lapack_int lde,\n                                lapack_complex_double* f, lapack_int ldf,\n                                double* scale, double* dif,\n                                lapack_complex_double* work, lapack_int lwork,\n                                lapack_int* iwork );\n\nlapack_int LAPACKE_stpcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n, const float* ap,\n                                float* rcond, float* work, lapack_int* iwork );\nlapack_int LAPACKE_dtpcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n, const double* ap,\n                                double* rcond, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_ctpcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n,\n                                const lapack_complex_float* ap, float* rcond,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_ztpcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n,\n                                const lapack_complex_double* ap, double* rcond,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_stprfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const float* ap, const float* b, lapack_int ldb,\n                                const float* x, lapack_int ldx, float* ferr,\n                                float* berr, float* work, lapack_int* iwork );\nlapack_int LAPACKE_dtprfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const double* ap, const double* b,\n                                lapack_int ldb, const double* x, lapack_int ldx,\n                                double* ferr, double* berr, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_ctprfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const lapack_complex_float* ap,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                const lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_ztprfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const lapack_complex_double* ap,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                const lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_stptri_work( int matrix_order, char uplo, char diag,\n                                lapack_int n, float* ap );\nlapack_int LAPACKE_dtptri_work( int matrix_order, char uplo, char diag,\n                                lapack_int n, double* ap );\nlapack_int LAPACKE_ctptri_work( int matrix_order, char uplo, char diag,\n                                lapack_int n, lapack_complex_float* ap );\nlapack_int LAPACKE_ztptri_work( int matrix_order, char uplo, char diag,\n                                lapack_int n, lapack_complex_double* ap );\n\nlapack_int LAPACKE_stptrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const float* ap, float* b, lapack_int ldb );\nlapack_int LAPACKE_dtptrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const double* ap, double* b, lapack_int ldb );\nlapack_int LAPACKE_ctptrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const lapack_complex_float* ap,\n                                lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_ztptrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const lapack_complex_double* ap,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_stpttf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const float* ap, float* arf );\nlapack_int LAPACKE_dtpttf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const double* ap, double* arf );\nlapack_int LAPACKE_ctpttf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const lapack_complex_float* ap,\n                                lapack_complex_float* arf );\nlapack_int LAPACKE_ztpttf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const lapack_complex_double* ap,\n                                lapack_complex_double* arf );\n\nlapack_int LAPACKE_stpttr_work( int matrix_order, char uplo, lapack_int n,\n                                const float* ap, float* a, lapack_int lda );\nlapack_int LAPACKE_dtpttr_work( int matrix_order, char uplo, lapack_int n,\n                                const double* ap, double* a, lapack_int lda );\nlapack_int LAPACKE_ctpttr_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_float* ap,\n                                lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_ztpttr_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_double* ap,\n                                lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_strcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n, const float* a,\n                                lapack_int lda, float* rcond, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dtrcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n, const double* a,\n                                lapack_int lda, double* rcond, double* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_ctrcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                float* rcond, lapack_complex_float* work,\n                                float* rwork );\nlapack_int LAPACKE_ztrcon_work( int matrix_order, char norm, char uplo,\n                                char diag, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                double* rcond, lapack_complex_double* work,\n                                double* rwork );\n\nlapack_int LAPACKE_strevc_work( int matrix_order, char side, char howmny,\n                                lapack_logical* select, lapack_int n,\n                                const float* t, lapack_int ldt, float* vl,\n                                lapack_int ldvl, float* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m, float* work );\nlapack_int LAPACKE_dtrevc_work( int matrix_order, char side, char howmny,\n                                lapack_logical* select, lapack_int n,\n                                const double* t, lapack_int ldt, double* vl,\n                                lapack_int ldvl, double* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m, double* work );\nlapack_int LAPACKE_ctrevc_work( int matrix_order, char side, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                lapack_complex_float* t, lapack_int ldt,\n                                lapack_complex_float* vl, lapack_int ldvl,\n                                lapack_complex_float* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_ztrevc_work( int matrix_order, char side, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                lapack_complex_double* t, lapack_int ldt,\n                                lapack_complex_double* vl, lapack_int ldvl,\n                                lapack_complex_double* vr, lapack_int ldvr,\n                                lapack_int mm, lapack_int* m,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_strexc_work( int matrix_order, char compq, lapack_int n,\n                                float* t, lapack_int ldt, float* q,\n                                lapack_int ldq, lapack_int* ifst,\n                                lapack_int* ilst, float* work );\nlapack_int LAPACKE_dtrexc_work( int matrix_order, char compq, lapack_int n,\n                                double* t, lapack_int ldt, double* q,\n                                lapack_int ldq, lapack_int* ifst,\n                                lapack_int* ilst, double* work );\nlapack_int LAPACKE_ctrexc_work( int matrix_order, char compq, lapack_int n,\n                                lapack_complex_float* t, lapack_int ldt,\n                                lapack_complex_float* q, lapack_int ldq,\n                                lapack_int ifst, lapack_int ilst );\nlapack_int LAPACKE_ztrexc_work( int matrix_order, char compq, lapack_int n,\n                                lapack_complex_double* t, lapack_int ldt,\n                                lapack_complex_double* q, lapack_int ldq,\n                                lapack_int ifst, lapack_int ilst );\n\nlapack_int LAPACKE_strrfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const float* a, lapack_int lda, const float* b,\n                                lapack_int ldb, const float* x, lapack_int ldx,\n                                float* ferr, float* berr, float* work,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dtrrfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const double* a, lapack_int lda,\n                                const double* b, lapack_int ldb,\n                                const double* x, lapack_int ldx, double* ferr,\n                                double* berr, double* work, lapack_int* iwork );\nlapack_int LAPACKE_ctrrfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                const lapack_complex_float* x, lapack_int ldx,\n                                float* ferr, float* berr,\n                                lapack_complex_float* work, float* rwork );\nlapack_int LAPACKE_ztrrfs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                const lapack_complex_double* x, lapack_int ldx,\n                                double* ferr, double* berr,\n                                lapack_complex_double* work, double* rwork );\n\nlapack_int LAPACKE_strsen_work( int matrix_order, char job, char compq,\n                                const lapack_logical* select, lapack_int n,\n                                float* t, lapack_int ldt, float* q,\n                                lapack_int ldq, float* wr, float* wi,\n                                lapack_int* m, float* s, float* sep,\n                                float* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_dtrsen_work( int matrix_order, char job, char compq,\n                                const lapack_logical* select, lapack_int n,\n                                double* t, lapack_int ldt, double* q,\n                                lapack_int ldq, double* wr, double* wi,\n                                lapack_int* m, double* s, double* sep,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork, lapack_int liwork );\nlapack_int LAPACKE_ctrsen_work( int matrix_order, char job, char compq,\n                                const lapack_logical* select, lapack_int n,\n                                lapack_complex_float* t, lapack_int ldt,\n                                lapack_complex_float* q, lapack_int ldq,\n                                lapack_complex_float* w, lapack_int* m,\n                                float* s, float* sep,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_ztrsen_work( int matrix_order, char job, char compq,\n                                const lapack_logical* select, lapack_int n,\n                                lapack_complex_double* t, lapack_int ldt,\n                                lapack_complex_double* q, lapack_int ldq,\n                                lapack_complex_double* w, lapack_int* m,\n                                double* s, double* sep,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_strsna_work( int matrix_order, char job, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const float* t, lapack_int ldt, const float* vl,\n                                lapack_int ldvl, const float* vr,\n                                lapack_int ldvr, float* s, float* sep,\n                                lapack_int mm, lapack_int* m, float* work,\n                                lapack_int ldwork, lapack_int* iwork );\nlapack_int LAPACKE_dtrsna_work( int matrix_order, char job, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const double* t, lapack_int ldt,\n                                const double* vl, lapack_int ldvl,\n                                const double* vr, lapack_int ldvr, double* s,\n                                double* sep, lapack_int mm, lapack_int* m,\n                                double* work, lapack_int ldwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_ctrsna_work( int matrix_order, char job, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const lapack_complex_float* t, lapack_int ldt,\n                                const lapack_complex_float* vl, lapack_int ldvl,\n                                const lapack_complex_float* vr, lapack_int ldvr,\n                                float* s, float* sep, lapack_int mm,\n                                lapack_int* m, lapack_complex_float* work,\n                                lapack_int ldwork, float* rwork );\nlapack_int LAPACKE_ztrsna_work( int matrix_order, char job, char howmny,\n                                const lapack_logical* select, lapack_int n,\n                                const lapack_complex_double* t, lapack_int ldt,\n                                const lapack_complex_double* vl,\n                                lapack_int ldvl,\n                                const lapack_complex_double* vr,\n                                lapack_int ldvr, double* s, double* sep,\n                                lapack_int mm, lapack_int* m,\n                                lapack_complex_double* work, lapack_int ldwork,\n                                double* rwork );\n\nlapack_int LAPACKE_strsyl_work( int matrix_order, char trana, char tranb,\n                                lapack_int isgn, lapack_int m, lapack_int n,\n                                const float* a, lapack_int lda, const float* b,\n                                lapack_int ldb, float* c, lapack_int ldc,\n                                float* scale );\nlapack_int LAPACKE_dtrsyl_work( int matrix_order, char trana, char tranb,\n                                lapack_int isgn, lapack_int m, lapack_int n,\n                                const double* a, lapack_int lda,\n                                const double* b, lapack_int ldb, double* c,\n                                lapack_int ldc, double* scale );\nlapack_int LAPACKE_ctrsyl_work( int matrix_order, char trana, char tranb,\n                                lapack_int isgn, lapack_int m, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* b, lapack_int ldb,\n                                lapack_complex_float* c, lapack_int ldc,\n                                float* scale );\nlapack_int LAPACKE_ztrsyl_work( int matrix_order, char trana, char tranb,\n                                lapack_int isgn, lapack_int m, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* c, lapack_int ldc,\n                                double* scale );\n\nlapack_int LAPACKE_strtri_work( int matrix_order, char uplo, char diag,\n                                lapack_int n, float* a, lapack_int lda );\nlapack_int LAPACKE_dtrtri_work( int matrix_order, char uplo, char diag,\n                                lapack_int n, double* a, lapack_int lda );\nlapack_int LAPACKE_ctrtri_work( int matrix_order, char uplo, char diag,\n                                lapack_int n, lapack_complex_float* a,\n                                lapack_int lda );\nlapack_int LAPACKE_ztrtri_work( int matrix_order, char uplo, char diag,\n                                lapack_int n, lapack_complex_double* a,\n                                lapack_int lda );\n\nlapack_int LAPACKE_strtrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const float* a, lapack_int lda, float* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_dtrtrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const double* a, lapack_int lda, double* b,\n                                lapack_int ldb );\nlapack_int LAPACKE_ctrtrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_ztrtrs_work( int matrix_order, char uplo, char trans,\n                                char diag, lapack_int n, lapack_int nrhs,\n                                const lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_strttf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const float* a, lapack_int lda,\n                                float* arf );\nlapack_int LAPACKE_dtrttf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const double* a, lapack_int lda,\n                                double* arf );\nlapack_int LAPACKE_ctrttf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* arf );\nlapack_int LAPACKE_ztrttf_work( int matrix_order, char transr, char uplo,\n                                lapack_int n, const lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* arf );\n\nlapack_int LAPACKE_strttp_work( int matrix_order, char uplo, lapack_int n,\n                                const float* a, lapack_int lda, float* ap );\nlapack_int LAPACKE_dtrttp_work( int matrix_order, char uplo, lapack_int n,\n                                const double* a, lapack_int lda, double* ap );\nlapack_int LAPACKE_ctrttp_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* ap );\nlapack_int LAPACKE_ztrttp_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* ap );\n\nlapack_int LAPACKE_stzrzf_work( int matrix_order, lapack_int m, lapack_int n,\n                                float* a, lapack_int lda, float* tau,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_dtzrzf_work( int matrix_order, lapack_int m, lapack_int n,\n                                double* a, lapack_int lda, double* tau,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_ctzrzf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_ztzrzf_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cungbr_work( int matrix_order, char vect, lapack_int m,\n                                lapack_int n, lapack_int k,\n                                lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zungbr_work( int matrix_order, char vect, lapack_int m,\n                                lapack_int n, lapack_int k,\n                                lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cunghr_work( int matrix_order, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zunghr_work( int matrix_order, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, lapack_complex_double* a,\n                                lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cunglq_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zunglq_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, lapack_complex_double* a,\n                                lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cungql_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zungql_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, lapack_complex_double* a,\n                                lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cungqr_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zungqr_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, lapack_complex_double* a,\n                                lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cungrq_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zungrq_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int k, lapack_complex_double* a,\n                                lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cungtr_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* tau,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zungtr_work( int matrix_order, char uplo, lapack_int n,\n                                lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cunmbr_work( int matrix_order, char vect, char side,\n                                char trans, lapack_int m, lapack_int n,\n                                lapack_int k, const lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* tau,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zunmbr_work( int matrix_order, char vect, char side,\n                                char trans, lapack_int m, lapack_int n,\n                                lapack_int k, const lapack_complex_double* a,\n                                lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cunmhr_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, const lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* tau,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zunmhr_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int ilo,\n                                lapack_int ihi, const lapack_complex_double* a,\n                                lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cunmlq_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* tau,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zunmlq_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cunmql_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* tau,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zunmql_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cunmqr_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* tau,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zunmqr_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cunmrq_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* tau,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zunmrq_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cunmrz_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                lapack_int l, const lapack_complex_float* a,\n                                lapack_int lda, const lapack_complex_float* tau,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zunmrz_work( int matrix_order, char side, char trans,\n                                lapack_int m, lapack_int n, lapack_int k,\n                                lapack_int l, const lapack_complex_double* a,\n                                lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cunmtr_work( int matrix_order, char side, char uplo,\n                                char trans, lapack_int m, lapack_int n,\n                                const lapack_complex_float* a, lapack_int lda,\n                                const lapack_complex_float* tau,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_zunmtr_work( int matrix_order, char side, char uplo,\n                                char trans, lapack_int m, lapack_int n,\n                                const lapack_complex_double* a, lapack_int lda,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work, lapack_int lwork );\n\nlapack_int LAPACKE_cupgtr_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_float* ap,\n                                const lapack_complex_float* tau,\n                                lapack_complex_float* q, lapack_int ldq,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zupgtr_work( int matrix_order, char uplo, lapack_int n,\n                                const lapack_complex_double* ap,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* q, lapack_int ldq,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_cupmtr_work( int matrix_order, char side, char uplo,\n                                char trans, lapack_int m, lapack_int n,\n                                const lapack_complex_float* ap,\n                                const lapack_complex_float* tau,\n                                lapack_complex_float* c, lapack_int ldc,\n                                lapack_complex_float* work );\nlapack_int LAPACKE_zupmtr_work( int matrix_order, char side, char uplo,\n                                char trans, lapack_int m, lapack_int n,\n                                const lapack_complex_double* ap,\n                                const lapack_complex_double* tau,\n                                lapack_complex_double* c, lapack_int ldc,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_claghe( int matrix_order, lapack_int n, lapack_int k,\n                           const float* d, lapack_complex_float* a,\n                           lapack_int lda, lapack_int* iseed );\nlapack_int LAPACKE_zlaghe( int matrix_order, lapack_int n, lapack_int k,\n                           const double* d, lapack_complex_double* a,\n                           lapack_int lda, lapack_int* iseed );\n\nlapack_int LAPACKE_slagsy( int matrix_order, lapack_int n, lapack_int k,\n                           const float* d, float* a, lapack_int lda,\n                           lapack_int* iseed );\nlapack_int LAPACKE_dlagsy( int matrix_order, lapack_int n, lapack_int k,\n                           const double* d, double* a, lapack_int lda,\n                           lapack_int* iseed );\nlapack_int LAPACKE_clagsy( int matrix_order, lapack_int n, lapack_int k,\n                           const float* d, lapack_complex_float* a,\n                           lapack_int lda, lapack_int* iseed );\nlapack_int LAPACKE_zlagsy( int matrix_order, lapack_int n, lapack_int k,\n                           const double* d, lapack_complex_double* a,\n                           lapack_int lda, lapack_int* iseed );\n\nlapack_int LAPACKE_slapmr( int matrix_order, lapack_logical forwrd,\n                           lapack_int m, lapack_int n, float* x, lapack_int ldx,\n                           lapack_int* k );\nlapack_int LAPACKE_dlapmr( int matrix_order, lapack_logical forwrd,\n                           lapack_int m, lapack_int n, double* x,\n                           lapack_int ldx, lapack_int* k );\nlapack_int LAPACKE_clapmr( int matrix_order, lapack_logical forwrd,\n                           lapack_int m, lapack_int n, lapack_complex_float* x,\n                           lapack_int ldx, lapack_int* k );\nlapack_int LAPACKE_zlapmr( int matrix_order, lapack_logical forwrd,\n                           lapack_int m, lapack_int n, lapack_complex_double* x,\n                           lapack_int ldx, lapack_int* k );\n\n\nfloat LAPACKE_slapy2( float x, float y );\ndouble LAPACKE_dlapy2( double x, double y );\n\nfloat LAPACKE_slapy3( float x, float y, float z );\ndouble LAPACKE_dlapy3( double x, double y, double z );\n\nlapack_int LAPACKE_slartgp( float f, float g, float* cs, float* sn, float* r );\nlapack_int LAPACKE_dlartgp( double f, double g, double* cs, double* sn,\n                            double* r );\n\nlapack_int LAPACKE_slartgs( float x, float y, float sigma, float* cs,\n                            float* sn );\nlapack_int LAPACKE_dlartgs( double x, double y, double sigma, double* cs,\n                            double* sn );\n\n\n//LAPACK 3.3.0\nlapack_int LAPACKE_cbbcsd( int matrix_order, char jobu1, char jobu2,\n                           char jobv1t, char jobv2t, char trans, lapack_int m,\n                           lapack_int p, lapack_int q, float* theta, float* phi,\n                           lapack_complex_float* u1, lapack_int ldu1,\n                           lapack_complex_float* u2, lapack_int ldu2,\n                           lapack_complex_float* v1t, lapack_int ldv1t,\n                           lapack_complex_float* v2t, lapack_int ldv2t,\n                           float* b11d, float* b11e, float* b12d, float* b12e,\n                           float* b21d, float* b21e, float* b22d, float* b22e );\nlapack_int LAPACKE_cbbcsd_work( int matrix_order, char jobu1, char jobu2,\n                                char jobv1t, char jobv2t, char trans,\n                                lapack_int m, lapack_int p, lapack_int q,\n                                float* theta, float* phi,\n                                lapack_complex_float* u1, lapack_int ldu1,\n                                lapack_complex_float* u2, lapack_int ldu2,\n                                lapack_complex_float* v1t, lapack_int ldv1t,\n                                lapack_complex_float* v2t, lapack_int ldv2t,\n                                float* b11d, float* b11e, float* b12d,\n                                float* b12e, float* b21d, float* b21e,\n                                float* b22d, float* b22e, float* rwork,\n                                lapack_int lrwork );\nlapack_int LAPACKE_cheswapr( int matrix_order, char uplo, lapack_int n,\n                             lapack_complex_float* a, lapack_int i1,\n                             lapack_int i2 );\nlapack_int LAPACKE_cheswapr_work( int matrix_order, char uplo, lapack_int n,\n                                  lapack_complex_float* a, lapack_int i1,\n                                  lapack_int i2 );\nlapack_int LAPACKE_chetri2( int matrix_order, char uplo, lapack_int n,\n                            lapack_complex_float* a, lapack_int lda,\n                            const lapack_int* ipiv );\nlapack_int LAPACKE_chetri2_work( int matrix_order, char uplo, lapack_int n,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 const lapack_int* ipiv,\n                                 lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_chetri2x( int matrix_order, char uplo, lapack_int n,\n                             lapack_complex_float* a, lapack_int lda,\n                             const lapack_int* ipiv, lapack_int nb );\nlapack_int LAPACKE_chetri2x_work( int matrix_order, char uplo, lapack_int n,\n                                  lapack_complex_float* a, lapack_int lda,\n                                  const lapack_int* ipiv,\n                                  lapack_complex_float* work, lapack_int nb );\nlapack_int LAPACKE_chetrs2( int matrix_order, char uplo, lapack_int n,\n                            lapack_int nrhs, const lapack_complex_float* a,\n                            lapack_int lda, const lapack_int* ipiv,\n                            lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_chetrs2_work( int matrix_order, char uplo, lapack_int n,\n                                 lapack_int nrhs, const lapack_complex_float* a,\n                                 lapack_int lda, const lapack_int* ipiv,\n                                 lapack_complex_float* b, lapack_int ldb,\n                                 lapack_complex_float* work );\nlapack_int LAPACKE_csyconv( int matrix_order, char uplo, char way, lapack_int n,\n                            lapack_complex_float* a, lapack_int lda,\n                            const lapack_int* ipiv );\nlapack_int LAPACKE_csyconv_work( int matrix_order, char uplo, char way,\n                                 lapack_int n, lapack_complex_float* a,\n                                 lapack_int lda, const lapack_int* ipiv,\n                                 lapack_complex_float* work );\nlapack_int LAPACKE_csyswapr( int matrix_order, char uplo, lapack_int n,\n                             lapack_complex_float* a, lapack_int i1,\n                             lapack_int i2 );\nlapack_int LAPACKE_csyswapr_work( int matrix_order, char uplo, lapack_int n,\n                                  lapack_complex_float* a, lapack_int i1,\n                                  lapack_int i2 );\nlapack_int LAPACKE_csytri2( int matrix_order, char uplo, lapack_int n,\n                            lapack_complex_float* a, lapack_int lda,\n                            const lapack_int* ipiv );\nlapack_int LAPACKE_csytri2_work( int matrix_order, char uplo, lapack_int n,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 const lapack_int* ipiv,\n                                 lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_csytri2x( int matrix_order, char uplo, lapack_int n,\n                             lapack_complex_float* a, lapack_int lda,\n                             const lapack_int* ipiv, lapack_int nb );\nlapack_int LAPACKE_csytri2x_work( int matrix_order, char uplo, lapack_int n,\n                                  lapack_complex_float* a, lapack_int lda,\n                                  const lapack_int* ipiv,\n                                  lapack_complex_float* work, lapack_int nb );\nlapack_int LAPACKE_csytrs2( int matrix_order, char uplo, lapack_int n,\n                            lapack_int nrhs, const lapack_complex_float* a,\n                            lapack_int lda, const lapack_int* ipiv,\n                            lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_csytrs2_work( int matrix_order, char uplo, lapack_int n,\n                                 lapack_int nrhs, const lapack_complex_float* a,\n                                 lapack_int lda, const lapack_int* ipiv,\n                                 lapack_complex_float* b, lapack_int ldb,\n                                 lapack_complex_float* work );\nlapack_int LAPACKE_cunbdb( int matrix_order, char trans, char signs,\n                           lapack_int m, lapack_int p, lapack_int q,\n                           lapack_complex_float* x11, lapack_int ldx11,\n                           lapack_complex_float* x12, lapack_int ldx12,\n                           lapack_complex_float* x21, lapack_int ldx21,\n                           lapack_complex_float* x22, lapack_int ldx22,\n                           float* theta, float* phi,\n                           lapack_complex_float* taup1,\n                           lapack_complex_float* taup2,\n                           lapack_complex_float* tauq1,\n                           lapack_complex_float* tauq2 );\nlapack_int LAPACKE_cunbdb_work( int matrix_order, char trans, char signs,\n                                lapack_int m, lapack_int p, lapack_int q,\n                                lapack_complex_float* x11, lapack_int ldx11,\n                                lapack_complex_float* x12, lapack_int ldx12,\n                                lapack_complex_float* x21, lapack_int ldx21,\n                                lapack_complex_float* x22, lapack_int ldx22,\n                                float* theta, float* phi,\n                                lapack_complex_float* taup1,\n                                lapack_complex_float* taup2,\n                                lapack_complex_float* tauq1,\n                                lapack_complex_float* tauq2,\n                                lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_cuncsd( int matrix_order, char jobu1, char jobu2,\n                           char jobv1t, char jobv2t, char trans, char signs,\n                           lapack_int m, lapack_int p, lapack_int q,\n                           lapack_complex_float* x11, lapack_int ldx11,\n                           lapack_complex_float* x12, lapack_int ldx12,\n                           lapack_complex_float* x21, lapack_int ldx21,\n                           lapack_complex_float* x22, lapack_int ldx22,\n                           float* theta, lapack_complex_float* u1,\n                           lapack_int ldu1, lapack_complex_float* u2,\n                           lapack_int ldu2, lapack_complex_float* v1t,\n                           lapack_int ldv1t, lapack_complex_float* v2t,\n                           lapack_int ldv2t );\nlapack_int LAPACKE_cuncsd_work( int matrix_order, char jobu1, char jobu2,\n                                char jobv1t, char jobv2t, char trans,\n                                char signs, lapack_int m, lapack_int p,\n                                lapack_int q, lapack_complex_float* x11,\n                                lapack_int ldx11, lapack_complex_float* x12,\n                                lapack_int ldx12, lapack_complex_float* x21,\n                                lapack_int ldx21, lapack_complex_float* x22,\n                                lapack_int ldx22, float* theta,\n                                lapack_complex_float* u1, lapack_int ldu1,\n                                lapack_complex_float* u2, lapack_int ldu2,\n                                lapack_complex_float* v1t, lapack_int ldv1t,\n                                lapack_complex_float* v2t, lapack_int ldv2t,\n                                lapack_complex_float* work, lapack_int lwork,\n                                float* rwork, lapack_int lrwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dbbcsd( int matrix_order, char jobu1, char jobu2,\n                           char jobv1t, char jobv2t, char trans, lapack_int m,\n                           lapack_int p, lapack_int q, double* theta,\n                           double* phi, double* u1, lapack_int ldu1, double* u2,\n                           lapack_int ldu2, double* v1t, lapack_int ldv1t,\n                           double* v2t, lapack_int ldv2t, double* b11d,\n                           double* b11e, double* b12d, double* b12e,\n                           double* b21d, double* b21e, double* b22d,\n                           double* b22e );\nlapack_int LAPACKE_dbbcsd_work( int matrix_order, char jobu1, char jobu2,\n                                char jobv1t, char jobv2t, char trans,\n                                lapack_int m, lapack_int p, lapack_int q,\n                                double* theta, double* phi, double* u1,\n                                lapack_int ldu1, double* u2, lapack_int ldu2,\n                                double* v1t, lapack_int ldv1t, double* v2t,\n                                lapack_int ldv2t, double* b11d, double* b11e,\n                                double* b12d, double* b12e, double* b21d,\n                                double* b21e, double* b22d, double* b22e,\n                                double* work, lapack_int lwork );\nlapack_int LAPACKE_dorbdb( int matrix_order, char trans, char signs,\n                           lapack_int m, lapack_int p, lapack_int q,\n                           double* x11, lapack_int ldx11, double* x12,\n                           lapack_int ldx12, double* x21, lapack_int ldx21,\n                           double* x22, lapack_int ldx22, double* theta,\n                           double* phi, double* taup1, double* taup2,\n                           double* tauq1, double* tauq2 );\nlapack_int LAPACKE_dorbdb_work( int matrix_order, char trans, char signs,\n                                lapack_int m, lapack_int p, lapack_int q,\n                                double* x11, lapack_int ldx11, double* x12,\n                                lapack_int ldx12, double* x21, lapack_int ldx21,\n                                double* x22, lapack_int ldx22, double* theta,\n                                double* phi, double* taup1, double* taup2,\n                                double* tauq1, double* tauq2, double* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_dorcsd( int matrix_order, char jobu1, char jobu2,\n                           char jobv1t, char jobv2t, char trans, char signs,\n                           lapack_int m, lapack_int p, lapack_int q,\n                           double* x11, lapack_int ldx11, double* x12,\n                           lapack_int ldx12, double* x21, lapack_int ldx21,\n                           double* x22, lapack_int ldx22, double* theta,\n                           double* u1, lapack_int ldu1, double* u2,\n                           lapack_int ldu2, double* v1t, lapack_int ldv1t,\n                           double* v2t, lapack_int ldv2t );\nlapack_int LAPACKE_dorcsd_work( int matrix_order, char jobu1, char jobu2,\n                                char jobv1t, char jobv2t, char trans,\n                                char signs, lapack_int m, lapack_int p,\n                                lapack_int q, double* x11, lapack_int ldx11,\n                                double* x12, lapack_int ldx12, double* x21,\n                                lapack_int ldx21, double* x22, lapack_int ldx22,\n                                double* theta, double* u1, lapack_int ldu1,\n                                double* u2, lapack_int ldu2, double* v1t,\n                                lapack_int ldv1t, double* v2t, lapack_int ldv2t,\n                                double* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_dsyconv( int matrix_order, char uplo, char way, lapack_int n,\n                            double* a, lapack_int lda, const lapack_int* ipiv );\nlapack_int LAPACKE_dsyconv_work( int matrix_order, char uplo, char way,\n                                 lapack_int n, double* a, lapack_int lda,\n                                 const lapack_int* ipiv, double* work );\nlapack_int LAPACKE_dsyswapr( int matrix_order, char uplo, lapack_int n,\n                             double* a, lapack_int i1, lapack_int i2 );\nlapack_int LAPACKE_dsyswapr_work( int matrix_order, char uplo, lapack_int n,\n                                  double* a, lapack_int i1, lapack_int i2 );\nlapack_int LAPACKE_dsytri2( int matrix_order, char uplo, lapack_int n,\n                            double* a, lapack_int lda, const lapack_int* ipiv );\nlapack_int LAPACKE_dsytri2_work( int matrix_order, char uplo, lapack_int n,\n                                 double* a, lapack_int lda,\n                                 const lapack_int* ipiv,\n                                 lapack_complex_double* work, lapack_int lwork );\nlapack_int LAPACKE_dsytri2x( int matrix_order, char uplo, lapack_int n,\n                             double* a, lapack_int lda, const lapack_int* ipiv,\n                             lapack_int nb );\nlapack_int LAPACKE_dsytri2x_work( int matrix_order, char uplo, lapack_int n,\n                                  double* a, lapack_int lda,\n                                  const lapack_int* ipiv, double* work,\n                                  lapack_int nb );\nlapack_int LAPACKE_dsytrs2( int matrix_order, char uplo, lapack_int n,\n                            lapack_int nrhs, const double* a, lapack_int lda,\n                            const lapack_int* ipiv, double* b, lapack_int ldb );\nlapack_int LAPACKE_dsytrs2_work( int matrix_order, char uplo, lapack_int n,\n                                 lapack_int nrhs, const double* a,\n                                 lapack_int lda, const lapack_int* ipiv,\n                                 double* b, lapack_int ldb, double* work );\nlapack_int LAPACKE_sbbcsd( int matrix_order, char jobu1, char jobu2,\n                           char jobv1t, char jobv2t, char trans, lapack_int m,\n                           lapack_int p, lapack_int q, float* theta, float* phi,\n                           float* u1, lapack_int ldu1, float* u2,\n                           lapack_int ldu2, float* v1t, lapack_int ldv1t,\n                           float* v2t, lapack_int ldv2t, float* b11d,\n                           float* b11e, float* b12d, float* b12e, float* b21d,\n                           float* b21e, float* b22d, float* b22e );\nlapack_int LAPACKE_sbbcsd_work( int matrix_order, char jobu1, char jobu2,\n                                char jobv1t, char jobv2t, char trans,\n                                lapack_int m, lapack_int p, lapack_int q,\n                                float* theta, float* phi, float* u1,\n                                lapack_int ldu1, float* u2, lapack_int ldu2,\n                                float* v1t, lapack_int ldv1t, float* v2t,\n                                lapack_int ldv2t, float* b11d, float* b11e,\n                                float* b12d, float* b12e, float* b21d,\n                                float* b21e, float* b22d, float* b22e,\n                                float* work, lapack_int lwork );\nlapack_int LAPACKE_sorbdb( int matrix_order, char trans, char signs,\n                           lapack_int m, lapack_int p, lapack_int q, float* x11,\n                           lapack_int ldx11, float* x12, lapack_int ldx12,\n                           float* x21, lapack_int ldx21, float* x22,\n                           lapack_int ldx22, float* theta, float* phi,\n                           float* taup1, float* taup2, float* tauq1,\n                           float* tauq2 );\nlapack_int LAPACKE_sorbdb_work( int matrix_order, char trans, char signs,\n                                lapack_int m, lapack_int p, lapack_int q,\n                                float* x11, lapack_int ldx11, float* x12,\n                                lapack_int ldx12, float* x21, lapack_int ldx21,\n                                float* x22, lapack_int ldx22, float* theta,\n                                float* phi, float* taup1, float* taup2,\n                                float* tauq1, float* tauq2, float* work,\n                                lapack_int lwork );\nlapack_int LAPACKE_sorcsd( int matrix_order, char jobu1, char jobu2,\n                           char jobv1t, char jobv2t, char trans, char signs,\n                           lapack_int m, lapack_int p, lapack_int q, float* x11,\n                           lapack_int ldx11, float* x12, lapack_int ldx12,\n                           float* x21, lapack_int ldx21, float* x22,\n                           lapack_int ldx22, float* theta, float* u1,\n                           lapack_int ldu1, float* u2, lapack_int ldu2,\n                           float* v1t, lapack_int ldv1t, float* v2t,\n                           lapack_int ldv2t );\nlapack_int LAPACKE_sorcsd_work( int matrix_order, char jobu1, char jobu2,\n                                char jobv1t, char jobv2t, char trans,\n                                char signs, lapack_int m, lapack_int p,\n                                lapack_int q, float* x11, lapack_int ldx11,\n                                float* x12, lapack_int ldx12, float* x21,\n                                lapack_int ldx21, float* x22, lapack_int ldx22,\n                                float* theta, float* u1, lapack_int ldu1,\n                                float* u2, lapack_int ldu2, float* v1t,\n                                lapack_int ldv1t, float* v2t, lapack_int ldv2t,\n                                float* work, lapack_int lwork,\n                                lapack_int* iwork );\nlapack_int LAPACKE_ssyconv( int matrix_order, char uplo, char way, lapack_int n,\n                            float* a, lapack_int lda, const lapack_int* ipiv );\nlapack_int LAPACKE_ssyconv_work( int matrix_order, char uplo, char way,\n                                 lapack_int n, float* a, lapack_int lda,\n                                 const lapack_int* ipiv, float* work );\nlapack_int LAPACKE_ssyswapr( int matrix_order, char uplo, lapack_int n,\n                             float* a, lapack_int i1, lapack_int i2 );\nlapack_int LAPACKE_ssyswapr_work( int matrix_order, char uplo, lapack_int n,\n                                  float* a, lapack_int i1, lapack_int i2 );\nlapack_int LAPACKE_ssytri2( int matrix_order, char uplo, lapack_int n, float* a,\n                            lapack_int lda, const lapack_int* ipiv );\nlapack_int LAPACKE_ssytri2_work( int matrix_order, char uplo, lapack_int n,\n                                 float* a, lapack_int lda,\n                                 const lapack_int* ipiv,\n                                 lapack_complex_float* work, lapack_int lwork );\nlapack_int LAPACKE_ssytri2x( int matrix_order, char uplo, lapack_int n,\n                             float* a, lapack_int lda, const lapack_int* ipiv,\n                             lapack_int nb );\nlapack_int LAPACKE_ssytri2x_work( int matrix_order, char uplo, lapack_int n,\n                                  float* a, lapack_int lda,\n                                  const lapack_int* ipiv, float* work,\n                                  lapack_int nb );\nlapack_int LAPACKE_ssytrs2( int matrix_order, char uplo, lapack_int n,\n                            lapack_int nrhs, const float* a, lapack_int lda,\n                            const lapack_int* ipiv, float* b, lapack_int ldb );\nlapack_int LAPACKE_ssytrs2_work( int matrix_order, char uplo, lapack_int n,\n                                 lapack_int nrhs, const float* a,\n                                 lapack_int lda, const lapack_int* ipiv,\n                                 float* b, lapack_int ldb, float* work );\nlapack_int LAPACKE_zbbcsd( int matrix_order, char jobu1, char jobu2,\n                           char jobv1t, char jobv2t, char trans, lapack_int m,\n                           lapack_int p, lapack_int q, double* theta,\n                           double* phi, lapack_complex_double* u1,\n                           lapack_int ldu1, lapack_complex_double* u2,\n                           lapack_int ldu2, lapack_complex_double* v1t,\n                           lapack_int ldv1t, lapack_complex_double* v2t,\n                           lapack_int ldv2t, double* b11d, double* b11e,\n                           double* b12d, double* b12e, double* b21d,\n                           double* b21e, double* b22d, double* b22e );\nlapack_int LAPACKE_zbbcsd_work( int matrix_order, char jobu1, char jobu2,\n                                char jobv1t, char jobv2t, char trans,\n                                lapack_int m, lapack_int p, lapack_int q,\n                                double* theta, double* phi,\n                                lapack_complex_double* u1, lapack_int ldu1,\n                                lapack_complex_double* u2, lapack_int ldu2,\n                                lapack_complex_double* v1t, lapack_int ldv1t,\n                                lapack_complex_double* v2t, lapack_int ldv2t,\n                                double* b11d, double* b11e, double* b12d,\n                                double* b12e, double* b21d, double* b21e,\n                                double* b22d, double* b22e, double* rwork,\n                                lapack_int lrwork );\nlapack_int LAPACKE_zheswapr( int matrix_order, char uplo, lapack_int n,\n                             lapack_complex_double* a, lapack_int i1,\n                             lapack_int i2 );\nlapack_int LAPACKE_zheswapr_work( int matrix_order, char uplo, lapack_int n,\n                                  lapack_complex_double* a, lapack_int i1,\n                                  lapack_int i2 );\nlapack_int LAPACKE_zhetri2( int matrix_order, char uplo, lapack_int n,\n                            lapack_complex_double* a, lapack_int lda,\n                            const lapack_int* ipiv );\nlapack_int LAPACKE_zhetri2_work( int matrix_order, char uplo, lapack_int n,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 const lapack_int* ipiv,\n                                 lapack_complex_double* work, lapack_int lwork );\nlapack_int LAPACKE_zhetri2x( int matrix_order, char uplo, lapack_int n,\n                             lapack_complex_double* a, lapack_int lda,\n                             const lapack_int* ipiv, lapack_int nb );\nlapack_int LAPACKE_zhetri2x_work( int matrix_order, char uplo, lapack_int n,\n                                  lapack_complex_double* a, lapack_int lda,\n                                  const lapack_int* ipiv,\n                                  lapack_complex_double* work, lapack_int nb );\nlapack_int LAPACKE_zhetrs2( int matrix_order, char uplo, lapack_int n,\n                            lapack_int nrhs, const lapack_complex_double* a,\n                            lapack_int lda, const lapack_int* ipiv,\n                            lapack_complex_double* b, lapack_int ldb );\nlapack_int LAPACKE_zhetrs2_work( int matrix_order, char uplo, lapack_int n,\n                                 lapack_int nrhs, const lapack_complex_double* a,\n                                 lapack_int lda, const lapack_int* ipiv,\n                                 lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* work );\nlapack_int LAPACKE_zsyconv( int matrix_order, char uplo, char way, lapack_int n,\n                            lapack_complex_double* a, lapack_int lda,\n                            const lapack_int* ipiv );\nlapack_int LAPACKE_zsyconv_work( int matrix_order, char uplo, char way,\n                                 lapack_int n, lapack_complex_double* a,\n                                 lapack_int lda, const lapack_int* ipiv,\n                                 lapack_complex_double* work );\nlapack_int LAPACKE_zsyswapr( int matrix_order, char uplo, lapack_int n,\n                             lapack_complex_double* a, lapack_int i1,\n                             lapack_int i2 );\nlapack_int LAPACKE_zsyswapr_work( int matrix_order, char uplo, lapack_int n,\n                                  lapack_complex_double* a, lapack_int i1,\n                                  lapack_int i2 );\nlapack_int LAPACKE_zsytri2( int matrix_order, char uplo, lapack_int n,\n                            lapack_complex_double* a, lapack_int lda,\n                            const lapack_int* ipiv );\nlapack_int LAPACKE_zsytri2_work( int matrix_order, char uplo, lapack_int n,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 const lapack_int* ipiv,\n                                 lapack_complex_double* work, lapack_int lwork );\nlapack_int LAPACKE_zsytri2x( int matrix_order, char uplo, lapack_int n,\n                             lapack_complex_double* a, lapack_int lda,\n                             const lapack_int* ipiv, lapack_int nb );\nlapack_int LAPACKE_zsytri2x_work( int matrix_order, char uplo, lapack_int n,\n                                  lapack_complex_double* a, lapack_int lda,\n                                  const lapack_int* ipiv,\n                                  lapack_complex_double* work, lapack_int nb );\nlapack_int LAPACKE_zsytrs2( int matrix_order, char uplo, lapack_int n,\n                            lapack_int nrhs, const lapack_complex_double* a,\n                            lapack_int lda, const lapack_int* ipiv,\n                            lapack_complex_double* b, lapack_int ldb );\nlapack_int LAPACKE_zsytrs2_work( int matrix_order, char uplo, lapack_int n,\n                                 lapack_int nrhs, const lapack_complex_double* a,\n                                 lapack_int lda, const lapack_int* ipiv,\n                                 lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* work );\nlapack_int LAPACKE_zunbdb( int matrix_order, char trans, char signs,\n                           lapack_int m, lapack_int p, lapack_int q,\n                           lapack_complex_double* x11, lapack_int ldx11,\n                           lapack_complex_double* x12, lapack_int ldx12,\n                           lapack_complex_double* x21, lapack_int ldx21,\n                           lapack_complex_double* x22, lapack_int ldx22,\n                           double* theta, double* phi,\n                           lapack_complex_double* taup1,\n                           lapack_complex_double* taup2,\n                           lapack_complex_double* tauq1,\n                           lapack_complex_double* tauq2 );\nlapack_int LAPACKE_zunbdb_work( int matrix_order, char trans, char signs,\n                                lapack_int m, lapack_int p, lapack_int q,\n                                lapack_complex_double* x11, lapack_int ldx11,\n                                lapack_complex_double* x12, lapack_int ldx12,\n                                lapack_complex_double* x21, lapack_int ldx21,\n                                lapack_complex_double* x22, lapack_int ldx22,\n                                double* theta, double* phi,\n                                lapack_complex_double* taup1,\n                                lapack_complex_double* taup2,\n                                lapack_complex_double* tauq1,\n                                lapack_complex_double* tauq2,\n                                lapack_complex_double* work, lapack_int lwork );\nlapack_int LAPACKE_zuncsd( int matrix_order, char jobu1, char jobu2,\n                           char jobv1t, char jobv2t, char trans, char signs,\n                           lapack_int m, lapack_int p, lapack_int q,\n                           lapack_complex_double* x11, lapack_int ldx11,\n                           lapack_complex_double* x12, lapack_int ldx12,\n                           lapack_complex_double* x21, lapack_int ldx21,\n                           lapack_complex_double* x22, lapack_int ldx22,\n                           double* theta, lapack_complex_double* u1,\n                           lapack_int ldu1, lapack_complex_double* u2,\n                           lapack_int ldu2, lapack_complex_double* v1t,\n                           lapack_int ldv1t, lapack_complex_double* v2t,\n                           lapack_int ldv2t );\nlapack_int LAPACKE_zuncsd_work( int matrix_order, char jobu1, char jobu2,\n                                char jobv1t, char jobv2t, char trans,\n                                char signs, lapack_int m, lapack_int p,\n                                lapack_int q, lapack_complex_double* x11,\n                                lapack_int ldx11, lapack_complex_double* x12,\n                                lapack_int ldx12, lapack_complex_double* x21,\n                                lapack_int ldx21, lapack_complex_double* x22,\n                                lapack_int ldx22, double* theta,\n                                lapack_complex_double* u1, lapack_int ldu1,\n                                lapack_complex_double* u2, lapack_int ldu2,\n                                lapack_complex_double* v1t, lapack_int ldv1t,\n                                lapack_complex_double* v2t, lapack_int ldv2t,\n                                lapack_complex_double* work, lapack_int lwork,\n                                double* rwork, lapack_int lrwork,\n                                lapack_int* iwork );\n//LAPACK 3.4.0\nlapack_int LAPACKE_sgemqrt( int matrix_order, char side, char trans,\n                            lapack_int m, lapack_int n, lapack_int k,\n                            lapack_int nb, const float* v, lapack_int ldv,\n                            const float* t, lapack_int ldt, float* c,\n                            lapack_int ldc );\nlapack_int LAPACKE_dgemqrt( int matrix_order, char side, char trans,\n                            lapack_int m, lapack_int n, lapack_int k,\n                            lapack_int nb, const double* v, lapack_int ldv,\n                            const double* t, lapack_int ldt, double* c,\n                            lapack_int ldc );\nlapack_int LAPACKE_cgemqrt( int matrix_order, char side, char trans,\n                            lapack_int m, lapack_int n, lapack_int k,\n                            lapack_int nb, const lapack_complex_float* v,\n                            lapack_int ldv, const lapack_complex_float* t,\n                            lapack_int ldt, lapack_complex_float* c,\n                            lapack_int ldc );\nlapack_int LAPACKE_zgemqrt( int matrix_order, char side, char trans,\n                            lapack_int m, lapack_int n, lapack_int k,\n                            lapack_int nb, const lapack_complex_double* v,\n                            lapack_int ldv, const lapack_complex_double* t,\n                            lapack_int ldt, lapack_complex_double* c,\n                            lapack_int ldc );\n\nlapack_int LAPACKE_sgeqrt( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nb, float* a, lapack_int lda, float* t,\n                           lapack_int ldt );\nlapack_int LAPACKE_dgeqrt( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nb, double* a, lapack_int lda, double* t,\n                           lapack_int ldt );\nlapack_int LAPACKE_cgeqrt( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nb, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* t,\n                           lapack_int ldt );\nlapack_int LAPACKE_zgeqrt( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int nb, lapack_complex_double* a,\n                           lapack_int lda, lapack_complex_double* t,\n                           lapack_int ldt );\n\nlapack_int LAPACKE_sgeqrt2( int matrix_order, lapack_int m, lapack_int n,\n                            float* a, lapack_int lda, float* t,\n                            lapack_int ldt );\nlapack_int LAPACKE_dgeqrt2( int matrix_order, lapack_int m, lapack_int n,\n                            double* a, lapack_int lda, double* t,\n                            lapack_int ldt );\nlapack_int LAPACKE_cgeqrt2( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_complex_float* a, lapack_int lda,\n                            lapack_complex_float* t, lapack_int ldt );\nlapack_int LAPACKE_zgeqrt2( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_complex_double* a, lapack_int lda,\n                            lapack_complex_double* t, lapack_int ldt );\n\nlapack_int LAPACKE_sgeqrt3( int matrix_order, lapack_int m, lapack_int n,\n                            float* a, lapack_int lda, float* t,\n                            lapack_int ldt );\nlapack_int LAPACKE_dgeqrt3( int matrix_order, lapack_int m, lapack_int n,\n                            double* a, lapack_int lda, double* t,\n                            lapack_int ldt );\nlapack_int LAPACKE_cgeqrt3( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_complex_float* a, lapack_int lda,\n                            lapack_complex_float* t, lapack_int ldt );\nlapack_int LAPACKE_zgeqrt3( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_complex_double* a, lapack_int lda,\n                            lapack_complex_double* t, lapack_int ldt );\n\nlapack_int LAPACKE_stpmqrt( int matrix_order, char side, char trans,\n                            lapack_int m, lapack_int n, lapack_int k,\n                            lapack_int l, lapack_int nb, const float* v,\n                            lapack_int ldv, const float* t, lapack_int ldt,\n                            float* a, lapack_int lda, float* b,\n                            lapack_int ldb );\nlapack_int LAPACKE_dtpmqrt( int matrix_order, char side, char trans,\n                            lapack_int m, lapack_int n, lapack_int k,\n                            lapack_int l, lapack_int nb, const double* v,\n                            lapack_int ldv, const double* t, lapack_int ldt,\n                            double* a, lapack_int lda, double* b,\n                            lapack_int ldb );\nlapack_int LAPACKE_ctpmqrt( int matrix_order, char side, char trans,\n                            lapack_int m, lapack_int n, lapack_int k,\n                            lapack_int l, lapack_int nb,\n                            const lapack_complex_float* v, lapack_int ldv,\n                            const lapack_complex_float* t, lapack_int ldt,\n                            lapack_complex_float* a, lapack_int lda,\n                            lapack_complex_float* b, lapack_int ldb );\nlapack_int LAPACKE_ztpmqrt( int matrix_order, char side, char trans,\n                            lapack_int m, lapack_int n, lapack_int k,\n                            lapack_int l, lapack_int nb,\n                            const lapack_complex_double* v, lapack_int ldv,\n                            const lapack_complex_double* t, lapack_int ldt,\n                            lapack_complex_double* a, lapack_int lda,\n                            lapack_complex_double* b, lapack_int ldb );\n\nlapack_int LAPACKE_dtpqrt( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int l, lapack_int nb, double* a,\n                           lapack_int lda, double* b, lapack_int ldb, double* t,\n                           lapack_int ldt );\nlapack_int LAPACKE_ctpqrt( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int l, lapack_int nb, lapack_complex_float* a,\n                           lapack_int lda, lapack_complex_float* t,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_int ldt );\nlapack_int LAPACKE_ztpqrt( int matrix_order, lapack_int m, lapack_int n,\n                           lapack_int l, lapack_int nb,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_complex_double* t, lapack_int ldt );\n\nlapack_int LAPACKE_stpqrt2( int matrix_order, lapack_int m, lapack_int n,\n                            float* a, lapack_int lda, float* b, lapack_int ldb,\n                            float* t, lapack_int ldt );\nlapack_int LAPACKE_dtpqrt2( int matrix_order, lapack_int m, lapack_int n,\n                            double* a, lapack_int lda, double* b,\n                            lapack_int ldb, double* t, lapack_int ldt );\nlapack_int LAPACKE_ctpqrt2( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_complex_float* a, lapack_int lda,\n                            lapack_complex_float* b, lapack_int ldb,\n                            lapack_complex_float* t, lapack_int ldt );\nlapack_int LAPACKE_ztpqrt2( int matrix_order, lapack_int m, lapack_int n,\n                            lapack_complex_double* a, lapack_int lda,\n                            lapack_complex_double* b, lapack_int ldb,\n                            lapack_complex_double* t, lapack_int ldt );\n\nlapack_int LAPACKE_stprfb( int matrix_order, char side, char trans, char direct,\n                           char storev, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_int l, const float* v,\n                           lapack_int ldv, const float* t, lapack_int ldt,\n                           float* a, lapack_int lda, float* b, lapack_int ldb,\n                           lapack_int myldwork );\nlapack_int LAPACKE_dtprfb( int matrix_order, char side, char trans, char direct,\n                           char storev, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_int l, const double* v,\n                           lapack_int ldv, const double* t, lapack_int ldt,\n                           double* a, lapack_int lda, double* b, lapack_int ldb,\n                           lapack_int myldwork );\nlapack_int LAPACKE_ctprfb( int matrix_order, char side, char trans, char direct,\n                           char storev, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_int l,\n                           const lapack_complex_float* v, lapack_int ldv,\n                           const lapack_complex_float* t, lapack_int ldt,\n                           lapack_complex_float* a, lapack_int lda,\n                           lapack_complex_float* b, lapack_int ldb,\n                           lapack_int myldwork );\nlapack_int LAPACKE_ztprfb( int matrix_order, char side, char trans, char direct,\n                           char storev, lapack_int m, lapack_int n,\n                           lapack_int k, lapack_int l,\n                           const lapack_complex_double* v, lapack_int ldv,\n                           const lapack_complex_double* t, lapack_int ldt,\n                           lapack_complex_double* a, lapack_int lda,\n                           lapack_complex_double* b, lapack_int ldb,\n                           lapack_int myldwork );\n\nlapack_int LAPACKE_sgemqrt_work( int matrix_order, char side, char trans,\n                                 lapack_int m, lapack_int n, lapack_int k,\n                                 lapack_int nb, const float* v, lapack_int ldv,\n                                 const float* t, lapack_int ldt, float* c,\n                                 lapack_int ldc, float* work );\nlapack_int LAPACKE_dgemqrt_work( int matrix_order, char side, char trans,\n                                 lapack_int m, lapack_int n, lapack_int k,\n                                 lapack_int nb, const double* v, lapack_int ldv,\n                                 const double* t, lapack_int ldt, double* c,\n                                 lapack_int ldc, double* work );\nlapack_int LAPACKE_cgemqrt_work( int matrix_order, char side, char trans,\n                                 lapack_int m, lapack_int n, lapack_int k,\n                                 lapack_int nb, const lapack_complex_float* v,\n                                 lapack_int ldv, const lapack_complex_float* t,\n                                 lapack_int ldt, lapack_complex_float* c,\n                                 lapack_int ldc, lapack_complex_float* work );\nlapack_int LAPACKE_zgemqrt_work( int matrix_order, char side, char trans,\n                                 lapack_int m, lapack_int n, lapack_int k,\n                                 lapack_int nb, const lapack_complex_double* v,\n                                 lapack_int ldv, const lapack_complex_double* t,\n                                 lapack_int ldt, lapack_complex_double* c,\n                                 lapack_int ldc, lapack_complex_double* work );\n\nlapack_int LAPACKE_sgeqrt_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nb, float* a, lapack_int lda,\n                                float* t, lapack_int ldt, float* work );\nlapack_int LAPACKE_dgeqrt_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nb, double* a, lapack_int lda,\n                                double* t, lapack_int ldt, double* work );\nlapack_int LAPACKE_cgeqrt_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nb, lapack_complex_float* a,\n                                lapack_int lda, lapack_complex_float* t,\n                                lapack_int ldt, lapack_complex_float* work );\nlapack_int LAPACKE_zgeqrt_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int nb, lapack_complex_double* a,\n                                lapack_int lda, lapack_complex_double* t,\n                                lapack_int ldt, lapack_complex_double* work );\n\nlapack_int LAPACKE_sgeqrt2_work( int matrix_order, lapack_int m, lapack_int n,\n                                 float* a, lapack_int lda, float* t,\n                                 lapack_int ldt );\nlapack_int LAPACKE_dgeqrt2_work( int matrix_order, lapack_int m, lapack_int n,\n                                 double* a, lapack_int lda, double* t,\n                                 lapack_int ldt );\nlapack_int LAPACKE_cgeqrt2_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 lapack_complex_float* t, lapack_int ldt );\nlapack_int LAPACKE_zgeqrt2_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 lapack_complex_double* t, lapack_int ldt );\n\nlapack_int LAPACKE_sgeqrt3_work( int matrix_order, lapack_int m, lapack_int n,\n                                 float* a, lapack_int lda, float* t,\n                                 lapack_int ldt );\nlapack_int LAPACKE_dgeqrt3_work( int matrix_order, lapack_int m, lapack_int n,\n                                 double* a, lapack_int lda, double* t,\n                                 lapack_int ldt );\nlapack_int LAPACKE_cgeqrt3_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 lapack_complex_float* t, lapack_int ldt );\nlapack_int LAPACKE_zgeqrt3_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 lapack_complex_double* t, lapack_int ldt );\n\nlapack_int LAPACKE_stpmqrt_work( int matrix_order, char side, char trans,\n                                 lapack_int m, lapack_int n, lapack_int k,\n                                 lapack_int l, lapack_int nb, const float* v,\n                                 lapack_int ldv, const float* t, lapack_int ldt,\n                                 float* a, lapack_int lda, float* b,\n                                 lapack_int ldb, float* work );\nlapack_int LAPACKE_dtpmqrt_work( int matrix_order, char side, char trans,\n                                 lapack_int m, lapack_int n, lapack_int k,\n                                 lapack_int l, lapack_int nb, const double* v,\n                                 lapack_int ldv, const double* t,\n                                 lapack_int ldt, double* a, lapack_int lda,\n                                 double* b, lapack_int ldb, double* work );\nlapack_int LAPACKE_ctpmqrt_work( int matrix_order, char side, char trans,\n                                 lapack_int m, lapack_int n, lapack_int k,\n                                 lapack_int l, lapack_int nb,\n                                 const lapack_complex_float* v, lapack_int ldv,\n                                 const lapack_complex_float* t, lapack_int ldt,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 lapack_complex_float* b, lapack_int ldb,\n                                 lapack_complex_float* work );\nlapack_int LAPACKE_ztpmqrt_work( int matrix_order, char side, char trans,\n                                 lapack_int m, lapack_int n, lapack_int k,\n                                 lapack_int l, lapack_int nb,\n                                 const lapack_complex_double* v, lapack_int ldv,\n                                 const lapack_complex_double* t, lapack_int ldt,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* work );\n\nlapack_int LAPACKE_dtpqrt_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int l, lapack_int nb, double* a,\n                                lapack_int lda, double* b, lapack_int ldb,\n                                double* t, lapack_int ldt, double* work );\nlapack_int LAPACKE_ctpqrt_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int l, lapack_int nb,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* t,\n                                lapack_complex_float* b, lapack_int ldb,\n                                lapack_int ldt, lapack_complex_float* work );\nlapack_int LAPACKE_ztpqrt_work( int matrix_order, lapack_int m, lapack_int n,\n                                lapack_int l, lapack_int nb,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                lapack_complex_double* t, lapack_int ldt,\n                                lapack_complex_double* work );\n\nlapack_int LAPACKE_stpqrt2_work( int matrix_order, lapack_int m, lapack_int n,\n                                 float* a, lapack_int lda, float* b,\n                                 lapack_int ldb, float* t, lapack_int ldt );\nlapack_int LAPACKE_dtpqrt2_work( int matrix_order, lapack_int m, lapack_int n,\n                                 double* a, lapack_int lda, double* b,\n                                 lapack_int ldb, double* t, lapack_int ldt );\nlapack_int LAPACKE_ctpqrt2_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_complex_float* a, lapack_int lda,\n                                 lapack_complex_float* b, lapack_int ldb,\n                                 lapack_complex_float* t, lapack_int ldt );\nlapack_int LAPACKE_ztpqrt2_work( int matrix_order, lapack_int m, lapack_int n,\n                                 lapack_complex_double* a, lapack_int lda,\n                                 lapack_complex_double* b, lapack_int ldb,\n                                 lapack_complex_double* t, lapack_int ldt );\n\nlapack_int LAPACKE_stprfb_work( int matrix_order, char side, char trans,\n                                char direct, char storev, lapack_int m,\n                                lapack_int n, lapack_int k, lapack_int l,\n                                const float* v, lapack_int ldv, const float* t,\n                                lapack_int ldt, float* a, lapack_int lda,\n                                float* b, lapack_int ldb, const float* mywork,\n                                lapack_int myldwork );\nlapack_int LAPACKE_dtprfb_work( int matrix_order, char side, char trans,\n                                char direct, char storev, lapack_int m,\n                                lapack_int n, lapack_int k, lapack_int l,\n                                const double* v, lapack_int ldv,\n                                const double* t, lapack_int ldt, double* a,\n                                lapack_int lda, double* b, lapack_int ldb,\n                                const double* mywork, lapack_int myldwork );\nlapack_int LAPACKE_ctprfb_work( int matrix_order, char side, char trans,\n                                char direct, char storev, lapack_int m,\n                                lapack_int n, lapack_int k, lapack_int l,\n                                const lapack_complex_float* v, lapack_int ldv,\n                                const lapack_complex_float* t, lapack_int ldt,\n                                lapack_complex_float* a, lapack_int lda,\n                                lapack_complex_float* b, lapack_int ldb,\n                                const float* mywork, lapack_int myldwork );\nlapack_int LAPACKE_ztprfb_work( int matrix_order, char side, char trans,\n                                char direct, char storev, lapack_int m,\n                                lapack_int n, lapack_int k, lapack_int l,\n                                const lapack_complex_double* v, lapack_int ldv,\n                                const lapack_complex_double* t, lapack_int ldt,\n                                lapack_complex_double* a, lapack_int lda,\n                                lapack_complex_double* b, lapack_int ldb,\n                                const double* mywork, lapack_int myldwork );\n//LAPACK 3.X.X\nlapack_int LAPACKE_csyr( int matrix_order, char uplo, lapack_int n,\n                             lapack_complex_float alpha,\n                             const lapack_complex_float* x, lapack_int incx,\n                             lapack_complex_float* a, lapack_int lda );\nlapack_int LAPACKE_zsyr( int matrix_order, char uplo, lapack_int n,\n                             lapack_complex_double alpha,\n                             const lapack_complex_double* x, lapack_int incx,\n                             lapack_complex_double* a, lapack_int lda );\n\nlapack_int LAPACKE_csyr_work( int matrix_order, char uplo, lapack_int n,\n                                  lapack_complex_float alpha,\n                                  const lapack_complex_float* x,\n                                  lapack_int incx, lapack_complex_float* a,\n                                  lapack_int lda );\nlapack_int LAPACKE_zsyr_work( int matrix_order, char uplo, lapack_int n,\n                                  lapack_complex_double alpha,\n                                  const lapack_complex_double* x,\n                                  lapack_int incx, lapack_complex_double* a,\n                                  lapack_int lda );\n\n\n\n#define LAPACK_sgetrf LAPACK_GLOBAL(sgetrf,SGETRF)\n#define LAPACK_dgetrf LAPACK_GLOBAL(dgetrf,DGETRF)\n#define LAPACK_cgetrf LAPACK_GLOBAL(cgetrf,CGETRF)\n#define LAPACK_zgetrf LAPACK_GLOBAL(zgetrf,ZGETRF)\n#define LAPACK_sgbtrf LAPACK_GLOBAL(sgbtrf,SGBTRF)\n#define LAPACK_dgbtrf LAPACK_GLOBAL(dgbtrf,DGBTRF)\n#define LAPACK_cgbtrf LAPACK_GLOBAL(cgbtrf,CGBTRF)\n#define LAPACK_zgbtrf LAPACK_GLOBAL(zgbtrf,ZGBTRF)\n#define LAPACK_sgttrf LAPACK_GLOBAL(sgttrf,SGTTRF)\n#define LAPACK_dgttrf LAPACK_GLOBAL(dgttrf,DGTTRF)\n#define LAPACK_cgttrf LAPACK_GLOBAL(cgttrf,CGTTRF)\n#define LAPACK_zgttrf LAPACK_GLOBAL(zgttrf,ZGTTRF)\n#define LAPACK_spotrf LAPACK_GLOBAL(spotrf,SPOTRF)\n#define LAPACK_dpotrf LAPACK_GLOBAL(dpotrf,DPOTRF)\n#define LAPACK_cpotrf LAPACK_GLOBAL(cpotrf,CPOTRF)\n#define LAPACK_zpotrf LAPACK_GLOBAL(zpotrf,ZPOTRF)\n#define LAPACK_dpstrf LAPACK_GLOBAL(dpstrf,DPSTRF)\n#define LAPACK_spstrf LAPACK_GLOBAL(spstrf,SPSTRF)\n#define LAPACK_zpstrf LAPACK_GLOBAL(zpstrf,ZPSTRF)\n#define LAPACK_cpstrf LAPACK_GLOBAL(cpstrf,CPSTRF)\n#define LAPACK_dpftrf LAPACK_GLOBAL(dpftrf,DPFTRF)\n#define LAPACK_spftrf LAPACK_GLOBAL(spftrf,SPFTRF)\n#define LAPACK_zpftrf LAPACK_GLOBAL(zpftrf,ZPFTRF)\n#define LAPACK_cpftrf LAPACK_GLOBAL(cpftrf,CPFTRF)\n#define LAPACK_spptrf LAPACK_GLOBAL(spptrf,SPPTRF)\n#define LAPACK_dpptrf LAPACK_GLOBAL(dpptrf,DPPTRF)\n#define LAPACK_cpptrf LAPACK_GLOBAL(cpptrf,CPPTRF)\n#define LAPACK_zpptrf LAPACK_GLOBAL(zpptrf,ZPPTRF)\n#define LAPACK_spbtrf LAPACK_GLOBAL(spbtrf,SPBTRF)\n#define LAPACK_dpbtrf LAPACK_GLOBAL(dpbtrf,DPBTRF)\n#define LAPACK_cpbtrf LAPACK_GLOBAL(cpbtrf,CPBTRF)\n#define LAPACK_zpbtrf LAPACK_GLOBAL(zpbtrf,ZPBTRF)\n#define LAPACK_spttrf LAPACK_GLOBAL(spttrf,SPTTRF)\n#define LAPACK_dpttrf LAPACK_GLOBAL(dpttrf,DPTTRF)\n#define LAPACK_cpttrf LAPACK_GLOBAL(cpttrf,CPTTRF)\n#define LAPACK_zpttrf LAPACK_GLOBAL(zpttrf,ZPTTRF)\n#define LAPACK_ssytrf LAPACK_GLOBAL(ssytrf,SSYTRF)\n#define LAPACK_dsytrf LAPACK_GLOBAL(dsytrf,DSYTRF)\n#define LAPACK_csytrf LAPACK_GLOBAL(csytrf,CSYTRF)\n#define LAPACK_zsytrf LAPACK_GLOBAL(zsytrf,ZSYTRF)\n#define LAPACK_chetrf LAPACK_GLOBAL(chetrf,CHETRF)\n#define LAPACK_zhetrf LAPACK_GLOBAL(zhetrf,ZHETRF)\n#define LAPACK_ssptrf LAPACK_GLOBAL(ssptrf,SSPTRF)\n#define LAPACK_dsptrf LAPACK_GLOBAL(dsptrf,DSPTRF)\n#define LAPACK_csptrf LAPACK_GLOBAL(csptrf,CSPTRF)\n#define LAPACK_zsptrf LAPACK_GLOBAL(zsptrf,ZSPTRF)\n#define LAPACK_chptrf LAPACK_GLOBAL(chptrf,CHPTRF)\n#define LAPACK_zhptrf LAPACK_GLOBAL(zhptrf,ZHPTRF)\n#define LAPACK_sgetrs LAPACK_GLOBAL(sgetrs,SGETRS)\n#define LAPACK_dgetrs LAPACK_GLOBAL(dgetrs,DGETRS)\n#define LAPACK_cgetrs LAPACK_GLOBAL(cgetrs,CGETRS)\n#define LAPACK_zgetrs LAPACK_GLOBAL(zgetrs,ZGETRS)\n#define LAPACK_sgbtrs LAPACK_GLOBAL(sgbtrs,SGBTRS)\n#define LAPACK_dgbtrs LAPACK_GLOBAL(dgbtrs,DGBTRS)\n#define LAPACK_cgbtrs LAPACK_GLOBAL(cgbtrs,CGBTRS)\n#define LAPACK_zgbtrs LAPACK_GLOBAL(zgbtrs,ZGBTRS)\n#define LAPACK_sgttrs LAPACK_GLOBAL(sgttrs,SGTTRS)\n#define LAPACK_dgttrs LAPACK_GLOBAL(dgttrs,DGTTRS)\n#define LAPACK_cgttrs LAPACK_GLOBAL(cgttrs,CGTTRS)\n#define LAPACK_zgttrs LAPACK_GLOBAL(zgttrs,ZGTTRS)\n#define LAPACK_spotrs LAPACK_GLOBAL(spotrs,SPOTRS)\n#define LAPACK_dpotrs LAPACK_GLOBAL(dpotrs,DPOTRS)\n#define LAPACK_cpotrs LAPACK_GLOBAL(cpotrs,CPOTRS)\n#define LAPACK_zpotrs LAPACK_GLOBAL(zpotrs,ZPOTRS)\n#define LAPACK_dpftrs LAPACK_GLOBAL(dpftrs,DPFTRS)\n#define LAPACK_spftrs LAPACK_GLOBAL(spftrs,SPFTRS)\n#define LAPACK_zpftrs LAPACK_GLOBAL(zpftrs,ZPFTRS)\n#define LAPACK_cpftrs LAPACK_GLOBAL(cpftrs,CPFTRS)\n#define LAPACK_spptrs LAPACK_GLOBAL(spptrs,SPPTRS)\n#define LAPACK_dpptrs LAPACK_GLOBAL(dpptrs,DPPTRS)\n#define LAPACK_cpptrs LAPACK_GLOBAL(cpptrs,CPPTRS)\n#define LAPACK_zpptrs LAPACK_GLOBAL(zpptrs,ZPPTRS)\n#define LAPACK_spbtrs LAPACK_GLOBAL(spbtrs,SPBTRS)\n#define LAPACK_dpbtrs LAPACK_GLOBAL(dpbtrs,DPBTRS)\n#define LAPACK_cpbtrs LAPACK_GLOBAL(cpbtrs,CPBTRS)\n#define LAPACK_zpbtrs LAPACK_GLOBAL(zpbtrs,ZPBTRS)\n#define LAPACK_spttrs LAPACK_GLOBAL(spttrs,SPTTRS)\n#define LAPACK_dpttrs LAPACK_GLOBAL(dpttrs,DPTTRS)\n#define LAPACK_cpttrs LAPACK_GLOBAL(cpttrs,CPTTRS)\n#define LAPACK_zpttrs LAPACK_GLOBAL(zpttrs,ZPTTRS)\n#define LAPACK_ssytrs LAPACK_GLOBAL(ssytrs,SSYTRS)\n#define LAPACK_dsytrs LAPACK_GLOBAL(dsytrs,DSYTRS)\n#define LAPACK_csytrs LAPACK_GLOBAL(csytrs,CSYTRS)\n#define LAPACK_zsytrs LAPACK_GLOBAL(zsytrs,ZSYTRS)\n#define LAPACK_chetrs LAPACK_GLOBAL(chetrs,CHETRS)\n#define LAPACK_zhetrs LAPACK_GLOBAL(zhetrs,ZHETRS)\n#define LAPACK_ssptrs LAPACK_GLOBAL(ssptrs,SSPTRS)\n#define LAPACK_dsptrs LAPACK_GLOBAL(dsptrs,DSPTRS)\n#define LAPACK_csptrs LAPACK_GLOBAL(csptrs,CSPTRS)\n#define LAPACK_zsptrs LAPACK_GLOBAL(zsptrs,ZSPTRS)\n#define LAPACK_chptrs LAPACK_GLOBAL(chptrs,CHPTRS)\n#define LAPACK_zhptrs LAPACK_GLOBAL(zhptrs,ZHPTRS)\n#define LAPACK_strtrs LAPACK_GLOBAL(strtrs,STRTRS)\n#define LAPACK_dtrtrs LAPACK_GLOBAL(dtrtrs,DTRTRS)\n#define LAPACK_ctrtrs LAPACK_GLOBAL(ctrtrs,CTRTRS)\n#define LAPACK_ztrtrs LAPACK_GLOBAL(ztrtrs,ZTRTRS)\n#define LAPACK_stptrs LAPACK_GLOBAL(stptrs,STPTRS)\n#define LAPACK_dtptrs LAPACK_GLOBAL(dtptrs,DTPTRS)\n#define LAPACK_ctptrs LAPACK_GLOBAL(ctptrs,CTPTRS)\n#define LAPACK_ztptrs LAPACK_GLOBAL(ztptrs,ZTPTRS)\n#define LAPACK_stbtrs LAPACK_GLOBAL(stbtrs,STBTRS)\n#define LAPACK_dtbtrs LAPACK_GLOBAL(dtbtrs,DTBTRS)\n#define LAPACK_ctbtrs LAPACK_GLOBAL(ctbtrs,CTBTRS)\n#define LAPACK_ztbtrs LAPACK_GLOBAL(ztbtrs,ZTBTRS)\n#define LAPACK_sgecon LAPACK_GLOBAL(sgecon,SGECON)\n#define LAPACK_dgecon LAPACK_GLOBAL(dgecon,DGECON)\n#define LAPACK_cgecon LAPACK_GLOBAL(cgecon,CGECON)\n#define LAPACK_zgecon LAPACK_GLOBAL(zgecon,ZGECON)\n#define LAPACK_sgbcon LAPACK_GLOBAL(sgbcon,SGBCON)\n#define LAPACK_dgbcon LAPACK_GLOBAL(dgbcon,DGBCON)\n#define LAPACK_cgbcon LAPACK_GLOBAL(cgbcon,CGBCON)\n#define LAPACK_zgbcon LAPACK_GLOBAL(zgbcon,ZGBCON)\n#define LAPACK_sgtcon LAPACK_GLOBAL(sgtcon,SGTCON)\n#define LAPACK_dgtcon LAPACK_GLOBAL(dgtcon,DGTCON)\n#define LAPACK_cgtcon LAPACK_GLOBAL(cgtcon,CGTCON)\n#define LAPACK_zgtcon LAPACK_GLOBAL(zgtcon,ZGTCON)\n#define LAPACK_spocon LAPACK_GLOBAL(spocon,SPOCON)\n#define LAPACK_dpocon LAPACK_GLOBAL(dpocon,DPOCON)\n#define LAPACK_cpocon LAPACK_GLOBAL(cpocon,CPOCON)\n#define LAPACK_zpocon LAPACK_GLOBAL(zpocon,ZPOCON)\n#define LAPACK_sppcon LAPACK_GLOBAL(sppcon,SPPCON)\n#define LAPACK_dppcon LAPACK_GLOBAL(dppcon,DPPCON)\n#define LAPACK_cppcon LAPACK_GLOBAL(cppcon,CPPCON)\n#define LAPACK_zppcon LAPACK_GLOBAL(zppcon,ZPPCON)\n#define LAPACK_spbcon LAPACK_GLOBAL(spbcon,SPBCON)\n#define LAPACK_dpbcon LAPACK_GLOBAL(dpbcon,DPBCON)\n#define LAPACK_cpbcon LAPACK_GLOBAL(cpbcon,CPBCON)\n#define LAPACK_zpbcon LAPACK_GLOBAL(zpbcon,ZPBCON)\n#define LAPACK_sptcon LAPACK_GLOBAL(sptcon,SPTCON)\n#define LAPACK_dptcon LAPACK_GLOBAL(dptcon,DPTCON)\n#define LAPACK_cptcon LAPACK_GLOBAL(cptcon,CPTCON)\n#define LAPACK_zptcon LAPACK_GLOBAL(zptcon,ZPTCON)\n#define LAPACK_ssycon LAPACK_GLOBAL(ssycon,SSYCON)\n#define LAPACK_dsycon LAPACK_GLOBAL(dsycon,DSYCON)\n#define LAPACK_csycon LAPACK_GLOBAL(csycon,CSYCON)\n#define LAPACK_zsycon LAPACK_GLOBAL(zsycon,ZSYCON)\n#define LAPACK_checon LAPACK_GLOBAL(checon,CHECON)\n#define LAPACK_zhecon LAPACK_GLOBAL(zhecon,ZHECON)\n#define LAPACK_sspcon LAPACK_GLOBAL(sspcon,SSPCON)\n#define LAPACK_dspcon LAPACK_GLOBAL(dspcon,DSPCON)\n#define LAPACK_cspcon LAPACK_GLOBAL(cspcon,CSPCON)\n#define LAPACK_zspcon LAPACK_GLOBAL(zspcon,ZSPCON)\n#define LAPACK_chpcon LAPACK_GLOBAL(chpcon,CHPCON)\n#define LAPACK_zhpcon LAPACK_GLOBAL(zhpcon,ZHPCON)\n#define LAPACK_strcon LAPACK_GLOBAL(strcon,STRCON)\n#define LAPACK_dtrcon LAPACK_GLOBAL(dtrcon,DTRCON)\n#define LAPACK_ctrcon LAPACK_GLOBAL(ctrcon,CTRCON)\n#define LAPACK_ztrcon LAPACK_GLOBAL(ztrcon,ZTRCON)\n#define LAPACK_stpcon LAPACK_GLOBAL(stpcon,STPCON)\n#define LAPACK_dtpcon LAPACK_GLOBAL(dtpcon,DTPCON)\n#define LAPACK_ctpcon LAPACK_GLOBAL(ctpcon,CTPCON)\n#define LAPACK_ztpcon LAPACK_GLOBAL(ztpcon,ZTPCON)\n#define LAPACK_stbcon LAPACK_GLOBAL(stbcon,STBCON)\n#define LAPACK_dtbcon LAPACK_GLOBAL(dtbcon,DTBCON)\n#define LAPACK_ctbcon LAPACK_GLOBAL(ctbcon,CTBCON)\n#define LAPACK_ztbcon LAPACK_GLOBAL(ztbcon,ZTBCON)\n#define LAPACK_sgerfs LAPACK_GLOBAL(sgerfs,SGERFS)\n#define LAPACK_dgerfs LAPACK_GLOBAL(dgerfs,DGERFS)\n#define LAPACK_cgerfs LAPACK_GLOBAL(cgerfs,CGERFS)\n#define LAPACK_zgerfs LAPACK_GLOBAL(zgerfs,ZGERFS)\n#define LAPACK_dgerfsx LAPACK_GLOBAL(dgerfsx,DGERFSX)\n#define LAPACK_sgerfsx LAPACK_GLOBAL(sgerfsx,SGERFSX)\n#define LAPACK_zgerfsx LAPACK_GLOBAL(zgerfsx,ZGERFSX)\n#define LAPACK_cgerfsx LAPACK_GLOBAL(cgerfsx,CGERFSX)\n#define LAPACK_sgbrfs LAPACK_GLOBAL(sgbrfs,SGBRFS)\n#define LAPACK_dgbrfs LAPACK_GLOBAL(dgbrfs,DGBRFS)\n#define LAPACK_cgbrfs LAPACK_GLOBAL(cgbrfs,CGBRFS)\n#define LAPACK_zgbrfs LAPACK_GLOBAL(zgbrfs,ZGBRFS)\n#define LAPACK_dgbrfsx LAPACK_GLOBAL(dgbrfsx,DGBRFSX)\n#define LAPACK_sgbrfsx LAPACK_GLOBAL(sgbrfsx,SGBRFSX)\n#define LAPACK_zgbrfsx LAPACK_GLOBAL(zgbrfsx,ZGBRFSX)\n#define LAPACK_cgbrfsx LAPACK_GLOBAL(cgbrfsx,CGBRFSX)\n#define LAPACK_sgtrfs LAPACK_GLOBAL(sgtrfs,SGTRFS)\n#define LAPACK_dgtrfs LAPACK_GLOBAL(dgtrfs,DGTRFS)\n#define LAPACK_cgtrfs LAPACK_GLOBAL(cgtrfs,CGTRFS)\n#define LAPACK_zgtrfs LAPACK_GLOBAL(zgtrfs,ZGTRFS)\n#define LAPACK_sporfs LAPACK_GLOBAL(sporfs,SPORFS)\n#define LAPACK_dporfs LAPACK_GLOBAL(dporfs,DPORFS)\n#define LAPACK_cporfs LAPACK_GLOBAL(cporfs,CPORFS)\n#define LAPACK_zporfs LAPACK_GLOBAL(zporfs,ZPORFS)\n#define LAPACK_dporfsx LAPACK_GLOBAL(dporfsx,DPORFSX)\n#define LAPACK_sporfsx LAPACK_GLOBAL(sporfsx,SPORFSX)\n#define LAPACK_zporfsx LAPACK_GLOBAL(zporfsx,ZPORFSX)\n#define LAPACK_cporfsx LAPACK_GLOBAL(cporfsx,CPORFSX)\n#define LAPACK_spprfs LAPACK_GLOBAL(spprfs,SPPRFS)\n#define LAPACK_dpprfs LAPACK_GLOBAL(dpprfs,DPPRFS)\n#define LAPACK_cpprfs LAPACK_GLOBAL(cpprfs,CPPRFS)\n#define LAPACK_zpprfs LAPACK_GLOBAL(zpprfs,ZPPRFS)\n#define LAPACK_spbrfs LAPACK_GLOBAL(spbrfs,SPBRFS)\n#define LAPACK_dpbrfs LAPACK_GLOBAL(dpbrfs,DPBRFS)\n#define LAPACK_cpbrfs LAPACK_GLOBAL(cpbrfs,CPBRFS)\n#define LAPACK_zpbrfs LAPACK_GLOBAL(zpbrfs,ZPBRFS)\n#define LAPACK_sptrfs LAPACK_GLOBAL(sptrfs,SPTRFS)\n#define LAPACK_dptrfs LAPACK_GLOBAL(dptrfs,DPTRFS)\n#define LAPACK_cptrfs LAPACK_GLOBAL(cptrfs,CPTRFS)\n#define LAPACK_zptrfs LAPACK_GLOBAL(zptrfs,ZPTRFS)\n#define LAPACK_ssyrfs LAPACK_GLOBAL(ssyrfs,SSYRFS)\n#define LAPACK_dsyrfs LAPACK_GLOBAL(dsyrfs,DSYRFS)\n#define LAPACK_csyrfs LAPACK_GLOBAL(csyrfs,CSYRFS)\n#define LAPACK_zsyrfs LAPACK_GLOBAL(zsyrfs,ZSYRFS)\n#define LAPACK_dsyrfsx LAPACK_GLOBAL(dsyrfsx,DSYRFSX)\n#define LAPACK_ssyrfsx LAPACK_GLOBAL(ssyrfsx,SSYRFSX)\n#define LAPACK_zsyrfsx LAPACK_GLOBAL(zsyrfsx,ZSYRFSX)\n#define LAPACK_csyrfsx LAPACK_GLOBAL(csyrfsx,CSYRFSX)\n#define LAPACK_cherfs LAPACK_GLOBAL(cherfs,CHERFS)\n#define LAPACK_zherfs LAPACK_GLOBAL(zherfs,ZHERFS)\n#define LAPACK_zherfsx LAPACK_GLOBAL(zherfsx,ZHERFSX)\n#define LAPACK_cherfsx LAPACK_GLOBAL(cherfsx,CHERFSX)\n#define LAPACK_ssprfs LAPACK_GLOBAL(ssprfs,SSPRFS)\n#define LAPACK_dsprfs LAPACK_GLOBAL(dsprfs,DSPRFS)\n#define LAPACK_csprfs LAPACK_GLOBAL(csprfs,CSPRFS)\n#define LAPACK_zsprfs LAPACK_GLOBAL(zsprfs,ZSPRFS)\n#define LAPACK_chprfs LAPACK_GLOBAL(chprfs,CHPRFS)\n#define LAPACK_zhprfs LAPACK_GLOBAL(zhprfs,ZHPRFS)\n#define LAPACK_strrfs LAPACK_GLOBAL(strrfs,STRRFS)\n#define LAPACK_dtrrfs LAPACK_GLOBAL(dtrrfs,DTRRFS)\n#define LAPACK_ctrrfs LAPACK_GLOBAL(ctrrfs,CTRRFS)\n#define LAPACK_ztrrfs LAPACK_GLOBAL(ztrrfs,ZTRRFS)\n#define LAPACK_stprfs LAPACK_GLOBAL(stprfs,STPRFS)\n#define LAPACK_dtprfs LAPACK_GLOBAL(dtprfs,DTPRFS)\n#define LAPACK_ctprfs LAPACK_GLOBAL(ctprfs,CTPRFS)\n#define LAPACK_ztprfs LAPACK_GLOBAL(ztprfs,ZTPRFS)\n#define LAPACK_stbrfs LAPACK_GLOBAL(stbrfs,STBRFS)\n#define LAPACK_dtbrfs LAPACK_GLOBAL(dtbrfs,DTBRFS)\n#define LAPACK_ctbrfs LAPACK_GLOBAL(ctbrfs,CTBRFS)\n#define LAPACK_ztbrfs LAPACK_GLOBAL(ztbrfs,ZTBRFS)\n#define LAPACK_sgetri LAPACK_GLOBAL(sgetri,SGETRI)\n#define LAPACK_dgetri LAPACK_GLOBAL(dgetri,DGETRI)\n#define LAPACK_cgetri LAPACK_GLOBAL(cgetri,CGETRI)\n#define LAPACK_zgetri LAPACK_GLOBAL(zgetri,ZGETRI)\n#define LAPACK_spotri LAPACK_GLOBAL(spotri,SPOTRI)\n#define LAPACK_dpotri LAPACK_GLOBAL(dpotri,DPOTRI)\n#define LAPACK_cpotri LAPACK_GLOBAL(cpotri,CPOTRI)\n#define LAPACK_zpotri LAPACK_GLOBAL(zpotri,ZPOTRI)\n#define LAPACK_dpftri LAPACK_GLOBAL(dpftri,DPFTRI)\n#define LAPACK_spftri LAPACK_GLOBAL(spftri,SPFTRI)\n#define LAPACK_zpftri LAPACK_GLOBAL(zpftri,ZPFTRI)\n#define LAPACK_cpftri LAPACK_GLOBAL(cpftri,CPFTRI)\n#define LAPACK_spptri LAPACK_GLOBAL(spptri,SPPTRI)\n#define LAPACK_dpptri LAPACK_GLOBAL(dpptri,DPPTRI)\n#define LAPACK_cpptri LAPACK_GLOBAL(cpptri,CPPTRI)\n#define LAPACK_zpptri LAPACK_GLOBAL(zpptri,ZPPTRI)\n#define LAPACK_ssytri LAPACK_GLOBAL(ssytri,SSYTRI)\n#define LAPACK_dsytri LAPACK_GLOBAL(dsytri,DSYTRI)\n#define LAPACK_csytri LAPACK_GLOBAL(csytri,CSYTRI)\n#define LAPACK_zsytri LAPACK_GLOBAL(zsytri,ZSYTRI)\n#define LAPACK_chetri LAPACK_GLOBAL(chetri,CHETRI)\n#define LAPACK_zhetri LAPACK_GLOBAL(zhetri,ZHETRI)\n#define LAPACK_ssptri LAPACK_GLOBAL(ssptri,SSPTRI)\n#define LAPACK_dsptri LAPACK_GLOBAL(dsptri,DSPTRI)\n#define LAPACK_csptri LAPACK_GLOBAL(csptri,CSPTRI)\n#define LAPACK_zsptri LAPACK_GLOBAL(zsptri,ZSPTRI)\n#define LAPACK_chptri LAPACK_GLOBAL(chptri,CHPTRI)\n#define LAPACK_zhptri LAPACK_GLOBAL(zhptri,ZHPTRI)\n#define LAPACK_strtri LAPACK_GLOBAL(strtri,STRTRI)\n#define LAPACK_dtrtri LAPACK_GLOBAL(dtrtri,DTRTRI)\n#define LAPACK_ctrtri LAPACK_GLOBAL(ctrtri,CTRTRI)\n#define LAPACK_ztrtri LAPACK_GLOBAL(ztrtri,ZTRTRI)\n#define LAPACK_dtftri LAPACK_GLOBAL(dtftri,DTFTRI)\n#define LAPACK_stftri LAPACK_GLOBAL(stftri,STFTRI)\n#define LAPACK_ztftri LAPACK_GLOBAL(ztftri,ZTFTRI)\n#define LAPACK_ctftri LAPACK_GLOBAL(ctftri,CTFTRI)\n#define LAPACK_stptri LAPACK_GLOBAL(stptri,STPTRI)\n#define LAPACK_dtptri LAPACK_GLOBAL(dtptri,DTPTRI)\n#define LAPACK_ctptri LAPACK_GLOBAL(ctptri,CTPTRI)\n#define LAPACK_ztptri LAPACK_GLOBAL(ztptri,ZTPTRI)\n#define LAPACK_sgeequ LAPACK_GLOBAL(sgeequ,SGEEQU)\n#define LAPACK_dgeequ LAPACK_GLOBAL(dgeequ,DGEEQU)\n#define LAPACK_cgeequ LAPACK_GLOBAL(cgeequ,CGEEQU)\n#define LAPACK_zgeequ LAPACK_GLOBAL(zgeequ,ZGEEQU)\n#define LAPACK_dgeequb LAPACK_GLOBAL(dgeequb,DGEEQUB)\n#define LAPACK_sgeequb LAPACK_GLOBAL(sgeequb,SGEEQUB)\n#define LAPACK_zgeequb LAPACK_GLOBAL(zgeequb,ZGEEQUB)\n#define LAPACK_cgeequb LAPACK_GLOBAL(cgeequb,CGEEQUB)\n#define LAPACK_sgbequ LAPACK_GLOBAL(sgbequ,SGBEQU)\n#define LAPACK_dgbequ LAPACK_GLOBAL(dgbequ,DGBEQU)\n#define LAPACK_cgbequ LAPACK_GLOBAL(cgbequ,CGBEQU)\n#define LAPACK_zgbequ LAPACK_GLOBAL(zgbequ,ZGBEQU)\n#define LAPACK_dgbequb LAPACK_GLOBAL(dgbequb,DGBEQUB)\n#define LAPACK_sgbequb LAPACK_GLOBAL(sgbequb,SGBEQUB)\n#define LAPACK_zgbequb LAPACK_GLOBAL(zgbequb,ZGBEQUB)\n#define LAPACK_cgbequb LAPACK_GLOBAL(cgbequb,CGBEQUB)\n#define LAPACK_spoequ LAPACK_GLOBAL(spoequ,SPOEQU)\n#define LAPACK_dpoequ LAPACK_GLOBAL(dpoequ,DPOEQU)\n#define LAPACK_cpoequ LAPACK_GLOBAL(cpoequ,CPOEQU)\n#define LAPACK_zpoequ LAPACK_GLOBAL(zpoequ,ZPOEQU)\n#define LAPACK_dpoequb LAPACK_GLOBAL(dpoequb,DPOEQUB)\n#define LAPACK_spoequb LAPACK_GLOBAL(spoequb,SPOEQUB)\n#define LAPACK_zpoequb LAPACK_GLOBAL(zpoequb,ZPOEQUB)\n#define LAPACK_cpoequb LAPACK_GLOBAL(cpoequb,CPOEQUB)\n#define LAPACK_sppequ LAPACK_GLOBAL(sppequ,SPPEQU)\n#define LAPACK_dppequ LAPACK_GLOBAL(dppequ,DPPEQU)\n#define LAPACK_cppequ LAPACK_GLOBAL(cppequ,CPPEQU)\n#define LAPACK_zppequ LAPACK_GLOBAL(zppequ,ZPPEQU)\n#define LAPACK_spbequ LAPACK_GLOBAL(spbequ,SPBEQU)\n#define LAPACK_dpbequ LAPACK_GLOBAL(dpbequ,DPBEQU)\n#define LAPACK_cpbequ LAPACK_GLOBAL(cpbequ,CPBEQU)\n#define LAPACK_zpbequ LAPACK_GLOBAL(zpbequ,ZPBEQU)\n#define LAPACK_dsyequb LAPACK_GLOBAL(dsyequb,DSYEQUB)\n#define LAPACK_ssyequb LAPACK_GLOBAL(ssyequb,SSYEQUB)\n#define LAPACK_zsyequb LAPACK_GLOBAL(zsyequb,ZSYEQUB)\n#define LAPACK_csyequb LAPACK_GLOBAL(csyequb,CSYEQUB)\n#define LAPACK_zheequb LAPACK_GLOBAL(zheequb,ZHEEQUB)\n#define LAPACK_cheequb LAPACK_GLOBAL(cheequb,CHEEQUB)\n#define LAPACK_sgesv LAPACK_GLOBAL(sgesv,SGESV)\n#define LAPACK_dgesv LAPACK_GLOBAL(dgesv,DGESV)\n#define LAPACK_cgesv LAPACK_GLOBAL(cgesv,CGESV)\n#define LAPACK_zgesv LAPACK_GLOBAL(zgesv,ZGESV)\n#define LAPACK_dsgesv LAPACK_GLOBAL(dsgesv,DSGESV)\n#define LAPACK_zcgesv LAPACK_GLOBAL(zcgesv,ZCGESV)\n#define LAPACK_sgesvx LAPACK_GLOBAL(sgesvx,SGESVX)\n#define LAPACK_dgesvx LAPACK_GLOBAL(dgesvx,DGESVX)\n#define LAPACK_cgesvx LAPACK_GLOBAL(cgesvx,CGESVX)\n#define LAPACK_zgesvx LAPACK_GLOBAL(zgesvx,ZGESVX)\n#define LAPACK_dgesvxx LAPACK_GLOBAL(dgesvxx,DGESVXX)\n#define LAPACK_sgesvxx LAPACK_GLOBAL(sgesvxx,SGESVXX)\n#define LAPACK_zgesvxx LAPACK_GLOBAL(zgesvxx,ZGESVXX)\n#define LAPACK_cgesvxx LAPACK_GLOBAL(cgesvxx,CGESVXX)\n#define LAPACK_sgbsv LAPACK_GLOBAL(sgbsv,SGBSV)\n#define LAPACK_dgbsv LAPACK_GLOBAL(dgbsv,DGBSV)\n#define LAPACK_cgbsv LAPACK_GLOBAL(cgbsv,CGBSV)\n#define LAPACK_zgbsv LAPACK_GLOBAL(zgbsv,ZGBSV)\n#define LAPACK_sgbsvx LAPACK_GLOBAL(sgbsvx,SGBSVX)\n#define LAPACK_dgbsvx LAPACK_GLOBAL(dgbsvx,DGBSVX)\n#define LAPACK_cgbsvx LAPACK_GLOBAL(cgbsvx,CGBSVX)\n#define LAPACK_zgbsvx LAPACK_GLOBAL(zgbsvx,ZGBSVX)\n#define LAPACK_dgbsvxx LAPACK_GLOBAL(dgbsvxx,DGBSVXX)\n#define LAPACK_sgbsvxx LAPACK_GLOBAL(sgbsvxx,SGBSVXX)\n#define LAPACK_zgbsvxx LAPACK_GLOBAL(zgbsvxx,ZGBSVXX)\n#define LAPACK_cgbsvxx LAPACK_GLOBAL(cgbsvxx,CGBSVXX)\n#define LAPACK_sgtsv LAPACK_GLOBAL(sgtsv,SGTSV)\n#define LAPACK_dgtsv LAPACK_GLOBAL(dgtsv,DGTSV)\n#define LAPACK_cgtsv LAPACK_GLOBAL(cgtsv,CGTSV)\n#define LAPACK_zgtsv LAPACK_GLOBAL(zgtsv,ZGTSV)\n#define LAPACK_sgtsvx LAPACK_GLOBAL(sgtsvx,SGTSVX)\n#define LAPACK_dgtsvx LAPACK_GLOBAL(dgtsvx,DGTSVX)\n#define LAPACK_cgtsvx LAPACK_GLOBAL(cgtsvx,CGTSVX)\n#define LAPACK_zgtsvx LAPACK_GLOBAL(zgtsvx,ZGTSVX)\n#define LAPACK_sposv LAPACK_GLOBAL(sposv,SPOSV)\n#define LAPACK_dposv LAPACK_GLOBAL(dposv,DPOSV)\n#define LAPACK_cposv LAPACK_GLOBAL(cposv,CPOSV)\n#define LAPACK_zposv LAPACK_GLOBAL(zposv,ZPOSV)\n#define LAPACK_dsposv LAPACK_GLOBAL(dsposv,DSPOSV)\n#define LAPACK_zcposv LAPACK_GLOBAL(zcposv,ZCPOSV)\n#define LAPACK_sposvx LAPACK_GLOBAL(sposvx,SPOSVX)\n#define LAPACK_dposvx LAPACK_GLOBAL(dposvx,DPOSVX)\n#define LAPACK_cposvx LAPACK_GLOBAL(cposvx,CPOSVX)\n#define LAPACK_zposvx LAPACK_GLOBAL(zposvx,ZPOSVX)\n#define LAPACK_dposvxx LAPACK_GLOBAL(dposvxx,DPOSVXX)\n#define LAPACK_sposvxx LAPACK_GLOBAL(sposvxx,SPOSVXX)\n#define LAPACK_zposvxx LAPACK_GLOBAL(zposvxx,ZPOSVXX)\n#define LAPACK_cposvxx LAPACK_GLOBAL(cposvxx,CPOSVXX)\n#define LAPACK_sppsv LAPACK_GLOBAL(sppsv,SPPSV)\n#define LAPACK_dppsv LAPACK_GLOBAL(dppsv,DPPSV)\n#define LAPACK_cppsv LAPACK_GLOBAL(cppsv,CPPSV)\n#define LAPACK_zppsv LAPACK_GLOBAL(zppsv,ZPPSV)\n#define LAPACK_sppsvx LAPACK_GLOBAL(sppsvx,SPPSVX)\n#define LAPACK_dppsvx LAPACK_GLOBAL(dppsvx,DPPSVX)\n#define LAPACK_cppsvx LAPACK_GLOBAL(cppsvx,CPPSVX)\n#define LAPACK_zppsvx LAPACK_GLOBAL(zppsvx,ZPPSVX)\n#define LAPACK_spbsv LAPACK_GLOBAL(spbsv,SPBSV)\n#define LAPACK_dpbsv LAPACK_GLOBAL(dpbsv,DPBSV)\n#define LAPACK_cpbsv LAPACK_GLOBAL(cpbsv,CPBSV)\n#define LAPACK_zpbsv LAPACK_GLOBAL(zpbsv,ZPBSV)\n#define LAPACK_spbsvx LAPACK_GLOBAL(spbsvx,SPBSVX)\n#define LAPACK_dpbsvx LAPACK_GLOBAL(dpbsvx,DPBSVX)\n#define LAPACK_cpbsvx LAPACK_GLOBAL(cpbsvx,CPBSVX)\n#define LAPACK_zpbsvx LAPACK_GLOBAL(zpbsvx,ZPBSVX)\n#define LAPACK_sptsv LAPACK_GLOBAL(sptsv,SPTSV)\n#define LAPACK_dptsv LAPACK_GLOBAL(dptsv,DPTSV)\n#define LAPACK_cptsv LAPACK_GLOBAL(cptsv,CPTSV)\n#define LAPACK_zptsv LAPACK_GLOBAL(zptsv,ZPTSV)\n#define LAPACK_sptsvx LAPACK_GLOBAL(sptsvx,SPTSVX)\n#define LAPACK_dptsvx LAPACK_GLOBAL(dptsvx,DPTSVX)\n#define LAPACK_cptsvx LAPACK_GLOBAL(cptsvx,CPTSVX)\n#define LAPACK_zptsvx LAPACK_GLOBAL(zptsvx,ZPTSVX)\n#define LAPACK_ssysv LAPACK_GLOBAL(ssysv,SSYSV)\n#define LAPACK_dsysv LAPACK_GLOBAL(dsysv,DSYSV)\n#define LAPACK_csysv LAPACK_GLOBAL(csysv,CSYSV)\n#define LAPACK_zsysv LAPACK_GLOBAL(zsysv,ZSYSV)\n#define LAPACK_ssysvx LAPACK_GLOBAL(ssysvx,SSYSVX)\n#define LAPACK_dsysvx LAPACK_GLOBAL(dsysvx,DSYSVX)\n#define LAPACK_csysvx LAPACK_GLOBAL(csysvx,CSYSVX)\n#define LAPACK_zsysvx LAPACK_GLOBAL(zsysvx,ZSYSVX)\n#define LAPACK_dsysvxx LAPACK_GLOBAL(dsysvxx,DSYSVXX)\n#define LAPACK_ssysvxx LAPACK_GLOBAL(ssysvxx,SSYSVXX)\n#define LAPACK_zsysvxx LAPACK_GLOBAL(zsysvxx,ZSYSVXX)\n#define LAPACK_csysvxx LAPACK_GLOBAL(csysvxx,CSYSVXX)\n#define LAPACK_chesv LAPACK_GLOBAL(chesv,CHESV)\n#define LAPACK_zhesv LAPACK_GLOBAL(zhesv,ZHESV)\n#define LAPACK_chesvx LAPACK_GLOBAL(chesvx,CHESVX)\n#define LAPACK_zhesvx LAPACK_GLOBAL(zhesvx,ZHESVX)\n#define LAPACK_zhesvxx LAPACK_GLOBAL(zhesvxx,ZHESVXX)\n#define LAPACK_chesvxx LAPACK_GLOBAL(chesvxx,CHESVXX)\n#define LAPACK_sspsv LAPACK_GLOBAL(sspsv,SSPSV)\n#define LAPACK_dspsv LAPACK_GLOBAL(dspsv,DSPSV)\n#define LAPACK_cspsv LAPACK_GLOBAL(cspsv,CSPSV)\n#define LAPACK_zspsv LAPACK_GLOBAL(zspsv,ZSPSV)\n#define LAPACK_sspsvx LAPACK_GLOBAL(sspsvx,SSPSVX)\n#define LAPACK_dspsvx LAPACK_GLOBAL(dspsvx,DSPSVX)\n#define LAPACK_cspsvx LAPACK_GLOBAL(cspsvx,CSPSVX)\n#define LAPACK_zspsvx LAPACK_GLOBAL(zspsvx,ZSPSVX)\n#define LAPACK_chpsv LAPACK_GLOBAL(chpsv,CHPSV)\n#define LAPACK_zhpsv LAPACK_GLOBAL(zhpsv,ZHPSV)\n#define LAPACK_chpsvx LAPACK_GLOBAL(chpsvx,CHPSVX)\n#define LAPACK_zhpsvx LAPACK_GLOBAL(zhpsvx,ZHPSVX)\n#define LAPACK_sgeqrf LAPACK_GLOBAL(sgeqrf,SGEQRF)\n#define LAPACK_dgeqrf LAPACK_GLOBAL(dgeqrf,DGEQRF)\n#define LAPACK_cgeqrf LAPACK_GLOBAL(cgeqrf,CGEQRF)\n#define LAPACK_zgeqrf LAPACK_GLOBAL(zgeqrf,ZGEQRF)\n#define LAPACK_sgeqpf LAPACK_GLOBAL(sgeqpf,SGEQPF)\n#define LAPACK_dgeqpf LAPACK_GLOBAL(dgeqpf,DGEQPF)\n#define LAPACK_cgeqpf LAPACK_GLOBAL(cgeqpf,CGEQPF)\n#define LAPACK_zgeqpf LAPACK_GLOBAL(zgeqpf,ZGEQPF)\n#define LAPACK_sgeqp3 LAPACK_GLOBAL(sgeqp3,SGEQP3)\n#define LAPACK_dgeqp3 LAPACK_GLOBAL(dgeqp3,DGEQP3)\n#define LAPACK_cgeqp3 LAPACK_GLOBAL(cgeqp3,CGEQP3)\n#define LAPACK_zgeqp3 LAPACK_GLOBAL(zgeqp3,ZGEQP3)\n#define LAPACK_sorgqr LAPACK_GLOBAL(sorgqr,SORGQR)\n#define LAPACK_dorgqr LAPACK_GLOBAL(dorgqr,DORGQR)\n#define LAPACK_sormqr LAPACK_GLOBAL(sormqr,SORMQR)\n#define LAPACK_dormqr LAPACK_GLOBAL(dormqr,DORMQR)\n#define LAPACK_cungqr LAPACK_GLOBAL(cungqr,CUNGQR)\n#define LAPACK_zungqr LAPACK_GLOBAL(zungqr,ZUNGQR)\n#define LAPACK_cunmqr LAPACK_GLOBAL(cunmqr,CUNMQR)\n#define LAPACK_zunmqr LAPACK_GLOBAL(zunmqr,ZUNMQR)\n#define LAPACK_sgelqf LAPACK_GLOBAL(sgelqf,SGELQF)\n#define LAPACK_dgelqf LAPACK_GLOBAL(dgelqf,DGELQF)\n#define LAPACK_cgelqf LAPACK_GLOBAL(cgelqf,CGELQF)\n#define LAPACK_zgelqf LAPACK_GLOBAL(zgelqf,ZGELQF)\n#define LAPACK_sorglq LAPACK_GLOBAL(sorglq,SORGLQ)\n#define LAPACK_dorglq LAPACK_GLOBAL(dorglq,DORGLQ)\n#define LAPACK_sormlq LAPACK_GLOBAL(sormlq,SORMLQ)\n#define LAPACK_dormlq LAPACK_GLOBAL(dormlq,DORMLQ)\n#define LAPACK_cunglq LAPACK_GLOBAL(cunglq,CUNGLQ)\n#define LAPACK_zunglq LAPACK_GLOBAL(zunglq,ZUNGLQ)\n#define LAPACK_cunmlq LAPACK_GLOBAL(cunmlq,CUNMLQ)\n#define LAPACK_zunmlq LAPACK_GLOBAL(zunmlq,ZUNMLQ)\n#define LAPACK_sgeqlf LAPACK_GLOBAL(sgeqlf,SGEQLF)\n#define LAPACK_dgeqlf LAPACK_GLOBAL(dgeqlf,DGEQLF)\n#define LAPACK_cgeqlf LAPACK_GLOBAL(cgeqlf,CGEQLF)\n#define LAPACK_zgeqlf LAPACK_GLOBAL(zgeqlf,ZGEQLF)\n#define LAPACK_sorgql LAPACK_GLOBAL(sorgql,SORGQL)\n#define LAPACK_dorgql LAPACK_GLOBAL(dorgql,DORGQL)\n#define LAPACK_cungql LAPACK_GLOBAL(cungql,CUNGQL)\n#define LAPACK_zungql LAPACK_GLOBAL(zungql,ZUNGQL)\n#define LAPACK_sormql LAPACK_GLOBAL(sormql,SORMQL)\n#define LAPACK_dormql LAPACK_GLOBAL(dormql,DORMQL)\n#define LAPACK_cunmql LAPACK_GLOBAL(cunmql,CUNMQL)\n#define LAPACK_zunmql LAPACK_GLOBAL(zunmql,ZUNMQL)\n#define LAPACK_sgerqf LAPACK_GLOBAL(sgerqf,SGERQF)\n#define LAPACK_dgerqf LAPACK_GLOBAL(dgerqf,DGERQF)\n#define LAPACK_cgerqf LAPACK_GLOBAL(cgerqf,CGERQF)\n#define LAPACK_zgerqf LAPACK_GLOBAL(zgerqf,ZGERQF)\n#define LAPACK_sorgrq LAPACK_GLOBAL(sorgrq,SORGRQ)\n#define LAPACK_dorgrq LAPACK_GLOBAL(dorgrq,DORGRQ)\n#define LAPACK_cungrq LAPACK_GLOBAL(cungrq,CUNGRQ)\n#define LAPACK_zungrq LAPACK_GLOBAL(zungrq,ZUNGRQ)\n#define LAPACK_sormrq LAPACK_GLOBAL(sormrq,SORMRQ)\n#define LAPACK_dormrq LAPACK_GLOBAL(dormrq,DORMRQ)\n#define LAPACK_cunmrq LAPACK_GLOBAL(cunmrq,CUNMRQ)\n#define LAPACK_zunmrq LAPACK_GLOBAL(zunmrq,ZUNMRQ)\n#define LAPACK_stzrzf LAPACK_GLOBAL(stzrzf,STZRZF)\n#define LAPACK_dtzrzf LAPACK_GLOBAL(dtzrzf,DTZRZF)\n#define LAPACK_ctzrzf LAPACK_GLOBAL(ctzrzf,CTZRZF)\n#define LAPACK_ztzrzf LAPACK_GLOBAL(ztzrzf,ZTZRZF)\n#define LAPACK_sormrz LAPACK_GLOBAL(sormrz,SORMRZ)\n#define LAPACK_dormrz LAPACK_GLOBAL(dormrz,DORMRZ)\n#define LAPACK_cunmrz LAPACK_GLOBAL(cunmrz,CUNMRZ)\n#define LAPACK_zunmrz LAPACK_GLOBAL(zunmrz,ZUNMRZ)\n#define LAPACK_sggqrf LAPACK_GLOBAL(sggqrf,SGGQRF)\n#define LAPACK_dggqrf LAPACK_GLOBAL(dggqrf,DGGQRF)\n#define LAPACK_cggqrf LAPACK_GLOBAL(cggqrf,CGGQRF)\n#define LAPACK_zggqrf LAPACK_GLOBAL(zggqrf,ZGGQRF)\n#define LAPACK_sggrqf LAPACK_GLOBAL(sggrqf,SGGRQF)\n#define LAPACK_dggrqf LAPACK_GLOBAL(dggrqf,DGGRQF)\n#define LAPACK_cggrqf LAPACK_GLOBAL(cggrqf,CGGRQF)\n#define LAPACK_zggrqf LAPACK_GLOBAL(zggrqf,ZGGRQF)\n#define LAPACK_sgebrd LAPACK_GLOBAL(sgebrd,SGEBRD)\n#define LAPACK_dgebrd LAPACK_GLOBAL(dgebrd,DGEBRD)\n#define LAPACK_cgebrd LAPACK_GLOBAL(cgebrd,CGEBRD)\n#define LAPACK_zgebrd LAPACK_GLOBAL(zgebrd,ZGEBRD)\n#define LAPACK_sgbbrd LAPACK_GLOBAL(sgbbrd,SGBBRD)\n#define LAPACK_dgbbrd LAPACK_GLOBAL(dgbbrd,DGBBRD)\n#define LAPACK_cgbbrd LAPACK_GLOBAL(cgbbrd,CGBBRD)\n#define LAPACK_zgbbrd LAPACK_GLOBAL(zgbbrd,ZGBBRD)\n#define LAPACK_sorgbr LAPACK_GLOBAL(sorgbr,SORGBR)\n#define LAPACK_dorgbr LAPACK_GLOBAL(dorgbr,DORGBR)\n#define LAPACK_sormbr LAPACK_GLOBAL(sormbr,SORMBR)\n#define LAPACK_dormbr LAPACK_GLOBAL(dormbr,DORMBR)\n#define LAPACK_cungbr LAPACK_GLOBAL(cungbr,CUNGBR)\n#define LAPACK_zungbr LAPACK_GLOBAL(zungbr,ZUNGBR)\n#define LAPACK_cunmbr LAPACK_GLOBAL(cunmbr,CUNMBR)\n#define LAPACK_zunmbr LAPACK_GLOBAL(zunmbr,ZUNMBR)\n#define LAPACK_sbdsqr LAPACK_GLOBAL(sbdsqr,SBDSQR)\n#define LAPACK_dbdsqr LAPACK_GLOBAL(dbdsqr,DBDSQR)\n#define LAPACK_cbdsqr LAPACK_GLOBAL(cbdsqr,CBDSQR)\n#define LAPACK_zbdsqr LAPACK_GLOBAL(zbdsqr,ZBDSQR)\n#define LAPACK_sbdsdc LAPACK_GLOBAL(sbdsdc,SBDSDC)\n#define LAPACK_dbdsdc LAPACK_GLOBAL(dbdsdc,DBDSDC)\n#define LAPACK_ssytrd LAPACK_GLOBAL(ssytrd,SSYTRD)\n#define LAPACK_dsytrd LAPACK_GLOBAL(dsytrd,DSYTRD)\n#define LAPACK_sorgtr LAPACK_GLOBAL(sorgtr,SORGTR)\n#define LAPACK_dorgtr LAPACK_GLOBAL(dorgtr,DORGTR)\n#define LAPACK_sormtr LAPACK_GLOBAL(sormtr,SORMTR)\n#define LAPACK_dormtr LAPACK_GLOBAL(dormtr,DORMTR)\n#define LAPACK_chetrd LAPACK_GLOBAL(chetrd,CHETRD)\n#define LAPACK_zhetrd LAPACK_GLOBAL(zhetrd,ZHETRD)\n#define LAPACK_cungtr LAPACK_GLOBAL(cungtr,CUNGTR)\n#define LAPACK_zungtr LAPACK_GLOBAL(zungtr,ZUNGTR)\n#define LAPACK_cunmtr LAPACK_GLOBAL(cunmtr,CUNMTR)\n#define LAPACK_zunmtr LAPACK_GLOBAL(zunmtr,ZUNMTR)\n#define LAPACK_ssptrd LAPACK_GLOBAL(ssptrd,SSPTRD)\n#define LAPACK_dsptrd LAPACK_GLOBAL(dsptrd,DSPTRD)\n#define LAPACK_sopgtr LAPACK_GLOBAL(sopgtr,SOPGTR)\n#define LAPACK_dopgtr LAPACK_GLOBAL(dopgtr,DOPGTR)\n#define LAPACK_sopmtr LAPACK_GLOBAL(sopmtr,SOPMTR)\n#define LAPACK_dopmtr LAPACK_GLOBAL(dopmtr,DOPMTR)\n#define LAPACK_chptrd LAPACK_GLOBAL(chptrd,CHPTRD)\n#define LAPACK_zhptrd LAPACK_GLOBAL(zhptrd,ZHPTRD)\n#define LAPACK_cupgtr LAPACK_GLOBAL(cupgtr,CUPGTR)\n#define LAPACK_zupgtr LAPACK_GLOBAL(zupgtr,ZUPGTR)\n#define LAPACK_cupmtr LAPACK_GLOBAL(cupmtr,CUPMTR)\n#define LAPACK_zupmtr LAPACK_GLOBAL(zupmtr,ZUPMTR)\n#define LAPACK_ssbtrd LAPACK_GLOBAL(ssbtrd,SSBTRD)\n#define LAPACK_dsbtrd LAPACK_GLOBAL(dsbtrd,DSBTRD)\n#define LAPACK_chbtrd LAPACK_GLOBAL(chbtrd,CHBTRD)\n#define LAPACK_zhbtrd LAPACK_GLOBAL(zhbtrd,ZHBTRD)\n#define LAPACK_ssterf LAPACK_GLOBAL(ssterf,SSTERF)\n#define LAPACK_dsterf LAPACK_GLOBAL(dsterf,DSTERF)\n#define LAPACK_ssteqr LAPACK_GLOBAL(ssteqr,SSTEQR)\n#define LAPACK_dsteqr LAPACK_GLOBAL(dsteqr,DSTEQR)\n#define LAPACK_csteqr LAPACK_GLOBAL(csteqr,CSTEQR)\n#define LAPACK_zsteqr LAPACK_GLOBAL(zsteqr,ZSTEQR)\n#define LAPACK_sstemr LAPACK_GLOBAL(sstemr,SSTEMR)\n#define LAPACK_dstemr LAPACK_GLOBAL(dstemr,DSTEMR)\n#define LAPACK_cstemr LAPACK_GLOBAL(cstemr,CSTEMR)\n#define LAPACK_zstemr LAPACK_GLOBAL(zstemr,ZSTEMR)\n#define LAPACK_sstedc LAPACK_GLOBAL(sstedc,SSTEDC)\n#define LAPACK_dstedc LAPACK_GLOBAL(dstedc,DSTEDC)\n#define LAPACK_cstedc LAPACK_GLOBAL(cstedc,CSTEDC)\n#define LAPACK_zstedc LAPACK_GLOBAL(zstedc,ZSTEDC)\n#define LAPACK_sstegr LAPACK_GLOBAL(sstegr,SSTEGR)\n#define LAPACK_dstegr LAPACK_GLOBAL(dstegr,DSTEGR)\n#define LAPACK_cstegr LAPACK_GLOBAL(cstegr,CSTEGR)\n#define LAPACK_zstegr LAPACK_GLOBAL(zstegr,ZSTEGR)\n#define LAPACK_spteqr LAPACK_GLOBAL(spteqr,SPTEQR)\n#define LAPACK_dpteqr LAPACK_GLOBAL(dpteqr,DPTEQR)\n#define LAPACK_cpteqr LAPACK_GLOBAL(cpteqr,CPTEQR)\n#define LAPACK_zpteqr LAPACK_GLOBAL(zpteqr,ZPTEQR)\n#define LAPACK_sstebz LAPACK_GLOBAL(sstebz,SSTEBZ)\n#define LAPACK_dstebz LAPACK_GLOBAL(dstebz,DSTEBZ)\n#define LAPACK_sstein LAPACK_GLOBAL(sstein,SSTEIN)\n#define LAPACK_dstein LAPACK_GLOBAL(dstein,DSTEIN)\n#define LAPACK_cstein LAPACK_GLOBAL(cstein,CSTEIN)\n#define LAPACK_zstein LAPACK_GLOBAL(zstein,ZSTEIN)\n#define LAPACK_sdisna LAPACK_GLOBAL(sdisna,SDISNA)\n#define LAPACK_ddisna LAPACK_GLOBAL(ddisna,DDISNA)\n#define LAPACK_ssygst LAPACK_GLOBAL(ssygst,SSYGST)\n#define LAPACK_dsygst LAPACK_GLOBAL(dsygst,DSYGST)\n#define LAPACK_chegst LAPACK_GLOBAL(chegst,CHEGST)\n#define LAPACK_zhegst LAPACK_GLOBAL(zhegst,ZHEGST)\n#define LAPACK_sspgst LAPACK_GLOBAL(sspgst,SSPGST)\n#define LAPACK_dspgst LAPACK_GLOBAL(dspgst,DSPGST)\n#define LAPACK_chpgst LAPACK_GLOBAL(chpgst,CHPGST)\n#define LAPACK_zhpgst LAPACK_GLOBAL(zhpgst,ZHPGST)\n#define LAPACK_ssbgst LAPACK_GLOBAL(ssbgst,SSBGST)\n#define LAPACK_dsbgst LAPACK_GLOBAL(dsbgst,DSBGST)\n#define LAPACK_chbgst LAPACK_GLOBAL(chbgst,CHBGST)\n#define LAPACK_zhbgst LAPACK_GLOBAL(zhbgst,ZHBGST)\n#define LAPACK_spbstf LAPACK_GLOBAL(spbstf,SPBSTF)\n#define LAPACK_dpbstf LAPACK_GLOBAL(dpbstf,DPBSTF)\n#define LAPACK_cpbstf LAPACK_GLOBAL(cpbstf,CPBSTF)\n#define LAPACK_zpbstf LAPACK_GLOBAL(zpbstf,ZPBSTF)\n#define LAPACK_sgehrd LAPACK_GLOBAL(sgehrd,SGEHRD)\n#define LAPACK_dgehrd LAPACK_GLOBAL(dgehrd,DGEHRD)\n#define LAPACK_cgehrd LAPACK_GLOBAL(cgehrd,CGEHRD)\n#define LAPACK_zgehrd LAPACK_GLOBAL(zgehrd,ZGEHRD)\n#define LAPACK_sorghr LAPACK_GLOBAL(sorghr,SORGHR)\n#define LAPACK_dorghr LAPACK_GLOBAL(dorghr,DORGHR)\n#define LAPACK_sormhr LAPACK_GLOBAL(sormhr,SORMHR)\n#define LAPACK_dormhr LAPACK_GLOBAL(dormhr,DORMHR)\n#define LAPACK_cunghr LAPACK_GLOBAL(cunghr,CUNGHR)\n#define LAPACK_zunghr LAPACK_GLOBAL(zunghr,ZUNGHR)\n#define LAPACK_cunmhr LAPACK_GLOBAL(cunmhr,CUNMHR)\n#define LAPACK_zunmhr LAPACK_GLOBAL(zunmhr,ZUNMHR)\n#define LAPACK_sgebal LAPACK_GLOBAL(sgebal,SGEBAL)\n#define LAPACK_dgebal LAPACK_GLOBAL(dgebal,DGEBAL)\n#define LAPACK_cgebal LAPACK_GLOBAL(cgebal,CGEBAL)\n#define LAPACK_zgebal LAPACK_GLOBAL(zgebal,ZGEBAL)\n#define LAPACK_sgebak LAPACK_GLOBAL(sgebak,SGEBAK)\n#define LAPACK_dgebak LAPACK_GLOBAL(dgebak,DGEBAK)\n#define LAPACK_cgebak LAPACK_GLOBAL(cgebak,CGEBAK)\n#define LAPACK_zgebak LAPACK_GLOBAL(zgebak,ZGEBAK)\n#define LAPACK_shseqr LAPACK_GLOBAL(shseqr,SHSEQR)\n#define LAPACK_dhseqr LAPACK_GLOBAL(dhseqr,DHSEQR)\n#define LAPACK_chseqr LAPACK_GLOBAL(chseqr,CHSEQR)\n#define LAPACK_zhseqr LAPACK_GLOBAL(zhseqr,ZHSEQR)\n#define LAPACK_shsein LAPACK_GLOBAL(shsein,SHSEIN)\n#define LAPACK_dhsein LAPACK_GLOBAL(dhsein,DHSEIN)\n#define LAPACK_chsein LAPACK_GLOBAL(chsein,CHSEIN)\n#define LAPACK_zhsein LAPACK_GLOBAL(zhsein,ZHSEIN)\n#define LAPACK_strevc LAPACK_GLOBAL(strevc,STREVC)\n#define LAPACK_dtrevc LAPACK_GLOBAL(dtrevc,DTREVC)\n#define LAPACK_ctrevc LAPACK_GLOBAL(ctrevc,CTREVC)\n#define LAPACK_ztrevc LAPACK_GLOBAL(ztrevc,ZTREVC)\n#define LAPACK_strsna LAPACK_GLOBAL(strsna,STRSNA)\n#define LAPACK_dtrsna LAPACK_GLOBAL(dtrsna,DTRSNA)\n#define LAPACK_ctrsna LAPACK_GLOBAL(ctrsna,CTRSNA)\n#define LAPACK_ztrsna LAPACK_GLOBAL(ztrsna,ZTRSNA)\n#define LAPACK_strexc LAPACK_GLOBAL(strexc,STREXC)\n#define LAPACK_dtrexc LAPACK_GLOBAL(dtrexc,DTREXC)\n#define LAPACK_ctrexc LAPACK_GLOBAL(ctrexc,CTREXC)\n#define LAPACK_ztrexc LAPACK_GLOBAL(ztrexc,ZTREXC)\n#define LAPACK_strsen LAPACK_GLOBAL(strsen,STRSEN)\n#define LAPACK_dtrsen LAPACK_GLOBAL(dtrsen,DTRSEN)\n#define LAPACK_ctrsen LAPACK_GLOBAL(ctrsen,CTRSEN)\n#define LAPACK_ztrsen LAPACK_GLOBAL(ztrsen,ZTRSEN)\n#define LAPACK_strsyl LAPACK_GLOBAL(strsyl,STRSYL)\n#define LAPACK_dtrsyl LAPACK_GLOBAL(dtrsyl,DTRSYL)\n#define LAPACK_ctrsyl LAPACK_GLOBAL(ctrsyl,CTRSYL)\n#define LAPACK_ztrsyl LAPACK_GLOBAL(ztrsyl,ZTRSYL)\n#define LAPACK_sgghrd LAPACK_GLOBAL(sgghrd,SGGHRD)\n#define LAPACK_dgghrd LAPACK_GLOBAL(dgghrd,DGGHRD)\n#define LAPACK_cgghrd LAPACK_GLOBAL(cgghrd,CGGHRD)\n#define LAPACK_zgghrd LAPACK_GLOBAL(zgghrd,ZGGHRD)\n#define LAPACK_sggbal LAPACK_GLOBAL(sggbal,SGGBAL)\n#define LAPACK_dggbal LAPACK_GLOBAL(dggbal,DGGBAL)\n#define LAPACK_cggbal LAPACK_GLOBAL(cggbal,CGGBAL)\n#define LAPACK_zggbal LAPACK_GLOBAL(zggbal,ZGGBAL)\n#define LAPACK_sggbak LAPACK_GLOBAL(sggbak,SGGBAK)\n#define LAPACK_dggbak LAPACK_GLOBAL(dggbak,DGGBAK)\n#define LAPACK_cggbak LAPACK_GLOBAL(cggbak,CGGBAK)\n#define LAPACK_zggbak LAPACK_GLOBAL(zggbak,ZGGBAK)\n#define LAPACK_shgeqz LAPACK_GLOBAL(shgeqz,SHGEQZ)\n#define LAPACK_dhgeqz LAPACK_GLOBAL(dhgeqz,DHGEQZ)\n#define LAPACK_chgeqz LAPACK_GLOBAL(chgeqz,CHGEQZ)\n#define LAPACK_zhgeqz LAPACK_GLOBAL(zhgeqz,ZHGEQZ)\n#define LAPACK_stgevc LAPACK_GLOBAL(stgevc,STGEVC)\n#define LAPACK_dtgevc LAPACK_GLOBAL(dtgevc,DTGEVC)\n#define LAPACK_ctgevc LAPACK_GLOBAL(ctgevc,CTGEVC)\n#define LAPACK_ztgevc LAPACK_GLOBAL(ztgevc,ZTGEVC)\n#define LAPACK_stgexc LAPACK_GLOBAL(stgexc,STGEXC)\n#define LAPACK_dtgexc LAPACK_GLOBAL(dtgexc,DTGEXC)\n#define LAPACK_ctgexc LAPACK_GLOBAL(ctgexc,CTGEXC)\n#define LAPACK_ztgexc LAPACK_GLOBAL(ztgexc,ZTGEXC)\n#define LAPACK_stgsen LAPACK_GLOBAL(stgsen,STGSEN)\n#define LAPACK_dtgsen LAPACK_GLOBAL(dtgsen,DTGSEN)\n#define LAPACK_ctgsen LAPACK_GLOBAL(ctgsen,CTGSEN)\n#define LAPACK_ztgsen LAPACK_GLOBAL(ztgsen,ZTGSEN)\n#define LAPACK_stgsyl LAPACK_GLOBAL(stgsyl,STGSYL)\n#define LAPACK_dtgsyl LAPACK_GLOBAL(dtgsyl,DTGSYL)\n#define LAPACK_ctgsyl LAPACK_GLOBAL(ctgsyl,CTGSYL)\n#define LAPACK_ztgsyl LAPACK_GLOBAL(ztgsyl,ZTGSYL)\n#define LAPACK_stgsna LAPACK_GLOBAL(stgsna,STGSNA)\n#define LAPACK_dtgsna LAPACK_GLOBAL(dtgsna,DTGSNA)\n#define LAPACK_ctgsna LAPACK_GLOBAL(ctgsna,CTGSNA)\n#define LAPACK_ztgsna LAPACK_GLOBAL(ztgsna,ZTGSNA)\n#define LAPACK_sggsvp LAPACK_GLOBAL(sggsvp,SGGSVP)\n#define LAPACK_dggsvp LAPACK_GLOBAL(dggsvp,DGGSVP)\n#define LAPACK_cggsvp LAPACK_GLOBAL(cggsvp,CGGSVP)\n#define LAPACK_zggsvp LAPACK_GLOBAL(zggsvp,ZGGSVP)\n#define LAPACK_stgsja LAPACK_GLOBAL(stgsja,STGSJA)\n#define LAPACK_dtgsja LAPACK_GLOBAL(dtgsja,DTGSJA)\n#define LAPACK_ctgsja LAPACK_GLOBAL(ctgsja,CTGSJA)\n#define LAPACK_ztgsja LAPACK_GLOBAL(ztgsja,ZTGSJA)\n#define LAPACK_sgels LAPACK_GLOBAL(sgels,SGELS)\n#define LAPACK_dgels LAPACK_GLOBAL(dgels,DGELS)\n#define LAPACK_cgels LAPACK_GLOBAL(cgels,CGELS)\n#define LAPACK_zgels LAPACK_GLOBAL(zgels,ZGELS)\n#define LAPACK_sgelsy LAPACK_GLOBAL(sgelsy,SGELSY)\n#define LAPACK_dgelsy LAPACK_GLOBAL(dgelsy,DGELSY)\n#define LAPACK_cgelsy LAPACK_GLOBAL(cgelsy,CGELSY)\n#define LAPACK_zgelsy LAPACK_GLOBAL(zgelsy,ZGELSY)\n#define LAPACK_sgelss LAPACK_GLOBAL(sgelss,SGELSS)\n#define LAPACK_dgelss LAPACK_GLOBAL(dgelss,DGELSS)\n#define LAPACK_cgelss LAPACK_GLOBAL(cgelss,CGELSS)\n#define LAPACK_zgelss LAPACK_GLOBAL(zgelss,ZGELSS)\n#define LAPACK_sgelsd LAPACK_GLOBAL(sgelsd,SGELSD)\n#define LAPACK_dgelsd LAPACK_GLOBAL(dgelsd,DGELSD)\n#define LAPACK_cgelsd LAPACK_GLOBAL(cgelsd,CGELSD)\n#define LAPACK_zgelsd LAPACK_GLOBAL(zgelsd,ZGELSD)\n#define LAPACK_sgglse LAPACK_GLOBAL(sgglse,SGGLSE)\n#define LAPACK_dgglse LAPACK_GLOBAL(dgglse,DGGLSE)\n#define LAPACK_cgglse LAPACK_GLOBAL(cgglse,CGGLSE)\n#define LAPACK_zgglse LAPACK_GLOBAL(zgglse,ZGGLSE)\n#define LAPACK_sggglm LAPACK_GLOBAL(sggglm,SGGGLM)\n#define LAPACK_dggglm LAPACK_GLOBAL(dggglm,DGGGLM)\n#define LAPACK_cggglm LAPACK_GLOBAL(cggglm,CGGGLM)\n#define LAPACK_zggglm LAPACK_GLOBAL(zggglm,ZGGGLM)\n#define LAPACK_ssyev LAPACK_GLOBAL(ssyev,SSYEV)\n#define LAPACK_dsyev LAPACK_GLOBAL(dsyev,DSYEV)\n#define LAPACK_cheev LAPACK_GLOBAL(cheev,CHEEV)\n#define LAPACK_zheev LAPACK_GLOBAL(zheev,ZHEEV)\n#define LAPACK_ssyevd LAPACK_GLOBAL(ssyevd,SSYEVD)\n#define LAPACK_dsyevd LAPACK_GLOBAL(dsyevd,DSYEVD)\n#define LAPACK_cheevd LAPACK_GLOBAL(cheevd,CHEEVD)\n#define LAPACK_zheevd LAPACK_GLOBAL(zheevd,ZHEEVD)\n#define LAPACK_ssyevx LAPACK_GLOBAL(ssyevx,SSYEVX)\n#define LAPACK_dsyevx LAPACK_GLOBAL(dsyevx,DSYEVX)\n#define LAPACK_cheevx LAPACK_GLOBAL(cheevx,CHEEVX)\n#define LAPACK_zheevx LAPACK_GLOBAL(zheevx,ZHEEVX)\n#define LAPACK_ssyevr LAPACK_GLOBAL(ssyevr,SSYEVR)\n#define LAPACK_dsyevr LAPACK_GLOBAL(dsyevr,DSYEVR)\n#define LAPACK_cheevr LAPACK_GLOBAL(cheevr,CHEEVR)\n#define LAPACK_zheevr LAPACK_GLOBAL(zheevr,ZHEEVR)\n#define LAPACK_sspev LAPACK_GLOBAL(sspev,SSPEV)\n#define LAPACK_dspev LAPACK_GLOBAL(dspev,DSPEV)\n#define LAPACK_chpev LAPACK_GLOBAL(chpev,CHPEV)\n#define LAPACK_zhpev LAPACK_GLOBAL(zhpev,ZHPEV)\n#define LAPACK_sspevd LAPACK_GLOBAL(sspevd,SSPEVD)\n#define LAPACK_dspevd LAPACK_GLOBAL(dspevd,DSPEVD)\n#define LAPACK_chpevd LAPACK_GLOBAL(chpevd,CHPEVD)\n#define LAPACK_zhpevd LAPACK_GLOBAL(zhpevd,ZHPEVD)\n#define LAPACK_sspevx LAPACK_GLOBAL(sspevx,SSPEVX)\n#define LAPACK_dspevx LAPACK_GLOBAL(dspevx,DSPEVX)\n#define LAPACK_chpevx LAPACK_GLOBAL(chpevx,CHPEVX)\n#define LAPACK_zhpevx LAPACK_GLOBAL(zhpevx,ZHPEVX)\n#define LAPACK_ssbev LAPACK_GLOBAL(ssbev,SSBEV)\n#define LAPACK_dsbev LAPACK_GLOBAL(dsbev,DSBEV)\n#define LAPACK_chbev LAPACK_GLOBAL(chbev,CHBEV)\n#define LAPACK_zhbev LAPACK_GLOBAL(zhbev,ZHBEV)\n#define LAPACK_ssbevd LAPACK_GLOBAL(ssbevd,SSBEVD)\n#define LAPACK_dsbevd LAPACK_GLOBAL(dsbevd,DSBEVD)\n#define LAPACK_chbevd LAPACK_GLOBAL(chbevd,CHBEVD)\n#define LAPACK_zhbevd LAPACK_GLOBAL(zhbevd,ZHBEVD)\n#define LAPACK_ssbevx LAPACK_GLOBAL(ssbevx,SSBEVX)\n#define LAPACK_dsbevx LAPACK_GLOBAL(dsbevx,DSBEVX)\n#define LAPACK_chbevx LAPACK_GLOBAL(chbevx,CHBEVX)\n#define LAPACK_zhbevx LAPACK_GLOBAL(zhbevx,ZHBEVX)\n#define LAPACK_sstev LAPACK_GLOBAL(sstev,SSTEV)\n#define LAPACK_dstev LAPACK_GLOBAL(dstev,DSTEV)\n#define LAPACK_sstevd LAPACK_GLOBAL(sstevd,SSTEVD)\n#define LAPACK_dstevd LAPACK_GLOBAL(dstevd,DSTEVD)\n#define LAPACK_sstevx LAPACK_GLOBAL(sstevx,SSTEVX)\n#define LAPACK_dstevx LAPACK_GLOBAL(dstevx,DSTEVX)\n#define LAPACK_sstevr LAPACK_GLOBAL(sstevr,SSTEVR)\n#define LAPACK_dstevr LAPACK_GLOBAL(dstevr,DSTEVR)\n#define LAPACK_sgees LAPACK_GLOBAL(sgees,SGEES)\n#define LAPACK_dgees LAPACK_GLOBAL(dgees,DGEES)\n#define LAPACK_cgees LAPACK_GLOBAL(cgees,CGEES)\n#define LAPACK_zgees LAPACK_GLOBAL(zgees,ZGEES)\n#define LAPACK_sgeesx LAPACK_GLOBAL(sgeesx,SGEESX)\n#define LAPACK_dgeesx LAPACK_GLOBAL(dgeesx,DGEESX)\n#define LAPACK_cgeesx LAPACK_GLOBAL(cgeesx,CGEESX)\n#define LAPACK_zgeesx LAPACK_GLOBAL(zgeesx,ZGEESX)\n#define LAPACK_sgeev LAPACK_GLOBAL(sgeev,SGEEV)\n#define LAPACK_dgeev LAPACK_GLOBAL(dgeev,DGEEV)\n#define LAPACK_cgeev LAPACK_GLOBAL(cgeev,CGEEV)\n#define LAPACK_zgeev LAPACK_GLOBAL(zgeev,ZGEEV)\n#define LAPACK_sgeevx LAPACK_GLOBAL(sgeevx,SGEEVX)\n#define LAPACK_dgeevx LAPACK_GLOBAL(dgeevx,DGEEVX)\n#define LAPACK_cgeevx LAPACK_GLOBAL(cgeevx,CGEEVX)\n#define LAPACK_zgeevx LAPACK_GLOBAL(zgeevx,ZGEEVX)\n#define LAPACK_sgesvd LAPACK_GLOBAL(sgesvd,SGESVD)\n#define LAPACK_dgesvd LAPACK_GLOBAL(dgesvd,DGESVD)\n#define LAPACK_cgesvd LAPACK_GLOBAL(cgesvd,CGESVD)\n#define LAPACK_zgesvd LAPACK_GLOBAL(zgesvd,ZGESVD)\n#define LAPACK_sgesdd LAPACK_GLOBAL(sgesdd,SGESDD)\n#define LAPACK_dgesdd LAPACK_GLOBAL(dgesdd,DGESDD)\n#define LAPACK_cgesdd LAPACK_GLOBAL(cgesdd,CGESDD)\n#define LAPACK_zgesdd LAPACK_GLOBAL(zgesdd,ZGESDD)\n#define LAPACK_dgejsv LAPACK_GLOBAL(dgejsv,DGEJSV)\n#define LAPACK_sgejsv LAPACK_GLOBAL(sgejsv,SGEJSV)\n#define LAPACK_dgesvj LAPACK_GLOBAL(dgesvj,DGESVJ)\n#define LAPACK_sgesvj LAPACK_GLOBAL(sgesvj,SGESVJ)\n#define LAPACK_sggsvd LAPACK_GLOBAL(sggsvd,SGGSVD)\n#define LAPACK_dggsvd LAPACK_GLOBAL(dggsvd,DGGSVD)\n#define LAPACK_cggsvd LAPACK_GLOBAL(cggsvd,CGGSVD)\n#define LAPACK_zggsvd LAPACK_GLOBAL(zggsvd,ZGGSVD)\n#define LAPACK_ssygv LAPACK_GLOBAL(ssygv,SSYGV)\n#define LAPACK_dsygv LAPACK_GLOBAL(dsygv,DSYGV)\n#define LAPACK_chegv LAPACK_GLOBAL(chegv,CHEGV)\n#define LAPACK_zhegv LAPACK_GLOBAL(zhegv,ZHEGV)\n#define LAPACK_ssygvd LAPACK_GLOBAL(ssygvd,SSYGVD)\n#define LAPACK_dsygvd LAPACK_GLOBAL(dsygvd,DSYGVD)\n#define LAPACK_chegvd LAPACK_GLOBAL(chegvd,CHEGVD)\n#define LAPACK_zhegvd LAPACK_GLOBAL(zhegvd,ZHEGVD)\n#define LAPACK_ssygvx LAPACK_GLOBAL(ssygvx,SSYGVX)\n#define LAPACK_dsygvx LAPACK_GLOBAL(dsygvx,DSYGVX)\n#define LAPACK_chegvx LAPACK_GLOBAL(chegvx,CHEGVX)\n#define LAPACK_zhegvx LAPACK_GLOBAL(zhegvx,ZHEGVX)\n#define LAPACK_sspgv LAPACK_GLOBAL(sspgv,SSPGV)\n#define LAPACK_dspgv LAPACK_GLOBAL(dspgv,DSPGV)\n#define LAPACK_chpgv LAPACK_GLOBAL(chpgv,CHPGV)\n#define LAPACK_zhpgv LAPACK_GLOBAL(zhpgv,ZHPGV)\n#define LAPACK_sspgvd LAPACK_GLOBAL(sspgvd,SSPGVD)\n#define LAPACK_dspgvd LAPACK_GLOBAL(dspgvd,DSPGVD)\n#define LAPACK_chpgvd LAPACK_GLOBAL(chpgvd,CHPGVD)\n#define LAPACK_zhpgvd LAPACK_GLOBAL(zhpgvd,ZHPGVD)\n#define LAPACK_sspgvx LAPACK_GLOBAL(sspgvx,SSPGVX)\n#define LAPACK_dspgvx LAPACK_GLOBAL(dspgvx,DSPGVX)\n#define LAPACK_chpgvx LAPACK_GLOBAL(chpgvx,CHPGVX)\n#define LAPACK_zhpgvx LAPACK_GLOBAL(zhpgvx,ZHPGVX)\n#define LAPACK_ssbgv LAPACK_GLOBAL(ssbgv,SSBGV)\n#define LAPACK_dsbgv LAPACK_GLOBAL(dsbgv,DSBGV)\n#define LAPACK_chbgv LAPACK_GLOBAL(chbgv,CHBGV)\n#define LAPACK_zhbgv LAPACK_GLOBAL(zhbgv,ZHBGV)\n#define LAPACK_ssbgvd LAPACK_GLOBAL(ssbgvd,SSBGVD)\n#define LAPACK_dsbgvd LAPACK_GLOBAL(dsbgvd,DSBGVD)\n#define LAPACK_chbgvd LAPACK_GLOBAL(chbgvd,CHBGVD)\n#define LAPACK_zhbgvd LAPACK_GLOBAL(zhbgvd,ZHBGVD)\n#define LAPACK_ssbgvx LAPACK_GLOBAL(ssbgvx,SSBGVX)\n#define LAPACK_dsbgvx LAPACK_GLOBAL(dsbgvx,DSBGVX)\n#define LAPACK_chbgvx LAPACK_GLOBAL(chbgvx,CHBGVX)\n#define LAPACK_zhbgvx LAPACK_GLOBAL(zhbgvx,ZHBGVX)\n#define LAPACK_sgges LAPACK_GLOBAL(sgges,SGGES)\n#define LAPACK_dgges LAPACK_GLOBAL(dgges,DGGES)\n#define LAPACK_cgges LAPACK_GLOBAL(cgges,CGGES)\n#define LAPACK_zgges LAPACK_GLOBAL(zgges,ZGGES)\n#define LAPACK_sggesx LAPACK_GLOBAL(sggesx,SGGESX)\n#define LAPACK_dggesx LAPACK_GLOBAL(dggesx,DGGESX)\n#define LAPACK_cggesx LAPACK_GLOBAL(cggesx,CGGESX)\n#define LAPACK_zggesx LAPACK_GLOBAL(zggesx,ZGGESX)\n#define LAPACK_sggev LAPACK_GLOBAL(sggev,SGGEV)\n#define LAPACK_dggev LAPACK_GLOBAL(dggev,DGGEV)\n#define LAPACK_cggev LAPACK_GLOBAL(cggev,CGGEV)\n#define LAPACK_zggev LAPACK_GLOBAL(zggev,ZGGEV)\n#define LAPACK_sggevx LAPACK_GLOBAL(sggevx,SGGEVX)\n#define LAPACK_dggevx LAPACK_GLOBAL(dggevx,DGGEVX)\n#define LAPACK_cggevx LAPACK_GLOBAL(cggevx,CGGEVX)\n#define LAPACK_zggevx LAPACK_GLOBAL(zggevx,ZGGEVX)\n#define LAPACK_dsfrk LAPACK_GLOBAL(dsfrk,DSFRK)\n#define LAPACK_ssfrk LAPACK_GLOBAL(ssfrk,SSFRK)\n#define LAPACK_zhfrk LAPACK_GLOBAL(zhfrk,ZHFRK)\n#define LAPACK_chfrk LAPACK_GLOBAL(chfrk,CHFRK)\n#define LAPACK_dtfsm LAPACK_GLOBAL(dtfsm,DTFSM)\n#define LAPACK_stfsm LAPACK_GLOBAL(stfsm,STFSM)\n#define LAPACK_ztfsm LAPACK_GLOBAL(ztfsm,ZTFSM)\n#define LAPACK_ctfsm LAPACK_GLOBAL(ctfsm,CTFSM)\n#define LAPACK_dtfttp LAPACK_GLOBAL(dtfttp,DTFTTP)\n#define LAPACK_stfttp LAPACK_GLOBAL(stfttp,STFTTP)\n#define LAPACK_ztfttp LAPACK_GLOBAL(ztfttp,ZTFTTP)\n#define LAPACK_ctfttp LAPACK_GLOBAL(ctfttp,CTFTTP)\n#define LAPACK_dtfttr LAPACK_GLOBAL(dtfttr,DTFTTR)\n#define LAPACK_stfttr LAPACK_GLOBAL(stfttr,STFTTR)\n#define LAPACK_ztfttr LAPACK_GLOBAL(ztfttr,ZTFTTR)\n#define LAPACK_ctfttr LAPACK_GLOBAL(ctfttr,CTFTTR)\n#define LAPACK_dtpttf LAPACK_GLOBAL(dtpttf,DTPTTF)\n#define LAPACK_stpttf LAPACK_GLOBAL(stpttf,STPTTF)\n#define LAPACK_ztpttf LAPACK_GLOBAL(ztpttf,ZTPTTF)\n#define LAPACK_ctpttf LAPACK_GLOBAL(ctpttf,CTPTTF)\n#define LAPACK_dtpttr LAPACK_GLOBAL(dtpttr,DTPTTR)\n#define LAPACK_stpttr LAPACK_GLOBAL(stpttr,STPTTR)\n#define LAPACK_ztpttr LAPACK_GLOBAL(ztpttr,ZTPTTR)\n#define LAPACK_ctpttr LAPACK_GLOBAL(ctpttr,CTPTTR)\n#define LAPACK_dtrttf LAPACK_GLOBAL(dtrttf,DTRTTF)\n#define LAPACK_strttf LAPACK_GLOBAL(strttf,STRTTF)\n#define LAPACK_ztrttf LAPACK_GLOBAL(ztrttf,ZTRTTF)\n#define LAPACK_ctrttf LAPACK_GLOBAL(ctrttf,CTRTTF)\n#define LAPACK_dtrttp LAPACK_GLOBAL(dtrttp,DTRTTP)\n#define LAPACK_strttp LAPACK_GLOBAL(strttp,STRTTP)\n#define LAPACK_ztrttp LAPACK_GLOBAL(ztrttp,ZTRTTP)\n#define LAPACK_ctrttp LAPACK_GLOBAL(ctrttp,CTRTTP)\n#define LAPACK_sgeqrfp LAPACK_GLOBAL(sgeqrfp,SGEQRFP)\n#define LAPACK_dgeqrfp LAPACK_GLOBAL(dgeqrfp,DGEQRFP)\n#define LAPACK_cgeqrfp LAPACK_GLOBAL(cgeqrfp,CGEQRFP)\n#define LAPACK_zgeqrfp LAPACK_GLOBAL(zgeqrfp,ZGEQRFP)\n#define LAPACK_clacgv LAPACK_GLOBAL(clacgv,CLACGV)\n#define LAPACK_zlacgv LAPACK_GLOBAL(zlacgv,ZLACGV)\n#define LAPACK_slarnv LAPACK_GLOBAL(slarnv,SLARNV)\n#define LAPACK_dlarnv LAPACK_GLOBAL(dlarnv,DLARNV)\n#define LAPACK_clarnv LAPACK_GLOBAL(clarnv,CLARNV)\n#define LAPACK_zlarnv LAPACK_GLOBAL(zlarnv,ZLARNV)\n#define LAPACK_sgeqr2 LAPACK_GLOBAL(sgeqr2,SGEQR2)\n#define LAPACK_dgeqr2 LAPACK_GLOBAL(dgeqr2,DGEQR2)\n#define LAPACK_cgeqr2 LAPACK_GLOBAL(cgeqr2,CGEQR2)\n#define LAPACK_zgeqr2 LAPACK_GLOBAL(zgeqr2,ZGEQR2)\n#define LAPACK_slacpy LAPACK_GLOBAL(slacpy,SLACPY)\n#define LAPACK_dlacpy LAPACK_GLOBAL(dlacpy,DLACPY)\n#define LAPACK_clacpy LAPACK_GLOBAL(clacpy,CLACPY)\n#define LAPACK_zlacpy LAPACK_GLOBAL(zlacpy,ZLACPY)\n#define LAPACK_sgetf2 LAPACK_GLOBAL(sgetf2,SGETF2)\n#define LAPACK_dgetf2 LAPACK_GLOBAL(dgetf2,DGETF2)\n#define LAPACK_cgetf2 LAPACK_GLOBAL(cgetf2,CGETF2)\n#define LAPACK_zgetf2 LAPACK_GLOBAL(zgetf2,ZGETF2)\n#define LAPACK_slaswp LAPACK_GLOBAL(slaswp,SLASWP)\n#define LAPACK_dlaswp LAPACK_GLOBAL(dlaswp,DLASWP)\n#define LAPACK_claswp LAPACK_GLOBAL(claswp,CLASWP)\n#define LAPACK_zlaswp LAPACK_GLOBAL(zlaswp,ZLASWP)\n#define LAPACK_slange LAPACK_GLOBAL(slange,SLANGE)\n#define LAPACK_dlange LAPACK_GLOBAL(dlange,DLANGE)\n#define LAPACK_clange LAPACK_GLOBAL(clange,CLANGE)\n#define LAPACK_zlange LAPACK_GLOBAL(zlange,ZLANGE)\n#define LAPACK_clanhe LAPACK_GLOBAL(clanhe,CLANHE)\n#define LAPACK_zlanhe LAPACK_GLOBAL(zlanhe,ZLANHE)\n#define LAPACK_slansy LAPACK_GLOBAL(slansy,SLANSY)\n#define LAPACK_dlansy LAPACK_GLOBAL(dlansy,DLANSY)\n#define LAPACK_clansy LAPACK_GLOBAL(clansy,CLANSY)\n#define LAPACK_zlansy LAPACK_GLOBAL(zlansy,ZLANSY)\n#define LAPACK_slantr LAPACK_GLOBAL(slantr,SLANTR)\n#define LAPACK_dlantr LAPACK_GLOBAL(dlantr,DLANTR)\n#define LAPACK_clantr LAPACK_GLOBAL(clantr,CLANTR)\n#define LAPACK_zlantr LAPACK_GLOBAL(zlantr,ZLANTR)\n#define LAPACK_slamch LAPACK_GLOBAL(slamch,SLAMCH)\n#define LAPACK_dlamch LAPACK_GLOBAL(dlamch,DLAMCH)\n#define LAPACK_sgelq2 LAPACK_GLOBAL(sgelq2,SGELQ2)\n#define LAPACK_dgelq2 LAPACK_GLOBAL(dgelq2,DGELQ2)\n#define LAPACK_cgelq2 LAPACK_GLOBAL(cgelq2,CGELQ2)\n#define LAPACK_zgelq2 LAPACK_GLOBAL(zgelq2,ZGELQ2)\n#define LAPACK_slarfb LAPACK_GLOBAL(slarfb,SLARFB)\n#define LAPACK_dlarfb LAPACK_GLOBAL(dlarfb,DLARFB)\n#define LAPACK_clarfb LAPACK_GLOBAL(clarfb,CLARFB)\n#define LAPACK_zlarfb LAPACK_GLOBAL(zlarfb,ZLARFB)\n#define LAPACK_slarfg LAPACK_GLOBAL(slarfg,SLARFG)\n#define LAPACK_dlarfg LAPACK_GLOBAL(dlarfg,DLARFG)\n#define LAPACK_clarfg LAPACK_GLOBAL(clarfg,CLARFG)\n#define LAPACK_zlarfg LAPACK_GLOBAL(zlarfg,ZLARFG)\n#define LAPACK_slarft LAPACK_GLOBAL(slarft,SLARFT)\n#define LAPACK_dlarft LAPACK_GLOBAL(dlarft,DLARFT)\n#define LAPACK_clarft LAPACK_GLOBAL(clarft,CLARFT)\n#define LAPACK_zlarft LAPACK_GLOBAL(zlarft,ZLARFT)\n#define LAPACK_slarfx LAPACK_GLOBAL(slarfx,SLARFX)\n#define LAPACK_dlarfx LAPACK_GLOBAL(dlarfx,DLARFX)\n#define LAPACK_clarfx LAPACK_GLOBAL(clarfx,CLARFX)\n#define LAPACK_zlarfx LAPACK_GLOBAL(zlarfx,ZLARFX)\n#define LAPACK_slatms LAPACK_GLOBAL(slatms,SLATMS)\n#define LAPACK_dlatms LAPACK_GLOBAL(dlatms,DLATMS)\n#define LAPACK_clatms LAPACK_GLOBAL(clatms,CLATMS)\n#define LAPACK_zlatms LAPACK_GLOBAL(zlatms,ZLATMS)\n#define LAPACK_slag2d LAPACK_GLOBAL(slag2d,SLAG2D)\n#define LAPACK_dlag2s LAPACK_GLOBAL(dlag2s,DLAG2S)\n#define LAPACK_clag2z LAPACK_GLOBAL(clag2z,CLAG2Z)\n#define LAPACK_zlag2c LAPACK_GLOBAL(zlag2c,ZLAG2C)\n#define LAPACK_slauum LAPACK_GLOBAL(slauum,SLAUUM)\n#define LAPACK_dlauum LAPACK_GLOBAL(dlauum,DLAUUM)\n#define LAPACK_clauum LAPACK_GLOBAL(clauum,CLAUUM)\n#define LAPACK_zlauum LAPACK_GLOBAL(zlauum,ZLAUUM)\n#define LAPACK_slagge LAPACK_GLOBAL(slagge,SLAGGE)\n#define LAPACK_dlagge LAPACK_GLOBAL(dlagge,DLAGGE)\n#define LAPACK_clagge LAPACK_GLOBAL(clagge,CLAGGE)\n#define LAPACK_zlagge LAPACK_GLOBAL(zlagge,ZLAGGE)\n#define LAPACK_slaset LAPACK_GLOBAL(slaset,SLASET)\n#define LAPACK_dlaset LAPACK_GLOBAL(dlaset,DLASET)\n#define LAPACK_claset LAPACK_GLOBAL(claset,CLASET)\n#define LAPACK_zlaset LAPACK_GLOBAL(zlaset,ZLASET)\n#define LAPACK_slasrt LAPACK_GLOBAL(slasrt,SLASRT)\n#define LAPACK_dlasrt LAPACK_GLOBAL(dlasrt,DLASRT)\n#define LAPACK_slagsy LAPACK_GLOBAL(slagsy,SLAGSY)\n#define LAPACK_dlagsy LAPACK_GLOBAL(dlagsy,DLAGSY)\n#define LAPACK_clagsy LAPACK_GLOBAL(clagsy,CLAGSY)\n#define LAPACK_zlagsy LAPACK_GLOBAL(zlagsy,ZLAGSY)\n#define LAPACK_claghe LAPACK_GLOBAL(claghe,CLAGHE)\n#define LAPACK_zlaghe LAPACK_GLOBAL(zlaghe,ZLAGHE)\n#define LAPACK_slapmr LAPACK_GLOBAL(slapmr,SLAPMR)\n#define LAPACK_dlapmr LAPACK_GLOBAL(dlapmr,DLAPMR)\n#define LAPACK_clapmr LAPACK_GLOBAL(clapmr,CLAPMR)\n#define LAPACK_zlapmr LAPACK_GLOBAL(zlapmr,ZLAPMR)\n#define LAPACK_slapy2 LAPACK_GLOBAL(slapy2,SLAPY2)\n#define LAPACK_dlapy2 LAPACK_GLOBAL(dlapy2,DLAPY2)\n#define LAPACK_slapy3 LAPACK_GLOBAL(slapy3,SLAPY3)\n#define LAPACK_dlapy3 LAPACK_GLOBAL(dlapy3,DLAPY3)\n#define LAPACK_slartgp LAPACK_GLOBAL(slartgp,SLARTGP)\n#define LAPACK_dlartgp LAPACK_GLOBAL(dlartgp,DLARTGP)\n#define LAPACK_slartgs LAPACK_GLOBAL(slartgs,SLARTGS)\n#define LAPACK_dlartgs LAPACK_GLOBAL(dlartgs,DLARTGS)\n// LAPACK 3.3.0\n#define LAPACK_cbbcsd LAPACK_GLOBAL(cbbcsd,CBBCSD)\n#define LAPACK_cheswapr LAPACK_GLOBAL(cheswapr,CHESWAPR)\n#define LAPACK_chetri2 LAPACK_GLOBAL(chetri2,CHETRI2)\n#define LAPACK_chetri2x LAPACK_GLOBAL(chetri2x,CHETRI2X)\n#define LAPACK_chetrs2 LAPACK_GLOBAL(chetrs2,CHETRS2)\n#define LAPACK_csyconv LAPACK_GLOBAL(csyconv,CSYCONV)\n#define LAPACK_csyswapr LAPACK_GLOBAL(csyswapr,CSYSWAPR)\n#define LAPACK_csytri2 LAPACK_GLOBAL(csytri2,CSYTRI2)\n#define LAPACK_csytri2x LAPACK_GLOBAL(csytri2x,CSYTRI2X)\n#define LAPACK_csytrs2 LAPACK_GLOBAL(csytrs2,CSYTRS2)\n#define LAPACK_cunbdb LAPACK_GLOBAL(cunbdb,CUNBDB)\n#define LAPACK_cuncsd LAPACK_GLOBAL(cuncsd,CUNCSD)\n#define LAPACK_dbbcsd LAPACK_GLOBAL(dbbcsd,DBBCSD)\n#define LAPACK_dorbdb LAPACK_GLOBAL(dorbdb,DORBDB)\n#define LAPACK_dorcsd LAPACK_GLOBAL(dorcsd,DORCSD)\n#define LAPACK_dsyconv LAPACK_GLOBAL(dsyconv,DSYCONV)\n#define LAPACK_dsyswapr LAPACK_GLOBAL(dsyswapr,DSYSWAPR)\n#define LAPACK_dsytri2 LAPACK_GLOBAL(dsytri2,DSYTRI2)\n#define LAPACK_dsytri2x LAPACK_GLOBAL(dsytri2x,DSYTRI2X)\n#define LAPACK_dsytrs2 LAPACK_GLOBAL(dsytrs2,DSYTRS2)\n#define LAPACK_sbbcsd LAPACK_GLOBAL(sbbcsd,SBBCSD)\n#define LAPACK_sorbdb LAPACK_GLOBAL(sorbdb,SORBDB)\n#define LAPACK_sorcsd LAPACK_GLOBAL(sorcsd,SORCSD)\n#define LAPACK_ssyconv LAPACK_GLOBAL(ssyconv,SSYCONV)\n#define LAPACK_ssyswapr LAPACK_GLOBAL(ssyswapr,SSYSWAPR)\n#define LAPACK_ssytri2 LAPACK_GLOBAL(ssytri2,SSYTRI2)\n#define LAPACK_ssytri2x LAPACK_GLOBAL(ssytri2x,SSYTRI2X)\n#define LAPACK_ssytrs2 LAPACK_GLOBAL(ssytrs2,SSYTRS2)\n#define LAPACK_zbbcsd LAPACK_GLOBAL(zbbcsd,ZBBCSD)\n#define LAPACK_zheswapr LAPACK_GLOBAL(zheswapr,ZHESWAPR)\n#define LAPACK_zhetri2 LAPACK_GLOBAL(zhetri2,ZHETRI2)\n#define LAPACK_zhetri2x LAPACK_GLOBAL(zhetri2x,ZHETRI2X)\n#define LAPACK_zhetrs2 LAPACK_GLOBAL(zhetrs2,ZHETRS2)\n#define LAPACK_zsyconv LAPACK_GLOBAL(zsyconv,ZSYCONV)\n#define LAPACK_zsyswapr LAPACK_GLOBAL(zsyswapr,ZSYSWAPR)\n#define LAPACK_zsytri2 LAPACK_GLOBAL(zsytri2,ZSYTRI2)\n#define LAPACK_zsytri2x LAPACK_GLOBAL(zsytri2x,ZSYTRI2X)\n#define LAPACK_zsytrs2 LAPACK_GLOBAL(zsytrs2,ZSYTRS2)\n#define LAPACK_zunbdb LAPACK_GLOBAL(zunbdb,ZUNBDB)\n#define LAPACK_zuncsd LAPACK_GLOBAL(zuncsd,ZUNCSD)\n// LAPACK 3.4.0\n#define LAPACK_sgemqrt LAPACK_GLOBAL(sgemqrt,SGEMQRT)\n#define LAPACK_dgemqrt LAPACK_GLOBAL(dgemqrt,DGEMQRT)\n#define LAPACK_cgemqrt LAPACK_GLOBAL(cgemqrt,CGEMQRT)\n#define LAPACK_zgemqrt LAPACK_GLOBAL(zgemqrt,ZGEMQRT)\n#define LAPACK_sgeqrt LAPACK_GLOBAL(sgeqrt,SGEQRT)\n#define LAPACK_dgeqrt LAPACK_GLOBAL(dgeqrt,DGEQRT)\n#define LAPACK_cgeqrt LAPACK_GLOBAL(cgeqrt,CGEQRT)\n#define LAPACK_zgeqrt LAPACK_GLOBAL(zgeqrt,ZGEQRT)\n#define LAPACK_sgeqrt2 LAPACK_GLOBAL(sgeqrt2,SGEQRT2)\n#define LAPACK_dgeqrt2 LAPACK_GLOBAL(dgeqrt2,DGEQRT2)\n#define LAPACK_cgeqrt2 LAPACK_GLOBAL(cgeqrt2,CGEQRT2)\n#define LAPACK_zgeqrt2 LAPACK_GLOBAL(zgeqrt2,ZGEQRT2)\n#define LAPACK_sgeqrt3 LAPACK_GLOBAL(sgeqrt3,SGEQRT3)\n#define LAPACK_dgeqrt3 LAPACK_GLOBAL(dgeqrt3,DGEQRT3)\n#define LAPACK_cgeqrt3 LAPACK_GLOBAL(cgeqrt3,CGEQRT3)\n#define LAPACK_zgeqrt3 LAPACK_GLOBAL(zgeqrt3,ZGEQRT3)\n#define LAPACK_stpmqrt LAPACK_GLOBAL(stpmqrt,STPMQRT)\n#define LAPACK_dtpmqrt LAPACK_GLOBAL(dtpmqrt,DTPMQRT)\n#define LAPACK_ctpmqrt LAPACK_GLOBAL(ctpmqrt,CTPMQRT)\n#define LAPACK_ztpmqrt LAPACK_GLOBAL(ztpmqrt,ZTPMQRT)\n#define LAPACK_dtpqrt LAPACK_GLOBAL(dtpqrt,DTPQRT)\n#define LAPACK_ctpqrt LAPACK_GLOBAL(ctpqrt,CTPQRT)\n#define LAPACK_ztpqrt LAPACK_GLOBAL(ztpqrt,ZTPQRT)\n#define LAPACK_stpqrt2 LAPACK_GLOBAL(stpqrt2,STPQRT2)\n#define LAPACK_dtpqrt2 LAPACK_GLOBAL(dtpqrt2,DTPQRT2)\n#define LAPACK_ctpqrt2 LAPACK_GLOBAL(ctpqrt2,CTPQRT2)\n#define LAPACK_ztpqrt2 LAPACK_GLOBAL(ztpqrt2,ZTPQRT2)\n#define LAPACK_stprfb LAPACK_GLOBAL(stprfb,STPRFB)\n#define LAPACK_dtprfb LAPACK_GLOBAL(dtprfb,DTPRFB)\n#define LAPACK_ctprfb LAPACK_GLOBAL(ctprfb,CTPRFB)\n#define LAPACK_ztprfb LAPACK_GLOBAL(ztprfb,ZTPRFB)\n// LAPACK 3.X.X\n#define LAPACK_csyr LAPACK_GLOBAL(csyr,CSYR)\n#define LAPACK_zsyr LAPACK_GLOBAL(zsyr,ZSYR)\n\n\nvoid LAPACK_sgetrf( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_dgetrf( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_cgetrf( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_zgetrf( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_sgbtrf( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, float* ab, lapack_int* ldab,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_dgbtrf( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, double* ab, lapack_int* ldab,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_cgbtrf( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, lapack_complex_float* ab, lapack_int* ldab,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_zgbtrf( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, lapack_complex_double* ab, lapack_int* ldab,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_sgttrf( lapack_int* n, float* dl, float* d, float* du, float* du2,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_dgttrf( lapack_int* n, double* dl, double* d, double* du,\n                    double* du2, lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_cgttrf( lapack_int* n, lapack_complex_float* dl,\n                    lapack_complex_float* d, lapack_complex_float* du,\n                    lapack_complex_float* du2, lapack_int* ipiv,\n                    lapack_int *info );\nvoid LAPACK_zgttrf( lapack_int* n, lapack_complex_double* dl,\n                    lapack_complex_double* d, lapack_complex_double* du,\n                    lapack_complex_double* du2, lapack_int* ipiv,\n                    lapack_int *info );\nvoid LAPACK_spotrf( char* uplo, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_dpotrf( char* uplo, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_cpotrf( char* uplo, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_zpotrf( char* uplo, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_dpstrf( char* uplo, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int* piv, lapack_int* rank, double* tol,\n                    double* work, lapack_int *info );\nvoid LAPACK_spstrf( char* uplo, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int* piv, lapack_int* rank, float* tol, float* work,\n                    lapack_int *info );\nvoid LAPACK_zpstrf( char* uplo, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* piv, lapack_int* rank,\n                    double* tol, double* work, lapack_int *info );\nvoid LAPACK_cpstrf( char* uplo, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int* piv, lapack_int* rank,\n                    float* tol, float* work, lapack_int *info );\nvoid LAPACK_dpftrf( char* transr, char* uplo, lapack_int* n, double* a,\n                    lapack_int *info );\nvoid LAPACK_spftrf( char* transr, char* uplo, lapack_int* n, float* a,\n                    lapack_int *info );\nvoid LAPACK_zpftrf( char* transr, char* uplo, lapack_int* n,\n                    lapack_complex_double* a, lapack_int *info );\nvoid LAPACK_cpftrf( char* transr, char* uplo, lapack_int* n,\n                    lapack_complex_float* a, lapack_int *info );\nvoid LAPACK_spptrf( char* uplo, lapack_int* n, float* ap, lapack_int *info );\nvoid LAPACK_dpptrf( char* uplo, lapack_int* n, double* ap, lapack_int *info );\nvoid LAPACK_cpptrf( char* uplo, lapack_int* n, lapack_complex_float* ap,\n                    lapack_int *info );\nvoid LAPACK_zpptrf( char* uplo, lapack_int* n, lapack_complex_double* ap,\n                    lapack_int *info );\nvoid LAPACK_spbtrf( char* uplo, lapack_int* n, lapack_int* kd, float* ab,\n                    lapack_int* ldab, lapack_int *info );\nvoid LAPACK_dpbtrf( char* uplo, lapack_int* n, lapack_int* kd, double* ab,\n                    lapack_int* ldab, lapack_int *info );\nvoid LAPACK_cpbtrf( char* uplo, lapack_int* n, lapack_int* kd,\n                    lapack_complex_float* ab, lapack_int* ldab,\n                    lapack_int *info );\nvoid LAPACK_zpbtrf( char* uplo, lapack_int* n, lapack_int* kd,\n                    lapack_complex_double* ab, lapack_int* ldab,\n                    lapack_int *info );\nvoid LAPACK_spttrf( lapack_int* n, float* d, float* e, lapack_int *info );\nvoid LAPACK_dpttrf( lapack_int* n, double* d, double* e, lapack_int *info );\nvoid LAPACK_cpttrf( lapack_int* n, float* d, lapack_complex_float* e,\n                    lapack_int *info );\nvoid LAPACK_zpttrf( lapack_int* n, double* d, lapack_complex_double* e,\n                    lapack_int *info );\nvoid LAPACK_ssytrf( char* uplo, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int* ipiv, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dsytrf( char* uplo, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int* ipiv, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_csytrf( char* uplo, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int* ipiv,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zsytrf( char* uplo, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* ipiv,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_chetrf( char* uplo, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int* ipiv,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zhetrf( char* uplo, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* ipiv,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_ssptrf( char* uplo, lapack_int* n, float* ap, lapack_int* ipiv,\n                    lapack_int *info );\nvoid LAPACK_dsptrf( char* uplo, lapack_int* n, double* ap, lapack_int* ipiv,\n                    lapack_int *info );\nvoid LAPACK_csptrf( char* uplo, lapack_int* n, lapack_complex_float* ap,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_zsptrf( char* uplo, lapack_int* n, lapack_complex_double* ap,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_chptrf( char* uplo, lapack_int* n, lapack_complex_float* ap,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_zhptrf( char* uplo, lapack_int* n, lapack_complex_double* ap,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_sgetrs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const float* a, lapack_int* lda, const lapack_int* ipiv,\n                    float* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dgetrs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const double* a, lapack_int* lda, const lapack_int* ipiv,\n                    double* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_cgetrs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    const lapack_int* ipiv, lapack_complex_float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zgetrs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_int* ipiv, lapack_complex_double* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_sgbtrs( char* trans, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    lapack_int* nrhs, const float* ab, lapack_int* ldab,\n                    const lapack_int* ipiv, float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_dgbtrs( char* trans, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    lapack_int* nrhs, const double* ab, lapack_int* ldab,\n                    const lapack_int* ipiv, double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_cgbtrs( char* trans, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    lapack_int* nrhs, const lapack_complex_float* ab,\n                    lapack_int* ldab, const lapack_int* ipiv,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_zgbtrs( char* trans, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    lapack_int* nrhs, const lapack_complex_double* ab,\n                    lapack_int* ldab, const lapack_int* ipiv,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_sgttrs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const float* dl, const float* d, const float* du,\n                    const float* du2, const lapack_int* ipiv, float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dgttrs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const double* dl, const double* d, const double* du,\n                    const double* du2, const lapack_int* ipiv, double* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_cgttrs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* dl,\n                    const lapack_complex_float* d,\n                    const lapack_complex_float* du,\n                    const lapack_complex_float* du2, const lapack_int* ipiv,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_zgttrs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* dl,\n                    const lapack_complex_double* d,\n                    const lapack_complex_double* du,\n                    const lapack_complex_double* du2, const lapack_int* ipiv,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_spotrs( char* uplo, lapack_int* n, lapack_int* nrhs, const float* a,\n                    lapack_int* lda, float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_dpotrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* a, lapack_int* lda, double* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_cpotrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_zpotrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_dpftrs( char* transr, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* a, double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_spftrs( char* transr, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const float* a, float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_zpftrs( char* transr, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_complex_double* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_cpftrs( char* transr, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_complex_float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_spptrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const float* ap, float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_dpptrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* ap, double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_cpptrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* ap, lapack_complex_float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zpptrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* ap, lapack_complex_double* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_spbtrs( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                    const float* ab, lapack_int* ldab, float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dpbtrs( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                    const double* ab, lapack_int* ldab, double* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_cpbtrs( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                    const lapack_complex_float* ab, lapack_int* ldab,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_zpbtrs( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                    const lapack_complex_double* ab, lapack_int* ldab,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_spttrs( lapack_int* n, lapack_int* nrhs, const float* d,\n                    const float* e, float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_dpttrs( lapack_int* n, lapack_int* nrhs, const double* d,\n                    const double* e, double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_cpttrs( char* uplo, lapack_int* n, lapack_int* nrhs, const float* d,\n                    const lapack_complex_float* e, lapack_complex_float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zpttrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* d, const lapack_complex_double* e,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_ssytrs( char* uplo, lapack_int* n, lapack_int* nrhs, const float* a,\n                    lapack_int* lda, const lapack_int* ipiv, float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dsytrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* a, lapack_int* lda, const lapack_int* ipiv,\n                    double* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_csytrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    const lapack_int* ipiv, lapack_complex_float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zsytrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_int* ipiv, lapack_complex_double* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_chetrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    const lapack_int* ipiv, lapack_complex_float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zhetrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_int* ipiv, lapack_complex_double* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_ssptrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const float* ap, const lapack_int* ipiv, float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dsptrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* ap, const lapack_int* ipiv, double* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_csptrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* ap, const lapack_int* ipiv,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_zsptrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* ap, const lapack_int* ipiv,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_chptrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* ap, const lapack_int* ipiv,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_zhptrs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* ap, const lapack_int* ipiv,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_strtrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const float* a, lapack_int* lda, float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dtrtrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const double* a, lapack_int* lda,\n                    double* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_ctrtrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_ztrtrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_stptrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const float* ap, float* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dtptrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const double* ap, double* b,\n                    lapack_int* ldb, lapack_int *info );\nvoid LAPACK_ctptrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const lapack_complex_float* ap,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_ztptrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const lapack_complex_double* ap,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_stbtrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* kd, lapack_int* nrhs, const float* ab,\n                    lapack_int* ldab, float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_dtbtrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* kd, lapack_int* nrhs, const double* ab,\n                    lapack_int* ldab, double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_ctbtrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* kd, lapack_int* nrhs,\n                    const lapack_complex_float* ab, lapack_int* ldab,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_ztbtrs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* kd, lapack_int* nrhs,\n                    const lapack_complex_double* ab, lapack_int* ldab,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_sgecon( char* norm, lapack_int* n, const float* a, lapack_int* lda,\n                    float* anorm, float* rcond, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dgecon( char* norm, lapack_int* n, const double* a, lapack_int* lda,\n                    double* anorm, double* rcond, double* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cgecon( char* norm, lapack_int* n, const lapack_complex_float* a,\n                    lapack_int* lda, float* anorm, float* rcond,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zgecon( char* norm, lapack_int* n, const lapack_complex_double* a,\n                    lapack_int* lda, double* anorm, double* rcond,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_sgbcon( char* norm, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    const float* ab, lapack_int* ldab, const lapack_int* ipiv,\n                    float* anorm, float* rcond, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dgbcon( char* norm, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    const double* ab, lapack_int* ldab, const lapack_int* ipiv,\n                    double* anorm, double* rcond, double* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cgbcon( char* norm, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    const lapack_complex_float* ab, lapack_int* ldab,\n                    const lapack_int* ipiv, float* anorm, float* rcond,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zgbcon( char* norm, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    const lapack_complex_double* ab, lapack_int* ldab,\n                    const lapack_int* ipiv, double* anorm, double* rcond,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_sgtcon( char* norm, lapack_int* n, const float* dl, const float* d,\n                    const float* du, const float* du2, const lapack_int* ipiv,\n                    float* anorm, float* rcond, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dgtcon( char* norm, lapack_int* n, const double* dl,\n                    const double* d, const double* du, const double* du2,\n                    const lapack_int* ipiv, double* anorm, double* rcond,\n                    double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cgtcon( char* norm, lapack_int* n, const lapack_complex_float* dl,\n                    const lapack_complex_float* d,\n                    const lapack_complex_float* du,\n                    const lapack_complex_float* du2, const lapack_int* ipiv,\n                    float* anorm, float* rcond, lapack_complex_float* work,\n                    lapack_int *info );\nvoid LAPACK_zgtcon( char* norm, lapack_int* n, const lapack_complex_double* dl,\n                    const lapack_complex_double* d,\n                    const lapack_complex_double* du,\n                    const lapack_complex_double* du2, const lapack_int* ipiv,\n                    double* anorm, double* rcond, lapack_complex_double* work,\n                    lapack_int *info );\nvoid LAPACK_spocon( char* uplo, lapack_int* n, const float* a, lapack_int* lda,\n                    float* anorm, float* rcond, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dpocon( char* uplo, lapack_int* n, const double* a, lapack_int* lda,\n                    double* anorm, double* rcond, double* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cpocon( char* uplo, lapack_int* n, const lapack_complex_float* a,\n                    lapack_int* lda, float* anorm, float* rcond,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zpocon( char* uplo, lapack_int* n, const lapack_complex_double* a,\n                    lapack_int* lda, double* anorm, double* rcond,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_sppcon( char* uplo, lapack_int* n, const float* ap, float* anorm,\n                    float* rcond, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dppcon( char* uplo, lapack_int* n, const double* ap, double* anorm,\n                    double* rcond, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_cppcon( char* uplo, lapack_int* n, const lapack_complex_float* ap,\n                    float* anorm, float* rcond, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zppcon( char* uplo, lapack_int* n, const lapack_complex_double* ap,\n                    double* anorm, double* rcond, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_spbcon( char* uplo, lapack_int* n, lapack_int* kd, const float* ab,\n                    lapack_int* ldab, float* anorm, float* rcond, float* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dpbcon( char* uplo, lapack_int* n, lapack_int* kd, const double* ab,\n                    lapack_int* ldab, double* anorm, double* rcond,\n                    double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cpbcon( char* uplo, lapack_int* n, lapack_int* kd,\n                    const lapack_complex_float* ab, lapack_int* ldab,\n                    float* anorm, float* rcond, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zpbcon( char* uplo, lapack_int* n, lapack_int* kd,\n                    const lapack_complex_double* ab, lapack_int* ldab,\n                    double* anorm, double* rcond, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_sptcon( lapack_int* n, const float* d, const float* e, float* anorm,\n                    float* rcond, float* work, lapack_int *info );\nvoid LAPACK_dptcon( lapack_int* n, const double* d, const double* e,\n                    double* anorm, double* rcond, double* work,\n                    lapack_int *info );\nvoid LAPACK_cptcon( lapack_int* n, const float* d,\n                    const lapack_complex_float* e, float* anorm, float* rcond,\n                    float* work, lapack_int *info );\nvoid LAPACK_zptcon( lapack_int* n, const double* d,\n                    const lapack_complex_double* e, double* anorm,\n                    double* rcond, double* work, lapack_int *info );\nvoid LAPACK_ssycon( char* uplo, lapack_int* n, const float* a, lapack_int* lda,\n                    const lapack_int* ipiv, float* anorm, float* rcond,\n                    float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dsycon( char* uplo, lapack_int* n, const double* a, lapack_int* lda,\n                    const lapack_int* ipiv, double* anorm, double* rcond,\n                    double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_csycon( char* uplo, lapack_int* n, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_int* ipiv, float* anorm,\n                    float* rcond, lapack_complex_float* work,\n                    lapack_int *info );\nvoid LAPACK_zsycon( char* uplo, lapack_int* n, const lapack_complex_double* a,\n                    lapack_int* lda, const lapack_int* ipiv, double* anorm,\n                    double* rcond, lapack_complex_double* work,\n                    lapack_int *info );\nvoid LAPACK_checon( char* uplo, lapack_int* n, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_int* ipiv, float* anorm,\n                    float* rcond, lapack_complex_float* work,\n                    lapack_int *info );\nvoid LAPACK_zhecon( char* uplo, lapack_int* n, const lapack_complex_double* a,\n                    lapack_int* lda, const lapack_int* ipiv, double* anorm,\n                    double* rcond, lapack_complex_double* work,\n                    lapack_int *info );\nvoid LAPACK_sspcon( char* uplo, lapack_int* n, const float* ap,\n                    const lapack_int* ipiv, float* anorm, float* rcond,\n                    float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dspcon( char* uplo, lapack_int* n, const double* ap,\n                    const lapack_int* ipiv, double* anorm, double* rcond,\n                    double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cspcon( char* uplo, lapack_int* n, const lapack_complex_float* ap,\n                    const lapack_int* ipiv, float* anorm, float* rcond,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zspcon( char* uplo, lapack_int* n, const lapack_complex_double* ap,\n                    const lapack_int* ipiv, double* anorm, double* rcond,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_chpcon( char* uplo, lapack_int* n, const lapack_complex_float* ap,\n                    const lapack_int* ipiv, float* anorm, float* rcond,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zhpcon( char* uplo, lapack_int* n, const lapack_complex_double* ap,\n                    const lapack_int* ipiv, double* anorm, double* rcond,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_strcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    const float* a, lapack_int* lda, float* rcond, float* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dtrcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    const double* a, lapack_int* lda, double* rcond,\n                    double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ctrcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    float* rcond, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_ztrcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    double* rcond, lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_stpcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    const float* ap, float* rcond, float* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dtpcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    const double* ap, double* rcond, double* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ctpcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    const lapack_complex_float* ap, float* rcond,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_ztpcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    const lapack_complex_double* ap, double* rcond,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_stbcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    lapack_int* kd, const float* ab, lapack_int* ldab,\n                    float* rcond, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dtbcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    lapack_int* kd, const double* ab, lapack_int* ldab,\n                    double* rcond, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_ctbcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    lapack_int* kd, const lapack_complex_float* ab,\n                    lapack_int* ldab, float* rcond, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_ztbcon( char* norm, char* uplo, char* diag, lapack_int* n,\n                    lapack_int* kd, const lapack_complex_double* ab,\n                    lapack_int* ldab, double* rcond,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_sgerfs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const float* a, lapack_int* lda, const float* af,\n                    lapack_int* ldaf, const lapack_int* ipiv, const float* b,\n                    lapack_int* ldb, float* x, lapack_int* ldx, float* ferr,\n                    float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dgerfs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const double* a, lapack_int* lda, const double* af,\n                    lapack_int* ldaf, const lapack_int* ipiv, const double* b,\n                    lapack_int* ldb, double* x, lapack_int* ldx, double* ferr,\n                    double* berr, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_cgerfs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* af, lapack_int* ldaf,\n                    const lapack_int* ipiv, const lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* x, lapack_int* ldx,\n                    float* ferr, float* berr, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zgerfs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* af, lapack_int* ldaf,\n                    const lapack_int* ipiv, const lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                    double* ferr, double* berr, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_dgerfsx( char* trans, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const double* a, lapack_int* lda, const double* af,\n                     lapack_int* ldaf, const lapack_int* ipiv, const double* r,\n                     const double* c, const double* b, lapack_int* ldb,\n                     double* x, lapack_int* ldx, double* rcond, double* berr,\n                     lapack_int* n_err_bnds, double* err_bnds_norm,\n                     double* err_bnds_comp, lapack_int* nparams, double* params,\n                     double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_sgerfsx( char* trans, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const float* a, lapack_int* lda, const float* af,\n                     lapack_int* ldaf, const lapack_int* ipiv, const float* r,\n                     const float* c, const float* b, lapack_int* ldb, float* x,\n                     lapack_int* ldx, float* rcond, float* berr,\n                     lapack_int* n_err_bnds, float* err_bnds_norm,\n                     float* err_bnds_comp, lapack_int* nparams, float* params,\n                     float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_zgerfsx( char* trans, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const lapack_complex_double* a, lapack_int* lda,\n                     const lapack_complex_double* af, lapack_int* ldaf,\n                     const lapack_int* ipiv, const double* r, const double* c,\n                     const lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                     double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params,\n                     lapack_complex_double* work, double* rwork,\n                     lapack_int *info );\nvoid LAPACK_cgerfsx( char* trans, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const lapack_complex_float* a, lapack_int* lda,\n                     const lapack_complex_float* af, lapack_int* ldaf,\n                     const lapack_int* ipiv, const float* r, const float* c,\n                     const lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                     float* berr, lapack_int* n_err_bnds, float* err_bnds_norm,\n                     float* err_bnds_comp, lapack_int* nparams, float* params,\n                     lapack_complex_float* work, float* rwork,\n                     lapack_int *info );\nvoid LAPACK_sgbrfs( char* trans, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    lapack_int* nrhs, const float* ab, lapack_int* ldab,\n                    const float* afb, lapack_int* ldafb, const lapack_int* ipiv,\n                    const float* b, lapack_int* ldb, float* x, lapack_int* ldx,\n                    float* ferr, float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dgbrfs( char* trans, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    lapack_int* nrhs, const double* ab, lapack_int* ldab,\n                    const double* afb, lapack_int* ldafb,\n                    const lapack_int* ipiv, const double* b, lapack_int* ldb,\n                    double* x, lapack_int* ldx, double* ferr, double* berr,\n                    double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cgbrfs( char* trans, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    lapack_int* nrhs, const lapack_complex_float* ab,\n                    lapack_int* ldab, const lapack_complex_float* afb,\n                    lapack_int* ldafb, const lapack_int* ipiv,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* ferr,\n                    float* berr, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zgbrfs( char* trans, lapack_int* n, lapack_int* kl, lapack_int* ku,\n                    lapack_int* nrhs, const lapack_complex_double* ab,\n                    lapack_int* ldab, const lapack_complex_double* afb,\n                    lapack_int* ldafb, const lapack_int* ipiv,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* ferr,\n                    double* berr, lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_dgbrfsx( char* trans, char* equed, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, lapack_int* nrhs, const double* ab,\n                     lapack_int* ldab, const double* afb, lapack_int* ldafb,\n                     const lapack_int* ipiv, const double* r, const double* c,\n                     const double* b, lapack_int* ldb, double* x,\n                     lapack_int* ldx, double* rcond, double* berr,\n                     lapack_int* n_err_bnds, double* err_bnds_norm,\n                     double* err_bnds_comp, lapack_int* nparams, double* params,\n                     double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_sgbrfsx( char* trans, char* equed, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, lapack_int* nrhs, const float* ab,\n                     lapack_int* ldab, const float* afb, lapack_int* ldafb,\n                     const lapack_int* ipiv, const float* r, const float* c,\n                     const float* b, lapack_int* ldb, float* x, lapack_int* ldx,\n                     float* rcond, float* berr, lapack_int* n_err_bnds,\n                     float* err_bnds_norm, float* err_bnds_comp,\n                     lapack_int* nparams, float* params, float* work,\n                     lapack_int* iwork, lapack_int *info );\nvoid LAPACK_zgbrfsx( char* trans, char* equed, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, lapack_int* nrhs,\n                     const lapack_complex_double* ab, lapack_int* ldab,\n                     const lapack_complex_double* afb, lapack_int* ldafb,\n                     const lapack_int* ipiv, const double* r, const double* c,\n                     const lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                     double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params,\n                     lapack_complex_double* work, double* rwork,\n                     lapack_int *info );\nvoid LAPACK_cgbrfsx( char* trans, char* equed, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, lapack_int* nrhs,\n                     const lapack_complex_float* ab, lapack_int* ldab,\n                     const lapack_complex_float* afb, lapack_int* ldafb,\n                     const lapack_int* ipiv, const float* r, const float* c,\n                     const lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                     float* berr, lapack_int* n_err_bnds, float* err_bnds_norm,\n                     float* err_bnds_comp, lapack_int* nparams, float* params,\n                     lapack_complex_float* work, float* rwork,\n                     lapack_int *info );\nvoid LAPACK_sgtrfs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const float* dl, const float* d, const float* du,\n                    const float* dlf, const float* df, const float* duf,\n                    const float* du2, const lapack_int* ipiv, const float* b,\n                    lapack_int* ldb, float* x, lapack_int* ldx, float* ferr,\n                    float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dgtrfs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const double* dl, const double* d, const double* du,\n                    const double* dlf, const double* df, const double* duf,\n                    const double* du2, const lapack_int* ipiv, const double* b,\n                    lapack_int* ldb, double* x, lapack_int* ldx, double* ferr,\n                    double* berr, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_cgtrfs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* dl,\n                    const lapack_complex_float* d,\n                    const lapack_complex_float* du,\n                    const lapack_complex_float* dlf,\n                    const lapack_complex_float* df,\n                    const lapack_complex_float* duf,\n                    const lapack_complex_float* du2, const lapack_int* ipiv,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* ferr,\n                    float* berr, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zgtrfs( char* trans, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* dl,\n                    const lapack_complex_double* d,\n                    const lapack_complex_double* du,\n                    const lapack_complex_double* dlf,\n                    const lapack_complex_double* df,\n                    const lapack_complex_double* duf,\n                    const lapack_complex_double* du2, const lapack_int* ipiv,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* ferr,\n                    double* berr, lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_sporfs( char* uplo, lapack_int* n, lapack_int* nrhs, const float* a,\n                    lapack_int* lda, const float* af, lapack_int* ldaf,\n                    const float* b, lapack_int* ldb, float* x, lapack_int* ldx,\n                    float* ferr, float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dporfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* a, lapack_int* lda, const double* af,\n                    lapack_int* ldaf, const double* b, lapack_int* ldb,\n                    double* x, lapack_int* ldx, double* ferr, double* berr,\n                    double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cporfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* af, lapack_int* ldaf,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* ferr,\n                    float* berr, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zporfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* af, lapack_int* ldaf,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* ferr,\n                    double* berr, lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_dporfsx( char* uplo, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const double* a, lapack_int* lda, const double* af,\n                     lapack_int* ldaf, const double* s, const double* b,\n                     lapack_int* ldb, double* x, lapack_int* ldx, double* rcond,\n                     double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params, double* work,\n                     lapack_int* iwork, lapack_int *info );\nvoid LAPACK_sporfsx( char* uplo, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const float* a, lapack_int* lda, const float* af,\n                     lapack_int* ldaf, const float* s, const float* b,\n                     lapack_int* ldb, float* x, lapack_int* ldx, float* rcond,\n                     float* berr, lapack_int* n_err_bnds, float* err_bnds_norm,\n                     float* err_bnds_comp, lapack_int* nparams, float* params,\n                     float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_zporfsx( char* uplo, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const lapack_complex_double* a, lapack_int* lda,\n                     const lapack_complex_double* af, lapack_int* ldaf,\n                     const double* s, const lapack_complex_double* b,\n                     lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                     double* rcond, double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params,\n                     lapack_complex_double* work, double* rwork,\n                     lapack_int *info );\nvoid LAPACK_cporfsx( char* uplo, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const lapack_complex_float* a, lapack_int* lda,\n                     const lapack_complex_float* af, lapack_int* ldaf,\n                     const float* s, const lapack_complex_float* b,\n                     lapack_int* ldb, lapack_complex_float* x, lapack_int* ldx,\n                     float* rcond, float* berr, lapack_int* n_err_bnds,\n                     float* err_bnds_norm, float* err_bnds_comp,\n                     lapack_int* nparams, float* params,\n                     lapack_complex_float* work, float* rwork,\n                     lapack_int *info );\nvoid LAPACK_spprfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const float* ap, const float* afp, const float* b,\n                    lapack_int* ldb, float* x, lapack_int* ldx, float* ferr,\n                    float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dpprfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* ap, const double* afp, const double* b,\n                    lapack_int* ldb, double* x, lapack_int* ldx, double* ferr,\n                    double* berr, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_cpprfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* ap,\n                    const lapack_complex_float* afp,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* ferr,\n                    float* berr, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zpprfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* ap,\n                    const lapack_complex_double* afp,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* ferr,\n                    double* berr, lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_spbrfs( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                    const float* ab, lapack_int* ldab, const float* afb,\n                    lapack_int* ldafb, const float* b, lapack_int* ldb,\n                    float* x, lapack_int* ldx, float* ferr, float* berr,\n                    float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dpbrfs( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                    const double* ab, lapack_int* ldab, const double* afb,\n                    lapack_int* ldafb, const double* b, lapack_int* ldb,\n                    double* x, lapack_int* ldx, double* ferr, double* berr,\n                    double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cpbrfs( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                    const lapack_complex_float* ab, lapack_int* ldab,\n                    const lapack_complex_float* afb, lapack_int* ldafb,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* ferr,\n                    float* berr, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zpbrfs( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                    const lapack_complex_double* ab, lapack_int* ldab,\n                    const lapack_complex_double* afb, lapack_int* ldafb,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* ferr,\n                    double* berr, lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_sptrfs( lapack_int* n, lapack_int* nrhs, const float* d,\n                    const float* e, const float* df, const float* ef,\n                    const float* b, lapack_int* ldb, float* x, lapack_int* ldx,\n                    float* ferr, float* berr, float* work, lapack_int *info );\nvoid LAPACK_dptrfs( lapack_int* n, lapack_int* nrhs, const double* d,\n                    const double* e, const double* df, const double* ef,\n                    const double* b, lapack_int* ldb, double* x,\n                    lapack_int* ldx, double* ferr, double* berr, double* work,\n                    lapack_int *info );\nvoid LAPACK_cptrfs( char* uplo, lapack_int* n, lapack_int* nrhs, const float* d,\n                    const lapack_complex_float* e, const float* df,\n                    const lapack_complex_float* ef,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* ferr,\n                    float* berr, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zptrfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* d, const lapack_complex_double* e,\n                    const double* df, const lapack_complex_double* ef,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* ferr,\n                    double* berr, lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_ssyrfs( char* uplo, lapack_int* n, lapack_int* nrhs, const float* a,\n                    lapack_int* lda, const float* af, lapack_int* ldaf,\n                    const lapack_int* ipiv, const float* b, lapack_int* ldb,\n                    float* x, lapack_int* ldx, float* ferr, float* berr,\n                    float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dsyrfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* a, lapack_int* lda, const double* af,\n                    lapack_int* ldaf, const lapack_int* ipiv, const double* b,\n                    lapack_int* ldb, double* x, lapack_int* ldx, double* ferr,\n                    double* berr, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_csyrfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* af, lapack_int* ldaf,\n                    const lapack_int* ipiv, const lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* x, lapack_int* ldx,\n                    float* ferr, float* berr, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zsyrfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* af, lapack_int* ldaf,\n                    const lapack_int* ipiv, const lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                    double* ferr, double* berr, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_dsyrfsx( char* uplo, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const double* a, lapack_int* lda, const double* af,\n                     lapack_int* ldaf, const lapack_int* ipiv, const double* s,\n                     const double* b, lapack_int* ldb, double* x,\n                     lapack_int* ldx, double* rcond, double* berr,\n                     lapack_int* n_err_bnds, double* err_bnds_norm,\n                     double* err_bnds_comp, lapack_int* nparams, double* params,\n                     double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ssyrfsx( char* uplo, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const float* a, lapack_int* lda, const float* af,\n                     lapack_int* ldaf, const lapack_int* ipiv, const float* s,\n                     const float* b, lapack_int* ldb, float* x, lapack_int* ldx,\n                     float* rcond, float* berr, lapack_int* n_err_bnds,\n                     float* err_bnds_norm, float* err_bnds_comp,\n                     lapack_int* nparams, float* params, float* work,\n                     lapack_int* iwork, lapack_int *info );\nvoid LAPACK_zsyrfsx( char* uplo, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const lapack_complex_double* a, lapack_int* lda,\n                     const lapack_complex_double* af, lapack_int* ldaf,\n                     const lapack_int* ipiv, const double* s,\n                     const lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                     double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params,\n                     lapack_complex_double* work, double* rwork,\n                     lapack_int *info );\nvoid LAPACK_csyrfsx( char* uplo, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const lapack_complex_float* a, lapack_int* lda,\n                     const lapack_complex_float* af, lapack_int* ldaf,\n                     const lapack_int* ipiv, const float* s,\n                     const lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                     float* berr, lapack_int* n_err_bnds, float* err_bnds_norm,\n                     float* err_bnds_comp, lapack_int* nparams, float* params,\n                     lapack_complex_float* work, float* rwork,\n                     lapack_int *info );\nvoid LAPACK_cherfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* af, lapack_int* ldaf,\n                    const lapack_int* ipiv, const lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* x, lapack_int* ldx,\n                    float* ferr, float* berr, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zherfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* af, lapack_int* ldaf,\n                    const lapack_int* ipiv, const lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                    double* ferr, double* berr, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_zherfsx( char* uplo, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const lapack_complex_double* a, lapack_int* lda,\n                     const lapack_complex_double* af, lapack_int* ldaf,\n                     const lapack_int* ipiv, const double* s,\n                     const lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                     double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params,\n                     lapack_complex_double* work, double* rwork,\n                     lapack_int *info );\nvoid LAPACK_cherfsx( char* uplo, char* equed, lapack_int* n, lapack_int* nrhs,\n                     const lapack_complex_float* a, lapack_int* lda,\n                     const lapack_complex_float* af, lapack_int* ldaf,\n                     const lapack_int* ipiv, const float* s,\n                     const lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                     float* berr, lapack_int* n_err_bnds, float* err_bnds_norm,\n                     float* err_bnds_comp, lapack_int* nparams, float* params,\n                     lapack_complex_float* work, float* rwork,\n                     lapack_int *info );\nvoid LAPACK_ssprfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const float* ap, const float* afp, const lapack_int* ipiv,\n                    const float* b, lapack_int* ldb, float* x, lapack_int* ldx,\n                    float* ferr, float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dsprfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* ap, const double* afp, const lapack_int* ipiv,\n                    const double* b, lapack_int* ldb, double* x,\n                    lapack_int* ldx, double* ferr, double* berr, double* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_csprfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* ap,\n                    const lapack_complex_float* afp, const lapack_int* ipiv,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* ferr,\n                    float* berr, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zsprfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* ap,\n                    const lapack_complex_double* afp, const lapack_int* ipiv,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* ferr,\n                    double* berr, lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_chprfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* ap,\n                    const lapack_complex_float* afp, const lapack_int* ipiv,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* ferr,\n                    float* berr, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zhprfs( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* ap,\n                    const lapack_complex_double* afp, const lapack_int* ipiv,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* ferr,\n                    double* berr, lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_strrfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const float* a, lapack_int* lda,\n                    const float* b, lapack_int* ldb, const float* x,\n                    lapack_int* ldx, float* ferr, float* berr, float* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dtrrfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const double* a, lapack_int* lda,\n                    const double* b, lapack_int* ldb, const double* x,\n                    lapack_int* ldx, double* ferr, double* berr, double* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ctrrfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* b,\n                    lapack_int* ldb, const lapack_complex_float* x,\n                    lapack_int* ldx, float* ferr, float* berr,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_ztrrfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const lapack_complex_double* a,\n                    lapack_int* lda, const lapack_complex_double* b,\n                    lapack_int* ldb, const lapack_complex_double* x,\n                    lapack_int* ldx, double* ferr, double* berr,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_stprfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const float* ap, const float* b,\n                    lapack_int* ldb, const float* x, lapack_int* ldx,\n                    float* ferr, float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dtprfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const double* ap, const double* b,\n                    lapack_int* ldb, const double* x, lapack_int* ldx,\n                    double* ferr, double* berr, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_ctprfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const lapack_complex_float* ap,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    const lapack_complex_float* x, lapack_int* ldx, float* ferr,\n                    float* berr, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_ztprfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* nrhs, const lapack_complex_double* ap,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    const lapack_complex_double* x, lapack_int* ldx,\n                    double* ferr, double* berr, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_stbrfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* kd, lapack_int* nrhs, const float* ab,\n                    lapack_int* ldab, const float* b, lapack_int* ldb,\n                    const float* x, lapack_int* ldx, float* ferr, float* berr,\n                    float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dtbrfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* kd, lapack_int* nrhs, const double* ab,\n                    lapack_int* ldab, const double* b, lapack_int* ldb,\n                    const double* x, lapack_int* ldx, double* ferr,\n                    double* berr, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_ctbrfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* kd, lapack_int* nrhs,\n                    const lapack_complex_float* ab, lapack_int* ldab,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    const lapack_complex_float* x, lapack_int* ldx, float* ferr,\n                    float* berr, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_ztbrfs( char* uplo, char* trans, char* diag, lapack_int* n,\n                    lapack_int* kd, lapack_int* nrhs,\n                    const lapack_complex_double* ab, lapack_int* ldab,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    const lapack_complex_double* x, lapack_int* ldx,\n                    double* ferr, double* berr, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_sgetri( lapack_int* n, float* a, lapack_int* lda,\n                    const lapack_int* ipiv, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dgetri( lapack_int* n, double* a, lapack_int* lda,\n                    const lapack_int* ipiv, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cgetri( lapack_int* n, lapack_complex_float* a, lapack_int* lda,\n                    const lapack_int* ipiv, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zgetri( lapack_int* n, lapack_complex_double* a, lapack_int* lda,\n                    const lapack_int* ipiv, lapack_complex_double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_spotri( char* uplo, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_dpotri( char* uplo, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_cpotri( char* uplo, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_zpotri( char* uplo, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_dpftri( char* transr, char* uplo, lapack_int* n, double* a,\n                    lapack_int *info );\nvoid LAPACK_spftri( char* transr, char* uplo, lapack_int* n, float* a,\n                    lapack_int *info );\nvoid LAPACK_zpftri( char* transr, char* uplo, lapack_int* n,\n                    lapack_complex_double* a, lapack_int *info );\nvoid LAPACK_cpftri( char* transr, char* uplo, lapack_int* n,\n                    lapack_complex_float* a, lapack_int *info );\nvoid LAPACK_spptri( char* uplo, lapack_int* n, float* ap, lapack_int *info );\nvoid LAPACK_dpptri( char* uplo, lapack_int* n, double* ap, lapack_int *info );\nvoid LAPACK_cpptri( char* uplo, lapack_int* n, lapack_complex_float* ap,\n                    lapack_int *info );\nvoid LAPACK_zpptri( char* uplo, lapack_int* n, lapack_complex_double* ap,\n                    lapack_int *info );\nvoid LAPACK_ssytri( char* uplo, lapack_int* n, float* a, lapack_int* lda,\n                    const lapack_int* ipiv, float* work, lapack_int *info );\nvoid LAPACK_dsytri( char* uplo, lapack_int* n, double* a, lapack_int* lda,\n                    const lapack_int* ipiv, double* work, lapack_int *info );\nvoid LAPACK_csytri( char* uplo, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, const lapack_int* ipiv,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zsytri( char* uplo, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, const lapack_int* ipiv,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_chetri( char* uplo, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, const lapack_int* ipiv,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zhetri( char* uplo, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, const lapack_int* ipiv,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_ssptri( char* uplo, lapack_int* n, float* ap,\n                    const lapack_int* ipiv, float* work, lapack_int *info );\nvoid LAPACK_dsptri( char* uplo, lapack_int* n, double* ap,\n                    const lapack_int* ipiv, double* work, lapack_int *info );\nvoid LAPACK_csptri( char* uplo, lapack_int* n, lapack_complex_float* ap,\n                    const lapack_int* ipiv, lapack_complex_float* work,\n                    lapack_int *info );\nvoid LAPACK_zsptri( char* uplo, lapack_int* n, lapack_complex_double* ap,\n                    const lapack_int* ipiv, lapack_complex_double* work,\n                    lapack_int *info );\nvoid LAPACK_chptri( char* uplo, lapack_int* n, lapack_complex_float* ap,\n                    const lapack_int* ipiv, lapack_complex_float* work,\n                    lapack_int *info );\nvoid LAPACK_zhptri( char* uplo, lapack_int* n, lapack_complex_double* ap,\n                    const lapack_int* ipiv, lapack_complex_double* work,\n                    lapack_int *info );\nvoid LAPACK_strtri( char* uplo, char* diag, lapack_int* n, float* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_dtrtri( char* uplo, char* diag, lapack_int* n, double* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_ctrtri( char* uplo, char* diag, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_ztrtri( char* uplo, char* diag, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_dtftri( char* transr, char* uplo, char* diag, lapack_int* n,\n                    double* a, lapack_int *info );\nvoid LAPACK_stftri( char* transr, char* uplo, char* diag, lapack_int* n,\n                    float* a, lapack_int *info );\nvoid LAPACK_ztftri( char* transr, char* uplo, char* diag, lapack_int* n,\n                    lapack_complex_double* a, lapack_int *info );\nvoid LAPACK_ctftri( char* transr, char* uplo, char* diag, lapack_int* n,\n                    lapack_complex_float* a, lapack_int *info );\nvoid LAPACK_stptri( char* uplo, char* diag, lapack_int* n, float* ap,\n                    lapack_int *info );\nvoid LAPACK_dtptri( char* uplo, char* diag, lapack_int* n, double* ap,\n                    lapack_int *info );\nvoid LAPACK_ctptri( char* uplo, char* diag, lapack_int* n,\n                    lapack_complex_float* ap, lapack_int *info );\nvoid LAPACK_ztptri( char* uplo, char* diag, lapack_int* n,\n                    lapack_complex_double* ap, lapack_int *info );\nvoid LAPACK_sgeequ( lapack_int* m, lapack_int* n, const float* a,\n                    lapack_int* lda, float* r, float* c, float* rowcnd,\n                    float* colcnd, float* amax, lapack_int *info );\nvoid LAPACK_dgeequ( lapack_int* m, lapack_int* n, const double* a,\n                    lapack_int* lda, double* r, double* c, double* rowcnd,\n                    double* colcnd, double* amax, lapack_int *info );\nvoid LAPACK_cgeequ( lapack_int* m, lapack_int* n, const lapack_complex_float* a,\n                    lapack_int* lda, float* r, float* c, float* rowcnd,\n                    float* colcnd, float* amax, lapack_int *info );\nvoid LAPACK_zgeequ( lapack_int* m, lapack_int* n,\n                    const lapack_complex_double* a, lapack_int* lda, double* r,\n                    double* c, double* rowcnd, double* colcnd, double* amax,\n                    lapack_int *info );\nvoid LAPACK_dgeequb( lapack_int* m, lapack_int* n, const double* a,\n                     lapack_int* lda, double* r, double* c, double* rowcnd,\n                     double* colcnd, double* amax, lapack_int *info );\nvoid LAPACK_sgeequb( lapack_int* m, lapack_int* n, const float* a,\n                     lapack_int* lda, float* r, float* c, float* rowcnd,\n                     float* colcnd, float* amax, lapack_int *info );\nvoid LAPACK_zgeequb( lapack_int* m, lapack_int* n,\n                     const lapack_complex_double* a, lapack_int* lda, double* r,\n                     double* c, double* rowcnd, double* colcnd, double* amax,\n                     lapack_int *info );\nvoid LAPACK_cgeequb( lapack_int* m, lapack_int* n,\n                     const lapack_complex_float* a, lapack_int* lda, float* r,\n                     float* c, float* rowcnd, float* colcnd, float* amax,\n                     lapack_int *info );\nvoid LAPACK_sgbequ( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, const float* ab, lapack_int* ldab, float* r,\n                    float* c, float* rowcnd, float* colcnd, float* amax,\n                    lapack_int *info );\nvoid LAPACK_dgbequ( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, const double* ab, lapack_int* ldab,\n                    double* r, double* c, double* rowcnd, double* colcnd,\n                    double* amax, lapack_int *info );\nvoid LAPACK_cgbequ( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, const lapack_complex_float* ab,\n                    lapack_int* ldab, float* r, float* c, float* rowcnd,\n                    float* colcnd, float* amax, lapack_int *info );\nvoid LAPACK_zgbequ( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, const lapack_complex_double* ab,\n                    lapack_int* ldab, double* r, double* c, double* rowcnd,\n                    double* colcnd, double* amax, lapack_int *info );\nvoid LAPACK_dgbequb( lapack_int* m, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, const double* ab, lapack_int* ldab,\n                     double* r, double* c, double* rowcnd, double* colcnd,\n                     double* amax, lapack_int *info );\nvoid LAPACK_sgbequb( lapack_int* m, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, const float* ab, lapack_int* ldab,\n                     float* r, float* c, float* rowcnd, float* colcnd,\n                     float* amax, lapack_int *info );\nvoid LAPACK_zgbequb( lapack_int* m, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, const lapack_complex_double* ab,\n                     lapack_int* ldab, double* r, double* c, double* rowcnd,\n                     double* colcnd, double* amax, lapack_int *info );\nvoid LAPACK_cgbequb( lapack_int* m, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, const lapack_complex_float* ab,\n                     lapack_int* ldab, float* r, float* c, float* rowcnd,\n                     float* colcnd, float* amax, lapack_int *info );\nvoid LAPACK_spoequ( lapack_int* n, const float* a, lapack_int* lda, float* s,\n                    float* scond, float* amax, lapack_int *info );\nvoid LAPACK_dpoequ( lapack_int* n, const double* a, lapack_int* lda, double* s,\n                    double* scond, double* amax, lapack_int *info );\nvoid LAPACK_cpoequ( lapack_int* n, const lapack_complex_float* a,\n                    lapack_int* lda, float* s, float* scond, float* amax,\n                    lapack_int *info );\nvoid LAPACK_zpoequ( lapack_int* n, const lapack_complex_double* a,\n                    lapack_int* lda, double* s, double* scond, double* amax,\n                    lapack_int *info );\nvoid LAPACK_dpoequb( lapack_int* n, const double* a, lapack_int* lda, double* s,\n                     double* scond, double* amax, lapack_int *info );\nvoid LAPACK_spoequb( lapack_int* n, const float* a, lapack_int* lda, float* s,\n                     float* scond, float* amax, lapack_int *info );\nvoid LAPACK_zpoequb( lapack_int* n, const lapack_complex_double* a,\n                     lapack_int* lda, double* s, double* scond, double* amax,\n                     lapack_int *info );\nvoid LAPACK_cpoequb( lapack_int* n, const lapack_complex_float* a,\n                     lapack_int* lda, float* s, float* scond, float* amax,\n                     lapack_int *info );\nvoid LAPACK_sppequ( char* uplo, lapack_int* n, const float* ap, float* s,\n                    float* scond, float* amax, lapack_int *info );\nvoid LAPACK_dppequ( char* uplo, lapack_int* n, const double* ap, double* s,\n                    double* scond, double* amax, lapack_int *info );\nvoid LAPACK_cppequ( char* uplo, lapack_int* n, const lapack_complex_float* ap,\n                    float* s, float* scond, float* amax, lapack_int *info );\nvoid LAPACK_zppequ( char* uplo, lapack_int* n, const lapack_complex_double* ap,\n                    double* s, double* scond, double* amax, lapack_int *info );\nvoid LAPACK_spbequ( char* uplo, lapack_int* n, lapack_int* kd, const float* ab,\n                    lapack_int* ldab, float* s, float* scond, float* amax,\n                    lapack_int *info );\nvoid LAPACK_dpbequ( char* uplo, lapack_int* n, lapack_int* kd, const double* ab,\n                    lapack_int* ldab, double* s, double* scond, double* amax,\n                    lapack_int *info );\nvoid LAPACK_cpbequ( char* uplo, lapack_int* n, lapack_int* kd,\n                    const lapack_complex_float* ab, lapack_int* ldab, float* s,\n                    float* scond, float* amax, lapack_int *info );\nvoid LAPACK_zpbequ( char* uplo, lapack_int* n, lapack_int* kd,\n                    const lapack_complex_double* ab, lapack_int* ldab,\n                    double* s, double* scond, double* amax, lapack_int *info );\nvoid LAPACK_dsyequb( char* uplo, lapack_int* n, const double* a,\n                     lapack_int* lda, double* s, double* scond, double* amax,\n                     double* work, lapack_int *info );\nvoid LAPACK_ssyequb( char* uplo, lapack_int* n, const float* a, lapack_int* lda,\n                     float* s, float* scond, float* amax, float* work,\n                     lapack_int *info );\nvoid LAPACK_zsyequb( char* uplo, lapack_int* n, const lapack_complex_double* a,\n                     lapack_int* lda, double* s, double* scond, double* amax,\n                     lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_csyequb( char* uplo, lapack_int* n, const lapack_complex_float* a,\n                     lapack_int* lda, float* s, float* scond, float* amax,\n                     lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zheequb( char* uplo, lapack_int* n, const lapack_complex_double* a,\n                     lapack_int* lda, double* s, double* scond, double* amax,\n                     lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_cheequb( char* uplo, lapack_int* n, const lapack_complex_float* a,\n                     lapack_int* lda, float* s, float* scond, float* amax,\n                     lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_sgesv( lapack_int* n, lapack_int* nrhs, float* a, lapack_int* lda,\n                   lapack_int* ipiv, float* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_dgesv( lapack_int* n, lapack_int* nrhs, double* a, lapack_int* lda,\n                   lapack_int* ipiv, double* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_cgesv( lapack_int* n, lapack_int* nrhs, lapack_complex_float* a,\n                   lapack_int* lda, lapack_int* ipiv, lapack_complex_float* b,\n                   lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zgesv( lapack_int* n, lapack_int* nrhs, lapack_complex_double* a,\n                   lapack_int* lda, lapack_int* ipiv, lapack_complex_double* b,\n                   lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dsgesv( lapack_int* n, lapack_int* nrhs, double* a, lapack_int* lda,\n                    lapack_int* ipiv, double* b, lapack_int* ldb, double* x,\n                    lapack_int* ldx, double* work, float* swork,\n                    lapack_int* iter, lapack_int *info );\nvoid LAPACK_zcgesv( lapack_int* n, lapack_int* nrhs, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* ipiv, lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                    lapack_complex_double* work, lapack_complex_float* swork,\n                    double* rwork, lapack_int* iter, lapack_int *info );\nvoid LAPACK_sgesvx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                    float* a, lapack_int* lda, float* af, lapack_int* ldaf,\n                    lapack_int* ipiv, char* equed, float* r, float* c, float* b,\n                    lapack_int* ldb, float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dgesvx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                    double* a, lapack_int* lda, double* af, lapack_int* ldaf,\n                    lapack_int* ipiv, char* equed, double* r, double* c,\n                    double* b, lapack_int* ldb, double* x, lapack_int* ldx,\n                    double* rcond, double* ferr, double* berr, double* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cgesvx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* af, lapack_int* ldaf,\n                    lapack_int* ipiv, char* equed, float* r, float* c,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zgesvx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* af, lapack_int* ldaf,\n                    lapack_int* ipiv, char* equed, double* r, double* c,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                    double* ferr, double* berr, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_dgesvxx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                     double* a, lapack_int* lda, double* af, lapack_int* ldaf,\n                     lapack_int* ipiv, char* equed, double* r, double* c,\n                     double* b, lapack_int* ldb, double* x, lapack_int* ldx,\n                     double* rcond, double* rpvgrw, double* berr,\n                     lapack_int* n_err_bnds, double* err_bnds_norm,\n                     double* err_bnds_comp, lapack_int* nparams, double* params,\n                     double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_sgesvxx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                     float* a, lapack_int* lda, float* af, lapack_int* ldaf,\n                     lapack_int* ipiv, char* equed, float* r, float* c,\n                     float* b, lapack_int* ldb, float* x, lapack_int* ldx,\n                     float* rcond, float* rpvgrw, float* berr,\n                     lapack_int* n_err_bnds, float* err_bnds_norm,\n                     float* err_bnds_comp, lapack_int* nparams, float* params,\n                     float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_zgesvxx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                     lapack_complex_double* a, lapack_int* lda,\n                     lapack_complex_double* af, lapack_int* ldaf,\n                     lapack_int* ipiv, char* equed, double* r, double* c,\n                     lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                     double* rpvgrw, double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params,\n                     lapack_complex_double* work, double* rwork,\n                     lapack_int *info );\nvoid LAPACK_cgesvxx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                     lapack_complex_float* a, lapack_int* lda,\n                     lapack_complex_float* af, lapack_int* ldaf,\n                     lapack_int* ipiv, char* equed, float* r, float* c,\n                     lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                     float* rpvgrw, float* berr, lapack_int* n_err_bnds,\n                     float* err_bnds_norm, float* err_bnds_comp,\n                     lapack_int* nparams, float* params,\n                     lapack_complex_float* work, float* rwork,\n                     lapack_int *info );\nvoid LAPACK_sgbsv( lapack_int* n, lapack_int* kl, lapack_int* ku,\n                   lapack_int* nrhs, float* ab, lapack_int* ldab,\n                   lapack_int* ipiv, float* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_dgbsv( lapack_int* n, lapack_int* kl, lapack_int* ku,\n                   lapack_int* nrhs, double* ab, lapack_int* ldab,\n                   lapack_int* ipiv, double* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_cgbsv( lapack_int* n, lapack_int* kl, lapack_int* ku,\n                   lapack_int* nrhs, lapack_complex_float* ab, lapack_int* ldab,\n                   lapack_int* ipiv, lapack_complex_float* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_zgbsv( lapack_int* n, lapack_int* kl, lapack_int* ku,\n                   lapack_int* nrhs, lapack_complex_double* ab,\n                   lapack_int* ldab, lapack_int* ipiv, lapack_complex_double* b,\n                   lapack_int* ldb, lapack_int *info );\nvoid LAPACK_sgbsvx( char* fact, char* trans, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, lapack_int* nrhs, float* ab,\n                    lapack_int* ldab, float* afb, lapack_int* ldafb,\n                    lapack_int* ipiv, char* equed, float* r, float* c, float* b,\n                    lapack_int* ldb, float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dgbsvx( char* fact, char* trans, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, lapack_int* nrhs, double* ab,\n                    lapack_int* ldab, double* afb, lapack_int* ldafb,\n                    lapack_int* ipiv, char* equed, double* r, double* c,\n                    double* b, lapack_int* ldb, double* x, lapack_int* ldx,\n                    double* rcond, double* ferr, double* berr, double* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cgbsvx( char* fact, char* trans, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, lapack_int* nrhs, lapack_complex_float* ab,\n                    lapack_int* ldab, lapack_complex_float* afb,\n                    lapack_int* ldafb, lapack_int* ipiv, char* equed, float* r,\n                    float* c, lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zgbsvx( char* fact, char* trans, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, lapack_int* nrhs, lapack_complex_double* ab,\n                    lapack_int* ldab, lapack_complex_double* afb,\n                    lapack_int* ldafb, lapack_int* ipiv, char* equed, double* r,\n                    double* c, lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                    double* ferr, double* berr, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_dgbsvxx( char* fact, char* trans, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, lapack_int* nrhs, double* ab,\n                     lapack_int* ldab, double* afb, lapack_int* ldafb,\n                     lapack_int* ipiv, char* equed, double* r, double* c,\n                     double* b, lapack_int* ldb, double* x, lapack_int* ldx,\n                     double* rcond, double* rpvgrw, double* berr,\n                     lapack_int* n_err_bnds, double* err_bnds_norm,\n                     double* err_bnds_comp, lapack_int* nparams, double* params,\n                     double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_sgbsvxx( char* fact, char* trans, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, lapack_int* nrhs, float* ab,\n                     lapack_int* ldab, float* afb, lapack_int* ldafb,\n                     lapack_int* ipiv, char* equed, float* r, float* c,\n                     float* b, lapack_int* ldb, float* x, lapack_int* ldx,\n                     float* rcond, float* rpvgrw, float* berr,\n                     lapack_int* n_err_bnds, float* err_bnds_norm,\n                     float* err_bnds_comp, lapack_int* nparams, float* params,\n                     float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_zgbsvxx( char* fact, char* trans, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, lapack_int* nrhs,\n                     lapack_complex_double* ab, lapack_int* ldab,\n                     lapack_complex_double* afb, lapack_int* ldafb,\n                     lapack_int* ipiv, char* equed, double* r, double* c,\n                     lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                     double* rpvgrw, double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params,\n                     lapack_complex_double* work, double* rwork,\n                     lapack_int *info );\nvoid LAPACK_cgbsvxx( char* fact, char* trans, lapack_int* n, lapack_int* kl,\n                     lapack_int* ku, lapack_int* nrhs, lapack_complex_float* ab,\n                     lapack_int* ldab, lapack_complex_float* afb,\n                     lapack_int* ldafb, lapack_int* ipiv, char* equed, float* r,\n                     float* c, lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                     float* rpvgrw, float* berr, lapack_int* n_err_bnds,\n                     float* err_bnds_norm, float* err_bnds_comp,\n                     lapack_int* nparams, float* params,\n                     lapack_complex_float* work, float* rwork,\n                     lapack_int *info );\nvoid LAPACK_sgtsv( lapack_int* n, lapack_int* nrhs, float* dl, float* d,\n                   float* du, float* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dgtsv( lapack_int* n, lapack_int* nrhs, double* dl, double* d,\n                   double* du, double* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_cgtsv( lapack_int* n, lapack_int* nrhs, lapack_complex_float* dl,\n                   lapack_complex_float* d, lapack_complex_float* du,\n                   lapack_complex_float* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zgtsv( lapack_int* n, lapack_int* nrhs, lapack_complex_double* dl,\n                   lapack_complex_double* d, lapack_complex_double* du,\n                   lapack_complex_double* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_sgtsvx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                    const float* dl, const float* d, const float* du,\n                    float* dlf, float* df, float* duf, float* du2,\n                    lapack_int* ipiv, const float* b, lapack_int* ldb, float* x,\n                    lapack_int* ldx, float* rcond, float* ferr, float* berr,\n                    float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dgtsvx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                    const double* dl, const double* d, const double* du,\n                    double* dlf, double* df, double* duf, double* du2,\n                    lapack_int* ipiv, const double* b, lapack_int* ldb,\n                    double* x, lapack_int* ldx, double* rcond, double* ferr,\n                    double* berr, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_cgtsvx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* dl,\n                    const lapack_complex_float* d,\n                    const lapack_complex_float* du, lapack_complex_float* dlf,\n                    lapack_complex_float* df, lapack_complex_float* duf,\n                    lapack_complex_float* du2, lapack_int* ipiv,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zgtsvx( char* fact, char* trans, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* dl,\n                    const lapack_complex_double* d,\n                    const lapack_complex_double* du, lapack_complex_double* dlf,\n                    lapack_complex_double* df, lapack_complex_double* duf,\n                    lapack_complex_double* du2, lapack_int* ipiv,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                    double* ferr, double* berr, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_sposv( char* uplo, lapack_int* n, lapack_int* nrhs, float* a,\n                   lapack_int* lda, float* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_dposv( char* uplo, lapack_int* n, lapack_int* nrhs, double* a,\n                   lapack_int* lda, double* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_cposv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_float* a, lapack_int* lda,\n                   lapack_complex_float* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zposv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_double* a, lapack_int* lda,\n                   lapack_complex_double* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_dsposv( char* uplo, lapack_int* n, lapack_int* nrhs, double* a,\n                    lapack_int* lda, double* b, lapack_int* ldb, double* x,\n                    lapack_int* ldx, double* work, float* swork,\n                    lapack_int* iter, lapack_int *info );\nvoid LAPACK_zcposv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx,\n                    lapack_complex_double* work, lapack_complex_float* swork,\n                    double* rwork, lapack_int* iter, lapack_int *info );\nvoid LAPACK_sposvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    float* a, lapack_int* lda, float* af, lapack_int* ldaf,\n                    char* equed, float* s, float* b, lapack_int* ldb, float* x,\n                    lapack_int* ldx, float* rcond, float* ferr, float* berr,\n                    float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dposvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    double* a, lapack_int* lda, double* af, lapack_int* ldaf,\n                    char* equed, double* s, double* b, lapack_int* ldb,\n                    double* x, lapack_int* ldx, double* rcond, double* ferr,\n                    double* berr, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_cposvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* af, lapack_int* ldaf, char* equed,\n                    float* s, lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zposvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* af, lapack_int* ldaf, char* equed,\n                    double* s, lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                    double* ferr, double* berr, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_dposvxx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                     double* a, lapack_int* lda, double* af, lapack_int* ldaf,\n                     char* equed, double* s, double* b, lapack_int* ldb,\n                     double* x, lapack_int* ldx, double* rcond, double* rpvgrw,\n                     double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params, double* work,\n                     lapack_int* iwork, lapack_int *info );\nvoid LAPACK_sposvxx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                     float* a, lapack_int* lda, float* af, lapack_int* ldaf,\n                     char* equed, float* s, float* b, lapack_int* ldb, float* x,\n                     lapack_int* ldx, float* rcond, float* rpvgrw, float* berr,\n                     lapack_int* n_err_bnds, float* err_bnds_norm,\n                     float* err_bnds_comp, lapack_int* nparams, float* params,\n                     float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_zposvxx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                     lapack_complex_double* a, lapack_int* lda,\n                     lapack_complex_double* af, lapack_int* ldaf, char* equed,\n                     double* s, lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                     double* rpvgrw, double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params,\n                     lapack_complex_double* work, double* rwork,\n                     lapack_int *info );\nvoid LAPACK_cposvxx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                     lapack_complex_float* a, lapack_int* lda,\n                     lapack_complex_float* af, lapack_int* ldaf, char* equed,\n                     float* s, lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                     float* rpvgrw, float* berr, lapack_int* n_err_bnds,\n                     float* err_bnds_norm, float* err_bnds_comp,\n                     lapack_int* nparams, float* params,\n                     lapack_complex_float* work, float* rwork,\n                     lapack_int *info );\nvoid LAPACK_sppsv( char* uplo, lapack_int* n, lapack_int* nrhs, float* ap,\n                   float* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dppsv( char* uplo, lapack_int* n, lapack_int* nrhs, double* ap,\n                   double* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_cppsv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_float* ap, lapack_complex_float* b,\n                   lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zppsv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_double* ap, lapack_complex_double* b,\n                   lapack_int* ldb, lapack_int *info );\nvoid LAPACK_sppsvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    float* ap, float* afp, char* equed, float* s, float* b,\n                    lapack_int* ldb, float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dppsvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    double* ap, double* afp, char* equed, double* s, double* b,\n                    lapack_int* ldb, double* x, lapack_int* ldx, double* rcond,\n                    double* ferr, double* berr, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_cppsvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_float* ap, lapack_complex_float* afp,\n                    char* equed, float* s, lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* x, lapack_int* ldx,\n                    float* rcond, float* ferr, float* berr,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zppsvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_double* ap, lapack_complex_double* afp,\n                    char* equed, double* s, lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                    double* rcond, double* ferr, double* berr,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_spbsv( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                   float* ab, lapack_int* ldab, float* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_dpbsv( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                   double* ab, lapack_int* ldab, double* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_cpbsv( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                   lapack_complex_float* ab, lapack_int* ldab,\n                   lapack_complex_float* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zpbsv( char* uplo, lapack_int* n, lapack_int* kd, lapack_int* nrhs,\n                   lapack_complex_double* ab, lapack_int* ldab,\n                   lapack_complex_double* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_spbsvx( char* fact, char* uplo, lapack_int* n, lapack_int* kd,\n                    lapack_int* nrhs, float* ab, lapack_int* ldab, float* afb,\n                    lapack_int* ldafb, char* equed, float* s, float* b,\n                    lapack_int* ldb, float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dpbsvx( char* fact, char* uplo, lapack_int* n, lapack_int* kd,\n                    lapack_int* nrhs, double* ab, lapack_int* ldab, double* afb,\n                    lapack_int* ldafb, char* equed, double* s, double* b,\n                    lapack_int* ldb, double* x, lapack_int* ldx, double* rcond,\n                    double* ferr, double* berr, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_cpbsvx( char* fact, char* uplo, lapack_int* n, lapack_int* kd,\n                    lapack_int* nrhs, lapack_complex_float* ab,\n                    lapack_int* ldab, lapack_complex_float* afb,\n                    lapack_int* ldafb, char* equed, float* s,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zpbsvx( char* fact, char* uplo, lapack_int* n, lapack_int* kd,\n                    lapack_int* nrhs, lapack_complex_double* ab,\n                    lapack_int* ldab, lapack_complex_double* afb,\n                    lapack_int* ldafb, char* equed, double* s,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                    double* ferr, double* berr, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_sptsv( lapack_int* n, lapack_int* nrhs, float* d, float* e,\n                   float* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_dptsv( lapack_int* n, lapack_int* nrhs, double* d, double* e,\n                   double* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_cptsv( lapack_int* n, lapack_int* nrhs, float* d,\n                   lapack_complex_float* e, lapack_complex_float* b,\n                   lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zptsv( lapack_int* n, lapack_int* nrhs, double* d,\n                   lapack_complex_double* e, lapack_complex_double* b,\n                   lapack_int* ldb, lapack_int *info );\nvoid LAPACK_sptsvx( char* fact, lapack_int* n, lapack_int* nrhs, const float* d,\n                    const float* e, float* df, float* ef, const float* b,\n                    lapack_int* ldb, float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, float* work, lapack_int *info );\nvoid LAPACK_dptsvx( char* fact, lapack_int* n, lapack_int* nrhs,\n                    const double* d, const double* e, double* df, double* ef,\n                    const double* b, lapack_int* ldb, double* x,\n                    lapack_int* ldx, double* rcond, double* ferr, double* berr,\n                    double* work, lapack_int *info );\nvoid LAPACK_cptsvx( char* fact, lapack_int* n, lapack_int* nrhs, const float* d,\n                    const lapack_complex_float* e, float* df,\n                    lapack_complex_float* ef, const lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* x, lapack_int* ldx,\n                    float* rcond, float* ferr, float* berr,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zptsvx( char* fact, lapack_int* n, lapack_int* nrhs,\n                    const double* d, const lapack_complex_double* e, double* df,\n                    lapack_complex_double* ef, const lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                    double* rcond, double* ferr, double* berr,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_ssysv( char* uplo, lapack_int* n, lapack_int* nrhs, float* a,\n                   lapack_int* lda, lapack_int* ipiv, float* b, lapack_int* ldb,\n                   float* work, lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dsysv( char* uplo, lapack_int* n, lapack_int* nrhs, double* a,\n                   lapack_int* lda, lapack_int* ipiv, double* b,\n                   lapack_int* ldb, double* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_csysv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_float* a, lapack_int* lda, lapack_int* ipiv,\n                   lapack_complex_float* b, lapack_int* ldb,\n                   lapack_complex_float* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_zsysv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_double* a, lapack_int* lda, lapack_int* ipiv,\n                   lapack_complex_double* b, lapack_int* ldb,\n                   lapack_complex_double* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_ssysvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const float* a, lapack_int* lda, float* af,\n                    lapack_int* ldaf, lapack_int* ipiv, const float* b,\n                    lapack_int* ldb, float* x, lapack_int* ldx, float* rcond,\n                    float* ferr, float* berr, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dsysvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* a, lapack_int* lda, double* af,\n                    lapack_int* ldaf, lapack_int* ipiv, const double* b,\n                    lapack_int* ldb, double* x, lapack_int* ldx, double* rcond,\n                    double* ferr, double* berr, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_csysvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* af, lapack_int* ldaf,\n                    lapack_int* ipiv, const lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* x, lapack_int* ldx,\n                    float* rcond, float* ferr, float* berr,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zsysvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* af, lapack_int* ldaf,\n                    lapack_int* ipiv, const lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                    double* rcond, double* ferr, double* berr,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_dsysvxx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                     double* a, lapack_int* lda, double* af, lapack_int* ldaf,\n                     lapack_int* ipiv, char* equed, double* s, double* b,\n                     lapack_int* ldb, double* x, lapack_int* ldx, double* rcond,\n                     double* rpvgrw, double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params, double* work,\n                     lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ssysvxx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                     float* a, lapack_int* lda, float* af, lapack_int* ldaf,\n                     lapack_int* ipiv, char* equed, float* s, float* b,\n                     lapack_int* ldb, float* x, lapack_int* ldx, float* rcond,\n                     float* rpvgrw, float* berr, lapack_int* n_err_bnds,\n                     float* err_bnds_norm, float* err_bnds_comp,\n                     lapack_int* nparams, float* params, float* work,\n                     lapack_int* iwork, lapack_int *info );\nvoid LAPACK_zsysvxx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                     lapack_complex_double* a, lapack_int* lda,\n                     lapack_complex_double* af, lapack_int* ldaf,\n                     lapack_int* ipiv, char* equed, double* s,\n                     lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                     double* rpvgrw, double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params,\n                     lapack_complex_double* work, double* rwork,\n                     lapack_int *info );\nvoid LAPACK_csysvxx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                     lapack_complex_float* a, lapack_int* lda,\n                     lapack_complex_float* af, lapack_int* ldaf,\n                     lapack_int* ipiv, char* equed, float* s,\n                     lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                     float* rpvgrw, float* berr, lapack_int* n_err_bnds,\n                     float* err_bnds_norm, float* err_bnds_comp,\n                     lapack_int* nparams, float* params,\n                     lapack_complex_float* work, float* rwork,\n                     lapack_int *info );\nvoid LAPACK_chesv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_float* a, lapack_int* lda, lapack_int* ipiv,\n                   lapack_complex_float* b, lapack_int* ldb,\n                   lapack_complex_float* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_zhesv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_double* a, lapack_int* lda, lapack_int* ipiv,\n                   lapack_complex_double* b, lapack_int* ldb,\n                   lapack_complex_double* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_chesvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* af, lapack_int* ldaf,\n                    lapack_int* ipiv, const lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* x, lapack_int* ldx,\n                    float* rcond, float* ferr, float* berr,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zhesvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* af, lapack_int* ldaf,\n                    lapack_int* ipiv, const lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                    double* rcond, double* ferr, double* berr,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_zhesvxx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                     lapack_complex_double* a, lapack_int* lda,\n                     lapack_complex_double* af, lapack_int* ldaf,\n                     lapack_int* ipiv, char* equed, double* s,\n                     lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* x, lapack_int* ldx, double* rcond,\n                     double* rpvgrw, double* berr, lapack_int* n_err_bnds,\n                     double* err_bnds_norm, double* err_bnds_comp,\n                     lapack_int* nparams, double* params,\n                     lapack_complex_double* work, double* rwork,\n                     lapack_int *info );\nvoid LAPACK_chesvxx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                     lapack_complex_float* a, lapack_int* lda,\n                     lapack_complex_float* af, lapack_int* ldaf,\n                     lapack_int* ipiv, char* equed, float* s,\n                     lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* x, lapack_int* ldx, float* rcond,\n                     float* rpvgrw, float* berr, lapack_int* n_err_bnds,\n                     float* err_bnds_norm, float* err_bnds_comp,\n                     lapack_int* nparams, float* params,\n                     lapack_complex_float* work, float* rwork,\n                     lapack_int *info );\nvoid LAPACK_sspsv( char* uplo, lapack_int* n, lapack_int* nrhs, float* ap,\n                   lapack_int* ipiv, float* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_dspsv( char* uplo, lapack_int* n, lapack_int* nrhs, double* ap,\n                   lapack_int* ipiv, double* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_cspsv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_float* ap, lapack_int* ipiv,\n                   lapack_complex_float* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zspsv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_double* ap, lapack_int* ipiv,\n                   lapack_complex_double* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_sspsvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const float* ap, float* afp, lapack_int* ipiv,\n                    const float* b, lapack_int* ldb, float* x, lapack_int* ldx,\n                    float* rcond, float* ferr, float* berr, float* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dspsvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const double* ap, double* afp, lapack_int* ipiv,\n                    const double* b, lapack_int* ldb, double* x,\n                    lapack_int* ldx, double* rcond, double* ferr, double* berr,\n                    double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cspsvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* ap, lapack_complex_float* afp,\n                    lapack_int* ipiv, const lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* x, lapack_int* ldx,\n                    float* rcond, float* ferr, float* berr,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zspsvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* ap, lapack_complex_double* afp,\n                    lapack_int* ipiv, const lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                    double* rcond, double* ferr, double* berr,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_chpsv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_float* ap, lapack_int* ipiv,\n                   lapack_complex_float* b, lapack_int* ldb, lapack_int *info );\nvoid LAPACK_zhpsv( char* uplo, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_double* ap, lapack_int* ipiv,\n                   lapack_complex_double* b, lapack_int* ldb,\n                   lapack_int *info );\nvoid LAPACK_chpsvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_float* ap, lapack_complex_float* afp,\n                    lapack_int* ipiv, const lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* x, lapack_int* ldx,\n                    float* rcond, float* ferr, float* berr,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zhpsvx( char* fact, char* uplo, lapack_int* n, lapack_int* nrhs,\n                    const lapack_complex_double* ap, lapack_complex_double* afp,\n                    lapack_int* ipiv, const lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* x, lapack_int* ldx,\n                    double* rcond, double* ferr, double* berr,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_sgeqrf( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    float* tau, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dgeqrf( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    double* tau, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cgeqrf( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* tau,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zgeqrf( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sgeqpf( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int* jpvt, float* tau, float* work,\n                    lapack_int *info );\nvoid LAPACK_dgeqpf( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int* jpvt, double* tau, double* work,\n                    lapack_int *info );\nvoid LAPACK_cgeqpf( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int* jpvt,\n                    lapack_complex_float* tau, lapack_complex_float* work,\n                    float* rwork, lapack_int *info );\nvoid LAPACK_zgeqpf( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* jpvt,\n                    lapack_complex_double* tau, lapack_complex_double* work,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_sgeqp3( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int* jpvt, float* tau, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dgeqp3( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int* jpvt, double* tau, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cgeqp3( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int* jpvt,\n                    lapack_complex_float* tau, lapack_complex_float* work,\n                    lapack_int* lwork, float* rwork, lapack_int *info );\nvoid LAPACK_zgeqp3( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* jpvt,\n                    lapack_complex_double* tau, lapack_complex_double* work,\n                    lapack_int* lwork, double* rwork, lapack_int *info );\nvoid LAPACK_sorgqr( lapack_int* m, lapack_int* n, lapack_int* k, float* a,\n                    lapack_int* lda, const float* tau, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dorgqr( lapack_int* m, lapack_int* n, lapack_int* k, double* a,\n                    lapack_int* lda, const double* tau, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sormqr( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const float* a, lapack_int* lda,\n                    const float* tau, float* c, lapack_int* ldc, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dormqr( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const double* a, lapack_int* lda,\n                    const double* tau, double* c, lapack_int* ldc, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cungqr( lapack_int* m, lapack_int* n, lapack_int* k,\n                    lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* tau, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zungqr( lapack_int* m, lapack_int* n, lapack_int* k,\n                    lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cunmqr( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* tau,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zunmqr( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const lapack_complex_double* a,\n                    lapack_int* lda, const lapack_complex_double* tau,\n                    lapack_complex_double* c, lapack_int* ldc,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sgelqf( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    float* tau, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dgelqf( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    double* tau, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cgelqf( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* tau,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zgelqf( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sorglq( lapack_int* m, lapack_int* n, lapack_int* k, float* a,\n                    lapack_int* lda, const float* tau, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dorglq( lapack_int* m, lapack_int* n, lapack_int* k, double* a,\n                    lapack_int* lda, const double* tau, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sormlq( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const float* a, lapack_int* lda,\n                    const float* tau, float* c, lapack_int* ldc, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dormlq( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const double* a, lapack_int* lda,\n                    const double* tau, double* c, lapack_int* ldc, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cunglq( lapack_int* m, lapack_int* n, lapack_int* k,\n                    lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* tau, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zunglq( lapack_int* m, lapack_int* n, lapack_int* k,\n                    lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cunmlq( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* tau,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zunmlq( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const lapack_complex_double* a,\n                    lapack_int* lda, const lapack_complex_double* tau,\n                    lapack_complex_double* c, lapack_int* ldc,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sgeqlf( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    float* tau, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dgeqlf( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    double* tau, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cgeqlf( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* tau,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zgeqlf( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sorgql( lapack_int* m, lapack_int* n, lapack_int* k, float* a,\n                    lapack_int* lda, const float* tau, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dorgql( lapack_int* m, lapack_int* n, lapack_int* k, double* a,\n                    lapack_int* lda, const double* tau, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cungql( lapack_int* m, lapack_int* n, lapack_int* k,\n                    lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* tau, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zungql( lapack_int* m, lapack_int* n, lapack_int* k,\n                    lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sormql( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const float* a, lapack_int* lda,\n                    const float* tau, float* c, lapack_int* ldc, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dormql( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const double* a, lapack_int* lda,\n                    const double* tau, double* c, lapack_int* ldc, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cunmql( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* tau,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zunmql( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const lapack_complex_double* a,\n                    lapack_int* lda, const lapack_complex_double* tau,\n                    lapack_complex_double* c, lapack_int* ldc,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sgerqf( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    float* tau, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dgerqf( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    double* tau, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cgerqf( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* tau,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zgerqf( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sorgrq( lapack_int* m, lapack_int* n, lapack_int* k, float* a,\n                    lapack_int* lda, const float* tau, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dorgrq( lapack_int* m, lapack_int* n, lapack_int* k, double* a,\n                    lapack_int* lda, const double* tau, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cungrq( lapack_int* m, lapack_int* n, lapack_int* k,\n                    lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* tau, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zungrq( lapack_int* m, lapack_int* n, lapack_int* k,\n                    lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sormrq( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const float* a, lapack_int* lda,\n                    const float* tau, float* c, lapack_int* ldc, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dormrq( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const double* a, lapack_int* lda,\n                    const double* tau, double* c, lapack_int* ldc, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cunmrq( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* tau,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zunmrq( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, const lapack_complex_double* a,\n                    lapack_int* lda, const lapack_complex_double* tau,\n                    lapack_complex_double* c, lapack_int* ldc,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_stzrzf( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    float* tau, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dtzrzf( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    double* tau, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_ctzrzf( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* tau,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_ztzrzf( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sormrz( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, lapack_int* l, const float* a,\n                    lapack_int* lda, const float* tau, float* c,\n                    lapack_int* ldc, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dormrz( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, lapack_int* l, const double* a,\n                    lapack_int* lda, const double* tau, double* c,\n                    lapack_int* ldc, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cunmrz( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, lapack_int* l, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* tau,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zunmrz( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* k, lapack_int* l,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* tau, lapack_complex_double* c,\n                    lapack_int* ldc, lapack_complex_double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sggqrf( lapack_int* n, lapack_int* m, lapack_int* p, float* a,\n                    lapack_int* lda, float* taua, float* b, lapack_int* ldb,\n                    float* taub, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dggqrf( lapack_int* n, lapack_int* m, lapack_int* p, double* a,\n                    lapack_int* lda, double* taua, double* b, lapack_int* ldb,\n                    double* taub, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cggqrf( lapack_int* n, lapack_int* m, lapack_int* p,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* taua, lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* taub,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zggqrf( lapack_int* n, lapack_int* m, lapack_int* p,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* taua, lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* taub,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sggrqf( lapack_int* m, lapack_int* p, lapack_int* n, float* a,\n                    lapack_int* lda, float* taua, float* b, lapack_int* ldb,\n                    float* taub, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dggrqf( lapack_int* m, lapack_int* p, lapack_int* n, double* a,\n                    lapack_int* lda, double* taua, double* b, lapack_int* ldb,\n                    double* taub, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cggrqf( lapack_int* m, lapack_int* p, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* taua, lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* taub,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zggrqf( lapack_int* m, lapack_int* p, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* taua, lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* taub,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sgebrd( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    float* d, float* e, float* tauq, float* taup, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dgebrd( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    double* d, double* e, double* tauq, double* taup,\n                    double* work, lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cgebrd( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, float* d, float* e,\n                    lapack_complex_float* tauq, lapack_complex_float* taup,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zgebrd( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, double* d, double* e,\n                    lapack_complex_double* tauq, lapack_complex_double* taup,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sgbbrd( char* vect, lapack_int* m, lapack_int* n, lapack_int* ncc,\n                    lapack_int* kl, lapack_int* ku, float* ab, lapack_int* ldab,\n                    float* d, float* e, float* q, lapack_int* ldq, float* pt,\n                    lapack_int* ldpt, float* c, lapack_int* ldc, float* work,\n                    lapack_int *info );\nvoid LAPACK_dgbbrd( char* vect, lapack_int* m, lapack_int* n, lapack_int* ncc,\n                    lapack_int* kl, lapack_int* ku, double* ab,\n                    lapack_int* ldab, double* d, double* e, double* q,\n                    lapack_int* ldq, double* pt, lapack_int* ldpt, double* c,\n                    lapack_int* ldc, double* work, lapack_int *info );\nvoid LAPACK_cgbbrd( char* vect, lapack_int* m, lapack_int* n, lapack_int* ncc,\n                    lapack_int* kl, lapack_int* ku, lapack_complex_float* ab,\n                    lapack_int* ldab, float* d, float* e,\n                    lapack_complex_float* q, lapack_int* ldq,\n                    lapack_complex_float* pt, lapack_int* ldpt,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zgbbrd( char* vect, lapack_int* m, lapack_int* n, lapack_int* ncc,\n                    lapack_int* kl, lapack_int* ku, lapack_complex_double* ab,\n                    lapack_int* ldab, double* d, double* e,\n                    lapack_complex_double* q, lapack_int* ldq,\n                    lapack_complex_double* pt, lapack_int* ldpt,\n                    lapack_complex_double* c, lapack_int* ldc,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_sorgbr( char* vect, lapack_int* m, lapack_int* n, lapack_int* k,\n                    float* a, lapack_int* lda, const float* tau, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dorgbr( char* vect, lapack_int* m, lapack_int* n, lapack_int* k,\n                    double* a, lapack_int* lda, const double* tau, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sormbr( char* vect, char* side, char* trans, lapack_int* m,\n                    lapack_int* n, lapack_int* k, const float* a,\n                    lapack_int* lda, const float* tau, float* c,\n                    lapack_int* ldc, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dormbr( char* vect, char* side, char* trans, lapack_int* m,\n                    lapack_int* n, lapack_int* k, const double* a,\n                    lapack_int* lda, const double* tau, double* c,\n                    lapack_int* ldc, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cungbr( char* vect, lapack_int* m, lapack_int* n, lapack_int* k,\n                    lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* tau, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zungbr( char* vect, lapack_int* m, lapack_int* n, lapack_int* k,\n                    lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cunmbr( char* vect, char* side, char* trans, lapack_int* m,\n                    lapack_int* n, lapack_int* k, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* tau,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zunmbr( char* vect, char* side, char* trans, lapack_int* m,\n                    lapack_int* n, lapack_int* k,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* tau, lapack_complex_double* c,\n                    lapack_int* ldc, lapack_complex_double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sbdsqr( char* uplo, lapack_int* n, lapack_int* ncvt,\n                    lapack_int* nru, lapack_int* ncc, float* d, float* e,\n                    float* vt, lapack_int* ldvt, float* u, lapack_int* ldu,\n                    float* c, lapack_int* ldc, float* work, lapack_int *info );\nvoid LAPACK_dbdsqr( char* uplo, lapack_int* n, lapack_int* ncvt,\n                    lapack_int* nru, lapack_int* ncc, double* d, double* e,\n                    double* vt, lapack_int* ldvt, double* u, lapack_int* ldu,\n                    double* c, lapack_int* ldc, double* work,\n                    lapack_int *info );\nvoid LAPACK_cbdsqr( char* uplo, lapack_int* n, lapack_int* ncvt,\n                    lapack_int* nru, lapack_int* ncc, float* d, float* e,\n                    lapack_complex_float* vt, lapack_int* ldvt,\n                    lapack_complex_float* u, lapack_int* ldu,\n                    lapack_complex_float* c, lapack_int* ldc, float* work,\n                    lapack_int *info );\nvoid LAPACK_zbdsqr( char* uplo, lapack_int* n, lapack_int* ncvt,\n                    lapack_int* nru, lapack_int* ncc, double* d, double* e,\n                    lapack_complex_double* vt, lapack_int* ldvt,\n                    lapack_complex_double* u, lapack_int* ldu,\n                    lapack_complex_double* c, lapack_int* ldc, double* work,\n                    lapack_int *info );\nvoid LAPACK_sbdsdc( char* uplo, char* compq, lapack_int* n, float* d, float* e,\n                    float* u, lapack_int* ldu, float* vt, lapack_int* ldvt,\n                    float* q, lapack_int* iq, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dbdsdc( char* uplo, char* compq, lapack_int* n, double* d,\n                    double* e, double* u, lapack_int* ldu, double* vt,\n                    lapack_int* ldvt, double* q, lapack_int* iq, double* work,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ssytrd( char* uplo, lapack_int* n, float* a, lapack_int* lda,\n                    float* d, float* e, float* tau, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dsytrd( char* uplo, lapack_int* n, double* a, lapack_int* lda,\n                    double* d, double* e, double* tau, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sorgtr( char* uplo, lapack_int* n, float* a, lapack_int* lda,\n                    const float* tau, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dorgtr( char* uplo, lapack_int* n, double* a, lapack_int* lda,\n                    const double* tau, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_sormtr( char* side, char* uplo, char* trans, lapack_int* m,\n                    lapack_int* n, const float* a, lapack_int* lda,\n                    const float* tau, float* c, lapack_int* ldc, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dormtr( char* side, char* uplo, char* trans, lapack_int* m,\n                    lapack_int* n, const double* a, lapack_int* lda,\n                    const double* tau, double* c, lapack_int* ldc, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_chetrd( char* uplo, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, float* d, float* e,\n                    lapack_complex_float* tau, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zhetrd( char* uplo, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, double* d, double* e,\n                    lapack_complex_double* tau, lapack_complex_double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cungtr( char* uplo, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* tau,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zungtr( char* uplo, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, const lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cunmtr( char* side, char* uplo, char* trans, lapack_int* m,\n                    lapack_int* n, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* tau,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_zunmtr( char* side, char* uplo, char* trans, lapack_int* m,\n                    lapack_int* n, const lapack_complex_double* a,\n                    lapack_int* lda, const lapack_complex_double* tau,\n                    lapack_complex_double* c, lapack_int* ldc,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_ssptrd( char* uplo, lapack_int* n, float* ap, float* d, float* e,\n                    float* tau, lapack_int *info );\nvoid LAPACK_dsptrd( char* uplo, lapack_int* n, double* ap, double* d, double* e,\n                    double* tau, lapack_int *info );\nvoid LAPACK_sopgtr( char* uplo, lapack_int* n, const float* ap,\n                    const float* tau, float* q, lapack_int* ldq, float* work,\n                    lapack_int *info );\nvoid LAPACK_dopgtr( char* uplo, lapack_int* n, const double* ap,\n                    const double* tau, double* q, lapack_int* ldq, double* work,\n                    lapack_int *info );\nvoid LAPACK_sopmtr( char* side, char* uplo, char* trans, lapack_int* m,\n                    lapack_int* n, const float* ap, const float* tau, float* c,\n                    lapack_int* ldc, float* work, lapack_int *info );\nvoid LAPACK_dopmtr( char* side, char* uplo, char* trans, lapack_int* m,\n                    lapack_int* n, const double* ap, const double* tau,\n                    double* c, lapack_int* ldc, double* work,\n                    lapack_int *info );\nvoid LAPACK_chptrd( char* uplo, lapack_int* n, lapack_complex_float* ap,\n                    float* d, float* e, lapack_complex_float* tau,\n                    lapack_int *info );\nvoid LAPACK_zhptrd( char* uplo, lapack_int* n, lapack_complex_double* ap,\n                    double* d, double* e, lapack_complex_double* tau,\n                    lapack_int *info );\nvoid LAPACK_cupgtr( char* uplo, lapack_int* n, const lapack_complex_float* ap,\n                    const lapack_complex_float* tau, lapack_complex_float* q,\n                    lapack_int* ldq, lapack_complex_float* work,\n                    lapack_int *info );\nvoid LAPACK_zupgtr( char* uplo, lapack_int* n, const lapack_complex_double* ap,\n                    const lapack_complex_double* tau, lapack_complex_double* q,\n                    lapack_int* ldq, lapack_complex_double* work,\n                    lapack_int *info );\nvoid LAPACK_cupmtr( char* side, char* uplo, char* trans, lapack_int* m,\n                    lapack_int* n, const lapack_complex_float* ap,\n                    const lapack_complex_float* tau, lapack_complex_float* c,\n                    lapack_int* ldc, lapack_complex_float* work,\n                    lapack_int *info );\nvoid LAPACK_zupmtr( char* side, char* uplo, char* trans, lapack_int* m,\n                    lapack_int* n, const lapack_complex_double* ap,\n                    const lapack_complex_double* tau, lapack_complex_double* c,\n                    lapack_int* ldc, lapack_complex_double* work,\n                    lapack_int *info );\nvoid LAPACK_ssbtrd( char* vect, char* uplo, lapack_int* n, lapack_int* kd,\n                    float* ab, lapack_int* ldab, float* d, float* e, float* q,\n                    lapack_int* ldq, float* work, lapack_int *info );\nvoid LAPACK_dsbtrd( char* vect, char* uplo, lapack_int* n, lapack_int* kd,\n                    double* ab, lapack_int* ldab, double* d, double* e,\n                    double* q, lapack_int* ldq, double* work,\n                    lapack_int *info );\nvoid LAPACK_chbtrd( char* vect, char* uplo, lapack_int* n, lapack_int* kd,\n                    lapack_complex_float* ab, lapack_int* ldab, float* d,\n                    float* e, lapack_complex_float* q, lapack_int* ldq,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zhbtrd( char* vect, char* uplo, lapack_int* n, lapack_int* kd,\n                    lapack_complex_double* ab, lapack_int* ldab, double* d,\n                    double* e, lapack_complex_double* q, lapack_int* ldq,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_ssterf( lapack_int* n, float* d, float* e, lapack_int *info );\nvoid LAPACK_dsterf( lapack_int* n, double* d, double* e, lapack_int *info );\nvoid LAPACK_ssteqr( char* compz, lapack_int* n, float* d, float* e, float* z,\n                    lapack_int* ldz, float* work, lapack_int *info );\nvoid LAPACK_dsteqr( char* compz, lapack_int* n, double* d, double* e, double* z,\n                    lapack_int* ldz, double* work, lapack_int *info );\nvoid LAPACK_csteqr( char* compz, lapack_int* n, float* d, float* e,\n                    lapack_complex_float* z, lapack_int* ldz, float* work,\n                    lapack_int *info );\nvoid LAPACK_zsteqr( char* compz, lapack_int* n, double* d, double* e,\n                    lapack_complex_double* z, lapack_int* ldz, double* work,\n                    lapack_int *info );\nvoid LAPACK_sstemr( char* jobz, char* range, lapack_int* n, float* d, float* e,\n                    float* vl, float* vu, lapack_int* il, lapack_int* iu,\n                    lapack_int* m, float* w, float* z, lapack_int* ldz,\n                    lapack_int* nzc, lapack_int* isuppz, lapack_logical* tryrac,\n                    float* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dstemr( char* jobz, char* range, lapack_int* n, double* d,\n                    double* e, double* vl, double* vu, lapack_int* il,\n                    lapack_int* iu, lapack_int* m, double* w, double* z,\n                    lapack_int* ldz, lapack_int* nzc, lapack_int* isuppz,\n                    lapack_logical* tryrac, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_cstemr( char* jobz, char* range, lapack_int* n, float* d, float* e,\n                    float* vl, float* vu, lapack_int* il, lapack_int* iu,\n                    lapack_int* m, float* w, lapack_complex_float* z,\n                    lapack_int* ldz, lapack_int* nzc, lapack_int* isuppz,\n                    lapack_logical* tryrac, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_zstemr( char* jobz, char* range, lapack_int* n, double* d,\n                    double* e, double* vl, double* vu, lapack_int* il,\n                    lapack_int* iu, lapack_int* m, double* w,\n                    lapack_complex_double* z, lapack_int* ldz, lapack_int* nzc,\n                    lapack_int* isuppz, lapack_logical* tryrac, double* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_sstedc( char* compz, lapack_int* n, float* d, float* e, float* z,\n                    lapack_int* ldz, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dstedc( char* compz, lapack_int* n, double* d, double* e, double* z,\n                    lapack_int* ldz, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_cstedc( char* compz, lapack_int* n, float* d, float* e,\n                    lapack_complex_float* z, lapack_int* ldz,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int* lrwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_zstedc( char* compz, lapack_int* n, double* d, double* e,\n                    lapack_complex_double* z, lapack_int* ldz,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* lrwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_sstegr( char* jobz, char* range, lapack_int* n, float* d, float* e,\n                    float* vl, float* vu, lapack_int* il, lapack_int* iu,\n                    float* abstol, lapack_int* m, float* w, float* z,\n                    lapack_int* ldz, lapack_int* isuppz, float* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_dstegr( char* jobz, char* range, lapack_int* n, double* d,\n                    double* e, double* vl, double* vu, lapack_int* il,\n                    lapack_int* iu, double* abstol, lapack_int* m, double* w,\n                    double* z, lapack_int* ldz, lapack_int* isuppz,\n                    double* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_cstegr( char* jobz, char* range, lapack_int* n, float* d, float* e,\n                    float* vl, float* vu, lapack_int* il, lapack_int* iu,\n                    float* abstol, lapack_int* m, float* w,\n                    lapack_complex_float* z, lapack_int* ldz,\n                    lapack_int* isuppz, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_zstegr( char* jobz, char* range, lapack_int* n, double* d,\n                    double* e, double* vl, double* vu, lapack_int* il,\n                    lapack_int* iu, double* abstol, lapack_int* m, double* w,\n                    lapack_complex_double* z, lapack_int* ldz,\n                    lapack_int* isuppz, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_spteqr( char* compz, lapack_int* n, float* d, float* e, float* z,\n                    lapack_int* ldz, float* work, lapack_int *info );\nvoid LAPACK_dpteqr( char* compz, lapack_int* n, double* d, double* e, double* z,\n                    lapack_int* ldz, double* work, lapack_int *info );\nvoid LAPACK_cpteqr( char* compz, lapack_int* n, float* d, float* e,\n                    lapack_complex_float* z, lapack_int* ldz, float* work,\n                    lapack_int *info );\nvoid LAPACK_zpteqr( char* compz, lapack_int* n, double* d, double* e,\n                    lapack_complex_double* z, lapack_int* ldz, double* work,\n                    lapack_int *info );\nvoid LAPACK_sstebz( char* range, char* order, lapack_int* n, float* vl,\n                    float* vu, lapack_int* il, lapack_int* iu, float* abstol,\n                    const float* d, const float* e, lapack_int* m,\n                    lapack_int* nsplit, float* w, lapack_int* iblock,\n                    lapack_int* isplit, float* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dstebz( char* range, char* order, lapack_int* n, double* vl,\n                    double* vu, lapack_int* il, lapack_int* iu, double* abstol,\n                    const double* d, const double* e, lapack_int* m,\n                    lapack_int* nsplit, double* w, lapack_int* iblock,\n                    lapack_int* isplit, double* work, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_sstein( lapack_int* n, const float* d, const float* e,\n                    lapack_int* m, const float* w, const lapack_int* iblock,\n                    const lapack_int* isplit, float* z, lapack_int* ldz,\n                    float* work, lapack_int* iwork, lapack_int* ifailv,\n                    lapack_int *info );\nvoid LAPACK_dstein( lapack_int* n, const double* d, const double* e,\n                    lapack_int* m, const double* w, const lapack_int* iblock,\n                    const lapack_int* isplit, double* z, lapack_int* ldz,\n                    double* work, lapack_int* iwork, lapack_int* ifailv,\n                    lapack_int *info );\nvoid LAPACK_cstein( lapack_int* n, const float* d, const float* e,\n                    lapack_int* m, const float* w, const lapack_int* iblock,\n                    const lapack_int* isplit, lapack_complex_float* z,\n                    lapack_int* ldz, float* work, lapack_int* iwork,\n                    lapack_int* ifailv, lapack_int *info );\nvoid LAPACK_zstein( lapack_int* n, const double* d, const double* e,\n                    lapack_int* m, const double* w, const lapack_int* iblock,\n                    const lapack_int* isplit, lapack_complex_double* z,\n                    lapack_int* ldz, double* work, lapack_int* iwork,\n                    lapack_int* ifailv, lapack_int *info );\nvoid LAPACK_sdisna( char* job, lapack_int* m, lapack_int* n, const float* d,\n                    float* sep, lapack_int *info );\nvoid LAPACK_ddisna( char* job, lapack_int* m, lapack_int* n, const double* d,\n                    double* sep, lapack_int *info );\nvoid LAPACK_ssygst( lapack_int* itype, char* uplo, lapack_int* n, float* a,\n                    lapack_int* lda, const float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_dsygst( lapack_int* itype, char* uplo, lapack_int* n, double* a,\n                    lapack_int* lda, const double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_chegst( lapack_int* itype, char* uplo, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_zhegst( lapack_int* itype, char* uplo, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int *info );\nvoid LAPACK_sspgst( lapack_int* itype, char* uplo, lapack_int* n, float* ap,\n                    const float* bp, lapack_int *info );\nvoid LAPACK_dspgst( lapack_int* itype, char* uplo, lapack_int* n, double* ap,\n                    const double* bp, lapack_int *info );\nvoid LAPACK_chpgst( lapack_int* itype, char* uplo, lapack_int* n,\n                    lapack_complex_float* ap, const lapack_complex_float* bp,\n                    lapack_int *info );\nvoid LAPACK_zhpgst( lapack_int* itype, char* uplo, lapack_int* n,\n                    lapack_complex_double* ap, const lapack_complex_double* bp,\n                    lapack_int *info );\nvoid LAPACK_ssbgst( char* vect, char* uplo, lapack_int* n, lapack_int* ka,\n                    lapack_int* kb, float* ab, lapack_int* ldab,\n                    const float* bb, lapack_int* ldbb, float* x,\n                    lapack_int* ldx, float* work, lapack_int *info );\nvoid LAPACK_dsbgst( char* vect, char* uplo, lapack_int* n, lapack_int* ka,\n                    lapack_int* kb, double* ab, lapack_int* ldab,\n                    const double* bb, lapack_int* ldbb, double* x,\n                    lapack_int* ldx, double* work, lapack_int *info );\nvoid LAPACK_chbgst( char* vect, char* uplo, lapack_int* n, lapack_int* ka,\n                    lapack_int* kb, lapack_complex_float* ab, lapack_int* ldab,\n                    const lapack_complex_float* bb, lapack_int* ldbb,\n                    lapack_complex_float* x, lapack_int* ldx,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zhbgst( char* vect, char* uplo, lapack_int* n, lapack_int* ka,\n                    lapack_int* kb, lapack_complex_double* ab, lapack_int* ldab,\n                    const lapack_complex_double* bb, lapack_int* ldbb,\n                    lapack_complex_double* x, lapack_int* ldx,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_spbstf( char* uplo, lapack_int* n, lapack_int* kb, float* bb,\n                    lapack_int* ldbb, lapack_int *info );\nvoid LAPACK_dpbstf( char* uplo, lapack_int* n, lapack_int* kb, double* bb,\n                    lapack_int* ldbb, lapack_int *info );\nvoid LAPACK_cpbstf( char* uplo, lapack_int* n, lapack_int* kb,\n                    lapack_complex_float* bb, lapack_int* ldbb,\n                    lapack_int *info );\nvoid LAPACK_zpbstf( char* uplo, lapack_int* n, lapack_int* kb,\n                    lapack_complex_double* bb, lapack_int* ldbb,\n                    lapack_int *info );\nvoid LAPACK_sgehrd( lapack_int* n, lapack_int* ilo, lapack_int* ihi, float* a,\n                    lapack_int* lda, float* tau, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dgehrd( lapack_int* n, lapack_int* ilo, lapack_int* ihi, double* a,\n                    lapack_int* lda, double* tau, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cgehrd( lapack_int* n, lapack_int* ilo, lapack_int* ihi,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* tau, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zgehrd( lapack_int* n, lapack_int* ilo, lapack_int* ihi,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* tau, lapack_complex_double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sorghr( lapack_int* n, lapack_int* ilo, lapack_int* ihi, float* a,\n                    lapack_int* lda, const float* tau, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dorghr( lapack_int* n, lapack_int* ilo, lapack_int* ihi, double* a,\n                    lapack_int* lda, const double* tau, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sormhr( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* ilo, lapack_int* ihi, const float* a,\n                    lapack_int* lda, const float* tau, float* c,\n                    lapack_int* ldc, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dormhr( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* ilo, lapack_int* ihi, const double* a,\n                    lapack_int* lda, const double* tau, double* c,\n                    lapack_int* ldc, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cunghr( lapack_int* n, lapack_int* ilo, lapack_int* ihi,\n                    lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* tau, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zunghr( lapack_int* n, lapack_int* ilo, lapack_int* ihi,\n                    lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cunmhr( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* ilo, lapack_int* ihi,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* tau, lapack_complex_float* c,\n                    lapack_int* ldc, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zunmhr( char* side, char* trans, lapack_int* m, lapack_int* n,\n                    lapack_int* ilo, lapack_int* ihi,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* tau, lapack_complex_double* c,\n                    lapack_int* ldc, lapack_complex_double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sgebal( char* job, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int* ilo, lapack_int* ihi, float* scale,\n                    lapack_int *info );\nvoid LAPACK_dgebal( char* job, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int* ilo, lapack_int* ihi, double* scale,\n                    lapack_int *info );\nvoid LAPACK_cgebal( char* job, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int* ilo, lapack_int* ihi,\n                    float* scale, lapack_int *info );\nvoid LAPACK_zgebal( char* job, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* ilo, lapack_int* ihi,\n                    double* scale, lapack_int *info );\nvoid LAPACK_sgebak( char* job, char* side, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, const float* scale, lapack_int* m,\n                    float* v, lapack_int* ldv, lapack_int *info );\nvoid LAPACK_dgebak( char* job, char* side, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, const double* scale, lapack_int* m,\n                    double* v, lapack_int* ldv, lapack_int *info );\nvoid LAPACK_cgebak( char* job, char* side, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, const float* scale, lapack_int* m,\n                    lapack_complex_float* v, lapack_int* ldv,\n                    lapack_int *info );\nvoid LAPACK_zgebak( char* job, char* side, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, const double* scale, lapack_int* m,\n                    lapack_complex_double* v, lapack_int* ldv,\n                    lapack_int *info );\nvoid LAPACK_shseqr( char* job, char* compz, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, float* h, lapack_int* ldh, float* wr,\n                    float* wi, float* z, lapack_int* ldz, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dhseqr( char* job, char* compz, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, double* h, lapack_int* ldh, double* wr,\n                    double* wi, double* z, lapack_int* ldz, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_chseqr( char* job, char* compz, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, lapack_complex_float* h, lapack_int* ldh,\n                    lapack_complex_float* w, lapack_complex_float* z,\n                    lapack_int* ldz, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zhseqr( char* job, char* compz, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, lapack_complex_double* h, lapack_int* ldh,\n                    lapack_complex_double* w, lapack_complex_double* z,\n                    lapack_int* ldz, lapack_complex_double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_shsein( char* job, char* eigsrc, char* initv,\n                    lapack_logical* select, lapack_int* n, const float* h,\n                    lapack_int* ldh, float* wr, const float* wi, float* vl,\n                    lapack_int* ldvl, float* vr, lapack_int* ldvr,\n                    lapack_int* mm, lapack_int* m, float* work,\n                    lapack_int* ifaill, lapack_int* ifailr, lapack_int *info );\nvoid LAPACK_dhsein( char* job, char* eigsrc, char* initv,\n                    lapack_logical* select, lapack_int* n, const double* h,\n                    lapack_int* ldh, double* wr, const double* wi, double* vl,\n                    lapack_int* ldvl, double* vr, lapack_int* ldvr,\n                    lapack_int* mm, lapack_int* m, double* work,\n                    lapack_int* ifaill, lapack_int* ifailr, lapack_int *info );\nvoid LAPACK_chsein( char* job, char* eigsrc, char* initv,\n                    const lapack_logical* select, lapack_int* n,\n                    const lapack_complex_float* h, lapack_int* ldh,\n                    lapack_complex_float* w, lapack_complex_float* vl,\n                    lapack_int* ldvl, lapack_complex_float* vr,\n                    lapack_int* ldvr, lapack_int* mm, lapack_int* m,\n                    lapack_complex_float* work, float* rwork,\n                    lapack_int* ifaill, lapack_int* ifailr, lapack_int *info );\nvoid LAPACK_zhsein( char* job, char* eigsrc, char* initv,\n                    const lapack_logical* select, lapack_int* n,\n                    const lapack_complex_double* h, lapack_int* ldh,\n                    lapack_complex_double* w, lapack_complex_double* vl,\n                    lapack_int* ldvl, lapack_complex_double* vr,\n                    lapack_int* ldvr, lapack_int* mm, lapack_int* m,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int* ifaill, lapack_int* ifailr, lapack_int *info );\nvoid LAPACK_strevc( char* side, char* howmny, lapack_logical* select,\n                    lapack_int* n, const float* t, lapack_int* ldt, float* vl,\n                    lapack_int* ldvl, float* vr, lapack_int* ldvr,\n                    lapack_int* mm, lapack_int* m, float* work,\n                    lapack_int *info );\nvoid LAPACK_dtrevc( char* side, char* howmny, lapack_logical* select,\n                    lapack_int* n, const double* t, lapack_int* ldt, double* vl,\n                    lapack_int* ldvl, double* vr, lapack_int* ldvr,\n                    lapack_int* mm, lapack_int* m, double* work,\n                    lapack_int *info );\nvoid LAPACK_ctrevc( char* side, char* howmny, const lapack_logical* select,\n                    lapack_int* n, lapack_complex_float* t, lapack_int* ldt,\n                    lapack_complex_float* vl, lapack_int* ldvl,\n                    lapack_complex_float* vr, lapack_int* ldvr, lapack_int* mm,\n                    lapack_int* m, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_ztrevc( char* side, char* howmny, const lapack_logical* select,\n                    lapack_int* n, lapack_complex_double* t, lapack_int* ldt,\n                    lapack_complex_double* vl, lapack_int* ldvl,\n                    lapack_complex_double* vr, lapack_int* ldvr, lapack_int* mm,\n                    lapack_int* m, lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_strsna( char* job, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const float* t, lapack_int* ldt,\n                    const float* vl, lapack_int* ldvl, const float* vr,\n                    lapack_int* ldvr, float* s, float* sep, lapack_int* mm,\n                    lapack_int* m, float* work, lapack_int* ldwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dtrsna( char* job, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const double* t, lapack_int* ldt,\n                    const double* vl, lapack_int* ldvl, const double* vr,\n                    lapack_int* ldvr, double* s, double* sep, lapack_int* mm,\n                    lapack_int* m, double* work, lapack_int* ldwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ctrsna( char* job, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const lapack_complex_float* t,\n                    lapack_int* ldt, const lapack_complex_float* vl,\n                    lapack_int* ldvl, const lapack_complex_float* vr,\n                    lapack_int* ldvr, float* s, float* sep, lapack_int* mm,\n                    lapack_int* m, lapack_complex_float* work,\n                    lapack_int* ldwork, float* rwork, lapack_int *info );\nvoid LAPACK_ztrsna( char* job, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const lapack_complex_double* t,\n                    lapack_int* ldt, const lapack_complex_double* vl,\n                    lapack_int* ldvl, const lapack_complex_double* vr,\n                    lapack_int* ldvr, double* s, double* sep, lapack_int* mm,\n                    lapack_int* m, lapack_complex_double* work,\n                    lapack_int* ldwork, double* rwork, lapack_int *info );\nvoid LAPACK_strexc( char* compq, lapack_int* n, float* t, lapack_int* ldt,\n                    float* q, lapack_int* ldq, lapack_int* ifst,\n                    lapack_int* ilst, float* work, lapack_int *info );\nvoid LAPACK_dtrexc( char* compq, lapack_int* n, double* t, lapack_int* ldt,\n                    double* q, lapack_int* ldq, lapack_int* ifst,\n                    lapack_int* ilst, double* work, lapack_int *info );\nvoid LAPACK_ctrexc( char* compq, lapack_int* n, lapack_complex_float* t,\n                    lapack_int* ldt, lapack_complex_float* q, lapack_int* ldq,\n                    lapack_int* ifst, lapack_int* ilst, lapack_int *info );\nvoid LAPACK_ztrexc( char* compq, lapack_int* n, lapack_complex_double* t,\n                    lapack_int* ldt, lapack_complex_double* q, lapack_int* ldq,\n                    lapack_int* ifst, lapack_int* ilst, lapack_int *info );\nvoid LAPACK_strsen( char* job, char* compq, const lapack_logical* select,\n                    lapack_int* n, float* t, lapack_int* ldt, float* q,\n                    lapack_int* ldq, float* wr, float* wi, lapack_int* m,\n                    float* s, float* sep, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dtrsen( char* job, char* compq, const lapack_logical* select,\n                    lapack_int* n, double* t, lapack_int* ldt, double* q,\n                    lapack_int* ldq, double* wr, double* wi, lapack_int* m,\n                    double* s, double* sep, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_ctrsen( char* job, char* compq, const lapack_logical* select,\n                    lapack_int* n, lapack_complex_float* t, lapack_int* ldt,\n                    lapack_complex_float* q, lapack_int* ldq,\n                    lapack_complex_float* w, lapack_int* m, float* s,\n                    float* sep, lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_ztrsen( char* job, char* compq, const lapack_logical* select,\n                    lapack_int* n, lapack_complex_double* t, lapack_int* ldt,\n                    lapack_complex_double* q, lapack_int* ldq,\n                    lapack_complex_double* w, lapack_int* m, double* s,\n                    double* sep, lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_strsyl( char* trana, char* tranb, lapack_int* isgn, lapack_int* m,\n                    lapack_int* n, const float* a, lapack_int* lda,\n                    const float* b, lapack_int* ldb, float* c, lapack_int* ldc,\n                    float* scale, lapack_int *info );\nvoid LAPACK_dtrsyl( char* trana, char* tranb, lapack_int* isgn, lapack_int* m,\n                    lapack_int* n, const double* a, lapack_int* lda,\n                    const double* b, lapack_int* ldb, double* c,\n                    lapack_int* ldc, double* scale, lapack_int *info );\nvoid LAPACK_ctrsyl( char* trana, char* tranb, lapack_int* isgn, lapack_int* m,\n                    lapack_int* n, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* b,\n                    lapack_int* ldb, lapack_complex_float* c, lapack_int* ldc,\n                    float* scale, lapack_int *info );\nvoid LAPACK_ztrsyl( char* trana, char* tranb, lapack_int* isgn, lapack_int* m,\n                    lapack_int* n, const lapack_complex_double* a,\n                    lapack_int* lda, const lapack_complex_double* b,\n                    lapack_int* ldb, lapack_complex_double* c, lapack_int* ldc,\n                    double* scale, lapack_int *info );\nvoid LAPACK_sgghrd( char* compq, char* compz, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, float* a, lapack_int* lda, float* b,\n                    lapack_int* ldb, float* q, lapack_int* ldq, float* z,\n                    lapack_int* ldz, lapack_int *info );\nvoid LAPACK_dgghrd( char* compq, char* compz, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, double* a, lapack_int* lda, double* b,\n                    lapack_int* ldb, double* q, lapack_int* ldq, double* z,\n                    lapack_int* ldz, lapack_int *info );\nvoid LAPACK_cgghrd( char* compq, char* compz, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* q, lapack_int* ldq,\n                    lapack_complex_float* z, lapack_int* ldz,\n                    lapack_int *info );\nvoid LAPACK_zgghrd( char* compq, char* compz, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* q, lapack_int* ldq,\n                    lapack_complex_double* z, lapack_int* ldz,\n                    lapack_int *info );\nvoid LAPACK_sggbal( char* job, lapack_int* n, float* a, lapack_int* lda,\n                    float* b, lapack_int* ldb, lapack_int* ilo, lapack_int* ihi,\n                    float* lscale, float* rscale, float* work,\n                    lapack_int *info );\nvoid LAPACK_dggbal( char* job, lapack_int* n, double* a, lapack_int* lda,\n                    double* b, lapack_int* ldb, lapack_int* ilo,\n                    lapack_int* ihi, double* lscale, double* rscale,\n                    double* work, lapack_int *info );\nvoid LAPACK_cggbal( char* job, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* b, lapack_int* ldb,\n                    lapack_int* ilo, lapack_int* ihi, float* lscale,\n                    float* rscale, float* work, lapack_int *info );\nvoid LAPACK_zggbal( char* job, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* b, lapack_int* ldb,\n                    lapack_int* ilo, lapack_int* ihi, double* lscale,\n                    double* rscale, double* work, lapack_int *info );\nvoid LAPACK_sggbak( char* job, char* side, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, const float* lscale, const float* rscale,\n                    lapack_int* m, float* v, lapack_int* ldv,\n                    lapack_int *info );\nvoid LAPACK_dggbak( char* job, char* side, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, const double* lscale, const double* rscale,\n                    lapack_int* m, double* v, lapack_int* ldv,\n                    lapack_int *info );\nvoid LAPACK_cggbak( char* job, char* side, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, const float* lscale, const float* rscale,\n                    lapack_int* m, lapack_complex_float* v, lapack_int* ldv,\n                    lapack_int *info );\nvoid LAPACK_zggbak( char* job, char* side, lapack_int* n, lapack_int* ilo,\n                    lapack_int* ihi, const double* lscale, const double* rscale,\n                    lapack_int* m, lapack_complex_double* v, lapack_int* ldv,\n                    lapack_int *info );\nvoid LAPACK_shgeqz( char* job, char* compq, char* compz, lapack_int* n,\n                    lapack_int* ilo, lapack_int* ihi, float* h, lapack_int* ldh,\n                    float* t, lapack_int* ldt, float* alphar, float* alphai,\n                    float* beta, float* q, lapack_int* ldq, float* z,\n                    lapack_int* ldz, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dhgeqz( char* job, char* compq, char* compz, lapack_int* n,\n                    lapack_int* ilo, lapack_int* ihi, double* h,\n                    lapack_int* ldh, double* t, lapack_int* ldt, double* alphar,\n                    double* alphai, double* beta, double* q, lapack_int* ldq,\n                    double* z, lapack_int* ldz, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_chgeqz( char* job, char* compq, char* compz, lapack_int* n,\n                    lapack_int* ilo, lapack_int* ihi, lapack_complex_float* h,\n                    lapack_int* ldh, lapack_complex_float* t, lapack_int* ldt,\n                    lapack_complex_float* alpha, lapack_complex_float* beta,\n                    lapack_complex_float* q, lapack_int* ldq,\n                    lapack_complex_float* z, lapack_int* ldz,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zhgeqz( char* job, char* compq, char* compz, lapack_int* n,\n                    lapack_int* ilo, lapack_int* ihi, lapack_complex_double* h,\n                    lapack_int* ldh, lapack_complex_double* t, lapack_int* ldt,\n                    lapack_complex_double* alpha, lapack_complex_double* beta,\n                    lapack_complex_double* q, lapack_int* ldq,\n                    lapack_complex_double* z, lapack_int* ldz,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_stgevc( char* side, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const float* s, lapack_int* lds,\n                    const float* p, lapack_int* ldp, float* vl,\n                    lapack_int* ldvl, float* vr, lapack_int* ldvr,\n                    lapack_int* mm, lapack_int* m, float* work,\n                    lapack_int *info );\nvoid LAPACK_dtgevc( char* side, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const double* s, lapack_int* lds,\n                    const double* p, lapack_int* ldp, double* vl,\n                    lapack_int* ldvl, double* vr, lapack_int* ldvr,\n                    lapack_int* mm, lapack_int* m, double* work,\n                    lapack_int *info );\nvoid LAPACK_ctgevc( char* side, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const lapack_complex_float* s,\n                    lapack_int* lds, const lapack_complex_float* p,\n                    lapack_int* ldp, lapack_complex_float* vl, lapack_int* ldvl,\n                    lapack_complex_float* vr, lapack_int* ldvr, lapack_int* mm,\n                    lapack_int* m, lapack_complex_float* work, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_ztgevc( char* side, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const lapack_complex_double* s,\n                    lapack_int* lds, const lapack_complex_double* p,\n                    lapack_int* ldp, lapack_complex_double* vl,\n                    lapack_int* ldvl, lapack_complex_double* vr,\n                    lapack_int* ldvr, lapack_int* mm, lapack_int* m,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int *info );\nvoid LAPACK_stgexc( lapack_logical* wantq, lapack_logical* wantz, lapack_int* n,\n                    float* a, lapack_int* lda, float* b, lapack_int* ldb,\n                    float* q, lapack_int* ldq, float* z, lapack_int* ldz,\n                    lapack_int* ifst, lapack_int* ilst, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dtgexc( lapack_logical* wantq, lapack_logical* wantz, lapack_int* n,\n                    double* a, lapack_int* lda, double* b, lapack_int* ldb,\n                    double* q, lapack_int* ldq, double* z, lapack_int* ldz,\n                    lapack_int* ifst, lapack_int* ilst, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_ctgexc( lapack_logical* wantq, lapack_logical* wantz, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* q, lapack_int* ldq,\n                    lapack_complex_float* z, lapack_int* ldz, lapack_int* ifst,\n                    lapack_int* ilst, lapack_int *info );\nvoid LAPACK_ztgexc( lapack_logical* wantq, lapack_logical* wantz, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* q, lapack_int* ldq,\n                    lapack_complex_double* z, lapack_int* ldz, lapack_int* ifst,\n                    lapack_int* ilst, lapack_int *info );\nvoid LAPACK_stgsen( lapack_int* ijob, lapack_logical* wantq,\n                    lapack_logical* wantz, const lapack_logical* select,\n                    lapack_int* n, float* a, lapack_int* lda, float* b,\n                    lapack_int* ldb, float* alphar, float* alphai, float* beta,\n                    float* q, lapack_int* ldq, float* z, lapack_int* ldz,\n                    lapack_int* m, float* pl, float* pr, float* dif,\n                    float* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dtgsen( lapack_int* ijob, lapack_logical* wantq,\n                    lapack_logical* wantz, const lapack_logical* select,\n                    lapack_int* n, double* a, lapack_int* lda, double* b,\n                    lapack_int* ldb, double* alphar, double* alphai,\n                    double* beta, double* q, lapack_int* ldq, double* z,\n                    lapack_int* ldz, lapack_int* m, double* pl, double* pr,\n                    double* dif, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_ctgsen( lapack_int* ijob, lapack_logical* wantq,\n                    lapack_logical* wantz, const lapack_logical* select,\n                    lapack_int* n, lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* alpha, lapack_complex_float* beta,\n                    lapack_complex_float* q, lapack_int* ldq,\n                    lapack_complex_float* z, lapack_int* ldz, lapack_int* m,\n                    float* pl, float* pr, float* dif,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_ztgsen( lapack_int* ijob, lapack_logical* wantq,\n                    lapack_logical* wantz, const lapack_logical* select,\n                    lapack_int* n, lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* alpha, lapack_complex_double* beta,\n                    lapack_complex_double* q, lapack_int* ldq,\n                    lapack_complex_double* z, lapack_int* ldz, lapack_int* m,\n                    double* pl, double* pr, double* dif,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_stgsyl( char* trans, lapack_int* ijob, lapack_int* m, lapack_int* n,\n                    const float* a, lapack_int* lda, const float* b,\n                    lapack_int* ldb, float* c, lapack_int* ldc, const float* d,\n                    lapack_int* ldd, const float* e, lapack_int* lde, float* f,\n                    lapack_int* ldf, float* scale, float* dif, float* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dtgsyl( char* trans, lapack_int* ijob, lapack_int* m, lapack_int* n,\n                    const double* a, lapack_int* lda, const double* b,\n                    lapack_int* ldb, double* c, lapack_int* ldc,\n                    const double* d, lapack_int* ldd, const double* e,\n                    lapack_int* lde, double* f, lapack_int* ldf, double* scale,\n                    double* dif, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ctgsyl( char* trans, lapack_int* ijob, lapack_int* m, lapack_int* n,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    const lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    const lapack_complex_float* d, lapack_int* ldd,\n                    const lapack_complex_float* e, lapack_int* lde,\n                    lapack_complex_float* f, lapack_int* ldf, float* scale,\n                    float* dif, lapack_complex_float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ztgsyl( char* trans, lapack_int* ijob, lapack_int* m, lapack_int* n,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    const lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* c, lapack_int* ldc,\n                    const lapack_complex_double* d, lapack_int* ldd,\n                    const lapack_complex_double* e, lapack_int* lde,\n                    lapack_complex_double* f, lapack_int* ldf, double* scale,\n                    double* dif, lapack_complex_double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_stgsna( char* job, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const float* a, lapack_int* lda,\n                    const float* b, lapack_int* ldb, const float* vl,\n                    lapack_int* ldvl, const float* vr, lapack_int* ldvr,\n                    float* s, float* dif, lapack_int* mm, lapack_int* m,\n                    float* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dtgsna( char* job, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const double* a, lapack_int* lda,\n                    const double* b, lapack_int* ldb, const double* vl,\n                    lapack_int* ldvl, const double* vr, lapack_int* ldvr,\n                    double* s, double* dif, lapack_int* mm, lapack_int* m,\n                    double* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_ctgsna( char* job, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const lapack_complex_float* a,\n                    lapack_int* lda, const lapack_complex_float* b,\n                    lapack_int* ldb, const lapack_complex_float* vl,\n                    lapack_int* ldvl, const lapack_complex_float* vr,\n                    lapack_int* ldvr, float* s, float* dif, lapack_int* mm,\n                    lapack_int* m, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ztgsna( char* job, char* howmny, const lapack_logical* select,\n                    lapack_int* n, const lapack_complex_double* a,\n                    lapack_int* lda, const lapack_complex_double* b,\n                    lapack_int* ldb, const lapack_complex_double* vl,\n                    lapack_int* ldvl, const lapack_complex_double* vr,\n                    lapack_int* ldvr, double* s, double* dif, lapack_int* mm,\n                    lapack_int* m, lapack_complex_double* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_sggsvp( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* p, lapack_int* n, float* a, lapack_int* lda,\n                    float* b, lapack_int* ldb, float* tola, float* tolb,\n                    lapack_int* k, lapack_int* l, float* u, lapack_int* ldu,\n                    float* v, lapack_int* ldv, float* q, lapack_int* ldq,\n                    lapack_int* iwork, float* tau, float* work,\n                    lapack_int *info );\nvoid LAPACK_dggsvp( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* p, lapack_int* n, double* a, lapack_int* lda,\n                    double* b, lapack_int* ldb, double* tola, double* tolb,\n                    lapack_int* k, lapack_int* l, double* u, lapack_int* ldu,\n                    double* v, lapack_int* ldv, double* q, lapack_int* ldq,\n                    lapack_int* iwork, double* tau, double* work,\n                    lapack_int *info );\nvoid LAPACK_cggsvp( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* p, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* b, lapack_int* ldb,\n                    float* tola, float* tolb, lapack_int* k, lapack_int* l,\n                    lapack_complex_float* u, lapack_int* ldu,\n                    lapack_complex_float* v, lapack_int* ldv,\n                    lapack_complex_float* q, lapack_int* ldq, lapack_int* iwork,\n                    float* rwork, lapack_complex_float* tau,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zggsvp( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* p, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* b, lapack_int* ldb,\n                    double* tola, double* tolb, lapack_int* k, lapack_int* l,\n                    lapack_complex_double* u, lapack_int* ldu,\n                    lapack_complex_double* v, lapack_int* ldv,\n                    lapack_complex_double* q, lapack_int* ldq,\n                    lapack_int* iwork, double* rwork,\n                    lapack_complex_double* tau, lapack_complex_double* work,\n                    lapack_int *info );\nvoid LAPACK_stgsja( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* p, lapack_int* n, lapack_int* k, lapack_int* l,\n                    float* a, lapack_int* lda, float* b, lapack_int* ldb,\n                    float* tola, float* tolb, float* alpha, float* beta,\n                    float* u, lapack_int* ldu, float* v, lapack_int* ldv,\n                    float* q, lapack_int* ldq, float* work, lapack_int* ncycle,\n                    lapack_int *info );\nvoid LAPACK_dtgsja( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* p, lapack_int* n, lapack_int* k, lapack_int* l,\n                    double* a, lapack_int* lda, double* b, lapack_int* ldb,\n                    double* tola, double* tolb, double* alpha, double* beta,\n                    double* u, lapack_int* ldu, double* v, lapack_int* ldv,\n                    double* q, lapack_int* ldq, double* work,\n                    lapack_int* ncycle, lapack_int *info );\nvoid LAPACK_ctgsja( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* p, lapack_int* n, lapack_int* k, lapack_int* l,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb, float* tola,\n                    float* tolb, float* alpha, float* beta,\n                    lapack_complex_float* u, lapack_int* ldu,\n                    lapack_complex_float* v, lapack_int* ldv,\n                    lapack_complex_float* q, lapack_int* ldq,\n                    lapack_complex_float* work, lapack_int* ncycle,\n                    lapack_int *info );\nvoid LAPACK_ztgsja( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* p, lapack_int* n, lapack_int* k, lapack_int* l,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb, double* tola,\n                    double* tolb, double* alpha, double* beta,\n                    lapack_complex_double* u, lapack_int* ldu,\n                    lapack_complex_double* v, lapack_int* ldv,\n                    lapack_complex_double* q, lapack_int* ldq,\n                    lapack_complex_double* work, lapack_int* ncycle,\n                    lapack_int *info );\nvoid LAPACK_sgels( char* trans, lapack_int* m, lapack_int* n, lapack_int* nrhs,\n                   float* a, lapack_int* lda, float* b, lapack_int* ldb,\n                   float* work, lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dgels( char* trans, lapack_int* m, lapack_int* n, lapack_int* nrhs,\n                   double* a, lapack_int* lda, double* b, lapack_int* ldb,\n                   double* work, lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cgels( char* trans, lapack_int* m, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_float* a, lapack_int* lda,\n                   lapack_complex_float* b, lapack_int* ldb,\n                   lapack_complex_float* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_zgels( char* trans, lapack_int* m, lapack_int* n, lapack_int* nrhs,\n                   lapack_complex_double* a, lapack_int* lda,\n                   lapack_complex_double* b, lapack_int* ldb,\n                   lapack_complex_double* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_sgelsy( lapack_int* m, lapack_int* n, lapack_int* nrhs, float* a,\n                    lapack_int* lda, float* b, lapack_int* ldb,\n                    lapack_int* jpvt, float* rcond, lapack_int* rank,\n                    float* work, lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dgelsy( lapack_int* m, lapack_int* n, lapack_int* nrhs, double* a,\n                    lapack_int* lda, double* b, lapack_int* ldb,\n                    lapack_int* jpvt, double* rcond, lapack_int* rank,\n                    double* work, lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cgelsy( lapack_int* m, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb, lapack_int* jpvt,\n                    float* rcond, lapack_int* rank, lapack_complex_float* work,\n                    lapack_int* lwork, float* rwork, lapack_int *info );\nvoid LAPACK_zgelsy( lapack_int* m, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb, lapack_int* jpvt,\n                    double* rcond, lapack_int* rank,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_sgelss( lapack_int* m, lapack_int* n, lapack_int* nrhs, float* a,\n                    lapack_int* lda, float* b, lapack_int* ldb, float* s,\n                    float* rcond, lapack_int* rank, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dgelss( lapack_int* m, lapack_int* n, lapack_int* nrhs, double* a,\n                    lapack_int* lda, double* b, lapack_int* ldb, double* s,\n                    double* rcond, lapack_int* rank, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cgelss( lapack_int* m, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb, float* s,\n                    float* rcond, lapack_int* rank, lapack_complex_float* work,\n                    lapack_int* lwork, float* rwork, lapack_int *info );\nvoid LAPACK_zgelss( lapack_int* m, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb, double* s,\n                    double* rcond, lapack_int* rank,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_sgelsd( lapack_int* m, lapack_int* n, lapack_int* nrhs, float* a,\n                    lapack_int* lda, float* b, lapack_int* ldb, float* s,\n                    float* rcond, lapack_int* rank, float* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dgelsd( lapack_int* m, lapack_int* n, lapack_int* nrhs, double* a,\n                    lapack_int* lda, double* b, lapack_int* ldb, double* s,\n                    double* rcond, lapack_int* rank, double* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cgelsd( lapack_int* m, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb, float* s,\n                    float* rcond, lapack_int* rank, lapack_complex_float* work,\n                    lapack_int* lwork, float* rwork, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_zgelsd( lapack_int* m, lapack_int* n, lapack_int* nrhs,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb, double* s,\n                    double* rcond, lapack_int* rank,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_sgglse( lapack_int* m, lapack_int* n, lapack_int* p, float* a,\n                    lapack_int* lda, float* b, lapack_int* ldb, float* c,\n                    float* d, float* x, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dgglse( lapack_int* m, lapack_int* n, lapack_int* p, double* a,\n                    lapack_int* lda, double* b, lapack_int* ldb, double* c,\n                    double* d, double* x, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cgglse( lapack_int* m, lapack_int* n, lapack_int* p,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* c, lapack_complex_float* d,\n                    lapack_complex_float* x, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zgglse( lapack_int* m, lapack_int* n, lapack_int* p,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* c, lapack_complex_double* d,\n                    lapack_complex_double* x, lapack_complex_double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sggglm( lapack_int* n, lapack_int* m, lapack_int* p, float* a,\n                    lapack_int* lda, float* b, lapack_int* ldb, float* d,\n                    float* x, float* y, float* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_dggglm( lapack_int* n, lapack_int* m, lapack_int* p, double* a,\n                    lapack_int* lda, double* b, lapack_int* ldb, double* d,\n                    double* x, double* y, double* work, lapack_int* lwork,\n                    lapack_int *info );\nvoid LAPACK_cggglm( lapack_int* n, lapack_int* m, lapack_int* p,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* d, lapack_complex_float* x,\n                    lapack_complex_float* y, lapack_complex_float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_zggglm( lapack_int* n, lapack_int* m, lapack_int* p,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* d, lapack_complex_double* x,\n                    lapack_complex_double* y, lapack_complex_double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_ssyev( char* jobz, char* uplo, lapack_int* n, float* a,\n                   lapack_int* lda, float* w, float* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_dsyev( char* jobz, char* uplo, lapack_int* n, double* a,\n                   lapack_int* lda, double* w, double* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_cheev( char* jobz, char* uplo, lapack_int* n,\n                   lapack_complex_float* a, lapack_int* lda, float* w,\n                   lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                   lapack_int *info );\nvoid LAPACK_zheev( char* jobz, char* uplo, lapack_int* n,\n                   lapack_complex_double* a, lapack_int* lda, double* w,\n                   lapack_complex_double* work, lapack_int* lwork,\n                   double* rwork, lapack_int *info );\nvoid LAPACK_ssyevd( char* jobz, char* uplo, lapack_int* n, float* a,\n                    lapack_int* lda, float* w, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dsyevd( char* jobz, char* uplo, lapack_int* n, double* a,\n                    lapack_int* lda, double* w, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_cheevd( char* jobz, char* uplo, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda, float* w,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int* lrwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_zheevd( char* jobz, char* uplo, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda, double* w,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* lrwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_ssyevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    float* a, lapack_int* lda, float* vl, float* vu,\n                    lapack_int* il, lapack_int* iu, float* abstol,\n                    lapack_int* m, float* w, float* z, lapack_int* ldz,\n                    float* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_dsyevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    double* a, lapack_int* lda, double* vl, double* vu,\n                    lapack_int* il, lapack_int* iu, double* abstol,\n                    lapack_int* m, double* w, double* z, lapack_int* ldz,\n                    double* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_cheevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda, float* vl,\n                    float* vu, lapack_int* il, lapack_int* iu, float* abstol,\n                    lapack_int* m, float* w, lapack_complex_float* z,\n                    lapack_int* ldz, lapack_complex_float* work,\n                    lapack_int* lwork, float* rwork, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_zheevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda, double* vl,\n                    double* vu, lapack_int* il, lapack_int* iu, double* abstol,\n                    lapack_int* m, double* w, lapack_complex_double* z,\n                    lapack_int* ldz, lapack_complex_double* work,\n                    lapack_int* lwork, double* rwork, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_ssyevr( char* jobz, char* range, char* uplo, lapack_int* n,\n                    float* a, lapack_int* lda, float* vl, float* vu,\n                    lapack_int* il, lapack_int* iu, float* abstol,\n                    lapack_int* m, float* w, float* z, lapack_int* ldz,\n                    lapack_int* isuppz, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dsyevr( char* jobz, char* range, char* uplo, lapack_int* n,\n                    double* a, lapack_int* lda, double* vl, double* vu,\n                    lapack_int* il, lapack_int* iu, double* abstol,\n                    lapack_int* m, double* w, double* z, lapack_int* ldz,\n                    lapack_int* isuppz, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_cheevr( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda, float* vl,\n                    float* vu, lapack_int* il, lapack_int* iu, float* abstol,\n                    lapack_int* m, float* w, lapack_complex_float* z,\n                    lapack_int* ldz, lapack_int* isuppz,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int* lrwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_zheevr( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda, double* vl,\n                    double* vu, lapack_int* il, lapack_int* iu, double* abstol,\n                    lapack_int* m, double* w, lapack_complex_double* z,\n                    lapack_int* ldz, lapack_int* isuppz,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* lrwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_sspev( char* jobz, char* uplo, lapack_int* n, float* ap, float* w,\n                   float* z, lapack_int* ldz, float* work, lapack_int *info );\nvoid LAPACK_dspev( char* jobz, char* uplo, lapack_int* n, double* ap, double* w,\n                   double* z, lapack_int* ldz, double* work, lapack_int *info );\nvoid LAPACK_chpev( char* jobz, char* uplo, lapack_int* n,\n                   lapack_complex_float* ap, float* w, lapack_complex_float* z,\n                   lapack_int* ldz, lapack_complex_float* work, float* rwork,\n                   lapack_int *info );\nvoid LAPACK_zhpev( char* jobz, char* uplo, lapack_int* n,\n                   lapack_complex_double* ap, double* w,\n                   lapack_complex_double* z, lapack_int* ldz,\n                   lapack_complex_double* work, double* rwork,\n                   lapack_int *info );\nvoid LAPACK_sspevd( char* jobz, char* uplo, lapack_int* n, float* ap, float* w,\n                    float* z, lapack_int* ldz, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dspevd( char* jobz, char* uplo, lapack_int* n, double* ap,\n                    double* w, double* z, lapack_int* ldz, double* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_chpevd( char* jobz, char* uplo, lapack_int* n,\n                    lapack_complex_float* ap, float* w, lapack_complex_float* z,\n                    lapack_int* ldz, lapack_complex_float* work,\n                    lapack_int* lwork, float* rwork, lapack_int* lrwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_zhpevd( char* jobz, char* uplo, lapack_int* n,\n                    lapack_complex_double* ap, double* w,\n                    lapack_complex_double* z, lapack_int* ldz,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* lrwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_sspevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    float* ap, float* vl, float* vu, lapack_int* il,\n                    lapack_int* iu, float* abstol, lapack_int* m, float* w,\n                    float* z, lapack_int* ldz, float* work, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_dspevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    double* ap, double* vl, double* vu, lapack_int* il,\n                    lapack_int* iu, double* abstol, lapack_int* m, double* w,\n                    double* z, lapack_int* ldz, double* work, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_chpevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_complex_float* ap, float* vl, float* vu,\n                    lapack_int* il, lapack_int* iu, float* abstol,\n                    lapack_int* m, float* w, lapack_complex_float* z,\n                    lapack_int* ldz, lapack_complex_float* work, float* rwork,\n                    lapack_int* iwork, lapack_int* ifail, lapack_int *info );\nvoid LAPACK_zhpevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_complex_double* ap, double* vl, double* vu,\n                    lapack_int* il, lapack_int* iu, double* abstol,\n                    lapack_int* m, double* w, lapack_complex_double* z,\n                    lapack_int* ldz, lapack_complex_double* work, double* rwork,\n                    lapack_int* iwork, lapack_int* ifail, lapack_int *info );\nvoid LAPACK_ssbev( char* jobz, char* uplo, lapack_int* n, lapack_int* kd,\n                   float* ab, lapack_int* ldab, float* w, float* z,\n                   lapack_int* ldz, float* work, lapack_int *info );\nvoid LAPACK_dsbev( char* jobz, char* uplo, lapack_int* n, lapack_int* kd,\n                   double* ab, lapack_int* ldab, double* w, double* z,\n                   lapack_int* ldz, double* work, lapack_int *info );\nvoid LAPACK_chbev( char* jobz, char* uplo, lapack_int* n, lapack_int* kd,\n                   lapack_complex_float* ab, lapack_int* ldab, float* w,\n                   lapack_complex_float* z, lapack_int* ldz,\n                   lapack_complex_float* work, float* rwork, lapack_int *info );\nvoid LAPACK_zhbev( char* jobz, char* uplo, lapack_int* n, lapack_int* kd,\n                   lapack_complex_double* ab, lapack_int* ldab, double* w,\n                   lapack_complex_double* z, lapack_int* ldz,\n                   lapack_complex_double* work, double* rwork,\n                   lapack_int *info );\nvoid LAPACK_ssbevd( char* jobz, char* uplo, lapack_int* n, lapack_int* kd,\n                    float* ab, lapack_int* ldab, float* w, float* z,\n                    lapack_int* ldz, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dsbevd( char* jobz, char* uplo, lapack_int* n, lapack_int* kd,\n                    double* ab, lapack_int* ldab, double* w, double* z,\n                    lapack_int* ldz, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_chbevd( char* jobz, char* uplo, lapack_int* n, lapack_int* kd,\n                    lapack_complex_float* ab, lapack_int* ldab, float* w,\n                    lapack_complex_float* z, lapack_int* ldz,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int* lrwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_zhbevd( char* jobz, char* uplo, lapack_int* n, lapack_int* kd,\n                    lapack_complex_double* ab, lapack_int* ldab, double* w,\n                    lapack_complex_double* z, lapack_int* ldz,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* lrwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_ssbevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_int* kd, float* ab, lapack_int* ldab, float* q,\n                    lapack_int* ldq, float* vl, float* vu, lapack_int* il,\n                    lapack_int* iu, float* abstol, lapack_int* m, float* w,\n                    float* z, lapack_int* ldz, float* work, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_dsbevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_int* kd, double* ab, lapack_int* ldab, double* q,\n                    lapack_int* ldq, double* vl, double* vu, lapack_int* il,\n                    lapack_int* iu, double* abstol, lapack_int* m, double* w,\n                    double* z, lapack_int* ldz, double* work, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_chbevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_int* kd, lapack_complex_float* ab, lapack_int* ldab,\n                    lapack_complex_float* q, lapack_int* ldq, float* vl,\n                    float* vu, lapack_int* il, lapack_int* iu, float* abstol,\n                    lapack_int* m, float* w, lapack_complex_float* z,\n                    lapack_int* ldz, lapack_complex_float* work, float* rwork,\n                    lapack_int* iwork, lapack_int* ifail, lapack_int *info );\nvoid LAPACK_zhbevx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_int* kd, lapack_complex_double* ab, lapack_int* ldab,\n                    lapack_complex_double* q, lapack_int* ldq, double* vl,\n                    double* vu, lapack_int* il, lapack_int* iu, double* abstol,\n                    lapack_int* m, double* w, lapack_complex_double* z,\n                    lapack_int* ldz, lapack_complex_double* work, double* rwork,\n                    lapack_int* iwork, lapack_int* ifail, lapack_int *info );\nvoid LAPACK_sstev( char* jobz, lapack_int* n, float* d, float* e, float* z,\n                   lapack_int* ldz, float* work, lapack_int *info );\nvoid LAPACK_dstev( char* jobz, lapack_int* n, double* d, double* e, double* z,\n                   lapack_int* ldz, double* work, lapack_int *info );\nvoid LAPACK_sstevd( char* jobz, lapack_int* n, float* d, float* e, float* z,\n                    lapack_int* ldz, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dstevd( char* jobz, lapack_int* n, double* d, double* e, double* z,\n                    lapack_int* ldz, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_sstevx( char* jobz, char* range, lapack_int* n, float* d, float* e,\n                    float* vl, float* vu, lapack_int* il, lapack_int* iu,\n                    float* abstol, lapack_int* m, float* w, float* z,\n                    lapack_int* ldz, float* work, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_dstevx( char* jobz, char* range, lapack_int* n, double* d,\n                    double* e, double* vl, double* vu, lapack_int* il,\n                    lapack_int* iu, double* abstol, lapack_int* m, double* w,\n                    double* z, lapack_int* ldz, double* work, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_sstevr( char* jobz, char* range, lapack_int* n, float* d, float* e,\n                    float* vl, float* vu, lapack_int* il, lapack_int* iu,\n                    float* abstol, lapack_int* m, float* w, float* z,\n                    lapack_int* ldz, lapack_int* isuppz, float* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_dstevr( char* jobz, char* range, lapack_int* n, double* d,\n                    double* e, double* vl, double* vu, lapack_int* il,\n                    lapack_int* iu, double* abstol, lapack_int* m, double* w,\n                    double* z, lapack_int* ldz, lapack_int* isuppz,\n                    double* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_sgees( char* jobvs, char* sort, LAPACK_S_SELECT2 select,\n                   lapack_int* n, float* a, lapack_int* lda, lapack_int* sdim,\n                   float* wr, float* wi, float* vs, lapack_int* ldvs,\n                   float* work, lapack_int* lwork, lapack_logical* bwork,\n                   lapack_int *info );\nvoid LAPACK_dgees( char* jobvs, char* sort, LAPACK_D_SELECT2 select,\n                   lapack_int* n, double* a, lapack_int* lda, lapack_int* sdim,\n                   double* wr, double* wi, double* vs, lapack_int* ldvs,\n                   double* work, lapack_int* lwork, lapack_logical* bwork,\n                   lapack_int *info );\nvoid LAPACK_cgees( char* jobvs, char* sort, LAPACK_C_SELECT1 select,\n                   lapack_int* n, lapack_complex_float* a, lapack_int* lda,\n                   lapack_int* sdim, lapack_complex_float* w,\n                   lapack_complex_float* vs, lapack_int* ldvs,\n                   lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                   lapack_logical* bwork, lapack_int *info );\nvoid LAPACK_zgees( char* jobvs, char* sort, LAPACK_Z_SELECT1 select,\n                   lapack_int* n, lapack_complex_double* a, lapack_int* lda,\n                   lapack_int* sdim, lapack_complex_double* w,\n                   lapack_complex_double* vs, lapack_int* ldvs,\n                   lapack_complex_double* work, lapack_int* lwork,\n                   double* rwork, lapack_logical* bwork, lapack_int *info );\nvoid LAPACK_sgeesx( char* jobvs, char* sort, LAPACK_S_SELECT2 select,\n                    char* sense, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int* sdim, float* wr, float* wi, float* vs,\n                    lapack_int* ldvs, float* rconde, float* rcondv, float* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_logical* bwork, lapack_int *info );\nvoid LAPACK_dgeesx( char* jobvs, char* sort, LAPACK_D_SELECT2 select,\n                    char* sense, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int* sdim, double* wr, double* wi, double* vs,\n                    lapack_int* ldvs, double* rconde, double* rcondv,\n                    double* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_logical* bwork,\n                    lapack_int *info );\nvoid LAPACK_cgeesx( char* jobvs, char* sort, LAPACK_C_SELECT1 select,\n                    char* sense, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int* sdim, lapack_complex_float* w,\n                    lapack_complex_float* vs, lapack_int* ldvs, float* rconde,\n                    float* rcondv, lapack_complex_float* work,\n                    lapack_int* lwork, float* rwork, lapack_logical* bwork,\n                    lapack_int *info );\nvoid LAPACK_zgeesx( char* jobvs, char* sort, LAPACK_Z_SELECT1 select,\n                    char* sense, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* sdim, lapack_complex_double* w,\n                    lapack_complex_double* vs, lapack_int* ldvs, double* rconde,\n                    double* rcondv, lapack_complex_double* work,\n                    lapack_int* lwork, double* rwork, lapack_logical* bwork,\n                    lapack_int *info );\nvoid LAPACK_sgeev( char* jobvl, char* jobvr, lapack_int* n, float* a,\n                   lapack_int* lda, float* wr, float* wi, float* vl,\n                   lapack_int* ldvl, float* vr, lapack_int* ldvr, float* work,\n                   lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dgeev( char* jobvl, char* jobvr, lapack_int* n, double* a,\n                   lapack_int* lda, double* wr, double* wi, double* vl,\n                   lapack_int* ldvl, double* vr, lapack_int* ldvr, double* work,\n                   lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cgeev( char* jobvl, char* jobvr, lapack_int* n,\n                   lapack_complex_float* a, lapack_int* lda,\n                   lapack_complex_float* w, lapack_complex_float* vl,\n                   lapack_int* ldvl, lapack_complex_float* vr, lapack_int* ldvr,\n                   lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                   lapack_int *info );\nvoid LAPACK_zgeev( char* jobvl, char* jobvr, lapack_int* n,\n                   lapack_complex_double* a, lapack_int* lda,\n                   lapack_complex_double* w, lapack_complex_double* vl,\n                   lapack_int* ldvl, lapack_complex_double* vr,\n                   lapack_int* ldvr, lapack_complex_double* work,\n                   lapack_int* lwork, double* rwork, lapack_int *info );\nvoid LAPACK_sgeevx( char* balanc, char* jobvl, char* jobvr, char* sense,\n                    lapack_int* n, float* a, lapack_int* lda, float* wr,\n                    float* wi, float* vl, lapack_int* ldvl, float* vr,\n                    lapack_int* ldvr, lapack_int* ilo, lapack_int* ihi,\n                    float* scale, float* abnrm, float* rconde, float* rcondv,\n                    float* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_dgeevx( char* balanc, char* jobvl, char* jobvr, char* sense,\n                    lapack_int* n, double* a, lapack_int* lda, double* wr,\n                    double* wi, double* vl, lapack_int* ldvl, double* vr,\n                    lapack_int* ldvr, lapack_int* ilo, lapack_int* ihi,\n                    double* scale, double* abnrm, double* rconde,\n                    double* rcondv, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cgeevx( char* balanc, char* jobvl, char* jobvr, char* sense,\n                    lapack_int* n, lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* w, lapack_complex_float* vl,\n                    lapack_int* ldvl, lapack_complex_float* vr,\n                    lapack_int* ldvr, lapack_int* ilo, lapack_int* ihi,\n                    float* scale, float* abnrm, float* rconde, float* rcondv,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zgeevx( char* balanc, char* jobvl, char* jobvr, char* sense,\n                    lapack_int* n, lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* w, lapack_complex_double* vl,\n                    lapack_int* ldvl, lapack_complex_double* vr,\n                    lapack_int* ldvr, lapack_int* ilo, lapack_int* ihi,\n                    double* scale, double* abnrm, double* rconde,\n                    double* rcondv, lapack_complex_double* work,\n                    lapack_int* lwork, double* rwork, lapack_int *info );\nvoid LAPACK_sgesvd( char* jobu, char* jobvt, lapack_int* m, lapack_int* n,\n                    float* a, lapack_int* lda, float* s, float* u,\n                    lapack_int* ldu, float* vt, lapack_int* ldvt, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dgesvd( char* jobu, char* jobvt, lapack_int* m, lapack_int* n,\n                    double* a, lapack_int* lda, double* s, double* u,\n                    lapack_int* ldu, double* vt, lapack_int* ldvt, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cgesvd( char* jobu, char* jobvt, lapack_int* m, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda, float* s,\n                    lapack_complex_float* u, lapack_int* ldu,\n                    lapack_complex_float* vt, lapack_int* ldvt,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int *info );\nvoid LAPACK_zgesvd( char* jobu, char* jobvt, lapack_int* m, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda, double* s,\n                    lapack_complex_double* u, lapack_int* ldu,\n                    lapack_complex_double* vt, lapack_int* ldvt,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int *info );\nvoid LAPACK_sgesdd( char* jobz, lapack_int* m, lapack_int* n, float* a,\n                    lapack_int* lda, float* s, float* u, lapack_int* ldu,\n                    float* vt, lapack_int* ldvt, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dgesdd( char* jobz, lapack_int* m, lapack_int* n, double* a,\n                    lapack_int* lda, double* s, double* u, lapack_int* ldu,\n                    double* vt, lapack_int* ldvt, double* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cgesdd( char* jobz, lapack_int* m, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda, float* s,\n                    lapack_complex_float* u, lapack_int* ldu,\n                    lapack_complex_float* vt, lapack_int* ldvt,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_zgesdd( char* jobz, lapack_int* m, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda, double* s,\n                    lapack_complex_double* u, lapack_int* ldu,\n                    lapack_complex_double* vt, lapack_int* ldvt,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dgejsv( char* joba, char* jobu, char* jobv, char* jobr, char* jobt,\n                    char* jobp, lapack_int* m, lapack_int* n, double* a,\n                    lapack_int* lda, double* sva, double* u, lapack_int* ldu,\n                    double* v, lapack_int* ldv, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_sgejsv( char* joba, char* jobu, char* jobv, char* jobr, char* jobt,\n                    char* jobp, lapack_int* m, lapack_int* n, float* a,\n                    lapack_int* lda, float* sva, float* u, lapack_int* ldu,\n                    float* v, lapack_int* ldv, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dgesvj( char* joba, char* jobu, char* jobv, lapack_int* m,\n                    lapack_int* n, double* a, lapack_int* lda, double* sva,\n                    lapack_int* mv, double* v, lapack_int* ldv, double* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sgesvj( char* joba, char* jobu, char* jobv, lapack_int* m,\n                    lapack_int* n, float* a, lapack_int* lda, float* sva,\n                    lapack_int* mv, float* v, lapack_int* ldv, float* work,\n                    lapack_int* lwork, lapack_int *info );\nvoid LAPACK_sggsvd( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* n, lapack_int* p, lapack_int* k, lapack_int* l,\n                    float* a, lapack_int* lda, float* b, lapack_int* ldb,\n                    float* alpha, float* beta, float* u, lapack_int* ldu,\n                    float* v, lapack_int* ldv, float* q, lapack_int* ldq,\n                    float* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_dggsvd( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* n, lapack_int* p, lapack_int* k, lapack_int* l,\n                    double* a, lapack_int* lda, double* b, lapack_int* ldb,\n                    double* alpha, double* beta, double* u, lapack_int* ldu,\n                    double* v, lapack_int* ldv, double* q, lapack_int* ldq,\n                    double* work, lapack_int* iwork, lapack_int *info );\nvoid LAPACK_cggsvd( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* n, lapack_int* p, lapack_int* k, lapack_int* l,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb, float* alpha,\n                    float* beta, lapack_complex_float* u, lapack_int* ldu,\n                    lapack_complex_float* v, lapack_int* ldv,\n                    lapack_complex_float* q, lapack_int* ldq,\n                    lapack_complex_float* work, float* rwork, lapack_int* iwork,\n                    lapack_int *info );\nvoid LAPACK_zggsvd( char* jobu, char* jobv, char* jobq, lapack_int* m,\n                    lapack_int* n, lapack_int* p, lapack_int* k, lapack_int* l,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb, double* alpha,\n                    double* beta, lapack_complex_double* u, lapack_int* ldu,\n                    lapack_complex_double* v, lapack_int* ldv,\n                    lapack_complex_double* q, lapack_int* ldq,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int* iwork, lapack_int *info );\nvoid LAPACK_ssygv( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                   float* a, lapack_int* lda, float* b, lapack_int* ldb,\n                   float* w, float* work, lapack_int* lwork, lapack_int *info );\nvoid LAPACK_dsygv( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                   double* a, lapack_int* lda, double* b, lapack_int* ldb,\n                   double* w, double* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_chegv( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                   lapack_complex_float* a, lapack_int* lda,\n                   lapack_complex_float* b, lapack_int* ldb, float* w,\n                   lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                   lapack_int *info );\nvoid LAPACK_zhegv( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                   lapack_complex_double* a, lapack_int* lda,\n                   lapack_complex_double* b, lapack_int* ldb, double* w,\n                   lapack_complex_double* work, lapack_int* lwork,\n                   double* rwork, lapack_int *info );\nvoid LAPACK_ssygvd( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                    float* a, lapack_int* lda, float* b, lapack_int* ldb,\n                    float* w, float* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dsygvd( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                    double* a, lapack_int* lda, double* b, lapack_int* ldb,\n                    double* w, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_chegvd( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb, float* w,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int* lrwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_zhegvd( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb, double* w,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* lrwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_ssygvx( lapack_int* itype, char* jobz, char* range, char* uplo,\n                    lapack_int* n, float* a, lapack_int* lda, float* b,\n                    lapack_int* ldb, float* vl, float* vu, lapack_int* il,\n                    lapack_int* iu, float* abstol, lapack_int* m, float* w,\n                    float* z, lapack_int* ldz, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* ifail, lapack_int *info );\nvoid LAPACK_dsygvx( lapack_int* itype, char* jobz, char* range, char* uplo,\n                    lapack_int* n, double* a, lapack_int* lda, double* b,\n                    lapack_int* ldb, double* vl, double* vu, lapack_int* il,\n                    lapack_int* iu, double* abstol, lapack_int* m, double* w,\n                    double* z, lapack_int* ldz, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* ifail, lapack_int *info );\nvoid LAPACK_chegvx( lapack_int* itype, char* jobz, char* range, char* uplo,\n                    lapack_int* n, lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb, float* vl,\n                    float* vu, lapack_int* il, lapack_int* iu, float* abstol,\n                    lapack_int* m, float* w, lapack_complex_float* z,\n                    lapack_int* ldz, lapack_complex_float* work,\n                    lapack_int* lwork, float* rwork, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_zhegvx( lapack_int* itype, char* jobz, char* range, char* uplo,\n                    lapack_int* n, lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb, double* vl,\n                    double* vu, lapack_int* il, lapack_int* iu, double* abstol,\n                    lapack_int* m, double* w, lapack_complex_double* z,\n                    lapack_int* ldz, lapack_complex_double* work,\n                    lapack_int* lwork, double* rwork, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_sspgv( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                   float* ap, float* bp, float* w, float* z, lapack_int* ldz,\n                   float* work, lapack_int *info );\nvoid LAPACK_dspgv( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                   double* ap, double* bp, double* w, double* z,\n                   lapack_int* ldz, double* work, lapack_int *info );\nvoid LAPACK_chpgv( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                   lapack_complex_float* ap, lapack_complex_float* bp, float* w,\n                   lapack_complex_float* z, lapack_int* ldz,\n                   lapack_complex_float* work, float* rwork, lapack_int *info );\nvoid LAPACK_zhpgv( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                   lapack_complex_double* ap, lapack_complex_double* bp,\n                   double* w, lapack_complex_double* z, lapack_int* ldz,\n                   lapack_complex_double* work, double* rwork,\n                   lapack_int *info );\nvoid LAPACK_sspgvd( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                    float* ap, float* bp, float* w, float* z, lapack_int* ldz,\n                    float* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dspgvd( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                    double* ap, double* bp, double* w, double* z,\n                    lapack_int* ldz, double* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_int* liwork, lapack_int *info );\nvoid LAPACK_chpgvd( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                    lapack_complex_float* ap, lapack_complex_float* bp,\n                    float* w, lapack_complex_float* z, lapack_int* ldz,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int* lrwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_zhpgvd( lapack_int* itype, char* jobz, char* uplo, lapack_int* n,\n                    lapack_complex_double* ap, lapack_complex_double* bp,\n                    double* w, lapack_complex_double* z, lapack_int* ldz,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* lrwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_sspgvx( lapack_int* itype, char* jobz, char* range, char* uplo,\n                    lapack_int* n, float* ap, float* bp, float* vl, float* vu,\n                    lapack_int* il, lapack_int* iu, float* abstol,\n                    lapack_int* m, float* w, float* z, lapack_int* ldz,\n                    float* work, lapack_int* iwork, lapack_int* ifail,\n                    lapack_int *info );\nvoid LAPACK_dspgvx( lapack_int* itype, char* jobz, char* range, char* uplo,\n                    lapack_int* n, double* ap, double* bp, double* vl,\n                    double* vu, lapack_int* il, lapack_int* iu, double* abstol,\n                    lapack_int* m, double* w, double* z, lapack_int* ldz,\n                    double* work, lapack_int* iwork, lapack_int* ifail,\n                    lapack_int *info );\nvoid LAPACK_chpgvx( lapack_int* itype, char* jobz, char* range, char* uplo,\n                    lapack_int* n, lapack_complex_float* ap,\n                    lapack_complex_float* bp, float* vl, float* vu,\n                    lapack_int* il, lapack_int* iu, float* abstol,\n                    lapack_int* m, float* w, lapack_complex_float* z,\n                    lapack_int* ldz, lapack_complex_float* work, float* rwork,\n                    lapack_int* iwork, lapack_int* ifail, lapack_int *info );\nvoid LAPACK_zhpgvx( lapack_int* itype, char* jobz, char* range, char* uplo,\n                    lapack_int* n, lapack_complex_double* ap,\n                    lapack_complex_double* bp, double* vl, double* vu,\n                    lapack_int* il, lapack_int* iu, double* abstol,\n                    lapack_int* m, double* w, lapack_complex_double* z,\n                    lapack_int* ldz, lapack_complex_double* work, double* rwork,\n                    lapack_int* iwork, lapack_int* ifail, lapack_int *info );\nvoid LAPACK_ssbgv( char* jobz, char* uplo, lapack_int* n, lapack_int* ka,\n                   lapack_int* kb, float* ab, lapack_int* ldab, float* bb,\n                   lapack_int* ldbb, float* w, float* z, lapack_int* ldz,\n                   float* work, lapack_int *info );\nvoid LAPACK_dsbgv( char* jobz, char* uplo, lapack_int* n, lapack_int* ka,\n                   lapack_int* kb, double* ab, lapack_int* ldab, double* bb,\n                   lapack_int* ldbb, double* w, double* z, lapack_int* ldz,\n                   double* work, lapack_int *info );\nvoid LAPACK_chbgv( char* jobz, char* uplo, lapack_int* n, lapack_int* ka,\n                   lapack_int* kb, lapack_complex_float* ab, lapack_int* ldab,\n                   lapack_complex_float* bb, lapack_int* ldbb, float* w,\n                   lapack_complex_float* z, lapack_int* ldz,\n                   lapack_complex_float* work, float* rwork, lapack_int *info );\nvoid LAPACK_zhbgv( char* jobz, char* uplo, lapack_int* n, lapack_int* ka,\n                   lapack_int* kb, lapack_complex_double* ab, lapack_int* ldab,\n                   lapack_complex_double* bb, lapack_int* ldbb, double* w,\n                   lapack_complex_double* z, lapack_int* ldz,\n                   lapack_complex_double* work, double* rwork,\n                   lapack_int *info );\nvoid LAPACK_ssbgvd( char* jobz, char* uplo, lapack_int* n, lapack_int* ka,\n                    lapack_int* kb, float* ab, lapack_int* ldab, float* bb,\n                    lapack_int* ldbb, float* w, float* z, lapack_int* ldz,\n                    float* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_dsbgvd( char* jobz, char* uplo, lapack_int* n, lapack_int* ka,\n                    lapack_int* kb, double* ab, lapack_int* ldab, double* bb,\n                    lapack_int* ldbb, double* w, double* z, lapack_int* ldz,\n                    double* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_chbgvd( char* jobz, char* uplo, lapack_int* n, lapack_int* ka,\n                    lapack_int* kb, lapack_complex_float* ab, lapack_int* ldab,\n                    lapack_complex_float* bb, lapack_int* ldbb, float* w,\n                    lapack_complex_float* z, lapack_int* ldz,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int* lrwork, lapack_int* iwork, lapack_int* liwork,\n                    lapack_int *info );\nvoid LAPACK_zhbgvd( char* jobz, char* uplo, lapack_int* n, lapack_int* ka,\n                    lapack_int* kb, lapack_complex_double* ab, lapack_int* ldab,\n                    lapack_complex_double* bb, lapack_int* ldbb, double* w,\n                    lapack_complex_double* z, lapack_int* ldz,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* lrwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_int *info );\nvoid LAPACK_ssbgvx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_int* ka, lapack_int* kb, float* ab, lapack_int* ldab,\n                    float* bb, lapack_int* ldbb, float* q, lapack_int* ldq,\n                    float* vl, float* vu, lapack_int* il, lapack_int* iu,\n                    float* abstol, lapack_int* m, float* w, float* z,\n                    lapack_int* ldz, float* work, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_dsbgvx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_int* ka, lapack_int* kb, double* ab,\n                    lapack_int* ldab, double* bb, lapack_int* ldbb, double* q,\n                    lapack_int* ldq, double* vl, double* vu, lapack_int* il,\n                    lapack_int* iu, double* abstol, lapack_int* m, double* w,\n                    double* z, lapack_int* ldz, double* work, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_chbgvx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_int* ka, lapack_int* kb, lapack_complex_float* ab,\n                    lapack_int* ldab, lapack_complex_float* bb,\n                    lapack_int* ldbb, lapack_complex_float* q, lapack_int* ldq,\n                    float* vl, float* vu, lapack_int* il, lapack_int* iu,\n                    float* abstol, lapack_int* m, float* w,\n                    lapack_complex_float* z, lapack_int* ldz,\n                    lapack_complex_float* work, float* rwork, lapack_int* iwork,\n                    lapack_int* ifail, lapack_int *info );\nvoid LAPACK_zhbgvx( char* jobz, char* range, char* uplo, lapack_int* n,\n                    lapack_int* ka, lapack_int* kb, lapack_complex_double* ab,\n                    lapack_int* ldab, lapack_complex_double* bb,\n                    lapack_int* ldbb, lapack_complex_double* q, lapack_int* ldq,\n                    double* vl, double* vu, lapack_int* il, lapack_int* iu,\n                    double* abstol, lapack_int* m, double* w,\n                    lapack_complex_double* z, lapack_int* ldz,\n                    lapack_complex_double* work, double* rwork,\n                    lapack_int* iwork, lapack_int* ifail, lapack_int *info );\nvoid LAPACK_sgges( char* jobvsl, char* jobvsr, char* sort,\n                   LAPACK_S_SELECT3 selctg, lapack_int* n, float* a,\n                   lapack_int* lda, float* b, lapack_int* ldb, lapack_int* sdim,\n                   float* alphar, float* alphai, float* beta, float* vsl,\n                   lapack_int* ldvsl, float* vsr, lapack_int* ldvsr,\n                   float* work, lapack_int* lwork, lapack_logical* bwork,\n                   lapack_int *info );\nvoid LAPACK_dgges( char* jobvsl, char* jobvsr, char* sort,\n                   LAPACK_D_SELECT3 selctg, lapack_int* n, double* a,\n                   lapack_int* lda, double* b, lapack_int* ldb,\n                   lapack_int* sdim, double* alphar, double* alphai,\n                   double* beta, double* vsl, lapack_int* ldvsl, double* vsr,\n                   lapack_int* ldvsr, double* work, lapack_int* lwork,\n                   lapack_logical* bwork, lapack_int *info );\nvoid LAPACK_cgges( char* jobvsl, char* jobvsr, char* sort,\n                   LAPACK_C_SELECT2 selctg, lapack_int* n,\n                   lapack_complex_float* a, lapack_int* lda,\n                   lapack_complex_float* b, lapack_int* ldb, lapack_int* sdim,\n                   lapack_complex_float* alpha, lapack_complex_float* beta,\n                   lapack_complex_float* vsl, lapack_int* ldvsl,\n                   lapack_complex_float* vsr, lapack_int* ldvsr,\n                   lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                   lapack_logical* bwork, lapack_int *info );\nvoid LAPACK_zgges( char* jobvsl, char* jobvsr, char* sort,\n                   LAPACK_Z_SELECT2 selctg, lapack_int* n,\n                   lapack_complex_double* a, lapack_int* lda,\n                   lapack_complex_double* b, lapack_int* ldb, lapack_int* sdim,\n                   lapack_complex_double* alpha, lapack_complex_double* beta,\n                   lapack_complex_double* vsl, lapack_int* ldvsl,\n                   lapack_complex_double* vsr, lapack_int* ldvsr,\n                   lapack_complex_double* work, lapack_int* lwork,\n                   double* rwork, lapack_logical* bwork, lapack_int *info );\nvoid LAPACK_sggesx( char* jobvsl, char* jobvsr, char* sort,\n                    LAPACK_S_SELECT3 selctg, char* sense, lapack_int* n,\n                    float* a, lapack_int* lda, float* b, lapack_int* ldb,\n                    lapack_int* sdim, float* alphar, float* alphai, float* beta,\n                    float* vsl, lapack_int* ldvsl, float* vsr,\n                    lapack_int* ldvsr, float* rconde, float* rcondv,\n                    float* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_logical* bwork,\n                    lapack_int *info );\nvoid LAPACK_dggesx( char* jobvsl, char* jobvsr, char* sort,\n                    LAPACK_D_SELECT3 selctg, char* sense, lapack_int* n,\n                    double* a, lapack_int* lda, double* b, lapack_int* ldb,\n                    lapack_int* sdim, double* alphar, double* alphai,\n                    double* beta, double* vsl, lapack_int* ldvsl, double* vsr,\n                    lapack_int* ldvsr, double* rconde, double* rcondv,\n                    double* work, lapack_int* lwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_logical* bwork,\n                    lapack_int *info );\nvoid LAPACK_cggesx( char* jobvsl, char* jobvsr, char* sort,\n                    LAPACK_C_SELECT2 selctg, char* sense, lapack_int* n,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb, lapack_int* sdim,\n                    lapack_complex_float* alpha, lapack_complex_float* beta,\n                    lapack_complex_float* vsl, lapack_int* ldvsl,\n                    lapack_complex_float* vsr, lapack_int* ldvsr, float* rconde,\n                    float* rcondv, lapack_complex_float* work,\n                    lapack_int* lwork, float* rwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_logical* bwork,\n                    lapack_int *info );\nvoid LAPACK_zggesx( char* jobvsl, char* jobvsr, char* sort,\n                    LAPACK_Z_SELECT2 selctg, char* sense, lapack_int* n,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb, lapack_int* sdim,\n                    lapack_complex_double* alpha, lapack_complex_double* beta,\n                    lapack_complex_double* vsl, lapack_int* ldvsl,\n                    lapack_complex_double* vsr, lapack_int* ldvsr,\n                    double* rconde, double* rcondv, lapack_complex_double* work,\n                    lapack_int* lwork, double* rwork, lapack_int* iwork,\n                    lapack_int* liwork, lapack_logical* bwork,\n                    lapack_int *info );\nvoid LAPACK_sggev( char* jobvl, char* jobvr, lapack_int* n, float* a,\n                   lapack_int* lda, float* b, lapack_int* ldb, float* alphar,\n                   float* alphai, float* beta, float* vl, lapack_int* ldvl,\n                   float* vr, lapack_int* ldvr, float* work, lapack_int* lwork,\n                   lapack_int *info );\nvoid LAPACK_dggev( char* jobvl, char* jobvr, lapack_int* n, double* a,\n                   lapack_int* lda, double* b, lapack_int* ldb, double* alphar,\n                   double* alphai, double* beta, double* vl, lapack_int* ldvl,\n                   double* vr, lapack_int* ldvr, double* work,\n                   lapack_int* lwork, lapack_int *info );\nvoid LAPACK_cggev( char* jobvl, char* jobvr, lapack_int* n,\n                   lapack_complex_float* a, lapack_int* lda,\n                   lapack_complex_float* b, lapack_int* ldb,\n                   lapack_complex_float* alpha, lapack_complex_float* beta,\n                   lapack_complex_float* vl, lapack_int* ldvl,\n                   lapack_complex_float* vr, lapack_int* ldvr,\n                   lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                   lapack_int *info );\nvoid LAPACK_zggev( char* jobvl, char* jobvr, lapack_int* n,\n                   lapack_complex_double* a, lapack_int* lda,\n                   lapack_complex_double* b, lapack_int* ldb,\n                   lapack_complex_double* alpha, lapack_complex_double* beta,\n                   lapack_complex_double* vl, lapack_int* ldvl,\n                   lapack_complex_double* vr, lapack_int* ldvr,\n                   lapack_complex_double* work, lapack_int* lwork,\n                   double* rwork, lapack_int *info );\nvoid LAPACK_sggevx( char* balanc, char* jobvl, char* jobvr, char* sense,\n                    lapack_int* n, float* a, lapack_int* lda, float* b,\n                    lapack_int* ldb, float* alphar, float* alphai, float* beta,\n                    float* vl, lapack_int* ldvl, float* vr, lapack_int* ldvr,\n                    lapack_int* ilo, lapack_int* ihi, float* lscale,\n                    float* rscale, float* abnrm, float* bbnrm, float* rconde,\n                    float* rcondv, float* work, lapack_int* lwork,\n                    lapack_int* iwork, lapack_logical* bwork,\n                    lapack_int *info );\nvoid LAPACK_dggevx( char* balanc, char* jobvl, char* jobvr, char* sense,\n                    lapack_int* n, double* a, lapack_int* lda, double* b,\n                    lapack_int* ldb, double* alphar, double* alphai,\n                    double* beta, double* vl, lapack_int* ldvl, double* vr,\n                    lapack_int* ldvr, lapack_int* ilo, lapack_int* ihi,\n                    double* lscale, double* rscale, double* abnrm,\n                    double* bbnrm, double* rconde, double* rcondv, double* work,\n                    lapack_int* lwork, lapack_int* iwork, lapack_logical* bwork,\n                    lapack_int *info );\nvoid LAPACK_cggevx( char* balanc, char* jobvl, char* jobvr, char* sense,\n                    lapack_int* n, lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    lapack_complex_float* alpha, lapack_complex_float* beta,\n                    lapack_complex_float* vl, lapack_int* ldvl,\n                    lapack_complex_float* vr, lapack_int* ldvr, lapack_int* ilo,\n                    lapack_int* ihi, float* lscale, float* rscale, float* abnrm,\n                    float* bbnrm, float* rconde, float* rcondv,\n                    lapack_complex_float* work, lapack_int* lwork, float* rwork,\n                    lapack_int* iwork, lapack_logical* bwork,\n                    lapack_int *info );\nvoid LAPACK_zggevx( char* balanc, char* jobvl, char* jobvr, char* sense,\n                    lapack_int* n, lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* alpha, lapack_complex_double* beta,\n                    lapack_complex_double* vl, lapack_int* ldvl,\n                    lapack_complex_double* vr, lapack_int* ldvr,\n                    lapack_int* ilo, lapack_int* ihi, double* lscale,\n                    double* rscale, double* abnrm, double* bbnrm,\n                    double* rconde, double* rcondv, lapack_complex_double* work,\n                    lapack_int* lwork, double* rwork, lapack_int* iwork,\n                    lapack_logical* bwork, lapack_int *info );\nvoid LAPACK_dsfrk( char* transr, char* uplo, char* trans, lapack_int* n,\n                   lapack_int* k, double* alpha, const double* a,\n                   lapack_int* lda, double* beta, double* c );\nvoid LAPACK_ssfrk( char* transr, char* uplo, char* trans, lapack_int* n,\n                   lapack_int* k, float* alpha, const float* a, lapack_int* lda,\n                   float* beta, float* c );\nvoid LAPACK_zhfrk( char* transr, char* uplo, char* trans, lapack_int* n,\n                   lapack_int* k, double* alpha, const lapack_complex_double* a,\n                   lapack_int* lda, double* beta, lapack_complex_double* c );\nvoid LAPACK_chfrk( char* transr, char* uplo, char* trans, lapack_int* n,\n                   lapack_int* k, float* alpha, const lapack_complex_float* a,\n                   lapack_int* lda, float* beta, lapack_complex_float* c );\nvoid LAPACK_dtfsm( char* transr, char* side, char* uplo, char* trans,\n                   char* diag, lapack_int* m, lapack_int* n, double* alpha,\n                   const double* a, double* b, lapack_int* ldb );\nvoid LAPACK_stfsm( char* transr, char* side, char* uplo, char* trans,\n                   char* diag, lapack_int* m, lapack_int* n, float* alpha,\n                   const float* a, float* b, lapack_int* ldb );\nvoid LAPACK_ztfsm( char* transr, char* side, char* uplo, char* trans,\n                   char* diag, lapack_int* m, lapack_int* n,\n                   lapack_complex_double* alpha, const lapack_complex_double* a,\n                   lapack_complex_double* b, lapack_int* ldb );\nvoid LAPACK_ctfsm( char* transr, char* side, char* uplo, char* trans,\n                   char* diag, lapack_int* m, lapack_int* n,\n                   lapack_complex_float* alpha, const lapack_complex_float* a,\n                   lapack_complex_float* b, lapack_int* ldb );\nvoid LAPACK_dtfttp( char* transr, char* uplo, lapack_int* n, const double* arf,\n                    double* ap, lapack_int *info );\nvoid LAPACK_stfttp( char* transr, char* uplo, lapack_int* n, const float* arf,\n                    float* ap, lapack_int *info );\nvoid LAPACK_ztfttp( char* transr, char* uplo, lapack_int* n,\n                    const lapack_complex_double* arf, lapack_complex_double* ap,\n                    lapack_int *info );\nvoid LAPACK_ctfttp( char* transr, char* uplo, lapack_int* n,\n                    const lapack_complex_float* arf, lapack_complex_float* ap,\n                    lapack_int *info );\nvoid LAPACK_dtfttr( char* transr, char* uplo, lapack_int* n, const double* arf,\n                    double* a, lapack_int* lda, lapack_int *info );\nvoid LAPACK_stfttr( char* transr, char* uplo, lapack_int* n, const float* arf,\n                    float* a, lapack_int* lda, lapack_int *info );\nvoid LAPACK_ztfttr( char* transr, char* uplo, lapack_int* n,\n                    const lapack_complex_double* arf, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_ctfttr( char* transr, char* uplo, lapack_int* n,\n                    const lapack_complex_float* arf, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_dtpttf( char* transr, char* uplo, lapack_int* n, const double* ap,\n                    double* arf, lapack_int *info );\nvoid LAPACK_stpttf( char* transr, char* uplo, lapack_int* n, const float* ap,\n                    float* arf, lapack_int *info );\nvoid LAPACK_ztpttf( char* transr, char* uplo, lapack_int* n,\n                    const lapack_complex_double* ap, lapack_complex_double* arf,\n                    lapack_int *info );\nvoid LAPACK_ctpttf( char* transr, char* uplo, lapack_int* n,\n                    const lapack_complex_float* ap, lapack_complex_float* arf,\n                    lapack_int *info );\nvoid LAPACK_dtpttr( char* uplo, lapack_int* n, const double* ap, double* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_stpttr( char* uplo, lapack_int* n, const float* ap, float* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_ztpttr( char* uplo, lapack_int* n, const lapack_complex_double* ap,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_ctpttr( char* uplo, lapack_int* n, const lapack_complex_float* ap,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_dtrttf( char* transr, char* uplo, lapack_int* n, const double* a,\n                    lapack_int* lda, double* arf, lapack_int *info );\nvoid LAPACK_strttf( char* transr, char* uplo, lapack_int* n, const float* a,\n                    lapack_int* lda, float* arf, lapack_int *info );\nvoid LAPACK_ztrttf( char* transr, char* uplo, lapack_int* n,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* arf, lapack_int *info );\nvoid LAPACK_ctrttf( char* transr, char* uplo, lapack_int* n,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* arf, lapack_int *info );\nvoid LAPACK_dtrttp( char* uplo, lapack_int* n, const double* a, lapack_int* lda,\n                    double* ap, lapack_int *info );\nvoid LAPACK_strttp( char* uplo, lapack_int* n, const float* a, lapack_int* lda,\n                    float* ap, lapack_int *info );\nvoid LAPACK_ztrttp( char* uplo, lapack_int* n, const lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* ap,\n                    lapack_int *info );\nvoid LAPACK_ctrttp( char* uplo, lapack_int* n, const lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* ap,\n                    lapack_int *info );\nvoid LAPACK_sgeqrfp( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                     float* tau, float* work, lapack_int* lwork,\n                     lapack_int *info );\nvoid LAPACK_dgeqrfp( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                     double* tau, double* work, lapack_int* lwork,\n                     lapack_int *info );\nvoid LAPACK_cgeqrfp( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                     lapack_int* lda, lapack_complex_float* tau,\n                     lapack_complex_float* work, lapack_int* lwork,\n                     lapack_int *info );\nvoid LAPACK_zgeqrfp( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                     lapack_int* lda, lapack_complex_double* tau,\n                     lapack_complex_double* work, lapack_int* lwork,\n                     lapack_int *info );\nvoid LAPACK_clacgv( lapack_int* n, lapack_complex_float* x, lapack_int* incx );\nvoid LAPACK_zlacgv( lapack_int* n, lapack_complex_double* x, lapack_int* incx );\nvoid LAPACK_slarnv( lapack_int* idist, lapack_int* iseed, lapack_int* n,\n                    float* x );\nvoid LAPACK_dlarnv( lapack_int* idist, lapack_int* iseed, lapack_int* n,\n                    double* x );\nvoid LAPACK_clarnv( lapack_int* idist, lapack_int* iseed, lapack_int* n,\n                    lapack_complex_float* x );\nvoid LAPACK_zlarnv( lapack_int* idist, lapack_int* iseed, lapack_int* n,\n                    lapack_complex_double* x );\nvoid LAPACK_sgeqr2( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    float* tau, float* work, lapack_int *info );\nvoid LAPACK_dgeqr2( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    double* tau, double* work, lapack_int *info );\nvoid LAPACK_cgeqr2( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* tau,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zgeqr2( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_slacpy( char* uplo, lapack_int* m, lapack_int* n, const float* a,\n                    lapack_int* lda, float* b, lapack_int* ldb );\nvoid LAPACK_dlacpy( char* uplo, lapack_int* m, lapack_int* n, const double* a,\n                    lapack_int* lda, double* b, lapack_int* ldb );\nvoid LAPACK_clacpy( char* uplo, lapack_int* m, lapack_int* n,\n                    const lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb );\nvoid LAPACK_zlacpy( char* uplo, lapack_int* m, lapack_int* n,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb );\nvoid LAPACK_sgetf2( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_dgetf2( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_cgetf2( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_zgetf2( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* ipiv, lapack_int *info );\nvoid LAPACK_slaswp( lapack_int* n, float* a, lapack_int* lda, lapack_int* k1,\n                    lapack_int* k2, const lapack_int* ipiv, lapack_int* incx );\nvoid LAPACK_dlaswp( lapack_int* n, double* a, lapack_int* lda, lapack_int* k1,\n                    lapack_int* k2, const lapack_int* ipiv, lapack_int* incx );\nvoid LAPACK_claswp( lapack_int* n, lapack_complex_float* a, lapack_int* lda,\n                    lapack_int* k1, lapack_int* k2, const lapack_int* ipiv,\n                    lapack_int* incx );\nvoid LAPACK_zlaswp( lapack_int* n, lapack_complex_double* a, lapack_int* lda,\n                    lapack_int* k1, lapack_int* k2, const lapack_int* ipiv,\n                    lapack_int* incx );\nfloat LAPACK_slange( char* norm, lapack_int* m, lapack_int* n, const float* a,\n                    lapack_int* lda, float* work );\ndouble LAPACK_dlange( char* norm, lapack_int* m, lapack_int* n, const double* a,\n                    lapack_int* lda, double* work );\nfloat LAPACK_clange( char* norm, lapack_int* m, lapack_int* n,\n                    const lapack_complex_float* a, lapack_int* lda, float* work );\ndouble LAPACK_zlange( char* norm, lapack_int* m, lapack_int* n,\n                    const lapack_complex_double* a, lapack_int* lda, double* work );\nfloat LAPACK_clanhe( char* norm, char* uplo, lapack_int* n,\n                    const lapack_complex_float* a, lapack_int* lda, float* work );\ndouble LAPACK_zlanhe( char* norm, char* uplo, lapack_int* n,\n                    const lapack_complex_double* a, lapack_int* lda, double* work );\nfloat LAPACK_slansy( char* norm, char* uplo, lapack_int* n, const float* a,\n                    lapack_int* lda, float* work );\ndouble LAPACK_dlansy( char* norm, char* uplo, lapack_int* n, const double* a,\n                    lapack_int* lda, double* work );\nfloat LAPACK_clansy( char* norm, char* uplo, lapack_int* n,\n                    const lapack_complex_float* a, lapack_int* lda, float* work );\ndouble LAPACK_zlansy( char* norm, char* uplo, lapack_int* n,\n                    const lapack_complex_double* a, lapack_int* lda, double* work );\nfloat LAPACK_slantr( char* norm, char* uplo, char* diag, lapack_int* m,\n                    lapack_int* n, const float* a, lapack_int* lda, float* work );\ndouble LAPACK_dlantr( char* norm, char* uplo, char* diag, lapack_int* m,\n                    lapack_int* n, const double* a, lapack_int* lda, double* work );\nfloat LAPACK_clantr( char* norm, char* uplo, char* diag, lapack_int* m,\n                    lapack_int* n, const lapack_complex_float* a, lapack_int* lda,\n                    float* work );\ndouble LAPACK_zlantr( char* norm, char* uplo, char* diag, lapack_int* m,\n                    lapack_int* n, const lapack_complex_double* a, lapack_int* lda,\n                    double* work );\nfloat LAPACK_slamch( char* cmach );\ndouble LAPACK_dlamch( char* cmach );\nvoid LAPACK_sgelq2( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                    float* tau, float* work, lapack_int *info );\nvoid LAPACK_dgelq2( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                    double* tau, double* work, lapack_int *info );\nvoid LAPACK_cgelq2( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_complex_float* tau,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zgelq2( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_complex_double* tau,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_slarfb( char* side, char* trans, char* direct, char* storev,\n                    lapack_int* m, lapack_int* n, lapack_int* k, const float* v,\n                    lapack_int* ldv, const float* t, lapack_int* ldt, float* c,\n                    lapack_int* ldc, float* work, lapack_int* ldwork );\nvoid LAPACK_dlarfb( char* side, char* trans, char* direct, char* storev,\n                    lapack_int* m, lapack_int* n, lapack_int* k,\n                    const double* v, lapack_int* ldv, const double* t,\n                    lapack_int* ldt, double* c, lapack_int* ldc, double* work,\n                    lapack_int* ldwork );\nvoid LAPACK_clarfb( char* side, char* trans, char* direct, char* storev,\n                    lapack_int* m, lapack_int* n, lapack_int* k,\n                    const lapack_complex_float* v, lapack_int* ldv,\n                    const lapack_complex_float* t, lapack_int* ldt,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    lapack_complex_float* work, lapack_int* ldwork );\nvoid LAPACK_zlarfb( char* side, char* trans, char* direct, char* storev,\n                    lapack_int* m, lapack_int* n, lapack_int* k,\n                    const lapack_complex_double* v, lapack_int* ldv,\n                    const lapack_complex_double* t, lapack_int* ldt,\n                    lapack_complex_double* c, lapack_int* ldc,\n                    lapack_complex_double* work, lapack_int* ldwork );\nvoid LAPACK_slarfg( lapack_int* n, float* alpha, float* x, lapack_int* incx,\n                    float* tau );\nvoid LAPACK_dlarfg( lapack_int* n, double* alpha, double* x, lapack_int* incx,\n                    double* tau );\nvoid LAPACK_clarfg( lapack_int* n, lapack_complex_float* alpha,\n                    lapack_complex_float* x, lapack_int* incx,\n                    lapack_complex_float* tau );\nvoid LAPACK_zlarfg( lapack_int* n, lapack_complex_double* alpha,\n                    lapack_complex_double* x, lapack_int* incx,\n                    lapack_complex_double* tau );\nvoid LAPACK_slarft( char* direct, char* storev, lapack_int* n, lapack_int* k,\n                    const float* v, lapack_int* ldv, const float* tau, float* t,\n                    lapack_int* ldt );\nvoid LAPACK_dlarft( char* direct, char* storev, lapack_int* n, lapack_int* k,\n                    const double* v, lapack_int* ldv, const double* tau,\n                    double* t, lapack_int* ldt );\nvoid LAPACK_clarft( char* direct, char* storev, lapack_int* n, lapack_int* k,\n                    const lapack_complex_float* v, lapack_int* ldv,\n                    const lapack_complex_float* tau, lapack_complex_float* t,\n                    lapack_int* ldt );\nvoid LAPACK_zlarft( char* direct, char* storev, lapack_int* n, lapack_int* k,\n                    const lapack_complex_double* v, lapack_int* ldv,\n                    const lapack_complex_double* tau, lapack_complex_double* t,\n                    lapack_int* ldt );\nvoid LAPACK_slarfx( char* side, lapack_int* m, lapack_int* n, const float* v,\n                    float* tau, float* c, lapack_int* ldc, float* work );\nvoid LAPACK_dlarfx( char* side, lapack_int* m, lapack_int* n, const double* v,\n                    double* tau, double* c, lapack_int* ldc, double* work );\nvoid LAPACK_clarfx( char* side, lapack_int* m, lapack_int* n,\n                    const lapack_complex_float* v, lapack_complex_float* tau,\n                    lapack_complex_float* c, lapack_int* ldc,\n                    lapack_complex_float* work );\nvoid LAPACK_zlarfx( char* side, lapack_int* m, lapack_int* n,\n                    const lapack_complex_double* v, lapack_complex_double* tau,\n                    lapack_complex_double* c, lapack_int* ldc,\n                    lapack_complex_double* work );\nvoid LAPACK_slatms( lapack_int* m, lapack_int* n, char* dist, lapack_int* iseed,\n                    char* sym, float* d, lapack_int* mode, float* cond,\n                    float* dmax, lapack_int* kl, lapack_int* ku, char* pack,\n                    float* a, lapack_int* lda, float* work, lapack_int *info );\nvoid LAPACK_dlatms( lapack_int* m, lapack_int* n, char* dist, lapack_int* iseed,\n                    char* sym, double* d, lapack_int* mode, double* cond,\n                    double* dmax, lapack_int* kl, lapack_int* ku, char* pack,\n                    double* a, lapack_int* lda, double* work,\n                    lapack_int *info );\nvoid LAPACK_clatms( lapack_int* m, lapack_int* n, char* dist, lapack_int* iseed,\n                    char* sym, float* d, lapack_int* mode, float* cond,\n                    float* dmax, lapack_int* kl, lapack_int* ku, char* pack,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zlatms( lapack_int* m, lapack_int* n, char* dist, lapack_int* iseed,\n                    char* sym, double* d, lapack_int* mode, double* cond,\n                    double* dmax, lapack_int* kl, lapack_int* ku, char* pack,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_slag2d( lapack_int* m, lapack_int* n, const float* sa,\n                    lapack_int* ldsa, double* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_dlag2s( lapack_int* m, lapack_int* n, const double* a,\n                    lapack_int* lda, float* sa, lapack_int* ldsa,\n                    lapack_int *info );\nvoid LAPACK_clag2z( lapack_int* m, lapack_int* n,\n                    const lapack_complex_float* sa, lapack_int* ldsa,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_zlag2c( lapack_int* m, lapack_int* n,\n                    const lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_float* sa, lapack_int* ldsa,\n                    lapack_int *info );\nvoid LAPACK_slauum( char* uplo, lapack_int* n, float* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_dlauum( char* uplo, lapack_int* n, double* a, lapack_int* lda,\n                    lapack_int *info );\nvoid LAPACK_clauum( char* uplo, lapack_int* n, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_zlauum( char* uplo, lapack_int* n, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int *info );\nvoid LAPACK_slagge( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, const float* d, float* a, lapack_int* lda,\n                    lapack_int* iseed, float* work, lapack_int *info );\nvoid LAPACK_dlagge( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, const double* d, double* a, lapack_int* lda,\n                    lapack_int* iseed, double* work, lapack_int *info );\nvoid LAPACK_clagge( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, const float* d, lapack_complex_float* a,\n                    lapack_int* lda, lapack_int* iseed,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zlagge( lapack_int* m, lapack_int* n, lapack_int* kl,\n                    lapack_int* ku, const double* d, lapack_complex_double* a,\n                    lapack_int* lda, lapack_int* iseed,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_slaset( char* uplo, lapack_int* m, lapack_int* n, float* alpha,\n                    float* beta, float* a, lapack_int* lda );\nvoid LAPACK_dlaset( char* uplo, lapack_int* m, lapack_int* n, double* alpha,\n                    double* beta, double* a, lapack_int* lda );\nvoid LAPACK_claset( char* uplo, lapack_int* m, lapack_int* n,\n                    lapack_complex_float* alpha, lapack_complex_float* beta,\n                    lapack_complex_float* a, lapack_int* lda );\nvoid LAPACK_zlaset( char* uplo, lapack_int* m, lapack_int* n,\n                    lapack_complex_double* alpha, lapack_complex_double* beta,\n                    lapack_complex_double* a, lapack_int* lda );\nvoid LAPACK_slasrt( char* id, lapack_int* n, float* d, lapack_int *info );\nvoid LAPACK_dlasrt( char* id, lapack_int* n, double* d, lapack_int *info );\nvoid LAPACK_claghe( lapack_int* n, lapack_int* k, const float* d,\n                    lapack_complex_float* a, lapack_int* lda, lapack_int* iseed,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zlaghe( lapack_int* n, lapack_int* k, const double* d,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_int* iseed, lapack_complex_double* work,\n                    lapack_int *info );\nvoid LAPACK_slagsy( lapack_int* n, lapack_int* k, const float* d, float* a,\n                    lapack_int* lda, lapack_int* iseed, float* work,\n                    lapack_int *info );\nvoid LAPACK_dlagsy( lapack_int* n, lapack_int* k, const double* d, double* a,\n                    lapack_int* lda, lapack_int* iseed, double* work,\n                    lapack_int *info );\nvoid LAPACK_clagsy( lapack_int* n, lapack_int* k, const float* d,\n                    lapack_complex_float* a, lapack_int* lda, lapack_int* iseed,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zlagsy( lapack_int* n, lapack_int* k, const double* d,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_int* iseed, lapack_complex_double* work,\n                    lapack_int *info );\nvoid LAPACK_slapmr( lapack_logical* forwrd, lapack_int* m, lapack_int* n,\n                    float* x, lapack_int* ldx, lapack_int* k );\nvoid LAPACK_dlapmr( lapack_logical* forwrd, lapack_int* m, lapack_int* n,\n                    double* x, lapack_int* ldx, lapack_int* k );\nvoid LAPACK_clapmr( lapack_logical* forwrd, lapack_int* m, lapack_int* n,\n                    lapack_complex_float* x, lapack_int* ldx, lapack_int* k );\nvoid LAPACK_zlapmr( lapack_logical* forwrd, lapack_int* m, lapack_int* n,\n                    lapack_complex_double* x, lapack_int* ldx, lapack_int* k );\nfloat LAPACK_slapy2( float* x, float* y );\ndouble LAPACK_dlapy2( double* x, double* y );\nfloat LAPACK_slapy3( float* x, float* y, float* z );\ndouble LAPACK_dlapy3( double* x, double* y, double* z );\nvoid LAPACK_slartgp( float* f, float* g, float* cs, float* sn, float* r );\nvoid LAPACK_dlartgp( double* f, double* g, double* cs, double* sn, double* r );\nvoid LAPACK_slartgs( float* x, float* y, float* sigma, float* cs, float* sn );\nvoid LAPACK_dlartgs( double* x, double* y, double* sigma, double* cs,\n                     double* sn );\n// LAPACK 3.3.0\nvoid LAPACK_cbbcsd( char* jobu1, char* jobu2,\n                    char* jobv1t, char* jobv2t, char* trans,\n                    lapack_int* m, lapack_int* p, lapack_int* q,\n                    float* theta, float* phi,\n                    lapack_complex_float* u1, lapack_int* ldu1,\n                    lapack_complex_float* u2, lapack_int* ldu2,\n                    lapack_complex_float* v1t, lapack_int* ldv1t,\n                    lapack_complex_float* v2t, lapack_int* ldv2t,\n                    float* b11d, float* b11e, float* b12d,\n                    float* b12e, float* b21d, float* b21e,\n                    float* b22d, float* b22e, float* rwork,\n                    lapack_int* lrwork , lapack_int *info );\nvoid LAPACK_cheswapr( char* uplo, lapack_int* n,\n                      lapack_complex_float* a, lapack_int* i1,\n                      lapack_int* i2 );\nvoid LAPACK_chetri2( char* uplo, lapack_int* n,\n                     lapack_complex_float* a, lapack_int* lda,\n                     const lapack_int* ipiv,\n                     lapack_complex_float* work, lapack_int* lwork , lapack_int *info );\nvoid LAPACK_chetri2x( char* uplo, lapack_int* n,\n                      lapack_complex_float* a, lapack_int* lda,\n                      const lapack_int* ipiv,\n                      lapack_complex_float* work, lapack_int* nb , lapack_int *info );\nvoid LAPACK_chetrs2( char* uplo, lapack_int* n,\n                     lapack_int* nrhs, const lapack_complex_float* a,\n                     lapack_int* lda, const lapack_int* ipiv,\n                     lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* work , lapack_int *info );\nvoid LAPACK_csyconv( char* uplo, char* way,\n                     lapack_int* n, lapack_complex_float* a,\n                     lapack_int* lda, const lapack_int* ipiv,\n                     lapack_complex_float* work , lapack_int *info );\nvoid LAPACK_csyswapr( char* uplo, lapack_int* n,\n                      lapack_complex_float* a, lapack_int* i1,\n                      lapack_int* i2 );\nvoid LAPACK_csytri2( char* uplo, lapack_int* n,\n                     lapack_complex_float* a, lapack_int* lda,\n                     const lapack_int* ipiv,\n                     lapack_complex_float* work, lapack_int* lwork , lapack_int *info );\nvoid LAPACK_csytri2x( char* uplo, lapack_int* n,\n                      lapack_complex_float* a, lapack_int* lda,\n                      const lapack_int* ipiv,\n                      lapack_complex_float* work, lapack_int* nb , lapack_int *info );\nvoid LAPACK_csytrs2( char* uplo, lapack_int* n,\n                     lapack_int* nrhs, const lapack_complex_float* a,\n                     lapack_int* lda, const lapack_int* ipiv,\n                     lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* work , lapack_int *info );\nvoid LAPACK_cunbdb( char* trans, char* signs,\n                    lapack_int* m, lapack_int* p, lapack_int* q,\n                    lapack_complex_float* x11, lapack_int* ldx11,\n                    lapack_complex_float* x12, lapack_int* ldx12,\n                    lapack_complex_float* x21, lapack_int* ldx21,\n                    lapack_complex_float* x22, lapack_int* ldx22,\n                    float* theta, float* phi,\n                    lapack_complex_float* taup1,\n                    lapack_complex_float* taup2,\n                    lapack_complex_float* tauq1,\n                    lapack_complex_float* tauq2,\n                    lapack_complex_float* work, lapack_int* lwork , lapack_int *info );\nvoid LAPACK_cuncsd( char* jobu1, char* jobu2,\n                    char* jobv1t, char* jobv2t, char* trans,\n                    char* signs, lapack_int* m, lapack_int* p,\n                    lapack_int* q, lapack_complex_float* x11,\n                    lapack_int* ldx11, lapack_complex_float* x12,\n                    lapack_int* ldx12, lapack_complex_float* x21,\n                    lapack_int* ldx21, lapack_complex_float* x22,\n                    lapack_int* ldx22, float* theta,\n                    lapack_complex_float* u1, lapack_int* ldu1,\n                    lapack_complex_float* u2, lapack_int* ldu2,\n                    lapack_complex_float* v1t, lapack_int* ldv1t,\n                    lapack_complex_float* v2t, lapack_int* ldv2t,\n                    lapack_complex_float* work, lapack_int* lwork,\n                    float* rwork, lapack_int* lrwork,\n                    lapack_int* iwork , lapack_int *info );\nvoid LAPACK_dbbcsd( char* jobu1, char* jobu2,\n                    char* jobv1t, char* jobv2t, char* trans,\n                    lapack_int* m, lapack_int* p, lapack_int* q,\n                    double* theta, double* phi, double* u1,\n                    lapack_int* ldu1, double* u2, lapack_int* ldu2,\n                    double* v1t, lapack_int* ldv1t, double* v2t,\n                    lapack_int* ldv2t, double* b11d, double* b11e,\n                    double* b12d, double* b12e, double* b21d,\n                    double* b21e, double* b22d, double* b22e,\n                    double* work, lapack_int* lwork , lapack_int *info );\nvoid LAPACK_dorbdb( char* trans, char* signs,\n                    lapack_int* m, lapack_int* p, lapack_int* q,\n                    double* x11, lapack_int* ldx11, double* x12,\n                    lapack_int* ldx12, double* x21, lapack_int* ldx21,\n                    double* x22, lapack_int* ldx22, double* theta,\n                    double* phi, double* taup1, double* taup2,\n                    double* tauq1, double* tauq2, double* work,\n                    lapack_int* lwork , lapack_int *info );\nvoid LAPACK_dorcsd( char* jobu1, char* jobu2,\n                    char* jobv1t, char* jobv2t, char* trans,\n                    char* signs, lapack_int* m, lapack_int* p,\n                    lapack_int* q, double* x11, lapack_int* ldx11,\n                    double* x12, lapack_int* ldx12, double* x21,\n                    lapack_int* ldx21, double* x22, lapack_int* ldx22,\n                    double* theta, double* u1, lapack_int* ldu1,\n                    double* u2, lapack_int* ldu2, double* v1t,\n                    lapack_int* ldv1t, double* v2t, lapack_int* ldv2t,\n                    double* work, lapack_int* lwork,\n                    lapack_int* iwork , lapack_int *info );\nvoid LAPACK_dsyconv( char* uplo, char* way,\n                     lapack_int* n, double* a, lapack_int* lda,\n                     const lapack_int* ipiv, double* work , lapack_int *info );\nvoid LAPACK_dsyswapr( char* uplo, lapack_int* n,\n                      double* a, lapack_int* i1, lapack_int* i2 );\nvoid LAPACK_dsytri2( char* uplo, lapack_int* n,\n                     double* a, lapack_int* lda,\n                     const lapack_int* ipiv,\n                     lapack_complex_double* work, lapack_int* lwork , lapack_int *info );\nvoid LAPACK_dsytri2x( char* uplo, lapack_int* n,\n                      double* a, lapack_int* lda,\n                      const lapack_int* ipiv, double* work,\n                      lapack_int* nb , lapack_int *info );\nvoid LAPACK_dsytrs2( char* uplo, lapack_int* n,\n                     lapack_int* nrhs, const double* a,\n                     lapack_int* lda, const lapack_int* ipiv,\n                     double* b, lapack_int* ldb, double* work , lapack_int *info );\nvoid LAPACK_sbbcsd( char* jobu1, char* jobu2,\n                    char* jobv1t, char* jobv2t, char* trans,\n                    lapack_int* m, lapack_int* p, lapack_int* q,\n                    float* theta, float* phi, float* u1,\n                    lapack_int* ldu1, float* u2, lapack_int* ldu2,\n                    float* v1t, lapack_int* ldv1t, float* v2t,\n                    lapack_int* ldv2t, float* b11d, float* b11e,\n                    float* b12d, float* b12e, float* b21d,\n                    float* b21e, float* b22d, float* b22e,\n                    float* work, lapack_int* lwork , lapack_int *info );\nvoid LAPACK_sorbdb( char* trans, char* signs,\n                    lapack_int* m, lapack_int* p, lapack_int* q,\n                    float* x11, lapack_int* ldx11, float* x12,\n                    lapack_int* ldx12, float* x21, lapack_int* ldx21,\n                    float* x22, lapack_int* ldx22, float* theta,\n                    float* phi, float* taup1, float* taup2,\n                    float* tauq1, float* tauq2, float* work,\n                    lapack_int* lwork , lapack_int *info );\nvoid LAPACK_sorcsd( char* jobu1, char* jobu2,\n                    char* jobv1t, char* jobv2t, char* trans,\n                    char* signs, lapack_int* m, lapack_int* p,\n                    lapack_int* q, float* x11, lapack_int* ldx11,\n                    float* x12, lapack_int* ldx12, float* x21,\n                    lapack_int* ldx21, float* x22, lapack_int* ldx22,\n                    float* theta, float* u1, lapack_int* ldu1,\n                    float* u2, lapack_int* ldu2, float* v1t,\n                    lapack_int* ldv1t, float* v2t, lapack_int* ldv2t,\n                    float* work, lapack_int* lwork,\n                    lapack_int* iwork , lapack_int *info );\nvoid LAPACK_ssyconv( char* uplo, char* way,\n                     lapack_int* n, float* a, lapack_int* lda,\n                     const lapack_int* ipiv, float* work , lapack_int *info );\nvoid LAPACK_ssyswapr( char* uplo, lapack_int* n,\n                      float* a, lapack_int* i1, lapack_int* i2 );\nvoid LAPACK_ssytri2( char* uplo, lapack_int* n,\n                     float* a, lapack_int* lda,\n                     const lapack_int* ipiv,\n                     lapack_complex_float* work, lapack_int* lwork , lapack_int *info );\nvoid LAPACK_ssytri2x( char* uplo, lapack_int* n,\n                      float* a, lapack_int* lda,\n                      const lapack_int* ipiv, float* work,\n                      lapack_int* nb , lapack_int *info );\nvoid LAPACK_ssytrs2( char* uplo, lapack_int* n,\n                     lapack_int* nrhs, const float* a,\n                     lapack_int* lda, const lapack_int* ipiv,\n                     float* b, lapack_int* ldb, float* work , lapack_int *info );\nvoid LAPACK_zbbcsd( char* jobu1, char* jobu2,\n                    char* jobv1t, char* jobv2t, char* trans,\n                    lapack_int* m, lapack_int* p, lapack_int* q,\n                    double* theta, double* phi,\n                    lapack_complex_double* u1, lapack_int* ldu1,\n                    lapack_complex_double* u2, lapack_int* ldu2,\n                    lapack_complex_double* v1t, lapack_int* ldv1t,\n                    lapack_complex_double* v2t, lapack_int* ldv2t,\n                    double* b11d, double* b11e, double* b12d,\n                    double* b12e, double* b21d, double* b21e,\n                    double* b22d, double* b22e, double* rwork,\n                    lapack_int* lrwork , lapack_int *info );\nvoid LAPACK_zheswapr( char* uplo, lapack_int* n,\n                      lapack_complex_double* a, lapack_int* i1,\n                      lapack_int* i2 );\nvoid LAPACK_zhetri2( char* uplo, lapack_int* n,\n                     lapack_complex_double* a, lapack_int* lda,\n                     const lapack_int* ipiv,\n                     lapack_complex_double* work, lapack_int* lwork , lapack_int *info );\nvoid LAPACK_zhetri2x( char* uplo, lapack_int* n,\n                      lapack_complex_double* a, lapack_int* lda,\n                      const lapack_int* ipiv,\n                      lapack_complex_double* work, lapack_int* nb , lapack_int *info );\nvoid LAPACK_zhetrs2( char* uplo, lapack_int* n,\n                     lapack_int* nrhs,\n                     const lapack_complex_double* a, lapack_int* lda,\n                     const lapack_int* ipiv,\n                     lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* work , lapack_int *info );\nvoid LAPACK_zsyconv( char* uplo, char* way,\n                     lapack_int* n, lapack_complex_double* a,\n                     lapack_int* lda, const lapack_int* ipiv,\n                     lapack_complex_double* work , lapack_int *info );\nvoid LAPACK_zsyswapr( char* uplo, lapack_int* n,\n                      lapack_complex_double* a, lapack_int* i1,\n                      lapack_int* i2 );\nvoid LAPACK_zsytri2( char* uplo, lapack_int* n,\n                     lapack_complex_double* a, lapack_int* lda,\n                     const lapack_int* ipiv,\n                     lapack_complex_double* work, lapack_int* lwork , lapack_int *info );\nvoid LAPACK_zsytri2x( char* uplo, lapack_int* n,\n                      lapack_complex_double* a, lapack_int* lda,\n                      const lapack_int* ipiv,\n                      lapack_complex_double* work, lapack_int* nb , lapack_int *info );\nvoid LAPACK_zsytrs2( char* uplo, lapack_int* n,\n                     lapack_int* nrhs,\n                     const lapack_complex_double* a, lapack_int* lda,\n                     const lapack_int* ipiv,\n                     lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* work , lapack_int *info );\nvoid LAPACK_zunbdb( char* trans, char* signs,\n                    lapack_int* m, lapack_int* p, lapack_int* q,\n                    lapack_complex_double* x11, lapack_int* ldx11,\n                    lapack_complex_double* x12, lapack_int* ldx12,\n                    lapack_complex_double* x21, lapack_int* ldx21,\n                    lapack_complex_double* x22, lapack_int* ldx22,\n                    double* theta, double* phi,\n                    lapack_complex_double* taup1,\n                    lapack_complex_double* taup2,\n                    lapack_complex_double* tauq1,\n                    lapack_complex_double* tauq2,\n                    lapack_complex_double* work, lapack_int* lwork , lapack_int *info );\nvoid LAPACK_zuncsd( char* jobu1, char* jobu2,\n                    char* jobv1t, char* jobv2t, char* trans,\n                    char* signs, lapack_int* m, lapack_int* p,\n                    lapack_int* q, lapack_complex_double* x11,\n                    lapack_int* ldx11, lapack_complex_double* x12,\n                    lapack_int* ldx12, lapack_complex_double* x21,\n                    lapack_int* ldx21, lapack_complex_double* x22,\n                    lapack_int* ldx22, double* theta,\n                    lapack_complex_double* u1, lapack_int* ldu1,\n                    lapack_complex_double* u2, lapack_int* ldu2,\n                    lapack_complex_double* v1t, lapack_int* ldv1t,\n                    lapack_complex_double* v2t, lapack_int* ldv2t,\n                    lapack_complex_double* work, lapack_int* lwork,\n                    double* rwork, lapack_int* lrwork,\n                    lapack_int* iwork , lapack_int *info );\n// LAPACK 3.4.0\nvoid LAPACK_sgemqrt( char* side, char* trans, lapack_int* m, lapack_int* n,\n                     lapack_int* k, lapack_int* nb, const float* v,\n                     lapack_int* ldv, const float* t, lapack_int* ldt, float* c,\n                     lapack_int* ldc, float* work, lapack_int *info );\nvoid LAPACK_dgemqrt( char* side, char* trans, lapack_int* m, lapack_int* n,\n                     lapack_int* k, lapack_int* nb, const double* v,\n                     lapack_int* ldv, const double* t, lapack_int* ldt,\n                     double* c, lapack_int* ldc, double* work,\n                     lapack_int *info );\nvoid LAPACK_cgemqrt( char* side, char* trans, lapack_int* m, lapack_int* n,\n                     lapack_int* k, lapack_int* nb,\n                     const lapack_complex_float* v, lapack_int* ldv,\n                     const lapack_complex_float* t, lapack_int* ldt,\n                     lapack_complex_float* c, lapack_int* ldc,\n                     lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zgemqrt( char* side, char* trans, lapack_int* m, lapack_int* n,\n                     lapack_int* k, lapack_int* nb,\n                     const lapack_complex_double* v, lapack_int* ldv,\n                     const lapack_complex_double* t, lapack_int* ldt,\n                     lapack_complex_double* c, lapack_int* ldc,\n                     lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_sgeqrt( lapack_int* m, lapack_int* n, lapack_int* nb, float* a,\n                    lapack_int* lda, float* t, lapack_int* ldt, float* work,\n                    lapack_int *info );\nvoid LAPACK_dgeqrt( lapack_int* m, lapack_int* n, lapack_int* nb, double* a,\n                    lapack_int* lda, double* t, lapack_int* ldt, double* work,\n                    lapack_int *info );\nvoid LAPACK_cgeqrt( lapack_int* m, lapack_int* n, lapack_int* nb,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* t, lapack_int* ldt,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_zgeqrt( lapack_int* m, lapack_int* n, lapack_int* nb,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* t, lapack_int* ldt,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_sgeqrt2( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                     float* t, lapack_int* ldt, lapack_int *info );\nvoid LAPACK_dgeqrt2( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                     double* t, lapack_int* ldt, lapack_int *info );\nvoid LAPACK_cgeqrt2( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                     lapack_int* lda, lapack_complex_float* t, lapack_int* ldt,\n                     lapack_int *info );\nvoid LAPACK_zgeqrt2( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                     lapack_int* lda, lapack_complex_double* t, lapack_int* ldt,\n                     lapack_int *info );\nvoid LAPACK_sgeqrt3( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                     float* t, lapack_int* ldt, lapack_int *info );\nvoid LAPACK_dgeqrt3( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                     double* t, lapack_int* ldt, lapack_int *info );\nvoid LAPACK_cgeqrt3( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                     lapack_int* lda, lapack_complex_float* t, lapack_int* ldt,\n                     lapack_int *info );\nvoid LAPACK_zgeqrt3( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                     lapack_int* lda, lapack_complex_double* t, lapack_int* ldt,\n                     lapack_int *info );\nvoid LAPACK_stpmqrt( char* side, char* trans, lapack_int* m, lapack_int* n,\n                     lapack_int* k, lapack_int* l, lapack_int* nb,\n                     const float* v, lapack_int* ldv, const float* t,\n                     lapack_int* ldt, float* a, lapack_int* lda, float* b,\n                     lapack_int* ldb, float* work, lapack_int *info );\nvoid LAPACK_dtpmqrt( char* side, char* trans, lapack_int* m, lapack_int* n,\n                     lapack_int* k, lapack_int* l, lapack_int* nb,\n                     const double* v, lapack_int* ldv, const double* t,\n                     lapack_int* ldt, double* a, lapack_int* lda, double* b,\n                     lapack_int* ldb, double* work, lapack_int *info );\nvoid LAPACK_ctpmqrt( char* side, char* trans, lapack_int* m, lapack_int* n,\n                     lapack_int* k, lapack_int* l, lapack_int* nb,\n                     const lapack_complex_float* v, lapack_int* ldv,\n                     const lapack_complex_float* t, lapack_int* ldt,\n                     lapack_complex_float* a, lapack_int* lda,\n                     lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_ztpmqrt( char* side, char* trans, lapack_int* m, lapack_int* n,\n                     lapack_int* k, lapack_int* l, lapack_int* nb,\n                     const lapack_complex_double* v, lapack_int* ldv,\n                     const lapack_complex_double* t, lapack_int* ldt,\n                     lapack_complex_double* a, lapack_int* lda,\n                     lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_dtpqrt( lapack_int* m, lapack_int* n, lapack_int* l, lapack_int* nb,\n                    double* a, lapack_int* lda, double* b, lapack_int* ldb,\n                    double* t, lapack_int* ldt, double* work,\n                    lapack_int *info );\nvoid LAPACK_ctpqrt( lapack_int* m, lapack_int* n, lapack_int* l, lapack_int* nb,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* t, lapack_complex_float* b,\n                    lapack_int* ldb, lapack_int* ldt,\n                    lapack_complex_float* work, lapack_int *info );\nvoid LAPACK_ztpqrt( lapack_int* m, lapack_int* n, lapack_int* l, lapack_int* nb,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    lapack_complex_double* t, lapack_int* ldt,\n                    lapack_complex_double* work, lapack_int *info );\nvoid LAPACK_stpqrt2( lapack_int* m, lapack_int* n, float* a, lapack_int* lda,\n                     float* b, lapack_int* ldb, float* t, lapack_int* ldt,\n                     lapack_int *info );\nvoid LAPACK_dtpqrt2( lapack_int* m, lapack_int* n, double* a, lapack_int* lda,\n                     double* b, lapack_int* ldb, double* t, lapack_int* ldt,\n                     lapack_int *info );\nvoid LAPACK_ctpqrt2( lapack_int* m, lapack_int* n, lapack_complex_float* a,\n                     lapack_int* lda, lapack_complex_float* b, lapack_int* ldb,\n                     lapack_complex_float* t, lapack_int* ldt,\n                     lapack_int *info );\nvoid LAPACK_ztpqrt2( lapack_int* m, lapack_int* n, lapack_complex_double* a,\n                     lapack_int* lda, lapack_complex_double* b, lapack_int* ldb,\n                     lapack_complex_double* t, lapack_int* ldt,\n                     lapack_int *info );\nvoid LAPACK_stprfb( char* side, char* trans, char* direct, char* storev,\n                    lapack_int* m, lapack_int* n, lapack_int* k, lapack_int* l,\n                    const float* v, lapack_int* ldv, const float* t,\n                    lapack_int* ldt, float* a, lapack_int* lda, float* b,\n                    lapack_int* ldb, const float* mywork,\n                    lapack_int* myldwork );\nvoid LAPACK_dtprfb( char* side, char* trans, char* direct, char* storev,\n                    lapack_int* m, lapack_int* n, lapack_int* k, lapack_int* l,\n                    const double* v, lapack_int* ldv, const double* t,\n                    lapack_int* ldt, double* a, lapack_int* lda, double* b,\n                    lapack_int* ldb, const double* mywork,\n                    lapack_int* myldwork );\nvoid LAPACK_ctprfb( char* side, char* trans, char* direct, char* storev,\n                    lapack_int* m, lapack_int* n, lapack_int* k, lapack_int* l,\n                    const lapack_complex_float* v, lapack_int* ldv,\n                    const lapack_complex_float* t, lapack_int* ldt,\n                    lapack_complex_float* a, lapack_int* lda,\n                    lapack_complex_float* b, lapack_int* ldb,\n                    const float* mywork, lapack_int* myldwork );\nvoid LAPACK_ztprfb( char* side, char* trans, char* direct, char* storev,\n                    lapack_int* m, lapack_int* n, lapack_int* k, lapack_int* l,\n                    const lapack_complex_double* v, lapack_int* ldv,\n                    const lapack_complex_double* t, lapack_int* ldt,\n                    lapack_complex_double* a, lapack_int* lda,\n                    lapack_complex_double* b, lapack_int* ldb,\n                    const double* mywork, lapack_int* myldwork );\n// LAPACK 3.X.X\nvoid LAPACK_csyr( char* uplo, lapack_int* n, lapack_complex_float* alpha,\n                      const lapack_complex_float* x, lapack_int* incx,\n                      lapack_complex_float* a, lapack_int* lda );\nvoid LAPACK_zsyr( char* uplo, lapack_int* n, lapack_complex_double* alpha,\n                      const lapack_complex_double* x, lapack_int* incx,\n                      lapack_complex_double* a, lapack_int* lda );\n\n#ifdef __cplusplus\n}\n#endif /* __cplusplus */\n\n#endif /* _LAPACKE_H_ */\n\n#endif /* _MKL_LAPACKE_H_ */\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/misc/lapacke_mangling.h",
    "content": "#ifndef LAPACK_HEADER_INCLUDED\n#define LAPACK_HEADER_INCLUDED\n\n#ifndef LAPACK_GLOBAL\n#if defined(LAPACK_GLOBAL_PATTERN_LC) || defined(ADD_)\n#define LAPACK_GLOBAL(lcname,UCNAME)  lcname##_\n#elif defined(LAPACK_GLOBAL_PATTERN_UC) || defined(UPPER)\n#define LAPACK_GLOBAL(lcname,UCNAME)  UCNAME\n#elif defined(LAPACK_GLOBAL_PATTERN_MC) || defined(NOCHANGE)\n#define LAPACK_GLOBAL(lcname,UCNAME)  lcname\n#else\n#define LAPACK_GLOBAL(lcname,UCNAME)  lcname##_\n#endif\n#endif\n\n#endif\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/plugins/ArrayCwiseBinaryOps.h",
    "content": "\n/** \\returns an expression of the coefficient wise product of \\c *this and \\a other\n  *\n  * \\sa MatrixBase::cwiseProduct\n  */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const EIGEN_CWISE_BINARY_RETURN_TYPE(Derived,OtherDerived,product)\noperator*(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  return EIGEN_CWISE_BINARY_RETURN_TYPE(Derived,OtherDerived,product)(derived(), other.derived());\n}\n\n/** \\returns an expression of the coefficient wise quotient of \\c *this and \\a other\n  *\n  * \\sa MatrixBase::cwiseQuotient\n  */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_quotient_op<Scalar,typename OtherDerived::Scalar>, const Derived, const OtherDerived>\noperator/(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  return CwiseBinaryOp<internal::scalar_quotient_op<Scalar,typename OtherDerived::Scalar>, const Derived, const OtherDerived>(derived(), other.derived());\n}\n\n/** \\returns an expression of the coefficient-wise min of \\c *this and \\a other\n  *\n  * Example: \\include Cwise_min.cpp\n  * Output: \\verbinclude Cwise_min.out\n  *\n  * \\sa max()\n  */\nEIGEN_MAKE_CWISE_BINARY_OP(min,min)\n\n/** \\returns an expression of the coefficient-wise min of \\c *this and scalar \\a other\n  *\n  * \\sa max()\n  */\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_min_op<Scalar,Scalar>, const Derived,\n                                        const CwiseNullaryOp<internal::scalar_constant_op<Scalar>, PlainObject> >\n#ifdef EIGEN_PARSED_BY_DOXYGEN\nmin\n#else\n(min)\n#endif\n(const Scalar &other) const\n{\n  return (min)(Derived::PlainObject::Constant(rows(), cols(), other));\n}\n\n/** \\returns an expression of the coefficient-wise max of \\c *this and \\a other\n  *\n  * Example: \\include Cwise_max.cpp\n  * Output: \\verbinclude Cwise_max.out\n  *\n  * \\sa min()\n  */\nEIGEN_MAKE_CWISE_BINARY_OP(max,max)\n\n/** \\returns an expression of the coefficient-wise max of \\c *this and scalar \\a other\n  *\n  * \\sa min()\n  */\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_max_op<Scalar,Scalar>, const Derived,\n                                        const CwiseNullaryOp<internal::scalar_constant_op<Scalar>, PlainObject> >\n#ifdef EIGEN_PARSED_BY_DOXYGEN\nmax\n#else\n(max)\n#endif\n(const Scalar &other) const\n{\n  return (max)(Derived::PlainObject::Constant(rows(), cols(), other));\n}\n\n/** \\returns an expression of the coefficient-wise absdiff of \\c *this and \\a other\n  *\n  * Example: \\include Cwise_absolute_difference.cpp\n  * Output: \\verbinclude Cwise_absolute_difference.out\n  *\n  * \\sa absolute_difference()\n  */\nEIGEN_MAKE_CWISE_BINARY_OP(absolute_difference,absolute_difference)\n\n/** \\returns an expression of the coefficient-wise absolute_difference of \\c *this and scalar \\a other\n  *\n  * \\sa absolute_difference()\n  */\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_absolute_difference_op<Scalar,Scalar>, const Derived,\n                                        const CwiseNullaryOp<internal::scalar_constant_op<Scalar>, PlainObject> >\n#ifdef EIGEN_PARSED_BY_DOXYGEN\nabsolute_difference\n#else\n(absolute_difference)\n#endif\n(const Scalar &other) const\n{\n  return (absolute_difference)(Derived::PlainObject::Constant(rows(), cols(), other));\n}\n\n/** \\returns an expression of the coefficient-wise power of \\c *this to the given array of \\a exponents.\n  *\n  * This function computes the coefficient-wise power.\n  *\n  * Example: \\include Cwise_array_power_array.cpp\n  * Output: \\verbinclude Cwise_array_power_array.out\n  */\nEIGEN_MAKE_CWISE_BINARY_OP(pow,pow)\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nEIGEN_MAKE_SCALAR_BINARY_OP_ONTHERIGHT(pow,pow)\n#else\n/** \\returns an expression of the coefficients of \\c *this rasied to the constant power \\a exponent\n  *\n  * \\tparam T is the scalar type of \\a exponent. It must be compatible with the scalar type of the given expression.\n  *\n  * This function computes the coefficient-wise power. The function MatrixBase::pow() in the\n  * unsupported module MatrixFunctions computes the matrix power.\n  *\n  * Example: \\include Cwise_pow.cpp\n  * Output: \\verbinclude Cwise_pow.out\n  *\n  * \\sa ArrayBase::pow(ArrayBase), square(), cube(), exp(), log()\n  */\ntemplate<typename T>\nconst CwiseBinaryOp<internal::scalar_pow_op<Scalar,T>,Derived,Constant<T> > pow(const T& exponent) const;\n#endif\n\n\n// TODO code generating macros could be moved to Macros.h and could include generation of documentation\n#define EIGEN_MAKE_CWISE_COMP_OP(OP, COMPARATOR) \\\ntemplate<typename OtherDerived> \\\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_cmp_op<Scalar, typename OtherDerived::Scalar, internal::cmp_ ## COMPARATOR>, const Derived, const OtherDerived> \\\nOP(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const \\\n{ \\\n  return CwiseBinaryOp<internal::scalar_cmp_op<Scalar, typename OtherDerived::Scalar, internal::cmp_ ## COMPARATOR>, const Derived, const OtherDerived>(derived(), other.derived()); \\\n}\\\ntypedef CwiseBinaryOp<internal::scalar_cmp_op<Scalar,Scalar, internal::cmp_ ## COMPARATOR>, const Derived, const CwiseNullaryOp<internal::scalar_constant_op<Scalar>, PlainObject> > Cmp ## COMPARATOR ## ReturnType; \\\ntypedef CwiseBinaryOp<internal::scalar_cmp_op<Scalar,Scalar, internal::cmp_ ## COMPARATOR>, const CwiseNullaryOp<internal::scalar_constant_op<Scalar>, PlainObject>, const Derived > RCmp ## COMPARATOR ## ReturnType; \\\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Cmp ## COMPARATOR ## ReturnType \\\nOP(const Scalar& s) const { \\\n  return this->OP(Derived::PlainObject::Constant(rows(), cols(), s)); \\\n} \\\nEIGEN_DEVICE_FUNC friend EIGEN_STRONG_INLINE const RCmp ## COMPARATOR ## ReturnType \\\nOP(const Scalar& s, const EIGEN_CURRENT_STORAGE_BASE_CLASS<Derived>& d) { \\\n  return Derived::PlainObject::Constant(d.rows(), d.cols(), s).OP(d); \\\n}\n\n#define EIGEN_MAKE_CWISE_COMP_R_OP(OP, R_OP, RCOMPARATOR) \\\ntemplate<typename OtherDerived> \\\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_cmp_op<typename OtherDerived::Scalar, Scalar, internal::cmp_##RCOMPARATOR>, const OtherDerived, const Derived> \\\nOP(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const \\\n{ \\\n  return CwiseBinaryOp<internal::scalar_cmp_op<typename OtherDerived::Scalar, Scalar, internal::cmp_##RCOMPARATOR>, const OtherDerived, const Derived>(other.derived(), derived()); \\\n} \\\nEIGEN_DEVICE_FUNC \\\ninline const RCmp ## RCOMPARATOR ## ReturnType \\\nOP(const Scalar& s) const { \\\n  return Derived::PlainObject::Constant(rows(), cols(), s).R_OP(*this); \\\n} \\\nfriend inline const Cmp ## RCOMPARATOR ## ReturnType \\\nOP(const Scalar& s, const Derived& d) { \\\n  return d.R_OP(Derived::PlainObject::Constant(d.rows(), d.cols(), s)); \\\n}\n\n\n\n/** \\returns an expression of the coefficient-wise \\< operator of *this and \\a other\n  *\n  * Example: \\include Cwise_less.cpp\n  * Output: \\verbinclude Cwise_less.out\n  *\n  * \\sa all(), any(), operator>(), operator<=()\n  */\nEIGEN_MAKE_CWISE_COMP_OP(operator<, LT)\n\n/** \\returns an expression of the coefficient-wise \\<= operator of *this and \\a other\n  *\n  * Example: \\include Cwise_less_equal.cpp\n  * Output: \\verbinclude Cwise_less_equal.out\n  *\n  * \\sa all(), any(), operator>=(), operator<()\n  */\nEIGEN_MAKE_CWISE_COMP_OP(operator<=, LE)\n\n/** \\returns an expression of the coefficient-wise \\> operator of *this and \\a other\n  *\n  * Example: \\include Cwise_greater.cpp\n  * Output: \\verbinclude Cwise_greater.out\n  *\n  * \\sa all(), any(), operator>=(), operator<()\n  */\nEIGEN_MAKE_CWISE_COMP_R_OP(operator>, operator<, LT)\n\n/** \\returns an expression of the coefficient-wise \\>= operator of *this and \\a other\n  *\n  * Example: \\include Cwise_greater_equal.cpp\n  * Output: \\verbinclude Cwise_greater_equal.out\n  *\n  * \\sa all(), any(), operator>(), operator<=()\n  */\nEIGEN_MAKE_CWISE_COMP_R_OP(operator>=, operator<=, LE)\n\n/** \\returns an expression of the coefficient-wise == operator of *this and \\a other\n  *\n  * \\warning this performs an exact comparison, which is generally a bad idea with floating-point types.\n  * In order to check for equality between two vectors or matrices with floating-point coefficients, it is\n  * generally a far better idea to use a fuzzy comparison as provided by isApprox() and\n  * isMuchSmallerThan().\n  *\n  * Example: \\include Cwise_equal_equal.cpp\n  * Output: \\verbinclude Cwise_equal_equal.out\n  *\n  * \\sa all(), any(), isApprox(), isMuchSmallerThan()\n  */\nEIGEN_MAKE_CWISE_COMP_OP(operator==, EQ)\n\n/** \\returns an expression of the coefficient-wise != operator of *this and \\a other\n  *\n  * \\warning this performs an exact comparison, which is generally a bad idea with floating-point types.\n  * In order to check for equality between two vectors or matrices with floating-point coefficients, it is\n  * generally a far better idea to use a fuzzy comparison as provided by isApprox() and\n  * isMuchSmallerThan().\n  *\n  * Example: \\include Cwise_not_equal.cpp\n  * Output: \\verbinclude Cwise_not_equal.out\n  *\n  * \\sa all(), any(), isApprox(), isMuchSmallerThan()\n  */\nEIGEN_MAKE_CWISE_COMP_OP(operator!=, NEQ)\n\n\n#undef EIGEN_MAKE_CWISE_COMP_OP\n#undef EIGEN_MAKE_CWISE_COMP_R_OP\n\n// scalar addition\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nEIGEN_MAKE_SCALAR_BINARY_OP(operator+,sum)\n#else\n/** \\returns an expression of \\c *this with each coeff incremented by the constant \\a scalar\n  *\n  * \\tparam T is the scalar type of \\a scalar. It must be compatible with the scalar type of the given expression.\n  *\n  * Example: \\include Cwise_plus.cpp\n  * Output: \\verbinclude Cwise_plus.out\n  *\n  * \\sa operator+=(), operator-()\n  */\ntemplate<typename T>\nconst CwiseBinaryOp<internal::scalar_sum_op<Scalar,T>,Derived,Constant<T> > operator+(const T& scalar) const;\n/** \\returns an expression of \\a expr with each coeff incremented by the constant \\a scalar\n  *\n  * \\tparam T is the scalar type of \\a scalar. It must be compatible with the scalar type of the given expression.\n  */\ntemplate<typename T> friend\nconst CwiseBinaryOp<internal::scalar_sum_op<T,Scalar>,Constant<T>,Derived> operator+(const T& scalar, const StorageBaseType& expr);\n#endif\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nEIGEN_MAKE_SCALAR_BINARY_OP(operator-,difference)\n#else\n/** \\returns an expression of \\c *this with each coeff decremented by the constant \\a scalar\n  *\n  * \\tparam T is the scalar type of \\a scalar. It must be compatible with the scalar type of the given expression.\n  *\n  * Example: \\include Cwise_minus.cpp\n  * Output: \\verbinclude Cwise_minus.out\n  *\n  * \\sa operator+=(), operator-()\n  */\ntemplate<typename T>\nconst CwiseBinaryOp<internal::scalar_difference_op<Scalar,T>,Derived,Constant<T> > operator-(const T& scalar) const;\n/** \\returns an expression of the constant matrix of value \\a scalar decremented by the coefficients of \\a expr\n  *\n  * \\tparam T is the scalar type of \\a scalar. It must be compatible with the scalar type of the given expression.\n  */\ntemplate<typename T> friend\nconst CwiseBinaryOp<internal::scalar_difference_op<T,Scalar>,Constant<T>,Derived> operator-(const T& scalar, const StorageBaseType& expr);\n#endif\n\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n  EIGEN_MAKE_SCALAR_BINARY_OP_ONTHELEFT(operator/,quotient)\n#else\n  /**\n    * \\brief Component-wise division of the scalar \\a s by array elements of \\a a.\n    *\n    * \\tparam Scalar is the scalar type of \\a x. It must be compatible with the scalar type of the given array expression (\\c Derived::Scalar).\n    */\n  template<typename T> friend\n  inline const CwiseBinaryOp<internal::scalar_quotient_op<T,Scalar>,Constant<T>,Derived>\n  operator/(const T& s,const StorageBaseType& a);\n#endif\n\n/** \\returns an expression of the coefficient-wise ^ operator of *this and \\a other\n *\n * \\warning this operator is for expression of bool only.\n *\n * Example: \\include Cwise_boolean_xor.cpp\n * Output: \\verbinclude Cwise_boolean_xor.out\n *\n * \\sa operator&&(), select()\n */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\ninline const CwiseBinaryOp<internal::scalar_boolean_xor_op, const Derived, const OtherDerived>\noperator^(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  EIGEN_STATIC_ASSERT((internal::is_same<bool,Scalar>::value && internal::is_same<bool,typename OtherDerived::Scalar>::value),\n                      THIS_METHOD_IS_ONLY_FOR_EXPRESSIONS_OF_BOOL);\n  return CwiseBinaryOp<internal::scalar_boolean_xor_op, const Derived, const OtherDerived>(derived(),other.derived());\n}\n\n// NOTE disabled until we agree on argument order\n#if 0\n/** \\cpp11 \\returns an expression of the coefficient-wise polygamma function.\n  *\n  * \\specialfunctions_module\n  *\n  * It returns the \\a n -th derivative of the digamma(psi) evaluated at \\c *this.\n  *\n  * \\warning Be careful with the order of the parameters: x.polygamma(n) is equivalent to polygamma(n,x)\n  *\n  * \\sa Eigen::polygamma()\n  */\ntemplate<typename DerivedN>\ninline const CwiseBinaryOp<internal::scalar_polygamma_op<Scalar>, const DerivedN, const Derived>\npolygamma(const EIGEN_CURRENT_STORAGE_BASE_CLASS<DerivedN> &n) const\n{\n  return CwiseBinaryOp<internal::scalar_polygamma_op<Scalar>, const DerivedN, const Derived>(n.derived(), this->derived());\n}\n#endif\n\n/** \\returns an expression of the coefficient-wise zeta function.\n  *\n  * \\specialfunctions_module\n  *\n  * It returns the Riemann zeta function of two arguments \\c *this and \\a q:\n  *\n  * \\param q is the shift, it must be > 0\n  *\n  * \\note *this is the exponent, it must be > 1.\n  * \\note This function supports only float and double scalar types. To support other scalar types, the user has\n  * to provide implementations of zeta(T,T) for any scalar type T to be supported.\n  *\n  * This method is an alias for zeta(*this,q);\n  *\n  * \\sa Eigen::zeta()\n  */\ntemplate<typename DerivedQ>\ninline const CwiseBinaryOp<internal::scalar_zeta_op<Scalar>, const Derived, const DerivedQ>\nzeta(const EIGEN_CURRENT_STORAGE_BASE_CLASS<DerivedQ> &q) const\n{\n  return CwiseBinaryOp<internal::scalar_zeta_op<Scalar>, const Derived, const DerivedQ>(this->derived(), q.derived());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/plugins/ArrayCwiseUnaryOps.h",
    "content": "\n\ntypedef CwiseUnaryOp<internal::scalar_abs_op<Scalar>, const Derived> AbsReturnType;\ntypedef CwiseUnaryOp<internal::scalar_arg_op<Scalar>, const Derived> ArgReturnType;\ntypedef CwiseUnaryOp<internal::scalar_abs2_op<Scalar>, const Derived> Abs2ReturnType;\ntypedef CwiseUnaryOp<internal::scalar_sqrt_op<Scalar>, const Derived> SqrtReturnType;\ntypedef CwiseUnaryOp<internal::scalar_rsqrt_op<Scalar>, const Derived> RsqrtReturnType;\ntypedef CwiseUnaryOp<internal::scalar_sign_op<Scalar>, const Derived> SignReturnType;\ntypedef CwiseUnaryOp<internal::scalar_inverse_op<Scalar>, const Derived> InverseReturnType;\ntypedef CwiseUnaryOp<internal::scalar_boolean_not_op<Scalar>, const Derived> BooleanNotReturnType;\n\ntypedef CwiseUnaryOp<internal::scalar_exp_op<Scalar>, const Derived> ExpReturnType;\ntypedef CwiseUnaryOp<internal::scalar_expm1_op<Scalar>, const Derived> Expm1ReturnType;\ntypedef CwiseUnaryOp<internal::scalar_log_op<Scalar>, const Derived> LogReturnType;\ntypedef CwiseUnaryOp<internal::scalar_log1p_op<Scalar>, const Derived> Log1pReturnType;\ntypedef CwiseUnaryOp<internal::scalar_log10_op<Scalar>, const Derived> Log10ReturnType;\ntypedef CwiseUnaryOp<internal::scalar_log2_op<Scalar>, const Derived> Log2ReturnType;\ntypedef CwiseUnaryOp<internal::scalar_cos_op<Scalar>, const Derived> CosReturnType;\ntypedef CwiseUnaryOp<internal::scalar_sin_op<Scalar>, const Derived> SinReturnType;\ntypedef CwiseUnaryOp<internal::scalar_tan_op<Scalar>, const Derived> TanReturnType;\ntypedef CwiseUnaryOp<internal::scalar_acos_op<Scalar>, const Derived> AcosReturnType;\ntypedef CwiseUnaryOp<internal::scalar_asin_op<Scalar>, const Derived> AsinReturnType;\ntypedef CwiseUnaryOp<internal::scalar_atan_op<Scalar>, const Derived> AtanReturnType;\ntypedef CwiseUnaryOp<internal::scalar_tanh_op<Scalar>, const Derived> TanhReturnType;\ntypedef CwiseUnaryOp<internal::scalar_logistic_op<Scalar>, const Derived> LogisticReturnType;\ntypedef CwiseUnaryOp<internal::scalar_sinh_op<Scalar>, const Derived> SinhReturnType;\n#if EIGEN_HAS_CXX11_MATH\ntypedef CwiseUnaryOp<internal::scalar_atanh_op<Scalar>, const Derived> AtanhReturnType;\ntypedef CwiseUnaryOp<internal::scalar_asinh_op<Scalar>, const Derived> AsinhReturnType;\ntypedef CwiseUnaryOp<internal::scalar_acosh_op<Scalar>, const Derived> AcoshReturnType;\n#endif\ntypedef CwiseUnaryOp<internal::scalar_cosh_op<Scalar>, const Derived> CoshReturnType;\ntypedef CwiseUnaryOp<internal::scalar_square_op<Scalar>, const Derived> SquareReturnType;\ntypedef CwiseUnaryOp<internal::scalar_cube_op<Scalar>, const Derived> CubeReturnType;\ntypedef CwiseUnaryOp<internal::scalar_round_op<Scalar>, const Derived> RoundReturnType;\ntypedef CwiseUnaryOp<internal::scalar_rint_op<Scalar>, const Derived> RintReturnType;\ntypedef CwiseUnaryOp<internal::scalar_floor_op<Scalar>, const Derived> FloorReturnType;\ntypedef CwiseUnaryOp<internal::scalar_ceil_op<Scalar>, const Derived> CeilReturnType;\ntypedef CwiseUnaryOp<internal::scalar_isnan_op<Scalar>, const Derived> IsNaNReturnType;\ntypedef CwiseUnaryOp<internal::scalar_isinf_op<Scalar>, const Derived> IsInfReturnType;\ntypedef CwiseUnaryOp<internal::scalar_isfinite_op<Scalar>, const Derived> IsFiniteReturnType;\n\n/** \\returns an expression of the coefficient-wise absolute value of \\c *this\n  *\n  * Example: \\include Cwise_abs.cpp\n  * Output: \\verbinclude Cwise_abs.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_abs\">Math functions</a>, abs2()\n  */\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const AbsReturnType\nabs() const\n{\n  return AbsReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise phase angle of \\c *this\n  *\n  * Example: \\include Cwise_arg.cpp\n  * Output: \\verbinclude Cwise_arg.out\n  *\n  * \\sa abs()\n  */\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const ArgReturnType\narg() const\n{\n  return ArgReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise squared absolute value of \\c *this\n  *\n  * Example: \\include Cwise_abs2.cpp\n  * Output: \\verbinclude Cwise_abs2.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_abs2\">Math functions</a>, abs(), square()\n  */\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const Abs2ReturnType\nabs2() const\n{\n  return Abs2ReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise exponential of *this.\n  *\n  * This function computes the coefficient-wise exponential. The function MatrixBase::exp() in the\n  * unsupported module MatrixFunctions computes the matrix exponential.\n  *\n  * Example: \\include Cwise_exp.cpp\n  * Output: \\verbinclude Cwise_exp.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_exp\">Math functions</a>, pow(), log(), sin(), cos()\n  */\nEIGEN_DEVICE_FUNC\ninline const ExpReturnType\nexp() const\n{\n  return ExpReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise exponential of *this minus 1.\n  *\n  * In exact arithmetic, \\c x.expm1() is equivalent to \\c x.exp() - 1,\n  * however, with finite precision, this function is much more accurate when \\c x is close to zero.\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_expm1\">Math functions</a>, exp()\n  */\nEIGEN_DEVICE_FUNC\ninline const Expm1ReturnType\nexpm1() const\n{\n  return Expm1ReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise logarithm of *this.\n  *\n  * This function computes the coefficient-wise logarithm. The function MatrixBase::log() in the\n  * unsupported module MatrixFunctions computes the matrix logarithm.\n  *\n  * Example: \\include Cwise_log.cpp\n  * Output: \\verbinclude Cwise_log.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_log\">Math functions</a>, log()\n  */\nEIGEN_DEVICE_FUNC\ninline const LogReturnType\nlog() const\n{\n  return LogReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise logarithm of 1 plus \\c *this.\n  *\n  * In exact arithmetic, \\c x.log() is equivalent to \\c (x+1).log(),\n  * however, with finite precision, this function is much more accurate when \\c x is close to zero.\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_log1p\">Math functions</a>, log()\n  */\nEIGEN_DEVICE_FUNC\ninline const Log1pReturnType\nlog1p() const\n{\n  return Log1pReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise base-10 logarithm of *this.\n  *\n  * This function computes the coefficient-wise base-10 logarithm.\n  *\n  * Example: \\include Cwise_log10.cpp\n  * Output: \\verbinclude Cwise_log10.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_log10\">Math functions</a>, log()\n  */\nEIGEN_DEVICE_FUNC\ninline const Log10ReturnType\nlog10() const\n{\n  return Log10ReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise base-2 logarithm of *this.\n  *\n  * This function computes the coefficient-wise base-2 logarithm.\n  *\n  */\nEIGEN_DEVICE_FUNC\ninline const Log2ReturnType\nlog2() const\n{\n  return Log2ReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise square root of *this.\n  *\n  * This function computes the coefficient-wise square root. The function MatrixBase::sqrt() in the\n  * unsupported module MatrixFunctions computes the matrix square root.\n  *\n  * Example: \\include Cwise_sqrt.cpp\n  * Output: \\verbinclude Cwise_sqrt.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_sqrt\">Math functions</a>, pow(), square()\n  */\nEIGEN_DEVICE_FUNC\ninline const SqrtReturnType\nsqrt() const\n{\n  return SqrtReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise inverse square root of *this.\n  *\n  * This function computes the coefficient-wise inverse square root.\n  *\n  * Example: \\include Cwise_sqrt.cpp\n  * Output: \\verbinclude Cwise_sqrt.out\n  *\n  * \\sa pow(), square()\n  */\nEIGEN_DEVICE_FUNC\ninline const RsqrtReturnType\nrsqrt() const\n{\n  return RsqrtReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise signum of *this.\n  *\n  * This function computes the coefficient-wise signum.\n  *\n  * Example: \\include Cwise_sign.cpp\n  * Output: \\verbinclude Cwise_sign.out\n  *\n  * \\sa pow(), square()\n  */\nEIGEN_DEVICE_FUNC\ninline const SignReturnType\nsign() const\n{\n  return SignReturnType(derived());\n}\n\n\n/** \\returns an expression of the coefficient-wise cosine of *this.\n  *\n  * This function computes the coefficient-wise cosine. The function MatrixBase::cos() in the\n  * unsupported module MatrixFunctions computes the matrix cosine.\n  *\n  * Example: \\include Cwise_cos.cpp\n  * Output: \\verbinclude Cwise_cos.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_cos\">Math functions</a>, sin(), acos()\n  */\nEIGEN_DEVICE_FUNC\ninline const CosReturnType\ncos() const\n{\n  return CosReturnType(derived());\n}\n\n\n/** \\returns an expression of the coefficient-wise sine of *this.\n  *\n  * This function computes the coefficient-wise sine. The function MatrixBase::sin() in the\n  * unsupported module MatrixFunctions computes the matrix sine.\n  *\n  * Example: \\include Cwise_sin.cpp\n  * Output: \\verbinclude Cwise_sin.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_sin\">Math functions</a>, cos(), asin()\n  */\nEIGEN_DEVICE_FUNC\ninline const SinReturnType\nsin() const\n{\n  return SinReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise tan of *this.\n  *\n  * Example: \\include Cwise_tan.cpp\n  * Output: \\verbinclude Cwise_tan.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_tan\">Math functions</a>, cos(), sin()\n  */\nEIGEN_DEVICE_FUNC\ninline const TanReturnType\ntan() const\n{\n  return TanReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise arc tan of *this.\n  *\n  * Example: \\include Cwise_atan.cpp\n  * Output: \\verbinclude Cwise_atan.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_atan\">Math functions</a>, tan(), asin(), acos()\n  */\nEIGEN_DEVICE_FUNC\ninline const AtanReturnType\natan() const\n{\n  return AtanReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise arc cosine of *this.\n  *\n  * Example: \\include Cwise_acos.cpp\n  * Output: \\verbinclude Cwise_acos.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_acos\">Math functions</a>, cos(), asin()\n  */\nEIGEN_DEVICE_FUNC\ninline const AcosReturnType\nacos() const\n{\n  return AcosReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise arc sine of *this.\n  *\n  * Example: \\include Cwise_asin.cpp\n  * Output: \\verbinclude Cwise_asin.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_asin\">Math functions</a>, sin(), acos()\n  */\nEIGEN_DEVICE_FUNC\ninline const AsinReturnType\nasin() const\n{\n  return AsinReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise hyperbolic tan of *this.\n  *\n  * Example: \\include Cwise_tanh.cpp\n  * Output: \\verbinclude Cwise_tanh.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_tanh\">Math functions</a>, tan(), sinh(), cosh()\n  */\nEIGEN_DEVICE_FUNC\ninline const TanhReturnType\ntanh() const\n{\n  return TanhReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise hyperbolic sin of *this.\n  *\n  * Example: \\include Cwise_sinh.cpp\n  * Output: \\verbinclude Cwise_sinh.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_sinh\">Math functions</a>, sin(), tanh(), cosh()\n  */\nEIGEN_DEVICE_FUNC\ninline const SinhReturnType\nsinh() const\n{\n  return SinhReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise hyperbolic cos of *this.\n  *\n  * Example: \\include Cwise_cosh.cpp\n  * Output: \\verbinclude Cwise_cosh.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_cosh\">Math functions</a>, tanh(), sinh(), cosh()\n  */\nEIGEN_DEVICE_FUNC\ninline const CoshReturnType\ncosh() const\n{\n  return CoshReturnType(derived());\n}\n\n#if EIGEN_HAS_CXX11_MATH\n/** \\returns an expression of the coefficient-wise inverse hyperbolic tan of *this.\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_atanh\">Math functions</a>, atanh(), asinh(), acosh()\n  */\nEIGEN_DEVICE_FUNC\ninline const AtanhReturnType\natanh() const\n{\n  return AtanhReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise inverse hyperbolic sin of *this.\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_asinh\">Math functions</a>, atanh(), asinh(), acosh()\n  */\nEIGEN_DEVICE_FUNC\ninline const AsinhReturnType\nasinh() const\n{\n  return AsinhReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise inverse hyperbolic cos of *this.\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_acosh\">Math functions</a>, atanh(), asinh(), acosh()\n  */\nEIGEN_DEVICE_FUNC\ninline const AcoshReturnType\nacosh() const\n{\n  return AcoshReturnType(derived());\n}\n#endif\n\n/** \\returns an expression of the coefficient-wise logistic of *this.\n  */\nEIGEN_DEVICE_FUNC\ninline const LogisticReturnType\nlogistic() const\n{\n  return LogisticReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise inverse of *this.\n  *\n  * Example: \\include Cwise_inverse.cpp\n  * Output: \\verbinclude Cwise_inverse.out\n  *\n  * \\sa operator/(), operator*()\n  */\nEIGEN_DEVICE_FUNC\ninline const InverseReturnType\ninverse() const\n{\n  return InverseReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise square of *this.\n  *\n  * Example: \\include Cwise_square.cpp\n  * Output: \\verbinclude Cwise_square.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_squareE\">Math functions</a>, abs2(), cube(), pow()\n  */\nEIGEN_DEVICE_FUNC\ninline const SquareReturnType\nsquare() const\n{\n  return SquareReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise cube of *this.\n  *\n  * Example: \\include Cwise_cube.cpp\n  * Output: \\verbinclude Cwise_cube.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_cube\">Math functions</a>, square(), pow()\n  */\nEIGEN_DEVICE_FUNC\ninline const CubeReturnType\ncube() const\n{\n  return CubeReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise rint of *this.\n  *\n  * Example: \\include Cwise_rint.cpp\n  * Output: \\verbinclude Cwise_rint.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_rint\">Math functions</a>, ceil(), floor()\n  */\nEIGEN_DEVICE_FUNC\ninline const RintReturnType\nrint() const\n{\n  return RintReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise round of *this.\n  *\n  * Example: \\include Cwise_round.cpp\n  * Output: \\verbinclude Cwise_round.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_round\">Math functions</a>, ceil(), floor()\n  */\nEIGEN_DEVICE_FUNC\ninline const RoundReturnType\nround() const\n{\n  return RoundReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise floor of *this.\n  *\n  * Example: \\include Cwise_floor.cpp\n  * Output: \\verbinclude Cwise_floor.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_floor\">Math functions</a>, ceil(), round()\n  */\nEIGEN_DEVICE_FUNC\ninline const FloorReturnType\nfloor() const\n{\n  return FloorReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise ceil of *this.\n  *\n  * Example: \\include Cwise_ceil.cpp\n  * Output: \\verbinclude Cwise_ceil.out\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_ceil\">Math functions</a>, floor(), round()\n  */\nEIGEN_DEVICE_FUNC\ninline const CeilReturnType\nceil() const\n{\n  return CeilReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise isnan of *this.\n  *\n  * Example: \\include Cwise_isNaN.cpp\n  * Output: \\verbinclude Cwise_isNaN.out\n  *\n  * \\sa isfinite(), isinf()\n  */\nEIGEN_DEVICE_FUNC\ninline const IsNaNReturnType\nisNaN() const\n{\n  return IsNaNReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise isinf of *this.\n  *\n  * Example: \\include Cwise_isInf.cpp\n  * Output: \\verbinclude Cwise_isInf.out\n  *\n  * \\sa isnan(), isfinite()\n  */\nEIGEN_DEVICE_FUNC\ninline const IsInfReturnType\nisInf() const\n{\n  return IsInfReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise isfinite of *this.\n  *\n  * Example: \\include Cwise_isFinite.cpp\n  * Output: \\verbinclude Cwise_isFinite.out\n  *\n  * \\sa isnan(), isinf()\n  */\nEIGEN_DEVICE_FUNC\ninline const IsFiniteReturnType\nisFinite() const\n{\n  return IsFiniteReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise ! operator of *this\n  *\n  * \\warning this operator is for expression of bool only.\n  *\n  * Example: \\include Cwise_boolean_not.cpp\n  * Output: \\verbinclude Cwise_boolean_not.out\n  *\n  * \\sa operator!=()\n  */\nEIGEN_DEVICE_FUNC\ninline const BooleanNotReturnType\noperator!() const\n{\n  EIGEN_STATIC_ASSERT((internal::is_same<bool,Scalar>::value),\n                      THIS_METHOD_IS_ONLY_FOR_EXPRESSIONS_OF_BOOL);\n  return BooleanNotReturnType(derived());\n}\n\n\n// --- SpecialFunctions module ---\n\ntypedef CwiseUnaryOp<internal::scalar_lgamma_op<Scalar>, const Derived> LgammaReturnType;\ntypedef CwiseUnaryOp<internal::scalar_digamma_op<Scalar>, const Derived> DigammaReturnType;\ntypedef CwiseUnaryOp<internal::scalar_erf_op<Scalar>, const Derived> ErfReturnType;\ntypedef CwiseUnaryOp<internal::scalar_erfc_op<Scalar>, const Derived> ErfcReturnType;\ntypedef CwiseUnaryOp<internal::scalar_ndtri_op<Scalar>, const Derived> NdtriReturnType;\n\n/** \\cpp11 \\returns an expression of the coefficient-wise ln(|gamma(*this)|).\n  *\n  * \\specialfunctions_module\n  *\n  * \\note This function supports only float and double scalar types in c++11 mode. To support other scalar types,\n  * or float/double in non c++11 mode, the user has to provide implementations of lgamma(T) for any scalar\n  * type T to be supported.\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_lgamma\">Math functions</a>, digamma()\n  */\nEIGEN_DEVICE_FUNC\ninline const LgammaReturnType\nlgamma() const\n{\n  return LgammaReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise digamma (psi, derivative of lgamma).\n  *\n  * \\specialfunctions_module\n  *\n  * \\note This function supports only float and double scalar types. To support other scalar types,\n  * the user has to provide implementations of digamma(T) for any scalar\n  * type T to be supported.\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_digamma\">Math functions</a>, Eigen::digamma(), Eigen::polygamma(), lgamma()\n  */\nEIGEN_DEVICE_FUNC\ninline const DigammaReturnType\ndigamma() const\n{\n  return DigammaReturnType(derived());\n}\n\n/** \\cpp11 \\returns an expression of the coefficient-wise Gauss error\n  * function of *this.\n  *\n  * \\specialfunctions_module\n  *\n  * \\note This function supports only float and double scalar types in c++11 mode. To support other scalar types,\n  * or float/double in non c++11 mode, the user has to provide implementations of erf(T) for any scalar\n  * type T to be supported.\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_erf\">Math functions</a>, erfc()\n  */\nEIGEN_DEVICE_FUNC\ninline const ErfReturnType\nerf() const\n{\n  return ErfReturnType(derived());\n}\n\n/** \\cpp11 \\returns an expression of the coefficient-wise Complementary error\n  * function of *this.\n  *\n  * \\specialfunctions_module\n  *\n  * \\note This function supports only float and double scalar types in c++11 mode. To support other scalar types,\n  * or float/double in non c++11 mode, the user has to provide implementations of erfc(T) for any scalar\n  * type T to be supported.\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_erfc\">Math functions</a>, erf()\n  */\nEIGEN_DEVICE_FUNC\ninline const ErfcReturnType\nerfc() const\n{\n  return ErfcReturnType(derived());\n}\n\n/** \\returns an expression of the coefficient-wise inverse of the CDF of the Normal distribution function\n  * function of *this.\n  *\n  * \\specialfunctions_module\n  * \n  * In other words, considering `x = ndtri(y)`, it returns the argument, x, for which the area under the\n  * Gaussian probability density function (integrated from minus infinity to x) is equal to y.\n  *\n  * \\note This function supports only float and double scalar types. To support other scalar types,\n  * the user has to provide implementations of ndtri(T) for any scalar type T to be supported.\n  *\n  * \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_ndtri\">Math functions</a>\n  */\nEIGEN_DEVICE_FUNC\ninline const NdtriReturnType\nndtri() const\n{\n  return NdtriReturnType(derived());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/plugins/BlockMethods.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2006-2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n\n/// \\internal expression type of a column */\ntypedef Block<Derived, internal::traits<Derived>::RowsAtCompileTime, 1, !IsRowMajor> ColXpr;\ntypedef const Block<const Derived, internal::traits<Derived>::RowsAtCompileTime, 1, !IsRowMajor> ConstColXpr;\n/// \\internal expression type of a row */\ntypedef Block<Derived, 1, internal::traits<Derived>::ColsAtCompileTime, IsRowMajor> RowXpr;\ntypedef const Block<const Derived, 1, internal::traits<Derived>::ColsAtCompileTime, IsRowMajor> ConstRowXpr;\n/// \\internal expression type of a block of whole columns */\ntypedef Block<Derived, internal::traits<Derived>::RowsAtCompileTime, Dynamic, !IsRowMajor> ColsBlockXpr;\ntypedef const Block<const Derived, internal::traits<Derived>::RowsAtCompileTime, Dynamic, !IsRowMajor> ConstColsBlockXpr;\n/// \\internal expression type of a block of whole rows */\ntypedef Block<Derived, Dynamic, internal::traits<Derived>::ColsAtCompileTime, IsRowMajor> RowsBlockXpr;\ntypedef const Block<const Derived, Dynamic, internal::traits<Derived>::ColsAtCompileTime, IsRowMajor> ConstRowsBlockXpr;\n/// \\internal expression type of a block of whole columns */\ntemplate<int N> struct NColsBlockXpr { typedef Block<Derived, internal::traits<Derived>::RowsAtCompileTime, N, !IsRowMajor> Type; };\ntemplate<int N> struct ConstNColsBlockXpr { typedef const Block<const Derived, internal::traits<Derived>::RowsAtCompileTime, N, !IsRowMajor> Type; };\n/// \\internal expression type of a block of whole rows */\ntemplate<int N> struct NRowsBlockXpr { typedef Block<Derived, N, internal::traits<Derived>::ColsAtCompileTime, IsRowMajor> Type; };\ntemplate<int N> struct ConstNRowsBlockXpr { typedef const Block<const Derived, N, internal::traits<Derived>::ColsAtCompileTime, IsRowMajor> Type; };\n/// \\internal expression of a block */\ntypedef Block<Derived> BlockXpr;\ntypedef const Block<const Derived> ConstBlockXpr;\n/// \\internal expression of a block of fixed sizes */\ntemplate<int Rows, int Cols> struct FixedBlockXpr { typedef Block<Derived,Rows,Cols> Type; };\ntemplate<int Rows, int Cols> struct ConstFixedBlockXpr { typedef Block<const Derived,Rows,Cols> Type; };\n\ntypedef VectorBlock<Derived> SegmentReturnType;\ntypedef const VectorBlock<const Derived> ConstSegmentReturnType;\ntemplate<int Size> struct FixedSegmentReturnType { typedef VectorBlock<Derived, Size> Type; };\ntemplate<int Size> struct ConstFixedSegmentReturnType { typedef const VectorBlock<const Derived, Size> Type; };\n\n/// \\internal inner-vector\ntypedef Block<Derived,IsRowMajor?1:Dynamic,IsRowMajor?Dynamic:1,true>       InnerVectorReturnType;\ntypedef Block<const Derived,IsRowMajor?1:Dynamic,IsRowMajor?Dynamic:1,true> ConstInnerVectorReturnType;\n\n/// \\internal set of inner-vectors\ntypedef Block<Derived,Dynamic,Dynamic,true> InnerVectorsReturnType;\ntypedef Block<const Derived,Dynamic,Dynamic,true> ConstInnerVectorsReturnType;\n\n#endif // not EIGEN_PARSED_BY_DOXYGEN\n\n/// \\returns an expression of a block in \\c *this with either dynamic or fixed sizes.\n///\n/// \\param  startRow  the first row in the block\n/// \\param  startCol  the first column in the block\n/// \\param  blockRows number of rows in the block, specified at either run-time or compile-time\n/// \\param  blockCols number of columns in the block, specified at either run-time or compile-time\n/// \\tparam NRowsType the type of the value handling the number of rows in the block, typically Index.\n/// \\tparam NColsType the type of the value handling the number of columns in the block, typically Index.\n///\n/// Example using runtime (aka dynamic) sizes: \\include MatrixBase_block_int_int_int_int.cpp\n/// Output: \\verbinclude MatrixBase_block_int_int_int_int.out\n///\n/// \\newin{3.4}:\n///\n/// The number of rows \\a blockRows and columns \\a blockCols can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments. In the later case, \\c n plays the role of a runtime fallback value in case \\c N equals Eigen::Dynamic.\n/// Here is an example with a fixed number of rows \\c NRows and dynamic number of columns \\c cols:\n/// \\code\n/// mat.block(i,j,fix<NRows>,cols)\n/// \\endcode\n///\n/// This function thus fully covers the features offered by the following overloads block<NRows,NCols>(Index, Index),\n/// and block<NRows,NCols>(Index, Index, Index, Index) that are thus obsolete. Indeed, this generic version avoids\n/// redundancy, it preserves the argument order, and prevents the need to rely on the template keyword in templated code.\n///\n/// but with less redundancy and more consistency as it does not modify the argument order\n/// and seamlessly enable hybrid fixed/dynamic sizes.\n///\n/// \\note Even in the case that the returned expression has dynamic size, in the case\n/// when it is applied to a fixed-size matrix, it inherits a fixed maximal size,\n/// which means that evaluating it does not cause a dynamic memory allocation.\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa class Block, fix, fix<N>(int)\n///\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename FixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n#else\ntypename FixedBlockXpr<...,...>::Type\n#endif\nblock(Index startRow, Index startCol, NRowsType blockRows, NColsType blockCols)\n{\n  return typename FixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type(\n            derived(), startRow, startCol, internal::get_runtime_value(blockRows), internal::get_runtime_value(blockCols));\n}\n\n/// This is the const version of block(Index,Index,NRowsType,NColsType)\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstFixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n#else\nconst typename ConstFixedBlockXpr<...,...>::Type\n#endif\nblock(Index startRow, Index startCol, NRowsType blockRows, NColsType blockCols) const\n{\n  return typename ConstFixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type(\n            derived(), startRow, startCol, internal::get_runtime_value(blockRows), internal::get_runtime_value(blockCols));\n}\n\n\n\n/// \\returns a expression of a top-right corner of \\c *this with either dynamic or fixed sizes.\n///\n/// \\param cRows the number of rows in the corner\n/// \\param cCols the number of columns in the corner\n/// \\tparam NRowsType the type of the value handling the number of rows in the block, typically Index.\n/// \\tparam NColsType the type of the value handling the number of columns in the block, typically Index.\n///\n/// Example with dynamic sizes: \\include MatrixBase_topRightCorner_int_int.cpp\n/// Output: \\verbinclude MatrixBase_topRightCorner_int_int.out\n///\n/// The number of rows \\a blockRows and columns \\a blockCols can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments. See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename FixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n#else\ntypename FixedBlockXpr<...,...>::Type\n#endif\ntopRightCorner(NRowsType cRows, NColsType cCols)\n{\n  return typename FixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), 0, cols() - internal::get_runtime_value(cCols), internal::get_runtime_value(cRows), internal::get_runtime_value(cCols));\n}\n\n/// This is the const version of topRightCorner(NRowsType, NColsType).\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstFixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n#else\nconst typename ConstFixedBlockXpr<...,...>::Type\n#endif\ntopRightCorner(NRowsType cRows, NColsType cCols) const\n{\n  return typename ConstFixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), 0, cols() - internal::get_runtime_value(cCols), internal::get_runtime_value(cRows), internal::get_runtime_value(cCols));\n}\n\n/// \\returns an expression of a fixed-size top-right corner of \\c *this.\n///\n/// \\tparam CRows the number of rows in the corner\n/// \\tparam CCols the number of columns in the corner\n///\n/// Example: \\include MatrixBase_template_int_int_topRightCorner.cpp\n/// Output: \\verbinclude MatrixBase_template_int_int_topRightCorner.out\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa class Block, block<int,int>(Index,Index)\n///\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedBlockXpr<CRows,CCols>::Type topRightCorner()\n{\n  return typename FixedBlockXpr<CRows,CCols>::Type(derived(), 0, cols() - CCols);\n}\n\n/// This is the const version of topRightCorner<int, int>().\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst typename ConstFixedBlockXpr<CRows,CCols>::Type topRightCorner() const\n{\n  return typename ConstFixedBlockXpr<CRows,CCols>::Type(derived(), 0, cols() - CCols);\n}\n\n/// \\returns an expression of a top-right corner of \\c *this.\n///\n/// \\tparam CRows number of rows in corner as specified at compile-time\n/// \\tparam CCols number of columns in corner as specified at compile-time\n/// \\param  cRows number of rows in corner as specified at run-time\n/// \\param  cCols number of columns in corner as specified at run-time\n///\n/// This function is mainly useful for corners where the number of rows is specified at compile-time\n/// and the number of columns is specified at run-time, or vice versa. The compile-time and run-time\n/// information should not contradict. In other words, \\a cRows should equal \\a CRows unless\n/// \\a CRows is \\a Dynamic, and the same for the number of columns.\n///\n/// Example: \\include MatrixBase_template_int_int_topRightCorner_int_int.cpp\n/// Output: \\verbinclude MatrixBase_template_int_int_topRightCorner_int_int.out\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa class Block\n///\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedBlockXpr<CRows,CCols>::Type topRightCorner(Index cRows, Index cCols)\n{\n  return typename FixedBlockXpr<CRows,CCols>::Type(derived(), 0, cols() - cCols, cRows, cCols);\n}\n\n/// This is the const version of topRightCorner<int, int>(Index, Index).\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst typename ConstFixedBlockXpr<CRows,CCols>::Type topRightCorner(Index cRows, Index cCols) const\n{\n  return typename ConstFixedBlockXpr<CRows,CCols>::Type(derived(), 0, cols() - cCols, cRows, cCols);\n}\n\n\n\n/// \\returns an expression of a top-left corner of \\c *this  with either dynamic or fixed sizes.\n///\n/// \\param cRows the number of rows in the corner\n/// \\param cCols the number of columns in the corner\n/// \\tparam NRowsType the type of the value handling the number of rows in the block, typically Index.\n/// \\tparam NColsType the type of the value handling the number of columns in the block, typically Index.\n///\n/// Example: \\include MatrixBase_topLeftCorner_int_int.cpp\n/// Output: \\verbinclude MatrixBase_topLeftCorner_int_int.out\n///\n/// The number of rows \\a blockRows and columns \\a blockCols can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments. See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename FixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n#else\ntypename FixedBlockXpr<...,...>::Type\n#endif\ntopLeftCorner(NRowsType cRows, NColsType cCols)\n{\n  return typename FixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), 0, 0, internal::get_runtime_value(cRows), internal::get_runtime_value(cCols));\n}\n\n/// This is the const version of topLeftCorner(Index, Index).\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstFixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n#else\nconst typename ConstFixedBlockXpr<...,...>::Type\n#endif\ntopLeftCorner(NRowsType cRows, NColsType cCols) const\n{\n  return typename ConstFixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), 0, 0, internal::get_runtime_value(cRows), internal::get_runtime_value(cCols));\n}\n\n/// \\returns an expression of a fixed-size top-left corner of \\c *this.\n///\n/// The template parameters CRows and CCols are the number of rows and columns in the corner.\n///\n/// Example: \\include MatrixBase_template_int_int_topLeftCorner.cpp\n/// Output: \\verbinclude MatrixBase_template_int_int_topLeftCorner.out\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedBlockXpr<CRows,CCols>::Type topLeftCorner()\n{\n  return typename FixedBlockXpr<CRows,CCols>::Type(derived(), 0, 0);\n}\n\n/// This is the const version of topLeftCorner<int, int>().\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst typename ConstFixedBlockXpr<CRows,CCols>::Type topLeftCorner() const\n{\n  return typename ConstFixedBlockXpr<CRows,CCols>::Type(derived(), 0, 0);\n}\n\n/// \\returns an expression of a top-left corner of \\c *this.\n///\n/// \\tparam CRows number of rows in corner as specified at compile-time\n/// \\tparam CCols number of columns in corner as specified at compile-time\n/// \\param  cRows number of rows in corner as specified at run-time\n/// \\param  cCols number of columns in corner as specified at run-time\n///\n/// This function is mainly useful for corners where the number of rows is specified at compile-time\n/// and the number of columns is specified at run-time, or vice versa. The compile-time and run-time\n/// information should not contradict. In other words, \\a cRows should equal \\a CRows unless\n/// \\a CRows is \\a Dynamic, and the same for the number of columns.\n///\n/// Example: \\include MatrixBase_template_int_int_topLeftCorner_int_int.cpp\n/// Output: \\verbinclude MatrixBase_template_int_int_topLeftCorner_int_int.out\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa class Block\n///\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedBlockXpr<CRows,CCols>::Type topLeftCorner(Index cRows, Index cCols)\n{\n  return typename FixedBlockXpr<CRows,CCols>::Type(derived(), 0, 0, cRows, cCols);\n}\n\n/// This is the const version of topLeftCorner<int, int>(Index, Index).\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst typename ConstFixedBlockXpr<CRows,CCols>::Type topLeftCorner(Index cRows, Index cCols) const\n{\n  return typename ConstFixedBlockXpr<CRows,CCols>::Type(derived(), 0, 0, cRows, cCols);\n}\n\n\n\n/// \\returns an expression of a bottom-right corner of \\c *this  with either dynamic or fixed sizes.\n///\n/// \\param cRows the number of rows in the corner\n/// \\param cCols the number of columns in the corner\n/// \\tparam NRowsType the type of the value handling the number of rows in the block, typically Index.\n/// \\tparam NColsType the type of the value handling the number of columns in the block, typically Index.\n///\n/// Example: \\include MatrixBase_bottomRightCorner_int_int.cpp\n/// Output: \\verbinclude MatrixBase_bottomRightCorner_int_int.out\n///\n/// The number of rows \\a blockRows and columns \\a blockCols can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments. See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename FixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n#else\ntypename FixedBlockXpr<...,...>::Type\n#endif\nbottomRightCorner(NRowsType cRows, NColsType cCols)\n{\n  return typename FixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), rows() - internal::get_runtime_value(cRows), cols() - internal::get_runtime_value(cCols),\n                        internal::get_runtime_value(cRows), internal::get_runtime_value(cCols));\n}\n\n/// This is the const version of bottomRightCorner(NRowsType, NColsType).\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstFixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n#else\nconst typename ConstFixedBlockXpr<...,...>::Type\n#endif\nbottomRightCorner(NRowsType cRows, NColsType cCols) const\n{\n  return typename ConstFixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), rows() - internal::get_runtime_value(cRows), cols() - internal::get_runtime_value(cCols),\n                        internal::get_runtime_value(cRows), internal::get_runtime_value(cCols));\n}\n\n/// \\returns an expression of a fixed-size bottom-right corner of \\c *this.\n///\n/// The template parameters CRows and CCols are the number of rows and columns in the corner.\n///\n/// Example: \\include MatrixBase_template_int_int_bottomRightCorner.cpp\n/// Output: \\verbinclude MatrixBase_template_int_int_bottomRightCorner.out\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedBlockXpr<CRows,CCols>::Type bottomRightCorner()\n{\n  return typename FixedBlockXpr<CRows,CCols>::Type(derived(), rows() - CRows, cols() - CCols);\n}\n\n/// This is the const version of bottomRightCorner<int, int>().\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst typename ConstFixedBlockXpr<CRows,CCols>::Type bottomRightCorner() const\n{\n  return typename ConstFixedBlockXpr<CRows,CCols>::Type(derived(), rows() - CRows, cols() - CCols);\n}\n\n/// \\returns an expression of a bottom-right corner of \\c *this.\n///\n/// \\tparam CRows number of rows in corner as specified at compile-time\n/// \\tparam CCols number of columns in corner as specified at compile-time\n/// \\param  cRows number of rows in corner as specified at run-time\n/// \\param  cCols number of columns in corner as specified at run-time\n///\n/// This function is mainly useful for corners where the number of rows is specified at compile-time\n/// and the number of columns is specified at run-time, or vice versa. The compile-time and run-time\n/// information should not contradict. In other words, \\a cRows should equal \\a CRows unless\n/// \\a CRows is \\a Dynamic, and the same for the number of columns.\n///\n/// Example: \\include MatrixBase_template_int_int_bottomRightCorner_int_int.cpp\n/// Output: \\verbinclude MatrixBase_template_int_int_bottomRightCorner_int_int.out\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa class Block\n///\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedBlockXpr<CRows,CCols>::Type bottomRightCorner(Index cRows, Index cCols)\n{\n  return typename FixedBlockXpr<CRows,CCols>::Type(derived(), rows() - cRows, cols() - cCols, cRows, cCols);\n}\n\n/// This is the const version of bottomRightCorner<int, int>(Index, Index).\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst typename ConstFixedBlockXpr<CRows,CCols>::Type bottomRightCorner(Index cRows, Index cCols) const\n{\n  return typename ConstFixedBlockXpr<CRows,CCols>::Type(derived(), rows() - cRows, cols() - cCols, cRows, cCols);\n}\n\n\n\n/// \\returns an expression of a bottom-left corner of \\c *this  with either dynamic or fixed sizes.\n///\n/// \\param cRows the number of rows in the corner\n/// \\param cCols the number of columns in the corner\n/// \\tparam NRowsType the type of the value handling the number of rows in the block, typically Index.\n/// \\tparam NColsType the type of the value handling the number of columns in the block, typically Index.\n///\n/// Example: \\include MatrixBase_bottomLeftCorner_int_int.cpp\n/// Output: \\verbinclude MatrixBase_bottomLeftCorner_int_int.out\n///\n/// The number of rows \\a blockRows and columns \\a blockCols can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments. See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename FixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n#else\ntypename FixedBlockXpr<...,...>::Type\n#endif\nbottomLeftCorner(NRowsType cRows, NColsType cCols)\n{\n  return typename FixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), rows() - internal::get_runtime_value(cRows), 0,\n                        internal::get_runtime_value(cRows), internal::get_runtime_value(cCols));\n}\n\n/// This is the const version of bottomLeftCorner(NRowsType, NColsType).\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename ConstFixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n#else\ntypename ConstFixedBlockXpr<...,...>::Type\n#endif\nbottomLeftCorner(NRowsType cRows, NColsType cCols) const\n{\n  return typename ConstFixedBlockXpr<internal::get_fixed_value<NRowsType>::value,internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), rows() - internal::get_runtime_value(cRows), 0,\n                        internal::get_runtime_value(cRows), internal::get_runtime_value(cCols));\n}\n\n/// \\returns an expression of a fixed-size bottom-left corner of \\c *this.\n///\n/// The template parameters CRows and CCols are the number of rows and columns in the corner.\n///\n/// Example: \\include MatrixBase_template_int_int_bottomLeftCorner.cpp\n/// Output: \\verbinclude MatrixBase_template_int_int_bottomLeftCorner.out\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedBlockXpr<CRows,CCols>::Type bottomLeftCorner()\n{\n  return typename FixedBlockXpr<CRows,CCols>::Type(derived(), rows() - CRows, 0);\n}\n\n/// This is the const version of bottomLeftCorner<int, int>().\ntemplate<int CRows, int CCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst typename ConstFixedBlockXpr<CRows,CCols>::Type bottomLeftCorner() const\n{\n  return typename ConstFixedBlockXpr<CRows,CCols>::Type(derived(), rows() - CRows, 0);\n}\n\n/// \\returns an expression of a bottom-left corner of \\c *this.\n///\n/// \\tparam CRows number of rows in corner as specified at compile-time\n/// \\tparam CCols number of columns in corner as specified at compile-time\n/// \\param  cRows number of rows in corner as specified at run-time\n/// \\param  cCols number of columns in corner as specified at run-time\n///\n/// This function is mainly useful for corners where the number of rows is specified at compile-time\n/// and the number of columns is specified at run-time, or vice versa. The compile-time and run-time\n/// information should not contradict. In other words, \\a cRows should equal \\a CRows unless\n/// \\a CRows is \\a Dynamic, and the same for the number of columns.\n///\n/// Example: \\include MatrixBase_template_int_int_bottomLeftCorner_int_int.cpp\n/// Output: \\verbinclude MatrixBase_template_int_int_bottomLeftCorner_int_int.out\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa class Block\n///\ntemplate<int CRows, int CCols>\nEIGEN_STRONG_INLINE\ntypename FixedBlockXpr<CRows,CCols>::Type bottomLeftCorner(Index cRows, Index cCols)\n{\n  return typename FixedBlockXpr<CRows,CCols>::Type(derived(), rows() - cRows, 0, cRows, cCols);\n}\n\n/// This is the const version of bottomLeftCorner<int, int>(Index, Index).\ntemplate<int CRows, int CCols>\nEIGEN_STRONG_INLINE\nconst typename ConstFixedBlockXpr<CRows,CCols>::Type bottomLeftCorner(Index cRows, Index cCols) const\n{\n  return typename ConstFixedBlockXpr<CRows,CCols>::Type(derived(), rows() - cRows, 0, cRows, cCols);\n}\n\n\n\n/// \\returns a block consisting of the top rows of \\c *this.\n///\n/// \\param n the number of rows in the block\n/// \\tparam NRowsType the type of the value handling the number of rows in the block, typically Index.\n///\n/// Example: \\include MatrixBase_topRows_int.cpp\n/// Output: \\verbinclude MatrixBase_topRows_int.out\n///\n/// The number of rows \\a n can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments.\n/// See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<typename NRowsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename NRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n#else\ntypename NRowsBlockXpr<...>::Type\n#endif\ntopRows(NRowsType n)\n{\n  return typename NRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n            (derived(), 0, 0, internal::get_runtime_value(n), cols());\n}\n\n/// This is the const version of topRows(NRowsType).\ntemplate<typename NRowsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstNRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n#else\nconst typename ConstNRowsBlockXpr<...>::Type\n#endif\ntopRows(NRowsType n) const\n{\n  return typename ConstNRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n            (derived(), 0, 0, internal::get_runtime_value(n), cols());\n}\n\n/// \\returns a block consisting of the top rows of \\c *this.\n///\n/// \\tparam N the number of rows in the block as specified at compile-time\n/// \\param n the number of rows in the block as specified at run-time\n///\n/// The compile-time and run-time information should not contradict. In other words,\n/// \\a n should equal \\a N unless \\a N is \\a Dynamic.\n///\n/// Example: \\include MatrixBase_template_int_topRows.cpp\n/// Output: \\verbinclude MatrixBase_template_int_topRows.out\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename NRowsBlockXpr<N>::Type topRows(Index n = N)\n{\n  return typename NRowsBlockXpr<N>::Type(derived(), 0, 0, n, cols());\n}\n\n/// This is the const version of topRows<int>().\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename ConstNRowsBlockXpr<N>::Type topRows(Index n = N) const\n{\n  return typename ConstNRowsBlockXpr<N>::Type(derived(), 0, 0, n, cols());\n}\n\n\n\n/// \\returns a block consisting of the bottom rows of \\c *this.\n///\n/// \\param n the number of rows in the block\n/// \\tparam NRowsType the type of the value handling the number of rows in the block, typically Index.\n///\n/// Example: \\include MatrixBase_bottomRows_int.cpp\n/// Output: \\verbinclude MatrixBase_bottomRows_int.out\n///\n/// The number of rows \\a n can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments.\n/// See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<typename NRowsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename NRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n#else\ntypename NRowsBlockXpr<...>::Type\n#endif\nbottomRows(NRowsType n)\n{\n  return typename NRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n            (derived(), rows() - internal::get_runtime_value(n), 0, internal::get_runtime_value(n), cols());\n}\n\n/// This is the const version of bottomRows(NRowsType).\ntemplate<typename NRowsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstNRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n#else\nconst typename ConstNRowsBlockXpr<...>::Type\n#endif\nbottomRows(NRowsType n) const\n{\n  return typename ConstNRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n            (derived(), rows() - internal::get_runtime_value(n), 0, internal::get_runtime_value(n), cols());\n}\n\n/// \\returns a block consisting of the bottom rows of \\c *this.\n///\n/// \\tparam N the number of rows in the block as specified at compile-time\n/// \\param n the number of rows in the block as specified at run-time\n///\n/// The compile-time and run-time information should not contradict. In other words,\n/// \\a n should equal \\a N unless \\a N is \\a Dynamic.\n///\n/// Example: \\include MatrixBase_template_int_bottomRows.cpp\n/// Output: \\verbinclude MatrixBase_template_int_bottomRows.out\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename NRowsBlockXpr<N>::Type bottomRows(Index n = N)\n{\n  return typename NRowsBlockXpr<N>::Type(derived(), rows() - n, 0, n, cols());\n}\n\n/// This is the const version of bottomRows<int>().\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename ConstNRowsBlockXpr<N>::Type bottomRows(Index n = N) const\n{\n  return typename ConstNRowsBlockXpr<N>::Type(derived(), rows() - n, 0, n, cols());\n}\n\n\n\n/// \\returns a block consisting of a range of rows of \\c *this.\n///\n/// \\param startRow the index of the first row in the block\n/// \\param n the number of rows in the block\n/// \\tparam NRowsType the type of the value handling the number of rows in the block, typically Index.\n///\n/// Example: \\include DenseBase_middleRows_int.cpp\n/// Output: \\verbinclude DenseBase_middleRows_int.out\n///\n/// The number of rows \\a n can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments.\n/// See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<typename NRowsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename NRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n#else\ntypename NRowsBlockXpr<...>::Type\n#endif\nmiddleRows(Index startRow, NRowsType n)\n{\n  return typename NRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n            (derived(), startRow, 0, internal::get_runtime_value(n), cols());\n}\n\n/// This is the const version of middleRows(Index,NRowsType).\ntemplate<typename NRowsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstNRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n#else\nconst typename ConstNRowsBlockXpr<...>::Type\n#endif\nmiddleRows(Index startRow, NRowsType n) const\n{\n  return typename ConstNRowsBlockXpr<internal::get_fixed_value<NRowsType>::value>::Type\n            (derived(), startRow, 0, internal::get_runtime_value(n), cols());\n}\n\n/// \\returns a block consisting of a range of rows of \\c *this.\n///\n/// \\tparam N the number of rows in the block as specified at compile-time\n/// \\param startRow the index of the first row in the block\n/// \\param n the number of rows in the block as specified at run-time\n///\n/// The compile-time and run-time information should not contradict. In other words,\n/// \\a n should equal \\a N unless \\a N is \\a Dynamic.\n///\n/// Example: \\include DenseBase_template_int_middleRows.cpp\n/// Output: \\verbinclude DenseBase_template_int_middleRows.out\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename NRowsBlockXpr<N>::Type middleRows(Index startRow, Index n = N)\n{\n  return typename NRowsBlockXpr<N>::Type(derived(), startRow, 0, n, cols());\n}\n\n/// This is the const version of middleRows<int>().\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename ConstNRowsBlockXpr<N>::Type middleRows(Index startRow, Index n = N) const\n{\n  return typename ConstNRowsBlockXpr<N>::Type(derived(), startRow, 0, n, cols());\n}\n\n\n\n/// \\returns a block consisting of the left columns of \\c *this.\n///\n/// \\param n the number of columns in the block\n/// \\tparam NColsType the type of the value handling the number of columns in the block, typically Index.\n///\n/// Example: \\include MatrixBase_leftCols_int.cpp\n/// Output: \\verbinclude MatrixBase_leftCols_int.out\n///\n/// The number of columns \\a n can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments.\n/// See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename NColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n#else\ntypename NColsBlockXpr<...>::Type\n#endif\nleftCols(NColsType n)\n{\n  return typename NColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), 0, 0, rows(), internal::get_runtime_value(n));\n}\n\n/// This is the const version of leftCols(NColsType).\ntemplate<typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstNColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n#else\nconst typename ConstNColsBlockXpr<...>::Type\n#endif\nleftCols(NColsType n) const\n{\n  return typename ConstNColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), 0, 0, rows(), internal::get_runtime_value(n));\n}\n\n/// \\returns a block consisting of the left columns of \\c *this.\n///\n/// \\tparam N the number of columns in the block as specified at compile-time\n/// \\param n the number of columns in the block as specified at run-time\n///\n/// The compile-time and run-time information should not contradict. In other words,\n/// \\a n should equal \\a N unless \\a N is \\a Dynamic.\n///\n/// Example: \\include MatrixBase_template_int_leftCols.cpp\n/// Output: \\verbinclude MatrixBase_template_int_leftCols.out\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename NColsBlockXpr<N>::Type leftCols(Index n = N)\n{\n  return typename NColsBlockXpr<N>::Type(derived(), 0, 0, rows(), n);\n}\n\n/// This is the const version of leftCols<int>().\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename ConstNColsBlockXpr<N>::Type leftCols(Index n = N) const\n{\n  return typename ConstNColsBlockXpr<N>::Type(derived(), 0, 0, rows(), n);\n}\n\n\n\n/// \\returns a block consisting of the right columns of \\c *this.\n///\n/// \\param n the number of columns in the block\n/// \\tparam NColsType the type of the value handling the number of columns in the block, typically Index.\n///\n/// Example: \\include MatrixBase_rightCols_int.cpp\n/// Output: \\verbinclude MatrixBase_rightCols_int.out\n///\n/// The number of columns \\a n can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments.\n/// See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename NColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n#else\ntypename NColsBlockXpr<...>::Type\n#endif\nrightCols(NColsType n)\n{\n  return typename NColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), 0, cols() - internal::get_runtime_value(n), rows(), internal::get_runtime_value(n));\n}\n\n/// This is the const version of rightCols(NColsType).\ntemplate<typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstNColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n#else\nconst typename ConstNColsBlockXpr<...>::Type\n#endif\nrightCols(NColsType n) const\n{\n  return typename ConstNColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), 0, cols() - internal::get_runtime_value(n), rows(), internal::get_runtime_value(n));\n}\n\n/// \\returns a block consisting of the right columns of \\c *this.\n///\n/// \\tparam N the number of columns in the block as specified at compile-time\n/// \\param n the number of columns in the block as specified at run-time\n///\n/// The compile-time and run-time information should not contradict. In other words,\n/// \\a n should equal \\a N unless \\a N is \\a Dynamic.\n///\n/// Example: \\include MatrixBase_template_int_rightCols.cpp\n/// Output: \\verbinclude MatrixBase_template_int_rightCols.out\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename NColsBlockXpr<N>::Type rightCols(Index n = N)\n{\n  return typename NColsBlockXpr<N>::Type(derived(), 0, cols() - n, rows(), n);\n}\n\n/// This is the const version of rightCols<int>().\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename ConstNColsBlockXpr<N>::Type rightCols(Index n = N) const\n{\n  return typename ConstNColsBlockXpr<N>::Type(derived(), 0, cols() - n, rows(), n);\n}\n\n\n\n/// \\returns a block consisting of a range of columns of \\c *this.\n///\n/// \\param startCol the index of the first column in the block\n/// \\param numCols the number of columns in the block\n/// \\tparam NColsType the type of the value handling the number of columns in the block, typically Index.\n///\n/// Example: \\include DenseBase_middleCols_int.cpp\n/// Output: \\verbinclude DenseBase_middleCols_int.out\n///\n/// The number of columns \\a n can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments.\n/// See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename NColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n#else\ntypename NColsBlockXpr<...>::Type\n#endif\nmiddleCols(Index startCol, NColsType numCols)\n{\n  return typename NColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), 0, startCol, rows(), internal::get_runtime_value(numCols));\n}\n\n/// This is the const version of middleCols(Index,NColsType).\ntemplate<typename NColsType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstNColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n#else\nconst typename ConstNColsBlockXpr<...>::Type\n#endif\nmiddleCols(Index startCol, NColsType numCols) const\n{\n  return typename ConstNColsBlockXpr<internal::get_fixed_value<NColsType>::value>::Type\n            (derived(), 0, startCol, rows(), internal::get_runtime_value(numCols));\n}\n\n/// \\returns a block consisting of a range of columns of \\c *this.\n///\n/// \\tparam N the number of columns in the block as specified at compile-time\n/// \\param startCol the index of the first column in the block\n/// \\param n the number of columns in the block as specified at run-time\n///\n/// The compile-time and run-time information should not contradict. In other words,\n/// \\a n should equal \\a N unless \\a N is \\a Dynamic.\n///\n/// Example: \\include DenseBase_template_int_middleCols.cpp\n/// Output: \\verbinclude DenseBase_template_int_middleCols.out\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major)\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename NColsBlockXpr<N>::Type middleCols(Index startCol, Index n = N)\n{\n  return typename NColsBlockXpr<N>::Type(derived(), 0, startCol, rows(), n);\n}\n\n/// This is the const version of middleCols<int>().\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename ConstNColsBlockXpr<N>::Type middleCols(Index startCol, Index n = N) const\n{\n  return typename ConstNColsBlockXpr<N>::Type(derived(), 0, startCol, rows(), n);\n}\n\n\n\n/// \\returns a fixed-size expression of a block of \\c *this.\n///\n/// The template parameters \\a NRows and \\a NCols are the number of\n/// rows and columns in the block.\n///\n/// \\param startRow the first row in the block\n/// \\param startCol the first column in the block\n///\n/// Example: \\include MatrixBase_block_int_int.cpp\n/// Output: \\verbinclude MatrixBase_block_int_int.out\n///\n/// \\note The usage of of this overload is discouraged from %Eigen 3.4, better used the generic\n/// block(Index,Index,NRowsType,NColsType), here is the one-to-one equivalence:\n/// \\code\n/// mat.template block<NRows,NCols>(i,j)  <-->  mat.block(i,j,fix<NRows>,fix<NCols>)\n/// \\endcode\n///\n/// \\note since block is a templated member, the keyword template has to be used\n/// if the matrix type is also a template parameter: \\code m.template block<3,3>(1,1); \\endcode\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int NRows, int NCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedBlockXpr<NRows,NCols>::Type block(Index startRow, Index startCol)\n{\n  return typename FixedBlockXpr<NRows,NCols>::Type(derived(), startRow, startCol);\n}\n\n/// This is the const version of block<>(Index, Index). */\ntemplate<int NRows, int NCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst typename ConstFixedBlockXpr<NRows,NCols>::Type block(Index startRow, Index startCol) const\n{\n  return typename ConstFixedBlockXpr<NRows,NCols>::Type(derived(), startRow, startCol);\n}\n\n/// \\returns an expression of a block of \\c *this.\n///\n/// \\tparam NRows number of rows in block as specified at compile-time\n/// \\tparam NCols number of columns in block as specified at compile-time\n/// \\param  startRow  the first row in the block\n/// \\param  startCol  the first column in the block\n/// \\param  blockRows number of rows in block as specified at run-time\n/// \\param  blockCols number of columns in block as specified at run-time\n///\n/// This function is mainly useful for blocks where the number of rows is specified at compile-time\n/// and the number of columns is specified at run-time, or vice versa. The compile-time and run-time\n/// information should not contradict. In other words, \\a blockRows should equal \\a NRows unless\n/// \\a NRows is \\a Dynamic, and the same for the number of columns.\n///\n/// Example: \\include MatrixBase_template_int_int_block_int_int_int_int.cpp\n/// Output: \\verbinclude MatrixBase_template_int_int_block_int_int_int_int.out\n///\n/// \\note The usage of of this overload is discouraged from %Eigen 3.4, better used the generic\n/// block(Index,Index,NRowsType,NColsType), here is the one-to-one complete equivalence:\n/// \\code\n/// mat.template block<NRows,NCols>(i,j,rows,cols)     <-->  mat.block(i,j,fix<NRows>(rows),fix<NCols>(cols))\n/// \\endcode\n/// If we known that, e.g., NRows==Dynamic and NCols!=Dynamic, then the equivalence becomes:\n/// \\code\n/// mat.template block<Dynamic,NCols>(i,j,rows,NCols)  <-->  mat.block(i,j,rows,fix<NCols>)\n/// \\endcode\n///\nEIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), class Block\n///\ntemplate<int NRows, int NCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedBlockXpr<NRows,NCols>::Type block(Index startRow, Index startCol,\n                                                  Index blockRows, Index blockCols)\n{\n  return typename FixedBlockXpr<NRows,NCols>::Type(derived(), startRow, startCol, blockRows, blockCols);\n}\n\n/// This is the const version of block<>(Index, Index, Index, Index).\ntemplate<int NRows, int NCols>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst typename ConstFixedBlockXpr<NRows,NCols>::Type block(Index startRow, Index startCol,\n                                                              Index blockRows, Index blockCols) const\n{\n  return typename ConstFixedBlockXpr<NRows,NCols>::Type(derived(), startRow, startCol, blockRows, blockCols);\n}\n\n/// \\returns an expression of the \\a i-th column of \\c *this. Note that the numbering starts at 0.\n///\n/// Example: \\include MatrixBase_col.cpp\n/// Output: \\verbinclude MatrixBase_col.out\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(column-major)\n/**\n  * \\sa row(), class Block */\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nColXpr col(Index i)\n{\n  return ColXpr(derived(), i);\n}\n\n/// This is the const version of col().\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nConstColXpr col(Index i) const\n{\n  return ConstColXpr(derived(), i);\n}\n\n/// \\returns an expression of the \\a i-th row of \\c *this. Note that the numbering starts at 0.\n///\n/// Example: \\include MatrixBase_row.cpp\n/// Output: \\verbinclude MatrixBase_row.out\n///\nEIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF(row-major)\n/**\n  * \\sa col(), class Block */\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nRowXpr row(Index i)\n{\n  return RowXpr(derived(), i);\n}\n\n/// This is the const version of row(). */\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nConstRowXpr row(Index i) const\n{\n  return ConstRowXpr(derived(), i);\n}\n\n/// \\returns an expression of a segment (i.e. a vector block) in \\c *this with either dynamic or fixed sizes.\n///\n/// \\only_for_vectors\n///\n/// \\param start the first coefficient in the segment\n/// \\param n the number of coefficients in the segment\n/// \\tparam NType the type of the value handling the number of coefficients in the segment, typically Index.\n///\n/// Example: \\include MatrixBase_segment_int_int.cpp\n/// Output: \\verbinclude MatrixBase_segment_int_int.out\n///\n/// The number of coefficients \\a n can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments.\n/// See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\n/// \\note Even in the case that the returned expression has dynamic size, in the case\n/// when it is applied to a fixed-size vector, it inherits a fixed maximal size,\n/// which means that evaluating it does not cause a dynamic memory allocation.\n///\n/// \\sa block(Index,Index,NRowsType,NColsType), fix<N>, fix<N>(int), class Block\n///\ntemplate<typename NType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename FixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n#else\ntypename FixedSegmentReturnType<...>::Type\n#endif\nsegment(Index start, NType n)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename FixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n            (derived(), start, internal::get_runtime_value(n));\n}\n\n\n/// This is the const version of segment(Index,NType).\ntemplate<typename NType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstFixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n#else\nconst typename ConstFixedSegmentReturnType<...>::Type\n#endif\nsegment(Index start, NType n) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename ConstFixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n            (derived(), start, internal::get_runtime_value(n));\n}\n\n/// \\returns an expression of the first coefficients of \\c *this with either dynamic or fixed sizes.\n///\n/// \\only_for_vectors\n///\n/// \\param n the number of coefficients in the segment\n/// \\tparam NType the type of the value handling the number of coefficients in the segment, typically Index.\n///\n/// Example: \\include MatrixBase_start_int.cpp\n/// Output: \\verbinclude MatrixBase_start_int.out\n///\n/// The number of coefficients \\a n can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments.\n/// See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\n/// \\note Even in the case that the returned expression has dynamic size, in the case\n/// when it is applied to a fixed-size vector, it inherits a fixed maximal size,\n/// which means that evaluating it does not cause a dynamic memory allocation.\n///\n/// \\sa class Block, block(Index,Index)\n///\ntemplate<typename NType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename FixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n#else\ntypename FixedSegmentReturnType<...>::Type\n#endif\nhead(NType n)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename FixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n              (derived(), 0, internal::get_runtime_value(n));\n}\n\n/// This is the const version of head(NType).\ntemplate<typename NType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstFixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n#else\nconst typename ConstFixedSegmentReturnType<...>::Type\n#endif\nhead(NType n) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename ConstFixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n            (derived(), 0, internal::get_runtime_value(n));\n}\n\n/// \\returns an expression of a last coefficients of \\c *this with either dynamic or fixed sizes.\n///\n/// \\only_for_vectors\n///\n/// \\param n the number of coefficients in the segment\n/// \\tparam NType the type of the value handling the number of coefficients in the segment, typically Index.\n///\n/// Example: \\include MatrixBase_end_int.cpp\n/// Output: \\verbinclude MatrixBase_end_int.out\n///\n/// The number of coefficients \\a n can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments.\n/// See \\link block(Index,Index,NRowsType,NColsType) block() \\endlink for the details.\n///\n/// \\note Even in the case that the returned expression has dynamic size, in the case\n/// when it is applied to a fixed-size vector, it inherits a fixed maximal size,\n/// which means that evaluating it does not cause a dynamic memory allocation.\n///\n/// \\sa class Block, block(Index,Index)\n///\ntemplate<typename NType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntypename FixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n#else\ntypename FixedSegmentReturnType<...>::Type\n#endif\ntail(NType n)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename FixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n            (derived(), this->size() - internal::get_runtime_value(n), internal::get_runtime_value(n));\n}\n\n/// This is the const version of tail(Index).\ntemplate<typename NType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nconst typename ConstFixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n#else\nconst typename ConstFixedSegmentReturnType<...>::Type\n#endif\ntail(NType n) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename ConstFixedSegmentReturnType<internal::get_fixed_value<NType>::value>::Type\n            (derived(), this->size() - internal::get_runtime_value(n), internal::get_runtime_value(n));\n}\n\n/// \\returns a fixed-size expression of a segment (i.e. a vector block) in \\c *this\n///\n/// \\only_for_vectors\n///\n/// \\tparam N the number of coefficients in the segment as specified at compile-time\n/// \\param start the index of the first element in the segment\n/// \\param n the number of coefficients in the segment as specified at compile-time\n///\n/// The compile-time and run-time information should not contradict. In other words,\n/// \\a n should equal \\a N unless \\a N is \\a Dynamic.\n///\n/// Example: \\include MatrixBase_template_int_segment.cpp\n/// Output: \\verbinclude MatrixBase_template_int_segment.out\n///\n/// \\sa segment(Index,NType), class Block\n///\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedSegmentReturnType<N>::Type segment(Index start, Index n = N)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename FixedSegmentReturnType<N>::Type(derived(), start, n);\n}\n\n/// This is the const version of segment<int>(Index).\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename ConstFixedSegmentReturnType<N>::Type segment(Index start, Index n = N) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename ConstFixedSegmentReturnType<N>::Type(derived(), start, n);\n}\n\n/// \\returns a fixed-size expression of the first coefficients of \\c *this.\n///\n/// \\only_for_vectors\n///\n/// \\tparam N the number of coefficients in the segment as specified at compile-time\n/// \\param  n the number of coefficients in the segment as specified at run-time\n///\n/// The compile-time and run-time information should not contradict. In other words,\n/// \\a n should equal \\a N unless \\a N is \\a Dynamic.\n///\n/// Example: \\include MatrixBase_template_int_start.cpp\n/// Output: \\verbinclude MatrixBase_template_int_start.out\n///\n/// \\sa head(NType), class Block\n///\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedSegmentReturnType<N>::Type head(Index n = N)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename FixedSegmentReturnType<N>::Type(derived(), 0, n);\n}\n\n/// This is the const version of head<int>().\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename ConstFixedSegmentReturnType<N>::Type head(Index n = N) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename ConstFixedSegmentReturnType<N>::Type(derived(), 0, n);\n}\n\n/// \\returns a fixed-size expression of the last coefficients of \\c *this.\n///\n/// \\only_for_vectors\n///\n/// \\tparam N the number of coefficients in the segment as specified at compile-time\n/// \\param  n the number of coefficients in the segment as specified at run-time\n///\n/// The compile-time and run-time information should not contradict. In other words,\n/// \\a n should equal \\a N unless \\a N is \\a Dynamic.\n///\n/// Example: \\include MatrixBase_template_int_end.cpp\n/// Output: \\verbinclude MatrixBase_template_int_end.out\n///\n/// \\sa tail(NType), class Block\n///\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename FixedSegmentReturnType<N>::Type tail(Index n = N)\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename FixedSegmentReturnType<N>::Type(derived(), size() - n);\n}\n\n/// This is the const version of tail<int>.\ntemplate<int N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename ConstFixedSegmentReturnType<N>::Type tail(Index n = N) const\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return typename ConstFixedSegmentReturnType<N>::Type(derived(), size() - n);\n}\n\n/// \\returns the \\a outer -th column (resp. row) of the matrix \\c *this if \\c *this\n/// is col-major (resp. row-major).\n///\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nInnerVectorReturnType innerVector(Index outer)\n{ return InnerVectorReturnType(derived(), outer); }\n\n/// \\returns the \\a outer -th column (resp. row) of the matrix \\c *this if \\c *this\n/// is col-major (resp. row-major). Read-only.\n///\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst ConstInnerVectorReturnType innerVector(Index outer) const\n{ return ConstInnerVectorReturnType(derived(), outer); }\n\n/// \\returns the \\a outer -th column (resp. row) of the matrix \\c *this if \\c *this\n/// is col-major (resp. row-major).\n///\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nInnerVectorsReturnType\ninnerVectors(Index outerStart, Index outerSize)\n{\n  return Block<Derived,Dynamic,Dynamic,true>(derived(),\n                                             IsRowMajor ? outerStart : 0, IsRowMajor ? 0 : outerStart,\n                                             IsRowMajor ? outerSize : rows(), IsRowMajor ? cols() : outerSize);\n\n}\n\n/// \\returns the \\a outer -th column (resp. row) of the matrix \\c *this if \\c *this\n/// is col-major (resp. row-major). Read-only.\n///\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nconst ConstInnerVectorsReturnType\ninnerVectors(Index outerStart, Index outerSize) const\n{\n  return Block<const Derived,Dynamic,Dynamic,true>(derived(),\n                                                  IsRowMajor ? outerStart : 0, IsRowMajor ? 0 : outerStart,\n                                                  IsRowMajor ? outerSize : rows(), IsRowMajor ? cols() : outerSize);\n\n}\n\n/** \\returns the i-th subvector (column or vector) according to the \\c Direction\n  * \\sa subVectors()\n  */\ntemplate<DirectionType Direction>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename internal::conditional<Direction==Vertical,ColXpr,RowXpr>::type\nsubVector(Index i)\n{\n  return typename internal::conditional<Direction==Vertical,ColXpr,RowXpr>::type(derived(),i);\n}\n\n/** This is the const version of subVector(Index) */\ntemplate<DirectionType Direction>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ntypename internal::conditional<Direction==Vertical,ConstColXpr,ConstRowXpr>::type\nsubVector(Index i) const\n{\n  return typename internal::conditional<Direction==Vertical,ConstColXpr,ConstRowXpr>::type(derived(),i);\n}\n\n/** \\returns the number of subvectors (rows or columns) in the direction \\c Direction\n  * \\sa subVector(Index)\n  */\ntemplate<DirectionType Direction>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nIndex subVectors() const\n{ return (Direction==Vertical)?cols():rows(); }\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/plugins/CommonCwiseBinaryOps.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// This file is a base class plugin containing common coefficient wise functions.\n\n/** \\returns an expression of the difference of \\c *this and \\a other\n  *\n  * \\note If you want to substract a given scalar from all coefficients, see Cwise::operator-().\n  *\n  * \\sa class CwiseBinaryOp, operator-=()\n  */\nEIGEN_MAKE_CWISE_BINARY_OP(operator-,difference)\n\n/** \\returns an expression of the sum of \\c *this and \\a other\n  *\n  * \\note If you want to add a given scalar to all coefficients, see Cwise::operator+().\n  *\n  * \\sa class CwiseBinaryOp, operator+=()\n  */\nEIGEN_MAKE_CWISE_BINARY_OP(operator+,sum)\n\n/** \\returns an expression of a custom coefficient-wise operator \\a func of *this and \\a other\n  *\n  * The template parameter \\a CustomBinaryOp is the type of the functor\n  * of the custom operator (see class CwiseBinaryOp for an example)\n  *\n  * Here is an example illustrating the use of custom functors:\n  * \\include class_CwiseBinaryOp.cpp\n  * Output: \\verbinclude class_CwiseBinaryOp.out\n  *\n  * \\sa class CwiseBinaryOp, operator+(), operator-(), cwiseProduct()\n  */\ntemplate<typename CustomBinaryOp, typename OtherDerived>\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseBinaryOp<CustomBinaryOp, const Derived, const OtherDerived>\nbinaryExpr(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other, const CustomBinaryOp& func = CustomBinaryOp()) const\n{\n  return CwiseBinaryOp<CustomBinaryOp, const Derived, const OtherDerived>(derived(), other.derived(), func);\n}\n\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nEIGEN_MAKE_SCALAR_BINARY_OP(operator*,product)\n#else\n/** \\returns an expression of \\c *this scaled by the scalar factor \\a scalar\n  *\n  * \\tparam T is the scalar type of \\a scalar. It must be compatible with the scalar type of the given expression.\n  */\ntemplate<typename T>\nconst CwiseBinaryOp<internal::scalar_product_op<Scalar,T>,Derived,Constant<T> > operator*(const T& scalar) const;\n/** \\returns an expression of \\a expr scaled by the scalar factor \\a scalar\n  *\n  * \\tparam T is the scalar type of \\a scalar. It must be compatible with the scalar type of the given expression.\n  */\ntemplate<typename T> friend\nconst CwiseBinaryOp<internal::scalar_product_op<T,Scalar>,Constant<T>,Derived> operator*(const T& scalar, const StorageBaseType& expr);\n#endif\n\n\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\nEIGEN_MAKE_SCALAR_BINARY_OP_ONTHERIGHT(operator/,quotient)\n#else\n/** \\returns an expression of \\c *this divided by the scalar value \\a scalar\n  *\n  * \\tparam T is the scalar type of \\a scalar. It must be compatible with the scalar type of the given expression.\n  */\ntemplate<typename T>\nconst CwiseBinaryOp<internal::scalar_quotient_op<Scalar,T>,Derived,Constant<T> > operator/(const T& scalar) const;\n#endif\n\n/** \\returns an expression of the coefficient-wise boolean \\b and operator of \\c *this and \\a other\n  *\n  * \\warning this operator is for expression of bool only.\n  *\n  * Example: \\include Cwise_boolean_and.cpp\n  * Output: \\verbinclude Cwise_boolean_and.out\n  *\n  * \\sa operator||(), select()\n  */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\ninline const CwiseBinaryOp<internal::scalar_boolean_and_op, const Derived, const OtherDerived>\noperator&&(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  EIGEN_STATIC_ASSERT((internal::is_same<bool,Scalar>::value && internal::is_same<bool,typename OtherDerived::Scalar>::value),\n                      THIS_METHOD_IS_ONLY_FOR_EXPRESSIONS_OF_BOOL);\n  return CwiseBinaryOp<internal::scalar_boolean_and_op, const Derived, const OtherDerived>(derived(),other.derived());\n}\n\n/** \\returns an expression of the coefficient-wise boolean \\b or operator of \\c *this and \\a other\n  *\n  * \\warning this operator is for expression of bool only.\n  *\n  * Example: \\include Cwise_boolean_or.cpp\n  * Output: \\verbinclude Cwise_boolean_or.out\n  *\n  * \\sa operator&&(), select()\n  */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\ninline const CwiseBinaryOp<internal::scalar_boolean_or_op, const Derived, const OtherDerived>\noperator||(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  EIGEN_STATIC_ASSERT((internal::is_same<bool,Scalar>::value && internal::is_same<bool,typename OtherDerived::Scalar>::value),\n                      THIS_METHOD_IS_ONLY_FOR_EXPRESSIONS_OF_BOOL);\n  return CwiseBinaryOp<internal::scalar_boolean_or_op, const Derived, const OtherDerived>(derived(),other.derived());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/plugins/CommonCwiseUnaryOps.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// This file is a base class plugin containing common coefficient wise functions.\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n\n/** \\internal the return type of conjugate() */\ntypedef typename internal::conditional<NumTraits<Scalar>::IsComplex,\n                    const CwiseUnaryOp<internal::scalar_conjugate_op<Scalar>, const Derived>,\n                    const Derived&\n                  >::type ConjugateReturnType;\n/** \\internal the return type of real() const */\ntypedef typename internal::conditional<NumTraits<Scalar>::IsComplex,\n                    const CwiseUnaryOp<internal::scalar_real_op<Scalar>, const Derived>,\n                    const Derived&\n                  >::type RealReturnType;\n/** \\internal the return type of real() */\ntypedef typename internal::conditional<NumTraits<Scalar>::IsComplex,\n                    CwiseUnaryView<internal::scalar_real_ref_op<Scalar>, Derived>,\n                    Derived&\n                  >::type NonConstRealReturnType;\n/** \\internal the return type of imag() const */\ntypedef CwiseUnaryOp<internal::scalar_imag_op<Scalar>, const Derived> ImagReturnType;\n/** \\internal the return type of imag() */\ntypedef CwiseUnaryView<internal::scalar_imag_ref_op<Scalar>, Derived> NonConstImagReturnType;\n\ntypedef CwiseUnaryOp<internal::scalar_opposite_op<Scalar>, const Derived> NegativeReturnType;\n\n#endif // not EIGEN_PARSED_BY_DOXYGEN\n\n/// \\returns an expression of the opposite of \\c *this\n///\nEIGEN_DOC_UNARY_ADDONS(operator-,opposite)\n///\nEIGEN_DEVICE_FUNC\ninline const NegativeReturnType\noperator-() const { return NegativeReturnType(derived()); }\n\n\ntemplate<class NewType> struct CastXpr { typedef typename internal::cast_return_type<Derived,const CwiseUnaryOp<internal::scalar_cast_op<Scalar, NewType>, const Derived> >::type Type; };\n\n/// \\returns an expression of \\c *this with the \\a Scalar type casted to\n/// \\a NewScalar.\n///\n/// The template parameter \\a NewScalar is the type we are casting the scalars to.\n///\nEIGEN_DOC_UNARY_ADDONS(cast,conversion function)\n///\n/// \\sa class CwiseUnaryOp\n///\ntemplate<typename NewType>\nEIGEN_DEVICE_FUNC\ntypename CastXpr<NewType>::Type\ncast() const\n{\n  return typename CastXpr<NewType>::Type(derived());\n}\n\ntemplate<int N> struct ShiftRightXpr {\n  typedef CwiseUnaryOp<internal::scalar_shift_right_op<Scalar, N>, const Derived> Type;\n};\n\n/// \\returns an expression of \\c *this with the \\a Scalar type arithmetically\n/// shifted right by \\a N bit positions.\n///\n/// The template parameter \\a N specifies the number of bit positions to shift.\n///\nEIGEN_DOC_UNARY_ADDONS(cast,conversion function)\n///\n/// \\sa class CwiseUnaryOp\n///\ntemplate<int N>\nEIGEN_DEVICE_FUNC\ntypename ShiftRightXpr<N>::Type\nshift_right() const\n{\n  return typename ShiftRightXpr<N>::Type(derived());\n}\n\n\ntemplate<int N> struct ShiftLeftXpr {\n  typedef CwiseUnaryOp<internal::scalar_shift_left_op<Scalar, N>, const Derived> Type;\n};\n\n/// \\returns an expression of \\c *this with the \\a Scalar type logically\n/// shifted left by \\a N bit positions.\n///\n/// The template parameter \\a N specifies the number of bit positions to shift.\n///\nEIGEN_DOC_UNARY_ADDONS(cast,conversion function)\n///\n/// \\sa class CwiseUnaryOp\n///\ntemplate<int N>\nEIGEN_DEVICE_FUNC\ntypename ShiftLeftXpr<N>::Type\nshift_left() const\n{\n  return typename ShiftLeftXpr<N>::Type(derived());\n}\n\n/// \\returns an expression of the complex conjugate of \\c *this.\n///\nEIGEN_DOC_UNARY_ADDONS(conjugate,complex conjugate)\n///\n/// \\sa <a href=\"group__CoeffwiseMathFunctions.html#cwisetable_conj\">Math functions</a>, MatrixBase::adjoint()\nEIGEN_DEVICE_FUNC\ninline ConjugateReturnType\nconjugate() const\n{\n  return ConjugateReturnType(derived());\n}\n\n/// \\returns an expression of the complex conjugate of \\c *this if Cond==true, returns derived() otherwise.\n///\nEIGEN_DOC_UNARY_ADDONS(conjugate,complex conjugate)\n///\n/// \\sa conjugate()\ntemplate<bool Cond>\nEIGEN_DEVICE_FUNC\ninline typename internal::conditional<Cond,ConjugateReturnType,const Derived&>::type\nconjugateIf() const\n{\n  typedef typename internal::conditional<Cond,ConjugateReturnType,const Derived&>::type ReturnType;\n  return ReturnType(derived());\n}\n\n/// \\returns a read-only expression of the real part of \\c *this.\n///\nEIGEN_DOC_UNARY_ADDONS(real,real part function)\n///\n/// \\sa imag()\nEIGEN_DEVICE_FUNC\ninline RealReturnType\nreal() const { return RealReturnType(derived()); }\n\n/// \\returns an read-only expression of the imaginary part of \\c *this.\n///\nEIGEN_DOC_UNARY_ADDONS(imag,imaginary part function)\n///\n/// \\sa real()\nEIGEN_DEVICE_FUNC\ninline const ImagReturnType\nimag() const { return ImagReturnType(derived()); }\n\n/// \\brief Apply a unary operator coefficient-wise\n/// \\param[in]  func  Functor implementing the unary operator\n/// \\tparam  CustomUnaryOp Type of \\a func\n/// \\returns An expression of a custom coefficient-wise unary operator \\a func of *this\n///\n/// The function \\c ptr_fun() from the C++ standard library can be used to make functors out of normal functions.\n///\n/// Example:\n/// \\include class_CwiseUnaryOp_ptrfun.cpp\n/// Output: \\verbinclude class_CwiseUnaryOp_ptrfun.out\n///\n/// Genuine functors allow for more possibilities, for instance it may contain a state.\n///\n/// Example:\n/// \\include class_CwiseUnaryOp.cpp\n/// Output: \\verbinclude class_CwiseUnaryOp.out\n///\nEIGEN_DOC_UNARY_ADDONS(unaryExpr,unary function)\n///\n/// \\sa unaryViewExpr, binaryExpr, class CwiseUnaryOp\n///\ntemplate<typename CustomUnaryOp>\nEIGEN_DEVICE_FUNC\ninline const CwiseUnaryOp<CustomUnaryOp, const Derived>\nunaryExpr(const CustomUnaryOp& func = CustomUnaryOp()) const\n{\n  return CwiseUnaryOp<CustomUnaryOp, const Derived>(derived(), func);\n}\n\n/// \\returns an expression of a custom coefficient-wise unary operator \\a func of *this\n///\n/// The template parameter \\a CustomUnaryOp is the type of the functor\n/// of the custom unary operator.\n///\n/// Example:\n/// \\include class_CwiseUnaryOp.cpp\n/// Output: \\verbinclude class_CwiseUnaryOp.out\n///\nEIGEN_DOC_UNARY_ADDONS(unaryViewExpr,unary function)\n///\n/// \\sa unaryExpr, binaryExpr class CwiseUnaryOp\n///\ntemplate<typename CustomViewOp>\nEIGEN_DEVICE_FUNC\ninline const CwiseUnaryView<CustomViewOp, const Derived>\nunaryViewExpr(const CustomViewOp& func = CustomViewOp()) const\n{\n  return CwiseUnaryView<CustomViewOp, const Derived>(derived(), func);\n}\n\n/// \\returns a non const expression of the real part of \\c *this.\n///\nEIGEN_DOC_UNARY_ADDONS(real,real part function)\n///\n/// \\sa imag()\nEIGEN_DEVICE_FUNC\ninline NonConstRealReturnType\nreal() { return NonConstRealReturnType(derived()); }\n\n/// \\returns a non const expression of the imaginary part of \\c *this.\n///\nEIGEN_DOC_UNARY_ADDONS(imag,imaginary part function)\n///\n/// \\sa real()\nEIGEN_DEVICE_FUNC\ninline NonConstImagReturnType\nimag() { return NonConstImagReturnType(derived()); }\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/plugins/IndexedViewMethods.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2017 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#if !defined(EIGEN_PARSED_BY_DOXYGEN)\n\n// This file is automatically included twice to generate const and non-const versions\n\n#ifndef EIGEN_INDEXED_VIEW_METHOD_2ND_PASS\n#define EIGEN_INDEXED_VIEW_METHOD_CONST const\n#define EIGEN_INDEXED_VIEW_METHOD_TYPE  ConstIndexedViewType\n#else\n#define EIGEN_INDEXED_VIEW_METHOD_CONST\n#define EIGEN_INDEXED_VIEW_METHOD_TYPE IndexedViewType\n#endif\n\n#ifndef EIGEN_INDEXED_VIEW_METHOD_2ND_PASS\nprotected:\n\n// define some aliases to ease readability\n\ntemplate<typename Indices>\nstruct IvcRowType : public internal::IndexedViewCompatibleType<Indices,RowsAtCompileTime> {};\n\ntemplate<typename Indices>\nstruct IvcColType : public internal::IndexedViewCompatibleType<Indices,ColsAtCompileTime> {};\n\ntemplate<typename Indices>\nstruct IvcType : public internal::IndexedViewCompatibleType<Indices,SizeAtCompileTime> {};\n\ntypedef typename internal::IndexedViewCompatibleType<Index,1>::type IvcIndex;\n\ntemplate<typename Indices>\ntypename IvcRowType<Indices>::type\nivcRow(const Indices& indices) const {\n  return internal::makeIndexedViewCompatible(indices, internal::variable_if_dynamic<Index,RowsAtCompileTime>(derived().rows()),Specialized);\n}\n\ntemplate<typename Indices>\ntypename IvcColType<Indices>::type\nivcCol(const Indices& indices) const {\n  return internal::makeIndexedViewCompatible(indices, internal::variable_if_dynamic<Index,ColsAtCompileTime>(derived().cols()),Specialized);\n}\n\ntemplate<typename Indices>\ntypename IvcColType<Indices>::type\nivcSize(const Indices& indices) const {\n  return internal::makeIndexedViewCompatible(indices, internal::variable_if_dynamic<Index,SizeAtCompileTime>(derived().size()),Specialized);\n}\n\npublic:\n\n#endif\n\ntemplate<typename RowIndices, typename ColIndices>\nstruct EIGEN_INDEXED_VIEW_METHOD_TYPE {\n  typedef IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,\n                      typename IvcRowType<RowIndices>::type,\n                      typename IvcColType<ColIndices>::type> type;\n};\n\n// This is the generic version\n\ntemplate<typename RowIndices, typename ColIndices>\ntypename internal::enable_if<internal::valid_indexed_view_overload<RowIndices,ColIndices>::value\n  && internal::traits<typename EIGEN_INDEXED_VIEW_METHOD_TYPE<RowIndices,ColIndices>::type>::ReturnAsIndexedView,\n  typename EIGEN_INDEXED_VIEW_METHOD_TYPE<RowIndices,ColIndices>::type >::type\noperator()(const RowIndices& rowIndices, const ColIndices& colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  return typename EIGEN_INDEXED_VIEW_METHOD_TYPE<RowIndices,ColIndices>::type\n            (derived(), ivcRow(rowIndices), ivcCol(colIndices));\n}\n\n// The following overload returns a Block<> object\n\ntemplate<typename RowIndices, typename ColIndices>\ntypename internal::enable_if<internal::valid_indexed_view_overload<RowIndices,ColIndices>::value\n  && internal::traits<typename EIGEN_INDEXED_VIEW_METHOD_TYPE<RowIndices,ColIndices>::type>::ReturnAsBlock,\n  typename internal::traits<typename EIGEN_INDEXED_VIEW_METHOD_TYPE<RowIndices,ColIndices>::type>::BlockType>::type\noperator()(const RowIndices& rowIndices, const ColIndices& colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  typedef typename internal::traits<typename EIGEN_INDEXED_VIEW_METHOD_TYPE<RowIndices,ColIndices>::type>::BlockType BlockType;\n  typename IvcRowType<RowIndices>::type actualRowIndices = ivcRow(rowIndices);\n  typename IvcColType<ColIndices>::type actualColIndices = ivcCol(colIndices);\n  return BlockType(derived(),\n                   internal::first(actualRowIndices),\n                   internal::first(actualColIndices),\n                   internal::size(actualRowIndices),\n                   internal::size(actualColIndices));\n}\n\n// The following overload returns a Scalar\n\ntemplate<typename RowIndices, typename ColIndices>\ntypename internal::enable_if<internal::valid_indexed_view_overload<RowIndices,ColIndices>::value\n  && internal::traits<typename EIGEN_INDEXED_VIEW_METHOD_TYPE<RowIndices,ColIndices>::type>::ReturnAsScalar,\n  CoeffReturnType >::type\noperator()(const RowIndices& rowIndices, const ColIndices& colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  return Base::operator()(internal::eval_expr_given_size(rowIndices,rows()),internal::eval_expr_given_size(colIndices,cols()));\n}\n\n#if EIGEN_HAS_STATIC_ARRAY_TEMPLATE\n\n// The following three overloads are needed to handle raw Index[N] arrays.\n\ntemplate<typename RowIndicesT, std::size_t RowIndicesN, typename ColIndices>\nIndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,const RowIndicesT (&)[RowIndicesN],typename IvcColType<ColIndices>::type>\noperator()(const RowIndicesT (&rowIndices)[RowIndicesN], const ColIndices& colIndices) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  return IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,const RowIndicesT (&)[RowIndicesN],typename IvcColType<ColIndices>::type>\n                    (derived(), rowIndices, ivcCol(colIndices));\n}\n\ntemplate<typename RowIndices, typename ColIndicesT, std::size_t ColIndicesN>\nIndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,typename IvcRowType<RowIndices>::type, const ColIndicesT (&)[ColIndicesN]>\noperator()(const RowIndices& rowIndices, const ColIndicesT (&colIndices)[ColIndicesN]) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  return IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,typename IvcRowType<RowIndices>::type,const ColIndicesT (&)[ColIndicesN]>\n                    (derived(), ivcRow(rowIndices), colIndices);\n}\n\ntemplate<typename RowIndicesT, std::size_t RowIndicesN, typename ColIndicesT, std::size_t ColIndicesN>\nIndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,const RowIndicesT (&)[RowIndicesN], const ColIndicesT (&)[ColIndicesN]>\noperator()(const RowIndicesT (&rowIndices)[RowIndicesN], const ColIndicesT (&colIndices)[ColIndicesN]) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  return IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,const RowIndicesT (&)[RowIndicesN],const ColIndicesT (&)[ColIndicesN]>\n                    (derived(), rowIndices, colIndices);\n}\n\n#endif // EIGEN_HAS_STATIC_ARRAY_TEMPLATE\n\n// Overloads for 1D vectors/arrays\n\ntemplate<typename Indices>\ntypename internal::enable_if<\n  IsRowMajor && (!(internal::get_compile_time_incr<typename IvcType<Indices>::type>::value==1 || internal::is_valid_index_type<Indices>::value)),\n  IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,IvcIndex,typename IvcType<Indices>::type> >::type\noperator()(const Indices& indices) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,IvcIndex,typename IvcType<Indices>::type>\n            (derived(), IvcIndex(0), ivcCol(indices));\n}\n\ntemplate<typename Indices>\ntypename internal::enable_if<\n  (!IsRowMajor) && (!(internal::get_compile_time_incr<typename IvcType<Indices>::type>::value==1 || internal::is_valid_index_type<Indices>::value)),\n  IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,typename IvcType<Indices>::type,IvcIndex> >::type\noperator()(const Indices& indices) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,typename IvcType<Indices>::type,IvcIndex>\n            (derived(), ivcRow(indices), IvcIndex(0));\n}\n\ntemplate<typename Indices>\ntypename internal::enable_if<\n  (internal::get_compile_time_incr<typename IvcType<Indices>::type>::value==1) && (!internal::is_valid_index_type<Indices>::value) && (!symbolic::is_symbolic<Indices>::value),\n  VectorBlock<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,internal::array_size<Indices>::value> >::type\noperator()(const Indices& indices) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  typename IvcType<Indices>::type actualIndices = ivcSize(indices);\n  return VectorBlock<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,internal::array_size<Indices>::value>\n            (derived(), internal::first(actualIndices), internal::size(actualIndices));\n}\n\ntemplate<typename IndexType>\ntypename internal::enable_if<symbolic::is_symbolic<IndexType>::value, CoeffReturnType >::type\noperator()(const IndexType& id) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  return Base::operator()(internal::eval_expr_given_size(id,size()));\n}\n\n#if EIGEN_HAS_STATIC_ARRAY_TEMPLATE\n\ntemplate<typename IndicesT, std::size_t IndicesN>\ntypename internal::enable_if<IsRowMajor,\n  IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,IvcIndex,const IndicesT (&)[IndicesN]> >::type\noperator()(const IndicesT (&indices)[IndicesN]) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,IvcIndex,const IndicesT (&)[IndicesN]>\n            (derived(), IvcIndex(0), indices);\n}\n\ntemplate<typename IndicesT, std::size_t IndicesN>\ntypename internal::enable_if<!IsRowMajor,\n  IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,const IndicesT (&)[IndicesN],IvcIndex> >::type\noperator()(const IndicesT (&indices)[IndicesN]) EIGEN_INDEXED_VIEW_METHOD_CONST\n{\n  EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived)\n  return IndexedView<EIGEN_INDEXED_VIEW_METHOD_CONST Derived,const IndicesT (&)[IndicesN],IvcIndex>\n            (derived(), indices, IvcIndex(0));\n}\n\n#endif // EIGEN_HAS_STATIC_ARRAY_TEMPLATE\n\n#undef EIGEN_INDEXED_VIEW_METHOD_CONST\n#undef EIGEN_INDEXED_VIEW_METHOD_TYPE\n\n#ifndef EIGEN_INDEXED_VIEW_METHOD_2ND_PASS\n#define EIGEN_INDEXED_VIEW_METHOD_2ND_PASS\n#include \"IndexedViewMethods.h\"\n#undef EIGEN_INDEXED_VIEW_METHOD_2ND_PASS\n#endif\n\n#else // EIGEN_PARSED_BY_DOXYGEN\n\n/**\n  * \\returns a generic submatrix view defined by the rows and columns indexed \\a rowIndices and \\a colIndices respectively.\n  *\n  * Each parameter must either be:\n  *  - An integer indexing a single row or column\n  *  - Eigen::all indexing the full set of respective rows or columns in increasing order\n  *  - An ArithmeticSequence as returned by the Eigen::seq and Eigen::seqN functions\n  *  - Any %Eigen's vector/array of integers or expressions\n  *  - Plain C arrays: \\c int[N]\n  *  - And more generally any type exposing the following two member functions:\n  * \\code\n  * <integral type> operator[](<integral type>) const;\n  * <integral type> size() const;\n  * \\endcode\n  * where \\c <integral \\c type>  stands for any integer type compatible with Eigen::Index (i.e. \\c std::ptrdiff_t).\n  *\n  * The last statement implies compatibility with \\c std::vector, \\c std::valarray, \\c std::array, many of the Range-v3's ranges, etc.\n  *\n  * If the submatrix can be represented using a starting position \\c (i,j) and positive sizes \\c (rows,columns), then this\n  * method will returns a Block object after extraction of the relevant information from the passed arguments. This is the case\n  * when all arguments are either:\n  *  - An integer\n  *  - Eigen::all\n  *  - An ArithmeticSequence with compile-time increment strictly equal to 1, as returned by Eigen::seq(a,b), and Eigen::seqN(a,N).\n  *\n  * Otherwise a more general IndexedView<Derived,RowIndices',ColIndices'> object will be returned, after conversion of the inputs\n  * to more suitable types \\c RowIndices' and \\c ColIndices'.\n  *\n  * For 1D vectors and arrays, you better use the operator()(const Indices&) overload, which behave the same way but taking a single parameter.\n  *\n  * See also this <a href=\"https://stackoverflow.com/questions/46110917/eigen-replicate-items-along-one-dimension-without-useless-allocations\">question</a> and its answer for an example of how to duplicate coefficients.\n  *\n  * \\sa operator()(const Indices&), class Block, class IndexedView, DenseBase::block(Index,Index,Index,Index)\n  */\ntemplate<typename RowIndices, typename ColIndices>\nIndexedView_or_Block\noperator()(const RowIndices& rowIndices, const ColIndices& colIndices);\n\n/** This is an overload of operator()(const RowIndices&, const ColIndices&) for 1D vectors or arrays\n  *\n  * \\only_for_vectors\n  */\ntemplate<typename Indices>\nIndexedView_or_VectorBlock\noperator()(const Indices& indices);\n\n#endif  // EIGEN_PARSED_BY_DOXYGEN\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/plugins/MatrixCwiseBinaryOps.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// This file is a base class plugin containing matrix specifics coefficient wise functions.\n\n/** \\returns an expression of the Schur product (coefficient wise product) of *this and \\a other\n  *\n  * Example: \\include MatrixBase_cwiseProduct.cpp\n  * Output: \\verbinclude MatrixBase_cwiseProduct.out\n  *\n  * \\sa class CwiseBinaryOp, cwiseAbs2\n  */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const EIGEN_CWISE_BINARY_RETURN_TYPE(Derived,OtherDerived,product)\ncwiseProduct(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  return EIGEN_CWISE_BINARY_RETURN_TYPE(Derived,OtherDerived,product)(derived(), other.derived());\n}\n\n/** \\returns an expression of the coefficient-wise == operator of *this and \\a other\n  *\n  * \\warning this performs an exact comparison, which is generally a bad idea with floating-point types.\n  * In order to check for equality between two vectors or matrices with floating-point coefficients, it is\n  * generally a far better idea to use a fuzzy comparison as provided by isApprox() and\n  * isMuchSmallerThan().\n  *\n  * Example: \\include MatrixBase_cwiseEqual.cpp\n  * Output: \\verbinclude MatrixBase_cwiseEqual.out\n  *\n  * \\sa cwiseNotEqual(), isApprox(), isMuchSmallerThan()\n  */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\ninline const CwiseBinaryOp<std::equal_to<Scalar>, const Derived, const OtherDerived>\ncwiseEqual(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  return CwiseBinaryOp<std::equal_to<Scalar>, const Derived, const OtherDerived>(derived(), other.derived());\n}\n\n/** \\returns an expression of the coefficient-wise != operator of *this and \\a other\n  *\n  * \\warning this performs an exact comparison, which is generally a bad idea with floating-point types.\n  * In order to check for equality between two vectors or matrices with floating-point coefficients, it is\n  * generally a far better idea to use a fuzzy comparison as provided by isApprox() and\n  * isMuchSmallerThan().\n  *\n  * Example: \\include MatrixBase_cwiseNotEqual.cpp\n  * Output: \\verbinclude MatrixBase_cwiseNotEqual.out\n  *\n  * \\sa cwiseEqual(), isApprox(), isMuchSmallerThan()\n  */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\ninline const CwiseBinaryOp<std::not_equal_to<Scalar>, const Derived, const OtherDerived>\ncwiseNotEqual(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  return CwiseBinaryOp<std::not_equal_to<Scalar>, const Derived, const OtherDerived>(derived(), other.derived());\n}\n\n/** \\returns an expression of the coefficient-wise min of *this and \\a other\n  *\n  * Example: \\include MatrixBase_cwiseMin.cpp\n  * Output: \\verbinclude MatrixBase_cwiseMin.out\n  *\n  * \\sa class CwiseBinaryOp, max()\n  */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_min_op<Scalar,Scalar>, const Derived, const OtherDerived>\ncwiseMin(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  return CwiseBinaryOp<internal::scalar_min_op<Scalar,Scalar>, const Derived, const OtherDerived>(derived(), other.derived());\n}\n\n/** \\returns an expression of the coefficient-wise min of *this and scalar \\a other\n  *\n  * \\sa class CwiseBinaryOp, min()\n  */\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_min_op<Scalar,Scalar>, const Derived, const ConstantReturnType>\ncwiseMin(const Scalar &other) const\n{\n  return cwiseMin(Derived::Constant(rows(), cols(), other));\n}\n\n/** \\returns an expression of the coefficient-wise max of *this and \\a other\n  *\n  * Example: \\include MatrixBase_cwiseMax.cpp\n  * Output: \\verbinclude MatrixBase_cwiseMax.out\n  *\n  * \\sa class CwiseBinaryOp, min()\n  */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_max_op<Scalar,Scalar>, const Derived, const OtherDerived>\ncwiseMax(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  return CwiseBinaryOp<internal::scalar_max_op<Scalar,Scalar>, const Derived, const OtherDerived>(derived(), other.derived());\n}\n\n/** \\returns an expression of the coefficient-wise max of *this and scalar \\a other\n  *\n  * \\sa class CwiseBinaryOp, min()\n  */\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_max_op<Scalar,Scalar>, const Derived, const ConstantReturnType>\ncwiseMax(const Scalar &other) const\n{\n  return cwiseMax(Derived::Constant(rows(), cols(), other));\n}\n\n\n/** \\returns an expression of the coefficient-wise quotient of *this and \\a other\n  *\n  * Example: \\include MatrixBase_cwiseQuotient.cpp\n  * Output: \\verbinclude MatrixBase_cwiseQuotient.out\n  *\n  * \\sa class CwiseBinaryOp, cwiseProduct(), cwiseInverse()\n  */\ntemplate<typename OtherDerived>\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseBinaryOp<internal::scalar_quotient_op<Scalar>, const Derived, const OtherDerived>\ncwiseQuotient(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const\n{\n  return CwiseBinaryOp<internal::scalar_quotient_op<Scalar>, const Derived, const OtherDerived>(derived(), other.derived());\n}\n\ntypedef CwiseBinaryOp<internal::scalar_cmp_op<Scalar,Scalar,internal::cmp_EQ>, const Derived, const ConstantReturnType> CwiseScalarEqualReturnType;\n\n/** \\returns an expression of the coefficient-wise == operator of \\c *this and a scalar \\a s\n  *\n  * \\warning this performs an exact comparison, which is generally a bad idea with floating-point types.\n  * In order to check for equality between two vectors or matrices with floating-point coefficients, it is\n  * generally a far better idea to use a fuzzy comparison as provided by isApprox() and\n  * isMuchSmallerThan().\n  *\n  * \\sa cwiseEqual(const MatrixBase<OtherDerived> &) const\n  */\nEIGEN_DEVICE_FUNC\ninline const CwiseScalarEqualReturnType\ncwiseEqual(const Scalar& s) const\n{\n  return CwiseScalarEqualReturnType(derived(), Derived::Constant(rows(), cols(), s), internal::scalar_cmp_op<Scalar,Scalar,internal::cmp_EQ>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/plugins/MatrixCwiseUnaryOps.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// This file is included into the body of the base classes supporting matrix specific coefficient-wise functions.\n// This include MatrixBase and SparseMatrixBase.\n\n\ntypedef CwiseUnaryOp<internal::scalar_abs_op<Scalar>, const Derived> CwiseAbsReturnType;\ntypedef CwiseUnaryOp<internal::scalar_abs2_op<Scalar>, const Derived> CwiseAbs2ReturnType;\ntypedef CwiseUnaryOp<internal::scalar_arg_op<Scalar>, const Derived> CwiseArgReturnType;\ntypedef CwiseUnaryOp<internal::scalar_sqrt_op<Scalar>, const Derived> CwiseSqrtReturnType;\ntypedef CwiseUnaryOp<internal::scalar_sign_op<Scalar>, const Derived> CwiseSignReturnType;\ntypedef CwiseUnaryOp<internal::scalar_inverse_op<Scalar>, const Derived> CwiseInverseReturnType;\n\n/// \\returns an expression of the coefficient-wise absolute value of \\c *this\n///\n/// Example: \\include MatrixBase_cwiseAbs.cpp\n/// Output: \\verbinclude MatrixBase_cwiseAbs.out\n///\nEIGEN_DOC_UNARY_ADDONS(cwiseAbs,absolute value)\n///\n/// \\sa cwiseAbs2()\n///\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseAbsReturnType\ncwiseAbs() const { return CwiseAbsReturnType(derived()); }\n\n/// \\returns an expression of the coefficient-wise squared absolute value of \\c *this\n///\n/// Example: \\include MatrixBase_cwiseAbs2.cpp\n/// Output: \\verbinclude MatrixBase_cwiseAbs2.out\n///\nEIGEN_DOC_UNARY_ADDONS(cwiseAbs2,squared absolute value)\n///\n/// \\sa cwiseAbs()\n///\nEIGEN_DEVICE_FUNC\nEIGEN_STRONG_INLINE const CwiseAbs2ReturnType\ncwiseAbs2() const { return CwiseAbs2ReturnType(derived()); }\n\n/// \\returns an expression of the coefficient-wise square root of *this.\n///\n/// Example: \\include MatrixBase_cwiseSqrt.cpp\n/// Output: \\verbinclude MatrixBase_cwiseSqrt.out\n///\nEIGEN_DOC_UNARY_ADDONS(cwiseSqrt,square-root)\n///\n/// \\sa cwisePow(), cwiseSquare()\n///\nEIGEN_DEVICE_FUNC\ninline const CwiseSqrtReturnType\ncwiseSqrt() const { return CwiseSqrtReturnType(derived()); }\n\n/// \\returns an expression of the coefficient-wise signum of *this.\n///\n/// Example: \\include MatrixBase_cwiseSign.cpp\n/// Output: \\verbinclude MatrixBase_cwiseSign.out\n///\nEIGEN_DOC_UNARY_ADDONS(cwiseSign,sign function)\n///\nEIGEN_DEVICE_FUNC\ninline const CwiseSignReturnType\ncwiseSign() const { return CwiseSignReturnType(derived()); }\n\n\n/// \\returns an expression of the coefficient-wise inverse of *this.\n///\n/// Example: \\include MatrixBase_cwiseInverse.cpp\n/// Output: \\verbinclude MatrixBase_cwiseInverse.out\n///\nEIGEN_DOC_UNARY_ADDONS(cwiseInverse,inverse)\n///\n/// \\sa cwiseProduct()\n///\nEIGEN_DEVICE_FUNC\ninline const CwiseInverseReturnType\ncwiseInverse() const { return CwiseInverseReturnType(derived()); }\n\n/// \\returns an expression of the coefficient-wise phase angle of \\c *this\n///\n/// Example: \\include MatrixBase_cwiseArg.cpp\n/// Output: \\verbinclude MatrixBase_cwiseArg.out\n///\nEIGEN_DOC_UNARY_ADDONS(cwiseArg,arg)\n\nEIGEN_DEVICE_FUNC\ninline const CwiseArgReturnType\ncwiseArg() const { return CwiseArgReturnType(derived()); }\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/Eigen/src/plugins/ReshapedMethods.h",
    "content": "\n#ifdef EIGEN_PARSED_BY_DOXYGEN\n\n/// \\returns an expression of \\c *this with reshaped sizes.\n///\n/// \\param nRows the number of rows in the reshaped expression, specified at either run-time or compile-time, or AutoSize\n/// \\param nCols the number of columns in the reshaped expression, specified at either run-time or compile-time, or AutoSize\n/// \\tparam Order specifies whether the coefficients should be processed in column-major-order (ColMajor), in row-major-order (RowMajor),\n///               or follows the \\em natural order of the nested expression (AutoOrder). The default is ColMajor.\n/// \\tparam NRowsType the type of the value handling the number of rows, typically Index.\n/// \\tparam NColsType the type of the value handling the number of columns, typically Index.\n///\n/// Dynamic size example: \\include MatrixBase_reshaped_int_int.cpp\n/// Output: \\verbinclude MatrixBase_reshaped_int_int.out\n///\n/// The number of rows \\a nRows and columns \\a nCols can also be specified at compile-time by passing Eigen::fix<N>,\n/// or Eigen::fix<N>(n) as arguments. In the later case, \\c n plays the role of a runtime fallback value in case \\c N equals Eigen::Dynamic.\n/// Here is an example with a fixed number of rows and columns:\n/// \\include MatrixBase_reshaped_fixed.cpp\n/// Output: \\verbinclude MatrixBase_reshaped_fixed.out\n///\n/// Finally, one of the sizes parameter can be automatically deduced from the other one by passing AutoSize as in the following example:\n/// \\include MatrixBase_reshaped_auto.cpp\n/// Output: \\verbinclude MatrixBase_reshaped_auto.out\n/// AutoSize does preserve compile-time sizes when possible, i.e., when the sizes of the input are known at compile time \\b and\n/// that the other size is passed at compile-time using Eigen::fix<N> as above.\n///\n/// \\sa class Reshaped, fix, fix<N>(int)\n///\ntemplate<int Order = ColMajor, typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC\ninline Reshaped<Derived,...>\nreshaped(NRowsType nRows, NColsType nCols);\n\n/// This is the const version of reshaped(NRowsType,NColsType).\ntemplate<int Order = ColMajor, typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC\ninline const Reshaped<const Derived,...>\nreshaped(NRowsType nRows, NColsType nCols) const;\n\n/// \\returns an expression of \\c *this with columns (or rows) stacked to a linear column vector\n///\n/// \\tparam Order specifies whether the coefficients should be processed in column-major-order (ColMajor), in row-major-order (RowMajor),\n///               or follows the \\em natural order of the nested expression (AutoOrder). The default is ColMajor.\n///\n/// This overloads is essentially a shortcut for `A.reshaped<Order>(AutoSize,fix<1>)`.\n///\n/// - If `Order==ColMajor` (the default), then it returns a column-vector from the stacked columns of \\c *this.\n/// - If `Order==RowMajor`, then it returns a column-vector from the stacked rows of \\c *this.\n/// - If `Order==AutoOrder`, then it returns a column-vector with elements stacked following the storage order of \\c *this.\n///   This mode is the recommended one when the particular ordering of the element is not relevant.\n///\n/// Example:\n/// \\include MatrixBase_reshaped_to_vector.cpp\n/// Output: \\verbinclude MatrixBase_reshaped_to_vector.out\n///\n/// If you want more control, you can still fall back to reshaped(NRowsType,NColsType).\n///\n/// \\sa reshaped(NRowsType,NColsType), class Reshaped\n///\ntemplate<int Order = ColMajor>\nEIGEN_DEVICE_FUNC\ninline Reshaped<Derived,...>\nreshaped();\n\n/// This is the const version of reshaped().\ntemplate<int Order = ColMajor>\nEIGEN_DEVICE_FUNC\ninline const Reshaped<const Derived,...>\nreshaped() const;\n\n#else\n\n// This file is automatically included twice to generate const and non-const versions\n\n#ifndef EIGEN_RESHAPED_METHOD_2ND_PASS\n#define EIGEN_RESHAPED_METHOD_CONST const\n#else\n#define EIGEN_RESHAPED_METHOD_CONST\n#endif\n\n#ifndef EIGEN_RESHAPED_METHOD_2ND_PASS\n\n// This part is included once\n\n#endif\n\ntemplate<typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC\ninline Reshaped<EIGEN_RESHAPED_METHOD_CONST Derived,\n                internal::get_compiletime_reshape_size<NRowsType,NColsType,SizeAtCompileTime>::value,\n                internal::get_compiletime_reshape_size<NColsType,NRowsType,SizeAtCompileTime>::value>\nreshaped(NRowsType nRows, NColsType nCols) EIGEN_RESHAPED_METHOD_CONST\n{\n  return Reshaped<EIGEN_RESHAPED_METHOD_CONST Derived,\n                  internal::get_compiletime_reshape_size<NRowsType,NColsType,SizeAtCompileTime>::value,\n                  internal::get_compiletime_reshape_size<NColsType,NRowsType,SizeAtCompileTime>::value>\n                (derived(),\n                 internal::get_runtime_reshape_size(nRows,internal::get_runtime_value(nCols),size()),\n                 internal::get_runtime_reshape_size(nCols,internal::get_runtime_value(nRows),size()));\n}\n\ntemplate<int Order, typename NRowsType, typename NColsType>\nEIGEN_DEVICE_FUNC\ninline Reshaped<EIGEN_RESHAPED_METHOD_CONST Derived,\n                internal::get_compiletime_reshape_size<NRowsType,NColsType,SizeAtCompileTime>::value,\n                internal::get_compiletime_reshape_size<NColsType,NRowsType,SizeAtCompileTime>::value,\n                internal::get_compiletime_reshape_order<Flags,Order>::value>\nreshaped(NRowsType nRows, NColsType nCols) EIGEN_RESHAPED_METHOD_CONST\n{\n  return Reshaped<EIGEN_RESHAPED_METHOD_CONST Derived,\n                  internal::get_compiletime_reshape_size<NRowsType,NColsType,SizeAtCompileTime>::value,\n                  internal::get_compiletime_reshape_size<NColsType,NRowsType,SizeAtCompileTime>::value,\n                  internal::get_compiletime_reshape_order<Flags,Order>::value>\n                (derived(),\n                 internal::get_runtime_reshape_size(nRows,internal::get_runtime_value(nCols),size()),\n                 internal::get_runtime_reshape_size(nCols,internal::get_runtime_value(nRows),size()));\n}\n\n// Views as linear vectors\n\nEIGEN_DEVICE_FUNC\ninline Reshaped<EIGEN_RESHAPED_METHOD_CONST Derived,SizeAtCompileTime,1>\nreshaped() EIGEN_RESHAPED_METHOD_CONST\n{\n  return Reshaped<EIGEN_RESHAPED_METHOD_CONST Derived,SizeAtCompileTime,1>(derived(),size(),1);\n}\n\ntemplate<int Order>\nEIGEN_DEVICE_FUNC\ninline Reshaped<EIGEN_RESHAPED_METHOD_CONST Derived, SizeAtCompileTime, 1,\n                internal::get_compiletime_reshape_order<Flags,Order>::value>\nreshaped() EIGEN_RESHAPED_METHOD_CONST\n{\n  EIGEN_STATIC_ASSERT(Order==RowMajor || Order==ColMajor || Order==AutoOrder, INVALID_TEMPLATE_PARAMETER);\n  return Reshaped<EIGEN_RESHAPED_METHOD_CONST Derived, SizeAtCompileTime, 1,\n                  internal::get_compiletime_reshape_order<Flags,Order>::value>\n                (derived(), size(), 1);\n}\n\n#undef EIGEN_RESHAPED_METHOD_CONST\n\n#ifndef EIGEN_RESHAPED_METHOD_2ND_PASS\n#define EIGEN_RESHAPED_METHOD_2ND_PASS\n#include \"ReshapedMethods.h\"\n#undef EIGEN_RESHAPED_METHOD_2ND_PASS\n#endif\n\n#endif // EIGEN_PARSED_BY_DOXYGEN\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/INSTALL",
    "content": "Installation instructions for Eigen\n***********************************\n\nExplanation before starting\n***************************\n\nEigen consists only of header files, hence there is nothing to compile\nbefore you can use it. Moreover, these header files do not depend on your\nplatform, they are the same for everybody.\n\nMethod 1. Installing without using CMake\n****************************************\n\nYou can use right away the headers in the Eigen/ subdirectory. In order\nto install, just copy this Eigen/ subdirectory to your favorite location.\nIf you also want the unsupported features, copy the unsupported/\nsubdirectory too.\n\nMethod 2. Installing using CMake\n********************************\n\nLet's call this directory 'source_dir' (where this INSTALL file is).\nBefore starting, create another directory which we will call 'build_dir'.\n\nDo:\n\n  cd build_dir\n  cmake source_dir\n  make install\n\nThe \"make install\" step may require administrator privileges.\n\nYou can adjust the installation destination (the \"prefix\")\nby passing the -DCMAKE_INSTALL_PREFIX=myprefix option to cmake, as is\nexplained in the message that cmake prints at the end.\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/README.md",
    "content": "**Eigen is a C++ template library for linear algebra: matrices, vectors, numerical solvers, and related algorithms.**\n\nFor more information go to http://eigen.tuxfamily.org/.\n\nFor ***pull request***, ***bug reports***, and ***feature requests***, go to https://gitlab.com/libeigen/eigen.\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/BenchSparseUtil.h",
    "content": "\n#include <Eigen/Sparse>\n#include <bench/BenchTimer.h>\n#include <set>\n\nusing namespace std;\nusing namespace Eigen;\nusing namespace Eigen;\n\n#ifndef SIZE\n#define SIZE 1024\n#endif\n\n#ifndef DENSITY\n#define DENSITY 0.01\n#endif\n\n#ifndef SCALAR\n#define SCALAR double\n#endif\n\ntypedef SCALAR Scalar;\ntypedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\ntypedef Matrix<Scalar,Dynamic,1> DenseVector;\ntypedef SparseMatrix<Scalar> EigenSparseMatrix;\n\nvoid fillMatrix(float density, int rows, int cols,  EigenSparseMatrix& dst)\n{\n  dst.reserve(double(rows)*cols*density);\n  for(int j = 0; j < cols; j++)\n  {\n    for(int i = 0; i < rows; i++)\n    {\n      Scalar v = (internal::random<float>(0,1) < density) ? internal::random<Scalar>() : 0;\n      if (v!=0)\n        dst.insert(i,j) = v;\n    }\n  }\n  dst.finalize();\n}\n\nvoid fillMatrix2(int nnzPerCol, int rows, int cols,  EigenSparseMatrix& dst)\n{\n//   std::cout << \"alloc \" << nnzPerCol*cols << \"\\n\";\n  dst.reserve(nnzPerCol*cols);\n  for(int j = 0; j < cols; j++)\n  {\n    std::set<int> aux;\n    for(int i = 0; i < nnzPerCol; i++)\n    {\n      int k = internal::random<int>(0,rows-1);\n      while (aux.find(k)!=aux.end())\n        k = internal::random<int>(0,rows-1);\n      aux.insert(k);\n\n      dst.insert(k,j) = internal::random<Scalar>();\n    }\n  }\n  dst.finalize();\n}\n\nvoid eiToDense(const EigenSparseMatrix& src, DenseMatrix& dst)\n{\n  dst.setZero();\n  for (int j=0; j<src.cols(); ++j)\n    for (EigenSparseMatrix::InnerIterator it(src.derived(), j); it; ++it)\n      dst(it.index(),j) = it.value();\n}\n\n#ifndef NOGMM\n#include \"gmm/gmm.h\"\ntypedef gmm::csc_matrix<Scalar> GmmSparse;\ntypedef gmm::col_matrix< gmm::wsvector<Scalar> > GmmDynSparse;\nvoid eiToGmm(const EigenSparseMatrix& src, GmmSparse& dst)\n{\n  GmmDynSparse tmp(src.rows(), src.cols());\n  for (int j=0; j<src.cols(); ++j)\n    for (EigenSparseMatrix::InnerIterator it(src.derived(), j); it; ++it)\n      tmp(it.index(),j) = it.value();\n  gmm::copy(tmp, dst);\n}\n#endif\n\n#ifndef NOMTL\n#include <boost/numeric/mtl/mtl.hpp>\ntypedef mtl::compressed2D<Scalar, mtl::matrix::parameters<mtl::tag::col_major> > MtlSparse;\ntypedef mtl::compressed2D<Scalar, mtl::matrix::parameters<mtl::tag::row_major> > MtlSparseRowMajor;\nvoid eiToMtl(const EigenSparseMatrix& src, MtlSparse& dst)\n{\n  mtl::matrix::inserter<MtlSparse> ins(dst);\n  for (int j=0; j<src.cols(); ++j)\n    for (EigenSparseMatrix::InnerIterator it(src.derived(), j); it; ++it)\n      ins[it.index()][j] = it.value();\n}\n#endif\n\n#ifdef CSPARSE\nextern \"C\" {\n#include \"cs.h\"\n}\nvoid eiToCSparse(const EigenSparseMatrix& src, cs* &dst)\n{\n  cs* aux = cs_spalloc (0, 0, 1, 1, 1);\n  for (int j=0; j<src.cols(); ++j)\n    for (EigenSparseMatrix::InnerIterator it(src.derived(), j); it; ++it)\n      if (!cs_entry(aux, it.index(), j, it.value()))\n      {\n        std::cout << \"cs_entry error\\n\";\n        exit(2);\n      }\n   dst = cs_compress(aux);\n//    cs_spfree(aux);\n}\n#endif // CSPARSE\n\n#ifndef NOUBLAS\n#include <boost/numeric/ublas/vector.hpp>\n#include <boost/numeric/ublas/matrix.hpp>\n#include <boost/numeric/ublas/io.hpp>\n#include <boost/numeric/ublas/triangular.hpp>\n#include <boost/numeric/ublas/vector_sparse.hpp>\n#include <boost/numeric/ublas/matrix_sparse.hpp>\n#include <boost/numeric/ublas/vector_of_vector.hpp>\n#include <boost/numeric/ublas/operation.hpp>\n\ntypedef boost::numeric::ublas::compressed_matrix<Scalar,boost::numeric::ublas::column_major> UBlasSparse;\n\nvoid eiToUblas(const EigenSparseMatrix& src, UBlasSparse& dst)\n{\n  dst.resize(src.rows(), src.cols(), false);\n  for (int j=0; j<src.cols(); ++j)\n    for (EigenSparseMatrix::InnerIterator it(src.derived(), j); it; ++it)\n      dst(it.index(),j) = it.value();\n}\n\ntemplate <typename EigenType, typename UblasType>\nvoid eiToUblasVec(const EigenType& src, UblasType& dst)\n{\n  dst.resize(src.size());\n  for (int j=0; j<src.size(); ++j)\n      dst[j] = src.coeff(j);\n}\n#endif\n\n#ifdef OSKI\nextern \"C\" {\n#include <oski/oski.h>\n}\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/BenchTimer.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BENCH_TIMERR_H\n#define EIGEN_BENCH_TIMERR_H\n\n#if defined(_WIN32) || defined(__CYGWIN__)\n# ifndef NOMINMAX\n#   define NOMINMAX\n#   define EIGEN_BT_UNDEF_NOMINMAX\n# endif\n# ifndef WIN32_LEAN_AND_MEAN\n#   define WIN32_LEAN_AND_MEAN\n#   define EIGEN_BT_UNDEF_WIN32_LEAN_AND_MEAN\n# endif\n# include <windows.h>\n#elif defined(__APPLE__)\n#include <mach/mach_time.h>\n#else\n# include <unistd.h>\n#endif\n\nstatic void escape(void *p) {\n#if EIGEN_COMP_GNUC || EIGEN_COMP_CLANG\n  asm volatile(\"\" : : \"g\"(p) : \"memory\");\n#endif\n}\n\nstatic void clobber() {\n#if EIGEN_COMP_GNUC || EIGEN_COMP_CLANG\n  asm volatile(\"\" : : : \"memory\");\n#endif\n}\n\n#include <Eigen/Core>\n\nnamespace Eigen\n{\n\nenum {\n  CPU_TIMER = 0,\n  REAL_TIMER = 1\n};\n\n/** Elapsed time timer keeping the best try.\n  *\n  * On POSIX platforms we use clock_gettime with CLOCK_PROCESS_CPUTIME_ID.\n  * On Windows we use QueryPerformanceCounter\n  *\n  * Important: on linux, you must link with -lrt\n  */\nclass BenchTimer\n{\npublic:\n\n  BenchTimer()\n  {\n#if defined(_WIN32) || defined(__CYGWIN__)\n    LARGE_INTEGER freq;\n    QueryPerformanceFrequency(&freq);\n    m_frequency = (double)freq.QuadPart;\n#endif\n    reset();\n  }\n\n  ~BenchTimer() {}\n\n  inline void reset()\n  {\n    m_bests.fill(1e9);\n    m_worsts.fill(0);\n    m_totals.setZero();\n  }\n  inline void start()\n  {\n    m_starts[CPU_TIMER]  = getCpuTime();\n    m_starts[REAL_TIMER] = getRealTime();\n  }\n  inline void stop()\n  {\n    m_times[CPU_TIMER] = getCpuTime() - m_starts[CPU_TIMER];\n    m_times[REAL_TIMER] = getRealTime() - m_starts[REAL_TIMER];\n    #if EIGEN_VERSION_AT_LEAST(2,90,0)\n    m_bests = m_bests.cwiseMin(m_times);\n    m_worsts = m_worsts.cwiseMax(m_times);\n    #else\n    m_bests(0) = std::min(m_bests(0),m_times(0));\n    m_bests(1) = std::min(m_bests(1),m_times(1));\n    m_worsts(0) = std::max(m_worsts(0),m_times(0));\n    m_worsts(1) = std::max(m_worsts(1),m_times(1));\n    #endif\n    m_totals += m_times;\n  }\n\n  /** Return the elapsed time in seconds between the last start/stop pair\n    */\n  inline double value(int TIMER = CPU_TIMER) const\n  {\n    return m_times[TIMER];\n  }\n\n  /** Return the best elapsed time in seconds\n    */\n  inline double best(int TIMER = CPU_TIMER) const\n  {\n    return m_bests[TIMER];\n  }\n\n  /** Return the worst elapsed time in seconds\n    */\n  inline double worst(int TIMER = CPU_TIMER) const\n  {\n    return m_worsts[TIMER];\n  }\n\n  /** Return the total elapsed time in seconds.\n    */\n  inline double total(int TIMER = CPU_TIMER) const\n  {\n    return m_totals[TIMER];\n  }\n\n  inline double getCpuTime() const\n  {\n#ifdef _WIN32\n    LARGE_INTEGER query_ticks;\n    QueryPerformanceCounter(&query_ticks);\n    return query_ticks.QuadPart/m_frequency;\n#elif __APPLE__\n    return double(mach_absolute_time())*1e-9;\n#else\n    timespec ts;\n    clock_gettime(CLOCK_PROCESS_CPUTIME_ID, &ts);\n    return double(ts.tv_sec) + 1e-9 * double(ts.tv_nsec);\n#endif\n  }\n\n  inline double getRealTime() const\n  {\n#ifdef _WIN32\n    SYSTEMTIME st;\n    GetSystemTime(&st);\n    return (double)st.wSecond + 1.e-3 * (double)st.wMilliseconds;\n#elif __APPLE__\n    return double(mach_absolute_time())*1e-9;\n#else\n    timespec ts;\n    clock_gettime(CLOCK_REALTIME, &ts);\n    return double(ts.tv_sec) + 1e-9 * double(ts.tv_nsec);\n#endif\n  }\n\nprotected:\n#if defined(_WIN32) || defined(__CYGWIN__)\n  double m_frequency;\n#endif\n  Vector2d m_starts;\n  Vector2d m_times;\n  Vector2d m_bests;\n  Vector2d m_worsts;\n  Vector2d m_totals;\n\npublic:\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n};\n\n#define BENCH(TIMER,TRIES,REP,CODE) { \\\n    TIMER.reset(); \\\n    for(int uglyvarname1=0; uglyvarname1<TRIES; ++uglyvarname1){ \\\n      TIMER.start(); \\\n      for(int uglyvarname2=0; uglyvarname2<REP; ++uglyvarname2){ \\\n        CODE; \\\n      } \\\n      TIMER.stop(); \\\n      clobber(); \\\n    } \\\n  }\n\n}\n\n// clean #defined tokens\n#ifdef EIGEN_BT_UNDEF_NOMINMAX\n# undef EIGEN_BT_UNDEF_NOMINMAX\n# undef NOMINMAX\n#endif\n\n#ifdef EIGEN_BT_UNDEF_WIN32_LEAN_AND_MEAN\n# undef EIGEN_BT_UNDEF_WIN32_LEAN_AND_MEAN\n# undef WIN32_LEAN_AND_MEAN\n#endif\n\n#endif // EIGEN_BENCH_TIMERR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/BenchUtil.h",
    "content": "\n#ifndef EIGEN_BENCH_UTIL_H\n#define EIGEN_BENCH_UTIL_H\n\n#include <Eigen/Core>\n#include \"BenchTimer.h\"\n\nusing namespace std;\nusing namespace Eigen;\n\n#include <boost/preprocessor/repetition/enum_params.hpp>\n#include <boost/preprocessor/repetition.hpp>\n#include <boost/preprocessor/seq.hpp>\n#include <boost/preprocessor/array.hpp>\n#include <boost/preprocessor/arithmetic.hpp>\n#include <boost/preprocessor/comparison.hpp>\n#include <boost/preprocessor/punctuation.hpp>\n#include <boost/preprocessor/punctuation/comma.hpp>\n#include <boost/preprocessor/stringize.hpp>\n\ntemplate<typename MatrixType> void initMatrix_random(MatrixType& mat) __attribute__((noinline));\ntemplate<typename MatrixType> void initMatrix_random(MatrixType& mat)\n{\n  mat.setRandom();// = MatrixType::random(mat.rows(), mat.cols());\n}\n\ntemplate<typename MatrixType> void initMatrix_identity(MatrixType& mat) __attribute__((noinline));\ntemplate<typename MatrixType> void initMatrix_identity(MatrixType& mat)\n{\n  mat.setIdentity();\n}\n\n#ifndef __INTEL_COMPILER\n#define DISABLE_SSE_EXCEPTIONS()  { \\\n  int aux; \\\n  asm( \\\n  \"stmxcsr   %[aux]           \\n\\t\" \\\n  \"orl       $32832, %[aux]   \\n\\t\" \\\n  \"ldmxcsr   %[aux]           \\n\\t\" \\\n  : : [aux] \"m\" (aux)); \\\n}\n#else\n#define DISABLE_SSE_EXCEPTIONS()  \n#endif\n\n#ifdef BENCH_GMM\n#include <gmm/gmm.h>\ntemplate <typename EigenMatrixType, typename GmmMatrixType>\nvoid eiToGmm(const EigenMatrixType& src, GmmMatrixType& dst)\n{\n  dst.resize(src.rows(),src.cols());\n  for (int j=0; j<src.cols(); ++j)\n    for (int i=0; i<src.rows(); ++i)\n      dst(i,j) = src.coeff(i,j);\n}\n#endif\n\n\n#ifdef BENCH_GSL\n#include <gsl/gsl_matrix.h>\n#include <gsl/gsl_linalg.h>\n#include <gsl/gsl_eigen.h>\ntemplate <typename EigenMatrixType>\nvoid eiToGsl(const EigenMatrixType& src, gsl_matrix** dst)\n{\n  for (int j=0; j<src.cols(); ++j)\n    for (int i=0; i<src.rows(); ++i)\n      gsl_matrix_set(*dst, i, j, src.coeff(i,j));\n}\n#endif\n\n#ifdef BENCH_UBLAS\n#include <boost/numeric/ublas/matrix.hpp>\n#include <boost/numeric/ublas/vector.hpp>\ntemplate <typename EigenMatrixType, typename UblasMatrixType>\nvoid eiToUblas(const EigenMatrixType& src, UblasMatrixType& dst)\n{\n  dst.resize(src.rows(),src.cols());\n  for (int j=0; j<src.cols(); ++j)\n    for (int i=0; i<src.rows(); ++i)\n      dst(i,j) = src.coeff(i,j);\n}\ntemplate <typename EigenType, typename UblasType>\nvoid eiToUblasVec(const EigenType& src, UblasType& dst)\n{\n  dst.resize(src.size());\n  for (int j=0; j<src.size(); ++j)\n      dst[j] = src.coeff(j);\n}\n#endif\n\n#endif // EIGEN_BENCH_UTIL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/README.txt",
    "content": "\nThis folder contains a couple of benchmark utities and Eigen benchmarks.\n\n****************************\n* bench_multi_compilers.sh *\n****************************\n\nThis script allows to run a benchmark on a set of different compilers/compiler options.\nIt takes two arguments:\n - a file defining the list of the compilers with their options\n - the .cpp file of the benchmark\n\nExamples:\n\n$ ./bench_multi_compilers.sh basicbench.cxxlist basicbenchmark.cpp\n\n    g++-4.1 -O3 -DNDEBUG -finline-limit=10000\n    3d-3x3   /   4d-4x4   /   Xd-4x4   /   Xd-20x20   /\n    0.271102   0.131416   0.422322   0.198633\n    0.201658   0.102436   0.397566   0.207282\n\n    g++-4.2 -O3 -DNDEBUG -finline-limit=10000\n    3d-3x3   /   4d-4x4   /   Xd-4x4   /   Xd-20x20   /\n    0.107805   0.0890579   0.30265   0.161843\n    0.127157   0.0712581   0.278341   0.191029\n\n    g++-4.3 -O3 -DNDEBUG -finline-limit=10000\n    3d-3x3   /   4d-4x4   /   Xd-4x4   /   Xd-20x20   /\n    0.134318   0.105291   0.3704   0.180966\n    0.137703   0.0732472   0.31225   0.202204\n\n    icpc -fast -DNDEBUG -fno-exceptions -no-inline-max-size\n    3d-3x3   /   4d-4x4   /   Xd-4x4   /   Xd-20x20   /\n    0.226145   0.0941319   0.371873   0.159433\n    0.109302   0.0837538   0.328102   0.173891\n\n\n$ ./bench_multi_compilers.sh ompbench.cxxlist ompbenchmark.cpp\n\n    g++-4.2 -O3 -DNDEBUG -finline-limit=10000 -fopenmp\n    double, fixed-size 4x4: 0.00165105s  0.0778739s\n    double, 32x32: 0.0654769s 0.075289s  => x0.869674 (2)\n    double, 128x128: 0.054148s 0.0419669s  => x1.29025 (2)\n    double, 512x512: 0.913799s 0.428533s  => x2.13239 (2)\n    double, 1024x1024: 14.5972s 9.3542s  => x1.5605 (2)\n\n    icpc -fast -DNDEBUG -fno-exceptions -no-inline-max-size -openmp\n    double, fixed-size 4x4: 0.000589848s  0.019949s\n    double, 32x32: 0.0682781s 0.0449722s  => x1.51823 (2)\n    double, 128x128: 0.0547509s 0.0435519s  => x1.25714 (2)\n    double, 512x512: 0.829436s 0.424438s  => x1.9542 (2)\n    double, 1024x1024: 14.5243s 10.7735s  => x1.34815 (2)\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/analyze-blocking-sizes.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Jacob <benoitjacob@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <iostream>\n#include <cstdint>\n#include <cstdlib>\n#include <vector>\n#include <algorithm>\n#include <fstream>\n#include <string>\n#include <cmath>\n#include <cassert>\n#include <cstring>\n#include <memory>\n\n#include <Eigen/Core>\n\nusing namespace std;\n\nconst int default_precision = 4;\n\n// see --only-cubic-sizes\nbool only_cubic_sizes = false;\n\n// see --dump-tables\nbool dump_tables = false;\n\nuint8_t log2_pot(size_t x) {\n  size_t l = 0;\n  while (x >>= 1) l++;\n  return l;\n}\n\nuint16_t compact_size_triple(size_t k, size_t m, size_t n)\n{\n  return (log2_pot(k) << 8) | (log2_pot(m) << 4) | log2_pot(n);\n}\n\n// just a helper to store a triple of K,M,N sizes for matrix product\nstruct size_triple_t\n{\n  uint16_t k, m, n;\n  size_triple_t() : k(0), m(0), n(0) {}\n  size_triple_t(size_t _k, size_t _m, size_t _n) : k(_k), m(_m), n(_n) {}\n  size_triple_t(const size_triple_t& o) : k(o.k), m(o.m), n(o.n) {}\n  size_triple_t(uint16_t compact)\n  {\n    k = 1 << ((compact & 0xf00) >> 8);\n    m = 1 << ((compact & 0x0f0) >> 4);\n    n = 1 << ((compact & 0x00f) >> 0);\n  }\n  bool is_cubic() const { return k == m && m == n; }\n};\n\nostream& operator<<(ostream& s, const size_triple_t& t)\n{\n  return s << \"(\" << t.k << \", \" << t.m << \", \" << t.n << \")\";\n}\n\nstruct inputfile_entry_t\n{\n  uint16_t product_size;\n  uint16_t pot_block_size;\n  size_triple_t nonpot_block_size;\n  float gflops;\n};\n\nstruct inputfile_t\n{\n  enum class type_t {\n    unknown,\n    all_pot_sizes,\n    default_sizes\n  };\n\n  string filename;\n  vector<inputfile_entry_t> entries;\n  type_t type;\n\n  inputfile_t(const string& fname)\n    : filename(fname)\n    , type(type_t::unknown)\n  {\n    ifstream stream(filename);\n    if (!stream.is_open()) {\n      cerr << \"couldn't open input file: \" << filename << endl;\n      exit(1);\n    }\n    string line;\n    while (getline(stream, line)) {\n      if (line.empty()) continue;\n      if (line.find(\"BEGIN MEASUREMENTS ALL POT SIZES\") == 0) {\n        if (type != type_t::unknown) {\n          cerr << \"Input file \" << filename << \" contains redundant BEGIN MEASUREMENTS lines\";\n          exit(1);\n        }\n        type = type_t::all_pot_sizes;\n        continue;\n      }\n      if (line.find(\"BEGIN MEASUREMENTS DEFAULT SIZES\") == 0) {\n        if (type != type_t::unknown) {\n          cerr << \"Input file \" << filename << \" contains redundant BEGIN MEASUREMENTS lines\";\n          exit(1);\n        }\n        type = type_t::default_sizes;\n        continue;\n      }\n      \n\n      if (type == type_t::unknown) {\n        continue;\n      }\n      switch(type) {\n        case type_t::all_pot_sizes: {\n          unsigned int product_size, block_size;\n          float gflops;\n          int sscanf_result =\n            sscanf(line.c_str(), \"%x %x %f\",\n                   &product_size,\n                   &block_size,\n                   &gflops);\n          if (3 != sscanf_result ||\n              !product_size ||\n              product_size > 0xfff ||\n              !block_size ||\n              block_size > 0xfff ||\n              !isfinite(gflops))\n          {\n            cerr << \"ill-formed input file: \" << filename << endl;\n            cerr << \"offending line:\" << endl << line << endl;\n            exit(1);\n          }\n          if (only_cubic_sizes && !size_triple_t(product_size).is_cubic()) {\n            continue;\n          }\n          inputfile_entry_t entry;\n          entry.product_size = uint16_t(product_size);\n          entry.pot_block_size = uint16_t(block_size);\n          entry.gflops = gflops;\n          entries.push_back(entry);\n          break;\n        }\n        case type_t::default_sizes: {\n          unsigned int product_size;\n          float gflops;\n          int bk, bm, bn;\n          int sscanf_result =\n            sscanf(line.c_str(), \"%x default(%d, %d, %d) %f\",\n                   &product_size,\n                   &bk, &bm, &bn,\n                   &gflops);\n          if (5 != sscanf_result ||\n              !product_size ||\n              product_size > 0xfff ||\n              !isfinite(gflops))\n          {\n            cerr << \"ill-formed input file: \" << filename << endl;\n            cerr << \"offending line:\" << endl << line << endl;\n            exit(1);\n          }\n          if (only_cubic_sizes && !size_triple_t(product_size).is_cubic()) {\n            continue;\n          }\n          inputfile_entry_t entry;\n          entry.product_size = uint16_t(product_size);\n          entry.pot_block_size = 0;\n          entry.nonpot_block_size = size_triple_t(bk, bm, bn);\n          entry.gflops = gflops;\n          entries.push_back(entry);\n          break;\n        }\n        \n        default:\n          break;\n      }\n    }\n    stream.close();\n    if (type == type_t::unknown) {\n      cerr << \"Unrecognized input file \" << filename << endl;\n      exit(1);\n    }\n    if (entries.empty()) {\n      cerr << \"didn't find any measurements in input file: \" << filename << endl;\n      exit(1);\n    }\n  }\n};\n\nstruct preprocessed_inputfile_entry_t\n{\n  uint16_t product_size;\n  uint16_t block_size;\n\n  float efficiency;\n};\n\nbool lower_efficiency(const preprocessed_inputfile_entry_t& e1, const preprocessed_inputfile_entry_t& e2)\n{\n  return e1.efficiency < e2.efficiency;\n}\n\nstruct preprocessed_inputfile_t\n{\n  string filename;\n  vector<preprocessed_inputfile_entry_t> entries;\n\n  preprocessed_inputfile_t(const inputfile_t& inputfile)\n    : filename(inputfile.filename)\n  {\n    if (inputfile.type != inputfile_t::type_t::all_pot_sizes) {\n      abort();\n    }\n    auto it = inputfile.entries.begin();\n    auto it_first_with_given_product_size = it;\n    while (it != inputfile.entries.end()) {\n      ++it;\n      if (it == inputfile.entries.end() ||\n        it->product_size != it_first_with_given_product_size->product_size)\n      {\n        import_input_file_range_one_product_size(it_first_with_given_product_size, it);\n        it_first_with_given_product_size = it;\n      }\n    }\n  }\n\nprivate:\n  void import_input_file_range_one_product_size(\n    const vector<inputfile_entry_t>::const_iterator& begin,\n    const vector<inputfile_entry_t>::const_iterator& end)\n  {\n    uint16_t product_size = begin->product_size;\n    float max_gflops = 0.0f;\n    for (auto it = begin; it != end; ++it) {\n      if (it->product_size != product_size) {\n        cerr << \"Unexpected ordering of entries in \" << filename << endl;\n        cerr << \"(Expected all entries for product size \" << hex << product_size << dec << \" to be grouped)\" << endl;\n        exit(1);\n      }\n      max_gflops = max(max_gflops, it->gflops);\n    }\n    for (auto it = begin; it != end; ++it) {\n      preprocessed_inputfile_entry_t entry;\n      entry.product_size = it->product_size;\n      entry.block_size = it->pot_block_size;\n      entry.efficiency = it->gflops / max_gflops;\n      entries.push_back(entry);\n    }\n  }\n};\n\nvoid check_all_files_in_same_exact_order(\n       const vector<preprocessed_inputfile_t>& preprocessed_inputfiles)\n{\n  if (preprocessed_inputfiles.empty()) {\n    return;\n  }\n\n  const preprocessed_inputfile_t& first_file = preprocessed_inputfiles[0];\n  const size_t num_entries = first_file.entries.size();\n\n  for (size_t i = 0; i < preprocessed_inputfiles.size(); i++) {\n    if (preprocessed_inputfiles[i].entries.size() != num_entries) {\n      cerr << \"these files have different number of entries: \"\n           << preprocessed_inputfiles[i].filename\n           << \" and \"\n           << first_file.filename\n           << endl;\n      exit(1);\n    }\n  }\n\n  for (size_t entry_index = 0; entry_index < num_entries; entry_index++) {\n    const uint16_t entry_product_size = first_file.entries[entry_index].product_size;\n    const uint16_t entry_block_size = first_file.entries[entry_index].block_size;\n    for (size_t file_index = 0; file_index < preprocessed_inputfiles.size(); file_index++) {\n      const preprocessed_inputfile_t& cur_file = preprocessed_inputfiles[file_index];\n      if (cur_file.entries[entry_index].product_size != entry_product_size ||\n          cur_file.entries[entry_index].block_size != entry_block_size)\n      {\n        cerr << \"entries not in same order between these files: \"\n             << first_file.filename\n             << \" and \"\n             << cur_file.filename\n             << endl;\n        exit(1);\n      }\n    }\n  }\n}\n\nfloat efficiency_of_subset(\n        const vector<preprocessed_inputfile_t>& preprocessed_inputfiles,\n        const vector<size_t>& subset)\n{\n  if (subset.size() <= 1) {\n    return 1.0f;\n  }\n  const preprocessed_inputfile_t& first_file = preprocessed_inputfiles[subset[0]];\n  const size_t num_entries = first_file.entries.size();\n  float efficiency = 1.0f;\n  size_t entry_index = 0;\n  size_t first_entry_index_with_this_product_size = 0;\n  uint16_t product_size = first_file.entries[0].product_size;\n  while (entry_index < num_entries) {\n    ++entry_index;\n    if (entry_index == num_entries ||\n        first_file.entries[entry_index].product_size != product_size)\n    {\n      float efficiency_this_product_size = 0.0f;\n      for (size_t e = first_entry_index_with_this_product_size; e < entry_index; e++) {\n        float efficiency_this_entry = 1.0f;\n        for (auto i = subset.begin(); i != subset.end(); ++i) {\n          efficiency_this_entry = min(efficiency_this_entry, preprocessed_inputfiles[*i].entries[e].efficiency);\n        }\n        efficiency_this_product_size = max(efficiency_this_product_size, efficiency_this_entry);\n      }\n      efficiency = min(efficiency, efficiency_this_product_size);\n      if (entry_index < num_entries) {\n        first_entry_index_with_this_product_size = entry_index;\n        product_size = first_file.entries[entry_index].product_size;\n      }\n    }\n  }\n\n  return efficiency;\n}\n\nvoid dump_table_for_subset(\n        const vector<preprocessed_inputfile_t>& preprocessed_inputfiles,\n        const vector<size_t>& subset)\n{\n  const preprocessed_inputfile_t& first_file = preprocessed_inputfiles[subset[0]];\n  const size_t num_entries = first_file.entries.size();\n  size_t entry_index = 0;\n  size_t first_entry_index_with_this_product_size = 0;\n  uint16_t product_size = first_file.entries[0].product_size;\n  size_t i = 0;\n  size_triple_t min_product_size(first_file.entries.front().product_size);\n  size_triple_t max_product_size(first_file.entries.back().product_size);\n  if (!min_product_size.is_cubic() || !max_product_size.is_cubic()) {\n    abort();\n  }\n  if (only_cubic_sizes) {\n    cerr << \"Can't generate tables with --only-cubic-sizes.\" << endl;\n    abort();\n  }\n  cout << \"struct LookupTable {\" << endl;\n  cout << \"  static const size_t BaseSize = \" << min_product_size.k << \";\" << endl;\n  const size_t NumSizes = log2_pot(max_product_size.k / min_product_size.k) + 1;\n  const size_t TableSize = NumSizes * NumSizes * NumSizes;\n  cout << \"  static const size_t NumSizes = \" << NumSizes << \";\" << endl;\n  cout << \"  static const unsigned short* Data() {\" << endl;\n  cout << \"    static const unsigned short data[\" << TableSize << \"] = {\";\n  while (entry_index < num_entries) {\n    ++entry_index;\n    if (entry_index == num_entries ||\n        first_file.entries[entry_index].product_size != product_size)\n    {\n      float best_efficiency_this_product_size = 0.0f;\n      uint16_t best_block_size_this_product_size = 0;\n      for (size_t e = first_entry_index_with_this_product_size; e < entry_index; e++) {\n        float efficiency_this_entry = 1.0f;\n        for (auto i = subset.begin(); i != subset.end(); ++i) {\n          efficiency_this_entry = min(efficiency_this_entry, preprocessed_inputfiles[*i].entries[e].efficiency);\n        }\n        if (efficiency_this_entry > best_efficiency_this_product_size) {\n          best_efficiency_this_product_size = efficiency_this_entry;\n          best_block_size_this_product_size = first_file.entries[e].block_size;\n        }\n      }\n      if ((i++) % NumSizes) {\n        cout << \" \";\n      } else {\n        cout << endl << \"      \";\n      }\n      cout << \"0x\" << hex << best_block_size_this_product_size << dec;\n      if (entry_index < num_entries) {\n        cout << \",\";\n        first_entry_index_with_this_product_size = entry_index;\n        product_size = first_file.entries[entry_index].product_size;\n      }\n    }\n  }\n  if (i != TableSize) {\n    cerr << endl << \"Wrote \" << i << \" table entries, expected \" << TableSize << endl;\n    abort();\n  }\n  cout << endl << \"    };\" << endl;\n  cout << \"    return data;\" << endl;\n  cout << \"  }\" << endl;\n  cout << \"};\" << endl;\n}\n\nfloat efficiency_of_partition(\n        const vector<preprocessed_inputfile_t>& preprocessed_inputfiles,\n        const vector<vector<size_t>>& partition)\n{\n  float efficiency = 1.0f;\n  for (auto s = partition.begin(); s != partition.end(); ++s) {\n    efficiency = min(efficiency, efficiency_of_subset(preprocessed_inputfiles, *s));\n  }\n  return efficiency;\n}\n\nvoid make_first_subset(size_t subset_size, vector<size_t>& out_subset, size_t set_size)\n{\n  assert(subset_size >= 1 && subset_size <= set_size);\n  out_subset.resize(subset_size);\n  for (size_t i = 0; i < subset_size; i++) {\n    out_subset[i] = i;\n  }\n}\n\nbool is_last_subset(const vector<size_t>& subset, size_t set_size)\n{\n  return subset[0] == set_size - subset.size();\n}\n\nvoid next_subset(vector<size_t>& inout_subset, size_t set_size)\n{\n  if (is_last_subset(inout_subset, set_size)) {\n    cerr << \"iterating past the last subset\" << endl;\n    abort();\n  }\n  size_t i = 1;\n  while (inout_subset[inout_subset.size() - i] == set_size - i) {\n    i++;\n    assert(i <= inout_subset.size());\n  }\n  size_t first_index_to_change = inout_subset.size() - i;\n  inout_subset[first_index_to_change]++;\n  size_t p = inout_subset[first_index_to_change];\n  for (size_t j = first_index_to_change + 1; j < inout_subset.size(); j++) {\n    inout_subset[j] = ++p;\n  }\n}\n\nconst size_t number_of_subsets_limit = 100;\nconst size_t always_search_subsets_of_size_at_least = 2;\n\nbool is_number_of_subsets_feasible(size_t n, size_t p)\n{ \n  assert(n>0 && p>0 && p<=n);\n  uint64_t numerator = 1, denominator = 1;\n  for (size_t i = 0; i < p; i++) {\n    numerator *= n - i;\n    denominator *= i + 1;\n    if (numerator > denominator * number_of_subsets_limit) {\n      return false;\n    }\n  }\n  return true;\n}\n\nsize_t max_feasible_subset_size(size_t n)\n{\n  assert(n > 0);\n  const size_t minresult = min<size_t>(n-1, always_search_subsets_of_size_at_least);\n  for (size_t p = 1; p <= n - 1; p++) {\n    if (!is_number_of_subsets_feasible(n, p+1)) {\n      return max(p, minresult);\n    }\n  }\n  return n - 1;\n}\n\nvoid find_subset_with_efficiency_higher_than(\n       const vector<preprocessed_inputfile_t>& preprocessed_inputfiles,\n       float required_efficiency_to_beat,\n       vector<size_t>& inout_remainder,\n       vector<size_t>& out_subset)\n{\n  out_subset.resize(0);\n\n  if (required_efficiency_to_beat >= 1.0f) {\n    cerr << \"can't beat efficiency 1.\" << endl;\n    abort();\n  }\n\n  while (!inout_remainder.empty()) {\n\n    vector<size_t> candidate_indices(inout_remainder.size());\n    for (size_t i = 0; i < candidate_indices.size(); i++) {\n      candidate_indices[i] = i;\n    }\n\n    size_t candidate_indices_subset_size = max_feasible_subset_size(candidate_indices.size());\n    while (candidate_indices_subset_size >= 1) {\n      vector<size_t> candidate_indices_subset;\n      make_first_subset(candidate_indices_subset_size,\n                        candidate_indices_subset,\n                        candidate_indices.size());\n\n      vector<size_t> best_candidate_indices_subset;\n      float best_efficiency = 0.0f;\n      vector<size_t> trial_subset = out_subset;\n      trial_subset.resize(out_subset.size() + candidate_indices_subset_size);\n      while (true)\n      {\n        for (size_t i = 0; i < candidate_indices_subset_size; i++) {\n          trial_subset[out_subset.size() + i] = inout_remainder[candidate_indices_subset[i]];\n        }\n        \n        float trial_efficiency = efficiency_of_subset(preprocessed_inputfiles, trial_subset);\n        if (trial_efficiency > best_efficiency) {\n          best_efficiency = trial_efficiency;\n          best_candidate_indices_subset = candidate_indices_subset;\n        }\n        if (is_last_subset(candidate_indices_subset, candidate_indices.size())) {\n          break;\n        }\n        next_subset(candidate_indices_subset, candidate_indices.size());\n      }\n       \n      if (best_efficiency > required_efficiency_to_beat) {\n        for (size_t i = 0; i < best_candidate_indices_subset.size(); i++) {\n          candidate_indices[i] = candidate_indices[best_candidate_indices_subset[i]];\n        }\n        candidate_indices.resize(best_candidate_indices_subset.size());\n      }\n      candidate_indices_subset_size--;\n    }\n      \n    size_t candidate_index = candidate_indices[0];\n    auto candidate_iterator = inout_remainder.begin() + candidate_index;\n    vector<size_t> trial_subset = out_subset;\n\n    trial_subset.push_back(*candidate_iterator);\n    float trial_efficiency = efficiency_of_subset(preprocessed_inputfiles, trial_subset);\n    if (trial_efficiency > required_efficiency_to_beat) {\n      out_subset.push_back(*candidate_iterator);\n      inout_remainder.erase(candidate_iterator);\n    } else {\n      break;\n    }\n  }\n}\n\nvoid find_partition_with_efficiency_higher_than(\n       const vector<preprocessed_inputfile_t>& preprocessed_inputfiles,\n       float required_efficiency_to_beat,\n       vector<vector<size_t>>& out_partition)\n{\n  out_partition.resize(0);\n\n  vector<size_t> remainder;\n  for (size_t i = 0; i < preprocessed_inputfiles.size(); i++) {\n    remainder.push_back(i);\n  }\n\n  while (!remainder.empty()) {\n    vector<size_t> new_subset;\n    find_subset_with_efficiency_higher_than(\n      preprocessed_inputfiles,\n      required_efficiency_to_beat,\n      remainder,\n      new_subset);\n    out_partition.push_back(new_subset);\n  }\n}\n\nvoid print_partition(\n       const vector<preprocessed_inputfile_t>& preprocessed_inputfiles,\n       const vector<vector<size_t>>& partition)\n{\n  float efficiency = efficiency_of_partition(preprocessed_inputfiles, partition);\n  cout << \"Partition into \" << partition.size() << \" subsets for \" << efficiency * 100.0f << \"% efficiency\"  << endl;\n  for (auto subset = partition.begin(); subset != partition.end(); ++subset) {\n    cout << \"  Subset \" << (subset - partition.begin())\n         << \", efficiency \" << efficiency_of_subset(preprocessed_inputfiles, *subset) * 100.0f << \"%:\"\n         << endl;\n    for (auto file = subset->begin(); file != subset->end(); ++file) {\n      cout << \"    \" << preprocessed_inputfiles[*file].filename << endl;\n    }\n    if (dump_tables) {\n      cout << \"  Table:\" << endl;\n      dump_table_for_subset(preprocessed_inputfiles, *subset);\n    }\n  }\n  cout << endl;\n}\n\nstruct action_t\n{\n  virtual const char* invokation_name() const { abort(); return nullptr; }\n  virtual void run(const vector<string>&) const { abort(); }\n  virtual ~action_t() {}\n};\n\nstruct partition_action_t : action_t\n{\n  virtual const char* invokation_name() const override { return \"partition\"; }\n  virtual void run(const vector<string>& input_filenames) const override\n  {\n    vector<preprocessed_inputfile_t> preprocessed_inputfiles;\n\n    if (input_filenames.empty()) {\n      cerr << \"The \" << invokation_name() << \" action needs a list of input files.\" << endl;\n      exit(1);\n    }\n\n    for (auto it = input_filenames.begin(); it != input_filenames.end(); ++it) {\n      inputfile_t inputfile(*it);\n      switch (inputfile.type) {\n        case inputfile_t::type_t::all_pot_sizes:\n          preprocessed_inputfiles.emplace_back(inputfile);\n          break;\n        case inputfile_t::type_t::default_sizes:\n          cerr << \"The \" << invokation_name() << \" action only uses measurements for all pot sizes, and \"\n               << \"has no use for \" << *it << \" which contains measurements for default sizes.\" << endl;\n          exit(1);\n          break;\n        default:\n          cerr << \"Unrecognized input file: \" << *it << endl;\n          exit(1);\n      }\n    }\n\n    check_all_files_in_same_exact_order(preprocessed_inputfiles);\n\n    float required_efficiency_to_beat = 0.0f;\n    vector<vector<vector<size_t>>> partitions;\n    cerr << \"searching for partitions...\\r\" << flush;\n    while (true)\n    {\n      vector<vector<size_t>> partition;\n      find_partition_with_efficiency_higher_than(\n        preprocessed_inputfiles,\n        required_efficiency_to_beat,\n        partition);\n      float actual_efficiency = efficiency_of_partition(preprocessed_inputfiles, partition);\n      cerr << \"partition \" << preprocessed_inputfiles.size() << \" files into \" << partition.size()\n           << \" subsets for \" << 100.0f * actual_efficiency\n           << \" % efficiency\"\n           << \"                  \\r\" << flush;\n      partitions.push_back(partition);\n      if (partition.size() == preprocessed_inputfiles.size() || actual_efficiency == 1.0f) {\n        break;\n      }\n      required_efficiency_to_beat = actual_efficiency;\n    }\n    cerr << \"                                                                  \" << endl;\n    while (true) {\n      bool repeat = false;\n      for (size_t i = 0; i < partitions.size() - 1; i++) {\n        if (partitions[i].size() >= partitions[i+1].size()) {\n          partitions.erase(partitions.begin() + i);\n          repeat = true;\n          break;\n        }\n      }\n      if (!repeat) {\n        break;\n      }\n    }\n    for (auto it = partitions.begin(); it != partitions.end(); ++it) {\n      print_partition(preprocessed_inputfiles, *it);\n    }\n  }\n};\n\nstruct evaluate_defaults_action_t : action_t\n{\n  struct results_entry_t {\n    uint16_t product_size;\n    size_triple_t default_block_size;\n    uint16_t best_pot_block_size;\n    float default_gflops;\n    float best_pot_gflops;\n    float default_efficiency;\n  };\n  friend ostream& operator<<(ostream& s, const results_entry_t& entry)\n  {\n    return s\n      << \"Product size \" << size_triple_t(entry.product_size)\n      << \": default block size \" << entry.default_block_size\n      << \" -> \" << entry.default_gflops\n      << \" GFlop/s = \" << entry.default_efficiency * 100.0f << \" %\"\n      << \" of best POT block size \" << size_triple_t(entry.best_pot_block_size)\n      << \" -> \" << entry.best_pot_gflops\n      << \" GFlop/s\" << dec;\n  }\n  static bool lower_efficiency(const results_entry_t& e1, const results_entry_t& e2) {\n    return e1.default_efficiency < e2.default_efficiency;\n  }\n  virtual const char* invokation_name() const override { return \"evaluate-defaults\"; }\n  void show_usage_and_exit() const\n  {\n    cerr << \"usage: \" << invokation_name() << \" default-sizes-data all-pot-sizes-data\" << endl;\n    cerr << \"checks how well the performance with default sizes compares to the best \"\n         << \"performance measured over all POT sizes.\" << endl;\n    exit(1);\n  }\n  virtual void run(const vector<string>& input_filenames) const override\n  {\n    if (input_filenames.size() != 2) {\n      show_usage_and_exit();\n    }\n    inputfile_t inputfile_default_sizes(input_filenames[0]);\n    inputfile_t inputfile_all_pot_sizes(input_filenames[1]);\n    if (inputfile_default_sizes.type != inputfile_t::type_t::default_sizes) {\n      cerr << inputfile_default_sizes.filename << \" is not an input file with default sizes.\" << endl;\n      show_usage_and_exit();\n    }\n    if (inputfile_all_pot_sizes.type != inputfile_t::type_t::all_pot_sizes) {\n      cerr << inputfile_all_pot_sizes.filename << \" is not an input file with all POT sizes.\" << endl;\n      show_usage_and_exit();\n    }\n    vector<results_entry_t> results;\n    vector<results_entry_t> cubic_results;\n    \n    uint16_t product_size = 0;\n    auto it_all_pot_sizes = inputfile_all_pot_sizes.entries.begin();\n    for (auto it_default_sizes = inputfile_default_sizes.entries.begin();\n         it_default_sizes != inputfile_default_sizes.entries.end();\n         ++it_default_sizes)\n    {\n      if (it_default_sizes->product_size == product_size) {\n        continue;\n      }\n      product_size = it_default_sizes->product_size;\n      while (it_all_pot_sizes != inputfile_all_pot_sizes.entries.end() &&\n             it_all_pot_sizes->product_size != product_size)\n      {\n        ++it_all_pot_sizes;\n      }\n      if (it_all_pot_sizes == inputfile_all_pot_sizes.entries.end()) {\n        break;\n      }\n      uint16_t best_pot_block_size = 0;\n      float best_pot_gflops = 0;\n      for (auto it = it_all_pot_sizes;\n           it != inputfile_all_pot_sizes.entries.end() && it->product_size == product_size;\n           ++it)\n      {\n        if (it->gflops > best_pot_gflops) {\n          best_pot_gflops = it->gflops;\n          best_pot_block_size = it->pot_block_size;\n        }\n      }\n      results_entry_t entry;\n      entry.product_size = product_size;\n      entry.default_block_size = it_default_sizes->nonpot_block_size;\n      entry.best_pot_block_size = best_pot_block_size;\n      entry.default_gflops = it_default_sizes->gflops;\n      entry.best_pot_gflops = best_pot_gflops;\n      entry.default_efficiency = entry.default_gflops / entry.best_pot_gflops;\n      results.push_back(entry);\n\n      size_triple_t t(product_size);\n      if (t.k == t.m && t.m == t.n) {\n        cubic_results.push_back(entry);\n      }\n    }\n\n    cout << \"All results:\" << endl;\n    for (auto it = results.begin(); it != results.end(); ++it) {\n      cout << *it << endl;\n    }\n    cout << endl;\n\n    sort(results.begin(), results.end(), lower_efficiency);\n    \n    const size_t n = min<size_t>(20, results.size());\n    cout << n << \" worst results:\" << endl;\n    for (size_t i = 0; i < n; i++) {\n      cout << results[i] << endl;\n    }\n    cout << endl;\n\n    cout << \"cubic results:\" << endl;\n    for (auto it = cubic_results.begin(); it != cubic_results.end(); ++it) {\n      cout << *it << endl;\n    }\n    cout << endl;\n\n    sort(cubic_results.begin(), cubic_results.end(), lower_efficiency);\n    \n    cout.precision(2);\n    vector<float> a = {0.5f, 0.20f, 0.10f, 0.05f, 0.02f, 0.01f};\n    for (auto it = a.begin(); it != a.end(); ++it) {\n      size_t n = min(results.size() - 1, size_t(*it * results.size()));\n      cout << (100.0f * n / (results.size() - 1))\n           << \" % of product sizes have default efficiency <= \"\n           << 100.0f * results[n].default_efficiency << \" %\" << endl;\n    }\n    cout.precision(default_precision);\n  }\n};\n\n\nvoid show_usage_and_exit(int argc, char* argv[],\n                         const vector<unique_ptr<action_t>>& available_actions)\n{\n  cerr << \"usage: \" << argv[0] << \" <action> [options...] <input files...>\" << endl;\n  cerr << \"available actions:\" << endl;\n  for (auto it = available_actions.begin(); it != available_actions.end(); ++it) {\n    cerr << \"  \" << (*it)->invokation_name() << endl;\n  } \n  cerr << \"the input files should each contain an output of benchmark-blocking-sizes\" << endl;\n  exit(1);\n}\n\nint main(int argc, char* argv[])\n{\n  cout.precision(default_precision);\n  cerr.precision(default_precision);\n\n  vector<unique_ptr<action_t>> available_actions;\n  available_actions.emplace_back(new partition_action_t);\n  available_actions.emplace_back(new evaluate_defaults_action_t);\n\n  vector<string> input_filenames;\n\n  action_t* action = nullptr;\n\n  if (argc < 2) {\n    show_usage_and_exit(argc, argv, available_actions);\n  }\n  for (int i = 1; i < argc; i++) {\n    bool arg_handled = false;\n    // Step 1. Try to match action invocation names.\n    for (auto it = available_actions.begin(); it != available_actions.end(); ++it) {\n      if (!strcmp(argv[i], (*it)->invokation_name())) {\n        if (!action) {\n          action = it->get();\n          arg_handled = true;\n          break;\n        } else {\n          cerr << \"can't specify more than one action!\" << endl;\n          show_usage_and_exit(argc, argv, available_actions);\n        }\n      }\n    }\n    if (arg_handled) {\n      continue;\n    }\n    // Step 2. Try to match option names.\n    if (argv[i][0] == '-') {\n      if (!strcmp(argv[i], \"--only-cubic-sizes\")) {\n        only_cubic_sizes = true;\n        arg_handled = true;\n      }\n      if (!strcmp(argv[i], \"--dump-tables\")) {\n        dump_tables = true;\n        arg_handled = true;\n      }\n      if (!arg_handled) {\n        cerr << \"Unrecognized option: \" << argv[i] << endl;\n        show_usage_and_exit(argc, argv, available_actions);\n      }\n    }\n    if (arg_handled) {\n      continue;\n    }\n    // Step 3. Default to interpreting args as input filenames.\n    input_filenames.emplace_back(argv[i]);\n  }\n\n  if (dump_tables && only_cubic_sizes) {\n    cerr << \"Incompatible options: --only-cubic-sizes and --dump-tables.\" << endl;\n    show_usage_and_exit(argc, argv, available_actions);\n  }\n\n  if (!action) {\n    show_usage_and_exit(argc, argv, available_actions);\n  }\n\n  action->run(input_filenames);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/basicbench.cxxlist",
    "content": "#!/bin/bash\n\n# CLIST[((g++))]=\"g++-3.4 -O3 -DNDEBUG\"\n# CLIST[((g++))]=\"g++-3.4 -O3 -DNDEBUG -finline-limit=20000\"\n\n# CLIST[((g++))]=\"g++-4.1 -O3 -DNDEBUG\"\n#CLIST[((g++))]=\"g++-4.1 -O3 -DNDEBUG -finline-limit=20000\"\n\n# CLIST[((g++))]=\"g++-4.2 -O3 -DNDEBUG\"\n#CLIST[((g++))]=\"g++-4.2 -O3 -DNDEBUG -finline-limit=20000\"\n# CLIST[((g++))]=\"g++-4.2 -O3 -DNDEBUG -finline-limit=20000 -fprofile-generate\"\n# CLIST[((g++))]=\"g++-4.2 -O3 -DNDEBUG -finline-limit=20000 -fprofile-use\"\n\n# CLIST[((g++))]=\"g++-4.3 -O3 -DNDEBUG\"\n#CLIST[((g++))]=\"g++-4.3 -O3 -DNDEBUG -finline-limit=20000\"\n# CLIST[((g++))]=\"g++-4.3 -O3 -DNDEBUG -finline-limit=20000 -fprofile-generate\"\n# CLIST[((g++))]=\"g++-4.3 -O3 -DNDEBUG -finline-limit=20000 -fprofile-use\"\n\n# CLIST[((g++))]=\"icpc -fast -DNDEBUG -fno-exceptions -no-inline-max-size -prof-genx\"\n# CLIST[((g++))]=\"icpc -fast -DNDEBUG -fno-exceptions -no-inline-max-size -prof-use\"\n\n#CLIST[((g++))]=\"/opt/intel/Compiler/11.1/072/bin/intel64/icpc -fast -DNDEBUG -fno-exceptions -no-inline-max-size -lrt\"\nCLIST[((g++))]=\"/home/orzel/svn/llvm/Release/bin/clang++ -O3 -DNDEBUG -DEIGEN_DONT_VECTORIZE -lrt\"\nCLIST[((g++))]=\"/home/orzel/svn/llvm/Release/bin/clang++ -O3 -DNDEBUG -lrt\"\nCLIST[((g++))]=\"g++-4.4.4 -O3 -DNDEBUG -DEIGEN_DONT_VECTORIZE -lrt\"\nCLIST[((g++))]=\"g++-4.4.4 -O3 -DNDEBUG -lrt\"\nCLIST[((g++))]=\"g++-4.5.0 -O3 -DNDEBUG -DEIGEN_DONT_VECTORIZE -lrt\"\nCLIST[((g++))]=\"g++-4.5.0 -O3 -DNDEBUG -lrt\"\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/basicbenchmark.cpp",
    "content": "\n#include <iostream>\n#include \"BenchUtil.h\"\n#include \"basicbenchmark.h\"\n\nint main(int argc, char *argv[])\n{\n  DISABLE_SSE_EXCEPTIONS();\n\n  // this is the list of matrix type and size we want to bench:\n  // ((suffix) (matrix size) (number of iterations))\n  #define MODES ((3d)(3)(4000000)) ((4d)(4)(1000000)) ((Xd)(4)(1000000)) ((Xd)(20)(10000))\n//   #define MODES ((Xd)(20)(10000))\n\n  #define _GENERATE_HEADER(R,ARG,EL) << BOOST_PP_STRINGIZE(BOOST_PP_SEQ_HEAD(EL)) << \"-\" \\\n    << BOOST_PP_STRINGIZE(BOOST_PP_SEQ_ELEM(1,EL)) << \"x\" \\\n    << BOOST_PP_STRINGIZE(BOOST_PP_SEQ_ELEM(1,EL)) << \"   /   \"\n\n  std::cout BOOST_PP_SEQ_FOR_EACH(_GENERATE_HEADER, ~, MODES ) << endl;\n\n  const int tries = 10;\n\n  #define _RUN_BENCH(R,ARG,EL) \\\n    std::cout << ARG( \\\n      BOOST_PP_CAT(Matrix, BOOST_PP_SEQ_HEAD(EL)) (\\\n         BOOST_PP_SEQ_ELEM(1,EL),BOOST_PP_SEQ_ELEM(1,EL)), BOOST_PP_SEQ_ELEM(2,EL), tries) \\\n    << \"   \";\n\n  BOOST_PP_SEQ_FOR_EACH(_RUN_BENCH, benchBasic<LazyEval>, MODES );\n  std::cout << endl;\n  BOOST_PP_SEQ_FOR_EACH(_RUN_BENCH, benchBasic<EarlyEval>, MODES );\n  std::cout << endl;\n\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/basicbenchmark.h",
    "content": "\n#ifndef EIGEN_BENCH_BASICBENCH_H\n#define EIGEN_BENCH_BASICBENCH_H\n\nenum {LazyEval, EarlyEval, OmpEval};\n\ntemplate<int Mode, typename MatrixType>\nvoid benchBasic_loop(const MatrixType& I, MatrixType& m, int iterations) __attribute__((noinline));\n\ntemplate<int Mode, typename MatrixType>\nvoid benchBasic_loop(const MatrixType& I, MatrixType& m, int iterations)\n{\n  for(int a = 0; a < iterations; a++)\n  {\n    if (Mode==LazyEval)\n    {\n      asm(\"#begin_bench_loop LazyEval\");\n      if (MatrixType::SizeAtCompileTime!=Eigen::Dynamic) asm(\"#fixedsize\");\n      m = (I + 0.00005 * (m + m.lazy() * m)).eval();\n    }\n    else if (Mode==OmpEval)\n    {\n      asm(\"#begin_bench_loop OmpEval\");\n      if (MatrixType::SizeAtCompileTime!=Eigen::Dynamic) asm(\"#fixedsize\");\n      m = (I + 0.00005 * (m + m.lazy() * m)).evalOMP();\n    }\n    else\n    {\n      asm(\"#begin_bench_loop EarlyEval\");\n      if (MatrixType::SizeAtCompileTime!=Eigen::Dynamic) asm(\"#fixedsize\");\n      m = I + 0.00005 * (m + m * m);\n    }\n    asm(\"#end_bench_loop\");\n  }\n}\n\ntemplate<int Mode, typename MatrixType>\ndouble benchBasic(const MatrixType& mat, int size, int tries) __attribute__((noinline));\n\ntemplate<int Mode, typename MatrixType>\ndouble benchBasic(const MatrixType& mat, int iterations, int tries)\n{\n  const int rows = mat.rows();\n  const int cols = mat.cols();\n\n  MatrixType I(rows,cols);\n  MatrixType m(rows,cols);\n\n  initMatrix_identity(I);\n\n  Eigen::BenchTimer timer;\n  for(uint t=0; t<tries; ++t)\n  {\n    initMatrix_random(m);\n    timer.start();\n    benchBasic_loop<Mode>(I, m, iterations);\n    timer.stop();\n    cerr << m;\n  }\n  return timer.value();\n};\n\n#endif // EIGEN_BENCH_BASICBENCH_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/benchBlasGemm.cpp",
    "content": "// g++ -O3 -DNDEBUG -I.. -L /usr/lib64/atlas/ benchBlasGemm.cpp -o benchBlasGemm -lrt -lcblas\n// possible options:\n//    -DEIGEN_DONT_VECTORIZE\n//    -msse2\n\n// #define EIGEN_DEFAULT_TO_ROW_MAJOR\n#define _FLOAT\n\n#include <iostream>\n\n#include <Eigen/Core>\n#include \"BenchTimer.h\"\n\n// include the BLAS headers\nextern \"C\" {\n#include <cblas.h>\n}\n#include <string>\n\n#ifdef _FLOAT\ntypedef float Scalar;\n#define CBLAS_GEMM cblas_sgemm\n#else\ntypedef double Scalar;\n#define CBLAS_GEMM cblas_dgemm\n#endif\n\n\ntypedef Eigen::Matrix<Scalar,Eigen::Dynamic,Eigen::Dynamic> MyMatrix;\nvoid bench_eigengemm(MyMatrix& mc, const MyMatrix& ma, const MyMatrix& mb, int nbloops);\nvoid check_product(int M, int N, int K);\nvoid check_product(void);\n\nint main(int argc, char *argv[])\n{\n  // disable SSE exceptions\n  #ifdef __GNUC__\n  {\n    int aux;\n    asm(\n    \"stmxcsr   %[aux]           \\n\\t\"\n    \"orl       $32832, %[aux]   \\n\\t\"\n    \"ldmxcsr   %[aux]           \\n\\t\"\n    : : [aux] \"m\" (aux));\n  }\n  #endif\n\n  int nbtries=1, nbloops=1, M, N, K;\n\n  if (argc==2)\n  {\n    if (std::string(argv[1])==\"check\")\n      check_product();\n    else\n      M = N = K = atoi(argv[1]);\n  }\n  else if ((argc==3) && (std::string(argv[1])==\"auto\"))\n  {\n    M = N = K = atoi(argv[2]);\n    nbloops = 1000000000/(M*M*M);\n    if (nbloops<1)\n      nbloops = 1;\n    nbtries = 6;\n  }\n  else if (argc==4)\n  {\n    M = N = K = atoi(argv[1]);\n    nbloops = atoi(argv[2]);\n    nbtries = atoi(argv[3]);\n  }\n  else if (argc==6)\n  {\n    M = atoi(argv[1]);\n    N = atoi(argv[2]);\n    K = atoi(argv[3]);\n    nbloops = atoi(argv[4]);\n    nbtries = atoi(argv[5]);\n  }\n  else\n  {\n    std::cout << \"Usage: \" << argv[0] << \" size  \\n\";\n    std::cout << \"Usage: \" << argv[0] << \" auto size\\n\";\n    std::cout << \"Usage: \" << argv[0] << \" size nbloops nbtries\\n\";\n    std::cout << \"Usage: \" << argv[0] << \" M N K nbloops nbtries\\n\";\n    std::cout << \"Usage: \" << argv[0] << \" check\\n\";\n    std::cout << \"Options:\\n\";\n    std::cout << \"    size       unique size of the 2 matrices (integer)\\n\";\n    std::cout << \"    auto       automatically set the number of repetitions and tries\\n\";\n    std::cout << \"    nbloops    number of times the GEMM routines is executed\\n\";\n    std::cout << \"    nbtries    number of times the loop is benched (return the best try)\\n\";\n    std::cout << \"    M N K      sizes of the matrices: MxN  =  MxK * KxN (integers)\\n\";\n    std::cout << \"    check      check eigen product using cblas as a reference\\n\";\n    exit(1);\n  }\n\n  double nbmad = double(M) * double(N) * double(K) * double(nbloops);\n\n  if (!(std::string(argv[1])==\"auto\"))\n    std::cout << M << \" x \" << N << \" x \" << K << \"\\n\";\n\n  Scalar alpha, beta;\n  MyMatrix ma(M,K), mb(K,N), mc(M,N);\n  ma = MyMatrix::Random(M,K);\n  mb = MyMatrix::Random(K,N);\n  mc = MyMatrix::Random(M,N);\n\n  Eigen::BenchTimer timer;\n\n  // we simply compute c += a*b, so:\n  alpha = 1;\n  beta = 1;\n\n  // bench cblas\n  // ROWS_A, COLS_B, COLS_A, 1.0,  A, COLS_A, B, COLS_B, 0.0, C, COLS_B);\n  if (!(std::string(argv[1])==\"auto\"))\n  {\n    timer.reset();\n    for (uint k=0 ; k<nbtries ; ++k)\n    {\n        timer.start();\n        for (uint j=0 ; j<nbloops ; ++j)\n              #ifdef EIGEN_DEFAULT_TO_ROW_MAJOR\n              CBLAS_GEMM(CblasRowMajor, CblasNoTrans, CblasNoTrans, M, N, K, alpha, ma.data(), K, mb.data(), N, beta, mc.data(), N);\n              #else\n              CBLAS_GEMM(CblasColMajor, CblasNoTrans, CblasNoTrans, M, N, K, alpha, ma.data(), M, mb.data(), K, beta, mc.data(), M);\n              #endif\n        timer.stop();\n    }\n    if (!(std::string(argv[1])==\"auto\"))\n      std::cout << \"cblas: \" << timer.value() << \" (\" << 1e-3*floor(1e-6*nbmad/timer.value()) << \" GFlops/s)\\n\";\n    else\n        std::cout << M << \" : \" << timer.value() << \" ; \" << 1e-3*floor(1e-6*nbmad/timer.value()) << \"\\n\";\n  }\n\n  // clear\n  ma = MyMatrix::Random(M,K);\n  mb = MyMatrix::Random(K,N);\n  mc = MyMatrix::Random(M,N);\n\n  // eigen\n//   if (!(std::string(argv[1])==\"auto\"))\n  {\n      timer.reset();\n      for (uint k=0 ; k<nbtries ; ++k)\n      {\n          timer.start();\n          bench_eigengemm(mc, ma, mb, nbloops);\n          timer.stop();\n      }\n      if (!(std::string(argv[1])==\"auto\"))\n        std::cout << \"eigen : \" << timer.value() << \" (\" << 1e-3*floor(1e-6*nbmad/timer.value()) << \" GFlops/s)\\n\";\n      else\n        std::cout << M << \" : \" << timer.value() << \" ; \" << 1e-3*floor(1e-6*nbmad/timer.value()) << \"\\n\";\n  }\n\n  std::cout << \"l1: \" << Eigen::l1CacheSize() << std::endl;\n  std::cout << \"l2: \" << Eigen::l2CacheSize() << std::endl;\n  \n\n  return 0;\n}\n\nusing namespace Eigen;\n\nvoid bench_eigengemm(MyMatrix& mc, const MyMatrix& ma, const MyMatrix& mb, int nbloops)\n{\n  for (uint j=0 ; j<nbloops ; ++j)\n      mc.noalias() += ma * mb;\n}\n\n#define MYVERIFY(A,M) if (!(A)) { \\\n    std::cout << \"FAIL: \" << M << \"\\n\"; \\\n  }\nvoid check_product(int M, int N, int K)\n{\n  MyMatrix ma(M,K), mb(K,N), mc(M,N), maT(K,M), mbT(N,K), meigen(M,N), mref(M,N);\n  ma = MyMatrix::Random(M,K);\n  mb = MyMatrix::Random(K,N);\n  maT = ma.transpose();\n  mbT = mb.transpose();\n  mc = MyMatrix::Random(M,N);\n\n  MyMatrix::Scalar eps = 1e-4;\n\n  meigen = mref = mc;\n  CBLAS_GEMM(CblasColMajor, CblasNoTrans, CblasNoTrans, M, N, K, 1, ma.data(), M, mb.data(), K, 1, mref.data(), M);\n  meigen += ma * mb;\n  MYVERIFY(meigen.isApprox(mref, eps),\". * .\");\n\n  meigen = mref = mc;\n  CBLAS_GEMM(CblasColMajor, CblasTrans, CblasNoTrans, M, N, K, 1, maT.data(), K, mb.data(), K, 1, mref.data(), M);\n  meigen += maT.transpose() * mb;\n  MYVERIFY(meigen.isApprox(mref, eps),\"T * .\");\n\n  meigen = mref = mc;\n  CBLAS_GEMM(CblasColMajor, CblasTrans, CblasTrans, M, N, K, 1, maT.data(), K, mbT.data(), N, 1, mref.data(), M);\n  meigen += (maT.transpose()) * (mbT.transpose());\n  MYVERIFY(meigen.isApprox(mref, eps),\"T * T\");\n\n  meigen = mref = mc;\n  CBLAS_GEMM(CblasColMajor, CblasNoTrans, CblasTrans, M, N, K, 1, ma.data(), M, mbT.data(), N, 1, mref.data(), M);\n  meigen += ma * mbT.transpose();\n  MYVERIFY(meigen.isApprox(mref, eps),\". * T\");\n}\n\nvoid check_product(void)\n{\n  int M, N, K;\n  for (uint i=0; i<1000; ++i)\n  {\n    M = internal::random<int>(1,64);\n    N = internal::random<int>(1,768);\n    K = internal::random<int>(1,768);\n    M = (0 + M) * 1;\n    std::cout << M << \" x \" << N << \" x \" << K << \"\\n\";\n    check_product(M, N, K);\n  }\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/benchCholesky.cpp",
    "content": "// g++ -DNDEBUG -O3 -I.. benchCholesky.cpp  -o benchCholesky && ./benchCholesky\n// options:\n//  -DBENCH_GSL -lgsl /usr/lib/libcblas.so.3\n//  -DEIGEN_DONT_VECTORIZE\n//  -msse2\n//  -DREPEAT=100\n//  -DTRIES=10\n//  -DSCALAR=double\n\n#include <iostream>\n\n#include <Eigen/Core>\n#include <Eigen/Cholesky>\n#include <bench/BenchUtil.h>\nusing namespace Eigen;\n\n#ifndef REPEAT\n#define REPEAT 10000\n#endif\n\n#ifndef TRIES\n#define TRIES 10\n#endif\n\ntypedef float Scalar;\n\ntemplate <typename MatrixType>\n__attribute__ ((noinline)) void benchLLT(const MatrixType& m)\n{\n  int rows = m.rows();\n  int cols = m.cols();\n\n  double cost = 0;\n  for (int j=0; j<rows; ++j)\n  {\n    int r = std::max(rows - j -1,0);\n    cost += 2*(r*j+r+j);\n  }\n\n  int repeats = (REPEAT*1000)/(rows*rows);\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> SquareMatrixType;\n\n  MatrixType a = MatrixType::Random(rows,cols);\n  SquareMatrixType covMat =  a * a.adjoint();\n\n  BenchTimer timerNoSqrt, timerSqrt;\n\n  Scalar acc = 0;\n  int r = internal::random<int>(0,covMat.rows()-1);\n  int c = internal::random<int>(0,covMat.cols()-1);\n  for (int t=0; t<TRIES; ++t)\n  {\n    timerNoSqrt.start();\n    for (int k=0; k<repeats; ++k)\n    {\n      LDLT<SquareMatrixType> cholnosqrt(covMat);\n      acc += cholnosqrt.matrixL().coeff(r,c);\n    }\n    timerNoSqrt.stop();\n  }\n\n  for (int t=0; t<TRIES; ++t)\n  {\n    timerSqrt.start();\n    for (int k=0; k<repeats; ++k)\n    {\n      LLT<SquareMatrixType> chol(covMat);\n      acc += chol.matrixL().coeff(r,c);\n    }\n    timerSqrt.stop();\n  }\n\n  if (MatrixType::RowsAtCompileTime==Dynamic)\n    std::cout << \"dyn   \";\n  else\n    std::cout << \"fixed \";\n  std::cout << covMat.rows() << \" \\t\"\n            << (timerNoSqrt.best()) / repeats << \"s \"\n            << \"(\" << 1e-9 * cost*repeats/timerNoSqrt.best() << \" GFLOPS)\\t\"\n            << (timerSqrt.best()) / repeats << \"s \"\n            << \"(\" << 1e-9 * cost*repeats/timerSqrt.best() << \" GFLOPS)\\n\";\n\n\n  #ifdef BENCH_GSL\n  if (MatrixType::RowsAtCompileTime==Dynamic)\n  {\n    timerSqrt.reset();\n\n    gsl_matrix* gslCovMat = gsl_matrix_alloc(covMat.rows(),covMat.cols());\n    gsl_matrix* gslCopy = gsl_matrix_alloc(covMat.rows(),covMat.cols());\n\n    eiToGsl(covMat, &gslCovMat);\n    for (int t=0; t<TRIES; ++t)\n    {\n      timerSqrt.start();\n      for (int k=0; k<repeats; ++k)\n      {\n        gsl_matrix_memcpy(gslCopy,gslCovMat);\n        gsl_linalg_cholesky_decomp(gslCopy);\n        acc += gsl_matrix_get(gslCopy,r,c);\n      }\n      timerSqrt.stop();\n    }\n\n    std::cout << \" | \\t\"\n              << timerSqrt.value() * REPEAT / repeats << \"s\";\n\n    gsl_matrix_free(gslCovMat);\n  }\n  #endif\n  std::cout << \"\\n\";\n  // make sure the compiler does not optimize too much\n  if (acc==123)\n    std::cout << acc;\n}\n\nint main(int argc, char* argv[])\n{\n  const int dynsizes[] = {4,6,8,16,24,32,49,64,128,256,512,900,1500,0};\n  std::cout << \"size            LDLT                            LLT\";\n//   #ifdef BENCH_GSL\n//   std::cout << \"       GSL (standard + double + ATLAS)  \";\n//   #endif\n  std::cout << \"\\n\";\n  for (int i=0; dynsizes[i]>0; ++i)\n    benchLLT(Matrix<Scalar,Dynamic,Dynamic>(dynsizes[i],dynsizes[i]));\n\n  benchLLT(Matrix<Scalar,2,2>());\n  benchLLT(Matrix<Scalar,3,3>());\n  benchLLT(Matrix<Scalar,4,4>());\n  benchLLT(Matrix<Scalar,5,5>());\n  benchLLT(Matrix<Scalar,6,6>());\n  benchLLT(Matrix<Scalar,7,7>());\n  benchLLT(Matrix<Scalar,8,8>());\n  benchLLT(Matrix<Scalar,12,12>());\n  benchLLT(Matrix<Scalar,16,16>());\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/benchEigenSolver.cpp",
    "content": "\n// g++ -DNDEBUG -O3 -I.. benchEigenSolver.cpp  -o benchEigenSolver && ./benchEigenSolver\n// options:\n//  -DBENCH_GMM\n//  -DBENCH_GSL -lgsl /usr/lib/libcblas.so.3\n//  -DEIGEN_DONT_VECTORIZE\n//  -msse2\n//  -DREPEAT=100\n//  -DTRIES=10\n//  -DSCALAR=double\n\n#include <iostream>\n\n#include <Eigen/Core>\n#include <Eigen/QR>\n#include <bench/BenchUtil.h>\nusing namespace Eigen;\n\n#ifndef REPEAT\n#define REPEAT 1000\n#endif\n\n#ifndef TRIES\n#define TRIES 4\n#endif\n\n#ifndef SCALAR\n#define SCALAR float\n#endif\n\ntypedef SCALAR Scalar;\n\ntemplate <typename MatrixType>\n__attribute__ ((noinline)) void benchEigenSolver(const MatrixType& m)\n{\n  int rows = m.rows();\n  int cols = m.cols();\n\n  int stdRepeats = std::max(1,int((REPEAT*1000)/(rows*rows*sqrt(rows))));\n  int saRepeats = stdRepeats * 4;\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> SquareMatrixType;\n\n  MatrixType a = MatrixType::Random(rows,cols);\n  SquareMatrixType covMat =  a * a.adjoint();\n\n  BenchTimer timerSa, timerStd;\n\n  Scalar acc = 0;\n  int r = internal::random<int>(0,covMat.rows()-1);\n  int c = internal::random<int>(0,covMat.cols()-1);\n  {\n    SelfAdjointEigenSolver<SquareMatrixType> ei(covMat);\n    for (int t=0; t<TRIES; ++t)\n    {\n      timerSa.start();\n      for (int k=0; k<saRepeats; ++k)\n      {\n        ei.compute(covMat);\n        acc += ei.eigenvectors().coeff(r,c);\n      }\n      timerSa.stop();\n    }\n  }\n\n  {\n    EigenSolver<SquareMatrixType> ei(covMat);\n    for (int t=0; t<TRIES; ++t)\n    {\n      timerStd.start();\n      for (int k=0; k<stdRepeats; ++k)\n      {\n        ei.compute(covMat);\n        acc += ei.eigenvectors().coeff(r,c);\n      }\n      timerStd.stop();\n    }\n  }\n\n  if (MatrixType::RowsAtCompileTime==Dynamic)\n    std::cout << \"dyn   \";\n  else\n    std::cout << \"fixed \";\n  std::cout << covMat.rows() << \" \\t\"\n            << timerSa.value() * REPEAT / saRepeats << \"s \\t\"\n            << timerStd.value() * REPEAT / stdRepeats << \"s\";\n\n  #ifdef BENCH_GMM\n  if (MatrixType::RowsAtCompileTime==Dynamic)\n  {\n    timerSa.reset();\n    timerStd.reset();\n\n    gmm::dense_matrix<Scalar> gmmCovMat(covMat.rows(),covMat.cols());\n    gmm::dense_matrix<Scalar> eigvect(covMat.rows(),covMat.cols());\n    std::vector<Scalar> eigval(covMat.rows());\n    eiToGmm(covMat, gmmCovMat);\n    for (int t=0; t<TRIES; ++t)\n    {\n      timerSa.start();\n      for (int k=0; k<saRepeats; ++k)\n      {\n        gmm::symmetric_qr_algorithm(gmmCovMat, eigval, eigvect);\n        acc += eigvect(r,c);\n      }\n      timerSa.stop();\n    }\n    // the non-selfadjoint solver does not compute the eigen vectors\n//     for (int t=0; t<TRIES; ++t)\n//     {\n//       timerStd.start();\n//       for (int k=0; k<stdRepeats; ++k)\n//       {\n//         gmm::implicit_qr_algorithm(gmmCovMat, eigval, eigvect);\n//         acc += eigvect(r,c);\n//       }\n//       timerStd.stop();\n//     }\n\n    std::cout << \" | \\t\"\n              << timerSa.value() * REPEAT / saRepeats << \"s\"\n              << /*timerStd.value() * REPEAT / stdRepeats << \"s\"*/ \"   na   \";\n  }\n  #endif\n\n  #ifdef BENCH_GSL\n  if (MatrixType::RowsAtCompileTime==Dynamic)\n  {\n    timerSa.reset();\n    timerStd.reset();\n\n    gsl_matrix* gslCovMat = gsl_matrix_alloc(covMat.rows(),covMat.cols());\n    gsl_matrix* gslCopy = gsl_matrix_alloc(covMat.rows(),covMat.cols());\n    gsl_matrix* eigvect = gsl_matrix_alloc(covMat.rows(),covMat.cols());\n    gsl_vector* eigval  = gsl_vector_alloc(covMat.rows());\n    gsl_eigen_symmv_workspace* eisymm = gsl_eigen_symmv_alloc(covMat.rows());\n    \n    gsl_matrix_complex* eigvectz = gsl_matrix_complex_alloc(covMat.rows(),covMat.cols());\n    gsl_vector_complex* eigvalz  = gsl_vector_complex_alloc(covMat.rows());\n    gsl_eigen_nonsymmv_workspace* einonsymm = gsl_eigen_nonsymmv_alloc(covMat.rows());\n    \n    eiToGsl(covMat, &gslCovMat);\n    for (int t=0; t<TRIES; ++t)\n    {\n      timerSa.start();\n      for (int k=0; k<saRepeats; ++k)\n      {\n        gsl_matrix_memcpy(gslCopy,gslCovMat);\n        gsl_eigen_symmv(gslCopy, eigval, eigvect, eisymm);\n        acc += gsl_matrix_get(eigvect,r,c);\n      }\n      timerSa.stop();\n    }\n    for (int t=0; t<TRIES; ++t)\n    {\n      timerStd.start();\n      for (int k=0; k<stdRepeats; ++k)\n      {\n        gsl_matrix_memcpy(gslCopy,gslCovMat);\n        gsl_eigen_nonsymmv(gslCopy, eigvalz, eigvectz, einonsymm);\n        acc += GSL_REAL(gsl_matrix_complex_get(eigvectz,r,c));\n      }\n      timerStd.stop();\n    }\n\n    std::cout << \" | \\t\"\n              << timerSa.value() * REPEAT / saRepeats << \"s \\t\"\n              << timerStd.value() * REPEAT / stdRepeats << \"s\";\n\n    gsl_matrix_free(gslCovMat);\n    gsl_vector_free(gslCopy);\n    gsl_matrix_free(eigvect);\n    gsl_vector_free(eigval);\n    gsl_matrix_complex_free(eigvectz);\n    gsl_vector_complex_free(eigvalz);\n    gsl_eigen_symmv_free(eisymm);\n    gsl_eigen_nonsymmv_free(einonsymm);\n  }\n  #endif\n\n  std::cout << \"\\n\";\n  \n  // make sure the compiler does not optimize too much\n  if (acc==123)\n    std::cout << acc;\n}\n\nint main(int argc, char* argv[])\n{\n  const int dynsizes[] = {4,6,8,12,16,24,32,64,128,256,512,0};\n  std::cout << \"size            selfadjoint       generic\";\n  #ifdef BENCH_GMM\n  std::cout << \"        GMM++          \";\n  #endif\n  #ifdef BENCH_GSL\n  std::cout << \"       GSL (double + ATLAS)  \";\n  #endif\n  std::cout << \"\\n\";\n  for (uint i=0; dynsizes[i]>0; ++i)\n    benchEigenSolver(Matrix<Scalar,Dynamic,Dynamic>(dynsizes[i],dynsizes[i]));\n\n  benchEigenSolver(Matrix<Scalar,2,2>());\n  benchEigenSolver(Matrix<Scalar,3,3>());\n  benchEigenSolver(Matrix<Scalar,4,4>());\n  benchEigenSolver(Matrix<Scalar,6,6>());\n  benchEigenSolver(Matrix<Scalar,8,8>());\n  benchEigenSolver(Matrix<Scalar,12,12>());\n  benchEigenSolver(Matrix<Scalar,16,16>());\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/benchFFT.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Mark Borgerding mark a borgerding net\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <iostream>\n\n#include <bench/BenchUtil.h>\n#include <complex>\n#include <vector>\n#include <Eigen/Core>\n\n#include <unsupported/Eigen/FFT>\n\nusing namespace Eigen;\nusing namespace std;\n\n\ntemplate <typename T>\nstring nameof();\n\ntemplate <> string nameof<float>() {return \"float\";}\ntemplate <> string nameof<double>() {return \"double\";}\ntemplate <> string nameof<long double>() {return \"long double\";}\n\n#ifndef TYPE\n#define TYPE float\n#endif\n\n#ifndef NFFT\n#define NFFT 1024\n#endif\n#ifndef NDATA\n#define NDATA 1000000\n#endif\n\nusing namespace Eigen;\n\ntemplate <typename T>\nvoid bench(int nfft,bool fwd,bool unscaled=false, bool halfspec=false)\n{\n    typedef typename NumTraits<T>::Real Scalar;\n    typedef typename std::complex<Scalar> Complex;\n    int nits = NDATA/nfft;\n    vector<T> inbuf(nfft);\n    vector<Complex > outbuf(nfft);\n    FFT< Scalar > fft;\n\n    if (unscaled) {\n        fft.SetFlag(fft.Unscaled);\n        cout << \"unscaled \";\n    }\n    if (halfspec) {\n        fft.SetFlag(fft.HalfSpectrum);\n        cout << \"halfspec \";\n    }\n\n\n    std::fill(inbuf.begin(),inbuf.end(),0);\n    fft.fwd( outbuf , inbuf);\n\n    BenchTimer timer;\n    timer.reset();\n    for (int k=0;k<8;++k) {\n        timer.start();\n        if (fwd)\n            for(int i = 0; i < nits; i++)\n                fft.fwd( outbuf , inbuf);\n        else\n            for(int i = 0; i < nits; i++)\n                fft.inv(inbuf,outbuf);\n        timer.stop();\n    }\n\n    cout << nameof<Scalar>() << \" \";\n    double mflops = 5.*nfft*log2((double)nfft) / (1e6 * timer.value() / (double)nits );\n    if ( NumTraits<T>::IsComplex ) {\n        cout << \"complex\";\n    }else{\n        cout << \"real   \";\n        mflops /= 2;\n    }\n\n\n    if (fwd)\n        cout << \" fwd\";\n    else\n        cout << \" inv\";\n\n    cout << \" NFFT=\" << nfft << \"  \" << (double(1e-6*nfft*nits)/timer.value()) << \" MS/s  \" << mflops << \"MFLOPS\\n\";\n}\n\nint main(int argc,char ** argv)\n{\n    bench<complex<float> >(NFFT,true);\n    bench<complex<float> >(NFFT,false);\n    bench<float>(NFFT,true);\n    bench<float>(NFFT,false);\n    bench<float>(NFFT,false,true);\n    bench<float>(NFFT,false,true,true);\n\n    bench<complex<double> >(NFFT,true);\n    bench<complex<double> >(NFFT,false);\n    bench<double>(NFFT,true);\n    bench<double>(NFFT,false);\n    bench<complex<long double> >(NFFT,true);\n    bench<complex<long double> >(NFFT,false);\n    bench<long double>(NFFT,true);\n    bench<long double>(NFFT,false);\n    return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/benchGeometry.cpp",
    "content": "#include <iostream>\n#include <iomanip>\n#include <Eigen/Core>\n#include <Eigen/Geometry>\n#include <bench/BenchTimer.h>\n\nusing namespace Eigen;\nusing namespace std;\n\n#ifndef REPEAT\n#define REPEAT 1000000\n#endif\n\nenum func_opt\n{\n    TV,\n    TMATV,\n    TMATVMAT,\n};\n\n\ntemplate <class res, class arg1, class arg2, int opt>\nstruct func;\n\ntemplate <class res, class arg1, class arg2>\nstruct func<res, arg1, arg2, TV>\n{\n    static EIGEN_DONT_INLINE res run( arg1& a1, arg2& a2 )\n    {\n\tasm (\"\");\n\treturn a1 * a2;\n    }\n};\n\ntemplate <class res, class arg1, class arg2>\nstruct func<res, arg1, arg2, TMATV>\n{\n    static EIGEN_DONT_INLINE res run( arg1& a1, arg2& a2 )\n    {\n\tasm (\"\");\n\treturn a1.matrix() * a2;\n    }\n};\n\ntemplate <class res, class arg1, class arg2>\nstruct func<res, arg1, arg2, TMATVMAT>\n{\n    static EIGEN_DONT_INLINE res run( arg1& a1, arg2& a2 )\n    {\n\tasm (\"\");\n\treturn res(a1.matrix() * a2.matrix());\n    }\n};\n\ntemplate <class func, class arg1, class arg2>\nstruct test_transform\n{\n    static void run()\n    {\n\targ1 a1;\n\ta1.setIdentity();\n\targ2 a2;\n\ta2.setIdentity();\n\n\tBenchTimer timer;\n\ttimer.reset();\n\tfor (int k=0; k<10; ++k)\n\t{\n\t    timer.start();\n\t    for (int k=0; k<REPEAT; ++k)\n\t\ta2 = func::run( a1, a2 );\n\t    timer.stop();\n\t}\n\tcout << setprecision(4) << fixed << timer.value() << \"s  \" << endl;;\n    }\n};\n\n\n#define run_vec( op, scalar, mode, option, vsize ) \\\n    std::cout << #scalar << \"\\t \" << #mode << \"\\t \" << #option << \" \" << #vsize \" \"; \\\n    {\\\n\ttypedef Transform<scalar, 3, mode, option> Trans;\\\n\ttypedef Matrix<scalar, vsize, 1, option> Vec;\\\n\ttypedef func<Vec,Trans,Vec,op> Func;\\\n\ttest_transform< Func, Trans, Vec >::run();\\\n    }\n\n#define run_trans( op, scalar, mode, option ) \\\n    std::cout << #scalar << \"\\t \" << #mode << \"\\t \" << #option << \"   \"; \\\n    {\\\n\ttypedef Transform<scalar, 3, mode, option> Trans;\\\n\ttypedef func<Trans,Trans,Trans,op> Func;\\\n\ttest_transform< Func, Trans, Trans >::run();\\\n    }\n\nint main(int argc, char* argv[])\n{\n    cout << \"vec = trans * vec\" << endl;\n    run_vec(TV, float,  Isometry, AutoAlign, 3);\n    run_vec(TV, float,  Isometry, DontAlign, 3);\n    run_vec(TV, float,  Isometry, AutoAlign, 4);\n    run_vec(TV, float,  Isometry, DontAlign, 4);\n    run_vec(TV, float,  Projective, AutoAlign, 4);\n    run_vec(TV, float,  Projective, DontAlign, 4);\n    run_vec(TV, double, Isometry, AutoAlign, 3);\n    run_vec(TV, double, Isometry, DontAlign, 3);\n    run_vec(TV, double, Isometry, AutoAlign, 4);\n    run_vec(TV, double, Isometry, DontAlign, 4);\n    run_vec(TV, double, Projective, AutoAlign, 4);\n    run_vec(TV, double, Projective, DontAlign, 4);\n\n    cout << \"vec = trans.matrix() * vec\" << endl;\n    run_vec(TMATV, float,  Isometry, AutoAlign, 4);\n    run_vec(TMATV, float,  Isometry, DontAlign, 4);\n    run_vec(TMATV, double, Isometry, AutoAlign, 4);\n    run_vec(TMATV, double, Isometry, DontAlign, 4);\n\n    cout << \"trans = trans1 * trans\" << endl;\n    run_trans(TV, float,  Isometry, AutoAlign);\n    run_trans(TV, float,  Isometry, DontAlign);\n    run_trans(TV, double, Isometry, AutoAlign);\n    run_trans(TV, double, Isometry, DontAlign);\n    run_trans(TV, float,  Projective, AutoAlign);\n    run_trans(TV, float,  Projective, DontAlign);\n    run_trans(TV, double, Projective, AutoAlign);\n    run_trans(TV, double, Projective, DontAlign);\n\n    cout << \"trans = trans1.matrix() * trans.matrix()\" << endl;\n    run_trans(TMATVMAT, float,  Isometry, AutoAlign);\n    run_trans(TMATVMAT, float,  Isometry, DontAlign);\n    run_trans(TMATVMAT, double, Isometry, AutoAlign);\n    run_trans(TMATVMAT, double, Isometry, DontAlign);\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/benchVecAdd.cpp",
    "content": "\n#include <iostream>\n#include <Eigen/Core>\n#include <bench/BenchTimer.h>\nusing namespace Eigen;\n\n#ifndef SIZE\n#define SIZE 50\n#endif\n\n#ifndef REPEAT\n#define REPEAT 10000\n#endif\n\ntypedef float Scalar;\n\n__attribute__ ((noinline)) void benchVec(Scalar* a, Scalar* b, Scalar* c, int size);\n__attribute__ ((noinline)) void benchVec(MatrixXf& a, MatrixXf& b, MatrixXf& c);\n__attribute__ ((noinline)) void benchVec(VectorXf& a, VectorXf& b, VectorXf& c);\n\nint main(int argc, char* argv[])\n{\n    int size = SIZE * 8;\n    int size2 = size * size;\n    Scalar* a = internal::aligned_new<Scalar>(size2);\n    Scalar* b = internal::aligned_new<Scalar>(size2+4)+1;\n    Scalar* c = internal::aligned_new<Scalar>(size2); \n    \n    for (int i=0; i<size; ++i)\n    {\n        a[i] = b[i] = c[i] = 0;\n    }\n    \n    BenchTimer timer;\n    \n    timer.reset();\n    for (int k=0; k<10; ++k)\n    {\n        timer.start();\n        benchVec(a, b, c, size2);\n        timer.stop();\n    }\n    std::cout << timer.value() << \"s  \" << (double(size2*REPEAT)/timer.value())/(1024.*1024.*1024.) << \" GFlops\\n\";\n    return 0;\n    for (int innersize = size; innersize>2 ; --innersize)\n    {\n        if (size2%innersize==0)\n        {\n            int outersize = size2/innersize;\n            MatrixXf ma = Map<MatrixXf>(a, innersize, outersize );\n            MatrixXf mb = Map<MatrixXf>(b, innersize, outersize );\n            MatrixXf mc = Map<MatrixXf>(c, innersize, outersize );\n            timer.reset();\n            for (int k=0; k<3; ++k)\n            {\n                timer.start();\n                benchVec(ma, mb, mc);\n                timer.stop();\n            }\n            std::cout << innersize << \" x \" << outersize << \"  \" << timer.value() << \"s   \" << (double(size2*REPEAT)/timer.value())/(1024.*1024.*1024.) << \" GFlops\\n\";\n        }\n    }\n    \n    VectorXf va = Map<VectorXf>(a, size2);\n    VectorXf vb = Map<VectorXf>(b, size2);\n    VectorXf vc = Map<VectorXf>(c, size2);\n    timer.reset();\n    for (int k=0; k<3; ++k)\n    {\n        timer.start();\n        benchVec(va, vb, vc);\n        timer.stop();\n    }\n    std::cout << timer.value() << \"s   \" << (double(size2*REPEAT)/timer.value())/(1024.*1024.*1024.) << \" GFlops\\n\";\n\n    return 0;\n}\n\nvoid benchVec(MatrixXf& a, MatrixXf& b, MatrixXf& c)\n{\n    for (int k=0; k<REPEAT; ++k)\n        a = a + b;\n}\n\nvoid benchVec(VectorXf& a, VectorXf& b, VectorXf& c)\n{\n    for (int k=0; k<REPEAT; ++k)\n        a = a + b;\n}\n\nvoid benchVec(Scalar* a, Scalar* b, Scalar* c, int size)\n{\n    typedef internal::packet_traits<Scalar>::type PacketScalar;\n    const int PacketSize = internal::packet_traits<Scalar>::size;\n    PacketScalar a0, a1, a2, a3, b0, b1, b2, b3;\n    for (int k=0; k<REPEAT; ++k)\n        for (int i=0; i<size; i+=PacketSize*8)\n        {\n//             a0 = internal::pload(&a[i]);\n//             b0 = internal::pload(&b[i]);\n//             a1 = internal::pload(&a[i+1*PacketSize]);\n//             b1 = internal::pload(&b[i+1*PacketSize]);\n//             a2 = internal::pload(&a[i+2*PacketSize]);\n//             b2 = internal::pload(&b[i+2*PacketSize]);\n//             a3 = internal::pload(&a[i+3*PacketSize]);\n//             b3 = internal::pload(&b[i+3*PacketSize]);\n//             internal::pstore(&a[i], internal::padd(a0, b0));\n//             a0 = internal::pload(&a[i+4*PacketSize]);\n//             b0 = internal::pload(&b[i+4*PacketSize]);\n//             \n//             internal::pstore(&a[i+1*PacketSize], internal::padd(a1, b1));\n//             a1 = internal::pload(&a[i+5*PacketSize]);\n//             b1 = internal::pload(&b[i+5*PacketSize]);\n//             \n//             internal::pstore(&a[i+2*PacketSize], internal::padd(a2, b2));\n//             a2 = internal::pload(&a[i+6*PacketSize]);\n//             b2 = internal::pload(&b[i+6*PacketSize]);\n//             \n//             internal::pstore(&a[i+3*PacketSize], internal::padd(a3, b3));\n//             a3 = internal::pload(&a[i+7*PacketSize]);\n//             b3 = internal::pload(&b[i+7*PacketSize]);\n//             \n//             internal::pstore(&a[i+4*PacketSize], internal::padd(a0, b0));\n//             internal::pstore(&a[i+5*PacketSize], internal::padd(a1, b1));\n//             internal::pstore(&a[i+6*PacketSize], internal::padd(a2, b2));\n//             internal::pstore(&a[i+7*PacketSize], internal::padd(a3, b3));\n            \n            internal::pstore(&a[i+2*PacketSize], internal::padd(internal::ploadu(&a[i+2*PacketSize]), internal::ploadu(&b[i+2*PacketSize])));\n            internal::pstore(&a[i+3*PacketSize], internal::padd(internal::ploadu(&a[i+3*PacketSize]), internal::ploadu(&b[i+3*PacketSize])));\n            internal::pstore(&a[i+4*PacketSize], internal::padd(internal::ploadu(&a[i+4*PacketSize]), internal::ploadu(&b[i+4*PacketSize])));\n            internal::pstore(&a[i+5*PacketSize], internal::padd(internal::ploadu(&a[i+5*PacketSize]), internal::ploadu(&b[i+5*PacketSize])));\n            internal::pstore(&a[i+6*PacketSize], internal::padd(internal::ploadu(&a[i+6*PacketSize]), internal::ploadu(&b[i+6*PacketSize])));\n            internal::pstore(&a[i+7*PacketSize], internal::padd(internal::ploadu(&a[i+7*PacketSize]), internal::ploadu(&b[i+7*PacketSize])));\n        }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/bench_gemm.cpp",
    "content": "\n// g++-4.4 bench_gemm.cpp -I .. -O2 -DNDEBUG -lrt -fopenmp && OMP_NUM_THREADS=2  ./a.out\n// icpc bench_gemm.cpp -I .. -O3 -DNDEBUG -lrt -openmp  && OMP_NUM_THREADS=2  ./a.out\n\n// Compilation options:\n// \n// -DSCALAR=std::complex<double>\n// -DSCALARA=double or -DSCALARB=double\n// -DHAVE_BLAS\n// -DDECOUPLED\n//\n\n#include <iostream>\n#include <bench/BenchTimer.h>\n#include <Eigen/Core>\n\n\nusing namespace std;\nusing namespace Eigen;\n\n#ifndef SCALAR\n// #define SCALAR std::complex<float>\n#define SCALAR float\n#endif\n\n#ifndef SCALARA\n#define SCALARA SCALAR\n#endif\n\n#ifndef SCALARB\n#define SCALARB SCALAR\n#endif\n\n#ifdef ROWMAJ_A\nconst int opt_A = RowMajor;\n#else\nconst int opt_A = ColMajor;\n#endif\n\n#ifdef ROWMAJ_B\nconst int opt_B = RowMajor;\n#else\nconst int opt_B = ColMajor;\n#endif\n\ntypedef SCALAR Scalar;\ntypedef NumTraits<Scalar>::Real RealScalar;\ntypedef Matrix<SCALARA,Dynamic,Dynamic,opt_A> A;\ntypedef Matrix<SCALARB,Dynamic,Dynamic,opt_B> B;\ntypedef Matrix<Scalar,Dynamic,Dynamic> C;\ntypedef Matrix<RealScalar,Dynamic,Dynamic> M;\n\n#ifdef HAVE_BLAS\n\nextern \"C\" {\n  #include <Eigen/src/misc/blas.h>\n}\n\nstatic float fone = 1;\nstatic float fzero = 0;\nstatic double done = 1;\nstatic double szero = 0;\nstatic std::complex<float> cfone = 1;\nstatic std::complex<float> cfzero = 0;\nstatic std::complex<double> cdone = 1;\nstatic std::complex<double> cdzero = 0;\nstatic char notrans = 'N';\nstatic char trans = 'T';  \nstatic char nonunit = 'N';\nstatic char lower = 'L';\nstatic char right = 'R';\nstatic int intone = 1;\n\n#ifdef ROWMAJ_A\nconst char transA = trans;\n#else\nconst char transA = notrans;\n#endif\n\n#ifdef ROWMAJ_B\nconst char transB = trans;\n#else\nconst char transB = notrans;\n#endif\n\ntemplate<typename A,typename B>\nvoid blas_gemm(const A& a, const B& b, MatrixXf& c)\n{\n  int M = c.rows(); int N = c.cols(); int K = a.cols();\n  int lda = a.outerStride(); int ldb = b.outerStride(); int ldc = c.rows();\n\n  sgemm_(&transA,&transB,&M,&N,&K,&fone,\n         const_cast<float*>(a.data()),&lda,\n         const_cast<float*>(b.data()),&ldb,&fone,\n         c.data(),&ldc);\n}\n\ntemplate<typename A,typename B>\nvoid blas_gemm(const A& a, const B& b, MatrixXd& c)\n{\n  int M = c.rows(); int N = c.cols(); int K = a.cols();\n  int lda = a.outerStride(); int ldb = b.outerStride(); int ldc = c.rows();\n\n  dgemm_(&transA,&transB,&M,&N,&K,&done,\n         const_cast<double*>(a.data()),&lda,\n         const_cast<double*>(b.data()),&ldb,&done,\n         c.data(),&ldc);\n}\n\ntemplate<typename A,typename B>\nvoid blas_gemm(const A& a, const B& b, MatrixXcf& c)\n{\n  int M = c.rows(); int N = c.cols(); int K = a.cols();\n  int lda = a.outerStride(); int ldb = b.outerStride(); int ldc = c.rows();\n\n  cgemm_(&transA,&transB,&M,&N,&K,(float*)&cfone,\n         const_cast<float*>((const float*)a.data()),&lda,\n         const_cast<float*>((const float*)b.data()),&ldb,(float*)&cfone,\n         (float*)c.data(),&ldc);\n}\n\ntemplate<typename A,typename B>\nvoid blas_gemm(const A& a, const B& b, MatrixXcd& c)\n{\n  int M = c.rows(); int N = c.cols(); int K = a.cols();\n  int lda = a.outerStride(); int ldb = b.outerStride(); int ldc = c.rows();\n\n  zgemm_(&transA,&transB,&M,&N,&K,(double*)&cdone,\n         const_cast<double*>((const double*)a.data()),&lda,\n         const_cast<double*>((const double*)b.data()),&ldb,(double*)&cdone,\n         (double*)c.data(),&ldc);\n}\n\n\n\n#endif\n\nvoid matlab_cplx_cplx(const M& ar, const M& ai, const M& br, const M& bi, M& cr, M& ci)\n{\n  cr.noalias() += ar * br;\n  cr.noalias() -= ai * bi;\n  ci.noalias() += ar * bi;\n  ci.noalias() += ai * br;\n  // [cr ci] += [ar ai] * br + [-ai ar] * bi\n}\n\nvoid matlab_real_cplx(const M& a, const M& br, const M& bi, M& cr, M& ci)\n{\n  cr.noalias() += a * br;\n  ci.noalias() += a * bi;\n}\n\nvoid matlab_cplx_real(const M& ar, const M& ai, const M& b, M& cr, M& ci)\n{\n  cr.noalias() += ar * b;\n  ci.noalias() += ai * b;\n}\n\n\n\ntemplate<typename A, typename B, typename C>\nEIGEN_DONT_INLINE void gemm(const A& a, const B& b, C& c)\n{\n  c.noalias() += a * b;\n}\n\nint main(int argc, char ** argv)\n{\n  std::ptrdiff_t l1 = internal::queryL1CacheSize();\n  std::ptrdiff_t l2 = internal::queryTopLevelCacheSize();\n  std::cout << \"L1 cache size     = \" << (l1>0 ? l1/1024 : -1) << \" KB\\n\";\n  std::cout << \"L2/L3 cache size  = \" << (l2>0 ? l2/1024 : -1) << \" KB\\n\";\n  typedef internal::gebp_traits<Scalar,Scalar> Traits;\n  std::cout << \"Register blocking = \" << Traits::mr << \" x \" << Traits::nr << \"\\n\";\n\n  int rep = 1;    // number of repetitions per try\n  int tries = 2;  // number of tries, we keep the best\n\n  int s = 2048;\n  int m = s;\n  int n = s;\n  int p = s;\n  int cache_size1=-1, cache_size2=l2, cache_size3 = 0;\n\n  bool need_help = false;\n  for (int i=1; i<argc;)\n  {\n    if(argv[i][0]=='-')\n    {\n      if(argv[i][1]=='s')\n      {\n        ++i;\n        s = atoi(argv[i++]);\n        m = n = p = s;\n        if(argv[i][0]!='-')\n        {\n          n = atoi(argv[i++]);\n          p = atoi(argv[i++]);\n        }\n      }\n      else if(argv[i][1]=='c')\n      {\n        ++i;\n        cache_size1 = atoi(argv[i++]);\n        if(argv[i][0]!='-')\n        {\n          cache_size2 = atoi(argv[i++]);\n          if(argv[i][0]!='-')\n            cache_size3 = atoi(argv[i++]);\n        }\n      }\n      else if(argv[i][1]=='t')\n      {\n        tries = atoi(argv[++i]);\n        ++i;\n      }\n      else if(argv[i][1]=='p')\n      {\n        ++i;\n        rep = atoi(argv[i++]);\n      }\n    }\n    else\n    {\n      need_help = true;\n      break;\n    }\n  }\n\n  if(need_help)\n  {\n    std::cout << argv[0] << \" -s <matrix sizes> -c <cache sizes> -t <nb tries> -p <nb repeats>\\n\";\n    std::cout << \"   <matrix sizes> : size\\n\";\n    std::cout << \"   <matrix sizes> : rows columns depth\\n\";\n    return 1;\n  }\n\n#if EIGEN_VERSION_AT_LEAST(3,2,90)\n  if(cache_size1>0)\n    setCpuCacheSizes(cache_size1,cache_size2,cache_size3);\n#endif\n  \n  A a(m,p); a.setRandom();\n  B b(p,n); b.setRandom();\n  C c(m,n); c.setOnes();\n  C rc = c;\n\n  std::cout << \"Matrix sizes = \" << m << \"x\" << p << \" * \" << p << \"x\" << n << \"\\n\";\n  std::ptrdiff_t mc(m), nc(n), kc(p);\n  internal::computeProductBlockingSizes<Scalar,Scalar>(kc, mc, nc);\n  std::cout << \"blocking size (mc x kc) = \" << mc << \" x \" << kc << \" x \" << nc << \"\\n\";\n\n  C r = c;\n\n  // check the parallel product is correct\n  #if defined EIGEN_HAS_OPENMP\n  Eigen::initParallel();\n  int procs = omp_get_max_threads();\n  if(procs>1)\n  {\n    #ifdef HAVE_BLAS\n    blas_gemm(a,b,r);\n    #else\n    omp_set_num_threads(1);\n    r.noalias() += a * b;\n    omp_set_num_threads(procs);\n    #endif\n    c.noalias() += a * b;\n    if(!r.isApprox(c)) std::cerr << \"Warning, your parallel product is crap!\\n\\n\";\n  }\n  #elif defined HAVE_BLAS\n    blas_gemm(a,b,r);\n    c.noalias() += a * b;\n    if(!r.isApprox(c)) {\n      std::cout << (r  - c).norm()/r.norm() << \"\\n\";\n      std::cerr << \"Warning, your product is crap!\\n\\n\";\n    }\n  #else\n    if(1.*m*n*p<2000.*2000*2000)\n    {\n      gemm(a,b,c);\n      r.noalias() += a.cast<Scalar>() .lazyProduct( b.cast<Scalar>() );\n      if(!r.isApprox(c)) {\n        std::cout << (r  - c).norm()/r.norm() << \"\\n\";\n        std::cerr << \"Warning, your product is crap!\\n\\n\";\n      }\n    }\n  #endif\n\n  #ifdef HAVE_BLAS\n  BenchTimer tblas;\n  c = rc;\n  BENCH(tblas, tries, rep, blas_gemm(a,b,c));\n  std::cout << \"blas  cpu         \" << tblas.best(CPU_TIMER)/rep  << \"s  \\t\" << (double(m)*n*p*rep*2/tblas.best(CPU_TIMER))*1e-9  <<  \" GFLOPS \\t(\" << tblas.total(CPU_TIMER)  << \"s)\\n\";\n  std::cout << \"blas  real        \" << tblas.best(REAL_TIMER)/rep << \"s  \\t\" << (double(m)*n*p*rep*2/tblas.best(REAL_TIMER))*1e-9 <<  \" GFLOPS \\t(\" << tblas.total(REAL_TIMER) << \"s)\\n\";\n  #endif\n\n  // warm start\n  if(b.norm()+a.norm()==123.554) std::cout << \"\\n\";\n\n  BenchTimer tmt;\n  c = rc;\n  BENCH(tmt, tries, rep, gemm(a,b,c));\n  std::cout << \"eigen cpu         \" << tmt.best(CPU_TIMER)/rep  << \"s  \\t\" << (double(m)*n*p*rep*2/tmt.best(CPU_TIMER))*1e-9  <<  \" GFLOPS \\t(\" << tmt.total(CPU_TIMER)  << \"s)\\n\";\n  std::cout << \"eigen real        \" << tmt.best(REAL_TIMER)/rep << \"s  \\t\" << (double(m)*n*p*rep*2/tmt.best(REAL_TIMER))*1e-9 <<  \" GFLOPS \\t(\" << tmt.total(REAL_TIMER) << \"s)\\n\";\n\n  #ifdef EIGEN_HAS_OPENMP\n  if(procs>1)\n  {\n    BenchTimer tmono;\n    omp_set_num_threads(1);\n    Eigen::setNbThreads(1);\n    c = rc;\n    BENCH(tmono, tries, rep, gemm(a,b,c));\n    std::cout << \"eigen mono cpu    \" << tmono.best(CPU_TIMER)/rep  << \"s  \\t\" << (double(m)*n*p*rep*2/tmono.best(CPU_TIMER))*1e-9  <<  \" GFLOPS \\t(\" << tmono.total(CPU_TIMER)  << \"s)\\n\";\n    std::cout << \"eigen mono real   \" << tmono.best(REAL_TIMER)/rep << \"s  \\t\" << (double(m)*n*p*rep*2/tmono.best(REAL_TIMER))*1e-9 <<  \" GFLOPS \\t(\" << tmono.total(REAL_TIMER) << \"s)\\n\";\n    std::cout << \"mt speed up x\" << tmono.best(CPU_TIMER) / tmt.best(REAL_TIMER)  << \" => \" << (100.0*tmono.best(CPU_TIMER) / tmt.best(REAL_TIMER))/procs << \"%\\n\";\n  }\n  #endif\n  \n  if(1.*m*n*p<30*30*30)\n  {\n    BenchTimer tmt;\n    c = rc;\n    BENCH(tmt, tries, rep, c.noalias()+=a.lazyProduct(b));\n    std::cout << \"lazy cpu         \" << tmt.best(CPU_TIMER)/rep  << \"s  \\t\" << (double(m)*n*p*rep*2/tmt.best(CPU_TIMER))*1e-9  <<  \" GFLOPS \\t(\" << tmt.total(CPU_TIMER)  << \"s)\\n\";\n    std::cout << \"lazy real        \" << tmt.best(REAL_TIMER)/rep << \"s  \\t\" << (double(m)*n*p*rep*2/tmt.best(REAL_TIMER))*1e-9 <<  \" GFLOPS \\t(\" << tmt.total(REAL_TIMER) << \"s)\\n\";\n  }\n  \n  #ifdef DECOUPLED\n  if((NumTraits<A::Scalar>::IsComplex) && (NumTraits<B::Scalar>::IsComplex))\n  {\n    M ar(m,p); ar.setRandom();\n    M ai(m,p); ai.setRandom();\n    M br(p,n); br.setRandom();\n    M bi(p,n); bi.setRandom();\n    M cr(m,n); cr.setRandom();\n    M ci(m,n); ci.setRandom();\n    \n    BenchTimer t;\n    BENCH(t, tries, rep, matlab_cplx_cplx(ar,ai,br,bi,cr,ci));\n    std::cout << \"\\\"matlab\\\" cpu    \" << t.best(CPU_TIMER)/rep  << \"s  \\t\" << (double(m)*n*p*rep*2/t.best(CPU_TIMER))*1e-9  <<  \" GFLOPS \\t(\" << t.total(CPU_TIMER)  << \"s)\\n\";\n    std::cout << \"\\\"matlab\\\" real   \" << t.best(REAL_TIMER)/rep << \"s  \\t\" << (double(m)*n*p*rep*2/t.best(REAL_TIMER))*1e-9 <<  \" GFLOPS \\t(\" << t.total(REAL_TIMER) << \"s)\\n\";\n  }\n  if((!NumTraits<A::Scalar>::IsComplex) && (NumTraits<B::Scalar>::IsComplex))\n  {\n    M a(m,p);  a.setRandom();\n    M br(p,n); br.setRandom();\n    M bi(p,n); bi.setRandom();\n    M cr(m,n); cr.setRandom();\n    M ci(m,n); ci.setRandom();\n    \n    BenchTimer t;\n    BENCH(t, tries, rep, matlab_real_cplx(a,br,bi,cr,ci));\n    std::cout << \"\\\"matlab\\\" cpu    \" << t.best(CPU_TIMER)/rep  << \"s  \\t\" << (double(m)*n*p*rep*2/t.best(CPU_TIMER))*1e-9  <<  \" GFLOPS \\t(\" << t.total(CPU_TIMER)  << \"s)\\n\";\n    std::cout << \"\\\"matlab\\\" real   \" << t.best(REAL_TIMER)/rep << \"s  \\t\" << (double(m)*n*p*rep*2/t.best(REAL_TIMER))*1e-9 <<  \" GFLOPS \\t(\" << t.total(REAL_TIMER) << \"s)\\n\";\n  }\n  if((NumTraits<A::Scalar>::IsComplex) && (!NumTraits<B::Scalar>::IsComplex))\n  {\n    M ar(m,p); ar.setRandom();\n    M ai(m,p); ai.setRandom();\n    M b(p,n);  b.setRandom();\n    M cr(m,n); cr.setRandom();\n    M ci(m,n); ci.setRandom();\n    \n    BenchTimer t;\n    BENCH(t, tries, rep, matlab_cplx_real(ar,ai,b,cr,ci));\n    std::cout << \"\\\"matlab\\\" cpu    \" << t.best(CPU_TIMER)/rep  << \"s  \\t\" << (double(m)*n*p*rep*2/t.best(CPU_TIMER))*1e-9  <<  \" GFLOPS \\t(\" << t.total(CPU_TIMER)  << \"s)\\n\";\n    std::cout << \"\\\"matlab\\\" real   \" << t.best(REAL_TIMER)/rep << \"s  \\t\" << (double(m)*n*p*rep*2/t.best(REAL_TIMER))*1e-9 <<  \" GFLOPS \\t(\" << t.total(REAL_TIMER) << \"s)\\n\";\n  }\n  #endif\n\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/bench_move_semantics.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2020 Sebastien Boisvert <seb@boisvert.info>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"BenchTimer.h\"\n#include \"../test/MovableScalar.h\"\n\n#include <Eigen/Core>\n\n#include <iostream>\n#include <utility>\n\ntemplate <typename MatrixType>\nvoid copy_matrix(MatrixType& m)\n{\n  MatrixType tmp(m);\n  m = tmp;\n}\n\ntemplate <typename MatrixType>\nvoid move_matrix(MatrixType&& m)\n{\n  MatrixType tmp(std::move(m));\n  m = std::move(tmp);\n}\n\ntemplate<typename Scalar>\nvoid bench(const std::string& label)\n{\n  using MatrixType = Eigen::Matrix<Eigen::MovableScalar<Scalar>,1,10>;\n  Eigen::BenchTimer t;\n\n  int tries = 10;\n  int rep = 1000000;\n\n  MatrixType data = MatrixType::Random().eval();\n  MatrixType dest;\n\n  BENCH(t, tries, rep, copy_matrix(data));\n  std::cout << label << \" copy semantics: \" << 1e3*t.best(Eigen::CPU_TIMER) << \" ms\" << std::endl;\n\n  BENCH(t, tries, rep, move_matrix(std::move(data)));\n  std::cout << label << \" move semantics: \" << 1e3*t.best(Eigen::CPU_TIMER) << \" ms\" << std::endl;\n}\n\nint main()\n{\n  bench<float>(\"float\");\n  bench<double>(\"double\");\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/bench_multi_compilers.sh",
    "content": "#!/bin/bash\n\nif (($# < 2)); then\n    echo \"Usage: $0 compilerlist.txt benchfile.cpp\"\nelse\n\ncompilerlist=$1\nbenchfile=$2\n\ng=0\nsource $compilerlist\n\n# for each compiler, compile benchfile and run the benchmark\nfor (( i=0 ; i<g ; ++i )) ; do\n  # check the compiler exists\n  compiler=`echo ${CLIST[$i]} | cut -d \" \" -f 1`\n  if [ -e `which $compiler` ]; then\n    echo \"${CLIST[$i]}\"\n#     echo \"${CLIST[$i]} $benchfile -I.. -o bench~\"\n#     if [ -e ./.bench ] ; then rm .bench; fi\n    ${CLIST[$i]} $benchfile -I.. -o .bench && ./.bench 2> /dev/null\n    echo \"\"\n  else\n    echo \"compiler not found: $compiler\"\n  fi\ndone\n\nfi\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/bench_norm.cpp",
    "content": "#include <typeinfo>\n#include <iostream>\n#include <Eigen/Core>\n#include \"BenchTimer.h\"\nusing namespace Eigen;\nusing namespace std;\n\ntemplate<typename T>\nEIGEN_DONT_INLINE typename T::Scalar sqsumNorm(T& v)\n{\n  return v.norm();\n}\n\ntemplate<typename T>\nEIGEN_DONT_INLINE typename T::Scalar stableNorm(T& v)\n{\n  return v.stableNorm();\n}\n\ntemplate<typename T>\nEIGEN_DONT_INLINE typename T::Scalar hypotNorm(T& v)\n{\n  return v.hypotNorm();\n}\n\ntemplate<typename T>\nEIGEN_DONT_INLINE typename T::Scalar blueNorm(T& v)\n{\n  return v.blueNorm();\n}\n\ntemplate<typename T>\nEIGEN_DONT_INLINE typename T::Scalar lapackNorm(T& v)\n{\n  typedef typename T::Scalar Scalar;\n  int n = v.size();\n  Scalar scale = 0;\n  Scalar ssq = 1;\n  for (int i=0;i<n;++i)\n  {\n    Scalar ax = std::abs(v.coeff(i));\n    if (scale >= ax)\n    {\n      ssq += numext::abs2(ax/scale);\n    }\n    else\n    {\n      ssq = Scalar(1) + ssq * numext::abs2(scale/ax);\n      scale = ax;\n    }\n  }\n  return scale * std::sqrt(ssq);\n}\n\ntemplate<typename T>\nEIGEN_DONT_INLINE typename T::Scalar twopassNorm(T& v)\n{\n  typedef typename T::Scalar Scalar;\n  Scalar s = v.array().abs().maxCoeff();\n  return s*(v/s).norm();\n}\n\ntemplate<typename T>\nEIGEN_DONT_INLINE typename T::Scalar bl2passNorm(T& v)\n{\n  return v.stableNorm();\n}\n\ntemplate<typename T>\nEIGEN_DONT_INLINE typename T::Scalar divacNorm(T& v)\n{\n  int n =v.size() / 2;\n  for (int i=0;i<n;++i)\n    v(i) = v(2*i)*v(2*i) + v(2*i+1)*v(2*i+1);\n  n = n/2;\n  while (n>0)\n  {\n    for (int i=0;i<n;++i)\n      v(i) = v(2*i) + v(2*i+1);\n    n = n/2;\n  }\n  return std::sqrt(v(0));\n}\n\nnamespace Eigen {\nnamespace internal {\n#ifdef EIGEN_VECTORIZE\nPacket4f plt(const Packet4f& a, Packet4f& b) { return _mm_cmplt_ps(a,b); }\nPacket2d plt(const Packet2d& a, Packet2d& b) { return _mm_cmplt_pd(a,b); }\n\nPacket4f pandnot(const Packet4f& a, Packet4f& b) { return _mm_andnot_ps(a,b); }\nPacket2d pandnot(const Packet2d& a, Packet2d& b) { return _mm_andnot_pd(a,b); }\n#endif\n}\n}\n\ntemplate<typename T>\nEIGEN_DONT_INLINE typename T::Scalar pblueNorm(const T& v)\n{\n  #ifndef EIGEN_VECTORIZE\n  return v.blueNorm();\n  #else\n  typedef typename T::Scalar Scalar;\n\n  static int nmax = 0;\n  static Scalar b1, b2, s1m, s2m, overfl, rbig, relerr;\n  int n;\n\n  if(nmax <= 0)\n  {\n    int nbig, ibeta, it, iemin, iemax, iexp;\n    Scalar abig, eps;\n\n    nbig  = NumTraits<int>::highest();          // largest integer\n    ibeta = std::numeric_limits<Scalar>::radix; // NumTraits<Scalar>::Base;                    // base for floating-point numbers\n    it    = NumTraits<Scalar>::digits();        // NumTraits<Scalar>::Mantissa;                // number of base-beta digits in mantissa\n    iemin = NumTraits<Scalar>::min_exponent();  // minimum exponent\n    iemax = NumTraits<Scalar>::max_exponent();  // maximum exponent\n    rbig  = NumTraits<Scalar>::highest();       // largest floating-point number\n\n    // Check the basic machine-dependent constants.\n    if(iemin > 1 - 2*it || 1+it>iemax || (it==2 && ibeta<5)\n      || (it<=4 && ibeta <= 3 ) || it<2)\n    {\n      eigen_assert(false && \"the algorithm cannot be guaranteed on this computer\");\n    }\n    iexp  = -((1-iemin)/2);\n    b1    = std::pow(ibeta, iexp);  // lower boundary of midrange\n    iexp  = (iemax + 1 - it)/2;\n    b2    = std::pow(ibeta,iexp);   // upper boundary of midrange\n\n    iexp  = (2-iemin)/2;\n    s1m   = std::pow(ibeta,iexp);   // scaling factor for lower range\n    iexp  = - ((iemax+it)/2);\n    s2m   = std::pow(ibeta,iexp);   // scaling factor for upper range\n\n    overfl  = rbig*s2m;          // overflow boundary for abig\n    eps     = std::pow(ibeta, 1-it);\n    relerr  = std::sqrt(eps);      // tolerance for neglecting asml\n    abig    = 1.0/eps - 1.0;\n    if (Scalar(nbig)>abig)  nmax = abig;  // largest safe n\n    else                    nmax = nbig;\n  }\n\n  typedef typename internal::packet_traits<Scalar>::type Packet;\n  const int ps = internal::packet_traits<Scalar>::size;\n  Packet pasml = internal::pset1<Packet>(Scalar(0));\n  Packet pamed = internal::pset1<Packet>(Scalar(0));\n  Packet pabig = internal::pset1<Packet>(Scalar(0));\n  Packet ps2m = internal::pset1<Packet>(s2m);\n  Packet ps1m = internal::pset1<Packet>(s1m);\n  Packet pb2  = internal::pset1<Packet>(b2);\n  Packet pb1  = internal::pset1<Packet>(b1);\n  for(int j=0; j<v.size(); j+=ps)\n  {\n    Packet ax = internal::pabs(v.template packet<Aligned>(j));\n    Packet ax_s2m = internal::pmul(ax,ps2m);\n    Packet ax_s1m = internal::pmul(ax,ps1m);\n    Packet maskBig = internal::plt(pb2,ax);\n    Packet maskSml = internal::plt(ax,pb1);\n\n//     Packet maskMed = internal::pand(maskSml,maskBig);\n//     Packet scale = internal::pset1(Scalar(0));\n//     scale = internal::por(scale, internal::pand(maskBig,ps2m));\n//     scale = internal::por(scale, internal::pand(maskSml,ps1m));\n//     scale = internal::por(scale, internal::pandnot(internal::pset1(Scalar(1)),maskMed));\n//     ax = internal::pmul(ax,scale);\n//     ax = internal::pmul(ax,ax);\n//     pabig = internal::padd(pabig, internal::pand(maskBig, ax));\n//     pasml = internal::padd(pasml, internal::pand(maskSml, ax));\n//     pamed = internal::padd(pamed, internal::pandnot(ax,maskMed));\n\n\n    pabig = internal::padd(pabig, internal::pand(maskBig, internal::pmul(ax_s2m,ax_s2m)));\n    pasml = internal::padd(pasml, internal::pand(maskSml, internal::pmul(ax_s1m,ax_s1m)));\n    pamed = internal::padd(pamed, internal::pandnot(internal::pmul(ax,ax),internal::pand(maskSml,maskBig)));\n  }\n  Scalar abig = internal::predux(pabig);\n  Scalar asml = internal::predux(pasml);\n  Scalar amed = internal::predux(pamed);\n  if(abig > Scalar(0))\n  {\n    abig = std::sqrt(abig);\n    if(abig > overfl)\n    {\n      eigen_assert(false && \"overflow\");\n      return rbig;\n    }\n    if(amed > Scalar(0))\n    {\n      abig = abig/s2m;\n      amed = std::sqrt(amed);\n    }\n    else\n    {\n      return abig/s2m;\n    }\n\n  }\n  else if(asml > Scalar(0))\n  {\n    if (amed > Scalar(0))\n    {\n      abig = std::sqrt(amed);\n      amed = std::sqrt(asml) / s1m;\n    }\n    else\n    {\n      return std::sqrt(asml)/s1m;\n    }\n  }\n  else\n  {\n    return std::sqrt(amed);\n  }\n  asml = std::min(abig, amed);\n  abig = std::max(abig, amed);\n  if(asml <= abig*relerr)\n    return abig;\n  else\n    return abig * std::sqrt(Scalar(1) + numext::abs2(asml/abig));\n  #endif\n}\n\n#define BENCH_PERF(NRM) { \\\n  float af = 0; double ad = 0; std::complex<float> ac = 0; \\\n  Eigen::BenchTimer tf, td, tcf; tf.reset(); td.reset(); tcf.reset();\\\n  for (int k=0; k<tries; ++k) { \\\n    tf.start(); \\\n    for (int i=0; i<iters; ++i) { af += NRM(vf); } \\\n    tf.stop(); \\\n  } \\\n  for (int k=0; k<tries; ++k) { \\\n    td.start(); \\\n    for (int i=0; i<iters; ++i) { ad += NRM(vd); } \\\n    td.stop(); \\\n  } \\\n  /*for (int k=0; k<std::max(1,tries/3); ++k) { \\\n    tcf.start(); \\\n    for (int i=0; i<iters; ++i) { ac += NRM(vcf); } \\\n    tcf.stop(); \\\n  } */\\\n  std::cout << #NRM << \"\\t\" << tf.value() << \"   \" << td.value() <<  \"    \" << tcf.value() << \"\\n\"; \\\n}\n\nvoid check_accuracy(double basef, double based, int s)\n{\n  double yf = basef * std::abs(internal::random<double>());\n  double yd = based * std::abs(internal::random<double>());\n  VectorXf vf = VectorXf::Ones(s) * yf;\n  VectorXd vd = VectorXd::Ones(s) * yd;\n\n  std::cout << \"reference\\t\" << std::sqrt(double(s))*yf << \"\\t\" << std::sqrt(double(s))*yd << \"\\n\";\n  std::cout << \"sqsumNorm\\t\" << sqsumNorm(vf) << \"\\t\" << sqsumNorm(vd) << \"\\n\";\n  std::cout << \"hypotNorm\\t\" << hypotNorm(vf) << \"\\t\" << hypotNorm(vd) << \"\\n\";\n  std::cout << \"blueNorm\\t\" << blueNorm(vf) << \"\\t\" << blueNorm(vd) << \"\\n\";\n  std::cout << \"pblueNorm\\t\" << pblueNorm(vf) << \"\\t\" << pblueNorm(vd) << \"\\n\";\n  std::cout << \"lapackNorm\\t\" << lapackNorm(vf) << \"\\t\" << lapackNorm(vd) << \"\\n\";\n  std::cout << \"twopassNorm\\t\" << twopassNorm(vf) << \"\\t\" << twopassNorm(vd) << \"\\n\";\n  std::cout << \"bl2passNorm\\t\" << bl2passNorm(vf) << \"\\t\" << bl2passNorm(vd) << \"\\n\";\n}\n\nvoid check_accuracy_var(int ef0, int ef1, int ed0, int ed1, int s)\n{\n  VectorXf vf(s);\n  VectorXd vd(s);\n  for (int i=0; i<s; ++i)\n  {\n    vf[i] = std::abs(internal::random<double>()) * std::pow(double(10), internal::random<int>(ef0,ef1));\n    vd[i] = std::abs(internal::random<double>()) * std::pow(double(10), internal::random<int>(ed0,ed1));\n  }\n\n  //std::cout << \"reference\\t\" << internal::sqrt(double(s))*yf << \"\\t\" << internal::sqrt(double(s))*yd << \"\\n\";\n  std::cout << \"sqsumNorm\\t\"  << sqsumNorm(vf)  << \"\\t\" << sqsumNorm(vd)  << \"\\t\" << sqsumNorm(vf.cast<long double>()) << \"\\t\" << sqsumNorm(vd.cast<long double>()) << \"\\n\";\n  std::cout << \"hypotNorm\\t\"  << hypotNorm(vf)  << \"\\t\" << hypotNorm(vd)  << \"\\t\" << hypotNorm(vf.cast<long double>()) << \"\\t\" << hypotNorm(vd.cast<long double>()) << \"\\n\";\n  std::cout << \"blueNorm\\t\"   << blueNorm(vf)   << \"\\t\" << blueNorm(vd)   << \"\\t\" << blueNorm(vf.cast<long double>()) << \"\\t\" << blueNorm(vd.cast<long double>()) << \"\\n\";\n  std::cout << \"pblueNorm\\t\"  << pblueNorm(vf)  << \"\\t\" << pblueNorm(vd)  << \"\\t\" << blueNorm(vf.cast<long double>()) << \"\\t\" << blueNorm(vd.cast<long double>()) << \"\\n\";\n  std::cout << \"lapackNorm\\t\" << lapackNorm(vf) << \"\\t\" << lapackNorm(vd) << \"\\t\" << lapackNorm(vf.cast<long double>()) << \"\\t\" << lapackNorm(vd.cast<long double>()) << \"\\n\";\n  std::cout << \"twopassNorm\\t\" << twopassNorm(vf) << \"\\t\" << twopassNorm(vd) << \"\\t\" << twopassNorm(vf.cast<long double>()) << \"\\t\" << twopassNorm(vd.cast<long double>()) << \"\\n\";\n//   std::cout << \"bl2passNorm\\t\" << bl2passNorm(vf) << \"\\t\" << bl2passNorm(vd) << \"\\t\" << bl2passNorm(vf.cast<long double>()) << \"\\t\" << bl2passNorm(vd.cast<long double>()) << \"\\n\";\n}\n\nint main(int argc, char** argv)\n{\n  int tries = 10;\n  int iters = 100000;\n  double y = 1.1345743233455785456788e12 * internal::random<double>();\n  VectorXf v = VectorXf::Ones(1024) * y;\n\n// return 0;\n  int s = 10000;\n  double basef_ok = 1.1345743233455785456788e15;\n  double based_ok = 1.1345743233455785456788e95;\n\n  double basef_under = 1.1345743233455785456788e-27;\n  double based_under = 1.1345743233455785456788e-303;\n\n  double basef_over = 1.1345743233455785456788e+27;\n  double based_over = 1.1345743233455785456788e+302;\n\n  std::cout.precision(20);\n\n  std::cerr << \"\\nNo under/overflow:\\n\";\n  check_accuracy(basef_ok, based_ok, s);\n\n  std::cerr << \"\\nUnderflow:\\n\";\n  check_accuracy(basef_under, based_under, s);\n\n  std::cerr << \"\\nOverflow:\\n\";\n  check_accuracy(basef_over, based_over, s);\n\n  std::cerr << \"\\nVarying (over):\\n\";\n  for (int k=0; k<1; ++k)\n  {\n    check_accuracy_var(20,27,190,302,s);\n    std::cout << \"\\n\";\n  }\n\n  std::cerr << \"\\nVarying (under):\\n\";\n  for (int k=0; k<1; ++k)\n  {\n    check_accuracy_var(-27,20,-302,-190,s);\n    std::cout << \"\\n\";\n  }\n\n  y = 1;\n  std::cout.precision(4);\n  int s1 = 1024*1024*32;\n  std::cerr << \"Performance (out of cache, \" << s1 << \"):\\n\";\n  {\n    int iters = 1;\n    VectorXf vf = VectorXf::Random(s1) * y;\n    VectorXd vd = VectorXd::Random(s1) * y;\n    VectorXcf vcf = VectorXcf::Random(s1) * y;\n    BENCH_PERF(sqsumNorm);\n    BENCH_PERF(stableNorm);\n    BENCH_PERF(blueNorm);\n    BENCH_PERF(pblueNorm);\n    BENCH_PERF(lapackNorm);\n    BENCH_PERF(hypotNorm);\n    BENCH_PERF(twopassNorm);\n    BENCH_PERF(bl2passNorm);\n  }\n\n  std::cerr << \"\\nPerformance (in cache, \" << 512 << \"):\\n\";\n  {\n    int iters = 100000;\n    VectorXf vf = VectorXf::Random(512) * y;\n    VectorXd vd = VectorXd::Random(512) * y;\n    VectorXcf vcf = VectorXcf::Random(512) * y;\n    BENCH_PERF(sqsumNorm);\n    BENCH_PERF(stableNorm);\n    BENCH_PERF(blueNorm);\n    BENCH_PERF(pblueNorm);\n    BENCH_PERF(lapackNorm);\n    BENCH_PERF(hypotNorm);\n    BENCH_PERF(twopassNorm);\n    BENCH_PERF(bl2passNorm);\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/bench_reverse.cpp",
    "content": "\n#include <iostream>\n#include <Eigen/Core>\n#include <bench/BenchUtil.h>\nusing namespace Eigen;\n\n#ifndef REPEAT\n#define REPEAT 100000\n#endif\n\n#ifndef TRIES\n#define TRIES 20\n#endif\n\ntypedef double Scalar;\n\ntemplate <typename MatrixType>\n__attribute__ ((noinline)) void bench_reverse(const MatrixType& m)\n{\n  int rows = m.rows();\n  int cols = m.cols();\n  int size = m.size();\n\n  int repeats = (REPEAT*1000)/size;\n  MatrixType a = MatrixType::Random(rows,cols);\n  MatrixType b = MatrixType::Random(rows,cols);\n\n  BenchTimer timerB, timerH, timerV;\n\n  Scalar acc = 0;\n  int r = internal::random<int>(0,rows-1);\n  int c = internal::random<int>(0,cols-1);\n  for (int t=0; t<TRIES; ++t)\n  {\n    timerB.start();\n    for (int k=0; k<repeats; ++k)\n    {\n      asm(\"#begin foo\");\n      b = a.reverse();\n      asm(\"#end foo\");\n      acc += b.coeff(r,c);\n    }\n    timerB.stop();\n  }\n\n  if (MatrixType::RowsAtCompileTime==Dynamic)\n    std::cout << \"dyn   \";\n  else\n    std::cout << \"fixed \";\n  std::cout << rows << \" x \" << cols << \" \\t\"\n            << (timerB.value() * REPEAT) / repeats << \"s \"\n            << \"(\" << 1e-6 * size*repeats/timerB.value() << \" MFLOPS)\\t\";\n\n  std::cout << \"\\n\";\n  // make sure the compiler does not optimize too much\n  if (acc==123)\n    std::cout << acc;\n}\n\nint main(int argc, char* argv[])\n{\n  const int dynsizes[] = {4,6,8,16,24,32,49,64,128,256,512,900,0};\n  std::cout << \"size            no sqrt                           standard\";\n//   #ifdef BENCH_GSL\n//   std::cout << \"       GSL (standard + double + ATLAS)  \";\n//   #endif\n  std::cout << \"\\n\";\n  for (uint i=0; dynsizes[i]>0; ++i)\n  {\n    bench_reverse(Matrix<Scalar,Dynamic,Dynamic>(dynsizes[i],dynsizes[i]));\n    bench_reverse(Matrix<Scalar,Dynamic,1>(dynsizes[i]*dynsizes[i]));\n  }\n//   bench_reverse(Matrix<Scalar,2,2>());\n//   bench_reverse(Matrix<Scalar,3,3>());\n//   bench_reverse(Matrix<Scalar,4,4>());\n//   bench_reverse(Matrix<Scalar,5,5>());\n//   bench_reverse(Matrix<Scalar,6,6>());\n//   bench_reverse(Matrix<Scalar,7,7>());\n//   bench_reverse(Matrix<Scalar,8,8>());\n//   bench_reverse(Matrix<Scalar,12,12>());\n//   bench_reverse(Matrix<Scalar,16,16>());\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/bench_sum.cpp",
    "content": "#include <iostream>\n#include <Eigen/Core>\nusing namespace Eigen;\nusing namespace std;\n\nint main() \n{\n  typedef Matrix<SCALAR,Eigen::Dynamic,1> Vec;\n  Vec v(SIZE);\n  v.setZero();\n  v[0] = 1;\n  v[1] = 2;\n  for(int i = 0; i < 1000000; i++)\n  {\n    v.coeffRef(0) += v.sum() * SCALAR(1e-20);\n  }\n  cout << v.sum() << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/bench_unrolling",
    "content": "#!/bin/bash\n\n# gcc : CXX=\"g++  -finline-limit=10000 -ftemplate-depth-2000 --param max-inline-recursive-depth=2000\"\n# icc : CXX=\"icpc -fast -no-inline-max-size -fno-exceptions\"\nCXX=${CXX-g++  -finline-limit=10000 -ftemplate-depth-2000 --param max-inline-recursive-depth=2000} # default value\n\nfor ((i=1; i<16; ++i)); do\n    echo \"Matrix size: $i x $i :\"\n    $CXX -O3 -I.. -DNDEBUG  benchmark.cpp -DMATSIZE=$i -DEIGEN_UNROLLING_LIMIT=400 -o benchmark && time ./benchmark >/dev/null\n    $CXX -O3 -I.. -DNDEBUG -finline-limit=10000 benchmark.cpp -DMATSIZE=$i -DEIGEN_DONT_USE_UNROLLED_LOOPS=1 -o benchmark && time ./benchmark >/dev/null\n    echo \" \"\ndone\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/benchmark-blocking-sizes.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Jacob <benoitjacob@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <iostream>\n#include <cstdint>\n#include <cstdlib>\n#include <vector>\n#include <fstream>\n#include <memory>\n#include <cstdio>\n\nbool eigen_use_specific_block_size;\nint eigen_block_size_k, eigen_block_size_m, eigen_block_size_n;\n#define EIGEN_TEST_SPECIFIC_BLOCKING_SIZES eigen_use_specific_block_size\n#define EIGEN_TEST_SPECIFIC_BLOCKING_SIZE_K eigen_block_size_k\n#define EIGEN_TEST_SPECIFIC_BLOCKING_SIZE_M eigen_block_size_m\n#define EIGEN_TEST_SPECIFIC_BLOCKING_SIZE_N eigen_block_size_n\n#include <Eigen/Core>\n\n#include <bench/BenchTimer.h>\n\nusing namespace Eigen;\nusing namespace std;\n\nstatic BenchTimer timer;\n\n// how many times we repeat each measurement.\n// measurements are randomly shuffled - we're not doing\n// all N identical measurements in a row.\nconst int measurement_repetitions = 3;\n\n// Timings below this value are too short to be accurate,\n// we'll repeat measurements with more iterations until\n// we get a timing above that threshold.\nconst float min_accurate_time = 1e-2f;\n\n// See --min-working-set-size command line parameter.\nsize_t min_working_set_size = 0;\n\nfloat max_clock_speed = 0.0f;\n\n// range of sizes that we will benchmark (in all 3 K,M,N dimensions)\nconst size_t maxsize = 2048;\nconst size_t minsize = 16;\n\ntypedef MatrixXf MatrixType;\ntypedef MatrixType::Scalar Scalar;\ntypedef internal::packet_traits<Scalar>::type Packet;\n\nstatic_assert((maxsize & (maxsize - 1)) == 0, \"maxsize must be a power of two\");\nstatic_assert((minsize & (minsize - 1)) == 0, \"minsize must be a power of two\");\nstatic_assert(maxsize > minsize, \"maxsize must be larger than minsize\");\nstatic_assert(maxsize < (minsize << 16), \"maxsize must be less than (minsize<<16)\");\n\n// just a helper to store a triple of K,M,N sizes for matrix product\nstruct size_triple_t\n{\n  size_t k, m, n;\n  size_triple_t() : k(0), m(0), n(0) {}\n  size_triple_t(size_t _k, size_t _m, size_t _n) : k(_k), m(_m), n(_n) {}\n  size_triple_t(const size_triple_t& o) : k(o.k), m(o.m), n(o.n) {}\n  size_triple_t(uint16_t compact)\n  {\n    k = 1 << ((compact & 0xf00) >> 8);\n    m = 1 << ((compact & 0x0f0) >> 4);\n    n = 1 << ((compact & 0x00f) >> 0);\n  }\n};\n\nuint8_t log2_pot(size_t x) {\n  size_t l = 0;\n  while (x >>= 1) l++;\n  return l;\n}\n\n// Convert between size tripes and a compact form fitting in 12 bits\n// where each size, which must be a POT, is encoded as its log2, on 4 bits\n// so the largest representable size is 2^15 == 32k  ... big enough.\nuint16_t compact_size_triple(size_t k, size_t m, size_t n)\n{\n  return (log2_pot(k) << 8) | (log2_pot(m) << 4) | log2_pot(n);\n}\n\nuint16_t compact_size_triple(const size_triple_t& t)\n{\n  return compact_size_triple(t.k, t.m, t.n);\n}\n\n// A single benchmark. Initially only contains benchmark params.\n// Then call run(), which stores the result in the gflops field.\nstruct benchmark_t\n{\n  uint16_t compact_product_size;\n  uint16_t compact_block_size;\n  bool use_default_block_size;\n  float gflops;\n  benchmark_t()\n    : compact_product_size(0)\n    , compact_block_size(0)\n    , use_default_block_size(false)\n    , gflops(0)\n  {\n  }\n  benchmark_t(size_t pk, size_t pm, size_t pn,\n              size_t bk, size_t bm, size_t bn)\n    : compact_product_size(compact_size_triple(pk, pm, pn))\n    , compact_block_size(compact_size_triple(bk, bm, bn))\n    , use_default_block_size(false)\n    , gflops(0)\n  {}\n  benchmark_t(size_t pk, size_t pm, size_t pn)\n    : compact_product_size(compact_size_triple(pk, pm, pn))\n    , compact_block_size(0)\n    , use_default_block_size(true)\n    , gflops(0)\n  {}\n\n  void run();\n};\n\nostream& operator<<(ostream& s, const benchmark_t& b)\n{\n  s << hex << b.compact_product_size << dec;\n  if (b.use_default_block_size) {\n    size_triple_t t(b.compact_product_size);\n    Index k = t.k, m = t.m, n = t.n;\n    internal::computeProductBlockingSizes<Scalar, Scalar>(k, m, n);\n    s << \" default(\" << k << \", \" << m << \", \" << n << \")\";\n  } else {\n    s << \" \" << hex << b.compact_block_size << dec;\n  }\n  s << \" \" << b.gflops;\n  return s;\n}\n\n// We sort first by increasing benchmark parameters,\n// then by decreasing performance.\nbool operator<(const benchmark_t& b1, const benchmark_t& b2)\n{ \n  return b1.compact_product_size < b2.compact_product_size ||\n           (b1.compact_product_size == b2.compact_product_size && (\n             (b1.compact_block_size < b2.compact_block_size || (\n               b1.compact_block_size == b2.compact_block_size &&\n                 b1.gflops > b2.gflops))));\n}\n\nvoid benchmark_t::run()\n{\n  size_triple_t productsizes(compact_product_size);\n\n  if (use_default_block_size) {\n    eigen_use_specific_block_size = false;\n  } else {\n    // feed eigen with our custom blocking params\n    eigen_use_specific_block_size = true;\n    size_triple_t blocksizes(compact_block_size);\n    eigen_block_size_k = blocksizes.k;\n    eigen_block_size_m = blocksizes.m;\n    eigen_block_size_n = blocksizes.n;\n  }\n\n  // set up the matrix pool\n\n  const size_t combined_three_matrices_sizes =\n    sizeof(Scalar) *\n      (productsizes.k * productsizes.m +\n       productsizes.k * productsizes.n +\n       productsizes.m * productsizes.n);\n\n  // 64 M is large enough that nobody has a cache bigger than that,\n  // while still being small enough that everybody has this much RAM,\n  // so conveniently we don't need to special-case platforms here.\n  const size_t unlikely_large_cache_size = 64 << 20;\n\n  const size_t working_set_size =\n    min_working_set_size ? min_working_set_size : unlikely_large_cache_size;\n\n  const size_t matrix_pool_size =\n    1 + working_set_size / combined_three_matrices_sizes;\n\n  MatrixType *lhs = new MatrixType[matrix_pool_size];\n  MatrixType *rhs = new MatrixType[matrix_pool_size];\n  MatrixType *dst = new MatrixType[matrix_pool_size];\n  \n  for (size_t i = 0; i < matrix_pool_size; i++) {\n    lhs[i] = MatrixType::Zero(productsizes.m, productsizes.k);\n    rhs[i] = MatrixType::Zero(productsizes.k, productsizes.n);\n    dst[i] = MatrixType::Zero(productsizes.m, productsizes.n);\n  }\n\n  // main benchmark loop\n\n  int iters_at_a_time = 1;\n  float time_per_iter = 0.0f;\n  size_t matrix_index = 0;\n  while (true) {\n\n    double starttime = timer.getCpuTime();\n    for (int i = 0; i < iters_at_a_time; i++) {\n      dst[matrix_index].noalias() = lhs[matrix_index] * rhs[matrix_index];\n      matrix_index++;\n      if (matrix_index == matrix_pool_size) {\n        matrix_index = 0;\n      }\n    }\n    double endtime = timer.getCpuTime();\n\n    const float timing = float(endtime - starttime);\n\n    if (timing >= min_accurate_time) {\n      time_per_iter = timing / iters_at_a_time;\n      break;\n    }\n\n    iters_at_a_time *= 2;\n  }\n\n  delete[] lhs;\n  delete[] rhs;\n  delete[] dst;\n\n  gflops = 2e-9 * productsizes.k * productsizes.m * productsizes.n / time_per_iter;\n}\n\nvoid print_cpuinfo()\n{\n#ifdef __linux__\n  cout << \"contents of /proc/cpuinfo:\" << endl;\n  string line;\n  ifstream cpuinfo(\"/proc/cpuinfo\");\n  if (cpuinfo.is_open()) {\n    while (getline(cpuinfo, line)) {\n      cout << line << endl;\n    }\n    cpuinfo.close();\n  }\n  cout << endl;\n#elif defined __APPLE__\n  cout << \"output of sysctl hw:\" << endl;\n  system(\"sysctl hw\");\n  cout << endl;\n#endif\n}\n\ntemplate <typename T>\nstring type_name()\n{\n  return \"unknown\";\n}\n\ntemplate<>\nstring type_name<float>()\n{\n  return \"float\";\n}\n\ntemplate<>\nstring type_name<double>()\n{\n  return \"double\";\n}\n\nstruct action_t\n{\n  virtual const char* invokation_name() const { abort(); return nullptr; }\n  virtual void run() const { abort(); }\n  virtual ~action_t() {}\n};\n\nvoid show_usage_and_exit(int /*argc*/, char* argv[],\n                         const vector<unique_ptr<action_t>>& available_actions)\n{\n  cerr << \"usage: \" << argv[0] << \" <action> [options...]\" << endl << endl;\n  cerr << \"available actions:\" << endl << endl;\n  for (auto it = available_actions.begin(); it != available_actions.end(); ++it) {\n    cerr << \"  \" << (*it)->invokation_name() << endl;\n  }\n  cerr << endl;\n  cerr << \"options:\" << endl << endl;\n  cerr << \"  --min-working-set-size=N:\" << endl;\n  cerr << \"       Set the minimum working set size to N bytes.\" << endl;\n  cerr << \"       This is rounded up as needed to a multiple of matrix size.\" << endl;\n  cerr << \"       A larger working set lowers the chance of a warm cache.\" << endl;\n  cerr << \"       The default value 0 means use a large enough working\" << endl;\n  cerr << \"       set to likely outsize caches.\" << endl;\n  cerr << \"       A value of 1 (that is, 1 byte) would mean don't do anything to\" << endl;\n  cerr << \"       avoid warm caches.\" << endl;\n  exit(1);\n}\n     \nfloat measure_clock_speed()\n{\n  cerr << \"Measuring clock speed...                              \\r\" << flush;\n          \n  vector<float> all_gflops;\n  for (int i = 0; i < 8; i++) {\n    benchmark_t b(1024, 1024, 1024);\n    b.run();\n    all_gflops.push_back(b.gflops);\n  }\n\n  sort(all_gflops.begin(), all_gflops.end());\n  float stable_estimate = all_gflops[2] + all_gflops[3] + all_gflops[4] + all_gflops[5];\n\n  // multiply by an arbitrary constant to discourage trying doing anything with the\n  // returned values besides just comparing them with each other.\n  float result = stable_estimate * 123.456f;\n\n  return result;\n}\n\nstruct human_duration_t\n{\n  int seconds;\n  human_duration_t(int s) : seconds(s) {}\n};\n\nostream& operator<<(ostream& s, const human_duration_t& d)\n{\n  int remainder = d.seconds;\n  if (remainder > 3600) {\n    int hours = remainder / 3600;\n    s << hours << \" h \";\n    remainder -= hours * 3600;\n  }\n  if (remainder > 60) {\n    int minutes = remainder / 60;\n    s << minutes << \" min \";\n    remainder -= minutes * 60;\n  }\n  if (d.seconds < 600) {\n    s << remainder << \" s\";\n  }\n  return s;\n}\n\nconst char session_filename[] = \"/data/local/tmp/benchmark-blocking-sizes-session.data\";\n\nvoid serialize_benchmarks(const char* filename, const vector<benchmark_t>& benchmarks, size_t first_benchmark_to_run)\n{\n  FILE* file = fopen(filename, \"w\");\n  if (!file) {\n    cerr << \"Could not open file \" << filename << \" for writing.\" << endl;\n    cerr << \"Do you have write permissions on the current working directory?\" << endl;\n    exit(1);\n  }\n  size_t benchmarks_vector_size = benchmarks.size();\n  fwrite(&max_clock_speed, sizeof(max_clock_speed), 1, file);\n  fwrite(&benchmarks_vector_size, sizeof(benchmarks_vector_size), 1, file);\n  fwrite(&first_benchmark_to_run, sizeof(first_benchmark_to_run), 1, file);\n  fwrite(benchmarks.data(), sizeof(benchmark_t), benchmarks.size(), file);\n  fclose(file);\n}\n\nbool deserialize_benchmarks(const char* filename, vector<benchmark_t>& benchmarks, size_t& first_benchmark_to_run)\n{\n  FILE* file = fopen(filename, \"r\");\n  if (!file) {\n    return false;\n  }\n  if (1 != fread(&max_clock_speed, sizeof(max_clock_speed), 1, file)) {\n    return false;\n  }\n  size_t benchmarks_vector_size = 0;\n  if (1 != fread(&benchmarks_vector_size, sizeof(benchmarks_vector_size), 1, file)) {\n    return false;\n  }\n  if (1 != fread(&first_benchmark_to_run, sizeof(first_benchmark_to_run), 1, file)) {\n    return false;\n  }\n  benchmarks.resize(benchmarks_vector_size);\n  if (benchmarks.size() != fread(benchmarks.data(), sizeof(benchmark_t), benchmarks.size(), file)) {\n    return false;\n  }\n  unlink(filename);\n  return true;\n}\n\nvoid try_run_some_benchmarks(\n  vector<benchmark_t>& benchmarks,\n  double time_start,\n  size_t& first_benchmark_to_run)\n{\n  if (first_benchmark_to_run == benchmarks.size()) {\n    return;\n  }\n\n  double time_last_progress_update = 0;\n  double time_last_clock_speed_measurement = 0;\n  double time_now = 0;\n\n  size_t benchmark_index = first_benchmark_to_run;\n\n  while (true) {\n    float ratio_done = float(benchmark_index) / benchmarks.size();\n    time_now = timer.getRealTime();\n\n    // We check clock speed every minute and at the end.\n    if (benchmark_index == benchmarks.size() ||\n        time_now > time_last_clock_speed_measurement + 60.0f)\n    {\n      time_last_clock_speed_measurement = time_now;\n\n      // Ensure that clock speed is as expected\n      float current_clock_speed = measure_clock_speed();\n\n      // The tolerance needs to be smaller than the relative difference between\n      // clock speeds that a device could operate under.\n      // It seems unlikely that a device would be throttling clock speeds by\n      // amounts smaller than 2%.\n      // With a value of 1%, I was getting within noise on a Sandy Bridge.\n      const float clock_speed_tolerance = 0.02f;\n\n      if (current_clock_speed > (1 + clock_speed_tolerance) * max_clock_speed) {\n        // Clock speed is now higher than we previously measured.\n        // Either our initial measurement was inaccurate, which won't happen\n        // too many times as we are keeping the best clock speed value and\n        // and allowing some tolerance; or something really weird happened,\n        // which invalidates all benchmark results collected so far.\n        // Either way, we better restart all over again now.\n        if (benchmark_index) {\n          cerr << \"Restarting at \" << 100.0f * ratio_done\n               << \" % because clock speed increased.          \" << endl;\n        }\n        max_clock_speed = current_clock_speed;\n        first_benchmark_to_run = 0;\n        return;\n      }\n\n      bool rerun_last_tests = false;\n\n      if (current_clock_speed < (1 - clock_speed_tolerance) * max_clock_speed) {\n        cerr << \"Measurements completed so far: \"\n             << 100.0f * ratio_done\n             << \" %                             \" << endl;\n        cerr << \"Clock speed seems to be only \"\n             << current_clock_speed/max_clock_speed\n             << \" times what it used to be.\" << endl;\n\n        unsigned int seconds_to_sleep_if_lower_clock_speed = 1;\n\n        while (current_clock_speed < (1 - clock_speed_tolerance) * max_clock_speed) {\n          if (seconds_to_sleep_if_lower_clock_speed > 32) {\n            cerr << \"Sleeping longer probably won't make a difference.\" << endl;\n            cerr << \"Serializing benchmarks to \" << session_filename << endl;\n            serialize_benchmarks(session_filename, benchmarks, first_benchmark_to_run);\n            cerr << \"Now restart this benchmark, and it should pick up where we left.\" << endl;\n            exit(2);\n          }\n          rerun_last_tests = true;\n          cerr << \"Sleeping \"\n               << seconds_to_sleep_if_lower_clock_speed\n               << \" s...                                   \\r\" << endl;\n          sleep(seconds_to_sleep_if_lower_clock_speed);\n          current_clock_speed = measure_clock_speed();\n          seconds_to_sleep_if_lower_clock_speed *= 2;\n        }\n      }\n\n      if (rerun_last_tests) {\n        cerr << \"Redoing the last \"\n             << 100.0f * float(benchmark_index - first_benchmark_to_run) / benchmarks.size()\n             << \" % because clock speed had been low.   \" << endl;\n        return;\n      }\n\n      // nothing wrong with the clock speed so far, so there won't be a need to rerun\n      // benchmarks run so far in case we later encounter a lower clock speed.\n      first_benchmark_to_run = benchmark_index;\n    }\n\n    if (benchmark_index == benchmarks.size()) {\n      // We're done!\n      first_benchmark_to_run = benchmarks.size();\n      // Erase progress info\n      cerr << \"                                                            \" << endl;\n      return;\n    }\n\n    // Display progress info on stderr\n    if (time_now > time_last_progress_update + 1.0f) {\n      time_last_progress_update = time_now;\n      cerr << \"Measurements... \" << 100.0f * ratio_done\n           << \" %, ETA \"\n           << human_duration_t(float(time_now - time_start) * (1.0f - ratio_done) / ratio_done)\n           << \"                          \\r\" << flush;\n    }\n\n    // This is where we actually run a benchmark!\n    benchmarks[benchmark_index].run();\n    benchmark_index++;\n  }\n}\n\nvoid run_benchmarks(vector<benchmark_t>& benchmarks)\n{\n  size_t first_benchmark_to_run;\n  vector<benchmark_t> deserialized_benchmarks;\n  bool use_deserialized_benchmarks = false;\n  if (deserialize_benchmarks(session_filename, deserialized_benchmarks, first_benchmark_to_run)) {\n    cerr << \"Found serialized session with \"\n         << 100.0f * first_benchmark_to_run / deserialized_benchmarks.size()\n         << \" % already done\" << endl;\n    if (deserialized_benchmarks.size() == benchmarks.size() &&\n        first_benchmark_to_run > 0 &&\n        first_benchmark_to_run < benchmarks.size())\n    {\n      use_deserialized_benchmarks = true;\n    }\n  }\n\n  if (use_deserialized_benchmarks) {\n    benchmarks = deserialized_benchmarks;\n  } else {\n    // not using deserialized benchmarks, starting from scratch\n    first_benchmark_to_run = 0;\n\n    // Randomly shuffling benchmarks allows us to get accurate enough progress info,\n    // as now the cheap/expensive benchmarks are randomly mixed so they average out.\n    // It also means that if data is corrupted for some time span, the odds are that\n    // not all repetitions of a given benchmark will be corrupted.\n    random_shuffle(benchmarks.begin(), benchmarks.end());\n  }\n\n  for (int i = 0; i < 4; i++) {\n    max_clock_speed = max(max_clock_speed, measure_clock_speed());\n  }\n  \n  double time_start = 0.0;\n  while (first_benchmark_to_run < benchmarks.size()) {\n    if (first_benchmark_to_run == 0) {\n      time_start = timer.getRealTime();\n    }\n    try_run_some_benchmarks(benchmarks,\n                            time_start,\n                            first_benchmark_to_run);\n  }\n\n  // Sort timings by increasing benchmark parameters, and decreasing gflops.\n  // The latter is very important. It means that we can ignore all but the first\n  // benchmark with given parameters.\n  sort(benchmarks.begin(), benchmarks.end());\n\n  // Collect best (i.e. now first) results for each parameter values.\n  vector<benchmark_t> best_benchmarks;\n  for (auto it = benchmarks.begin(); it != benchmarks.end(); ++it) {\n    if (best_benchmarks.empty() ||\n        best_benchmarks.back().compact_product_size != it->compact_product_size ||\n        best_benchmarks.back().compact_block_size != it->compact_block_size)\n    {\n      best_benchmarks.push_back(*it);\n    }\n  }\n\n  // keep and return only the best benchmarks\n  benchmarks = best_benchmarks;\n}\n\nstruct measure_all_pot_sizes_action_t : action_t\n{\n  virtual const char* invokation_name() const { return \"all-pot-sizes\"; }\n  virtual void run() const\n  {\n    vector<benchmark_t> benchmarks;\n    for (int repetition = 0; repetition < measurement_repetitions; repetition++) {\n      for (size_t ksize = minsize; ksize <= maxsize; ksize *= 2) {\n        for (size_t msize = minsize; msize <= maxsize; msize *= 2) {\n          for (size_t nsize = minsize; nsize <= maxsize; nsize *= 2) {\n            for (size_t kblock = minsize; kblock <= ksize; kblock *= 2) {\n              for (size_t mblock = minsize; mblock <= msize; mblock *= 2) {\n                for (size_t nblock = minsize; nblock <= nsize; nblock *= 2) {\n                  benchmarks.emplace_back(ksize, msize, nsize, kblock, mblock, nblock);\n                }\n              }\n            }\n          }\n        }\n      }\n    }\n\n    run_benchmarks(benchmarks);\n\n    cout << \"BEGIN MEASUREMENTS ALL POT SIZES\" << endl;\n    for (auto it = benchmarks.begin(); it != benchmarks.end(); ++it) {\n      cout << *it << endl;\n    }\n  }\n};\n\nstruct measure_default_sizes_action_t : action_t\n{\n  virtual const char* invokation_name() const { return \"default-sizes\"; }\n  virtual void run() const\n  {\n    vector<benchmark_t> benchmarks;\n    for (int repetition = 0; repetition < measurement_repetitions; repetition++) {\n      for (size_t ksize = minsize; ksize <= maxsize; ksize *= 2) {\n        for (size_t msize = minsize; msize <= maxsize; msize *= 2) {\n          for (size_t nsize = minsize; nsize <= maxsize; nsize *= 2) {\n            benchmarks.emplace_back(ksize, msize, nsize);\n          }\n        }\n      }\n    }\n\n    run_benchmarks(benchmarks);\n\n    cout << \"BEGIN MEASUREMENTS DEFAULT SIZES\" << endl;\n    for (auto it = benchmarks.begin(); it != benchmarks.end(); ++it) {\n      cout << *it << endl;\n    }\n  }\n};\n\nint main(int argc, char* argv[])\n{\n  double time_start = timer.getRealTime();\n  cout.precision(4);\n  cerr.precision(4);\n\n  vector<unique_ptr<action_t>> available_actions;\n  available_actions.emplace_back(new measure_all_pot_sizes_action_t);\n  available_actions.emplace_back(new measure_default_sizes_action_t);\n\n  auto action = available_actions.end();\n\n  if (argc <= 1) {\n    show_usage_and_exit(argc, argv, available_actions);\n  }\n  for (auto it = available_actions.begin(); it != available_actions.end(); ++it) {\n    if (!strcmp(argv[1], (*it)->invokation_name())) {\n      action = it;\n      break;\n    }\n  }\n\n  if (action == available_actions.end()) {\n    show_usage_and_exit(argc, argv, available_actions);\n  }\n\n  for (int i = 2; i < argc; i++) {\n    if (argv[i] == strstr(argv[i], \"--min-working-set-size=\")) {\n      const char* equals_sign = strchr(argv[i], '=');\n      min_working_set_size = strtoul(equals_sign+1, nullptr, 10);\n    } else {\n      cerr << \"unrecognized option: \" << argv[i] << endl << endl;\n      show_usage_and_exit(argc, argv, available_actions);\n    }\n  }\n\n  print_cpuinfo();\n\n  cout << \"benchmark parameters:\" << endl;\n  cout << \"pointer size: \" << 8*sizeof(void*) << \" bits\" << endl;\n  cout << \"scalar type: \" << type_name<Scalar>() << endl;\n  cout << \"packet size: \" << internal::packet_traits<MatrixType::Scalar>::size << endl;\n  cout << \"minsize = \" << minsize << endl;\n  cout << \"maxsize = \" << maxsize << endl;\n  cout << \"measurement_repetitions = \" << measurement_repetitions << endl;\n  cout << \"min_accurate_time = \" << min_accurate_time << endl;\n  cout << \"min_working_set_size = \" << min_working_set_size;\n  if (min_working_set_size == 0) {\n    cout << \" (try to outsize caches)\";\n  }\n  cout << endl << endl;\n\n  (*action)->run();\n\n  double time_end = timer.getRealTime();\n  cerr << \"Finished in \" << human_duration_t(time_end - time_start) << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/benchmark.cpp",
    "content": "// g++ -O3 -DNDEBUG -DMATSIZE=<x> benchmark.cpp -o benchmark && time ./benchmark\n\n#include <iostream>\n\n#include <Eigen/Core>\n\n#ifndef MATSIZE\n#define MATSIZE 3\n#endif\n\nusing namespace std;\nusing namespace Eigen;\n\n#ifndef REPEAT\n#define REPEAT 40000000\n#endif\n\n#ifndef SCALAR\n#define SCALAR double\n#endif\n\nint main(int argc, char *argv[])\n{\n    Matrix<SCALAR,MATSIZE,MATSIZE> I = Matrix<SCALAR,MATSIZE,MATSIZE>::Ones();\n    Matrix<SCALAR,MATSIZE,MATSIZE> m;\n    for(int i = 0; i < MATSIZE; i++)\n        for(int j = 0; j < MATSIZE; j++)\n        {\n            m(i,j) = (i+MATSIZE*j);\n        }\n    asm(\"#begin\");\n    for(int a = 0; a < REPEAT; a++)\n    {\n        m = Matrix<SCALAR,MATSIZE,MATSIZE>::Ones() + 0.00005 * (m + (m*m));\n    }\n    asm(\"#end\");\n    cout << m << endl;\n    return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/benchmarkSlice.cpp",
    "content": "// g++ -O3 -DNDEBUG benchmarkX.cpp -o benchmarkX && time ./benchmarkX\n\n#include <iostream>\n\n#include <Eigen/Core>\n\nusing namespace std;\nusing namespace Eigen;\n\n#ifndef REPEAT\n#define REPEAT 10000\n#endif\n\n#ifndef SCALAR\n#define SCALAR float\n#endif\n\nint main(int argc, char *argv[])\n{\n  typedef Matrix<SCALAR, Eigen::Dynamic, Eigen::Dynamic> Mat;\n  Mat m(100, 100);\n  m.setRandom();\n\n  for(int a = 0; a < REPEAT; a++)\n  {\n    int r, c, nr, nc;\n    r = Eigen::internal::random<int>(0,10);\n    c = Eigen::internal::random<int>(0,10);\n    nr = Eigen::internal::random<int>(50,80);\n    nc = Eigen::internal::random<int>(50,80);\n    m.block(r,c,nr,nc) += Mat::Ones(nr,nc);\n    m.block(r,c,nr,nc) *= SCALAR(10);\n    m.block(r,c,nr,nc) -= Mat::constant(nr,nc,10);\n    m.block(r,c,nr,nc) /= SCALAR(10);\n  }\n  cout << m[0] << endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/benchmarkX.cpp",
    "content": "// g++ -fopenmp -I .. -O3 -DNDEBUG -finline-limit=1000 benchmarkX.cpp -o b && time ./b\n\n#include <iostream>\n\n#include <Eigen/Core>\n\nusing namespace std;\nusing namespace Eigen;\n\n#ifndef MATTYPE\n#define MATTYPE MatrixXLd\n#endif\n\n#ifndef MATSIZE\n#define MATSIZE 400\n#endif\n\n#ifndef REPEAT\n#define REPEAT 100\n#endif\n\nint main(int argc, char *argv[])\n{\n\tMATTYPE I = MATTYPE::Ones(MATSIZE,MATSIZE);\n\tMATTYPE m(MATSIZE,MATSIZE);\n\tfor(int i = 0; i < MATSIZE; i++) for(int j = 0; j < MATSIZE; j++)\n\t{\n\t\tm(i,j) = (i+j+1)/(MATSIZE*MATSIZE);\n\t}\n\tfor(int a = 0; a < REPEAT; a++)\n\t{\n\t\tm = I + 0.0001 * (m + m*m);\n\t}\n\tcout << m(0,0) << endl;\n\treturn 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/benchmarkXcwise.cpp",
    "content": "// g++ -O3 -DNDEBUG benchmarkX.cpp -o benchmarkX && time ./benchmarkX\n\n#include <iostream>\n#include <Eigen/Core>\n\nusing namespace std;\nusing namespace Eigen;\n\n#ifndef VECTYPE\n#define VECTYPE VectorXLd\n#endif\n\n#ifndef VECSIZE\n#define VECSIZE 1000000\n#endif\n\n#ifndef REPEAT\n#define REPEAT 1000\n#endif\n\nint main(int argc, char *argv[])\n{\n\tVECTYPE I = VECTYPE::Ones(VECSIZE);\n\tVECTYPE m(VECSIZE,1);\n\tfor(int i = 0; i < VECSIZE; i++)\n\t{\n\t\tm[i] = 0.1 * i/VECSIZE;\n\t}\n\tfor(int a = 0; a < REPEAT; a++)\n\t{\n\t\tm = VECTYPE::Ones(VECSIZE) + 0.00005 * (m.cwise().square() + m/4);\n\t}\n\tcout << m[0] << endl;\n\treturn 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/benchmark_suite",
    "content": "#!/bin/bash\nCXX=${CXX-g++} # default value unless caller has defined CXX\necho \"Fixed size 3x3, column-major, -DNDEBUG\"\n$CXX -O3 -I .. -DNDEBUG benchmark.cpp -o benchmark && time ./benchmark >/dev/null\necho \"Fixed size 3x3, column-major, with asserts\"\n$CXX -O3 -I .. benchmark.cpp -o benchmark && time ./benchmark >/dev/null\necho \"Fixed size 3x3, row-major, -DNDEBUG\"\n$CXX -O3 -I .. -DEIGEN_DEFAULT_TO_ROW_MAJOR -DNDEBUG benchmark.cpp -o benchmark && time ./benchmark >/dev/null\necho \"Fixed size 3x3, row-major, with asserts\"\n$CXX -O3 -I .. -DEIGEN_DEFAULT_TO_ROW_MAJOR benchmark.cpp -o benchmark && time ./benchmark >/dev/null\necho \"Dynamic size 20x20, column-major, -DNDEBUG\"\n$CXX -O3 -I .. -DNDEBUG benchmarkX.cpp -o benchmarkX && time ./benchmarkX >/dev/null\necho \"Dynamic size 20x20, column-major, with asserts\"\n$CXX -O3 -I .. benchmarkX.cpp -o benchmarkX && time ./benchmarkX >/dev/null\necho \"Dynamic size 20x20, row-major, -DNDEBUG\"\n$CXX -O3 -I .. -DEIGEN_DEFAULT_TO_ROW_MAJOR -DNDEBUG benchmarkX.cpp -o benchmarkX && time ./benchmarkX >/dev/null\necho \"Dynamic size 20x20, row-major, with asserts\"\n$CXX -O3 -I .. -DEIGEN_DEFAULT_TO_ROW_MAJOR benchmarkX.cpp -o benchmarkX && time ./benchmarkX >/dev/null\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/CMakeLists.txt",
    "content": "project(BTL)\n\ncmake_minimum_required(VERSION 2.6.2)\n\nset(CMAKE_MODULE_PATH ${PROJECT_SOURCE_DIR}/cmake ${Eigen_SOURCE_DIR}/cmake)\ninclude(MacroOptionalAddSubdirectory)\n\noption(BTL_NOVEC \"Disable SSE/Altivec optimizations when possible\" OFF)\n\nset(CMAKE_INCLUDE_CURRENT_DIR ON)\n\nstring(REGEX MATCH icpc IS_ICPC ${CMAKE_CXX_COMPILER})\nif(CMAKE_COMPILER_IS_GNUCXX OR IS_ICPC)\n  set(CMAKE_CXX_FLAGS \"-g0 -O3 -DNDEBUG ${CMAKE_CXX_FLAGS}\")\n  set(CMAKE_Fortran_FLAGS \"-g0 -O3 -DNDEBUG ${CMAKE_Fortran_FLAGS}\")\n  if(BTL_NOVEC)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -DEIGEN_DONT_VECTORIZE\")\n  endif(BTL_NOVEC)\nendif(CMAKE_COMPILER_IS_GNUCXX OR IS_ICPC)\n\nif(MSVC)\n  set(CMAKE_CXX_FLAGS \" /O2 /Ot /GL /fp:fast -DNDEBUG\")\n#   set(CMAKE_Fortran_FLAGS \"-g0 -O3 -DNDEBUG\")\n  if(BTL_NOVEC)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -DEIGEN_DONT_VECTORIZE\")\n  endif(BTL_NOVEC)\nendif(MSVC)\n\nif(IS_ICPC)\n  set(CMAKE_CXX_FLAGS \"-fast ${CMAKE_CXX_FLAGS}\")\n  set(CMAKE_Fortran_FLAGS \"-fast ${CMAKE_Fortran_FLAGS}\")\nendif()\n\ninclude_directories(\n  ${PROJECT_SOURCE_DIR}/actions\n  ${PROJECT_SOURCE_DIR}/generic_bench\n  ${PROJECT_SOURCE_DIR}/generic_bench/utils\n  ${PROJECT_SOURCE_DIR}/libs/STL)\n\n# find_package(MKL)\n# if (MKL_FOUND)\n#   add_definitions(-DHAVE_MKL)\n#   set(DEFAULT_LIBRARIES ${MKL_LIBRARIES})\n# endif ()\n\nfind_library(EIGEN_BTL_RT_LIBRARY rt)\n# if we cannot find it easily, then we don't need it!\nif(NOT EIGEN_BTL_RT_LIBRARY)\n  set(EIGEN_BTL_RT_LIBRARY \"\")\nendif()\n\nmacro(BTL_ADD_BENCH targetname)\n\n  foreach(_current_var ${ARGN})\n    set(_last_var ${_current_var})\n  endforeach()\n\n  set(_sources ${ARGN})\n  list(LENGTH _sources _argn_length)\n\n  list(REMOVE_ITEM _sources ON OFF TRUE FALSE)\n\n  list(LENGTH _sources _src_length)\n\n  if (${_argn_length} EQUAL ${_src_length})\n    set(_last_var ON)\n  endif ()\n\n  option(BUILD_${targetname} \"Build benchmark ${targetname}\" ${_last_var})\n\n  if(BUILD_${targetname})\n    add_executable(${targetname} ${_sources})\n    add_test(${targetname} \"${targetname}\")\n    target_link_libraries(${targetname} ${DEFAULT_LIBRARIES} ${EIGEN_BTL_RT_LIBRARY})\n  endif(BUILD_${targetname})\n\nendmacro(BTL_ADD_BENCH)\n\nmacro(btl_add_target_property target prop value)\n\n  if(BUILD_${target})\n    get_target_property(previous ${target} ${prop})\n    if(NOT previous)\n      set(previous \"\")\n    endif()\n    set_target_properties(${target} PROPERTIES ${prop} \"${previous} ${value}\")\n  endif()\n\nendmacro()\n\nenable_testing()\n\nadd_subdirectory(libs/eigen3)\nadd_subdirectory(libs/eigen2)\nadd_subdirectory(libs/tensors)\nadd_subdirectory(libs/BLAS)\nadd_subdirectory(libs/ublas)\nadd_subdirectory(libs/gmm)\nadd_subdirectory(libs/mtl4)\nadd_subdirectory(libs/blitz)\nadd_subdirectory(libs/tvmet)\nadd_subdirectory(libs/STL)\nadd_subdirectory(libs/blaze)\n\nadd_subdirectory(data)\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/COPYING",
    "content": "                    GNU GENERAL PUBLIC LICENSE\n                       Version 2, June 1991\n\n Copyright (C) 1989, 1991 Free Software Foundation, Inc.\n                       59 Temple Place, Suite 330, Boston, MA  02111-1307  USA\n Everyone is permitted to copy and distribute verbatim copies\n of this license document, but changing it is not allowed.\n\n                            Preamble\n\n  The licenses for most software are designed to take away your\nfreedom to share and change it.  By contrast, the GNU General Public\nLicense is intended to guarantee your freedom to share and change free\nsoftware--to make sure the software is free for all its users.  This\nGeneral Public License applies to most of the Free Software\nFoundation's software and to any other program whose authors commit to\nusing it.  (Some other Free Software Foundation software is covered by\nthe GNU Library General Public License instead.)  You can apply it to\nyour programs, too.\n\n  When we speak of free software, we are referring to freedom, not\nprice.  Our General Public Licenses are designed to make sure that you\nhave the freedom to distribute copies of free software (and charge for\nthis service if you wish), that you receive source code or can get it\nif you want it, that you can change the software or use pieces of it\nin new free programs; and that you know you can do these things.\n\n  To protect your rights, we need to make restrictions that forbid\nanyone to deny you these rights or to ask you to surrender the rights.\nThese restrictions translate to certain responsibilities for you if you\ndistribute copies of the software, or if you modify it.\n\n  For example, if you distribute copies of such a program, whether\ngratis or for a fee, you must give the recipients all the rights that\nyou have.  You must make sure that they, too, receive or can get the\nsource code.  And you must show them these terms so they know their\nrights.\n\n  We protect your rights with two steps: (1) copyright the software, and\n(2) offer you this license which gives you legal permission to copy,\ndistribute and/or modify the software.\n\n  Also, for each author's protection and ours, we want to make certain\nthat everyone understands that there is no warranty for this free\nsoftware.  If the software is modified by someone else and passed on, we\nwant its recipients to know that what they have is not the original, so\nthat any problems introduced by others will not reflect on the original\nauthors' reputations.\n\n  Finally, any free program is threatened constantly by software\npatents.  We wish to avoid the danger that redistributors of a free\nprogram will individually obtain patent licenses, in effect making the\nprogram proprietary.  To prevent this, we have made it clear that any\npatent must be licensed for everyone's free use or not licensed at all.\n\n  The precise terms and conditions for copying, distribution and\nmodification follow.\n\n                    GNU GENERAL PUBLIC LICENSE\n   TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION\n\n  0. This License applies to any program or other work which contains\na notice placed by the copyright holder saying it may be distributed\nunder the terms of this General Public License.  The \"Program\", below,\nrefers to any such program or work, and a \"work based on the Program\"\nmeans either the Program or any derivative work under copyright law:\nthat is to say, a work containing the Program or a portion of it,\neither verbatim or with modifications and/or translated into another\nlanguage.  (Hereinafter, translation is included without limitation in\nthe term \"modification\".)  Each licensee is addressed as \"you\".\n\nActivities other than copying, distribution and modification are not\ncovered by this License; they are outside its scope.  The act of\nrunning the Program is not restricted, and the output from the Program\nis covered only if its contents constitute a work based on the\nProgram (independent of having been made by running the Program).\nWhether that is true depends on what the Program does.\n\n  1. You may copy and distribute verbatim copies of the Program's\nsource code as you receive it, in any medium, provided that you\nconspicuously and appropriately publish on each copy an appropriate\ncopyright notice and disclaimer of warranty; keep intact all the\nnotices that refer to this License and to the absence of any warranty;\nand give any other recipients of the Program a copy of this License\nalong with the Program.\n\nYou may charge a fee for the physical act of transferring a copy, and\nyou may at your option offer warranty protection in exchange for a fee.\n\n  2. You may modify your copy or copies of the Program or any portion\nof it, thus forming a work based on the Program, and copy and\ndistribute such modifications or work under the terms of Section 1\nabove, provided that you also meet all of these conditions:\n\n    a) You must cause the modified files to carry prominent notices\n    stating that you changed the files and the date of any change.\n\n    b) You must cause any work that you distribute or publish, that in\n    whole or in part contains or is derived from the Program or any\n    part thereof, to be licensed as a whole at no charge to all third\n    parties under the terms of this License.\n\n    c) If the modified program normally reads commands interactively\n    when run, you must cause it, when started running for such\n    interactive use in the most ordinary way, to print or display an\n    announcement including an appropriate copyright notice and a\n    notice that there is no warranty (or else, saying that you provide\n    a warranty) and that users may redistribute the program under\n    these conditions, and telling the user how to view a copy of this\n    License.  (Exception: if the Program itself is interactive but\n    does not normally print such an announcement, your work based on\n    the Program is not required to print an announcement.)\n\nThese requirements apply to the modified work as a whole.  If\nidentifiable sections of that work are not derived from the Program,\nand can be reasonably considered independent and separate works in\nthemselves, then this License, and its terms, do not apply to those\nsections when you distribute them as separate works.  But when you\ndistribute the same sections as part of a whole which is a work based\non the Program, the distribution of the whole must be on the terms of\nthis License, whose permissions for other licensees extend to the\nentire whole, and thus to each and every part regardless of who wrote it.\n\nThus, it is not the intent of this section to claim rights or contest\nyour rights to work written entirely by you; rather, the intent is to\nexercise the right to control the distribution of derivative or\ncollective works based on the Program.\n\nIn addition, mere aggregation of another work not based on the Program\nwith the Program (or with a work based on the Program) on a volume of\na storage or distribution medium does not bring the other work under\nthe scope of this License.\n\n  3. You may copy and distribute the Program (or a work based on it,\nunder Section 2) in object code or executable form under the terms of\nSections 1 and 2 above provided that you also do one of the following:\n\n    a) Accompany it with the complete corresponding machine-readable\n    source code, which must be distributed under the terms of Sections\n    1 and 2 above on a medium customarily used for software interchange; or,\n\n    b) Accompany it with a written offer, valid for at least three\n    years, to give any third party, for a charge no more than your\n    cost of physically performing source distribution, a complete\n    machine-readable copy of the corresponding source code, to be\n    distributed under the terms of Sections 1 and 2 above on a medium\n    customarily used for software interchange; or,\n\n    c) Accompany it with the information you received as to the offer\n    to distribute corresponding source code.  (This alternative is\n    allowed only for noncommercial distribution and only if you\n    received the program in object code or executable form with such\n    an offer, in accord with Subsection b above.)\n\nThe source code for a work means the preferred form of the work for\nmaking modifications to it.  For an executable work, complete source\ncode means all the source code for all modules it contains, plus any\nassociated interface definition files, plus the scripts used to\ncontrol compilation and installation of the executable.  However, as a\nspecial exception, the source code distributed need not include\nanything that is normally distributed (in either source or binary\nform) with the major components (compiler, kernel, and so on) of the\noperating system on which the executable runs, unless that component\nitself accompanies the executable.\n\nIf distribution of executable or object code is made by offering\naccess to copy from a designated place, then offering equivalent\naccess to copy the source code from the same place counts as\ndistribution of the source code, even though third parties are not\ncompelled to copy the source along with the object code.\n\n  4. You may not copy, modify, sublicense, or distribute the Program\nexcept as expressly provided under this License.  Any attempt\notherwise to copy, modify, sublicense or distribute the Program is\nvoid, and will automatically terminate your rights under this License.\nHowever, parties who have received copies, or rights, from you under\nthis License will not have their licenses terminated so long as such\nparties remain in full compliance.\n\n  5. You are not required to accept this License, since you have not\nsigned it.  However, nothing else grants you permission to modify or\ndistribute the Program or its derivative works.  These actions are\nprohibited by law if you do not accept this License.  Therefore, by\nmodifying or distributing the Program (or any work based on the\nProgram), you indicate your acceptance of this License to do so, and\nall its terms and conditions for copying, distributing or modifying\nthe Program or works based on it.\n\n  6. Each time you redistribute the Program (or any work based on the\nProgram), the recipient automatically receives a license from the\noriginal licensor to copy, distribute or modify the Program subject to\nthese terms and conditions.  You may not impose any further\nrestrictions on the recipients' exercise of the rights granted herein.\nYou are not responsible for enforcing compliance by third parties to\nthis License.\n\n  7. If, as a consequence of a court judgment or allegation of patent\ninfringement or for any other reason (not limited to patent issues),\nconditions are imposed on you (whether by court order, agreement or\notherwise) that contradict the conditions of this License, they do not\nexcuse you from the conditions of this License.  If you cannot\ndistribute so as to satisfy simultaneously your obligations under this\nLicense and any other pertinent obligations, then as a consequence you\nmay not distribute the Program at all.  For example, if a patent\nlicense would not permit royalty-free redistribution of the Program by\nall those who receive copies directly or indirectly through you, then\nthe only way you could satisfy both it and this License would be to\nrefrain entirely from distribution of the Program.\n\nIf any portion of this section is held invalid or unenforceable under\nany particular circumstance, the balance of the section is intended to\napply and the section as a whole is intended to apply in other\ncircumstances.\n\nIt is not the purpose of this section to induce you to infringe any\npatents or other property right claims or to contest validity of any\nsuch claims; this section has the sole purpose of protecting the\nintegrity of the free software distribution system, which is\nimplemented by public license practices.  Many people have made\ngenerous contributions to the wide range of software distributed\nthrough that system in reliance on consistent application of that\nsystem; it is up to the author/donor to decide if he or she is willing\nto distribute software through any other system and a licensee cannot\nimpose that choice.\n\nThis section is intended to make thoroughly clear what is believed to\nbe a consequence of the rest of this License.\n\n  8. If the distribution and/or use of the Program is restricted in\ncertain countries either by patents or by copyrighted interfaces, the\noriginal copyright holder who places the Program under this License\nmay add an explicit geographical distribution limitation excluding\nthose countries, so that distribution is permitted only in or among\ncountries not thus excluded.  In such case, this License incorporates\nthe limitation as if written in the body of this License.\n\n  9. The Free Software Foundation may publish revised and/or new versions\nof the General Public License from time to time.  Such new versions will\nbe similar in spirit to the present version, but may differ in detail to\naddress new problems or concerns.\n\nEach version is given a distinguishing version number.  If the Program\nspecifies a version number of this License which applies to it and \"any\nlater version\", you have the option of following the terms and conditions\neither of that version or of any later version published by the Free\nSoftware Foundation.  If the Program does not specify a version number of\nthis License, you may choose any version ever published by the Free Software\nFoundation.\n\n  10. If you wish to incorporate parts of the Program into other free\nprograms whose distribution conditions are different, write to the author\nto ask for permission.  For software which is copyrighted by the Free\nSoftware Foundation, write to the Free Software Foundation; we sometimes\nmake exceptions for this.  Our decision will be guided by the two goals\nof preserving the free status of all derivatives of our free software and\nof promoting the sharing and reuse of software generally.\n\n                            NO WARRANTY\n\n  11. BECAUSE THE PROGRAM IS LICENSED FREE OF CHARGE, THERE IS NO WARRANTY\nFOR THE PROGRAM, TO THE EXTENT PERMITTED BY APPLICABLE LAW.  EXCEPT WHEN\nOTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR OTHER PARTIES\nPROVIDE THE PROGRAM \"AS IS\" WITHOUT WARRANTY OF ANY KIND, EITHER EXPRESSED\nOR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF\nMERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE.  THE ENTIRE RISK AS\nTO THE QUALITY AND PERFORMANCE OF THE PROGRAM IS WITH YOU.  SHOULD THE\nPROGRAM PROVE DEFECTIVE, YOU ASSUME THE COST OF ALL NECESSARY SERVICING,\nREPAIR OR CORRECTION.\n\n  12. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN WRITING\nWILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY AND/OR\nREDISTRIBUTE THE PROGRAM AS PERMITTED ABOVE, BE LIABLE TO YOU FOR DAMAGES,\nINCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR CONSEQUENTIAL DAMAGES ARISING\nOUT OF THE USE OR INABILITY TO USE THE PROGRAM (INCLUDING BUT NOT LIMITED\nTO LOSS OF DATA OR DATA BEING RENDERED INACCURATE OR LOSSES SUSTAINED BY\nYOU OR THIRD PARTIES OR A FAILURE OF THE PROGRAM TO OPERATE WITH ANY OTHER\nPROGRAMS), EVEN IF SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE\nPOSSIBILITY OF SUCH DAMAGES.\n\n                     END OF TERMS AND CONDITIONS\n\n            How to Apply These Terms to Your New Programs\n\n  If you develop a new program, and you want it to be of the greatest\npossible use to the public, the best way to achieve this is to make it\nfree software which everyone can redistribute and change under these terms.\n\n  To do so, attach the following notices to the program.  It is safest\nto attach them to the start of each source file to most effectively\nconvey the exclusion of warranty; and each file should have at least\nthe \"copyright\" line and a pointer to where the full notice is found.\n\n    <one line to give the program's name and a brief idea of what it does.>\n    Copyright (C) <year>  <name of author>\n\n    This program is free software; you can redistribute it and/or modify\n    it under the terms of the GNU General Public License as published by\n    the Free Software Foundation; either version 2 of the License, or\n    (at your option) any later version.\n\n    This program is distributed in the hope that it will be useful,\n    but WITHOUT ANY WARRANTY; without even the implied warranty of\n    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n    GNU General Public License for more details.\n\n    You should have received a copy of the GNU General Public License\n    along with this program; if not, write to the Free Software\n    Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA  02111-1307  USA\n\n\nAlso add information on how to contact you by electronic and paper mail.\n\nIf the program is interactive, make it output a short notice like this\nwhen it starts in an interactive mode:\n\n    Gnomovision version 69, Copyright (C) year name of author\n    Gnomovision comes with ABSOLUTELY NO WARRANTY; for details type `show w'.\n    This is free software, and you are welcome to redistribute it\n    under certain conditions; type `show c' for details.\n\nThe hypothetical commands `show w' and `show c' should show the appropriate\nparts of the General Public License.  Of course, the commands you use may\nbe called something other than `show w' and `show c'; they could even be\nmouse-clicks or menu items--whatever suits your program.\n\nYou should also get your employer (if you work as a programmer) or your\nschool, if any, to sign a \"copyright disclaimer\" for the program, if\nnecessary.  Here is a sample; alter the names:\n\n  Yoyodyne, Inc., hereby disclaims all copyright interest in the program\n  `Gnomovision' (which makes passes at compilers) written by James Hacker.\n\n  <signature of Ty Coon>, 1 April 1989\n  Ty Coon, President of Vice\n\nThis General Public License does not permit incorporating your program into\nproprietary programs.  If your program is a subroutine library, you may\nconsider it more useful to permit linking proprietary applications with the\nlibrary.  If this is what you want to do, use the GNU Library General\nPublic License instead of this License.\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/README",
    "content": "Bench Template Library\n\n****************************************\nIntroduction :\n\nThe aim of this project is to compare the performance\nof available numerical libraries. The code is designed\nas generic and modular as possible. Thus, adding new\nnumerical libraries or new numerical tests should\nrequire minimal effort.\n\n\n*****************************************\n\nInstallation :\n\nBTL uses cmake / ctest:\n\n1 - create a build directory:\n\n  $ mkdir build\n  $ cd build\n\n2 - configure:\n\n  $ ccmake ..\n\n3 - run the bench using ctest:\n\n  $ ctest -V\n\nYou can run the benchmarks only on libraries matching a given regular expression:\n  ctest -V -R <regexp>\nFor instance:\n  ctest -V -R eigen2\n\nYou can also select a given set of actions defining the environment variable BTL_CONFIG this way:\n  BTL_CONFIG=\"-a action1{:action2}*\" ctest -V\nAn example:\n  BTL_CONFIG=\"-a axpy:vector_matrix:trisolve:ata\" ctest -V -R eigen2\n\nFinally, if bench results already exist (the bench*.dat files) then they merges by keeping the best for each matrix size. If you want to overwrite the previous ones you can simply add the \"--overwrite\" option:\n  BTL_CONFIG=\"-a axpy:vector_matrix:trisolve:ata --overwrite\" ctest -V -R eigen2\n\n4 : Analyze the result. different data files (.dat) are produced in each libs directories.\n If gnuplot is available, choose a directory name in the data directory to store the results and type:\n        $ cd data\n        $ mkdir my_directory\n        $ cp ../libs/*/*.dat my_directory\n Build the data utilities in this (data) directory\n        make\n Then you can look the raw data,\n        go_mean my_directory\n or smooth the data first :\n\tsmooth_all.sh my_directory\n\tgo_mean my_directory_smooth\n\n\n*************************************************\n\nFiles and directories :\n\n generic_bench : all the bench sources common to all libraries\n\n actions : sources for different action wrappers (axpy, matrix-matrix product) to be tested.\n\n libs/* : bench sources specific to each tested libraries.\n\n machine_dep : directory used to store machine specific Makefile.in\n\n data : directory used to store gnuplot scripts and data analysis utilities\n\n**************************************************\n\nPrinciples : the code modularity is achieved by defining two concepts :\n\n ****** Action concept : This is a class defining which kind\n  of test must be performed (e.g. a matrix_vector_product).\n\tAn Action should define the following methods :\n\n        *** Ctor using the size of the problem (matrix or vector size) as an argument\n\t    Action action(size);\n        *** initialize : this method initialize the calculation (e.g. initialize the matrices and vectors arguments)\n\t    action.initialize();\n\t*** calculate : this method actually launch the calculation to be benchmarked\n\t    action.calculate;\n\t*** nb_op_base() : this method returns the complexity of the calculate method (allowing the mflops evaluation)\n        *** name() : this method returns the name of the action (std::string)\n\n ****** Interface concept : This is a class or namespace defining how to use a given library and\n  its specific containers (matrix and vector). Up to now an interface should following types\n\n\t*** real_type : kind of float to be used (float or double)\n\t*** stl_vector : must correspond to std::vector<real_type>\n\t*** stl_matrix : must correspond to std::vector<stl_vector>\n\t*** gene_vector : the vector type for this interface        --> e.g. (real_type *) for the C_interface\n\t*** gene_matrix : the matrix type for this interface        --> e.g. (gene_vector *) for the C_interface\n\n\t+ the following common methods\n\n        *** free_matrix(gene_matrix & A, int N)  dealocation of a N sized gene_matrix A\n        *** free_vector(gene_vector & B)  dealocation of a N sized gene_vector B\n        *** matrix_from_stl(gene_matrix & A, stl_matrix & A_stl) copy the content of an stl_matrix A_stl into a gene_matrix A.\n\t     The allocation of A is done in this function.\n\t*** vector_to_stl(gene_vector & B, stl_vector & B_stl)  copy the content of an stl_vector B_stl into a gene_vector B.\n\t     The allocation of B is done in this function.\n        *** matrix_to_stl(gene_matrix & A, stl_matrix & A_stl) copy the content of an gene_matrix A into an stl_matrix A_stl.\n             The size of A_STL must corresponds to the size of A.\n        *** vector_to_stl(gene_vector & A, stl_vector & A_stl) copy the content of an gene_vector A into an stl_vector A_stl.\n             The size of B_STL must corresponds to the size of B.\n\t*** copy_matrix(gene_matrix & source, gene_matrix & cible, int N) : copy the content of source in cible. Both source\n\t\tand cible must be sized NxN.\n\t*** copy_vector(gene_vector & source, gene_vector & cible, int N) : copy the content of source in cible. Both source\n \t\tand cible must be sized N.\n\n\tand the following method corresponding to the action one wants to be benchmarked :\n\n\t***  matrix_vector_product(const gene_matrix & A, const gene_vector & B, gene_vector & X, int N)\n\t***  matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N)\n        ***  ata_product(const gene_matrix & A, gene_matrix & X, int N)\n\t***  aat_product(const gene_matrix & A, gene_matrix & X, int N)\n        ***  axpy(real coef, const gene_vector & X, gene_vector & Y, int N)\n\n The bench algorithm (generic_bench/bench.hh) is templated with an action itself templated with\n an interface. A typical main.cpp source stored in a given library directory libs/A_LIB\n looks like :\n\n bench< AN_ACTION < AN_INTERFACE > >( 10 , 1000 , 50 ) ;\n\n this function will produce XY data file containing measured  mflops as a function of the size for 50\n sizes between 10 and 10000.\n\n This algorithm can be adapted by providing a given Perf_Analyzer object which determines how the time\n measurements must be done. For example, the X86_Perf_Analyzer use the asm rdtsc function and provides\n a very fast and accurate (but less portable) timing method. The default is the Portable_Perf_Analyzer\n so\n\n bench< AN_ACTION < AN_INTERFACE > >( 10 , 1000 , 50 ) ;\n\n is equivalent to\n\n bench< Portable_Perf_Analyzer,AN_ACTION < AN_INTERFACE > >( 10 , 1000 , 50 ) ;\n\n If your system supports it we suggest to use a mixed implementation (X86_perf_Analyzer+Portable_Perf_Analyzer).\n replace\n     bench<Portable_Perf_Analyzer,Action>(size_min,size_max,nb_point);\n with\n     bench<Mixed_Perf_Analyzer,Action>(size_min,size_max,nb_point);\n in generic/bench.hh\n\n.\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/action_aat_product.hh",
    "content": "//=====================================================\n// File   :  action_aat_product.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_AAT_PRODUCT\n#define ACTION_AAT_PRODUCT\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_aat_product {\n\npublic :\n\n  // Ctor\n\n  Action_aat_product( int size ):_size(size)\n  {\n    MESSAGE(\"Action_aat_product Ctor\");\n\n    // STL matrix and vector initialization\n\n    init_matrix<pseudo_random>(A_stl,_size);\n    init_matrix<null_function>(X_stl,_size);\n    init_matrix<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::matrix_from_stl(X_ref,X_stl);\n\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::matrix_from_stl(X,X_stl);\n\n  }\n\n  // invalidate copy ctor\n\n  Action_aat_product( const  Action_aat_product & )\n  {\n    INFOS(\"illegal call to Action_aat_product Copy Ctor\");\n    exit(0);\n  }\n\n  // Dtor\n\n  ~Action_aat_product( void ){\n\n    MESSAGE(\"Action_aat_product Dtor\");\n\n    // deallocation\n\n    Interface::free_matrix(A,_size);\n    Interface::free_matrix(X,_size);\n\n    Interface::free_matrix(A_ref,_size);\n    Interface::free_matrix(X_ref,_size);\n\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"aat_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return double(_size)*double(_size)*double(_size);\n  }\n\n  inline void initialize( void ){\n\n    Interface::copy_matrix(A_ref,A,_size);\n    Interface::copy_matrix(X_ref,X,_size);\n\n  }\n\n  inline void calculate( void ) {\n\n      Interface::aat_product(A,X,_size);\n\n  }\n\n  void check_result( void ){\n    if (_size>128) return;\n    // calculation check\n\n    Interface::matrix_to_stl(X,resu_stl);\n\n    STL_interface<typename Interface::real_type>::aat_product(A_stl,X_stl,_size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n\n    if (error>1.e-6){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n      exit(1);\n    }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix A_stl;\n  typename Interface::stl_matrix X_stl;\n  typename Interface::stl_matrix resu_stl;\n\n  typename Interface::gene_matrix A_ref;\n  typename Interface::gene_matrix X_ref;\n\n  typename Interface::gene_matrix A;\n  typename Interface::gene_matrix X;\n\n\n  int _size;\n\n};\n\n\n#endif\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/action_ata_product.hh",
    "content": "//=====================================================\n// File   :  action_ata_product.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_ATA_PRODUCT\n#define ACTION_ATA_PRODUCT\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_ata_product {\n\npublic :\n\n  // Ctor\n\n  Action_ata_product( int size ):_size(size)\n  {\n    MESSAGE(\"Action_ata_product Ctor\");\n\n    // STL matrix and vector initialization\n\n    init_matrix<pseudo_random>(A_stl,_size);\n    init_matrix<null_function>(X_stl,_size);\n    init_matrix<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::matrix_from_stl(X_ref,X_stl);\n\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::matrix_from_stl(X,X_stl);\n\n  }\n\n  // invalidate copy ctor\n\n  Action_ata_product( const  Action_ata_product & )\n  {\n    INFOS(\"illegal call to Action_ata_product Copy Ctor\");\n    exit(0);\n  }\n\n  // Dtor\n\n  ~Action_ata_product( void ){\n\n    MESSAGE(\"Action_ata_product Dtor\");\n\n    // deallocation\n\n    Interface::free_matrix(A,_size);\n    Interface::free_matrix(X,_size);\n\n    Interface::free_matrix(A_ref,_size);\n    Interface::free_matrix(X_ref,_size);\n\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"ata_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return 2.0*_size*_size*_size;\n  }\n\n  inline void initialize( void ){\n\n    Interface::copy_matrix(A_ref,A,_size);\n    Interface::copy_matrix(X_ref,X,_size);\n\n  }\n\n  inline void calculate( void ) {\n\n      Interface::ata_product(A,X,_size);\n\n  }\n\n  void check_result( void ){\n    if (_size>128) return;\n    // calculation check\n\n    Interface::matrix_to_stl(X,resu_stl);\n\n    STL_interface<typename Interface::real_type>::ata_product(A_stl,X_stl,_size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n\n    if (error>1.e-6){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n      exit(1);\n    }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix A_stl;\n  typename Interface::stl_matrix X_stl;\n  typename Interface::stl_matrix resu_stl;\n\n  typename Interface::gene_matrix A_ref;\n  typename Interface::gene_matrix X_ref;\n\n  typename Interface::gene_matrix A;\n  typename Interface::gene_matrix X;\n\n\n  int _size;\n\n};\n\n\n#endif\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/action_atv_product.hh",
    "content": "//=====================================================\n// File   :  action_atv_product.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_ATV_PRODUCT\n#define ACTION_ATV_PRODUCT\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_atv_product {\n\npublic :\n\n  Action_atv_product( int size ) : _size(size)\n  {\n    MESSAGE(\"Action_atv_product Ctor\");\n\n    // STL matrix and vector initialization\n\n    init_matrix<pseudo_random>(A_stl,_size);\n    init_vector<pseudo_random>(B_stl,_size);\n    init_vector<null_function>(X_stl,_size);\n    init_vector<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::vector_from_stl(B_ref,B_stl);\n    Interface::vector_from_stl(X_ref,X_stl);\n\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::vector_from_stl(B,B_stl);\n    Interface::vector_from_stl(X,X_stl);\n  }\n\n  // invalidate copy ctor\n  Action_atv_product( const  Action_atv_product & )\n  {\n    INFOS(\"illegal call to Action_atv_product Copy Ctor\");\n    exit(1);\n  }\n\n  ~Action_atv_product( void )\n  {\n    MESSAGE(\"Action_atv_product Dtor\");\n\n    Interface::free_matrix(A,_size);\n    Interface::free_vector(B);\n    Interface::free_vector(X);\n\n    Interface::free_matrix(A_ref,_size);\n    Interface::free_vector(B_ref);\n    Interface::free_vector(X_ref);\n  }\n\n  static inline std::string name() { return \"atv_\" + Interface::name(); }\n\n  double nb_op_base( void ) { return 2.0*_size*_size; }\n\n  inline void initialize( void ){\n    Interface::copy_matrix(A_ref,A,_size);\n    Interface::copy_vector(B_ref,B,_size);\n    Interface::copy_vector(X_ref,X,_size);\n  }\n\n  BTL_DONT_INLINE void calculate( void ) {\n    BTL_ASM_COMMENT(\"begin atv\");\n    Interface::atv_product(A,B,X,_size);\n    BTL_ASM_COMMENT(\"end atv\");\n  }\n\n  void check_result( void )\n  {\n    if (_size>128) return;\n    Interface::vector_to_stl(X,resu_stl);\n\n    STL_interface<typename Interface::real_type>::atv_product(A_stl,B_stl,X_stl,_size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n\n    if (error>1.e-6){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n      exit(1);\n    }\n  }\n\nprivate :\n\n  typename Interface::stl_matrix A_stl;\n  typename Interface::stl_vector B_stl;\n  typename Interface::stl_vector X_stl;\n  typename Interface::stl_vector resu_stl;\n\n  typename Interface::gene_matrix A_ref;\n  typename Interface::gene_vector B_ref;\n  typename Interface::gene_vector X_ref;\n\n  typename Interface::gene_matrix A;\n  typename Interface::gene_vector B;\n  typename Interface::gene_vector X;\n\n\n  int _size;\n\n};\n\n\n#endif\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/action_axpby.hh",
    "content": "//=====================================================\n// File   :  action_axpby.hh\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_AXPBY\n#define ACTION_AXPBY\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_axpby {\n\npublic :\n\n  // Ctor\n  Action_axpby( int size ):_alpha(0.5),_beta(0.95),_size(size)\n  {\n    MESSAGE(\"Action_axpby Ctor\");\n\n    // STL vector initialization\n    init_vector<pseudo_random>(X_stl,_size);\n    init_vector<pseudo_random>(Y_stl,_size);\n    init_vector<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n    Interface::vector_from_stl(X_ref,X_stl);\n    Interface::vector_from_stl(Y_ref,Y_stl);\n\n    Interface::vector_from_stl(X,X_stl);\n    Interface::vector_from_stl(Y,Y_stl);\n  }\n\n  // invalidate copy ctor\n  Action_axpby( const  Action_axpby & )\n  {\n    INFOS(\"illegal call to Action_axpby Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n  ~Action_axpby( void ){\n    MESSAGE(\"Action_axpby Dtor\");\n\n    // deallocation\n    Interface::free_vector(X_ref);\n    Interface::free_vector(Y_ref);\n\n    Interface::free_vector(X);\n    Interface::free_vector(Y);\n  }\n\n  // action name\n  static inline std::string name( void )\n  {\n    return \"axpby_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return 3.0*_size;\n  }\n\n  inline void initialize( void ){\n    Interface::copy_vector(X_ref,X,_size);\n    Interface::copy_vector(Y_ref,Y,_size);\n  }\n\n  inline void calculate( void ) {\n    BTL_ASM_COMMENT(\"mybegin axpby\");\n    Interface::axpby(_alpha,X,_beta,Y,_size);\n    BTL_ASM_COMMENT(\"myend axpby\");\n  }\n\n  void check_result( void ){\n    if (_size>128) return;\n    // calculation check\n    Interface::vector_to_stl(Y,resu_stl);\n\n    STL_interface<typename Interface::real_type>::axpby(_alpha,X_stl,_beta,Y_stl,_size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(Y_stl,resu_stl);\n\n    if (error>1.e-6){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n      exit(2);\n    }\n  }\n\nprivate :\n\n  typename Interface::stl_vector X_stl;\n  typename Interface::stl_vector Y_stl;\n  typename Interface::stl_vector resu_stl;\n\n  typename Interface::gene_vector X_ref;\n  typename Interface::gene_vector Y_ref;\n\n  typename Interface::gene_vector X;\n  typename Interface::gene_vector Y;\n\n  typename Interface::real_type _alpha;\n  typename Interface::real_type _beta;\n\n  int _size;\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/action_axpy.hh",
    "content": "//=====================================================\n// File   :  action_axpy.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_AXPY\n#define ACTION_AXPY\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_axpy {\n\npublic :\n\n  // Ctor\n\n  Action_axpy( int size ):_coef(1.0),_size(size)\n  {\n    MESSAGE(\"Action_axpy Ctor\");\n\n    // STL vector initialization\n\n    init_vector<pseudo_random>(X_stl,_size);\n    init_vector<pseudo_random>(Y_stl,_size);\n    init_vector<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n\n    Interface::vector_from_stl(X_ref,X_stl);\n    Interface::vector_from_stl(Y_ref,Y_stl);\n\n    Interface::vector_from_stl(X,X_stl);\n    Interface::vector_from_stl(Y,Y_stl);\n\n\n  }\n\n  // invalidate copy ctor\n\n  Action_axpy( const  Action_axpy & )\n  {\n    INFOS(\"illegal call to Action_axpy Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n\n  ~Action_axpy( void ){\n\n    MESSAGE(\"Action_axpy Dtor\");\n\n    // deallocation\n\n    Interface::free_vector(X_ref);\n    Interface::free_vector(Y_ref);\n\n    Interface::free_vector(X);\n    Interface::free_vector(Y);\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"axpy_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return 2.0*_size;\n  }\n\n  inline void initialize( void ){\n    Interface::copy_vector(X_ref,X,_size);\n    Interface::copy_vector(Y_ref,Y,_size);\n  }\n\n  inline void calculate( void ) {\n    BTL_ASM_COMMENT(\"mybegin axpy\");\n    Interface::axpy(_coef,X,Y,_size);\n    BTL_ASM_COMMENT(\"myend axpy\");\n  }\n\n  void check_result( void ){\n    if (_size>128) return;\n    // calculation check\n\n    Interface::vector_to_stl(Y,resu_stl);\n\n    STL_interface<typename Interface::real_type>::axpy(_coef,X_stl,Y_stl,_size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(Y_stl,resu_stl);\n\n    if (error>1.e-6){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n      exit(0);\n    }\n\n  }\n\nprivate :\n\n  typename Interface::stl_vector X_stl;\n  typename Interface::stl_vector Y_stl;\n  typename Interface::stl_vector resu_stl;\n\n  typename Interface::gene_vector X_ref;\n  typename Interface::gene_vector Y_ref;\n\n  typename Interface::gene_vector X;\n  typename Interface::gene_vector Y;\n\n  typename Interface::real_type _coef;\n\n  int _size;\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/action_cholesky.hh",
    "content": "//=====================================================\n// File   :  action_cholesky.hh\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_CHOLESKY\n#define ACTION_CHOLESKY\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_cholesky {\n\npublic :\n\n  // Ctor\n\n  Action_cholesky( int size ):_size(size)\n  {\n    MESSAGE(\"Action_cholesky Ctor\");\n\n    // STL mat/vec initialization\n    init_matrix_symm<pseudo_random>(X_stl,_size);\n    init_matrix<null_function>(C_stl,_size);\n\n    // make sure X is invertible\n    for (int i=0; i<_size; ++i)\n      X_stl[i][i] = std::abs(X_stl[i][i]) * 1e2 + 100;\n\n    // generic matrix and vector initialization\n    Interface::matrix_from_stl(X_ref,X_stl);\n    Interface::matrix_from_stl(X,X_stl);\n    Interface::matrix_from_stl(C,C_stl);\n\n    _cost = 0;\n    for (int j=0; j<_size; ++j)\n    {\n      double r = std::max(_size - j -1,0);\n      _cost += 2*(r*j+r+j);\n    }\n  }\n\n  // invalidate copy ctor\n\n  Action_cholesky( const  Action_cholesky & )\n  {\n    INFOS(\"illegal call to Action_cholesky Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n\n  ~Action_cholesky( void ){\n\n    MESSAGE(\"Action_cholesky Dtor\");\n\n    // deallocation\n    Interface::free_matrix(X_ref,_size);\n    Interface::free_matrix(X,_size);\n    Interface::free_matrix(C,_size);\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"cholesky_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return _cost;\n  }\n\n  inline void initialize( void ){\n    Interface::copy_matrix(X_ref,X,_size);\n  }\n\n  inline void calculate( void ) {\n      Interface::cholesky(X,C,_size);\n  }\n\n  void check_result( void ){\n    // calculation check\n//     STL_interface<typename Interface::real_type>::cholesky(X_stl,C_stl,_size);\n//\n//     typename Interface::real_type error=\n//       STL_interface<typename Interface::real_type>::norm_diff(C_stl,resu_stl);\n//\n//     if (error>1.e-6){\n//       INFOS(\"WRONG CALCULATION...residual=\" << error);\n//       exit(0);\n//     }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix X_stl;\n  typename Interface::stl_matrix C_stl;\n\n  typename Interface::gene_matrix X_ref;\n  typename Interface::gene_matrix X;\n  typename Interface::gene_matrix C;\n\n  int _size;\n  double _cost;\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/action_ger.hh",
    "content": "\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_GER\n#define ACTION_GER\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_ger {\n\npublic :\n\n  // Ctor\n  BTL_DONT_INLINE Action_ger( int size ):_size(size)\n  {\n    MESSAGE(\"Action_ger Ctor\");\n\n    // STL matrix and vector initialization\n    typename Interface::stl_matrix tmp;\n    init_matrix<pseudo_random>(A_stl,_size);\n    init_vector<pseudo_random>(B_stl,_size);\n    init_vector<pseudo_random>(X_stl,_size);\n    init_vector<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::vector_from_stl(B_ref,B_stl);\n    Interface::vector_from_stl(B,B_stl);\n    Interface::vector_from_stl(X_ref,X_stl);\n    Interface::vector_from_stl(X,X_stl);\n  }\n\n  // invalidate copy ctor\n  Action_ger( const  Action_ger & )\n  {\n    INFOS(\"illegal call to Action_ger Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n  BTL_DONT_INLINE ~Action_ger( void ){\n    MESSAGE(\"Action_ger Dtor\");\n    Interface::free_matrix(A,_size);\n    Interface::free_vector(B);\n    Interface::free_vector(X);\n    Interface::free_matrix(A_ref,_size);\n    Interface::free_vector(B_ref);\n    Interface::free_vector(X_ref);\n\n  }\n\n  // action name\n  static inline std::string name( void )\n  {\n    return \"ger_\" + Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return 2.0*_size*_size;\n  }\n\n  BTL_DONT_INLINE  void initialize( void ){\n    Interface::copy_matrix(A_ref,A,_size);\n    Interface::copy_vector(B_ref,B,_size);\n    Interface::copy_vector(X_ref,X,_size);\n  }\n\n  BTL_DONT_INLINE void calculate( void ) {\n    BTL_ASM_COMMENT(\"#begin ger\");\n    Interface::ger(A,B,X,_size);\n    BTL_ASM_COMMENT(\"end ger\");\n  }\n\n  BTL_DONT_INLINE void check_result( void ){\n    // calculation check\n    Interface::vector_to_stl(X,resu_stl);\n\n    STL_interface<typename Interface::real_type>::ger(A_stl,B_stl,X_stl,_size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n\n    if (error>1.e-3){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n//       exit(0);\n    }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix A_stl;\n  typename Interface::stl_vector B_stl;\n  typename Interface::stl_vector X_stl;\n  typename Interface::stl_vector resu_stl;\n\n  typename Interface::gene_matrix A_ref;\n  typename Interface::gene_vector B_ref;\n  typename Interface::gene_vector X_ref;\n\n  typename Interface::gene_matrix A;\n  typename Interface::gene_vector B;\n  typename Interface::gene_vector X;\n\n  int _size;\n};\n\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/action_hessenberg.hh",
    "content": "//=====================================================\n// File   :  action_hessenberg.hh\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_HESSENBERG\n#define ACTION_HESSENBERG\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_hessenberg {\n\npublic :\n\n  // Ctor\n\n  Action_hessenberg( int size ):_size(size)\n  {\n    MESSAGE(\"Action_hessenberg Ctor\");\n\n    // STL vector initialization\n    init_matrix<pseudo_random>(X_stl,_size);\n\n    init_matrix<null_function>(C_stl,_size);\n    init_matrix<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n    Interface::matrix_from_stl(X_ref,X_stl);\n    Interface::matrix_from_stl(X,X_stl);\n    Interface::matrix_from_stl(C,C_stl);\n\n    _cost = 0;\n    for (int j=0; j<_size-2; ++j)\n    {\n      double r = std::max(0,_size-j-1);\n      double b = std::max(0,_size-j-2);\n      _cost += 6 + 3*b + r*r*4 + r*_size*4;\n    }\n  }\n\n  // invalidate copy ctor\n\n  Action_hessenberg( const  Action_hessenberg & )\n  {\n    INFOS(\"illegal call to Action_hessenberg Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n\n  ~Action_hessenberg( void ){\n\n    MESSAGE(\"Action_hessenberg Dtor\");\n\n    // deallocation\n    Interface::free_matrix(X_ref,_size);\n    Interface::free_matrix(X,_size);\n    Interface::free_matrix(C,_size);\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"hessenberg_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return _cost;\n  }\n\n  inline void initialize( void ){\n    Interface::copy_matrix(X_ref,X,_size);\n  }\n\n  inline void calculate( void ) {\n      Interface::hessenberg(X,C,_size);\n  }\n\n  void check_result( void ){\n    // calculation check\n    Interface::matrix_to_stl(C,resu_stl);\n\n//     STL_interface<typename Interface::real_type>::hessenberg(X_stl,C_stl,_size);\n//\n//     typename Interface::real_type error=\n//       STL_interface<typename Interface::real_type>::norm_diff(C_stl,resu_stl);\n//\n//     if (error>1.e-6){\n//       INFOS(\"WRONG CALCULATION...residual=\" << error);\n//       exit(0);\n//     }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix X_stl;\n  typename Interface::stl_matrix C_stl;\n  typename Interface::stl_matrix resu_stl;\n\n  typename Interface::gene_matrix X_ref;\n  typename Interface::gene_matrix X;\n  typename Interface::gene_matrix C;\n\n  int _size;\n  double _cost;\n};\n\ntemplate<class Interface>\nclass Action_tridiagonalization {\n\npublic :\n\n  // Ctor\n\n  Action_tridiagonalization( int size ):_size(size)\n  {\n    MESSAGE(\"Action_tridiagonalization Ctor\");\n\n    // STL vector initialization\n    init_matrix<pseudo_random>(X_stl,_size);\n    \n    for(int i=0; i<_size; ++i)\n    {\n      for(int j=0; j<i; ++j)\n        X_stl[i][j] = X_stl[j][i];\n    }\n    \n    init_matrix<null_function>(C_stl,_size);\n    init_matrix<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n    Interface::matrix_from_stl(X_ref,X_stl);\n    Interface::matrix_from_stl(X,X_stl);\n    Interface::matrix_from_stl(C,C_stl);\n\n    _cost = 0;\n    for (int j=0; j<_size-2; ++j)\n    {\n      double r = std::max(0,_size-j-1);\n      double b = std::max(0,_size-j-2);\n      _cost += 6. + 3.*b + r*r*8.;\n    }\n  }\n\n  // invalidate copy ctor\n\n  Action_tridiagonalization( const  Action_tridiagonalization & )\n  {\n    INFOS(\"illegal call to Action_tridiagonalization Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n\n  ~Action_tridiagonalization( void ){\n\n    MESSAGE(\"Action_tridiagonalization Dtor\");\n\n    // deallocation\n    Interface::free_matrix(X_ref,_size);\n    Interface::free_matrix(X,_size);\n    Interface::free_matrix(C,_size);\n  }\n\n  // action name\n\n  static inline std::string name( void ) { return \"tridiagonalization_\"+Interface::name(); }\n\n  double nb_op_base( void ){\n    return _cost;\n  }\n\n  inline void initialize( void ){\n    Interface::copy_matrix(X_ref,X,_size);\n  }\n\n  inline void calculate( void ) {\n      Interface::tridiagonalization(X,C,_size);\n  }\n\n  void check_result( void ){\n    // calculation check\n    Interface::matrix_to_stl(C,resu_stl);\n\n//     STL_interface<typename Interface::real_type>::tridiagonalization(X_stl,C_stl,_size);\n//\n//     typename Interface::real_type error=\n//       STL_interface<typename Interface::real_type>::norm_diff(C_stl,resu_stl);\n//\n//     if (error>1.e-6){\n//       INFOS(\"WRONG CALCULATION...residual=\" << error);\n//       exit(0);\n//     }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix X_stl;\n  typename Interface::stl_matrix C_stl;\n  typename Interface::stl_matrix resu_stl;\n\n  typename Interface::gene_matrix X_ref;\n  typename Interface::gene_matrix X;\n  typename Interface::gene_matrix C;\n\n  int _size;\n  double _cost;\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/action_lu_decomp.hh",
    "content": "//=====================================================\n// File   :  action_lu_decomp.hh\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_LU_DECOMP\n#define ACTION_LU_DECOMP\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_lu_decomp {\n\npublic :\n\n  // Ctor\n\n  Action_lu_decomp( int size ):_size(size)\n  {\n    MESSAGE(\"Action_lu_decomp Ctor\");\n\n    // STL vector initialization\n    init_matrix<pseudo_random>(X_stl,_size);\n\n    init_matrix<null_function>(C_stl,_size);\n    init_matrix<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n    Interface::matrix_from_stl(X_ref,X_stl);\n    Interface::matrix_from_stl(X,X_stl);\n    Interface::matrix_from_stl(C,C_stl);\n\n    _cost = 2.0*size*size*size/3.0 + size*size;\n  }\n\n  // invalidate copy ctor\n\n  Action_lu_decomp( const  Action_lu_decomp & )\n  {\n    INFOS(\"illegal call to Action_lu_decomp Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n\n  ~Action_lu_decomp( void ){\n\n    MESSAGE(\"Action_lu_decomp Dtor\");\n\n    // deallocation\n    Interface::free_matrix(X_ref,_size);\n    Interface::free_matrix(X,_size);\n    Interface::free_matrix(C,_size);\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"complete_lu_decomp_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return _cost;\n  }\n\n  inline void initialize( void ){\n    Interface::copy_matrix(X_ref,X,_size);\n  }\n\n  inline void calculate( void ) {\n      Interface::lu_decomp(X,C,_size);\n  }\n\n  void check_result( void ){\n    // calculation check\n    Interface::matrix_to_stl(C,resu_stl);\n\n//     STL_interface<typename Interface::real_type>::lu_decomp(X_stl,C_stl,_size);\n//\n//     typename Interface::real_type error=\n//       STL_interface<typename Interface::real_type>::norm_diff(C_stl,resu_stl);\n//\n//     if (error>1.e-6){\n//       INFOS(\"WRONG CALCULATION...residual=\" << error);\n//       exit(0);\n//     }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix X_stl;\n  typename Interface::stl_matrix C_stl;\n  typename Interface::stl_matrix resu_stl;\n\n  typename Interface::gene_matrix X_ref;\n  typename Interface::gene_matrix X;\n  typename Interface::gene_matrix C;\n\n  int _size;\n  double _cost;\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/action_lu_solve.hh",
    "content": "//=====================================================\n// File   :  action_lu_solve.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef ACTION_LU_SOLVE\n#define ACTION_LU_SOLVE\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_lu_solve \n{\n\npublic :\n\n  static inline std::string name( void )\n  {\n    return \"lu_solve_\"+Interface::name();\n  }\n  \n  static double nb_op_base(int size){\n    return 2.0*size*size*size/3.0;  // questionable but not really important\n  }\n\n\n  static double calculate( int nb_calc, int size ) {\n\n    // STL matrix and vector initialization\n    \n    typename Interface::stl_matrix A_stl;\n    typename Interface::stl_vector B_stl;\n    typename Interface::stl_vector X_stl;\n\n    init_matrix<pseudo_random>(A_stl,size);\n    init_vector<pseudo_random>(B_stl,size);\n    init_vector<null_function>(X_stl,size);\n\n    // generic matrix and vector initialization\n\n    typename Interface::gene_matrix A;\n    typename Interface::gene_vector B;\n    typename Interface::gene_vector X;\n\n    typename Interface::gene_matrix LU; \n\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::vector_from_stl(B,B_stl);\n    Interface::vector_from_stl(X,X_stl);\n    Interface::matrix_from_stl(LU,A_stl);\n  \n    // local variable :\n\n    typename Interface::Pivot_Vector pivot; // pivot vector\n    Interface::new_Pivot_Vector(pivot,size);\n    \n    // timer utilities\n\n    Portable_Timer chronos;\n\n    // time measurement\n\n    chronos.start();\n    \n    for (int ii=0;ii<nb_calc;ii++){\n\n      // LU factorization\n      Interface::copy_matrix(A,LU,size);\n      Interface::LU_factor(LU,pivot,size);\n      \n      // LU solve\n\n      Interface::LU_solve(LU,pivot,B,X,size);\n\n    }\n\n    // Time stop\n\n    chronos.stop();\n\n    double time=chronos.user_time();\n  \n    // check result :\n\n    typename Interface::stl_vector B_new_stl(size);\n    Interface::vector_to_stl(X,X_stl);\n\n    STL_interface<typename Interface::real_type>::matrix_vector_product(A_stl,X_stl,B_new_stl,size); \n  \n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(B_stl,B_new_stl);\n    \n    if (error>1.e-5){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n      STL_interface<typename Interface::real_type>::display_vector(B_stl);\n      STL_interface<typename Interface::real_type>::display_vector(B_new_stl);\n      exit(0);\n    }\n    \n    // deallocation and return time\n    \n    Interface::free_matrix(A,size);\n    Interface::free_vector(B);\n    Interface::free_vector(X);\n    Interface::free_Pivot_Vector(pivot);\n\n    return time;\n  }\n\n};\n  \n\n#endif\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/action_matrix_matrix_product.hh",
    "content": "//=====================================================\n// File   :  action_matrix_matrix_product.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_MATRIX_MATRIX_PRODUCT\n#define ACTION_MATRIX_MATRIX_PRODUCT\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_matrix_matrix_product {\n\npublic :\n\n  // Ctor\n\n  Action_matrix_matrix_product( int size ):_size(size)\n  {\n    MESSAGE(\"Action_matrix_matrix_product Ctor\");\n\n    // STL matrix and vector initialization\n\n    init_matrix<pseudo_random>(A_stl,_size);\n    init_matrix<pseudo_random>(B_stl,_size);\n    init_matrix<null_function>(X_stl,_size);\n    init_matrix<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::matrix_from_stl(B_ref,B_stl);\n    Interface::matrix_from_stl(X_ref,X_stl);\n\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::matrix_from_stl(B,B_stl);\n    Interface::matrix_from_stl(X,X_stl);\n\n  }\n\n  // invalidate copy ctor\n\n  Action_matrix_matrix_product( const  Action_matrix_matrix_product & )\n  {\n    INFOS(\"illegal call to Action_matrix_matrix_product Copy Ctor\");\n    exit(0);\n  }\n\n  // Dtor\n\n  ~Action_matrix_matrix_product( void ){\n\n    MESSAGE(\"Action_matrix_matrix_product Dtor\");\n\n    // deallocation\n\n    Interface::free_matrix(A,_size);\n    Interface::free_matrix(B,_size);\n    Interface::free_matrix(X,_size);\n\n    Interface::free_matrix(A_ref,_size);\n    Interface::free_matrix(B_ref,_size);\n    Interface::free_matrix(X_ref,_size);\n\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"matrix_matrix_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return 2.0*_size*_size*_size;\n  }\n\n  inline void initialize( void ){\n\n    Interface::copy_matrix(A_ref,A,_size);\n    Interface::copy_matrix(B_ref,B,_size);\n    Interface::copy_matrix(X_ref,X,_size);\n\n  }\n\n  inline void calculate( void ) {\n      Interface::matrix_matrix_product(A,B,X,_size);\n  }\n\n  void check_result( void ){\n\n    // calculation check\n    if (_size<200)\n    {\n      Interface::matrix_to_stl(X,resu_stl);\n      STL_interface<typename Interface::real_type>::matrix_matrix_product(A_stl,B_stl,X_stl,_size);\n      typename Interface::real_type error=\n        STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n      if (error>1.e-6){\n        INFOS(\"WRONG CALCULATION...residual=\" << error);\n        exit(1);\n      }\n    }\n  }\n\nprivate :\n\n  typename Interface::stl_matrix A_stl;\n  typename Interface::stl_matrix B_stl;\n  typename Interface::stl_matrix X_stl;\n  typename Interface::stl_matrix resu_stl;\n\n  typename Interface::gene_matrix A_ref;\n  typename Interface::gene_matrix B_ref;\n  typename Interface::gene_matrix X_ref;\n\n  typename Interface::gene_matrix A;\n  typename Interface::gene_matrix B;\n  typename Interface::gene_matrix X;\n\n\n  int _size;\n\n};\n\n\n#endif\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/action_matrix_matrix_product_bis.hh",
    "content": "//=====================================================\n// File   :  action_matrix_matrix_product_bis.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_MATRIX_MATRIX_PRODUCT_BIS\n#define ACTION_MATRIX_MATRIX_PRODUCT_BIS\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include \"STL_timer.hh\"\n#include <string>\n#include \"init_function.hh\"\n#include \"init_vector.hh\"\n#include \"init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_matrix_matrix_product_bis {\n\npublic :\n\n  static inline std::string name( void )\n  {\n    return \"matrix_matrix_\"+Interface::name();\n  }\n\n  static double nb_op_base(int size){\n    return 2.0*size*size*size;\n  }\n\n  static double calculate( int nb_calc, int size ) {\n\n    // STL matrix and vector initialization\n\n    typename Interface::stl_matrix A_stl;\n    typename Interface::stl_matrix B_stl;\n    typename Interface::stl_matrix X_stl;\n\n    init_matrix<pseudo_random>(A_stl,size);\n    init_matrix<pseudo_random>(B_stl,size);\n    init_matrix<null_function>(X_stl,size);\n\n    // generic matrix and vector initialization\n\n    typename Interface::gene_matrix A_ref;\n    typename Interface::gene_matrix B_ref;\n    typename Interface::gene_matrix X_ref;\n\n    typename Interface::gene_matrix A;\n    typename Interface::gene_matrix B;\n    typename Interface::gene_matrix X;\n\n\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::matrix_from_stl(B_ref,B_stl);\n    Interface::matrix_from_stl(X_ref,X_stl);\n\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::matrix_from_stl(B,B_stl);\n    Interface::matrix_from_stl(X,X_stl);\n\n\n    // STL_timer utilities\n\n    STL_timer chronos;\n\n    // Baseline evaluation\n\n    chronos.start_baseline(nb_calc);\n\n    do {\n\n      Interface::copy_matrix(A_ref,A,size);\n      Interface::copy_matrix(B_ref,B,size);\n      Interface::copy_matrix(X_ref,X,size);\n\n\n      //      Interface::matrix_matrix_product(A,B,X,size); This line must be commented !!!!\n    }\n    while(chronos.check());\n\n    chronos.report(true);\n\n    // Time measurement\n\n    chronos.start(nb_calc);\n\n    do {\n\n      Interface::copy_matrix(A_ref,A,size);\n      Interface::copy_matrix(B_ref,B,size);\n      Interface::copy_matrix(X_ref,X,size);\n\n      Interface::matrix_matrix_product(A,B,X,size); // here it is not commented !!!!\n    }\n    while(chronos.check());\n\n    chronos.report(true);\n\n    double time=chronos.calculated_time/2000.0;\n\n    // calculation check\n\n    typename Interface::stl_matrix resu_stl(size);\n\n    Interface::matrix_to_stl(X,resu_stl);\n\n    STL_interface<typename Interface::real_type>::matrix_matrix_product(A_stl,B_stl,X_stl,size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n\n    if (error>1.e-6){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n      exit(1);\n    }\n\n    // deallocation and return time\n\n    Interface::free_matrix(A,size);\n    Interface::free_matrix(B,size);\n    Interface::free_matrix(X,size);\n\n    Interface::free_matrix(A_ref,size);\n    Interface::free_matrix(B_ref,size);\n    Interface::free_matrix(X_ref,size);\n\n    return time;\n  }\n\n};\n\n\n#endif\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/action_matrix_vector_product.hh",
    "content": "//=====================================================\n// File   :  action_matrix_vector_product.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_MATRIX_VECTOR_PRODUCT\n#define ACTION_MATRIX_VECTOR_PRODUCT\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_matrix_vector_product {\n\npublic :\n\n  // Ctor\n\n  BTL_DONT_INLINE Action_matrix_vector_product( int size ):_size(size)\n  {\n    MESSAGE(\"Action_matrix_vector_product Ctor\");\n\n    // STL matrix and vector initialization\n\n    init_matrix<pseudo_random>(A_stl,_size);\n    init_vector<pseudo_random>(B_stl,_size);\n    init_vector<null_function>(X_stl,_size);\n    init_vector<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::vector_from_stl(B_ref,B_stl);\n    Interface::vector_from_stl(B,B_stl);\n    Interface::vector_from_stl(X_ref,X_stl);\n    Interface::vector_from_stl(X,X_stl);\n\n  }\n\n  // invalidate copy ctor\n\n  Action_matrix_vector_product( const  Action_matrix_vector_product & )\n  {\n    INFOS(\"illegal call to Action_matrix_vector_product Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n\n  BTL_DONT_INLINE ~Action_matrix_vector_product( void ){\n\n    MESSAGE(\"Action_matrix_vector_product Dtor\");\n\n    // deallocation\n\n    Interface::free_matrix(A,_size);\n    Interface::free_vector(B);\n    Interface::free_vector(X);\n\n    Interface::free_matrix(A_ref,_size);\n    Interface::free_vector(B_ref);\n    Interface::free_vector(X_ref);\n\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"matrix_vector_\" + Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return 2.0*_size*_size;\n  }\n\n  BTL_DONT_INLINE  void initialize( void ){\n\n    Interface::copy_matrix(A_ref,A,_size);\n    Interface::copy_vector(B_ref,B,_size);\n    Interface::copy_vector(X_ref,X,_size);\n\n  }\n\n  BTL_DONT_INLINE void calculate( void ) {\n      BTL_ASM_COMMENT(\"#begin matrix_vector_product\");\n      Interface::matrix_vector_product(A,B,X,_size);\n      BTL_ASM_COMMENT(\"end matrix_vector_product\");\n  }\n\n  BTL_DONT_INLINE void check_result( void ){\n\n    // calculation check\n\n    Interface::vector_to_stl(X,resu_stl);\n\n    STL_interface<typename Interface::real_type>::matrix_vector_product(A_stl,B_stl,X_stl,_size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n\n    if (error>1.e-5){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n      exit(0);\n    }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix A_stl;\n  typename Interface::stl_vector B_stl;\n  typename Interface::stl_vector X_stl;\n  typename Interface::stl_vector resu_stl;\n\n  typename Interface::gene_matrix A_ref;\n  typename Interface::gene_vector B_ref;\n  typename Interface::gene_vector X_ref;\n\n  typename Interface::gene_matrix A;\n  typename Interface::gene_vector B;\n  typename Interface::gene_vector X;\n\n\n  int _size;\n\n};\n\n\n#endif\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/action_partial_lu.hh",
    "content": "//=====================================================\n// File   :  action_lu_decomp.hh\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_PARTIAL_LU\n#define ACTION_PARTIAL_LU\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_partial_lu {\n\npublic :\n\n  // Ctor\n\n  Action_partial_lu( int size ):_size(size)\n  {\n    MESSAGE(\"Action_partial_lu Ctor\");\n\n    // STL vector initialization\n    init_matrix<pseudo_random>(X_stl,_size);\n    init_matrix<null_function>(C_stl,_size);\n\n    // make sure X is invertible\n    for (int i=0; i<_size; ++i)\n      X_stl[i][i] = X_stl[i][i] * 1e2 + 1;\n\n    // generic matrix and vector initialization\n    Interface::matrix_from_stl(X_ref,X_stl);\n    Interface::matrix_from_stl(X,X_stl);\n    Interface::matrix_from_stl(C,C_stl);\n\n    _cost = 2.0*size*size*size/3.0 + size*size;\n  }\n\n  // invalidate copy ctor\n\n  Action_partial_lu( const  Action_partial_lu & )\n  {\n    INFOS(\"illegal call to Action_partial_lu Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n\n  ~Action_partial_lu( void ){\n\n    MESSAGE(\"Action_partial_lu Dtor\");\n\n    // deallocation\n    Interface::free_matrix(X_ref,_size);\n    Interface::free_matrix(X,_size);\n    Interface::free_matrix(C,_size);\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"partial_lu_decomp_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return _cost;\n  }\n\n  inline void initialize( void ){\n    Interface::copy_matrix(X_ref,X,_size);\n  }\n\n  inline void calculate( void ) {\n      Interface::partial_lu_decomp(X,C,_size);\n  }\n\n  void check_result( void ){\n    // calculation check\n//     Interface::matrix_to_stl(C,resu_stl);\n\n//     STL_interface<typename Interface::real_type>::lu_decomp(X_stl,C_stl,_size);\n//\n//     typename Interface::real_type error=\n//       STL_interface<typename Interface::real_type>::norm_diff(C_stl,resu_stl);\n//\n//     if (error>1.e-6){\n//       INFOS(\"WRONG CALCULATION...residual=\" << error);\n//       exit(0);\n//     }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix X_stl;\n  typename Interface::stl_matrix C_stl;\n\n  typename Interface::gene_matrix X_ref;\n  typename Interface::gene_matrix X;\n  typename Interface::gene_matrix C;\n\n  int _size;\n  double _cost;\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/action_rot.hh",
    "content": "\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_ROT\n#define ACTION_ROT\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_rot {\n\npublic :\n\n  // Ctor\n  BTL_DONT_INLINE Action_rot( int size ):_size(size)\n  {\n    MESSAGE(\"Action_rot Ctor\");\n\n    // STL matrix and vector initialization\n    typename Interface::stl_matrix tmp;\n    init_vector<pseudo_random>(A_stl,_size);\n    init_vector<pseudo_random>(B_stl,_size);\n\n    // generic matrix and vector initialization\n    Interface::vector_from_stl(A_ref,A_stl);\n    Interface::vector_from_stl(A,A_stl);\n    Interface::vector_from_stl(B_ref,B_stl);\n    Interface::vector_from_stl(B,B_stl);\n  }\n\n  // invalidate copy ctor\n  Action_rot( const  Action_rot & )\n  {\n    INFOS(\"illegal call to Action_rot Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n  BTL_DONT_INLINE ~Action_rot( void ){\n    MESSAGE(\"Action_rot Dtor\");\n    Interface::free_vector(A);\n    Interface::free_vector(B);\n    Interface::free_vector(A_ref);\n    Interface::free_vector(B_ref);\n  }\n\n  // action name\n  static inline std::string name( void )\n  {\n    return \"rot_\" + Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return 6.0*_size;\n  }\n\n  BTL_DONT_INLINE  void initialize( void ){\n    Interface::copy_vector(A_ref,A,_size);\n    Interface::copy_vector(B_ref,B,_size);\n  }\n\n  BTL_DONT_INLINE void calculate( void ) {\n    BTL_ASM_COMMENT(\"#begin rot\");\n    Interface::rot(A,B,0.5,0.6,_size);\n    BTL_ASM_COMMENT(\"end rot\");\n  }\n\n  BTL_DONT_INLINE void check_result( void ){\n    // calculation check\n//     Interface::vector_to_stl(X,resu_stl);\n\n//     STL_interface<typename Interface::real_type>::rot(A_stl,B_stl,X_stl,_size);\n\n//     typename Interface::real_type error=\n//       STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n\n//     if (error>1.e-3){\n//       INFOS(\"WRONG CALCULATION...residual=\" << error);\n//       exit(0);\n//     }\n\n  }\n\nprivate :\n\n  typename Interface::stl_vector A_stl;\n  typename Interface::stl_vector B_stl;\n\n  typename Interface::gene_vector A_ref;\n  typename Interface::gene_vector B_ref;\n\n  typename Interface::gene_vector A;\n  typename Interface::gene_vector B;\n\n  int _size;\n};\n\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/action_symv.hh",
    "content": "//=====================================================\n// File   :  action_symv.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_SYMV\n#define ACTION_SYMV\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_symv {\n\npublic :\n\n  // Ctor\n\n  BTL_DONT_INLINE Action_symv( int size ):_size(size)\n  {\n    MESSAGE(\"Action_symv Ctor\");\n\n    // STL matrix and vector initialization\n    init_matrix_symm<pseudo_random>(A_stl,_size);\n    init_vector<pseudo_random>(B_stl,_size);\n    init_vector<null_function>(X_stl,_size);\n    init_vector<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::vector_from_stl(B_ref,B_stl);\n    Interface::vector_from_stl(B,B_stl);\n    Interface::vector_from_stl(X_ref,X_stl);\n    Interface::vector_from_stl(X,X_stl);\n\n  }\n\n  // invalidate copy ctor\n\n  Action_symv( const  Action_symv & )\n  {\n    INFOS(\"illegal call to Action_symv Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n  BTL_DONT_INLINE ~Action_symv( void ){\n    Interface::free_matrix(A,_size);\n    Interface::free_vector(B);\n    Interface::free_vector(X);\n    Interface::free_matrix(A_ref,_size);\n    Interface::free_vector(B_ref);\n    Interface::free_vector(X_ref);\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"symv_\" + Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return 2.0*_size*_size;\n  }\n\n  BTL_DONT_INLINE  void initialize( void ){\n\n    Interface::copy_matrix(A_ref,A,_size);\n    Interface::copy_vector(B_ref,B,_size);\n    Interface::copy_vector(X_ref,X,_size);\n\n  }\n\n  BTL_DONT_INLINE void calculate( void ) {\n      BTL_ASM_COMMENT(\"#begin symv\");\n      Interface::symv(A,B,X,_size);\n      BTL_ASM_COMMENT(\"end symv\");\n  }\n\n  BTL_DONT_INLINE void check_result( void ){\n    if (_size>128) return;\n    // calculation check\n    Interface::vector_to_stl(X,resu_stl);\n\n    STL_interface<typename Interface::real_type>::symv(A_stl,B_stl,X_stl,_size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n\n    if (error>1.e-5){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n      exit(0);\n    }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix A_stl;\n  typename Interface::stl_vector B_stl;\n  typename Interface::stl_vector X_stl;\n  typename Interface::stl_vector resu_stl;\n\n  typename Interface::gene_matrix A_ref;\n  typename Interface::gene_vector B_ref;\n  typename Interface::gene_vector X_ref;\n\n  typename Interface::gene_matrix A;\n  typename Interface::gene_vector B;\n  typename Interface::gene_vector X;\n\n\n  int _size;\n\n};\n\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/action_syr2.hh",
    "content": "//=====================================================\n// File   :  action_syr2.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_SYR2\n#define ACTION_SYR2\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_syr2 {\n\npublic :\n\n  // Ctor\n\n  BTL_DONT_INLINE Action_syr2( int size ):_size(size)\n  {\n    // STL matrix and vector initialization\n    typename Interface::stl_matrix tmp;\n    init_matrix<pseudo_random>(A_stl,_size);\n    init_vector<pseudo_random>(B_stl,_size);\n    init_vector<pseudo_random>(X_stl,_size);\n    init_vector<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::vector_from_stl(B_ref,B_stl);\n    Interface::vector_from_stl(B,B_stl);\n    Interface::vector_from_stl(X_ref,X_stl);\n    Interface::vector_from_stl(X,X_stl);\n  }\n\n  // invalidate copy ctor\n  Action_syr2( const  Action_syr2 & )\n  {\n    INFOS(\"illegal call to Action_syr2 Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n  BTL_DONT_INLINE ~Action_syr2( void ){\n    Interface::free_matrix(A,_size);\n    Interface::free_vector(B);\n    Interface::free_vector(X);\n    Interface::free_matrix(A_ref,_size);\n    Interface::free_vector(B_ref);\n    Interface::free_vector(X_ref);\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"syr2_\" + Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return 2.0*_size*_size;\n  }\n\n  BTL_DONT_INLINE  void initialize( void ){\n    Interface::copy_matrix(A_ref,A,_size);\n    Interface::copy_vector(B_ref,B,_size);\n    Interface::copy_vector(X_ref,X,_size);\n  }\n\n  BTL_DONT_INLINE void calculate( void ) {\n      BTL_ASM_COMMENT(\"#begin syr2\");\n      Interface::syr2(A,B,X,_size);\n      BTL_ASM_COMMENT(\"end syr2\");\n  }\n\n  BTL_DONT_INLINE void check_result( void ){\n    // calculation check\n    Interface::vector_to_stl(X,resu_stl);\n\n    STL_interface<typename Interface::real_type>::syr2(A_stl,B_stl,X_stl,_size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n\n    if (error>1.e-3){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n//       exit(0);\n    }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix A_stl;\n  typename Interface::stl_vector B_stl;\n  typename Interface::stl_vector X_stl;\n  typename Interface::stl_vector resu_stl;\n\n  typename Interface::gene_matrix A_ref;\n  typename Interface::gene_vector B_ref;\n  typename Interface::gene_vector X_ref;\n\n  typename Interface::gene_matrix A;\n  typename Interface::gene_vector B;\n  typename Interface::gene_vector X;\n\n\n  int _size;\n\n};\n\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/action_trisolve.hh",
    "content": "//=====================================================\n// File   :  action_trisolve.hh\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_TRISOLVE\n#define ACTION_TRISOLVE\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_trisolve {\n\npublic :\n\n  // Ctor\n\n  Action_trisolve( int size ):_size(size)\n  {\n    MESSAGE(\"Action_trisolve Ctor\");\n\n    // STL vector initialization\n    init_matrix<pseudo_random>(L_stl,_size);\n    init_vector<pseudo_random>(B_stl,_size);\n    init_vector<null_function>(X_stl,_size);\n    for (int j=0; j<_size; ++j)\n    {\n      for (int i=0; i<j; ++i)\n        L_stl[j][i] = 0;\n      L_stl[j][j] += 3;\n    }\n\n    init_vector<null_function>(resu_stl,_size);\n\n    // generic matrix and vector initialization\n    Interface::matrix_from_stl(L,L_stl);\n    Interface::vector_from_stl(X,X_stl);\n    Interface::vector_from_stl(B,B_stl);\n\n    _cost = 0;\n    for (int j=0; j<_size; ++j)\n    {\n      _cost += 2*j + 1;\n    }\n  }\n\n  // invalidate copy ctor\n\n  Action_trisolve( const  Action_trisolve & )\n  {\n    INFOS(\"illegal call to Action_trisolve Copy Ctor\");\n    exit(1);\n  }\n\n  // Dtor\n\n  ~Action_trisolve( void ){\n\n    MESSAGE(\"Action_trisolve Dtor\");\n\n    // deallocation\n    Interface::free_matrix(L,_size);\n    Interface::free_vector(B);\n    Interface::free_vector(X);\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"trisolve_vector_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return _cost;\n  }\n\n  inline void initialize( void ){\n    //Interface::copy_vector(X_ref,X,_size);\n  }\n\n  inline void calculate( void ) {\n      Interface::trisolve_lower(L,B,X,_size);\n  }\n\n  void check_result(){\n    if (_size>128) return;\n    // calculation check\n    Interface::vector_to_stl(X,resu_stl);\n\n    STL_interface<typename Interface::real_type>::trisolve_lower(L_stl,B_stl,X_stl,_size);\n\n    typename Interface::real_type error=\n      STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n\n    if (error>1.e-4){\n      INFOS(\"WRONG CALCULATION...residual=\" << error);\n      exit(2);\n    } //else INFOS(\"CALCULATION OK...residual=\" << error);\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix L_stl;\n  typename Interface::stl_vector X_stl;\n  typename Interface::stl_vector B_stl;\n  typename Interface::stl_vector resu_stl;\n\n  typename Interface::gene_matrix L;\n  typename Interface::gene_vector X;\n  typename Interface::gene_vector B;\n\n  int _size;\n  double _cost;\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/action_trisolve_matrix.hh",
    "content": "//=====================================================\n// File   :  action_matrix_matrix_product.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_TRISOLVE_MATRIX_PRODUCT\n#define ACTION_TRISOLVE_MATRIX_PRODUCT\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_trisolve_matrix {\n\npublic :\n\n  // Ctor\n\n  Action_trisolve_matrix( int size ):_size(size)\n  {\n    MESSAGE(\"Action_trisolve_matrix Ctor\");\n\n    // STL matrix and vector initialization\n\n    init_matrix<pseudo_random>(A_stl,_size);\n    init_matrix<pseudo_random>(B_stl,_size);\n    init_matrix<null_function>(X_stl,_size);\n    init_matrix<null_function>(resu_stl,_size);\n\n    for (int j=0; j<_size; ++j)\n    {\n      for (int i=0; i<j; ++i)\n        A_stl[j][i] = 0;\n      A_stl[j][j] += 3;\n    }\n\n    // generic matrix and vector initialization\n\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::matrix_from_stl(B_ref,B_stl);\n    Interface::matrix_from_stl(X_ref,X_stl);\n\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::matrix_from_stl(B,B_stl);\n    Interface::matrix_from_stl(X,X_stl);\n\n    _cost = 0;\n    for (int j=0; j<_size; ++j)\n    {\n      _cost += 2*j + 1;\n    }\n    _cost *= _size;\n  }\n\n  // invalidate copy ctor\n\n  Action_trisolve_matrix( const  Action_trisolve_matrix & )\n  {\n    INFOS(\"illegal call to Action_trisolve_matrix Copy Ctor\");\n    exit(0);\n  }\n\n  // Dtor\n\n  ~Action_trisolve_matrix( void ){\n\n    MESSAGE(\"Action_trisolve_matrix Dtor\");\n\n    // deallocation\n\n    Interface::free_matrix(A,_size);\n    Interface::free_matrix(B,_size);\n    Interface::free_matrix(X,_size);\n\n    Interface::free_matrix(A_ref,_size);\n    Interface::free_matrix(B_ref,_size);\n    Interface::free_matrix(X_ref,_size);\n\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"trisolve_matrix_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return _cost;\n  }\n\n  inline void initialize( void ){\n\n    Interface::copy_matrix(A_ref,A,_size);\n    Interface::copy_matrix(B_ref,B,_size);\n    Interface::copy_matrix(X_ref,X,_size);\n\n  }\n\n  inline void calculate( void ) {\n      Interface::trisolve_lower_matrix(A,B,X,_size);\n  }\n\n  void check_result( void ){\n\n    // calculation check\n\n//     Interface::matrix_to_stl(X,resu_stl);\n//\n//     STL_interface<typename Interface::real_type>::matrix_matrix_product(A_stl,B_stl,X_stl,_size);\n//\n//     typename Interface::real_type error=\n//       STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n//\n//     if (error>1.e-6){\n//       INFOS(\"WRONG CALCULATION...residual=\" << error);\n// //       exit(1);\n//     }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix A_stl;\n  typename Interface::stl_matrix B_stl;\n  typename Interface::stl_matrix X_stl;\n  typename Interface::stl_matrix resu_stl;\n\n  typename Interface::gene_matrix A_ref;\n  typename Interface::gene_matrix B_ref;\n  typename Interface::gene_matrix X_ref;\n\n  typename Interface::gene_matrix A;\n  typename Interface::gene_matrix B;\n  typename Interface::gene_matrix X;\n\n  int _size;\n  double _cost;\n\n};\n\n\n#endif\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/action_trmm.hh",
    "content": "//=====================================================\n// File   :  action_matrix_matrix_product.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef ACTION_TRMM\n#define ACTION_TRMM\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include <string>\n#include \"init/init_function.hh\"\n#include \"init/init_vector.hh\"\n#include \"init/init_matrix.hh\"\n\nusing namespace std;\n\ntemplate<class Interface>\nclass Action_trmm {\n\npublic :\n\n  // Ctor\n\n  Action_trmm( int size ):_size(size)\n  {\n    MESSAGE(\"Action_trmm Ctor\");\n\n    // STL matrix and vector initialization\n\n    init_matrix<pseudo_random>(A_stl,_size);\n    init_matrix<pseudo_random>(B_stl,_size);\n    init_matrix<null_function>(X_stl,_size);\n    init_matrix<null_function>(resu_stl,_size);\n\n    for (int j=0; j<_size; ++j)\n    {\n      for (int i=0; i<j; ++i)\n        A_stl[j][i] = 0;\n      A_stl[j][j] += 3;\n    }\n\n    // generic matrix and vector initialization\n\n    Interface::matrix_from_stl(A_ref,A_stl);\n    Interface::matrix_from_stl(B_ref,B_stl);\n    Interface::matrix_from_stl(X_ref,X_stl);\n\n    Interface::matrix_from_stl(A,A_stl);\n    Interface::matrix_from_stl(B,B_stl);\n    Interface::matrix_from_stl(X,X_stl);\n\n    _cost = 0;\n    for (int j=0; j<_size; ++j)\n    {\n      _cost += 2*j + 1;\n    }\n    _cost *= _size;\n  }\n\n  // invalidate copy ctor\n\n  Action_trmm( const  Action_trmm & )\n  {\n    INFOS(\"illegal call to Action_trmm Copy Ctor\");\n    exit(0);\n  }\n\n  // Dtor\n\n  ~Action_trmm( void ){\n\n    MESSAGE(\"Action_trmm Dtor\");\n\n    // deallocation\n\n    Interface::free_matrix(A,_size);\n    Interface::free_matrix(B,_size);\n    Interface::free_matrix(X,_size);\n\n    Interface::free_matrix(A_ref,_size);\n    Interface::free_matrix(B_ref,_size);\n    Interface::free_matrix(X_ref,_size);\n\n  }\n\n  // action name\n\n  static inline std::string name( void )\n  {\n    return \"trmm_\"+Interface::name();\n  }\n\n  double nb_op_base( void ){\n    return _cost;\n  }\n\n  inline void initialize( void ){\n\n    Interface::copy_matrix(A_ref,A,_size);\n    Interface::copy_matrix(B_ref,B,_size);\n    Interface::copy_matrix(X_ref,X,_size);\n\n  }\n\n  inline void calculate( void ) {\n      Interface::trmm(A,B,X,_size);\n  }\n\n  void check_result( void ){\n\n    // calculation check\n\n//     Interface::matrix_to_stl(X,resu_stl);\n//\n//     STL_interface<typename Interface::real_type>::matrix_matrix_product(A_stl,B_stl,X_stl,_size);\n//\n//     typename Interface::real_type error=\n//       STL_interface<typename Interface::real_type>::norm_diff(X_stl,resu_stl);\n//\n//     if (error>1.e-6){\n//       INFOS(\"WRONG CALCULATION...residual=\" << error);\n// //       exit(1);\n//     }\n\n  }\n\nprivate :\n\n  typename Interface::stl_matrix A_stl;\n  typename Interface::stl_matrix B_stl;\n  typename Interface::stl_matrix X_stl;\n  typename Interface::stl_matrix resu_stl;\n\n  typename Interface::gene_matrix A_ref;\n  typename Interface::gene_matrix B_ref;\n  typename Interface::gene_matrix X_ref;\n\n  typename Interface::gene_matrix A;\n  typename Interface::gene_matrix B;\n  typename Interface::gene_matrix X;\n\n  int _size;\n  double _cost;\n\n};\n\n\n#endif\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/actions/basic_actions.hh",
    "content": "\n#include \"action_axpy.hh\"\n#include \"action_axpby.hh\"\n\n#include \"action_matrix_vector_product.hh\"\n#include \"action_atv_product.hh\"\n\n#include \"action_matrix_matrix_product.hh\"\n#include \"action_ata_product.hh\"\n#include \"action_aat_product.hh\"\n\n#include \"action_trisolve.hh\"\n#include \"action_trmm.hh\"\n#include \"action_symv.hh\"\n// #include \"action_symm.hh\"\n#include \"action_syr2.hh\"\n#include \"action_ger.hh\"\n#include \"action_rot.hh\"\n\n// #include \"action_lu_solve.hh\"\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/cmake/FindACML.cmake",
    "content": "\nif (ACML_LIBRARIES)\n  set(ACML_FIND_QUIETLY TRUE)\nendif ()\n\nfind_library(ACML_LIBRARIES\n  NAMES\n  acml_mp acml_mv\n  PATHS\n  $ENV{ACMLDIR}/lib\n  $ENV{ACML_DIR}/lib\n  ${LIB_INSTALL_DIR}\n)\n\nfind_file(ACML_LIBRARIES\n  NAMES\n  libacml_mp.so\n  PATHS\n  /usr/lib\n  /usr/lib64\n  $ENV{ACMLDIR}/lib\n  ${LIB_INSTALL_DIR}\n)\n\nif(NOT ACML_LIBRARIES)\n    message(STATUS \"Multi-threaded library not found, looking for single-threaded\")\n    find_library(ACML_LIBRARIES\n        NAMES\n        acml acml_mv\n        PATHS\n        $ENV{ACMLDIR}/lib\n        $ENV{ACML_DIR}/lib\n        ${LIB_INSTALL_DIR}\n        )\n    find_file(ACML_LIBRARIES\n        libacml.so libacml_mv.so\n        PATHS\n        /usr/lib\n        /usr/lib64\n        $ENV{ACMLDIR}/lib\n        ${LIB_INSTALL_DIR}\n        )\nendif()\n\n\n\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(ACML DEFAULT_MSG ACML_LIBRARIES)\n\nmark_as_advanced(ACML_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/cmake/FindATLAS.cmake",
    "content": "\nif (ATLAS_LIBRARIES)\n  set(ATLAS_FIND_QUIETLY TRUE)\nendif ()\n\nfind_file(ATLAS_LIB libatlas.so.3 PATHS /usr/lib /usr/lib/atlas /usr/lib64 /usr/lib64/atlas $ENV{ATLASDIR} ${LIB_INSTALL_DIR})\nfind_library(ATLAS_LIB satlas PATHS $ENV{ATLASDIR} ${LIB_INSTALL_DIR})\n\nfind_file(ATLAS_LAPACK NAMES liblapack_atlas.so.3 liblapack.so.3 PATHS /usr/lib /usr/lib/atlas /usr/lib64 /usr/lib64/atlas $ENV{ATLASDIR} ${LIB_INSTALL_DIR})\nfind_library(ATLAS_LAPACK NAMES lapack_atlas lapack PATHS $ENV{ATLASDIR} ${LIB_INSTALL_DIR})\n\nfind_file(ATLAS_F77BLAS libf77blas.so.3 PATHS /usr/lib /usr/lib/atlas /usr/lib64 /usr/lib64/atlas $ENV{ATLASDIR} ${LIB_INSTALL_DIR})\nfind_library(ATLAS_F77BLAS f77blas PATHS $ENV{ATLASDIR} ${LIB_INSTALL_DIR})\n\nif(ATLAS_LIB AND ATLAS_CBLAS AND ATLAS_LAPACK AND ATLAS_F77BLAS)\n\n  set(ATLAS_LIBRARIES ${ATLAS_LAPACK}  ${ATLAS_LIB})\n  \n  # search the default lapack lib link to it\n  find_file(ATLAS_REFERENCE_LAPACK liblapack.so.3 PATHS /usr/lib /usr/lib64)\n  find_library(ATLAS_REFERENCE_LAPACK NAMES lapack)\n#   if(ATLAS_REFERENCE_LAPACK)\n#     set(ATLAS_LIBRARIES ${ATLAS_LIBRARIES} ${ATLAS_REFERENCE_LAPACK})\n#   endif()\n  \nendif()\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(ATLAS DEFAULT_MSG ATLAS_LIBRARIES)\n\nmark_as_advanced(ATLAS_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/cmake/FindBLAZE.cmake",
    "content": "# - Try to find eigen2 headers\n# Once done this will define\n#\n#  BLAZE_FOUND - system has blaze lib\n#  BLAZE_INCLUDE_DIR - the blaze include directory\n#\n# Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n# Adapted from FindEigen.cmake:\n# Copyright (c) 2006, 2007 Montel Laurent, <montel@kde.org>\n# Redistribution and use is allowed according to the terms of the BSD license.\n# For details see the accompanying COPYING-CMAKE-SCRIPTS file.\n\nif (BLAZE_INCLUDE_DIR)\n\n  # in cache already\n  set(BLAZE_FOUND TRUE)\n\nelse ()\n\nfind_path(BLAZE_INCLUDE_DIR NAMES blaze/Blaze.h\n     PATHS\n     ${INCLUDE_INSTALL_DIR}\n   )\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(BLAZE DEFAULT_MSG BLAZE_INCLUDE_DIR)\n\nmark_as_advanced(BLAZE_INCLUDE_DIR)\n\nendif()\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/cmake/FindBlitz.cmake",
    "content": "# - Try to find blitz lib\n# Once done this will define\n#\n#  BLITZ_FOUND - system has blitz lib\n#  BLITZ_INCLUDES - the blitz include directory\n#  BLITZ_LIBRARIES - The libraries needed to use blitz\n\n# Copyright (c) 2006, Montel Laurent, <montel@kde.org>\n# Copyright (c) 2007, Allen Winter, <winter@kde.org>\n# Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n# Redistribution and use is allowed according to the terms of the BSD license.\n# For details see the accompanying COPYING-CMAKE-SCRIPTS file.\n\n# include(FindLibraryWithDebug)\n\nif (BLITZ_INCLUDES AND BLITZ_LIBRARIES)\n  set(Blitz_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(BLITZ_INCLUDES\n  NAMES\n  blitz/array.h\n  PATH_SUFFIXES blitz*\n  PATHS\n  $ENV{BLITZDIR}/include\n  ${INCLUDE_INSTALL_DIR}\n)\n\nfind_library(BLITZ_LIBRARIES\n  blitz\n  PATHS\n  $ENV{BLITZDIR}/lib\n  ${LIB_INSTALL_DIR}\n)\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(Blitz DEFAULT_MSG\n                                  BLITZ_INCLUDES BLITZ_LIBRARIES)\n\nmark_as_advanced(BLITZ_INCLUDES BLITZ_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/cmake/FindCBLAS.cmake",
    "content": "# include(FindLibraryWithDebug)\n\nif (CBLAS_INCLUDES AND CBLAS_LIBRARIES)\n  set(CBLAS_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(CBLAS_INCLUDES\n  NAMES\n  cblas.h\n  PATHS\n  $ENV{CBLASDIR}/include\n  ${INCLUDE_INSTALL_DIR}\n)\n\nfind_library(CBLAS_LIBRARIES\n  cblas\n  PATHS\n  $ENV{CBLASDIR}/lib\n  ${LIB_INSTALL_DIR}\n)\n\nfind_file(CBLAS_LIBRARIES\n  libcblas.so.3\n  PATHS\n  /usr/lib\n  /usr/lib64\n  $ENV{CBLASDIR}/lib\n  ${LIB_INSTALL_DIR}\n)\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(CBLAS DEFAULT_MSG\n                                  CBLAS_INCLUDES CBLAS_LIBRARIES)\n\nmark_as_advanced(CBLAS_INCLUDES CBLAS_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/cmake/FindGMM.cmake",
    "content": "if (GMM_INCLUDE_DIR)\n  # in cache already\n  set(GMM_FOUND TRUE)\nelse ()\n\nfind_path(GMM_INCLUDE_DIR NAMES gmm/gmm.h\n     PATHS\n     ${INCLUDE_INSTALL_DIR}\n     ${GMM_INCLUDE_PATH}\n   )\n\ninclude(FindPackageHandleStandardArgs)\nFIND_PACKAGE_HANDLE_STANDARD_ARGS(GMM DEFAULT_MSG GMM_INCLUDE_DIR )\n\nmark_as_advanced(GMM_INCLUDE_DIR)\n\nendif()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/cmake/FindMKL.cmake",
    "content": "\nif (MKL_LIBRARIES)\n  set(MKL_FIND_QUIETLY TRUE)\nendif ()\n\nif(CMAKE_MINOR_VERSION GREATER 4)\n\nif(${CMAKE_HOST_SYSTEM_PROCESSOR} STREQUAL \"x86_64\")\n\nfind_library(MKL_LIBRARIES\n  mkl_core\n  PATHS\n  $ENV{MKLLIB}\n  /opt/intel/mkl/*/lib/em64t\n  /opt/intel/Compiler/*/*/mkl/lib/em64t\n  ${LIB_INSTALL_DIR}\n)\n\nfind_library(MKL_GUIDE\n  guide\n  PATHS\n  $ENV{MKLLIB}\n  /opt/intel/mkl/*/lib/em64t\n  /opt/intel/Compiler/*/*/mkl/lib/em64t\n  /opt/intel/Compiler/*/*/lib/intel64\n  ${LIB_INSTALL_DIR}\n)\n\nif(MKL_LIBRARIES AND MKL_GUIDE)\n  set(MKL_LIBRARIES ${MKL_LIBRARIES} mkl_intel_lp64 mkl_sequential ${MKL_GUIDE} pthread)\nendif()\n\nelse()\n\nfind_library(MKL_LIBRARIES\n  mkl_core\n  PATHS\n  $ENV{MKLLIB}\n  /opt/intel/mkl/*/lib/32\n  /opt/intel/Compiler/*/*/mkl/lib/32\n  ${LIB_INSTALL_DIR}\n)\n\nfind_library(MKL_GUIDE\n  guide\n  PATHS\n  $ENV{MKLLIB}\n  /opt/intel/mkl/*/lib/32\n  /opt/intel/Compiler/*/*/mkl/lib/32\n  /opt/intel/Compiler/*/*/lib/intel32\n  ${LIB_INSTALL_DIR}\n)\n\nif(MKL_LIBRARIES AND MKL_GUIDE)\n  set(MKL_LIBRARIES ${MKL_LIBRARIES} mkl_intel mkl_sequential ${MKL_GUIDE} pthread)\nendif()\n\nendif()\n\nendif()\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(MKL DEFAULT_MSG MKL_LIBRARIES)\n\nmark_as_advanced(MKL_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/cmake/FindMTL4.cmake",
    "content": "# - Try to find eigen2 headers\n# Once done this will define\n#\n#  MTL4_FOUND - system has eigen2 lib\n#  MTL4_INCLUDE_DIR - the eigen2 include directory\n#\n# Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n# Adapted from FindEigen.cmake:\n# Copyright (c) 2006, 2007 Montel Laurent, <montel@kde.org>\n# Redistribution and use is allowed according to the terms of the BSD license.\n# For details see the accompanying COPYING-CMAKE-SCRIPTS file.\n\nif (MTL4_INCLUDE_DIR)\n\n  # in cache already\n  set(MTL4_FOUND TRUE)\n\nelse ()\n\nfind_path(MTL4_INCLUDE_DIR NAMES boost/numeric/mtl/mtl.hpp\n     PATHS\n     ${INCLUDE_INSTALL_DIR}\n   )\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(MTL4 DEFAULT_MSG MTL4_INCLUDE_DIR)\n\nmark_as_advanced(MTL4_INCLUDE_DIR)\n\nendif()\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/cmake/FindOPENBLAS.cmake",
    "content": "\nif (OPENBLAS_LIBRARIES)\n  set(OPENBLAS_FIND_QUIETLY TRUE)\nendif ()\n\nfind_file(OPENBLAS_LIBRARIES NAMES libopenblas.so libopenblas.so.0 PATHS /usr/lib /usr/lib64 $ENV{OPENBLASDIR} ${LIB_INSTALL_DIR})\nfind_library(OPENBLAS_LIBRARIES openblas PATHS $ENV{OPENBLASDIR} ${LIB_INSTALL_DIR})\n\nif(OPENBLAS_LIBRARIES AND CMAKE_COMPILER_IS_GNUCXX)\n  set(OPENBLAS_LIBRARIES ${OPENBLAS_LIBRARIES} \"-lpthread -lgfortran\")\nendif()\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(OPENBLAS DEFAULT_MSG\n                                  OPENBLAS_LIBRARIES)\n\nmark_as_advanced(OPENBLAS_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/cmake/FindPackageHandleStandardArgs.cmake",
    "content": "# FIND_PACKAGE_HANDLE_STANDARD_ARGS(NAME (DEFAULT_MSG|\"Custom failure message\") VAR1 ... )\n#\n# This macro is intended to be used in FindXXX.cmake modules files.\n# It handles the REQUIRED and QUIET argument to find_package() and\n# it also sets the <UPPERCASED_NAME>_FOUND variable.\n# The package is found if all variables listed are TRUE.\n# Example:\n#\n#    FIND_PACKAGE_HANDLE_STANDARD_ARGS(LibXml2 DEFAULT_MSG LIBXML2_LIBRARIES LIBXML2_INCLUDE_DIR)\n#\n# LibXml2 is considered to be found, if both LIBXML2_LIBRARIES and \n# LIBXML2_INCLUDE_DIR are valid. Then also LIBXML2_FOUND is set to TRUE.\n# If it is not found and REQUIRED was used, it fails with FATAL_ERROR, \n# independent whether QUIET was used or not.\n#\n# If it is found, the location is reported using the VAR1 argument, so \n# here a message \"Found LibXml2: /usr/lib/libxml2.so\" will be printed out.\n# If the second argument is DEFAULT_MSG, the message in the failure case will \n# be \"Could NOT find LibXml2\", if you don't like this message you can specify\n# your own custom failure message there.\n\nmacro(FIND_PACKAGE_HANDLE_STANDARD_ARGS _NAME _FAIL_MSG _VAR1 )\n\n  if(\"${_FAIL_MSG}\" STREQUAL \"DEFAULT_MSG\")\n    if (${_NAME}_FIND_REQUIRED)\n      set(_FAIL_MESSAGE \"Could not find REQUIRED package ${_NAME}\")\n    else (${_NAME}_FIND_REQUIRED)\n      set(_FAIL_MESSAGE \"Could not find OPTIONAL package ${_NAME}\")\n    endif (${_NAME}_FIND_REQUIRED)\n  else(\"${_FAIL_MSG}\" STREQUAL \"DEFAULT_MSG\")\n    set(_FAIL_MESSAGE \"${_FAIL_MSG}\")\n  endif(\"${_FAIL_MSG}\" STREQUAL \"DEFAULT_MSG\")\n\n  string(TOUPPER ${_NAME} _NAME_UPPER)\n\n  set(${_NAME_UPPER}_FOUND TRUE)\n  if(NOT ${_VAR1})\n    set(${_NAME_UPPER}_FOUND FALSE)\n  endif(NOT ${_VAR1})\n\n  foreach(_CURRENT_VAR ${ARGN})\n    if(NOT ${_CURRENT_VAR})\n      set(${_NAME_UPPER}_FOUND FALSE)\n    endif(NOT ${_CURRENT_VAR})\n  endforeach(_CURRENT_VAR)\n\n  if (${_NAME_UPPER}_FOUND)\n    if (NOT ${_NAME}_FIND_QUIETLY)\n        message(STATUS \"Found ${_NAME}: ${${_VAR1}}\")\n    endif (NOT ${_NAME}_FIND_QUIETLY)\n  else (${_NAME_UPPER}_FOUND)\n    if (${_NAME}_FIND_REQUIRED)\n        message(FATAL_ERROR \"${_FAIL_MESSAGE}\")\n    else (${_NAME}_FIND_REQUIRED)\n      if (NOT ${_NAME}_FIND_QUIETLY)\n        message(STATUS \"${_FAIL_MESSAGE}\")\n      endif (NOT ${_NAME}_FIND_QUIETLY)\n    endif (${_NAME}_FIND_REQUIRED)\n  endif (${_NAME_UPPER}_FOUND)\nendmacro(FIND_PACKAGE_HANDLE_STANDARD_ARGS)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/cmake/FindTvmet.cmake",
    "content": "# - Try to find tvmet headers\n# Once done this will define\n#\n#  TVMET_FOUND - system has tvmet lib\n#  TVMET_INCLUDE_DIR - the tvmet include directory\n#\n# Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n# Adapted from FindEigen.cmake:\n# Copyright (c) 2006, 2007 Montel Laurent, <montel@kde.org>\n# Redistribution and use is allowed according to the terms of the BSD license.\n# For details see the accompanying COPYING-CMAKE-SCRIPTS file.\n\nif (TVMET_INCLUDE_DIR)\n\n  # in cache already\n  set(TVMET_FOUND TRUE)\n\nelse ()\n\nfind_path(TVMET_INCLUDE_DIR NAMES tvmet/tvmet.h\n     PATHS\n     ${TVMETDIR}/\n     ${INCLUDE_INSTALL_DIR}\n   )\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(Tvmet DEFAULT_MSG TVMET_INCLUDE_DIR)\n\nmark_as_advanced(TVMET_INCLUDE_DIR)\n\nendif()\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/cmake/MacroOptionalAddSubdirectory.cmake",
    "content": "# - MACRO_OPTIONAL_ADD_SUBDIRECTORY() combines add_subdirectory() with an option()\n# MACRO_OPTIONAL_ADD_SUBDIRECTORY( <dir> )\n# If you use MACRO_OPTIONAL_ADD_SUBDIRECTORY() instead of add_subdirectory(),\n# this will have two effects\n# 1 - CMake will not complain if the directory doesn't exist\n#     This makes sense if you want to distribute just one of the subdirs\n#     in a source package, e.g. just one of the subdirs in kdeextragear.\n# 2 - If the directory exists, it will offer an option to skip the \n#     subdirectory.\n#     This is useful if you want to compile only a subset of all\n#     directories.\n\n# Copyright (c) 2007, Alexander Neundorf, <neundorf@kde.org>\n#\n# Redistribution and use is allowed according to the terms of the BSD license.\n# For details see the accompanying COPYING-CMAKE-SCRIPTS file.\n\n\nmacro (MACRO_OPTIONAL_ADD_SUBDIRECTORY _dir )\n   get_filename_component(_fullPath ${_dir} ABSOLUTE)\n   if(EXISTS ${_fullPath})\n      if(${ARGC} EQUAL 2)\n        option(BUILD_${_dir} \"Build directory ${_dir}\" ${ARGV1})\n      else(${ARGC} EQUAL 2)\n        option(BUILD_${_dir} \"Build directory ${_dir}\" TRUE)\n      endif(${ARGC} EQUAL 2)\n      if(BUILD_${_dir})\n         add_subdirectory(${_dir})\n      endif(BUILD_${_dir})\n   endif(EXISTS ${_fullPath})\nendmacro (MACRO_OPTIONAL_ADD_SUBDIRECTORY)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/bench.hh",
    "content": "//=====================================================\n// File   :  bench.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:16 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef BENCH_HH\n#define BENCH_HH\n\n#include \"btl.hh\"\n#include \"bench_parameter.hh\"\n#include <iostream>\n#include \"utilities.h\"\n#include \"size_lin_log.hh\"\n#include \"xy_file.hh\"\n#include <vector>\n#include <string>\n#include \"timers/portable_perf_analyzer.hh\"\n// #include \"timers/mixed_perf_analyzer.hh\"\n// #include \"timers/x86_perf_analyzer.hh\"\n// #include \"timers/STL_perf_analyzer.hh\"\n#ifdef HAVE_MKL\nextern \"C\" void cblas_saxpy(const int, const float, const float*, const int, float *, const int);\n#endif\nusing namespace std;\n\ntemplate <template<class> class Perf_Analyzer, class Action>\nBTL_DONT_INLINE void bench( int size_min, int size_max, int nb_point )\n{\n  if (BtlConfig::skipAction(Action::name()))\n    return;\n\n  string filename=\"bench_\"+Action::name()+\".dat\";\n\n  INFOS(\"starting \" <<filename);\n\n  // utilities\n\n  std::vector<double> tab_mflops(nb_point);\n  std::vector<int> tab_sizes(nb_point);\n\n  // matrices and vector size calculations\n  size_lin_log(nb_point,size_min,size_max,tab_sizes);\n\n  std::vector<int> oldSizes;\n  std::vector<double> oldFlops;\n  bool hasOldResults = read_xy_file(filename, oldSizes, oldFlops, true);\n  int oldi = oldSizes.size() - 1;\n\n  // loop on matrix size\n  Perf_Analyzer<Action> perf_action;\n  for (int i=nb_point-1;i>=0;i--)\n  {\n    //INFOS(\"size=\" <<tab_sizes[i]<<\"   (\"<<nb_point-i<<\"/\"<<nb_point<<\")\");\n    std::cout << \" \" << \"size = \" << tab_sizes[i] << \"  \" << std::flush;\n\n    BTL_DISABLE_SSE_EXCEPTIONS();\n    #ifdef HAVE_MKL\n    {\n      float dummy;\n      cblas_saxpy(1,0,&dummy,1,&dummy,1);\n    }\n    #endif\n\n    tab_mflops[i] = perf_action.eval_mflops(tab_sizes[i]);\n    std::cout << tab_mflops[i];\n    \n    if (hasOldResults)\n    {\n      while (oldi>=0 && oldSizes[oldi]>tab_sizes[i])\n        --oldi;\n      if (oldi>=0 && oldSizes[oldi]==tab_sizes[i])\n      {\n        if (oldFlops[oldi]<tab_mflops[i])\n          std::cout << \"\\t > \";\n        else\n          std::cout << \"\\t < \";\n        std::cout << oldFlops[oldi];\n      }\n      --oldi;\n    }\n    std::cout << \" MFlops    (\" << nb_point-i << \"/\" << nb_point << \")\" << std::endl;\n  }\n\n  if (!BtlConfig::Instance.overwriteResults)\n  {\n    if (hasOldResults)\n    {\n      // merge the two data\n      std::vector<int> newSizes;\n      std::vector<double> newFlops;\n      unsigned int i=0;\n      unsigned int j=0;\n      while (i<tab_sizes.size() && j<oldSizes.size())\n      {\n        if (tab_sizes[i] == oldSizes[j])\n        {\n          newSizes.push_back(tab_sizes[i]);\n          newFlops.push_back(std::max(tab_mflops[i], oldFlops[j]));\n          ++i;\n          ++j;\n        }\n        else if (tab_sizes[i] < oldSizes[j])\n        {\n          newSizes.push_back(tab_sizes[i]);\n          newFlops.push_back(tab_mflops[i]);\n          ++i;\n        }\n        else\n        {\n          newSizes.push_back(oldSizes[j]);\n          newFlops.push_back(oldFlops[j]);\n          ++j;\n        }\n      }\n      while (i<tab_sizes.size())\n      {\n        newSizes.push_back(tab_sizes[i]);\n        newFlops.push_back(tab_mflops[i]);\n        ++i;\n      }\n      while (j<oldSizes.size())\n      {\n        newSizes.push_back(oldSizes[j]);\n        newFlops.push_back(oldFlops[j]);\n        ++j;\n      }\n      tab_mflops = newFlops;\n      tab_sizes = newSizes;\n    }\n  }\n\n  // dump the result in a file  :\n  dump_xy_file(tab_sizes,tab_mflops,filename);\n\n}\n\n// default Perf Analyzer\n\ntemplate <class Action>\nBTL_DONT_INLINE void bench( int size_min, int size_max, int nb_point ){\n\n  // if the rdtsc is not available :\n  bench<Portable_Perf_Analyzer,Action>(size_min,size_max,nb_point);\n  // if the rdtsc is available :\n//    bench<Mixed_Perf_Analyzer,Action>(size_min,size_max,nb_point);\n\n\n  // Only for small problem size. Otherwise it will be too long\n//   bench<X86_Perf_Analyzer,Action>(size_min,size_max,nb_point);\n//   bench<STL_Perf_Analyzer,Action>(size_min,size_max,nb_point);\n\n}\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/bench_parameter.hh",
    "content": "//=====================================================\n// File   :  bench_parameter.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:16 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef BENCH_PARAMETER_HH\n#define BENCH_PARAMETER_HH\n\n// minimal time for each measurement\n#define REAL_TYPE float\n// minimal time for each measurement\n#define MIN_TIME 0.2\n// nb of point on bench curves\n#define NB_POINT 100\n// min vector size for axpy bench\n#define MIN_AXPY 5\n// max vector size for axpy bench\n#define MAX_AXPY 3000000\n// min matrix size for matrix vector product bench\n#define MIN_MV 5\n// max matrix size for matrix vector product bench\n#define MAX_MV 5000\n// min matrix size for matrix matrix product bench\n#define MIN_MM 5\n// max matrix size for matrix matrix product bench\n#define MAX_MM MAX_MV\n// min matrix size for LU bench\n#define MIN_LU 5\n// max matrix size for LU bench\n#define MAX_LU 3000\n// max size for tiny vector and matrix\n#define TINY_MV_MAX_SIZE 16\n// default nb_sample for x86 timer\n#define DEFAULT_NB_SAMPLE 1000\n\n// how many times we run a single bench (keep the best perf)\n#define DEFAULT_NB_TRIES 3\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/btl.hh",
    "content": "//=====================================================\n// File   :  btl.hh\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef BTL_HH\n#define BTL_HH\n\n#include \"bench_parameter.hh\"\n#include <iostream>\n#include <algorithm>\n#include <vector>\n#include <string>\n#include \"utilities.h\"\n\n#if (defined __GNUC__)\n#define BTL_ALWAYS_INLINE __attribute__((always_inline)) inline\n#else\n#define BTL_ALWAYS_INLINE inline\n#endif\n\n#if (defined __GNUC__)\n#define BTL_DONT_INLINE __attribute__((noinline))\n#else\n#define BTL_DONT_INLINE\n#endif\n\n#if (defined __GNUC__)\n#define BTL_ASM_COMMENT(X)  asm(\"#\" X)\n#else\n#define BTL_ASM_COMMENT(X)\n#endif\n\n#ifdef __SSE__\n#include \"xmmintrin.h\"\n// This enables flush to zero (FTZ) and denormals are zero (DAZ) modes:\n#define BTL_DISABLE_SSE_EXCEPTIONS()  { _mm_setcsr(_mm_getcsr() | 0x8040); }\n#else\n#define BTL_DISABLE_SSE_EXCEPTIONS()\n#endif\n\n/** Enhanced std::string\n*/\nclass BtlString : public std::string\n{\npublic:\n    BtlString() : std::string() {}\n    BtlString(const BtlString& str) : std::string(static_cast<const std::string&>(str)) {}\n    BtlString(const std::string& str) : std::string(str) {}\n    BtlString(const char* str) : std::string(str) {}\n\n    operator const char* () const { return c_str(); }\n\n    void trim( bool left = true, bool right = true )\n    {\n        int lspaces, rspaces, len = length(), i;\n        lspaces = rspaces = 0;\n\n        if ( left )\n            for (i=0; i<len && (at(i)==' '||at(i)=='\\t'||at(i)=='\\r'||at(i)=='\\n'); ++lspaces,++i);\n\n        if ( right && lspaces < len )\n            for(i=len-1; i>=0 && (at(i)==' '||at(i)=='\\t'||at(i)=='\\r'||at(i)=='\\n'); rspaces++,i--);\n\n        *this = substr(lspaces, len-lspaces-rspaces);\n    }\n\n    std::vector<BtlString> split( const BtlString& delims = \"\\t\\n \") const\n    {\n        std::vector<BtlString> ret;\n        unsigned int numSplits = 0;\n        size_t start, pos;\n        start = 0;\n        do\n        {\n            pos = find_first_of(delims, start);\n            if (pos == start)\n            {\n                ret.push_back(\"\");\n                start = pos + 1;\n            }\n            else if (pos == npos)\n                ret.push_back( substr(start) );\n            else\n            {\n                ret.push_back( substr(start, pos - start) );\n                start = pos + 1;\n            }\n            //start = find_first_not_of(delims, start);\n            ++numSplits;\n        } while (pos != npos);\n        return ret;\n    }\n\n    bool endsWith(const BtlString& str) const\n    {\n        if(str.size()>this->size())\n            return false;\n        return this->substr(this->size()-str.size(),str.size()) == str;\n    }\n    bool contains(const BtlString& str) const\n    {\n        return this->find(str)<this->size();\n    }\n    bool beginsWith(const BtlString& str) const\n    {\n        if(str.size()>this->size())\n            return false;\n        return this->substr(0,str.size()) == str;\n    }\n\n    BtlString toLowerCase( void )\n    {\n        std::transform(begin(), end(), begin(), static_cast<int(*)(int)>(::tolower) );\n        return *this;\n    }\n    BtlString toUpperCase( void )\n    {\n        std::transform(begin(), end(), begin(), static_cast<int(*)(int)>(::toupper) );\n        return *this;\n    }\n\n    /** Case insensitive comparison.\n    */\n    bool isEquiv(const BtlString& str) const\n    {\n        BtlString str0 = *this;\n        str0.toLowerCase();\n        BtlString str1 = str;\n        str1.toLowerCase();\n        return str0 == str1;\n    }\n\n    /** Decompose the current string as a path and a file.\n        For instance: \"dir1/dir2/file.ext\" leads to path=\"dir1/dir2/\" and filename=\"file.ext\"\n    */\n    void decomposePathAndFile(BtlString& path, BtlString& filename) const\n    {\n        std::vector<BtlString> elements = this->split(\"/\\\\\");\n        path = \"\";\n        filename = elements.back();\n        elements.pop_back();\n        if (this->at(0)=='/')\n            path = \"/\";\n        for (unsigned int i=0 ; i<elements.size() ; ++i)\n            path += elements[i] + \"/\";\n    }\n};\n\nclass BtlConfig\n{\npublic:\n  BtlConfig()\n    : overwriteResults(false), checkResults(true), realclock(false), tries(DEFAULT_NB_TRIES)\n  {\n    char * _config;\n    _config = getenv (\"BTL_CONFIG\");\n    if (_config!=NULL)\n    {\n      std::vector<BtlString> config = BtlString(_config).split(\" \\t\\n\");\n      for (unsigned int i = 0; i<config.size(); i++)\n      {\n        if (config[i].beginsWith(\"-a\"))\n        {\n          if (i+1==config.size())\n          {\n            std::cerr << \"error processing option: \" << config[i] << \"\\n\";\n            exit(2);\n          }\n          Instance.m_selectedActionNames = config[i+1].split(\":\");\n\n          i += 1;\n        }\n        else if (config[i].beginsWith(\"-t\"))\n        {\n          if (i+1==config.size())\n          {\n            std::cerr << \"error processing option: \" << config[i] << \"\\n\";\n            exit(2);\n          }\n          Instance.tries = atoi(config[i+1].c_str());\n\n          i += 1;\n        }\n        else if (config[i].beginsWith(\"--overwrite\"))\n        {\n          Instance.overwriteResults = true;\n        }\n        else if (config[i].beginsWith(\"--nocheck\"))\n        {\n          Instance.checkResults = false;\n        }\n        else if (config[i].beginsWith(\"--real\"))\n        {\n          Instance.realclock = true;\n        }\n      }\n    }\n\n    BTL_DISABLE_SSE_EXCEPTIONS();\n  }\n\n  BTL_DONT_INLINE static bool skipAction(const std::string& _name)\n  {\n    if (Instance.m_selectedActionNames.empty())\n      return false;\n\n    BtlString name(_name);\n    for (unsigned int i=0; i<Instance.m_selectedActionNames.size(); ++i)\n      if (name.contains(Instance.m_selectedActionNames[i]))\n        return false;\n\n    return true;\n  }\n\n  static BtlConfig Instance;\n  bool overwriteResults;\n  bool checkResults;\n  bool realclock;\n  int tries;\n\nprotected:\n  std::vector<BtlString> m_selectedActionNames;\n};\n\n#define BTL_MAIN \\\n  BtlConfig BtlConfig::Instance\n\n#endif // BTL_HH\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/init/init_function.hh",
    "content": "//=====================================================\n// File   :  init_function.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  lun sep 30 14:23:18 CEST 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef INIT_FUNCTION_HH\n#define INIT_FUNCTION_HH\n\ndouble simple_function(int index)\n{\n  return index;\n}\n\ndouble simple_function(int index_i, int index_j)\n{\n  return index_i+index_j;\n}\n\ndouble pseudo_random(int /*index*/)\n{\n  return std::rand()/double(RAND_MAX);\n}\n\ndouble pseudo_random(int /*index_i*/, int /*index_j*/)\n{\n  return std::rand()/double(RAND_MAX);\n}\n\n\ndouble null_function(int /*index*/)\n{\n  return 0.0;\n}\n\ndouble null_function(int /*index_i*/, int /*index_j*/)\n{\n  return 0.0;\n}\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/init/init_matrix.hh",
    "content": "//=====================================================\n// File   :  init_matrix.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:19 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef INIT_MATRIX_HH\n#define INIT_MATRIX_HH\n\n// The Vector class must satisfy the following part of STL vector concept :\n//            resize() method\n//            [] operator for setting element\n//            value_type defined\ntemplate<double init_function(int,int), class Vector>\nBTL_DONT_INLINE void init_row(Vector & X, int size, int row){\n\n  X.resize(size);\n\n  for (unsigned int j=0;j<X.size();j++){\n    X[j]=typename Vector::value_type(init_function(row,j));\n  }\n}\n\n\n// Matrix is a Vector of Vector\n// The Matrix class must satisfy the following part of STL vector concept :\n//            resize() method\n//            [] operator for setting rows\ntemplate<double init_function(int,int),class Vector>\nBTL_DONT_INLINE void init_matrix(Vector &  A, int size){\n  A.resize(size);\n  for (unsigned int row=0; row<A.size() ; row++){\n    init_row<init_function>(A[row],size,row);\n  }\n}\n\ntemplate<double init_function(int,int),class Matrix>\nBTL_DONT_INLINE void init_matrix_symm(Matrix&  A, int size){\n  A.resize(size);\n  for (unsigned int row=0; row<A.size() ; row++)\n    A[row].resize(size);\n  for (unsigned int row=0; row<A.size() ; row++){\n    A[row][row] = init_function(row,row);\n    for (unsigned int col=0; col<row ; col++){\n      double x = init_function(row,col);\n      A[row][col] = A[col][row] = x;\n    }\n  }\n}\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/init/init_vector.hh",
    "content": "//=====================================================\n// File   :  init_vector.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:18 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef INIT_VECTOR_HH\n#define INIT_VECTOR_HH\n\n// The Vector class must satisfy the following part of STL vector concept :\n//            resize() method\n//            [] operator for setting element\n//            value_type defined\ntemplate<double init_function(int), class Vector>\nvoid init_vector(Vector & X, int size){\n\n  X.resize(size);\n\n  for (unsigned int i=0;i<X.size();i++){\n    X[i]=typename Vector::value_type(init_function(i));\n  }\n}\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/static/bench_static.hh",
    "content": "//=====================================================\n// File   :  bench_static.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:16 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef BENCH_STATIC_HH\n#define BENCH_STATIC_HH\n\n#include \"btl.hh\"\n#include \"bench_parameter.hh\"\n#include <iostream>\n#include \"utilities.h\"\n#include \"xy_file.hh\"\n#include \"static/static_size_generator.hh\"\n#include \"timers/portable_perf_analyzer.hh\"\n// #include \"timers/mixed_perf_analyzer.hh\"\n// #include \"timers/x86_perf_analyzer.hh\"\n\nusing namespace std;\n\n\ntemplate <template<class> class Perf_Analyzer, template<class> class Action, template<class,int> class Interface>\nBTL_DONT_INLINE  void bench_static(void)\n{\n  if (BtlConfig::skipAction(Action<Interface<REAL_TYPE,10> >::name()))\n    return;\n\n  string filename = \"bench_\" + Action<Interface<REAL_TYPE,10> >::name() + \".dat\";\n\n  INFOS(\"starting \" << filename);\n\n  const int max_size = TINY_MV_MAX_SIZE;\n\n  std::vector<double> tab_mflops;\n  std::vector<double> tab_sizes;\n\n  static_size_generator<max_size,Perf_Analyzer,Action,Interface>::go(tab_sizes,tab_mflops);\n\n  dump_xy_file(tab_sizes,tab_mflops,filename);\n}\n\n// default Perf Analyzer\ntemplate <template<class> class Action, template<class,int> class Interface>\nBTL_DONT_INLINE  void bench_static(void)\n{\n  bench_static<Portable_Perf_Analyzer,Action,Interface>();\n  //bench_static<Mixed_Perf_Analyzer,Action,Interface>();\n  //bench_static<X86_Perf_Analyzer,Action,Interface>();\n}\n\n#endif\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/static/intel_bench_fixed_size.hh",
    "content": "//=====================================================\n// File   :  intel_bench_fixed_size.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  mar dc 3 18:59:37 CET 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef _BENCH_FIXED_SIZE_HH_\n#define _BENCH_FIXED_SIZE_HH_\n\n#include \"utilities.h\"\n#include \"function_time.hh\"\n\ntemplate <class Action>\ndouble bench_fixed_size(int size, unsigned long long  & nb_calc,unsigned long long & nb_init)\n{\n  \n  Action action(size);\n  \n  double time_baseline=time_init(nb_init,action);\n\n  while (time_baseline < MIN_TIME) {\n\n    //INFOS(\"nb_init=\"<<nb_init);\n    //INFOS(\"time_baseline=\"<<time_baseline);\n    nb_init*=2;\n    time_baseline=time_init(nb_init,action);\n  }\n  \n  time_baseline=time_baseline/(double(nb_init));\n  \n  double time_action=time_calculate(nb_calc,action);\n  \n  while (time_action < MIN_TIME) {\n    \n    nb_calc*=2;\n    time_action=time_calculate(nb_calc,action);\n  }\n\n  INFOS(\"nb_init=\"<<nb_init);\n  INFOS(\"nb_calc=\"<<nb_calc);\n  \n  \n  time_action=time_action/(double(nb_calc));\n  \n  action.check_result();\n  \n  time_action=time_action-time_baseline;\n\n  return action.nb_op_base()/(time_action*1000000.0);\n\n}\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/static/static_size_generator.hh",
    "content": "//=====================================================\n// File   :  static_size_generator.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  mar dc 3 18:59:36 CET 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef _STATIC_SIZE_GENERATOR_HH\n#define _STATIC_SIZE_GENERATOR_HH\n#include <vector>\n\nusing namespace std;\n\n//recursive generation of statically defined matrix and vector sizes\n\ntemplate <int SIZE,template<class> class Perf_Analyzer, template<class> class Action, template<class,int> class Interface> \nstruct static_size_generator{\n  static void go(vector<double> & tab_sizes, vector<double> & tab_mflops)\n  {\n    tab_sizes.push_back(SIZE);\n    std::cout << tab_sizes.back() << \" \\t\" << std::flush;\n    Perf_Analyzer<Action<Interface<REAL_TYPE,SIZE> > > perf_action;\n    tab_mflops.push_back(perf_action.eval_mflops(SIZE));\n    std::cout << tab_mflops.back() << \" MFlops\" << std::endl;\n    static_size_generator<SIZE-1,Perf_Analyzer,Action,Interface>::go(tab_sizes,tab_mflops);\n  };\n};\n\n//recursion end\n\ntemplate <template<class> class Perf_Analyzer, template<class> class Action, template<class,int> class Interface> \nstruct static_size_generator<1,Perf_Analyzer,Action,Interface>{  \n  static  void go(vector<double> & tab_sizes, vector<double> & tab_mflops)\n  {\n    tab_sizes.push_back(1);\n    Perf_Analyzer<Action<Interface<REAL_TYPE,1> > > perf_action;\n    tab_mflops.push_back(perf_action.eval_mflops(1));\n  };\n};\n\n#endif\n  \n  \n  \n  \n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/timers/STL_perf_analyzer.hh",
    "content": "//=====================================================\n// File   :  STL_perf_analyzer.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  mar dc 3 18:59:35 CET 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef _STL_PERF_ANALYSER_HH\n#define _STL_PERF_ANALYSER_HH\n\n#include \"STL_timer.hh\"\n#include \"bench_parameter.hh\"\n\ntemplate<class ACTION>\nclass STL_Perf_Analyzer{\npublic:  \n  STL_Perf_Analyzer(unsigned long long nb_sample=DEFAULT_NB_SAMPLE):_nb_sample(nb_sample),_chronos()\n  {\n    MESSAGE(\"STL_Perf_Analyzer Ctor\");\n  }; \n  STL_Perf_Analyzer( const STL_Perf_Analyzer & ){\n    INFOS(\"Copy Ctor not implemented\");\n    exit(0);\n  };\n  ~STL_Perf_Analyzer( void ){\n    MESSAGE(\"STL_Perf_Analyzer Dtor\");\n  };\n  \n  \n  inline double eval_mflops(int size)\n  {\n\n    ACTION action(size);\n\n    _chronos.start_baseline(_nb_sample);\n      \n    do {\n\n      action.initialize();\n    } while (_chronos.check());\n\n    double baseline_time=_chronos.get_time();\n\n    _chronos.start(_nb_sample);\n    do {\n      action.initialize();\n      action.calculate();\n    } while (_chronos.check());\n\n    double calculate_time=_chronos.get_time();\n\n    double corrected_time=calculate_time-baseline_time;\n    \n    //    cout << size <<\" \"<<baseline_time<<\" \"<<calculate_time<<\" \"<<corrected_time<<\" \"<<action.nb_op_base() << endl;    \n    \n    return action.nb_op_base()/(corrected_time*1000000.0);\n    //return action.nb_op_base()/(calculate_time*1000000.0);\n    \n  }\nprivate:\n\n  STL_Timer _chronos;\n  unsigned long long _nb_sample;\n\n  \n};\n\n  \n  \n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/timers/STL_timer.hh",
    "content": "//=====================================================\n// File   :  STL_Timer.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  mar dc 3 18:59:35 CET 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n// STL Timer Class. Adapted (L.P.) from the timer class by Musser et Al\n// described int the Book : STL Tutorial and reference guide.\n// Define a timer class for analyzing algorithm performance.\n#include <iostream>\n#include <iomanip>\n#include <vector>\n#include <map>\n#include <algorithm>\nusing namespace std;\n\nclass STL_Timer {\npublic:\n  STL_Timer(){ baseline = false; };  // Default constructor\n  // Start a series of r trials:\n  void start(unsigned int r){\n    reps = r;\n    count = 0;\n    iterations.clear();\n    iterations.reserve(reps);\n    initial = time(0);\n  };\n  // Start a series of r trials to determine baseline time:\n  void start_baseline(unsigned int r)\n  {\n    baseline = true;\n    start(r);\n  }\n  // Returns true if the trials have been completed, else false\n  bool check()\n  {\n    ++count;\n    final = time(0);\n    if (initial < final) {\n      iterations.push_back(count);  \n      initial = final;\n      count = 0;\n    }\n    return (iterations.size() < reps);\n  };\n  // Returns the results for external use\n  double get_time( void )\n  {\n    sort(iterations.begin(), iterations.end());\n    return 1.0/iterations[reps/2];\n  };\nprivate:\n  unsigned int reps;  // Number of trials\n  // For storing loop iterations of a trial\n  vector<long> iterations;\n  // For saving initial and final times of a trial\n  time_t initial, final;\n  // For counting loop iterations of a trial\n  unsigned long count;\n  // true if this is a baseline computation, false otherwise\n  bool baseline;\n  // For recording the baseline time \n  double baseline_time;\n};\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/timers/mixed_perf_analyzer.hh",
    "content": "//=====================================================\n// File   :  mixed_perf_analyzer.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  mar dc 3 18:59:36 CET 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef _MIXED_PERF_ANALYSER_HH\n#define _MIXED_PERF_ANALYSER_HH\n\n#include \"x86_perf_analyzer.hh\"\n#include \"portable_perf_analyzer.hh\"\n\n// choose portable perf analyzer for long calculations and x86 analyser for short ones\n\n\ntemplate<class Action>\nclass Mixed_Perf_Analyzer{\n  \npublic:  \n  Mixed_Perf_Analyzer( void ):_x86pa(),_ppa(),_use_ppa(true)\n  {\n    MESSAGE(\"Mixed_Perf_Analyzer Ctor\");\n  }; \n  Mixed_Perf_Analyzer( const Mixed_Perf_Analyzer & ){\n    INFOS(\"Copy Ctor not implemented\");\n    exit(0);\n  };\n  ~Mixed_Perf_Analyzer( void ){\n    MESSAGE(\"Mixed_Perf_Analyzer Dtor\");\n  };\n    \n  \n  inline double eval_mflops(int size)\n  {\n\n    double result=0.0;\n    if (_use_ppa){      \n      result=_ppa.eval_mflops(size);\n      if (_ppa.get_nb_calc()>DEFAULT_NB_SAMPLE){_use_ppa=false;}      \n    }\n    else{      \n      result=_x86pa.eval_mflops(size);\n    }\n\n    return result;\n  }\n\nprivate:\n\n  Portable_Perf_Analyzer<Action> _ppa;\n  X86_Perf_Analyzer<Action> _x86pa;\n  bool _use_ppa;\n\n};\n\n#endif\n\n  \n    \n  \n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/timers/portable_perf_analyzer.hh",
    "content": "//=====================================================\n// File   :  portable_perf_analyzer.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  mar d�c 3 18:59:35 CET 2002\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef _PORTABLE_PERF_ANALYZER_HH\n#define _PORTABLE_PERF_ANALYZER_HH\n\n#include \"utilities.h\"\n#include \"timers/portable_timer.hh\"\n\ntemplate <class Action>\nclass Portable_Perf_Analyzer{\npublic:\n  Portable_Perf_Analyzer( ):_nb_calc(0), m_time_action(0), _chronos(){\n    MESSAGE(\"Portable_Perf_Analyzer Ctor\");\n  };\n  Portable_Perf_Analyzer( const Portable_Perf_Analyzer & ){\n    INFOS(\"Copy Ctor not implemented\");\n    exit(0);\n  };\n  ~Portable_Perf_Analyzer(){\n    MESSAGE(\"Portable_Perf_Analyzer Dtor\");\n  };\n\n  BTL_DONT_INLINE double eval_mflops(int size)\n  {\n    Action action(size);\n\n//     action.initialize();\n//     time_action = time_calculate(action);\n    while (m_time_action < MIN_TIME)\n    {\n      if(_nb_calc==0) _nb_calc = 1;\n      else            _nb_calc *= 2;\n      action.initialize();\n      m_time_action = time_calculate(action);\n    }\n\n    // optimize\n    for (int i=1; i<BtlConfig::Instance.tries; ++i)\n    {\n      Action _action(size);\n      std::cout << \" \" << _action.nb_op_base()*_nb_calc/(m_time_action*1e6) << \" \";\n      _action.initialize();\n      m_time_action = std::min(m_time_action, time_calculate(_action));\n    }\n\n    double time_action = m_time_action / (double(_nb_calc));\n\n    // check\n    if (BtlConfig::Instance.checkResults && size<128)\n    {\n      action.initialize();\n      action.calculate();\n      action.check_result();\n    }\n    return action.nb_op_base()/(time_action*1e6);\n  }\n\n  BTL_DONT_INLINE double time_calculate(Action & action)\n  {\n    // time measurement\n    action.calculate();\n    _chronos.start();\n    for (unsigned int ii=0;ii<_nb_calc;ii++)\n    {\n      action.calculate();\n    }\n    _chronos.stop();\n    return _chronos.user_time();\n  }\n\n  unsigned long long get_nb_calc()\n  {\n    return _nb_calc;\n  }\n\n\nprivate:\n  unsigned long long _nb_calc;\n  double m_time_action;\n  Portable_Timer _chronos;\n\n};\n\n#endif //_PORTABLE_PERF_ANALYZER_HH\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/timers/portable_perf_analyzer_old.hh",
    "content": "//=====================================================\n// File   :  portable_perf_analyzer.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  mar d�c 3 18:59:35 CET 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef _PORTABLE_PERF_ANALYZER_HH\n#define _PORTABLE_PERF_ANALYZER_HH\n\n#include \"utilities.h\"\n#include \"timers/portable_timer.hh\"\n\ntemplate <class Action>\nclass Portable_Perf_Analyzer{\npublic:\n  Portable_Perf_Analyzer( void ):_nb_calc(1),_nb_init(1),_chronos(){\n    MESSAGE(\"Portable_Perf_Analyzer Ctor\");\n  };\n  Portable_Perf_Analyzer( const Portable_Perf_Analyzer & ){\n    INFOS(\"Copy Ctor not implemented\");\n    exit(0);\n  };\n  ~Portable_Perf_Analyzer( void ){\n    MESSAGE(\"Portable_Perf_Analyzer Dtor\");\n  };\n\n\n\n  inline double eval_mflops(int size)\n  {\n\n    Action action(size);\n\n//     double time_baseline = time_init(action);\n//     while (time_baseline < MIN_TIME_INIT)\n//     {\n//       _nb_init *= 2;\n//       time_baseline = time_init(action);\n//     }\n//\n//     // optimize\n//     for (int i=1; i<NB_TRIES; ++i)\n//       time_baseline = std::min(time_baseline, time_init(action));\n//\n//     time_baseline = time_baseline/(double(_nb_init));\n\n    double time_action = time_calculate(action);\n    while (time_action < MIN_TIME)\n    {\n      _nb_calc *= 2;\n      time_action = time_calculate(action);\n    }\n\n    // optimize\n    for (int i=1; i<NB_TRIES; ++i)\n      time_action = std::min(time_action, time_calculate(action));\n\n//     INFOS(\"size=\"<<size);\n//     INFOS(\"_nb_init=\"<<_nb_init);\n//     INFOS(\"_nb_calc=\"<<_nb_calc);\n\n    time_action = time_action / (double(_nb_calc));\n\n    action.check_result();\n\n\n    double time_baseline = time_init(action);\n    for (int i=1; i<NB_TRIES; ++i)\n      time_baseline = std::min(time_baseline, time_init(action));\n    time_baseline = time_baseline/(double(_nb_init));\n\n\n\n//     INFOS(\"time_baseline=\"<<time_baseline);\n//     INFOS(\"time_action=\"<<time_action);\n\n    time_action = time_action - time_baseline;\n\n//     INFOS(\"time_corrected=\"<<time_action);\n\n    return action.nb_op_base()/(time_action*1000000.0);\n  }\n\n  inline double time_init(Action & action)\n  {\n    // time measurement\n    _chronos.start();\n    for (int ii=0; ii<_nb_init; ii++)\n      action.initialize();\n    _chronos.stop();\n    return _chronos.user_time();\n  }\n\n\n  inline double time_calculate(Action & action)\n  {\n    // time measurement\n    _chronos.start();\n    for (int ii=0;ii<_nb_calc;ii++)\n    {\n      action.initialize();\n      action.calculate();\n    }\n    _chronos.stop();\n    return _chronos.user_time();\n  }\n\n  unsigned long long get_nb_calc( void )\n  {\n    return _nb_calc;\n  }\n\n\nprivate:\n  unsigned long long _nb_calc;\n  unsigned long long _nb_init;\n  Portable_Timer _chronos;\n\n};\n\n#endif //_PORTABLE_PERF_ANALYZER_HH\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/timers/portable_timer.hh",
    "content": "//=====================================================\n// File   :  portable_timer.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)> from boost lib\n// Copyright (C) EDF R&D,  lun sep 30 14:23:17 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n//  simple_time extracted from the boost library\n//\n#ifndef _PORTABLE_TIMER_HH\n#define _PORTABLE_TIMER_HH\n\n#include <ctime>\n#include <cstdlib>\n\n#include <time.h>\n\n\n#define USEC_IN_SEC 1000000\n\n\n//  timer  -------------------------------------------------------------------//\n\n//  A timer object measures CPU time.\n#if defined(_MSC_VER)\n\n#define NOMINMAX\n#include <windows.h>\n\n/*#ifndef hr_timer\n#include \"hr_time.h\"\n#define hr_timer\n#endif*/\n\n class Portable_Timer\n {\n  public:\n\n   typedef struct {\n    LARGE_INTEGER start;\n    LARGE_INTEGER stop;\n   } stopWatch;\n\n\n   Portable_Timer()\n   {\n\t startVal.QuadPart = 0;\n\t stopVal.QuadPart = 0;\n\t QueryPerformanceFrequency(&frequency);\n   }\n\n   void start() { QueryPerformanceCounter(&startVal); }\n\n   void stop() { QueryPerformanceCounter(&stopVal); }\n\n   double elapsed() {\n\t LARGE_INTEGER time;\n     time.QuadPart = stopVal.QuadPart - startVal.QuadPart;\n     return LIToSecs(time);\n   }\n\n   double user_time() { return elapsed(); }\n\n\n private:\n\n   double LIToSecs(LARGE_INTEGER& L) {\n     return ((double)L.QuadPart /(double)frequency.QuadPart) ;\n   }\n\n   LARGE_INTEGER startVal;\n   LARGE_INTEGER stopVal;\n   LARGE_INTEGER frequency;\n\n\n }; // Portable_Timer\n\n#elif defined(__APPLE__)\n#include <CoreServices/CoreServices.h>\n#include <mach/mach_time.h>\n\n\nclass Portable_Timer\n{\n public:\n\n  Portable_Timer()\n  {\n  }\n\n  void start()\n  {\n    m_start_time = double(mach_absolute_time())*1e-9;;\n\n  }\n\n  void stop()\n  {\n    m_stop_time = double(mach_absolute_time())*1e-9;;\n\n  }\n\n  double elapsed()\n  {\n    return  user_time();\n  }\n\n  double user_time()\n  {\n    return m_stop_time - m_start_time;\n  }\n\n\nprivate:\n\n  double m_stop_time, m_start_time;\n\n}; // Portable_Timer (Apple)\n\n#else\n\n#include <sys/time.h>\n#include <sys/resource.h>\n#include <unistd.h>\n#include <sys/times.h>\n\nclass Portable_Timer\n{\n public:\n\n  Portable_Timer()\n  {\n    m_clkid = BtlConfig::Instance.realclock ? CLOCK_REALTIME : CLOCK_PROCESS_CPUTIME_ID;\n  }\n\n  Portable_Timer(int clkid) : m_clkid(clkid)\n  {}\n\n  void start()\n  {\n    timespec ts;\n    clock_gettime(m_clkid, &ts);\n    m_start_time = double(ts.tv_sec) + 1e-9 * double(ts.tv_nsec);\n\n  }\n\n  void stop()\n  {\n    timespec ts;\n    clock_gettime(m_clkid, &ts);\n    m_stop_time = double(ts.tv_sec) + 1e-9 * double(ts.tv_nsec);\n\n  }\n\n  double elapsed()\n  {\n    return  user_time();\n  }\n\n  double user_time()\n  {\n    return m_stop_time - m_start_time;\n  }\n\n\nprivate:\n\n  int m_clkid;\n  double m_stop_time, m_start_time;\n\n}; // Portable_Timer (Linux)\n\n#endif\n\n#endif  // PORTABLE_TIMER_HPP\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/timers/x86_perf_analyzer.hh",
    "content": "//=====================================================\n// File   :  x86_perf_analyzer.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  mar d�c 3 18:59:35 CET 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef _X86_PERF_ANALYSER_HH\n#define _X86_PERF_ANALYSER_HH\n\n#include \"x86_timer.hh\"\n#include \"bench_parameter.hh\"\n\ntemplate<class ACTION>\nclass X86_Perf_Analyzer{\npublic:\n  X86_Perf_Analyzer( unsigned long long nb_sample=DEFAULT_NB_SAMPLE):_nb_sample(nb_sample),_chronos()\n  {\n    MESSAGE(\"X86_Perf_Analyzer Ctor\");\n    _chronos.find_frequency();\n  };\n  X86_Perf_Analyzer( const X86_Perf_Analyzer & ){\n    INFOS(\"Copy Ctor not implemented\");\n    exit(0);\n  };\n  ~X86_Perf_Analyzer( void ){\n    MESSAGE(\"X86_Perf_Analyzer Dtor\");\n  };\n\n\n  inline double eval_mflops(int size)\n  {\n\n    ACTION action(size);\n\n    int nb_loop=5;\n    double calculate_time=0.0;\n    double baseline_time=0.0;\n\n    for (int j=0 ; j < nb_loop ; j++){\n\n      _chronos.clear();\n\n      for(int i=0 ; i < _nb_sample  ; i++)\n      {\n        _chronos.start();\n        action.initialize();\n        action.calculate();\n        _chronos.stop();\n        _chronos.add_get_click();\n      }\n\n      calculate_time += double(_chronos.get_shortest_clicks())/_chronos.frequency();\n\n      if (j==0) action.check_result();\n\n      _chronos.clear();\n\n      for(int i=0 ; i < _nb_sample  ; i++)\n      {\n        _chronos.start();\n        action.initialize();\n        _chronos.stop();\n        _chronos.add_get_click();\n\n      }\n\n      baseline_time+=double(_chronos.get_shortest_clicks())/_chronos.frequency();\n\n    }\n\n    double corrected_time = (calculate_time-baseline_time)/double(nb_loop);\n\n\n//     INFOS(\"_nb_sample=\"<<_nb_sample);\n//     INFOS(\"baseline_time=\"<<baseline_time);\n//     INFOS(\"calculate_time=\"<<calculate_time);\n//     INFOS(\"corrected_time=\"<<corrected_time);\n\n//    cout << size <<\" \"<<baseline_time<<\" \"<<calculate_time<<\" \"<<corrected_time<<\" \"<<action.nb_op_base() << endl;\n\n    return action.nb_op_base()/(corrected_time*1000000.0);\n    //return action.nb_op_base()/(calculate_time*1000000.0);\n  }\n\nprivate:\n\n  X86_Timer _chronos;\n  unsigned long long _nb_sample;\n\n\n};\n\n\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/timers/x86_timer.hh",
    "content": "//=====================================================\n// File   :  x86_timer.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  mar d�c 3 18:59:35 CET 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef _X86_TIMER_HH\n#define _X86_TIMER_HH\n\n#include <sys/time.h>\n#include <sys/resource.h>\n#include <unistd.h>\n#include <sys/times.h>\n//#include \"system_time.h\"\n#define u32 unsigned int\n#include <asm/msr.h>\n#include \"utilities.h\"\n#include <map>\n#include <fstream>\n#include <string>\n#include <iostream>\n\n// frequence de la becanne en Hz\n//#define FREQUENCY 648000000\n//#define FREQUENCY 1400000000\n#define FREQUENCY 1695000000\n\nusing namespace std;\n\n\nclass X86_Timer {\n\npublic :\n\n  X86_Timer( void ):_frequency(FREQUENCY),_nb_sample(0)\n  {\n    MESSAGE(\"X86_Timer Default Ctor\");    \n  }\n\n  inline void start( void ){\n\n    rdtsc(_click_start.n32[0],_click_start.n32[1]);\n\n  }\n\n\n  inline void stop( void ){\n\n    rdtsc(_click_stop.n32[0],_click_stop.n32[1]);\n\n  }\n  \n\n  inline double frequency( void ){\n    return _frequency;\n  }\n\n  double get_elapsed_time_in_second( void ){\n\n    return (_click_stop.n64-_click_start.n64)/double(FREQUENCY);\n\n\n  }    \n\n  unsigned long long  get_click( void ){\n    \n    return (_click_stop.n64-_click_start.n64);\n\n  }    \n\n  inline void find_frequency( void ){\n\n    time_t initial, final;\n    int dummy=2;\n\n    initial = time(0);\n    start();\n    do {\n      dummy+=2;\n    }\n    while(time(0)==initial);\n    // On est au debut d'un cycle d'une seconde !!!\n    initial = time(0);\n    start();\n    do {\n      dummy+=2;\n    }\n    while(time(0)==initial);\n    final=time(0);\n    stop();\n    //    INFOS(\"fine grained time : \"<<  get_elapsed_time_in_second());\n    //  INFOS(\"coarse grained time : \"<<  final-initial);\n    _frequency=_frequency*get_elapsed_time_in_second()/double(final-initial);\n    ///  INFOS(\"CPU frequency : \"<<  _frequency);        \n\n  }\n\n  void  add_get_click( void ){\n       \n    _nb_sample++;\n    _counted_clicks[get_click()]++;\n    fill_history_clicks();\n\n  }    \n\n  void dump_statistics(string filemane){\n    \n    ofstream outfile (filemane.c_str(),ios::out) ;\n\n    std::map<unsigned long long , unsigned long long>::iterator itr;\n    for(itr=_counted_clicks.begin() ; itr!=_counted_clicks.end()  ; itr++)\n      {      \n      outfile  << (*itr).first << \"  \" << (*itr).second << endl ;       \n      }      \n    \n    outfile.close();\n\n  }\n\n  void dump_history(string filemane){\n    \n    ofstream outfile (filemane.c_str(),ios::out) ;\n\n\n\n    for(int i=0 ; i<_history_mean_clicks.size() ; i++)\n      {      \n\toutfile  << i << \" \" \n\t\t << _history_mean_clicks[i] << \" \" \n\t\t << _history_shortest_clicks[i] << \" \" \n\t\t << _history_most_occured_clicks[i] << endl ;\n      }      \n    \n    outfile.close();\n\n  }\n     \n\n\n  double get_mean_clicks( void ){\n    \n    std::map<unsigned long long,unsigned long long>::iterator itr;\n    \n    unsigned long long mean_clicks=0;\n\n    for(itr=_counted_clicks.begin() ; itr!=_counted_clicks.end()  ; itr++)\n      {      \n\t\n\tmean_clicks+=(*itr).second*(*itr).first;\n      }      \n\n    return mean_clicks/double(_nb_sample);\n\n  }\n\n  double get_shortest_clicks( void ){\n    \n    return double((*_counted_clicks.begin()).first);\n\n  }\n\n  void fill_history_clicks( void ){\n\n    _history_mean_clicks.push_back(get_mean_clicks());\n    _history_shortest_clicks.push_back(get_shortest_clicks());\n    _history_most_occured_clicks.push_back(get_most_occured_clicks());\n\n  }\n\n\n  double get_most_occured_clicks( void ){\n\n    unsigned long long moc=0;\n    unsigned long long max_occurence=0;\n\n    std::map<unsigned long long,unsigned long long>::iterator itr;\n\n    for(itr=_counted_clicks.begin() ; itr!=_counted_clicks.end()  ; itr++)\n      {      \n\t\n\tif (max_occurence<=(*itr).second){\n\t  max_occurence=(*itr).second;\n\t  moc=(*itr).first;\n\t}\n      }      \n    \n    return double(moc);    \n\n  }\n  \n  void clear( void )\n  {\n    _counted_clicks.clear();\n\n    _history_mean_clicks.clear();\n    _history_shortest_clicks.clear();\n    _history_most_occured_clicks.clear();\n\n    _nb_sample=0;\n  }\n\n\n    \nprivate :\n  \n  union\n  {\n    unsigned long int n32[2] ;\n    unsigned long long n64 ;\n  } _click_start;\n\n  union\n  {\n    unsigned long int n32[2] ;\n    unsigned long long n64 ;\n  } _click_stop;\n\n  double _frequency ;\n\n  map<unsigned long long,unsigned long long> _counted_clicks;\n\n  vector<double> _history_mean_clicks;\n  vector<double> _history_shortest_clicks;\n  vector<double> _history_most_occured_clicks;\n\n  unsigned long long _nb_sample;\n\n  \n\n};\n\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/utils/size_lin_log.hh",
    "content": "//=====================================================\n// File   :  size_lin_log.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  mar dc 3 18:59:37 CET 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef SIZE_LIN_LOG\n#define SIZE_LIN_LOG\n\n#include \"size_log.hh\"\n\ntemplate<class Vector>\nvoid size_lin_log(const int nb_point, const int /*size_min*/, const int size_max, Vector & X)\n{\n  int ten=10;\n  int nine=9;\n\n  X.resize(nb_point);\n\n  if (nb_point>ten){\n\n    for (int i=0;i<nine;i++){\n      \n      X[i]=i+1;\n\n    }\n\n    Vector log_size;\n    size_log(nb_point-nine,ten,size_max,log_size);\n\n    for (int i=0;i<nb_point-nine;i++){\n      \n      X[i+nine]=log_size[i];\n\n    }\n  }\n  else{\n\n    for (int i=0;i<nb_point;i++){\n      \n      X[i]=i+1;\n\n    }\n  }\n\n //  for (int i=0;i<nb_point;i++){\n    \n//        INFOS(\"computed sizes : X[\"<<i<<\"]=\"<<X[i]);\n    \n//   }\n\n}\n  \n#endif\n    \n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/utils/size_log.hh",
    "content": "//=====================================================\n// File   :  size_log.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  lun sep 30 14:23:17 CEST 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef SIZE_LOG\n#define SIZE_LOG\n\n#include \"math.h\"\n// The Vector class must satisfy the following part of STL vector concept :\n//            resize() method\n//            [] operator for setting element\n// the vector element are int compatible.\ntemplate<class Vector>\nvoid size_log(const int nb_point, const int size_min, const int size_max, Vector & X)\n{\n  X.resize(nb_point);\n\n  float ls_min=log(float(size_min));\n  float ls_max=log(float(size_max));\n\n  float ls=0.0;\n\n  float delta_ls=(ls_max-ls_min)/(float(nb_point-1));\n\n  int size=0;\n\n  for (int i=0;i<nb_point;i++){\n\n    ls = ls_min + float(i)*delta_ls ;\n    \n    size=int(exp(ls)); \n\n    X[i]=size;\n  }\n\n}\n\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/utils/utilities.h",
    "content": "//=============================================================================\n// File      : utilities.h\n// Created   : mar jun 19 13:18:14 CEST 2001\n// Author    : Antoine YESSAYAN, Paul RASCLE, EDF\n// Project   : SALOME\n// Copyright : EDF 2001\n// $Header$\n//=============================================================================\n\n/* ---  Definition macros file to print information if _DEBUG_ is defined --- */\n\n# ifndef UTILITIES_H\n# define UTILITIES_H\n\n# include <stdlib.h>\n//# include <iostream> ok for gcc3.01\n# include <iostream>\n\n/* ---  INFOS is always defined (without _DEBUG_): to be used for warnings, with release version --- */\n\n# define HEREWEARE cout<<flush ; cerr << __FILE__ << \" [\" << __LINE__ << \"] : \" << flush ;\n# define INFOS(chain) {HEREWEARE ; cerr << chain << endl ;}\n# define PYSCRIPT(chain) {cout<<flush ; cerr << \"---PYSCRIPT--- \" << chain << endl ;}\n\n/* --- To print date and time of compilation of current source on stdout --- */\n\n# if defined ( __GNUC__ )\n# define COMPILER\t\t\"g++\" ;\n# elif defined ( __sun )\n# define COMPILER\t\t\"CC\" ;\n# elif defined ( __KCC )\n# define COMPILER\t\t\"KCC\" ;\n# elif defined ( __PGI )\n# define COMPILER\t\t\"pgCC\" ;\n# else\n# define COMPILER\t\t\"undefined\" ;\n# endif\n\n# ifdef INFOS_COMPILATION\n# error INFOS_COMPILATION already defined\n# endif\n# define INFOS_COMPILATION\t{\\\n\t\t\t\t\tcerr << flush;\\\n\t\t\t\t\tcout << __FILE__ ;\\\n\t\t\t\t\tcout << \" [\" << __LINE__ << \"] : \" ;\\\n\t\t\t\t\tcout << \"COMPILED with \" << COMPILER ;\\\n\t\t\t\t\tcout << \", \" << __DATE__ ; \\\n\t\t\t\t\tcout << \" at \" << __TIME__ << endl ;\\\n\t\t\t\t\tcout << \"\\n\\n\" ;\\\n\t\t\t\t\tcout << flush ;\\\n\t\t\t\t}\n\n# ifdef _DEBUG_\n\n/* --- the following MACROS are useful at debug time --- */\n\n# define HERE cout<<flush ; cerr << \"- Trace \" << __FILE__ << \" [\" << __LINE__ << \"] : \" << flush ;\n# define SCRUTE(var) HERE ; cerr << #var << \"=\" << var << endl ;\n# define MESSAGE(chain) {HERE ; cerr << chain << endl ;}\n# define INTERRUPTION(code) HERE ; cerr << \"INTERRUPTION return code= \" << code << endl ; exit(code) ;\n\n# ifndef ASSERT\n# define ASSERT(condition) if (!(condition)){ HERE ; cerr << \"CONDITION \" << #condition << \" NOT VERIFIED\"<< endl ; INTERRUPTION(1) ;}\n# endif /* ASSERT */\n\n#define REPERE cout<<flush ; cerr << \"   --------------\" << endl << flush ;\n#define BEGIN_OF(chain) {REPERE ; HERE ; cerr << \"Begin of: \" << chain << endl ; REPERE ; }\n#define END_OF(chain) {REPERE ; HERE ; cerr << \"Normal end of: \" << chain << endl ; REPERE ; }\n\n\n\n# else /* ifdef _DEBUG_*/\n\n# define HERE\n# define SCRUTE(var)\n# define MESSAGE(chain)\n# define INTERRUPTION(code)\n\n# ifndef ASSERT\n# define ASSERT(condition)\n# endif /* ASSERT */\n\n#define REPERE\n#define BEGIN_OF(chain)\n#define END_OF(chain)\n\n\n# endif /* ifdef _DEBUG_*/\n\n# endif /* ifndef UTILITIES_H */\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/generic_bench/utils/xy_file.hh",
    "content": "//=====================================================\n// File   :  dump_file_x_y.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  lun sep 30 14:23:20 CEST 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef XY_FILE_HH\n#define XY_FILE_HH\n#include <fstream>\n#include <iostream>\n#include <string>\n#include <vector>\nusing namespace std;\n\nbool read_xy_file(const std::string & filename, std::vector<int> & tab_sizes,\n                  std::vector<double> & tab_mflops, bool quiet = false)\n{\n\n  std::ifstream input_file (filename.c_str(),std::ios::in);\n\n  if (!input_file){\n    if (!quiet) {\n      INFOS(\"!!! Error opening \"<<filename);\n    }\n    return false;\n  }\n\n  int nb_point=0;\n  int size=0;\n  double mflops=0;\n\n  while (input_file >> size >> mflops ){\n    nb_point++;\n    tab_sizes.push_back(size);\n    tab_mflops.push_back(mflops);\n  }\n  SCRUTE(nb_point);\n\n  input_file.close();\n  return true;\n}\n\n// The Vector class must satisfy the following part of STL vector concept :\n//            resize() method\n//            [] operator for setting element\n// the vector element must have the << operator define\n\nusing namespace std;\n\ntemplate<class Vector_A, class Vector_B>\nvoid dump_xy_file(const Vector_A & X, const Vector_B & Y, const std::string & filename){\n  \n  ofstream outfile (filename.c_str(),ios::out) ;\n  int size=X.size();\n  \n  for (int i=0;i<size;i++)\n    outfile << X[i] << \" \" << Y[i] << endl;\n\n  outfile.close();\n} \n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/BLAS/CMakeLists.txt",
    "content": "\nfind_package(ATLAS)\nif (ATLAS_FOUND)\n  btl_add_bench(btl_atlas main.cpp)\n  if(BUILD_btl_atlas)\n    target_link_libraries(btl_atlas ${ATLAS_LIBRARIES})\n    set_target_properties(btl_atlas PROPERTIES COMPILE_FLAGS \"-DCBLASNAME=ATLAS -DHAS_LAPACK=1\")\n  endif()\nendif ()\n\nfind_package(MKL)\nif (MKL_FOUND)\n  btl_add_bench(btl_mkl main.cpp)\n  if(BUILD_btl_mkl)\n    target_link_libraries(btl_mkl ${MKL_LIBRARIES})\n    set_target_properties(btl_mkl PROPERTIES COMPILE_FLAGS \"-DCBLASNAME=INTEL_MKL -DHAS_LAPACK=1\")\n  endif()\nendif ()\n\n\nfind_package(OPENBLAS)\nif (OPENBLAS_FOUND)\n  btl_add_bench(btl_openblas main.cpp)\n  if(BUILD_btl_openblas)\n    target_link_libraries(btl_openblas ${OPENBLAS_LIBRARIES} )\n    set_target_properties(btl_openblas PROPERTIES COMPILE_FLAGS \"-DCBLASNAME=OPENBLAS\")\n  endif()\nendif ()\n\nfind_package(ACML)\nif (ACML_FOUND)\n  btl_add_bench(btl_acml main.cpp)\n  if(BUILD_btl_acml)\n    target_link_libraries(btl_acml ${ACML_LIBRARIES} )\n    set_target_properties(btl_acml PROPERTIES COMPILE_FLAGS \"-DCBLASNAME=ACML -DHAS_LAPACK=1\")\n  endif()\nendif ()\n\nif(Eigen_SOURCE_DIR AND CMAKE_Fortran_COMPILER_WORKS)\n  # we are inside Eigen and blas/lapack interface is compilable\n  include_directories(${Eigen_SOURCE_DIR})\n  btl_add_bench(btl_eigenblas main.cpp)\n  if(BUILD_btl_eigenblas)\n    target_link_libraries(btl_eigenblas eigen_blas eigen_lapack )\n    set_target_properties(btl_eigenblas PROPERTIES COMPILE_FLAGS \"-DCBLASNAME=EigenBLAS\")\n  endif()\nendif()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/BLAS/blas.h",
    "content": "#ifndef BLAS_H\n#define BLAS_H\n\n#define BLASFUNC(FUNC) FUNC##_\n\n#ifdef __WIN64__\ntypedef long long BLASLONG;\ntypedef unsigned long long BLASULONG;\n#else\ntypedef long BLASLONG;\ntypedef unsigned long BLASULONG;\n#endif\n\nint    BLASFUNC(xerbla)(const char *, int *info, int);\n\nfloat  BLASFUNC(sdot)  (int *, float  *, int *, float  *, int *);\nfloat  BLASFUNC(sdsdot)(int *, float  *,        float  *, int *, float  *, int *);\n\ndouble BLASFUNC(dsdot) (int *, float  *, int *, float  *, int *);\ndouble BLASFUNC(ddot)  (int *, double *, int *, double *, int *);\ndouble BLASFUNC(qdot)  (int *, double *, int *, double *, int *);\n\n#if defined(F_INTERFACE_GFORT) && !defined(__64BIT__)\nint   BLASFUNC(cdotu)  (int *, float  * , int *, float  *,  int *);\nint   BLASFUNC(cdotc)  (int *, float  *,  int *, float  *,  int *);\nvoid  BLASFUNC(zdotu)  (double *, int *, double  *, int *, double  *, int *);\nvoid  BLASFUNC(zdotc)  (double *, int *, double  *, int *, double  *, int *);\nvoid  BLASFUNC(xdotu)  (double *, int *, double  *, int *, double  *, int *);\nvoid  BLASFUNC(xdotc)  (double *, int *, double  *, int *, double  *, int *);\n#elif  defined(F_INTERFACE_F2C) || \\\n     defined(F_INTERFACE_PGI) || \\\n     defined(F_INTERFACE_GFORT) || \\\n    (defined(F_INTERFACE_PATHSCALE) && defined(__64BIT__))\nvoid  BLASFUNC(cdotu)  (float *,  int *, float  * , int *, float  *,  int *);\nvoid  BLASFUNC(cdotc)  (float *,  int *, float  *,  int *, float  *,  int *);\nvoid  BLASFUNC(zdotu)  (double *, int *, double  *, int *, double  *, int *);\nvoid  BLASFUNC(zdotc)  (double *, int *, double  *, int *, double  *, int *);\nvoid  BLASFUNC(xdotu)  (double *, int *, double  *, int *, double  *, int *);\nvoid  BLASFUNC(xdotc)  (double *, int *, double  *, int *, double  *, int *);\n#else\nstd::complex<float>   BLASFUNC(cdotu)  (int *, float  *, int *, float  *, int *);\nstd::complex<float>   BLASFUNC(cdotc)  (int *, float  *, int *, float  *, int *);\nstd::complex<double>  BLASFUNC(zdotu)  (int *, double  *, int *, double  *, int *);\nstd::complex<double>  BLASFUNC(zdotc)  (int *, double  *, int *, double  *, int *);\ndouble  BLASFUNC(xdotu)  (int *, double  *, int *, double  *, int *);\ndouble  BLASFUNC(xdotc)  (int *, double  *, int *, double  *, int *);\n#endif\n\nint  BLASFUNC(cdotuw)  (int *, float  *, int *, float  *, int *, float*);\nint  BLASFUNC(cdotcw)  (int *, float  *, int *, float  *, int *, float*);\nint  BLASFUNC(zdotuw)  (int *, double  *, int *, double  *, int *, double*);\nint  BLASFUNC(zdotcw)  (int *, double  *, int *, double  *, int *, double*);\n\nint    BLASFUNC(saxpy) (int *, float  *, float  *, int *, float  *, int *);\nint    BLASFUNC(daxpy) (int *, double *, double *, int *, double *, int *);\nint    BLASFUNC(qaxpy) (int *, double *, double *, int *, double *, int *);\nint    BLASFUNC(caxpy) (int *, float  *, float  *, int *, float  *, int *);\nint    BLASFUNC(zaxpy) (int *, double *, double *, int *, double *, int *);\nint    BLASFUNC(xaxpy) (int *, double *, double *, int *, double *, int *);\nint    BLASFUNC(caxpyc)(int *, float  *, float  *, int *, float  *, int *);\nint    BLASFUNC(zaxpyc)(int *, double *, double *, int *, double *, int *);\nint    BLASFUNC(xaxpyc)(int *, double *, double *, int *, double *, int *);\n\nint    BLASFUNC(scopy) (int *, float  *, int *, float  *, int *);\nint    BLASFUNC(dcopy) (int *, double *, int *, double *, int *);\nint    BLASFUNC(qcopy) (int *, double *, int *, double *, int *);\nint    BLASFUNC(ccopy) (int *, float  *, int *, float  *, int *);\nint    BLASFUNC(zcopy) (int *, double *, int *, double *, int *);\nint    BLASFUNC(xcopy) (int *, double *, int *, double *, int *);\n\nint    BLASFUNC(sswap) (int *, float  *, int *, float  *, int *);\nint    BLASFUNC(dswap) (int *, double *, int *, double *, int *);\nint    BLASFUNC(qswap) (int *, double *, int *, double *, int *);\nint    BLASFUNC(cswap) (int *, float  *, int *, float  *, int *);\nint    BLASFUNC(zswap) (int *, double *, int *, double *, int *);\nint    BLASFUNC(xswap) (int *, double *, int *, double *, int *);\n\nfloat  BLASFUNC(sasum) (int *, float  *, int *);\nfloat  BLASFUNC(scasum)(int *, float  *, int *);\ndouble BLASFUNC(dasum) (int *, double *, int *);\ndouble BLASFUNC(qasum) (int *, double *, int *);\ndouble BLASFUNC(dzasum)(int *, double *, int *);\ndouble BLASFUNC(qxasum)(int *, double *, int *);\n\nint    BLASFUNC(isamax)(int *, float  *, int *);\nint    BLASFUNC(idamax)(int *, double *, int *);\nint    BLASFUNC(iqamax)(int *, double *, int *);\nint    BLASFUNC(icamax)(int *, float  *, int *);\nint    BLASFUNC(izamax)(int *, double *, int *);\nint    BLASFUNC(ixamax)(int *, double *, int *);\n\nint    BLASFUNC(ismax) (int *, float  *, int *);\nint    BLASFUNC(idmax) (int *, double *, int *);\nint    BLASFUNC(iqmax) (int *, double *, int *);\nint    BLASFUNC(icmax) (int *, float  *, int *);\nint    BLASFUNC(izmax) (int *, double *, int *);\nint    BLASFUNC(ixmax) (int *, double *, int *);\n\nint    BLASFUNC(isamin)(int *, float  *, int *);\nint    BLASFUNC(idamin)(int *, double *, int *);\nint    BLASFUNC(iqamin)(int *, double *, int *);\nint    BLASFUNC(icamin)(int *, float  *, int *);\nint    BLASFUNC(izamin)(int *, double *, int *);\nint    BLASFUNC(ixamin)(int *, double *, int *);\n\nint    BLASFUNC(ismin)(int *, float  *, int *);\nint    BLASFUNC(idmin)(int *, double *, int *);\nint    BLASFUNC(iqmin)(int *, double *, int *);\nint    BLASFUNC(icmin)(int *, float  *, int *);\nint    BLASFUNC(izmin)(int *, double *, int *);\nint    BLASFUNC(ixmin)(int *, double *, int *);\n\nfloat  BLASFUNC(samax) (int *, float  *, int *);\ndouble BLASFUNC(damax) (int *, double *, int *);\ndouble BLASFUNC(qamax) (int *, double *, int *);\nfloat  BLASFUNC(scamax)(int *, float  *, int *);\ndouble BLASFUNC(dzamax)(int *, double *, int *);\ndouble BLASFUNC(qxamax)(int *, double *, int *);\n\nfloat  BLASFUNC(samin) (int *, float  *, int *);\ndouble BLASFUNC(damin) (int *, double *, int *);\ndouble BLASFUNC(qamin) (int *, double *, int *);\nfloat  BLASFUNC(scamin)(int *, float  *, int *);\ndouble BLASFUNC(dzamin)(int *, double *, int *);\ndouble BLASFUNC(qxamin)(int *, double *, int *);\n\nfloat  BLASFUNC(smax)  (int *, float  *, int *);\ndouble BLASFUNC(dmax)  (int *, double *, int *);\ndouble BLASFUNC(qmax)  (int *, double *, int *);\nfloat  BLASFUNC(scmax) (int *, float  *, int *);\ndouble BLASFUNC(dzmax) (int *, double *, int *);\ndouble BLASFUNC(qxmax) (int *, double *, int *);\n\nfloat  BLASFUNC(smin)  (int *, float  *, int *);\ndouble BLASFUNC(dmin)  (int *, double *, int *);\ndouble BLASFUNC(qmin)  (int *, double *, int *);\nfloat  BLASFUNC(scmin) (int *, float  *, int *);\ndouble BLASFUNC(dzmin) (int *, double *, int *);\ndouble BLASFUNC(qxmin) (int *, double *, int *);\n\nint    BLASFUNC(sscal) (int *,  float  *, float  *, int *);\nint    BLASFUNC(dscal) (int *,  double *, double *, int *);\nint    BLASFUNC(qscal) (int *,  double *, double *, int *);\nint    BLASFUNC(cscal) (int *,  float  *, float  *, int *);\nint    BLASFUNC(zscal) (int *,  double *, double *, int *);\nint    BLASFUNC(xscal) (int *,  double *, double *, int *);\nint    BLASFUNC(csscal)(int *,  float  *, float  *, int *);\nint    BLASFUNC(zdscal)(int *,  double *, double *, int *);\nint    BLASFUNC(xqscal)(int *,  double *, double *, int *);\n\nfloat  BLASFUNC(snrm2) (int *, float  *, int *);\nfloat  BLASFUNC(scnrm2)(int *, float  *, int *);\n\ndouble BLASFUNC(dnrm2) (int *, double *, int *);\ndouble BLASFUNC(qnrm2) (int *, double *, int *);\ndouble BLASFUNC(dznrm2)(int *, double *, int *);\ndouble BLASFUNC(qxnrm2)(int *, double *, int *);\n\nint    BLASFUNC(srot)  (int *, float  *, int *, float  *, int *, float  *, float  *);\nint    BLASFUNC(drot)  (int *, double *, int *, double *, int *, double *, double *);\nint    BLASFUNC(qrot)  (int *, double *, int *, double *, int *, double *, double *);\nint    BLASFUNC(csrot) (int *, float  *, int *, float  *, int *, float  *, float  *);\nint    BLASFUNC(zdrot) (int *, double *, int *, double *, int *, double *, double *);\nint    BLASFUNC(xqrot) (int *, double *, int *, double *, int *, double *, double *);\n\nint    BLASFUNC(srotg) (float  *, float  *, float  *, float  *);\nint    BLASFUNC(drotg) (double *, double *, double *, double *);\nint    BLASFUNC(qrotg) (double *, double *, double *, double *);\nint    BLASFUNC(crotg) (float  *, float  *, float  *, float  *);\nint    BLASFUNC(zrotg) (double *, double *, double *, double *);\nint    BLASFUNC(xrotg) (double *, double *, double *, double *);\n\nint    BLASFUNC(srotmg)(float  *, float  *, float  *, float  *, float  *);\nint    BLASFUNC(drotmg)(double *, double *, double *, double *, double *);\n\nint    BLASFUNC(srotm) (int *, float  *, int *, float  *, int *, float  *);\nint    BLASFUNC(drotm) (int *, double *, int *, double *, int *, double *);\nint    BLASFUNC(qrotm) (int *, double *, int *, double *, int *, double *);\n\n/* Level 2 routines */\n\nint BLASFUNC(sger)(int *,    int *, float *,  float *, int *,\n\t\t   float *,  int *, float *,  int *);\nint BLASFUNC(dger)(int *,    int *, double *, double *, int *,\n\t\t   double *, int *, double *, int *);\nint BLASFUNC(qger)(int *,    int *, double *, double *, int *,\n\t\t   double *, int *, double *, int *);\nint BLASFUNC(cgeru)(int *,    int *, float *,  float *, int *,\n\t\t    float *,  int *, float *,  int *);\nint BLASFUNC(cgerc)(int *,    int *, float *,  float *, int *,\n\t\t    float *,  int *, float *,  int *);\nint BLASFUNC(zgeru)(int *,    int *, double *, double *, int *,\n\t\t    double *, int *, double *, int *);\nint BLASFUNC(zgerc)(int *,    int *, double *, double *, int *,\n\t\t    double *, int *, double *, int *);\nint BLASFUNC(xgeru)(int *,    int *, double *, double *, int *,\n\t\t    double *, int *, double *, int *);\nint BLASFUNC(xgerc)(int *,    int *, double *, double *, int *,\n\t\t    double *, int *, double *, int *);\n\nint BLASFUNC(sgemv)(char *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(dgemv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(qgemv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(cgemv)(char *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zgemv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(xgemv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\n\nint BLASFUNC(strsv) (char *, char *, char *, int *, float  *, int *,\n\t\t     float  *, int *);\nint BLASFUNC(dtrsv) (char *, char *, char *, int *, double *, int *,\n\t\t     double *, int *);\nint BLASFUNC(qtrsv) (char *, char *, char *, int *, double *, int *,\n\t\t     double *, int *);\nint BLASFUNC(ctrsv) (char *, char *, char *, int *, float  *, int *,\n\t\t     float  *, int *);\nint BLASFUNC(ztrsv) (char *, char *, char *, int *, double *, int *,\n\t\t     double *, int *);\nint BLASFUNC(xtrsv) (char *, char *, char *, int *, double *, int *,\n\t\t     double *, int *);\n\nint BLASFUNC(stpsv) (char *, char *, char *, int *, float  *, float  *, int *);\nint BLASFUNC(dtpsv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(qtpsv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(ctpsv) (char *, char *, char *, int *, float  *, float  *, int *);\nint BLASFUNC(ztpsv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(xtpsv) (char *, char *, char *, int *, double *, double *, int *);\n\nint BLASFUNC(strmv) (char *, char *, char *, int *, float  *, int *,\n\t\t     float  *, int *);\nint BLASFUNC(dtrmv) (char *, char *, char *, int *, double *, int *,\n\t\t     double *, int *);\nint BLASFUNC(qtrmv) (char *, char *, char *, int *, double *, int *,\n\t\t     double *, int *);\nint BLASFUNC(ctrmv) (char *, char *, char *, int *, float  *, int *,\n\t\t     float  *, int *);\nint BLASFUNC(ztrmv) (char *, char *, char *, int *, double *, int *,\n\t\t     double *, int *);\nint BLASFUNC(xtrmv) (char *, char *, char *, int *, double *, int *,\n\t\t     double *, int *);\n\nint BLASFUNC(stpmv) (char *, char *, char *, int *, float  *, float  *, int *);\nint BLASFUNC(dtpmv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(qtpmv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(ctpmv) (char *, char *, char *, int *, float  *, float  *, int *);\nint BLASFUNC(ztpmv) (char *, char *, char *, int *, double *, double *, int *);\nint BLASFUNC(xtpmv) (char *, char *, char *, int *, double *, double *, int *);\n\nint BLASFUNC(stbmv) (char *, char *, char *, int *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(dtbmv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(qtbmv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(ctbmv) (char *, char *, char *, int *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(ztbmv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(xtbmv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\n\nint BLASFUNC(stbsv) (char *, char *, char *, int *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(dtbsv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(qtbsv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(ctbsv) (char *, char *, char *, int *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(ztbsv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\nint BLASFUNC(xtbsv) (char *, char *, char *, int *, int *, double *, int *, double *, int *);\n\nint BLASFUNC(ssymv) (char *, int *, float  *, float *, int *,\n\t\t     float  *, int *, float *, float *, int *);\nint BLASFUNC(dsymv) (char *, int *, double  *, double *, int *,\n\t\t     double  *, int *, double *, double *, int *);\nint BLASFUNC(qsymv) (char *, int *, double  *, double *, int *,\n\t\t     double  *, int *, double *, double *, int *);\nint BLASFUNC(csymv) (char *, int *, float  *, float *, int *,\n\t\t     float  *, int *, float *, float *, int *);\nint BLASFUNC(zsymv) (char *, int *, double  *, double *, int *,\n\t\t     double  *, int *, double *, double *, int *);\nint BLASFUNC(xsymv) (char *, int *, double  *, double *, int *,\n\t\t     double  *, int *, double *, double *, int *);\n\nint BLASFUNC(sspmv) (char *, int *, float  *, float *,\n\t\t     float  *, int *, float *, float *, int *);\nint BLASFUNC(dspmv) (char *, int *, double  *, double *,\n\t\t     double  *, int *, double *, double *, int *);\nint BLASFUNC(qspmv) (char *, int *, double  *, double *,\n\t\t     double  *, int *, double *, double *, int *);\nint BLASFUNC(cspmv) (char *, int *, float  *, float *,\n\t\t     float  *, int *, float *, float *, int *);\nint BLASFUNC(zspmv) (char *, int *, double  *, double *,\n\t\t     double  *, int *, double *, double *, int *);\nint BLASFUNC(xspmv) (char *, int *, double  *, double *,\n\t\t     double  *, int *, double *, double *, int *);\n\nint BLASFUNC(ssyr) (char *, int *, float   *, float  *, int *,\n\t\t    float  *, int *);\nint BLASFUNC(dsyr) (char *, int *, double  *, double *, int *,\n\t\t    double *, int *);\nint BLASFUNC(qsyr) (char *, int *, double  *, double *, int *,\n\t\t    double *, int *);\nint BLASFUNC(csyr) (char *, int *, float   *, float  *, int *,\n\t\t    float  *, int *);\nint BLASFUNC(zsyr) (char *, int *, double  *, double *, int *,\n\t\t    double *, int *);\nint BLASFUNC(xsyr) (char *, int *, double  *, double *, int *,\n\t\t    double *, int *);\n\nint BLASFUNC(ssyr2) (char *, int *, float   *,\n\t\t     float  *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(dsyr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *, int *);\nint BLASFUNC(qsyr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *, int *);\nint BLASFUNC(csyr2) (char *, int *, float   *,\n\t\t     float  *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(zsyr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *, int *);\nint BLASFUNC(xsyr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *, int *);\n\nint BLASFUNC(sspr) (char *, int *, float   *, float  *, int *,\n\t\t    float  *);\nint BLASFUNC(dspr) (char *, int *, double  *, double *, int *,\n\t\t    double *);\nint BLASFUNC(qspr) (char *, int *, double  *, double *, int *,\n\t\t    double *);\nint BLASFUNC(cspr) (char *, int *, float   *, float  *, int *,\n\t\t    float  *);\nint BLASFUNC(zspr) (char *, int *, double  *, double *, int *,\n\t\t    double *);\nint BLASFUNC(xspr) (char *, int *, double  *, double *, int *,\n\t\t    double *);\n\nint BLASFUNC(sspr2) (char *, int *, float   *,\n\t\t     float  *, int *, float  *, int *, float  *);\nint BLASFUNC(dspr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\nint BLASFUNC(qspr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\nint BLASFUNC(cspr2) (char *, int *, float   *,\n\t\t     float  *, int *, float  *, int *, float  *);\nint BLASFUNC(zspr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\nint BLASFUNC(xspr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\n\nint BLASFUNC(cher) (char *, int *, float   *, float  *, int *,\n\t\t    float  *, int *);\nint BLASFUNC(zher) (char *, int *, double  *, double *, int *,\n\t\t    double *, int *);\nint BLASFUNC(xher) (char *, int *, double  *, double *, int *,\n\t\t    double *, int *);\n\nint BLASFUNC(chpr) (char *, int *, float   *, float  *, int *, float  *);\nint BLASFUNC(zhpr) (char *, int *, double  *, double *, int *, double *);\nint BLASFUNC(xhpr) (char *, int *, double  *, double *, int *, double *);\n\nint BLASFUNC(cher2) (char *, int *, float   *,\n\t\t     float  *, int *, float  *, int *, float  *, int *);\nint BLASFUNC(zher2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *, int *);\nint BLASFUNC(xher2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *, int *);\n\nint BLASFUNC(chpr2) (char *, int *, float   *,\n\t\t     float  *, int *, float  *, int *, float  *);\nint BLASFUNC(zhpr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\nint BLASFUNC(xhpr2) (char *, int *, double  *,\n\t\t     double *, int *, double *, int *, double *);\n\nint BLASFUNC(chemv) (char *, int *, float  *, float *, int *,\n\t\t     float  *, int *, float *, float *, int *);\nint BLASFUNC(zhemv) (char *, int *, double  *, double *, int *,\n\t\t     double  *, int *, double *, double *, int *);\nint BLASFUNC(xhemv) (char *, int *, double  *, double *, int *,\n\t\t     double  *, int *, double *, double *, int *);\n\nint BLASFUNC(chpmv) (char *, int *, float  *, float *,\n\t\t     float  *, int *, float *, float *, int *);\nint BLASFUNC(zhpmv) (char *, int *, double  *, double *,\n\t\t     double  *, int *, double *, double *, int *);\nint BLASFUNC(xhpmv) (char *, int *, double  *, double *,\n\t\t     double  *, int *, double *, double *, int *);\n\nint BLASFUNC(snorm)(char *, int *, int *, float  *, int *);\nint BLASFUNC(dnorm)(char *, int *, int *, double *, int *);\nint BLASFUNC(cnorm)(char *, int *, int *, float  *, int *);\nint BLASFUNC(znorm)(char *, int *, int *, double *, int *);\n\nint BLASFUNC(sgbmv)(char *, int *, int *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(dgbmv)(char *, int *, int *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(qgbmv)(char *, int *, int *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(cgbmv)(char *, int *, int *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zgbmv)(char *, int *, int *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(xgbmv)(char *, int *, int *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\n\nint BLASFUNC(ssbmv)(char *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(dsbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(qsbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(csbmv)(char *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zsbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(xsbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\n\nint BLASFUNC(chbmv)(char *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zhbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\nint BLASFUNC(xhbmv)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *, double *, double *, int *);\n\n/* Level 3 routines */\n\nint BLASFUNC(sgemm)(char *, char *, int *, int *, int *, float *,\n\t   float  *, int *, float  *, int *, float  *, float  *, int *);\nint BLASFUNC(dgemm)(char *, char *, int *, int *, int *, double *,\n\t   double *, int *, double *, int *, double *, double *, int *);\nint BLASFUNC(qgemm)(char *, char *, int *, int *, int *, double *,\n\t   double *, int *, double *, int *, double *, double *, int *);\nint BLASFUNC(cgemm)(char *, char *, int *, int *, int *, float *,\n\t   float  *, int *, float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zgemm)(char *, char *, int *, int *, int *, double *,\n\t   double *, int *, double *, int *, double *, double *, int *);\nint BLASFUNC(xgemm)(char *, char *, int *, int *, int *, double *,\n\t   double *, int *, double *, int *, double *, double *, int *);\n\nint BLASFUNC(cgemm3m)(char *, char *, int *, int *, int *, float *,\n\t   float  *, int *, float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zgemm3m)(char *, char *, int *, int *, int *, double *,\n\t   double *, int *, double *, int *, double *, double *, int *);\nint BLASFUNC(xgemm3m)(char *, char *, int *, int *, int *, double *,\n\t   double *, int *, double *, int *, double *, double *, int *);\n\nint BLASFUNC(sge2mm)(char *, char *, char *, int *, int *,\n\t\t     float *, float  *, int *, float  *, int *,\n\t\t     float *, float  *, int *);\nint BLASFUNC(dge2mm)(char *, char *, char *, int *, int *,\n\t\t     double *, double  *, int *, double  *, int *,\n\t\t     double *, double  *, int *);\nint BLASFUNC(cge2mm)(char *, char *, char *, int *, int *,\n\t\t     float *, float  *, int *, float  *, int *,\n\t\t     float *, float  *, int *);\nint BLASFUNC(zge2mm)(char *, char *, char *, int *, int *,\n\t\t     double *, double  *, int *, double  *, int *,\n\t\t     double *, double  *, int *);\n\nint BLASFUNC(strsm)(char *, char *, char *, char *, int *, int *,\n\t   float *,  float *, int *, float *, int *);\nint BLASFUNC(dtrsm)(char *, char *, char *, char *, int *, int *,\n\t   double *,  double *, int *, double *, int *);\nint BLASFUNC(qtrsm)(char *, char *, char *, char *, int *, int *,\n\t   double *,  double *, int *, double *, int *);\nint BLASFUNC(ctrsm)(char *, char *, char *, char *, int *, int *,\n\t   float *,  float *, int *, float *, int *);\nint BLASFUNC(ztrsm)(char *, char *, char *, char *, int *, int *,\n\t   double *,  double *, int *, double *, int *);\nint BLASFUNC(xtrsm)(char *, char *, char *, char *, int *, int *,\n\t   double *,  double *, int *, double *, int *);\n\nint BLASFUNC(strmm)(char *, char *, char *, char *, int *, int *,\n\t   float *,  float *, int *, float *, int *);\nint BLASFUNC(dtrmm)(char *, char *, char *, char *, int *, int *,\n\t   double *,  double *, int *, double *, int *);\nint BLASFUNC(qtrmm)(char *, char *, char *, char *, int *, int *,\n\t   double *,  double *, int *, double *, int *);\nint BLASFUNC(ctrmm)(char *, char *, char *, char *, int *, int *,\n\t   float *,  float *, int *, float *, int *);\nint BLASFUNC(ztrmm)(char *, char *, char *, char *, int *, int *,\n\t   double *,  double *, int *, double *, int *);\nint BLASFUNC(xtrmm)(char *, char *, char *, char *, int *, int *,\n\t   double *,  double *, int *, double *, int *);\n\nint BLASFUNC(ssymm)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float  *, int *, float  *, float  *, int *);\nint BLASFUNC(dsymm)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\nint BLASFUNC(qsymm)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\nint BLASFUNC(csymm)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zsymm)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\nint BLASFUNC(xsymm)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\n\nint BLASFUNC(csymm3m)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zsymm3m)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\nint BLASFUNC(xsymm3m)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\n\nint BLASFUNC(ssyrk)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float  *, float  *, int *);\nint BLASFUNC(dsyrk)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, double *, int *);\nint BLASFUNC(qsyrk)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, double *, int *);\nint BLASFUNC(csyrk)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float  *, float  *, int *);\nint BLASFUNC(zsyrk)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, double *, int *);\nint BLASFUNC(xsyrk)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, double *, int *);\n\nint BLASFUNC(ssyr2k)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float *, int *, float  *, float  *, int *);\nint BLASFUNC(dsyr2k)(char *, char *, int *, int *, double *, double *, int *,\n\t   double*, int *, double *, double *, int *);\nint BLASFUNC(qsyr2k)(char *, char *, int *, int *, double *, double *, int *,\n\t   double*, int *, double *, double *, int *);\nint BLASFUNC(csyr2k)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float *, int *, float  *, float  *, int *);\nint BLASFUNC(zsyr2k)(char *, char *, int *, int *, double *, double *, int *,\n\t   double*, int *, double *, double *, int *);\nint BLASFUNC(xsyr2k)(char *, char *, int *, int *, double *, double *, int *,\n\t   double*, int *, double *, double *, int *);\n\nint BLASFUNC(chemm)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zhemm)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\nint BLASFUNC(xhemm)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\n\nint BLASFUNC(chemm3m)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float  *, int *, float  *, float  *, int *);\nint BLASFUNC(zhemm3m)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\nint BLASFUNC(xhemm3m)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, int *, double *, double *, int *);\n\nint BLASFUNC(cherk)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float  *, float  *, int *);\nint BLASFUNC(zherk)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, double *, int *);\nint BLASFUNC(xherk)(char *, char *, int *, int *, double *, double *, int *,\n\t   double *, double *, int *);\n\nint BLASFUNC(cher2k)(char *, char *, int *, int *, float  *, float  *, int *,\n\t   float *, int *, float  *, float  *, int *);\nint BLASFUNC(zher2k)(char *, char *, int *, int *, double *, double *, int *,\n\t   double*, int *, double *, double *, int *);\nint BLASFUNC(xher2k)(char *, char *, int *, int *, double *, double *, int *,\n\t   double*, int *, double *, double *, int *);\nint BLASFUNC(cher2m)(char *, char *, char *, int *, int *, float  *, float  *, int *,\n\t   float *, int *, float  *, float  *, int *);\nint BLASFUNC(zher2m)(char *, char *, char *, int *, int *, double *, double *, int *,\n\t   double*, int *, double *, double *, int *);\nint BLASFUNC(xher2m)(char *, char *, char *, int *, int *, double *, double *, int *,\n\t   double*, int *, double *, double *, int *);\n\nint BLASFUNC(sgemt)(char *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *);\nint BLASFUNC(dgemt)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *);\nint BLASFUNC(cgemt)(char *, int *, int *, float  *, float  *, int *,\n\t\t    float  *, int *);\nint BLASFUNC(zgemt)(char *, int *, int *, double *, double *, int *,\n\t\t    double *, int *);\n\nint BLASFUNC(sgema)(char *, char *, int *, int *, float  *,\n\t\t    float  *, int *, float *, float  *, int *, float *, int *);\nint BLASFUNC(dgema)(char *, char *, int *, int *, double *,\n\t\t    double *, int *, double*, double *, int *, double*, int *);\nint BLASFUNC(cgema)(char *, char *, int *, int *, float  *,\n\t\t    float  *, int *, float *, float  *, int *, float *, int *);\nint BLASFUNC(zgema)(char *, char *, int *, int *, double *,\n\t\t    double *, int *, double*, double *, int *, double*, int *);\n\nint BLASFUNC(sgems)(char *, char *, int *, int *, float  *,\n\t\t    float  *, int *, float *, float  *, int *, float *, int *);\nint BLASFUNC(dgems)(char *, char *, int *, int *, double *,\n\t\t    double *, int *, double*, double *, int *, double*, int *);\nint BLASFUNC(cgems)(char *, char *, int *, int *, float  *,\n\t\t    float  *, int *, float *, float  *, int *, float *, int *);\nint BLASFUNC(zgems)(char *, char *, int *, int *, double *,\n\t\t    double *, int *, double*, double *, int *, double*, int *);\n\nint BLASFUNC(sgetf2)(int *, int *, float  *, int *, int *, int *);\nint BLASFUNC(dgetf2)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(qgetf2)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(cgetf2)(int *, int *, float  *, int *, int *, int *);\nint BLASFUNC(zgetf2)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(xgetf2)(int *, int *, double *, int *, int *, int *);\n\nint BLASFUNC(sgetrf)(int *, int *, float  *, int *, int *, int *);\nint BLASFUNC(dgetrf)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(qgetrf)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(cgetrf)(int *, int *, float  *, int *, int *, int *);\nint BLASFUNC(zgetrf)(int *, int *, double *, int *, int *, int *);\nint BLASFUNC(xgetrf)(int *, int *, double *, int *, int *, int *);\n\nint BLASFUNC(slaswp)(int *, float  *, int *, int *, int *, int *, int *);\nint BLASFUNC(dlaswp)(int *, double *, int *, int *, int *, int *, int *);\nint BLASFUNC(qlaswp)(int *, double *, int *, int *, int *, int *, int *);\nint BLASFUNC(claswp)(int *, float  *, int *, int *, int *, int *, int *);\nint BLASFUNC(zlaswp)(int *, double *, int *, int *, int *, int *, int *);\nint BLASFUNC(xlaswp)(int *, double *, int *, int *, int *, int *, int *);\n\nint BLASFUNC(sgetrs)(char *, int *, int *, float  *, int *, int *, float  *, int *, int *);\nint BLASFUNC(dgetrs)(char *, int *, int *, double *, int *, int *, double *, int *, int *);\nint BLASFUNC(qgetrs)(char *, int *, int *, double *, int *, int *, double *, int *, int *);\nint BLASFUNC(cgetrs)(char *, int *, int *, float  *, int *, int *, float  *, int *, int *);\nint BLASFUNC(zgetrs)(char *, int *, int *, double *, int *, int *, double *, int *, int *);\nint BLASFUNC(xgetrs)(char *, int *, int *, double *, int *, int *, double *, int *, int *);\n\nint BLASFUNC(sgesv)(int *, int *, float  *, int *, int *, float *, int *, int *);\nint BLASFUNC(dgesv)(int *, int *, double *, int *, int *, double*, int *, int *);\nint BLASFUNC(qgesv)(int *, int *, double *, int *, int *, double*, int *, int *);\nint BLASFUNC(cgesv)(int *, int *, float  *, int *, int *, float *, int *, int *);\nint BLASFUNC(zgesv)(int *, int *, double *, int *, int *, double*, int *, int *);\nint BLASFUNC(xgesv)(int *, int *, double *, int *, int *, double*, int *, int *);\n\nint BLASFUNC(spotf2)(char *, int *, float  *, int *, int *);\nint BLASFUNC(dpotf2)(char *, int *, double *, int *, int *);\nint BLASFUNC(qpotf2)(char *, int *, double *, int *, int *);\nint BLASFUNC(cpotf2)(char *, int *, float  *, int *, int *);\nint BLASFUNC(zpotf2)(char *, int *, double *, int *, int *);\nint BLASFUNC(xpotf2)(char *, int *, double *, int *, int *);\n\nint BLASFUNC(spotrf)(char *, int *, float  *, int *, int *);\nint BLASFUNC(dpotrf)(char *, int *, double *, int *, int *);\nint BLASFUNC(qpotrf)(char *, int *, double *, int *, int *);\nint BLASFUNC(cpotrf)(char *, int *, float  *, int *, int *);\nint BLASFUNC(zpotrf)(char *, int *, double *, int *, int *);\nint BLASFUNC(xpotrf)(char *, int *, double *, int *, int *);\n\nint BLASFUNC(slauu2)(char *, int *, float  *, int *, int *);\nint BLASFUNC(dlauu2)(char *, int *, double *, int *, int *);\nint BLASFUNC(qlauu2)(char *, int *, double *, int *, int *);\nint BLASFUNC(clauu2)(char *, int *, float  *, int *, int *);\nint BLASFUNC(zlauu2)(char *, int *, double *, int *, int *);\nint BLASFUNC(xlauu2)(char *, int *, double *, int *, int *);\n\nint BLASFUNC(slauum)(char *, int *, float  *, int *, int *);\nint BLASFUNC(dlauum)(char *, int *, double *, int *, int *);\nint BLASFUNC(qlauum)(char *, int *, double *, int *, int *);\nint BLASFUNC(clauum)(char *, int *, float  *, int *, int *);\nint BLASFUNC(zlauum)(char *, int *, double *, int *, int *);\nint BLASFUNC(xlauum)(char *, int *, double *, int *, int *);\n\nint BLASFUNC(strti2)(char *, char *, int *, float  *, int *, int *);\nint BLASFUNC(dtrti2)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(qtrti2)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(ctrti2)(char *, char *, int *, float  *, int *, int *);\nint BLASFUNC(ztrti2)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(xtrti2)(char *, char *, int *, double *, int *, int *);\n\nint BLASFUNC(strtri)(char *, char *, int *, float  *, int *, int *);\nint BLASFUNC(dtrtri)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(qtrtri)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(ctrtri)(char *, char *, int *, float  *, int *, int *);\nint BLASFUNC(ztrtri)(char *, char *, int *, double *, int *, int *);\nint BLASFUNC(xtrtri)(char *, char *, int *, double *, int *, int *);\n\nint BLASFUNC(spotri)(char *, int *, float  *, int *, int *);\nint BLASFUNC(dpotri)(char *, int *, double *, int *, int *);\nint BLASFUNC(qpotri)(char *, int *, double *, int *, int *);\nint BLASFUNC(cpotri)(char *, int *, float  *, int *, int *);\nint BLASFUNC(zpotri)(char *, int *, double *, int *, int *);\nint BLASFUNC(xpotri)(char *, int *, double *, int *, int *);\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/BLAS/blas_interface.hh",
    "content": "//=====================================================\n// File   :  blas_interface.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:28 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef blas_PRODUIT_MATRICE_VECTEUR_HH\n#define blas_PRODUIT_MATRICE_VECTEUR_HH\n\n#include <c_interface_base.h>\n#include <complex>\nextern \"C\"\n{\n#include \"blas.h\"\n\n  // Cholesky Factorization\n//   void spotrf_(const char* uplo, const int* n, float *a, const int* ld, int* info);\n//   void dpotrf_(const char* uplo, const int* n, double *a, const int* ld, int* info);\n  void ssytrd_(char *uplo, const int *n, float *a, const int *lda, float *d, float *e, float *tau, float *work, int *lwork, int *info );\n  void dsytrd_(char *uplo, const int *n, double *a, const int *lda, double *d, double *e, double *tau, double *work, int *lwork, int *info );\n  void sgehrd_( const int *n, int *ilo, int *ihi, float *a, const int *lda, float *tau, float *work, int *lwork, int *info );\n  void dgehrd_( const int *n, int *ilo, int *ihi, double *a, const int *lda, double *tau, double *work, int *lwork, int *info );\n\n  // LU row pivoting\n//   void dgetrf_( int *m, int *n, double *a, int *lda, int *ipiv, int *info );\n//   void sgetrf_(const int* m, const int* n, float *a, const int* ld, int* ipivot, int* info);\n  // LU full pivoting\n  void sgetc2_(const int* n, float *a, const int *lda, int *ipiv, int *jpiv, int*info );\n  void dgetc2_(const int* n, double *a, const int *lda, int *ipiv, int *jpiv, int*info );\n#ifdef HAS_LAPACK\n#endif\n}\n\n#define MAKE_STRING2(S) #S\n#define MAKE_STRING(S) MAKE_STRING2(S)\n\n#define CAT2(A,B) A##B\n#define CAT(A,B) CAT2(A,B)\n\n\ntemplate<class real> class blas_interface;\n\n\nstatic char notrans = 'N';\nstatic char trans = 'T';\nstatic char nonunit = 'N';\nstatic char lower = 'L';\nstatic char right = 'R';\nstatic char left = 'L';\nstatic int intone = 1;\n\n\n\n#define SCALAR        float\n#define SCALAR_PREFIX s\n#include \"blas_interface_impl.hh\"\n#undef SCALAR\n#undef SCALAR_PREFIX\n\n\n#define SCALAR        double\n#define SCALAR_PREFIX d\n#include \"blas_interface_impl.hh\"\n#undef SCALAR\n#undef SCALAR_PREFIX\n\n#endif\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/BLAS/blas_interface_impl.hh",
    "content": "\n#define BLAS_FUNC(NAME) CAT(CAT(SCALAR_PREFIX,NAME),_)\n\ntemplate<> class blas_interface<SCALAR> : public c_interface_base<SCALAR>\n{\n\npublic :\n  \n  static SCALAR fone;\n  static SCALAR fzero;\n\n  static inline std::string name()\n  {\n    return MAKE_STRING(CBLASNAME);\n  }\n\n  static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    BLAS_FUNC(gemv)(&notrans,&N,&N,&fone,A,&N,B,&intone,&fzero,X,&intone);\n  }\n\n  static inline void symv(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    BLAS_FUNC(symv)(&lower, &N,&fone,A,&N,B,&intone,&fzero,X,&intone);\n  }\n\n  static inline void syr2(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    BLAS_FUNC(syr2)(&lower,&N,&fone,B,&intone,X,&intone,A,&N);\n  }\n\n  static inline void ger(gene_matrix & A, gene_vector & X, gene_vector & Y, int N){\n    BLAS_FUNC(ger)(&N,&N,&fone,X,&intone,Y,&intone,A,&N);\n  }\n\n  static inline void rot(gene_vector & A,  gene_vector & B, SCALAR c, SCALAR s, int N){\n    BLAS_FUNC(rot)(&N,A,&intone,B,&intone,&c,&s);\n  }\n\n  static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    BLAS_FUNC(gemv)(&trans,&N,&N,&fone,A,&N,B,&intone,&fzero,X,&intone);\n  }\n\n  static inline void matrix_matrix_product(gene_matrix & A, gene_matrix & B, gene_matrix & X, int N){\n    BLAS_FUNC(gemm)(&notrans,&notrans,&N,&N,&N,&fone,A,&N,B,&N,&fzero,X,&N);\n  }\n\n  static inline void transposed_matrix_matrix_product(gene_matrix & A, gene_matrix & B, gene_matrix & X, int N){\n    BLAS_FUNC(gemm)(&notrans,&notrans,&N,&N,&N,&fone,A,&N,B,&N,&fzero,X,&N);\n  }\n\n  static inline void ata_product(gene_matrix & A, gene_matrix & X, int N){\n    BLAS_FUNC(syrk)(&lower,&trans,&N,&N,&fone,A,&N,&fzero,X,&N);\n  }\n\n  static inline void aat_product(gene_matrix & A, gene_matrix & X, int N){\n    BLAS_FUNC(syrk)(&lower,&notrans,&N,&N,&fone,A,&N,&fzero,X,&N);\n  }\n\n  static inline void axpy(SCALAR coef, const gene_vector & X, gene_vector & Y, int N){\n    BLAS_FUNC(axpy)(&N,&coef,X,&intone,Y,&intone);\n  }\n\n  static inline void axpby(SCALAR a, const gene_vector & X, SCALAR b, gene_vector & Y, int N){\n    BLAS_FUNC(scal)(&N,&b,Y,&intone);\n    BLAS_FUNC(axpy)(&N,&a,X,&intone,Y,&intone);\n  }\n\n  static inline void cholesky(const gene_matrix & X, gene_matrix & C, int N){\n    int N2 = N*N;\n    BLAS_FUNC(copy)(&N2, X, &intone, C, &intone);\n    char uplo = 'L';\n    int info = 0;\n    BLAS_FUNC(potrf)(&uplo, &N, C, &N, &info);\n    if(info!=0) std::cerr << \"potrf_ error \" << info << \"\\n\";\n  }\n\n  static inline void partial_lu_decomp(const gene_matrix & X, gene_matrix & C, int N){\n    int N2 = N*N;\n    BLAS_FUNC(copy)(&N2, X, &intone, C, &intone);\n    int info = 0;\n    int * ipiv = (int*)alloca(sizeof(int)*N);\n    BLAS_FUNC(getrf)(&N, &N, C, &N, ipiv, &info);\n    if(info!=0) std::cerr << \"getrf_ error \" << info << \"\\n\";\n  }\n  \n  static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector & X, int N){\n    BLAS_FUNC(copy)(&N, B, &intone, X, &intone);\n    BLAS_FUNC(trsv)(&lower, &notrans, &nonunit, &N, L, &N, X, &intone);\n  }\n\n  static inline void trisolve_lower_matrix(const gene_matrix & L, const gene_matrix& B, gene_matrix & X, int N){\n    BLAS_FUNC(copy)(&N, B, &intone, X, &intone);\n    BLAS_FUNC(trsm)(&right, &lower, &notrans, &nonunit, &N, &N, &fone, L, &N, X, &N);\n  }\n\n  static inline void trmm(gene_matrix & A, gene_matrix & B, gene_matrix & /*X*/, int N){\n    BLAS_FUNC(trmm)(&left, &lower, &notrans,&nonunit, &N,&N,&fone,A,&N,B,&N);\n  }\n\n  #ifdef HAS_LAPACK\n\n  static inline void lu_decomp(const gene_matrix & X, gene_matrix & C, int N){\n    int N2 = N*N;\n    BLAS_FUNC(copy)(&N2, X, &intone, C, &intone);\n    int info = 0;\n    int * ipiv = (int*)alloca(sizeof(int)*N);\n    int * jpiv = (int*)alloca(sizeof(int)*N);\n    BLAS_FUNC(getc2)(&N, C, &N, ipiv, jpiv, &info);\n  }\n\n\n\n  static inline void hessenberg(const gene_matrix & X, gene_matrix & C, int N){\n    {\n      int N2 = N*N;\n      int inc = 1;\n      BLAS_FUNC(copy)(&N2, X, &inc, C, &inc);\n    }\n    int info = 0;\n    int ilo = 1;\n    int ihi = N;\n    int bsize = 64;\n    int worksize = N*bsize;\n    SCALAR* d = new SCALAR[N+worksize];\n    BLAS_FUNC(gehrd)(&N, &ilo, &ihi, C, &N, d, d+N, &worksize, &info);\n    delete[] d;\n  }\n\n  static inline void tridiagonalization(const gene_matrix & X, gene_matrix & C, int N){\n    {\n      int N2 = N*N;\n      int inc = 1;\n      BLAS_FUNC(copy)(&N2, X, &inc, C, &inc);\n    }\n    char uplo = 'U';\n    int info = 0;\n    int bsize = 64;\n    int worksize = N*bsize;\n    SCALAR* d = new SCALAR[3*N+worksize];\n    BLAS_FUNC(sytrd)(&uplo, &N, C, &N, d, d+N, d+2*N, d+3*N, &worksize, &info);\n    delete[] d;\n  }\n  \n  #endif // HAS_LAPACK\n\n};\n\nSCALAR blas_interface<SCALAR>::fone = SCALAR(1);\nSCALAR blas_interface<SCALAR>::fzero = SCALAR(0);\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/BLAS/c_interface_base.h",
    "content": "\n#ifndef BTL_C_INTERFACE_BASE_H\n#define BTL_C_INTERFACE_BASE_H\n\n#include \"utilities.h\"\n#include <vector>\n\ntemplate<class real> class c_interface_base\n{\n\npublic:\n\n  typedef real                      real_type;\n  typedef std::vector<real>         stl_vector;\n  typedef std::vector<stl_vector >  stl_matrix;\n\n  typedef real* gene_matrix;\n  typedef real* gene_vector;\n\n  static void free_matrix(gene_matrix & A, int /*N*/){\n    delete[] A;\n  }\n\n  static void free_vector(gene_vector & B){\n    delete[] B;\n  }\n\n  static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    int N = A_stl.size();\n    A = new real[N*N];\n    for (int j=0;j<N;j++)\n      for (int i=0;i<N;i++)\n        A[i+N*j] = A_stl[j][i];\n  }\n\n  static inline void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    int N = B_stl.size();\n    B = new real[N];\n    for (int i=0;i<N;i++)\n      B[i] = B_stl[i];\n  }\n\n  static inline void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    int N = B_stl.size();\n    for (int i=0;i<N;i++)\n      B_stl[i] = B[i];\n  }\n\n  static inline void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int N = A_stl.size();\n    for (int j=0;j<N;j++){\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++)\n        A_stl[j][i] = A[i+N*j];\n    }\n  }\n\n  static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){\n    for (int i=0;i<N;i++)\n      cible[i]=source[i];\n  }\n\n  static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){\n    for (int j=0;j<N;j++){\n      for (int i=0;i<N;i++){\n        cible[i+N*j] = source[i+N*j];\n      }\n    }\n  }\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/BLAS/main.cpp",
    "content": "//=====================================================\n// File   :  main.cpp\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:28 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"blas_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\n#include \"action_cholesky.hh\"\n#include \"action_lu_decomp.hh\"\n#include \"action_partial_lu.hh\"\n#include \"action_trisolve_matrix.hh\"\n\n#ifdef HAS_LAPACK\n#include \"action_hessenberg.hh\"\n#endif\n\nBTL_MAIN;\n\nint main()\n{\n\n  bench<Action_axpy<blas_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_axpby<blas_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n\n  bench<Action_matrix_vector_product<blas_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_atv_product<blas_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_symv<blas_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_syr2<blas_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n\n  bench<Action_ger<blas_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_rot<blas_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n\n  bench<Action_matrix_matrix_product<blas_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_ata_product<blas_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_aat_product<blas_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  bench<Action_trisolve<blas_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_trisolve_matrix<blas_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  bench<Action_trmm<blas_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  bench<Action_cholesky<blas_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n  bench<Action_partial_lu<blas_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n\n  #ifdef HAS_LAPACK\n//   bench<Action_lu_decomp<blas_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n  bench<Action_hessenberg<blas_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n  bench<Action_tridiagonalization<blas_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n  #endif\n\n  //bench<Action_lu_solve<blas_LU_solve_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/STL/CMakeLists.txt",
    "content": "\nbtl_add_bench(btl_STL main.cpp OFF)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/STL/STL_interface.hh",
    "content": "//=====================================================\n// File   :  STL_interface.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:24 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef STL_INTERFACE_HH\n#define STL_INTERFACE_HH\n#include <string>\n#include <vector>\n#include \"utilities.h\"\n\nusing namespace std;\n\ntemplate<class real>\nclass STL_interface{\n\npublic :\n\n  typedef real real_type ;\n\n  typedef std::vector<real>  stl_vector;\n  typedef std::vector<stl_vector > stl_matrix;\n\n  typedef stl_matrix gene_matrix;\n\n  typedef stl_vector gene_vector;\n\n  static inline std::string name( void )\n  {\n    return \"STL\";\n  }\n\n  static void free_matrix(gene_matrix & /*A*/, int /*N*/){}\n\n  static void free_vector(gene_vector & /*B*/){}\n\n  static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    A = A_stl;\n  }\n\n  static inline void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    B = B_stl;\n  }\n\n  static inline void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    B_stl = B ;\n  }\n\n\n  static inline void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    A_stl = A ;\n  }\n\n  static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){\n    for (int i=0;i<N;i++){\n      cible[i]=source[i];\n    }\n  }\n\n\n  static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){\n    for (int i=0;i<N;i++)\n      for (int j=0;j<N;j++)\n        cible[i][j]=source[i][j];\n  }\n\n  static inline void ata_product(const gene_matrix & A, gene_matrix & X, int N)\n  {\n    real somme;\n    for (int j=0;j<N;j++){\n      for (int i=0;i<N;i++){\n        somme=0.0;\n        for (int k=0;k<N;k++)\n          somme += A[i][k]*A[j][k];\n        X[j][i]=somme;\n      }\n    }\n  }\n\n  static inline void aat_product(const gene_matrix & A, gene_matrix & X, int N)\n  {\n    real somme;\n    for (int j=0;j<N;j++){\n      for (int i=0;i<N;i++){\n        somme=0.0;\n        if(i>=j)\n        {\n          for (int k=0;k<N;k++){\n            somme+=A[k][i]*A[k][j];\n          }\n          X[j][i]=somme;\n        }\n      }\n    }\n  }\n\n\n  static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N)\n  {\n    real somme;\n    for (int j=0;j<N;j++){\n      for (int i=0;i<N;i++){\n        somme=0.0;\n        for (int k=0;k<N;k++)\n          somme+=A[k][i]*B[j][k];\n        X[j][i]=somme;\n      }\n    }\n  }\n\n  static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N)\n  {\n    real somme;\n    for (int i=0;i<N;i++){\n      somme=0.0;\n      for (int j=0;j<N;j++)\n        somme+=A[j][i]*B[j];\n      X[i]=somme;\n    }\n  }\n\n  static inline void symv(gene_matrix & A, gene_vector & B, gene_vector & X, int N)\n  {\n    for (int j=0; j<N; ++j)\n      X[j] = 0;\n    for (int j=0; j<N; ++j)\n    {\n      real t1 = B[j];\n      real t2 = 0;\n      X[j] += t1 * A[j][j];\n      for (int i=j+1; i<N; ++i) {\n        X[i] += t1 * A[j][i];\n        t2 += A[j][i] * B[i];\n      }\n      X[j] += t2;\n    }\n  }\n  \n  static inline void syr2(gene_matrix & A, gene_vector & B, gene_vector & X, int N)\n  {\n    for (int j=0; j<N; ++j)\n    {\n      for (int i=j; i<N; ++i)\n        A[j][i] += B[i]*X[j] + B[j]*X[i];\n    }\n  }\n\n  static inline void ger(gene_matrix & A, gene_vector & X, gene_vector & Y, int N)\n  {\n    for (int j=0; j<N; ++j)\n    {\n      for (int i=j; i<N; ++i)\n        A[j][i] += X[i]*Y[j];\n    }\n  }\n\n  static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N)\n  {\n    real somme;\n    for (int i=0;i<N;i++){\n      somme = 0.0;\n      for (int j=0;j<N;j++)\n        somme += A[i][j]*B[j];\n      X[i] = somme;\n    }\n  }\n\n  static inline void axpy(real coef, const gene_vector & X, gene_vector & Y, int N){\n    for (int i=0;i<N;i++)\n      Y[i]+=coef*X[i];\n  }\n\n  static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int N){\n    for (int i=0;i<N;i++)\n      Y[i] = a*X[i] + b*Y[i];\n  }\n\n  static inline void trisolve_lower(const gene_matrix & L, const gene_vector & B, gene_vector & X, int N){\n    copy_vector(B,X,N);\n    for(int i=0; i<N; ++i)\n    {\n      X[i] /= L[i][i];\n      real tmp = X[i];\n      for (int j=i+1; j<N; ++j)\n        X[j] -= tmp * L[i][j];\n    }\n  }\n\n  static inline real norm_diff(const stl_vector & A, const stl_vector & B)\n  {\n    int N=A.size();\n    real somme=0.0;\n    real somme2=0.0;\n\n    for (int i=0;i<N;i++){\n      real diff=A[i]-B[i];\n      somme+=diff*diff;\n      somme2+=A[i]*A[i];\n    }\n    return somme/somme2;\n  }\n\n  static inline real norm_diff(const stl_matrix & A, const stl_matrix & B)\n  {\n    int N=A[0].size();\n    real somme=0.0;\n    real somme2=0.0;\n\n    for (int i=0;i<N;i++){\n      for (int j=0;j<N;j++){\n        real diff=A[i][j] - B[i][j];\n        somme += diff*diff;\n        somme2 += A[i][j]*A[i][j];\n      }\n    }\n\n    return somme/somme2;\n  }\n\n  static inline void display_vector(const stl_vector & A)\n  {\n    int N=A.size();\n    for (int i=0;i<N;i++){\n      INFOS(\"A[\"<<i<<\"]=\"<<A[i]<<endl);\n    }\n  }\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/STL/main.cpp",
    "content": "//=====================================================\n// File   :  main.cpp\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:23 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"STL_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_axpy<STL_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_axpby<STL_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_matrix_vector_product<STL_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_atv_product<STL_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_symv<STL_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_syr2<STL_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_matrix_matrix_product<STL_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_ata_product<STL_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_aat_product<STL_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/blaze/CMakeLists.txt",
    "content": "\nfind_package(BLAZE)\nfind_package(Boost COMPONENTS system)\nif (BLAZE_FOUND AND Boost_FOUND)\n  include_directories(${BLAZE_INCLUDE_DIR} ${Boost_INCLUDE_DIRS})\n  btl_add_bench(btl_blaze main.cpp)\n  # Note: The newest blaze version requires C++14.\n  # Ideally, we should set this depending on the version of Blaze we found\n  set_property(TARGET btl_blaze PROPERTY CXX_STANDARD 14)\n  if(BUILD_btl_blaze)\n    target_link_libraries(btl_blaze ${Boost_LIBRARIES})\n  endif()\nendif ()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/blaze/blaze_interface.hh",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef BLAZE_INTERFACE_HH\n#define BLAZE_INTERFACE_HH\n\n#include <blaze/Math.h>\n#include <blaze/Blaze.h>\n#include <Eigen/Core>\n// using namespace blaze;\n\n#include <vector>\n\ntemplate<class real>\nclass blaze_interface {\n\npublic :\n\n  typedef real real_type ;\n\n  typedef std::vector<real>        stl_vector;\n  typedef std::vector<stl_vector > stl_matrix;\n\n  typedef blaze::DynamicMatrix<real,blaze::columnMajor>  gene_matrix;\n  typedef blaze::DynamicVector<real>  gene_vector;\n\n  static inline std::string name() { return \"blaze\"; }\n\n  static void free_matrix(gene_matrix & A, int N){\n    return ;\n  }\n\n  static void free_vector(gene_vector & B){\n    return ;\n  }\n\n  static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    A.resize(A_stl[0].size(), A_stl.size());\n\n    for (int j=0; j<A_stl.size() ; j++){\n      for (int i=0; i<A_stl[j].size() ; i++){\n        A(i,j) = A_stl[j][i];\n      }\n    }\n  }\n\n  static inline void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    B.resize(B_stl.size());\n    for (int i=0; i<B_stl.size() ; i++){\n      B[i] = B_stl[i];\n    }\n  }\n\n  static inline void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    for (int i=0; i<B_stl.size() ; i++){\n      B_stl[i] = B[i];\n    }\n  }\n\n  static inline void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int N=A_stl.size();\n    for (int j=0;j<N;j++){\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++){\n        A_stl[j][i] = A(i,j);\n      }\n    }\n  }\n\n  static EIGEN_DONT_INLINE void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N){\n    X = (A*B);\n  }\n\n  static EIGEN_DONT_INLINE void transposed_matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N){\n    X = (trans(A)*trans(B));\n  }\n\n  static EIGEN_DONT_INLINE void ata_product(const gene_matrix & A, gene_matrix & X, int N){\n    X = (trans(A)*A);\n  }\n\n  static EIGEN_DONT_INLINE void aat_product(const gene_matrix & A, gene_matrix & X, int N){\n    X = (A*trans(A));\n  }\n\n  static EIGEN_DONT_INLINE void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X = (A*B);\n  }\n\n  static EIGEN_DONT_INLINE void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X = (trans(A)*B);\n  }\n\n  static EIGEN_DONT_INLINE void axpy(const real coef, const gene_vector & X, gene_vector & Y, int N){\n    Y += coef * X;\n  }\n\n  static EIGEN_DONT_INLINE void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int N){\n    Y = a*X + b*Y;\n  }\n\n//   static inline void cholesky(const gene_matrix & X, gene_matrix & C, int N){\n//     C = X;\n//     recursive_cholesky(C);\n//   }\n\n//   static inline void lu_decomp(const gene_matrix & X, gene_matrix & R, int N){\n//     R = X;\n//     std::vector<int> ipvt(N);\n//     lu_factor(R, ipvt);\n//   }\n\n//   static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector & X, int N){\n//     X = lower_trisolve(L, B);\n//   }\n\n  static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){\n    cible = source;\n  }\n\n  static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){\n    cible = source;\n  }\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/blaze/main.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"blaze_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n\n  bench<Action_axpy<blaze_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_axpby<blaze_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n\n  bench<Action_matrix_vector_product<blaze_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_atv_product<blaze_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_matrix_matrix_product<blaze_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_ata_product<blaze_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_aat_product<blaze_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/blitz/CMakeLists.txt",
    "content": "\nfind_package(Blitz)\n\nif (BLITZ_FOUND)\n  include_directories(${BLITZ_INCLUDES})\n\n  btl_add_bench(btl_blitz btl_blitz.cpp)\n  if (BUILD_btl_blitz)\n    target_link_libraries(btl_blitz ${BLITZ_LIBRARIES})\n  endif ()\n\n  btl_add_bench(btl_tiny_blitz btl_tiny_blitz.cpp OFF)\n  if (BUILD_btl_tiny_blitz)\n    target_link_libraries(btl_tiny_blitz ${BLITZ_LIBRARIES})\n  endif ()\n\nendif ()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/blitz/blitz_LU_solve_interface.hh",
    "content": "//=====================================================\n// File   :  blitz_LU_solve_interface.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  lun sep 30 14:23:31 CEST 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef BLITZ_LU_SOLVE_INTERFACE_HH\n#define BLITZ_LU_SOLVE_INTERFACE_HH\n\n#include \"blitz/array.h\"\n#include <vector>\n\nBZ_USING_NAMESPACE(blitz)\n\ntemplate<class real>\nclass blitz_LU_solve_interface : public blitz_interface<real>\n{\n\npublic :\n\n  typedef typename blitz_interface<real>::gene_matrix gene_matrix;\n  typedef typename blitz_interface<real>::gene_vector gene_vector;\n\n  typedef blitz::Array<int,1> Pivot_Vector;\n\n  inline static void new_Pivot_Vector(Pivot_Vector & pivot,int N)\n  {\n\n    pivot.resize(N);\n\n  }\n\n  inline static void free_Pivot_Vector(Pivot_Vector & pivot)\n  {\n    \n    return;\n\n  }\n\n\n  static inline real matrix_vector_product_sliced(const gene_matrix & A, gene_vector B, int row, int col_start, int col_end)\n  {\n    \n    real somme=0.;\n    \n    for (int j=col_start ; j<col_end+1 ; j++){\n\t\n\tsomme+=A(row,j)*B(j);\n\t\n    }\n\n    return somme;\n\n  }\n\n\n\n\n  static inline real matrix_matrix_product_sliced(gene_matrix & A, int row, int col_start, int col_end, gene_matrix & B, int row_shift, int col )\n  {\n    \n    real somme=0.;\n    \n    for (int j=col_start ; j<col_end+1 ; j++){\n\t\n\tsomme+=A(row,j)*B(j+row_shift,col);\n\t\n    }\n\n    return somme;\n\n  }\n\n  inline static void LU_factor(gene_matrix & LU, Pivot_Vector & pivot, int N)\n  {\n\n    ASSERT( LU.rows()==LU.cols() ) ;\n    int index_max = 0 ;\n    real big = 0. ;\n    real theSum = 0. ;\n    real dum = 0. ;\n    // Get the implicit scaling information :\n    gene_vector ImplicitScaling( N ) ;\n    for( int i=0; i<N; i++ ) {\n      big = 0. ;\n      for( int j=0; j<N; j++ ) {\n\tif( abs( LU( i, j ) )>=big ) big = abs( LU( i, j ) ) ;\n      }\n      if( big==0. ) {\n\tINFOS( \"blitz_LU_factor::Singular matrix\" ) ;\n\texit( 0 ) ;\n      }\n      ImplicitScaling( i ) = 1./big ;\n    }\n    // Loop over columns of Crout's method :\n    for( int j=0; j<N; j++ ) {\n      for( int i=0; i<j; i++ ) {\n\ttheSum = LU( i, j ) ;\n\ttheSum -= matrix_matrix_product_sliced(LU, i, 0, i-1, LU, 0, j) ;\n\t//\ttheSum -= sum( LU( i, Range( fromStart, i-1 ) )*LU( Range( fromStart, i-1 ), j ) ) ;\n\tLU( i, j ) = theSum ;\n      }\n      \n      // Search for the largest pivot element :\n      big = 0. ;\n      for( int i=j; i<N; i++ ) {\n\ttheSum = LU( i, j ) ;\n\ttheSum -= matrix_matrix_product_sliced(LU, i, 0, j-1, LU, 0, j) ;\n\t//\ttheSum -= sum( LU( i, Range( fromStart, j-1 ) )*LU( Range( fromStart, j-1 ), j ) ) ;\n\tLU( i, j ) = theSum ;\n\tif( (ImplicitScaling( i )*abs( theSum ))>=big ) {\n\t  dum = ImplicitScaling( i )*abs( theSum ) ;\n\t  big = dum ;\n\t  index_max = i ;\n\t}\n      }\n      // Interchanging rows and the scale factor :\n      if( j!=index_max ) {\n\tfor( int k=0; k<N; k++ ) {\n\t  dum = LU( index_max, k ) ;\n\t  LU( index_max, k ) = LU( j, k ) ;\n\t  LU( j, k ) = dum ;\n\t}\n\tImplicitScaling( index_max ) = ImplicitScaling( j ) ;\n      }\n      pivot( j ) = index_max ;\n      if ( LU( j, j )==0. ) LU( j, j ) = 1.e-20 ;\n      // Divide by the pivot element :\n      if( j<N ) {\n\tdum = 1./LU( j, j ) ;\n\tfor( int i=j+1; i<N; i++ ) LU( i, j ) *= dum ;\n      }\n    }\n\n  }\n\n  inline static void LU_solve(const gene_matrix & LU, const Pivot_Vector pivot, gene_vector &B, gene_vector X, int N)\n  {\n\n    // Pour conserver le meme header, on travaille sur X, copie du second-membre B\n    X = B.copy() ;\n    ASSERT( LU.rows()==LU.cols() ) ;\n    firstIndex indI ;\n    // Forward substitution :\n    int ii = 0 ;\n    real theSum = 0. ;\n    for( int i=0; i<N; i++ ) {\n      int ip = pivot( i ) ;\n      theSum = X( ip ) ;\n      //      theSum = B( ip ) ;\n      X( ip ) = X( i ) ;\n      //      B( ip ) = B( i ) ;\n      if( ii ) {\n\ttheSum -= matrix_vector_product_sliced(LU, X, i, ii-1, i-1) ;\n\t//\ttheSum -= sum( LU( i, Range( ii-1, i-1 ) )*X( Range( ii-1, i-1 ) ) ) ;\n\t//\ttheSum -= sum( LU( i, Range( ii-1, i-1 ) )*B( Range( ii-1, i-1 ) ) ) ;\n      } else if( theSum ) {\n\tii = i+1 ;\n      }\n      X( i ) = theSum ;\n      //      B( i ) = theSum ;\n    }\n    // Backsubstitution :\n    for( int i=N-1; i>=0; i-- ) {\n      theSum = X( i ) ;\n      //      theSum = B( i ) ;\n      theSum -= matrix_vector_product_sliced(LU, X, i, i+1, N) ;\n      //      theSum -= sum( LU( i, Range( i+1, toEnd ) )*X( Range( i+1, toEnd ) ) ) ;\n      //      theSum -= sum( LU( i, Range( i+1, toEnd ) )*B( Range( i+1, toEnd ) ) ) ;\n      // Store a component of the solution vector :\n      X( i ) = theSum/LU( i, i ) ;\n      //      B( i ) = theSum/LU( i, i ) ;\n    }\n\n  }\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/blitz/blitz_interface.hh",
    "content": "//=====================================================\n// File   :  blitz_interface.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:30 CEST 2002\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef BLITZ_INTERFACE_HH\n#define BLITZ_INTERFACE_HH\n\n#include <blitz/blitz.h>\n#include <blitz/array.h>\n#include <blitz/vector-et.h>\n#include <blitz/vecwhere.h>\n#include <blitz/matrix.h>\n#include <vector>\n\nBZ_USING_NAMESPACE(blitz)\n\ntemplate<class real>\nclass blitz_interface{\n\npublic :\n\n  typedef real real_type ;\n\n  typedef std::vector<real>  stl_vector;\n  typedef std::vector<stl_vector > stl_matrix;\n\n  typedef blitz::Array<real, 2>  gene_matrix;\n  typedef blitz::Array<real, 1>  gene_vector;\n//   typedef blitz::Matrix<real, blitz::ColumnMajor>  gene_matrix;\n//   typedef blitz::Vector<real> gene_vector;\n\n  static inline std::string name() { return \"blitz\"; }\n\n  static void free_matrix(gene_matrix & A, int N){}\n\n  static void free_vector(gene_vector & B){}\n\n  static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    A.resize(A_stl[0].size(),A_stl.size());\n    for (int j=0; j<A_stl.size() ; j++){\n      for (int i=0; i<A_stl[j].size() ; i++){\n        A(i,j)=A_stl[j][i];\n      }\n    }\n  }\n\n  static inline void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    B.resize(B_stl.size());\n    for (int i=0; i<B_stl.size() ; i++){\n      B(i)=B_stl[i];\n    }\n  }\n\n  static inline void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    for (int i=0; i<B_stl.size() ; i++){\n      B_stl[i]=B(i);\n    }\n  }\n\n  static inline void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int N=A_stl.size();\n    for (int j=0;j<N;j++){\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++)\n        A_stl[j][i] = A(i,j);\n    }\n  }\n\n  static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N)\n  {\n    firstIndex i;\n    secondIndex j;\n    thirdIndex k;\n    X = sum(A(i,k) * B(k,j), k);\n  }\n\n  static inline void ata_product(const gene_matrix & A, gene_matrix & X, int N)\n  {\n    firstIndex i;\n    secondIndex j;\n    thirdIndex k;\n    X = sum(A(k,i) * A(k,j), k);\n  }\n\n  static inline void aat_product(const gene_matrix & A, gene_matrix & X, int N)\n  {\n    firstIndex i;\n    secondIndex j;\n    thirdIndex k;\n    X = sum(A(i,k) * A(j,k), k);\n  }\n\n  static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N)\n  {\n    firstIndex i;\n    secondIndex j;\n    X = sum(A(i,j)*B(j),j);\n  }\n\n  static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N)\n  {\n    firstIndex i;\n    secondIndex j;\n    X = sum(A(j,i) * B(j),j);\n  }\n\n  static inline void axpy(const real coef, const gene_vector & X, gene_vector & Y, int N)\n  {\n    firstIndex i;\n    Y = Y(i) + coef * X(i);\n    //Y += coef * X;\n  }\n\n  static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){\n    cible = source;\n    //cible.template operator=<gene_matrix>(source);\n//     for (int i=0;i<N;i++){\n//       for (int j=0;j<N;j++){\n//         cible(i,j)=source(i,j);\n//       }\n//     }\n  }\n\n  static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){\n    //cible.template operator=<gene_vector>(source);\n    cible = source;\n  }\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/blitz/btl_blitz.cpp",
    "content": "//=====================================================\n// File   :  main.cpp\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:30 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"blitz_interface.hh\"\n#include \"blitz_LU_solve_interface.hh\"\n#include \"bench.hh\"\n#include \"action_matrix_vector_product.hh\"\n#include \"action_matrix_matrix_product.hh\"\n#include \"action_axpy.hh\"\n#include \"action_lu_solve.hh\"\n#include \"action_ata_product.hh\"\n#include \"action_aat_product.hh\"\n#include \"action_atv_product.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n\n  bench<Action_matrix_vector_product<blitz_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_atv_product<blitz_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n\n  bench<Action_matrix_matrix_product<blitz_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_ata_product<blitz_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_aat_product<blitz_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  bench<Action_axpy<blitz_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n\n  //bench<Action_lu_solve<blitz_LU_solve_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/blitz/btl_tiny_blitz.cpp",
    "content": "//=====================================================\n// File   :  main.cpp\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:30 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"tiny_blitz_interface.hh\"\n#include \"static/bench_static.hh\"\n#include \"action_matrix_vector_product.hh\"\n#include \"action_matrix_matrix_product.hh\"\n#include \"action_axpy.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench_static<Action_axpy,tiny_blitz_interface>();\n  bench_static<Action_matrix_matrix_product,tiny_blitz_interface>();\n  bench_static<Action_matrix_vector_product,tiny_blitz_interface>();\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/blitz/tiny_blitz_interface.hh",
    "content": "//=====================================================\n// File   :  tiny_blitz_interface.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:30 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef TINY_BLITZ_INTERFACE_HH\n#define TINY_BLITZ_INTERFACE_HH\n\n#include \"blitz/array.h\"\n#include \"blitz/tiny.h\"\n#include \"blitz/tinymat.h\"\n#include \"blitz/tinyvec.h\"\n#include <blitz/tinyvec-et.h>\n\n#include <vector>\n\nBZ_USING_NAMESPACE(blitz)\n\ntemplate<class real, int SIZE>\nclass tiny_blitz_interface\n{\n\npublic :\n\n  typedef real real_type ;\n\n  typedef std::vector<real>  stl_vector;\n  typedef std::vector<stl_vector > stl_matrix;\n\n  typedef TinyVector<real,SIZE> gene_vector;\n  typedef TinyMatrix<real,SIZE,SIZE> gene_matrix;\n\n  static inline std::string name() { return \"tiny_blitz\"; }\n\n  static void free_matrix(gene_matrix & A, int N){}\n\n  static void free_vector(gene_vector & B){}\n\n  static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    for (int j=0; j<A_stl.size() ; j++)\n      for (int i=0; i<A_stl[j].size() ; i++)\n        A(i,j)=A_stl[j][i];\n  }\n\n  static inline void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    for (int i=0; i<B_stl.size() ; i++)\n      B(i) = B_stl[i];\n  }\n\n  static inline void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    for (int i=0; i<B_stl.size() ; i++)\n      B_stl[i] = B(i);\n  }\n\n  static inline void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int N = A_stl.size();\n    for (int j=0;j<N;j++)\n    {\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++)\n        A_stl[j][i] = A(i,j);\n    }\n  }\n\n  static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){\n    for (int j=0;j<N;j++)\n      for (int i=0;i<N;i++)\n        cible(i,j) = source(i,j);\n  }\n\n  static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){\n    for (int i=0;i<N;i++){\n      cible(i) = source(i);\n    }\n  }\n\n  static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N){\n    X = product(A,B);\n  }\n\n  static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X = product(A,B);\n  }\n\n  static inline void axpy(const real coef, const gene_vector & X, gene_vector & Y, int N){\n    Y += coef * X;\n  }\n\n};\n\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/eigen2/CMakeLists.txt",
    "content": "\nfind_package(Eigen2)\n\nif(EIGEN2_FOUND)\n\n  include_directories(BEFORE ${EIGEN2_INCLUDE_DIR})\n  btl_add_bench(btl_eigen2_linear main_linear.cpp)\n  btl_add_bench(btl_eigen2_vecmat main_vecmat.cpp)\n  btl_add_bench(btl_eigen2_matmat main_matmat.cpp)\n  btl_add_bench(btl_eigen2_adv main_adv.cpp      )\n\n  btl_add_target_property(btl_eigen2_linear COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=eigen2\")\n  btl_add_target_property(btl_eigen2_vecmat COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=eigen2\")\n  btl_add_target_property(btl_eigen2_matmat COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=eigen2\")\n  btl_add_target_property(btl_eigen2_adv    COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=eigen2\")\n\n  btl_add_bench(btl_tiny_eigen2 btl_tiny_eigen2.cpp OFF)\n\nendif() # EIGEN2_FOUND\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/eigen2/btl_tiny_eigen2.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"eigen3_interface.hh\"\n#include \"static/bench_static.hh\"\n#include \"action_matrix_vector_product.hh\"\n#include \"action_matrix_matrix_product.hh\"\n#include \"action_axpy.hh\"\n#include \"action_lu_solve.hh\"\n#include \"action_ata_product.hh\"\n#include \"action_aat_product.hh\"\n#include \"action_atv_product.hh\"\n#include \"action_cholesky.hh\"\n#include \"action_trisolve.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n\n  bench_static<Action_axpy,eigen2_interface>();\n  bench_static<Action_matrix_matrix_product,eigen2_interface>();\n  bench_static<Action_matrix_vector_product,eigen2_interface>();\n  bench_static<Action_atv_product,eigen2_interface>();\n  bench_static<Action_cholesky,eigen2_interface>();\n  bench_static<Action_trisolve,eigen2_interface>();\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/eigen2/eigen2_interface.hh",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <g.gael@free.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef EIGEN2_INTERFACE_HH\n#define EIGEN2_INTERFACE_HH\n// #include <cblas.h>\n#include <Eigen/Core>\n#include <Eigen/Cholesky>\n#include <Eigen/LU>\n#include <Eigen/QR>\n#include <vector>\n#include \"btl.hh\"\n\nusing namespace Eigen;\n\ntemplate<class real, int SIZE=Dynamic>\nclass eigen2_interface\n{\n\npublic :\n\n  enum {IsFixedSize = (SIZE!=Dynamic)};\n\n  typedef real real_type;\n\n  typedef std::vector<real> stl_vector;\n  typedef std::vector<stl_vector> stl_matrix;\n\n  typedef Eigen::Matrix<real,SIZE,SIZE> gene_matrix;\n  typedef Eigen::Matrix<real,SIZE,1> gene_vector;\n\n  static inline std::string name( void )\n  {\n    #if defined(EIGEN_VECTORIZE_SSE)\n    if (SIZE==Dynamic) return \"eigen2\"; else return \"tiny_eigen2\";\n    #elif defined(EIGEN_VECTORIZE_ALTIVEC) || defined(EIGEN_VECTORIZE_VSX)\n    if (SIZE==Dynamic) return \"eigen2\"; else return \"tiny_eigen2\";\n    #else\n    if (SIZE==Dynamic) return \"eigen2_novec\"; else return \"tiny_eigen2_novec\";\n    #endif\n  }\n\n  static void free_matrix(gene_matrix & A, int N) {}\n\n  static void free_vector(gene_vector & B) {}\n\n  static BTL_DONT_INLINE void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    A.resize(A_stl[0].size(), A_stl.size());\n\n    for (int j=0; j<A_stl.size() ; j++){\n      for (int i=0; i<A_stl[j].size() ; i++){\n        A.coeffRef(i,j) = A_stl[j][i];\n      }\n    }\n  }\n\n  static BTL_DONT_INLINE  void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    B.resize(B_stl.size(),1);\n\n    for (int i=0; i<B_stl.size() ; i++){\n      B.coeffRef(i) = B_stl[i];\n    }\n  }\n\n  static BTL_DONT_INLINE  void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    for (int i=0; i<B_stl.size() ; i++){\n      B_stl[i] = B.coeff(i);\n    }\n  }\n\n  static BTL_DONT_INLINE  void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int N=A_stl.size();\n\n    for (int j=0;j<N;j++){\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++){\n        A_stl[j][i] = A.coeff(i,j);\n      }\n    }\n  }\n\n  static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N){\n    X = (A*B).lazy();\n  }\n\n  static inline void transposed_matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N){\n    X = (A.transpose()*B.transpose()).lazy();\n  }\n\n  static inline void ata_product(const gene_matrix & A, gene_matrix & X, int N){\n    X = (A.transpose()*A).lazy();\n  }\n\n  static inline void aat_product(const gene_matrix & A, gene_matrix & X, int N){\n    X = (A*A.transpose()).lazy();\n  }\n\n  static inline void matrix_vector_product(const gene_matrix & A, const gene_vector & B, gene_vector & X, int N){\n    X = (A*B)/*.lazy()*/;\n  }\n\n  static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X = (A.transpose()*B)/*.lazy()*/;\n  }\n\n  static inline void axpy(real coef, const gene_vector & X, gene_vector & Y, int N){\n    Y += coef * X;\n  }\n\n  static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int N){\n    Y = a*X + b*Y;\n  }\n\n  static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){\n    cible = source;\n  }\n\n  static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){\n    cible = source;\n  }\n\n  static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector& X, int N){\n    X = L.template marked<LowerTriangular>().solveTriangular(B);\n  }\n\n  static inline void trisolve_lower_matrix(const gene_matrix & L, const gene_matrix& B, gene_matrix& X, int N){\n    X = L.template marked<LowerTriangular>().solveTriangular(B);\n  }\n\n  static inline void cholesky(const gene_matrix & X, gene_matrix & C, int N){\n    C = X.llt().matrixL();\n//     C = X;\n//     Cholesky<gene_matrix>::computeInPlace(C);\n//     Cholesky<gene_matrix>::computeInPlaceBlock(C);\n  }\n\n  static inline void lu_decomp(const gene_matrix & X, gene_matrix & C, int N){\n    C = X.lu().matrixLU();\n//     C = X.inverse();\n  }\n\n  static inline void tridiagonalization(const gene_matrix & X, gene_matrix & C, int N){\n    C = Tridiagonalization<gene_matrix>(X).packedMatrix();\n  }\n\n  static inline void hessenberg(const gene_matrix & X, gene_matrix & C, int N){\n    C = HessenbergDecomposition<gene_matrix>(X).packedMatrix();\n  }\n\n\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/eigen2/main_adv.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"eigen2_interface.hh\"\n#include \"bench.hh\"\n#include \"action_trisolve.hh\"\n#include \"action_trisolve_matrix.hh\"\n#include \"action_cholesky.hh\"\n#include \"action_hessenberg.hh\"\n#include \"action_lu_decomp.hh\"\n// #include \"action_partial_lu.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_trisolve<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_trisolve_matrix<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_cholesky<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_lu_decomp<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_partial_lu<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  bench<Action_hessenberg<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_tridiagonalization<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/eigen2/main_linear.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"eigen2_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n\n  bench<Action_axpy<eigen2_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_axpby<eigen2_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  \n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/eigen2/main_matmat.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"eigen2_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_matrix_matrix_product<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_ata_product<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_aat_product<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_trmm<eigen2_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/eigen2/main_vecmat.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"eigen2_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_matrix_vector_product<eigen2_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_atv_product<eigen2_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n//   bench<Action_symv<eigen2_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n//   bench<Action_syr2<eigen2_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n//   bench<Action_ger<eigen2_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/eigen3/CMakeLists.txt",
    "content": "\n\nif((NOT EIGEN3_INCLUDE_DIR) AND Eigen_SOURCE_DIR)\n  # unless EIGEN3_INCLUDE_DIR is defined, let's use current Eigen version\n  set(EIGEN3_INCLUDE_DIR ${Eigen_SOURCE_DIR})\n  set(EIGEN3_FOUND TRUE)\nelse()\n  find_package(Eigen3)\nendif()\n\nif (EIGEN3_FOUND)\n\n  include_directories(${EIGEN3_INCLUDE_DIR})\n  btl_add_bench(btl_eigen3_linear main_linear.cpp)\n  btl_add_bench(btl_eigen3_vecmat main_vecmat.cpp)\n  btl_add_bench(btl_eigen3_matmat main_matmat.cpp)\n  btl_add_bench(btl_eigen3_adv main_adv.cpp      )\n\n  btl_add_target_property(btl_eigen3_linear COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=eigen3\")\n  btl_add_target_property(btl_eigen3_vecmat COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=eigen3\")\n  btl_add_target_property(btl_eigen3_matmat COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=eigen3\")\n  btl_add_target_property(btl_eigen3_adv    COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=eigen3\")\n\n  option(BTL_BENCH_NOGCCVEC \"also bench Eigen explicit vec without GCC's auto vec\" OFF)\n  if(CMAKE_COMPILER_IS_GNUCXX AND BTL_BENCH_NOGCCVEC)\n    btl_add_bench(btl_eigen3_nogccvec_linear main_linear.cpp)\n    btl_add_bench(btl_eigen3_nogccvec_vecmat main_vecmat.cpp)\n    btl_add_bench(btl_eigen3_nogccvec_matmat main_matmat.cpp)\n    btl_add_bench(btl_eigen3_nogccvec_adv    main_adv.cpp   )\n\n    btl_add_target_property(btl_eigen3_nogccvec_linear COMPILE_FLAGS \"-fno-exceptions -fno-tree-vectorize -DBTL_PREFIX=eigen3_nogccvec\")\n    btl_add_target_property(btl_eigen3_nogccvec_vecmat COMPILE_FLAGS \"-fno-exceptions -fno-tree-vectorize -DBTL_PREFIX=eigen3_nogccvec\")\n    btl_add_target_property(btl_eigen3_nogccvec_matmat COMPILE_FLAGS \"-fno-exceptions -fno-tree-vectorize -DBTL_PREFIX=eigen3_nogccvec\")\n    btl_add_target_property(btl_eigen3_nogccvec_adv    COMPILE_FLAGS \"-fno-exceptions -fno-tree-vectorize -DBTL_PREFIX=eigen3_nogccvec\")\n  endif()\n\n\n  if(NOT BTL_NOVEC)\n    btl_add_bench(btl_eigen3_novec_linear main_linear.cpp OFF)\n    btl_add_bench(btl_eigen3_novec_vecmat main_vecmat.cpp OFF)\n    btl_add_bench(btl_eigen3_novec_matmat main_matmat.cpp OFF)\n    btl_add_bench(btl_eigen3_novec_adv main_adv.cpp       OFF)\n    btl_add_target_property(btl_eigen3_novec_linear COMPILE_FLAGS \"-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=eigen3_novec\")\n    btl_add_target_property(btl_eigen3_novec_vecmat COMPILE_FLAGS \"-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=eigen3_novec\")\n    btl_add_target_property(btl_eigen3_novec_matmat COMPILE_FLAGS \"-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=eigen3_novec\")\n    btl_add_target_property(btl_eigen3_novec_adv    COMPILE_FLAGS \"-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=eigen3_novec\")\n\n#     if(BUILD_btl_eigen3_adv)\n#       target_link_libraries(btl_eigen3_adv ${MKL_LIBRARIES})\n#     endif()\n\n  endif()\n\n  btl_add_bench(btl_tiny_eigen3 btl_tiny_eigen3.cpp OFF)\n\n  if(NOT BTL_NOVEC)\n    btl_add_bench(btl_tiny_eigen3_novec btl_tiny_eigen3.cpp OFF)\n    btl_add_target_property(btl_tiny_eigen3_novec    COMPILE_FLAGS \"-DBTL_PREFIX=eigen3_tiny\")\n\n    if(BUILD_btl_tiny_eigen3_novec)\n      btl_add_target_property(btl_tiny_eigen3_novec    COMPILE_FLAGS \"-DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=eigen3_tiny_novec\")\n    endif()\n  endif()\n\nendif ()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/eigen3/btl_tiny_eigen3.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"eigen3_interface.hh\"\n#include \"static/bench_static.hh\"\n#include \"action_matrix_vector_product.hh\"\n#include \"action_matrix_matrix_product.hh\"\n#include \"action_axpy.hh\"\n#include \"action_lu_solve.hh\"\n#include \"action_ata_product.hh\"\n#include \"action_aat_product.hh\"\n#include \"action_atv_product.hh\"\n#include \"action_cholesky.hh\"\n#include \"action_trisolve.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n\n  bench_static<Action_axpy,eigen2_interface>();\n  bench_static<Action_matrix_matrix_product,eigen2_interface>();\n  bench_static<Action_matrix_vector_product,eigen2_interface>();\n  bench_static<Action_atv_product,eigen2_interface>();\n  bench_static<Action_cholesky,eigen2_interface>();\n  bench_static<Action_trisolve,eigen2_interface>();\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/eigen3/eigen3_interface.hh",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef EIGEN3_INTERFACE_HH\n#define EIGEN3_INTERFACE_HH\n\n#include <Eigen/Eigen>\n#include <vector>\n#include \"btl.hh\"\n\nusing namespace Eigen;\n\ntemplate<class real, int SIZE=Dynamic>\nclass eigen3_interface\n{\n\npublic :\n\n  enum {IsFixedSize = (SIZE!=Dynamic)};\n\n  typedef real real_type;\n\n  typedef std::vector<real> stl_vector;\n  typedef std::vector<stl_vector> stl_matrix;\n\n  typedef Eigen::Matrix<real,SIZE,SIZE> gene_matrix;\n  typedef Eigen::Matrix<real,SIZE,1> gene_vector;\n\n  static inline std::string name( void )\n  {\n    return EIGEN_MAKESTRING(BTL_PREFIX);\n  }\n\n  static void free_matrix(gene_matrix & /*A*/, int /*N*/) {}\n\n  static void free_vector(gene_vector & /*B*/) {}\n\n  static BTL_DONT_INLINE void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    A.resize(A_stl[0].size(), A_stl.size());\n\n    for (unsigned int j=0; j<A_stl.size() ; j++){\n      for (unsigned int i=0; i<A_stl[j].size() ; i++){\n        A.coeffRef(i,j) = A_stl[j][i];\n      }\n    }\n  }\n\n  static BTL_DONT_INLINE  void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    B.resize(B_stl.size(),1);\n\n    for (unsigned int i=0; i<B_stl.size() ; i++){\n      B.coeffRef(i) = B_stl[i];\n    }\n  }\n\n  static BTL_DONT_INLINE  void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    for (unsigned int i=0; i<B_stl.size() ; i++){\n      B_stl[i] = B.coeff(i);\n    }\n  }\n\n  static BTL_DONT_INLINE  void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int  N=A_stl.size();\n\n    for (int j=0;j<N;j++){\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++){\n        A_stl[j][i] = A.coeff(i,j);\n      }\n    }\n  }\n\n  static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int  /*N*/){\n    X.noalias() = A*B;\n  }\n\n  static inline void transposed_matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int  /*N*/){\n    X.noalias() = A.transpose()*B.transpose();\n  }\n\n  static inline void ata_product(const gene_matrix & A, gene_matrix & X, int  /*N*/){\n    //X.noalias() = A.transpose()*A;\n    X.template triangularView<Lower>().setZero();\n    X.template selfadjointView<Lower>().rankUpdate(A.transpose());\n  }\n\n  static inline void aat_product(const gene_matrix & A, gene_matrix & X, int  /*N*/){\n    X.template triangularView<Lower>().setZero();\n    X.template selfadjointView<Lower>().rankUpdate(A);\n  }\n\n  static inline void matrix_vector_product(const gene_matrix & A, const gene_vector & B, gene_vector & X, int  /*N*/){\n    X.noalias() = A*B;\n  }\n\n  static inline void symv(const gene_matrix & A, const gene_vector & B, gene_vector & X, int  /*N*/){\n    X.noalias() = (A.template selfadjointView<Lower>() * B);\n//     internal::product_selfadjoint_vector<real,0,LowerTriangularBit,false,false>(N,A.data(),N, B.data(), 1, X.data(), 1);\n  }\n\n  template<typename Dest, typename Src> static void triassign(Dest& dst, const Src& src)\n  {\n    typedef typename Dest::Scalar Scalar;\n    typedef typename internal::packet_traits<Scalar>::type Packet;\n    const int PacketSize = sizeof(Packet)/sizeof(Scalar);\n    int size = dst.cols();\n    for(int j=0; j<size; j+=1)\n    {\n//       const int alignedEnd = alignedStart + ((innerSize-alignedStart) & ~packetAlignedMask);\n      Scalar* A0 = dst.data() + j*dst.stride();\n      int starti = j;\n      int alignedEnd = starti;\n      int alignedStart = (starti) + internal::first_aligned(&A0[starti], size-starti);\n      alignedEnd = alignedStart + ((size-alignedStart)/(2*PacketSize))*(PacketSize*2);\n\n      // do the non-vectorizable part of the assignment\n      for (int index = starti; index<alignedStart ; ++index)\n      {\n        if(Dest::Flags&RowMajorBit)\n          dst.copyCoeff(j, index, src);\n        else\n          dst.copyCoeff(index, j, src);\n      }\n\n      // do the vectorizable part of the assignment\n      for (int index = alignedStart; index<alignedEnd; index+=PacketSize)\n      {\n        if(Dest::Flags&RowMajorBit)\n          dst.template copyPacket<Src, Aligned, Unaligned>(j, index, src);\n        else\n          dst.template copyPacket<Src, Aligned, Unaligned>(index, j, src);\n      }\n\n      // do the non-vectorizable part of the assignment\n      for (int index = alignedEnd; index<size; ++index)\n      {\n        if(Dest::Flags&RowMajorBit)\n          dst.copyCoeff(j, index, src);\n        else\n          dst.copyCoeff(index, j, src);\n      }\n      //dst.col(j).tail(N-j) = src.col(j).tail(N-j);\n    }\n  }\n\n  static EIGEN_DONT_INLINE void syr2(gene_matrix & A,  gene_vector & X, gene_vector & Y, int  N){\n    // internal::product_selfadjoint_rank2_update<real,0,LowerTriangularBit>(N,A.data(),N, X.data(), 1, Y.data(), 1, -1);\n    for(int j=0; j<N; ++j)\n      A.col(j).tail(N-j) += X[j] * Y.tail(N-j) + Y[j] * X.tail(N-j);\n  }\n\n  static EIGEN_DONT_INLINE void ger(gene_matrix & A,  gene_vector & X, gene_vector & Y, int  N){\n    for(int j=0; j<N; ++j)\n      A.col(j) += X * Y[j];\n  }\n\n  static EIGEN_DONT_INLINE void rot(gene_vector & A,  gene_vector & B, real c, real s, int  /*N*/){\n    internal::apply_rotation_in_the_plane(A, B, JacobiRotation<real>(c,s));\n  }\n\n  static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int  /*N*/){\n    X.noalias() = (A.transpose()*B);\n  }\n\n  static inline void axpy(real coef, const gene_vector & X, gene_vector & Y, int  /*N*/){\n    Y += coef * X;\n  }\n\n  static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int  /*N*/){\n    Y = a*X + b*Y;\n  }\n\n  static EIGEN_DONT_INLINE void copy_matrix(const gene_matrix & source, gene_matrix & cible, int  /*N*/){\n    cible = source;\n  }\n\n  static EIGEN_DONT_INLINE void copy_vector(const gene_vector & source, gene_vector & cible, int  /*N*/){\n    cible = source;\n  }\n\n  static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector& X, int  /*N*/){\n    X = L.template triangularView<Lower>().solve(B);\n  }\n\n  static inline void trisolve_lower_matrix(const gene_matrix & L, const gene_matrix& B, gene_matrix& X, int  /*N*/){\n    X = L.template triangularView<Upper>().solve(B);\n  }\n\n  static inline void trmm(const gene_matrix & L, const gene_matrix& B, gene_matrix& X, int  /*N*/){\n    X.noalias() = L.template triangularView<Lower>() * B;\n  }\n\n  static inline void cholesky(const gene_matrix & X, gene_matrix & C, int  /*N*/){\n    C = X;\n    internal::llt_inplace<real,Lower>::blocked(C);\n    //C = X.llt().matrixL();\n//     C = X;\n//     Cholesky<gene_matrix>::computeInPlace(C);\n//     Cholesky<gene_matrix>::computeInPlaceBlock(C);\n  }\n\n  static inline void lu_decomp(const gene_matrix & X, gene_matrix & C, int  /*N*/){\n    C = X.fullPivLu().matrixLU();\n  }\n\n  static inline void partial_lu_decomp(const gene_matrix & X, gene_matrix & C, int  N){\n    Matrix<DenseIndex,1,Dynamic> piv(N);\n    DenseIndex nb;\n    C = X;\n    internal::partial_lu_inplace(C,piv,nb);\n//     C = X.partialPivLu().matrixLU();\n  }\n\n  static inline void tridiagonalization(const gene_matrix & X, gene_matrix & C, int  N){\n    typename Tridiagonalization<gene_matrix>::CoeffVectorType aux(N-1);\n    C = X;\n    internal::tridiagonalization_inplace(C, aux);\n  }\n\n  static inline void hessenberg(const gene_matrix & X, gene_matrix & C, int  /*N*/){\n    C = HessenbergDecomposition<gene_matrix>(X).packedMatrix();\n  }\n\n\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/eigen3/main_adv.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"eigen3_interface.hh\"\n#include \"bench.hh\"\n#include \"action_trisolve.hh\"\n#include \"action_trisolve_matrix.hh\"\n#include \"action_cholesky.hh\"\n#include \"action_hessenberg.hh\"\n#include \"action_lu_decomp.hh\"\n#include \"action_partial_lu.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_trisolve<eigen3_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n  bench<Action_trisolve_matrix<eigen3_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n  bench<Action_cholesky<eigen3_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n//   bench<Action_lu_decomp<eigen3_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n  bench<Action_partial_lu<eigen3_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n\n//   bench<Action_hessenberg<eigen3_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n  bench<Action_tridiagonalization<eigen3_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/eigen3/main_linear.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"eigen3_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n\n  bench<Action_axpy<eigen3_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_axpby<eigen3_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_rot<eigen3_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  \n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/eigen3/main_matmat.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"eigen3_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_matrix_matrix_product<eigen3_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_ata_product<eigen3_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_aat_product<eigen3_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_trmm<eigen3_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/eigen3/main_vecmat.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"eigen3_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_matrix_vector_product<eigen3_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_atv_product<eigen3_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_symv<eigen3_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_syr2<eigen3_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_ger<eigen3_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/gmm/CMakeLists.txt",
    "content": "\nfind_package(GMM)\nif (GMM_FOUND)\n  include_directories(${GMM_INCLUDES})\n  btl_add_bench(btl_gmm main.cpp)\nendif ()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/gmm/gmm_LU_solve_interface.hh",
    "content": "//=====================================================\n// File   :  blitz_LU_solve_interface.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  lun sep 30 14:23:31 CEST 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef BLITZ_LU_SOLVE_INTERFACE_HH\n#define BLITZ_LU_SOLVE_INTERFACE_HH\n\n#include \"blitz/array.h\"\n#include <vector>\n\nBZ_USING_NAMESPACE(blitz)\n\ntemplate<class real>\nclass blitz_LU_solve_interface : public blitz_interface<real>\n{\n\npublic :\n\n  typedef typename blitz_interface<real>::gene_matrix gene_matrix;\n  typedef typename blitz_interface<real>::gene_vector gene_vector;\n\n  typedef blitz::Array<int,1> Pivot_Vector;\n\n  inline static void new_Pivot_Vector(Pivot_Vector & pivot,int N)\n  {\n\n    pivot.resize(N);\n\n  }\n\n  inline static void free_Pivot_Vector(Pivot_Vector & pivot)\n  {\n    \n    return;\n\n  }\n\n\n  static inline real matrix_vector_product_sliced(const gene_matrix & A, gene_vector B, int row, int col_start, int col_end)\n  {\n    \n    real somme=0.;\n    \n    for (int j=col_start ; j<col_end+1 ; j++){\n\t\n\tsomme+=A(row,j)*B(j);\n\t\n    }\n\n    return somme;\n\n  }\n\n\n\n\n  static inline real matrix_matrix_product_sliced(gene_matrix & A, int row, int col_start, int col_end, gene_matrix & B, int row_shift, int col )\n  {\n    \n    real somme=0.;\n    \n    for (int j=col_start ; j<col_end+1 ; j++){\n\t\n\tsomme+=A(row,j)*B(j+row_shift,col);\n\t\n    }\n\n    return somme;\n\n  }\n\n  inline static void LU_factor(gene_matrix & LU, Pivot_Vector & pivot, int N)\n  {\n\n    ASSERT( LU.rows()==LU.cols() ) ;\n    int index_max = 0 ;\n    real big = 0. ;\n    real theSum = 0. ;\n    real dum = 0. ;\n    // Get the implicit scaling information :\n    gene_vector ImplicitScaling( N ) ;\n    for( int i=0; i<N; i++ ) {\n      big = 0. ;\n      for( int j=0; j<N; j++ ) {\n\tif( abs( LU( i, j ) )>=big ) big = abs( LU( i, j ) ) ;\n      }\n      if( big==0. ) {\n\tINFOS( \"blitz_LU_factor::Singular matrix\" ) ;\n\texit( 0 ) ;\n      }\n      ImplicitScaling( i ) = 1./big ;\n    }\n    // Loop over columns of Crout's method :\n    for( int j=0; j<N; j++ ) {\n      for( int i=0; i<j; i++ ) {\n\ttheSum = LU( i, j ) ;\n\ttheSum -= matrix_matrix_product_sliced(LU, i, 0, i-1, LU, 0, j) ;\n\t//\ttheSum -= sum( LU( i, Range( fromStart, i-1 ) )*LU( Range( fromStart, i-1 ), j ) ) ;\n\tLU( i, j ) = theSum ;\n      }\n      \n      // Search for the largest pivot element :\n      big = 0. ;\n      for( int i=j; i<N; i++ ) {\n\ttheSum = LU( i, j ) ;\n\ttheSum -= matrix_matrix_product_sliced(LU, i, 0, j-1, LU, 0, j) ;\n\t//\ttheSum -= sum( LU( i, Range( fromStart, j-1 ) )*LU( Range( fromStart, j-1 ), j ) ) ;\n\tLU( i, j ) = theSum ;\n\tif( (ImplicitScaling( i )*abs( theSum ))>=big ) {\n\t  dum = ImplicitScaling( i )*abs( theSum ) ;\n\t  big = dum ;\n\t  index_max = i ;\n\t}\n      }\n      // Interchanging rows and the scale factor :\n      if( j!=index_max ) {\n\tfor( int k=0; k<N; k++ ) {\n\t  dum = LU( index_max, k ) ;\n\t  LU( index_max, k ) = LU( j, k ) ;\n\t  LU( j, k ) = dum ;\n\t}\n\tImplicitScaling( index_max ) = ImplicitScaling( j ) ;\n      }\n      pivot( j ) = index_max ;\n      if ( LU( j, j )==0. ) LU( j, j ) = 1.e-20 ;\n      // Divide by the pivot element :\n      if( j<N ) {\n\tdum = 1./LU( j, j ) ;\n\tfor( int i=j+1; i<N; i++ ) LU( i, j ) *= dum ;\n      }\n    }\n\n  }\n\n  inline static void LU_solve(const gene_matrix & LU, const Pivot_Vector pivot, gene_vector &B, gene_vector X, int N)\n  {\n\n    // Pour conserver le meme header, on travaille sur X, copie du second-membre B\n    X = B.copy() ;\n    ASSERT( LU.rows()==LU.cols() ) ;\n    firstIndex indI ;\n    // Forward substitution :\n    int ii = 0 ;\n    real theSum = 0. ;\n    for( int i=0; i<N; i++ ) {\n      int ip = pivot( i ) ;\n      theSum = X( ip ) ;\n      //      theSum = B( ip ) ;\n      X( ip ) = X( i ) ;\n      //      B( ip ) = B( i ) ;\n      if( ii ) {\n\ttheSum -= matrix_vector_product_sliced(LU, X, i, ii-1, i-1) ;\n\t//\ttheSum -= sum( LU( i, Range( ii-1, i-1 ) )*X( Range( ii-1, i-1 ) ) ) ;\n\t//\ttheSum -= sum( LU( i, Range( ii-1, i-1 ) )*B( Range( ii-1, i-1 ) ) ) ;\n      } else if( theSum ) {\n\tii = i+1 ;\n      }\n      X( i ) = theSum ;\n      //      B( i ) = theSum ;\n    }\n    // Backsubstitution :\n    for( int i=N-1; i>=0; i-- ) {\n      theSum = X( i ) ;\n      //      theSum = B( i ) ;\n      theSum -= matrix_vector_product_sliced(LU, X, i, i+1, N) ;\n      //      theSum -= sum( LU( i, Range( i+1, toEnd ) )*X( Range( i+1, toEnd ) ) ) ;\n      //      theSum -= sum( LU( i, Range( i+1, toEnd ) )*B( Range( i+1, toEnd ) ) ) ;\n      // Store a component of the solution vector :\n      X( i ) = theSum/LU( i, i ) ;\n      //      B( i ) = theSum/LU( i, i ) ;\n    }\n\n  }\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/gmm/gmm_interface.hh",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef GMM_INTERFACE_HH\n#define GMM_INTERFACE_HH\n\n#include <gmm/gmm.h>\n#include <vector>\n\nusing namespace gmm;\n\ntemplate<class real>\nclass gmm_interface {\n\npublic :\n\n  typedef real real_type ;\n\n  typedef std::vector<real>  stl_vector;\n  typedef std::vector<stl_vector > stl_matrix;\n\n  typedef gmm::dense_matrix<real> gene_matrix;\n  typedef stl_vector gene_vector;\n\n  static inline std::string name( void )\n  {\n    return \"gmm\";\n  }\n\n  static void free_matrix(gene_matrix & A, int N){\n    return ;\n  }\n\n  static void free_vector(gene_vector & B){\n    return ;\n  }\n\n  static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    A.resize(A_stl[0].size(),A_stl.size());\n\n    for (int j=0; j<A_stl.size() ; j++){\n      for (int i=0; i<A_stl[j].size() ; i++){\n        A(i,j) = A_stl[j][i];\n      }\n    }\n  }\n\n  static inline void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    B = B_stl;\n  }\n\n  static inline void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    B_stl = B;\n  }\n\n  static inline void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int N=A_stl.size();\n\n    for (int j=0;j<N;j++){\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++){\n        A_stl[j][i] = A(i,j);\n      }\n    }\n  }\n\n  static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N){\n    gmm::mult(A,B, X);\n  }\n\n  static inline void transposed_matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N){\n    gmm::mult(gmm::transposed(A),gmm::transposed(B), X);\n  }\n\n  static inline void ata_product(const gene_matrix & A, gene_matrix & X, int N){\n    gmm::mult(gmm::transposed(A),A, X);\n  }\n\n  static inline void aat_product(const gene_matrix & A, gene_matrix & X, int N){\n    gmm::mult(A,gmm::transposed(A), X);\n  }\n\n  static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    gmm::mult(A,B,X);\n  }\n\n  static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    gmm::mult(gmm::transposed(A),B,X);\n  }\n\n  static inline void axpy(const real coef, const gene_vector & X, gene_vector & Y, int N){\n    gmm::add(gmm::scaled(X,coef), Y);\n  }\n\n  static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int N){\n    gmm::add(gmm::scaled(X,a), gmm::scaled(Y,b), Y);\n  }\n\n  static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){\n    gmm::copy(source,cible);\n  }\n\n  static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){\n    gmm::copy(source,cible);\n  }\n\n  static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector & X, int N){\n    gmm::copy(B,X);\n    gmm::lower_tri_solve(L, X, false);\n  }\n\n  static inline void partial_lu_decomp(const gene_matrix & X, gene_matrix & R, int N){\n    gmm::copy(X,R);\n    std::vector<int> ipvt(N);\n    gmm::lu_factor(R, ipvt);\n  }\n\n  static inline void hessenberg(const gene_matrix & X, gene_matrix & R, int N){\n    gmm::copy(X,R);\n    gmm::Hessenberg_reduction(R,X,false);\n  }\n\n  static inline void tridiagonalization(const gene_matrix & X, gene_matrix & R, int N){\n    gmm::copy(X,R);\n    gmm::Householder_tridiagonalization(R,X,false);\n  }\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/gmm/main.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"gmm_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n#include \"action_hessenberg.hh\"\n#include \"action_partial_lu.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n\n  bench<Action_axpy<gmm_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_axpby<gmm_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n\n  bench<Action_matrix_vector_product<gmm_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_atv_product<gmm_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n\n  bench<Action_matrix_matrix_product<gmm_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_ata_product<gmm_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_aat_product<gmm_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  bench<Action_trisolve<gmm_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  //bench<Action_lu_solve<blitz_LU_solve_interface<REAL_TYPE> > >(MIN_LU,MAX_LU,NB_POINT);\n\n  bench<Action_partial_lu<gmm_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  \n  bench<Action_hessenberg<gmm_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n  bench<Action_tridiagonalization<gmm_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/mtl4/.kdbgrc.main",
    "content": "[General]\nDebuggerCmdStr=\nDriverName=GDB\nFileVersion=1\nOptionsSelected=\nProgramArgs=\nTTYLevel=7\nWorkingDirectory=\n\n[Memory]\nColumnWidths=80,0\nNumExprs=0\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/mtl4/CMakeLists.txt",
    "content": "\nfind_package(MTL4)\nif (MTL4_FOUND)\n  include_directories(${MTL4_INCLUDE_DIR})\n  btl_add_bench(btl_mtl4 main.cpp)\nendif ()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/mtl4/main.cpp",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"mtl4_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n#include \"action_cholesky.hh\"\n// #include \"action_lu_decomp.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n\n  bench<Action_axpy<mtl4_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_axpby<mtl4_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n\n  bench<Action_matrix_vector_product<mtl4_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_atv_product<mtl4_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_matrix_matrix_product<mtl4_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_ata_product<mtl4_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_aat_product<mtl4_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  bench<Action_trisolve<mtl4_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_cholesky<mtl4_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_lu_decomp<mtl4_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/mtl4/mtl4_LU_solve_interface.hh",
    "content": "//=====================================================\n// File   :  blitz_LU_solve_interface.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>        \n// Copyright (C) EDF R&D,  lun sep 30 14:23:31 CEST 2002\n//=====================================================\n// \n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n// \n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n// \n#ifndef BLITZ_LU_SOLVE_INTERFACE_HH\n#define BLITZ_LU_SOLVE_INTERFACE_HH\n\n#include \"blitz/array.h\"\n#include <vector>\n\nBZ_USING_NAMESPACE(blitz)\n\ntemplate<class real>\nclass blitz_LU_solve_interface : public blitz_interface<real>\n{\n\npublic :\n\n  typedef typename blitz_interface<real>::gene_matrix gene_matrix;\n  typedef typename blitz_interface<real>::gene_vector gene_vector;\n\n  typedef blitz::Array<int,1> Pivot_Vector;\n\n  inline static void new_Pivot_Vector(Pivot_Vector & pivot,int N)\n  {\n\n    pivot.resize(N);\n\n  }\n\n  inline static void free_Pivot_Vector(Pivot_Vector & pivot)\n  {\n    \n    return;\n\n  }\n\n\n  static inline real matrix_vector_product_sliced(const gene_matrix & A, gene_vector B, int row, int col_start, int col_end)\n  {\n    \n    real somme=0.;\n    \n    for (int j=col_start ; j<col_end+1 ; j++){\n\t\n\tsomme+=A(row,j)*B(j);\n\t\n    }\n\n    return somme;\n\n  }\n\n\n\n\n  static inline real matrix_matrix_product_sliced(gene_matrix & A, int row, int col_start, int col_end, gene_matrix & B, int row_shift, int col )\n  {\n    \n    real somme=0.;\n    \n    for (int j=col_start ; j<col_end+1 ; j++){\n\t\n\tsomme+=A(row,j)*B(j+row_shift,col);\n\t\n    }\n\n    return somme;\n\n  }\n\n  inline static void LU_factor(gene_matrix & LU, Pivot_Vector & pivot, int N)\n  {\n\n    ASSERT( LU.rows()==LU.cols() ) ;\n    int index_max = 0 ;\n    real big = 0. ;\n    real theSum = 0. ;\n    real dum = 0. ;\n    // Get the implicit scaling information :\n    gene_vector ImplicitScaling( N ) ;\n    for( int i=0; i<N; i++ ) {\n      big = 0. ;\n      for( int j=0; j<N; j++ ) {\n\tif( abs( LU( i, j ) )>=big ) big = abs( LU( i, j ) ) ;\n      }\n      if( big==0. ) {\n\tINFOS( \"blitz_LU_factor::Singular matrix\" ) ;\n\texit( 0 ) ;\n      }\n      ImplicitScaling( i ) = 1./big ;\n    }\n    // Loop over columns of Crout's method :\n    for( int j=0; j<N; j++ ) {\n      for( int i=0; i<j; i++ ) {\n\ttheSum = LU( i, j ) ;\n\ttheSum -= matrix_matrix_product_sliced(LU, i, 0, i-1, LU, 0, j) ;\n\t//\ttheSum -= sum( LU( i, Range( fromStart, i-1 ) )*LU( Range( fromStart, i-1 ), j ) ) ;\n\tLU( i, j ) = theSum ;\n      }\n      \n      // Search for the largest pivot element :\n      big = 0. ;\n      for( int i=j; i<N; i++ ) {\n\ttheSum = LU( i, j ) ;\n\ttheSum -= matrix_matrix_product_sliced(LU, i, 0, j-1, LU, 0, j) ;\n\t//\ttheSum -= sum( LU( i, Range( fromStart, j-1 ) )*LU( Range( fromStart, j-1 ), j ) ) ;\n\tLU( i, j ) = theSum ;\n\tif( (ImplicitScaling( i )*abs( theSum ))>=big ) {\n\t  dum = ImplicitScaling( i )*abs( theSum ) ;\n\t  big = dum ;\n\t  index_max = i ;\n\t}\n      }\n      // Interchanging rows and the scale factor :\n      if( j!=index_max ) {\n\tfor( int k=0; k<N; k++ ) {\n\t  dum = LU( index_max, k ) ;\n\t  LU( index_max, k ) = LU( j, k ) ;\n\t  LU( j, k ) = dum ;\n\t}\n\tImplicitScaling( index_max ) = ImplicitScaling( j ) ;\n      }\n      pivot( j ) = index_max ;\n      if ( LU( j, j )==0. ) LU( j, j ) = 1.e-20 ;\n      // Divide by the pivot element :\n      if( j<N ) {\n\tdum = 1./LU( j, j ) ;\n\tfor( int i=j+1; i<N; i++ ) LU( i, j ) *= dum ;\n      }\n    }\n\n  }\n\n  inline static void LU_solve(const gene_matrix & LU, const Pivot_Vector pivot, gene_vector &B, gene_vector X, int N)\n  {\n\n    // Pour conserver le meme header, on travaille sur X, copie du second-membre B\n    X = B.copy() ;\n    ASSERT( LU.rows()==LU.cols() ) ;\n    firstIndex indI ;\n    // Forward substitution :\n    int ii = 0 ;\n    real theSum = 0. ;\n    for( int i=0; i<N; i++ ) {\n      int ip = pivot( i ) ;\n      theSum = X( ip ) ;\n      //      theSum = B( ip ) ;\n      X( ip ) = X( i ) ;\n      //      B( ip ) = B( i ) ;\n      if( ii ) {\n\ttheSum -= matrix_vector_product_sliced(LU, X, i, ii-1, i-1) ;\n\t//\ttheSum -= sum( LU( i, Range( ii-1, i-1 ) )*X( Range( ii-1, i-1 ) ) ) ;\n\t//\ttheSum -= sum( LU( i, Range( ii-1, i-1 ) )*B( Range( ii-1, i-1 ) ) ) ;\n      } else if( theSum ) {\n\tii = i+1 ;\n      }\n      X( i ) = theSum ;\n      //      B( i ) = theSum ;\n    }\n    // Backsubstitution :\n    for( int i=N-1; i>=0; i-- ) {\n      theSum = X( i ) ;\n      //      theSum = B( i ) ;\n      theSum -= matrix_vector_product_sliced(LU, X, i, i+1, N) ;\n      //      theSum -= sum( LU( i, Range( i+1, toEnd ) )*X( Range( i+1, toEnd ) ) ) ;\n      //      theSum -= sum( LU( i, Range( i+1, toEnd ) )*B( Range( i+1, toEnd ) ) ) ;\n      // Store a component of the solution vector :\n      X( i ) = theSum/LU( i, i ) ;\n      //      B( i ) = theSum/LU( i, i ) ;\n    }\n\n  }\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/mtl4/mtl4_interface.hh",
    "content": "//=====================================================\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef MTL4_INTERFACE_HH\n#define MTL4_INTERFACE_HH\n\n#include <boost/numeric/mtl/mtl.hpp>\n#include <boost/numeric/mtl/utility/range_generator.hpp>\n// #include <boost/numeric/mtl/operation/cholesky.hpp>\n#include <vector>\n\nusing namespace mtl;\n\ntemplate<class real>\nclass mtl4_interface {\n\npublic :\n\n  typedef real real_type ;\n\n  typedef std::vector<real>  stl_vector;\n  typedef std::vector<stl_vector > stl_matrix;\n\n  typedef mtl::dense2D<real, mtl::matrix::parameters<mtl::tag::col_major> > gene_matrix;\n  typedef mtl::dense_vector<real>  gene_vector;\n\n  static inline std::string name() { return \"mtl4\"; }\n\n  static void free_matrix(gene_matrix & A, int N){\n    return ;\n  }\n\n  static void free_vector(gene_vector & B){\n    return ;\n  }\n\n  static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    A.change_dim(A_stl[0].size(), A_stl.size());\n\n    for (int j=0; j<A_stl.size() ; j++){\n      for (int i=0; i<A_stl[j].size() ; i++){\n        A(i,j) = A_stl[j][i];\n      }\n    }\n  }\n\n  static inline void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    B.change_dim(B_stl.size());\n    for (int i=0; i<B_stl.size() ; i++){\n      B[i] = B_stl[i];\n    }\n  }\n\n  static inline void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    for (int i=0; i<B_stl.size() ; i++){\n      B_stl[i] = B[i];\n    }\n  }\n\n  static inline void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int N=A_stl.size();\n    for (int j=0;j<N;j++){\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++){\n        A_stl[j][i] = A(i,j);\n      }\n    }\n  }\n\n  static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N){\n    X = (A*B);\n//     morton_dense<double, doppled_64_row_mask> C(N,N);\n//     C = B;\n//     X = (A*C);\n  }\n\n  static inline void transposed_matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N){\n    X = (trans(A)*trans(B));\n  }\n\n//   static inline void ata_product(const gene_matrix & A, gene_matrix & X, int N){\n//     X = (trans(A)*A);\n//   }\n\n  static inline void aat_product(const gene_matrix & A, gene_matrix & X, int N){\n    X = (A*trans(A));\n  }\n\n  static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X = (A*B);\n  }\n\n  static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X = (trans(A)*B);\n  }\n\n  static inline void axpy(const real coef, const gene_vector & X, gene_vector & Y, int N){\n    Y += coef * X;\n  }\n\n  static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int N){\n    Y = a*X + b*Y;\n  }\n\n//   static inline void cholesky(const gene_matrix & X, gene_matrix & C, int N){\n//     C = X;\n//     recursive_cholesky(C);\n//   }\n\n//   static inline void lu_decomp(const gene_matrix & X, gene_matrix & R, int N){\n//     R = X;\n//     std::vector<int> ipvt(N);\n//     lu_factor(R, ipvt);\n//   }\n\n  static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector & X, int N){\n    X = lower_trisolve(L, B);\n  }\n\n  static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){\n    cible = source;\n  }\n\n  static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){\n    cible = source;\n  }\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/tensors/CMakeLists.txt",
    "content": "\n\nif((NOT TENSOR_INCLUDE_DIR) AND Eigen_SOURCE_DIR)\n  # unless TENSOR_INCLUDE_DIR is defined, let's use current Eigen version\n  set(TENSOR_INCLUDE_DIR ${Eigen_SOURCE_DIR})\n  set(TENSOR_FOUND TRUE)\nelse()\n  find_package(Tensor)\nendif()\n\nif (TENSOR_FOUND)\n\n  include_directories(${TENSOR_INCLUDE_DIR})\n  btl_add_bench(btl_tensor_linear main_linear.cpp)\n  btl_add_bench(btl_tensor_vecmat main_vecmat.cpp)\n  btl_add_bench(btl_tensor_matmat main_matmat.cpp)\n\n  btl_add_target_property(btl_tensor_linear COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=tensor\")\n  btl_add_target_property(btl_tensor_vecmat COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=tensor\")\n  btl_add_target_property(btl_tensor_matmat COMPILE_FLAGS \"-fno-exceptions -DBTL_PREFIX=tensor\")\n\n  option(BTL_BENCH_NOGCCVEC \"also bench Eigen explicit vec without GCC's auto vec\" OFF)\n  if(CMAKE_COMPILER_IS_GNUCXX AND BTL_BENCH_NOGCCVEC)\n    btl_add_bench(btl_tensor_nogccvec_linear main_linear.cpp)\n    btl_add_bench(btl_tensor_nogccvec_vecmat main_vecmat.cpp)\n    btl_add_bench(btl_tensor_nogccvec_matmat main_matmat.cpp)\n\n    btl_add_target_property(btl_tensor_nogccvec_linear COMPILE_FLAGS \"-fno-exceptions -fno-tree-vectorize -DBTL_PREFIX=tensor_nogccvec\")\n    btl_add_target_property(btl_tensor_nogccvec_vecmat COMPILE_FLAGS \"-fno-exceptions -fno-tree-vectorize -DBTL_PREFIX=tensor_nogccvec\")\n    btl_add_target_property(btl_tensor_nogccvec_matmat COMPILE_FLAGS \"-fno-exceptions -fno-tree-vectorize -DBTL_PREFIX=tensor_nogccvec\")\n  endif()\n\n\n  if(NOT BTL_NOVEC)\n    btl_add_bench(btl_tensor_novec_linear main_linear.cpp OFF)\n    btl_add_bench(btl_tensor_novec_vecmat main_vecmat.cpp OFF)\n    btl_add_bench(btl_tensor_novec_matmat main_matmat.cpp OFF)\n    btl_add_target_property(btl_tensor_novec_linear COMPILE_FLAGS \"-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=tensor_novec\")\n    btl_add_target_property(btl_tensor_novec_vecmat COMPILE_FLAGS \"-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=tensor_novec\")\n    btl_add_target_property(btl_tensor_novec_matmat COMPILE_FLAGS \"-fno-exceptions -DEIGEN_DONT_VECTORIZE -DBTL_PREFIX=tensor_novec\")\n\n  endif()\n\nendif ()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/tensors/main_linear.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"utilities.h\"\n#include \"tensor_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_axpy<tensor_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_axpby<tensor_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/tensors/main_matmat.cpp",
    "content": "//=====================================================\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//=====================================================\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n//\n#include \"utilities.h\"\n#include \"tensor_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_matrix_matrix_product<tensor_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/tensors/main_vecmat.cpp",
    "content": "//=====================================================\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//=====================================================\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n//\n#include \"utilities.h\"\n#include \"tensor_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_matrix_vector_product<tensor_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/tensors/tensor_interface.hh",
    "content": "//=====================================================\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//=====================================================\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n//\n#ifndef TENSOR_INTERFACE_HH\n#define TENSOR_INTERFACE_HH\n\n#include <unsupported/Eigen/CXX11/Tensor>\n#include <vector>\n#include \"btl.hh\"\n\nusing namespace Eigen;\n\ntemplate<class real>\nclass tensor_interface\n{\npublic :\n  typedef real real_type;\n  typedef typename Eigen::Tensor<real,2>::Index Index;\n\n  typedef std::vector<real> stl_vector;\n  typedef std::vector<stl_vector> stl_matrix;\n\n  typedef Eigen::Tensor<real,2> gene_matrix;\n  typedef Eigen::Tensor<real,1> gene_vector;\n\n\n  static inline std::string name( void )\n  {\n    return EIGEN_MAKESTRING(BTL_PREFIX);\n  }\n\n  static void free_matrix(gene_matrix & /*A*/, int /*N*/) {}\n\n  static void free_vector(gene_vector & /*B*/) {}\n\n  static BTL_DONT_INLINE void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    A.resize(Eigen::array<Index,2>(A_stl[0].size(), A_stl.size()));\n\n    for (unsigned int j=0; j<A_stl.size() ; j++){\n      for (unsigned int i=0; i<A_stl[j].size() ; i++){\n        A.coeffRef(Eigen::array<Index,2>(i,j)) = A_stl[j][i];\n      }\n    }\n  }\n\n  static BTL_DONT_INLINE  void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    B.resize(B_stl.size());\n\n    for (unsigned int i=0; i<B_stl.size() ; i++){\n      B.coeffRef(i) = B_stl[i];\n    }\n  }\n\n  static BTL_DONT_INLINE  void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    for (unsigned int i=0; i<B_stl.size() ; i++){\n      B_stl[i] = B.coeff(i);\n    }\n  }\n\n  static BTL_DONT_INLINE  void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int  N=A_stl.size();\n\n    for (int j=0;j<N;j++){\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++){\n        A_stl[j][i] = A.coeff(Eigen::array<Index,2>(i,j));\n      }\n    }\n  }\n\n  static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int  /*N*/){\n    typedef typename Eigen::Tensor<real_type, 1>::DimensionPair DimPair;\n    const Eigen::array<DimPair, 1> dims(DimPair(1, 0));\n    X/*.noalias()*/ = A.contract(B, dims);\n  }\n\n  static inline void matrix_vector_product(const gene_matrix & A, const gene_vector & B, gene_vector & X, int  /*N*/){\n    typedef typename Eigen::Tensor<real_type, 1>::DimensionPair DimPair;\n    const Eigen::array<DimPair, 1> dims(DimPair(1, 0));\n    X/*.noalias()*/ = A.contract(B, dims);\n  }\n\n  static inline void axpy(real coef, const gene_vector & X, gene_vector & Y, int  /*N*/){\n    Y += X.constant(coef) * X;\n  }\n\n  static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int  /*N*/){\n    Y = X.constant(a)*X + Y.constant(b)*Y;\n  }\n\n  static EIGEN_DONT_INLINE void copy_matrix(const gene_matrix & source, gene_matrix & cible, int  /*N*/){\n    cible = source;\n  }\n\n  static EIGEN_DONT_INLINE void copy_vector(const gene_vector & source, gene_vector & cible, int  /*N*/){\n    cible = source;\n  }\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/tvmet/CMakeLists.txt",
    "content": "\nfind_package(Tvmet)\nif (TVMET_FOUND)\n  include_directories(${TVMET_INCLUDE_DIR})\n  btl_add_bench(btl_tvmet main.cpp OFF)\nendif ()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/tvmet/main.cpp",
    "content": "//=====================================================\n// File   :  main.cpp\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:30 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"tvmet_interface.hh\"\n#include \"static/bench_static.hh\"\n#include \"action_matrix_vector_product.hh\"\n#include \"action_matrix_matrix_product.hh\"\n#include \"action_atv_product.hh\"\n#include \"action_axpy.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench_static<Action_axpy,tvmet_interface>();\n  bench_static<Action_matrix_matrix_product,tvmet_interface>();\n  bench_static<Action_matrix_vector_product,tvmet_interface>();\n  bench_static<Action_atv_product,tvmet_interface>();\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/tvmet/tvmet_interface.hh",
    "content": "//=====================================================\n// File   :  tvmet_interface.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:30 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef TVMET_INTERFACE_HH\n#define TVMET_INTERFACE_HH\n\n#include <tvmet/tvmet.h>\n#include <tvmet/Vector.h>\n#include <tvmet/Matrix.h>\n\n#include <vector>\n\nusing namespace tvmet;\n\ntemplate<class real, int SIZE>\nclass tvmet_interface{\n\npublic :\n\n  typedef real real_type ;\n\n  typedef std::vector<real>  stl_vector;\n  typedef std::vector<stl_vector > stl_matrix;\n\n  typedef Vector<real,SIZE> gene_vector;\n  typedef Matrix<real,SIZE,SIZE> gene_matrix;\n\n  static inline std::string name() { return \"tiny_tvmet\"; }\n\n  static void free_matrix(gene_matrix & A, int N){}\n\n  static void free_vector(gene_vector & B){}\n\n  static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    for (int j=0; j<A_stl.size() ; j++)\n      for (int i=0; i<A_stl[j].size() ; i++)\n        A(i,j) = A_stl[j][i];\n  }\n\n  static inline void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    for (int i=0; i<B_stl.size() ; i++)\n      B[i]=B_stl[i];\n  }\n\n  static inline void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    for (int i=0; i<B_stl.size() ; i++){\n      B_stl[i]=B[i];\n    }\n  }\n\n  static inline void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int N = A_stl.size();\n    for (int j=0;j<N;j++){\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++)\n        A_stl[j][i] = A(i,j);\n    }\n  }\n\n\n  static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){\n    cible = source;\n  }\n\n  static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){\n    cible = source;\n  }\n\n  static inline void matrix_matrix_product(const gene_matrix & A, const gene_matrix & B, gene_matrix & X, int N){\n    X = prod(A,B);\n  }\n\n  static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X = prod(A,B);\n  }\n\n  static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X = prod(trans(A),B);\n  }\n\n  static inline void axpy(const real coef, const gene_vector & X, gene_vector & Y, int N){\n    Y+=coef*X;\n  }\n\n};\n\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/ublas/CMakeLists.txt",
    "content": "\nfind_package(Boost)\nif (Boost_FOUND)\n  include_directories(${Boost_INCLUDE_DIRS})\n  include_directories(${Boost_INCLUDES})\n  btl_add_bench(btl_ublas main.cpp)\nendif ()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/ublas/main.cpp",
    "content": "//=====================================================\n// File   :  main.cpp\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:27 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#include \"utilities.h\"\n#include \"ublas_interface.hh\"\n#include \"bench.hh\"\n#include \"basic_actions.hh\"\n\nBTL_MAIN;\n\nint main()\n{\n  bench<Action_axpy<ublas_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n  bench<Action_axpby<ublas_interface<REAL_TYPE> > >(MIN_AXPY,MAX_AXPY,NB_POINT);\n\n  bench<Action_matrix_vector_product<ublas_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n  bench<Action_atv_product<ublas_interface<REAL_TYPE> > >(MIN_MV,MAX_MV,NB_POINT);\n\n  bench<Action_matrix_matrix_product<ublas_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_ata_product<ublas_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n//   bench<Action_aat_product<ublas_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  bench<Action_trisolve<ublas_interface<REAL_TYPE> > >(MIN_MM,MAX_MM,NB_POINT);\n\n  return 0;\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/btl/libs/ublas/ublas_interface.hh",
    "content": "//=====================================================\n// File   :  ublas_interface.hh\n// Author :  L. Plagne <laurent.plagne@edf.fr)>\n// Copyright (C) EDF R&D,  lun sep 30 14:23:27 CEST 2002\n//=====================================================\n//\n// This program is free software; you can redistribute it and/or\n// modify it under the terms of the GNU General Public License\n// as published by the Free Software Foundation; either version 2\n// of the License, or (at your option) any later version.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU General Public License for more details.\n// You should have received a copy of the GNU General Public License\n// along with this program; if not, write to the Free Software\n// Foundation, Inc., 59 Temple Place - Suite 330, Boston, MA  02111-1307, USA.\n//\n#ifndef UBLAS_INTERFACE_HH\n#define UBLAS_INTERFACE_HH\n\n#include <boost/numeric/ublas/vector.hpp>\n#include <boost/numeric/ublas/matrix.hpp>\n#include <boost/numeric/ublas/io.hpp>\n#include <boost/numeric/ublas/triangular.hpp>\n\nusing namespace boost::numeric;\n\ntemplate <class real>\nclass ublas_interface{\n\npublic :\n\n  typedef real real_type ;\n\n  typedef std::vector<real> stl_vector;\n  typedef std::vector<stl_vector> stl_matrix;\n\n  typedef typename boost::numeric::ublas::matrix<real,boost::numeric::ublas::column_major> gene_matrix;\n  typedef typename boost::numeric::ublas::vector<real> gene_vector;\n\n  static inline std::string name( void ) { return \"ublas\"; }\n\n  static void free_matrix(gene_matrix & A, int N) {}\n\n  static void free_vector(gene_vector & B) {}\n\n  static inline void matrix_from_stl(gene_matrix & A, stl_matrix & A_stl){\n    A.resize(A_stl.size(),A_stl[0].size());\n    for (int j=0; j<A_stl.size() ; j++)\n      for (int i=0; i<A_stl[j].size() ; i++)\n        A(i,j)=A_stl[j][i];\n  }\n\n  static inline void vector_from_stl(gene_vector & B, stl_vector & B_stl){\n    B.resize(B_stl.size());\n    for (int i=0; i<B_stl.size() ; i++)\n      B(i)=B_stl[i];\n  }\n\n  static inline void vector_to_stl(gene_vector & B, stl_vector & B_stl){\n    for (int i=0; i<B_stl.size() ; i++)\n      B_stl[i]=B(i);\n  }\n\n  static inline void matrix_to_stl(gene_matrix & A, stl_matrix & A_stl){\n    int N=A_stl.size();\n    for (int j=0;j<N;j++)\n    {\n      A_stl[j].resize(N);\n      for (int i=0;i<N;i++)\n        A_stl[j][i]=A(i,j);\n    }\n  }\n\n  static inline void copy_vector(const gene_vector & source, gene_vector & cible, int N){\n    for (int i=0;i<N;i++){\n      cible(i) = source(i);\n    }\n  }\n\n  static inline void copy_matrix(const gene_matrix & source, gene_matrix & cible, int N){\n    for (int i=0;i<N;i++){\n      for (int j=0;j<N;j++){\n        cible(i,j) = source(i,j);\n      }\n    }\n  }\n\n  static inline void matrix_vector_product_slow(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X =  prod(A,B);\n  }\n\n  static inline void matrix_matrix_product_slow(gene_matrix & A, gene_matrix & B, gene_matrix & X, int N){\n    X =  prod(A,B);\n  }\n\n  static inline void axpy_slow(const real coef, const gene_vector & X, gene_vector & Y, int N){\n    Y+=coef*X;\n  }\n\n  // alias free assignments\n\n  static inline void matrix_vector_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X.assign(prod(A,B));\n  }\n\n  static inline void atv_product(gene_matrix & A, gene_vector & B, gene_vector & X, int N){\n    X.assign(prod(trans(A),B));\n  }\n\n  static inline void matrix_matrix_product(gene_matrix & A, gene_matrix & B, gene_matrix & X, int N){\n    X.assign(prod(A,B));\n  }\n\n  static inline void axpy(const real coef, const gene_vector & X, gene_vector & Y, int N){\n    Y.plus_assign(coef*X);\n  }\n\n  static inline void axpby(real a, const gene_vector & X, real b, gene_vector & Y, int N){\n    Y = a*X + b*Y;\n  }\n\n  static inline void ata_product(gene_matrix & A, gene_matrix & X, int N){\n    // X =  prod(trans(A),A);\n    X.assign(prod(trans(A),A));\n  }\n\n  static inline void aat_product(gene_matrix & A, gene_matrix & X, int N){\n    // X =  prod(A,trans(A));\n    X.assign(prod(A,trans(A)));\n  }\n\n  static inline void trisolve_lower(const gene_matrix & L, const gene_vector& B, gene_vector & X, int N){\n    X = solve(L, B, ublas::lower_tag ());\n  }\n\n};\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/check_cache_queries.cpp",
    "content": "\n#define EIGEN_INTERNAL_DEBUG_CACHE_QUERY\n#include <iostream>\n#include \"../Eigen/Core\"\n\nusing namespace Eigen;\nusing namespace std;\n\n#define DUMP_CPUID(CODE) {\\\n  int abcd[4]; \\\n  abcd[0] = abcd[1] = abcd[2] = abcd[3] = 0;\\\n  EIGEN_CPUID(abcd, CODE, 0); \\\n  std::cout << \"The code \" << CODE << \" gives \" \\\n              << (int*)(abcd[0]) << \" \" << (int*)(abcd[1]) << \" \" \\\n              << (int*)(abcd[2]) << \" \" << (int*)(abcd[3]) << \" \" << std::endl; \\\n  }\n  \nint main()\n{\n  cout << \"Eigen's L1    = \" << internal::queryL1CacheSize() << endl;\n  cout << \"Eigen's L2/L3 = \" << internal::queryTopLevelCacheSize() << endl;\n  int l1, l2, l3;\n  internal::queryCacheSizes(l1, l2, l3);\n  cout << \"Eigen's L1, L2, L3       = \" << l1 << \" \" << l2 << \" \" << l3 << endl;\n  \n  #ifdef EIGEN_CPUID\n\n  int abcd[4];\n  int string[8];\n  char* string_char = (char*)(string);\n\n  // vendor ID\n  EIGEN_CPUID(abcd,0x0,0);\n  string[0] = abcd[1];\n  string[1] = abcd[3];\n  string[2] = abcd[2];\n  string[3] = 0;\n  cout << endl;\n  cout << \"vendor id = \" << string_char << endl;\n  cout << endl;\n  int max_funcs = abcd[0];\n\n  internal::queryCacheSizes_intel_codes(l1, l2, l3);\n  cout << \"Eigen's intel codes L1, L2, L3 = \" << l1 << \" \" << l2 << \" \" << l3 << endl;\n  if(max_funcs>=4)\n  {\n    internal::queryCacheSizes_intel_direct(l1, l2, l3);\n    cout << \"Eigen's intel direct L1, L2, L3 = \" << l1 << \" \" << l2 << \" \" << l3 << endl;\n  }\n  internal::queryCacheSizes_amd(l1, l2, l3);\n  cout << \"Eigen's amd L1, L2, L3         = \" << l1 << \" \" << l2 << \" \" << l3 << endl;\n  cout << endl;\n  \n  // dump Intel direct method\n  if(max_funcs>=4)\n  {\n    l1 = l2 = l3 = 0;\n    int cache_id = 0;\n    int cache_type = 0;\n    do {\n      abcd[0] = abcd[1] = abcd[2] = abcd[3] = 0;\n      EIGEN_CPUID(abcd,0x4,cache_id);\n      cache_type  = (abcd[0] & 0x0F) >> 0;\n      int cache_level = (abcd[0] & 0xE0) >> 5;  // A[7:5]\n      int ways        = (abcd[1] & 0xFFC00000) >> 22; // B[31:22]\n      int partitions  = (abcd[1] & 0x003FF000) >> 12; // B[21:12]\n      int line_size   = (abcd[1] & 0x00000FFF) >>  0; // B[11:0]\n      int sets        = (abcd[2]);                    // C[31:0]\n      int cache_size = (ways+1) * (partitions+1) * (line_size+1) * (sets+1);\n      \n      cout << \"cache[\" << cache_id << \"].type       = \" << cache_type << \"\\n\";\n      cout << \"cache[\" << cache_id << \"].level      = \" << cache_level << \"\\n\";\n      cout << \"cache[\" << cache_id << \"].ways       = \" << ways << \"\\n\";\n      cout << \"cache[\" << cache_id << \"].partitions = \" << partitions << \"\\n\";\n      cout << \"cache[\" << cache_id << \"].line_size  = \" << line_size << \"\\n\";\n      cout << \"cache[\" << cache_id << \"].sets       = \" << sets << \"\\n\";\n      cout << \"cache[\" << cache_id << \"].size       = \" << cache_size << \"\\n\";\n      \n      cache_id++;\n    } while(cache_type>0 && cache_id<16);\n  }\n  \n  // dump everything\n  std::cout << endl <<\"Raw dump:\" << endl;\n  for(int i=0; i<max_funcs; ++i)\n    DUMP_CPUID(i);\n\n  DUMP_CPUID(0x80000000);\n  DUMP_CPUID(0x80000001);\n  DUMP_CPUID(0x80000002);\n  DUMP_CPUID(0x80000003);\n  DUMP_CPUID(0x80000004);\n  DUMP_CPUID(0x80000005);\n  DUMP_CPUID(0x80000006);\n  DUMP_CPUID(0x80000007);\n  DUMP_CPUID(0x80000008);\n  #else\n  cout << \"EIGEN_CPUID is not defined\" << endl;\n  #endif\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/dense_solvers.cpp",
    "content": "#include <iostream>\n#include \"BenchTimer.h\"\n#include <Eigen/Dense>\n#include <map>\n#include <vector>\n#include <string>\n#include <sstream>\nusing namespace Eigen;\n\nstd::map<std::string,Array<float,1,8,DontAlign|RowMajor> > results;\nstd::vector<std::string> labels;\nstd::vector<Array2i> sizes;\n\ntemplate<typename Solver,typename MatrixType>\nEIGEN_DONT_INLINE\nvoid compute_norm_equation(Solver &solver, const MatrixType &A) {\n  if(A.rows()!=A.cols())\n    solver.compute(A.transpose()*A);\n  else\n    solver.compute(A);\n}\n\ntemplate<typename Solver,typename MatrixType>\nEIGEN_DONT_INLINE\nvoid compute(Solver &solver, const MatrixType &A) {\n  solver.compute(A);\n}\n\ntemplate<typename Scalar,int Size>\nvoid bench(int id, int rows, int size = Size)\n{\n  typedef Matrix<Scalar,Dynamic,Size> Mat;\n  typedef Matrix<Scalar,Dynamic,Dynamic> MatDyn;\n  typedef Matrix<Scalar,Size,Size> MatSquare;\n  Mat A(rows,size);\n  A.setRandom();\n  if(rows==size)\n    A = A*A.adjoint();\n  BenchTimer t_llt, t_ldlt, t_lu, t_fplu, t_qr, t_cpqr, t_cod, t_fpqr, t_jsvd, t_bdcsvd;\n\n  int svd_opt = ComputeThinU|ComputeThinV;\n  \n  int tries = 5;\n  int rep = 1000/size;\n  if(rep==0) rep = 1;\n//   rep = rep*rep;\n  \n  LLT<MatSquare> llt(size);\n  LDLT<MatSquare> ldlt(size);\n  PartialPivLU<MatSquare> lu(size);\n  FullPivLU<MatSquare> fplu(size,size);\n  HouseholderQR<Mat> qr(A.rows(),A.cols());\n  ColPivHouseholderQR<Mat> cpqr(A.rows(),A.cols());\n  CompleteOrthogonalDecomposition<Mat> cod(A.rows(),A.cols());\n  FullPivHouseholderQR<Mat> fpqr(A.rows(),A.cols());\n  JacobiSVD<MatDyn> jsvd(A.rows(),A.cols());\n  BDCSVD<MatDyn> bdcsvd(A.rows(),A.cols());\n  \n  BENCH(t_llt, tries, rep, compute_norm_equation(llt,A));\n  BENCH(t_ldlt, tries, rep, compute_norm_equation(ldlt,A));\n  BENCH(t_lu, tries, rep, compute_norm_equation(lu,A));\n  if(size<=1000)\n    BENCH(t_fplu, tries, rep, compute_norm_equation(fplu,A));\n  BENCH(t_qr, tries, rep, compute(qr,A));\n  BENCH(t_cpqr, tries, rep, compute(cpqr,A));\n  BENCH(t_cod, tries, rep, compute(cod,A));\n  if(size*rows<=10000000)\n    BENCH(t_fpqr, tries, rep, compute(fpqr,A));\n  if(size<500) // JacobiSVD is really too slow for too large matrices\n    BENCH(t_jsvd, tries, rep, jsvd.compute(A,svd_opt));\n//   if(size*rows<=20000000)\n    BENCH(t_bdcsvd, tries, rep, bdcsvd.compute(A,svd_opt));\n  \n  results[\"LLT\"][id] = t_llt.best();\n  results[\"LDLT\"][id] = t_ldlt.best();\n  results[\"PartialPivLU\"][id] = t_lu.best();\n  results[\"FullPivLU\"][id] = t_fplu.best();\n  results[\"HouseholderQR\"][id] = t_qr.best();\n  results[\"ColPivHouseholderQR\"][id] = t_cpqr.best();\n  results[\"CompleteOrthogonalDecomposition\"][id] = t_cod.best();\n  results[\"FullPivHouseholderQR\"][id] = t_fpqr.best();\n  results[\"JacobiSVD\"][id] = t_jsvd.best();\n  results[\"BDCSVD\"][id] = t_bdcsvd.best();\n}\n\n\nint main()\n{\n  labels.push_back(\"LLT\");\n  labels.push_back(\"LDLT\");\n  labels.push_back(\"PartialPivLU\");\n  labels.push_back(\"FullPivLU\");\n  labels.push_back(\"HouseholderQR\");\n  labels.push_back(\"ColPivHouseholderQR\");\n  labels.push_back(\"CompleteOrthogonalDecomposition\");\n  labels.push_back(\"FullPivHouseholderQR\");\n  labels.push_back(\"JacobiSVD\");\n  labels.push_back(\"BDCSVD\");\n\n  for(int i=0; i<labels.size(); ++i)\n    results[labels[i]].fill(-1);\n\n  const int small = 8;\n  sizes.push_back(Array2i(small,small));\n  sizes.push_back(Array2i(100,100));\n  sizes.push_back(Array2i(1000,1000));\n  sizes.push_back(Array2i(4000,4000));\n  sizes.push_back(Array2i(10000,small));\n  sizes.push_back(Array2i(10000,100));\n  sizes.push_back(Array2i(10000,1000));\n  sizes.push_back(Array2i(10000,4000));\n\n  using namespace std;\n\n  for(int k=0; k<sizes.size(); ++k)\n  {\n    cout << sizes[k](0) << \"x\" << sizes[k](1) << \"...\\n\";\n    bench<float,Dynamic>(k,sizes[k](0),sizes[k](1));\n  }\n\n  cout.width(32);\n  cout << \"solver/size\";\n  cout << \"  \";\n  for(int k=0; k<sizes.size(); ++k)\n  {\n    std::stringstream ss;\n    ss << sizes[k](0) << \"x\" << sizes[k](1);\n    cout.width(10); cout << ss.str(); cout << \" \";\n  }\n  cout << endl;\n\n\n  for(int i=0; i<labels.size(); ++i)\n  {\n    cout.width(32); cout << labels[i]; cout << \"  \";\n    ArrayXf r = (results[labels[i]]*100000.f).floor()/100.f;\n    for(int k=0; k<sizes.size(); ++k)\n    {\n      cout.width(10);\n      if(r(k)>=1e6)  cout << \"-\";\n      else           cout << r(k);\n      cout << \" \";\n    }\n    cout << endl;\n  }\n\n  // HTML output\n  cout << \"<table class=\\\"manual\\\">\" << endl;\n  cout << \"<tr><th>solver/size</th>\" << endl;\n  for(int k=0; k<sizes.size(); ++k)\n    cout << \"  <th>\" << sizes[k](0) << \"x\" << sizes[k](1) << \"</th>\";\n  cout << \"</tr>\" << endl;\n  for(int i=0; i<labels.size(); ++i)\n  {\n    cout << \"<tr\";\n    if(i%2==1) cout << \" class=\\\"alt\\\"\";\n    cout << \"><td>\" << labels[i] << \"</td>\";\n    ArrayXf r = (results[labels[i]]*100000.f).floor()/100.f;\n    for(int k=0; k<sizes.size(); ++k)\n    {\n      if(r(k)>=1e6) cout << \"<td>-</td>\";\n      else\n      {\n        cout << \"<td>\" << r(k);\n        if(i>0)\n          cout << \" (x\" << numext::round(10.f*results[labels[i]](k)/results[\"LLT\"](k))/10.f << \")\";\n        if(i<4 && sizes[k](0)!=sizes[k](1))\n          cout << \" <sup><a href=\\\"#note_ls\\\">*</a></sup>\";\n        cout << \"</td>\";\n      }\n    }\n    cout << \"</tr>\" << endl;\n  }\n  cout << \"</table>\" << endl;\n\n//   cout << \"LLT                             (ms)  \" << (results[\"LLT\"]*1000.).format(fmt) << \"\\n\";\n//   cout << \"LDLT                             (%)  \" << (results[\"LDLT\"]/results[\"LLT\"]).format(fmt) << \"\\n\";\n//   cout << \"PartialPivLU                     (%)  \" << (results[\"PartialPivLU\"]/results[\"LLT\"]).format(fmt) << \"\\n\";\n//   cout << \"FullPivLU                        (%)  \" << (results[\"FullPivLU\"]/results[\"LLT\"]).format(fmt) << \"\\n\";\n//   cout << \"HouseholderQR                    (%)  \" << (results[\"HouseholderQR\"]/results[\"LLT\"]).format(fmt) << \"\\n\";\n//   cout << \"ColPivHouseholderQR              (%)  \" << (results[\"ColPivHouseholderQR\"]/results[\"LLT\"]).format(fmt) << \"\\n\";\n//   cout << \"CompleteOrthogonalDecomposition  (%)  \" << (results[\"CompleteOrthogonalDecomposition\"]/results[\"LLT\"]).format(fmt) << \"\\n\";\n//   cout << \"FullPivHouseholderQR             (%)  \" << (results[\"FullPivHouseholderQR\"]/results[\"LLT\"]).format(fmt) << \"\\n\";\n//   cout << \"JacobiSVD                        (%)  \" << (results[\"JacobiSVD\"]/results[\"LLT\"]).format(fmt) << \"\\n\";\n//   cout << \"BDCSVD                           (%)  \" << (results[\"BDCSVD\"]/results[\"LLT\"]).format(fmt) << \"\\n\";\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/eig33.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// The computeRoots function included in this is based on materials\n// covered by the following copyright and license:\n// \n// Geometric Tools, LLC\n// Copyright (c) 1998-2010\n// Distributed under the Boost Software License, Version 1.0.\n// \n// Permission is hereby granted, free of charge, to any person or organization\n// obtaining a copy of the software and accompanying documentation covered by\n// this license (the \"Software\") to use, reproduce, display, distribute,\n// execute, and transmit the Software, and to prepare derivative works of the\n// Software, and to permit third-parties to whom the Software is furnished to\n// do so, all subject to the following:\n// \n// The copyright notices in the Software and this entire statement, including\n// the above license grant, this restriction and the following disclaimer,\n// must be included in all copies of the Software, in whole or in part, and\n// all derivative works of the Software, unless such copies or derivative\n// works are solely in the form of machine-executable object code generated by\n// a source language processor.\n// \n// THE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR\n// IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,\n// FITNESS FOR A PARTICULAR PURPOSE, TITLE AND NON-INFRINGEMENT. IN NO EVENT\n// SHALL THE COPYRIGHT HOLDERS OR ANYONE DISTRIBUTING THE SOFTWARE BE LIABLE\n// FOR ANY DAMAGES OR OTHER LIABILITY, WHETHER IN CONTRACT, TORT OR OTHERWISE,\n// ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER\n// DEALINGS IN THE SOFTWARE.\n\n#include <iostream>\n#include <Eigen/Core>\n#include <Eigen/Eigenvalues>\n#include <Eigen/Geometry>\n#include <bench/BenchTimer.h>\n\nusing namespace Eigen;\nusing namespace std;\n\ntemplate<typename Matrix, typename Roots>\ninline void computeRoots(const Matrix& m, Roots& roots)\n{\n  typedef typename Matrix::Scalar Scalar;\n  const Scalar s_inv3 = 1.0/3.0;\n  const Scalar s_sqrt3 = std::sqrt(Scalar(3.0));\n\n  // The characteristic equation is x^3 - c2*x^2 + c1*x - c0 = 0.  The\n  // eigenvalues are the roots to this equation, all guaranteed to be\n  // real-valued, because the matrix is symmetric.\n  Scalar c0 = m(0,0)*m(1,1)*m(2,2) + Scalar(2)*m(0,1)*m(0,2)*m(1,2) - m(0,0)*m(1,2)*m(1,2) - m(1,1)*m(0,2)*m(0,2) - m(2,2)*m(0,1)*m(0,1);\n  Scalar c1 = m(0,0)*m(1,1) - m(0,1)*m(0,1) + m(0,0)*m(2,2) - m(0,2)*m(0,2) + m(1,1)*m(2,2) - m(1,2)*m(1,2);\n  Scalar c2 = m(0,0) + m(1,1) + m(2,2);\n\n  // Construct the parameters used in classifying the roots of the equation\n  // and in solving the equation for the roots in closed form.\n  Scalar c2_over_3 = c2*s_inv3;\n  Scalar a_over_3 = (c1 - c2*c2_over_3)*s_inv3;\n  if (a_over_3 > Scalar(0))\n    a_over_3 = Scalar(0);\n\n  Scalar half_b = Scalar(0.5)*(c0 + c2_over_3*(Scalar(2)*c2_over_3*c2_over_3 - c1));\n\n  Scalar q = half_b*half_b + a_over_3*a_over_3*a_over_3;\n  if (q > Scalar(0))\n    q = Scalar(0);\n\n  // Compute the eigenvalues by solving for the roots of the polynomial.\n  Scalar rho = std::sqrt(-a_over_3);\n  Scalar theta = std::atan2(std::sqrt(-q),half_b)*s_inv3;\n  Scalar cos_theta = std::cos(theta);\n  Scalar sin_theta = std::sin(theta);\n  roots(2) = c2_over_3 + Scalar(2)*rho*cos_theta;\n  roots(0) = c2_over_3 - rho*(cos_theta + s_sqrt3*sin_theta);\n  roots(1) = c2_over_3 - rho*(cos_theta - s_sqrt3*sin_theta);\n}\n\ntemplate<typename Matrix, typename Vector>\nvoid eigen33(const Matrix& mat, Matrix& evecs, Vector& evals)\n{\n  typedef typename Matrix::Scalar Scalar;\n  // Scale the matrix so its entries are in [-1,1].  The scaling is applied\n  // only when at least one matrix entry has magnitude larger than 1.\n\n  Scalar shift = mat.trace()/3;\n  Matrix scaledMat = mat;\n  scaledMat.diagonal().array() -= shift;\n  Scalar scale = scaledMat.cwiseAbs()/*.template triangularView<Lower>()*/.maxCoeff();\n  scale = std::max(scale,Scalar(1));\n  scaledMat/=scale;\n\n  // Compute the eigenvalues\n//   scaledMat.setZero();\n  computeRoots(scaledMat,evals);\n\n  // compute the eigen vectors\n  // **here we assume 3 different eigenvalues**\n\n  // \"optimized version\" which appears to be slower with gcc!\n//     Vector base;\n//     Scalar alpha, beta;\n//     base <<   scaledMat(1,0) * scaledMat(2,1),\n//               scaledMat(1,0) * scaledMat(2,0),\n//              -scaledMat(1,0) * scaledMat(1,0);\n//     for(int k=0; k<2; ++k)\n//     {\n//       alpha = scaledMat(0,0) - evals(k);\n//       beta  = scaledMat(1,1) - evals(k);\n//       evecs.col(k) = (base + Vector(-beta*scaledMat(2,0), -alpha*scaledMat(2,1), alpha*beta)).normalized();\n//     }\n//     evecs.col(2) = evecs.col(0).cross(evecs.col(1)).normalized();\n\n//   // naive version\n//   Matrix tmp;\n//   tmp = scaledMat;\n//   tmp.diagonal().array() -= evals(0);\n//   evecs.col(0) = tmp.row(0).cross(tmp.row(1)).normalized();\n// \n//   tmp = scaledMat;\n//   tmp.diagonal().array() -= evals(1);\n//   evecs.col(1) = tmp.row(0).cross(tmp.row(1)).normalized();\n// \n//   tmp = scaledMat;\n//   tmp.diagonal().array() -= evals(2);\n//   evecs.col(2) = tmp.row(0).cross(tmp.row(1)).normalized();\n  \n  // a more stable version:\n  if((evals(2)-evals(0))<=Eigen::NumTraits<Scalar>::epsilon())\n  {\n    evecs.setIdentity();\n  }\n  else\n  {\n    Matrix tmp;\n    tmp = scaledMat;\n    tmp.diagonal ().array () -= evals (2);\n    evecs.col (2) = tmp.row (0).cross (tmp.row (1)).normalized ();\n    \n    tmp = scaledMat;\n    tmp.diagonal ().array () -= evals (1);\n    evecs.col(1) = tmp.row (0).cross(tmp.row (1));\n    Scalar n1 = evecs.col(1).norm();\n    if(n1<=Eigen::NumTraits<Scalar>::epsilon())\n      evecs.col(1) = evecs.col(2).unitOrthogonal();\n    else\n      evecs.col(1) /= n1;\n    \n    // make sure that evecs[1] is orthogonal to evecs[2]\n    evecs.col(1) = evecs.col(2).cross(evecs.col(1).cross(evecs.col(2))).normalized();\n    evecs.col(0) = evecs.col(2).cross(evecs.col(1));\n  }\n  \n  // Rescale back to the original size.\n  evals *= scale;\n  evals.array()+=shift;\n}\n\nint main()\n{\n  BenchTimer t;\n  int tries = 10;\n  int rep = 400000;\n  typedef Matrix3d Mat;\n  typedef Vector3d Vec;\n  Mat A = Mat::Random(3,3);\n  A = A.adjoint() * A;\n//   Mat Q = A.householderQr().householderQ();\n//   A = Q * Vec(2.2424567,2.2424566,7.454353).asDiagonal() * Q.transpose();\n\n  SelfAdjointEigenSolver<Mat> eig(A);\n  BENCH(t, tries, rep, eig.compute(A));\n  std::cout << \"Eigen iterative:  \" << t.best() << \"s\\n\";\n  \n  BENCH(t, tries, rep, eig.computeDirect(A));\n  std::cout << \"Eigen direct   :  \" << t.best() << \"s\\n\";\n\n  Mat evecs;\n  Vec evals;\n  BENCH(t, tries, rep, eigen33(A,evecs,evals));\n  std::cout << \"Direct: \" << t.best() << \"s\\n\\n\";\n\n//   std::cerr << \"Eigenvalue/eigenvector diffs:\\n\";\n//   std::cerr << (evals - eig.eigenvalues()).transpose() << \"\\n\";\n//   for(int k=0;k<3;++k)\n//     if(evecs.col(k).dot(eig.eigenvectors().col(k))<0)\n//       evecs.col(k) = -evecs.col(k);\n//   std::cerr << evecs - eig.eigenvectors() << \"\\n\\n\";\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/geometry.cpp",
    "content": "\n#include <iostream>\n#include <Eigen/Geometry>\n#include <bench/BenchTimer.h>\n\nusing namespace std;\nusing namespace Eigen;\n\n#ifndef SCALAR\n#define SCALAR float\n#endif\n\n#ifndef SIZE\n#define SIZE 8\n#endif\n\ntypedef SCALAR Scalar;\ntypedef NumTraits<Scalar>::Real RealScalar;\ntypedef Matrix<RealScalar,Dynamic,Dynamic> A;\ntypedef Matrix</*Real*/Scalar,Dynamic,Dynamic> B;\ntypedef Matrix<Scalar,Dynamic,Dynamic> C;\ntypedef Matrix<RealScalar,Dynamic,Dynamic> M;\n\ntemplate<typename Transformation, typename Data>\nEIGEN_DONT_INLINE void transform(const Transformation& t, Data& data)\n{\n  EIGEN_ASM_COMMENT(\"begin\");\n  data = t * data;\n  EIGEN_ASM_COMMENT(\"end\");\n}\n\ntemplate<typename Scalar, typename Data>\nEIGEN_DONT_INLINE void transform(const Quaternion<Scalar>& t, Data& data)\n{\n  EIGEN_ASM_COMMENT(\"begin quat\");\n  for(int i=0;i<data.cols();++i)\n    data.col(i) = t * data.col(i);\n  EIGEN_ASM_COMMENT(\"end quat\");\n}\n\ntemplate<typename T> struct ToRotationMatrixWrapper\n{\n  enum {Dim = T::Dim};\n  typedef typename T::Scalar Scalar;\n  ToRotationMatrixWrapper(const T& o) : object(o) {}\n  T object;\n};\n\ntemplate<typename QType, typename Data>\nEIGEN_DONT_INLINE void transform(const ToRotationMatrixWrapper<QType>& t, Data& data)\n{\n  EIGEN_ASM_COMMENT(\"begin quat via mat\");\n  data = t.object.toRotationMatrix() * data;\n  EIGEN_ASM_COMMENT(\"end quat via mat\");\n}\n\ntemplate<typename Scalar, int Dim, typename Data>\nEIGEN_DONT_INLINE void transform(const Transform<Scalar,Dim,Projective>& t, Data& data)\n{\n  data = (t * data.colwise().homogeneous()).template block<Dim,Data::ColsAtCompileTime>(0,0);\n}\n\ntemplate<typename T> struct get_dim { enum { Dim = T::Dim }; };\ntemplate<typename S, int R, int C, int O, int MR, int MC>\nstruct get_dim<Matrix<S,R,C,O,MR,MC> > { enum { Dim = R }; };\n\ntemplate<typename Transformation, int N>\nstruct bench_impl\n{\n  static EIGEN_DONT_INLINE void run(const Transformation& t)\n  {\n    Matrix<typename Transformation::Scalar,get_dim<Transformation>::Dim,N> data;\n    data.setRandom();\n    bench_impl<Transformation,N-1>::run(t);\n    BenchTimer timer;\n    BENCH(timer,10,100000,transform(t,data));\n    cout.width(9);\n    cout << timer.best() << \" \";\n  }\n};\n\n\ntemplate<typename Transformation>\nstruct bench_impl<Transformation,0>\n{\n  static EIGEN_DONT_INLINE void run(const Transformation&) {}\n};\n\ntemplate<typename Transformation>\nEIGEN_DONT_INLINE void bench(const std::string& msg, const Transformation& t)\n{\n  cout << msg << \" \";\n  bench_impl<Transformation,SIZE>::run(t);\n  std::cout << \"\\n\";\n}\n\nint main(int argc, char ** argv)\n{\n  Matrix<Scalar,3,4> mat34; mat34.setRandom();\n  Transform<Scalar,3,Isometry> iso3(mat34);\n  Transform<Scalar,3,Affine> aff3(mat34);\n  Transform<Scalar,3,AffineCompact> caff3(mat34);\n  Transform<Scalar,3,Projective> proj3(mat34);\n  Quaternion<Scalar> quat;quat.setIdentity();\n  ToRotationMatrixWrapper<Quaternion<Scalar> > quatmat(quat);\n  Matrix<Scalar,3,3> mat33; mat33.setRandom();\n  \n  cout.precision(4);\n  std::cout\n     << \"N          \";\n  for(int i=0;i<SIZE;++i)\n  {\n    cout.width(9);\n    cout << i+1 << \" \";\n  }\n  cout << \"\\n\";\n  \n  bench(\"matrix 3x3\", mat33);\n  bench(\"quaternion\", quat);\n  bench(\"quat-mat  \", quatmat);\n  bench(\"isometry3 \", iso3);\n  bench(\"affine3   \", aff3);\n  bench(\"c affine3 \", caff3);\n  bench(\"proj3     \", proj3);\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/changesets.txt",
    "content": "Load hg-to-git hash maps from ./eigen_git/.git/\n#3.0.1\n#3.1.1\n#3.2.0\n3.2.4\n#574a7621809fe\n58964a85800bd  # introduce AVX\n#589cbd7e98174  # merge\n589db7d49efbb  # introduce FMA\n#590a078f442a3  # complex and AVX\n590a419cea4a0  # improve packing with ptranspose\n#59251e85c936d  # merge\n#592e497a27ddc\n593d5a795f673  # New gebp kernel: up to 3 packets x 4 register-level blocks\n#5942c3c95990d  # merge\n#596c9788d55b9  # Disable 3pX4 kernel on Altivec\n#5999aa3dc4e21  # merge\n6209452eb38f8   # before-evaluators\n#6333eba5e1101  # Implement evaluator for sparse outer products\n#663b9d314ae19\n#6655ef95fabee  # Properly detect FMA support on ARM\n#667fe25f3b8e3   # FMA has been wrongly disabled\n#668409547a0c8\n#6694304c73542   # merge default to tensors\n#67216047c8d4a   # merge default to tensors\n#67410a79ca3a3   # merge default to tensors\n#674b7271dffb5   # Generalized the gebp apis\n676bfdd9f3ac9   # Made the blocking computation aware of the l3 cache;<br/> Also optimized the blocking parameters to take<br/> into account the number of threads used for a computation.\n6782dde63499c   # generalized gemv\n6799f98650d0a   # ensured that contractions that can be reduced to a matrix vector product\n#6840918c51e60   # merge tensor\n684e972b55ec4   # change prefetching in gebp\n#68598604576d1   # merge index conversion\n68963eb0f6fe6   # clean blocking size computation\n689db05f2d01e   # rotating kernel for ARM only\n#6901b7e12847d   # result_of\n69226275b250a   # fix prefetching change for ARM\n692692136350b   # prefetching\n693a8ad8887bf   # blocking size strategy\n693bcf9bb5c1f   # avoid redundant pack_rhs\n6987550107028   # dynamic loop swapping\n69858740ce4c6   # rm dynamic loop swapping,<br/> adjust lhs's micro panel height to fully exploit L1 cache\n698cd3bbffa73   # blocking heuristic:<br/> block on the rhs in L1 if the lhs fit in L1.\n701488c15615a   # organize a little our default cache sizes,<br/> and use a saner default L1 outside of x86 (10% faster on Nexus 5)\n701e56aabf205   # Refactor computeProductBlockingSizes to make room<br/> for the possibility of using lookup tables\n701ca5c12587b   # Polish lookup tables generation\n7013589a9c115   # actual_panel_rows computation should always be resilient<br/> to parameters not consistent with the known L1 cache size, see comment\n70102babb9c0f   # Provide a empirical lookup table for blocking sizes measured on a Nexus 5.<br/> Only for float, only for Android on ARM 32bit for now.\n7088481dc21ea   # Bug 986: add support for coefficient-based<br/> product with 0 depth.\n709d7f51feb07   # Bug 992: don't select a 3p GEMM path with non-SIMD scalar types.\n759f9303cc7c5   # 3.3-alpha1\n765aba1eda71e   # help clang inlining\n770fe630c9873   # Improve numerical accuracy in LLT and triangular solve<br/> by using true scalar divisions (instead of x * (1/y))\n#8741d23430628   # Improved the matrix multiplication blocking in the case<br/> where mr is not a power of 2 (e.g on Haswell CPUs)\n878f629fe95c8   # Made the index type a template parameter to evaluateProductBlockingSizes.<br/> Use numext::mini and numext::maxi instead of <br/> std::min/std::max to compute blocking sizes.\n8975d51a7f12c   # Don't optimize the processing of the last rows of<br/> a matrix matrix product in cases that violate<br/> the assumptions made by the optimized code path.\n8986136f4fdd4   # Remove the rotating kernel.\n898e68e165a23   # Bug 256: enable vectorization with unaligned loads/stores.\n91466e99ab6a1   # Relax mixing-type constraints for binary coeff-wise operators\n91776236cdea4   # merge\n917101ea26f5e   # Include the cost of stores in unrolling\n921672076db5d   # Fix perf regression introduced in changeset e56aabf205\n9210fa9e4a15c   # Fix perf regression in dgemm introduced by changeset 5d51a7f12c\n936f6b3cf8de9   # 3.3-beta2\n944504a4404f1   # Optimize expression matching 'd?=a-b*c' as 'd?=a; d?=b*c;'\n95877e27fbeee   # 3.3-rc1\n959779774f98c   # Bug 1311: fix alignment logic in some cases<br/> of (scalar*small).lazyProduct(small)\n9729f9d8d2f62   # Disabled part of the matrix matrix peeling code<br/> that's incompatible with 512 bit registers\n979eeac81b8c0   # 3.3.0\n989c927af60ed   # Fix a performance regression in (mat*mat)*vec<br/> for which mat*mat was evaluated multiple times.\n994fe696022ec   # Operators += and -= do not resize!\n99466f65ccc36   # Ease compiler generating clean and efficient code in mat*vec\n9946a5fe86098   # Complete rewrite of column-major-matrix * vector product<br/> to deliver higher performance of modern CPU.\n99591003f3b86   # Improve performance of row-major-dense-matrix * vector products<br/> for recent CPUs.\n997eb621413c1   # Revert vec/y to vec*(1/y) in row-major TRSM\n10444bbc320468  # Bug 1435: fix aliasing issue in exressions like: A = C - B*A;\n1073624df50945  # Adds missing EIGEN_STRONG_INLINE to support MSVC<br/> properly inlining small vector calculations\n1094d428a199ab  # Bug 1562: optimize evaluation of small products<br/> of the form s*A*B by rewriting them as: s*(A.lazyProduct(B))<br/> to save a costly temporary.<br/> Measured speedup from 2x to 5x.\n1096de9e31a06d  # Introduce the macro ei_declare_local_nested_eval to<br/> help allocating on the stack local temporaries via alloca,<br/> and let outer-products makes a good use of it.\n11087b91c11207  # Bug 1578: Improve prefetching in matrix multiplication on MIPS.\n1153aa110e681b  # PR 526: Speed up multiplication of small, dynamically sized matrices\n11544ad359237a  # Vectorize row-by-row gebp loop iterations on 16 packets as well\n1157a476054879  # Bug 1624: improve matrix-matrix product on ARM 64, 20% speedup\n1160a4159dba08  # do not read buffers out of bounds\n1163c53eececb0  # Implement AVX512 vectorization of std::complex<float/double>\n11644e7746fe22  # Bug 1636: fix gemm performance issue with gcc>=6 and no FMA\n1164956678a4ef  # Bug 1515: disable gebp's 3pX4 micro kernel<br/> for MSVC<=19.14 because of register spilling.\n1165426bce7529  # fix EIGEN_GEBP_2PX4_SPILLING_WORKAROUND<br/> for non vectorized type, and non x86/64 target\n11660d90637838  # enable spilling workaround on architectures with SSE/AVX\n1166f159cf3d75  # Artificially increase l1-blocking size for AVX512.<br/> +10% speedup with current kernels.\n11686dd93f7e3b  # Make code compile again for older compilers.\n1175dbfcceabf5  # Bug: 1633: refactor gebp kernel and optimize for neon\n117670e133333d  # Bug 1661: fix regression in GEBP and AVX512\n11760f028f61cb  # GEBP: cleanup logic to choose between<br/> a 4 packets of 1 packet (=e118ce86fd+fix)\n1180de77bf5d6c  # gebp: Add new ½ and ¼ packet rows per (peeling) round on the lhs\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/gemm.cpp",
    "content": "#include \"gemm_common.h\"\n\nEIGEN_DONT_INLINE\nvoid gemm(const Mat &A, const Mat &B, Mat &C)\n{\n  C.noalias() += A * B;\n}\n\nint main(int argc, char **argv)\n{\n  return main_gemm(argc, argv, gemm);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/gemm_common.h",
    "content": "#include <iostream>\n#include <fstream>\n#include <vector>\n#include <string>\n#include \"eigen_src/Eigen/Core\"\n#include \"../BenchTimer.h\"\nusing namespace Eigen;\n\n#ifndef SCALAR\n#error SCALAR must be defined\n#endif\n\ntypedef SCALAR Scalar;\n\ntypedef Matrix<Scalar,Dynamic,Dynamic> Mat;\n\ntemplate<typename Func>\nEIGEN_DONT_INLINE\ndouble bench(long m, long n, long k, const Func& f)\n{\n  Mat A(m,k);\n  Mat B(k,n);\n  Mat C(m,n);\n  A.setRandom();\n  B.setRandom();\n  C.setZero();\n  \n  BenchTimer t;\n  \n  double up = 1e8*4/sizeof(Scalar);\n  double tm0 = 4, tm1 = 10;\n  if(NumTraits<Scalar>::IsComplex)\n  {\n    up /= 4;\n    tm0 = 2;\n    tm1 = 4;\n  }\n  \n  double flops = 2. * m * n * k;\n  long rep = std::max(1., std::min(100., up/flops) );\n  long tries = std::max(tm0, std::min(tm1, up/flops) );\n  \n  BENCH(t, tries, rep, f(A,B,C));\n  \n  return 1e-9 * rep * flops / t.best();\n}\n\ntemplate<typename Func>\nint main_gemm(int argc, char **argv, const Func& f)\n{\n  std::vector<double> results;\n  \n  std::string filename = std::string(\"gemm_settings.txt\");\n  if(argc>1)\n    filename = std::string(argv[1]);\n  std::ifstream settings(filename);\n  long m, n, k;\n  while(settings >> m >> n >> k)\n  {\n    //std::cerr << \"  Testing \" << m << \" \" << n << \" \" << k << std::endl;\n    results.push_back( bench(m, n, k, f) );\n  }\n  \n  std::cout << RowVectorXd::Map(results.data(), results.size());\n  \n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/gemm_settings.txt",
    "content": "8 8 8\n9 9 9\n24 24 24\n239 239 239\n240 240 240\n2400 24 24\n24 2400 24\n24 24 2400\n24 2400 2400\n2400 24 2400\n2400 2400 24\n2400 2400 64\n4800 23 160\n23 4800 160\n2400 2400 2400\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/gemm_square_settings.txt",
    "content": "8 8 8\n9 9 9\n12 12 12\n15 15 15\n16 16 16\n24 24 24\n102 102 102\n239 239 239\n240 240 240\n2400 2400 2400\n2463 2463 2463\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/gemv.cpp",
    "content": "#include \"gemv_common.h\"\n\nEIGEN_DONT_INLINE\nvoid gemv(const Mat &A, const Vec &B, Vec &C)\n{\n  C.noalias() += A * B;\n}\n\nint main(int argc, char **argv)\n{\n  return main_gemv(argc, argv, gemv);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/gemv_common.h",
    "content": "#include <iostream>\n#include <fstream>\n#include <vector>\n#include <string>\n#include <functional>\n#include \"eigen_src/Eigen/Core\"\n#include \"../BenchTimer.h\"\nusing namespace Eigen;\n\n#ifndef SCALAR\n#error SCALAR must be defined\n#endif\n\ntypedef SCALAR Scalar;\n\ntypedef Matrix<Scalar,Dynamic,Dynamic> Mat;\ntypedef Matrix<Scalar,Dynamic,1>       Vec;\n\ntemplate<typename Func>\nEIGEN_DONT_INLINE\ndouble bench(long m, long n, Func &f)\n{\n  Mat A(m,n);\n  Vec B(n);\n  Vec C(m);\n  A.setRandom();\n  B.setRandom();\n  C.setRandom();\n\n  BenchTimer t;\n\n  double up = 1e8/sizeof(Scalar);\n  double tm0 = 4, tm1 = 10;\n  if(NumTraits<Scalar>::IsComplex)\n  {\n    up /= 4;\n    tm0 = 2;\n    tm1 = 4;\n  }\n\n  double flops = 2. * m * n;\n  long rep = std::max(1., std::min(100., up/flops) );\n  long tries = std::max(tm0, std::min(tm1, up/flops) );\n\n  BENCH(t, tries, rep, f(A,B,C));\n\n  return 1e-9 * rep * flops / t.best();\n}\n\ntemplate<typename Func>\nint main_gemv(int argc, char **argv, Func& f)\n{\n  std::vector<double> results;\n\n  std::string filename = std::string(\"gemv_settings.txt\");\n  if(argc>1)\n    filename = std::string(argv[1]);\n  std::ifstream settings(filename);\n  long m, n;\n  while(settings >> m >> n)\n  {\n    //std::cerr << \"  Testing \" << m << \" \" << n << std::endl;\n    results.push_back( bench(m, n, f) );\n  }\n\n  std::cout << RowVectorXd::Map(results.data(), results.size());\n\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/gemv_settings.txt",
    "content": "8 8\n9 9\n24 24\n239 239\n240 240\n2400 24\n24 2400\n24 240\n2400 2400\n4800 23\n23 4800\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/gemv_square_settings.txt",
    "content": "8 8\n9 9\n12 12\n15 15\n16 16\n24 24\n53 53\n74 74\n102 102\n239 239\n240 240\n2400 2400\n2463 2463\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/gemvt.cpp",
    "content": "#include \"gemv_common.h\"\n\nEIGEN_DONT_INLINE\nvoid gemv(const Mat &A, Vec &B, const Vec &C)\n{\n  B.noalias() += A.transpose() * C;\n}\n\nint main(int argc, char **argv)\n{\n  return main_gemv(argc, argv, gemv);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/lazy_gemm.cpp",
    "content": "#include <iostream>\n#include <fstream>\n#include <vector>\n#include <Eigen/Core>\n#include \"../../BenchTimer.h\"\nusing namespace Eigen;\n\n#ifndef SCALAR\n#error SCALAR must be defined\n#endif\n\ntypedef SCALAR Scalar;\n\ntemplate<typename MatA, typename MatB, typename MatC>\nEIGEN_DONT_INLINE\nvoid lazy_gemm(const MatA &A, const MatB &B, MatC &C)\n{\n//   escape((void*)A.data());\n//   escape((void*)B.data());\n  C.noalias() += A.lazyProduct(B);\n//   escape((void*)C.data());\n}\n\ntemplate<int m, int n, int k, int TA>\nEIGEN_DONT_INLINE\ndouble bench()\n{\n  typedef Matrix<Scalar,m,k,TA> MatA;\n  typedef Matrix<Scalar,k,n> MatB;\n  typedef Matrix<Scalar,m,n> MatC;\n\n  MatA A(m,k);\n  MatB B(k,n);\n  MatC C(m,n);\n  A.setRandom();\n  B.setRandom();\n  C.setZero();\n\n  BenchTimer t;\n\n  double up = 1e7*4/sizeof(Scalar);\n  double tm0 = 10, tm1 = 20;\n\n  double flops = 2. * m * n * k;\n  long rep = std::max(10., std::min(10000., up/flops) );\n  long tries = std::max(tm0, std::min(tm1, up/flops) );\n\n  BENCH(t, tries, rep, lazy_gemm(A,B,C));\n\n  return 1e-9 * rep * flops / t.best();\n}\n\ntemplate<int m, int n, int k>\ndouble bench_t(int t)\n{\n  if(t)\n    return bench<m,n,k,RowMajor>();\n  else\n    return bench<m,n,k,0>();\n}\n\nEIGEN_DONT_INLINE\ndouble bench_mnk(int m, int n, int k, int t)\n{\n  int id = m*10000 + n*100 + k;\n  switch(id) {\n    case  10101 : return bench_t< 1, 1, 1>(t); break;\n    case  20202 : return bench_t< 2, 2, 2>(t); break;\n    case  30303 : return bench_t< 3, 3, 3>(t); break;\n    case  40404 : return bench_t< 4, 4, 4>(t); break;\n    case  50505 : return bench_t< 5, 5, 5>(t); break;\n    case  60606 : return bench_t< 6, 6, 6>(t); break;\n    case  70707 : return bench_t< 7, 7, 7>(t); break;\n    case  80808 : return bench_t< 8, 8, 8>(t); break;\n    case  90909 : return bench_t< 9, 9, 9>(t); break;\n    case 101010 : return bench_t<10,10,10>(t); break;\n    case 111111 : return bench_t<11,11,11>(t); break;\n    case 121212 : return bench_t<12,12,12>(t); break;\n  }\n  return 0;\n}\n\nint main(int argc, char **argv)\n{\n  std::vector<double> results;\n  \n  std::string filename = std::string(\"lazy_gemm_settings.txt\");\n  if(argc>1)\n    filename = std::string(argv[1]);\n  std::ifstream settings(filename);\n  long m, n, k, t;\n  while(settings >> m >> n >> k >> t)\n  {\n    //std::cerr << \"  Testing \" << m << \" \" << n << \" \" << k << std::endl;\n    results.push_back( bench_mnk(m, n, k, t) );\n  }\n  \n  std::cout << RowVectorXd::Map(results.data(), results.size());\n  \n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/lazy_gemm_settings.txt",
    "content": "1 1 1 0\n2 2 2 0\n3 3 3 0\n4 4 4 0\n4 4 4 1\n5 5 5 0\n6 6 6 0\n7 7 7 0\n7 7 7 1\n8 8 8 0\n9 9 9 0\n10 10 10 0\n11 11 11 0\n12 12 12 0\n12 12 12 1\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/llt.cpp",
    "content": "#include \"gemm_common.h\"\n#include <Eigen/Cholesky>\n\nEIGEN_DONT_INLINE\nvoid llt(const Mat &A, const Mat &B, Mat &C)\n{\n  C = A;\n  C.diagonal().array() += 1000;\n  Eigen::internal::llt_inplace<Mat::Scalar, Lower>::blocked(C);\n}\n\nint main(int argc, char **argv)\n{\n  return main_gemm(argc, argv, llt);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/make_plot.sh",
    "content": "#!/bin/bash\n\n# base name of the bench\n# it reads $1.out\n# and generates $1.pdf\nWHAT=$1\nbench=$2\nsettings_file=$3\n\nheader=\"rev \"\nwhile read line\ndo\n  if [ ! -z '$line' ]; then\n    header=\"$header  \\\"$line\\\"\"\n  fi\ndone < $settings_file\n\necho $header > $WHAT.out.header\ncat $WHAT.out >> $WHAT.out.header\n\n\necho \"set title '$WHAT'\" > $WHAT.gnuplot\necho \"set key autotitle columnhead outside \" >> $WHAT.gnuplot\necho \"set xtics rotate 1\" >> $WHAT.gnuplot\n\necho \"set term pdf color rounded enhanced fontscale 0.35 size 7in,5in\" >> $WHAT.gnuplot\necho set output \"'\"$WHAT.pdf\"'\" >> $WHAT.gnuplot\n\ncol=`cat $settings_file | wc -l`\necho \"plot for [col=2:$col+1] '$WHAT.out.header' using 0:col:xticlabels(1) with lines\" >> $WHAT.gnuplot\necho \" \" >>  $WHAT.gnuplot\n\ngnuplot -persist < $WHAT.gnuplot\n\n# generate a png file (thumbnail)\nconvert -colors 256 -background white -density 300 -resize 300  -quality 0 $WHAT.pdf -background white -flatten $WHAT.png\n\n# clean\nrm $WHAT.out.header $WHAT.gnuplot\n\n\n# generate html/svg graph\n\necho \" \" > $WHAT.html\ncat resources/chart_header.html > $WHAT.html\necho 'var customSettings = {\"TITLE\":\"\",\"SUBTITLE\":\"\",\"XLABEL\":\"\",\"YLABEL\":\"\"};' >> $WHAT.html\n#  'data' is an array of datasets (i.e. curves), each of which is an object of the form\n#  {\n#    key: <name of the curve>,\n#    color: <optional color of the curve>,\n#    values: [{\n#        r: <revision number>,\n#        v: <GFlops>\n#    }]\n#  }\necho 'var data = [' >> $WHAT.html\n\ncol=2\nwhile read line\ndo\n  if [ ! -z '$line' ]; then\n    header=\"$header  \\\"$line\\\"\"\n    echo '{\"key\":\"'$line'\",\"values\":[' >> $WHAT.html\n    i=0\n    while read line2\n    do\n      if [ ! -z \"$line2\" ]; then\n        val=`echo $line2 | cut -s -f $col -d ' '`\n        if [ -n \"$val\" ]; then # skip build failures\n          echo '{\"r\":'$i',\"v\":'$val'},' >> $WHAT.html\n        fi\n      fi\n      ((i++))\n    done < $WHAT.out\n    echo ']},'  >> $WHAT.html\n  fi\n  ((col++))\ndone < $settings_file\necho '];'  >> $WHAT.html\n\necho 'var changesets = [' >> $WHAT.html\nwhile read line2\ndo\n  if [ ! -z '$line2' ]; then\n    echo '\"'`echo $line2 | cut -f 1 -d ' '`'\",' >> $WHAT.html\n  fi\ndone < $WHAT.out\necho '];'  >> $WHAT.html\n\necho 'var changesets_details = [' >> $WHAT.html\nwhile read line2\ndo\n  if [ ! -z '$line2' ]; then\n    num=`echo \"$line2\" | cut -f 1 -d ' '`\n    comment=`grep \":$num\" changesets.txt | cut -f 2 -d '#'`\n    echo '\"'\"$comment\"'\",' >> $WHAT.html\n  fi\ndone < $WHAT.out\necho '];'  >> $WHAT.html\n\necho 'var changesets_count = [' >> $WHAT.html\ni=0\nwhile read line2\ndo\n  if [ ! -z '$line2' ]; then\n    echo $i ',' >> $WHAT.html\n  fi\n  ((i++))\ndone < $WHAT.out\necho '];'  >> $WHAT.html\n\ncat resources/chart_footer.html >> $WHAT.html\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/resources/chart_footer.html",
    "content": "      /* setup the chart and its options */                                                                                \n      var chart = nv.models.lineChart()                                                                                    \n                    .color(d3.scale.category10().range())                                                                  \n                    .margin({left: 75, bottom: 100})                                                                        \n                    .forceX([0]).forceY([0]);                                                                              \n                                                                                                                           \n      chart.x(function(datum){ return datum.r; })                                                                          \n           .xAxis.options({                                                                                                \n             axisLabel: customSettings.XLABEL || 'Changeset',\n             tickFormat: d3.format('.0f')                                                                                  \n           });\n      chart.xAxis\n        .tickValues(changesets_count)\n        .tickFormat(function(d){return changesets[d]})\n        .rotateLabels(-90);\n                                                                                                                                                                                                       \n      chart.y(function(datum){ return datum.v; })                                                    \n            .yAxis.options({                                                                                              \n              axisLabel: customSettings.YLABEL || 'GFlops'/*,\n              tickFormat: function(val){ return d3.format('.0f')(val) + ' GFlops'; }*/\n            });\n      \n      chart.tooltip.headerFormatter(function(d) { return changesets[d]\n        + ' <p style=\"font-weight:normal;text-align: left;\">'\n        + changesets_details[d] + \"</p>\"; });\n\n      //chart.useInteractiveGuideline(true);\n      d3.select('#chart').datum(data).call(chart);                                                                         \n      var plot = d3.select('#chart > g');                                                                                  \n                                                                                                                           \n      /* setup the title */                                                                                                \n      plot.append('text')                                                                                                  \n          .style('font-size', '24px')                                                                                      \n          .attr('text-anchor', 'middle').attr('x', '50%').attr('y', '20px')                                                \n          .text(customSettings.TITLE || '');                                                                                                                   \n                                                                                                                           \n      /* ensure the chart is responsive */                                                                                 \n      nv.utils.windowResize(chart.update);                                                                                 \n    </script>                                                                                                              \n  </body>                                                                                                                  \n</html>  \n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/resources/chart_header.html",
    "content": "\n<!DOCTYPE html>                                                                                                            \n<html>                                                                                                                     \n  <head>                                                                                                                   \n    <meta charset='utf-8'>                                                                                                 \n    <style>.nvd3 .nv-axis line,.nvd3 .nv-axis path{fill:none;shape-rendering:crispEdges}.nv-brush .extent,.nvd3 .background path,.nvd3 .nv-axis line,.nvd3 .nv-axis path{shape-rendering:crispEdges}.nv-distx,.nv-disty,.nv-noninteractive,.nvd3 .nv-axis,.nvd3.nv-pie .nv-label,.nvd3.nv-sparklineplus g.nv-hoverValue{pointer-events:none}.nvtooltip,svg.nvd3-svg{display:block;-webkit-touch-callout:none;-khtml-user-select:none}.nvd3 .nv-axis{opacity:1}.nvd3 .nv-axis.nv-disabled,.nvd3 .nv-controlsWrap .nv-legend .nv-check-box .nv-check{opacity:0}.nvd3 .nv-axis path{stroke:#000;stroke-opacity:.75}.nvd3 .nv-axis path.domain{stroke-opacity:.75}.nvd3 .nv-axis.nv-x path.domain{stroke-opacity:0}.nvd3 .nv-axis line{stroke:#e5e5e5}.nvd3 .nv-axis .zero line, .nvd3 .nv-axis line.zero{stroke-opacity:.75}.nvd3 .nv-axis .nv-axisMaxMin text{font-weight:700}.nvd3 .x .nv-axis .nv-axisMaxMin text,.nvd3 .x2 .nv-axis .nv-axisMaxMin text,.nvd3 .x3 .nv-axis .nv-axisMaxMin text{text-anchor:middle}.nvd3 .nv-bars rect{fill-opacity:.75;transition:fill-opacity 250ms linear;-moz-transition:fill-opacity 250ms linear;-webkit-transition:fill-opacity 250ms linear}.nvd3 .nv-bars rect.hover{fill-opacity:1}.nvd3 .nv-bars .hover rect{fill:#add8e6}.nvd3 .nv-bars text{fill:transparent}.nvd3 .nv-bars .hover text{fill:rgba(0,0,0,1)}.nvd3 .nv-discretebar .nv-groups rect,.nvd3 .nv-multibar .nv-groups rect,.nvd3 .nv-multibarHorizontal .nv-groups rect{stroke-opacity:0;transition:fill-opacity 250ms linear;-moz-transition:fill-opacity 250ms linear;-webkit-transition:fill-opacity 250ms linear}.nvd3 .nv-candlestickBar .nv-ticks rect:hover,.nvd3 .nv-discretebar .nv-groups rect:hover,.nvd3 .nv-multibar .nv-groups rect:hover,.nvd3 .nv-multibarHorizontal .nv-groups rect:hover{fill-opacity:1}.nvd3 .nv-discretebar .nv-groups text,.nvd3 .nv-multibarHorizontal .nv-groups text{font-weight:700;fill:rgba(0,0,0,1);stroke:transparent}.nvd3 .nv-boxplot circle{fill-opacity:.5}.nvd3 .nv-boxplot circle:hover,.nvd3 .nv-boxplot rect:hover{fill-opacity:1}.nvd3 line.nv-boxplot-median{stroke:#000}.nv-boxplot-tick:hover{stroke-width:2.5px}.nvd3.nv-bullet{font:10px sans-serif}.nvd3.nv-bullet .nv-measure{fill-opacity:.8}.nvd3.nv-bullet .nv-measure:hover{fill-opacity:1}.nvd3.nv-bullet .nv-marker{stroke:#000;stroke-width:2px}.nvd3.nv-bullet .nv-markerTriangle{stroke:#000;fill:#fff;stroke-width:1.5px}.nvd3.nv-bullet .nv-markerLine{stroke:#000;stroke-width:1.5px}.nvd3.nv-bullet .nv-tick line{stroke:#666;stroke-width:.5px}.nvd3.nv-bullet .nv-range.nv-s0{fill:#eee}.nvd3.nv-bullet .nv-range.nv-s1{fill:#ddd}.nvd3.nv-bullet .nv-range.nv-s2{fill:#ccc}.nvd3.nv-bullet .nv-title{font-size:14px;font-weight:700}.nvd3.nv-bullet .nv-subtitle{fill:#999}.nvd3.nv-bullet .nv-range{fill:#bababa;fill-opacity:.4}.nvd3.nv-bullet .nv-range:hover{fill-opacity:.7}.nvd3.nv-candlestickBar .nv-ticks .nv-tick{stroke-width:1px}.nvd3.nv-candlestickBar .nv-ticks .nv-tick.hover{stroke-width:2px}.nvd3.nv-candlestickBar .nv-ticks .nv-tick.positive rect{stroke:#2ca02c;fill:#2ca02c}.nvd3.nv-candlestickBar .nv-ticks .nv-tick.negative rect{stroke:#d62728;fill:#d62728}.with-transitions .nv-candlestickBar .nv-ticks .nv-tick{transition:stroke-width 250ms linear,stroke-opacity 250ms linear;-moz-transition:stroke-width 250ms linear,stroke-opacity 250ms linear;-webkit-transition:stroke-width 250ms linear,stroke-opacity 250ms linear}.nvd3.nv-candlestickBar .nv-ticks line{stroke:#333}.nv-force-node{stroke:#fff;stroke-width:1.5px}.nv-force-link{stroke:#999;stroke-opacity:.6}.nv-force-node text{stroke-width:0}.nvd3 .nv-check-box .nv-box{fill-opacity:0;stroke-width:2}.nvd3 .nv-check-box .nv-check{fill-opacity:0;stroke-width:4}.nvd3 .nv-series.nv-disabled .nv-check-box .nv-check{fill-opacity:0;stroke-opacity:0}.nvd3.nv-linePlusBar .nv-bar rect{fill-opacity:.75}.nvd3.nv-linePlusBar .nv-bar rect:hover{fill-opacity:1}.nvd3 .nv-groups path.nv-line{fill:none}.nvd3 .nv-groups path.nv-area{stroke:none}.nvd3.nv-line .nvd3.nv-scatter .nv-groups .nv-point{fill-opacity:0;stroke-opacity:0}.nvd3.nv-scatter.nv-single-point .nv-groups .nv-point{fill-opacity:.5!important;stroke-opacity:.5!important}.with-transitions .nvd3 .nv-groups .nv-point{transition:stroke-width 250ms linear,stroke-opacity 250ms linear;-moz-transition:stroke-width 250ms linear,stroke-opacity 250ms linear;-webkit-transition:stroke-width 250ms linear,stroke-opacity 250ms linear}.nvd3 .nv-groups .nv-point.hover,.nvd3.nv-scatter .nv-groups .nv-point.hover{stroke-width:7px;fill-opacity:.95!important;stroke-opacity:.95!important}.nvd3 .nv-point-paths path{stroke:#aaa;stroke-opacity:0;fill:#eee;fill-opacity:0}.nvd3 .nv-indexLine{cursor:ew-resize}svg.nvd3-svg{-webkit-user-select:none;-ms-user-select:none;-moz-user-select:none;user-select:none;width:100%;height:100%}.nvtooltip.with-3d-shadow,.with-3d-shadow .nvtooltip{-moz-box-shadow:0 5px 10px rgba(0,0,0,.2);-webkit-box-shadow:0 5px 10px rgba(0,0,0,.2);box-shadow:0 5px 10px rgba(0,0,0,.2);-webkit-border-radius:5px;-moz-border-radius:5px;border-radius:5px}.nvd3 text{font:400 12px Arial}.nvd3 .title{font:700 14px Arial}.nvd3 .nv-background{fill:#fff;fill-opacity:0}.nvd3.nv-noData{font-size:18px;font-weight:700}.nv-brush .extent{fill-opacity:.125}.nv-brush .resize path{fill:#eee;stroke:#666}.nvd3 .nv-legend .nv-series{cursor:pointer}.nvd3 .nv-legend .nv-disabled circle{fill-opacity:0}.nvd3 .nv-brush .extent{fill-opacity:0!important}.nvd3 .nv-brushBackground rect{stroke:#000;stroke-width:.4;fill:#fff;fill-opacity:.7}@media print{.nvd3 text{stroke-width:0;fill-opacity:1}}.nvd3.nv-ohlcBar .nv-ticks .nv-tick{stroke-width:1px}.nvd3.nv-ohlcBar .nv-ticks .nv-tick.hover{stroke-width:2px}.nvd3.nv-ohlcBar .nv-ticks .nv-tick.positive{stroke:#2ca02c}.nvd3.nv-ohlcBar .nv-ticks .nv-tick.negative{stroke:#d62728}.nvd3 .background path{fill:none;stroke:#EEE;stroke-opacity:.4}.nvd3 .foreground path{fill:none;stroke-opacity:.7}.nvd3 .nv-parallelCoordinates-brush .extent{fill:#fff;fill-opacity:.6;stroke:gray;shape-rendering:crispEdges}.nvd3 .nv-parallelCoordinates .hover{fill-opacity:1;stroke-width:3px}.nvd3 .missingValuesline line{fill:none;stroke:#000;stroke-width:1;stroke-opacity:1;stroke-dasharray:5,5}.nvd3.nv-pie .nv-pie-title{font-size:24px;fill:rgba(19,196,249,.59)}.nvd3.nv-pie .nv-slice text{stroke:#000;stroke-width:0}.nvd3.nv-pie path{transition:fill-opacity 250ms linear,stroke-width 250ms linear,stroke-opacity 250ms linear;-moz-transition:fill-opacity 250ms linear,stroke-width 250ms linear,stroke-opacity 250ms linear;-webkit-transition:fill-opacity 250ms linear,stroke-width 250ms linear,stroke-opacity 250ms linear;stroke:#fff;stroke-width:1px;stroke-opacity:1;fill-opacity:.7}.nvd3.nv-pie .hover path{fill-opacity:1}.nvd3.nv-pie .nv-label rect{fill-opacity:0;stroke-opacity:0}.nvd3 .nv-groups .nv-point.hover{stroke-width:20px;stroke-opacity:.5}.nvd3 .nv-scatter .nv-point.hover{fill-opacity:1}.nvd3.nv-sparkline path{fill:none}.nvd3.nv-sparklineplus .nv-hoverValue line{stroke:#333;stroke-width:1.5px}.nvd3.nv-sparklineplus,.nvd3.nv-sparklineplus g{pointer-events:all}.nvd3 .nv-interactiveGuideLine,.nvtooltip{pointer-events:none}.nvd3 .nv-hoverArea{fill-opacity:0;stroke-opacity:0}.nvd3.nv-sparklineplus .nv-xValue,.nvd3.nv-sparklineplus .nv-yValue{stroke-width:0;font-size:.9em;font-weight:400}.nvd3.nv-sparklineplus .nv-yValue{stroke:#f66}.nvd3.nv-sparklineplus .nv-maxValue{stroke:#2ca02c;fill:#2ca02c}.nvd3.nv-sparklineplus .nv-minValue{stroke:#d62728;fill:#d62728}.nvd3.nv-sparklineplus .nv-currentValue{font-weight:700;font-size:1.1em}.nvtooltip h3,.nvtooltip table td.key{font-weight:400}.nvd3.nv-stackedarea path.nv-area{fill-opacity:.7;stroke-opacity:0;transition:fill-opacity 250ms linear,stroke-opacity 250ms linear;-moz-transition:fill-opacity 250ms linear,stroke-opacity 250ms linear;-webkit-transition:fill-opacity 250ms linear,stroke-opacity 250ms linear}.nvd3.nv-stackedarea path.nv-area.hover{fill-opacity:.9}.nvd3.nv-stackedarea .nv-groups .nv-point{stroke-opacity:0;fill-opacity:0}.nvtooltip{position:absolute;color:rgba(0,0,0,1);padding:1px;z-index:10000;font-family:Arial;font-size:13px;text-align:left;white-space:nowrap;-webkit-user-select:none;-moz-user-select:none;-ms-user-select:none;user-select:none;background:rgba(255,255,255,.8);border:1px solid rgba(0,0,0,.5);border-radius:4px}.nvtooltip h3,.nvtooltip p{margin:0;text-align:center}.nvtooltip.with-transitions,.with-transitions .nvtooltip{transition:opacity 50ms linear;-moz-transition:opacity 50ms linear;-webkit-transition:opacity 50ms linear;transition-delay:200ms;-moz-transition-delay:200ms;-webkit-transition-delay:200ms}.nvtooltip.x-nvtooltip,.nvtooltip.y-nvtooltip{padding:8px}.nvtooltip h3{padding:4px 14px;line-height:18px;background-color:rgba(247,247,247,.75);color:rgba(0,0,0,1);border-bottom:1px solid #ebebeb;-webkit-border-radius:5px 5px 0 0;-moz-border-radius:5px 5px 0 0;border-radius:5px 5px 0 0}.nvtooltip p{padding:5px 14px}.nvtooltip span{display:inline-block;margin:2px 0}.nvtooltip table{margin:6px;border-spacing:0}.nvtooltip table td{padding:2px 9px 2px 0;vertical-align:middle}.nvtooltip table td.key.total{font-weight:700}.nvtooltip table td.value{text-align:right;font-weight:700}.nvtooltip table td.percent{color:#a9a9a9}.nvtooltip table tr.highlight td{padding:1px 9px 1px 0;border-bottom-style:solid;border-bottom-width:1px;border-top-style:solid;border-top-width:1px}.nvtooltip table td.legend-color-guide div{vertical-align:middle;width:12px;height:12px;border:1px solid #999}.nvtooltip .footer{padding:3px;text-align:center}.nvtooltip-pending-removal{pointer-events:none;display:none}.nvd3 line.nv-guideline{stroke:#ccc}</style>                                                             \n    <style>                                                                                                                \n      * {                                                                                                                  \n        box-sizing: border-box;                                                                                            \n      }                                                                                                                    \n      html, body {                                                                                                         \n        position: relative;                                                                                                \n        height: 100%;                                                                                                      \n        width: 100%;                                                                                                       \n        border: 0;                                                                                                         \n        margin: 0;                                                                                                         \n        padding: 0;                                                                                                        \n        font-size: 0;                                                                                                      \n      }                                                                                                                    \n      svg g {                                                                                                              \n        clip-path: none;                                                                                                   \n      }                                                                                                                    \n      svg text {                                                                                                           \n        fill: #333;                                                                                                        \n      }                                                                                                                    \n      .nv-axislabel {                                                                                                      \n        font-size: 16px !important;                                                                                        \n      }                                                                                                                    \n      .control {                                                                                                           \n        cursor: pointer;                                                                                                   \n        visibility: hidden;                                                                                                \n        pointer-events: visible;                                                                                           \n      }                                                                                                                    \n      @media (min-width: 768px) {                                                                                          \n        .control {                                                                                                         \n          visibility: visible;                                                                                             \n        }                                                                                                                  \n      }                                                                                                                    \n    </style>                                                                                                               \n    <script src=\"s1.js\"></script>                                                              \n    <script src=\"s2.js\"></script>                                                            \n  </head>                                                                                                                  \n  <body>                                                                                                                   \n    <svg id='chart'></svg> \n    <script type='text/javascript'>\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/resources/footer.html",
    "content": "</table>\n</body>\n</html>\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/resources/header.html",
    "content": "<!DOCTYPE html PUBLIC \"-//W3C//DTD XHTML 1.0 Transitional//EN\" \"http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd\">\n<html xmlns=\"http://www.w3.org/1999/xhtml\">\n<head>\n<meta http-equiv=\"Content-Type\" content=\"text/html; charset=utf-8\" />\n<title>Eigen performance monitoring</title>\n<style type=\"text/css\">\n\nbody\n{\n background:#fff;\n}\nth {\n\n}\nimg\n{\n width:auto;\n box-shadow:0px 0px 20px #cecece;\n margin: 20px 20px  20px  20px;\n  -moz-transform: scale(1);\n -moz-transition-duration: 0.4s;\n -webkit-transition-duration: 0.4s;\n -webkit-transform: scale(1);\n\n -ms-transform: scale(1);\n -ms-transition-duration: 0.4s;\n}\nimg:hover\n{\nbox-shadow: 5px 5px 20px #dcdcdc;\n -moz-transform: scale(1.1);\n -moz-transition-duration: 0.4s;\n -webkit-transition-duration: 0.4s;\n -webkit-transform: scale(1.1);\n\n -ms-transform: scale(1.1);\n -ms-transition-duration: 0.4s;\n\n}\n</style>\n</head>\n<body>\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/resources/s1.js",
    "content": "!function(){function n(n){return n&&(n.ownerDocument||n.document||n).documentElement}function t(n){return n&&(n.ownerDocument&&n.ownerDocument.defaultView||n.document&&n||n.defaultView)}function e(n,t){return t>n?-1:n>t?1:n>=t?0:NaN}function r(n){return null===n?NaN:+n}function i(n){return!isNaN(n)}function u(n){return{left:function(t,e,r,i){for(arguments.length<3&&(r=0),arguments.length<4&&(i=t.length);i>r;){var u=r+i>>>1;n(t[u],e)<0?r=u+1:i=u}return r},right:function(t,e,r,i){for(arguments.length<3&&(r=0),arguments.length<4&&(i=t.length);i>r;){var u=r+i>>>1;n(t[u],e)>0?i=u:r=u+1}return r}}}function o(n){return n.length}function a(n){for(var t=1;n*t%1;)t*=10;return t}function l(n,t){for(var e in t)Object.defineProperty(n.prototype,e,{value:t[e],enumerable:!1})}function c(){this._=Object.create(null)}function f(n){return(n+=\"\")===bo||n[0]===_o?_o+n:n}function s(n){return(n+=\"\")[0]===_o?n.slice(1):n}function h(n){return f(n)in this._}function p(n){return(n=f(n))in this._&&delete this._[n]}function g(){var n=[];for(var t in this._)n.push(s(t));return n}function v(){var n=0;for(var t in this._)++n;return n}function d(){for(var n in this._)return!1;return!0}function y(){this._=Object.create(null)}function m(n){return n}function M(n,t,e){return function(){var r=e.apply(t,arguments);return r===t?n:r}}function x(n,t){if(t in n)return t;t=t.charAt(0).toUpperCase()+t.slice(1);for(var e=0,r=wo.length;r>e;++e){var i=wo[e]+t;if(i in n)return i}}function b(){}function _(){}function w(n){function t(){for(var t,r=e,i=-1,u=r.length;++i<u;)(t=r[i].on)&&t.apply(this,arguments);return n}var e=[],r=new c;return t.on=function(t,i){var u,o=r.get(t);return arguments.length<2?o&&o.on:(o&&(o.on=null,e=e.slice(0,u=e.indexOf(o)).concat(e.slice(u+1)),r.remove(t)),i&&e.push(r.set(t,{on:i})),n)},t}function S(){ao.event.preventDefault()}function k(){for(var n,t=ao.event;n=t.sourceEvent;)t=n;return t}function N(n){for(var t=new _,e=0,r=arguments.length;++e<r;)t[arguments[e]]=w(t);return t.of=function(e,r){return function(i){try{var u=i.sourceEvent=ao.event;i.target=n,ao.event=i,t[i.type].apply(e,r)}finally{ao.event=u}}},t}function E(n){return ko(n,Co),n}function A(n){return\"function\"==typeof n?n:function(){return No(n,this)}}function C(n){return\"function\"==typeof n?n:function(){return Eo(n,this)}}function z(n,t){function e(){this.removeAttribute(n)}function r(){this.removeAttributeNS(n.space,n.local)}function i(){this.setAttribute(n,t)}function u(){this.setAttributeNS(n.space,n.local,t)}function o(){var e=t.apply(this,arguments);null==e?this.removeAttribute(n):this.setAttribute(n,e)}function a(){var e=t.apply(this,arguments);null==e?this.removeAttributeNS(n.space,n.local):this.setAttributeNS(n.space,n.local,e)}return n=ao.ns.qualify(n),null==t?n.local?r:e:\"function\"==typeof t?n.local?a:o:n.local?u:i}function L(n){return n.trim().replace(/\\s+/g,\" \")}function q(n){return new RegExp(\"(?:^|\\\\s+)\"+ao.requote(n)+\"(?:\\\\s+|$)\",\"g\")}function T(n){return(n+\"\").trim().split(/^|\\s+/)}function R(n,t){function e(){for(var e=-1;++e<i;)n[e](this,t)}function r(){for(var e=-1,r=t.apply(this,arguments);++e<i;)n[e](this,r)}n=T(n).map(D);var i=n.length;return\"function\"==typeof t?r:e}function D(n){var t=q(n);return function(e,r){if(i=e.classList)return r?i.add(n):i.remove(n);var i=e.getAttribute(\"class\")||\"\";r?(t.lastIndex=0,t.test(i)||e.setAttribute(\"class\",L(i+\" \"+n))):e.setAttribute(\"class\",L(i.replace(t,\" \")))}}function P(n,t,e){function r(){this.style.removeProperty(n)}function i(){this.style.setProperty(n,t,e)}function u(){var r=t.apply(this,arguments);null==r?this.style.removeProperty(n):this.style.setProperty(n,r,e)}return null==t?r:\"function\"==typeof t?u:i}function U(n,t){function e(){delete this[n]}function r(){this[n]=t}function i(){var e=t.apply(this,arguments);null==e?delete this[n]:this[n]=e}return null==t?e:\"function\"==typeof t?i:r}function j(n){function t(){var t=this.ownerDocument,e=this.namespaceURI;return e===zo&&t.documentElement.namespaceURI===zo?t.createElement(n):t.createElementNS(e,n)}function e(){return this.ownerDocument.createElementNS(n.space,n.local)}return\"function\"==typeof n?n:(n=ao.ns.qualify(n)).local?e:t}function F(){var n=this.parentNode;n&&n.removeChild(this)}function H(n){return{__data__:n}}function O(n){return function(){return Ao(this,n)}}function I(n){return arguments.length||(n=e),function(t,e){return t&&e?n(t.__data__,e.__data__):!t-!e}}function Y(n,t){for(var e=0,r=n.length;r>e;e++)for(var i,u=n[e],o=0,a=u.length;a>o;o++)(i=u[o])&&t(i,o,e);return n}function Z(n){return ko(n,qo),n}function V(n){var t,e;return function(r,i,u){var o,a=n[u].update,l=a.length;for(u!=e&&(e=u,t=0),i>=t&&(t=i+1);!(o=a[t])&&++t<l;);return o}}function X(n,t,e){function r(){var t=this[o];t&&(this.removeEventListener(n,t,t.$),delete this[o])}function i(){var i=l(t,co(arguments));r.call(this),this.addEventListener(n,this[o]=i,i.$=e),i._=t}function u(){var t,e=new RegExp(\"^__on([^.]+)\"+ao.requote(n)+\"$\");for(var r in this)if(t=r.match(e)){var i=this[r];this.removeEventListener(t[1],i,i.$),delete this[r]}}var o=\"__on\"+n,a=n.indexOf(\".\"),l=$;a>0&&(n=n.slice(0,a));var c=To.get(n);return c&&(n=c,l=B),a?t?i:r:t?b:u}function $(n,t){return function(e){var r=ao.event;ao.event=e,t[0]=this.__data__;try{n.apply(this,t)}finally{ao.event=r}}}function B(n,t){var e=$(n,t);return function(n){var t=this,r=n.relatedTarget;r&&(r===t||8&r.compareDocumentPosition(t))||e.call(t,n)}}function W(e){var r=\".dragsuppress-\"+ ++Do,i=\"click\"+r,u=ao.select(t(e)).on(\"touchmove\"+r,S).on(\"dragstart\"+r,S).on(\"selectstart\"+r,S);if(null==Ro&&(Ro=\"onselectstart\"in e?!1:x(e.style,\"userSelect\")),Ro){var o=n(e).style,a=o[Ro];o[Ro]=\"none\"}return function(n){if(u.on(r,null),Ro&&(o[Ro]=a),n){var t=function(){u.on(i,null)};u.on(i,function(){S(),t()},!0),setTimeout(t,0)}}}function J(n,e){e.changedTouches&&(e=e.changedTouches[0]);var r=n.ownerSVGElement||n;if(r.createSVGPoint){var i=r.createSVGPoint();if(0>Po){var u=t(n);if(u.scrollX||u.scrollY){r=ao.select(\"body\").append(\"svg\").style({position:\"absolute\",top:0,left:0,margin:0,padding:0,border:\"none\"},\"important\");var o=r[0][0].getScreenCTM();Po=!(o.f||o.e),r.remove()}}return Po?(i.x=e.pageX,i.y=e.pageY):(i.x=e.clientX,i.y=e.clientY),i=i.matrixTransform(n.getScreenCTM().inverse()),[i.x,i.y]}var a=n.getBoundingClientRect();return[e.clientX-a.left-n.clientLeft,e.clientY-a.top-n.clientTop]}function G(){return ao.event.changedTouches[0].identifier}function K(n){return n>0?1:0>n?-1:0}function Q(n,t,e){return(t[0]-n[0])*(e[1]-n[1])-(t[1]-n[1])*(e[0]-n[0])}function nn(n){return n>1?0:-1>n?Fo:Math.acos(n)}function tn(n){return n>1?Io:-1>n?-Io:Math.asin(n)}function en(n){return((n=Math.exp(n))-1/n)/2}function rn(n){return((n=Math.exp(n))+1/n)/2}function un(n){return((n=Math.exp(2*n))-1)/(n+1)}function on(n){return(n=Math.sin(n/2))*n}function an(){}function ln(n,t,e){return this instanceof ln?(this.h=+n,this.s=+t,void(this.l=+e)):arguments.length<2?n instanceof ln?new ln(n.h,n.s,n.l):_n(\"\"+n,wn,ln):new ln(n,t,e)}function cn(n,t,e){function r(n){return n>360?n-=360:0>n&&(n+=360),60>n?u+(o-u)*n/60:180>n?o:240>n?u+(o-u)*(240-n)/60:u}function i(n){return Math.round(255*r(n))}var u,o;return n=isNaN(n)?0:(n%=360)<0?n+360:n,t=isNaN(t)?0:0>t?0:t>1?1:t,e=0>e?0:e>1?1:e,o=.5>=e?e*(1+t):e+t-e*t,u=2*e-o,new mn(i(n+120),i(n),i(n-120))}function fn(n,t,e){return this instanceof fn?(this.h=+n,this.c=+t,void(this.l=+e)):arguments.length<2?n instanceof fn?new fn(n.h,n.c,n.l):n instanceof hn?gn(n.l,n.a,n.b):gn((n=Sn((n=ao.rgb(n)).r,n.g,n.b)).l,n.a,n.b):new fn(n,t,e)}function sn(n,t,e){return isNaN(n)&&(n=0),isNaN(t)&&(t=0),new hn(e,Math.cos(n*=Yo)*t,Math.sin(n)*t)}function hn(n,t,e){return this instanceof hn?(this.l=+n,this.a=+t,void(this.b=+e)):arguments.length<2?n instanceof hn?new hn(n.l,n.a,n.b):n instanceof fn?sn(n.h,n.c,n.l):Sn((n=mn(n)).r,n.g,n.b):new hn(n,t,e)}function pn(n,t,e){var r=(n+16)/116,i=r+t/500,u=r-e/200;return i=vn(i)*na,r=vn(r)*ta,u=vn(u)*ea,new mn(yn(3.2404542*i-1.5371385*r-.4985314*u),yn(-.969266*i+1.8760108*r+.041556*u),yn(.0556434*i-.2040259*r+1.0572252*u))}function gn(n,t,e){return n>0?new fn(Math.atan2(e,t)*Zo,Math.sqrt(t*t+e*e),n):new fn(NaN,NaN,n)}function vn(n){return n>.206893034?n*n*n:(n-4/29)/7.787037}function dn(n){return n>.008856?Math.pow(n,1/3):7.787037*n+4/29}function yn(n){return Math.round(255*(.00304>=n?12.92*n:1.055*Math.pow(n,1/2.4)-.055))}function mn(n,t,e){return this instanceof mn?(this.r=~~n,this.g=~~t,void(this.b=~~e)):arguments.length<2?n instanceof mn?new mn(n.r,n.g,n.b):_n(\"\"+n,mn,cn):new mn(n,t,e)}function Mn(n){return new mn(n>>16,n>>8&255,255&n)}function xn(n){return Mn(n)+\"\"}function bn(n){return 16>n?\"0\"+Math.max(0,n).toString(16):Math.min(255,n).toString(16)}function _n(n,t,e){var r,i,u,o=0,a=0,l=0;if(r=/([a-z]+)\\((.*)\\)/.exec(n=n.toLowerCase()))switch(i=r[2].split(\",\"),r[1]){case\"hsl\":return e(parseFloat(i[0]),parseFloat(i[1])/100,parseFloat(i[2])/100);case\"rgb\":return t(Nn(i[0]),Nn(i[1]),Nn(i[2]))}return(u=ua.get(n))?t(u.r,u.g,u.b):(null==n||\"#\"!==n.charAt(0)||isNaN(u=parseInt(n.slice(1),16))||(4===n.length?(o=(3840&u)>>4,o=o>>4|o,a=240&u,a=a>>4|a,l=15&u,l=l<<4|l):7===n.length&&(o=(16711680&u)>>16,a=(65280&u)>>8,l=255&u)),t(o,a,l))}function wn(n,t,e){var r,i,u=Math.min(n/=255,t/=255,e/=255),o=Math.max(n,t,e),a=o-u,l=(o+u)/2;return a?(i=.5>l?a/(o+u):a/(2-o-u),r=n==o?(t-e)/a+(e>t?6:0):t==o?(e-n)/a+2:(n-t)/a+4,r*=60):(r=NaN,i=l>0&&1>l?0:r),new ln(r,i,l)}function Sn(n,t,e){n=kn(n),t=kn(t),e=kn(e);var r=dn((.4124564*n+.3575761*t+.1804375*e)/na),i=dn((.2126729*n+.7151522*t+.072175*e)/ta),u=dn((.0193339*n+.119192*t+.9503041*e)/ea);return hn(116*i-16,500*(r-i),200*(i-u))}function kn(n){return(n/=255)<=.04045?n/12.92:Math.pow((n+.055)/1.055,2.4)}function Nn(n){var t=parseFloat(n);return\"%\"===n.charAt(n.length-1)?Math.round(2.55*t):t}function En(n){return\"function\"==typeof n?n:function(){return n}}function An(n){return function(t,e,r){return 2===arguments.length&&\"function\"==typeof e&&(r=e,e=null),Cn(t,e,n,r)}}function Cn(n,t,e,r){function i(){var n,t=l.status;if(!t&&Ln(l)||t>=200&&300>t||304===t){try{n=e.call(u,l)}catch(r){return void o.error.call(u,r)}o.load.call(u,n)}else o.error.call(u,l)}var u={},o=ao.dispatch(\"beforesend\",\"progress\",\"load\",\"error\"),a={},l=new XMLHttpRequest,c=null;return!this.XDomainRequest||\"withCredentials\"in l||!/^(http(s)?:)?\\/\\//.test(n)||(l=new XDomainRequest),\"onload\"in l?l.onload=l.onerror=i:l.onreadystatechange=function(){l.readyState>3&&i()},l.onprogress=function(n){var t=ao.event;ao.event=n;try{o.progress.call(u,l)}finally{ao.event=t}},u.header=function(n,t){return n=(n+\"\").toLowerCase(),arguments.length<2?a[n]:(null==t?delete a[n]:a[n]=t+\"\",u)},u.mimeType=function(n){return arguments.length?(t=null==n?null:n+\"\",u):t},u.responseType=function(n){return arguments.length?(c=n,u):c},u.response=function(n){return e=n,u},[\"get\",\"post\"].forEach(function(n){u[n]=function(){return u.send.apply(u,[n].concat(co(arguments)))}}),u.send=function(e,r,i){if(2===arguments.length&&\"function\"==typeof r&&(i=r,r=null),l.open(e,n,!0),null==t||\"accept\"in a||(a.accept=t+\",*/*\"),l.setRequestHeader)for(var f in a)l.setRequestHeader(f,a[f]);return null!=t&&l.overrideMimeType&&l.overrideMimeType(t),null!=c&&(l.responseType=c),null!=i&&u.on(\"error\",i).on(\"load\",function(n){i(null,n)}),o.beforesend.call(u,l),l.send(null==r?null:r),u},u.abort=function(){return l.abort(),u},ao.rebind(u,o,\"on\"),null==r?u:u.get(zn(r))}function zn(n){return 1===n.length?function(t,e){n(null==t?e:null)}:n}function Ln(n){var t=n.responseType;return t&&\"text\"!==t?n.response:n.responseText}function qn(n,t,e){var r=arguments.length;2>r&&(t=0),3>r&&(e=Date.now());var i=e+t,u={c:n,t:i,n:null};return aa?aa.n=u:oa=u,aa=u,la||(ca=clearTimeout(ca),la=1,fa(Tn)),u}function Tn(){var n=Rn(),t=Dn()-n;t>24?(isFinite(t)&&(clearTimeout(ca),ca=setTimeout(Tn,t)),la=0):(la=1,fa(Tn))}function Rn(){for(var n=Date.now(),t=oa;t;)n>=t.t&&t.c(n-t.t)&&(t.c=null),t=t.n;return n}function Dn(){for(var n,t=oa,e=1/0;t;)t.c?(t.t<e&&(e=t.t),t=(n=t).n):t=n?n.n=t.n:oa=t.n;return aa=n,e}function Pn(n,t){return t-(n?Math.ceil(Math.log(n)/Math.LN10):1)}function Un(n,t){var e=Math.pow(10,3*xo(8-t));return{scale:t>8?function(n){return n/e}:function(n){return n*e},symbol:n}}function jn(n){var t=n.decimal,e=n.thousands,r=n.grouping,i=n.currency,u=r&&e?function(n,t){for(var i=n.length,u=[],o=0,a=r[0],l=0;i>0&&a>0&&(l+a+1>t&&(a=Math.max(1,t-l)),u.push(n.substring(i-=a,i+a)),!((l+=a+1)>t));)a=r[o=(o+1)%r.length];return u.reverse().join(e)}:m;return function(n){var e=ha.exec(n),r=e[1]||\" \",o=e[2]||\">\",a=e[3]||\"-\",l=e[4]||\"\",c=e[5],f=+e[6],s=e[7],h=e[8],p=e[9],g=1,v=\"\",d=\"\",y=!1,m=!0;switch(h&&(h=+h.substring(1)),(c||\"0\"===r&&\"=\"===o)&&(c=r=\"0\",o=\"=\"),p){case\"n\":s=!0,p=\"g\";break;case\"%\":g=100,d=\"%\",p=\"f\";break;case\"p\":g=100,d=\"%\",p=\"r\";break;case\"b\":case\"o\":case\"x\":case\"X\":\"#\"===l&&(v=\"0\"+p.toLowerCase());case\"c\":m=!1;case\"d\":y=!0,h=0;break;case\"s\":g=-1,p=\"r\"}\"$\"===l&&(v=i[0],d=i[1]),\"r\"!=p||h||(p=\"g\"),null!=h&&(\"g\"==p?h=Math.max(1,Math.min(21,h)):\"e\"!=p&&\"f\"!=p||(h=Math.max(0,Math.min(20,h)))),p=pa.get(p)||Fn;var M=c&&s;return function(n){var e=d;if(y&&n%1)return\"\";var i=0>n||0===n&&0>1/n?(n=-n,\"-\"):\"-\"===a?\"\":a;if(0>g){var l=ao.formatPrefix(n,h);n=l.scale(n),e=l.symbol+d}else n*=g;n=p(n,h);var x,b,_=n.lastIndexOf(\".\");if(0>_){var w=m?n.lastIndexOf(\"e\"):-1;0>w?(x=n,b=\"\"):(x=n.substring(0,w),b=n.substring(w))}else x=n.substring(0,_),b=t+n.substring(_+1);!c&&s&&(x=u(x,1/0));var S=v.length+x.length+b.length+(M?0:i.length),k=f>S?new Array(S=f-S+1).join(r):\"\";return M&&(x=u(k+x,k.length?f-b.length:1/0)),i+=v,n=x+b,(\"<\"===o?i+n+k:\">\"===o?k+i+n:\"^\"===o?k.substring(0,S>>=1)+i+n+k.substring(S):i+(M?n:k+n))+e}}}function Fn(n){return n+\"\"}function Hn(){this._=new Date(arguments.length>1?Date.UTC.apply(this,arguments):arguments[0])}function On(n,t,e){function r(t){var e=n(t),r=u(e,1);return r-t>t-e?e:r}function i(e){return t(e=n(new va(e-1)),1),e}function u(n,e){return t(n=new va(+n),e),n}function o(n,r,u){var o=i(n),a=[];if(u>1)for(;r>o;)e(o)%u||a.push(new Date(+o)),t(o,1);else for(;r>o;)a.push(new Date(+o)),t(o,1);return a}function a(n,t,e){try{va=Hn;var r=new Hn;return r._=n,o(r,t,e)}finally{va=Date}}n.floor=n,n.round=r,n.ceil=i,n.offset=u,n.range=o;var l=n.utc=In(n);return l.floor=l,l.round=In(r),l.ceil=In(i),l.offset=In(u),l.range=a,n}function In(n){return function(t,e){try{va=Hn;var r=new Hn;return r._=t,n(r,e)._}finally{va=Date}}}function Yn(n){function t(n){function t(t){for(var e,i,u,o=[],a=-1,l=0;++a<r;)37===n.charCodeAt(a)&&(o.push(n.slice(l,a)),null!=(i=ya[e=n.charAt(++a)])&&(e=n.charAt(++a)),(u=A[e])&&(e=u(t,null==i?\"e\"===e?\" \":\"0\":i)),o.push(e),l=a+1);return o.push(n.slice(l,a)),o.join(\"\")}var r=n.length;return t.parse=function(t){var r={y:1900,m:0,d:1,H:0,M:0,S:0,L:0,Z:null},i=e(r,n,t,0);if(i!=t.length)return null;\"p\"in r&&(r.H=r.H%12+12*r.p);var u=null!=r.Z&&va!==Hn,o=new(u?Hn:va);return\"j\"in r?o.setFullYear(r.y,0,r.j):\"W\"in r||\"U\"in r?(\"w\"in r||(r.w=\"W\"in r?1:0),o.setFullYear(r.y,0,1),o.setFullYear(r.y,0,\"W\"in r?(r.w+6)%7+7*r.W-(o.getDay()+5)%7:r.w+7*r.U-(o.getDay()+6)%7)):o.setFullYear(r.y,r.m,r.d),o.setHours(r.H+(r.Z/100|0),r.M+r.Z%100,r.S,r.L),u?o._:o},t.toString=function(){return n},t}function e(n,t,e,r){for(var i,u,o,a=0,l=t.length,c=e.length;l>a;){if(r>=c)return-1;if(i=t.charCodeAt(a++),37===i){if(o=t.charAt(a++),u=C[o in ya?t.charAt(a++):o],!u||(r=u(n,e,r))<0)return-1}else if(i!=e.charCodeAt(r++))return-1}return r}function r(n,t,e){_.lastIndex=0;var r=_.exec(t.slice(e));return r?(n.w=w.get(r[0].toLowerCase()),e+r[0].length):-1}function i(n,t,e){x.lastIndex=0;var r=x.exec(t.slice(e));return r?(n.w=b.get(r[0].toLowerCase()),e+r[0].length):-1}function u(n,t,e){N.lastIndex=0;var r=N.exec(t.slice(e));return r?(n.m=E.get(r[0].toLowerCase()),e+r[0].length):-1}function o(n,t,e){S.lastIndex=0;var r=S.exec(t.slice(e));return r?(n.m=k.get(r[0].toLowerCase()),e+r[0].length):-1}function a(n,t,r){return e(n,A.c.toString(),t,r)}function l(n,t,r){return e(n,A.x.toString(),t,r)}function c(n,t,r){return e(n,A.X.toString(),t,r)}function f(n,t,e){var r=M.get(t.slice(e,e+=2).toLowerCase());return null==r?-1:(n.p=r,e)}var s=n.dateTime,h=n.date,p=n.time,g=n.periods,v=n.days,d=n.shortDays,y=n.months,m=n.shortMonths;t.utc=function(n){function e(n){try{va=Hn;var t=new va;return t._=n,r(t)}finally{va=Date}}var r=t(n);return e.parse=function(n){try{va=Hn;var t=r.parse(n);return t&&t._}finally{va=Date}},e.toString=r.toString,e},t.multi=t.utc.multi=ct;var M=ao.map(),x=Vn(v),b=Xn(v),_=Vn(d),w=Xn(d),S=Vn(y),k=Xn(y),N=Vn(m),E=Xn(m);g.forEach(function(n,t){M.set(n.toLowerCase(),t)});var A={a:function(n){return d[n.getDay()]},A:function(n){return v[n.getDay()]},b:function(n){return m[n.getMonth()]},B:function(n){return y[n.getMonth()]},c:t(s),d:function(n,t){return Zn(n.getDate(),t,2)},e:function(n,t){return Zn(n.getDate(),t,2)},H:function(n,t){return Zn(n.getHours(),t,2)},I:function(n,t){return Zn(n.getHours()%12||12,t,2)},j:function(n,t){return Zn(1+ga.dayOfYear(n),t,3)},L:function(n,t){return Zn(n.getMilliseconds(),t,3)},m:function(n,t){return Zn(n.getMonth()+1,t,2)},M:function(n,t){return Zn(n.getMinutes(),t,2)},p:function(n){return g[+(n.getHours()>=12)]},S:function(n,t){return Zn(n.getSeconds(),t,2)},U:function(n,t){return Zn(ga.sundayOfYear(n),t,2)},w:function(n){return n.getDay()},W:function(n,t){return Zn(ga.mondayOfYear(n),t,2)},x:t(h),X:t(p),y:function(n,t){return Zn(n.getFullYear()%100,t,2)},Y:function(n,t){return Zn(n.getFullYear()%1e4,t,4)},Z:at,\"%\":function(){return\"%\"}},C={a:r,A:i,b:u,B:o,c:a,d:tt,e:tt,H:rt,I:rt,j:et,L:ot,m:nt,M:it,p:f,S:ut,U:Bn,w:$n,W:Wn,x:l,X:c,y:Gn,Y:Jn,Z:Kn,\"%\":lt};return t}function Zn(n,t,e){var r=0>n?\"-\":\"\",i=(r?-n:n)+\"\",u=i.length;return r+(e>u?new Array(e-u+1).join(t)+i:i)}function Vn(n){return new RegExp(\"^(?:\"+n.map(ao.requote).join(\"|\")+\")\",\"i\")}function Xn(n){for(var t=new c,e=-1,r=n.length;++e<r;)t.set(n[e].toLowerCase(),e);return t}function $n(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e,e+1));return r?(n.w=+r[0],e+r[0].length):-1}function Bn(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e));return r?(n.U=+r[0],e+r[0].length):-1}function Wn(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e));return r?(n.W=+r[0],e+r[0].length):-1}function Jn(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e,e+4));return r?(n.y=+r[0],e+r[0].length):-1}function Gn(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e,e+2));return r?(n.y=Qn(+r[0]),e+r[0].length):-1}function Kn(n,t,e){return/^[+-]\\d{4}$/.test(t=t.slice(e,e+5))?(n.Z=-t,e+5):-1}function Qn(n){return n+(n>68?1900:2e3)}function nt(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e,e+2));return r?(n.m=r[0]-1,e+r[0].length):-1}function tt(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e,e+2));return r?(n.d=+r[0],e+r[0].length):-1}function et(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e,e+3));return r?(n.j=+r[0],e+r[0].length):-1}function rt(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e,e+2));return r?(n.H=+r[0],e+r[0].length):-1}function it(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e,e+2));return r?(n.M=+r[0],e+r[0].length):-1}function ut(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e,e+2));return r?(n.S=+r[0],e+r[0].length):-1}function ot(n,t,e){ma.lastIndex=0;var r=ma.exec(t.slice(e,e+3));return r?(n.L=+r[0],e+r[0].length):-1}function at(n){var t=n.getTimezoneOffset(),e=t>0?\"-\":\"+\",r=xo(t)/60|0,i=xo(t)%60;return e+Zn(r,\"0\",2)+Zn(i,\"0\",2)}function lt(n,t,e){Ma.lastIndex=0;var r=Ma.exec(t.slice(e,e+1));return r?e+r[0].length:-1}function ct(n){for(var t=n.length,e=-1;++e<t;)n[e][0]=this(n[e][0]);return function(t){for(var e=0,r=n[e];!r[1](t);)r=n[++e];return r[0](t)}}function ft(){}function st(n,t,e){var r=e.s=n+t,i=r-n,u=r-i;e.t=n-u+(t-i)}function ht(n,t){n&&wa.hasOwnProperty(n.type)&&wa[n.type](n,t)}function pt(n,t,e){var r,i=-1,u=n.length-e;for(t.lineStart();++i<u;)r=n[i],t.point(r[0],r[1],r[2]);t.lineEnd()}function gt(n,t){var e=-1,r=n.length;for(t.polygonStart();++e<r;)pt(n[e],t,1);t.polygonEnd()}function vt(){function n(n,t){n*=Yo,t=t*Yo/2+Fo/4;var e=n-r,o=e>=0?1:-1,a=o*e,l=Math.cos(t),c=Math.sin(t),f=u*c,s=i*l+f*Math.cos(a),h=f*o*Math.sin(a);ka.add(Math.atan2(h,s)),r=n,i=l,u=c}var t,e,r,i,u;Na.point=function(o,a){Na.point=n,r=(t=o)*Yo,i=Math.cos(a=(e=a)*Yo/2+Fo/4),u=Math.sin(a)},Na.lineEnd=function(){n(t,e)}}function dt(n){var t=n[0],e=n[1],r=Math.cos(e);return[r*Math.cos(t),r*Math.sin(t),Math.sin(e)]}function yt(n,t){return n[0]*t[0]+n[1]*t[1]+n[2]*t[2]}function mt(n,t){return[n[1]*t[2]-n[2]*t[1],n[2]*t[0]-n[0]*t[2],n[0]*t[1]-n[1]*t[0]]}function Mt(n,t){n[0]+=t[0],n[1]+=t[1],n[2]+=t[2]}function xt(n,t){return[n[0]*t,n[1]*t,n[2]*t]}function bt(n){var t=Math.sqrt(n[0]*n[0]+n[1]*n[1]+n[2]*n[2]);n[0]/=t,n[1]/=t,n[2]/=t}function _t(n){return[Math.atan2(n[1],n[0]),tn(n[2])]}function wt(n,t){return xo(n[0]-t[0])<Uo&&xo(n[1]-t[1])<Uo}function St(n,t){n*=Yo;var e=Math.cos(t*=Yo);kt(e*Math.cos(n),e*Math.sin(n),Math.sin(t))}function kt(n,t,e){++Ea,Ca+=(n-Ca)/Ea,za+=(t-za)/Ea,La+=(e-La)/Ea}function Nt(){function n(n,i){n*=Yo;var u=Math.cos(i*=Yo),o=u*Math.cos(n),a=u*Math.sin(n),l=Math.sin(i),c=Math.atan2(Math.sqrt((c=e*l-r*a)*c+(c=r*o-t*l)*c+(c=t*a-e*o)*c),t*o+e*a+r*l);Aa+=c,qa+=c*(t+(t=o)),Ta+=c*(e+(e=a)),Ra+=c*(r+(r=l)),kt(t,e,r)}var t,e,r;ja.point=function(i,u){i*=Yo;var o=Math.cos(u*=Yo);t=o*Math.cos(i),e=o*Math.sin(i),r=Math.sin(u),ja.point=n,kt(t,e,r)}}function Et(){ja.point=St}function At(){function n(n,t){n*=Yo;var e=Math.cos(t*=Yo),o=e*Math.cos(n),a=e*Math.sin(n),l=Math.sin(t),c=i*l-u*a,f=u*o-r*l,s=r*a-i*o,h=Math.sqrt(c*c+f*f+s*s),p=r*o+i*a+u*l,g=h&&-nn(p)/h,v=Math.atan2(h,p);Da+=g*c,Pa+=g*f,Ua+=g*s,Aa+=v,qa+=v*(r+(r=o)),Ta+=v*(i+(i=a)),Ra+=v*(u+(u=l)),kt(r,i,u)}var t,e,r,i,u;ja.point=function(o,a){t=o,e=a,ja.point=n,o*=Yo;var l=Math.cos(a*=Yo);r=l*Math.cos(o),i=l*Math.sin(o),u=Math.sin(a),kt(r,i,u)},ja.lineEnd=function(){n(t,e),ja.lineEnd=Et,ja.point=St}}function Ct(n,t){function e(e,r){return e=n(e,r),t(e[0],e[1])}return n.invert&&t.invert&&(e.invert=function(e,r){return e=t.invert(e,r),e&&n.invert(e[0],e[1])}),e}function zt(){return!0}function Lt(n,t,e,r,i){var u=[],o=[];if(n.forEach(function(n){if(!((t=n.length-1)<=0)){var t,e=n[0],r=n[t];if(wt(e,r)){i.lineStart();for(var a=0;t>a;++a)i.point((e=n[a])[0],e[1]);return void i.lineEnd()}var l=new Tt(e,n,null,!0),c=new Tt(e,null,l,!1);l.o=c,u.push(l),o.push(c),l=new Tt(r,n,null,!1),c=new Tt(r,null,l,!0),l.o=c,u.push(l),o.push(c)}}),o.sort(t),qt(u),qt(o),u.length){for(var a=0,l=e,c=o.length;c>a;++a)o[a].e=l=!l;for(var f,s,h=u[0];;){for(var p=h,g=!0;p.v;)if((p=p.n)===h)return;f=p.z,i.lineStart();do{if(p.v=p.o.v=!0,p.e){if(g)for(var a=0,c=f.length;c>a;++a)i.point((s=f[a])[0],s[1]);else r(p.x,p.n.x,1,i);p=p.n}else{if(g){f=p.p.z;for(var a=f.length-1;a>=0;--a)i.point((s=f[a])[0],s[1])}else r(p.x,p.p.x,-1,i);p=p.p}p=p.o,f=p.z,g=!g}while(!p.v);i.lineEnd()}}}function qt(n){if(t=n.length){for(var t,e,r=0,i=n[0];++r<t;)i.n=e=n[r],e.p=i,i=e;i.n=e=n[0],e.p=i}}function Tt(n,t,e,r){this.x=n,this.z=t,this.o=e,this.e=r,this.v=!1,this.n=this.p=null}function Rt(n,t,e,r){return function(i,u){function o(t,e){var r=i(t,e);n(t=r[0],e=r[1])&&u.point(t,e)}function a(n,t){var e=i(n,t);d.point(e[0],e[1])}function l(){m.point=a,d.lineStart()}function c(){m.point=o,d.lineEnd()}function f(n,t){v.push([n,t]);var e=i(n,t);x.point(e[0],e[1])}function s(){x.lineStart(),v=[]}function h(){f(v[0][0],v[0][1]),x.lineEnd();var n,t=x.clean(),e=M.buffer(),r=e.length;if(v.pop(),g.push(v),v=null,r)if(1&t){n=e[0];var i,r=n.length-1,o=-1;if(r>0){for(b||(u.polygonStart(),b=!0),u.lineStart();++o<r;)u.point((i=n[o])[0],i[1]);u.lineEnd()}}else r>1&&2&t&&e.push(e.pop().concat(e.shift())),p.push(e.filter(Dt))}var p,g,v,d=t(u),y=i.invert(r[0],r[1]),m={point:o,lineStart:l,lineEnd:c,polygonStart:function(){m.point=f,m.lineStart=s,m.lineEnd=h,p=[],g=[]},polygonEnd:function(){m.point=o,m.lineStart=l,m.lineEnd=c,p=ao.merge(p);var n=Ot(y,g);p.length?(b||(u.polygonStart(),b=!0),Lt(p,Ut,n,e,u)):n&&(b||(u.polygonStart(),b=!0),u.lineStart(),e(null,null,1,u),u.lineEnd()),b&&(u.polygonEnd(),b=!1),p=g=null},sphere:function(){u.polygonStart(),u.lineStart(),e(null,null,1,u),u.lineEnd(),u.polygonEnd()}},M=Pt(),x=t(M),b=!1;return m}}function Dt(n){return n.length>1}function Pt(){var n,t=[];return{lineStart:function(){t.push(n=[])},point:function(t,e){n.push([t,e])},lineEnd:b,buffer:function(){var e=t;return t=[],n=null,e},rejoin:function(){t.length>1&&t.push(t.pop().concat(t.shift()))}}}function Ut(n,t){return((n=n.x)[0]<0?n[1]-Io-Uo:Io-n[1])-((t=t.x)[0]<0?t[1]-Io-Uo:Io-t[1])}function jt(n){var t,e=NaN,r=NaN,i=NaN;return{lineStart:function(){n.lineStart(),t=1},point:function(u,o){var a=u>0?Fo:-Fo,l=xo(u-e);xo(l-Fo)<Uo?(n.point(e,r=(r+o)/2>0?Io:-Io),n.point(i,r),n.lineEnd(),n.lineStart(),n.point(a,r),n.point(u,r),t=0):i!==a&&l>=Fo&&(xo(e-i)<Uo&&(e-=i*Uo),xo(u-a)<Uo&&(u-=a*Uo),r=Ft(e,r,u,o),n.point(i,r),n.lineEnd(),n.lineStart(),n.point(a,r),t=0),n.point(e=u,r=o),i=a},lineEnd:function(){n.lineEnd(),e=r=NaN},clean:function(){return 2-t}}}function Ft(n,t,e,r){var i,u,o=Math.sin(n-e);return xo(o)>Uo?Math.atan((Math.sin(t)*(u=Math.cos(r))*Math.sin(e)-Math.sin(r)*(i=Math.cos(t))*Math.sin(n))/(i*u*o)):(t+r)/2}function Ht(n,t,e,r){var i;if(null==n)i=e*Io,r.point(-Fo,i),r.point(0,i),r.point(Fo,i),r.point(Fo,0),r.point(Fo,-i),r.point(0,-i),r.point(-Fo,-i),r.point(-Fo,0),r.point(-Fo,i);else if(xo(n[0]-t[0])>Uo){var u=n[0]<t[0]?Fo:-Fo;i=e*u/2,r.point(-u,i),r.point(0,i),r.point(u,i)}else r.point(t[0],t[1])}function Ot(n,t){var e=n[0],r=n[1],i=[Math.sin(e),-Math.cos(e),0],u=0,o=0;ka.reset();for(var a=0,l=t.length;l>a;++a){var c=t[a],f=c.length;if(f)for(var s=c[0],h=s[0],p=s[1]/2+Fo/4,g=Math.sin(p),v=Math.cos(p),d=1;;){d===f&&(d=0),n=c[d];var y=n[0],m=n[1]/2+Fo/4,M=Math.sin(m),x=Math.cos(m),b=y-h,_=b>=0?1:-1,w=_*b,S=w>Fo,k=g*M;if(ka.add(Math.atan2(k*_*Math.sin(w),v*x+k*Math.cos(w))),u+=S?b+_*Ho:b,S^h>=e^y>=e){var N=mt(dt(s),dt(n));bt(N);var E=mt(i,N);bt(E);var A=(S^b>=0?-1:1)*tn(E[2]);(r>A||r===A&&(N[0]||N[1]))&&(o+=S^b>=0?1:-1)}if(!d++)break;h=y,g=M,v=x,s=n}}return(-Uo>u||Uo>u&&-Uo>ka)^1&o}function It(n){function t(n,t){return Math.cos(n)*Math.cos(t)>u}function e(n){var e,u,l,c,f;return{lineStart:function(){c=l=!1,f=1},point:function(s,h){var p,g=[s,h],v=t(s,h),d=o?v?0:i(s,h):v?i(s+(0>s?Fo:-Fo),h):0;if(!e&&(c=l=v)&&n.lineStart(),v!==l&&(p=r(e,g),(wt(e,p)||wt(g,p))&&(g[0]+=Uo,g[1]+=Uo,v=t(g[0],g[1]))),v!==l)f=0,v?(n.lineStart(),p=r(g,e),n.point(p[0],p[1])):(p=r(e,g),n.point(p[0],p[1]),n.lineEnd()),e=p;else if(a&&e&&o^v){var y;d&u||!(y=r(g,e,!0))||(f=0,o?(n.lineStart(),n.point(y[0][0],y[0][1]),n.point(y[1][0],y[1][1]),n.lineEnd()):(n.point(y[1][0],y[1][1]),n.lineEnd(),n.lineStart(),n.point(y[0][0],y[0][1])))}!v||e&&wt(e,g)||n.point(g[0],g[1]),e=g,l=v,u=d},lineEnd:function(){l&&n.lineEnd(),e=null},clean:function(){return f|(c&&l)<<1}}}function r(n,t,e){var r=dt(n),i=dt(t),o=[1,0,0],a=mt(r,i),l=yt(a,a),c=a[0],f=l-c*c;if(!f)return!e&&n;var s=u*l/f,h=-u*c/f,p=mt(o,a),g=xt(o,s),v=xt(a,h);Mt(g,v);var d=p,y=yt(g,d),m=yt(d,d),M=y*y-m*(yt(g,g)-1);if(!(0>M)){var x=Math.sqrt(M),b=xt(d,(-y-x)/m);if(Mt(b,g),b=_t(b),!e)return b;var _,w=n[0],S=t[0],k=n[1],N=t[1];w>S&&(_=w,w=S,S=_);var E=S-w,A=xo(E-Fo)<Uo,C=A||Uo>E;if(!A&&k>N&&(_=k,k=N,N=_),C?A?k+N>0^b[1]<(xo(b[0]-w)<Uo?k:N):k<=b[1]&&b[1]<=N:E>Fo^(w<=b[0]&&b[0]<=S)){var z=xt(d,(-y+x)/m);return Mt(z,g),[b,_t(z)]}}}function i(t,e){var r=o?n:Fo-n,i=0;return-r>t?i|=1:t>r&&(i|=2),-r>e?i|=4:e>r&&(i|=8),i}var u=Math.cos(n),o=u>0,a=xo(u)>Uo,l=ve(n,6*Yo);return Rt(t,e,l,o?[0,-n]:[-Fo,n-Fo])}function Yt(n,t,e,r){return function(i){var u,o=i.a,a=i.b,l=o.x,c=o.y,f=a.x,s=a.y,h=0,p=1,g=f-l,v=s-c;if(u=n-l,g||!(u>0)){if(u/=g,0>g){if(h>u)return;p>u&&(p=u)}else if(g>0){if(u>p)return;u>h&&(h=u)}if(u=e-l,g||!(0>u)){if(u/=g,0>g){if(u>p)return;u>h&&(h=u)}else if(g>0){if(h>u)return;p>u&&(p=u)}if(u=t-c,v||!(u>0)){if(u/=v,0>v){if(h>u)return;p>u&&(p=u)}else if(v>0){if(u>p)return;u>h&&(h=u)}if(u=r-c,v||!(0>u)){if(u/=v,0>v){if(u>p)return;u>h&&(h=u)}else if(v>0){if(h>u)return;p>u&&(p=u)}return h>0&&(i.a={x:l+h*g,y:c+h*v}),1>p&&(i.b={x:l+p*g,y:c+p*v}),i}}}}}}function Zt(n,t,e,r){function i(r,i){return xo(r[0]-n)<Uo?i>0?0:3:xo(r[0]-e)<Uo?i>0?2:1:xo(r[1]-t)<Uo?i>0?1:0:i>0?3:2}function u(n,t){return o(n.x,t.x)}function o(n,t){var e=i(n,1),r=i(t,1);return e!==r?e-r:0===e?t[1]-n[1]:1===e?n[0]-t[0]:2===e?n[1]-t[1]:t[0]-n[0]}return function(a){function l(n){for(var t=0,e=d.length,r=n[1],i=0;e>i;++i)for(var u,o=1,a=d[i],l=a.length,c=a[0];l>o;++o)u=a[o],c[1]<=r?u[1]>r&&Q(c,u,n)>0&&++t:u[1]<=r&&Q(c,u,n)<0&&--t,c=u;return 0!==t}function c(u,a,l,c){var f=0,s=0;if(null==u||(f=i(u,l))!==(s=i(a,l))||o(u,a)<0^l>0){do c.point(0===f||3===f?n:e,f>1?r:t);while((f=(f+l+4)%4)!==s)}else c.point(a[0],a[1])}function f(i,u){return i>=n&&e>=i&&u>=t&&r>=u}function s(n,t){f(n,t)&&a.point(n,t)}function h(){C.point=g,d&&d.push(y=[]),S=!0,w=!1,b=_=NaN}function p(){v&&(g(m,M),x&&w&&E.rejoin(),v.push(E.buffer())),C.point=s,w&&a.lineEnd()}function g(n,t){n=Math.max(-Ha,Math.min(Ha,n)),t=Math.max(-Ha,Math.min(Ha,t));var e=f(n,t);if(d&&y.push([n,t]),S)m=n,M=t,x=e,S=!1,e&&(a.lineStart(),a.point(n,t));else if(e&&w)a.point(n,t);else{var r={a:{x:b,y:_},b:{x:n,y:t}};A(r)?(w||(a.lineStart(),a.point(r.a.x,r.a.y)),a.point(r.b.x,r.b.y),e||a.lineEnd(),k=!1):e&&(a.lineStart(),a.point(n,t),k=!1)}b=n,_=t,w=e}var v,d,y,m,M,x,b,_,w,S,k,N=a,E=Pt(),A=Yt(n,t,e,r),C={point:s,lineStart:h,lineEnd:p,polygonStart:function(){a=E,v=[],d=[],k=!0},polygonEnd:function(){a=N,v=ao.merge(v);var t=l([n,r]),e=k&&t,i=v.length;(e||i)&&(a.polygonStart(),e&&(a.lineStart(),c(null,null,1,a),a.lineEnd()),i&&Lt(v,u,t,c,a),a.polygonEnd()),v=d=y=null}};return C}}function Vt(n){var t=0,e=Fo/3,r=ae(n),i=r(t,e);return i.parallels=function(n){return arguments.length?r(t=n[0]*Fo/180,e=n[1]*Fo/180):[t/Fo*180,e/Fo*180]},i}function Xt(n,t){function e(n,t){var e=Math.sqrt(u-2*i*Math.sin(t))/i;return[e*Math.sin(n*=i),o-e*Math.cos(n)]}var r=Math.sin(n),i=(r+Math.sin(t))/2,u=1+r*(2*i-r),o=Math.sqrt(u)/i;return e.invert=function(n,t){var e=o-t;return[Math.atan2(n,e)/i,tn((u-(n*n+e*e)*i*i)/(2*i))]},e}function $t(){function n(n,t){Ia+=i*n-r*t,r=n,i=t}var t,e,r,i;$a.point=function(u,o){$a.point=n,t=r=u,e=i=o},$a.lineEnd=function(){n(t,e)}}function Bt(n,t){Ya>n&&(Ya=n),n>Va&&(Va=n),Za>t&&(Za=t),t>Xa&&(Xa=t)}function Wt(){function n(n,t){o.push(\"M\",n,\",\",t,u)}function t(n,t){o.push(\"M\",n,\",\",t),a.point=e}function e(n,t){o.push(\"L\",n,\",\",t)}function r(){a.point=n}function i(){o.push(\"Z\")}var u=Jt(4.5),o=[],a={point:n,lineStart:function(){a.point=t},lineEnd:r,polygonStart:function(){a.lineEnd=i},polygonEnd:function(){a.lineEnd=r,a.point=n},pointRadius:function(n){return u=Jt(n),a},result:function(){if(o.length){var n=o.join(\"\");return o=[],n}}};return a}function Jt(n){return\"m0,\"+n+\"a\"+n+\",\"+n+\" 0 1,1 0,\"+-2*n+\"a\"+n+\",\"+n+\" 0 1,1 0,\"+2*n+\"z\"}function Gt(n,t){Ca+=n,za+=t,++La}function Kt(){function n(n,r){var i=n-t,u=r-e,o=Math.sqrt(i*i+u*u);qa+=o*(t+n)/2,Ta+=o*(e+r)/2,Ra+=o,Gt(t=n,e=r)}var t,e;Wa.point=function(r,i){Wa.point=n,Gt(t=r,e=i)}}function Qt(){Wa.point=Gt}function ne(){function n(n,t){var e=n-r,u=t-i,o=Math.sqrt(e*e+u*u);qa+=o*(r+n)/2,Ta+=o*(i+t)/2,Ra+=o,o=i*n-r*t,Da+=o*(r+n),Pa+=o*(i+t),Ua+=3*o,Gt(r=n,i=t)}var t,e,r,i;Wa.point=function(u,o){Wa.point=n,Gt(t=r=u,e=i=o)},Wa.lineEnd=function(){n(t,e)}}function te(n){function t(t,e){n.moveTo(t+o,e),n.arc(t,e,o,0,Ho)}function e(t,e){n.moveTo(t,e),a.point=r}function r(t,e){n.lineTo(t,e)}function i(){a.point=t}function u(){n.closePath()}var o=4.5,a={point:t,lineStart:function(){a.point=e},lineEnd:i,polygonStart:function(){a.lineEnd=u},polygonEnd:function(){a.lineEnd=i,a.point=t},pointRadius:function(n){return o=n,a},result:b};return a}function ee(n){function t(n){return(a?r:e)(n)}function e(t){return ue(t,function(e,r){e=n(e,r),t.point(e[0],e[1])})}function r(t){function e(e,r){e=n(e,r),t.point(e[0],e[1])}function r(){M=NaN,S.point=u,t.lineStart()}function u(e,r){var u=dt([e,r]),o=n(e,r);i(M,x,m,b,_,w,M=o[0],x=o[1],m=e,b=u[0],_=u[1],w=u[2],a,t),t.point(M,x)}function o(){S.point=e,t.lineEnd()}function l(){r(),S.point=c,S.lineEnd=f}function c(n,t){u(s=n,h=t),p=M,g=x,v=b,d=_,y=w,S.point=u}function f(){i(M,x,m,b,_,w,p,g,s,v,d,y,a,t),S.lineEnd=o,o()}var s,h,p,g,v,d,y,m,M,x,b,_,w,S={point:e,lineStart:r,lineEnd:o,polygonStart:function(){t.polygonStart(),S.lineStart=l},polygonEnd:function(){t.polygonEnd(),S.lineStart=r}};return S}function i(t,e,r,a,l,c,f,s,h,p,g,v,d,y){var m=f-t,M=s-e,x=m*m+M*M;if(x>4*u&&d--){var b=a+p,_=l+g,w=c+v,S=Math.sqrt(b*b+_*_+w*w),k=Math.asin(w/=S),N=xo(xo(w)-1)<Uo||xo(r-h)<Uo?(r+h)/2:Math.atan2(_,b),E=n(N,k),A=E[0],C=E[1],z=A-t,L=C-e,q=M*z-m*L;(q*q/x>u||xo((m*z+M*L)/x-.5)>.3||o>a*p+l*g+c*v)&&(i(t,e,r,a,l,c,A,C,N,b/=S,_/=S,w,d,y),y.point(A,C),i(A,C,N,b,_,w,f,s,h,p,g,v,d,y))}}var u=.5,o=Math.cos(30*Yo),a=16;return t.precision=function(n){return arguments.length?(a=(u=n*n)>0&&16,t):Math.sqrt(u)},t}function re(n){var t=ee(function(t,e){return n([t*Zo,e*Zo])});return function(n){return le(t(n))}}function ie(n){this.stream=n}function ue(n,t){return{point:t,sphere:function(){n.sphere()},lineStart:function(){n.lineStart()},lineEnd:function(){n.lineEnd()},polygonStart:function(){n.polygonStart()},polygonEnd:function(){n.polygonEnd()}}}function oe(n){return ae(function(){return n})()}function ae(n){function t(n){return n=a(n[0]*Yo,n[1]*Yo),[n[0]*h+l,c-n[1]*h]}function e(n){return n=a.invert((n[0]-l)/h,(c-n[1])/h),n&&[n[0]*Zo,n[1]*Zo]}function r(){a=Ct(o=se(y,M,x),u);var n=u(v,d);return l=p-n[0]*h,c=g+n[1]*h,i()}function i(){return f&&(f.valid=!1,f=null),t}var u,o,a,l,c,f,s=ee(function(n,t){return n=u(n,t),[n[0]*h+l,c-n[1]*h]}),h=150,p=480,g=250,v=0,d=0,y=0,M=0,x=0,b=Fa,_=m,w=null,S=null;return t.stream=function(n){return f&&(f.valid=!1),f=le(b(o,s(_(n)))),f.valid=!0,f},t.clipAngle=function(n){return arguments.length?(b=null==n?(w=n,Fa):It((w=+n)*Yo),i()):w},t.clipExtent=function(n){return arguments.length?(S=n,_=n?Zt(n[0][0],n[0][1],n[1][0],n[1][1]):m,i()):S},t.scale=function(n){return arguments.length?(h=+n,r()):h},t.translate=function(n){return arguments.length?(p=+n[0],g=+n[1],r()):[p,g]},t.center=function(n){return arguments.length?(v=n[0]%360*Yo,d=n[1]%360*Yo,r()):[v*Zo,d*Zo]},t.rotate=function(n){return arguments.length?(y=n[0]%360*Yo,M=n[1]%360*Yo,x=n.length>2?n[2]%360*Yo:0,r()):[y*Zo,M*Zo,x*Zo]},ao.rebind(t,s,\"precision\"),function(){return u=n.apply(this,arguments),t.invert=u.invert&&e,r()}}function le(n){return ue(n,function(t,e){n.point(t*Yo,e*Yo)})}function ce(n,t){return[n,t]}function fe(n,t){return[n>Fo?n-Ho:-Fo>n?n+Ho:n,t]}function se(n,t,e){return n?t||e?Ct(pe(n),ge(t,e)):pe(n):t||e?ge(t,e):fe}function he(n){return function(t,e){return t+=n,[t>Fo?t-Ho:-Fo>t?t+Ho:t,e]}}function pe(n){var t=he(n);return t.invert=he(-n),t}function ge(n,t){function e(n,t){var e=Math.cos(t),a=Math.cos(n)*e,l=Math.sin(n)*e,c=Math.sin(t),f=c*r+a*i;return[Math.atan2(l*u-f*o,a*r-c*i),tn(f*u+l*o)]}var r=Math.cos(n),i=Math.sin(n),u=Math.cos(t),o=Math.sin(t);return e.invert=function(n,t){var e=Math.cos(t),a=Math.cos(n)*e,l=Math.sin(n)*e,c=Math.sin(t),f=c*u-l*o;return[Math.atan2(l*u+c*o,a*r+f*i),tn(f*r-a*i)]},e}function ve(n,t){var e=Math.cos(n),r=Math.sin(n);return function(i,u,o,a){var l=o*t;null!=i?(i=de(e,i),u=de(e,u),(o>0?u>i:i>u)&&(i+=o*Ho)):(i=n+o*Ho,u=n-.5*l);for(var c,f=i;o>0?f>u:u>f;f-=l)a.point((c=_t([e,-r*Math.cos(f),-r*Math.sin(f)]))[0],c[1])}}function de(n,t){var e=dt(t);e[0]-=n,bt(e);var r=nn(-e[1]);return((-e[2]<0?-r:r)+2*Math.PI-Uo)%(2*Math.PI)}function ye(n,t,e){var r=ao.range(n,t-Uo,e).concat(t);return function(n){return r.map(function(t){return[n,t]})}}function me(n,t,e){var r=ao.range(n,t-Uo,e).concat(t);return function(n){return r.map(function(t){return[t,n]})}}function Me(n){return n.source}function xe(n){return n.target}function be(n,t,e,r){var i=Math.cos(t),u=Math.sin(t),o=Math.cos(r),a=Math.sin(r),l=i*Math.cos(n),c=i*Math.sin(n),f=o*Math.cos(e),s=o*Math.sin(e),h=2*Math.asin(Math.sqrt(on(r-t)+i*o*on(e-n))),p=1/Math.sin(h),g=h?function(n){var t=Math.sin(n*=h)*p,e=Math.sin(h-n)*p,r=e*l+t*f,i=e*c+t*s,o=e*u+t*a;return[Math.atan2(i,r)*Zo,Math.atan2(o,Math.sqrt(r*r+i*i))*Zo]}:function(){return[n*Zo,t*Zo]};return g.distance=h,g}function _e(){function n(n,i){var u=Math.sin(i*=Yo),o=Math.cos(i),a=xo((n*=Yo)-t),l=Math.cos(a);Ja+=Math.atan2(Math.sqrt((a=o*Math.sin(a))*a+(a=r*u-e*o*l)*a),e*u+r*o*l),t=n,e=u,r=o}var t,e,r;Ga.point=function(i,u){t=i*Yo,e=Math.sin(u*=Yo),r=Math.cos(u),Ga.point=n},Ga.lineEnd=function(){Ga.point=Ga.lineEnd=b}}function we(n,t){function e(t,e){var r=Math.cos(t),i=Math.cos(e),u=n(r*i);return[u*i*Math.sin(t),u*Math.sin(e)]}return e.invert=function(n,e){var r=Math.sqrt(n*n+e*e),i=t(r),u=Math.sin(i),o=Math.cos(i);return[Math.atan2(n*u,r*o),Math.asin(r&&e*u/r)]},e}function Se(n,t){function e(n,t){o>0?-Io+Uo>t&&(t=-Io+Uo):t>Io-Uo&&(t=Io-Uo);var e=o/Math.pow(i(t),u);return[e*Math.sin(u*n),o-e*Math.cos(u*n)]}var r=Math.cos(n),i=function(n){return Math.tan(Fo/4+n/2)},u=n===t?Math.sin(n):Math.log(r/Math.cos(t))/Math.log(i(t)/i(n)),o=r*Math.pow(i(n),u)/u;return u?(e.invert=function(n,t){var e=o-t,r=K(u)*Math.sqrt(n*n+e*e);return[Math.atan2(n,e)/u,2*Math.atan(Math.pow(o/r,1/u))-Io]},e):Ne}function ke(n,t){function e(n,t){var e=u-t;return[e*Math.sin(i*n),u-e*Math.cos(i*n)]}var r=Math.cos(n),i=n===t?Math.sin(n):(r-Math.cos(t))/(t-n),u=r/i+n;return xo(i)<Uo?ce:(e.invert=function(n,t){var e=u-t;return[Math.atan2(n,e)/i,u-K(i)*Math.sqrt(n*n+e*e)]},e)}function Ne(n,t){return[n,Math.log(Math.tan(Fo/4+t/2))]}function Ee(n){var t,e=oe(n),r=e.scale,i=e.translate,u=e.clipExtent;return e.scale=function(){var n=r.apply(e,arguments);return n===e?t?e.clipExtent(null):e:n},e.translate=function(){var n=i.apply(e,arguments);return n===e?t?e.clipExtent(null):e:n},e.clipExtent=function(n){var o=u.apply(e,arguments);if(o===e){if(t=null==n){var a=Fo*r(),l=i();u([[l[0]-a,l[1]-a],[l[0]+a,l[1]+a]])}}else t&&(o=null);return o},e.clipExtent(null)}function Ae(n,t){return[Math.log(Math.tan(Fo/4+t/2)),-n]}function Ce(n){return n[0]}function ze(n){return n[1]}function Le(n){for(var t=n.length,e=[0,1],r=2,i=2;t>i;i++){for(;r>1&&Q(n[e[r-2]],n[e[r-1]],n[i])<=0;)--r;e[r++]=i}return e.slice(0,r)}function qe(n,t){return n[0]-t[0]||n[1]-t[1]}function Te(n,t,e){return(e[0]-t[0])*(n[1]-t[1])<(e[1]-t[1])*(n[0]-t[0])}function Re(n,t,e,r){var i=n[0],u=e[0],o=t[0]-i,a=r[0]-u,l=n[1],c=e[1],f=t[1]-l,s=r[1]-c,h=(a*(l-c)-s*(i-u))/(s*o-a*f);return[i+h*o,l+h*f]}function De(n){var t=n[0],e=n[n.length-1];return!(t[0]-e[0]||t[1]-e[1])}function Pe(){rr(this),this.edge=this.site=this.circle=null}function Ue(n){var t=cl.pop()||new Pe;return t.site=n,t}function je(n){Be(n),ol.remove(n),cl.push(n),rr(n)}function Fe(n){var t=n.circle,e=t.x,r=t.cy,i={x:e,y:r},u=n.P,o=n.N,a=[n];je(n);for(var l=u;l.circle&&xo(e-l.circle.x)<Uo&&xo(r-l.circle.cy)<Uo;)u=l.P,a.unshift(l),je(l),l=u;a.unshift(l),Be(l);for(var c=o;c.circle&&xo(e-c.circle.x)<Uo&&xo(r-c.circle.cy)<Uo;)o=c.N,a.push(c),je(c),c=o;a.push(c),Be(c);var f,s=a.length;for(f=1;s>f;++f)c=a[f],l=a[f-1],nr(c.edge,l.site,c.site,i);l=a[0],c=a[s-1],c.edge=Ke(l.site,c.site,null,i),$e(l),$e(c)}function He(n){for(var t,e,r,i,u=n.x,o=n.y,a=ol._;a;)if(r=Oe(a,o)-u,r>Uo)a=a.L;else{if(i=u-Ie(a,o),!(i>Uo)){r>-Uo?(t=a.P,e=a):i>-Uo?(t=a,e=a.N):t=e=a;break}if(!a.R){t=a;break}a=a.R}var l=Ue(n);if(ol.insert(t,l),t||e){if(t===e)return Be(t),e=Ue(t.site),ol.insert(l,e),l.edge=e.edge=Ke(t.site,l.site),$e(t),void $e(e);if(!e)return void(l.edge=Ke(t.site,l.site));Be(t),Be(e);var c=t.site,f=c.x,s=c.y,h=n.x-f,p=n.y-s,g=e.site,v=g.x-f,d=g.y-s,y=2*(h*d-p*v),m=h*h+p*p,M=v*v+d*d,x={x:(d*m-p*M)/y+f,y:(h*M-v*m)/y+s};nr(e.edge,c,g,x),l.edge=Ke(c,n,null,x),e.edge=Ke(n,g,null,x),$e(t),$e(e)}}function Oe(n,t){var e=n.site,r=e.x,i=e.y,u=i-t;if(!u)return r;var o=n.P;if(!o)return-(1/0);e=o.site;var a=e.x,l=e.y,c=l-t;if(!c)return a;var f=a-r,s=1/u-1/c,h=f/c;return s?(-h+Math.sqrt(h*h-2*s*(f*f/(-2*c)-l+c/2+i-u/2)))/s+r:(r+a)/2}function Ie(n,t){var e=n.N;if(e)return Oe(e,t);var r=n.site;return r.y===t?r.x:1/0}function Ye(n){this.site=n,this.edges=[]}function Ze(n){for(var t,e,r,i,u,o,a,l,c,f,s=n[0][0],h=n[1][0],p=n[0][1],g=n[1][1],v=ul,d=v.length;d--;)if(u=v[d],u&&u.prepare())for(a=u.edges,l=a.length,o=0;l>o;)f=a[o].end(),r=f.x,i=f.y,c=a[++o%l].start(),t=c.x,e=c.y,(xo(r-t)>Uo||xo(i-e)>Uo)&&(a.splice(o,0,new tr(Qe(u.site,f,xo(r-s)<Uo&&g-i>Uo?{x:s,y:xo(t-s)<Uo?e:g}:xo(i-g)<Uo&&h-r>Uo?{x:xo(e-g)<Uo?t:h,y:g}:xo(r-h)<Uo&&i-p>Uo?{x:h,y:xo(t-h)<Uo?e:p}:xo(i-p)<Uo&&r-s>Uo?{x:xo(e-p)<Uo?t:s,y:p}:null),u.site,null)),++l)}function Ve(n,t){return t.angle-n.angle}function Xe(){rr(this),this.x=this.y=this.arc=this.site=this.cy=null}function $e(n){var t=n.P,e=n.N;if(t&&e){var r=t.site,i=n.site,u=e.site;if(r!==u){var o=i.x,a=i.y,l=r.x-o,c=r.y-a,f=u.x-o,s=u.y-a,h=2*(l*s-c*f);if(!(h>=-jo)){var p=l*l+c*c,g=f*f+s*s,v=(s*p-c*g)/h,d=(l*g-f*p)/h,s=d+a,y=fl.pop()||new Xe;y.arc=n,y.site=i,y.x=v+o,y.y=s+Math.sqrt(v*v+d*d),y.cy=s,n.circle=y;for(var m=null,M=ll._;M;)if(y.y<M.y||y.y===M.y&&y.x<=M.x){if(!M.L){m=M.P;break}M=M.L}else{if(!M.R){m=M;break}M=M.R}ll.insert(m,y),m||(al=y)}}}}function Be(n){var t=n.circle;t&&(t.P||(al=t.N),ll.remove(t),fl.push(t),rr(t),n.circle=null)}function We(n){for(var t,e=il,r=Yt(n[0][0],n[0][1],n[1][0],n[1][1]),i=e.length;i--;)t=e[i],(!Je(t,n)||!r(t)||xo(t.a.x-t.b.x)<Uo&&xo(t.a.y-t.b.y)<Uo)&&(t.a=t.b=null,e.splice(i,1))}function Je(n,t){var e=n.b;if(e)return!0;var r,i,u=n.a,o=t[0][0],a=t[1][0],l=t[0][1],c=t[1][1],f=n.l,s=n.r,h=f.x,p=f.y,g=s.x,v=s.y,d=(h+g)/2,y=(p+v)/2;if(v===p){if(o>d||d>=a)return;if(h>g){if(u){if(u.y>=c)return}else u={x:d,y:l};e={x:d,y:c}}else{if(u){if(u.y<l)return}else u={x:d,y:c};e={x:d,y:l}}}else if(r=(h-g)/(v-p),i=y-r*d,-1>r||r>1)if(h>g){if(u){if(u.y>=c)return}else u={x:(l-i)/r,y:l};e={x:(c-i)/r,y:c}}else{if(u){if(u.y<l)return}else u={x:(c-i)/r,y:c};e={x:(l-i)/r,y:l}}else if(v>p){if(u){if(u.x>=a)return}else u={x:o,y:r*o+i};e={x:a,y:r*a+i}}else{if(u){if(u.x<o)return}else u={x:a,y:r*a+i};e={x:o,y:r*o+i}}return n.a=u,n.b=e,!0}function Ge(n,t){this.l=n,this.r=t,this.a=this.b=null}function Ke(n,t,e,r){var i=new Ge(n,t);return il.push(i),e&&nr(i,n,t,e),r&&nr(i,t,n,r),ul[n.i].edges.push(new tr(i,n,t)),ul[t.i].edges.push(new tr(i,t,n)),i}function Qe(n,t,e){var r=new Ge(n,null);return r.a=t,r.b=e,il.push(r),r}function nr(n,t,e,r){n.a||n.b?n.l===e?n.b=r:n.a=r:(n.a=r,n.l=t,n.r=e)}function tr(n,t,e){var r=n.a,i=n.b;this.edge=n,this.site=t,this.angle=e?Math.atan2(e.y-t.y,e.x-t.x):n.l===t?Math.atan2(i.x-r.x,r.y-i.y):Math.atan2(r.x-i.x,i.y-r.y)}function er(){this._=null}function rr(n){n.U=n.C=n.L=n.R=n.P=n.N=null}function ir(n,t){var e=t,r=t.R,i=e.U;i?i.L===e?i.L=r:i.R=r:n._=r,r.U=i,e.U=r,e.R=r.L,e.R&&(e.R.U=e),r.L=e}function ur(n,t){var e=t,r=t.L,i=e.U;i?i.L===e?i.L=r:i.R=r:n._=r,r.U=i,e.U=r,e.L=r.R,e.L&&(e.L.U=e),r.R=e}function or(n){for(;n.L;)n=n.L;return n}function ar(n,t){var e,r,i,u=n.sort(lr).pop();for(il=[],ul=new Array(n.length),ol=new er,ll=new er;;)if(i=al,u&&(!i||u.y<i.y||u.y===i.y&&u.x<i.x))u.x===e&&u.y===r||(ul[u.i]=new Ye(u),He(u),e=u.x,r=u.y),u=n.pop();else{if(!i)break;Fe(i.arc)}t&&(We(t),Ze(t));var o={cells:ul,edges:il};return ol=ll=il=ul=null,o}function lr(n,t){return t.y-n.y||t.x-n.x}function cr(n,t,e){return(n.x-e.x)*(t.y-n.y)-(n.x-t.x)*(e.y-n.y)}function fr(n){return n.x}function sr(n){return n.y}function hr(){return{leaf:!0,nodes:[],point:null,x:null,y:null}}function pr(n,t,e,r,i,u){if(!n(t,e,r,i,u)){var o=.5*(e+i),a=.5*(r+u),l=t.nodes;l[0]&&pr(n,l[0],e,r,o,a),l[1]&&pr(n,l[1],o,r,i,a),l[2]&&pr(n,l[2],e,a,o,u),l[3]&&pr(n,l[3],o,a,i,u)}}function gr(n,t,e,r,i,u,o){var a,l=1/0;return function c(n,f,s,h,p){if(!(f>u||s>o||r>h||i>p)){if(g=n.point){var g,v=t-n.x,d=e-n.y,y=v*v+d*d;if(l>y){var m=Math.sqrt(l=y);r=t-m,i=e-m,u=t+m,o=e+m,a=g}}for(var M=n.nodes,x=.5*(f+h),b=.5*(s+p),_=t>=x,w=e>=b,S=w<<1|_,k=S+4;k>S;++S)if(n=M[3&S])switch(3&S){case 0:c(n,f,s,x,b);break;case 1:c(n,x,s,h,b);break;case 2:c(n,f,b,x,p);break;case 3:c(n,x,b,h,p)}}}(n,r,i,u,o),a}function vr(n,t){n=ao.rgb(n),t=ao.rgb(t);var e=n.r,r=n.g,i=n.b,u=t.r-e,o=t.g-r,a=t.b-i;return function(n){return\"#\"+bn(Math.round(e+u*n))+bn(Math.round(r+o*n))+bn(Math.round(i+a*n))}}function dr(n,t){var e,r={},i={};for(e in n)e in t?r[e]=Mr(n[e],t[e]):i[e]=n[e];for(e in t)e in n||(i[e]=t[e]);return function(n){for(e in r)i[e]=r[e](n);return i}}function yr(n,t){return n=+n,t=+t,function(e){return n*(1-e)+t*e}}function mr(n,t){var e,r,i,u=hl.lastIndex=pl.lastIndex=0,o=-1,a=[],l=[];for(n+=\"\",t+=\"\";(e=hl.exec(n))&&(r=pl.exec(t));)(i=r.index)>u&&(i=t.slice(u,i),a[o]?a[o]+=i:a[++o]=i),(e=e[0])===(r=r[0])?a[o]?a[o]+=r:a[++o]=r:(a[++o]=null,l.push({i:o,x:yr(e,r)})),u=pl.lastIndex;return u<t.length&&(i=t.slice(u),a[o]?a[o]+=i:a[++o]=i),a.length<2?l[0]?(t=l[0].x,function(n){return t(n)+\"\"}):function(){return t}:(t=l.length,function(n){for(var e,r=0;t>r;++r)a[(e=l[r]).i]=e.x(n);return a.join(\"\")})}function Mr(n,t){for(var e,r=ao.interpolators.length;--r>=0&&!(e=ao.interpolators[r](n,t)););return e}function xr(n,t){var e,r=[],i=[],u=n.length,o=t.length,a=Math.min(n.length,t.length);for(e=0;a>e;++e)r.push(Mr(n[e],t[e]));for(;u>e;++e)i[e]=n[e];for(;o>e;++e)i[e]=t[e];return function(n){for(e=0;a>e;++e)i[e]=r[e](n);return i}}function br(n){return function(t){return 0>=t?0:t>=1?1:n(t)}}function _r(n){return function(t){return 1-n(1-t)}}function wr(n){return function(t){return.5*(.5>t?n(2*t):2-n(2-2*t))}}function Sr(n){return n*n}function kr(n){return n*n*n}function Nr(n){if(0>=n)return 0;if(n>=1)return 1;var t=n*n,e=t*n;return 4*(.5>n?e:3*(n-t)+e-.75)}function Er(n){return function(t){return Math.pow(t,n)}}function Ar(n){return 1-Math.cos(n*Io)}function Cr(n){return Math.pow(2,10*(n-1))}function zr(n){return 1-Math.sqrt(1-n*n)}function Lr(n,t){var e;return arguments.length<2&&(t=.45),arguments.length?e=t/Ho*Math.asin(1/n):(n=1,e=t/4),function(r){return 1+n*Math.pow(2,-10*r)*Math.sin((r-e)*Ho/t)}}function qr(n){return n||(n=1.70158),function(t){return t*t*((n+1)*t-n)}}function Tr(n){return 1/2.75>n?7.5625*n*n:2/2.75>n?7.5625*(n-=1.5/2.75)*n+.75:2.5/2.75>n?7.5625*(n-=2.25/2.75)*n+.9375:7.5625*(n-=2.625/2.75)*n+.984375}function Rr(n,t){n=ao.hcl(n),t=ao.hcl(t);var e=n.h,r=n.c,i=n.l,u=t.h-e,o=t.c-r,a=t.l-i;return isNaN(o)&&(o=0,r=isNaN(r)?t.c:r),isNaN(u)?(u=0,e=isNaN(e)?t.h:e):u>180?u-=360:-180>u&&(u+=360),function(n){return sn(e+u*n,r+o*n,i+a*n)+\"\"}}function Dr(n,t){n=ao.hsl(n),t=ao.hsl(t);var e=n.h,r=n.s,i=n.l,u=t.h-e,o=t.s-r,a=t.l-i;return isNaN(o)&&(o=0,r=isNaN(r)?t.s:r),isNaN(u)?(u=0,e=isNaN(e)?t.h:e):u>180?u-=360:-180>u&&(u+=360),function(n){return cn(e+u*n,r+o*n,i+a*n)+\"\"}}function Pr(n,t){n=ao.lab(n),t=ao.lab(t);var e=n.l,r=n.a,i=n.b,u=t.l-e,o=t.a-r,a=t.b-i;return function(n){return pn(e+u*n,r+o*n,i+a*n)+\"\"}}function Ur(n,t){return t-=n,function(e){return Math.round(n+t*e)}}function jr(n){var t=[n.a,n.b],e=[n.c,n.d],r=Hr(t),i=Fr(t,e),u=Hr(Or(e,t,-i))||0;t[0]*e[1]<e[0]*t[1]&&(t[0]*=-1,t[1]*=-1,r*=-1,i*=-1),this.rotate=(r?Math.atan2(t[1],t[0]):Math.atan2(-e[0],e[1]))*Zo,this.translate=[n.e,n.f],this.scale=[r,u],this.skew=u?Math.atan2(i,u)*Zo:0}function Fr(n,t){return n[0]*t[0]+n[1]*t[1]}function Hr(n){var t=Math.sqrt(Fr(n,n));return t&&(n[0]/=t,n[1]/=t),t}function Or(n,t,e){return n[0]+=e*t[0],n[1]+=e*t[1],n}function Ir(n){return n.length?n.pop()+\",\":\"\"}function Yr(n,t,e,r){if(n[0]!==t[0]||n[1]!==t[1]){var i=e.push(\"translate(\",null,\",\",null,\")\");r.push({i:i-4,x:yr(n[0],t[0])},{i:i-2,x:yr(n[1],t[1])})}else(t[0]||t[1])&&e.push(\"translate(\"+t+\")\")}function Zr(n,t,e,r){n!==t?(n-t>180?t+=360:t-n>180&&(n+=360),r.push({i:e.push(Ir(e)+\"rotate(\",null,\")\")-2,x:yr(n,t)})):t&&e.push(Ir(e)+\"rotate(\"+t+\")\")}function Vr(n,t,e,r){n!==t?r.push({i:e.push(Ir(e)+\"skewX(\",null,\")\")-2,x:yr(n,t)}):t&&e.push(Ir(e)+\"skewX(\"+t+\")\")}function Xr(n,t,e,r){if(n[0]!==t[0]||n[1]!==t[1]){var i=e.push(Ir(e)+\"scale(\",null,\",\",null,\")\");r.push({i:i-4,x:yr(n[0],t[0])},{i:i-2,x:yr(n[1],t[1])})}else 1===t[0]&&1===t[1]||e.push(Ir(e)+\"scale(\"+t+\")\")}function $r(n,t){var e=[],r=[];return n=ao.transform(n),t=ao.transform(t),Yr(n.translate,t.translate,e,r),Zr(n.rotate,t.rotate,e,r),Vr(n.skew,t.skew,e,r),Xr(n.scale,t.scale,e,r),n=t=null,function(n){for(var t,i=-1,u=r.length;++i<u;)e[(t=r[i]).i]=t.x(n);return e.join(\"\")}}function Br(n,t){return t=(t-=n=+n)||1/t,function(e){return(e-n)/t}}function Wr(n,t){return t=(t-=n=+n)||1/t,function(e){return Math.max(0,Math.min(1,(e-n)/t))}}function Jr(n){for(var t=n.source,e=n.target,r=Kr(t,e),i=[t];t!==r;)t=t.parent,i.push(t);for(var u=i.length;e!==r;)i.splice(u,0,e),e=e.parent;return i}function Gr(n){for(var t=[],e=n.parent;null!=e;)t.push(n),n=e,e=e.parent;return t.push(n),t}function Kr(n,t){if(n===t)return n;for(var e=Gr(n),r=Gr(t),i=e.pop(),u=r.pop(),o=null;i===u;)o=i,i=e.pop(),u=r.pop();return o}function Qr(n){n.fixed|=2}function ni(n){n.fixed&=-7}function ti(n){n.fixed|=4,n.px=n.x,n.py=n.y}function ei(n){n.fixed&=-5}function ri(n,t,e){var r=0,i=0;if(n.charge=0,!n.leaf)for(var u,o=n.nodes,a=o.length,l=-1;++l<a;)u=o[l],null!=u&&(ri(u,t,e),n.charge+=u.charge,r+=u.charge*u.cx,i+=u.charge*u.cy);if(n.point){n.leaf||(n.point.x+=Math.random()-.5,n.point.y+=Math.random()-.5);var c=t*e[n.point.index];n.charge+=n.pointCharge=c,r+=c*n.point.x,i+=c*n.point.y}n.cx=r/n.charge,n.cy=i/n.charge}function ii(n,t){return ao.rebind(n,t,\"sort\",\"children\",\"value\"),n.nodes=n,n.links=fi,n}function ui(n,t){for(var e=[n];null!=(n=e.pop());)if(t(n),(i=n.children)&&(r=i.length))for(var r,i;--r>=0;)e.push(i[r])}function oi(n,t){for(var e=[n],r=[];null!=(n=e.pop());)if(r.push(n),(u=n.children)&&(i=u.length))for(var i,u,o=-1;++o<i;)e.push(u[o]);for(;null!=(n=r.pop());)t(n)}function ai(n){return n.children}function li(n){return n.value}function ci(n,t){return t.value-n.value}function fi(n){return ao.merge(n.map(function(n){return(n.children||[]).map(function(t){return{source:n,target:t}})}))}function si(n){return n.x}function hi(n){return n.y}function pi(n,t,e){n.y0=t,n.y=e}function gi(n){return ao.range(n.length)}function vi(n){for(var t=-1,e=n[0].length,r=[];++t<e;)r[t]=0;return r}function di(n){for(var t,e=1,r=0,i=n[0][1],u=n.length;u>e;++e)(t=n[e][1])>i&&(r=e,i=t);return r}function yi(n){return n.reduce(mi,0)}function mi(n,t){return n+t[1]}function Mi(n,t){return xi(n,Math.ceil(Math.log(t.length)/Math.LN2+1))}function xi(n,t){for(var e=-1,r=+n[0],i=(n[1]-r)/t,u=[];++e<=t;)u[e]=i*e+r;return u}function bi(n){return[ao.min(n),ao.max(n)]}function _i(n,t){return n.value-t.value}function wi(n,t){var e=n._pack_next;n._pack_next=t,t._pack_prev=n,t._pack_next=e,e._pack_prev=t}function Si(n,t){n._pack_next=t,t._pack_prev=n}function ki(n,t){var e=t.x-n.x,r=t.y-n.y,i=n.r+t.r;return.999*i*i>e*e+r*r}function Ni(n){function t(n){f=Math.min(n.x-n.r,f),s=Math.max(n.x+n.r,s),h=Math.min(n.y-n.r,h),p=Math.max(n.y+n.r,p)}if((e=n.children)&&(c=e.length)){var e,r,i,u,o,a,l,c,f=1/0,s=-(1/0),h=1/0,p=-(1/0);if(e.forEach(Ei),r=e[0],r.x=-r.r,r.y=0,t(r),c>1&&(i=e[1],i.x=i.r,i.y=0,t(i),c>2))for(u=e[2],zi(r,i,u),t(u),wi(r,u),r._pack_prev=u,wi(u,i),i=r._pack_next,o=3;c>o;o++){zi(r,i,u=e[o]);var g=0,v=1,d=1;for(a=i._pack_next;a!==i;a=a._pack_next,v++)if(ki(a,u)){g=1;break}if(1==g)for(l=r._pack_prev;l!==a._pack_prev&&!ki(l,u);l=l._pack_prev,d++);g?(d>v||v==d&&i.r<r.r?Si(r,i=a):Si(r=l,i),o--):(wi(r,u),i=u,t(u))}var y=(f+s)/2,m=(h+p)/2,M=0;for(o=0;c>o;o++)u=e[o],u.x-=y,u.y-=m,M=Math.max(M,u.r+Math.sqrt(u.x*u.x+u.y*u.y));n.r=M,e.forEach(Ai)}}function Ei(n){n._pack_next=n._pack_prev=n}function Ai(n){delete n._pack_next,delete n._pack_prev}function Ci(n,t,e,r){var i=n.children;if(n.x=t+=r*n.x,n.y=e+=r*n.y,n.r*=r,i)for(var u=-1,o=i.length;++u<o;)Ci(i[u],t,e,r)}function zi(n,t,e){var r=n.r+e.r,i=t.x-n.x,u=t.y-n.y;if(r&&(i||u)){var o=t.r+e.r,a=i*i+u*u;o*=o,r*=r;var l=.5+(r-o)/(2*a),c=Math.sqrt(Math.max(0,2*o*(r+a)-(r-=a)*r-o*o))/(2*a);e.x=n.x+l*i+c*u,e.y=n.y+l*u-c*i}else e.x=n.x+r,e.y=n.y}function Li(n,t){return n.parent==t.parent?1:2}function qi(n){var t=n.children;return t.length?t[0]:n.t}function Ti(n){var t,e=n.children;return(t=e.length)?e[t-1]:n.t}function Ri(n,t,e){var r=e/(t.i-n.i);t.c-=r,t.s+=e,n.c+=r,t.z+=e,t.m+=e}function Di(n){for(var t,e=0,r=0,i=n.children,u=i.length;--u>=0;)t=i[u],t.z+=e,t.m+=e,e+=t.s+(r+=t.c)}function Pi(n,t,e){return n.a.parent===t.parent?n.a:e}function Ui(n){return 1+ao.max(n,function(n){return n.y})}function ji(n){return n.reduce(function(n,t){return n+t.x},0)/n.length}function Fi(n){var t=n.children;return t&&t.length?Fi(t[0]):n}function Hi(n){var t,e=n.children;return e&&(t=e.length)?Hi(e[t-1]):n}function Oi(n){return{x:n.x,y:n.y,dx:n.dx,dy:n.dy}}function Ii(n,t){var e=n.x+t[3],r=n.y+t[0],i=n.dx-t[1]-t[3],u=n.dy-t[0]-t[2];return 0>i&&(e+=i/2,i=0),0>u&&(r+=u/2,u=0),{x:e,y:r,dx:i,dy:u}}function Yi(n){var t=n[0],e=n[n.length-1];return e>t?[t,e]:[e,t]}function Zi(n){return n.rangeExtent?n.rangeExtent():Yi(n.range())}function Vi(n,t,e,r){var i=e(n[0],n[1]),u=r(t[0],t[1]);return function(n){return u(i(n))}}function Xi(n,t){var e,r=0,i=n.length-1,u=n[r],o=n[i];return u>o&&(e=r,r=i,i=e,e=u,u=o,o=e),n[r]=t.floor(u),n[i]=t.ceil(o),n}function $i(n){return n?{floor:function(t){return Math.floor(t/n)*n},ceil:function(t){return Math.ceil(t/n)*n}}:Sl}function Bi(n,t,e,r){var i=[],u=[],o=0,a=Math.min(n.length,t.length)-1;for(n[a]<n[0]&&(n=n.slice().reverse(),t=t.slice().reverse());++o<=a;)i.push(e(n[o-1],n[o])),u.push(r(t[o-1],t[o]));return function(t){var e=ao.bisect(n,t,1,a)-1;return u[e](i[e](t))}}function Wi(n,t,e,r){function i(){var i=Math.min(n.length,t.length)>2?Bi:Vi,l=r?Wr:Br;return o=i(n,t,l,e),a=i(t,n,l,Mr),u}function u(n){return o(n)}var o,a;return u.invert=function(n){return a(n)},u.domain=function(t){return arguments.length?(n=t.map(Number),i()):n},u.range=function(n){return arguments.length?(t=n,i()):t},u.rangeRound=function(n){return u.range(n).interpolate(Ur)},u.clamp=function(n){return arguments.length?(r=n,i()):r},u.interpolate=function(n){return arguments.length?(e=n,i()):e},u.ticks=function(t){return Qi(n,t)},u.tickFormat=function(t,e){return nu(n,t,e)},u.nice=function(t){return Gi(n,t),i()},u.copy=function(){return Wi(n,t,e,r)},i()}function Ji(n,t){return ao.rebind(n,t,\"range\",\"rangeRound\",\"interpolate\",\"clamp\")}function Gi(n,t){return Xi(n,$i(Ki(n,t)[2])),Xi(n,$i(Ki(n,t)[2])),n}function Ki(n,t){null==t&&(t=10);var e=Yi(n),r=e[1]-e[0],i=Math.pow(10,Math.floor(Math.log(r/t)/Math.LN10)),u=t/r*i;return.15>=u?i*=10:.35>=u?i*=5:.75>=u&&(i*=2),e[0]=Math.ceil(e[0]/i)*i,e[1]=Math.floor(e[1]/i)*i+.5*i,e[2]=i,e}function Qi(n,t){return ao.range.apply(ao,Ki(n,t))}function nu(n,t,e){var r=Ki(n,t);if(e){var i=ha.exec(e);if(i.shift(),\"s\"===i[8]){var u=ao.formatPrefix(Math.max(xo(r[0]),xo(r[1])));return i[7]||(i[7]=\".\"+tu(u.scale(r[2]))),i[8]=\"f\",e=ao.format(i.join(\"\")),function(n){return e(u.scale(n))+u.symbol}}i[7]||(i[7]=\".\"+eu(i[8],r)),e=i.join(\"\")}else e=\",.\"+tu(r[2])+\"f\";return ao.format(e)}function tu(n){return-Math.floor(Math.log(n)/Math.LN10+.01)}function eu(n,t){var e=tu(t[2]);return n in kl?Math.abs(e-tu(Math.max(xo(t[0]),xo(t[1]))))+ +(\"e\"!==n):e-2*(\"%\"===n)}function ru(n,t,e,r){function i(n){return(e?Math.log(0>n?0:n):-Math.log(n>0?0:-n))/Math.log(t)}function u(n){return e?Math.pow(t,n):-Math.pow(t,-n)}function o(t){return n(i(t))}return o.invert=function(t){return u(n.invert(t))},o.domain=function(t){return arguments.length?(e=t[0]>=0,n.domain((r=t.map(Number)).map(i)),o):r},o.base=function(e){return arguments.length?(t=+e,n.domain(r.map(i)),o):t},o.nice=function(){var t=Xi(r.map(i),e?Math:El);return n.domain(t),r=t.map(u),o},o.ticks=function(){var n=Yi(r),o=[],a=n[0],l=n[1],c=Math.floor(i(a)),f=Math.ceil(i(l)),s=t%1?2:t;if(isFinite(f-c)){if(e){for(;f>c;c++)for(var h=1;s>h;h++)o.push(u(c)*h);o.push(u(c))}else for(o.push(u(c));c++<f;)for(var h=s-1;h>0;h--)o.push(u(c)*h);for(c=0;o[c]<a;c++);for(f=o.length;o[f-1]>l;f--);o=o.slice(c,f)}return o},o.tickFormat=function(n,e){if(!arguments.length)return Nl;arguments.length<2?e=Nl:\"function\"!=typeof e&&(e=ao.format(e));var r=Math.max(1,t*n/o.ticks().length);return function(n){var o=n/u(Math.round(i(n)));return t-.5>o*t&&(o*=t),r>=o?e(n):\"\"}},o.copy=function(){return ru(n.copy(),t,e,r)},Ji(o,n)}function iu(n,t,e){function r(t){return n(i(t))}var i=uu(t),u=uu(1/t);return r.invert=function(t){return u(n.invert(t))},r.domain=function(t){return arguments.length?(n.domain((e=t.map(Number)).map(i)),r):e},r.ticks=function(n){return Qi(e,n)},r.tickFormat=function(n,t){return nu(e,n,t)},r.nice=function(n){return r.domain(Gi(e,n))},r.exponent=function(o){return arguments.length?(i=uu(t=o),u=uu(1/t),n.domain(e.map(i)),r):t},r.copy=function(){return iu(n.copy(),t,e)},Ji(r,n)}function uu(n){return function(t){return 0>t?-Math.pow(-t,n):Math.pow(t,n)}}function ou(n,t){function e(e){return u[((i.get(e)||(\"range\"===t.t?i.set(e,n.push(e)):NaN))-1)%u.length]}function r(t,e){return ao.range(n.length).map(function(n){return t+e*n})}var i,u,o;return e.domain=function(r){if(!arguments.length)return n;n=[],i=new c;for(var u,o=-1,a=r.length;++o<a;)i.has(u=r[o])||i.set(u,n.push(u));return e[t.t].apply(e,t.a)},e.range=function(n){return arguments.length?(u=n,o=0,t={t:\"range\",a:arguments},e):u},e.rangePoints=function(i,a){arguments.length<2&&(a=0);var l=i[0],c=i[1],f=n.length<2?(l=(l+c)/2,0):(c-l)/(n.length-1+a);return u=r(l+f*a/2,f),o=0,t={t:\"rangePoints\",a:arguments},e},e.rangeRoundPoints=function(i,a){arguments.length<2&&(a=0);var l=i[0],c=i[1],f=n.length<2?(l=c=Math.round((l+c)/2),0):(c-l)/(n.length-1+a)|0;return u=r(l+Math.round(f*a/2+(c-l-(n.length-1+a)*f)/2),f),o=0,t={t:\"rangeRoundPoints\",a:arguments},e},e.rangeBands=function(i,a,l){arguments.length<2&&(a=0),arguments.length<3&&(l=a);var c=i[1]<i[0],f=i[c-0],s=i[1-c],h=(s-f)/(n.length-a+2*l);return u=r(f+h*l,h),c&&u.reverse(),o=h*(1-a),t={t:\"rangeBands\",a:arguments},e},e.rangeRoundBands=function(i,a,l){arguments.length<2&&(a=0),arguments.length<3&&(l=a);var c=i[1]<i[0],f=i[c-0],s=i[1-c],h=Math.floor((s-f)/(n.length-a+2*l));return u=r(f+Math.round((s-f-(n.length-a)*h)/2),h),c&&u.reverse(),o=Math.round(h*(1-a)),t={t:\"rangeRoundBands\",a:arguments},e},e.rangeBand=function(){return o},e.rangeExtent=function(){return Yi(t.a[0])},e.copy=function(){return ou(n,t)},e.domain(n)}function au(n,t){function u(){var e=0,r=t.length;for(a=[];++e<r;)a[e-1]=ao.quantile(n,e/r);return o}function o(n){return isNaN(n=+n)?void 0:t[ao.bisect(a,n)]}var a;return o.domain=function(t){return arguments.length?(n=t.map(r).filter(i).sort(e),u()):n},o.range=function(n){return arguments.length?(t=n,u()):t},o.quantiles=function(){return a},o.invertExtent=function(e){return e=t.indexOf(e),0>e?[NaN,NaN]:[e>0?a[e-1]:n[0],e<a.length?a[e]:n[n.length-1]]},o.copy=function(){return au(n,t)},u()}function lu(n,t,e){function r(t){return e[Math.max(0,Math.min(o,Math.floor(u*(t-n))))]}function i(){return u=e.length/(t-n),o=e.length-1,r}var u,o;return r.domain=function(e){return arguments.length?(n=+e[0],t=+e[e.length-1],i()):[n,t]},r.range=function(n){return arguments.length?(e=n,i()):e},r.invertExtent=function(t){return t=e.indexOf(t),t=0>t?NaN:t/u+n,[t,t+1/u]},r.copy=function(){return lu(n,t,e)},i()}function cu(n,t){function e(e){return e>=e?t[ao.bisect(n,e)]:void 0}return e.domain=function(t){return arguments.length?(n=t,e):n},e.range=function(n){return arguments.length?(t=n,e):t},e.invertExtent=function(e){return e=t.indexOf(e),[n[e-1],n[e]]},e.copy=function(){return cu(n,t)},e}function fu(n){function t(n){return+n}return t.invert=t,t.domain=t.range=function(e){return arguments.length?(n=e.map(t),t):n},t.ticks=function(t){return Qi(n,t)},t.tickFormat=function(t,e){return nu(n,t,e)},t.copy=function(){return fu(n)},t}function su(){return 0}function hu(n){return n.innerRadius}function pu(n){return n.outerRadius}function gu(n){return n.startAngle}function vu(n){return n.endAngle}function du(n){return n&&n.padAngle}function yu(n,t,e,r){return(n-e)*t-(t-r)*n>0?0:1}function mu(n,t,e,r,i){var u=n[0]-t[0],o=n[1]-t[1],a=(i?r:-r)/Math.sqrt(u*u+o*o),l=a*o,c=-a*u,f=n[0]+l,s=n[1]+c,h=t[0]+l,p=t[1]+c,g=(f+h)/2,v=(s+p)/2,d=h-f,y=p-s,m=d*d+y*y,M=e-r,x=f*p-h*s,b=(0>y?-1:1)*Math.sqrt(Math.max(0,M*M*m-x*x)),_=(x*y-d*b)/m,w=(-x*d-y*b)/m,S=(x*y+d*b)/m,k=(-x*d+y*b)/m,N=_-g,E=w-v,A=S-g,C=k-v;return N*N+E*E>A*A+C*C&&(_=S,w=k),[[_-l,w-c],[_*e/M,w*e/M]]}function Mu(n){function t(t){function o(){c.push(\"M\",u(n(f),a))}for(var l,c=[],f=[],s=-1,h=t.length,p=En(e),g=En(r);++s<h;)i.call(this,l=t[s],s)?f.push([+p.call(this,l,s),+g.call(this,l,s)]):f.length&&(o(),f=[]);return f.length&&o(),c.length?c.join(\"\"):null}var e=Ce,r=ze,i=zt,u=xu,o=u.key,a=.7;return t.x=function(n){return arguments.length?(e=n,t):e},t.y=function(n){return arguments.length?(r=n,t):r},t.defined=function(n){return arguments.length?(i=n,t):i},t.interpolate=function(n){return arguments.length?(o=\"function\"==typeof n?u=n:(u=Tl.get(n)||xu).key,t):o},t.tension=function(n){return arguments.length?(a=n,t):a},t}function xu(n){return n.length>1?n.join(\"L\"):n+\"Z\"}function bu(n){return n.join(\"L\")+\"Z\"}function _u(n){for(var t=0,e=n.length,r=n[0],i=[r[0],\",\",r[1]];++t<e;)i.push(\"H\",(r[0]+(r=n[t])[0])/2,\"V\",r[1]);return e>1&&i.push(\"H\",r[0]),i.join(\"\")}function wu(n){for(var t=0,e=n.length,r=n[0],i=[r[0],\",\",r[1]];++t<e;)i.push(\"V\",(r=n[t])[1],\"H\",r[0]);return i.join(\"\")}function Su(n){for(var t=0,e=n.length,r=n[0],i=[r[0],\",\",r[1]];++t<e;)i.push(\"H\",(r=n[t])[0],\"V\",r[1]);return i.join(\"\")}function ku(n,t){return n.length<4?xu(n):n[1]+Au(n.slice(1,-1),Cu(n,t))}function Nu(n,t){return n.length<3?bu(n):n[0]+Au((n.push(n[0]),n),Cu([n[n.length-2]].concat(n,[n[1]]),t))}function Eu(n,t){return n.length<3?xu(n):n[0]+Au(n,Cu(n,t))}function Au(n,t){if(t.length<1||n.length!=t.length&&n.length!=t.length+2)return xu(n);var e=n.length!=t.length,r=\"\",i=n[0],u=n[1],o=t[0],a=o,l=1;if(e&&(r+=\"Q\"+(u[0]-2*o[0]/3)+\",\"+(u[1]-2*o[1]/3)+\",\"+u[0]+\",\"+u[1],i=n[1],l=2),t.length>1){a=t[1],u=n[l],l++,r+=\"C\"+(i[0]+o[0])+\",\"+(i[1]+o[1])+\",\"+(u[0]-a[0])+\",\"+(u[1]-a[1])+\",\"+u[0]+\",\"+u[1];for(var c=2;c<t.length;c++,l++)u=n[l],a=t[c],r+=\"S\"+(u[0]-a[0])+\",\"+(u[1]-a[1])+\",\"+u[0]+\",\"+u[1]}if(e){var f=n[l];r+=\"Q\"+(u[0]+2*a[0]/3)+\",\"+(u[1]+2*a[1]/3)+\",\"+f[0]+\",\"+f[1]}return r}function Cu(n,t){for(var e,r=[],i=(1-t)/2,u=n[0],o=n[1],a=1,l=n.length;++a<l;)e=u,u=o,o=n[a],r.push([i*(o[0]-e[0]),i*(o[1]-e[1])]);return r}function zu(n){if(n.length<3)return xu(n);var t=1,e=n.length,r=n[0],i=r[0],u=r[1],o=[i,i,i,(r=n[1])[0]],a=[u,u,u,r[1]],l=[i,\",\",u,\"L\",Ru(Pl,o),\",\",Ru(Pl,a)];for(n.push(n[e-1]);++t<=e;)r=n[t],o.shift(),o.push(r[0]),a.shift(),a.push(r[1]),Du(l,o,a);return n.pop(),l.push(\"L\",r),l.join(\"\")}function Lu(n){if(n.length<4)return xu(n);for(var t,e=[],r=-1,i=n.length,u=[0],o=[0];++r<3;)t=n[r],u.push(t[0]),o.push(t[1]);for(e.push(Ru(Pl,u)+\",\"+Ru(Pl,o)),--r;++r<i;)t=n[r],u.shift(),u.push(t[0]),o.shift(),o.push(t[1]),Du(e,u,o);return e.join(\"\")}function qu(n){for(var t,e,r=-1,i=n.length,u=i+4,o=[],a=[];++r<4;)e=n[r%i],o.push(e[0]),a.push(e[1]);for(t=[Ru(Pl,o),\",\",Ru(Pl,a)],--r;++r<u;)e=n[r%i],o.shift(),o.push(e[0]),a.shift(),a.push(e[1]),Du(t,o,a);return t.join(\"\")}function Tu(n,t){var e=n.length-1;if(e)for(var r,i,u=n[0][0],o=n[0][1],a=n[e][0]-u,l=n[e][1]-o,c=-1;++c<=e;)r=n[c],i=c/e,r[0]=t*r[0]+(1-t)*(u+i*a),r[1]=t*r[1]+(1-t)*(o+i*l);return zu(n)}function Ru(n,t){return n[0]*t[0]+n[1]*t[1]+n[2]*t[2]+n[3]*t[3]}function Du(n,t,e){n.push(\"C\",Ru(Rl,t),\",\",Ru(Rl,e),\",\",Ru(Dl,t),\",\",Ru(Dl,e),\",\",Ru(Pl,t),\",\",Ru(Pl,e))}function Pu(n,t){return(t[1]-n[1])/(t[0]-n[0])}function Uu(n){for(var t=0,e=n.length-1,r=[],i=n[0],u=n[1],o=r[0]=Pu(i,u);++t<e;)r[t]=(o+(o=Pu(i=u,u=n[t+1])))/2;return r[t]=o,r}function ju(n){for(var t,e,r,i,u=[],o=Uu(n),a=-1,l=n.length-1;++a<l;)t=Pu(n[a],n[a+1]),xo(t)<Uo?o[a]=o[a+1]=0:(e=o[a]/t,r=o[a+1]/t,i=e*e+r*r,i>9&&(i=3*t/Math.sqrt(i),o[a]=i*e,o[a+1]=i*r));for(a=-1;++a<=l;)i=(n[Math.min(l,a+1)][0]-n[Math.max(0,a-1)][0])/(6*(1+o[a]*o[a])),u.push([i||0,o[a]*i||0]);return u}function Fu(n){return n.length<3?xu(n):n[0]+Au(n,ju(n))}function Hu(n){for(var t,e,r,i=-1,u=n.length;++i<u;)t=n[i],e=t[0],r=t[1]-Io,t[0]=e*Math.cos(r),t[1]=e*Math.sin(r);return n}function Ou(n){function t(t){function l(){v.push(\"M\",a(n(y),s),f,c(n(d.reverse()),s),\"Z\")}for(var h,p,g,v=[],d=[],y=[],m=-1,M=t.length,x=En(e),b=En(i),_=e===r?function(){return p}:En(r),w=i===u?function(){return g}:En(u);++m<M;)o.call(this,h=t[m],m)?(d.push([p=+x.call(this,h,m),g=+b.call(this,h,m)]),y.push([+_.call(this,h,m),+w.call(this,h,m)])):d.length&&(l(),d=[],y=[]);return d.length&&l(),v.length?v.join(\"\"):null}var e=Ce,r=Ce,i=0,u=ze,o=zt,a=xu,l=a.key,c=a,f=\"L\",s=.7;return t.x=function(n){return arguments.length?(e=r=n,t):r},t.x0=function(n){return arguments.length?(e=n,t):e},t.x1=function(n){return arguments.length?(r=n,t):r},t.y=function(n){return arguments.length?(i=u=n,t):u},t.y0=function(n){return arguments.length?(i=n,t):i},t.y1=function(n){return arguments.length?(u=n,t):u},t.defined=function(n){return arguments.length?(o=n,t):o},t.interpolate=function(n){return arguments.length?(l=\"function\"==typeof n?a=n:(a=Tl.get(n)||xu).key,c=a.reverse||a,f=a.closed?\"M\":\"L\",t):l},t.tension=function(n){return arguments.length?(s=n,t):s},t}function Iu(n){return n.radius}function Yu(n){return[n.x,n.y]}function Zu(n){return function(){var t=n.apply(this,arguments),e=t[0],r=t[1]-Io;return[e*Math.cos(r),e*Math.sin(r)]}}function Vu(){return 64}function Xu(){return\"circle\"}function $u(n){var t=Math.sqrt(n/Fo);return\"M0,\"+t+\"A\"+t+\",\"+t+\" 0 1,1 0,\"+-t+\"A\"+t+\",\"+t+\" 0 1,1 0,\"+t+\"Z\"}function Bu(n){return function(){var t,e,r;(t=this[n])&&(r=t[e=t.active])&&(r.timer.c=null,r.timer.t=NaN,--t.count?delete t[e]:delete this[n],t.active+=.5,r.event&&r.event.interrupt.call(this,this.__data__,r.index))}}function Wu(n,t,e){return ko(n,Yl),n.namespace=t,n.id=e,n}function Ju(n,t,e,r){var i=n.id,u=n.namespace;return Y(n,\"function\"==typeof e?function(n,o,a){n[u][i].tween.set(t,r(e.call(n,n.__data__,o,a)))}:(e=r(e),function(n){n[u][i].tween.set(t,e)}))}function Gu(n){return null==n&&(n=\"\"),function(){this.textContent=n}}function Ku(n){return null==n?\"__transition__\":\"__transition_\"+n+\"__\"}function Qu(n,t,e,r,i){function u(n){var t=v.delay;return f.t=t+l,n>=t?o(n-t):void(f.c=o)}function o(e){var i=g.active,u=g[i];u&&(u.timer.c=null,u.timer.t=NaN,--g.count,delete g[i],u.event&&u.event.interrupt.call(n,n.__data__,u.index));for(var o in g)if(r>+o){var c=g[o];c.timer.c=null,c.timer.t=NaN,--g.count,delete g[o]}f.c=a,qn(function(){return f.c&&a(e||1)&&(f.c=null,f.t=NaN),1},0,l),g.active=r,v.event&&v.event.start.call(n,n.__data__,t),p=[],v.tween.forEach(function(e,r){(r=r.call(n,n.__data__,t))&&p.push(r)}),h=v.ease,s=v.duration}function a(i){for(var u=i/s,o=h(u),a=p.length;a>0;)p[--a].call(n,o);return u>=1?(v.event&&v.event.end.call(n,n.__data__,t),--g.count?delete g[r]:delete n[e],1):void 0}var l,f,s,h,p,g=n[e]||(n[e]={active:0,count:0}),v=g[r];v||(l=i.time,f=qn(u,0,l),v=g[r]={tween:new c,time:l,timer:f,delay:i.delay,duration:i.duration,ease:i.ease,index:t},i=null,++g.count)}function no(n,t,e){n.attr(\"transform\",function(n){var r=t(n);return\"translate(\"+(isFinite(r)?r:e(n))+\",0)\"})}function to(n,t,e){n.attr(\"transform\",function(n){var r=t(n);return\"translate(0,\"+(isFinite(r)?r:e(n))+\")\"})}function eo(n){return n.toISOString()}function ro(n,t,e){function r(t){return n(t)}function i(n,e){var r=n[1]-n[0],i=r/e,u=ao.bisect(Kl,i);return u==Kl.length?[t.year,Ki(n.map(function(n){return n/31536e6}),e)[2]]:u?t[i/Kl[u-1]<Kl[u]/i?u-1:u]:[tc,Ki(n,e)[2]]}return r.invert=function(t){return io(n.invert(t))},r.domain=function(t){return arguments.length?(n.domain(t),r):n.domain().map(io)},r.nice=function(n,t){function e(e){return!isNaN(e)&&!n.range(e,io(+e+1),t).length}var u=r.domain(),o=Yi(u),a=null==n?i(o,10):\"number\"==typeof n&&i(o,n);return a&&(n=a[0],t=a[1]),r.domain(Xi(u,t>1?{floor:function(t){for(;e(t=n.floor(t));)t=io(t-1);return t},ceil:function(t){for(;e(t=n.ceil(t));)t=io(+t+1);return t}}:n))},r.ticks=function(n,t){var e=Yi(r.domain()),u=null==n?i(e,10):\"number\"==typeof n?i(e,n):!n.range&&[{range:n},t];return u&&(n=u[0],t=u[1]),n.range(e[0],io(+e[1]+1),1>t?1:t)},r.tickFormat=function(){return e},r.copy=function(){return ro(n.copy(),t,e)},Ji(r,n)}function io(n){return new Date(n)}function uo(n){return JSON.parse(n.responseText)}function oo(n){var t=fo.createRange();return t.selectNode(fo.body),t.createContextualFragment(n.responseText)}var ao={version:\"3.5.17\"},lo=[].slice,co=function(n){return lo.call(n)},fo=this.document;if(fo)try{co(fo.documentElement.childNodes)[0].nodeType}catch(so){co=function(n){for(var t=n.length,e=new Array(t);t--;)e[t]=n[t];return e}}if(Date.now||(Date.now=function(){return+new Date}),fo)try{fo.createElement(\"DIV\").style.setProperty(\"opacity\",0,\"\")}catch(ho){var po=this.Element.prototype,go=po.setAttribute,vo=po.setAttributeNS,yo=this.CSSStyleDeclaration.prototype,mo=yo.setProperty;po.setAttribute=function(n,t){go.call(this,n,t+\"\")},po.setAttributeNS=function(n,t,e){vo.call(this,n,t,e+\"\")},yo.setProperty=function(n,t,e){mo.call(this,n,t+\"\",e)}}ao.ascending=e,ao.descending=function(n,t){return n>t?-1:t>n?1:t>=n?0:NaN},ao.min=function(n,t){var e,r,i=-1,u=n.length;if(1===arguments.length){for(;++i<u;)if(null!=(r=n[i])&&r>=r){e=r;break}for(;++i<u;)null!=(r=n[i])&&e>r&&(e=r)}else{for(;++i<u;)if(null!=(r=t.call(n,n[i],i))&&r>=r){e=r;break}for(;++i<u;)null!=(r=t.call(n,n[i],i))&&e>r&&(e=r)}return e},ao.max=function(n,t){var e,r,i=-1,u=n.length;if(1===arguments.length){for(;++i<u;)if(null!=(r=n[i])&&r>=r){e=r;break}for(;++i<u;)null!=(r=n[i])&&r>e&&(e=r)}else{for(;++i<u;)if(null!=(r=t.call(n,n[i],i))&&r>=r){e=r;break}for(;++i<u;)null!=(r=t.call(n,n[i],i))&&r>e&&(e=r)}return e},ao.extent=function(n,t){var e,r,i,u=-1,o=n.length;if(1===arguments.length){for(;++u<o;)if(null!=(r=n[u])&&r>=r){e=i=r;break}for(;++u<o;)null!=(r=n[u])&&(e>r&&(e=r),r>i&&(i=r))}else{for(;++u<o;)if(null!=(r=t.call(n,n[u],u))&&r>=r){e=i=r;break}for(;++u<o;)null!=(r=t.call(n,n[u],u))&&(e>r&&(e=r),r>i&&(i=r))}return[e,i]},ao.sum=function(n,t){var e,r=0,u=n.length,o=-1;if(1===arguments.length)for(;++o<u;)i(e=+n[o])&&(r+=e);else for(;++o<u;)i(e=+t.call(n,n[o],o))&&(r+=e);return r},ao.mean=function(n,t){var e,u=0,o=n.length,a=-1,l=o;if(1===arguments.length)for(;++a<o;)i(e=r(n[a]))?u+=e:--l;else for(;++a<o;)i(e=r(t.call(n,n[a],a)))?u+=e:--l;return l?u/l:void 0},ao.quantile=function(n,t){var e=(n.length-1)*t+1,r=Math.floor(e),i=+n[r-1],u=e-r;return u?i+u*(n[r]-i):i},ao.median=function(n,t){var u,o=[],a=n.length,l=-1;if(1===arguments.length)for(;++l<a;)i(u=r(n[l]))&&o.push(u);else for(;++l<a;)i(u=r(t.call(n,n[l],l)))&&o.push(u);return o.length?ao.quantile(o.sort(e),.5):void 0},ao.variance=function(n,t){var e,u,o=n.length,a=0,l=0,c=-1,f=0;if(1===arguments.length)for(;++c<o;)i(e=r(n[c]))&&(u=e-a,a+=u/++f,l+=u*(e-a));else for(;++c<o;)i(e=r(t.call(n,n[c],c)))&&(u=e-a,a+=u/++f,l+=u*(e-a));return f>1?l/(f-1):void 0},ao.deviation=function(){var n=ao.variance.apply(this,arguments);return n?Math.sqrt(n):n};var Mo=u(e);ao.bisectLeft=Mo.left,ao.bisect=ao.bisectRight=Mo.right,ao.bisector=function(n){return u(1===n.length?function(t,r){return e(n(t),r)}:n)},ao.shuffle=function(n,t,e){(u=arguments.length)<3&&(e=n.length,2>u&&(t=0));for(var r,i,u=e-t;u;)i=Math.random()*u--|0,r=n[u+t],n[u+t]=n[i+t],n[i+t]=r;return n},ao.permute=function(n,t){for(var e=t.length,r=new Array(e);e--;)r[e]=n[t[e]];return r},ao.pairs=function(n){for(var t,e=0,r=n.length-1,i=n[0],u=new Array(0>r?0:r);r>e;)u[e]=[t=i,i=n[++e]];return u},ao.transpose=function(n){if(!(i=n.length))return[];for(var t=-1,e=ao.min(n,o),r=new Array(e);++t<e;)for(var i,u=-1,a=r[t]=new Array(i);++u<i;)a[u]=n[u][t];return r},ao.zip=function(){return ao.transpose(arguments)},ao.keys=function(n){var t=[];for(var e in n)t.push(e);return t},ao.values=function(n){var t=[];for(var e in n)t.push(n[e]);return t},ao.entries=function(n){var t=[];for(var e in n)t.push({key:e,value:n[e]});return t},ao.merge=function(n){for(var t,e,r,i=n.length,u=-1,o=0;++u<i;)o+=n[u].length;for(e=new Array(o);--i>=0;)for(r=n[i],t=r.length;--t>=0;)e[--o]=r[t];return e};var xo=Math.abs;ao.range=function(n,t,e){if(arguments.length<3&&(e=1,arguments.length<2&&(t=n,n=0)),(t-n)/e===1/0)throw new Error(\"infinite range\");var r,i=[],u=a(xo(e)),o=-1;if(n*=u,t*=u,e*=u,0>e)for(;(r=n+e*++o)>t;)i.push(r/u);else for(;(r=n+e*++o)<t;)i.push(r/u);return i},ao.map=function(n,t){var e=new c;if(n instanceof c)n.forEach(function(n,t){e.set(n,t)});else if(Array.isArray(n)){var r,i=-1,u=n.length;if(1===arguments.length)for(;++i<u;)e.set(i,n[i]);else for(;++i<u;)e.set(t.call(n,r=n[i],i),r)}else for(var o in n)e.set(o,n[o]);return e};var bo=\"__proto__\",_o=\"\\x00\";l(c,{has:h,get:function(n){return this._[f(n)]},set:function(n,t){return this._[f(n)]=t},remove:p,keys:g,values:function(){var n=[];for(var t in this._)n.push(this._[t]);return n},entries:function(){var n=[];for(var t in this._)n.push({key:s(t),value:this._[t]});return n},size:v,empty:d,forEach:function(n){for(var t in this._)n.call(this,s(t),this._[t])}}),ao.nest=function(){function n(t,o,a){if(a>=u.length)return r?r.call(i,o):e?o.sort(e):o;for(var l,f,s,h,p=-1,g=o.length,v=u[a++],d=new c;++p<g;)(h=d.get(l=v(f=o[p])))?h.push(f):d.set(l,[f]);return t?(f=t(),s=function(e,r){f.set(e,n(t,r,a))}):(f={},s=function(e,r){f[e]=n(t,r,a)}),d.forEach(s),f}function t(n,e){if(e>=u.length)return n;var r=[],i=o[e++];return n.forEach(function(n,i){r.push({key:n,values:t(i,e)})}),i?r.sort(function(n,t){return i(n.key,t.key)}):r}var e,r,i={},u=[],o=[];return i.map=function(t,e){return n(e,t,0)},i.entries=function(e){return t(n(ao.map,e,0),0)},i.key=function(n){return u.push(n),i},i.sortKeys=function(n){return o[u.length-1]=n,i},i.sortValues=function(n){return e=n,i},i.rollup=function(n){return r=n,i},i},ao.set=function(n){var t=new y;if(n)for(var e=0,r=n.length;r>e;++e)t.add(n[e]);return t},l(y,{has:h,add:function(n){return this._[f(n+=\"\")]=!0,n},remove:p,values:g,size:v,empty:d,forEach:function(n){for(var t in this._)n.call(this,s(t))}}),ao.behavior={},ao.rebind=function(n,t){for(var e,r=1,i=arguments.length;++r<i;)n[e=arguments[r]]=M(n,t,t[e]);return n};var wo=[\"webkit\",\"ms\",\"moz\",\"Moz\",\"o\",\"O\"];ao.dispatch=function(){for(var n=new _,t=-1,e=arguments.length;++t<e;)n[arguments[t]]=w(n);return n},_.prototype.on=function(n,t){var e=n.indexOf(\".\"),r=\"\";if(e>=0&&(r=n.slice(e+1),n=n.slice(0,e)),n)return arguments.length<2?this[n].on(r):this[n].on(r,t);if(2===arguments.length){if(null==t)for(n in this)this.hasOwnProperty(n)&&this[n].on(r,null);return this}},ao.event=null,ao.requote=function(n){return n.replace(So,\"\\\\$&\")};var So=/[\\\\\\^\\$\\*\\+\\?\\|\\[\\]\\(\\)\\.\\{\\}]/g,ko={}.__proto__?function(n,t){n.__proto__=t}:function(n,t){for(var e in t)n[e]=t[e]},No=function(n,t){return t.querySelector(n)},Eo=function(n,t){return t.querySelectorAll(n)},Ao=function(n,t){var e=n.matches||n[x(n,\"matchesSelector\")];return(Ao=function(n,t){return e.call(n,t)})(n,t)};\"function\"==typeof Sizzle&&(No=function(n,t){return Sizzle(n,t)[0]||null},Eo=Sizzle,Ao=Sizzle.matchesSelector),ao.selection=function(){return ao.select(fo.documentElement)};var Co=ao.selection.prototype=[];Co.select=function(n){var t,e,r,i,u=[];n=A(n);for(var o=-1,a=this.length;++o<a;){u.push(t=[]),t.parentNode=(r=this[o]).parentNode;for(var l=-1,c=r.length;++l<c;)(i=r[l])?(t.push(e=n.call(i,i.__data__,l,o)),e&&\"__data__\"in i&&(e.__data__=i.__data__)):t.push(null)}return E(u)},Co.selectAll=function(n){var t,e,r=[];n=C(n);for(var i=-1,u=this.length;++i<u;)for(var o=this[i],a=-1,l=o.length;++a<l;)(e=o[a])&&(r.push(t=co(n.call(e,e.__data__,a,i))),t.parentNode=e);return E(r)};var zo=\"http://www.w3.org/1999/xhtml\",Lo={svg:\"http://www.w3.org/2000/svg\",xhtml:zo,xlink:\"http://www.w3.org/1999/xlink\",xml:\"http://www.w3.org/XML/1998/namespace\",xmlns:\"http://www.w3.org/2000/xmlns/\"};ao.ns={prefix:Lo,qualify:function(n){var t=n.indexOf(\":\"),e=n;return t>=0&&\"xmlns\"!==(e=n.slice(0,t))&&(n=n.slice(t+1)),Lo.hasOwnProperty(e)?{space:Lo[e],local:n}:n}},Co.attr=function(n,t){if(arguments.length<2){if(\"string\"==typeof n){var e=this.node();return n=ao.ns.qualify(n),n.local?e.getAttributeNS(n.space,n.local):e.getAttribute(n)}for(t in n)this.each(z(t,n[t]));return this}return this.each(z(n,t))},Co.classed=function(n,t){if(arguments.length<2){if(\"string\"==typeof n){var e=this.node(),r=(n=T(n)).length,i=-1;if(t=e.classList){for(;++i<r;)if(!t.contains(n[i]))return!1}else for(t=e.getAttribute(\"class\");++i<r;)if(!q(n[i]).test(t))return!1;return!0}for(t in n)this.each(R(t,n[t]));return this}return this.each(R(n,t))},Co.style=function(n,e,r){var i=arguments.length;if(3>i){if(\"string\"!=typeof n){2>i&&(e=\"\");for(r in n)this.each(P(r,n[r],e));return this}if(2>i){var u=this.node();return t(u).getComputedStyle(u,null).getPropertyValue(n)}r=\"\"}return this.each(P(n,e,r))},Co.property=function(n,t){if(arguments.length<2){if(\"string\"==typeof n)return this.node()[n];for(t in n)this.each(U(t,n[t]));return this}return this.each(U(n,t))},Co.text=function(n){return arguments.length?this.each(\"function\"==typeof n?function(){var t=n.apply(this,arguments);this.textContent=null==t?\"\":t}:null==n?function(){this.textContent=\"\"}:function(){this.textContent=n}):this.node().textContent},Co.html=function(n){return arguments.length?this.each(\"function\"==typeof n?function(){var t=n.apply(this,arguments);this.innerHTML=null==t?\"\":t}:null==n?function(){this.innerHTML=\"\"}:function(){this.innerHTML=n}):this.node().innerHTML},Co.append=function(n){return n=j(n),this.select(function(){return this.appendChild(n.apply(this,arguments))})},Co.insert=function(n,t){return n=j(n),t=A(t),this.select(function(){return this.insertBefore(n.apply(this,arguments),t.apply(this,arguments)||null)})},Co.remove=function(){return this.each(F)},Co.data=function(n,t){function e(n,e){var r,i,u,o=n.length,s=e.length,h=Math.min(o,s),p=new Array(s),g=new Array(s),v=new Array(o);if(t){var d,y=new c,m=new Array(o);for(r=-1;++r<o;)(i=n[r])&&(y.has(d=t.call(i,i.__data__,r))?v[r]=i:y.set(d,i),m[r]=d);for(r=-1;++r<s;)(i=y.get(d=t.call(e,u=e[r],r)))?i!==!0&&(p[r]=i,i.__data__=u):g[r]=H(u),y.set(d,!0);for(r=-1;++r<o;)r in m&&y.get(m[r])!==!0&&(v[r]=n[r])}else{for(r=-1;++r<h;)i=n[r],u=e[r],i?(i.__data__=u,p[r]=i):g[r]=H(u);for(;s>r;++r)g[r]=H(e[r]);for(;o>r;++r)v[r]=n[r]}g.update=p,g.parentNode=p.parentNode=v.parentNode=n.parentNode,a.push(g),l.push(p),f.push(v)}var r,i,u=-1,o=this.length;if(!arguments.length){for(n=new Array(o=(r=this[0]).length);++u<o;)(i=r[u])&&(n[u]=i.__data__);return n}var a=Z([]),l=E([]),f=E([]);if(\"function\"==typeof n)for(;++u<o;)e(r=this[u],n.call(r,r.parentNode.__data__,u));else for(;++u<o;)e(r=this[u],n);return l.enter=function(){return a},l.exit=function(){return f},l},Co.datum=function(n){return arguments.length?this.property(\"__data__\",n):this.property(\"__data__\")},Co.filter=function(n){var t,e,r,i=[];\"function\"!=typeof n&&(n=O(n));for(var u=0,o=this.length;o>u;u++){i.push(t=[]),t.parentNode=(e=this[u]).parentNode;for(var a=0,l=e.length;l>a;a++)(r=e[a])&&n.call(r,r.__data__,a,u)&&t.push(r)}return E(i)},Co.order=function(){for(var n=-1,t=this.length;++n<t;)for(var e,r=this[n],i=r.length-1,u=r[i];--i>=0;)(e=r[i])&&(u&&u!==e.nextSibling&&u.parentNode.insertBefore(e,u),u=e);return this},Co.sort=function(n){n=I.apply(this,arguments);for(var t=-1,e=this.length;++t<e;)this[t].sort(n);return this.order()},Co.each=function(n){return Y(this,function(t,e,r){n.call(t,t.__data__,e,r)})},Co.call=function(n){var t=co(arguments);return n.apply(t[0]=this,t),this},Co.empty=function(){return!this.node()},Co.node=function(){for(var n=0,t=this.length;t>n;n++)for(var e=this[n],r=0,i=e.length;i>r;r++){var u=e[r];if(u)return u}return null},Co.size=function(){var n=0;return Y(this,function(){++n}),n};var qo=[];ao.selection.enter=Z,ao.selection.enter.prototype=qo,qo.append=Co.append,qo.empty=Co.empty,qo.node=Co.node,qo.call=Co.call,qo.size=Co.size,qo.select=function(n){for(var t,e,r,i,u,o=[],a=-1,l=this.length;++a<l;){r=(i=this[a]).update,o.push(t=[]),t.parentNode=i.parentNode;for(var c=-1,f=i.length;++c<f;)(u=i[c])?(t.push(r[c]=e=n.call(i.parentNode,u.__data__,c,a)),e.__data__=u.__data__):t.push(null)}return E(o)},qo.insert=function(n,t){return arguments.length<2&&(t=V(this)),Co.insert.call(this,n,t)},ao.select=function(t){var e;return\"string\"==typeof t?(e=[No(t,fo)],e.parentNode=fo.documentElement):(e=[t],e.parentNode=n(t)),E([e])},ao.selectAll=function(n){var t;return\"string\"==typeof n?(t=co(Eo(n,fo)),t.parentNode=fo.documentElement):(t=co(n),t.parentNode=null),E([t])},Co.on=function(n,t,e){var r=arguments.length;if(3>r){if(\"string\"!=typeof n){2>r&&(t=!1);for(e in n)this.each(X(e,n[e],t));return this}if(2>r)return(r=this.node()[\"__on\"+n])&&r._;e=!1}return this.each(X(n,t,e))};var To=ao.map({mouseenter:\"mouseover\",mouseleave:\"mouseout\"});fo&&To.forEach(function(n){\"on\"+n in fo&&To.remove(n)});var Ro,Do=0;ao.mouse=function(n){return J(n,k())};var Po=this.navigator&&/WebKit/.test(this.navigator.userAgent)?-1:0;ao.touch=function(n,t,e){if(arguments.length<3&&(e=t,t=k().changedTouches),t)for(var r,i=0,u=t.length;u>i;++i)if((r=t[i]).identifier===e)return J(n,r)},ao.behavior.drag=function(){function n(){this.on(\"mousedown.drag\",u).on(\"touchstart.drag\",o)}function e(n,t,e,u,o){return function(){function a(){var n,e,r=t(h,v);r&&(n=r[0]-M[0],e=r[1]-M[1],g|=n|e,M=r,p({type:\"drag\",x:r[0]+c[0],y:r[1]+c[1],dx:n,dy:e}))}function l(){t(h,v)&&(y.on(u+d,null).on(o+d,null),m(g),p({type:\"dragend\"}))}var c,f=this,s=ao.event.target.correspondingElement||ao.event.target,h=f.parentNode,p=r.of(f,arguments),g=0,v=n(),d=\".drag\"+(null==v?\"\":\"-\"+v),y=ao.select(e(s)).on(u+d,a).on(o+d,l),m=W(s),M=t(h,v);i?(c=i.apply(f,arguments),c=[c.x-M[0],c.y-M[1]]):c=[0,0],p({type:\"dragstart\"})}}var r=N(n,\"drag\",\"dragstart\",\"dragend\"),i=null,u=e(b,ao.mouse,t,\"mousemove\",\"mouseup\"),o=e(G,ao.touch,m,\"touchmove\",\"touchend\");return n.origin=function(t){return arguments.length?(i=t,n):i},ao.rebind(n,r,\"on\")},ao.touches=function(n,t){return arguments.length<2&&(t=k().touches),t?co(t).map(function(t){var e=J(n,t);return e.identifier=t.identifier,e}):[]};var Uo=1e-6,jo=Uo*Uo,Fo=Math.PI,Ho=2*Fo,Oo=Ho-Uo,Io=Fo/2,Yo=Fo/180,Zo=180/Fo,Vo=Math.SQRT2,Xo=2,$o=4;ao.interpolateZoom=function(n,t){var e,r,i=n[0],u=n[1],o=n[2],a=t[0],l=t[1],c=t[2],f=a-i,s=l-u,h=f*f+s*s;if(jo>h)r=Math.log(c/o)/Vo,e=function(n){return[i+n*f,u+n*s,o*Math.exp(Vo*n*r)]};else{var p=Math.sqrt(h),g=(c*c-o*o+$o*h)/(2*o*Xo*p),v=(c*c-o*o-$o*h)/(2*c*Xo*p),d=Math.log(Math.sqrt(g*g+1)-g),y=Math.log(Math.sqrt(v*v+1)-v);r=(y-d)/Vo,e=function(n){var t=n*r,e=rn(d),a=o/(Xo*p)*(e*un(Vo*t+d)-en(d));return[i+a*f,u+a*s,o*e/rn(Vo*t+d)]}}return e.duration=1e3*r,e},ao.behavior.zoom=function(){function n(n){n.on(L,s).on(Wo+\".zoom\",p).on(\"dblclick.zoom\",g).on(R,h)}function e(n){return[(n[0]-k.x)/k.k,(n[1]-k.y)/k.k]}function r(n){return[n[0]*k.k+k.x,n[1]*k.k+k.y]}function i(n){k.k=Math.max(A[0],Math.min(A[1],n))}function u(n,t){t=r(t),k.x+=n[0]-t[0],k.y+=n[1]-t[1]}function o(t,e,r,o){t.__chart__={x:k.x,y:k.y,k:k.k},i(Math.pow(2,o)),u(d=e,r),t=ao.select(t),C>0&&(t=t.transition().duration(C)),t.call(n.event)}function a(){b&&b.domain(x.range().map(function(n){return(n-k.x)/k.k}).map(x.invert)),w&&w.domain(_.range().map(function(n){return(n-k.y)/k.k}).map(_.invert))}function l(n){z++||n({type:\"zoomstart\"})}function c(n){a(),n({type:\"zoom\",scale:k.k,translate:[k.x,k.y]})}function f(n){--z||(n({type:\"zoomend\"}),d=null)}function s(){function n(){a=1,u(ao.mouse(i),h),c(o)}function r(){s.on(q,null).on(T,null),p(a),f(o)}var i=this,o=D.of(i,arguments),a=0,s=ao.select(t(i)).on(q,n).on(T,r),h=e(ao.mouse(i)),p=W(i);Il.call(i),l(o)}function h(){function n(){var n=ao.touches(g);return p=k.k,n.forEach(function(n){n.identifier in d&&(d[n.identifier]=e(n))}),n}function t(){var t=ao.event.target;ao.select(t).on(x,r).on(b,a),_.push(t);for(var e=ao.event.changedTouches,i=0,u=e.length;u>i;++i)d[e[i].identifier]=null;var l=n(),c=Date.now();if(1===l.length){if(500>c-M){var f=l[0];o(g,f,d[f.identifier],Math.floor(Math.log(k.k)/Math.LN2)+1),S()}M=c}else if(l.length>1){var f=l[0],s=l[1],h=f[0]-s[0],p=f[1]-s[1];y=h*h+p*p}}function r(){var n,t,e,r,o=ao.touches(g);Il.call(g);for(var a=0,l=o.length;l>a;++a,r=null)if(e=o[a],r=d[e.identifier]){if(t)break;n=e,t=r}if(r){var f=(f=e[0]-n[0])*f+(f=e[1]-n[1])*f,s=y&&Math.sqrt(f/y);n=[(n[0]+e[0])/2,(n[1]+e[1])/2],t=[(t[0]+r[0])/2,(t[1]+r[1])/2],i(s*p)}M=null,u(n,t),c(v)}function a(){if(ao.event.touches.length){for(var t=ao.event.changedTouches,e=0,r=t.length;r>e;++e)delete d[t[e].identifier];for(var i in d)return void n()}ao.selectAll(_).on(m,null),w.on(L,s).on(R,h),N(),f(v)}var p,g=this,v=D.of(g,arguments),d={},y=0,m=\".zoom-\"+ao.event.changedTouches[0].identifier,x=\"touchmove\"+m,b=\"touchend\"+m,_=[],w=ao.select(g),N=W(g);t(),l(v),w.on(L,null).on(R,t)}function p(){var n=D.of(this,arguments);m?clearTimeout(m):(Il.call(this),v=e(d=y||ao.mouse(this)),l(n)),m=setTimeout(function(){m=null,f(n)},50),S(),i(Math.pow(2,.002*Bo())*k.k),u(d,v),c(n)}function g(){var n=ao.mouse(this),t=Math.log(k.k)/Math.LN2;o(this,n,e(n),ao.event.shiftKey?Math.ceil(t)-1:Math.floor(t)+1)}var v,d,y,m,M,x,b,_,w,k={x:0,y:0,k:1},E=[960,500],A=Jo,C=250,z=0,L=\"mousedown.zoom\",q=\"mousemove.zoom\",T=\"mouseup.zoom\",R=\"touchstart.zoom\",D=N(n,\"zoomstart\",\"zoom\",\"zoomend\");return Wo||(Wo=\"onwheel\"in fo?(Bo=function(){return-ao.event.deltaY*(ao.event.deltaMode?120:1)},\"wheel\"):\"onmousewheel\"in fo?(Bo=function(){return ao.event.wheelDelta},\"mousewheel\"):(Bo=function(){return-ao.event.detail},\"MozMousePixelScroll\")),n.event=function(n){n.each(function(){var n=D.of(this,arguments),t=k;Hl?ao.select(this).transition().each(\"start.zoom\",function(){k=this.__chart__||{x:0,y:0,k:1},l(n)}).tween(\"zoom:zoom\",function(){var e=E[0],r=E[1],i=d?d[0]:e/2,u=d?d[1]:r/2,o=ao.interpolateZoom([(i-k.x)/k.k,(u-k.y)/k.k,e/k.k],[(i-t.x)/t.k,(u-t.y)/t.k,e/t.k]);return function(t){var r=o(t),a=e/r[2];this.__chart__=k={x:i-r[0]*a,y:u-r[1]*a,k:a},c(n)}}).each(\"interrupt.zoom\",function(){f(n)}).each(\"end.zoom\",function(){f(n)}):(this.__chart__=k,l(n),c(n),f(n))})},n.translate=function(t){return arguments.length?(k={x:+t[0],y:+t[1],k:k.k},a(),n):[k.x,k.y]},n.scale=function(t){return arguments.length?(k={x:k.x,y:k.y,k:null},i(+t),a(),n):k.k},n.scaleExtent=function(t){return arguments.length?(A=null==t?Jo:[+t[0],+t[1]],n):A},n.center=function(t){return arguments.length?(y=t&&[+t[0],+t[1]],n):y},n.size=function(t){return arguments.length?(E=t&&[+t[0],+t[1]],n):E},n.duration=function(t){return arguments.length?(C=+t,n):C},n.x=function(t){return arguments.length?(b=t,x=t.copy(),k={x:0,y:0,k:1},n):b},n.y=function(t){return arguments.length?(w=t,_=t.copy(),k={x:0,y:0,k:1},n):w},ao.rebind(n,D,\"on\")};var Bo,Wo,Jo=[0,1/0];ao.color=an,an.prototype.toString=function(){return this.rgb()+\"\"},ao.hsl=ln;var Go=ln.prototype=new an;Go.brighter=function(n){return n=Math.pow(.7,arguments.length?n:1),new ln(this.h,this.s,this.l/n)},Go.darker=function(n){return n=Math.pow(.7,arguments.length?n:1),new ln(this.h,this.s,n*this.l)},Go.rgb=function(){return cn(this.h,this.s,this.l)},ao.hcl=fn;var Ko=fn.prototype=new an;Ko.brighter=function(n){return new fn(this.h,this.c,Math.min(100,this.l+Qo*(arguments.length?n:1)))},Ko.darker=function(n){return new fn(this.h,this.c,Math.max(0,this.l-Qo*(arguments.length?n:1)))},Ko.rgb=function(){return sn(this.h,this.c,this.l).rgb()},ao.lab=hn;var Qo=18,na=.95047,ta=1,ea=1.08883,ra=hn.prototype=new an;ra.brighter=function(n){return new hn(Math.min(100,this.l+Qo*(arguments.length?n:1)),this.a,this.b)},ra.darker=function(n){return new hn(Math.max(0,this.l-Qo*(arguments.length?n:1)),this.a,this.b)},ra.rgb=function(){return pn(this.l,this.a,this.b)},ao.rgb=mn;var ia=mn.prototype=new an;ia.brighter=function(n){n=Math.pow(.7,arguments.length?n:1);var t=this.r,e=this.g,r=this.b,i=30;return t||e||r?(t&&i>t&&(t=i),e&&i>e&&(e=i),r&&i>r&&(r=i),new mn(Math.min(255,t/n),Math.min(255,e/n),Math.min(255,r/n))):new mn(i,i,i)},ia.darker=function(n){return n=Math.pow(.7,arguments.length?n:1),new mn(n*this.r,n*this.g,n*this.b)},ia.hsl=function(){return wn(this.r,this.g,this.b)},ia.toString=function(){return\"#\"+bn(this.r)+bn(this.g)+bn(this.b)};var ua=ao.map({aliceblue:15792383,antiquewhite:16444375,aqua:65535,aquamarine:8388564,azure:15794175,beige:16119260,bisque:16770244,black:0,blanchedalmond:16772045,blue:255,blueviolet:9055202,brown:10824234,burlywood:14596231,cadetblue:6266528,chartreuse:8388352,chocolate:13789470,coral:16744272,cornflowerblue:6591981,cornsilk:16775388,crimson:14423100,cyan:65535,darkblue:139,darkcyan:35723,darkgoldenrod:12092939,darkgray:11119017,darkgreen:25600,darkgrey:11119017,darkkhaki:12433259,darkmagenta:9109643,darkolivegreen:5597999,darkorange:16747520,darkorchid:10040012,darkred:9109504,darksalmon:15308410,darkseagreen:9419919,darkslateblue:4734347,darkslategray:3100495,darkslategrey:3100495,darkturquoise:52945,darkviolet:9699539,deeppink:16716947,deepskyblue:49151,dimgray:6908265,dimgrey:6908265,dodgerblue:2003199,firebrick:11674146,floralwhite:16775920,forestgreen:2263842,fuchsia:16711935,gainsboro:14474460,ghostwhite:16316671,gold:16766720,goldenrod:14329120,gray:8421504,green:32768,greenyellow:11403055,grey:8421504,honeydew:15794160,hotpink:16738740,indianred:13458524,indigo:4915330,ivory:16777200,khaki:15787660,lavender:15132410,lavenderblush:16773365,lawngreen:8190976,lemonchiffon:16775885,lightblue:11393254,lightcoral:15761536,lightcyan:14745599,lightgoldenrodyellow:16448210,lightgray:13882323,lightgreen:9498256,lightgrey:13882323,lightpink:16758465,lightsalmon:16752762,lightseagreen:2142890,lightskyblue:8900346,lightslategray:7833753,lightslategrey:7833753,lightsteelblue:11584734,lightyellow:16777184,lime:65280,limegreen:3329330,linen:16445670,magenta:16711935,maroon:8388608,mediumaquamarine:6737322,mediumblue:205,mediumorchid:12211667,mediumpurple:9662683,mediumseagreen:3978097,mediumslateblue:8087790,mediumspringgreen:64154,mediumturquoise:4772300,mediumvioletred:13047173,midnightblue:1644912,mintcream:16121850,mistyrose:16770273,moccasin:16770229,navajowhite:16768685,navy:128,oldlace:16643558,olive:8421376,olivedrab:7048739,orange:16753920,orangered:16729344,orchid:14315734,palegoldenrod:15657130,palegreen:10025880,paleturquoise:11529966,palevioletred:14381203,papayawhip:16773077,peachpuff:16767673,peru:13468991,pink:16761035,plum:14524637,powderblue:11591910,purple:8388736,rebeccapurple:6697881,red:16711680,rosybrown:12357519,royalblue:4286945,saddlebrown:9127187,salmon:16416882,sandybrown:16032864,seagreen:3050327,seashell:16774638,sienna:10506797,silver:12632256,skyblue:8900331,slateblue:6970061,slategray:7372944,slategrey:7372944,snow:16775930,springgreen:65407,steelblue:4620980,tan:13808780,teal:32896,thistle:14204888,tomato:16737095,turquoise:4251856,violet:15631086,wheat:16113331,white:16777215,whitesmoke:16119285,yellow:16776960,yellowgreen:10145074});ua.forEach(function(n,t){ua.set(n,Mn(t))}),ao.functor=En,ao.xhr=An(m),ao.dsv=function(n,t){function e(n,e,u){arguments.length<3&&(u=e,e=null);var o=Cn(n,t,null==e?r:i(e),u);return o.row=function(n){return arguments.length?o.response(null==(e=n)?r:i(n)):e},o}function r(n){return e.parse(n.responseText)}function i(n){return function(t){return e.parse(t.responseText,n)}}function u(t){return t.map(o).join(n)}function o(n){return a.test(n)?'\"'+n.replace(/\\\"/g,'\"\"')+'\"':n}var a=new RegExp('[\"'+n+\"\\n]\"),l=n.charCodeAt(0);return e.parse=function(n,t){var r;return e.parseRows(n,function(n,e){if(r)return r(n,e-1);var i=new Function(\"d\",\"return {\"+n.map(function(n,t){return JSON.stringify(n)+\": d[\"+t+\"]\"}).join(\",\")+\"}\");r=t?function(n,e){return t(i(n),e)}:i})},e.parseRows=function(n,t){function e(){if(f>=c)return o;if(i)return i=!1,u;var t=f;if(34===n.charCodeAt(t)){for(var e=t;e++<c;)if(34===n.charCodeAt(e)){if(34!==n.charCodeAt(e+1))break;++e}f=e+2;var r=n.charCodeAt(e+1);return 13===r?(i=!0,10===n.charCodeAt(e+2)&&++f):10===r&&(i=!0),n.slice(t+1,e).replace(/\"\"/g,'\"')}for(;c>f;){var r=n.charCodeAt(f++),a=1;if(10===r)i=!0;else if(13===r)i=!0,10===n.charCodeAt(f)&&(++f,++a);else if(r!==l)continue;return n.slice(t,f-a)}return n.slice(t)}for(var r,i,u={},o={},a=[],c=n.length,f=0,s=0;(r=e())!==o;){for(var h=[];r!==u&&r!==o;)h.push(r),r=e();t&&null==(h=t(h,s++))||a.push(h)}return a},e.format=function(t){if(Array.isArray(t[0]))return e.formatRows(t);var r=new y,i=[];return t.forEach(function(n){for(var t in n)r.has(t)||i.push(r.add(t))}),[i.map(o).join(n)].concat(t.map(function(t){return i.map(function(n){return o(t[n])}).join(n)})).join(\"\\n\")},e.formatRows=function(n){return n.map(u).join(\"\\n\")},e},ao.csv=ao.dsv(\",\",\"text/csv\"),ao.tsv=ao.dsv(\"  \",\"text/tab-separated-values\");var oa,aa,la,ca,fa=this[x(this,\"requestAnimationFrame\")]||function(n){setTimeout(n,17)};ao.timer=function(){qn.apply(this,arguments)},ao.timer.flush=function(){Rn(),Dn()},ao.round=function(n,t){return t?Math.round(n*(t=Math.pow(10,t)))/t:Math.round(n)};var sa=[\"y\",\"z\",\"a\",\"f\",\"p\",\"n\",\"\\xb5\",\"m\",\"\",\"k\",\"M\",\"G\",\"T\",\"P\",\"E\",\"Z\",\"Y\"].map(Un);ao.formatPrefix=function(n,t){var e=0;return(n=+n)&&(0>n&&(n*=-1),t&&(n=ao.round(n,Pn(n,t))),e=1+Math.floor(1e-12+Math.log(n)/Math.LN10),e=Math.max(-24,Math.min(24,3*Math.floor((e-1)/3)))),sa[8+e/3]};var ha=/(?:([^{])?([<>=^]))?([+\\- ])?([$#])?(0)?(\\d+)?(,)?(\\.-?\\d+)?([a-z%])?/i,pa=ao.map({b:function(n){return n.toString(2)},c:function(n){return String.fromCharCode(n)},o:function(n){return n.toString(8)},x:function(n){return n.toString(16)},X:function(n){return n.toString(16).toUpperCase()},g:function(n,t){return n.toPrecision(t)},e:function(n,t){return n.toExponential(t)},f:function(n,t){return n.toFixed(t)},r:function(n,t){return(n=ao.round(n,Pn(n,t))).toFixed(Math.max(0,Math.min(20,Pn(n*(1+1e-15),t))))}}),ga=ao.time={},va=Date;Hn.prototype={getDate:function(){return this._.getUTCDate()},getDay:function(){return this._.getUTCDay()},getFullYear:function(){return this._.getUTCFullYear()},getHours:function(){return this._.getUTCHours()},getMilliseconds:function(){return this._.getUTCMilliseconds()},getMinutes:function(){return this._.getUTCMinutes()},getMonth:function(){return this._.getUTCMonth()},getSeconds:function(){return this._.getUTCSeconds()},getTime:function(){return this._.getTime()},getTimezoneOffset:function(){return 0},valueOf:function(){return this._.valueOf()},setDate:function(){da.setUTCDate.apply(this._,arguments)},setDay:function(){da.setUTCDay.apply(this._,arguments)},setFullYear:function(){da.setUTCFullYear.apply(this._,arguments)},setHours:function(){da.setUTCHours.apply(this._,arguments)},setMilliseconds:function(){da.setUTCMilliseconds.apply(this._,arguments)},setMinutes:function(){da.setUTCMinutes.apply(this._,arguments)},setMonth:function(){da.setUTCMonth.apply(this._,arguments)},setSeconds:function(){da.setUTCSeconds.apply(this._,arguments)},setTime:function(){da.setTime.apply(this._,arguments)}};var da=Date.prototype;ga.year=On(function(n){return n=ga.day(n),n.setMonth(0,1),n},function(n,t){n.setFullYear(n.getFullYear()+t)},function(n){return n.getFullYear()}),ga.years=ga.year.range,ga.years.utc=ga.year.utc.range,ga.day=On(function(n){var t=new va(2e3,0);return t.setFullYear(n.getFullYear(),n.getMonth(),n.getDate()),t},function(n,t){n.setDate(n.getDate()+t)},function(n){return n.getDate()-1}),ga.days=ga.day.range,ga.days.utc=ga.day.utc.range,ga.dayOfYear=function(n){var t=ga.year(n);return Math.floor((n-t-6e4*(n.getTimezoneOffset()-t.getTimezoneOffset()))/864e5)},[\"sunday\",\"monday\",\"tuesday\",\"wednesday\",\"thursday\",\"friday\",\"saturday\"].forEach(function(n,t){t=7-t;var e=ga[n]=On(function(n){return(n=ga.day(n)).setDate(n.getDate()-(n.getDay()+t)%7),n},function(n,t){n.setDate(n.getDate()+7*Math.floor(t))},function(n){var e=ga.year(n).getDay();return Math.floor((ga.dayOfYear(n)+(e+t)%7)/7)-(e!==t)});ga[n+\"s\"]=e.range,ga[n+\"s\"].utc=e.utc.range,ga[n+\"OfYear\"]=function(n){var e=ga.year(n).getDay();return Math.floor((ga.dayOfYear(n)+(e+t)%7)/7)}}),ga.week=ga.sunday,ga.weeks=ga.sunday.range,ga.weeks.utc=ga.sunday.utc.range,ga.weekOfYear=ga.sundayOfYear;var ya={\"-\":\"\",_:\" \",0:\"0\"},ma=/^\\s*\\d+/,Ma=/^%/;ao.locale=function(n){return{numberFormat:jn(n),timeFormat:Yn(n)}};var xa=ao.locale({decimal:\".\",thousands:\",\",grouping:[3],currency:[\"$\",\"\"],dateTime:\"%a %b %e %X %Y\",date:\"%m/%d/%Y\",time:\"%H:%M:%S\",periods:[\"AM\",\"PM\"],days:[\"Sunday\",\"Monday\",\"Tuesday\",\"Wednesday\",\"Thursday\",\"Friday\",\"Saturday\"],shortDays:[\"Sun\",\"Mon\",\"Tue\",\"Wed\",\"Thu\",\"Fri\",\"Sat\"],months:[\"January\",\"February\",\"March\",\"April\",\"May\",\"June\",\"July\",\"August\",\"September\",\"October\",\"November\",\"December\"],shortMonths:[\"Jan\",\"Feb\",\"Mar\",\"Apr\",\"May\",\"Jun\",\"Jul\",\"Aug\",\"Sep\",\"Oct\",\"Nov\",\"Dec\"]});ao.format=xa.numberFormat,ao.geo={},ft.prototype={s:0,t:0,add:function(n){st(n,this.t,ba),st(ba.s,this.s,this),this.s?this.t+=ba.t:this.s=ba.t},reset:function(){this.s=this.t=0},valueOf:function(){return this.s}};var ba=new ft;ao.geo.stream=function(n,t){n&&_a.hasOwnProperty(n.type)?_a[n.type](n,t):ht(n,t)};var _a={Feature:function(n,t){ht(n.geometry,t)},FeatureCollection:function(n,t){for(var e=n.features,r=-1,i=e.length;++r<i;)ht(e[r].geometry,t)}},wa={Sphere:function(n,t){t.sphere()},Point:function(n,t){n=n.coordinates,t.point(n[0],n[1],n[2])},MultiPoint:function(n,t){for(var e=n.coordinates,r=-1,i=e.length;++r<i;)n=e[r],t.point(n[0],n[1],n[2])},LineString:function(n,t){pt(n.coordinates,t,0)},MultiLineString:function(n,t){for(var e=n.coordinates,r=-1,i=e.length;++r<i;)pt(e[r],t,0)},Polygon:function(n,t){gt(n.coordinates,t)},MultiPolygon:function(n,t){for(var e=n.coordinates,r=-1,i=e.length;++r<i;)gt(e[r],t)},GeometryCollection:function(n,t){for(var e=n.geometries,r=-1,i=e.length;++r<i;)ht(e[r],t)}};ao.geo.area=function(n){return Sa=0,ao.geo.stream(n,Na),Sa};var Sa,ka=new ft,Na={sphere:function(){Sa+=4*Fo},point:b,lineStart:b,lineEnd:b,polygonStart:function(){ka.reset(),Na.lineStart=vt},polygonEnd:function(){var n=2*ka;Sa+=0>n?4*Fo+n:n,Na.lineStart=Na.lineEnd=Na.point=b}};ao.geo.bounds=function(){function n(n,t){M.push(x=[f=n,h=n]),s>t&&(s=t),t>p&&(p=t)}function t(t,e){var r=dt([t*Yo,e*Yo]);if(y){var i=mt(y,r),u=[i[1],-i[0],0],o=mt(u,i);bt(o),o=_t(o);var l=t-g,c=l>0?1:-1,v=o[0]*Zo*c,d=xo(l)>180;if(d^(v>c*g&&c*t>v)){var m=o[1]*Zo;m>p&&(p=m)}else if(v=(v+360)%360-180,d^(v>c*g&&c*t>v)){var m=-o[1]*Zo;s>m&&(s=m)}else s>e&&(s=e),e>p&&(p=e);d?g>t?a(f,t)>a(f,h)&&(h=t):a(t,h)>a(f,h)&&(f=t):h>=f?(f>t&&(f=t),t>h&&(h=t)):t>g?a(f,t)>a(f,h)&&(h=t):a(t,h)>a(f,h)&&(f=t)}else n(t,e);y=r,g=t}function e(){b.point=t}function r(){x[0]=f,x[1]=h,b.point=n,y=null}function i(n,e){if(y){var r=n-g;m+=xo(r)>180?r+(r>0?360:-360):r}else v=n,d=e;Na.point(n,e),t(n,e)}function u(){Na.lineStart()}function o(){i(v,d),Na.lineEnd(),xo(m)>Uo&&(f=-(h=180)),x[0]=f,x[1]=h,y=null}function a(n,t){return(t-=n)<0?t+360:t}function l(n,t){return n[0]-t[0]}function c(n,t){return t[0]<=t[1]?t[0]<=n&&n<=t[1]:n<t[0]||t[1]<n}var f,s,h,p,g,v,d,y,m,M,x,b={point:n,lineStart:e,lineEnd:r,polygonStart:function(){b.point=i,b.lineStart=u,b.lineEnd=o,m=0,Na.polygonStart()},polygonEnd:function(){Na.polygonEnd(),b.point=n,b.lineStart=e,b.lineEnd=r,0>ka?(f=-(h=180),s=-(p=90)):m>Uo?p=90:-Uo>m&&(s=-90),x[0]=f,x[1]=h}};return function(n){p=h=-(f=s=1/0),M=[],ao.geo.stream(n,b);var t=M.length;if(t){M.sort(l);for(var e,r=1,i=M[0],u=[i];t>r;++r)e=M[r],c(e[0],i)||c(e[1],i)?(a(i[0],e[1])>a(i[0],i[1])&&(i[1]=e[1]),a(e[0],i[1])>a(i[0],i[1])&&(i[0]=e[0])):u.push(i=e);for(var o,e,g=-(1/0),t=u.length-1,r=0,i=u[t];t>=r;i=e,++r)e=u[r],(o=a(i[1],e[0]))>g&&(g=o,f=e[0],h=i[1])}return M=x=null,f===1/0||s===1/0?[[NaN,NaN],[NaN,NaN]]:[[f,s],[h,p]]}}(),ao.geo.centroid=function(n){Ea=Aa=Ca=za=La=qa=Ta=Ra=Da=Pa=Ua=0,ao.geo.stream(n,ja);var t=Da,e=Pa,r=Ua,i=t*t+e*e+r*r;return jo>i&&(t=qa,e=Ta,r=Ra,Uo>Aa&&(t=Ca,e=za,r=La),i=t*t+e*e+r*r,jo>i)?[NaN,NaN]:[Math.atan2(e,t)*Zo,tn(r/Math.sqrt(i))*Zo]};var Ea,Aa,Ca,za,La,qa,Ta,Ra,Da,Pa,Ua,ja={sphere:b,point:St,lineStart:Nt,lineEnd:Et,polygonStart:function(){ja.lineStart=At},polygonEnd:function(){ja.lineStart=Nt}},Fa=Rt(zt,jt,Ht,[-Fo,-Fo/2]),Ha=1e9;ao.geo.clipExtent=function(){var n,t,e,r,i,u,o={stream:function(n){return i&&(i.valid=!1),i=u(n),i.valid=!0,i},extent:function(a){return arguments.length?(u=Zt(n=+a[0][0],t=+a[0][1],e=+a[1][0],r=+a[1][1]),i&&(i.valid=!1,i=null),o):[[n,t],[e,r]]}};return o.extent([[0,0],[960,500]])},(ao.geo.conicEqualArea=function(){return Vt(Xt)}).raw=Xt,ao.geo.albers=function(){return ao.geo.conicEqualArea().rotate([96,0]).center([-.6,38.7]).parallels([29.5,45.5]).scale(1070)},ao.geo.albersUsa=function(){function n(n){var u=n[0],o=n[1];return t=null,e(u,o),t||(r(u,o),t)||i(u,o),t}var t,e,r,i,u=ao.geo.albers(),o=ao.geo.conicEqualArea().rotate([154,0]).center([-2,58.5]).parallels([55,65]),a=ao.geo.conicEqualArea().rotate([157,0]).center([-3,19.9]).parallels([8,18]),l={point:function(n,e){t=[n,e]}};return n.invert=function(n){var t=u.scale(),e=u.translate(),r=(n[0]-e[0])/t,i=(n[1]-e[1])/t;return(i>=.12&&.234>i&&r>=-.425&&-.214>r?o:i>=.166&&.234>i&&r>=-.214&&-.115>r?a:u).invert(n)},n.stream=function(n){var t=u.stream(n),e=o.stream(n),r=a.stream(n);return{point:function(n,i){t.point(n,i),e.point(n,i),r.point(n,i)},sphere:function(){t.sphere(),e.sphere(),r.sphere()},lineStart:function(){t.lineStart(),e.lineStart(),r.lineStart()},lineEnd:function(){t.lineEnd(),e.lineEnd(),r.lineEnd()},polygonStart:function(){t.polygonStart(),e.polygonStart(),r.polygonStart()},polygonEnd:function(){t.polygonEnd(),e.polygonEnd(),r.polygonEnd()}}},n.precision=function(t){return arguments.length?(u.precision(t),o.precision(t),a.precision(t),n):u.precision()},n.scale=function(t){return arguments.length?(u.scale(t),o.scale(.35*t),a.scale(t),n.translate(u.translate())):u.scale()},n.translate=function(t){if(!arguments.length)return u.translate();var c=u.scale(),f=+t[0],s=+t[1];return e=u.translate(t).clipExtent([[f-.455*c,s-.238*c],[f+.455*c,s+.238*c]]).stream(l).point,r=o.translate([f-.307*c,s+.201*c]).clipExtent([[f-.425*c+Uo,s+.12*c+Uo],[f-.214*c-Uo,s+.234*c-Uo]]).stream(l).point,i=a.translate([f-.205*c,s+.212*c]).clipExtent([[f-.214*c+Uo,s+.166*c+Uo],[f-.115*c-Uo,s+.234*c-Uo]]).stream(l).point,n},n.scale(1070)};var Oa,Ia,Ya,Za,Va,Xa,$a={point:b,lineStart:b,lineEnd:b,polygonStart:function(){Ia=0,$a.lineStart=$t},polygonEnd:function(){$a.lineStart=$a.lineEnd=$a.point=b,Oa+=xo(Ia/2)}},Ba={point:Bt,lineStart:b,lineEnd:b,polygonStart:b,polygonEnd:b},Wa={point:Gt,lineStart:Kt,lineEnd:Qt,polygonStart:function(){Wa.lineStart=ne},polygonEnd:function(){Wa.point=Gt,Wa.lineStart=Kt,Wa.lineEnd=Qt}};ao.geo.path=function(){function n(n){return n&&(\"function\"==typeof a&&u.pointRadius(+a.apply(this,arguments)),o&&o.valid||(o=i(u)),ao.geo.stream(n,o)),u.result()}function t(){return o=null,n}var e,r,i,u,o,a=4.5;return n.area=function(n){return Oa=0,ao.geo.stream(n,i($a)),Oa},n.centroid=function(n){return Ca=za=La=qa=Ta=Ra=Da=Pa=Ua=0,ao.geo.stream(n,i(Wa)),Ua?[Da/Ua,Pa/Ua]:Ra?[qa/Ra,Ta/Ra]:La?[Ca/La,za/La]:[NaN,NaN]},n.bounds=function(n){return Va=Xa=-(Ya=Za=1/0),ao.geo.stream(n,i(Ba)),[[Ya,Za],[Va,Xa]]},n.projection=function(n){return arguments.length?(i=(e=n)?n.stream||re(n):m,t()):e},n.context=function(n){return arguments.length?(u=null==(r=n)?new Wt:new te(n),\"function\"!=typeof a&&u.pointRadius(a),t()):r},n.pointRadius=function(t){return arguments.length?(a=\"function\"==typeof t?t:(u.pointRadius(+t),+t),n):a},n.projection(ao.geo.albersUsa()).context(null)},ao.geo.transform=function(n){return{stream:function(t){var e=new ie(t);for(var r in n)e[r]=n[r];return e}}},ie.prototype={point:function(n,t){this.stream.point(n,t)},sphere:function(){this.stream.sphere()},lineStart:function(){this.stream.lineStart()},lineEnd:function(){this.stream.lineEnd()},polygonStart:function(){this.stream.polygonStart()},polygonEnd:function(){this.stream.polygonEnd()}},ao.geo.projection=oe,ao.geo.projectionMutator=ae,(ao.geo.equirectangular=function(){return oe(ce)}).raw=ce.invert=ce,ao.geo.rotation=function(n){function t(t){return t=n(t[0]*Yo,t[1]*Yo),t[0]*=Zo,t[1]*=Zo,t}return n=se(n[0]%360*Yo,n[1]*Yo,n.length>2?n[2]*Yo:0),t.invert=function(t){return t=n.invert(t[0]*Yo,t[1]*Yo),t[0]*=Zo,t[1]*=Zo,t},t},fe.invert=ce,ao.geo.circle=function(){function n(){var n=\"function\"==typeof r?r.apply(this,arguments):r,t=se(-n[0]*Yo,-n[1]*Yo,0).invert,i=[];return e(null,null,1,{point:function(n,e){i.push(n=t(n,e)),n[0]*=Zo,n[1]*=Zo}}),{type:\"Polygon\",coordinates:[i]}}var t,e,r=[0,0],i=6;return n.origin=function(t){return arguments.length?(r=t,n):r},n.angle=function(r){return arguments.length?(e=ve((t=+r)*Yo,i*Yo),n):t},n.precision=function(r){return arguments.length?(e=ve(t*Yo,(i=+r)*Yo),n):i},n.angle(90)},ao.geo.distance=function(n,t){var e,r=(t[0]-n[0])*Yo,i=n[1]*Yo,u=t[1]*Yo,o=Math.sin(r),a=Math.cos(r),l=Math.sin(i),c=Math.cos(i),f=Math.sin(u),s=Math.cos(u);return Math.atan2(Math.sqrt((e=s*o)*e+(e=c*f-l*s*a)*e),l*f+c*s*a)},ao.geo.graticule=function(){function n(){return{type:\"MultiLineString\",coordinates:t()}}function t(){return ao.range(Math.ceil(u/d)*d,i,d).map(h).concat(ao.range(Math.ceil(c/y)*y,l,y).map(p)).concat(ao.range(Math.ceil(r/g)*g,e,g).filter(function(n){return xo(n%d)>Uo}).map(f)).concat(ao.range(Math.ceil(a/v)*v,o,v).filter(function(n){return xo(n%y)>Uo}).map(s))}var e,r,i,u,o,a,l,c,f,s,h,p,g=10,v=g,d=90,y=360,m=2.5;return n.lines=function(){return t().map(function(n){return{type:\"LineString\",coordinates:n}})},n.outline=function(){return{type:\"Polygon\",coordinates:[h(u).concat(p(l).slice(1),h(i).reverse().slice(1),p(c).reverse().slice(1))]}},n.extent=function(t){return arguments.length?n.majorExtent(t).minorExtent(t):n.minorExtent()},n.majorExtent=function(t){return arguments.length?(u=+t[0][0],i=+t[1][0],c=+t[0][1],l=+t[1][1],u>i&&(t=u,u=i,i=t),c>l&&(t=c,c=l,l=t),n.precision(m)):[[u,c],[i,l]]},n.minorExtent=function(t){return arguments.length?(r=+t[0][0],e=+t[1][0],a=+t[0][1],o=+t[1][1],r>e&&(t=r,r=e,e=t),a>o&&(t=a,a=o,o=t),n.precision(m)):[[r,a],[e,o]]},n.step=function(t){return arguments.length?n.majorStep(t).minorStep(t):n.minorStep()},n.majorStep=function(t){return arguments.length?(d=+t[0],y=+t[1],n):[d,y]},n.minorStep=function(t){return arguments.length?(g=+t[0],v=+t[1],n):[g,v]},n.precision=function(t){return arguments.length?(m=+t,f=ye(a,o,90),s=me(r,e,m),h=ye(c,l,90),p=me(u,i,m),n):m},n.majorExtent([[-180,-90+Uo],[180,90-Uo]]).minorExtent([[-180,-80-Uo],[180,80+Uo]])},ao.geo.greatArc=function(){function n(){return{type:\"LineString\",coordinates:[t||r.apply(this,arguments),e||i.apply(this,arguments)]}}var t,e,r=Me,i=xe;return n.distance=function(){return ao.geo.distance(t||r.apply(this,arguments),e||i.apply(this,arguments))},n.source=function(e){return arguments.length?(r=e,t=\"function\"==typeof e?null:e,n):r},n.target=function(t){return arguments.length?(i=t,e=\"function\"==typeof t?null:t,n):i},n.precision=function(){return arguments.length?n:0},n},ao.geo.interpolate=function(n,t){return be(n[0]*Yo,n[1]*Yo,t[0]*Yo,t[1]*Yo)},ao.geo.length=function(n){return Ja=0,ao.geo.stream(n,Ga),Ja};var Ja,Ga={sphere:b,point:b,lineStart:_e,lineEnd:b,polygonStart:b,polygonEnd:b},Ka=we(function(n){return Math.sqrt(2/(1+n))},function(n){return 2*Math.asin(n/2)});(ao.geo.azimuthalEqualArea=function(){return oe(Ka)}).raw=Ka;var Qa=we(function(n){var t=Math.acos(n);return t&&t/Math.sin(t)},m);(ao.geo.azimuthalEquidistant=function(){return oe(Qa)}).raw=Qa,(ao.geo.conicConformal=function(){return Vt(Se)}).raw=Se,(ao.geo.conicEquidistant=function(){return Vt(ke)}).raw=ke;var nl=we(function(n){return 1/n},Math.atan);(ao.geo.gnomonic=function(){return oe(nl)}).raw=nl,Ne.invert=function(n,t){return[n,2*Math.atan(Math.exp(t))-Io]},(ao.geo.mercator=function(){return Ee(Ne)}).raw=Ne;var tl=we(function(){return 1},Math.asin);(ao.geo.orthographic=function(){return oe(tl)}).raw=tl;var el=we(function(n){return 1/(1+n)},function(n){return 2*Math.atan(n)});(ao.geo.stereographic=function(){return oe(el)}).raw=el,Ae.invert=function(n,t){return[-t,2*Math.atan(Math.exp(n))-Io]},(ao.geo.transverseMercator=function(){var n=Ee(Ae),t=n.center,e=n.rotate;return n.center=function(n){return n?t([-n[1],n[0]]):(n=t(),[n[1],-n[0]])},n.rotate=function(n){return n?e([n[0],n[1],n.length>2?n[2]+90:90]):(n=e(),[n[0],n[1],n[2]-90])},e([0,0,90])}).raw=Ae,ao.geom={},ao.geom.hull=function(n){function t(n){if(n.length<3)return[];var t,i=En(e),u=En(r),o=n.length,a=[],l=[];for(t=0;o>t;t++)a.push([+i.call(this,n[t],t),+u.call(this,n[t],t),t]);for(a.sort(qe),t=0;o>t;t++)l.push([a[t][0],-a[t][1]]);var c=Le(a),f=Le(l),s=f[0]===c[0],h=f[f.length-1]===c[c.length-1],p=[];for(t=c.length-1;t>=0;--t)p.push(n[a[c[t]][2]]);for(t=+s;t<f.length-h;++t)p.push(n[a[f[t]][2]]);return p}var e=Ce,r=ze;return arguments.length?t(n):(t.x=function(n){return arguments.length?(e=n,t):e},t.y=function(n){return arguments.length?(r=n,t):r},t)},ao.geom.polygon=function(n){return ko(n,rl),n};var rl=ao.geom.polygon.prototype=[];rl.area=function(){for(var n,t=-1,e=this.length,r=this[e-1],i=0;++t<e;)n=r,r=this[t],i+=n[1]*r[0]-n[0]*r[1];return.5*i},rl.centroid=function(n){var t,e,r=-1,i=this.length,u=0,o=0,a=this[i-1];for(arguments.length||(n=-1/(6*this.area()));++r<i;)t=a,a=this[r],e=t[0]*a[1]-a[0]*t[1],u+=(t[0]+a[0])*e,o+=(t[1]+a[1])*e;return[u*n,o*n]},rl.clip=function(n){for(var t,e,r,i,u,o,a=De(n),l=-1,c=this.length-De(this),f=this[c-1];++l<c;){for(t=n.slice(),n.length=0,i=this[l],u=t[(r=t.length-a)-1],e=-1;++e<r;)o=t[e],Te(o,f,i)?(Te(u,f,i)||n.push(Re(u,o,f,i)),n.push(o)):Te(u,f,i)&&n.push(Re(u,o,f,i)),u=o;a&&n.push(n[0]),f=i}return n};var il,ul,ol,al,ll,cl=[],fl=[];Ye.prototype.prepare=function(){for(var n,t=this.edges,e=t.length;e--;)n=t[e].edge,n.b&&n.a||t.splice(e,1);return t.sort(Ve),t.length},tr.prototype={start:function(){return this.edge.l===this.site?this.edge.a:this.edge.b},end:function(){return this.edge.l===this.site?this.edge.b:this.edge.a}},er.prototype={insert:function(n,t){var e,r,i;if(n){if(t.P=n,t.N=n.N,n.N&&(n.N.P=t),n.N=t,n.R){for(n=n.R;n.L;)n=n.L;n.L=t}else n.R=t;e=n}else this._?(n=or(this._),t.P=null,t.N=n,n.P=n.L=t,e=n):(t.P=t.N=null,this._=t,e=null);for(t.L=t.R=null,t.U=e,t.C=!0,n=t;e&&e.C;)r=e.U,e===r.L?(i=r.R,i&&i.C?(e.C=i.C=!1,r.C=!0,n=r):(n===e.R&&(ir(this,e),n=e,e=n.U),e.C=!1,r.C=!0,ur(this,r))):(i=r.L,i&&i.C?(e.C=i.C=!1,r.C=!0,n=r):(n===e.L&&(ur(this,e),n=e,e=n.U),e.C=!1,r.C=!0,ir(this,r))),e=n.U;this._.C=!1},remove:function(n){n.N&&(n.N.P=n.P),n.P&&(n.P.N=n.N),n.N=n.P=null;var t,e,r,i=n.U,u=n.L,o=n.R;if(e=u?o?or(o):u:o,i?i.L===n?i.L=e:i.R=e:this._=e,u&&o?(r=e.C,e.C=n.C,e.L=u,u.U=e,e!==o?(i=e.U,e.U=n.U,n=e.R,i.L=n,e.R=o,o.U=e):(e.U=i,i=e,n=e.R)):(r=n.C,n=e),n&&(n.U=i),!r){if(n&&n.C)return void(n.C=!1);do{if(n===this._)break;if(n===i.L){if(t=i.R,t.C&&(t.C=!1,i.C=!0,ir(this,i),t=i.R),t.L&&t.L.C||t.R&&t.R.C){t.R&&t.R.C||(t.L.C=!1,t.C=!0,ur(this,t),t=i.R),t.C=i.C,i.C=t.R.C=!1,ir(this,i),n=this._;break}}else if(t=i.L,t.C&&(t.C=!1,i.C=!0,ur(this,i),t=i.L),t.L&&t.L.C||t.R&&t.R.C){t.L&&t.L.C||(t.R.C=!1,t.C=!0,ir(this,t),t=i.L),t.C=i.C,i.C=t.L.C=!1,ur(this,i),n=this._;break}t.C=!0,n=i,i=i.U}while(!n.C);n&&(n.C=!1)}}},ao.geom.voronoi=function(n){function t(n){var t=new Array(n.length),r=a[0][0],i=a[0][1],u=a[1][0],o=a[1][1];return ar(e(n),a).cells.forEach(function(e,a){var l=e.edges,c=e.site,f=t[a]=l.length?l.map(function(n){var t=n.start();return[t.x,t.y]}):c.x>=r&&c.x<=u&&c.y>=i&&c.y<=o?[[r,o],[u,o],[u,i],[r,i]]:[];f.point=n[a]}),t}function e(n){return n.map(function(n,t){return{x:Math.round(u(n,t)/Uo)*Uo,y:Math.round(o(n,t)/Uo)*Uo,i:t}})}var r=Ce,i=ze,u=r,o=i,a=sl;return n?t(n):(t.links=function(n){return ar(e(n)).edges.filter(function(n){return n.l&&n.r}).map(function(t){return{source:n[t.l.i],target:n[t.r.i]}})},t.triangles=function(n){var t=[];return ar(e(n)).cells.forEach(function(e,r){for(var i,u,o=e.site,a=e.edges.sort(Ve),l=-1,c=a.length,f=a[c-1].edge,s=f.l===o?f.r:f.l;++l<c;)i=f,u=s,f=a[l].edge,s=f.l===o?f.r:f.l,r<u.i&&r<s.i&&cr(o,u,s)<0&&t.push([n[r],n[u.i],n[s.i]])}),t},t.x=function(n){return arguments.length?(u=En(r=n),t):r},t.y=function(n){return arguments.length?(o=En(i=n),t):i},t.clipExtent=function(n){return arguments.length?(a=null==n?sl:n,t):a===sl?null:a},t.size=function(n){return arguments.length?t.clipExtent(n&&[[0,0],n]):a===sl?null:a&&a[1]},t)};var sl=[[-1e6,-1e6],[1e6,1e6]];ao.geom.delaunay=function(n){return ao.geom.voronoi().triangles(n)},ao.geom.quadtree=function(n,t,e,r,i){function u(n){function u(n,t,e,r,i,u,o,a){if(!isNaN(e)&&!isNaN(r))if(n.leaf){var l=n.x,f=n.y;if(null!=l)if(xo(l-e)+xo(f-r)<.01)c(n,t,e,r,i,u,o,a);else{var s=n.point;n.x=n.y=n.point=null,c(n,s,l,f,i,u,o,a),c(n,t,e,r,i,u,o,a)}else n.x=e,n.y=r,n.point=t}else c(n,t,e,r,i,u,o,a)}function c(n,t,e,r,i,o,a,l){var c=.5*(i+a),f=.5*(o+l),s=e>=c,h=r>=f,p=h<<1|s;n.leaf=!1,n=n.nodes[p]||(n.nodes[p]=hr()),s?i=c:a=c,h?o=f:l=f,u(n,t,e,r,i,o,a,l)}var f,s,h,p,g,v,d,y,m,M=En(a),x=En(l);if(null!=t)v=t,d=e,y=r,m=i;else if(y=m=-(v=d=1/0),s=[],h=[],g=n.length,o)for(p=0;g>p;++p)f=n[p],f.x<v&&(v=f.x),f.y<d&&(d=f.y),f.x>y&&(y=f.x),f.y>m&&(m=f.y),s.push(f.x),h.push(f.y);else for(p=0;g>p;++p){var b=+M(f=n[p],p),_=+x(f,p);v>b&&(v=b),d>_&&(d=_),b>y&&(y=b),_>m&&(m=_),s.push(b),h.push(_)}var w=y-v,S=m-d;w>S?m=d+w:y=v+S;var k=hr();if(k.add=function(n){u(k,n,+M(n,++p),+x(n,p),v,d,y,m)},k.visit=function(n){pr(n,k,v,d,y,m)},k.find=function(n){return gr(k,n[0],n[1],v,d,y,m)},p=-1,null==t){for(;++p<g;)u(k,n[p],s[p],h[p],v,d,y,m);--p}else n.forEach(k.add);return s=h=n=f=null,k}var o,a=Ce,l=ze;return(o=arguments.length)?(a=fr,l=sr,3===o&&(i=e,r=t,e=t=0),u(n)):(u.x=function(n){return arguments.length?(a=n,u):a},u.y=function(n){return arguments.length?(l=n,u):l},u.extent=function(n){return arguments.length?(null==n?t=e=r=i=null:(t=+n[0][0],e=+n[0][1],r=+n[1][0],i=+n[1][1]),u):null==t?null:[[t,e],[r,i]]},u.size=function(n){return arguments.length?(null==n?t=e=r=i=null:(t=e=0,r=+n[0],i=+n[1]),u):null==t?null:[r-t,i-e]},u)},ao.interpolateRgb=vr,ao.interpolateObject=dr,ao.interpolateNumber=yr,ao.interpolateString=mr;var hl=/[-+]?(?:\\d+\\.?\\d*|\\.?\\d+)(?:[eE][-+]?\\d+)?/g,pl=new RegExp(hl.source,\"g\");ao.interpolate=Mr,ao.interpolators=[function(n,t){var e=typeof t;return(\"string\"===e?ua.has(t.toLowerCase())||/^(#|rgb\\(|hsl\\()/i.test(t)?vr:mr:t instanceof an?vr:Array.isArray(t)?xr:\"object\"===e&&isNaN(t)?dr:yr)(n,t)}],ao.interpolateArray=xr;var gl=function(){return m},vl=ao.map({linear:gl,poly:Er,quad:function(){return Sr},cubic:function(){return kr},sin:function(){return Ar},exp:function(){return Cr},circle:function(){return zr},elastic:Lr,back:qr,bounce:function(){return Tr}}),dl=ao.map({\"in\":m,out:_r,\"in-out\":wr,\"out-in\":function(n){return wr(_r(n))}});ao.ease=function(n){var t=n.indexOf(\"-\"),e=t>=0?n.slice(0,t):n,r=t>=0?n.slice(t+1):\"in\";return e=vl.get(e)||gl,r=dl.get(r)||m,br(r(e.apply(null,lo.call(arguments,1))))},ao.interpolateHcl=Rr,ao.interpolateHsl=Dr,ao.interpolateLab=Pr,ao.interpolateRound=Ur,ao.transform=function(n){var t=fo.createElementNS(ao.ns.prefix.svg,\"g\");return(ao.transform=function(n){if(null!=n){t.setAttribute(\"transform\",n);var e=t.transform.baseVal.consolidate()}return new jr(e?e.matrix:yl)})(n)},jr.prototype.toString=function(){return\"translate(\"+this.translate+\")rotate(\"+this.rotate+\")skewX(\"+this.skew+\")scale(\"+this.scale+\")\"};var yl={a:1,b:0,c:0,d:1,e:0,f:0};ao.interpolateTransform=$r,ao.layout={},ao.layout.bundle=function(){return function(n){for(var t=[],e=-1,r=n.length;++e<r;)t.push(Jr(n[e]));return t}},ao.layout.chord=function(){function n(){var n,c,s,h,p,g={},v=[],d=ao.range(u),y=[];for(e=[],r=[],n=0,h=-1;++h<u;){for(c=0,p=-1;++p<u;)c+=i[h][p];v.push(c),y.push(ao.range(u)),n+=c}for(o&&d.sort(function(n,t){return o(v[n],v[t])}),a&&y.forEach(function(n,t){n.sort(function(n,e){return a(i[t][n],i[t][e])})}),n=(Ho-f*u)/n,c=0,h=-1;++h<u;){for(s=c,p=-1;++p<u;){var m=d[h],M=y[m][p],x=i[m][M],b=c,_=c+=x*n;g[m+\"-\"+M]={index:m,subindex:M,startAngle:b,endAngle:_,value:x}}r[m]={index:m,startAngle:s,endAngle:c,value:v[m]},c+=f}for(h=-1;++h<u;)for(p=h-1;++p<u;){var w=g[h+\"-\"+p],S=g[p+\"-\"+h];(w.value||S.value)&&e.push(w.value<S.value?{source:S,target:w}:{source:w,target:S})}l&&t()}function t(){e.sort(function(n,t){return l((n.source.value+n.target.value)/2,(t.source.value+t.target.value)/2)})}var e,r,i,u,o,a,l,c={},f=0;return c.matrix=function(n){return arguments.length?(u=(i=n)&&i.length,e=r=null,c):i},c.padding=function(n){return arguments.length?(f=n,e=r=null,c):f},c.sortGroups=function(n){return arguments.length?(o=n,e=r=null,c):o},c.sortSubgroups=function(n){return arguments.length?(a=n,e=null,c):a},c.sortChords=function(n){return arguments.length?(l=n,e&&t(),c):l},c.chords=function(){return e||n(),e},c.groups=function(){return r||n(),r},c},ao.layout.force=function(){function n(n){return function(t,e,r,i){if(t.point!==n){var u=t.cx-n.x,o=t.cy-n.y,a=i-e,l=u*u+o*o;if(l>a*a/y){if(v>l){var c=t.charge/l;n.px-=u*c,n.py-=o*c}return!0}if(t.point&&l&&v>l){var c=t.pointCharge/l;n.px-=u*c,n.py-=o*c}}return!t.charge}}function t(n){n.px=ao.event.x,n.py=ao.event.y,l.resume()}var e,r,i,u,o,a,l={},c=ao.dispatch(\"start\",\"tick\",\"end\"),f=[1,1],s=.9,h=ml,p=Ml,g=-30,v=xl,d=.1,y=.64,M=[],x=[];return l.tick=function(){if((i*=.99)<.005)return e=null,c.end({type:\"end\",alpha:i=0}),!0;var t,r,l,h,p,v,y,m,b,_=M.length,w=x.length;for(r=0;w>r;++r)l=x[r],h=l.source,p=l.target,m=p.x-h.x,b=p.y-h.y,(v=m*m+b*b)&&(v=i*o[r]*((v=Math.sqrt(v))-u[r])/v,m*=v,b*=v,p.x-=m*(y=h.weight+p.weight?h.weight/(h.weight+p.weight):.5),p.y-=b*y,h.x+=m*(y=1-y),h.y+=b*y);if((y=i*d)&&(m=f[0]/2,b=f[1]/2,r=-1,y))for(;++r<_;)l=M[r],l.x+=(m-l.x)*y,l.y+=(b-l.y)*y;if(g)for(ri(t=ao.geom.quadtree(M),i,a),r=-1;++r<_;)(l=M[r]).fixed||t.visit(n(l));for(r=-1;++r<_;)l=M[r],l.fixed?(l.x=l.px,l.y=l.py):(l.x-=(l.px-(l.px=l.x))*s,l.y-=(l.py-(l.py=l.y))*s);c.tick({type:\"tick\",alpha:i})},l.nodes=function(n){return arguments.length?(M=n,l):M},l.links=function(n){return arguments.length?(x=n,l):x},l.size=function(n){return arguments.length?(f=n,l):f},l.linkDistance=function(n){return arguments.length?(h=\"function\"==typeof n?n:+n,l):h},l.distance=l.linkDistance,l.linkStrength=function(n){return arguments.length?(p=\"function\"==typeof n?n:+n,l):p},l.friction=function(n){return arguments.length?(s=+n,l):s},l.charge=function(n){return arguments.length?(g=\"function\"==typeof n?n:+n,l):g},l.chargeDistance=function(n){return arguments.length?(v=n*n,l):Math.sqrt(v)},l.gravity=function(n){return arguments.length?(d=+n,l):d},l.theta=function(n){return arguments.length?(y=n*n,l):Math.sqrt(y)},l.alpha=function(n){return arguments.length?(n=+n,i?n>0?i=n:(e.c=null,e.t=NaN,e=null,c.end({type:\"end\",alpha:i=0})):n>0&&(c.start({type:\"start\",alpha:i=n}),e=qn(l.tick)),l):i},l.start=function(){function n(n,r){if(!e){for(e=new Array(i),l=0;i>l;++l)e[l]=[];for(l=0;c>l;++l){var u=x[l];e[u.source.index].push(u.target),e[u.target.index].push(u.source)}}for(var o,a=e[t],l=-1,f=a.length;++l<f;)if(!isNaN(o=a[l][n]))return o;return Math.random()*r}var t,e,r,i=M.length,c=x.length,s=f[0],v=f[1];for(t=0;i>t;++t)(r=M[t]).index=t,r.weight=0;for(t=0;c>t;++t)r=x[t],\"number\"==typeof r.source&&(r.source=M[r.source]),\"number\"==typeof r.target&&(r.target=M[r.target]),++r.source.weight,++r.target.weight;for(t=0;i>t;++t)r=M[t],isNaN(r.x)&&(r.x=n(\"x\",s)),isNaN(r.y)&&(r.y=n(\"y\",v)),isNaN(r.px)&&(r.px=r.x),isNaN(r.py)&&(r.py=r.y);if(u=[],\"function\"==typeof h)for(t=0;c>t;++t)u[t]=+h.call(this,x[t],t);else for(t=0;c>t;++t)u[t]=h;if(o=[],\"function\"==typeof p)for(t=0;c>t;++t)o[t]=+p.call(this,x[t],t);else for(t=0;c>t;++t)o[t]=p;if(a=[],\"function\"==typeof g)for(t=0;i>t;++t)a[t]=+g.call(this,M[t],t);else for(t=0;i>t;++t)a[t]=g;return l.resume()},l.resume=function(){return l.alpha(.1)},l.stop=function(){return l.alpha(0)},l.drag=function(){return r||(r=ao.behavior.drag().origin(m).on(\"dragstart.force\",Qr).on(\"drag.force\",t).on(\"dragend.force\",ni)),arguments.length?void this.on(\"mouseover.force\",ti).on(\"mouseout.force\",ei).call(r):r},ao.rebind(l,c,\"on\")};var ml=20,Ml=1,xl=1/0;ao.layout.hierarchy=function(){function n(i){var u,o=[i],a=[];for(i.depth=0;null!=(u=o.pop());)if(a.push(u),(c=e.call(n,u,u.depth))&&(l=c.length)){for(var l,c,f;--l>=0;)o.push(f=c[l]),f.parent=u,f.depth=u.depth+1;r&&(u.value=0),u.children=c}else r&&(u.value=+r.call(n,u,u.depth)||0),delete u.children;return oi(i,function(n){var e,i;t&&(e=n.children)&&e.sort(t),r&&(i=n.parent)&&(i.value+=n.value)}),a}var t=ci,e=ai,r=li;return n.sort=function(e){return arguments.length?(t=e,n):t},n.children=function(t){return arguments.length?(e=t,n):e},n.value=function(t){return arguments.length?(r=t,n):r},n.revalue=function(t){return r&&(ui(t,function(n){n.children&&(n.value=0)}),oi(t,function(t){var e;t.children||(t.value=+r.call(n,t,t.depth)||0),(e=t.parent)&&(e.value+=t.value)})),t},n},ao.layout.partition=function(){function n(t,e,r,i){var u=t.children;if(t.x=e,t.y=t.depth*i,t.dx=r,t.dy=i,u&&(o=u.length)){var o,a,l,c=-1;for(r=t.value?r/t.value:0;++c<o;)n(a=u[c],e,l=a.value*r,i),e+=l}}function t(n){var e=n.children,r=0;if(e&&(i=e.length))for(var i,u=-1;++u<i;)r=Math.max(r,t(e[u]));return 1+r}function e(e,u){var o=r.call(this,e,u);return n(o[0],0,i[0],i[1]/t(o[0])),o}var r=ao.layout.hierarchy(),i=[1,1];return e.size=function(n){return arguments.length?(i=n,e):i},ii(e,r)},ao.layout.pie=function(){function n(o){var a,l=o.length,c=o.map(function(e,r){return+t.call(n,e,r)}),f=+(\"function\"==typeof r?r.apply(this,arguments):r),s=(\"function\"==typeof i?i.apply(this,arguments):i)-f,h=Math.min(Math.abs(s)/l,+(\"function\"==typeof u?u.apply(this,arguments):u)),p=h*(0>s?-1:1),g=ao.sum(c),v=g?(s-l*p)/g:0,d=ao.range(l),y=[];return null!=e&&d.sort(e===bl?function(n,t){return c[t]-c[n]}:function(n,t){return e(o[n],o[t])}),d.forEach(function(n){y[n]={data:o[n],value:a=c[n],startAngle:f,endAngle:f+=a*v+p,padAngle:h}}),y}var t=Number,e=bl,r=0,i=Ho,u=0;return n.value=function(e){return arguments.length?(t=e,n):t},n.sort=function(t){return arguments.length?(e=t,n):e},n.startAngle=function(t){return arguments.length?(r=t,n):r},n.endAngle=function(t){return arguments.length?(i=t,n):i},n.padAngle=function(t){return arguments.length?(u=t,n):u},n};var bl={};ao.layout.stack=function(){function n(a,l){if(!(h=a.length))return a;var c=a.map(function(e,r){return t.call(n,e,r)}),f=c.map(function(t){return t.map(function(t,e){return[u.call(n,t,e),o.call(n,t,e)]})}),s=e.call(n,f,l);c=ao.permute(c,s),f=ao.permute(f,s);var h,p,g,v,d=r.call(n,f,l),y=c[0].length;for(g=0;y>g;++g)for(i.call(n,c[0][g],v=d[g],f[0][g][1]),p=1;h>p;++p)i.call(n,c[p][g],v+=f[p-1][g][1],f[p][g][1]);return a}var t=m,e=gi,r=vi,i=pi,u=si,o=hi;return n.values=function(e){return arguments.length?(t=e,n):t},n.order=function(t){return arguments.length?(e=\"function\"==typeof t?t:_l.get(t)||gi,n):e},n.offset=function(t){return arguments.length?(r=\"function\"==typeof t?t:wl.get(t)||vi,n):r},n.x=function(t){return arguments.length?(u=t,n):u},n.y=function(t){return arguments.length?(o=t,n):o},n.out=function(t){return arguments.length?(i=t,n):i},n};var _l=ao.map({\"inside-out\":function(n){var t,e,r=n.length,i=n.map(di),u=n.map(yi),o=ao.range(r).sort(function(n,t){return i[n]-i[t]}),a=0,l=0,c=[],f=[];for(t=0;r>t;++t)e=o[t],l>a?(a+=u[e],c.push(e)):(l+=u[e],f.push(e));return f.reverse().concat(c)},reverse:function(n){return ao.range(n.length).reverse()},\"default\":gi}),wl=ao.map({silhouette:function(n){var t,e,r,i=n.length,u=n[0].length,o=[],a=0,l=[];for(e=0;u>e;++e){for(t=0,r=0;i>t;t++)r+=n[t][e][1];r>a&&(a=r),o.push(r)}for(e=0;u>e;++e)l[e]=(a-o[e])/2;return l},wiggle:function(n){var t,e,r,i,u,o,a,l,c,f=n.length,s=n[0],h=s.length,p=[];for(p[0]=l=c=0,e=1;h>e;++e){for(t=0,i=0;f>t;++t)i+=n[t][e][1];for(t=0,u=0,a=s[e][0]-s[e-1][0];f>t;++t){for(r=0,o=(n[t][e][1]-n[t][e-1][1])/(2*a);t>r;++r)o+=(n[r][e][1]-n[r][e-1][1])/a;u+=o*n[t][e][1]}p[e]=l-=i?u/i*a:0,c>l&&(c=l)}for(e=0;h>e;++e)p[e]-=c;return p},expand:function(n){var t,e,r,i=n.length,u=n[0].length,o=1/i,a=[];for(e=0;u>e;++e){for(t=0,r=0;i>t;t++)r+=n[t][e][1];if(r)for(t=0;i>t;t++)n[t][e][1]/=r;else for(t=0;i>t;t++)n[t][e][1]=o}for(e=0;u>e;++e)a[e]=0;return a},zero:vi});ao.layout.histogram=function(){function n(n,u){for(var o,a,l=[],c=n.map(e,this),f=r.call(this,c,u),s=i.call(this,f,c,u),u=-1,h=c.length,p=s.length-1,g=t?1:1/h;++u<p;)o=l[u]=[],o.dx=s[u+1]-(o.x=s[u]),o.y=0;if(p>0)for(u=-1;++u<h;)a=c[u],a>=f[0]&&a<=f[1]&&(o=l[ao.bisect(s,a,1,p)-1],o.y+=g,o.push(n[u]));return l}var t=!0,e=Number,r=bi,i=Mi;return n.value=function(t){return arguments.length?(e=t,n):e},n.range=function(t){return arguments.length?(r=En(t),n):r},n.bins=function(t){return arguments.length?(i=\"number\"==typeof t?function(n){return xi(n,t)}:En(t),n):i},n.frequency=function(e){return arguments.length?(t=!!e,n):t},n},ao.layout.pack=function(){function n(n,u){var o=e.call(this,n,u),a=o[0],l=i[0],c=i[1],f=null==t?Math.sqrt:\"function\"==typeof t?t:function(){return t};if(a.x=a.y=0,oi(a,function(n){n.r=+f(n.value)}),oi(a,Ni),r){var s=r*(t?1:Math.max(2*a.r/l,2*a.r/c))/2;oi(a,function(n){n.r+=s}),oi(a,Ni),oi(a,function(n){n.r-=s})}return Ci(a,l/2,c/2,t?1:1/Math.max(2*a.r/l,2*a.r/c)),o}var t,e=ao.layout.hierarchy().sort(_i),r=0,i=[1,1];return n.size=function(t){return arguments.length?(i=t,n):i},n.radius=function(e){return arguments.length?(t=null==e||\"function\"==typeof e?e:+e,n):t},n.padding=function(t){return arguments.length?(r=+t,n):r},ii(n,e)},ao.layout.tree=function(){function n(n,i){var f=o.call(this,n,i),s=f[0],h=t(s);if(oi(h,e),h.parent.m=-h.z,ui(h,r),c)ui(s,u);else{var p=s,g=s,v=s;ui(s,function(n){n.x<p.x&&(p=n),n.x>g.x&&(g=n),n.depth>v.depth&&(v=n)});var d=a(p,g)/2-p.x,y=l[0]/(g.x+a(g,p)/2+d),m=l[1]/(v.depth||1);ui(s,function(n){n.x=(n.x+d)*y,n.y=n.depth*m})}return f}function t(n){for(var t,e={A:null,children:[n]},r=[e];null!=(t=r.pop());)for(var i,u=t.children,o=0,a=u.length;a>o;++o)r.push((u[o]=i={_:u[o],parent:t,children:(i=u[o].children)&&i.slice()||[],A:null,a:null,z:0,m:0,c:0,s:0,t:null,i:o}).a=i);return e.children[0]}function e(n){var t=n.children,e=n.parent.children,r=n.i?e[n.i-1]:null;if(t.length){Di(n);var u=(t[0].z+t[t.length-1].z)/2;r?(n.z=r.z+a(n._,r._),n.m=n.z-u):n.z=u}else r&&(n.z=r.z+a(n._,r._));n.parent.A=i(n,r,n.parent.A||e[0])}function r(n){n._.x=n.z+n.parent.m,n.m+=n.parent.m}function i(n,t,e){if(t){for(var r,i=n,u=n,o=t,l=i.parent.children[0],c=i.m,f=u.m,s=o.m,h=l.m;o=Ti(o),i=qi(i),o&&i;)l=qi(l),u=Ti(u),u.a=n,r=o.z+s-i.z-c+a(o._,i._),r>0&&(Ri(Pi(o,n,e),n,r),c+=r,f+=r),s+=o.m,c+=i.m,h+=l.m,f+=u.m;o&&!Ti(u)&&(u.t=o,u.m+=s-f),i&&!qi(l)&&(l.t=i,l.m+=c-h,e=n)}return e}function u(n){n.x*=l[0],n.y=n.depth*l[1]}var o=ao.layout.hierarchy().sort(null).value(null),a=Li,l=[1,1],c=null;return n.separation=function(t){return arguments.length?(a=t,n):a},n.size=function(t){return arguments.length?(c=null==(l=t)?u:null,n):c?null:l},n.nodeSize=function(t){return arguments.length?(c=null==(l=t)?null:u,n):c?l:null},ii(n,o)},ao.layout.cluster=function(){function n(n,u){var o,a=t.call(this,n,u),l=a[0],c=0;oi(l,function(n){var t=n.children;t&&t.length?(n.x=ji(t),n.y=Ui(t)):(n.x=o?c+=e(n,o):0,n.y=0,o=n)});var f=Fi(l),s=Hi(l),h=f.x-e(f,s)/2,p=s.x+e(s,f)/2;return oi(l,i?function(n){n.x=(n.x-l.x)*r[0],n.y=(l.y-n.y)*r[1]}:function(n){n.x=(n.x-h)/(p-h)*r[0],n.y=(1-(l.y?n.y/l.y:1))*r[1]}),a}var t=ao.layout.hierarchy().sort(null).value(null),e=Li,r=[1,1],i=!1;return n.separation=function(t){return arguments.length?(e=t,n):e},n.size=function(t){return arguments.length?(i=null==(r=t),n):i?null:r},n.nodeSize=function(t){return arguments.length?(i=null!=(r=t),n):i?r:null},ii(n,t)},ao.layout.treemap=function(){function n(n,t){for(var e,r,i=-1,u=n.length;++i<u;)r=(e=n[i]).value*(0>t?0:t),e.area=isNaN(r)||0>=r?0:r}function t(e){var u=e.children;if(u&&u.length){var o,a,l,c=s(e),f=[],h=u.slice(),g=1/0,v=\"slice\"===p?c.dx:\"dice\"===p?c.dy:\"slice-dice\"===p?1&e.depth?c.dy:c.dx:Math.min(c.dx,c.dy);for(n(h,c.dx*c.dy/e.value),f.area=0;(l=h.length)>0;)f.push(o=h[l-1]),f.area+=o.area,\"squarify\"!==p||(a=r(f,v))<=g?(h.pop(),g=a):(f.area-=f.pop().area,i(f,v,c,!1),v=Math.min(c.dx,c.dy),f.length=f.area=0,g=1/0);f.length&&(i(f,v,c,!0),f.length=f.area=0),u.forEach(t)}}function e(t){var r=t.children;if(r&&r.length){var u,o=s(t),a=r.slice(),l=[];for(n(a,o.dx*o.dy/t.value),l.area=0;u=a.pop();)l.push(u),l.area+=u.area,null!=u.z&&(i(l,u.z?o.dx:o.dy,o,!a.length),l.length=l.area=0);r.forEach(e)}}function r(n,t){for(var e,r=n.area,i=0,u=1/0,o=-1,a=n.length;++o<a;)(e=n[o].area)&&(u>e&&(u=e),e>i&&(i=e));return r*=r,t*=t,r?Math.max(t*i*g/r,r/(t*u*g)):1/0}function i(n,t,e,r){var i,u=-1,o=n.length,a=e.x,c=e.y,f=t?l(n.area/t):0;if(t==e.dx){for((r||f>e.dy)&&(f=e.dy);++u<o;)i=n[u],i.x=a,i.y=c,i.dy=f,a+=i.dx=Math.min(e.x+e.dx-a,f?l(i.area/f):0);i.z=!0,i.dx+=e.x+e.dx-a,e.y+=f,e.dy-=f}else{for((r||f>e.dx)&&(f=e.dx);++u<o;)i=n[u],i.x=a,i.y=c,i.dx=f,c+=i.dy=Math.min(e.y+e.dy-c,f?l(i.area/f):0);i.z=!1,i.dy+=e.y+e.dy-c,e.x+=f,e.dx-=f}}function u(r){var i=o||a(r),u=i[0];return u.x=u.y=0,u.value?(u.dx=c[0],u.dy=c[1]):u.dx=u.dy=0,o&&a.revalue(u),n([u],u.dx*u.dy/u.value),(o?e:t)(u),h&&(o=i),i}var o,a=ao.layout.hierarchy(),l=Math.round,c=[1,1],f=null,s=Oi,h=!1,p=\"squarify\",g=.5*(1+Math.sqrt(5));return u.size=function(n){return arguments.length?(c=n,u):c},u.padding=function(n){function t(t){var e=n.call(u,t,t.depth);return null==e?Oi(t):Ii(t,\"number\"==typeof e?[e,e,e,e]:e)}function e(t){return Ii(t,n)}if(!arguments.length)return f;var r;return s=null==(f=n)?Oi:\"function\"==(r=typeof n)?t:\"number\"===r?(n=[n,n,n,n],e):e,u},u.round=function(n){return arguments.length?(l=n?Math.round:Number,u):l!=Number},u.sticky=function(n){return arguments.length?(h=n,o=null,u):h},u.ratio=function(n){return arguments.length?(g=n,u):g},u.mode=function(n){return arguments.length?(p=n+\"\",u):p},ii(u,a)},ao.random={normal:function(n,t){var e=arguments.length;return 2>e&&(t=1),1>e&&(n=0),function(){var e,r,i;do e=2*Math.random()-1,r=2*Math.random()-1,i=e*e+r*r;while(!i||i>1);return n+t*e*Math.sqrt(-2*Math.log(i)/i)}},logNormal:function(){var n=ao.random.normal.apply(ao,arguments);return function(){return Math.exp(n())}},bates:function(n){var t=ao.random.irwinHall(n);return function(){return t()/n}},irwinHall:function(n){return function(){for(var t=0,e=0;n>e;e++)t+=Math.random();return t}}},ao.scale={};var Sl={floor:m,ceil:m};ao.scale.linear=function(){return Wi([0,1],[0,1],Mr,!1)};var kl={s:1,g:1,p:1,r:1,e:1};ao.scale.log=function(){return ru(ao.scale.linear().domain([0,1]),10,!0,[1,10])};var Nl=ao.format(\".0e\"),El={floor:function(n){return-Math.ceil(-n)},ceil:function(n){return-Math.floor(-n)}};ao.scale.pow=function(){return iu(ao.scale.linear(),1,[0,1])},ao.scale.sqrt=function(){return ao.scale.pow().exponent(.5)},ao.scale.ordinal=function(){return ou([],{t:\"range\",a:[[]]})},ao.scale.category10=function(){return ao.scale.ordinal().range(Al)},ao.scale.category20=function(){return ao.scale.ordinal().range(Cl)},ao.scale.category20b=function(){return ao.scale.ordinal().range(zl)},ao.scale.category20c=function(){return ao.scale.ordinal().range(Ll)};var Al=[2062260,16744206,2924588,14034728,9725885,9197131,14907330,8355711,12369186,1556175].map(xn),Cl=[2062260,11454440,16744206,16759672,2924588,10018698,14034728,16750742,9725885,12955861,9197131,12885140,14907330,16234194,8355711,13092807,12369186,14408589,1556175,10410725].map(xn),zl=[3750777,5395619,7040719,10264286,6519097,9216594,11915115,13556636,9202993,12426809,15186514,15190932,8666169,11356490,14049643,15177372,8077683,10834324,13528509,14589654].map(xn),Ll=[3244733,7057110,10406625,13032431,15095053,16616764,16625259,16634018,3253076,7652470,10607003,13101504,7695281,10394312,12369372,14342891,6513507,9868950,12434877,14277081].map(xn);ao.scale.quantile=function(){return au([],[])},ao.scale.quantize=function(){return lu(0,1,[0,1])},ao.scale.threshold=function(){return cu([.5],[0,1])},ao.scale.identity=function(){return fu([0,1])},ao.svg={},ao.svg.arc=function(){function n(){var n=Math.max(0,+e.apply(this,arguments)),c=Math.max(0,+r.apply(this,arguments)),f=o.apply(this,arguments)-Io,s=a.apply(this,arguments)-Io,h=Math.abs(s-f),p=f>s?0:1;if(n>c&&(g=c,c=n,n=g),h>=Oo)return t(c,p)+(n?t(n,1-p):\"\")+\"Z\";var g,v,d,y,m,M,x,b,_,w,S,k,N=0,E=0,A=[];if((y=(+l.apply(this,arguments)||0)/2)&&(d=u===ql?Math.sqrt(n*n+c*c):+u.apply(this,arguments),p||(E*=-1),c&&(E=tn(d/c*Math.sin(y))),n&&(N=tn(d/n*Math.sin(y)))),c){m=c*Math.cos(f+E),M=c*Math.sin(f+E),x=c*Math.cos(s-E),b=c*Math.sin(s-E);var C=Math.abs(s-f-2*E)<=Fo?0:1;if(E&&yu(m,M,x,b)===p^C){var z=(f+s)/2;m=c*Math.cos(z),M=c*Math.sin(z),x=b=null}}else m=M=0;if(n){_=n*Math.cos(s-N),w=n*Math.sin(s-N),S=n*Math.cos(f+N),k=n*Math.sin(f+N);var L=Math.abs(f-s+2*N)<=Fo?0:1;if(N&&yu(_,w,S,k)===1-p^L){var q=(f+s)/2;_=n*Math.cos(q),w=n*Math.sin(q),S=k=null}}else _=w=0;if(h>Uo&&(g=Math.min(Math.abs(c-n)/2,+i.apply(this,arguments)))>.001){v=c>n^p?0:1;var T=g,R=g;if(Fo>h){var D=null==S?[_,w]:null==x?[m,M]:Re([m,M],[S,k],[x,b],[_,w]),P=m-D[0],U=M-D[1],j=x-D[0],F=b-D[1],H=1/Math.sin(Math.acos((P*j+U*F)/(Math.sqrt(P*P+U*U)*Math.sqrt(j*j+F*F)))/2),O=Math.sqrt(D[0]*D[0]+D[1]*D[1]);R=Math.min(g,(n-O)/(H-1)),T=Math.min(g,(c-O)/(H+1))}if(null!=x){var I=mu(null==S?[_,w]:[S,k],[m,M],c,T,p),Y=mu([x,b],[_,w],c,T,p);g===T?A.push(\"M\",I[0],\"A\",T,\",\",T,\" 0 0,\",v,\" \",I[1],\"A\",c,\",\",c,\" 0 \",1-p^yu(I[1][0],I[1][1],Y[1][0],Y[1][1]),\",\",p,\" \",Y[1],\"A\",T,\",\",T,\" 0 0,\",v,\" \",Y[0]):A.push(\"M\",I[0],\"A\",T,\",\",T,\" 0 1,\",v,\" \",Y[0])}else A.push(\"M\",m,\",\",M);if(null!=S){var Z=mu([m,M],[S,k],n,-R,p),V=mu([_,w],null==x?[m,M]:[x,b],n,-R,p);g===R?A.push(\"L\",V[0],\"A\",R,\",\",R,\" 0 0,\",v,\" \",V[1],\"A\",n,\",\",n,\" 0 \",p^yu(V[1][0],V[1][1],Z[1][0],Z[1][1]),\",\",1-p,\" \",Z[1],\"A\",R,\",\",R,\" 0 0,\",v,\" \",Z[0]):A.push(\"L\",V[0],\"A\",R,\",\",R,\" 0 0,\",v,\" \",Z[0])}else A.push(\"L\",_,\",\",w)}else A.push(\"M\",m,\",\",M),null!=x&&A.push(\"A\",c,\",\",c,\" 0 \",C,\",\",p,\" \",x,\",\",b),A.push(\"L\",_,\",\",w),null!=S&&A.push(\"A\",n,\",\",n,\" 0 \",L,\",\",1-p,\" \",S,\",\",k);return A.push(\"Z\"),A.join(\"\")}function t(n,t){return\"M0,\"+n+\"A\"+n+\",\"+n+\" 0 1,\"+t+\" 0,\"+-n+\"A\"+n+\",\"+n+\" 0 1,\"+t+\" 0,\"+n}var e=hu,r=pu,i=su,u=ql,o=gu,a=vu,l=du;return n.innerRadius=function(t){return arguments.length?(e=En(t),n):e},n.outerRadius=function(t){return arguments.length?(r=En(t),n):r},n.cornerRadius=function(t){return arguments.length?(i=En(t),n):i},n.padRadius=function(t){return arguments.length?(u=t==ql?ql:En(t),n):u},n.startAngle=function(t){return arguments.length?(o=En(t),n):o},n.endAngle=function(t){return arguments.length?(a=En(t),n):a},n.padAngle=function(t){return arguments.length?(l=En(t),n):l},n.centroid=function(){var n=(+e.apply(this,arguments)+ +r.apply(this,arguments))/2,t=(+o.apply(this,arguments)+ +a.apply(this,arguments))/2-Io;return[Math.cos(t)*n,Math.sin(t)*n]},n};var ql=\"auto\";ao.svg.line=function(){return Mu(m)};var Tl=ao.map({linear:xu,\"linear-closed\":bu,step:_u,\"step-before\":wu,\"step-after\":Su,basis:zu,\"basis-open\":Lu,\"basis-closed\":qu,bundle:Tu,cardinal:Eu,\"cardinal-open\":ku,\"cardinal-closed\":Nu,monotone:Fu});Tl.forEach(function(n,t){t.key=n,t.closed=/-closed$/.test(n)});var Rl=[0,2/3,1/3,0],Dl=[0,1/3,2/3,0],Pl=[0,1/6,2/3,1/6];ao.svg.line.radial=function(){var n=Mu(Hu);return n.radius=n.x,delete n.x,n.angle=n.y,delete n.y,n},wu.reverse=Su,Su.reverse=wu,ao.svg.area=function(){return Ou(m)},ao.svg.area.radial=function(){var n=Ou(Hu);return n.radius=n.x,delete n.x,n.innerRadius=n.x0,delete n.x0,n.outerRadius=n.x1,delete n.x1,n.angle=n.y,delete n.y,n.startAngle=n.y0,delete n.y0,n.endAngle=n.y1,delete n.y1,n},ao.svg.chord=function(){function n(n,a){var l=t(this,u,n,a),c=t(this,o,n,a);return\"M\"+l.p0+r(l.r,l.p1,l.a1-l.a0)+(e(l,c)?i(l.r,l.p1,l.r,l.p0):i(l.r,l.p1,c.r,c.p0)+r(c.r,c.p1,c.a1-c.a0)+i(c.r,c.p1,l.r,l.p0))+\"Z\"}function t(n,t,e,r){var i=t.call(n,e,r),u=a.call(n,i,r),o=l.call(n,i,r)-Io,f=c.call(n,i,r)-Io;return{r:u,a0:o,a1:f,p0:[u*Math.cos(o),u*Math.sin(o)],p1:[u*Math.cos(f),u*Math.sin(f)]}}function e(n,t){return n.a0==t.a0&&n.a1==t.a1}function r(n,t,e){return\"A\"+n+\",\"+n+\" 0 \"+ +(e>Fo)+\",1 \"+t}function i(n,t,e,r){return\"Q 0,0 \"+r}var u=Me,o=xe,a=Iu,l=gu,c=vu;return n.radius=function(t){return arguments.length?(a=En(t),n):a},n.source=function(t){return arguments.length?(u=En(t),n):u},n.target=function(t){return arguments.length?(o=En(t),n):o},n.startAngle=function(t){return arguments.length?(l=En(t),n):l},n.endAngle=function(t){return arguments.length?(c=En(t),n):c},n},ao.svg.diagonal=function(){function n(n,i){var u=t.call(this,n,i),o=e.call(this,n,i),a=(u.y+o.y)/2,l=[u,{x:u.x,y:a},{x:o.x,y:a},o];return l=l.map(r),\"M\"+l[0]+\"C\"+l[1]+\" \"+l[2]+\" \"+l[3]}var t=Me,e=xe,r=Yu;return n.source=function(e){return arguments.length?(t=En(e),n):t},n.target=function(t){return arguments.length?(e=En(t),n):e},n.projection=function(t){return arguments.length?(r=t,n):r},n},ao.svg.diagonal.radial=function(){var n=ao.svg.diagonal(),t=Yu,e=n.projection;return n.projection=function(n){return arguments.length?e(Zu(t=n)):t},n},ao.svg.symbol=function(){function n(n,r){return(Ul.get(t.call(this,n,r))||$u)(e.call(this,n,r))}var t=Xu,e=Vu;return n.type=function(e){return arguments.length?(t=En(e),n):t},n.size=function(t){return arguments.length?(e=En(t),n):e},n};var Ul=ao.map({circle:$u,cross:function(n){var t=Math.sqrt(n/5)/2;return\"M\"+-3*t+\",\"+-t+\"H\"+-t+\"V\"+-3*t+\"H\"+t+\"V\"+-t+\"H\"+3*t+\"V\"+t+\"H\"+t+\"V\"+3*t+\"H\"+-t+\"V\"+t+\"H\"+-3*t+\"Z\"},diamond:function(n){var t=Math.sqrt(n/(2*Fl)),e=t*Fl;return\"M0,\"+-t+\"L\"+e+\",0 0,\"+t+\" \"+-e+\",0Z\"},square:function(n){var t=Math.sqrt(n)/2;return\"M\"+-t+\",\"+-t+\"L\"+t+\",\"+-t+\" \"+t+\",\"+t+\" \"+-t+\",\"+t+\"Z\"},\"triangle-down\":function(n){var t=Math.sqrt(n/jl),e=t*jl/2;return\"M0,\"+e+\"L\"+t+\",\"+-e+\" \"+-t+\",\"+-e+\"Z\"},\"triangle-up\":function(n){var t=Math.sqrt(n/jl),e=t*jl/2;return\"M0,\"+-e+\"L\"+t+\",\"+e+\" \"+-t+\",\"+e+\"Z\"}});ao.svg.symbolTypes=Ul.keys();var jl=Math.sqrt(3),Fl=Math.tan(30*Yo);Co.transition=function(n){for(var t,e,r=Hl||++Zl,i=Ku(n),u=[],o=Ol||{time:Date.now(),ease:Nr,delay:0,duration:250},a=-1,l=this.length;++a<l;){u.push(t=[]);for(var c=this[a],f=-1,s=c.length;++f<s;)(e=c[f])&&Qu(e,f,i,r,o),t.push(e)}return Wu(u,i,r)},Co.interrupt=function(n){return this.each(null==n?Il:Bu(Ku(n)))};var Hl,Ol,Il=Bu(Ku()),Yl=[],Zl=0;Yl.call=Co.call,Yl.empty=Co.empty,Yl.node=Co.node,Yl.size=Co.size,ao.transition=function(n,t){return n&&n.transition?Hl?n.transition(t):n:ao.selection().transition(n)},ao.transition.prototype=Yl,Yl.select=function(n){var t,e,r,i=this.id,u=this.namespace,o=[];n=A(n);for(var a=-1,l=this.length;++a<l;){o.push(t=[]);for(var c=this[a],f=-1,s=c.length;++f<s;)(r=c[f])&&(e=n.call(r,r.__data__,f,a))?(\"__data__\"in r&&(e.__data__=r.__data__),Qu(e,f,u,i,r[u][i]),t.push(e)):t.push(null)}return Wu(o,u,i)},Yl.selectAll=function(n){var t,e,r,i,u,o=this.id,a=this.namespace,l=[];n=C(n);for(var c=-1,f=this.length;++c<f;)for(var s=this[c],h=-1,p=s.length;++h<p;)if(r=s[h]){u=r[a][o],e=n.call(r,r.__data__,h,c),l.push(t=[]);for(var g=-1,v=e.length;++g<v;)(i=e[g])&&Qu(i,g,a,o,u),t.push(i)}return Wu(l,a,o)},Yl.filter=function(n){var t,e,r,i=[];\"function\"!=typeof n&&(n=O(n));for(var u=0,o=this.length;o>u;u++){i.push(t=[]);for(var e=this[u],a=0,l=e.length;l>a;a++)(r=e[a])&&n.call(r,r.__data__,a,u)&&t.push(r)}return Wu(i,this.namespace,this.id)},Yl.tween=function(n,t){var e=this.id,r=this.namespace;return arguments.length<2?this.node()[r][e].tween.get(n):Y(this,null==t?function(t){t[r][e].tween.remove(n)}:function(i){i[r][e].tween.set(n,t)})},Yl.attr=function(n,t){function e(){this.removeAttribute(a)}function r(){this.removeAttributeNS(a.space,a.local)}function i(n){return null==n?e:(n+=\"\",function(){var t,e=this.getAttribute(a);return e!==n&&(t=o(e,n),function(n){this.setAttribute(a,t(n))})})}function u(n){return null==n?r:(n+=\"\",function(){var t,e=this.getAttributeNS(a.space,a.local);return e!==n&&(t=o(e,n),function(n){this.setAttributeNS(a.space,a.local,t(n))})})}if(arguments.length<2){for(t in n)this.attr(t,n[t]);return this}var o=\"transform\"==n?$r:Mr,a=ao.ns.qualify(n);return Ju(this,\"attr.\"+n,t,a.local?u:i)},Yl.attrTween=function(n,t){function e(n,e){var r=t.call(this,n,e,this.getAttribute(i));return r&&function(n){this.setAttribute(i,r(n))}}function r(n,e){var r=t.call(this,n,e,this.getAttributeNS(i.space,i.local));return r&&function(n){this.setAttributeNS(i.space,i.local,r(n))}}var i=ao.ns.qualify(n);return this.tween(\"attr.\"+n,i.local?r:e)},Yl.style=function(n,e,r){function i(){this.style.removeProperty(n)}function u(e){return null==e?i:(e+=\"\",function(){var i,u=t(this).getComputedStyle(this,null).getPropertyValue(n);return u!==e&&(i=Mr(u,e),function(t){this.style.setProperty(n,i(t),r)})})}var o=arguments.length;if(3>o){if(\"string\"!=typeof n){2>o&&(e=\"\");for(r in n)this.style(r,n[r],e);return this}r=\"\"}return Ju(this,\"style.\"+n,e,u)},Yl.styleTween=function(n,e,r){function i(i,u){var o=e.call(this,i,u,t(this).getComputedStyle(this,null).getPropertyValue(n));return o&&function(t){this.style.setProperty(n,o(t),r)}}return arguments.length<3&&(r=\"\"),this.tween(\"style.\"+n,i)},Yl.text=function(n){return Ju(this,\"text\",n,Gu)},Yl.remove=function(){var n=this.namespace;return this.each(\"end.transition\",function(){var t;this[n].count<2&&(t=this.parentNode)&&t.removeChild(this)})},Yl.ease=function(n){var t=this.id,e=this.namespace;return arguments.length<1?this.node()[e][t].ease:(\"function\"!=typeof n&&(n=ao.ease.apply(ao,arguments)),Y(this,function(r){r[e][t].ease=n}))},Yl.delay=function(n){var t=this.id,e=this.namespace;return arguments.length<1?this.node()[e][t].delay:Y(this,\"function\"==typeof n?function(r,i,u){r[e][t].delay=+n.call(r,r.__data__,i,u)}:(n=+n,function(r){r[e][t].delay=n}))},Yl.duration=function(n){var t=this.id,e=this.namespace;return arguments.length<1?this.node()[e][t].duration:Y(this,\"function\"==typeof n?function(r,i,u){r[e][t].duration=Math.max(1,n.call(r,r.__data__,i,u))}:(n=Math.max(1,n),function(r){r[e][t].duration=n}))},Yl.each=function(n,t){var e=this.id,r=this.namespace;if(arguments.length<2){var i=Ol,u=Hl;try{Hl=e,Y(this,function(t,i,u){Ol=t[r][e],n.call(t,t.__data__,i,u)})}finally{Ol=i,Hl=u}}else Y(this,function(i){var u=i[r][e];(u.event||(u.event=ao.dispatch(\"start\",\"end\",\"interrupt\"))).on(n,t)});return this},Yl.transition=function(){for(var n,t,e,r,i=this.id,u=++Zl,o=this.namespace,a=[],l=0,c=this.length;c>l;l++){a.push(n=[]);for(var t=this[l],f=0,s=t.length;s>f;f++)(e=t[f])&&(r=e[o][i],Qu(e,f,o,u,{time:r.time,ease:r.ease,delay:r.delay+r.duration,duration:r.duration})),n.push(e)}return Wu(a,o,u)},ao.svg.axis=function(){function n(n){n.each(function(){var n,c=ao.select(this),f=this.__chart__||e,s=this.__chart__=e.copy(),h=null==l?s.ticks?s.ticks.apply(s,a):s.domain():l,p=null==t?s.tickFormat?s.tickFormat.apply(s,a):m:t,g=c.selectAll(\".tick\").data(h,s),v=g.enter().insert(\"g\",\".domain\").attr(\"class\",\"tick\").style(\"opacity\",Uo),d=ao.transition(g.exit()).style(\"opacity\",Uo).remove(),y=ao.transition(g.order()).style(\"opacity\",1),M=Math.max(i,0)+o,x=Zi(s),b=c.selectAll(\".domain\").data([0]),_=(b.enter().append(\"path\").attr(\"class\",\"domain\"),ao.transition(b));v.append(\"line\"),v.append(\"text\");var w,S,k,N,E=v.select(\"line\"),A=y.select(\"line\"),C=g.select(\"text\").text(p),z=v.select(\"text\"),L=y.select(\"text\"),q=\"top\"===r||\"left\"===r?-1:1;if(\"bottom\"===r||\"top\"===r?(n=no,w=\"x\",k=\"y\",S=\"x2\",N=\"y2\",C.attr(\"dy\",0>q?\"0em\":\".71em\").style(\"text-anchor\",\"middle\"),_.attr(\"d\",\"M\"+x[0]+\",\"+q*u+\"V0H\"+x[1]+\"V\"+q*u)):(n=to,w=\"y\",k=\"x\",S=\"y2\",N=\"x2\",C.attr(\"dy\",\".32em\").style(\"text-anchor\",0>q?\"end\":\"start\"),_.attr(\"d\",\"M\"+q*u+\",\"+x[0]+\"H0V\"+x[1]+\"H\"+q*u)),E.attr(N,q*i),z.attr(k,q*M),A.attr(S,0).attr(N,q*i),L.attr(w,0).attr(k,q*M),s.rangeBand){var T=s,R=T.rangeBand()/2;f=s=function(n){return T(n)+R}}else f.rangeBand?f=s:d.call(n,s,f);v.call(n,f,s),y.call(n,s,s)})}var t,e=ao.scale.linear(),r=Vl,i=6,u=6,o=3,a=[10],l=null;return n.scale=function(t){return arguments.length?(e=t,n):e},n.orient=function(t){return arguments.length?(r=t in Xl?t+\"\":Vl,n):r},n.ticks=function(){return arguments.length?(a=co(arguments),n):a},n.tickValues=function(t){return arguments.length?(l=t,n):l},n.tickFormat=function(e){return arguments.length?(t=e,n):t},n.tickSize=function(t){var e=arguments.length;return e?(i=+t,u=+arguments[e-1],n):i},n.innerTickSize=function(t){return arguments.length?(i=+t,n):i},n.outerTickSize=function(t){return arguments.length?(u=+t,n):u},n.tickPadding=function(t){return arguments.length?(o=+t,n):o},n.tickSubdivide=function(){return arguments.length&&n},n};var Vl=\"bottom\",Xl={top:1,right:1,bottom:1,left:1};ao.svg.brush=function(){function n(t){t.each(function(){var t=ao.select(this).style(\"pointer-events\",\"all\").style(\"-webkit-tap-highlight-color\",\"rgba(0,0,0,0)\").on(\"mousedown.brush\",u).on(\"touchstart.brush\",u),o=t.selectAll(\".background\").data([0]);o.enter().append(\"rect\").attr(\"class\",\"background\").style(\"visibility\",\"hidden\").style(\"cursor\",\"crosshair\"),t.selectAll(\".extent\").data([0]).enter().append(\"rect\").attr(\"class\",\"extent\").style(\"cursor\",\"move\");var a=t.selectAll(\".resize\").data(v,m);a.exit().remove(),a.enter().append(\"g\").attr(\"class\",function(n){return\"resize \"+n}).style(\"cursor\",function(n){return $l[n]}).append(\"rect\").attr(\"x\",function(n){return/[ew]$/.test(n)?-3:null}).attr(\"y\",function(n){return/^[ns]/.test(n)?-3:null}).attr(\"width\",6).attr(\"height\",6).style(\"visibility\",\"hidden\"),a.style(\"display\",n.empty()?\"none\":null);var l,s=ao.transition(t),h=ao.transition(o);c&&(l=Zi(c),h.attr(\"x\",l[0]).attr(\"width\",l[1]-l[0]),r(s)),f&&(l=Zi(f),h.attr(\"y\",l[0]).attr(\"height\",l[1]-l[0]),i(s)),e(s)})}function e(n){n.selectAll(\".resize\").attr(\"transform\",function(n){return\"translate(\"+s[+/e$/.test(n)]+\",\"+h[+/^s/.test(n)]+\")\"})}function r(n){n.select(\".extent\").attr(\"x\",s[0]),n.selectAll(\".extent,.n>rect,.s>rect\").attr(\"width\",s[1]-s[0])}function i(n){n.select(\".extent\").attr(\"y\",h[0]),n.selectAll(\".extent,.e>rect,.w>rect\").attr(\"height\",h[1]-h[0])}function u(){function u(){32==ao.event.keyCode&&(C||(M=null,L[0]-=s[1],L[1]-=h[1],C=2),S())}function v(){32==ao.event.keyCode&&2==C&&(L[0]+=s[1],L[1]+=h[1],C=0,S())}function d(){var n=ao.mouse(b),t=!1;x&&(n[0]+=x[0],n[1]+=x[1]),C||(ao.event.altKey?(M||(M=[(s[0]+s[1])/2,(h[0]+h[1])/2]),L[0]=s[+(n[0]<M[0])],L[1]=h[+(n[1]<M[1])]):M=null),E&&y(n,c,0)&&(r(k),t=!0),A&&y(n,f,1)&&(i(k),t=!0),t&&(e(k),w({type:\"brush\",mode:C?\"move\":\"resize\"}))}function y(n,t,e){var r,i,u=Zi(t),l=u[0],c=u[1],f=L[e],v=e?h:s,d=v[1]-v[0];return C&&(l-=f,c-=d+f),r=(e?g:p)?Math.max(l,Math.min(c,n[e])):n[e],C?i=(r+=f)+d:(M&&(f=Math.max(l,Math.min(c,2*M[e]-r))),r>f?(i=r,r=f):i=f),v[0]!=r||v[1]!=i?(e?a=null:o=null,v[0]=r,v[1]=i,!0):void 0}function m(){d(),k.style(\"pointer-events\",\"all\").selectAll(\".resize\").style(\"display\",n.empty()?\"none\":null),ao.select(\"body\").style(\"cursor\",null),q.on(\"mousemove.brush\",null).on(\"mouseup.brush\",null).on(\"touchmove.brush\",null).on(\"touchend.brush\",null).on(\"keydown.brush\",null).on(\"keyup.brush\",null),z(),w({type:\"brushend\"})}var M,x,b=this,_=ao.select(ao.event.target),w=l.of(b,arguments),k=ao.select(b),N=_.datum(),E=!/^(n|s)$/.test(N)&&c,A=!/^(e|w)$/.test(N)&&f,C=_.classed(\"extent\"),z=W(b),L=ao.mouse(b),q=ao.select(t(b)).on(\"keydown.brush\",u).on(\"keyup.brush\",v);if(ao.event.changedTouches?q.on(\"touchmove.brush\",d).on(\"touchend.brush\",m):q.on(\"mousemove.brush\",d).on(\"mouseup.brush\",m),k.interrupt().selectAll(\"*\").interrupt(),C)L[0]=s[0]-L[0],L[1]=h[0]-L[1];else if(N){var T=+/w$/.test(N),R=+/^n/.test(N);x=[s[1-T]-L[0],h[1-R]-L[1]],L[0]=s[T],L[1]=h[R]}else ao.event.altKey&&(M=L.slice());k.style(\"pointer-events\",\"none\").selectAll(\".resize\").style(\"display\",null),ao.select(\"body\").style(\"cursor\",_.style(\"cursor\")),w({type:\"brushstart\"}),d()}var o,a,l=N(n,\"brushstart\",\"brush\",\"brushend\"),c=null,f=null,s=[0,0],h=[0,0],p=!0,g=!0,v=Bl[0];return n.event=function(n){n.each(function(){var n=l.of(this,arguments),t={x:s,y:h,i:o,j:a},e=this.__chart__||t;this.__chart__=t,Hl?ao.select(this).transition().each(\"start.brush\",function(){o=e.i,a=e.j,s=e.x,h=e.y,n({type:\"brushstart\"})}).tween(\"brush:brush\",function(){var e=xr(s,t.x),r=xr(h,t.y);return o=a=null,function(i){s=t.x=e(i),h=t.y=r(i),n({type:\"brush\",mode:\"resize\"})}}).each(\"end.brush\",function(){o=t.i,a=t.j,n({type:\"brush\",mode:\"resize\"}),n({type:\"brushend\"})}):(n({type:\"brushstart\"}),n({type:\"brush\",mode:\"resize\"}),n({type:\"brushend\"}))})},n.x=function(t){return arguments.length?(c=t,v=Bl[!c<<1|!f],n):c},n.y=function(t){return arguments.length?(f=t,v=Bl[!c<<1|!f],n):f},n.clamp=function(t){return arguments.length?(c&&f?(p=!!t[0],g=!!t[1]):c?p=!!t:f&&(g=!!t),n):c&&f?[p,g]:c?p:f?g:null},n.extent=function(t){var e,r,i,u,l;return arguments.length?(c&&(e=t[0],r=t[1],f&&(e=e[0],r=r[0]),o=[e,r],c.invert&&(e=c(e),r=c(r)),e>r&&(l=e,e=r,r=l),e==s[0]&&r==s[1]||(s=[e,r])),f&&(i=t[0],u=t[1],c&&(i=i[1],u=u[1]),a=[i,u],f.invert&&(i=f(i),u=f(u)),i>u&&(l=i,i=u,u=l),i==h[0]&&u==h[1]||(h=[i,u])),n):(c&&(o?(e=o[0],r=o[1]):(e=s[0],r=s[1],c.invert&&(e=c.invert(e),r=c.invert(r)),e>r&&(l=e,e=r,r=l))),f&&(a?(i=a[0],u=a[1]):(i=h[0],u=h[1],f.invert&&(i=f.invert(i),u=f.invert(u)),i>u&&(l=i,i=u,u=l))),c&&f?[[e,i],[r,u]]:c?[e,r]:f&&[i,u])},n.clear=function(){return n.empty()||(s=[0,0],h=[0,0],o=a=null),n},n.empty=function(){return!!c&&s[0]==s[1]||!!f&&h[0]==h[1]},ao.rebind(n,l,\"on\")};var $l={n:\"ns-resize\",e:\"ew-resize\",s:\"ns-resize\",w:\"ew-resize\",nw:\"nwse-resize\",ne:\"nesw-resize\",se:\"nwse-resize\",sw:\"nesw-resize\"},Bl=[[\"n\",\"e\",\"s\",\"w\",\"nw\",\"ne\",\"se\",\"sw\"],[\"e\",\"w\"],[\"n\",\"s\"],[]],Wl=ga.format=xa.timeFormat,Jl=Wl.utc,Gl=Jl(\"%Y-%m-%dT%H:%M:%S.%LZ\");Wl.iso=Date.prototype.toISOString&&+new Date(\"2000-01-01T00:00:00.000Z\")?eo:Gl,eo.parse=function(n){var t=new Date(n);return isNaN(t)?null:t},eo.toString=Gl.toString,ga.second=On(function(n){return new va(1e3*Math.floor(n/1e3))},function(n,t){n.setTime(n.getTime()+1e3*Math.floor(t))},function(n){return n.getSeconds()}),ga.seconds=ga.second.range,ga.seconds.utc=ga.second.utc.range,ga.minute=On(function(n){return new va(6e4*Math.floor(n/6e4))},function(n,t){n.setTime(n.getTime()+6e4*Math.floor(t))},function(n){return n.getMinutes()}),ga.minutes=ga.minute.range,ga.minutes.utc=ga.minute.utc.range,ga.hour=On(function(n){var t=n.getTimezoneOffset()/60;return new va(36e5*(Math.floor(n/36e5-t)+t))},function(n,t){n.setTime(n.getTime()+36e5*Math.floor(t))},function(n){return n.getHours()}),ga.hours=ga.hour.range,ga.hours.utc=ga.hour.utc.range,ga.month=On(function(n){return n=ga.day(n),n.setDate(1),n},function(n,t){n.setMonth(n.getMonth()+t)},function(n){return n.getMonth()}),ga.months=ga.month.range,ga.months.utc=ga.month.utc.range;var Kl=[1e3,5e3,15e3,3e4,6e4,3e5,9e5,18e5,36e5,108e5,216e5,432e5,864e5,1728e5,6048e5,2592e6,7776e6,31536e6],Ql=[[ga.second,1],[ga.second,5],[ga.second,15],[ga.second,30],[ga.minute,1],[ga.minute,5],[ga.minute,15],[ga.minute,30],[ga.hour,1],[ga.hour,3],[ga.hour,6],[ga.hour,12],[ga.day,1],[ga.day,2],[ga.week,1],[ga.month,1],[ga.month,3],[ga.year,1]],nc=Wl.multi([[\".%L\",function(n){return n.getMilliseconds()}],[\":%S\",function(n){return n.getSeconds()}],[\"%I:%M\",function(n){return n.getMinutes()}],[\"%I %p\",function(n){return n.getHours()}],[\"%a %d\",function(n){return n.getDay()&&1!=n.getDate()}],[\"%b %d\",function(n){return 1!=n.getDate()}],[\"%B\",function(n){return n.getMonth()}],[\"%Y\",zt]]),tc={range:function(n,t,e){return ao.range(Math.ceil(n/e)*e,+t,e).map(io)},floor:m,ceil:m};Ql.year=ga.year,ga.scale=function(){return ro(ao.scale.linear(),Ql,nc)};var ec=Ql.map(function(n){return[n[0].utc,n[1]]}),rc=Jl.multi([[\".%L\",function(n){return n.getUTCMilliseconds()}],[\":%S\",function(n){return n.getUTCSeconds()}],[\"%I:%M\",function(n){return n.getUTCMinutes()}],[\"%I %p\",function(n){return n.getUTCHours()}],[\"%a %d\",function(n){return n.getUTCDay()&&1!=n.getUTCDate()}],[\"%b %d\",function(n){return 1!=n.getUTCDate()}],[\"%B\",function(n){return n.getUTCMonth()}],[\"%Y\",zt]]);ec.year=ga.year.utc,ga.scale.utc=function(){return ro(ao.scale.linear(),ec,rc)},ao.text=An(function(n){return n.responseText}),ao.json=function(n,t){return Cn(n,\"application/json\",uo,t)},ao.html=function(n,t){return Cn(n,\"text/html\",oo,t)},ao.xml=An(function(n){return n.responseXML}),\"function\"==typeof define&&define.amd?(this.d3=ao,define(ao)):\"object\"==typeof module&&module.exports?module.exports=ao:this.d3=ao}();\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/resources/s2.js",
    "content": "!function(){var a={};a.dev=!1,a.tooltip=a.tooltip||{},a.utils=a.utils||{},a.models=a.models||{},a.charts={},a.logs={},a.dom={},\"undefined\"!=typeof module&&\"undefined\"!=typeof exports&&\"undefined\"==typeof d3&&(d3=require(\"d3\")),a.dispatch=d3.dispatch(\"render_start\",\"render_end\"),Function.prototype.bind||(Function.prototype.bind=function(a){if(\"function\"!=typeof this)throw new TypeError(\"Function.prototype.bind - what is trying to be bound is not callable\");var b=Array.prototype.slice.call(arguments,1),c=this,d=function(){},e=function(){return c.apply(this instanceof d&&a?this:a,b.concat(Array.prototype.slice.call(arguments)))};return d.prototype=this.prototype,e.prototype=new d,e}),a.dev&&(a.dispatch.on(\"render_start\",function(b){a.logs.startTime=+new Date}),a.dispatch.on(\"render_end\",function(b){a.logs.endTime=+new Date,a.logs.totalTime=a.logs.endTime-a.logs.startTime,a.log(\"total\",a.logs.totalTime)})),a.log=function(){if(a.dev&&window.console&&console.log&&console.log.apply)console.log.apply(console,arguments);else if(a.dev&&window.console&&\"function\"==typeof console.log&&Function.prototype.bind){var b=Function.prototype.bind.call(console.log,console);b.apply(console,arguments)}return arguments[arguments.length-1]},a.deprecated=function(a,b){console&&console.warn&&console.warn(\"nvd3 warning: `\"+a+\"` has been deprecated. \",b||\"\")},a.render=function(b){b=b||1,a.render.active=!0,a.dispatch.render_start();var c=function(){for(var d,e,f=0;b>f&&(e=a.render.queue[f]);f++)d=e.generate(),typeof e.callback==typeof Function&&e.callback(d);a.render.queue.splice(0,f),a.render.queue.length?setTimeout(c):(a.dispatch.render_end(),a.render.active=!1)};setTimeout(c)},a.render.active=!1,a.render.queue=[],a.addGraph=function(b){typeof arguments[0]==typeof Function&&(b={generate:arguments[0],callback:arguments[1]}),a.render.queue.push(b),a.render.active||a.render()},\"undefined\"!=typeof module&&\"undefined\"!=typeof exports&&(module.exports=a),\"undefined\"!=typeof window&&(window.nv=a),a.dom.write=function(a){return void 0!==window.fastdom?fastdom.mutate(a):a()},a.dom.read=function(a){return void 0!==window.fastdom?fastdom.measure(a):a()},a.interactiveGuideline=function(){\"use strict\";function b(l){l.each(function(l){function m(){var a=d3.mouse(this),d=a[0],e=a[1],h=!0,i=!1;if(k&&(d=d3.event.offsetX,e=d3.event.offsetY,\"svg\"!==d3.event.target.tagName&&(h=!1),d3.event.target.className.baseVal.match(\"nv-legend\")&&(i=!0)),h&&(d-=c.left,e-=c.top),\"mouseout\"===d3.event.type||0>d||0>e||d>o||e>p||d3.event.relatedTarget&&void 0===d3.event.relatedTarget.ownerSVGElement||i){if(k&&d3.event.relatedTarget&&void 0===d3.event.relatedTarget.ownerSVGElement&&(void 0===d3.event.relatedTarget.className||d3.event.relatedTarget.className.match(j.nvPointerEventsClass)))return;return g.elementMouseout({mouseX:d,mouseY:e}),b.renderGuideLine(null),void j.hidden(!0)}j.hidden(!1);var l=\"function\"==typeof f.rangeBands,m=void 0;if(l){var n=d3.bisect(f.range(),d)-1;if(!(f.range()[n]+f.rangeBand()>=d))return g.elementMouseout({mouseX:d,mouseY:e}),b.renderGuideLine(null),void j.hidden(!0);m=f.domain()[d3.bisect(f.range(),d)-1]}else m=f.invert(d);g.elementMousemove({mouseX:d,mouseY:e,pointXValue:m}),\"dblclick\"===d3.event.type&&g.elementDblclick({mouseX:d,mouseY:e,pointXValue:m}),\"click\"===d3.event.type&&g.elementClick({mouseX:d,mouseY:e,pointXValue:m}),\"mousedown\"===d3.event.type&&g.elementMouseDown({mouseX:d,mouseY:e,pointXValue:m}),\"mouseup\"===d3.event.type&&g.elementMouseUp({mouseX:d,mouseY:e,pointXValue:m})}var n=d3.select(this),o=d||960,p=e||400,q=n.selectAll(\"g.nv-wrap.nv-interactiveLineLayer\").data([l]),r=q.enter().append(\"g\").attr(\"class\",\" nv-wrap nv-interactiveLineLayer\");r.append(\"g\").attr(\"class\",\"nv-interactiveGuideLine\"),i&&(i.on(\"touchmove\",m).on(\"mousemove\",m,!0).on(\"mouseout\",m,!0).on(\"mousedown\",m,!0).on(\"mouseup\",m,!0).on(\"dblclick\",m).on(\"click\",m),b.guideLine=null,b.renderGuideLine=function(c){h&&(b.guideLine&&b.guideLine.attr(\"x1\")===c||a.dom.write(function(){var b=q.select(\".nv-interactiveGuideLine\").selectAll(\"line\").data(null!=c?[a.utils.NaNtoZero(c)]:[],String);b.enter().append(\"line\").attr(\"class\",\"nv-guideline\").attr(\"x1\",function(a){return a}).attr(\"x2\",function(a){return a}).attr(\"y1\",p).attr(\"y2\",0),b.exit().remove()}))})})}var c={left:0,top:0},d=null,e=null,f=d3.scale.linear(),g=d3.dispatch(\"elementMousemove\",\"elementMouseout\",\"elementClick\",\"elementDblclick\",\"elementMouseDown\",\"elementMouseUp\"),h=!0,i=null,j=a.models.tooltip(),k=window.ActiveXObject;return j.duration(0).hideDelay(0).hidden(!1),b.dispatch=g,b.tooltip=j,b.margin=function(a){return arguments.length?(c.top=\"undefined\"!=typeof a.top?a.top:c.top,c.left=\"undefined\"!=typeof a.left?a.left:c.left,b):c},b.width=function(a){return arguments.length?(d=a,b):d},b.height=function(a){return arguments.length?(e=a,b):e},b.xScale=function(a){return arguments.length?(f=a,b):f},b.showGuideLine=function(a){return arguments.length?(h=a,b):h},b.svgContainer=function(a){return arguments.length?(i=a,b):i},b},a.interactiveBisect=function(a,b,c){\"use strict\";if(!(a instanceof Array))return null;var d;d=\"function\"!=typeof c?function(a){return a.x}:c;var e=function(a,b){return d(a)-b},f=d3.bisector(e).left,g=d3.max([0,f(a,b)-1]),h=d(a[g]);if(\"undefined\"==typeof h&&(h=g),h===b)return g;var i=d3.min([g+1,a.length-1]),j=d(a[i]);return\"undefined\"==typeof j&&(j=i),Math.abs(j-b)>=Math.abs(h-b)?g:i},a.nearestValueIndex=function(a,b,c){\"use strict\";var d=1/0,e=null;return a.forEach(function(a,f){var g=Math.abs(b-a);null!=a&&d>=g&&c>g&&(d=g,e=f)}),e},a.models.tooltip=function(){\"use strict\";function b(){if(!l||!l.node()){var a=[1];l=d3.select(document.body).selectAll(\".nvtooltip\").data(a),l.enter().append(\"div\").attr(\"class\",\"nvtooltip \"+(i?i:\"xy-tooltip\")).attr(\"id\",d).style(\"top\",0).style(\"left\",0).style(\"opacity\",0).style(\"position\",\"fixed\").selectAll(\"div, table, td, tr\").classed(q,!0).classed(q,!0),l.exit().remove()}}function c(){return n&&w(e)?(a.dom.write(function(){b();var a=u(e);a&&(l.node().innerHTML=a),y()}),c):void 0}var d=\"nvtooltip-\"+Math.floor(1e5*Math.random()),e=null,f=\"w\",g=25,h=0,i=null,j=!0,k=200,l=null,m={left:null,top:null},n=!0,o=100,p=!0,q=\"nv-pointer-events-none\",r=function(a,b){return a},s=function(a){return a},t=function(a,b){return a},u=function(a){if(null===a)return\"\";var b=d3.select(document.createElement(\"table\"));if(p){var c=b.selectAll(\"thead\").data([a]).enter().append(\"thead\");c.append(\"tr\").append(\"td\").attr(\"colspan\",3).append(\"strong\").classed(\"x-value\",!0).html(s(a.value))}var d=b.selectAll(\"tbody\").data([a]).enter().append(\"tbody\"),e=d.selectAll(\"tr\").data(function(a){return a.series}).enter().append(\"tr\").classed(\"highlight\",function(a){return a.highlight});e.append(\"td\").classed(\"legend-color-guide\",!0).append(\"div\").style(\"background-color\",function(a){return a.color}),e.append(\"td\").classed(\"key\",!0).classed(\"total\",function(a){return!!a.total}).html(function(a,b){return t(a.key,b)}),e.append(\"td\").classed(\"value\",!0).html(function(a,b){return r(a.value,b)}),e.filter(function(a,b){return void 0!==a.percent}).append(\"td\").classed(\"percent\",!0).html(function(a,b){return\"(\"+d3.format(\"%\")(a.percent)+\")\"}),e.selectAll(\"td\").each(function(a){if(a.highlight){var b=d3.scale.linear().domain([0,1]).range([\"#fff\",a.color]),c=.6;d3.select(this).style(\"border-bottom-color\",b(c)).style(\"border-top-color\",b(c))}});var f=b.node().outerHTML;return void 0!==a.footer&&(f+=\"<div class='footer'>\"+a.footer+\"</div>\"),f},v=function(){var a={left:null!==d3.event?d3.event.clientX:0,top:null!==d3.event?d3.event.clientY:0};if(\"none\"!=getComputedStyle(document.body).transform){var b=document.body.getBoundingClientRect();a.left-=b.left,a.top-=b.top}return a},w=function(b){if(b&&b.series){if(a.utils.isArray(b.series))return!0;if(a.utils.isObject(b.series))return b.series=[b.series],!0}return!1},x=function(a){var b,c,d,e=l.node().offsetHeight,h=l.node().offsetWidth,i=document.documentElement.clientWidth,j=document.documentElement.clientHeight;switch(f){case\"e\":b=-h-g,c=-(e/2),a.left+b<0&&(b=g),(d=a.top+c)<0&&(c-=d),(d=a.top+c+e)>j&&(c-=d-j);break;case\"w\":b=g,c=-(e/2),a.left+b+h>i&&(b=-h-g),(d=a.top+c)<0&&(c-=d),(d=a.top+c+e)>j&&(c-=d-j);break;case\"n\":b=-(h/2)-5,c=g,a.top+c+e>j&&(c=-e-g),(d=a.left+b)<0&&(b-=d),(d=a.left+b+h)>i&&(b-=d-i);break;case\"s\":b=-(h/2),c=-e-g,a.top+c<0&&(c=g),(d=a.left+b)<0&&(b-=d),(d=a.left+b+h)>i&&(b-=d-i);break;case\"center\":b=-(h/2),c=-(e/2);break;default:b=0,c=0}return{left:b,top:c}},y=function(){a.dom.read(function(){var a=v(),b=x(a),c=a.left+b.left,d=a.top+b.top;if(j)l.interrupt().transition().delay(k).duration(0).style(\"opacity\",0);else{var e=\"translate(\"+m.left+\"px, \"+m.top+\"px)\",f=\"translate(\"+Math.round(c)+\"px, \"+Math.round(d)+\"px)\",g=d3.interpolateString(e,f),h=l.style(\"opacity\")<.1;l.interrupt().transition().duration(h?0:o).styleTween(\"transform\",function(a){return g},\"important\").styleTween(\"-webkit-transform\",function(a){return g}).style(\"-ms-transform\",f).style(\"opacity\",1)}m.left=c,m.top=d})};return c.nvPointerEventsClass=q,c.options=a.utils.optionsFunc.bind(c),c._options=Object.create({},{duration:{get:function(){return o},set:function(a){o=a}},gravity:{get:function(){return f},set:function(a){f=a}},distance:{get:function(){return g},set:function(a){g=a}},snapDistance:{get:function(){return h},set:function(a){h=a}},classes:{get:function(){return i},set:function(a){i=a}},enabled:{get:function(){return n},set:function(a){n=a}},hideDelay:{get:function(){return k},set:function(a){k=a}},contentGenerator:{get:function(){return u},set:function(a){u=a}},valueFormatter:{get:function(){return r},set:function(a){r=a}},headerFormatter:{get:function(){return s},set:function(a){s=a}},keyFormatter:{get:function(){return t},set:function(a){t=a}},headerEnabled:{get:function(){return p},set:function(a){p=a}},position:{get:function(){return v},set:function(a){v=a}},chartContainer:{get:function(){return document.body},set:function(b){a.deprecated(\"chartContainer\",\"feature removed after 1.8.3\")}},fixedTop:{get:function(){return null},set:function(b){a.deprecated(\"fixedTop\",\"feature removed after 1.8.1\")}},offset:{get:function(){return{left:0,top:0}},set:function(b){a.deprecated(\"offset\",\"use chart.tooltip.distance() instead\")}},hidden:{get:function(){return j},set:function(a){j!=a&&(j=!!a,c())}},data:{get:function(){return e},set:function(a){a.point&&(a.value=a.point.x,a.series=a.series||{},a.series.value=a.point.y,a.series.color=a.point.color||a.series.color),e=a}},node:{get:function(){return l.node()},set:function(a){}},id:{get:function(){return d},set:function(a){}}}),a.utils.initOptions(c),c},a.utils.windowSize=function(){var a={width:640,height:480};return window.innerWidth&&window.innerHeight?(a.width=window.innerWidth,a.height=window.innerHeight,a):\"CSS1Compat\"==document.compatMode&&document.documentElement&&document.documentElement.offsetWidth?(a.width=document.documentElement.offsetWidth,a.height=document.documentElement.offsetHeight,a):document.body&&document.body.offsetWidth?(a.width=document.body.offsetWidth,a.height=document.body.offsetHeight,a):a},a.utils.isArray=Array.isArray,a.utils.isObject=function(a){return null!==a&&\"object\"==typeof a},a.utils.isFunction=function(a){return\"function\"==typeof a},a.utils.isDate=function(a){return\"[object Date]\"===toString.call(a)},a.utils.isNumber=function(a){return!isNaN(a)&&\"number\"==typeof a},a.utils.windowResize=function(b){return window.addEventListener?window.addEventListener(\"resize\",b):a.log(\"ERROR: Failed to bind to window.resize with: \",b),{callback:b,clear:function(){window.removeEventListener(\"resize\",b)}}},a.utils.getColor=function(b){if(void 0===b)return a.utils.defaultColor();if(a.utils.isArray(b)){var c=d3.scale.ordinal().range(b);return function(a,b){var d=void 0===b?a:b;return a.color||c(d)}}return b},a.utils.defaultColor=function(){return a.utils.getColor(d3.scale.category20().range())},a.utils.customTheme=function(b,c,d){c=c||function(a){return a.key},d=d||d3.scale.category20().range();var e=d.length;return function(f,g){var h=c(f);return a.utils.isFunction(b[h])?b[h]():void 0!==b[h]?b[h]:(e||(e=d.length),e-=1,d[e])}},a.utils.pjax=function(b,c){var d=function(d){d3.html(d,function(d){var e=d3.select(c).node();e.parentNode.replaceChild(d3.select(d).select(c).node(),e),a.utils.pjax(b,c)})};d3.selectAll(b).on(\"click\",function(){history.pushState(this.href,this.textContent,this.href),d(this.href),d3.event.preventDefault()}),d3.select(window).on(\"popstate\",function(){d3.event.state&&d(d3.event.state)})},a.utils.calcApproxTextWidth=function(b){if(a.utils.isFunction(b.style)&&a.utils.isFunction(b.text)){var c=parseInt(b.style(\"font-size\").replace(\"px\",\"\"),10),d=b.text().length;return a.utils.NaNtoZero(d*c*.5)}return 0},a.utils.NaNtoZero=function(b){return!a.utils.isNumber(b)||isNaN(b)||null===b||b===1/0||b===-(1/0)?0:b},d3.selection.prototype.watchTransition=function(a){var b=[this].concat([].slice.call(arguments,1));return a.transition.apply(a,b)},a.utils.renderWatch=function(b,c){if(!(this instanceof a.utils.renderWatch))return new a.utils.renderWatch(b,c);var d=void 0!==c?c:250,e=[],f=this;this.models=function(a){return a=[].slice.call(arguments,0),a.forEach(function(a){a.__rendered=!1,function(a){a.dispatch.on(\"renderEnd\",function(b){a.__rendered=!0,f.renderEnd(\"model\")})}(a),e.indexOf(a)<0&&e.push(a)}),this},this.reset=function(a){void 0!==a&&(d=a),e=[]},this.transition=function(a,b,c){if(b=arguments.length>1?[].slice.call(arguments,1):[],c=b.length>1?b.pop():void 0!==d?d:250,a.__rendered=!1,e.indexOf(a)<0&&e.push(a),0===c)return a.__rendered=!0,a.delay=function(){return this},a.duration=function(){return this},a;0===a.length?a.__rendered=!0:a.every(function(a){return!a.length})?a.__rendered=!0:a.__rendered=!1;var g=0;return a.transition().duration(c).each(function(){++g}).each(\"end\",function(c,d){0===--g&&(a.__rendered=!0,f.renderEnd.apply(this,b))})},this.renderEnd=function(){e.every(function(a){return a.__rendered})&&(e.forEach(function(a){a.__rendered=!1}),b.renderEnd.apply(this,arguments))}},a.utils.deepExtend=function(b){var c=arguments.length>1?[].slice.call(arguments,1):[];c.forEach(function(c){for(var d in c){var e=a.utils.isArray(b[d]),f=a.utils.isObject(b[d]),g=a.utils.isObject(c[d]);f&&!e&&g?a.utils.deepExtend(b[d],c[d]):b[d]=c[d]}})},a.utils.state=function(){if(!(this instanceof a.utils.state))return new a.utils.state;var b={},c=function(){},d=function(){return{}},e=null,f=null;this.dispatch=d3.dispatch(\"change\",\"set\"),this.dispatch.on(\"set\",function(a){c(a,!0)}),this.getter=function(a){return d=a,this},this.setter=function(a,b){return b||(b=function(){}),c=function(c,d){a(c),d&&b()},this},this.init=function(b){e=e||{},a.utils.deepExtend(e,b)};var g=function(){var a=d();if(JSON.stringify(a)===JSON.stringify(b))return!1;for(var c in a)void 0===b[c]&&(b[c]={}),b[c]=a[c],f=!0;return!0};this.update=function(){e&&(c(e,!1),e=null),g.call(this)&&this.dispatch.change(b)}},a.utils.optionsFunc=function(b){return b&&d3.map(b).forEach(function(b,c){a.utils.isFunction(this[b])&&this[b](c)}.bind(this)),this},a.utils.calcTicksX=function(b,c){var d=1,e=0;for(e;e<c.length;e+=1){var f=c[e]&&c[e].values?c[e].values.length:0;d=f>d?f:d}return a.log(\"Requested number of ticks: \",b),a.log(\"Calculated max values to be: \",d),b=b>d?b=d-1:b,b=1>b?1:b,b=Math.floor(b),a.log(\"Calculating tick count as: \",b),b},a.utils.calcTicksY=function(b,c){return a.utils.calcTicksX(b,c)},a.utils.initOption=function(a,b){a._calls&&a._calls[b]?a[b]=a._calls[b]:(a[b]=function(c){return arguments.length?(a._overrides[b]=!0,a._options[b]=c,a):a._options[b]},a[\"_\"+b]=function(c){return arguments.length?(a._overrides[b]||(a._options[b]=c),a):a._options[b]})},a.utils.initOptions=function(b){b._overrides=b._overrides||{};var c=Object.getOwnPropertyNames(b._options||{}),d=Object.getOwnPropertyNames(b._calls||{});c=c.concat(d);for(var e in c)a.utils.initOption(b,c[e])},a.utils.inheritOptionsD3=function(a,b,c){a._d3options=c.concat(a._d3options||[]),c.unshift(b),c.unshift(a),d3.rebind.apply(this,c)},a.utils.arrayUnique=function(a){return a.sort().filter(function(b,c){return!c||b!=a[c-1]})},a.utils.symbolMap=d3.map(),a.utils.symbol=function(){function b(b,e){var f=c.call(this,b,e),g=d.call(this,b,e);return-1!==d3.svg.symbolTypes.indexOf(f)?d3.svg.symbol().type(f).size(g)():a.utils.symbolMap.get(f)(g)}var c,d=64;return b.type=function(a){return arguments.length?(c=d3.functor(a),b):c},b.size=function(a){return arguments.length?(d=d3.functor(a),b):d},b},a.utils.inheritOptions=function(b,c){var d=Object.getOwnPropertyNames(c._options||{}),e=Object.getOwnPropertyNames(c._calls||{}),f=c._inherited||[],g=c._d3options||[],h=d.concat(e).concat(f).concat(g);h.unshift(c),h.unshift(b),d3.rebind.apply(this,h),b._inherited=a.utils.arrayUnique(d.concat(e).concat(f).concat(d).concat(b._inherited||[])),b._d3options=a.utils.arrayUnique(g.concat(b._d3options||[]))},a.utils.initSVG=function(a){a.classed({\"nvd3-svg\":!0})},a.utils.sanitizeHeight=function(a,b){return a||parseInt(b.style(\"height\"),10)||400},a.utils.sanitizeWidth=function(a,b){return a||parseInt(b.style(\"width\"),10)||960},a.utils.availableHeight=function(b,c,d){return Math.max(0,a.utils.sanitizeHeight(b,c)-d.top-d.bottom)},a.utils.availableWidth=function(b,c,d){return Math.max(0,a.utils.sanitizeWidth(b,c)-d.left-d.right)},a.utils.noData=function(b,c){var d=b.options(),e=d.margin(),f=d.noData(),g=null==f?[\"No Data Available.\"]:[f],h=a.utils.availableHeight(null,c,e),i=a.utils.availableWidth(null,c,e),j=e.left+i/2,k=e.top+h/2;c.selectAll(\"g\").remove();var l=c.selectAll(\".nv-noData\").data(g);l.enter().append(\"text\").attr(\"class\",\"nvd3 nv-noData\").attr(\"dy\",\"-.7em\").style(\"text-anchor\",\"middle\"),l.attr(\"x\",j).attr(\"y\",k).text(function(a){return a})},a.utils.wrapTicks=function(a,b){a.each(function(){for(var a,c=d3.select(this),d=c.text().split(/\\s+/).reverse(),e=[],f=0,g=1.1,h=c.attr(\"y\"),i=parseFloat(c.attr(\"dy\")),j=c.text(null).append(\"tspan\").attr(\"x\",0).attr(\"y\",h).attr(\"dy\",i+\"em\");a=d.pop();)e.push(a),j.text(e.join(\" \")),j.node().getComputedTextLength()>b&&(e.pop(),j.text(e.join(\" \")),e=[a],j=c.append(\"tspan\").attr(\"x\",0).attr(\"y\",h).attr(\"dy\",++f*g+i+\"em\").text(a))})},a.utils.arrayEquals=function(b,c){if(b===c)return!0;if(!b||!c)return!1;if(b.length!=c.length)return!1;for(var d=0,e=b.length;e>d;d++)if(b[d]instanceof Array&&c[d]instanceof Array){if(!a.arrayEquals(b[d],c[d]))return!1}else if(b[d]!=c[d])return!1;return!0},a.models.axis=function(){\"use strict\";function b(g){return t.reset(),g.each(function(b){var g=d3.select(this);a.utils.initSVG(g);var q=g.selectAll(\"g.nv-wrap.nv-axis\").data([b]),r=q.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-axis\"),u=(r.append(\"g\"),q.select(\"g\"));null!==n?c.ticks(n):(\"top\"==c.orient()||\"bottom\"==c.orient())&&c.ticks(Math.abs(d.range()[1]-d.range()[0])/100),u.watchTransition(t,\"axis\").call(c),s=s||c.scale();var v=c.tickFormat();null==v&&(v=s.tickFormat());var w=u.selectAll(\"text.nv-axislabel\").data([h||null]);w.exit().remove(),void 0!==p&&u.selectAll(\"g\").select(\"text\").style(\"font-size\",p);var x,y,z;switch(c.orient()){case\"top\":w.enter().append(\"text\").attr(\"class\",\"nv-axislabel\"),z=0,1===d.range().length?z=m?2*d.range()[0]+d.rangeBand():0:2===d.range().length?z=m?d.range()[0]+d.range()[1]+d.rangeBand():d.range()[1]:d.range().length>2&&(z=d.range()[d.range().length-1]+(d.range()[1]-d.range()[0])),w.attr(\"text-anchor\",\"middle\").attr(\"y\",0).attr(\"x\",z/2),i&&(y=q.selectAll(\"g.nv-axisMaxMin\").data(d.domain()),y.enter().append(\"g\").attr(\"class\",function(a,b){return[\"nv-axisMaxMin\",\"nv-axisMaxMin-x\",0==b?\"nv-axisMin-x\":\"nv-axisMax-x\"].join(\" \")}).append(\"text\"),y.exit().remove(),y.attr(\"transform\",function(b,c){return\"translate(\"+a.utils.NaNtoZero(d(b))+\",0)\"}).select(\"text\").attr(\"dy\",\"-0.5em\").attr(\"y\",-c.tickPadding()).attr(\"text-anchor\",\"middle\").text(function(a,b){var c=v(a);return(\"\"+c).match(\"NaN\")?\"\":c}),y.watchTransition(t,\"min-max top\").attr(\"transform\",function(b,c){return\"translate(\"+a.utils.NaNtoZero(d.range()[c])+\",0)\"}));break;case\"bottom\":x=o+36;var A=30,B=0,C=u.selectAll(\"g\").select(\"text\"),D=\"\";if(j%360){C.attr(\"transform\",\"\"),C.each(function(a,b){var c=this.getBoundingClientRect(),d=c.width;B=c.height,d>A&&(A=d)}),D=\"rotate(\"+j+\" 0,\"+(B/2+c.tickPadding())+\")\";var E=Math.abs(Math.sin(j*Math.PI/180));x=(E?E*A:A)+30,C.attr(\"transform\",D).style(\"text-anchor\",j%360>0?\"start\":\"end\")}else l?C.attr(\"transform\",function(a,b){return\"translate(0,\"+(b%2==0?\"0\":\"12\")+\")\"}):C.attr(\"transform\",\"translate(0,0)\");w.enter().append(\"text\").attr(\"class\",\"nv-axislabel\"),z=0,1===d.range().length?z=m?2*d.range()[0]+d.rangeBand():0:2===d.range().length?z=m?d.range()[0]+d.range()[1]+d.rangeBand():d.range()[1]:d.range().length>2&&(z=d.range()[d.range().length-1]+(d.range()[1]-d.range()[0])),w.attr(\"text-anchor\",\"middle\").attr(\"y\",x).attr(\"x\",z/2),i&&(y=q.selectAll(\"g.nv-axisMaxMin\").data([d.domain()[0],d.domain()[d.domain().length-1]]),y.enter().append(\"g\").attr(\"class\",function(a,b){return[\"nv-axisMaxMin\",\"nv-axisMaxMin-x\",0==b?\"nv-axisMin-x\":\"nv-axisMax-x\"].join(\" \")}).append(\"text\"),y.exit().remove(),y.attr(\"transform\",function(b,c){return\"translate(\"+a.utils.NaNtoZero(d(b)+(m?d.rangeBand()/2:0))+\",0)\"}).select(\"text\").attr(\"dy\",\".71em\").attr(\"y\",c.tickPadding()).attr(\"transform\",D).style(\"text-anchor\",j?j%360>0?\"start\":\"end\":\"middle\").text(function(a,b){var c=v(a);return(\"\"+c).match(\"NaN\")?\"\":c}),y.watchTransition(t,\"min-max bottom\").attr(\"transform\",function(b,c){return\"translate(\"+a.utils.NaNtoZero(d(b)+(m?d.rangeBand()/2:0))+\",0)\"}));break;case\"right\":w.enter().append(\"text\").attr(\"class\",\"nv-axislabel\"),w.style(\"text-anchor\",k?\"middle\":\"begin\").attr(\"transform\",k?\"rotate(90)\":\"\").attr(\"y\",k?-Math.max(e.right,f)+12-(o||0):-10).attr(\"x\",k?d3.max(d.range())/2:c.tickPadding()),i&&(y=q.selectAll(\"g.nv-axisMaxMin\").data(d.domain()),y.enter().append(\"g\").attr(\"class\",function(a,b){return[\"nv-axisMaxMin\",\"nv-axisMaxMin-y\",0==b?\"nv-axisMin-y\":\"nv-axisMax-y\"].join(\" \")}).append(\"text\").style(\"opacity\",0),y.exit().remove(),y.attr(\"transform\",function(b,c){return\"translate(0,\"+a.utils.NaNtoZero(d(b))+\")\"}).select(\"text\").attr(\"dy\",\".32em\").attr(\"y\",0).attr(\"x\",c.tickPadding()).style(\"text-anchor\",\"start\").text(function(a,b){var c=v(a);return(\"\"+c).match(\"NaN\")?\"\":c}),y.watchTransition(t,\"min-max right\").attr(\"transform\",function(b,c){return\"translate(0,\"+a.utils.NaNtoZero(d.range()[c])+\")\"}).select(\"text\").style(\"opacity\",1));break;case\"left\":w.enter().append(\"text\").attr(\"class\",\"nv-axislabel\"),w.style(\"text-anchor\",k?\"middle\":\"end\").attr(\"transform\",k?\"rotate(-90)\":\"\").attr(\"y\",k?-Math.max(e.left,f)+25-(o||0):-10).attr(\"x\",k?-d3.max(d.range())/2:-c.tickPadding()),i&&(y=q.selectAll(\"g.nv-axisMaxMin\").data(d.domain()),y.enter().append(\"g\").attr(\"class\",function(a,b){return[\"nv-axisMaxMin\",\"nv-axisMaxMin-y\",0==b?\"nv-axisMin-y\":\"nv-axisMax-y\"].join(\" \")}).append(\"text\").style(\"opacity\",0),y.exit().remove(),y.attr(\"transform\",function(b,c){return\"translate(0,\"+a.utils.NaNtoZero(s(b))+\")\"}).select(\"text\").attr(\"dy\",\".32em\").attr(\"y\",0).attr(\"x\",-c.tickPadding()).attr(\"text-anchor\",\"end\").text(function(a,b){var c=v(a);return(\"\"+c).match(\"NaN\")?\"\":c}),y.watchTransition(t,\"min-max right\").attr(\"transform\",function(b,c){return\"translate(0,\"+a.utils.NaNtoZero(d.range()[c])+\")\"}).select(\"text\").style(\"opacity\",1))}if(w.text(function(a){return a}),!i||\"left\"!==c.orient()&&\"right\"!==c.orient()||(u.selectAll(\"g\").each(function(a,b){d3.select(this).select(\"text\").attr(\"opacity\",1),(d(a)<d.range()[1]+10||d(a)>d.range()[0]-10)&&((a>1e-10||-1e-10>a)&&d3.select(this).attr(\"opacity\",0),d3.select(this).select(\"text\").attr(\"opacity\",0))}),d.domain()[0]==d.domain()[1]&&0==d.domain()[0]&&q.selectAll(\"g.nv-axisMaxMin\").style(\"opacity\",function(a,b){return b?0:1})),i&&(\"top\"===c.orient()||\"bottom\"===c.orient())){var F=[];q.selectAll(\"g.nv-axisMaxMin\").each(function(a,b){try{b?F.push(d(a)-this.getBoundingClientRect().width-4):F.push(d(a)+this.getBoundingClientRect().width+4)}catch(c){b?F.push(d(a)-4):F.push(d(a)+4)}}),u.selectAll(\"g\").each(function(a,b){(d(a)<F[0]||d(a)>F[1])&&(a>1e-10||-1e-10>a?d3.select(this).remove():d3.select(this).select(\"text\").remove())})}u.selectAll(\".tick\").filter(function(a){return!parseFloat(Math.round(1e5*a)/1e6)&&void 0!==a}).classed(\"zero\",!0),s=d.copy()}),t.renderEnd(\"axis immediate\"),b}var c=d3.svg.axis(),d=d3.scale.linear(),e={top:0,right:0,bottom:0,left:0},f=75,g=60,h=null,i=!0,j=0,k=!0,l=!1,m=!1,n=null,o=0,p=void 0,q=250,r=d3.dispatch(\"renderEnd\");c.scale(d).orient(\"bottom\").tickFormat(function(a){return a});var s,t=a.utils.renderWatch(r,q);return b.axis=c,b.dispatch=r,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{axisLabelDistance:{get:function(){return o},set:function(a){o=a}},staggerLabels:{get:function(){return l},set:function(a){l=a}},rotateLabels:{get:function(){return j},set:function(a){j=a}},rotateYLabel:{get:function(){return k},set:function(a){k=a}},showMaxMin:{get:function(){return i},set:function(a){i=a}},axisLabel:{get:function(){return h},set:function(a){h=a}},height:{get:function(){return g},set:function(a){g=a}},ticks:{get:function(){return n},set:function(a){n=a}},width:{get:function(){return f},set:function(a){f=a}},fontSize:{get:function(){return p},set:function(a){p=a}},margin:{get:function(){return e},set:function(a){e.top=void 0!==a.top?a.top:e.top,e.right=void 0!==a.right?a.right:e.right,e.bottom=void 0!==a.bottom?a.bottom:e.bottom,e.left=void 0!==a.left?a.left:e.left}},duration:{get:function(){return q},set:function(a){q=a,t.reset(q)}},scale:{get:function(){return d},set:function(e){d=e,c.scale(d),m=\"function\"==typeof d.rangeBands,a.utils.inheritOptionsD3(b,d,[\"domain\",\"range\",\"rangeBand\",\"rangeBands\"])}}}),a.utils.initOptions(b),a.utils.inheritOptionsD3(b,c,[\"orient\",\"tickValues\",\"tickSubdivide\",\"tickSize\",\"tickPadding\",\"tickFormat\"]),a.utils.inheritOptionsD3(b,d,[\"domain\",\"range\",\"rangeBand\",\"rangeBands\"]),b},a.models.boxPlot=function(){\"use strict\";function b(l){return E.reset(),l.each(function(b){var l=j-i.left-i.right,F=k-i.top-i.bottom;A=d3.select(this),a.utils.initSVG(A),m.domain(c||b.map(function(a,b){return o(a,b)})).rangeBands(d||[0,l],.1);var G=[];if(!e){var H,I,J=[];b.forEach(function(a,b){var c=p(a),d=r(a),e=s(a),f=t(a),g=v(a);g&&g.forEach(function(a,b){J.push(w(a,b,void 0))}),e&&J.push(e),c&&J.push(c),d&&J.push(d),f&&J.push(f)}),H=d3.min(J),I=d3.max(J),G=[H,I]}n.domain(e||G),n.range(f||[F,0]),g=g||m,h=h||n.copy().range([n(0),n(0)]);var K=A.selectAll(\"g.nv-wrap\").data([b]);K.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap\");K.attr(\"transform\",\"translate(\"+i.left+\",\"+i.top+\")\");var L=K.selectAll(\".nv-boxplot\").data(function(a){return a}),M=L.enter().append(\"g\").style(\"stroke-opacity\",1e-6).style(\"fill-opacity\",1e-6);L.attr(\"class\",\"nv-boxplot\").attr(\"transform\",function(a,b,c){return\"translate(\"+(m(o(a,b))+.05*m.rangeBand())+\", 0)\"}).classed(\"hover\",function(a){return a.hover}),L.watchTransition(E,\"nv-boxplot: boxplots\").style(\"stroke-opacity\",1).style(\"fill-opacity\",.75).delay(function(a,c){return c*C/b.length}).attr(\"transform\",function(a,b){return\"translate(\"+(m(o(a,b))+.05*m.rangeBand())+\", 0)\"}),L.exit().remove(),M.each(function(a,b){var c=d3.select(this);[s,t].forEach(function(d){if(d(a)){var e=d===s?\"low\":\"high\";c.append(\"line\").style(\"stroke\",u(a)||z(a,b)).attr(\"class\",\"nv-boxplot-whisker nv-boxplot-\"+e),c.append(\"line\").style(\"stroke\",u(a)||z(a,b)).attr(\"class\",\"nv-boxplot-tick nv-boxplot-\"+e)}})});var N=function(){return null===D?.9*m.rangeBand():Math.min(75,.9*m.rangeBand())},O=function(){return.45*m.rangeBand()-N()/2},P=function(){return.45*m.rangeBand()+N()/2};[s,t].forEach(function(a){var b=a===s?\"low\":\"high\",c=a===s?p:r;L.select(\"line.nv-boxplot-whisker.nv-boxplot-\"+b).watchTransition(E,\"nv-boxplot: boxplots\").attr(\"x1\",.45*m.rangeBand()).attr(\"y1\",function(b,c){return n(a(b))}).attr(\"x2\",.45*m.rangeBand()).attr(\"y2\",function(a,b){return n(c(a))}),L.select(\"line.nv-boxplot-tick.nv-boxplot-\"+b).watchTransition(E,\"nv-boxplot: boxplots\").attr(\"x1\",O).attr(\"y1\",function(b,c){return n(a(b))}).attr(\"x2\",P).attr(\"y2\",function(b,c){return n(a(b))})}),[s,t].forEach(function(a){var b=a===s?\"low\":\"high\";M.selectAll(\".nv-boxplot-\"+b).on(\"mouseover\",function(b,c,d){d3.select(this).classed(\"hover\",!0),B.elementMouseover({series:{key:a(b),color:u(b)||z(b,d)},e:d3.event})}).on(\"mouseout\",function(b,c,d){d3.select(this).classed(\"hover\",!1),B.elementMouseout({series:{key:a(b),color:u(b)||z(b,d)},e:d3.event})}).on(\"mousemove\",function(a,b){B.elementMousemove({e:d3.event})})}),M.append(\"rect\").attr(\"class\",\"nv-boxplot-box\").on(\"mouseover\",function(a,b){d3.select(this).classed(\"hover\",!0),B.elementMouseover({key:o(a),value:o(a),series:[{key:\"Q3\",value:r(a),color:u(a)||z(a,b)},{key:\"Q2\",value:q(a),color:u(a)||z(a,b)},{key:\"Q1\",value:p(a),color:u(a)||z(a,b)}],data:a,index:b,e:d3.event})}).on(\"mouseout\",function(a,b){d3.select(this).classed(\"hover\",!1),B.elementMouseout({key:o(a),value:o(a),series:[{key:\"Q3\",value:r(a),color:u(a)||z(a,b)},{key:\"Q2\",value:q(a),color:u(a)||z(a,b)},{key:\"Q1\",value:p(a),color:u(a)||z(a,b)}],data:a,index:b,e:d3.event})}).on(\"mousemove\",function(a,b){B.elementMousemove({e:d3.event})}),L.select(\"rect.nv-boxplot-box\").watchTransition(E,\"nv-boxplot: boxes\").attr(\"y\",function(a,b){return n(r(a))}).attr(\"width\",N).attr(\"x\",O).attr(\"height\",function(a,b){return Math.abs(n(r(a))-n(p(a)))||1}).style(\"fill\",function(a,b){return u(a)||z(a,b)}).style(\"stroke\",function(a,b){return u(a)||z(a,b)}),M.append(\"line\").attr(\"class\",\"nv-boxplot-median\"),L.select(\"line.nv-boxplot-median\").watchTransition(E,\"nv-boxplot: boxplots line\").attr(\"x1\",O).attr(\"y1\",function(a,b){return n(q(a))}).attr(\"x2\",P).attr(\"y2\",function(a,b){return n(q(a))});var Q=L.selectAll(\".nv-boxplot-outlier\").data(function(a){return v(a)||[]});Q.enter().append(\"circle\").style(\"fill\",function(a,b,c){return y(a,b,c)||z(a,c)}).style(\"stroke\",function(a,b,c){return y(a,b,c)||z(a,c)}).style(\"z-index\",9e3).on(\"mouseover\",function(a,b,c){d3.select(this).classed(\"hover\",!0),B.elementMouseover({series:{key:x(a,b,c),color:y(a,b,c)||z(a,c)},e:d3.event})}).on(\"mouseout\",function(a,b,c){d3.select(this).classed(\"hover\",!1),B.elementMouseout({series:{key:x(a,b,c),color:y(a,b,c)||z(a,c)},e:d3.event})}).on(\"mousemove\",function(a,b){B.elementMousemove({e:d3.event})}),Q.attr(\"class\",\"nv-boxplot-outlier\"),Q.watchTransition(E,\"nv-boxplot: nv-boxplot-outlier\").attr(\"cx\",.45*m.rangeBand()).attr(\"cy\",function(a,b,c){return n(w(a,b,c))}).attr(\"r\",\"3\"),Q.exit().remove(),g=m.copy(),h=n.copy()}),E.renderEnd(\"nv-boxplot immediate\"),b}var c,d,e,f,g,h,i={top:0,right:0,bottom:0,left:0},j=960,k=500,l=Math.floor(1e4*Math.random()),m=d3.scale.ordinal(),n=d3.scale.linear(),o=function(a){return a.label},p=function(a){return a.values.Q1},q=function(a){return a.values.Q2},r=function(a){return a.values.Q3},s=function(a){return a.values.whisker_low},t=function(a){return a.values.whisker_high},u=function(a){return a.color},v=function(a){return a.values.outliers},w=function(a,b,c){return a},x=function(a,b,c){return a},y=function(a,b,c){return void 0},z=a.utils.defaultColor(),A=null,B=d3.dispatch(\"elementMouseover\",\"elementMouseout\",\"elementMousemove\",\"renderEnd\"),C=250,D=null,E=a.utils.renderWatch(B,C);return b.dispatch=B,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return j},set:function(a){j=a}},height:{get:function(){return k},set:function(a){k=a}},maxBoxWidth:{get:function(){return D},set:function(a){D=a}},x:{get:function(){return o},set:function(a){o=a}},q1:{get:function(){return p},set:function(a){p=a}},q2:{get:function(){return q},set:function(a){q=a}},q3:{get:function(){return r},set:function(a){r=a}},wl:{get:function(){return s},set:function(a){s=a}},wh:{get:function(){return t},set:function(a){t=a}},itemColor:{get:function(){return u},set:function(a){u=a}},outliers:{get:function(){return v},set:function(a){v=a;}},outlierValue:{get:function(){return w},set:function(a){w=a}},outlierLabel:{get:function(){return x},set:function(a){x=a}},outlierColor:{get:function(){return y},set:function(a){y=a}},xScale:{get:function(){return m},set:function(a){m=a}},yScale:{get:function(){return n},set:function(a){n=a}},xDomain:{get:function(){return c},set:function(a){c=a}},yDomain:{get:function(){return e},set:function(a){e=a}},xRange:{get:function(){return d},set:function(a){d=a}},yRange:{get:function(){return f},set:function(a){f=a}},id:{get:function(){return l},set:function(a){l=a}},y:{get:function(){return console.warn(\"BoxPlot 'y' chart option is deprecated. Please use model overrides instead.\"),{}},set:function(a){console.warn(\"BoxPlot 'y' chart option is deprecated. Please use model overrides instead.\")}},margin:{get:function(){return i},set:function(a){i.top=void 0!==a.top?a.top:i.top,i.right=void 0!==a.right?a.right:i.right,i.bottom=void 0!==a.bottom?a.bottom:i.bottom,i.left=void 0!==a.left?a.left:i.left}},color:{get:function(){return z},set:function(b){z=a.utils.getColor(b)}},duration:{get:function(){return C},set:function(a){C=a,E.reset(C)}}}),a.utils.initOptions(b),b},a.models.boxPlotChart=function(){\"use strict\";function b(k){return t.reset(),t.models(e),l&&t.models(f),m&&t.models(g),k.each(function(k){var p=d3.select(this);a.utils.initSVG(p);var t=(i||parseInt(p.style(\"width\"))||960)-h.left-h.right,u=(j||parseInt(p.style(\"height\"))||400)-h.top-h.bottom;if(b.update=function(){r.beforeUpdate(),p.transition().duration(s).call(b)},b.container=this,!k||!k.length){var v=p.selectAll(\".nv-noData\").data([q]);return v.enter().append(\"text\").attr(\"class\",\"nvd3 nv-noData\").attr(\"dy\",\"-.7em\").style(\"text-anchor\",\"middle\"),v.attr(\"x\",h.left+t/2).attr(\"y\",h.top+u/2).text(function(a){return a}),b}p.selectAll(\".nv-noData\").remove(),c=e.xScale(),d=e.yScale().clamp(!0);var w=p.selectAll(\"g.nv-wrap.nv-boxPlotWithAxes\").data([k]),x=w.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-boxPlotWithAxes\").append(\"g\"),y=x.append(\"defs\"),z=w.select(\"g\");x.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),x.append(\"g\").attr(\"class\",\"nv-y nv-axis\").append(\"g\").attr(\"class\",\"nv-zeroLine\").append(\"line\"),x.append(\"g\").attr(\"class\",\"nv-barsWrap\"),z.attr(\"transform\",\"translate(\"+h.left+\",\"+h.top+\")\"),n&&z.select(\".nv-y.nv-axis\").attr(\"transform\",\"translate(\"+t+\",0)\"),e.width(t).height(u);var A=z.select(\".nv-barsWrap\").datum(k.filter(function(a){return!a.disabled}));if(A.transition().call(e),y.append(\"clipPath\").attr(\"id\",\"nv-x-label-clip-\"+e.id()).append(\"rect\"),z.select(\"#nv-x-label-clip-\"+e.id()+\" rect\").attr(\"width\",c.rangeBand()*(o?2:1)).attr(\"height\",16).attr(\"x\",-c.rangeBand()/(o?1:2)),l){f.scale(c).ticks(a.utils.calcTicksX(t/100,k)).tickSize(-u,0),z.select(\".nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+d.range()[0]+\")\"),z.select(\".nv-x.nv-axis\").call(f);var B=z.select(\".nv-x.nv-axis\").selectAll(\"g\");o&&B.selectAll(\"text\").attr(\"transform\",function(a,b,c){return\"translate(0,\"+(c%2===0?\"5\":\"17\")+\")\"})}m&&(g.scale(d).ticks(Math.floor(u/36)).tickSize(-t,0),z.select(\".nv-y.nv-axis\").call(g)),z.select(\".nv-zeroLine line\").attr(\"x1\",0).attr(\"x2\",t).attr(\"y1\",d(0)).attr(\"y2\",d(0))}),t.renderEnd(\"nv-boxplot chart immediate\"),b}var c,d,e=a.models.boxPlot(),f=a.models.axis(),g=a.models.axis(),h={top:15,right:10,bottom:50,left:60},i=null,j=null,k=a.utils.getColor(),l=!0,m=!0,n=!1,o=!1,p=a.models.tooltip(),q=\"No Data Available.\",r=d3.dispatch(\"beforeUpdate\",\"renderEnd\"),s=250;f.orient(\"bottom\").showMaxMin(!1).tickFormat(function(a){return a}),g.orient(n?\"right\":\"left\").tickFormat(d3.format(\",.1f\")),p.duration(0);var t=a.utils.renderWatch(r,s);return e.dispatch.on(\"elementMouseover.tooltip\",function(a){p.data(a).hidden(!1)}),e.dispatch.on(\"elementMouseout.tooltip\",function(a){p.data(a).hidden(!0)}),e.dispatch.on(\"elementMousemove.tooltip\",function(a){p()}),b.dispatch=r,b.boxplot=e,b.xAxis=f,b.yAxis=g,b.tooltip=p,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return i},set:function(a){i=a}},height:{get:function(){return j},set:function(a){j=a}},staggerLabels:{get:function(){return o},set:function(a){o=a}},showXAxis:{get:function(){return l},set:function(a){l=a}},showYAxis:{get:function(){return m},set:function(a){m=a}},tooltipContent:{get:function(){return p},set:function(a){p=a}},noData:{get:function(){return q},set:function(a){q=a}},margin:{get:function(){return h},set:function(a){h.top=void 0!==a.top?a.top:h.top,h.right=void 0!==a.right?a.right:h.right,h.bottom=void 0!==a.bottom?a.bottom:h.bottom,h.left=void 0!==a.left?a.left:h.left}},duration:{get:function(){return s},set:function(a){s=a,t.reset(s),e.duration(s),f.duration(s),g.duration(s)}},color:{get:function(){return k},set:function(b){k=a.utils.getColor(b),e.color(k)}},rightAlignYAxis:{get:function(){return n},set:function(a){n=a,g.orient(a?\"right\":\"left\")}}}),a.utils.inheritOptions(b,e),a.utils.initOptions(b),b},a.models.bullet=function(){\"use strict\";function b(a,b){var c=a.slice();a.sort(function(a,d){var e=c.indexOf(a),f=c.indexOf(d);return d3.descending(b[e],b[f])})}function c(e){return e.each(function(c,e){var s=p-d.left-d.right,x=q-d.top-d.bottom;r=d3.select(this),a.utils.initSVG(r);var y=g.call(this,c,e).slice(),z=h.call(this,c,e).slice(),A=i.call(this,c,e).slice().sort(d3.descending),B=j.call(this,c,e).slice(),C=k.call(this,c,e).slice(),D=l.call(this,c,e).slice(),E=m.call(this,c,e).slice(),F=n.call(this,c,e).slice();b(C,y),b(D,z),b(E,A),b(F,B),y.sort(d3.descending),z.sort(d3.descending),B.sort(d3.descending);var G=d3.scale.linear().domain(d3.extent(d3.merge([o,y]))).range(f?[s,0]:[0,s]);this.__chart__||d3.scale.linear().domain([0,1/0]).range(G.range());this.__chart__=G;for(var H=(d3.min(y),d3.max(y),y[1],r.selectAll(\"g.nv-wrap.nv-bullet\").data([c])),I=H.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-bullet\"),J=I.append(\"g\"),K=H.select(\"g\"),e=0,L=y.length;L>e;e++){var M=\"nv-range nv-range\"+e;2>=e&&(M=M+\" nv-range\"+w[e]),J.append(\"rect\").attr(\"class\",M)}J.append(\"rect\").attr(\"class\",\"nv-measure\"),H.attr(\"transform\",\"translate(\"+d.left+\",\"+d.top+\")\");for(var N=function(a){return Math.abs(G(a)-G(0))},O=function(a){return G(0>a?a:0)},e=0,L=y.length;L>e;e++){var P=y[e];K.select(\"rect.nv-range\"+e).attr(\"height\",x).attr(\"width\",N(P)).attr(\"x\",O(P)).datum(P)}K.select(\"rect.nv-measure\").style(\"fill\",t).attr(\"height\",x/3).attr(\"y\",x/3).attr(\"width\",0>B?G(0)-G(B[0]):G(B[0])-G(0)).attr(\"x\",O(B)).on(\"mouseover\",function(){u.elementMouseover({value:B[0],label:F[0]||\"Current\",color:d3.select(this).style(\"fill\")})}).on(\"mousemove\",function(){u.elementMousemove({value:B[0],label:F[0]||\"Current\",color:d3.select(this).style(\"fill\")})}).on(\"mouseout\",function(){u.elementMouseout({value:B[0],label:F[0]||\"Current\",color:d3.select(this).style(\"fill\")})});var Q=x/6,R=z.map(function(a,b){return{value:a,label:D[b]}});J.selectAll(\"path.nv-markerTriangle\").data(R).enter().append(\"path\").attr(\"class\",\"nv-markerTriangle\").attr(\"d\",\"M0,\"+Q+\"L\"+Q+\",\"+-Q+\" \"+-Q+\",\"+-Q+\"Z\").on(\"mouseover\",function(a){u.elementMouseover({value:a.value,label:a.label||\"Previous\",color:d3.select(this).style(\"fill\"),pos:[G(a.value),x/2]})}).on(\"mousemove\",function(a){u.elementMousemove({value:a.value,label:a.label||\"Previous\",color:d3.select(this).style(\"fill\")})}).on(\"mouseout\",function(a,b){u.elementMouseout({value:a.value,label:a.label||\"Previous\",color:d3.select(this).style(\"fill\")})}),K.selectAll(\"path.nv-markerTriangle\").data(R).attr(\"transform\",function(a){return\"translate(\"+G(a.value)+\",\"+x/2+\")\"});var S=A.map(function(a,b){return{value:a,label:E[b]}});J.selectAll(\"path.nv-markerLine\").data(S).enter().append(\"line\").attr(\"cursor\",\"\").attr(\"class\",\"nv-markerLine\").attr(\"x1\",function(a){return G(a.value)}).attr(\"y1\",\"2\").attr(\"x2\",function(a){return G(a.value)}).attr(\"y2\",x-2).on(\"mouseover\",function(a){u.elementMouseover({value:a.value,label:a.label||\"Previous\",color:d3.select(this).style(\"fill\"),pos:[G(a.value),x/2]})}).on(\"mousemove\",function(a){u.elementMousemove({value:a.value,label:a.label||\"Previous\",color:d3.select(this).style(\"fill\")})}).on(\"mouseout\",function(a,b){u.elementMouseout({value:a.value,label:a.label||\"Previous\",color:d3.select(this).style(\"fill\")})}),K.selectAll(\"path.nv-markerLines\").data(S).attr(\"transform\",function(a){return\"translate(\"+G(a.value)+\",\"+x/2+\")\"}),H.selectAll(\".nv-range\").on(\"mouseover\",function(a,b){var c=C[b]||v[b];u.elementMouseover({value:a,label:c,color:d3.select(this).style(\"fill\")})}).on(\"mousemove\",function(){u.elementMousemove({value:B[0],label:F[0]||\"Previous\",color:d3.select(this).style(\"fill\")})}).on(\"mouseout\",function(a,b){var c=C[b]||v[b];u.elementMouseout({value:a,label:c,color:d3.select(this).style(\"fill\")})})}),c}var d={top:0,right:0,bottom:0,left:0},e=\"left\",f=!1,g=function(a){return a.ranges},h=function(a){return a.markers?a.markers:[]},i=function(a){return a.markerLines?a.markerLines:[0]},j=function(a){return a.measures},k=function(a){return a.rangeLabels?a.rangeLabels:[]},l=function(a){return a.markerLabels?a.markerLabels:[]},m=function(a){return a.markerLineLabels?a.markerLineLabels:[]},n=function(a){return a.measureLabels?a.measureLabels:[]},o=[0],p=380,q=30,r=null,s=null,t=a.utils.getColor([\"#1f77b4\"]),u=d3.dispatch(\"elementMouseover\",\"elementMouseout\",\"elementMousemove\"),v=[\"Maximum\",\"Mean\",\"Minimum\"],w=[\"Max\",\"Avg\",\"Min\"];return c.dispatch=u,c.options=a.utils.optionsFunc.bind(c),c._options=Object.create({},{ranges:{get:function(){return g},set:function(a){g=a}},markers:{get:function(){return h},set:function(a){h=a}},measures:{get:function(){return j},set:function(a){j=a}},forceX:{get:function(){return o},set:function(a){o=a}},width:{get:function(){return p},set:function(a){p=a}},height:{get:function(){return q},set:function(a){q=a}},tickFormat:{get:function(){return s},set:function(a){s=a}},margin:{get:function(){return d},set:function(a){d.top=void 0!==a.top?a.top:d.top,d.right=void 0!==a.right?a.right:d.right,d.bottom=void 0!==a.bottom?a.bottom:d.bottom,d.left=void 0!==a.left?a.left:d.left}},orient:{get:function(){return e},set:function(a){e=a,f=\"right\"==e||\"bottom\"==e}},color:{get:function(){return t},set:function(b){t=a.utils.getColor(b)}}}),a.utils.initOptions(c),c},a.models.bulletChart=function(){\"use strict\";function b(d){return d.each(function(e,o){var p=d3.select(this);a.utils.initSVG(p);var q=a.utils.availableWidth(k,p,g),r=l-g.top-g.bottom;if(b.update=function(){b(d)},b.container=this,!e||!h.call(this,e,o))return a.utils.noData(b,p),b;p.selectAll(\".nv-noData\").remove();var s=h.call(this,e,o).slice().sort(d3.descending),t=i.call(this,e,o).slice().sort(d3.descending),u=j.call(this,e,o).slice().sort(d3.descending),v=p.selectAll(\"g.nv-wrap.nv-bulletChart\").data([e]),w=v.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-bulletChart\"),x=w.append(\"g\"),y=v.select(\"g\");x.append(\"g\").attr(\"class\",\"nv-bulletWrap\"),x.append(\"g\").attr(\"class\",\"nv-titles\"),v.attr(\"transform\",\"translate(\"+g.left+\",\"+g.top+\")\");var z=d3.scale.linear().domain([0,Math.max(s[0],t[0]||0,u[0])]).range(f?[q,0]:[0,q]),A=this.__chart__||d3.scale.linear().domain([0,1/0]).range(z.range());this.__chart__=z;var B=x.select(\".nv-titles\").append(\"g\").attr(\"text-anchor\",\"end\").attr(\"transform\",\"translate(-6,\"+(l-g.top-g.bottom)/2+\")\");B.append(\"text\").attr(\"class\",\"nv-title\").text(function(a){return a.title}),B.append(\"text\").attr(\"class\",\"nv-subtitle\").attr(\"dy\",\"1em\").text(function(a){return a.subtitle}),c.width(q).height(r);var C=y.select(\".nv-bulletWrap\");d3.transition(C).call(c);var D=m||z.tickFormat(q/100),E=y.selectAll(\"g.nv-tick\").data(z.ticks(n?n:q/50),function(a){return this.textContent||D(a)}),F=E.enter().append(\"g\").attr(\"class\",\"nv-tick\").attr(\"transform\",function(a){return\"translate(\"+A(a)+\",0)\"}).style(\"opacity\",1e-6);F.append(\"line\").attr(\"y1\",r).attr(\"y2\",7*r/6),F.append(\"text\").attr(\"text-anchor\",\"middle\").attr(\"dy\",\"1em\").attr(\"y\",7*r/6).text(D);var G=d3.transition(E).attr(\"transform\",function(a){return\"translate(\"+z(a)+\",0)\"}).style(\"opacity\",1);G.select(\"line\").attr(\"y1\",r).attr(\"y2\",7*r/6),G.select(\"text\").attr(\"y\",7*r/6),d3.transition(E.exit()).attr(\"transform\",function(a){return\"translate(\"+z(a)+\",0)\"}).style(\"opacity\",1e-6).remove()}),d3.timer.flush(),b}var c=a.models.bullet(),d=a.models.tooltip(),e=\"left\",f=!1,g={top:5,right:40,bottom:20,left:120},h=function(a){return a.ranges},i=function(a){return a.markers?a.markers:[]},j=function(a){return a.measures},k=null,l=55,m=null,n=null,o=null,p=d3.dispatch();return d.duration(0).headerEnabled(!1),c.dispatch.on(\"elementMouseover.tooltip\",function(a){a.series={key:a.label,value:a.value,color:a.color},d.data(a).hidden(!1)}),c.dispatch.on(\"elementMouseout.tooltip\",function(a){d.hidden(!0)}),c.dispatch.on(\"elementMousemove.tooltip\",function(a){d()}),b.bullet=c,b.dispatch=p,b.tooltip=d,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{ranges:{get:function(){return h},set:function(a){h=a}},markers:{get:function(){return i},set:function(a){i=a}},measures:{get:function(){return j},set:function(a){j=a}},width:{get:function(){return k},set:function(a){k=a}},height:{get:function(){return l},set:function(a){l=a}},tickFormat:{get:function(){return m},set:function(a){m=a}},ticks:{get:function(){return n},set:function(a){n=a}},noData:{get:function(){return o},set:function(a){o=a}},margin:{get:function(){return g},set:function(a){g.top=void 0!==a.top?a.top:g.top,g.right=void 0!==a.right?a.right:g.right,g.bottom=void 0!==a.bottom?a.bottom:g.bottom,g.left=void 0!==a.left?a.left:g.left}},orient:{get:function(){return e},set:function(a){e=a,f=\"right\"==e||\"bottom\"==e}}}),a.utils.inheritOptions(b,c),a.utils.initOptions(b),b},a.models.candlestickBar=function(){\"use strict\";function b(x){return x.each(function(b){c=d3.select(this);var x=a.utils.availableWidth(i,c,h),y=a.utils.availableHeight(j,c,h);a.utils.initSVG(c);var A=x/b[0].values.length*.45;l.domain(d||d3.extent(b[0].values.map(n).concat(t))),v?l.range(f||[.5*x/b[0].values.length,x*(b[0].values.length-.5)/b[0].values.length]):l.range(f||[5+A/2,x-A/2-5]),m.domain(e||[d3.min(b[0].values.map(s).concat(u)),d3.max(b[0].values.map(r).concat(u))]).range(g||[y,0]),l.domain()[0]===l.domain()[1]&&(l.domain()[0]?l.domain([l.domain()[0]-.01*l.domain()[0],l.domain()[1]+.01*l.domain()[1]]):l.domain([-1,1])),m.domain()[0]===m.domain()[1]&&(m.domain()[0]?m.domain([m.domain()[0]+.01*m.domain()[0],m.domain()[1]-.01*m.domain()[1]]):m.domain([-1,1]));var B=d3.select(this).selectAll(\"g.nv-wrap.nv-candlestickBar\").data([b[0].values]),C=B.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-candlestickBar\"),D=C.append(\"defs\"),E=C.append(\"g\"),F=B.select(\"g\");E.append(\"g\").attr(\"class\",\"nv-ticks\"),B.attr(\"transform\",\"translate(\"+h.left+\",\"+h.top+\")\"),c.on(\"click\",function(a,b){z.chartClick({data:a,index:b,pos:d3.event,id:k})}),D.append(\"clipPath\").attr(\"id\",\"nv-chart-clip-path-\"+k).append(\"rect\"),B.select(\"#nv-chart-clip-path-\"+k+\" rect\").attr(\"width\",x).attr(\"height\",y),F.attr(\"clip-path\",w?\"url(#nv-chart-clip-path-\"+k+\")\":\"\");var G=B.select(\".nv-ticks\").selectAll(\".nv-tick\").data(function(a){return a});G.exit().remove();var H=G.enter().append(\"g\");G.attr(\"class\",function(a,b,c){return(p(a,b)>q(a,b)?\"nv-tick negative\":\"nv-tick positive\")+\" nv-tick-\"+c+\"-\"+b});H.append(\"line\").attr(\"class\",\"nv-candlestick-lines\").attr(\"transform\",function(a,b){return\"translate(\"+l(n(a,b))+\",0)\"}).attr(\"x1\",0).attr(\"y1\",function(a,b){return m(r(a,b))}).attr(\"x2\",0).attr(\"y2\",function(a,b){return m(s(a,b))}),H.append(\"rect\").attr(\"class\",\"nv-candlestick-rects nv-bars\").attr(\"transform\",function(a,b){return\"translate(\"+(l(n(a,b))-A/2)+\",\"+(m(o(a,b))-(p(a,b)>q(a,b)?m(q(a,b))-m(p(a,b)):0))+\")\"}).attr(\"x\",0).attr(\"y\",0).attr(\"width\",A).attr(\"height\",function(a,b){var c=p(a,b),d=q(a,b);return c>d?m(d)-m(c):m(c)-m(d)});G.select(\".nv-candlestick-lines\").transition().attr(\"transform\",function(a,b){return\"translate(\"+l(n(a,b))+\",0)\"}).attr(\"x1\",0).attr(\"y1\",function(a,b){return m(r(a,b))}).attr(\"x2\",0).attr(\"y2\",function(a,b){return m(s(a,b))}),G.select(\".nv-candlestick-rects\").transition().attr(\"transform\",function(a,b){return\"translate(\"+(l(n(a,b))-A/2)+\",\"+(m(o(a,b))-(p(a,b)>q(a,b)?m(q(a,b))-m(p(a,b)):0))+\")\"}).attr(\"x\",0).attr(\"y\",0).attr(\"width\",A).attr(\"height\",function(a,b){var c=p(a,b),d=q(a,b);return c>d?m(d)-m(c):m(c)-m(d)})}),b}var c,d,e,f,g,h={top:0,right:0,bottom:0,left:0},i=null,j=null,k=Math.floor(1e4*Math.random()),l=d3.scale.linear(),m=d3.scale.linear(),n=function(a){return a.x},o=function(a){return a.y},p=function(a){return a.open},q=function(a){return a.close},r=function(a){return a.high},s=function(a){return a.low},t=[],u=[],v=!1,w=!0,x=a.utils.defaultColor(),y=!1,z=d3.dispatch(\"stateChange\",\"changeState\",\"renderEnd\",\"chartClick\",\"elementClick\",\"elementDblClick\",\"elementMouseover\",\"elementMouseout\",\"elementMousemove\");return b.highlightPoint=function(a,d){b.clearHighlights(),c.select(\".nv-candlestickBar .nv-tick-0-\"+a).classed(\"hover\",d)},b.clearHighlights=function(){c.select(\".nv-candlestickBar .nv-tick.hover\").classed(\"hover\",!1)},b.dispatch=z,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return i},set:function(a){i=a}},height:{get:function(){return j},set:function(a){j=a}},xScale:{get:function(){return l},set:function(a){l=a}},yScale:{get:function(){return m},set:function(a){m=a}},xDomain:{get:function(){return d},set:function(a){d=a}},yDomain:{get:function(){return e},set:function(a){e=a}},xRange:{get:function(){return f},set:function(a){f=a}},yRange:{get:function(){return g},set:function(a){g=a}},forceX:{get:function(){return t},set:function(a){t=a}},forceY:{get:function(){return u},set:function(a){u=a}},padData:{get:function(){return v},set:function(a){v=a}},clipEdge:{get:function(){return w},set:function(a){w=a}},id:{get:function(){return k},set:function(a){k=a}},interactive:{get:function(){return y},set:function(a){y=a}},x:{get:function(){return n},set:function(a){n=a}},y:{get:function(){return o},set:function(a){o=a}},open:{get:function(){return p()},set:function(a){p=a}},close:{get:function(){return q()},set:function(a){q=a}},high:{get:function(){return r},set:function(a){r=a}},low:{get:function(){return s},set:function(a){s=a}},margin:{get:function(){return h},set:function(a){h.top=void 0!=a.top?a.top:h.top,h.right=void 0!=a.right?a.right:h.right,h.bottom=void 0!=a.bottom?a.bottom:h.bottom,h.left=void 0!=a.left?a.left:h.left}},color:{get:function(){return x},set:function(b){x=a.utils.getColor(b)}}}),a.utils.initOptions(b),b},a.models.cumulativeLineChart=function(){\"use strict\";function b(l){return H.reset(),H.models(f),r&&H.models(g),s&&H.models(h),l.each(function(l){function A(a,c){d3.select(b.container).style(\"cursor\",\"ew-resize\")}function E(a,b){G.x=d3.event.x,G.i=Math.round(F.invert(G.x)),K()}function H(a,c){d3.select(b.container).style(\"cursor\",\"auto\"),y.index=G.i,C.stateChange(y)}function K(){aa.data([G]);var a=b.duration();b.duration(0),b.update(),b.duration(a)}var L=d3.select(this);a.utils.initSVG(L),L.classed(\"nv-chart-\"+x,!0);var M=a.utils.availableWidth(o,L,m),N=a.utils.availableHeight(p,L,m);if(b.update=function(){0===D?L.call(b):L.transition().duration(D).call(b)},b.container=this,y.setter(J(l),b.update).getter(I(l)).update(),y.disabled=l.map(function(a){return!!a.disabled}),!z){var O;z={};for(O in y)y[O]instanceof Array?z[O]=y[O].slice(0):z[O]=y[O]}var P=d3.behavior.drag().on(\"dragstart\",A).on(\"drag\",E).on(\"dragend\",H);if(!(l&&l.length&&l.filter(function(a){return a.values.length}).length))return a.utils.noData(b,L),b;if(L.selectAll(\".nv-noData\").remove(),d=f.xScale(),e=f.yScale(),w)f.yDomain(null);else{var Q=l.filter(function(a){return!a.disabled}).map(function(a,b){var c=d3.extent(a.values,f.y());return c[0]<-.95&&(c[0]=-.95),[(c[0]-c[1])/(1+c[1]),(c[1]-c[0])/(1+c[0])]}),R=[d3.min(Q,function(a){return a[0]}),d3.max(Q,function(a){return a[1]})];f.yDomain(R)}F.domain([0,l[0].values.length-1]).range([0,M]).clamp(!0);var l=c(G.i,l),S=v?\"none\":\"all\",T=L.selectAll(\"g.nv-wrap.nv-cumulativeLine\").data([l]),U=T.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-cumulativeLine\").append(\"g\"),V=T.select(\"g\");if(U.append(\"g\").attr(\"class\",\"nv-interactive\"),U.append(\"g\").attr(\"class\",\"nv-x nv-axis\").style(\"pointer-events\",\"none\"),U.append(\"g\").attr(\"class\",\"nv-y nv-axis\"),U.append(\"g\").attr(\"class\",\"nv-background\"),U.append(\"g\").attr(\"class\",\"nv-linesWrap\").style(\"pointer-events\",S),U.append(\"g\").attr(\"class\",\"nv-avgLinesWrap\").style(\"pointer-events\",\"none\"),U.append(\"g\").attr(\"class\",\"nv-legendWrap\"),U.append(\"g\").attr(\"class\",\"nv-controlsWrap\"),q?(i.width(M),V.select(\".nv-legendWrap\").datum(l).call(i),i.height()>m.top&&(m.top=i.height(),N=a.utils.availableHeight(p,L,m)),V.select(\".nv-legendWrap\").attr(\"transform\",\"translate(0,\"+-m.top+\")\")):V.select(\".nv-legendWrap\").selectAll(\"*\").remove(),u){var W=[{key:\"Re-scale y-axis\",disabled:!w}];j.width(140).color([\"#444\",\"#444\",\"#444\"]).rightAlign(!1).margin({top:5,right:0,bottom:5,left:20}),V.select(\".nv-controlsWrap\").datum(W).attr(\"transform\",\"translate(0,\"+-m.top+\")\").call(j)}else V.select(\".nv-controlsWrap\").selectAll(\"*\").remove();T.attr(\"transform\",\"translate(\"+m.left+\",\"+m.top+\")\"),t&&V.select(\".nv-y.nv-axis\").attr(\"transform\",\"translate(\"+M+\",0)\");var X=l.filter(function(a){return a.tempDisabled});T.select(\".tempDisabled\").remove(),X.length&&T.append(\"text\").attr(\"class\",\"tempDisabled\").attr(\"x\",M/2).attr(\"y\",\"-.71em\").style(\"text-anchor\",\"end\").text(X.map(function(a){return a.key}).join(\", \")+\" values cannot be calculated for this time period.\"),v&&(k.width(M).height(N).margin({left:m.left,top:m.top}).svgContainer(L).xScale(d),T.select(\".nv-interactive\").call(k)),U.select(\".nv-background\").append(\"rect\"),V.select(\".nv-background rect\").attr(\"width\",M).attr(\"height\",N),f.y(function(a){return a.display.y}).width(M).height(N).color(l.map(function(a,b){return a.color||n(a,b)}).filter(function(a,b){return!l[b].disabled&&!l[b].tempDisabled}));var Y=V.select(\".nv-linesWrap\").datum(l.filter(function(a){return!a.disabled&&!a.tempDisabled}));Y.call(f),l.forEach(function(a,b){a.seriesIndex=b});var Z=l.filter(function(a){return!a.disabled&&!!B(a)}),$=V.select(\".nv-avgLinesWrap\").selectAll(\"line\").data(Z,function(a){return a.key}),_=function(a){var b=e(B(a));return 0>b?0:b>N?N:b};$.enter().append(\"line\").style(\"stroke-width\",2).style(\"stroke-dasharray\",\"10,10\").style(\"stroke\",function(a,b){return f.color()(a,a.seriesIndex)}).attr(\"x1\",0).attr(\"x2\",M).attr(\"y1\",_).attr(\"y2\",_),$.style(\"stroke-opacity\",function(a){var b=e(B(a));return 0>b||b>N?0:1}).attr(\"x1\",0).attr(\"x2\",M).attr(\"y1\",_).attr(\"y2\",_),$.exit().remove();var aa=Y.selectAll(\".nv-indexLine\").data([G]);aa.enter().append(\"rect\").attr(\"class\",\"nv-indexLine\").attr(\"width\",3).attr(\"x\",-2).attr(\"fill\",\"red\").attr(\"fill-opacity\",.5).style(\"pointer-events\",\"all\").call(P),aa.attr(\"transform\",function(a){return\"translate(\"+F(a.i)+\",0)\"}).attr(\"height\",N),r&&(g.scale(d)._ticks(a.utils.calcTicksX(M/70,l)).tickSize(-N,0),V.select(\".nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+e.range()[0]+\")\"),V.select(\".nv-x.nv-axis\").call(g)),s&&(h.scale(e)._ticks(a.utils.calcTicksY(N/36,l)).tickSize(-M,0),V.select(\".nv-y.nv-axis\").call(h)),V.select(\".nv-background rect\").on(\"click\",function(){G.x=d3.mouse(this)[0],G.i=Math.round(F.invert(G.x)),y.index=G.i,C.stateChange(y),K()}),f.dispatch.on(\"elementClick\",function(a){G.i=a.pointIndex,G.x=F(G.i),y.index=G.i,C.stateChange(y),K()}),j.dispatch.on(\"legendClick\",function(a,c){a.disabled=!a.disabled,w=!a.disabled,y.rescaleY=w,C.stateChange(y),b.update()}),i.dispatch.on(\"stateChange\",function(a){for(var c in a)y[c]=a[c];C.stateChange(y),b.update()}),k.dispatch.on(\"elementMousemove\",function(c){f.clearHighlights();var d,e,i,j=[];if(l.filter(function(a,b){return a.seriesIndex=b,!a.disabled}).forEach(function(g,h){e=a.interactiveBisect(g.values,c.pointXValue,b.x()),f.highlightPoint(h,e,!0);var k=g.values[e];\"undefined\"!=typeof k&&(\"undefined\"==typeof d&&(d=k),\"undefined\"==typeof i&&(i=b.xScale()(b.x()(k,e))),j.push({key:g.key,value:b.y()(k,e),color:n(g,g.seriesIndex)}))}),j.length>2){var m=b.yScale().invert(c.mouseY),o=Math.abs(b.yScale().domain()[0]-b.yScale().domain()[1]),p=.03*o,q=a.nearestValueIndex(j.map(function(a){return a.value}),m,p);null!==q&&(j[q].highlight=!0)}var r=g.tickFormat()(b.x()(d,e),e);k.tooltip.valueFormatter(function(a,b){return h.tickFormat()(a)}).data({value:r,series:j})(),k.renderGuideLine(i)}),k.dispatch.on(\"elementMouseout\",function(a){f.clearHighlights()}),C.on(\"changeState\",function(a){\"undefined\"!=typeof a.disabled&&(l.forEach(function(b,c){b.disabled=a.disabled[c]}),y.disabled=a.disabled),\"undefined\"!=typeof a.index&&(G.i=a.index,G.x=F(G.i),y.index=a.index,aa.data([G])),\"undefined\"!=typeof a.rescaleY&&(w=a.rescaleY),b.update()})}),H.renderEnd(\"cumulativeLineChart immediate\"),b}function c(a,b){return K||(K=f.y()),b.map(function(b,c){if(!b.values)return b;var d=b.values[a];if(null==d)return b;var e=K(d,a);return-.95>e&&!E?(b.tempDisabled=!0,b):(b.tempDisabled=!1,b.values=b.values.map(function(a,b){return a.display={y:(K(a,b)-e)/(1+e)},a}),b)})}var d,e,f=a.models.line(),g=a.models.axis(),h=a.models.axis(),i=a.models.legend(),j=a.models.legend(),k=a.interactiveGuideline(),l=a.models.tooltip(),m={top:30,right:30,bottom:50,left:60},n=a.utils.defaultColor(),o=null,p=null,q=!0,r=!0,s=!0,t=!1,u=!0,v=!1,w=!0,x=f.id(),y=a.utils.state(),z=null,A=null,B=function(a){return a.average},C=d3.dispatch(\"stateChange\",\"changeState\",\"renderEnd\"),D=250,E=!1;y.index=0,y.rescaleY=w,g.orient(\"bottom\").tickPadding(7),h.orient(t?\"right\":\"left\"),l.valueFormatter(function(a,b){return h.tickFormat()(a,b)}).headerFormatter(function(a,b){return g.tickFormat()(a,b)}),j.updateState(!1);var F=d3.scale.linear(),G={i:0,x:0},H=a.utils.renderWatch(C,D),I=function(a){return function(){return{active:a.map(function(a){return!a.disabled}),index:G.i,rescaleY:w}}},J=function(a){return function(b){void 0!==b.index&&(G.i=b.index),void 0!==b.rescaleY&&(w=b.rescaleY),void 0!==b.active&&a.forEach(function(a,c){a.disabled=!b.active[c]})}};f.dispatch.on(\"elementMouseover.tooltip\",function(a){var c={x:b.x()(a.point),y:b.y()(a.point),color:a.point.color};a.point=c,l.data(a).hidden(!1)}),f.dispatch.on(\"elementMouseout.tooltip\",function(a){l.hidden(!0)});var K=null;return b.dispatch=C,b.lines=f,b.legend=i,b.controls=j,b.xAxis=g,b.yAxis=h,b.interactiveLayer=k,b.state=y,b.tooltip=l,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return o},set:function(a){o=a}},height:{get:function(){return p},set:function(a){p=a}},rescaleY:{get:function(){return w},set:function(a){w=a}},showControls:{get:function(){return u},set:function(a){u=a}},showLegend:{get:function(){return q},set:function(a){q=a}},average:{get:function(){return B},set:function(a){B=a}},defaultState:{get:function(){return z},set:function(a){z=a}},noData:{get:function(){return A},set:function(a){A=a}},showXAxis:{get:function(){return r},set:function(a){r=a}},showYAxis:{get:function(){return s},set:function(a){s=a}},noErrorCheck:{get:function(){return E},set:function(a){E=a}},margin:{get:function(){return m},set:function(a){m.top=void 0!==a.top?a.top:m.top,m.right=void 0!==a.right?a.right:m.right,m.bottom=void 0!==a.bottom?a.bottom:m.bottom,m.left=void 0!==a.left?a.left:m.left}},color:{get:function(){return n},set:function(b){n=a.utils.getColor(b),i.color(n)}},useInteractiveGuideline:{get:function(){return v},set:function(a){v=a,a===!0&&(b.interactive(!1),b.useVoronoi(!1))}},rightAlignYAxis:{get:function(){return t},set:function(a){t=a,h.orient(a?\"right\":\"left\")}},duration:{get:function(){return D},set:function(a){D=a,f.duration(D),g.duration(D),h.duration(D),H.reset(D)}}}),a.utils.inheritOptions(b,f),a.utils.initOptions(b),b},a.models.discreteBar=function(){\"use strict\";function b(m){return y.reset(),m.each(function(b){var m=k-j.left-j.right,x=l-j.top-j.bottom;c=d3.select(this),a.utils.initSVG(c),b.forEach(function(a,b){a.values.forEach(function(a){a.series=b})});var z=d&&e?[]:b.map(function(a){return a.values.map(function(a,b){return{x:p(a,b),y:q(a,b),y0:a.y0}})});n.domain(d||d3.merge(z).map(function(a){return a.x})).rangeBands(f||[0,m],.1),o.domain(e||d3.extent(d3.merge(z).map(function(a){return a.y}).concat(r))),t?o.range(g||[x-(o.domain()[0]<0?12:0),o.domain()[1]>0?12:0]):o.range(g||[x,0]),h=h||n,i=i||o.copy().range([o(0),o(0)]);var A=c.selectAll(\"g.nv-wrap.nv-discretebar\").data([b]),B=A.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-discretebar\"),C=B.append(\"g\");A.select(\"g\");C.append(\"g\").attr(\"class\",\"nv-groups\"),A.attr(\"transform\",\"translate(\"+j.left+\",\"+j.top+\")\");var D=A.select(\".nv-groups\").selectAll(\".nv-group\").data(function(a){return a},function(a){return a.key});D.enter().append(\"g\").style(\"stroke-opacity\",1e-6).style(\"fill-opacity\",1e-6),D.exit().watchTransition(y,\"discreteBar: exit groups\").style(\"stroke-opacity\",1e-6).style(\"fill-opacity\",1e-6).remove(),D.attr(\"class\",function(a,b){return\"nv-group nv-series-\"+b}).classed(\"hover\",function(a){return a.hover}),D.watchTransition(y,\"discreteBar: groups\").style(\"stroke-opacity\",1).style(\"fill-opacity\",.75);var E=D.selectAll(\"g.nv-bar\").data(function(a){return a.values});E.exit().remove();var F=E.enter().append(\"g\").attr(\"transform\",function(a,b,c){return\"translate(\"+(n(p(a,b))+.05*n.rangeBand())+\", \"+o(0)+\")\"}).on(\"mouseover\",function(a,b){d3.select(this).classed(\"hover\",!0),v.elementMouseover({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"mouseout\",function(a,b){d3.select(this).classed(\"hover\",!1),v.elementMouseout({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"mousemove\",function(a,b){v.elementMousemove({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"click\",function(a,b){var c=this;v.elementClick({data:a,index:b,color:d3.select(this).style(\"fill\"),event:d3.event,element:c}),d3.event.stopPropagation()}).on(\"dblclick\",function(a,b){v.elementDblClick({data:a,index:b,color:d3.select(this).style(\"fill\")}),d3.event.stopPropagation()});F.append(\"rect\").attr(\"height\",0).attr(\"width\",.9*n.rangeBand()/b.length),t?(F.append(\"text\").attr(\"text-anchor\",\"middle\"),E.select(\"text\").text(function(a,b){return u(q(a,b))}).watchTransition(y,\"discreteBar: bars text\").attr(\"x\",.9*n.rangeBand()/2).attr(\"y\",function(a,b){return q(a,b)<0?o(q(a,b))-o(0)+12:-4})):E.selectAll(\"text\").remove(),E.attr(\"class\",function(a,b){return q(a,b)<0?\"nv-bar negative\":\"nv-bar positive\"}).style(\"fill\",function(a,b){return a.color||s(a,b)}).style(\"stroke\",function(a,b){return a.color||s(a,b)}).select(\"rect\").attr(\"class\",w).watchTransition(y,\"discreteBar: bars rect\").attr(\"width\",.9*n.rangeBand()/b.length),E.watchTransition(y,\"discreteBar: bars\").attr(\"transform\",function(a,b){var c=n(p(a,b))+.05*n.rangeBand(),d=q(a,b)<0?o(0):o(0)-o(q(a,b))<1?o(0)-1:o(q(a,b));return\"translate(\"+c+\", \"+d+\")\"}).select(\"rect\").attr(\"height\",function(a,b){return Math.max(Math.abs(o(q(a,b))-o(0)),1)}),h=n.copy(),i=o.copy()}),y.renderEnd(\"discreteBar immediate\"),b}var c,d,e,f,g,h,i,j={top:0,right:0,bottom:0,left:0},k=960,l=500,m=Math.floor(1e4*Math.random()),n=d3.scale.ordinal(),o=d3.scale.linear(),p=function(a){return a.x},q=function(a){return a.y},r=[0],s=a.utils.defaultColor(),t=!1,u=d3.format(\",.2f\"),v=d3.dispatch(\"chartClick\",\"elementClick\",\"elementDblClick\",\"elementMouseover\",\"elementMouseout\",\"elementMousemove\",\"renderEnd\"),w=\"discreteBar\",x=250,y=a.utils.renderWatch(v,x);return b.dispatch=v,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return k},set:function(a){k=a}},height:{get:function(){return l},set:function(a){l=a}},forceY:{get:function(){return r},set:function(a){r=a}},showValues:{get:function(){return t},set:function(a){t=a}},x:{get:function(){return p},set:function(a){p=a}},y:{get:function(){return q},set:function(a){q=a}},xScale:{get:function(){return n},set:function(a){n=a}},yScale:{get:function(){return o},set:function(a){o=a}},xDomain:{get:function(){return d},set:function(a){d=a}},yDomain:{get:function(){return e},set:function(a){e=a}},xRange:{get:function(){return f},set:function(a){f=a}},yRange:{get:function(){return g},set:function(a){g=a}},valueFormat:{get:function(){return u},set:function(a){u=a}},id:{get:function(){return m},set:function(a){m=a}},rectClass:{get:function(){return w},set:function(a){w=a}},margin:{get:function(){return j},set:function(a){j.top=void 0!==a.top?a.top:j.top,j.right=void 0!==a.right?a.right:j.right,j.bottom=void 0!==a.bottom?a.bottom:j.bottom,j.left=void 0!==a.left?a.left:j.left}},color:{get:function(){return s},set:function(b){s=a.utils.getColor(b)}},duration:{get:function(){return x},set:function(a){x=a,y.reset(x)}}}),a.utils.initOptions(b),b},a.models.discreteBarChart=function(){\"use strict\";function b(i){return x.reset(),x.models(e),o&&x.models(f),p&&x.models(g),i.each(function(i){var m=d3.select(this);a.utils.initSVG(m);var u=a.utils.availableWidth(k,m,j),x=a.utils.availableHeight(l,m,j);if(b.update=function(){v.beforeUpdate(),m.transition().duration(w).call(b)},b.container=this,!(i&&i.length&&i.filter(function(a){return a.values.length}).length))return a.utils.noData(b,m),b;m.selectAll(\".nv-noData\").remove(),c=e.xScale(),d=e.yScale().clamp(!0);var y=m.selectAll(\"g.nv-wrap.nv-discreteBarWithAxes\").data([i]),z=y.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-discreteBarWithAxes\").append(\"g\"),A=z.append(\"defs\"),B=y.select(\"g\");z.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),z.append(\"g\").attr(\"class\",\"nv-y nv-axis\").append(\"g\").attr(\"class\",\"nv-zeroLine\").append(\"line\"),z.append(\"g\").attr(\"class\",\"nv-barsWrap\"),z.append(\"g\").attr(\"class\",\"nv-legendWrap\"),B.attr(\"transform\",\"translate(\"+j.left+\",\"+j.top+\")\"),n?(h.width(u),B.select(\".nv-legendWrap\").datum(i).call(h),h.height()>j.top&&(j.top=h.height(),x=a.utils.availableHeight(l,m,j)),y.select(\".nv-legendWrap\").attr(\"transform\",\"translate(0,\"+-j.top+\")\")):B.select(\".nv-legendWrap\").selectAll(\"*\").remove(),q&&B.select(\".nv-y.nv-axis\").attr(\"transform\",\"translate(\"+u+\",0)\"),e.width(u).height(x);var C=B.select(\".nv-barsWrap\").datum(i.filter(function(a){return!a.disabled}));if(C.transition().call(e),A.append(\"clipPath\").attr(\"id\",\"nv-x-label-clip-\"+e.id()).append(\"rect\"),B.select(\"#nv-x-label-clip-\"+e.id()+\" rect\").attr(\"width\",c.rangeBand()*(r?2:1)).attr(\"height\",16).attr(\"x\",-c.rangeBand()/(r?1:2)),o){f.scale(c)._ticks(a.utils.calcTicksX(u/100,i)).tickSize(-x,0),B.select(\".nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+(d.range()[0]+(e.showValues()&&d.domain()[0]<0?16:0))+\")\"),B.select(\".nv-x.nv-axis\").call(f);var D=B.select(\".nv-x.nv-axis\").selectAll(\"g\");r&&D.selectAll(\"text\").attr(\"transform\",function(a,b,c){return\"translate(0,\"+(c%2==0?\"5\":\"17\")+\")\"}),t&&D.selectAll(\".tick text\").attr(\"transform\",\"rotate(\"+t+\" 0,0)\").style(\"text-anchor\",t>0?\"start\":\"end\"),s&&B.selectAll(\".tick text\").call(a.utils.wrapTicks,b.xAxis.rangeBand())}p&&(g.scale(d)._ticks(a.utils.calcTicksY(x/36,i)).tickSize(-u,0),B.select(\".nv-y.nv-axis\").call(g)),B.select(\".nv-zeroLine line\").attr(\"x1\",0).attr(\"x2\",q?-u:u).attr(\"y1\",d(0)).attr(\"y2\",d(0))}),x.renderEnd(\"discreteBar chart immediate\"),b}var c,d,e=a.models.discreteBar(),f=a.models.axis(),g=a.models.axis(),h=a.models.legend(),i=a.models.tooltip(),j={top:15,right:10,bottom:50,left:60},k=null,l=null,m=a.utils.getColor(),n=!1,o=!0,p=!0,q=!1,r=!1,s=!1,t=0,u=null,v=d3.dispatch(\"beforeUpdate\",\"renderEnd\"),w=250;f.orient(\"bottom\").showMaxMin(!1).tickFormat(function(a){return a}),g.orient(q?\"right\":\"left\").tickFormat(d3.format(\",.1f\")),i.duration(0).headerEnabled(!1).valueFormatter(function(a,b){return g.tickFormat()(a,b)}).keyFormatter(function(a,b){return f.tickFormat()(a,b)});var x=a.utils.renderWatch(v,w);return e.dispatch.on(\"elementMouseover.tooltip\",function(a){a.series={key:b.x()(a.data),value:b.y()(a.data),color:a.color},i.data(a).hidden(!1)}),e.dispatch.on(\"elementMouseout.tooltip\",function(a){i.hidden(!0)}),e.dispatch.on(\"elementMousemove.tooltip\",function(a){i()}),b.dispatch=v,b.discretebar=e,b.legend=h,b.xAxis=f,b.yAxis=g,b.tooltip=i,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return k},set:function(a){k=a}},height:{get:function(){return l},set:function(a){l=a}},showLegend:{get:function(){return n},set:function(a){n=a}},staggerLabels:{get:function(){return r},set:function(a){r=a}},rotateLabels:{get:function(){return t},set:function(a){t=a}},wrapLabels:{get:function(){return s},set:function(a){s=!!a}},showXAxis:{get:function(){return o},set:function(a){o=a}},showYAxis:{get:function(){return p},set:function(a){p=a}},noData:{get:function(){return u},set:function(a){u=a}},margin:{get:function(){return j},set:function(a){j.top=void 0!==a.top?a.top:j.top,j.right=void 0!==a.right?a.right:j.right,j.bottom=void 0!==a.bottom?a.bottom:j.bottom,j.left=void 0!==a.left?a.left:j.left}},duration:{get:function(){return w},set:function(a){w=a,x.reset(w),e.duration(w),f.duration(w),g.duration(w)}},color:{get:function(){return m},set:function(b){m=a.utils.getColor(b),e.color(m),h.color(m)}},rightAlignYAxis:{get:function(){return q},set:function(a){q=a,g.orient(a?\"right\":\"left\")}}}),a.utils.inheritOptions(b,e),a.utils.initOptions(b),b},a.models.distribution=function(){\"use strict\";function b(k){return m.reset(),k.each(function(b){var k=(e-(\"x\"===g?d.left+d.right:d.top+d.bottom),\"x\"==g?\"y\":\"x\"),l=d3.select(this);a.utils.initSVG(l),c=c||j;var n=l.selectAll(\"g.nv-distribution\").data([b]),o=n.enter().append(\"g\").attr(\"class\",\"nvd3 nv-distribution\"),p=(o.append(\"g\"),n.select(\"g\"));n.attr(\"transform\",\"translate(\"+d.left+\",\"+d.top+\")\");var q=p.selectAll(\"g.nv-dist\").data(function(a){return a},function(a){return a.key});q.enter().append(\"g\"),q.attr(\"class\",function(a,b){return\"nv-dist nv-series-\"+b}).style(\"stroke\",function(a,b){return i(a,b)});var r=q.selectAll(\"line.nv-dist\"+g).data(function(a){return a.values});r.enter().append(\"line\").attr(g+\"1\",function(a,b){return c(h(a,b))}).attr(g+\"2\",function(a,b){return c(h(a,b))}),m.transition(q.exit().selectAll(\"line.nv-dist\"+g),\"dist exit\").attr(g+\"1\",function(a,b){return j(h(a,b))}).attr(g+\"2\",function(a,b){return j(h(a,b))}).style(\"stroke-opacity\",0).remove(),r.attr(\"class\",function(a,b){return\"nv-dist\"+g+\" nv-dist\"+g+\"-\"+b}).attr(k+\"1\",0).attr(k+\"2\",f),m.transition(r,\"dist\").attr(g+\"1\",function(a,b){return j(h(a,b))}).attr(g+\"2\",function(a,b){return j(h(a,b))}),c=j.copy()}),m.renderEnd(\"distribution immediate\"),b}var c,d={top:0,right:0,bottom:0,left:0},e=400,f=8,g=\"x\",h=function(a){return a[g]},i=a.utils.defaultColor(),j=d3.scale.linear(),k=250,l=d3.dispatch(\"renderEnd\"),m=a.utils.renderWatch(l,k);return b.options=a.utils.optionsFunc.bind(b),b.dispatch=l,b.margin=function(a){return arguments.length?(d.top=\"undefined\"!=typeof a.top?a.top:d.top,d.right=\"undefined\"!=typeof a.right?a.right:d.right,d.bottom=\"undefined\"!=typeof a.bottom?a.bottom:d.bottom,d.left=\"undefined\"!=typeof a.left?a.left:d.left,b):d},b.width=function(a){return arguments.length?(e=a,b):e},b.axis=function(a){return arguments.length?(g=a,b):g},b.size=function(a){return arguments.length?(f=a,b):f},b.getData=function(a){return arguments.length?(h=d3.functor(a),b):h},b.scale=function(a){return arguments.length?(j=a,b):j},b.color=function(c){return arguments.length?(i=a.utils.getColor(c),b):i},b.duration=function(a){return arguments.length?(k=a,m.reset(k),b):k},b},a.models.focus=function(b){\"use strict\";function c(t){return s.reset(),s.models(b),m&&s.models(f),n&&s.models(g),t.each(function(s){function t(a){var b=+(\"e\"==a),c=b?1:-1,d=y/3;return\"M\"+.5*c+\",\"+d+\"A6,6 0 0 \"+b+\" \"+6.5*c+\",\"+(d+6)+\"V\"+(2*d-6)+\"A6,6 0 0 \"+b+\" \"+.5*c+\",\"+2*d+\"ZM\"+2.5*c+\",\"+(d+8)+\"V\"+(2*d-8)+\"M\"+4.5*c+\",\"+(d+8)+\"V\"+(2*d-8)}function u(){h.empty()||h.extent(p),D.data([h.empty()?d.domain():p]).each(function(a,b){var c=d(a[0])-d.range()[0],e=x-d(a[1]);d3.select(this).select(\".left\").attr(\"width\",0>c?0:c),d3.select(this).select(\".right\").attr(\"x\",d(a[1])).attr(\"width\",0>e?0:e)})}function v(){p=h.empty()?null:h.extent();var a=h.empty()?d.domain():h.extent();Math.abs(a[0]-a[1])<=1||(r.brush({extent:a,brush:h}),u(),r.onBrush(a))}var w=d3.select(this);a.utils.initSVG(w);var x=a.utils.availableWidth(k,w,i),y=l-i.top-i.bottom;c.update=function(){0===q?w.call(c):w.transition().duration(q).call(c)},c.container=this,d=b.xScale(),e=b.yScale();var z=w.selectAll(\"g.nv-focus\").data([s]),A=z.enter().append(\"g\").attr(\"class\",\"nvd3 nv-focus\").append(\"g\"),B=z.select(\"g\");z.attr(\"transform\",\"translate(\"+i.left+\",\"+i.top+\")\"),A.append(\"g\").attr(\"class\",\"nv-background\").append(\"rect\"),A.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),A.append(\"g\").attr(\"class\",\"nv-y nv-axis\"),A.append(\"g\").attr(\"class\",\"nv-contentWrap\"),A.append(\"g\").attr(\"class\",\"nv-brushBackground\"),A.append(\"g\").attr(\"class\",\"nv-x nv-brush\"),o&&B.select(\".nv-y.nv-axis\").attr(\"transform\",\"translate(\"+x+\",0)\"),B.select(\".nv-background rect\").attr(\"width\",x).attr(\"height\",y),b.width(x).height(y).color(s.map(function(a,b){return a.color||j(a,b)}).filter(function(a,b){return!s[b].disabled}));var C=B.select(\".nv-contentWrap\").datum(s.filter(function(a){return!a.disabled}));d3.transition(C).call(b),h.x(d).on(\"brush\",function(){v()}),p&&h.extent(p);var D=B.select(\".nv-brushBackground\").selectAll(\"g\").data([p||h.extent()]),E=D.enter().append(\"g\");E.append(\"rect\").attr(\"class\",\"left\").attr(\"x\",0).attr(\"y\",0).attr(\"height\",y),E.append(\"rect\").attr(\"class\",\"right\").attr(\"x\",0).attr(\"y\",0).attr(\"height\",y);var F=B.select(\".nv-x.nv-brush\").call(h);F.selectAll(\"rect\").attr(\"height\",y),F.selectAll(\".resize\").append(\"path\").attr(\"d\",t),v(),B.select(\".nv-background rect\").attr(\"width\",x).attr(\"height\",y),m&&(f.scale(d)._ticks(a.utils.calcTicksX(x/100,s)).tickSize(-y,0),B.select(\".nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+e.range()[0]+\")\"),d3.transition(B.select(\".nv-x.nv-axis\")).call(f)),n&&(g.scale(e)._ticks(a.utils.calcTicksY(y/36,s)).tickSize(-x,0),d3.transition(B.select(\".nv-y.nv-axis\")).call(g)),B.select(\".nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+e.range()[0]+\")\")}),s.renderEnd(\"focus immediate\"),c}var d,e,b=b||a.models.line(),f=a.models.axis(),g=a.models.axis(),h=d3.svg.brush(),i={top:10,right:0,bottom:30,left:0},j=a.utils.defaultColor(),k=null,l=70,m=!0,n=!1,o=!1,p=null,q=250,r=d3.dispatch(\"brush\",\"onBrush\",\"renderEnd\");b.interactive(!1),b.pointActive(function(a){return!1});var s=a.utils.renderWatch(r,q);return c.dispatch=r,c.content=b,c.brush=h,c.xAxis=f,c.yAxis=g,c.options=a.utils.optionsFunc.bind(c),c._options=Object.create({},{width:{get:function(){return k},set:function(a){k=a}},height:{get:function(){return l},set:function(a){l=a}},showXAxis:{get:function(){return m},set:function(a){m=a}},showYAxis:{get:function(){return n},set:function(a){n=a}},brushExtent:{get:function(){return p},set:function(a){p=a}},margin:{get:function(){return i},set:function(a){i.top=void 0!==a.top?a.top:i.top,i.right=void 0!==a.right?a.right:i.right,i.bottom=void 0!==a.bottom?a.bottom:i.bottom,i.left=void 0!==a.left?a.left:i.left}},duration:{get:function(){return q},set:function(a){q=a,s.reset(q),b.duration(q),f.duration(q),g.duration(q)}},color:{get:function(){return j},set:function(c){j=a.utils.getColor(c),b.color(j)}},interpolate:{get:function(){return b.interpolate()},set:function(a){b.interpolate(a)}},xTickFormat:{get:function(){return f.tickFormat()},set:function(a){f.tickFormat(a)}},yTickFormat:{get:function(){return g.tickFormat()},set:function(a){g.tickFormat(a)}},x:{get:function(){return b.x()},set:function(a){b.x(a)}},y:{get:function(){return b.y()},set:function(a){b.y(a)}},rightAlignYAxis:{get:function(){return o},set:function(a){o=a,g.orient(o?\"right\":\"left\")}}}),a.utils.inheritOptions(c,b),a.utils.initOptions(c),c},a.models.forceDirectedGraph=function(){\"use strict\";function b(g){return u.reset(),g.each(function(g){f=d3.select(this),a.utils.initSVG(f);var j=a.utils.availableWidth(d,f,c),u=a.utils.availableHeight(e,f,c);if(f.attr(\"width\",j).attr(\"height\",u),!(g&&g.links&&g.nodes))return a.utils.noData(b,f),b;f.selectAll(\".nv-noData\").remove(),f.selectAll(\"*\").remove();var v=new Set;g.nodes.forEach(function(a){var b=Object.keys(a);b.forEach(function(a){v.add(a)})});var w=d3.layout.force().nodes(g.nodes).links(g.links).size([j,u]).linkStrength(k).friction(l).linkDistance(m).charge(n).gravity(o).theta(p).alpha(q).start(),x=f.selectAll(\".link\").data(g.links).enter().append(\"line\").attr(\"class\",\"nv-force-link\").style(\"stroke-width\",function(a){return Math.sqrt(a.value)}),y=f.selectAll(\".node\").data(g.nodes).enter().append(\"g\").attr(\"class\",\"nv-force-node\").call(w.drag);y.append(\"circle\").attr(\"r\",r).style(\"fill\",function(a){return h(a)}).on(\"mouseover\",function(a){f.select(\".nv-series-\"+a.seriesIndex+\" .nv-distx-\"+a.pointIndex).attr(\"y1\",a.py),f.select(\".nv-series-\"+a.seriesIndex+\" .nv-disty-\"+a.pointIndex).attr(\"x2\",a.px);var b=h(a);a.series=[],v.forEach(function(c){a.series.push({color:b,key:c,value:a[c]})}),i.data(a).hidden(!1)}).on(\"mouseout\",function(a){i.hidden(!0)}),i.headerFormatter(function(a){return\"Node\"}),t(x),s(y),w.on(\"tick\",function(){x.attr(\"x1\",function(a){return a.source.x}).attr(\"y1\",function(a){return a.source.y}).attr(\"x2\",function(a){return a.target.x}).attr(\"y2\",function(a){return a.target.y}),y.attr(\"transform\",function(a){return\"translate(\"+a.x+\", \"+a.y+\")\"})})}),b}var c={top:2,right:0,bottom:2,left:0},d=400,e=32,f=null,g=d3.dispatch(\"renderEnd\"),h=a.utils.getColor([\"#000\"]),i=a.models.tooltip(),j=null,k=.1,l=.9,m=30,n=-120,o=.1,p=.8,q=.1,r=5,s=function(a){},t=function(a){},u=a.utils.renderWatch(g);return b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return d},set:function(a){d=a}},height:{get:function(){return e},set:function(a){e=a}},linkStrength:{get:function(){return k},set:function(a){k=a}},friction:{get:function(){return l},set:function(a){l=a}},linkDist:{get:function(){return m},set:function(a){m=a}},charge:{get:function(){return n},set:function(a){n=a}},gravity:{get:function(){return o},set:function(a){o=a}},theta:{get:function(){return p},set:function(a){p=a}},alpha:{get:function(){return q},set:function(a){q=a}},radius:{get:function(){return r},set:function(a){r=a}},x:{get:function(){return getX},set:function(a){getX=d3.functor(a)}},y:{get:function(){return getY},set:function(a){getY=d3.functor(a)}},margin:{get:function(){return c},set:function(a){c.top=void 0!==a.top?a.top:c.top,c.right=void 0!==a.right?a.right:c.right,c.bottom=void 0!==a.bottom?a.bottom:c.bottom,c.left=void 0!==a.left?a.left:c.left}},color:{get:function(){return h},set:function(b){h=a.utils.getColor(b)}},noData:{get:function(){return j},set:function(a){j=a}},nodeExtras:{get:function(){return s},set:function(a){s=a}},linkExtras:{get:function(){return t},set:function(a){t=a}}}),b.dispatch=g,b.tooltip=i,a.utils.initOptions(b),b},a.models.furiousLegend=function(){\"use strict\";function b(r){function s(a,b){return\"furious\"!=q?\"#000\":o?a.disengaged?h(a,b):\"#fff\":o?void 0:a.disabled?h(a,b):\"#fff\"}function t(a,b){return o&&\"furious\"==q?a.disengaged?\"#fff\":h(a,b):a.disabled?\"#fff\":h(a,b)}return r.each(function(b){var r=d-c.left-c.right,u=d3.select(this);a.utils.initSVG(u);var v=u.selectAll(\"g.nv-legend\").data([b]),w=(v.enter().append(\"g\").attr(\"class\",\"nvd3 nv-legend\").append(\"g\"),v.select(\"g\"));v.attr(\"transform\",\"translate(\"+c.left+\",\"+c.top+\")\");var x,y=w.selectAll(\".nv-series\").data(function(a){return\"furious\"!=q?a:a.filter(function(a){return o?!0:!a.disengaged})}),z=y.enter().append(\"g\").attr(\"class\",\"nv-series\");if(\"classic\"==q)z.append(\"circle\").style(\"stroke-width\",2).attr(\"class\",\"nv-legend-symbol\").attr(\"r\",5),x=y.select(\"circle\");else if(\"furious\"==q){z.append(\"rect\").style(\"stroke-width\",2).attr(\"class\",\"nv-legend-symbol\").attr(\"rx\",3).attr(\"ry\",3),x=y.select(\"rect\"),z.append(\"g\").attr(\"class\",\"nv-check-box\").property(\"innerHTML\",'<path d=\"M0.5,5 L22.5,5 L22.5,26.5 L0.5,26.5 L0.5,5 Z\" class=\"nv-box\"></path><path d=\"M5.5,12.8618467 L11.9185089,19.2803556 L31,0.198864511\" class=\"nv-check\"></path>').attr(\"transform\",\"translate(-10,-8)scale(0.5)\");var A=y.select(\".nv-check-box\");A.each(function(a,b){d3.select(this).selectAll(\"path\").attr(\"stroke\",s(a,b))})}z.append(\"text\").attr(\"text-anchor\",\"start\").attr(\"class\",\"nv-legend-text\").attr(\"dy\",\".32em\").attr(\"dx\",\"8\");var B=y.select(\"text.nv-legend-text\");y.on(\"mouseover\",function(a,b){p.legendMouseover(a,b)}).on(\"mouseout\",function(a,b){p.legendMouseout(a,b)}).on(\"click\",function(a,b){p.legendClick(a,b);var c=y.data();if(m){if(\"classic\"==q)n?(c.forEach(function(a){a.disabled=!0}),a.disabled=!1):(a.disabled=!a.disabled,c.every(function(a){return a.disabled})&&c.forEach(function(a){a.disabled=!1}));else if(\"furious\"==q)if(o)a.disengaged=!a.disengaged,a.userDisabled=void 0==a.userDisabled?!!a.disabled:a.userDisabled,a.disabled=a.disengaged||a.userDisabled;else if(!o){a.disabled=!a.disabled,a.userDisabled=a.disabled;var d=c.filter(function(a){return!a.disengaged});d.every(function(a){return a.userDisabled})&&c.forEach(function(a){a.disabled=a.userDisabled=!1})}p.stateChange({disabled:c.map(function(a){return!!a.disabled}),disengaged:c.map(function(a){return!!a.disengaged})})}}).on(\"dblclick\",function(a,b){if((\"furious\"!=q||!o)&&(p.legendDblclick(a,b),m)){var c=y.data();c.forEach(function(a){a.disabled=!0,\"furious\"==q&&(a.userDisabled=a.disabled)}),a.disabled=!1,\"furious\"==q&&(a.userDisabled=a.disabled),p.stateChange({disabled:c.map(function(a){return!!a.disabled})})}}),y.classed(\"nv-disabled\",function(a){return a.userDisabled}),y.exit().remove(),B.attr(\"fill\",s).text(function(a){return g(f(a))});var C;switch(q){case\"furious\":C=23;break;case\"classic\":C=20}if(j){var D=[];y.each(function(b,c){var d;if(g(f(b))&&g(f(b)).length>i){var e=g(f(b)).substring(0,i);d=d3.select(this).select(\"text\").text(e+\"...\"),d3.select(this).append(\"svg:title\").text(g(f(b)))}else d=d3.select(this).select(\"text\");var h;try{if(h=d.node().getComputedTextLength(),0>=h)throw Error()}catch(j){h=a.utils.calcApproxTextWidth(d)}D.push(h+k)});for(var E=0,F=0,G=[];r>F&&E<D.length;)G[E]=D[E],F+=D[E++];for(0===E&&(E=1);F>r&&E>1;){G=[],E--;for(var H=0;H<D.length;H++)D[H]>(G[H%E]||0)&&(G[H%E]=D[H]);F=G.reduce(function(a,b,c,d){return a+b})}for(var I=[],J=0,K=0;E>J;J++)I[J]=K,K+=G[J];y.attr(\"transform\",function(a,b){return\"translate(\"+I[b%E]+\",\"+(5+Math.floor(b/E)*C)+\")\"}),l?w.attr(\"transform\",\"translate(\"+(d-c.right-F)+\",\"+c.top+\")\"):w.attr(\"transform\",\"translate(0,\"+c.top+\")\"),e=c.top+c.bottom+Math.ceil(D.length/E)*C}else{var L,M=5,N=5,O=0;y.attr(\"transform\",function(a,b){var e=d3.select(this).select(\"text\").node().getComputedTextLength()+k;return L=N,d<c.left+c.right+L+e&&(N=L=5,M+=C),N+=e,N>O&&(O=N),\"translate(\"+L+\",\"+M+\")\"}),w.attr(\"transform\",\"translate(\"+(d-c.right-O)+\",\"+c.top+\")\"),e=c.top+c.bottom+M+15}\"furious\"==q&&x.attr(\"width\",function(a,b){return B[0][b].getComputedTextLength()+27}).attr(\"height\",18).attr(\"y\",-9).attr(\"x\",-15),x.style(\"fill\",t).style(\"stroke\",function(a,b){return a.color||h(a,b)})}),b}var c={top:5,right:0,bottom:5,left:0},d=400,e=20,f=function(a){return a.key},g=function(a){return a},h=a.utils.getColor(),i=20,j=!0,k=28,l=!0,m=!0,n=!1,o=!1,p=d3.dispatch(\"legendClick\",\"legendDblclick\",\"legendMouseover\",\"legendMouseout\",\"stateChange\"),q=\"classic\";return b.dispatch=p,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return d},set:function(a){d=a}},height:{get:function(){return e},set:function(a){e=a}},key:{get:function(){return f},set:function(a){f=a}},keyFormatter:{get:function(){return g},set:function(a){g=a}},align:{get:function(){return j},set:function(a){j=a}},rightAlign:{get:function(){return l},set:function(a){l=a}},maxKeyLength:{get:function(){return i},set:function(a){i=a}},padding:{get:function(){return k},set:function(a){k=a}},updateState:{get:function(){return m},set:function(a){m=a}},radioButtonMode:{get:function(){return n},set:function(a){n=a}},expanded:{get:function(){return o},set:function(a){o=a}},vers:{get:function(){return q},set:function(a){q=a}},margin:{get:function(){return c},set:function(a){c.top=void 0!==a.top?a.top:c.top,c.right=void 0!==a.right?a.right:c.right,c.bottom=void 0!==a.bottom?a.bottom:c.bottom,c.left=void 0!==a.left?a.left:c.left}},color:{get:function(){return h},set:function(b){h=a.utils.getColor(b)}}}),a.utils.initOptions(b),b},a.models.historicalBar=function(){\"use strict\";function b(x){return x.each(function(b){w.reset(),k=d3.select(this);var x=a.utils.availableWidth(h,k,g),y=a.utils.availableHeight(i,k,g);a.utils.initSVG(k),l.domain(c||d3.extent(b[0].values.map(n).concat(p))),r?l.range(e||[.5*x/b[0].values.length,x*(b[0].values.length-.5)/b[0].values.length]):l.range(e||[0,x]),m.domain(d||d3.extent(b[0].values.map(o).concat(q))).range(f||[y,0]),l.domain()[0]===l.domain()[1]&&(l.domain()[0]?l.domain([l.domain()[0]-.01*l.domain()[0],l.domain()[1]+.01*l.domain()[1]]):l.domain([-1,1])),m.domain()[0]===m.domain()[1]&&(m.domain()[0]?m.domain([m.domain()[0]+.01*m.domain()[0],m.domain()[1]-.01*m.domain()[1]]):m.domain([-1,1]));var z=k.selectAll(\"g.nv-wrap.nv-historicalBar-\"+j).data([b[0].values]),A=z.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-historicalBar-\"+j),B=A.append(\"defs\"),C=A.append(\"g\"),D=z.select(\"g\");C.append(\"g\").attr(\"class\",\"nv-bars\"),z.attr(\"transform\",\"translate(\"+g.left+\",\"+g.top+\")\"),k.on(\"click\",function(a,b){u.chartClick({data:a,index:b,pos:d3.event,id:j})}),B.append(\"clipPath\").attr(\"id\",\"nv-chart-clip-path-\"+j).append(\"rect\"),z.select(\"#nv-chart-clip-path-\"+j+\" rect\").attr(\"width\",x).attr(\"height\",y),D.attr(\"clip-path\",s?\"url(#nv-chart-clip-path-\"+j+\")\":\"\");var E=z.select(\".nv-bars\").selectAll(\".nv-bar\").data(function(a){return a},function(a,b){return n(a,b)});E.exit().remove(),E.enter().append(\"rect\").attr(\"x\",0).attr(\"y\",function(b,c){return a.utils.NaNtoZero(m(Math.max(0,o(b,c))))}).attr(\"height\",function(b,c){return a.utils.NaNtoZero(Math.abs(m(o(b,c))-m(0)))}).attr(\"transform\",function(a,c){return\"translate(\"+(l(n(a,c))-x/b[0].values.length*.45)+\",0)\"}).on(\"mouseover\",function(a,b){v&&(d3.select(this).classed(\"hover\",!0),u.elementMouseover({data:a,index:b,color:d3.select(this).style(\"fill\")}))}).on(\"mouseout\",function(a,b){v&&(d3.select(this).classed(\"hover\",!1),u.elementMouseout({data:a,index:b,color:d3.select(this).style(\"fill\")}))}).on(\"mousemove\",function(a,b){v&&u.elementMousemove({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"click\",function(a,b){v&&(u.elementClick({data:a,index:b,color:d3.select(this).style(\"fill\")}),d3.event.stopPropagation())}).on(\"dblclick\",function(a,b){v&&(u.elementDblClick({data:a,index:b,color:d3.select(this).style(\"fill\")}),d3.event.stopPropagation())}),E.attr(\"fill\",function(a,b){return t(a,b)}).attr(\"class\",function(a,b,c){return(o(a,b)<0?\"nv-bar negative\":\"nv-bar positive\")+\" nv-bar-\"+c+\"-\"+b}).watchTransition(w,\"bars\").attr(\"transform\",function(a,c){return\"translate(\"+(l(n(a,c))-x/b[0].values.length*.45)+\",0)\"}).attr(\"width\",x/b[0].values.length*.9),E.watchTransition(w,\"bars\").attr(\"y\",function(b,c){var d=o(b,c)<0?m(0):m(0)-m(o(b,c))<1?m(0)-1:m(o(b,c));return a.utils.NaNtoZero(d)}).attr(\"height\",function(b,c){return a.utils.NaNtoZero(Math.max(Math.abs(m(o(b,c))-m(0)),1))})}),w.renderEnd(\"historicalBar immediate\"),b}var c,d,e,f,g={top:0,right:0,bottom:0,left:0},h=null,i=null,j=Math.floor(1e4*Math.random()),k=null,l=d3.scale.linear(),m=d3.scale.linear(),n=function(a){return a.x},o=function(a){return a.y},p=[],q=[0],r=!1,s=!0,t=a.utils.defaultColor(),u=d3.dispatch(\"chartClick\",\"elementClick\",\"elementDblClick\",\"elementMouseover\",\"elementMouseout\",\"elementMousemove\",\"renderEnd\"),v=!0,w=a.utils.renderWatch(u,0);return b.highlightPoint=function(a,b){k.select(\".nv-bars .nv-bar-0-\"+a).classed(\"hover\",b)},b.clearHighlights=function(){k.select(\".nv-bars .nv-bar.hover\").classed(\"hover\",!1)},b.dispatch=u,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return h},set:function(a){h=a}},height:{get:function(){return i},set:function(a){i=a}},forceX:{get:function(){return p},set:function(a){p=a}},forceY:{get:function(){return q},set:function(a){q=a}},padData:{get:function(){return r},set:function(a){r=a}},x:{get:function(){return n},set:function(a){n=a}},y:{get:function(){return o},set:function(a){o=a}},xScale:{get:function(){return l},set:function(a){l=a}},yScale:{get:function(){return m},set:function(a){m=a}},xDomain:{get:function(){return c},set:function(a){c=a}},yDomain:{get:function(){return d},set:function(a){d=a}},xRange:{get:function(){return e},set:function(a){e=a}},yRange:{get:function(){return f},set:function(a){f=a}},clipEdge:{get:function(){return s},set:function(a){s=a}},id:{get:function(){return j},set:function(a){j=a}},interactive:{get:function(){return v},set:function(a){v=a}},margin:{get:function(){return g},set:function(a){g.top=void 0!==a.top?a.top:g.top,g.right=void 0!==a.right?a.right:g.right,g.bottom=void 0!==a.bottom?a.bottom:g.bottom,g.left=void 0!==a.left?a.left:g.left}},color:{get:function(){return t},set:function(b){t=a.utils.getColor(b)}}}),a.utils.initOptions(b),b},a.models.historicalBarChart=function(b){\"use strict\";function c(b){return b.each(function(k){z.reset(),z.models(f),q&&z.models(g),r&&z.models(h);var w=d3.select(this);a.utils.initSVG(w);var A=a.utils.availableWidth(n,w,l),B=a.utils.availableHeight(o,w,l);if(c.update=function(){w.transition().duration(y).call(c)},c.container=this,u.disabled=k.map(function(a){return!!a.disabled}),!v){var C;v={};for(C in u)u[C]instanceof Array?v[C]=u[C].slice(0):v[C]=u[C]}if(!(k&&k.length&&k.filter(function(a){return a.values.length}).length))return a.utils.noData(c,w),c;w.selectAll(\".nv-noData\").remove(),d=f.xScale(),e=f.yScale();var D=w.selectAll(\"g.nv-wrap.nv-historicalBarChart\").data([k]),E=D.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-historicalBarChart\").append(\"g\"),F=D.select(\"g\");E.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),E.append(\"g\").attr(\"class\",\"nv-y nv-axis\"),E.append(\"g\").attr(\"class\",\"nv-barsWrap\"),E.append(\"g\").attr(\"class\",\"nv-legendWrap\"),E.append(\"g\").attr(\"class\",\"nv-interactive\"),p?(i.width(A),F.select(\".nv-legendWrap\").datum(k).call(i),i.height()>l.top&&(l.top=i.height(),B=a.utils.availableHeight(o,w,l)),D.select(\".nv-legendWrap\").attr(\"transform\",\"translate(0,\"+-l.top+\")\")):F.select(\".nv-legendWrap\").selectAll(\"*\").remove(),D.attr(\"transform\",\"translate(\"+l.left+\",\"+l.top+\")\"),s&&F.select(\".nv-y.nv-axis\").attr(\"transform\",\"translate(\"+A+\",0)\"),t&&(j.width(A).height(B).margin({left:l.left,top:l.top}).svgContainer(w).xScale(d),D.select(\".nv-interactive\").call(j)),f.width(A).height(B).color(k.map(function(a,b){return a.color||m(a,b)}).filter(function(a,b){return!k[b].disabled}));var G=F.select(\".nv-barsWrap\").datum(k.filter(function(a){return!a.disabled}));G.transition().call(f),q&&(g.scale(d)._ticks(a.utils.calcTicksX(A/100,k)).tickSize(-B,0),F.select(\".nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+e.range()[0]+\")\"),F.select(\".nv-x.nv-axis\").transition().call(g)),r&&(h.scale(e)._ticks(a.utils.calcTicksY(B/36,k)).tickSize(-A,0),F.select(\".nv-y.nv-axis\").transition().call(h)),j.dispatch.on(\"elementMousemove\",function(b){f.clearHighlights();var d,e,i,l=[];k.filter(function(a,b){return a.seriesIndex=b,!a.disabled}).forEach(function(g,h){e=a.interactiveBisect(g.values,b.pointXValue,c.x()),f.highlightPoint(e,!0);var j=g.values[e];void 0!==j&&(void 0===d&&(d=j),void 0===i&&(i=c.xScale()(c.x()(j,e))),l.push({key:g.key,value:c.y()(j,e),color:m(g,g.seriesIndex),data:g.values[e]}))});var n=g.tickFormat()(c.x()(d,e));j.tooltip.valueFormatter(function(a,b){return h.tickFormat()(a)}).data({value:n,index:e,series:l})(),j.renderGuideLine(i)}),j.dispatch.on(\"elementMouseout\",function(a){x.tooltipHide(),f.clearHighlights()}),i.dispatch.on(\"legendClick\",function(a,d){a.disabled=!a.disabled,k.filter(function(a){return!a.disabled}).length||k.map(function(a){return a.disabled=!1,D.selectAll(\".nv-series\").classed(\"disabled\",!1),a}),u.disabled=k.map(function(a){return!!a.disabled}),x.stateChange(u),b.transition().call(c)}),i.dispatch.on(\"legendDblclick\",function(a){k.forEach(function(a){a.disabled=!0}),a.disabled=!1,u.disabled=k.map(function(a){return!!a.disabled}),x.stateChange(u),c.update()}),x.on(\"changeState\",function(a){\"undefined\"!=typeof a.disabled&&(k.forEach(function(b,c){b.disabled=a.disabled[c]}),u.disabled=a.disabled),c.update()})}),z.renderEnd(\"historicalBarChart immediate\"),c}var d,e,f=b||a.models.historicalBar(),g=a.models.axis(),h=a.models.axis(),i=a.models.legend(),j=a.interactiveGuideline(),k=a.models.tooltip(),l={top:30,right:90,bottom:50,left:90},m=a.utils.defaultColor(),n=null,o=null,p=!1,q=!0,r=!0,s=!1,t=!1,u={},v=null,w=null,x=d3.dispatch(\"tooltipHide\",\"stateChange\",\"changeState\",\"renderEnd\"),y=250;g.orient(\"bottom\").tickPadding(7),h.orient(s?\"right\":\"left\"),k.duration(0).headerEnabled(!1).valueFormatter(function(a,b){return h.tickFormat()(a,b)}).headerFormatter(function(a,b){return g.tickFormat()(a,b)});var z=a.utils.renderWatch(x,0);return f.dispatch.on(\"elementMouseover.tooltip\",function(a){a.series={key:c.x()(a.data),value:c.y()(a.data),color:a.color},k.data(a).hidden(!1)}),f.dispatch.on(\"elementMouseout.tooltip\",function(a){k.hidden(!0)}),f.dispatch.on(\"elementMousemove.tooltip\",function(a){k()}),c.dispatch=x,c.bars=f,c.legend=i,c.xAxis=g,c.yAxis=h,c.interactiveLayer=j,c.tooltip=k,c.options=a.utils.optionsFunc.bind(c),c._options=Object.create({},{width:{get:function(){return n},set:function(a){n=a}},height:{get:function(){return o},set:function(a){o=a}},showLegend:{get:function(){return p},set:function(a){p=a}},showXAxis:{get:function(){return q},set:function(a){q=a}},showYAxis:{get:function(){return r},set:function(a){r=a}},defaultState:{get:function(){return v},set:function(a){v=a}},noData:{get:function(){return w},set:function(a){w=a}},margin:{get:function(){return l},set:function(a){l.top=void 0!==a.top?a.top:l.top,l.right=void 0!==a.right?a.right:l.right,l.bottom=void 0!==a.bottom?a.bottom:l.bottom,l.left=void 0!==a.left?a.left:l.left}},color:{get:function(){return m},set:function(b){m=a.utils.getColor(b),i.color(m),f.color(m)}},duration:{get:function(){return y},set:function(a){y=a,z.reset(y),h.duration(y),g.duration(y)}},rightAlignYAxis:{get:function(){return s},set:function(a){s=a,h.orient(a?\"right\":\"left\")}},useInteractiveGuideline:{get:function(){return t},set:function(a){t=a,a===!0&&c.interactive(!1)}}}),a.utils.inheritOptions(c,f),a.utils.initOptions(c),c},a.models.ohlcBarChart=function(){var b=a.models.historicalBarChart(a.models.ohlcBar());return b.useInteractiveGuideline(!0),b.interactiveLayer.tooltip.contentGenerator(function(a){var c=a.series[0].data,d=c.open<c.close?\"2ca02c\":\"d62728\";return'<h3 style=\"color: #'+d+'\">'+a.value+\"</h3><table><tr><td>open:</td><td>\"+b.yAxis.tickFormat()(c.open)+\"</td></tr><tr><td>close:</td><td>\"+b.yAxis.tickFormat()(c.close)+\"</td></tr><tr><td>high</td><td>\"+b.yAxis.tickFormat()(c.high)+\"</td></tr><tr><td>low:</td><td>\"+b.yAxis.tickFormat()(c.low)+\"</td></tr></table>\"}),b},a.models.candlestickBarChart=function(){var b=a.models.historicalBarChart(a.models.candlestickBar());return b.useInteractiveGuideline(!0),b.interactiveLayer.tooltip.contentGenerator(function(a){var c=a.series[0].data,d=c.open<c.close?\"2ca02c\":\"d62728\";return'<h3 style=\"color: #'+d+'\">'+a.value+\"</h3><table><tr><td>open:</td><td>\"+b.yAxis.tickFormat()(c.open)+\"</td></tr><tr><td>close:</td><td>\"+b.yAxis.tickFormat()(c.close)+\"</td></tr><tr><td>high</td><td>\"+b.yAxis.tickFormat()(c.high)+\"</td></tr><tr><td>low:</td><td>\"+b.yAxis.tickFormat()(c.low)+\"</td></tr></table>\"}),b},a.models.legend=function(){\"use strict\";function b(r){function s(a,b){return\"furious\"!=q?\"#000\":o?a.disengaged?\"#000\":\"#fff\":o?void 0:(a.color||(a.color=h(a,b)),a.disabled?a.color:\"#fff\")}function t(a,b){return o&&\"furious\"==q&&a.disengaged?\"#eee\":a.color||h(a,b)}function u(a,b){return o&&\"furious\"==q?1:a.disabled?0:1}return r.each(function(b){var h=d-c.left-c.right,r=d3.select(this);a.utils.initSVG(r);var v=r.selectAll(\"g.nv-legend\").data([b]),w=v.enter().append(\"g\").attr(\"class\",\"nvd3 nv-legend\").append(\"g\"),x=v.select(\"g\");v.attr(\"transform\",\"translate(\"+c.left+\",\"+c.top+\")\");var y,z,A=x.selectAll(\".nv-series\").data(function(a){return\"furious\"!=q?a:a.filter(function(a){return o?!0:!a.disengaged})}),B=A.enter().append(\"g\").attr(\"class\",\"nv-series\");switch(q){case\"furious\":z=23;break;case\"classic\":z=20}if(\"classic\"==q)B.append(\"circle\").style(\"stroke-width\",2).attr(\"class\",\"nv-legend-symbol\").attr(\"r\",5),y=A.select(\".nv-legend-symbol\");else if(\"furious\"==q){B.append(\"rect\").style(\"stroke-width\",2).attr(\"class\",\"nv-legend-symbol\").attr(\"rx\",3).attr(\"ry\",3),y=A.select(\".nv-legend-symbol\"),B.append(\"g\").attr(\"class\",\"nv-check-box\").property(\"innerHTML\",'<path d=\"M0.5,5 L22.5,5 L22.5,26.5 L0.5,26.5 L0.5,5 Z\" class=\"nv-box\"></path><path d=\"M5.5,12.8618467 L11.9185089,19.2803556 L31,0.198864511\" class=\"nv-check\"></path>').attr(\"transform\",\"translate(-10,-8)scale(0.5)\");var C=A.select(\".nv-check-box\");C.each(function(a,b){d3.select(this).selectAll(\"path\").attr(\"stroke\",s(a,b))})}B.append(\"text\").attr(\"text-anchor\",\"start\").attr(\"class\",\"nv-legend-text\").attr(\"dy\",\".32em\").attr(\"dx\",\"8\");var D=A.select(\"text.nv-legend-text\");A.on(\"mouseover\",function(a,b){p.legendMouseover(a,b)}).on(\"mouseout\",function(a,b){p.legendMouseout(a,b)}).on(\"click\",function(a,b){p.legendClick(a,b);var c=A.data();if(m){if(\"classic\"==q)n?(c.forEach(function(a){a.disabled=!0}),a.disabled=!1):(a.disabled=!a.disabled,c.every(function(a){return a.disabled})&&c.forEach(function(a){a.disabled=!1}));else if(\"furious\"==q)if(o)a.disengaged=!a.disengaged,a.userDisabled=void 0==a.userDisabled?!!a.disabled:a.userDisabled,a.disabled=a.disengaged||a.userDisabled;else if(!o){a.disabled=!a.disabled,a.userDisabled=a.disabled;var d=c.filter(function(a){return!a.disengaged});d.every(function(a){return a.userDisabled})&&c.forEach(function(a){a.disabled=a.userDisabled=!1})}p.stateChange({disabled:c.map(function(a){return!!a.disabled}),disengaged:c.map(function(a){return!!a.disengaged})})}}).on(\"dblclick\",function(a,b){if((\"furious\"!=q||!o)&&(p.legendDblclick(a,b),m)){var c=A.data();c.forEach(function(a){a.disabled=!0,\"furious\"==q&&(a.userDisabled=a.disabled)}),a.disabled=!1,\"furious\"==q&&(a.userDisabled=a.disabled),p.stateChange({disabled:c.map(function(a){return!!a.disabled})})}}),A.classed(\"nv-disabled\",function(a){return a.userDisabled}),A.exit().remove(),D.attr(\"fill\",s).text(function(a){return g(f(a))});var E=0;if(j){var F=[];A.each(function(b,c){var d;if(g(f(b))&&g(f(b)).length>i){var e=g(f(b)).substring(0,i);d=d3.select(this).select(\"text\").text(e+\"...\"),d3.select(this).append(\"svg:title\").text(g(f(b)))}else d=d3.select(this).select(\"text\");var h;try{if(h=d.node().getComputedTextLength(),0>=h)throw Error()}catch(j){h=a.utils.calcApproxTextWidth(d)}F.push(h+k)});var G=0,H=[];for(E=0;h>E&&G<F.length;)H[G]=F[G],E+=F[G++];for(0===G&&(G=1);E>h&&G>1;){H=[],G--;for(var I=0;I<F.length;I++)F[I]>(H[I%G]||0)&&(H[I%G]=F[I]);E=H.reduce(function(a,b,c,d){return a+b})}for(var J=[],K=0,L=0;G>K;K++)J[K]=L,L+=H[K];A.attr(\"transform\",function(a,b){return\"translate(\"+J[b%G]+\",\"+(5+Math.floor(b/G)*z)+\")\"}),l?x.attr(\"transform\",\"translate(\"+(d-c.right-E)+\",\"+c.top+\")\"):x.attr(\"transform\",\"translate(0,\"+c.top+\")\"),e=c.top+c.bottom+Math.ceil(F.length/G)*z}else{var M,N=5,O=5,P=0;A.attr(\"transform\",function(a,b){var e=d3.select(this).select(\"text\").node().getComputedTextLength()+k;return M=O,d<c.left+c.right+M+e&&(O=M=5,N+=z),O+=e,O>P&&(P=O),M+P>E&&(E=M+P),\"translate(\"+M+\",\"+N+\")\"}),x.attr(\"transform\",\"translate(\"+(d-c.right-P)+\",\"+c.top+\")\"),e=c.top+c.bottom+N+15}if(\"furious\"==q){y.attr(\"width\",function(a,b){return D[0][b].getComputedTextLength()+27}).attr(\"height\",18).attr(\"y\",-9).attr(\"x\",-15),w.insert(\"rect\",\":first-child\").attr(\"class\",\"nv-legend-bg\").attr(\"fill\",\"#eee\").attr(\"opacity\",0);var Q=x.select(\".nv-legend-bg\");Q.transition().duration(300).attr(\"x\",-z).attr(\"width\",E+z-12).attr(\"height\",e+10).attr(\"y\",-c.top-10).attr(\"opacity\",o?1:0)}y.style(\"fill\",t).style(\"fill-opacity\",u).style(\"stroke\",t)}),b}var c={top:5,right:0,bottom:5,left:0},d=400,e=20,f=function(a){return a.key},g=function(a){return a},h=a.utils.getColor(),i=20,j=!0,k=32,l=!0,m=!0,n=!1,o=!1,p=d3.dispatch(\"legendClick\",\"legendDblclick\",\"legendMouseover\",\"legendMouseout\",\"stateChange\"),q=\"classic\";return b.dispatch=p,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return d},set:function(a){d=a}},height:{get:function(){return e},set:function(a){e=a}},key:{get:function(){return f},set:function(a){f=a}},keyFormatter:{get:function(){return g},set:function(a){g=a}},align:{get:function(){return j},set:function(a){j=a}},maxKeyLength:{get:function(){return i},set:function(a){i=a}},rightAlign:{get:function(){return l},set:function(a){l=a}},padding:{get:function(){return k},set:function(a){k=a}},updateState:{get:function(){return m},set:function(a){m=a}},radioButtonMode:{get:function(){return n},set:function(a){n=a}},expanded:{get:function(){return o},set:function(a){o=a}},vers:{get:function(){return q},set:function(a){q=a}},margin:{get:function(){return c},set:function(a){c.top=void 0!==a.top?a.top:c.top,c.right=void 0!==a.right?a.right:c.right,c.bottom=void 0!==a.bottom?a.bottom:c.bottom,c.left=void 0!==a.left?a.left:c.left}},color:{get:function(){return h},set:function(b){h=a.utils.getColor(b)}}}),a.utils.initOptions(b),b},a.models.line=function(){\"use strict\";function b(r){return v.reset(),v.models(e),r.each(function(b){i=d3.select(this);var r=a.utils.availableWidth(g,i,f),s=a.utils.availableHeight(h,i,f);a.utils.initSVG(i),c=e.xScale(),d=e.yScale(),t=t||c,u=u||d;var w=i.selectAll(\"g.nv-wrap.nv-line\").data([b]),x=w.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-line\"),y=x.append(\"defs\"),z=x.append(\"g\"),A=w.select(\"g\");z.append(\"g\").attr(\"class\",\"nv-groups\"),z.append(\"g\").attr(\"class\",\"nv-scatterWrap\"),w.attr(\"transform\",\"translate(\"+f.left+\",\"+f.top+\")\"),e.width(r).height(s);var B=w.select(\".nv-scatterWrap\");B.call(e),y.append(\"clipPath\").attr(\"id\",\"nv-edge-clip-\"+e.id()).append(\"rect\"),w.select(\"#nv-edge-clip-\"+e.id()+\" rect\").attr(\"width\",r).attr(\"height\",s>0?s:0),A.attr(\"clip-path\",p?\"url(#nv-edge-clip-\"+e.id()+\")\":\"\"),B.attr(\"clip-path\",p?\"url(#nv-edge-clip-\"+e.id()+\")\":\"\");var C=w.select(\".nv-groups\").selectAll(\".nv-group\").data(function(a){return a},function(a){return a.key});C.enter().append(\"g\").style(\"stroke-opacity\",1e-6).style(\"stroke-width\",function(a){return a.strokeWidth||j}).style(\"fill-opacity\",1e-6),C.exit().remove(),C.attr(\"class\",function(a,b){return(a.classed||\"\")+\" nv-group nv-series-\"+b}).classed(\"hover\",function(a){return a.hover}).style(\"fill\",function(a,b){return k(a,b)}).style(\"stroke\",function(a,b){return k(a,b)}),C.watchTransition(v,\"line: groups\").style(\"stroke-opacity\",1).style(\"fill-opacity\",function(a){return a.fillOpacity||.5});var D=C.selectAll(\"path.nv-area\").data(function(a){return o(a)?[a]:[]});D.enter().append(\"path\").attr(\"class\",\"nv-area\").attr(\"d\",function(b){return d3.svg.area().interpolate(q).defined(n).x(function(b,c){return a.utils.NaNtoZero(t(l(b,c)))}).y0(function(b,c){return a.utils.NaNtoZero(u(m(b,c)))}).y1(function(a,b){return u(d.domain()[0]<=0?d.domain()[1]>=0?0:d.domain()[1]:d.domain()[0])}).apply(this,[b.values])}),C.exit().selectAll(\"path.nv-area\").remove(),D.watchTransition(v,\"line: areaPaths\").attr(\"d\",function(b){return d3.svg.area().interpolate(q).defined(n).x(function(b,d){return a.utils.NaNtoZero(c(l(b,d)))}).y0(function(b,c){return a.utils.NaNtoZero(d(m(b,c)))}).y1(function(a,b){return d(d.domain()[0]<=0?d.domain()[1]>=0?0:d.domain()[1]:d.domain()[0])}).apply(this,[b.values])});var E=C.selectAll(\"path.nv-line\").data(function(a){return[a.values]});E.enter().append(\"path\").attr(\"class\",\"nv-line\").attr(\"d\",d3.svg.line().interpolate(q).defined(n).x(function(b,c){return a.utils.NaNtoZero(t(l(b,c)))}).y(function(b,c){return a.utils.NaNtoZero(u(m(b,c)))})),E.watchTransition(v,\"line: linePaths\").attr(\"d\",d3.svg.line().interpolate(q).defined(n).x(function(b,d){return a.utils.NaNtoZero(c(l(b,d)))}).y(function(b,c){return a.utils.NaNtoZero(d(m(b,c)))})),t=c.copy(),u=d.copy()}),v.renderEnd(\"line immediate\"),b}var c,d,e=a.models.scatter(),f={top:0,right:0,bottom:0,left:0},g=960,h=500,i=null,j=1.5,k=a.utils.defaultColor(),l=function(a){return a.x},m=function(a){return a.y},n=function(a,b){return!isNaN(m(a,b))&&null!==m(a,b)},o=function(a){return a.area},p=!1,q=\"linear\",r=250,s=d3.dispatch(\"elementClick\",\"elementMouseover\",\"elementMouseout\",\"renderEnd\");e.pointSize(16).pointDomain([16,256]);var t,u,v=a.utils.renderWatch(s,r);return b.dispatch=s,b.scatter=e,e.dispatch.on(\"elementClick\",function(){s.elementClick.apply(this,arguments)}),e.dispatch.on(\"elementMouseover\",function(){s.elementMouseover.apply(this,arguments)}),e.dispatch.on(\"elementMouseout\",function(){s.elementMouseout.apply(this,arguments)}),b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return g},set:function(a){g=a}},height:{get:function(){return h},set:function(a){h=a}},defined:{get:function(){return n},set:function(a){n=a}},interpolate:{get:function(){return q},set:function(a){q=a}},clipEdge:{get:function(){return p},set:function(a){p=a}},margin:{get:function(){return f},set:function(a){f.top=void 0!==a.top?a.top:f.top,f.right=void 0!==a.right?a.right:f.right,f.bottom=void 0!==a.bottom?a.bottom:f.bottom,f.left=void 0!==a.left?a.left:f.left}},duration:{get:function(){return r},set:function(a){r=a,v.reset(r),e.duration(r)}},isArea:{get:function(){return o},set:function(a){o=d3.functor(a)}},x:{get:function(){return l},set:function(a){l=a,e.x(a)}},y:{get:function(){return m},set:function(a){m=a,e.y(a)}},color:{get:function(){return k},set:function(b){k=a.utils.getColor(b),e.color(k)}}}),a.utils.inheritOptions(b,e),a.utils.initOptions(b),b},a.models.lineChart=function(){\"use strict\";function b(j){return B.reset(),B.models(e),r&&B.models(f),s&&B.models(g),j.each(function(j){function y(){r&&L.select(\".nv-focus .nv-x.nv-axis\").transition().duration(A).call(f)}function B(){s&&L.select(\".nv-focus .nv-y.nv-axis\").transition().duration(A).call(g)}function E(a){var b=L.select(\".nv-focus .nv-linesWrap\").datum(j.filter(function(a){return!a.disabled}).map(function(b,c){return{key:b.key,area:b.area,classed:b.classed,values:b.values.filter(function(b,c){return e.x()(b,c)>=a[0]&&e.x()(b,c)<=a[1]}),disableTooltip:b.disableTooltip}}));b.transition().duration(A).call(e),y(),B()}var F=d3.select(this);a.utils.initSVG(F);var G=a.utils.availableWidth(n,F,l),H=a.utils.availableHeight(o,F,l)-(v?k.height():0);if(b.update=function(){0===A?F.call(b):F.transition().duration(A).call(b)},b.container=this,w.setter(D(j),b.update).getter(C(j)).update(),w.disabled=j.map(function(a){return!!a.disabled}),!x){var I;x={};for(I in w)w[I]instanceof Array?x[I]=w[I].slice(0):x[I]=w[I]}if(!(j&&j.length&&j.filter(function(a){return a.values.length}).length))return a.utils.noData(b,F),b;F.selectAll(\".nv-noData\").remove(),k.dispatch.on(\"onBrush\",function(a){E(a)}),c=e.xScale(),d=e.yScale();var J=F.selectAll(\"g.nv-wrap.nv-lineChart\").data([j]),K=J.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-lineChart\").append(\"g\"),L=J.select(\"g\");K.append(\"g\").attr(\"class\",\"nv-legendWrap\");var M=K.append(\"g\").attr(\"class\",\"nv-focus\");M.append(\"g\").attr(\"class\",\"nv-background\").append(\"rect\"),M.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),M.append(\"g\").attr(\"class\",\"nv-y nv-axis\"),M.append(\"g\").attr(\"class\",\"nv-linesWrap\"),M.append(\"g\").attr(\"class\",\"nv-interactive\");K.append(\"g\").attr(\"class\",\"nv-focusWrap\");p?(h.width(G),L.select(\".nv-legendWrap\").datum(j).call(h),\"bottom\"===q?J.select(\".nv-legendWrap\").attr(\"transform\",\"translate(0,\"+H+\")\"):\"top\"===q&&(h.height()>l.top&&(l.top=h.height(),H=a.utils.availableHeight(o,F,l)-(v?k.height():0)),J.select(\".nv-legendWrap\").attr(\"transform\",\"translate(0,\"+-l.top+\")\"))):L.select(\".nv-legendWrap\").selectAll(\"*\").remove(),J.attr(\"transform\",\"translate(\"+l.left+\",\"+l.top+\")\"),t&&L.select(\".nv-y.nv-axis\").attr(\"transform\",\"translate(\"+G+\",0)\"),u&&(i.width(G).height(H).margin({left:l.left,top:l.top}).svgContainer(F).xScale(c),J.select(\".nv-interactive\").call(i)),L.select(\".nv-focus .nv-background rect\").attr(\"width\",G).attr(\"height\",H),e.width(G).height(H).color(j.map(function(a,b){return a.color||m(a,b)}).filter(function(a,b){return!j[b].disabled}));var N=L.select(\".nv-linesWrap\").datum(j.filter(function(a){return!a.disabled}));if(r&&f.scale(c)._ticks(a.utils.calcTicksX(G/100,j)).tickSize(-H,0),s&&g.scale(d)._ticks(a.utils.calcTicksY(H/36,j)).tickSize(-G,0),L.select(\".nv-focus .nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+H+\")\"),v){k.width(G),L.select(\".nv-focusWrap\").attr(\"transform\",\"translate(0,\"+(H+l.bottom+k.margin().top)+\")\").datum(j.filter(function(a){return!a.disabled})).call(k);var O=k.brush.empty()?k.xDomain():k.brush.extent();null!==O&&E(O)}else N.call(e),y(),B();h.dispatch.on(\"stateChange\",function(a){for(var c in a)w[c]=a[c];z.stateChange(w),b.update()}),i.dispatch.on(\"elementMousemove\",function(d){e.clearHighlights();var f,h,l,n=[];if(j.filter(function(a,b){return a.seriesIndex=b,!a.disabled&&!a.disableTooltip}).forEach(function(g,i){var j=v?k.brush.empty()?k.xScale().domain():k.brush.extent():c.domain(),o=g.values.filter(function(a,b){return e.x()(a,b)>=j[0]&&e.x()(a,b)<=j[1]});h=a.interactiveBisect(o,d.pointXValue,e.x());var p=o[h],q=b.y()(p,h);null!==q&&e.highlightPoint(g.seriesIndex,h,!0),void 0!==p&&(void 0===f&&(f=p),void 0===l&&(l=b.xScale()(b.x()(p,h))),n.push({key:g.key,value:q,color:m(g,g.seriesIndex),data:p}))}),n.length>2){var o=b.yScale().invert(d.mouseY),p=Math.abs(b.yScale().domain()[0]-b.yScale().domain()[1]),q=.03*p,r=a.nearestValueIndex(n.map(function(a){return a.value}),o,q);null!==r&&(n[r].highlight=!0)}var s=function(a,b){return null==a?\"N/A\":g.tickFormat()(a)};i.tooltip.valueFormatter(i.tooltip.valueFormatter()||s).data({value:b.x()(f,h),index:h,series:n})(),i.renderGuideLine(l)}),i.dispatch.on(\"elementClick\",function(c){var d,f=[];j.filter(function(a,b){return a.seriesIndex=b,!a.disabled}).forEach(function(e){var g=a.interactiveBisect(e.values,c.pointXValue,b.x()),h=e.values[g];if(\"undefined\"!=typeof h){\"undefined\"==typeof d&&(d=b.xScale()(b.x()(h,g)));var i=b.yScale()(b.y()(h,g));f.push({point:h,pointIndex:g,pos:[d,i],seriesIndex:e.seriesIndex,series:e})}}),e.dispatch.elementClick(f)}),i.dispatch.on(\"elementMouseout\",function(a){e.clearHighlights()}),z.on(\"changeState\",function(a){\"undefined\"!=typeof a.disabled&&j.length===a.disabled.length&&(j.forEach(function(b,c){b.disabled=a.disabled[c]}),w.disabled=a.disabled),b.update()})}),B.renderEnd(\"lineChart immediate\"),b}var c,d,e=a.models.line(),f=a.models.axis(),g=a.models.axis(),h=a.models.legend(),i=a.interactiveGuideline(),j=a.models.tooltip(),k=a.models.focus(a.models.line()),l={top:30,right:20,bottom:50,left:60},m=a.utils.defaultColor(),n=null,o=null,p=!0,q=\"top\",r=!0,s=!0,t=!1,u=!1,v=!1,w=a.utils.state(),x=null,y=null,z=d3.dispatch(\"tooltipShow\",\"tooltipHide\",\"stateChange\",\"changeState\",\"renderEnd\"),A=250;f.orient(\"bottom\").tickPadding(7),g.orient(t?\"right\":\"left\"),e.clipEdge(!0).duration(0),j.valueFormatter(function(a,b){return g.tickFormat()(a,b)}).headerFormatter(function(a,b){return f.tickFormat()(a,b)}),i.tooltip.valueFormatter(function(a,b){return g.tickFormat()(a,b)}).headerFormatter(function(a,b){return f.tickFormat()(a,b)});var B=a.utils.renderWatch(z,A),C=function(a){return function(){return{active:a.map(function(a){return!a.disabled})}}},D=function(a){return function(b){void 0!==b.active&&a.forEach(function(a,c){a.disabled=!b.active[c]})}};return e.dispatch.on(\"elementMouseover.tooltip\",function(a){a.series.disableTooltip||j.data(a).hidden(!1)}),e.dispatch.on(\"elementMouseout.tooltip\",function(a){j.hidden(!0)}),b.dispatch=z,b.lines=e,b.legend=h,b.focus=k,b.xAxis=f,b.x2Axis=k.xAxis,b.yAxis=g,b.y2Axis=k.yAxis,b.interactiveLayer=i,b.tooltip=j,b.state=w,b.dispatch=z,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return n},set:function(a){n=a}},height:{get:function(){return o},set:function(a){o=a}},showLegend:{get:function(){return p},set:function(a){p=a}},legendPosition:{get:function(){return q},set:function(a){q=a}},showXAxis:{get:function(){return r},set:function(a){r=a}},showYAxis:{get:function(){return s},set:function(a){s=a}},defaultState:{get:function(){return x},set:function(a){x=a}},noData:{get:function(){return y},set:function(a){y=a}},focusEnable:{get:function(){return v},set:function(a){v=a}},focusHeight:{get:function(){return k.height()},set:function(a){k.height(a)}},focusShowAxisX:{get:function(){return k.showXAxis()},set:function(a){k.showXAxis(a)}},focusShowAxisY:{get:function(){return k.showYAxis()},set:function(a){k.showYAxis(a)}},brushExtent:{get:function(){return k.brushExtent()},set:function(a){k.brushExtent(a)}},focusMargin:{get:function(){return k.margin},set:function(a){k.margin.top=void 0!==a.top?a.top:k.margin.top,k.margin.right=void 0!==a.right?a.right:k.margin.right,k.margin.bottom=void 0!==a.bottom?a.bottom:k.margin.bottom,k.margin.left=void 0!==a.left?a.left:k.margin.left}},margin:{get:function(){return l},set:function(a){l.top=void 0!==a.top?a.top:l.top,l.right=void 0!==a.right?a.right:l.right,l.bottom=void 0!==a.bottom?a.bottom:l.bottom,l.left=void 0!==a.left?a.left:l.left}},duration:{get:function(){return A},set:function(a){A=a,B.reset(A),e.duration(A),k.duration(A),f.duration(A),g.duration(A)}},color:{get:function(){return m},set:function(b){m=a.utils.getColor(b),h.color(m),e.color(m),k.color(m)}},interpolate:{get:function(){return e.interpolate()},set:function(a){e.interpolate(a),k.interpolate(a)}},xTickFormat:{get:function(){return f.tickFormat()},set:function(a){f.tickFormat(a),k.xTickFormat(a)}},yTickFormat:{get:function(){return g.tickFormat()},set:function(a){g.tickFormat(a),k.yTickFormat(a)}},x:{get:function(){return e.x()},set:function(a){e.x(a),k.x(a)}},y:{get:function(){return e.y()},set:function(a){e.y(a),k.y(a)}},rightAlignYAxis:{get:function(){return t},set:function(a){t=a,g.orient(t?\"right\":\"left\")}},useInteractiveGuideline:{get:function(){return u},set:function(a){u=a,u&&(e.interactive(!1),e.useVoronoi(!1))}}}),a.utils.inheritOptions(b,e),a.utils.initOptions(b),b},a.models.lineWithFocusChart=function(){return a.models.lineChart().margin({bottom:30}).focusEnable(!0)},a.models.linePlusBarChart=function(){\"use strict\";function b(v){return v.each(function(v){function J(a){var b=+(\"e\"==a),c=b?1:-1,d=Z/3;return\"M\"+.5*c+\",\"+d+\"A6,6 0 0 \"+b+\" \"+6.5*c+\",\"+(d+6)+\"V\"+(2*d-6)+\"A6,6 0 0 \"+b+\" \"+.5*c+\",\"+2*d+\"ZM\"+2.5*c+\",\"+(d+8)+\"V\"+(2*d-8)+\"M\"+4.5*c+\",\"+(d+8)+\"V\"+(2*d-8)}function R(){u.empty()||u.extent(I),ma.data([u.empty()?e.domain():I]).each(function(a,b){var c=e(a[0])-e.range()[0],d=e.range()[1]-e(a[1]);d3.select(this).select(\".left\").attr(\"width\",0>c?0:c),d3.select(this).select(\".right\").attr(\"x\",e(a[1])).attr(\"width\",0>d?0:d)})}function S(){I=u.empty()?null:u.extent(),c=u.empty()?e.domain():u.extent(),K.brush({extent:c,brush:u}),R(),l.width(X).height(Y).color(v.map(function(a,b){return a.color||C(a,b)}).filter(function(a,b){return!v[b].disabled&&v[b].bar})),j.width(X).height(Y).color(v.map(function(a,b){return a.color||C(a,b)}).filter(function(a,b){return!v[b].disabled&&!v[b].bar}));var b=fa.select(\".nv-focus .nv-barsWrap\").datum(_.length?_.map(function(a,b){return{key:a.key,values:a.values.filter(function(a,b){return l.x()(a,b)>=c[0]&&l.x()(a,b)<=c[1]})}}):[{values:[]}]),h=fa.select(\".nv-focus .nv-linesWrap\").datum(V(aa)?[{values:[]}]:aa.filter(function(a){return!a.disabled}).map(function(a,b){return{area:a.area,fillOpacity:a.fillOpacity,strokeWidth:a.strokeWidth,key:a.key,values:a.values.filter(function(a,b){return j.x()(a,b)>=c[0]&&j.x()(a,b)<=c[1]})}}));d=_.length&&!Q?l.xScale():j.xScale(),n.scale(d)._ticks(a.utils.calcTicksX(X/100,v)).tickSize(-Y,0),n.domain([Math.ceil(c[0]),Math.floor(c[1])]),fa.select(\".nv-x.nv-axis\").transition().duration(L).call(n),b.transition().duration(L).call(l),h.transition().duration(L).call(j),fa.select(\".nv-focus .nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+f.range()[0]+\")\"),p.scale(f)._ticks(a.utils.calcTicksY(Y/36,v)).tickSize(-X,0),q.scale(g)._ticks(a.utils.calcTicksY(Y/36,v)),Q?q.tickSize(aa.length?0:-X,0):q.tickSize(_.length?0:-X,0);var i=_.length?1:0,k=aa.length&&!V(aa)?1:0,m=Q?k:i,o=Q?i:k;fa.select(\".nv-focus .nv-y1.nv-axis\").style(\"opacity\",m),fa.select(\".nv-focus .nv-y2.nv-axis\").style(\"opacity\",o).attr(\"transform\",\"translate(\"+d.range()[1]+\",0)\"),fa.select(\".nv-focus .nv-y1.nv-axis\").transition().duration(L).call(p),fa.select(\".nv-focus .nv-y2.nv-axis\").transition().duration(L).call(q)}var W=d3.select(this);a.utils.initSVG(W);var X=a.utils.availableWidth(y,W,w),Y=a.utils.availableHeight(z,W,w)-(E?H:0),Z=H-x.top-x.bottom;if(b.update=function(){W.transition().duration(L).call(b)},b.container=this,M.setter(U(v),b.update).getter(T(v)).update(),M.disabled=v.map(function(a){return!!a.disabled}),!N){var $;N={};for($ in M)M[$]instanceof Array?N[$]=M[$].slice(0):N[$]=M[$]}if(!(v&&v.length&&v.filter(function(a){return a.values.length}).length))return a.utils.noData(b,W),b;W.selectAll(\".nv-noData\").remove();var _=v.filter(function(a){return!a.disabled&&a.bar}),aa=v.filter(function(a){return!a.bar});d=_.length&&!Q?l.xScale():j.xScale(),e=o.scale(),f=Q?j.yScale():l.yScale(),g=Q?l.yScale():j.yScale(),h=Q?k.yScale():m.yScale(),i=Q?m.yScale():k.yScale();var ba=v.filter(function(a){return!a.disabled&&(Q?!a.bar:a.bar)}).map(function(a){return a.values.map(function(a,b){return{x:A(a,b),y:B(a,b)}})}),ca=v.filter(function(a){return!a.disabled&&(Q?a.bar:!a.bar)}).map(function(a){return a.values.map(function(a,b){return{x:A(a,b),y:B(a,b)}})});d.range([0,X]),e.domain(d3.extent(d3.merge(ba.concat(ca)),function(a){return a.x})).range([0,X]);var da=W.selectAll(\"g.nv-wrap.nv-linePlusBar\").data([v]),ea=da.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-linePlusBar\").append(\"g\"),fa=da.select(\"g\");ea.append(\"g\").attr(\"class\",\"nv-legendWrap\");var ga=ea.append(\"g\").attr(\"class\",\"nv-focus\");ga.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),ga.append(\"g\").attr(\"class\",\"nv-y1 nv-axis\"),ga.append(\"g\").attr(\"class\",\"nv-y2 nv-axis\"),ga.append(\"g\").attr(\"class\",\"nv-barsWrap\"),ga.append(\"g\").attr(\"class\",\"nv-linesWrap\");var ha=ea.append(\"g\").attr(\"class\",\"nv-context\");if(ha.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),ha.append(\"g\").attr(\"class\",\"nv-y1 nv-axis\"),ha.append(\"g\").attr(\"class\",\"nv-y2 nv-axis\"),ha.append(\"g\").attr(\"class\",\"nv-barsWrap\"),ha.append(\"g\").attr(\"class\",\"nv-linesWrap\"),ha.append(\"g\").attr(\"class\",\"nv-brushBackground\"),ha.append(\"g\").attr(\"class\",\"nv-x nv-brush\"),D){var ia=t.align()?X/2:X,ja=t.align()?ia:0;t.width(ia),fa.select(\".nv-legendWrap\").datum(v.map(function(a){return a.originalKey=void 0===a.originalKey?a.key:a.originalKey,Q?a.key=a.originalKey+(a.bar?P:O):a.key=a.originalKey+(a.bar?O:P),a})).call(t),t.height()>w.top&&(w.top=t.height(),Y=a.utils.availableHeight(z,W,w)-H),fa.select(\".nv-legendWrap\").attr(\"transform\",\"translate(\"+ja+\",\"+-w.top+\")\")}else fa.select(\".nv-legendWrap\").selectAll(\"*\").remove();da.attr(\"transform\",\"translate(\"+w.left+\",\"+w.top+\")\"),fa.select(\".nv-context\").style(\"display\",E?\"initial\":\"none\"),m.width(X).height(Z).color(v.map(function(a,b){return a.color||C(a,b)}).filter(function(a,b){return!v[b].disabled&&v[b].bar})),k.width(X).height(Z).color(v.map(function(a,b){return a.color||C(a,b)}).filter(function(a,b){return!v[b].disabled&&!v[b].bar}));var ka=fa.select(\".nv-context .nv-barsWrap\").datum(_.length?_:[{values:[]}]),la=fa.select(\".nv-context .nv-linesWrap\").datum(V(aa)?[{values:[]}]:aa.filter(function(a){return!a.disabled}));fa.select(\".nv-context\").attr(\"transform\",\"translate(0,\"+(Y+w.bottom+x.top)+\")\"),ka.transition().call(m),la.transition().call(k),G&&(o._ticks(a.utils.calcTicksX(X/100,v)).tickSize(-Z,0),fa.select(\".nv-context .nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+h.range()[0]+\")\"),fa.select(\".nv-context .nv-x.nv-axis\").transition().call(o)),F&&(r.scale(h)._ticks(Z/36).tickSize(-X,0),s.scale(i)._ticks(Z/36).tickSize(_.length?0:-X,0),fa.select(\".nv-context .nv-y3.nv-axis\").style(\"opacity\",_.length?1:0).attr(\"transform\",\"translate(0,\"+e.range()[0]+\")\"),fa.select(\".nv-context .nv-y2.nv-axis\").style(\"opacity\",aa.length?1:0).attr(\"transform\",\"translate(\"+e.range()[1]+\",0)\"),fa.select(\".nv-context .nv-y1.nv-axis\").transition().call(r),fa.select(\".nv-context .nv-y2.nv-axis\").transition().call(s)),u.x(e).on(\"brush\",S),I&&u.extent(I);var ma=fa.select(\".nv-brushBackground\").selectAll(\"g\").data([I||u.extent()]),na=ma.enter().append(\"g\");na.append(\"rect\").attr(\"class\",\"left\").attr(\"x\",0).attr(\"y\",0).attr(\"height\",Z),na.append(\"rect\").attr(\"class\",\"right\").attr(\"x\",0).attr(\"y\",0).attr(\"height\",Z);var oa=fa.select(\".nv-x.nv-brush\").call(u);oa.selectAll(\"rect\").attr(\"height\",Z),oa.selectAll(\".resize\").append(\"path\").attr(\"d\",J),t.dispatch.on(\"stateChange\",function(a){for(var c in a)M[c]=a[c];K.stateChange(M),b.update()}),K.on(\"changeState\",function(a){\"undefined\"!=typeof a.disabled&&(v.forEach(function(b,c){b.disabled=a.disabled[c]}),M.disabled=a.disabled),b.update()}),S()}),b}var c,d,e,f,g,h,i,j=a.models.line(),k=a.models.line(),l=a.models.historicalBar(),m=a.models.historicalBar(),n=a.models.axis(),o=a.models.axis(),p=a.models.axis(),q=a.models.axis(),r=a.models.axis(),s=a.models.axis(),t=a.models.legend(),u=d3.svg.brush(),v=a.models.tooltip(),w={top:30,right:30,bottom:30,left:60},x={top:0,right:30,bottom:20,left:60},y=null,z=null,A=function(a){return a.x},B=function(a){return a.y},C=a.utils.defaultColor(),D=!0,E=!0,F=!1,G=!0,H=50,I=null,J=null,K=d3.dispatch(\"brush\",\"stateChange\",\"changeState\"),L=0,M=a.utils.state(),N=null,O=\" (left axis)\",P=\" (right axis)\",Q=!1;j.clipEdge(!0),k.interactive(!1),k.pointActive(function(a){return!1}),n.orient(\"bottom\").tickPadding(5),p.orient(\"left\"),q.orient(\"right\"),o.orient(\"bottom\").tickPadding(5),r.orient(\"left\"),s.orient(\"right\"),v.headerEnabled(!0).headerFormatter(function(a,b){return n.tickFormat()(a,b)});var R=function(){return Q?{main:q,focus:s}:{main:p,focus:r}},S=function(){return Q?{main:p,focus:r}:{main:q,focus:s}},T=function(a){return function(){return{active:a.map(function(a){return!a.disabled})}}},U=function(a){return function(b){void 0!==b.active&&a.forEach(function(a,c){a.disabled=!b.active[c]})}},V=function(a){return a.every(function(a){return a.disabled})};return j.dispatch.on(\"elementMouseover.tooltip\",function(a){v.duration(100).valueFormatter(function(a,b){return S().main.tickFormat()(a,b)}).data(a).hidden(!1)}),j.dispatch.on(\"elementMouseout.tooltip\",function(a){v.hidden(!0)}),l.dispatch.on(\"elementMouseover.tooltip\",function(a){a.value=b.x()(a.data),a.series={value:b.y()(a.data),color:a.color},v.duration(0).valueFormatter(function(a,b){return R().main.tickFormat()(a,b)}).data(a).hidden(!1)}),l.dispatch.on(\"elementMouseout.tooltip\",function(a){v.hidden(!0)}),l.dispatch.on(\"elementMousemove.tooltip\",function(a){v()}),b.dispatch=K,b.legend=t,b.lines=j,b.lines2=k,b.bars=l,b.bars2=m,b.xAxis=n,b.x2Axis=o,b.y1Axis=p,b.y2Axis=q,b.y3Axis=r,b.y4Axis=s,b.tooltip=v,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return y},set:function(a){y=a}},height:{get:function(){return z},set:function(a){z=a}},showLegend:{get:function(){return D},set:function(a){D=a}},brushExtent:{get:function(){return I},set:function(a){I=a}},noData:{get:function(){return J},set:function(a){J=a}},focusEnable:{get:function(){return E},set:function(a){E=a}},focusHeight:{get:function(){return H},set:function(a){H=a}},focusShowAxisX:{get:function(){return G},set:function(a){G=a}},focusShowAxisY:{get:function(){return F},set:function(a){F=a}},legendLeftAxisHint:{get:function(){return O},set:function(a){O=a}},legendRightAxisHint:{get:function(){return P},set:function(a){P=a}},margin:{get:function(){return w},set:function(a){w.top=void 0!==a.top?a.top:w.top,w.right=void 0!==a.right?a.right:w.right,w.bottom=void 0!==a.bottom?a.bottom:w.bottom,w.left=void 0!==a.left?a.left:w.left}},focusMargin:{get:function(){return x},set:function(a){x.top=void 0!==a.top?a.top:x.top,x.right=void 0!==a.right?a.right:x.right,x.bottom=void 0!==a.bottom?a.bottom:x.bottom,x.left=void 0!==a.left?a.left:x.left}},duration:{get:function(){return L},set:function(a){L=a}},color:{get:function(){return C},set:function(b){C=a.utils.getColor(b),t.color(C)}},x:{get:function(){return A},set:function(a){A=a,j.x(a),k.x(a),l.x(a),m.x(a)}},y:{get:function(){return B},set:function(a){B=a,j.y(a),k.y(a),l.y(a),m.y(a)}},switchYAxisOrder:{get:function(){return Q},set:function(a){if(Q!==a){var b=p;p=q,q=b;var c=r;r=s,s=c}Q=a,p.orient(\"left\"),q.orient(\"right\"),r.orient(\"left\"),s.orient(\"right\")}}}),a.utils.inheritOptions(b,j),a.utils.initOptions(b),b},a.models.multiBar=function(){\"use strict\";function b(F){return D.reset(),F.each(function(b){var F=k-j.left-j.right,G=l-j.top-j.bottom;p=d3.select(this),a.utils.initSVG(p);var H=0;if(x&&b.length&&(x=[{values:b[0].values.map(function(a){return{x:a.x,y:0,series:a.series,size:.01}})}]),u){var I=d3.layout.stack().offset(v).values(function(a){return a.values}).y(r)(!b.length&&x?x:b);I.forEach(function(a,c){a.nonStackable?(b[c].nonStackableSeries=H++,I[c]=b[c]):c>0&&I[c-1].nonStackable&&I[c].values.map(function(a,b){a.y0-=I[c-1].values[b].y,a.y1=a.y0+a.y})}),b=I}b.forEach(function(a,b){a.values.forEach(function(c){c.series=b,c.key=a.key})}),u&&b.length>0&&b[0].values.map(function(a,c){var d=0,e=0;b.map(function(a,f){if(!b[f].nonStackable){var g=a.values[c];g.size=Math.abs(g.y),g.y<0?(g.y1=e,e-=g.size):(g.y1=g.size+d,d+=g.size)}})});var J=d&&e?[]:b.map(function(a,b){return a.values.map(function(a,c){return{x:q(a,c),y:r(a,c),y0:a.y0,y1:a.y1,idx:b}})});m.domain(d||d3.merge(J).map(function(a){return a.x})).rangeBands(f||[0,F],A),n.domain(e||d3.extent(d3.merge(J).map(function(a){var c=a.y;return u&&!b[a.idx].nonStackable&&(c=a.y>0?a.y1:a.y1+a.y),c}).concat(s))).range(g||[G,0]),m.domain()[0]===m.domain()[1]&&(m.domain()[0]?m.domain([m.domain()[0]-.01*m.domain()[0],m.domain()[1]+.01*m.domain()[1]]):m.domain([-1,1])),n.domain()[0]===n.domain()[1]&&(n.domain()[0]?n.domain([n.domain()[0]+.01*n.domain()[0],n.domain()[1]-.01*n.domain()[1]]):n.domain([-1,1])),h=h||m,i=i||n;var K=p.selectAll(\"g.nv-wrap.nv-multibar\").data([b]),L=K.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-multibar\"),M=L.append(\"defs\"),N=L.append(\"g\"),O=K.select(\"g\");N.append(\"g\").attr(\"class\",\"nv-groups\"),K.attr(\"transform\",\"translate(\"+j.left+\",\"+j.top+\")\"),M.append(\"clipPath\").attr(\"id\",\"nv-edge-clip-\"+o).append(\"rect\"),K.select(\"#nv-edge-clip-\"+o+\" rect\").attr(\"width\",F).attr(\"height\",G),O.attr(\"clip-path\",t?\"url(#nv-edge-clip-\"+o+\")\":\"\");var P=K.select(\".nv-groups\").selectAll(\".nv-group\").data(function(a){return a},function(a,b){return b});P.enter().append(\"g\").style(\"stroke-opacity\",1e-6).style(\"fill-opacity\",1e-6);var Q=D.transition(P.exit().selectAll(\"rect.nv-bar\"),\"multibarExit\",Math.min(100,z)).attr(\"y\",function(a,c,d){var e=i(0)||0;return u&&b[a.series]&&!b[a.series].nonStackable&&(e=i(a.y0)),e}).attr(\"height\",0).remove();Q.delay&&Q.delay(function(a,b){var c=b*(z/(E+1))-b;return c}),P.attr(\"class\",function(a,b){return\"nv-group nv-series-\"+b}).classed(\"hover\",function(a){return a.hover}).style(\"fill\",function(a,b){return w(a,b)}).style(\"stroke\",function(a,b){return w(a,b)}),P.style(\"stroke-opacity\",1).style(\"fill-opacity\",B);var R=P.selectAll(\"rect.nv-bar\").data(function(a){return x&&!b.length?x.values:a.values});R.exit().remove();R.enter().append(\"rect\").attr(\"class\",function(a,b){return r(a,b)<0?\"nv-bar negative\":\"nv-bar positive\"}).attr(\"x\",function(a,c,d){return u&&!b[d].nonStackable?0:d*m.rangeBand()/b.length}).attr(\"y\",function(a,c,d){return i(u&&!b[d].nonStackable?a.y0:0)||0}).attr(\"height\",0).attr(\"width\",function(a,c,d){return m.rangeBand()/(u&&!b[d].nonStackable?1:b.length)}).attr(\"transform\",function(a,b){return\"translate(\"+m(q(a,b))+\",0)\"});R.style(\"fill\",function(a,b,c){return w(a,c,b)}).style(\"stroke\",function(a,b,c){return w(a,c,b)}).on(\"mouseover\",function(a,b){d3.select(this).classed(\"hover\",!0),C.elementMouseover({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"mouseout\",function(a,b){d3.select(this).classed(\"hover\",!1),C.elementMouseout({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"mousemove\",function(a,b){C.elementMousemove({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"click\",function(a,b){var c=this;C.elementClick({data:a,index:b,color:d3.select(this).style(\"fill\"),event:d3.event,element:c}),d3.event.stopPropagation()}).on(\"dblclick\",function(a,b){C.elementDblClick({data:a,index:b,color:d3.select(this).style(\"fill\")}),d3.event.stopPropagation()}),R.attr(\"class\",function(a,b){return r(a,b)<0?\"nv-bar negative\":\"nv-bar positive\"}).attr(\"transform\",function(a,b){return\"translate(\"+m(q(a,b))+\",0)\"}),y&&(c||(c=b.map(function(){return!0})),R.style(\"fill\",function(a,b,d){return d3.rgb(y(a,b)).darker(c.map(function(a,b){return b}).filter(function(a,b){return!c[b]})[d]).toString()}).style(\"stroke\",function(a,b,d){return d3.rgb(y(a,b)).darker(c.map(function(a,b){return b}).filter(function(a,b){return!c[b]})[d]).toString()}));var S=R.watchTransition(D,\"multibar\",Math.min(250,z)).delay(function(a,c){return c*z/b[0].values.length});u?S.attr(\"y\",function(a,c,d){var e=0;return e=b[d].nonStackable?r(a,c)<0?n(0):n(0)-n(r(a,c))<-1?n(0)-1:n(r(a,c))||0:n(a.y1)}).attr(\"height\",function(a,c,d){return b[d].nonStackable?Math.max(Math.abs(n(r(a,c))-n(0)),0)||0:Math.max(Math.abs(n(a.y+a.y0)-n(a.y0)),0)}).attr(\"x\",function(a,c,d){var e=0;return b[d].nonStackable&&(e=a.series*m.rangeBand()/b.length,b.length!==H&&(e=b[d].nonStackableSeries*m.rangeBand()/(2*H))),e}).attr(\"width\",function(a,c,d){if(b[d].nonStackable){var e=m.rangeBand()/H;return b.length!==H&&(e=m.rangeBand()/(2*H)),e}return m.rangeBand()}):S.attr(\"x\",function(a,c){return a.series*m.rangeBand()/b.length}).attr(\"width\",m.rangeBand()/b.length).attr(\"y\",function(a,b){return r(a,b)<0?n(0):n(0)-n(r(a,b))<1?n(0)-1:n(r(a,b))||0}).attr(\"height\",function(a,b){return Math.max(Math.abs(n(r(a,b))-n(0)),1)||0}),h=m.copy(),i=n.copy(),b[0]&&b[0].values&&(E=b[0].values.length)}),D.renderEnd(\"multibar immediate\"),b}var c,d,e,f,g,h,i,j={top:0,right:0,bottom:0,left:0},k=960,l=500,m=d3.scale.ordinal(),n=d3.scale.linear(),o=Math.floor(1e4*Math.random()),p=null,q=function(a){return a.x},r=function(a){return a.y},s=[0],t=!0,u=!1,v=\"zero\",w=a.utils.defaultColor(),x=!1,y=null,z=500,A=.1,B=.75,C=d3.dispatch(\"chartClick\",\"elementClick\",\"elementDblClick\",\"elementMouseover\",\"elementMouseout\",\"elementMousemove\",\"renderEnd\"),D=a.utils.renderWatch(C,z),E=0;return b.dispatch=C,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return k},set:function(a){k=a}},height:{get:function(){return l},set:function(a){l=a}},x:{get:function(){return q},set:function(a){q=a}},y:{get:function(){return r},set:function(a){r=a}},xScale:{get:function(){return m},set:function(a){m=a}},yScale:{get:function(){return n},set:function(a){n=a}},xDomain:{get:function(){return d},set:function(a){d=a}},yDomain:{get:function(){return e},set:function(a){e=a}},xRange:{get:function(){return f},set:function(a){f=a}},yRange:{get:function(){return g},set:function(a){g=a}},forceY:{get:function(){return s},set:function(a){s=a}},stacked:{get:function(){return u},set:function(a){u=a}},stackOffset:{get:function(){return v},set:function(a){v=a}},clipEdge:{get:function(){return t},set:function(a){t=a}},disabled:{get:function(){return c},set:function(a){c=a}},id:{get:function(){return o},set:function(a){o=a}},hideable:{get:function(){return x},set:function(a){x=a}},groupSpacing:{get:function(){return A},set:function(a){A=a}},fillOpacity:{get:function(){return B},set:function(a){B=a}},margin:{get:function(){return j},set:function(a){j.top=void 0!==a.top?a.top:j.top,j.right=void 0!==a.right?a.right:j.right,j.bottom=void 0!==a.bottom?a.bottom:j.bottom,j.left=void 0!==a.left?a.left:j.left}},duration:{get:function(){return z},set:function(a){z=a,D.reset(z)}},color:{get:function(){return w},set:function(b){w=a.utils.getColor(b)}},barColor:{get:function(){return y},set:function(b){y=b?a.utils.getColor(b):null}}}),a.utils.initOptions(b),b},a.models.multiBarChart=function(){\"use strict\";function b(B){return G.reset(),G.models(e),s&&G.models(f),t&&G.models(g),B.each(function(B){var G=d3.select(this);a.utils.initSVG(G);var K=a.utils.availableWidth(m,G,l),L=a.utils.availableHeight(n,G,l);if(b.update=function(){0===E?G.call(b):G.transition().duration(E).call(b)},b.container=this,z.setter(J(B),b.update).getter(I(B)).update(),z.disabled=B.map(function(a){return!!a.disabled}),!A){var M;A={};for(M in z)z[M]instanceof Array?A[M]=z[M].slice(0):A[M]=z[M]}if(!(B&&B.length&&B.filter(function(a){return a.values.length}).length))return a.utils.noData(b,G),b;G.selectAll(\".nv-noData\").remove(),c=e.xScale(),d=e.yScale();var N=G.selectAll(\"g.nv-wrap.nv-multiBarWithLegend\").data([B]),O=N.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-multiBarWithLegend\").append(\"g\"),P=N.select(\"g\");if(O.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),O.append(\"g\").attr(\"class\",\"nv-y nv-axis\"),O.append(\"g\").attr(\"class\",\"nv-barsWrap\"),O.append(\"g\").attr(\"class\",\"nv-legendWrap\"),O.append(\"g\").attr(\"class\",\"nv-controlsWrap\"),O.append(\"g\").attr(\"class\",\"nv-interactive\"),r?(i.width(K-D()),P.select(\".nv-legendWrap\").datum(B).call(i),i.height()>l.top&&(l.top=i.height(),L=a.utils.availableHeight(n,G,l)),P.select(\".nv-legendWrap\").attr(\"transform\",\"translate(\"+D()+\",\"+-l.top+\")\")):P.select(\".nv-legendWrap\").selectAll(\"*\").remove(),p){var Q=[{key:q.grouped||\"Grouped\",disabled:e.stacked()},{key:q.stacked||\"Stacked\",disabled:!e.stacked()}];j.width(D()).color([\"#444\",\"#444\",\"#444\"]),P.select(\".nv-controlsWrap\").datum(Q).attr(\"transform\",\"translate(0,\"+-l.top+\")\").call(j)}else P.select(\".nv-controlsWrap\").selectAll(\"*\").remove();N.attr(\"transform\",\"translate(\"+l.left+\",\"+l.top+\")\"),u&&P.select(\".nv-y.nv-axis\").attr(\"transform\",\"translate(\"+K+\",0)\"),e.disabled(B.map(function(a){return a.disabled})).width(K).height(L).color(B.map(function(a,b){return a.color||o(a,b)}).filter(function(a,b){return!B[b].disabled}));var R=P.select(\".nv-barsWrap\").datum(B.filter(function(a){return!a.disabled}));if(R.call(e),s){f.scale(c)._ticks(a.utils.calcTicksX(K/100,B)).tickSize(-L,0),P.select(\".nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+d.range()[0]+\")\"),P.select(\".nv-x.nv-axis\").call(f);var S=P.select(\".nv-x.nv-axis > g\").selectAll(\"g\");if(S.selectAll(\"line, text\").style(\"opacity\",1),w){var T=function(a,b){return\"translate(\"+a+\",\"+b+\")\"},U=5,V=17;S.selectAll(\"text\").attr(\"transform\",function(a,b,c){return T(0,c%2==0?U:V)});var W=d3.selectAll(\".nv-x.nv-axis .nv-wrap g g text\")[0].length;P.selectAll(\".nv-x.nv-axis .nv-axisMaxMin text\").attr(\"transform\",function(a,b){return T(0,0===b||W%2!==0?V:U)})}x&&P.selectAll(\".tick text\").call(a.utils.wrapTicks,b.xAxis.rangeBand()),v&&S.filter(function(a,b){return b%Math.ceil(B[0].values.length/(K/100))!==0}).selectAll(\"text, line\").style(\"opacity\",0),y&&S.selectAll(\".tick text\").attr(\"transform\",\"rotate(\"+y+\" 0,0)\").style(\"text-anchor\",y>0?\"start\":\"end\"),P.select(\".nv-x.nv-axis\").selectAll(\"g.nv-axisMaxMin text\").style(\"opacity\",1)}t&&(g.scale(d)._ticks(a.utils.calcTicksY(L/36,B)).tickSize(-K,0),P.select(\".nv-y.nv-axis\").call(g)),F&&(h.width(K).height(L).margin({left:l.left,top:l.top}).svgContainer(G).xScale(c),N.select(\".nv-interactive\").call(h)),i.dispatch.on(\"stateChange\",function(a){for(var c in a)z[c]=a[c];C.stateChange(z),b.update()}),j.dispatch.on(\"legendClick\",function(a,c){if(a.disabled){switch(Q=Q.map(function(a){return a.disabled=!0,a}),a.disabled=!1,a.key){case\"Grouped\":case q.grouped:e.stacked(!1);break;case\"Stacked\":case q.stacked:e.stacked(!0)}z.stacked=e.stacked(),C.stateChange(z),b.update()}}),C.on(\"changeState\",function(a){\"undefined\"!=typeof a.disabled&&(B.forEach(function(b,c){b.disabled=a.disabled[c]}),z.disabled=a.disabled),\"undefined\"!=typeof a.stacked&&(e.stacked(a.stacked),z.stacked=a.stacked,H=a.stacked),b.update()}),F?(h.dispatch.on(\"elementMousemove\",function(a){if(void 0!=a.pointXValue){var d,e,f,g,i=[];B.filter(function(a,b){return a.seriesIndex=b,!a.disabled}).forEach(function(h,j){e=c.domain().indexOf(a.pointXValue);var k=h.values[e];void 0!==k&&(g=k.x,void 0===d&&(d=k),void 0===f&&(f=a.mouseX),i.push({key:h.key,value:b.y()(k,e),color:o(h,h.seriesIndex),data:h.values[e]}))}),h.tooltip.data({value:g,index:e,series:i})(),h.renderGuideLine(f)}}),h.dispatch.on(\"elementMouseout\",function(a){h.tooltip.hidden(!0)})):(e.dispatch.on(\"elementMouseover.tooltip\",function(a){a.value=b.x()(a.data),a.series={key:a.data.key,value:b.y()(a.data),color:a.color},k.data(a).hidden(!1)}),e.dispatch.on(\"elementMouseout.tooltip\",function(a){k.hidden(!0)}),e.dispatch.on(\"elementMousemove.tooltip\",function(a){k()}))}),G.renderEnd(\"multibarchart immediate\"),b}var c,d,e=a.models.multiBar(),f=a.models.axis(),g=a.models.axis(),h=a.interactiveGuideline(),i=a.models.legend(),j=a.models.legend(),k=a.models.tooltip(),l={top:30,right:20,bottom:50,left:60},m=null,n=null,o=a.utils.defaultColor(),p=!0,q={},r=!0,s=!0,t=!0,u=!1,v=!0,w=!1,x=!1,y=0,z=a.utils.state(),A=null,B=null,C=d3.dispatch(\"stateChange\",\"changeState\",\"renderEnd\"),D=function(){return p?180:0},E=250,F=!1;z.stacked=!1,e.stacked(!1),f.orient(\"bottom\").tickPadding(7).showMaxMin(!1).tickFormat(function(a){return a}),g.orient(u?\"right\":\"left\").tickFormat(d3.format(\",.1f\")),k.duration(0).valueFormatter(function(a,b){return g.tickFormat()(a,b)}).headerFormatter(function(a,b){return f.tickFormat()(a,b)}),j.updateState(!1);var G=a.utils.renderWatch(C),H=!1,I=function(a){return function(){return{active:a.map(function(a){return!a.disabled}),stacked:H}}},J=function(a){return function(b){void 0!==b.stacked&&(H=b.stacked),void 0!==b.active&&a.forEach(function(a,c){a.disabled=!b.active[c]})}};return b.dispatch=C,b.multibar=e,b.legend=i,b.controls=j,b.xAxis=f,b.yAxis=g,b.state=z,b.tooltip=k,b.interactiveLayer=h,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return m},set:function(a){m=a}},height:{get:function(){return n},set:function(a){n=a}},showLegend:{get:function(){return r},set:function(a){r=a}},showControls:{get:function(){return p},set:function(a){p=a}},controlLabels:{get:function(){return q},set:function(a){q=a}},showXAxis:{get:function(){return s},set:function(a){s=a}},showYAxis:{get:function(){return t},set:function(a){t=a}},defaultState:{get:function(){return A},set:function(a){A=a}},noData:{get:function(){return B},set:function(a){B=a}},reduceXTicks:{get:function(){return v},set:function(a){v=a}},rotateLabels:{get:function(){return y},set:function(a){y=a}},staggerLabels:{get:function(){return w},set:function(a){w=a}},wrapLabels:{get:function(){return x},set:function(a){x=!!a}},margin:{get:function(){return l},set:function(a){l.top=void 0!==a.top?a.top:l.top,l.right=void 0!==a.right?a.right:l.right,l.bottom=void 0!==a.bottom?a.bottom:l.bottom,l.left=void 0!==a.left?a.left:l.left}},duration:{get:function(){return E},set:function(a){E=a,e.duration(E),f.duration(E),g.duration(E),G.reset(E)}},color:{get:function(){return o},set:function(b){o=a.utils.getColor(b),i.color(o)}},rightAlignYAxis:{get:function(){return u},set:function(a){u=a,g.orient(u?\"right\":\"left\")}},useInteractiveGuideline:{get:function(){return F},set:function(a){F=a}},barColor:{get:function(){return e.barColor},set:function(a){e.barColor(a),i.color(function(a,b){return d3.rgb(\"#ccc\").darker(1.5*b).toString()})}}}),a.utils.inheritOptions(b,e),a.utils.initOptions(b),b},a.models.multiBarHorizontal=function(){\"use strict\";function b(m){return F.reset(),m.each(function(b){var m=k-j.left-j.right,D=l-j.top-j.bottom;n=d3.select(this),a.utils.initSVG(n),w&&(b=d3.layout.stack().offset(\"zero\").values(function(a){return a.values}).y(r)(b)),b.forEach(function(a,b){a.values.forEach(function(c){c.series=b,c.key=a.key})}),w&&b[0].values.map(function(a,c){var d=0,e=0;b.map(function(a){var b=a.values[c];b.size=Math.abs(b.y),b.y<0?(b.y1=e-b.size,e-=b.size):(b.y1=d,d+=b.size)})});var G=d&&e?[]:b.map(function(a){return a.values.map(function(a,b){return{x:q(a,b),y:r(a,b),y0:a.y0,y1:a.y1}})});o.domain(d||d3.merge(G).map(function(a){return a.x})).rangeBands(f||[0,D],A),p.domain(e||d3.extent(d3.merge(G).map(function(a){return w?a.y>0?a.y1+a.y:a.y1:a.y}).concat(t))),x&&!w?p.range(g||[p.domain()[0]<0?z:0,m-(p.domain()[1]>0?z:0)]):p.range(g||[0,m]),h=h||o,i=i||d3.scale.linear().domain(p.domain()).range([p(0),p(0)]);var H=d3.select(this).selectAll(\"g.nv-wrap.nv-multibarHorizontal\").data([b]),I=H.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-multibarHorizontal\"),J=(I.append(\"defs\"),I.append(\"g\"));H.select(\"g\");J.append(\"g\").attr(\"class\",\"nv-groups\"),H.attr(\"transform\",\"translate(\"+j.left+\",\"+j.top+\")\");var K=H.select(\".nv-groups\").selectAll(\".nv-group\").data(function(a){return a},function(a,b){return b});K.enter().append(\"g\").style(\"stroke-opacity\",1e-6).style(\"fill-opacity\",1e-6),K.exit().watchTransition(F,\"multibarhorizontal: exit groups\").style(\"stroke-opacity\",1e-6).style(\"fill-opacity\",1e-6).remove(),K.attr(\"class\",function(a,b){return\"nv-group nv-series-\"+b}).classed(\"hover\",function(a){return a.hover}).style(\"fill\",function(a,b){return u(a,b)}).style(\"stroke\",function(a,b){return u(a,b)}),K.watchTransition(F,\"multibarhorizontal: groups\").style(\"stroke-opacity\",1).style(\"fill-opacity\",B);var L=K.selectAll(\"g.nv-bar\").data(function(a){return a.values});L.exit().remove();var M=L.enter().append(\"g\").attr(\"transform\",function(a,c,d){return\"translate(\"+i(w?a.y0:0)+\",\"+(w?0:d*o.rangeBand()/b.length+o(q(a,c)))+\")\"});M.append(\"rect\").attr(\"width\",0).attr(\"height\",o.rangeBand()/(w?1:b.length)),L.on(\"mouseover\",function(a,b){d3.select(this).classed(\"hover\",!0),E.elementMouseover({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"mouseout\",function(a,b){d3.select(this).classed(\"hover\",!1),E.elementMouseout({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"mouseout\",function(a,b){E.elementMouseout({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"mousemove\",function(a,b){E.elementMousemove({data:a,index:b,color:d3.select(this).style(\"fill\")})}).on(\"click\",function(a,b){var c=this;E.elementClick({data:a,index:b,color:d3.select(this).style(\"fill\"),event:d3.event,element:c}),d3.event.stopPropagation()}).on(\"dblclick\",function(a,b){E.elementDblClick({data:a,index:b,color:d3.select(this).style(\"fill\")}),d3.event.stopPropagation()}),s(b[0],0)&&(M.append(\"polyline\"),L.select(\"polyline\").attr(\"fill\",\"none\").attr(\"points\",function(a,c){var d=s(a,c),e=.8*o.rangeBand()/(2*(w?1:b.length));d=d.length?d:[-Math.abs(d),Math.abs(d)],d=d.map(function(a){return p(a)-p(0)});var f=[[d[0],-e],[d[0],e],[d[0],0],[d[1],0],[d[1],-e],[d[1],e]];return f.map(function(a){return a.join(\",\")}).join(\" \")}).attr(\"transform\",function(a,c){var d=o.rangeBand()/(2*(w?1:b.length));return\"translate(\"+(r(a,c)<0?0:p(r(a,c))-p(0))+\", \"+d+\")\"})),M.append(\"text\"),x&&!w?(L.select(\"text\").attr(\"text-anchor\",function(a,b){return r(a,b)<0?\"end\":\"start\"}).attr(\"y\",o.rangeBand()/(2*b.length)).attr(\"dy\",\".32em\").text(function(a,b){var c=C(r(a,b)),d=s(a,b);return void 0===d?c:d.length?c+\"+\"+C(Math.abs(d[1]))+\"-\"+C(Math.abs(d[0])):c+\"±\"+C(Math.abs(d))}),L.watchTransition(F,\"multibarhorizontal: bars\").select(\"text\").attr(\"x\",function(a,b){return r(a,b)<0?-4:p(r(a,b))-p(0)+4})):L.selectAll(\"text\").text(\"\"),y&&!w?(M.append(\"text\").classed(\"nv-bar-label\",!0),L.select(\"text.nv-bar-label\").attr(\"text-anchor\",function(a,b){return r(a,b)<0?\"start\":\"end\"}).attr(\"y\",o.rangeBand()/(2*b.length)).attr(\"dy\",\".32em\").text(function(a,b){return q(a,b)}),L.watchTransition(F,\"multibarhorizontal: bars\").select(\"text.nv-bar-label\").attr(\"x\",function(a,b){return r(a,b)<0?p(0)-p(r(a,b))+4:-4})):L.selectAll(\"text.nv-bar-label\").text(\"\"),L.attr(\"class\",function(a,b){return r(a,b)<0?\"nv-bar negative\":\"nv-bar positive\"}),v&&(c||(c=b.map(function(){return!0})),L.style(\"fill\",function(a,b,d){return d3.rgb(v(a,b)).darker(c.map(function(a,b){return b}).filter(function(a,b){return!c[b]})[d]).toString()}).style(\"stroke\",function(a,b,d){return d3.rgb(v(a,b)).darker(c.map(function(a,b){return b}).filter(function(a,b){return!c[b]})[d]).toString()})),w?L.watchTransition(F,\"multibarhorizontal: bars\").attr(\"transform\",function(a,b){return\"translate(\"+p(a.y1)+\",\"+o(q(a,b))+\")\"}).select(\"rect\").attr(\"width\",function(a,b){return Math.abs(p(r(a,b)+a.y0)-p(a.y0))||0}).attr(\"height\",o.rangeBand()):L.watchTransition(F,\"multibarhorizontal: bars\").attr(\"transform\",function(a,c){return\"translate(\"+p(r(a,c)<0?r(a,c):0)+\",\"+(a.series*o.rangeBand()/b.length+o(q(a,c)))+\")\"}).select(\"rect\").attr(\"height\",o.rangeBand()/b.length).attr(\"width\",function(a,b){return Math.max(Math.abs(p(r(a,b))-p(0)),1)||0}),h=o.copy(),i=p.copy()}),F.renderEnd(\"multibarHorizontal immediate\"),b}var c,d,e,f,g,h,i,j={top:0,right:0,bottom:0,left:0},k=960,l=500,m=Math.floor(1e4*Math.random()),n=null,o=d3.scale.ordinal(),p=d3.scale.linear(),q=function(a){return a.x},r=function(a){return a.y},s=function(a){return a.yErr},t=[0],u=a.utils.defaultColor(),v=null,w=!1,x=!1,y=!1,z=60,A=.1,B=.75,C=d3.format(\",.2f\"),D=250,E=d3.dispatch(\"chartClick\",\"elementClick\",\"elementDblClick\",\"elementMouseover\",\"elementMouseout\",\"elementMousemove\",\"renderEnd\"),F=a.utils.renderWatch(E,D);return b.dispatch=E,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return k},set:function(a){k=a}},height:{get:function(){return l},set:function(a){l=a}},x:{get:function(){return q},set:function(a){q=a}},y:{get:function(){return r},set:function(a){r=a}},yErr:{get:function(){return s},set:function(a){s=a}},xScale:{get:function(){return o},set:function(a){o=a}},yScale:{get:function(){return p},set:function(a){p=a}},xDomain:{get:function(){return d},set:function(a){d=a}},yDomain:{get:function(){return e},set:function(a){e=a}},xRange:{get:function(){return f},set:function(a){f=a}},yRange:{get:function(){return g},set:function(a){g=a}},forceY:{get:function(){return t},set:function(a){t=a}},stacked:{get:function(){return w},set:function(a){w=a}},showValues:{get:function(){return x},set:function(a){x=a}},disabled:{get:function(){return c},set:function(a){c=a}},id:{get:function(){return m},set:function(a){m=a}},valueFormat:{get:function(){return C},set:function(a){C=a}},valuePadding:{get:function(){return z},set:function(a){z=a}},groupSpacing:{get:function(){return A},set:function(a){A=a}},fillOpacity:{get:function(){return B},set:function(a){B=a}},margin:{get:function(){return j},set:function(a){j.top=void 0!==a.top?a.top:j.top,j.right=void 0!==a.right?a.right:j.right,j.bottom=void 0!==a.bottom?a.bottom:j.bottom,j.left=void 0!==a.left?a.left:j.left}},duration:{get:function(){return D},set:function(a){D=a,F.reset(D)}},color:{get:function(){return u},set:function(b){u=a.utils.getColor(b)}},barColor:{get:function(){return v},set:function(b){v=b?a.utils.getColor(b):null}}}),a.utils.initOptions(b),b},a.models.multiBarHorizontalChart=function(){\"use strict\";function b(j){return C.reset(),C.models(e),r&&C.models(f),s&&C.models(g),j.each(function(j){var w=d3.select(this);a.utils.initSVG(w);var C=a.utils.availableWidth(l,w,k),D=a.utils.availableHeight(m,w,k);if(b.update=function(){w.transition().duration(z).call(b)},b.container=this,t=e.stacked(),u.setter(B(j),b.update).getter(A(j)).update(),u.disabled=j.map(function(a){return!!a.disabled}),!v){var E;v={};for(E in u)u[E]instanceof Array?v[E]=u[E].slice(0):v[E]=u[E]}if(!(j&&j.length&&j.filter(function(a){return a.values.length}).length))return a.utils.noData(b,w),b;w.selectAll(\".nv-noData\").remove(),c=e.xScale(),d=e.yScale().clamp(!0);var F=w.selectAll(\"g.nv-wrap.nv-multiBarHorizontalChart\").data([j]),G=F.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-multiBarHorizontalChart\").append(\"g\"),H=F.select(\"g\");if(G.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),G.append(\"g\").attr(\"class\",\"nv-y nv-axis\").append(\"g\").attr(\"class\",\"nv-zeroLine\").append(\"line\"),G.append(\"g\").attr(\"class\",\"nv-barsWrap\"),G.append(\"g\").attr(\"class\",\"nv-legendWrap\"),G.append(\"g\").attr(\"class\",\"nv-controlsWrap\"),q?(h.width(C-y()),H.select(\".nv-legendWrap\").datum(j).call(h),h.height()>k.top&&(k.top=h.height(),D=a.utils.availableHeight(m,w,k)),H.select(\".nv-legendWrap\").attr(\"transform\",\"translate(\"+y()+\",\"+-k.top+\")\")):H.select(\".nv-legendWrap\").selectAll(\"*\").remove(),o){var I=[{key:p.grouped||\"Grouped\",disabled:e.stacked()},{key:p.stacked||\"Stacked\",disabled:!e.stacked()}];i.width(y()).color([\"#444\",\"#444\",\"#444\"]),H.select(\".nv-controlsWrap\").datum(I).attr(\"transform\",\"translate(0,\"+-k.top+\")\").call(i)}else H.select(\".nv-controlsWrap\").selectAll(\"*\").remove();F.attr(\"transform\",\"translate(\"+k.left+\",\"+k.top+\")\"),e.disabled(j.map(function(a){return a.disabled})).width(C).height(D).color(j.map(function(a,b){return a.color||n(a,b)}).filter(function(a,b){return!j[b].disabled}));var J=H.select(\".nv-barsWrap\").datum(j.filter(function(a){return!a.disabled}));if(J.transition().call(e),r){f.scale(c)._ticks(a.utils.calcTicksY(D/24,j)).tickSize(-C,0),H.select(\".nv-x.nv-axis\").call(f);var K=H.select(\".nv-x.nv-axis\").selectAll(\"g\");K.selectAll(\"line, text\")}s&&(g.scale(d)._ticks(a.utils.calcTicksX(C/100,j)).tickSize(-D,0),H.select(\".nv-y.nv-axis\").attr(\"transform\",\"translate(0,\"+D+\")\"),H.select(\".nv-y.nv-axis\").call(g)),H.select(\".nv-zeroLine line\").attr(\"x1\",d(0)).attr(\"x2\",d(0)).attr(\"y1\",0).attr(\"y2\",-D),h.dispatch.on(\"stateChange\",function(a){for(var c in a)u[c]=a[c];x.stateChange(u),b.update()}),i.dispatch.on(\"legendClick\",function(a,c){if(a.disabled){switch(I=I.map(function(a){return a.disabled=!0,a}),a.disabled=!1,a.key){case\"Grouped\":case p.grouped:e.stacked(!1);break;case\"Stacked\":case p.stacked:e.stacked(!0)}u.stacked=e.stacked(),x.stateChange(u),t=e.stacked(),b.update()}}),x.on(\"changeState\",function(a){\"undefined\"!=typeof a.disabled&&(j.forEach(function(b,c){b.disabled=a.disabled[c]}),u.disabled=a.disabled),\"undefined\"!=typeof a.stacked&&(e.stacked(a.stacked),u.stacked=a.stacked,t=a.stacked),b.update()})}),C.renderEnd(\"multibar horizontal chart immediate\"),b}var c,d,e=a.models.multiBarHorizontal(),f=a.models.axis(),g=a.models.axis(),h=a.models.legend().height(30),i=a.models.legend().height(30),j=a.models.tooltip(),k={top:30,right:20,bottom:50,left:60},l=null,m=null,n=a.utils.defaultColor(),o=!0,p={},q=!0,r=!0,s=!0,t=!1,u=a.utils.state(),v=null,w=null,x=d3.dispatch(\"stateChange\",\"changeState\",\"renderEnd\"),y=function(){return o?180:0},z=250;u.stacked=!1,e.stacked(t),f.orient(\"left\").tickPadding(5).showMaxMin(!1).tickFormat(function(a){return a}),g.orient(\"bottom\").tickFormat(d3.format(\",.1f\")),j.duration(0).valueFormatter(function(a,b){return g.tickFormat()(a,b)}).headerFormatter(function(a,b){return f.tickFormat()(a,b)}),i.updateState(!1);var A=function(a){return function(){return{active:a.map(function(a){return!a.disabled}),stacked:t}}},B=function(a){return function(b){void 0!==b.stacked&&(t=b.stacked),void 0!==b.active&&a.forEach(function(a,c){a.disabled=!b.active[c]})}},C=a.utils.renderWatch(x,z);return e.dispatch.on(\"elementMouseover.tooltip\",function(a){a.value=b.x()(a.data),a.series={key:a.data.key,value:b.y()(a.data),color:a.color},j.data(a).hidden(!1)}),e.dispatch.on(\"elementMouseout.tooltip\",function(a){j.hidden(!0)}),e.dispatch.on(\"elementMousemove.tooltip\",function(a){j()}),b.dispatch=x,b.multibar=e,b.legend=h,b.controls=i,b.xAxis=f,b.yAxis=g,b.state=u,b.tooltip=j,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return l},set:function(a){l=a}},height:{get:function(){return m},set:function(a){m=a}},showLegend:{get:function(){return q},set:function(a){q=a}},showControls:{get:function(){return o},set:function(a){o=a}},controlLabels:{get:function(){return p},set:function(a){p=a}},showXAxis:{get:function(){return r},set:function(a){r=a}},showYAxis:{get:function(){return s},set:function(a){s=a}},defaultState:{get:function(){return v},set:function(a){v=a}},noData:{get:function(){return w},set:function(a){w=a}},margin:{get:function(){return k},set:function(a){k.top=void 0!==a.top?a.top:k.top,k.right=void 0!==a.right?a.right:k.right,k.bottom=void 0!==a.bottom?a.bottom:k.bottom,k.left=void 0!==a.left?a.left:k.left}},duration:{get:function(){return z},set:function(a){z=a,C.reset(z),e.duration(z),f.duration(z),g.duration(z)}},color:{get:function(){return n},set:function(b){n=a.utils.getColor(b),h.color(n)}},barColor:{get:function(){return e.barColor},set:function(a){e.barColor(a),h.color(function(a,b){return d3.rgb(\"#ccc\").darker(1.5*b).toString()})}}}),a.utils.inheritOptions(b,e),a.utils.initOptions(b),b},a.models.multiChart=function(){\"use strict\";function b(j){return j.each(function(j){function n(a){var b=2===j[a.seriesIndex].yAxis?E:D;a.value=a.point.x,a.series={value:a.point.y,color:a.point.color,key:a.series.key},G.duration(0).headerFormatter(function(a,b){return C.tickFormat()(a,b)}).valueFormatter(function(a,c){return b.tickFormat()(a,c)}).data(a).hidden(!1)}function H(a){var b=2===j[a.seriesIndex].yAxis?E:D;a.value=a.point.x,a.series={value:a.point.y,color:a.point.color,key:a.series.key},G.duration(100).headerFormatter(function(a,b){return C.tickFormat()(a,b)}).valueFormatter(function(a,c){return b.tickFormat()(a,c)}).data(a).hidden(!1)}function J(a){var b=2===j[a.seriesIndex].yAxis?E:D;a.point.x=A.x()(a.point),a.point.y=A.y()(a.point),G.duration(0).headerFormatter(function(a,b){return C.tickFormat()(a,b)}).valueFormatter(function(a,c){return b.tickFormat()(a,c)}).data(a).hidden(!1)}function K(a){var b=2===j[a.data.series].yAxis?E:D;a.value=y.x()(a.data),a.series={value:y.y()(a.data),color:a.color,key:a.data.key},G.duration(0).headerFormatter(function(a,b){return C.tickFormat()(a,b)}).valueFormatter(function(a,c){return b.tickFormat()(a,c)}).data(a).hidden(!1)}function L(){for(var a=0,b=I.length;b>a;a++){var c=I[a];try{c.clearHighlights()}catch(d){}}}function M(a,b,c){for(var d=0,e=I.length;e>d;d++){var f=I[d];try{f.highlightPoint(a,b,c)}catch(g){}}}var N=d3.select(this);a.utils.initSVG(N),b.update=function(){N.transition().call(b)},b.container=this;var O=a.utils.availableWidth(g,N,e),P=a.utils.availableHeight(h,N,e),Q=j.filter(function(a){return\"line\"==a.type&&1==a.yAxis}),R=j.filter(function(a){return\"line\"==a.type&&2==a.yAxis}),S=j.filter(function(a){return\"scatter\"==a.type&&1==a.yAxis}),T=j.filter(function(a){return\"scatter\"==a.type&&2==a.yAxis}),U=j.filter(function(a){return\"bar\"==a.type&&1==a.yAxis}),V=j.filter(function(a){return\"bar\"==a.type&&2==a.yAxis}),W=j.filter(function(a){return\"area\"==a.type&&1==a.yAxis}),X=j.filter(function(a){return\"area\"==a.type&&2==a.yAxis});if(!(j&&j.length&&j.filter(function(a){return a.values.length}).length))return a.utils.noData(b,N),b;N.selectAll(\".nv-noData\").remove();var Y=j.filter(function(a){return!a.disabled&&1==a.yAxis}).map(function(a){return a.values.map(function(a,b){return{x:k(a),y:l(a)}})}),Z=j.filter(function(a){return!a.disabled&&2==a.yAxis}).map(function(a){return a.values.map(function(a,b){return{x:k(a),y:l(a)}})});r.domain(d3.extent(d3.merge(Y.concat(Z)),function(a){return a.x})).range([0,O]);var $=N.selectAll(\"g.wrap.multiChart\").data([j]),_=$.enter().append(\"g\").attr(\"class\",\"wrap nvd3 multiChart\").append(\"g\");_.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),_.append(\"g\").attr(\"class\",\"nv-y1 nv-axis\"),_.append(\"g\").attr(\"class\",\"nv-y2 nv-axis\"),_.append(\"g\").attr(\"class\",\"stack1Wrap\"),_.append(\"g\").attr(\"class\",\"stack2Wrap\"),_.append(\"g\").attr(\"class\",\"bars1Wrap\"),_.append(\"g\").attr(\"class\",\"bars2Wrap\"),_.append(\"g\").attr(\"class\",\"scatters1Wrap\"),_.append(\"g\").attr(\"class\",\"scatters2Wrap\"),_.append(\"g\").attr(\"class\",\"lines1Wrap\"),_.append(\"g\").attr(\"class\",\"lines2Wrap\"),_.append(\"g\").attr(\"class\",\"legendWrap\"),_.append(\"g\").attr(\"class\",\"nv-interactive\");var aa=$.select(\"g\"),ba=j.map(function(a,b){return j[b].color||f(a,b)});if(i){var ca=F.align()?O/2:O,da=F.align()?ca:0;F.width(ca),F.color(ba),aa.select(\".legendWrap\").datum(j.map(function(a){return a.originalKey=void 0===a.originalKey?a.key:a.originalKey,a.key=a.originalKey+(1==a.yAxis?\"\":q),a})).call(F),F.height()>e.top&&(e.top=F.height(),P=a.utils.availableHeight(h,N,e)),aa.select(\".legendWrap\").attr(\"transform\",\"translate(\"+da+\",\"+-e.top+\")\")}else aa.select(\".legendWrap\").selectAll(\"*\").remove();u.width(O).height(P).interpolate(m).color(ba.filter(function(a,b){return!j[b].disabled&&1==j[b].yAxis&&\"line\"==j[b].type})),v.width(O).height(P).interpolate(m).color(ba.filter(function(a,b){return!j[b].disabled&&2==j[b].yAxis&&\"line\"==j[b].type})),w.width(O).height(P).color(ba.filter(function(a,b){return!j[b].disabled&&1==j[b].yAxis&&\"scatter\"==j[b].type})),x.width(O).height(P).color(ba.filter(function(a,b){return!j[b].disabled&&2==j[b].yAxis&&\"scatter\"==j[b].type})),y.width(O).height(P).color(ba.filter(function(a,b){return!j[b].disabled&&1==j[b].yAxis&&\"bar\"==j[b].type})),z.width(O).height(P).color(ba.filter(function(a,b){return!j[b].disabled&&2==j[b].yAxis&&\"bar\"==j[b].type})),A.width(O).height(P).interpolate(m).color(ba.filter(function(a,b){return!j[b].disabled&&1==j[b].yAxis&&\"area\"==j[b].type})),B.width(O).height(P).interpolate(m).color(ba.filter(function(a,b){return!j[b].disabled&&2==j[b].yAxis&&\"area\"==j[b].type})),aa.attr(\"transform\",\"translate(\"+e.left+\",\"+e.top+\")\");var ea=aa.select(\".lines1Wrap\").datum(Q.filter(function(a){return!a.disabled})),fa=aa.select(\".scatters1Wrap\").datum(S.filter(function(a){return!a.disabled})),ga=aa.select(\".bars1Wrap\").datum(U.filter(function(a){return!a.disabled})),ha=aa.select(\".stack1Wrap\").datum(W.filter(function(a){return!a.disabled})),ia=aa.select(\".lines2Wrap\").datum(R.filter(function(a){return!a.disabled})),ja=aa.select(\".scatters2Wrap\").datum(T.filter(function(a){return!a.disabled})),ka=aa.select(\".bars2Wrap\").datum(V.filter(function(a){return!a.disabled})),la=aa.select(\".stack2Wrap\").datum(X.filter(function(a){return!a.disabled})),ma=W.length?W.map(function(a){return a.values}).reduce(function(a,b){return a.map(function(a,c){return{x:a.x,y:a.y+b[c].y}})}).concat([{x:0,y:0}]):[],na=X.length?X.map(function(a){return a.values}).reduce(function(a,b){return a.map(function(a,c){return{x:a.x,y:a.y+b[c].y}})}).concat([{x:0,y:0}]):[];s.domain(c||d3.extent(d3.merge(Y).concat(ma),function(a){return a.y})).range([0,P]),t.domain(d||d3.extent(d3.merge(Z).concat(na),function(a){return a.y})).range([0,P]),u.yDomain(s.domain()),w.yDomain(s.domain()),y.yDomain(s.domain()),A.yDomain(s.domain()),v.yDomain(t.domain()),x.yDomain(t.domain()),z.yDomain(t.domain()),B.yDomain(t.domain()),W.length&&d3.transition(ha).call(A),X.length&&d3.transition(la).call(B),U.length&&d3.transition(ga).call(y),V.length&&d3.transition(ka).call(z),Q.length&&d3.transition(ea).call(u),R.length&&d3.transition(ia).call(v),S.length&&d3.transition(fa).call(w),T.length&&d3.transition(ja).call(x),C._ticks(a.utils.calcTicksX(O/100,j)).tickSize(-P,0),aa.select(\".nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+P+\")\"),d3.transition(aa.select(\".nv-x.nv-axis\")).call(C),D._ticks(a.utils.calcTicksY(P/36,j)).tickSize(-O,0),d3.transition(aa.select(\".nv-y1.nv-axis\")).call(D),E._ticks(a.utils.calcTicksY(P/36,j)).tickSize(-O,0),d3.transition(aa.select(\".nv-y2.nv-axis\")).call(E),aa.select(\".nv-y1.nv-axis\").classed(\"nv-disabled\",Y.length?!1:!0).attr(\"transform\",\"translate(\"+r.range()[0]+\",0)\"),aa.select(\".nv-y2.nv-axis\").classed(\"nv-disabled\",Z.length?!1:!0).attr(\"transform\",\"translate(\"+r.range()[1]+\",0)\"),F.dispatch.on(\"stateChange\",function(a){b.update()}),p&&(o.width(O).height(P).margin({left:e.left,top:e.top}).svgContainer(N).xScale(r),$.select(\".nv-interactive\").call(o)),p?(o.dispatch.on(\"elementMousemove\",function(c){L();var d,e,g,h=[];j.filter(function(a,b){return a.seriesIndex=b,!a.disabled}).forEach(function(i,j){var k=r.domain(),l=i.values.filter(function(a,c){return b.x()(a,c)>=k[0]&&b.x()(a,c)<=k[1]});e=a.interactiveBisect(l,c.pointXValue,b.x());var m=l[e],n=b.y()(m,e);null!==n&&M(j,e,!0),void 0!==m&&(void 0===d&&(d=m),void 0===g&&(g=r(b.x()(m,e))),h.push({key:i.key,value:n,color:f(i,i.seriesIndex),data:m,yAxis:2==i.yAxis?E:D}))});var i=function(a,b){var c=h[b].yAxis;return null==a?\"N/A\":c.tickFormat()(a)};o.tooltip.headerFormatter(function(a,b){return C.tickFormat()(a,b)}).valueFormatter(o.tooltip.valueFormatter()||i).data({value:b.x()(d,e),index:e,series:h})(),o.renderGuideLine(g)}),o.dispatch.on(\"elementMouseout\",function(a){L()})):(u.dispatch.on(\"elementMouseover.tooltip\",n),v.dispatch.on(\"elementMouseover.tooltip\",n),u.dispatch.on(\"elementMouseout.tooltip\",function(a){G.hidden(!0)}),v.dispatch.on(\"elementMouseout.tooltip\",function(a){G.hidden(!0)}),w.dispatch.on(\"elementMouseover.tooltip\",H),x.dispatch.on(\"elementMouseover.tooltip\",H),w.dispatch.on(\"elementMouseout.tooltip\",function(a){G.hidden(!0)}),x.dispatch.on(\"elementMouseout.tooltip\",function(a){G.hidden(!0)}),A.dispatch.on(\"elementMouseover.tooltip\",J),B.dispatch.on(\"elementMouseover.tooltip\",J),A.dispatch.on(\"elementMouseout.tooltip\",function(a){G.hidden(!0)}),B.dispatch.on(\"elementMouseout.tooltip\",function(a){G.hidden(!0)}),y.dispatch.on(\"elementMouseover.tooltip\",K),z.dispatch.on(\"elementMouseover.tooltip\",K),y.dispatch.on(\"elementMouseout.tooltip\",function(a){G.hidden(!0)}),z.dispatch.on(\"elementMouseout.tooltip\",function(a){G.hidden(!0)}),y.dispatch.on(\"elementMousemove.tooltip\",function(a){G()}),z.dispatch.on(\"elementMousemove.tooltip\",function(a){G()}))}),b}var c,d,e={top:30,right:20,bottom:50,left:60},f=a.utils.defaultColor(),g=null,h=null,i=!0,j=null,k=function(a){return a.x},l=function(a){return a.y},m=\"linear\",n=!0,o=a.interactiveGuideline(),p=!1,q=\" (right axis)\",r=d3.scale.linear(),s=d3.scale.linear(),t=d3.scale.linear(),u=a.models.line().yScale(s),v=a.models.line().yScale(t),w=a.models.scatter().yScale(s),x=a.models.scatter().yScale(t),y=a.models.multiBar().stacked(!1).yScale(s),z=a.models.multiBar().stacked(!1).yScale(t),A=a.models.stackedArea().yScale(s),B=a.models.stackedArea().yScale(t),C=a.models.axis().scale(r).orient(\"bottom\").tickPadding(5),D=a.models.axis().scale(s).orient(\"left\"),E=a.models.axis().scale(t).orient(\"right\"),F=a.models.legend().height(30),G=a.models.tooltip(),H=d3.dispatch(),I=[u,v,w,x,y,z,A,B];return b.dispatch=H,b.legend=F,b.lines1=u,b.lines2=v,b.scatters1=w,b.scatters2=x,b.bars1=y,b.bars2=z,b.stack1=A,b.stack2=B,b.xAxis=C,b.yAxis1=D,b.yAxis2=E,b.tooltip=G,b.interactiveLayer=o,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return g},set:function(a){g=a}},height:{get:function(){return h},set:function(a){h=a}},showLegend:{get:function(){return i},set:function(a){i=a}},yDomain1:{get:function(){return c},set:function(a){c=a}},yDomain2:{get:function(){return d},set:function(a){d=a}},noData:{get:function(){return j},set:function(a){j=a}},interpolate:{get:function(){return m},set:function(a){m=a}},legendRightAxisHint:{get:function(){return q},set:function(a){q=a}},margin:{get:function(){return e},set:function(a){e.top=void 0!==a.top?a.top:e.top,e.right=void 0!==a.right?a.right:e.right,e.bottom=void 0!==a.bottom?a.bottom:e.bottom,e.left=void 0!==a.left?a.left:e.left}},color:{get:function(){return f},set:function(b){f=a.utils.getColor(b)}},x:{get:function(){return k},set:function(a){k=a,u.x(a),v.x(a),w.x(a),x.x(a),y.x(a),z.x(a),A.x(a),B.x(a)}},y:{get:function(){return l},set:function(a){l=a,u.y(a),v.y(a),w.y(a),x.y(a),A.y(a),B.y(a),y.y(a),z.y(a)}},useVoronoi:{get:function(){return n},set:function(a){n=a,u.useVoronoi(a),v.useVoronoi(a),A.useVoronoi(a),B.useVoronoi(a)}},useInteractiveGuideline:{get:function(){return p},set:function(a){p=a,p&&(u.interactive(!1),u.useVoronoi(!1),v.interactive(!1),v.useVoronoi(!1),A.interactive(!1),A.useVoronoi(!1),B.interactive(!1),B.useVoronoi(!1),w.interactive(!1),x.interactive(!1))}}}),a.utils.initOptions(b),b},a.models.ohlcBar=function(){\"use strict\";function b(y){return y.each(function(b){k=d3.select(this);var y=a.utils.availableWidth(h,k,g),A=a.utils.availableHeight(i,k,g);a.utils.initSVG(k);var B=y/b[0].values.length*.9;l.domain(c||d3.extent(b[0].values.map(n).concat(t))),v?l.range(e||[.5*y/b[0].values.length,y*(b[0].values.length-.5)/b[0].values.length]):l.range(e||[5+B/2,y-B/2-5]),m.domain(d||[d3.min(b[0].values.map(s).concat(u)),d3.max(b[0].values.map(r).concat(u))]).range(f||[A,0]),l.domain()[0]===l.domain()[1]&&(l.domain()[0]?l.domain([l.domain()[0]-.01*l.domain()[0],l.domain()[1]+.01*l.domain()[1]]):l.domain([-1,1])),m.domain()[0]===m.domain()[1]&&(m.domain()[0]?m.domain([m.domain()[0]+.01*m.domain()[0],m.domain()[1]-.01*m.domain()[1]]):m.domain([-1,1]));var C=d3.select(this).selectAll(\"g.nv-wrap.nv-ohlcBar\").data([b[0].values]),D=C.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-ohlcBar\"),E=D.append(\"defs\"),F=D.append(\"g\"),G=C.select(\"g\");F.append(\"g\").attr(\"class\",\"nv-ticks\"),C.attr(\"transform\",\"translate(\"+g.left+\",\"+g.top+\")\"),k.on(\"click\",function(a,b){z.chartClick({data:a,index:b,pos:d3.event,id:j})}),E.append(\"clipPath\").attr(\"id\",\"nv-chart-clip-path-\"+j).append(\"rect\"),C.select(\"#nv-chart-clip-path-\"+j+\" rect\").attr(\"width\",y).attr(\"height\",A),G.attr(\"clip-path\",w?\"url(#nv-chart-clip-path-\"+j+\")\":\"\");var H=C.select(\".nv-ticks\").selectAll(\".nv-tick\").data(function(a){return a});H.exit().remove(),H.enter().append(\"path\").attr(\"class\",function(a,b,c){return(p(a,b)>q(a,b)?\"nv-tick negative\":\"nv-tick positive\")+\" nv-tick-\"+c+\"-\"+b}).attr(\"d\",function(a,b){return\"m0,0l0,\"+(m(p(a,b))-m(r(a,b)))+\"l\"+-B/2+\",0l\"+B/2+\",0l0,\"+(m(s(a,b))-m(p(a,b)))+\"l0,\"+(m(q(a,b))-m(s(a,b)))+\"l\"+B/2+\",0l\"+-B/2+\",0z\"}).attr(\"transform\",function(a,b){return\"translate(\"+l(n(a,b))+\",\"+m(r(a,b))+\")\"}).attr(\"fill\",function(a,b){return x[0]}).attr(\"stroke\",function(a,b){return x[0]}).attr(\"x\",0).attr(\"y\",function(a,b){return m(Math.max(0,o(a,b)))}).attr(\"height\",function(a,b){return Math.abs(m(o(a,b))-m(0))}),H.attr(\"class\",function(a,b,c){return(p(a,b)>q(a,b)?\"nv-tick negative\":\"nv-tick positive\")+\" nv-tick-\"+c+\"-\"+b}),d3.transition(H).attr(\"transform\",function(a,b){return\"translate(\"+l(n(a,b))+\",\"+m(r(a,b))+\")\"}).attr(\"d\",function(a,c){var d=y/b[0].values.length*.9;return\"m0,0l0,\"+(m(p(a,c))-m(r(a,c)))+\"l\"+-d/2+\",0l\"+d/2+\",0l0,\"+(m(s(a,c))-m(p(a,c)))+\"l0,\"+(m(q(a,c))-m(s(a,c)))+\"l\"+d/2+\",0l\"+-d/2+\",0z\"})}),b}var c,d,e,f,g={top:0,right:0,bottom:0,left:0},h=null,i=null,j=Math.floor(1e4*Math.random()),k=null,l=d3.scale.linear(),m=d3.scale.linear(),n=function(a){return a.x},o=function(a){return a.y},p=function(a){return a.open},q=function(a){return a.close},r=function(a){return a.high},s=function(a){return a.low},t=[],u=[],v=!1,w=!0,x=a.utils.defaultColor(),y=!1,z=d3.dispatch(\"stateChange\",\"changeState\",\"renderEnd\",\"chartClick\",\"elementClick\",\"elementDblClick\",\"elementMouseover\",\"elementMouseout\",\"elementMousemove\");return b.highlightPoint=function(a,c){b.clearHighlights(),k.select(\".nv-ohlcBar .nv-tick-0-\"+a).classed(\"hover\",c)},b.clearHighlights=function(){k.select(\".nv-ohlcBar .nv-tick.hover\").classed(\"hover\",!1)},b.dispatch=z,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return h},set:function(a){h=a}},height:{get:function(){return i},set:function(a){i=a}},xScale:{get:function(){return l},set:function(a){l=a}},yScale:{get:function(){return m},set:function(a){m=a}},xDomain:{get:function(){return c},set:function(a){c=a}},yDomain:{get:function(){return d},set:function(a){d=a}},xRange:{get:function(){return e},set:function(a){e=a}},yRange:{get:function(){return f},set:function(a){f=a}},forceX:{get:function(){return t},set:function(a){t=a}},forceY:{get:function(){return u},set:function(a){u=a}},padData:{get:function(){return v},set:function(a){v=a}},clipEdge:{get:function(){return w},set:function(a){w=a}},id:{get:function(){return j},set:function(a){j=a}},interactive:{get:function(){return y},set:function(a){y=a}},x:{get:function(){return n},set:function(a){n=a}},y:{get:function(){return o},set:function(a){o=a}},open:{get:function(){return p()},set:function(a){p=a}},close:{get:function(){return q()},set:function(a){q=a}},high:{get:function(){return r},set:function(a){r=a}},low:{get:function(){return s},set:function(a){s=a}},margin:{get:function(){return g},set:function(a){g.top=void 0!=a.top?a.top:g.top,g.right=void 0!=a.right?a.right:g.right,g.bottom=void 0!=a.bottom?a.bottom:g.bottom,g.left=void 0!=a.left?a.left:g.left}},color:{get:function(){return x},set:function(b){x=a.utils.getColor(b)}}}),a.utils.initOptions(b),b},a.models.parallelCoordinates=function(){\"use strict\";function b(B){return A.reset(),B.each(function(b){function A(a){return x(o.map(function(b){if(isNaN(a.values[b.key])||isNaN(parseFloat(a.values[b.key]))||O){var c=l[b.key].domain(),d=l[b.key].range(),e=c[0]-(c[1]-c[0])/9;if(v.indexOf(b.key)<0){var f=d3.scale.linear().domain([e,c[1]]).range([j-12,d[1]]);l[b.key].brush.y(f),v.push(b.key)}if(isNaN(a.values[b.key])||isNaN(parseFloat(a.values[b.key])))return[k(b.key),l[b.key](e)]}return void 0!==U&&(v.length>0||O?(U.style(\"display\",\"inline\"),V.style(\"display\",\"inline\")):(U.style(\"display\",\"none\"),V.style(\"display\",\"none\"))),[k(b.key),l[b.key](a.values[b.key])]}))}function B(a){s.forEach(function(b){var c=l[b.dimension].brush.y().domain();b.hasOnlyNaN&&(b.extent[1]=(l[b.dimension].domain()[1]-c[0])*(b.extent[1]-b.extent[0])/(N[b.dimension]-b.extent[0])+c[0]),b.hasNaN&&(b.extent[0]=c[0]),a&&l[b.dimension].brush.extent(b.extent)}),e.select(\".nv-brushBackground\").each(function(a){d3.select(this).call(l[a.key].brush)}).selectAll(\"rect\").attr(\"x\",-8).attr(\"width\",16),F()}function C(){q===!1&&(q=!0,B(!0))}function D(){$=p.filter(function(a){return!l[a].brush.empty()}),_=$.map(function(a){return l[a].brush.extent()}),s=[],$.forEach(function(a,b){s[b]={dimension:a,extent:_[b],hasNaN:!1,hasOnlyNaN:!1}}),t=[],c.style(\"display\",function(a){var b=$.every(function(b,c){return(isNaN(a.values[b])||isNaN(parseFloat(a.values[b])))&&_[c][0]==l[b].brush.y().domain()[0]?!0:_[c][0]<=a.values[b]&&a.values[b]<=_[c][1]&&!isNaN(parseFloat(a.values[b]))});return b&&t.push(a),b?null:\"none\"}),F(),z.brush({filters:s,active:t})}function E(){var a=$.length>0?!0:!1;s.forEach(function(a){a.extent[0]===l[a.dimension].brush.y().domain()[0]&&v.indexOf(a.dimension)>=0&&(a.hasNaN=!0),a.extent[1]<l[a.dimension].domain()[0]&&(a.hasOnlyNaN=!0)}),z.brushEnd(t,a)}function F(){e.select(\".nv-axis\").each(function(a,b){var c=s.filter(function(b){return b.dimension==a.key});P[a.key]=l[a.key].domain(),0!=c.length&&q&&(P[a.key]=[],c[0].extent[1]>l[a.key].domain()[0]&&(P[a.key]=[c[0].extent[1]]),c[0].extent[0]>=l[a.key].domain()[0]&&P[a.key].push(c[0].extent[0])),d3.select(this).call(y.scale(l[a.key]).tickFormat(a.format).tickValues(P[a.key]))})}function G(a){u[a.key]=this.parentNode.__origin__=k(a.key),d.attr(\"visibility\",\"hidden\")}function H(a){u[a.key]=Math.min(i,Math.max(0,this.parentNode.__origin__+=d3.event.x)),c.attr(\"d\",A),o.sort(function(a,b){return J(a.key)-J(b.key)}),o.forEach(function(a,b){return a.currentPosition=b}),k.domain(o.map(function(a){return a.key})),e.attr(\"transform\",function(a){return\"translate(\"+J(a.key)+\")\"})}function I(a,b){delete this.parentNode.__origin__,delete u[a.key],d3.select(this.parentNode).attr(\"transform\",\"translate(\"+k(a.key)+\")\"),c.attr(\"d\",A),d.attr(\"d\",A).attr(\"visibility\",null),z.dimensionsOrder(o)}function J(a){var b=u[a];return null==b?k(a):b}var K=d3.select(this);if(i=a.utils.availableWidth(g,K,f),j=a.utils.availableHeight(h,K,f),a.utils.initSVG(K),void 0===b[0].values){var L=[];b.forEach(function(a){var b={},c=Object.keys(a);c.forEach(function(c){\"name\"!==c&&(b[c]=a[c])}),L.push({key:a.name,values:b})}),b=L}var M=b.map(function(a){return a.values});0===t.length&&(t=b),p=n.sort(function(a,b){return a.currentPosition-b.currentPosition}).map(function(a){return a.key}),o=n.filter(function(a){return!a.disabled}),k.rangePoints([0,i],1).domain(o.map(function(a){return a.key}));var N={},O=!1,P=[];p.forEach(function(a){var b=d3.extent(M,function(b){return+b[a]}),c=b[0],d=b[1],e=!1;(isNaN(c)||isNaN(d))&&(e=!0,c=0,d=0),c===d&&(c-=1,d+=1);var f=s.filter(function(b){return b.dimension==a});0!==f.length&&(e?(c=l[a].domain()[0],d=l[a].domain()[1]):!f[0].hasOnlyNaN&&q?(c=c>f[0].extent[0]?f[0].extent[0]:c,d=d<f[0].extent[1]?f[0].extent[1]:d):f[0].hasNaN&&(d=d<f[0].extent[1]?f[0].extent[1]:d,N[a]=l[a].domain()[1],O=!0)),l[a]=d3.scale.linear().domain([c,d]).range([.9*(j-12),0]),v=[],l[a].brush=d3.svg.brush().y(l[a]).on(\"brushstart\",C).on(\"brush\",D).on(\"brushend\",E)});var Q=K.selectAll(\"g.nv-wrap.nv-parallelCoordinates\").data([b]),R=Q.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-parallelCoordinates\"),S=R.append(\"g\"),T=Q.select(\"g\");S.append(\"g\").attr(\"class\",\"nv-parallelCoordinates background\"),S.append(\"g\").attr(\"class\",\"nv-parallelCoordinates foreground\"),S.append(\"g\").attr(\"class\",\"nv-parallelCoordinates missingValuesline\"),Q.attr(\"transform\",\"translate(\"+f.left+\",\"+f.top+\")\"),x.interpolate(\"cardinal\").tension(w),y.orient(\"left\");var U,V,W=d3.behavior.drag().on(\"dragstart\",G).on(\"drag\",H).on(\"dragend\",I),X=k.range()[1]-k.range()[0];if(!isNaN(X)){var Y=[0+X/2,j-12,i-X/2,j-12];U=Q.select(\".missingValuesline\").selectAll(\"line\").data([Y]),U.enter().append(\"line\"),U.exit().remove(),U.attr(\"x1\",function(a){return a[0]}).attr(\"y1\",function(a){return a[1]}).attr(\"x2\",function(a){return a[2]}).attr(\"y2\",function(a){return a[3]}),V=Q.select(\".missingValuesline\").selectAll(\"text\").data([m]),V.append(\"text\").data([m]),V.enter().append(\"text\"),V.exit().remove(),V.attr(\"y\",j).attr(\"x\",i-92-X/2).text(function(a){return a})}d=Q.select(\".background\").selectAll(\"path\").data(b),d.enter().append(\"path\"),d.exit().remove(),d.attr(\"d\",A),c=Q.select(\".foreground\").selectAll(\"path\").data(b),c.enter().append(\"path\"),c.exit().remove(),c.attr(\"d\",A).style(\"stroke-width\",function(a,b){return isNaN(a.strokeWidth)&&(a.strokeWidth=1),a.strokeWidth}).attr(\"stroke\",function(a,b){return a.color||r(a,b)}),c.on(\"mouseover\",function(a,b){d3.select(this).classed(\"hover\",!0).style(\"stroke-width\",a.strokeWidth+2+\"px\").style(\"stroke-opacity\",1),z.elementMouseover({label:a.name,color:a.color||r(a,b),values:a.values,dimensions:o})}),c.on(\"mouseout\",function(a,b){d3.select(this).classed(\"hover\",!1).style(\"stroke-width\",a.strokeWidth+\"px\").style(\"stroke-opacity\",.7),z.elementMouseout({label:a.name,index:b})}),c.on(\"mousemove\",function(a,b){z.elementMousemove()}),c.on(\"click\",function(a){z.elementClick({id:a.id})}),e=T.selectAll(\".dimension\").data(o);var Z=e.enter().append(\"g\").attr(\"class\",\"nv-parallelCoordinates dimension\");e.attr(\"transform\",function(a){return\"translate(\"+k(a.key)+\",0)\"}),Z.append(\"g\").attr(\"class\",\"nv-axis\"),Z.append(\"text\").attr(\"class\",\"nv-label\").style(\"cursor\",\"move\").attr(\"dy\",\"-1em\").attr(\"text-anchor\",\"middle\").on(\"mouseover\",function(a,b){z.elementMouseover({label:a.tooltip||a.key,color:a.color})}).on(\"mouseout\",function(a,b){z.elementMouseout({label:a.tooltip})}).on(\"mousemove\",function(a,b){z.elementMousemove()}).call(W),Z.append(\"g\").attr(\"class\",\"nv-brushBackground\"),e.exit().remove(),e.select(\".nv-label\").text(function(a){return a.key}),B(q);var $=p.filter(function(a){return!l[a].brush.empty()}),_=$.map(function(a){return l[a].brush.extent()}),aa=t.slice(0);t=[],c.style(\"display\",function(a){var b=$.every(function(b,c){return(isNaN(a.values[b])||isNaN(parseFloat(a.values[b])))&&_[c][0]==l[b].brush.y().domain()[0]?!0:_[c][0]<=a.values[b]&&a.values[b]<=_[c][1]&&!isNaN(parseFloat(a.values[b]))});return b&&t.push(a),b?null:\"none\"}),(s.length>0||!a.utils.arrayEquals(t,aa))&&z.activeChanged(t)}),b}var c,d,e,f={top:30,right:0,bottom:10,left:0},g=null,h=null,i=null,j=null,k=d3.scale.ordinal(),l={},m=\"undefined values\",n=[],o=[],p=[],q=!0,r=a.utils.defaultColor(),s=[],t=[],u=[],v=[],w=1,x=d3.svg.line(),y=d3.svg.axis(),z=d3.dispatch(\"brushstart\",\"brush\",\"brushEnd\",\"dimensionsOrder\",\"stateChange\",\"elementClick\",\"elementMouseover\",\"elementMouseout\",\"elementMousemove\",\"renderEnd\",\"activeChanged\"),A=a.utils.renderWatch(z);return b.dispatch=z,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return g},set:function(a){g=a}},height:{get:function(){return h},set:function(a){h=a}},dimensionData:{get:function(){return n},set:function(a){n=a}},displayBrush:{get:function(){return q},set:function(a){q=a}},filters:{get:function(){return s},set:function(a){s=a}},active:{get:function(){return t},set:function(a){t=a}},lineTension:{get:function(){return w},set:function(a){w=a}},undefinedValuesLabel:{get:function(){return m},set:function(a){m=a}},dimensions:{get:function(){return n.map(function(a){return a.key})},set:function(b){a.deprecated(\"dimensions\",\"use dimensionData instead\"),0===n.length?b.forEach(function(a){n.push({key:a})}):b.forEach(function(a,b){n[b].key=a})}},dimensionNames:{get:function(){return n.map(function(a){return a.key})},set:function(b){a.deprecated(\"dimensionNames\",\"use dimensionData instead\"),p=[],0===n.length?b.forEach(function(a){n.push({key:a})}):b.forEach(function(a,b){n[b].key=a})}},dimensionFormats:{get:function(){return n.map(function(a){return a.format})},set:function(b){a.deprecated(\"dimensionFormats\",\"use dimensionData instead\"),0===n.length?b.forEach(function(a){n.push({format:a})}):b.forEach(function(a,b){n[b].format=a})}},margin:{get:function(){return f},set:function(a){f.top=void 0!==a.top?a.top:f.top,f.right=void 0!==a.right?a.right:f.right,f.bottom=void 0!==a.bottom?a.bottom:f.bottom,f.left=void 0!==a.left?a.left:f.left}},color:{get:function(){return r},set:function(b){r=a.utils.getColor(b)}}}),a.utils.initOptions(b),b},a.models.parallelCoordinatesChart=function(){\"use strict\";function b(e){return r.reset(),r.models(c),e.each(function(e){var j=d3.select(this);a.utils.initSVG(j);var o=a.utils.availableWidth(g,j,f),p=a.utils.availableHeight(h,j,f);if(b.update=function(){j.call(b)},b.container=this,k.setter(t(l),b.update).getter(s(l)).update(),k.disabled=l.map(function(a){return!!a.disabled}),l=l.map(function(a){return a.disabled=!!a.disabled,a}),l.forEach(function(a,b){a.originalPosition=isNaN(a.originalPosition)?b:a.originalPosition,a.currentPosition=isNaN(a.currentPosition)?b:a.currentPosition}),!n){var r;n={};for(r in k)k[r]instanceof Array?n[r]=k[r].slice(0):n[r]=k[r]}if(!e||!e.length)return a.utils.noData(b,j),b;j.selectAll(\".nv-noData\").remove();var u=j.selectAll(\"g.nv-wrap.nv-parallelCoordinatesChart\").data([e]),v=u.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-parallelCoordinatesChart\").append(\"g\"),w=u.select(\"g\");v.append(\"g\").attr(\"class\",\"nv-parallelCoordinatesWrap\"),v.append(\"g\").attr(\"class\",\"nv-legendWrap\"),w.select(\"rect\").attr(\"width\",o).attr(\"height\",p>0?p:0),i?(d.width(o).color(function(a){return\"rgb(188,190,192)\"}),w.select(\".nv-legendWrap\").datum(l.sort(function(a,b){return a.originalPosition-b.originalPosition})).call(d),d.height()>f.top&&(f.top=d.height(),p=a.utils.availableHeight(h,j,f)),u.select(\".nv-legendWrap\").attr(\"transform\",\"translate( 0 ,\"+-f.top+\")\")):w.select(\".nv-legendWrap\").selectAll(\"*\").remove(),u.attr(\"transform\",\"translate(\"+f.left+\",\"+f.top+\")\"),c.width(o).height(p).dimensionData(l).displayBrush(m);var x=w.select(\".nv-parallelCoordinatesWrap \").datum(e);x.transition().call(c),c.dispatch.on(\"brushEnd\",function(a,b){b?(m=!0,q.brushEnd(a)):m=!1}),d.dispatch.on(\"stateChange\",function(a){for(var c in a)k[c]=a[c];q.stateChange(k),b.update()}),c.dispatch.on(\"dimensionsOrder\",function(a){l.sort(function(a,b){return a.currentPosition-b.currentPosition});var b=!1;l.forEach(function(a,c){a.currentPosition=c,a.currentPosition!==a.originalPosition&&(b=!0)}),q.dimensionsOrder(l,b)}),q.on(\"changeState\",function(a){\"undefined\"!=typeof a.disabled&&(l.forEach(function(b,c){b.disabled=a.disabled[c]}),k.disabled=a.disabled),b.update()})}),r.renderEnd(\"parraleleCoordinateChart immediate\"),b}var c=a.models.parallelCoordinates(),d=a.models.legend(),e=a.models.tooltip(),f=(a.models.tooltip(),{top:0,right:0,bottom:0,left:0}),g=null,h=null,i=!0,j=a.utils.defaultColor(),k=a.utils.state(),l=[],m=!0,n=null,o=null,p=\"undefined\",q=d3.dispatch(\"dimensionsOrder\",\"brushEnd\",\"stateChange\",\"changeState\",\"renderEnd\"),r=a.utils.renderWatch(q),s=function(a){return function(){return{active:a.map(function(a){return!a.disabled})}}},t=function(a){return function(b){void 0!==b.active&&a.forEach(function(a,c){a.disabled=!b.active[c]})}};return e.contentGenerator(function(a){var b='<table><thead><tr><td class=\"legend-color-guide\"><div style=\"background-color:'+a.color+'\"></div></td><td><strong>'+a.key+\"</strong></td></tr></thead>\";return 0!==a.series.length&&(b+='<tbody><tr><td height =\"10px\"></td></tr>',a.series.forEach(function(a){b=b+'<tr><td class=\"legend-color-guide\"><div style=\"background-color:'+a.color+'\"></div></td><td class=\"key\">'+a.key+'</td><td class=\"value\">'+a.value+\"</td></tr>\"}),b+=\"</tbody>\"),b+=\"</table>\"}),c.dispatch.on(\"elementMouseover.tooltip\",function(a){var b={key:a.label,color:a.color,series:[]};a.values&&(Object.keys(a.values).forEach(function(c){var d=a.dimensions.filter(function(a){return a.key===c})[0];if(d){var e;e=isNaN(a.values[c])||isNaN(parseFloat(a.values[c]))?p:d.format(a.values[c]),b.series.push({idx:d.currentPosition,key:c,value:e,color:d.color})}}),b.series.sort(function(a,b){return a.idx-b.idx})),e.data(b).hidden(!1)}),c.dispatch.on(\"elementMouseout.tooltip\",function(a){e.hidden(!0)}),c.dispatch.on(\"elementMousemove.tooltip\",function(){e()}),b.dispatch=q,b.parallelCoordinates=c,b.legend=d,b.tooltip=e,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return g},set:function(a){g=a}},height:{get:function(){return h},set:function(a){h=a}},showLegend:{get:function(){return i},set:function(a){i=a}},defaultState:{get:function(){return n},set:function(a){n=a}},dimensionData:{get:function(){return l},set:function(a){l=a}},displayBrush:{get:function(){return m},set:function(a){m=a}},noData:{get:function(){return o},set:function(a){o=a}},nanValue:{get:function(){return p},set:function(a){p=a}},margin:{get:function(){return f},set:function(a){f.top=void 0!==a.top?a.top:f.top,f.right=void 0!==a.right?a.right:f.right,f.bottom=void 0!==a.bottom?a.bottom:f.bottom,f.left=void 0!==a.left?a.left:f.left}},color:{get:function(){return j},set:function(b){j=a.utils.getColor(b),d.color(j),c.color(j)}}}),a.utils.inheritOptions(b,c),a.utils.initOptions(b),b},a.models.pie=function(){\"use strict\";function b(F){return E.reset(),F.each(function(b){function F(a,b){a.endAngle=isNaN(a.endAngle)?0:a.endAngle,a.startAngle=isNaN(a.startAngle)?0:a.startAngle,p||(a.innerRadius=0);var c=d3.interpolate(this._current,a);return this._current=c(0),function(a){return C[b](c(a))}}var G=d-c.left-c.right,H=e-c.top-c.bottom,I=Math.min(G,H)/2,J=[],K=[];if(i=d3.select(this),0===A.length)for(var L=I-I/5,M=y*I,N=0;N<b[0].length;N++)J.push(L),K.push(M);else r?(J=A.map(function(a){return(a.outer-a.outer/5)*I}),K=A.map(function(a){return(a.inner-a.inner/5)*I}),y=d3.min(A.map(function(a){return a.inner-a.inner/5}))):(J=A.map(function(a){return a.outer*I}),K=A.map(function(a){return a.inner*I}),y=d3.min(A.map(function(a){return a.inner})));a.utils.initSVG(i);var O=i.selectAll(\".nv-wrap.nv-pie\").data(b),P=O.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-pie nv-chart-\"+h),Q=P.append(\"g\"),R=O.select(\"g\"),S=Q.append(\"g\").attr(\"class\",\"nv-pie\");Q.append(\"g\").attr(\"class\",\"nv-pieLabels\"),O.attr(\"transform\",\"translate(\"+c.left+\",\"+c.top+\")\"),R.select(\".nv-pie\").attr(\"transform\",\"translate(\"+G/2+\",\"+H/2+\")\"),R.select(\".nv-pieLabels\").attr(\"transform\",\"translate(\"+G/2+\",\"+H/2+\")\"),i.on(\"click\",function(a,b){B.chartClick({data:a,index:b,pos:d3.event,id:h})}),C=[],D=[];for(var N=0;N<b[0].length;N++){var T=d3.svg.arc().outerRadius(J[N]),U=d3.svg.arc().outerRadius(J[N]+5);u!==!1&&(T.startAngle(u),U.startAngle(u)),w!==!1&&(T.endAngle(w),U.endAngle(w)),p&&(T.innerRadius(K[N]),U.innerRadius(K[N])),T.cornerRadius&&x&&(T.cornerRadius(x),U.cornerRadius(x)),C.push(T),D.push(U)}var V=d3.layout.pie().sort(null).value(function(a){return a.disabled?0:g(a)});V.padAngle&&v&&V.padAngle(v),p&&q&&(S.append(\"text\").attr(\"class\",\"nv-pie-title\"),O.select(\".nv-pie-title\").style(\"text-anchor\",\"middle\").text(function(a){return q}).style(\"font-size\",Math.min(G,H)*y*2/(q.length+2)+\"px\").attr(\"dy\",\"0.35em\").attr(\"transform\",function(a,b){return\"translate(0, \"+s+\")\"}));var W=O.select(\".nv-pie\").selectAll(\".nv-slice\").data(V),X=O.select(\".nv-pieLabels\").selectAll(\".nv-label\").data(V);W.exit().remove(),X.exit().remove();var Y=W.enter().append(\"g\");Y.attr(\"class\",\"nv-slice\"),Y.on(\"mouseover\",function(a,b){d3.select(this).classed(\"hover\",!0),r&&d3.select(this).select(\"path\").transition().duration(70).attr(\"d\",D[b]),B.elementMouseover({data:a.data,index:b,color:d3.select(this).style(\"fill\"),percent:(a.endAngle-a.startAngle)/(2*Math.PI)})}),Y.on(\"mouseout\",function(a,b){d3.select(this).classed(\"hover\",!1),r&&d3.select(this).select(\"path\").transition().duration(50).attr(\"d\",C[b]),B.elementMouseout({data:a.data,index:b})}),Y.on(\"mousemove\",function(a,b){B.elementMousemove({data:a.data,index:b})}),Y.on(\"click\",function(a,b){var c=this;B.elementClick({data:a.data,index:b,color:d3.select(this).style(\"fill\"),event:d3.event,element:c})}),Y.on(\"dblclick\",function(a,b){B.elementDblClick({data:a.data,index:b,color:d3.select(this).style(\"fill\")})}),W.attr(\"fill\",function(a,b){return j(a.data,b)}),W.attr(\"stroke\",function(a,b){return j(a.data,b)});Y.append(\"path\").each(function(a){this._current=a});if(W.select(\"path\").transition().duration(z).attr(\"d\",function(a,b){return C[b](a)}).attrTween(\"d\",F),l){for(var Z=[],N=0;N<b[0].length;N++)Z.push(C[N]),m?p&&(Z[N]=d3.svg.arc().outerRadius(C[N].outerRadius()),u!==!1&&Z[N].startAngle(u),w!==!1&&Z[N].endAngle(w)):p||Z[N].innerRadius(0);X.enter().append(\"g\").classed(\"nv-label\",!0).each(function(a,b){var c=d3.select(this);c.attr(\"transform\",function(a,b){if(t){a.outerRadius=J[b]+10,a.innerRadius=J[b]+15;var c=(a.startAngle+a.endAngle)/2*(180/Math.PI);return(a.startAngle+a.endAngle)/2<Math.PI?c-=90:c+=90,\"translate(\"+Z[b].centroid(a)+\") rotate(\"+c+\")\"}return a.outerRadius=I+10,a.innerRadius=I+15,\"translate(\"+Z[b].centroid(a)+\")\"}),c.append(\"rect\").style(\"stroke\",\"#fff\").style(\"fill\",\"#fff\").attr(\"rx\",3).attr(\"ry\",3),c.append(\"text\").style(\"text-anchor\",t?(a.startAngle+a.endAngle)/2<Math.PI?\"start\":\"end\":\"middle\").style(\"fill\",\"#000\")});var $={},_=14,aa=140,ba=function(a){return Math.floor(a[0]/aa)*aa+\",\"+Math.floor(a[1]/_)*_},ca=function(a){return(a.endAngle-a.startAngle)/(2*Math.PI)};X.watchTransition(E,\"pie labels\").attr(\"transform\",function(a,b){if(t){a.outerRadius=J[b]+10,a.innerRadius=J[b]+15;var c=(a.startAngle+a.endAngle)/2*(180/Math.PI);return(a.startAngle+a.endAngle)/2<Math.PI?c-=90:c+=90,\"translate(\"+Z[b].centroid(a)+\") rotate(\"+c+\")\"}a.outerRadius=I+10,a.innerRadius=I+15;var d=Z[b].centroid(a),e=ca(a);if(a.value&&e>=o){var f=ba(d);$[f]&&(d[1]-=_),$[ba(d)]=!0}return\"translate(\"+d+\")\"}),X.select(\".nv-label text\").style(\"text-anchor\",function(a,b){return t?(a.startAngle+a.endAngle)/2<Math.PI?\"start\":\"end\":\"middle\"}).text(function(a,b){var c=ca(a),d=\"\";if(!a.value||o>c)return\"\";if(\"function\"==typeof n)d=n(a,b,{key:f(a.data),value:g(a.data),percent:k(c)});else switch(n){case\"key\":d=f(a.data);break;case\"value\":d=k(g(a.data));break;case\"percent\":d=d3.format(\"%\")(c)}return d})}}),E.renderEnd(\"pie immediate\"),b}var c={top:0,right:0,bottom:0,left:0},d=500,e=500,f=function(a){return a.x},g=function(a){return a.y},h=Math.floor(1e4*Math.random()),i=null,j=a.utils.defaultColor(),k=d3.format(\",.2f\"),l=!0,m=!1,n=\"key\",o=.02,p=!1,q=!1,r=!0,s=0,t=!1,u=!1,v=!1,w=!1,x=0,y=.5,z=250,A=[],B=d3.dispatch(\"chartClick\",\"elementClick\",\"elementDblClick\",\"elementMouseover\",\"elementMouseout\",\"elementMousemove\",\"renderEnd\"),C=[],D=[],E=a.utils.renderWatch(B);return b.dispatch=B,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{arcsRadius:{get:function(){return A},set:function(a){A=a}},width:{get:function(){return d},set:function(a){d=a}},height:{get:function(){return e},set:function(a){e=a}},showLabels:{get:function(){return l},set:function(a){l=a}},title:{get:function(){return q},set:function(a){q=a}},titleOffset:{get:function(){return s},set:function(a){s=a}},labelThreshold:{get:function(){return o},set:function(a){o=a}},valueFormat:{get:function(){return k},set:function(a){k=a}},x:{get:function(){return f},set:function(a){f=a}},id:{get:function(){return h},set:function(a){h=a}},endAngle:{get:function(){return w},set:function(a){w=a}},startAngle:{get:function(){return u},set:function(a){u=a}},padAngle:{get:function(){return v},set:function(a){v=a}},cornerRadius:{get:function(){return x},set:function(a){x=a}},donutRatio:{get:function(){return y},set:function(a){y=a}},labelsOutside:{get:function(){return m},set:function(a){m=a}},labelSunbeamLayout:{get:function(){return t},set:function(a){t=a}},donut:{get:function(){return p},set:function(a){p=a}},growOnHover:{get:function(){return r},set:function(a){r=a}},pieLabelsOutside:{get:function(){return m},set:function(b){m=b,a.deprecated(\"pieLabelsOutside\",\"use labelsOutside instead\")}},donutLabelsOutside:{get:function(){return m},set:function(b){m=b,a.deprecated(\"donutLabelsOutside\",\"use labelsOutside instead\")}},labelFormat:{get:function(){return k},set:function(b){k=b,a.deprecated(\"labelFormat\",\"use valueFormat instead\")}},margin:{get:function(){return c},set:function(a){c.top=\"undefined\"!=typeof a.top?a.top:c.top,c.right=\"undefined\"!=typeof a.right?a.right:c.right,c.bottom=\"undefined\"!=typeof a.bottom?a.bottom:c.bottom,c.left=\"undefined\"!=typeof a.left?a.left:c.left}},duration:{get:function(){return z},set:function(a){z=a,E.reset(z)}},y:{get:function(){return g},set:function(a){g=d3.functor(a)}},color:{get:function(){return j},set:function(b){j=a.utils.getColor(b)}},labelType:{get:function(){return n},set:function(a){n=a||\"key\"}}}),a.utils.initOptions(b),b},a.models.pieChart=function(){\"use strict\";function b(e){return r.reset(),r.models(c),e.each(function(e){var i=d3.select(this);a.utils.initSVG(i);var l=a.utils.availableWidth(g,i,f),o=a.utils.availableHeight(h,i,f);if(b.update=function(){i.transition().call(b)},b.container=this,m.setter(t(e),b.update).getter(s(e)).update(),m.disabled=e.map(function(a){return!!a.disabled}),!n){var p;n={};for(p in m)m[p]instanceof Array?n[p]=m[p].slice(0):n[p]=m[p]}if(!e||!e.length)return a.utils.noData(b,i),b;i.selectAll(\".nv-noData\").remove();var r=i.selectAll(\"g.nv-wrap.nv-pieChart\").data([e]),u=r.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-pieChart\").append(\"g\"),v=r.select(\"g\");if(u.append(\"g\").attr(\"class\",\"nv-pieWrap\"),u.append(\"g\").attr(\"class\",\"nv-legendWrap\"),j){if(\"top\"===k)d.width(l).key(c.x()),r.select(\".nv-legendWrap\").datum(e).call(d),d.height()>f.top&&(f.top=d.height(),o=a.utils.availableHeight(h,i,f)),r.select(\".nv-legendWrap\").attr(\"transform\",\"translate(0,\"+-f.top+\")\");else if(\"right\"===k){var w=a.models.legend().width();w>l/2&&(w=l/2),d.height(o).key(c.x()),d.width(w),l-=d.width(),r.select(\".nv-legendWrap\").datum(e).call(d).attr(\"transform\",\"translate(\"+l+\",0)\")}}else v.select(\".nv-legendWrap\").selectAll(\"*\").remove();r.attr(\"transform\",\"translate(\"+f.left+\",\"+f.top+\")\"),c.width(l).height(o);var x=v.select(\".nv-pieWrap\").datum([e]);d3.transition(x).call(c),d.dispatch.on(\"stateChange\",function(a){for(var c in a)m[c]=a[c];q.stateChange(m),b.update()}),q.on(\"changeState\",function(a){\"undefined\"!=typeof a.disabled&&(e.forEach(function(b,c){b.disabled=a.disabled[c]}),m.disabled=a.disabled),b.update()})}),r.renderEnd(\"pieChart immediate\"),b}var c=a.models.pie(),d=a.models.legend(),e=a.models.tooltip(),f={top:30,right:20,bottom:20,left:20},g=null,h=null,i=!1,j=!0,k=\"top\",l=a.utils.defaultColor(),m=a.utils.state(),n=null,o=null,p=250,q=d3.dispatch(\"stateChange\",\"changeState\",\"renderEnd\");e.duration(0).headerEnabled(!1).valueFormatter(function(a,b){return c.valueFormat()(a,b)});var r=a.utils.renderWatch(q),s=function(a){return function(){return{active:a.map(function(a){return!a.disabled})}}},t=function(a){return function(b){void 0!==b.active&&a.forEach(function(a,c){a.disabled=!b.active[c]})}};return c.dispatch.on(\"elementMouseover.tooltip\",function(a){a.series={key:b.x()(a.data),value:b.y()(a.data),color:a.color,percent:a.percent},i||(delete a.percent,delete a.series.percent),e.data(a).hidden(!1)}),c.dispatch.on(\"elementMouseout.tooltip\",function(a){e.hidden(!0)}),c.dispatch.on(\"elementMousemove.tooltip\",function(a){e()}),b.legend=d,b.dispatch=q,b.pie=c,b.tooltip=e,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return g},set:function(a){g=a}},height:{get:function(){return h},set:function(a){h=a}},noData:{get:function(){return o},set:function(a){o=a}},showTooltipPercent:{get:function(){return i},set:function(a){i=a}},showLegend:{get:function(){return j},set:function(a){j=a}},legendPosition:{get:function(){return k},set:function(a){k=a}},defaultState:{get:function(){return n},set:function(a){n=a}},color:{get:function(){return l},set:function(a){l=a,d.color(l),c.color(l)}},duration:{get:function(){return p},set:function(a){p=a,r.reset(p),c.duration(p)}},margin:{get:function(){return f},set:function(a){f.top=void 0!==a.top?a.top:f.top,f.right=void 0!==a.right?a.right:f.right,f.bottom=void 0!==a.bottom?a.bottom:f.bottom,f.left=void 0!==a.left?a.left:f.left}}}),a.utils.inheritOptions(b,c),a.utils.initOptions(b),b},a.models.scatter=function(){\"use strict\";function b(a){var b,c;return b=i=i||{},c=a[0].series,b=b[c]=b[c]||{},c=a[1],b=b[c]=b[c]||{}}function c(a){var c,d,e=a[0],f=b(a),g=!1;for(c=1;c<arguments.length;c++)d=arguments[c],f[d]===e[d]&&f.hasOwnProperty(d)||(f[d]=e[d],g=!0);return g}function d(b){return U.reset(),b.each(function(b){function i(){if(T=!1,!z)return!1;if(P===!0){var c=d3.merge(b.map(function(b,c){return b.values.map(function(b,d){var e=s(b,d),f=t(b,d);return[a.utils.NaNtoZero(p(e))+1e-4*Math.random(),a.utils.NaNtoZero(q(f))+1e-4*Math.random(),c,d,b]}).filter(function(a,b){return A(a[4],b)})}));if(0==c.length)return!1;c.length<3&&(c.push([p.range()[0]-20,q.range()[0]-20,null,null]),c.push([p.range()[1]+20,q.range()[1]+20,null,null]),c.push([p.range()[0]-20,q.range()[0]+20,null,null]),c.push([p.range()[1]+20,q.range()[1]-20,null,null]));var d=d3.geom.polygon([[-10,-10],[-10,l+10],[k+10,l+10],[k+10,-10]]),e=d3.geom.voronoi(c).map(function(a,b){return{data:d.clip(a),series:c[b][2],point:c[b][3]}});_.select(\".nv-point-paths\").selectAll(\"path\").remove();var f=_.select(\".nv-point-paths\").selectAll(\"path\").data(e),g=f.enter().append(\"svg:path\").attr(\"d\",function(a){return a&&a.data&&0!==a.data.length?\"M\"+a.data.join(\",\")+\"Z\":\"M 0 0\"}).attr(\"id\",function(a,b){return\"nv-path-\"+b}).attr(\"clip-path\",function(a,b){return\"url(#nv-clip-\"+n+\"-\"+b+\")\"});if(F&&g.style(\"fill\",d3.rgb(230,230,230)).style(\"fill-opacity\",.4).style(\"stroke-opacity\",1).style(\"stroke\",d3.rgb(200,200,200)),E){_.select(\".nv-point-clips\").selectAll(\"*\").remove();var h=_.select(\".nv-point-clips\").selectAll(\"clipPath\").data(c);h.enter().append(\"svg:clipPath\").attr(\"id\",function(a,b){return\"nv-clip-\"+n+\"-\"+b}).append(\"svg:circle\").attr(\"cx\",function(a){return a[0]}).attr(\"cy\",function(a){return a[1]}).attr(\"r\",G)}var i=function(a,c){if(T)return 0;var d=b[a.series];if(void 0!==d){var e=d.values[a.point];e.color=m(d,a.series),e.x=s(e),e.y=t(e);var f=o.node().getBoundingClientRect(),g=window.pageYOffset||document.documentElement.scrollTop,h=window.pageXOffset||document.documentElement.scrollLeft,i={left:p(s(e,a.point))+f.left+h+j.left+10,top:q(t(e,a.point))+f.top+g+j.top+10};c({point:e,series:d,pos:i,relativePos:[p(s(e,a.point))+j.left,q(t(e,a.point))+j.top],seriesIndex:a.series,pointIndex:a.point})}};f.on(\"click\",function(a){i(a,O.elementClick)}).on(\"dblclick\",function(a){i(a,O.elementDblClick)}).on(\"mouseover\",function(a){i(a,O.elementMouseover)}).on(\"mouseout\",function(a,b){i(a,O.elementMouseout)})}else _.select(\".nv-groups\").selectAll(\".nv-group\").selectAll(\".nv-point\").on(\"click\",function(a,c){if(T||!b[a.series])return 0;var d=b[a.series],e=d.values[c],f=this;O.elementClick({point:e,series:d,pos:[p(s(e,c))+j.left,q(t(e,c))+j.top],relativePos:[p(s(e,c))+j.left,q(t(e,c))+j.top],seriesIndex:a.series,pointIndex:c,event:d3.event,element:f})}).on(\"dblclick\",function(a,c){if(T||!b[a.series])return 0;var d=b[a.series],e=d.values[c];O.elementDblClick({point:e,series:d,pos:[p(s(e,c))+j.left,q(t(e,c))+j.top],relativePos:[p(s(e,c))+j.left,q(t(e,c))+j.top],seriesIndex:a.series,pointIndex:c})}).on(\"mouseover\",function(a,c){if(T||!b[a.series])return 0;var d=b[a.series],e=d.values[c];O.elementMouseover({point:e,series:d,pos:[p(s(e,c))+j.left,q(t(e,c))+j.top],relativePos:[p(s(e,c))+j.left,q(t(e,c))+j.top],seriesIndex:a.series,pointIndex:c,color:m(a,c)})}).on(\"mouseout\",function(a,c){if(T||!b[a.series])return 0;var d=b[a.series],e=d.values[c];O.elementMouseout({point:e,series:d,pos:[p(s(e,c))+j.left,q(t(e,c))+j.top],relativePos:[p(s(e,c))+j.left,q(t(e,c))+j.top],seriesIndex:a.series,pointIndex:c,color:m(a,c)})})}o=d3.select(this);var Q=a.utils.availableWidth(k,o,j),W=a.utils.availableHeight(l,o,j);a.utils.initSVG(o),b.forEach(function(a,b){a.values.forEach(function(a){a.series=b})});var X=d.yScale().name===d3.scale.log().name?!0:!1,Y=H&&I&&L?[]:d3.merge(b.map(function(a){return a.values.map(function(a,b){return{x:s(a,b),y:t(a,b),size:u(a,b)}})}));if(p.domain(H||d3.extent(Y.map(function(a){return a.x}).concat(w))),B&&b[0]?p.range(J||[(Q*C+Q)/(2*b[0].values.length),Q-Q*(1+C)/(2*b[0].values.length)]):p.range(J||[0,Q]),X){var Z=d3.min(Y.map(function(a){return 0!==a.y?a.y:void 0}));q.clamp(!0).domain(I||d3.extent(Y.map(function(a){return 0!==a.y?a.y:.1*Z}).concat(x))).range(K||[W,0])}else q.domain(I||d3.extent(Y.map(function(a){return a.y}).concat(x))).range(K||[W,0]);r.domain(L||d3.extent(Y.map(function(a){return a.size}).concat(y))).range(M||V),N=p.domain()[0]===p.domain()[1]||q.domain()[0]===q.domain()[1],p.domain()[0]===p.domain()[1]&&(p.domain()[0]?p.domain([p.domain()[0]-.01*p.domain()[0],p.domain()[1]+.01*p.domain()[1]]):p.domain([-1,1])),q.domain()[0]===q.domain()[1]&&(q.domain()[0]?q.domain([q.domain()[0]-.01*q.domain()[0],q.domain()[1]+.01*q.domain()[1]]):q.domain([-1,1])),isNaN(p.domain()[0])&&p.domain([-1,1]),isNaN(q.domain()[0])&&q.domain([-1,1]),e=e||p,f=f||q,g=g||r;var $=p(1)!==e(1)||q(1)!==f(1)||r(1)!==g(1),_=o.selectAll(\"g.nv-wrap.nv-scatter\").data([b]),aa=_.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-scatter nv-chart-\"+n),ba=aa.append(\"defs\"),ca=aa.append(\"g\"),da=_.select(\"g\");_.classed(\"nv-single-point\",N),ca.append(\"g\").attr(\"class\",\"nv-groups\"),ca.append(\"g\").attr(\"class\",\"nv-point-paths\"),aa.append(\"g\").attr(\"class\",\"nv-point-clips\"),_.attr(\"transform\",\"translate(\"+j.left+\",\"+j.top+\")\"),ba.append(\"clipPath\").attr(\"id\",\"nv-edge-clip-\"+n).append(\"rect\"),_.select(\"#nv-edge-clip-\"+n+\" rect\").attr(\"width\",Q).attr(\"height\",W>0?W:0),da.attr(\"clip-path\",D?\"url(#nv-edge-clip-\"+n+\")\":\"\"),T=!0;var ea=_.select(\".nv-groups\").selectAll(\".nv-group\").data(function(a){return a},function(a){return a.key});ea.enter().append(\"g\").style(\"stroke-opacity\",1e-6).style(\"fill-opacity\",1e-6),ea.exit().remove(),ea.attr(\"class\",function(a,b){return(a.classed||\"\")+\" nv-group nv-series-\"+b}).classed(\"nv-noninteractive\",!z).classed(\"hover\",function(a){return a.hover}),ea.watchTransition(U,\"scatter: groups\").style(\"fill\",function(a,b){return m(a,b)}).style(\"stroke\",function(a,b){return m(a,b)}).style(\"stroke-opacity\",1).style(\"fill-opacity\",.5);var fa=ea.selectAll(\"path.nv-point\").data(function(a){return a.values.map(function(a,b){return[a,b]}).filter(function(a,b){return A(a[0],b)})});if(fa.enter().append(\"path\").attr(\"class\",function(a){return\"nv-point nv-point-\"+a[1]}).style(\"fill\",function(a){return a.color}).style(\"stroke\",function(a){return a.color}).attr(\"transform\",function(b){return\"translate(\"+a.utils.NaNtoZero(e(s(b[0],b[1])))+\",\"+a.utils.NaNtoZero(f(t(b[0],b[1])))+\")\"}).attr(\"d\",a.utils.symbol().type(function(a){return v(a[0])}).size(function(a){return r(u(a[0],a[1]))})),fa.exit().remove(),ea.exit().selectAll(\"path.nv-point\").watchTransition(U,\"scatter exit\").attr(\"transform\",function(b){return\"translate(\"+a.utils.NaNtoZero(p(s(b[0],b[1])))+\",\"+a.utils.NaNtoZero(q(t(b[0],b[1])))+\")\"}).remove(),fa.filter(function(a){return $||c(a,\"x\",\"y\")}).watchTransition(U,\"scatter points\").attr(\"transform\",function(b){return\"translate(\"+a.utils.NaNtoZero(p(s(b[0],b[1])))+\",\"+a.utils.NaNtoZero(q(t(b[0],b[1])))+\")\"}),fa.filter(function(a){return $||c(a,\"shape\",\"size\")}).watchTransition(U,\"scatter points\").attr(\"d\",a.utils.symbol().type(function(a){return v(a[0])}).size(function(a){return r(u(a[0],a[1]))})),S){var ga=ea.selectAll(\".nv-label\").data(function(a){return a.values.map(function(a,b){return[a,b]}).filter(function(a,b){return A(a[0],b)})});ga.enter().append(\"text\").style(\"fill\",function(a,b){return a.color}).style(\"stroke-opacity\",0).style(\"fill-opacity\",1).attr(\"transform\",function(b){var c=a.utils.NaNtoZero(e(s(b[0],b[1])))+Math.sqrt(r(u(b[0],b[1]))/Math.PI)+2;return\"translate(\"+c+\",\"+a.utils.NaNtoZero(f(t(b[0],b[1])))+\")\"}).text(function(a,b){return a[0].label}),ga.exit().remove(),ea.exit().selectAll(\"path.nv-label\").watchTransition(U,\"scatter exit\").attr(\"transform\",function(b){var c=a.utils.NaNtoZero(p(s(b[0],b[1])))+Math.sqrt(r(u(b[0],b[1]))/Math.PI)+2;return\"translate(\"+c+\",\"+a.utils.NaNtoZero(q(t(b[0],b[1])))+\")\"}).remove(),ga.each(function(a){d3.select(this).classed(\"nv-label\",!0).classed(\"nv-label-\"+a[1],!1).classed(\"hover\",!1)}),ga.watchTransition(U,\"scatter labels\").attr(\"transform\",function(b){var c=a.utils.NaNtoZero(p(s(b[0],b[1])))+Math.sqrt(r(u(b[0],b[1]))/Math.PI)+2;return\"translate(\"+c+\",\"+a.utils.NaNtoZero(q(t(b[0],b[1])))+\")\"})}R?(clearTimeout(h),h=setTimeout(i,R)):i(),e=p.copy(),f=q.copy(),g=r.copy()}),U.renderEnd(\"scatter immediate\"),d}var e,f,g,h,i,j={top:0,right:0,bottom:0,left:0},k=null,l=null,m=a.utils.defaultColor(),n=Math.floor(1e5*Math.random()),o=null,p=d3.scale.linear(),q=d3.scale.linear(),r=d3.scale.linear(),s=function(a){return a.x},t=function(a){return a.y},u=function(a){return a.size||1},v=function(a){return a.shape||\"circle\"},w=[],x=[],y=[],z=!0,A=function(a){return!a.notActive},B=!1,C=.1,D=!1,E=!0,F=!1,G=function(){return 25},H=null,I=null,J=null,K=null,L=null,M=null,N=!1,O=d3.dispatch(\"elementClick\",\"elementDblClick\",\"elementMouseover\",\"elementMouseout\",\"renderEnd\"),P=!0,Q=250,R=300,S=!1,T=!1,U=a.utils.renderWatch(O,Q),V=[16,256];return d.dispatch=O,d.options=a.utils.optionsFunc.bind(d),d._calls=new function(){this.clearHighlights=function(){return a.dom.write(function(){o.selectAll(\".nv-point.hover\").classed(\"hover\",!1)}),null},this.highlightPoint=function(b,c,d){a.dom.write(function(){o.select(\".nv-groups\").selectAll(\".nv-series-\"+b).selectAll(\".nv-point-\"+c).classed(\"hover\",d)})}},O.on(\"elementMouseover.point\",function(a){z&&d._calls.highlightPoint(a.seriesIndex,a.pointIndex,!0)}),O.on(\"elementMouseout.point\",function(a){z&&d._calls.highlightPoint(a.seriesIndex,a.pointIndex,!1)}),d._options=Object.create({},{width:{get:function(){return k},set:function(a){k=a}},height:{get:function(){return l},set:function(a){l=a}},xScale:{get:function(){return p},set:function(a){p=a}},yScale:{get:function(){return q},set:function(a){q=a}},pointScale:{get:function(){return r},set:function(a){r=a}},xDomain:{get:function(){return H},set:function(a){H=a}},yDomain:{get:function(){return I},set:function(a){I=a}},pointDomain:{get:function(){return L},set:function(a){L=a}},xRange:{get:function(){return J},set:function(a){J=a}},yRange:{get:function(){return K},set:function(a){K=a}},pointRange:{get:function(){return M},set:function(a){M=a}},forceX:{get:function(){return w},set:function(a){w=a}},forceY:{get:function(){return x},set:function(a){x=a}},forcePoint:{get:function(){return y},set:function(a){y=a}},interactive:{get:function(){return z},set:function(a){z=a}},pointActive:{get:function(){return A},set:function(a){A=a}},padDataOuter:{get:function(){return C},set:function(a){C=a}},padData:{get:function(){return B},set:function(a){B=a}},clipEdge:{get:function(){return D},set:function(a){D=a}},clipVoronoi:{get:function(){return E},set:function(a){E=a}},clipRadius:{get:function(){return G},set:function(a){G=a}},showVoronoi:{get:function(){return F},set:function(a){F=a}},id:{get:function(){return n},set:function(a){n=a}},interactiveUpdateDelay:{get:function(){return R},set:function(a){R=a}},showLabels:{get:function(){return S},set:function(a){S=a}},x:{get:function(){return s},set:function(a){s=d3.functor(a)}},y:{get:function(){return t},set:function(a){t=d3.functor(a)}},pointSize:{get:function(){return u},set:function(a){u=d3.functor(a)}},pointShape:{get:function(){return v},set:function(a){v=d3.functor(a)}},margin:{get:function(){return j},set:function(a){j.top=void 0!==a.top?a.top:j.top,j.right=void 0!==a.right?a.right:j.right,j.bottom=void 0!==a.bottom?a.bottom:j.bottom,j.left=void 0!==a.left?a.left:j.left}},duration:{get:function(){return Q},set:function(a){Q=a,U.reset(Q)}},color:{get:function(){return m},set:function(b){m=a.utils.getColor(b)}},useVoronoi:{get:function(){return P},set:function(a){P=a,P===!1&&(E=!1)}}}),a.utils.initOptions(d),d},a.models.scatterChart=function(){\"use strict\";function b(z){return E.reset(),E.models(c),t&&E.models(d),u&&E.models(e),q&&E.models(g),r&&E.models(h),z.each(function(z){m=d3.select(this),a.utils.initSVG(m);var H=a.utils.availableWidth(k,m,j),I=a.utils.availableHeight(l,m,j);if(b.update=function(){0===A?m.call(b):m.transition().duration(A).call(b)},b.container=this,w.setter(G(z),b.update).getter(F(z)).update(),w.disabled=z.map(function(a){return!!a.disabled}),!x){var J;x={};for(J in w)w[J]instanceof Array?x[J]=w[J].slice(0):x[J]=w[J]}if(!(z&&z.length&&z.filter(function(a){return a.values.length}).length))return a.utils.noData(b,m),E.renderEnd(\"scatter immediate\"),b;m.selectAll(\".nv-noData\").remove(),o=c.xScale(),p=c.yScale();var K=m.selectAll(\"g.nv-wrap.nv-scatterChart\").data([z]),L=K.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-scatterChart nv-chart-\"+c.id()),M=L.append(\"g\"),N=K.select(\"g\");if(M.append(\"rect\").attr(\"class\",\"nvd3 nv-background\").style(\"pointer-events\",\"none\"),M.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),M.append(\"g\").attr(\"class\",\"nv-y nv-axis\"),M.append(\"g\").attr(\"class\",\"nv-scatterWrap\"),M.append(\"g\").attr(\"class\",\"nv-regressionLinesWrap\"),M.append(\"g\").attr(\"class\",\"nv-distWrap\"),M.append(\"g\").attr(\"class\",\"nv-legendWrap\"),v&&N.select(\".nv-y.nv-axis\").attr(\"transform\",\"translate(\"+H+\",0)\"),s){var O=H;f.width(O),K.select(\".nv-legendWrap\").datum(z).call(f),f.height()>j.top&&(j.top=f.height(),I=a.utils.availableHeight(l,m,j)),K.select(\".nv-legendWrap\").attr(\"transform\",\"translate(0,\"+-j.top+\")\")}else N.select(\".nv-legendWrap\").selectAll(\"*\").remove();K.attr(\"transform\",\"translate(\"+j.left+\",\"+j.top+\")\"),c.width(H).height(I).color(z.map(function(a,b){return a.color=a.color||n(a,b),a.color}).filter(function(a,b){return!z[b].disabled})).showLabels(B),K.select(\".nv-scatterWrap\").datum(z.filter(function(a){return!a.disabled})).call(c),K.select(\".nv-regressionLinesWrap\").attr(\"clip-path\",\"url(#nv-edge-clip-\"+c.id()+\")\");var P=K.select(\".nv-regressionLinesWrap\").selectAll(\".nv-regLines\").data(function(a){return a});P.enter().append(\"g\").attr(\"class\",\"nv-regLines\");var Q=P.selectAll(\".nv-regLine\").data(function(a){return[a]});Q.enter().append(\"line\").attr(\"class\",\"nv-regLine\").style(\"stroke-opacity\",0),Q.filter(function(a){return a.intercept&&a.slope}).watchTransition(E,\"scatterPlusLineChart: regline\").attr(\"x1\",o.range()[0]).attr(\"x2\",o.range()[1]).attr(\"y1\",function(a,b){return p(o.domain()[0]*a.slope+a.intercept)}).attr(\"y2\",function(a,b){return p(o.domain()[1]*a.slope+a.intercept)}).style(\"stroke\",function(a,b,c){return n(a,c)}).style(\"stroke-opacity\",function(a,b){return a.disabled||\"undefined\"==typeof a.slope||\"undefined\"==typeof a.intercept?0:1}),t&&(d.scale(o)._ticks(a.utils.calcTicksX(H/100,z)).tickSize(-I,0),N.select(\".nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+p.range()[0]+\")\").call(d)),u&&(e.scale(p)._ticks(a.utils.calcTicksY(I/36,z)).tickSize(-H,0),N.select(\".nv-y.nv-axis\").call(e)),q&&(g.getData(c.x()).scale(o).width(H).color(z.map(function(a,b){return a.color||n(a,b)}).filter(function(a,b){return!z[b].disabled})),M.select(\".nv-distWrap\").append(\"g\").attr(\"class\",\"nv-distributionX\"),N.select(\".nv-distributionX\").attr(\"transform\",\"translate(0,\"+p.range()[0]+\")\").datum(z.filter(function(a){return!a.disabled})).call(g)),r&&(h.getData(c.y()).scale(p).width(I).color(z.map(function(a,b){return a.color||n(a,b)}).filter(function(a,b){return!z[b].disabled})),M.select(\".nv-distWrap\").append(\"g\").attr(\"class\",\"nv-distributionY\"),N.select(\".nv-distributionY\").attr(\"transform\",\"translate(\"+(v?H:-h.size())+\",0)\").datum(z.filter(function(a){return!a.disabled})).call(h)),f.dispatch.on(\"stateChange\",function(a){for(var c in a)w[c]=a[c];y.stateChange(w),b.update()}),y.on(\"changeState\",function(a){\"undefined\"!=typeof a.disabled&&(z.forEach(function(b,c){b.disabled=a.disabled[c]}),w.disabled=a.disabled),b.update()}),c.dispatch.on(\"elementMouseout.tooltip\",function(a){i.hidden(!0),m.select(\".nv-chart-\"+c.id()+\" .nv-series-\"+a.seriesIndex+\" .nv-distx-\"+a.pointIndex).attr(\"y1\",0),m.select(\".nv-chart-\"+c.id()+\" .nv-series-\"+a.seriesIndex+\" .nv-disty-\"+a.pointIndex).attr(\"x2\",h.size())}),c.dispatch.on(\"elementMouseover.tooltip\",function(a){m.select(\".nv-series-\"+a.seriesIndex+\" .nv-distx-\"+a.pointIndex).attr(\"y1\",a.relativePos[1]-I),m.select(\".nv-series-\"+a.seriesIndex+\" .nv-disty-\"+a.pointIndex).attr(\"x2\",a.relativePos[0]+g.size()),i.data(a).hidden(!1)}),C=o.copy(),D=p.copy()}),E.renderEnd(\"scatter with line immediate\"),b}var c=a.models.scatter(),d=a.models.axis(),e=a.models.axis(),f=a.models.legend(),g=a.models.distribution(),h=a.models.distribution(),i=a.models.tooltip(),j={top:30,right:20,bottom:50,left:75},k=null,l=null,m=null,n=a.utils.defaultColor(),o=c.xScale(),p=c.yScale(),q=!1,r=!1,s=!0,t=!0,u=!0,v=!1,w=a.utils.state(),x=null,y=d3.dispatch(\"stateChange\",\"changeState\",\"renderEnd\"),z=null,A=250,B=!1;c.xScale(o).yScale(p),d.orient(\"bottom\").tickPadding(10),e.orient(v?\"right\":\"left\").tickPadding(10),g.axis(\"x\"),h.axis(\"y\"),i.headerFormatter(function(a,b){return d.tickFormat()(a,b)}).valueFormatter(function(a,b){return e.tickFormat()(a,b)});var C,D,E=a.utils.renderWatch(y,A),F=function(a){return function(){return{active:a.map(function(a){return!a.disabled})}}},G=function(a){return function(b){void 0!==b.active&&a.forEach(function(a,c){a.disabled=!b.active[c]})}};return b.dispatch=y,b.scatter=c,b.legend=f,b.xAxis=d,b.yAxis=e,b.distX=g,b.distY=h,b.tooltip=i,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return k},set:function(a){k=a}},height:{get:function(){return l},set:function(a){l=a}},container:{get:function(){return m},set:function(a){m=a}},showDistX:{get:function(){return q},set:function(a){q=a}},showDistY:{get:function(){return r},set:function(a){r=a}},showLegend:{get:function(){return s},set:function(a){s=a}},showXAxis:{get:function(){return t},set:function(a){t=a}},showYAxis:{get:function(){return u},set:function(a){u=a}},defaultState:{get:function(){return x},set:function(a){x=a}},noData:{get:function(){return z},set:function(a){z=a}},duration:{get:function(){return A},set:function(a){A=a}},showLabels:{get:function(){return B},set:function(a){B=a}},margin:{get:function(){return j},set:function(a){j.top=void 0!==a.top?a.top:j.top,j.right=void 0!==a.right?a.right:j.right,j.bottom=void 0!==a.bottom?a.bottom:j.bottom,j.left=void 0!==a.left?a.left:j.left}},rightAlignYAxis:{get:function(){return v},set:function(a){v=a,e.orient(a?\"right\":\"left\")}},color:{get:function(){return n},set:function(b){n=a.utils.getColor(b),f.color(n),g.color(n),h.color(n)}}}),a.utils.inheritOptions(b,c),a.utils.initOptions(b),b},a.models.sparkline=function(){\"use strict\";function b(k){return t.reset(),k.each(function(b){var k=h-g.left-g.right,s=i-g.top-g.bottom;j=d3.select(this),a.utils.initSVG(j),l.domain(c||d3.extent(b,n)).range(e||[0,k]),m.domain(d||d3.extent(b,o)).range(f||[s,0]);var t=j.selectAll(\"g.nv-wrap.nv-sparkline\").data([b]),u=t.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-sparkline\");u.append(\"g\"),t.select(\"g\");t.attr(\"transform\",\"translate(\"+g.left+\",\"+g.top+\")\");var v=t.selectAll(\"path\").data(function(a){return[a]});v.enter().append(\"path\"),v.exit().remove(),v.style(\"stroke\",function(a,b){return a.color||p(a,b)}).attr(\"d\",d3.svg.line().x(function(a,b){return l(n(a,b))}).y(function(a,b){return m(o(a,b))}));var w=t.selectAll(\"circle.nv-point\").data(function(a){function b(b){if(-1!=b){var c=a[b];return c.pointIndex=b,c}return null}var c=a.map(function(a,b){return o(a,b)}),d=b(c.lastIndexOf(m.domain()[1])),e=b(c.indexOf(m.domain()[0])),f=b(c.length-1);return[q?e:null,q?d:null,r?f:null].filter(function(a){return null!=a})});w.enter().append(\"circle\"),w.exit().remove(),w.attr(\"cx\",function(a,b){return l(n(a,a.pointIndex))}).attr(\"cy\",function(a,b){return m(o(a,a.pointIndex))}).attr(\"r\",2).attr(\"class\",function(a,b){return n(a,a.pointIndex)==l.domain()[1]?\"nv-point nv-currentValue\":o(a,a.pointIndex)==m.domain()[0]?\"nv-point nv-minValue\":\"nv-point nv-maxValue\"})}),t.renderEnd(\"sparkline immediate\"),b}var c,d,e,f,g={top:2,right:0,bottom:2,left:0},h=400,i=32,j=null,k=!0,l=d3.scale.linear(),m=d3.scale.linear(),n=function(a){return a.x},o=function(a){return a.y},p=a.utils.getColor([\"#000\"]),q=!0,r=!0,s=d3.dispatch(\"renderEnd\"),t=a.utils.renderWatch(s);return b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return h},set:function(a){h=a}},height:{get:function(){return i},set:function(a){i=a}},xDomain:{get:function(){return c},set:function(a){c=a}},yDomain:{get:function(){return d},set:function(a){d=a}},xRange:{get:function(){return e},set:function(a){e=a}},yRange:{get:function(){return f},set:function(a){f=a}},xScale:{get:function(){return l},set:function(a){l=a}},yScale:{get:function(){return m},set:function(a){m=a}},animate:{get:function(){return k},set:function(a){k=a}},showMinMaxPoints:{get:function(){return q},set:function(a){q=a}},showCurrentPoint:{get:function(){return r},set:function(a){r=a}},x:{get:function(){return n},set:function(a){n=d3.functor(a)}},y:{get:function(){return o},set:function(a){o=d3.functor(a)}},margin:{get:function(){return g},set:function(a){g.top=void 0!==a.top?a.top:g.top,g.right=void 0!==a.right?a.right:g.right,g.bottom=void 0!==a.bottom?a.bottom:g.bottom,g.left=void 0!==a.left?a.left:g.left}},color:{get:function(){return p},set:function(b){p=a.utils.getColor(b)}}}),b.dispatch=s,a.utils.initOptions(b),b},a.models.sparklinePlus=function(){\"use strict\";function b(p){return r.reset(),r.models(e),p.each(function(p){function q(){if(!j){var a=z.selectAll(\".nv-hoverValue\").data(i),b=a.enter().append(\"g\").attr(\"class\",\"nv-hoverValue\").style(\"stroke-opacity\",0).style(\"fill-opacity\",0);a.exit().transition().duration(250).style(\"stroke-opacity\",0).style(\"fill-opacity\",0).remove(),a.attr(\"transform\",function(a){return\"translate(\"+c(e.x()(p[a],a))+\",0)\"}).transition().duration(250).style(\"stroke-opacity\",1).style(\"fill-opacity\",1),i.length&&(b.append(\"line\").attr(\"x1\",0).attr(\"y1\",-f.top).attr(\"x2\",0).attr(\"y2\",u),b.append(\"text\").attr(\"class\",\"nv-xValue\").attr(\"x\",-6).attr(\"y\",-f.top).attr(\"text-anchor\",\"end\").attr(\"dy\",\".9em\"),z.select(\".nv-hoverValue .nv-xValue\").text(k(e.x()(p[i[0]],i[0]))),b.append(\"text\").attr(\"class\",\"nv-yValue\").attr(\"x\",6).attr(\"y\",-f.top).attr(\"text-anchor\",\"start\").attr(\"dy\",\".9em\"),z.select(\".nv-hoverValue .nv-yValue\").text(l(e.y()(p[i[0]],i[0]))))}}function r(){function a(a,b){for(var c=Math.abs(e.x()(a[0],0)-b),d=0,f=0;f<a.length;f++)Math.abs(e.x()(a[f],f)-b)<c&&(c=Math.abs(e.x()(a[f],f)-b),d=f);return d}if(!j){var b=d3.mouse(this)[0]-f.left;i=[a(p,Math.round(c.invert(b)))],q()}}var s=d3.select(this);a.utils.initSVG(s);var t=a.utils.availableWidth(g,s,f),u=a.utils.availableHeight(h,s,f);if(b.update=function(){s.call(b)},b.container=this,!p||!p.length)return a.utils.noData(b,s),b;s.selectAll(\".nv-noData\").remove();var v=e.y()(p[p.length-1],p.length-1);c=e.xScale(),d=e.yScale();var w=s.selectAll(\"g.nv-wrap.nv-sparklineplus\").data([p]),x=w.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-sparklineplus\"),y=x.append(\"g\"),z=w.select(\"g\");y.append(\"g\").attr(\"class\",\"nv-sparklineWrap\"),y.append(\"g\").attr(\"class\",\"nv-valueWrap\"),y.append(\"g\").attr(\"class\",\"nv-hoverArea\"),w.attr(\"transform\",\"translate(\"+f.left+\",\"+f.top+\")\");var A=z.select(\".nv-sparklineWrap\");if(e.width(t).height(u),A.call(e),m){var B=z.select(\".nv-valueWrap\"),C=B.selectAll(\".nv-currentValue\").data([v]);C.enter().append(\"text\").attr(\"class\",\"nv-currentValue\").attr(\"dx\",o?-8:8).attr(\"dy\",\".9em\").style(\"text-anchor\",o?\"end\":\"start\"),C.attr(\"x\",t+(o?f.right:0)).attr(\"y\",n?function(a){return d(a)}:0).style(\"fill\",e.color()(p[p.length-1],p.length-1)).text(l(v))}y.select(\".nv-hoverArea\").append(\"rect\").on(\"mousemove\",r).on(\"click\",function(){j=!j}).on(\"mouseout\",function(){i=[],q()}),z.select(\".nv-hoverArea rect\").attr(\"transform\",function(a){return\"translate(\"+-f.left+\",\"+-f.top+\")\"}).attr(\"width\",t+f.left+f.right).attr(\"height\",u+f.top)}),r.renderEnd(\"sparklinePlus immediate\"),b}var c,d,e=a.models.sparkline(),f={top:15,right:100,bottom:10,left:50},g=null,h=null,i=[],j=!1,k=d3.format(\",r\"),l=d3.format(\",.2f\"),m=!0,n=!0,o=!1,p=null,q=d3.dispatch(\"renderEnd\"),r=a.utils.renderWatch(q);return b.dispatch=q,b.sparkline=e,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return g},set:function(a){g=a}},height:{get:function(){return h},set:function(a){h=a}},xTickFormat:{get:function(){return k},set:function(a){k=a}},yTickFormat:{get:function(){return l},set:function(a){l=a}},showLastValue:{get:function(){return m},set:function(a){m=a}},alignValue:{get:function(){return n},set:function(a){n=a}},rightAlignValue:{get:function(){return o},set:function(a){o=a}},noData:{get:function(){return p},set:function(a){p=a}},margin:{get:function(){return f},set:function(a){f.top=void 0!==a.top?a.top:f.top,f.right=void 0!==a.right?a.right:f.right,f.bottom=void 0!==a.bottom?a.bottom:f.bottom,f.left=void 0!==a.left?a.left:f.left}}}),a.utils.inheritOptions(b,e),a.utils.initOptions(b),b},a.models.stackedArea=function(){\"use strict\";function b(n){return v.reset(),v.models(s),n.each(function(n){var t=f-e.left-e.right,w=g-e.top-e.bottom;j=d3.select(this),a.utils.initSVG(j),c=s.xScale(),d=s.yScale();var x=n;n.forEach(function(a,b){a.seriesIndex=b,a.values=a.values.map(function(a,c){return a.index=c,a.seriesIndex=b,a})});var y=n.filter(function(a){return!a.disabled});n=d3.layout.stack().order(p).offset(o).values(function(a){return a.values}).x(k).y(l).out(function(a,b,c){a.display={y:c,y0:b}})(y);var z=j.selectAll(\"g.nv-wrap.nv-stackedarea\").data([n]),A=z.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-stackedarea\"),B=A.append(\"defs\"),C=A.append(\"g\"),D=z.select(\"g\");C.append(\"g\").attr(\"class\",\"nv-areaWrap\"),C.append(\"g\").attr(\"class\",\"nv-scatterWrap\"),z.attr(\"transform\",\"translate(\"+e.left+\",\"+e.top+\")\"),0==s.forceY().length&&s.forceY().push(0),s.width(t).height(w).x(k).y(function(a){return void 0!==a.display?a.display.y+a.display.y0:void 0}).color(n.map(function(a,b){return a.color=a.color||h(a,a.seriesIndex),a.color}));var E=D.select(\".nv-scatterWrap\").datum(n);E.call(s),B.append(\"clipPath\").attr(\"id\",\"nv-edge-clip-\"+i).append(\"rect\"),z.select(\"#nv-edge-clip-\"+i+\" rect\").attr(\"width\",t).attr(\"height\",w),D.attr(\"clip-path\",r?\"url(#nv-edge-clip-\"+i+\")\":\"\");var F=d3.svg.area().defined(m).x(function(a,b){return c(k(a,b))}).y0(function(a){return d(a.display.y0)}).y1(function(a){return d(a.display.y+a.display.y0)}).interpolate(q),G=d3.svg.area().defined(m).x(function(a,b){return c(k(a,b))}).y0(function(a){return d(a.display.y0)}).y1(function(a){return d(a.display.y0)}),H=D.select(\".nv-areaWrap\").selectAll(\"path.nv-area\").data(function(a){return a});H.enter().append(\"path\").attr(\"class\",function(a,b){return\"nv-area nv-area-\"+b}).attr(\"d\",function(a,b){return G(a.values,a.seriesIndex)}).on(\"mouseover\",function(a,b){d3.select(this).classed(\"hover\",!0),u.areaMouseover({point:a,series:a.key,pos:[d3.event.pageX,d3.event.pageY],seriesIndex:a.seriesIndex})}).on(\"mouseout\",function(a,b){d3.select(this).classed(\"hover\",!1),u.areaMouseout({point:a,series:a.key,pos:[d3.event.pageX,d3.event.pageY],seriesIndex:a.seriesIndex})}).on(\"click\",function(a,b){d3.select(this).classed(\"hover\",!1),u.areaClick({point:a,series:a.key,pos:[d3.event.pageX,d3.event.pageY],seriesIndex:a.seriesIndex})}),H.exit().remove(),H.style(\"fill\",function(a,b){return a.color||h(a,a.seriesIndex)}).style(\"stroke\",function(a,b){return a.color||h(a,a.seriesIndex)}),H.watchTransition(v,\"stackedArea path\").attr(\"d\",function(a,b){return F(a.values,b)}),s.dispatch.on(\"elementMouseover.area\",function(a){D.select(\".nv-chart-\"+i+\" .nv-area-\"+a.seriesIndex).classed(\"hover\",!0)}),s.dispatch.on(\"elementMouseout.area\",function(a){D.select(\".nv-chart-\"+i+\" .nv-area-\"+a.seriesIndex).classed(\"hover\",!1)}),b.d3_stackedOffset_stackPercent=function(a){var b,c,d,e=a.length,f=a[0].length,g=[];for(c=0;f>c;++c){for(b=0,d=0;b<x.length;b++)d+=l(x[b].values[c]);if(d)for(b=0;e>b;b++)a[b][c][1]/=d;else for(b=0;e>b;b++)a[b][c][1]=0}for(c=0;f>c;++c)g[c]=0;return g}}),v.renderEnd(\"stackedArea immediate\"),b}var c,d,e={top:0,right:0,bottom:0,left:0},f=960,g=500,h=a.utils.defaultColor(),i=Math.floor(1e5*Math.random()),j=null,k=function(a){return a.x},l=function(a){return a.y},m=function(a,b){return!isNaN(l(a,b))&&null!==l(a,b)},n=\"stack\",o=\"zero\",p=\"default\",q=\"linear\",r=!1,s=a.models.scatter(),t=250,u=d3.dispatch(\"areaClick\",\"areaMouseover\",\"areaMouseout\",\"renderEnd\",\"elementClick\",\"elementMouseover\",\"elementMouseout\");s.pointSize(2.2).pointDomain([2.2,2.2]);var v=a.utils.renderWatch(u,t);return b.dispatch=u,b.scatter=s,s.dispatch.on(\"elementClick\",function(){u.elementClick.apply(this,arguments)}),s.dispatch.on(\"elementMouseover\",function(){u.elementMouseover.apply(this,arguments)}),s.dispatch.on(\"elementMouseout\",function(){u.elementMouseout.apply(this,arguments)}),b.interpolate=function(a){return arguments.length?(q=a,b):q},b.duration=function(a){return arguments.length?(t=a,v.reset(t),s.duration(t),b):t},b.dispatch=u,b.scatter=s,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return f},set:function(a){f=a}},height:{get:function(){return g},set:function(a){g=a}},defined:{get:function(){return m},set:function(a){m=a}},clipEdge:{get:function(){return r},set:function(a){r=a}},offset:{get:function(){return o},set:function(a){o=a}},order:{get:function(){return p},set:function(a){p=a}},interpolate:{get:function(){return q},set:function(a){q=a}},x:{get:function(){return k},set:function(a){k=d3.functor(a)}},y:{get:function(){return l},set:function(a){l=d3.functor(a)}},margin:{get:function(){return e},set:function(a){e.top=void 0!==a.top?a.top:e.top,e.right=void 0!==a.right?a.right:e.right,e.bottom=void 0!==a.bottom?a.bottom:e.bottom,e.left=void 0!==a.left?a.left:e.left}},color:{get:function(){return h},set:function(b){h=a.utils.getColor(b)}},style:{get:function(){return n},set:function(a){switch(n=a){case\"stack\":b.offset(\"zero\"),b.order(\"default\");break;case\"stream\":b.offset(\"wiggle\"),b.order(\"inside-out\");break;case\"stream-center\":b.offset(\"silhouette\"),b.order(\"inside-out\");break;case\"expand\":b.offset(\"expand\"),b.order(\"default\");break;case\"stack_percent\":b.offset(b.d3_stackedOffset_stackPercent),b.order(\"default\")}}},duration:{get:function(){return t},set:function(a){t=a,v.reset(t),s.duration(t)}}}),a.utils.inheritOptions(b,s),a.utils.initOptions(b),b},a.models.stackedAreaChart=function(){\"use strict\";function b(k){return J.reset(),J.models(e),s&&J.models(f),t&&J.models(g),k.each(function(k){function B(){s&&V.select(\".nv-focus .nv-x.nv-axis\").attr(\"transform\",\"translate(0,\"+R+\")\").transition().duration(G).call(f)}function J(){if(t){if(\"expand\"===e.style()||\"stack_percent\"===e.style()){var a=g.tickFormat();H&&a===N||(H=a),g.tickFormat(N)}else H&&(g.tickFormat(H),H=null);V.select(\".nv-focus .nv-y.nv-axis\").transition().duration(0).call(g)}}function O(a){var b=V.select(\".nv-focus .nv-stackedWrap\").datum(k.filter(function(a){return!a.disabled}).map(function(b,c){return{key:b.key,area:b.area,classed:b.classed,values:b.values.filter(function(b,c){return e.x()(b,c)>=a[0]&&e.x()(b,c)<=a[1]}),disableTooltip:b.disableTooltip}}));b.transition().duration(G).call(e),B(),J()}var P=d3.select(this);a.utils.initSVG(P);var Q=a.utils.availableWidth(n,P,m),R=a.utils.availableHeight(o,P,m)-(v?l.height():0);if(b.update=function(){P.transition().duration(G).call(b)},b.container=this,z.setter(M(k),b.update).getter(L(k)).update(),z.disabled=k.map(function(a){return!!a.disabled}),!A){var S;A={};for(S in z)z[S]instanceof Array?A[S]=z[S].slice(0):A[S]=z[S]}if(!(k&&k.length&&k.filter(function(a){return a.values.length}).length))return a.utils.noData(b,P),b;P.selectAll(\".nv-noData\").remove(),c=e.xScale(),d=e.yScale();var T=P.selectAll(\"g.nv-wrap.nv-stackedAreaChart\").data([k]),U=T.enter().append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-stackedAreaChart\").append(\"g\"),V=T.select(\"g\");U.append(\"g\").attr(\"class\",\"nv-legendWrap\"),U.append(\"g\").attr(\"class\",\"nv-controlsWrap\");var W=U.append(\"g\").attr(\"class\",\"nv-focus\");W.append(\"g\").attr(\"class\",\"nv-background\").append(\"rect\"),W.append(\"g\").attr(\"class\",\"nv-x nv-axis\"),W.append(\"g\").attr(\"class\",\"nv-y nv-axis\"),W.append(\"g\").attr(\"class\",\"nv-stackedWrap\"),W.append(\"g\").attr(\"class\",\"nv-interactive\");U.append(\"g\").attr(\"class\",\"nv-focusWrap\");if(r){var X=q?Q-D:Q;h.width(X),V.select(\".nv-legendWrap\").datum(k).call(h),h.height()>m.top&&(m.top=h.height(),R=a.utils.availableHeight(o,P,m)-(v?l.height():0)),V.select(\".nv-legendWrap\").attr(\"transform\",\"translate(\"+(Q-X)+\",\"+-m.top+\")\")}else V.select(\".nv-legendWrap\").selectAll(\"*\").remove();if(q){var Y=[{key:F.stacked||\"Stacked\",metaKey:\"Stacked\",disabled:\"stack\"!=e.style(),style:\"stack\"},{key:F.stream||\"Stream\",metaKey:\"Stream\",disabled:\"stream\"!=e.style(),style:\"stream\"},{key:F.expanded||\"Expanded\",metaKey:\"Expanded\",disabled:\"expand\"!=e.style(),style:\"expand\"},{key:F.stack_percent||\"Stack %\",metaKey:\"Stack_Percent\",disabled:\"stack_percent\"!=e.style(),style:\"stack_percent\"}];D=E.length/3*260,Y=Y.filter(function(a){return-1!==E.indexOf(a.metaKey)}),i.width(D).color([\"#444\",\"#444\",\"#444\"]),V.select(\".nv-controlsWrap\").datum(Y).call(i),Math.max(i.height(),h.height())>m.top&&(m.top=Math.max(i.height(),h.height()),R=a.utils.availableHeight(o,P,m)),V.select(\".nv-controlsWrap\").attr(\"transform\",\"translate(0,\"+-m.top+\")\")}else V.select(\".nv-controlsWrap\").selectAll(\"*\").remove();T.attr(\"transform\",\"translate(\"+m.left+\",\"+m.top+\")\"),u&&V.select(\".nv-y.nv-axis\").attr(\"transform\",\"translate(\"+Q+\",0)\"),w&&(j.width(Q).height(R).margin({left:m.left,top:m.top}).svgContainer(P).xScale(c),T.select(\".nv-interactive\").call(j)),V.select(\".nv-focus .nv-background rect\").attr(\"width\",Q).attr(\"height\",R),e.width(Q).height(R).color(k.map(function(a,b){return a.color||p(a,b)}).filter(function(a,b){return!k[b].disabled}));var Z=V.select(\".nv-focus .nv-stackedWrap\").datum(k.filter(function(a){return!a.disabled}));if(s&&f.scale(c)._ticks(a.utils.calcTicksX(Q/100,k)).tickSize(-R,0),t){var $;$=\"wiggle\"===e.offset()?0:a.utils.calcTicksY(R/36,k),g.scale(d)._ticks($).tickSize(-Q,0)}if(v){l.width(Q),V.select(\".nv-focusWrap\").attr(\"transform\",\"translate(0,\"+(R+m.bottom+l.margin().top)+\")\").datum(k.filter(function(a){return!a.disabled})).call(l);var _=l.brush.empty()?l.xDomain():l.brush.extent();null!==_&&O(_)}else Z.transition().call(e),B(),J();e.dispatch.on(\"areaClick.toggle\",function(a){1===k.filter(function(a){return!a.disabled}).length?k.forEach(function(a){a.disabled=!1}):k.forEach(function(b,c){b.disabled=c!=a.seriesIndex}),z.disabled=k.map(function(a){return!!a.disabled}),C.stateChange(z),b.update()}),h.dispatch.on(\"stateChange\",function(a){for(var c in a)z[c]=a[c];C.stateChange(z),b.update()}),i.dispatch.on(\"legendClick\",function(a,c){a.disabled&&(Y=Y.map(function(a){return a.disabled=!0,a}),a.disabled=!1,e.style(a.style),z.style=e.style(),C.stateChange(z),b.update())}),j.dispatch.on(\"elementMousemove\",function(c){e.clearHighlights();var d,f,g,h=[],i=0,l=!0;if(k.filter(function(a,b){return a.seriesIndex=b,!a.disabled}).forEach(function(j,k){f=a.interactiveBisect(j.values,c.pointXValue,b.x());var m=j.values[f],n=b.y()(m,f);if(null!=n&&e.highlightPoint(k,f,!0),\"undefined\"!=typeof m){\"undefined\"==typeof d&&(d=m),\"undefined\"==typeof g&&(g=b.xScale()(b.x()(m,f)));var o=\"expand\"==e.style()?m.display.y:b.y()(m,f);h.push({key:j.key,value:o,color:p(j,j.seriesIndex),point:m}),x&&\"expand\"!=e.style()&&null!=o&&(i+=o,l=!1)}}),h.reverse(),h.length>2){var m=b.yScale().invert(c.mouseY),n=null;h.forEach(function(a,b){m=Math.abs(m);var c=Math.abs(a.point.display.y0),d=Math.abs(a.point.display.y);return m>=c&&d+c>=m?void(n=b):void 0}),null!=n&&(h[n].highlight=!0)}x&&\"expand\"!=e.style()&&h.length>=2&&!l&&h.push({key:y,value:i,total:!0});var o=b.x()(d,f),q=j.tooltip.valueFormatter();\"expand\"===e.style()||\"stack_percent\"===e.style()?(I||(I=q),q=d3.format(\".1%\")):I&&(q=I,I=null),j.tooltip.valueFormatter(q).data({value:o,series:h})(),j.renderGuideLine(g)}),j.dispatch.on(\"elementMouseout\",function(a){e.clearHighlights()}),l.dispatch.on(\"onBrush\",function(a){O(a)}),C.on(\"changeState\",function(a){\"undefined\"!=typeof a.disabled&&k.length===a.disabled.length&&(k.forEach(function(b,c){b.disabled=a.disabled[c]}),z.disabled=a.disabled),\"undefined\"!=typeof a.style&&(e.style(a.style),K=a.style),b.update()})}),J.renderEnd(\"stacked Area chart immediate\"),b}var c,d,e=a.models.stackedArea(),f=a.models.axis(),g=a.models.axis(),h=a.models.legend(),i=a.models.legend(),j=a.interactiveGuideline(),k=a.models.tooltip(),l=a.models.focus(a.models.stackedArea()),m={top:30,right:25,bottom:50,left:60},n=null,o=null,p=a.utils.defaultColor(),q=!0,r=!0,s=!0,t=!0,u=!1,v=!1,w=!1,x=!0,y=\"TOTAL\",z=a.utils.state(),A=null,B=null,C=d3.dispatch(\"stateChange\",\"changeState\",\"renderEnd\"),D=250,E=[\"Stacked\",\"Stream\",\"Expanded\"],F={},G=250;z.style=e.style(),f.orient(\"bottom\").tickPadding(7),g.orient(u?\"right\":\"left\"),k.headerFormatter(function(a,b){return f.tickFormat()(a,b)}).valueFormatter(function(a,b){return g.tickFormat()(a,b)}),j.tooltip.headerFormatter(function(a,b){return f.tickFormat()(a,b)}).valueFormatter(function(a,b){return null==a?\"N/A\":g.tickFormat()(a,b)});var H=null,I=null;i.updateState(!1);var J=a.utils.renderWatch(C),K=e.style(),L=function(a){return function(){return{active:a.map(function(a){return!a.disabled}),style:e.style()}}},M=function(a){return function(b){void 0!==b.style&&(K=b.style),void 0!==b.active&&a.forEach(function(a,c){a.disabled=!b.active[c]})}},N=d3.format(\"%\");return e.dispatch.on(\"elementMouseover.tooltip\",function(a){a.point.x=e.x()(a.point),a.point.y=e.y()(a.point),k.data(a).hidden(!1)}),e.dispatch.on(\"elementMouseout.tooltip\",function(a){k.hidden(!0)}),b.dispatch=C,b.stacked=e,b.legend=h,b.controls=i,b.xAxis=f,b.x2Axis=l.xAxis,b.yAxis=g,b.y2Axis=l.yAxis,b.interactiveLayer=j,b.tooltip=k,b.focus=l,b.dispatch=C,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{width:{get:function(){return n},set:function(a){n=a}},height:{get:function(){return o},set:function(a){o=a}},showLegend:{get:function(){return r},set:function(a){r=a}},showXAxis:{get:function(){return s},set:function(a){s=a}},showYAxis:{get:function(){return t},set:function(a){t=a}},defaultState:{get:function(){return A},set:function(a){A=a}},noData:{get:function(){return B},set:function(a){B=a}},showControls:{get:function(){return q},set:function(a){q=a}},controlLabels:{get:function(){return F},set:function(a){F=a}},controlOptions:{get:function(){return E},set:function(a){E=a}},showTotalInTooltip:{get:function(){return x},set:function(a){x=a}},totalLabel:{get:function(){return y},set:function(a){y=a}},focusEnable:{get:function(){return v},set:function(a){v=a}},focusHeight:{get:function(){return l.height()},set:function(a){l.height(a)}},brushExtent:{get:function(){return l.brushExtent()},set:function(a){l.brushExtent(a)}},margin:{get:function(){return m},set:function(a){m.top=void 0!==a.top?a.top:m.top,m.right=void 0!==a.right?a.right:m.right,m.bottom=void 0!==a.bottom?a.bottom:m.bottom,m.left=void 0!==a.left?a.left:m.left}},focusMargin:{get:function(){return l.margin},set:function(a){l.margin.top=void 0!==a.top?a.top:l.margin.top,l.margin.right=void 0!==a.right?a.right:l.margin.right,l.margin.bottom=void 0!==a.bottom?a.bottom:l.margin.bottom,l.margin.left=void 0!==a.left?a.left:l.margin.left}},duration:{get:function(){return G},set:function(a){G=a,J.reset(G),e.duration(G),f.duration(G),g.duration(G)}},color:{get:function(){return p},set:function(b){p=a.utils.getColor(b),h.color(p),e.color(p),l.color(p)}},x:{get:function(){return e.x()},set:function(a){e.x(a),l.x(a)}},y:{get:function(){return e.y()},set:function(a){e.y(a),l.y(a)}},rightAlignYAxis:{get:function(){return u},set:function(a){u=a,g.orient(u?\"right\":\"left\")}},useInteractiveGuideline:{get:function(){return w},set:function(a){w=!!a,b.interactive(!a),b.useVoronoi(!a),e.scatter.interactive(!a)}}}),a.utils.inheritOptions(b,e),a.utils.initOptions(b),b},a.models.stackedAreaWithFocusChart=function(){return a.models.stackedAreaChart().margin({bottom:30}).focusEnable(!0)},a.models.sunburst=function(){\"use strict\";function b(a){var b=c(a);return b>90?180:0}function c(a){var b=Math.max(0,Math.min(2*Math.PI,F(a.x))),c=Math.max(0,Math.min(2*Math.PI,F(a.x+a.dx))),d=(b+c)/2*(180/Math.PI)-90;return d}function d(a){var b=Math.max(0,Math.min(2*Math.PI,F(a.x))),c=Math.max(0,Math.min(2*Math.PI,F(a.x+a.dx)));return(c-b)/(2*Math.PI)}function e(a){var b=Math.max(0,Math.min(2*Math.PI,F(a.x))),c=Math.max(0,Math.min(2*Math.PI,F(a.x+a.dx))),d=c-b;return d>z}function f(a,b){var c=d3.interpolate(F.domain(),[l.x,l.x+l.dx]),d=d3.interpolate(G.domain(),[l.y,1]),e=d3.interpolate(G.range(),[l.y?20:0,o]);return 0===b?function(){return J(a)}:function(b){return F.domain(c(b)),G.domain(d(b)).range(e(b)),J(a)}}function g(a){var b=d3.interpolate({x:a.x0,dx:a.dx0,y:a.y0,dy:a.dy0},a);return function(c){var d=b(c);return a.x0=d.x,a.dx0=d.dx,a.y0=d.y,a.dy0=d.dy,J(d)}}function h(a){var b=B(a);I[b]||(I[b]={});var c=I[b];c.dx=a.dx,c.x=a.x,c.dy=a.dy,c.y=a.y}function i(a){a.forEach(function(a){var b=B(a),c=I[b];c?(a.dx0=c.dx,a.x0=c.x,a.dy0=c.dy,a.y0=c.y):(a.dx0=a.dx,a.x0=a.x,a.dy0=a.dy,a.y0=a.y),h(a)})}function j(a){var d=v.selectAll(\"text\"),g=v.selectAll(\"path\");d.transition().attr(\"opacity\",0),l=a,g.transition().duration(D).attrTween(\"d\",f).each(\"end\",function(d){if(d.x>=a.x&&d.x<a.x+a.dx&&d.depth>=a.depth){var f=d3.select(this.parentNode),g=f.select(\"text\");g.transition().duration(D).text(function(a){return y(a)}).attr(\"opacity\",function(a){return e(a)?1:0}).attr(\"transform\",function(){var e=this.getBBox().width;if(0===d.depth)return\"translate(\"+e/2*-1+\",0)\";if(d.depth===a.depth)return\"translate(\"+(G(d.y)+5)+\",0)\";var f=c(d),g=b(d);return 0===g?\"rotate(\"+f+\")translate(\"+(G(d.y)+5)+\",0)\":\"rotate(\"+f+\")translate(\"+(G(d.y)+e+5)+\",0)rotate(\"+g+\")\"})}})}function k(f){return K.reset(),f.each(function(f){v=d3.select(this),m=a.utils.availableWidth(q,v,p),n=a.utils.availableHeight(r,v,p),o=Math.min(m,n)/2,G.range([0,o]);var h=v.select(\"g.nvd3.nv-wrap.nv-sunburst\");h[0][0]?h.attr(\"transform\",\"translate(\"+(m/2+p.left+p.right)+\",\"+(n/2+p.top+p.bottom)+\")\"):h=v.append(\"g\").attr(\"class\",\"nvd3 nv-wrap nv-sunburst nv-chart-\"+u).attr(\"transform\",\"translate(\"+(m/2+p.left+p.right)+\",\"+(n/2+p.top+p.bottom)+\")\"),v.on(\"click\",function(a,b){E.chartClick({data:a,index:b,pos:d3.event,id:u})}),H.value(t[s]||t.count);var k=H.nodes(f[0]).reverse();i(k);var l=h.selectAll(\".arc-container\").data(k,B),z=l.enter().append(\"g\").attr(\"class\",\"arc-container\");z.append(\"path\").attr(\"d\",J).style(\"fill\",function(a){return a.color?a.color:w(C?(a.children?a:a.parent).name:a.name)}).style(\"stroke\",\"#FFF\").on(\"click\",j).on(\"mouseover\",function(a,b){d3.select(this).classed(\"hover\",!0).style(\"opacity\",.8),E.elementMouseover({data:a,color:d3.select(this).style(\"fill\"),percent:d(a)})}).on(\"mouseout\",function(a,b){d3.select(this).classed(\"hover\",!1).style(\"opacity\",1),E.elementMouseout({data:a})}).on(\"mousemove\",function(a,b){E.elementMousemove({data:a})}),l.each(function(a){d3.select(this).select(\"path\").transition().duration(D).attrTween(\"d\",g)}),x&&(l.selectAll(\"text\").remove(),l.append(\"text\").text(function(a){return y(a)}).transition().duration(D).attr(\"opacity\",function(a){return e(a)?1:0}).attr(\"transform\",function(a){var d=this.getBBox().width;if(0===a.depth)return\"rotate(0)translate(\"+d/2*-1+\",0)\";var e=c(a),f=b(a);return 0===f?\"rotate(\"+e+\")translate(\"+(G(a.y)+5)+\",0)\":\"rotate(\"+e+\")translate(\"+(G(a.y)+d+5)+\",0)rotate(\"+f+\")\"})),j(k[k.length-1]),l.exit().transition().duration(D).attr(\"opacity\",0).each(\"end\",function(a){var b=B(a);I[b]=void 0}).remove()}),K.renderEnd(\"sunburst immediate\"),k}var l,m,n,o,p={top:0,right:0,bottom:0,left:0},q=600,r=600,s=\"count\",t={count:function(a){return 1},value:function(a){return a.value||a.size},size:function(a){return a.value||a.size}},u=Math.floor(1e4*Math.random()),v=null,w=a.utils.defaultColor(),x=!1,y=function(a){return\"count\"===s?a.name+\" #\"+a.value:a.name+\" \"+(a.value||a.size)},z=.02,A=function(a,b){return a.name>b.name},B=function(a,b){return a.name},C=!0,D=500,E=d3.dispatch(\"chartClick\",\"elementClick\",\"elementDblClick\",\"elementMousemove\",\"elementMouseover\",\"elementMouseout\",\"renderEnd\"),F=d3.scale.linear().range([0,2*Math.PI]),G=d3.scale.sqrt(),H=d3.layout.partition().sort(A),I={},J=d3.svg.arc().startAngle(function(a){return Math.max(0,Math.min(2*Math.PI,F(a.x)))}).endAngle(function(a){return Math.max(0,Math.min(2*Math.PI,F(a.x+a.dx)))}).innerRadius(function(a){return Math.max(0,G(a.y))}).outerRadius(function(a){return Math.max(0,G(a.y+a.dy))}),K=a.utils.renderWatch(E);return k.dispatch=E,k.options=a.utils.optionsFunc.bind(k),k._options=Object.create({},{width:{get:function(){return q},set:function(a){q=a}},height:{get:function(){return r},set:function(a){r=a}},mode:{get:function(){return s},set:function(a){s=a}},id:{get:function(){return u},set:function(a){u=a}},duration:{get:function(){return D},set:function(a){D=a}},groupColorByParent:{get:function(){return C},set:function(a){C=!!a}},showLabels:{get:function(){return x},set:function(a){x=!!a}},labelFormat:{get:function(){return y},set:function(a){y=a}},labelThreshold:{get:function(){return z},set:function(a){z=a}},sort:{get:function(){return A},set:function(a){A=a}},key:{get:function(){return B},set:function(a){B=a}},margin:{get:function(){return p},set:function(a){p.top=void 0!=a.top?a.top:p.top,p.right=void 0!=a.right?a.right:p.right,p.bottom=void 0!=a.bottom?a.bottom:p.bottom,p.left=void 0!=a.left?a.left:p.left}},color:{get:function(){return w},set:function(b){w=a.utils.getColor(b)}}}),a.utils.initOptions(k),k},a.models.sunburstChart=function(){\"use strict\";function b(d){return n.reset(),n.models(c),d.each(function(d){var h=d3.select(this);a.utils.initSVG(h);var i=a.utils.availableWidth(f,h,e),j=a.utils.availableHeight(g,h,e);return b.update=function(){0===l?h.call(b):h.transition().duration(l).call(b)},b.container=h,d&&d.length?(h.selectAll(\".nv-noData\").remove(),c.width(i).height(j).margin(e),void h.call(c)):(a.utils.noData(b,h),b)}),n.renderEnd(\"sunburstChart immediate\"),b}var c=a.models.sunburst(),d=a.models.tooltip(),e={top:30,right:20,bottom:20,left:20},f=null,g=null,h=a.utils.defaultColor(),i=!1,j=(Math.round(1e5*Math.random()),null),k=null,l=250,m=d3.dispatch(\"stateChange\",\"changeState\",\"renderEnd\"),n=a.utils.renderWatch(m);return d.duration(0).headerEnabled(!1).valueFormatter(function(a){return a}),c.dispatch.on(\"elementMouseover.tooltip\",function(a){a.series={key:a.data.name,value:a.data.value||a.data.size,color:a.color,percent:a.percent},i||(delete a.percent,delete a.series.percent),d.data(a).hidden(!1)}),c.dispatch.on(\"elementMouseout.tooltip\",function(a){d.hidden(!0)}),c.dispatch.on(\"elementMousemove.tooltip\",function(a){d()}),b.dispatch=m,b.sunburst=c,b.tooltip=d,b.options=a.utils.optionsFunc.bind(b),b._options=Object.create({},{noData:{get:function(){return k},set:function(a){k=a}},defaultState:{get:function(){return j},set:function(a){j=a}},showTooltipPercent:{get:function(){return i},set:function(a){i=a}},color:{get:function(){return h},set:function(a){h=a,c.color(h)}},duration:{get:function(){return l},set:function(a){l=a,n.reset(l),c.duration(l)}},margin:{get:function(){return e},set:function(a){e.top=void 0!==a.top?a.top:e.top,e.right=void 0!==a.right?a.right:e.right,e.bottom=void 0!==a.bottom?a.bottom:e.bottom,e.left=void 0!==a.left?a.left:e.left,c.margin(e)}}}),a.utils.inheritOptions(b,c),a.utils.initOptions(b),b},a.version=\"1.8.4-dev\"}();"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/run.sh",
    "content": "#!/bin/bash\n\n# ./run.sh gemm gemm_settings.txt\n# ./run.sh lazy_gemm lazy_gemm_settings.txt\n# ./run.sh gemv gemv_settings.txt\n# ./run.sh trmv_up gemv_square_settings.txt\n# ...\n\n# Examples of environment variables to be set:\n#   PREFIX=\"haswell-fma-\"\n#   CXX_FLAGS=\"-mfma\"\n#   CXX=clang++\n\n# Options:\n#   -up : enforce the recomputation of existing data, and keep best results as a merging strategy\n#   -s  : recompute selected changesets only and keep bests\n#   -np : no plotting of results, just generate the data\n\nbench=$1\nsettings_file=$2\n\nif [[ \"$*\" =~ '-up' ]]; then\n  update=true\nelse\n  update=false\nfi\n\nif [[ \"$*\" =~ '-s' ]]; then\n  selected=true\nelse\n  selected=false\nfi\n\nif [[ \"$*\" =~ '-np' ]]; then\n  do_plot=false\nelse\n  do_plot=true\nfi\n\n\nWORKING_DIR=${PREFIX:?\"default\"}\n\nif [ -z \"$PREFIX\" ]; then\n  WORKING_DIR_PREFIX=\"$WORKING_DIR/\"\nelse\n  WORKING_DIR_PREFIX=\"$WORKING_DIR/$PREFIX-\"\nfi\necho \"WORKING_DIR_PREFIX=$WORKING_DIR_PREFIX\"\nmkdir -p $WORKING_DIR\n\nglobal_args=\"$*\"\n\nif $selected ; then\n echo \"Recompute selected changesets only and keep bests\"\nelif $update ; then\n echo \"(Re-)Compute all changesets and keep bests\"\nelse\n echo \"Skip previously computed changesets\"\nfi\n\n\n\nif [ ! -d \"eigen_src\" ]; then\n  git clone https://gitlab.com/libeigen/eigen.git eigen_src\nelse\n  cd eigen_src\n  git pull\n  cd ..\nfi\n\nif [ -z \"$CXX\" ]; then\n  CXX=g++\nfi\n\nfunction make_backup\n{\n  if [ -f \"$1.out\" ]; then\n    mv \"$1.out\" \"$1.backup\"\n  fi\n}\n\nfunction merge\n{\n  count1=`echo $1 |  wc -w`\n  count2=`echo $2 |  wc -w`\n  \n  if [ $count1 == $count2 ]; then\n    a=( $1 ); b=( $2 )\n    res=\"\"\n    for (( i=0 ; i<$count1 ; i++ )); do\n      ai=${a[$i]}; bi=${b[$i]}\n      tmp=`echo \"if ($ai > $bi) $ai else $bi \" | bc -l`\n      res=\"$res $tmp\"\n    done\n    echo $res\n\n  else\n    echo $1\n  fi\n}\n\nfunction test_current \n{\n  rev=$1\n  scalar=$2\n  name=$3\n  \n  prev=\"\"\n  if [ -e \"$name.backup\" ]; then\n    prev=`grep $rev \"$name.backup\" | cut -d ' ' -f 2-`\n  fi\n  res=$prev\n  count_rev=`echo $prev |  wc -w`\n  count_ref=`cat $settings_file |  wc -l`\n  if echo \"$global_args\" | grep \"$rev\" > /dev/null; then\n    rev_found=true\n  else\n    rev_found=false\n  fi\n#  echo $update et $selected et $rev_found because $rev et \"$global_args\"\n#  echo $count_rev et $count_ref\n  if $update || [ $count_rev != $count_ref ] || ( $selected &&  $rev_found ); then\n    echo \"RUN: $CXX -O3 -DNDEBUG -march=native $CXX_FLAGS -I eigen_src $bench.cpp -DSCALAR=$scalar -o $name\"\n    if $CXX -O3 -DNDEBUG -march=native $CXX_FLAGS -I eigen_src $bench.cpp -DSCALAR=$scalar -o $name; then\n      curr=`./$name $settings_file`\n      if [ $count_rev == $count_ref ]; then\n        echo \"merge previous $prev\"\n        echo \"with new       $curr\"\n      else\n        echo \"got            $curr\"\n      fi\n      res=`merge \"$curr\" \"$prev\"`\n#       echo $res\n      echo \"$rev $res\" >> $name.out\n    else\n      echo \"Compilation failed, skip rev $rev\"\n    fi\n  else\n    echo \"Skip existing results for $rev / $name\"\n    echo \"$rev $res\" >> $name.out\n  fi\n}\n\nmake_backup $WORKING_DIR_PREFIX\"s\"$bench\nmake_backup $WORKING_DIR_PREFIX\"d\"$bench\nmake_backup $WORKING_DIR_PREFIX\"c\"$bench\n\ncut -f1 -d\"#\" < changesets.txt | grep -E '[[:alnum:]]' | while read rev\ndo\n  if [ ! -z '$rev' ]; then\n    rev2=`echo $rev | cut -f 2 -d':'`\n    echo \"Testing rev $rev, $rev2\"\n    cd eigen_src\n    git checkout $rev2 > /dev/null\n    actual_rev=`git rev-parse --short HEAD`\n    cd ..\n    \n    test_current $actual_rev float                  $WORKING_DIR_PREFIX\"s\"$bench\n    test_current $actual_rev double                 $WORKING_DIR_PREFIX\"d\"$bench\n    test_current $actual_rev \"std::complex<double>\" $WORKING_DIR_PREFIX\"c\"$bench\n  fi\n  \ndone\n\necho \"Float:\"\ncat $WORKING_DIR_PREFIX\"s\"\"$bench.out\"\necho \" \"\n\necho \"Double:\"\ncat $WORKING_DIR_PREFIX\"d\"\"$bench.out\"\necho \"\"\n\necho \"Complex:\"\ncat $WORKING_DIR_PREFIX\"c\"\"$bench.out\"\necho \"\"\n\nif $do_plot ; then\n\n./make_plot.sh $WORKING_DIR_PREFIX\"s\"$bench $bench $settings_file\n./make_plot.sh $WORKING_DIR_PREFIX\"d\"$bench $bench $settings_file\n./make_plot.sh $WORKING_DIR_PREFIX\"c\"$bench $bench $settings_file\n\nfi\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/runall.sh",
    "content": "#!/bin/bash\n\n# ./runall.sh \"Title\"\n\n# Examples of environment variables to be set:\n#   PREFIX=\"haswell-fma-\"\n#   CXX_FLAGS=\"-mfma\"\n#   CXX=clang++\n\n# Options:\n#   -up : enforce the recomputation of existing data, and keep best results as a merging strategy\n#   -s  : recompute selected changesets only and keep bests\n#   -np : no plotting of results, just generate the data\n\nif [[ \"$*\" =~ '-np' ]]; then\n  do_plot=false\nelse\n  do_plot=true\nfi\n\n./run.sh gemm gemm_settings.txt $*\n./run.sh lazy_gemm lazy_gemm_settings.txt $*\n./run.sh gemv gemv_settings.txt $*\n./run.sh gemvt gemv_settings.txt $*\n./run.sh trmv_up gemv_square_settings.txt $*\n./run.sh trmv_lo gemv_square_settings.txt $*\n./run.sh trmv_upt gemv_square_settings.txt $*\n./run.sh trmv_lot gemv_square_settings.txt $*\n./run.sh llt gemm_square_settings.txt $*\n\nif $do_plot ; then\n\n# generate html file\n\nfunction print_td {\n  echo '<td><a href=\"'$PREFIX'-'$1\"$2\"'.html\"><img src=\"'$PREFIX'-'$1\"$2\"'.png\" title=\"'$3'\"></a></td>' >> $htmlfile\n}\n\nfunction print_tr {\n  echo '<tr><th colspan=\"3\">'\"$2\"'</th></tr>' >> $htmlfile\n  echo '<tr>' >> $htmlfile\n  print_td s $1 float\n  print_td d $1 double\n  print_td c $1 complex\n  echo '</tr>' >> $htmlfile\n}\n\nif [ -n \"$PREFIX\" ]; then\n\n\ncp resources/s1.js $PREFIX/\ncp resources/s2.js $PREFIX/\n\nhtmlfile=\"$PREFIX/index.html\"\ncat resources/header.html > $htmlfile\n\necho '<h1>'$1'</h1>' >> $htmlfile\necho '<table>' >> $htmlfile\nprint_tr gemm       'C += A &middot; B   &nbsp; (gemm)'\nprint_tr lazy_gemm  'C += A &middot; B   &nbsp; (gemm lazy)'\nprint_tr gemv       'y += A &middot; x   &nbsp; (gemv)'\nprint_tr gemvt      'y += A<sup>T</sup> &middot; x  &nbsp; (gemv)'\nprint_tr trmv_up    'y += U &middot; x   &nbsp; (trmv)'\nprint_tr trmv_upt   'y += U<sup>T</sup> &middot; x  &nbsp; (trmv)'\nprint_tr trmv_lo    'y += L &middot; x   &nbsp; (trmv)'\nprint_tr trmv_lot   'y += L<sup>T</sup> &middot; x  &nbsp; (trmv)'\nprint_tr trmv_lot   'L &middot; L<sup>T<sup> = A &nbsp;  (Cholesky,potrf)'\n\ncat resources/footer.html >> $htmlfile\n\nfi\nfi\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/trmv_lo.cpp",
    "content": "#include \"gemv_common.h\"\n\nEIGEN_DONT_INLINE\nvoid trmv(const Mat &A, const Vec &B, Vec &C)\n{\n  C.noalias() += A.triangularView<Lower>() * B;\n}\n\nint main(int argc, char **argv)\n{\n  return main_gemv(argc, argv, trmv);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/trmv_lot.cpp",
    "content": "#include \"gemv_common.h\"\n\nEIGEN_DONT_INLINE\nvoid trmv(const Mat &A, Vec &B, const Vec &C)\n{\n  B.noalias() += A.transpose().triangularView<Lower>() * C;\n}\n\nint main(int argc, char **argv)\n{\n  return main_gemv(argc, argv, trmv);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/trmv_up.cpp",
    "content": "#include \"gemv_common.h\"\n\nEIGEN_DONT_INLINE\nvoid trmv(const Mat &A, const Vec &B, Vec &C)\n{\n  C.noalias() += A.triangularView<Upper>() * B;\n}\n\nint main(int argc, char **argv)\n{\n  return main_gemv(argc, argv, trmv);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/perf_monitoring/trmv_upt.cpp",
    "content": "#include \"gemv_common.h\"\n\nEIGEN_DONT_INLINE\nvoid trmv(const Mat &A, Vec &B, const Vec &C)\n{\n  B.noalias() += A.transpose().triangularView<Upper>() * C;\n}\n\nint main(int argc, char **argv)\n{\n  return main_gemv(argc, argv, trmv);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/product_threshold.cpp",
    "content": "\n#include <iostream>\n#include <Eigen/Core>\n#include <bench/BenchTimer.h>\n\nusing namespace Eigen;\nusing namespace std;\n\n#define END 9\n\ntemplate<int S> struct map_size { enum { ret = S }; };\ntemplate<>  struct map_size<10> { enum { ret = 20 }; };\ntemplate<>  struct map_size<11> { enum { ret = 50 }; };\ntemplate<>  struct map_size<12> { enum { ret = 100 }; };\ntemplate<>  struct map_size<13> { enum { ret = 300 }; };\n\ntemplate<int M, int N,int K> struct alt_prod\n{\n  enum {\n    ret = M==1 && N==1 ? InnerProduct\n        : K==1 ? OuterProduct\n        : M==1 ? GemvProduct\n        : N==1 ? GemvProduct\n        : GemmProduct\n  };\n};\n        \nvoid print_mode(int mode)\n{\n  if(mode==InnerProduct) std::cout << \"i\";\n  if(mode==OuterProduct) std::cout << \"o\";\n  if(mode==CoeffBasedProductMode) std::cout << \"c\";\n  if(mode==LazyCoeffBasedProductMode) std::cout << \"l\";\n  if(mode==GemvProduct) std::cout << \"v\";\n  if(mode==GemmProduct) std::cout << \"m\";\n}\n\ntemplate<int Mode, typename Lhs, typename Rhs, typename Res>\nEIGEN_DONT_INLINE void prod(const Lhs& a, const Rhs& b, Res& c)\n{\n  c.noalias() += typename ProductReturnType<Lhs,Rhs,Mode>::Type(a,b);\n}\n\ntemplate<int M, int N, int K, typename Scalar, int Mode>\nEIGEN_DONT_INLINE void bench_prod()\n{\n  typedef Matrix<Scalar,M,K> Lhs; Lhs a; a.setRandom();\n  typedef Matrix<Scalar,K,N> Rhs; Rhs b; b.setRandom();\n  typedef Matrix<Scalar,M,N> Res; Res c; c.setRandom();\n\n  BenchTimer t;\n  double n = 2.*double(M)*double(N)*double(K);\n  int rep = 100000./n;\n  rep /= 2;\n  if(rep<1) rep = 1;\n  do {\n    rep *= 2;\n    t.reset();\n    BENCH(t,1,rep,prod<CoeffBasedProductMode>(a,b,c));\n  } while(t.best()<0.1);\n  \n  t.reset();\n  BENCH(t,5,rep,prod<Mode>(a,b,c));\n\n  print_mode(Mode);\n  std::cout << int(1e-6*n*rep/t.best()) << \"\\t\";\n}\n\ntemplate<int N> struct print_n;\ntemplate<int M, int N, int K> struct loop_on_m;\ntemplate<int M, int N, int K, typename Scalar, int Mode> struct loop_on_n;\n\ntemplate<int M, int N, int K>\nstruct loop_on_k\n{\n  static void run()\n  {\n    std::cout << \"K=\" << K << \"\\t\";\n    print_n<N>::run();\n    std::cout << \"\\n\";\n\n    loop_on_m<M,N,K>::run();\n    std::cout << \"\\n\\n\";\n\n    loop_on_k<M,N,K+1>::run();\n  }\n};\n\ntemplate<int M, int N>\nstruct loop_on_k<M,N,END> { static void run(){} };\n\n\ntemplate<int M, int N, int K>\nstruct loop_on_m\n{\n  static void run()\n  {\n    std::cout << M << \"f\\t\";\n    loop_on_n<M,N,K,float,CoeffBasedProductMode>::run();\n    std::cout << \"\\n\";\n    \n    std::cout << M << \"f\\t\";\n    loop_on_n<M,N,K,float,-1>::run();\n    std::cout << \"\\n\";\n\n    loop_on_m<M+1,N,K>::run();\n  }\n};\n\ntemplate<int N, int K>\nstruct loop_on_m<END,N,K> { static void run(){} };\n\ntemplate<int M, int N, int K, typename Scalar, int Mode>\nstruct loop_on_n\n{\n  static void run()\n  {\n    bench_prod<M,N,K,Scalar,Mode==-1? alt_prod<M,N,K>::ret : Mode>();\n    \n    loop_on_n<M,N+1,K,Scalar,Mode>::run();\n  }\n};\n\ntemplate<int M, int K, typename Scalar, int Mode>\nstruct loop_on_n<M,END,K,Scalar,Mode> { static void run(){} };\n\ntemplate<int N> struct print_n\n{\n  static void run()\n  {\n    std::cout << map_size<N>::ret << \"\\t\";\n    print_n<N+1>::run();\n  }\n};\n\ntemplate<> struct print_n<END> { static void run(){} };\n\nint main()\n{\n  loop_on_k<1,1,1>::run();\n  \n  return 0; \n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/quat_slerp.cpp",
    "content": "\n#include <iostream>\n#include <Eigen/Geometry>\n#include <bench/BenchTimer.h>\nusing namespace Eigen;\nusing namespace std;\n\n\n\ntemplate<typename Q>\nEIGEN_DONT_INLINE Q nlerp(const Q& a, const Q& b, typename Q::Scalar t)\n{\n  return Q((a.coeffs() * (1.0-t) + b.coeffs() * t).normalized());\n}\n\ntemplate<typename Q>\nEIGEN_DONT_INLINE Q slerp_eigen(const Q& a, const Q& b, typename Q::Scalar t)\n{\n  return a.slerp(t,b);\n}\n\ntemplate<typename Q>\nEIGEN_DONT_INLINE Q slerp_legacy(const Q& a, const Q& b, typename Q::Scalar t)\n{\n  typedef typename Q::Scalar Scalar;\n  static const Scalar one = Scalar(1) - dummy_precision<Scalar>();\n  Scalar d = a.dot(b);\n  Scalar absD = internal::abs(d);\n  if (absD>=one)\n    return a;\n\n  // theta is the angle between the 2 quaternions\n  Scalar theta = std::acos(absD);\n  Scalar sinTheta = internal::sin(theta);\n\n  Scalar scale0 = internal::sin( ( Scalar(1) - t ) * theta) / sinTheta;\n  Scalar scale1 = internal::sin( ( t * theta) ) / sinTheta;\n  if (d<0)\n    scale1 = -scale1;\n\n  return Q(scale0 * a.coeffs() + scale1 * b.coeffs());\n}\n\ntemplate<typename Q>\nEIGEN_DONT_INLINE Q slerp_legacy_nlerp(const Q& a, const Q& b, typename Q::Scalar t)\n{\n  typedef typename Q::Scalar Scalar;\n  static const Scalar one = Scalar(1) - epsilon<Scalar>();\n  Scalar d = a.dot(b);\n  Scalar absD = internal::abs(d);\n  \n  Scalar scale0;\n  Scalar scale1;\n  \n  if (absD>=one)\n  {\n    scale0 = Scalar(1) - t;\n    scale1 = t;\n  }\n  else\n  {\n    // theta is the angle between the 2 quaternions\n    Scalar theta = std::acos(absD);\n    Scalar sinTheta = internal::sin(theta);\n\n    scale0 = internal::sin( ( Scalar(1) - t ) * theta) / sinTheta;\n    scale1 = internal::sin( ( t * theta) ) / sinTheta;\n    if (d<0)\n      scale1 = -scale1;\n  }\n\n  return Q(scale0 * a.coeffs() + scale1 * b.coeffs());\n}\n\ntemplate<typename T>\ninline T sin_over_x(T x)\n{\n  if (T(1) + x*x == T(1))\n    return T(1);\n  else\n    return std::sin(x)/x;\n}\n\ntemplate<typename Q>\nEIGEN_DONT_INLINE Q slerp_rw(const Q& a, const Q& b, typename Q::Scalar t)\n{\n  typedef typename Q::Scalar Scalar;\n  \n  Scalar d = a.dot(b);\n  Scalar theta;\n  if (d<0.0)\n    theta = /*M_PI -*/ Scalar(2)*std::asin( (a.coeffs()+b.coeffs()).norm()/2 );\n  else\n    theta = Scalar(2)*std::asin( (a.coeffs()-b.coeffs()).norm()/2 );\n  \n  // theta is the angle between the 2 quaternions\n//   Scalar theta = std::acos(absD);\n  Scalar sinOverTheta = sin_over_x(theta);\n\n  Scalar scale0 = (Scalar(1)-t)*sin_over_x( ( Scalar(1) - t ) * theta) / sinOverTheta;\n  Scalar scale1 = t * sin_over_x( ( t * theta) ) / sinOverTheta;\n  if (d<0)\n    scale1 = -scale1;\n\n  return Quaternion<Scalar>(scale0 * a.coeffs() + scale1 * b.coeffs());\n}\n\ntemplate<typename Q>\nEIGEN_DONT_INLINE Q slerp_gael(const Q& a, const Q& b, typename Q::Scalar t)\n{\n  typedef typename Q::Scalar Scalar;\n  \n  Scalar d = a.dot(b);\n  Scalar theta;\n//   theta = Scalar(2) * atan2((a.coeffs()-b.coeffs()).norm(),(a.coeffs()+b.coeffs()).norm());\n//   if (d<0.0)\n//     theta = M_PI-theta;\n  \n  if (d<0.0)\n    theta = /*M_PI -*/ Scalar(2)*std::asin( (-a.coeffs()-b.coeffs()).norm()/2 );\n  else\n    theta = Scalar(2)*std::asin( (a.coeffs()-b.coeffs()).norm()/2 );\n  \n  \n  Scalar scale0;\n  Scalar scale1;\n  if(theta*theta-Scalar(6)==-Scalar(6))\n  {\n    scale0 = Scalar(1) - t;\n    scale1 = t;\n  }\n  else\n  {\n    Scalar sinTheta = std::sin(theta);\n    scale0 = internal::sin( ( Scalar(1) - t ) * theta) / sinTheta;\n    scale1 = internal::sin( ( t * theta) ) / sinTheta;\n    if (d<0)\n      scale1 = -scale1;\n  }\n\n  return Quaternion<Scalar>(scale0 * a.coeffs() + scale1 * b.coeffs());\n}\n\nint main()\n{\n  typedef double RefScalar;\n  typedef float TestScalar;\n  \n  typedef Quaternion<RefScalar>  Qd;\n  typedef Quaternion<TestScalar> Qf;\n  \n  unsigned int g_seed = (unsigned int) time(NULL);\n  std::cout << g_seed << \"\\n\";\n//   g_seed = 1259932496;\n  srand(g_seed);\n  \n  Matrix<RefScalar,Dynamic,1> maxerr(7);\n  maxerr.setZero();\n  \n  Matrix<RefScalar,Dynamic,1> avgerr(7);\n  avgerr.setZero();\n  \n  cout << \"double=>float=>double       nlerp        eigen        legacy(snap)         legacy(nlerp)        rightway         gael's criteria\\n\";\n  \n  int rep = 100;\n  int iters = 40;\n  for (int w=0; w<rep; ++w)\n  {\n    Qf a, b;\n    a.coeffs().setRandom();\n    a.normalize();\n    b.coeffs().setRandom();\n    b.normalize();\n    \n    Qf c[6];\n    \n    Qd ar(a.cast<RefScalar>());\n    Qd br(b.cast<RefScalar>());\n    Qd cr;\n    \n    \n    \n    cout.precision(8);\n    cout << std::scientific;\n    for (int i=0; i<iters; ++i)\n    {\n      RefScalar t = 0.65;\n      cr = slerp_rw(ar,br,t);\n      \n      Qf refc = cr.cast<TestScalar>();\n      c[0] = nlerp(a,b,t);\n      c[1] = slerp_eigen(a,b,t);\n      c[2] = slerp_legacy(a,b,t);\n      c[3] = slerp_legacy_nlerp(a,b,t);\n      c[4] = slerp_rw(a,b,t);\n      c[5] = slerp_gael(a,b,t);\n      \n      VectorXd err(7);\n      err[0] = (cr.coeffs()-refc.cast<RefScalar>().coeffs()).norm();\n//       std::cout << err[0] << \"    \";\n      for (int k=0; k<6; ++k)\n      {\n        err[k+1] = (c[k].coeffs()-refc.coeffs()).norm();\n//         std::cout << err[k+1] << \"    \";\n      }\n      maxerr = maxerr.cwise().max(err);\n      avgerr += err;\n//       std::cout << \"\\n\";\n      b = cr.cast<TestScalar>();\n      br = cr;\n    }\n//     std::cout << \"\\n\";\n  }\n  avgerr /= RefScalar(rep*iters);\n  cout << \"\\n\\nAccuracy:\\n\"\n       << \"  max: \" << maxerr.transpose() << \"\\n\";\n  cout << \"  avg: \" << avgerr.transpose() << \"\\n\";\n  \n  // perf bench\n  Quaternionf a,b;\n  a.coeffs().setRandom();\n  a.normalize();\n  b.coeffs().setRandom();\n  b.normalize();\n  //b = a;\n  float s = 0.65;\n    \n  #define BENCH(FUNC) {\\\n    BenchTimer t; \\\n    for(int k=0; k<2; ++k) {\\\n      t.start(); \\\n      for(int i=0; i<1000000; ++i) \\\n        FUNC(a,b,s); \\\n      t.stop(); \\\n    } \\\n    cout << \"  \" << #FUNC << \" => \\t \" << t.value() << \"s\\n\"; \\\n  }\n  \n  cout << \"\\nSpeed:\\n\" << std::fixed;\n  BENCH(nlerp);\n  BENCH(slerp_eigen);\n  BENCH(slerp_legacy);\n  BENCH(slerp_legacy_nlerp);\n  BENCH(slerp_rw);\n  BENCH(slerp_gael);\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/quatmul.cpp",
    "content": "#include <iostream>\n#include <Eigen/Core>\n#include <Eigen/Geometry>\n#include <bench/BenchTimer.h>\n\nusing namespace Eigen; \n\ntemplate<typename Quat>\nEIGEN_DONT_INLINE void quatmul_default(const Quat& a, const Quat& b, Quat& c)\n{\n  c = a * b;\n}\n\ntemplate<typename Quat>\nEIGEN_DONT_INLINE void quatmul_novec(const Quat& a, const Quat& b, Quat& c)\n{\n  c = internal::quat_product<0, Quat, Quat, typename Quat::Scalar, Aligned>::run(a,b);\n}\n\ntemplate<typename Quat> void bench(const std::string& label)\n{\n  int tries = 10;\n  int rep = 1000000;\n  BenchTimer t;\n  \n  Quat a(4, 1, 2, 3);\n  Quat b(2, 3, 4, 5);\n  Quat c;\n  \n  std::cout.precision(3);\n  \n  BENCH(t, tries, rep, quatmul_default(a,b,c));\n  std::cout << label << \" default \" << 1e3*t.best(CPU_TIMER) << \"ms  \\t\" << 1e-6*double(rep)/(t.best(CPU_TIMER)) << \" M mul/s\\n\";\n  \n  BENCH(t, tries, rep, quatmul_novec(a,b,c));\n  std::cout << label << \" novec   \" << 1e3*t.best(CPU_TIMER) << \"ms  \\t\" << 1e-6*double(rep)/(t.best(CPU_TIMER)) << \" M mul/s\\n\";\n}\n\nint main()\n{\n  bench<Quaternionf>(\"float \");\n  bench<Quaterniond>(\"double\");\n\n  return 0;\n\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/sparse_cholesky.cpp",
    "content": "// #define EIGEN_TAUCS_SUPPORT\n// #define EIGEN_CHOLMOD_SUPPORT\n#include <iostream>\n#include <Eigen/Sparse>\n\n// g++ -DSIZE=10000 -DDENSITY=0.001  sparse_cholesky.cpp -I.. -DDENSEMATRI -O3 -g0 -DNDEBUG   -DNBTRIES=1 -I /home/gael/Coding/LinearAlgebra/taucs_full/src/ -I/home/gael/Coding/LinearAlgebra/taucs_full/build/linux/  -L/home/gael/Coding/LinearAlgebra/taucs_full/lib/linux/ -ltaucs /home/gael/Coding/LinearAlgebra/GotoBLAS/libgoto.a -lpthread -I /home/gael/Coding/LinearAlgebra/SuiteSparse/CHOLMOD/Include/ $CHOLLIB -I /home/gael/Coding/LinearAlgebra/SuiteSparse/UFconfig/ /home/gael/Coding/LinearAlgebra/SuiteSparse/CCOLAMD/Lib/libccolamd.a   /home/gael/Coding/LinearAlgebra/SuiteSparse/CHOLMOD/Lib/libcholmod.a -lmetis /home/gael/Coding/LinearAlgebra/SuiteSparse/AMD/Lib/libamd.a  /home/gael/Coding/LinearAlgebra/SuiteSparse/CAMD/Lib/libcamd.a   /home/gael/Coding/LinearAlgebra/SuiteSparse/CCOLAMD/Lib/libccolamd.a  /home/gael/Coding/LinearAlgebra/SuiteSparse/COLAMD/Lib/libcolamd.a -llapack && ./a.out\n\n#define NOGMM\n#define NOMTL\n\n#ifndef SIZE\n#define SIZE 10\n#endif\n\n#ifndef DENSITY\n#define DENSITY 0.01\n#endif\n\n#ifndef REPEAT\n#define REPEAT 1\n#endif\n\n#include \"BenchSparseUtil.h\"\n\n#ifndef MINDENSITY\n#define MINDENSITY 0.0004\n#endif\n\n#ifndef NBTRIES\n#define NBTRIES 10\n#endif\n\n#define BENCH(X) \\\n  timer.reset(); \\\n  for (int _j=0; _j<NBTRIES; ++_j) { \\\n    timer.start(); \\\n    for (int _k=0; _k<REPEAT; ++_k) { \\\n        X  \\\n  } timer.stop(); }\n\n// typedef SparseMatrix<Scalar,UpperTriangular> EigenSparseTriMatrix;\ntypedef SparseMatrix<Scalar,SelfAdjoint|LowerTriangular> EigenSparseSelfAdjointMatrix;\n\nvoid fillSpdMatrix(float density, int rows, int cols,  EigenSparseSelfAdjointMatrix& dst)\n{\n  dst.startFill(rows*cols*density);\n  for(int j = 0; j < cols; j++)\n  {\n    dst.fill(j,j) = internal::random<Scalar>(10,20);\n    for(int i = j+1; i < rows; i++)\n    {\n      Scalar v = (internal::random<float>(0,1) < density) ? internal::random<Scalar>() : 0;\n      if (v!=0)\n        dst.fill(i,j) = v;\n    }\n\n  }\n  dst.endFill();\n}\n\n#include <Eigen/Cholesky>\n\ntemplate<int Backend>\nvoid doEigen(const char* name, const EigenSparseSelfAdjointMatrix& sm1, int flags = 0)\n{\n  std::cout << name << \"...\" << std::flush;\n  BenchTimer timer;\n  timer.start();\n  SparseLLT<EigenSparseSelfAdjointMatrix,Backend> chol(sm1, flags);\n  timer.stop();\n  std::cout << \":\\t\" << timer.value() << endl;\n\n  std::cout << \"  nnz: \" << sm1.nonZeros() << \" => \" << chol.matrixL().nonZeros() << \"\\n\";\n//   std::cout << \"sparse\\n\" << chol.matrixL() << \"%\\n\";\n}\n\nint main(int argc, char *argv[])\n{\n  int rows = SIZE;\n  int cols = SIZE;\n  float density = DENSITY;\n  BenchTimer timer;\n\n  VectorXf b = VectorXf::Random(cols);\n  VectorXf x = VectorXf::Random(cols);\n\n  bool densedone = false;\n\n  //for (float density = DENSITY; density>=MINDENSITY; density*=0.5)\n//   float density = 0.5;\n  {\n    EigenSparseSelfAdjointMatrix sm1(rows, cols);\n    std::cout << \"Generate sparse matrix (might take a while)...\\n\";\n    fillSpdMatrix(density, rows, cols, sm1);\n    std::cout << \"DONE\\n\\n\";\n\n    // dense matrices\n    #ifdef DENSEMATRIX\n    if (!densedone)\n    {\n      densedone = true;\n      std::cout << \"Eigen Dense\\t\" << density*100 << \"%\\n\";\n      DenseMatrix m1(rows,cols);\n      eiToDense(sm1, m1);\n      m1 = (m1 + m1.transpose()).eval();\n      m1.diagonal() *= 0.5;\n\n//       BENCH(LLT<DenseMatrix> chol(m1);)\n//       std::cout << \"dense:\\t\" << timer.value() << endl;\n\n      BenchTimer timer;\n      timer.start();\n      LLT<DenseMatrix> chol(m1);\n      timer.stop();\n      std::cout << \"dense:\\t\" << timer.value() << endl;\n      int count = 0;\n      for (int j=0; j<cols; ++j)\n        for (int i=j; i<rows; ++i)\n          if (!internal::isMuchSmallerThan(internal::abs(chol.matrixL()(i,j)), 0.1))\n            count++;\n      std::cout << \"dense: \" << \"nnz = \" << count << \"\\n\";\n//       std::cout << \"dense:\\n\" << m1 << \"\\n\\n\" << chol.matrixL() << endl;\n    }\n    #endif\n\n    // eigen sparse matrices\n    doEigen<Eigen::DefaultBackend>(\"Eigen/Sparse\", sm1, Eigen::IncompleteFactorization);\n\n    #ifdef EIGEN_CHOLMOD_SUPPORT\n    doEigen<Eigen::Cholmod>(\"Eigen/Cholmod\", sm1, Eigen::IncompleteFactorization);\n    #endif\n\n    #ifdef EIGEN_TAUCS_SUPPORT\n    doEigen<Eigen::Taucs>(\"Eigen/Taucs\", sm1, Eigen::IncompleteFactorization);\n    #endif\n\n    #if 0\n    // TAUCS\n    {\n      taucs_ccs_matrix A = sm1.asTaucsMatrix();\n\n      //BENCH(taucs_ccs_matrix* chol = taucs_ccs_factor_llt(&A, 0, 0);)\n//       BENCH(taucs_supernodal_factor_to_ccs(taucs_ccs_factor_llt_ll(&A));)\n//       std::cout << \"taucs:\\t\" << timer.value() << endl;\n\n      taucs_ccs_matrix* chol = taucs_ccs_factor_llt(&A, 0, 0);\n\n      for (int j=0; j<cols; ++j)\n      {\n        for (int i=chol->colptr[j]; i<chol->colptr[j+1]; ++i)\n          std::cout << chol->values.d[i] << \" \";\n      }\n    }\n\n    // CHOLMOD\n    #ifdef EIGEN_CHOLMOD_SUPPORT\n    {\n      cholmod_common c;\n      cholmod_start (&c);\n      cholmod_sparse A;\n      cholmod_factor *L;\n\n      A = sm1.asCholmodMatrix();\n      BenchTimer timer;\n//       timer.reset();\n      timer.start();\n      std::vector<int> perm(cols);\n//       std::vector<int> set(ncols);\n      for (int i=0; i<cols; ++i)\n        perm[i] = i;\n//       c.nmethods = 1;\n//       c.method[0] = 1;\n\n      c.nmethods = 1;\n      c.method [0].ordering = CHOLMOD_NATURAL;\n      c.postorder = 0;\n      c.final_ll = 1;\n\n      L = cholmod_analyze_p(&A, &perm[0], &perm[0], cols, &c);\n      timer.stop();\n      std::cout << \"cholmod/analyze:\\t\" << timer.value() << endl;\n      timer.reset();\n      timer.start();\n      cholmod_factorize(&A, L, &c);\n      timer.stop();\n      std::cout << \"cholmod/factorize:\\t\" << timer.value() << endl;\n\n      cholmod_sparse* cholmat = cholmod_factor_to_sparse(L, &c);\n\n      cholmod_print_factor(L, \"Factors\", &c);\n\n      cholmod_print_sparse(cholmat, \"Chol\", &c);\n      cholmod_write_sparse(stdout, cholmat, 0, 0, &c);\n//\n//       cholmod_print_sparse(&A, \"A\", &c);\n//       cholmod_write_sparse(stdout, &A, 0, 0, &c);\n\n\n//       for (int j=0; j<cols; ++j)\n//       {\n//           for (int i=chol->colptr[j]; i<chol->colptr[j+1]; ++i)\n//             std::cout << chol->values.s[i] << \" \";\n//       }\n    }\n    #endif\n\n    #endif\n\n\n\n  }\n\n\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/sparse_dense_product.cpp",
    "content": "\n//g++ -O3 -g0 -DNDEBUG  sparse_product.cpp -I.. -I/home/gael/Coding/LinearAlgebra/mtl4/ -DDENSITY=0.005 -DSIZE=10000 && ./a.out\n//g++ -O3 -g0 -DNDEBUG  sparse_product.cpp -I.. -I/home/gael/Coding/LinearAlgebra/mtl4/ -DDENSITY=0.05 -DSIZE=2000 && ./a.out\n// -DNOGMM -DNOMTL -DCSPARSE\n// -I /home/gael/Coding/LinearAlgebra/CSparse/Include/ /home/gael/Coding/LinearAlgebra/CSparse/Lib/libcsparse.a\n#ifndef SIZE\n#define SIZE 650000\n#endif\n\n#ifndef DENSITY\n#define DENSITY 0.01\n#endif\n\n#ifndef REPEAT\n#define REPEAT 1\n#endif\n\n#include \"BenchSparseUtil.h\"\n\n#ifndef MINDENSITY\n#define MINDENSITY 0.0004\n#endif\n\n#ifndef NBTRIES\n#define NBTRIES 10\n#endif\n\n#define BENCH(X) \\\n  timer.reset(); \\\n  for (int _j=0; _j<NBTRIES; ++_j) { \\\n    timer.start(); \\\n    for (int _k=0; _k<REPEAT; ++_k) { \\\n        X  \\\n  } timer.stop(); }\n\n\n#ifdef CSPARSE\ncs* cs_sorted_multiply(const cs* a, const cs* b)\n{\n  cs* A = cs_transpose (a, 1) ;\n  cs* B = cs_transpose (b, 1) ;\n  cs* D = cs_multiply (B,A) ;   /* D = B'*A' */\n  cs_spfree (A) ;\n  cs_spfree (B) ;\n  cs_dropzeros (D) ;      /* drop zeros from D */\n  cs* C = cs_transpose (D, 1) ;   /* C = D', so that C is sorted */\n  cs_spfree (D) ;\n  return C;\n}\n#endif\n\nint main(int argc, char *argv[])\n{\n  int rows = SIZE;\n  int cols = SIZE;\n  float density = DENSITY;\n\n  EigenSparseMatrix sm1(rows,cols);\n  DenseVector v1(cols), v2(cols);\n  v1.setRandom();\n\n  BenchTimer timer;\n  for (float density = DENSITY; density>=MINDENSITY; density*=0.5)\n  {\n    //fillMatrix(density, rows, cols, sm1);\n    fillMatrix2(7, rows, cols, sm1);\n\n    // dense matrices\n    #ifdef DENSEMATRIX\n    {\n      std::cout << \"Eigen Dense\\t\" << density*100 << \"%\\n\";\n      DenseMatrix m1(rows,cols);\n      eiToDense(sm1, m1);\n\n      timer.reset();\n      timer.start();\n      for (int k=0; k<REPEAT; ++k)\n        v2 = m1 * v1;\n      timer.stop();\n      std::cout << \"   a * v:\\t\" << timer.best() << \"  \" << double(REPEAT)/timer.best() << \" * / sec \" << endl;\n\n      timer.reset();\n      timer.start();\n      for (int k=0; k<REPEAT; ++k)\n        v2 = m1.transpose() * v1;\n      timer.stop();\n      std::cout << \"   a' * v:\\t\" << timer.best() << endl;\n    }\n    #endif\n\n    // eigen sparse matrices\n    {\n      std::cout << \"Eigen sparse\\t\" << sm1.nonZeros()/float(sm1.rows()*sm1.cols())*100 << \"%\\n\";\n\n      BENCH(asm(\"#myc\"); v2 = sm1 * v1; asm(\"#myd\");)\n      std::cout << \"   a * v:\\t\" << timer.best()/REPEAT << \"  \" << double(REPEAT)/timer.best(REAL_TIMER) << \" * / sec \" << endl;\n\n\n      BENCH( { asm(\"#mya\"); v2 = sm1.transpose() * v1; asm(\"#myb\"); })\n\n      std::cout << \"   a' * v:\\t\" << timer.best()/REPEAT << endl;\n    }\n\n//     {\n//       DynamicSparseMatrix<Scalar> m1(sm1);\n//       std::cout << \"Eigen dyn-sparse\\t\" << m1.nonZeros()/float(m1.rows()*m1.cols())*100 << \"%\\n\";\n//\n//       BENCH(for (int k=0; k<REPEAT; ++k) v2 = m1 * v1;)\n//       std::cout << \"   a * v:\\t\" << timer.value() << endl;\n//\n//       BENCH(for (int k=0; k<REPEAT; ++k) v2 = m1.transpose() * v1;)\n//       std::cout << \"   a' * v:\\t\" << timer.value() << endl;\n//     }\n\n    // GMM++\n    #ifndef NOGMM\n    {\n      std::cout << \"GMM++ sparse\\t\" << density*100 << \"%\\n\";\n      //GmmDynSparse  gmmT3(rows,cols);\n      GmmSparse m1(rows,cols);\n      eiToGmm(sm1, m1);\n\n      std::vector<Scalar> gmmV1(cols), gmmV2(cols);\n      Map<Matrix<Scalar,Dynamic,1> >(&gmmV1[0], cols) = v1;\n      Map<Matrix<Scalar,Dynamic,1> >(&gmmV2[0], cols) = v2;\n\n      BENCH( asm(\"#myx\"); gmm::mult(m1, gmmV1, gmmV2); asm(\"#myy\"); )\n      std::cout << \"   a * v:\\t\" << timer.value() << endl;\n\n      BENCH( gmm::mult(gmm::transposed(m1), gmmV1, gmmV2); )\n      std::cout << \"   a' * v:\\t\" << timer.value() << endl;\n    }\n    #endif\n    \n    #ifndef NOUBLAS\n    {\n      std::cout << \"ublas sparse\\t\" << density*100 << \"%\\n\";\n      UBlasSparse m1(rows,cols);\n      eiToUblas(sm1, m1);\n      \n      boost::numeric::ublas::vector<Scalar> uv1, uv2;\n      eiToUblasVec(v1,uv1);\n      eiToUblasVec(v2,uv2);\n\n//       std::vector<Scalar> gmmV1(cols), gmmV2(cols);\n//       Map<Matrix<Scalar,Dynamic,1> >(&gmmV1[0], cols) = v1;\n//       Map<Matrix<Scalar,Dynamic,1> >(&gmmV2[0], cols) = v2;\n\n      BENCH( uv2 = boost::numeric::ublas::prod(m1, uv1); )\n      std::cout << \"   a * v:\\t\" << timer.value() << endl;\n\n//       BENCH( boost::ublas::prod(gmm::transposed(m1), gmmV1, gmmV2); )\n//       std::cout << \"   a' * v:\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    // MTL4\n    #ifndef NOMTL\n    {\n      std::cout << \"MTL4\\t\" << density*100 << \"%\\n\";\n      MtlSparse m1(rows,cols);\n      eiToMtl(sm1, m1);\n      mtl::dense_vector<Scalar> mtlV1(cols, 1.0);\n      mtl::dense_vector<Scalar> mtlV2(cols, 1.0);\n\n      timer.reset();\n      timer.start();\n      for (int k=0; k<REPEAT; ++k)\n        mtlV2 = m1 * mtlV1;\n      timer.stop();\n      std::cout << \"   a * v:\\t\" << timer.value() << endl;\n\n      timer.reset();\n      timer.start();\n      for (int k=0; k<REPEAT; ++k)\n        mtlV2 = trans(m1) * mtlV1;\n      timer.stop();\n      std::cout << \"   a' * v:\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    std::cout << \"\\n\\n\";\n  }\n\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/sparse_lu.cpp",
    "content": "\n// g++ -I.. sparse_lu.cpp -O3 -g0 -I /usr/include/superlu/ -lsuperlu -lgfortran -DSIZE=1000 -DDENSITY=.05 && ./a.out\n\n#define EIGEN_SUPERLU_SUPPORT\n#define EIGEN_UMFPACK_SUPPORT\n#include <Eigen/Sparse>\n\n#define NOGMM\n#define NOMTL\n\n#ifndef SIZE\n#define SIZE 10\n#endif\n\n#ifndef DENSITY\n#define DENSITY 0.01\n#endif\n\n#ifndef REPEAT\n#define REPEAT 1\n#endif\n\n#include \"BenchSparseUtil.h\"\n\n#ifndef MINDENSITY\n#define MINDENSITY 0.0004\n#endif\n\n#ifndef NBTRIES\n#define NBTRIES 10\n#endif\n\n#define BENCH(X) \\\n  timer.reset(); \\\n  for (int _j=0; _j<NBTRIES; ++_j) { \\\n    timer.start(); \\\n    for (int _k=0; _k<REPEAT; ++_k) { \\\n        X  \\\n  } timer.stop(); }\n\ntypedef Matrix<Scalar,Dynamic,1> VectorX;\n\n#include <Eigen/LU>\n\ntemplate<int Backend>\nvoid doEigen(const char* name, const EigenSparseMatrix& sm1, const VectorX& b, VectorX& x, int flags = 0)\n{\n  std::cout << name << \"...\" << std::flush;\n  BenchTimer timer; timer.start();\n  SparseLU<EigenSparseMatrix,Backend> lu(sm1, flags);\n  timer.stop();\n  if (lu.succeeded())\n    std::cout << \":\\t\" << timer.value() << endl;\n  else\n  {\n    std::cout << \":\\t FAILED\" << endl;\n    return;\n  }\n\n  bool ok;\n  timer.reset(); timer.start();\n  ok = lu.solve(b,&x);\n  timer.stop();\n  if (ok)\n    std::cout << \"  solve:\\t\" << timer.value() << endl;\n  else\n    std::cout << \"  solve:\\t\" << \" FAILED\" << endl;\n\n  //std::cout << x.transpose() << \"\\n\";\n}\n\nint main(int argc, char *argv[])\n{\n  int rows = SIZE;\n  int cols = SIZE;\n  float density = DENSITY;\n  BenchTimer timer;\n\n  VectorX b = VectorX::Random(cols);\n  VectorX x = VectorX::Random(cols);\n\n  bool densedone = false;\n\n  //for (float density = DENSITY; density>=MINDENSITY; density*=0.5)\n//   float density = 0.5;\n  {\n    EigenSparseMatrix sm1(rows, cols);\n    fillMatrix(density, rows, cols, sm1);\n\n    // dense matrices\n    #ifdef DENSEMATRIX\n    if (!densedone)\n    {\n      densedone = true;\n      std::cout << \"Eigen Dense\\t\" << density*100 << \"%\\n\";\n      DenseMatrix m1(rows,cols);\n      eiToDense(sm1, m1);\n\n      BenchTimer timer;\n      timer.start();\n      FullPivLU<DenseMatrix> lu(m1);\n      timer.stop();\n      std::cout << \"Eigen/dense:\\t\" << timer.value() << endl;\n\n      timer.reset();\n      timer.start();\n      lu.solve(b,&x);\n      timer.stop();\n      std::cout << \"  solve:\\t\" << timer.value() << endl;\n//       std::cout << b.transpose() << \"\\n\";\n//       std::cout << x.transpose() << \"\\n\";\n    }\n    #endif\n\n    #ifdef EIGEN_UMFPACK_SUPPORT\n    x.setZero();\n    doEigen<Eigen::UmfPack>(\"Eigen/UmfPack (auto)\", sm1, b, x, 0);\n    #endif\n\n    #ifdef EIGEN_SUPERLU_SUPPORT\n    x.setZero();\n    doEigen<Eigen::SuperLU>(\"Eigen/SuperLU (nat)\", sm1, b, x, Eigen::NaturalOrdering);\n//     doEigen<Eigen::SuperLU>(\"Eigen/SuperLU (MD AT+A)\", sm1, b, x, Eigen::MinimumDegree_AT_PLUS_A);\n//     doEigen<Eigen::SuperLU>(\"Eigen/SuperLU (MD ATA)\", sm1, b, x, Eigen::MinimumDegree_ATA);\n    doEigen<Eigen::SuperLU>(\"Eigen/SuperLU (COLAMD)\", sm1, b, x, Eigen::ColApproxMinimumDegree);\n    #endif\n\n  }\n\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/sparse_product.cpp",
    "content": "\n//g++ -O3 -g0 -DNDEBUG  sparse_product.cpp -I.. -I/home/gael/Coding/LinearAlgebra/mtl4/ -DDENSITY=0.005 -DSIZE=10000 && ./a.out\n//g++ -O3 -g0 -DNDEBUG  sparse_product.cpp -I.. -I/home/gael/Coding/LinearAlgebra/mtl4/ -DDENSITY=0.05 -DSIZE=2000 && ./a.out\n// -DNOGMM -DNOMTL -DCSPARSE\n// -I /home/gael/Coding/LinearAlgebra/CSparse/Include/ /home/gael/Coding/LinearAlgebra/CSparse/Lib/libcsparse.a\n\n#include <typeinfo>\n\n#ifndef SIZE\n#define SIZE 1000000\n#endif\n\n#ifndef NNZPERCOL\n#define NNZPERCOL 6\n#endif\n\n#ifndef REPEAT\n#define REPEAT 1\n#endif\n\n#include <algorithm>\n#include \"BenchTimer.h\"\n#include \"BenchUtil.h\"\n#include \"BenchSparseUtil.h\"\n\n#ifndef NBTRIES\n#define NBTRIES 1\n#endif\n\n#define BENCH(X) \\\n  timer.reset(); \\\n  for (int _j=0; _j<NBTRIES; ++_j) { \\\n    timer.start(); \\\n    for (int _k=0; _k<REPEAT; ++_k) { \\\n        X  \\\n  } timer.stop(); }\n\n// #ifdef MKL\n//\n// #include \"mkl_types.h\"\n// #include \"mkl_spblas.h\"\n//\n// template<typename Lhs,typename Rhs,typename Res>\n// void mkl_multiply(const Lhs& lhs, const Rhs& rhs, Res& res)\n// {\n//   char n = 'N';\n//   float alpha = 1;\n//   char matdescra[6];\n//   matdescra[0] = 'G';\n//   matdescra[1] = 0;\n//   matdescra[2] = 0;\n//   matdescra[3] = 'C';\n//   mkl_scscmm(&n, lhs.rows(), rhs.cols(), lhs.cols(), &alpha, matdescra,\n//              lhs._valuePtr(), lhs._innerIndexPtr(), lhs.outerIndexPtr(),\n//              pntre, b, &ldb, &beta, c, &ldc);\n// //   mkl_somatcopy('C', 'T', lhs.rows(), lhs.cols(), 1,\n// //                 lhs._valuePtr(), lhs.rows(), DST, dst_stride);\n// }\n//\n// #endif\n\n\n#ifdef CSPARSE\ncs* cs_sorted_multiply(const cs* a, const cs* b)\n{\n//   return cs_multiply(a,b);\n\n  cs* A = cs_transpose(a, 1);\n  cs* B = cs_transpose(b, 1);\n  cs* D = cs_multiply(B,A);   /* D = B'*A' */\n  cs_spfree (A) ;\n  cs_spfree (B) ;\n  cs_dropzeros (D) ;      /* drop zeros from D */\n  cs* C = cs_transpose (D, 1) ;   /* C = D', so that C is sorted */\n  cs_spfree (D) ;\n  return C;\n\n//   cs* A = cs_transpose(a, 1);\n//   cs* C = cs_transpose(A, 1);\n//   return C;\n}\n\ncs* cs_sorted_multiply2(const cs* a, const cs* b)\n{\n  cs* D = cs_multiply(a,b);\n  cs* E = cs_transpose(D,1);\n  cs_spfree(D);\n  cs* C = cs_transpose(E,1);\n  cs_spfree(E);\n  return C;\n}\n#endif\n\nvoid bench_sort();\n\nint main(int argc, char *argv[])\n{\n//   bench_sort();\n\n  int rows = SIZE;\n  int cols = SIZE;\n  float density = DENSITY;\n\n  EigenSparseMatrix sm1(rows,cols), sm2(rows,cols), sm3(rows,cols), sm4(rows,cols);\n\n  BenchTimer timer;\n  for (int nnzPerCol = NNZPERCOL; nnzPerCol>1; nnzPerCol/=1.1)\n  {\n    sm1.setZero();\n    sm2.setZero();\n    fillMatrix2(nnzPerCol, rows, cols, sm1);\n    fillMatrix2(nnzPerCol, rows, cols, sm2);\n//     std::cerr << \"filling OK\\n\";\n\n    // dense matrices\n    #ifdef DENSEMATRIX\n    {\n      std::cout << \"Eigen Dense\\t\" << nnzPerCol << \"%\\n\";\n      DenseMatrix m1(rows,cols), m2(rows,cols), m3(rows,cols);\n      eiToDense(sm1, m1);\n      eiToDense(sm2, m2);\n\n      timer.reset();\n      timer.start();\n      for (int k=0; k<REPEAT; ++k)\n        m3 = m1 * m2;\n      timer.stop();\n      std::cout << \"   a * b:\\t\" << timer.value() << endl;\n\n      timer.reset();\n      timer.start();\n      for (int k=0; k<REPEAT; ++k)\n        m3 = m1.transpose() * m2;\n      timer.stop();\n      std::cout << \"   a' * b:\\t\" << timer.value() << endl;\n\n      timer.reset();\n      timer.start();\n      for (int k=0; k<REPEAT; ++k)\n        m3 = m1.transpose() * m2.transpose();\n      timer.stop();\n      std::cout << \"   a' * b':\\t\" << timer.value() << endl;\n\n      timer.reset();\n      timer.start();\n      for (int k=0; k<REPEAT; ++k)\n        m3 = m1 * m2.transpose();\n      timer.stop();\n      std::cout << \"   a * b':\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    // eigen sparse matrices\n    {\n      std::cout << \"Eigen sparse\\t\" << sm1.nonZeros()/(float(sm1.rows())*float(sm1.cols()))*100 << \"% * \"\n                << sm2.nonZeros()/(float(sm2.rows())*float(sm2.cols()))*100 << \"%\\n\";\n\n      BENCH(sm3 = sm1 * sm2; )\n      std::cout << \"   a * b:\\t\" << timer.value() << endl;\n\n//       BENCH(sm3 = sm1.transpose() * sm2; )\n//       std::cout << \"   a' * b:\\t\" << timer.value() << endl;\n// //\n//       BENCH(sm3 = sm1.transpose() * sm2.transpose(); )\n//       std::cout << \"   a' * b':\\t\" << timer.value() << endl;\n// //\n//       BENCH(sm3 = sm1 * sm2.transpose(); )\n//       std::cout << \"   a * b' :\\t\" << timer.value() << endl;\n\n\n//       std::cout << \"\\n\";\n//\n//       BENCH( sm3._experimentalNewProduct(sm1, sm2); )\n//       std::cout << \"   a * b:\\t\" << timer.value() << endl;\n//\n//       BENCH(sm3._experimentalNewProduct(sm1.transpose(),sm2); )\n//       std::cout << \"   a' * b:\\t\" << timer.value() << endl;\n// //\n//       BENCH(sm3._experimentalNewProduct(sm1.transpose(),sm2.transpose()); )\n//       std::cout << \"   a' * b':\\t\" << timer.value() << endl;\n// //\n//       BENCH(sm3._experimentalNewProduct(sm1, sm2.transpose());)\n//       std::cout << \"   a * b' :\\t\" << timer.value() << endl;\n    }\n\n    // eigen dyn-sparse matrices\n    /*{\n      DynamicSparseMatrix<Scalar> m1(sm1), m2(sm2), m3(sm3);\n      std::cout << \"Eigen dyn-sparse\\t\" << m1.nonZeros()/(float(m1.rows())*float(m1.cols()))*100 << \"% * \"\n                << m2.nonZeros()/(float(m2.rows())*float(m2.cols()))*100 << \"%\\n\";\n\n//       timer.reset();\n//       timer.start();\n      BENCH(for (int k=0; k<REPEAT; ++k) m3 = m1 * m2;)\n//       timer.stop();\n      std::cout << \"   a * b:\\t\" << timer.value() << endl;\n//       std::cout << sm3 << \"\\n\";\n\n      timer.reset();\n      timer.start();\n//       std::cerr << \"transpose...\\n\";\n//       EigenSparseMatrix sm4 = sm1.transpose();\n//       std::cout << sm4.nonZeros() << \" == \" << sm1.nonZeros() << \"\\n\";\n//       exit(1);\n//       std::cerr << \"transpose OK\\n\";\n//       std::cout << sm1 << \"\\n\\n\" << sm1.transpose() << \"\\n\\n\" << sm4.transpose() << \"\\n\\n\";\n      BENCH(for (int k=0; k<REPEAT; ++k) m3 = m1.transpose() * m2;)\n//       timer.stop();\n      std::cout << \"   a' * b:\\t\" << timer.value() << endl;\n\n//       timer.reset();\n//       timer.start();\n      BENCH( for (int k=0; k<REPEAT; ++k) m3 = m1.transpose() * m2.transpose(); )\n//       timer.stop();\n      std::cout << \"   a' * b':\\t\" << timer.value() << endl;\n\n//       timer.reset();\n//       timer.start();\n      BENCH( for (int k=0; k<REPEAT; ++k) m3 = m1 * m2.transpose(); )\n//       timer.stop();\n      std::cout << \"   a * b' :\\t\" << timer.value() << endl;\n    }*/\n\n    // CSparse\n    #ifdef CSPARSE\n    {\n      std::cout << \"CSparse \\t\" << nnzPerCol << \"%\\n\";\n      cs *m1, *m2, *m3;\n      eiToCSparse(sm1, m1);\n      eiToCSparse(sm2, m2);\n\n      BENCH(\n      {\n        m3 = cs_sorted_multiply(m1, m2);\n        if (!m3)\n        {\n          std::cerr << \"cs_multiply failed\\n\";\n        }\n//         cs_print(m3, 0);\n        cs_spfree(m3);\n      }\n      );\n//       timer.stop();\n      std::cout << \"   a * b:\\t\" << timer.value() << endl;\n\n//       BENCH( { m3 = cs_sorted_multiply2(m1, m2); cs_spfree(m3); } );\n//       std::cout << \"   a * b:\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    #ifndef NOUBLAS\n    {\n      std::cout << \"ublas\\t\" << nnzPerCol << \"%\\n\";\n      UBlasSparse m1(rows,cols), m2(rows,cols), m3(rows,cols);\n      eiToUblas(sm1, m1);\n      eiToUblas(sm2, m2);\n\n      BENCH(boost::numeric::ublas::prod(m1, m2, m3););\n      std::cout << \"   a * b:\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    // GMM++\n    #ifndef NOGMM\n    {\n      std::cout << \"GMM++ sparse\\t\" << nnzPerCol << \"%\\n\";\n      GmmDynSparse  gmmT3(rows,cols);\n      GmmSparse m1(rows,cols), m2(rows,cols), m3(rows,cols);\n      eiToGmm(sm1, m1);\n      eiToGmm(sm2, m2);\n\n      BENCH(gmm::mult(m1, m2, gmmT3););\n      std::cout << \"   a * b:\\t\" << timer.value() << endl;\n\n//       BENCH(gmm::mult(gmm::transposed(m1), m2, gmmT3););\n//       std::cout << \"   a' * b:\\t\" << timer.value() << endl;\n//\n//       if (rows<500)\n//       {\n//         BENCH(gmm::mult(gmm::transposed(m1), gmm::transposed(m2), gmmT3););\n//         std::cout << \"   a' * b':\\t\" << timer.value() << endl;\n//\n//         BENCH(gmm::mult(m1, gmm::transposed(m2), gmmT3););\n//         std::cout << \"   a * b':\\t\" << timer.value() << endl;\n//       }\n//       else\n//       {\n//         std::cout << \"   a' * b':\\t\" << \"forever\" << endl;\n//         std::cout << \"   a * b':\\t\" << \"forever\" << endl;\n//       }\n    }\n    #endif\n\n    // MTL4\n    #ifndef NOMTL\n    {\n      std::cout << \"MTL4\\t\" << nnzPerCol << \"%\\n\";\n      MtlSparse m1(rows,cols), m2(rows,cols), m3(rows,cols);\n      eiToMtl(sm1, m1);\n      eiToMtl(sm2, m2);\n\n      BENCH(m3 = m1 * m2;);\n      std::cout << \"   a * b:\\t\" << timer.value() << endl;\n\n//       BENCH(m3 = trans(m1) * m2;);\n//       std::cout << \"   a' * b:\\t\" << timer.value() << endl;\n//\n//       BENCH(m3 = trans(m1) * trans(m2););\n//       std::cout << \"  a' * b':\\t\" << timer.value() << endl;\n//\n//       BENCH(m3 = m1 * trans(m2););\n//       std::cout << \"   a * b' :\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    std::cout << \"\\n\\n\";\n  }\n\n  return 0;\n}\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/sparse_randomsetter.cpp",
    "content": "\n#define NOGMM\n#define NOMTL\n\n#include <map>\n#include <ext/hash_map>\n#include <google/dense_hash_map>\n#include <google/sparse_hash_map>\n\n#ifndef SIZE\n#define SIZE 10000\n#endif\n\n#ifndef DENSITY\n#define DENSITY 0.01\n#endif\n\n#ifndef REPEAT\n#define REPEAT 1\n#endif\n\n#include \"BenchSparseUtil.h\"\n\n#ifndef MINDENSITY\n#define MINDENSITY 0.0004\n#endif\n\n#ifndef NBTRIES\n#define NBTRIES 10\n#endif\n\n#define BENCH(X) \\\n  timer.reset(); \\\n  for (int _j=0; _j<NBTRIES; ++_j) { \\\n    timer.start(); \\\n    for (int _k=0; _k<REPEAT; ++_k) { \\\n        X  \\\n  } timer.stop(); }\n\n\nstatic double rtime;\nstatic double nentries;\n\ntemplate<typename SetterType>\nvoid dostuff(const char* name, EigenSparseMatrix& sm1)\n{\n  int rows = sm1.rows();\n  int cols = sm1.cols();\n  sm1.setZero();\n  BenchTimer t;\n  SetterType* set1 = new SetterType(sm1);\n  t.reset(); t.start();\n  for (int k=0; k<nentries; ++k)\n    (*set1)(internal::random<int>(0,rows-1),internal::random<int>(0,cols-1)) += 1;\n  t.stop();\n  std::cout << \"std::map =>      \\t\" << t.value()-rtime\n            << \" nnz=\" << set1->nonZeros() << std::flush;\n\n  // getchar();\n\n  t.reset(); t.start(); delete set1; t.stop();\n  std::cout << \"  back: \\t\" << t.value() << \"\\n\";\n}\n    \nint main(int argc, char *argv[])\n{\n  int rows = SIZE;\n  int cols = SIZE;\n  float density = DENSITY;\n\n  EigenSparseMatrix sm1(rows,cols), sm2(rows,cols);\n\n\n  nentries = rows*cols*density;\n  std::cout << \"n = \" << nentries << \"\\n\";\n  int dummy;\n  BenchTimer t;\n\n  t.reset(); t.start();\n  for (int k=0; k<nentries; ++k)\n    dummy = internal::random<int>(0,rows-1) + internal::random<int>(0,cols-1);\n  t.stop();\n  rtime = t.value();\n  std::cout << \"rtime = \" << rtime << \" (\" << dummy << \")\\n\\n\";\n  const int Bits = 6;\n  for (;;)\n  {\n    dostuff<RandomSetter<EigenSparseMatrix,StdMapTraits,Bits> >(\"std::map     \", sm1);\n    dostuff<RandomSetter<EigenSparseMatrix,GnuHashMapTraits,Bits> >(\"gnu::hash_map\", sm1);\n    dostuff<RandomSetter<EigenSparseMatrix,GoogleDenseHashMapTraits,Bits> >(\"google::dense\", sm1);\n    dostuff<RandomSetter<EigenSparseMatrix,GoogleSparseHashMapTraits,Bits> >(\"google::sparse\", sm1);\n\n//     {\n//       RandomSetter<EigenSparseMatrix,GnuHashMapTraits,Bits> set1(sm1);\n//       t.reset(); t.start();\n//       for (int k=0; k<n; ++k)\n//         set1(internal::random<int>(0,rows-1),internal::random<int>(0,cols-1)) += 1;\n//       t.stop();\n//       std::cout << \"gnu::hash_map => \\t\" << t.value()-rtime\n//                 << \" nnz=\" << set1.nonZeros() << \"\\n\";getchar();\n//     }\n//     {\n//       RandomSetter<EigenSparseMatrix,GoogleDenseHashMapTraits,Bits> set1(sm1);\n//       t.reset(); t.start();\n//       for (int k=0; k<n; ++k)\n//         set1(internal::random<int>(0,rows-1),internal::random<int>(0,cols-1)) += 1;\n//       t.stop();\n//       std::cout << \"google::dense => \\t\" << t.value()-rtime\n//                 << \" nnz=\" << set1.nonZeros() << \"\\n\";getchar();\n//     }\n//     {\n//       RandomSetter<EigenSparseMatrix,GoogleSparseHashMapTraits,Bits> set1(sm1);\n//       t.reset(); t.start();\n//       for (int k=0; k<n; ++k)\n//         set1(internal::random<int>(0,rows-1),internal::random<int>(0,cols-1)) += 1;\n//       t.stop();\n//       std::cout << \"google::sparse => \\t\" << t.value()-rtime\n//                 << \" nnz=\" << set1.nonZeros() << \"\\n\";getchar();\n//     }\n    std::cout << \"\\n\\n\";\n  }\n\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/sparse_setter.cpp",
    "content": "\n//g++ -O3 -g0 -DNDEBUG  sparse_product.cpp -I.. -I/home/gael/Coding/LinearAlgebra/mtl4/ -DDENSITY=0.005 -DSIZE=10000 && ./a.out\n//g++ -O3 -g0 -DNDEBUG  sparse_product.cpp -I.. -I/home/gael/Coding/LinearAlgebra/mtl4/ -DDENSITY=0.05 -DSIZE=2000 && ./a.out\n// -DNOGMM -DNOMTL -DCSPARSE\n// -I /home/gael/Coding/LinearAlgebra/CSparse/Include/ /home/gael/Coding/LinearAlgebra/CSparse/Lib/libcsparse.a\n#ifndef SIZE\n#define SIZE 100000\n#endif\n\n#ifndef NBPERROW\n#define NBPERROW 24\n#endif\n\n#ifndef REPEAT\n#define REPEAT 2\n#endif\n\n#ifndef NBTRIES\n#define NBTRIES 2\n#endif\n\n#ifndef KK\n#define KK 10\n#endif\n\n#ifndef NOGOOGLE\n#define EIGEN_GOOGLEHASH_SUPPORT\n#include <google/sparse_hash_map>\n#endif\n\n#include \"BenchSparseUtil.h\"\n\n#define CHECK_MEM\n// #define CHECK_MEM  std/**/::cout << \"check mem\\n\"; getchar();\n\n#define BENCH(X) \\\n  timer.reset(); \\\n  for (int _j=0; _j<NBTRIES; ++_j) { \\\n    timer.start(); \\\n    for (int _k=0; _k<REPEAT; ++_k) { \\\n        X  \\\n  } timer.stop(); }\n\ntypedef std::vector<Vector2i> Coordinates;\ntypedef std::vector<float> Values;\n\nEIGEN_DONT_INLINE Scalar* setinnerrand_eigen(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_eigen_dynamic(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_eigen_compact(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_eigen_sumeq(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_eigen_gnu_hash(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_eigen_google_dense(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_eigen_google_sparse(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_scipy(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_ublas_mapped(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_ublas_coord(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_ublas_compressed(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_ublas_genvec(const Coordinates& coords, const Values& vals);\nEIGEN_DONT_INLINE Scalar* setrand_mtl(const Coordinates& coords, const Values& vals);\n\nint main(int argc, char *argv[])\n{\n  int rows = SIZE;\n  int cols = SIZE;\n  bool fullyrand = true;\n\n  BenchTimer timer;\n  Coordinates coords;\n  Values values;\n  if(fullyrand)\n  {\n    Coordinates pool;\n    pool.reserve(cols*NBPERROW);\n    std::cerr << \"fill pool\" << \"\\n\";\n    for (int i=0; i<cols*NBPERROW; )\n    {\n//       DynamicSparseMatrix<int> stencil(SIZE,SIZE);\n      Vector2i ij(internal::random<int>(0,rows-1),internal::random<int>(0,cols-1));\n//       if(stencil.coeffRef(ij.x(), ij.y())==0)\n      {\n//         stencil.coeffRef(ij.x(), ij.y()) = 1;\n        pool.push_back(ij);\n\n      }\n      ++i;\n    }\n    std::cerr << \"pool ok\" << \"\\n\";\n    int n = cols*NBPERROW*KK;\n    coords.reserve(n);\n    values.reserve(n);\n    for (int i=0; i<n; ++i)\n    {\n      int i = internal::random<int>(0,pool.size());\n      coords.push_back(pool[i]);\n      values.push_back(internal::random<Scalar>());\n    }\n  }\n  else\n  {\n    for (int j=0; j<cols; ++j)\n    for (int i=0; i<NBPERROW; ++i)\n    {\n      coords.push_back(Vector2i(internal::random<int>(0,rows-1),j));\n      values.push_back(internal::random<Scalar>());\n    }\n  }\n  std::cout << \"nnz = \" << coords.size()  << \"\\n\";\n  CHECK_MEM\n\n    // dense matrices\n    #ifdef DENSEMATRIX\n    {\n      BENCH(setrand_eigen_dense(coords,values);)\n      std::cout << \"Eigen Dense\\t\" << timer.value() << \"\\n\";\n    }\n    #endif\n\n    // eigen sparse matrices\n//     if (!fullyrand)\n//     {\n//       BENCH(setinnerrand_eigen(coords,values);)\n//       std::cout << \"Eigen fillrand\\t\" << timer.value() << \"\\n\";\n//     }\n    {\n      BENCH(setrand_eigen_dynamic(coords,values);)\n      std::cout << \"Eigen dynamic\\t\" << timer.value() << \"\\n\";\n    }\n//     {\n//       BENCH(setrand_eigen_compact(coords,values);)\n//       std::cout << \"Eigen compact\\t\" << timer.value() << \"\\n\";\n//     }\n    {\n      BENCH(setrand_eigen_sumeq(coords,values);)\n      std::cout << \"Eigen sumeq\\t\" << timer.value() << \"\\n\";\n    }\n    {\n//       BENCH(setrand_eigen_gnu_hash(coords,values);)\n//       std::cout << \"Eigen std::map\\t\" << timer.value() << \"\\n\";\n    }\n    {\n      BENCH(setrand_scipy(coords,values);)\n      std::cout << \"scipy\\t\" << timer.value() << \"\\n\";\n    }\n    #ifndef NOGOOGLE\n    {\n      BENCH(setrand_eigen_google_dense(coords,values);)\n      std::cout << \"Eigen google dense\\t\" << timer.value() << \"\\n\";\n    }\n    {\n      BENCH(setrand_eigen_google_sparse(coords,values);)\n      std::cout << \"Eigen google sparse\\t\" << timer.value() << \"\\n\";\n    }\n    #endif\n\n    #ifndef NOUBLAS\n    {\n//       BENCH(setrand_ublas_mapped(coords,values);)\n//       std::cout << \"ublas mapped\\t\" << timer.value() << \"\\n\";\n    }\n    {\n      BENCH(setrand_ublas_genvec(coords,values);)\n      std::cout << \"ublas vecofvec\\t\" << timer.value() << \"\\n\";\n    }\n    /*{\n      timer.reset();\n      timer.start();\n      for (int k=0; k<REPEAT; ++k)\n        setrand_ublas_compressed(coords,values);\n      timer.stop();\n      std::cout << \"ublas comp\\t\" << timer.value() << \"\\n\";\n    }\n    {\n      timer.reset();\n      timer.start();\n      for (int k=0; k<REPEAT; ++k)\n        setrand_ublas_coord(coords,values);\n      timer.stop();\n      std::cout << \"ublas coord\\t\" << timer.value() << \"\\n\";\n    }*/\n    #endif\n\n\n    // MTL4\n    #ifndef NOMTL\n    {\n      BENCH(setrand_mtl(coords,values));\n      std::cout << \"MTL\\t\" << timer.value() << \"\\n\";\n    }\n    #endif\n\n  return 0;\n}\n\nEIGEN_DONT_INLINE Scalar* setinnerrand_eigen(const Coordinates& coords, const Values& vals)\n{\n  using namespace Eigen;\n  SparseMatrix<Scalar> mat(SIZE,SIZE);\n  //mat.startFill(2000000/*coords.size()*/);\n  for (int i=0; i<coords.size(); ++i)\n  {\n    mat.insert(coords[i].x(), coords[i].y()) = vals[i];\n  }\n  mat.finalize();\n  CHECK_MEM;\n  return 0;\n}\n\nEIGEN_DONT_INLINE Scalar* setrand_eigen_dynamic(const Coordinates& coords, const Values& vals)\n{\n  using namespace Eigen;\n  DynamicSparseMatrix<Scalar> mat(SIZE,SIZE);\n  mat.reserve(coords.size()/10);\n  for (int i=0; i<coords.size(); ++i)\n  {\n    mat.coeffRef(coords[i].x(), coords[i].y()) += vals[i];\n  }\n  mat.finalize();\n  CHECK_MEM;\n  return &mat.coeffRef(coords[0].x(), coords[0].y());\n}\n\nEIGEN_DONT_INLINE Scalar* setrand_eigen_sumeq(const Coordinates& coords, const Values& vals)\n{\n  using namespace Eigen;\n  int n = coords.size()/KK;\n  DynamicSparseMatrix<Scalar> mat(SIZE,SIZE);\n  for (int j=0; j<KK; ++j)\n  {\n    DynamicSparseMatrix<Scalar> aux(SIZE,SIZE);\n    mat.reserve(n);\n    for (int i=j*n; i<(j+1)*n; ++i)\n    {\n      aux.insert(coords[i].x(), coords[i].y()) += vals[i];\n    }\n    aux.finalize();\n    mat += aux;\n  }\n  return &mat.coeffRef(coords[0].x(), coords[0].y());\n}\n\nEIGEN_DONT_INLINE Scalar* setrand_eigen_compact(const Coordinates& coords, const Values& vals)\n{\n  using namespace Eigen;\n  DynamicSparseMatrix<Scalar> setter(SIZE,SIZE);\n  setter.reserve(coords.size()/10);\n  for (int i=0; i<coords.size(); ++i)\n  {\n    setter.coeffRef(coords[i].x(), coords[i].y()) += vals[i];\n  }\n  SparseMatrix<Scalar> mat = setter;\n  CHECK_MEM;\n  return &mat.coeffRef(coords[0].x(), coords[0].y());\n}\n\nEIGEN_DONT_INLINE Scalar* setrand_eigen_gnu_hash(const Coordinates& coords, const Values& vals)\n{\n  using namespace Eigen;\n  SparseMatrix<Scalar> mat(SIZE,SIZE);\n  {\n    RandomSetter<SparseMatrix<Scalar>, StdMapTraits > setter(mat);\n    for (int i=0; i<coords.size(); ++i)\n    {\n      setter(coords[i].x(), coords[i].y()) += vals[i];\n    }\n    CHECK_MEM;\n  }\n  return &mat.coeffRef(coords[0].x(), coords[0].y());\n}\n\n#ifndef NOGOOGLE\nEIGEN_DONT_INLINE Scalar* setrand_eigen_google_dense(const Coordinates& coords, const Values& vals)\n{\n  using namespace Eigen;\n  SparseMatrix<Scalar> mat(SIZE,SIZE);\n  {\n    RandomSetter<SparseMatrix<Scalar>, GoogleDenseHashMapTraits> setter(mat);\n    for (int i=0; i<coords.size(); ++i)\n      setter(coords[i].x(), coords[i].y()) += vals[i];\n    CHECK_MEM;\n  }\n  return &mat.coeffRef(coords[0].x(), coords[0].y());\n}\n\nEIGEN_DONT_INLINE Scalar* setrand_eigen_google_sparse(const Coordinates& coords, const Values& vals)\n{\n  using namespace Eigen;\n  SparseMatrix<Scalar> mat(SIZE,SIZE);\n  {\n    RandomSetter<SparseMatrix<Scalar>, GoogleSparseHashMapTraits> setter(mat);\n    for (int i=0; i<coords.size(); ++i)\n      setter(coords[i].x(), coords[i].y()) += vals[i];\n    CHECK_MEM;\n  }\n  return &mat.coeffRef(coords[0].x(), coords[0].y());\n}\n#endif\n\n\ntemplate <class T>\nvoid coo_tocsr(const int n_row,\n               const int n_col,\n               const int nnz,\n               const Coordinates Aij,\n               const Values Ax,\n                     int Bp[],\n                     int Bj[],\n                     T Bx[])\n{\n    //compute number of non-zero entries per row of A coo_tocsr\n    std::fill(Bp, Bp + n_row, 0);\n\n    for (int n = 0; n < nnz; n++){\n        Bp[Aij[n].x()]++;\n    }\n\n    //cumsum the nnz per row to get Bp[]\n    for(int i = 0, cumsum = 0; i < n_row; i++){\n        int temp = Bp[i];\n        Bp[i] = cumsum;\n        cumsum += temp;\n    }\n    Bp[n_row] = nnz;\n\n    //write Aj,Ax into Bj,Bx\n    for(int n = 0; n < nnz; n++){\n        int row  = Aij[n].x();\n        int dest = Bp[row];\n\n        Bj[dest] = Aij[n].y();\n        Bx[dest] = Ax[n];\n\n        Bp[row]++;\n    }\n\n    for(int i = 0, last = 0; i <= n_row; i++){\n        int temp = Bp[i];\n        Bp[i]  = last;\n        last   = temp;\n    }\n\n    //now Bp,Bj,Bx form a CSR representation (with possible duplicates)\n}\n\ntemplate< class T1, class T2 >\nbool kv_pair_less(const std::pair<T1,T2>& x, const std::pair<T1,T2>& y){\n    return x.first < y.first;\n}\n\n\ntemplate<class I, class T>\nvoid csr_sort_indices(const I n_row,\n                      const I Ap[],\n                            I Aj[],\n                            T Ax[])\n{\n    std::vector< std::pair<I,T> > temp;\n\n    for(I i = 0; i < n_row; i++){\n        I row_start = Ap[i];\n        I row_end   = Ap[i+1];\n\n        temp.clear();\n\n        for(I jj = row_start; jj < row_end; jj++){\n            temp.push_back(std::make_pair(Aj[jj],Ax[jj]));\n        }\n\n        std::sort(temp.begin(),temp.end(),kv_pair_less<I,T>);\n\n        for(I jj = row_start, n = 0; jj < row_end; jj++, n++){\n            Aj[jj] = temp[n].first;\n            Ax[jj] = temp[n].second;\n        }\n    }\n}\n\ntemplate <class I, class T>\nvoid csr_sum_duplicates(const I n_row,\n                        const I n_col,\n                              I Ap[],\n                              I Aj[],\n                              T Ax[])\n{\n    I nnz = 0;\n    I row_end = 0;\n    for(I i = 0; i < n_row; i++){\n        I jj = row_end;\n        row_end = Ap[i+1];\n        while( jj < row_end ){\n            I j = Aj[jj];\n            T x = Ax[jj];\n            jj++;\n            while( jj < row_end && Aj[jj] == j ){\n                x += Ax[jj];\n                jj++;\n            }\n            Aj[nnz] = j;\n            Ax[nnz] = x;\n            nnz++;\n        }\n        Ap[i+1] = nnz;\n    }\n}\n\nEIGEN_DONT_INLINE Scalar* setrand_scipy(const Coordinates& coords, const Values& vals)\n{\n  using namespace Eigen;\n  SparseMatrix<Scalar> mat(SIZE,SIZE);\n  mat.resizeNonZeros(coords.size());\n//   std::cerr << \"setrand_scipy...\\n\";\n  coo_tocsr<Scalar>(SIZE,SIZE, coords.size(), coords, vals, mat._outerIndexPtr(), mat._innerIndexPtr(), mat._valuePtr());\n//   std::cerr << \"coo_tocsr ok\\n\";\n\n  csr_sort_indices(SIZE, mat._outerIndexPtr(), mat._innerIndexPtr(), mat._valuePtr());\n\n  csr_sum_duplicates(SIZE, SIZE, mat._outerIndexPtr(), mat._innerIndexPtr(), mat._valuePtr());\n\n  mat.resizeNonZeros(mat._outerIndexPtr()[SIZE]);\n\n  return &mat.coeffRef(coords[0].x(), coords[0].y());\n}\n\n\n#ifndef NOUBLAS\nEIGEN_DONT_INLINE Scalar* setrand_ublas_mapped(const Coordinates& coords, const Values& vals)\n{\n  using namespace boost;\n  using namespace boost::numeric;\n  using namespace boost::numeric::ublas;\n  mapped_matrix<Scalar> aux(SIZE,SIZE);\n  for (int i=0; i<coords.size(); ++i)\n  {\n    aux(coords[i].x(), coords[i].y()) += vals[i];\n  }\n  CHECK_MEM;\n  compressed_matrix<Scalar> mat(aux);\n  return 0;// &mat(coords[0].x(), coords[0].y());\n}\n/*EIGEN_DONT_INLINE Scalar* setrand_ublas_coord(const Coordinates& coords, const Values& vals)\n{\n  using namespace boost;\n  using namespace boost::numeric;\n  using namespace boost::numeric::ublas;\n  coordinate_matrix<Scalar> aux(SIZE,SIZE);\n  for (int i=0; i<coords.size(); ++i)\n  {\n    aux(coords[i].x(), coords[i].y()) = vals[i];\n  }\n  compressed_matrix<Scalar> mat(aux);\n  return 0;//&mat(coords[0].x(), coords[0].y());\n}\nEIGEN_DONT_INLINE Scalar* setrand_ublas_compressed(const Coordinates& coords, const Values& vals)\n{\n  using namespace boost;\n  using namespace boost::numeric;\n  using namespace boost::numeric::ublas;\n  compressed_matrix<Scalar> mat(SIZE,SIZE);\n  for (int i=0; i<coords.size(); ++i)\n  {\n    mat(coords[i].x(), coords[i].y()) = vals[i];\n  }\n  return 0;//&mat(coords[0].x(), coords[0].y());\n}*/\nEIGEN_DONT_INLINE Scalar* setrand_ublas_genvec(const Coordinates& coords, const Values& vals)\n{\n  using namespace boost;\n  using namespace boost::numeric;\n  using namespace boost::numeric::ublas;\n\n//   ublas::vector<coordinate_vector<Scalar> > foo;\n  generalized_vector_of_vector<Scalar, row_major, ublas::vector<coordinate_vector<Scalar> > > aux(SIZE,SIZE);\n  for (int i=0; i<coords.size(); ++i)\n  {\n    aux(coords[i].x(), coords[i].y()) += vals[i];\n  }\n  CHECK_MEM;\n  compressed_matrix<Scalar,row_major> mat(aux);\n  return 0;//&mat(coords[0].x(), coords[0].y());\n}\n#endif\n\n#ifndef NOMTL\nEIGEN_DONT_INLINE void setrand_mtl(const Coordinates& coords, const Values& vals);\n#endif\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/sparse_transpose.cpp",
    "content": "\n//g++ -O3 -g0 -DNDEBUG  sparse_transpose.cpp -I.. -I/home/gael/Coding/LinearAlgebra/mtl4/ -DDENSITY=0.005 -DSIZE=10000 && ./a.out\n// -DNOGMM -DNOMTL\n// -DCSPARSE -I /home/gael/Coding/LinearAlgebra/CSparse/Include/ /home/gael/Coding/LinearAlgebra/CSparse/Lib/libcsparse.a\n\n#ifndef SIZE\n#define SIZE 10000\n#endif\n\n#ifndef DENSITY\n#define DENSITY 0.01\n#endif\n\n#ifndef REPEAT\n#define REPEAT 1\n#endif\n\n#include \"BenchSparseUtil.h\"\n\n#ifndef MINDENSITY\n#define MINDENSITY 0.0004\n#endif\n\n#ifndef NBTRIES\n#define NBTRIES 10\n#endif\n\n#define BENCH(X) \\\n  timer.reset(); \\\n  for (int _j=0; _j<NBTRIES; ++_j) { \\\n    timer.start(); \\\n    for (int _k=0; _k<REPEAT; ++_k) { \\\n        X  \\\n  } timer.stop(); }\n\nint main(int argc, char *argv[])\n{\n  int rows = SIZE;\n  int cols = SIZE;\n  float density = DENSITY;\n\n  EigenSparseMatrix sm1(rows,cols), sm3(rows,cols);\n\n  BenchTimer timer;\n  for (float density = DENSITY; density>=MINDENSITY; density*=0.5)\n  {\n    fillMatrix(density, rows, cols, sm1);\n\n    // dense matrices\n    #ifdef DENSEMATRIX\n    {\n      DenseMatrix m1(rows,cols), m3(rows,cols);\n      eiToDense(sm1, m1);\n      BENCH(for (int k=0; k<REPEAT; ++k) m3 = m1.transpose();)\n      std::cout << \"  Eigen dense:\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    std::cout << \"Non zeros: \" << sm1.nonZeros()/float(sm1.rows()*sm1.cols())*100 << \"%\\n\";\n\n    // eigen sparse matrices\n    {\n      BENCH(for (int k=0; k<REPEAT; ++k) sm3 = sm1.transpose();)\n      std::cout << \"  Eigen:\\t\" << timer.value() << endl;\n    }\n\n    // CSparse\n    #ifdef CSPARSE\n    {\n      cs *m1, *m3;\n      eiToCSparse(sm1, m1);\n\n      BENCH(for (int k=0; k<REPEAT; ++k) { m3 = cs_transpose(m1,1); cs_spfree(m3);})\n      std::cout << \"  CSparse:\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    // GMM++\n    #ifndef NOGMM\n    {\n      GmmDynSparse  gmmT3(rows,cols);\n      GmmSparse m1(rows,cols), m3(rows,cols);\n      eiToGmm(sm1, m1);\n      BENCH(for (int k=0; k<REPEAT; ++k) gmm::copy(gmm::transposed(m1),m3);)\n      std::cout << \"  GMM:\\t\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    // MTL4\n    #ifndef NOMTL\n    {\n      MtlSparse m1(rows,cols), m3(rows,cols);\n      eiToMtl(sm1, m1);\n      BENCH(for (int k=0; k<REPEAT; ++k) m3 = trans(m1);)\n      std::cout << \"  MTL4:\\t\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    std::cout << \"\\n\\n\";\n  }\n\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/sparse_trisolver.cpp",
    "content": "\n//g++ -O3 -g0 -DNDEBUG  sparse_product.cpp -I.. -I/home/gael/Coding/LinearAlgebra/mtl4/ -DDENSITY=0.005 -DSIZE=10000 && ./a.out\n//g++ -O3 -g0 -DNDEBUG  sparse_product.cpp -I.. -I/home/gael/Coding/LinearAlgebra/mtl4/ -DDENSITY=0.05 -DSIZE=2000 && ./a.out\n// -DNOGMM -DNOMTL\n// -I /home/gael/Coding/LinearAlgebra/CSparse/Include/ /home/gael/Coding/LinearAlgebra/CSparse/Lib/libcsparse.a\n\n#ifndef SIZE\n#define SIZE 10000\n#endif\n\n#ifndef DENSITY\n#define DENSITY 0.01\n#endif\n\n#ifndef REPEAT\n#define REPEAT 1\n#endif\n\n#include \"BenchSparseUtil.h\"\n\n#ifndef MINDENSITY\n#define MINDENSITY 0.0004\n#endif\n\n#ifndef NBTRIES\n#define NBTRIES 10\n#endif\n\n#define BENCH(X) \\\n  timer.reset(); \\\n  for (int _j=0; _j<NBTRIES; ++_j) { \\\n    timer.start(); \\\n    for (int _k=0; _k<REPEAT; ++_k) { \\\n        X  \\\n  } timer.stop(); }\n\ntypedef SparseMatrix<Scalar,UpperTriangular> EigenSparseTriMatrix;\ntypedef SparseMatrix<Scalar,RowMajorBit|UpperTriangular> EigenSparseTriMatrixRow;\n\nvoid fillMatrix(float density, int rows, int cols,  EigenSparseTriMatrix& dst)\n{\n  dst.startFill(rows*cols*density);\n  for(int j = 0; j < cols; j++)\n  {\n    for(int i = 0; i < j; i++)\n    {\n      Scalar v = (internal::random<float>(0,1) < density) ? internal::random<Scalar>() : 0;\n      if (v!=0)\n        dst.fill(i,j) = v;\n    }\n    dst.fill(j,j) = internal::random<Scalar>();\n  }\n  dst.endFill();\n}\n\nint main(int argc, char *argv[])\n{\n  int rows = SIZE;\n  int cols = SIZE;\n  float density = DENSITY;\n  BenchTimer timer;\n  #if 1\n  EigenSparseTriMatrix sm1(rows,cols);\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n  DenseVector b = DenseVector::Random(cols);\n  DenseVector x = DenseVector::Random(cols);\n\n  bool densedone = false;\n\n  for (float density = DENSITY; density>=MINDENSITY; density*=0.5)\n  {\n    EigenSparseTriMatrix sm1(rows, cols);\n    fillMatrix(density, rows, cols, sm1);\n\n    // dense matrices\n    #ifdef DENSEMATRIX\n    if (!densedone)\n    {\n      densedone = true;\n      std::cout << \"Eigen Dense\\t\" << density*100 << \"%\\n\";\n      DenseMatrix m1(rows,cols);\n      Matrix<Scalar,Dynamic,Dynamic,Dynamic,Dynamic,RowMajorBit> m2(rows,cols);\n      eiToDense(sm1, m1);\n      m2 = m1;\n\n      BENCH(x = m1.marked<UpperTriangular>().solveTriangular(b);)\n      std::cout << \"   colmajor^-1 * b:\\t\" << timer.value() << endl;\n//       std::cerr << x.transpose() << \"\\n\";\n\n      BENCH(x = m2.marked<UpperTriangular>().solveTriangular(b);)\n      std::cout << \"   rowmajor^-1 * b:\\t\" << timer.value() << endl;\n//       std::cerr << x.transpose() << \"\\n\";\n    }\n    #endif\n\n    // eigen sparse matrices\n    {\n      std::cout << \"Eigen sparse\\t\" << density*100 << \"%\\n\";\n      EigenSparseTriMatrixRow sm2 = sm1;\n\n      BENCH(x = sm1.solveTriangular(b);)\n      std::cout << \"   colmajor^-1 * b:\\t\" << timer.value() << endl;\n//       std::cerr << x.transpose() << \"\\n\";\n\n      BENCH(x = sm2.solveTriangular(b);)\n      std::cout << \"   rowmajor^-1 * b:\\t\" << timer.value() << endl;\n//       std::cerr << x.transpose() << \"\\n\";\n\n//       x = b;\n//       BENCH(sm1.inverseProductInPlace(x);)\n//       std::cout << \"   colmajor^-1 * b:\\t\" << timer.value() << \" (inplace)\" << endl;\n//       std::cerr << x.transpose() << \"\\n\";\n//\n//       x = b;\n//       BENCH(sm2.inverseProductInPlace(x);)\n//       std::cout << \"   rowmajor^-1 * b:\\t\" << timer.value() << \" (inplace)\" << endl;\n//       std::cerr << x.transpose() << \"\\n\";\n    }\n\n\n\n    // CSparse\n    #ifdef CSPARSE\n    {\n      std::cout << \"CSparse \\t\" << density*100 << \"%\\n\";\n      cs *m1;\n      eiToCSparse(sm1, m1);\n\n      BENCH(x = b; if (!cs_lsolve (m1, x.data())){std::cerr << \"cs_lsolve failed\\n\"; break;}; )\n      std::cout << \"   colmajor^-1 * b:\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    // GMM++\n    #ifndef NOGMM\n    {\n      std::cout << \"GMM++ sparse\\t\" << density*100 << \"%\\n\";\n      GmmSparse m1(rows,cols);\n      gmm::csr_matrix<Scalar> m2;\n      eiToGmm(sm1, m1);\n      gmm::copy(m1,m2);\n      std::vector<Scalar> gmmX(cols), gmmB(cols);\n      Map<Matrix<Scalar,Dynamic,1> >(&gmmX[0], cols) = x;\n      Map<Matrix<Scalar,Dynamic,1> >(&gmmB[0], cols) = b;\n\n      gmmX = gmmB;\n      BENCH(gmm::upper_tri_solve(m1, gmmX, false);)\n      std::cout << \"   colmajor^-1 * b:\\t\" << timer.value() << endl;\n//       std::cerr << Map<Matrix<Scalar,Dynamic,1> >(&gmmX[0], cols).transpose() << \"\\n\";\n\n      gmmX = gmmB;\n      BENCH(gmm::upper_tri_solve(m2, gmmX, false);)\n      timer.stop();\n      std::cout << \"   rowmajor^-1 * b:\\t\" << timer.value() << endl;\n//       std::cerr << Map<Matrix<Scalar,Dynamic,1> >(&gmmX[0], cols).transpose() << \"\\n\";\n    }\n    #endif\n\n    // MTL4\n    #ifndef NOMTL\n    {\n      std::cout << \"MTL4\\t\" << density*100 << \"%\\n\";\n      MtlSparse m1(rows,cols);\n      MtlSparseRowMajor m2(rows,cols);\n      eiToMtl(sm1, m1);\n      m2 = m1;\n      mtl::dense_vector<Scalar> x(rows, 1.0);\n      mtl::dense_vector<Scalar> b(rows, 1.0);\n\n      BENCH(x = mtl::upper_trisolve(m1,b);)\n      std::cout << \"   colmajor^-1 * b:\\t\" << timer.value() << endl;\n//       std::cerr << x << \"\\n\";\n\n      BENCH(x = mtl::upper_trisolve(m2,b);)\n      std::cout << \"   rowmajor^-1 * b:\\t\" << timer.value() << endl;\n//       std::cerr << x << \"\\n\";\n    }\n    #endif\n\n\n    std::cout << \"\\n\\n\";\n  }\n  #endif\n\n  #if 0\n    // bench small matrices (in-place versus return bye value)\n    {\n      timer.reset();\n      for (int _j=0; _j<10; ++_j) {\n        Matrix4f m = Matrix4f::Random();\n        Vector4f b = Vector4f::Random();\n        Vector4f x = Vector4f::Random();\n        timer.start();\n        for (int _k=0; _k<1000000; ++_k) {\n          b = m.inverseProduct(b);\n        }\n        timer.stop();\n      }\n      std::cout << \"4x4 :\\t\" << timer.value() << endl;\n    }\n\n    {\n      timer.reset();\n      for (int _j=0; _j<10; ++_j) {\n        Matrix4f m = Matrix4f::Random();\n        Vector4f b = Vector4f::Random();\n        Vector4f x = Vector4f::Random();\n        timer.start();\n        for (int _k=0; _k<1000000; ++_k) {\n          m.inverseProductInPlace(x);\n        }\n        timer.stop();\n      }\n      std::cout << \"4x4 IP :\\t\" << timer.value() << endl;\n    }\n  #endif\n\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/spbench/CMakeLists.txt",
    "content": "\n\nset(BLAS_FOUND TRUE)\nset(LAPACK_FOUND TRUE)\nset(BLAS_LIBRARIES eigen_blas_static)\nset(LAPACK_LIBRARIES eigen_lapack_static)\n\nset(SPARSE_LIBS \"\")\n\n# find_library(PARDISO_LIBRARIES pardiso412-GNU450-X86-64)\n# if(PARDISO_LIBRARIES)\n#   add_definitions(\"-DEIGEN_PARDISO_SUPPORT\")\n#   set(SPARSE_LIBS ${SPARSE_LIBS} ${PARDISO_LIBRARIES})\n# endif()\n\nfind_package(CHOLMOD)\nif(CHOLMOD_FOUND AND BLAS_FOUND AND LAPACK_FOUND)\n  add_definitions(\"-DEIGEN_CHOLMOD_SUPPORT\")\n  include_directories(${CHOLMOD_INCLUDES})\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${CHOLMOD_LIBRARIES} ${BLAS_LIBRARIES} ${LAPACK_LIBRARIES})\n  set(CHOLMOD_ALL_LIBS  ${CHOLMOD_LIBRARIES} ${BLAS_LIBRARIES} ${LAPACK_LIBRARIES})\nendif()\n\nfind_package(UMFPACK)\nif(UMFPACK_FOUND AND BLAS_FOUND)\n  add_definitions(\"-DEIGEN_UMFPACK_SUPPORT\")\n  include_directories(${UMFPACK_INCLUDES})\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${UMFPACK_LIBRARIES} ${BLAS_LIBRARIES})\n  set(UMFPACK_ALL_LIBS ${UMFPACK_LIBRARIES} ${BLAS_LIBRARIES})\nendif()\n\nfind_package(KLU)\nif(KLU_FOUND)\n  add_definitions(\"-DEIGEN_KLU_SUPPORT\")\n  include_directories(${KLU_INCLUDES})\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${KLU_LIBRARIES})\nendif()\n\nfind_package(SuperLU 4.0)\nif(SuperLU_FOUND AND BLAS_FOUND)\n  add_definitions(\"-DEIGEN_SUPERLU_SUPPORT\")\n  include_directories(${SUPERLU_INCLUDES})\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${SUPERLU_LIBRARIES} ${BLAS_LIBRARIES})\n  set(SUPERLU_ALL_LIBS ${SUPERLU_LIBRARIES} ${BLAS_LIBRARIES})\nendif()\n\n\nfind_package(PASTIX QUIET COMPONENTS METIS SCOTCH)\n# check that the PASTIX found is a version without MPI\nfind_path(PASTIX_pastix_nompi.h_INCLUDE_DIRS\n  NAMES pastix_nompi.h\n  HINTS ${PASTIX_INCLUDE_DIRS}\n)\nif (NOT PASTIX_pastix_nompi.h_INCLUDE_DIRS)\n  message(STATUS \"A version of Pastix has been found but pastix_nompi.h does not exist in the include directory.\"\n                 \" Because Eigen tests require a version without MPI, we disable the Pastix backend.\")\nendif()\nif(PASTIX_FOUND AND PASTIX_pastix_nompi.h_INCLUDE_DIRS AND BLAS_FOUND)\n  add_definitions(\"-DEIGEN_PASTIX_SUPPORT\")\n  include_directories(${PASTIX_INCLUDE_DIRS_DEP})\n  if(SCOTCH_FOUND)\n    include_directories(${SCOTCH_INCLUDE_DIRS})\n    set(PASTIX_LIBRARIES ${PASTIX_LIBRARIES} ${SCOTCH_LIBRARIES})\n  elseif(METIS_FOUND)\n    include_directories(${METIS_INCLUDE_DIRS})\n    set(PASTIX_LIBRARIES ${PASTIX_LIBRARIES} ${METIS_LIBRARIES})  \n  endif()\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${PASTIX_LIBRARIES_DEP} ${ORDERING_LIBRARIES})\n  set(PASTIX_ALL_LIBS ${PASTIX_LIBRARIES_DEP})\nendif()\n\nif(METIS_FOUND)\n  include_directories(${METIS_INCLUDE_DIRS})\n  set (SPARSE_LIBS ${SPARSE_LIBS} ${METIS_LIBRARIES})\n  add_definitions(\"-DEIGEN_METIS_SUPPORT\")\nendif()\n\nfind_library(RT_LIBRARY rt)\nif(RT_LIBRARY)\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${RT_LIBRARY})\nendif()\n\nadd_executable(spbenchsolver spbenchsolver.cpp)\ntarget_link_libraries (spbenchsolver ${SPARSE_LIBS})\n\nadd_executable(spsolver sp_solver.cpp)\ntarget_link_libraries (spsolver ${SPARSE_LIBS})\n\n\nadd_executable(test_sparseLU test_sparseLU.cpp)\ntarget_link_libraries (test_sparseLU ${SPARSE_LIBS})\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/spbench/sp_solver.cpp",
    "content": "// Small bench routine for Eigen available in Eigen\n// (C) Desire NUENTSA WAKAM, INRIA\n\n#include <iostream>\n#include <fstream>\n#include <iomanip>\n#include <Eigen/Jacobi>\n#include <Eigen/Householder>\n#include <Eigen/IterativeLinearSolvers>\n#include <Eigen/LU>\n#include <unsupported/Eigen/SparseExtra>\n//#include <Eigen/SparseLU>\n#include <Eigen/SuperLUSupport>\n// #include <unsupported/Eigen/src/IterativeSolvers/Scaling.h>\n#include <bench/BenchTimer.h>\n#include <unsupported/Eigen/IterativeSolvers>\nusing namespace std;\nusing namespace Eigen;\n\nint main(int argc, char **args)\n{\n  SparseMatrix<double, ColMajor> A; \n  typedef SparseMatrix<double, ColMajor>::Index Index;\n  typedef Matrix<double, Dynamic, Dynamic> DenseMatrix;\n  typedef Matrix<double, Dynamic, 1> DenseRhs;\n  VectorXd b, x, tmp;\n  BenchTimer timer,totaltime; \n  //SparseLU<SparseMatrix<double, ColMajor> >   solver;\n//   SuperLU<SparseMatrix<double, ColMajor> >   solver;\n  ConjugateGradient<SparseMatrix<double, ColMajor>, Lower,IncompleteCholesky<double,Lower> > solver; \n  ifstream matrix_file; \n  string line;\n  int  n;\n  // Set parameters\n//   solver.iparm(IPARM_THREAD_NBR) = 4;\n  /* Fill the matrix with sparse matrix stored in Matrix-Market coordinate column-oriented format */\n  if (argc < 2) assert(false && \"please, give the matrix market file \");\n  \n  timer.start();\n  totaltime.start();\n  loadMarket(A, args[1]);\n  cout << \"End charging matrix \" << endl;\n  bool iscomplex=false, isvector=false;\n  int sym;\n  getMarketHeader(args[1], sym, iscomplex, isvector);\n  if (iscomplex) { cout<< \" Not for complex matrices \\n\"; return -1; }\n  if (isvector) { cout << \"The provided file is not a matrix file\\n\"; return -1;}\n  if (sym != 0) { // symmetric matrices, only the lower part is stored\n    SparseMatrix<double, ColMajor> temp; \n    temp = A;\n    A = temp.selfadjointView<Lower>();\n  }\n  timer.stop();\n  \n  n = A.cols();\n  // ====== TESTS FOR SPARSE TUTORIAL ======\n//   cout<< \"OuterSize \" << A.outerSize() << \" inner \" << A.innerSize() << endl; \n//   SparseMatrix<double, RowMajor> mat1(A); \n//   SparseMatrix<double, RowMajor> mat2;\n//   cout << \" norm of A \" << mat1.norm() << endl; ;\n//   PermutationMatrix<Dynamic, Dynamic, int> perm(n);\n//   perm.resize(n,1);\n//   perm.indices().setLinSpaced(n, 0, n-1);\n//   mat2 = perm * mat1;\n//   mat.subrows();\n//   mat2.resize(n,n); \n//   mat2.reserve(10);\n//   mat2.setConstant();\n//   std::cout<< \"NORM \" << mat1.squaredNorm()<< endl;  \n\n  cout<< \"Time to load the matrix \" << timer.value() <<endl;\n  /* Fill the right hand side */\n\n//   solver.set_restart(374);\n  if (argc > 2)\n    loadMarketVector(b, args[2]);\n  else \n  {\n    b.resize(n);\n    tmp.resize(n);\n//       tmp.setRandom();\n    for (int i = 0; i < n; i++) tmp(i) = i; \n    b = A * tmp ;\n  }\n//   Scaling<SparseMatrix<double> > scal; \n//   scal.computeRef(A);\n//   b = scal.LeftScaling().cwiseProduct(b);\n\n  /* Compute the factorization */\n  cout<< \"Starting the factorization \"<< endl; \n  timer.reset();\n  timer.start(); \n  cout<< \"Size of Input Matrix \"<< b.size()<<\"\\n\\n\";\n  cout<< \"Rows and columns \"<< A.rows() <<\" \" <<A.cols() <<\"\\n\";\n  solver.compute(A);\n//   solver.analyzePattern(A);\n//   solver.factorize(A);\n  if (solver.info() != Success) {\n    std::cout<< \"The solver failed \\n\";\n    return -1; \n  }\n  timer.stop(); \n  float time_comp = timer.value(); \n  cout <<\" Compute Time \" << time_comp<< endl; \n  \n  timer.reset();\n  timer.start();\n  x = solver.solve(b);\n//   x = scal.RightScaling().cwiseProduct(x);\n  timer.stop();\n  float time_solve = timer.value(); \n  cout<< \" Time to solve \" << time_solve << endl; \n \n  /* Check the accuracy */\n  VectorXd tmp2 = b - A*x;\n  double tempNorm = tmp2.norm()/b.norm();\n  cout << \"Relative norm of the computed solution : \" << tempNorm <<\"\\n\";\n//   cout << \"Iterations : \" << solver.iterations() << \"\\n\"; \n  \n  totaltime.stop();\n  cout << \"Total time \" << totaltime.value() << \"\\n\";\n//  std::cout<<x.transpose()<<\"\\n\";\n  \n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/spbench/spbench.dtd",
    "content": "<!ELEMENT BENCH (AVAILSOLVER+,LINEARSYSTEM+)>\n  <!ELEMENT AVAILSOLVER (SOLVER+)>\n    <!ELEMENT SOLVER (TYPE,PACKAGE)>\n      <!ELEMENT TYPE (#PCDATA)>  <!-- One of LU, LLT, LDLT, ITER -->\n      <!ELEMENT PACKAGE (#PCDATA)>  <!-- Derived from a library -->\n  <!ELEMENT LINEARSYSTEM (MATRIX,SOLVER_STAT+,BEST_SOLVER,GLOBAL_PARAMS*)>\n    <!ELEMENT MATRIX (NAME,SIZE,ENTRIES,PATTERN?,SYMMETRY,POSDEF?,ARITHMETIC,RHS*)>\n      <!ELEMENT NAME (#PCDATA)>\n      <!ELEMENT SIZE (#PCDATA)>\n      <!ELEMENT ENTRIES (#PCDATA)> <!-- The number of nonzeros elements -->\n      <!ELEMENT PATTERN (#PCDATA)>  <!-- Is structural pattern symmetric or not -->\n      <!ELEMENT SYMMETRY (#PCDATA)> <!-- symmmetry with numerical values -->\n      <!ELEMENT POSDEF (#PCDATA)> <!-- Is the matrix positive definite or not -->\n      <!ELEMENT ARITHMETIC (#PCDATA)> \n      <!ELEMENT RHS (SOURCE)>  <!-- A matrix can have one or more right hand side associated. -->\n        <!ELEMENT SOURCE (#PCDATA)> <!-- Source of the right hand side, either generated or provided -->\n    <!ELEMENT SOLVER_STAT (PARAMS*,TIME,ERROR,ITER?)>\n      <!ELEMENT PARAMS (#PCDATA)>\n      <!ELEMENT TIME (COMPUTE,SOLVE,TOTAL)>\n        <!ELEMENT COMPUTE (#PCDATA)> <!-- Time to analyze,to factorize, or to setup the preconditioner-->\n        <!ELEMENT SOLVE (#PCDATA)> <!-- Time to solve with all the available rhs -->\n        <!ELEMENT TOTAL (#PCDATA)>\n      <!ELEMENT ERROR (#PCDATA)> <!-- Either the relative error or the relative residual norm -->\n      <!ELEMENT ITER (#PCDATA)> <!-- Number of iterations -->\n    <!ELEMENT BEST_SOLVER CDATA> <!-- Id of the best solver -->\n    <!ELEMENT GLOBAL_PARAMS (#PCDATA)> <!-- Parameters shared by all solvers -->\n\n<!ATTLIST SOLVER ID CDATA #REQUIRED>\n<!ATTLIST SOLVER_STAT ID CDATA #REQUIRED>\n<!ATTLIST BEST_SOLVER ID CDATA #REQUIRED>\n<!ATTLIST RHS ID CDATA #IMPLIED>"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/spbench/spbenchsolver.cpp",
    "content": "#include <bench/spbench/spbenchsolver.h>\n\nvoid bench_printhelp()\n{\n    cout<< \" \\nbenchsolver : performs a benchmark of all the solvers available in Eigen \\n\\n\";\n    cout<< \" MATRIX FOLDER : \\n\";\n    cout<< \" The matrices for the benchmark should be collected in a folder specified with an environment variable EIGEN_MATRIXDIR \\n\";\n    cout<< \" The matrices are stored using the matrix market coordinate format \\n\";\n    cout<< \" The matrix and associated right-hand side (rhs) files are named respectively \\n\";\n    cout<< \" as MatrixName.mtx and MatrixName_b.mtx. If the rhs does not exist, a random one is generated. \\n\";\n    cout<< \" If a matrix is SPD, the matrix should be named as MatrixName_SPD.mtx \\n\";\n    cout<< \" If a true solution exists, it should be named as MatrixName_x.mtx; \\n\"     ;\n    cout<< \" it will be used to compute the norm of the error relative to the computed solutions\\n\\n\";\n    cout<< \" OPTIONS : \\n\"; \n    cout<< \" -h or --help \\n    print this help and return\\n\\n\";\n    cout<< \" -d matrixdir \\n    Use matrixdir as the matrix folder instead of the one specified in the environment variable EIGEN_MATRIXDIR\\n\\n\"; \n    cout<< \" -o outputfile.xml \\n    Output the statistics to a xml file \\n\\n\";\n    cout<< \" --eps <RelErr> Sets the relative tolerance for iterative solvers (default 1e-08) \\n\\n\";\n    cout<< \" --maxits <MaxIts> Sets the maximum number of iterations (default 1000) \\n\\n\";\n    \n}\nint main(int argc, char ** args)\n{\n  \n  bool help = ( get_options(argc, args, \"-h\") || get_options(argc, args, \"--help\") );\n  if(help) {\n    bench_printhelp();\n    return 0;\n  }\n\n  // Get the location of the test matrices\n  string matrix_dir;\n  if (!get_options(argc, args, \"-d\", &matrix_dir))\n  {\n    if(getenv(\"EIGEN_MATRIXDIR\") == NULL){\n      std::cerr << \"Please, specify the location of the matrices with -d mat_folder or the environment variable EIGEN_MATRIXDIR \\n\";\n      std::cerr << \" Run with --help to see the list of all the available options \\n\";\n      return -1;\n    }\n    matrix_dir = getenv(\"EIGEN_MATRIXDIR\");\n  }\n     \n  std::ofstream statbuf;\n  string statFile ;\n  \n  // Get the file to write the statistics\n  bool statFileExists = get_options(argc, args, \"-o\", &statFile);\n  if(statFileExists)\n  {\n    statbuf.open(statFile.c_str(), std::ios::out);\n    if(statbuf.good()){\n      statFileExists = true; \n      printStatheader(statbuf);\n      statbuf.close();\n    }\n    else\n      std::cerr << \"Unable to open the provided file for writing... \\n\";\n  }       \n  \n  // Get the maximum number of iterations and the tolerance\n  int maxiters = 1000; \n  double tol = 1e-08; \n  string inval; \n  if (get_options(argc, args, \"--eps\", &inval))\n    tol = atof(inval.c_str()); \n  if(get_options(argc, args, \"--maxits\", &inval))\n    maxiters = atoi(inval.c_str()); \n  \n  string current_dir; \n  // Test the real-arithmetics matrices\n  Browse_Matrices<double>(matrix_dir, statFileExists, statFile,maxiters, tol);\n  \n  // Test the complex-arithmetics matrices\n  Browse_Matrices<std::complex<double> >(matrix_dir, statFileExists, statFile, maxiters, tol); \n  \n  if(statFileExists)\n  {\n    statbuf.open(statFile.c_str(), std::ios::app); \n    statbuf << \"</BENCH> \\n\";\n    cout << \"\\n Output written in \" << statFile << \" ...\\n\";\n    statbuf.close();\n  }\n\n  return 0;\n}\n\n      \n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/spbench/spbenchsolver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#include <iostream>\n#include <fstream>\n#include <Eigen/SparseCore>\n#include <bench/BenchTimer.h>\n#include <cstdlib>\n#include <string>\n#include <Eigen/Cholesky>\n#include <Eigen/Jacobi>\n#include <Eigen/Householder>\n#include <Eigen/IterativeLinearSolvers>\n#include <unsupported/Eigen/IterativeSolvers>\n#include <Eigen/LU>\n#include <unsupported/Eigen/SparseExtra>\n#include <Eigen/SparseLU>\n\n#include \"spbenchstyle.h\"\n\n#ifdef EIGEN_METIS_SUPPORT\n#include <Eigen/MetisSupport>\n#endif\n\n#ifdef EIGEN_CHOLMOD_SUPPORT\n#include <Eigen/CholmodSupport>\n#endif\n\n#ifdef EIGEN_UMFPACK_SUPPORT\n#include <Eigen/UmfPackSupport>\n#endif\n\n#ifdef EIGEN_KLU_SUPPORT\n#include <Eigen/KLUSupport>\n#endif\n\n#ifdef EIGEN_PARDISO_SUPPORT\n#include <Eigen/PardisoSupport>\n#endif\n\n#ifdef EIGEN_SUPERLU_SUPPORT\n#include <Eigen/SuperLUSupport>\n#endif\n\n#ifdef EIGEN_PASTIX_SUPPORT\n#include <Eigen/PaStiXSupport>\n#endif\n\n// CONSTANTS\n#define EIGEN_UMFPACK  10\n#define EIGEN_KLU  11\n#define EIGEN_SUPERLU  20\n#define EIGEN_PASTIX  30\n#define EIGEN_PARDISO  40\n#define EIGEN_SPARSELU_COLAMD 50\n#define EIGEN_SPARSELU_METIS 51\n#define EIGEN_BICGSTAB  60\n#define EIGEN_BICGSTAB_ILUT  61\n#define EIGEN_GMRES 70\n#define EIGEN_GMRES_ILUT 71\n#define EIGEN_SIMPLICIAL_LDLT  80\n#define EIGEN_CHOLMOD_LDLT  90\n#define EIGEN_PASTIX_LDLT  100\n#define EIGEN_PARDISO_LDLT  110\n#define EIGEN_SIMPLICIAL_LLT  120\n#define EIGEN_CHOLMOD_SUPERNODAL_LLT  130\n#define EIGEN_CHOLMOD_SIMPLICIAL_LLT  140\n#define EIGEN_PASTIX_LLT  150\n#define EIGEN_PARDISO_LLT  160\n#define EIGEN_CG  170\n#define EIGEN_CG_PRECOND  180\n\nusing namespace Eigen;\nusing namespace std; \n\n\n// Global variables for input parameters\nint MaximumIters; // Maximum number of iterations\ndouble RelErr; // Relative error of the computed solution\ndouble best_time_val; // Current best time overall solvers \nint best_time_id; //  id of the best solver for the current system \n\ntemplate<typename T> inline typename NumTraits<T>::Real test_precision() { return NumTraits<T>::dummy_precision(); }\ntemplate<> inline float test_precision<float>() { return 1e-3f; }                                                             \ntemplate<> inline double test_precision<double>() { return 1e-6; }                                                            \ntemplate<> inline float test_precision<std::complex<float> >() { return test_precision<float>(); }\ntemplate<> inline double test_precision<std::complex<double> >() { return test_precision<double>(); }\n\nvoid printStatheader(std::ofstream& out)\n{\n  // Print XML header\n  // NOTE It would have been much easier to write these XML documents using external libraries like tinyXML or Xerces-C++.\n  \n  out << \"<?xml version='1.0' encoding='UTF-8'?> \\n\";\n  out << \"<?xml-stylesheet type='text/xsl' href='#stylesheet' ?> \\n\"; \n  out << \"<!DOCTYPE BENCH  [\\n<!ATTLIST xsl:stylesheet\\n id\\t ID  #REQUIRED>\\n]>\";\n  out << \"\\n\\n<!-- Generated by the Eigen library -->\\n\"; \n  \n  out << \"\\n<BENCH> \\n\" ; //root XML element \n  // Print the xsl style section\n  printBenchStyle(out); \n  // List all available solvers \n  out << \" <AVAILSOLVER> \\n\";\n#ifdef EIGEN_UMFPACK_SUPPORT\n  out <<\"  <SOLVER ID='\" << EIGEN_UMFPACK << \"'>\\n\"; \n  out << \"   <TYPE> LU </TYPE> \\n\";\n  out << \"   <PACKAGE> UMFPACK </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n#endif\n#ifdef EIGEN_KLU_SUPPORT\n  out <<\"  <SOLVER ID='\" << EIGEN_KLU << \"'>\\n\";\n  out << \"   <TYPE> LU </TYPE> \\n\";\n  out << \"   <PACKAGE> KLU </PACKAGE> \\n\";\n  out << \"  </SOLVER> \\n\";\n#endif\n#ifdef EIGEN_SUPERLU_SUPPORT\n  out <<\"  <SOLVER ID='\" << EIGEN_SUPERLU << \"'>\\n\"; \n  out << \"   <TYPE> LU </TYPE> \\n\";\n  out << \"   <PACKAGE> SUPERLU </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n#endif\n#ifdef EIGEN_CHOLMOD_SUPPORT\n  out <<\"  <SOLVER ID='\" << EIGEN_CHOLMOD_SIMPLICIAL_LLT << \"'>\\n\"; \n  out << \"   <TYPE> LLT SP</TYPE> \\n\";\n  out << \"   <PACKAGE> CHOLMOD </PACKAGE> \\n\";\n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_CHOLMOD_SUPERNODAL_LLT << \"'>\\n\"; \n  out << \"   <TYPE> LLT</TYPE> \\n\";\n  out << \"   <PACKAGE> CHOLMOD </PACKAGE> \\n\";\n  out << \"  </SOLVER> \\n\";\n  \n  out <<\"  <SOLVER ID='\" << EIGEN_CHOLMOD_LDLT << \"'>\\n\"; \n  out << \"   <TYPE> LDLT </TYPE> \\n\";\n  out << \"   <PACKAGE> CHOLMOD </PACKAGE> \\n\";  \n  out << \"  </SOLVER> \\n\"; \n#endif\n#ifdef EIGEN_PARDISO_SUPPORT\n  out <<\"  <SOLVER ID='\" << EIGEN_PARDISO << \"'>\\n\"; \n  out << \"   <TYPE> LU </TYPE> \\n\";\n  out << \"   <PACKAGE> PARDISO </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_PARDISO_LLT << \"'>\\n\"; \n  out << \"   <TYPE> LLT </TYPE> \\n\";\n  out << \"   <PACKAGE> PARDISO </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_PARDISO_LDLT << \"'>\\n\"; \n  out << \"   <TYPE> LDLT </TYPE> \\n\";\n  out << \"   <PACKAGE> PARDISO </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n#endif\n#ifdef EIGEN_PASTIX_SUPPORT\n  out <<\"  <SOLVER ID='\" << EIGEN_PASTIX << \"'>\\n\"; \n  out << \"   <TYPE> LU </TYPE> \\n\";\n  out << \"   <PACKAGE> PASTIX </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_PASTIX_LLT << \"'>\\n\"; \n  out << \"   <TYPE> LLT </TYPE> \\n\";\n  out << \"   <PACKAGE> PASTIX </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_PASTIX_LDLT << \"'>\\n\"; \n  out << \"   <TYPE> LDLT </TYPE> \\n\";\n  out << \"   <PACKAGE> PASTIX </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n#endif\n  \n  out <<\"  <SOLVER ID='\" << EIGEN_BICGSTAB << \"'>\\n\"; \n  out << \"   <TYPE> BICGSTAB </TYPE> \\n\";\n  out << \"   <PACKAGE> EIGEN </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_BICGSTAB_ILUT << \"'>\\n\"; \n  out << \"   <TYPE> BICGSTAB_ILUT </TYPE> \\n\";\n  out << \"   <PACKAGE> EIGEN </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_GMRES_ILUT << \"'>\\n\"; \n  out << \"   <TYPE> GMRES_ILUT </TYPE> \\n\";\n  out << \"   <PACKAGE> EIGEN </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_SIMPLICIAL_LDLT << \"'>\\n\"; \n  out << \"   <TYPE> LDLT </TYPE> \\n\";\n  out << \"   <PACKAGE> EIGEN </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_SIMPLICIAL_LLT << \"'>\\n\"; \n  out << \"   <TYPE> LLT </TYPE> \\n\";\n  out << \"   <PACKAGE> EIGEN </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_CG << \"'>\\n\"; \n  out << \"   <TYPE> CG </TYPE> \\n\";\n  out << \"   <PACKAGE> EIGEN </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n  out <<\"  <SOLVER ID='\" << EIGEN_SPARSELU_COLAMD << \"'>\\n\"; \n  out << \"   <TYPE> LU_COLAMD </TYPE> \\n\";\n  out << \"   <PACKAGE> EIGEN </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n  \n#ifdef EIGEN_METIS_SUPPORT\n  out <<\"  <SOLVER ID='\" << EIGEN_SPARSELU_METIS << \"'>\\n\"; \n  out << \"   <TYPE> LU_METIS </TYPE> \\n\";\n  out << \"   <PACKAGE> EIGEN </PACKAGE> \\n\"; \n  out << \"  </SOLVER> \\n\"; \n#endif\n  out << \" </AVAILSOLVER> \\n\"; \n  \n}\n\n\ntemplate<typename Solver, typename Scalar>\nvoid call_solver(Solver &solver, const int solver_id, const typename Solver::MatrixType& A, const Matrix<Scalar, Dynamic, 1>& b, const Matrix<Scalar, Dynamic, 1>& refX,std::ofstream& statbuf)\n{\n  \n  double total_time;\n  double compute_time;\n  double solve_time; \n  double rel_error;\n  Matrix<Scalar, Dynamic, 1> x; \n  BenchTimer timer; \n  timer.reset();\n  timer.start();\n  solver.compute(A); \n  if (solver.info() != Success)\n  {\n    std::cerr << \"Solver failed ... \\n\";\n    return;\n  }\n  timer.stop();\n  compute_time = timer.value();\n  statbuf << \"    <TIME>\\n\"; \n  statbuf << \"     <COMPUTE> \" << timer.value() << \"</COMPUTE>\\n\";\n  std::cout<< \"COMPUTE TIME : \" << timer.value() <<std::endl; \n    \n  timer.reset();\n  timer.start();\n  x = solver.solve(b); \n  if (solver.info() == NumericalIssue)\n  {\n    std::cerr << \"Solver failed ... \\n\";\n    return;\n  }\n  timer.stop();\n  solve_time = timer.value();\n  statbuf << \"     <SOLVE> \" << timer.value() << \"</SOLVE>\\n\"; \n  std::cout<< \"SOLVE TIME : \" << timer.value() <<std::endl; \n  \n  total_time = solve_time + compute_time;\n  statbuf << \"     <TOTAL> \" << total_time << \"</TOTAL>\\n\"; \n  std::cout<< \"TOTAL TIME : \" << total_time <<std::endl; \n  statbuf << \"    </TIME>\\n\"; \n  \n  // Verify the relative error\n  if(refX.size() != 0)\n    rel_error = (refX - x).norm()/refX.norm();\n  else \n  {\n    // Compute the relative residual norm\n    Matrix<Scalar, Dynamic, 1> temp; \n    temp = A * x; \n    rel_error = (b-temp).norm()/b.norm();\n  }\n  statbuf << \"    <ERROR> \" << rel_error << \"</ERROR>\\n\"; \n  std::cout<< \"REL. ERROR : \" << rel_error << \"\\n\\n\" ;\n  if ( rel_error <= RelErr )\n  {\n    // check the best time if convergence\n    if(!best_time_val || (best_time_val > total_time))\n    {\n      best_time_val = total_time;\n      best_time_id = solver_id;\n    }\n  }\n}\n\ntemplate<typename Solver, typename Scalar>\nvoid call_directsolver(Solver& solver, const int solver_id, const typename Solver::MatrixType& A, const Matrix<Scalar, Dynamic, 1>& b, const Matrix<Scalar, Dynamic, 1>& refX, std::string& statFile)\n{\n    std::ofstream statbuf(statFile.c_str(), std::ios::app);\n    statbuf << \"   <SOLVER_STAT ID='\" << solver_id <<\"'>\\n\"; \n    call_solver(solver, solver_id, A, b, refX,statbuf);\n    statbuf << \"   </SOLVER_STAT>\\n\";\n    statbuf.close();\n}\n\ntemplate<typename Solver, typename Scalar>\nvoid call_itersolver(Solver &solver, const int solver_id, const typename Solver::MatrixType& A, const Matrix<Scalar, Dynamic, 1>& b, const Matrix<Scalar, Dynamic, 1>& refX, std::string& statFile)\n{\n  solver.setTolerance(RelErr); \n  solver.setMaxIterations(MaximumIters);\n  \n  std::ofstream statbuf(statFile.c_str(), std::ios::app);\n  statbuf << \" <SOLVER_STAT ID='\" << solver_id <<\"'>\\n\"; \n  call_solver(solver, solver_id, A, b, refX,statbuf); \n  statbuf << \"   <ITER> \"<< solver.iterations() << \"</ITER>\\n\";\n  statbuf << \" </SOLVER_STAT>\\n\";\n  std::cout << \"ITERATIONS : \" << solver.iterations() <<\"\\n\\n\\n\"; \n  \n}\n\n\ntemplate <typename Scalar>\nvoid SelectSolvers(const SparseMatrix<Scalar>&A, unsigned int sym, Matrix<Scalar, Dynamic, 1>& b, const Matrix<Scalar, Dynamic, 1>& refX, std::string& statFile)\n{\n  typedef SparseMatrix<Scalar, ColMajor> SpMat; \n  // First, deal with Nonsymmetric and symmetric matrices\n  best_time_id = 0; \n  best_time_val = 0.0;\n  //UMFPACK\n  #ifdef EIGEN_UMFPACK_SUPPORT\n  {\n    cout << \"Solving with UMFPACK LU ... \\n\"; \n    UmfPackLU<SpMat> solver; \n    call_directsolver(solver, EIGEN_UMFPACK, A, b, refX,statFile); \n  }\n  #endif\n  //KLU\n  #ifdef EIGEN_KLU_SUPPORT\n  {\n    cout << \"Solving with KLU LU ... \\n\";\n    KLU<SpMat> solver;\n    call_directsolver(solver, EIGEN_KLU, A, b, refX,statFile);\n  }\n  #endif\n    //SuperLU\n  #ifdef EIGEN_SUPERLU_SUPPORT\n  {\n    cout << \"\\nSolving with SUPERLU ... \\n\"; \n    SuperLU<SpMat> solver;\n    call_directsolver(solver, EIGEN_SUPERLU, A, b, refX,statFile); \n  }\n  #endif\n    \n   // PaStix LU\n  #ifdef EIGEN_PASTIX_SUPPORT\n  {\n    cout << \"\\nSolving with PASTIX LU ... \\n\"; \n    PastixLU<SpMat> solver; \n    call_directsolver(solver, EIGEN_PASTIX, A, b, refX,statFile) ;\n  }\n  #endif\n\n   //PARDISO LU\n  #ifdef EIGEN_PARDISO_SUPPORT\n  {\n    cout << \"\\nSolving with PARDISO LU ... \\n\"; \n    PardisoLU<SpMat>  solver; \n    call_directsolver(solver, EIGEN_PARDISO, A, b, refX,statFile);\n  }\n  #endif\n  \n  // Eigen SparseLU METIS\n  cout << \"\\n Solving with Sparse LU AND COLAMD ... \\n\";\n  SparseLU<SpMat, COLAMDOrdering<int> >   solver;\n  call_directsolver(solver, EIGEN_SPARSELU_COLAMD, A, b, refX, statFile); \n  // Eigen SparseLU METIS\n  #ifdef EIGEN_METIS_SUPPORT\n  {\n    cout << \"\\n Solving with Sparse LU AND METIS ... \\n\";\n    SparseLU<SpMat, MetisOrdering<int> >   solver;\n    call_directsolver(solver, EIGEN_SPARSELU_METIS, A, b, refX, statFile); \n  }\n  #endif\n  \n  //BiCGSTAB\n  {\n    cout << \"\\nSolving with BiCGSTAB ... \\n\"; \n    BiCGSTAB<SpMat> solver; \n    call_itersolver(solver, EIGEN_BICGSTAB, A, b, refX,statFile);\n  }\n  //BiCGSTAB+ILUT\n  {\n    cout << \"\\nSolving with BiCGSTAB and ILUT ... \\n\"; \n    BiCGSTAB<SpMat, IncompleteLUT<Scalar> > solver; \n    call_itersolver(solver, EIGEN_BICGSTAB_ILUT, A, b, refX,statFile); \n  }\n  \n   \n  //GMRES\n//   {\n//     cout << \"\\nSolving with GMRES ... \\n\"; \n//     GMRES<SpMat> solver; \n//     call_itersolver(solver, EIGEN_GMRES, A, b, refX,statFile); \n//   }\n  //GMRES+ILUT\n  {\n    cout << \"\\nSolving with GMRES and ILUT ... \\n\"; \n    GMRES<SpMat, IncompleteLUT<Scalar> > solver; \n    call_itersolver(solver, EIGEN_GMRES_ILUT, A, b, refX,statFile);\n  }\n  \n  // Hermitian and not necessarily positive-definites\n  if (sym != NonSymmetric)\n  {\n    // Internal Cholesky\n    {\n      cout << \"\\nSolving with Simplicial LDLT ... \\n\"; \n      SimplicialLDLT<SpMat, Lower> solver;\n      call_directsolver(solver, EIGEN_SIMPLICIAL_LDLT, A, b, refX,statFile); \n    }\n    \n    // CHOLMOD\n    #ifdef EIGEN_CHOLMOD_SUPPORT\n    {\n      cout << \"\\nSolving with CHOLMOD LDLT ... \\n\"; \n      CholmodDecomposition<SpMat, Lower> solver;\n      solver.setMode(CholmodLDLt);\n       call_directsolver(solver,EIGEN_CHOLMOD_LDLT, A, b, refX,statFile);\n    }\n    #endif\n    \n    //PASTIX LLT\n    #ifdef EIGEN_PASTIX_SUPPORT\n    {\n      cout << \"\\nSolving with PASTIX LDLT ... \\n\"; \n      PastixLDLT<SpMat, Lower> solver; \n      call_directsolver(solver,EIGEN_PASTIX_LDLT, A, b, refX,statFile); \n    }\n    #endif\n    \n    //PARDISO LLT\n    #ifdef EIGEN_PARDISO_SUPPORT\n    {\n      cout << \"\\nSolving with PARDISO LDLT ... \\n\"; \n      PardisoLDLT<SpMat, Lower> solver; \n      call_directsolver(solver,EIGEN_PARDISO_LDLT, A, b, refX,statFile); \n    }\n    #endif\n  }\n\n   // Now, symmetric POSITIVE DEFINITE matrices\n  if (sym == SPD)\n  {\n    \n    //Internal Sparse Cholesky\n    {\n      cout << \"\\nSolving with SIMPLICIAL LLT ... \\n\"; \n      SimplicialLLT<SpMat, Lower> solver; \n      call_directsolver(solver,EIGEN_SIMPLICIAL_LLT, A, b, refX,statFile); \n    }\n    \n    // CHOLMOD\n    #ifdef EIGEN_CHOLMOD_SUPPORT\n    {\n      // CholMOD SuperNodal LLT\n      cout << \"\\nSolving with CHOLMOD LLT (Supernodal)... \\n\"; \n      CholmodDecomposition<SpMat, Lower> solver;\n      solver.setMode(CholmodSupernodalLLt);\n       call_directsolver(solver,EIGEN_CHOLMOD_SUPERNODAL_LLT, A, b, refX,statFile);\n      // CholMod Simplicial LLT\n      cout << \"\\nSolving with CHOLMOD LLT (Simplicial) ... \\n\"; \n      solver.setMode(CholmodSimplicialLLt);\n      call_directsolver(solver,EIGEN_CHOLMOD_SIMPLICIAL_LLT, A, b, refX,statFile);\n    }\n    #endif\n    \n    //PASTIX LLT\n    #ifdef EIGEN_PASTIX_SUPPORT\n    {\n      cout << \"\\nSolving with PASTIX LLT ... \\n\"; \n      PastixLLT<SpMat, Lower> solver; \n      call_directsolver(solver,EIGEN_PASTIX_LLT, A, b, refX,statFile);\n    }\n    #endif\n    \n    //PARDISO LLT\n    #ifdef EIGEN_PARDISO_SUPPORT\n    {\n      cout << \"\\nSolving with PARDISO LLT ... \\n\"; \n      PardisoLLT<SpMat, Lower> solver; \n      call_directsolver(solver,EIGEN_PARDISO_LLT, A, b, refX,statFile); \n    }\n    #endif\n    \n    // Internal CG\n    {\n      cout << \"\\nSolving with CG ... \\n\"; \n      ConjugateGradient<SpMat, Lower> solver; \n      call_itersolver(solver,EIGEN_CG, A, b, refX,statFile);\n    }\n    //CG+IdentityPreconditioner\n//     {\n//       cout << \"\\nSolving with CG and IdentityPreconditioner ... \\n\"; \n//       ConjugateGradient<SpMat, Lower, IdentityPreconditioner> solver; \n//       call_itersolver(solver,EIGEN_CG_PRECOND, A, b, refX,statFile);\n//     }\n  } // End SPD matrices \n}\n\n/* Browse all the matrices available in the specified folder \n * and solve the associated linear system.\n * The results of each solve are printed in the standard output\n * and optionally in the provided html file\n */\ntemplate <typename Scalar>\nvoid Browse_Matrices(const string folder, bool statFileExists, std::string& statFile, int maxiters, double tol)\n{\n  MaximumIters = maxiters; // Maximum number of iterations, global variable \n  RelErr = tol;  //Relative residual error  as stopping criterion for iterative solvers\n  MatrixMarketIterator<Scalar> it(folder);\n  for ( ; it; ++it)\n  {\n    //print the infos for this linear system \n    if(statFileExists)\n    {\n      std::ofstream statbuf(statFile.c_str(), std::ios::app);\n      statbuf << \"<LINEARSYSTEM> \\n\";\n      statbuf << \"   <MATRIX> \\n\";\n      statbuf << \"     <NAME> \" << it.matname() << \" </NAME>\\n\"; \n      statbuf << \"     <SIZE> \" << it.matrix().rows() << \" </SIZE>\\n\"; \n      statbuf << \"     <ENTRIES> \" << it.matrix().nonZeros() << \"</ENTRIES>\\n\";\n      if (it.sym()!=NonSymmetric)\n      {\n        statbuf << \"     <SYMMETRY> Symmetric </SYMMETRY>\\n\" ; \n        if (it.sym() == SPD) \n          statbuf << \"     <POSDEF> YES </POSDEF>\\n\"; \n        else \n          statbuf << \"     <POSDEF> NO </POSDEF>\\n\"; \n          \n      }\n      else\n      {\n        statbuf << \"     <SYMMETRY> NonSymmetric </SYMMETRY>\\n\" ; \n        statbuf << \"     <POSDEF> NO </POSDEF>\\n\"; \n      }\n      statbuf << \"   </MATRIX> \\n\";\n      statbuf.close();\n    }\n    \n    cout<< \"\\n\\n===================================================== \\n\";\n    cout<< \" ======  SOLVING WITH MATRIX \" << it.matname() << \" ====\\n\";\n    cout<< \" =================================================== \\n\\n\";\n    Matrix<Scalar, Dynamic, 1> refX;\n    if(it.hasrefX()) refX = it.refX();\n    // Call all suitable solvers for this linear system \n    SelectSolvers<Scalar>(it.matrix(), it.sym(), it.rhs(), refX, statFile);\n    \n    if(statFileExists)\n    {\n      std::ofstream statbuf(statFile.c_str(), std::ios::app);\n      statbuf << \"  <BEST_SOLVER ID='\"<< best_time_id\n              << \"'></BEST_SOLVER>\\n\"; \n      statbuf << \" </LINEARSYSTEM> \\n\"; \n      statbuf.close();\n    }\n  } \n} \n\nbool get_options(int argc, char **args, string option, string* value=0)\n{\n  int idx = 1, found=false; \n  while (idx<argc && !found){\n    if (option.compare(args[idx]) == 0){\n      found = true; \n      if(value) *value = args[idx+1];\n    }\n    idx+=2;\n  }\n  return found; \n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/spbench/spbenchstyle.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef SPBENCHSTYLE_H\n#define SPBENCHSTYLE_H\n\nvoid printBenchStyle(std::ofstream& out)\n{\n  out << \"<xsl:stylesheet id='stylesheet' version='1.0' \\\n      xmlns:xsl='http://www.w3.org/1999/XSL/Transform' >\\n \\\n      <xsl:template match='xsl:stylesheet' />\\n \\\n      <xsl:template match='/'> <!-- Root of the document -->\\n \\\n      <html>\\n \\\n        <head> \\n \\\n          <style type='text/css'> \\n \\\n            td { white-space: nowrap;}\\n \\\n          </style>\\n \\\n        </head>\\n \\\n        <body>\";\n  out<<\"<table border='1' width='100%' height='100%'>\\n \\\n        <TR> <!-- Write the table header -->\\n \\\n        <TH>Matrix</TH> <TH>N</TH> <TH> NNZ</TH>  <TH> Sym</TH>  <TH> SPD</TH> <TH> </TH>\\n \\\n          <xsl:for-each select='BENCH/AVAILSOLVER/SOLVER'>\\n \\\n            <xsl:sort select='@ID' data-type='number'/>\\n \\\n            <TH>\\n \\\n              <xsl:value-of select='TYPE' />\\n \\\n              <xsl:text></xsl:text>\\n \\\n              <xsl:value-of select='PACKAGE' />\\n \\\n              <xsl:text></xsl:text>\\n \\\n            </TH>\\n \\\n          </xsl:for-each>\\n \\\n        </TR>\";\n        \n  out<<\"  <xsl:for-each select='BENCH/LINEARSYSTEM'>\\n \\\n          <TR> <!-- print statistics for one linear system-->\\n \\\n            <TH rowspan='4'> <xsl:value-of select='MATRIX/NAME' /> </TH>\\n \\\n            <TD rowspan='4'> <xsl:value-of select='MATRIX/SIZE' /> </TD>\\n \\\n            <TD rowspan='4'> <xsl:value-of select='MATRIX/ENTRIES' /> </TD>\\n \\\n            <TD rowspan='4'> <xsl:value-of select='MATRIX/SYMMETRY' /> </TD>\\n \\\n            <TD rowspan='4'> <xsl:value-of select='MATRIX/POSDEF' /> </TD>\\n \\\n            <TH> Compute Time </TH>\\n \\\n            <xsl:for-each select='SOLVER_STAT'>\\n \\\n              <xsl:sort select='@ID' data-type='number'/>\\n \\\n              <TD> <xsl:value-of select='TIME/COMPUTE' /> </TD>\\n \\\n            </xsl:for-each>\\n \\\n          </TR>\";\n  out<<\"  <TR>\\n \\\n            <TH> Solve Time </TH>\\n \\\n            <xsl:for-each select='SOLVER_STAT'>\\n \\\n              <xsl:sort select='@ID' data-type='number'/>\\n \\\n              <TD> <xsl:value-of select='TIME/SOLVE' /> </TD>\\n \\\n            </xsl:for-each>\\n \\\n          </TR>\\n \\\n          <TR>\\n \\\n            <TH> Total Time </TH>\\n \\\n            <xsl:for-each select='SOLVER_STAT'>\\n \\\n              <xsl:sort select='@ID' data-type='number'/>\\n \\\n              <xsl:choose>\\n \\\n                <xsl:when test='@ID=../BEST_SOLVER/@ID'>\\n \\\n                  <TD style='background-color:red'> <xsl:value-of select='TIME/TOTAL' />  </TD>\\n \\\n                </xsl:when>\\n \\\n                <xsl:otherwise>\\n \\\n                  <TD>  <xsl:value-of select='TIME/TOTAL' /></TD>\\n \\\n                </xsl:otherwise>\\n \\\n              </xsl:choose>\\n \\\n            </xsl:for-each>\\n \\\n          </TR>\";\n  out<<\"  <TR>\\n \\\n              <TH> Error </TH>\\n \\\n              <xsl:for-each select='SOLVER_STAT'>\\n \\\n                <xsl:sort select='@ID' data-type='number'/>\\n \\\n                <TD> <xsl:value-of select='ERROR' />\\n \\\n                <xsl:if test='ITER'>\\n \\\n                  <xsl:text>(</xsl:text>\\n \\\n                  <xsl:value-of select='ITER' />\\n \\\n                  <xsl:text>)</xsl:text>\\n \\\n                </xsl:if> </TD>\\n \\\n              </xsl:for-each>\\n \\\n            </TR>\\n \\\n          </xsl:for-each>\\n \\\n      </table>\\n \\\n    </body>\\n \\\n    </html>\\n \\\n  </xsl:template>\\n \\\n  </xsl:stylesheet>\\n\\n\";\n  \n}\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/spbench/test_sparseLU.cpp",
    "content": "// Small bench routine for Eigen available in Eigen\n// (C) Desire NUENTSA WAKAM, INRIA\n\n#include <iostream>\n#include <fstream>\n#include <iomanip>\n#include <unsupported/Eigen/SparseExtra>\n#include <Eigen/SparseLU>\n#include <bench/BenchTimer.h>\n#ifdef EIGEN_METIS_SUPPORT\n#include <Eigen/MetisSupport>\n#endif\n\nusing namespace std;\nusing namespace Eigen;\n\nint main(int argc, char **args)\n{\n//   typedef complex<double> scalar; \n  typedef double scalar; \n  SparseMatrix<scalar, ColMajor> A; \n  typedef SparseMatrix<scalar, ColMajor>::Index Index;\n  typedef Matrix<scalar, Dynamic, Dynamic> DenseMatrix;\n  typedef Matrix<scalar, Dynamic, 1> DenseRhs;\n  Matrix<scalar, Dynamic, 1> b, x, tmp;\n//   SparseLU<SparseMatrix<scalar, ColMajor>, AMDOrdering<int> >   solver;\n// #ifdef EIGEN_METIS_SUPPORT\n//   SparseLU<SparseMatrix<scalar, ColMajor>, MetisOrdering<int> > solver; \n//   std::cout<< \"ORDERING : METIS\\n\"; \n// #else\n  SparseLU<SparseMatrix<scalar, ColMajor>, COLAMDOrdering<int> >  solver;\n  std::cout<< \"ORDERING : COLAMD\\n\"; \n// #endif\n  \n  ifstream matrix_file; \n  string line;\n  int  n;\n  BenchTimer timer; \n  \n  // Set parameters\n  /* Fill the matrix with sparse matrix stored in Matrix-Market coordinate column-oriented format */\n  if (argc < 2) assert(false && \"please, give the matrix market file \");\n  loadMarket(A, args[1]);\n  cout << \"End charging matrix \" << endl;\n  bool iscomplex=false, isvector=false;\n  int sym;\n  getMarketHeader(args[1], sym, iscomplex, isvector);\n//   if (iscomplex) { cout<< \" Not for complex matrices \\n\"; return -1; }\n  if (isvector) { cout << \"The provided file is not a matrix file\\n\"; return -1;}\n  if (sym != 0) { // symmetric matrices, only the lower part is stored\n    SparseMatrix<scalar, ColMajor> temp; \n    temp = A;\n    A = temp.selfadjointView<Lower>();\n  }\n  n = A.cols();\n  /* Fill the right hand side */\n\n  if (argc > 2)\n    loadMarketVector(b, args[2]);\n  else \n  {\n    b.resize(n);\n    tmp.resize(n);\n//       tmp.setRandom();\n    for (int i = 0; i < n; i++) tmp(i) = i; \n    b = A * tmp ;\n  }\n\n  /* Compute the factorization */\n//   solver.isSymmetric(true);\n  timer.start(); \n//   solver.compute(A);\n  solver.analyzePattern(A); \n  timer.stop(); \n  cout << \"Time to analyze \" << timer.value() << std::endl;\n  timer.reset(); \n  timer.start(); \n  solver.factorize(A); \n  timer.stop(); \n  cout << \"Factorize Time \" << timer.value() << std::endl;\n  timer.reset(); \n  timer.start(); \n  x = solver.solve(b);\n  timer.stop();\n  cout << \"solve time \" << timer.value() << std::endl; \n  /* Check the accuracy */\n  Matrix<scalar, Dynamic, 1> tmp2 = b - A*x;\n  scalar tempNorm = tmp2.norm()/b.norm();\n  cout << \"Relative norm of the computed solution : \" << tempNorm <<\"\\n\";\n  cout << \"Number of nonzeros in the factor : \" << solver.nnzL() + solver.nnzU() << std::endl; \n  \n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/spmv.cpp",
    "content": "\n//g++-4.4 -DNOMTL  -Wl,-rpath /usr/local/lib/oski -L /usr/local/lib/oski/ -l oski -l oski_util -l oski_util_Tid  -DOSKI -I ~/Coding/LinearAlgebra/mtl4/  spmv.cpp  -I .. -O2 -DNDEBUG -lrt  -lm -l oski_mat_CSC_Tid  -loskilt && ./a.out r200000 c200000 n100 t1 p1\n\n#define SCALAR double\n\n#include <iostream>\n#include <algorithm>\n#include \"BenchTimer.h\"\n#include \"BenchSparseUtil.h\"\n\n#define SPMV_BENCH(CODE) BENCH(t,tries,repeats,CODE);\n\n// #ifdef MKL\n//\n// #include \"mkl_types.h\"\n// #include \"mkl_spblas.h\"\n//\n// template<typename Lhs,typename Rhs,typename Res>\n// void mkl_multiply(const Lhs& lhs, const Rhs& rhs, Res& res)\n// {\n//   char n = 'N';\n//   float alpha = 1;\n//   char matdescra[6];\n//   matdescra[0] = 'G';\n//   matdescra[1] = 0;\n//   matdescra[2] = 0;\n//   matdescra[3] = 'C';\n//   mkl_scscmm(&n, lhs.rows(), rhs.cols(), lhs.cols(), &alpha, matdescra,\n//              lhs._valuePtr(), lhs._innerIndexPtr(), lhs.outerIndexPtr(),\n//              pntre, b, &ldb, &beta, c, &ldc);\n// //   mkl_somatcopy('C', 'T', lhs.rows(), lhs.cols(), 1,\n// //                 lhs._valuePtr(), lhs.rows(), DST, dst_stride);\n// }\n//\n// #endif\n\nint main(int argc, char *argv[])\n{\n  int size = 10000;\n  int rows = size;\n  int cols = size;\n  int nnzPerCol = 40;\n  int tries = 2;\n  int repeats = 2;\n\n  bool need_help = false;\n  for(int i = 1; i < argc; i++)\n  {\n    if(argv[i][0] == 'r')\n    {\n      rows = atoi(argv[i]+1);\n    }\n    else if(argv[i][0] == 'c')\n    {\n      cols = atoi(argv[i]+1);\n    }\n    else if(argv[i][0] == 'n')\n    {\n      nnzPerCol = atoi(argv[i]+1);\n    }\n    else if(argv[i][0] == 't')\n    {\n      tries = atoi(argv[i]+1);\n    }\n    else if(argv[i][0] == 'p')\n    {\n      repeats = atoi(argv[i]+1);\n    }\n    else\n    {\n      need_help = true;\n    }\n  }\n  if(need_help)\n  {\n    std::cout << argv[0] << \" r<nb rows> c<nb columns> n<non zeros per column> t<nb tries> p<nb repeats>\\n\";\n    return 1;\n  }\n\n  std::cout << \"SpMV \" << rows << \" x \" << cols << \" with \" << nnzPerCol << \" non zeros per column. (\" << repeats << \" repeats, and \" << tries << \" tries)\\n\\n\";\n\n  EigenSparseMatrix sm(rows,cols);\n  DenseVector dv(cols), res(rows);\n  dv.setRandom();\n\n  BenchTimer t;\n  while (nnzPerCol>=4)\n  {\n    std::cout << \"nnz: \" << nnzPerCol << \"\\n\";\n    sm.setZero();\n    fillMatrix2(nnzPerCol, rows, cols, sm);\n\n    // dense matrices\n    #ifdef DENSEMATRIX\n    {\n      DenseMatrix dm(rows,cols), (rows,cols);\n      eiToDense(sm, dm);\n\n      SPMV_BENCH(res = dm * sm);\n      std::cout << \"Dense       \" << t.value()/repeats << \"\\t\";\n\n      SPMV_BENCH(res = dm.transpose() * sm);\n      std::cout << t.value()/repeats << endl;\n    }\n    #endif\n\n    // eigen sparse matrices\n    {\n      SPMV_BENCH(res.noalias() += sm * dv; )\n      std::cout << \"Eigen       \" << t.value()/repeats << \"\\t\";\n\n      SPMV_BENCH(res.noalias() += sm.transpose() * dv; )\n      std::cout << t.value()/repeats << endl;\n    }\n\n    // CSparse\n    #ifdef CSPARSE\n    {\n      std::cout << \"CSparse \\n\";\n      cs *csm;\n      eiToCSparse(sm, csm);\n\n//       BENCH();\n//       timer.stop();\n//       std::cout << \"   a * b:\\t\" << timer.value() << endl;\n\n//       BENCH( { m3 = cs_sorted_multiply2(m1, m2); cs_spfree(m3); } );\n//       std::cout << \"   a * b:\\t\" << timer.value() << endl;\n    }\n    #endif\n\n    #ifdef OSKI\n    {\n      oski_matrix_t om;\n      oski_vecview_t ov, ores;\n      oski_Init();\n      om = oski_CreateMatCSC(sm._outerIndexPtr(), sm._innerIndexPtr(), sm._valuePtr(), rows, cols,\n                             SHARE_INPUTMAT, 1, INDEX_ZERO_BASED);\n      ov = oski_CreateVecView(dv.data(), cols, STRIDE_UNIT);\n      ores = oski_CreateVecView(res.data(), rows, STRIDE_UNIT);\n\n      SPMV_BENCH( oski_MatMult(om, OP_NORMAL, 1, ov, 0, ores) );\n      std::cout << \"OSKI        \" << t.value()/repeats << \"\\t\";\n\n      SPMV_BENCH( oski_MatMult(om, OP_TRANS, 1, ov, 0, ores) );\n      std::cout << t.value()/repeats << \"\\n\";\n\n      // tune\n      t.reset();\n      t.start();\n      oski_SetHintMatMult(om, OP_NORMAL, 1.0, SYMBOLIC_VEC, 0.0, SYMBOLIC_VEC, ALWAYS_TUNE_AGGRESSIVELY);\n      oski_TuneMat(om);\n      t.stop();\n      double tuning = t.value();\n\n      SPMV_BENCH( oski_MatMult(om, OP_NORMAL, 1, ov, 0, ores) );\n      std::cout << \"OSKI tuned  \" << t.value()/repeats << \"\\t\";\n\n      SPMV_BENCH( oski_MatMult(om, OP_TRANS, 1, ov, 0, ores) );\n      std::cout << t.value()/repeats << \"\\t(\" << tuning <<  \")\\n\";\n\n\n      oski_DestroyMat(om);\n      oski_DestroyVecView(ov);\n      oski_DestroyVecView(ores);\n      oski_Close();\n    }\n    #endif\n\n    #ifndef NOUBLAS\n    {\n      using namespace boost::numeric;\n      UblasMatrix um(rows,cols);\n      eiToUblas(sm, um);\n\n      boost::numeric::ublas::vector<Scalar> uv(cols), ures(rows);\n      Map<Matrix<Scalar,Dynamic,1> >(&uv[0], cols) = dv;\n      Map<Matrix<Scalar,Dynamic,1> >(&ures[0], rows) = res;\n\n      SPMV_BENCH(ublas::axpy_prod(um, uv, ures, true));\n      std::cout << \"ublas       \" << t.value()/repeats << \"\\t\";\n\n      SPMV_BENCH(ublas::axpy_prod(boost::numeric::ublas::trans(um), uv, ures, true));\n      std::cout << t.value()/repeats << endl;\n    }\n    #endif\n\n    // GMM++\n    #ifndef NOGMM\n    {\n      GmmSparse gm(rows,cols);\n      eiToGmm(sm, gm);\n\n      std::vector<Scalar> gv(cols), gres(rows);\n      Map<Matrix<Scalar,Dynamic,1> >(&gv[0], cols) = dv;\n      Map<Matrix<Scalar,Dynamic,1> >(&gres[0], rows) = res;\n\n      SPMV_BENCH(gmm::mult(gm, gv, gres));\n      std::cout << \"GMM++       \" << t.value()/repeats << \"\\t\";\n\n      SPMV_BENCH(gmm::mult(gmm::transposed(gm), gv, gres));\n      std::cout << t.value()/repeats << endl;\n    }\n    #endif\n\n    // MTL4\n    #ifndef NOMTL\n    {\n      MtlSparse mm(rows,cols);\n      eiToMtl(sm, mm);\n      mtl::dense_vector<Scalar> mv(cols, 1.0);\n      mtl::dense_vector<Scalar> mres(rows, 1.0);\n\n      SPMV_BENCH(mres = mm * mv);\n      std::cout << \"MTL4        \" << t.value()/repeats << \"\\t\";\n\n      SPMV_BENCH(mres = trans(mm) * mv);\n      std::cout << t.value()/repeats << endl;\n    }\n    #endif\n\n    std::cout << \"\\n\";\n\n    if(nnzPerCol==1)\n      break;\n    nnzPerCol -= nnzPerCol/2;\n  }\n\n  return 0;\n}\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/tensors/README",
    "content": "The tensor benchmark suite is made of several parts.\n\nThe first part is a generic suite, in which each benchmark comes in 2 flavors: one that runs on CPU, and one that runs on GPU.\n\nTo compile the floating point CPU benchmarks, simply call:\ng++ tensor_benchmarks_cpu.cc benchmark_main.cc -I ../../ -std=c++11 -O3 -DNDEBUG -pthread -mavx -o benchmarks_cpu\n\nTo compile the floating point GPU benchmarks, simply call:\nnvcc tensor_benchmarks_gpu.cu benchmark_main.cc -I ../../ -std=c++11 -O2 -DNDEBUG -use_fast_math -ftz=true -arch compute_35 -o benchmarks_gpu\n\nWe also provide a version of the generic GPU tensor benchmarks that uses half floats (aka fp16) instead of regular floats. To compile these benchmarks, simply call the command line below. You'll need a recent GPU that supports compute capability 5.3 or higher to run them and nvcc 7.5 or higher to compile the code.\nnvcc tensor_benchmarks_fp16_gpu.cu benchmark_main.cc -I ../../ -std=c++11 -O2 -DNDEBUG -use_fast_math -ftz=true -arch compute_53 -o benchmarks_fp16_gpu\n\nTo compile and run the benchmark for SYCL, using ComputeCpp, simply run the\nfollowing commands:\n1. export COMPUTECPP_PACKAGE_ROOT_DIR={PATH TO COMPUTECPP ROOT DIRECTORY}\n2. bash eigen_sycl_bench.sh\n\nLast but not least, we also provide a suite of benchmarks to measure the scalability of the contraction code on CPU. To compile these benchmarks, call\ng++ contraction_benchmarks_cpu.cc benchmark_main.cc -I ../../ -std=c++11 -O3 -DNDEBUG -pthread -mavx -o benchmarks_cpu\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/tensors/benchmark.h",
    "content": "/*\n * Copyright (C) 2012 The Android Open Source Project\n *\n * Licensed under the Apache License, Version 2.0 (the \"License\");\n * you may not use this file except in compliance with the License.\n * You may obtain a copy of the License at\n *\n *      http://www.apache.org/licenses/LICENSE-2.0\n *\n * Unless required by applicable law or agreed to in writing, software\n * distributed under the License is distributed on an \"AS IS\" BASIS,\n * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n * See the License for the specific language governing permissions and\n * limitations under the License.\n */\n#include <stddef.h>\n#include <stdint.h>\n#include <vector>\n\nnamespace testing {\nclass Benchmark {\n public:\n  Benchmark(const char* name, void (*fn)(int)) {\n    Register(name, fn, NULL);\n  }\n  Benchmark(const char* name, void (*fn_range)(int, int)) {\n    Register(name, NULL, fn_range);\n  }\n  Benchmark* Arg(int x);\n  Benchmark* Range(int lo, int hi);\n  const char* Name();\n  bool ShouldRun(int argc, char* argv[]);\n  void Run();\n private:\n  const char* name_;\n  void (*fn_)(int);\n  void (*fn_range_)(int, int);\n  std::vector<int> args_;\n  void Register(const char* name, void (*fn)(int), void (*fn_range)(int, int));\n  void RunRepeatedlyWithArg(int iterations, int arg);\n  void RunWithArg(int arg);\n};\n}  // namespace testing\nvoid SetBenchmarkFlopsProcessed(int64_t);\nvoid StopBenchmarkTiming();\nvoid StartBenchmarkTiming();\n#define BENCHMARK(f) \\\n    static ::testing::Benchmark* _benchmark_##f __attribute__((unused)) = \\\n        (new ::testing::Benchmark(#f, f))\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/tensors/benchmark_main.cc",
    "content": "/*\n * Copyright (C) 2012 The Android Open Source Project\n *\n * Licensed under the Apache License, Version 2.0 (the \"License\");\n * you may not use this file except in compliance with the License.\n * You may obtain a copy of the License at\n *\n *      http://www.apache.org/licenses/LICENSE-2.0\n *\n * Unless required by applicable law or agreed to in writing, software\n * distributed under the License is distributed on an \"AS IS\" BASIS,\n * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n * See the License for the specific language governing permissions and\n * limitations under the License.\n */\n#include \"benchmark.h\"\n#include <regex.h>\n#include <stdio.h>\n#include <stdlib.h>\n#include <string.h>\n#include <string>\n#include <inttypes.h>\n#include <time.h>\n#include <map>\n\nstatic int64_t g_flops_processed;\nstatic int64_t g_benchmark_total_time_ns;\nstatic int64_t g_benchmark_start_time_ns;\ntypedef std::map<std::string, ::testing::Benchmark*> BenchmarkMap;\ntypedef BenchmarkMap::iterator BenchmarkMapIt;\n\nBenchmarkMap& gBenchmarks() {\n  static BenchmarkMap g_benchmarks;\n  return g_benchmarks;\n}\n\nstatic int g_name_column_width = 20;\n\nstatic int Round(int n) {\n  int base = 1;\n  while (base*10 < n) {\n    base *= 10;\n  }\n  if (n < 2*base) {\n    return 2*base;\n  }\n  if (n < 5*base) {\n    return 5*base;\n  }\n  return 10*base;\n}\n\n#ifdef __APPLE__\n  #include <mach/mach_time.h>\n  static mach_timebase_info_data_t g_time_info;\n  static void __attribute__((constructor)) init_info() {\n    mach_timebase_info(&g_time_info);\n  }\n#endif\n\nstatic int64_t NanoTime() {\n#if defined(__APPLE__)\n  uint64_t t = mach_absolute_time();\n  return t * g_time_info.numer / g_time_info.denom;\n#else\n  struct timespec t;\n  t.tv_sec = t.tv_nsec = 0;\n  clock_gettime(CLOCK_MONOTONIC, &t);\n  return static_cast<int64_t>(t.tv_sec) * 1000000000LL + t.tv_nsec;\n#endif\n}\n\nnamespace testing {\nBenchmark* Benchmark::Arg(int arg) {\n  args_.push_back(arg);\n  return this;\n}\n\nBenchmark* Benchmark::Range(int lo, int hi) {\n  const int kRangeMultiplier = 8;\n  if (hi < lo) {\n    int temp = hi;\n    hi = lo;\n    lo = temp;\n  }\n  while (lo < hi) {\n    args_.push_back(lo);\n    lo *= kRangeMultiplier;\n  }\n  // We always run the hi number.\n  args_.push_back(hi);\n  return this;\n}\n\nconst char* Benchmark::Name() {\n  return name_;\n}\nbool Benchmark::ShouldRun(int argc, char* argv[]) {\n  if (argc == 1) {\n    return true;  // With no arguments, we run all benchmarks.\n  }\n  // Otherwise, we interpret each argument as a regular expression and\n  // see if any of our benchmarks match.\n  for (int i = 1; i < argc; i++) {\n    regex_t re;\n    if (regcomp(&re, argv[i], 0) != 0) {\n      fprintf(stderr, \"couldn't compile \\\"%s\\\" as a regular expression!\\n\", argv[i]);\n      exit(EXIT_FAILURE);\n    }\n    int match = regexec(&re, name_, 0, NULL, 0);\n    regfree(&re);\n    if (match != REG_NOMATCH) {\n      return true;\n    }\n  }\n  return false;\n}\nvoid Benchmark::Register(const char* name, void (*fn)(int), void (*fn_range)(int, int)) {\n  name_ = name;\n  fn_ = fn;\n  fn_range_ = fn_range;\n  if (fn_ == NULL && fn_range_ == NULL) {\n    fprintf(stderr, \"%s: missing function\\n\", name_);\n    exit(EXIT_FAILURE);\n  }\n  gBenchmarks().insert(std::make_pair(name, this));\n}\nvoid Benchmark::Run() {\n  if (fn_ != NULL) {\n    RunWithArg(0);\n  } else {\n    if (args_.empty()) {\n      fprintf(stderr, \"%s: no args!\\n\", name_);\n      exit(EXIT_FAILURE);\n    }\n    for (size_t i = 0; i < args_.size(); ++i) {\n      RunWithArg(args_[i]);\n    }\n  }\n}\nvoid Benchmark::RunRepeatedlyWithArg(int iterations, int arg) {\n  g_flops_processed = 0;\n  g_benchmark_total_time_ns = 0;\n  g_benchmark_start_time_ns = NanoTime();\n  if (fn_ != NULL) {\n    fn_(iterations);\n  } else {\n    fn_range_(iterations, arg);\n  }\n  if (g_benchmark_start_time_ns != 0) {\n    g_benchmark_total_time_ns += NanoTime() - g_benchmark_start_time_ns;\n  }\n}\nvoid Benchmark::RunWithArg(int arg) {\n  // run once in case it's expensive\n  int iterations = 1;\n  RunRepeatedlyWithArg(iterations, arg);\n  while (g_benchmark_total_time_ns < 1e9 && iterations < 1e9) {\n    int last = iterations;\n    if (g_benchmark_total_time_ns/iterations == 0) {\n      iterations = 1e9;\n    } else {\n      iterations = 1e9 / (g_benchmark_total_time_ns/iterations);\n    }\n    iterations = std::max(last + 1, std::min(iterations + iterations/2, 100*last));\n    iterations = Round(iterations);\n    RunRepeatedlyWithArg(iterations, arg);\n  }\n  char throughput[100];\n  throughput[0] = '\\0';\n  if (g_benchmark_total_time_ns > 0 && g_flops_processed > 0) {\n    double mflops_processed = static_cast<double>(g_flops_processed)/1e6;\n    double seconds = static_cast<double>(g_benchmark_total_time_ns)/1e9;\n    snprintf(throughput, sizeof(throughput), \" %8.2f MFlops/s\", mflops_processed/seconds);\n  }\n  char full_name[100];\n  if (fn_range_ != NULL) {\n    if (arg >= (1<<20)) {\n      snprintf(full_name, sizeof(full_name), \"%s/%dM\", name_, arg/(1<<20));\n    } else if (arg >= (1<<10)) {\n      snprintf(full_name, sizeof(full_name), \"%s/%dK\", name_, arg/(1<<10));\n    } else {\n      snprintf(full_name, sizeof(full_name), \"%s/%d\", name_, arg);\n    }\n  } else {\n    snprintf(full_name, sizeof(full_name), \"%s\", name_);\n  }\n  printf(\"%-*s %10d %10\" PRId64 \"%s\\n\", g_name_column_width, full_name,\n         iterations, g_benchmark_total_time_ns/iterations, throughput);\n  fflush(stdout);\n}\n}  // namespace testing\nvoid SetBenchmarkFlopsProcessed(int64_t x) {\n  g_flops_processed = x;\n}\nvoid StopBenchmarkTiming() {\n  if (g_benchmark_start_time_ns != 0) {\n    g_benchmark_total_time_ns += NanoTime() - g_benchmark_start_time_ns;\n  }\n  g_benchmark_start_time_ns = 0;\n}\nvoid StartBenchmarkTiming() {\n  if (g_benchmark_start_time_ns == 0) {\n    g_benchmark_start_time_ns = NanoTime();\n  }\n}\nint main(int argc, char* argv[]) {\n  if (gBenchmarks().empty()) {\n    fprintf(stderr, \"No benchmarks registered!\\n\");\n    exit(EXIT_FAILURE);\n  }\n  for (BenchmarkMapIt it = gBenchmarks().begin(); it != gBenchmarks().end(); ++it) {\n    int name_width = static_cast<int>(strlen(it->second->Name()));\n    g_name_column_width = std::max(g_name_column_width, name_width);\n  }\n  bool need_header = true;\n  for (BenchmarkMapIt it = gBenchmarks().begin(); it != gBenchmarks().end(); ++it) {\n    ::testing::Benchmark* b = it->second;\n    if (b->ShouldRun(argc, argv)) {\n      if (need_header) {\n        printf(\"%-*s %10s %10s\\n\", g_name_column_width, \"\", \"iterations\", \"ns/op\");\n        fflush(stdout);\n        need_header = false;\n      }\n      b->Run();\n    }\n  }\n  if (need_header) {\n    fprintf(stderr, \"No matching benchmarks!\\n\");\n    fprintf(stderr, \"Available benchmarks:\\n\");\n    for (BenchmarkMapIt it = gBenchmarks().begin(); it != gBenchmarks().end(); ++it) {\n      fprintf(stderr, \"  %s\\n\", it->second->Name());\n    }\n    exit(EXIT_FAILURE);\n  }\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/tensors/contraction_benchmarks_cpu.cc",
    "content": "#define EIGEN_USE_THREADS\n\n#include <string>\n\n#include \"tensor_benchmarks.h\"\n\n#define CREATE_THREAD_POOL(threads)             \\\nEigen::ThreadPool pool(threads);                \\\nEigen::ThreadPoolDevice device(&pool, threads);\n\n\n// Contractions for number of threads ranging from 1 to 32\n// Dimensions are Rows, Cols, Depth\n#define BM_ContractionCPU(D1, D2, D3)                                         \\\n  static void BM_##Contraction##_##D1##x##D2##x##D3(int iters, int Threads) { \\\n    StopBenchmarkTiming();                                                    \\\n    CREATE_THREAD_POOL(Threads);                                              \\\n    BenchmarkSuite<Eigen::ThreadPoolDevice, float> suite(device, D1, D2, D3); \\\n    suite.contraction(iters);                                                 \\\n  }                                                                           \\\n  BENCHMARK_RANGE(BM_##Contraction##_##D1##x##D2##x##D3, 1, 32);\n\n\n// Vector Matrix and Matrix Vector products\nBM_ContractionCPU(1, 2000, 500);\nBM_ContractionCPU(2000, 1, 500);\n\n// Various skinny matrices\nBM_ContractionCPU(250, 3, 512);\nBM_ContractionCPU(1500, 3, 512);\n\nBM_ContractionCPU(512, 800, 4);\nBM_ContractionCPU(512, 80, 800);\nBM_ContractionCPU(512, 80, 13522);\nBM_ContractionCPU(1, 80, 13522);\n\nBM_ContractionCPU(3200, 512, 4);\nBM_ContractionCPU(3200, 512, 80);\nBM_ContractionCPU(3200, 80, 512);\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/tensors/eigen_sycl_bench.sh",
    "content": "rm -f tensor_benchmark_sycl\n: \"${COMPUTECPP_PACKAGE_ROOT_DIR:?Need to set COMPUTECPP_PACKAGE_ROOT_DIR}\"\necho \"COMPUTECPP_PACKAGE_ROOT_DIR is set to: \"$COMPUTECPP_PACKAGE_ROOT_DIR\n${COMPUTECPP_PACKAGE_ROOT_DIR}/bin/compute++ \\\ntensor_benchmarks_sycl.cc \\\nbenchmark_main.cc \\\n-I ../../ \\\n-I ${COMPUTECPP_PACKAGE_ROOT_DIR}/include/ \\\n-std=c++11 \\\n-march=native \\\n-O3 \\\n-DNDEBUG \\\n-DEIGEN_MPL2_ONLY \\\n-DEIGEN_USE_SYCL=1 \\\n-DEIGEN_SYCL_LOCAL_MEM=1 \\\n-no-serial-memop \\\n-mllvm \\\n-inline-threshold=10000 \\\n-fsycl-ih-last \\\n-sycl-driver \\\n-Xclang -cl-mad-enable \\\n-lOpenCL \\\n-lComputeCpp \\\n-lpthread \\\n-o \\\ntensor_benchmark_sycl\\\n${@:1}\n\nexport LD_LIBRARY_PATH=${COMPUTECPP_PACKAGE_ROOT_DIR}/lib:$LD_LIBRARY_PATH\n./tensor_benchmark_sycl\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/tensors/eigen_sycl_bench_contract.sh",
    "content": "rm -f tensor_contract_sycl_bench\n: \"${COMPUTECPP_PACKAGE_ROOT_DIR:?Need to set COMPUTECPP_PACKAGE_ROOT_DIR}\"\necho \"COMPUTECPP_PACKAGE_ROOT_DIR is set to: \"$COMPUTECPP_PACKAGE_ROOT_DIR\n${COMPUTECPP_PACKAGE_ROOT_DIR}/bin/compute++  tensor_contract_sycl_bench.cc -I ../../ -I ${COMPUTECPP_PACKAGE_ROOT_DIR}/include/ -std=c++11 -O3 -DNDEBUG -DEIGEN_MPL2_ONLY -DEIGEN_USE_SYCL=1 -no-serial-memop -mllvm -inline-threshold=10000 -fsycl-ih-last -sycl-driver -Xclang -cl-mad-enable -lOpenCL -lComputeCpp -lpthread -o tensor_contract_sycl_bench ${@:1}\nexport LD_LIBRARY_PATH=${COMPUTECPP_PACKAGE_ROOT_DIR}/lib:$LD_LIBRARY_PATH\n./tensor_contract_sycl_bench\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/tensors/tensor_benchmarks.h",
    "content": "#ifndef THIRD_PARTY_EIGEN3_TENSOR_BENCHMARKS_H_\n#define THIRD_PARTY_EIGEN3_TENSOR_BENCHMARKS_H_\n\ntypedef int TensorIndex;\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int\n\n#include \"unsupported/Eigen/CXX11/Tensor\"\n#include \"benchmark.h\"\n\n#define BENCHMARK_RANGE(bench, lo, hi) \\\n  BENCHMARK(bench)->Range(lo, hi)\n\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\n// TODO(bsteiner): also templatize on the input type since we have users\n// for int8 as well as floats.\ntemplate <typename Device, typename T> class BenchmarkSuite {\n public:\n  BenchmarkSuite(const Device& device, size_t m, size_t k, size_t n)\n      : m_(m), k_(k), n_(n), device_(device) {\n    initialize();\n  }\n\n  BenchmarkSuite(const Device& device, size_t m)\n      : m_(m), k_(m), n_(m), device_(device) {\n    initialize();\n  }\n\n  BenchmarkSuite(const Device& device, size_t m, size_t k)\n      : m_(1), k_(k), n_(m), device_(device) {\n    initialize();\n  }\n\n  ~BenchmarkSuite() {\n    device_.deallocate(a_);\n    device_.deallocate(b_);\n    device_.deallocate(c_);\n  }\n\n  void memcpy(int num_iters) {\n    eigen_assert(m_ == k_ && k_ == n_);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      device_.memcpy(c_, a_, m_ * m_ * sizeof(T));\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      device_.memcpy(c_, a_, m_ * m_ * sizeof(T));\n    }\n    // Record the number of values copied per second\n    finalizeBenchmark(static_cast<int64_t>(m_) * m_ * num_iters);\n  }\n\n  void typeCasting(int num_iters) {\n    eigen_assert(m_ == n_);\n    Eigen::array<TensorIndex, 2> sizes;\n    if (sizeof(T) >= sizeof(int)) {\n      sizes[0] = m_;\n      sizes[1] = k_;\n    } else {\n      sizes[0] = m_ * sizeof(T) / sizeof(int);\n      sizes[1] = k_ * sizeof(T) / sizeof(int);\n    }\n    const TensorMap<Tensor<int, 2, 0, TensorIndex>, Eigen::Aligned> A((int*)a_, sizes);\n    TensorMap<Tensor<T, 2, 0, TensorIndex>, Eigen::Aligned> B(b_, sizes);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      B.device(device_) = A.template cast<T>();\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      B.device(device_) = A.template cast<T>();\n    }\n    // Record the number of values copied per second\n    finalizeBenchmark(static_cast<int64_t>(m_) * k_ * num_iters);\n  }\n\n  void random(int num_iters) {\n    eigen_assert(m_ == k_ && k_ == n_);\n    Eigen::array<TensorIndex, 2> sizes;\n    sizes[0] = m_;\n    sizes[1] = m_;\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> C(c_, sizes);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      C.device(device_) = C.random();\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = C.random();\n    }\n    // Record the number of random numbers generated per second\n    finalizeBenchmark(static_cast<int64_t>(m_) * m_ * num_iters);\n  }\n\n  void slicing(int num_iters) {\n    eigen_assert(m_ == k_ && k_ == n_);\n    Eigen::array<TensorIndex, 2> sizes;\n    sizes[0] = m_;\n    sizes[1] = m_;\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> A(a_, sizes);\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> B(b_, sizes);\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> C(c_, sizes);\n\n    const Eigen::DSizes<TensorIndex, 2> quarter_sizes(m_/2, m_/2);\n    const Eigen::DSizes<TensorIndex, 2> first_quadrant(0, 0);\n    const Eigen::DSizes<TensorIndex, 2> second_quadrant(0, m_/2);\n    const Eigen::DSizes<TensorIndex, 2> third_quadrant(m_/2, 0);\n    const Eigen::DSizes<TensorIndex, 2> fourth_quadrant(m_/2, m_/2);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      C.slice(first_quadrant, quarter_sizes).device(device_) =\n          A.slice(first_quadrant, quarter_sizes);\n      C.slice(second_quadrant, quarter_sizes).device(device_) =\n          B.slice(second_quadrant, quarter_sizes);\n      C.slice(third_quadrant, quarter_sizes).device(device_) =\n          A.slice(third_quadrant, quarter_sizes);\n      C.slice(fourth_quadrant, quarter_sizes).device(device_) =\n          B.slice(fourth_quadrant, quarter_sizes);\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.slice(first_quadrant, quarter_sizes).device(device_) =\n          A.slice(first_quadrant, quarter_sizes);\n      C.slice(second_quadrant, quarter_sizes).device(device_) =\n          B.slice(second_quadrant, quarter_sizes);\n      C.slice(third_quadrant, quarter_sizes).device(device_) =\n          A.slice(third_quadrant, quarter_sizes);\n      C.slice(fourth_quadrant, quarter_sizes).device(device_) =\n          B.slice(fourth_quadrant, quarter_sizes);\n    }\n    // Record the number of values copied from the rhs slice to the lhs slice\n    // each second\n    finalizeBenchmark(static_cast<int64_t>(m_) * m_ * num_iters);\n  }\n\n  void rowChip(int num_iters) {\n    Eigen::array<TensorIndex, 2> input_size;\n    input_size[0] = k_;\n    input_size[1] = n_;\n    const TensorMap<Tensor<T, 2, 0, TensorIndex>, Eigen::Aligned> B(b_, input_size);\n    Eigen::array<TensorIndex, 1> output_size;\n    output_size[0] = n_;\n    TensorMap<Tensor<T, 1, 0, TensorIndex>, Eigen::Aligned> C(c_, output_size);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      C.device(device_) = B.chip(iter % k_, 0);\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = B.chip(iter % k_, 0);\n    }\n    // Record the number of values copied from the rhs chip to the lhs.\n    finalizeBenchmark(static_cast<int64_t>(n_) * num_iters);\n  }\n\n  void colChip(int num_iters) {\n    Eigen::array<TensorIndex, 2> input_size;\n    input_size[0] = k_;\n    input_size[1] = n_;\n    const TensorMap<Tensor<T, 2, 0, TensorIndex>, Eigen::Aligned> B(b_, input_size);\n    Eigen::array<TensorIndex, 1> output_size;\n    output_size[0] = n_;\n    TensorMap<Tensor<T, 1, 0, TensorIndex>, Eigen::Aligned> C(c_, output_size);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      C.device(device_) = B.chip(iter % n_, 1);\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = B.chip(iter % n_, 1);\n    }\n    // Record the number of values copied from the rhs chip to the lhs.\n    finalizeBenchmark(static_cast<int64_t>(n_) * num_iters);\n  }\n\n  void shuffling(int num_iters) {\n    eigen_assert(m_ == n_);\n    Eigen::array<TensorIndex, 2> size_a;\n    size_a[0] = m_;\n    size_a[1] = k_;\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> A(a_, size_a);\n    Eigen::array<TensorIndex, 2> size_b;\n    size_b[0] = k_;\n    size_b[1] = m_;\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> B(b_, size_b);\n\n    Eigen::array<int, 2> shuffle;\n    shuffle[0] = 1;\n    shuffle[1] = 0;\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      B.device(device_) = A.shuffle(shuffle);\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      B.device(device_) = A.shuffle(shuffle);\n    }\n    // Record the number of values shuffled from A and copied to B each second\n    finalizeBenchmark(static_cast<int64_t>(m_) * k_ * num_iters);\n  }\n\n void padding(int num_iters) {\n    eigen_assert(m_ == k_);\n    Eigen::array<TensorIndex, 2> size_a;\n    size_a[0] = m_;\n    size_a[1] = k_-3;\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> A(a_, size_a);\n    Eigen::array<TensorIndex, 2> size_b;\n    size_b[0] = k_;\n    size_b[1] = m_;\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> B(b_, size_b);\n\n#if defined(EIGEN_HAS_INDEX_LIST)\n    Eigen::IndexPairList<Eigen::type2indexpair<0, 0>,\n                         Eigen::type2indexpair<2, 1> > paddings;\n#else\n    Eigen::array<Eigen::IndexPair<TensorIndex>, 2> paddings;\n    paddings[0] = Eigen::IndexPair<TensorIndex>(0, 0);\n    paddings[1] = Eigen::IndexPair<TensorIndex>(2, 1);\n#endif\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      B.device(device_) = A.pad(paddings);\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      B.device(device_) = A.pad(paddings);\n    }\n    // Record the number of values copied from the padded tensor A each second\n    finalizeBenchmark(static_cast<int64_t>(m_) * k_ * num_iters);\n  }\n\n void striding(int num_iters) {\n    eigen_assert(m_ == k_);\n    Eigen::array<TensorIndex, 2> size_a;\n    size_a[0] = m_;\n    size_a[1] = k_;\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> A(a_, size_a);\n    Eigen::array<TensorIndex, 2> size_b;\n    size_b[0] = m_;\n    size_b[1] = k_/2;\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> B(b_, size_b);\n\n#ifndef EIGEN_HAS_INDEX_LIST\n    Eigen::array<TensorIndex, 2> strides;\n    strides[0] = 1;\n    strides[1] = 2;\n#else\n    // Take advantage of cxx11 to give the compiler information it can use to\n    // optimize the code.\n    Eigen::IndexList<Eigen::type2index<1>, Eigen::type2index<2> > strides;\n#endif\n\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      B.device(device_) = A.stride(strides);\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      B.device(device_) = A.stride(strides);\n    }\n    // Record the number of values copied from the padded tensor A each second\n    finalizeBenchmark(static_cast<int64_t>(m_) * k_ * num_iters);\n  }\n\n\n  void broadcasting(int num_iters) {\n    Eigen::array<TensorIndex, 2> size_a;\n    size_a[0] = m_;\n    size_a[1] = 1;\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> A(a_, size_a);\n    Eigen::array<TensorIndex, 2> size_c;\n    size_c[0] = m_;\n    size_c[1] = n_;\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> C(c_, size_c);\n\n#ifndef EIGEN_HAS_INDEX_LIST\n    Eigen::array<int, 2> broadcast;\n    broadcast[0] = 1;\n    broadcast[1] = n_;\n#else\n    // Take advantage of cxx11 to give the compiler information it can use to\n    // optimize the code.\n    Eigen::IndexList<Eigen::type2index<1>, int> broadcast;\n    broadcast.set(1, n_);\n#endif\n\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      C.device(device_) = A.broadcast(broadcast);\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = A.broadcast(broadcast);\n    }\n    // Record the number of values broadcasted from A and copied to C each second\n    finalizeBenchmark(static_cast<int64_t>(m_) * n_ * num_iters);\n  }\n\n  void coeffWiseOp(int num_iters) {\n    eigen_assert(m_ == k_ && k_ == n_);\n    Eigen::array<TensorIndex, 2> sizes;\n    sizes[0] = m_;\n    sizes[1] = m_;\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> A(a_, sizes);\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> B(b_, sizes);\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> C(c_, sizes);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      C.device(device_) = A * A.constant(static_cast<T>(3.14)) + B * B.constant(static_cast<T>(2.7));\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = A * A.constant(static_cast<T>(3.14)) + B * B.constant(static_cast<T>(2.7));\n    }\n    // Record the number of FLOP executed per second (2 multiplications and\n    // 1 addition per value)\n    finalizeBenchmark(static_cast<int64_t>(3) * m_ * m_ * num_iters);\n  }\n\n  void algebraicFunc(int num_iters) {\n    eigen_assert(m_ == k_ && k_ == n_);\n    Eigen::array<TensorIndex, 2> sizes;\n    sizes[0] = m_;\n    sizes[1] = m_;\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> A(a_, sizes);\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> B(b_, sizes);\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> C(c_, sizes);\n\n#ifdef EIGEN_USE_SYCL // warmup for sycl\nfor (int iter = 0; iter < 10; ++iter) {\n      C.device(device_) = A.rsqrt() + B.sqrt() * B.square();\n}\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = A.rsqrt() + B.sqrt() * B.square();\n    }\n    // Record the number of FLOP executed per second (assuming one operation\n    // per value)\n    finalizeBenchmark(static_cast<int64_t>(m_) * m_ * num_iters);\n  }\n\n  void transcendentalFunc(int num_iters) {\n    eigen_assert(m_ == k_ && k_ == n_);\n    Eigen::array<TensorIndex, 2> sizes;\n    sizes[0] = m_;\n    sizes[1] = m_;\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> A(a_, sizes);\n    const TensorMap<Tensor<T, 2>, Eigen::Aligned> B(b_, sizes);\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> C(c_, sizes);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      C.device(device_) = A.exp() + B.log();\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = A.exp() + B.log();\n    }\n    // Record the number of FLOP executed per second (assuming one operation\n    // per value)\n    finalizeBenchmark(static_cast<int64_t>(m_) * m_ * num_iters);\n  }\n\n // Row reduction\n  void rowReduction(int num_iters) {\n    Eigen::array<TensorIndex, 2> input_size;\n    input_size[0] = k_;\n    input_size[1] = n_;\n    const TensorMap<Tensor<T, 2, 0, TensorIndex>, Eigen::Aligned> B(b_, input_size);\n    Eigen::array<TensorIndex, 1> output_size;\n    output_size[0] = n_;\n    TensorMap<Tensor<T, 1, 0, TensorIndex>, Eigen::Aligned> C(c_, output_size);\n\n#ifndef EIGEN_HAS_INDEX_LIST\n    Eigen::array<TensorIndex, 1> sum_along_dim;\n    sum_along_dim[0] = 0;\n#else\n    // Take advantage of cxx11 to give the compiler information it can use to\n    // optimize the code.\n    Eigen::IndexList<Eigen::type2index<0>> sum_along_dim;\n#endif\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n  for (int iter = 0; iter < 10; ++iter) {\n    C.device(device_) = B.sum(sum_along_dim);\n  }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = B.sum(sum_along_dim);\n    }\n    // Record the number of FLOP executed per second (assuming one operation\n    // per value)\n    finalizeBenchmark(static_cast<int64_t>(k_) * n_ * num_iters);\n  }\n\n  // Column reduction\n  void colReduction(int num_iters) {\n    Eigen::array<TensorIndex, 2> input_size;\n    input_size[0] = k_;\n    input_size[1] = n_;\n    const TensorMap<Tensor<T, 2, 0, TensorIndex>, Eigen::Aligned> B(\n        b_, input_size);\n    Eigen::array<TensorIndex, 1> output_size;\n    output_size[0] = k_;\n    TensorMap<Tensor<T, 1, 0, TensorIndex>, Eigen::Aligned> A(\n        a_, output_size);\n\n#ifndef EIGEN_HAS_INDEX_LIST\n    Eigen::array<TensorIndex, 1> sum_along_dim;\n    sum_along_dim[0] = 1;\n#else\n    // Take advantage of cxx11 to give the compiler information it can use to\n    // optimize the code.\n    Eigen::IndexList<Eigen::type2index<1>> sum_along_dim;\n#endif\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n  for (int iter = 0; iter < 10; ++iter) {\n    A.device(device_) = B.sum(sum_along_dim);\n  }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      A.device(device_) = B.sum(sum_along_dim);\n    }\n    // Record the number of FLOP executed per second (assuming one operation\n    // per value)\n    finalizeBenchmark(static_cast<int64_t>(k_) * n_ * num_iters);\n  }\n\n  // Full reduction\n  void fullReduction(int num_iters) {\n    Eigen::array<TensorIndex, 2> input_size;\n    input_size[0] = k_;\n    input_size[1] = n_;\n    const TensorMap<Tensor<T, 2, 0, TensorIndex>, Eigen::Aligned> B(\n        b_, input_size);\n    Eigen::array<TensorIndex, 0> output_size;\n    TensorMap<Tensor<T, 0, 0, TensorIndex>, Eigen::Aligned> C(\n        c_, output_size);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      C.device(device_) = B.sum();\n    }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = B.sum();\n    }\n    // Record the number of FLOP executed per second (assuming one operation\n    // per value)\n    finalizeBenchmark(static_cast<int64_t>(k_) * n_ * num_iters);\n  }\n\n  \n\n  // do a contraction which is equivalent to a matrix multiplication\n  void contraction(int num_iters) {\n      contraction<static_cast<int>(Eigen::ColMajor)>(num_iters, false, false);\n  }\n\n    void contractionRowMajor(int num_iters) {\n      contraction<static_cast<int>(Eigen::RowMajor)>(num_iters, false, false);\n  }\n    \n  void contractionRowMajorAT(int num_iters) {\n      contraction<static_cast<int>(Eigen::RowMajor)>(num_iters, true, false);\n  }\n\n  void contractionRowMajorBT(int num_iters) {\n      contraction<static_cast<int>(Eigen::RowMajor)>(num_iters, false, true);\n  }\n\n  void contractionRowMajorABT(int num_iters) {\n      contraction<static_cast<int>(Eigen::RowMajor)>(num_iters, true, true);\n  }\n\n  void convolution(int num_iters, int kernel_x, int kernel_y) {\n    Eigen::array<TensorIndex, 2> input_sizes;\n    input_sizes[0] = m_;\n    input_sizes[1] = n_;\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> A(a_, input_sizes);\n    Eigen::array<TensorIndex, 2> kernel_sizes;\n    kernel_sizes[0] = kernel_x;\n    kernel_sizes[1] = kernel_y;\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> B(b_, kernel_sizes);\n    Eigen::array<TensorIndex, 2> result_sizes;\n    result_sizes[0] = m_ - kernel_x + 1;\n    result_sizes[1] = n_ - kernel_y + 1;\n    TensorMap<Tensor<T, 2>, Eigen::Aligned> C(c_, result_sizes);\n    Eigen::array<TensorIndex, 2> dims;\n    dims[0] = 0;\n    dims[1] = 1;\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      C.device(device_) = A.convolve(B, dims);\n     }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = A.convolve(B, dims);\n    }\n    // Record the number of FLOPs executed per second (kernel_size\n    // multiplications and additions for each value in the resulting tensor)\n    finalizeBenchmark(static_cast<int64_t>(2) *\n        (m_ - kernel_x + 1) * (n_ - kernel_y + 1) * kernel_x * kernel_y * num_iters);\n  }\n\n private:\n // do a contraction which is equivalent to a matrix multiplication\n  template<int Layout>\n  void contraction(int num_iters, bool trans_a, bool trans_b) {\n    Eigen::array<TensorIndex, 2> sizeA;\n    sizeA[0] = (trans_a ? k_: m_);\n    sizeA[1] = (trans_a ? m_:  k_);\n    Eigen::array<TensorIndex, 2> sizeB;\n    sizeB[0] = (trans_b ? n_: k_);\n    sizeB[1] = (trans_b ? k_: n_);\n    Eigen::array<TensorIndex, 2> sizeC;\n    sizeC[0] = m_;\n    sizeC[1] = n_;\n\n    const TensorMap<Tensor<T, 2, Layout>, Eigen::Aligned> A(a_, sizeA);\n    const TensorMap<Tensor<T, 2, Layout>, Eigen::Aligned> B(b_, sizeB);\n    TensorMap<Tensor<T, 2, Layout>, Eigen::Aligned> C(c_, sizeC);\n\n    typedef typename Tensor<T, 2, Layout>::DimensionPair DimPair;\n    Eigen::array<DimPair, 1> dims;\n    TensorIndex a_contract_dim = (trans_a ? 0 : 1);\n    TensorIndex b_contract_dim = (trans_b ? 1 : 0);\n    dims[0] = DimPair(a_contract_dim, b_contract_dim);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n    for (int iter = 0; iter < 10; ++iter) {\n      C.device(device_) = A.contract(B, dims);\n     }\n#endif\n    StartBenchmarkTiming();\n    for (int iter = 0; iter < num_iters; ++iter) {\n      C.device(device_) = A.contract(B, dims);\n    }\n    // Record the number of FLOP executed per second (size_ multiplications and\n    // additions for each value in the resulting tensor)\n    finalizeBenchmark(static_cast<int64_t>(2) * m_ * n_ * k_ * num_iters);\n  }\n\n  void initialize() {\n    a_ = (T *) device_.allocate(m_ * k_ * sizeof(T));\n    b_ = (T *) device_.allocate(k_ * n_ * sizeof(T));\n    c_ = (T *) device_.allocate(m_ * n_ * sizeof(T));\n\n    // Initialize the content of the memory pools to prevent asan from\n    // complaining.\n    device_.memset(a_, 12, m_ * k_ * sizeof(T));\n    device_.memset(b_, 23, k_ * n_ * sizeof(T));\n    device_.memset(c_, 31, m_ * n_ * sizeof(T));\n\n  }\n\n  inline void finalizeBenchmark(int64_t num_items) {\n#if defined(EIGEN_USE_GPU) && defined(__CUDACC__)\n    if (Eigen::internal::is_same<Device, Eigen::GpuDevice>::value) {\n      device_.synchronize();\n    }\n#elif defined(EIGEN_USE_SYCL)\n    if (Eigen::internal::is_same<Device, Eigen::SyclDevice>::value) {\n      device_.synchronize();\n    }\n\n#endif\n    StopBenchmarkTiming();\n    SetBenchmarkFlopsProcessed(num_items);\n  }\n\n\n  TensorIndex m_;\n  TensorIndex k_;\n  TensorIndex n_;\n  T* a_;\n  T* b_;\n  T* c_;\n  Device device_;\n};\n#endif  // THIRD_PARTY_EIGEN3_TENSOR_BENCHMARKS_H_\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/tensors/tensor_benchmarks_cpu.cc",
    "content": "#define EIGEN_USE_THREADS\n\n#include <string>\n\n#include \"tensor_benchmarks.h\"\n\n#define CREATE_THREAD_POOL(threads)             \\\nEigen::ThreadPool pool(threads);                \\\nEigen::ThreadPoolDevice device(&pool, threads);\n\n// Simple functions\n#define BM_FuncCPU(FUNC, THREADS)                                    \\\n  static void BM_##FUNC##_##THREADS##T(int iters, int N) {           \\\n    StopBenchmarkTiming();                                           \\\n    CREATE_THREAD_POOL(THREADS);                                     \\\n    BenchmarkSuite<Eigen::ThreadPoolDevice, float> suite(device, N); \\\n    suite.FUNC(iters);                                               \\\n  }                                                                  \\\n  BENCHMARK_RANGE(BM_##FUNC##_##THREADS##T, 10, 5000);\n\nBM_FuncCPU(memcpy, 4);\nBM_FuncCPU(memcpy, 8);\nBM_FuncCPU(memcpy, 12);\n\nBM_FuncCPU(typeCasting, 4);\nBM_FuncCPU(typeCasting, 8);\nBM_FuncCPU(typeCasting, 12);\n\nBM_FuncCPU(random, 4);\nBM_FuncCPU(random, 8);\nBM_FuncCPU(random, 12);\n\nBM_FuncCPU(slicing, 4);\nBM_FuncCPU(slicing, 8);\nBM_FuncCPU(slicing, 12);\n\nBM_FuncCPU(rowChip, 4);\nBM_FuncCPU(rowChip, 8);\nBM_FuncCPU(rowChip, 12);\n\nBM_FuncCPU(colChip, 4);\nBM_FuncCPU(colChip, 8);\nBM_FuncCPU(colChip, 12);\n\nBM_FuncCPU(shuffling, 4);\nBM_FuncCPU(shuffling, 8);\nBM_FuncCPU(shuffling, 12);\n\nBM_FuncCPU(padding, 4);\nBM_FuncCPU(padding, 8);\nBM_FuncCPU(padding, 12);\n\nBM_FuncCPU(striding, 4);\nBM_FuncCPU(striding, 8);\nBM_FuncCPU(striding, 12);\n\nBM_FuncCPU(broadcasting, 4);\nBM_FuncCPU(broadcasting, 8);\nBM_FuncCPU(broadcasting, 12);\n\nBM_FuncCPU(coeffWiseOp, 4);\nBM_FuncCPU(coeffWiseOp, 8);\nBM_FuncCPU(coeffWiseOp, 12);\n\nBM_FuncCPU(algebraicFunc, 4);\nBM_FuncCPU(algebraicFunc, 8);\nBM_FuncCPU(algebraicFunc, 12);\n\nBM_FuncCPU(transcendentalFunc, 4);\nBM_FuncCPU(transcendentalFunc, 8);\nBM_FuncCPU(transcendentalFunc, 12);\n\nBM_FuncCPU(rowReduction, 4);\nBM_FuncCPU(rowReduction, 8);\nBM_FuncCPU(rowReduction, 12);\n\nBM_FuncCPU(colReduction, 4);\nBM_FuncCPU(colReduction, 8);\nBM_FuncCPU(colReduction, 12);\n\n\n// Contractions\n#define BM_FuncWithInputDimsCPU(FUNC, D1, D2, D3, THREADS)                      \\\n  static void BM_##FUNC##_##D1##x##D2##x##D3##_##THREADS##T(int iters, int N) { \\\n    StopBenchmarkTiming();                                                      \\\n    if (THREADS == 1) {                                                         \\\n      Eigen::DefaultDevice device;                                              \\\n      BenchmarkSuite<Eigen::DefaultDevice, float> suite(device, D1, D2, D3);    \\\n      suite.FUNC(iters);                                                        \\\n    } else {                                                                    \\\n      CREATE_THREAD_POOL(THREADS);                                              \\\n      BenchmarkSuite<Eigen::ThreadPoolDevice, float> suite(device, D1, D2, D3); \\\n      suite.FUNC(iters);                                                        \\\n    }                                                                           \\\n  }                                                                             \\\n  BENCHMARK_RANGE(BM_##FUNC##_##D1##x##D2##x##D3##_##THREADS##T, 10, 5000);\n\n\nBM_FuncWithInputDimsCPU(contraction, N, N, N, 1);\nBM_FuncWithInputDimsCPU(contraction, N, N, N, 4);\nBM_FuncWithInputDimsCPU(contraction, N, N, N, 8);\nBM_FuncWithInputDimsCPU(contraction, N, N, N, 12);\nBM_FuncWithInputDimsCPU(contraction, N, N, N, 16);\n\nBM_FuncWithInputDimsCPU(contraction, 64, N, N, 1);\nBM_FuncWithInputDimsCPU(contraction, 64, N, N, 4);\nBM_FuncWithInputDimsCPU(contraction, 64, N, N, 8);\nBM_FuncWithInputDimsCPU(contraction, 64, N, N, 12);\nBM_FuncWithInputDimsCPU(contraction, 64, N, N, 16);\n\nBM_FuncWithInputDimsCPU(contraction, N, 64, N, 1);\nBM_FuncWithInputDimsCPU(contraction, N, 64, N, 4);\nBM_FuncWithInputDimsCPU(contraction, N, 64, N, 8);\nBM_FuncWithInputDimsCPU(contraction, N, 64, N, 12);\nBM_FuncWithInputDimsCPU(contraction, N, 64, N, 16);\n\nBM_FuncWithInputDimsCPU(contraction, N, N, 64, 1);\nBM_FuncWithInputDimsCPU(contraction, N, N, 64, 4);\nBM_FuncWithInputDimsCPU(contraction, N, N, 64, 8);\nBM_FuncWithInputDimsCPU(contraction, N, N, 64, 12);\nBM_FuncWithInputDimsCPU(contraction, N, N, 64, 16);\n\nBM_FuncWithInputDimsCPU(contraction, 1, N, N, 1);\nBM_FuncWithInputDimsCPU(contraction, 1, N, N, 4);\nBM_FuncWithInputDimsCPU(contraction, 1, N, N, 8);\nBM_FuncWithInputDimsCPU(contraction, 1, N, N, 12);\nBM_FuncWithInputDimsCPU(contraction, 1, N, N, 16);\n\nBM_FuncWithInputDimsCPU(contraction, N, N, 1, 1);\nBM_FuncWithInputDimsCPU(contraction, N, N, 1, 4);\nBM_FuncWithInputDimsCPU(contraction, N, N, 1, 8);\nBM_FuncWithInputDimsCPU(contraction, N, N, 1, 12);\nBM_FuncWithInputDimsCPU(contraction, N, N, 1, 16);\n\n\n// Convolutions\n#define BM_FuncWithKernelDimsCPU(FUNC, DIM1, DIM2, THREADS)                    \\\n  static void BM_##FUNC##_##DIM1##x##DIM2##_##THREADS##T(int iters, int N) {   \\\n    StopBenchmarkTiming();                                                     \\\n    CREATE_THREAD_POOL(THREADS);                                               \\\n    BenchmarkSuite<Eigen::ThreadPoolDevice, float> suite(device, N);\t       \\\n    suite.FUNC(iters, DIM1, DIM2);                                             \\\n  }                                                                            \\\n  BENCHMARK_RANGE(BM_##FUNC##_##DIM1##x##DIM2##_##THREADS##T, 128, 5000);\n\nBM_FuncWithKernelDimsCPU(convolution, 7, 1, 4);\nBM_FuncWithKernelDimsCPU(convolution, 7, 1, 8);\nBM_FuncWithKernelDimsCPU(convolution, 7, 1, 12);\n\nBM_FuncWithKernelDimsCPU(convolution, 1, 7, 4);\nBM_FuncWithKernelDimsCPU(convolution, 1, 7, 8);\nBM_FuncWithKernelDimsCPU(convolution, 1, 7, 12);\n\nBM_FuncWithKernelDimsCPU(convolution, 7, 4, 4);\nBM_FuncWithKernelDimsCPU(convolution, 7, 4, 8);\nBM_FuncWithKernelDimsCPU(convolution, 7, 4, 12);\n\nBM_FuncWithKernelDimsCPU(convolution, 4, 7, 4);\nBM_FuncWithKernelDimsCPU(convolution, 4, 7, 8);\nBM_FuncWithKernelDimsCPU(convolution, 4, 7, 12);\n\nBM_FuncWithKernelDimsCPU(convolution, 7, 64, 4);\nBM_FuncWithKernelDimsCPU(convolution, 7, 64, 8);\nBM_FuncWithKernelDimsCPU(convolution, 7, 64, 12);\n\nBM_FuncWithKernelDimsCPU(convolution, 64, 7, 4);\nBM_FuncWithKernelDimsCPU(convolution, 64, 7, 8);\nBM_FuncWithKernelDimsCPU(convolution, 64, 7, 12);\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/tensors/tensor_benchmarks_fp16_gpu.cu",
    "content": "#define EIGEN_USE_GPU\n\n#include <cuda.h>\n#include <cuda_runtime.h>\n#include <iostream>\n\n#include \"tensor_benchmarks.h\"\n\n// Simple functions\n#define BM_FuncGPU(FUNC)                                                       \\\n  static void BM_##FUNC(int iters, int N) {                                    \\\n    StopBenchmarkTiming();                                                     \\\n    Eigen::CudaStreamDevice stream;                                            \\\n    Eigen::GpuDevice device(&stream);                                          \\\n    BenchmarkSuite<Eigen::GpuDevice, Eigen::half> suite(device, N);            \\\n    cudaDeviceSynchronize();                                                   \\\n    suite.FUNC(iters);                                                         \\\n  }                                                                            \\\n  BENCHMARK_RANGE(BM_##FUNC, 10, 5000);\n\nBM_FuncGPU(memcpy);\nBM_FuncGPU(typeCasting);\n//BM_FuncGPU(random);\nBM_FuncGPU(slicing);\nBM_FuncGPU(rowChip);\nBM_FuncGPU(colChip);\nBM_FuncGPU(shuffling);\nBM_FuncGPU(padding);\nBM_FuncGPU(striding);\nBM_FuncGPU(broadcasting);\nBM_FuncGPU(coeffWiseOp);\nBM_FuncGPU(algebraicFunc);\nBM_FuncGPU(transcendentalFunc);\nBM_FuncGPU(rowReduction);\nBM_FuncGPU(colReduction);\nBM_FuncGPU(fullReduction);\n\n\n// Contractions\n#define BM_FuncWithInputDimsGPU(FUNC, D1, D2, D3)                              \\\n  static void BM_##FUNC##_##D1##x##D2##x##D3(int iters, int N) {               \\\n    StopBenchmarkTiming();                                                     \\\n    Eigen::CudaStreamDevice stream;                                            \\\n    Eigen::GpuDevice device(&stream);                                          \\\n    BenchmarkSuite<Eigen::GpuDevice, Eigen::half> suite(device, D1, D2, D3);   \\\n    cudaDeviceSynchronize();                                                   \\\n    suite.FUNC(iters);                                                         \\\n  }                                                                            \\\n  BENCHMARK_RANGE(BM_##FUNC##_##D1##x##D2##x##D3, 10, 5000);\n\n\nBM_FuncWithInputDimsGPU(contraction, N, N, N);\nBM_FuncWithInputDimsGPU(contraction, 64, N, N);\nBM_FuncWithInputDimsGPU(contraction, N, 64, N);\nBM_FuncWithInputDimsGPU(contraction, N, N, 64);\n\n\n// Convolutions\n#define BM_FuncWithKernelDimsGPU(FUNC, DIM1, DIM2)                             \\\n  static void BM_##FUNC##_##DIM1##x##DIM2(int iters, int N) {                  \\\n    StopBenchmarkTiming();                                                     \\\n    Eigen::CudaStreamDevice stream;                                            \\\n    Eigen::GpuDevice device(&stream);                                          \\\n    BenchmarkSuite<Eigen::GpuDevice, Eigen::half> suite(device, N);            \\\n    cudaDeviceSynchronize();                                                   \\\n    suite.FUNC(iters, DIM1, DIM2);                                             \\\n  }                                                                            \\\n  BENCHMARK_RANGE(BM_##FUNC##_##DIM1##x##DIM2, 128, 5000);\n\n/*\nBM_FuncWithKernelDimsGPU(convolution, 7, 1);\nBM_FuncWithKernelDimsGPU(convolution, 1, 7);\nBM_FuncWithKernelDimsGPU(convolution, 7, 4);\nBM_FuncWithKernelDimsGPU(convolution, 4, 7);\nBM_FuncWithKernelDimsGPU(convolution, 7, 64);\nBM_FuncWithKernelDimsGPU(convolution, 64, 7);\n*/\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/tensors/tensor_benchmarks_gpu.cu",
    "content": "#define EIGEN_USE_GPU\n\n#include <cuda.h>\n#include <cuda_runtime.h>\n#include <iostream>\n\n#include \"tensor_benchmarks.h\"\n\n// Simple functions\n#define BM_FuncGPU(FUNC)                                                       \\\n  static void BM_##FUNC(int iters, int N) {                                    \\\n    StopBenchmarkTiming();                                                     \\\n    Eigen::CudaStreamDevice stream;                                            \\\n    Eigen::GpuDevice device(&stream);                                          \\\n    BenchmarkSuite<Eigen::GpuDevice, float> suite(device, N);                  \\\n    cudaDeviceSynchronize();                                                   \\\n    suite.FUNC(iters);                                                         \\\n  }                                                                            \\\n  BENCHMARK_RANGE(BM_##FUNC, 10, 5000);\n\nBM_FuncGPU(memcpy);\nBM_FuncGPU(typeCasting);\nBM_FuncGPU(random);\nBM_FuncGPU(slicing);\nBM_FuncGPU(rowChip);\nBM_FuncGPU(colChip);\nBM_FuncGPU(shuffling);\nBM_FuncGPU(padding);\nBM_FuncGPU(striding);\nBM_FuncGPU(broadcasting);\nBM_FuncGPU(coeffWiseOp);\nBM_FuncGPU(algebraicFunc);\nBM_FuncGPU(transcendentalFunc);\nBM_FuncGPU(rowReduction);\nBM_FuncGPU(colReduction);\nBM_FuncGPU(fullReduction);\n\n\n// Contractions\n#define BM_FuncWithInputDimsGPU(FUNC, D1, D2, D3)                              \\\n  static void BM_##FUNC##_##D1##x##D2##x##D3(int iters, int N) {               \\\n    StopBenchmarkTiming();                                                     \\\n    Eigen::CudaStreamDevice stream;                                            \\\n    Eigen::GpuDevice device(&stream);                                          \\\n    BenchmarkSuite<Eigen::GpuDevice, float> suite(device, D1, D2, D3);         \\\n    cudaDeviceSynchronize();                                                   \\\n    suite.FUNC(iters);                                                         \\\n  }                                                                            \\\n  BENCHMARK_RANGE(BM_##FUNC##_##D1##x##D2##x##D3, 10, 5000);\n\n\nBM_FuncWithInputDimsGPU(contraction, N, N, N);\nBM_FuncWithInputDimsGPU(contraction, 64, N, N);\nBM_FuncWithInputDimsGPU(contraction, N, 64, N);\nBM_FuncWithInputDimsGPU(contraction, N, N, 64);\n\n\n// Convolutions\n#define BM_FuncWithKernelDimsGPU(FUNC, DIM1, DIM2)                             \\\n  static void BM_##FUNC##_##DIM1##x##DIM2(int iters, int N) {                  \\\n    StopBenchmarkTiming();                                                     \\\n    Eigen::CudaStreamDevice stream;                                            \\\n    Eigen::GpuDevice device(&stream);                                          \\\n    BenchmarkSuite<Eigen::GpuDevice, float> suite(device, N);                  \\\n    cudaDeviceSynchronize();                                                   \\\n    suite.FUNC(iters, DIM1, DIM2);                                             \\\n  }                                                                            \\\n  BENCHMARK_RANGE(BM_##FUNC##_##DIM1##x##DIM2, 128, 5000);\n\nBM_FuncWithKernelDimsGPU(convolution, 7, 1);\nBM_FuncWithKernelDimsGPU(convolution, 1, 7);\nBM_FuncWithKernelDimsGPU(convolution, 7, 4);\nBM_FuncWithKernelDimsGPU(convolution, 4, 7);\nBM_FuncWithKernelDimsGPU(convolution, 7, 64);\nBM_FuncWithKernelDimsGPU(convolution, 64, 7);\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/tensors/tensor_benchmarks_sycl.cc",
    "content": "#ifdef EIGEN_USE_SYCL\n\n#include <CL/sycl.hpp>\n#include <iostream>\n\n#include \"tensor_benchmarks.h\"\n\ncl::sycl::gpu_selector selector;\nEigen::QueueInterface queue(selector);\n#define BM_FuncWithInput2DimsGPU(FUNC, D1, D2)                      \\\n  static void BM_##FUNC##_##D1##x##D2(int iters, int N) {           \\\n    StopBenchmarkTiming();                                          \\\n    Eigen::SyclDevice device(&queue);                               \\\n    BenchmarkSuite<Eigen::SyclDevice, float> suite(device, D1, D2); \\\n    suite.FUNC(iters);                                              \\\n  }                                                                 \\\n  BENCHMARK_RANGE(BM_##FUNC##_##D1##x##D2, 10, 10);\n\nBM_FuncWithInput2DimsGPU(rowReduction, 256, 100352);\nBM_FuncWithInput2DimsGPU(rowReduction, 64, 100352);\nBM_FuncWithInput2DimsGPU(rowReduction, 512, 25088);\nBM_FuncWithInput2DimsGPU(rowReduction, 128, 25088);\nBM_FuncWithInput2DimsGPU(rowReduction, 102, 6272);\nBM_FuncWithInput2DimsGPU(rowReduction, 256, 6272);\nBM_FuncWithInput2DimsGPU(rowReduction, 204, 1568);\nBM_FuncWithInput2DimsGPU(rowReduction, 512, 1568);\nBM_FuncWithInput2DimsGPU(rowReduction, 1024, 1568);\nBM_FuncWithInput2DimsGPU(rowReduction, 2048, 1568);\n\nBM_FuncWithInput2DimsGPU(colReduction, 100352, 256);\nBM_FuncWithInput2DimsGPU(colReduction, 100352, 64);\nBM_FuncWithInput2DimsGPU(colReduction, 25088, 512);\nBM_FuncWithInput2DimsGPU(colReduction, 6272, 102);\nBM_FuncWithInput2DimsGPU(colReduction, 25088, 128);\nBM_FuncWithInput2DimsGPU(colReduction, 6272, 256);\nBM_FuncWithInput2DimsGPU(colReduction, 1568, 204);\nBM_FuncWithInput2DimsGPU(colReduction, 1568, 512);\nBM_FuncWithInput2DimsGPU(colReduction, 1568, 1024);\nBM_FuncWithInput2DimsGPU(colReduction, 1568, 2048);\nBM_FuncWithInput2DimsGPU(fullReduction, 1001, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 2050048, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 2097152, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 2048, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 262144, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 256, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 589824, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 1024, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 524288, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 512, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 2359296, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 1048576, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 131072, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 16384, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 9408, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 64, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 4096, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 36864, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 32768, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 128, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 147456, 1);\nBM_FuncWithInput2DimsGPU(fullReduction, 65536, 1);\n#define BM_FuncGPU(FUNC)                                       \\\n  static void BM_##FUNC(int iters, int N) {                    \\\n    StopBenchmarkTiming();                                     \\\n    Eigen::SyclDevice device(&queue);                          \\\n    BenchmarkSuite<Eigen::SyclDevice, float> suite(device, N); \\\n    suite.FUNC(iters);                                         \\\n  }                                                            \\\n  BENCHMARK_RANGE(BM_##FUNC, 10, 5000);\n\nBM_FuncGPU(rowReduction);\nBM_FuncGPU(colReduction);\nBM_FuncGPU(fullReduction);\n\nBM_FuncGPU(memcpy);\nBM_FuncGPU(typeCasting);\nBM_FuncGPU(random);\nBM_FuncGPU(slicing);\nBM_FuncGPU(rowChip);\nBM_FuncGPU(colChip);\nBM_FuncGPU(shuffling);\nBM_FuncGPU(padding);\nBM_FuncGPU(striding);\nBM_FuncGPU(broadcasting);\nBM_FuncGPU(coeffWiseOp);\nBM_FuncGPU(algebraicFunc);\nBM_FuncGPU(transcendentalFunc);\n// Contractions\n#define BM_FuncWithInputDimsGPU(FUNC, D1, D2, D3)                       \\\n  static void BM_##FUNC##_##D1##x##D2##x##D3(int iters, int N) {        \\\n    StopBenchmarkTiming();                                              \\\n    Eigen::SyclDevice device(&queue);                                   \\\n    BenchmarkSuite<Eigen::SyclDevice, float> suite(device, D1, D2, D3); \\\n    suite.FUNC(iters);                                                  \\\n  }                                                                     \\\n  BENCHMARK_RANGE(BM_##FUNC##_##D1##x##D2##x##D3, 10, 5000);\n\nBM_FuncWithInputDimsGPU(contraction, N, N, N);\nBM_FuncWithInputDimsGPU(contraction, 64, N, N);\nBM_FuncWithInputDimsGPU(contraction, N, 64, N);\nBM_FuncWithInputDimsGPU(contraction, N, N, 64);\n\nBM_FuncWithInputDimsGPU(contractionRowMajor, N, N, N);\nBM_FuncWithInputDimsGPU(contractionRowMajor, 64, N, N);\nBM_FuncWithInputDimsGPU(contractionRowMajor, N, 64, N);\nBM_FuncWithInputDimsGPU(contractionRowMajor, N, N, 64);\n\nBM_FuncWithInputDimsGPU(contractionRowMajorAT, N, N, N);\nBM_FuncWithInputDimsGPU(contractionRowMajorAT, 64, N, N);\nBM_FuncWithInputDimsGPU(contractionRowMajorAT, N, 64, N);\nBM_FuncWithInputDimsGPU(contractionRowMajorAT, N, N, 64);\n\nBM_FuncWithInputDimsGPU(contractionRowMajorBT, N, N, N);\nBM_FuncWithInputDimsGPU(contractionRowMajorBT, 64, N, N);\nBM_FuncWithInputDimsGPU(contractionRowMajorBT, N, 64, N);\nBM_FuncWithInputDimsGPU(contractionRowMajorBT, N, N, 64);\n\n\nBM_FuncWithInputDimsGPU(contractionRowMajorABT, N, N, N);\nBM_FuncWithInputDimsGPU(contractionRowMajorABT, 64, N, N);\nBM_FuncWithInputDimsGPU(contractionRowMajorABT, N, 64, N);\nBM_FuncWithInputDimsGPU(contractionRowMajorABT, N, N, 64);\n\n// Convolutions\n#define BM_FuncWithKernelDimsGPU(FUNC, DIM1, DIM2)             \\\n  static void BM_##FUNC##_##DIM1##x##DIM2(int iters, int N) {  \\\n    StopBenchmarkTiming();                                     \\\n    Eigen::SyclDevice device(&queue);                          \\\n    BenchmarkSuite<Eigen::SyclDevice, float> suite(device, N); \\\n    suite.FUNC(iters, DIM1, DIM2);                             \\\n  }                                                            \\\n  BENCHMARK_RANGE(BM_##FUNC##_##DIM1##x##DIM2, 128, 5000);\n\nBM_FuncWithKernelDimsGPU(convolution, 7, 1);\nBM_FuncWithKernelDimsGPU(convolution, 1, 7);\nBM_FuncWithKernelDimsGPU(convolution, 7, 4);\nBM_FuncWithKernelDimsGPU(convolution, 4, 7);\nBM_FuncWithKernelDimsGPU(convolution, 7, 64);\nBM_FuncWithKernelDimsGPU(convolution, 64, 7);\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/tensors/tensor_contract_sycl_bench.cc",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n#ifndef EIGEN_BENCH_CONTRACT_SYCL\n#define EIGEN_BENCH_CONTRACT_SYCL\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#include <SYCL/sycl.hpp>\n#include <fstream>\n#include <iostream>\n#include <chrono>\n#include <ctime>\n\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\nstd::ofstream out(\"Result.txt\");\n\nstd::chrono::time_point<std::chrono::system_clock> get_time(){\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  return std::chrono::system_clock::now();\n}\n\ntemplate<typename Start, typename End, typename TensorIndex>\nvoid finalizeBenchmark(Start start, End end, TensorIndex m_, TensorIndex k_, TensorIndex n_ , TensorIndex num_iters, std::string name){\n\n  std::chrono::duration<double> elapsed_seconds = end-start;\n  std::cout <<\"Kernel Name : \" << name << \", M : \" << m_ << \",  N : \" << n_ << \", K : \" << k_ << \" GFLOP/s : \" <<\n  static_cast<float>((static_cast<int64_t>(2) * m_ * n_ * k_ * num_iters)/ elapsed_seconds.count()) * 1e-9 << \"\\n\";\n    out <<\"Kernel Name : \" << name << \", M : \" << m_ << \",  N : \" << n_ << \", K : \" << k_ << \" GFLOP/s : \" <<\n    static_cast<float>((static_cast<int64_t>(2) * m_ * n_ * k_ * num_iters)/ elapsed_seconds.count()) * 1e-9 << \"\\n\";\n}\n\n// do a contraction which is equivalent to a matrix multiplication\ntemplate<typename T, typename Device, typename TensorIndex>\nvoid contraction(const Device& device_, TensorIndex num_iters, TensorIndex m_, TensorIndex k_, TensorIndex n_) {\n  T* a_;\n  T* b_;\n  T* c_;\n  a_ = (T *) device_.allocate(m_ * k_ * sizeof(T));\n  b_ = (T *) device_.allocate(k_ * n_ * sizeof(T));\n  c_ = (T *) device_.allocate(m_ * n_ * sizeof(T));\n\n  // Initialize the content of the memory pools to prevent asan from\n  // complaining.\n  device_.memset(a_, 12, m_ * k_ * sizeof(T));\n  device_.memset(b_, 23, k_ * n_ * sizeof(T));\n  device_.memset(c_, 31, m_ * n_ * sizeof(T));\n\n  Eigen::array<TensorIndex, 2> sizeA;\n  sizeA[0] = m_;\n  sizeA[1] = k_;\n  Eigen::array<TensorIndex, 2> sizeB;\n  sizeB[0] = k_;\n  sizeB[1] = n_;\n  Eigen::array<TensorIndex, 2> sizeC;\n  sizeC[0] = m_;\n  sizeC[1] = n_;\n\n  const TensorMap<Tensor<T, 2>, Eigen::Aligned> A(a_, sizeA);\n  const TensorMap<Tensor<T, 2>, Eigen::Aligned> B(b_, sizeB);\n  TensorMap<Tensor<T, 2>, Eigen::Aligned> C(c_, sizeC);\n\n  typedef typename Tensor<T, 2>::DimensionPair DimPair;\n  Eigen::array<DimPair, 1> dims;\n  dims[0] = DimPair(1, 0);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n  for (int iter = 0; iter < 10; ++iter) {\n    C.device(device_) = A.contract(B, dims);\n   }\n#endif\n  auto start = get_time();\n  for (int iter = 0; iter < num_iters; ++iter) {\n    C.device(device_) = A.contract(B, dims);\n  }\n auto end = get_time();\n  // Record the number of FLOPs executed per second (size_ multiplications and\n  // additions for each value in the resulting tensor)\n  finalizeBenchmark(start, end, m_, k_, n_, num_iters, \"contraction\");\n  device_.deallocate(a_);\n  device_.deallocate(b_);\n  device_.deallocate(c_);\n  device_.synchronize();\n}\n\n\n\n// do a contraction which is equivalent to a matrix multiplication\ntemplate<typename T, typename Device, typename TensorIndex>\nvoid contractionRowMajor(const Device& device_, TensorIndex num_iters, TensorIndex m_, TensorIndex k_, TensorIndex n_) {\n  T* a_;\n  T* b_;\n  T* c_;\n  a_ = (T *) device_.allocate(m_ * k_ * sizeof(T));\n  b_ = (T *) device_.allocate(k_ * n_ * sizeof(T));\n  c_ = (T *) device_.allocate(m_ * n_ * sizeof(T));\n\n  // Initialize the content of the memory pools to prevent asan from\n  // complaining.\n  device_.memset(a_, 12, m_ * k_ * sizeof(T));\n  device_.memset(b_, 23, k_ * n_ * sizeof(T));\n  device_.memset(c_, 31, m_ * n_ * sizeof(T));\n\n  Eigen::array<TensorIndex, 2> sizeA;\n  sizeA[0] = m_;\n  sizeA[1] = k_;\n  Eigen::array<TensorIndex, 2> sizeB;\n  sizeB[0] = k_;\n  sizeB[1] = n_;\n  Eigen::array<TensorIndex, 2> sizeC;\n  sizeC[0] = m_;\n  sizeC[1] = n_;\n\n  const TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> A(a_, sizeA);\n  const TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> B(b_, sizeB);\n  TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> C(c_, sizeC);\n\n  typedef typename Tensor<T, 2>::DimensionPair DimPair;\n  Eigen::array<DimPair, 1> dims;\n  dims[0] = DimPair(1, 0);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n  for (int iter = 0; iter < 10; ++iter) {\n    C.device(device_) = A.contract(B, dims);\n   }\n#endif\n  auto start = get_time();\n  for (int iter = 0; iter < num_iters; ++iter) {\n    C.device(device_) = A.contract(B, dims);\n  }\n  auto end = get_time();\n  // Record the number of FLOPs executed per second (size_ multiplications and\n  // additions for each value in the resulting tensor)\n  finalizeBenchmark(start, end, m_, k_, n_, num_iters, \"contractionRowMajor\");\n  device_.deallocate(a_);\n  device_.deallocate(b_);\n  device_.deallocate(c_);\n  device_.synchronize();\n}\n\n\ntemplate<typename T, typename Device, typename TensorIndex>\nvoid contractionAT(const Device& device_, TensorIndex num_iters, TensorIndex m_, TensorIndex k_, TensorIndex n_) {\n  T* a_;\n  T* b_;\n  T* c_;\n  a_ = (T *) device_.allocate(m_ * k_ * sizeof(T));\n  b_ = (T *) device_.allocate(k_ * n_ * sizeof(T));\n  c_ = (T *) device_.allocate(m_ * n_ * sizeof(T));\n\n  // Initialize the content of the memory pools to prevent asan from\n  // complaining.\n  device_.memset(a_, 12, m_ * k_ * sizeof(T));\n  device_.memset(b_, 23, k_ * n_ * sizeof(T));\n  device_.memset(c_, 31, m_ * n_ * sizeof(T));\n  Eigen::array<TensorIndex, 2> sizeA;\n  sizeA[0] = k_;\n  sizeA[1] = m_;\n  Eigen::array<TensorIndex, 2> sizeB;\n  sizeB[0] = k_;\n  sizeB[1] = n_;\n  Eigen::array<TensorIndex, 2> sizeC;\n  sizeC[0] = m_;\n  sizeC[1] = n_;\n\n  const TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> A(a_, sizeA);\n  const TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> B(b_, sizeB);\n  TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> C(c_, sizeC);\n\n  typedef typename Tensor<T, 2>::DimensionPair DimPair;\n  Eigen::array<DimPair, 1> dims;\n  dims[0] = DimPair(0, 0);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n  for (int iter = 0; iter < 10; ++iter) {\n    C.device(device_) = A.contract(B, dims);\n   }\n#endif\n  auto start = get_time();\n  for (int iter = 0; iter < num_iters; ++iter) {\n    C.device(device_) = A.contract(B, dims);\n  }\n  auto end = get_time();\n  // Record the number of FLOPs executed per second (size_ multiplications and\n  // additions for each value in the resulting tensor)\n  finalizeBenchmark(start, end, m_, k_, n_, num_iters, \"contractionAT\");\n  device_.deallocate(a_);\n  device_.deallocate(b_);\n  device_.deallocate(c_);\n  device_.synchronize();\n\n}\n\ntemplate<typename T, typename Device, typename TensorIndex>\nvoid contractionBT(const Device& device_, TensorIndex num_iters, TensorIndex m_, TensorIndex k_, TensorIndex n_) {\n  T* a_;\n  T* b_;\n  T* c_;\n  a_ = (T *) device_.allocate(m_ * k_ * sizeof(T));\n  b_ = (T *) device_.allocate(k_ * n_ * sizeof(T));\n  c_ = (T *) device_.allocate(m_ * n_ * sizeof(T));\n\n  // Initialize the content of the memory pools to prevent asan from\n  // complaining.\n  device_.memset(a_, 12, m_ * k_ * sizeof(T));\n  device_.memset(b_, 23, k_ * n_ * sizeof(T));\n  device_.memset(c_, 31, m_ * n_ * sizeof(T));\n\n  Eigen::array<TensorIndex, 2> sizeA;\n  sizeA[0] = m_;\n  sizeA[1] = k_;\n  Eigen::array<TensorIndex, 2> sizeB;\n  sizeB[0] = n_;\n  sizeB[1] = k_;\n  Eigen::array<TensorIndex, 2> sizeC;\n  sizeC[0] = m_;\n  sizeC[1] = n_;\n\n  const TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> A(a_, sizeA);\n  const TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> B(b_, sizeB);\n  TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> C(c_, sizeC);\n\n  typedef typename Tensor<T, 2>::DimensionPair DimPair;\n  Eigen::array<DimPair, 1> dims;\n  dims[0] = DimPair(1, 1);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n  for (int iter = 0; iter < 10; ++iter) {\n    C.device(device_) = A.contract(B, dims);\n   }\n#endif\n  auto start = get_time();\n  for (int iter = 0; iter < num_iters; ++iter) {\n    C.device(device_) = A.contract(B, dims);\n  }\n  auto end = get_time();\n  // Record the number of FLOPs executed per second (size_ multiplications and\n  // additions for each value in the resulting tensor)\n  finalizeBenchmark(start, end, m_, k_, n_, num_iters, \"contractionBT\");\n  device_.deallocate(a_);\n  device_.deallocate(b_);\n  device_.deallocate(c_);\n  device_.synchronize();\n\n}\n\ntemplate<typename T, typename Device, typename TensorIndex>\nvoid contractionABT(const Device& device_, TensorIndex num_iters, TensorIndex m_, TensorIndex k_, TensorIndex n_) {\n  T* a_;\n  T* b_;\n  T* c_;\n  a_ = (T *) device_.allocate(m_ * k_ * sizeof(T));\n  b_ = (T *) device_.allocate(k_ * n_ * sizeof(T));\n  c_ = (T *) device_.allocate(m_ * n_ * sizeof(T));\n\n  // Initialize the content of the memory pools to prevent asan from\n  // complaining.\n  device_.memset(a_, 12, m_ * k_ * sizeof(T));\n  device_.memset(b_, 23, k_ * n_ * sizeof(T));\n  device_.memset(c_, 31, m_ * n_ * sizeof(T));\n\n  Eigen::array<TensorIndex, 2> sizeA;\n  sizeA[0] = k_;\n  sizeA[1] = m_;\n  Eigen::array<TensorIndex, 2> sizeB;\n  sizeB[0] = n_;\n  sizeB[1] = k_;\n  Eigen::array<TensorIndex, 2> sizeC;\n  sizeC[0] = m_;\n  sizeC[1] = n_;\n\n  const TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> A(a_, sizeA);\n  const TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> B(b_, sizeB);\n  TensorMap<Tensor<T, 2, Eigen::RowMajor>, Eigen::Aligned> C(c_, sizeC);\n\n  typedef typename Tensor<T, 2>::DimensionPair DimPair;\n  Eigen::array<DimPair, 1> dims;\n  dims[0] = DimPair(0, 1);\n#ifdef EIGEN_USE_SYCL // warmup for sycl\n  for (int iter = 0; iter < 10; ++iter) {\n    C.device(device_) = A.contract(B, dims);\n   }\n#endif\n  auto start = get_time();\n  for (int iter = 0; iter < num_iters; ++iter) {\n    C.device(device_) = A.contract(B, dims);\n  }\n  auto end = get_time();\n  // Record the number of FLOPs executed per second (size_ multiplications and\n  // additions for each value in the resulting tensor)\n  finalizeBenchmark(start, end, m_, k_, n_, num_iters, \"contractionABT\");\n  device_.deallocate(a_);\n  device_.deallocate(b_);\n  device_.deallocate(c_);\n  device_.synchronize();\n}\n\nint main() {\n  cl::sycl::gpu_selector selector;\n  Eigen::QueueInterface queue(selector);\n  Eigen::SyclDevice device(&queue);\n  int64_t num_iters =20;\n  for(int64_t m = 32; m <= 4096; m *= 2)\n    for(int64_t k = 32; k <= 4096; k *= 2)\n      for(int64_t n = 32; n <= 4096; n*= 2){\n        (contraction<float>(device, num_iters, m, k, n));\n        (contractionRowMajor<float>(device, num_iters, m, k, n));\n        (contractionAT<float>(device, num_iters, m, k, n));\n        (contractionBT<float>(device, num_iters, m, k, n));\n        (contractionABT<float>(device, num_iters, m, k, n));\n      }\n  return 0;\n  }\n\n#endif // EIGEN_BENCH_CONTRACT_SYCL\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/bench/vdw_new.cpp",
    "content": "#include <iostream>\n#include <Eigen/Core>\n\nusing namespace Eigen;\n\n#ifndef SCALAR\n#define SCALAR float\n#endif\n\n#ifndef SIZE\n#define SIZE 10000\n#endif\n\n#ifndef REPEAT\n#define REPEAT 10000\n#endif\n\ntypedef Matrix<SCALAR, Eigen::Dynamic, 1> Vec;\n\nusing namespace std;\n\nSCALAR E_VDW(const Vec &interactions1, const Vec &interactions2)\n{\n  return (interactions2.cwise()/interactions1)\n         .cwise().cube()\n         .cwise().square()\n         .cwise().square()\n         .sum();\n}\n\nint main() \n{\n  //\n  //          1   2   3   4  ... (interactions)\n  // ka       .   .   .   .  ...\n  // rab      .   .   .   .  ...\n  // energy   .   .   .   .  ...\n  // ...     ... ... ... ... ...\n  // (variables\n  //    for\n  // interaction)\n  //\n  Vec interactions1(SIZE), interactions2(SIZE); // SIZE is the number of vdw interactions in our system\n  // SetupCalculations()\n  SCALAR rab = 1.0;  \n  interactions1.setConstant(2.4);\n  interactions2.setConstant(rab);\n  \n  // Energy()\n  SCALAR energy = 0.0;\n  for (unsigned int i = 0; i<REPEAT; ++i) {\n    energy += E_VDW(interactions1, interactions2);\n    energy *= 1 + 1e-20 * i; // prevent compiler from optimizing the loop\n  }\n  cout << \"energy = \" << energy << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/BandTriangularSolver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BAND_TRIANGULARSOLVER_H\n#define EIGEN_BAND_TRIANGULARSOLVER_H\n\nnamespace internal {\n\n /* \\internal\n  * Solve Ax=b with A a band triangular matrix\n  * TODO: extend it to matrices for x abd b */\ntemplate<typename Index, int Mode, typename LhsScalar, bool ConjLhs, typename RhsScalar, int StorageOrder>\nstruct band_solve_triangular_selector;\n\n\ntemplate<typename Index, int Mode, typename LhsScalar, bool ConjLhs, typename RhsScalar>\nstruct band_solve_triangular_selector<Index,Mode,LhsScalar,ConjLhs,RhsScalar,RowMajor>\n{\n  typedef Map<const Matrix<LhsScalar,Dynamic,Dynamic,RowMajor>, 0, OuterStride<> > LhsMap;\n  typedef Map<Matrix<RhsScalar,Dynamic,1> > RhsMap;\n  enum { IsLower = (Mode&Lower) ? 1 : 0 };\n  static void run(Index size, Index k, const LhsScalar* _lhs, Index lhsStride, RhsScalar* _other)\n  {\n    const LhsMap lhs(_lhs,size,k+1,OuterStride<>(lhsStride));\n    RhsMap other(_other,size,1);\n    typename internal::conditional<\n                          ConjLhs,\n                          const CwiseUnaryOp<typename internal::scalar_conjugate_op<LhsScalar>,LhsMap>,\n                          const LhsMap&>\n                        ::type cjLhs(lhs);\n                        \n    for(int col=0 ; col<other.cols() ; ++col)\n    {\n      for(int ii=0; ii<size; ++ii)\n      {\n        int i = IsLower ? ii : size-ii-1;\n        int actual_k = (std::min)(k,ii);\n        int actual_start = IsLower ? k-actual_k : 1;\n        \n        if(actual_k>0)\n          other.coeffRef(i,col) -= cjLhs.row(i).segment(actual_start,actual_k).transpose()\n                                  .cwiseProduct(other.col(col).segment(IsLower ? i-actual_k : i+1,actual_k)).sum();\n\n        if((Mode&UnitDiag)==0)\n          other.coeffRef(i,col) /= cjLhs(i,IsLower ? k : 0);\n      }\n    }\n  }\n  \n};\n\ntemplate<typename Index, int Mode, typename LhsScalar, bool ConjLhs, typename RhsScalar>\nstruct band_solve_triangular_selector<Index,Mode,LhsScalar,ConjLhs,RhsScalar,ColMajor>\n{\n  typedef Map<const Matrix<LhsScalar,Dynamic,Dynamic,ColMajor>, 0, OuterStride<> > LhsMap;\n  typedef Map<Matrix<RhsScalar,Dynamic,1> > RhsMap;\n  enum { IsLower = (Mode&Lower) ? 1 : 0 };\n  static void run(Index size, Index k, const LhsScalar* _lhs, Index lhsStride, RhsScalar* _other)\n  {\n    const LhsMap lhs(_lhs,k+1,size,OuterStride<>(lhsStride));\n    RhsMap other(_other,size,1);\n    typename internal::conditional<\n                          ConjLhs,\n                          const CwiseUnaryOp<typename internal::scalar_conjugate_op<LhsScalar>,LhsMap>,\n                          const LhsMap&>\n                        ::type cjLhs(lhs);\n                        \n    for(int col=0 ; col<other.cols() ; ++col)\n    {\n      for(int ii=0; ii<size; ++ii)\n      {\n        int i = IsLower ? ii : size-ii-1;\n        int actual_k = (std::min)(k,size-ii-1);\n        int actual_start = IsLower ? 1 : k-actual_k;\n        \n        if((Mode&UnitDiag)==0)\n          other.coeffRef(i,col) /= cjLhs(IsLower ? 0 : k, i);\n\n        if(actual_k>0)\n          other.col(col).segment(IsLower ? i+1 : i-actual_k, actual_k)\n              -= other.coeff(i,col) * cjLhs.col(i).segment(actual_start,actual_k);\n        \n      }\n    }\n  }\n};\n\n\n} // end namespace internal\n\n#endif // EIGEN_BAND_TRIANGULARSOLVER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/CMakeLists.txt",
    "content": "\nproject(EigenBlas CXX)\n\ninclude(CheckLanguage)\ncheck_language(Fortran)\nif(CMAKE_Fortran_COMPILER)\n  enable_language(Fortran)\n  set(EIGEN_Fortran_COMPILER_WORKS ON)\nelse()\n  set(EIGEN_Fortran_COMPILER_WORKS OFF)\nendif()\n\nadd_custom_target(blas)\n\nset(EigenBlas_SRCS  single.cpp double.cpp complex_single.cpp complex_double.cpp xerbla.cpp\n                    f2c/srotm.c   f2c/srotmg.c  f2c/drotm.c f2c/drotmg.c\n                    f2c/lsame.c   f2c/dspmv.c   f2c/ssbmv.c f2c/chbmv.c\n                    f2c/sspmv.c   f2c/zhbmv.c   f2c/chpmv.c f2c/dsbmv.c\n                    f2c/zhpmv.c   f2c/dtbmv.c   f2c/stbmv.c f2c/ctbmv.c\n                    f2c/ztbmv.c   f2c/d_cnjg.c  f2c/r_cnjg.c\n   )\n\nif (EIGEN_Fortran_COMPILER_WORKS)\n  set(EigenBlas_SRCS ${EigenBlas_SRCS} fortran/complexdots.f)\nelse()\n  set(EigenBlas_SRCS ${EigenBlas_SRCS} f2c/complexdots.c)\nendif()\n\nadd_library(eigen_blas_static ${EigenBlas_SRCS})\nadd_library(eigen_blas SHARED ${EigenBlas_SRCS})\n\nif(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO)\n  target_link_libraries(eigen_blas_static ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO})\n  target_link_libraries(eigen_blas        ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO})\nendif()\n\nadd_dependencies(blas eigen_blas eigen_blas_static)\n\ninstall(TARGETS eigen_blas eigen_blas_static\n        RUNTIME DESTINATION bin\n        LIBRARY DESTINATION lib\n        ARCHIVE DESTINATION lib)\n\nif(EIGEN_Fortran_COMPILER_WORKS)\n\nif(BUILD_TESTING)\n  if(EIGEN_LEAVE_TEST_IN_ALL_TARGET)\n    add_subdirectory(testing) # can't do EXCLUDE_FROM_ALL here, breaks CTest\n  else()\n    add_subdirectory(testing EXCLUDE_FROM_ALL)\n  endif()\nendif()\n\nendif()\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/GeneralRank1Update.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_GENERAL_RANK1UPDATE_H\n#define EIGEN_GENERAL_RANK1UPDATE_H\n\nnamespace internal {\n\n/* Optimized matrix += alpha * uv' */\ntemplate<typename Scalar, typename Index, int StorageOrder, bool ConjLhs, bool ConjRhs>\nstruct general_rank1_update;\n\ntemplate<typename Scalar, typename Index, bool ConjLhs, bool ConjRhs>\nstruct general_rank1_update<Scalar,Index,ColMajor,ConjLhs,ConjRhs>\n{\n  static void run(Index rows, Index cols, Scalar* mat, Index stride, const Scalar* u, const Scalar* v, Scalar alpha)\n  {\n    typedef Map<const Matrix<Scalar,Dynamic,1> > OtherMap;\n    typedef typename conj_expr_if<ConjLhs,OtherMap>::type ConjRhsType;\n    conj_if<ConjRhs> cj;\n\n    for (Index i=0; i<cols; ++i)\n      Map<Matrix<Scalar,Dynamic,1> >(mat+stride*i,rows) += alpha * cj(v[i]) * ConjRhsType(OtherMap(u,rows));\n  }\n};\n\ntemplate<typename Scalar, typename Index, bool ConjLhs, bool ConjRhs>\nstruct general_rank1_update<Scalar,Index,RowMajor,ConjLhs,ConjRhs>\n{\n  static void run(Index rows, Index cols, Scalar* mat, Index stride, const Scalar* u, const Scalar* v, Scalar alpha)\n  {\n    general_rank1_update<Scalar,Index,ColMajor,ConjRhs,ConjRhs>::run(rows,cols,mat,stride,u,v,alpha);\n  }\n};\n\n} // end namespace internal\n\n#endif // EIGEN_GENERAL_RANK1UPDATE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/PackedSelfadjointProduct.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SELFADJOINT_PACKED_PRODUCT_H\n#define EIGEN_SELFADJOINT_PACKED_PRODUCT_H\n\nnamespace internal {\n\n/* Optimized matrix += alpha * uv'\n * The matrix is in packed form.\n */\ntemplate<typename Scalar, typename Index, int StorageOrder, int UpLo, bool ConjLhs, bool ConjRhs>\nstruct selfadjoint_packed_rank1_update;\n\ntemplate<typename Scalar, typename Index, int UpLo, bool ConjLhs, bool ConjRhs>\nstruct selfadjoint_packed_rank1_update<Scalar,Index,ColMajor,UpLo,ConjLhs,ConjRhs>\n{\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  static void run(Index size, Scalar* mat, const Scalar* vec, RealScalar alpha)\n  {\n    typedef Map<const Matrix<Scalar,Dynamic,1> > OtherMap;\n    typedef typename conj_expr_if<ConjLhs,OtherMap>::type ConjRhsType;\n    conj_if<ConjRhs> cj;\n\n    for (Index i=0; i<size; ++i)\n    {\n      Map<Matrix<Scalar,Dynamic,1> >(mat, UpLo==Lower ? size-i : (i+1)) += alpha * cj(vec[i]) * ConjRhsType(OtherMap(vec+(UpLo==Lower ? i : 0), UpLo==Lower ? size-i : (i+1)));\n      //FIXME This should be handled outside.\n      mat[UpLo==Lower ? 0 : i] = numext::real(mat[UpLo==Lower ? 0 : i]);\n      mat += UpLo==Lower ? size-i : (i+1);\n    }\n  }\n};\n\ntemplate<typename Scalar, typename Index, int UpLo, bool ConjLhs, bool ConjRhs>\nstruct selfadjoint_packed_rank1_update<Scalar,Index,RowMajor,UpLo,ConjLhs,ConjRhs>\n{\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  static void run(Index size, Scalar* mat, const Scalar* vec, RealScalar alpha)\n  {\n    selfadjoint_packed_rank1_update<Scalar,Index,ColMajor,UpLo==Lower?Upper:Lower,ConjRhs,ConjLhs>::run(size,mat,vec,alpha);\n  }\n};\n\n} // end namespace internal\n\n#endif // EIGEN_SELFADJOINT_PACKED_PRODUCT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/PackedTriangularMatrixVector.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_PACKED_TRIANGULAR_MATRIX_VECTOR_H\n#define EIGEN_PACKED_TRIANGULAR_MATRIX_VECTOR_H\n\nnamespace internal {\n\ntemplate<typename Index, int Mode, typename LhsScalar, bool ConjLhs, typename RhsScalar, bool ConjRhs, int StorageOrder>\nstruct packed_triangular_matrix_vector_product;\n\ntemplate<typename Index, int Mode, typename LhsScalar, bool ConjLhs, typename RhsScalar, bool ConjRhs>\nstruct packed_triangular_matrix_vector_product<Index,Mode,LhsScalar,ConjLhs,RhsScalar,ConjRhs,ColMajor>\n{\n  typedef typename ScalarBinaryOpTraits<LhsScalar, RhsScalar>::ReturnType ResScalar;\n  enum {\n    IsLower     = (Mode & Lower)   ==Lower,\n    HasUnitDiag = (Mode & UnitDiag)==UnitDiag,\n    HasZeroDiag = (Mode & ZeroDiag)==ZeroDiag\n  };\n  static void run(Index size, const LhsScalar* lhs, const RhsScalar* rhs, ResScalar* res, ResScalar alpha)\n  {\n    internal::conj_if<ConjRhs> cj;\n    typedef Map<const Matrix<LhsScalar,Dynamic,1> > LhsMap;\n    typedef typename conj_expr_if<ConjLhs,LhsMap>::type ConjLhsType;\n    typedef Map<Matrix<ResScalar,Dynamic,1> > ResMap;\n\n    for (Index i=0; i<size; ++i)\n    {\n      Index s = IsLower&&(HasUnitDiag||HasZeroDiag) ? 1 : 0;\n      Index r = IsLower ? size-i: i+1;\n      if (EIGEN_IMPLIES(HasUnitDiag||HasZeroDiag, (--r)>0))\n\tResMap(res+(IsLower ? s+i : 0),r) += alpha * cj(rhs[i]) * ConjLhsType(LhsMap(lhs+s,r));\n      if (HasUnitDiag)\n\tres[i] += alpha * cj(rhs[i]);\n      lhs += IsLower ? size-i: i+1;\n    }\n  };\n};\n\ntemplate<typename Index, int Mode, typename LhsScalar, bool ConjLhs, typename RhsScalar, bool ConjRhs>\nstruct packed_triangular_matrix_vector_product<Index,Mode,LhsScalar,ConjLhs,RhsScalar,ConjRhs,RowMajor>\n{\n  typedef typename ScalarBinaryOpTraits<LhsScalar, RhsScalar>::ReturnType ResScalar;\n  enum {\n    IsLower     = (Mode & Lower)   ==Lower,\n    HasUnitDiag = (Mode & UnitDiag)==UnitDiag,\n    HasZeroDiag = (Mode & ZeroDiag)==ZeroDiag\n  };\n  static void run(Index size, const LhsScalar* lhs, const RhsScalar* rhs, ResScalar* res, ResScalar alpha)\n  {\n    internal::conj_if<ConjRhs> cj;\n    typedef Map<const Matrix<LhsScalar,Dynamic,1> > LhsMap;\n    typedef typename conj_expr_if<ConjLhs,LhsMap>::type ConjLhsType;\n    typedef Map<const Matrix<RhsScalar,Dynamic,1> > RhsMap;\n    typedef typename conj_expr_if<ConjRhs,RhsMap>::type ConjRhsType;\n\n    for (Index i=0; i<size; ++i)\n    {\n      Index s = !IsLower&&(HasUnitDiag||HasZeroDiag) ? 1 : 0;\n      Index r = IsLower ? i+1 : size-i;\n      if (EIGEN_IMPLIES(HasUnitDiag||HasZeroDiag, (--r)>0))\n\tres[i] += alpha * (ConjLhsType(LhsMap(lhs+s,r)).cwiseProduct(ConjRhsType(RhsMap(rhs+(IsLower ? 0 : s+i),r)))).sum();\n      if (HasUnitDiag)\n\tres[i] += alpha * cj(rhs[i]);\n      lhs += IsLower ? i+1 : size-i;\n    }\n  };\n};\n\n} // end namespace internal\n\n#endif // EIGEN_PACKED_TRIANGULAR_MATRIX_VECTOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/PackedTriangularSolverVector.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_PACKED_TRIANGULAR_SOLVER_VECTOR_H\n#define EIGEN_PACKED_TRIANGULAR_SOLVER_VECTOR_H\n\nnamespace internal {\n\ntemplate<typename LhsScalar, typename RhsScalar, typename Index, int Side, int Mode, bool Conjugate, int StorageOrder>\nstruct packed_triangular_solve_vector;\n\n// forward and backward substitution, row-major, rhs is a vector\ntemplate<typename LhsScalar, typename RhsScalar, typename Index, int Mode, bool Conjugate>\nstruct packed_triangular_solve_vector<LhsScalar, RhsScalar, Index, OnTheLeft, Mode, Conjugate, RowMajor>\n{\n  enum {\n    IsLower = (Mode&Lower)==Lower\n  };\n  static void run(Index size, const LhsScalar* lhs, RhsScalar* rhs)\n  {\n    internal::conj_if<Conjugate> cj;\n    typedef Map<const Matrix<LhsScalar,Dynamic,1> > LhsMap;\n    typedef typename conj_expr_if<Conjugate,LhsMap>::type ConjLhsType;\n\n    lhs += IsLower ? 0 : (size*(size+1)>>1)-1;\n    for(Index pi=0; pi<size; ++pi)\n    {\n      Index i = IsLower ? pi : size-pi-1;\n      Index s = IsLower ? 0 : 1;\n      if (pi>0)\n\trhs[i] -= (ConjLhsType(LhsMap(lhs+s,pi))\n\t    .cwiseProduct(Map<const Matrix<RhsScalar,Dynamic,1> >(rhs+(IsLower ? 0 : i+1),pi))).sum();\n      if (!(Mode & UnitDiag))\n\trhs[i] /= cj(lhs[IsLower ? i : 0]);\n      IsLower ? lhs += pi+1 : lhs -= pi+2;\n    }\n  }\n};\n\n// forward and backward substitution, column-major, rhs is a vector\ntemplate<typename LhsScalar, typename RhsScalar, typename Index, int Mode, bool Conjugate>\nstruct packed_triangular_solve_vector<LhsScalar, RhsScalar, Index, OnTheLeft, Mode, Conjugate, ColMajor>\n{\n  enum {\n    IsLower = (Mode&Lower)==Lower\n  };\n  static void run(Index size, const LhsScalar* lhs, RhsScalar* rhs)\n  {\n    internal::conj_if<Conjugate> cj;\n    typedef Map<const Matrix<LhsScalar,Dynamic,1> > LhsMap;\n    typedef typename conj_expr_if<Conjugate,LhsMap>::type ConjLhsType;\n\n    lhs += IsLower ? 0 : size*(size-1)>>1;\n    for(Index pi=0; pi<size; ++pi)\n    {\n      Index i = IsLower ? pi : size-pi-1;\n      Index r = size - pi - 1;\n      if (!(Mode & UnitDiag))\n\trhs[i] /= cj(lhs[IsLower ? 0 : i]);\n      if (r>0)\n\tMap<Matrix<RhsScalar,Dynamic,1> >(rhs+(IsLower? i+1 : 0),r) -=\n\t    rhs[i] * ConjLhsType(LhsMap(lhs+(IsLower? 1 : 0),r));\n      IsLower ? lhs += size-pi : lhs -= r;\n    }\n  }\n};\n\ntemplate<typename LhsScalar, typename RhsScalar, typename Index, int Mode, bool Conjugate, int StorageOrder>\nstruct packed_triangular_solve_vector<LhsScalar, RhsScalar, Index, OnTheRight, Mode, Conjugate, StorageOrder>\n{\n  static void run(Index size, const LhsScalar* lhs, RhsScalar* rhs)\n  {\n    packed_triangular_solve_vector<LhsScalar,RhsScalar,Index,OnTheLeft,\n\t((Mode&Upper)==Upper ? Lower : Upper) | (Mode&UnitDiag),\n\tConjugate,StorageOrder==RowMajor?ColMajor:RowMajor\n      >::run(size, lhs, rhs);\n  }\n};\n\n} // end namespace internal\n\n#endif // EIGEN_PACKED_TRIANGULAR_SOLVER_VECTOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/README.txt",
    "content": "\nThis directory contains a BLAS library built on top of Eigen.\n\nThis module is not built by default. In order to compile it, you need to\ntype 'make blas' from within your build dir.\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/Rank2Update.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_RANK2UPDATE_H\n#define EIGEN_RANK2UPDATE_H\n\nnamespace internal {\n\n/* Optimized selfadjoint matrix += alpha * uv' + conj(alpha)*vu'\n * This is the low-level version of SelfadjointRank2Update.h\n */\ntemplate<typename Scalar, typename Index, int UpLo>\nstruct rank2_update_selector\n{\n  static void run(Index size, Scalar* mat, Index stride, const Scalar* u, const Scalar* v, Scalar alpha)\n  {\n    typedef Map<const Matrix<Scalar,Dynamic,1> > OtherMap;\n    for (Index i=0; i<size; ++i)\n    {\n      Map<Matrix<Scalar,Dynamic,1> >(mat+stride*i+(UpLo==Lower ? i : 0), UpLo==Lower ? size-i : (i+1)) +=\n      numext::conj(alpha) * numext::conj(u[i]) * OtherMap(v+(UpLo==Lower ? i : 0), UpLo==Lower ? size-i : (i+1))\n                + alpha * numext::conj(v[i]) * OtherMap(u+(UpLo==Lower ? i : 0), UpLo==Lower ? size-i : (i+1));\n    }\n  }\n};\n\n/* Optimized selfadjoint matrix += alpha * uv' + conj(alpha)*vu'\n * The matrix is in packed form.\n */\ntemplate<typename Scalar, typename Index, int UpLo>\nstruct packed_rank2_update_selector\n{\n  static void run(Index size, Scalar* mat, const Scalar* u, const Scalar* v, Scalar alpha)\n  {\n    typedef Map<const Matrix<Scalar,Dynamic,1> > OtherMap;\n    Index offset = 0;\n    for (Index i=0; i<size; ++i)\n    {\n      Map<Matrix<Scalar,Dynamic,1> >(mat+offset, UpLo==Lower ? size-i : (i+1)) +=\n      numext::conj(alpha) * numext::conj(u[i]) * OtherMap(v+(UpLo==Lower ? i : 0), UpLo==Lower ? size-i : (i+1))\n                + alpha * numext::conj(v[i]) * OtherMap(u+(UpLo==Lower ? i : 0), UpLo==Lower ? size-i : (i+1));\n      //FIXME This should be handled outside.\n      mat[offset+(UpLo==Lower ? 0 : i)] = numext::real(mat[offset+(UpLo==Lower ? 0 : i)]);\n      offset += UpLo==Lower ? size-i : (i+1);\n    }\n  }\n};\n\n} // end namespace internal\n\n#endif // EIGEN_RANK2UPDATE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/common.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BLAS_COMMON_H\n#define EIGEN_BLAS_COMMON_H\n\n#ifdef __GNUC__\n# if __GNUC__<5\n// GCC < 5.0 does not like the global Scalar typedef\n// we just keep shadow-warnings disabled permanently\n#  define EIGEN_PERMANENTLY_DISABLE_STUPID_WARNINGS\n# endif\n#endif\n\n#include \"../Eigen/Core\"\n#include \"../Eigen/Jacobi\"\n\n#include <complex>\n\n#ifndef SCALAR\n#error the token SCALAR must be defined to compile this file\n#endif\n\n#include \"../Eigen/src/misc/blas.h\"\n\n#define NOTR    0\n#define TR      1\n#define ADJ     2\n\n#define LEFT    0\n#define RIGHT   1\n\n#define UP      0\n#define LO      1\n\n#define NUNIT   0\n#define UNIT    1\n\n#define INVALID 0xff\n\n#define OP(X)   (   ((X)=='N' || (X)=='n') ? NOTR   \\\n                  : ((X)=='T' || (X)=='t') ? TR     \\\n                  : ((X)=='C' || (X)=='c') ? ADJ    \\\n                  : INVALID)\n\n#define SIDE(X) (   ((X)=='L' || (X)=='l') ? LEFT   \\\n                  : ((X)=='R' || (X)=='r') ? RIGHT  \\\n                  : INVALID)\n\n#define UPLO(X) (   ((X)=='U' || (X)=='u') ? UP     \\\n                  : ((X)=='L' || (X)=='l') ? LO     \\\n                  : INVALID)\n\n#define DIAG(X) (   ((X)=='N' || (X)=='n') ? NUNIT  \\\n                  : ((X)=='U' || (X)=='u') ? UNIT   \\\n                  : INVALID)\n\n\ninline bool check_op(const char* op)\n{\n  return OP(*op)!=0xff;\n}\n\ninline bool check_side(const char* side)\n{\n  return SIDE(*side)!=0xff;\n}\n\ninline bool check_uplo(const char* uplo)\n{\n  return UPLO(*uplo)!=0xff;\n}\n\n\nnamespace Eigen {\n#include \"BandTriangularSolver.h\"\n#include \"GeneralRank1Update.h\"\n#include \"PackedSelfadjointProduct.h\"\n#include \"PackedTriangularMatrixVector.h\"\n#include \"PackedTriangularSolverVector.h\"\n#include \"Rank2Update.h\"\n}\n\nusing namespace Eigen;\n\ntypedef SCALAR Scalar;\ntypedef NumTraits<Scalar>::Real RealScalar;\ntypedef std::complex<RealScalar> Complex;\n\nenum\n{\n  IsComplex = Eigen::NumTraits<SCALAR>::IsComplex,\n  Conj = IsComplex\n};\n\ntypedef Matrix<Scalar,Dynamic,Dynamic,ColMajor> PlainMatrixType;\ntypedef Map<Matrix<Scalar,Dynamic,Dynamic,ColMajor>, 0, OuterStride<> > MatrixType;\ntypedef Map<const Matrix<Scalar,Dynamic,Dynamic,ColMajor>, 0, OuterStride<> > ConstMatrixType;\ntypedef Map<Matrix<Scalar,Dynamic,1>, 0, InnerStride<Dynamic> > StridedVectorType;\ntypedef Map<Matrix<Scalar,Dynamic,1> > CompactVectorType;\n\ntemplate<typename T>\nMap<Matrix<T,Dynamic,Dynamic,ColMajor>, 0, OuterStride<> >\nmatrix(T* data, int rows, int cols, int stride)\n{\n  return Map<Matrix<T,Dynamic,Dynamic,ColMajor>, 0, OuterStride<> >(data, rows, cols, OuterStride<>(stride));\n}\n\ntemplate<typename T>\nMap<const Matrix<T,Dynamic,Dynamic,ColMajor>, 0, OuterStride<> >\nmatrix(const T* data, int rows, int cols, int stride)\n{\n  return Map<const Matrix<T,Dynamic,Dynamic,ColMajor>, 0, OuterStride<> >(data, rows, cols, OuterStride<>(stride));\n}\n\ntemplate<typename T>\nMap<Matrix<T,Dynamic,1>, 0, InnerStride<Dynamic> > make_vector(T* data, int size, int incr)\n{\n  return Map<Matrix<T,Dynamic,1>, 0, InnerStride<Dynamic> >(data, size, InnerStride<Dynamic>(incr));\n}\n\ntemplate<typename T>\nMap<const Matrix<T,Dynamic,1>, 0, InnerStride<Dynamic> > make_vector(const T* data, int size, int incr)\n{\n  return Map<const Matrix<T,Dynamic,1>, 0, InnerStride<Dynamic> >(data, size, InnerStride<Dynamic>(incr));\n}\n\ntemplate<typename T>\nMap<Matrix<T,Dynamic,1> > make_vector(T* data, int size)\n{\n  return Map<Matrix<T,Dynamic,1> >(data, size);\n}\n\ntemplate<typename T>\nMap<const Matrix<T,Dynamic,1> > make_vector(const T* data, int size)\n{\n  return Map<const Matrix<T,Dynamic,1> >(data, size);\n}\n\ntemplate<typename T>\nT* get_compact_vector(T* x, int n, int incx)\n{\n  if(incx==1)\n    return x;\n\n  typename Eigen::internal::remove_const<T>::type* ret = new Scalar[n];\n  if(incx<0) make_vector(ret,n) = make_vector(x,n,-incx).reverse();\n  else       make_vector(ret,n) = make_vector(x,n, incx);\n  return ret;\n}\n\ntemplate<typename T>\nT* copy_back(T* x_cpy, T* x, int n, int incx)\n{\n  if(x_cpy==x)\n    return 0;\n\n  if(incx<0) make_vector(x,n,-incx).reverse() = make_vector(x_cpy,n);\n  else       make_vector(x,n, incx)           = make_vector(x_cpy,n);\n  return x_cpy;\n}\n\n#ifndef EIGEN_BLAS_FUNC_SUFFIX\n#define EIGEN_BLAS_FUNC_SUFFIX _\n#endif\n\n#define EIGEN_BLAS_FUNC(X) EIGEN_CAT(SCALAR_SUFFIX, EIGEN_CAT(X, EIGEN_BLAS_FUNC_SUFFIX))\n\n#endif // EIGEN_BLAS_COMMON_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/complex_double.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define SCALAR        std::complex<double>\n#define SCALAR_SUFFIX z\n#define SCALAR_SUFFIX_UP \"Z\"\n#define REAL_SCALAR_SUFFIX d\n#define ISCOMPLEX     1\n\n#include \"level1_impl.h\"\n#include \"level1_cplx_impl.h\"\n#include \"level2_impl.h\"\n#include \"level2_cplx_impl.h\"\n#include \"level3_impl.h\"\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/complex_single.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define SCALAR        std::complex<float>\n#define SCALAR_SUFFIX c\n#define SCALAR_SUFFIX_UP \"C\"\n#define REAL_SCALAR_SUFFIX s\n#define ISCOMPLEX     1\n\n#include \"level1_impl.h\"\n#include \"level1_cplx_impl.h\"\n#include \"level2_impl.h\"\n#include \"level2_cplx_impl.h\"\n#include \"level3_impl.h\"\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/double.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2012 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define SCALAR        double\n#define SCALAR_SUFFIX d\n#define SCALAR_SUFFIX_UP \"D\"\n#define ISCOMPLEX     0\n\n#include \"level1_impl.h\"\n#include \"level1_real_impl.h\"\n#include \"level2_impl.h\"\n#include \"level2_real_impl.h\"\n#include \"level3_impl.h\"\n\ndouble EIGEN_BLAS_FUNC(sdot)(int* n, float* x, int* incx, float* y, int* incy)\n{\n  if(*n<=0) return 0;\n\n  if(*incx==1 && *incy==1)    return (make_vector(x,*n).cast<double>().cwiseProduct(make_vector(y,*n).cast<double>())).sum();\n  else if(*incx>0 && *incy>0) return (make_vector(x,*n,*incx).cast<double>().cwiseProduct(make_vector(y,*n,*incy).cast<double>())).sum();\n  else if(*incx<0 && *incy>0) return (make_vector(x,*n,-*incx).reverse().cast<double>().cwiseProduct(make_vector(y,*n,*incy).cast<double>())).sum();\n  else if(*incx>0 && *incy<0) return (make_vector(x,*n,*incx).cast<double>().cwiseProduct(make_vector(y,*n,-*incy).reverse().cast<double>())).sum();\n  else if(*incx<0 && *incy<0) return (make_vector(x,*n,-*incx).reverse().cast<double>().cwiseProduct(make_vector(y,*n,-*incy).reverse().cast<double>())).sum();\n  else return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/chbmv.c",
    "content": "/* chbmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int chbmv_(char *uplo, integer *n, integer *k, complex *\n\talpha, complex *a, integer *lda, complex *x, integer *incx, complex *\n\tbeta, complex *y, integer *incy, ftnlen uplo_len)\n{\n    /* System generated locals */\n    integer a_dim1, a_offset, i__1, i__2, i__3, i__4, i__5;\n    real r__1;\n    complex q__1, q__2, q__3, q__4;\n\n    /* Builtin functions */\n    void r_cnjg(complex *, complex *);\n\n    /* Local variables */\n    integer i__, j, l, ix, iy, jx, jy, kx, ky, info;\n    complex temp1, temp2;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    integer kplus1;\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  CHBMV  performs the matrix-vector  operation */\n\n/*     y := alpha*A*x + beta*y, */\n\n/*  where alpha and beta are scalars, x and y are n element vectors and */\n/*  A is an n by n hermitian band matrix, with k super-diagonals. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the upper or lower */\n/*           triangular part of the band matrix A is being supplied as */\n/*           follows: */\n\n/*              UPLO = 'U' or 'u'   The upper triangular part of A is */\n/*                                  being supplied. */\n\n/*              UPLO = 'L' or 'l'   The lower triangular part of A is */\n/*                                  being supplied. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  K      - INTEGER. */\n/*           On entry, K specifies the number of super-diagonals of the */\n/*           matrix A. K must satisfy  0 .le. K. */\n/*           Unchanged on exit. */\n\n/*  ALPHA  - COMPLEX         . */\n/*           On entry, ALPHA specifies the scalar alpha. */\n/*           Unchanged on exit. */\n\n/*  A      - COMPLEX          array of DIMENSION ( LDA, n ). */\n/*           Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the upper triangular */\n/*           band part of the hermitian matrix, supplied column by */\n/*           column, with the leading diagonal of the matrix in row */\n/*           ( k + 1 ) of the array, the first super-diagonal starting at */\n/*           position 2 in row k, and so on. The top left k by k triangle */\n/*           of the array A is not referenced. */\n/*           The following program segment will transfer the upper */\n/*           triangular part of a hermitian band matrix from conventional */\n/*           full matrix storage to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = K + 1 - J */\n/*                    DO 10, I = MAX( 1, J - K ), J */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the lower triangular */\n/*           band part of the hermitian matrix, supplied column by */\n/*           column, with the leading diagonal of the matrix in row 1 of */\n/*           the array, the first sub-diagonal starting at position 1 in */\n/*           row 2, and so on. The bottom right k by k triangle of the */\n/*           array A is not referenced. */\n/*           The following program segment will transfer the lower */\n/*           triangular part of a hermitian band matrix from conventional */\n/*           full matrix storage to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = 1 - J */\n/*                    DO 10, I = J, MIN( N, J + K ) */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Note that the imaginary parts of the diagonal elements need */\n/*           not be set and are assumed to be zero. */\n/*           Unchanged on exit. */\n\n/*  LDA    - INTEGER. */\n/*           On entry, LDA specifies the first dimension of A as declared */\n/*           in the calling (sub) program. LDA must be at least */\n/*           ( k + 1 ). */\n/*           Unchanged on exit. */\n\n/*  X      - COMPLEX          array of DIMENSION at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the */\n/*           vector x. */\n/*           Unchanged on exit. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  BETA   - COMPLEX         . */\n/*           On entry, BETA specifies the scalar beta. */\n/*           Unchanged on exit. */\n\n/*  Y      - COMPLEX          array of DIMENSION at least */\n/*           ( 1 + ( n - 1 )*abs( INCY ) ). */\n/*           Before entry, the incremented array Y must contain the */\n/*           vector y. On exit, Y is overwritten by the updated vector y. */\n\n/*  INCY   - INTEGER. */\n/*           On entry, INCY specifies the increment for the elements of */\n/*           Y. INCY must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    a_dim1 = *lda;\n    a_offset = 1 + a_dim1;\n    a -= a_offset;\n    --x;\n    --y;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (*n < 0) {\n\tinfo = 2;\n    } else if (*k < 0) {\n\tinfo = 3;\n    } else if (*lda < *k + 1) {\n\tinfo = 6;\n    } else if (*incx == 0) {\n\tinfo = 8;\n    } else if (*incy == 0) {\n\tinfo = 11;\n    }\n    if (info != 0) {\n\txerbla_(\"CHBMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0 || (alpha->r == 0.f && alpha->i == 0.f && (beta->r == 1.f && \n                                                           beta->i == 0.f))) {\n\treturn 0;\n    }\n\n/*     Set up the start points in  X  and  Y. */\n\n    if (*incx > 0) {\n\tkx = 1;\n    } else {\n\tkx = 1 - (*n - 1) * *incx;\n    }\n    if (*incy > 0) {\n\tky = 1;\n    } else {\n\tky = 1 - (*n - 1) * *incy;\n    }\n\n/*     Start the operations. In this version the elements of the array A */\n/*     are accessed sequentially with one pass through A. */\n\n/*     First form  y := beta*y. */\n\n    if (beta->r != 1.f || beta->i != 0.f) {\n\tif (*incy == 1) {\n\t    if (beta->r == 0.f && beta->i == 0.f) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = i__;\n\t\t    y[i__2].r = 0.f, y[i__2].i = 0.f;\n/* L10: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = i__;\n\t\t    i__3 = i__;\n\t\t    q__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, \n\t\t\t    q__1.i = beta->r * y[i__3].i + beta->i * y[i__3]\n\t\t\t    .r;\n\t\t    y[i__2].r = q__1.r, y[i__2].i = q__1.i;\n/* L20: */\n\t\t}\n\t    }\n\t} else {\n\t    iy = ky;\n\t    if (beta->r == 0.f && beta->i == 0.f) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = iy;\n\t\t    y[i__2].r = 0.f, y[i__2].i = 0.f;\n\t\t    iy += *incy;\n/* L30: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = iy;\n\t\t    i__3 = iy;\n\t\t    q__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, \n\t\t\t    q__1.i = beta->r * y[i__3].i + beta->i * y[i__3]\n\t\t\t    .r;\n\t\t    y[i__2].r = q__1.r, y[i__2].i = q__1.i;\n\t\t    iy += *incy;\n/* L40: */\n\t\t}\n\t    }\n\t}\n    }\n    if (alpha->r == 0.f && alpha->i == 0.f) {\n\treturn 0;\n    }\n    if (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\n/*        Form  y  when upper triangle of A is stored. */\n\n\tkplus1 = *k + 1;\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__2 = j;\n\t\tq__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, q__1.i =\n\t\t\t alpha->r * x[i__2].i + alpha->i * x[i__2].r;\n\t\ttemp1.r = q__1.r, temp1.i = q__1.i;\n\t\ttemp2.r = 0.f, temp2.i = 0.f;\n\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\ti__2 = 1, i__3 = j - *k;\n\t\ti__4 = j - 1;\n\t\tfor (i__ = max(i__2,i__3); i__ <= i__4; ++i__) {\n\t\t    i__2 = i__;\n\t\t    i__3 = i__;\n\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t    q__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, \n\t\t\t    q__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5]\n\t\t\t    .r;\n\t\t    q__1.r = y[i__3].r + q__2.r, q__1.i = y[i__3].i + q__2.i;\n\t\t    y[i__2].r = q__1.r, y[i__2].i = q__1.i;\n\t\t    r_cnjg(&q__3, &a[l + i__ + j * a_dim1]);\n\t\t    i__2 = i__;\n\t\t    q__2.r = q__3.r * x[i__2].r - q__3.i * x[i__2].i, q__2.i =\n\t\t\t     q__3.r * x[i__2].i + q__3.i * x[i__2].r;\n\t\t    q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i;\n\t\t    temp2.r = q__1.r, temp2.i = q__1.i;\n/* L50: */\n\t\t}\n\t\ti__4 = j;\n\t\ti__2 = j;\n\t\ti__3 = kplus1 + j * a_dim1;\n\t\tr__1 = a[i__3].r;\n\t\tq__3.r = r__1 * temp1.r, q__3.i = r__1 * temp1.i;\n\t\tq__2.r = y[i__2].r + q__3.r, q__2.i = y[i__2].i + q__3.i;\n\t\tq__4.r = alpha->r * temp2.r - alpha->i * temp2.i, q__4.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tq__1.r = q__2.r + q__4.r, q__1.i = q__2.i + q__4.i;\n\t\ty[i__4].r = q__1.r, y[i__4].i = q__1.i;\n/* L60: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__4 = jx;\n\t\tq__1.r = alpha->r * x[i__4].r - alpha->i * x[i__4].i, q__1.i =\n\t\t\t alpha->r * x[i__4].i + alpha->i * x[i__4].r;\n\t\ttemp1.r = q__1.r, temp1.i = q__1.i;\n\t\ttemp2.r = 0.f, temp2.i = 0.f;\n\t\tix = kx;\n\t\tiy = ky;\n\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\ti__4 = 1, i__2 = j - *k;\n\t\ti__3 = j - 1;\n\t\tfor (i__ = max(i__4,i__2); i__ <= i__3; ++i__) {\n\t\t    i__4 = iy;\n\t\t    i__2 = iy;\n\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t    q__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, \n\t\t\t    q__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5]\n\t\t\t    .r;\n\t\t    q__1.r = y[i__2].r + q__2.r, q__1.i = y[i__2].i + q__2.i;\n\t\t    y[i__4].r = q__1.r, y[i__4].i = q__1.i;\n\t\t    r_cnjg(&q__3, &a[l + i__ + j * a_dim1]);\n\t\t    i__4 = ix;\n\t\t    q__2.r = q__3.r * x[i__4].r - q__3.i * x[i__4].i, q__2.i =\n\t\t\t     q__3.r * x[i__4].i + q__3.i * x[i__4].r;\n\t\t    q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i;\n\t\t    temp2.r = q__1.r, temp2.i = q__1.i;\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n/* L70: */\n\t\t}\n\t\ti__3 = jy;\n\t\ti__4 = jy;\n\t\ti__2 = kplus1 + j * a_dim1;\n\t\tr__1 = a[i__2].r;\n\t\tq__3.r = r__1 * temp1.r, q__3.i = r__1 * temp1.i;\n\t\tq__2.r = y[i__4].r + q__3.r, q__2.i = y[i__4].i + q__3.i;\n\t\tq__4.r = alpha->r * temp2.r - alpha->i * temp2.i, q__4.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tq__1.r = q__2.r + q__4.r, q__1.i = q__2.i + q__4.i;\n\t\ty[i__3].r = q__1.r, y[i__3].i = q__1.i;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tif (j > *k) {\n\t\t    kx += *incx;\n\t\t    ky += *incy;\n\t\t}\n/* L80: */\n\t    }\n\t}\n    } else {\n\n/*        Form  y  when lower triangle of A is stored. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__3 = j;\n\t\tq__1.r = alpha->r * x[i__3].r - alpha->i * x[i__3].i, q__1.i =\n\t\t\t alpha->r * x[i__3].i + alpha->i * x[i__3].r;\n\t\ttemp1.r = q__1.r, temp1.i = q__1.i;\n\t\ttemp2.r = 0.f, temp2.i = 0.f;\n\t\ti__3 = j;\n\t\ti__4 = j;\n\t\ti__2 = j * a_dim1 + 1;\n\t\tr__1 = a[i__2].r;\n\t\tq__2.r = r__1 * temp1.r, q__2.i = r__1 * temp1.i;\n\t\tq__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i;\n\t\ty[i__3].r = q__1.r, y[i__3].i = q__1.i;\n\t\tl = 1 - j;\n/* Computing MIN */\n\t\ti__4 = *n, i__2 = j + *k;\n\t\ti__3 = min(i__4,i__2);\n\t\tfor (i__ = j + 1; i__ <= i__3; ++i__) {\n\t\t    i__4 = i__;\n\t\t    i__2 = i__;\n\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t    q__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, \n\t\t\t    q__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5]\n\t\t\t    .r;\n\t\t    q__1.r = y[i__2].r + q__2.r, q__1.i = y[i__2].i + q__2.i;\n\t\t    y[i__4].r = q__1.r, y[i__4].i = q__1.i;\n\t\t    r_cnjg(&q__3, &a[l + i__ + j * a_dim1]);\n\t\t    i__4 = i__;\n\t\t    q__2.r = q__3.r * x[i__4].r - q__3.i * x[i__4].i, q__2.i =\n\t\t\t     q__3.r * x[i__4].i + q__3.i * x[i__4].r;\n\t\t    q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i;\n\t\t    temp2.r = q__1.r, temp2.i = q__1.i;\n/* L90: */\n\t\t}\n\t\ti__3 = j;\n\t\ti__4 = j;\n\t\tq__2.r = alpha->r * temp2.r - alpha->i * temp2.i, q__2.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tq__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i;\n\t\ty[i__3].r = q__1.r, y[i__3].i = q__1.i;\n/* L100: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__3 = jx;\n\t\tq__1.r = alpha->r * x[i__3].r - alpha->i * x[i__3].i, q__1.i =\n\t\t\t alpha->r * x[i__3].i + alpha->i * x[i__3].r;\n\t\ttemp1.r = q__1.r, temp1.i = q__1.i;\n\t\ttemp2.r = 0.f, temp2.i = 0.f;\n\t\ti__3 = jy;\n\t\ti__4 = jy;\n\t\ti__2 = j * a_dim1 + 1;\n\t\tr__1 = a[i__2].r;\n\t\tq__2.r = r__1 * temp1.r, q__2.i = r__1 * temp1.i;\n\t\tq__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i;\n\t\ty[i__3].r = q__1.r, y[i__3].i = q__1.i;\n\t\tl = 1 - j;\n\t\tix = jx;\n\t\tiy = jy;\n/* Computing MIN */\n\t\ti__4 = *n, i__2 = j + *k;\n\t\ti__3 = min(i__4,i__2);\n\t\tfor (i__ = j + 1; i__ <= i__3; ++i__) {\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n\t\t    i__4 = iy;\n\t\t    i__2 = iy;\n\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t    q__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, \n\t\t\t    q__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5]\n\t\t\t    .r;\n\t\t    q__1.r = y[i__2].r + q__2.r, q__1.i = y[i__2].i + q__2.i;\n\t\t    y[i__4].r = q__1.r, y[i__4].i = q__1.i;\n\t\t    r_cnjg(&q__3, &a[l + i__ + j * a_dim1]);\n\t\t    i__4 = ix;\n\t\t    q__2.r = q__3.r * x[i__4].r - q__3.i * x[i__4].i, q__2.i =\n\t\t\t     q__3.r * x[i__4].i + q__3.i * x[i__4].r;\n\t\t    q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i;\n\t\t    temp2.r = q__1.r, temp2.i = q__1.i;\n/* L110: */\n\t\t}\n\t\ti__3 = jy;\n\t\ti__4 = jy;\n\t\tq__2.r = alpha->r * temp2.r - alpha->i * temp2.i, q__2.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tq__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i;\n\t\ty[i__3].r = q__1.r, y[i__3].i = q__1.i;\n\t\tjx += *incx;\n\t\tjy += *incy;\n/* L120: */\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of CHBMV . */\n\n} /* chbmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/chpmv.c",
    "content": "/* chpmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int chpmv_(char *uplo, integer *n, complex *alpha, complex *\n\tap, complex *x, integer *incx, complex *beta, complex *y, integer *\n\tincy, ftnlen uplo_len)\n{\n    /* System generated locals */\n    integer i__1, i__2, i__3, i__4, i__5;\n    real r__1;\n    complex q__1, q__2, q__3, q__4;\n\n    /* Builtin functions */\n    void r_cnjg(complex *, complex *);\n\n    /* Local variables */\n    integer i__, j, k, kk, ix, iy, jx, jy, kx, ky, info;\n    complex temp1, temp2;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  CHPMV  performs the matrix-vector operation */\n\n/*     y := alpha*A*x + beta*y, */\n\n/*  where alpha and beta are scalars, x and y are n element vectors and */\n/*  A is an n by n hermitian matrix, supplied in packed form. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the upper or lower */\n/*           triangular part of the matrix A is supplied in the packed */\n/*           array AP as follows: */\n\n/*              UPLO = 'U' or 'u'   The upper triangular part of A is */\n/*                                  supplied in AP. */\n\n/*              UPLO = 'L' or 'l'   The lower triangular part of A is */\n/*                                  supplied in AP. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  ALPHA  - COMPLEX         . */\n/*           On entry, ALPHA specifies the scalar alpha. */\n/*           Unchanged on exit. */\n\n/*  AP     - COMPLEX          array of DIMENSION at least */\n/*           ( ( n*( n + 1 ) )/2 ). */\n/*           Before entry with UPLO = 'U' or 'u', the array AP must */\n/*           contain the upper triangular part of the hermitian matrix */\n/*           packed sequentially, column by column, so that AP( 1 ) */\n/*           contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 1, 2 ) */\n/*           and a( 2, 2 ) respectively, and so on. */\n/*           Before entry with UPLO = 'L' or 'l', the array AP must */\n/*           contain the lower triangular part of the hermitian matrix */\n/*           packed sequentially, column by column, so that AP( 1 ) */\n/*           contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 2, 1 ) */\n/*           and a( 3, 1 ) respectively, and so on. */\n/*           Note that the imaginary parts of the diagonal elements need */\n/*           not be set and are assumed to be zero. */\n/*           Unchanged on exit. */\n\n/*  X      - COMPLEX          array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the n */\n/*           element vector x. */\n/*           Unchanged on exit. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  BETA   - COMPLEX         . */\n/*           On entry, BETA specifies the scalar beta. When BETA is */\n/*           supplied as zero then Y need not be set on input. */\n/*           Unchanged on exit. */\n\n/*  Y      - COMPLEX          array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCY ) ). */\n/*           Before entry, the incremented array Y must contain the n */\n/*           element vector y. On exit, Y is overwritten by the updated */\n/*           vector y. */\n\n/*  INCY   - INTEGER. */\n/*           On entry, INCY specifies the increment for the elements of */\n/*           Y. INCY must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    --y;\n    --x;\n    --ap;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (*n < 0) {\n\tinfo = 2;\n    } else if (*incx == 0) {\n\tinfo = 6;\n    } else if (*incy == 0) {\n\tinfo = 9;\n    }\n    if (info != 0) {\n\txerbla_(\"CHPMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0 || (alpha->r == 0.f && alpha->i == 0.f && (beta->r == 1.f && \n                                                           beta->i == 0.f))) {\n\treturn 0;\n    }\n\n/*     Set up the start points in  X  and  Y. */\n\n    if (*incx > 0) {\n\tkx = 1;\n    } else {\n\tkx = 1 - (*n - 1) * *incx;\n    }\n    if (*incy > 0) {\n\tky = 1;\n    } else {\n\tky = 1 - (*n - 1) * *incy;\n    }\n\n/*     Start the operations. In this version the elements of the array AP */\n/*     are accessed sequentially with one pass through AP. */\n\n/*     First form  y := beta*y. */\n\n    if (beta->r != 1.f || beta->i != 0.f) {\n\tif (*incy == 1) {\n\t    if (beta->r == 0.f && beta->i == 0.f) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = i__;\n\t\t    y[i__2].r = 0.f, y[i__2].i = 0.f;\n/* L10: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = i__;\n\t\t    i__3 = i__;\n\t\t    q__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, \n\t\t\t    q__1.i = beta->r * y[i__3].i + beta->i * y[i__3]\n\t\t\t    .r;\n\t\t    y[i__2].r = q__1.r, y[i__2].i = q__1.i;\n/* L20: */\n\t\t}\n\t    }\n\t} else {\n\t    iy = ky;\n\t    if (beta->r == 0.f && beta->i == 0.f) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = iy;\n\t\t    y[i__2].r = 0.f, y[i__2].i = 0.f;\n\t\t    iy += *incy;\n/* L30: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = iy;\n\t\t    i__3 = iy;\n\t\t    q__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, \n\t\t\t    q__1.i = beta->r * y[i__3].i + beta->i * y[i__3]\n\t\t\t    .r;\n\t\t    y[i__2].r = q__1.r, y[i__2].i = q__1.i;\n\t\t    iy += *incy;\n/* L40: */\n\t\t}\n\t    }\n\t}\n    }\n    if (alpha->r == 0.f && alpha->i == 0.f) {\n\treturn 0;\n    }\n    kk = 1;\n    if (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\n/*        Form  y  when AP contains the upper triangle. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__2 = j;\n\t\tq__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, q__1.i =\n\t\t\t alpha->r * x[i__2].i + alpha->i * x[i__2].r;\n\t\ttemp1.r = q__1.r, temp1.i = q__1.i;\n\t\ttemp2.r = 0.f, temp2.i = 0.f;\n\t\tk = kk;\n\t\ti__2 = j - 1;\n\t\tfor (i__ = 1; i__ <= i__2; ++i__) {\n\t\t    i__3 = i__;\n\t\t    i__4 = i__;\n\t\t    i__5 = k;\n\t\t    q__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, \n\t\t\t    q__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5]\n\t\t\t    .r;\n\t\t    q__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i;\n\t\t    y[i__3].r = q__1.r, y[i__3].i = q__1.i;\n\t\t    r_cnjg(&q__3, &ap[k]);\n\t\t    i__3 = i__;\n\t\t    q__2.r = q__3.r * x[i__3].r - q__3.i * x[i__3].i, q__2.i =\n\t\t\t     q__3.r * x[i__3].i + q__3.i * x[i__3].r;\n\t\t    q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i;\n\t\t    temp2.r = q__1.r, temp2.i = q__1.i;\n\t\t    ++k;\n/* L50: */\n\t\t}\n\t\ti__2 = j;\n\t\ti__3 = j;\n\t\ti__4 = kk + j - 1;\n\t\tr__1 = ap[i__4].r;\n\t\tq__3.r = r__1 * temp1.r, q__3.i = r__1 * temp1.i;\n\t\tq__2.r = y[i__3].r + q__3.r, q__2.i = y[i__3].i + q__3.i;\n\t\tq__4.r = alpha->r * temp2.r - alpha->i * temp2.i, q__4.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tq__1.r = q__2.r + q__4.r, q__1.i = q__2.i + q__4.i;\n\t\ty[i__2].r = q__1.r, y[i__2].i = q__1.i;\n\t\tkk += j;\n/* L60: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__2 = jx;\n\t\tq__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, q__1.i =\n\t\t\t alpha->r * x[i__2].i + alpha->i * x[i__2].r;\n\t\ttemp1.r = q__1.r, temp1.i = q__1.i;\n\t\ttemp2.r = 0.f, temp2.i = 0.f;\n\t\tix = kx;\n\t\tiy = ky;\n\t\ti__2 = kk + j - 2;\n\t\tfor (k = kk; k <= i__2; ++k) {\n\t\t    i__3 = iy;\n\t\t    i__4 = iy;\n\t\t    i__5 = k;\n\t\t    q__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, \n\t\t\t    q__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5]\n\t\t\t    .r;\n\t\t    q__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i;\n\t\t    y[i__3].r = q__1.r, y[i__3].i = q__1.i;\n\t\t    r_cnjg(&q__3, &ap[k]);\n\t\t    i__3 = ix;\n\t\t    q__2.r = q__3.r * x[i__3].r - q__3.i * x[i__3].i, q__2.i =\n\t\t\t     q__3.r * x[i__3].i + q__3.i * x[i__3].r;\n\t\t    q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i;\n\t\t    temp2.r = q__1.r, temp2.i = q__1.i;\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n/* L70: */\n\t\t}\n\t\ti__2 = jy;\n\t\ti__3 = jy;\n\t\ti__4 = kk + j - 1;\n\t\tr__1 = ap[i__4].r;\n\t\tq__3.r = r__1 * temp1.r, q__3.i = r__1 * temp1.i;\n\t\tq__2.r = y[i__3].r + q__3.r, q__2.i = y[i__3].i + q__3.i;\n\t\tq__4.r = alpha->r * temp2.r - alpha->i * temp2.i, q__4.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tq__1.r = q__2.r + q__4.r, q__1.i = q__2.i + q__4.i;\n\t\ty[i__2].r = q__1.r, y[i__2].i = q__1.i;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tkk += j;\n/* L80: */\n\t    }\n\t}\n    } else {\n\n/*        Form  y  when AP contains the lower triangle. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__2 = j;\n\t\tq__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, q__1.i =\n\t\t\t alpha->r * x[i__2].i + alpha->i * x[i__2].r;\n\t\ttemp1.r = q__1.r, temp1.i = q__1.i;\n\t\ttemp2.r = 0.f, temp2.i = 0.f;\n\t\ti__2 = j;\n\t\ti__3 = j;\n\t\ti__4 = kk;\n\t\tr__1 = ap[i__4].r;\n\t\tq__2.r = r__1 * temp1.r, q__2.i = r__1 * temp1.i;\n\t\tq__1.r = y[i__3].r + q__2.r, q__1.i = y[i__3].i + q__2.i;\n\t\ty[i__2].r = q__1.r, y[i__2].i = q__1.i;\n\t\tk = kk + 1;\n\t\ti__2 = *n;\n\t\tfor (i__ = j + 1; i__ <= i__2; ++i__) {\n\t\t    i__3 = i__;\n\t\t    i__4 = i__;\n\t\t    i__5 = k;\n\t\t    q__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, \n\t\t\t    q__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5]\n\t\t\t    .r;\n\t\t    q__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i;\n\t\t    y[i__3].r = q__1.r, y[i__3].i = q__1.i;\n\t\t    r_cnjg(&q__3, &ap[k]);\n\t\t    i__3 = i__;\n\t\t    q__2.r = q__3.r * x[i__3].r - q__3.i * x[i__3].i, q__2.i =\n\t\t\t     q__3.r * x[i__3].i + q__3.i * x[i__3].r;\n\t\t    q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i;\n\t\t    temp2.r = q__1.r, temp2.i = q__1.i;\n\t\t    ++k;\n/* L90: */\n\t\t}\n\t\ti__2 = j;\n\t\ti__3 = j;\n\t\tq__2.r = alpha->r * temp2.r - alpha->i * temp2.i, q__2.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tq__1.r = y[i__3].r + q__2.r, q__1.i = y[i__3].i + q__2.i;\n\t\ty[i__2].r = q__1.r, y[i__2].i = q__1.i;\n\t\tkk += *n - j + 1;\n/* L100: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__2 = jx;\n\t\tq__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, q__1.i =\n\t\t\t alpha->r * x[i__2].i + alpha->i * x[i__2].r;\n\t\ttemp1.r = q__1.r, temp1.i = q__1.i;\n\t\ttemp2.r = 0.f, temp2.i = 0.f;\n\t\ti__2 = jy;\n\t\ti__3 = jy;\n\t\ti__4 = kk;\n\t\tr__1 = ap[i__4].r;\n\t\tq__2.r = r__1 * temp1.r, q__2.i = r__1 * temp1.i;\n\t\tq__1.r = y[i__3].r + q__2.r, q__1.i = y[i__3].i + q__2.i;\n\t\ty[i__2].r = q__1.r, y[i__2].i = q__1.i;\n\t\tix = jx;\n\t\tiy = jy;\n\t\ti__2 = kk + *n - j;\n\t\tfor (k = kk + 1; k <= i__2; ++k) {\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n\t\t    i__3 = iy;\n\t\t    i__4 = iy;\n\t\t    i__5 = k;\n\t\t    q__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, \n\t\t\t    q__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5]\n\t\t\t    .r;\n\t\t    q__1.r = y[i__4].r + q__2.r, q__1.i = y[i__4].i + q__2.i;\n\t\t    y[i__3].r = q__1.r, y[i__3].i = q__1.i;\n\t\t    r_cnjg(&q__3, &ap[k]);\n\t\t    i__3 = ix;\n\t\t    q__2.r = q__3.r * x[i__3].r - q__3.i * x[i__3].i, q__2.i =\n\t\t\t     q__3.r * x[i__3].i + q__3.i * x[i__3].r;\n\t\t    q__1.r = temp2.r + q__2.r, q__1.i = temp2.i + q__2.i;\n\t\t    temp2.r = q__1.r, temp2.i = q__1.i;\n/* L110: */\n\t\t}\n\t\ti__2 = jy;\n\t\ti__3 = jy;\n\t\tq__2.r = alpha->r * temp2.r - alpha->i * temp2.i, q__2.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tq__1.r = y[i__3].r + q__2.r, q__1.i = y[i__3].i + q__2.i;\n\t\ty[i__2].r = q__1.r, y[i__2].i = q__1.i;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tkk += *n - j + 1;\n/* L120: */\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of CHPMV . */\n\n} /* chpmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/complexdots.c",
    "content": "/* This file has been modified to use the standard gfortran calling\n   convention, rather than the f2c calling convention.\n\n   It does not require -ff2c when compiled with gfortran.\n*/\n\n/* complexdots.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\ncomplex cdotc_(integer *n, complex *cx, integer \n\t*incx, complex *cy, integer *incy)\n{\n    complex res;\n    extern /* Subroutine */ int cdotcw_(integer *, complex *, integer *, \n\t    complex *, integer *, complex *);\n\n    /* Parameter adjustments */\n    --cy;\n    --cx;\n\n    /* Function Body */\n    cdotcw_(n, &cx[1], incx, &cy[1], incy, &res);\n    return res;\n} /* cdotc_ */\n\ncomplex cdotu_(integer *n, complex *cx, integer \n\t*incx, complex *cy, integer *incy)\n{\n    complex res;\n    extern /* Subroutine */ int cdotuw_(integer *, complex *, integer *, \n\t    complex *, integer *, complex *);\n\n    /* Parameter adjustments */\n    --cy;\n    --cx;\n\n    /* Function Body */\n    cdotuw_(n, &cx[1], incx, &cy[1], incy, &res);\n    return res;\n} /* cdotu_ */\n\ndoublecomplex zdotc_(integer *n, doublecomplex *cx, integer *incx, \n                     doublecomplex *cy, integer *incy)\n{\n    doublecomplex res;\n    extern /* Subroutine */ int zdotcw_(integer *, doublecomplex *, integer *,\n\t     doublecomplex *, integer *, doublecomplex *);\n\n    /* Parameter adjustments */\n    --cy;\n    --cx;\n\n    /* Function Body */\n    zdotcw_(n, &cx[1], incx, &cy[1], incy, &res);\n    return res;\n} /* zdotc_ */\n\ndoublecomplex zdotu_(integer *n, doublecomplex *cx, integer *incx, \n                     doublecomplex *cy, integer *incy)\n{\n    doublecomplex res;\n    extern /* Subroutine */ int zdotuw_(integer *, doublecomplex *, integer *,\n\t     doublecomplex *, integer *, doublecomplex *);\n\n    /* Parameter adjustments */\n    --cy;\n    --cx;\n\n    /* Function Body */\n    zdotuw_(n, &cx[1], incx, &cy[1], incy, &res);\n    return res;\n} /* zdotu_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/ctbmv.c",
    "content": "/* ctbmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int ctbmv_(char *uplo, char *trans, char *diag, integer *n, \n\tinteger *k, complex *a, integer *lda, complex *x, integer *incx, \n\tftnlen uplo_len, ftnlen trans_len, ftnlen diag_len)\n{\n    /* System generated locals */\n    integer a_dim1, a_offset, i__1, i__2, i__3, i__4, i__5;\n    complex q__1, q__2, q__3;\n\n    /* Builtin functions */\n    void r_cnjg(complex *, complex *);\n\n    /* Local variables */\n    integer i__, j, l, ix, jx, kx, info;\n    complex temp;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    integer kplus1;\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n    logical noconj, nounit;\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  CTBMV  performs one of the matrix-vector operations */\n\n/*     x := A*x,   or   x := A'*x,   or   x := conjg( A' )*x, */\n\n/*  where x is an n element vector and  A is an n by n unit, or non-unit, */\n/*  upper or lower triangular band matrix, with ( k + 1 ) diagonals. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the matrix is an upper or */\n/*           lower triangular matrix as follows: */\n\n/*              UPLO = 'U' or 'u'   A is an upper triangular matrix. */\n\n/*              UPLO = 'L' or 'l'   A is a lower triangular matrix. */\n\n/*           Unchanged on exit. */\n\n/*  TRANS  - CHARACTER*1. */\n/*           On entry, TRANS specifies the operation to be performed as */\n/*           follows: */\n\n/*              TRANS = 'N' or 'n'   x := A*x. */\n\n/*              TRANS = 'T' or 't'   x := A'*x. */\n\n/*              TRANS = 'C' or 'c'   x := conjg( A' )*x. */\n\n/*           Unchanged on exit. */\n\n/*  DIAG   - CHARACTER*1. */\n/*           On entry, DIAG specifies whether or not A is unit */\n/*           triangular as follows: */\n\n/*              DIAG = 'U' or 'u'   A is assumed to be unit triangular. */\n\n/*              DIAG = 'N' or 'n'   A is not assumed to be unit */\n/*                                  triangular. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  K      - INTEGER. */\n/*           On entry with UPLO = 'U' or 'u', K specifies the number of */\n/*           super-diagonals of the matrix A. */\n/*           On entry with UPLO = 'L' or 'l', K specifies the number of */\n/*           sub-diagonals of the matrix A. */\n/*           K must satisfy  0 .le. K. */\n/*           Unchanged on exit. */\n\n/*  A      - COMPLEX          array of DIMENSION ( LDA, n ). */\n/*           Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the upper triangular */\n/*           band part of the matrix of coefficients, supplied column by */\n/*           column, with the leading diagonal of the matrix in row */\n/*           ( k + 1 ) of the array, the first super-diagonal starting at */\n/*           position 2 in row k, and so on. The top left k by k triangle */\n/*           of the array A is not referenced. */\n/*           The following program segment will transfer an upper */\n/*           triangular band matrix from conventional full matrix storage */\n/*           to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = K + 1 - J */\n/*                    DO 10, I = MAX( 1, J - K ), J */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the lower triangular */\n/*           band part of the matrix of coefficients, supplied column by */\n/*           column, with the leading diagonal of the matrix in row 1 of */\n/*           the array, the first sub-diagonal starting at position 1 in */\n/*           row 2, and so on. The bottom right k by k triangle of the */\n/*           array A is not referenced. */\n/*           The following program segment will transfer a lower */\n/*           triangular band matrix from conventional full matrix storage */\n/*           to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = 1 - J */\n/*                    DO 10, I = J, MIN( N, J + K ) */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Note that when DIAG = 'U' or 'u' the elements of the array A */\n/*           corresponding to the diagonal elements of the matrix are not */\n/*           referenced, but are assumed to be unity. */\n/*           Unchanged on exit. */\n\n/*  LDA    - INTEGER. */\n/*           On entry, LDA specifies the first dimension of A as declared */\n/*           in the calling (sub) program. LDA must be at least */\n/*           ( k + 1 ). */\n/*           Unchanged on exit. */\n\n/*  X      - COMPLEX          array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the n */\n/*           element vector x. On exit, X is overwritten with the */\n/*           transformed vector x. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    a_dim1 = *lda;\n    a_offset = 1 + a_dim1;\n    a -= a_offset;\n    --x;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (! lsame_(trans, \"N\", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, \n\t    \"T\", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, \"C\", (ftnlen)1, (\n\t    ftnlen)1)) {\n\tinfo = 2;\n    } else if (! lsame_(diag, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(diag, \n\t    \"N\", (ftnlen)1, (ftnlen)1)) {\n\tinfo = 3;\n    } else if (*n < 0) {\n\tinfo = 4;\n    } else if (*k < 0) {\n\tinfo = 5;\n    } else if (*lda < *k + 1) {\n\tinfo = 7;\n    } else if (*incx == 0) {\n\tinfo = 9;\n    }\n    if (info != 0) {\n\txerbla_(\"CTBMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0) {\n\treturn 0;\n    }\n\n    noconj = lsame_(trans, \"T\", (ftnlen)1, (ftnlen)1);\n    nounit = lsame_(diag, \"N\", (ftnlen)1, (ftnlen)1);\n\n/*     Set up the start point in X if the increment is not unity. This */\n/*     will be  ( N - 1 )*INCX   too small for descending loops. */\n\n    if (*incx <= 0) {\n\tkx = 1 - (*n - 1) * *incx;\n    } else if (*incx != 1) {\n\tkx = 1;\n    }\n\n/*     Start the operations. In this version the elements of A are */\n/*     accessed sequentially with one pass through A. */\n\n    if (lsame_(trans, \"N\", (ftnlen)1, (ftnlen)1)) {\n\n/*         Form  x := A*x. */\n\n\tif (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\t    kplus1 = *k + 1;\n\t    if (*incx == 1) {\n\t\ti__1 = *n;\n\t\tfor (j = 1; j <= i__1; ++j) {\n\t\t    i__2 = j;\n\t\t    if (x[i__2].r != 0.f || x[i__2].i != 0.f) {\n\t\t\ti__2 = j;\n\t\t\ttemp.r = x[i__2].r, temp.i = x[i__2].i;\n\t\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\t\ti__2 = 1, i__3 = j - *k;\n\t\t\ti__4 = j - 1;\n\t\t\tfor (i__ = max(i__2,i__3); i__ <= i__4; ++i__) {\n\t\t\t    i__2 = i__;\n\t\t\t    i__3 = i__;\n\t\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t\t    q__2.r = temp.r * a[i__5].r - temp.i * a[i__5].i, \n\t\t\t\t    q__2.i = temp.r * a[i__5].i + temp.i * a[\n\t\t\t\t    i__5].r;\n\t\t\t    q__1.r = x[i__3].r + q__2.r, q__1.i = x[i__3].i + \n\t\t\t\t    q__2.i;\n\t\t\t    x[i__2].r = q__1.r, x[i__2].i = q__1.i;\n/* L10: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    i__4 = j;\n\t\t\t    i__2 = j;\n\t\t\t    i__3 = kplus1 + j * a_dim1;\n\t\t\t    q__1.r = x[i__2].r * a[i__3].r - x[i__2].i * a[\n\t\t\t\t    i__3].i, q__1.i = x[i__2].r * a[i__3].i + \n\t\t\t\t    x[i__2].i * a[i__3].r;\n\t\t\t    x[i__4].r = q__1.r, x[i__4].i = q__1.i;\n\t\t\t}\n\t\t    }\n/* L20: */\n\t\t}\n\t    } else {\n\t\tjx = kx;\n\t\ti__1 = *n;\n\t\tfor (j = 1; j <= i__1; ++j) {\n\t\t    i__4 = jx;\n\t\t    if (x[i__4].r != 0.f || x[i__4].i != 0.f) {\n\t\t\ti__4 = jx;\n\t\t\ttemp.r = x[i__4].r, temp.i = x[i__4].i;\n\t\t\tix = kx;\n\t\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\t\ti__4 = 1, i__2 = j - *k;\n\t\t\ti__3 = j - 1;\n\t\t\tfor (i__ = max(i__4,i__2); i__ <= i__3; ++i__) {\n\t\t\t    i__4 = ix;\n\t\t\t    i__2 = ix;\n\t\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t\t    q__2.r = temp.r * a[i__5].r - temp.i * a[i__5].i, \n\t\t\t\t    q__2.i = temp.r * a[i__5].i + temp.i * a[\n\t\t\t\t    i__5].r;\n\t\t\t    q__1.r = x[i__2].r + q__2.r, q__1.i = x[i__2].i + \n\t\t\t\t    q__2.i;\n\t\t\t    x[i__4].r = q__1.r, x[i__4].i = q__1.i;\n\t\t\t    ix += *incx;\n/* L30: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    i__3 = jx;\n\t\t\t    i__4 = jx;\n\t\t\t    i__2 = kplus1 + j * a_dim1;\n\t\t\t    q__1.r = x[i__4].r * a[i__2].r - x[i__4].i * a[\n\t\t\t\t    i__2].i, q__1.i = x[i__4].r * a[i__2].i + \n\t\t\t\t    x[i__4].i * a[i__2].r;\n\t\t\t    x[i__3].r = q__1.r, x[i__3].i = q__1.i;\n\t\t\t}\n\t\t    }\n\t\t    jx += *incx;\n\t\t    if (j > *k) {\n\t\t\tkx += *incx;\n\t\t    }\n/* L40: */\n\t\t}\n\t    }\n\t} else {\n\t    if (*incx == 1) {\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    i__1 = j;\n\t\t    if (x[i__1].r != 0.f || x[i__1].i != 0.f) {\n\t\t\ti__1 = j;\n\t\t\ttemp.r = x[i__1].r, temp.i = x[i__1].i;\n\t\t\tl = 1 - j;\n/* Computing MIN */\n\t\t\ti__1 = *n, i__3 = j + *k;\n\t\t\ti__4 = j + 1;\n\t\t\tfor (i__ = min(i__1,i__3); i__ >= i__4; --i__) {\n\t\t\t    i__1 = i__;\n\t\t\t    i__3 = i__;\n\t\t\t    i__2 = l + i__ + j * a_dim1;\n\t\t\t    q__2.r = temp.r * a[i__2].r - temp.i * a[i__2].i, \n\t\t\t\t    q__2.i = temp.r * a[i__2].i + temp.i * a[\n\t\t\t\t    i__2].r;\n\t\t\t    q__1.r = x[i__3].r + q__2.r, q__1.i = x[i__3].i + \n\t\t\t\t    q__2.i;\n\t\t\t    x[i__1].r = q__1.r, x[i__1].i = q__1.i;\n/* L50: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    i__4 = j;\n\t\t\t    i__1 = j;\n\t\t\t    i__3 = j * a_dim1 + 1;\n\t\t\t    q__1.r = x[i__1].r * a[i__3].r - x[i__1].i * a[\n\t\t\t\t    i__3].i, q__1.i = x[i__1].r * a[i__3].i + \n\t\t\t\t    x[i__1].i * a[i__3].r;\n\t\t\t    x[i__4].r = q__1.r, x[i__4].i = q__1.i;\n\t\t\t}\n\t\t    }\n/* L60: */\n\t\t}\n\t    } else {\n\t\tkx += (*n - 1) * *incx;\n\t\tjx = kx;\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    i__4 = jx;\n\t\t    if (x[i__4].r != 0.f || x[i__4].i != 0.f) {\n\t\t\ti__4 = jx;\n\t\t\ttemp.r = x[i__4].r, temp.i = x[i__4].i;\n\t\t\tix = kx;\n\t\t\tl = 1 - j;\n/* Computing MIN */\n\t\t\ti__4 = *n, i__1 = j + *k;\n\t\t\ti__3 = j + 1;\n\t\t\tfor (i__ = min(i__4,i__1); i__ >= i__3; --i__) {\n\t\t\t    i__4 = ix;\n\t\t\t    i__1 = ix;\n\t\t\t    i__2 = l + i__ + j * a_dim1;\n\t\t\t    q__2.r = temp.r * a[i__2].r - temp.i * a[i__2].i, \n\t\t\t\t    q__2.i = temp.r * a[i__2].i + temp.i * a[\n\t\t\t\t    i__2].r;\n\t\t\t    q__1.r = x[i__1].r + q__2.r, q__1.i = x[i__1].i + \n\t\t\t\t    q__2.i;\n\t\t\t    x[i__4].r = q__1.r, x[i__4].i = q__1.i;\n\t\t\t    ix -= *incx;\n/* L70: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    i__3 = jx;\n\t\t\t    i__4 = jx;\n\t\t\t    i__1 = j * a_dim1 + 1;\n\t\t\t    q__1.r = x[i__4].r * a[i__1].r - x[i__4].i * a[\n\t\t\t\t    i__1].i, q__1.i = x[i__4].r * a[i__1].i + \n\t\t\t\t    x[i__4].i * a[i__1].r;\n\t\t\t    x[i__3].r = q__1.r, x[i__3].i = q__1.i;\n\t\t\t}\n\t\t    }\n\t\t    jx -= *incx;\n\t\t    if (*n - j >= *k) {\n\t\t\tkx -= *incx;\n\t\t    }\n/* L80: */\n\t\t}\n\t    }\n\t}\n    } else {\n\n/*        Form  x := A'*x  or  x := conjg( A' )*x. */\n\n\tif (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\t    kplus1 = *k + 1;\n\t    if (*incx == 1) {\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    i__3 = j;\n\t\t    temp.r = x[i__3].r, temp.i = x[i__3].i;\n\t\t    l = kplus1 - j;\n\t\t    if (noconj) {\n\t\t\tif (nounit) {\n\t\t\t    i__3 = kplus1 + j * a_dim1;\n\t\t\t    q__1.r = temp.r * a[i__3].r - temp.i * a[i__3].i, \n\t\t\t\t    q__1.i = temp.r * a[i__3].i + temp.i * a[\n\t\t\t\t    i__3].r;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t}\n/* Computing MAX */\n\t\t\ti__4 = 1, i__1 = j - *k;\n\t\t\ti__3 = max(i__4,i__1);\n\t\t\tfor (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\t    i__4 = l + i__ + j * a_dim1;\n\t\t\t    i__1 = i__;\n\t\t\t    q__2.r = a[i__4].r * x[i__1].r - a[i__4].i * x[\n\t\t\t\t    i__1].i, q__2.i = a[i__4].r * x[i__1].i + \n\t\t\t\t    a[i__4].i * x[i__1].r;\n\t\t\t    q__1.r = temp.r + q__2.r, q__1.i = temp.i + \n\t\t\t\t    q__2.i;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n/* L90: */\n\t\t\t}\n\t\t    } else {\n\t\t\tif (nounit) {\n\t\t\t    r_cnjg(&q__2, &a[kplus1 + j * a_dim1]);\n\t\t\t    q__1.r = temp.r * q__2.r - temp.i * q__2.i, \n\t\t\t\t    q__1.i = temp.r * q__2.i + temp.i * \n\t\t\t\t    q__2.r;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t}\n/* Computing MAX */\n\t\t\ti__4 = 1, i__1 = j - *k;\n\t\t\ti__3 = max(i__4,i__1);\n\t\t\tfor (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\t    r_cnjg(&q__3, &a[l + i__ + j * a_dim1]);\n\t\t\t    i__4 = i__;\n\t\t\t    q__2.r = q__3.r * x[i__4].r - q__3.i * x[i__4].i, \n\t\t\t\t    q__2.i = q__3.r * x[i__4].i + q__3.i * x[\n\t\t\t\t    i__4].r;\n\t\t\t    q__1.r = temp.r + q__2.r, q__1.i = temp.i + \n\t\t\t\t    q__2.i;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n/* L100: */\n\t\t\t}\n\t\t    }\n\t\t    i__3 = j;\n\t\t    x[i__3].r = temp.r, x[i__3].i = temp.i;\n/* L110: */\n\t\t}\n\t    } else {\n\t\tkx += (*n - 1) * *incx;\n\t\tjx = kx;\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    i__3 = jx;\n\t\t    temp.r = x[i__3].r, temp.i = x[i__3].i;\n\t\t    kx -= *incx;\n\t\t    ix = kx;\n\t\t    l = kplus1 - j;\n\t\t    if (noconj) {\n\t\t\tif (nounit) {\n\t\t\t    i__3 = kplus1 + j * a_dim1;\n\t\t\t    q__1.r = temp.r * a[i__3].r - temp.i * a[i__3].i, \n\t\t\t\t    q__1.i = temp.r * a[i__3].i + temp.i * a[\n\t\t\t\t    i__3].r;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t}\n/* Computing MAX */\n\t\t\ti__4 = 1, i__1 = j - *k;\n\t\t\ti__3 = max(i__4,i__1);\n\t\t\tfor (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\t    i__4 = l + i__ + j * a_dim1;\n\t\t\t    i__1 = ix;\n\t\t\t    q__2.r = a[i__4].r * x[i__1].r - a[i__4].i * x[\n\t\t\t\t    i__1].i, q__2.i = a[i__4].r * x[i__1].i + \n\t\t\t\t    a[i__4].i * x[i__1].r;\n\t\t\t    q__1.r = temp.r + q__2.r, q__1.i = temp.i + \n\t\t\t\t    q__2.i;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t    ix -= *incx;\n/* L120: */\n\t\t\t}\n\t\t    } else {\n\t\t\tif (nounit) {\n\t\t\t    r_cnjg(&q__2, &a[kplus1 + j * a_dim1]);\n\t\t\t    q__1.r = temp.r * q__2.r - temp.i * q__2.i, \n\t\t\t\t    q__1.i = temp.r * q__2.i + temp.i * \n\t\t\t\t    q__2.r;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t}\n/* Computing MAX */\n\t\t\ti__4 = 1, i__1 = j - *k;\n\t\t\ti__3 = max(i__4,i__1);\n\t\t\tfor (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\t    r_cnjg(&q__3, &a[l + i__ + j * a_dim1]);\n\t\t\t    i__4 = ix;\n\t\t\t    q__2.r = q__3.r * x[i__4].r - q__3.i * x[i__4].i, \n\t\t\t\t    q__2.i = q__3.r * x[i__4].i + q__3.i * x[\n\t\t\t\t    i__4].r;\n\t\t\t    q__1.r = temp.r + q__2.r, q__1.i = temp.i + \n\t\t\t\t    q__2.i;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t    ix -= *incx;\n/* L130: */\n\t\t\t}\n\t\t    }\n\t\t    i__3 = jx;\n\t\t    x[i__3].r = temp.r, x[i__3].i = temp.i;\n\t\t    jx -= *incx;\n/* L140: */\n\t\t}\n\t    }\n\t} else {\n\t    if (*incx == 1) {\n\t\ti__3 = *n;\n\t\tfor (j = 1; j <= i__3; ++j) {\n\t\t    i__4 = j;\n\t\t    temp.r = x[i__4].r, temp.i = x[i__4].i;\n\t\t    l = 1 - j;\n\t\t    if (noconj) {\n\t\t\tif (nounit) {\n\t\t\t    i__4 = j * a_dim1 + 1;\n\t\t\t    q__1.r = temp.r * a[i__4].r - temp.i * a[i__4].i, \n\t\t\t\t    q__1.i = temp.r * a[i__4].i + temp.i * a[\n\t\t\t\t    i__4].r;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t}\n/* Computing MIN */\n\t\t\ti__1 = *n, i__2 = j + *k;\n\t\t\ti__4 = min(i__1,i__2);\n\t\t\tfor (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\t    i__1 = l + i__ + j * a_dim1;\n\t\t\t    i__2 = i__;\n\t\t\t    q__2.r = a[i__1].r * x[i__2].r - a[i__1].i * x[\n\t\t\t\t    i__2].i, q__2.i = a[i__1].r * x[i__2].i + \n\t\t\t\t    a[i__1].i * x[i__2].r;\n\t\t\t    q__1.r = temp.r + q__2.r, q__1.i = temp.i + \n\t\t\t\t    q__2.i;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n/* L150: */\n\t\t\t}\n\t\t    } else {\n\t\t\tif (nounit) {\n\t\t\t    r_cnjg(&q__2, &a[j * a_dim1 + 1]);\n\t\t\t    q__1.r = temp.r * q__2.r - temp.i * q__2.i, \n\t\t\t\t    q__1.i = temp.r * q__2.i + temp.i * \n\t\t\t\t    q__2.r;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t}\n/* Computing MIN */\n\t\t\ti__1 = *n, i__2 = j + *k;\n\t\t\ti__4 = min(i__1,i__2);\n\t\t\tfor (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\t    r_cnjg(&q__3, &a[l + i__ + j * a_dim1]);\n\t\t\t    i__1 = i__;\n\t\t\t    q__2.r = q__3.r * x[i__1].r - q__3.i * x[i__1].i, \n\t\t\t\t    q__2.i = q__3.r * x[i__1].i + q__3.i * x[\n\t\t\t\t    i__1].r;\n\t\t\t    q__1.r = temp.r + q__2.r, q__1.i = temp.i + \n\t\t\t\t    q__2.i;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n/* L160: */\n\t\t\t}\n\t\t    }\n\t\t    i__4 = j;\n\t\t    x[i__4].r = temp.r, x[i__4].i = temp.i;\n/* L170: */\n\t\t}\n\t    } else {\n\t\tjx = kx;\n\t\ti__3 = *n;\n\t\tfor (j = 1; j <= i__3; ++j) {\n\t\t    i__4 = jx;\n\t\t    temp.r = x[i__4].r, temp.i = x[i__4].i;\n\t\t    kx += *incx;\n\t\t    ix = kx;\n\t\t    l = 1 - j;\n\t\t    if (noconj) {\n\t\t\tif (nounit) {\n\t\t\t    i__4 = j * a_dim1 + 1;\n\t\t\t    q__1.r = temp.r * a[i__4].r - temp.i * a[i__4].i, \n\t\t\t\t    q__1.i = temp.r * a[i__4].i + temp.i * a[\n\t\t\t\t    i__4].r;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t}\n/* Computing MIN */\n\t\t\ti__1 = *n, i__2 = j + *k;\n\t\t\ti__4 = min(i__1,i__2);\n\t\t\tfor (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\t    i__1 = l + i__ + j * a_dim1;\n\t\t\t    i__2 = ix;\n\t\t\t    q__2.r = a[i__1].r * x[i__2].r - a[i__1].i * x[\n\t\t\t\t    i__2].i, q__2.i = a[i__1].r * x[i__2].i + \n\t\t\t\t    a[i__1].i * x[i__2].r;\n\t\t\t    q__1.r = temp.r + q__2.r, q__1.i = temp.i + \n\t\t\t\t    q__2.i;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t    ix += *incx;\n/* L180: */\n\t\t\t}\n\t\t    } else {\n\t\t\tif (nounit) {\n\t\t\t    r_cnjg(&q__2, &a[j * a_dim1 + 1]);\n\t\t\t    q__1.r = temp.r * q__2.r - temp.i * q__2.i, \n\t\t\t\t    q__1.i = temp.r * q__2.i + temp.i * \n\t\t\t\t    q__2.r;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t}\n/* Computing MIN */\n\t\t\ti__1 = *n, i__2 = j + *k;\n\t\t\ti__4 = min(i__1,i__2);\n\t\t\tfor (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\t    r_cnjg(&q__3, &a[l + i__ + j * a_dim1]);\n\t\t\t    i__1 = ix;\n\t\t\t    q__2.r = q__3.r * x[i__1].r - q__3.i * x[i__1].i, \n\t\t\t\t    q__2.i = q__3.r * x[i__1].i + q__3.i * x[\n\t\t\t\t    i__1].r;\n\t\t\t    q__1.r = temp.r + q__2.r, q__1.i = temp.i + \n\t\t\t\t    q__2.i;\n\t\t\t    temp.r = q__1.r, temp.i = q__1.i;\n\t\t\t    ix += *incx;\n/* L190: */\n\t\t\t}\n\t\t    }\n\t\t    i__4 = jx;\n\t\t    x[i__4].r = temp.r, x[i__4].i = temp.i;\n\t\t    jx += *incx;\n/* L200: */\n\t\t}\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of CTBMV . */\n\n} /* ctbmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/d_cnjg.c",
    "content": "#include \"datatypes.h\"    \n\nvoid d_cnjg(doublecomplex *r, doublecomplex *z) {\n    r->r = z->r;\n    r->i = -(z->i);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/datatypes.h",
    "content": "/* This contains a limited subset of the typedefs exposed by f2c\n   for use by the Eigen BLAS C-only implementation.\n*/\n\n#ifndef __EIGEN_DATATYPES_H__\n#define __EIGEN_DATATYPES_H__\n\ntypedef int integer;\ntypedef unsigned int uinteger;\ntypedef float real;\ntypedef double doublereal;\ntypedef struct { real r, i; } complex;\ntypedef struct { doublereal r, i; } doublecomplex;\ntypedef int ftnlen;\ntypedef int logical;\n\n#define abs(x) ((x) >= 0 ? (x) : -(x))\n#define dabs(x) (doublereal)abs(x)\n#define min(a,b) ((a) <= (b) ? (a) : (b))\n#define max(a,b) ((a) >= (b) ? (a) : (b))\n#define dmin(a,b) (doublereal)min(a,b)\n#define dmax(a,b) (doublereal)max(a,b)\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/drotm.c",
    "content": "/* drotm.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int drotm_(integer *n, doublereal *dx, integer *incx, \n\tdoublereal *dy, integer *incy, doublereal *dparam)\n{\n    /* Initialized data */\n\n    static doublereal zero = 0.;\n    static doublereal two = 2.;\n\n    /* System generated locals */\n    integer i__1, i__2;\n\n    /* Local variables */\n    integer i__;\n    doublereal w, z__;\n    integer kx, ky;\n    doublereal dh11, dh12, dh21, dh22, dflag;\n    integer nsteps;\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*     APPLY THE MODIFIED GIVENS TRANSFORMATION, H, TO THE 2 BY N MATRIX */\n\n/*     (DX**T) , WHERE **T INDICATES TRANSPOSE. THE ELEMENTS OF DX ARE IN */\n/*     (DY**T) */\n\n/*     DX(LX+I*INCX), I = 0 TO N-1, WHERE LX = 1 IF INCX .GE. 0, ELSE */\n/*     LX = (-INCX)*N, AND SIMILARLY FOR SY USING LY AND INCY. */\n/*     WITH DPARAM(1)=DFLAG, H HAS ONE OF THE FOLLOWING FORMS.. */\n\n/*     DFLAG=-1.D0     DFLAG=0.D0        DFLAG=1.D0     DFLAG=-2.D0 */\n\n/*       (DH11  DH12)    (1.D0  DH12)    (DH11  1.D0)    (1.D0  0.D0) */\n/*     H=(          )    (          )    (          )    (          ) */\n/*       (DH21  DH22),   (DH21  1.D0),   (-1.D0 DH22),   (0.D0  1.D0). */\n/*     SEE DROTMG FOR A DESCRIPTION OF DATA STORAGE IN DPARAM. */\n\n/*  Arguments */\n/*  ========= */\n\n/*  N      (input) INTEGER */\n/*         number of elements in input vector(s) */\n\n/*  DX     (input/output) DOUBLE PRECISION array, dimension N */\n/*         double precision vector with N elements */\n\n/*  INCX   (input) INTEGER */\n/*         storage spacing between elements of DX */\n\n/*  DY     (input/output) DOUBLE PRECISION array, dimension N */\n/*         double precision vector with N elements */\n\n/*  INCY   (input) INTEGER */\n/*         storage spacing between elements of DY */\n\n/*  DPARAM (input/output)  DOUBLE PRECISION array, dimension 5 */\n/*     DPARAM(1)=DFLAG */\n/*     DPARAM(2)=DH11 */\n/*     DPARAM(3)=DH21 */\n/*     DPARAM(4)=DH12 */\n/*     DPARAM(5)=DH22 */\n\n/*  ===================================================================== */\n\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. Data statements .. */\n    /* Parameter adjustments */\n    --dparam;\n    --dy;\n    --dx;\n\n    /* Function Body */\n/*     .. */\n\n    dflag = dparam[1];\n    if (*n <= 0 || dflag + two == zero) {\n\tgoto L140;\n    }\n    if (! (*incx == *incy && *incx > 0)) {\n\tgoto L70;\n    }\n\n    nsteps = *n * *incx;\n    if (dflag < 0.) {\n\tgoto L50;\n    } else if (dflag == 0) {\n\tgoto L10;\n    } else {\n\tgoto L30;\n    }\nL10:\n    dh12 = dparam[4];\n    dh21 = dparam[3];\n    i__1 = nsteps;\n    i__2 = *incx;\n    for (i__ = 1; i__2 < 0 ? i__ >= i__1 : i__ <= i__1; i__ += i__2) {\n\tw = dx[i__];\n\tz__ = dy[i__];\n\tdx[i__] = w + z__ * dh12;\n\tdy[i__] = w * dh21 + z__;\n/* L20: */\n    }\n    goto L140;\nL30:\n    dh11 = dparam[2];\n    dh22 = dparam[5];\n    i__2 = nsteps;\n    i__1 = *incx;\n    for (i__ = 1; i__1 < 0 ? i__ >= i__2 : i__ <= i__2; i__ += i__1) {\n\tw = dx[i__];\n\tz__ = dy[i__];\n\tdx[i__] = w * dh11 + z__;\n\tdy[i__] = -w + dh22 * z__;\n/* L40: */\n    }\n    goto L140;\nL50:\n    dh11 = dparam[2];\n    dh12 = dparam[4];\n    dh21 = dparam[3];\n    dh22 = dparam[5];\n    i__1 = nsteps;\n    i__2 = *incx;\n    for (i__ = 1; i__2 < 0 ? i__ >= i__1 : i__ <= i__1; i__ += i__2) {\n\tw = dx[i__];\n\tz__ = dy[i__];\n\tdx[i__] = w * dh11 + z__ * dh12;\n\tdy[i__] = w * dh21 + z__ * dh22;\n/* L60: */\n    }\n    goto L140;\nL70:\n    kx = 1;\n    ky = 1;\n    if (*incx < 0) {\n\tkx = (1 - *n) * *incx + 1;\n    }\n    if (*incy < 0) {\n\tky = (1 - *n) * *incy + 1;\n    }\n\n    if (dflag < 0.) {\n\tgoto L120;\n    } else if (dflag == 0) {\n\tgoto L80;\n    } else {\n\tgoto L100;\n    }\nL80:\n    dh12 = dparam[4];\n    dh21 = dparam[3];\n    i__2 = *n;\n    for (i__ = 1; i__ <= i__2; ++i__) {\n\tw = dx[kx];\n\tz__ = dy[ky];\n\tdx[kx] = w + z__ * dh12;\n\tdy[ky] = w * dh21 + z__;\n\tkx += *incx;\n\tky += *incy;\n/* L90: */\n    }\n    goto L140;\nL100:\n    dh11 = dparam[2];\n    dh22 = dparam[5];\n    i__2 = *n;\n    for (i__ = 1; i__ <= i__2; ++i__) {\n\tw = dx[kx];\n\tz__ = dy[ky];\n\tdx[kx] = w * dh11 + z__;\n\tdy[ky] = -w + dh22 * z__;\n\tkx += *incx;\n\tky += *incy;\n/* L110: */\n    }\n    goto L140;\nL120:\n    dh11 = dparam[2];\n    dh12 = dparam[4];\n    dh21 = dparam[3];\n    dh22 = dparam[5];\n    i__2 = *n;\n    for (i__ = 1; i__ <= i__2; ++i__) {\n\tw = dx[kx];\n\tz__ = dy[ky];\n\tdx[kx] = w * dh11 + z__ * dh12;\n\tdy[ky] = w * dh21 + z__ * dh22;\n\tkx += *incx;\n\tky += *incy;\n/* L130: */\n    }\nL140:\n    return 0;\n} /* drotm_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/drotmg.c",
    "content": "/* drotmg.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int drotmg_(doublereal *dd1, doublereal *dd2, doublereal *\n\tdx1, doublereal *dy1, doublereal *dparam)\n{\n    /* Initialized data */\n\n    static doublereal zero = 0.;\n    static doublereal one = 1.;\n    static doublereal two = 2.;\n    static doublereal gam = 4096.;\n    static doublereal gamsq = 16777216.;\n    static doublereal rgamsq = 5.9604645e-8;\n\n    /* Format strings */\n    static char fmt_120[] = \"\";\n    static char fmt_150[] = \"\";\n    static char fmt_180[] = \"\";\n    static char fmt_210[] = \"\";\n\n    /* System generated locals */\n    doublereal d__1;\n\n    /* Local variables */\n    doublereal du, dp1, dp2, dq1, dq2, dh11, dh12, dh21, dh22;\n    integer igo;\n    doublereal dflag, dtemp;\n\n    /* Assigned format variables */\n    static char *igo_fmt;\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*     CONSTRUCT THE MODIFIED GIVENS TRANSFORMATION MATRIX H WHICH ZEROS */\n/*     THE SECOND COMPONENT OF THE 2-VECTOR  (DSQRT(DD1)*DX1,DSQRT(DD2)* */\n/*     DY2)**T. */\n/*     WITH DPARAM(1)=DFLAG, H HAS ONE OF THE FOLLOWING FORMS.. */\n\n/*     DFLAG=-1.D0     DFLAG=0.D0        DFLAG=1.D0     DFLAG=-2.D0 */\n\n/*       (DH11  DH12)    (1.D0  DH12)    (DH11  1.D0)    (1.D0  0.D0) */\n/*     H=(          )    (          )    (          )    (          ) */\n/*       (DH21  DH22),   (DH21  1.D0),   (-1.D0 DH22),   (0.D0  1.D0). */\n/*     LOCATIONS 2-4 OF DPARAM CONTAIN DH11, DH21, DH12, AND DH22 */\n/*     RESPECTIVELY. (VALUES OF 1.D0, -1.D0, OR 0.D0 IMPLIED BY THE */\n/*     VALUE OF DPARAM(1) ARE NOT STORED IN DPARAM.) */\n\n/*     THE VALUES OF GAMSQ AND RGAMSQ SET IN THE DATA STATEMENT MAY BE */\n/*     INEXACT.  THIS IS OK AS THEY ARE ONLY USED FOR TESTING THE SIZE */\n/*     OF DD1 AND DD2.  ALL ACTUAL SCALING OF DATA IS DONE USING GAM. */\n\n\n/*  Arguments */\n/*  ========= */\n\n/*  DD1    (input/output) DOUBLE PRECISION */\n\n/*  DD2    (input/output) DOUBLE PRECISION */\n\n/*  DX1    (input/output) DOUBLE PRECISION */\n\n/*  DY1    (input) DOUBLE PRECISION */\n\n/*  DPARAM (input/output)  DOUBLE PRECISION array, dimension 5 */\n/*     DPARAM(1)=DFLAG */\n/*     DPARAM(2)=DH11 */\n/*     DPARAM(3)=DH21 */\n/*     DPARAM(4)=DH12 */\n/*     DPARAM(5)=DH22 */\n\n/*  ===================================================================== */\n\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n/*     .. Data statements .. */\n\n    /* Parameter adjustments */\n    --dparam;\n\n    /* Function Body */\n/*     .. */\n    if (! (*dd1 < zero)) {\n\tgoto L10;\n    }\n/*       GO ZERO-H-D-AND-DX1.. */\n    goto L60;\nL10:\n/*     CASE-DD1-NONNEGATIVE */\n    dp2 = *dd2 * *dy1;\n    if (! (dp2 == zero)) {\n\tgoto L20;\n    }\n    dflag = -two;\n    goto L260;\n/*     REGULAR-CASE.. */\nL20:\n    dp1 = *dd1 * *dx1;\n    dq2 = dp2 * *dy1;\n    dq1 = dp1 * *dx1;\n\n    if (! (abs(dq1) > abs(dq2))) {\n\tgoto L40;\n    }\n    dh21 = -(*dy1) / *dx1;\n    dh12 = dp2 / dp1;\n\n    du = one - dh12 * dh21;\n\n    if (! (du <= zero)) {\n\tgoto L30;\n    }\n/*         GO ZERO-H-D-AND-DX1.. */\n    goto L60;\nL30:\n    dflag = zero;\n    *dd1 /= du;\n    *dd2 /= du;\n    *dx1 *= du;\n/*         GO SCALE-CHECK.. */\n    goto L100;\nL40:\n    if (! (dq2 < zero)) {\n\tgoto L50;\n    }\n/*         GO ZERO-H-D-AND-DX1.. */\n    goto L60;\nL50:\n    dflag = one;\n    dh11 = dp1 / dp2;\n    dh22 = *dx1 / *dy1;\n    du = one + dh11 * dh22;\n    dtemp = *dd2 / du;\n    *dd2 = *dd1 / du;\n    *dd1 = dtemp;\n    *dx1 = *dy1 * du;\n/*         GO SCALE-CHECK */\n    goto L100;\n/*     PROCEDURE..ZERO-H-D-AND-DX1.. */\nL60:\n    dflag = -one;\n    dh11 = zero;\n    dh12 = zero;\n    dh21 = zero;\n    dh22 = zero;\n\n    *dd1 = zero;\n    *dd2 = zero;\n    *dx1 = zero;\n/*         RETURN.. */\n    goto L220;\n/*     PROCEDURE..FIX-H.. */\nL70:\n    if (! (dflag >= zero)) {\n\tgoto L90;\n    }\n\n    if (! (dflag == zero)) {\n\tgoto L80;\n    }\n    dh11 = one;\n    dh22 = one;\n    dflag = -one;\n    goto L90;\nL80:\n    dh21 = -one;\n    dh12 = one;\n    dflag = -one;\nL90:\n    switch (igo) {\n\tcase 0: goto L120;\n\tcase 1: goto L150;\n\tcase 2: goto L180;\n\tcase 3: goto L210;\n    }\n/*     PROCEDURE..SCALE-CHECK */\nL100:\nL110:\n    if (! (*dd1 <= rgamsq)) {\n\tgoto L130;\n    }\n    if (*dd1 == zero) {\n\tgoto L160;\n    }\n    igo = 0;\n    igo_fmt = fmt_120;\n/*              FIX-H.. */\n    goto L70;\nL120:\n/* Computing 2nd power */\n    d__1 = gam;\n    *dd1 *= d__1 * d__1;\n    *dx1 /= gam;\n    dh11 /= gam;\n    dh12 /= gam;\n    goto L110;\nL130:\nL140:\n    if (! (*dd1 >= gamsq)) {\n\tgoto L160;\n    }\n    igo = 1;\n    igo_fmt = fmt_150;\n/*              FIX-H.. */\n    goto L70;\nL150:\n/* Computing 2nd power */\n    d__1 = gam;\n    *dd1 /= d__1 * d__1;\n    *dx1 *= gam;\n    dh11 *= gam;\n    dh12 *= gam;\n    goto L140;\nL160:\nL170:\n    if (! (abs(*dd2) <= rgamsq)) {\n\tgoto L190;\n    }\n    if (*dd2 == zero) {\n\tgoto L220;\n    }\n    igo = 2;\n    igo_fmt = fmt_180;\n/*              FIX-H.. */\n    goto L70;\nL180:\n/* Computing 2nd power */\n    d__1 = gam;\n    *dd2 *= d__1 * d__1;\n    dh21 /= gam;\n    dh22 /= gam;\n    goto L170;\nL190:\nL200:\n    if (! (abs(*dd2) >= gamsq)) {\n\tgoto L220;\n    }\n    igo = 3;\n    igo_fmt = fmt_210;\n/*              FIX-H.. */\n    goto L70;\nL210:\n/* Computing 2nd power */\n    d__1 = gam;\n    *dd2 /= d__1 * d__1;\n    dh21 *= gam;\n    dh22 *= gam;\n    goto L200;\nL220:\n    if (dflag < 0.) {\n\tgoto L250;\n    } else if (dflag == 0) {\n\tgoto L230;\n    } else {\n\tgoto L240;\n    }\nL230:\n    dparam[3] = dh21;\n    dparam[4] = dh12;\n    goto L260;\nL240:\n    dparam[2] = dh11;\n    dparam[5] = dh22;\n    goto L260;\nL250:\n    dparam[2] = dh11;\n    dparam[3] = dh21;\n    dparam[4] = dh12;\n    dparam[5] = dh22;\nL260:\n    dparam[1] = dflag;\n    return 0;\n} /* drotmg_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/dsbmv.c",
    "content": "/* dsbmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int dsbmv_(char *uplo, integer *n, integer *k, doublereal *\n\talpha, doublereal *a, integer *lda, doublereal *x, integer *incx, \n\tdoublereal *beta, doublereal *y, integer *incy, ftnlen uplo_len)\n{\n    /* System generated locals */\n    integer a_dim1, a_offset, i__1, i__2, i__3, i__4;\n\n    /* Local variables */\n    integer i__, j, l, ix, iy, jx, jy, kx, ky, info;\n    doublereal temp1, temp2;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    integer kplus1;\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  DSBMV  performs the matrix-vector  operation */\n\n/*     y := alpha*A*x + beta*y, */\n\n/*  where alpha and beta are scalars, x and y are n element vectors and */\n/*  A is an n by n symmetric band matrix, with k super-diagonals. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the upper or lower */\n/*           triangular part of the band matrix A is being supplied as */\n/*           follows: */\n\n/*              UPLO = 'U' or 'u'   The upper triangular part of A is */\n/*                                  being supplied. */\n\n/*              UPLO = 'L' or 'l'   The lower triangular part of A is */\n/*                                  being supplied. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  K      - INTEGER. */\n/*           On entry, K specifies the number of super-diagonals of the */\n/*           matrix A. K must satisfy  0 .le. K. */\n/*           Unchanged on exit. */\n\n/*  ALPHA  - DOUBLE PRECISION. */\n/*           On entry, ALPHA specifies the scalar alpha. */\n/*           Unchanged on exit. */\n\n/*  A      - DOUBLE PRECISION array of DIMENSION ( LDA, n ). */\n/*           Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the upper triangular */\n/*           band part of the symmetric matrix, supplied column by */\n/*           column, with the leading diagonal of the matrix in row */\n/*           ( k + 1 ) of the array, the first super-diagonal starting at */\n/*           position 2 in row k, and so on. The top left k by k triangle */\n/*           of the array A is not referenced. */\n/*           The following program segment will transfer the upper */\n/*           triangular part of a symmetric band matrix from conventional */\n/*           full matrix storage to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = K + 1 - J */\n/*                    DO 10, I = MAX( 1, J - K ), J */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the lower triangular */\n/*           band part of the symmetric matrix, supplied column by */\n/*           column, with the leading diagonal of the matrix in row 1 of */\n/*           the array, the first sub-diagonal starting at position 1 in */\n/*           row 2, and so on. The bottom right k by k triangle of the */\n/*           array A is not referenced. */\n/*           The following program segment will transfer the lower */\n/*           triangular part of a symmetric band matrix from conventional */\n/*           full matrix storage to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = 1 - J */\n/*                    DO 10, I = J, MIN( N, J + K ) */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Unchanged on exit. */\n\n/*  LDA    - INTEGER. */\n/*           On entry, LDA specifies the first dimension of A as declared */\n/*           in the calling (sub) program. LDA must be at least */\n/*           ( k + 1 ). */\n/*           Unchanged on exit. */\n\n/*  X      - DOUBLE PRECISION array of DIMENSION at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the */\n/*           vector x. */\n/*           Unchanged on exit. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  BETA   - DOUBLE PRECISION. */\n/*           On entry, BETA specifies the scalar beta. */\n/*           Unchanged on exit. */\n\n/*  Y      - DOUBLE PRECISION array of DIMENSION at least */\n/*           ( 1 + ( n - 1 )*abs( INCY ) ). */\n/*           Before entry, the incremented array Y must contain the */\n/*           vector y. On exit, Y is overwritten by the updated vector y. */\n\n/*  INCY   - INTEGER. */\n/*           On entry, INCY specifies the increment for the elements of */\n/*           Y. INCY must not be zero. */\n/*           Unchanged on exit. */\n\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    a_dim1 = *lda;\n    a_offset = 1 + a_dim1;\n    a -= a_offset;\n    --x;\n    --y;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (*n < 0) {\n\tinfo = 2;\n    } else if (*k < 0) {\n\tinfo = 3;\n    } else if (*lda < *k + 1) {\n\tinfo = 6;\n    } else if (*incx == 0) {\n\tinfo = 8;\n    } else if (*incy == 0) {\n\tinfo = 11;\n    }\n    if (info != 0) {\n\txerbla_(\"DSBMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0 || (*alpha == 0. && *beta == 1.)) {\n\treturn 0;\n    }\n\n/*     Set up the start points in  X  and  Y. */\n\n    if (*incx > 0) {\n\tkx = 1;\n    } else {\n\tkx = 1 - (*n - 1) * *incx;\n    }\n    if (*incy > 0) {\n\tky = 1;\n    } else {\n\tky = 1 - (*n - 1) * *incy;\n    }\n\n/*     Start the operations. In this version the elements of the array A */\n/*     are accessed sequentially with one pass through A. */\n\n/*     First form  y := beta*y. */\n\n    if (*beta != 1.) {\n\tif (*incy == 1) {\n\t    if (*beta == 0.) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[i__] = 0.;\n/* L10: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[i__] = *beta * y[i__];\n/* L20: */\n\t\t}\n\t    }\n\t} else {\n\t    iy = ky;\n\t    if (*beta == 0.) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[iy] = 0.;\n\t\t    iy += *incy;\n/* L30: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[iy] = *beta * y[iy];\n\t\t    iy += *incy;\n/* L40: */\n\t\t}\n\t    }\n\t}\n    }\n    if (*alpha == 0.) {\n\treturn 0;\n    }\n    if (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\n/*        Form  y  when upper triangle of A is stored. */\n\n\tkplus1 = *k + 1;\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[j];\n\t\ttemp2 = 0.;\n\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\ti__2 = 1, i__3 = j - *k;\n\t\ti__4 = j - 1;\n\t\tfor (i__ = max(i__2,i__3); i__ <= i__4; ++i__) {\n\t\t    y[i__] += temp1 * a[l + i__ + j * a_dim1];\n\t\t    temp2 += a[l + i__ + j * a_dim1] * x[i__];\n/* L50: */\n\t\t}\n\t\ty[j] = y[j] + temp1 * a[kplus1 + j * a_dim1] + *alpha * temp2;\n/* L60: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[jx];\n\t\ttemp2 = 0.;\n\t\tix = kx;\n\t\tiy = ky;\n\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\ti__4 = 1, i__2 = j - *k;\n\t\ti__3 = j - 1;\n\t\tfor (i__ = max(i__4,i__2); i__ <= i__3; ++i__) {\n\t\t    y[iy] += temp1 * a[l + i__ + j * a_dim1];\n\t\t    temp2 += a[l + i__ + j * a_dim1] * x[ix];\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n/* L70: */\n\t\t}\n\t\ty[jy] = y[jy] + temp1 * a[kplus1 + j * a_dim1] + *alpha * \n\t\t\ttemp2;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tif (j > *k) {\n\t\t    kx += *incx;\n\t\t    ky += *incy;\n\t\t}\n/* L80: */\n\t    }\n\t}\n    } else {\n\n/*        Form  y  when lower triangle of A is stored. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[j];\n\t\ttemp2 = 0.;\n\t\ty[j] += temp1 * a[j * a_dim1 + 1];\n\t\tl = 1 - j;\n/* Computing MIN */\n\t\ti__4 = *n, i__2 = j + *k;\n\t\ti__3 = min(i__4,i__2);\n\t\tfor (i__ = j + 1; i__ <= i__3; ++i__) {\n\t\t    y[i__] += temp1 * a[l + i__ + j * a_dim1];\n\t\t    temp2 += a[l + i__ + j * a_dim1] * x[i__];\n/* L90: */\n\t\t}\n\t\ty[j] += *alpha * temp2;\n/* L100: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[jx];\n\t\ttemp2 = 0.;\n\t\ty[jy] += temp1 * a[j * a_dim1 + 1];\n\t\tl = 1 - j;\n\t\tix = jx;\n\t\tiy = jy;\n/* Computing MIN */\n\t\ti__4 = *n, i__2 = j + *k;\n\t\ti__3 = min(i__4,i__2);\n\t\tfor (i__ = j + 1; i__ <= i__3; ++i__) {\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n\t\t    y[iy] += temp1 * a[l + i__ + j * a_dim1];\n\t\t    temp2 += a[l + i__ + j * a_dim1] * x[ix];\n/* L110: */\n\t\t}\n\t\ty[jy] += *alpha * temp2;\n\t\tjx += *incx;\n\t\tjy += *incy;\n/* L120: */\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of DSBMV . */\n\n} /* dsbmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/dspmv.c",
    "content": "/* dspmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int dspmv_(char *uplo, integer *n, doublereal *alpha, \n\tdoublereal *ap, doublereal *x, integer *incx, doublereal *beta, \n\tdoublereal *y, integer *incy, ftnlen uplo_len)\n{\n    /* System generated locals */\n    integer i__1, i__2;\n\n    /* Local variables */\n    integer i__, j, k, kk, ix, iy, jx, jy, kx, ky, info;\n    doublereal temp1, temp2;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  DSPMV  performs the matrix-vector operation */\n\n/*     y := alpha*A*x + beta*y, */\n\n/*  where alpha and beta are scalars, x and y are n element vectors and */\n/*  A is an n by n symmetric matrix, supplied in packed form. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the upper or lower */\n/*           triangular part of the matrix A is supplied in the packed */\n/*           array AP as follows: */\n\n/*              UPLO = 'U' or 'u'   The upper triangular part of A is */\n/*                                  supplied in AP. */\n\n/*              UPLO = 'L' or 'l'   The lower triangular part of A is */\n/*                                  supplied in AP. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  ALPHA  - DOUBLE PRECISION. */\n/*           On entry, ALPHA specifies the scalar alpha. */\n/*           Unchanged on exit. */\n\n/*  AP     - DOUBLE PRECISION array of DIMENSION at least */\n/*           ( ( n*( n + 1 ) )/2 ). */\n/*           Before entry with UPLO = 'U' or 'u', the array AP must */\n/*           contain the upper triangular part of the symmetric matrix */\n/*           packed sequentially, column by column, so that AP( 1 ) */\n/*           contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 1, 2 ) */\n/*           and a( 2, 2 ) respectively, and so on. */\n/*           Before entry with UPLO = 'L' or 'l', the array AP must */\n/*           contain the lower triangular part of the symmetric matrix */\n/*           packed sequentially, column by column, so that AP( 1 ) */\n/*           contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 2, 1 ) */\n/*           and a( 3, 1 ) respectively, and so on. */\n/*           Unchanged on exit. */\n\n/*  X      - DOUBLE PRECISION array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the n */\n/*           element vector x. */\n/*           Unchanged on exit. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  BETA   - DOUBLE PRECISION. */\n/*           On entry, BETA specifies the scalar beta. When BETA is */\n/*           supplied as zero then Y need not be set on input. */\n/*           Unchanged on exit. */\n\n/*  Y      - DOUBLE PRECISION array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCY ) ). */\n/*           Before entry, the incremented array Y must contain the n */\n/*           element vector y. On exit, Y is overwritten by the updated */\n/*           vector y. */\n\n/*  INCY   - INTEGER. */\n/*           On entry, INCY specifies the increment for the elements of */\n/*           Y. INCY must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    --y;\n    --x;\n    --ap;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (*n < 0) {\n\tinfo = 2;\n    } else if (*incx == 0) {\n\tinfo = 6;\n    } else if (*incy == 0) {\n\tinfo = 9;\n    }\n    if (info != 0) {\n\txerbla_(\"DSPMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0 || (*alpha == 0. && *beta == 1.)) {\n\treturn 0;\n    }\n\n/*     Set up the start points in  X  and  Y. */\n\n    if (*incx > 0) {\n\tkx = 1;\n    } else {\n\tkx = 1 - (*n - 1) * *incx;\n    }\n    if (*incy > 0) {\n\tky = 1;\n    } else {\n\tky = 1 - (*n - 1) * *incy;\n    }\n\n/*     Start the operations. In this version the elements of the array AP */\n/*     are accessed sequentially with one pass through AP. */\n\n/*     First form  y := beta*y. */\n\n    if (*beta != 1.) {\n\tif (*incy == 1) {\n\t    if (*beta == 0.) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[i__] = 0.;\n/* L10: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[i__] = *beta * y[i__];\n/* L20: */\n\t\t}\n\t    }\n\t} else {\n\t    iy = ky;\n\t    if (*beta == 0.) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[iy] = 0.;\n\t\t    iy += *incy;\n/* L30: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[iy] = *beta * y[iy];\n\t\t    iy += *incy;\n/* L40: */\n\t\t}\n\t    }\n\t}\n    }\n    if (*alpha == 0.) {\n\treturn 0;\n    }\n    kk = 1;\n    if (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\n/*        Form  y  when AP contains the upper triangle. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[j];\n\t\ttemp2 = 0.;\n\t\tk = kk;\n\t\ti__2 = j - 1;\n\t\tfor (i__ = 1; i__ <= i__2; ++i__) {\n\t\t    y[i__] += temp1 * ap[k];\n\t\t    temp2 += ap[k] * x[i__];\n\t\t    ++k;\n/* L50: */\n\t\t}\n\t\ty[j] = y[j] + temp1 * ap[kk + j - 1] + *alpha * temp2;\n\t\tkk += j;\n/* L60: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[jx];\n\t\ttemp2 = 0.;\n\t\tix = kx;\n\t\tiy = ky;\n\t\ti__2 = kk + j - 2;\n\t\tfor (k = kk; k <= i__2; ++k) {\n\t\t    y[iy] += temp1 * ap[k];\n\t\t    temp2 += ap[k] * x[ix];\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n/* L70: */\n\t\t}\n\t\ty[jy] = y[jy] + temp1 * ap[kk + j - 1] + *alpha * temp2;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tkk += j;\n/* L80: */\n\t    }\n\t}\n    } else {\n\n/*        Form  y  when AP contains the lower triangle. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[j];\n\t\ttemp2 = 0.;\n\t\ty[j] += temp1 * ap[kk];\n\t\tk = kk + 1;\n\t\ti__2 = *n;\n\t\tfor (i__ = j + 1; i__ <= i__2; ++i__) {\n\t\t    y[i__] += temp1 * ap[k];\n\t\t    temp2 += ap[k] * x[i__];\n\t\t    ++k;\n/* L90: */\n\t\t}\n\t\ty[j] += *alpha * temp2;\n\t\tkk += *n - j + 1;\n/* L100: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[jx];\n\t\ttemp2 = 0.;\n\t\ty[jy] += temp1 * ap[kk];\n\t\tix = jx;\n\t\tiy = jy;\n\t\ti__2 = kk + *n - j;\n\t\tfor (k = kk + 1; k <= i__2; ++k) {\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n\t\t    y[iy] += temp1 * ap[k];\n\t\t    temp2 += ap[k] * x[ix];\n/* L110: */\n\t\t}\n\t\ty[jy] += *alpha * temp2;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tkk += *n - j + 1;\n/* L120: */\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of DSPMV . */\n\n} /* dspmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/dtbmv.c",
    "content": "/* dtbmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int dtbmv_(char *uplo, char *trans, char *diag, integer *n, \n\tinteger *k, doublereal *a, integer *lda, doublereal *x, integer *incx,\n\t ftnlen uplo_len, ftnlen trans_len, ftnlen diag_len)\n{\n    /* System generated locals */\n    integer a_dim1, a_offset, i__1, i__2, i__3, i__4;\n\n    /* Local variables */\n    integer i__, j, l, ix, jx, kx, info;\n    doublereal temp;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    integer kplus1;\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n    logical nounit;\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  DTBMV  performs one of the matrix-vector operations */\n\n/*     x := A*x,   or   x := A'*x, */\n\n/*  where x is an n element vector and  A is an n by n unit, or non-unit, */\n/*  upper or lower triangular band matrix, with ( k + 1 ) diagonals. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the matrix is an upper or */\n/*           lower triangular matrix as follows: */\n\n/*              UPLO = 'U' or 'u'   A is an upper triangular matrix. */\n\n/*              UPLO = 'L' or 'l'   A is a lower triangular matrix. */\n\n/*           Unchanged on exit. */\n\n/*  TRANS  - CHARACTER*1. */\n/*           On entry, TRANS specifies the operation to be performed as */\n/*           follows: */\n\n/*              TRANS = 'N' or 'n'   x := A*x. */\n\n/*              TRANS = 'T' or 't'   x := A'*x. */\n\n/*              TRANS = 'C' or 'c'   x := A'*x. */\n\n/*           Unchanged on exit. */\n\n/*  DIAG   - CHARACTER*1. */\n/*           On entry, DIAG specifies whether or not A is unit */\n/*           triangular as follows: */\n\n/*              DIAG = 'U' or 'u'   A is assumed to be unit triangular. */\n\n/*              DIAG = 'N' or 'n'   A is not assumed to be unit */\n/*                                  triangular. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  K      - INTEGER. */\n/*           On entry with UPLO = 'U' or 'u', K specifies the number of */\n/*           super-diagonals of the matrix A. */\n/*           On entry with UPLO = 'L' or 'l', K specifies the number of */\n/*           sub-diagonals of the matrix A. */\n/*           K must satisfy  0 .le. K. */\n/*           Unchanged on exit. */\n\n/*  A      - DOUBLE PRECISION array of DIMENSION ( LDA, n ). */\n/*           Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the upper triangular */\n/*           band part of the matrix of coefficients, supplied column by */\n/*           column, with the leading diagonal of the matrix in row */\n/*           ( k + 1 ) of the array, the first super-diagonal starting at */\n/*           position 2 in row k, and so on. The top left k by k triangle */\n/*           of the array A is not referenced. */\n/*           The following program segment will transfer an upper */\n/*           triangular band matrix from conventional full matrix storage */\n/*           to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = K + 1 - J */\n/*                    DO 10, I = MAX( 1, J - K ), J */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the lower triangular */\n/*           band part of the matrix of coefficients, supplied column by */\n/*           column, with the leading diagonal of the matrix in row 1 of */\n/*           the array, the first sub-diagonal starting at position 1 in */\n/*           row 2, and so on. The bottom right k by k triangle of the */\n/*           array A is not referenced. */\n/*           The following program segment will transfer a lower */\n/*           triangular band matrix from conventional full matrix storage */\n/*           to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = 1 - J */\n/*                    DO 10, I = J, MIN( N, J + K ) */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Note that when DIAG = 'U' or 'u' the elements of the array A */\n/*           corresponding to the diagonal elements of the matrix are not */\n/*           referenced, but are assumed to be unity. */\n/*           Unchanged on exit. */\n\n/*  LDA    - INTEGER. */\n/*           On entry, LDA specifies the first dimension of A as declared */\n/*           in the calling (sub) program. LDA must be at least */\n/*           ( k + 1 ). */\n/*           Unchanged on exit. */\n\n/*  X      - DOUBLE PRECISION array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the n */\n/*           element vector x. On exit, X is overwritten with the */\n/*           transformed vector x. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    a_dim1 = *lda;\n    a_offset = 1 + a_dim1;\n    a -= a_offset;\n    --x;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (! lsame_(trans, \"N\", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, \n\t    \"T\", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, \"C\", (ftnlen)1, (\n\t    ftnlen)1)) {\n\tinfo = 2;\n    } else if (! lsame_(diag, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(diag, \n\t    \"N\", (ftnlen)1, (ftnlen)1)) {\n\tinfo = 3;\n    } else if (*n < 0) {\n\tinfo = 4;\n    } else if (*k < 0) {\n\tinfo = 5;\n    } else if (*lda < *k + 1) {\n\tinfo = 7;\n    } else if (*incx == 0) {\n\tinfo = 9;\n    }\n    if (info != 0) {\n\txerbla_(\"DTBMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0) {\n\treturn 0;\n    }\n\n    nounit = lsame_(diag, \"N\", (ftnlen)1, (ftnlen)1);\n\n/*     Set up the start point in X if the increment is not unity. This */\n/*     will be  ( N - 1 )*INCX   too small for descending loops. */\n\n    if (*incx <= 0) {\n\tkx = 1 - (*n - 1) * *incx;\n    } else if (*incx != 1) {\n\tkx = 1;\n    }\n\n/*     Start the operations. In this version the elements of A are */\n/*     accessed sequentially with one pass through A. */\n\n    if (lsame_(trans, \"N\", (ftnlen)1, (ftnlen)1)) {\n\n/*         Form  x := A*x. */\n\n\tif (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\t    kplus1 = *k + 1;\n\t    if (*incx == 1) {\n\t\ti__1 = *n;\n\t\tfor (j = 1; j <= i__1; ++j) {\n\t\t    if (x[j] != 0.) {\n\t\t\ttemp = x[j];\n\t\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\t\ti__2 = 1, i__3 = j - *k;\n\t\t\ti__4 = j - 1;\n\t\t\tfor (i__ = max(i__2,i__3); i__ <= i__4; ++i__) {\n\t\t\t    x[i__] += temp * a[l + i__ + j * a_dim1];\n/* L10: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    x[j] *= a[kplus1 + j * a_dim1];\n\t\t\t}\n\t\t    }\n/* L20: */\n\t\t}\n\t    } else {\n\t\tjx = kx;\n\t\ti__1 = *n;\n\t\tfor (j = 1; j <= i__1; ++j) {\n\t\t    if (x[jx] != 0.) {\n\t\t\ttemp = x[jx];\n\t\t\tix = kx;\n\t\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\t\ti__4 = 1, i__2 = j - *k;\n\t\t\ti__3 = j - 1;\n\t\t\tfor (i__ = max(i__4,i__2); i__ <= i__3; ++i__) {\n\t\t\t    x[ix] += temp * a[l + i__ + j * a_dim1];\n\t\t\t    ix += *incx;\n/* L30: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    x[jx] *= a[kplus1 + j * a_dim1];\n\t\t\t}\n\t\t    }\n\t\t    jx += *incx;\n\t\t    if (j > *k) {\n\t\t\tkx += *incx;\n\t\t    }\n/* L40: */\n\t\t}\n\t    }\n\t} else {\n\t    if (*incx == 1) {\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    if (x[j] != 0.) {\n\t\t\ttemp = x[j];\n\t\t\tl = 1 - j;\n/* Computing MIN */\n\t\t\ti__1 = *n, i__3 = j + *k;\n\t\t\ti__4 = j + 1;\n\t\t\tfor (i__ = min(i__1,i__3); i__ >= i__4; --i__) {\n\t\t\t    x[i__] += temp * a[l + i__ + j * a_dim1];\n/* L50: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    x[j] *= a[j * a_dim1 + 1];\n\t\t\t}\n\t\t    }\n/* L60: */\n\t\t}\n\t    } else {\n\t\tkx += (*n - 1) * *incx;\n\t\tjx = kx;\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    if (x[jx] != 0.) {\n\t\t\ttemp = x[jx];\n\t\t\tix = kx;\n\t\t\tl = 1 - j;\n/* Computing MIN */\n\t\t\ti__4 = *n, i__1 = j + *k;\n\t\t\ti__3 = j + 1;\n\t\t\tfor (i__ = min(i__4,i__1); i__ >= i__3; --i__) {\n\t\t\t    x[ix] += temp * a[l + i__ + j * a_dim1];\n\t\t\t    ix -= *incx;\n/* L70: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    x[jx] *= a[j * a_dim1 + 1];\n\t\t\t}\n\t\t    }\n\t\t    jx -= *incx;\n\t\t    if (*n - j >= *k) {\n\t\t\tkx -= *incx;\n\t\t    }\n/* L80: */\n\t\t}\n\t    }\n\t}\n    } else {\n\n/*        Form  x := A'*x. */\n\n\tif (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\t    kplus1 = *k + 1;\n\t    if (*incx == 1) {\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    temp = x[j];\n\t\t    l = kplus1 - j;\n\t\t    if (nounit) {\n\t\t\ttemp *= a[kplus1 + j * a_dim1];\n\t\t    }\n/* Computing MAX */\n\t\t    i__4 = 1, i__1 = j - *k;\n\t\t    i__3 = max(i__4,i__1);\n\t\t    for (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\ttemp += a[l + i__ + j * a_dim1] * x[i__];\n/* L90: */\n\t\t    }\n\t\t    x[j] = temp;\n/* L100: */\n\t\t}\n\t    } else {\n\t\tkx += (*n - 1) * *incx;\n\t\tjx = kx;\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    temp = x[jx];\n\t\t    kx -= *incx;\n\t\t    ix = kx;\n\t\t    l = kplus1 - j;\n\t\t    if (nounit) {\n\t\t\ttemp *= a[kplus1 + j * a_dim1];\n\t\t    }\n/* Computing MAX */\n\t\t    i__4 = 1, i__1 = j - *k;\n\t\t    i__3 = max(i__4,i__1);\n\t\t    for (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\ttemp += a[l + i__ + j * a_dim1] * x[ix];\n\t\t\tix -= *incx;\n/* L110: */\n\t\t    }\n\t\t    x[jx] = temp;\n\t\t    jx -= *incx;\n/* L120: */\n\t\t}\n\t    }\n\t} else {\n\t    if (*incx == 1) {\n\t\ti__3 = *n;\n\t\tfor (j = 1; j <= i__3; ++j) {\n\t\t    temp = x[j];\n\t\t    l = 1 - j;\n\t\t    if (nounit) {\n\t\t\ttemp *= a[j * a_dim1 + 1];\n\t\t    }\n/* Computing MIN */\n\t\t    i__1 = *n, i__2 = j + *k;\n\t\t    i__4 = min(i__1,i__2);\n\t\t    for (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\ttemp += a[l + i__ + j * a_dim1] * x[i__];\n/* L130: */\n\t\t    }\n\t\t    x[j] = temp;\n/* L140: */\n\t\t}\n\t    } else {\n\t\tjx = kx;\n\t\ti__3 = *n;\n\t\tfor (j = 1; j <= i__3; ++j) {\n\t\t    temp = x[jx];\n\t\t    kx += *incx;\n\t\t    ix = kx;\n\t\t    l = 1 - j;\n\t\t    if (nounit) {\n\t\t\ttemp *= a[j * a_dim1 + 1];\n\t\t    }\n/* Computing MIN */\n\t\t    i__1 = *n, i__2 = j + *k;\n\t\t    i__4 = min(i__1,i__2);\n\t\t    for (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\ttemp += a[l + i__ + j * a_dim1] * x[ix];\n\t\t\tix += *incx;\n/* L150: */\n\t\t    }\n\t\t    x[jx] = temp;\n\t\t    jx += *incx;\n/* L160: */\n\t\t}\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of DTBMV . */\n\n} /* dtbmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/lsame.c",
    "content": "/* lsame.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\nlogical lsame_(char *ca, char *cb, ftnlen ca_len, ftnlen cb_len)\n{\n    /* System generated locals */\n    logical ret_val;\n\n    /* Local variables */\n    integer inta, intb, zcode;\n\n\n/*  -- LAPACK auxiliary routine (version 3.1) -- */\n/*     Univ. of Tennessee, Univ. of California Berkeley and NAG Ltd.. */\n/*     November 2006 */\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  LSAME returns .TRUE. if CA is the same letter as CB regardless of */\n/*  case. */\n\n/*  Arguments */\n/*  ========= */\n\n/*  CA      (input) CHARACTER*1 */\n\n/*  CB      (input) CHARACTER*1 */\n/*          CA and CB specify the single characters to be compared. */\n\n/* ===================================================================== */\n\n/*     .. Intrinsic Functions .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n\n/*     Test if the characters are equal */\n\n    ret_val = *(unsigned char *)ca == *(unsigned char *)cb;\n    if (ret_val) {\n\treturn ret_val;\n    }\n\n/*     Now test for equivalence if both characters are alphabetic. */\n\n    zcode = 'Z';\n\n/*     Use 'Z' rather than 'A' so that ASCII can be detected on Prime */\n/*     machines, on which ICHAR returns a value with bit 8 set. */\n/*     ICHAR('A') on Prime machines returns 193 which is the same as */\n/*     ICHAR('A') on an EBCDIC machine. */\n\n    inta = *(unsigned char *)ca;\n    intb = *(unsigned char *)cb;\n\n    if (zcode == 90 || zcode == 122) {\n\n/*        ASCII is assumed - ZCODE is the ASCII code of either lower or */\n/*        upper case 'Z'. */\n\n\tif (inta >= 97 && inta <= 122) {\n\t    inta += -32;\n\t}\n\tif (intb >= 97 && intb <= 122) {\n\t    intb += -32;\n\t}\n\n    } else if (zcode == 233 || zcode == 169) {\n\n/*        EBCDIC is assumed - ZCODE is the EBCDIC code of either lower or */\n/*        upper case 'Z'. */\n\n\tif ((inta >= 129 && inta <= 137) || (inta >= 145 && inta <= 153) || \n            (inta >= 162 && inta <= 169)) {\n\t    inta += 64;\n\t}\n\tif ((intb >= 129 && intb <= 137) || (intb >= 145 && intb <= 153) || \n            (intb >= 162 && intb <= 169)) {\n\t    intb += 64;\n\t}\n\n    } else if (zcode == 218 || zcode == 250) {\n\n/*        ASCII is assumed, on Prime machines - ZCODE is the ASCII code */\n/*        plus 128 of either lower or upper case 'Z'. */\n\n\tif (inta >= 225 && inta <= 250) {\n\t    inta += -32;\n\t}\n\tif (intb >= 225 && intb <= 250) {\n\t    intb += -32;\n\t}\n    }\n    ret_val = inta == intb;\n\n/*     RETURN */\n\n/*     End of LSAME */\n\n    return ret_val;\n} /* lsame_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/r_cnjg.c",
    "content": "#include \"datatypes.h\"    \n\nvoid r_cnjg(complex *r, complex *z) {\n    r->r = z->r;\n    r->i = -(z->i);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/srotm.c",
    "content": "/* srotm.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int srotm_(integer *n, real *sx, integer *incx, real *sy, \n\tinteger *incy, real *sparam)\n{\n    /* Initialized data */\n\n    static real zero = 0.f;\n    static real two = 2.f;\n\n    /* System generated locals */\n    integer i__1, i__2;\n\n    /* Local variables */\n    integer i__;\n    real w, z__;\n    integer kx, ky;\n    real sh11, sh12, sh21, sh22, sflag;\n    integer nsteps;\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*     APPLY THE MODIFIED GIVENS TRANSFORMATION, H, TO THE 2 BY N MATRIX */\n\n/*     (SX**T) , WHERE **T INDICATES TRANSPOSE. THE ELEMENTS OF SX ARE IN */\n/*     (DX**T) */\n\n/*     SX(LX+I*INCX), I = 0 TO N-1, WHERE LX = 1 IF INCX .GE. 0, ELSE */\n/*     LX = (-INCX)*N, AND SIMILARLY FOR SY USING USING LY AND INCY. */\n/*     WITH SPARAM(1)=SFLAG, H HAS ONE OF THE FOLLOWING FORMS.. */\n\n/*     SFLAG=-1.E0     SFLAG=0.E0        SFLAG=1.E0     SFLAG=-2.E0 */\n\n/*       (SH11  SH12)    (1.E0  SH12)    (SH11  1.E0)    (1.E0  0.E0) */\n/*     H=(          )    (          )    (          )    (          ) */\n/*       (SH21  SH22),   (SH21  1.E0),   (-1.E0 SH22),   (0.E0  1.E0). */\n/*     SEE  SROTMG FOR A DESCRIPTION OF DATA STORAGE IN SPARAM. */\n\n\n/*  Arguments */\n/*  ========= */\n\n/*  N      (input) INTEGER */\n/*         number of elements in input vector(s) */\n\n/*  SX     (input/output) REAL array, dimension N */\n/*         double precision vector with N elements */\n\n/*  INCX   (input) INTEGER */\n/*         storage spacing between elements of SX */\n\n/*  SY     (input/output) REAL array, dimension N */\n/*         double precision vector with N elements */\n\n/*  INCY   (input) INTEGER */\n/*         storage spacing between elements of SY */\n\n/*  SPARAM (input/output)  REAL array, dimension 5 */\n/*     SPARAM(1)=SFLAG */\n/*     SPARAM(2)=SH11 */\n/*     SPARAM(3)=SH21 */\n/*     SPARAM(4)=SH12 */\n/*     SPARAM(5)=SH22 */\n\n/*  ===================================================================== */\n\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. Data statements .. */\n    /* Parameter adjustments */\n    --sparam;\n    --sy;\n    --sx;\n\n    /* Function Body */\n/*     .. */\n\n    sflag = sparam[1];\n    if (*n <= 0 || sflag + two == zero) {\n\tgoto L140;\n    }\n    if (! (*incx == *incy && *incx > 0)) {\n\tgoto L70;\n    }\n\n    nsteps = *n * *incx;\n    if (sflag < 0.f) {\n\tgoto L50;\n    } else if (sflag == 0) {\n\tgoto L10;\n    } else {\n\tgoto L30;\n    }\nL10:\n    sh12 = sparam[4];\n    sh21 = sparam[3];\n    i__1 = nsteps;\n    i__2 = *incx;\n    for (i__ = 1; i__2 < 0 ? i__ >= i__1 : i__ <= i__1; i__ += i__2) {\n\tw = sx[i__];\n\tz__ = sy[i__];\n\tsx[i__] = w + z__ * sh12;\n\tsy[i__] = w * sh21 + z__;\n/* L20: */\n    }\n    goto L140;\nL30:\n    sh11 = sparam[2];\n    sh22 = sparam[5];\n    i__2 = nsteps;\n    i__1 = *incx;\n    for (i__ = 1; i__1 < 0 ? i__ >= i__2 : i__ <= i__2; i__ += i__1) {\n\tw = sx[i__];\n\tz__ = sy[i__];\n\tsx[i__] = w * sh11 + z__;\n\tsy[i__] = -w + sh22 * z__;\n/* L40: */\n    }\n    goto L140;\nL50:\n    sh11 = sparam[2];\n    sh12 = sparam[4];\n    sh21 = sparam[3];\n    sh22 = sparam[5];\n    i__1 = nsteps;\n    i__2 = *incx;\n    for (i__ = 1; i__2 < 0 ? i__ >= i__1 : i__ <= i__1; i__ += i__2) {\n\tw = sx[i__];\n\tz__ = sy[i__];\n\tsx[i__] = w * sh11 + z__ * sh12;\n\tsy[i__] = w * sh21 + z__ * sh22;\n/* L60: */\n    }\n    goto L140;\nL70:\n    kx = 1;\n    ky = 1;\n    if (*incx < 0) {\n\tkx = (1 - *n) * *incx + 1;\n    }\n    if (*incy < 0) {\n\tky = (1 - *n) * *incy + 1;\n    }\n\n    if (sflag < 0.f) {\n\tgoto L120;\n    } else if (sflag == 0) {\n\tgoto L80;\n    } else {\n\tgoto L100;\n    }\nL80:\n    sh12 = sparam[4];\n    sh21 = sparam[3];\n    i__2 = *n;\n    for (i__ = 1; i__ <= i__2; ++i__) {\n\tw = sx[kx];\n\tz__ = sy[ky];\n\tsx[kx] = w + z__ * sh12;\n\tsy[ky] = w * sh21 + z__;\n\tkx += *incx;\n\tky += *incy;\n/* L90: */\n    }\n    goto L140;\nL100:\n    sh11 = sparam[2];\n    sh22 = sparam[5];\n    i__2 = *n;\n    for (i__ = 1; i__ <= i__2; ++i__) {\n\tw = sx[kx];\n\tz__ = sy[ky];\n\tsx[kx] = w * sh11 + z__;\n\tsy[ky] = -w + sh22 * z__;\n\tkx += *incx;\n\tky += *incy;\n/* L110: */\n    }\n    goto L140;\nL120:\n    sh11 = sparam[2];\n    sh12 = sparam[4];\n    sh21 = sparam[3];\n    sh22 = sparam[5];\n    i__2 = *n;\n    for (i__ = 1; i__ <= i__2; ++i__) {\n\tw = sx[kx];\n\tz__ = sy[ky];\n\tsx[kx] = w * sh11 + z__ * sh12;\n\tsy[ky] = w * sh21 + z__ * sh22;\n\tkx += *incx;\n\tky += *incy;\n/* L130: */\n    }\nL140:\n    return 0;\n} /* srotm_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/srotmg.c",
    "content": "/* srotmg.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int srotmg_(real *sd1, real *sd2, real *sx1, real *sy1, real \n\t*sparam)\n{\n    /* Initialized data */\n\n    static real zero = 0.f;\n    static real one = 1.f;\n    static real two = 2.f;\n    static real gam = 4096.f;\n    static real gamsq = 16777200.f;\n    static real rgamsq = 5.96046e-8f;\n\n    /* Format strings */\n    static char fmt_120[] = \"\";\n    static char fmt_150[] = \"\";\n    static char fmt_180[] = \"\";\n    static char fmt_210[] = \"\";\n\n    /* System generated locals */\n    real r__1;\n\n    /* Local variables */\n    real su, sp1, sp2, sq1, sq2, sh11, sh12, sh21, sh22;\n    integer igo;\n    real sflag, stemp;\n\n    /* Assigned format variables */\n    static char *igo_fmt;\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*     CONSTRUCT THE MODIFIED GIVENS TRANSFORMATION MATRIX H WHICH ZEROS */\n/*     THE SECOND COMPONENT OF THE 2-VECTOR  (SQRT(SD1)*SX1,SQRT(SD2)* */\n/*     SY2)**T. */\n/*     WITH SPARAM(1)=SFLAG, H HAS ONE OF THE FOLLOWING FORMS.. */\n\n/*     SFLAG=-1.E0     SFLAG=0.E0        SFLAG=1.E0     SFLAG=-2.E0 */\n\n/*       (SH11  SH12)    (1.E0  SH12)    (SH11  1.E0)    (1.E0  0.E0) */\n/*     H=(          )    (          )    (          )    (          ) */\n/*       (SH21  SH22),   (SH21  1.E0),   (-1.E0 SH22),   (0.E0  1.E0). */\n/*     LOCATIONS 2-4 OF SPARAM CONTAIN SH11,SH21,SH12, AND SH22 */\n/*     RESPECTIVELY. (VALUES OF 1.E0, -1.E0, OR 0.E0 IMPLIED BY THE */\n/*     VALUE OF SPARAM(1) ARE NOT STORED IN SPARAM.) */\n\n/*     THE VALUES OF GAMSQ AND RGAMSQ SET IN THE DATA STATEMENT MAY BE */\n/*     INEXACT.  THIS IS OK AS THEY ARE ONLY USED FOR TESTING THE SIZE */\n/*     OF SD1 AND SD2.  ALL ACTUAL SCALING OF DATA IS DONE USING GAM. */\n\n\n/*  Arguments */\n/*  ========= */\n\n\n/*  SD1    (input/output) REAL */\n\n/*  SD2    (input/output) REAL */\n\n/*  SX1    (input/output) REAL */\n\n/*  SY1    (input) REAL */\n\n\n/*  SPARAM (input/output)  REAL array, dimension 5 */\n/*     SPARAM(1)=SFLAG */\n/*     SPARAM(2)=SH11 */\n/*     SPARAM(3)=SH21 */\n/*     SPARAM(4)=SH12 */\n/*     SPARAM(5)=SH22 */\n\n/*  ===================================================================== */\n\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n/*     .. Data statements .. */\n\n    /* Parameter adjustments */\n    --sparam;\n\n    /* Function Body */\n/*     .. */\n    if (! (*sd1 < zero)) {\n\tgoto L10;\n    }\n/*       GO ZERO-H-D-AND-SX1.. */\n    goto L60;\nL10:\n/*     CASE-SD1-NONNEGATIVE */\n    sp2 = *sd2 * *sy1;\n    if (! (sp2 == zero)) {\n\tgoto L20;\n    }\n    sflag = -two;\n    goto L260;\n/*     REGULAR-CASE.. */\nL20:\n    sp1 = *sd1 * *sx1;\n    sq2 = sp2 * *sy1;\n    sq1 = sp1 * *sx1;\n\n    if (! (dabs(sq1) > dabs(sq2))) {\n\tgoto L40;\n    }\n    sh21 = -(*sy1) / *sx1;\n    sh12 = sp2 / sp1;\n\n    su = one - sh12 * sh21;\n\n    if (! (su <= zero)) {\n\tgoto L30;\n    }\n/*         GO ZERO-H-D-AND-SX1.. */\n    goto L60;\nL30:\n    sflag = zero;\n    *sd1 /= su;\n    *sd2 /= su;\n    *sx1 *= su;\n/*         GO SCALE-CHECK.. */\n    goto L100;\nL40:\n    if (! (sq2 < zero)) {\n\tgoto L50;\n    }\n/*         GO ZERO-H-D-AND-SX1.. */\n    goto L60;\nL50:\n    sflag = one;\n    sh11 = sp1 / sp2;\n    sh22 = *sx1 / *sy1;\n    su = one + sh11 * sh22;\n    stemp = *sd2 / su;\n    *sd2 = *sd1 / su;\n    *sd1 = stemp;\n    *sx1 = *sy1 * su;\n/*         GO SCALE-CHECK */\n    goto L100;\n/*     PROCEDURE..ZERO-H-D-AND-SX1.. */\nL60:\n    sflag = -one;\n    sh11 = zero;\n    sh12 = zero;\n    sh21 = zero;\n    sh22 = zero;\n\n    *sd1 = zero;\n    *sd2 = zero;\n    *sx1 = zero;\n/*         RETURN.. */\n    goto L220;\n/*     PROCEDURE..FIX-H.. */\nL70:\n    if (! (sflag >= zero)) {\n\tgoto L90;\n    }\n\n    if (! (sflag == zero)) {\n\tgoto L80;\n    }\n    sh11 = one;\n    sh22 = one;\n    sflag = -one;\n    goto L90;\nL80:\n    sh21 = -one;\n    sh12 = one;\n    sflag = -one;\nL90:\n    switch (igo) {\n\tcase 0: goto L120;\n\tcase 1: goto L150;\n\tcase 2: goto L180;\n\tcase 3: goto L210;\n    }\n/*     PROCEDURE..SCALE-CHECK */\nL100:\nL110:\n    if (! (*sd1 <= rgamsq)) {\n\tgoto L130;\n    }\n    if (*sd1 == zero) {\n\tgoto L160;\n    }\n    igo = 0;\n    igo_fmt = fmt_120;\n/*              FIX-H.. */\n    goto L70;\nL120:\n/* Computing 2nd power */\n    r__1 = gam;\n    *sd1 *= r__1 * r__1;\n    *sx1 /= gam;\n    sh11 /= gam;\n    sh12 /= gam;\n    goto L110;\nL130:\nL140:\n    if (! (*sd1 >= gamsq)) {\n\tgoto L160;\n    }\n    igo = 1;\n    igo_fmt = fmt_150;\n/*              FIX-H.. */\n    goto L70;\nL150:\n/* Computing 2nd power */\n    r__1 = gam;\n    *sd1 /= r__1 * r__1;\n    *sx1 *= gam;\n    sh11 *= gam;\n    sh12 *= gam;\n    goto L140;\nL160:\nL170:\n    if (! (dabs(*sd2) <= rgamsq)) {\n\tgoto L190;\n    }\n    if (*sd2 == zero) {\n\tgoto L220;\n    }\n    igo = 2;\n    igo_fmt = fmt_180;\n/*              FIX-H.. */\n    goto L70;\nL180:\n/* Computing 2nd power */\n    r__1 = gam;\n    *sd2 *= r__1 * r__1;\n    sh21 /= gam;\n    sh22 /= gam;\n    goto L170;\nL190:\nL200:\n    if (! (dabs(*sd2) >= gamsq)) {\n\tgoto L220;\n    }\n    igo = 3;\n    igo_fmt = fmt_210;\n/*              FIX-H.. */\n    goto L70;\nL210:\n/* Computing 2nd power */\n    r__1 = gam;\n    *sd2 /= r__1 * r__1;\n    sh21 *= gam;\n    sh22 *= gam;\n    goto L200;\nL220:\n    if (sflag < 0.f) {\n\tgoto L250;\n    } else if (sflag == 0) {\n\tgoto L230;\n    } else {\n\tgoto L240;\n    }\nL230:\n    sparam[3] = sh21;\n    sparam[4] = sh12;\n    goto L260;\nL240:\n    sparam[2] = sh11;\n    sparam[5] = sh22;\n    goto L260;\nL250:\n    sparam[2] = sh11;\n    sparam[3] = sh21;\n    sparam[4] = sh12;\n    sparam[5] = sh22;\nL260:\n    sparam[1] = sflag;\n    return 0;\n} /* srotmg_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/ssbmv.c",
    "content": "/* ssbmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int ssbmv_(char *uplo, integer *n, integer *k, real *alpha, \n\treal *a, integer *lda, real *x, integer *incx, real *beta, real *y, \n\tinteger *incy, ftnlen uplo_len)\n{\n    /* System generated locals */\n    integer a_dim1, a_offset, i__1, i__2, i__3, i__4;\n\n    /* Local variables */\n    integer i__, j, l, ix, iy, jx, jy, kx, ky, info;\n    real temp1, temp2;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    integer kplus1;\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  SSBMV  performs the matrix-vector  operation */\n\n/*     y := alpha*A*x + beta*y, */\n\n/*  where alpha and beta are scalars, x and y are n element vectors and */\n/*  A is an n by n symmetric band matrix, with k super-diagonals. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the upper or lower */\n/*           triangular part of the band matrix A is being supplied as */\n/*           follows: */\n\n/*              UPLO = 'U' or 'u'   The upper triangular part of A is */\n/*                                  being supplied. */\n\n/*              UPLO = 'L' or 'l'   The lower triangular part of A is */\n/*                                  being supplied. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  K      - INTEGER. */\n/*           On entry, K specifies the number of super-diagonals of the */\n/*           matrix A. K must satisfy  0 .le. K. */\n/*           Unchanged on exit. */\n\n/*  ALPHA  - REAL            . */\n/*           On entry, ALPHA specifies the scalar alpha. */\n/*           Unchanged on exit. */\n\n/*  A      - REAL             array of DIMENSION ( LDA, n ). */\n/*           Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the upper triangular */\n/*           band part of the symmetric matrix, supplied column by */\n/*           column, with the leading diagonal of the matrix in row */\n/*           ( k + 1 ) of the array, the first super-diagonal starting at */\n/*           position 2 in row k, and so on. The top left k by k triangle */\n/*           of the array A is not referenced. */\n/*           The following program segment will transfer the upper */\n/*           triangular part of a symmetric band matrix from conventional */\n/*           full matrix storage to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = K + 1 - J */\n/*                    DO 10, I = MAX( 1, J - K ), J */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the lower triangular */\n/*           band part of the symmetric matrix, supplied column by */\n/*           column, with the leading diagonal of the matrix in row 1 of */\n/*           the array, the first sub-diagonal starting at position 1 in */\n/*           row 2, and so on. The bottom right k by k triangle of the */\n/*           array A is not referenced. */\n/*           The following program segment will transfer the lower */\n/*           triangular part of a symmetric band matrix from conventional */\n/*           full matrix storage to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = 1 - J */\n/*                    DO 10, I = J, MIN( N, J + K ) */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Unchanged on exit. */\n\n/*  LDA    - INTEGER. */\n/*           On entry, LDA specifies the first dimension of A as declared */\n/*           in the calling (sub) program. LDA must be at least */\n/*           ( k + 1 ). */\n/*           Unchanged on exit. */\n\n/*  X      - REAL             array of DIMENSION at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the */\n/*           vector x. */\n/*           Unchanged on exit. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  BETA   - REAL            . */\n/*           On entry, BETA specifies the scalar beta. */\n/*           Unchanged on exit. */\n\n/*  Y      - REAL             array of DIMENSION at least */\n/*           ( 1 + ( n - 1 )*abs( INCY ) ). */\n/*           Before entry, the incremented array Y must contain the */\n/*           vector y. On exit, Y is overwritten by the updated vector y. */\n\n/*  INCY   - INTEGER. */\n/*           On entry, INCY specifies the increment for the elements of */\n/*           Y. INCY must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    a_dim1 = *lda;\n    a_offset = 1 + a_dim1;\n    a -= a_offset;\n    --x;\n    --y;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (*n < 0) {\n\tinfo = 2;\n    } else if (*k < 0) {\n\tinfo = 3;\n    } else if (*lda < *k + 1) {\n\tinfo = 6;\n    } else if (*incx == 0) {\n\tinfo = 8;\n    } else if (*incy == 0) {\n\tinfo = 11;\n    }\n    if (info != 0) {\n\txerbla_(\"SSBMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0 || (*alpha == 0.f && *beta == 1.f)) {\n\treturn 0;\n    }\n\n/*     Set up the start points in  X  and  Y. */\n\n    if (*incx > 0) {\n\tkx = 1;\n    } else {\n\tkx = 1 - (*n - 1) * *incx;\n    }\n    if (*incy > 0) {\n\tky = 1;\n    } else {\n\tky = 1 - (*n - 1) * *incy;\n    }\n\n/*     Start the operations. In this version the elements of the array A */\n/*     are accessed sequentially with one pass through A. */\n\n/*     First form  y := beta*y. */\n\n    if (*beta != 1.f) {\n\tif (*incy == 1) {\n\t    if (*beta == 0.f) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[i__] = 0.f;\n/* L10: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[i__] = *beta * y[i__];\n/* L20: */\n\t\t}\n\t    }\n\t} else {\n\t    iy = ky;\n\t    if (*beta == 0.f) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[iy] = 0.f;\n\t\t    iy += *incy;\n/* L30: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[iy] = *beta * y[iy];\n\t\t    iy += *incy;\n/* L40: */\n\t\t}\n\t    }\n\t}\n    }\n    if (*alpha == 0.f) {\n\treturn 0;\n    }\n    if (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\n/*        Form  y  when upper triangle of A is stored. */\n\n\tkplus1 = *k + 1;\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[j];\n\t\ttemp2 = 0.f;\n\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\ti__2 = 1, i__3 = j - *k;\n\t\ti__4 = j - 1;\n\t\tfor (i__ = max(i__2,i__3); i__ <= i__4; ++i__) {\n\t\t    y[i__] += temp1 * a[l + i__ + j * a_dim1];\n\t\t    temp2 += a[l + i__ + j * a_dim1] * x[i__];\n/* L50: */\n\t\t}\n\t\ty[j] = y[j] + temp1 * a[kplus1 + j * a_dim1] + *alpha * temp2;\n/* L60: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[jx];\n\t\ttemp2 = 0.f;\n\t\tix = kx;\n\t\tiy = ky;\n\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\ti__4 = 1, i__2 = j - *k;\n\t\ti__3 = j - 1;\n\t\tfor (i__ = max(i__4,i__2); i__ <= i__3; ++i__) {\n\t\t    y[iy] += temp1 * a[l + i__ + j * a_dim1];\n\t\t    temp2 += a[l + i__ + j * a_dim1] * x[ix];\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n/* L70: */\n\t\t}\n\t\ty[jy] = y[jy] + temp1 * a[kplus1 + j * a_dim1] + *alpha * \n\t\t\ttemp2;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tif (j > *k) {\n\t\t    kx += *incx;\n\t\t    ky += *incy;\n\t\t}\n/* L80: */\n\t    }\n\t}\n    } else {\n\n/*        Form  y  when lower triangle of A is stored. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[j];\n\t\ttemp2 = 0.f;\n\t\ty[j] += temp1 * a[j * a_dim1 + 1];\n\t\tl = 1 - j;\n/* Computing MIN */\n\t\ti__4 = *n, i__2 = j + *k;\n\t\ti__3 = min(i__4,i__2);\n\t\tfor (i__ = j + 1; i__ <= i__3; ++i__) {\n\t\t    y[i__] += temp1 * a[l + i__ + j * a_dim1];\n\t\t    temp2 += a[l + i__ + j * a_dim1] * x[i__];\n/* L90: */\n\t\t}\n\t\ty[j] += *alpha * temp2;\n/* L100: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[jx];\n\t\ttemp2 = 0.f;\n\t\ty[jy] += temp1 * a[j * a_dim1 + 1];\n\t\tl = 1 - j;\n\t\tix = jx;\n\t\tiy = jy;\n/* Computing MIN */\n\t\ti__4 = *n, i__2 = j + *k;\n\t\ti__3 = min(i__4,i__2);\n\t\tfor (i__ = j + 1; i__ <= i__3; ++i__) {\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n\t\t    y[iy] += temp1 * a[l + i__ + j * a_dim1];\n\t\t    temp2 += a[l + i__ + j * a_dim1] * x[ix];\n/* L110: */\n\t\t}\n\t\ty[jy] += *alpha * temp2;\n\t\tjx += *incx;\n\t\tjy += *incy;\n/* L120: */\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of SSBMV . */\n\n} /* ssbmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/sspmv.c",
    "content": "/* sspmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int sspmv_(char *uplo, integer *n, real *alpha, real *ap, \n\treal *x, integer *incx, real *beta, real *y, integer *incy, ftnlen \n\tuplo_len)\n{\n    /* System generated locals */\n    integer i__1, i__2;\n\n    /* Local variables */\n    integer i__, j, k, kk, ix, iy, jx, jy, kx, ky, info;\n    real temp1, temp2;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  SSPMV  performs the matrix-vector operation */\n\n/*     y := alpha*A*x + beta*y, */\n\n/*  where alpha and beta are scalars, x and y are n element vectors and */\n/*  A is an n by n symmetric matrix, supplied in packed form. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the upper or lower */\n/*           triangular part of the matrix A is supplied in the packed */\n/*           array AP as follows: */\n\n/*              UPLO = 'U' or 'u'   The upper triangular part of A is */\n/*                                  supplied in AP. */\n\n/*              UPLO = 'L' or 'l'   The lower triangular part of A is */\n/*                                  supplied in AP. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  ALPHA  - REAL            . */\n/*           On entry, ALPHA specifies the scalar alpha. */\n/*           Unchanged on exit. */\n\n/*  AP     - REAL             array of DIMENSION at least */\n/*           ( ( n*( n + 1 ) )/2 ). */\n/*           Before entry with UPLO = 'U' or 'u', the array AP must */\n/*           contain the upper triangular part of the symmetric matrix */\n/*           packed sequentially, column by column, so that AP( 1 ) */\n/*           contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 1, 2 ) */\n/*           and a( 2, 2 ) respectively, and so on. */\n/*           Before entry with UPLO = 'L' or 'l', the array AP must */\n/*           contain the lower triangular part of the symmetric matrix */\n/*           packed sequentially, column by column, so that AP( 1 ) */\n/*           contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 2, 1 ) */\n/*           and a( 3, 1 ) respectively, and so on. */\n/*           Unchanged on exit. */\n\n/*  X      - REAL             array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the n */\n/*           element vector x. */\n/*           Unchanged on exit. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  BETA   - REAL            . */\n/*           On entry, BETA specifies the scalar beta. When BETA is */\n/*           supplied as zero then Y need not be set on input. */\n/*           Unchanged on exit. */\n\n/*  Y      - REAL             array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCY ) ). */\n/*           Before entry, the incremented array Y must contain the n */\n/*           element vector y. On exit, Y is overwritten by the updated */\n/*           vector y. */\n\n/*  INCY   - INTEGER. */\n/*           On entry, INCY specifies the increment for the elements of */\n/*           Y. INCY must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    --y;\n    --x;\n    --ap;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (*n < 0) {\n\tinfo = 2;\n    } else if (*incx == 0) {\n\tinfo = 6;\n    } else if (*incy == 0) {\n\tinfo = 9;\n    }\n    if (info != 0) {\n\txerbla_(\"SSPMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0 || (*alpha == 0.f && *beta == 1.f)) {\n\treturn 0;\n    }\n\n/*     Set up the start points in  X  and  Y. */\n\n    if (*incx > 0) {\n\tkx = 1;\n    } else {\n\tkx = 1 - (*n - 1) * *incx;\n    }\n    if (*incy > 0) {\n\tky = 1;\n    } else {\n\tky = 1 - (*n - 1) * *incy;\n    }\n\n/*     Start the operations. In this version the elements of the array AP */\n/*     are accessed sequentially with one pass through AP. */\n\n/*     First form  y := beta*y. */\n\n    if (*beta != 1.f) {\n\tif (*incy == 1) {\n\t    if (*beta == 0.f) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[i__] = 0.f;\n/* L10: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[i__] = *beta * y[i__];\n/* L20: */\n\t\t}\n\t    }\n\t} else {\n\t    iy = ky;\n\t    if (*beta == 0.f) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[iy] = 0.f;\n\t\t    iy += *incy;\n/* L30: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    y[iy] = *beta * y[iy];\n\t\t    iy += *incy;\n/* L40: */\n\t\t}\n\t    }\n\t}\n    }\n    if (*alpha == 0.f) {\n\treturn 0;\n    }\n    kk = 1;\n    if (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\n/*        Form  y  when AP contains the upper triangle. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[j];\n\t\ttemp2 = 0.f;\n\t\tk = kk;\n\t\ti__2 = j - 1;\n\t\tfor (i__ = 1; i__ <= i__2; ++i__) {\n\t\t    y[i__] += temp1 * ap[k];\n\t\t    temp2 += ap[k] * x[i__];\n\t\t    ++k;\n/* L50: */\n\t\t}\n\t\ty[j] = y[j] + temp1 * ap[kk + j - 1] + *alpha * temp2;\n\t\tkk += j;\n/* L60: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[jx];\n\t\ttemp2 = 0.f;\n\t\tix = kx;\n\t\tiy = ky;\n\t\ti__2 = kk + j - 2;\n\t\tfor (k = kk; k <= i__2; ++k) {\n\t\t    y[iy] += temp1 * ap[k];\n\t\t    temp2 += ap[k] * x[ix];\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n/* L70: */\n\t\t}\n\t\ty[jy] = y[jy] + temp1 * ap[kk + j - 1] + *alpha * temp2;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tkk += j;\n/* L80: */\n\t    }\n\t}\n    } else {\n\n/*        Form  y  when AP contains the lower triangle. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[j];\n\t\ttemp2 = 0.f;\n\t\ty[j] += temp1 * ap[kk];\n\t\tk = kk + 1;\n\t\ti__2 = *n;\n\t\tfor (i__ = j + 1; i__ <= i__2; ++i__) {\n\t\t    y[i__] += temp1 * ap[k];\n\t\t    temp2 += ap[k] * x[i__];\n\t\t    ++k;\n/* L90: */\n\t\t}\n\t\ty[j] += *alpha * temp2;\n\t\tkk += *n - j + 1;\n/* L100: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ttemp1 = *alpha * x[jx];\n\t\ttemp2 = 0.f;\n\t\ty[jy] += temp1 * ap[kk];\n\t\tix = jx;\n\t\tiy = jy;\n\t\ti__2 = kk + *n - j;\n\t\tfor (k = kk + 1; k <= i__2; ++k) {\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n\t\t    y[iy] += temp1 * ap[k];\n\t\t    temp2 += ap[k] * x[ix];\n/* L110: */\n\t\t}\n\t\ty[jy] += *alpha * temp2;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tkk += *n - j + 1;\n/* L120: */\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of SSPMV . */\n\n} /* sspmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/stbmv.c",
    "content": "/* stbmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int stbmv_(char *uplo, char *trans, char *diag, integer *n, \n\tinteger *k, real *a, integer *lda, real *x, integer *incx, ftnlen \n\tuplo_len, ftnlen trans_len, ftnlen diag_len)\n{\n    /* System generated locals */\n    integer a_dim1, a_offset, i__1, i__2, i__3, i__4;\n\n    /* Local variables */\n    integer i__, j, l, ix, jx, kx, info;\n    real temp;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    integer kplus1;\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n    logical nounit;\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  STBMV  performs one of the matrix-vector operations */\n\n/*     x := A*x,   or   x := A'*x, */\n\n/*  where x is an n element vector and  A is an n by n unit, or non-unit, */\n/*  upper or lower triangular band matrix, with ( k + 1 ) diagonals. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the matrix is an upper or */\n/*           lower triangular matrix as follows: */\n\n/*              UPLO = 'U' or 'u'   A is an upper triangular matrix. */\n\n/*              UPLO = 'L' or 'l'   A is a lower triangular matrix. */\n\n/*           Unchanged on exit. */\n\n/*  TRANS  - CHARACTER*1. */\n/*           On entry, TRANS specifies the operation to be performed as */\n/*           follows: */\n\n/*              TRANS = 'N' or 'n'   x := A*x. */\n\n/*              TRANS = 'T' or 't'   x := A'*x. */\n\n/*              TRANS = 'C' or 'c'   x := A'*x. */\n\n/*           Unchanged on exit. */\n\n/*  DIAG   - CHARACTER*1. */\n/*           On entry, DIAG specifies whether or not A is unit */\n/*           triangular as follows: */\n\n/*              DIAG = 'U' or 'u'   A is assumed to be unit triangular. */\n\n/*              DIAG = 'N' or 'n'   A is not assumed to be unit */\n/*                                  triangular. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  K      - INTEGER. */\n/*           On entry with UPLO = 'U' or 'u', K specifies the number of */\n/*           super-diagonals of the matrix A. */\n/*           On entry with UPLO = 'L' or 'l', K specifies the number of */\n/*           sub-diagonals of the matrix A. */\n/*           K must satisfy  0 .le. K. */\n/*           Unchanged on exit. */\n\n/*  A      - REAL             array of DIMENSION ( LDA, n ). */\n/*           Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the upper triangular */\n/*           band part of the matrix of coefficients, supplied column by */\n/*           column, with the leading diagonal of the matrix in row */\n/*           ( k + 1 ) of the array, the first super-diagonal starting at */\n/*           position 2 in row k, and so on. The top left k by k triangle */\n/*           of the array A is not referenced. */\n/*           The following program segment will transfer an upper */\n/*           triangular band matrix from conventional full matrix storage */\n/*           to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = K + 1 - J */\n/*                    DO 10, I = MAX( 1, J - K ), J */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the lower triangular */\n/*           band part of the matrix of coefficients, supplied column by */\n/*           column, with the leading diagonal of the matrix in row 1 of */\n/*           the array, the first sub-diagonal starting at position 1 in */\n/*           row 2, and so on. The bottom right k by k triangle of the */\n/*           array A is not referenced. */\n/*           The following program segment will transfer a lower */\n/*           triangular band matrix from conventional full matrix storage */\n/*           to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = 1 - J */\n/*                    DO 10, I = J, MIN( N, J + K ) */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Note that when DIAG = 'U' or 'u' the elements of the array A */\n/*           corresponding to the diagonal elements of the matrix are not */\n/*           referenced, but are assumed to be unity. */\n/*           Unchanged on exit. */\n\n/*  LDA    - INTEGER. */\n/*           On entry, LDA specifies the first dimension of A as declared */\n/*           in the calling (sub) program. LDA must be at least */\n/*           ( k + 1 ). */\n/*           Unchanged on exit. */\n\n/*  X      - REAL             array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the n */\n/*           element vector x. On exit, X is overwritten with the */\n/*           transformed vector x. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    a_dim1 = *lda;\n    a_offset = 1 + a_dim1;\n    a -= a_offset;\n    --x;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (! lsame_(trans, \"N\", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, \n\t    \"T\", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, \"C\", (ftnlen)1, (\n\t    ftnlen)1)) {\n\tinfo = 2;\n    } else if (! lsame_(diag, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(diag, \n\t    \"N\", (ftnlen)1, (ftnlen)1)) {\n\tinfo = 3;\n    } else if (*n < 0) {\n\tinfo = 4;\n    } else if (*k < 0) {\n\tinfo = 5;\n    } else if (*lda < *k + 1) {\n\tinfo = 7;\n    } else if (*incx == 0) {\n\tinfo = 9;\n    }\n    if (info != 0) {\n\txerbla_(\"STBMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0) {\n\treturn 0;\n    }\n\n    nounit = lsame_(diag, \"N\", (ftnlen)1, (ftnlen)1);\n\n/*     Set up the start point in X if the increment is not unity. This */\n/*     will be  ( N - 1 )*INCX   too small for descending loops. */\n\n    if (*incx <= 0) {\n\tkx = 1 - (*n - 1) * *incx;\n    } else if (*incx != 1) {\n\tkx = 1;\n    }\n\n/*     Start the operations. In this version the elements of A are */\n/*     accessed sequentially with one pass through A. */\n\n    if (lsame_(trans, \"N\", (ftnlen)1, (ftnlen)1)) {\n\n/*         Form  x := A*x. */\n\n\tif (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\t    kplus1 = *k + 1;\n\t    if (*incx == 1) {\n\t\ti__1 = *n;\n\t\tfor (j = 1; j <= i__1; ++j) {\n\t\t    if (x[j] != 0.f) {\n\t\t\ttemp = x[j];\n\t\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\t\ti__2 = 1, i__3 = j - *k;\n\t\t\ti__4 = j - 1;\n\t\t\tfor (i__ = max(i__2,i__3); i__ <= i__4; ++i__) {\n\t\t\t    x[i__] += temp * a[l + i__ + j * a_dim1];\n/* L10: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    x[j] *= a[kplus1 + j * a_dim1];\n\t\t\t}\n\t\t    }\n/* L20: */\n\t\t}\n\t    } else {\n\t\tjx = kx;\n\t\ti__1 = *n;\n\t\tfor (j = 1; j <= i__1; ++j) {\n\t\t    if (x[jx] != 0.f) {\n\t\t\ttemp = x[jx];\n\t\t\tix = kx;\n\t\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\t\ti__4 = 1, i__2 = j - *k;\n\t\t\ti__3 = j - 1;\n\t\t\tfor (i__ = max(i__4,i__2); i__ <= i__3; ++i__) {\n\t\t\t    x[ix] += temp * a[l + i__ + j * a_dim1];\n\t\t\t    ix += *incx;\n/* L30: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    x[jx] *= a[kplus1 + j * a_dim1];\n\t\t\t}\n\t\t    }\n\t\t    jx += *incx;\n\t\t    if (j > *k) {\n\t\t\tkx += *incx;\n\t\t    }\n/* L40: */\n\t\t}\n\t    }\n\t} else {\n\t    if (*incx == 1) {\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    if (x[j] != 0.f) {\n\t\t\ttemp = x[j];\n\t\t\tl = 1 - j;\n/* Computing MIN */\n\t\t\ti__1 = *n, i__3 = j + *k;\n\t\t\ti__4 = j + 1;\n\t\t\tfor (i__ = min(i__1,i__3); i__ >= i__4; --i__) {\n\t\t\t    x[i__] += temp * a[l + i__ + j * a_dim1];\n/* L50: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    x[j] *= a[j * a_dim1 + 1];\n\t\t\t}\n\t\t    }\n/* L60: */\n\t\t}\n\t    } else {\n\t\tkx += (*n - 1) * *incx;\n\t\tjx = kx;\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    if (x[jx] != 0.f) {\n\t\t\ttemp = x[jx];\n\t\t\tix = kx;\n\t\t\tl = 1 - j;\n/* Computing MIN */\n\t\t\ti__4 = *n, i__1 = j + *k;\n\t\t\ti__3 = j + 1;\n\t\t\tfor (i__ = min(i__4,i__1); i__ >= i__3; --i__) {\n\t\t\t    x[ix] += temp * a[l + i__ + j * a_dim1];\n\t\t\t    ix -= *incx;\n/* L70: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    x[jx] *= a[j * a_dim1 + 1];\n\t\t\t}\n\t\t    }\n\t\t    jx -= *incx;\n\t\t    if (*n - j >= *k) {\n\t\t\tkx -= *incx;\n\t\t    }\n/* L80: */\n\t\t}\n\t    }\n\t}\n    } else {\n\n/*        Form  x := A'*x. */\n\n\tif (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\t    kplus1 = *k + 1;\n\t    if (*incx == 1) {\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    temp = x[j];\n\t\t    l = kplus1 - j;\n\t\t    if (nounit) {\n\t\t\ttemp *= a[kplus1 + j * a_dim1];\n\t\t    }\n/* Computing MAX */\n\t\t    i__4 = 1, i__1 = j - *k;\n\t\t    i__3 = max(i__4,i__1);\n\t\t    for (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\ttemp += a[l + i__ + j * a_dim1] * x[i__];\n/* L90: */\n\t\t    }\n\t\t    x[j] = temp;\n/* L100: */\n\t\t}\n\t    } else {\n\t\tkx += (*n - 1) * *incx;\n\t\tjx = kx;\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    temp = x[jx];\n\t\t    kx -= *incx;\n\t\t    ix = kx;\n\t\t    l = kplus1 - j;\n\t\t    if (nounit) {\n\t\t\ttemp *= a[kplus1 + j * a_dim1];\n\t\t    }\n/* Computing MAX */\n\t\t    i__4 = 1, i__1 = j - *k;\n\t\t    i__3 = max(i__4,i__1);\n\t\t    for (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\ttemp += a[l + i__ + j * a_dim1] * x[ix];\n\t\t\tix -= *incx;\n/* L110: */\n\t\t    }\n\t\t    x[jx] = temp;\n\t\t    jx -= *incx;\n/* L120: */\n\t\t}\n\t    }\n\t} else {\n\t    if (*incx == 1) {\n\t\ti__3 = *n;\n\t\tfor (j = 1; j <= i__3; ++j) {\n\t\t    temp = x[j];\n\t\t    l = 1 - j;\n\t\t    if (nounit) {\n\t\t\ttemp *= a[j * a_dim1 + 1];\n\t\t    }\n/* Computing MIN */\n\t\t    i__1 = *n, i__2 = j + *k;\n\t\t    i__4 = min(i__1,i__2);\n\t\t    for (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\ttemp += a[l + i__ + j * a_dim1] * x[i__];\n/* L130: */\n\t\t    }\n\t\t    x[j] = temp;\n/* L140: */\n\t\t}\n\t    } else {\n\t\tjx = kx;\n\t\ti__3 = *n;\n\t\tfor (j = 1; j <= i__3; ++j) {\n\t\t    temp = x[jx];\n\t\t    kx += *incx;\n\t\t    ix = kx;\n\t\t    l = 1 - j;\n\t\t    if (nounit) {\n\t\t\ttemp *= a[j * a_dim1 + 1];\n\t\t    }\n/* Computing MIN */\n\t\t    i__1 = *n, i__2 = j + *k;\n\t\t    i__4 = min(i__1,i__2);\n\t\t    for (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\ttemp += a[l + i__ + j * a_dim1] * x[ix];\n\t\t\tix += *incx;\n/* L150: */\n\t\t    }\n\t\t    x[jx] = temp;\n\t\t    jx += *incx;\n/* L160: */\n\t\t}\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of STBMV . */\n\n} /* stbmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/zhbmv.c",
    "content": "/* zhbmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int zhbmv_(char *uplo, integer *n, integer *k, doublecomplex \n\t*alpha, doublecomplex *a, integer *lda, doublecomplex *x, integer *\n\tincx, doublecomplex *beta, doublecomplex *y, integer *incy, ftnlen \n\tuplo_len)\n{\n    /* System generated locals */\n    integer a_dim1, a_offset, i__1, i__2, i__3, i__4, i__5;\n    doublereal d__1;\n    doublecomplex z__1, z__2, z__3, z__4;\n\n    /* Builtin functions */\n    void d_cnjg(doublecomplex *, doublecomplex *);\n\n    /* Local variables */\n    integer i__, j, l, ix, iy, jx, jy, kx, ky, info;\n    doublecomplex temp1, temp2;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    integer kplus1;\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  ZHBMV  performs the matrix-vector  operation */\n\n/*     y := alpha*A*x + beta*y, */\n\n/*  where alpha and beta are scalars, x and y are n element vectors and */\n/*  A is an n by n hermitian band matrix, with k super-diagonals. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the upper or lower */\n/*           triangular part of the band matrix A is being supplied as */\n/*           follows: */\n\n/*              UPLO = 'U' or 'u'   The upper triangular part of A is */\n/*                                  being supplied. */\n\n/*              UPLO = 'L' or 'l'   The lower triangular part of A is */\n/*                                  being supplied. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  K      - INTEGER. */\n/*           On entry, K specifies the number of super-diagonals of the */\n/*           matrix A. K must satisfy  0 .le. K. */\n/*           Unchanged on exit. */\n\n/*  ALPHA  - COMPLEX*16      . */\n/*           On entry, ALPHA specifies the scalar alpha. */\n/*           Unchanged on exit. */\n\n/*  A      - COMPLEX*16       array of DIMENSION ( LDA, n ). */\n/*           Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the upper triangular */\n/*           band part of the hermitian matrix, supplied column by */\n/*           column, with the leading diagonal of the matrix in row */\n/*           ( k + 1 ) of the array, the first super-diagonal starting at */\n/*           position 2 in row k, and so on. The top left k by k triangle */\n/*           of the array A is not referenced. */\n/*           The following program segment will transfer the upper */\n/*           triangular part of a hermitian band matrix from conventional */\n/*           full matrix storage to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = K + 1 - J */\n/*                    DO 10, I = MAX( 1, J - K ), J */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the lower triangular */\n/*           band part of the hermitian matrix, supplied column by */\n/*           column, with the leading diagonal of the matrix in row 1 of */\n/*           the array, the first sub-diagonal starting at position 1 in */\n/*           row 2, and so on. The bottom right k by k triangle of the */\n/*           array A is not referenced. */\n/*           The following program segment will transfer the lower */\n/*           triangular part of a hermitian band matrix from conventional */\n/*           full matrix storage to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = 1 - J */\n/*                    DO 10, I = J, MIN( N, J + K ) */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Note that the imaginary parts of the diagonal elements need */\n/*           not be set and are assumed to be zero. */\n/*           Unchanged on exit. */\n\n/*  LDA    - INTEGER. */\n/*           On entry, LDA specifies the first dimension of A as declared */\n/*           in the calling (sub) program. LDA must be at least */\n/*           ( k + 1 ). */\n/*           Unchanged on exit. */\n\n/*  X      - COMPLEX*16       array of DIMENSION at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the */\n/*           vector x. */\n/*           Unchanged on exit. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  BETA   - COMPLEX*16      . */\n/*           On entry, BETA specifies the scalar beta. */\n/*           Unchanged on exit. */\n\n/*  Y      - COMPLEX*16       array of DIMENSION at least */\n/*           ( 1 + ( n - 1 )*abs( INCY ) ). */\n/*           Before entry, the incremented array Y must contain the */\n/*           vector y. On exit, Y is overwritten by the updated vector y. */\n\n/*  INCY   - INTEGER. */\n/*           On entry, INCY specifies the increment for the elements of */\n/*           Y. INCY must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    a_dim1 = *lda;\n    a_offset = 1 + a_dim1;\n    a -= a_offset;\n    --x;\n    --y;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (*n < 0) {\n\tinfo = 2;\n    } else if (*k < 0) {\n\tinfo = 3;\n    } else if (*lda < *k + 1) {\n\tinfo = 6;\n    } else if (*incx == 0) {\n\tinfo = 8;\n    } else if (*incy == 0) {\n\tinfo = 11;\n    }\n    if (info != 0) {\n\txerbla_(\"ZHBMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0 || (alpha->r == 0. && alpha->i == 0. && (beta->r == 1. && \n                                                         beta->i == 0.))) {\n\treturn 0;\n    }\n\n/*     Set up the start points in  X  and  Y. */\n\n    if (*incx > 0) {\n\tkx = 1;\n    } else {\n\tkx = 1 - (*n - 1) * *incx;\n    }\n    if (*incy > 0) {\n\tky = 1;\n    } else {\n\tky = 1 - (*n - 1) * *incy;\n    }\n\n/*     Start the operations. In this version the elements of the array A */\n/*     are accessed sequentially with one pass through A. */\n\n/*     First form  y := beta*y. */\n\n    if (beta->r != 1. || beta->i != 0.) {\n\tif (*incy == 1) {\n\t    if (beta->r == 0. && beta->i == 0.) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = i__;\n\t\t    y[i__2].r = 0., y[i__2].i = 0.;\n/* L10: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = i__;\n\t\t    i__3 = i__;\n\t\t    z__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, \n\t\t\t    z__1.i = beta->r * y[i__3].i + beta->i * y[i__3]\n\t\t\t    .r;\n\t\t    y[i__2].r = z__1.r, y[i__2].i = z__1.i;\n/* L20: */\n\t\t}\n\t    }\n\t} else {\n\t    iy = ky;\n\t    if (beta->r == 0. && beta->i == 0.) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = iy;\n\t\t    y[i__2].r = 0., y[i__2].i = 0.;\n\t\t    iy += *incy;\n/* L30: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = iy;\n\t\t    i__3 = iy;\n\t\t    z__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, \n\t\t\t    z__1.i = beta->r * y[i__3].i + beta->i * y[i__3]\n\t\t\t    .r;\n\t\t    y[i__2].r = z__1.r, y[i__2].i = z__1.i;\n\t\t    iy += *incy;\n/* L40: */\n\t\t}\n\t    }\n\t}\n    }\n    if (alpha->r == 0. && alpha->i == 0.) {\n\treturn 0;\n    }\n    if (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\n/*        Form  y  when upper triangle of A is stored. */\n\n\tkplus1 = *k + 1;\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__2 = j;\n\t\tz__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, z__1.i =\n\t\t\t alpha->r * x[i__2].i + alpha->i * x[i__2].r;\n\t\ttemp1.r = z__1.r, temp1.i = z__1.i;\n\t\ttemp2.r = 0., temp2.i = 0.;\n\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\ti__2 = 1, i__3 = j - *k;\n\t\ti__4 = j - 1;\n\t\tfor (i__ = max(i__2,i__3); i__ <= i__4; ++i__) {\n\t\t    i__2 = i__;\n\t\t    i__3 = i__;\n\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t    z__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, \n\t\t\t    z__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5]\n\t\t\t    .r;\n\t\t    z__1.r = y[i__3].r + z__2.r, z__1.i = y[i__3].i + z__2.i;\n\t\t    y[i__2].r = z__1.r, y[i__2].i = z__1.i;\n\t\t    d_cnjg(&z__3, &a[l + i__ + j * a_dim1]);\n\t\t    i__2 = i__;\n\t\t    z__2.r = z__3.r * x[i__2].r - z__3.i * x[i__2].i, z__2.i =\n\t\t\t     z__3.r * x[i__2].i + z__3.i * x[i__2].r;\n\t\t    z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i;\n\t\t    temp2.r = z__1.r, temp2.i = z__1.i;\n/* L50: */\n\t\t}\n\t\ti__4 = j;\n\t\ti__2 = j;\n\t\ti__3 = kplus1 + j * a_dim1;\n\t\td__1 = a[i__3].r;\n\t\tz__3.r = d__1 * temp1.r, z__3.i = d__1 * temp1.i;\n\t\tz__2.r = y[i__2].r + z__3.r, z__2.i = y[i__2].i + z__3.i;\n\t\tz__4.r = alpha->r * temp2.r - alpha->i * temp2.i, z__4.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tz__1.r = z__2.r + z__4.r, z__1.i = z__2.i + z__4.i;\n\t\ty[i__4].r = z__1.r, y[i__4].i = z__1.i;\n/* L60: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__4 = jx;\n\t\tz__1.r = alpha->r * x[i__4].r - alpha->i * x[i__4].i, z__1.i =\n\t\t\t alpha->r * x[i__4].i + alpha->i * x[i__4].r;\n\t\ttemp1.r = z__1.r, temp1.i = z__1.i;\n\t\ttemp2.r = 0., temp2.i = 0.;\n\t\tix = kx;\n\t\tiy = ky;\n\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\ti__4 = 1, i__2 = j - *k;\n\t\ti__3 = j - 1;\n\t\tfor (i__ = max(i__4,i__2); i__ <= i__3; ++i__) {\n\t\t    i__4 = iy;\n\t\t    i__2 = iy;\n\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t    z__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, \n\t\t\t    z__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5]\n\t\t\t    .r;\n\t\t    z__1.r = y[i__2].r + z__2.r, z__1.i = y[i__2].i + z__2.i;\n\t\t    y[i__4].r = z__1.r, y[i__4].i = z__1.i;\n\t\t    d_cnjg(&z__3, &a[l + i__ + j * a_dim1]);\n\t\t    i__4 = ix;\n\t\t    z__2.r = z__3.r * x[i__4].r - z__3.i * x[i__4].i, z__2.i =\n\t\t\t     z__3.r * x[i__4].i + z__3.i * x[i__4].r;\n\t\t    z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i;\n\t\t    temp2.r = z__1.r, temp2.i = z__1.i;\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n/* L70: */\n\t\t}\n\t\ti__3 = jy;\n\t\ti__4 = jy;\n\t\ti__2 = kplus1 + j * a_dim1;\n\t\td__1 = a[i__2].r;\n\t\tz__3.r = d__1 * temp1.r, z__3.i = d__1 * temp1.i;\n\t\tz__2.r = y[i__4].r + z__3.r, z__2.i = y[i__4].i + z__3.i;\n\t\tz__4.r = alpha->r * temp2.r - alpha->i * temp2.i, z__4.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tz__1.r = z__2.r + z__4.r, z__1.i = z__2.i + z__4.i;\n\t\ty[i__3].r = z__1.r, y[i__3].i = z__1.i;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tif (j > *k) {\n\t\t    kx += *incx;\n\t\t    ky += *incy;\n\t\t}\n/* L80: */\n\t    }\n\t}\n    } else {\n\n/*        Form  y  when lower triangle of A is stored. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__3 = j;\n\t\tz__1.r = alpha->r * x[i__3].r - alpha->i * x[i__3].i, z__1.i =\n\t\t\t alpha->r * x[i__3].i + alpha->i * x[i__3].r;\n\t\ttemp1.r = z__1.r, temp1.i = z__1.i;\n\t\ttemp2.r = 0., temp2.i = 0.;\n\t\ti__3 = j;\n\t\ti__4 = j;\n\t\ti__2 = j * a_dim1 + 1;\n\t\td__1 = a[i__2].r;\n\t\tz__2.r = d__1 * temp1.r, z__2.i = d__1 * temp1.i;\n\t\tz__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i;\n\t\ty[i__3].r = z__1.r, y[i__3].i = z__1.i;\n\t\tl = 1 - j;\n/* Computing MIN */\n\t\ti__4 = *n, i__2 = j + *k;\n\t\ti__3 = min(i__4,i__2);\n\t\tfor (i__ = j + 1; i__ <= i__3; ++i__) {\n\t\t    i__4 = i__;\n\t\t    i__2 = i__;\n\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t    z__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, \n\t\t\t    z__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5]\n\t\t\t    .r;\n\t\t    z__1.r = y[i__2].r + z__2.r, z__1.i = y[i__2].i + z__2.i;\n\t\t    y[i__4].r = z__1.r, y[i__4].i = z__1.i;\n\t\t    d_cnjg(&z__3, &a[l + i__ + j * a_dim1]);\n\t\t    i__4 = i__;\n\t\t    z__2.r = z__3.r * x[i__4].r - z__3.i * x[i__4].i, z__2.i =\n\t\t\t     z__3.r * x[i__4].i + z__3.i * x[i__4].r;\n\t\t    z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i;\n\t\t    temp2.r = z__1.r, temp2.i = z__1.i;\n/* L90: */\n\t\t}\n\t\ti__3 = j;\n\t\ti__4 = j;\n\t\tz__2.r = alpha->r * temp2.r - alpha->i * temp2.i, z__2.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tz__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i;\n\t\ty[i__3].r = z__1.r, y[i__3].i = z__1.i;\n/* L100: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__3 = jx;\n\t\tz__1.r = alpha->r * x[i__3].r - alpha->i * x[i__3].i, z__1.i =\n\t\t\t alpha->r * x[i__3].i + alpha->i * x[i__3].r;\n\t\ttemp1.r = z__1.r, temp1.i = z__1.i;\n\t\ttemp2.r = 0., temp2.i = 0.;\n\t\ti__3 = jy;\n\t\ti__4 = jy;\n\t\ti__2 = j * a_dim1 + 1;\n\t\td__1 = a[i__2].r;\n\t\tz__2.r = d__1 * temp1.r, z__2.i = d__1 * temp1.i;\n\t\tz__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i;\n\t\ty[i__3].r = z__1.r, y[i__3].i = z__1.i;\n\t\tl = 1 - j;\n\t\tix = jx;\n\t\tiy = jy;\n/* Computing MIN */\n\t\ti__4 = *n, i__2 = j + *k;\n\t\ti__3 = min(i__4,i__2);\n\t\tfor (i__ = j + 1; i__ <= i__3; ++i__) {\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n\t\t    i__4 = iy;\n\t\t    i__2 = iy;\n\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t    z__2.r = temp1.r * a[i__5].r - temp1.i * a[i__5].i, \n\t\t\t    z__2.i = temp1.r * a[i__5].i + temp1.i * a[i__5]\n\t\t\t    .r;\n\t\t    z__1.r = y[i__2].r + z__2.r, z__1.i = y[i__2].i + z__2.i;\n\t\t    y[i__4].r = z__1.r, y[i__4].i = z__1.i;\n\t\t    d_cnjg(&z__3, &a[l + i__ + j * a_dim1]);\n\t\t    i__4 = ix;\n\t\t    z__2.r = z__3.r * x[i__4].r - z__3.i * x[i__4].i, z__2.i =\n\t\t\t     z__3.r * x[i__4].i + z__3.i * x[i__4].r;\n\t\t    z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i;\n\t\t    temp2.r = z__1.r, temp2.i = z__1.i;\n/* L110: */\n\t\t}\n\t\ti__3 = jy;\n\t\ti__4 = jy;\n\t\tz__2.r = alpha->r * temp2.r - alpha->i * temp2.i, z__2.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tz__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i;\n\t\ty[i__3].r = z__1.r, y[i__3].i = z__1.i;\n\t\tjx += *incx;\n\t\tjy += *incy;\n/* L120: */\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of ZHBMV . */\n\n} /* zhbmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/zhpmv.c",
    "content": "/* zhpmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int zhpmv_(char *uplo, integer *n, doublecomplex *alpha, \n\tdoublecomplex *ap, doublecomplex *x, integer *incx, doublecomplex *\n\tbeta, doublecomplex *y, integer *incy, ftnlen uplo_len)\n{\n    /* System generated locals */\n    integer i__1, i__2, i__3, i__4, i__5;\n    doublereal d__1;\n    doublecomplex z__1, z__2, z__3, z__4;\n\n    /* Builtin functions */\n    void d_cnjg(doublecomplex *, doublecomplex *);\n\n    /* Local variables */\n    integer i__, j, k, kk, ix, iy, jx, jy, kx, ky, info;\n    doublecomplex temp1, temp2;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  ZHPMV  performs the matrix-vector operation */\n\n/*     y := alpha*A*x + beta*y, */\n\n/*  where alpha and beta are scalars, x and y are n element vectors and */\n/*  A is an n by n hermitian matrix, supplied in packed form. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the upper or lower */\n/*           triangular part of the matrix A is supplied in the packed */\n/*           array AP as follows: */\n\n/*              UPLO = 'U' or 'u'   The upper triangular part of A is */\n/*                                  supplied in AP. */\n\n/*              UPLO = 'L' or 'l'   The lower triangular part of A is */\n/*                                  supplied in AP. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  ALPHA  - COMPLEX*16      . */\n/*           On entry, ALPHA specifies the scalar alpha. */\n/*           Unchanged on exit. */\n\n/*  AP     - COMPLEX*16       array of DIMENSION at least */\n/*           ( ( n*( n + 1 ) )/2 ). */\n/*           Before entry with UPLO = 'U' or 'u', the array AP must */\n/*           contain the upper triangular part of the hermitian matrix */\n/*           packed sequentially, column by column, so that AP( 1 ) */\n/*           contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 1, 2 ) */\n/*           and a( 2, 2 ) respectively, and so on. */\n/*           Before entry with UPLO = 'L' or 'l', the array AP must */\n/*           contain the lower triangular part of the hermitian matrix */\n/*           packed sequentially, column by column, so that AP( 1 ) */\n/*           contains a( 1, 1 ), AP( 2 ) and AP( 3 ) contain a( 2, 1 ) */\n/*           and a( 3, 1 ) respectively, and so on. */\n/*           Note that the imaginary parts of the diagonal elements need */\n/*           not be set and are assumed to be zero. */\n/*           Unchanged on exit. */\n\n/*  X      - COMPLEX*16       array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the n */\n/*           element vector x. */\n/*           Unchanged on exit. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  BETA   - COMPLEX*16      . */\n/*           On entry, BETA specifies the scalar beta. When BETA is */\n/*           supplied as zero then Y need not be set on input. */\n/*           Unchanged on exit. */\n\n/*  Y      - COMPLEX*16       array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCY ) ). */\n/*           Before entry, the incremented array Y must contain the n */\n/*           element vector y. On exit, Y is overwritten by the updated */\n/*           vector y. */\n\n/*  INCY   - INTEGER. */\n/*           On entry, INCY specifies the increment for the elements of */\n/*           Y. INCY must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    --y;\n    --x;\n    --ap;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (*n < 0) {\n\tinfo = 2;\n    } else if (*incx == 0) {\n\tinfo = 6;\n    } else if (*incy == 0) {\n\tinfo = 9;\n    }\n    if (info != 0) {\n\txerbla_(\"ZHPMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0 || (alpha->r == 0. && alpha->i == 0. && (beta->r == 1. && \n                                                         beta->i == 0.))) {\n\treturn 0;\n    }\n\n/*     Set up the start points in  X  and  Y. */\n\n    if (*incx > 0) {\n\tkx = 1;\n    } else {\n\tkx = 1 - (*n - 1) * *incx;\n    }\n    if (*incy > 0) {\n\tky = 1;\n    } else {\n\tky = 1 - (*n - 1) * *incy;\n    }\n\n/*     Start the operations. In this version the elements of the array AP */\n/*     are accessed sequentially with one pass through AP. */\n\n/*     First form  y := beta*y. */\n\n    if (beta->r != 1. || beta->i != 0.) {\n\tif (*incy == 1) {\n\t    if (beta->r == 0. && beta->i == 0.) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = i__;\n\t\t    y[i__2].r = 0., y[i__2].i = 0.;\n/* L10: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = i__;\n\t\t    i__3 = i__;\n\t\t    z__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, \n\t\t\t    z__1.i = beta->r * y[i__3].i + beta->i * y[i__3]\n\t\t\t    .r;\n\t\t    y[i__2].r = z__1.r, y[i__2].i = z__1.i;\n/* L20: */\n\t\t}\n\t    }\n\t} else {\n\t    iy = ky;\n\t    if (beta->r == 0. && beta->i == 0.) {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = iy;\n\t\t    y[i__2].r = 0., y[i__2].i = 0.;\n\t\t    iy += *incy;\n/* L30: */\n\t\t}\n\t    } else {\n\t\ti__1 = *n;\n\t\tfor (i__ = 1; i__ <= i__1; ++i__) {\n\t\t    i__2 = iy;\n\t\t    i__3 = iy;\n\t\t    z__1.r = beta->r * y[i__3].r - beta->i * y[i__3].i, \n\t\t\t    z__1.i = beta->r * y[i__3].i + beta->i * y[i__3]\n\t\t\t    .r;\n\t\t    y[i__2].r = z__1.r, y[i__2].i = z__1.i;\n\t\t    iy += *incy;\n/* L40: */\n\t\t}\n\t    }\n\t}\n    }\n    if (alpha->r == 0. && alpha->i == 0.) {\n\treturn 0;\n    }\n    kk = 1;\n    if (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\n/*        Form  y  when AP contains the upper triangle. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__2 = j;\n\t\tz__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, z__1.i =\n\t\t\t alpha->r * x[i__2].i + alpha->i * x[i__2].r;\n\t\ttemp1.r = z__1.r, temp1.i = z__1.i;\n\t\ttemp2.r = 0., temp2.i = 0.;\n\t\tk = kk;\n\t\ti__2 = j - 1;\n\t\tfor (i__ = 1; i__ <= i__2; ++i__) {\n\t\t    i__3 = i__;\n\t\t    i__4 = i__;\n\t\t    i__5 = k;\n\t\t    z__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, \n\t\t\t    z__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5]\n\t\t\t    .r;\n\t\t    z__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i;\n\t\t    y[i__3].r = z__1.r, y[i__3].i = z__1.i;\n\t\t    d_cnjg(&z__3, &ap[k]);\n\t\t    i__3 = i__;\n\t\t    z__2.r = z__3.r * x[i__3].r - z__3.i * x[i__3].i, z__2.i =\n\t\t\t     z__3.r * x[i__3].i + z__3.i * x[i__3].r;\n\t\t    z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i;\n\t\t    temp2.r = z__1.r, temp2.i = z__1.i;\n\t\t    ++k;\n/* L50: */\n\t\t}\n\t\ti__2 = j;\n\t\ti__3 = j;\n\t\ti__4 = kk + j - 1;\n\t\td__1 = ap[i__4].r;\n\t\tz__3.r = d__1 * temp1.r, z__3.i = d__1 * temp1.i;\n\t\tz__2.r = y[i__3].r + z__3.r, z__2.i = y[i__3].i + z__3.i;\n\t\tz__4.r = alpha->r * temp2.r - alpha->i * temp2.i, z__4.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tz__1.r = z__2.r + z__4.r, z__1.i = z__2.i + z__4.i;\n\t\ty[i__2].r = z__1.r, y[i__2].i = z__1.i;\n\t\tkk += j;\n/* L60: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__2 = jx;\n\t\tz__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, z__1.i =\n\t\t\t alpha->r * x[i__2].i + alpha->i * x[i__2].r;\n\t\ttemp1.r = z__1.r, temp1.i = z__1.i;\n\t\ttemp2.r = 0., temp2.i = 0.;\n\t\tix = kx;\n\t\tiy = ky;\n\t\ti__2 = kk + j - 2;\n\t\tfor (k = kk; k <= i__2; ++k) {\n\t\t    i__3 = iy;\n\t\t    i__4 = iy;\n\t\t    i__5 = k;\n\t\t    z__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, \n\t\t\t    z__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5]\n\t\t\t    .r;\n\t\t    z__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i;\n\t\t    y[i__3].r = z__1.r, y[i__3].i = z__1.i;\n\t\t    d_cnjg(&z__3, &ap[k]);\n\t\t    i__3 = ix;\n\t\t    z__2.r = z__3.r * x[i__3].r - z__3.i * x[i__3].i, z__2.i =\n\t\t\t     z__3.r * x[i__3].i + z__3.i * x[i__3].r;\n\t\t    z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i;\n\t\t    temp2.r = z__1.r, temp2.i = z__1.i;\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n/* L70: */\n\t\t}\n\t\ti__2 = jy;\n\t\ti__3 = jy;\n\t\ti__4 = kk + j - 1;\n\t\td__1 = ap[i__4].r;\n\t\tz__3.r = d__1 * temp1.r, z__3.i = d__1 * temp1.i;\n\t\tz__2.r = y[i__3].r + z__3.r, z__2.i = y[i__3].i + z__3.i;\n\t\tz__4.r = alpha->r * temp2.r - alpha->i * temp2.i, z__4.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tz__1.r = z__2.r + z__4.r, z__1.i = z__2.i + z__4.i;\n\t\ty[i__2].r = z__1.r, y[i__2].i = z__1.i;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tkk += j;\n/* L80: */\n\t    }\n\t}\n    } else {\n\n/*        Form  y  when AP contains the lower triangle. */\n\n\tif (*incx == 1 && *incy == 1) {\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__2 = j;\n\t\tz__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, z__1.i =\n\t\t\t alpha->r * x[i__2].i + alpha->i * x[i__2].r;\n\t\ttemp1.r = z__1.r, temp1.i = z__1.i;\n\t\ttemp2.r = 0., temp2.i = 0.;\n\t\ti__2 = j;\n\t\ti__3 = j;\n\t\ti__4 = kk;\n\t\td__1 = ap[i__4].r;\n\t\tz__2.r = d__1 * temp1.r, z__2.i = d__1 * temp1.i;\n\t\tz__1.r = y[i__3].r + z__2.r, z__1.i = y[i__3].i + z__2.i;\n\t\ty[i__2].r = z__1.r, y[i__2].i = z__1.i;\n\t\tk = kk + 1;\n\t\ti__2 = *n;\n\t\tfor (i__ = j + 1; i__ <= i__2; ++i__) {\n\t\t    i__3 = i__;\n\t\t    i__4 = i__;\n\t\t    i__5 = k;\n\t\t    z__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, \n\t\t\t    z__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5]\n\t\t\t    .r;\n\t\t    z__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i;\n\t\t    y[i__3].r = z__1.r, y[i__3].i = z__1.i;\n\t\t    d_cnjg(&z__3, &ap[k]);\n\t\t    i__3 = i__;\n\t\t    z__2.r = z__3.r * x[i__3].r - z__3.i * x[i__3].i, z__2.i =\n\t\t\t     z__3.r * x[i__3].i + z__3.i * x[i__3].r;\n\t\t    z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i;\n\t\t    temp2.r = z__1.r, temp2.i = z__1.i;\n\t\t    ++k;\n/* L90: */\n\t\t}\n\t\ti__2 = j;\n\t\ti__3 = j;\n\t\tz__2.r = alpha->r * temp2.r - alpha->i * temp2.i, z__2.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tz__1.r = y[i__3].r + z__2.r, z__1.i = y[i__3].i + z__2.i;\n\t\ty[i__2].r = z__1.r, y[i__2].i = z__1.i;\n\t\tkk += *n - j + 1;\n/* L100: */\n\t    }\n\t} else {\n\t    jx = kx;\n\t    jy = ky;\n\t    i__1 = *n;\n\t    for (j = 1; j <= i__1; ++j) {\n\t\ti__2 = jx;\n\t\tz__1.r = alpha->r * x[i__2].r - alpha->i * x[i__2].i, z__1.i =\n\t\t\t alpha->r * x[i__2].i + alpha->i * x[i__2].r;\n\t\ttemp1.r = z__1.r, temp1.i = z__1.i;\n\t\ttemp2.r = 0., temp2.i = 0.;\n\t\ti__2 = jy;\n\t\ti__3 = jy;\n\t\ti__4 = kk;\n\t\td__1 = ap[i__4].r;\n\t\tz__2.r = d__1 * temp1.r, z__2.i = d__1 * temp1.i;\n\t\tz__1.r = y[i__3].r + z__2.r, z__1.i = y[i__3].i + z__2.i;\n\t\ty[i__2].r = z__1.r, y[i__2].i = z__1.i;\n\t\tix = jx;\n\t\tiy = jy;\n\t\ti__2 = kk + *n - j;\n\t\tfor (k = kk + 1; k <= i__2; ++k) {\n\t\t    ix += *incx;\n\t\t    iy += *incy;\n\t\t    i__3 = iy;\n\t\t    i__4 = iy;\n\t\t    i__5 = k;\n\t\t    z__2.r = temp1.r * ap[i__5].r - temp1.i * ap[i__5].i, \n\t\t\t    z__2.i = temp1.r * ap[i__5].i + temp1.i * ap[i__5]\n\t\t\t    .r;\n\t\t    z__1.r = y[i__4].r + z__2.r, z__1.i = y[i__4].i + z__2.i;\n\t\t    y[i__3].r = z__1.r, y[i__3].i = z__1.i;\n\t\t    d_cnjg(&z__3, &ap[k]);\n\t\t    i__3 = ix;\n\t\t    z__2.r = z__3.r * x[i__3].r - z__3.i * x[i__3].i, z__2.i =\n\t\t\t     z__3.r * x[i__3].i + z__3.i * x[i__3].r;\n\t\t    z__1.r = temp2.r + z__2.r, z__1.i = temp2.i + z__2.i;\n\t\t    temp2.r = z__1.r, temp2.i = z__1.i;\n/* L110: */\n\t\t}\n\t\ti__2 = jy;\n\t\ti__3 = jy;\n\t\tz__2.r = alpha->r * temp2.r - alpha->i * temp2.i, z__2.i = \n\t\t\talpha->r * temp2.i + alpha->i * temp2.r;\n\t\tz__1.r = y[i__3].r + z__2.r, z__1.i = y[i__3].i + z__2.i;\n\t\ty[i__2].r = z__1.r, y[i__2].i = z__1.i;\n\t\tjx += *incx;\n\t\tjy += *incy;\n\t\tkk += *n - j + 1;\n/* L120: */\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of ZHPMV . */\n\n} /* zhpmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/f2c/ztbmv.c",
    "content": "/* ztbmv.f -- translated by f2c (version 20100827).\n   You must link the resulting object file with libf2c:\n\ton Microsoft Windows system, link with libf2c.lib;\n\ton Linux or Unix systems, link with .../path/to/libf2c.a -lm\n\tor, if you install libf2c.a in a standard place, with -lf2c -lm\n\t-- in that order, at the end of the command line, as in\n\t\tcc *.o -lf2c -lm\n\tSource for libf2c is in /netlib/f2c/libf2c.zip, e.g.,\n\n\t\thttp://www.netlib.org/f2c/libf2c.zip\n*/\n\n#include \"datatypes.h\"\n\n/* Subroutine */ int ztbmv_(char *uplo, char *trans, char *diag, integer *n, \n\tinteger *k, doublecomplex *a, integer *lda, doublecomplex *x, integer \n\t*incx, ftnlen uplo_len, ftnlen trans_len, ftnlen diag_len)\n{\n    /* System generated locals */\n    integer a_dim1, a_offset, i__1, i__2, i__3, i__4, i__5;\n    doublecomplex z__1, z__2, z__3;\n\n    /* Builtin functions */\n    void d_cnjg(doublecomplex *, doublecomplex *);\n\n    /* Local variables */\n    integer i__, j, l, ix, jx, kx, info;\n    doublecomplex temp;\n    extern logical lsame_(char *, char *, ftnlen, ftnlen);\n    integer kplus1;\n    extern /* Subroutine */ int xerbla_(char *, integer *, ftnlen);\n    logical noconj, nounit;\n\n/*     .. Scalar Arguments .. */\n/*     .. */\n/*     .. Array Arguments .. */\n/*     .. */\n\n/*  Purpose */\n/*  ======= */\n\n/*  ZTBMV  performs one of the matrix-vector operations */\n\n/*     x := A*x,   or   x := A'*x,   or   x := conjg( A' )*x, */\n\n/*  where x is an n element vector and  A is an n by n unit, or non-unit, */\n/*  upper or lower triangular band matrix, with ( k + 1 ) diagonals. */\n\n/*  Arguments */\n/*  ========== */\n\n/*  UPLO   - CHARACTER*1. */\n/*           On entry, UPLO specifies whether the matrix is an upper or */\n/*           lower triangular matrix as follows: */\n\n/*              UPLO = 'U' or 'u'   A is an upper triangular matrix. */\n\n/*              UPLO = 'L' or 'l'   A is a lower triangular matrix. */\n\n/*           Unchanged on exit. */\n\n/*  TRANS  - CHARACTER*1. */\n/*           On entry, TRANS specifies the operation to be performed as */\n/*           follows: */\n\n/*              TRANS = 'N' or 'n'   x := A*x. */\n\n/*              TRANS = 'T' or 't'   x := A'*x. */\n\n/*              TRANS = 'C' or 'c'   x := conjg( A' )*x. */\n\n/*           Unchanged on exit. */\n\n/*  DIAG   - CHARACTER*1. */\n/*           On entry, DIAG specifies whether or not A is unit */\n/*           triangular as follows: */\n\n/*              DIAG = 'U' or 'u'   A is assumed to be unit triangular. */\n\n/*              DIAG = 'N' or 'n'   A is not assumed to be unit */\n/*                                  triangular. */\n\n/*           Unchanged on exit. */\n\n/*  N      - INTEGER. */\n/*           On entry, N specifies the order of the matrix A. */\n/*           N must be at least zero. */\n/*           Unchanged on exit. */\n\n/*  K      - INTEGER. */\n/*           On entry with UPLO = 'U' or 'u', K specifies the number of */\n/*           super-diagonals of the matrix A. */\n/*           On entry with UPLO = 'L' or 'l', K specifies the number of */\n/*           sub-diagonals of the matrix A. */\n/*           K must satisfy  0 .le. K. */\n/*           Unchanged on exit. */\n\n/*  A      - COMPLEX*16       array of DIMENSION ( LDA, n ). */\n/*           Before entry with UPLO = 'U' or 'u', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the upper triangular */\n/*           band part of the matrix of coefficients, supplied column by */\n/*           column, with the leading diagonal of the matrix in row */\n/*           ( k + 1 ) of the array, the first super-diagonal starting at */\n/*           position 2 in row k, and so on. The top left k by k triangle */\n/*           of the array A is not referenced. */\n/*           The following program segment will transfer an upper */\n/*           triangular band matrix from conventional full matrix storage */\n/*           to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = K + 1 - J */\n/*                    DO 10, I = MAX( 1, J - K ), J */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Before entry with UPLO = 'L' or 'l', the leading ( k + 1 ) */\n/*           by n part of the array A must contain the lower triangular */\n/*           band part of the matrix of coefficients, supplied column by */\n/*           column, with the leading diagonal of the matrix in row 1 of */\n/*           the array, the first sub-diagonal starting at position 1 in */\n/*           row 2, and so on. The bottom right k by k triangle of the */\n/*           array A is not referenced. */\n/*           The following program segment will transfer a lower */\n/*           triangular band matrix from conventional full matrix storage */\n/*           to band storage: */\n\n/*                 DO 20, J = 1, N */\n/*                    M = 1 - J */\n/*                    DO 10, I = J, MIN( N, J + K ) */\n/*                       A( M + I, J ) = matrix( I, J ) */\n/*              10    CONTINUE */\n/*              20 CONTINUE */\n\n/*           Note that when DIAG = 'U' or 'u' the elements of the array A */\n/*           corresponding to the diagonal elements of the matrix are not */\n/*           referenced, but are assumed to be unity. */\n/*           Unchanged on exit. */\n\n/*  LDA    - INTEGER. */\n/*           On entry, LDA specifies the first dimension of A as declared */\n/*           in the calling (sub) program. LDA must be at least */\n/*           ( k + 1 ). */\n/*           Unchanged on exit. */\n\n/*  X      - COMPLEX*16       array of dimension at least */\n/*           ( 1 + ( n - 1 )*abs( INCX ) ). */\n/*           Before entry, the incremented array X must contain the n */\n/*           element vector x. On exit, X is overwritten with the */\n/*           transformed vector x. */\n\n/*  INCX   - INTEGER. */\n/*           On entry, INCX specifies the increment for the elements of */\n/*           X. INCX must not be zero. */\n/*           Unchanged on exit. */\n\n/*  Further Details */\n/*  =============== */\n\n/*  Level 2 Blas routine. */\n\n/*  -- Written on 22-October-1986. */\n/*     Jack Dongarra, Argonne National Lab. */\n/*     Jeremy Du Croz, Nag Central Office. */\n/*     Sven Hammarling, Nag Central Office. */\n/*     Richard Hanson, Sandia National Labs. */\n\n/*  ===================================================================== */\n\n/*     .. Parameters .. */\n/*     .. */\n/*     .. Local Scalars .. */\n/*     .. */\n/*     .. External Functions .. */\n/*     .. */\n/*     .. External Subroutines .. */\n/*     .. */\n/*     .. Intrinsic Functions .. */\n/*     .. */\n\n/*     Test the input parameters. */\n\n    /* Parameter adjustments */\n    a_dim1 = *lda;\n    a_offset = 1 + a_dim1;\n    a -= a_offset;\n    --x;\n\n    /* Function Body */\n    info = 0;\n    if (! lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(uplo, \"L\", (\n\t    ftnlen)1, (ftnlen)1)) {\n\tinfo = 1;\n    } else if (! lsame_(trans, \"N\", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, \n\t    \"T\", (ftnlen)1, (ftnlen)1) && ! lsame_(trans, \"C\", (ftnlen)1, (\n\t    ftnlen)1)) {\n\tinfo = 2;\n    } else if (! lsame_(diag, \"U\", (ftnlen)1, (ftnlen)1) && ! lsame_(diag, \n\t    \"N\", (ftnlen)1, (ftnlen)1)) {\n\tinfo = 3;\n    } else if (*n < 0) {\n\tinfo = 4;\n    } else if (*k < 0) {\n\tinfo = 5;\n    } else if (*lda < *k + 1) {\n\tinfo = 7;\n    } else if (*incx == 0) {\n\tinfo = 9;\n    }\n    if (info != 0) {\n\txerbla_(\"ZTBMV \", &info, (ftnlen)6);\n\treturn 0;\n    }\n\n/*     Quick return if possible. */\n\n    if (*n == 0) {\n\treturn 0;\n    }\n\n    noconj = lsame_(trans, \"T\", (ftnlen)1, (ftnlen)1);\n    nounit = lsame_(diag, \"N\", (ftnlen)1, (ftnlen)1);\n\n/*     Set up the start point in X if the increment is not unity. This */\n/*     will be  ( N - 1 )*INCX   too small for descending loops. */\n\n    if (*incx <= 0) {\n\tkx = 1 - (*n - 1) * *incx;\n    } else if (*incx != 1) {\n\tkx = 1;\n    }\n\n/*     Start the operations. In this version the elements of A are */\n/*     accessed sequentially with one pass through A. */\n\n    if (lsame_(trans, \"N\", (ftnlen)1, (ftnlen)1)) {\n\n/*         Form  x := A*x. */\n\n\tif (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\t    kplus1 = *k + 1;\n\t    if (*incx == 1) {\n\t\ti__1 = *n;\n\t\tfor (j = 1; j <= i__1; ++j) {\n\t\t    i__2 = j;\n\t\t    if (x[i__2].r != 0. || x[i__2].i != 0.) {\n\t\t\ti__2 = j;\n\t\t\ttemp.r = x[i__2].r, temp.i = x[i__2].i;\n\t\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\t\ti__2 = 1, i__3 = j - *k;\n\t\t\ti__4 = j - 1;\n\t\t\tfor (i__ = max(i__2,i__3); i__ <= i__4; ++i__) {\n\t\t\t    i__2 = i__;\n\t\t\t    i__3 = i__;\n\t\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t\t    z__2.r = temp.r * a[i__5].r - temp.i * a[i__5].i, \n\t\t\t\t    z__2.i = temp.r * a[i__5].i + temp.i * a[\n\t\t\t\t    i__5].r;\n\t\t\t    z__1.r = x[i__3].r + z__2.r, z__1.i = x[i__3].i + \n\t\t\t\t    z__2.i;\n\t\t\t    x[i__2].r = z__1.r, x[i__2].i = z__1.i;\n/* L10: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    i__4 = j;\n\t\t\t    i__2 = j;\n\t\t\t    i__3 = kplus1 + j * a_dim1;\n\t\t\t    z__1.r = x[i__2].r * a[i__3].r - x[i__2].i * a[\n\t\t\t\t    i__3].i, z__1.i = x[i__2].r * a[i__3].i + \n\t\t\t\t    x[i__2].i * a[i__3].r;\n\t\t\t    x[i__4].r = z__1.r, x[i__4].i = z__1.i;\n\t\t\t}\n\t\t    }\n/* L20: */\n\t\t}\n\t    } else {\n\t\tjx = kx;\n\t\ti__1 = *n;\n\t\tfor (j = 1; j <= i__1; ++j) {\n\t\t    i__4 = jx;\n\t\t    if (x[i__4].r != 0. || x[i__4].i != 0.) {\n\t\t\ti__4 = jx;\n\t\t\ttemp.r = x[i__4].r, temp.i = x[i__4].i;\n\t\t\tix = kx;\n\t\t\tl = kplus1 - j;\n/* Computing MAX */\n\t\t\ti__4 = 1, i__2 = j - *k;\n\t\t\ti__3 = j - 1;\n\t\t\tfor (i__ = max(i__4,i__2); i__ <= i__3; ++i__) {\n\t\t\t    i__4 = ix;\n\t\t\t    i__2 = ix;\n\t\t\t    i__5 = l + i__ + j * a_dim1;\n\t\t\t    z__2.r = temp.r * a[i__5].r - temp.i * a[i__5].i, \n\t\t\t\t    z__2.i = temp.r * a[i__5].i + temp.i * a[\n\t\t\t\t    i__5].r;\n\t\t\t    z__1.r = x[i__2].r + z__2.r, z__1.i = x[i__2].i + \n\t\t\t\t    z__2.i;\n\t\t\t    x[i__4].r = z__1.r, x[i__4].i = z__1.i;\n\t\t\t    ix += *incx;\n/* L30: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    i__3 = jx;\n\t\t\t    i__4 = jx;\n\t\t\t    i__2 = kplus1 + j * a_dim1;\n\t\t\t    z__1.r = x[i__4].r * a[i__2].r - x[i__4].i * a[\n\t\t\t\t    i__2].i, z__1.i = x[i__4].r * a[i__2].i + \n\t\t\t\t    x[i__4].i * a[i__2].r;\n\t\t\t    x[i__3].r = z__1.r, x[i__3].i = z__1.i;\n\t\t\t}\n\t\t    }\n\t\t    jx += *incx;\n\t\t    if (j > *k) {\n\t\t\tkx += *incx;\n\t\t    }\n/* L40: */\n\t\t}\n\t    }\n\t} else {\n\t    if (*incx == 1) {\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    i__1 = j;\n\t\t    if (x[i__1].r != 0. || x[i__1].i != 0.) {\n\t\t\ti__1 = j;\n\t\t\ttemp.r = x[i__1].r, temp.i = x[i__1].i;\n\t\t\tl = 1 - j;\n/* Computing MIN */\n\t\t\ti__1 = *n, i__3 = j + *k;\n\t\t\ti__4 = j + 1;\n\t\t\tfor (i__ = min(i__1,i__3); i__ >= i__4; --i__) {\n\t\t\t    i__1 = i__;\n\t\t\t    i__3 = i__;\n\t\t\t    i__2 = l + i__ + j * a_dim1;\n\t\t\t    z__2.r = temp.r * a[i__2].r - temp.i * a[i__2].i, \n\t\t\t\t    z__2.i = temp.r * a[i__2].i + temp.i * a[\n\t\t\t\t    i__2].r;\n\t\t\t    z__1.r = x[i__3].r + z__2.r, z__1.i = x[i__3].i + \n\t\t\t\t    z__2.i;\n\t\t\t    x[i__1].r = z__1.r, x[i__1].i = z__1.i;\n/* L50: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    i__4 = j;\n\t\t\t    i__1 = j;\n\t\t\t    i__3 = j * a_dim1 + 1;\n\t\t\t    z__1.r = x[i__1].r * a[i__3].r - x[i__1].i * a[\n\t\t\t\t    i__3].i, z__1.i = x[i__1].r * a[i__3].i + \n\t\t\t\t    x[i__1].i * a[i__3].r;\n\t\t\t    x[i__4].r = z__1.r, x[i__4].i = z__1.i;\n\t\t\t}\n\t\t    }\n/* L60: */\n\t\t}\n\t    } else {\n\t\tkx += (*n - 1) * *incx;\n\t\tjx = kx;\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    i__4 = jx;\n\t\t    if (x[i__4].r != 0. || x[i__4].i != 0.) {\n\t\t\ti__4 = jx;\n\t\t\ttemp.r = x[i__4].r, temp.i = x[i__4].i;\n\t\t\tix = kx;\n\t\t\tl = 1 - j;\n/* Computing MIN */\n\t\t\ti__4 = *n, i__1 = j + *k;\n\t\t\ti__3 = j + 1;\n\t\t\tfor (i__ = min(i__4,i__1); i__ >= i__3; --i__) {\n\t\t\t    i__4 = ix;\n\t\t\t    i__1 = ix;\n\t\t\t    i__2 = l + i__ + j * a_dim1;\n\t\t\t    z__2.r = temp.r * a[i__2].r - temp.i * a[i__2].i, \n\t\t\t\t    z__2.i = temp.r * a[i__2].i + temp.i * a[\n\t\t\t\t    i__2].r;\n\t\t\t    z__1.r = x[i__1].r + z__2.r, z__1.i = x[i__1].i + \n\t\t\t\t    z__2.i;\n\t\t\t    x[i__4].r = z__1.r, x[i__4].i = z__1.i;\n\t\t\t    ix -= *incx;\n/* L70: */\n\t\t\t}\n\t\t\tif (nounit) {\n\t\t\t    i__3 = jx;\n\t\t\t    i__4 = jx;\n\t\t\t    i__1 = j * a_dim1 + 1;\n\t\t\t    z__1.r = x[i__4].r * a[i__1].r - x[i__4].i * a[\n\t\t\t\t    i__1].i, z__1.i = x[i__4].r * a[i__1].i + \n\t\t\t\t    x[i__4].i * a[i__1].r;\n\t\t\t    x[i__3].r = z__1.r, x[i__3].i = z__1.i;\n\t\t\t}\n\t\t    }\n\t\t    jx -= *incx;\n\t\t    if (*n - j >= *k) {\n\t\t\tkx -= *incx;\n\t\t    }\n/* L80: */\n\t\t}\n\t    }\n\t}\n    } else {\n\n/*        Form  x := A'*x  or  x := conjg( A' )*x. */\n\n\tif (lsame_(uplo, \"U\", (ftnlen)1, (ftnlen)1)) {\n\t    kplus1 = *k + 1;\n\t    if (*incx == 1) {\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    i__3 = j;\n\t\t    temp.r = x[i__3].r, temp.i = x[i__3].i;\n\t\t    l = kplus1 - j;\n\t\t    if (noconj) {\n\t\t\tif (nounit) {\n\t\t\t    i__3 = kplus1 + j * a_dim1;\n\t\t\t    z__1.r = temp.r * a[i__3].r - temp.i * a[i__3].i, \n\t\t\t\t    z__1.i = temp.r * a[i__3].i + temp.i * a[\n\t\t\t\t    i__3].r;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t}\n/* Computing MAX */\n\t\t\ti__4 = 1, i__1 = j - *k;\n\t\t\ti__3 = max(i__4,i__1);\n\t\t\tfor (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\t    i__4 = l + i__ + j * a_dim1;\n\t\t\t    i__1 = i__;\n\t\t\t    z__2.r = a[i__4].r * x[i__1].r - a[i__4].i * x[\n\t\t\t\t    i__1].i, z__2.i = a[i__4].r * x[i__1].i + \n\t\t\t\t    a[i__4].i * x[i__1].r;\n\t\t\t    z__1.r = temp.r + z__2.r, z__1.i = temp.i + \n\t\t\t\t    z__2.i;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n/* L90: */\n\t\t\t}\n\t\t    } else {\n\t\t\tif (nounit) {\n\t\t\t    d_cnjg(&z__2, &a[kplus1 + j * a_dim1]);\n\t\t\t    z__1.r = temp.r * z__2.r - temp.i * z__2.i, \n\t\t\t\t    z__1.i = temp.r * z__2.i + temp.i * \n\t\t\t\t    z__2.r;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t}\n/* Computing MAX */\n\t\t\ti__4 = 1, i__1 = j - *k;\n\t\t\ti__3 = max(i__4,i__1);\n\t\t\tfor (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\t    d_cnjg(&z__3, &a[l + i__ + j * a_dim1]);\n\t\t\t    i__4 = i__;\n\t\t\t    z__2.r = z__3.r * x[i__4].r - z__3.i * x[i__4].i, \n\t\t\t\t    z__2.i = z__3.r * x[i__4].i + z__3.i * x[\n\t\t\t\t    i__4].r;\n\t\t\t    z__1.r = temp.r + z__2.r, z__1.i = temp.i + \n\t\t\t\t    z__2.i;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n/* L100: */\n\t\t\t}\n\t\t    }\n\t\t    i__3 = j;\n\t\t    x[i__3].r = temp.r, x[i__3].i = temp.i;\n/* L110: */\n\t\t}\n\t    } else {\n\t\tkx += (*n - 1) * *incx;\n\t\tjx = kx;\n\t\tfor (j = *n; j >= 1; --j) {\n\t\t    i__3 = jx;\n\t\t    temp.r = x[i__3].r, temp.i = x[i__3].i;\n\t\t    kx -= *incx;\n\t\t    ix = kx;\n\t\t    l = kplus1 - j;\n\t\t    if (noconj) {\n\t\t\tif (nounit) {\n\t\t\t    i__3 = kplus1 + j * a_dim1;\n\t\t\t    z__1.r = temp.r * a[i__3].r - temp.i * a[i__3].i, \n\t\t\t\t    z__1.i = temp.r * a[i__3].i + temp.i * a[\n\t\t\t\t    i__3].r;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t}\n/* Computing MAX */\n\t\t\ti__4 = 1, i__1 = j - *k;\n\t\t\ti__3 = max(i__4,i__1);\n\t\t\tfor (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\t    i__4 = l + i__ + j * a_dim1;\n\t\t\t    i__1 = ix;\n\t\t\t    z__2.r = a[i__4].r * x[i__1].r - a[i__4].i * x[\n\t\t\t\t    i__1].i, z__2.i = a[i__4].r * x[i__1].i + \n\t\t\t\t    a[i__4].i * x[i__1].r;\n\t\t\t    z__1.r = temp.r + z__2.r, z__1.i = temp.i + \n\t\t\t\t    z__2.i;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t    ix -= *incx;\n/* L120: */\n\t\t\t}\n\t\t    } else {\n\t\t\tif (nounit) {\n\t\t\t    d_cnjg(&z__2, &a[kplus1 + j * a_dim1]);\n\t\t\t    z__1.r = temp.r * z__2.r - temp.i * z__2.i, \n\t\t\t\t    z__1.i = temp.r * z__2.i + temp.i * \n\t\t\t\t    z__2.r;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t}\n/* Computing MAX */\n\t\t\ti__4 = 1, i__1 = j - *k;\n\t\t\ti__3 = max(i__4,i__1);\n\t\t\tfor (i__ = j - 1; i__ >= i__3; --i__) {\n\t\t\t    d_cnjg(&z__3, &a[l + i__ + j * a_dim1]);\n\t\t\t    i__4 = ix;\n\t\t\t    z__2.r = z__3.r * x[i__4].r - z__3.i * x[i__4].i, \n\t\t\t\t    z__2.i = z__3.r * x[i__4].i + z__3.i * x[\n\t\t\t\t    i__4].r;\n\t\t\t    z__1.r = temp.r + z__2.r, z__1.i = temp.i + \n\t\t\t\t    z__2.i;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t    ix -= *incx;\n/* L130: */\n\t\t\t}\n\t\t    }\n\t\t    i__3 = jx;\n\t\t    x[i__3].r = temp.r, x[i__3].i = temp.i;\n\t\t    jx -= *incx;\n/* L140: */\n\t\t}\n\t    }\n\t} else {\n\t    if (*incx == 1) {\n\t\ti__3 = *n;\n\t\tfor (j = 1; j <= i__3; ++j) {\n\t\t    i__4 = j;\n\t\t    temp.r = x[i__4].r, temp.i = x[i__4].i;\n\t\t    l = 1 - j;\n\t\t    if (noconj) {\n\t\t\tif (nounit) {\n\t\t\t    i__4 = j * a_dim1 + 1;\n\t\t\t    z__1.r = temp.r * a[i__4].r - temp.i * a[i__4].i, \n\t\t\t\t    z__1.i = temp.r * a[i__4].i + temp.i * a[\n\t\t\t\t    i__4].r;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t}\n/* Computing MIN */\n\t\t\ti__1 = *n, i__2 = j + *k;\n\t\t\ti__4 = min(i__1,i__2);\n\t\t\tfor (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\t    i__1 = l + i__ + j * a_dim1;\n\t\t\t    i__2 = i__;\n\t\t\t    z__2.r = a[i__1].r * x[i__2].r - a[i__1].i * x[\n\t\t\t\t    i__2].i, z__2.i = a[i__1].r * x[i__2].i + \n\t\t\t\t    a[i__1].i * x[i__2].r;\n\t\t\t    z__1.r = temp.r + z__2.r, z__1.i = temp.i + \n\t\t\t\t    z__2.i;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n/* L150: */\n\t\t\t}\n\t\t    } else {\n\t\t\tif (nounit) {\n\t\t\t    d_cnjg(&z__2, &a[j * a_dim1 + 1]);\n\t\t\t    z__1.r = temp.r * z__2.r - temp.i * z__2.i, \n\t\t\t\t    z__1.i = temp.r * z__2.i + temp.i * \n\t\t\t\t    z__2.r;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t}\n/* Computing MIN */\n\t\t\ti__1 = *n, i__2 = j + *k;\n\t\t\ti__4 = min(i__1,i__2);\n\t\t\tfor (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\t    d_cnjg(&z__3, &a[l + i__ + j * a_dim1]);\n\t\t\t    i__1 = i__;\n\t\t\t    z__2.r = z__3.r * x[i__1].r - z__3.i * x[i__1].i, \n\t\t\t\t    z__2.i = z__3.r * x[i__1].i + z__3.i * x[\n\t\t\t\t    i__1].r;\n\t\t\t    z__1.r = temp.r + z__2.r, z__1.i = temp.i + \n\t\t\t\t    z__2.i;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n/* L160: */\n\t\t\t}\n\t\t    }\n\t\t    i__4 = j;\n\t\t    x[i__4].r = temp.r, x[i__4].i = temp.i;\n/* L170: */\n\t\t}\n\t    } else {\n\t\tjx = kx;\n\t\ti__3 = *n;\n\t\tfor (j = 1; j <= i__3; ++j) {\n\t\t    i__4 = jx;\n\t\t    temp.r = x[i__4].r, temp.i = x[i__4].i;\n\t\t    kx += *incx;\n\t\t    ix = kx;\n\t\t    l = 1 - j;\n\t\t    if (noconj) {\n\t\t\tif (nounit) {\n\t\t\t    i__4 = j * a_dim1 + 1;\n\t\t\t    z__1.r = temp.r * a[i__4].r - temp.i * a[i__4].i, \n\t\t\t\t    z__1.i = temp.r * a[i__4].i + temp.i * a[\n\t\t\t\t    i__4].r;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t}\n/* Computing MIN */\n\t\t\ti__1 = *n, i__2 = j + *k;\n\t\t\ti__4 = min(i__1,i__2);\n\t\t\tfor (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\t    i__1 = l + i__ + j * a_dim1;\n\t\t\t    i__2 = ix;\n\t\t\t    z__2.r = a[i__1].r * x[i__2].r - a[i__1].i * x[\n\t\t\t\t    i__2].i, z__2.i = a[i__1].r * x[i__2].i + \n\t\t\t\t    a[i__1].i * x[i__2].r;\n\t\t\t    z__1.r = temp.r + z__2.r, z__1.i = temp.i + \n\t\t\t\t    z__2.i;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t    ix += *incx;\n/* L180: */\n\t\t\t}\n\t\t    } else {\n\t\t\tif (nounit) {\n\t\t\t    d_cnjg(&z__2, &a[j * a_dim1 + 1]);\n\t\t\t    z__1.r = temp.r * z__2.r - temp.i * z__2.i, \n\t\t\t\t    z__1.i = temp.r * z__2.i + temp.i * \n\t\t\t\t    z__2.r;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t}\n/* Computing MIN */\n\t\t\ti__1 = *n, i__2 = j + *k;\n\t\t\ti__4 = min(i__1,i__2);\n\t\t\tfor (i__ = j + 1; i__ <= i__4; ++i__) {\n\t\t\t    d_cnjg(&z__3, &a[l + i__ + j * a_dim1]);\n\t\t\t    i__1 = ix;\n\t\t\t    z__2.r = z__3.r * x[i__1].r - z__3.i * x[i__1].i, \n\t\t\t\t    z__2.i = z__3.r * x[i__1].i + z__3.i * x[\n\t\t\t\t    i__1].r;\n\t\t\t    z__1.r = temp.r + z__2.r, z__1.i = temp.i + \n\t\t\t\t    z__2.i;\n\t\t\t    temp.r = z__1.r, temp.i = z__1.i;\n\t\t\t    ix += *incx;\n/* L190: */\n\t\t\t}\n\t\t    }\n\t\t    i__4 = jx;\n\t\t    x[i__4].r = temp.r, x[i__4].i = temp.i;\n\t\t    jx += *incx;\n/* L200: */\n\t\t}\n\t    }\n\t}\n    }\n\n    return 0;\n\n/*     End of ZTBMV . */\n\n} /* ztbmv_ */\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/fortran/complexdots.f",
    "content": "      COMPLEX FUNCTION CDOTC(N,CX,INCX,CY,INCY)\n      INTEGER INCX,INCY,N\n      COMPLEX CX(*),CY(*)\n      COMPLEX RES\n      EXTERNAL CDOTCW\n      \n      CALL CDOTCW(N,CX,INCX,CY,INCY,RES)\n      CDOTC = RES\n      RETURN\n      END\n      \n      COMPLEX FUNCTION CDOTU(N,CX,INCX,CY,INCY)\n      INTEGER INCX,INCY,N\n      COMPLEX CX(*),CY(*)\n      COMPLEX RES\n      EXTERNAL CDOTUW\n      \n      CALL CDOTUW(N,CX,INCX,CY,INCY,RES)\n      CDOTU = RES\n      RETURN\n      END\n      \n      DOUBLE COMPLEX FUNCTION ZDOTC(N,CX,INCX,CY,INCY)\n      INTEGER INCX,INCY,N\n      DOUBLE COMPLEX CX(*),CY(*)\n      DOUBLE COMPLEX RES\n      EXTERNAL ZDOTCW\n      \n      CALL ZDOTCW(N,CX,INCX,CY,INCY,RES)\n      ZDOTC = RES\n      RETURN\n      END\n      \n      DOUBLE COMPLEX FUNCTION ZDOTU(N,CX,INCX,CY,INCY)\n      INTEGER INCX,INCY,N\n      DOUBLE COMPLEX CX(*),CY(*)\n      DOUBLE COMPLEX RES\n      EXTERNAL ZDOTUW\n      \n      CALL ZDOTUW(N,CX,INCX,CY,INCY,RES)\n      ZDOTU = RES\n      RETURN\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/level1_cplx_impl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"common.h\"\n\nstruct scalar_norm1_op {\n  typedef RealScalar result_type;\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_norm1_op)\n  inline RealScalar operator() (const Scalar& a) const { return numext::norm1(a); }\n};\nnamespace Eigen {\n  namespace internal {\n    template<> struct functor_traits<scalar_norm1_op >\n    {\n      enum { Cost = 3 * NumTraits<Scalar>::AddCost, PacketAccess = 0 };\n    };\n  }\n}\n\n// computes the sum of magnitudes of all vector elements or, for a complex vector x, the sum\n// res = |Rex1| + |Imx1| + |Rex2| + |Imx2| + ... + |Rexn| + |Imxn|, where x is a vector of order n\nRealScalar EIGEN_CAT(REAL_SCALAR_SUFFIX, EIGEN_BLAS_FUNC(asum))(int *n, RealScalar *px, int *incx)\n{\n//   std::cerr << \"__asum \" << *n << \" \" << *incx << \"\\n\";\n  Complex* x = reinterpret_cast<Complex*>(px);\n\n  if(*n<=0) return 0;\n\n  if(*incx==1)  return make_vector(x,*n).unaryExpr<scalar_norm1_op>().sum();\n  else          return make_vector(x,*n,std::abs(*incx)).unaryExpr<scalar_norm1_op>().sum();\n}\n\nint EIGEN_CAT(i, EIGEN_BLAS_FUNC(amax))(int *n, RealScalar *px, int *incx)\n{\n  if(*n<=0) return 0;\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n\n  DenseIndex ret;\n  if(*incx==1)  make_vector(x,*n).unaryExpr<scalar_norm1_op>().maxCoeff(&ret);\n  else          make_vector(x,*n,std::abs(*incx)).unaryExpr<scalar_norm1_op>().maxCoeff(&ret);\n  return int(ret)+1;\n}\n\nint EIGEN_CAT(i, EIGEN_BLAS_FUNC(amin))(int *n, RealScalar *px, int *incx)\n{\n  if(*n<=0) return 0;\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n\n  DenseIndex ret;\n  if(*incx==1)  make_vector(x,*n).unaryExpr<scalar_norm1_op>().minCoeff(&ret);\n  else          make_vector(x,*n,std::abs(*incx)).unaryExpr<scalar_norm1_op>().minCoeff(&ret);\n  return int(ret)+1;\n}\n\n// computes a dot product of a conjugated vector with another vector.\nint EIGEN_BLAS_FUNC(dotcw)(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar* pres)\n{\n//   std::cerr << \"_dotc \" << *n << \" \" << *incx << \" \" << *incy << \"\\n\";\n  Scalar* res = reinterpret_cast<Scalar*>(pres);\n\n  if(*n<=0)\n  {\n    *res = Scalar(0);\n    return 0;\n  }\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n\n  if(*incx==1 && *incy==1)    *res = (make_vector(x,*n).dot(make_vector(y,*n)));\n  else if(*incx>0 && *incy>0) *res = (make_vector(x,*n,*incx).dot(make_vector(y,*n,*incy)));\n  else if(*incx<0 && *incy>0) *res = (make_vector(x,*n,-*incx).reverse().dot(make_vector(y,*n,*incy)));\n  else if(*incx>0 && *incy<0) *res = (make_vector(x,*n,*incx).dot(make_vector(y,*n,-*incy).reverse()));\n  else if(*incx<0 && *incy<0) *res = (make_vector(x,*n,-*incx).reverse().dot(make_vector(y,*n,-*incy).reverse()));\n  return 0;\n}\n\n// computes a vector-vector dot product without complex conjugation.\nint EIGEN_BLAS_FUNC(dotuw)(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar* pres)\n{\n  Scalar* res = reinterpret_cast<Scalar*>(pres);\n\n  if(*n<=0)\n  {\n    *res = Scalar(0);\n    return 0;\n  }\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n\n  if(*incx==1 && *incy==1)    *res = (make_vector(x,*n).cwiseProduct(make_vector(y,*n))).sum();\n  else if(*incx>0 && *incy>0) *res = (make_vector(x,*n,*incx).cwiseProduct(make_vector(y,*n,*incy))).sum();\n  else if(*incx<0 && *incy>0) *res = (make_vector(x,*n,-*incx).reverse().cwiseProduct(make_vector(y,*n,*incy))).sum();\n  else if(*incx>0 && *incy<0) *res = (make_vector(x,*n,*incx).cwiseProduct(make_vector(y,*n,-*incy).reverse())).sum();\n  else if(*incx<0 && *incy<0) *res = (make_vector(x,*n,-*incx).reverse().cwiseProduct(make_vector(y,*n,-*incy).reverse())).sum();\n  return 0;\n}\n\nRealScalar EIGEN_CAT(REAL_SCALAR_SUFFIX, EIGEN_BLAS_FUNC(nrm2))(int *n, RealScalar *px, int *incx)\n{\n//   std::cerr << \"__nrm2 \" << *n << \" \" << *incx << \"\\n\";\n  if(*n<=0) return 0;\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n\n  if(*incx==1)\n    return make_vector(x,*n).stableNorm();\n\n  return make_vector(x,*n,*incx).stableNorm();\n}\n\nint EIGEN_BLAS_FUNC(EIGEN_CAT(REAL_SCALAR_SUFFIX, rot))(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pc, RealScalar *ps)\n{\n  if(*n<=0) return 0;\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  RealScalar c = *pc;\n  RealScalar s = *ps;\n\n  StridedVectorType vx(make_vector(x,*n,std::abs(*incx)));\n  StridedVectorType vy(make_vector(y,*n,std::abs(*incy)));\n\n  Reverse<StridedVectorType> rvx(vx);\n  Reverse<StridedVectorType> rvy(vy);\n\n  // TODO implement mixed real-scalar rotations\n       if(*incx<0 && *incy>0) internal::apply_rotation_in_the_plane(rvx, vy, JacobiRotation<Scalar>(c,s));\n  else if(*incx>0 && *incy<0) internal::apply_rotation_in_the_plane(vx, rvy, JacobiRotation<Scalar>(c,s));\n  else                        internal::apply_rotation_in_the_plane(vx, vy,  JacobiRotation<Scalar>(c,s));\n\n  return 0;\n}\n\nint EIGEN_BLAS_FUNC(EIGEN_CAT(REAL_SCALAR_SUFFIX, scal))(int *n, RealScalar *palpha, RealScalar *px, int *incx)\n{\n  if(*n<=0) return 0;\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  RealScalar alpha = *palpha;\n\n//   std::cerr << \"__scal \" << *n << \" \" << alpha << \" \" << *incx << \"\\n\";\n\n  if(*incx==1)  make_vector(x,*n) *= alpha;\n  else          make_vector(x,*n,std::abs(*incx)) *= alpha;\n\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/level1_impl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"common.h\"\n\nint EIGEN_BLAS_FUNC(axpy)(const int *n, const RealScalar *palpha, const RealScalar *px, const int *incx, RealScalar *py, const int *incy)\n{\n  const Scalar* x = reinterpret_cast<const Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar alpha  = *reinterpret_cast<const Scalar*>(palpha);\n\n  if(*n<=0) return 0;\n\n  if(*incx==1 && *incy==1)    make_vector(y,*n) += alpha * make_vector(x,*n);\n  else if(*incx>0 && *incy>0) make_vector(y,*n,*incy) += alpha * make_vector(x,*n,*incx);\n  else if(*incx>0 && *incy<0) make_vector(y,*n,-*incy).reverse() += alpha * make_vector(x,*n,*incx);\n  else if(*incx<0 && *incy>0) make_vector(y,*n,*incy) += alpha * make_vector(x,*n,-*incx).reverse();\n  else if(*incx<0 && *incy<0) make_vector(y,*n,-*incy).reverse() += alpha * make_vector(x,*n,-*incx).reverse();\n\n  return 0;\n}\n\nint EIGEN_BLAS_FUNC(copy)(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)\n{\n  if(*n<=0) return 0;\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n\n  // be careful, *incx==0 is allowed !!\n  if(*incx==1 && *incy==1)\n    make_vector(y,*n) = make_vector(x,*n);\n  else\n  {\n    if(*incx<0) x = x - (*n-1)*(*incx);\n    if(*incy<0) y = y - (*n-1)*(*incy);\n    for(int i=0;i<*n;++i)\n    {\n      *y = *x;\n      x += *incx;\n      y += *incy;\n    }\n  }\n\n  return 0;\n}\n\nint EIGEN_BLAS_FUNC(rotg)(RealScalar *pa, RealScalar *pb, RealScalar *pc, RealScalar *ps)\n{\n  using std::sqrt;\n  using std::abs;\n\n  Scalar& a = *reinterpret_cast<Scalar*>(pa);\n  Scalar& b = *reinterpret_cast<Scalar*>(pb);\n  RealScalar* c = pc;\n  Scalar* s = reinterpret_cast<Scalar*>(ps);\n\n  #if !ISCOMPLEX\n  Scalar r,z;\n  Scalar aa = abs(a);\n  Scalar ab = abs(b);\n  if((aa+ab)==Scalar(0))\n  {\n    *c = 1;\n    *s = 0;\n    r = 0;\n    z = 0;\n  }\n  else\n  {\n    r = sqrt(a*a + b*b);\n    Scalar amax = aa>ab ? a : b;\n    r = amax>0 ? r : -r;\n    *c = a/r;\n    *s = b/r;\n    z = 1;\n    if (aa > ab) z = *s;\n    if (ab > aa && *c!=RealScalar(0))\n      z = Scalar(1)/ *c;\n  }\n  *pa = r;\n  *pb = z;\n  #else\n  Scalar alpha;\n  RealScalar norm,scale;\n  if(abs(a)==RealScalar(0))\n  {\n    *c = RealScalar(0);\n    *s = Scalar(1);\n    a = b;\n  }\n  else\n  {\n    scale = abs(a) + abs(b);\n    norm = scale*sqrt((numext::abs2(a/scale)) + (numext::abs2(b/scale)));\n    alpha = a/abs(a);\n    *c = abs(a)/norm;\n    *s = alpha*numext::conj(b)/norm;\n    a = alpha*norm;\n  }\n  #endif\n\n//   JacobiRotation<Scalar> r;\n//   r.makeGivens(a,b);\n//   *c = r.c();\n//   *s = r.s();\n\n  return 0;\n}\n\nint EIGEN_BLAS_FUNC(scal)(int *n, RealScalar *palpha, RealScalar *px, int *incx)\n{\n  if(*n<=0) return 0;\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar alpha = *reinterpret_cast<Scalar*>(palpha);\n\n  if(*incx==1)  make_vector(x,*n) *= alpha;\n  else          make_vector(x,*n,std::abs(*incx)) *= alpha;\n\n  return 0;\n}\n\nint EIGEN_BLAS_FUNC(swap)(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)\n{\n  if(*n<=0) return 0;\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n\n  if(*incx==1 && *incy==1)    make_vector(y,*n).swap(make_vector(x,*n));\n  else if(*incx>0 && *incy>0) make_vector(y,*n,*incy).swap(make_vector(x,*n,*incx));\n  else if(*incx>0 && *incy<0) make_vector(y,*n,-*incy).reverse().swap(make_vector(x,*n,*incx));\n  else if(*incx<0 && *incy>0) make_vector(y,*n,*incy).swap(make_vector(x,*n,-*incx).reverse());\n  else if(*incx<0 && *incy<0) make_vector(y,*n,-*incy).reverse().swap(make_vector(x,*n,-*incx).reverse());\n\n  return 1;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/level1_real_impl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"common.h\"\n\n// computes the sum of magnitudes of all vector elements or, for a complex vector x, the sum\n// res = |Rex1| + |Imx1| + |Rex2| + |Imx2| + ... + |Rexn| + |Imxn|, where x is a vector of order n\nRealScalar EIGEN_BLAS_FUNC(asum)(int *n, RealScalar *px, int *incx)\n{\n//   std::cerr << \"_asum \" << *n << \" \" << *incx << \"\\n\";\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n\n  if(*n<=0) return 0;\n\n  if(*incx==1)  return make_vector(x,*n).cwiseAbs().sum();\n  else          return make_vector(x,*n,std::abs(*incx)).cwiseAbs().sum();\n}\n\nint EIGEN_CAT(i, EIGEN_BLAS_FUNC(amax))(int *n, RealScalar *px, int *incx)\n{\n  if(*n<=0) return 0;\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n\n  DenseIndex ret;\n  if(*incx==1)  make_vector(x,*n).cwiseAbs().maxCoeff(&ret);\n  else          make_vector(x,*n,std::abs(*incx)).cwiseAbs().maxCoeff(&ret);\n  return int(ret)+1;\n}\n\nint EIGEN_CAT(i, EIGEN_BLAS_FUNC(amin))(int *n, RealScalar *px, int *incx)\n{\n  if(*n<=0) return 0;\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n\n  DenseIndex ret;\n  if(*incx==1)  make_vector(x,*n).cwiseAbs().minCoeff(&ret);\n  else          make_vector(x,*n,std::abs(*incx)).cwiseAbs().minCoeff(&ret);\n  return int(ret)+1;\n}\n\n// computes a vector-vector dot product.\nScalar EIGEN_BLAS_FUNC(dot)(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy)\n{\n//   std::cerr << \"_dot \" << *n << \" \" << *incx << \" \" << *incy << \"\\n\";\n\n  if(*n<=0) return 0;\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n\n  if(*incx==1 && *incy==1)    return (make_vector(x,*n).cwiseProduct(make_vector(y,*n))).sum();\n  else if(*incx>0 && *incy>0) return (make_vector(x,*n,*incx).cwiseProduct(make_vector(y,*n,*incy))).sum();\n  else if(*incx<0 && *incy>0) return (make_vector(x,*n,-*incx).reverse().cwiseProduct(make_vector(y,*n,*incy))).sum();\n  else if(*incx>0 && *incy<0) return (make_vector(x,*n,*incx).cwiseProduct(make_vector(y,*n,-*incy).reverse())).sum();\n  else if(*incx<0 && *incy<0) return (make_vector(x,*n,-*incx).reverse().cwiseProduct(make_vector(y,*n,-*incy).reverse())).sum();\n  else return 0;\n}\n\n// computes the Euclidean norm of a vector.\n// FIXME\nScalar EIGEN_BLAS_FUNC(nrm2)(int *n, RealScalar *px, int *incx)\n{\n//   std::cerr << \"_nrm2 \" << *n << \" \" << *incx << \"\\n\";\n  if(*n<=0) return 0;\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n\n  if(*incx==1)  return make_vector(x,*n).stableNorm();\n  else          return make_vector(x,*n,std::abs(*incx)).stableNorm();\n}\n\nint EIGEN_BLAS_FUNC(rot)(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pc, RealScalar *ps)\n{\n//   std::cerr << \"_rot \" << *n << \" \" << *incx << \" \" << *incy << \"\\n\";\n  if(*n<=0) return 0;\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar c = *reinterpret_cast<Scalar*>(pc);\n  Scalar s = *reinterpret_cast<Scalar*>(ps);\n\n  StridedVectorType vx(make_vector(x,*n,std::abs(*incx)));\n  StridedVectorType vy(make_vector(y,*n,std::abs(*incy)));\n\n  Reverse<StridedVectorType> rvx(vx);\n  Reverse<StridedVectorType> rvy(vy);\n\n       if(*incx<0 && *incy>0) internal::apply_rotation_in_the_plane(rvx, vy, JacobiRotation<Scalar>(c,s));\n  else if(*incx>0 && *incy<0) internal::apply_rotation_in_the_plane(vx, rvy, JacobiRotation<Scalar>(c,s));\n  else                        internal::apply_rotation_in_the_plane(vx, vy,  JacobiRotation<Scalar>(c,s));\n\n\n  return 0;\n}\n\n/*\n// performs rotation of points in the modified plane.\nint EIGEN_BLAS_FUNC(rotm)(int *n, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *param)\n{\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n\n  // TODO\n\n  return 0;\n}\n\n// computes the modified parameters for a Givens rotation.\nint EIGEN_BLAS_FUNC(rotmg)(RealScalar *d1, RealScalar *d2, RealScalar *x1, RealScalar *x2, RealScalar *param)\n{\n  // TODO\n\n  return 0;\n}\n*/\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/level2_cplx_impl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"common.h\"\n\n/**  ZHEMV  performs the matrix-vector  operation\n  *\n  *     y := alpha*A*x + beta*y,\n  *\n  *  where alpha and beta are scalars, x and y are n element vectors and\n  *  A is an n by n hermitian matrix.\n  */\nint EIGEN_BLAS_FUNC(hemv)(const char *uplo, const int *n, const RealScalar *palpha, const RealScalar *pa, const int *lda,\n                          const RealScalar *px, const int *incx, const RealScalar *pbeta, RealScalar *py, const int *incy)\n{\n  typedef void (*functype)(int, const Scalar*, int, const Scalar*, Scalar*, Scalar);\n  static const functype func[2] = {\n    // array index: UP\n    (internal::selfadjoint_matrix_vector_product<Scalar,int,ColMajor,Upper,false,false>::run),\n    // array index: LO\n    (internal::selfadjoint_matrix_vector_product<Scalar,int,ColMajor,Lower,false,false>::run),\n  };\n\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  const Scalar* x = reinterpret_cast<const Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar alpha  = *reinterpret_cast<const Scalar*>(palpha);\n  Scalar beta   = *reinterpret_cast<const Scalar*>(pbeta);\n\n  // check arguments\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)        info = 1;\n  else if(*n<0)                   info = 2;\n  else if(*lda<std::max(1,*n))    info = 5;\n  else if(*incx==0)               info = 7;\n  else if(*incy==0)               info = 10;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"HEMV \",&info,6);\n\n  if(*n==0)\n    return 1;\n\n  const Scalar* actual_x = get_compact_vector(x,*n,*incx);\n  Scalar* actual_y = get_compact_vector(y,*n,*incy);\n\n  if(beta!=Scalar(1))\n  {\n    if(beta==Scalar(0)) make_vector(actual_y, *n).setZero();\n    else                make_vector(actual_y, *n) *= beta;\n  }\n\n  if(alpha!=Scalar(0))\n  {\n    int code = UPLO(*uplo);\n    if(code>=2 || func[code]==0)\n      return 0;\n\n    func[code](*n, a, *lda, actual_x, actual_y, alpha);\n  }\n\n  if(actual_x!=x) delete[] actual_x;\n  if(actual_y!=y) delete[] copy_back(actual_y,y,*n,*incy);\n\n  return 1;\n}\n\n/**  ZHBMV  performs the matrix-vector  operation\n  *\n  *     y := alpha*A*x + beta*y,\n  *\n  *  where alpha and beta are scalars, x and y are n element vectors and\n  *  A is an n by n hermitian band matrix, with k super-diagonals.\n  */\n// int EIGEN_BLAS_FUNC(hbmv)(char *uplo, int *n, int *k, RealScalar *alpha, RealScalar *a, int *lda,\n//                           RealScalar *x, int *incx, RealScalar *beta, RealScalar *y, int *incy)\n// {\n//   return 1;\n// }\n\n/**  ZHPMV  performs the matrix-vector operation\n  *\n  *     y := alpha*A*x + beta*y,\n  *\n  *  where alpha and beta are scalars, x and y are n element vectors and\n  *  A is an n by n hermitian matrix, supplied in packed form.\n  */\n// int EIGEN_BLAS_FUNC(hpmv)(char *uplo, int *n, RealScalar *alpha, RealScalar *ap, RealScalar *x, int *incx, RealScalar *beta, RealScalar *y, int *incy)\n// {\n//   return 1;\n// }\n\n/**  ZHPR    performs the hermitian rank 1 operation\n  *\n  *     A := alpha*x*conjg( x' ) + A,\n  *\n  *  where alpha is a real scalar, x is an n element vector and A is an\n  *  n by n hermitian matrix, supplied in packed form.\n  */\nint EIGEN_BLAS_FUNC(hpr)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *pap)\n{\n  typedef void (*functype)(int, Scalar*, const Scalar*, RealScalar);\n  static const functype func[2] = {\n    // array index: UP\n    (internal::selfadjoint_packed_rank1_update<Scalar,int,ColMajor,Upper,false,Conj>::run),\n    // array index: LO\n    (internal::selfadjoint_packed_rank1_update<Scalar,int,ColMajor,Lower,false,Conj>::run),\n  };\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* ap = reinterpret_cast<Scalar*>(pap);\n  RealScalar alpha = *palpha;\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"HPR  \",&info,6);\n\n  if(alpha==Scalar(0))\n    return 1;\n\n  Scalar* x_cpy = get_compact_vector(x, *n, *incx);\n\n  int code = UPLO(*uplo);\n  if(code>=2 || func[code]==0)\n    return 0;\n\n  func[code](*n, ap, x_cpy, alpha);\n\n  if(x_cpy!=x)  delete[] x_cpy;\n\n  return 1;\n}\n\n/**  ZHPR2  performs the hermitian rank 2 operation\n  *\n  *     A := alpha*x*conjg( y' ) + conjg( alpha )*y*conjg( x' ) + A,\n  *\n  *  where alpha is a scalar, x and y are n element vectors and A is an\n  *  n by n hermitian matrix, supplied in packed form.\n  */\nint EIGEN_BLAS_FUNC(hpr2)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pap)\n{\n  typedef void (*functype)(int, Scalar*, const Scalar*, const Scalar*, Scalar);\n  static const functype func[2] = {\n    // array index: UP\n    (internal::packed_rank2_update_selector<Scalar,int,Upper>::run),\n    // array index: LO\n    (internal::packed_rank2_update_selector<Scalar,int,Lower>::run),\n  };\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar* ap = reinterpret_cast<Scalar*>(pap);\n  Scalar alpha = *reinterpret_cast<Scalar*>(palpha);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  else if(*incy==0)                                                   info = 7;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"HPR2 \",&info,6);\n\n  if(alpha==Scalar(0))\n    return 1;\n\n  Scalar* x_cpy = get_compact_vector(x, *n, *incx);\n  Scalar* y_cpy = get_compact_vector(y, *n, *incy);\n\n  int code = UPLO(*uplo);\n  if(code>=2 || func[code]==0)\n    return 0;\n\n  func[code](*n, ap, x_cpy, y_cpy, alpha);\n\n  if(x_cpy!=x)  delete[] x_cpy;\n  if(y_cpy!=y)  delete[] y_cpy;\n\n  return 1;\n}\n\n/**  ZHER   performs the hermitian rank 1 operation\n  *\n  *     A := alpha*x*conjg( x' ) + A,\n  *\n  *  where alpha is a real scalar, x is an n element vector and A is an\n  *  n by n hermitian matrix.\n  */\nint EIGEN_BLAS_FUNC(her)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *pa, int *lda)\n{\n  typedef void (*functype)(int, Scalar*, int, const Scalar*, const Scalar*, const Scalar&);\n  static const functype func[2] = {\n    // array index: UP\n    (selfadjoint_rank1_update<Scalar,int,ColMajor,Upper,false,Conj>::run),\n    // array index: LO\n    (selfadjoint_rank1_update<Scalar,int,ColMajor,Lower,false,Conj>::run),\n  };\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  RealScalar alpha = *reinterpret_cast<RealScalar*>(palpha);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  else if(*lda<std::max(1,*n))                                        info = 7;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"HER  \",&info,6);\n\n  if(alpha==RealScalar(0))\n    return 1;\n\n  Scalar* x_cpy = get_compact_vector(x, *n, *incx);\n\n  int code = UPLO(*uplo);\n  if(code>=2 || func[code]==0)\n    return 0;\n\n  func[code](*n, a, *lda, x_cpy, x_cpy, alpha);\n\n  matrix(a,*n,*n,*lda).diagonal().imag().setZero();\n\n  if(x_cpy!=x)  delete[] x_cpy;\n\n  return 1;\n}\n\n/**  ZHER2  performs the hermitian rank 2 operation\n  *\n  *     A := alpha*x*conjg( y' ) + conjg( alpha )*y*conjg( x' ) + A,\n  *\n  *  where alpha is a scalar, x and y are n element vectors and A is an n\n  *  by n hermitian matrix.\n  */\nint EIGEN_BLAS_FUNC(her2)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pa, int *lda)\n{\n  typedef void (*functype)(int, Scalar*, int, const Scalar*, const Scalar*, Scalar);\n  static const functype func[2] = {\n    // array index: UP\n    (internal::rank2_update_selector<Scalar,int,Upper>::run),\n    // array index: LO\n    (internal::rank2_update_selector<Scalar,int,Lower>::run),\n  };\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  Scalar alpha = *reinterpret_cast<Scalar*>(palpha);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  else if(*incy==0)                                                   info = 7;\n  else if(*lda<std::max(1,*n))                                        info = 9;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"HER2 \",&info,6);\n\n  if(alpha==Scalar(0))\n    return 1;\n\n  Scalar* x_cpy = get_compact_vector(x, *n, *incx);\n  Scalar* y_cpy = get_compact_vector(y, *n, *incy);\n\n  int code = UPLO(*uplo);\n  if(code>=2 || func[code]==0)\n    return 0;\n\n  func[code](*n, a, *lda, x_cpy, y_cpy, alpha);\n\n  matrix(a,*n,*n,*lda).diagonal().imag().setZero();\n\n  if(x_cpy!=x)  delete[] x_cpy;\n  if(y_cpy!=y)  delete[] y_cpy;\n\n  return 1;\n}\n\n/**  ZGERU  performs the rank 1 operation\n  *\n  *     A := alpha*x*y' + A,\n  *\n  *  where alpha is a scalar, x is an m element vector, y is an n element\n  *  vector and A is an m by n matrix.\n  */\nint EIGEN_BLAS_FUNC(geru)(int *m, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pa, int *lda)\n{\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  Scalar alpha = *reinterpret_cast<Scalar*>(palpha);\n\n  int info = 0;\n       if(*m<0)                                                       info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  else if(*incy==0)                                                   info = 7;\n  else if(*lda<std::max(1,*m))                                        info = 9;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"GERU \",&info,6);\n\n  if(alpha==Scalar(0))\n    return 1;\n\n  Scalar* x_cpy = get_compact_vector(x,*m,*incx);\n  Scalar* y_cpy = get_compact_vector(y,*n,*incy);\n\n  internal::general_rank1_update<Scalar,int,ColMajor,false,false>::run(*m, *n, a, *lda, x_cpy, y_cpy, alpha);\n\n  if(x_cpy!=x)  delete[] x_cpy;\n  if(y_cpy!=y)  delete[] y_cpy;\n\n  return 1;\n}\n\n/**  ZGERC  performs the rank 1 operation\n  *\n  *     A := alpha*x*conjg( y' ) + A,\n  *\n  *  where alpha is a scalar, x is an m element vector, y is an n element\n  *  vector and A is an m by n matrix.\n  */\nint EIGEN_BLAS_FUNC(gerc)(int *m, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pa, int *lda)\n{\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  Scalar alpha = *reinterpret_cast<Scalar*>(palpha);\n\n  int info = 0;\n       if(*m<0)                                                       info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  else if(*incy==0)                                                   info = 7;\n  else if(*lda<std::max(1,*m))                                        info = 9;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"GERC \",&info,6);\n\n  if(alpha==Scalar(0))\n    return 1;\n\n  Scalar* x_cpy = get_compact_vector(x,*m,*incx);\n  Scalar* y_cpy = get_compact_vector(y,*n,*incy);\n\n  internal::general_rank1_update<Scalar,int,ColMajor,false,Conj>::run(*m, *n, a, *lda, x_cpy, y_cpy, alpha);\n\n  if(x_cpy!=x)  delete[] x_cpy;\n  if(y_cpy!=y)  delete[] y_cpy;\n\n  return 1;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/level2_impl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"common.h\"\n\ntemplate<typename Index, typename Scalar, int StorageOrder, bool ConjugateLhs, bool ConjugateRhs>\nstruct general_matrix_vector_product_wrapper\n{\n  static void run(Index rows, Index cols,const Scalar *lhs, Index lhsStride, const Scalar *rhs, Index rhsIncr, Scalar* res, Index resIncr, Scalar alpha)\n  {\n    typedef internal::const_blas_data_mapper<Scalar,Index,StorageOrder> LhsMapper;\n    typedef internal::const_blas_data_mapper<Scalar,Index,RowMajor> RhsMapper;\n    \n    internal::general_matrix_vector_product\n        <Index,Scalar,LhsMapper,StorageOrder,ConjugateLhs,Scalar,RhsMapper,ConjugateRhs>::run(\n        rows, cols, LhsMapper(lhs, lhsStride), RhsMapper(rhs, rhsIncr), res, resIncr, alpha);\n  }\n};\n\nint EIGEN_BLAS_FUNC(gemv)(const char *opa, const int *m, const int *n, const RealScalar *palpha,\n                          const RealScalar *pa, const int *lda, const RealScalar *pb, const int *incb, const RealScalar *pbeta, RealScalar *pc, const int *incc)\n{\n  typedef void (*functype)(int, int, const Scalar *, int, const Scalar *, int , Scalar *, int, Scalar);\n  static const functype func[4] = {\n    // array index: NOTR\n    (general_matrix_vector_product_wrapper<int,Scalar,ColMajor,false,false>::run),\n    // array index: TR  \n    (general_matrix_vector_product_wrapper<int,Scalar,RowMajor,false,false>::run),\n    // array index: ADJ \n    (general_matrix_vector_product_wrapper<int,Scalar,RowMajor,Conj ,false>::run),\n    0\n  };\n\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  const Scalar* b = reinterpret_cast<const Scalar*>(pb);\n  Scalar* c = reinterpret_cast<Scalar*>(pc);\n  Scalar alpha  = *reinterpret_cast<const Scalar*>(palpha);\n  Scalar beta   = *reinterpret_cast<const Scalar*>(pbeta);\n\n  // check arguments\n  int info = 0;\n  if(OP(*opa)==INVALID)           info = 1;\n  else if(*m<0)                   info = 2;\n  else if(*n<0)                   info = 3;\n  else if(*lda<std::max(1,*m))    info = 6;\n  else if(*incb==0)               info = 8;\n  else if(*incc==0)               info = 11;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"GEMV \",&info,6);\n\n  if(*m==0 || *n==0 || (alpha==Scalar(0) && beta==Scalar(1)))\n    return 0;\n\n  int actual_m = *m;\n  int actual_n = *n;\n  int code = OP(*opa);\n  if(code!=NOTR)\n    std::swap(actual_m,actual_n);\n\n  const Scalar* actual_b = get_compact_vector(b,actual_n,*incb);\n  Scalar* actual_c = get_compact_vector(c,actual_m,*incc);\n\n  if(beta!=Scalar(1))\n  {\n    if(beta==Scalar(0)) make_vector(actual_c, actual_m).setZero();\n    else                make_vector(actual_c, actual_m) *= beta;\n  }\n\n  if(code>=4 || func[code]==0)\n    return 0;\n\n  func[code](actual_m, actual_n, a, *lda, actual_b, 1, actual_c, 1, alpha);\n\n  if(actual_b!=b) delete[] actual_b;\n  if(actual_c!=c) delete[] copy_back(actual_c,c,actual_m,*incc);\n\n  return 1;\n}\n\nint EIGEN_BLAS_FUNC(trsv)(const char *uplo, const char *opa, const char *diag, const int *n, const RealScalar *pa, const int *lda, RealScalar *pb, const int *incb)\n{\n  typedef void (*functype)(int, const Scalar *, int, Scalar *);\n  static const functype func[16] = {\n    // array index: NOTR  | (UP << 2) | (NUNIT << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|0,       false,ColMajor>::run),\n    // array index: TR    | (UP << 2) | (NUNIT << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|0,       false,RowMajor>::run),\n    // array index: ADJ   | (UP << 2) | (NUNIT << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|0,       Conj, RowMajor>::run),\n    0,\n    // array index: NOTR  | (LO << 2) | (NUNIT << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|0,       false,ColMajor>::run),\n    // array index: TR    | (LO << 2) | (NUNIT << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|0,       false,RowMajor>::run),\n    // array index: ADJ   | (LO << 2) | (NUNIT << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|0,       Conj, RowMajor>::run),\n    0,\n    // array index: NOTR  | (UP << 2) | (UNIT  << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|UnitDiag,false,ColMajor>::run),\n    // array index: TR    | (UP << 2) | (UNIT  << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|UnitDiag,false,RowMajor>::run),\n    // array index: ADJ   | (UP << 2) | (UNIT  << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|UnitDiag,Conj, RowMajor>::run),\n    0,\n    // array index: NOTR  | (LO << 2) | (UNIT  << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|UnitDiag,false,ColMajor>::run),\n    // array index: TR    | (LO << 2) | (UNIT  << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|UnitDiag,false,RowMajor>::run),\n    // array index: ADJ   | (LO << 2) | (UNIT  << 3)\n    (internal::triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|UnitDiag,Conj, RowMajor>::run),\n    0\n  };\n\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  Scalar* b = reinterpret_cast<Scalar*>(pb);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(OP(*opa)==INVALID)                                          info = 2;\n  else if(DIAG(*diag)==INVALID)                                       info = 3;\n  else if(*n<0)                                                       info = 4;\n  else if(*lda<std::max(1,*n))                                        info = 6;\n  else if(*incb==0)                                                   info = 8;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"TRSV \",&info,6);\n\n  Scalar* actual_b = get_compact_vector(b,*n,*incb);\n\n  int code = OP(*opa) | (UPLO(*uplo) << 2) | (DIAG(*diag) << 3);\n  func[code](*n, a, *lda, actual_b);\n\n  if(actual_b!=b) delete[] copy_back(actual_b,b,*n,*incb);\n\n  return 0;\n}\n\n\n\nint EIGEN_BLAS_FUNC(trmv)(const char *uplo, const char *opa, const char *diag, const int *n, const RealScalar *pa, const int *lda, RealScalar *pb, const int *incb)\n{\n  typedef void (*functype)(int, int, const Scalar *, int, const Scalar *, int, Scalar *, int, const Scalar&);\n  static const functype func[16] = {\n    // array index: NOTR  | (UP << 2) | (NUNIT << 3)\n    (internal::triangular_matrix_vector_product<int,Upper|0,       Scalar,false,Scalar,false,ColMajor>::run),\n    // array index: TR    | (UP << 2) | (NUNIT << 3)\n    (internal::triangular_matrix_vector_product<int,Lower|0,       Scalar,false,Scalar,false,RowMajor>::run),\n    // array index: ADJ   | (UP << 2) | (NUNIT << 3)\n    (internal::triangular_matrix_vector_product<int,Lower|0,       Scalar,Conj, Scalar,false,RowMajor>::run),\n    0,\n    // array index: NOTR  | (LO << 2) | (NUNIT << 3)\n    (internal::triangular_matrix_vector_product<int,Lower|0,       Scalar,false,Scalar,false,ColMajor>::run),\n    // array index: TR    | (LO << 2) | (NUNIT << 3)\n    (internal::triangular_matrix_vector_product<int,Upper|0,       Scalar,false,Scalar,false,RowMajor>::run),\n    // array index: ADJ   | (LO << 2) | (NUNIT << 3)\n    (internal::triangular_matrix_vector_product<int,Upper|0,       Scalar,Conj, Scalar,false,RowMajor>::run),\n    0,\n    // array index: NOTR  | (UP << 2) | (UNIT  << 3)\n    (internal::triangular_matrix_vector_product<int,Upper|UnitDiag,Scalar,false,Scalar,false,ColMajor>::run),\n    // array index: TR    | (UP << 2) | (UNIT  << 3)\n    (internal::triangular_matrix_vector_product<int,Lower|UnitDiag,Scalar,false,Scalar,false,RowMajor>::run),\n    // array index: ADJ   | (UP << 2) | (UNIT  << 3)\n    (internal::triangular_matrix_vector_product<int,Lower|UnitDiag,Scalar,Conj, Scalar,false,RowMajor>::run),\n    0,\n    // array index: NOTR  | (LO << 2) | (UNIT  << 3)\n    (internal::triangular_matrix_vector_product<int,Lower|UnitDiag,Scalar,false,Scalar,false,ColMajor>::run),\n    // array index: TR    | (LO << 2) | (UNIT  << 3)\n    (internal::triangular_matrix_vector_product<int,Upper|UnitDiag,Scalar,false,Scalar,false,RowMajor>::run),\n    // array index: ADJ   | (LO << 2) | (UNIT  << 3)\n    (internal::triangular_matrix_vector_product<int,Upper|UnitDiag,Scalar,Conj, Scalar,false,RowMajor>::run),\n    0\n  };\n\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  Scalar* b = reinterpret_cast<Scalar*>(pb);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(OP(*opa)==INVALID)                                          info = 2;\n  else if(DIAG(*diag)==INVALID)                                       info = 3;\n  else if(*n<0)                                                       info = 4;\n  else if(*lda<std::max(1,*n))                                        info = 6;\n  else if(*incb==0)                                                   info = 8;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"TRMV \",&info,6);\n\n  if(*n==0)\n    return 1;\n\n  Scalar* actual_b = get_compact_vector(b,*n,*incb);\n  Matrix<Scalar,Dynamic,1> res(*n);\n  res.setZero();\n\n  int code = OP(*opa) | (UPLO(*uplo) << 2) | (DIAG(*diag) << 3);\n  if(code>=16 || func[code]==0)\n    return 0;\n\n  func[code](*n, *n, a, *lda, actual_b, 1, res.data(), 1, Scalar(1));\n\n  copy_back(res.data(),b,*n,*incb);\n  if(actual_b!=b) delete[] actual_b;\n\n  return 1;\n}\n\n/**  GBMV  performs one of the matrix-vector operations\n  *\n  *     y := alpha*A*x + beta*y,   or   y := alpha*A'*x + beta*y,\n  *\n  *  where alpha and beta are scalars, x and y are vectors and A is an\n  *  m by n band matrix, with kl sub-diagonals and ku super-diagonals.\n  */\nint EIGEN_BLAS_FUNC(gbmv)(char *trans, int *m, int *n, int *kl, int *ku, RealScalar *palpha, RealScalar *pa, int *lda,\n                          RealScalar *px, int *incx, RealScalar *pbeta, RealScalar *py, int *incy)\n{\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  const Scalar* x = reinterpret_cast<const Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar alpha = *reinterpret_cast<const Scalar*>(palpha);\n  Scalar beta = *reinterpret_cast<const Scalar*>(pbeta);\n  int coeff_rows = *kl+*ku+1;\n\n  int info = 0;\n       if(OP(*trans)==INVALID)                                        info = 1;\n  else if(*m<0)                                                       info = 2;\n  else if(*n<0)                                                       info = 3;\n  else if(*kl<0)                                                      info = 4;\n  else if(*ku<0)                                                      info = 5;\n  else if(*lda<coeff_rows)                                            info = 8;\n  else if(*incx==0)                                                   info = 10;\n  else if(*incy==0)                                                   info = 13;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"GBMV \",&info,6);\n\n  if(*m==0 || *n==0 || (alpha==Scalar(0) && beta==Scalar(1)))\n    return 0;\n\n  int actual_m = *m;\n  int actual_n = *n;\n  if(OP(*trans)!=NOTR)\n    std::swap(actual_m,actual_n);\n\n  const Scalar* actual_x = get_compact_vector(x,actual_n,*incx);\n  Scalar* actual_y = get_compact_vector(y,actual_m,*incy);\n\n  if(beta!=Scalar(1))\n  {\n    if(beta==Scalar(0)) make_vector(actual_y, actual_m).setZero();\n    else                make_vector(actual_y, actual_m) *= beta;\n  }\n\n  ConstMatrixType mat_coeffs(a,coeff_rows,*n,*lda);\n\n  int nb = std::min(*n,(*m)+(*ku));\n  for(int j=0; j<nb; ++j)\n  {\n    int start = std::max(0,j - *ku);\n    int end = std::min((*m)-1,j + *kl);\n    int len = end - start + 1;\n    int offset = (*ku) - j + start;\n    if(OP(*trans)==NOTR)\n      make_vector(actual_y+start,len) += (alpha*actual_x[j]) * mat_coeffs.col(j).segment(offset,len);\n    else if(OP(*trans)==TR)\n      actual_y[j] += alpha * ( mat_coeffs.col(j).segment(offset,len).transpose() * make_vector(actual_x+start,len) ).value();\n    else\n      actual_y[j] += alpha * ( mat_coeffs.col(j).segment(offset,len).adjoint()   * make_vector(actual_x+start,len) ).value();\n  }\n\n  if(actual_x!=x) delete[] actual_x;\n  if(actual_y!=y) delete[] copy_back(actual_y,y,actual_m,*incy);\n\n  return 0;\n}\n\n#if 0\n/**  TBMV  performs one of the matrix-vector operations\n  *\n  *     x := A*x,   or   x := A'*x,\n  *\n  *  where x is an n element vector and  A is an n by n unit, or non-unit,\n  *  upper or lower triangular band matrix, with ( k + 1 ) diagonals.\n  */\nint EIGEN_BLAS_FUNC(tbmv)(char *uplo, char *opa, char *diag, int *n, int *k, RealScalar *pa, int *lda, RealScalar *px, int *incx)\n{\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  int coeff_rows = *k + 1;\n\n  int info = 0;\n       if(UPLO(*uplo)==INVALID)                                       info = 1;\n  else if(OP(*opa)==INVALID)                                          info = 2;\n  else if(DIAG(*diag)==INVALID)                                       info = 3;\n  else if(*n<0)                                                       info = 4;\n  else if(*k<0)                                                       info = 5;\n  else if(*lda<coeff_rows)                                            info = 7;\n  else if(*incx==0)                                                   info = 9;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"TBMV \",&info,6);\n\n  if(*n==0)\n    return 0;\n\n  int actual_n = *n;\n\n  Scalar* actual_x = get_compact_vector(x,actual_n,*incx);\n\n  MatrixType mat_coeffs(a,coeff_rows,*n,*lda);\n\n  int ku = UPLO(*uplo)==UPPER ? *k : 0;\n  int kl = UPLO(*uplo)==LOWER ? *k : 0;\n\n  for(int j=0; j<*n; ++j)\n  {\n    int start = std::max(0,j - ku);\n    int end = std::min((*m)-1,j + kl);\n    int len = end - start + 1;\n    int offset = (ku) - j + start;\n\n    if(OP(*trans)==NOTR)\n      make_vector(actual_y+start,len) += (alpha*actual_x[j]) * mat_coeffs.col(j).segment(offset,len);\n    else if(OP(*trans)==TR)\n      actual_y[j] += alpha * ( mat_coeffs.col(j).segment(offset,len).transpose() * make_vector(actual_x+start,len) ).value();\n    else\n      actual_y[j] += alpha * ( mat_coeffs.col(j).segment(offset,len).adjoint()   * make_vector(actual_x+start,len) ).value();\n  }\n\n  if(actual_x!=x) delete[] actual_x;\n  if(actual_y!=y) delete[] copy_back(actual_y,y,actual_m,*incy);\n\n  return 0;\n}\n#endif\n\n/**  DTBSV  solves one of the systems of equations\n  *\n  *     A*x = b,   or   A'*x = b,\n  *\n  *  where b and x are n element vectors and A is an n by n unit, or\n  *  non-unit, upper or lower triangular band matrix, with ( k + 1 )\n  *  diagonals.\n  *\n  *  No test for singularity or near-singularity is included in this\n  *  routine. Such tests must be performed before calling this routine.\n  */\nint EIGEN_BLAS_FUNC(tbsv)(char *uplo, char *op, char *diag, int *n, int *k, RealScalar *pa, int *lda, RealScalar *px, int *incx)\n{\n  typedef void (*functype)(int, int, const Scalar *, int, Scalar *);\n  static const functype func[16] = {\n    // array index: NOTR  | (UP << 2) | (NUNIT << 3)\n    (internal::band_solve_triangular_selector<int,Upper|0,       Scalar,false,Scalar,ColMajor>::run),\n    // array index: TR    | (UP << 2) | (NUNIT << 3)\n    (internal::band_solve_triangular_selector<int,Lower|0,       Scalar,false,Scalar,RowMajor>::run),\n    // array index: ADJ   | (UP << 2) | (NUNIT << 3)\n    (internal::band_solve_triangular_selector<int,Lower|0,       Scalar,Conj, Scalar,RowMajor>::run),\n    0,\n    // array index: NOTR  | (LO << 2) | (NUNIT << 3)\n    (internal::band_solve_triangular_selector<int,Lower|0,       Scalar,false,Scalar,ColMajor>::run),\n    // array index: TR    | (LO << 2) | (NUNIT << 3)\n    (internal::band_solve_triangular_selector<int,Upper|0,       Scalar,false,Scalar,RowMajor>::run),\n    // array index: ADJ   | (LO << 2) | (NUNIT << 3)\n    (internal::band_solve_triangular_selector<int,Upper|0,       Scalar,Conj, Scalar,RowMajor>::run),\n    0,\n    // array index: NOTR  | (UP << 2) | (UNIT  << 3)\n    (internal::band_solve_triangular_selector<int,Upper|UnitDiag,Scalar,false,Scalar,ColMajor>::run),\n    // array index: TR    | (UP << 2) | (UNIT  << 3)\n    (internal::band_solve_triangular_selector<int,Lower|UnitDiag,Scalar,false,Scalar,RowMajor>::run),\n    // array index: ADJ   | (UP << 2) | (UNIT  << 3)\n    (internal::band_solve_triangular_selector<int,Lower|UnitDiag,Scalar,Conj, Scalar,RowMajor>::run),\n    0,\n    // array index: NOTR  | (LO << 2) | (UNIT  << 3)\n    (internal::band_solve_triangular_selector<int,Lower|UnitDiag,Scalar,false,Scalar,ColMajor>::run),\n    // array index: TR    | (LO << 2) | (UNIT  << 3)\n    (internal::band_solve_triangular_selector<int,Upper|UnitDiag,Scalar,false,Scalar,RowMajor>::run),\n    // array index: ADJ   | (LO << 2) | (UNIT  << 3)\n    (internal::band_solve_triangular_selector<int,Upper|UnitDiag,Scalar,Conj, Scalar,RowMajor>::run),\n    0,\n  };\n\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  int coeff_rows = *k+1;\n\n  int info = 0;\n       if(UPLO(*uplo)==INVALID)                                       info = 1;\n  else if(OP(*op)==INVALID)                                           info = 2;\n  else if(DIAG(*diag)==INVALID)                                       info = 3;\n  else if(*n<0)                                                       info = 4;\n  else if(*k<0)                                                       info = 5;\n  else if(*lda<coeff_rows)                                            info = 7;\n  else if(*incx==0)                                                   info = 9;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"TBSV \",&info,6);\n\n  if(*n==0 || (*k==0 && DIAG(*diag)==UNIT))\n    return 0;\n\n  int actual_n = *n;\n\n  Scalar* actual_x = get_compact_vector(x,actual_n,*incx);\n\n  int code = OP(*op) | (UPLO(*uplo) << 2) | (DIAG(*diag) << 3);\n  if(code>=16 || func[code]==0)\n    return 0;\n\n  func[code](*n, *k, a, *lda, actual_x);\n\n  if(actual_x!=x) delete[] copy_back(actual_x,x,actual_n,*incx);\n\n  return 0;\n}\n\n/**  DTPMV  performs one of the matrix-vector operations\n  *\n  *     x := A*x,   or   x := A'*x,\n  *\n  *  where x is an n element vector and  A is an n by n unit, or non-unit,\n  *  upper or lower triangular matrix, supplied in packed form.\n  */\nint EIGEN_BLAS_FUNC(tpmv)(char *uplo, char *opa, char *diag, int *n, RealScalar *pap, RealScalar *px, int *incx)\n{\n  typedef void (*functype)(int, const Scalar*, const Scalar*, Scalar*, Scalar);\n  static const functype func[16] = {\n    // array index: NOTR  | (UP << 2) | (NUNIT << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Upper|0,       Scalar,false,Scalar,false,ColMajor>::run),\n    // array index: TR    | (UP << 2) | (NUNIT << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Lower|0,       Scalar,false,Scalar,false,RowMajor>::run),\n    // array index: ADJ   | (UP << 2) | (NUNIT << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Lower|0,       Scalar,Conj, Scalar,false,RowMajor>::run),\n    0,\n    // array index: NOTR  | (LO << 2) | (NUNIT << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Lower|0,       Scalar,false,Scalar,false,ColMajor>::run),\n    // array index: TR    | (LO << 2) | (NUNIT << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Upper|0,       Scalar,false,Scalar,false,RowMajor>::run),\n    // array index: ADJ   | (LO << 2) | (NUNIT << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Upper|0,       Scalar,Conj, Scalar,false,RowMajor>::run),\n    0,\n    // array index: NOTR  | (UP << 2) | (UNIT  << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Upper|UnitDiag,Scalar,false,Scalar,false,ColMajor>::run),\n    // array index: TR    | (UP << 2) | (UNIT  << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Lower|UnitDiag,Scalar,false,Scalar,false,RowMajor>::run),\n    // array index: ADJ   | (UP << 2) | (UNIT  << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Lower|UnitDiag,Scalar,Conj, Scalar,false,RowMajor>::run),\n    0,\n    // array index: NOTR  | (LO << 2) | (UNIT  << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Lower|UnitDiag,Scalar,false,Scalar,false,ColMajor>::run),\n    // array index: TR    | (LO << 2) | (UNIT  << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Upper|UnitDiag,Scalar,false,Scalar,false,RowMajor>::run),\n    // array index: ADJ   | (LO << 2) | (UNIT  << 3)\n    (internal::packed_triangular_matrix_vector_product<int,Upper|UnitDiag,Scalar,Conj, Scalar,false,RowMajor>::run),\n    0\n  };\n\n  Scalar* ap = reinterpret_cast<Scalar*>(pap);\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(OP(*opa)==INVALID)                                          info = 2;\n  else if(DIAG(*diag)==INVALID)                                       info = 3;\n  else if(*n<0)                                                       info = 4;\n  else if(*incx==0)                                                   info = 7;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"TPMV \",&info,6);\n\n  if(*n==0)\n    return 1;\n\n  Scalar* actual_x = get_compact_vector(x,*n,*incx);\n  Matrix<Scalar,Dynamic,1> res(*n);\n  res.setZero();\n\n  int code = OP(*opa) | (UPLO(*uplo) << 2) | (DIAG(*diag) << 3);\n  if(code>=16 || func[code]==0)\n    return 0;\n\n  func[code](*n, ap, actual_x, res.data(), Scalar(1));\n\n  copy_back(res.data(),x,*n,*incx);\n  if(actual_x!=x) delete[] actual_x;\n\n  return 1;\n}\n\n/**  DTPSV  solves one of the systems of equations\n  *\n  *     A*x = b,   or   A'*x = b,\n  *\n  *  where b and x are n element vectors and A is an n by n unit, or\n  *  non-unit, upper or lower triangular matrix, supplied in packed form.\n  *\n  *  No test for singularity or near-singularity is included in this\n  *  routine. Such tests must be performed before calling this routine.\n  */\nint EIGEN_BLAS_FUNC(tpsv)(char *uplo, char *opa, char *diag, int *n, RealScalar *pap, RealScalar *px, int *incx)\n{\n  typedef void (*functype)(int, const Scalar*, Scalar*);\n  static const functype func[16] = {\n    // array index: NOTR  | (UP << 2) | (NUNIT << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|0,       false,ColMajor>::run),\n    // array index: TR    | (UP << 2) | (NUNIT << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|0,       false,RowMajor>::run),\n    // array index: ADJ   | (UP << 2) | (NUNIT << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|0,       Conj, RowMajor>::run),\n    0,\n    // array index: NOTR  | (LO << 2) | (NUNIT << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|0,       false,ColMajor>::run),\n    // array index: TR    | (LO << 2) | (NUNIT << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|0,       false,RowMajor>::run),\n    // array index: ADJ   | (LO << 2) | (NUNIT << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|0,       Conj, RowMajor>::run),\n    0,\n    // array index: NOTR  | (UP << 2) | (UNIT  << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|UnitDiag,false,ColMajor>::run),\n    // array index: TR    | (UP << 2) | (UNIT  << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|UnitDiag,false,RowMajor>::run),\n    // array index: ADJ   | (UP << 2) | (UNIT  << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|UnitDiag,Conj, RowMajor>::run),\n    0,\n    // array index: NOTR  | (LO << 2) | (UNIT  << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Lower|UnitDiag,false,ColMajor>::run),\n    // array index: TR    | (LO << 2) | (UNIT  << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|UnitDiag,false,RowMajor>::run),\n    // array index: ADJ   | (LO << 2) | (UNIT  << 3)\n    (internal::packed_triangular_solve_vector<Scalar,Scalar,int,OnTheLeft, Upper|UnitDiag,Conj, RowMajor>::run),\n    0\n  };\n\n  Scalar* ap = reinterpret_cast<Scalar*>(pap);\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(OP(*opa)==INVALID)                                          info = 2;\n  else if(DIAG(*diag)==INVALID)                                       info = 3;\n  else if(*n<0)                                                       info = 4;\n  else if(*incx==0)                                                   info = 7;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"TPSV \",&info,6);\n\n  Scalar* actual_x = get_compact_vector(x,*n,*incx);\n\n  int code = OP(*opa) | (UPLO(*uplo) << 2) | (DIAG(*diag) << 3);\n  func[code](*n, ap, actual_x);\n\n  if(actual_x!=x) delete[] copy_back(actual_x,x,*n,*incx);\n\n  return 1;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/level2_real_impl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"common.h\"\n\n// y = alpha*A*x + beta*y\nint EIGEN_BLAS_FUNC(symv) (const char *uplo, const int *n, const RealScalar *palpha, const RealScalar *pa, const int *lda,\n                           const RealScalar *px, const int *incx, const RealScalar *pbeta, RealScalar *py, const int *incy)\n{\n  typedef void (*functype)(int, const Scalar*, int, const Scalar*, Scalar*, Scalar);\n  static const functype func[2] = {\n    // array index: UP\n    (internal::selfadjoint_matrix_vector_product<Scalar,int,ColMajor,Upper,false,false>::run),\n    // array index: LO\n    (internal::selfadjoint_matrix_vector_product<Scalar,int,ColMajor,Lower,false,false>::run),\n  };\n\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  const Scalar* x = reinterpret_cast<const Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar alpha  = *reinterpret_cast<const Scalar*>(palpha);\n  Scalar beta   = *reinterpret_cast<const Scalar*>(pbeta);\n\n  // check arguments\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)        info = 1;\n  else if(*n<0)                   info = 2;\n  else if(*lda<std::max(1,*n))    info = 5;\n  else if(*incx==0)               info = 7;\n  else if(*incy==0)               info = 10;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"SYMV \",&info,6);\n\n  if(*n==0)\n    return 0;\n\n  const Scalar* actual_x = get_compact_vector(x,*n,*incx);\n  Scalar* actual_y = get_compact_vector(y,*n,*incy);\n\n  if(beta!=Scalar(1))\n  {\n    if(beta==Scalar(0)) make_vector(actual_y, *n).setZero();\n    else                make_vector(actual_y, *n) *= beta;\n  }\n\n  int code = UPLO(*uplo);\n  if(code>=2 || func[code]==0)\n    return 0;\n\n  func[code](*n, a, *lda, actual_x, actual_y, alpha);\n\n  if(actual_x!=x) delete[] actual_x;\n  if(actual_y!=y) delete[] copy_back(actual_y,y,*n,*incy);\n\n  return 1;\n}\n\n// C := alpha*x*x' + C\nint EIGEN_BLAS_FUNC(syr)(const char *uplo, const int *n, const RealScalar *palpha, const RealScalar *px, const int *incx, RealScalar *pc, const int *ldc)\n{\n\n  typedef void (*functype)(int, Scalar*, int, const Scalar*, const Scalar*, const Scalar&);\n  static const functype func[2] = {\n    // array index: UP\n    (selfadjoint_rank1_update<Scalar,int,ColMajor,Upper,false,Conj>::run),\n    // array index: LO\n    (selfadjoint_rank1_update<Scalar,int,ColMajor,Lower,false,Conj>::run),\n  };\n\n  const Scalar* x = reinterpret_cast<const Scalar*>(px);\n  Scalar* c = reinterpret_cast<Scalar*>(pc);\n  Scalar alpha = *reinterpret_cast<const Scalar*>(palpha);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  else if(*ldc<std::max(1,*n))                                        info = 7;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"SYR  \",&info,6);\n\n  if(*n==0 || alpha==Scalar(0)) return 1;\n\n  // if the increment is not 1, let's copy it to a temporary vector to enable vectorization\n  const Scalar* x_cpy = get_compact_vector(x,*n,*incx);\n\n  int code = UPLO(*uplo);\n  if(code>=2 || func[code]==0)\n    return 0;\n\n  func[code](*n, c, *ldc, x_cpy, x_cpy, alpha);\n\n  if(x_cpy!=x)  delete[] x_cpy;\n\n  return 1;\n}\n\n// C := alpha*x*y' + alpha*y*x' + C\nint EIGEN_BLAS_FUNC(syr2)(const char *uplo, const int *n, const RealScalar *palpha, const RealScalar *px, const int *incx, const RealScalar *py, const int *incy, RealScalar *pc, const int *ldc)\n{\n  typedef void (*functype)(int, Scalar*, int, const Scalar*, const Scalar*, Scalar);\n  static const functype func[2] = {\n    // array index: UP\n    (internal::rank2_update_selector<Scalar,int,Upper>::run),\n    // array index: LO\n    (internal::rank2_update_selector<Scalar,int,Lower>::run),\n  };\n\n  const Scalar* x = reinterpret_cast<const Scalar*>(px);\n  const Scalar* y = reinterpret_cast<const Scalar*>(py);\n  Scalar* c = reinterpret_cast<Scalar*>(pc);\n  Scalar alpha = *reinterpret_cast<const Scalar*>(palpha);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  else if(*incy==0)                                                   info = 7;\n  else if(*ldc<std::max(1,*n))                                        info = 9;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"SYR2 \",&info,6);\n\n  if(alpha==Scalar(0))\n    return 1;\n\n  const Scalar* x_cpy = get_compact_vector(x,*n,*incx);\n  const Scalar* y_cpy = get_compact_vector(y,*n,*incy);\n\n  int code = UPLO(*uplo);\n  if(code>=2 || func[code]==0)\n    return 0;\n\n  func[code](*n, c, *ldc, x_cpy, y_cpy, alpha);\n\n  if(x_cpy!=x)  delete[] x_cpy;\n  if(y_cpy!=y)  delete[] y_cpy;\n\n//   int code = UPLO(*uplo);\n//   if(code>=2 || func[code]==0)\n//     return 0;\n\n//   func[code](*n, a, *inca, b, *incb, c, *ldc, alpha);\n  return 1;\n}\n\n/**  DSBMV  performs the matrix-vector  operation\n  *\n  *     y := alpha*A*x + beta*y,\n  *\n  *  where alpha and beta are scalars, x and y are n element vectors and\n  *  A is an n by n symmetric band matrix, with k super-diagonals.\n  */\n// int EIGEN_BLAS_FUNC(sbmv)( char *uplo, int *n, int *k, RealScalar *alpha, RealScalar *a, int *lda,\n//                            RealScalar *x, int *incx, RealScalar *beta, RealScalar *y, int *incy)\n// {\n//   return 1;\n// }\n\n\n/**  DSPMV  performs the matrix-vector operation\n  *\n  *     y := alpha*A*x + beta*y,\n  *\n  *  where alpha and beta are scalars, x and y are n element vectors and\n  *  A is an n by n symmetric matrix, supplied in packed form.\n  *\n  */\n// int EIGEN_BLAS_FUNC(spmv)(char *uplo, int *n, RealScalar *alpha, RealScalar *ap, RealScalar *x, int *incx, RealScalar *beta, RealScalar *y, int *incy)\n// {\n//   return 1;\n// }\n\n/**  DSPR    performs the symmetric rank 1 operation\n  *\n  *     A := alpha*x*x' + A,\n  *\n  *  where alpha is a real scalar, x is an n element vector and A is an\n  *  n by n symmetric matrix, supplied in packed form.\n  */\nint EIGEN_BLAS_FUNC(spr)(char *uplo, int *n, Scalar *palpha, Scalar *px, int *incx, Scalar *pap)\n{\n  typedef void (*functype)(int, Scalar*, const Scalar*, Scalar);\n  static const functype func[2] = {\n    // array index: UP\n    (internal::selfadjoint_packed_rank1_update<Scalar,int,ColMajor,Upper,false,false>::run),\n    // array index: LO\n    (internal::selfadjoint_packed_rank1_update<Scalar,int,ColMajor,Lower,false,false>::run),\n  };\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* ap = reinterpret_cast<Scalar*>(pap);\n  Scalar alpha = *reinterpret_cast<Scalar*>(palpha);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"SPR  \",&info,6);\n\n  if(alpha==Scalar(0))\n    return 1;\n\n  Scalar* x_cpy = get_compact_vector(x, *n, *incx);\n\n  int code = UPLO(*uplo);\n  if(code>=2 || func[code]==0)\n    return 0;\n\n  func[code](*n, ap, x_cpy, alpha);\n\n  if(x_cpy!=x)  delete[] x_cpy;\n\n  return 1;\n}\n\n/**  DSPR2  performs the symmetric rank 2 operation\n  *\n  *     A := alpha*x*y' + alpha*y*x' + A,\n  *\n  *  where alpha is a scalar, x and y are n element vectors and A is an\n  *  n by n symmetric matrix, supplied in packed form.\n  */\nint EIGEN_BLAS_FUNC(spr2)(char *uplo, int *n, RealScalar *palpha, RealScalar *px, int *incx, RealScalar *py, int *incy, RealScalar *pap)\n{\n  typedef void (*functype)(int, Scalar*, const Scalar*, const Scalar*, Scalar);\n  static const functype func[2] = {\n    // array index: UP\n    (internal::packed_rank2_update_selector<Scalar,int,Upper>::run),\n    // array index: LO\n    (internal::packed_rank2_update_selector<Scalar,int,Lower>::run),\n  };\n\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar* ap = reinterpret_cast<Scalar*>(pap);\n  Scalar alpha = *reinterpret_cast<Scalar*>(palpha);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  else if(*incy==0)                                                   info = 7;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"SPR2 \",&info,6);\n\n  if(alpha==Scalar(0))\n    return 1;\n\n  Scalar* x_cpy = get_compact_vector(x, *n, *incx);\n  Scalar* y_cpy = get_compact_vector(y, *n, *incy);\n\n  int code = UPLO(*uplo);\n  if(code>=2 || func[code]==0)\n    return 0;\n\n  func[code](*n, ap, x_cpy, y_cpy, alpha);\n\n  if(x_cpy!=x)  delete[] x_cpy;\n  if(y_cpy!=y)  delete[] y_cpy;\n\n  return 1;\n}\n\n/**  DGER   performs the rank 1 operation\n  *\n  *     A := alpha*x*y' + A,\n  *\n  *  where alpha is a scalar, x is an m element vector, y is an n element\n  *  vector and A is an m by n matrix.\n  */\nint EIGEN_BLAS_FUNC(ger)(int *m, int *n, Scalar *palpha, Scalar *px, int *incx, Scalar *py, int *incy, Scalar *pa, int *lda)\n{\n  Scalar* x = reinterpret_cast<Scalar*>(px);\n  Scalar* y = reinterpret_cast<Scalar*>(py);\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  Scalar alpha = *reinterpret_cast<Scalar*>(palpha);\n\n  int info = 0;\n       if(*m<0)                                                       info = 1;\n  else if(*n<0)                                                       info = 2;\n  else if(*incx==0)                                                   info = 5;\n  else if(*incy==0)                                                   info = 7;\n  else if(*lda<std::max(1,*m))                                        info = 9;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"GER  \",&info,6);\n\n  if(alpha==Scalar(0))\n    return 1;\n\n  Scalar* x_cpy = get_compact_vector(x,*m,*incx);\n  Scalar* y_cpy = get_compact_vector(y,*n,*incy);\n\n  internal::general_rank1_update<Scalar,int,ColMajor,false,false>::run(*m, *n, a, *lda, x_cpy, y_cpy, alpha);\n\n  if(x_cpy!=x)  delete[] x_cpy;\n  if(y_cpy!=y)  delete[] y_cpy;\n\n  return 1;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/level3_impl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n#include <iostream>\n#include \"common.h\"\n\nint EIGEN_BLAS_FUNC(gemm)(const char *opa, const char *opb, const int *m, const int *n, const int *k, const RealScalar *palpha,\n                          const RealScalar *pa, const int *lda, const RealScalar *pb, const int *ldb, const RealScalar *pbeta, RealScalar *pc, const int *ldc)\n{\n//   std::cerr << \"in gemm \" << *opa << \" \" << *opb << \" \" << *m << \" \" << *n << \" \" << *k << \" \" << *lda << \" \" << *ldb << \" \" << *ldc << \" \" << *palpha << \" \" << *pbeta << \"\\n\";\n  typedef void (*functype)(DenseIndex, DenseIndex, DenseIndex, const Scalar *, DenseIndex, const Scalar *, DenseIndex, Scalar *, DenseIndex, DenseIndex, Scalar, internal::level3_blocking<Scalar,Scalar>&, Eigen::internal::GemmParallelInfo<DenseIndex>*);\n  static const functype func[12] = {\n    // array index: NOTR  | (NOTR << 2)\n    (internal::general_matrix_matrix_product<DenseIndex,Scalar,ColMajor,false,Scalar,ColMajor,false,ColMajor,1>::run),\n    // array index: TR    | (NOTR << 2)\n    (internal::general_matrix_matrix_product<DenseIndex,Scalar,RowMajor,false,Scalar,ColMajor,false,ColMajor,1>::run),\n    // array index: ADJ   | (NOTR << 2)\n    (internal::general_matrix_matrix_product<DenseIndex,Scalar,RowMajor,Conj, Scalar,ColMajor,false,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (TR   << 2)\n    (internal::general_matrix_matrix_product<DenseIndex,Scalar,ColMajor,false,Scalar,RowMajor,false,ColMajor,1>::run),\n    // array index: TR    | (TR   << 2)\n    (internal::general_matrix_matrix_product<DenseIndex,Scalar,RowMajor,false,Scalar,RowMajor,false,ColMajor,1>::run),\n    // array index: ADJ   | (TR   << 2)\n    (internal::general_matrix_matrix_product<DenseIndex,Scalar,RowMajor,Conj, Scalar,RowMajor,false,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (ADJ  << 2)\n    (internal::general_matrix_matrix_product<DenseIndex,Scalar,ColMajor,false,Scalar,RowMajor,Conj, ColMajor,1>::run),\n    // array index: TR    | (ADJ  << 2)\n    (internal::general_matrix_matrix_product<DenseIndex,Scalar,RowMajor,false,Scalar,RowMajor,Conj, ColMajor,1>::run),\n    // array index: ADJ   | (ADJ  << 2)\n    (internal::general_matrix_matrix_product<DenseIndex,Scalar,RowMajor,Conj, Scalar,RowMajor,Conj, ColMajor,1>::run),\n    0\n  };\n\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  const Scalar* b = reinterpret_cast<const Scalar*>(pb);\n  Scalar* c = reinterpret_cast<Scalar*>(pc);\n  Scalar alpha  = *reinterpret_cast<const Scalar*>(palpha);\n  Scalar beta   = *reinterpret_cast<const Scalar*>(pbeta);\n\n  int info = 0;\n  if(OP(*opa)==INVALID)                                               info = 1;\n  else if(OP(*opb)==INVALID)                                          info = 2;\n  else if(*m<0)                                                       info = 3;\n  else if(*n<0)                                                       info = 4;\n  else if(*k<0)                                                       info = 5;\n  else if(*lda<std::max(1,(OP(*opa)==NOTR)?*m:*k))                    info = 8;\n  else if(*ldb<std::max(1,(OP(*opb)==NOTR)?*k:*n))                    info = 10;\n  else if(*ldc<std::max(1,*m))                                        info = 13;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"GEMM \",&info,6);\n\n  if (*m == 0 || *n == 0)\n    return 0;\n\n  if(beta!=Scalar(1))\n  {\n    if(beta==Scalar(0)) matrix(c, *m, *n, *ldc).setZero();\n    else                matrix(c, *m, *n, *ldc) *= beta;\n  }\n\n  if(*k == 0)\n    return 0;\n\n  internal::gemm_blocking_space<ColMajor,Scalar,Scalar,Dynamic,Dynamic,Dynamic> blocking(*m,*n,*k,1,true);\n\n  int code = OP(*opa) | (OP(*opb) << 2);\n  func[code](*m, *n, *k, a, *lda, b, *ldb, c, 1, *ldc, alpha, blocking, 0);\n  return 0;\n}\n\nint EIGEN_BLAS_FUNC(trsm)(const char *side, const char *uplo, const char *opa, const char *diag, const int *m, const int *n,\n                          const RealScalar *palpha,  const RealScalar *pa, const int *lda, RealScalar *pb, const int *ldb)\n{\n//   std::cerr << \"in trsm \" << *side << \" \" << *uplo << \" \" << *opa << \" \" << *diag << \" \" << *m << \",\" << *n << \" \" << *palpha << \" \" << *lda << \" \" << *ldb<< \"\\n\";\n  typedef void (*functype)(DenseIndex, DenseIndex, const Scalar *, DenseIndex, Scalar *, DenseIndex, DenseIndex, internal::level3_blocking<Scalar,Scalar>&);\n  static const functype func[32] = {\n    // array index: NOTR  | (LEFT  << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Upper|0,          false,ColMajor,ColMajor,1>::run),\n    // array index: TR    | (LEFT  << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Lower|0,          false,RowMajor,ColMajor,1>::run),\n    // array index: ADJ   | (LEFT  << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Lower|0,          Conj, RowMajor,ColMajor,1>::run),\\\n    0,\n    // array index: NOTR  | (RIGHT << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Upper|0,          false,ColMajor,ColMajor,1>::run),\n    // array index: TR    | (RIGHT << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Lower|0,          false,RowMajor,ColMajor,1>::run),\n    // array index: ADJ   | (RIGHT << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Lower|0,          Conj, RowMajor,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (LEFT  << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Lower|0,          false,ColMajor,ColMajor,1>::run),\n    // array index: TR    | (LEFT  << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Upper|0,          false,RowMajor,ColMajor,1>::run),\n    // array index: ADJ   | (LEFT  << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Upper|0,          Conj, RowMajor,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (RIGHT << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Lower|0,          false,ColMajor,ColMajor,1>::run),\n    // array index: TR    | (RIGHT << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Upper|0,          false,RowMajor,ColMajor,1>::run),\n    // array index: ADJ   | (RIGHT << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Upper|0,          Conj, RowMajor,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (LEFT  << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Upper|UnitDiag,false,ColMajor,ColMajor,1>::run),\n    // array index: TR    | (LEFT  << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Lower|UnitDiag,false,RowMajor,ColMajor,1>::run),\n    // array index: ADJ   | (LEFT  << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Lower|UnitDiag,Conj, RowMajor,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (RIGHT << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Upper|UnitDiag,false,ColMajor,ColMajor,1>::run),\n    // array index: TR    | (RIGHT << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Lower|UnitDiag,false,RowMajor,ColMajor,1>::run),\n    // array index: ADJ   | (RIGHT << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Lower|UnitDiag,Conj, RowMajor,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (LEFT  << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Lower|UnitDiag,false,ColMajor,ColMajor,1>::run),\n    // array index: TR    | (LEFT  << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Upper|UnitDiag,false,RowMajor,ColMajor,1>::run),\n    // array index: ADJ   | (LEFT  << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheLeft, Upper|UnitDiag,Conj, RowMajor,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (RIGHT << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Lower|UnitDiag,false,ColMajor,ColMajor,1>::run),\n    // array index: TR    | (RIGHT << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Upper|UnitDiag,false,RowMajor,ColMajor,1>::run),\n    // array index: ADJ   | (RIGHT << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::triangular_solve_matrix<Scalar,DenseIndex,OnTheRight,Upper|UnitDiag,Conj, RowMajor,ColMajor,1>::run),\n    0\n  };\n\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  Scalar* b = reinterpret_cast<Scalar*>(pb);\n  Scalar  alpha = *reinterpret_cast<const Scalar*>(palpha);\n\n  int info = 0;\n  if(SIDE(*side)==INVALID)                                            info = 1;\n  else if(UPLO(*uplo)==INVALID)                                       info = 2;\n  else if(OP(*opa)==INVALID)                                          info = 3;\n  else if(DIAG(*diag)==INVALID)                                       info = 4;\n  else if(*m<0)                                                       info = 5;\n  else if(*n<0)                                                       info = 6;\n  else if(*lda<std::max(1,(SIDE(*side)==LEFT)?*m:*n))                 info = 9;\n  else if(*ldb<std::max(1,*m))                                        info = 11;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"TRSM \",&info,6);\n\n  if(*m==0 || *n==0)\n    return 0;\n\n  int code = OP(*opa) | (SIDE(*side) << 2) | (UPLO(*uplo) << 3) | (DIAG(*diag) << 4);\n\n  if(SIDE(*side)==LEFT)\n  {\n    internal::gemm_blocking_space<ColMajor,Scalar,Scalar,Dynamic,Dynamic,Dynamic,4> blocking(*m,*n,*m,1,false);\n    func[code](*m, *n, a, *lda, b, 1, *ldb, blocking);\n  }\n  else\n  {\n    internal::gemm_blocking_space<ColMajor,Scalar,Scalar,Dynamic,Dynamic,Dynamic,4> blocking(*m,*n,*n,1,false);\n    func[code](*n, *m, a, *lda, b, 1, *ldb, blocking);\n  }\n\n  if(alpha!=Scalar(1))\n    matrix(b,*m,*n,*ldb) *= alpha;\n\n  return 0;\n}\n\n\n// b = alpha*op(a)*b  for side = 'L'or'l'\n// b = alpha*b*op(a)  for side = 'R'or'r'\nint EIGEN_BLAS_FUNC(trmm)(const char *side, const char *uplo, const char *opa, const char *diag, const int *m, const int *n,\n                          const RealScalar *palpha, const RealScalar *pa, const int *lda, RealScalar *pb, const int *ldb)\n{\n//   std::cerr << \"in trmm \" << *side << \" \" << *uplo << \" \" << *opa << \" \" << *diag << \" \" << *m << \" \" << *n << \" \" << *lda << \" \" << *ldb << \" \" << *palpha << \"\\n\";\n  typedef void (*functype)(DenseIndex, DenseIndex, DenseIndex, const Scalar *, DenseIndex, const Scalar *, DenseIndex, Scalar *, DenseIndex, DenseIndex, const Scalar&, internal::level3_blocking<Scalar,Scalar>&);\n  static const functype func[32] = {\n    // array index: NOTR  | (LEFT  << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|0,          true, ColMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: TR    | (LEFT  << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|0,          true, RowMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: ADJ   | (LEFT  << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|0,          true, RowMajor,Conj, ColMajor,false,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (RIGHT << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|0,          false,ColMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: TR    | (RIGHT << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|0,          false,ColMajor,false,RowMajor,false,ColMajor,1>::run),\n    // array index: ADJ   | (RIGHT << 2) | (UP << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|0,          false,ColMajor,false,RowMajor,Conj, ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (LEFT  << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|0,          true, ColMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: TR    | (LEFT  << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|0,          true, RowMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: ADJ   | (LEFT  << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|0,          true, RowMajor,Conj, ColMajor,false,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (RIGHT << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|0,          false,ColMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: TR    | (RIGHT << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|0,          false,ColMajor,false,RowMajor,false,ColMajor,1>::run),\n    // array index: ADJ   | (RIGHT << 2) | (LO << 3) | (NUNIT << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|0,          false,ColMajor,false,RowMajor,Conj, ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (LEFT  << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|UnitDiag,true, ColMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: TR    | (LEFT  << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|UnitDiag,true, RowMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: ADJ   | (LEFT  << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|UnitDiag,true, RowMajor,Conj, ColMajor,false,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (RIGHT << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|UnitDiag,false,ColMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: TR    | (RIGHT << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|UnitDiag,false,ColMajor,false,RowMajor,false,ColMajor,1>::run),\n    // array index: ADJ   | (RIGHT << 2) | (UP << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|UnitDiag,false,ColMajor,false,RowMajor,Conj, ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (LEFT  << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|UnitDiag,true, ColMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: TR    | (LEFT  << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|UnitDiag,true, RowMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: ADJ   | (LEFT  << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|UnitDiag,true, RowMajor,Conj, ColMajor,false,ColMajor,1>::run),\n    0,\n    // array index: NOTR  | (RIGHT << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Lower|UnitDiag,false,ColMajor,false,ColMajor,false,ColMajor,1>::run),\n    // array index: TR    | (RIGHT << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|UnitDiag,false,ColMajor,false,RowMajor,false,ColMajor,1>::run),\n    // array index: ADJ   | (RIGHT << 2) | (LO << 3) | (UNIT  << 4)\n    (internal::product_triangular_matrix_matrix<Scalar,DenseIndex,Upper|UnitDiag,false,ColMajor,false,RowMajor,Conj, ColMajor,1>::run),\n    0\n  };\n\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  Scalar* b = reinterpret_cast<Scalar*>(pb);\n  Scalar  alpha = *reinterpret_cast<const Scalar*>(palpha);\n\n  int info = 0;\n  if(SIDE(*side)==INVALID)                                            info = 1;\n  else if(UPLO(*uplo)==INVALID)                                       info = 2;\n  else if(OP(*opa)==INVALID)                                          info = 3;\n  else if(DIAG(*diag)==INVALID)                                       info = 4;\n  else if(*m<0)                                                       info = 5;\n  else if(*n<0)                                                       info = 6;\n  else if(*lda<std::max(1,(SIDE(*side)==LEFT)?*m:*n))                 info = 9;\n  else if(*ldb<std::max(1,*m))                                        info = 11;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"TRMM \",&info,6);\n\n  int code = OP(*opa) | (SIDE(*side) << 2) | (UPLO(*uplo) << 3) | (DIAG(*diag) << 4);\n\n  if(*m==0 || *n==0)\n    return 1;\n\n  // FIXME find a way to avoid this copy\n  Matrix<Scalar,Dynamic,Dynamic,ColMajor> tmp = matrix(b,*m,*n,*ldb);\n  matrix(b,*m,*n,*ldb).setZero();\n\n  if(SIDE(*side)==LEFT)\n  {\n    internal::gemm_blocking_space<ColMajor,Scalar,Scalar,Dynamic,Dynamic,Dynamic,4> blocking(*m,*n,*m,1,false);\n    func[code](*m, *n, *m, a, *lda, tmp.data(), tmp.outerStride(), b, 1, *ldb, alpha, blocking);\n  }\n  else\n  {\n    internal::gemm_blocking_space<ColMajor,Scalar,Scalar,Dynamic,Dynamic,Dynamic,4> blocking(*m,*n,*n,1,false);\n    func[code](*m, *n, *n, tmp.data(), tmp.outerStride(), a, *lda, b, 1, *ldb, alpha, blocking);\n  }\n  return 1;\n}\n\n// c = alpha*a*b + beta*c  for side = 'L'or'l'\n// c = alpha*b*a + beta*c  for side = 'R'or'r\nint EIGEN_BLAS_FUNC(symm)(const char *side, const char *uplo, const int *m, const int *n, const RealScalar *palpha,\n                          const RealScalar *pa, const int *lda, const RealScalar *pb, const int *ldb, const RealScalar *pbeta, RealScalar *pc, const int *ldc)\n{\n//   std::cerr << \"in symm \" << *side << \" \" << *uplo << \" \" << *m << \"x\" << *n << \" lda:\" << *lda << \" ldb:\" << *ldb << \" ldc:\" << *ldc << \" alpha:\" << *palpha << \" beta:\" << *pbeta << \"\\n\";\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  const Scalar* b = reinterpret_cast<const Scalar*>(pb);\n  Scalar* c = reinterpret_cast<Scalar*>(pc);\n  Scalar alpha = *reinterpret_cast<const Scalar*>(palpha);\n  Scalar beta  = *reinterpret_cast<const Scalar*>(pbeta);\n\n  int info = 0;\n  if(SIDE(*side)==INVALID)                                            info = 1;\n  else if(UPLO(*uplo)==INVALID)                                       info = 2;\n  else if(*m<0)                                                       info = 3;\n  else if(*n<0)                                                       info = 4;\n  else if(*lda<std::max(1,(SIDE(*side)==LEFT)?*m:*n))                 info = 7;\n  else if(*ldb<std::max(1,*m))                                        info = 9;\n  else if(*ldc<std::max(1,*m))                                        info = 12;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"SYMM \",&info,6);\n\n  if(beta!=Scalar(1))\n  {\n    if(beta==Scalar(0)) matrix(c, *m, *n, *ldc).setZero();\n    else                matrix(c, *m, *n, *ldc) *= beta;\n  }\n\n  if(*m==0 || *n==0)\n  {\n    return 1;\n  }\n\n  int size = (SIDE(*side)==LEFT) ? (*m) : (*n);\n  #if ISCOMPLEX\n  // FIXME add support for symmetric complex matrix\n  Matrix<Scalar,Dynamic,Dynamic,ColMajor> matA(size,size);\n  if(UPLO(*uplo)==UP)\n  {\n    matA.triangularView<Upper>() = matrix(a,size,size,*lda);\n    matA.triangularView<Lower>() = matrix(a,size,size,*lda).transpose();\n  }\n  else if(UPLO(*uplo)==LO)\n  {\n    matA.triangularView<Lower>() = matrix(a,size,size,*lda);\n    matA.triangularView<Upper>() = matrix(a,size,size,*lda).transpose();\n  }\n  if(SIDE(*side)==LEFT)\n    matrix(c, *m, *n, *ldc) += alpha * matA * matrix(b, *m, *n, *ldb);\n  else if(SIDE(*side)==RIGHT)\n    matrix(c, *m, *n, *ldc) += alpha * matrix(b, *m, *n, *ldb) * matA;\n  #else\n  internal::gemm_blocking_space<ColMajor,Scalar,Scalar,Dynamic,Dynamic,Dynamic> blocking(*m,*n,size,1,false);\n\n  if(SIDE(*side)==LEFT)\n    if(UPLO(*uplo)==UP)       internal::product_selfadjoint_matrix<Scalar, DenseIndex, RowMajor,true,false, ColMajor,false,false, ColMajor,1>::run(*m, *n, a, *lda, b, *ldb, c, 1, *ldc, alpha, blocking);\n    else if(UPLO(*uplo)==LO)  internal::product_selfadjoint_matrix<Scalar, DenseIndex, ColMajor,true,false, ColMajor,false,false, ColMajor,1>::run(*m, *n, a, *lda, b, *ldb, c, 1, *ldc, alpha, blocking);\n    else                      return 0;\n  else if(SIDE(*side)==RIGHT)\n    if(UPLO(*uplo)==UP)       internal::product_selfadjoint_matrix<Scalar, DenseIndex, ColMajor,false,false, RowMajor,true,false, ColMajor,1>::run(*m, *n, b, *ldb, a, *lda, c, 1, *ldc, alpha, blocking);\n    else if(UPLO(*uplo)==LO)  internal::product_selfadjoint_matrix<Scalar, DenseIndex, ColMajor,false,false, ColMajor,true,false, ColMajor,1>::run(*m, *n, b, *ldb, a, *lda, c, 1, *ldc, alpha, blocking);\n    else                      return 0;\n  else\n    return 0;\n  #endif\n\n  return 0;\n}\n\n// c = alpha*a*a' + beta*c  for op = 'N'or'n'\n// c = alpha*a'*a + beta*c  for op = 'T'or't','C'or'c'\nint EIGEN_BLAS_FUNC(syrk)(const char *uplo, const char *op, const int *n, const int *k,\n                          const RealScalar *palpha, const RealScalar *pa, const int *lda, const RealScalar *pbeta, RealScalar *pc, const int *ldc)\n{\n//   std::cerr << \"in syrk \" << *uplo << \" \" << *op << \" \" << *n << \" \" << *k << \" \" << *palpha << \" \" << *lda << \" \" << *pbeta << \" \" << *ldc << \"\\n\";\n  #if !ISCOMPLEX\n  typedef void (*functype)(DenseIndex, DenseIndex, const Scalar *, DenseIndex, const Scalar *, DenseIndex, Scalar *, DenseIndex, DenseIndex, const Scalar&, internal::level3_blocking<Scalar,Scalar>&);\n  static const functype func[8] = {\n    // array index: NOTR  | (UP << 2)\n    (internal::general_matrix_matrix_triangular_product<DenseIndex,Scalar,ColMajor,false,Scalar,RowMajor,ColMajor,Conj, 1, Upper>::run),\n    // array index: TR    | (UP << 2)\n    (internal::general_matrix_matrix_triangular_product<DenseIndex,Scalar,RowMajor,false,Scalar,ColMajor,ColMajor,Conj, 1, Upper>::run),\n    // array index: ADJ   | (UP << 2)\n    (internal::general_matrix_matrix_triangular_product<DenseIndex,Scalar,RowMajor,Conj, Scalar,ColMajor,ColMajor,false,1, Upper>::run),\n    0,\n    // array index: NOTR  | (LO << 2)\n    (internal::general_matrix_matrix_triangular_product<DenseIndex,Scalar,ColMajor,false,Scalar,RowMajor,ColMajor,Conj, 1, Lower>::run),\n    // array index: TR    | (LO << 2)\n    (internal::general_matrix_matrix_triangular_product<DenseIndex,Scalar,RowMajor,false,Scalar,ColMajor,ColMajor,Conj, 1, Lower>::run),\n    // array index: ADJ   | (LO << 2)\n    (internal::general_matrix_matrix_triangular_product<DenseIndex,Scalar,RowMajor,Conj, Scalar,ColMajor,ColMajor,false,1, Lower>::run),\n    0\n  };\n  #endif\n\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  Scalar* c = reinterpret_cast<Scalar*>(pc);\n  Scalar alpha = *reinterpret_cast<const Scalar*>(palpha);\n  Scalar beta  = *reinterpret_cast<const Scalar*>(pbeta);\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(OP(*op)==INVALID || (ISCOMPLEX && OP(*op)==ADJ) )           info = 2;\n  else if(*n<0)                                                       info = 3;\n  else if(*k<0)                                                       info = 4;\n  else if(*lda<std::max(1,(OP(*op)==NOTR)?*n:*k))                     info = 7;\n  else if(*ldc<std::max(1,*n))                                        info = 10;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"SYRK \",&info,6);\n\n  if(beta!=Scalar(1))\n  {\n    if(UPLO(*uplo)==UP)\n      if(beta==Scalar(0)) matrix(c, *n, *n, *ldc).triangularView<Upper>().setZero();\n      else                matrix(c, *n, *n, *ldc).triangularView<Upper>() *= beta;\n    else\n      if(beta==Scalar(0)) matrix(c, *n, *n, *ldc).triangularView<Lower>().setZero();\n      else                matrix(c, *n, *n, *ldc).triangularView<Lower>() *= beta;\n  }\n\n  if(*n==0 || *k==0)\n    return 0;\n\n  #if ISCOMPLEX\n  // FIXME add support for symmetric complex matrix\n  if(UPLO(*uplo)==UP)\n  {\n    if(OP(*op)==NOTR)\n      matrix(c, *n, *n, *ldc).triangularView<Upper>() += alpha * matrix(a,*n,*k,*lda) * matrix(a,*n,*k,*lda).transpose();\n    else\n      matrix(c, *n, *n, *ldc).triangularView<Upper>() += alpha * matrix(a,*k,*n,*lda).transpose() * matrix(a,*k,*n,*lda);\n  }\n  else\n  {\n    if(OP(*op)==NOTR)\n      matrix(c, *n, *n, *ldc).triangularView<Lower>() += alpha * matrix(a,*n,*k,*lda) * matrix(a,*n,*k,*lda).transpose();\n    else\n      matrix(c, *n, *n, *ldc).triangularView<Lower>() += alpha * matrix(a,*k,*n,*lda).transpose() * matrix(a,*k,*n,*lda);\n  }\n  #else\n  internal::gemm_blocking_space<ColMajor,Scalar,Scalar,Dynamic,Dynamic,Dynamic> blocking(*n,*n,*k,1,false);\n\n  int code = OP(*op) | (UPLO(*uplo) << 2);\n  func[code](*n, *k, a, *lda, a, *lda, c, 1, *ldc, alpha, blocking);\n  #endif\n\n  return 0;\n}\n\n// c = alpha*a*b' + alpha*b*a' + beta*c  for op = 'N'or'n'\n// c = alpha*a'*b + alpha*b'*a + beta*c  for op = 'T'or't'\nint EIGEN_BLAS_FUNC(syr2k)(const char *uplo, const char *op, const int *n, const int *k, const RealScalar *palpha,\n                           const RealScalar *pa, const int *lda, const RealScalar *pb, const int *ldb, const RealScalar *pbeta, RealScalar *pc, const int *ldc)\n{\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  const Scalar* b = reinterpret_cast<const Scalar*>(pb);\n  Scalar* c = reinterpret_cast<Scalar*>(pc);\n  Scalar alpha = *reinterpret_cast<const Scalar*>(palpha);\n  Scalar beta  = *reinterpret_cast<const Scalar*>(pbeta);\n\n//   std::cerr << \"in syr2k \" << *uplo << \" \" << *op << \" \" << *n << \" \" << *k << \" \" << alpha << \" \" << *lda << \" \" << *ldb << \" \" << beta << \" \" << *ldc << \"\\n\";\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if(OP(*op)==INVALID || (ISCOMPLEX && OP(*op)==ADJ) )           info = 2;\n  else if(*n<0)                                                       info = 3;\n  else if(*k<0)                                                       info = 4;\n  else if(*lda<std::max(1,(OP(*op)==NOTR)?*n:*k))                     info = 7;\n  else if(*ldb<std::max(1,(OP(*op)==NOTR)?*n:*k))                     info = 9;\n  else if(*ldc<std::max(1,*n))                                        info = 12;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"SYR2K\",&info,6);\n\n  if(beta!=Scalar(1))\n  {\n    if(UPLO(*uplo)==UP)\n      if(beta==Scalar(0)) matrix(c, *n, *n, *ldc).triangularView<Upper>().setZero();\n      else                matrix(c, *n, *n, *ldc).triangularView<Upper>() *= beta;\n    else\n      if(beta==Scalar(0)) matrix(c, *n, *n, *ldc).triangularView<Lower>().setZero();\n      else                matrix(c, *n, *n, *ldc).triangularView<Lower>() *= beta;\n  }\n\n  if(*k==0)\n    return 1;\n\n  if(OP(*op)==NOTR)\n  {\n    if(UPLO(*uplo)==UP)\n    {\n      matrix(c, *n, *n, *ldc).triangularView<Upper>()\n        += alpha *matrix(a, *n, *k, *lda)*matrix(b, *n, *k, *ldb).transpose()\n        +  alpha*matrix(b, *n, *k, *ldb)*matrix(a, *n, *k, *lda).transpose();\n    }\n    else if(UPLO(*uplo)==LO)\n      matrix(c, *n, *n, *ldc).triangularView<Lower>()\n        += alpha*matrix(a, *n, *k, *lda)*matrix(b, *n, *k, *ldb).transpose()\n        +  alpha*matrix(b, *n, *k, *ldb)*matrix(a, *n, *k, *lda).transpose();\n  }\n  else if(OP(*op)==TR || OP(*op)==ADJ)\n  {\n    if(UPLO(*uplo)==UP)\n      matrix(c, *n, *n, *ldc).triangularView<Upper>()\n        += alpha*matrix(a, *k, *n, *lda).transpose()*matrix(b, *k, *n, *ldb)\n        +  alpha*matrix(b, *k, *n, *ldb).transpose()*matrix(a, *k, *n, *lda);\n    else if(UPLO(*uplo)==LO)\n      matrix(c, *n, *n, *ldc).triangularView<Lower>()\n        += alpha*matrix(a, *k, *n, *lda).transpose()*matrix(b, *k, *n, *ldb)\n        +  alpha*matrix(b, *k, *n, *ldb).transpose()*matrix(a, *k, *n, *lda);\n  }\n\n  return 0;\n}\n\n\n#if ISCOMPLEX\n\n// c = alpha*a*b + beta*c  for side = 'L'or'l'\n// c = alpha*b*a + beta*c  for side = 'R'or'r\nint EIGEN_BLAS_FUNC(hemm)(const char *side, const char *uplo, const int *m, const int *n, const RealScalar *palpha,\n                          const RealScalar *pa, const int *lda, const RealScalar *pb, const int *ldb, const RealScalar *pbeta, RealScalar *pc, const int *ldc)\n{\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  const Scalar* b = reinterpret_cast<const Scalar*>(pb);\n  Scalar* c = reinterpret_cast<Scalar*>(pc);\n  Scalar alpha = *reinterpret_cast<const Scalar*>(palpha);\n  Scalar beta  = *reinterpret_cast<const Scalar*>(pbeta);\n\n//   std::cerr << \"in hemm \" << *side << \" \" << *uplo << \" \" << *m << \" \" << *n << \" \" << alpha << \" \" << *lda << \" \" << beta << \" \" << *ldc << \"\\n\";\n\n  int info = 0;\n  if(SIDE(*side)==INVALID)                                            info = 1;\n  else if(UPLO(*uplo)==INVALID)                                       info = 2;\n  else if(*m<0)                                                       info = 3;\n  else if(*n<0)                                                       info = 4;\n  else if(*lda<std::max(1,(SIDE(*side)==LEFT)?*m:*n))                 info = 7;\n  else if(*ldb<std::max(1,*m))                                        info = 9;\n  else if(*ldc<std::max(1,*m))                                        info = 12;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"HEMM \",&info,6);\n\n  if(beta==Scalar(0))       matrix(c, *m, *n, *ldc).setZero();\n  else if(beta!=Scalar(1))  matrix(c, *m, *n, *ldc) *= beta;\n\n  if(*m==0 || *n==0)\n  {\n    return 1;\n  }\n\n  int size = (SIDE(*side)==LEFT) ? (*m) : (*n);\n  internal::gemm_blocking_space<ColMajor,Scalar,Scalar,Dynamic,Dynamic,Dynamic> blocking(*m,*n,size,1,false);\n\n  if(SIDE(*side)==LEFT)\n  {\n    if(UPLO(*uplo)==UP)       internal::product_selfadjoint_matrix<Scalar,DenseIndex,RowMajor,true,Conj,  ColMajor,false,false, ColMajor, 1>\n                                ::run(*m, *n, a, *lda, b, *ldb, c, 1, *ldc, alpha, blocking);\n    else if(UPLO(*uplo)==LO)  internal::product_selfadjoint_matrix<Scalar,DenseIndex,ColMajor,true,false, ColMajor,false,false, ColMajor,1>\n                                ::run(*m, *n, a, *lda, b, *ldb, c, 1, *ldc, alpha, blocking);\n    else                      return 0;\n  }\n  else if(SIDE(*side)==RIGHT)\n  {\n    if(UPLO(*uplo)==UP)       matrix(c,*m,*n,*ldc) += alpha * matrix(b,*m,*n,*ldb) * matrix(a,*n,*n,*lda).selfadjointView<Upper>();/*internal::product_selfadjoint_matrix<Scalar,DenseIndex,ColMajor,false,false, RowMajor,true,Conj,  ColMajor, 1>\n                                ::run(*m, *n, b, *ldb, a, *lda, c, 1, *ldc, alpha, blocking);*/\n    else if(UPLO(*uplo)==LO)  internal::product_selfadjoint_matrix<Scalar,DenseIndex,ColMajor,false,false, ColMajor,true,false, ColMajor,1>\n                                ::run(*m, *n, b, *ldb, a, *lda, c, 1, *ldc, alpha, blocking);\n    else                      return 0;\n  }\n  else\n  {\n    return 0;\n  }\n\n  return 0;\n}\n\n// c = alpha*a*conj(a') + beta*c  for op = 'N'or'n'\n// c = alpha*conj(a')*a + beta*c  for op  = 'C'or'c'\nint EIGEN_BLAS_FUNC(herk)(const char *uplo, const char *op, const int *n, const int *k,\n                          const RealScalar *palpha, const RealScalar *pa, const int *lda, const RealScalar *pbeta, RealScalar *pc, const int *ldc)\n{\n//   std::cerr << \"in herk \" << *uplo << \" \" << *op << \" \" << *n << \" \" << *k << \" \" << *palpha << \" \" << *lda << \" \" << *pbeta << \" \" << *ldc << \"\\n\";\n\n  typedef void (*functype)(DenseIndex, DenseIndex, const Scalar *, DenseIndex, const Scalar *, DenseIndex, Scalar *, DenseIndex, DenseIndex, const Scalar&, internal::level3_blocking<Scalar,Scalar>&);\n  static const functype func[8] = {\n    // array index: NOTR  | (UP << 2)\n    (internal::general_matrix_matrix_triangular_product<DenseIndex,Scalar,ColMajor,false,Scalar,RowMajor,Conj, ColMajor,1,Upper>::run),\n    0,\n    // array index: ADJ   | (UP << 2)\n    (internal::general_matrix_matrix_triangular_product<DenseIndex,Scalar,RowMajor,Conj, Scalar,ColMajor,false,ColMajor,1,Upper>::run),\n    0,\n    // array index: NOTR  | (LO << 2)\n    (internal::general_matrix_matrix_triangular_product<DenseIndex,Scalar,ColMajor,false,Scalar,RowMajor,Conj, ColMajor,1,Lower>::run),\n    0,\n    // array index: ADJ   | (LO << 2)\n    (internal::general_matrix_matrix_triangular_product<DenseIndex,Scalar,RowMajor,Conj, Scalar,ColMajor,false,ColMajor,1,Lower>::run),\n    0\n  };\n\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  Scalar* c = reinterpret_cast<Scalar*>(pc);\n  RealScalar alpha = *palpha;\n  RealScalar beta  = *pbeta;\n\n//   std::cerr << \"in herk \" << *uplo << \" \" << *op << \" \" << *n << \" \" << *k << \" \" << alpha << \" \" << *lda << \" \" << beta << \" \" << *ldc << \"\\n\";\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if((OP(*op)==INVALID) || (OP(*op)==TR))                        info = 2;\n  else if(*n<0)                                                       info = 3;\n  else if(*k<0)                                                       info = 4;\n  else if(*lda<std::max(1,(OP(*op)==NOTR)?*n:*k))                     info = 7;\n  else if(*ldc<std::max(1,*n))                                        info = 10;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"HERK \",&info,6);\n\n  int code = OP(*op) | (UPLO(*uplo) << 2);\n\n  if(beta!=RealScalar(1))\n  {\n    if(UPLO(*uplo)==UP)\n      if(beta==Scalar(0)) matrix(c, *n, *n, *ldc).triangularView<Upper>().setZero();\n      else                matrix(c, *n, *n, *ldc).triangularView<StrictlyUpper>() *= beta;\n    else\n      if(beta==Scalar(0)) matrix(c, *n, *n, *ldc).triangularView<Lower>().setZero();\n      else                matrix(c, *n, *n, *ldc).triangularView<StrictlyLower>() *= beta;\n\n    if(beta!=Scalar(0))\n    {\n      matrix(c, *n, *n, *ldc).diagonal().real() *= beta;\n      matrix(c, *n, *n, *ldc).diagonal().imag().setZero();\n    }\n  }\n\n  if(*k>0 && alpha!=RealScalar(0))\n  {\n    internal::gemm_blocking_space<ColMajor,Scalar,Scalar,Dynamic,Dynamic,Dynamic> blocking(*n,*n,*k,1,false);\n    func[code](*n, *k, a, *lda, a, *lda, c, 1, *ldc, alpha, blocking);\n    matrix(c, *n, *n, *ldc).diagonal().imag().setZero();\n  }\n  return 0;\n}\n\n// c = alpha*a*conj(b') + conj(alpha)*b*conj(a') + beta*c,  for op = 'N'or'n'\n// c = alpha*conj(a')*b + conj(alpha)*conj(b')*a + beta*c,  for op = 'C'or'c'\nint EIGEN_BLAS_FUNC(her2k)(const char *uplo, const char *op, const int *n, const int *k,\n                           const RealScalar *palpha, const RealScalar *pa, const int *lda, const RealScalar *pb, const int *ldb, const RealScalar *pbeta, RealScalar *pc, const int *ldc)\n{\n  const Scalar* a = reinterpret_cast<const Scalar*>(pa);\n  const Scalar* b = reinterpret_cast<const Scalar*>(pb);\n  Scalar* c = reinterpret_cast<Scalar*>(pc);\n  Scalar alpha = *reinterpret_cast<const Scalar*>(palpha);\n  RealScalar beta  = *pbeta;\n\n//   std::cerr << \"in her2k \" << *uplo << \" \" << *op << \" \" << *n << \" \" << *k << \" \" << alpha << \" \" << *lda << \" \" << *ldb << \" \" << beta << \" \" << *ldc << \"\\n\";\n\n  int info = 0;\n  if(UPLO(*uplo)==INVALID)                                            info = 1;\n  else if((OP(*op)==INVALID) || (OP(*op)==TR))                        info = 2;\n  else if(*n<0)                                                       info = 3;\n  else if(*k<0)                                                       info = 4;\n  else if(*lda<std::max(1,(OP(*op)==NOTR)?*n:*k))                     info = 7;\n  else if(*ldb<std::max(1,(OP(*op)==NOTR)?*n:*k))                     info = 9;\n  else if(*ldc<std::max(1,*n))                                        info = 12;\n  if(info)\n    return xerbla_(SCALAR_SUFFIX_UP\"HER2K\",&info,6);\n\n  if(beta!=RealScalar(1))\n  {\n    if(UPLO(*uplo)==UP)\n      if(beta==Scalar(0)) matrix(c, *n, *n, *ldc).triangularView<Upper>().setZero();\n      else                matrix(c, *n, *n, *ldc).triangularView<StrictlyUpper>() *= beta;\n    else\n      if(beta==Scalar(0)) matrix(c, *n, *n, *ldc).triangularView<Lower>().setZero();\n      else                matrix(c, *n, *n, *ldc).triangularView<StrictlyLower>() *= beta;\n\n    if(beta!=Scalar(0))\n    {\n      matrix(c, *n, *n, *ldc).diagonal().real() *= beta;\n      matrix(c, *n, *n, *ldc).diagonal().imag().setZero();\n    }\n  }\n  else if(*k>0 && alpha!=Scalar(0))\n    matrix(c, *n, *n, *ldc).diagonal().imag().setZero();\n\n  if(*k==0)\n    return 1;\n\n  if(OP(*op)==NOTR)\n  {\n    if(UPLO(*uplo)==UP)\n    {\n      matrix(c, *n, *n, *ldc).triangularView<Upper>()\n        +=            alpha *matrix(a, *n, *k, *lda)*matrix(b, *n, *k, *ldb).adjoint()\n        +  numext::conj(alpha)*matrix(b, *n, *k, *ldb)*matrix(a, *n, *k, *lda).adjoint();\n    }\n    else if(UPLO(*uplo)==LO)\n      matrix(c, *n, *n, *ldc).triangularView<Lower>()\n        += alpha*matrix(a, *n, *k, *lda)*matrix(b, *n, *k, *ldb).adjoint()\n        +  numext::conj(alpha)*matrix(b, *n, *k, *ldb)*matrix(a, *n, *k, *lda).adjoint();\n  }\n  else if(OP(*op)==ADJ)\n  {\n    if(UPLO(*uplo)==UP)\n      matrix(c, *n, *n, *ldc).triangularView<Upper>()\n        +=             alpha*matrix(a, *k, *n, *lda).adjoint()*matrix(b, *k, *n, *ldb)\n        +  numext::conj(alpha)*matrix(b, *k, *n, *ldb).adjoint()*matrix(a, *k, *n, *lda);\n    else if(UPLO(*uplo)==LO)\n      matrix(c, *n, *n, *ldc).triangularView<Lower>()\n        +=             alpha*matrix(a, *k, *n, *lda).adjoint()*matrix(b, *k, *n, *ldb)\n        +  numext::conj(alpha)*matrix(b, *k, *n, *ldb).adjoint()*matrix(a, *k, *n, *lda);\n  }\n\n  return 1;\n}\n\n#endif // ISCOMPLEX\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/single.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define SCALAR        float\n#define SCALAR_SUFFIX s\n#define SCALAR_SUFFIX_UP \"S\"\n#define ISCOMPLEX     0\n\n#include \"level1_impl.h\"\n#include \"level1_real_impl.h\"\n#include \"level2_impl.h\"\n#include \"level2_real_impl.h\"\n#include \"level3_impl.h\"\n\nfloat EIGEN_BLAS_FUNC(dsdot)(int* n, float* alpha, float* x, int* incx, float* y, int* incy)\n{ return double(*alpha) + BLASFUNC(dsdot)(n, x, incx, y, incy); }\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/testing/CMakeLists.txt",
    "content": "\nmacro(ei_add_blas_test testname)\n\n  set(targetname ${testname})\n\n  set(filename ${testname}.f)\n  add_executable(${targetname} ${filename})\n\n  target_link_libraries(${targetname} eigen_blas)\n\n  if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO)\n    target_link_libraries(${targetname} ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO})\n  endif()\n\n  target_link_libraries(${targetname} ${EXTERNAL_LIBS})\n\n  add_test(${testname} \"${Eigen_SOURCE_DIR}/blas/testing/runblastest.sh\" \"${testname}\" \"${Eigen_SOURCE_DIR}/blas/testing/${testname}.dat\")\n  add_dependencies(buildtests ${targetname})\n  \nendmacro()\n\nei_add_blas_test(sblat1)\nei_add_blas_test(sblat2)\nei_add_blas_test(sblat3)\n\nei_add_blas_test(dblat1)\nei_add_blas_test(dblat2)\nei_add_blas_test(dblat3)\n\nei_add_blas_test(cblat1)\nei_add_blas_test(cblat2)\nei_add_blas_test(cblat3)\n\nei_add_blas_test(zblat1)\nei_add_blas_test(zblat2)\nei_add_blas_test(zblat3)\n\n# add_custom_target(level1)\n# add_dependencies(level1 sblat1)\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/testing/cblat1.f",
    "content": "*> \\brief \\b CBLAT1\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM CBLAT1\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*>    Test program for the COMPLEX Level 1 BLAS.\n*>    Based upon the original BLAS test routine together with:\n*>\n*>    F06GAF Example Program Text\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup complex_blas_testing\n*\n*  =====================================================================\n      PROGRAM CBLAT1\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER          NOUT\n      PARAMETER        (NOUT=6)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, MODE, N\n      LOGICAL          PASS\n*     .. Local Scalars ..\n      REAL             SFAC\n      INTEGER          IC\n*     .. External Subroutines ..\n      EXTERNAL         CHECK1, CHECK2, HEADER\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Data statements ..\n      DATA             SFAC/9.765625E-4/\n*     .. Executable Statements ..\n      WRITE (NOUT,99999)\n      DO 20 IC = 1, 10\n         ICASE = IC\n         CALL HEADER\n*\n*        Initialize PASS, INCX, INCY, and MODE for a new case.\n*        The value 9999 for INCX, INCY or MODE will appear in the\n*        detailed  output, if any, for cases that do not involve\n*        these parameters.\n*\n         PASS = .TRUE.\n         INCX = 9999\n         INCY = 9999\n         MODE = 9999\n         IF (ICASE.LE.5) THEN\n            CALL CHECK2(SFAC)\n         ELSE IF (ICASE.GE.6) THEN\n            CALL CHECK1(SFAC)\n         END IF\n*        -- Print\n         IF (PASS) WRITE (NOUT,99998)\n   20 CONTINUE\n      STOP\n*\n99999 FORMAT (' Complex BLAS Test Program Results',/1X)\n99998 FORMAT ('                                    ----- PASS -----')\n      END\n      SUBROUTINE HEADER\n*     .. Parameters ..\n      INTEGER          NOUT\n      PARAMETER        (NOUT=6)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, MODE, N\n      LOGICAL          PASS\n*     .. Local Arrays ..\n      CHARACTER*6      L(10)\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Data statements ..\n      DATA             L(1)/'CDOTC '/\n      DATA             L(2)/'CDOTU '/\n      DATA             L(3)/'CAXPY '/\n      DATA             L(4)/'CCOPY '/\n      DATA             L(5)/'CSWAP '/\n      DATA             L(6)/'SCNRM2'/\n      DATA             L(7)/'SCASUM'/\n      DATA             L(8)/'CSCAL '/\n      DATA             L(9)/'CSSCAL'/\n      DATA             L(10)/'ICAMAX'/\n*     .. Executable Statements ..\n      WRITE (NOUT,99999) ICASE, L(ICASE)\n      RETURN\n*\n99999 FORMAT (/' Test of subprogram number',I3,12X,A6)\n      END\n      SUBROUTINE CHECK1(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      REAL              SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, MODE, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      COMPLEX           CA\n      REAL              SA\n      INTEGER           I, J, LEN, NP1\n*     .. Local Arrays ..\n      COMPLEX           CTRUE5(8,5,2), CTRUE6(8,5,2), CV(8,5,2), CX(8),\n     +                  MWPCS(5), MWPCT(5)\n      REAL              STRUE2(5), STRUE4(5)\n      INTEGER           ITRUE3(5)\n*     .. External Functions ..\n      REAL              SCASUM, SCNRM2\n      INTEGER           ICAMAX\n      EXTERNAL          SCASUM, SCNRM2, ICAMAX\n*     .. External Subroutines ..\n      EXTERNAL          CSCAL, CSSCAL, CTEST, ITEST1, STEST1\n*     .. Intrinsic Functions ..\n      INTRINSIC         MAX\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Data statements ..\n      DATA              SA, CA/0.3E0, (0.4E0,-0.7E0)/\n      DATA              ((CV(I,J,1),I=1,8),J=1,5)/(0.1E0,0.1E0),\n     +                  (1.0E0,2.0E0), (1.0E0,2.0E0), (1.0E0,2.0E0),\n     +                  (1.0E0,2.0E0), (1.0E0,2.0E0), (1.0E0,2.0E0),\n     +                  (1.0E0,2.0E0), (0.3E0,-0.4E0), (3.0E0,4.0E0),\n     +                  (3.0E0,4.0E0), (3.0E0,4.0E0), (3.0E0,4.0E0),\n     +                  (3.0E0,4.0E0), (3.0E0,4.0E0), (3.0E0,4.0E0),\n     +                  (0.1E0,-0.3E0), (0.5E0,-0.1E0), (5.0E0,6.0E0),\n     +                  (5.0E0,6.0E0), (5.0E0,6.0E0), (5.0E0,6.0E0),\n     +                  (5.0E0,6.0E0), (5.0E0,6.0E0), (0.1E0,0.1E0),\n     +                  (-0.6E0,0.1E0), (0.1E0,-0.3E0), (7.0E0,8.0E0),\n     +                  (7.0E0,8.0E0), (7.0E0,8.0E0), (7.0E0,8.0E0),\n     +                  (7.0E0,8.0E0), (0.3E0,0.1E0), (0.5E0,0.0E0),\n     +                  (0.0E0,0.5E0), (0.0E0,0.2E0), (2.0E0,3.0E0),\n     +                  (2.0E0,3.0E0), (2.0E0,3.0E0), (2.0E0,3.0E0)/\n      DATA              ((CV(I,J,2),I=1,8),J=1,5)/(0.1E0,0.1E0),\n     +                  (4.0E0,5.0E0), (4.0E0,5.0E0), (4.0E0,5.0E0),\n     +                  (4.0E0,5.0E0), (4.0E0,5.0E0), (4.0E0,5.0E0),\n     +                  (4.0E0,5.0E0), (0.3E0,-0.4E0), (6.0E0,7.0E0),\n     +                  (6.0E0,7.0E0), (6.0E0,7.0E0), (6.0E0,7.0E0),\n     +                  (6.0E0,7.0E0), (6.0E0,7.0E0), (6.0E0,7.0E0),\n     +                  (0.1E0,-0.3E0), (8.0E0,9.0E0), (0.5E0,-0.1E0),\n     +                  (2.0E0,5.0E0), (2.0E0,5.0E0), (2.0E0,5.0E0),\n     +                  (2.0E0,5.0E0), (2.0E0,5.0E0), (0.1E0,0.1E0),\n     +                  (3.0E0,6.0E0), (-0.6E0,0.1E0), (4.0E0,7.0E0),\n     +                  (0.1E0,-0.3E0), (7.0E0,2.0E0), (7.0E0,2.0E0),\n     +                  (7.0E0,2.0E0), (0.3E0,0.1E0), (5.0E0,8.0E0),\n     +                  (0.5E0,0.0E0), (6.0E0,9.0E0), (0.0E0,0.5E0),\n     +                  (8.0E0,3.0E0), (0.0E0,0.2E0), (9.0E0,4.0E0)/\n      DATA              STRUE2/0.0E0, 0.5E0, 0.6E0, 0.7E0, 0.8E0/\n      DATA              STRUE4/0.0E0, 0.7E0, 1.0E0, 1.3E0, 1.6E0/\n      DATA              ((CTRUE5(I,J,1),I=1,8),J=1,5)/(0.1E0,0.1E0),\n     +                  (1.0E0,2.0E0), (1.0E0,2.0E0), (1.0E0,2.0E0),\n     +                  (1.0E0,2.0E0), (1.0E0,2.0E0), (1.0E0,2.0E0),\n     +                  (1.0E0,2.0E0), (-0.16E0,-0.37E0), (3.0E0,4.0E0),\n     +                  (3.0E0,4.0E0), (3.0E0,4.0E0), (3.0E0,4.0E0),\n     +                  (3.0E0,4.0E0), (3.0E0,4.0E0), (3.0E0,4.0E0),\n     +                  (-0.17E0,-0.19E0), (0.13E0,-0.39E0),\n     +                  (5.0E0,6.0E0), (5.0E0,6.0E0), (5.0E0,6.0E0),\n     +                  (5.0E0,6.0E0), (5.0E0,6.0E0), (5.0E0,6.0E0),\n     +                  (0.11E0,-0.03E0), (-0.17E0,0.46E0),\n     +                  (-0.17E0,-0.19E0), (7.0E0,8.0E0), (7.0E0,8.0E0),\n     +                  (7.0E0,8.0E0), (7.0E0,8.0E0), (7.0E0,8.0E0),\n     +                  (0.19E0,-0.17E0), (0.20E0,-0.35E0),\n     +                  (0.35E0,0.20E0), (0.14E0,0.08E0),\n     +                  (2.0E0,3.0E0), (2.0E0,3.0E0), (2.0E0,3.0E0),\n     +                  (2.0E0,3.0E0)/\n      DATA              ((CTRUE5(I,J,2),I=1,8),J=1,5)/(0.1E0,0.1E0),\n     +                  (4.0E0,5.0E0), (4.0E0,5.0E0), (4.0E0,5.0E0),\n     +                  (4.0E0,5.0E0), (4.0E0,5.0E0), (4.0E0,5.0E0),\n     +                  (4.0E0,5.0E0), (-0.16E0,-0.37E0), (6.0E0,7.0E0),\n     +                  (6.0E0,7.0E0), (6.0E0,7.0E0), (6.0E0,7.0E0),\n     +                  (6.0E0,7.0E0), (6.0E0,7.0E0), (6.0E0,7.0E0),\n     +                  (-0.17E0,-0.19E0), (8.0E0,9.0E0),\n     +                  (0.13E0,-0.39E0), (2.0E0,5.0E0), (2.0E0,5.0E0),\n     +                  (2.0E0,5.0E0), (2.0E0,5.0E0), (2.0E0,5.0E0),\n     +                  (0.11E0,-0.03E0), (3.0E0,6.0E0),\n     +                  (-0.17E0,0.46E0), (4.0E0,7.0E0),\n     +                  (-0.17E0,-0.19E0), (7.0E0,2.0E0), (7.0E0,2.0E0),\n     +                  (7.0E0,2.0E0), (0.19E0,-0.17E0), (5.0E0,8.0E0),\n     +                  (0.20E0,-0.35E0), (6.0E0,9.0E0),\n     +                  (0.35E0,0.20E0), (8.0E0,3.0E0),\n     +                  (0.14E0,0.08E0), (9.0E0,4.0E0)/\n      DATA              ((CTRUE6(I,J,1),I=1,8),J=1,5)/(0.1E0,0.1E0),\n     +                  (1.0E0,2.0E0), (1.0E0,2.0E0), (1.0E0,2.0E0),\n     +                  (1.0E0,2.0E0), (1.0E0,2.0E0), (1.0E0,2.0E0),\n     +                  (1.0E0,2.0E0), (0.09E0,-0.12E0), (3.0E0,4.0E0),\n     +                  (3.0E0,4.0E0), (3.0E0,4.0E0), (3.0E0,4.0E0),\n     +                  (3.0E0,4.0E0), (3.0E0,4.0E0), (3.0E0,4.0E0),\n     +                  (0.03E0,-0.09E0), (0.15E0,-0.03E0),\n     +                  (5.0E0,6.0E0), (5.0E0,6.0E0), (5.0E0,6.0E0),\n     +                  (5.0E0,6.0E0), (5.0E0,6.0E0), (5.0E0,6.0E0),\n     +                  (0.03E0,0.03E0), (-0.18E0,0.03E0),\n     +                  (0.03E0,-0.09E0), (7.0E0,8.0E0), (7.0E0,8.0E0),\n     +                  (7.0E0,8.0E0), (7.0E0,8.0E0), (7.0E0,8.0E0),\n     +                  (0.09E0,0.03E0), (0.15E0,0.00E0),\n     +                  (0.00E0,0.15E0), (0.00E0,0.06E0), (2.0E0,3.0E0),\n     +                  (2.0E0,3.0E0), (2.0E0,3.0E0), (2.0E0,3.0E0)/\n      DATA              ((CTRUE6(I,J,2),I=1,8),J=1,5)/(0.1E0,0.1E0),\n     +                  (4.0E0,5.0E0), (4.0E0,5.0E0), (4.0E0,5.0E0),\n     +                  (4.0E0,5.0E0), (4.0E0,5.0E0), (4.0E0,5.0E0),\n     +                  (4.0E0,5.0E0), (0.09E0,-0.12E0), (6.0E0,7.0E0),\n     +                  (6.0E0,7.0E0), (6.0E0,7.0E0), (6.0E0,7.0E0),\n     +                  (6.0E0,7.0E0), (6.0E0,7.0E0), (6.0E0,7.0E0),\n     +                  (0.03E0,-0.09E0), (8.0E0,9.0E0),\n     +                  (0.15E0,-0.03E0), (2.0E0,5.0E0), (2.0E0,5.0E0),\n     +                  (2.0E0,5.0E0), (2.0E0,5.0E0), (2.0E0,5.0E0),\n     +                  (0.03E0,0.03E0), (3.0E0,6.0E0),\n     +                  (-0.18E0,0.03E0), (4.0E0,7.0E0),\n     +                  (0.03E0,-0.09E0), (7.0E0,2.0E0), (7.0E0,2.0E0),\n     +                  (7.0E0,2.0E0), (0.09E0,0.03E0), (5.0E0,8.0E0),\n     +                  (0.15E0,0.00E0), (6.0E0,9.0E0), (0.00E0,0.15E0),\n     +                  (8.0E0,3.0E0), (0.00E0,0.06E0), (9.0E0,4.0E0)/\n      DATA              ITRUE3/0, 1, 2, 2, 2/\n*     .. Executable Statements ..\n      DO 60 INCX = 1, 2\n         DO 40 NP1 = 1, 5\n            N = NP1 - 1\n            LEN = 2*MAX(N,1)\n*           .. Set vector arguments ..\n            DO 20 I = 1, LEN\n               CX(I) = CV(I,NP1,INCX)\n   20       CONTINUE\n            IF (ICASE.EQ.6) THEN\n*              .. SCNRM2 ..\n               CALL STEST1(SCNRM2(N,CX,INCX),STRUE2(NP1),STRUE2(NP1),\n     +                     SFAC)\n            ELSE IF (ICASE.EQ.7) THEN\n*              .. SCASUM ..\n               CALL STEST1(SCASUM(N,CX,INCX),STRUE4(NP1),STRUE4(NP1),\n     +                     SFAC)\n            ELSE IF (ICASE.EQ.8) THEN\n*              .. CSCAL ..\n               CALL CSCAL(N,CA,CX,INCX)\n               CALL CTEST(LEN,CX,CTRUE5(1,NP1,INCX),CTRUE5(1,NP1,INCX),\n     +                    SFAC)\n            ELSE IF (ICASE.EQ.9) THEN\n*              .. CSSCAL ..\n               CALL CSSCAL(N,SA,CX,INCX)\n               CALL CTEST(LEN,CX,CTRUE6(1,NP1,INCX),CTRUE6(1,NP1,INCX),\n     +                    SFAC)\n            ELSE IF (ICASE.EQ.10) THEN\n*              .. ICAMAX ..\n               CALL ITEST1(ICAMAX(N,CX,INCX),ITRUE3(NP1))\n            ELSE\n               WRITE (NOUT,*) ' Shouldn''t be here in CHECK1'\n               STOP\n            END IF\n*\n   40    CONTINUE\n   60 CONTINUE\n*\n      INCX = 1\n      IF (ICASE.EQ.8) THEN\n*        CSCAL\n*        Add a test for alpha equal to zero.\n         CA = (0.0E0,0.0E0)\n         DO 80 I = 1, 5\n            MWPCT(I) = (0.0E0,0.0E0)\n            MWPCS(I) = (1.0E0,1.0E0)\n   80    CONTINUE\n         CALL CSCAL(5,CA,CX,INCX)\n         CALL CTEST(5,CX,MWPCT,MWPCS,SFAC)\n      ELSE IF (ICASE.EQ.9) THEN\n*        CSSCAL\n*        Add a test for alpha equal to zero.\n         SA = 0.0E0\n         DO 100 I = 1, 5\n            MWPCT(I) = (0.0E0,0.0E0)\n            MWPCS(I) = (1.0E0,1.0E0)\n  100    CONTINUE\n         CALL CSSCAL(5,SA,CX,INCX)\n         CALL CTEST(5,CX,MWPCT,MWPCS,SFAC)\n*        Add a test for alpha equal to one.\n         SA = 1.0E0\n         DO 120 I = 1, 5\n            MWPCT(I) = CX(I)\n            MWPCS(I) = CX(I)\n  120    CONTINUE\n         CALL CSSCAL(5,SA,CX,INCX)\n         CALL CTEST(5,CX,MWPCT,MWPCS,SFAC)\n*        Add a test for alpha equal to minus one.\n         SA = -1.0E0\n         DO 140 I = 1, 5\n            MWPCT(I) = -CX(I)\n            MWPCS(I) = -CX(I)\n  140    CONTINUE\n         CALL CSSCAL(5,SA,CX,INCX)\n         CALL CTEST(5,CX,MWPCT,MWPCS,SFAC)\n      END IF\n      RETURN\n      END\n      SUBROUTINE CHECK2(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      REAL              SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, MODE, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      COMPLEX           CA\n      INTEGER           I, J, KI, KN, KSIZE, LENX, LENY, MX, MY\n*     .. Local Arrays ..\n      COMPLEX           CDOT(1), CSIZE1(4), CSIZE2(7,2), CSIZE3(14),\n     +                  CT10X(7,4,4), CT10Y(7,4,4), CT6(4,4), CT7(4,4),\n     +                  CT8(7,4,4), CX(7), CX1(7), CY(7), CY1(7)\n      INTEGER           INCXS(4), INCYS(4), LENS(4,2), NS(4)\n*     .. External Functions ..\n      COMPLEX           CDOTC, CDOTU\n      EXTERNAL          CDOTC, CDOTU\n*     .. External Subroutines ..\n      EXTERNAL          CAXPY, CCOPY, CSWAP, CTEST\n*     .. Intrinsic Functions ..\n      INTRINSIC         ABS, MIN\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Data statements ..\n      DATA              CA/(0.4E0,-0.7E0)/\n      DATA              INCXS/1, 2, -2, -1/\n      DATA              INCYS/1, -2, 1, -2/\n      DATA              LENS/1, 1, 2, 4, 1, 1, 3, 7/\n      DATA              NS/0, 1, 2, 4/\n      DATA              CX1/(0.7E0,-0.8E0), (-0.4E0,-0.7E0),\n     +                  (-0.1E0,-0.9E0), (0.2E0,-0.8E0),\n     +                  (-0.9E0,-0.4E0), (0.1E0,0.4E0), (-0.6E0,0.6E0)/\n      DATA              CY1/(0.6E0,-0.6E0), (-0.9E0,0.5E0),\n     +                  (0.7E0,-0.6E0), (0.1E0,-0.5E0), (-0.1E0,-0.2E0),\n     +                  (-0.5E0,-0.3E0), (0.8E0,-0.7E0)/\n      DATA              ((CT8(I,J,1),I=1,7),J=1,4)/(0.6E0,-0.6E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.32E0,-1.41E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.32E0,-1.41E0),\n     +                  (-1.55E0,0.5E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.32E0,-1.41E0), (-1.55E0,0.5E0),\n     +                  (0.03E0,-0.89E0), (-0.38E0,-0.96E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0)/\n      DATA              ((CT8(I,J,2),I=1,7),J=1,4)/(0.6E0,-0.6E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.32E0,-1.41E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (-0.07E0,-0.89E0),\n     +                  (-0.9E0,0.5E0), (0.42E0,-1.41E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.78E0,0.06E0), (-0.9E0,0.5E0),\n     +                  (0.06E0,-0.13E0), (0.1E0,-0.5E0),\n     +                  (-0.77E0,-0.49E0), (-0.5E0,-0.3E0),\n     +                  (0.52E0,-1.51E0)/\n      DATA              ((CT8(I,J,3),I=1,7),J=1,4)/(0.6E0,-0.6E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.32E0,-1.41E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (-0.07E0,-0.89E0),\n     +                  (-1.18E0,-0.31E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.78E0,0.06E0), (-1.54E0,0.97E0),\n     +                  (0.03E0,-0.89E0), (-0.18E0,-1.31E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0)/\n      DATA              ((CT8(I,J,4),I=1,7),J=1,4)/(0.6E0,-0.6E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.32E0,-1.41E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.32E0,-1.41E0), (-0.9E0,0.5E0),\n     +                  (0.05E0,-0.6E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.32E0,-1.41E0),\n     +                  (-0.9E0,0.5E0), (0.05E0,-0.6E0), (0.1E0,-0.5E0),\n     +                  (-0.77E0,-0.49E0), (-0.5E0,-0.3E0),\n     +                  (0.32E0,-1.16E0)/\n      DATA              CT7/(0.0E0,0.0E0), (-0.06E0,-0.90E0),\n     +                  (0.65E0,-0.47E0), (-0.34E0,-1.22E0),\n     +                  (0.0E0,0.0E0), (-0.06E0,-0.90E0),\n     +                  (-0.59E0,-1.46E0), (-1.04E0,-0.04E0),\n     +                  (0.0E0,0.0E0), (-0.06E0,-0.90E0),\n     +                  (-0.83E0,0.59E0), (0.07E0,-0.37E0),\n     +                  (0.0E0,0.0E0), (-0.06E0,-0.90E0),\n     +                  (-0.76E0,-1.15E0), (-1.33E0,-1.82E0)/\n      DATA              CT6/(0.0E0,0.0E0), (0.90E0,0.06E0),\n     +                  (0.91E0,-0.77E0), (1.80E0,-0.10E0),\n     +                  (0.0E0,0.0E0), (0.90E0,0.06E0), (1.45E0,0.74E0),\n     +                  (0.20E0,0.90E0), (0.0E0,0.0E0), (0.90E0,0.06E0),\n     +                  (-0.55E0,0.23E0), (0.83E0,-0.39E0),\n     +                  (0.0E0,0.0E0), (0.90E0,0.06E0), (1.04E0,0.79E0),\n     +                  (1.95E0,1.22E0)/\n      DATA              ((CT10X(I,J,1),I=1,7),J=1,4)/(0.7E0,-0.8E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.6E0,-0.6E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.6E0,-0.6E0), (-0.9E0,0.5E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.6E0,-0.6E0),\n     +                  (-0.9E0,0.5E0), (0.7E0,-0.6E0), (0.1E0,-0.5E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0)/\n      DATA              ((CT10X(I,J,2),I=1,7),J=1,4)/(0.7E0,-0.8E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.6E0,-0.6E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.7E0,-0.6E0), (-0.4E0,-0.7E0),\n     +                  (0.6E0,-0.6E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.8E0,-0.7E0),\n     +                  (-0.4E0,-0.7E0), (-0.1E0,-0.2E0),\n     +                  (0.2E0,-0.8E0), (0.7E0,-0.6E0), (0.1E0,0.4E0),\n     +                  (0.6E0,-0.6E0)/\n      DATA              ((CT10X(I,J,3),I=1,7),J=1,4)/(0.7E0,-0.8E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.6E0,-0.6E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (-0.9E0,0.5E0), (-0.4E0,-0.7E0),\n     +                  (0.6E0,-0.6E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.1E0,-0.5E0),\n     +                  (-0.4E0,-0.7E0), (0.7E0,-0.6E0), (0.2E0,-0.8E0),\n     +                  (-0.9E0,0.5E0), (0.1E0,0.4E0), (0.6E0,-0.6E0)/\n      DATA              ((CT10X(I,J,4),I=1,7),J=1,4)/(0.7E0,-0.8E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.6E0,-0.6E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.6E0,-0.6E0), (0.7E0,-0.6E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.6E0,-0.6E0),\n     +                  (0.7E0,-0.6E0), (-0.1E0,-0.2E0), (0.8E0,-0.7E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0)/\n      DATA              ((CT10Y(I,J,1),I=1,7),J=1,4)/(0.6E0,-0.6E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.7E0,-0.8E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.7E0,-0.8E0), (-0.4E0,-0.7E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.7E0,-0.8E0),\n     +                  (-0.4E0,-0.7E0), (-0.1E0,-0.9E0),\n     +                  (0.2E0,-0.8E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0)/\n      DATA              ((CT10Y(I,J,2),I=1,7),J=1,4)/(0.6E0,-0.6E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.7E0,-0.8E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (-0.1E0,-0.9E0), (-0.9E0,0.5E0),\n     +                  (0.7E0,-0.8E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (-0.6E0,0.6E0),\n     +                  (-0.9E0,0.5E0), (-0.9E0,-0.4E0), (0.1E0,-0.5E0),\n     +                  (-0.1E0,-0.9E0), (-0.5E0,-0.3E0),\n     +                  (0.7E0,-0.8E0)/\n      DATA              ((CT10Y(I,J,3),I=1,7),J=1,4)/(0.6E0,-0.6E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.7E0,-0.8E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (-0.1E0,-0.9E0), (0.7E0,-0.8E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (-0.6E0,0.6E0),\n     +                  (-0.9E0,-0.4E0), (-0.1E0,-0.9E0),\n     +                  (0.7E0,-0.8E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0)/\n      DATA              ((CT10Y(I,J,4),I=1,7),J=1,4)/(0.6E0,-0.6E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.7E0,-0.8E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.7E0,-0.8E0), (-0.9E0,0.5E0),\n     +                  (-0.4E0,-0.7E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.7E0,-0.8E0),\n     +                  (-0.9E0,0.5E0), (-0.4E0,-0.7E0), (0.1E0,-0.5E0),\n     +                  (-0.1E0,-0.9E0), (-0.5E0,-0.3E0),\n     +                  (0.2E0,-0.8E0)/\n      DATA              CSIZE1/(0.0E0,0.0E0), (0.9E0,0.9E0),\n     +                  (1.63E0,1.73E0), (2.90E0,2.78E0)/\n      DATA              CSIZE3/(0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (1.17E0,1.17E0),\n     +                  (1.17E0,1.17E0), (1.17E0,1.17E0),\n     +                  (1.17E0,1.17E0), (1.17E0,1.17E0),\n     +                  (1.17E0,1.17E0), (1.17E0,1.17E0)/\n      DATA              CSIZE2/(0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (0.0E0,0.0E0),\n     +                  (0.0E0,0.0E0), (0.0E0,0.0E0), (1.54E0,1.54E0),\n     +                  (1.54E0,1.54E0), (1.54E0,1.54E0),\n     +                  (1.54E0,1.54E0), (1.54E0,1.54E0),\n     +                  (1.54E0,1.54E0), (1.54E0,1.54E0)/\n*     .. Executable Statements ..\n      DO 60 KI = 1, 4\n         INCX = INCXS(KI)\n         INCY = INCYS(KI)\n         MX = ABS(INCX)\n         MY = ABS(INCY)\n*\n         DO 40 KN = 1, 4\n            N = NS(KN)\n            KSIZE = MIN(2,KN)\n            LENX = LENS(KN,MX)\n            LENY = LENS(KN,MY)\n*           .. initialize all argument arrays ..\n            DO 20 I = 1, 7\n               CX(I) = CX1(I)\n               CY(I) = CY1(I)\n   20       CONTINUE\n            IF (ICASE.EQ.1) THEN\n*              .. CDOTC ..\n               CDOT(1) = CDOTC(N,CX,INCX,CY,INCY)\n               CALL CTEST(1,CDOT,CT6(KN,KI),CSIZE1(KN),SFAC)\n            ELSE IF (ICASE.EQ.2) THEN\n*              .. CDOTU ..\n               CDOT(1) = CDOTU(N,CX,INCX,CY,INCY)\n               CALL CTEST(1,CDOT,CT7(KN,KI),CSIZE1(KN),SFAC)\n            ELSE IF (ICASE.EQ.3) THEN\n*              .. CAXPY ..\n               CALL CAXPY(N,CA,CX,INCX,CY,INCY)\n               CALL CTEST(LENY,CY,CT8(1,KN,KI),CSIZE2(1,KSIZE),SFAC)\n            ELSE IF (ICASE.EQ.4) THEN\n*              .. CCOPY ..\n               CALL CCOPY(N,CX,INCX,CY,INCY)\n               CALL CTEST(LENY,CY,CT10Y(1,KN,KI),CSIZE3,1.0E0)\n            ELSE IF (ICASE.EQ.5) THEN\n*              .. CSWAP ..\n               CALL CSWAP(N,CX,INCX,CY,INCY)\n               CALL CTEST(LENX,CX,CT10X(1,KN,KI),CSIZE3,1.0E0)\n               CALL CTEST(LENY,CY,CT10Y(1,KN,KI),CSIZE3,1.0E0)\n            ELSE\n               WRITE (NOUT,*) ' Shouldn''t be here in CHECK2'\n               STOP\n            END IF\n*\n   40    CONTINUE\n   60 CONTINUE\n      RETURN\n      END\n      SUBROUTINE STEST(LEN,SCOMP,STRUE,SSIZE,SFAC)\n*     ********************************* STEST **************************\n*\n*     THIS SUBR COMPARES ARRAYS  SCOMP() AND STRUE() OF LENGTH LEN TO\n*     SEE IF THE TERM BY TERM DIFFERENCES, MULTIPLIED BY SFAC, ARE\n*     NEGLIGIBLE.\n*\n*     C. L. LAWSON, JPL, 1974 DEC 10\n*\n*     .. Parameters ..\n      INTEGER          NOUT\n      REAL             ZERO\n      PARAMETER        (NOUT=6, ZERO=0.0E0)\n*     .. Scalar Arguments ..\n      REAL             SFAC\n      INTEGER          LEN\n*     .. Array Arguments ..\n      REAL             SCOMP(LEN), SSIZE(LEN), STRUE(LEN)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, MODE, N\n      LOGICAL          PASS\n*     .. Local Scalars ..\n      REAL             SD\n      INTEGER          I\n*     .. External Functions ..\n      REAL             SDIFF\n      EXTERNAL         SDIFF\n*     .. Intrinsic Functions ..\n      INTRINSIC        ABS\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Executable Statements ..\n*\n      DO 40 I = 1, LEN\n         SD = SCOMP(I) - STRUE(I)\n         IF (ABS(SFAC*SD) .LE. ABS(SSIZE(I))*EPSILON(ZERO))\n     +       GO TO 40\n*\n*                             HERE    SCOMP(I) IS NOT CLOSE TO STRUE(I).\n*\n         IF ( .NOT. PASS) GO TO 20\n*                             PRINT FAIL MESSAGE AND HEADER.\n         PASS = .FALSE.\n         WRITE (NOUT,99999)\n         WRITE (NOUT,99998)\n   20    WRITE (NOUT,99997) ICASE, N, INCX, INCY, MODE, I, SCOMP(I),\n     +     STRUE(I), SD, SSIZE(I)\n   40 CONTINUE\n      RETURN\n*\n99999 FORMAT ('                                       FAIL')\n99998 FORMAT (/' CASE  N INCX INCY MODE  I                            ',\n     +       ' COMP(I)                             TRUE(I)  DIFFERENCE',\n     +       '     SIZE(I)',/1X)\n99997 FORMAT (1X,I4,I3,3I5,I3,2E36.8,2E12.4)\n      END\n      SUBROUTINE STEST1(SCOMP1,STRUE1,SSIZE,SFAC)\n*     ************************* STEST1 *****************************\n*\n*     THIS IS AN INTERFACE SUBROUTINE TO ACCOMMODATE THE FORTRAN\n*     REQUIREMENT THAT WHEN A DUMMY ARGUMENT IS AN ARRAY, THE\n*     ACTUAL ARGUMENT MUST ALSO BE AN ARRAY OR AN ARRAY ELEMENT.\n*\n*     C.L. LAWSON, JPL, 1978 DEC 6\n*\n*     .. Scalar Arguments ..\n      REAL              SCOMP1, SFAC, STRUE1\n*     .. Array Arguments ..\n      REAL              SSIZE(*)\n*     .. Local Arrays ..\n      REAL              SCOMP(1), STRUE(1)\n*     .. External Subroutines ..\n      EXTERNAL          STEST\n*     .. Executable Statements ..\n*\n      SCOMP(1) = SCOMP1\n      STRUE(1) = STRUE1\n      CALL STEST(1,SCOMP,STRUE,SSIZE,SFAC)\n*\n      RETURN\n      END\n      REAL             FUNCTION SDIFF(SA,SB)\n*     ********************************* SDIFF **************************\n*     COMPUTES DIFFERENCE OF TWO NUMBERS.  C. L. LAWSON, JPL 1974 FEB 15\n*\n*     .. Scalar Arguments ..\n      REAL                            SA, SB\n*     .. Executable Statements ..\n      SDIFF = SA - SB\n      RETURN\n      END\n      SUBROUTINE CTEST(LEN,CCOMP,CTRUE,CSIZE,SFAC)\n*     **************************** CTEST *****************************\n*\n*     C.L. LAWSON, JPL, 1978 DEC 6\n*\n*     .. Scalar Arguments ..\n      REAL             SFAC\n      INTEGER          LEN\n*     .. Array Arguments ..\n      COMPLEX          CCOMP(LEN), CSIZE(LEN), CTRUE(LEN)\n*     .. Local Scalars ..\n      INTEGER          I\n*     .. Local Arrays ..\n      REAL             SCOMP(20), SSIZE(20), STRUE(20)\n*     .. External Subroutines ..\n      EXTERNAL         STEST\n*     .. Intrinsic Functions ..\n      INTRINSIC        AIMAG, REAL\n*     .. Executable Statements ..\n      DO 20 I = 1, LEN\n         SCOMP(2*I-1) = REAL(CCOMP(I))\n         SCOMP(2*I) = AIMAG(CCOMP(I))\n         STRUE(2*I-1) = REAL(CTRUE(I))\n         STRUE(2*I) = AIMAG(CTRUE(I))\n         SSIZE(2*I-1) = REAL(CSIZE(I))\n         SSIZE(2*I) = AIMAG(CSIZE(I))\n   20 CONTINUE\n*\n      CALL STEST(2*LEN,SCOMP,STRUE,SSIZE,SFAC)\n      RETURN\n      END\n      SUBROUTINE ITEST1(ICOMP,ITRUE)\n*     ********************************* ITEST1 *************************\n*\n*     THIS SUBROUTINE COMPARES THE VARIABLES ICOMP AND ITRUE FOR\n*     EQUALITY.\n*     C. L. LAWSON, JPL, 1974 DEC 10\n*\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      INTEGER           ICOMP, ITRUE\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, MODE, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      INTEGER           ID\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Executable Statements ..\n      IF (ICOMP.EQ.ITRUE) GO TO 40\n*\n*                            HERE ICOMP IS NOT EQUAL TO ITRUE.\n*\n      IF ( .NOT. PASS) GO TO 20\n*                             PRINT FAIL MESSAGE AND HEADER.\n      PASS = .FALSE.\n      WRITE (NOUT,99999)\n      WRITE (NOUT,99998)\n   20 ID = ICOMP - ITRUE\n      WRITE (NOUT,99997) ICASE, N, INCX, INCY, MODE, ICOMP, ITRUE, ID\n   40 CONTINUE\n      RETURN\n*\n99999 FORMAT ('                                       FAIL')\n99998 FORMAT (/' CASE  N INCX INCY MODE                               ',\n     +       ' COMP                                TRUE     DIFFERENCE',\n     +       /1X)\n99997 FORMAT (1X,I4,I3,3I5,2I36,I12)\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/testing/cblat2.f",
    "content": "*> \\brief \\b CBLAT2\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM CBLAT2\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> Test program for the COMPLEX          Level 2 Blas.\n*>\n*> The program must be driven by a short data file. The first 18 records\n*> of the file are read using list-directed input, the last 17 records\n*> are read using the format ( A6, L2 ). An annotated example of a data\n*> file can be obtained by deleting the first 3 characters from the\n*> following 35 lines:\n*> 'cblat2.out'      NAME OF SUMMARY OUTPUT FILE\n*> 6                 UNIT NUMBER OF SUMMARY FILE\n*> 'CBLA2T.SNAP'     NAME OF SNAPSHOT OUTPUT FILE\n*> -1                UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0)\n*> F        LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD.\n*> F        LOGICAL FLAG, T TO STOP ON FAILURES.\n*> T        LOGICAL FLAG, T TO TEST ERROR EXITS.\n*> 16.0     THRESHOLD VALUE OF TEST RATIO\n*> 6                 NUMBER OF VALUES OF N\n*> 0 1 2 3 5 9       VALUES OF N\n*> 4                 NUMBER OF VALUES OF K\n*> 0 1 2 4           VALUES OF K\n*> 4                 NUMBER OF VALUES OF INCX AND INCY\n*> 1 2 -1 -2         VALUES OF INCX AND INCY\n*> 3                 NUMBER OF VALUES OF ALPHA\n*> (0.0,0.0) (1.0,0.0) (0.7,-0.9)       VALUES OF ALPHA\n*> 3                 NUMBER OF VALUES OF BETA\n*> (0.0,0.0) (1.0,0.0) (1.3,-1.1)       VALUES OF BETA\n*> CGEMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CGBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CHEMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CHBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CHPMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CTRMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CTBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CTPMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CTRSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CTBSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CTPSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CGERC  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CGERU  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CHER   T PUT F FOR NO TEST. SAME COLUMNS.\n*> CHPR   T PUT F FOR NO TEST. SAME COLUMNS.\n*> CHER2  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CHPR2  T PUT F FOR NO TEST. SAME COLUMNS.\n*>\n*> Further Details\n*> ===============\n*>\n*>    See:\n*>\n*>       Dongarra J. J., Du Croz J. J., Hammarling S.  and Hanson R. J..\n*>       An  extended  set of Fortran  Basic Linear Algebra Subprograms.\n*>\n*>       Technical  Memoranda  Nos. 41 (revision 3) and 81,  Mathematics\n*>       and  Computer Science  Division,  Argonne  National Laboratory,\n*>       9700 South Cass Avenue, Argonne, Illinois 60439, US.\n*>\n*>       Or\n*>\n*>       NAG  Technical Reports TR3/87 and TR4/87,  Numerical Algorithms\n*>       Group  Ltd.,  NAG  Central  Office,  256  Banbury  Road, Oxford\n*>       OX2 7DE, UK,  and  Numerical Algorithms Group Inc.,  1101  31st\n*>       Street,  Suite 100,  Downers Grove,  Illinois 60515-1263,  USA.\n*>\n*>\n*> -- Written on 10-August-1987.\n*>    Richard Hanson, Sandia National Labs.\n*>    Jeremy Du Croz, NAG Central Office.\n*>\n*>    10-9-00:  Change STATUS='NEW' to 'UNKNOWN' so that the testers\n*>              can be run multiple times without deleting generated\n*>              output files (susan)\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup complex_blas_testing\n*\n*  =====================================================================\n      PROGRAM CBLAT2\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER            NIN\n      PARAMETER          ( NIN = 5 )\n      INTEGER            NSUBS\n      PARAMETER          ( NSUBS = 17 )\n      COMPLEX            ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), ONE = ( 1.0, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n      INTEGER            NMAX, INCMAX\n      PARAMETER          ( NMAX = 65, INCMAX = 2 )\n      INTEGER            NINMAX, NIDMAX, NKBMAX, NALMAX, NBEMAX\n      PARAMETER          ( NINMAX = 7, NIDMAX = 9, NKBMAX = 7,\n     $                   NALMAX = 7, NBEMAX = 7 )\n*     .. Local Scalars ..\n      REAL               EPS, ERR, THRESH\n      INTEGER            I, ISNUM, J, N, NALF, NBET, NIDIM, NINC, NKB,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, LTESTT, REWI, SAME, SFATAL, TRACE,\n     $                   TSTERR\n      CHARACTER*1        TRANS\n      CHARACTER*6        SNAMET\n      CHARACTER*32       SNAPS, SUMMRY\n*     .. Local Arrays ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ),\n     $                   ALF( NALMAX ), AS( NMAX*NMAX ), BET( NBEMAX ),\n     $                   X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( 2*NMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDMAX ), INC( NINMAX ), KB( NKBMAX )\n      LOGICAL            LTEST( NSUBS )\n      CHARACTER*6        SNAMES( NSUBS )\n*     .. External Functions ..\n      REAL               SDIFF\n      LOGICAL            LCE\n      EXTERNAL           SDIFF, LCE\n*     .. External Subroutines ..\n      EXTERNAL           CCHK1, CCHK2, CCHK3, CCHK4, CCHK5, CCHK6,\n     $                   CCHKE, CMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Data statements ..\n      DATA               SNAMES/'CGEMV ', 'CGBMV ', 'CHEMV ', 'CHBMV ',\n     $                   'CHPMV ', 'CTRMV ', 'CTBMV ', 'CTPMV ',\n     $                   'CTRSV ', 'CTBSV ', 'CTPSV ', 'CGERC ',\n     $                   'CGERU ', 'CHER  ', 'CHPR  ', 'CHER2 ',\n     $                   'CHPR2 '/\n*     .. Executable Statements ..\n*\n*     Read name and unit number for summary output file and open file.\n*\n      READ( NIN, FMT = * )SUMMRY\n      READ( NIN, FMT = * )NOUT\n      OPEN( NOUT, FILE = SUMMRY, STATUS = 'UNKNOWN' )\n      NOUTC = NOUT\n*\n*     Read name and unit number for snapshot output file and open file.\n*\n      READ( NIN, FMT = * )SNAPS\n      READ( NIN, FMT = * )NTRA\n      TRACE = NTRA.GE.0\n      IF( TRACE )THEN\n         OPEN( NTRA, FILE = SNAPS, STATUS = 'UNKNOWN' )\n      END IF\n*     Read the flag that directs rewinding of the snapshot file.\n      READ( NIN, FMT = * )REWI\n      REWI = REWI.AND.TRACE\n*     Read the flag that directs stopping on any failure.\n      READ( NIN, FMT = * )SFATAL\n*     Read the flag that indicates whether error exits are to be tested.\n      READ( NIN, FMT = * )TSTERR\n*     Read the threshold value of the test ratio\n      READ( NIN, FMT = * )THRESH\n*\n*     Read and check the parameter values for the tests.\n*\n*     Values of N\n      READ( NIN, FMT = * )NIDIM\n      IF( NIDIM.LT.1.OR.NIDIM.GT.NIDMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'N', NIDMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( IDIM( I ), I = 1, NIDIM )\n      DO 10 I = 1, NIDIM\n         IF( IDIM( I ).LT.0.OR.IDIM( I ).GT.NMAX )THEN\n            WRITE( NOUT, FMT = 9996 )NMAX\n            GO TO 230\n         END IF\n   10 CONTINUE\n*     Values of K\n      READ( NIN, FMT = * )NKB\n      IF( NKB.LT.1.OR.NKB.GT.NKBMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'K', NKBMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( KB( I ), I = 1, NKB )\n      DO 20 I = 1, NKB\n         IF( KB( I ).LT.0 )THEN\n            WRITE( NOUT, FMT = 9995 )\n            GO TO 230\n         END IF\n   20 CONTINUE\n*     Values of INCX and INCY\n      READ( NIN, FMT = * )NINC\n      IF( NINC.LT.1.OR.NINC.GT.NINMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'INCX AND INCY', NINMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( INC( I ), I = 1, NINC )\n      DO 30 I = 1, NINC\n         IF( INC( I ).EQ.0.OR.ABS( INC( I ) ).GT.INCMAX )THEN\n            WRITE( NOUT, FMT = 9994 )INCMAX\n            GO TO 230\n         END IF\n   30 CONTINUE\n*     Values of ALPHA\n      READ( NIN, FMT = * )NALF\n      IF( NALF.LT.1.OR.NALF.GT.NALMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'ALPHA', NALMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( ALF( I ), I = 1, NALF )\n*     Values of BETA\n      READ( NIN, FMT = * )NBET\n      IF( NBET.LT.1.OR.NBET.GT.NBEMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'BETA', NBEMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( BET( I ), I = 1, NBET )\n*\n*     Report values of parameters.\n*\n      WRITE( NOUT, FMT = 9993 )\n      WRITE( NOUT, FMT = 9992 )( IDIM( I ), I = 1, NIDIM )\n      WRITE( NOUT, FMT = 9991 )( KB( I ), I = 1, NKB )\n      WRITE( NOUT, FMT = 9990 )( INC( I ), I = 1, NINC )\n      WRITE( NOUT, FMT = 9989 )( ALF( I ), I = 1, NALF )\n      WRITE( NOUT, FMT = 9988 )( BET( I ), I = 1, NBET )\n      IF( .NOT.TSTERR )THEN\n         WRITE( NOUT, FMT = * )\n         WRITE( NOUT, FMT = 9980 )\n      END IF\n      WRITE( NOUT, FMT = * )\n      WRITE( NOUT, FMT = 9999 )THRESH\n      WRITE( NOUT, FMT = * )\n*\n*     Read names of subroutines and flags which indicate\n*     whether they are to be tested.\n*\n      DO 40 I = 1, NSUBS\n         LTEST( I ) = .FALSE.\n   40 CONTINUE\n   50 READ( NIN, FMT = 9984, END = 80 )SNAMET, LTESTT\n      DO 60 I = 1, NSUBS\n         IF( SNAMET.EQ.SNAMES( I ) )\n     $      GO TO 70\n   60 CONTINUE\n      WRITE( NOUT, FMT = 9986 )SNAMET\n      STOP\n   70 LTEST( I ) = LTESTT\n      GO TO 50\n*\n   80 CONTINUE\n      CLOSE ( NIN )\n*\n*     Compute EPS (the machine precision).\n*\n      EPS = EPSILON(RZERO)\n      WRITE( NOUT, FMT = 9998 )EPS\n*\n*     Check the reliability of CMVCH using exact data.\n*\n      N = MIN( 32, NMAX )\n      DO 120 J = 1, N\n         DO 110 I = 1, N\n            A( I, J ) = MAX( I - J + 1, 0 )\n  110    CONTINUE\n         X( J ) = J\n         Y( J ) = ZERO\n  120 CONTINUE\n      DO 130 J = 1, N\n         YY( J ) = J*( ( J + 1 )*J )/2 - ( ( J + 1 )*J*( J - 1 ) )/3\n  130 CONTINUE\n*     YY holds the exact result. On exit from CMVCH YT holds\n*     the result computed by CMVCH.\n      TRANS = 'N'\n      CALL CMVCH( TRANS, N, N, ONE, A, NMAX, X, 1, ZERO, Y, 1, YT, G,\n     $            YY, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LCE( YY, YT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9985 )TRANS, SAME, ERR\n         STOP\n      END IF\n      TRANS = 'T'\n      CALL CMVCH( TRANS, N, N, ONE, A, NMAX, X, -1, ZERO, Y, -1, YT, G,\n     $            YY, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LCE( YY, YT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9985 )TRANS, SAME, ERR\n         STOP\n      END IF\n*\n*     Test each subroutine in turn.\n*\n      DO 210 ISNUM = 1, NSUBS\n         WRITE( NOUT, FMT = * )\n         IF( .NOT.LTEST( ISNUM ) )THEN\n*           Subprogram is not to be tested.\n            WRITE( NOUT, FMT = 9983 )SNAMES( ISNUM )\n         ELSE\n            SRNAMT = SNAMES( ISNUM )\n*           Test error exits.\n            IF( TSTERR )THEN\n               CALL CCHKE( ISNUM, SNAMES( ISNUM ), NOUT )\n               WRITE( NOUT, FMT = * )\n            END IF\n*           Test computations.\n            INFOT = 0\n            OK = .TRUE.\n            FATAL = .FALSE.\n            GO TO ( 140, 140, 150, 150, 150, 160, 160,\n     $              160, 160, 160, 160, 170, 170, 180,\n     $              180, 190, 190 )ISNUM\n*           Test CGEMV, 01, and CGBMV, 02.\n  140       CALL CCHK1( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF,\n     $                  NBET, BET, NINC, INC, NMAX, INCMAX, A, AA, AS,\n     $                  X, XX, XS, Y, YY, YS, YT, G )\n            GO TO 200\n*           Test CHEMV, 03, CHBMV, 04, and CHPMV, 05.\n  150       CALL CCHK2( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF,\n     $                  NBET, BET, NINC, INC, NMAX, INCMAX, A, AA, AS,\n     $                  X, XX, XS, Y, YY, YS, YT, G )\n            GO TO 200\n*           Test CTRMV, 06, CTBMV, 07, CTPMV, 08,\n*           CTRSV, 09, CTBSV, 10, and CTPSV, 11.\n  160       CALL CCHK3( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, Y, YY, YS, YT, G, Z )\n            GO TO 200\n*           Test CGERC, 12, CGERU, 13.\n  170       CALL CCHK4( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n            GO TO 200\n*           Test CHER, 14, and CHPR, 15.\n  180       CALL CCHK5( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n            GO TO 200\n*           Test CHER2, 16, and CHPR2, 17.\n  190       CALL CCHK6( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n*\n  200       IF( FATAL.AND.SFATAL )\n     $         GO TO 220\n         END IF\n  210 CONTINUE\n      WRITE( NOUT, FMT = 9982 )\n      GO TO 240\n*\n  220 CONTINUE\n      WRITE( NOUT, FMT = 9981 )\n      GO TO 240\n*\n  230 CONTINUE\n      WRITE( NOUT, FMT = 9987 )\n*\n  240 CONTINUE\n      IF( TRACE )\n     $   CLOSE ( NTRA )\n      CLOSE ( NOUT )\n      STOP\n*\n 9999 FORMAT( ' ROUTINES PASS COMPUTATIONAL TESTS IF TEST RATIO IS LES',\n     $      'S THAN', F8.2 )\n 9998 FORMAT( ' RELATIVE MACHINE PRECISION IS TAKEN TO BE', 1P, E9.1 )\n 9997 FORMAT( ' NUMBER OF VALUES OF ', A, ' IS LESS THAN 1 OR GREATER ',\n     $      'THAN ', I2 )\n 9996 FORMAT( ' VALUE OF N IS LESS THAN 0 OR GREATER THAN ', I2 )\n 9995 FORMAT( ' VALUE OF K IS LESS THAN 0' )\n 9994 FORMAT( ' ABSOLUTE VALUE OF INCX OR INCY IS 0 OR GREATER THAN ',\n     $      I2 )\n 9993 FORMAT( ' TESTS OF THE COMPLEX          LEVEL 2 BLAS', //' THE F',\n     $      'OLLOWING PARAMETER VALUES WILL BE USED:' )\n 9992 FORMAT( '   FOR N              ', 9I6 )\n 9991 FORMAT( '   FOR K              ', 7I6 )\n 9990 FORMAT( '   FOR INCX AND INCY  ', 7I6 )\n 9989 FORMAT( '   FOR ALPHA          ',\n     $      7( '(', F4.1, ',', F4.1, ')  ', : ) )\n 9988 FORMAT( '   FOR BETA           ',\n     $      7( '(', F4.1, ',', F4.1, ')  ', : ) )\n 9987 FORMAT( ' AMEND DATA FILE OR INCREASE ARRAY SIZES IN PROGRAM',\n     $      /' ******* TESTS ABANDONED *******' )\n 9986 FORMAT( ' SUBPROGRAM NAME ', A6, ' NOT RECOGNIZED', /' ******* T',\n     $      'ESTS ABANDONED *******' )\n 9985 FORMAT( ' ERROR IN CMVCH -  IN-LINE DOT PRODUCTS ARE BEING EVALU',\n     $      'ATED WRONGLY.', /' CMVCH WAS CALLED WITH TRANS = ', A1,\n     $      ' AND RETURNED SAME = ', L1, ' AND ERR = ', F12.3, '.', /\n     $   ' THIS MAY BE DUE TO FAULTS IN THE ARITHMETIC OR THE COMPILER.'\n     $      , /' ******* TESTS ABANDONED *******' )\n 9984 FORMAT( A6, L2 )\n 9983 FORMAT( 1X, A6, ' WAS NOT TESTED' )\n 9982 FORMAT( /' END OF TESTS' )\n 9981 FORMAT( /' ******* FATAL ERROR - TESTS ABANDONED *******' )\n 9980 FORMAT( ' ERROR-EXITS WILL NOT BE TESTED' )\n*\n*     End of CBLAT2.\n*\n      END\n      SUBROUTINE CCHK1( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF, NBET,\n     $                  BET, NINC, INC, NMAX, INCMAX, A, AA, AS, X, XX,\n     $                  XS, Y, YY, YS, YT, G )\n*\n*  Tests CGEMV and CGBMV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO, HALF\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), HALF = ( 0.5, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NALF, NBET, NIDIM, NINC, NKB, NMAX,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), BET( NBET ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XX( NMAX*INCMAX ),\n     $                   Y( NMAX ), YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, ALS, BETA, BLS, TRANSL\n      REAL               ERR, ERRMAX\n      INTEGER            I, IA, IB, IC, IKU, IM, IN, INCX, INCXS, INCY,\n     $                   INCYS, IX, IY, KL, KLS, KU, KUS, LAA, LDA,\n     $                   LDAS, LX, LY, M, ML, MS, N, NARGS, NC, ND, NK,\n     $                   NL, NS\n      LOGICAL            BANDED, FULL, NULL, RESET, SAME, TRAN\n      CHARACTER*1        TRANS, TRANSS\n      CHARACTER*3        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CGBMV, CGEMV, CMAKE, CMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'NTC'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'E'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 11\n      ELSE IF( BANDED )THEN\n         NARGS = 13\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 120 IN = 1, NIDIM\n         N = IDIM( IN )\n         ND = N/2 + 1\n*\n         DO 110 IM = 1, 2\n            IF( IM.EQ.1 )\n     $         M = MAX( N - ND, 0 )\n            IF( IM.EQ.2 )\n     $         M = MIN( N + ND, NMAX )\n*\n            IF( BANDED )THEN\n               NK = NKB\n            ELSE\n               NK = 1\n            END IF\n            DO 100 IKU = 1, NK\n               IF( BANDED )THEN\n                  KU = KB( IKU )\n                  KL = MAX( KU - 1, 0 )\n               ELSE\n                  KU = N - 1\n                  KL = M - 1\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               IF( BANDED )THEN\n                  LDA = KL + KU + 1\n               ELSE\n                  LDA = M\n               END IF\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 100\n               LAA = LDA*N\n               NULL = N.LE.0.OR.M.LE.0\n*\n*              Generate the matrix A.\n*\n               TRANSL = ZERO\n               CALL CMAKE( SNAME( 2: 3 ), ' ', ' ', M, N, A, NMAX, AA,\n     $                     LDA, KL, KU, RESET, TRANSL )\n*\n               DO 90 IC = 1, 3\n                  TRANS = ICH( IC: IC )\n                  TRAN = TRANS.EQ.'T'.OR.TRANS.EQ.'C'\n*\n                  IF( TRAN )THEN\n                     ML = N\n                     NL = M\n                  ELSE\n                     ML = M\n                     NL = N\n                  END IF\n*\n                  DO 80 IX = 1, NINC\n                     INCX = INC( IX )\n                     LX = ABS( INCX )*NL\n*\n*                    Generate the vector X.\n*\n                     TRANSL = HALF\n                     CALL CMAKE( 'GE', ' ', ' ', 1, NL, X, 1, XX,\n     $                           ABS( INCX ), 0, NL - 1, RESET, TRANSL )\n                     IF( NL.GT.1 )THEN\n                        X( NL/2 ) = ZERO\n                        XX( 1 + ABS( INCX )*( NL/2 - 1 ) ) = ZERO\n                     END IF\n*\n                     DO 70 IY = 1, NINC\n                        INCY = INC( IY )\n                        LY = ABS( INCY )*ML\n*\n                        DO 60 IA = 1, NALF\n                           ALPHA = ALF( IA )\n*\n                           DO 50 IB = 1, NBET\n                              BETA = BET( IB )\n*\n*                             Generate the vector Y.\n*\n                              TRANSL = ZERO\n                              CALL CMAKE( 'GE', ' ', ' ', 1, ML, Y, 1,\n     $                                    YY, ABS( INCY ), 0, ML - 1,\n     $                                    RESET, TRANSL )\n*\n                              NC = NC + 1\n*\n*                             Save every datum before calling the\n*                             subroutine.\n*\n                              TRANSS = TRANS\n                              MS = M\n                              NS = N\n                              KLS = KL\n                              KUS = KU\n                              ALS = ALPHA\n                              DO 10 I = 1, LAA\n                                 AS( I ) = AA( I )\n   10                         CONTINUE\n                              LDAS = LDA\n                              DO 20 I = 1, LX\n                                 XS( I ) = XX( I )\n   20                         CONTINUE\n                              INCXS = INCX\n                              BLS = BETA\n                              DO 30 I = 1, LY\n                                 YS( I ) = YY( I )\n   30                         CONTINUE\n                              INCYS = INCY\n*\n*                             Call the subroutine.\n*\n                              IF( FULL )THEN\n                                 IF( TRACE )\n     $                              WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                              TRANS, M, N, ALPHA, LDA, INCX, BETA,\n     $                              INCY\n                                 IF( REWI )\n     $                              REWIND NTRA\n                                 CALL CGEMV( TRANS, M, N, ALPHA, AA,\n     $                                       LDA, XX, INCX, BETA, YY,\n     $                                       INCY )\n                              ELSE IF( BANDED )THEN\n                                 IF( TRACE )\n     $                              WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                              TRANS, M, N, KL, KU, ALPHA, LDA,\n     $                              INCX, BETA, INCY\n                                 IF( REWI )\n     $                              REWIND NTRA\n                                 CALL CGBMV( TRANS, M, N, KL, KU, ALPHA,\n     $                                       AA, LDA, XX, INCX, BETA,\n     $                                       YY, INCY )\n                              END IF\n*\n*                             Check if error-exit was taken incorrectly.\n*\n                              IF( .NOT.OK )THEN\n                                 WRITE( NOUT, FMT = 9993 )\n                                 FATAL = .TRUE.\n                                 GO TO 130\n                              END IF\n*\n*                             See what data changed inside subroutines.\n*\n                              ISAME( 1 ) = TRANS.EQ.TRANSS\n                              ISAME( 2 ) = MS.EQ.M\n                              ISAME( 3 ) = NS.EQ.N\n                              IF( FULL )THEN\n                                 ISAME( 4 ) = ALS.EQ.ALPHA\n                                 ISAME( 5 ) = LCE( AS, AA, LAA )\n                                 ISAME( 6 ) = LDAS.EQ.LDA\n                                 ISAME( 7 ) = LCE( XS, XX, LX )\n                                 ISAME( 8 ) = INCXS.EQ.INCX\n                                 ISAME( 9 ) = BLS.EQ.BETA\n                                 IF( NULL )THEN\n                                    ISAME( 10 ) = LCE( YS, YY, LY )\n                                 ELSE\n                                    ISAME( 10 ) = LCERES( 'GE', ' ', 1,\n     $                                            ML, YS, YY,\n     $                                            ABS( INCY ) )\n                                 END IF\n                                 ISAME( 11 ) = INCYS.EQ.INCY\n                              ELSE IF( BANDED )THEN\n                                 ISAME( 4 ) = KLS.EQ.KL\n                                 ISAME( 5 ) = KUS.EQ.KU\n                                 ISAME( 6 ) = ALS.EQ.ALPHA\n                                 ISAME( 7 ) = LCE( AS, AA, LAA )\n                                 ISAME( 8 ) = LDAS.EQ.LDA\n                                 ISAME( 9 ) = LCE( XS, XX, LX )\n                                 ISAME( 10 ) = INCXS.EQ.INCX\n                                 ISAME( 11 ) = BLS.EQ.BETA\n                                 IF( NULL )THEN\n                                    ISAME( 12 ) = LCE( YS, YY, LY )\n                                 ELSE\n                                    ISAME( 12 ) = LCERES( 'GE', ' ', 1,\n     $                                            ML, YS, YY,\n     $                                            ABS( INCY ) )\n                                 END IF\n                                 ISAME( 13 ) = INCYS.EQ.INCY\n                              END IF\n*\n*                             If data was incorrectly changed, report\n*                             and return.\n*\n                              SAME = .TRUE.\n                              DO 40 I = 1, NARGS\n                                 SAME = SAME.AND.ISAME( I )\n                                 IF( .NOT.ISAME( I ) )\n     $                              WRITE( NOUT, FMT = 9998 )I\n   40                         CONTINUE\n                              IF( .NOT.SAME )THEN\n                                 FATAL = .TRUE.\n                                 GO TO 130\n                              END IF\n*\n                              IF( .NOT.NULL )THEN\n*\n*                                Check the result.\n*\n                                 CALL CMVCH( TRANS, M, N, ALPHA, A,\n     $                                       NMAX, X, INCX, BETA, Y,\n     $                                       INCY, YT, G, YY, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                                 ERRMAX = MAX( ERRMAX, ERR )\n*                                If got really bad answer, report and\n*                                return.\n                                 IF( FATAL )\n     $                              GO TO 130\n                              ELSE\n*                                Avoid repeating tests with M.le.0 or\n*                                N.le.0.\n                                 GO TO 110\n                              END IF\n*\n   50                      CONTINUE\n*\n   60                   CONTINUE\n*\n   70                CONTINUE\n*\n   80             CONTINUE\n*\n   90          CONTINUE\n*\n  100       CONTINUE\n*\n  110    CONTINUE\n*\n  120 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 140\n*\n  130 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, TRANS, M, N, ALPHA, LDA,\n     $      INCX, BETA, INCY\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, TRANS, M, N, KL, KU,\n     $      ALPHA, LDA, INCX, BETA, INCY\n      END IF\n*\n  140 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 4( I3, ',' ), '(',\n     $      F4.1, ',', F4.1, '), A,', I3, ', X,', I2, ',(', F4.1, ',',\n     $      F4.1, '), Y,', I2, ') .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 2( I3, ',' ), '(',\n     $      F4.1, ',', F4.1, '), A,', I3, ', X,', I2, ',(', F4.1, ',',\n     $      F4.1, '), Y,', I2, ')         .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK1.\n*\n      END\n      SUBROUTINE CCHK2( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF, NBET,\n     $                  BET, NINC, INC, NMAX, INCMAX, A, AA, AS, X, XX,\n     $                  XS, Y, YY, YS, YT, G )\n*\n*  Tests CHEMV, CHBMV and CHPMV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO, HALF\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), HALF = ( 0.5, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NALF, NBET, NIDIM, NINC, NKB, NMAX,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), BET( NBET ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XX( NMAX*INCMAX ),\n     $                   Y( NMAX ), YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, ALS, BETA, BLS, TRANSL\n      REAL               ERR, ERRMAX\n      INTEGER            I, IA, IB, IC, IK, IN, INCX, INCXS, INCY,\n     $                   INCYS, IX, IY, K, KS, LAA, LDA, LDAS, LX, LY,\n     $                   N, NARGS, NC, NK, NS\n      LOGICAL            BANDED, FULL, NULL, PACKED, RESET, SAME\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CHBMV, CHEMV, CHPMV, CMAKE, CMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'E'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 10\n      ELSE IF( BANDED )THEN\n         NARGS = 11\n      ELSE IF( PACKED )THEN\n         NARGS = 9\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 110 IN = 1, NIDIM\n         N = IDIM( IN )\n*\n         IF( BANDED )THEN\n            NK = NKB\n         ELSE\n            NK = 1\n         END IF\n         DO 100 IK = 1, NK\n            IF( BANDED )THEN\n               K = KB( IK )\n            ELSE\n               K = N - 1\n            END IF\n*           Set LDA to 1 more than minimum value if room.\n            IF( BANDED )THEN\n               LDA = K + 1\n            ELSE\n               LDA = N\n            END IF\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 100\n            IF( PACKED )THEN\n               LAA = ( N*( N + 1 ) )/2\n            ELSE\n               LAA = LDA*N\n            END IF\n            NULL = N.LE.0\n*\n            DO 90 IC = 1, 2\n               UPLO = ICH( IC: IC )\n*\n*              Generate the matrix A.\n*\n               TRANSL = ZERO\n               CALL CMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A, NMAX, AA,\n     $                     LDA, K, K, RESET, TRANSL )\n*\n               DO 80 IX = 1, NINC\n                  INCX = INC( IX )\n                  LX = ABS( INCX )*N\n*\n*                 Generate the vector X.\n*\n                  TRANSL = HALF\n                  CALL CMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX,\n     $                        ABS( INCX ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     X( N/2 ) = ZERO\n                     XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 70 IY = 1, NINC\n                     INCY = INC( IY )\n                     LY = ABS( INCY )*N\n*\n                     DO 60 IA = 1, NALF\n                        ALPHA = ALF( IA )\n*\n                        DO 50 IB = 1, NBET\n                           BETA = BET( IB )\n*\n*                          Generate the vector Y.\n*\n                           TRANSL = ZERO\n                           CALL CMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                                 ABS( INCY ), 0, N - 1, RESET,\n     $                                 TRANSL )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           UPLOS = UPLO\n                           NS = N\n                           KS = K\n                           ALS = ALPHA\n                           DO 10 I = 1, LAA\n                              AS( I ) = AA( I )\n   10                      CONTINUE\n                           LDAS = LDA\n                           DO 20 I = 1, LX\n                              XS( I ) = XX( I )\n   20                      CONTINUE\n                           INCXS = INCX\n                           BLS = BETA\n                           DO 30 I = 1, LY\n                              YS( I ) = YY( I )\n   30                      CONTINUE\n                           INCYS = INCY\n*\n*                          Call the subroutine.\n*\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, N, ALPHA, LDA, INCX, BETA, INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CHEMV( UPLO, N, ALPHA, AA, LDA, XX,\n     $                                    INCX, BETA, YY, INCY )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, N, K, ALPHA, LDA, INCX, BETA,\n     $                           INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CHBMV( UPLO, N, K, ALPHA, AA, LDA,\n     $                                    XX, INCX, BETA, YY, INCY )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, N, ALPHA, INCX, BETA, INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CHPMV( UPLO, N, ALPHA, AA, XX, INCX,\n     $                                    BETA, YY, INCY )\n                           END IF\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9992 )\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = UPLO.EQ.UPLOS\n                           ISAME( 2 ) = NS.EQ.N\n                           IF( FULL )THEN\n                              ISAME( 3 ) = ALS.EQ.ALPHA\n                              ISAME( 4 ) = LCE( AS, AA, LAA )\n                              ISAME( 5 ) = LDAS.EQ.LDA\n                              ISAME( 6 ) = LCE( XS, XX, LX )\n                              ISAME( 7 ) = INCXS.EQ.INCX\n                              ISAME( 8 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 9 ) = LCE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 9 ) = LCERES( 'GE', ' ', 1, N,\n     $                                        YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 10 ) = INCYS.EQ.INCY\n                           ELSE IF( BANDED )THEN\n                              ISAME( 3 ) = KS.EQ.K\n                              ISAME( 4 ) = ALS.EQ.ALPHA\n                              ISAME( 5 ) = LCE( AS, AA, LAA )\n                              ISAME( 6 ) = LDAS.EQ.LDA\n                              ISAME( 7 ) = LCE( XS, XX, LX )\n                              ISAME( 8 ) = INCXS.EQ.INCX\n                              ISAME( 9 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 10 ) = LCE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 10 ) = LCERES( 'GE', ' ', 1, N,\n     $                                         YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 11 ) = INCYS.EQ.INCY\n                           ELSE IF( PACKED )THEN\n                              ISAME( 3 ) = ALS.EQ.ALPHA\n                              ISAME( 4 ) = LCE( AS, AA, LAA )\n                              ISAME( 5 ) = LCE( XS, XX, LX )\n                              ISAME( 6 ) = INCXS.EQ.INCX\n                              ISAME( 7 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 8 ) = LCE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 8 ) = LCERES( 'GE', ' ', 1, N,\n     $                                        YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 9 ) = INCYS.EQ.INCY\n                           END IF\n*\n*                          If data was incorrectly changed, report and\n*                          return.\n*\n                           SAME = .TRUE.\n                           DO 40 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   40                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n*\n*                             Check the result.\n*\n                              CALL CMVCH( 'N', N, N, ALPHA, A, NMAX, X,\n     $                                    INCX, BETA, Y, INCY, YT, G,\n     $                                    YY, EPS, ERR, FATAL, NOUT,\n     $                                    .TRUE. )\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 120\n                           ELSE\n*                             Avoid repeating tests with N.le.0\n                              GO TO 110\n                           END IF\n*\n   50                   CONTINUE\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, ALPHA, LDA, INCX,\n     $      BETA, INCY\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, K, ALPHA, LDA,\n     $      INCX, BETA, INCY\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, UPLO, N, ALPHA, INCX,\n     $      BETA, INCY\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',(', F4.1, ',',\n     $      F4.1, '), AP, X,', I2, ',(', F4.1, ',', F4.1, '), Y,', I2,\n     $      ')                .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 2( I3, ',' ), '(',\n     $      F4.1, ',', F4.1, '), A,', I3, ', X,', I2, ',(', F4.1, ',',\n     $      F4.1, '), Y,', I2, ')         .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',(', F4.1, ',',\n     $      F4.1, '), A,', I3, ', X,', I2, ',(', F4.1, ',', F4.1, '), ',\n     $      'Y,', I2, ')             .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK2.\n*\n      END\n      SUBROUTINE CCHK3( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, XT, G, Z )\n*\n*  Tests CTRMV, CTBMV, CTPMV, CTRSV, CTBSV and CTPSV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO, HALF, ONE\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), HALF = ( 0.5, 0.0 ),\n     $                   ONE = ( 1.0, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NIDIM, NINC, NKB, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ),\n     $                   AS( NMAX*NMAX ), X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XT( NMAX ), XX( NMAX*INCMAX ), Z( NMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      COMPLEX            TRANSL\n      REAL               ERR, ERRMAX\n      INTEGER            I, ICD, ICT, ICU, IK, IN, INCX, INCXS, IX, K,\n     $                   KS, LAA, LDA, LDAS, LX, N, NARGS, NC, NK, NS\n      LOGICAL            BANDED, FULL, NULL, PACKED, RESET, SAME\n      CHARACTER*1        DIAG, DIAGS, TRANS, TRANSS, UPLO, UPLOS\n      CHARACTER*2        ICHD, ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CMAKE, CMVCH, CTBMV, CTBSV, CTPMV, CTPSV,\n     $                   CTRMV, CTRSV\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHU/'UL'/, ICHT/'NTC'/, ICHD/'UN'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'R'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 8\n      ELSE IF( BANDED )THEN\n         NARGS = 9\n      ELSE IF( PACKED )THEN\n         NARGS = 7\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*     Set up zero vector for CMVCH.\n      DO 10 I = 1, NMAX\n         Z( I ) = ZERO\n   10 CONTINUE\n*\n      DO 110 IN = 1, NIDIM\n         N = IDIM( IN )\n*\n         IF( BANDED )THEN\n            NK = NKB\n         ELSE\n            NK = 1\n         END IF\n         DO 100 IK = 1, NK\n            IF( BANDED )THEN\n               K = KB( IK )\n            ELSE\n               K = N - 1\n            END IF\n*           Set LDA to 1 more than minimum value if room.\n            IF( BANDED )THEN\n               LDA = K + 1\n            ELSE\n               LDA = N\n            END IF\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 100\n            IF( PACKED )THEN\n               LAA = ( N*( N + 1 ) )/2\n            ELSE\n               LAA = LDA*N\n            END IF\n            NULL = N.LE.0\n*\n            DO 90 ICU = 1, 2\n               UPLO = ICHU( ICU: ICU )\n*\n               DO 80 ICT = 1, 3\n                  TRANS = ICHT( ICT: ICT )\n*\n                  DO 70 ICD = 1, 2\n                     DIAG = ICHD( ICD: ICD )\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL CMAKE( SNAME( 2: 3 ), UPLO, DIAG, N, N, A,\n     $                           NMAX, AA, LDA, K, K, RESET, TRANSL )\n*\n                     DO 60 IX = 1, NINC\n                        INCX = INC( IX )\n                        LX = ABS( INCX )*N\n*\n*                       Generate the vector X.\n*\n                        TRANSL = HALF\n                        CALL CMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX,\n     $                              ABS( INCX ), 0, N - 1, RESET,\n     $                              TRANSL )\n                        IF( N.GT.1 )THEN\n                           X( N/2 ) = ZERO\n                           XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n                        END IF\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        DIAGS = DIAG\n                        NS = N\n                        KS = K\n                        DO 20 I = 1, LAA\n                           AS( I ) = AA( I )\n   20                   CONTINUE\n                        LDAS = LDA\n                        DO 30 I = 1, LX\n                           XS( I ) = XX( I )\n   30                   CONTINUE\n                        INCXS = INCX\n*\n*                       Call the subroutine.\n*\n                        IF( SNAME( 4: 5 ).EQ.'MV' )THEN\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CTRMV( UPLO, TRANS, DIAG, N, AA, LDA,\n     $                                    XX, INCX )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, K, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CTBMV( UPLO, TRANS, DIAG, N, K, AA,\n     $                                    LDA, XX, INCX )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CTPMV( UPLO, TRANS, DIAG, N, AA, XX,\n     $                                    INCX )\n                           END IF\n                        ELSE IF( SNAME( 4: 5 ).EQ.'SV' )THEN\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CTRSV( UPLO, TRANS, DIAG, N, AA, LDA,\n     $                                    XX, INCX )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, K, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CTBSV( UPLO, TRANS, DIAG, N, K, AA,\n     $                                    LDA, XX, INCX )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CTPSV( UPLO, TRANS, DIAG, N, AA, XX,\n     $                                    INCX )\n                           END IF\n                        END IF\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9992 )\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLO.EQ.UPLOS\n                        ISAME( 2 ) = TRANS.EQ.TRANSS\n                        ISAME( 3 ) = DIAG.EQ.DIAGS\n                        ISAME( 4 ) = NS.EQ.N\n                        IF( FULL )THEN\n                           ISAME( 5 ) = LCE( AS, AA, LAA )\n                           ISAME( 6 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 7 ) = LCE( XS, XX, LX )\n                           ELSE\n                              ISAME( 7 ) = LCERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 8 ) = INCXS.EQ.INCX\n                        ELSE IF( BANDED )THEN\n                           ISAME( 5 ) = KS.EQ.K\n                           ISAME( 6 ) = LCE( AS, AA, LAA )\n                           ISAME( 7 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 8 ) = LCE( XS, XX, LX )\n                           ELSE\n                              ISAME( 8 ) = LCERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 9 ) = INCXS.EQ.INCX\n                        ELSE IF( PACKED )THEN\n                           ISAME( 5 ) = LCE( AS, AA, LAA )\n                           IF( NULL )THEN\n                              ISAME( 6 ) = LCE( XS, XX, LX )\n                           ELSE\n                              ISAME( 6 ) = LCERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 7 ) = INCXS.EQ.INCX\n                        END IF\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n                           IF( SNAME( 4: 5 ).EQ.'MV' )THEN\n*\n*                             Check the result.\n*\n                              CALL CMVCH( TRANS, N, N, ONE, A, NMAX, X,\n     $                                    INCX, ZERO, Z, INCX, XT, G,\n     $                                    XX, EPS, ERR, FATAL, NOUT,\n     $                                    .TRUE. )\n                           ELSE IF( SNAME( 4: 5 ).EQ.'SV' )THEN\n*\n*                             Compute approximation to original vector.\n*\n                              DO 50 I = 1, N\n                                 Z( I ) = XX( 1 + ( I - 1 )*\n     $                                    ABS( INCX ) )\n                                 XX( 1 + ( I - 1 )*ABS( INCX ) )\n     $                              = X( I )\n   50                         CONTINUE\n                              CALL CMVCH( TRANS, N, N, ONE, A, NMAX, Z,\n     $                                    INCX, ZERO, X, INCX, XT, G,\n     $                                    XX, EPS, ERR, FATAL, NOUT,\n     $                                    .FALSE. )\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 120\n                        ELSE\n*                          Avoid repeating tests with N.le.0.\n                           GO TO 110\n                        END IF\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, TRANS, DIAG, N, LDA,\n     $      INCX\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, DIAG, N, K,\n     $      LDA, INCX\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, UPLO, TRANS, DIAG, N, INCX\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), I3, ', AP, ',\n     $      'X,', I2, ')                                      .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), 2( I3, ',' ),\n     $      ' A,', I3, ', X,', I2, ')                               .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), I3, ', A,',\n     $      I3, ', X,', I2, ')                                   .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK3.\n*\n      END\n      SUBROUTINE CCHK4( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests CGERC and CGERU.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO, HALF, ONE\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), HALF = ( 0.5, 0.0 ),\n     $                   ONE = ( 1.0, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, ALS, TRANSL\n      REAL               ERR, ERRMAX\n      INTEGER            I, IA, IM, IN, INCX, INCXS, INCY, INCYS, IX,\n     $                   IY, J, LAA, LDA, LDAS, LX, LY, M, MS, N, NARGS,\n     $                   NC, ND, NS\n      LOGICAL            CONJ, NULL, RESET, SAME\n*     .. Local Arrays ..\n      COMPLEX            W( 1 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CGERC, CGERU, CMAKE, CMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, CONJG, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n      CONJ = SNAME( 5: 5 ).EQ.'C'\n*     Define the number of arguments.\n      NARGS = 9\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 120 IN = 1, NIDIM\n         N = IDIM( IN )\n         ND = N/2 + 1\n*\n         DO 110 IM = 1, 2\n            IF( IM.EQ.1 )\n     $         M = MAX( N - ND, 0 )\n            IF( IM.EQ.2 )\n     $         M = MIN( N + ND, NMAX )\n*\n*           Set LDA to 1 more than minimum value if room.\n            LDA = M\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 110\n            LAA = LDA*N\n            NULL = N.LE.0.OR.M.LE.0\n*\n            DO 100 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*M\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL CMAKE( 'GE', ' ', ' ', 1, M, X, 1, XX, ABS( INCX ),\n     $                     0, M - 1, RESET, TRANSL )\n               IF( M.GT.1 )THEN\n                  X( M/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( M/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 90 IY = 1, NINC\n                  INCY = INC( IY )\n                  LY = ABS( INCY )*N\n*\n*                 Generate the vector Y.\n*\n                  TRANSL = ZERO\n                  CALL CMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                        ABS( INCY ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     Y( N/2 ) = ZERO\n                     YY( 1 + ABS( INCY )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 80 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL CMAKE( SNAME( 2: 3 ), ' ', ' ', M, N, A, NMAX,\n     $                           AA, LDA, M - 1, N - 1, RESET, TRANSL )\n*\n                     NC = NC + 1\n*\n*                    Save every datum before calling the subroutine.\n*\n                     MS = M\n                     NS = N\n                     ALS = ALPHA\n                     DO 10 I = 1, LAA\n                        AS( I ) = AA( I )\n   10                CONTINUE\n                     LDAS = LDA\n                     DO 20 I = 1, LX\n                        XS( I ) = XX( I )\n   20                CONTINUE\n                     INCXS = INCX\n                     DO 30 I = 1, LY\n                        YS( I ) = YY( I )\n   30                CONTINUE\n                     INCYS = INCY\n*\n*                    Call the subroutine.\n*\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9994 )NC, SNAME, M, N,\n     $                  ALPHA, INCX, INCY, LDA\n                     IF( CONJ )THEN\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL CGERC( M, N, ALPHA, XX, INCX, YY, INCY, AA,\n     $                              LDA )\n                     ELSE\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL CGERU( M, N, ALPHA, XX, INCX, YY, INCY, AA,\n     $                              LDA )\n                     END IF\n*\n*                    Check if error-exit was taken incorrectly.\n*\n                     IF( .NOT.OK )THEN\n                        WRITE( NOUT, FMT = 9993 )\n                        FATAL = .TRUE.\n                        GO TO 140\n                     END IF\n*\n*                    See what data changed inside subroutine.\n*\n                     ISAME( 1 ) = MS.EQ.M\n                     ISAME( 2 ) = NS.EQ.N\n                     ISAME( 3 ) = ALS.EQ.ALPHA\n                     ISAME( 4 ) = LCE( XS, XX, LX )\n                     ISAME( 5 ) = INCXS.EQ.INCX\n                     ISAME( 6 ) = LCE( YS, YY, LY )\n                     ISAME( 7 ) = INCYS.EQ.INCY\n                     IF( NULL )THEN\n                        ISAME( 8 ) = LCE( AS, AA, LAA )\n                     ELSE\n                        ISAME( 8 ) = LCERES( 'GE', ' ', M, N, AS, AA,\n     $                               LDA )\n                     END IF\n                     ISAME( 9 ) = LDAS.EQ.LDA\n*\n*                    If data was incorrectly changed, report and return.\n*\n                     SAME = .TRUE.\n                     DO 40 I = 1, NARGS\n                        SAME = SAME.AND.ISAME( I )\n                        IF( .NOT.ISAME( I ) )\n     $                     WRITE( NOUT, FMT = 9998 )I\n   40                CONTINUE\n                     IF( .NOT.SAME )THEN\n                        FATAL = .TRUE.\n                        GO TO 140\n                     END IF\n*\n                     IF( .NOT.NULL )THEN\n*\n*                       Check the result column by column.\n*\n                        IF( INCX.GT.0 )THEN\n                           DO 50 I = 1, M\n                              Z( I ) = X( I )\n   50                      CONTINUE\n                        ELSE\n                           DO 60 I = 1, M\n                              Z( I ) = X( M - I + 1 )\n   60                      CONTINUE\n                        END IF\n                        DO 70 J = 1, N\n                           IF( INCY.GT.0 )THEN\n                              W( 1 ) = Y( J )\n                           ELSE\n                              W( 1 ) = Y( N - J + 1 )\n                           END IF\n                           IF( CONJ )\n     $                        W( 1 ) = CONJG( W( 1 ) )\n                           CALL CMVCH( 'N', M, 1, ALPHA, Z, NMAX, W, 1,\n     $                                 ONE, A( 1, J ), 1, YT, G,\n     $                                 AA( 1 + ( J - 1 )*LDA ), EPS,\n     $                                 ERR, FATAL, NOUT, .TRUE. )\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 130\n   70                   CONTINUE\n                     ELSE\n*                       Avoid repeating tests with M.le.0 or N.le.0.\n                        GO TO 110\n                     END IF\n*\n   80             CONTINUE\n*\n   90          CONTINUE\n*\n  100       CONTINUE\n*\n  110    CONTINUE\n*\n  120 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 150\n*\n  130 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  140 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9994 )NC, SNAME, M, N, ALPHA, INCX, INCY, LDA\n*\n  150 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( I3, ',' ), '(', F4.1, ',', F4.1,\n     $      '), X,', I2, ', Y,', I2, ', A,', I3, ')                   ',\n     $      '      .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK4.\n*\n      END\n      SUBROUTINE CCHK5( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests CHER and CHPR.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO, HALF, ONE\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), HALF = ( 0.5, 0.0 ),\n     $                   ONE = ( 1.0, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, TRANSL\n      REAL               ERR, ERRMAX, RALPHA, RALS\n      INTEGER            I, IA, IC, IN, INCX, INCXS, IX, J, JA, JJ, LAA,\n     $                   LDA, LDAS, LJ, LX, N, NARGS, NC, NS\n      LOGICAL            FULL, NULL, PACKED, RESET, SAME, UPPER\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      COMPLEX            W( 1 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CHER, CHPR, CMAKE, CMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, CMPLX, CONJG, MAX, REAL\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'E'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 7\n      ELSE IF( PACKED )THEN\n         NARGS = 6\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 100 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDA to 1 more than minimum value if room.\n         LDA = N\n         IF( LDA.LT.NMAX )\n     $      LDA = LDA + 1\n*        Skip tests if not enough room.\n         IF( LDA.GT.NMAX )\n     $      GO TO 100\n         IF( PACKED )THEN\n            LAA = ( N*( N + 1 ) )/2\n         ELSE\n            LAA = LDA*N\n         END IF\n*\n         DO 90 IC = 1, 2\n            UPLO = ICH( IC: IC )\n            UPPER = UPLO.EQ.'U'\n*\n            DO 80 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*N\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL CMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX, ABS( INCX ),\n     $                     0, N - 1, RESET, TRANSL )\n               IF( N.GT.1 )THEN\n                  X( N/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 70 IA = 1, NALF\n                  RALPHA = REAL( ALF( IA ) )\n                  ALPHA = CMPLX( RALPHA, RZERO )\n                  NULL = N.LE.0.OR.RALPHA.EQ.RZERO\n*\n*                 Generate the matrix A.\n*\n                  TRANSL = ZERO\n                  CALL CMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A, NMAX,\n     $                        AA, LDA, N - 1, N - 1, RESET, TRANSL )\n*\n                  NC = NC + 1\n*\n*                 Save every datum before calling the subroutine.\n*\n                  UPLOS = UPLO\n                  NS = N\n                  RALS = RALPHA\n                  DO 10 I = 1, LAA\n                     AS( I ) = AA( I )\n   10             CONTINUE\n                  LDAS = LDA\n                  DO 20 I = 1, LX\n                     XS( I ) = XX( I )\n   20             CONTINUE\n                  INCXS = INCX\n*\n*                 Call the subroutine.\n*\n                  IF( FULL )THEN\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO, N,\n     $                  RALPHA, INCX, LDA\n                     IF( REWI )\n     $                  REWIND NTRA\n                     CALL CHER( UPLO, N, RALPHA, XX, INCX, AA, LDA )\n                  ELSE IF( PACKED )THEN\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO, N,\n     $                  RALPHA, INCX\n                     IF( REWI )\n     $                  REWIND NTRA\n                     CALL CHPR( UPLO, N, RALPHA, XX, INCX, AA )\n                  END IF\n*\n*                 Check if error-exit was taken incorrectly.\n*\n                  IF( .NOT.OK )THEN\n                     WRITE( NOUT, FMT = 9992 )\n                     FATAL = .TRUE.\n                     GO TO 120\n                  END IF\n*\n*                 See what data changed inside subroutines.\n*\n                  ISAME( 1 ) = UPLO.EQ.UPLOS\n                  ISAME( 2 ) = NS.EQ.N\n                  ISAME( 3 ) = RALS.EQ.RALPHA\n                  ISAME( 4 ) = LCE( XS, XX, LX )\n                  ISAME( 5 ) = INCXS.EQ.INCX\n                  IF( NULL )THEN\n                     ISAME( 6 ) = LCE( AS, AA, LAA )\n                  ELSE\n                     ISAME( 6 ) = LCERES( SNAME( 2: 3 ), UPLO, N, N, AS,\n     $                            AA, LDA )\n                  END IF\n                  IF( .NOT.PACKED )THEN\n                     ISAME( 7 ) = LDAS.EQ.LDA\n                  END IF\n*\n*                 If data was incorrectly changed, report and return.\n*\n                  SAME = .TRUE.\n                  DO 30 I = 1, NARGS\n                     SAME = SAME.AND.ISAME( I )\n                     IF( .NOT.ISAME( I ) )\n     $                  WRITE( NOUT, FMT = 9998 )I\n   30             CONTINUE\n                  IF( .NOT.SAME )THEN\n                     FATAL = .TRUE.\n                     GO TO 120\n                  END IF\n*\n                  IF( .NOT.NULL )THEN\n*\n*                    Check the result column by column.\n*\n                     IF( INCX.GT.0 )THEN\n                        DO 40 I = 1, N\n                           Z( I ) = X( I )\n   40                   CONTINUE\n                     ELSE\n                        DO 50 I = 1, N\n                           Z( I ) = X( N - I + 1 )\n   50                   CONTINUE\n                     END IF\n                     JA = 1\n                     DO 60 J = 1, N\n                        W( 1 ) = CONJG( Z( J ) )\n                        IF( UPPER )THEN\n                           JJ = 1\n                           LJ = J\n                        ELSE\n                           JJ = J\n                           LJ = N - J + 1\n                        END IF\n                        CALL CMVCH( 'N', LJ, 1, ALPHA, Z( JJ ), LJ, W,\n     $                              1, ONE, A( JJ, J ), 1, YT, G,\n     $                              AA( JA ), EPS, ERR, FATAL, NOUT,\n     $                              .TRUE. )\n                        IF( FULL )THEN\n                           IF( UPPER )THEN\n                              JA = JA + LDA\n                           ELSE\n                              JA = JA + LDA + 1\n                           END IF\n                        ELSE\n                           JA = JA + LJ\n                        END IF\n                        ERRMAX = MAX( ERRMAX, ERR )\n*                       If got really bad answer, report and return.\n                        IF( FATAL )\n     $                     GO TO 110\n   60                CONTINUE\n                  ELSE\n*                    Avoid repeating tests if N.le.0.\n                     IF( N.LE.0 )\n     $                  GO TO 100\n                  END IF\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  110 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, RALPHA, INCX, LDA\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, RALPHA, INCX\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', AP)                                         .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', A,', I3, ')                                      .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK5.\n*\n      END\n      SUBROUTINE CCHK6( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests CHER2 and CHPR2.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO, HALF, ONE\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), HALF = ( 0.5, 0.0 ),\n     $                   ONE = ( 1.0, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX, 2 )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, ALS, TRANSL\n      REAL               ERR, ERRMAX\n      INTEGER            I, IA, IC, IN, INCX, INCXS, INCY, INCYS, IX,\n     $                   IY, J, JA, JJ, LAA, LDA, LDAS, LJ, LX, LY, N,\n     $                   NARGS, NC, NS\n      LOGICAL            FULL, NULL, PACKED, RESET, SAME, UPPER\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      COMPLEX            W( 2 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CHER2, CHPR2, CMAKE, CMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, CONJG, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'E'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 9\n      ELSE IF( PACKED )THEN\n         NARGS = 8\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 140 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDA to 1 more than minimum value if room.\n         LDA = N\n         IF( LDA.LT.NMAX )\n     $      LDA = LDA + 1\n*        Skip tests if not enough room.\n         IF( LDA.GT.NMAX )\n     $      GO TO 140\n         IF( PACKED )THEN\n            LAA = ( N*( N + 1 ) )/2\n         ELSE\n            LAA = LDA*N\n         END IF\n*\n         DO 130 IC = 1, 2\n            UPLO = ICH( IC: IC )\n            UPPER = UPLO.EQ.'U'\n*\n            DO 120 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*N\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL CMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX, ABS( INCX ),\n     $                     0, N - 1, RESET, TRANSL )\n               IF( N.GT.1 )THEN\n                  X( N/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 110 IY = 1, NINC\n                  INCY = INC( IY )\n                  LY = ABS( INCY )*N\n*\n*                 Generate the vector Y.\n*\n                  TRANSL = ZERO\n                  CALL CMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                        ABS( INCY ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     Y( N/2 ) = ZERO\n                     YY( 1 + ABS( INCY )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 100 IA = 1, NALF\n                     ALPHA = ALF( IA )\n                     NULL = N.LE.0.OR.ALPHA.EQ.ZERO\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL CMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A,\n     $                           NMAX, AA, LDA, N - 1, N - 1, RESET,\n     $                           TRANSL )\n*\n                     NC = NC + 1\n*\n*                    Save every datum before calling the subroutine.\n*\n                     UPLOS = UPLO\n                     NS = N\n                     ALS = ALPHA\n                     DO 10 I = 1, LAA\n                        AS( I ) = AA( I )\n   10                CONTINUE\n                     LDAS = LDA\n                     DO 20 I = 1, LX\n                        XS( I ) = XX( I )\n   20                CONTINUE\n                     INCXS = INCX\n                     DO 30 I = 1, LY\n                        YS( I ) = YY( I )\n   30                CONTINUE\n                     INCYS = INCY\n*\n*                    Call the subroutine.\n*\n                     IF( FULL )THEN\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO, N,\n     $                     ALPHA, INCX, INCY, LDA\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL CHER2( UPLO, N, ALPHA, XX, INCX, YY, INCY,\n     $                              AA, LDA )\n                     ELSE IF( PACKED )THEN\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO, N,\n     $                     ALPHA, INCX, INCY\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL CHPR2( UPLO, N, ALPHA, XX, INCX, YY, INCY,\n     $                              AA )\n                     END IF\n*\n*                    Check if error-exit was taken incorrectly.\n*\n                     IF( .NOT.OK )THEN\n                        WRITE( NOUT, FMT = 9992 )\n                        FATAL = .TRUE.\n                        GO TO 160\n                     END IF\n*\n*                    See what data changed inside subroutines.\n*\n                     ISAME( 1 ) = UPLO.EQ.UPLOS\n                     ISAME( 2 ) = NS.EQ.N\n                     ISAME( 3 ) = ALS.EQ.ALPHA\n                     ISAME( 4 ) = LCE( XS, XX, LX )\n                     ISAME( 5 ) = INCXS.EQ.INCX\n                     ISAME( 6 ) = LCE( YS, YY, LY )\n                     ISAME( 7 ) = INCYS.EQ.INCY\n                     IF( NULL )THEN\n                        ISAME( 8 ) = LCE( AS, AA, LAA )\n                     ELSE\n                        ISAME( 8 ) = LCERES( SNAME( 2: 3 ), UPLO, N, N,\n     $                               AS, AA, LDA )\n                     END IF\n                     IF( .NOT.PACKED )THEN\n                        ISAME( 9 ) = LDAS.EQ.LDA\n                     END IF\n*\n*                    If data was incorrectly changed, report and return.\n*\n                     SAME = .TRUE.\n                     DO 40 I = 1, NARGS\n                        SAME = SAME.AND.ISAME( I )\n                        IF( .NOT.ISAME( I ) )\n     $                     WRITE( NOUT, FMT = 9998 )I\n   40                CONTINUE\n                     IF( .NOT.SAME )THEN\n                        FATAL = .TRUE.\n                        GO TO 160\n                     END IF\n*\n                     IF( .NOT.NULL )THEN\n*\n*                       Check the result column by column.\n*\n                        IF( INCX.GT.0 )THEN\n                           DO 50 I = 1, N\n                              Z( I, 1 ) = X( I )\n   50                      CONTINUE\n                        ELSE\n                           DO 60 I = 1, N\n                              Z( I, 1 ) = X( N - I + 1 )\n   60                      CONTINUE\n                        END IF\n                        IF( INCY.GT.0 )THEN\n                           DO 70 I = 1, N\n                              Z( I, 2 ) = Y( I )\n   70                      CONTINUE\n                        ELSE\n                           DO 80 I = 1, N\n                              Z( I, 2 ) = Y( N - I + 1 )\n   80                      CONTINUE\n                        END IF\n                        JA = 1\n                        DO 90 J = 1, N\n                           W( 1 ) = ALPHA*CONJG( Z( J, 2 ) )\n                           W( 2 ) = CONJG( ALPHA )*CONJG( Z( J, 1 ) )\n                           IF( UPPER )THEN\n                              JJ = 1\n                              LJ = J\n                           ELSE\n                              JJ = J\n                              LJ = N - J + 1\n                           END IF\n                           CALL CMVCH( 'N', LJ, 2, ONE, Z( JJ, 1 ),\n     $                                 NMAX, W, 1, ONE, A( JJ, J ), 1,\n     $                                 YT, G, AA( JA ), EPS, ERR, FATAL,\n     $                                 NOUT, .TRUE. )\n                           IF( FULL )THEN\n                              IF( UPPER )THEN\n                                 JA = JA + LDA\n                              ELSE\n                                 JA = JA + LDA + 1\n                              END IF\n                           ELSE\n                              JA = JA + LJ\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 150\n   90                   CONTINUE\n                     ELSE\n*                       Avoid repeating tests with N.le.0.\n                        IF( N.LE.0 )\n     $                     GO TO 140\n                     END IF\n*\n  100             CONTINUE\n*\n  110          CONTINUE\n*\n  120       CONTINUE\n*\n  130    CONTINUE\n*\n  140 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 170\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  160 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, ALPHA, INCX,\n     $      INCY, LDA\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, ALPHA, INCX, INCY\n      END IF\n*\n  170 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',(', F4.1, ',',\n     $      F4.1, '), X,', I2, ', Y,', I2, ', AP)                     ',\n     $      '       .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',(', F4.1, ',',\n     $      F4.1, '), X,', I2, ', Y,', I2, ', A,', I3, ')             ',\n     $      '            .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK6.\n*\n      END\n      SUBROUTINE CCHKE( ISNUM, SRNAMT, NOUT )\n*\n*  Tests the error exits from the Level 2 Blas.\n*  Requires a special version of the error-handling routine XERBLA.\n*  ALPHA, RALPHA, BETA, A, X and Y should not need to be defined.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            ISNUM, NOUT\n      CHARACTER*6        SRNAMT\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, BETA\n      REAL               RALPHA\n*     .. Local Arrays ..\n      COMPLEX            A( 1, 1 ), X( 1 ), Y( 1 )\n*     .. External Subroutines ..\n      EXTERNAL           CGBMV, CGEMV, CGERC, CGERU, CHBMV, CHEMV, CHER,\n     $                   CHER2, CHKXER, CHPMV, CHPR, CHPR2, CTBMV,\n     $                   CTBSV, CTPMV, CTPSV, CTRMV, CTRSV\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n*     OK is set to .FALSE. by the special version of XERBLA or by CHKXER\n*     if anything is wrong.\n      OK = .TRUE.\n*     LERR is set to .TRUE. by the special version of XERBLA each time\n*     it is called, and is then tested and re-set by CHKXER.\n      LERR = .FALSE.\n      GO TO ( 10, 20, 30, 40, 50, 60, 70, 80,\n     $        90, 100, 110, 120, 130, 140, 150, 160,\n     $        170 )ISNUM\n   10 INFOT = 1\n      CALL CGEMV( '/', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CGEMV( 'N', -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGEMV( 'N', 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CGEMV( 'N', 2, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGEMV( 'N', 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CGEMV( 'N', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   20 INFOT = 1\n      CALL CGBMV( '/', 0, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CGBMV( 'N', -1, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGBMV( 'N', 0, -1, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CGBMV( 'N', 0, 0, -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGBMV( 'N', 2, 0, 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGBMV( 'N', 0, 0, 1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CGBMV( 'N', 0, 0, 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL CGBMV( 'N', 0, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   30 INFOT = 1\n      CALL CHEMV( '/', 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CHEMV( 'U', -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CHEMV( 'U', 2, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHEMV( 'U', 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CHEMV( 'U', 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   40 INFOT = 1\n      CALL CHBMV( '/', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CHBMV( 'U', -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHBMV( 'U', 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CHBMV( 'U', 0, 1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CHBMV( 'U', 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CHBMV( 'U', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   50 INFOT = 1\n      CALL CHPMV( '/', 0, ALPHA, A, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CHPMV( 'U', -1, ALPHA, A, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CHPMV( 'U', 0, ALPHA, A, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CHPMV( 'U', 0, ALPHA, A, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   60 INFOT = 1\n      CALL CTRMV( '/', 'N', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CTRMV( 'U', '/', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CTRMV( 'U', 'N', '/', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CTRMV( 'U', 'N', 'N', -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMV( 'U', 'N', 'N', 2, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CTRMV( 'U', 'N', 'N', 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   70 INFOT = 1\n      CALL CTBMV( '/', 'N', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CTBMV( 'U', '/', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CTBMV( 'U', 'N', '/', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CTBMV( 'U', 'N', 'N', -1, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTBMV( 'U', 'N', 'N', 0, -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CTBMV( 'U', 'N', 'N', 0, 1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTBMV( 'U', 'N', 'N', 0, 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   80 INFOT = 1\n      CALL CTPMV( '/', 'N', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CTPMV( 'U', '/', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CTPMV( 'U', 'N', '/', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CTPMV( 'U', 'N', 'N', -1, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CTPMV( 'U', 'N', 'N', 0, A, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   90 INFOT = 1\n      CALL CTRSV( '/', 'N', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CTRSV( 'U', '/', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CTRSV( 'U', 'N', '/', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CTRSV( 'U', 'N', 'N', -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSV( 'U', 'N', 'N', 2, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CTRSV( 'U', 'N', 'N', 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  100 INFOT = 1\n      CALL CTBSV( '/', 'N', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CTBSV( 'U', '/', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CTBSV( 'U', 'N', '/', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CTBSV( 'U', 'N', 'N', -1, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTBSV( 'U', 'N', 'N', 0, -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CTBSV( 'U', 'N', 'N', 0, 1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTBSV( 'U', 'N', 'N', 0, 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  110 INFOT = 1\n      CALL CTPSV( '/', 'N', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CTPSV( 'U', '/', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CTPSV( 'U', 'N', '/', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CTPSV( 'U', 'N', 'N', -1, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CTPSV( 'U', 'N', 'N', 0, A, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  120 INFOT = 1\n      CALL CGERC( -1, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CGERC( 0, -1, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGERC( 0, 0, ALPHA, X, 0, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CGERC( 0, 0, ALPHA, X, 1, Y, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CGERC( 2, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  130 INFOT = 1\n      CALL CGERU( -1, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CGERU( 0, -1, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGERU( 0, 0, ALPHA, X, 0, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CGERU( 0, 0, ALPHA, X, 1, Y, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CGERU( 2, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  140 INFOT = 1\n      CALL CHER( '/', 0, RALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CHER( 'U', -1, RALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CHER( 'U', 0, RALPHA, X, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHER( 'U', 2, RALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  150 INFOT = 1\n      CALL CHPR( '/', 0, RALPHA, X, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CHPR( 'U', -1, RALPHA, X, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CHPR( 'U', 0, RALPHA, X, 0, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  160 INFOT = 1\n      CALL CHER2( '/', 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CHER2( 'U', -1, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CHER2( 'U', 0, ALPHA, X, 0, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHER2( 'U', 0, ALPHA, X, 1, Y, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CHER2( 'U', 2, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  170 INFOT = 1\n      CALL CHPR2( '/', 0, ALPHA, X, 1, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CHPR2( 'U', -1, ALPHA, X, 1, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CHPR2( 'U', 0, ALPHA, X, 0, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHPR2( 'U', 0, ALPHA, X, 1, Y, 0, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n  180 IF( OK )THEN\n         WRITE( NOUT, FMT = 9999 )SRNAMT\n      ELSE\n         WRITE( NOUT, FMT = 9998 )SRNAMT\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE TESTS OF ERROR-EXITS' )\n 9998 FORMAT( ' ******* ', A6, ' FAILED THE TESTS OF ERROR-EXITS *****',\n     $      '**' )\n*\n*     End of CCHKE.\n*\n      END\n      SUBROUTINE CMAKE( TYPE, UPLO, DIAG, M, N, A, NMAX, AA, LDA, KL,\n     $                  KU, RESET, TRANSL )\n*\n*  Generates values for an M by N matrix A within the bandwidth\n*  defined by KL and KU.\n*  Stores the values in the array AA in the data structure required\n*  by the routine, with unwanted elements set to rogue value.\n*\n*  TYPE is 'GE', 'GB', 'HE', 'HB', 'HP', 'TR', 'TB' OR 'TP'.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), ONE = ( 1.0, 0.0 ) )\n      COMPLEX            ROGUE\n      PARAMETER          ( ROGUE = ( -1.0E10, 1.0E10 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n      REAL               RROGUE\n      PARAMETER          ( RROGUE = -1.0E10 )\n*     .. Scalar Arguments ..\n      COMPLEX            TRANSL\n      INTEGER            KL, KU, LDA, M, N, NMAX\n      LOGICAL            RESET\n      CHARACTER*1        DIAG, UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, * ), AA( * )\n*     .. Local Scalars ..\n      INTEGER            I, I1, I2, I3, IBEG, IEND, IOFF, J, JJ, KK\n      LOGICAL            GEN, LOWER, SYM, TRI, UNIT, UPPER\n*     .. External Functions ..\n      COMPLEX            CBEG\n      EXTERNAL           CBEG\n*     .. Intrinsic Functions ..\n      INTRINSIC          CMPLX, CONJG, MAX, MIN, REAL\n*     .. Executable Statements ..\n      GEN = TYPE( 1: 1 ).EQ.'G'\n      SYM = TYPE( 1: 1 ).EQ.'H'\n      TRI = TYPE( 1: 1 ).EQ.'T'\n      UPPER = ( SYM.OR.TRI ).AND.UPLO.EQ.'U'\n      LOWER = ( SYM.OR.TRI ).AND.UPLO.EQ.'L'\n      UNIT = TRI.AND.DIAG.EQ.'U'\n*\n*     Generate data in array A.\n*\n      DO 20 J = 1, N\n         DO 10 I = 1, M\n            IF( GEN.OR.( UPPER.AND.I.LE.J ).OR.( LOWER.AND.I.GE.J ) )\n     $          THEN\n               IF( ( I.LE.J.AND.J - I.LE.KU ).OR.\n     $             ( I.GE.J.AND.I - J.LE.KL ) )THEN\n                  A( I, J ) = CBEG( RESET ) + TRANSL\n               ELSE\n                  A( I, J ) = ZERO\n               END IF\n               IF( I.NE.J )THEN\n                  IF( SYM )THEN\n                     A( J, I ) = CONJG( A( I, J ) )\n                  ELSE IF( TRI )THEN\n                     A( J, I ) = ZERO\n                  END IF\n               END IF\n            END IF\n   10    CONTINUE\n         IF( SYM )\n     $      A( J, J ) = CMPLX( REAL( A( J, J ) ), RZERO )\n         IF( TRI )\n     $      A( J, J ) = A( J, J ) + ONE\n         IF( UNIT )\n     $      A( J, J ) = ONE\n   20 CONTINUE\n*\n*     Store elements in array AS in data structure required by routine.\n*\n      IF( TYPE.EQ.'GE' )THEN\n         DO 50 J = 1, N\n            DO 30 I = 1, M\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   30       CONTINUE\n            DO 40 I = M + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   40       CONTINUE\n   50    CONTINUE\n      ELSE IF( TYPE.EQ.'GB' )THEN\n         DO 90 J = 1, N\n            DO 60 I1 = 1, KU + 1 - J\n               AA( I1 + ( J - 1 )*LDA ) = ROGUE\n   60       CONTINUE\n            DO 70 I2 = I1, MIN( KL + KU + 1, KU + 1 + M - J )\n               AA( I2 + ( J - 1 )*LDA ) = A( I2 + J - KU - 1, J )\n   70       CONTINUE\n            DO 80 I3 = I2, LDA\n               AA( I3 + ( J - 1 )*LDA ) = ROGUE\n   80       CONTINUE\n   90    CONTINUE\n      ELSE IF( TYPE.EQ.'HE'.OR.TYPE.EQ.'TR' )THEN\n         DO 130 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IF( UNIT )THEN\n                  IEND = J - 1\n               ELSE\n                  IEND = J\n               END IF\n            ELSE\n               IF( UNIT )THEN\n                  IBEG = J + 1\n               ELSE\n                  IBEG = J\n               END IF\n               IEND = N\n            END IF\n            DO 100 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  100       CONTINUE\n            DO 110 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n  110       CONTINUE\n            DO 120 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  120       CONTINUE\n            IF( SYM )THEN\n               JJ = J + ( J - 1 )*LDA\n               AA( JJ ) = CMPLX( REAL( AA( JJ ) ), RROGUE )\n            END IF\n  130    CONTINUE\n      ELSE IF( TYPE.EQ.'HB'.OR.TYPE.EQ.'TB' )THEN\n         DO 170 J = 1, N\n            IF( UPPER )THEN\n               KK = KL + 1\n               IBEG = MAX( 1, KL + 2 - J )\n               IF( UNIT )THEN\n                  IEND = KL\n               ELSE\n                  IEND = KL + 1\n               END IF\n            ELSE\n               KK = 1\n               IF( UNIT )THEN\n                  IBEG = 2\n               ELSE\n                  IBEG = 1\n               END IF\n               IEND = MIN( KL + 1, 1 + M - J )\n            END IF\n            DO 140 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  140       CONTINUE\n            DO 150 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I + J - KK, J )\n  150       CONTINUE\n            DO 160 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  160       CONTINUE\n            IF( SYM )THEN\n               JJ = KK + ( J - 1 )*LDA\n               AA( JJ ) = CMPLX( REAL( AA( JJ ) ), RROGUE )\n            END IF\n  170    CONTINUE\n      ELSE IF( TYPE.EQ.'HP'.OR.TYPE.EQ.'TP' )THEN\n         IOFF = 0\n         DO 190 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 180 I = IBEG, IEND\n               IOFF = IOFF + 1\n               AA( IOFF ) = A( I, J )\n               IF( I.EQ.J )THEN\n                  IF( UNIT )\n     $               AA( IOFF ) = ROGUE\n                  IF( SYM )\n     $               AA( IOFF ) = CMPLX( REAL( AA( IOFF ) ), RROGUE )\n               END IF\n  180       CONTINUE\n  190    CONTINUE\n      END IF\n      RETURN\n*\n*     End of CMAKE.\n*\n      END\n      SUBROUTINE CMVCH( TRANS, M, N, ALPHA, A, NMAX, X, INCX, BETA, Y,\n     $                  INCY, YT, G, YY, EPS, ERR, FATAL, NOUT, MV )\n*\n*  Checks the results of the computational tests.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ) )\n      REAL               RZERO, RONE\n      PARAMETER          ( RZERO = 0.0, RONE = 1.0 )\n*     .. Scalar Arguments ..\n      COMPLEX            ALPHA, BETA\n      REAL               EPS, ERR\n      INTEGER            INCX, INCY, M, N, NMAX, NOUT\n      LOGICAL            FATAL, MV\n      CHARACTER*1        TRANS\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, * ), X( * ), Y( * ), YT( * ), YY( * )\n      REAL               G( * )\n*     .. Local Scalars ..\n      COMPLEX            C\n      REAL               ERRI\n      INTEGER            I, INCXL, INCYL, IY, J, JX, KX, KY, ML, NL\n      LOGICAL            CTRAN, TRAN\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, AIMAG, CONJG, MAX, REAL, SQRT\n*     .. Statement Functions ..\n      REAL               ABS1\n*     .. Statement Function definitions ..\n      ABS1( C ) = ABS( REAL( C ) ) + ABS( AIMAG( C ) )\n*     .. Executable Statements ..\n      TRAN = TRANS.EQ.'T'\n      CTRAN = TRANS.EQ.'C'\n      IF( TRAN.OR.CTRAN )THEN\n         ML = N\n         NL = M\n      ELSE\n         ML = M\n         NL = N\n      END IF\n      IF( INCX.LT.0 )THEN\n         KX = NL\n         INCXL = -1\n      ELSE\n         KX = 1\n         INCXL = 1\n      END IF\n      IF( INCY.LT.0 )THEN\n         KY = ML\n         INCYL = -1\n      ELSE\n         KY = 1\n         INCYL = 1\n      END IF\n*\n*     Compute expected result in YT using data in A, X and Y.\n*     Compute gauges in G.\n*\n      IY = KY\n      DO 40 I = 1, ML\n         YT( IY ) = ZERO\n         G( IY ) = RZERO\n         JX = KX\n         IF( TRAN )THEN\n            DO 10 J = 1, NL\n               YT( IY ) = YT( IY ) + A( J, I )*X( JX )\n               G( IY ) = G( IY ) + ABS1( A( J, I ) )*ABS1( X( JX ) )\n               JX = JX + INCXL\n   10       CONTINUE\n         ELSE IF( CTRAN )THEN\n            DO 20 J = 1, NL\n               YT( IY ) = YT( IY ) + CONJG( A( J, I ) )*X( JX )\n               G( IY ) = G( IY ) + ABS1( A( J, I ) )*ABS1( X( JX ) )\n               JX = JX + INCXL\n   20       CONTINUE\n         ELSE\n            DO 30 J = 1, NL\n               YT( IY ) = YT( IY ) + A( I, J )*X( JX )\n               G( IY ) = G( IY ) + ABS1( A( I, J ) )*ABS1( X( JX ) )\n               JX = JX + INCXL\n   30       CONTINUE\n         END IF\n         YT( IY ) = ALPHA*YT( IY ) + BETA*Y( IY )\n         G( IY ) = ABS1( ALPHA )*G( IY ) + ABS1( BETA )*ABS1( Y( IY ) )\n         IY = IY + INCYL\n   40 CONTINUE\n*\n*     Compute the error ratio for this result.\n*\n      ERR = ZERO\n      DO 50 I = 1, ML\n         ERRI = ABS( YT( I ) - YY( 1 + ( I - 1 )*ABS( INCY ) ) )/EPS\n         IF( G( I ).NE.RZERO )\n     $      ERRI = ERRI/G( I )\n         ERR = MAX( ERR, ERRI )\n         IF( ERR*SQRT( EPS ).GE.RONE )\n     $      GO TO 60\n   50 CONTINUE\n*     If the loop completes, all results are at least half accurate.\n      GO TO 80\n*\n*     Report fatal error.\n*\n   60 FATAL = .TRUE.\n      WRITE( NOUT, FMT = 9999 )\n      DO 70 I = 1, ML\n         IF( MV )THEN\n            WRITE( NOUT, FMT = 9998 )I, YT( I ),\n     $         YY( 1 + ( I - 1 )*ABS( INCY ) )\n         ELSE\n            WRITE( NOUT, FMT = 9998 )I,\n     $         YY( 1 + ( I - 1 )*ABS( INCY ) ), YT( I )\n         END IF\n   70 CONTINUE\n*\n   80 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ******* FATAL ERROR - COMPUTED RESULT IS LESS THAN HAL',\n     $      'F ACCURATE *******', /'                       EXPECTED RE',\n     $      'SULT                    COMPUTED RESULT' )\n 9998 FORMAT( 1X, I7, 2( '  (', G15.6, ',', G15.6, ')' ) )\n*\n*     End of CMVCH.\n*\n      END\n      LOGICAL FUNCTION LCE( RI, RJ, LR )\n*\n*  Tests if two arrays are identical.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LR\n*     .. Array Arguments ..\n      COMPLEX            RI( * ), RJ( * )\n*     .. Local Scalars ..\n      INTEGER            I\n*     .. Executable Statements ..\n      DO 10 I = 1, LR\n         IF( RI( I ).NE.RJ( I ) )\n     $      GO TO 20\n   10 CONTINUE\n      LCE = .TRUE.\n      GO TO 30\n   20 CONTINUE\n      LCE = .FALSE.\n   30 RETURN\n*\n*     End of LCE.\n*\n      END\n      LOGICAL FUNCTION LCERES( TYPE, UPLO, M, N, AA, AS, LDA )\n*\n*  Tests if selected elements in two arrays are equal.\n*\n*  TYPE is 'GE', 'HE' or 'HP'.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LDA, M, N\n      CHARACTER*1        UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      COMPLEX            AA( LDA, * ), AS( LDA, * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J\n      LOGICAL            UPPER\n*     .. Executable Statements ..\n      UPPER = UPLO.EQ.'U'\n      IF( TYPE.EQ.'GE' )THEN\n         DO 20 J = 1, N\n            DO 10 I = M + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   10       CONTINUE\n   20    CONTINUE\n      ELSE IF( TYPE.EQ.'HE' )THEN\n         DO 50 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 30 I = 1, IBEG - 1\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   30       CONTINUE\n            DO 40 I = IEND + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   40       CONTINUE\n   50    CONTINUE\n      END IF\n*\n      LCERES = .TRUE.\n      GO TO 80\n   70 CONTINUE\n      LCERES = .FALSE.\n   80 RETURN\n*\n*     End of LCERES.\n*\n      END\n      COMPLEX FUNCTION CBEG( RESET )\n*\n*  Generates complex numbers as pairs of random numbers uniformly\n*  distributed between -0.5 and 0.5.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      LOGICAL            RESET\n*     .. Local Scalars ..\n      INTEGER            I, IC, J, MI, MJ\n*     .. Save statement ..\n      SAVE               I, IC, J, MI, MJ\n*     .. Intrinsic Functions ..\n      INTRINSIC          CMPLX\n*     .. Executable Statements ..\n      IF( RESET )THEN\n*        Initialize local variables.\n         MI = 891\n         MJ = 457\n         I = 7\n         J = 7\n         IC = 0\n         RESET = .FALSE.\n      END IF\n*\n*     The sequence of values of I or J is bounded between 1 and 999.\n*     If initial I or J = 1,2,3,6,7 or 9, the period will be 50.\n*     If initial I or J = 4 or 8, the period will be 25.\n*     If initial I or J = 5, the period will be 10.\n*     IC is used to break up the period by skipping 1 value of I or J\n*     in 6.\n*\n      IC = IC + 1\n   10 I = I*MI\n      J = J*MJ\n      I = I - 1000*( I/1000 )\n      J = J - 1000*( J/1000 )\n      IF( IC.GE.5 )THEN\n         IC = 0\n         GO TO 10\n      END IF\n      CBEG = CMPLX( ( I - 500 )/1001.0, ( J - 500 )/1001.0 )\n      RETURN\n*\n*     End of CBEG.\n*\n      END\n      REAL FUNCTION SDIFF( X, Y )\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*\n*     .. Scalar Arguments ..\n      REAL               X, Y\n*     .. Executable Statements ..\n      SDIFF = X - Y\n      RETURN\n*\n*     End of SDIFF.\n*\n      END\n      SUBROUTINE CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n*  Tests whether XERBLA has detected an error when it should.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Executable Statements ..\n      IF( .NOT.LERR )THEN\n         WRITE( NOUT, FMT = 9999 )INFOT, SRNAMT\n         OK = .FALSE.\n      END IF\n      LERR = .FALSE.\n      RETURN\n*\n 9999 FORMAT( ' ***** ILLEGAL VALUE OF PARAMETER NUMBER ', I2, ' NOT D',\n     $      'ETECTED BY ', A6, ' *****' )\n*\n*     End of CHKXER.\n*\n      END\n      SUBROUTINE XERBLA( SRNAME, INFO )\n*\n*  This is a special version of XERBLA to be used only as part of\n*  the test program for testing error exits from the Level 2 BLAS\n*  routines.\n*\n*  XERBLA  is an error handler for the Level 2 BLAS routines.\n*\n*  It is called by the Level 2 BLAS routines if an input parameter is\n*  invalid.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFO\n      CHARACTER*6        SRNAME\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUT, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Executable Statements ..\n      LERR = .TRUE.\n      IF( INFO.NE.INFOT )THEN\n         IF( INFOT.NE.0 )THEN\n            WRITE( NOUT, FMT = 9999 )INFO, INFOT\n         ELSE\n            WRITE( NOUT, FMT = 9997 )INFO\n         END IF\n         OK = .FALSE.\n      END IF\n      IF( SRNAME.NE.SRNAMT )THEN\n         WRITE( NOUT, FMT = 9998 )SRNAME, SRNAMT\n         OK = .FALSE.\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6, ' INSTEAD',\n     $      ' OF ', I2, ' *******' )\n 9998 FORMAT( ' ******* XERBLA WAS CALLED WITH SRNAME = ', A6, ' INSTE',\n     $      'AD OF ', A6, ' *******' )\n 9997 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6,\n     $      ' *******' )\n*\n*     End of XERBLA\n*\n      END\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/testing/cblat3.f",
    "content": "*> \\brief \\b CBLAT3\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM CBLAT3\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> Test program for the COMPLEX          Level 3 Blas.\n*>\n*> The program must be driven by a short data file. The first 14 records\n*> of the file are read using list-directed input, the last 9 records\n*> are read using the format ( A6, L2 ). An annotated example of a data\n*> file can be obtained by deleting the first 3 characters from the\n*> following 23 lines:\n*> 'cblat3.out'      NAME OF SUMMARY OUTPUT FILE\n*> 6                 UNIT NUMBER OF SUMMARY FILE\n*> 'CBLAT3.SNAP'     NAME OF SNAPSHOT OUTPUT FILE\n*> -1                UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0)\n*> F        LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD.\n*> F        LOGICAL FLAG, T TO STOP ON FAILURES.\n*> T        LOGICAL FLAG, T TO TEST ERROR EXITS.\n*> 16.0     THRESHOLD VALUE OF TEST RATIO\n*> 6                 NUMBER OF VALUES OF N\n*> 0 1 2 3 5 9       VALUES OF N\n*> 3                 NUMBER OF VALUES OF ALPHA\n*> (0.0,0.0) (1.0,0.0) (0.7,-0.9)       VALUES OF ALPHA\n*> 3                 NUMBER OF VALUES OF BETA\n*> (0.0,0.0) (1.0,0.0) (1.3,-1.1)       VALUES OF BETA\n*> CGEMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CHEMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CSYMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CTRMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CTRSM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CHERK  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CSYRK  T PUT F FOR NO TEST. SAME COLUMNS.\n*> CHER2K T PUT F FOR NO TEST. SAME COLUMNS.\n*> CSYR2K T PUT F FOR NO TEST. SAME COLUMNS.\n*>\n*> Further Details\n*> ===============\n*>\n*> See:\n*>\n*>    Dongarra J. J., Du Croz J. J., Duff I. S. and Hammarling S.\n*>    A Set of Level 3 Basic Linear Algebra Subprograms.\n*>\n*>    Technical Memorandum No.88 (Revision 1), Mathematics and\n*>    Computer Science Division, Argonne National Laboratory, 9700\n*>    South Cass Avenue, Argonne, Illinois 60439, US.\n*>\n*> -- Written on 8-February-1989.\n*>    Jack Dongarra, Argonne National Laboratory.\n*>    Iain Duff, AERE Harwell.\n*>    Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*>    Sven Hammarling, Numerical Algorithms Group Ltd.\n*>\n*>    10-9-00:  Change STATUS='NEW' to 'UNKNOWN' so that the testers\n*>              can be run multiple times without deleting generated\n*>              output files (susan)\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup complex_blas_testing\n*\n*  =====================================================================\n      PROGRAM CBLAT3\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER            NIN\n      PARAMETER          ( NIN = 5 )\n      INTEGER            NSUBS\n      PARAMETER          ( NSUBS = 9 )\n      COMPLEX            ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), ONE = ( 1.0, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n      INTEGER            NMAX\n      PARAMETER          ( NMAX = 65 )\n      INTEGER            NIDMAX, NALMAX, NBEMAX\n      PARAMETER          ( NIDMAX = 9, NALMAX = 7, NBEMAX = 7 )\n*     .. Local Scalars ..\n      REAL               EPS, ERR, THRESH\n      INTEGER            I, ISNUM, J, N, NALF, NBET, NIDIM, NOUT, NTRA\n      LOGICAL            FATAL, LTESTT, REWI, SAME, SFATAL, TRACE,\n     $                   TSTERR\n      CHARACTER*1        TRANSA, TRANSB\n      CHARACTER*6        SNAMET\n      CHARACTER*32       SNAPS, SUMMRY\n*     .. Local Arrays ..\n      COMPLEX            AA( NMAX*NMAX ), AB( NMAX, 2*NMAX ),\n     $                   ALF( NALMAX ), AS( NMAX*NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBEMAX ),\n     $                   BS( NMAX*NMAX ), C( NMAX, NMAX ),\n     $                   CC( NMAX*NMAX ), CS( NMAX*NMAX ), CT( NMAX ),\n     $                   W( 2*NMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDMAX )\n      LOGICAL            LTEST( NSUBS )\n      CHARACTER*6        SNAMES( NSUBS )\n*     .. External Functions ..\n      REAL               SDIFF\n      LOGICAL            LCE\n      EXTERNAL           SDIFF, LCE\n*     .. External Subroutines ..\n      EXTERNAL           CCHK1, CCHK2, CCHK3, CCHK4, CCHK5, CCHKE, CMMCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Data statements ..\n      DATA               SNAMES/'CGEMM ', 'CHEMM ', 'CSYMM ', 'CTRMM ',\n     $                   'CTRSM ', 'CHERK ', 'CSYRK ', 'CHER2K',\n     $                   'CSYR2K'/\n*     .. Executable Statements ..\n*\n*     Read name and unit number for summary output file and open file.\n*\n      READ( NIN, FMT = * )SUMMRY\n      READ( NIN, FMT = * )NOUT\n      OPEN( NOUT, FILE = SUMMRY )\n      NOUTC = NOUT\n*\n*     Read name and unit number for snapshot output file and open file.\n*\n      READ( NIN, FMT = * )SNAPS\n      READ( NIN, FMT = * )NTRA\n      TRACE = NTRA.GE.0\n      IF( TRACE )THEN\n         OPEN( NTRA, FILE = SNAPS )\n      END IF\n*     Read the flag that directs rewinding of the snapshot file.\n      READ( NIN, FMT = * )REWI\n      REWI = REWI.AND.TRACE\n*     Read the flag that directs stopping on any failure.\n      READ( NIN, FMT = * )SFATAL\n*     Read the flag that indicates whether error exits are to be tested.\n      READ( NIN, FMT = * )TSTERR\n*     Read the threshold value of the test ratio\n      READ( NIN, FMT = * )THRESH\n*\n*     Read and check the parameter values for the tests.\n*\n*     Values of N\n      READ( NIN, FMT = * )NIDIM\n      IF( NIDIM.LT.1.OR.NIDIM.GT.NIDMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'N', NIDMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( IDIM( I ), I = 1, NIDIM )\n      DO 10 I = 1, NIDIM\n         IF( IDIM( I ).LT.0.OR.IDIM( I ).GT.NMAX )THEN\n            WRITE( NOUT, FMT = 9996 )NMAX\n            GO TO 220\n         END IF\n   10 CONTINUE\n*     Values of ALPHA\n      READ( NIN, FMT = * )NALF\n      IF( NALF.LT.1.OR.NALF.GT.NALMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'ALPHA', NALMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( ALF( I ), I = 1, NALF )\n*     Values of BETA\n      READ( NIN, FMT = * )NBET\n      IF( NBET.LT.1.OR.NBET.GT.NBEMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'BETA', NBEMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( BET( I ), I = 1, NBET )\n*\n*     Report values of parameters.\n*\n      WRITE( NOUT, FMT = 9995 )\n      WRITE( NOUT, FMT = 9994 )( IDIM( I ), I = 1, NIDIM )\n      WRITE( NOUT, FMT = 9993 )( ALF( I ), I = 1, NALF )\n      WRITE( NOUT, FMT = 9992 )( BET( I ), I = 1, NBET )\n      IF( .NOT.TSTERR )THEN\n         WRITE( NOUT, FMT = * )\n         WRITE( NOUT, FMT = 9984 )\n      END IF\n      WRITE( NOUT, FMT = * )\n      WRITE( NOUT, FMT = 9999 )THRESH\n      WRITE( NOUT, FMT = * )\n*\n*     Read names of subroutines and flags which indicate\n*     whether they are to be tested.\n*\n      DO 20 I = 1, NSUBS\n         LTEST( I ) = .FALSE.\n   20 CONTINUE\n   30 READ( NIN, FMT = 9988, END = 60 )SNAMET, LTESTT\n      DO 40 I = 1, NSUBS\n         IF( SNAMET.EQ.SNAMES( I ) )\n     $      GO TO 50\n   40 CONTINUE\n      WRITE( NOUT, FMT = 9990 )SNAMET\n      STOP\n   50 LTEST( I ) = LTESTT\n      GO TO 30\n*\n   60 CONTINUE\n      CLOSE ( NIN )\n*\n*     Compute EPS (the machine precision).\n*\n      EPS = EPSILON(RZERO)\n      WRITE( NOUT, FMT = 9998 )EPS\n*\n*     Check the reliability of CMMCH using exact data.\n*\n      N = MIN( 32, NMAX )\n      DO 100 J = 1, N\n         DO 90 I = 1, N\n            AB( I, J ) = MAX( I - J + 1, 0 )\n   90    CONTINUE\n         AB( J, NMAX + 1 ) = J\n         AB( 1, NMAX + J ) = J\n         C( J, 1 ) = ZERO\n  100 CONTINUE\n      DO 110 J = 1, N\n         CC( J ) = J*( ( J + 1 )*J )/2 - ( ( J + 1 )*J*( J - 1 ) )/3\n  110 CONTINUE\n*     CC holds the exact result. On exit from CMMCH CT holds\n*     the result computed by CMMCH.\n      TRANSA = 'N'\n      TRANSB = 'N'\n      CALL CMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LCE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      TRANSB = 'C'\n      CALL CMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LCE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      DO 120 J = 1, N\n         AB( J, NMAX + 1 ) = N - J + 1\n         AB( 1, NMAX + J ) = N - J + 1\n  120 CONTINUE\n      DO 130 J = 1, N\n         CC( N - J + 1 ) = J*( ( J + 1 )*J )/2 -\n     $                     ( ( J + 1 )*J*( J - 1 ) )/3\n  130 CONTINUE\n      TRANSA = 'C'\n      TRANSB = 'N'\n      CALL CMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LCE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      TRANSB = 'C'\n      CALL CMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LCE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n*\n*     Test each subroutine in turn.\n*\n      DO 200 ISNUM = 1, NSUBS\n         WRITE( NOUT, FMT = * )\n         IF( .NOT.LTEST( ISNUM ) )THEN\n*           Subprogram is not to be tested.\n            WRITE( NOUT, FMT = 9987 )SNAMES( ISNUM )\n         ELSE\n            SRNAMT = SNAMES( ISNUM )\n*           Test error exits.\n            IF( TSTERR )THEN\n               CALL CCHKE( ISNUM, SNAMES( ISNUM ), NOUT )\n               WRITE( NOUT, FMT = * )\n            END IF\n*           Test computations.\n            INFOT = 0\n            OK = .TRUE.\n            FATAL = .FALSE.\n            GO TO ( 140, 150, 150, 160, 160, 170, 170,\n     $              180, 180 )ISNUM\n*           Test CGEMM, 01.\n  140       CALL CCHK1( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test CHEMM, 02, CSYMM, 03.\n  150       CALL CCHK2( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test CTRMM, 04, CTRSM, 05.\n  160       CALL CCHK3( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NMAX, AB,\n     $                  AA, AS, AB( 1, NMAX + 1 ), BB, BS, CT, G, C )\n            GO TO 190\n*           Test CHERK, 06, CSYRK, 07.\n  170       CALL CCHK4( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test CHER2K, 08, CSYR2K, 09.\n  180       CALL CCHK5( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, BB, BS, C, CC, CS, CT, G, W )\n            GO TO 190\n*\n  190       IF( FATAL.AND.SFATAL )\n     $         GO TO 210\n         END IF\n  200 CONTINUE\n      WRITE( NOUT, FMT = 9986 )\n      GO TO 230\n*\n  210 CONTINUE\n      WRITE( NOUT, FMT = 9985 )\n      GO TO 230\n*\n  220 CONTINUE\n      WRITE( NOUT, FMT = 9991 )\n*\n  230 CONTINUE\n      IF( TRACE )\n     $   CLOSE ( NTRA )\n      CLOSE ( NOUT )\n      STOP\n*\n 9999 FORMAT( ' ROUTINES PASS COMPUTATIONAL TESTS IF TEST RATIO IS LES',\n     $      'S THAN', F8.2 )\n 9998 FORMAT( ' RELATIVE MACHINE PRECISION IS TAKEN TO BE', 1P, E9.1 )\n 9997 FORMAT( ' NUMBER OF VALUES OF ', A, ' IS LESS THAN 1 OR GREATER ',\n     $      'THAN ', I2 )\n 9996 FORMAT( ' VALUE OF N IS LESS THAN 0 OR GREATER THAN ', I2 )\n 9995 FORMAT( ' TESTS OF THE COMPLEX          LEVEL 3 BLAS', //' THE F',\n     $      'OLLOWING PARAMETER VALUES WILL BE USED:' )\n 9994 FORMAT( '   FOR N              ', 9I6 )\n 9993 FORMAT( '   FOR ALPHA          ',\n     $      7( '(', F4.1, ',', F4.1, ')  ', : ) )\n 9992 FORMAT( '   FOR BETA           ',\n     $      7( '(', F4.1, ',', F4.1, ')  ', : ) )\n 9991 FORMAT( ' AMEND DATA FILE OR INCREASE ARRAY SIZES IN PROGRAM',\n     $      /' ******* TESTS ABANDONED *******' )\n 9990 FORMAT( ' SUBPROGRAM NAME ', A6, ' NOT RECOGNIZED', /' ******* T',\n     $      'ESTS ABANDONED *******' )\n 9989 FORMAT( ' ERROR IN CMMCH -  IN-LINE DOT PRODUCTS ARE BEING EVALU',\n     $      'ATED WRONGLY.', /' CMMCH WAS CALLED WITH TRANSA = ', A1,\n     $      ' AND TRANSB = ', A1, /' AND RETURNED SAME = ', L1, ' AND ',\n     $      'ERR = ', F12.3, '.', /' THIS MAY BE DUE TO FAULTS IN THE ',\n     $      'ARITHMETIC OR THE COMPILER.', /' ******* TESTS ABANDONED ',\n     $      '*******' )\n 9988 FORMAT( A6, L2 )\n 9987 FORMAT( 1X, A6, ' WAS NOT TESTED' )\n 9986 FORMAT( /' END OF TESTS' )\n 9985 FORMAT( /' ******* FATAL ERROR - TESTS ABANDONED *******' )\n 9984 FORMAT( ' ERROR-EXITS WILL NOT BE TESTED' )\n*\n*     End of CBLAT3.\n*\n      END\n      SUBROUTINE CCHK1( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests CGEMM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, ALS, BETA, BLS\n      REAL               ERR, ERRMAX\n      INTEGER            I, IA, IB, ICA, ICB, IK, IM, IN, K, KS, LAA,\n     $                   LBB, LCC, LDA, LDAS, LDB, LDBS, LDC, LDCS, M,\n     $                   MA, MB, MS, N, NA, NARGS, NB, NC, NS\n      LOGICAL            NULL, RESET, SAME, TRANA, TRANB\n      CHARACTER*1        TRANAS, TRANBS, TRANSA, TRANSB\n      CHARACTER*3        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CGEMM, CMAKE, CMMCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'NTC'/\n*     .. Executable Statements ..\n*\n      NARGS = 13\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 110 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 100 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDC to 1 more than minimum value if room.\n            LDC = M\n            IF( LDC.LT.NMAX )\n     $         LDC = LDC + 1\n*           Skip tests if not enough room.\n            IF( LDC.GT.NMAX )\n     $         GO TO 100\n            LCC = LDC*N\n            NULL = N.LE.0.OR.M.LE.0\n*\n            DO 90 IK = 1, NIDIM\n               K = IDIM( IK )\n*\n               DO 80 ICA = 1, 3\n                  TRANSA = ICH( ICA: ICA )\n                  TRANA = TRANSA.EQ.'T'.OR.TRANSA.EQ.'C'\n*\n                  IF( TRANA )THEN\n                     MA = K\n                     NA = M\n                  ELSE\n                     MA = M\n                     NA = K\n                  END IF\n*                 Set LDA to 1 more than minimum value if room.\n                  LDA = MA\n                  IF( LDA.LT.NMAX )\n     $               LDA = LDA + 1\n*                 Skip tests if not enough room.\n                  IF( LDA.GT.NMAX )\n     $               GO TO 80\n                  LAA = LDA*NA\n*\n*                 Generate the matrix A.\n*\n                  CALL CMAKE( 'GE', ' ', ' ', MA, NA, A, NMAX, AA, LDA,\n     $                        RESET, ZERO )\n*\n                  DO 70 ICB = 1, 3\n                     TRANSB = ICH( ICB: ICB )\n                     TRANB = TRANSB.EQ.'T'.OR.TRANSB.EQ.'C'\n*\n                     IF( TRANB )THEN\n                        MB = N\n                        NB = K\n                     ELSE\n                        MB = K\n                        NB = N\n                     END IF\n*                    Set LDB to 1 more than minimum value if room.\n                     LDB = MB\n                     IF( LDB.LT.NMAX )\n     $                  LDB = LDB + 1\n*                    Skip tests if not enough room.\n                     IF( LDB.GT.NMAX )\n     $                  GO TO 70\n                     LBB = LDB*NB\n*\n*                    Generate the matrix B.\n*\n                     CALL CMAKE( 'GE', ' ', ' ', MB, NB, B, NMAX, BB,\n     $                           LDB, RESET, ZERO )\n*\n                     DO 60 IA = 1, NALF\n                        ALPHA = ALF( IA )\n*\n                        DO 50 IB = 1, NBET\n                           BETA = BET( IB )\n*\n*                          Generate the matrix C.\n*\n                           CALL CMAKE( 'GE', ' ', ' ', M, N, C, NMAX,\n     $                                 CC, LDC, RESET, ZERO )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           TRANAS = TRANSA\n                           TRANBS = TRANSB\n                           MS = M\n                           NS = N\n                           KS = K\n                           ALS = ALPHA\n                           DO 10 I = 1, LAA\n                              AS( I ) = AA( I )\n   10                      CONTINUE\n                           LDAS = LDA\n                           DO 20 I = 1, LBB\n                              BS( I ) = BB( I )\n   20                      CONTINUE\n                           LDBS = LDB\n                           BLS = BETA\n                           DO 30 I = 1, LCC\n                              CS( I ) = CC( I )\n   30                      CONTINUE\n                           LDCS = LDC\n*\n*                          Call the subroutine.\n*\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                        TRANSA, TRANSB, M, N, K, ALPHA, LDA, LDB,\n     $                        BETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL CGEMM( TRANSA, TRANSB, M, N, K, ALPHA,\n     $                                 AA, LDA, BB, LDB, BETA, CC, LDC )\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9994 )\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = TRANSA.EQ.TRANAS\n                           ISAME( 2 ) = TRANSB.EQ.TRANBS\n                           ISAME( 3 ) = MS.EQ.M\n                           ISAME( 4 ) = NS.EQ.N\n                           ISAME( 5 ) = KS.EQ.K\n                           ISAME( 6 ) = ALS.EQ.ALPHA\n                           ISAME( 7 ) = LCE( AS, AA, LAA )\n                           ISAME( 8 ) = LDAS.EQ.LDA\n                           ISAME( 9 ) = LCE( BS, BB, LBB )\n                           ISAME( 10 ) = LDBS.EQ.LDB\n                           ISAME( 11 ) = BLS.EQ.BETA\n                           IF( NULL )THEN\n                              ISAME( 12 ) = LCE( CS, CC, LCC )\n                           ELSE\n                              ISAME( 12 ) = LCERES( 'GE', ' ', M, N, CS,\n     $                                      CC, LDC )\n                           END IF\n                           ISAME( 13 ) = LDCS.EQ.LDC\n*\n*                          If data was incorrectly changed, report\n*                          and return.\n*\n                           SAME = .TRUE.\n                           DO 40 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   40                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n*\n*                             Check the result.\n*\n                              CALL CMMCH( TRANSA, TRANSB, M, N, K,\n     $                                    ALPHA, A, NMAX, B, NMAX, BETA,\n     $                                    C, NMAX, CT, G, CC, LDC, EPS,\n     $                                    ERR, FATAL, NOUT, .TRUE. )\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 120\n                           END IF\n*\n   50                   CONTINUE\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, TRANSA, TRANSB, M, N, K,\n     $   ALPHA, LDA, LDB, BETA, LDC\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',''', A1, ''',',\n     $      3( I3, ',' ), '(', F4.1, ',', F4.1, '), A,', I3, ', B,', I3,\n     $      ',(', F4.1, ',', F4.1, '), C,', I3, ').' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK1.\n*\n      END\n      SUBROUTINE CCHK2( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests CHEMM and CSYMM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, ALS, BETA, BLS\n      REAL               ERR, ERRMAX\n      INTEGER            I, IA, IB, ICS, ICU, IM, IN, LAA, LBB, LCC,\n     $                   LDA, LDAS, LDB, LDBS, LDC, LDCS, M, MS, N, NA,\n     $                   NARGS, NC, NS\n      LOGICAL            CONJ, LEFT, NULL, RESET, SAME\n      CHARACTER*1        SIDE, SIDES, UPLO, UPLOS\n      CHARACTER*2        ICHS, ICHU\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CHEMM, CMAKE, CMMCH, CSYMM\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHS/'LR'/, ICHU/'UL'/\n*     .. Executable Statements ..\n      CONJ = SNAME( 2: 3 ).EQ.'HE'\n*\n      NARGS = 12\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 100 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 90 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDC to 1 more than minimum value if room.\n            LDC = M\n            IF( LDC.LT.NMAX )\n     $         LDC = LDC + 1\n*           Skip tests if not enough room.\n            IF( LDC.GT.NMAX )\n     $         GO TO 90\n            LCC = LDC*N\n            NULL = N.LE.0.OR.M.LE.0\n*           Set LDB to 1 more than minimum value if room.\n            LDB = M\n            IF( LDB.LT.NMAX )\n     $         LDB = LDB + 1\n*           Skip tests if not enough room.\n            IF( LDB.GT.NMAX )\n     $         GO TO 90\n            LBB = LDB*N\n*\n*           Generate the matrix B.\n*\n            CALL CMAKE( 'GE', ' ', ' ', M, N, B, NMAX, BB, LDB, RESET,\n     $                  ZERO )\n*\n            DO 80 ICS = 1, 2\n               SIDE = ICHS( ICS: ICS )\n               LEFT = SIDE.EQ.'L'\n*\n               IF( LEFT )THEN\n                  NA = M\n               ELSE\n                  NA = N\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = NA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 80\n               LAA = LDA*NA\n*\n               DO 70 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n*\n*                 Generate the hermitian or symmetric matrix A.\n*\n                  CALL CMAKE( SNAME( 2: 3 ), UPLO, ' ', NA, NA, A, NMAX,\n     $                        AA, LDA, RESET, ZERO )\n*\n                  DO 60 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n                     DO 50 IB = 1, NBET\n                        BETA = BET( IB )\n*\n*                       Generate the matrix C.\n*\n                        CALL CMAKE( 'GE', ' ', ' ', M, N, C, NMAX, CC,\n     $                              LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the\n*                       subroutine.\n*\n                        SIDES = SIDE\n                        UPLOS = UPLO\n                        MS = M\n                        NS = N\n                        ALS = ALPHA\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        DO 20 I = 1, LBB\n                           BS( I ) = BB( I )\n   20                   CONTINUE\n                        LDBS = LDB\n                        BLS = BETA\n                        DO 30 I = 1, LCC\n                           CS( I ) = CC( I )\n   30                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9995 )NC, SNAME, SIDE,\n     $                     UPLO, M, N, ALPHA, LDA, LDB, BETA, LDC\n                        IF( REWI )\n     $                     REWIND NTRA\n                        IF( CONJ )THEN\n                           CALL CHEMM( SIDE, UPLO, M, N, ALPHA, AA, LDA,\n     $                                 BB, LDB, BETA, CC, LDC )\n                        ELSE\n                           CALL CSYMM( SIDE, UPLO, M, N, ALPHA, AA, LDA,\n     $                                 BB, LDB, BETA, CC, LDC )\n                        END IF\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9994 )\n                           FATAL = .TRUE.\n                           GO TO 110\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = SIDES.EQ.SIDE\n                        ISAME( 2 ) = UPLOS.EQ.UPLO\n                        ISAME( 3 ) = MS.EQ.M\n                        ISAME( 4 ) = NS.EQ.N\n                        ISAME( 5 ) = ALS.EQ.ALPHA\n                        ISAME( 6 ) = LCE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        ISAME( 8 ) = LCE( BS, BB, LBB )\n                        ISAME( 9 ) = LDBS.EQ.LDB\n                        ISAME( 10 ) = BLS.EQ.BETA\n                        IF( NULL )THEN\n                           ISAME( 11 ) = LCE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 11 ) = LCERES( 'GE', ' ', M, N, CS,\n     $                                   CC, LDC )\n                        END IF\n                        ISAME( 12 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 110\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result.\n*\n                           IF( LEFT )THEN\n                              CALL CMMCH( 'N', 'N', M, N, M, ALPHA, A,\n     $                                    NMAX, B, NMAX, BETA, C, NMAX,\n     $                                    CT, G, CC, LDC, EPS, ERR,\n     $                                    FATAL, NOUT, .TRUE. )\n                           ELSE\n                              CALL CMMCH( 'N', 'N', M, N, N, ALPHA, B,\n     $                                    NMAX, A, NMAX, BETA, C, NMAX,\n     $                                    CT, G, CC, LDC, EPS, ERR,\n     $                                    FATAL, NOUT, .TRUE. )\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and\n*                          return.\n                           IF( FATAL )\n     $                        GO TO 110\n                        END IF\n*\n   50                CONTINUE\n*\n   60             CONTINUE\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 120\n*\n  110 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, SIDE, UPLO, M, N, ALPHA, LDA,\n     $   LDB, BETA, LDC\n*\n  120 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      '(', F4.1, ',', F4.1, '), A,', I3, ', B,', I3, ',(', F4.1,\n     $      ',', F4.1, '), C,', I3, ')    .' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK2.\n*\n      END\n      SUBROUTINE CCHK3( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NMAX, A, AA, AS,\n     $                  B, BB, BS, CT, G, C )\n*\n*  Tests CTRMM and CTRSM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), ONE = ( 1.0, 0.0 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            NALF, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CT( NMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, ALS\n      REAL               ERR, ERRMAX\n      INTEGER            I, IA, ICD, ICS, ICT, ICU, IM, IN, J, LAA, LBB,\n     $                   LDA, LDAS, LDB, LDBS, M, MS, N, NA, NARGS, NC,\n     $                   NS\n      LOGICAL            LEFT, NULL, RESET, SAME\n      CHARACTER*1        DIAG, DIAGS, SIDE, SIDES, TRANAS, TRANSA, UPLO,\n     $                   UPLOS\n      CHARACTER*2        ICHD, ICHS, ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CMAKE, CMMCH, CTRMM, CTRSM\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHU/'UL'/, ICHT/'NTC'/, ICHD/'UN'/, ICHS/'LR'/\n*     .. Executable Statements ..\n*\n      NARGS = 11\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*     Set up zero matrix for CMMCH.\n      DO 20 J = 1, NMAX\n         DO 10 I = 1, NMAX\n            C( I, J ) = ZERO\n   10    CONTINUE\n   20 CONTINUE\n*\n      DO 140 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 130 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDB to 1 more than minimum value if room.\n            LDB = M\n            IF( LDB.LT.NMAX )\n     $         LDB = LDB + 1\n*           Skip tests if not enough room.\n            IF( LDB.GT.NMAX )\n     $         GO TO 130\n            LBB = LDB*N\n            NULL = M.LE.0.OR.N.LE.0\n*\n            DO 120 ICS = 1, 2\n               SIDE = ICHS( ICS: ICS )\n               LEFT = SIDE.EQ.'L'\n               IF( LEFT )THEN\n                  NA = M\n               ELSE\n                  NA = N\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = NA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 130\n               LAA = LDA*NA\n*\n               DO 110 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n*\n                  DO 100 ICT = 1, 3\n                     TRANSA = ICHT( ICT: ICT )\n*\n                     DO 90 ICD = 1, 2\n                        DIAG = ICHD( ICD: ICD )\n*\n                        DO 80 IA = 1, NALF\n                           ALPHA = ALF( IA )\n*\n*                          Generate the matrix A.\n*\n                           CALL CMAKE( 'TR', UPLO, DIAG, NA, NA, A,\n     $                                 NMAX, AA, LDA, RESET, ZERO )\n*\n*                          Generate the matrix B.\n*\n                           CALL CMAKE( 'GE', ' ', ' ', M, N, B, NMAX,\n     $                                 BB, LDB, RESET, ZERO )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           SIDES = SIDE\n                           UPLOS = UPLO\n                           TRANAS = TRANSA\n                           DIAGS = DIAG\n                           MS = M\n                           NS = N\n                           ALS = ALPHA\n                           DO 30 I = 1, LAA\n                              AS( I ) = AA( I )\n   30                      CONTINUE\n                           LDAS = LDA\n                           DO 40 I = 1, LBB\n                              BS( I ) = BB( I )\n   40                      CONTINUE\n                           LDBS = LDB\n*\n*                          Call the subroutine.\n*\n                           IF( SNAME( 4: 5 ).EQ.'MM' )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           SIDE, UPLO, TRANSA, DIAG, M, N, ALPHA,\n     $                           LDA, LDB\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CTRMM( SIDE, UPLO, TRANSA, DIAG, M,\n     $                                    N, ALPHA, AA, LDA, BB, LDB )\n                           ELSE IF( SNAME( 4: 5 ).EQ.'SM' )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           SIDE, UPLO, TRANSA, DIAG, M, N, ALPHA,\n     $                           LDA, LDB\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL CTRSM( SIDE, UPLO, TRANSA, DIAG, M,\n     $                                    N, ALPHA, AA, LDA, BB, LDB )\n                           END IF\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9994 )\n                              FATAL = .TRUE.\n                              GO TO 150\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = SIDES.EQ.SIDE\n                           ISAME( 2 ) = UPLOS.EQ.UPLO\n                           ISAME( 3 ) = TRANAS.EQ.TRANSA\n                           ISAME( 4 ) = DIAGS.EQ.DIAG\n                           ISAME( 5 ) = MS.EQ.M\n                           ISAME( 6 ) = NS.EQ.N\n                           ISAME( 7 ) = ALS.EQ.ALPHA\n                           ISAME( 8 ) = LCE( AS, AA, LAA )\n                           ISAME( 9 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 10 ) = LCE( BS, BB, LBB )\n                           ELSE\n                              ISAME( 10 ) = LCERES( 'GE', ' ', M, N, BS,\n     $                                      BB, LDB )\n                           END IF\n                           ISAME( 11 ) = LDBS.EQ.LDB\n*\n*                          If data was incorrectly changed, report and\n*                          return.\n*\n                           SAME = .TRUE.\n                           DO 50 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   50                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 150\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n                              IF( SNAME( 4: 5 ).EQ.'MM' )THEN\n*\n*                                Check the result.\n*\n                                 IF( LEFT )THEN\n                                    CALL CMMCH( TRANSA, 'N', M, N, M,\n     $                                          ALPHA, A, NMAX, B, NMAX,\n     $                                          ZERO, C, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .TRUE. )\n                                 ELSE\n                                    CALL CMMCH( 'N', TRANSA, M, N, N,\n     $                                          ALPHA, B, NMAX, A, NMAX,\n     $                                          ZERO, C, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .TRUE. )\n                                 END IF\n                              ELSE IF( SNAME( 4: 5 ).EQ.'SM' )THEN\n*\n*                                Compute approximation to original\n*                                matrix.\n*\n                                 DO 70 J = 1, N\n                                    DO 60 I = 1, M\n                                       C( I, J ) = BB( I + ( J - 1 )*\n     $                                             LDB )\n                                       BB( I + ( J - 1 )*LDB ) = ALPHA*\n     $                                    B( I, J )\n   60                               CONTINUE\n   70                            CONTINUE\n*\n                                 IF( LEFT )THEN\n                                    CALL CMMCH( TRANSA, 'N', M, N, M,\n     $                                          ONE, A, NMAX, C, NMAX,\n     $                                          ZERO, B, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .FALSE. )\n                                 ELSE\n                                    CALL CMMCH( 'N', TRANSA, M, N, N,\n     $                                          ONE, C, NMAX, A, NMAX,\n     $                                          ZERO, B, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .FALSE. )\n                                 END IF\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 150\n                           END IF\n*\n   80                   CONTINUE\n*\n   90                CONTINUE\n*\n  100             CONTINUE\n*\n  110          CONTINUE\n*\n  120       CONTINUE\n*\n  130    CONTINUE\n*\n  140 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 160\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, SIDE, UPLO, TRANSA, DIAG, M,\n     $   N, ALPHA, LDA, LDB\n*\n  160 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 4( '''', A1, ''',' ), 2( I3, ',' ),\n     $      '(', F4.1, ',', F4.1, '), A,', I3, ', B,', I3, ')         ',\n     $      '      .' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK3.\n*\n      END\n      SUBROUTINE CCHK4( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests CHERK and CSYRK.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ) )\n      REAL               RONE, RZERO\n      PARAMETER          ( RONE = 1.0, RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, ALS, BETA, BETS\n      REAL               ERR, ERRMAX, RALPHA, RALS, RBETA, RBETS\n      INTEGER            I, IA, IB, ICT, ICU, IK, IN, J, JC, JJ, K, KS,\n     $                   LAA, LCC, LDA, LDAS, LDC, LDCS, LJ, MA, N, NA,\n     $                   NARGS, NC, NS\n      LOGICAL            CONJ, NULL, RESET, SAME, TRAN, UPPER\n      CHARACTER*1        TRANS, TRANSS, TRANST, UPLO, UPLOS\n      CHARACTER*2        ICHT, ICHU\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CHERK, CMAKE, CMMCH, CSYRK\n*     .. Intrinsic Functions ..\n      INTRINSIC          CMPLX, MAX, REAL\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHT/'NC'/, ICHU/'UL'/\n*     .. Executable Statements ..\n      CONJ = SNAME( 2: 3 ).EQ.'HE'\n*\n      NARGS = 10\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 100 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDC to 1 more than minimum value if room.\n         LDC = N\n         IF( LDC.LT.NMAX )\n     $      LDC = LDC + 1\n*        Skip tests if not enough room.\n         IF( LDC.GT.NMAX )\n     $      GO TO 100\n         LCC = LDC*N\n*\n         DO 90 IK = 1, NIDIM\n            K = IDIM( IK )\n*\n            DO 80 ICT = 1, 2\n               TRANS = ICHT( ICT: ICT )\n               TRAN = TRANS.EQ.'C'\n               IF( TRAN.AND..NOT.CONJ )\n     $            TRANS = 'T'\n               IF( TRAN )THEN\n                  MA = K\n                  NA = N\n               ELSE\n                  MA = N\n                  NA = K\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = MA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 80\n               LAA = LDA*NA\n*\n*              Generate the matrix A.\n*\n               CALL CMAKE( 'GE', ' ', ' ', MA, NA, A, NMAX, AA, LDA,\n     $                     RESET, ZERO )\n*\n               DO 70 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n                  UPPER = UPLO.EQ.'U'\n*\n                  DO 60 IA = 1, NALF\n                     ALPHA = ALF( IA )\n                     IF( CONJ )THEN\n                        RALPHA = REAL( ALPHA )\n                        ALPHA = CMPLX( RALPHA, RZERO )\n                     END IF\n*\n                     DO 50 IB = 1, NBET\n                        BETA = BET( IB )\n                        IF( CONJ )THEN\n                           RBETA = REAL( BETA )\n                           BETA = CMPLX( RBETA, RZERO )\n                        END IF\n                        NULL = N.LE.0\n                        IF( CONJ )\n     $                     NULL = NULL.OR.( ( K.LE.0.OR.RALPHA.EQ.\n     $                            RZERO ).AND.RBETA.EQ.RONE )\n*\n*                       Generate the matrix C.\n*\n                        CALL CMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, C,\n     $                              NMAX, CC, LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        NS = N\n                        KS = K\n                        IF( CONJ )THEN\n                           RALS = RALPHA\n                        ELSE\n                           ALS = ALPHA\n                        END IF\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        IF( CONJ )THEN\n                           RBETS = RBETA\n                        ELSE\n                           BETS = BETA\n                        END IF\n                        DO 20 I = 1, LCC\n                           CS( I ) = CC( I )\n   20                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( CONJ )THEN\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO,\n     $                        TRANS, N, K, RALPHA, LDA, RBETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL CHERK( UPLO, TRANS, N, K, RALPHA, AA,\n     $                                 LDA, RBETA, CC, LDC )\n                        ELSE\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO,\n     $                        TRANS, N, K, ALPHA, LDA, BETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL CSYRK( UPLO, TRANS, N, K, ALPHA, AA,\n     $                                 LDA, BETA, CC, LDC )\n                        END IF\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9992 )\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLOS.EQ.UPLO\n                        ISAME( 2 ) = TRANSS.EQ.TRANS\n                        ISAME( 3 ) = NS.EQ.N\n                        ISAME( 4 ) = KS.EQ.K\n                        IF( CONJ )THEN\n                           ISAME( 5 ) = RALS.EQ.RALPHA\n                        ELSE\n                           ISAME( 5 ) = ALS.EQ.ALPHA\n                        END IF\n                        ISAME( 6 ) = LCE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        IF( CONJ )THEN\n                           ISAME( 8 ) = RBETS.EQ.RBETA\n                        ELSE\n                           ISAME( 8 ) = BETS.EQ.BETA\n                        END IF\n                        IF( NULL )THEN\n                           ISAME( 9 ) = LCE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 9 ) = LCERES( SNAME( 2: 3 ), UPLO, N,\n     $                                  N, CS, CC, LDC )\n                        END IF\n                        ISAME( 10 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 30 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   30                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result column by column.\n*\n                           IF( CONJ )THEN\n                              TRANST = 'C'\n                           ELSE\n                              TRANST = 'T'\n                           END IF\n                           JC = 1\n                           DO 40 J = 1, N\n                              IF( UPPER )THEN\n                                 JJ = 1\n                                 LJ = J\n                              ELSE\n                                 JJ = J\n                                 LJ = N - J + 1\n                              END IF\n                              IF( TRAN )THEN\n                                 CALL CMMCH( TRANST, 'N', LJ, 1, K,\n     $                                       ALPHA, A( 1, JJ ), NMAX,\n     $                                       A( 1, J ), NMAX, BETA,\n     $                                       C( JJ, J ), NMAX, CT, G,\n     $                                       CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              ELSE\n                                 CALL CMMCH( 'N', TRANST, LJ, 1, K,\n     $                                       ALPHA, A( JJ, 1 ), NMAX,\n     $                                       A( J, 1 ), NMAX, BETA,\n     $                                       C( JJ, J ), NMAX, CT, G,\n     $                                       CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              END IF\n                              IF( UPPER )THEN\n                                 JC = JC + LDC\n                              ELSE\n                                 JC = JC + LDC + 1\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 110\n   40                      CONTINUE\n                        END IF\n*\n   50                CONTINUE\n*\n   60             CONTINUE\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  110 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9995 )J\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( CONJ )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, N, K, RALPHA,\n     $      LDA, RBETA, LDC\n      ELSE\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, TRANS, N, K, ALPHA,\n     $      LDA, BETA, LDC\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      F4.1, ', A,', I3, ',', F4.1, ', C,', I3, ')               ',\n     $      '          .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      '(', F4.1, ',', F4.1, ') , A,', I3, ',(', F4.1, ',', F4.1,\n     $      '), C,', I3, ')          .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK4.\n*\n      END\n      SUBROUTINE CCHK5( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  AB, AA, AS, BB, BS, C, CC, CS, CT, G, W )\n*\n*  Tests CHER2K and CSYR2K.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), ONE = ( 1.0, 0.0 ) )\n      REAL               RONE, RZERO\n      PARAMETER          ( RONE = 1.0, RZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX            AA( NMAX*NMAX ), AB( 2*NMAX*NMAX ),\n     $                   ALF( NALF ), AS( NMAX*NMAX ), BB( NMAX*NMAX ),\n     $                   BET( NBET ), BS( NMAX*NMAX ), C( NMAX, NMAX ),\n     $                   CC( NMAX*NMAX ), CS( NMAX*NMAX ), CT( NMAX ),\n     $                   W( 2*NMAX )\n      REAL               G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, ALS, BETA, BETS\n      REAL               ERR, ERRMAX, RBETA, RBETS\n      INTEGER            I, IA, IB, ICT, ICU, IK, IN, J, JC, JJ, JJAB,\n     $                   K, KS, LAA, LBB, LCC, LDA, LDAS, LDB, LDBS,\n     $                   LDC, LDCS, LJ, MA, N, NA, NARGS, NC, NS\n      LOGICAL            CONJ, NULL, RESET, SAME, TRAN, UPPER\n      CHARACTER*1        TRANS, TRANSS, TRANST, UPLO, UPLOS\n      CHARACTER*2        ICHT, ICHU\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LCE, LCERES\n      EXTERNAL           LCE, LCERES\n*     .. External Subroutines ..\n      EXTERNAL           CHER2K, CMAKE, CMMCH, CSYR2K\n*     .. Intrinsic Functions ..\n      INTRINSIC          CMPLX, CONJG, MAX, REAL\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHT/'NC'/, ICHU/'UL'/\n*     .. Executable Statements ..\n      CONJ = SNAME( 2: 3 ).EQ.'HE'\n*\n      NARGS = 12\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 130 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDC to 1 more than minimum value if room.\n         LDC = N\n         IF( LDC.LT.NMAX )\n     $      LDC = LDC + 1\n*        Skip tests if not enough room.\n         IF( LDC.GT.NMAX )\n     $      GO TO 130\n         LCC = LDC*N\n*\n         DO 120 IK = 1, NIDIM\n            K = IDIM( IK )\n*\n            DO 110 ICT = 1, 2\n               TRANS = ICHT( ICT: ICT )\n               TRAN = TRANS.EQ.'C'\n               IF( TRAN.AND..NOT.CONJ )\n     $            TRANS = 'T'\n               IF( TRAN )THEN\n                  MA = K\n                  NA = N\n               ELSE\n                  MA = N\n                  NA = K\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = MA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 110\n               LAA = LDA*NA\n*\n*              Generate the matrix A.\n*\n               IF( TRAN )THEN\n                  CALL CMAKE( 'GE', ' ', ' ', MA, NA, AB, 2*NMAX, AA,\n     $                        LDA, RESET, ZERO )\n               ELSE\n                  CALL CMAKE( 'GE', ' ', ' ', MA, NA, AB, NMAX, AA, LDA,\n     $                        RESET, ZERO )\n               END IF\n*\n*              Generate the matrix B.\n*\n               LDB = LDA\n               LBB = LAA\n               IF( TRAN )THEN\n                  CALL CMAKE( 'GE', ' ', ' ', MA, NA, AB( K + 1 ),\n     $                        2*NMAX, BB, LDB, RESET, ZERO )\n               ELSE\n                  CALL CMAKE( 'GE', ' ', ' ', MA, NA, AB( K*NMAX + 1 ),\n     $                        NMAX, BB, LDB, RESET, ZERO )\n               END IF\n*\n               DO 100 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n                  UPPER = UPLO.EQ.'U'\n*\n                  DO 90 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n                     DO 80 IB = 1, NBET\n                        BETA = BET( IB )\n                        IF( CONJ )THEN\n                           RBETA = REAL( BETA )\n                           BETA = CMPLX( RBETA, RZERO )\n                        END IF\n                        NULL = N.LE.0\n                        IF( CONJ )\n     $                     NULL = NULL.OR.( ( K.LE.0.OR.ALPHA.EQ.\n     $                            ZERO ).AND.RBETA.EQ.RONE )\n*\n*                       Generate the matrix C.\n*\n                        CALL CMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, C,\n     $                              NMAX, CC, LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        NS = N\n                        KS = K\n                        ALS = ALPHA\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        DO 20 I = 1, LBB\n                           BS( I ) = BB( I )\n   20                   CONTINUE\n                        LDBS = LDB\n                        IF( CONJ )THEN\n                           RBETS = RBETA\n                        ELSE\n                           BETS = BETA\n                        END IF\n                        DO 30 I = 1, LCC\n                           CS( I ) = CC( I )\n   30                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( CONJ )THEN\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO,\n     $                        TRANS, N, K, ALPHA, LDA, LDB, RBETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL CHER2K( UPLO, TRANS, N, K, ALPHA, AA,\n     $                                  LDA, BB, LDB, RBETA, CC, LDC )\n                        ELSE\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO,\n     $                        TRANS, N, K, ALPHA, LDA, LDB, BETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL CSYR2K( UPLO, TRANS, N, K, ALPHA, AA,\n     $                                  LDA, BB, LDB, BETA, CC, LDC )\n                        END IF\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9992 )\n                           FATAL = .TRUE.\n                           GO TO 150\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLOS.EQ.UPLO\n                        ISAME( 2 ) = TRANSS.EQ.TRANS\n                        ISAME( 3 ) = NS.EQ.N\n                        ISAME( 4 ) = KS.EQ.K\n                        ISAME( 5 ) = ALS.EQ.ALPHA\n                        ISAME( 6 ) = LCE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        ISAME( 8 ) = LCE( BS, BB, LBB )\n                        ISAME( 9 ) = LDBS.EQ.LDB\n                        IF( CONJ )THEN\n                           ISAME( 10 ) = RBETS.EQ.RBETA\n                        ELSE\n                           ISAME( 10 ) = BETS.EQ.BETA\n                        END IF\n                        IF( NULL )THEN\n                           ISAME( 11 ) = LCE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 11 ) = LCERES( 'HE', UPLO, N, N, CS,\n     $                                   CC, LDC )\n                        END IF\n                        ISAME( 12 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 150\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result column by column.\n*\n                           IF( CONJ )THEN\n                              TRANST = 'C'\n                           ELSE\n                              TRANST = 'T'\n                           END IF\n                           JJAB = 1\n                           JC = 1\n                           DO 70 J = 1, N\n                              IF( UPPER )THEN\n                                 JJ = 1\n                                 LJ = J\n                              ELSE\n                                 JJ = J\n                                 LJ = N - J + 1\n                              END IF\n                              IF( TRAN )THEN\n                                 DO 50 I = 1, K\n                                    W( I ) = ALPHA*AB( ( J - 1 )*2*\n     $                                       NMAX + K + I )\n                                    IF( CONJ )THEN\n                                       W( K + I ) = CONJG( ALPHA )*\n     $                                              AB( ( J - 1 )*2*\n     $                                              NMAX + I )\n                                    ELSE\n                                       W( K + I ) = ALPHA*\n     $                                              AB( ( J - 1 )*2*\n     $                                              NMAX + I )\n                                    END IF\n   50                            CONTINUE\n                                 CALL CMMCH( TRANST, 'N', LJ, 1, 2*K,\n     $                                       ONE, AB( JJAB ), 2*NMAX, W,\n     $                                       2*NMAX, BETA, C( JJ, J ),\n     $                                       NMAX, CT, G, CC( JC ), LDC,\n     $                                       EPS, ERR, FATAL, NOUT,\n     $                                       .TRUE. )\n                              ELSE\n                                 DO 60 I = 1, K\n                                    IF( CONJ )THEN\n                                       W( I ) = ALPHA*CONJG( AB( ( K +\n     $                                          I - 1 )*NMAX + J ) )\n                                       W( K + I ) = CONJG( ALPHA*\n     $                                              AB( ( I - 1 )*NMAX +\n     $                                              J ) )\n                                    ELSE\n                                       W( I ) = ALPHA*AB( ( K + I - 1 )*\n     $                                          NMAX + J )\n                                       W( K + I ) = ALPHA*\n     $                                              AB( ( I - 1 )*NMAX +\n     $                                              J )\n                                    END IF\n   60                            CONTINUE\n                                 CALL CMMCH( 'N', 'N', LJ, 1, 2*K, ONE,\n     $                                       AB( JJ ), NMAX, W, 2*NMAX,\n     $                                       BETA, C( JJ, J ), NMAX, CT,\n     $                                       G, CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              END IF\n                              IF( UPPER )THEN\n                                 JC = JC + LDC\n                              ELSE\n                                 JC = JC + LDC + 1\n                                 IF( TRAN )\n     $                              JJAB = JJAB + 2*NMAX\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 140\n   70                      CONTINUE\n                        END IF\n*\n   80                CONTINUE\n*\n   90             CONTINUE\n*\n  100          CONTINUE\n*\n  110       CONTINUE\n*\n  120    CONTINUE\n*\n  130 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 160\n*\n  140 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9995 )J\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( CONJ )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, N, K, ALPHA,\n     $      LDA, LDB, RBETA, LDC\n      ELSE\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, TRANS, N, K, ALPHA,\n     $      LDA, LDB, BETA, LDC\n      END IF\n*\n  160 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      '(', F4.1, ',', F4.1, '), A,', I3, ', B,', I3, ',', F4.1,\n     $      ', C,', I3, ')           .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      '(', F4.1, ',', F4.1, '), A,', I3, ', B,', I3, ',(', F4.1,\n     $      ',', F4.1, '), C,', I3, ')    .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of CCHK5.\n*\n      END\n      SUBROUTINE CCHKE( ISNUM, SRNAMT, NOUT )\n*\n*  Tests the error exits from the Level 3 Blas.\n*  Requires a special version of the error-handling routine XERBLA.\n*  A, B and C should not need to be defined.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*  3-19-92:  Initialize ALPHA, BETA, RALPHA, and RBETA  (eca)\n*  3-19-92:  Fix argument 12 in calls to CSYMM and CHEMM\n*            with INFOT = 9  (eca)\n*\n*     .. Scalar Arguments ..\n      INTEGER            ISNUM, NOUT\n      CHARACTER*6        SRNAMT\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Parameters ..\n      REAL               ONE, TWO\n      PARAMETER          ( ONE = 1.0E0, TWO = 2.0E0 )\n*     .. Local Scalars ..\n      COMPLEX            ALPHA, BETA\n      REAL               RALPHA, RBETA\n*     .. Local Arrays ..\n      COMPLEX            A( 2, 1 ), B( 2, 1 ), C( 2, 1 )\n*     .. External Subroutines ..\n      EXTERNAL           CGEMM, CHEMM, CHER2K, CHERK, CHKXER, CSYMM,\n     $                   CSYR2K, CSYRK, CTRMM, CTRSM\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n*     OK is set to .FALSE. by the special version of XERBLA or by CHKXER\n*     if anything is wrong.\n      OK = .TRUE.\n*     LERR is set to .TRUE. by the special version of XERBLA each time\n*     it is called, and is then tested and re-set by CHKXER.\n      LERR = .FALSE.\n*\n*     Initialize ALPHA, BETA, RALPHA, and RBETA.\n*\n      ALPHA = CMPLX( ONE, -ONE )\n      BETA = CMPLX( TWO, -TWO )\n      RALPHA = ONE\n      RBETA = TWO\n*\n      GO TO ( 10, 20, 30, 40, 50, 60, 70, 80,\n     $        90 )ISNUM\n   10 INFOT = 1\n      CALL CGEMM( '/', 'N', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 1\n      CALL CGEMM( '/', 'C', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 1\n      CALL CGEMM( '/', 'T', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CGEMM( 'N', '/', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CGEMM( 'C', '/', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CGEMM( 'T', '/', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGEMM( 'N', 'N', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGEMM( 'N', 'C', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGEMM( 'N', 'T', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGEMM( 'C', 'N', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGEMM( 'C', 'C', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGEMM( 'C', 'T', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGEMM( 'T', 'N', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGEMM( 'T', 'C', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CGEMM( 'T', 'T', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CGEMM( 'N', 'N', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CGEMM( 'N', 'C', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CGEMM( 'N', 'T', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CGEMM( 'C', 'N', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CGEMM( 'C', 'C', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CGEMM( 'C', 'T', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CGEMM( 'T', 'N', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CGEMM( 'T', 'C', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CGEMM( 'T', 'T', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGEMM( 'N', 'N', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGEMM( 'N', 'C', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGEMM( 'N', 'T', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGEMM( 'C', 'N', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGEMM( 'C', 'C', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGEMM( 'C', 'T', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGEMM( 'T', 'N', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGEMM( 'T', 'C', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CGEMM( 'T', 'T', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGEMM( 'N', 'N', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGEMM( 'N', 'C', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGEMM( 'N', 'T', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGEMM( 'C', 'N', 0, 0, 2, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGEMM( 'C', 'C', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGEMM( 'C', 'T', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGEMM( 'T', 'N', 0, 0, 2, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGEMM( 'T', 'C', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL CGEMM( 'T', 'T', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CGEMM( 'N', 'N', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CGEMM( 'C', 'N', 0, 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CGEMM( 'T', 'N', 0, 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CGEMM( 'N', 'C', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CGEMM( 'C', 'C', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CGEMM( 'T', 'C', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CGEMM( 'N', 'T', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CGEMM( 'C', 'T', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CGEMM( 'T', 'T', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL CGEMM( 'N', 'N', 2, 0, 0, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL CGEMM( 'N', 'C', 2, 0, 0, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL CGEMM( 'N', 'T', 2, 0, 0, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL CGEMM( 'C', 'N', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL CGEMM( 'C', 'C', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL CGEMM( 'C', 'T', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL CGEMM( 'T', 'N', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL CGEMM( 'T', 'C', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL CGEMM( 'T', 'T', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   20 INFOT = 1\n      CALL CHEMM( '/', 'U', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CHEMM( 'L', '/', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHEMM( 'L', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHEMM( 'R', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHEMM( 'L', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHEMM( 'R', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHEMM( 'L', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHEMM( 'R', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHEMM( 'L', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHEMM( 'R', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHEMM( 'L', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHEMM( 'R', 'U', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHEMM( 'L', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHEMM( 'R', 'L', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CHEMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CHEMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CHEMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CHEMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CHEMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CHEMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CHEMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CHEMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   30 INFOT = 1\n      CALL CSYMM( '/', 'U', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CSYMM( 'L', '/', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYMM( 'L', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYMM( 'R', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYMM( 'L', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYMM( 'R', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYMM( 'L', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYMM( 'R', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYMM( 'L', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYMM( 'R', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYMM( 'L', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYMM( 'R', 'U', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYMM( 'L', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYMM( 'R', 'L', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   40 INFOT = 1\n      CALL CTRMM( '/', 'U', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CTRMM( 'L', '/', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CTRMM( 'L', 'U', '/', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CTRMM( 'L', 'U', 'N', '/', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'L', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'L', 'U', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'L', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'R', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'R', 'U', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'R', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'L', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'L', 'L', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'L', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'R', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'R', 'L', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRMM( 'R', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'L', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'L', 'U', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'L', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'R', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'R', 'U', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'R', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'L', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'L', 'L', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'L', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'R', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'R', 'L', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRMM( 'R', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'L', 'U', 'C', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'R', 'U', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'R', 'U', 'C', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'R', 'U', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'L', 'L', 'C', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'R', 'L', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'R', 'L', 'C', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRMM( 'R', 'L', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'L', 'U', 'C', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'R', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'R', 'U', 'C', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'R', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'L', 'L', 'C', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'R', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'R', 'L', 'C', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRMM( 'R', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   50 INFOT = 1\n      CALL CTRSM( '/', 'U', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CTRSM( 'L', '/', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CTRSM( 'L', 'U', '/', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CTRSM( 'L', 'U', 'N', '/', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'L', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'L', 'U', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'L', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'R', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'R', 'U', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'R', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'L', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'L', 'L', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'L', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'R', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'R', 'L', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL CTRSM( 'R', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'L', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'L', 'U', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'L', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'R', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'R', 'U', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'R', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'L', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'L', 'L', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'L', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'R', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'R', 'L', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL CTRSM( 'R', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'L', 'U', 'C', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'R', 'U', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'R', 'U', 'C', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'R', 'U', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'L', 'L', 'C', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'R', 'L', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'R', 'L', 'C', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CTRSM( 'R', 'L', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'L', 'U', 'C', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'R', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'R', 'U', 'C', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'R', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'L', 'L', 'C', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'R', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'R', 'L', 'C', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL CTRSM( 'R', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   60 INFOT = 1\n      CALL CHERK( '/', 'N', 0, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CHERK( 'U', 'T', 0, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHERK( 'U', 'N', -1, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHERK( 'U', 'C', -1, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHERK( 'L', 'N', -1, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHERK( 'L', 'C', -1, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHERK( 'U', 'N', 0, -1, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHERK( 'U', 'C', 0, -1, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHERK( 'L', 'N', 0, -1, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHERK( 'L', 'C', 0, -1, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHERK( 'U', 'N', 2, 0, RALPHA, A, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHERK( 'U', 'C', 0, 2, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHERK( 'L', 'N', 2, 0, RALPHA, A, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHERK( 'L', 'C', 0, 2, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CHERK( 'U', 'N', 2, 0, RALPHA, A, 2, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CHERK( 'U', 'C', 2, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CHERK( 'L', 'N', 2, 0, RALPHA, A, 2, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CHERK( 'L', 'C', 2, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   70 INFOT = 1\n      CALL CSYRK( '/', 'N', 0, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CSYRK( 'U', 'C', 0, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYRK( 'U', 'N', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYRK( 'U', 'T', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYRK( 'L', 'N', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYRK( 'L', 'T', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYRK( 'U', 'N', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYRK( 'U', 'T', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYRK( 'L', 'N', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYRK( 'L', 'T', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYRK( 'U', 'N', 2, 0, ALPHA, A, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYRK( 'U', 'T', 0, 2, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYRK( 'L', 'N', 2, 0, ALPHA, A, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYRK( 'L', 'T', 0, 2, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CSYRK( 'U', 'N', 2, 0, ALPHA, A, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CSYRK( 'U', 'T', 2, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CSYRK( 'L', 'N', 2, 0, ALPHA, A, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL CSYRK( 'L', 'T', 2, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   80 INFOT = 1\n      CALL CHER2K( '/', 'N', 0, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CHER2K( 'U', 'T', 0, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHER2K( 'U', 'N', -1, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHER2K( 'U', 'C', -1, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHER2K( 'L', 'N', -1, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CHER2K( 'L', 'C', -1, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHER2K( 'U', 'N', 0, -1, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHER2K( 'U', 'C', 0, -1, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHER2K( 'L', 'N', 0, -1, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CHER2K( 'L', 'C', 0, -1, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHER2K( 'U', 'N', 2, 0, ALPHA, A, 1, B, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHER2K( 'U', 'C', 0, 2, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHER2K( 'L', 'N', 2, 0, ALPHA, A, 1, B, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CHER2K( 'L', 'C', 0, 2, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CHER2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CHER2K( 'U', 'C', 0, 2, ALPHA, A, 2, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CHER2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CHER2K( 'L', 'C', 0, 2, ALPHA, A, 2, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CHER2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 2, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CHER2K( 'U', 'C', 2, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CHER2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 2, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CHER2K( 'L', 'C', 2, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   90 INFOT = 1\n      CALL CSYR2K( '/', 'N', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL CSYR2K( 'U', 'C', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYR2K( 'U', 'N', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYR2K( 'U', 'T', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYR2K( 'L', 'N', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL CSYR2K( 'L', 'T', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYR2K( 'U', 'N', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYR2K( 'U', 'T', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYR2K( 'L', 'N', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL CSYR2K( 'L', 'T', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYR2K( 'U', 'N', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYR2K( 'U', 'T', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYR2K( 'L', 'N', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL CSYR2K( 'L', 'T', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CSYR2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CSYR2K( 'U', 'T', 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CSYR2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL CSYR2K( 'L', 'T', 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CSYR2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CSYR2K( 'U', 'T', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CSYR2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL CSYR2K( 'L', 'T', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n  100 IF( OK )THEN\n         WRITE( NOUT, FMT = 9999 )SRNAMT\n      ELSE\n         WRITE( NOUT, FMT = 9998 )SRNAMT\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE TESTS OF ERROR-EXITS' )\n 9998 FORMAT( ' ******* ', A6, ' FAILED THE TESTS OF ERROR-EXITS *****',\n     $      '**' )\n*\n*     End of CCHKE.\n*\n      END\n      SUBROUTINE CMAKE( TYPE, UPLO, DIAG, M, N, A, NMAX, AA, LDA, RESET,\n     $                  TRANSL )\n*\n*  Generates values for an M by N matrix A.\n*  Stores the values in the array AA in the data structure required\n*  by the routine, with unwanted elements set to rogue value.\n*\n*  TYPE is 'GE', 'HE', 'SY' or 'TR'.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ), ONE = ( 1.0, 0.0 ) )\n      COMPLEX            ROGUE\n      PARAMETER          ( ROGUE = ( -1.0E10, 1.0E10 ) )\n      REAL               RZERO\n      PARAMETER          ( RZERO = 0.0 )\n      REAL               RROGUE\n      PARAMETER          ( RROGUE = -1.0E10 )\n*     .. Scalar Arguments ..\n      COMPLEX            TRANSL\n      INTEGER            LDA, M, N, NMAX\n      LOGICAL            RESET\n      CHARACTER*1        DIAG, UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      COMPLEX            A( NMAX, * ), AA( * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J, JJ\n      LOGICAL            GEN, HER, LOWER, SYM, TRI, UNIT, UPPER\n*     .. External Functions ..\n      COMPLEX            CBEG\n      EXTERNAL           CBEG\n*     .. Intrinsic Functions ..\n      INTRINSIC          CMPLX, CONJG, REAL\n*     .. Executable Statements ..\n      GEN = TYPE.EQ.'GE'\n      HER = TYPE.EQ.'HE'\n      SYM = TYPE.EQ.'SY'\n      TRI = TYPE.EQ.'TR'\n      UPPER = ( HER.OR.SYM.OR.TRI ).AND.UPLO.EQ.'U'\n      LOWER = ( HER.OR.SYM.OR.TRI ).AND.UPLO.EQ.'L'\n      UNIT = TRI.AND.DIAG.EQ.'U'\n*\n*     Generate data in array A.\n*\n      DO 20 J = 1, N\n         DO 10 I = 1, M\n            IF( GEN.OR.( UPPER.AND.I.LE.J ).OR.( LOWER.AND.I.GE.J ) )\n     $          THEN\n               A( I, J ) = CBEG( RESET ) + TRANSL\n               IF( I.NE.J )THEN\n*                 Set some elements to zero\n                  IF( N.GT.3.AND.J.EQ.N/2 )\n     $               A( I, J ) = ZERO\n                  IF( HER )THEN\n                     A( J, I ) = CONJG( A( I, J ) )\n                  ELSE IF( SYM )THEN\n                     A( J, I ) = A( I, J )\n                  ELSE IF( TRI )THEN\n                     A( J, I ) = ZERO\n                  END IF\n               END IF\n            END IF\n   10    CONTINUE\n         IF( HER )\n     $      A( J, J ) = CMPLX( REAL( A( J, J ) ), RZERO )\n         IF( TRI )\n     $      A( J, J ) = A( J, J ) + ONE\n         IF( UNIT )\n     $      A( J, J ) = ONE\n   20 CONTINUE\n*\n*     Store elements in array AS in data structure required by routine.\n*\n      IF( TYPE.EQ.'GE' )THEN\n         DO 50 J = 1, N\n            DO 30 I = 1, M\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   30       CONTINUE\n            DO 40 I = M + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   40       CONTINUE\n   50    CONTINUE\n      ELSE IF( TYPE.EQ.'HE'.OR.TYPE.EQ.'SY'.OR.TYPE.EQ.'TR' )THEN\n         DO 90 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IF( UNIT )THEN\n                  IEND = J - 1\n               ELSE\n                  IEND = J\n               END IF\n            ELSE\n               IF( UNIT )THEN\n                  IBEG = J + 1\n               ELSE\n                  IBEG = J\n               END IF\n               IEND = N\n            END IF\n            DO 60 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   60       CONTINUE\n            DO 70 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   70       CONTINUE\n            DO 80 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   80       CONTINUE\n            IF( HER )THEN\n               JJ = J + ( J - 1 )*LDA\n               AA( JJ ) = CMPLX( REAL( AA( JJ ) ), RROGUE )\n            END IF\n   90    CONTINUE\n      END IF\n      RETURN\n*\n*     End of CMAKE.\n*\n      END\n      SUBROUTINE CMMCH( TRANSA, TRANSB, M, N, KK, ALPHA, A, LDA, B, LDB,\n     $                  BETA, C, LDC, CT, G, CC, LDCC, EPS, ERR, FATAL,\n     $                  NOUT, MV )\n*\n*  Checks the results of the computational tests.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX            ZERO\n      PARAMETER          ( ZERO = ( 0.0, 0.0 ) )\n      REAL               RZERO, RONE\n      PARAMETER          ( RZERO = 0.0, RONE = 1.0 )\n*     .. Scalar Arguments ..\n      COMPLEX            ALPHA, BETA\n      REAL               EPS, ERR\n      INTEGER            KK, LDA, LDB, LDC, LDCC, M, N, NOUT\n      LOGICAL            FATAL, MV\n      CHARACTER*1        TRANSA, TRANSB\n*     .. Array Arguments ..\n      COMPLEX            A( LDA, * ), B( LDB, * ), C( LDC, * ),\n     $                   CC( LDCC, * ), CT( * )\n      REAL               G( * )\n*     .. Local Scalars ..\n      COMPLEX            CL\n      REAL               ERRI\n      INTEGER            I, J, K\n      LOGICAL            CTRANA, CTRANB, TRANA, TRANB\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, AIMAG, CONJG, MAX, REAL, SQRT\n*     .. Statement Functions ..\n      REAL               ABS1\n*     .. Statement Function definitions ..\n      ABS1( CL ) = ABS( REAL( CL ) ) + ABS( AIMAG( CL ) )\n*     .. Executable Statements ..\n      TRANA = TRANSA.EQ.'T'.OR.TRANSA.EQ.'C'\n      TRANB = TRANSB.EQ.'T'.OR.TRANSB.EQ.'C'\n      CTRANA = TRANSA.EQ.'C'\n      CTRANB = TRANSB.EQ.'C'\n*\n*     Compute expected result, one column at a time, in CT using data\n*     in A, B and C.\n*     Compute gauges in G.\n*\n      DO 220 J = 1, N\n*\n         DO 10 I = 1, M\n            CT( I ) = ZERO\n            G( I ) = RZERO\n   10    CONTINUE\n         IF( .NOT.TRANA.AND..NOT.TRANB )THEN\n            DO 30 K = 1, KK\n               DO 20 I = 1, M\n                  CT( I ) = CT( I ) + A( I, K )*B( K, J )\n                  G( I ) = G( I ) + ABS1( A( I, K ) )*ABS1( B( K, J ) )\n   20          CONTINUE\n   30       CONTINUE\n         ELSE IF( TRANA.AND..NOT.TRANB )THEN\n            IF( CTRANA )THEN\n               DO 50 K = 1, KK\n                  DO 40 I = 1, M\n                     CT( I ) = CT( I ) + CONJG( A( K, I ) )*B( K, J )\n                     G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                        ABS1( B( K, J ) )\n   40             CONTINUE\n   50          CONTINUE\n            ELSE\n               DO 70 K = 1, KK\n                  DO 60 I = 1, M\n                     CT( I ) = CT( I ) + A( K, I )*B( K, J )\n                     G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                        ABS1( B( K, J ) )\n   60             CONTINUE\n   70          CONTINUE\n            END IF\n         ELSE IF( .NOT.TRANA.AND.TRANB )THEN\n            IF( CTRANB )THEN\n               DO 90 K = 1, KK\n                  DO 80 I = 1, M\n                     CT( I ) = CT( I ) + A( I, K )*CONJG( B( J, K ) )\n                     G( I ) = G( I ) + ABS1( A( I, K ) )*\n     $                        ABS1( B( J, K ) )\n   80             CONTINUE\n   90          CONTINUE\n            ELSE\n               DO 110 K = 1, KK\n                  DO 100 I = 1, M\n                     CT( I ) = CT( I ) + A( I, K )*B( J, K )\n                     G( I ) = G( I ) + ABS1( A( I, K ) )*\n     $                        ABS1( B( J, K ) )\n  100             CONTINUE\n  110          CONTINUE\n            END IF\n         ELSE IF( TRANA.AND.TRANB )THEN\n            IF( CTRANA )THEN\n               IF( CTRANB )THEN\n                  DO 130 K = 1, KK\n                     DO 120 I = 1, M\n                        CT( I ) = CT( I ) + CONJG( A( K, I ) )*\n     $                            CONJG( B( J, K ) )\n                        G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                           ABS1( B( J, K ) )\n  120                CONTINUE\n  130             CONTINUE\n               ELSE\n                  DO 150 K = 1, KK\n                     DO 140 I = 1, M\n                        CT( I ) = CT( I ) + CONJG( A( K, I ) )*B( J, K )\n                        G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                           ABS1( B( J, K ) )\n  140                CONTINUE\n  150             CONTINUE\n               END IF\n            ELSE\n               IF( CTRANB )THEN\n                  DO 170 K = 1, KK\n                     DO 160 I = 1, M\n                        CT( I ) = CT( I ) + A( K, I )*CONJG( B( J, K ) )\n                        G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                           ABS1( B( J, K ) )\n  160                CONTINUE\n  170             CONTINUE\n               ELSE\n                  DO 190 K = 1, KK\n                     DO 180 I = 1, M\n                        CT( I ) = CT( I ) + A( K, I )*B( J, K )\n                        G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                           ABS1( B( J, K ) )\n  180                CONTINUE\n  190             CONTINUE\n               END IF\n            END IF\n         END IF\n         DO 200 I = 1, M\n            CT( I ) = ALPHA*CT( I ) + BETA*C( I, J )\n            G( I ) = ABS1( ALPHA )*G( I ) +\n     $               ABS1( BETA )*ABS1( C( I, J ) )\n  200    CONTINUE\n*\n*        Compute the error ratio for this result.\n*\n         ERR = ZERO\n         DO 210 I = 1, M\n            ERRI = ABS1( CT( I ) - CC( I, J ) )/EPS\n            IF( G( I ).NE.RZERO )\n     $         ERRI = ERRI/G( I )\n            ERR = MAX( ERR, ERRI )\n            IF( ERR*SQRT( EPS ).GE.RONE )\n     $         GO TO 230\n  210    CONTINUE\n*\n  220 CONTINUE\n*\n*     If the loop completes, all results are at least half accurate.\n      GO TO 250\n*\n*     Report fatal error.\n*\n  230 FATAL = .TRUE.\n      WRITE( NOUT, FMT = 9999 )\n      DO 240 I = 1, M\n         IF( MV )THEN\n            WRITE( NOUT, FMT = 9998 )I, CT( I ), CC( I, J )\n         ELSE\n            WRITE( NOUT, FMT = 9998 )I, CC( I, J ), CT( I )\n         END IF\n  240 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9997 )J\n*\n  250 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ******* FATAL ERROR - COMPUTED RESULT IS LESS THAN HAL',\n     $      'F ACCURATE *******', /'                       EXPECTED RE',\n     $      'SULT                    COMPUTED RESULT' )\n 9998 FORMAT( 1X, I7, 2( '  (', G15.6, ',', G15.6, ')' ) )\n 9997 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n*\n*     End of CMMCH.\n*\n      END\n      LOGICAL FUNCTION LCE( RI, RJ, LR )\n*\n*  Tests if two arrays are identical.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LR\n*     .. Array Arguments ..\n      COMPLEX            RI( * ), RJ( * )\n*     .. Local Scalars ..\n      INTEGER            I\n*     .. Executable Statements ..\n      DO 10 I = 1, LR\n         IF( RI( I ).NE.RJ( I ) )\n     $      GO TO 20\n   10 CONTINUE\n      LCE = .TRUE.\n      GO TO 30\n   20 CONTINUE\n      LCE = .FALSE.\n   30 RETURN\n*\n*     End of LCE.\n*\n      END\n      LOGICAL FUNCTION LCERES( TYPE, UPLO, M, N, AA, AS, LDA )\n*\n*  Tests if selected elements in two arrays are equal.\n*\n*  TYPE is 'GE' or 'HE' or 'SY'.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LDA, M, N\n      CHARACTER*1        UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      COMPLEX            AA( LDA, * ), AS( LDA, * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J\n      LOGICAL            UPPER\n*     .. Executable Statements ..\n      UPPER = UPLO.EQ.'U'\n      IF( TYPE.EQ.'GE' )THEN\n         DO 20 J = 1, N\n            DO 10 I = M + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   10       CONTINUE\n   20    CONTINUE\n      ELSE IF( TYPE.EQ.'HE'.OR.TYPE.EQ.'SY' )THEN\n         DO 50 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 30 I = 1, IBEG - 1\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   30       CONTINUE\n            DO 40 I = IEND + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   40       CONTINUE\n   50    CONTINUE\n      END IF\n*\n      LCERES = .TRUE.\n      GO TO 80\n   70 CONTINUE\n      LCERES = .FALSE.\n   80 RETURN\n*\n*     End of LCERES.\n*\n      END\n      COMPLEX FUNCTION CBEG( RESET )\n*\n*  Generates complex numbers as pairs of random numbers uniformly\n*  distributed between -0.5 and 0.5.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      LOGICAL            RESET\n*     .. Local Scalars ..\n      INTEGER            I, IC, J, MI, MJ\n*     .. Save statement ..\n      SAVE               I, IC, J, MI, MJ\n*     .. Intrinsic Functions ..\n      INTRINSIC          CMPLX\n*     .. Executable Statements ..\n      IF( RESET )THEN\n*        Initialize local variables.\n         MI = 891\n         MJ = 457\n         I = 7\n         J = 7\n         IC = 0\n         RESET = .FALSE.\n      END IF\n*\n*     The sequence of values of I or J is bounded between 1 and 999.\n*     If initial I or J = 1,2,3,6,7 or 9, the period will be 50.\n*     If initial I or J = 4 or 8, the period will be 25.\n*     If initial I or J = 5, the period will be 10.\n*     IC is used to break up the period by skipping 1 value of I or J\n*     in 6.\n*\n      IC = IC + 1\n   10 I = I*MI\n      J = J*MJ\n      I = I - 1000*( I/1000 )\n      J = J - 1000*( J/1000 )\n      IF( IC.GE.5 )THEN\n         IC = 0\n         GO TO 10\n      END IF\n      CBEG = CMPLX( ( I - 500 )/1001.0, ( J - 500 )/1001.0 )\n      RETURN\n*\n*     End of CBEG.\n*\n      END\n      REAL FUNCTION SDIFF( X, Y )\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      REAL               X, Y\n*     .. Executable Statements ..\n      SDIFF = X - Y\n      RETURN\n*\n*     End of SDIFF.\n*\n      END\n      SUBROUTINE CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n*  Tests whether XERBLA has detected an error when it should.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Executable Statements ..\n      IF( .NOT.LERR )THEN\n         WRITE( NOUT, FMT = 9999 )INFOT, SRNAMT\n         OK = .FALSE.\n      END IF\n      LERR = .FALSE.\n      RETURN\n*\n 9999 FORMAT( ' ***** ILLEGAL VALUE OF PARAMETER NUMBER ', I2, ' NOT D',\n     $      'ETECTED BY ', A6, ' *****' )\n*\n*     End of CHKXER.\n*\n      END\n      SUBROUTINE XERBLA( SRNAME, INFO )\n*\n*  This is a special version of XERBLA to be used only as part of\n*  the test program for testing error exits from the Level 3 BLAS\n*  routines.\n*\n*  XERBLA  is an error handler for the Level 3 BLAS routines.\n*\n*  It is called by the Level 3 BLAS routines if an input parameter is\n*  invalid.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFO\n      CHARACTER*6        SRNAME\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUT, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Executable Statements ..\n      LERR = .TRUE.\n      IF( INFO.NE.INFOT )THEN\n         IF( INFOT.NE.0 )THEN\n            WRITE( NOUT, FMT = 9999 )INFO, INFOT\n         ELSE\n            WRITE( NOUT, FMT = 9997 )INFO\n         END IF\n         OK = .FALSE.\n      END IF\n      IF( SRNAME.NE.SRNAMT )THEN\n         WRITE( NOUT, FMT = 9998 )SRNAME, SRNAMT\n         OK = .FALSE.\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6, ' INSTEAD',\n     $      ' OF ', I2, ' *******' )\n 9998 FORMAT( ' ******* XERBLA WAS CALLED WITH SRNAME = ', A6, ' INSTE',\n     $      'AD OF ', A6, ' *******' )\n 9997 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6,\n     $      ' *******' )\n*\n*     End of XERBLA\n*\n      END\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/testing/dblat1.f",
    "content": "*> \\brief \\b DBLAT1\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM DBLAT1\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*>    Test program for the DOUBLE PRECISION Level 1 BLAS.\n*>\n*>    Based upon the original BLAS test routine together with:\n*>    F06EAF Example Program Text\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup double_blas_testing\n*\n*  =====================================================================\n      PROGRAM DBLAT1\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER          NOUT\n      PARAMETER        (NOUT=6)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, N\n      LOGICAL          PASS\n*     .. Local Scalars ..\n      DOUBLE PRECISION SFAC\n      INTEGER          IC\n*     .. External Subroutines ..\n      EXTERNAL         CHECK0, CHECK1, CHECK2, CHECK3, HEADER\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      DATA             SFAC/9.765625D-4/\n*     .. Executable Statements ..\n      WRITE (NOUT,99999)\n      DO 20 IC = 1, 13\n         ICASE = IC\n         CALL HEADER\n*\n*        .. Initialize  PASS,  INCX,  and INCY for a new case. ..\n*        .. the value 9999 for INCX or INCY will appear in the ..\n*        .. detailed  output, if any, for cases  that do not involve ..\n*        .. these parameters ..\n*\n         PASS = .TRUE.\n         INCX = 9999\n         INCY = 9999\n         IF (ICASE.EQ.3 .OR. ICASE.EQ.11) THEN\n            CALL CHECK0(SFAC)\n         ELSE IF (ICASE.EQ.7 .OR. ICASE.EQ.8 .OR. ICASE.EQ.9 .OR.\n     +            ICASE.EQ.10) THEN\n            CALL CHECK1(SFAC)\n         ELSE IF (ICASE.EQ.1 .OR. ICASE.EQ.2 .OR. ICASE.EQ.5 .OR.\n     +            ICASE.EQ.6 .OR. ICASE.EQ.12 .OR. ICASE.EQ.13) THEN\n            CALL CHECK2(SFAC)\n         ELSE IF (ICASE.EQ.4) THEN\n            CALL CHECK3(SFAC)\n         END IF\n*        -- Print\n         IF (PASS) WRITE (NOUT,99998)\n   20 CONTINUE\n      STOP\n*\n99999 FORMAT (' Real BLAS Test Program Results',/1X)\n99998 FORMAT ('                                    ----- PASS -----')\n      END\n      SUBROUTINE HEADER\n*     .. Parameters ..\n      INTEGER          NOUT\n      PARAMETER        (NOUT=6)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, N\n      LOGICAL          PASS\n*     .. Local Arrays ..\n      CHARACTER*6      L(13)\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      DATA             L(1)/' DDOT '/\n      DATA             L(2)/'DAXPY '/\n      DATA             L(3)/'DROTG '/\n      DATA             L(4)/' DROT '/\n      DATA             L(5)/'DCOPY '/\n      DATA             L(6)/'DSWAP '/\n      DATA             L(7)/'DNRM2 '/\n      DATA             L(8)/'DASUM '/\n      DATA             L(9)/'DSCAL '/\n      DATA             L(10)/'IDAMAX'/\n      DATA             L(11)/'DROTMG'/\n      DATA             L(12)/'DROTM '/\n      DATA             L(13)/'DSDOT '/\n*     .. Executable Statements ..\n      WRITE (NOUT,99999) ICASE, L(ICASE)\n      RETURN\n*\n99999 FORMAT (/' Test of subprogram number',I3,12X,A6)\n      END\n      SUBROUTINE CHECK0(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION  SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      DOUBLE PRECISION  SA, SB, SC, SS, D12\n      INTEGER           I, K\n*     .. Local Arrays ..\n      DOUBLE PRECISION  DA1(8), DATRUE(8), DB1(8), DBTRUE(8), DC1(8),\n     $                  DS1(8), DAB(4,9), DTEMP(9), DTRUE(9,9)\n*     .. External Subroutines ..\n      EXTERNAL          DROTG, DROTMG, STEST1\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      DATA              DA1/0.3D0, 0.4D0, -0.3D0, -0.4D0, -0.3D0, 0.0D0,\n     +                  0.0D0, 1.0D0/\n      DATA              DB1/0.4D0, 0.3D0, 0.4D0, 0.3D0, -0.4D0, 0.0D0,\n     +                  1.0D0, 0.0D0/\n      DATA              DC1/0.6D0, 0.8D0, -0.6D0, 0.8D0, 0.6D0, 1.0D0,\n     +                  0.0D0, 1.0D0/\n      DATA              DS1/0.8D0, 0.6D0, 0.8D0, -0.6D0, 0.8D0, 0.0D0,\n     +                  1.0D0, 0.0D0/\n      DATA              DATRUE/0.5D0, 0.5D0, 0.5D0, -0.5D0, -0.5D0,\n     +                  0.0D0, 1.0D0, 1.0D0/\n      DATA              DBTRUE/0.0D0, 0.6D0, 0.0D0, -0.6D0, 0.0D0,\n     +                  0.0D0, 1.0D0, 0.0D0/\n*     INPUT FOR MODIFIED GIVENS\n      DATA DAB/ .1D0,.3D0,1.2D0,.2D0,\n     A          .7D0, .2D0, .6D0, 4.2D0,\n     B          0.D0,0.D0,0.D0,0.D0,\n     C          4.D0, -1.D0, 2.D0, 4.D0,\n     D          6.D-10, 2.D-2, 1.D5, 10.D0,\n     E          4.D10, 2.D-2, 1.D-5, 10.D0,\n     F          2.D-10, 4.D-2, 1.D5, 10.D0,\n     G          2.D10, 4.D-2, 1.D-5, 10.D0,\n     H          4.D0, -2.D0, 8.D0, 4.D0    /\n*    TRUE RESULTS FOR MODIFIED GIVENS\n      DATA DTRUE/0.D0,0.D0, 1.3D0, .2D0, 0.D0,0.D0,0.D0, .5D0, 0.D0,\n     A           0.D0,0.D0, 4.5D0, 4.2D0, 1.D0, .5D0, 0.D0,0.D0,0.D0,\n     B           0.D0,0.D0,0.D0,0.D0, -2.D0, 0.D0,0.D0,0.D0,0.D0,\n     C           0.D0,0.D0,0.D0, 4.D0, -1.D0, 0.D0,0.D0,0.D0,0.D0,\n     D           0.D0, 15.D-3, 0.D0, 10.D0, -1.D0, 0.D0, -1.D-4,\n     E           0.D0, 1.D0,\n     F           0.D0,0.D0, 6144.D-5, 10.D0, -1.D0, 4096.D0, -1.D6,\n     G           0.D0, 1.D0,\n     H           0.D0,0.D0,15.D0,10.D0,-1.D0, 5.D-5, 0.D0,1.D0,0.D0,\n     I           0.D0,0.D0, 15.D0, 10.D0, -1. D0, 5.D5, -4096.D0,\n     J           1.D0, 4096.D-6,\n     K           0.D0,0.D0, 7.D0, 4.D0, 0.D0,0.D0, -.5D0, -.25D0, 0.D0/\n*                   4096 = 2 ** 12\n      DATA D12  /4096.D0/\n      DTRUE(1,1) = 12.D0 / 130.D0\n      DTRUE(2,1) = 36.D0 / 130.D0\n      DTRUE(7,1) = -1.D0 / 6.D0\n      DTRUE(1,2) = 14.D0 / 75.D0\n      DTRUE(2,2) = 49.D0 / 75.D0\n      DTRUE(9,2) = 1.D0 / 7.D0\n      DTRUE(1,5) = 45.D-11 * (D12 * D12)\n      DTRUE(3,5) = 4.D5 / (3.D0 * D12)\n      DTRUE(6,5) = 1.D0 / D12\n      DTRUE(8,5) = 1.D4 / (3.D0 * D12)\n      DTRUE(1,6) = 4.D10 / (1.5D0 * D12 * D12)\n      DTRUE(2,6) = 2.D-2 / 1.5D0\n      DTRUE(8,6) = 5.D-7 * D12\n      DTRUE(1,7) = 4.D0 / 150.D0\n      DTRUE(2,7) = (2.D-10 / 1.5D0) * (D12 * D12)\n      DTRUE(7,7) = -DTRUE(6,5)\n      DTRUE(9,7) = 1.D4 / D12\n      DTRUE(1,8) = DTRUE(1,7)\n      DTRUE(2,8) = 2.D10 / (1.5D0 * D12 * D12)\n      DTRUE(1,9) = 32.D0 / 7.D0\n      DTRUE(2,9) = -16.D0 / 7.D0\n*     .. Executable Statements ..\n*\n*     Compute true values which cannot be prestored\n*     in decimal notation\n*\n      DBTRUE(1) = 1.0D0/0.6D0\n      DBTRUE(3) = -1.0D0/0.6D0\n      DBTRUE(5) = 1.0D0/0.6D0\n*\n      DO 20 K = 1, 8\n*        .. Set N=K for identification in output if any ..\n         N = K\n         IF (ICASE.EQ.3) THEN\n*           .. DROTG ..\n            IF (K.GT.8) GO TO 40\n            SA = DA1(K)\n            SB = DB1(K)\n            CALL DROTG(SA,SB,SC,SS)\n            CALL STEST1(SA,DATRUE(K),DATRUE(K),SFAC)\n            CALL STEST1(SB,DBTRUE(K),DBTRUE(K),SFAC)\n            CALL STEST1(SC,DC1(K),DC1(K),SFAC)\n            CALL STEST1(SS,DS1(K),DS1(K),SFAC)\n         ELSEIF (ICASE.EQ.11) THEN\n*           .. DROTMG ..\n            DO I=1,4\n               DTEMP(I)= DAB(I,K)\n               DTEMP(I+4) = 0.0\n            END DO\n            DTEMP(9) = 0.0\n            CALL DROTMG(DTEMP(1),DTEMP(2),DTEMP(3),DTEMP(4),DTEMP(5))\n            CALL STEST(9,DTEMP,DTRUE(1,K),DTRUE(1,K),SFAC)\n         ELSE\n            WRITE (NOUT,*) ' Shouldn''t be here in CHECK0'\n            STOP\n         END IF\n   20 CONTINUE\n   40 RETURN\n      END\n      SUBROUTINE CHECK1(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION  SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      INTEGER           I, LEN, NP1\n*     .. Local Arrays ..\n      DOUBLE PRECISION  DTRUE1(5), DTRUE3(5), DTRUE5(8,5,2), DV(8,5,2),\n     +                  SA(10), STEMP(1), STRUE(8), SX(8)\n      INTEGER           ITRUE2(5)\n*     .. External Functions ..\n      DOUBLE PRECISION  DASUM, DNRM2\n      INTEGER           IDAMAX\n      EXTERNAL          DASUM, DNRM2, IDAMAX\n*     .. External Subroutines ..\n      EXTERNAL          ITEST1, DSCAL, STEST, STEST1\n*     .. Intrinsic Functions ..\n      INTRINSIC         MAX\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      DATA              SA/0.3D0, -1.0D0, 0.0D0, 1.0D0, 0.3D0, 0.3D0,\n     +                  0.3D0, 0.3D0, 0.3D0, 0.3D0/\n      DATA              DV/0.1D0, 2.0D0, 2.0D0, 2.0D0, 2.0D0, 2.0D0,\n     +                  2.0D0, 2.0D0, 0.3D0, 3.0D0, 3.0D0, 3.0D0, 3.0D0,\n     +                  3.0D0, 3.0D0, 3.0D0, 0.3D0, -0.4D0, 4.0D0,\n     +                  4.0D0, 4.0D0, 4.0D0, 4.0D0, 4.0D0, 0.2D0,\n     +                  -0.6D0, 0.3D0, 5.0D0, 5.0D0, 5.0D0, 5.0D0,\n     +                  5.0D0, 0.1D0, -0.3D0, 0.5D0, -0.1D0, 6.0D0,\n     +                  6.0D0, 6.0D0, 6.0D0, 0.1D0, 8.0D0, 8.0D0, 8.0D0,\n     +                  8.0D0, 8.0D0, 8.0D0, 8.0D0, 0.3D0, 9.0D0, 9.0D0,\n     +                  9.0D0, 9.0D0, 9.0D0, 9.0D0, 9.0D0, 0.3D0, 2.0D0,\n     +                  -0.4D0, 2.0D0, 2.0D0, 2.0D0, 2.0D0, 2.0D0,\n     +                  0.2D0, 3.0D0, -0.6D0, 5.0D0, 0.3D0, 2.0D0,\n     +                  2.0D0, 2.0D0, 0.1D0, 4.0D0, -0.3D0, 6.0D0,\n     +                  -0.5D0, 7.0D0, -0.1D0, 3.0D0/\n      DATA              DTRUE1/0.0D0, 0.3D0, 0.5D0, 0.7D0, 0.6D0/\n      DATA              DTRUE3/0.0D0, 0.3D0, 0.7D0, 1.1D0, 1.0D0/\n      DATA              DTRUE5/0.10D0, 2.0D0, 2.0D0, 2.0D0, 2.0D0,\n     +                  2.0D0, 2.0D0, 2.0D0, -0.3D0, 3.0D0, 3.0D0,\n     +                  3.0D0, 3.0D0, 3.0D0, 3.0D0, 3.0D0, 0.0D0, 0.0D0,\n     +                  4.0D0, 4.0D0, 4.0D0, 4.0D0, 4.0D0, 4.0D0,\n     +                  0.20D0, -0.60D0, 0.30D0, 5.0D0, 5.0D0, 5.0D0,\n     +                  5.0D0, 5.0D0, 0.03D0, -0.09D0, 0.15D0, -0.03D0,\n     +                  6.0D0, 6.0D0, 6.0D0, 6.0D0, 0.10D0, 8.0D0,\n     +                  8.0D0, 8.0D0, 8.0D0, 8.0D0, 8.0D0, 8.0D0,\n     +                  0.09D0, 9.0D0, 9.0D0, 9.0D0, 9.0D0, 9.0D0,\n     +                  9.0D0, 9.0D0, 0.09D0, 2.0D0, -0.12D0, 2.0D0,\n     +                  2.0D0, 2.0D0, 2.0D0, 2.0D0, 0.06D0, 3.0D0,\n     +                  -0.18D0, 5.0D0, 0.09D0, 2.0D0, 2.0D0, 2.0D0,\n     +                  0.03D0, 4.0D0, -0.09D0, 6.0D0, -0.15D0, 7.0D0,\n     +                  -0.03D0, 3.0D0/\n      DATA              ITRUE2/0, 1, 2, 2, 3/\n*     .. Executable Statements ..\n      DO 80 INCX = 1, 2\n         DO 60 NP1 = 1, 5\n            N = NP1 - 1\n            LEN = 2*MAX(N,1)\n*           .. Set vector arguments ..\n            DO 20 I = 1, LEN\n               SX(I) = DV(I,NP1,INCX)\n   20       CONTINUE\n*\n            IF (ICASE.EQ.7) THEN\n*              .. DNRM2 ..\n               STEMP(1) = DTRUE1(NP1)\n               CALL STEST1(DNRM2(N,SX,INCX),STEMP(1),STEMP,SFAC)\n            ELSE IF (ICASE.EQ.8) THEN\n*              .. DASUM ..\n               STEMP(1) = DTRUE3(NP1)\n               CALL STEST1(DASUM(N,SX,INCX),STEMP(1),STEMP,SFAC)\n            ELSE IF (ICASE.EQ.9) THEN\n*              .. DSCAL ..\n               CALL DSCAL(N,SA((INCX-1)*5+NP1),SX,INCX)\n               DO 40 I = 1, LEN\n                  STRUE(I) = DTRUE5(I,NP1,INCX)\n   40          CONTINUE\n               CALL STEST(LEN,SX,STRUE,STRUE,SFAC)\n            ELSE IF (ICASE.EQ.10) THEN\n*              .. IDAMAX ..\n               CALL ITEST1(IDAMAX(N,SX,INCX),ITRUE2(NP1))\n            ELSE\n               WRITE (NOUT,*) ' Shouldn''t be here in CHECK1'\n               STOP\n            END IF\n   60    CONTINUE\n   80 CONTINUE\n      RETURN\n      END\n      SUBROUTINE CHECK2(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION  SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      DOUBLE PRECISION  SA\n      INTEGER           I, J, KI, KN, KNI, KPAR, KSIZE, LENX, LENY,\n     $                  MX, MY \n*     .. Local Arrays ..\n      DOUBLE PRECISION  DT10X(7,4,4), DT10Y(7,4,4), DT7(4,4),\n     $                  DT8(7,4,4), DX1(7),\n     $                  DY1(7), SSIZE1(4), SSIZE2(14,2), SSIZE(7),\n     $                  STX(7), STY(7), SX(7), SY(7),\n     $                  DPAR(5,4), DT19X(7,4,16),DT19XA(7,4,4),\n     $                  DT19XB(7,4,4), DT19XC(7,4,4),DT19XD(7,4,4),\n     $                  DT19Y(7,4,16), DT19YA(7,4,4),DT19YB(7,4,4),\n     $                  DT19YC(7,4,4), DT19YD(7,4,4), DTEMP(5)\n      INTEGER           INCXS(4), INCYS(4), LENS(4,2), NS(4)\n*     .. External Functions ..\n      DOUBLE PRECISION  DDOT, DSDOT\n      EXTERNAL          DDOT, DSDOT\n*     .. External Subroutines ..\n      EXTERNAL          DAXPY, DCOPY, DROTM, DSWAP, STEST, STEST1\n*     .. Intrinsic Functions ..\n      INTRINSIC         ABS, MIN\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      EQUIVALENCE (DT19X(1,1,1),DT19XA(1,1,1)),(DT19X(1,1,5),\n     A   DT19XB(1,1,1)),(DT19X(1,1,9),DT19XC(1,1,1)),\n     B   (DT19X(1,1,13),DT19XD(1,1,1))\n      EQUIVALENCE (DT19Y(1,1,1),DT19YA(1,1,1)),(DT19Y(1,1,5),\n     A   DT19YB(1,1,1)),(DT19Y(1,1,9),DT19YC(1,1,1)),\n     B   (DT19Y(1,1,13),DT19YD(1,1,1))\n\n      DATA              SA/0.3D0/\n      DATA              INCXS/1, 2, -2, -1/\n      DATA              INCYS/1, -2, 1, -2/\n      DATA              LENS/1, 1, 2, 4, 1, 1, 3, 7/\n      DATA              NS/0, 1, 2, 4/\n      DATA              DX1/0.6D0, 0.1D0, -0.5D0, 0.8D0, 0.9D0, -0.3D0,\n     +                  -0.4D0/\n      DATA              DY1/0.5D0, -0.9D0, 0.3D0, 0.7D0, -0.6D0, 0.2D0,\n     +                  0.8D0/\n      DATA              DT7/0.0D0, 0.30D0, 0.21D0, 0.62D0, 0.0D0,\n     +                  0.30D0, -0.07D0, 0.85D0, 0.0D0, 0.30D0, -0.79D0,\n     +                  -0.74D0, 0.0D0, 0.30D0, 0.33D0, 1.27D0/\n      DATA              DT8/0.5D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.68D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.68D0, -0.87D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.68D0, -0.87D0, 0.15D0,\n     +                  0.94D0, 0.0D0, 0.0D0, 0.0D0, 0.5D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.68D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.35D0, -0.9D0, 0.48D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.38D0, -0.9D0, 0.57D0, 0.7D0, -0.75D0,\n     +                  0.2D0, 0.98D0, 0.5D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.68D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.35D0, -0.72D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.38D0,\n     +                  -0.63D0, 0.15D0, 0.88D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.5D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.68D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.68D0, -0.9D0, 0.33D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.68D0, -0.9D0, 0.33D0, 0.7D0,\n     +                  -0.75D0, 0.2D0, 1.04D0/\n      DATA              DT10X/0.6D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.5D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.5D0, -0.9D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.5D0, -0.9D0, 0.3D0, 0.7D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.6D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.5D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.3D0, 0.1D0, 0.5D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.8D0, 0.1D0, -0.6D0,\n     +                  0.8D0, 0.3D0, -0.3D0, 0.5D0, 0.6D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.5D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, -0.9D0,\n     +                  0.1D0, 0.5D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.7D0,\n     +                  0.1D0, 0.3D0, 0.8D0, -0.9D0, -0.3D0, 0.5D0,\n     +                  0.6D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.5D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.5D0, 0.3D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.5D0, 0.3D0, -0.6D0, 0.8D0, 0.0D0, 0.0D0,\n     +                  0.0D0/\n      DATA              DT10Y/0.5D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.6D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.6D0, 0.1D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.6D0, 0.1D0, -0.5D0, 0.8D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.5D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.6D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, -0.5D0, -0.9D0, 0.6D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, -0.4D0, -0.9D0, 0.9D0,\n     +                  0.7D0, -0.5D0, 0.2D0, 0.6D0, 0.5D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.6D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, -0.5D0,\n     +                  0.6D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  -0.4D0, 0.9D0, -0.5D0, 0.6D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.5D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.6D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.6D0, -0.9D0, 0.1D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.6D0, -0.9D0, 0.1D0, 0.7D0,\n     +                  -0.5D0, 0.2D0, 0.8D0/\n      DATA              SSIZE1/0.0D0, 0.3D0, 1.6D0, 3.2D0/\n      DATA              SSIZE2/0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 1.17D0, 1.17D0, 1.17D0, 1.17D0, 1.17D0,\n     +                  1.17D0, 1.17D0, 1.17D0, 1.17D0, 1.17D0, 1.17D0,\n     +                  1.17D0, 1.17D0, 1.17D0/\n*\n*                         FOR DROTM\n*\n      DATA DPAR/-2.D0,  0.D0,0.D0,0.D0,0.D0,\n     A          -1.D0,  2.D0, -3.D0, -4.D0,  5.D0,\n     B           0.D0,  0.D0,  2.D0, -3.D0,  0.D0,\n     C           1.D0,  5.D0,  2.D0,  0.D0, -4.D0/\n*                        TRUE X RESULTS F0R ROTATIONS DROTM\n      DATA DT19XA/.6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     A            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     B            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     C            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     D            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     E           -.8D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     F           -.9D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     G           3.5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     H            .6D0,   .1D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     I           -.8D0,  3.8D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     J           -.9D0,  2.8D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     K           3.5D0,  -.4D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     L            .6D0,   .1D0,  -.5D0,   .8D0,          0.D0,0.D0,0.D0,\n     M           -.8D0,  3.8D0, -2.2D0, -1.2D0,          0.D0,0.D0,0.D0,\n     N           -.9D0,  2.8D0, -1.4D0, -1.3D0,          0.D0,0.D0,0.D0,\n     O           3.5D0,  -.4D0, -2.2D0,  4.7D0,          0.D0,0.D0,0.D0/\n*\n      DATA DT19XB/.6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     A            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     B            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     C            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     D            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     E           -.8D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     F           -.9D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     G           3.5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     H            .6D0,   .1D0,  -.5D0,             0.D0,0.D0,0.D0,0.D0,\n     I           0.D0,    .1D0, -3.0D0,             0.D0,0.D0,0.D0,0.D0,\n     J           -.3D0,   .1D0, -2.0D0,             0.D0,0.D0,0.D0,0.D0,\n     K           3.3D0,   .1D0, -2.0D0,             0.D0,0.D0,0.D0,0.D0,\n     L            .6D0,   .1D0,  -.5D0,   .8D0,   .9D0,  -.3D0,  -.4D0,\n     M          -2.0D0,   .1D0,  1.4D0,   .8D0,   .6D0,  -.3D0, -2.8D0,\n     N          -1.8D0,   .1D0,  1.3D0,   .8D0,  0.D0,   -.3D0, -1.9D0,\n     O           3.8D0,   .1D0, -3.1D0,   .8D0,  4.8D0,  -.3D0, -1.5D0 /\n*\n      DATA DT19XC/.6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     A            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     B            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     C            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     D            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     E           -.8D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     F           -.9D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     G           3.5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     H            .6D0,   .1D0,  -.5D0,             0.D0,0.D0,0.D0,0.D0,\n     I           4.8D0,   .1D0, -3.0D0,             0.D0,0.D0,0.D0,0.D0,\n     J           3.3D0,   .1D0, -2.0D0,             0.D0,0.D0,0.D0,0.D0,\n     K           2.1D0,   .1D0, -2.0D0,             0.D0,0.D0,0.D0,0.D0,\n     L            .6D0,   .1D0,  -.5D0,   .8D0,   .9D0,  -.3D0,  -.4D0,\n     M          -1.6D0,   .1D0, -2.2D0,   .8D0,  5.4D0,  -.3D0, -2.8D0,\n     N          -1.5D0,   .1D0, -1.4D0,   .8D0,  3.6D0,  -.3D0, -1.9D0,\n     O           3.7D0,   .1D0, -2.2D0,   .8D0,  3.6D0,  -.3D0, -1.5D0 /\n*\n      DATA DT19XD/.6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     A            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     B            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     C            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     D            .6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     E           -.8D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     F           -.9D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     G           3.5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     H            .6D0,   .1D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     I           -.8D0, -1.0D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     J           -.9D0,  -.8D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     K           3.5D0,   .8D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     L            .6D0,   .1D0,  -.5D0,   .8D0,          0.D0,0.D0,0.D0,\n     M           -.8D0, -1.0D0,  1.4D0, -1.6D0,          0.D0,0.D0,0.D0,\n     N           -.9D0,  -.8D0,  1.3D0, -1.6D0,          0.D0,0.D0,0.D0,\n     O           3.5D0,   .8D0, -3.1D0,  4.8D0,          0.D0,0.D0,0.D0/\n*                        TRUE Y RESULTS FOR ROTATIONS DROTM\n      DATA DT19YA/.5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     A            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     B            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     C            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     D            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     E            .7D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     F           1.7D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     G          -2.6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     H            .5D0,  -.9D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     I            .7D0, -4.8D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     J           1.7D0,  -.7D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     K          -2.6D0,  3.5D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     L            .5D0,  -.9D0,   .3D0,   .7D0,          0.D0,0.D0,0.D0,\n     M            .7D0, -4.8D0,  3.0D0,  1.1D0,          0.D0,0.D0,0.D0,\n     N           1.7D0,  -.7D0,  -.7D0,  2.3D0,          0.D0,0.D0,0.D0,\n     O          -2.6D0,  3.5D0,  -.7D0, -3.6D0,          0.D0,0.D0,0.D0/\n*\n      DATA DT19YB/.5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     A            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     B            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     C            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     D            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     E            .7D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     F           1.7D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     G          -2.6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     H            .5D0,  -.9D0,   .3D0,             0.D0,0.D0,0.D0,0.D0,\n     I           4.0D0,  -.9D0,  -.3D0,             0.D0,0.D0,0.D0,0.D0,\n     J           -.5D0,  -.9D0,  1.5D0,             0.D0,0.D0,0.D0,0.D0,\n     K          -1.5D0,  -.9D0, -1.8D0,             0.D0,0.D0,0.D0,0.D0,\n     L            .5D0,  -.9D0,   .3D0,   .7D0,  -.6D0,   .2D0,   .8D0,\n     M           3.7D0,  -.9D0, -1.2D0,   .7D0, -1.5D0,   .2D0,  2.2D0,\n     N           -.3D0,  -.9D0,  2.1D0,   .7D0, -1.6D0,   .2D0,  2.0D0,\n     O          -1.6D0,  -.9D0, -2.1D0,   .7D0,  2.9D0,   .2D0, -3.8D0 /\n*\n      DATA DT19YC/.5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     A            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     B            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     C            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     D            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     E            .7D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     F           1.7D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     G          -2.6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     H            .5D0,  -.9D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     I           4.0D0, -6.3D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     J           -.5D0,   .3D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     K          -1.5D0,  3.0D0,             0.D0,0.D0,0.D0,0.D0,0.D0,\n     L            .5D0,  -.9D0,   .3D0,   .7D0,          0.D0,0.D0,0.D0,\n     M           3.7D0, -7.2D0,  3.0D0,  1.7D0,          0.D0,0.D0,0.D0,\n     N           -.3D0,   .9D0,  -.7D0,  1.9D0,          0.D0,0.D0,0.D0,\n     O          -1.6D0,  2.7D0,  -.7D0, -3.4D0,          0.D0,0.D0,0.D0/\n*\n      DATA DT19YD/.5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     A            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     B            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     C            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     D            .5D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     E            .7D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     F           1.7D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     G          -2.6D0,                  0.D0,0.D0,0.D0,0.D0,0.D0,0.D0,\n     H            .5D0,  -.9D0,   .3D0,             0.D0,0.D0,0.D0,0.D0,\n     I            .7D0,  -.9D0,  1.2D0,             0.D0,0.D0,0.D0,0.D0,\n     J           1.7D0,  -.9D0,   .5D0,             0.D0,0.D0,0.D0,0.D0,\n     K          -2.6D0,  -.9D0, -1.3D0,             0.D0,0.D0,0.D0,0.D0,\n     L            .5D0,  -.9D0,   .3D0,   .7D0,  -.6D0,   .2D0,   .8D0,\n     M            .7D0,  -.9D0,  1.2D0,   .7D0, -1.5D0,   .2D0,  1.6D0,\n     N           1.7D0,  -.9D0,   .5D0,   .7D0, -1.6D0,   .2D0,  2.4D0,\n     O          -2.6D0,  -.9D0, -1.3D0,   .7D0,  2.9D0,   .2D0, -4.0D0 /\n*    \n*     .. Executable Statements ..\n*\n      DO 120 KI = 1, 4\n         INCX = INCXS(KI)\n         INCY = INCYS(KI)\n         MX = ABS(INCX)\n         MY = ABS(INCY)\n*\n         DO 100 KN = 1, 4\n            N = NS(KN)\n            KSIZE = MIN(2,KN)\n            LENX = LENS(KN,MX)\n            LENY = LENS(KN,MY)\n*           .. Initialize all argument arrays ..\n            DO 20 I = 1, 7\n               SX(I) = DX1(I)\n               SY(I) = DY1(I)\n   20       CONTINUE\n*\n            IF (ICASE.EQ.1) THEN\n*              .. DDOT ..\n               CALL STEST1(DDOT(N,SX,INCX,SY,INCY),DT7(KN,KI),SSIZE1(KN)\n     +                     ,SFAC)\n            ELSE IF (ICASE.EQ.2) THEN\n*              .. DAXPY ..\n               CALL DAXPY(N,SA,SX,INCX,SY,INCY)\n               DO 40 J = 1, LENY\n                  STY(J) = DT8(J,KN,KI)\n   40          CONTINUE\n               CALL STEST(LENY,SY,STY,SSIZE2(1,KSIZE),SFAC)\n            ELSE IF (ICASE.EQ.5) THEN\n*              .. DCOPY ..\n               DO 60 I = 1, 7\n                  STY(I) = DT10Y(I,KN,KI)\n   60          CONTINUE\n               CALL DCOPY(N,SX,INCX,SY,INCY)\n               CALL STEST(LENY,SY,STY,SSIZE2(1,1),1.0D0)\n            ELSE IF (ICASE.EQ.6) THEN\n*              .. DSWAP ..\n               CALL DSWAP(N,SX,INCX,SY,INCY)\n               DO 80 I = 1, 7\n                  STX(I) = DT10X(I,KN,KI)\n                  STY(I) = DT10Y(I,KN,KI)\n   80          CONTINUE\n               CALL STEST(LENX,SX,STX,SSIZE2(1,1),1.0D0)\n               CALL STEST(LENY,SY,STY,SSIZE2(1,1),1.0D0)\n            ELSE IF (ICASE.EQ.12) THEN\n*              .. DROTM ..\n               KNI=KN+4*(KI-1)\n               DO KPAR=1,4\n                  DO I=1,7\n                     SX(I) = DX1(I)\n                     SY(I) = DY1(I)\n                     STX(I)= DT19X(I,KPAR,KNI)\n                     STY(I)= DT19Y(I,KPAR,KNI)\n                  END DO\n*\n                  DO I=1,5\n                     DTEMP(I) = DPAR(I,KPAR)\n                  END DO\n*\n                  DO  I=1,LENX\n                     SSIZE(I)=STX(I)\n                  END DO\n*                   SEE REMARK ABOVE ABOUT DT11X(1,2,7)\n*                       AND DT11X(5,3,8).\n                  IF ((KPAR .EQ. 2) .AND. (KNI .EQ. 7))\n     $               SSIZE(1) = 2.4D0\n                  IF ((KPAR .EQ. 3) .AND. (KNI .EQ. 8))\n     $               SSIZE(5) = 1.8D0\n*\n                  CALL   DROTM(N,SX,INCX,SY,INCY,DTEMP)\n                  CALL   STEST(LENX,SX,STX,SSIZE,SFAC)\n                  CALL   STEST(LENY,SY,STY,STY,SFAC)\n               END DO\n            ELSE IF (ICASE.EQ.13) THEN\n*              .. DSDOT ..\n            CALL TESTDSDOT(REAL(DSDOT(N,REAL(SX),INCX,REAL(SY),INCY)),\n     $                 REAL(DT7(KN,KI)),REAL(SSIZE1(KN)), .3125E-1)\n            ELSE\n               WRITE (NOUT,*) ' Shouldn''t be here in CHECK2'\n               STOP\n            END IF\n  100    CONTINUE\n  120 CONTINUE\n      RETURN\n      END\n      SUBROUTINE CHECK3(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION  SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      DOUBLE PRECISION  SC, SS\n      INTEGER           I, K, KI, KN, KSIZE, LENX, LENY, MX, MY\n*     .. Local Arrays ..\n      DOUBLE PRECISION  COPYX(5), COPYY(5), DT9X(7,4,4), DT9Y(7,4,4),\n     +                  DX1(7), DY1(7), MWPC(11), MWPS(11), MWPSTX(5),\n     +                  MWPSTY(5), MWPTX(11,5), MWPTY(11,5), MWPX(5),\n     +                  MWPY(5), SSIZE2(14,2), STX(7), STY(7), SX(7),\n     +                  SY(7)\n      INTEGER           INCXS(4), INCYS(4), LENS(4,2), MWPINX(11),\n     +                  MWPINY(11), MWPN(11), NS(4)\n*     .. External Subroutines ..\n      EXTERNAL          DROT, STEST\n*     .. Intrinsic Functions ..\n      INTRINSIC         ABS, MIN\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      DATA              INCXS/1, 2, -2, -1/\n      DATA              INCYS/1, -2, 1, -2/\n      DATA              LENS/1, 1, 2, 4, 1, 1, 3, 7/\n      DATA              NS/0, 1, 2, 4/\n      DATA              DX1/0.6D0, 0.1D0, -0.5D0, 0.8D0, 0.9D0, -0.3D0,\n     +                  -0.4D0/\n      DATA              DY1/0.5D0, -0.9D0, 0.3D0, 0.7D0, -0.6D0, 0.2D0,\n     +                  0.8D0/\n      DATA              SC, SS/0.8D0, 0.6D0/\n      DATA              DT9X/0.6D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.78D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.78D0, -0.46D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.78D0, -0.46D0, -0.22D0,\n     +                  1.06D0, 0.0D0, 0.0D0, 0.0D0, 0.6D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.78D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.66D0, 0.1D0, -0.1D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.96D0, 0.1D0, -0.76D0, 0.8D0, 0.90D0,\n     +                  -0.3D0, -0.02D0, 0.6D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.78D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, -0.06D0, 0.1D0,\n     +                  -0.1D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.90D0,\n     +                  0.1D0, -0.22D0, 0.8D0, 0.18D0, -0.3D0, -0.02D0,\n     +                  0.6D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.78D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.78D0, 0.26D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.78D0, 0.26D0, -0.76D0, 1.12D0,\n     +                  0.0D0, 0.0D0, 0.0D0/\n      DATA              DT9Y/0.5D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.04D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.04D0, -0.78D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.04D0, -0.78D0, 0.54D0,\n     +                  0.08D0, 0.0D0, 0.0D0, 0.0D0, 0.5D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.04D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.7D0,\n     +                  -0.9D0, -0.12D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.64D0, -0.9D0, -0.30D0, 0.7D0, -0.18D0, 0.2D0,\n     +                  0.28D0, 0.5D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.04D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.7D0, -1.08D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.64D0, -1.26D0,\n     +                  0.54D0, 0.20D0, 0.0D0, 0.0D0, 0.0D0, 0.5D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.04D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.04D0, -0.9D0, 0.18D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.04D0, -0.9D0, 0.18D0, 0.7D0,\n     +                  -0.18D0, 0.2D0, 0.16D0/\n      DATA              SSIZE2/0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0, 0.0D0,\n     +                  0.0D0, 1.17D0, 1.17D0, 1.17D0, 1.17D0, 1.17D0,\n     +                  1.17D0, 1.17D0, 1.17D0, 1.17D0, 1.17D0, 1.17D0,\n     +                  1.17D0, 1.17D0, 1.17D0/\n*     .. Executable Statements ..\n*\n      DO 60 KI = 1, 4\n         INCX = INCXS(KI)\n         INCY = INCYS(KI)\n         MX = ABS(INCX)\n         MY = ABS(INCY)\n*\n         DO 40 KN = 1, 4\n            N = NS(KN)\n            KSIZE = MIN(2,KN)\n            LENX = LENS(KN,MX)\n            LENY = LENS(KN,MY)\n*\n            IF (ICASE.EQ.4) THEN\n*              .. DROT ..\n               DO 20 I = 1, 7\n                  SX(I) = DX1(I)\n                  SY(I) = DY1(I)\n                  STX(I) = DT9X(I,KN,KI)\n                  STY(I) = DT9Y(I,KN,KI)\n   20          CONTINUE\n               CALL DROT(N,SX,INCX,SY,INCY,SC,SS)\n               CALL STEST(LENX,SX,STX,SSIZE2(1,KSIZE),SFAC)\n               CALL STEST(LENY,SY,STY,SSIZE2(1,KSIZE),SFAC)\n            ELSE\n               WRITE (NOUT,*) ' Shouldn''t be here in CHECK3'\n               STOP\n            END IF\n   40    CONTINUE\n   60 CONTINUE\n*\n      MWPC(1) = 1\n      DO 80 I = 2, 11\n         MWPC(I) = 0\n   80 CONTINUE\n      MWPS(1) = 0\n      DO 100 I = 2, 6\n         MWPS(I) = 1\n  100 CONTINUE\n      DO 120 I = 7, 11\n         MWPS(I) = -1\n  120 CONTINUE\n      MWPINX(1) = 1\n      MWPINX(2) = 1\n      MWPINX(3) = 1\n      MWPINX(4) = -1\n      MWPINX(5) = 1\n      MWPINX(6) = -1\n      MWPINX(7) = 1\n      MWPINX(8) = 1\n      MWPINX(9) = -1\n      MWPINX(10) = 1\n      MWPINX(11) = -1\n      MWPINY(1) = 1\n      MWPINY(2) = 1\n      MWPINY(3) = -1\n      MWPINY(4) = -1\n      MWPINY(5) = 2\n      MWPINY(6) = 1\n      MWPINY(7) = 1\n      MWPINY(8) = -1\n      MWPINY(9) = -1\n      MWPINY(10) = 2\n      MWPINY(11) = 1\n      DO 140 I = 1, 11\n         MWPN(I) = 5\n  140 CONTINUE\n      MWPN(5) = 3\n      MWPN(10) = 3\n      DO 160 I = 1, 5\n         MWPX(I) = I\n         MWPY(I) = I\n         MWPTX(1,I) = I\n         MWPTY(1,I) = I\n         MWPTX(2,I) = I\n         MWPTY(2,I) = -I\n         MWPTX(3,I) = 6 - I\n         MWPTY(3,I) = I - 6\n         MWPTX(4,I) = I\n         MWPTY(4,I) = -I\n         MWPTX(6,I) = 6 - I\n         MWPTY(6,I) = I - 6\n         MWPTX(7,I) = -I\n         MWPTY(7,I) = I\n         MWPTX(8,I) = I - 6\n         MWPTY(8,I) = 6 - I\n         MWPTX(9,I) = -I\n         MWPTY(9,I) = I\n         MWPTX(11,I) = I - 6\n         MWPTY(11,I) = 6 - I\n  160 CONTINUE\n      MWPTX(5,1) = 1\n      MWPTX(5,2) = 3\n      MWPTX(5,3) = 5\n      MWPTX(5,4) = 4\n      MWPTX(5,5) = 5\n      MWPTY(5,1) = -1\n      MWPTY(5,2) = 2\n      MWPTY(5,3) = -2\n      MWPTY(5,4) = 4\n      MWPTY(5,5) = -3\n      MWPTX(10,1) = -1\n      MWPTX(10,2) = -3\n      MWPTX(10,3) = -5\n      MWPTX(10,4) = 4\n      MWPTX(10,5) = 5\n      MWPTY(10,1) = 1\n      MWPTY(10,2) = 2\n      MWPTY(10,3) = 2\n      MWPTY(10,4) = 4\n      MWPTY(10,5) = 3\n      DO 200 I = 1, 11\n         INCX = MWPINX(I)\n         INCY = MWPINY(I)\n         DO 180 K = 1, 5\n            COPYX(K) = MWPX(K)\n            COPYY(K) = MWPY(K)\n            MWPSTX(K) = MWPTX(I,K)\n            MWPSTY(K) = MWPTY(I,K)\n  180    CONTINUE\n         CALL DROT(MWPN(I),COPYX,INCX,COPYY,INCY,MWPC(I),MWPS(I))\n         CALL STEST(5,COPYX,MWPSTX,MWPSTX,SFAC)\n         CALL STEST(5,COPYY,MWPSTY,MWPSTY,SFAC)\n  200 CONTINUE\n      RETURN\n      END\n      SUBROUTINE STEST(LEN,SCOMP,STRUE,SSIZE,SFAC)\n*     ********************************* STEST **************************\n*\n*     THIS SUBR COMPARES ARRAYS  SCOMP() AND STRUE() OF LENGTH LEN TO\n*     SEE IF THE TERM BY TERM DIFFERENCES, MULTIPLIED BY SFAC, ARE\n*     NEGLIGIBLE.\n*\n*     C. L. LAWSON, JPL, 1974 DEC 10\n*\n*     .. Parameters ..\n      INTEGER          NOUT\n      DOUBLE PRECISION ZERO\n      PARAMETER        (NOUT=6, ZERO=0.0D0)\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION SFAC\n      INTEGER          LEN\n*     .. Array Arguments ..\n      DOUBLE PRECISION SCOMP(LEN), SSIZE(LEN), STRUE(LEN)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, N\n      LOGICAL          PASS\n*     .. Local Scalars ..\n      DOUBLE PRECISION SD\n      INTEGER          I\n*     .. External Functions ..\n      DOUBLE PRECISION SDIFF\n      EXTERNAL         SDIFF\n*     .. Intrinsic Functions ..\n      INTRINSIC        ABS\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Executable Statements ..\n*\n      DO 40 I = 1, LEN\n         SD = SCOMP(I) - STRUE(I)\n         IF (ABS(SFAC*SD) .LE. ABS(SSIZE(I))*EPSILON(ZERO))\n     +       GO TO 40\n*\n*                             HERE    SCOMP(I) IS NOT CLOSE TO STRUE(I).\n*\n         IF ( .NOT. PASS) GO TO 20\n*                             PRINT FAIL MESSAGE AND HEADER.\n         PASS = .FALSE.\n         WRITE (NOUT,99999)\n         WRITE (NOUT,99998)\n   20    WRITE (NOUT,99997) ICASE, N, INCX, INCY, I, SCOMP(I),\n     +     STRUE(I), SD, SSIZE(I)\n   40 CONTINUE\n      RETURN\n*\n99999 FORMAT ('                                       FAIL')\n99998 FORMAT (/' CASE  N INCX INCY  I                            ',\n     +       ' COMP(I)                             TRUE(I)  DIFFERENCE',\n     +       '     SIZE(I)',/1X)\n99997 FORMAT (1X,I4,I3,2I5,I3,2D36.8,2D12.4)\n      END\n      SUBROUTINE TESTDSDOT(SCOMP,STRUE,SSIZE,SFAC)\n*     ********************************* STEST **************************\n*\n*     THIS SUBR COMPARES ARRAYS  SCOMP() AND STRUE() OF LENGTH LEN TO\n*     SEE IF THE TERM BY TERM DIFFERENCES, MULTIPLIED BY SFAC, ARE\n*     NEGLIGIBLE.\n*\n*     C. L. LAWSON, JPL, 1974 DEC 10\n*\n*     .. Parameters ..\n      INTEGER          NOUT\n      REAL             ZERO\n      PARAMETER        (NOUT=6, ZERO=0.0E0)\n*     .. Scalar Arguments ..\n      REAL             SFAC, SCOMP, SSIZE, STRUE\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, N\n      LOGICAL          PASS\n*     .. Local Scalars ..\n      REAL             SD\n*     .. Intrinsic Functions ..\n      INTRINSIC        ABS\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Executable Statements ..\n*\n         SD = SCOMP - STRUE\n         IF (ABS(SFAC*SD) .LE. ABS(SSIZE) * EPSILON(ZERO))\n     +       GO TO 40\n*\n*                             HERE    SCOMP(I) IS NOT CLOSE TO STRUE(I).\n*\n         IF ( .NOT. PASS) GO TO 20\n*                             PRINT FAIL MESSAGE AND HEADER.\n         PASS = .FALSE.\n         WRITE (NOUT,99999)\n         WRITE (NOUT,99998)\n   20    WRITE (NOUT,99997) ICASE, N, INCX, INCY, SCOMP,\n     +     STRUE, SD, SSIZE\n   40 CONTINUE\n      RETURN\n*\n99999 FORMAT ('                                       FAIL')\n99998 FORMAT (/' CASE  N INCX INCY                           ',\n     +       ' COMP(I)                             TRUE(I)  DIFFERENCE',\n     +       '     SIZE(I)',/1X)\n99997 FORMAT (1X,I4,I3,1I5,I3,2E36.8,2E12.4)\n      END\n      SUBROUTINE STEST1(SCOMP1,STRUE1,SSIZE,SFAC)\n*     ************************* STEST1 *****************************\n*\n*     THIS IS AN INTERFACE SUBROUTINE TO ACCOMMODATE THE FORTRAN\n*     REQUIREMENT THAT WHEN A DUMMY ARGUMENT IS AN ARRAY, THE\n*     ACTUAL ARGUMENT MUST ALSO BE AN ARRAY OR AN ARRAY ELEMENT.\n*\n*     C.L. LAWSON, JPL, 1978 DEC 6\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION  SCOMP1, SFAC, STRUE1\n*     .. Array Arguments ..\n      DOUBLE PRECISION  SSIZE(*)\n*     .. Local Arrays ..\n      DOUBLE PRECISION  SCOMP(1), STRUE(1)\n*     .. External Subroutines ..\n      EXTERNAL          STEST\n*     .. Executable Statements ..\n*\n      SCOMP(1) = SCOMP1\n      STRUE(1) = STRUE1\n      CALL STEST(1,SCOMP,STRUE,SSIZE,SFAC)\n*\n      RETURN\n      END\n      DOUBLE PRECISION FUNCTION SDIFF(SA,SB)\n*     ********************************* SDIFF **************************\n*     COMPUTES DIFFERENCE OF TWO NUMBERS.  C. L. LAWSON, JPL 1974 FEB 15\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION                SA, SB\n*     .. Executable Statements ..\n      SDIFF = SA - SB\n      RETURN\n      END\n      SUBROUTINE ITEST1(ICOMP,ITRUE)\n*     ********************************* ITEST1 *************************\n*\n*     THIS SUBROUTINE COMPARES THE VARIABLES ICOMP AND ITRUE FOR\n*     EQUALITY.\n*     C. L. LAWSON, JPL, 1974 DEC 10\n*\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      INTEGER           ICOMP, ITRUE\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      INTEGER           ID\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Executable Statements ..\n*\n      IF (ICOMP.EQ.ITRUE) GO TO 40\n*\n*                            HERE ICOMP IS NOT EQUAL TO ITRUE.\n*\n      IF ( .NOT. PASS) GO TO 20\n*                             PRINT FAIL MESSAGE AND HEADER.\n      PASS = .FALSE.\n      WRITE (NOUT,99999)\n      WRITE (NOUT,99998)\n   20 ID = ICOMP - ITRUE\n      WRITE (NOUT,99997) ICASE, N, INCX, INCY, ICOMP, ITRUE, ID\n   40 CONTINUE\n      RETURN\n*\n99999 FORMAT ('                                       FAIL')\n99998 FORMAT (/' CASE  N INCX INCY                               ',\n     +       ' COMP                                TRUE     DIFFERENCE',\n     +       /1X)\n99997 FORMAT (1X,I4,I3,2I5,2I36,I12)\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/testing/dblat2.f",
    "content": "*> \\brief \\b DBLAT2\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM DBLAT2\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> Test program for the DOUBLE PRECISION Level 2 Blas.\n*>\n*> The program must be driven by a short data file. The first 18 records\n*> of the file are read using list-directed input, the last 16 records\n*> are read using the format ( A6, L2 ). An annotated example of a data\n*> file can be obtained by deleting the first 3 characters from the\n*> following 34 lines:\n*> 'dblat2.out'      NAME OF SUMMARY OUTPUT FILE\n*> 6                 UNIT NUMBER OF SUMMARY FILE\n*> 'DBLAT2.SNAP'     NAME OF SNAPSHOT OUTPUT FILE\n*> -1                UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0)\n*> F        LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD.\n*> F        LOGICAL FLAG, T TO STOP ON FAILURES.\n*> T        LOGICAL FLAG, T TO TEST ERROR EXITS.\n*> 16.0     THRESHOLD VALUE OF TEST RATIO\n*> 6                 NUMBER OF VALUES OF N\n*> 0 1 2 3 5 9       VALUES OF N\n*> 4                 NUMBER OF VALUES OF K\n*> 0 1 2 4           VALUES OF K\n*> 4                 NUMBER OF VALUES OF INCX AND INCY\n*> 1 2 -1 -2         VALUES OF INCX AND INCY\n*> 3                 NUMBER OF VALUES OF ALPHA\n*> 0.0 1.0 0.7       VALUES OF ALPHA\n*> 3                 NUMBER OF VALUES OF BETA\n*> 0.0 1.0 0.9       VALUES OF BETAC\n*> DGEMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DGBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DSYMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DSBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DSPMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DTRMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DTBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DTPMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DTRSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DTBSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DTPSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DGER   T PUT F FOR NO TEST. SAME COLUMNS.\n*> DSYR   T PUT F FOR NO TEST. SAME COLUMNS.\n*> DSPR   T PUT F FOR NO TEST. SAME COLUMNS.\n*> DSYR2  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DSPR2  T PUT F FOR NO TEST. SAME COLUMNS.\n*>\n*> Further Details\n*> ===============\n*>\n*>    See:\n*>\n*>       Dongarra J. J., Du Croz J. J., Hammarling S.  and Hanson R. J..\n*>       An  extended  set of Fortran  Basic Linear Algebra Subprograms.\n*>\n*>       Technical  Memoranda  Nos. 41 (revision 3) and 81,  Mathematics\n*>       and  Computer Science  Division,  Argonne  National Laboratory,\n*>       9700 South Cass Avenue, Argonne, Illinois 60439, US.\n*>\n*>       Or\n*>\n*>       NAG  Technical Reports TR3/87 and TR4/87,  Numerical Algorithms\n*>       Group  Ltd.,  NAG  Central  Office,  256  Banbury  Road, Oxford\n*>       OX2 7DE, UK,  and  Numerical Algorithms Group Inc.,  1101  31st\n*>       Street,  Suite 100,  Downers Grove,  Illinois 60515-1263,  USA.\n*>\n*>\n*> -- Written on 10-August-1987.\n*>    Richard Hanson, Sandia National Labs.\n*>    Jeremy Du Croz, NAG Central Office.\n*>\n*>    10-9-00:  Change STATUS='NEW' to 'UNKNOWN' so that the testers\n*>              can be run multiple times without deleting generated\n*>              output files (susan)\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup double_blas_testing\n*\n*  =====================================================================\n      PROGRAM DBLAT2\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER            NIN\n      PARAMETER          ( NIN = 5 )\n      INTEGER            NSUBS\n      PARAMETER          ( NSUBS = 16 )\n      DOUBLE PRECISION   ZERO, ONE\n      PARAMETER          ( ZERO = 0.0D0, ONE = 1.0D0 )\n      INTEGER            NMAX, INCMAX\n      PARAMETER          ( NMAX = 65, INCMAX = 2 )\n      INTEGER            NINMAX, NIDMAX, NKBMAX, NALMAX, NBEMAX\n      PARAMETER          ( NINMAX = 7, NIDMAX = 9, NKBMAX = 7,\n     $                   NALMAX = 7, NBEMAX = 7 )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   EPS, ERR, THRESH\n      INTEGER            I, ISNUM, J, N, NALF, NBET, NIDIM, NINC, NKB,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, LTESTT, REWI, SAME, SFATAL, TRACE,\n     $                   TSTERR\n      CHARACTER*1        TRANS\n      CHARACTER*6        SNAMET\n      CHARACTER*32       SNAPS, SUMMRY\n*     .. Local Arrays ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ),\n     $                   ALF( NALMAX ), AS( NMAX*NMAX ), BET( NBEMAX ),\n     $                   G( NMAX ), X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( 2*NMAX )\n      INTEGER            IDIM( NIDMAX ), INC( NINMAX ), KB( NKBMAX )\n      LOGICAL            LTEST( NSUBS )\n      CHARACTER*6        SNAMES( NSUBS )\n*     .. External Functions ..\n      DOUBLE PRECISION   DDIFF\n      LOGICAL            LDE\n      EXTERNAL           DDIFF, LDE\n*     .. External Subroutines ..\n      EXTERNAL           DCHK1, DCHK2, DCHK3, DCHK4, DCHK5, DCHK6,\n     $                   DCHKE, DMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Data statements ..\n      DATA               SNAMES/'DGEMV ', 'DGBMV ', 'DSYMV ', 'DSBMV ',\n     $                   'DSPMV ', 'DTRMV ', 'DTBMV ', 'DTPMV ',\n     $                   'DTRSV ', 'DTBSV ', 'DTPSV ', 'DGER  ',\n     $                   'DSYR  ', 'DSPR  ', 'DSYR2 ', 'DSPR2 '/\n*     .. Executable Statements ..\n*\n*     Read name and unit number for summary output file and open file.\n*\n      READ( NIN, FMT = * )SUMMRY\n      READ( NIN, FMT = * )NOUT\n      OPEN( NOUT, FILE = SUMMRY, STATUS = 'UNKNOWN' )\n      NOUTC = NOUT\n*\n*     Read name and unit number for snapshot output file and open file.\n*\n      READ( NIN, FMT = * )SNAPS\n      READ( NIN, FMT = * )NTRA\n      TRACE = NTRA.GE.0\n      IF( TRACE )THEN\n         OPEN( NTRA, FILE = SNAPS, STATUS = 'UNKNOWN' )\n      END IF\n*     Read the flag that directs rewinding of the snapshot file.\n      READ( NIN, FMT = * )REWI\n      REWI = REWI.AND.TRACE\n*     Read the flag that directs stopping on any failure.\n      READ( NIN, FMT = * )SFATAL\n*     Read the flag that indicates whether error exits are to be tested.\n      READ( NIN, FMT = * )TSTERR\n*     Read the threshold value of the test ratio\n      READ( NIN, FMT = * )THRESH\n*\n*     Read and check the parameter values for the tests.\n*\n*     Values of N\n      READ( NIN, FMT = * )NIDIM\n      IF( NIDIM.LT.1.OR.NIDIM.GT.NIDMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'N', NIDMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( IDIM( I ), I = 1, NIDIM )\n      DO 10 I = 1, NIDIM\n         IF( IDIM( I ).LT.0.OR.IDIM( I ).GT.NMAX )THEN\n            WRITE( NOUT, FMT = 9996 )NMAX\n            GO TO 230\n         END IF\n   10 CONTINUE\n*     Values of K\n      READ( NIN, FMT = * )NKB\n      IF( NKB.LT.1.OR.NKB.GT.NKBMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'K', NKBMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( KB( I ), I = 1, NKB )\n      DO 20 I = 1, NKB\n         IF( KB( I ).LT.0 )THEN\n            WRITE( NOUT, FMT = 9995 )\n            GO TO 230\n         END IF\n   20 CONTINUE\n*     Values of INCX and INCY\n      READ( NIN, FMT = * )NINC\n      IF( NINC.LT.1.OR.NINC.GT.NINMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'INCX AND INCY', NINMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( INC( I ), I = 1, NINC )\n      DO 30 I = 1, NINC\n         IF( INC( I ).EQ.0.OR.ABS( INC( I ) ).GT.INCMAX )THEN\n            WRITE( NOUT, FMT = 9994 )INCMAX\n            GO TO 230\n         END IF\n   30 CONTINUE\n*     Values of ALPHA\n      READ( NIN, FMT = * )NALF\n      IF( NALF.LT.1.OR.NALF.GT.NALMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'ALPHA', NALMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( ALF( I ), I = 1, NALF )\n*     Values of BETA\n      READ( NIN, FMT = * )NBET\n      IF( NBET.LT.1.OR.NBET.GT.NBEMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'BETA', NBEMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( BET( I ), I = 1, NBET )\n*\n*     Report values of parameters.\n*\n      WRITE( NOUT, FMT = 9993 )\n      WRITE( NOUT, FMT = 9992 )( IDIM( I ), I = 1, NIDIM )\n      WRITE( NOUT, FMT = 9991 )( KB( I ), I = 1, NKB )\n      WRITE( NOUT, FMT = 9990 )( INC( I ), I = 1, NINC )\n      WRITE( NOUT, FMT = 9989 )( ALF( I ), I = 1, NALF )\n      WRITE( NOUT, FMT = 9988 )( BET( I ), I = 1, NBET )\n      IF( .NOT.TSTERR )THEN\n         WRITE( NOUT, FMT = * )\n         WRITE( NOUT, FMT = 9980 )\n      END IF\n      WRITE( NOUT, FMT = * )\n      WRITE( NOUT, FMT = 9999 )THRESH\n      WRITE( NOUT, FMT = * )\n*\n*     Read names of subroutines and flags which indicate\n*     whether they are to be tested.\n*\n      DO 40 I = 1, NSUBS\n         LTEST( I ) = .FALSE.\n   40 CONTINUE\n   50 READ( NIN, FMT = 9984, END = 80 )SNAMET, LTESTT\n      DO 60 I = 1, NSUBS\n         IF( SNAMET.EQ.SNAMES( I ) )\n     $      GO TO 70\n   60 CONTINUE\n      WRITE( NOUT, FMT = 9986 )SNAMET\n      STOP\n   70 LTEST( I ) = LTESTT\n      GO TO 50\n*\n   80 CONTINUE\n      CLOSE ( NIN )\n*\n*     Compute EPS (the machine precision).\n*\n      EPS = EPSILON(ZERO)\n      WRITE( NOUT, FMT = 9998 )EPS\n*\n*     Check the reliability of DMVCH using exact data.\n*\n      N = MIN( 32, NMAX )\n      DO 120 J = 1, N\n         DO 110 I = 1, N\n            A( I, J ) = MAX( I - J + 1, 0 )\n  110    CONTINUE\n         X( J ) = J\n         Y( J ) = ZERO\n  120 CONTINUE\n      DO 130 J = 1, N\n         YY( J ) = J*( ( J + 1 )*J )/2 - ( ( J + 1 )*J*( J - 1 ) )/3\n  130 CONTINUE\n*     YY holds the exact result. On exit from DMVCH YT holds\n*     the result computed by DMVCH.\n      TRANS = 'N'\n      CALL DMVCH( TRANS, N, N, ONE, A, NMAX, X, 1, ZERO, Y, 1, YT, G,\n     $            YY, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LDE( YY, YT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9985 )TRANS, SAME, ERR\n         STOP\n      END IF\n      TRANS = 'T'\n      CALL DMVCH( TRANS, N, N, ONE, A, NMAX, X, -1, ZERO, Y, -1, YT, G,\n     $            YY, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LDE( YY, YT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9985 )TRANS, SAME, ERR\n         STOP\n      END IF\n*\n*     Test each subroutine in turn.\n*\n      DO 210 ISNUM = 1, NSUBS\n         WRITE( NOUT, FMT = * )\n         IF( .NOT.LTEST( ISNUM ) )THEN\n*           Subprogram is not to be tested.\n            WRITE( NOUT, FMT = 9983 )SNAMES( ISNUM )\n         ELSE\n            SRNAMT = SNAMES( ISNUM )\n*           Test error exits.\n            IF( TSTERR )THEN\n               CALL DCHKE( ISNUM, SNAMES( ISNUM ), NOUT )\n               WRITE( NOUT, FMT = * )\n            END IF\n*           Test computations.\n            INFOT = 0\n            OK = .TRUE.\n            FATAL = .FALSE.\n            GO TO ( 140, 140, 150, 150, 150, 160, 160,\n     $              160, 160, 160, 160, 170, 180, 180,\n     $              190, 190 )ISNUM\n*           Test DGEMV, 01, and DGBMV, 02.\n  140       CALL DCHK1( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF,\n     $                  NBET, BET, NINC, INC, NMAX, INCMAX, A, AA, AS,\n     $                  X, XX, XS, Y, YY, YS, YT, G )\n            GO TO 200\n*           Test DSYMV, 03, DSBMV, 04, and DSPMV, 05.\n  150       CALL DCHK2( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF,\n     $                  NBET, BET, NINC, INC, NMAX, INCMAX, A, AA, AS,\n     $                  X, XX, XS, Y, YY, YS, YT, G )\n            GO TO 200\n*           Test DTRMV, 06, DTBMV, 07, DTPMV, 08,\n*           DTRSV, 09, DTBSV, 10, and DTPSV, 11.\n  160       CALL DCHK3( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, Y, YY, YS, YT, G, Z )\n            GO TO 200\n*           Test DGER, 12.\n  170       CALL DCHK4( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n            GO TO 200\n*           Test DSYR, 13, and DSPR, 14.\n  180       CALL DCHK5( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n            GO TO 200\n*           Test DSYR2, 15, and DSPR2, 16.\n  190       CALL DCHK6( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n*\n  200       IF( FATAL.AND.SFATAL )\n     $         GO TO 220\n         END IF\n  210 CONTINUE\n      WRITE( NOUT, FMT = 9982 )\n      GO TO 240\n*\n  220 CONTINUE\n      WRITE( NOUT, FMT = 9981 )\n      GO TO 240\n*\n  230 CONTINUE\n      WRITE( NOUT, FMT = 9987 )\n*\n  240 CONTINUE\n      IF( TRACE )\n     $   CLOSE ( NTRA )\n      CLOSE ( NOUT )\n      STOP\n*\n 9999 FORMAT( ' ROUTINES PASS COMPUTATIONAL TESTS IF TEST RATIO IS LES',\n     $      'S THAN', F8.2 )\n 9998 FORMAT( ' RELATIVE MACHINE PRECISION IS TAKEN TO BE', 1P, D9.1 )\n 9997 FORMAT( ' NUMBER OF VALUES OF ', A, ' IS LESS THAN 1 OR GREATER ',\n     $      'THAN ', I2 )\n 9996 FORMAT( ' VALUE OF N IS LESS THAN 0 OR GREATER THAN ', I2 )\n 9995 FORMAT( ' VALUE OF K IS LESS THAN 0' )\n 9994 FORMAT( ' ABSOLUTE VALUE OF INCX OR INCY IS 0 OR GREATER THAN ',\n     $      I2 )\n 9993 FORMAT( ' TESTS OF THE DOUBLE PRECISION LEVEL 2 BLAS', //' THE F',\n     $      'OLLOWING PARAMETER VALUES WILL BE USED:' )\n 9992 FORMAT( '   FOR N              ', 9I6 )\n 9991 FORMAT( '   FOR K              ', 7I6 )\n 9990 FORMAT( '   FOR INCX AND INCY  ', 7I6 )\n 9989 FORMAT( '   FOR ALPHA          ', 7F6.1 )\n 9988 FORMAT( '   FOR BETA           ', 7F6.1 )\n 9987 FORMAT( ' AMEND DATA FILE OR INCREASE ARRAY SIZES IN PROGRAM',\n     $      /' ******* TESTS ABANDONED *******' )\n 9986 FORMAT( ' SUBPROGRAM NAME ', A6, ' NOT RECOGNIZED', /' ******* T',\n     $      'ESTS ABANDONED *******' )\n 9985 FORMAT( ' ERROR IN DMVCH -  IN-LINE DOT PRODUCTS ARE BEING EVALU',\n     $      'ATED WRONGLY.', /' DMVCH WAS CALLED WITH TRANS = ', A1,\n     $      ' AND RETURNED SAME = ', L1, ' AND ERR = ', F12.3, '.', /\n     $   ' THIS MAY BE DUE TO FAULTS IN THE ARITHMETIC OR THE COMPILER.'\n     $      , /' ******* TESTS ABANDONED *******' )\n 9984 FORMAT( A6, L2 )\n 9983 FORMAT( 1X, A6, ' WAS NOT TESTED' )\n 9982 FORMAT( /' END OF TESTS' )\n 9981 FORMAT( /' ******* FATAL ERROR - TESTS ABANDONED *******' )\n 9980 FORMAT( ' ERROR-EXITS WILL NOT BE TESTED' )\n*\n*     End of DBLAT2.\n*\n      END\n      SUBROUTINE DCHK1( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF, NBET,\n     $                  BET, NINC, INC, NMAX, INCMAX, A, AA, AS, X, XX,\n     $                  XS, Y, YY, YS, YT, G )\n*\n*  Tests DGEMV and DGBMV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, HALF\n      PARAMETER          ( ZERO = 0.0D0, HALF = 0.5D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NALF, NBET, NIDIM, NINC, NKB, NMAX,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), BET( NBET ), G( NMAX ),\n     $                   X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, ALS, BETA, BLS, ERR, ERRMAX, TRANSL\n      INTEGER            I, IA, IB, IC, IKU, IM, IN, INCX, INCXS, INCY,\n     $                   INCYS, IX, IY, KL, KLS, KU, KUS, LAA, LDA,\n     $                   LDAS, LX, LY, M, ML, MS, N, NARGS, NC, ND, NK,\n     $                   NL, NS\n      LOGICAL            BANDED, FULL, NULL, RESET, SAME, TRAN\n      CHARACTER*1        TRANS, TRANSS\n      CHARACTER*3        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DGBMV, DGEMV, DMAKE, DMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'NTC'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'E'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 11\n      ELSE IF( BANDED )THEN\n         NARGS = 13\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 120 IN = 1, NIDIM\n         N = IDIM( IN )\n         ND = N/2 + 1\n*\n         DO 110 IM = 1, 2\n            IF( IM.EQ.1 )\n     $         M = MAX( N - ND, 0 )\n            IF( IM.EQ.2 )\n     $         M = MIN( N + ND, NMAX )\n*\n            IF( BANDED )THEN\n               NK = NKB\n            ELSE\n               NK = 1\n            END IF\n            DO 100 IKU = 1, NK\n               IF( BANDED )THEN\n                  KU = KB( IKU )\n                  KL = MAX( KU - 1, 0 )\n               ELSE\n                  KU = N - 1\n                  KL = M - 1\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               IF( BANDED )THEN\n                  LDA = KL + KU + 1\n               ELSE\n                  LDA = M\n               END IF\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 100\n               LAA = LDA*N\n               NULL = N.LE.0.OR.M.LE.0\n*\n*              Generate the matrix A.\n*\n               TRANSL = ZERO\n               CALL DMAKE( SNAME( 2: 3 ), ' ', ' ', M, N, A, NMAX, AA,\n     $                     LDA, KL, KU, RESET, TRANSL )\n*\n               DO 90 IC = 1, 3\n                  TRANS = ICH( IC: IC )\n                  TRAN = TRANS.EQ.'T'.OR.TRANS.EQ.'C'\n*\n                  IF( TRAN )THEN\n                     ML = N\n                     NL = M\n                  ELSE\n                     ML = M\n                     NL = N\n                  END IF\n*\n                  DO 80 IX = 1, NINC\n                     INCX = INC( IX )\n                     LX = ABS( INCX )*NL\n*\n*                    Generate the vector X.\n*\n                     TRANSL = HALF\n                     CALL DMAKE( 'GE', ' ', ' ', 1, NL, X, 1, XX,\n     $                           ABS( INCX ), 0, NL - 1, RESET, TRANSL )\n                     IF( NL.GT.1 )THEN\n                        X( NL/2 ) = ZERO\n                        XX( 1 + ABS( INCX )*( NL/2 - 1 ) ) = ZERO\n                     END IF\n*\n                     DO 70 IY = 1, NINC\n                        INCY = INC( IY )\n                        LY = ABS( INCY )*ML\n*\n                        DO 60 IA = 1, NALF\n                           ALPHA = ALF( IA )\n*\n                           DO 50 IB = 1, NBET\n                              BETA = BET( IB )\n*\n*                             Generate the vector Y.\n*\n                              TRANSL = ZERO\n                              CALL DMAKE( 'GE', ' ', ' ', 1, ML, Y, 1,\n     $                                    YY, ABS( INCY ), 0, ML - 1,\n     $                                    RESET, TRANSL )\n*\n                              NC = NC + 1\n*\n*                             Save every datum before calling the\n*                             subroutine.\n*\n                              TRANSS = TRANS\n                              MS = M\n                              NS = N\n                              KLS = KL\n                              KUS = KU\n                              ALS = ALPHA\n                              DO 10 I = 1, LAA\n                                 AS( I ) = AA( I )\n   10                         CONTINUE\n                              LDAS = LDA\n                              DO 20 I = 1, LX\n                                 XS( I ) = XX( I )\n   20                         CONTINUE\n                              INCXS = INCX\n                              BLS = BETA\n                              DO 30 I = 1, LY\n                                 YS( I ) = YY( I )\n   30                         CONTINUE\n                              INCYS = INCY\n*\n*                             Call the subroutine.\n*\n                              IF( FULL )THEN\n                                 IF( TRACE )\n     $                              WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                              TRANS, M, N, ALPHA, LDA, INCX, BETA,\n     $                              INCY\n                                 IF( REWI )\n     $                              REWIND NTRA\n                                 CALL DGEMV( TRANS, M, N, ALPHA, AA,\n     $                                       LDA, XX, INCX, BETA, YY,\n     $                                       INCY )\n                              ELSE IF( BANDED )THEN\n                                 IF( TRACE )\n     $                              WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                              TRANS, M, N, KL, KU, ALPHA, LDA,\n     $                              INCX, BETA, INCY\n                                 IF( REWI )\n     $                              REWIND NTRA\n                                 CALL DGBMV( TRANS, M, N, KL, KU, ALPHA,\n     $                                       AA, LDA, XX, INCX, BETA,\n     $                                       YY, INCY )\n                              END IF\n*\n*                             Check if error-exit was taken incorrectly.\n*\n                              IF( .NOT.OK )THEN\n                                 WRITE( NOUT, FMT = 9993 )\n                                 FATAL = .TRUE.\n                                 GO TO 130\n                              END IF\n*\n*                             See what data changed inside subroutines.\n*\n                              ISAME( 1 ) = TRANS.EQ.TRANSS\n                              ISAME( 2 ) = MS.EQ.M\n                              ISAME( 3 ) = NS.EQ.N\n                              IF( FULL )THEN\n                                 ISAME( 4 ) = ALS.EQ.ALPHA\n                                 ISAME( 5 ) = LDE( AS, AA, LAA )\n                                 ISAME( 6 ) = LDAS.EQ.LDA\n                                 ISAME( 7 ) = LDE( XS, XX, LX )\n                                 ISAME( 8 ) = INCXS.EQ.INCX\n                                 ISAME( 9 ) = BLS.EQ.BETA\n                                 IF( NULL )THEN\n                                    ISAME( 10 ) = LDE( YS, YY, LY )\n                                 ELSE\n                                    ISAME( 10 ) = LDERES( 'GE', ' ', 1,\n     $                                            ML, YS, YY,\n     $                                            ABS( INCY ) )\n                                 END IF\n                                 ISAME( 11 ) = INCYS.EQ.INCY\n                              ELSE IF( BANDED )THEN\n                                 ISAME( 4 ) = KLS.EQ.KL\n                                 ISAME( 5 ) = KUS.EQ.KU\n                                 ISAME( 6 ) = ALS.EQ.ALPHA\n                                 ISAME( 7 ) = LDE( AS, AA, LAA )\n                                 ISAME( 8 ) = LDAS.EQ.LDA\n                                 ISAME( 9 ) = LDE( XS, XX, LX )\n                                 ISAME( 10 ) = INCXS.EQ.INCX\n                                 ISAME( 11 ) = BLS.EQ.BETA\n                                 IF( NULL )THEN\n                                    ISAME( 12 ) = LDE( YS, YY, LY )\n                                 ELSE\n                                    ISAME( 12 ) = LDERES( 'GE', ' ', 1,\n     $                                            ML, YS, YY,\n     $                                            ABS( INCY ) )\n                                 END IF\n                                 ISAME( 13 ) = INCYS.EQ.INCY\n                              END IF\n*\n*                             If data was incorrectly changed, report\n*                             and return.\n*\n                              SAME = .TRUE.\n                              DO 40 I = 1, NARGS\n                                 SAME = SAME.AND.ISAME( I )\n                                 IF( .NOT.ISAME( I ) )\n     $                              WRITE( NOUT, FMT = 9998 )I\n   40                         CONTINUE\n                              IF( .NOT.SAME )THEN\n                                 FATAL = .TRUE.\n                                 GO TO 130\n                              END IF\n*\n                              IF( .NOT.NULL )THEN\n*\n*                                Check the result.\n*\n                                 CALL DMVCH( TRANS, M, N, ALPHA, A,\n     $                                       NMAX, X, INCX, BETA, Y,\n     $                                       INCY, YT, G, YY, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                                 ERRMAX = MAX( ERRMAX, ERR )\n*                                If got really bad answer, report and\n*                                return.\n                                 IF( FATAL )\n     $                              GO TO 130\n                              ELSE\n*                                Avoid repeating tests with M.le.0 or\n*                                N.le.0.\n                                 GO TO 110\n                              END IF\n*\n   50                      CONTINUE\n*\n   60                   CONTINUE\n*\n   70                CONTINUE\n*\n   80             CONTINUE\n*\n   90          CONTINUE\n*\n  100       CONTINUE\n*\n  110    CONTINUE\n*\n  120 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 140\n*\n  130 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, TRANS, M, N, ALPHA, LDA,\n     $      INCX, BETA, INCY\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, TRANS, M, N, KL, KU,\n     $      ALPHA, LDA, INCX, BETA, INCY\n      END IF\n*\n  140 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 4( I3, ',' ), F4.1,\n     $      ', A,', I3, ', X,', I2, ',', F4.1, ', Y,', I2, ') .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 2( I3, ',' ), F4.1,\n     $      ', A,', I3, ', X,', I2, ',', F4.1, ', Y,', I2,\n     $      ')         .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK1.\n*\n      END\n      SUBROUTINE DCHK2( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF, NBET,\n     $                  BET, NINC, INC, NMAX, INCMAX, A, AA, AS, X, XX,\n     $                  XS, Y, YY, YS, YT, G )\n*\n*  Tests DSYMV, DSBMV and DSPMV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, HALF\n      PARAMETER          ( ZERO = 0.0D0, HALF = 0.5D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NALF, NBET, NIDIM, NINC, NKB, NMAX,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), BET( NBET ), G( NMAX ),\n     $                   X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, ALS, BETA, BLS, ERR, ERRMAX, TRANSL\n      INTEGER            I, IA, IB, IC, IK, IN, INCX, INCXS, INCY,\n     $                   INCYS, IX, IY, K, KS, LAA, LDA, LDAS, LX, LY,\n     $                   N, NARGS, NC, NK, NS\n      LOGICAL            BANDED, FULL, NULL, PACKED, RESET, SAME\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DMAKE, DMVCH, DSBMV, DSPMV, DSYMV\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'Y'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 10\n      ELSE IF( BANDED )THEN\n         NARGS = 11\n      ELSE IF( PACKED )THEN\n         NARGS = 9\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 110 IN = 1, NIDIM\n         N = IDIM( IN )\n*\n         IF( BANDED )THEN\n            NK = NKB\n         ELSE\n            NK = 1\n         END IF\n         DO 100 IK = 1, NK\n            IF( BANDED )THEN\n               K = KB( IK )\n            ELSE\n               K = N - 1\n            END IF\n*           Set LDA to 1 more than minimum value if room.\n            IF( BANDED )THEN\n               LDA = K + 1\n            ELSE\n               LDA = N\n            END IF\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 100\n            IF( PACKED )THEN\n               LAA = ( N*( N + 1 ) )/2\n            ELSE\n               LAA = LDA*N\n            END IF\n            NULL = N.LE.0\n*\n            DO 90 IC = 1, 2\n               UPLO = ICH( IC: IC )\n*\n*              Generate the matrix A.\n*\n               TRANSL = ZERO\n               CALL DMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A, NMAX, AA,\n     $                     LDA, K, K, RESET, TRANSL )\n*\n               DO 80 IX = 1, NINC\n                  INCX = INC( IX )\n                  LX = ABS( INCX )*N\n*\n*                 Generate the vector X.\n*\n                  TRANSL = HALF\n                  CALL DMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX,\n     $                        ABS( INCX ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     X( N/2 ) = ZERO\n                     XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 70 IY = 1, NINC\n                     INCY = INC( IY )\n                     LY = ABS( INCY )*N\n*\n                     DO 60 IA = 1, NALF\n                        ALPHA = ALF( IA )\n*\n                        DO 50 IB = 1, NBET\n                           BETA = BET( IB )\n*\n*                          Generate the vector Y.\n*\n                           TRANSL = ZERO\n                           CALL DMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                                 ABS( INCY ), 0, N - 1, RESET,\n     $                                 TRANSL )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           UPLOS = UPLO\n                           NS = N\n                           KS = K\n                           ALS = ALPHA\n                           DO 10 I = 1, LAA\n                              AS( I ) = AA( I )\n   10                      CONTINUE\n                           LDAS = LDA\n                           DO 20 I = 1, LX\n                              XS( I ) = XX( I )\n   20                      CONTINUE\n                           INCXS = INCX\n                           BLS = BETA\n                           DO 30 I = 1, LY\n                              YS( I ) = YY( I )\n   30                      CONTINUE\n                           INCYS = INCY\n*\n*                          Call the subroutine.\n*\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, N, ALPHA, LDA, INCX, BETA, INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DSYMV( UPLO, N, ALPHA, AA, LDA, XX,\n     $                                    INCX, BETA, YY, INCY )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, N, K, ALPHA, LDA, INCX, BETA,\n     $                           INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DSBMV( UPLO, N, K, ALPHA, AA, LDA,\n     $                                    XX, INCX, BETA, YY, INCY )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, N, ALPHA, INCX, BETA, INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DSPMV( UPLO, N, ALPHA, AA, XX, INCX,\n     $                                    BETA, YY, INCY )\n                           END IF\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9992 )\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = UPLO.EQ.UPLOS\n                           ISAME( 2 ) = NS.EQ.N\n                           IF( FULL )THEN\n                              ISAME( 3 ) = ALS.EQ.ALPHA\n                              ISAME( 4 ) = LDE( AS, AA, LAA )\n                              ISAME( 5 ) = LDAS.EQ.LDA\n                              ISAME( 6 ) = LDE( XS, XX, LX )\n                              ISAME( 7 ) = INCXS.EQ.INCX\n                              ISAME( 8 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 9 ) = LDE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 9 ) = LDERES( 'GE', ' ', 1, N,\n     $                                        YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 10 ) = INCYS.EQ.INCY\n                           ELSE IF( BANDED )THEN\n                              ISAME( 3 ) = KS.EQ.K\n                              ISAME( 4 ) = ALS.EQ.ALPHA\n                              ISAME( 5 ) = LDE( AS, AA, LAA )\n                              ISAME( 6 ) = LDAS.EQ.LDA\n                              ISAME( 7 ) = LDE( XS, XX, LX )\n                              ISAME( 8 ) = INCXS.EQ.INCX\n                              ISAME( 9 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 10 ) = LDE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 10 ) = LDERES( 'GE', ' ', 1, N,\n     $                                         YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 11 ) = INCYS.EQ.INCY\n                           ELSE IF( PACKED )THEN\n                              ISAME( 3 ) = ALS.EQ.ALPHA\n                              ISAME( 4 ) = LDE( AS, AA, LAA )\n                              ISAME( 5 ) = LDE( XS, XX, LX )\n                              ISAME( 6 ) = INCXS.EQ.INCX\n                              ISAME( 7 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 8 ) = LDE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 8 ) = LDERES( 'GE', ' ', 1, N,\n     $                                        YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 9 ) = INCYS.EQ.INCY\n                           END IF\n*\n*                          If data was incorrectly changed, report and\n*                          return.\n*\n                           SAME = .TRUE.\n                           DO 40 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   40                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n*\n*                             Check the result.\n*\n                              CALL DMVCH( 'N', N, N, ALPHA, A, NMAX, X,\n     $                                    INCX, BETA, Y, INCY, YT, G,\n     $                                    YY, EPS, ERR, FATAL, NOUT,\n     $                                    .TRUE. )\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 120\n                           ELSE\n*                             Avoid repeating tests with N.le.0\n                              GO TO 110\n                           END IF\n*\n   50                   CONTINUE\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, ALPHA, LDA, INCX,\n     $      BETA, INCY\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, K, ALPHA, LDA,\n     $      INCX, BETA, INCY\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, UPLO, N, ALPHA, INCX,\n     $      BETA, INCY\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', AP',\n     $      ', X,', I2, ',', F4.1, ', Y,', I2, ')                .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 2( I3, ',' ), F4.1,\n     $      ', A,', I3, ', X,', I2, ',', F4.1, ', Y,', I2,\n     $      ')         .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', A,',\n     $      I3, ', X,', I2, ',', F4.1, ', Y,', I2, ')             .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK2.\n*\n      END\n      SUBROUTINE DCHK3( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, XT, G, Z )\n*\n*  Tests DTRMV, DTBMV, DTPMV, DTRSV, DTBSV and DTPSV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, HALF, ONE\n      PARAMETER          ( ZERO = 0.0D0, HALF = 0.5D0, ONE = 1.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NIDIM, NINC, NKB, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ),\n     $                   AS( NMAX*NMAX ), G( NMAX ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XT( NMAX ),\n     $                   XX( NMAX*INCMAX ), Z( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ERR, ERRMAX, TRANSL\n      INTEGER            I, ICD, ICT, ICU, IK, IN, INCX, INCXS, IX, K,\n     $                   KS, LAA, LDA, LDAS, LX, N, NARGS, NC, NK, NS\n      LOGICAL            BANDED, FULL, NULL, PACKED, RESET, SAME\n      CHARACTER*1        DIAG, DIAGS, TRANS, TRANSS, UPLO, UPLOS\n      CHARACTER*2        ICHD, ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DMAKE, DMVCH, DTBMV, DTBSV, DTPMV, DTPSV,\n     $                   DTRMV, DTRSV\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHU/'UL'/, ICHT/'NTC'/, ICHD/'UN'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'R'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 8\n      ELSE IF( BANDED )THEN\n         NARGS = 9\n      ELSE IF( PACKED )THEN\n         NARGS = 7\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*     Set up zero vector for DMVCH.\n      DO 10 I = 1, NMAX\n         Z( I ) = ZERO\n   10 CONTINUE\n*\n      DO 110 IN = 1, NIDIM\n         N = IDIM( IN )\n*\n         IF( BANDED )THEN\n            NK = NKB\n         ELSE\n            NK = 1\n         END IF\n         DO 100 IK = 1, NK\n            IF( BANDED )THEN\n               K = KB( IK )\n            ELSE\n               K = N - 1\n            END IF\n*           Set LDA to 1 more than minimum value if room.\n            IF( BANDED )THEN\n               LDA = K + 1\n            ELSE\n               LDA = N\n            END IF\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 100\n            IF( PACKED )THEN\n               LAA = ( N*( N + 1 ) )/2\n            ELSE\n               LAA = LDA*N\n            END IF\n            NULL = N.LE.0\n*\n            DO 90 ICU = 1, 2\n               UPLO = ICHU( ICU: ICU )\n*\n               DO 80 ICT = 1, 3\n                  TRANS = ICHT( ICT: ICT )\n*\n                  DO 70 ICD = 1, 2\n                     DIAG = ICHD( ICD: ICD )\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL DMAKE( SNAME( 2: 3 ), UPLO, DIAG, N, N, A,\n     $                           NMAX, AA, LDA, K, K, RESET, TRANSL )\n*\n                     DO 60 IX = 1, NINC\n                        INCX = INC( IX )\n                        LX = ABS( INCX )*N\n*\n*                       Generate the vector X.\n*\n                        TRANSL = HALF\n                        CALL DMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX,\n     $                              ABS( INCX ), 0, N - 1, RESET,\n     $                              TRANSL )\n                        IF( N.GT.1 )THEN\n                           X( N/2 ) = ZERO\n                           XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n                        END IF\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        DIAGS = DIAG\n                        NS = N\n                        KS = K\n                        DO 20 I = 1, LAA\n                           AS( I ) = AA( I )\n   20                   CONTINUE\n                        LDAS = LDA\n                        DO 30 I = 1, LX\n                           XS( I ) = XX( I )\n   30                   CONTINUE\n                        INCXS = INCX\n*\n*                       Call the subroutine.\n*\n                        IF( SNAME( 4: 5 ).EQ.'MV' )THEN\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DTRMV( UPLO, TRANS, DIAG, N, AA, LDA,\n     $                                    XX, INCX )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, K, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DTBMV( UPLO, TRANS, DIAG, N, K, AA,\n     $                                    LDA, XX, INCX )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DTPMV( UPLO, TRANS, DIAG, N, AA, XX,\n     $                                    INCX )\n                           END IF\n                        ELSE IF( SNAME( 4: 5 ).EQ.'SV' )THEN\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DTRSV( UPLO, TRANS, DIAG, N, AA, LDA,\n     $                                    XX, INCX )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, K, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DTBSV( UPLO, TRANS, DIAG, N, K, AA,\n     $                                    LDA, XX, INCX )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DTPSV( UPLO, TRANS, DIAG, N, AA, XX,\n     $                                    INCX )\n                           END IF\n                        END IF\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9992 )\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLO.EQ.UPLOS\n                        ISAME( 2 ) = TRANS.EQ.TRANSS\n                        ISAME( 3 ) = DIAG.EQ.DIAGS\n                        ISAME( 4 ) = NS.EQ.N\n                        IF( FULL )THEN\n                           ISAME( 5 ) = LDE( AS, AA, LAA )\n                           ISAME( 6 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 7 ) = LDE( XS, XX, LX )\n                           ELSE\n                              ISAME( 7 ) = LDERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 8 ) = INCXS.EQ.INCX\n                        ELSE IF( BANDED )THEN\n                           ISAME( 5 ) = KS.EQ.K\n                           ISAME( 6 ) = LDE( AS, AA, LAA )\n                           ISAME( 7 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 8 ) = LDE( XS, XX, LX )\n                           ELSE\n                              ISAME( 8 ) = LDERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 9 ) = INCXS.EQ.INCX\n                        ELSE IF( PACKED )THEN\n                           ISAME( 5 ) = LDE( AS, AA, LAA )\n                           IF( NULL )THEN\n                              ISAME( 6 ) = LDE( XS, XX, LX )\n                           ELSE\n                              ISAME( 6 ) = LDERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 7 ) = INCXS.EQ.INCX\n                        END IF\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n                           IF( SNAME( 4: 5 ).EQ.'MV' )THEN\n*\n*                             Check the result.\n*\n                              CALL DMVCH( TRANS, N, N, ONE, A, NMAX, X,\n     $                                    INCX, ZERO, Z, INCX, XT, G,\n     $                                    XX, EPS, ERR, FATAL, NOUT,\n     $                                    .TRUE. )\n                           ELSE IF( SNAME( 4: 5 ).EQ.'SV' )THEN\n*\n*                             Compute approximation to original vector.\n*\n                              DO 50 I = 1, N\n                                 Z( I ) = XX( 1 + ( I - 1 )*\n     $                                    ABS( INCX ) )\n                                 XX( 1 + ( I - 1 )*ABS( INCX ) )\n     $                              = X( I )\n   50                         CONTINUE\n                              CALL DMVCH( TRANS, N, N, ONE, A, NMAX, Z,\n     $                                    INCX, ZERO, X, INCX, XT, G,\n     $                                    XX, EPS, ERR, FATAL, NOUT,\n     $                                    .FALSE. )\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 120\n                        ELSE\n*                          Avoid repeating tests with N.le.0.\n                           GO TO 110\n                        END IF\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, TRANS, DIAG, N, LDA,\n     $      INCX\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, DIAG, N, K,\n     $      LDA, INCX\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, UPLO, TRANS, DIAG, N, INCX\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), I3, ', AP, ',\n     $      'X,', I2, ')                        .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), 2( I3, ',' ),\n     $      ' A,', I3, ', X,', I2, ')                 .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), I3, ', A,',\n     $      I3, ', X,', I2, ')                     .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK3.\n*\n      END\n      SUBROUTINE DCHK4( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests DGER.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, HALF, ONE\n      PARAMETER          ( ZERO = 0.0D0, HALF = 0.5D0, ONE = 1.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), G( NMAX ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XX( NMAX*INCMAX ),\n     $                   Y( NMAX ), YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, ALS, ERR, ERRMAX, TRANSL\n      INTEGER            I, IA, IM, IN, INCX, INCXS, INCY, INCYS, IX,\n     $                   IY, J, LAA, LDA, LDAS, LX, LY, M, MS, N, NARGS,\n     $                   NC, ND, NS\n      LOGICAL            NULL, RESET, SAME\n*     .. Local Arrays ..\n      DOUBLE PRECISION   W( 1 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DGER, DMAKE, DMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n*     Define the number of arguments.\n      NARGS = 9\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 120 IN = 1, NIDIM\n         N = IDIM( IN )\n         ND = N/2 + 1\n*\n         DO 110 IM = 1, 2\n            IF( IM.EQ.1 )\n     $         M = MAX( N - ND, 0 )\n            IF( IM.EQ.2 )\n     $         M = MIN( N + ND, NMAX )\n*\n*           Set LDA to 1 more than minimum value if room.\n            LDA = M\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 110\n            LAA = LDA*N\n            NULL = N.LE.0.OR.M.LE.0\n*\n            DO 100 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*M\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL DMAKE( 'GE', ' ', ' ', 1, M, X, 1, XX, ABS( INCX ),\n     $                     0, M - 1, RESET, TRANSL )\n               IF( M.GT.1 )THEN\n                  X( M/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( M/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 90 IY = 1, NINC\n                  INCY = INC( IY )\n                  LY = ABS( INCY )*N\n*\n*                 Generate the vector Y.\n*\n                  TRANSL = ZERO\n                  CALL DMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                        ABS( INCY ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     Y( N/2 ) = ZERO\n                     YY( 1 + ABS( INCY )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 80 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL DMAKE( SNAME( 2: 3 ), ' ', ' ', M, N, A, NMAX,\n     $                           AA, LDA, M - 1, N - 1, RESET, TRANSL )\n*\n                     NC = NC + 1\n*\n*                    Save every datum before calling the subroutine.\n*\n                     MS = M\n                     NS = N\n                     ALS = ALPHA\n                     DO 10 I = 1, LAA\n                        AS( I ) = AA( I )\n   10                CONTINUE\n                     LDAS = LDA\n                     DO 20 I = 1, LX\n                        XS( I ) = XX( I )\n   20                CONTINUE\n                     INCXS = INCX\n                     DO 30 I = 1, LY\n                        YS( I ) = YY( I )\n   30                CONTINUE\n                     INCYS = INCY\n*\n*                    Call the subroutine.\n*\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9994 )NC, SNAME, M, N,\n     $                  ALPHA, INCX, INCY, LDA\n                     IF( REWI )\n     $                  REWIND NTRA\n                     CALL DGER( M, N, ALPHA, XX, INCX, YY, INCY, AA,\n     $                          LDA )\n*\n*                    Check if error-exit was taken incorrectly.\n*\n                     IF( .NOT.OK )THEN\n                        WRITE( NOUT, FMT = 9993 )\n                        FATAL = .TRUE.\n                        GO TO 140\n                     END IF\n*\n*                    See what data changed inside subroutine.\n*\n                     ISAME( 1 ) = MS.EQ.M\n                     ISAME( 2 ) = NS.EQ.N\n                     ISAME( 3 ) = ALS.EQ.ALPHA\n                     ISAME( 4 ) = LDE( XS, XX, LX )\n                     ISAME( 5 ) = INCXS.EQ.INCX\n                     ISAME( 6 ) = LDE( YS, YY, LY )\n                     ISAME( 7 ) = INCYS.EQ.INCY\n                     IF( NULL )THEN\n                        ISAME( 8 ) = LDE( AS, AA, LAA )\n                     ELSE\n                        ISAME( 8 ) = LDERES( 'GE', ' ', M, N, AS, AA,\n     $                               LDA )\n                     END IF\n                     ISAME( 9 ) = LDAS.EQ.LDA\n*\n*                    If data was incorrectly changed, report and return.\n*\n                     SAME = .TRUE.\n                     DO 40 I = 1, NARGS\n                        SAME = SAME.AND.ISAME( I )\n                        IF( .NOT.ISAME( I ) )\n     $                     WRITE( NOUT, FMT = 9998 )I\n   40                CONTINUE\n                     IF( .NOT.SAME )THEN\n                        FATAL = .TRUE.\n                        GO TO 140\n                     END IF\n*\n                     IF( .NOT.NULL )THEN\n*\n*                       Check the result column by column.\n*\n                        IF( INCX.GT.0 )THEN\n                           DO 50 I = 1, M\n                              Z( I ) = X( I )\n   50                      CONTINUE\n                        ELSE\n                           DO 60 I = 1, M\n                              Z( I ) = X( M - I + 1 )\n   60                      CONTINUE\n                        END IF\n                        DO 70 J = 1, N\n                           IF( INCY.GT.0 )THEN\n                              W( 1 ) = Y( J )\n                           ELSE\n                              W( 1 ) = Y( N - J + 1 )\n                           END IF\n                           CALL DMVCH( 'N', M, 1, ALPHA, Z, NMAX, W, 1,\n     $                                 ONE, A( 1, J ), 1, YT, G,\n     $                                 AA( 1 + ( J - 1 )*LDA ), EPS,\n     $                                 ERR, FATAL, NOUT, .TRUE. )\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 130\n   70                   CONTINUE\n                     ELSE\n*                       Avoid repeating tests with M.le.0 or N.le.0.\n                        GO TO 110\n                     END IF\n*\n   80             CONTINUE\n*\n   90          CONTINUE\n*\n  100       CONTINUE\n*\n  110    CONTINUE\n*\n  120 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 150\n*\n  130 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  140 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9994 )NC, SNAME, M, N, ALPHA, INCX, INCY, LDA\n*\n  150 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( I3, ',' ), F4.1, ', X,', I2,\n     $      ', Y,', I2, ', A,', I3, ')                  .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK4.\n*\n      END\n      SUBROUTINE DCHK5( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests DSYR and DSPR.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, HALF, ONE\n      PARAMETER          ( ZERO = 0.0D0, HALF = 0.5D0, ONE = 1.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), G( NMAX ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XX( NMAX*INCMAX ),\n     $                   Y( NMAX ), YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, ALS, ERR, ERRMAX, TRANSL\n      INTEGER            I, IA, IC, IN, INCX, INCXS, IX, J, JA, JJ, LAA,\n     $                   LDA, LDAS, LJ, LX, N, NARGS, NC, NS\n      LOGICAL            FULL, NULL, PACKED, RESET, SAME, UPPER\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      DOUBLE PRECISION   W( 1 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DMAKE, DMVCH, DSPR, DSYR\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'Y'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 7\n      ELSE IF( PACKED )THEN\n         NARGS = 6\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 100 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDA to 1 more than minimum value if room.\n         LDA = N\n         IF( LDA.LT.NMAX )\n     $      LDA = LDA + 1\n*        Skip tests if not enough room.\n         IF( LDA.GT.NMAX )\n     $      GO TO 100\n         IF( PACKED )THEN\n            LAA = ( N*( N + 1 ) )/2\n         ELSE\n            LAA = LDA*N\n         END IF\n*\n         DO 90 IC = 1, 2\n            UPLO = ICH( IC: IC )\n            UPPER = UPLO.EQ.'U'\n*\n            DO 80 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*N\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL DMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX, ABS( INCX ),\n     $                     0, N - 1, RESET, TRANSL )\n               IF( N.GT.1 )THEN\n                  X( N/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 70 IA = 1, NALF\n                  ALPHA = ALF( IA )\n                  NULL = N.LE.0.OR.ALPHA.EQ.ZERO\n*\n*                 Generate the matrix A.\n*\n                  TRANSL = ZERO\n                  CALL DMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A, NMAX,\n     $                        AA, LDA, N - 1, N - 1, RESET, TRANSL )\n*\n                  NC = NC + 1\n*\n*                 Save every datum before calling the subroutine.\n*\n                  UPLOS = UPLO\n                  NS = N\n                  ALS = ALPHA\n                  DO 10 I = 1, LAA\n                     AS( I ) = AA( I )\n   10             CONTINUE\n                  LDAS = LDA\n                  DO 20 I = 1, LX\n                     XS( I ) = XX( I )\n   20             CONTINUE\n                  INCXS = INCX\n*\n*                 Call the subroutine.\n*\n                  IF( FULL )THEN\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO, N,\n     $                  ALPHA, INCX, LDA\n                     IF( REWI )\n     $                  REWIND NTRA\n                     CALL DSYR( UPLO, N, ALPHA, XX, INCX, AA, LDA )\n                  ELSE IF( PACKED )THEN\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO, N,\n     $                  ALPHA, INCX\n                     IF( REWI )\n     $                  REWIND NTRA\n                     CALL DSPR( UPLO, N, ALPHA, XX, INCX, AA )\n                  END IF\n*\n*                 Check if error-exit was taken incorrectly.\n*\n                  IF( .NOT.OK )THEN\n                     WRITE( NOUT, FMT = 9992 )\n                     FATAL = .TRUE.\n                     GO TO 120\n                  END IF\n*\n*                 See what data changed inside subroutines.\n*\n                  ISAME( 1 ) = UPLO.EQ.UPLOS\n                  ISAME( 2 ) = NS.EQ.N\n                  ISAME( 3 ) = ALS.EQ.ALPHA\n                  ISAME( 4 ) = LDE( XS, XX, LX )\n                  ISAME( 5 ) = INCXS.EQ.INCX\n                  IF( NULL )THEN\n                     ISAME( 6 ) = LDE( AS, AA, LAA )\n                  ELSE\n                     ISAME( 6 ) = LDERES( SNAME( 2: 3 ), UPLO, N, N, AS,\n     $                            AA, LDA )\n                  END IF\n                  IF( .NOT.PACKED )THEN\n                     ISAME( 7 ) = LDAS.EQ.LDA\n                  END IF\n*\n*                 If data was incorrectly changed, report and return.\n*\n                  SAME = .TRUE.\n                  DO 30 I = 1, NARGS\n                     SAME = SAME.AND.ISAME( I )\n                     IF( .NOT.ISAME( I ) )\n     $                  WRITE( NOUT, FMT = 9998 )I\n   30             CONTINUE\n                  IF( .NOT.SAME )THEN\n                     FATAL = .TRUE.\n                     GO TO 120\n                  END IF\n*\n                  IF( .NOT.NULL )THEN\n*\n*                    Check the result column by column.\n*\n                     IF( INCX.GT.0 )THEN\n                        DO 40 I = 1, N\n                           Z( I ) = X( I )\n   40                   CONTINUE\n                     ELSE\n                        DO 50 I = 1, N\n                           Z( I ) = X( N - I + 1 )\n   50                   CONTINUE\n                     END IF\n                     JA = 1\n                     DO 60 J = 1, N\n                        W( 1 ) = Z( J )\n                        IF( UPPER )THEN\n                           JJ = 1\n                           LJ = J\n                        ELSE\n                           JJ = J\n                           LJ = N - J + 1\n                        END IF\n                        CALL DMVCH( 'N', LJ, 1, ALPHA, Z( JJ ), LJ, W,\n     $                              1, ONE, A( JJ, J ), 1, YT, G,\n     $                              AA( JA ), EPS, ERR, FATAL, NOUT,\n     $                              .TRUE. )\n                        IF( FULL )THEN\n                           IF( UPPER )THEN\n                              JA = JA + LDA\n                           ELSE\n                              JA = JA + LDA + 1\n                           END IF\n                        ELSE\n                           JA = JA + LJ\n                        END IF\n                        ERRMAX = MAX( ERRMAX, ERR )\n*                       If got really bad answer, report and return.\n                        IF( FATAL )\n     $                     GO TO 110\n   60                CONTINUE\n                  ELSE\n*                    Avoid repeating tests if N.le.0.\n                     IF( N.LE.0 )\n     $                  GO TO 100\n                  END IF\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  110 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, ALPHA, INCX, LDA\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, ALPHA, INCX\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', AP)                           .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', A,', I3, ')                        .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK5.\n*\n      END\n      SUBROUTINE DCHK6( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests DSYR2 and DSPR2.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, HALF, ONE\n      PARAMETER          ( ZERO = 0.0D0, HALF = 0.5D0, ONE = 1.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), G( NMAX ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XX( NMAX*INCMAX ),\n     $                   Y( NMAX ), YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX, 2 )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, ALS, ERR, ERRMAX, TRANSL\n      INTEGER            I, IA, IC, IN, INCX, INCXS, INCY, INCYS, IX,\n     $                   IY, J, JA, JJ, LAA, LDA, LDAS, LJ, LX, LY, N,\n     $                   NARGS, NC, NS\n      LOGICAL            FULL, NULL, PACKED, RESET, SAME, UPPER\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      DOUBLE PRECISION   W( 2 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DMAKE, DMVCH, DSPR2, DSYR2\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'Y'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 9\n      ELSE IF( PACKED )THEN\n         NARGS = 8\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 140 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDA to 1 more than minimum value if room.\n         LDA = N\n         IF( LDA.LT.NMAX )\n     $      LDA = LDA + 1\n*        Skip tests if not enough room.\n         IF( LDA.GT.NMAX )\n     $      GO TO 140\n         IF( PACKED )THEN\n            LAA = ( N*( N + 1 ) )/2\n         ELSE\n            LAA = LDA*N\n         END IF\n*\n         DO 130 IC = 1, 2\n            UPLO = ICH( IC: IC )\n            UPPER = UPLO.EQ.'U'\n*\n            DO 120 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*N\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL DMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX, ABS( INCX ),\n     $                     0, N - 1, RESET, TRANSL )\n               IF( N.GT.1 )THEN\n                  X( N/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 110 IY = 1, NINC\n                  INCY = INC( IY )\n                  LY = ABS( INCY )*N\n*\n*                 Generate the vector Y.\n*\n                  TRANSL = ZERO\n                  CALL DMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                        ABS( INCY ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     Y( N/2 ) = ZERO\n                     YY( 1 + ABS( INCY )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 100 IA = 1, NALF\n                     ALPHA = ALF( IA )\n                     NULL = N.LE.0.OR.ALPHA.EQ.ZERO\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL DMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A,\n     $                           NMAX, AA, LDA, N - 1, N - 1, RESET,\n     $                           TRANSL )\n*\n                     NC = NC + 1\n*\n*                    Save every datum before calling the subroutine.\n*\n                     UPLOS = UPLO\n                     NS = N\n                     ALS = ALPHA\n                     DO 10 I = 1, LAA\n                        AS( I ) = AA( I )\n   10                CONTINUE\n                     LDAS = LDA\n                     DO 20 I = 1, LX\n                        XS( I ) = XX( I )\n   20                CONTINUE\n                     INCXS = INCX\n                     DO 30 I = 1, LY\n                        YS( I ) = YY( I )\n   30                CONTINUE\n                     INCYS = INCY\n*\n*                    Call the subroutine.\n*\n                     IF( FULL )THEN\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO, N,\n     $                     ALPHA, INCX, INCY, LDA\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL DSYR2( UPLO, N, ALPHA, XX, INCX, YY, INCY,\n     $                              AA, LDA )\n                     ELSE IF( PACKED )THEN\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO, N,\n     $                     ALPHA, INCX, INCY\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL DSPR2( UPLO, N, ALPHA, XX, INCX, YY, INCY,\n     $                              AA )\n                     END IF\n*\n*                    Check if error-exit was taken incorrectly.\n*\n                     IF( .NOT.OK )THEN\n                        WRITE( NOUT, FMT = 9992 )\n                        FATAL = .TRUE.\n                        GO TO 160\n                     END IF\n*\n*                    See what data changed inside subroutines.\n*\n                     ISAME( 1 ) = UPLO.EQ.UPLOS\n                     ISAME( 2 ) = NS.EQ.N\n                     ISAME( 3 ) = ALS.EQ.ALPHA\n                     ISAME( 4 ) = LDE( XS, XX, LX )\n                     ISAME( 5 ) = INCXS.EQ.INCX\n                     ISAME( 6 ) = LDE( YS, YY, LY )\n                     ISAME( 7 ) = INCYS.EQ.INCY\n                     IF( NULL )THEN\n                        ISAME( 8 ) = LDE( AS, AA, LAA )\n                     ELSE\n                        ISAME( 8 ) = LDERES( SNAME( 2: 3 ), UPLO, N, N,\n     $                               AS, AA, LDA )\n                     END IF\n                     IF( .NOT.PACKED )THEN\n                        ISAME( 9 ) = LDAS.EQ.LDA\n                     END IF\n*\n*                    If data was incorrectly changed, report and return.\n*\n                     SAME = .TRUE.\n                     DO 40 I = 1, NARGS\n                        SAME = SAME.AND.ISAME( I )\n                        IF( .NOT.ISAME( I ) )\n     $                     WRITE( NOUT, FMT = 9998 )I\n   40                CONTINUE\n                     IF( .NOT.SAME )THEN\n                        FATAL = .TRUE.\n                        GO TO 160\n                     END IF\n*\n                     IF( .NOT.NULL )THEN\n*\n*                       Check the result column by column.\n*\n                        IF( INCX.GT.0 )THEN\n                           DO 50 I = 1, N\n                              Z( I, 1 ) = X( I )\n   50                      CONTINUE\n                        ELSE\n                           DO 60 I = 1, N\n                              Z( I, 1 ) = X( N - I + 1 )\n   60                      CONTINUE\n                        END IF\n                        IF( INCY.GT.0 )THEN\n                           DO 70 I = 1, N\n                              Z( I, 2 ) = Y( I )\n   70                      CONTINUE\n                        ELSE\n                           DO 80 I = 1, N\n                              Z( I, 2 ) = Y( N - I + 1 )\n   80                      CONTINUE\n                        END IF\n                        JA = 1\n                        DO 90 J = 1, N\n                           W( 1 ) = Z( J, 2 )\n                           W( 2 ) = Z( J, 1 )\n                           IF( UPPER )THEN\n                              JJ = 1\n                              LJ = J\n                           ELSE\n                              JJ = J\n                              LJ = N - J + 1\n                           END IF\n                           CALL DMVCH( 'N', LJ, 2, ALPHA, Z( JJ, 1 ),\n     $                                 NMAX, W, 1, ONE, A( JJ, J ), 1,\n     $                                 YT, G, AA( JA ), EPS, ERR, FATAL,\n     $                                 NOUT, .TRUE. )\n                           IF( FULL )THEN\n                              IF( UPPER )THEN\n                                 JA = JA + LDA\n                              ELSE\n                                 JA = JA + LDA + 1\n                              END IF\n                           ELSE\n                              JA = JA + LJ\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 150\n   90                   CONTINUE\n                     ELSE\n*                       Avoid repeating tests with N.le.0.\n                        IF( N.LE.0 )\n     $                     GO TO 140\n                     END IF\n*\n  100             CONTINUE\n*\n  110          CONTINUE\n*\n  120       CONTINUE\n*\n  130    CONTINUE\n*\n  140 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 170\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  160 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, ALPHA, INCX,\n     $      INCY, LDA\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, ALPHA, INCX, INCY\n      END IF\n*\n  170 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', Y,', I2, ', AP)                     .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', Y,', I2, ', A,', I3, ')                  .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK6.\n*\n      END\n      SUBROUTINE DCHKE( ISNUM, SRNAMT, NOUT )\n*\n*  Tests the error exits from the Level 2 Blas.\n*  Requires a special version of the error-handling routine XERBLA.\n*  ALPHA, BETA, A, X and Y should not need to be defined.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            ISNUM, NOUT\n      CHARACTER*6        SRNAMT\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, BETA\n*     .. Local Arrays ..\n      DOUBLE PRECISION   A( 1, 1 ), X( 1 ), Y( 1 )\n*     .. External Subroutines ..\n      EXTERNAL           CHKXER, DGBMV, DGEMV, DGER, DSBMV, DSPMV, DSPR,\n     $                   DSPR2, DSYMV, DSYR, DSYR2, DTBMV, DTBSV, DTPMV,\n     $                   DTPSV, DTRMV, DTRSV\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n*     OK is set to .FALSE. by the special version of XERBLA or by CHKXER\n*     if anything is wrong.\n      OK = .TRUE.\n*     LERR is set to .TRUE. by the special version of XERBLA each time\n*     it is called, and is then tested and re-set by CHKXER.\n      LERR = .FALSE.\n      GO TO ( 10, 20, 30, 40, 50, 60, 70, 80,\n     $        90, 100, 110, 120, 130, 140, 150,\n     $        160 )ISNUM\n   10 INFOT = 1\n      CALL DGEMV( '/', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DGEMV( 'N', -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DGEMV( 'N', 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DGEMV( 'N', 2, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL DGEMV( 'N', 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DGEMV( 'N', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   20 INFOT = 1\n      CALL DGBMV( '/', 0, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DGBMV( 'N', -1, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DGBMV( 'N', 0, -1, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DGBMV( 'N', 0, 0, -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DGBMV( 'N', 2, 0, 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL DGBMV( 'N', 0, 0, 1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL DGBMV( 'N', 0, 0, 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL DGBMV( 'N', 0, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   30 INFOT = 1\n      CALL DSYMV( '/', 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DSYMV( 'U', -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DSYMV( 'U', 2, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYMV( 'U', 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL DSYMV( 'U', 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   40 INFOT = 1\n      CALL DSBMV( '/', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DSBMV( 'U', -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSBMV( 'U', 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DSBMV( 'U', 0, 1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL DSBMV( 'U', 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DSBMV( 'U', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   50 INFOT = 1\n      CALL DSPMV( '/', 0, ALPHA, A, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DSPMV( 'U', -1, ALPHA, A, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DSPMV( 'U', 0, ALPHA, A, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DSPMV( 'U', 0, ALPHA, A, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   60 INFOT = 1\n      CALL DTRMV( '/', 'N', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DTRMV( 'U', '/', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DTRMV( 'U', 'N', '/', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DTRMV( 'U', 'N', 'N', -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRMV( 'U', 'N', 'N', 2, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL DTRMV( 'U', 'N', 'N', 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   70 INFOT = 1\n      CALL DTBMV( '/', 'N', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DTBMV( 'U', '/', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DTBMV( 'U', 'N', '/', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DTBMV( 'U', 'N', 'N', -1, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTBMV( 'U', 'N', 'N', 0, -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DTBMV( 'U', 'N', 'N', 0, 1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTBMV( 'U', 'N', 'N', 0, 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   80 INFOT = 1\n      CALL DTPMV( '/', 'N', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DTPMV( 'U', '/', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DTPMV( 'U', 'N', '/', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DTPMV( 'U', 'N', 'N', -1, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DTPMV( 'U', 'N', 'N', 0, A, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   90 INFOT = 1\n      CALL DTRSV( '/', 'N', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DTRSV( 'U', '/', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DTRSV( 'U', 'N', '/', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DTRSV( 'U', 'N', 'N', -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRSV( 'U', 'N', 'N', 2, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL DTRSV( 'U', 'N', 'N', 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  100 INFOT = 1\n      CALL DTBSV( '/', 'N', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DTBSV( 'U', '/', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DTBSV( 'U', 'N', '/', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DTBSV( 'U', 'N', 'N', -1, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTBSV( 'U', 'N', 'N', 0, -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DTBSV( 'U', 'N', 'N', 0, 1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTBSV( 'U', 'N', 'N', 0, 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  110 INFOT = 1\n      CALL DTPSV( '/', 'N', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DTPSV( 'U', '/', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DTPSV( 'U', 'N', '/', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DTPSV( 'U', 'N', 'N', -1, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DTPSV( 'U', 'N', 'N', 0, A, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  120 INFOT = 1\n      CALL DGER( -1, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DGER( 0, -1, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DGER( 0, 0, ALPHA, X, 0, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DGER( 0, 0, ALPHA, X, 1, Y, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DGER( 2, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  130 INFOT = 1\n      CALL DSYR( '/', 0, ALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DSYR( 'U', -1, ALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DSYR( 'U', 0, ALPHA, X, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYR( 'U', 2, ALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  140 INFOT = 1\n      CALL DSPR( '/', 0, ALPHA, X, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DSPR( 'U', -1, ALPHA, X, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DSPR( 'U', 0, ALPHA, X, 0, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  150 INFOT = 1\n      CALL DSYR2( '/', 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DSYR2( 'U', -1, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DSYR2( 'U', 0, ALPHA, X, 0, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYR2( 'U', 0, ALPHA, X, 1, Y, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DSYR2( 'U', 2, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  160 INFOT = 1\n      CALL DSPR2( '/', 0, ALPHA, X, 1, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DSPR2( 'U', -1, ALPHA, X, 1, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DSPR2( 'U', 0, ALPHA, X, 0, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSPR2( 'U', 0, ALPHA, X, 1, Y, 0, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n  170 IF( OK )THEN\n         WRITE( NOUT, FMT = 9999 )SRNAMT\n      ELSE\n         WRITE( NOUT, FMT = 9998 )SRNAMT\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE TESTS OF ERROR-EXITS' )\n 9998 FORMAT( ' ******* ', A6, ' FAILED THE TESTS OF ERROR-EXITS *****',\n     $      '**' )\n*\n*     End of DCHKE.\n*\n      END\n      SUBROUTINE DMAKE( TYPE, UPLO, DIAG, M, N, A, NMAX, AA, LDA, KL,\n     $                  KU, RESET, TRANSL )\n*\n*  Generates values for an M by N matrix A within the bandwidth\n*  defined by KL and KU.\n*  Stores the values in the array AA in the data structure required\n*  by the routine, with unwanted elements set to rogue value.\n*\n*  TYPE is 'GE', 'GB', 'SY', 'SB', 'SP', 'TR', 'TB' OR 'TP'.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, ONE\n      PARAMETER          ( ZERO = 0.0D0, ONE = 1.0D0 )\n      DOUBLE PRECISION   ROGUE\n      PARAMETER          ( ROGUE = -1.0D10 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   TRANSL\n      INTEGER            KL, KU, LDA, M, N, NMAX\n      LOGICAL            RESET\n      CHARACTER*1        DIAG, UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, * ), AA( * )\n*     .. Local Scalars ..\n      INTEGER            I, I1, I2, I3, IBEG, IEND, IOFF, J, KK\n      LOGICAL            GEN, LOWER, SYM, TRI, UNIT, UPPER\n*     .. External Functions ..\n      DOUBLE PRECISION   DBEG\n      EXTERNAL           DBEG\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX, MIN\n*     .. Executable Statements ..\n      GEN = TYPE( 1: 1 ).EQ.'G'\n      SYM = TYPE( 1: 1 ).EQ.'S'\n      TRI = TYPE( 1: 1 ).EQ.'T'\n      UPPER = ( SYM.OR.TRI ).AND.UPLO.EQ.'U'\n      LOWER = ( SYM.OR.TRI ).AND.UPLO.EQ.'L'\n      UNIT = TRI.AND.DIAG.EQ.'U'\n*\n*     Generate data in array A.\n*\n      DO 20 J = 1, N\n         DO 10 I = 1, M\n            IF( GEN.OR.( UPPER.AND.I.LE.J ).OR.( LOWER.AND.I.GE.J ) )\n     $          THEN\n               IF( ( I.LE.J.AND.J - I.LE.KU ).OR.\n     $             ( I.GE.J.AND.I - J.LE.KL ) )THEN\n                  A( I, J ) = DBEG( RESET ) + TRANSL\n               ELSE\n                  A( I, J ) = ZERO\n               END IF\n               IF( I.NE.J )THEN\n                  IF( SYM )THEN\n                     A( J, I ) = A( I, J )\n                  ELSE IF( TRI )THEN\n                     A( J, I ) = ZERO\n                  END IF\n               END IF\n            END IF\n   10    CONTINUE\n         IF( TRI )\n     $      A( J, J ) = A( J, J ) + ONE\n         IF( UNIT )\n     $      A( J, J ) = ONE\n   20 CONTINUE\n*\n*     Store elements in array AS in data structure required by routine.\n*\n      IF( TYPE.EQ.'GE' )THEN\n         DO 50 J = 1, N\n            DO 30 I = 1, M\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   30       CONTINUE\n            DO 40 I = M + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   40       CONTINUE\n   50    CONTINUE\n      ELSE IF( TYPE.EQ.'GB' )THEN\n         DO 90 J = 1, N\n            DO 60 I1 = 1, KU + 1 - J\n               AA( I1 + ( J - 1 )*LDA ) = ROGUE\n   60       CONTINUE\n            DO 70 I2 = I1, MIN( KL + KU + 1, KU + 1 + M - J )\n               AA( I2 + ( J - 1 )*LDA ) = A( I2 + J - KU - 1, J )\n   70       CONTINUE\n            DO 80 I3 = I2, LDA\n               AA( I3 + ( J - 1 )*LDA ) = ROGUE\n   80       CONTINUE\n   90    CONTINUE\n      ELSE IF( TYPE.EQ.'SY'.OR.TYPE.EQ.'TR' )THEN\n         DO 130 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IF( UNIT )THEN\n                  IEND = J - 1\n               ELSE\n                  IEND = J\n               END IF\n            ELSE\n               IF( UNIT )THEN\n                  IBEG = J + 1\n               ELSE\n                  IBEG = J\n               END IF\n               IEND = N\n            END IF\n            DO 100 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  100       CONTINUE\n            DO 110 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n  110       CONTINUE\n            DO 120 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  120       CONTINUE\n  130    CONTINUE\n      ELSE IF( TYPE.EQ.'SB'.OR.TYPE.EQ.'TB' )THEN\n         DO 170 J = 1, N\n            IF( UPPER )THEN\n               KK = KL + 1\n               IBEG = MAX( 1, KL + 2 - J )\n               IF( UNIT )THEN\n                  IEND = KL\n               ELSE\n                  IEND = KL + 1\n               END IF\n            ELSE\n               KK = 1\n               IF( UNIT )THEN\n                  IBEG = 2\n               ELSE\n                  IBEG = 1\n               END IF\n               IEND = MIN( KL + 1, 1 + M - J )\n            END IF\n            DO 140 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  140       CONTINUE\n            DO 150 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I + J - KK, J )\n  150       CONTINUE\n            DO 160 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  160       CONTINUE\n  170    CONTINUE\n      ELSE IF( TYPE.EQ.'SP'.OR.TYPE.EQ.'TP' )THEN\n         IOFF = 0\n         DO 190 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 180 I = IBEG, IEND\n               IOFF = IOFF + 1\n               AA( IOFF ) = A( I, J )\n               IF( I.EQ.J )THEN\n                  IF( UNIT )\n     $               AA( IOFF ) = ROGUE\n               END IF\n  180       CONTINUE\n  190    CONTINUE\n      END IF\n      RETURN\n*\n*     End of DMAKE.\n*\n      END\n      SUBROUTINE DMVCH( TRANS, M, N, ALPHA, A, NMAX, X, INCX, BETA, Y,\n     $                  INCY, YT, G, YY, EPS, ERR, FATAL, NOUT, MV )\n*\n*  Checks the results of the computational tests.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, ONE\n      PARAMETER          ( ZERO = 0.0D0, ONE = 1.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   ALPHA, BETA, EPS, ERR\n      INTEGER            INCX, INCY, M, N, NMAX, NOUT\n      LOGICAL            FATAL, MV\n      CHARACTER*1        TRANS\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, * ), G( * ), X( * ), Y( * ), YT( * ),\n     $                   YY( * )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ERRI\n      INTEGER            I, INCXL, INCYL, IY, J, JX, KX, KY, ML, NL\n      LOGICAL            TRAN\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, SQRT\n*     .. Executable Statements ..\n      TRAN = TRANS.EQ.'T'.OR.TRANS.EQ.'C'\n      IF( TRAN )THEN\n         ML = N\n         NL = M\n      ELSE\n         ML = M\n         NL = N\n      END IF\n      IF( INCX.LT.0 )THEN\n         KX = NL\n         INCXL = -1\n      ELSE\n         KX = 1\n         INCXL = 1\n      END IF\n      IF( INCY.LT.0 )THEN\n         KY = ML\n         INCYL = -1\n      ELSE\n         KY = 1\n         INCYL = 1\n      END IF\n*\n*     Compute expected result in YT using data in A, X and Y.\n*     Compute gauges in G.\n*\n      IY = KY\n      DO 30 I = 1, ML\n         YT( IY ) = ZERO\n         G( IY ) = ZERO\n         JX = KX\n         IF( TRAN )THEN\n            DO 10 J = 1, NL\n               YT( IY ) = YT( IY ) + A( J, I )*X( JX )\n               G( IY ) = G( IY ) + ABS( A( J, I )*X( JX ) )\n               JX = JX + INCXL\n   10       CONTINUE\n         ELSE\n            DO 20 J = 1, NL\n               YT( IY ) = YT( IY ) + A( I, J )*X( JX )\n               G( IY ) = G( IY ) + ABS( A( I, J )*X( JX ) )\n               JX = JX + INCXL\n   20       CONTINUE\n         END IF\n         YT( IY ) = ALPHA*YT( IY ) + BETA*Y( IY )\n         G( IY ) = ABS( ALPHA )*G( IY ) + ABS( BETA*Y( IY ) )\n         IY = IY + INCYL\n   30 CONTINUE\n*\n*     Compute the error ratio for this result.\n*\n      ERR = ZERO\n      DO 40 I = 1, ML\n         ERRI = ABS( YT( I ) - YY( 1 + ( I - 1 )*ABS( INCY ) ) )/EPS\n         IF( G( I ).NE.ZERO )\n     $      ERRI = ERRI/G( I )\n         ERR = MAX( ERR, ERRI )\n         IF( ERR*SQRT( EPS ).GE.ONE )\n     $      GO TO 50\n   40 CONTINUE\n*     If the loop completes, all results are at least half accurate.\n      GO TO 70\n*\n*     Report fatal error.\n*\n   50 FATAL = .TRUE.\n      WRITE( NOUT, FMT = 9999 )\n      DO 60 I = 1, ML\n         IF( MV )THEN\n            WRITE( NOUT, FMT = 9998 )I, YT( I ),\n     $         YY( 1 + ( I - 1 )*ABS( INCY ) )\n         ELSE\n            WRITE( NOUT, FMT = 9998 )I,\n     $         YY( 1 + ( I - 1 )*ABS( INCY ) ), YT( I )\n         END IF\n   60 CONTINUE\n*\n   70 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ******* FATAL ERROR - COMPUTED RESULT IS LESS THAN HAL',\n     $      'F ACCURATE *******', /'           EXPECTED RESULT   COMPU',\n     $      'TED RESULT' )\n 9998 FORMAT( 1X, I7, 2G18.6 )\n*\n*     End of DMVCH.\n*\n      END\n      LOGICAL FUNCTION LDE( RI, RJ, LR )\n*\n*  Tests if two arrays are identical.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LR\n*     .. Array Arguments ..\n      DOUBLE PRECISION   RI( * ), RJ( * )\n*     .. Local Scalars ..\n      INTEGER            I\n*     .. Executable Statements ..\n      DO 10 I = 1, LR\n         IF( RI( I ).NE.RJ( I ) )\n     $      GO TO 20\n   10 CONTINUE\n      LDE = .TRUE.\n      GO TO 30\n   20 CONTINUE\n      LDE = .FALSE.\n   30 RETURN\n*\n*     End of LDE.\n*\n      END\n      LOGICAL FUNCTION LDERES( TYPE, UPLO, M, N, AA, AS, LDA )\n*\n*  Tests if selected elements in two arrays are equal.\n*\n*  TYPE is 'GE', 'SY' or 'SP'.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LDA, M, N\n      CHARACTER*1        UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      DOUBLE PRECISION   AA( LDA, * ), AS( LDA, * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J\n      LOGICAL            UPPER\n*     .. Executable Statements ..\n      UPPER = UPLO.EQ.'U'\n      IF( TYPE.EQ.'GE' )THEN\n         DO 20 J = 1, N\n            DO 10 I = M + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   10       CONTINUE\n   20    CONTINUE\n      ELSE IF( TYPE.EQ.'SY' )THEN\n         DO 50 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 30 I = 1, IBEG - 1\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   30       CONTINUE\n            DO 40 I = IEND + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   40       CONTINUE\n   50    CONTINUE\n      END IF\n*\n      LDERES = .TRUE.\n      GO TO 80\n   70 CONTINUE\n      LDERES = .FALSE.\n   80 RETURN\n*\n*     End of LDERES.\n*\n      END\n      DOUBLE PRECISION FUNCTION DBEG( RESET )\n*\n*  Generates random numbers uniformly distributed between -0.5 and 0.5.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      LOGICAL            RESET\n*     .. Local Scalars ..\n      INTEGER            I, IC, MI\n*     .. Save statement ..\n      SAVE               I, IC, MI\n*     .. Intrinsic Functions ..\n      INTRINSIC          DBLE\n*     .. Executable Statements ..\n      IF( RESET )THEN\n*        Initialize local variables.\n         MI = 891\n         I = 7\n         IC = 0\n         RESET = .FALSE.\n      END IF\n*\n*     The sequence of values of I is bounded between 1 and 999.\n*     If initial I = 1,2,3,6,7 or 9, the period will be 50.\n*     If initial I = 4 or 8, the period will be 25.\n*     If initial I = 5, the period will be 10.\n*     IC is used to break up the period by skipping 1 value of I in 6.\n*\n      IC = IC + 1\n   10 I = I*MI\n      I = I - 1000*( I/1000 )\n      IF( IC.GE.5 )THEN\n         IC = 0\n         GO TO 10\n      END IF\n      DBEG = DBLE( I - 500 )/1001.0D0\n      RETURN\n*\n*     End of DBEG.\n*\n      END\n      DOUBLE PRECISION FUNCTION DDIFF( X, Y )\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   X, Y\n*     .. Executable Statements ..\n      DDIFF = X - Y\n      RETURN\n*\n*     End of DDIFF.\n*\n      END\n      SUBROUTINE CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n*  Tests whether XERBLA has detected an error when it should.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Executable Statements ..\n      IF( .NOT.LERR )THEN\n         WRITE( NOUT, FMT = 9999 )INFOT, SRNAMT\n         OK = .FALSE.\n      END IF\n      LERR = .FALSE.\n      RETURN\n*\n 9999 FORMAT( ' ***** ILLEGAL VALUE OF PARAMETER NUMBER ', I2, ' NOT D',\n     $      'ETECTED BY ', A6, ' *****' )\n*\n*     End of CHKXER.\n*\n      END\n      SUBROUTINE XERBLA( SRNAME, INFO )\n*\n*  This is a special version of XERBLA to be used only as part of\n*  the test program for testing error exits from the Level 2 BLAS\n*  routines.\n*\n*  XERBLA  is an error handler for the Level 2 BLAS routines.\n*\n*  It is called by the Level 2 BLAS routines if an input parameter is\n*  invalid.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFO\n      CHARACTER*6        SRNAME\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUT, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Executable Statements ..\n      LERR = .TRUE.\n      IF( INFO.NE.INFOT )THEN\n         IF( INFOT.NE.0 )THEN\n            WRITE( NOUT, FMT = 9999 )INFO, INFOT\n         ELSE\n            WRITE( NOUT, FMT = 9997 )INFO\n         END IF\n         OK = .FALSE.\n      END IF\n      IF( SRNAME.NE.SRNAMT )THEN\n         WRITE( NOUT, FMT = 9998 )SRNAME, SRNAMT\n         OK = .FALSE.\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6, ' INSTEAD',\n     $      ' OF ', I2, ' *******' )\n 9998 FORMAT( ' ******* XERBLA WAS CALLED WITH SRNAME = ', A6, ' INSTE',\n     $      'AD OF ', A6, ' *******' )\n 9997 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6,\n     $      ' *******' )\n*\n*     End of XERBLA\n*\n      END\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/testing/dblat3.f",
    "content": "*> \\brief \\b DBLAT3\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM DBLAT3\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> Test program for the DOUBLE PRECISION Level 3 Blas.\n*>\n*> The program must be driven by a short data file. The first 14 records\n*> of the file are read using list-directed input, the last 6 records\n*> are read using the format ( A6, L2 ). An annotated example of a data\n*> file can be obtained by deleting the first 3 characters from the\n*> following 20 lines:\n*> 'dblat3.out'      NAME OF SUMMARY OUTPUT FILE\n*> 6                 UNIT NUMBER OF SUMMARY FILE\n*> 'DBLAT3.SNAP'     NAME OF SNAPSHOT OUTPUT FILE\n*> -1                UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0)\n*> F        LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD.\n*> F        LOGICAL FLAG, T TO STOP ON FAILURES.\n*> T        LOGICAL FLAG, T TO TEST ERROR EXITS.\n*> 16.0     THRESHOLD VALUE OF TEST RATIO\n*> 6                 NUMBER OF VALUES OF N\n*> 0 1 2 3 5 9       VALUES OF N\n*> 3                 NUMBER OF VALUES OF ALPHA\n*> 0.0 1.0 0.7       VALUES OF ALPHA\n*> 3                 NUMBER OF VALUES OF BETA\n*> 0.0 1.0 1.3       VALUES OF BETA\n*> DGEMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DSYMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DTRMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DTRSM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DSYRK  T PUT F FOR NO TEST. SAME COLUMNS.\n*> DSYR2K T PUT F FOR NO TEST. SAME COLUMNS.\n*>\n*> Further Details\n*> ===============\n*>\n*> See:\n*>\n*>    Dongarra J. J., Du Croz J. J., Duff I. S. and Hammarling S.\n*>    A Set of Level 3 Basic Linear Algebra Subprograms.\n*>\n*>    Technical Memorandum No.88 (Revision 1), Mathematics and\n*>    Computer Science Division, Argonne National Laboratory, 9700\n*>    South Cass Avenue, Argonne, Illinois 60439, US.\n*>\n*> -- Written on 8-February-1989.\n*>    Jack Dongarra, Argonne National Laboratory.\n*>    Iain Duff, AERE Harwell.\n*>    Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*>    Sven Hammarling, Numerical Algorithms Group Ltd.\n*>\n*>    10-9-00:  Change STATUS='NEW' to 'UNKNOWN' so that the testers\n*>              can be run multiple times without deleting generated\n*>              output files (susan)\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup double_blas_testing\n*\n*  =====================================================================\n      PROGRAM DBLAT3\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER            NIN\n      PARAMETER          ( NIN = 5 )\n      INTEGER            NSUBS\n      PARAMETER          ( NSUBS = 6 )\n      DOUBLE PRECISION   ZERO, ONE\n      PARAMETER          ( ZERO = 0.0D0, ONE = 1.0D0 )\n      INTEGER            NMAX\n      PARAMETER          ( NMAX = 65 )\n      INTEGER            NIDMAX, NALMAX, NBEMAX\n      PARAMETER          ( NIDMAX = 9, NALMAX = 7, NBEMAX = 7 )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   EPS, ERR, THRESH\n      INTEGER            I, ISNUM, J, N, NALF, NBET, NIDIM, NOUT, NTRA\n      LOGICAL            FATAL, LTESTT, REWI, SAME, SFATAL, TRACE,\n     $                   TSTERR\n      CHARACTER*1        TRANSA, TRANSB\n      CHARACTER*6        SNAMET\n      CHARACTER*32       SNAPS, SUMMRY\n*     .. Local Arrays ..\n      DOUBLE PRECISION   AA( NMAX*NMAX ), AB( NMAX, 2*NMAX ),\n     $                   ALF( NALMAX ), AS( NMAX*NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBEMAX ),\n     $                   BS( NMAX*NMAX ), C( NMAX, NMAX ),\n     $                   CC( NMAX*NMAX ), CS( NMAX*NMAX ), CT( NMAX ),\n     $                   G( NMAX ), W( 2*NMAX )\n      INTEGER            IDIM( NIDMAX )\n      LOGICAL            LTEST( NSUBS )\n      CHARACTER*6        SNAMES( NSUBS )\n*     .. External Functions ..\n      DOUBLE PRECISION   DDIFF\n      LOGICAL            LDE\n      EXTERNAL           DDIFF, LDE\n*     .. External Subroutines ..\n      EXTERNAL           DCHK1, DCHK2, DCHK3, DCHK4, DCHK5, DCHKE, DMMCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Data statements ..\n      DATA               SNAMES/'DGEMM ', 'DSYMM ', 'DTRMM ', 'DTRSM ',\n     $                   'DSYRK ', 'DSYR2K'/\n*     .. Executable Statements ..\n*\n*     Read name and unit number for summary output file and open file.\n*\n      READ( NIN, FMT = * )SUMMRY\n      READ( NIN, FMT = * )NOUT\n      OPEN( NOUT, FILE = SUMMRY, STATUS = 'UNKNOWN' )\n      NOUTC = NOUT\n*\n*     Read name and unit number for snapshot output file and open file.\n*\n      READ( NIN, FMT = * )SNAPS\n      READ( NIN, FMT = * )NTRA\n      TRACE = NTRA.GE.0\n      IF( TRACE )THEN\n         OPEN( NTRA, FILE = SNAPS, STATUS = 'UNKNOWN' )\n      END IF\n*     Read the flag that directs rewinding of the snapshot file.\n      READ( NIN, FMT = * )REWI\n      REWI = REWI.AND.TRACE\n*     Read the flag that directs stopping on any failure.\n      READ( NIN, FMT = * )SFATAL\n*     Read the flag that indicates whether error exits are to be tested.\n      READ( NIN, FMT = * )TSTERR\n*     Read the threshold value of the test ratio\n      READ( NIN, FMT = * )THRESH\n*\n*     Read and check the parameter values for the tests.\n*\n*     Values of N\n      READ( NIN, FMT = * )NIDIM\n      IF( NIDIM.LT.1.OR.NIDIM.GT.NIDMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'N', NIDMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( IDIM( I ), I = 1, NIDIM )\n      DO 10 I = 1, NIDIM\n         IF( IDIM( I ).LT.0.OR.IDIM( I ).GT.NMAX )THEN\n            WRITE( NOUT, FMT = 9996 )NMAX\n            GO TO 220\n         END IF\n   10 CONTINUE\n*     Values of ALPHA\n      READ( NIN, FMT = * )NALF\n      IF( NALF.LT.1.OR.NALF.GT.NALMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'ALPHA', NALMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( ALF( I ), I = 1, NALF )\n*     Values of BETA\n      READ( NIN, FMT = * )NBET\n      IF( NBET.LT.1.OR.NBET.GT.NBEMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'BETA', NBEMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( BET( I ), I = 1, NBET )\n*\n*     Report values of parameters.\n*\n      WRITE( NOUT, FMT = 9995 )\n      WRITE( NOUT, FMT = 9994 )( IDIM( I ), I = 1, NIDIM )\n      WRITE( NOUT, FMT = 9993 )( ALF( I ), I = 1, NALF )\n      WRITE( NOUT, FMT = 9992 )( BET( I ), I = 1, NBET )\n      IF( .NOT.TSTERR )THEN\n         WRITE( NOUT, FMT = * )\n         WRITE( NOUT, FMT = 9984 )\n      END IF\n      WRITE( NOUT, FMT = * )\n      WRITE( NOUT, FMT = 9999 )THRESH\n      WRITE( NOUT, FMT = * )\n*\n*     Read names of subroutines and flags which indicate\n*     whether they are to be tested.\n*\n      DO 20 I = 1, NSUBS\n         LTEST( I ) = .FALSE.\n   20 CONTINUE\n   30 READ( NIN, FMT = 9988, END = 60 )SNAMET, LTESTT\n      DO 40 I = 1, NSUBS\n         IF( SNAMET.EQ.SNAMES( I ) )\n     $      GO TO 50\n   40 CONTINUE\n      WRITE( NOUT, FMT = 9990 )SNAMET\n      STOP\n   50 LTEST( I ) = LTESTT\n      GO TO 30\n*\n   60 CONTINUE\n      CLOSE ( NIN )\n*\n*     Compute EPS (the machine precision).\n*\n      EPS = EPSILON(ZERO)\n      WRITE( NOUT, FMT = 9998 )EPS\n*\n*     Check the reliability of DMMCH using exact data.\n*\n      N = MIN( 32, NMAX )\n      DO 100 J = 1, N\n         DO 90 I = 1, N\n            AB( I, J ) = MAX( I - J + 1, 0 )\n   90    CONTINUE\n         AB( J, NMAX + 1 ) = J\n         AB( 1, NMAX + J ) = J\n         C( J, 1 ) = ZERO\n  100 CONTINUE\n      DO 110 J = 1, N\n         CC( J ) = J*( ( J + 1 )*J )/2 - ( ( J + 1 )*J*( J - 1 ) )/3\n  110 CONTINUE\n*     CC holds the exact result. On exit from DMMCH CT holds\n*     the result computed by DMMCH.\n      TRANSA = 'N'\n      TRANSB = 'N'\n      CALL DMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LDE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      TRANSB = 'T'\n      CALL DMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LDE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      DO 120 J = 1, N\n         AB( J, NMAX + 1 ) = N - J + 1\n         AB( 1, NMAX + J ) = N - J + 1\n  120 CONTINUE\n      DO 130 J = 1, N\n         CC( N - J + 1 ) = J*( ( J + 1 )*J )/2 -\n     $                     ( ( J + 1 )*J*( J - 1 ) )/3\n  130 CONTINUE\n      TRANSA = 'T'\n      TRANSB = 'N'\n      CALL DMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LDE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      TRANSB = 'T'\n      CALL DMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LDE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n*\n*     Test each subroutine in turn.\n*\n      DO 200 ISNUM = 1, NSUBS\n         WRITE( NOUT, FMT = * )\n         IF( .NOT.LTEST( ISNUM ) )THEN\n*           Subprogram is not to be tested.\n            WRITE( NOUT, FMT = 9987 )SNAMES( ISNUM )\n         ELSE\n            SRNAMT = SNAMES( ISNUM )\n*           Test error exits.\n            IF( TSTERR )THEN\n               CALL DCHKE( ISNUM, SNAMES( ISNUM ), NOUT )\n               WRITE( NOUT, FMT = * )\n            END IF\n*           Test computations.\n            INFOT = 0\n            OK = .TRUE.\n            FATAL = .FALSE.\n            GO TO ( 140, 150, 160, 160, 170, 180 )ISNUM\n*           Test DGEMM, 01.\n  140       CALL DCHK1( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test DSYMM, 02.\n  150       CALL DCHK2( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test DTRMM, 03, DTRSM, 04.\n  160       CALL DCHK3( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NMAX, AB,\n     $                  AA, AS, AB( 1, NMAX + 1 ), BB, BS, CT, G, C )\n            GO TO 190\n*           Test DSYRK, 05.\n  170       CALL DCHK4( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test DSYR2K, 06.\n  180       CALL DCHK5( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, BB, BS, C, CC, CS, CT, G, W )\n            GO TO 190\n*\n  190       IF( FATAL.AND.SFATAL )\n     $         GO TO 210\n         END IF\n  200 CONTINUE\n      WRITE( NOUT, FMT = 9986 )\n      GO TO 230\n*\n  210 CONTINUE\n      WRITE( NOUT, FMT = 9985 )\n      GO TO 230\n*\n  220 CONTINUE\n      WRITE( NOUT, FMT = 9991 )\n*\n  230 CONTINUE\n      IF( TRACE )\n     $   CLOSE ( NTRA )\n      CLOSE ( NOUT )\n      STOP\n*\n 9999 FORMAT( ' ROUTINES PASS COMPUTATIONAL TESTS IF TEST RATIO IS LES',\n     $      'S THAN', F8.2 )\n 9998 FORMAT( ' RELATIVE MACHINE PRECISION IS TAKEN TO BE', 1P, D9.1 )\n 9997 FORMAT( ' NUMBER OF VALUES OF ', A, ' IS LESS THAN 1 OR GREATER ',\n     $      'THAN ', I2 )\n 9996 FORMAT( ' VALUE OF N IS LESS THAN 0 OR GREATER THAN ', I2 )\n 9995 FORMAT( ' TESTS OF THE DOUBLE PRECISION LEVEL 3 BLAS', //' THE F',\n     $      'OLLOWING PARAMETER VALUES WILL BE USED:' )\n 9994 FORMAT( '   FOR N              ', 9I6 )\n 9993 FORMAT( '   FOR ALPHA          ', 7F6.1 )\n 9992 FORMAT( '   FOR BETA           ', 7F6.1 )\n 9991 FORMAT( ' AMEND DATA FILE OR INCREASE ARRAY SIZES IN PROGRAM',\n     $      /' ******* TESTS ABANDONED *******' )\n 9990 FORMAT( ' SUBPROGRAM NAME ', A6, ' NOT RECOGNIZED', /' ******* T',\n     $      'ESTS ABANDONED *******' )\n 9989 FORMAT( ' ERROR IN DMMCH -  IN-LINE DOT PRODUCTS ARE BEING EVALU',\n     $      'ATED WRONGLY.', /' DMMCH WAS CALLED WITH TRANSA = ', A1,\n     $      ' AND TRANSB = ', A1, /' AND RETURNED SAME = ', L1, ' AND ',\n     $      'ERR = ', F12.3, '.', /' THIS MAY BE DUE TO FAULTS IN THE ',\n     $      'ARITHMETIC OR THE COMPILER.', /' ******* TESTS ABANDONED ',\n     $      '*******' )\n 9988 FORMAT( A6, L2 )\n 9987 FORMAT( 1X, A6, ' WAS NOT TESTED' )\n 9986 FORMAT( /' END OF TESTS' )\n 9985 FORMAT( /' ******* FATAL ERROR - TESTS ABANDONED *******' )\n 9984 FORMAT( ' ERROR-EXITS WILL NOT BE TESTED' )\n*\n*     End of DBLAT3.\n*\n      END\n      SUBROUTINE DCHK1( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests DGEMM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO\n      PARAMETER          ( ZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX ), G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, ALS, BETA, BLS, ERR, ERRMAX\n      INTEGER            I, IA, IB, ICA, ICB, IK, IM, IN, K, KS, LAA,\n     $                   LBB, LCC, LDA, LDAS, LDB, LDBS, LDC, LDCS, M,\n     $                   MA, MB, MS, N, NA, NARGS, NB, NC, NS\n      LOGICAL            NULL, RESET, SAME, TRANA, TRANB\n      CHARACTER*1        TRANAS, TRANBS, TRANSA, TRANSB\n      CHARACTER*3        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DGEMM, DMAKE, DMMCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'NTC'/\n*     .. Executable Statements ..\n*\n      NARGS = 13\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 110 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 100 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDC to 1 more than minimum value if room.\n            LDC = M\n            IF( LDC.LT.NMAX )\n     $         LDC = LDC + 1\n*           Skip tests if not enough room.\n            IF( LDC.GT.NMAX )\n     $         GO TO 100\n            LCC = LDC*N\n            NULL = N.LE.0.OR.M.LE.0\n*\n            DO 90 IK = 1, NIDIM\n               K = IDIM( IK )\n*\n               DO 80 ICA = 1, 3\n                  TRANSA = ICH( ICA: ICA )\n                  TRANA = TRANSA.EQ.'T'.OR.TRANSA.EQ.'C'\n*\n                  IF( TRANA )THEN\n                     MA = K\n                     NA = M\n                  ELSE\n                     MA = M\n                     NA = K\n                  END IF\n*                 Set LDA to 1 more than minimum value if room.\n                  LDA = MA\n                  IF( LDA.LT.NMAX )\n     $               LDA = LDA + 1\n*                 Skip tests if not enough room.\n                  IF( LDA.GT.NMAX )\n     $               GO TO 80\n                  LAA = LDA*NA\n*\n*                 Generate the matrix A.\n*\n                  CALL DMAKE( 'GE', ' ', ' ', MA, NA, A, NMAX, AA, LDA,\n     $                        RESET, ZERO )\n*\n                  DO 70 ICB = 1, 3\n                     TRANSB = ICH( ICB: ICB )\n                     TRANB = TRANSB.EQ.'T'.OR.TRANSB.EQ.'C'\n*\n                     IF( TRANB )THEN\n                        MB = N\n                        NB = K\n                     ELSE\n                        MB = K\n                        NB = N\n                     END IF\n*                    Set LDB to 1 more than minimum value if room.\n                     LDB = MB\n                     IF( LDB.LT.NMAX )\n     $                  LDB = LDB + 1\n*                    Skip tests if not enough room.\n                     IF( LDB.GT.NMAX )\n     $                  GO TO 70\n                     LBB = LDB*NB\n*\n*                    Generate the matrix B.\n*\n                     CALL DMAKE( 'GE', ' ', ' ', MB, NB, B, NMAX, BB,\n     $                           LDB, RESET, ZERO )\n*\n                     DO 60 IA = 1, NALF\n                        ALPHA = ALF( IA )\n*\n                        DO 50 IB = 1, NBET\n                           BETA = BET( IB )\n*\n*                          Generate the matrix C.\n*\n                           CALL DMAKE( 'GE', ' ', ' ', M, N, C, NMAX,\n     $                                 CC, LDC, RESET, ZERO )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           TRANAS = TRANSA\n                           TRANBS = TRANSB\n                           MS = M\n                           NS = N\n                           KS = K\n                           ALS = ALPHA\n                           DO 10 I = 1, LAA\n                              AS( I ) = AA( I )\n   10                      CONTINUE\n                           LDAS = LDA\n                           DO 20 I = 1, LBB\n                              BS( I ) = BB( I )\n   20                      CONTINUE\n                           LDBS = LDB\n                           BLS = BETA\n                           DO 30 I = 1, LCC\n                              CS( I ) = CC( I )\n   30                      CONTINUE\n                           LDCS = LDC\n*\n*                          Call the subroutine.\n*\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                        TRANSA, TRANSB, M, N, K, ALPHA, LDA, LDB,\n     $                        BETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL DGEMM( TRANSA, TRANSB, M, N, K, ALPHA,\n     $                                 AA, LDA, BB, LDB, BETA, CC, LDC )\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9994 )\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = TRANSA.EQ.TRANAS\n                           ISAME( 2 ) = TRANSB.EQ.TRANBS\n                           ISAME( 3 ) = MS.EQ.M\n                           ISAME( 4 ) = NS.EQ.N\n                           ISAME( 5 ) = KS.EQ.K\n                           ISAME( 6 ) = ALS.EQ.ALPHA\n                           ISAME( 7 ) = LDE( AS, AA, LAA )\n                           ISAME( 8 ) = LDAS.EQ.LDA\n                           ISAME( 9 ) = LDE( BS, BB, LBB )\n                           ISAME( 10 ) = LDBS.EQ.LDB\n                           ISAME( 11 ) = BLS.EQ.BETA\n                           IF( NULL )THEN\n                              ISAME( 12 ) = LDE( CS, CC, LCC )\n                           ELSE\n                              ISAME( 12 ) = LDERES( 'GE', ' ', M, N, CS,\n     $                                      CC, LDC )\n                           END IF\n                           ISAME( 13 ) = LDCS.EQ.LDC\n*\n*                          If data was incorrectly changed, report\n*                          and return.\n*\n                           SAME = .TRUE.\n                           DO 40 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   40                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n*\n*                             Check the result.\n*\n                              CALL DMMCH( TRANSA, TRANSB, M, N, K,\n     $                                    ALPHA, A, NMAX, B, NMAX, BETA,\n     $                                    C, NMAX, CT, G, CC, LDC, EPS,\n     $                                    ERR, FATAL, NOUT, .TRUE. )\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 120\n                           END IF\n*\n   50                   CONTINUE\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, TRANSA, TRANSB, M, N, K,\n     $   ALPHA, LDA, LDB, BETA, LDC\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',''', A1, ''',',\n     $      3( I3, ',' ), F4.1, ', A,', I3, ', B,', I3, ',', F4.1, ', ',\n     $      'C,', I3, ').' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK1.\n*\n      END\n      SUBROUTINE DCHK2( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests DSYMM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO\n      PARAMETER          ( ZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX ), G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, ALS, BETA, BLS, ERR, ERRMAX\n      INTEGER            I, IA, IB, ICS, ICU, IM, IN, LAA, LBB, LCC,\n     $                   LDA, LDAS, LDB, LDBS, LDC, LDCS, M, MS, N, NA,\n     $                   NARGS, NC, NS\n      LOGICAL            LEFT, NULL, RESET, SAME\n      CHARACTER*1        SIDE, SIDES, UPLO, UPLOS\n      CHARACTER*2        ICHS, ICHU\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DMAKE, DMMCH, DSYMM\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHS/'LR'/, ICHU/'UL'/\n*     .. Executable Statements ..\n*\n      NARGS = 12\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 100 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 90 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDC to 1 more than minimum value if room.\n            LDC = M\n            IF( LDC.LT.NMAX )\n     $         LDC = LDC + 1\n*           Skip tests if not enough room.\n            IF( LDC.GT.NMAX )\n     $         GO TO 90\n            LCC = LDC*N\n            NULL = N.LE.0.OR.M.LE.0\n*\n*           Set LDB to 1 more than minimum value if room.\n            LDB = M\n            IF( LDB.LT.NMAX )\n     $         LDB = LDB + 1\n*           Skip tests if not enough room.\n            IF( LDB.GT.NMAX )\n     $         GO TO 90\n            LBB = LDB*N\n*\n*           Generate the matrix B.\n*\n            CALL DMAKE( 'GE', ' ', ' ', M, N, B, NMAX, BB, LDB, RESET,\n     $                  ZERO )\n*\n            DO 80 ICS = 1, 2\n               SIDE = ICHS( ICS: ICS )\n               LEFT = SIDE.EQ.'L'\n*\n               IF( LEFT )THEN\n                  NA = M\n               ELSE\n                  NA = N\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = NA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 80\n               LAA = LDA*NA\n*\n               DO 70 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n*\n*                 Generate the symmetric matrix A.\n*\n                  CALL DMAKE( 'SY', UPLO, ' ', NA, NA, A, NMAX, AA, LDA,\n     $                        RESET, ZERO )\n*\n                  DO 60 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n                     DO 50 IB = 1, NBET\n                        BETA = BET( IB )\n*\n*                       Generate the matrix C.\n*\n                        CALL DMAKE( 'GE', ' ', ' ', M, N, C, NMAX, CC,\n     $                              LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the\n*                       subroutine.\n*\n                        SIDES = SIDE\n                        UPLOS = UPLO\n                        MS = M\n                        NS = N\n                        ALS = ALPHA\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        DO 20 I = 1, LBB\n                           BS( I ) = BB( I )\n   20                   CONTINUE\n                        LDBS = LDB\n                        BLS = BETA\n                        DO 30 I = 1, LCC\n                           CS( I ) = CC( I )\n   30                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9995 )NC, SNAME, SIDE,\n     $                     UPLO, M, N, ALPHA, LDA, LDB, BETA, LDC\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL DSYMM( SIDE, UPLO, M, N, ALPHA, AA, LDA,\n     $                              BB, LDB, BETA, CC, LDC )\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9994 )\n                           FATAL = .TRUE.\n                           GO TO 110\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = SIDES.EQ.SIDE\n                        ISAME( 2 ) = UPLOS.EQ.UPLO\n                        ISAME( 3 ) = MS.EQ.M\n                        ISAME( 4 ) = NS.EQ.N\n                        ISAME( 5 ) = ALS.EQ.ALPHA\n                        ISAME( 6 ) = LDE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        ISAME( 8 ) = LDE( BS, BB, LBB )\n                        ISAME( 9 ) = LDBS.EQ.LDB\n                        ISAME( 10 ) = BLS.EQ.BETA\n                        IF( NULL )THEN\n                           ISAME( 11 ) = LDE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 11 ) = LDERES( 'GE', ' ', M, N, CS,\n     $                                   CC, LDC )\n                        END IF\n                        ISAME( 12 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 110\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result.\n*\n                           IF( LEFT )THEN\n                              CALL DMMCH( 'N', 'N', M, N, M, ALPHA, A,\n     $                                    NMAX, B, NMAX, BETA, C, NMAX,\n     $                                    CT, G, CC, LDC, EPS, ERR,\n     $                                    FATAL, NOUT, .TRUE. )\n                           ELSE\n                              CALL DMMCH( 'N', 'N', M, N, N, ALPHA, B,\n     $                                    NMAX, A, NMAX, BETA, C, NMAX,\n     $                                    CT, G, CC, LDC, EPS, ERR,\n     $                                    FATAL, NOUT, .TRUE. )\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and\n*                          return.\n                           IF( FATAL )\n     $                        GO TO 110\n                        END IF\n*\n   50                CONTINUE\n*\n   60             CONTINUE\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 120\n*\n  110 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, SIDE, UPLO, M, N, ALPHA, LDA,\n     $   LDB, BETA, LDC\n*\n  120 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      F4.1, ', A,', I3, ', B,', I3, ',', F4.1, ', C,', I3, ')   ',\n     $      ' .' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK2.\n*\n      END\n      SUBROUTINE DCHK3( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NMAX, A, AA, AS,\n     $                  B, BB, BS, CT, G, C )\n*\n*  Tests DTRMM and DTRSM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, ONE\n      PARAMETER          ( ZERO = 0.0D0, ONE = 1.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            NALF, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CT( NMAX ), G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, ALS, ERR, ERRMAX\n      INTEGER            I, IA, ICD, ICS, ICT, ICU, IM, IN, J, LAA, LBB,\n     $                   LDA, LDAS, LDB, LDBS, M, MS, N, NA, NARGS, NC,\n     $                   NS\n      LOGICAL            LEFT, NULL, RESET, SAME\n      CHARACTER*1        DIAG, DIAGS, SIDE, SIDES, TRANAS, TRANSA, UPLO,\n     $                   UPLOS\n      CHARACTER*2        ICHD, ICHS, ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DMAKE, DMMCH, DTRMM, DTRSM\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHU/'UL'/, ICHT/'NTC'/, ICHD/'UN'/, ICHS/'LR'/\n*     .. Executable Statements ..\n*\n      NARGS = 11\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*     Set up zero matrix for DMMCH.\n      DO 20 J = 1, NMAX\n         DO 10 I = 1, NMAX\n            C( I, J ) = ZERO\n   10    CONTINUE\n   20 CONTINUE\n*\n      DO 140 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 130 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDB to 1 more than minimum value if room.\n            LDB = M\n            IF( LDB.LT.NMAX )\n     $         LDB = LDB + 1\n*           Skip tests if not enough room.\n            IF( LDB.GT.NMAX )\n     $         GO TO 130\n            LBB = LDB*N\n            NULL = M.LE.0.OR.N.LE.0\n*\n            DO 120 ICS = 1, 2\n               SIDE = ICHS( ICS: ICS )\n               LEFT = SIDE.EQ.'L'\n               IF( LEFT )THEN\n                  NA = M\n               ELSE\n                  NA = N\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = NA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 130\n               LAA = LDA*NA\n*\n               DO 110 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n*\n                  DO 100 ICT = 1, 3\n                     TRANSA = ICHT( ICT: ICT )\n*\n                     DO 90 ICD = 1, 2\n                        DIAG = ICHD( ICD: ICD )\n*\n                        DO 80 IA = 1, NALF\n                           ALPHA = ALF( IA )\n*\n*                          Generate the matrix A.\n*\n                           CALL DMAKE( 'TR', UPLO, DIAG, NA, NA, A,\n     $                                 NMAX, AA, LDA, RESET, ZERO )\n*\n*                          Generate the matrix B.\n*\n                           CALL DMAKE( 'GE', ' ', ' ', M, N, B, NMAX,\n     $                                 BB, LDB, RESET, ZERO )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           SIDES = SIDE\n                           UPLOS = UPLO\n                           TRANAS = TRANSA\n                           DIAGS = DIAG\n                           MS = M\n                           NS = N\n                           ALS = ALPHA\n                           DO 30 I = 1, LAA\n                              AS( I ) = AA( I )\n   30                      CONTINUE\n                           LDAS = LDA\n                           DO 40 I = 1, LBB\n                              BS( I ) = BB( I )\n   40                      CONTINUE\n                           LDBS = LDB\n*\n*                          Call the subroutine.\n*\n                           IF( SNAME( 4: 5 ).EQ.'MM' )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           SIDE, UPLO, TRANSA, DIAG, M, N, ALPHA,\n     $                           LDA, LDB\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DTRMM( SIDE, UPLO, TRANSA, DIAG, M,\n     $                                    N, ALPHA, AA, LDA, BB, LDB )\n                           ELSE IF( SNAME( 4: 5 ).EQ.'SM' )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           SIDE, UPLO, TRANSA, DIAG, M, N, ALPHA,\n     $                           LDA, LDB\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL DTRSM( SIDE, UPLO, TRANSA, DIAG, M,\n     $                                    N, ALPHA, AA, LDA, BB, LDB )\n                           END IF\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9994 )\n                              FATAL = .TRUE.\n                              GO TO 150\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = SIDES.EQ.SIDE\n                           ISAME( 2 ) = UPLOS.EQ.UPLO\n                           ISAME( 3 ) = TRANAS.EQ.TRANSA\n                           ISAME( 4 ) = DIAGS.EQ.DIAG\n                           ISAME( 5 ) = MS.EQ.M\n                           ISAME( 6 ) = NS.EQ.N\n                           ISAME( 7 ) = ALS.EQ.ALPHA\n                           ISAME( 8 ) = LDE( AS, AA, LAA )\n                           ISAME( 9 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 10 ) = LDE( BS, BB, LBB )\n                           ELSE\n                              ISAME( 10 ) = LDERES( 'GE', ' ', M, N, BS,\n     $                                      BB, LDB )\n                           END IF\n                           ISAME( 11 ) = LDBS.EQ.LDB\n*\n*                          If data was incorrectly changed, report and\n*                          return.\n*\n                           SAME = .TRUE.\n                           DO 50 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   50                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 150\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n                              IF( SNAME( 4: 5 ).EQ.'MM' )THEN\n*\n*                                Check the result.\n*\n                                 IF( LEFT )THEN\n                                    CALL DMMCH( TRANSA, 'N', M, N, M,\n     $                                          ALPHA, A, NMAX, B, NMAX,\n     $                                          ZERO, C, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .TRUE. )\n                                 ELSE\n                                    CALL DMMCH( 'N', TRANSA, M, N, N,\n     $                                          ALPHA, B, NMAX, A, NMAX,\n     $                                          ZERO, C, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .TRUE. )\n                                 END IF\n                              ELSE IF( SNAME( 4: 5 ).EQ.'SM' )THEN\n*\n*                                Compute approximation to original\n*                                matrix.\n*\n                                 DO 70 J = 1, N\n                                    DO 60 I = 1, M\n                                       C( I, J ) = BB( I + ( J - 1 )*\n     $                                             LDB )\n                                       BB( I + ( J - 1 )*LDB ) = ALPHA*\n     $                                    B( I, J )\n   60                               CONTINUE\n   70                            CONTINUE\n*\n                                 IF( LEFT )THEN\n                                    CALL DMMCH( TRANSA, 'N', M, N, M,\n     $                                          ONE, A, NMAX, C, NMAX,\n     $                                          ZERO, B, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .FALSE. )\n                                 ELSE\n                                    CALL DMMCH( 'N', TRANSA, M, N, N,\n     $                                          ONE, C, NMAX, A, NMAX,\n     $                                          ZERO, B, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .FALSE. )\n                                 END IF\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 150\n                           END IF\n*\n   80                   CONTINUE\n*\n   90                CONTINUE\n*\n  100             CONTINUE\n*\n  110          CONTINUE\n*\n  120       CONTINUE\n*\n  130    CONTINUE\n*\n  140 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 160\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, SIDE, UPLO, TRANSA, DIAG, M,\n     $   N, ALPHA, LDA, LDB\n*\n  160 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 4( '''', A1, ''',' ), 2( I3, ',' ),\n     $      F4.1, ', A,', I3, ', B,', I3, ')        .' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK3.\n*\n      END\n      SUBROUTINE DCHK4( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests DSYRK.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO\n      PARAMETER          ( ZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX ), G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, ALS, BETA, BETS, ERR, ERRMAX\n      INTEGER            I, IA, IB, ICT, ICU, IK, IN, J, JC, JJ, K, KS,\n     $                   LAA, LCC, LDA, LDAS, LDC, LDCS, LJ, MA, N, NA,\n     $                   NARGS, NC, NS\n      LOGICAL            NULL, RESET, SAME, TRAN, UPPER\n      CHARACTER*1        TRANS, TRANSS, UPLO, UPLOS\n      CHARACTER*2        ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DMAKE, DMMCH, DSYRK\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHT/'NTC'/, ICHU/'UL'/\n*     .. Executable Statements ..\n*\n      NARGS = 10\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 100 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDC to 1 more than minimum value if room.\n         LDC = N\n         IF( LDC.LT.NMAX )\n     $      LDC = LDC + 1\n*        Skip tests if not enough room.\n         IF( LDC.GT.NMAX )\n     $      GO TO 100\n         LCC = LDC*N\n         NULL = N.LE.0\n*\n         DO 90 IK = 1, NIDIM\n            K = IDIM( IK )\n*\n            DO 80 ICT = 1, 3\n               TRANS = ICHT( ICT: ICT )\n               TRAN = TRANS.EQ.'T'.OR.TRANS.EQ.'C'\n               IF( TRAN )THEN\n                  MA = K\n                  NA = N\n               ELSE\n                  MA = N\n                  NA = K\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = MA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 80\n               LAA = LDA*NA\n*\n*              Generate the matrix A.\n*\n               CALL DMAKE( 'GE', ' ', ' ', MA, NA, A, NMAX, AA, LDA,\n     $                     RESET, ZERO )\n*\n               DO 70 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n                  UPPER = UPLO.EQ.'U'\n*\n                  DO 60 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n                     DO 50 IB = 1, NBET\n                        BETA = BET( IB )\n*\n*                       Generate the matrix C.\n*\n                        CALL DMAKE( 'SY', UPLO, ' ', N, N, C, NMAX, CC,\n     $                              LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        NS = N\n                        KS = K\n                        ALS = ALPHA\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        BETS = BETA\n                        DO 20 I = 1, LCC\n                           CS( I ) = CC( I )\n   20                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO,\n     $                     TRANS, N, K, ALPHA, LDA, BETA, LDC\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL DSYRK( UPLO, TRANS, N, K, ALPHA, AA, LDA,\n     $                              BETA, CC, LDC )\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9993 )\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLOS.EQ.UPLO\n                        ISAME( 2 ) = TRANSS.EQ.TRANS\n                        ISAME( 3 ) = NS.EQ.N\n                        ISAME( 4 ) = KS.EQ.K\n                        ISAME( 5 ) = ALS.EQ.ALPHA\n                        ISAME( 6 ) = LDE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        ISAME( 8 ) = BETS.EQ.BETA\n                        IF( NULL )THEN\n                           ISAME( 9 ) = LDE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 9 ) = LDERES( 'SY', UPLO, N, N, CS,\n     $                                  CC, LDC )\n                        END IF\n                        ISAME( 10 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 30 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   30                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result column by column.\n*\n                           JC = 1\n                           DO 40 J = 1, N\n                              IF( UPPER )THEN\n                                 JJ = 1\n                                 LJ = J\n                              ELSE\n                                 JJ = J\n                                 LJ = N - J + 1\n                              END IF\n                              IF( TRAN )THEN\n                                 CALL DMMCH( 'T', 'N', LJ, 1, K, ALPHA,\n     $                                       A( 1, JJ ), NMAX,\n     $                                       A( 1, J ), NMAX, BETA,\n     $                                       C( JJ, J ), NMAX, CT, G,\n     $                                       CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              ELSE\n                                 CALL DMMCH( 'N', 'T', LJ, 1, K, ALPHA,\n     $                                       A( JJ, 1 ), NMAX,\n     $                                       A( J, 1 ), NMAX, BETA,\n     $                                       C( JJ, J ), NMAX, CT, G,\n     $                                       CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              END IF\n                              IF( UPPER )THEN\n                                 JC = JC + LDC\n                              ELSE\n                                 JC = JC + LDC + 1\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 110\n   40                      CONTINUE\n                        END IF\n*\n   50                CONTINUE\n*\n   60             CONTINUE\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  110 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9995 )J\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, N, K, ALPHA,\n     $   LDA, BETA, LDC\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      F4.1, ', A,', I3, ',', F4.1, ', C,', I3, ')           .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK4.\n*\n      END\n      SUBROUTINE DCHK5( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  AB, AA, AS, BB, BS, C, CC, CS, CT, G, W )\n*\n*  Tests DSYR2K.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO\n      PARAMETER          ( ZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      DOUBLE PRECISION   AA( NMAX*NMAX ), AB( 2*NMAX*NMAX ),\n     $                   ALF( NALF ), AS( NMAX*NMAX ), BB( NMAX*NMAX ),\n     $                   BET( NBET ), BS( NMAX*NMAX ), C( NMAX, NMAX ),\n     $                   CC( NMAX*NMAX ), CS( NMAX*NMAX ), CT( NMAX ),\n     $                   G( NMAX ), W( 2*NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, ALS, BETA, BETS, ERR, ERRMAX\n      INTEGER            I, IA, IB, ICT, ICU, IK, IN, J, JC, JJ, JJAB,\n     $                   K, KS, LAA, LBB, LCC, LDA, LDAS, LDB, LDBS,\n     $                   LDC, LDCS, LJ, MA, N, NA, NARGS, NC, NS\n      LOGICAL            NULL, RESET, SAME, TRAN, UPPER\n      CHARACTER*1        TRANS, TRANSS, UPLO, UPLOS\n      CHARACTER*2        ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LDE, LDERES\n      EXTERNAL           LDE, LDERES\n*     .. External Subroutines ..\n      EXTERNAL           DMAKE, DMMCH, DSYR2K\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHT/'NTC'/, ICHU/'UL'/\n*     .. Executable Statements ..\n*\n      NARGS = 12\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 130 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDC to 1 more than minimum value if room.\n         LDC = N\n         IF( LDC.LT.NMAX )\n     $      LDC = LDC + 1\n*        Skip tests if not enough room.\n         IF( LDC.GT.NMAX )\n     $      GO TO 130\n         LCC = LDC*N\n         NULL = N.LE.0\n*\n         DO 120 IK = 1, NIDIM\n            K = IDIM( IK )\n*\n            DO 110 ICT = 1, 3\n               TRANS = ICHT( ICT: ICT )\n               TRAN = TRANS.EQ.'T'.OR.TRANS.EQ.'C'\n               IF( TRAN )THEN\n                  MA = K\n                  NA = N\n               ELSE\n                  MA = N\n                  NA = K\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = MA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 110\n               LAA = LDA*NA\n*\n*              Generate the matrix A.\n*\n               IF( TRAN )THEN\n                  CALL DMAKE( 'GE', ' ', ' ', MA, NA, AB, 2*NMAX, AA,\n     $                        LDA, RESET, ZERO )\n               ELSE\n                  CALL DMAKE( 'GE', ' ', ' ', MA, NA, AB, NMAX, AA, LDA,\n     $                        RESET, ZERO )\n               END IF\n*\n*              Generate the matrix B.\n*\n               LDB = LDA\n               LBB = LAA\n               IF( TRAN )THEN\n                  CALL DMAKE( 'GE', ' ', ' ', MA, NA, AB( K + 1 ),\n     $                        2*NMAX, BB, LDB, RESET, ZERO )\n               ELSE\n                  CALL DMAKE( 'GE', ' ', ' ', MA, NA, AB( K*NMAX + 1 ),\n     $                        NMAX, BB, LDB, RESET, ZERO )\n               END IF\n*\n               DO 100 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n                  UPPER = UPLO.EQ.'U'\n*\n                  DO 90 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n                     DO 80 IB = 1, NBET\n                        BETA = BET( IB )\n*\n*                       Generate the matrix C.\n*\n                        CALL DMAKE( 'SY', UPLO, ' ', N, N, C, NMAX, CC,\n     $                              LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        NS = N\n                        KS = K\n                        ALS = ALPHA\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        DO 20 I = 1, LBB\n                           BS( I ) = BB( I )\n   20                   CONTINUE\n                        LDBS = LDB\n                        BETS = BETA\n                        DO 30 I = 1, LCC\n                           CS( I ) = CC( I )\n   30                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO,\n     $                     TRANS, N, K, ALPHA, LDA, LDB, BETA, LDC\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL DSYR2K( UPLO, TRANS, N, K, ALPHA, AA, LDA,\n     $                               BB, LDB, BETA, CC, LDC )\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9993 )\n                           FATAL = .TRUE.\n                           GO TO 150\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLOS.EQ.UPLO\n                        ISAME( 2 ) = TRANSS.EQ.TRANS\n                        ISAME( 3 ) = NS.EQ.N\n                        ISAME( 4 ) = KS.EQ.K\n                        ISAME( 5 ) = ALS.EQ.ALPHA\n                        ISAME( 6 ) = LDE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        ISAME( 8 ) = LDE( BS, BB, LBB )\n                        ISAME( 9 ) = LDBS.EQ.LDB\n                        ISAME( 10 ) = BETS.EQ.BETA\n                        IF( NULL )THEN\n                           ISAME( 11 ) = LDE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 11 ) = LDERES( 'SY', UPLO, N, N, CS,\n     $                                   CC, LDC )\n                        END IF\n                        ISAME( 12 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 150\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result column by column.\n*\n                           JJAB = 1\n                           JC = 1\n                           DO 70 J = 1, N\n                              IF( UPPER )THEN\n                                 JJ = 1\n                                 LJ = J\n                              ELSE\n                                 JJ = J\n                                 LJ = N - J + 1\n                              END IF\n                              IF( TRAN )THEN\n                                 DO 50 I = 1, K\n                                    W( I ) = AB( ( J - 1 )*2*NMAX + K +\n     $                                       I )\n                                    W( K + I ) = AB( ( J - 1 )*2*NMAX +\n     $                                           I )\n   50                            CONTINUE\n                                 CALL DMMCH( 'T', 'N', LJ, 1, 2*K,\n     $                                       ALPHA, AB( JJAB ), 2*NMAX,\n     $                                       W, 2*NMAX, BETA,\n     $                                       C( JJ, J ), NMAX, CT, G,\n     $                                       CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              ELSE\n                                 DO 60 I = 1, K\n                                    W( I ) = AB( ( K + I - 1 )*NMAX +\n     $                                       J )\n                                    W( K + I ) = AB( ( I - 1 )*NMAX +\n     $                                           J )\n   60                            CONTINUE\n                                 CALL DMMCH( 'N', 'N', LJ, 1, 2*K,\n     $                                       ALPHA, AB( JJ ), NMAX, W,\n     $                                       2*NMAX, BETA, C( JJ, J ),\n     $                                       NMAX, CT, G, CC( JC ), LDC,\n     $                                       EPS, ERR, FATAL, NOUT,\n     $                                       .TRUE. )\n                              END IF\n                              IF( UPPER )THEN\n                                 JC = JC + LDC\n                              ELSE\n                                 JC = JC + LDC + 1\n                                 IF( TRAN )\n     $                              JJAB = JJAB + 2*NMAX\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 140\n   70                      CONTINUE\n                        END IF\n*\n   80                CONTINUE\n*\n   90             CONTINUE\n*\n  100          CONTINUE\n*\n  110       CONTINUE\n*\n  120    CONTINUE\n*\n  130 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 160\n*\n  140 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9995 )J\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, N, K, ALPHA,\n     $   LDA, LDB, BETA, LDC\n*\n  160 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      F4.1, ', A,', I3, ', B,', I3, ',', F4.1, ', C,', I3, ')   ',\n     $      ' .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of DCHK5.\n*\n      END\n      SUBROUTINE DCHKE( ISNUM, SRNAMT, NOUT )\n*\n*  Tests the error exits from the Level 3 Blas.\n*  Requires a special version of the error-handling routine XERBLA.\n*  A, B and C should not need to be defined.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*  3-19-92:  Initialize ALPHA and BETA  (eca)\n*  3-19-92:  Fix argument 12 in calls to SSYMM with INFOT = 9  (eca)\n*\n*     .. Scalar Arguments ..\n      INTEGER            ISNUM, NOUT\n      CHARACTER*6        SRNAMT\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Parameters ..\n      DOUBLE PRECISION   ONE, TWO\n      PARAMETER          ( ONE = 1.0D0, TWO = 2.0D0 )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ALPHA, BETA\n*     .. Local Arrays ..\n      DOUBLE PRECISION   A( 2, 1 ), B( 2, 1 ), C( 2, 1 )\n*     .. External Subroutines ..\n      EXTERNAL           CHKXER, DGEMM, DSYMM, DSYR2K, DSYRK, DTRMM,\n     $                   DTRSM\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n*     OK is set to .FALSE. by the special version of XERBLA or by CHKXER\n*     if anything is wrong.\n      OK = .TRUE.\n*     LERR is set to .TRUE. by the special version of XERBLA each time\n*     it is called, and is then tested and re-set by CHKXER.\n      LERR = .FALSE.\n*\n*     Initialize ALPHA and BETA.\n*\n      ALPHA = ONE\n      BETA = TWO\n*\n      GO TO ( 10, 20, 30, 40, 50, 60 )ISNUM\n   10 INFOT = 1\n      CALL DGEMM( '/', 'N', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 1\n      CALL DGEMM( '/', 'T', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DGEMM( 'N', '/', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DGEMM( 'T', '/', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DGEMM( 'N', 'N', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DGEMM( 'N', 'T', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DGEMM( 'T', 'N', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DGEMM( 'T', 'T', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DGEMM( 'N', 'N', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DGEMM( 'N', 'T', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DGEMM( 'T', 'N', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DGEMM( 'T', 'T', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DGEMM( 'N', 'N', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DGEMM( 'N', 'T', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DGEMM( 'T', 'N', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DGEMM( 'T', 'T', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL DGEMM( 'N', 'N', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL DGEMM( 'N', 'T', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL DGEMM( 'T', 'N', 0, 0, 2, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL DGEMM( 'T', 'T', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL DGEMM( 'N', 'N', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL DGEMM( 'T', 'N', 0, 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL DGEMM( 'N', 'T', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL DGEMM( 'T', 'T', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL DGEMM( 'N', 'N', 2, 0, 0, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL DGEMM( 'N', 'T', 2, 0, 0, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL DGEMM( 'T', 'N', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL DGEMM( 'T', 'T', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 70\n   20 INFOT = 1\n      CALL DSYMM( '/', 'U', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DSYMM( 'L', '/', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYMM( 'L', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYMM( 'R', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYMM( 'L', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYMM( 'R', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYMM( 'L', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYMM( 'R', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYMM( 'L', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYMM( 'R', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYMM( 'L', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYMM( 'R', 'U', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYMM( 'L', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYMM( 'R', 'L', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL DSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL DSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL DSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL DSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 70\n   30 INFOT = 1\n      CALL DTRMM( '/', 'U', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DTRMM( 'L', '/', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DTRMM( 'L', 'U', '/', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DTRMM( 'L', 'U', 'N', '/', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRMM( 'L', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRMM( 'L', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRMM( 'R', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRMM( 'R', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRMM( 'L', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRMM( 'L', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRMM( 'R', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRMM( 'R', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRMM( 'L', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRMM( 'L', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRMM( 'R', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRMM( 'R', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRMM( 'L', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRMM( 'L', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRMM( 'R', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRMM( 'R', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRMM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRMM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRMM( 'R', 'U', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRMM( 'R', 'U', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRMM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRMM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRMM( 'R', 'L', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRMM( 'R', 'L', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRMM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRMM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRMM( 'R', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRMM( 'R', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRMM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRMM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRMM( 'R', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRMM( 'R', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 70\n   40 INFOT = 1\n      CALL DTRSM( '/', 'U', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DTRSM( 'L', '/', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DTRSM( 'L', 'U', '/', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DTRSM( 'L', 'U', 'N', '/', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRSM( 'L', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRSM( 'L', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRSM( 'R', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRSM( 'R', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRSM( 'L', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRSM( 'L', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRSM( 'R', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL DTRSM( 'R', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRSM( 'L', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRSM( 'L', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRSM( 'R', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRSM( 'R', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRSM( 'L', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRSM( 'L', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRSM( 'R', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL DTRSM( 'R', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRSM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRSM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRSM( 'R', 'U', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRSM( 'R', 'U', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRSM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRSM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRSM( 'R', 'L', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DTRSM( 'R', 'L', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRSM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRSM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRSM( 'R', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRSM( 'R', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRSM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRSM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRSM( 'R', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL DTRSM( 'R', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 70\n   50 INFOT = 1\n      CALL DSYRK( '/', 'N', 0, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DSYRK( 'U', '/', 0, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYRK( 'U', 'N', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYRK( 'U', 'T', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYRK( 'L', 'N', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYRK( 'L', 'T', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYRK( 'U', 'N', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYRK( 'U', 'T', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYRK( 'L', 'N', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYRK( 'L', 'T', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYRK( 'U', 'N', 2, 0, ALPHA, A, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYRK( 'U', 'T', 0, 2, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYRK( 'L', 'N', 2, 0, ALPHA, A, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYRK( 'L', 'T', 0, 2, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL DSYRK( 'U', 'N', 2, 0, ALPHA, A, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL DSYRK( 'U', 'T', 2, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL DSYRK( 'L', 'N', 2, 0, ALPHA, A, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL DSYRK( 'L', 'T', 2, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 70\n   60 INFOT = 1\n      CALL DSYR2K( '/', 'N', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL DSYR2K( 'U', '/', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYR2K( 'U', 'N', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYR2K( 'U', 'T', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYR2K( 'L', 'N', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL DSYR2K( 'L', 'T', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYR2K( 'U', 'N', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYR2K( 'U', 'T', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYR2K( 'L', 'N', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL DSYR2K( 'L', 'T', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYR2K( 'U', 'N', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYR2K( 'U', 'T', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYR2K( 'L', 'N', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL DSYR2K( 'L', 'T', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DSYR2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DSYR2K( 'U', 'T', 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DSYR2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL DSYR2K( 'L', 'T', 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL DSYR2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL DSYR2K( 'U', 'T', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL DSYR2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL DSYR2K( 'L', 'T', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n   70 IF( OK )THEN\n         WRITE( NOUT, FMT = 9999 )SRNAMT\n      ELSE\n         WRITE( NOUT, FMT = 9998 )SRNAMT\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE TESTS OF ERROR-EXITS' )\n 9998 FORMAT( ' ******* ', A6, ' FAILED THE TESTS OF ERROR-EXITS *****',\n     $      '**' )\n*\n*     End of DCHKE.\n*\n      END\n      SUBROUTINE DMAKE( TYPE, UPLO, DIAG, M, N, A, NMAX, AA, LDA, RESET,\n     $                  TRANSL )\n*\n*  Generates values for an M by N matrix A.\n*  Stores the values in the array AA in the data structure required\n*  by the routine, with unwanted elements set to rogue value.\n*\n*  TYPE is 'GE', 'SY' or 'TR'.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, ONE\n      PARAMETER          ( ZERO = 0.0D0, ONE = 1.0D0 )\n      DOUBLE PRECISION   ROGUE\n      PARAMETER          ( ROGUE = -1.0D10 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   TRANSL\n      INTEGER            LDA, M, N, NMAX\n      LOGICAL            RESET\n      CHARACTER*1        DIAG, UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( NMAX, * ), AA( * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J\n      LOGICAL            GEN, LOWER, SYM, TRI, UNIT, UPPER\n*     .. External Functions ..\n      DOUBLE PRECISION   DBEG\n      EXTERNAL           DBEG\n*     .. Executable Statements ..\n      GEN = TYPE.EQ.'GE'\n      SYM = TYPE.EQ.'SY'\n      TRI = TYPE.EQ.'TR'\n      UPPER = ( SYM.OR.TRI ).AND.UPLO.EQ.'U'\n      LOWER = ( SYM.OR.TRI ).AND.UPLO.EQ.'L'\n      UNIT = TRI.AND.DIAG.EQ.'U'\n*\n*     Generate data in array A.\n*\n      DO 20 J = 1, N\n         DO 10 I = 1, M\n            IF( GEN.OR.( UPPER.AND.I.LE.J ).OR.( LOWER.AND.I.GE.J ) )\n     $          THEN\n               A( I, J ) = DBEG( RESET ) + TRANSL\n               IF( I.NE.J )THEN\n*                 Set some elements to zero\n                  IF( N.GT.3.AND.J.EQ.N/2 )\n     $               A( I, J ) = ZERO\n                  IF( SYM )THEN\n                     A( J, I ) = A( I, J )\n                  ELSE IF( TRI )THEN\n                     A( J, I ) = ZERO\n                  END IF\n               END IF\n            END IF\n   10    CONTINUE\n         IF( TRI )\n     $      A( J, J ) = A( J, J ) + ONE\n         IF( UNIT )\n     $      A( J, J ) = ONE\n   20 CONTINUE\n*\n*     Store elements in array AS in data structure required by routine.\n*\n      IF( TYPE.EQ.'GE' )THEN\n         DO 50 J = 1, N\n            DO 30 I = 1, M\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   30       CONTINUE\n            DO 40 I = M + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   40       CONTINUE\n   50    CONTINUE\n      ELSE IF( TYPE.EQ.'SY'.OR.TYPE.EQ.'TR' )THEN\n         DO 90 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IF( UNIT )THEN\n                  IEND = J - 1\n               ELSE\n                  IEND = J\n               END IF\n            ELSE\n               IF( UNIT )THEN\n                  IBEG = J + 1\n               ELSE\n                  IBEG = J\n               END IF\n               IEND = N\n            END IF\n            DO 60 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   60       CONTINUE\n            DO 70 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   70       CONTINUE\n            DO 80 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   80       CONTINUE\n   90    CONTINUE\n      END IF\n      RETURN\n*\n*     End of DMAKE.\n*\n      END\n      SUBROUTINE DMMCH( TRANSA, TRANSB, M, N, KK, ALPHA, A, LDA, B, LDB,\n     $                  BETA, C, LDC, CT, G, CC, LDCC, EPS, ERR, FATAL,\n     $                  NOUT, MV )\n*\n*  Checks the results of the computational tests.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO, ONE\n      PARAMETER          ( ZERO = 0.0D0, ONE = 1.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   ALPHA, BETA, EPS, ERR\n      INTEGER            KK, LDA, LDB, LDC, LDCC, M, N, NOUT\n      LOGICAL            FATAL, MV\n      CHARACTER*1        TRANSA, TRANSB\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( LDA, * ), B( LDB, * ), C( LDC, * ),\n     $                   CC( LDCC, * ), CT( * ), G( * )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ERRI\n      INTEGER            I, J, K\n      LOGICAL            TRANA, TRANB\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, SQRT\n*     .. Executable Statements ..\n      TRANA = TRANSA.EQ.'T'.OR.TRANSA.EQ.'C'\n      TRANB = TRANSB.EQ.'T'.OR.TRANSB.EQ.'C'\n*\n*     Compute expected result, one column at a time, in CT using data\n*     in A, B and C.\n*     Compute gauges in G.\n*\n      DO 120 J = 1, N\n*\n         DO 10 I = 1, M\n            CT( I ) = ZERO\n            G( I ) = ZERO\n   10    CONTINUE\n         IF( .NOT.TRANA.AND..NOT.TRANB )THEN\n            DO 30 K = 1, KK\n               DO 20 I = 1, M\n                  CT( I ) = CT( I ) + A( I, K )*B( K, J )\n                  G( I ) = G( I ) + ABS( A( I, K ) )*ABS( B( K, J ) )\n   20          CONTINUE\n   30       CONTINUE\n         ELSE IF( TRANA.AND..NOT.TRANB )THEN\n            DO 50 K = 1, KK\n               DO 40 I = 1, M\n                  CT( I ) = CT( I ) + A( K, I )*B( K, J )\n                  G( I ) = G( I ) + ABS( A( K, I ) )*ABS( B( K, J ) )\n   40          CONTINUE\n   50       CONTINUE\n         ELSE IF( .NOT.TRANA.AND.TRANB )THEN\n            DO 70 K = 1, KK\n               DO 60 I = 1, M\n                  CT( I ) = CT( I ) + A( I, K )*B( J, K )\n                  G( I ) = G( I ) + ABS( A( I, K ) )*ABS( B( J, K ) )\n   60          CONTINUE\n   70       CONTINUE\n         ELSE IF( TRANA.AND.TRANB )THEN\n            DO 90 K = 1, KK\n               DO 80 I = 1, M\n                  CT( I ) = CT( I ) + A( K, I )*B( J, K )\n                  G( I ) = G( I ) + ABS( A( K, I ) )*ABS( B( J, K ) )\n   80          CONTINUE\n   90       CONTINUE\n         END IF\n         DO 100 I = 1, M\n            CT( I ) = ALPHA*CT( I ) + BETA*C( I, J )\n            G( I ) = ABS( ALPHA )*G( I ) + ABS( BETA )*ABS( C( I, J ) )\n  100    CONTINUE\n*\n*        Compute the error ratio for this result.\n*\n         ERR = ZERO\n         DO 110 I = 1, M\n            ERRI = ABS( CT( I ) - CC( I, J ) )/EPS\n            IF( G( I ).NE.ZERO )\n     $         ERRI = ERRI/G( I )\n            ERR = MAX( ERR, ERRI )\n            IF( ERR*SQRT( EPS ).GE.ONE )\n     $         GO TO 130\n  110    CONTINUE\n*\n  120 CONTINUE\n*\n*     If the loop completes, all results are at least half accurate.\n      GO TO 150\n*\n*     Report fatal error.\n*\n  130 FATAL = .TRUE.\n      WRITE( NOUT, FMT = 9999 )\n      DO 140 I = 1, M\n         IF( MV )THEN\n            WRITE( NOUT, FMT = 9998 )I, CT( I ), CC( I, J )\n         ELSE\n            WRITE( NOUT, FMT = 9998 )I, CC( I, J ), CT( I )\n         END IF\n  140 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9997 )J\n*\n  150 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ******* FATAL ERROR - COMPUTED RESULT IS LESS THAN HAL',\n     $      'F ACCURATE *******', /'           EXPECTED RESULT   COMPU',\n     $      'TED RESULT' )\n 9998 FORMAT( 1X, I7, 2G18.6 )\n 9997 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n*\n*     End of DMMCH.\n*\n      END\n      LOGICAL FUNCTION LDE( RI, RJ, LR )\n*\n*  Tests if two arrays are identical.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LR\n*     .. Array Arguments ..\n      DOUBLE PRECISION   RI( * ), RJ( * )\n*     .. Local Scalars ..\n      INTEGER            I\n*     .. Executable Statements ..\n      DO 10 I = 1, LR\n         IF( RI( I ).NE.RJ( I ) )\n     $      GO TO 20\n   10 CONTINUE\n      LDE = .TRUE.\n      GO TO 30\n   20 CONTINUE\n      LDE = .FALSE.\n   30 RETURN\n*\n*     End of LDE.\n*\n      END\n      LOGICAL FUNCTION LDERES( TYPE, UPLO, M, N, AA, AS, LDA )\n*\n*  Tests if selected elements in two arrays are equal.\n*\n*  TYPE is 'GE' or 'SY'.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LDA, M, N\n      CHARACTER*1        UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      DOUBLE PRECISION   AA( LDA, * ), AS( LDA, * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J\n      LOGICAL            UPPER\n*     .. Executable Statements ..\n      UPPER = UPLO.EQ.'U'\n      IF( TYPE.EQ.'GE' )THEN\n         DO 20 J = 1, N\n            DO 10 I = M + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   10       CONTINUE\n   20    CONTINUE\n      ELSE IF( TYPE.EQ.'SY' )THEN\n         DO 50 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 30 I = 1, IBEG - 1\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   30       CONTINUE\n            DO 40 I = IEND + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   40       CONTINUE\n   50    CONTINUE\n      END IF\n*\n      LDERES = .TRUE.\n      GO TO 80\n   70 CONTINUE\n      LDERES = .FALSE.\n   80 RETURN\n*\n*     End of LDERES.\n*\n      END\n      DOUBLE PRECISION FUNCTION DBEG( RESET )\n*\n*  Generates random numbers uniformly distributed between -0.5 and 0.5.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      LOGICAL            RESET\n*     .. Local Scalars ..\n      INTEGER            I, IC, MI\n*     .. Save statement ..\n      SAVE               I, IC, MI\n*     .. Executable Statements ..\n      IF( RESET )THEN\n*        Initialize local variables.\n         MI = 891\n         I = 7\n         IC = 0\n         RESET = .FALSE.\n      END IF\n*\n*     The sequence of values of I is bounded between 1 and 999.\n*     If initial I = 1,2,3,6,7 or 9, the period will be 50.\n*     If initial I = 4 or 8, the period will be 25.\n*     If initial I = 5, the period will be 10.\n*     IC is used to break up the period by skipping 1 value of I in 6.\n*\n      IC = IC + 1\n   10 I = I*MI\n      I = I - 1000*( I/1000 )\n      IF( IC.GE.5 )THEN\n         IC = 0\n         GO TO 10\n      END IF\n      DBEG = ( I - 500 )/1001.0D0\n      RETURN\n*\n*     End of DBEG.\n*\n      END\n      DOUBLE PRECISION FUNCTION DDIFF( X, Y )\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   X, Y\n*     .. Executable Statements ..\n      DDIFF = X - Y\n      RETURN\n*\n*     End of DDIFF.\n*\n      END\n      SUBROUTINE CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n*  Tests whether XERBLA has detected an error when it should.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Executable Statements ..\n      IF( .NOT.LERR )THEN\n         WRITE( NOUT, FMT = 9999 )INFOT, SRNAMT\n         OK = .FALSE.\n      END IF\n      LERR = .FALSE.\n      RETURN\n*\n 9999 FORMAT( ' ***** ILLEGAL VALUE OF PARAMETER NUMBER ', I2, ' NOT D',\n     $      'ETECTED BY ', A6, ' *****' )\n*\n*     End of CHKXER.\n*\n      END\n      SUBROUTINE XERBLA( SRNAME, INFO )\n*\n*  This is a special version of XERBLA to be used only as part of\n*  the test program for testing error exits from the Level 3 BLAS\n*  routines.\n*\n*  XERBLA  is an error handler for the Level 3 BLAS routines.\n*\n*  It is called by the Level 3 BLAS routines if an input parameter is\n*  invalid.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFO\n      CHARACTER*6        SRNAME\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUT, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Executable Statements ..\n      LERR = .TRUE.\n      IF( INFO.NE.INFOT )THEN\n         IF( INFOT.NE.0 )THEN\n            WRITE( NOUT, FMT = 9999 )INFO, INFOT\n         ELSE\n            WRITE( NOUT, FMT = 9997 )INFO\n         END IF\n         OK = .FALSE.\n      END IF\n      IF( SRNAME.NE.SRNAMT )THEN\n         WRITE( NOUT, FMT = 9998 )SRNAME, SRNAMT\n         OK = .FALSE.\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6, ' INSTEAD',\n     $      ' OF ', I2, ' *******' )\n 9998 FORMAT( ' ******* XERBLA WAS CALLED WITH SRNAME = ', A6, ' INSTE',\n     $      'AD OF ', A6, ' *******' )\n 9997 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6,\n     $      ' *******' )\n*\n*     End of XERBLA\n*\n      END\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/testing/runblastest.sh",
    "content": "#!/bin/bash\n\nblack='\\E[30m'\nred='\\E[31m'\ngreen='\\E[32m'\nyellow='\\E[33m'\nblue='\\E[34m'\nmagenta='\\E[35m'\ncyan='\\E[36m'\nwhite='\\E[37m'\n\nif [ -f $2 ]; then\n  data=$2\n  if [ -f $1.summ ]; then rm $1.summ; fi\n  if [ -f $1.snap ]; then rm $1.snap; fi\nelse\n  data=$1\nfi\n\nif ! ./$1 < $data > /dev/null 2> .runtest.log ; then\n  echo -e  $red Test $1 failed: $black\n  echo -e $blue\n  cat .runtest.log\n  echo -e $black\n  exit 1\nelse\n  if [ -f $1.summ ]; then\n    if [ `grep \"FATAL ERROR\" $1.summ | wc -l` -gt 0 ]; then\n      echo -e  $red \"Test $1 failed (FATAL ERROR, read the file $1.summ for details)\" $black\n      echo -e $blue\n      cat .runtest.log\n      echo -e $black\n      exit 1;\n    fi\n\n    if [ `grep \"FAILED THE TESTS OF ERROR-EXITS\" $1.summ | wc -l` -gt 0 ]; then\n      echo -e  $red \"Test $1 failed (FAILED THE TESTS OF ERROR-EXITS, read the file $1.summ for details)\" $black\n      echo -e $blue\n      cat .runtest.log\n      echo -e $black\n      exit 1;\n    fi      \n  fi\n  echo -e $green Test $1 passed$black\nfi\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/testing/sblat1.f",
    "content": "*> \\brief \\b SBLAT1\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM SBLAT1\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*>    Test program for the REAL Level 1 BLAS.\n*>\n*>    Based upon the original BLAS test routine together with:\n*>    F06EAF Example Program Text\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup single_blas_testing\n*\n*  =====================================================================\n      PROGRAM SBLAT1\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER          NOUT\n      PARAMETER        (NOUT=6)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, N\n      LOGICAL          PASS\n*     .. Local Scalars ..\n      REAL             SFAC\n      INTEGER          IC\n*     .. External Subroutines ..\n      EXTERNAL         CHECK0, CHECK1, CHECK2, CHECK3, HEADER\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      DATA             SFAC/9.765625E-4/\n*     .. Executable Statements ..\n      WRITE (NOUT,99999)\n      DO 20 IC = 1, 13\n         ICASE = IC\n         CALL HEADER\n*\n*        .. Initialize  PASS,  INCX,  and INCY for a new case. ..\n*        .. the value 9999 for INCX or INCY will appear in the ..\n*        .. detailed  output, if any, for cases  that do not involve ..\n*        .. these parameters ..\n*\n         PASS = .TRUE.\n         INCX = 9999\n         INCY = 9999\n         IF (ICASE.EQ.3 .OR. ICASE.EQ.11) THEN\n            CALL CHECK0(SFAC)\n         ELSE IF (ICASE.EQ.7 .OR. ICASE.EQ.8 .OR. ICASE.EQ.9 .OR.\n     +            ICASE.EQ.10) THEN\n            CALL CHECK1(SFAC)\n         ELSE IF (ICASE.EQ.1 .OR. ICASE.EQ.2 .OR. ICASE.EQ.5 .OR.\n     +            ICASE.EQ.6 .OR. ICASE.EQ.12 .OR. ICASE.EQ.13) THEN\n            CALL CHECK2(SFAC)\n         ELSE IF (ICASE.EQ.4) THEN\n            CALL CHECK3(SFAC)\n         END IF\n*        -- Print\n         IF (PASS) WRITE (NOUT,99998)\n   20 CONTINUE\n      STOP\n*\n99999 FORMAT (' Real BLAS Test Program Results',/1X)\n99998 FORMAT ('                                    ----- PASS -----')\n      END\n      SUBROUTINE HEADER\n*     .. Parameters ..\n      INTEGER          NOUT\n      PARAMETER        (NOUT=6)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, N\n      LOGICAL          PASS\n*     .. Local Arrays ..\n      CHARACTER*6      L(13)\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      DATA             L(1)/' SDOT '/\n      DATA             L(2)/'SAXPY '/\n      DATA             L(3)/'SROTG '/\n      DATA             L(4)/' SROT '/\n      DATA             L(5)/'SCOPY '/\n      DATA             L(6)/'SSWAP '/\n      DATA             L(7)/'SNRM2 '/\n      DATA             L(8)/'SASUM '/\n      DATA             L(9)/'SSCAL '/\n      DATA             L(10)/'ISAMAX'/\n      DATA             L(11)/'SROTMG'/\n      DATA             L(12)/'SROTM '/\n      DATA             L(13)/'SDSDOT'/\n*     .. Executable Statements ..\n      WRITE (NOUT,99999) ICASE, L(ICASE)\n      RETURN\n*\n99999 FORMAT (/' Test of subprogram number',I3,12X,A6)\n      END\n      SUBROUTINE CHECK0(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      REAL              SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      REAL              D12, SA, SB, SC, SS\n      INTEGER           I, K\n*     .. Local Arrays ..\n      REAL              DA1(8), DATRUE(8), DB1(8), DBTRUE(8), DC1(8),\n     +                  DS1(8), DAB(4,9), DTEMP(9), DTRUE(9,9)\n*     .. External Subroutines ..\n      EXTERNAL          SROTG, SROTMG, STEST1\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      DATA              DA1/0.3E0, 0.4E0, -0.3E0, -0.4E0, -0.3E0, 0.0E0,\n     +                  0.0E0, 1.0E0/\n      DATA              DB1/0.4E0, 0.3E0, 0.4E0, 0.3E0, -0.4E0, 0.0E0,\n     +                  1.0E0, 0.0E0/\n      DATA              DC1/0.6E0, 0.8E0, -0.6E0, 0.8E0, 0.6E0, 1.0E0,\n     +                  0.0E0, 1.0E0/\n      DATA              DS1/0.8E0, 0.6E0, 0.8E0, -0.6E0, 0.8E0, 0.0E0,\n     +                  1.0E0, 0.0E0/\n      DATA              DATRUE/0.5E0, 0.5E0, 0.5E0, -0.5E0, -0.5E0,\n     +                  0.0E0, 1.0E0, 1.0E0/\n      DATA              DBTRUE/0.0E0, 0.6E0, 0.0E0, -0.6E0, 0.0E0,\n     +                  0.0E0, 1.0E0, 0.0E0/\n*     INPUT FOR MODIFIED GIVENS\n      DATA DAB/ .1E0,.3E0,1.2E0,.2E0,\n     A          .7E0, .2E0, .6E0, 4.2E0,\n     B          0.E0,0.E0,0.E0,0.E0,\n     C          4.E0, -1.E0, 2.E0, 4.E0,\n     D          6.E-10, 2.E-2, 1.E5, 10.E0,\n     E          4.E10, 2.E-2, 1.E-5, 10.E0,\n     F          2.E-10, 4.E-2, 1.E5, 10.E0,\n     G          2.E10, 4.E-2, 1.E-5, 10.E0,\n     H          4.E0, -2.E0, 8.E0, 4.E0    /\n*    TRUE RESULTS FOR MODIFIED GIVENS\n      DATA DTRUE/0.E0,0.E0, 1.3E0, .2E0, 0.E0,0.E0,0.E0, .5E0, 0.E0,\n     A           0.E0,0.E0, 4.5E0, 4.2E0, 1.E0, .5E0, 0.E0,0.E0,0.E0,\n     B           0.E0,0.E0,0.E0,0.E0, -2.E0, 0.E0,0.E0,0.E0,0.E0,\n     C           0.E0,0.E0,0.E0, 4.E0, -1.E0, 0.E0,0.E0,0.E0,0.E0,\n     D           0.E0, 15.E-3, 0.E0, 10.E0, -1.E0, 0.E0, -1.E-4,\n     E           0.E0, 1.E0,\n     F           0.E0,0.E0, 6144.E-5, 10.E0, -1.E0, 4096.E0, -1.E6,\n     G           0.E0, 1.E0,\n     H           0.E0,0.E0,15.E0,10.E0,-1.E0, 5.E-5, 0.E0,1.E0,0.E0,\n     I           0.E0,0.E0, 15.E0, 10.E0, -1. E0, 5.E5, -4096.E0,\n     J           1.E0, 4096.E-6,\n     K           0.E0,0.E0, 7.E0, 4.E0, 0.E0,0.E0, -.5E0, -.25E0, 0.E0/\n*                   4096 = 2 ** 12\n      DATA D12  /4096.E0/\n      DTRUE(1,1) = 12.E0 / 130.E0\n      DTRUE(2,1) = 36.E0 / 130.E0\n      DTRUE(7,1) = -1.E0 / 6.E0\n      DTRUE(1,2) = 14.E0 / 75.E0\n      DTRUE(2,2) = 49.E0 / 75.E0\n      DTRUE(9,2) = 1.E0 / 7.E0\n      DTRUE(1,5) = 45.E-11 * (D12 * D12)\n      DTRUE(3,5) = 4.E5 / (3.E0 * D12)\n      DTRUE(6,5) = 1.E0 / D12\n      DTRUE(8,5) = 1.E4 / (3.E0 * D12)\n      DTRUE(1,6) = 4.E10 / (1.5E0 * D12 * D12)\n      DTRUE(2,6) = 2.E-2 / 1.5E0\n      DTRUE(8,6) = 5.E-7 * D12\n      DTRUE(1,7) = 4.E0 / 150.E0\n      DTRUE(2,7) = (2.E-10 / 1.5E0) * (D12 * D12)\n      DTRUE(7,7) = -DTRUE(6,5)\n      DTRUE(9,7) = 1.E4 / D12\n      DTRUE(1,8) = DTRUE(1,7)\n      DTRUE(2,8) = 2.E10 / (1.5E0 * D12 * D12)\n      DTRUE(1,9) = 32.E0 / 7.E0\n      DTRUE(2,9) = -16.E0 / 7.E0\n*     .. Executable Statements ..\n*\n*     Compute true values which cannot be prestored\n*     in decimal notation\n*\n      DBTRUE(1) = 1.0E0/0.6E0\n      DBTRUE(3) = -1.0E0/0.6E0\n      DBTRUE(5) = 1.0E0/0.6E0\n*\n      DO 20 K = 1, 8\n*        .. Set N=K for identification in output if any ..\n         N = K\n         IF (ICASE.EQ.3) THEN\n*           .. SROTG ..\n            IF (K.GT.8) GO TO 40\n            SA = DA1(K)\n            SB = DB1(K)\n            CALL SROTG(SA,SB,SC,SS)\n            CALL STEST1(SA,DATRUE(K),DATRUE(K),SFAC)\n            CALL STEST1(SB,DBTRUE(K),DBTRUE(K),SFAC)\n            CALL STEST1(SC,DC1(K),DC1(K),SFAC)\n            CALL STEST1(SS,DS1(K),DS1(K),SFAC)\n         ELSEIF (ICASE.EQ.11) THEN\n*           .. SROTMG ..\n            DO I=1,4\n               DTEMP(I)= DAB(I,K)\n               DTEMP(I+4) = 0.0\n            END DO\n            DTEMP(9) = 0.0\n            CALL SROTMG(DTEMP(1),DTEMP(2),DTEMP(3),DTEMP(4),DTEMP(5))\n            CALL STEST(9,DTEMP,DTRUE(1,K),DTRUE(1,K),SFAC)\n         ELSE\n            WRITE (NOUT,*) ' Shouldn''t be here in CHECK0'\n            STOP\n         END IF\n   20 CONTINUE\n   40 RETURN\n      END\n      SUBROUTINE CHECK1(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      REAL              SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      INTEGER           I, LEN, NP1\n*     .. Local Arrays ..\n      REAL              DTRUE1(5), DTRUE3(5), DTRUE5(8,5,2), DV(8,5,2),\n     +                  SA(10), STEMP(1), STRUE(8), SX(8)\n      INTEGER           ITRUE2(5)\n*     .. External Functions ..\n      REAL              SASUM, SNRM2\n      INTEGER           ISAMAX\n      EXTERNAL          SASUM, SNRM2, ISAMAX\n*     .. External Subroutines ..\n      EXTERNAL          ITEST1, SSCAL, STEST, STEST1\n*     .. Intrinsic Functions ..\n      INTRINSIC         MAX\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      DATA              SA/0.3E0, -1.0E0, 0.0E0, 1.0E0, 0.3E0, 0.3E0,\n     +                  0.3E0, 0.3E0, 0.3E0, 0.3E0/\n      DATA              DV/0.1E0, 2.0E0, 2.0E0, 2.0E0, 2.0E0, 2.0E0,\n     +                  2.0E0, 2.0E0, 0.3E0, 3.0E0, 3.0E0, 3.0E0, 3.0E0,\n     +                  3.0E0, 3.0E0, 3.0E0, 0.3E0, -0.4E0, 4.0E0,\n     +                  4.0E0, 4.0E0, 4.0E0, 4.0E0, 4.0E0, 0.2E0,\n     +                  -0.6E0, 0.3E0, 5.0E0, 5.0E0, 5.0E0, 5.0E0,\n     +                  5.0E0, 0.1E0, -0.3E0, 0.5E0, -0.1E0, 6.0E0,\n     +                  6.0E0, 6.0E0, 6.0E0, 0.1E0, 8.0E0, 8.0E0, 8.0E0,\n     +                  8.0E0, 8.0E0, 8.0E0, 8.0E0, 0.3E0, 9.0E0, 9.0E0,\n     +                  9.0E0, 9.0E0, 9.0E0, 9.0E0, 9.0E0, 0.3E0, 2.0E0,\n     +                  -0.4E0, 2.0E0, 2.0E0, 2.0E0, 2.0E0, 2.0E0,\n     +                  0.2E0, 3.0E0, -0.6E0, 5.0E0, 0.3E0, 2.0E0,\n     +                  2.0E0, 2.0E0, 0.1E0, 4.0E0, -0.3E0, 6.0E0,\n     +                  -0.5E0, 7.0E0, -0.1E0, 3.0E0/\n      DATA              DTRUE1/0.0E0, 0.3E0, 0.5E0, 0.7E0, 0.6E0/\n      DATA              DTRUE3/0.0E0, 0.3E0, 0.7E0, 1.1E0, 1.0E0/\n      DATA              DTRUE5/0.10E0, 2.0E0, 2.0E0, 2.0E0, 2.0E0,\n     +                  2.0E0, 2.0E0, 2.0E0, -0.3E0, 3.0E0, 3.0E0,\n     +                  3.0E0, 3.0E0, 3.0E0, 3.0E0, 3.0E0, 0.0E0, 0.0E0,\n     +                  4.0E0, 4.0E0, 4.0E0, 4.0E0, 4.0E0, 4.0E0,\n     +                  0.20E0, -0.60E0, 0.30E0, 5.0E0, 5.0E0, 5.0E0,\n     +                  5.0E0, 5.0E0, 0.03E0, -0.09E0, 0.15E0, -0.03E0,\n     +                  6.0E0, 6.0E0, 6.0E0, 6.0E0, 0.10E0, 8.0E0,\n     +                  8.0E0, 8.0E0, 8.0E0, 8.0E0, 8.0E0, 8.0E0,\n     +                  0.09E0, 9.0E0, 9.0E0, 9.0E0, 9.0E0, 9.0E0,\n     +                  9.0E0, 9.0E0, 0.09E0, 2.0E0, -0.12E0, 2.0E0,\n     +                  2.0E0, 2.0E0, 2.0E0, 2.0E0, 0.06E0, 3.0E0,\n     +                  -0.18E0, 5.0E0, 0.09E0, 2.0E0, 2.0E0, 2.0E0,\n     +                  0.03E0, 4.0E0, -0.09E0, 6.0E0, -0.15E0, 7.0E0,\n     +                  -0.03E0, 3.0E0/\n      DATA              ITRUE2/0, 1, 2, 2, 3/\n*     .. Executable Statements ..\n      DO 80 INCX = 1, 2\n         DO 60 NP1 = 1, 5\n            N = NP1 - 1\n            LEN = 2*MAX(N,1)\n*           .. Set vector arguments ..\n            DO 20 I = 1, LEN\n               SX(I) = DV(I,NP1,INCX)\n   20       CONTINUE\n*\n            IF (ICASE.EQ.7) THEN\n*              .. SNRM2 ..\n               STEMP(1) = DTRUE1(NP1)\n               CALL STEST1(SNRM2(N,SX,INCX),STEMP(1),STEMP,SFAC)\n            ELSE IF (ICASE.EQ.8) THEN\n*              .. SASUM ..\n               STEMP(1) = DTRUE3(NP1)\n               CALL STEST1(SASUM(N,SX,INCX),STEMP(1),STEMP,SFAC)\n            ELSE IF (ICASE.EQ.9) THEN\n*              .. SSCAL ..\n               CALL SSCAL(N,SA((INCX-1)*5+NP1),SX,INCX)\n               DO 40 I = 1, LEN\n                  STRUE(I) = DTRUE5(I,NP1,INCX)\n   40          CONTINUE\n               CALL STEST(LEN,SX,STRUE,STRUE,SFAC)\n            ELSE IF (ICASE.EQ.10) THEN\n*              .. ISAMAX ..\n               CALL ITEST1(ISAMAX(N,SX,INCX),ITRUE2(NP1))\n            ELSE\n               WRITE (NOUT,*) ' Shouldn''t be here in CHECK1'\n               STOP\n            END IF\n   60    CONTINUE\n   80 CONTINUE\n      RETURN\n      END\n      SUBROUTINE CHECK2(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      REAL              SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      REAL              SA\n      INTEGER           I, J, KI, KN, KNI, KPAR, KSIZE, LENX, LENY,\n     $                  MX, MY \n*     .. Local Arrays ..\n      REAL              DT10X(7,4,4), DT10Y(7,4,4), DT7(4,4),\n     $                  DT8(7,4,4), DX1(7),\n     $                  DY1(7), SSIZE1(4), SSIZE2(14,2), SSIZE3(4),\n     $                  SSIZE(7), STX(7), STY(7), SX(7), SY(7),\n     $                  DPAR(5,4), DT19X(7,4,16),DT19XA(7,4,4),\n     $                  DT19XB(7,4,4), DT19XC(7,4,4),DT19XD(7,4,4),\n     $                  DT19Y(7,4,16), DT19YA(7,4,4),DT19YB(7,4,4),\n     $                  DT19YC(7,4,4), DT19YD(7,4,4), DTEMP(5),\n     $                  ST7B(4,4)\n      INTEGER           INCXS(4), INCYS(4), LENS(4,2), NS(4)\n*     .. External Functions ..\n      REAL              SDOT, SDSDOT\n      EXTERNAL          SDOT, SDSDOT\n*     .. External Subroutines ..\n      EXTERNAL          SAXPY, SCOPY, SROTM, SSWAP, STEST, STEST1\n*     .. Intrinsic Functions ..\n      INTRINSIC         ABS, MIN\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      EQUIVALENCE (DT19X(1,1,1),DT19XA(1,1,1)),(DT19X(1,1,5),\n     A   DT19XB(1,1,1)),(DT19X(1,1,9),DT19XC(1,1,1)),\n     B   (DT19X(1,1,13),DT19XD(1,1,1))\n      EQUIVALENCE (DT19Y(1,1,1),DT19YA(1,1,1)),(DT19Y(1,1,5),\n     A   DT19YB(1,1,1)),(DT19Y(1,1,9),DT19YC(1,1,1)),\n     B   (DT19Y(1,1,13),DT19YD(1,1,1))\n\n      DATA              SA/0.3E0/\n      DATA              INCXS/1, 2, -2, -1/\n      DATA              INCYS/1, -2, 1, -2/\n      DATA              LENS/1, 1, 2, 4, 1, 1, 3, 7/\n      DATA              NS/0, 1, 2, 4/\n      DATA              DX1/0.6E0, 0.1E0, -0.5E0, 0.8E0, 0.9E0, -0.3E0,\n     +                  -0.4E0/\n      DATA              DY1/0.5E0, -0.9E0, 0.3E0, 0.7E0, -0.6E0, 0.2E0,\n     +                  0.8E0/\n      DATA              DT7/0.0E0, 0.30E0, 0.21E0, 0.62E0, 0.0E0,\n     +                  0.30E0, -0.07E0, 0.85E0, 0.0E0, 0.30E0, -0.79E0,\n     +                  -0.74E0, 0.0E0, 0.30E0, 0.33E0, 1.27E0/\n      DATA              ST7B/ .1, .4, .31, .72,     .1, .4, .03, .95,\n     +                  .1, .4, -.69, -.64,   .1, .4, .43, 1.37/\n      DATA              DT8/0.5E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.68E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.68E0, -0.87E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.68E0, -0.87E0, 0.15E0,\n     +                  0.94E0, 0.0E0, 0.0E0, 0.0E0, 0.5E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.68E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.35E0, -0.9E0, 0.48E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.38E0, -0.9E0, 0.57E0, 0.7E0, -0.75E0,\n     +                  0.2E0, 0.98E0, 0.5E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.68E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.35E0, -0.72E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.38E0,\n     +                  -0.63E0, 0.15E0, 0.88E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.5E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.68E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.68E0, -0.9E0, 0.33E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.68E0, -0.9E0, 0.33E0, 0.7E0,\n     +                  -0.75E0, 0.2E0, 1.04E0/\n      DATA              DT10X/0.6E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.5E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.5E0, -0.9E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.5E0, -0.9E0, 0.3E0, 0.7E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.6E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.5E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.3E0, 0.1E0, 0.5E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.8E0, 0.1E0, -0.6E0,\n     +                  0.8E0, 0.3E0, -0.3E0, 0.5E0, 0.6E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.5E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, -0.9E0,\n     +                  0.1E0, 0.5E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.7E0,\n     +                  0.1E0, 0.3E0, 0.8E0, -0.9E0, -0.3E0, 0.5E0,\n     +                  0.6E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.5E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.5E0, 0.3E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.5E0, 0.3E0, -0.6E0, 0.8E0, 0.0E0, 0.0E0,\n     +                  0.0E0/\n      DATA              DT10Y/0.5E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.6E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.6E0, 0.1E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.6E0, 0.1E0, -0.5E0, 0.8E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.5E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.6E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, -0.5E0, -0.9E0, 0.6E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, -0.4E0, -0.9E0, 0.9E0,\n     +                  0.7E0, -0.5E0, 0.2E0, 0.6E0, 0.5E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.6E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, -0.5E0,\n     +                  0.6E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  -0.4E0, 0.9E0, -0.5E0, 0.6E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.5E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.6E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.6E0, -0.9E0, 0.1E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.6E0, -0.9E0, 0.1E0, 0.7E0,\n     +                  -0.5E0, 0.2E0, 0.8E0/\n      DATA              SSIZE1/0.0E0, 0.3E0, 1.6E0, 3.2E0/\n      DATA              SSIZE2/0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 1.17E0, 1.17E0, 1.17E0, 1.17E0, 1.17E0,\n     +                  1.17E0, 1.17E0, 1.17E0, 1.17E0, 1.17E0, 1.17E0,\n     +                  1.17E0, 1.17E0, 1.17E0/\n      DATA              SSIZE3/ .1, .4, 1.7, 3.3 /\n*\n*                         FOR DROTM\n*\n      DATA DPAR/-2.E0,  0.E0,0.E0,0.E0,0.E0,\n     A          -1.E0,  2.E0, -3.E0, -4.E0,  5.E0,\n     B           0.E0,  0.E0,  2.E0, -3.E0,  0.E0,\n     C           1.E0,  5.E0,  2.E0,  0.E0, -4.E0/\n*                        TRUE X RESULTS F0R ROTATIONS DROTM\n      DATA DT19XA/.6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     A            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     B            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     C            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     D            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     E           -.8E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     F           -.9E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     G           3.5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     H            .6E0,   .1E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     I           -.8E0,  3.8E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     J           -.9E0,  2.8E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     K           3.5E0,  -.4E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     L            .6E0,   .1E0,  -.5E0,   .8E0,          0.E0,0.E0,0.E0,\n     M           -.8E0,  3.8E0, -2.2E0, -1.2E0,          0.E0,0.E0,0.E0,\n     N           -.9E0,  2.8E0, -1.4E0, -1.3E0,          0.E0,0.E0,0.E0,\n     O           3.5E0,  -.4E0, -2.2E0,  4.7E0,          0.E0,0.E0,0.E0/\n*\n      DATA DT19XB/.6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     A            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     B            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     C            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     D            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     E           -.8E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     F           -.9E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     G           3.5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     H            .6E0,   .1E0,  -.5E0,             0.E0,0.E0,0.E0,0.E0,\n     I           0.E0,    .1E0, -3.0E0,             0.E0,0.E0,0.E0,0.E0,\n     J           -.3E0,   .1E0, -2.0E0,             0.E0,0.E0,0.E0,0.E0,\n     K           3.3E0,   .1E0, -2.0E0,             0.E0,0.E0,0.E0,0.E0,\n     L            .6E0,   .1E0,  -.5E0,   .8E0,   .9E0,  -.3E0,  -.4E0,\n     M          -2.0E0,   .1E0,  1.4E0,   .8E0,   .6E0,  -.3E0, -2.8E0,\n     N          -1.8E0,   .1E0,  1.3E0,   .8E0,  0.E0,   -.3E0, -1.9E0,\n     O           3.8E0,   .1E0, -3.1E0,   .8E0,  4.8E0,  -.3E0, -1.5E0 /\n*\n      DATA DT19XC/.6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     A            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     B            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     C            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     D            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     E           -.8E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     F           -.9E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     G           3.5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     H            .6E0,   .1E0,  -.5E0,             0.E0,0.E0,0.E0,0.E0,\n     I           4.8E0,   .1E0, -3.0E0,             0.E0,0.E0,0.E0,0.E0,\n     J           3.3E0,   .1E0, -2.0E0,             0.E0,0.E0,0.E0,0.E0,\n     K           2.1E0,   .1E0, -2.0E0,             0.E0,0.E0,0.E0,0.E0,\n     L            .6E0,   .1E0,  -.5E0,   .8E0,   .9E0,  -.3E0,  -.4E0,\n     M          -1.6E0,   .1E0, -2.2E0,   .8E0,  5.4E0,  -.3E0, -2.8E0,\n     N          -1.5E0,   .1E0, -1.4E0,   .8E0,  3.6E0,  -.3E0, -1.9E0,\n     O           3.7E0,   .1E0, -2.2E0,   .8E0,  3.6E0,  -.3E0, -1.5E0 /\n*\n      DATA DT19XD/.6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     A            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     B            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     C            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     D            .6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     E           -.8E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     F           -.9E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     G           3.5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     H            .6E0,   .1E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     I           -.8E0, -1.0E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     J           -.9E0,  -.8E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     K           3.5E0,   .8E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     L            .6E0,   .1E0,  -.5E0,   .8E0,          0.E0,0.E0,0.E0,\n     M           -.8E0, -1.0E0,  1.4E0, -1.6E0,          0.E0,0.E0,0.E0,\n     N           -.9E0,  -.8E0,  1.3E0, -1.6E0,          0.E0,0.E0,0.E0,\n     O           3.5E0,   .8E0, -3.1E0,  4.8E0,          0.E0,0.E0,0.E0/\n*                        TRUE Y RESULTS FOR ROTATIONS DROTM\n      DATA DT19YA/.5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     A            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     B            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     C            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     D            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     E            .7E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     F           1.7E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     G          -2.6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     H            .5E0,  -.9E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     I            .7E0, -4.8E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     J           1.7E0,  -.7E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     K          -2.6E0,  3.5E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     L            .5E0,  -.9E0,   .3E0,   .7E0,          0.E0,0.E0,0.E0,\n     M            .7E0, -4.8E0,  3.0E0,  1.1E0,          0.E0,0.E0,0.E0,\n     N           1.7E0,  -.7E0,  -.7E0,  2.3E0,          0.E0,0.E0,0.E0,\n     O          -2.6E0,  3.5E0,  -.7E0, -3.6E0,          0.E0,0.E0,0.E0/\n*\n      DATA DT19YB/.5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     A            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     B            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     C            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     D            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     E            .7E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     F           1.7E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     G          -2.6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     H            .5E0,  -.9E0,   .3E0,             0.E0,0.E0,0.E0,0.E0,\n     I           4.0E0,  -.9E0,  -.3E0,             0.E0,0.E0,0.E0,0.E0,\n     J           -.5E0,  -.9E0,  1.5E0,             0.E0,0.E0,0.E0,0.E0,\n     K          -1.5E0,  -.9E0, -1.8E0,             0.E0,0.E0,0.E0,0.E0,\n     L            .5E0,  -.9E0,   .3E0,   .7E0,  -.6E0,   .2E0,   .8E0,\n     M           3.7E0,  -.9E0, -1.2E0,   .7E0, -1.5E0,   .2E0,  2.2E0,\n     N           -.3E0,  -.9E0,  2.1E0,   .7E0, -1.6E0,   .2E0,  2.0E0,\n     O          -1.6E0,  -.9E0, -2.1E0,   .7E0,  2.9E0,   .2E0, -3.8E0 /\n*\n      DATA DT19YC/.5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     A            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     B            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     C            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     D            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     E            .7E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     F           1.7E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     G          -2.6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     H            .5E0,  -.9E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     I           4.0E0, -6.3E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     J           -.5E0,   .3E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     K          -1.5E0,  3.0E0,             0.E0,0.E0,0.E0,0.E0,0.E0,\n     L            .5E0,  -.9E0,   .3E0,   .7E0,          0.E0,0.E0,0.E0,\n     M           3.7E0, -7.2E0,  3.0E0,  1.7E0,          0.E0,0.E0,0.E0,\n     N           -.3E0,   .9E0,  -.7E0,  1.9E0,          0.E0,0.E0,0.E0,\n     O          -1.6E0,  2.7E0,  -.7E0, -3.4E0,          0.E0,0.E0,0.E0/\n*\n      DATA DT19YD/.5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     A            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     B            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     C            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     D            .5E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     E            .7E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     F           1.7E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     G          -2.6E0,                  0.E0,0.E0,0.E0,0.E0,0.E0,0.E0,\n     H            .5E0,  -.9E0,   .3E0,             0.E0,0.E0,0.E0,0.E0,\n     I            .7E0,  -.9E0,  1.2E0,             0.E0,0.E0,0.E0,0.E0,\n     J           1.7E0,  -.9E0,   .5E0,             0.E0,0.E0,0.E0,0.E0,\n     K          -2.6E0,  -.9E0, -1.3E0,             0.E0,0.E0,0.E0,0.E0,\n     L            .5E0,  -.9E0,   .3E0,   .7E0,  -.6E0,   .2E0,   .8E0,\n     M            .7E0,  -.9E0,  1.2E0,   .7E0, -1.5E0,   .2E0,  1.6E0,\n     N           1.7E0,  -.9E0,   .5E0,   .7E0, -1.6E0,   .2E0,  2.4E0,\n     O          -2.6E0,  -.9E0, -1.3E0,   .7E0,  2.9E0,   .2E0, -4.0E0 /\n*\n*     .. Executable Statements ..\n*\n      DO 120 KI = 1, 4\n         INCX = INCXS(KI)\n         INCY = INCYS(KI)\n         MX = ABS(INCX)\n         MY = ABS(INCY)\n*\n         DO 100 KN = 1, 4\n            N = NS(KN)\n            KSIZE = MIN(2,KN)\n            LENX = LENS(KN,MX)\n            LENY = LENS(KN,MY)\n*           .. Initialize all argument arrays ..\n            DO 20 I = 1, 7\n               SX(I) = DX1(I)\n               SY(I) = DY1(I)\n   20       CONTINUE\n*\n            IF (ICASE.EQ.1) THEN\n*              .. SDOT ..\n               CALL STEST1(SDOT(N,SX,INCX,SY,INCY),DT7(KN,KI),SSIZE1(KN)\n     +                     ,SFAC)\n            ELSE IF (ICASE.EQ.2) THEN\n*              .. SAXPY ..\n               CALL SAXPY(N,SA,SX,INCX,SY,INCY)\n               DO 40 J = 1, LENY\n                  STY(J) = DT8(J,KN,KI)\n   40          CONTINUE\n               CALL STEST(LENY,SY,STY,SSIZE2(1,KSIZE),SFAC)\n            ELSE IF (ICASE.EQ.5) THEN\n*              .. SCOPY ..\n               DO 60 I = 1, 7\n                  STY(I) = DT10Y(I,KN,KI)\n   60          CONTINUE\n               CALL SCOPY(N,SX,INCX,SY,INCY)\n               CALL STEST(LENY,SY,STY,SSIZE2(1,1),1.0E0)\n            ELSE IF (ICASE.EQ.6) THEN\n*              .. SSWAP ..\n               CALL SSWAP(N,SX,INCX,SY,INCY)\n               DO 80 I = 1, 7\n                  STX(I) = DT10X(I,KN,KI)\n                  STY(I) = DT10Y(I,KN,KI)\n   80          CONTINUE\n               CALL STEST(LENX,SX,STX,SSIZE2(1,1),1.0E0)\n               CALL STEST(LENY,SY,STY,SSIZE2(1,1),1.0E0)\n            ELSEIF (ICASE.EQ.12) THEN\n*              .. SROTM ..\n               KNI=KN+4*(KI-1)\n               DO KPAR=1,4\n                  DO I=1,7\n                     SX(I) = DX1(I)\n                     SY(I) = DY1(I)\n                     STX(I)= DT19X(I,KPAR,KNI)\n                     STY(I)= DT19Y(I,KPAR,KNI)\n                  END DO\n*\n                  DO I=1,5\n                     DTEMP(I) = DPAR(I,KPAR)\n                  END DO\n*\n                  DO  I=1,LENX\n                     SSIZE(I)=STX(I)\n                  END DO\n*                   SEE REMARK ABOVE ABOUT DT11X(1,2,7)\n*                       AND DT11X(5,3,8).\n                  IF ((KPAR .EQ. 2) .AND. (KNI .EQ. 7))\n     $               SSIZE(1) = 2.4E0\n                  IF ((KPAR .EQ. 3) .AND. (KNI .EQ. 8))\n     $               SSIZE(5) = 1.8E0\n*\n                  CALL   SROTM(N,SX,INCX,SY,INCY,DTEMP)\n                  CALL   STEST(LENX,SX,STX,SSIZE,SFAC)\n                  CALL   STEST(LENY,SY,STY,STY,SFAC)\n               END DO\n            ELSEIF (ICASE.EQ.13) THEN\n*              .. SDSROT ..\n               CALL STEST1 (SDSDOT(N,.1,SX,INCX,SY,INCY),\n     $                 ST7B(KN,KI),SSIZE3(KN),SFAC)\n            ELSE\n               WRITE (NOUT,*) ' Shouldn''t be here in CHECK2'\n               STOP\n            END IF\n  100    CONTINUE\n  120 CONTINUE\n      RETURN\n      END\n      SUBROUTINE CHECK3(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      REAL              SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      REAL              SC, SS\n      INTEGER           I, K, KI, KN, KSIZE, LENX, LENY, MX, MY\n*     .. Local Arrays ..\n      REAL              COPYX(5), COPYY(5), DT9X(7,4,4), DT9Y(7,4,4),\n     +                  DX1(7), DY1(7), MWPC(11), MWPS(11), MWPSTX(5),\n     +                  MWPSTY(5), MWPTX(11,5), MWPTY(11,5), MWPX(5),\n     +                  MWPY(5), SSIZE2(14,2), STX(7), STY(7), SX(7),\n     +                  SY(7)\n      INTEGER           INCXS(4), INCYS(4), LENS(4,2), MWPINX(11),\n     +                  MWPINY(11), MWPN(11), NS(4)\n*     .. External Subroutines ..\n      EXTERNAL          SROT, STEST\n*     .. Intrinsic Functions ..\n      INTRINSIC         ABS, MIN\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Data statements ..\n      DATA              INCXS/1, 2, -2, -1/\n      DATA              INCYS/1, -2, 1, -2/\n      DATA              LENS/1, 1, 2, 4, 1, 1, 3, 7/\n      DATA              NS/0, 1, 2, 4/\n      DATA              DX1/0.6E0, 0.1E0, -0.5E0, 0.8E0, 0.9E0, -0.3E0,\n     +                  -0.4E0/\n      DATA              DY1/0.5E0, -0.9E0, 0.3E0, 0.7E0, -0.6E0, 0.2E0,\n     +                  0.8E0/\n      DATA              SC, SS/0.8E0, 0.6E0/\n      DATA              DT9X/0.6E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.78E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.78E0, -0.46E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.78E0, -0.46E0, -0.22E0,\n     +                  1.06E0, 0.0E0, 0.0E0, 0.0E0, 0.6E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.78E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.66E0, 0.1E0, -0.1E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.96E0, 0.1E0, -0.76E0, 0.8E0, 0.90E0,\n     +                  -0.3E0, -0.02E0, 0.6E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.78E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, -0.06E0, 0.1E0,\n     +                  -0.1E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.90E0,\n     +                  0.1E0, -0.22E0, 0.8E0, 0.18E0, -0.3E0, -0.02E0,\n     +                  0.6E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.78E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.78E0, 0.26E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.78E0, 0.26E0, -0.76E0, 1.12E0,\n     +                  0.0E0, 0.0E0, 0.0E0/\n      DATA              DT9Y/0.5E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.04E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.04E0, -0.78E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.04E0, -0.78E0, 0.54E0,\n     +                  0.08E0, 0.0E0, 0.0E0, 0.0E0, 0.5E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.04E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.7E0,\n     +                  -0.9E0, -0.12E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.64E0, -0.9E0, -0.30E0, 0.7E0, -0.18E0, 0.2E0,\n     +                  0.28E0, 0.5E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.04E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.7E0, -1.08E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.64E0, -1.26E0,\n     +                  0.54E0, 0.20E0, 0.0E0, 0.0E0, 0.0E0, 0.5E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.04E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.04E0, -0.9E0, 0.18E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.04E0, -0.9E0, 0.18E0, 0.7E0,\n     +                  -0.18E0, 0.2E0, 0.16E0/\n      DATA              SSIZE2/0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0, 0.0E0,\n     +                  0.0E0, 1.17E0, 1.17E0, 1.17E0, 1.17E0, 1.17E0,\n     +                  1.17E0, 1.17E0, 1.17E0, 1.17E0, 1.17E0, 1.17E0,\n     +                  1.17E0, 1.17E0, 1.17E0/\n*     .. Executable Statements ..\n*\n      DO 60 KI = 1, 4\n         INCX = INCXS(KI)\n         INCY = INCYS(KI)\n         MX = ABS(INCX)\n         MY = ABS(INCY)\n*\n         DO 40 KN = 1, 4\n            N = NS(KN)\n            KSIZE = MIN(2,KN)\n            LENX = LENS(KN,MX)\n            LENY = LENS(KN,MY)\n*\n            IF (ICASE.EQ.4) THEN\n*              .. SROT ..\n               DO 20 I = 1, 7\n                  SX(I) = DX1(I)\n                  SY(I) = DY1(I)\n                  STX(I) = DT9X(I,KN,KI)\n                  STY(I) = DT9Y(I,KN,KI)\n   20          CONTINUE\n               CALL SROT(N,SX,INCX,SY,INCY,SC,SS)\n               CALL STEST(LENX,SX,STX,SSIZE2(1,KSIZE),SFAC)\n               CALL STEST(LENY,SY,STY,SSIZE2(1,KSIZE),SFAC)\n            ELSE\n               WRITE (NOUT,*) ' Shouldn''t be here in CHECK3'\n               STOP\n            END IF\n   40    CONTINUE\n   60 CONTINUE\n*\n      MWPC(1) = 1\n      DO 80 I = 2, 11\n         MWPC(I) = 0\n   80 CONTINUE\n      MWPS(1) = 0\n      DO 100 I = 2, 6\n         MWPS(I) = 1\n  100 CONTINUE\n      DO 120 I = 7, 11\n         MWPS(I) = -1\n  120 CONTINUE\n      MWPINX(1) = 1\n      MWPINX(2) = 1\n      MWPINX(3) = 1\n      MWPINX(4) = -1\n      MWPINX(5) = 1\n      MWPINX(6) = -1\n      MWPINX(7) = 1\n      MWPINX(8) = 1\n      MWPINX(9) = -1\n      MWPINX(10) = 1\n      MWPINX(11) = -1\n      MWPINY(1) = 1\n      MWPINY(2) = 1\n      MWPINY(3) = -1\n      MWPINY(4) = -1\n      MWPINY(5) = 2\n      MWPINY(6) = 1\n      MWPINY(7) = 1\n      MWPINY(8) = -1\n      MWPINY(9) = -1\n      MWPINY(10) = 2\n      MWPINY(11) = 1\n      DO 140 I = 1, 11\n         MWPN(I) = 5\n  140 CONTINUE\n      MWPN(5) = 3\n      MWPN(10) = 3\n      DO 160 I = 1, 5\n         MWPX(I) = I\n         MWPY(I) = I\n         MWPTX(1,I) = I\n         MWPTY(1,I) = I\n         MWPTX(2,I) = I\n         MWPTY(2,I) = -I\n         MWPTX(3,I) = 6 - I\n         MWPTY(3,I) = I - 6\n         MWPTX(4,I) = I\n         MWPTY(4,I) = -I\n         MWPTX(6,I) = 6 - I\n         MWPTY(6,I) = I - 6\n         MWPTX(7,I) = -I\n         MWPTY(7,I) = I\n         MWPTX(8,I) = I - 6\n         MWPTY(8,I) = 6 - I\n         MWPTX(9,I) = -I\n         MWPTY(9,I) = I\n         MWPTX(11,I) = I - 6\n         MWPTY(11,I) = 6 - I\n  160 CONTINUE\n      MWPTX(5,1) = 1\n      MWPTX(5,2) = 3\n      MWPTX(5,3) = 5\n      MWPTX(5,4) = 4\n      MWPTX(5,5) = 5\n      MWPTY(5,1) = -1\n      MWPTY(5,2) = 2\n      MWPTY(5,3) = -2\n      MWPTY(5,4) = 4\n      MWPTY(5,5) = -3\n      MWPTX(10,1) = -1\n      MWPTX(10,2) = -3\n      MWPTX(10,3) = -5\n      MWPTX(10,4) = 4\n      MWPTX(10,5) = 5\n      MWPTY(10,1) = 1\n      MWPTY(10,2) = 2\n      MWPTY(10,3) = 2\n      MWPTY(10,4) = 4\n      MWPTY(10,5) = 3\n      DO 200 I = 1, 11\n         INCX = MWPINX(I)\n         INCY = MWPINY(I)\n         DO 180 K = 1, 5\n            COPYX(K) = MWPX(K)\n            COPYY(K) = MWPY(K)\n            MWPSTX(K) = MWPTX(I,K)\n            MWPSTY(K) = MWPTY(I,K)\n  180    CONTINUE\n         CALL SROT(MWPN(I),COPYX,INCX,COPYY,INCY,MWPC(I),MWPS(I))\n         CALL STEST(5,COPYX,MWPSTX,MWPSTX,SFAC)\n         CALL STEST(5,COPYY,MWPSTY,MWPSTY,SFAC)\n  200 CONTINUE\n      RETURN\n      END\n      SUBROUTINE STEST(LEN,SCOMP,STRUE,SSIZE,SFAC)\n*     ********************************* STEST **************************\n*\n*     THIS SUBR COMPARES ARRAYS  SCOMP() AND STRUE() OF LENGTH LEN TO\n*     SEE IF THE TERM BY TERM DIFFERENCES, MULTIPLIED BY SFAC, ARE\n*     NEGLIGIBLE.\n*\n*     C. L. LAWSON, JPL, 1974 DEC 10\n*\n*     .. Parameters ..\n      INTEGER          NOUT\n      REAL             ZERO\n      PARAMETER        (NOUT=6, ZERO=0.0E0)\n*     .. Scalar Arguments ..\n      REAL             SFAC\n      INTEGER          LEN\n*     .. Array Arguments ..\n      REAL             SCOMP(LEN), SSIZE(LEN), STRUE(LEN)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, N\n      LOGICAL          PASS\n*     .. Local Scalars ..\n      REAL             SD\n      INTEGER          I\n*     .. External Functions ..\n      REAL             SDIFF\n      EXTERNAL         SDIFF\n*     .. Intrinsic Functions ..\n      INTRINSIC        ABS\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Executable Statements ..\n*\n      DO 40 I = 1, LEN\n         SD = SCOMP(I) - STRUE(I)\n         IF (ABS(SFAC*SD) .LE. ABS(SSIZE(I))*EPSILON(ZERO))\n     +       GO TO 40\n*\n*                             HERE    SCOMP(I) IS NOT CLOSE TO STRUE(I).\n*\n         IF ( .NOT. PASS) GO TO 20\n*                             PRINT FAIL MESSAGE AND HEADER.\n         PASS = .FALSE.\n         WRITE (NOUT,99999)\n         WRITE (NOUT,99998)\n   20    WRITE (NOUT,99997) ICASE, N, INCX, INCY, I, SCOMP(I),\n     +     STRUE(I), SD, SSIZE(I)\n   40 CONTINUE\n      RETURN\n*\n99999 FORMAT ('                                       FAIL')\n99998 FORMAT (/' CASE  N INCX INCY  I                            ',\n     +       ' COMP(I)                             TRUE(I)  DIFFERENCE',\n     +       '     SIZE(I)',/1X)\n99997 FORMAT (1X,I4,I3,2I5,I3,2E36.8,2E12.4)\n      END\n      SUBROUTINE STEST1(SCOMP1,STRUE1,SSIZE,SFAC)\n*     ************************* STEST1 *****************************\n*\n*     THIS IS AN INTERFACE SUBROUTINE TO ACCOMMODATE THE FORTRAN\n*     REQUIREMENT THAT WHEN A DUMMY ARGUMENT IS AN ARRAY, THE\n*     ACTUAL ARGUMENT MUST ALSO BE AN ARRAY OR AN ARRAY ELEMENT.\n*\n*     C.L. LAWSON, JPL, 1978 DEC 6\n*\n*     .. Scalar Arguments ..\n      REAL              SCOMP1, SFAC, STRUE1\n*     .. Array Arguments ..\n      REAL              SSIZE(*)\n*     .. Local Arrays ..\n      REAL              SCOMP(1), STRUE(1)\n*     .. External Subroutines ..\n      EXTERNAL          STEST\n*     .. Executable Statements ..\n*\n      SCOMP(1) = SCOMP1\n      STRUE(1) = STRUE1\n      CALL STEST(1,SCOMP,STRUE,SSIZE,SFAC)\n*\n      RETURN\n      END\n      REAL             FUNCTION SDIFF(SA,SB)\n*     ********************************* SDIFF **************************\n*     COMPUTES DIFFERENCE OF TWO NUMBERS.  C. L. LAWSON, JPL 1974 FEB 15\n*\n*     .. Scalar Arguments ..\n      REAL                            SA, SB\n*     .. Executable Statements ..\n      SDIFF = SA - SB\n      RETURN\n      END\n      SUBROUTINE ITEST1(ICOMP,ITRUE)\n*     ********************************* ITEST1 *************************\n*\n*     THIS SUBROUTINE COMPARES THE VARIABLES ICOMP AND ITRUE FOR\n*     EQUALITY.\n*     C. L. LAWSON, JPL, 1974 DEC 10\n*\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      INTEGER           ICOMP, ITRUE\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      INTEGER           ID\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, PASS\n*     .. Executable Statements ..\n*\n      IF (ICOMP.EQ.ITRUE) GO TO 40\n*\n*                            HERE ICOMP IS NOT EQUAL TO ITRUE.\n*\n      IF ( .NOT. PASS) GO TO 20\n*                             PRINT FAIL MESSAGE AND HEADER.\n      PASS = .FALSE.\n      WRITE (NOUT,99999)\n      WRITE (NOUT,99998)\n   20 ID = ICOMP - ITRUE\n      WRITE (NOUT,99997) ICASE, N, INCX, INCY, ICOMP, ITRUE, ID\n   40 CONTINUE\n      RETURN\n*\n99999 FORMAT ('                                       FAIL')\n99998 FORMAT (/' CASE  N INCX INCY                               ',\n     +       ' COMP                                TRUE     DIFFERENCE',\n     +       /1X)\n99997 FORMAT (1X,I4,I3,2I5,2I36,I12)\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/testing/sblat2.f",
    "content": "*> \\brief \\b SBLAT2\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM SBLAT2\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> Test program for the REAL Level 2 Blas.\n*>\n*> The program must be driven by a short data file. The first 18 records\n*> of the file are read using list-directed input, the last 16 records\n*> are read using the format ( A6, L2 ). An annotated example of a data\n*> file can be obtained by deleting the first 3 characters from the\n*> following 34 lines:\n*> 'sblat2.out'      NAME OF SUMMARY OUTPUT FILE\n*> 6                 UNIT NUMBER OF SUMMARY FILE\n*> 'SBLAT2.SNAP'     NAME OF SNAPSHOT OUTPUT FILE\n*> -1                UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0)\n*> F        LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD.\n*> F        LOGICAL FLAG, T TO STOP ON FAILURES.\n*> T        LOGICAL FLAG, T TO TEST ERROR EXITS.\n*> 16.0     THRESHOLD VALUE OF TEST RATIO\n*> 6                 NUMBER OF VALUES OF N\n*> 0 1 2 3 5 9       VALUES OF N\n*> 4                 NUMBER OF VALUES OF K\n*> 0 1 2 4           VALUES OF K\n*> 4                 NUMBER OF VALUES OF INCX AND INCY\n*> 1 2 -1 -2         VALUES OF INCX AND INCY\n*> 3                 NUMBER OF VALUES OF ALPHA\n*> 0.0 1.0 0.7       VALUES OF ALPHA\n*> 3                 NUMBER OF VALUES OF BETA\n*> 0.0 1.0 0.9       VALUES OF BETA\n*> SGEMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> SGBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> SSYMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> SSBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> SSPMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> STRMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> STBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> STPMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> STRSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> STBSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> STPSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> SGER   T PUT F FOR NO TEST. SAME COLUMNS.\n*> SSYR   T PUT F FOR NO TEST. SAME COLUMNS.\n*> SSPR   T PUT F FOR NO TEST. SAME COLUMNS.\n*> SSYR2  T PUT F FOR NO TEST. SAME COLUMNS.\n*> SSPR2  T PUT F FOR NO TEST. SAME COLUMNS.\n*>\n*> Further Details\n*> ===============\n*>\n*>    See:\n*>\n*>       Dongarra J. J., Du Croz J. J., Hammarling S.  and Hanson R. J..\n*>       An  extended  set of Fortran  Basic Linear Algebra Subprograms.\n*>\n*>       Technical  Memoranda  Nos. 41 (revision 3) and 81,  Mathematics\n*>       and  Computer Science  Division,  Argonne  National Laboratory,\n*>       9700 South Cass Avenue, Argonne, Illinois 60439, US.\n*>\n*>       Or\n*>\n*>       NAG  Technical Reports TR3/87 and TR4/87,  Numerical Algorithms\n*>       Group  Ltd.,  NAG  Central  Office,  256  Banbury  Road, Oxford\n*>       OX2 7DE, UK,  and  Numerical Algorithms Group Inc.,  1101  31st\n*>       Street,  Suite 100,  Downers Grove,  Illinois 60515-1263,  USA.\n*>\n*>\n*> -- Written on 10-August-1987.\n*>    Richard Hanson, Sandia National Labs.\n*>    Jeremy Du Croz, NAG Central Office.\n*>\n*>    10-9-00:  Change STATUS='NEW' to 'UNKNOWN' so that the testers\n*>              can be run multiple times without deleting generated\n*>              output files (susan)\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup single_blas_testing\n*\n*  =====================================================================\n      PROGRAM SBLAT2\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER            NIN\n      PARAMETER          ( NIN = 5 )\n      INTEGER            NSUBS\n      PARAMETER          ( NSUBS = 16 )\n      REAL               ZERO, ONE\n      PARAMETER          ( ZERO = 0.0, ONE = 1.0 )\n      INTEGER            NMAX, INCMAX\n      PARAMETER          ( NMAX = 65, INCMAX = 2 )\n      INTEGER            NINMAX, NIDMAX, NKBMAX, NALMAX, NBEMAX\n      PARAMETER          ( NINMAX = 7, NIDMAX = 9, NKBMAX = 7,\n     $                   NALMAX = 7, NBEMAX = 7 )\n*     .. Local Scalars ..\n      REAL               EPS, ERR, THRESH\n      INTEGER            I, ISNUM, J, N, NALF, NBET, NIDIM, NINC, NKB,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, LTESTT, REWI, SAME, SFATAL, TRACE,\n     $                   TSTERR\n      CHARACTER*1        TRANS\n      CHARACTER*6        SNAMET\n      CHARACTER*32       SNAPS, SUMMRY\n*     .. Local Arrays ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ),\n     $                   ALF( NALMAX ), AS( NMAX*NMAX ), BET( NBEMAX ),\n     $                   G( NMAX ), X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( 2*NMAX )\n      INTEGER            IDIM( NIDMAX ), INC( NINMAX ), KB( NKBMAX )\n      LOGICAL            LTEST( NSUBS )\n      CHARACTER*6        SNAMES( NSUBS )\n*     .. External Functions ..\n      REAL               SDIFF\n      LOGICAL            LSE\n      EXTERNAL           SDIFF, LSE\n*     .. External Subroutines ..\n      EXTERNAL           SCHK1, SCHK2, SCHK3, SCHK4, SCHK5, SCHK6,\n     $                   SCHKE, SMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Data statements ..\n      DATA               SNAMES/'SGEMV ', 'SGBMV ', 'SSYMV ', 'SSBMV ',\n     $                   'SSPMV ', 'STRMV ', 'STBMV ', 'STPMV ',\n     $                   'STRSV ', 'STBSV ', 'STPSV ', 'SGER  ',\n     $                   'SSYR  ', 'SSPR  ', 'SSYR2 ', 'SSPR2 '/\n*     .. Executable Statements ..\n*\n*     Read name and unit number for summary output file and open file.\n*\n      READ( NIN, FMT = * )SUMMRY\n      READ( NIN, FMT = * )NOUT\n      OPEN( NOUT, FILE = SUMMRY, STATUS = 'UNKNOWN' )\n      NOUTC = NOUT\n*\n*     Read name and unit number for snapshot output file and open file.\n*\n      READ( NIN, FMT = * )SNAPS\n      READ( NIN, FMT = * )NTRA\n      TRACE = NTRA.GE.0\n      IF( TRACE )THEN\n         OPEN( NTRA, FILE = SNAPS, STATUS = 'UNKNOWN' )\n      END IF\n*     Read the flag that directs rewinding of the snapshot file.\n      READ( NIN, FMT = * )REWI\n      REWI = REWI.AND.TRACE\n*     Read the flag that directs stopping on any failure.\n      READ( NIN, FMT = * )SFATAL\n*     Read the flag that indicates whether error exits are to be tested.\n      READ( NIN, FMT = * )TSTERR\n*     Read the threshold value of the test ratio\n      READ( NIN, FMT = * )THRESH\n*\n*     Read and check the parameter values for the tests.\n*\n*     Values of N\n      READ( NIN, FMT = * )NIDIM\n      IF( NIDIM.LT.1.OR.NIDIM.GT.NIDMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'N', NIDMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( IDIM( I ), I = 1, NIDIM )\n      DO 10 I = 1, NIDIM\n         IF( IDIM( I ).LT.0.OR.IDIM( I ).GT.NMAX )THEN\n            WRITE( NOUT, FMT = 9996 )NMAX\n            GO TO 230\n         END IF\n   10 CONTINUE\n*     Values of K\n      READ( NIN, FMT = * )NKB\n      IF( NKB.LT.1.OR.NKB.GT.NKBMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'K', NKBMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( KB( I ), I = 1, NKB )\n      DO 20 I = 1, NKB\n         IF( KB( I ).LT.0 )THEN\n            WRITE( NOUT, FMT = 9995 )\n            GO TO 230\n         END IF\n   20 CONTINUE\n*     Values of INCX and INCY\n      READ( NIN, FMT = * )NINC\n      IF( NINC.LT.1.OR.NINC.GT.NINMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'INCX AND INCY', NINMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( INC( I ), I = 1, NINC )\n      DO 30 I = 1, NINC\n         IF( INC( I ).EQ.0.OR.ABS( INC( I ) ).GT.INCMAX )THEN\n            WRITE( NOUT, FMT = 9994 )INCMAX\n            GO TO 230\n         END IF\n   30 CONTINUE\n*     Values of ALPHA\n      READ( NIN, FMT = * )NALF\n      IF( NALF.LT.1.OR.NALF.GT.NALMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'ALPHA', NALMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( ALF( I ), I = 1, NALF )\n*     Values of BETA\n      READ( NIN, FMT = * )NBET\n      IF( NBET.LT.1.OR.NBET.GT.NBEMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'BETA', NBEMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( BET( I ), I = 1, NBET )\n*\n*     Report values of parameters.\n*\n      WRITE( NOUT, FMT = 9993 )\n      WRITE( NOUT, FMT = 9992 )( IDIM( I ), I = 1, NIDIM )\n      WRITE( NOUT, FMT = 9991 )( KB( I ), I = 1, NKB )\n      WRITE( NOUT, FMT = 9990 )( INC( I ), I = 1, NINC )\n      WRITE( NOUT, FMT = 9989 )( ALF( I ), I = 1, NALF )\n      WRITE( NOUT, FMT = 9988 )( BET( I ), I = 1, NBET )\n      IF( .NOT.TSTERR )THEN\n         WRITE( NOUT, FMT = * )\n         WRITE( NOUT, FMT = 9980 )\n      END IF\n      WRITE( NOUT, FMT = * )\n      WRITE( NOUT, FMT = 9999 )THRESH\n      WRITE( NOUT, FMT = * )\n*\n*     Read names of subroutines and flags which indicate\n*     whether they are to be tested.\n*\n      DO 40 I = 1, NSUBS\n         LTEST( I ) = .FALSE.\n   40 CONTINUE\n   50 READ( NIN, FMT = 9984, END = 80 )SNAMET, LTESTT\n      DO 60 I = 1, NSUBS\n         IF( SNAMET.EQ.SNAMES( I ) )\n     $      GO TO 70\n   60 CONTINUE\n      WRITE( NOUT, FMT = 9986 )SNAMET\n      STOP\n   70 LTEST( I ) = LTESTT\n      GO TO 50\n*\n   80 CONTINUE\n      CLOSE ( NIN )\n*\n*     Compute EPS (the machine precision).\n*\n      EPS = EPSILON(ZERO)\n      WRITE( NOUT, FMT = 9998 )EPS\n*\n*     Check the reliability of SMVCH using exact data.\n*\n      N = MIN( 32, NMAX )\n      DO 120 J = 1, N\n         DO 110 I = 1, N\n            A( I, J ) = MAX( I - J + 1, 0 )\n  110    CONTINUE\n         X( J ) = J\n         Y( J ) = ZERO\n  120 CONTINUE\n      DO 130 J = 1, N\n         YY( J ) = J*( ( J + 1 )*J )/2 - ( ( J + 1 )*J*( J - 1 ) )/3\n  130 CONTINUE\n*     YY holds the exact result. On exit from SMVCH YT holds\n*     the result computed by SMVCH.\n      TRANS = 'N'\n      CALL SMVCH( TRANS, N, N, ONE, A, NMAX, X, 1, ZERO, Y, 1, YT, G,\n     $            YY, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LSE( YY, YT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9985 )TRANS, SAME, ERR\n         STOP\n      END IF\n      TRANS = 'T'\n      CALL SMVCH( TRANS, N, N, ONE, A, NMAX, X, -1, ZERO, Y, -1, YT, G,\n     $            YY, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LSE( YY, YT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9985 )TRANS, SAME, ERR\n         STOP\n      END IF\n*\n*     Test each subroutine in turn.\n*\n      DO 210 ISNUM = 1, NSUBS\n         WRITE( NOUT, FMT = * )\n         IF( .NOT.LTEST( ISNUM ) )THEN\n*           Subprogram is not to be tested.\n            WRITE( NOUT, FMT = 9983 )SNAMES( ISNUM )\n         ELSE\n            SRNAMT = SNAMES( ISNUM )\n*           Test error exits.\n            IF( TSTERR )THEN\n               CALL SCHKE( ISNUM, SNAMES( ISNUM ), NOUT )\n               WRITE( NOUT, FMT = * )\n            END IF\n*           Test computations.\n            INFOT = 0\n            OK = .TRUE.\n            FATAL = .FALSE.\n            GO TO ( 140, 140, 150, 150, 150, 160, 160,\n     $              160, 160, 160, 160, 170, 180, 180,\n     $              190, 190 )ISNUM\n*           Test SGEMV, 01, and SGBMV, 02.\n  140       CALL SCHK1( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF,\n     $                  NBET, BET, NINC, INC, NMAX, INCMAX, A, AA, AS,\n     $                  X, XX, XS, Y, YY, YS, YT, G )\n            GO TO 200\n*           Test SSYMV, 03, SSBMV, 04, and SSPMV, 05.\n  150       CALL SCHK2( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF,\n     $                  NBET, BET, NINC, INC, NMAX, INCMAX, A, AA, AS,\n     $                  X, XX, XS, Y, YY, YS, YT, G )\n            GO TO 200\n*           Test STRMV, 06, STBMV, 07, STPMV, 08,\n*           STRSV, 09, STBSV, 10, and STPSV, 11.\n  160       CALL SCHK3( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, Y, YY, YS, YT, G, Z )\n            GO TO 200\n*           Test SGER, 12.\n  170       CALL SCHK4( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n            GO TO 200\n*           Test SSYR, 13, and SSPR, 14.\n  180       CALL SCHK5( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n            GO TO 200\n*           Test SSYR2, 15, and SSPR2, 16.\n  190       CALL SCHK6( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n*\n  200       IF( FATAL.AND.SFATAL )\n     $         GO TO 220\n         END IF\n  210 CONTINUE\n      WRITE( NOUT, FMT = 9982 )\n      GO TO 240\n*\n  220 CONTINUE\n      WRITE( NOUT, FMT = 9981 )\n      GO TO 240\n*\n  230 CONTINUE\n      WRITE( NOUT, FMT = 9987 )\n*\n  240 CONTINUE\n      IF( TRACE )\n     $   CLOSE ( NTRA )\n      CLOSE ( NOUT )\n      STOP\n*\n 9999 FORMAT( ' ROUTINES PASS COMPUTATIONAL TESTS IF TEST RATIO IS LES',\n     $      'S THAN', F8.2 )\n 9998 FORMAT( ' RELATIVE MACHINE PRECISION IS TAKEN TO BE', 1P, E9.1 )\n 9997 FORMAT( ' NUMBER OF VALUES OF ', A, ' IS LESS THAN 1 OR GREATER ',\n     $      'THAN ', I2 )\n 9996 FORMAT( ' VALUE OF N IS LESS THAN 0 OR GREATER THAN ', I2 )\n 9995 FORMAT( ' VALUE OF K IS LESS THAN 0' )\n 9994 FORMAT( ' ABSOLUTE VALUE OF INCX OR INCY IS 0 OR GREATER THAN ',\n     $      I2 )\n 9993 FORMAT( ' TESTS OF THE REAL             LEVEL 2 BLAS', //' THE F',\n     $      'OLLOWING PARAMETER VALUES WILL BE USED:' )\n 9992 FORMAT( '   FOR N              ', 9I6 )\n 9991 FORMAT( '   FOR K              ', 7I6 )\n 9990 FORMAT( '   FOR INCX AND INCY  ', 7I6 )\n 9989 FORMAT( '   FOR ALPHA          ', 7F6.1 )\n 9988 FORMAT( '   FOR BETA           ', 7F6.1 )\n 9987 FORMAT( ' AMEND DATA FILE OR INCREASE ARRAY SIZES IN PROGRAM',\n     $      /' ******* TESTS ABANDONED *******' )\n 9986 FORMAT( ' SUBPROGRAM NAME ', A6, ' NOT RECOGNIZED', /' ******* T',\n     $      'ESTS ABANDONED *******' )\n 9985 FORMAT( ' ERROR IN SMVCH -  IN-LINE DOT PRODUCTS ARE BEING EVALU',\n     $      'ATED WRONGLY.', /' SMVCH WAS CALLED WITH TRANS = ', A1,\n     $      ' AND RETURNED SAME = ', L1, ' AND ERR = ', F12.3, '.', /\n     $   ' THIS MAY BE DUE TO FAULTS IN THE ARITHMETIC OR THE COMPILER.'\n     $      , /' ******* TESTS ABANDONED *******' )\n 9984 FORMAT( A6, L2 )\n 9983 FORMAT( 1X, A6, ' WAS NOT TESTED' )\n 9982 FORMAT( /' END OF TESTS' )\n 9981 FORMAT( /' ******* FATAL ERROR - TESTS ABANDONED *******' )\n 9980 FORMAT( ' ERROR-EXITS WILL NOT BE TESTED' )\n*\n*     End of SBLAT2.\n*\n      END\n      SUBROUTINE SCHK1( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF, NBET,\n     $                  BET, NINC, INC, NMAX, INCMAX, A, AA, AS, X, XX,\n     $                  XS, Y, YY, YS, YT, G )\n*\n*  Tests SGEMV and SGBMV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      REAL               ZERO, HALF\n      PARAMETER          ( ZERO = 0.0, HALF = 0.5 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NALF, NBET, NIDIM, NINC, NKB, NMAX,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), BET( NBET ), G( NMAX ),\n     $                   X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      REAL               ALPHA, ALS, BETA, BLS, ERR, ERRMAX, TRANSL\n      INTEGER            I, IA, IB, IC, IKU, IM, IN, INCX, INCXS, INCY,\n     $                   INCYS, IX, IY, KL, KLS, KU, KUS, LAA, LDA,\n     $                   LDAS, LX, LY, M, ML, MS, N, NARGS, NC, ND, NK,\n     $                   NL, NS\n      LOGICAL            BANDED, FULL, NULL, RESET, SAME, TRAN\n      CHARACTER*1        TRANS, TRANSS\n      CHARACTER*3        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SGBMV, SGEMV, SMAKE, SMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'NTC'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'E'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 11\n      ELSE IF( BANDED )THEN\n         NARGS = 13\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 120 IN = 1, NIDIM\n         N = IDIM( IN )\n         ND = N/2 + 1\n*\n         DO 110 IM = 1, 2\n            IF( IM.EQ.1 )\n     $         M = MAX( N - ND, 0 )\n            IF( IM.EQ.2 )\n     $         M = MIN( N + ND, NMAX )\n*\n            IF( BANDED )THEN\n               NK = NKB\n            ELSE\n               NK = 1\n            END IF\n            DO 100 IKU = 1, NK\n               IF( BANDED )THEN\n                  KU = KB( IKU )\n                  KL = MAX( KU - 1, 0 )\n               ELSE\n                  KU = N - 1\n                  KL = M - 1\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               IF( BANDED )THEN\n                  LDA = KL + KU + 1\n               ELSE\n                  LDA = M\n               END IF\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 100\n               LAA = LDA*N\n               NULL = N.LE.0.OR.M.LE.0\n*\n*              Generate the matrix A.\n*\n               TRANSL = ZERO\n               CALL SMAKE( SNAME( 2: 3 ), ' ', ' ', M, N, A, NMAX, AA,\n     $                     LDA, KL, KU, RESET, TRANSL )\n*\n               DO 90 IC = 1, 3\n                  TRANS = ICH( IC: IC )\n                  TRAN = TRANS.EQ.'T'.OR.TRANS.EQ.'C'\n*\n                  IF( TRAN )THEN\n                     ML = N\n                     NL = M\n                  ELSE\n                     ML = M\n                     NL = N\n                  END IF\n*\n                  DO 80 IX = 1, NINC\n                     INCX = INC( IX )\n                     LX = ABS( INCX )*NL\n*\n*                    Generate the vector X.\n*\n                     TRANSL = HALF\n                     CALL SMAKE( 'GE', ' ', ' ', 1, NL, X, 1, XX,\n     $                           ABS( INCX ), 0, NL - 1, RESET, TRANSL )\n                     IF( NL.GT.1 )THEN\n                        X( NL/2 ) = ZERO\n                        XX( 1 + ABS( INCX )*( NL/2 - 1 ) ) = ZERO\n                     END IF\n*\n                     DO 70 IY = 1, NINC\n                        INCY = INC( IY )\n                        LY = ABS( INCY )*ML\n*\n                        DO 60 IA = 1, NALF\n                           ALPHA = ALF( IA )\n*\n                           DO 50 IB = 1, NBET\n                              BETA = BET( IB )\n*\n*                             Generate the vector Y.\n*\n                              TRANSL = ZERO\n                              CALL SMAKE( 'GE', ' ', ' ', 1, ML, Y, 1,\n     $                                    YY, ABS( INCY ), 0, ML - 1,\n     $                                    RESET, TRANSL )\n*\n                              NC = NC + 1\n*\n*                             Save every datum before calling the\n*                             subroutine.\n*\n                              TRANSS = TRANS\n                              MS = M\n                              NS = N\n                              KLS = KL\n                              KUS = KU\n                              ALS = ALPHA\n                              DO 10 I = 1, LAA\n                                 AS( I ) = AA( I )\n   10                         CONTINUE\n                              LDAS = LDA\n                              DO 20 I = 1, LX\n                                 XS( I ) = XX( I )\n   20                         CONTINUE\n                              INCXS = INCX\n                              BLS = BETA\n                              DO 30 I = 1, LY\n                                 YS( I ) = YY( I )\n   30                         CONTINUE\n                              INCYS = INCY\n*\n*                             Call the subroutine.\n*\n                              IF( FULL )THEN\n                                 IF( TRACE )\n     $                              WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                              TRANS, M, N, ALPHA, LDA, INCX, BETA,\n     $                              INCY\n                                 IF( REWI )\n     $                              REWIND NTRA\n                                 CALL SGEMV( TRANS, M, N, ALPHA, AA,\n     $                                       LDA, XX, INCX, BETA, YY,\n     $                                       INCY )\n                              ELSE IF( BANDED )THEN\n                                 IF( TRACE )\n     $                              WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                              TRANS, M, N, KL, KU, ALPHA, LDA,\n     $                              INCX, BETA, INCY\n                                 IF( REWI )\n     $                              REWIND NTRA\n                                 CALL SGBMV( TRANS, M, N, KL, KU, ALPHA,\n     $                                       AA, LDA, XX, INCX, BETA,\n     $                                       YY, INCY )\n                              END IF\n*\n*                             Check if error-exit was taken incorrectly.\n*\n                              IF( .NOT.OK )THEN\n                                 WRITE( NOUT, FMT = 9993 )\n                                 FATAL = .TRUE.\n                                 GO TO 130\n                              END IF\n*\n*                             See what data changed inside subroutines.\n*\n                              ISAME( 1 ) = TRANS.EQ.TRANSS\n                              ISAME( 2 ) = MS.EQ.M\n                              ISAME( 3 ) = NS.EQ.N\n                              IF( FULL )THEN\n                                 ISAME( 4 ) = ALS.EQ.ALPHA\n                                 ISAME( 5 ) = LSE( AS, AA, LAA )\n                                 ISAME( 6 ) = LDAS.EQ.LDA\n                                 ISAME( 7 ) = LSE( XS, XX, LX )\n                                 ISAME( 8 ) = INCXS.EQ.INCX\n                                 ISAME( 9 ) = BLS.EQ.BETA\n                                 IF( NULL )THEN\n                                    ISAME( 10 ) = LSE( YS, YY, LY )\n                                 ELSE\n                                    ISAME( 10 ) = LSERES( 'GE', ' ', 1,\n     $                                            ML, YS, YY,\n     $                                            ABS( INCY ) )\n                                 END IF\n                                 ISAME( 11 ) = INCYS.EQ.INCY\n                              ELSE IF( BANDED )THEN\n                                 ISAME( 4 ) = KLS.EQ.KL\n                                 ISAME( 5 ) = KUS.EQ.KU\n                                 ISAME( 6 ) = ALS.EQ.ALPHA\n                                 ISAME( 7 ) = LSE( AS, AA, LAA )\n                                 ISAME( 8 ) = LDAS.EQ.LDA\n                                 ISAME( 9 ) = LSE( XS, XX, LX )\n                                 ISAME( 10 ) = INCXS.EQ.INCX\n                                 ISAME( 11 ) = BLS.EQ.BETA\n                                 IF( NULL )THEN\n                                    ISAME( 12 ) = LSE( YS, YY, LY )\n                                 ELSE\n                                    ISAME( 12 ) = LSERES( 'GE', ' ', 1,\n     $                                            ML, YS, YY,\n     $                                            ABS( INCY ) )\n                                 END IF\n                                 ISAME( 13 ) = INCYS.EQ.INCY\n                              END IF\n*\n*                             If data was incorrectly changed, report\n*                             and return.\n*\n                              SAME = .TRUE.\n                              DO 40 I = 1, NARGS\n                                 SAME = SAME.AND.ISAME( I )\n                                 IF( .NOT.ISAME( I ) )\n     $                              WRITE( NOUT, FMT = 9998 )I\n   40                         CONTINUE\n                              IF( .NOT.SAME )THEN\n                                 FATAL = .TRUE.\n                                 GO TO 130\n                              END IF\n*\n                              IF( .NOT.NULL )THEN\n*\n*                                Check the result.\n*\n                                 CALL SMVCH( TRANS, M, N, ALPHA, A,\n     $                                       NMAX, X, INCX, BETA, Y,\n     $                                       INCY, YT, G, YY, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                                 ERRMAX = MAX( ERRMAX, ERR )\n*                                If got really bad answer, report and\n*                                return.\n                                 IF( FATAL )\n     $                              GO TO 130\n                              ELSE\n*                                Avoid repeating tests with M.le.0 or\n*                                N.le.0.\n                                 GO TO 110\n                              END IF\n*\n   50                      CONTINUE\n*\n   60                   CONTINUE\n*\n   70                CONTINUE\n*\n   80             CONTINUE\n*\n   90          CONTINUE\n*\n  100       CONTINUE\n*\n  110    CONTINUE\n*\n  120 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 140\n*\n  130 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, TRANS, M, N, ALPHA, LDA,\n     $      INCX, BETA, INCY\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, TRANS, M, N, KL, KU,\n     $      ALPHA, LDA, INCX, BETA, INCY\n      END IF\n*\n  140 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 4( I3, ',' ), F4.1,\n     $      ', A,', I3, ', X,', I2, ',', F4.1, ', Y,', I2, ') .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 2( I3, ',' ), F4.1,\n     $      ', A,', I3, ', X,', I2, ',', F4.1, ', Y,', I2,\n     $      ')         .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK1.\n*\n      END\n      SUBROUTINE SCHK2( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF, NBET,\n     $                  BET, NINC, INC, NMAX, INCMAX, A, AA, AS, X, XX,\n     $                  XS, Y, YY, YS, YT, G )\n*\n*  Tests SSYMV, SSBMV and SSPMV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      REAL               ZERO, HALF\n      PARAMETER          ( ZERO = 0.0, HALF = 0.5 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NALF, NBET, NIDIM, NINC, NKB, NMAX,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), BET( NBET ), G( NMAX ),\n     $                   X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      REAL               ALPHA, ALS, BETA, BLS, ERR, ERRMAX, TRANSL\n      INTEGER            I, IA, IB, IC, IK, IN, INCX, INCXS, INCY,\n     $                   INCYS, IX, IY, K, KS, LAA, LDA, LDAS, LX, LY,\n     $                   N, NARGS, NC, NK, NS\n      LOGICAL            BANDED, FULL, NULL, PACKED, RESET, SAME\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SMAKE, SMVCH, SSBMV, SSPMV, SSYMV\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'Y'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 10\n      ELSE IF( BANDED )THEN\n         NARGS = 11\n      ELSE IF( PACKED )THEN\n         NARGS = 9\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 110 IN = 1, NIDIM\n         N = IDIM( IN )\n*\n         IF( BANDED )THEN\n            NK = NKB\n         ELSE\n            NK = 1\n         END IF\n         DO 100 IK = 1, NK\n            IF( BANDED )THEN\n               K = KB( IK )\n            ELSE\n               K = N - 1\n            END IF\n*           Set LDA to 1 more than minimum value if room.\n            IF( BANDED )THEN\n               LDA = K + 1\n            ELSE\n               LDA = N\n            END IF\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 100\n            IF( PACKED )THEN\n               LAA = ( N*( N + 1 ) )/2\n            ELSE\n               LAA = LDA*N\n            END IF\n            NULL = N.LE.0\n*\n            DO 90 IC = 1, 2\n               UPLO = ICH( IC: IC )\n*\n*              Generate the matrix A.\n*\n               TRANSL = ZERO\n               CALL SMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A, NMAX, AA,\n     $                     LDA, K, K, RESET, TRANSL )\n*\n               DO 80 IX = 1, NINC\n                  INCX = INC( IX )\n                  LX = ABS( INCX )*N\n*\n*                 Generate the vector X.\n*\n                  TRANSL = HALF\n                  CALL SMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX,\n     $                        ABS( INCX ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     X( N/2 ) = ZERO\n                     XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 70 IY = 1, NINC\n                     INCY = INC( IY )\n                     LY = ABS( INCY )*N\n*\n                     DO 60 IA = 1, NALF\n                        ALPHA = ALF( IA )\n*\n                        DO 50 IB = 1, NBET\n                           BETA = BET( IB )\n*\n*                          Generate the vector Y.\n*\n                           TRANSL = ZERO\n                           CALL SMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                                 ABS( INCY ), 0, N - 1, RESET,\n     $                                 TRANSL )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           UPLOS = UPLO\n                           NS = N\n                           KS = K\n                           ALS = ALPHA\n                           DO 10 I = 1, LAA\n                              AS( I ) = AA( I )\n   10                      CONTINUE\n                           LDAS = LDA\n                           DO 20 I = 1, LX\n                              XS( I ) = XX( I )\n   20                      CONTINUE\n                           INCXS = INCX\n                           BLS = BETA\n                           DO 30 I = 1, LY\n                              YS( I ) = YY( I )\n   30                      CONTINUE\n                           INCYS = INCY\n*\n*                          Call the subroutine.\n*\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, N, ALPHA, LDA, INCX, BETA, INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL SSYMV( UPLO, N, ALPHA, AA, LDA, XX,\n     $                                    INCX, BETA, YY, INCY )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, N, K, ALPHA, LDA, INCX, BETA,\n     $                           INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL SSBMV( UPLO, N, K, ALPHA, AA, LDA,\n     $                                    XX, INCX, BETA, YY, INCY )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, N, ALPHA, INCX, BETA, INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL SSPMV( UPLO, N, ALPHA, AA, XX, INCX,\n     $                                    BETA, YY, INCY )\n                           END IF\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9992 )\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = UPLO.EQ.UPLOS\n                           ISAME( 2 ) = NS.EQ.N\n                           IF( FULL )THEN\n                              ISAME( 3 ) = ALS.EQ.ALPHA\n                              ISAME( 4 ) = LSE( AS, AA, LAA )\n                              ISAME( 5 ) = LDAS.EQ.LDA\n                              ISAME( 6 ) = LSE( XS, XX, LX )\n                              ISAME( 7 ) = INCXS.EQ.INCX\n                              ISAME( 8 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 9 ) = LSE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 9 ) = LSERES( 'GE', ' ', 1, N,\n     $                                        YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 10 ) = INCYS.EQ.INCY\n                           ELSE IF( BANDED )THEN\n                              ISAME( 3 ) = KS.EQ.K\n                              ISAME( 4 ) = ALS.EQ.ALPHA\n                              ISAME( 5 ) = LSE( AS, AA, LAA )\n                              ISAME( 6 ) = LDAS.EQ.LDA\n                              ISAME( 7 ) = LSE( XS, XX, LX )\n                              ISAME( 8 ) = INCXS.EQ.INCX\n                              ISAME( 9 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 10 ) = LSE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 10 ) = LSERES( 'GE', ' ', 1, N,\n     $                                         YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 11 ) = INCYS.EQ.INCY\n                           ELSE IF( PACKED )THEN\n                              ISAME( 3 ) = ALS.EQ.ALPHA\n                              ISAME( 4 ) = LSE( AS, AA, LAA )\n                              ISAME( 5 ) = LSE( XS, XX, LX )\n                              ISAME( 6 ) = INCXS.EQ.INCX\n                              ISAME( 7 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 8 ) = LSE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 8 ) = LSERES( 'GE', ' ', 1, N,\n     $                                        YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 9 ) = INCYS.EQ.INCY\n                           END IF\n*\n*                          If data was incorrectly changed, report and\n*                          return.\n*\n                           SAME = .TRUE.\n                           DO 40 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   40                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n*\n*                             Check the result.\n*\n                              CALL SMVCH( 'N', N, N, ALPHA, A, NMAX, X,\n     $                                    INCX, BETA, Y, INCY, YT, G,\n     $                                    YY, EPS, ERR, FATAL, NOUT,\n     $                                    .TRUE. )\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 120\n                           ELSE\n*                             Avoid repeating tests with N.le.0\n                              GO TO 110\n                           END IF\n*\n   50                   CONTINUE\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, ALPHA, LDA, INCX,\n     $      BETA, INCY\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, K, ALPHA, LDA,\n     $      INCX, BETA, INCY\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, UPLO, N, ALPHA, INCX,\n     $      BETA, INCY\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', AP',\n     $      ', X,', I2, ',', F4.1, ', Y,', I2, ')                .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 2( I3, ',' ), F4.1,\n     $      ', A,', I3, ', X,', I2, ',', F4.1, ', Y,', I2,\n     $      ')         .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', A,',\n     $      I3, ', X,', I2, ',', F4.1, ', Y,', I2, ')             .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK2.\n*\n      END\n      SUBROUTINE SCHK3( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, XT, G, Z )\n*\n*  Tests STRMV, STBMV, STPMV, STRSV, STBSV and STPSV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      REAL               ZERO, HALF, ONE\n      PARAMETER          ( ZERO = 0.0, HALF = 0.5, ONE = 1.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NIDIM, NINC, NKB, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ),\n     $                   AS( NMAX*NMAX ), G( NMAX ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XT( NMAX ),\n     $                   XX( NMAX*INCMAX ), Z( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      REAL               ERR, ERRMAX, TRANSL\n      INTEGER            I, ICD, ICT, ICU, IK, IN, INCX, INCXS, IX, K,\n     $                   KS, LAA, LDA, LDAS, LX, N, NARGS, NC, NK, NS\n      LOGICAL            BANDED, FULL, NULL, PACKED, RESET, SAME\n      CHARACTER*1        DIAG, DIAGS, TRANS, TRANSS, UPLO, UPLOS\n      CHARACTER*2        ICHD, ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SMAKE, SMVCH, STBMV, STBSV, STPMV, STPSV,\n     $                   STRMV, STRSV\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHU/'UL'/, ICHT/'NTC'/, ICHD/'UN'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'R'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 8\n      ELSE IF( BANDED )THEN\n         NARGS = 9\n      ELSE IF( PACKED )THEN\n         NARGS = 7\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*     Set up zero vector for SMVCH.\n      DO 10 I = 1, NMAX\n         Z( I ) = ZERO\n   10 CONTINUE\n*\n      DO 110 IN = 1, NIDIM\n         N = IDIM( IN )\n*\n         IF( BANDED )THEN\n            NK = NKB\n         ELSE\n            NK = 1\n         END IF\n         DO 100 IK = 1, NK\n            IF( BANDED )THEN\n               K = KB( IK )\n            ELSE\n               K = N - 1\n            END IF\n*           Set LDA to 1 more than minimum value if room.\n            IF( BANDED )THEN\n               LDA = K + 1\n            ELSE\n               LDA = N\n            END IF\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 100\n            IF( PACKED )THEN\n               LAA = ( N*( N + 1 ) )/2\n            ELSE\n               LAA = LDA*N\n            END IF\n            NULL = N.LE.0\n*\n            DO 90 ICU = 1, 2\n               UPLO = ICHU( ICU: ICU )\n*\n               DO 80 ICT = 1, 3\n                  TRANS = ICHT( ICT: ICT )\n*\n                  DO 70 ICD = 1, 2\n                     DIAG = ICHD( ICD: ICD )\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL SMAKE( SNAME( 2: 3 ), UPLO, DIAG, N, N, A,\n     $                           NMAX, AA, LDA, K, K, RESET, TRANSL )\n*\n                     DO 60 IX = 1, NINC\n                        INCX = INC( IX )\n                        LX = ABS( INCX )*N\n*\n*                       Generate the vector X.\n*\n                        TRANSL = HALF\n                        CALL SMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX,\n     $                              ABS( INCX ), 0, N - 1, RESET,\n     $                              TRANSL )\n                        IF( N.GT.1 )THEN\n                           X( N/2 ) = ZERO\n                           XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n                        END IF\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        DIAGS = DIAG\n                        NS = N\n                        KS = K\n                        DO 20 I = 1, LAA\n                           AS( I ) = AA( I )\n   20                   CONTINUE\n                        LDAS = LDA\n                        DO 30 I = 1, LX\n                           XS( I ) = XX( I )\n   30                   CONTINUE\n                        INCXS = INCX\n*\n*                       Call the subroutine.\n*\n                        IF( SNAME( 4: 5 ).EQ.'MV' )THEN\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL STRMV( UPLO, TRANS, DIAG, N, AA, LDA,\n     $                                    XX, INCX )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, K, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL STBMV( UPLO, TRANS, DIAG, N, K, AA,\n     $                                    LDA, XX, INCX )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL STPMV( UPLO, TRANS, DIAG, N, AA, XX,\n     $                                    INCX )\n                           END IF\n                        ELSE IF( SNAME( 4: 5 ).EQ.'SV' )THEN\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL STRSV( UPLO, TRANS, DIAG, N, AA, LDA,\n     $                                    XX, INCX )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, K, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL STBSV( UPLO, TRANS, DIAG, N, K, AA,\n     $                                    LDA, XX, INCX )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL STPSV( UPLO, TRANS, DIAG, N, AA, XX,\n     $                                    INCX )\n                           END IF\n                        END IF\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9992 )\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLO.EQ.UPLOS\n                        ISAME( 2 ) = TRANS.EQ.TRANSS\n                        ISAME( 3 ) = DIAG.EQ.DIAGS\n                        ISAME( 4 ) = NS.EQ.N\n                        IF( FULL )THEN\n                           ISAME( 5 ) = LSE( AS, AA, LAA )\n                           ISAME( 6 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 7 ) = LSE( XS, XX, LX )\n                           ELSE\n                              ISAME( 7 ) = LSERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 8 ) = INCXS.EQ.INCX\n                        ELSE IF( BANDED )THEN\n                           ISAME( 5 ) = KS.EQ.K\n                           ISAME( 6 ) = LSE( AS, AA, LAA )\n                           ISAME( 7 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 8 ) = LSE( XS, XX, LX )\n                           ELSE\n                              ISAME( 8 ) = LSERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 9 ) = INCXS.EQ.INCX\n                        ELSE IF( PACKED )THEN\n                           ISAME( 5 ) = LSE( AS, AA, LAA )\n                           IF( NULL )THEN\n                              ISAME( 6 ) = LSE( XS, XX, LX )\n                           ELSE\n                              ISAME( 6 ) = LSERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 7 ) = INCXS.EQ.INCX\n                        END IF\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n                           IF( SNAME( 4: 5 ).EQ.'MV' )THEN\n*\n*                             Check the result.\n*\n                              CALL SMVCH( TRANS, N, N, ONE, A, NMAX, X,\n     $                                    INCX, ZERO, Z, INCX, XT, G,\n     $                                    XX, EPS, ERR, FATAL, NOUT,\n     $                                    .TRUE. )\n                           ELSE IF( SNAME( 4: 5 ).EQ.'SV' )THEN\n*\n*                             Compute approximation to original vector.\n*\n                              DO 50 I = 1, N\n                                 Z( I ) = XX( 1 + ( I - 1 )*\n     $                                    ABS( INCX ) )\n                                 XX( 1 + ( I - 1 )*ABS( INCX ) )\n     $                              = X( I )\n   50                         CONTINUE\n                              CALL SMVCH( TRANS, N, N, ONE, A, NMAX, Z,\n     $                                    INCX, ZERO, X, INCX, XT, G,\n     $                                    XX, EPS, ERR, FATAL, NOUT,\n     $                                    .FALSE. )\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 120\n                        ELSE\n*                          Avoid repeating tests with N.le.0.\n                           GO TO 110\n                        END IF\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, TRANS, DIAG, N, LDA,\n     $      INCX\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, DIAG, N, K,\n     $      LDA, INCX\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, UPLO, TRANS, DIAG, N, INCX\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), I3, ', AP, ',\n     $      'X,', I2, ')                        .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), 2( I3, ',' ),\n     $      ' A,', I3, ', X,', I2, ')                 .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), I3, ', A,',\n     $      I3, ', X,', I2, ')                     .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK3.\n*\n      END\n      SUBROUTINE SCHK4( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests SGER.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      REAL               ZERO, HALF, ONE\n      PARAMETER          ( ZERO = 0.0, HALF = 0.5, ONE = 1.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), G( NMAX ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XX( NMAX*INCMAX ),\n     $                   Y( NMAX ), YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      REAL               ALPHA, ALS, ERR, ERRMAX, TRANSL\n      INTEGER            I, IA, IM, IN, INCX, INCXS, INCY, INCYS, IX,\n     $                   IY, J, LAA, LDA, LDAS, LX, LY, M, MS, N, NARGS,\n     $                   NC, ND, NS\n      LOGICAL            NULL, RESET, SAME\n*     .. Local Arrays ..\n      REAL               W( 1 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SGER, SMAKE, SMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n*     Define the number of arguments.\n      NARGS = 9\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 120 IN = 1, NIDIM\n         N = IDIM( IN )\n         ND = N/2 + 1\n*\n         DO 110 IM = 1, 2\n            IF( IM.EQ.1 )\n     $         M = MAX( N - ND, 0 )\n            IF( IM.EQ.2 )\n     $         M = MIN( N + ND, NMAX )\n*\n*           Set LDA to 1 more than minimum value if room.\n            LDA = M\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 110\n            LAA = LDA*N\n            NULL = N.LE.0.OR.M.LE.0\n*\n            DO 100 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*M\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL SMAKE( 'GE', ' ', ' ', 1, M, X, 1, XX, ABS( INCX ),\n     $                     0, M - 1, RESET, TRANSL )\n               IF( M.GT.1 )THEN\n                  X( M/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( M/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 90 IY = 1, NINC\n                  INCY = INC( IY )\n                  LY = ABS( INCY )*N\n*\n*                 Generate the vector Y.\n*\n                  TRANSL = ZERO\n                  CALL SMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                        ABS( INCY ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     Y( N/2 ) = ZERO\n                     YY( 1 + ABS( INCY )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 80 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL SMAKE( SNAME( 2: 3 ), ' ', ' ', M, N, A, NMAX,\n     $                           AA, LDA, M - 1, N - 1, RESET, TRANSL )\n*\n                     NC = NC + 1\n*\n*                    Save every datum before calling the subroutine.\n*\n                     MS = M\n                     NS = N\n                     ALS = ALPHA\n                     DO 10 I = 1, LAA\n                        AS( I ) = AA( I )\n   10                CONTINUE\n                     LDAS = LDA\n                     DO 20 I = 1, LX\n                        XS( I ) = XX( I )\n   20                CONTINUE\n                     INCXS = INCX\n                     DO 30 I = 1, LY\n                        YS( I ) = YY( I )\n   30                CONTINUE\n                     INCYS = INCY\n*\n*                    Call the subroutine.\n*\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9994 )NC, SNAME, M, N,\n     $                  ALPHA, INCX, INCY, LDA\n                     IF( REWI )\n     $                  REWIND NTRA\n                     CALL SGER( M, N, ALPHA, XX, INCX, YY, INCY, AA,\n     $                          LDA )\n*\n*                    Check if error-exit was taken incorrectly.\n*\n                     IF( .NOT.OK )THEN\n                        WRITE( NOUT, FMT = 9993 )\n                        FATAL = .TRUE.\n                        GO TO 140\n                     END IF\n*\n*                    See what data changed inside subroutine.\n*\n                     ISAME( 1 ) = MS.EQ.M\n                     ISAME( 2 ) = NS.EQ.N\n                     ISAME( 3 ) = ALS.EQ.ALPHA\n                     ISAME( 4 ) = LSE( XS, XX, LX )\n                     ISAME( 5 ) = INCXS.EQ.INCX\n                     ISAME( 6 ) = LSE( YS, YY, LY )\n                     ISAME( 7 ) = INCYS.EQ.INCY\n                     IF( NULL )THEN\n                        ISAME( 8 ) = LSE( AS, AA, LAA )\n                     ELSE\n                        ISAME( 8 ) = LSERES( 'GE', ' ', M, N, AS, AA,\n     $                               LDA )\n                     END IF\n                     ISAME( 9 ) = LDAS.EQ.LDA\n*\n*                    If data was incorrectly changed, report and return.\n*\n                     SAME = .TRUE.\n                     DO 40 I = 1, NARGS\n                        SAME = SAME.AND.ISAME( I )\n                        IF( .NOT.ISAME( I ) )\n     $                     WRITE( NOUT, FMT = 9998 )I\n   40                CONTINUE\n                     IF( .NOT.SAME )THEN\n                        FATAL = .TRUE.\n                        GO TO 140\n                     END IF\n*\n                     IF( .NOT.NULL )THEN\n*\n*                       Check the result column by column.\n*\n                        IF( INCX.GT.0 )THEN\n                           DO 50 I = 1, M\n                              Z( I ) = X( I )\n   50                      CONTINUE\n                        ELSE\n                           DO 60 I = 1, M\n                              Z( I ) = X( M - I + 1 )\n   60                      CONTINUE\n                        END IF\n                        DO 70 J = 1, N\n                           IF( INCY.GT.0 )THEN\n                              W( 1 ) = Y( J )\n                           ELSE\n                              W( 1 ) = Y( N - J + 1 )\n                           END IF\n                           CALL SMVCH( 'N', M, 1, ALPHA, Z, NMAX, W, 1,\n     $                                 ONE, A( 1, J ), 1, YT, G,\n     $                                 AA( 1 + ( J - 1 )*LDA ), EPS,\n     $                                 ERR, FATAL, NOUT, .TRUE. )\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 130\n   70                   CONTINUE\n                     ELSE\n*                       Avoid repeating tests with M.le.0 or N.le.0.\n                        GO TO 110\n                     END IF\n*\n   80             CONTINUE\n*\n   90          CONTINUE\n*\n  100       CONTINUE\n*\n  110    CONTINUE\n*\n  120 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 150\n*\n  130 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  140 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9994 )NC, SNAME, M, N, ALPHA, INCX, INCY, LDA\n*\n  150 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( I3, ',' ), F4.1, ', X,', I2,\n     $      ', Y,', I2, ', A,', I3, ')                  .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK4.\n*\n      END\n      SUBROUTINE SCHK5( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests SSYR and SSPR.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      REAL               ZERO, HALF, ONE\n      PARAMETER          ( ZERO = 0.0, HALF = 0.5, ONE = 1.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), G( NMAX ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XX( NMAX*INCMAX ),\n     $                   Y( NMAX ), YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      REAL               ALPHA, ALS, ERR, ERRMAX, TRANSL\n      INTEGER            I, IA, IC, IN, INCX, INCXS, IX, J, JA, JJ, LAA,\n     $                   LDA, LDAS, LJ, LX, N, NARGS, NC, NS\n      LOGICAL            FULL, NULL, PACKED, RESET, SAME, UPPER\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      REAL               W( 1 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SMAKE, SMVCH, SSPR, SSYR\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'Y'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 7\n      ELSE IF( PACKED )THEN\n         NARGS = 6\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 100 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDA to 1 more than minimum value if room.\n         LDA = N\n         IF( LDA.LT.NMAX )\n     $      LDA = LDA + 1\n*        Skip tests if not enough room.\n         IF( LDA.GT.NMAX )\n     $      GO TO 100\n         IF( PACKED )THEN\n            LAA = ( N*( N + 1 ) )/2\n         ELSE\n            LAA = LDA*N\n         END IF\n*\n         DO 90 IC = 1, 2\n            UPLO = ICH( IC: IC )\n            UPPER = UPLO.EQ.'U'\n*\n            DO 80 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*N\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL SMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX, ABS( INCX ),\n     $                     0, N - 1, RESET, TRANSL )\n               IF( N.GT.1 )THEN\n                  X( N/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 70 IA = 1, NALF\n                  ALPHA = ALF( IA )\n                  NULL = N.LE.0.OR.ALPHA.EQ.ZERO\n*\n*                 Generate the matrix A.\n*\n                  TRANSL = ZERO\n                  CALL SMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A, NMAX,\n     $                        AA, LDA, N - 1, N - 1, RESET, TRANSL )\n*\n                  NC = NC + 1\n*\n*                 Save every datum before calling the subroutine.\n*\n                  UPLOS = UPLO\n                  NS = N\n                  ALS = ALPHA\n                  DO 10 I = 1, LAA\n                     AS( I ) = AA( I )\n   10             CONTINUE\n                  LDAS = LDA\n                  DO 20 I = 1, LX\n                     XS( I ) = XX( I )\n   20             CONTINUE\n                  INCXS = INCX\n*\n*                 Call the subroutine.\n*\n                  IF( FULL )THEN\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO, N,\n     $                  ALPHA, INCX, LDA\n                     IF( REWI )\n     $                  REWIND NTRA\n                     CALL SSYR( UPLO, N, ALPHA, XX, INCX, AA, LDA )\n                  ELSE IF( PACKED )THEN\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO, N,\n     $                  ALPHA, INCX\n                     IF( REWI )\n     $                  REWIND NTRA\n                     CALL SSPR( UPLO, N, ALPHA, XX, INCX, AA )\n                  END IF\n*\n*                 Check if error-exit was taken incorrectly.\n*\n                  IF( .NOT.OK )THEN\n                     WRITE( NOUT, FMT = 9992 )\n                     FATAL = .TRUE.\n                     GO TO 120\n                  END IF\n*\n*                 See what data changed inside subroutines.\n*\n                  ISAME( 1 ) = UPLO.EQ.UPLOS\n                  ISAME( 2 ) = NS.EQ.N\n                  ISAME( 3 ) = ALS.EQ.ALPHA\n                  ISAME( 4 ) = LSE( XS, XX, LX )\n                  ISAME( 5 ) = INCXS.EQ.INCX\n                  IF( NULL )THEN\n                     ISAME( 6 ) = LSE( AS, AA, LAA )\n                  ELSE\n                     ISAME( 6 ) = LSERES( SNAME( 2: 3 ), UPLO, N, N, AS,\n     $                            AA, LDA )\n                  END IF\n                  IF( .NOT.PACKED )THEN\n                     ISAME( 7 ) = LDAS.EQ.LDA\n                  END IF\n*\n*                 If data was incorrectly changed, report and return.\n*\n                  SAME = .TRUE.\n                  DO 30 I = 1, NARGS\n                     SAME = SAME.AND.ISAME( I )\n                     IF( .NOT.ISAME( I ) )\n     $                  WRITE( NOUT, FMT = 9998 )I\n   30             CONTINUE\n                  IF( .NOT.SAME )THEN\n                     FATAL = .TRUE.\n                     GO TO 120\n                  END IF\n*\n                  IF( .NOT.NULL )THEN\n*\n*                    Check the result column by column.\n*\n                     IF( INCX.GT.0 )THEN\n                        DO 40 I = 1, N\n                           Z( I ) = X( I )\n   40                   CONTINUE\n                     ELSE\n                        DO 50 I = 1, N\n                           Z( I ) = X( N - I + 1 )\n   50                   CONTINUE\n                     END IF\n                     JA = 1\n                     DO 60 J = 1, N\n                        W( 1 ) = Z( J )\n                        IF( UPPER )THEN\n                           JJ = 1\n                           LJ = J\n                        ELSE\n                           JJ = J\n                           LJ = N - J + 1\n                        END IF\n                        CALL SMVCH( 'N', LJ, 1, ALPHA, Z( JJ ), LJ, W,\n     $                              1, ONE, A( JJ, J ), 1, YT, G,\n     $                              AA( JA ), EPS, ERR, FATAL, NOUT,\n     $                              .TRUE. )\n                        IF( FULL )THEN\n                           IF( UPPER )THEN\n                              JA = JA + LDA\n                           ELSE\n                              JA = JA + LDA + 1\n                           END IF\n                        ELSE\n                           JA = JA + LJ\n                        END IF\n                        ERRMAX = MAX( ERRMAX, ERR )\n*                       If got really bad answer, report and return.\n                        IF( FATAL )\n     $                     GO TO 110\n   60                CONTINUE\n                  ELSE\n*                    Avoid repeating tests if N.le.0.\n                     IF( N.LE.0 )\n     $                  GO TO 100\n                  END IF\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  110 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, ALPHA, INCX, LDA\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, ALPHA, INCX\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', AP)                           .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', A,', I3, ')                        .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK5.\n*\n      END\n      SUBROUTINE SCHK6( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests SSYR2 and SSPR2.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      REAL               ZERO, HALF, ONE\n      PARAMETER          ( ZERO = 0.0, HALF = 0.5, ONE = 1.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), G( NMAX ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XX( NMAX*INCMAX ),\n     $                   Y( NMAX ), YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX, 2 )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      REAL               ALPHA, ALS, ERR, ERRMAX, TRANSL\n      INTEGER            I, IA, IC, IN, INCX, INCXS, INCY, INCYS, IX,\n     $                   IY, J, JA, JJ, LAA, LDA, LDAS, LJ, LX, LY, N,\n     $                   NARGS, NC, NS\n      LOGICAL            FULL, NULL, PACKED, RESET, SAME, UPPER\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      REAL               W( 2 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SMAKE, SMVCH, SSPR2, SSYR2\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'Y'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 9\n      ELSE IF( PACKED )THEN\n         NARGS = 8\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 140 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDA to 1 more than minimum value if room.\n         LDA = N\n         IF( LDA.LT.NMAX )\n     $      LDA = LDA + 1\n*        Skip tests if not enough room.\n         IF( LDA.GT.NMAX )\n     $      GO TO 140\n         IF( PACKED )THEN\n            LAA = ( N*( N + 1 ) )/2\n         ELSE\n            LAA = LDA*N\n         END IF\n*\n         DO 130 IC = 1, 2\n            UPLO = ICH( IC: IC )\n            UPPER = UPLO.EQ.'U'\n*\n            DO 120 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*N\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL SMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX, ABS( INCX ),\n     $                     0, N - 1, RESET, TRANSL )\n               IF( N.GT.1 )THEN\n                  X( N/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 110 IY = 1, NINC\n                  INCY = INC( IY )\n                  LY = ABS( INCY )*N\n*\n*                 Generate the vector Y.\n*\n                  TRANSL = ZERO\n                  CALL SMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                        ABS( INCY ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     Y( N/2 ) = ZERO\n                     YY( 1 + ABS( INCY )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 100 IA = 1, NALF\n                     ALPHA = ALF( IA )\n                     NULL = N.LE.0.OR.ALPHA.EQ.ZERO\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL SMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A,\n     $                           NMAX, AA, LDA, N - 1, N - 1, RESET,\n     $                           TRANSL )\n*\n                     NC = NC + 1\n*\n*                    Save every datum before calling the subroutine.\n*\n                     UPLOS = UPLO\n                     NS = N\n                     ALS = ALPHA\n                     DO 10 I = 1, LAA\n                        AS( I ) = AA( I )\n   10                CONTINUE\n                     LDAS = LDA\n                     DO 20 I = 1, LX\n                        XS( I ) = XX( I )\n   20                CONTINUE\n                     INCXS = INCX\n                     DO 30 I = 1, LY\n                        YS( I ) = YY( I )\n   30                CONTINUE\n                     INCYS = INCY\n*\n*                    Call the subroutine.\n*\n                     IF( FULL )THEN\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO, N,\n     $                     ALPHA, INCX, INCY, LDA\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL SSYR2( UPLO, N, ALPHA, XX, INCX, YY, INCY,\n     $                              AA, LDA )\n                     ELSE IF( PACKED )THEN\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO, N,\n     $                     ALPHA, INCX, INCY\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL SSPR2( UPLO, N, ALPHA, XX, INCX, YY, INCY,\n     $                              AA )\n                     END IF\n*\n*                    Check if error-exit was taken incorrectly.\n*\n                     IF( .NOT.OK )THEN\n                        WRITE( NOUT, FMT = 9992 )\n                        FATAL = .TRUE.\n                        GO TO 160\n                     END IF\n*\n*                    See what data changed inside subroutines.\n*\n                     ISAME( 1 ) = UPLO.EQ.UPLOS\n                     ISAME( 2 ) = NS.EQ.N\n                     ISAME( 3 ) = ALS.EQ.ALPHA\n                     ISAME( 4 ) = LSE( XS, XX, LX )\n                     ISAME( 5 ) = INCXS.EQ.INCX\n                     ISAME( 6 ) = LSE( YS, YY, LY )\n                     ISAME( 7 ) = INCYS.EQ.INCY\n                     IF( NULL )THEN\n                        ISAME( 8 ) = LSE( AS, AA, LAA )\n                     ELSE\n                        ISAME( 8 ) = LSERES( SNAME( 2: 3 ), UPLO, N, N,\n     $                               AS, AA, LDA )\n                     END IF\n                     IF( .NOT.PACKED )THEN\n                        ISAME( 9 ) = LDAS.EQ.LDA\n                     END IF\n*\n*                    If data was incorrectly changed, report and return.\n*\n                     SAME = .TRUE.\n                     DO 40 I = 1, NARGS\n                        SAME = SAME.AND.ISAME( I )\n                        IF( .NOT.ISAME( I ) )\n     $                     WRITE( NOUT, FMT = 9998 )I\n   40                CONTINUE\n                     IF( .NOT.SAME )THEN\n                        FATAL = .TRUE.\n                        GO TO 160\n                     END IF\n*\n                     IF( .NOT.NULL )THEN\n*\n*                       Check the result column by column.\n*\n                        IF( INCX.GT.0 )THEN\n                           DO 50 I = 1, N\n                              Z( I, 1 ) = X( I )\n   50                      CONTINUE\n                        ELSE\n                           DO 60 I = 1, N\n                              Z( I, 1 ) = X( N - I + 1 )\n   60                      CONTINUE\n                        END IF\n                        IF( INCY.GT.0 )THEN\n                           DO 70 I = 1, N\n                              Z( I, 2 ) = Y( I )\n   70                      CONTINUE\n                        ELSE\n                           DO 80 I = 1, N\n                              Z( I, 2 ) = Y( N - I + 1 )\n   80                      CONTINUE\n                        END IF\n                        JA = 1\n                        DO 90 J = 1, N\n                           W( 1 ) = Z( J, 2 )\n                           W( 2 ) = Z( J, 1 )\n                           IF( UPPER )THEN\n                              JJ = 1\n                              LJ = J\n                           ELSE\n                              JJ = J\n                              LJ = N - J + 1\n                           END IF\n                           CALL SMVCH( 'N', LJ, 2, ALPHA, Z( JJ, 1 ),\n     $                                 NMAX, W, 1, ONE, A( JJ, J ), 1,\n     $                                 YT, G, AA( JA ), EPS, ERR, FATAL,\n     $                                 NOUT, .TRUE. )\n                           IF( FULL )THEN\n                              IF( UPPER )THEN\n                                 JA = JA + LDA\n                              ELSE\n                                 JA = JA + LDA + 1\n                              END IF\n                           ELSE\n                              JA = JA + LJ\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 150\n   90                   CONTINUE\n                     ELSE\n*                       Avoid repeating tests with N.le.0.\n                        IF( N.LE.0 )\n     $                     GO TO 140\n                     END IF\n*\n  100             CONTINUE\n*\n  110          CONTINUE\n*\n  120       CONTINUE\n*\n  130    CONTINUE\n*\n  140 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 170\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  160 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, ALPHA, INCX,\n     $      INCY, LDA\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, ALPHA, INCX, INCY\n      END IF\n*\n  170 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', Y,', I2, ', AP)                     .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', Y,', I2, ', A,', I3, ')                  .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK6.\n*\n      END\n      SUBROUTINE SCHKE( ISNUM, SRNAMT, NOUT )\n*\n*  Tests the error exits from the Level 2 Blas.\n*  Requires a special version of the error-handling routine XERBLA.\n*  ALPHA, BETA, A, X and Y should not need to be defined.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            ISNUM, NOUT\n      CHARACTER*6        SRNAMT\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Local Scalars ..\n      REAL               ALPHA, BETA\n*     .. Local Arrays ..\n      REAL               A( 1, 1 ), X( 1 ), Y( 1 )\n*     .. External Subroutines ..\n      EXTERNAL           CHKXER, SGBMV, SGEMV, SGER, SSBMV, SSPMV, SSPR,\n     $                   SSPR2, SSYMV, SSYR, SSYR2, STBMV, STBSV, STPMV,\n     $                   STPSV, STRMV, STRSV\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n*     OK is set to .FALSE. by the special version of XERBLA or by CHKXER\n*     if anything is wrong.\n      OK = .TRUE.\n*     LERR is set to .TRUE. by the special version of XERBLA each time\n*     it is called, and is then tested and re-set by CHKXER.\n      LERR = .FALSE.\n      GO TO ( 10, 20, 30, 40, 50, 60, 70, 80,\n     $        90, 100, 110, 120, 130, 140, 150,\n     $        160 )ISNUM\n   10 INFOT = 1\n      CALL SGEMV( '/', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SGEMV( 'N', -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SGEMV( 'N', 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL SGEMV( 'N', 2, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL SGEMV( 'N', 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL SGEMV( 'N', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   20 INFOT = 1\n      CALL SGBMV( '/', 0, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SGBMV( 'N', -1, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SGBMV( 'N', 0, -1, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SGBMV( 'N', 0, 0, -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SGBMV( 'N', 2, 0, 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL SGBMV( 'N', 0, 0, 1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL SGBMV( 'N', 0, 0, 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL SGBMV( 'N', 0, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   30 INFOT = 1\n      CALL SSYMV( '/', 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SSYMV( 'U', -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SSYMV( 'U', 2, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYMV( 'U', 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL SSYMV( 'U', 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   40 INFOT = 1\n      CALL SSBMV( '/', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SSBMV( 'U', -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSBMV( 'U', 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL SSBMV( 'U', 0, 1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL SSBMV( 'U', 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL SSBMV( 'U', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   50 INFOT = 1\n      CALL SSPMV( '/', 0, ALPHA, A, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SSPMV( 'U', -1, ALPHA, A, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL SSPMV( 'U', 0, ALPHA, A, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SSPMV( 'U', 0, ALPHA, A, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   60 INFOT = 1\n      CALL STRMV( '/', 'N', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL STRMV( 'U', '/', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL STRMV( 'U', 'N', '/', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL STRMV( 'U', 'N', 'N', -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRMV( 'U', 'N', 'N', 2, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL STRMV( 'U', 'N', 'N', 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   70 INFOT = 1\n      CALL STBMV( '/', 'N', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL STBMV( 'U', '/', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL STBMV( 'U', 'N', '/', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL STBMV( 'U', 'N', 'N', -1, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STBMV( 'U', 'N', 'N', 0, -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL STBMV( 'U', 'N', 'N', 0, 1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STBMV( 'U', 'N', 'N', 0, 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   80 INFOT = 1\n      CALL STPMV( '/', 'N', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL STPMV( 'U', '/', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL STPMV( 'U', 'N', '/', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL STPMV( 'U', 'N', 'N', -1, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL STPMV( 'U', 'N', 'N', 0, A, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n   90 INFOT = 1\n      CALL STRSV( '/', 'N', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL STRSV( 'U', '/', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL STRSV( 'U', 'N', '/', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL STRSV( 'U', 'N', 'N', -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRSV( 'U', 'N', 'N', 2, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL STRSV( 'U', 'N', 'N', 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  100 INFOT = 1\n      CALL STBSV( '/', 'N', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL STBSV( 'U', '/', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL STBSV( 'U', 'N', '/', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL STBSV( 'U', 'N', 'N', -1, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STBSV( 'U', 'N', 'N', 0, -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL STBSV( 'U', 'N', 'N', 0, 1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STBSV( 'U', 'N', 'N', 0, 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  110 INFOT = 1\n      CALL STPSV( '/', 'N', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL STPSV( 'U', '/', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL STPSV( 'U', 'N', '/', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL STPSV( 'U', 'N', 'N', -1, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL STPSV( 'U', 'N', 'N', 0, A, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  120 INFOT = 1\n      CALL SGER( -1, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SGER( 0, -1, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SGER( 0, 0, ALPHA, X, 0, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SGER( 0, 0, ALPHA, X, 1, Y, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SGER( 2, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  130 INFOT = 1\n      CALL SSYR( '/', 0, ALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SSYR( 'U', -1, ALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SSYR( 'U', 0, ALPHA, X, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYR( 'U', 2, ALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  140 INFOT = 1\n      CALL SSPR( '/', 0, ALPHA, X, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SSPR( 'U', -1, ALPHA, X, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SSPR( 'U', 0, ALPHA, X, 0, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  150 INFOT = 1\n      CALL SSYR2( '/', 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SSYR2( 'U', -1, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SSYR2( 'U', 0, ALPHA, X, 0, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYR2( 'U', 0, ALPHA, X, 1, Y, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SSYR2( 'U', 2, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 170\n  160 INFOT = 1\n      CALL SSPR2( '/', 0, ALPHA, X, 1, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SSPR2( 'U', -1, ALPHA, X, 1, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SSPR2( 'U', 0, ALPHA, X, 0, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSPR2( 'U', 0, ALPHA, X, 1, Y, 0, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n  170 IF( OK )THEN\n         WRITE( NOUT, FMT = 9999 )SRNAMT\n      ELSE\n         WRITE( NOUT, FMT = 9998 )SRNAMT\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE TESTS OF ERROR-EXITS' )\n 9998 FORMAT( ' ******* ', A6, ' FAILED THE TESTS OF ERROR-EXITS *****',\n     $      '**' )\n*\n*     End of SCHKE.\n*\n      END\n      SUBROUTINE SMAKE( TYPE, UPLO, DIAG, M, N, A, NMAX, AA, LDA, KL,\n     $                  KU, RESET, TRANSL )\n*\n*  Generates values for an M by N matrix A within the bandwidth\n*  defined by KL and KU.\n*  Stores the values in the array AA in the data structure required\n*  by the routine, with unwanted elements set to rogue value.\n*\n*  TYPE is 'GE', 'GB', 'SY', 'SB', 'SP', 'TR', 'TB' OR 'TP'.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      REAL               ZERO, ONE\n      PARAMETER          ( ZERO = 0.0, ONE = 1.0 )\n      REAL               ROGUE\n      PARAMETER          ( ROGUE = -1.0E10 )\n*     .. Scalar Arguments ..\n      REAL               TRANSL\n      INTEGER            KL, KU, LDA, M, N, NMAX\n      LOGICAL            RESET\n      CHARACTER*1        DIAG, UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      REAL               A( NMAX, * ), AA( * )\n*     .. Local Scalars ..\n      INTEGER            I, I1, I2, I3, IBEG, IEND, IOFF, J, KK\n      LOGICAL            GEN, LOWER, SYM, TRI, UNIT, UPPER\n*     .. External Functions ..\n      REAL               SBEG\n      EXTERNAL           SBEG\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX, MIN\n*     .. Executable Statements ..\n      GEN = TYPE( 1: 1 ).EQ.'G'\n      SYM = TYPE( 1: 1 ).EQ.'S'\n      TRI = TYPE( 1: 1 ).EQ.'T'\n      UPPER = ( SYM.OR.TRI ).AND.UPLO.EQ.'U'\n      LOWER = ( SYM.OR.TRI ).AND.UPLO.EQ.'L'\n      UNIT = TRI.AND.DIAG.EQ.'U'\n*\n*     Generate data in array A.\n*\n      DO 20 J = 1, N\n         DO 10 I = 1, M\n            IF( GEN.OR.( UPPER.AND.I.LE.J ).OR.( LOWER.AND.I.GE.J ) )\n     $          THEN\n               IF( ( I.LE.J.AND.J - I.LE.KU ).OR.\n     $             ( I.GE.J.AND.I - J.LE.KL ) )THEN\n                  A( I, J ) = SBEG( RESET ) + TRANSL\n               ELSE\n                  A( I, J ) = ZERO\n               END IF\n               IF( I.NE.J )THEN\n                  IF( SYM )THEN\n                     A( J, I ) = A( I, J )\n                  ELSE IF( TRI )THEN\n                     A( J, I ) = ZERO\n                  END IF\n               END IF\n            END IF\n   10    CONTINUE\n         IF( TRI )\n     $      A( J, J ) = A( J, J ) + ONE\n         IF( UNIT )\n     $      A( J, J ) = ONE\n   20 CONTINUE\n*\n*     Store elements in array AS in data structure required by routine.\n*\n      IF( TYPE.EQ.'GE' )THEN\n         DO 50 J = 1, N\n            DO 30 I = 1, M\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   30       CONTINUE\n            DO 40 I = M + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   40       CONTINUE\n   50    CONTINUE\n      ELSE IF( TYPE.EQ.'GB' )THEN\n         DO 90 J = 1, N\n            DO 60 I1 = 1, KU + 1 - J\n               AA( I1 + ( J - 1 )*LDA ) = ROGUE\n   60       CONTINUE\n            DO 70 I2 = I1, MIN( KL + KU + 1, KU + 1 + M - J )\n               AA( I2 + ( J - 1 )*LDA ) = A( I2 + J - KU - 1, J )\n   70       CONTINUE\n            DO 80 I3 = I2, LDA\n               AA( I3 + ( J - 1 )*LDA ) = ROGUE\n   80       CONTINUE\n   90    CONTINUE\n      ELSE IF( TYPE.EQ.'SY'.OR.TYPE.EQ.'TR' )THEN\n         DO 130 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IF( UNIT )THEN\n                  IEND = J - 1\n               ELSE\n                  IEND = J\n               END IF\n            ELSE\n               IF( UNIT )THEN\n                  IBEG = J + 1\n               ELSE\n                  IBEG = J\n               END IF\n               IEND = N\n            END IF\n            DO 100 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  100       CONTINUE\n            DO 110 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n  110       CONTINUE\n            DO 120 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  120       CONTINUE\n  130    CONTINUE\n      ELSE IF( TYPE.EQ.'SB'.OR.TYPE.EQ.'TB' )THEN\n         DO 170 J = 1, N\n            IF( UPPER )THEN\n               KK = KL + 1\n               IBEG = MAX( 1, KL + 2 - J )\n               IF( UNIT )THEN\n                  IEND = KL\n               ELSE\n                  IEND = KL + 1\n               END IF\n            ELSE\n               KK = 1\n               IF( UNIT )THEN\n                  IBEG = 2\n               ELSE\n                  IBEG = 1\n               END IF\n               IEND = MIN( KL + 1, 1 + M - J )\n            END IF\n            DO 140 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  140       CONTINUE\n            DO 150 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I + J - KK, J )\n  150       CONTINUE\n            DO 160 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  160       CONTINUE\n  170    CONTINUE\n      ELSE IF( TYPE.EQ.'SP'.OR.TYPE.EQ.'TP' )THEN\n         IOFF = 0\n         DO 190 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 180 I = IBEG, IEND\n               IOFF = IOFF + 1\n               AA( IOFF ) = A( I, J )\n               IF( I.EQ.J )THEN\n                  IF( UNIT )\n     $               AA( IOFF ) = ROGUE\n               END IF\n  180       CONTINUE\n  190    CONTINUE\n      END IF\n      RETURN\n*\n*     End of SMAKE.\n*\n      END\n      SUBROUTINE SMVCH( TRANS, M, N, ALPHA, A, NMAX, X, INCX, BETA, Y,\n     $                  INCY, YT, G, YY, EPS, ERR, FATAL, NOUT, MV )\n*\n*  Checks the results of the computational tests.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      REAL               ZERO, ONE\n      PARAMETER          ( ZERO = 0.0, ONE = 1.0 )\n*     .. Scalar Arguments ..\n      REAL               ALPHA, BETA, EPS, ERR\n      INTEGER            INCX, INCY, M, N, NMAX, NOUT\n      LOGICAL            FATAL, MV\n      CHARACTER*1        TRANS\n*     .. Array Arguments ..\n      REAL               A( NMAX, * ), G( * ), X( * ), Y( * ), YT( * ),\n     $                   YY( * )\n*     .. Local Scalars ..\n      REAL               ERRI\n      INTEGER            I, INCXL, INCYL, IY, J, JX, KX, KY, ML, NL\n      LOGICAL            TRAN\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, SQRT\n*     .. Executable Statements ..\n      TRAN = TRANS.EQ.'T'.OR.TRANS.EQ.'C'\n      IF( TRAN )THEN\n         ML = N\n         NL = M\n      ELSE\n         ML = M\n         NL = N\n      END IF\n      IF( INCX.LT.0 )THEN\n         KX = NL\n         INCXL = -1\n      ELSE\n         KX = 1\n         INCXL = 1\n      END IF\n      IF( INCY.LT.0 )THEN\n         KY = ML\n         INCYL = -1\n      ELSE\n         KY = 1\n         INCYL = 1\n      END IF\n*\n*     Compute expected result in YT using data in A, X and Y.\n*     Compute gauges in G.\n*\n      IY = KY\n      DO 30 I = 1, ML\n         YT( IY ) = ZERO\n         G( IY ) = ZERO\n         JX = KX\n         IF( TRAN )THEN\n            DO 10 J = 1, NL\n               YT( IY ) = YT( IY ) + A( J, I )*X( JX )\n               G( IY ) = G( IY ) + ABS( A( J, I )*X( JX ) )\n               JX = JX + INCXL\n   10       CONTINUE\n         ELSE\n            DO 20 J = 1, NL\n               YT( IY ) = YT( IY ) + A( I, J )*X( JX )\n               G( IY ) = G( IY ) + ABS( A( I, J )*X( JX ) )\n               JX = JX + INCXL\n   20       CONTINUE\n         END IF\n         YT( IY ) = ALPHA*YT( IY ) + BETA*Y( IY )\n         G( IY ) = ABS( ALPHA )*G( IY ) + ABS( BETA*Y( IY ) )\n         IY = IY + INCYL\n   30 CONTINUE\n*\n*     Compute the error ratio for this result.\n*\n      ERR = ZERO\n      DO 40 I = 1, ML\n         ERRI = ABS( YT( I ) - YY( 1 + ( I - 1 )*ABS( INCY ) ) )/EPS\n         IF( G( I ).NE.ZERO )\n     $      ERRI = ERRI/G( I )\n         ERR = MAX( ERR, ERRI )\n         IF( ERR*SQRT( EPS ).GE.ONE )\n     $      GO TO 50\n   40 CONTINUE\n*     If the loop completes, all results are at least half accurate.\n      GO TO 70\n*\n*     Report fatal error.\n*\n   50 FATAL = .TRUE.\n      WRITE( NOUT, FMT = 9999 )\n      DO 60 I = 1, ML\n         IF( MV )THEN\n            WRITE( NOUT, FMT = 9998 )I, YT( I ),\n     $         YY( 1 + ( I - 1 )*ABS( INCY ) )\n         ELSE\n            WRITE( NOUT, FMT = 9998 )I, \n     $         YY( 1 + ( I - 1 )*ABS( INCY ) ), YT(I)\n         END IF\n   60 CONTINUE\n*\n   70 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ******* FATAL ERROR - COMPUTED RESULT IS LESS THAN HAL',\n     $      'F ACCURATE *******', /'           EXPECTED RESULT   COMPU',\n     $      'TED RESULT' )\n 9998 FORMAT( 1X, I7, 2G18.6 )\n*\n*     End of SMVCH.\n*\n      END\n      LOGICAL FUNCTION LSE( RI, RJ, LR )\n*\n*  Tests if two arrays are identical.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LR\n*     .. Array Arguments ..\n      REAL               RI( * ), RJ( * )\n*     .. Local Scalars ..\n      INTEGER            I\n*     .. Executable Statements ..\n      DO 10 I = 1, LR\n         IF( RI( I ).NE.RJ( I ) )\n     $      GO TO 20\n   10 CONTINUE\n      LSE = .TRUE.\n      GO TO 30\n   20 CONTINUE\n      LSE = .FALSE.\n   30 RETURN\n*\n*     End of LSE.\n*\n      END\n      LOGICAL FUNCTION LSERES( TYPE, UPLO, M, N, AA, AS, LDA )\n*\n*  Tests if selected elements in two arrays are equal.\n*\n*  TYPE is 'GE', 'SY' or 'SP'.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LDA, M, N\n      CHARACTER*1        UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      REAL               AA( LDA, * ), AS( LDA, * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J\n      LOGICAL            UPPER\n*     .. Executable Statements ..\n      UPPER = UPLO.EQ.'U'\n      IF( TYPE.EQ.'GE' )THEN\n         DO 20 J = 1, N\n            DO 10 I = M + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   10       CONTINUE\n   20    CONTINUE\n      ELSE IF( TYPE.EQ.'SY' )THEN\n         DO 50 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 30 I = 1, IBEG - 1\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   30       CONTINUE\n            DO 40 I = IEND + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   40       CONTINUE\n   50    CONTINUE\n      END IF\n*\n      LSERES = .TRUE.\n      GO TO 80\n   70 CONTINUE\n      LSERES = .FALSE.\n   80 RETURN\n*\n*     End of LSERES.\n*\n      END\n      REAL FUNCTION SBEG( RESET )\n*\n*  Generates random numbers uniformly distributed between -0.5 and 0.5.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      LOGICAL            RESET\n*     .. Local Scalars ..\n      INTEGER            I, IC, MI\n*     .. Save statement ..\n      SAVE               I, IC, MI\n*     .. Intrinsic Functions ..\n      INTRINSIC          REAL\n*     .. Executable Statements ..\n      IF( RESET )THEN\n*        Initialize local variables.\n         MI = 891\n         I = 7\n         IC = 0\n         RESET = .FALSE.\n      END IF\n*\n*     The sequence of values of I is bounded between 1 and 999.\n*     If initial I = 1,2,3,6,7 or 9, the period will be 50.\n*     If initial I = 4 or 8, the period will be 25.\n*     If initial I = 5, the period will be 10.\n*     IC is used to break up the period by skipping 1 value of I in 6.\n*\n      IC = IC + 1\n   10 I = I*MI\n      I = I - 1000*( I/1000 )\n      IF( IC.GE.5 )THEN\n         IC = 0\n         GO TO 10\n      END IF\n      SBEG = REAL( I - 500 )/1001.0\n      RETURN\n*\n*     End of SBEG.\n*\n      END\n      REAL FUNCTION SDIFF( X, Y )\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*\n*     .. Scalar Arguments ..\n      REAL               X, Y\n*     .. Executable Statements ..\n      SDIFF = X - Y\n      RETURN\n*\n*     End of SDIFF.\n*\n      END\n      SUBROUTINE CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n*  Tests whether XERBLA has detected an error when it should.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Executable Statements ..\n      IF( .NOT.LERR )THEN\n         WRITE( NOUT, FMT = 9999 )INFOT, SRNAMT\n         OK = .FALSE.\n      END IF\n      LERR = .FALSE.\n      RETURN\n*\n 9999 FORMAT( ' ***** ILLEGAL VALUE OF PARAMETER NUMBER ', I2, ' NOT D',\n     $      'ETECTED BY ', A6, ' *****' )\n*\n*     End of CHKXER.\n*\n      END\n      SUBROUTINE XERBLA( SRNAME, INFO )\n*\n*  This is a special version of XERBLA to be used only as part of\n*  the test program for testing error exits from the Level 2 BLAS\n*  routines.\n*\n*  XERBLA  is an error handler for the Level 2 BLAS routines.\n*\n*  It is called by the Level 2 BLAS routines if an input parameter is\n*  invalid.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFO\n      CHARACTER*6        SRNAME\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUT, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Executable Statements ..\n      LERR = .TRUE.\n      IF( INFO.NE.INFOT )THEN\n         IF( INFOT.NE.0 )THEN\n            WRITE( NOUT, FMT = 9999 )INFO, INFOT\n         ELSE\n            WRITE( NOUT, FMT = 9997 )INFO\n         END IF\n         OK = .FALSE.\n      END IF\n      IF( SRNAME.NE.SRNAMT )THEN\n         WRITE( NOUT, FMT = 9998 )SRNAME, SRNAMT\n         OK = .FALSE.\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6, ' INSTEAD',\n     $      ' OF ', I2, ' *******' )\n 9998 FORMAT( ' ******* XERBLA WAS CALLED WITH SRNAME = ', A6, ' INSTE',\n     $      'AD OF ', A6, ' *******' )\n 9997 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6,\n     $      ' *******' )\n*\n*     End of XERBLA\n*\n      END\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/testing/sblat3.f",
    "content": "*> \\brief \\b SBLAT3\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM SBLAT3\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> Test program for the REAL             Level 3 Blas.\n*>\n*> The program must be driven by a short data file. The first 14 records\n*> of the file are read using list-directed input, the last 6 records\n*> are read using the format ( A6, L2 ). An annotated example of a data\n*> file can be obtained by deleting the first 3 characters from the\n*> following 20 lines:\n*> 'sblat3.out'      NAME OF SUMMARY OUTPUT FILE\n*> 6                 UNIT NUMBER OF SUMMARY FILE\n*> 'SBLAT3.SNAP'     NAME OF SNAPSHOT OUTPUT FILE\n*> -1                UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0)\n*> F        LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD.\n*> F        LOGICAL FLAG, T TO STOP ON FAILURES.\n*> T        LOGICAL FLAG, T TO TEST ERROR EXITS.\n*> 16.0     THRESHOLD VALUE OF TEST RATIO\n*> 6                 NUMBER OF VALUES OF N\n*> 0 1 2 3 5 9       VALUES OF N\n*> 3                 NUMBER OF VALUES OF ALPHA\n*> 0.0 1.0 0.7       VALUES OF ALPHA\n*> 3                 NUMBER OF VALUES OF BETA\n*> 0.0 1.0 1.3       VALUES OF BETA\n*> SGEMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> SSYMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> STRMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> STRSM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> SSYRK  T PUT F FOR NO TEST. SAME COLUMNS.\n*> SSYR2K T PUT F FOR NO TEST. SAME COLUMNS.\n*>\n*> Further Details\n*> ===============\n*>\n*> See:\n*>\n*>    Dongarra J. J., Du Croz J. J., Duff I. S. and Hammarling S.\n*>    A Set of Level 3 Basic Linear Algebra Subprograms.\n*>\n*>    Technical Memorandum No.88 (Revision 1), Mathematics and\n*>    Computer Science Division, Argonne National Laboratory, 9700\n*>    South Cass Avenue, Argonne, Illinois 60439, US.\n*>\n*> -- Written on 8-February-1989.\n*>    Jack Dongarra, Argonne National Laboratory.\n*>    Iain Duff, AERE Harwell.\n*>    Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*>    Sven Hammarling, Numerical Algorithms Group Ltd.\n*>\n*>    10-9-00:  Change STATUS='NEW' to 'UNKNOWN' so that the testers\n*>              can be run multiple times without deleting generated\n*>              output files (susan)\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup single_blas_testing\n*\n*  =====================================================================\n      PROGRAM SBLAT3\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER            NIN\n      PARAMETER          ( NIN = 5 )\n      INTEGER            NSUBS\n      PARAMETER          ( NSUBS = 6 )\n      REAL               ZERO, ONE\n      PARAMETER          ( ZERO = 0.0, ONE = 1.0 )\n      INTEGER            NMAX\n      PARAMETER          ( NMAX = 65 )\n      INTEGER            NIDMAX, NALMAX, NBEMAX\n      PARAMETER          ( NIDMAX = 9, NALMAX = 7, NBEMAX = 7 )\n*     .. Local Scalars ..\n      REAL               EPS, ERR, THRESH\n      INTEGER            I, ISNUM, J, N, NALF, NBET, NIDIM, NOUT, NTRA\n      LOGICAL            FATAL, LTESTT, REWI, SAME, SFATAL, TRACE,\n     $                   TSTERR\n      CHARACTER*1        TRANSA, TRANSB\n      CHARACTER*6        SNAMET\n      CHARACTER*32       SNAPS, SUMMRY\n*     .. Local Arrays ..\n      REAL               AA( NMAX*NMAX ), AB( NMAX, 2*NMAX ),\n     $                   ALF( NALMAX ), AS( NMAX*NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBEMAX ),\n     $                   BS( NMAX*NMAX ), C( NMAX, NMAX ),\n     $                   CC( NMAX*NMAX ), CS( NMAX*NMAX ), CT( NMAX ),\n     $                   G( NMAX ), W( 2*NMAX )\n      INTEGER            IDIM( NIDMAX )\n      LOGICAL            LTEST( NSUBS )\n      CHARACTER*6        SNAMES( NSUBS )\n*     .. External Functions ..\n      REAL               SDIFF\n      LOGICAL            LSE\n      EXTERNAL           SDIFF, LSE\n*     .. External Subroutines ..\n      EXTERNAL           SCHK1, SCHK2, SCHK3, SCHK4, SCHK5, SCHKE, SMMCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Data statements ..\n      DATA               SNAMES/'SGEMM ', 'SSYMM ', 'STRMM ', 'STRSM ',\n     $                   'SSYRK ', 'SSYR2K'/\n*     .. Executable Statements ..\n*\n*     Read name and unit number for summary output file and open file.\n*\n      READ( NIN, FMT = * )SUMMRY\n      READ( NIN, FMT = * )NOUT\n      OPEN( NOUT, FILE = SUMMRY )\n      NOUTC = NOUT\n*\n*     Read name and unit number for snapshot output file and open file.\n*\n      READ( NIN, FMT = * )SNAPS\n      READ( NIN, FMT = * )NTRA\n      TRACE = NTRA.GE.0\n      IF( TRACE )THEN\n         OPEN( NTRA, FILE = SNAPS )\n      END IF\n*     Read the flag that directs rewinding of the snapshot file.\n      READ( NIN, FMT = * )REWI\n      REWI = REWI.AND.TRACE\n*     Read the flag that directs stopping on any failure.\n      READ( NIN, FMT = * )SFATAL\n*     Read the flag that indicates whether error exits are to be tested.\n      READ( NIN, FMT = * )TSTERR\n*     Read the threshold value of the test ratio\n      READ( NIN, FMT = * )THRESH\n*\n*     Read and check the parameter values for the tests.\n*\n*     Values of N\n      READ( NIN, FMT = * )NIDIM\n      IF( NIDIM.LT.1.OR.NIDIM.GT.NIDMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'N', NIDMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( IDIM( I ), I = 1, NIDIM )\n      DO 10 I = 1, NIDIM\n         IF( IDIM( I ).LT.0.OR.IDIM( I ).GT.NMAX )THEN\n            WRITE( NOUT, FMT = 9996 )NMAX\n            GO TO 220\n         END IF\n   10 CONTINUE\n*     Values of ALPHA\n      READ( NIN, FMT = * )NALF\n      IF( NALF.LT.1.OR.NALF.GT.NALMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'ALPHA', NALMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( ALF( I ), I = 1, NALF )\n*     Values of BETA\n      READ( NIN, FMT = * )NBET\n      IF( NBET.LT.1.OR.NBET.GT.NBEMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'BETA', NBEMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( BET( I ), I = 1, NBET )\n*\n*     Report values of parameters.\n*\n      WRITE( NOUT, FMT = 9995 )\n      WRITE( NOUT, FMT = 9994 )( IDIM( I ), I = 1, NIDIM )\n      WRITE( NOUT, FMT = 9993 )( ALF( I ), I = 1, NALF )\n      WRITE( NOUT, FMT = 9992 )( BET( I ), I = 1, NBET )\n      IF( .NOT.TSTERR )THEN\n         WRITE( NOUT, FMT = * )\n         WRITE( NOUT, FMT = 9984 )\n      END IF\n      WRITE( NOUT, FMT = * )\n      WRITE( NOUT, FMT = 9999 )THRESH\n      WRITE( NOUT, FMT = * )\n*\n*     Read names of subroutines and flags which indicate\n*     whether they are to be tested.\n*\n      DO 20 I = 1, NSUBS\n         LTEST( I ) = .FALSE.\n   20 CONTINUE\n   30 READ( NIN, FMT = 9988, END = 60 )SNAMET, LTESTT\n      DO 40 I = 1, NSUBS\n         IF( SNAMET.EQ.SNAMES( I ) )\n     $      GO TO 50\n   40 CONTINUE\n      WRITE( NOUT, FMT = 9990 )SNAMET\n      STOP\n   50 LTEST( I ) = LTESTT\n      GO TO 30\n*\n   60 CONTINUE\n      CLOSE ( NIN )\n*\n*     Compute EPS (the machine precision).\n*\n      EPS = EPSILON(ZERO)\n      WRITE( NOUT, FMT = 9998 )EPS\n*\n*     Check the reliability of SMMCH using exact data.\n*\n      N = MIN( 32, NMAX )\n      DO 100 J = 1, N\n         DO 90 I = 1, N\n            AB( I, J ) = MAX( I - J + 1, 0 )\n   90    CONTINUE\n         AB( J, NMAX + 1 ) = J\n         AB( 1, NMAX + J ) = J\n         C( J, 1 ) = ZERO\n  100 CONTINUE\n      DO 110 J = 1, N\n         CC( J ) = J*( ( J + 1 )*J )/2 - ( ( J + 1 )*J*( J - 1 ) )/3\n  110 CONTINUE\n*     CC holds the exact result. On exit from SMMCH CT holds\n*     the result computed by SMMCH.\n      TRANSA = 'N'\n      TRANSB = 'N'\n      CALL SMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LSE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      TRANSB = 'T'\n      CALL SMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LSE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      DO 120 J = 1, N\n         AB( J, NMAX + 1 ) = N - J + 1\n         AB( 1, NMAX + J ) = N - J + 1\n  120 CONTINUE\n      DO 130 J = 1, N\n         CC( N - J + 1 ) = J*( ( J + 1 )*J )/2 -\n     $                     ( ( J + 1 )*J*( J - 1 ) )/3\n  130 CONTINUE\n      TRANSA = 'T'\n      TRANSB = 'N'\n      CALL SMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LSE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      TRANSB = 'T'\n      CALL SMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LSE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.ZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n*\n*     Test each subroutine in turn.\n*\n      DO 200 ISNUM = 1, NSUBS\n         WRITE( NOUT, FMT = * )\n         IF( .NOT.LTEST( ISNUM ) )THEN\n*           Subprogram is not to be tested.\n            WRITE( NOUT, FMT = 9987 )SNAMES( ISNUM )\n         ELSE\n            SRNAMT = SNAMES( ISNUM )\n*           Test error exits.\n            IF( TSTERR )THEN\n               CALL SCHKE( ISNUM, SNAMES( ISNUM ), NOUT )\n               WRITE( NOUT, FMT = * )\n            END IF\n*           Test computations.\n            INFOT = 0\n            OK = .TRUE.\n            FATAL = .FALSE.\n            GO TO ( 140, 150, 160, 160, 170, 180 )ISNUM\n*           Test SGEMM, 01.\n  140       CALL SCHK1( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test SSYMM, 02.\n  150       CALL SCHK2( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test STRMM, 03, STRSM, 04.\n  160       CALL SCHK3( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NMAX, AB,\n     $                  AA, AS, AB( 1, NMAX + 1 ), BB, BS, CT, G, C )\n            GO TO 190\n*           Test SSYRK, 05.\n  170       CALL SCHK4( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test SSYR2K, 06.\n  180       CALL SCHK5( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, BB, BS, C, CC, CS, CT, G, W )\n            GO TO 190\n*\n  190       IF( FATAL.AND.SFATAL )\n     $         GO TO 210\n         END IF\n  200 CONTINUE\n      WRITE( NOUT, FMT = 9986 )\n      GO TO 230\n*\n  210 CONTINUE\n      WRITE( NOUT, FMT = 9985 )\n      GO TO 230\n*\n  220 CONTINUE\n      WRITE( NOUT, FMT = 9991 )\n*\n  230 CONTINUE\n      IF( TRACE )\n     $   CLOSE ( NTRA )\n      CLOSE ( NOUT )\n      STOP\n*\n 9999 FORMAT( ' ROUTINES PASS COMPUTATIONAL TESTS IF TEST RATIO IS LES',\n     $      'S THAN', F8.2 )\n 9998 FORMAT( ' RELATIVE MACHINE PRECISION IS TAKEN TO BE', 1P, E9.1 )\n 9997 FORMAT( ' NUMBER OF VALUES OF ', A, ' IS LESS THAN 1 OR GREATER ',\n     $      'THAN ', I2 )\n 9996 FORMAT( ' VALUE OF N IS LESS THAN 0 OR GREATER THAN ', I2 )\n 9995 FORMAT( ' TESTS OF THE REAL             LEVEL 3 BLAS', //' THE F',\n     $      'OLLOWING PARAMETER VALUES WILL BE USED:' )\n 9994 FORMAT( '   FOR N              ', 9I6 )\n 9993 FORMAT( '   FOR ALPHA          ', 7F6.1 )\n 9992 FORMAT( '   FOR BETA           ', 7F6.1 )\n 9991 FORMAT( ' AMEND DATA FILE OR INCREASE ARRAY SIZES IN PROGRAM',\n     $      /' ******* TESTS ABANDONED *******' )\n 9990 FORMAT( ' SUBPROGRAM NAME ', A6, ' NOT RECOGNIZED', /' ******* T',\n     $      'ESTS ABANDONED *******' )\n 9989 FORMAT( ' ERROR IN SMMCH -  IN-LINE DOT PRODUCTS ARE BEING EVALU',\n     $      'ATED WRONGLY.', /' SMMCH WAS CALLED WITH TRANSA = ', A1,\n     $      ' AND TRANSB = ', A1, /' AND RETURNED SAME = ', L1, ' AND ',\n     $      'ERR = ', F12.3, '.', /' THIS MAY BE DUE TO FAULTS IN THE ',\n     $      'ARITHMETIC OR THE COMPILER.', /' ******* TESTS ABANDONED ',\n     $      '*******' )\n 9988 FORMAT( A6, L2 )\n 9987 FORMAT( 1X, A6, ' WAS NOT TESTED' )\n 9986 FORMAT( /' END OF TESTS' )\n 9985 FORMAT( /' ******* FATAL ERROR - TESTS ABANDONED *******' )\n 9984 FORMAT( ' ERROR-EXITS WILL NOT BE TESTED' )\n*\n*     End of SBLAT3.\n*\n      END\n      SUBROUTINE SCHK1( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests SGEMM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      REAL               ZERO\n      PARAMETER          ( ZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX ), G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      REAL               ALPHA, ALS, BETA, BLS, ERR, ERRMAX\n      INTEGER            I, IA, IB, ICA, ICB, IK, IM, IN, K, KS, LAA,\n     $                   LBB, LCC, LDA, LDAS, LDB, LDBS, LDC, LDCS, M,\n     $                   MA, MB, MS, N, NA, NARGS, NB, NC, NS\n      LOGICAL            NULL, RESET, SAME, TRANA, TRANB\n      CHARACTER*1        TRANAS, TRANBS, TRANSA, TRANSB\n      CHARACTER*3        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SGEMM, SMAKE, SMMCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'NTC'/\n*     .. Executable Statements ..\n*\n      NARGS = 13\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 110 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 100 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDC to 1 more than minimum value if room.\n            LDC = M\n            IF( LDC.LT.NMAX )\n     $         LDC = LDC + 1\n*           Skip tests if not enough room.\n            IF( LDC.GT.NMAX )\n     $         GO TO 100\n            LCC = LDC*N\n            NULL = N.LE.0.OR.M.LE.0\n*\n            DO 90 IK = 1, NIDIM\n               K = IDIM( IK )\n*\n               DO 80 ICA = 1, 3\n                  TRANSA = ICH( ICA: ICA )\n                  TRANA = TRANSA.EQ.'T'.OR.TRANSA.EQ.'C'\n*\n                  IF( TRANA )THEN\n                     MA = K\n                     NA = M\n                  ELSE\n                     MA = M\n                     NA = K\n                  END IF\n*                 Set LDA to 1 more than minimum value if room.\n                  LDA = MA\n                  IF( LDA.LT.NMAX )\n     $               LDA = LDA + 1\n*                 Skip tests if not enough room.\n                  IF( LDA.GT.NMAX )\n     $               GO TO 80\n                  LAA = LDA*NA\n*\n*                 Generate the matrix A.\n*\n                  CALL SMAKE( 'GE', ' ', ' ', MA, NA, A, NMAX, AA, LDA,\n     $                        RESET, ZERO )\n*\n                  DO 70 ICB = 1, 3\n                     TRANSB = ICH( ICB: ICB )\n                     TRANB = TRANSB.EQ.'T'.OR.TRANSB.EQ.'C'\n*\n                     IF( TRANB )THEN\n                        MB = N\n                        NB = K\n                     ELSE\n                        MB = K\n                        NB = N\n                     END IF\n*                    Set LDB to 1 more than minimum value if room.\n                     LDB = MB\n                     IF( LDB.LT.NMAX )\n     $                  LDB = LDB + 1\n*                    Skip tests if not enough room.\n                     IF( LDB.GT.NMAX )\n     $                  GO TO 70\n                     LBB = LDB*NB\n*\n*                    Generate the matrix B.\n*\n                     CALL SMAKE( 'GE', ' ', ' ', MB, NB, B, NMAX, BB,\n     $                           LDB, RESET, ZERO )\n*\n                     DO 60 IA = 1, NALF\n                        ALPHA = ALF( IA )\n*\n                        DO 50 IB = 1, NBET\n                           BETA = BET( IB )\n*\n*                          Generate the matrix C.\n*\n                           CALL SMAKE( 'GE', ' ', ' ', M, N, C, NMAX,\n     $                                 CC, LDC, RESET, ZERO )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           TRANAS = TRANSA\n                           TRANBS = TRANSB\n                           MS = M\n                           NS = N\n                           KS = K\n                           ALS = ALPHA\n                           DO 10 I = 1, LAA\n                              AS( I ) = AA( I )\n   10                      CONTINUE\n                           LDAS = LDA\n                           DO 20 I = 1, LBB\n                              BS( I ) = BB( I )\n   20                      CONTINUE\n                           LDBS = LDB\n                           BLS = BETA\n                           DO 30 I = 1, LCC\n                              CS( I ) = CC( I )\n   30                      CONTINUE\n                           LDCS = LDC\n*\n*                          Call the subroutine.\n*\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                        TRANSA, TRANSB, M, N, K, ALPHA, LDA, LDB,\n     $                        BETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL SGEMM( TRANSA, TRANSB, M, N, K, ALPHA,\n     $                                 AA, LDA, BB, LDB, BETA, CC, LDC )\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9994 )\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = TRANSA.EQ.TRANAS\n                           ISAME( 2 ) = TRANSB.EQ.TRANBS\n                           ISAME( 3 ) = MS.EQ.M\n                           ISAME( 4 ) = NS.EQ.N\n                           ISAME( 5 ) = KS.EQ.K\n                           ISAME( 6 ) = ALS.EQ.ALPHA\n                           ISAME( 7 ) = LSE( AS, AA, LAA )\n                           ISAME( 8 ) = LDAS.EQ.LDA\n                           ISAME( 9 ) = LSE( BS, BB, LBB )\n                           ISAME( 10 ) = LDBS.EQ.LDB\n                           ISAME( 11 ) = BLS.EQ.BETA\n                           IF( NULL )THEN\n                              ISAME( 12 ) = LSE( CS, CC, LCC )\n                           ELSE\n                              ISAME( 12 ) = LSERES( 'GE', ' ', M, N, CS,\n     $                                      CC, LDC )\n                           END IF\n                           ISAME( 13 ) = LDCS.EQ.LDC\n*\n*                          If data was incorrectly changed, report\n*                          and return.\n*\n                           SAME = .TRUE.\n                           DO 40 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   40                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n*\n*                             Check the result.\n*\n                              CALL SMMCH( TRANSA, TRANSB, M, N, K,\n     $                                    ALPHA, A, NMAX, B, NMAX, BETA,\n     $                                    C, NMAX, CT, G, CC, LDC, EPS,\n     $                                    ERR, FATAL, NOUT, .TRUE. )\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 120\n                           END IF\n*\n   50                   CONTINUE\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, TRANSA, TRANSB, M, N, K,\n     $   ALPHA, LDA, LDB, BETA, LDC\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',''', A1, ''',',\n     $      3( I3, ',' ), F4.1, ', A,', I3, ', B,', I3, ',', F4.1, ', ',\n     $      'C,', I3, ').' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK1.\n*\n      END\n      SUBROUTINE SCHK2( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests SSYMM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      REAL               ZERO\n      PARAMETER          ( ZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX ), G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      REAL               ALPHA, ALS, BETA, BLS, ERR, ERRMAX\n      INTEGER            I, IA, IB, ICS, ICU, IM, IN, LAA, LBB, LCC,\n     $                   LDA, LDAS, LDB, LDBS, LDC, LDCS, M, MS, N, NA,\n     $                   NARGS, NC, NS\n      LOGICAL            LEFT, NULL, RESET, SAME\n      CHARACTER*1        SIDE, SIDES, UPLO, UPLOS\n      CHARACTER*2        ICHS, ICHU\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SMAKE, SMMCH, SSYMM\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHS/'LR'/, ICHU/'UL'/\n*     .. Executable Statements ..\n*\n      NARGS = 12\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 100 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 90 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDC to 1 more than minimum value if room.\n            LDC = M\n            IF( LDC.LT.NMAX )\n     $         LDC = LDC + 1\n*           Skip tests if not enough room.\n            IF( LDC.GT.NMAX )\n     $         GO TO 90\n            LCC = LDC*N\n            NULL = N.LE.0.OR.M.LE.0\n*\n*           Set LDB to 1 more than minimum value if room.\n            LDB = M\n            IF( LDB.LT.NMAX )\n     $         LDB = LDB + 1\n*           Skip tests if not enough room.\n            IF( LDB.GT.NMAX )\n     $         GO TO 90\n            LBB = LDB*N\n*\n*           Generate the matrix B.\n*\n            CALL SMAKE( 'GE', ' ', ' ', M, N, B, NMAX, BB, LDB, RESET,\n     $                  ZERO )\n*\n            DO 80 ICS = 1, 2\n               SIDE = ICHS( ICS: ICS )\n               LEFT = SIDE.EQ.'L'\n*\n               IF( LEFT )THEN\n                  NA = M\n               ELSE\n                  NA = N\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = NA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 80\n               LAA = LDA*NA\n*\n               DO 70 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n*\n*                 Generate the symmetric matrix A.\n*\n                  CALL SMAKE( 'SY', UPLO, ' ', NA, NA, A, NMAX, AA, LDA,\n     $                        RESET, ZERO )\n*\n                  DO 60 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n                     DO 50 IB = 1, NBET\n                        BETA = BET( IB )\n*\n*                       Generate the matrix C.\n*\n                        CALL SMAKE( 'GE', ' ', ' ', M, N, C, NMAX, CC,\n     $                              LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the\n*                       subroutine.\n*\n                        SIDES = SIDE\n                        UPLOS = UPLO\n                        MS = M\n                        NS = N\n                        ALS = ALPHA\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        DO 20 I = 1, LBB\n                           BS( I ) = BB( I )\n   20                   CONTINUE\n                        LDBS = LDB\n                        BLS = BETA\n                        DO 30 I = 1, LCC\n                           CS( I ) = CC( I )\n   30                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9995 )NC, SNAME, SIDE,\n     $                     UPLO, M, N, ALPHA, LDA, LDB, BETA, LDC\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL SSYMM( SIDE, UPLO, M, N, ALPHA, AA, LDA,\n     $                              BB, LDB, BETA, CC, LDC )\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9994 )\n                           FATAL = .TRUE.\n                           GO TO 110\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = SIDES.EQ.SIDE\n                        ISAME( 2 ) = UPLOS.EQ.UPLO\n                        ISAME( 3 ) = MS.EQ.M\n                        ISAME( 4 ) = NS.EQ.N\n                        ISAME( 5 ) = ALS.EQ.ALPHA\n                        ISAME( 6 ) = LSE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        ISAME( 8 ) = LSE( BS, BB, LBB )\n                        ISAME( 9 ) = LDBS.EQ.LDB\n                        ISAME( 10 ) = BLS.EQ.BETA\n                        IF( NULL )THEN\n                           ISAME( 11 ) = LSE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 11 ) = LSERES( 'GE', ' ', M, N, CS,\n     $                                   CC, LDC )\n                        END IF\n                        ISAME( 12 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 110\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result.\n*\n                           IF( LEFT )THEN\n                              CALL SMMCH( 'N', 'N', M, N, M, ALPHA, A,\n     $                                    NMAX, B, NMAX, BETA, C, NMAX,\n     $                                    CT, G, CC, LDC, EPS, ERR,\n     $                                    FATAL, NOUT, .TRUE. )\n                           ELSE\n                              CALL SMMCH( 'N', 'N', M, N, N, ALPHA, B,\n     $                                    NMAX, A, NMAX, BETA, C, NMAX,\n     $                                    CT, G, CC, LDC, EPS, ERR,\n     $                                    FATAL, NOUT, .TRUE. )\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and\n*                          return.\n                           IF( FATAL )\n     $                        GO TO 110\n                        END IF\n*\n   50                CONTINUE\n*\n   60             CONTINUE\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 120\n*\n  110 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, SIDE, UPLO, M, N, ALPHA, LDA,\n     $   LDB, BETA, LDC\n*\n  120 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      F4.1, ', A,', I3, ', B,', I3, ',', F4.1, ', C,', I3, ')   ',\n     $      ' .' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK2.\n*\n      END\n      SUBROUTINE SCHK3( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NMAX, A, AA, AS,\n     $                  B, BB, BS, CT, G, C )\n*\n*  Tests STRMM and STRSM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      REAL               ZERO, ONE\n      PARAMETER          ( ZERO = 0.0, ONE = 1.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            NALF, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CT( NMAX ), G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      REAL               ALPHA, ALS, ERR, ERRMAX\n      INTEGER            I, IA, ICD, ICS, ICT, ICU, IM, IN, J, LAA, LBB,\n     $                   LDA, LDAS, LDB, LDBS, M, MS, N, NA, NARGS, NC,\n     $                   NS\n      LOGICAL            LEFT, NULL, RESET, SAME\n      CHARACTER*1        DIAG, DIAGS, SIDE, SIDES, TRANAS, TRANSA, UPLO,\n     $                   UPLOS\n      CHARACTER*2        ICHD, ICHS, ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SMAKE, SMMCH, STRMM, STRSM\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHU/'UL'/, ICHT/'NTC'/, ICHD/'UN'/, ICHS/'LR'/\n*     .. Executable Statements ..\n*\n      NARGS = 11\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*     Set up zero matrix for SMMCH.\n      DO 20 J = 1, NMAX\n         DO 10 I = 1, NMAX\n            C( I, J ) = ZERO\n   10    CONTINUE\n   20 CONTINUE\n*\n      DO 140 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 130 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDB to 1 more than minimum value if room.\n            LDB = M\n            IF( LDB.LT.NMAX )\n     $         LDB = LDB + 1\n*           Skip tests if not enough room.\n            IF( LDB.GT.NMAX )\n     $         GO TO 130\n            LBB = LDB*N\n            NULL = M.LE.0.OR.N.LE.0\n*\n            DO 120 ICS = 1, 2\n               SIDE = ICHS( ICS: ICS )\n               LEFT = SIDE.EQ.'L'\n               IF( LEFT )THEN\n                  NA = M\n               ELSE\n                  NA = N\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = NA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 130\n               LAA = LDA*NA\n*\n               DO 110 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n*\n                  DO 100 ICT = 1, 3\n                     TRANSA = ICHT( ICT: ICT )\n*\n                     DO 90 ICD = 1, 2\n                        DIAG = ICHD( ICD: ICD )\n*\n                        DO 80 IA = 1, NALF\n                           ALPHA = ALF( IA )\n*\n*                          Generate the matrix A.\n*\n                           CALL SMAKE( 'TR', UPLO, DIAG, NA, NA, A,\n     $                                 NMAX, AA, LDA, RESET, ZERO )\n*\n*                          Generate the matrix B.\n*\n                           CALL SMAKE( 'GE', ' ', ' ', M, N, B, NMAX,\n     $                                 BB, LDB, RESET, ZERO )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           SIDES = SIDE\n                           UPLOS = UPLO\n                           TRANAS = TRANSA\n                           DIAGS = DIAG\n                           MS = M\n                           NS = N\n                           ALS = ALPHA\n                           DO 30 I = 1, LAA\n                              AS( I ) = AA( I )\n   30                      CONTINUE\n                           LDAS = LDA\n                           DO 40 I = 1, LBB\n                              BS( I ) = BB( I )\n   40                      CONTINUE\n                           LDBS = LDB\n*\n*                          Call the subroutine.\n*\n                           IF( SNAME( 4: 5 ).EQ.'MM' )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           SIDE, UPLO, TRANSA, DIAG, M, N, ALPHA,\n     $                           LDA, LDB\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL STRMM( SIDE, UPLO, TRANSA, DIAG, M,\n     $                                    N, ALPHA, AA, LDA, BB, LDB )\n                           ELSE IF( SNAME( 4: 5 ).EQ.'SM' )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           SIDE, UPLO, TRANSA, DIAG, M, N, ALPHA,\n     $                           LDA, LDB\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL STRSM( SIDE, UPLO, TRANSA, DIAG, M,\n     $                                    N, ALPHA, AA, LDA, BB, LDB )\n                           END IF\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9994 )\n                              FATAL = .TRUE.\n                              GO TO 150\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = SIDES.EQ.SIDE\n                           ISAME( 2 ) = UPLOS.EQ.UPLO\n                           ISAME( 3 ) = TRANAS.EQ.TRANSA\n                           ISAME( 4 ) = DIAGS.EQ.DIAG\n                           ISAME( 5 ) = MS.EQ.M\n                           ISAME( 6 ) = NS.EQ.N\n                           ISAME( 7 ) = ALS.EQ.ALPHA\n                           ISAME( 8 ) = LSE( AS, AA, LAA )\n                           ISAME( 9 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 10 ) = LSE( BS, BB, LBB )\n                           ELSE\n                              ISAME( 10 ) = LSERES( 'GE', ' ', M, N, BS,\n     $                                      BB, LDB )\n                           END IF\n                           ISAME( 11 ) = LDBS.EQ.LDB\n*\n*                          If data was incorrectly changed, report and\n*                          return.\n*\n                           SAME = .TRUE.\n                           DO 50 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   50                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 150\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n                              IF( SNAME( 4: 5 ).EQ.'MM' )THEN\n*\n*                                Check the result.\n*\n                                 IF( LEFT )THEN\n                                    CALL SMMCH( TRANSA, 'N', M, N, M,\n     $                                          ALPHA, A, NMAX, B, NMAX,\n     $                                          ZERO, C, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .TRUE. )\n                                 ELSE\n                                    CALL SMMCH( 'N', TRANSA, M, N, N,\n     $                                          ALPHA, B, NMAX, A, NMAX,\n     $                                          ZERO, C, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .TRUE. )\n                                 END IF\n                              ELSE IF( SNAME( 4: 5 ).EQ.'SM' )THEN\n*\n*                                Compute approximation to original\n*                                matrix.\n*\n                                 DO 70 J = 1, N\n                                    DO 60 I = 1, M\n                                       C( I, J ) = BB( I + ( J - 1 )*\n     $                                             LDB )\n                                       BB( I + ( J - 1 )*LDB ) = ALPHA*\n     $                                    B( I, J )\n   60                               CONTINUE\n   70                            CONTINUE\n*\n                                 IF( LEFT )THEN\n                                    CALL SMMCH( TRANSA, 'N', M, N, M,\n     $                                          ONE, A, NMAX, C, NMAX,\n     $                                          ZERO, B, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .FALSE. )\n                                 ELSE\n                                    CALL SMMCH( 'N', TRANSA, M, N, N,\n     $                                          ONE, C, NMAX, A, NMAX,\n     $                                          ZERO, B, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .FALSE. )\n                                 END IF\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 150\n                           END IF\n*\n   80                   CONTINUE\n*\n   90                CONTINUE\n*\n  100             CONTINUE\n*\n  110          CONTINUE\n*\n  120       CONTINUE\n*\n  130    CONTINUE\n*\n  140 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 160\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, SIDE, UPLO, TRANSA, DIAG, M,\n     $   N, ALPHA, LDA, LDB\n*\n  160 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 4( '''', A1, ''',' ), 2( I3, ',' ),\n     $      F4.1, ', A,', I3, ', B,', I3, ')        .' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK3.\n*\n      END\n      SUBROUTINE SCHK4( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests SSYRK.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      REAL               ZERO\n      PARAMETER          ( ZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX ), G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      REAL               ALPHA, ALS, BETA, BETS, ERR, ERRMAX\n      INTEGER            I, IA, IB, ICT, ICU, IK, IN, J, JC, JJ, K, KS,\n     $                   LAA, LCC, LDA, LDAS, LDC, LDCS, LJ, MA, N, NA,\n     $                   NARGS, NC, NS\n      LOGICAL            NULL, RESET, SAME, TRAN, UPPER\n      CHARACTER*1        TRANS, TRANSS, UPLO, UPLOS\n      CHARACTER*2        ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SMAKE, SMMCH, SSYRK\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHT/'NTC'/, ICHU/'UL'/\n*     .. Executable Statements ..\n*\n      NARGS = 10\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 100 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDC to 1 more than minimum value if room.\n         LDC = N\n         IF( LDC.LT.NMAX )\n     $      LDC = LDC + 1\n*        Skip tests if not enough room.\n         IF( LDC.GT.NMAX )\n     $      GO TO 100\n         LCC = LDC*N\n         NULL = N.LE.0\n*\n         DO 90 IK = 1, NIDIM\n            K = IDIM( IK )\n*\n            DO 80 ICT = 1, 3\n               TRANS = ICHT( ICT: ICT )\n               TRAN = TRANS.EQ.'T'.OR.TRANS.EQ.'C'\n               IF( TRAN )THEN\n                  MA = K\n                  NA = N\n               ELSE\n                  MA = N\n                  NA = K\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = MA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 80\n               LAA = LDA*NA\n*\n*              Generate the matrix A.\n*\n               CALL SMAKE( 'GE', ' ', ' ', MA, NA, A, NMAX, AA, LDA,\n     $                     RESET, ZERO )\n*\n               DO 70 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n                  UPPER = UPLO.EQ.'U'\n*\n                  DO 60 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n                     DO 50 IB = 1, NBET\n                        BETA = BET( IB )\n*\n*                       Generate the matrix C.\n*\n                        CALL SMAKE( 'SY', UPLO, ' ', N, N, C, NMAX, CC,\n     $                              LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        NS = N\n                        KS = K\n                        ALS = ALPHA\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        BETS = BETA\n                        DO 20 I = 1, LCC\n                           CS( I ) = CC( I )\n   20                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO,\n     $                     TRANS, N, K, ALPHA, LDA, BETA, LDC\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL SSYRK( UPLO, TRANS, N, K, ALPHA, AA, LDA,\n     $                              BETA, CC, LDC )\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9993 )\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLOS.EQ.UPLO\n                        ISAME( 2 ) = TRANSS.EQ.TRANS\n                        ISAME( 3 ) = NS.EQ.N\n                        ISAME( 4 ) = KS.EQ.K\n                        ISAME( 5 ) = ALS.EQ.ALPHA\n                        ISAME( 6 ) = LSE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        ISAME( 8 ) = BETS.EQ.BETA\n                        IF( NULL )THEN\n                           ISAME( 9 ) = LSE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 9 ) = LSERES( 'SY', UPLO, N, N, CS,\n     $                                  CC, LDC )\n                        END IF\n                        ISAME( 10 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 30 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   30                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result column by column.\n*\n                           JC = 1\n                           DO 40 J = 1, N\n                              IF( UPPER )THEN\n                                 JJ = 1\n                                 LJ = J\n                              ELSE\n                                 JJ = J\n                                 LJ = N - J + 1\n                              END IF\n                              IF( TRAN )THEN\n                                 CALL SMMCH( 'T', 'N', LJ, 1, K, ALPHA,\n     $                                       A( 1, JJ ), NMAX,\n     $                                       A( 1, J ), NMAX, BETA,\n     $                                       C( JJ, J ), NMAX, CT, G,\n     $                                       CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              ELSE\n                                 CALL SMMCH( 'N', 'T', LJ, 1, K, ALPHA,\n     $                                       A( JJ, 1 ), NMAX,\n     $                                       A( J, 1 ), NMAX, BETA,\n     $                                       C( JJ, J ), NMAX, CT, G,\n     $                                       CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              END IF\n                              IF( UPPER )THEN\n                                 JC = JC + LDC\n                              ELSE\n                                 JC = JC + LDC + 1\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 110\n   40                      CONTINUE\n                        END IF\n*\n   50                CONTINUE\n*\n   60             CONTINUE\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  110 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9995 )J\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, N, K, ALPHA,\n     $   LDA, BETA, LDC\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      F4.1, ', A,', I3, ',', F4.1, ', C,', I3, ')           .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK4.\n*\n      END\n      SUBROUTINE SCHK5( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  AB, AA, AS, BB, BS, C, CC, CS, CT, G, W )\n*\n*  Tests SSYR2K.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      REAL               ZERO\n      PARAMETER          ( ZERO = 0.0 )\n*     .. Scalar Arguments ..\n      REAL               EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      REAL               AA( NMAX*NMAX ), AB( 2*NMAX*NMAX ),\n     $                   ALF( NALF ), AS( NMAX*NMAX ), BB( NMAX*NMAX ),\n     $                   BET( NBET ), BS( NMAX*NMAX ), C( NMAX, NMAX ),\n     $                   CC( NMAX*NMAX ), CS( NMAX*NMAX ), CT( NMAX ),\n     $                   G( NMAX ), W( 2*NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      REAL               ALPHA, ALS, BETA, BETS, ERR, ERRMAX\n      INTEGER            I, IA, IB, ICT, ICU, IK, IN, J, JC, JJ, JJAB,\n     $                   K, KS, LAA, LBB, LCC, LDA, LDAS, LDB, LDBS,\n     $                   LDC, LDCS, LJ, MA, N, NA, NARGS, NC, NS\n      LOGICAL            NULL, RESET, SAME, TRAN, UPPER\n      CHARACTER*1        TRANS, TRANSS, UPLO, UPLOS\n      CHARACTER*2        ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LSE, LSERES\n      EXTERNAL           LSE, LSERES\n*     .. External Subroutines ..\n      EXTERNAL           SMAKE, SMMCH, SSYR2K\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHT/'NTC'/, ICHU/'UL'/\n*     .. Executable Statements ..\n*\n      NARGS = 12\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = ZERO\n*\n      DO 130 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDC to 1 more than minimum value if room.\n         LDC = N\n         IF( LDC.LT.NMAX )\n     $      LDC = LDC + 1\n*        Skip tests if not enough room.\n         IF( LDC.GT.NMAX )\n     $      GO TO 130\n         LCC = LDC*N\n         NULL = N.LE.0\n*\n         DO 120 IK = 1, NIDIM\n            K = IDIM( IK )\n*\n            DO 110 ICT = 1, 3\n               TRANS = ICHT( ICT: ICT )\n               TRAN = TRANS.EQ.'T'.OR.TRANS.EQ.'C'\n               IF( TRAN )THEN\n                  MA = K\n                  NA = N\n               ELSE\n                  MA = N\n                  NA = K\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = MA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 110\n               LAA = LDA*NA\n*\n*              Generate the matrix A.\n*\n               IF( TRAN )THEN\n                  CALL SMAKE( 'GE', ' ', ' ', MA, NA, AB, 2*NMAX, AA,\n     $                        LDA, RESET, ZERO )\n               ELSE\n                  CALL SMAKE( 'GE', ' ', ' ', MA, NA, AB, NMAX, AA, LDA,\n     $                        RESET, ZERO )\n               END IF\n*\n*              Generate the matrix B.\n*\n               LDB = LDA\n               LBB = LAA\n               IF( TRAN )THEN\n                  CALL SMAKE( 'GE', ' ', ' ', MA, NA, AB( K + 1 ),\n     $                        2*NMAX, BB, LDB, RESET, ZERO )\n               ELSE\n                  CALL SMAKE( 'GE', ' ', ' ', MA, NA, AB( K*NMAX + 1 ),\n     $                        NMAX, BB, LDB, RESET, ZERO )\n               END IF\n*\n               DO 100 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n                  UPPER = UPLO.EQ.'U'\n*\n                  DO 90 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n                     DO 80 IB = 1, NBET\n                        BETA = BET( IB )\n*\n*                       Generate the matrix C.\n*\n                        CALL SMAKE( 'SY', UPLO, ' ', N, N, C, NMAX, CC,\n     $                              LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        NS = N\n                        KS = K\n                        ALS = ALPHA\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        DO 20 I = 1, LBB\n                           BS( I ) = BB( I )\n   20                   CONTINUE\n                        LDBS = LDB\n                        BETS = BETA\n                        DO 30 I = 1, LCC\n                           CS( I ) = CC( I )\n   30                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO,\n     $                     TRANS, N, K, ALPHA, LDA, LDB, BETA, LDC\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL SSYR2K( UPLO, TRANS, N, K, ALPHA, AA, LDA,\n     $                               BB, LDB, BETA, CC, LDC )\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9993 )\n                           FATAL = .TRUE.\n                           GO TO 150\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLOS.EQ.UPLO\n                        ISAME( 2 ) = TRANSS.EQ.TRANS\n                        ISAME( 3 ) = NS.EQ.N\n                        ISAME( 4 ) = KS.EQ.K\n                        ISAME( 5 ) = ALS.EQ.ALPHA\n                        ISAME( 6 ) = LSE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        ISAME( 8 ) = LSE( BS, BB, LBB )\n                        ISAME( 9 ) = LDBS.EQ.LDB\n                        ISAME( 10 ) = BETS.EQ.BETA\n                        IF( NULL )THEN\n                           ISAME( 11 ) = LSE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 11 ) = LSERES( 'SY', UPLO, N, N, CS,\n     $                                   CC, LDC )\n                        END IF\n                        ISAME( 12 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 150\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result column by column.\n*\n                           JJAB = 1\n                           JC = 1\n                           DO 70 J = 1, N\n                              IF( UPPER )THEN\n                                 JJ = 1\n                                 LJ = J\n                              ELSE\n                                 JJ = J\n                                 LJ = N - J + 1\n                              END IF\n                              IF( TRAN )THEN\n                                 DO 50 I = 1, K\n                                    W( I ) = AB( ( J - 1 )*2*NMAX + K +\n     $                                       I )\n                                    W( K + I ) = AB( ( J - 1 )*2*NMAX +\n     $                                           I )\n   50                            CONTINUE\n                                 CALL SMMCH( 'T', 'N', LJ, 1, 2*K,\n     $                                       ALPHA, AB( JJAB ), 2*NMAX,\n     $                                       W, 2*NMAX, BETA,\n     $                                       C( JJ, J ), NMAX, CT, G,\n     $                                       CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              ELSE\n                                 DO 60 I = 1, K\n                                    W( I ) = AB( ( K + I - 1 )*NMAX +\n     $                                       J )\n                                    W( K + I ) = AB( ( I - 1 )*NMAX +\n     $                                           J )\n   60                            CONTINUE\n                                 CALL SMMCH( 'N', 'N', LJ, 1, 2*K,\n     $                                       ALPHA, AB( JJ ), NMAX, W,\n     $                                       2*NMAX, BETA, C( JJ, J ),\n     $                                       NMAX, CT, G, CC( JC ), LDC,\n     $                                       EPS, ERR, FATAL, NOUT,\n     $                                       .TRUE. )\n                              END IF\n                              IF( UPPER )THEN\n                                 JC = JC + LDC\n                              ELSE\n                                 JC = JC + LDC + 1\n                                 IF( TRAN )\n     $                              JJAB = JJAB + 2*NMAX\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 140\n   70                      CONTINUE\n                        END IF\n*\n   80                CONTINUE\n*\n   90             CONTINUE\n*\n  100          CONTINUE\n*\n  110       CONTINUE\n*\n  120    CONTINUE\n*\n  130 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 160\n*\n  140 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9995 )J\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, N, K, ALPHA,\n     $   LDA, LDB, BETA, LDC\n*\n  160 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      F4.1, ', A,', I3, ', B,', I3, ',', F4.1, ', C,', I3, ')   ',\n     $      ' .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of SCHK5.\n*\n      END\n      SUBROUTINE SCHKE( ISNUM, SRNAMT, NOUT )\n*\n*  Tests the error exits from the Level 3 Blas.\n*  Requires a special version of the error-handling routine XERBLA.\n*  A, B and C should not need to be defined.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*  3-19-92:  Initialize ALPHA and BETA  (eca)\n*  3-19-92:  Fix argument 12 in calls to SSYMM with INFOT = 9  (eca)\n*\n*     .. Scalar Arguments ..\n      INTEGER            ISNUM, NOUT\n      CHARACTER*6        SRNAMT\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Parameters ..\n      REAL               ONE, TWO\n      PARAMETER          ( ONE = 1.0E0, TWO = 2.0E0 )\n*     .. Local Scalars ..\n      REAL               ALPHA, BETA\n*     .. Local Arrays ..\n      REAL               A( 2, 1 ), B( 2, 1 ), C( 2, 1 )\n*     .. External Subroutines ..\n      EXTERNAL           CHKXER, SGEMM, SSYMM, SSYR2K, SSYRK, STRMM,\n     $                   STRSM\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n*     OK is set to .FALSE. by the special version of XERBLA or by CHKXER\n*     if anything is wrong.\n      OK = .TRUE.\n*     LERR is set to .TRUE. by the special version of XERBLA each time\n*     it is called, and is then tested and re-set by CHKXER.\n      LERR = .FALSE.\n*\n*     Initialize ALPHA and BETA.\n*\n      ALPHA = ONE\n      BETA = TWO\n*\n      GO TO ( 10, 20, 30, 40, 50, 60 )ISNUM\n   10 INFOT = 1\n      CALL SGEMM( '/', 'N', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 1\n      CALL SGEMM( '/', 'T', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SGEMM( 'N', '/', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SGEMM( 'T', '/', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SGEMM( 'N', 'N', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SGEMM( 'N', 'T', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SGEMM( 'T', 'N', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SGEMM( 'T', 'T', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SGEMM( 'N', 'N', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SGEMM( 'N', 'T', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SGEMM( 'T', 'N', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SGEMM( 'T', 'T', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SGEMM( 'N', 'N', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SGEMM( 'N', 'T', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SGEMM( 'T', 'N', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL SGEMM( 'T', 'T', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL SGEMM( 'N', 'N', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL SGEMM( 'N', 'T', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL SGEMM( 'T', 'N', 0, 0, 2, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL SGEMM( 'T', 'T', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL SGEMM( 'N', 'N', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL SGEMM( 'T', 'N', 0, 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL SGEMM( 'N', 'T', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL SGEMM( 'T', 'T', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL SGEMM( 'N', 'N', 2, 0, 0, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL SGEMM( 'N', 'T', 2, 0, 0, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL SGEMM( 'T', 'N', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL SGEMM( 'T', 'T', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 70\n   20 INFOT = 1\n      CALL SSYMM( '/', 'U', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SSYMM( 'L', '/', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYMM( 'L', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYMM( 'R', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYMM( 'L', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYMM( 'R', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYMM( 'L', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYMM( 'R', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYMM( 'L', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYMM( 'R', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYMM( 'L', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYMM( 'R', 'U', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYMM( 'L', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYMM( 'R', 'L', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL SSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL SSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL SSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL SSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 70\n   30 INFOT = 1\n      CALL STRMM( '/', 'U', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL STRMM( 'L', '/', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL STRMM( 'L', 'U', '/', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL STRMM( 'L', 'U', 'N', '/', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRMM( 'L', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRMM( 'L', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRMM( 'R', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRMM( 'R', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRMM( 'L', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRMM( 'L', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRMM( 'R', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRMM( 'R', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRMM( 'L', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRMM( 'L', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRMM( 'R', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRMM( 'R', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRMM( 'L', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRMM( 'L', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRMM( 'R', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRMM( 'R', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRMM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRMM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRMM( 'R', 'U', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRMM( 'R', 'U', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRMM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRMM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRMM( 'R', 'L', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRMM( 'R', 'L', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRMM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRMM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRMM( 'R', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRMM( 'R', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRMM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRMM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRMM( 'R', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRMM( 'R', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 70\n   40 INFOT = 1\n      CALL STRSM( '/', 'U', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL STRSM( 'L', '/', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL STRSM( 'L', 'U', '/', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL STRSM( 'L', 'U', 'N', '/', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRSM( 'L', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRSM( 'L', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRSM( 'R', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRSM( 'R', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRSM( 'L', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRSM( 'L', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRSM( 'R', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL STRSM( 'R', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRSM( 'L', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRSM( 'L', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRSM( 'R', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRSM( 'R', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRSM( 'L', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRSM( 'L', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRSM( 'R', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL STRSM( 'R', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRSM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRSM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRSM( 'R', 'U', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRSM( 'R', 'U', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRSM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRSM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRSM( 'R', 'L', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL STRSM( 'R', 'L', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRSM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRSM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRSM( 'R', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRSM( 'R', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRSM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRSM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRSM( 'R', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL STRSM( 'R', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 70\n   50 INFOT = 1\n      CALL SSYRK( '/', 'N', 0, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SSYRK( 'U', '/', 0, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYRK( 'U', 'N', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYRK( 'U', 'T', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYRK( 'L', 'N', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYRK( 'L', 'T', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYRK( 'U', 'N', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYRK( 'U', 'T', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYRK( 'L', 'N', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYRK( 'L', 'T', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYRK( 'U', 'N', 2, 0, ALPHA, A, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYRK( 'U', 'T', 0, 2, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYRK( 'L', 'N', 2, 0, ALPHA, A, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYRK( 'L', 'T', 0, 2, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL SSYRK( 'U', 'N', 2, 0, ALPHA, A, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL SSYRK( 'U', 'T', 2, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL SSYRK( 'L', 'N', 2, 0, ALPHA, A, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL SSYRK( 'L', 'T', 2, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 70\n   60 INFOT = 1\n      CALL SSYR2K( '/', 'N', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL SSYR2K( 'U', '/', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYR2K( 'U', 'N', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYR2K( 'U', 'T', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYR2K( 'L', 'N', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL SSYR2K( 'L', 'T', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYR2K( 'U', 'N', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYR2K( 'U', 'T', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYR2K( 'L', 'N', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL SSYR2K( 'L', 'T', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYR2K( 'U', 'N', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYR2K( 'U', 'T', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYR2K( 'L', 'N', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL SSYR2K( 'L', 'T', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SSYR2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SSYR2K( 'U', 'T', 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SSYR2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL SSYR2K( 'L', 'T', 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL SSYR2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL SSYR2K( 'U', 'T', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL SSYR2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL SSYR2K( 'L', 'T', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n   70 IF( OK )THEN\n         WRITE( NOUT, FMT = 9999 )SRNAMT\n      ELSE\n         WRITE( NOUT, FMT = 9998 )SRNAMT\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE TESTS OF ERROR-EXITS' )\n 9998 FORMAT( ' ******* ', A6, ' FAILED THE TESTS OF ERROR-EXITS *****',\n     $      '**' )\n*\n*     End of SCHKE.\n*\n      END\n      SUBROUTINE SMAKE( TYPE, UPLO, DIAG, M, N, A, NMAX, AA, LDA, RESET,\n     $                  TRANSL )\n*\n*  Generates values for an M by N matrix A.\n*  Stores the values in the array AA in the data structure required\n*  by the routine, with unwanted elements set to rogue value.\n*\n*  TYPE is 'GE', 'SY' or 'TR'.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      REAL               ZERO, ONE\n      PARAMETER          ( ZERO = 0.0, ONE = 1.0 )\n      REAL               ROGUE\n      PARAMETER          ( ROGUE = -1.0E10 )\n*     .. Scalar Arguments ..\n      REAL               TRANSL\n      INTEGER            LDA, M, N, NMAX\n      LOGICAL            RESET\n      CHARACTER*1        DIAG, UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      REAL               A( NMAX, * ), AA( * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J\n      LOGICAL            GEN, LOWER, SYM, TRI, UNIT, UPPER\n*     .. External Functions ..\n      REAL               SBEG\n      EXTERNAL           SBEG\n*     .. Executable Statements ..\n      GEN = TYPE.EQ.'GE'\n      SYM = TYPE.EQ.'SY'\n      TRI = TYPE.EQ.'TR'\n      UPPER = ( SYM.OR.TRI ).AND.UPLO.EQ.'U'\n      LOWER = ( SYM.OR.TRI ).AND.UPLO.EQ.'L'\n      UNIT = TRI.AND.DIAG.EQ.'U'\n*\n*     Generate data in array A.\n*\n      DO 20 J = 1, N\n         DO 10 I = 1, M\n            IF( GEN.OR.( UPPER.AND.I.LE.J ).OR.( LOWER.AND.I.GE.J ) )\n     $          THEN\n               A( I, J ) = SBEG( RESET ) + TRANSL\n               IF( I.NE.J )THEN\n*                 Set some elements to zero\n                  IF( N.GT.3.AND.J.EQ.N/2 )\n     $               A( I, J ) = ZERO\n                  IF( SYM )THEN\n                     A( J, I ) = A( I, J )\n                  ELSE IF( TRI )THEN\n                     A( J, I ) = ZERO\n                  END IF\n               END IF\n            END IF\n   10    CONTINUE\n         IF( TRI )\n     $      A( J, J ) = A( J, J ) + ONE\n         IF( UNIT )\n     $      A( J, J ) = ONE\n   20 CONTINUE\n*\n*     Store elements in array AS in data structure required by routine.\n*\n      IF( TYPE.EQ.'GE' )THEN\n         DO 50 J = 1, N\n            DO 30 I = 1, M\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   30       CONTINUE\n            DO 40 I = M + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   40       CONTINUE\n   50    CONTINUE\n      ELSE IF( TYPE.EQ.'SY'.OR.TYPE.EQ.'TR' )THEN\n         DO 90 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IF( UNIT )THEN\n                  IEND = J - 1\n               ELSE\n                  IEND = J\n               END IF\n            ELSE\n               IF( UNIT )THEN\n                  IBEG = J + 1\n               ELSE\n                  IBEG = J\n               END IF\n               IEND = N\n            END IF\n            DO 60 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   60       CONTINUE\n            DO 70 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   70       CONTINUE\n            DO 80 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   80       CONTINUE\n   90    CONTINUE\n      END IF\n      RETURN\n*\n*     End of SMAKE.\n*\n      END\n      SUBROUTINE SMMCH( TRANSA, TRANSB, M, N, KK, ALPHA, A, LDA, B, LDB,\n     $                  BETA, C, LDC, CT, G, CC, LDCC, EPS, ERR, FATAL,\n     $                  NOUT, MV )\n*\n*  Checks the results of the computational tests.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      REAL               ZERO, ONE\n      PARAMETER          ( ZERO = 0.0, ONE = 1.0 )\n*     .. Scalar Arguments ..\n      REAL               ALPHA, BETA, EPS, ERR\n      INTEGER            KK, LDA, LDB, LDC, LDCC, M, N, NOUT\n      LOGICAL            FATAL, MV\n      CHARACTER*1        TRANSA, TRANSB\n*     .. Array Arguments ..\n      REAL               A( LDA, * ), B( LDB, * ), C( LDC, * ),\n     $                   CC( LDCC, * ), CT( * ), G( * )\n*     .. Local Scalars ..\n      REAL               ERRI\n      INTEGER            I, J, K\n      LOGICAL            TRANA, TRANB\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, SQRT\n*     .. Executable Statements ..\n      TRANA = TRANSA.EQ.'T'.OR.TRANSA.EQ.'C'\n      TRANB = TRANSB.EQ.'T'.OR.TRANSB.EQ.'C'\n*\n*     Compute expected result, one column at a time, in CT using data\n*     in A, B and C.\n*     Compute gauges in G.\n*\n      DO 120 J = 1, N\n*\n         DO 10 I = 1, M\n            CT( I ) = ZERO\n            G( I ) = ZERO\n   10    CONTINUE\n         IF( .NOT.TRANA.AND..NOT.TRANB )THEN\n            DO 30 K = 1, KK\n               DO 20 I = 1, M\n                  CT( I ) = CT( I ) + A( I, K )*B( K, J )\n                  G( I ) = G( I ) + ABS( A( I, K ) )*ABS( B( K, J ) )\n   20          CONTINUE\n   30       CONTINUE\n         ELSE IF( TRANA.AND..NOT.TRANB )THEN\n            DO 50 K = 1, KK\n               DO 40 I = 1, M\n                  CT( I ) = CT( I ) + A( K, I )*B( K, J )\n                  G( I ) = G( I ) + ABS( A( K, I ) )*ABS( B( K, J ) )\n   40          CONTINUE\n   50       CONTINUE\n         ELSE IF( .NOT.TRANA.AND.TRANB )THEN\n            DO 70 K = 1, KK\n               DO 60 I = 1, M\n                  CT( I ) = CT( I ) + A( I, K )*B( J, K )\n                  G( I ) = G( I ) + ABS( A( I, K ) )*ABS( B( J, K ) )\n   60          CONTINUE\n   70       CONTINUE\n         ELSE IF( TRANA.AND.TRANB )THEN\n            DO 90 K = 1, KK\n               DO 80 I = 1, M\n                  CT( I ) = CT( I ) + A( K, I )*B( J, K )\n                  G( I ) = G( I ) + ABS( A( K, I ) )*ABS( B( J, K ) )\n   80          CONTINUE\n   90       CONTINUE\n         END IF\n         DO 100 I = 1, M\n            CT( I ) = ALPHA*CT( I ) + BETA*C( I, J )\n            G( I ) = ABS( ALPHA )*G( I ) + ABS( BETA )*ABS( C( I, J ) )\n  100    CONTINUE\n*\n*        Compute the error ratio for this result.\n*\n         ERR = ZERO\n         DO 110 I = 1, M\n            ERRI = ABS( CT( I ) - CC( I, J ) )/EPS\n            IF( G( I ).NE.ZERO )\n     $         ERRI = ERRI/G( I )\n            ERR = MAX( ERR, ERRI )\n            IF( ERR*SQRT( EPS ).GE.ONE )\n     $         GO TO 130\n  110    CONTINUE\n*\n  120 CONTINUE\n*\n*     If the loop completes, all results are at least half accurate.\n      GO TO 150\n*\n*     Report fatal error.\n*\n  130 FATAL = .TRUE.\n      WRITE( NOUT, FMT = 9999 )\n      DO 140 I = 1, M\n         IF( MV )THEN\n            WRITE( NOUT, FMT = 9998 )I, CT( I ), CC( I, J )\n         ELSE\n            WRITE( NOUT, FMT = 9998 )I, CC( I, J ), CT( I )\n         END IF\n  140 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9997 )J\n*\n  150 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ******* FATAL ERROR - COMPUTED RESULT IS LESS THAN HAL',\n     $      'F ACCURATE *******', /'           EXPECTED RESULT   COMPU',\n     $      'TED RESULT' )\n 9998 FORMAT( 1X, I7, 2G18.6 )\n 9997 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n*\n*     End of SMMCH.\n*\n      END\n      LOGICAL FUNCTION LSE( RI, RJ, LR )\n*\n*  Tests if two arrays are identical.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LR\n*     .. Array Arguments ..\n      REAL               RI( * ), RJ( * )\n*     .. Local Scalars ..\n      INTEGER            I\n*     .. Executable Statements ..\n      DO 10 I = 1, LR\n         IF( RI( I ).NE.RJ( I ) )\n     $      GO TO 20\n   10 CONTINUE\n      LSE = .TRUE.\n      GO TO 30\n   20 CONTINUE\n      LSE = .FALSE.\n   30 RETURN\n*\n*     End of LSE.\n*\n      END\n      LOGICAL FUNCTION LSERES( TYPE, UPLO, M, N, AA, AS, LDA )\n*\n*  Tests if selected elements in two arrays are equal.\n*\n*  TYPE is 'GE' or 'SY'.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LDA, M, N\n      CHARACTER*1        UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      REAL               AA( LDA, * ), AS( LDA, * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J\n      LOGICAL            UPPER\n*     .. Executable Statements ..\n      UPPER = UPLO.EQ.'U'\n      IF( TYPE.EQ.'GE' )THEN\n         DO 20 J = 1, N\n            DO 10 I = M + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   10       CONTINUE\n   20    CONTINUE\n      ELSE IF( TYPE.EQ.'SY' )THEN\n         DO 50 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 30 I = 1, IBEG - 1\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   30       CONTINUE\n            DO 40 I = IEND + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   40       CONTINUE\n   50    CONTINUE\n      END IF\n*\n      LSERES = .TRUE.\n      GO TO 80\n   70 CONTINUE\n      LSERES = .FALSE.\n   80 RETURN\n*\n*     End of LSERES.\n*\n      END\n      REAL FUNCTION SBEG( RESET )\n*\n*  Generates random numbers uniformly distributed between -0.5 and 0.5.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      LOGICAL            RESET\n*     .. Local Scalars ..\n      INTEGER            I, IC, MI\n*     .. Save statement ..\n      SAVE               I, IC, MI\n*     .. Executable Statements ..\n      IF( RESET )THEN\n*        Initialize local variables.\n         MI = 891\n         I = 7\n         IC = 0\n         RESET = .FALSE.\n      END IF\n*\n*     The sequence of values of I is bounded between 1 and 999.\n*     If initial I = 1,2,3,6,7 or 9, the period will be 50.\n*     If initial I = 4 or 8, the period will be 25.\n*     If initial I = 5, the period will be 10.\n*     IC is used to break up the period by skipping 1 value of I in 6.\n*\n      IC = IC + 1\n   10 I = I*MI\n      I = I - 1000*( I/1000 )\n      IF( IC.GE.5 )THEN\n         IC = 0\n         GO TO 10\n      END IF\n      SBEG = ( I - 500 )/1001.0\n      RETURN\n*\n*     End of SBEG.\n*\n      END\n      REAL FUNCTION SDIFF( X, Y )\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      REAL               X, Y\n*     .. Executable Statements ..\n      SDIFF = X - Y\n      RETURN\n*\n*     End of SDIFF.\n*\n      END\n      SUBROUTINE CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n*  Tests whether XERBLA has detected an error when it should.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Executable Statements ..\n      IF( .NOT.LERR )THEN\n         WRITE( NOUT, FMT = 9999 )INFOT, SRNAMT\n         OK = .FALSE.\n      END IF\n      LERR = .FALSE.\n      RETURN\n*\n 9999 FORMAT( ' ***** ILLEGAL VALUE OF PARAMETER NUMBER ', I2, ' NOT D',\n     $      'ETECTED BY ', A6, ' *****' )\n*\n*     End of CHKXER.\n*\n      END\n      SUBROUTINE XERBLA( SRNAME, INFO )\n*\n*  This is a special version of XERBLA to be used only as part of\n*  the test program for testing error exits from the Level 3 BLAS\n*  routines.\n*\n*  XERBLA  is an error handler for the Level 3 BLAS routines.\n*\n*  It is called by the Level 3 BLAS routines if an input parameter is\n*  invalid.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFO\n      CHARACTER*6        SRNAME\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUT, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Executable Statements ..\n      LERR = .TRUE.\n      IF( INFO.NE.INFOT )THEN\n         IF( INFOT.NE.0 )THEN\n            WRITE( NOUT, FMT = 9999 )INFO, INFOT\n         ELSE\n            WRITE( NOUT, FMT = 9997 )INFO\n         END IF\n         OK = .FALSE.\n      END IF\n      IF( SRNAME.NE.SRNAMT )THEN\n         WRITE( NOUT, FMT = 9998 )SRNAME, SRNAMT\n         OK = .FALSE.\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6, ' INSTEAD',\n     $      ' OF ', I2, ' *******' )\n 9998 FORMAT( ' ******* XERBLA WAS CALLED WITH SRNAME = ', A6, ' INSTE',\n     $      'AD OF ', A6, ' *******' )\n 9997 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6,\n     $      ' *******' )\n*\n*     End of XERBLA\n*\n      END\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/testing/zblat1.f",
    "content": "*> \\brief \\b ZBLAT1\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM ZBLAT1\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*>    Test program for the COMPLEX*16 Level 1 BLAS.\n*>\n*>    Based upon the original BLAS test routine together with:\n*>    F06GAF Example Program Text\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup complex16_blas_testing\n*\n*  =====================================================================\n      PROGRAM ZBLAT1\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER          NOUT\n      PARAMETER        (NOUT=6)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, MODE, N\n      LOGICAL          PASS\n*     .. Local Scalars ..\n      DOUBLE PRECISION SFAC\n      INTEGER          IC\n*     .. External Subroutines ..\n      EXTERNAL         CHECK1, CHECK2, HEADER\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Data statements ..\n      DATA             SFAC/9.765625D-4/\n*     .. Executable Statements ..\n      WRITE (NOUT,99999)\n      DO 20 IC = 1, 10\n         ICASE = IC\n         CALL HEADER\n*\n*        Initialize PASS, INCX, INCY, and MODE for a new case.\n*        The value 9999 for INCX, INCY or MODE will appear in the\n*        detailed  output, if any, for cases that do not involve\n*        these parameters.\n*\n         PASS = .TRUE.\n         INCX = 9999\n         INCY = 9999\n         MODE = 9999\n         IF (ICASE.LE.5) THEN\n            CALL CHECK2(SFAC)\n         ELSE IF (ICASE.GE.6) THEN\n            CALL CHECK1(SFAC)\n         END IF\n*        -- Print\n         IF (PASS) WRITE (NOUT,99998)\n   20 CONTINUE\n      STOP\n*\n99999 FORMAT (' Complex BLAS Test Program Results',/1X)\n99998 FORMAT ('                                    ----- PASS -----')\n      END\n      SUBROUTINE HEADER\n*     .. Parameters ..\n      INTEGER          NOUT\n      PARAMETER        (NOUT=6)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, MODE, N\n      LOGICAL          PASS\n*     .. Local Arrays ..\n      CHARACTER*6      L(10)\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Data statements ..\n      DATA             L(1)/'ZDOTC '/\n      DATA             L(2)/'ZDOTU '/\n      DATA             L(3)/'ZAXPY '/\n      DATA             L(4)/'ZCOPY '/\n      DATA             L(5)/'ZSWAP '/\n      DATA             L(6)/'DZNRM2'/\n      DATA             L(7)/'DZASUM'/\n      DATA             L(8)/'ZSCAL '/\n      DATA             L(9)/'ZDSCAL'/\n      DATA             L(10)/'IZAMAX'/\n*     .. Executable Statements ..\n      WRITE (NOUT,99999) ICASE, L(ICASE)\n      RETURN\n*\n99999 FORMAT (/' Test of subprogram number',I3,12X,A6)\n      END\n      SUBROUTINE CHECK1(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION  SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, MODE, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      COMPLEX*16        CA\n      DOUBLE PRECISION  SA\n      INTEGER           I, J, LEN, NP1\n*     .. Local Arrays ..\n      COMPLEX*16        CTRUE5(8,5,2), CTRUE6(8,5,2), CV(8,5,2), CX(8),\n     +                  MWPCS(5), MWPCT(5)\n      DOUBLE PRECISION  STRUE2(5), STRUE4(5)\n      INTEGER           ITRUE3(5)\n*     .. External Functions ..\n      DOUBLE PRECISION  DZASUM, DZNRM2\n      INTEGER           IZAMAX\n      EXTERNAL          DZASUM, DZNRM2, IZAMAX\n*     .. External Subroutines ..\n      EXTERNAL          ZSCAL, ZDSCAL, CTEST, ITEST1, STEST1\n*     .. Intrinsic Functions ..\n      INTRINSIC         MAX\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Data statements ..\n      DATA              SA, CA/0.3D0, (0.4D0,-0.7D0)/\n      DATA              ((CV(I,J,1),I=1,8),J=1,5)/(0.1D0,0.1D0),\n     +                  (1.0D0,2.0D0), (1.0D0,2.0D0), (1.0D0,2.0D0),\n     +                  (1.0D0,2.0D0), (1.0D0,2.0D0), (1.0D0,2.0D0),\n     +                  (1.0D0,2.0D0), (0.3D0,-0.4D0), (3.0D0,4.0D0),\n     +                  (3.0D0,4.0D0), (3.0D0,4.0D0), (3.0D0,4.0D0),\n     +                  (3.0D0,4.0D0), (3.0D0,4.0D0), (3.0D0,4.0D0),\n     +                  (0.1D0,-0.3D0), (0.5D0,-0.1D0), (5.0D0,6.0D0),\n     +                  (5.0D0,6.0D0), (5.0D0,6.0D0), (5.0D0,6.0D0),\n     +                  (5.0D0,6.0D0), (5.0D0,6.0D0), (0.1D0,0.1D0),\n     +                  (-0.6D0,0.1D0), (0.1D0,-0.3D0), (7.0D0,8.0D0),\n     +                  (7.0D0,8.0D0), (7.0D0,8.0D0), (7.0D0,8.0D0),\n     +                  (7.0D0,8.0D0), (0.3D0,0.1D0), (0.5D0,0.0D0),\n     +                  (0.0D0,0.5D0), (0.0D0,0.2D0), (2.0D0,3.0D0),\n     +                  (2.0D0,3.0D0), (2.0D0,3.0D0), (2.0D0,3.0D0)/\n      DATA              ((CV(I,J,2),I=1,8),J=1,5)/(0.1D0,0.1D0),\n     +                  (4.0D0,5.0D0), (4.0D0,5.0D0), (4.0D0,5.0D0),\n     +                  (4.0D0,5.0D0), (4.0D0,5.0D0), (4.0D0,5.0D0),\n     +                  (4.0D0,5.0D0), (0.3D0,-0.4D0), (6.0D0,7.0D0),\n     +                  (6.0D0,7.0D0), (6.0D0,7.0D0), (6.0D0,7.0D0),\n     +                  (6.0D0,7.0D0), (6.0D0,7.0D0), (6.0D0,7.0D0),\n     +                  (0.1D0,-0.3D0), (8.0D0,9.0D0), (0.5D0,-0.1D0),\n     +                  (2.0D0,5.0D0), (2.0D0,5.0D0), (2.0D0,5.0D0),\n     +                  (2.0D0,5.0D0), (2.0D0,5.0D0), (0.1D0,0.1D0),\n     +                  (3.0D0,6.0D0), (-0.6D0,0.1D0), (4.0D0,7.0D0),\n     +                  (0.1D0,-0.3D0), (7.0D0,2.0D0), (7.0D0,2.0D0),\n     +                  (7.0D0,2.0D0), (0.3D0,0.1D0), (5.0D0,8.0D0),\n     +                  (0.5D0,0.0D0), (6.0D0,9.0D0), (0.0D0,0.5D0),\n     +                  (8.0D0,3.0D0), (0.0D0,0.2D0), (9.0D0,4.0D0)/\n      DATA              STRUE2/0.0D0, 0.5D0, 0.6D0, 0.7D0, 0.8D0/\n      DATA              STRUE4/0.0D0, 0.7D0, 1.0D0, 1.3D0, 1.6D0/\n      DATA              ((CTRUE5(I,J,1),I=1,8),J=1,5)/(0.1D0,0.1D0),\n     +                  (1.0D0,2.0D0), (1.0D0,2.0D0), (1.0D0,2.0D0),\n     +                  (1.0D0,2.0D0), (1.0D0,2.0D0), (1.0D0,2.0D0),\n     +                  (1.0D0,2.0D0), (-0.16D0,-0.37D0), (3.0D0,4.0D0),\n     +                  (3.0D0,4.0D0), (3.0D0,4.0D0), (3.0D0,4.0D0),\n     +                  (3.0D0,4.0D0), (3.0D0,4.0D0), (3.0D0,4.0D0),\n     +                  (-0.17D0,-0.19D0), (0.13D0,-0.39D0),\n     +                  (5.0D0,6.0D0), (5.0D0,6.0D0), (5.0D0,6.0D0),\n     +                  (5.0D0,6.0D0), (5.0D0,6.0D0), (5.0D0,6.0D0),\n     +                  (0.11D0,-0.03D0), (-0.17D0,0.46D0),\n     +                  (-0.17D0,-0.19D0), (7.0D0,8.0D0), (7.0D0,8.0D0),\n     +                  (7.0D0,8.0D0), (7.0D0,8.0D0), (7.0D0,8.0D0),\n     +                  (0.19D0,-0.17D0), (0.20D0,-0.35D0),\n     +                  (0.35D0,0.20D0), (0.14D0,0.08D0),\n     +                  (2.0D0,3.0D0), (2.0D0,3.0D0), (2.0D0,3.0D0),\n     +                  (2.0D0,3.0D0)/\n      DATA              ((CTRUE5(I,J,2),I=1,8),J=1,5)/(0.1D0,0.1D0),\n     +                  (4.0D0,5.0D0), (4.0D0,5.0D0), (4.0D0,5.0D0),\n     +                  (4.0D0,5.0D0), (4.0D0,5.0D0), (4.0D0,5.0D0),\n     +                  (4.0D0,5.0D0), (-0.16D0,-0.37D0), (6.0D0,7.0D0),\n     +                  (6.0D0,7.0D0), (6.0D0,7.0D0), (6.0D0,7.0D0),\n     +                  (6.0D0,7.0D0), (6.0D0,7.0D0), (6.0D0,7.0D0),\n     +                  (-0.17D0,-0.19D0), (8.0D0,9.0D0),\n     +                  (0.13D0,-0.39D0), (2.0D0,5.0D0), (2.0D0,5.0D0),\n     +                  (2.0D0,5.0D0), (2.0D0,5.0D0), (2.0D0,5.0D0),\n     +                  (0.11D0,-0.03D0), (3.0D0,6.0D0),\n     +                  (-0.17D0,0.46D0), (4.0D0,7.0D0),\n     +                  (-0.17D0,-0.19D0), (7.0D0,2.0D0), (7.0D0,2.0D0),\n     +                  (7.0D0,2.0D0), (0.19D0,-0.17D0), (5.0D0,8.0D0),\n     +                  (0.20D0,-0.35D0), (6.0D0,9.0D0),\n     +                  (0.35D0,0.20D0), (8.0D0,3.0D0),\n     +                  (0.14D0,0.08D0), (9.0D0,4.0D0)/\n      DATA              ((CTRUE6(I,J,1),I=1,8),J=1,5)/(0.1D0,0.1D0),\n     +                  (1.0D0,2.0D0), (1.0D0,2.0D0), (1.0D0,2.0D0),\n     +                  (1.0D0,2.0D0), (1.0D0,2.0D0), (1.0D0,2.0D0),\n     +                  (1.0D0,2.0D0), (0.09D0,-0.12D0), (3.0D0,4.0D0),\n     +                  (3.0D0,4.0D0), (3.0D0,4.0D0), (3.0D0,4.0D0),\n     +                  (3.0D0,4.0D0), (3.0D0,4.0D0), (3.0D0,4.0D0),\n     +                  (0.03D0,-0.09D0), (0.15D0,-0.03D0),\n     +                  (5.0D0,6.0D0), (5.0D0,6.0D0), (5.0D0,6.0D0),\n     +                  (5.0D0,6.0D0), (5.0D0,6.0D0), (5.0D0,6.0D0),\n     +                  (0.03D0,0.03D0), (-0.18D0,0.03D0),\n     +                  (0.03D0,-0.09D0), (7.0D0,8.0D0), (7.0D0,8.0D0),\n     +                  (7.0D0,8.0D0), (7.0D0,8.0D0), (7.0D0,8.0D0),\n     +                  (0.09D0,0.03D0), (0.15D0,0.00D0),\n     +                  (0.00D0,0.15D0), (0.00D0,0.06D0), (2.0D0,3.0D0),\n     +                  (2.0D0,3.0D0), (2.0D0,3.0D0), (2.0D0,3.0D0)/\n      DATA              ((CTRUE6(I,J,2),I=1,8),J=1,5)/(0.1D0,0.1D0),\n     +                  (4.0D0,5.0D0), (4.0D0,5.0D0), (4.0D0,5.0D0),\n     +                  (4.0D0,5.0D0), (4.0D0,5.0D0), (4.0D0,5.0D0),\n     +                  (4.0D0,5.0D0), (0.09D0,-0.12D0), (6.0D0,7.0D0),\n     +                  (6.0D0,7.0D0), (6.0D0,7.0D0), (6.0D0,7.0D0),\n     +                  (6.0D0,7.0D0), (6.0D0,7.0D0), (6.0D0,7.0D0),\n     +                  (0.03D0,-0.09D0), (8.0D0,9.0D0),\n     +                  (0.15D0,-0.03D0), (2.0D0,5.0D0), (2.0D0,5.0D0),\n     +                  (2.0D0,5.0D0), (2.0D0,5.0D0), (2.0D0,5.0D0),\n     +                  (0.03D0,0.03D0), (3.0D0,6.0D0),\n     +                  (-0.18D0,0.03D0), (4.0D0,7.0D0),\n     +                  (0.03D0,-0.09D0), (7.0D0,2.0D0), (7.0D0,2.0D0),\n     +                  (7.0D0,2.0D0), (0.09D0,0.03D0), (5.0D0,8.0D0),\n     +                  (0.15D0,0.00D0), (6.0D0,9.0D0), (0.00D0,0.15D0),\n     +                  (8.0D0,3.0D0), (0.00D0,0.06D0), (9.0D0,4.0D0)/\n      DATA              ITRUE3/0, 1, 2, 2, 2/\n*     .. Executable Statements ..\n      DO 60 INCX = 1, 2\n         DO 40 NP1 = 1, 5\n            N = NP1 - 1\n            LEN = 2*MAX(N,1)\n*           .. Set vector arguments ..\n            DO 20 I = 1, LEN\n               CX(I) = CV(I,NP1,INCX)\n   20       CONTINUE\n            IF (ICASE.EQ.6) THEN\n*              .. DZNRM2 ..\n               CALL STEST1(DZNRM2(N,CX,INCX),STRUE2(NP1),STRUE2(NP1),\n     +                     SFAC)\n            ELSE IF (ICASE.EQ.7) THEN\n*              .. DZASUM ..\n               CALL STEST1(DZASUM(N,CX,INCX),STRUE4(NP1),STRUE4(NP1),\n     +                     SFAC)\n            ELSE IF (ICASE.EQ.8) THEN\n*              .. ZSCAL ..\n               CALL ZSCAL(N,CA,CX,INCX)\n               CALL CTEST(LEN,CX,CTRUE5(1,NP1,INCX),CTRUE5(1,NP1,INCX),\n     +                    SFAC)\n            ELSE IF (ICASE.EQ.9) THEN\n*              .. ZDSCAL ..\n               CALL ZDSCAL(N,SA,CX,INCX)\n               CALL CTEST(LEN,CX,CTRUE6(1,NP1,INCX),CTRUE6(1,NP1,INCX),\n     +                    SFAC)\n            ELSE IF (ICASE.EQ.10) THEN\n*              .. IZAMAX ..\n               CALL ITEST1(IZAMAX(N,CX,INCX),ITRUE3(NP1))\n            ELSE\n               WRITE (NOUT,*) ' Shouldn''t be here in CHECK1'\n               STOP\n            END IF\n*\n   40    CONTINUE\n   60 CONTINUE\n*\n      INCX = 1\n      IF (ICASE.EQ.8) THEN\n*        ZSCAL\n*        Add a test for alpha equal to zero.\n         CA = (0.0D0,0.0D0)\n         DO 80 I = 1, 5\n            MWPCT(I) = (0.0D0,0.0D0)\n            MWPCS(I) = (1.0D0,1.0D0)\n   80    CONTINUE\n         CALL ZSCAL(5,CA,CX,INCX)\n         CALL CTEST(5,CX,MWPCT,MWPCS,SFAC)\n      ELSE IF (ICASE.EQ.9) THEN\n*        ZDSCAL\n*        Add a test for alpha equal to zero.\n         SA = 0.0D0\n         DO 100 I = 1, 5\n            MWPCT(I) = (0.0D0,0.0D0)\n            MWPCS(I) = (1.0D0,1.0D0)\n  100    CONTINUE\n         CALL ZDSCAL(5,SA,CX,INCX)\n         CALL CTEST(5,CX,MWPCT,MWPCS,SFAC)\n*        Add a test for alpha equal to one.\n         SA = 1.0D0\n         DO 120 I = 1, 5\n            MWPCT(I) = CX(I)\n            MWPCS(I) = CX(I)\n  120    CONTINUE\n         CALL ZDSCAL(5,SA,CX,INCX)\n         CALL CTEST(5,CX,MWPCT,MWPCS,SFAC)\n*        Add a test for alpha equal to minus one.\n         SA = -1.0D0\n         DO 140 I = 1, 5\n            MWPCT(I) = -CX(I)\n            MWPCS(I) = -CX(I)\n  140    CONTINUE\n         CALL ZDSCAL(5,SA,CX,INCX)\n         CALL CTEST(5,CX,MWPCT,MWPCS,SFAC)\n      END IF\n      RETURN\n      END\n      SUBROUTINE CHECK2(SFAC)\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION  SFAC\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, MODE, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      COMPLEX*16        CA\n      INTEGER           I, J, KI, KN, KSIZE, LENX, LENY, MX, MY\n*     .. Local Arrays ..\n      COMPLEX*16        CDOT(1), CSIZE1(4), CSIZE2(7,2), CSIZE3(14),\n     +                  CT10X(7,4,4), CT10Y(7,4,4), CT6(4,4), CT7(4,4),\n     +                  CT8(7,4,4), CX(7), CX1(7), CY(7), CY1(7)\n      INTEGER           INCXS(4), INCYS(4), LENS(4,2), NS(4)\n*     .. External Functions ..\n      COMPLEX*16        ZDOTC, ZDOTU\n      EXTERNAL          ZDOTC, ZDOTU\n*     .. External Subroutines ..\n      EXTERNAL          ZAXPY, ZCOPY, ZSWAP, CTEST\n*     .. Intrinsic Functions ..\n      INTRINSIC         ABS, MIN\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Data statements ..\n      DATA              CA/(0.4D0,-0.7D0)/\n      DATA              INCXS/1, 2, -2, -1/\n      DATA              INCYS/1, -2, 1, -2/\n      DATA              LENS/1, 1, 2, 4, 1, 1, 3, 7/\n      DATA              NS/0, 1, 2, 4/\n      DATA              CX1/(0.7D0,-0.8D0), (-0.4D0,-0.7D0),\n     +                  (-0.1D0,-0.9D0), (0.2D0,-0.8D0),\n     +                  (-0.9D0,-0.4D0), (0.1D0,0.4D0), (-0.6D0,0.6D0)/\n      DATA              CY1/(0.6D0,-0.6D0), (-0.9D0,0.5D0),\n     +                  (0.7D0,-0.6D0), (0.1D0,-0.5D0), (-0.1D0,-0.2D0),\n     +                  (-0.5D0,-0.3D0), (0.8D0,-0.7D0)/\n      DATA              ((CT8(I,J,1),I=1,7),J=1,4)/(0.6D0,-0.6D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.32D0,-1.41D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.32D0,-1.41D0),\n     +                  (-1.55D0,0.5D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.32D0,-1.41D0), (-1.55D0,0.5D0),\n     +                  (0.03D0,-0.89D0), (-0.38D0,-0.96D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0)/\n      DATA              ((CT8(I,J,2),I=1,7),J=1,4)/(0.6D0,-0.6D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.32D0,-1.41D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (-0.07D0,-0.89D0),\n     +                  (-0.9D0,0.5D0), (0.42D0,-1.41D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.78D0,0.06D0), (-0.9D0,0.5D0),\n     +                  (0.06D0,-0.13D0), (0.1D0,-0.5D0),\n     +                  (-0.77D0,-0.49D0), (-0.5D0,-0.3D0),\n     +                  (0.52D0,-1.51D0)/\n      DATA              ((CT8(I,J,3),I=1,7),J=1,4)/(0.6D0,-0.6D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.32D0,-1.41D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (-0.07D0,-0.89D0),\n     +                  (-1.18D0,-0.31D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.78D0,0.06D0), (-1.54D0,0.97D0),\n     +                  (0.03D0,-0.89D0), (-0.18D0,-1.31D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0)/\n      DATA              ((CT8(I,J,4),I=1,7),J=1,4)/(0.6D0,-0.6D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.32D0,-1.41D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.32D0,-1.41D0), (-0.9D0,0.5D0),\n     +                  (0.05D0,-0.6D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.32D0,-1.41D0),\n     +                  (-0.9D0,0.5D0), (0.05D0,-0.6D0), (0.1D0,-0.5D0),\n     +                  (-0.77D0,-0.49D0), (-0.5D0,-0.3D0),\n     +                  (0.32D0,-1.16D0)/\n      DATA              CT7/(0.0D0,0.0D0), (-0.06D0,-0.90D0),\n     +                  (0.65D0,-0.47D0), (-0.34D0,-1.22D0),\n     +                  (0.0D0,0.0D0), (-0.06D0,-0.90D0),\n     +                  (-0.59D0,-1.46D0), (-1.04D0,-0.04D0),\n     +                  (0.0D0,0.0D0), (-0.06D0,-0.90D0),\n     +                  (-0.83D0,0.59D0), (0.07D0,-0.37D0),\n     +                  (0.0D0,0.0D0), (-0.06D0,-0.90D0),\n     +                  (-0.76D0,-1.15D0), (-1.33D0,-1.82D0)/\n      DATA              CT6/(0.0D0,0.0D0), (0.90D0,0.06D0),\n     +                  (0.91D0,-0.77D0), (1.80D0,-0.10D0),\n     +                  (0.0D0,0.0D0), (0.90D0,0.06D0), (1.45D0,0.74D0),\n     +                  (0.20D0,0.90D0), (0.0D0,0.0D0), (0.90D0,0.06D0),\n     +                  (-0.55D0,0.23D0), (0.83D0,-0.39D0),\n     +                  (0.0D0,0.0D0), (0.90D0,0.06D0), (1.04D0,0.79D0),\n     +                  (1.95D0,1.22D0)/\n      DATA              ((CT10X(I,J,1),I=1,7),J=1,4)/(0.7D0,-0.8D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.6D0,-0.6D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.6D0,-0.6D0), (-0.9D0,0.5D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.6D0,-0.6D0),\n     +                  (-0.9D0,0.5D0), (0.7D0,-0.6D0), (0.1D0,-0.5D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0)/\n      DATA              ((CT10X(I,J,2),I=1,7),J=1,4)/(0.7D0,-0.8D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.6D0,-0.6D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.7D0,-0.6D0), (-0.4D0,-0.7D0),\n     +                  (0.6D0,-0.6D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.8D0,-0.7D0),\n     +                  (-0.4D0,-0.7D0), (-0.1D0,-0.2D0),\n     +                  (0.2D0,-0.8D0), (0.7D0,-0.6D0), (0.1D0,0.4D0),\n     +                  (0.6D0,-0.6D0)/\n      DATA              ((CT10X(I,J,3),I=1,7),J=1,4)/(0.7D0,-0.8D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.6D0,-0.6D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (-0.9D0,0.5D0), (-0.4D0,-0.7D0),\n     +                  (0.6D0,-0.6D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.1D0,-0.5D0),\n     +                  (-0.4D0,-0.7D0), (0.7D0,-0.6D0), (0.2D0,-0.8D0),\n     +                  (-0.9D0,0.5D0), (0.1D0,0.4D0), (0.6D0,-0.6D0)/\n      DATA              ((CT10X(I,J,4),I=1,7),J=1,4)/(0.7D0,-0.8D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.6D0,-0.6D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.6D0,-0.6D0), (0.7D0,-0.6D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.6D0,-0.6D0),\n     +                  (0.7D0,-0.6D0), (-0.1D0,-0.2D0), (0.8D0,-0.7D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0)/\n      DATA              ((CT10Y(I,J,1),I=1,7),J=1,4)/(0.6D0,-0.6D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.7D0,-0.8D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.7D0,-0.8D0), (-0.4D0,-0.7D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.7D0,-0.8D0),\n     +                  (-0.4D0,-0.7D0), (-0.1D0,-0.9D0),\n     +                  (0.2D0,-0.8D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0)/\n      DATA              ((CT10Y(I,J,2),I=1,7),J=1,4)/(0.6D0,-0.6D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.7D0,-0.8D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (-0.1D0,-0.9D0), (-0.9D0,0.5D0),\n     +                  (0.7D0,-0.8D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (-0.6D0,0.6D0),\n     +                  (-0.9D0,0.5D0), (-0.9D0,-0.4D0), (0.1D0,-0.5D0),\n     +                  (-0.1D0,-0.9D0), (-0.5D0,-0.3D0),\n     +                  (0.7D0,-0.8D0)/\n      DATA              ((CT10Y(I,J,3),I=1,7),J=1,4)/(0.6D0,-0.6D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.7D0,-0.8D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (-0.1D0,-0.9D0), (0.7D0,-0.8D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (-0.6D0,0.6D0),\n     +                  (-0.9D0,-0.4D0), (-0.1D0,-0.9D0),\n     +                  (0.7D0,-0.8D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0)/\n      DATA              ((CT10Y(I,J,4),I=1,7),J=1,4)/(0.6D0,-0.6D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.7D0,-0.8D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.7D0,-0.8D0), (-0.9D0,0.5D0),\n     +                  (-0.4D0,-0.7D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.7D0,-0.8D0),\n     +                  (-0.9D0,0.5D0), (-0.4D0,-0.7D0), (0.1D0,-0.5D0),\n     +                  (-0.1D0,-0.9D0), (-0.5D0,-0.3D0),\n     +                  (0.2D0,-0.8D0)/\n      DATA              CSIZE1/(0.0D0,0.0D0), (0.9D0,0.9D0),\n     +                  (1.63D0,1.73D0), (2.90D0,2.78D0)/\n      DATA              CSIZE3/(0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (1.17D0,1.17D0),\n     +                  (1.17D0,1.17D0), (1.17D0,1.17D0),\n     +                  (1.17D0,1.17D0), (1.17D0,1.17D0),\n     +                  (1.17D0,1.17D0), (1.17D0,1.17D0)/\n      DATA              CSIZE2/(0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (0.0D0,0.0D0),\n     +                  (0.0D0,0.0D0), (0.0D0,0.0D0), (1.54D0,1.54D0),\n     +                  (1.54D0,1.54D0), (1.54D0,1.54D0),\n     +                  (1.54D0,1.54D0), (1.54D0,1.54D0),\n     +                  (1.54D0,1.54D0), (1.54D0,1.54D0)/\n*     .. Executable Statements ..\n      DO 60 KI = 1, 4\n         INCX = INCXS(KI)\n         INCY = INCYS(KI)\n         MX = ABS(INCX)\n         MY = ABS(INCY)\n*\n         DO 40 KN = 1, 4\n            N = NS(KN)\n            KSIZE = MIN(2,KN)\n            LENX = LENS(KN,MX)\n            LENY = LENS(KN,MY)\n*           .. initialize all argument arrays ..\n            DO 20 I = 1, 7\n               CX(I) = CX1(I)\n               CY(I) = CY1(I)\n   20       CONTINUE\n            IF (ICASE.EQ.1) THEN\n*              .. ZDOTC ..\n               CDOT(1) = ZDOTC(N,CX,INCX,CY,INCY)\n               CALL CTEST(1,CDOT,CT6(KN,KI),CSIZE1(KN),SFAC)\n            ELSE IF (ICASE.EQ.2) THEN\n*              .. ZDOTU ..\n               CDOT(1) = ZDOTU(N,CX,INCX,CY,INCY)\n               CALL CTEST(1,CDOT,CT7(KN,KI),CSIZE1(KN),SFAC)\n            ELSE IF (ICASE.EQ.3) THEN\n*              .. ZAXPY ..\n               CALL ZAXPY(N,CA,CX,INCX,CY,INCY)\n               CALL CTEST(LENY,CY,CT8(1,KN,KI),CSIZE2(1,KSIZE),SFAC)\n            ELSE IF (ICASE.EQ.4) THEN\n*              .. ZCOPY ..\n               CALL ZCOPY(N,CX,INCX,CY,INCY)\n               CALL CTEST(LENY,CY,CT10Y(1,KN,KI),CSIZE3,1.0D0)\n            ELSE IF (ICASE.EQ.5) THEN\n*              .. ZSWAP ..\n               CALL ZSWAP(N,CX,INCX,CY,INCY)\n               CALL CTEST(LENX,CX,CT10X(1,KN,KI),CSIZE3,1.0D0)\n               CALL CTEST(LENY,CY,CT10Y(1,KN,KI),CSIZE3,1.0D0)\n            ELSE\n               WRITE (NOUT,*) ' Shouldn''t be here in CHECK2'\n               STOP\n            END IF\n*\n   40    CONTINUE\n   60 CONTINUE\n      RETURN\n      END\n      SUBROUTINE STEST(LEN,SCOMP,STRUE,SSIZE,SFAC)\n*     ********************************* STEST **************************\n*\n*     THIS SUBR COMPARES ARRAYS  SCOMP() AND STRUE() OF LENGTH LEN TO\n*     SEE IF THE TERM BY TERM DIFFERENCES, MULTIPLIED BY SFAC, ARE\n*     NEGLIGIBLE.\n*\n*     C. L. LAWSON, JPL, 1974 DEC 10\n*\n*     .. Parameters ..\n      INTEGER          NOUT\n      DOUBLE PRECISION ZERO\n      PARAMETER        (NOUT=6, ZERO=0.0D0)\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION SFAC\n      INTEGER          LEN\n*     .. Array Arguments ..\n      DOUBLE PRECISION SCOMP(LEN), SSIZE(LEN), STRUE(LEN)\n*     .. Scalars in Common ..\n      INTEGER          ICASE, INCX, INCY, MODE, N\n      LOGICAL          PASS\n*     .. Local Scalars ..\n      DOUBLE PRECISION SD\n      INTEGER          I\n*     .. External Functions ..\n      DOUBLE PRECISION SDIFF\n      EXTERNAL         SDIFF\n*     .. Intrinsic Functions ..\n      INTRINSIC        ABS\n*     .. Common blocks ..\n      COMMON           /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Executable Statements ..\n*\n      DO 40 I = 1, LEN\n         SD = SCOMP(I) - STRUE(I)\n         IF (ABS(SFAC*SD) .LE. ABS(SSIZE(I))*EPSILON(ZERO))\n     +       GO TO 40\n*\n*                             HERE    SCOMP(I) IS NOT CLOSE TO STRUE(I).\n*\n         IF ( .NOT. PASS) GO TO 20\n*                             PRINT FAIL MESSAGE AND HEADER.\n         PASS = .FALSE.\n         WRITE (NOUT,99999)\n         WRITE (NOUT,99998)\n   20    WRITE (NOUT,99997) ICASE, N, INCX, INCY, MODE, I, SCOMP(I),\n     +     STRUE(I), SD, SSIZE(I)\n   40 CONTINUE\n      RETURN\n*\n99999 FORMAT ('                                       FAIL')\n99998 FORMAT (/' CASE  N INCX INCY MODE  I                            ',\n     +       ' COMP(I)                             TRUE(I)  DIFFERENCE',\n     +       '     SIZE(I)',/1X)\n99997 FORMAT (1X,I4,I3,3I5,I3,2D36.8,2D12.4)\n      END\n      SUBROUTINE STEST1(SCOMP1,STRUE1,SSIZE,SFAC)\n*     ************************* STEST1 *****************************\n*\n*     THIS IS AN INTERFACE SUBROUTINE TO ACCOMMODATE THE FORTRAN\n*     REQUIREMENT THAT WHEN A DUMMY ARGUMENT IS AN ARRAY, THE\n*     ACTUAL ARGUMENT MUST ALSO BE AN ARRAY OR AN ARRAY ELEMENT.\n*\n*     C.L. LAWSON, JPL, 1978 DEC 6\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION  SCOMP1, SFAC, STRUE1\n*     .. Array Arguments ..\n      DOUBLE PRECISION  SSIZE(*)\n*     .. Local Arrays ..\n      DOUBLE PRECISION  SCOMP(1), STRUE(1)\n*     .. External Subroutines ..\n      EXTERNAL          STEST\n*     .. Executable Statements ..\n*\n      SCOMP(1) = SCOMP1\n      STRUE(1) = STRUE1\n      CALL STEST(1,SCOMP,STRUE,SSIZE,SFAC)\n*\n      RETURN\n      END\n      DOUBLE PRECISION FUNCTION SDIFF(SA,SB)\n*     ********************************* SDIFF **************************\n*     COMPUTES DIFFERENCE OF TWO NUMBERS.  C. L. LAWSON, JPL 1974 FEB 15\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION                SA, SB\n*     .. Executable Statements ..\n      SDIFF = SA - SB\n      RETURN\n      END\n      SUBROUTINE CTEST(LEN,CCOMP,CTRUE,CSIZE,SFAC)\n*     **************************** CTEST *****************************\n*\n*     C.L. LAWSON, JPL, 1978 DEC 6\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION SFAC\n      INTEGER          LEN\n*     .. Array Arguments ..\n      COMPLEX*16       CCOMP(LEN), CSIZE(LEN), CTRUE(LEN)\n*     .. Local Scalars ..\n      INTEGER          I\n*     .. Local Arrays ..\n      DOUBLE PRECISION SCOMP(20), SSIZE(20), STRUE(20)\n*     .. External Subroutines ..\n      EXTERNAL         STEST\n*     .. Intrinsic Functions ..\n      INTRINSIC        DIMAG, DBLE\n*     .. Executable Statements ..\n      DO 20 I = 1, LEN\n         SCOMP(2*I-1) = DBLE(CCOMP(I))\n         SCOMP(2*I) = DIMAG(CCOMP(I))\n         STRUE(2*I-1) = DBLE(CTRUE(I))\n         STRUE(2*I) = DIMAG(CTRUE(I))\n         SSIZE(2*I-1) = DBLE(CSIZE(I))\n         SSIZE(2*I) = DIMAG(CSIZE(I))\n   20 CONTINUE\n*\n      CALL STEST(2*LEN,SCOMP,STRUE,SSIZE,SFAC)\n      RETURN\n      END\n      SUBROUTINE ITEST1(ICOMP,ITRUE)\n*     ********************************* ITEST1 *************************\n*\n*     THIS SUBROUTINE COMPARES THE VARIABLES ICOMP AND ITRUE FOR\n*     EQUALITY.\n*     C. L. LAWSON, JPL, 1974 DEC 10\n*\n*     .. Parameters ..\n      INTEGER           NOUT\n      PARAMETER         (NOUT=6)\n*     .. Scalar Arguments ..\n      INTEGER           ICOMP, ITRUE\n*     .. Scalars in Common ..\n      INTEGER           ICASE, INCX, INCY, MODE, N\n      LOGICAL           PASS\n*     .. Local Scalars ..\n      INTEGER           ID\n*     .. Common blocks ..\n      COMMON            /COMBLA/ICASE, N, INCX, INCY, MODE, PASS\n*     .. Executable Statements ..\n      IF (ICOMP.EQ.ITRUE) GO TO 40\n*\n*                            HERE ICOMP IS NOT EQUAL TO ITRUE.\n*\n      IF ( .NOT. PASS) GO TO 20\n*                             PRINT FAIL MESSAGE AND HEADER.\n      PASS = .FALSE.\n      WRITE (NOUT,99999)\n      WRITE (NOUT,99998)\n   20 ID = ICOMP - ITRUE\n      WRITE (NOUT,99997) ICASE, N, INCX, INCY, MODE, ICOMP, ITRUE, ID\n   40 CONTINUE\n      RETURN\n*\n99999 FORMAT ('                                       FAIL')\n99998 FORMAT (/' CASE  N INCX INCY MODE                               ',\n     +       ' COMP                                TRUE     DIFFERENCE',\n     +       /1X)\n99997 FORMAT (1X,I4,I3,3I5,2I36,I12)\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/testing/zblat2.f",
    "content": "*> \\brief \\b ZBLAT2\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM ZBLAT2\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> Test program for the COMPLEX*16       Level 2 Blas.\n*>\n*> The program must be driven by a short data file. The first 18 records\n*> of the file are read using list-directed input, the last 17 records\n*> are read using the format ( A6, L2 ). An annotated example of a data\n*> file can be obtained by deleting the first 3 characters from the\n*> following 35 lines:\n*> 'zblat2.out'      NAME OF SUMMARY OUTPUT FILE\n*> 6                 UNIT NUMBER OF SUMMARY FILE\n*> 'CBLA2T.SNAP'     NAME OF SNAPSHOT OUTPUT FILE\n*> -1                UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0)\n*> F        LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD.\n*> F        LOGICAL FLAG, T TO STOP ON FAILURES.\n*> T        LOGICAL FLAG, T TO TEST ERROR EXITS.\n*> 16.0     THRESHOLD VALUE OF TEST RATIO\n*> 6                 NUMBER OF VALUES OF N\n*> 0 1 2 3 5 9       VALUES OF N\n*> 4                 NUMBER OF VALUES OF K\n*> 0 1 2 4           VALUES OF K\n*> 4                 NUMBER OF VALUES OF INCX AND INCY\n*> 1 2 -1 -2         VALUES OF INCX AND INCY\n*> 3                 NUMBER OF VALUES OF ALPHA\n*> (0.0,0.0) (1.0,0.0) (0.7,-0.9)       VALUES OF ALPHA\n*> 3                 NUMBER OF VALUES OF BETA\n*> (0.0,0.0) (1.0,0.0) (1.3,-1.1)       VALUES OF BETA\n*> ZGEMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZGBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZHEMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZHBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZHPMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZTRMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZTBMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZTPMV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZTRSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZTBSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZTPSV  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZGERC  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZGERU  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZHER   T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZHPR   T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZHER2  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZHPR2  T PUT F FOR NO TEST. SAME COLUMNS.\n*>\n*> Further Details\n*> ===============\n*>\n*>    See:\n*>\n*>       Dongarra J. J., Du Croz J. J., Hammarling S.  and Hanson R. J..\n*>       An  extended  set of Fortran  Basic Linear Algebra Subprograms.\n*>\n*>       Technical  Memoranda  Nos. 41 (revision 3) and 81,  Mathematics\n*>       and  Computer Science  Division,  Argonne  National Laboratory,\n*>       9700 South Cass Avenue, Argonne, Illinois 60439, US.\n*>\n*>       Or\n*>\n*>       NAG  Technical Reports TR3/87 and TR4/87,  Numerical Algorithms\n*>       Group  Ltd.,  NAG  Central  Office,  256  Banbury  Road, Oxford\n*>       OX2 7DE, UK,  and  Numerical Algorithms Group Inc.,  1101  31st\n*>       Street,  Suite 100,  Downers Grove,  Illinois 60515-1263,  USA.\n*>\n*>\n*> -- Written on 10-August-1987.\n*>    Richard Hanson, Sandia National Labs.\n*>    Jeremy Du Croz, NAG Central Office.\n*>\n*>    10-9-00:  Change STATUS='NEW' to 'UNKNOWN' so that the testers\n*>              can be run multiple times without deleting generated\n*>              output files (susan)\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup complex16_blas_testing\n*\n*  =====================================================================\n      PROGRAM ZBLAT2\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER            NIN\n      PARAMETER          ( NIN = 5 )\n      INTEGER            NSUBS\n      PARAMETER          ( NSUBS = 17 )\n      COMPLEX*16         ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   ONE = ( 1.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n      INTEGER            NMAX, INCMAX\n      PARAMETER          ( NMAX = 65, INCMAX = 2 )\n      INTEGER            NINMAX, NIDMAX, NKBMAX, NALMAX, NBEMAX\n      PARAMETER          ( NINMAX = 7, NIDMAX = 9, NKBMAX = 7,\n     $                   NALMAX = 7, NBEMAX = 7 )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   EPS, ERR, THRESH\n      INTEGER            I, ISNUM, J, N, NALF, NBET, NIDIM, NINC, NKB,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, LTESTT, REWI, SAME, SFATAL, TRACE,\n     $                   TSTERR\n      CHARACTER*1        TRANS\n      CHARACTER*6        SNAMET\n      CHARACTER*32       SNAPS, SUMMRY\n*     .. Local Arrays ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ),\n     $                   ALF( NALMAX ), AS( NMAX*NMAX ), BET( NBEMAX ),\n     $                   X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( 2*NMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDMAX ), INC( NINMAX ), KB( NKBMAX )\n      LOGICAL            LTEST( NSUBS )\n      CHARACTER*6        SNAMES( NSUBS )\n*     .. External Functions ..\n      DOUBLE PRECISION   DDIFF\n      LOGICAL            LZE\n      EXTERNAL           DDIFF, LZE\n*     .. External Subroutines ..\n      EXTERNAL           ZCHK1, ZCHK2, ZCHK3, ZCHK4, ZCHK5, ZCHK6,\n     $                   ZCHKE, ZMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Data statements ..\n      DATA               SNAMES/'ZGEMV ', 'ZGBMV ', 'ZHEMV ', 'ZHBMV ',\n     $                   'ZHPMV ', 'ZTRMV ', 'ZTBMV ', 'ZTPMV ',\n     $                   'ZTRSV ', 'ZTBSV ', 'ZTPSV ', 'ZGERC ',\n     $                   'ZGERU ', 'ZHER  ', 'ZHPR  ', 'ZHER2 ',\n     $                   'ZHPR2 '/\n*     .. Executable Statements ..\n*\n*     Read name and unit number for summary output file and open file.\n*\n      READ( NIN, FMT = * )SUMMRY\n      READ( NIN, FMT = * )NOUT\n      OPEN( NOUT, FILE = SUMMRY, STATUS = 'UNKNOWN' )\n      NOUTC = NOUT\n*\n*     Read name and unit number for snapshot output file and open file.\n*\n      READ( NIN, FMT = * )SNAPS\n      READ( NIN, FMT = * )NTRA\n      TRACE = NTRA.GE.0\n      IF( TRACE )THEN\n         OPEN( NTRA, FILE = SNAPS, STATUS = 'UNKNOWN' )\n      END IF\n*     Read the flag that directs rewinding of the snapshot file.\n      READ( NIN, FMT = * )REWI\n      REWI = REWI.AND.TRACE\n*     Read the flag that directs stopping on any failure.\n      READ( NIN, FMT = * )SFATAL\n*     Read the flag that indicates whether error exits are to be tested.\n      READ( NIN, FMT = * )TSTERR\n*     Read the threshold value of the test ratio\n      READ( NIN, FMT = * )THRESH\n*\n*     Read and check the parameter values for the tests.\n*\n*     Values of N\n      READ( NIN, FMT = * )NIDIM\n      IF( NIDIM.LT.1.OR.NIDIM.GT.NIDMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'N', NIDMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( IDIM( I ), I = 1, NIDIM )\n      DO 10 I = 1, NIDIM\n         IF( IDIM( I ).LT.0.OR.IDIM( I ).GT.NMAX )THEN\n            WRITE( NOUT, FMT = 9996 )NMAX\n            GO TO 230\n         END IF\n   10 CONTINUE\n*     Values of K\n      READ( NIN, FMT = * )NKB\n      IF( NKB.LT.1.OR.NKB.GT.NKBMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'K', NKBMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( KB( I ), I = 1, NKB )\n      DO 20 I = 1, NKB\n         IF( KB( I ).LT.0 )THEN\n            WRITE( NOUT, FMT = 9995 )\n            GO TO 230\n         END IF\n   20 CONTINUE\n*     Values of INCX and INCY\n      READ( NIN, FMT = * )NINC\n      IF( NINC.LT.1.OR.NINC.GT.NINMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'INCX AND INCY', NINMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( INC( I ), I = 1, NINC )\n      DO 30 I = 1, NINC\n         IF( INC( I ).EQ.0.OR.ABS( INC( I ) ).GT.INCMAX )THEN\n            WRITE( NOUT, FMT = 9994 )INCMAX\n            GO TO 230\n         END IF\n   30 CONTINUE\n*     Values of ALPHA\n      READ( NIN, FMT = * )NALF\n      IF( NALF.LT.1.OR.NALF.GT.NALMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'ALPHA', NALMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( ALF( I ), I = 1, NALF )\n*     Values of BETA\n      READ( NIN, FMT = * )NBET\n      IF( NBET.LT.1.OR.NBET.GT.NBEMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'BETA', NBEMAX\n         GO TO 230\n      END IF\n      READ( NIN, FMT = * )( BET( I ), I = 1, NBET )\n*\n*     Report values of parameters.\n*\n      WRITE( NOUT, FMT = 9993 )\n      WRITE( NOUT, FMT = 9992 )( IDIM( I ), I = 1, NIDIM )\n      WRITE( NOUT, FMT = 9991 )( KB( I ), I = 1, NKB )\n      WRITE( NOUT, FMT = 9990 )( INC( I ), I = 1, NINC )\n      WRITE( NOUT, FMT = 9989 )( ALF( I ), I = 1, NALF )\n      WRITE( NOUT, FMT = 9988 )( BET( I ), I = 1, NBET )\n      IF( .NOT.TSTERR )THEN\n         WRITE( NOUT, FMT = * )\n         WRITE( NOUT, FMT = 9980 )\n      END IF\n      WRITE( NOUT, FMT = * )\n      WRITE( NOUT, FMT = 9999 )THRESH\n      WRITE( NOUT, FMT = * )\n*\n*     Read names of subroutines and flags which indicate\n*     whether they are to be tested.\n*\n      DO 40 I = 1, NSUBS\n         LTEST( I ) = .FALSE.\n   40 CONTINUE\n   50 READ( NIN, FMT = 9984, END = 80 )SNAMET, LTESTT\n      DO 60 I = 1, NSUBS\n         IF( SNAMET.EQ.SNAMES( I ) )\n     $      GO TO 70\n   60 CONTINUE\n      WRITE( NOUT, FMT = 9986 )SNAMET\n      STOP\n   70 LTEST( I ) = LTESTT\n      GO TO 50\n*\n   80 CONTINUE\n      CLOSE ( NIN )\n*\n*     Compute EPS (the machine precision).\n*\n      EPS = EPSILON(RZERO)\n      WRITE( NOUT, FMT = 9998 )EPS\n*\n*     Check the reliability of ZMVCH using exact data.\n*\n      N = MIN( 32, NMAX )\n      DO 120 J = 1, N\n         DO 110 I = 1, N\n            A( I, J ) = MAX( I - J + 1, 0 )\n  110    CONTINUE\n         X( J ) = J\n         Y( J ) = ZERO\n  120 CONTINUE\n      DO 130 J = 1, N\n         YY( J ) = J*( ( J + 1 )*J )/2 - ( ( J + 1 )*J*( J - 1 ) )/3\n  130 CONTINUE\n*     YY holds the exact result. On exit from ZMVCH YT holds\n*     the result computed by ZMVCH.\n      TRANS = 'N'\n      CALL ZMVCH( TRANS, N, N, ONE, A, NMAX, X, 1, ZERO, Y, 1, YT, G,\n     $            YY, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LZE( YY, YT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9985 )TRANS, SAME, ERR\n         STOP\n      END IF\n      TRANS = 'T'\n      CALL ZMVCH( TRANS, N, N, ONE, A, NMAX, X, -1, ZERO, Y, -1, YT, G,\n     $            YY, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LZE( YY, YT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9985 )TRANS, SAME, ERR\n         STOP\n      END IF\n*\n*     Test each subroutine in turn.\n*\n      DO 210 ISNUM = 1, NSUBS\n         WRITE( NOUT, FMT = * )\n         IF( .NOT.LTEST( ISNUM ) )THEN\n*           Subprogram is not to be tested.\n            WRITE( NOUT, FMT = 9983 )SNAMES( ISNUM )\n         ELSE\n            SRNAMT = SNAMES( ISNUM )\n*           Test error exits.\n            IF( TSTERR )THEN\n               CALL ZCHKE( ISNUM, SNAMES( ISNUM ), NOUT )\n               WRITE( NOUT, FMT = * )\n            END IF\n*           Test computations.\n            INFOT = 0\n            OK = .TRUE.\n            FATAL = .FALSE.\n            GO TO ( 140, 140, 150, 150, 150, 160, 160,\n     $              160, 160, 160, 160, 170, 170, 180,\n     $              180, 190, 190 )ISNUM\n*           Test ZGEMV, 01, and ZGBMV, 02.\n  140       CALL ZCHK1( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF,\n     $                  NBET, BET, NINC, INC, NMAX, INCMAX, A, AA, AS,\n     $                  X, XX, XS, Y, YY, YS, YT, G )\n            GO TO 200\n*           Test ZHEMV, 03, ZHBMV, 04, and ZHPMV, 05.\n  150       CALL ZCHK2( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF,\n     $                  NBET, BET, NINC, INC, NMAX, INCMAX, A, AA, AS,\n     $                  X, XX, XS, Y, YY, YS, YT, G )\n            GO TO 200\n*           Test ZTRMV, 06, ZTBMV, 07, ZTPMV, 08,\n*           ZTRSV, 09, ZTBSV, 10, and ZTPSV, 11.\n  160       CALL ZCHK3( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NKB, KB, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, Y, YY, YS, YT, G, Z )\n            GO TO 200\n*           Test ZGERC, 12, ZGERU, 13.\n  170       CALL ZCHK4( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n            GO TO 200\n*           Test ZHER, 14, and ZHPR, 15.\n  180       CALL ZCHK5( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n            GO TO 200\n*           Test ZHER2, 16, and ZHPR2, 17.\n  190       CALL ZCHK6( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC,\n     $                  NMAX, INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS,\n     $                  YT, G, Z )\n*\n  200       IF( FATAL.AND.SFATAL )\n     $         GO TO 220\n         END IF\n  210 CONTINUE\n      WRITE( NOUT, FMT = 9982 )\n      GO TO 240\n*\n  220 CONTINUE\n      WRITE( NOUT, FMT = 9981 )\n      GO TO 240\n*\n  230 CONTINUE\n      WRITE( NOUT, FMT = 9987 )\n*\n  240 CONTINUE\n      IF( TRACE )\n     $   CLOSE ( NTRA )\n      CLOSE ( NOUT )\n      STOP\n*\n 9999 FORMAT( ' ROUTINES PASS COMPUTATIONAL TESTS IF TEST RATIO IS LES',\n     $      'S THAN', F8.2 )\n 9998 FORMAT( ' RELATIVE MACHINE PRECISION IS TAKEN TO BE', 1P, D9.1 )\n 9997 FORMAT( ' NUMBER OF VALUES OF ', A, ' IS LESS THAN 1 OR GREATER ',\n     $      'THAN ', I2 )\n 9996 FORMAT( ' VALUE OF N IS LESS THAN 0 OR GREATER THAN ', I2 )\n 9995 FORMAT( ' VALUE OF K IS LESS THAN 0' )\n 9994 FORMAT( ' ABSOLUTE VALUE OF INCX OR INCY IS 0 OR GREATER THAN ',\n     $      I2 )\n 9993 FORMAT( ' TESTS OF THE COMPLEX*16       LEVEL 2 BLAS', //' THE F',\n     $      'OLLOWING PARAMETER VALUES WILL BE USED:' )\n 9992 FORMAT( '   FOR N              ', 9I6 )\n 9991 FORMAT( '   FOR K              ', 7I6 )\n 9990 FORMAT( '   FOR INCX AND INCY  ', 7I6 )\n 9989 FORMAT( '   FOR ALPHA          ',\n     $      7( '(', F4.1, ',', F4.1, ')  ', : ) )\n 9988 FORMAT( '   FOR BETA           ',\n     $      7( '(', F4.1, ',', F4.1, ')  ', : ) )\n 9987 FORMAT( ' AMEND DATA FILE OR INCREASE ARRAY SIZES IN PROGRAM',\n     $      /' ******* TESTS ABANDONED *******' )\n 9986 FORMAT( ' SUBPROGRAM NAME ', A6, ' NOT RECOGNIZED', /' ******* T',\n     $      'ESTS ABANDONED *******' )\n 9985 FORMAT( ' ERROR IN ZMVCH -  IN-LINE DOT PRODUCTS ARE BEING EVALU',\n     $      'ATED WRONGLY.', /' ZMVCH WAS CALLED WITH TRANS = ', A1,\n     $      ' AND RETURNED SAME = ', L1, ' AND ERR = ', F12.3, '.', /\n     $   ' THIS MAY BE DUE TO FAULTS IN THE ARITHMETIC OR THE COMPILER.'\n     $      , /' ******* TESTS ABANDONED *******' )\n 9984 FORMAT( A6, L2 )\n 9983 FORMAT( 1X, A6, ' WAS NOT TESTED' )\n 9982 FORMAT( /' END OF TESTS' )\n 9981 FORMAT( /' ******* FATAL ERROR - TESTS ABANDONED *******' )\n 9980 FORMAT( ' ERROR-EXITS WILL NOT BE TESTED' )\n*\n*     End of ZBLAT2.\n*\n      END\n      SUBROUTINE ZCHK1( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF, NBET,\n     $                  BET, NINC, INC, NMAX, INCMAX, A, AA, AS, X, XX,\n     $                  XS, Y, YY, YS, YT, G )\n*\n*  Tests ZGEMV and ZGBMV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO, HALF\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   HALF = ( 0.5D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NALF, NBET, NIDIM, NINC, NKB, NMAX,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), BET( NBET ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XX( NMAX*INCMAX ),\n     $                   Y( NMAX ), YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, ALS, BETA, BLS, TRANSL\n      DOUBLE PRECISION   ERR, ERRMAX\n      INTEGER            I, IA, IB, IC, IKU, IM, IN, INCX, INCXS, INCY,\n     $                   INCYS, IX, IY, KL, KLS, KU, KUS, LAA, LDA,\n     $                   LDAS, LX, LY, M, ML, MS, N, NARGS, NC, ND, NK,\n     $                   NL, NS\n      LOGICAL            BANDED, FULL, NULL, RESET, SAME, TRAN\n      CHARACTER*1        TRANS, TRANSS\n      CHARACTER*3        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZGBMV, ZGEMV, ZMAKE, ZMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'NTC'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'E'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 11\n      ELSE IF( BANDED )THEN\n         NARGS = 13\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 120 IN = 1, NIDIM\n         N = IDIM( IN )\n         ND = N/2 + 1\n*\n         DO 110 IM = 1, 2\n            IF( IM.EQ.1 )\n     $         M = MAX( N - ND, 0 )\n            IF( IM.EQ.2 )\n     $         M = MIN( N + ND, NMAX )\n*\n            IF( BANDED )THEN\n               NK = NKB\n            ELSE\n               NK = 1\n            END IF\n            DO 100 IKU = 1, NK\n               IF( BANDED )THEN\n                  KU = KB( IKU )\n                  KL = MAX( KU - 1, 0 )\n               ELSE\n                  KU = N - 1\n                  KL = M - 1\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               IF( BANDED )THEN\n                  LDA = KL + KU + 1\n               ELSE\n                  LDA = M\n               END IF\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 100\n               LAA = LDA*N\n               NULL = N.LE.0.OR.M.LE.0\n*\n*              Generate the matrix A.\n*\n               TRANSL = ZERO\n               CALL ZMAKE( SNAME( 2: 3 ), ' ', ' ', M, N, A, NMAX, AA,\n     $                     LDA, KL, KU, RESET, TRANSL )\n*\n               DO 90 IC = 1, 3\n                  TRANS = ICH( IC: IC )\n                  TRAN = TRANS.EQ.'T'.OR.TRANS.EQ.'C'\n*\n                  IF( TRAN )THEN\n                     ML = N\n                     NL = M\n                  ELSE\n                     ML = M\n                     NL = N\n                  END IF\n*\n                  DO 80 IX = 1, NINC\n                     INCX = INC( IX )\n                     LX = ABS( INCX )*NL\n*\n*                    Generate the vector X.\n*\n                     TRANSL = HALF\n                     CALL ZMAKE( 'GE', ' ', ' ', 1, NL, X, 1, XX,\n     $                           ABS( INCX ), 0, NL - 1, RESET, TRANSL )\n                     IF( NL.GT.1 )THEN\n                        X( NL/2 ) = ZERO\n                        XX( 1 + ABS( INCX )*( NL/2 - 1 ) ) = ZERO\n                     END IF\n*\n                     DO 70 IY = 1, NINC\n                        INCY = INC( IY )\n                        LY = ABS( INCY )*ML\n*\n                        DO 60 IA = 1, NALF\n                           ALPHA = ALF( IA )\n*\n                           DO 50 IB = 1, NBET\n                              BETA = BET( IB )\n*\n*                             Generate the vector Y.\n*\n                              TRANSL = ZERO\n                              CALL ZMAKE( 'GE', ' ', ' ', 1, ML, Y, 1,\n     $                                    YY, ABS( INCY ), 0, ML - 1,\n     $                                    RESET, TRANSL )\n*\n                              NC = NC + 1\n*\n*                             Save every datum before calling the\n*                             subroutine.\n*\n                              TRANSS = TRANS\n                              MS = M\n                              NS = N\n                              KLS = KL\n                              KUS = KU\n                              ALS = ALPHA\n                              DO 10 I = 1, LAA\n                                 AS( I ) = AA( I )\n   10                         CONTINUE\n                              LDAS = LDA\n                              DO 20 I = 1, LX\n                                 XS( I ) = XX( I )\n   20                         CONTINUE\n                              INCXS = INCX\n                              BLS = BETA\n                              DO 30 I = 1, LY\n                                 YS( I ) = YY( I )\n   30                         CONTINUE\n                              INCYS = INCY\n*\n*                             Call the subroutine.\n*\n                              IF( FULL )THEN\n                                 IF( TRACE )\n     $                              WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                              TRANS, M, N, ALPHA, LDA, INCX, BETA,\n     $                              INCY\n                                 IF( REWI )\n     $                              REWIND NTRA\n                                 CALL ZGEMV( TRANS, M, N, ALPHA, AA,\n     $                                       LDA, XX, INCX, BETA, YY,\n     $                                       INCY )\n                              ELSE IF( BANDED )THEN\n                                 IF( TRACE )\n     $                              WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                              TRANS, M, N, KL, KU, ALPHA, LDA,\n     $                              INCX, BETA, INCY\n                                 IF( REWI )\n     $                              REWIND NTRA\n                                 CALL ZGBMV( TRANS, M, N, KL, KU, ALPHA,\n     $                                       AA, LDA, XX, INCX, BETA,\n     $                                       YY, INCY )\n                              END IF\n*\n*                             Check if error-exit was taken incorrectly.\n*\n                              IF( .NOT.OK )THEN\n                                 WRITE( NOUT, FMT = 9993 )\n                                 FATAL = .TRUE.\n                                 GO TO 130\n                              END IF\n*\n*                             See what data changed inside subroutines.\n*\n                              ISAME( 1 ) = TRANS.EQ.TRANSS\n                              ISAME( 2 ) = MS.EQ.M\n                              ISAME( 3 ) = NS.EQ.N\n                              IF( FULL )THEN\n                                 ISAME( 4 ) = ALS.EQ.ALPHA\n                                 ISAME( 5 ) = LZE( AS, AA, LAA )\n                                 ISAME( 6 ) = LDAS.EQ.LDA\n                                 ISAME( 7 ) = LZE( XS, XX, LX )\n                                 ISAME( 8 ) = INCXS.EQ.INCX\n                                 ISAME( 9 ) = BLS.EQ.BETA\n                                 IF( NULL )THEN\n                                    ISAME( 10 ) = LZE( YS, YY, LY )\n                                 ELSE\n                                    ISAME( 10 ) = LZERES( 'GE', ' ', 1,\n     $                                            ML, YS, YY,\n     $                                            ABS( INCY ) )\n                                 END IF\n                                 ISAME( 11 ) = INCYS.EQ.INCY\n                              ELSE IF( BANDED )THEN\n                                 ISAME( 4 ) = KLS.EQ.KL\n                                 ISAME( 5 ) = KUS.EQ.KU\n                                 ISAME( 6 ) = ALS.EQ.ALPHA\n                                 ISAME( 7 ) = LZE( AS, AA, LAA )\n                                 ISAME( 8 ) = LDAS.EQ.LDA\n                                 ISAME( 9 ) = LZE( XS, XX, LX )\n                                 ISAME( 10 ) = INCXS.EQ.INCX\n                                 ISAME( 11 ) = BLS.EQ.BETA\n                                 IF( NULL )THEN\n                                    ISAME( 12 ) = LZE( YS, YY, LY )\n                                 ELSE\n                                    ISAME( 12 ) = LZERES( 'GE', ' ', 1,\n     $                                            ML, YS, YY,\n     $                                            ABS( INCY ) )\n                                 END IF\n                                 ISAME( 13 ) = INCYS.EQ.INCY\n                              END IF\n*\n*                             If data was incorrectly changed, report\n*                             and return.\n*\n                              SAME = .TRUE.\n                              DO 40 I = 1, NARGS\n                                 SAME = SAME.AND.ISAME( I )\n                                 IF( .NOT.ISAME( I ) )\n     $                              WRITE( NOUT, FMT = 9998 )I\n   40                         CONTINUE\n                              IF( .NOT.SAME )THEN\n                                 FATAL = .TRUE.\n                                 GO TO 130\n                              END IF\n*\n                              IF( .NOT.NULL )THEN\n*\n*                                Check the result.\n*\n                                 CALL ZMVCH( TRANS, M, N, ALPHA, A,\n     $                                       NMAX, X, INCX, BETA, Y,\n     $                                       INCY, YT, G, YY, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                                 ERRMAX = MAX( ERRMAX, ERR )\n*                                If got really bad answer, report and\n*                                return.\n                                 IF( FATAL )\n     $                              GO TO 130\n                              ELSE\n*                                Avoid repeating tests with M.le.0 or\n*                                N.le.0.\n                                 GO TO 110\n                              END IF\n*\n   50                      CONTINUE\n*\n   60                   CONTINUE\n*\n   70                CONTINUE\n*\n   80             CONTINUE\n*\n   90          CONTINUE\n*\n  100       CONTINUE\n*\n  110    CONTINUE\n*\n  120 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 140\n*\n  130 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, TRANS, M, N, ALPHA, LDA,\n     $      INCX, BETA, INCY\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, TRANS, M, N, KL, KU,\n     $      ALPHA, LDA, INCX, BETA, INCY\n      END IF\n*\n  140 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 4( I3, ',' ), '(',\n     $      F4.1, ',', F4.1, '), A,', I3, ', X,', I2, ',(', F4.1, ',',\n     $      F4.1, '), Y,', I2, ') .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 2( I3, ',' ), '(',\n     $      F4.1, ',', F4.1, '), A,', I3, ', X,', I2, ',(', F4.1, ',',\n     $      F4.1, '), Y,', I2, ')         .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK1.\n*\n      END\n      SUBROUTINE ZCHK2( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NALF, ALF, NBET,\n     $                  BET, NINC, INC, NMAX, INCMAX, A, AA, AS, X, XX,\n     $                  XS, Y, YY, YS, YT, G )\n*\n*  Tests ZHEMV, ZHBMV and ZHPMV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO, HALF\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   HALF = ( 0.5D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NALF, NBET, NIDIM, NINC, NKB, NMAX,\n     $                   NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), BET( NBET ), X( NMAX ),\n     $                   XS( NMAX*INCMAX ), XX( NMAX*INCMAX ),\n     $                   Y( NMAX ), YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, ALS, BETA, BLS, TRANSL\n      DOUBLE PRECISION   ERR, ERRMAX\n      INTEGER            I, IA, IB, IC, IK, IN, INCX, INCXS, INCY,\n     $                   INCYS, IX, IY, K, KS, LAA, LDA, LDAS, LX, LY,\n     $                   N, NARGS, NC, NK, NS\n      LOGICAL            BANDED, FULL, NULL, PACKED, RESET, SAME\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZHBMV, ZHEMV, ZHPMV, ZMAKE, ZMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'E'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 10\n      ELSE IF( BANDED )THEN\n         NARGS = 11\n      ELSE IF( PACKED )THEN\n         NARGS = 9\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 110 IN = 1, NIDIM\n         N = IDIM( IN )\n*\n         IF( BANDED )THEN\n            NK = NKB\n         ELSE\n            NK = 1\n         END IF\n         DO 100 IK = 1, NK\n            IF( BANDED )THEN\n               K = KB( IK )\n            ELSE\n               K = N - 1\n            END IF\n*           Set LDA to 1 more than minimum value if room.\n            IF( BANDED )THEN\n               LDA = K + 1\n            ELSE\n               LDA = N\n            END IF\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 100\n            IF( PACKED )THEN\n               LAA = ( N*( N + 1 ) )/2\n            ELSE\n               LAA = LDA*N\n            END IF\n            NULL = N.LE.0\n*\n            DO 90 IC = 1, 2\n               UPLO = ICH( IC: IC )\n*\n*              Generate the matrix A.\n*\n               TRANSL = ZERO\n               CALL ZMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A, NMAX, AA,\n     $                     LDA, K, K, RESET, TRANSL )\n*\n               DO 80 IX = 1, NINC\n                  INCX = INC( IX )\n                  LX = ABS( INCX )*N\n*\n*                 Generate the vector X.\n*\n                  TRANSL = HALF\n                  CALL ZMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX,\n     $                        ABS( INCX ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     X( N/2 ) = ZERO\n                     XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 70 IY = 1, NINC\n                     INCY = INC( IY )\n                     LY = ABS( INCY )*N\n*\n                     DO 60 IA = 1, NALF\n                        ALPHA = ALF( IA )\n*\n                        DO 50 IB = 1, NBET\n                           BETA = BET( IB )\n*\n*                          Generate the vector Y.\n*\n                           TRANSL = ZERO\n                           CALL ZMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                                 ABS( INCY ), 0, N - 1, RESET,\n     $                                 TRANSL )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           UPLOS = UPLO\n                           NS = N\n                           KS = K\n                           ALS = ALPHA\n                           DO 10 I = 1, LAA\n                              AS( I ) = AA( I )\n   10                      CONTINUE\n                           LDAS = LDA\n                           DO 20 I = 1, LX\n                              XS( I ) = XX( I )\n   20                      CONTINUE\n                           INCXS = INCX\n                           BLS = BETA\n                           DO 30 I = 1, LY\n                              YS( I ) = YY( I )\n   30                      CONTINUE\n                           INCYS = INCY\n*\n*                          Call the subroutine.\n*\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, N, ALPHA, LDA, INCX, BETA, INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZHEMV( UPLO, N, ALPHA, AA, LDA, XX,\n     $                                    INCX, BETA, YY, INCY )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, N, K, ALPHA, LDA, INCX, BETA,\n     $                           INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZHBMV( UPLO, N, K, ALPHA, AA, LDA,\n     $                                    XX, INCX, BETA, YY, INCY )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, N, ALPHA, INCX, BETA, INCY\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZHPMV( UPLO, N, ALPHA, AA, XX, INCX,\n     $                                    BETA, YY, INCY )\n                           END IF\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9992 )\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = UPLO.EQ.UPLOS\n                           ISAME( 2 ) = NS.EQ.N\n                           IF( FULL )THEN\n                              ISAME( 3 ) = ALS.EQ.ALPHA\n                              ISAME( 4 ) = LZE( AS, AA, LAA )\n                              ISAME( 5 ) = LDAS.EQ.LDA\n                              ISAME( 6 ) = LZE( XS, XX, LX )\n                              ISAME( 7 ) = INCXS.EQ.INCX\n                              ISAME( 8 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 9 ) = LZE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 9 ) = LZERES( 'GE', ' ', 1, N,\n     $                                        YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 10 ) = INCYS.EQ.INCY\n                           ELSE IF( BANDED )THEN\n                              ISAME( 3 ) = KS.EQ.K\n                              ISAME( 4 ) = ALS.EQ.ALPHA\n                              ISAME( 5 ) = LZE( AS, AA, LAA )\n                              ISAME( 6 ) = LDAS.EQ.LDA\n                              ISAME( 7 ) = LZE( XS, XX, LX )\n                              ISAME( 8 ) = INCXS.EQ.INCX\n                              ISAME( 9 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 10 ) = LZE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 10 ) = LZERES( 'GE', ' ', 1, N,\n     $                                         YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 11 ) = INCYS.EQ.INCY\n                           ELSE IF( PACKED )THEN\n                              ISAME( 3 ) = ALS.EQ.ALPHA\n                              ISAME( 4 ) = LZE( AS, AA, LAA )\n                              ISAME( 5 ) = LZE( XS, XX, LX )\n                              ISAME( 6 ) = INCXS.EQ.INCX\n                              ISAME( 7 ) = BLS.EQ.BETA\n                              IF( NULL )THEN\n                                 ISAME( 8 ) = LZE( YS, YY, LY )\n                              ELSE\n                                 ISAME( 8 ) = LZERES( 'GE', ' ', 1, N,\n     $                                        YS, YY, ABS( INCY ) )\n                              END IF\n                              ISAME( 9 ) = INCYS.EQ.INCY\n                           END IF\n*\n*                          If data was incorrectly changed, report and\n*                          return.\n*\n                           SAME = .TRUE.\n                           DO 40 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   40                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n*\n*                             Check the result.\n*\n                              CALL ZMVCH( 'N', N, N, ALPHA, A, NMAX, X,\n     $                                    INCX, BETA, Y, INCY, YT, G,\n     $                                    YY, EPS, ERR, FATAL, NOUT,\n     $                                    .TRUE. )\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 120\n                           ELSE\n*                             Avoid repeating tests with N.le.0\n                              GO TO 110\n                           END IF\n*\n   50                   CONTINUE\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, ALPHA, LDA, INCX,\n     $      BETA, INCY\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, K, ALPHA, LDA,\n     $      INCX, BETA, INCY\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, UPLO, N, ALPHA, INCX,\n     $      BETA, INCY\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',(', F4.1, ',',\n     $      F4.1, '), AP, X,', I2, ',(', F4.1, ',', F4.1, '), Y,', I2,\n     $      ')                .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', 2( I3, ',' ), '(',\n     $      F4.1, ',', F4.1, '), A,', I3, ', X,', I2, ',(', F4.1, ',',\n     $      F4.1, '), Y,', I2, ')         .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',(', F4.1, ',',\n     $      F4.1, '), A,', I3, ', X,', I2, ',(', F4.1, ',', F4.1, '), ',\n     $      'Y,', I2, ')             .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK2.\n*\n      END\n      SUBROUTINE ZCHK3( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NKB, KB, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, XT, G, Z )\n*\n*  Tests ZTRMV, ZTBMV, ZTPMV, ZTRSV, ZTBSV and ZTPSV.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO, HALF, ONE\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   HALF = ( 0.5D0, 0.0D0 ),\n     $                   ONE = ( 1.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NIDIM, NINC, NKB, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ),\n     $                   AS( NMAX*NMAX ), X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XT( NMAX ), XX( NMAX*INCMAX ), Z( NMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC ), KB( NKB )\n*     .. Local Scalars ..\n      COMPLEX*16         TRANSL\n      DOUBLE PRECISION   ERR, ERRMAX\n      INTEGER            I, ICD, ICT, ICU, IK, IN, INCX, INCXS, IX, K,\n     $                   KS, LAA, LDA, LDAS, LX, N, NARGS, NC, NK, NS\n      LOGICAL            BANDED, FULL, NULL, PACKED, RESET, SAME\n      CHARACTER*1        DIAG, DIAGS, TRANS, TRANSS, UPLO, UPLOS\n      CHARACTER*2        ICHD, ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZMAKE, ZMVCH, ZTBMV, ZTBSV, ZTPMV, ZTPSV,\n     $                   ZTRMV, ZTRSV\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHU/'UL'/, ICHT/'NTC'/, ICHD/'UN'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'R'\n      BANDED = SNAME( 3: 3 ).EQ.'B'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 8\n      ELSE IF( BANDED )THEN\n         NARGS = 9\n      ELSE IF( PACKED )THEN\n         NARGS = 7\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*     Set up zero vector for ZMVCH.\n      DO 10 I = 1, NMAX\n         Z( I ) = ZERO\n   10 CONTINUE\n*\n      DO 110 IN = 1, NIDIM\n         N = IDIM( IN )\n*\n         IF( BANDED )THEN\n            NK = NKB\n         ELSE\n            NK = 1\n         END IF\n         DO 100 IK = 1, NK\n            IF( BANDED )THEN\n               K = KB( IK )\n            ELSE\n               K = N - 1\n            END IF\n*           Set LDA to 1 more than minimum value if room.\n            IF( BANDED )THEN\n               LDA = K + 1\n            ELSE\n               LDA = N\n            END IF\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 100\n            IF( PACKED )THEN\n               LAA = ( N*( N + 1 ) )/2\n            ELSE\n               LAA = LDA*N\n            END IF\n            NULL = N.LE.0\n*\n            DO 90 ICU = 1, 2\n               UPLO = ICHU( ICU: ICU )\n*\n               DO 80 ICT = 1, 3\n                  TRANS = ICHT( ICT: ICT )\n*\n                  DO 70 ICD = 1, 2\n                     DIAG = ICHD( ICD: ICD )\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL ZMAKE( SNAME( 2: 3 ), UPLO, DIAG, N, N, A,\n     $                           NMAX, AA, LDA, K, K, RESET, TRANSL )\n*\n                     DO 60 IX = 1, NINC\n                        INCX = INC( IX )\n                        LX = ABS( INCX )*N\n*\n*                       Generate the vector X.\n*\n                        TRANSL = HALF\n                        CALL ZMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX,\n     $                              ABS( INCX ), 0, N - 1, RESET,\n     $                              TRANSL )\n                        IF( N.GT.1 )THEN\n                           X( N/2 ) = ZERO\n                           XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n                        END IF\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        DIAGS = DIAG\n                        NS = N\n                        KS = K\n                        DO 20 I = 1, LAA\n                           AS( I ) = AA( I )\n   20                   CONTINUE\n                        LDAS = LDA\n                        DO 30 I = 1, LX\n                           XS( I ) = XX( I )\n   30                   CONTINUE\n                        INCXS = INCX\n*\n*                       Call the subroutine.\n*\n                        IF( SNAME( 4: 5 ).EQ.'MV' )THEN\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZTRMV( UPLO, TRANS, DIAG, N, AA, LDA,\n     $                                    XX, INCX )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, K, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZTBMV( UPLO, TRANS, DIAG, N, K, AA,\n     $                                    LDA, XX, INCX )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZTPMV( UPLO, TRANS, DIAG, N, AA, XX,\n     $                                    INCX )\n                           END IF\n                        ELSE IF( SNAME( 4: 5 ).EQ.'SV' )THEN\n                           IF( FULL )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9993 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZTRSV( UPLO, TRANS, DIAG, N, AA, LDA,\n     $                                    XX, INCX )\n                           ELSE IF( BANDED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9994 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, K, LDA, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZTBSV( UPLO, TRANS, DIAG, N, K, AA,\n     $                                    LDA, XX, INCX )\n                           ELSE IF( PACKED )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           UPLO, TRANS, DIAG, N, INCX\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZTPSV( UPLO, TRANS, DIAG, N, AA, XX,\n     $                                    INCX )\n                           END IF\n                        END IF\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9992 )\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLO.EQ.UPLOS\n                        ISAME( 2 ) = TRANS.EQ.TRANSS\n                        ISAME( 3 ) = DIAG.EQ.DIAGS\n                        ISAME( 4 ) = NS.EQ.N\n                        IF( FULL )THEN\n                           ISAME( 5 ) = LZE( AS, AA, LAA )\n                           ISAME( 6 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 7 ) = LZE( XS, XX, LX )\n                           ELSE\n                              ISAME( 7 ) = LZERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 8 ) = INCXS.EQ.INCX\n                        ELSE IF( BANDED )THEN\n                           ISAME( 5 ) = KS.EQ.K\n                           ISAME( 6 ) = LZE( AS, AA, LAA )\n                           ISAME( 7 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 8 ) = LZE( XS, XX, LX )\n                           ELSE\n                              ISAME( 8 ) = LZERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 9 ) = INCXS.EQ.INCX\n                        ELSE IF( PACKED )THEN\n                           ISAME( 5 ) = LZE( AS, AA, LAA )\n                           IF( NULL )THEN\n                              ISAME( 6 ) = LZE( XS, XX, LX )\n                           ELSE\n                              ISAME( 6 ) = LZERES( 'GE', ' ', 1, N, XS,\n     $                                     XX, ABS( INCX ) )\n                           END IF\n                           ISAME( 7 ) = INCXS.EQ.INCX\n                        END IF\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n                           IF( SNAME( 4: 5 ).EQ.'MV' )THEN\n*\n*                             Check the result.\n*\n                              CALL ZMVCH( TRANS, N, N, ONE, A, NMAX, X,\n     $                                    INCX, ZERO, Z, INCX, XT, G,\n     $                                    XX, EPS, ERR, FATAL, NOUT,\n     $                                    .TRUE. )\n                           ELSE IF( SNAME( 4: 5 ).EQ.'SV' )THEN\n*\n*                             Compute approximation to original vector.\n*\n                              DO 50 I = 1, N\n                                 Z( I ) = XX( 1 + ( I - 1 )*\n     $                                    ABS( INCX ) )\n                                 XX( 1 + ( I - 1 )*ABS( INCX ) )\n     $                              = X( I )\n   50                         CONTINUE\n                              CALL ZMVCH( TRANS, N, N, ONE, A, NMAX, Z,\n     $                                    INCX, ZERO, X, INCX, XT, G,\n     $                                    XX, EPS, ERR, FATAL, NOUT,\n     $                                    .FALSE. )\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 120\n                        ELSE\n*                          Avoid repeating tests with N.le.0.\n                           GO TO 110\n                        END IF\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, TRANS, DIAG, N, LDA,\n     $      INCX\n      ELSE IF( BANDED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, DIAG, N, K,\n     $      LDA, INCX\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9995 )NC, SNAME, UPLO, TRANS, DIAG, N, INCX\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), I3, ', AP, ',\n     $      'X,', I2, ')                                      .' )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), 2( I3, ',' ),\n     $      ' A,', I3, ', X,', I2, ')                               .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(', 3( '''', A1, ''',' ), I3, ', A,',\n     $      I3, ', X,', I2, ')                                   .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK3.\n*\n      END\n      SUBROUTINE ZCHK4( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests ZGERC and ZGERU.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO, HALF, ONE\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   HALF = ( 0.5D0, 0.0D0 ),\n     $                   ONE = ( 1.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, ALS, TRANSL\n      DOUBLE PRECISION   ERR, ERRMAX\n      INTEGER            I, IA, IM, IN, INCX, INCXS, INCY, INCYS, IX,\n     $                   IY, J, LAA, LDA, LDAS, LX, LY, M, MS, N, NARGS,\n     $                   NC, ND, NS\n      LOGICAL            CONJ, NULL, RESET, SAME\n*     .. Local Arrays ..\n      COMPLEX*16         W( 1 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZGERC, ZGERU, ZMAKE, ZMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, DCONJG, MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n      CONJ = SNAME( 5: 5 ).EQ.'C'\n*     Define the number of arguments.\n      NARGS = 9\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 120 IN = 1, NIDIM\n         N = IDIM( IN )\n         ND = N/2 + 1\n*\n         DO 110 IM = 1, 2\n            IF( IM.EQ.1 )\n     $         M = MAX( N - ND, 0 )\n            IF( IM.EQ.2 )\n     $         M = MIN( N + ND, NMAX )\n*\n*           Set LDA to 1 more than minimum value if room.\n            LDA = M\n            IF( LDA.LT.NMAX )\n     $         LDA = LDA + 1\n*           Skip tests if not enough room.\n            IF( LDA.GT.NMAX )\n     $         GO TO 110\n            LAA = LDA*N\n            NULL = N.LE.0.OR.M.LE.0\n*\n            DO 100 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*M\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL ZMAKE( 'GE', ' ', ' ', 1, M, X, 1, XX, ABS( INCX ),\n     $                     0, M - 1, RESET, TRANSL )\n               IF( M.GT.1 )THEN\n                  X( M/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( M/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 90 IY = 1, NINC\n                  INCY = INC( IY )\n                  LY = ABS( INCY )*N\n*\n*                 Generate the vector Y.\n*\n                  TRANSL = ZERO\n                  CALL ZMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                        ABS( INCY ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     Y( N/2 ) = ZERO\n                     YY( 1 + ABS( INCY )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 80 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL ZMAKE( SNAME( 2: 3 ), ' ', ' ', M, N, A, NMAX,\n     $                           AA, LDA, M - 1, N - 1, RESET, TRANSL )\n*\n                     NC = NC + 1\n*\n*                    Save every datum before calling the subroutine.\n*\n                     MS = M\n                     NS = N\n                     ALS = ALPHA\n                     DO 10 I = 1, LAA\n                        AS( I ) = AA( I )\n   10                CONTINUE\n                     LDAS = LDA\n                     DO 20 I = 1, LX\n                        XS( I ) = XX( I )\n   20                CONTINUE\n                     INCXS = INCX\n                     DO 30 I = 1, LY\n                        YS( I ) = YY( I )\n   30                CONTINUE\n                     INCYS = INCY\n*\n*                    Call the subroutine.\n*\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9994 )NC, SNAME, M, N,\n     $                  ALPHA, INCX, INCY, LDA\n                     IF( CONJ )THEN\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL ZGERC( M, N, ALPHA, XX, INCX, YY, INCY, AA,\n     $                              LDA )\n                     ELSE\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL ZGERU( M, N, ALPHA, XX, INCX, YY, INCY, AA,\n     $                              LDA )\n                     END IF\n*\n*                    Check if error-exit was taken incorrectly.\n*\n                     IF( .NOT.OK )THEN\n                        WRITE( NOUT, FMT = 9993 )\n                        FATAL = .TRUE.\n                        GO TO 140\n                     END IF\n*\n*                    See what data changed inside subroutine.\n*\n                     ISAME( 1 ) = MS.EQ.M\n                     ISAME( 2 ) = NS.EQ.N\n                     ISAME( 3 ) = ALS.EQ.ALPHA\n                     ISAME( 4 ) = LZE( XS, XX, LX )\n                     ISAME( 5 ) = INCXS.EQ.INCX\n                     ISAME( 6 ) = LZE( YS, YY, LY )\n                     ISAME( 7 ) = INCYS.EQ.INCY\n                     IF( NULL )THEN\n                        ISAME( 8 ) = LZE( AS, AA, LAA )\n                     ELSE\n                        ISAME( 8 ) = LZERES( 'GE', ' ', M, N, AS, AA,\n     $                               LDA )\n                     END IF\n                     ISAME( 9 ) = LDAS.EQ.LDA\n*\n*                    If data was incorrectly changed, report and return.\n*\n                     SAME = .TRUE.\n                     DO 40 I = 1, NARGS\n                        SAME = SAME.AND.ISAME( I )\n                        IF( .NOT.ISAME( I ) )\n     $                     WRITE( NOUT, FMT = 9998 )I\n   40                CONTINUE\n                     IF( .NOT.SAME )THEN\n                        FATAL = .TRUE.\n                        GO TO 140\n                     END IF\n*\n                     IF( .NOT.NULL )THEN\n*\n*                       Check the result column by column.\n*\n                        IF( INCX.GT.0 )THEN\n                           DO 50 I = 1, M\n                              Z( I ) = X( I )\n   50                      CONTINUE\n                        ELSE\n                           DO 60 I = 1, M\n                              Z( I ) = X( M - I + 1 )\n   60                      CONTINUE\n                        END IF\n                        DO 70 J = 1, N\n                           IF( INCY.GT.0 )THEN\n                              W( 1 ) = Y( J )\n                           ELSE\n                              W( 1 ) = Y( N - J + 1 )\n                           END IF\n                           IF( CONJ )\n     $                        W( 1 ) = DCONJG( W( 1 ) )\n                           CALL ZMVCH( 'N', M, 1, ALPHA, Z, NMAX, W, 1,\n     $                                 ONE, A( 1, J ), 1, YT, G,\n     $                                 AA( 1 + ( J - 1 )*LDA ), EPS,\n     $                                 ERR, FATAL, NOUT, .TRUE. )\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 130\n   70                   CONTINUE\n                     ELSE\n*                       Avoid repeating tests with M.le.0 or N.le.0.\n                        GO TO 110\n                     END IF\n*\n   80             CONTINUE\n*\n   90          CONTINUE\n*\n  100       CONTINUE\n*\n  110    CONTINUE\n*\n  120 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 150\n*\n  130 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  140 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9994 )NC, SNAME, M, N, ALPHA, INCX, INCY, LDA\n*\n  150 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( I3, ',' ), '(', F4.1, ',', F4.1,\n     $      '), X,', I2, ', Y,', I2, ', A,', I3, ')                   ',\n     $      '      .' )\n 9993 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK4.\n*\n      END\n      SUBROUTINE ZCHK5( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests ZHER and ZHPR.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO, HALF, ONE\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   HALF = ( 0.5D0, 0.0D0 ),\n     $                   ONE = ( 1.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, TRANSL\n      DOUBLE PRECISION   ERR, ERRMAX, RALPHA, RALS\n      INTEGER            I, IA, IC, IN, INCX, INCXS, IX, J, JA, JJ, LAA,\n     $                   LDA, LDAS, LJ, LX, N, NARGS, NC, NS\n      LOGICAL            FULL, NULL, PACKED, RESET, SAME, UPPER\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      COMPLEX*16         W( 1 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZHER, ZHPR, ZMAKE, ZMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, DBLE, DCMPLX, DCONJG, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'E'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 7\n      ELSE IF( PACKED )THEN\n         NARGS = 6\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 100 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDA to 1 more than minimum value if room.\n         LDA = N\n         IF( LDA.LT.NMAX )\n     $      LDA = LDA + 1\n*        Skip tests if not enough room.\n         IF( LDA.GT.NMAX )\n     $      GO TO 100\n         IF( PACKED )THEN\n            LAA = ( N*( N + 1 ) )/2\n         ELSE\n            LAA = LDA*N\n         END IF\n*\n         DO 90 IC = 1, 2\n            UPLO = ICH( IC: IC )\n            UPPER = UPLO.EQ.'U'\n*\n            DO 80 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*N\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL ZMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX, ABS( INCX ),\n     $                     0, N - 1, RESET, TRANSL )\n               IF( N.GT.1 )THEN\n                  X( N/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 70 IA = 1, NALF\n                  RALPHA = DBLE( ALF( IA ) )\n                  ALPHA = DCMPLX( RALPHA, RZERO )\n                  NULL = N.LE.0.OR.RALPHA.EQ.RZERO\n*\n*                 Generate the matrix A.\n*\n                  TRANSL = ZERO\n                  CALL ZMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A, NMAX,\n     $                        AA, LDA, N - 1, N - 1, RESET, TRANSL )\n*\n                  NC = NC + 1\n*\n*                 Save every datum before calling the subroutine.\n*\n                  UPLOS = UPLO\n                  NS = N\n                  RALS = RALPHA\n                  DO 10 I = 1, LAA\n                     AS( I ) = AA( I )\n   10             CONTINUE\n                  LDAS = LDA\n                  DO 20 I = 1, LX\n                     XS( I ) = XX( I )\n   20             CONTINUE\n                  INCXS = INCX\n*\n*                 Call the subroutine.\n*\n                  IF( FULL )THEN\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO, N,\n     $                  RALPHA, INCX, LDA\n                     IF( REWI )\n     $                  REWIND NTRA\n                     CALL ZHER( UPLO, N, RALPHA, XX, INCX, AA, LDA )\n                  ELSE IF( PACKED )THEN\n                     IF( TRACE )\n     $                  WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO, N,\n     $                  RALPHA, INCX\n                     IF( REWI )\n     $                  REWIND NTRA\n                     CALL ZHPR( UPLO, N, RALPHA, XX, INCX, AA )\n                  END IF\n*\n*                 Check if error-exit was taken incorrectly.\n*\n                  IF( .NOT.OK )THEN\n                     WRITE( NOUT, FMT = 9992 )\n                     FATAL = .TRUE.\n                     GO TO 120\n                  END IF\n*\n*                 See what data changed inside subroutines.\n*\n                  ISAME( 1 ) = UPLO.EQ.UPLOS\n                  ISAME( 2 ) = NS.EQ.N\n                  ISAME( 3 ) = RALS.EQ.RALPHA\n                  ISAME( 4 ) = LZE( XS, XX, LX )\n                  ISAME( 5 ) = INCXS.EQ.INCX\n                  IF( NULL )THEN\n                     ISAME( 6 ) = LZE( AS, AA, LAA )\n                  ELSE\n                     ISAME( 6 ) = LZERES( SNAME( 2: 3 ), UPLO, N, N, AS,\n     $                            AA, LDA )\n                  END IF\n                  IF( .NOT.PACKED )THEN\n                     ISAME( 7 ) = LDAS.EQ.LDA\n                  END IF\n*\n*                 If data was incorrectly changed, report and return.\n*\n                  SAME = .TRUE.\n                  DO 30 I = 1, NARGS\n                     SAME = SAME.AND.ISAME( I )\n                     IF( .NOT.ISAME( I ) )\n     $                  WRITE( NOUT, FMT = 9998 )I\n   30             CONTINUE\n                  IF( .NOT.SAME )THEN\n                     FATAL = .TRUE.\n                     GO TO 120\n                  END IF\n*\n                  IF( .NOT.NULL )THEN\n*\n*                    Check the result column by column.\n*\n                     IF( INCX.GT.0 )THEN\n                        DO 40 I = 1, N\n                           Z( I ) = X( I )\n   40                   CONTINUE\n                     ELSE\n                        DO 50 I = 1, N\n                           Z( I ) = X( N - I + 1 )\n   50                   CONTINUE\n                     END IF\n                     JA = 1\n                     DO 60 J = 1, N\n                        W( 1 ) = DCONJG( Z( J ) )\n                        IF( UPPER )THEN\n                           JJ = 1\n                           LJ = J\n                        ELSE\n                           JJ = J\n                           LJ = N - J + 1\n                        END IF\n                        CALL ZMVCH( 'N', LJ, 1, ALPHA, Z( JJ ), LJ, W,\n     $                              1, ONE, A( JJ, J ), 1, YT, G,\n     $                              AA( JA ), EPS, ERR, FATAL, NOUT,\n     $                              .TRUE. )\n                        IF( FULL )THEN\n                           IF( UPPER )THEN\n                              JA = JA + LDA\n                           ELSE\n                              JA = JA + LDA + 1\n                           END IF\n                        ELSE\n                           JA = JA + LJ\n                        END IF\n                        ERRMAX = MAX( ERRMAX, ERR )\n*                       If got really bad answer, report and return.\n                        IF( FATAL )\n     $                     GO TO 110\n   60                CONTINUE\n                  ELSE\n*                    Avoid repeating tests if N.le.0.\n                     IF( N.LE.0 )\n     $                  GO TO 100\n                  END IF\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  110 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, RALPHA, INCX, LDA\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, RALPHA, INCX\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', AP)                                         .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',', F4.1, ', X,',\n     $      I2, ', A,', I3, ')                                      .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK5.\n*\n      END\n      SUBROUTINE ZCHK6( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NINC, INC, NMAX,\n     $                  INCMAX, A, AA, AS, X, XX, XS, Y, YY, YS, YT, G,\n     $                  Z )\n*\n*  Tests ZHER2 and ZHPR2.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO, HALF, ONE\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   HALF = ( 0.5D0, 0.0D0 ),\n     $                   ONE = ( 1.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            INCMAX, NALF, NIDIM, NINC, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), X( NMAX ), XS( NMAX*INCMAX ),\n     $                   XX( NMAX*INCMAX ), Y( NMAX ),\n     $                   YS( NMAX*INCMAX ), YT( NMAX ),\n     $                   YY( NMAX*INCMAX ), Z( NMAX, 2 )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM ), INC( NINC )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, ALS, TRANSL\n      DOUBLE PRECISION   ERR, ERRMAX\n      INTEGER            I, IA, IC, IN, INCX, INCXS, INCY, INCYS, IX,\n     $                   IY, J, JA, JJ, LAA, LDA, LDAS, LJ, LX, LY, N,\n     $                   NARGS, NC, NS\n      LOGICAL            FULL, NULL, PACKED, RESET, SAME, UPPER\n      CHARACTER*1        UPLO, UPLOS\n      CHARACTER*2        ICH\n*     .. Local Arrays ..\n      COMPLEX*16         W( 2 )\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZHER2, ZHPR2, ZMAKE, ZMVCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, DCONJG, MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'UL'/\n*     .. Executable Statements ..\n      FULL = SNAME( 3: 3 ).EQ.'E'\n      PACKED = SNAME( 3: 3 ).EQ.'P'\n*     Define the number of arguments.\n      IF( FULL )THEN\n         NARGS = 9\n      ELSE IF( PACKED )THEN\n         NARGS = 8\n      END IF\n*\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 140 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDA to 1 more than minimum value if room.\n         LDA = N\n         IF( LDA.LT.NMAX )\n     $      LDA = LDA + 1\n*        Skip tests if not enough room.\n         IF( LDA.GT.NMAX )\n     $      GO TO 140\n         IF( PACKED )THEN\n            LAA = ( N*( N + 1 ) )/2\n         ELSE\n            LAA = LDA*N\n         END IF\n*\n         DO 130 IC = 1, 2\n            UPLO = ICH( IC: IC )\n            UPPER = UPLO.EQ.'U'\n*\n            DO 120 IX = 1, NINC\n               INCX = INC( IX )\n               LX = ABS( INCX )*N\n*\n*              Generate the vector X.\n*\n               TRANSL = HALF\n               CALL ZMAKE( 'GE', ' ', ' ', 1, N, X, 1, XX, ABS( INCX ),\n     $                     0, N - 1, RESET, TRANSL )\n               IF( N.GT.1 )THEN\n                  X( N/2 ) = ZERO\n                  XX( 1 + ABS( INCX )*( N/2 - 1 ) ) = ZERO\n               END IF\n*\n               DO 110 IY = 1, NINC\n                  INCY = INC( IY )\n                  LY = ABS( INCY )*N\n*\n*                 Generate the vector Y.\n*\n                  TRANSL = ZERO\n                  CALL ZMAKE( 'GE', ' ', ' ', 1, N, Y, 1, YY,\n     $                        ABS( INCY ), 0, N - 1, RESET, TRANSL )\n                  IF( N.GT.1 )THEN\n                     Y( N/2 ) = ZERO\n                     YY( 1 + ABS( INCY )*( N/2 - 1 ) ) = ZERO\n                  END IF\n*\n                  DO 100 IA = 1, NALF\n                     ALPHA = ALF( IA )\n                     NULL = N.LE.0.OR.ALPHA.EQ.ZERO\n*\n*                    Generate the matrix A.\n*\n                     TRANSL = ZERO\n                     CALL ZMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, A,\n     $                           NMAX, AA, LDA, N - 1, N - 1, RESET,\n     $                           TRANSL )\n*\n                     NC = NC + 1\n*\n*                    Save every datum before calling the subroutine.\n*\n                     UPLOS = UPLO\n                     NS = N\n                     ALS = ALPHA\n                     DO 10 I = 1, LAA\n                        AS( I ) = AA( I )\n   10                CONTINUE\n                     LDAS = LDA\n                     DO 20 I = 1, LX\n                        XS( I ) = XX( I )\n   20                CONTINUE\n                     INCXS = INCX\n                     DO 30 I = 1, LY\n                        YS( I ) = YY( I )\n   30                CONTINUE\n                     INCYS = INCY\n*\n*                    Call the subroutine.\n*\n                     IF( FULL )THEN\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO, N,\n     $                     ALPHA, INCX, INCY, LDA\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL ZHER2( UPLO, N, ALPHA, XX, INCX, YY, INCY,\n     $                              AA, LDA )\n                     ELSE IF( PACKED )THEN\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO, N,\n     $                     ALPHA, INCX, INCY\n                        IF( REWI )\n     $                     REWIND NTRA\n                        CALL ZHPR2( UPLO, N, ALPHA, XX, INCX, YY, INCY,\n     $                              AA )\n                     END IF\n*\n*                    Check if error-exit was taken incorrectly.\n*\n                     IF( .NOT.OK )THEN\n                        WRITE( NOUT, FMT = 9992 )\n                        FATAL = .TRUE.\n                        GO TO 160\n                     END IF\n*\n*                    See what data changed inside subroutines.\n*\n                     ISAME( 1 ) = UPLO.EQ.UPLOS\n                     ISAME( 2 ) = NS.EQ.N\n                     ISAME( 3 ) = ALS.EQ.ALPHA\n                     ISAME( 4 ) = LZE( XS, XX, LX )\n                     ISAME( 5 ) = INCXS.EQ.INCX\n                     ISAME( 6 ) = LZE( YS, YY, LY )\n                     ISAME( 7 ) = INCYS.EQ.INCY\n                     IF( NULL )THEN\n                        ISAME( 8 ) = LZE( AS, AA, LAA )\n                     ELSE\n                        ISAME( 8 ) = LZERES( SNAME( 2: 3 ), UPLO, N, N,\n     $                               AS, AA, LDA )\n                     END IF\n                     IF( .NOT.PACKED )THEN\n                        ISAME( 9 ) = LDAS.EQ.LDA\n                     END IF\n*\n*                    If data was incorrectly changed, report and return.\n*\n                     SAME = .TRUE.\n                     DO 40 I = 1, NARGS\n                        SAME = SAME.AND.ISAME( I )\n                        IF( .NOT.ISAME( I ) )\n     $                     WRITE( NOUT, FMT = 9998 )I\n   40                CONTINUE\n                     IF( .NOT.SAME )THEN\n                        FATAL = .TRUE.\n                        GO TO 160\n                     END IF\n*\n                     IF( .NOT.NULL )THEN\n*\n*                       Check the result column by column.\n*\n                        IF( INCX.GT.0 )THEN\n                           DO 50 I = 1, N\n                              Z( I, 1 ) = X( I )\n   50                      CONTINUE\n                        ELSE\n                           DO 60 I = 1, N\n                              Z( I, 1 ) = X( N - I + 1 )\n   60                      CONTINUE\n                        END IF\n                        IF( INCY.GT.0 )THEN\n                           DO 70 I = 1, N\n                              Z( I, 2 ) = Y( I )\n   70                      CONTINUE\n                        ELSE\n                           DO 80 I = 1, N\n                              Z( I, 2 ) = Y( N - I + 1 )\n   80                      CONTINUE\n                        END IF\n                        JA = 1\n                        DO 90 J = 1, N\n                           W( 1 ) = ALPHA*DCONJG( Z( J, 2 ) )\n                           W( 2 ) = DCONJG( ALPHA )*DCONJG( Z( J, 1 ) )\n                           IF( UPPER )THEN\n                              JJ = 1\n                              LJ = J\n                           ELSE\n                              JJ = J\n                              LJ = N - J + 1\n                           END IF\n                           CALL ZMVCH( 'N', LJ, 2, ONE, Z( JJ, 1 ),\n     $                                 NMAX, W, 1, ONE, A( JJ, J ), 1,\n     $                                 YT, G, AA( JA ), EPS, ERR, FATAL,\n     $                                 NOUT, .TRUE. )\n                           IF( FULL )THEN\n                              IF( UPPER )THEN\n                                 JA = JA + LDA\n                              ELSE\n                                 JA = JA + LDA + 1\n                              END IF\n                           ELSE\n                              JA = JA + LJ\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and return.\n                           IF( FATAL )\n     $                        GO TO 150\n   90                   CONTINUE\n                     ELSE\n*                       Avoid repeating tests with N.le.0.\n                        IF( N.LE.0 )\n     $                     GO TO 140\n                     END IF\n*\n  100             CONTINUE\n*\n  110          CONTINUE\n*\n  120       CONTINUE\n*\n  130    CONTINUE\n*\n  140 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 170\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9995 )J\n*\n  160 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( FULL )THEN\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, N, ALPHA, INCX,\n     $      INCY, LDA\n      ELSE IF( PACKED )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, N, ALPHA, INCX, INCY\n      END IF\n*\n  170 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',(', F4.1, ',',\n     $      F4.1, '), X,', I2, ', Y,', I2, ', AP)                     ',\n     $      '       .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',', I3, ',(', F4.1, ',',\n     $      F4.1, '), X,', I2, ', Y,', I2, ', A,', I3, ')             ',\n     $      '            .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK6.\n*\n      END\n      SUBROUTINE ZCHKE( ISNUM, SRNAMT, NOUT )\n*\n*  Tests the error exits from the Level 2 Blas.\n*  Requires a special version of the error-handling routine XERBLA.\n*  ALPHA, RALPHA, BETA, A, X and Y should not need to be defined.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            ISNUM, NOUT\n      CHARACTER*6        SRNAMT\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, BETA\n      DOUBLE PRECISION   RALPHA\n*     .. Local Arrays ..\n      COMPLEX*16         A( 1, 1 ), X( 1 ), Y( 1 )\n*     .. External Subroutines ..\n      EXTERNAL           CHKXER, ZGBMV, ZGEMV, ZGERC, ZGERU, ZHBMV,\n     $                   ZHEMV, ZHER, ZHER2, ZHPMV, ZHPR, ZHPR2, ZTBMV,\n     $                   ZTBSV, ZTPMV, ZTPSV, ZTRMV, ZTRSV\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n*     OK is set to .FALSE. by the special version of XERBLA or by CHKXER\n*     if anything is wrong.\n      OK = .TRUE.\n*     LERR is set to .TRUE. by the special version of XERBLA each time\n*     it is called, and is then tested and re-set by CHKXER.\n      LERR = .FALSE.\n      GO TO ( 10, 20, 30, 40, 50, 60, 70, 80,\n     $        90, 100, 110, 120, 130, 140, 150, 160,\n     $        170 )ISNUM\n   10 INFOT = 1\n      CALL ZGEMV( '/', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZGEMV( 'N', -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGEMV( 'N', 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZGEMV( 'N', 2, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGEMV( 'N', 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZGEMV( 'N', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   20 INFOT = 1\n      CALL ZGBMV( '/', 0, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZGBMV( 'N', -1, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGBMV( 'N', 0, -1, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZGBMV( 'N', 0, 0, -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGBMV( 'N', 2, 0, 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGBMV( 'N', 0, 0, 1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZGBMV( 'N', 0, 0, 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL ZGBMV( 'N', 0, 0, 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   30 INFOT = 1\n      CALL ZHEMV( '/', 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZHEMV( 'U', -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZHEMV( 'U', 2, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHEMV( 'U', 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZHEMV( 'U', 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   40 INFOT = 1\n      CALL ZHBMV( '/', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZHBMV( 'U', -1, 0, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHBMV( 'U', 0, -1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZHBMV( 'U', 0, 1, ALPHA, A, 1, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZHBMV( 'U', 0, 0, ALPHA, A, 1, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZHBMV( 'U', 0, 0, ALPHA, A, 1, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   50 INFOT = 1\n      CALL ZHPMV( '/', 0, ALPHA, A, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZHPMV( 'U', -1, ALPHA, A, X, 1, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZHPMV( 'U', 0, ALPHA, A, X, 0, BETA, Y, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZHPMV( 'U', 0, ALPHA, A, X, 1, BETA, Y, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   60 INFOT = 1\n      CALL ZTRMV( '/', 'N', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZTRMV( 'U', '/', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZTRMV( 'U', 'N', '/', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZTRMV( 'U', 'N', 'N', -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMV( 'U', 'N', 'N', 2, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZTRMV( 'U', 'N', 'N', 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   70 INFOT = 1\n      CALL ZTBMV( '/', 'N', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZTBMV( 'U', '/', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZTBMV( 'U', 'N', '/', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZTBMV( 'U', 'N', 'N', -1, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTBMV( 'U', 'N', 'N', 0, -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZTBMV( 'U', 'N', 'N', 0, 1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTBMV( 'U', 'N', 'N', 0, 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   80 INFOT = 1\n      CALL ZTPMV( '/', 'N', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZTPMV( 'U', '/', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZTPMV( 'U', 'N', '/', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZTPMV( 'U', 'N', 'N', -1, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZTPMV( 'U', 'N', 'N', 0, A, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n   90 INFOT = 1\n      CALL ZTRSV( '/', 'N', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZTRSV( 'U', '/', 'N', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZTRSV( 'U', 'N', '/', 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZTRSV( 'U', 'N', 'N', -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSV( 'U', 'N', 'N', 2, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZTRSV( 'U', 'N', 'N', 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  100 INFOT = 1\n      CALL ZTBSV( '/', 'N', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZTBSV( 'U', '/', 'N', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZTBSV( 'U', 'N', '/', 0, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZTBSV( 'U', 'N', 'N', -1, 0, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTBSV( 'U', 'N', 'N', 0, -1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZTBSV( 'U', 'N', 'N', 0, 1, A, 1, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTBSV( 'U', 'N', 'N', 0, 0, A, 1, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  110 INFOT = 1\n      CALL ZTPSV( '/', 'N', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZTPSV( 'U', '/', 'N', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZTPSV( 'U', 'N', '/', 0, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZTPSV( 'U', 'N', 'N', -1, A, X, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZTPSV( 'U', 'N', 'N', 0, A, X, 0 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  120 INFOT = 1\n      CALL ZGERC( -1, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZGERC( 0, -1, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGERC( 0, 0, ALPHA, X, 0, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZGERC( 0, 0, ALPHA, X, 1, Y, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZGERC( 2, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  130 INFOT = 1\n      CALL ZGERU( -1, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZGERU( 0, -1, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGERU( 0, 0, ALPHA, X, 0, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZGERU( 0, 0, ALPHA, X, 1, Y, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZGERU( 2, 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  140 INFOT = 1\n      CALL ZHER( '/', 0, RALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZHER( 'U', -1, RALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZHER( 'U', 0, RALPHA, X, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHER( 'U', 2, RALPHA, X, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  150 INFOT = 1\n      CALL ZHPR( '/', 0, RALPHA, X, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZHPR( 'U', -1, RALPHA, X, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZHPR( 'U', 0, RALPHA, X, 0, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  160 INFOT = 1\n      CALL ZHER2( '/', 0, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZHER2( 'U', -1, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZHER2( 'U', 0, ALPHA, X, 0, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHER2( 'U', 0, ALPHA, X, 1, Y, 0, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZHER2( 'U', 2, ALPHA, X, 1, Y, 1, A, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 180\n  170 INFOT = 1\n      CALL ZHPR2( '/', 0, ALPHA, X, 1, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZHPR2( 'U', -1, ALPHA, X, 1, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZHPR2( 'U', 0, ALPHA, X, 0, Y, 1, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHPR2( 'U', 0, ALPHA, X, 1, Y, 0, A )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n  180 IF( OK )THEN\n         WRITE( NOUT, FMT = 9999 )SRNAMT\n      ELSE\n         WRITE( NOUT, FMT = 9998 )SRNAMT\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE TESTS OF ERROR-EXITS' )\n 9998 FORMAT( ' ******* ', A6, ' FAILED THE TESTS OF ERROR-EXITS *****',\n     $      '**' )\n*\n*     End of ZCHKE.\n*\n      END\n      SUBROUTINE ZMAKE( TYPE, UPLO, DIAG, M, N, A, NMAX, AA, LDA, KL,\n     $                  KU, RESET, TRANSL )\n*\n*  Generates values for an M by N matrix A within the bandwidth\n*  defined by KL and KU.\n*  Stores the values in the array AA in the data structure required\n*  by the routine, with unwanted elements set to rogue value.\n*\n*  TYPE is 'GE', 'GB', 'HE', 'HB', 'HP', 'TR', 'TB' OR 'TP'.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   ONE = ( 1.0D0, 0.0D0 ) )\n      COMPLEX*16         ROGUE\n      PARAMETER          ( ROGUE = ( -1.0D10, 1.0D10 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n      DOUBLE PRECISION   RROGUE\n      PARAMETER          ( RROGUE = -1.0D10 )\n*     .. Scalar Arguments ..\n      COMPLEX*16         TRANSL\n      INTEGER            KL, KU, LDA, M, N, NMAX\n      LOGICAL            RESET\n      CHARACTER*1        DIAG, UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, * ), AA( * )\n*     .. Local Scalars ..\n      INTEGER            I, I1, I2, I3, IBEG, IEND, IOFF, J, JJ, KK\n      LOGICAL            GEN, LOWER, SYM, TRI, UNIT, UPPER\n*     .. External Functions ..\n      COMPLEX*16         ZBEG\n      EXTERNAL           ZBEG\n*     .. Intrinsic Functions ..\n      INTRINSIC          DBLE, DCMPLX, DCONJG, MAX, MIN\n*     .. Executable Statements ..\n      GEN = TYPE( 1: 1 ).EQ.'G'\n      SYM = TYPE( 1: 1 ).EQ.'H'\n      TRI = TYPE( 1: 1 ).EQ.'T'\n      UPPER = ( SYM.OR.TRI ).AND.UPLO.EQ.'U'\n      LOWER = ( SYM.OR.TRI ).AND.UPLO.EQ.'L'\n      UNIT = TRI.AND.DIAG.EQ.'U'\n*\n*     Generate data in array A.\n*\n      DO 20 J = 1, N\n         DO 10 I = 1, M\n            IF( GEN.OR.( UPPER.AND.I.LE.J ).OR.( LOWER.AND.I.GE.J ) )\n     $          THEN\n               IF( ( I.LE.J.AND.J - I.LE.KU ).OR.\n     $             ( I.GE.J.AND.I - J.LE.KL ) )THEN\n                  A( I, J ) = ZBEG( RESET ) + TRANSL\n               ELSE\n                  A( I, J ) = ZERO\n               END IF\n               IF( I.NE.J )THEN\n                  IF( SYM )THEN\n                     A( J, I ) = DCONJG( A( I, J ) )\n                  ELSE IF( TRI )THEN\n                     A( J, I ) = ZERO\n                  END IF\n               END IF\n            END IF\n   10    CONTINUE\n         IF( SYM )\n     $      A( J, J ) = DCMPLX( DBLE( A( J, J ) ), RZERO )\n         IF( TRI )\n     $      A( J, J ) = A( J, J ) + ONE\n         IF( UNIT )\n     $      A( J, J ) = ONE\n   20 CONTINUE\n*\n*     Store elements in array AS in data structure required by routine.\n*\n      IF( TYPE.EQ.'GE' )THEN\n         DO 50 J = 1, N\n            DO 30 I = 1, M\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   30       CONTINUE\n            DO 40 I = M + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   40       CONTINUE\n   50    CONTINUE\n      ELSE IF( TYPE.EQ.'GB' )THEN\n         DO 90 J = 1, N\n            DO 60 I1 = 1, KU + 1 - J\n               AA( I1 + ( J - 1 )*LDA ) = ROGUE\n   60       CONTINUE\n            DO 70 I2 = I1, MIN( KL + KU + 1, KU + 1 + M - J )\n               AA( I2 + ( J - 1 )*LDA ) = A( I2 + J - KU - 1, J )\n   70       CONTINUE\n            DO 80 I3 = I2, LDA\n               AA( I3 + ( J - 1 )*LDA ) = ROGUE\n   80       CONTINUE\n   90    CONTINUE\n      ELSE IF( TYPE.EQ.'HE'.OR.TYPE.EQ.'TR' )THEN\n         DO 130 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IF( UNIT )THEN\n                  IEND = J - 1\n               ELSE\n                  IEND = J\n               END IF\n            ELSE\n               IF( UNIT )THEN\n                  IBEG = J + 1\n               ELSE\n                  IBEG = J\n               END IF\n               IEND = N\n            END IF\n            DO 100 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  100       CONTINUE\n            DO 110 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n  110       CONTINUE\n            DO 120 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  120       CONTINUE\n            IF( SYM )THEN\n               JJ = J + ( J - 1 )*LDA\n               AA( JJ ) = DCMPLX( DBLE( AA( JJ ) ), RROGUE )\n            END IF\n  130    CONTINUE\n      ELSE IF( TYPE.EQ.'HB'.OR.TYPE.EQ.'TB' )THEN\n         DO 170 J = 1, N\n            IF( UPPER )THEN\n               KK = KL + 1\n               IBEG = MAX( 1, KL + 2 - J )\n               IF( UNIT )THEN\n                  IEND = KL\n               ELSE\n                  IEND = KL + 1\n               END IF\n            ELSE\n               KK = 1\n               IF( UNIT )THEN\n                  IBEG = 2\n               ELSE\n                  IBEG = 1\n               END IF\n               IEND = MIN( KL + 1, 1 + M - J )\n            END IF\n            DO 140 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  140       CONTINUE\n            DO 150 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I + J - KK, J )\n  150       CONTINUE\n            DO 160 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n  160       CONTINUE\n            IF( SYM )THEN\n               JJ = KK + ( J - 1 )*LDA\n               AA( JJ ) = DCMPLX( DBLE( AA( JJ ) ), RROGUE )\n            END IF\n  170    CONTINUE\n      ELSE IF( TYPE.EQ.'HP'.OR.TYPE.EQ.'TP' )THEN\n         IOFF = 0\n         DO 190 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 180 I = IBEG, IEND\n               IOFF = IOFF + 1\n               AA( IOFF ) = A( I, J )\n               IF( I.EQ.J )THEN\n                  IF( UNIT )\n     $               AA( IOFF ) = ROGUE\n                  IF( SYM )\n     $               AA( IOFF ) = DCMPLX( DBLE( AA( IOFF ) ), RROGUE )\n               END IF\n  180       CONTINUE\n  190    CONTINUE\n      END IF\n      RETURN\n*\n*     End of ZMAKE.\n*\n      END\n      SUBROUTINE ZMVCH( TRANS, M, N, ALPHA, A, NMAX, X, INCX, BETA, Y,\n     $                  INCY, YT, G, YY, EPS, ERR, FATAL, NOUT, MV )\n*\n*  Checks the results of the computational tests.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO, RONE\n      PARAMETER          ( RZERO = 0.0D0, RONE = 1.0D0 )\n*     .. Scalar Arguments ..\n      COMPLEX*16         ALPHA, BETA\n      DOUBLE PRECISION   EPS, ERR\n      INTEGER            INCX, INCY, M, N, NMAX, NOUT\n      LOGICAL            FATAL, MV\n      CHARACTER*1        TRANS\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, * ), X( * ), Y( * ), YT( * ), YY( * )\n      DOUBLE PRECISION   G( * )\n*     .. Local Scalars ..\n      COMPLEX*16         C\n      DOUBLE PRECISION   ERRI\n      INTEGER            I, INCXL, INCYL, IY, J, JX, KX, KY, ML, NL\n      LOGICAL            CTRAN, TRAN\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, DBLE, DCONJG, DIMAG, MAX, SQRT\n*     .. Statement Functions ..\n      DOUBLE PRECISION   ABS1\n*     .. Statement Function definitions ..\n      ABS1( C ) = ABS( DBLE( C ) ) + ABS( DIMAG( C ) )\n*     .. Executable Statements ..\n      TRAN = TRANS.EQ.'T'\n      CTRAN = TRANS.EQ.'C'\n      IF( TRAN.OR.CTRAN )THEN\n         ML = N\n         NL = M\n      ELSE\n         ML = M\n         NL = N\n      END IF\n      IF( INCX.LT.0 )THEN\n         KX = NL\n         INCXL = -1\n      ELSE\n         KX = 1\n         INCXL = 1\n      END IF\n      IF( INCY.LT.0 )THEN\n         KY = ML\n         INCYL = -1\n      ELSE\n         KY = 1\n         INCYL = 1\n      END IF\n*\n*     Compute expected result in YT using data in A, X and Y.\n*     Compute gauges in G.\n*\n      IY = KY\n      DO 40 I = 1, ML\n         YT( IY ) = ZERO\n         G( IY ) = RZERO\n         JX = KX\n         IF( TRAN )THEN\n            DO 10 J = 1, NL\n               YT( IY ) = YT( IY ) + A( J, I )*X( JX )\n               G( IY ) = G( IY ) + ABS1( A( J, I ) )*ABS1( X( JX ) )\n               JX = JX + INCXL\n   10       CONTINUE\n         ELSE IF( CTRAN )THEN\n            DO 20 J = 1, NL\n               YT( IY ) = YT( IY ) + DCONJG( A( J, I ) )*X( JX )\n               G( IY ) = G( IY ) + ABS1( A( J, I ) )*ABS1( X( JX ) )\n               JX = JX + INCXL\n   20       CONTINUE\n         ELSE\n            DO 30 J = 1, NL\n               YT( IY ) = YT( IY ) + A( I, J )*X( JX )\n               G( IY ) = G( IY ) + ABS1( A( I, J ) )*ABS1( X( JX ) )\n               JX = JX + INCXL\n   30       CONTINUE\n         END IF\n         YT( IY ) = ALPHA*YT( IY ) + BETA*Y( IY )\n         G( IY ) = ABS1( ALPHA )*G( IY ) + ABS1( BETA )*ABS1( Y( IY ) )\n         IY = IY + INCYL\n   40 CONTINUE\n*\n*     Compute the error ratio for this result.\n*\n      ERR = ZERO\n      DO 50 I = 1, ML\n         ERRI = ABS( YT( I ) - YY( 1 + ( I - 1 )*ABS( INCY ) ) )/EPS\n         IF( G( I ).NE.RZERO )\n     $      ERRI = ERRI/G( I )\n         ERR = MAX( ERR, ERRI )\n         IF( ERR*SQRT( EPS ).GE.RONE )\n     $      GO TO 60\n   50 CONTINUE\n*     If the loop completes, all results are at least half accurate.\n      GO TO 80\n*\n*     Report fatal error.\n*\n   60 FATAL = .TRUE.\n      WRITE( NOUT, FMT = 9999 )\n      DO 70 I = 1, ML\n         IF( MV )THEN\n            WRITE( NOUT, FMT = 9998 )I, YT( I ),\n     $         YY( 1 + ( I - 1 )*ABS( INCY ) )\n         ELSE\n            WRITE( NOUT, FMT = 9998 )I,\n     $         YY( 1 + ( I - 1 )*ABS( INCY ) ), YT( I )\n         END IF\n   70 CONTINUE\n*\n   80 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ******* FATAL ERROR - COMPUTED RESULT IS LESS THAN HAL',\n     $      'F ACCURATE *******', /'                       EXPECTED RE',\n     $      'SULT                    COMPUTED RESULT' )\n 9998 FORMAT( 1X, I7, 2( '  (', G15.6, ',', G15.6, ')' ) )\n*\n*     End of ZMVCH.\n*\n      END\n      LOGICAL FUNCTION LZE( RI, RJ, LR )\n*\n*  Tests if two arrays are identical.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LR\n*     .. Array Arguments ..\n      COMPLEX*16         RI( * ), RJ( * )\n*     .. Local Scalars ..\n      INTEGER            I\n*     .. Executable Statements ..\n      DO 10 I = 1, LR\n         IF( RI( I ).NE.RJ( I ) )\n     $      GO TO 20\n   10 CONTINUE\n      LZE = .TRUE.\n      GO TO 30\n   20 CONTINUE\n      LZE = .FALSE.\n   30 RETURN\n*\n*     End of LZE.\n*\n      END\n      LOGICAL FUNCTION LZERES( TYPE, UPLO, M, N, AA, AS, LDA )\n*\n*  Tests if selected elements in two arrays are equal.\n*\n*  TYPE is 'GE', 'HE' or 'HP'.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LDA, M, N\n      CHARACTER*1        UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      COMPLEX*16         AA( LDA, * ), AS( LDA, * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J\n      LOGICAL            UPPER\n*     .. Executable Statements ..\n      UPPER = UPLO.EQ.'U'\n      IF( TYPE.EQ.'GE' )THEN\n         DO 20 J = 1, N\n            DO 10 I = M + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   10       CONTINUE\n   20    CONTINUE\n      ELSE IF( TYPE.EQ.'HE' )THEN\n         DO 50 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 30 I = 1, IBEG - 1\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   30       CONTINUE\n            DO 40 I = IEND + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   40       CONTINUE\n   50    CONTINUE\n      END IF\n*\n      LZERES = .TRUE.\n      GO TO 80\n   70 CONTINUE\n      LZERES = .FALSE.\n   80 RETURN\n*\n*     End of LZERES.\n*\n      END\n      COMPLEX*16 FUNCTION ZBEG( RESET )\n*\n*  Generates complex numbers as pairs of random numbers uniformly\n*  distributed between -0.5 and 0.5.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      LOGICAL            RESET\n*     .. Local Scalars ..\n      INTEGER            I, IC, J, MI, MJ\n*     .. Save statement ..\n      SAVE               I, IC, J, MI, MJ\n*     .. Intrinsic Functions ..\n      INTRINSIC          DCMPLX\n*     .. Executable Statements ..\n      IF( RESET )THEN\n*        Initialize local variables.\n         MI = 891\n         MJ = 457\n         I = 7\n         J = 7\n         IC = 0\n         RESET = .FALSE.\n      END IF\n*\n*     The sequence of values of I or J is bounded between 1 and 999.\n*     If initial I or J = 1,2,3,6,7 or 9, the period will be 50.\n*     If initial I or J = 4 or 8, the period will be 25.\n*     If initial I or J = 5, the period will be 10.\n*     IC is used to break up the period by skipping 1 value of I or J\n*     in 6.\n*\n      IC = IC + 1\n   10 I = I*MI\n      J = J*MJ\n      I = I - 1000*( I/1000 )\n      J = J - 1000*( J/1000 )\n      IF( IC.GE.5 )THEN\n         IC = 0\n         GO TO 10\n      END IF\n      ZBEG = DCMPLX( ( I - 500 )/1001.0D0, ( J - 500 )/1001.0D0 )\n      RETURN\n*\n*     End of ZBEG.\n*\n      END\n      DOUBLE PRECISION FUNCTION DDIFF( X, Y )\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   X, Y\n*     .. Executable Statements ..\n      DDIFF = X - Y\n      RETURN\n*\n*     End of DDIFF.\n*\n      END\n      SUBROUTINE CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n*  Tests whether XERBLA has detected an error when it should.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Executable Statements ..\n      IF( .NOT.LERR )THEN\n         WRITE( NOUT, FMT = 9999 )INFOT, SRNAMT\n         OK = .FALSE.\n      END IF\n      LERR = .FALSE.\n      RETURN\n*\n 9999 FORMAT( ' ***** ILLEGAL VALUE OF PARAMETER NUMBER ', I2, ' NOT D',\n     $      'ETECTED BY ', A6, ' *****' )\n*\n*     End of CHKXER.\n*\n      END\n      SUBROUTINE XERBLA( SRNAME, INFO )\n*\n*  This is a special version of XERBLA to be used only as part of\n*  the test program for testing error exits from the Level 2 BLAS\n*  routines.\n*\n*  XERBLA  is an error handler for the Level 2 BLAS routines.\n*\n*  It is called by the Level 2 BLAS routines if an input parameter is\n*  invalid.\n*\n*  Auxiliary routine for test program for Level 2 Blas.\n*\n*  -- Written on 10-August-1987.\n*     Richard Hanson, Sandia National Labs.\n*     Jeremy Du Croz, NAG Central Office.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFO\n      CHARACTER*6        SRNAME\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUT, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Executable Statements ..\n      LERR = .TRUE.\n      IF( INFO.NE.INFOT )THEN\n         IF( INFOT.NE.0 )THEN\n            WRITE( NOUT, FMT = 9999 )INFO, INFOT\n         ELSE\n            WRITE( NOUT, FMT = 9997 )INFO\n         END IF\n         OK = .FALSE.\n      END IF\n      IF( SRNAME.NE.SRNAMT )THEN\n         WRITE( NOUT, FMT = 9998 )SRNAME, SRNAMT\n         OK = .FALSE.\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6, ' INSTEAD',\n     $      ' OF ', I2, ' *******' )\n 9998 FORMAT( ' ******* XERBLA WAS CALLED WITH SRNAME = ', A6, ' INSTE',\n     $      'AD OF ', A6, ' *******' )\n 9997 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6,\n     $      ' *******' )\n*\n*     End of XERBLA\n*\n      END\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/testing/zblat3.f",
    "content": "*> \\brief \\b ZBLAT3\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*       PROGRAM ZBLAT3\n* \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> Test program for the COMPLEX*16       Level 3 Blas.\n*>\n*> The program must be driven by a short data file. The first 14 records\n*> of the file are read using list-directed input, the last 9 records\n*> are read using the format ( A6, L2 ). An annotated example of a data\n*> file can be obtained by deleting the first 3 characters from the\n*> following 23 lines:\n*> 'zblat3.out'      NAME OF SUMMARY OUTPUT FILE\n*> 6                 UNIT NUMBER OF SUMMARY FILE\n*> 'ZBLAT3.SNAP'     NAME OF SNAPSHOT OUTPUT FILE\n*> -1                UNIT NUMBER OF SNAPSHOT FILE (NOT USED IF .LT. 0)\n*> F        LOGICAL FLAG, T TO REWIND SNAPSHOT FILE AFTER EACH RECORD.\n*> F        LOGICAL FLAG, T TO STOP ON FAILURES.\n*> T        LOGICAL FLAG, T TO TEST ERROR EXITS.\n*> 16.0     THRESHOLD VALUE OF TEST RATIO\n*> 6                 NUMBER OF VALUES OF N\n*> 0 1 2 3 5 9       VALUES OF N\n*> 3                 NUMBER OF VALUES OF ALPHA\n*> (0.0,0.0) (1.0,0.0) (0.7,-0.9)       VALUES OF ALPHA\n*> 3                 NUMBER OF VALUES OF BETA\n*> (0.0,0.0) (1.0,0.0) (1.3,-1.1)       VALUES OF BETA\n*> ZGEMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZHEMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZSYMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZTRMM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZTRSM  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZHERK  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZSYRK  T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZHER2K T PUT F FOR NO TEST. SAME COLUMNS.\n*> ZSYR2K T PUT F FOR NO TEST. SAME COLUMNS.\n*>\n*> \n*> Further Details\n*> ===============\n*>\n*> See:\n*>\n*>    Dongarra J. J., Du Croz J. J., Duff I. S. and Hammarling S.\n*>    A Set of Level 3 Basic Linear Algebra Subprograms.\n*>\n*>    Technical Memorandum No.88 (Revision 1), Mathematics and\n*>    Computer Science Division, Argonne National Laboratory, 9700\n*>    South Cass Avenue, Argonne, Illinois 60439, US.\n*>\n*> -- Written on 8-February-1989.\n*>    Jack Dongarra, Argonne National Laboratory.\n*>    Iain Duff, AERE Harwell.\n*>    Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*>    Sven Hammarling, Numerical Algorithms Group Ltd.\n*>\n*>    10-9-00:  Change STATUS='NEW' to 'UNKNOWN' so that the testers\n*>              can be run multiple times without deleting generated\n*>              output files (susan)\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup complex16_blas_testing\n*\n*  =====================================================================\n      PROGRAM ZBLAT3\n*\n*  -- Reference BLAS test routine (version 3.4.1) --\n*  -- Reference BLAS is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      INTEGER            NIN\n      PARAMETER          ( NIN = 5 )\n      INTEGER            NSUBS\n      PARAMETER          ( NSUBS = 9 )\n      COMPLEX*16         ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   ONE = ( 1.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n      INTEGER            NMAX\n      PARAMETER          ( NMAX = 65 )\n      INTEGER            NIDMAX, NALMAX, NBEMAX\n      PARAMETER          ( NIDMAX = 9, NALMAX = 7, NBEMAX = 7 )\n*     .. Local Scalars ..\n      DOUBLE PRECISION   EPS, ERR, THRESH\n      INTEGER            I, ISNUM, J, N, NALF, NBET, NIDIM, NOUT, NTRA\n      LOGICAL            FATAL, LTESTT, REWI, SAME, SFATAL, TRACE,\n     $                   TSTERR\n      CHARACTER*1        TRANSA, TRANSB\n      CHARACTER*6        SNAMET\n      CHARACTER*32       SNAPS, SUMMRY\n*     .. Local Arrays ..\n      COMPLEX*16         AA( NMAX*NMAX ), AB( NMAX, 2*NMAX ),\n     $                   ALF( NALMAX ), AS( NMAX*NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBEMAX ),\n     $                   BS( NMAX*NMAX ), C( NMAX, NMAX ),\n     $                   CC( NMAX*NMAX ), CS( NMAX*NMAX ), CT( NMAX ),\n     $                   W( 2*NMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDMAX )\n      LOGICAL            LTEST( NSUBS )\n      CHARACTER*6        SNAMES( NSUBS )\n*     .. External Functions ..\n      DOUBLE PRECISION   DDIFF\n      LOGICAL            LZE\n      EXTERNAL           DDIFF, LZE\n*     .. External Subroutines ..\n      EXTERNAL           ZCHK1, ZCHK2, ZCHK3, ZCHK4, ZCHK5, ZCHKE, ZMMCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX, MIN\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Data statements ..\n      DATA               SNAMES/'ZGEMM ', 'ZHEMM ', 'ZSYMM ', 'ZTRMM ',\n     $                   'ZTRSM ', 'ZHERK ', 'ZSYRK ', 'ZHER2K',\n     $                   'ZSYR2K'/\n*     .. Executable Statements ..\n*\n*     Read name and unit number for summary output file and open file.\n*\n      READ( NIN, FMT = * )SUMMRY\n      READ( NIN, FMT = * )NOUT\n      OPEN( NOUT, FILE = SUMMRY, STATUS = 'UNKNOWN' )\n      NOUTC = NOUT\n*\n*     Read name and unit number for snapshot output file and open file.\n*\n      READ( NIN, FMT = * )SNAPS\n      READ( NIN, FMT = * )NTRA\n      TRACE = NTRA.GE.0\n      IF( TRACE )THEN\n         OPEN( NTRA, FILE = SNAPS, STATUS = 'UNKNOWN' )\n      END IF\n*     Read the flag that directs rewinding of the snapshot file.\n      READ( NIN, FMT = * )REWI\n      REWI = REWI.AND.TRACE\n*     Read the flag that directs stopping on any failure.\n      READ( NIN, FMT = * )SFATAL\n*     Read the flag that indicates whether error exits are to be tested.\n      READ( NIN, FMT = * )TSTERR\n*     Read the threshold value of the test ratio\n      READ( NIN, FMT = * )THRESH\n*\n*     Read and check the parameter values for the tests.\n*\n*     Values of N\n      READ( NIN, FMT = * )NIDIM\n      IF( NIDIM.LT.1.OR.NIDIM.GT.NIDMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'N', NIDMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( IDIM( I ), I = 1, NIDIM )\n      DO 10 I = 1, NIDIM\n         IF( IDIM( I ).LT.0.OR.IDIM( I ).GT.NMAX )THEN\n            WRITE( NOUT, FMT = 9996 )NMAX\n            GO TO 220\n         END IF\n   10 CONTINUE\n*     Values of ALPHA\n      READ( NIN, FMT = * )NALF\n      IF( NALF.LT.1.OR.NALF.GT.NALMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'ALPHA', NALMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( ALF( I ), I = 1, NALF )\n*     Values of BETA\n      READ( NIN, FMT = * )NBET\n      IF( NBET.LT.1.OR.NBET.GT.NBEMAX )THEN\n         WRITE( NOUT, FMT = 9997 )'BETA', NBEMAX\n         GO TO 220\n      END IF\n      READ( NIN, FMT = * )( BET( I ), I = 1, NBET )\n*\n*     Report values of parameters.\n*\n      WRITE( NOUT, FMT = 9995 )\n      WRITE( NOUT, FMT = 9994 )( IDIM( I ), I = 1, NIDIM )\n      WRITE( NOUT, FMT = 9993 )( ALF( I ), I = 1, NALF )\n      WRITE( NOUT, FMT = 9992 )( BET( I ), I = 1, NBET )\n      IF( .NOT.TSTERR )THEN\n         WRITE( NOUT, FMT = * )\n         WRITE( NOUT, FMT = 9984 )\n      END IF\n      WRITE( NOUT, FMT = * )\n      WRITE( NOUT, FMT = 9999 )THRESH\n      WRITE( NOUT, FMT = * )\n*\n*     Read names of subroutines and flags which indicate\n*     whether they are to be tested.\n*\n      DO 20 I = 1, NSUBS\n         LTEST( I ) = .FALSE.\n   20 CONTINUE\n   30 READ( NIN, FMT = 9988, END = 60 )SNAMET, LTESTT\n      DO 40 I = 1, NSUBS\n         IF( SNAMET.EQ.SNAMES( I ) )\n     $      GO TO 50\n   40 CONTINUE\n      WRITE( NOUT, FMT = 9990 )SNAMET\n      STOP\n   50 LTEST( I ) = LTESTT\n      GO TO 30\n*\n   60 CONTINUE\n      CLOSE ( NIN )\n*\n*     Compute EPS (the machine precision).\n*\n      EPS = EPSILON(RZERO)\n      WRITE( NOUT, FMT = 9998 )EPS\n*\n*     Check the reliability of ZMMCH using exact data.\n*\n      N = MIN( 32, NMAX )\n      DO 100 J = 1, N\n         DO 90 I = 1, N\n            AB( I, J ) = MAX( I - J + 1, 0 )\n   90    CONTINUE\n         AB( J, NMAX + 1 ) = J\n         AB( 1, NMAX + J ) = J\n         C( J, 1 ) = ZERO\n  100 CONTINUE\n      DO 110 J = 1, N\n         CC( J ) = J*( ( J + 1 )*J )/2 - ( ( J + 1 )*J*( J - 1 ) )/3\n  110 CONTINUE\n*     CC holds the exact result. On exit from ZMMCH CT holds\n*     the result computed by ZMMCH.\n      TRANSA = 'N'\n      TRANSB = 'N'\n      CALL ZMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LZE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      TRANSB = 'C'\n      CALL ZMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LZE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      DO 120 J = 1, N\n         AB( J, NMAX + 1 ) = N - J + 1\n         AB( 1, NMAX + J ) = N - J + 1\n  120 CONTINUE\n      DO 130 J = 1, N\n         CC( N - J + 1 ) = J*( ( J + 1 )*J )/2 -\n     $                     ( ( J + 1 )*J*( J - 1 ) )/3\n  130 CONTINUE\n      TRANSA = 'C'\n      TRANSB = 'N'\n      CALL ZMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LZE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n      TRANSB = 'C'\n      CALL ZMMCH( TRANSA, TRANSB, N, 1, N, ONE, AB, NMAX,\n     $            AB( 1, NMAX + 1 ), NMAX, ZERO, C, NMAX, CT, G, CC,\n     $            NMAX, EPS, ERR, FATAL, NOUT, .TRUE. )\n      SAME = LZE( CC, CT, N )\n      IF( .NOT.SAME.OR.ERR.NE.RZERO )THEN\n         WRITE( NOUT, FMT = 9989 )TRANSA, TRANSB, SAME, ERR\n         STOP\n      END IF\n*\n*     Test each subroutine in turn.\n*\n      DO 200 ISNUM = 1, NSUBS\n         WRITE( NOUT, FMT = * )\n         IF( .NOT.LTEST( ISNUM ) )THEN\n*           Subprogram is not to be tested.\n            WRITE( NOUT, FMT = 9987 )SNAMES( ISNUM )\n         ELSE\n            SRNAMT = SNAMES( ISNUM )\n*           Test error exits.\n            IF( TSTERR )THEN\n               CALL ZCHKE( ISNUM, SNAMES( ISNUM ), NOUT )\n               WRITE( NOUT, FMT = * )\n            END IF\n*           Test computations.\n            INFOT = 0\n            OK = .TRUE.\n            FATAL = .FALSE.\n            GO TO ( 140, 150, 150, 160, 160, 170, 170,\n     $              180, 180 )ISNUM\n*           Test ZGEMM, 01.\n  140       CALL ZCHK1( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test ZHEMM, 02, ZSYMM, 03.\n  150       CALL ZCHK2( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test ZTRMM, 04, ZTRSM, 05.\n  160       CALL ZCHK3( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NMAX, AB,\n     $                  AA, AS, AB( 1, NMAX + 1 ), BB, BS, CT, G, C )\n            GO TO 190\n*           Test ZHERK, 06, ZSYRK, 07.\n  170       CALL ZCHK4( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, AB( 1, NMAX + 1 ), BB, BS, C,\n     $                  CC, CS, CT, G )\n            GO TO 190\n*           Test ZHER2K, 08, ZSYR2K, 09.\n  180       CALL ZCHK5( SNAMES( ISNUM ), EPS, THRESH, NOUT, NTRA, TRACE,\n     $                  REWI, FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET,\n     $                  NMAX, AB, AA, AS, BB, BS, C, CC, CS, CT, G, W )\n            GO TO 190\n*\n  190       IF( FATAL.AND.SFATAL )\n     $         GO TO 210\n         END IF\n  200 CONTINUE\n      WRITE( NOUT, FMT = 9986 )\n      GO TO 230\n*\n  210 CONTINUE\n      WRITE( NOUT, FMT = 9985 )\n      GO TO 230\n*\n  220 CONTINUE\n      WRITE( NOUT, FMT = 9991 )\n*\n  230 CONTINUE\n      IF( TRACE )\n     $   CLOSE ( NTRA )\n      CLOSE ( NOUT )\n      STOP\n*\n 9999 FORMAT( ' ROUTINES PASS COMPUTATIONAL TESTS IF TEST RATIO IS LES',\n     $      'S THAN', F8.2 )\n 9998 FORMAT( ' RELATIVE MACHINE PRECISION IS TAKEN TO BE', 1P, D9.1 )\n 9997 FORMAT( ' NUMBER OF VALUES OF ', A, ' IS LESS THAN 1 OR GREATER ',\n     $      'THAN ', I2 )\n 9996 FORMAT( ' VALUE OF N IS LESS THAN 0 OR GREATER THAN ', I2 )\n 9995 FORMAT( ' TESTS OF THE COMPLEX*16       LEVEL 3 BLAS', //' THE F',\n     $      'OLLOWING PARAMETER VALUES WILL BE USED:' )\n 9994 FORMAT( '   FOR N              ', 9I6 )\n 9993 FORMAT( '   FOR ALPHA          ',\n     $      7( '(', F4.1, ',', F4.1, ')  ', : ) )\n 9992 FORMAT( '   FOR BETA           ',\n     $      7( '(', F4.1, ',', F4.1, ')  ', : ) )\n 9991 FORMAT( ' AMEND DATA FILE OR INCREASE ARRAY SIZES IN PROGRAM',\n     $      /' ******* TESTS ABANDONED *******' )\n 9990 FORMAT( ' SUBPROGRAM NAME ', A6, ' NOT RECOGNIZED', /' ******* T',\n     $      'ESTS ABANDONED *******' )\n 9989 FORMAT( ' ERROR IN ZMMCH -  IN-LINE DOT PRODUCTS ARE BEING EVALU',\n     $      'ATED WRONGLY.', /' ZMMCH WAS CALLED WITH TRANSA = ', A1,\n     $      ' AND TRANSB = ', A1, /' AND RETURNED SAME = ', L1, ' AND ',\n     $      'ERR = ', F12.3, '.', /' THIS MAY BE DUE TO FAULTS IN THE ',\n     $      'ARITHMETIC OR THE COMPILER.', /' ******* TESTS ABANDONED ',\n     $      '*******' )\n 9988 FORMAT( A6, L2 )\n 9987 FORMAT( 1X, A6, ' WAS NOT TESTED' )\n 9986 FORMAT( /' END OF TESTS' )\n 9985 FORMAT( /' ******* FATAL ERROR - TESTS ABANDONED *******' )\n 9984 FORMAT( ' ERROR-EXITS WILL NOT BE TESTED' )\n*\n*     End of ZBLAT3.\n*\n      END\n      SUBROUTINE ZCHK1( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests ZGEMM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, ALS, BETA, BLS\n      DOUBLE PRECISION   ERR, ERRMAX\n      INTEGER            I, IA, IB, ICA, ICB, IK, IM, IN, K, KS, LAA,\n     $                   LBB, LCC, LDA, LDAS, LDB, LDBS, LDC, LDCS, M,\n     $                   MA, MB, MS, N, NA, NARGS, NB, NC, NS\n      LOGICAL            NULL, RESET, SAME, TRANA, TRANB\n      CHARACTER*1        TRANAS, TRANBS, TRANSA, TRANSB\n      CHARACTER*3        ICH\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZGEMM, ZMAKE, ZMMCH\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICH/'NTC'/\n*     .. Executable Statements ..\n*\n      NARGS = 13\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 110 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 100 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDC to 1 more than minimum value if room.\n            LDC = M\n            IF( LDC.LT.NMAX )\n     $         LDC = LDC + 1\n*           Skip tests if not enough room.\n            IF( LDC.GT.NMAX )\n     $         GO TO 100\n            LCC = LDC*N\n            NULL = N.LE.0.OR.M.LE.0\n*\n            DO 90 IK = 1, NIDIM\n               K = IDIM( IK )\n*\n               DO 80 ICA = 1, 3\n                  TRANSA = ICH( ICA: ICA )\n                  TRANA = TRANSA.EQ.'T'.OR.TRANSA.EQ.'C'\n*\n                  IF( TRANA )THEN\n                     MA = K\n                     NA = M\n                  ELSE\n                     MA = M\n                     NA = K\n                  END IF\n*                 Set LDA to 1 more than minimum value if room.\n                  LDA = MA\n                  IF( LDA.LT.NMAX )\n     $               LDA = LDA + 1\n*                 Skip tests if not enough room.\n                  IF( LDA.GT.NMAX )\n     $               GO TO 80\n                  LAA = LDA*NA\n*\n*                 Generate the matrix A.\n*\n                  CALL ZMAKE( 'GE', ' ', ' ', MA, NA, A, NMAX, AA, LDA,\n     $                        RESET, ZERO )\n*\n                  DO 70 ICB = 1, 3\n                     TRANSB = ICH( ICB: ICB )\n                     TRANB = TRANSB.EQ.'T'.OR.TRANSB.EQ.'C'\n*\n                     IF( TRANB )THEN\n                        MB = N\n                        NB = K\n                     ELSE\n                        MB = K\n                        NB = N\n                     END IF\n*                    Set LDB to 1 more than minimum value if room.\n                     LDB = MB\n                     IF( LDB.LT.NMAX )\n     $                  LDB = LDB + 1\n*                    Skip tests if not enough room.\n                     IF( LDB.GT.NMAX )\n     $                  GO TO 70\n                     LBB = LDB*NB\n*\n*                    Generate the matrix B.\n*\n                     CALL ZMAKE( 'GE', ' ', ' ', MB, NB, B, NMAX, BB,\n     $                           LDB, RESET, ZERO )\n*\n                     DO 60 IA = 1, NALF\n                        ALPHA = ALF( IA )\n*\n                        DO 50 IB = 1, NBET\n                           BETA = BET( IB )\n*\n*                          Generate the matrix C.\n*\n                           CALL ZMAKE( 'GE', ' ', ' ', M, N, C, NMAX,\n     $                                 CC, LDC, RESET, ZERO )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           TRANAS = TRANSA\n                           TRANBS = TRANSB\n                           MS = M\n                           NS = N\n                           KS = K\n                           ALS = ALPHA\n                           DO 10 I = 1, LAA\n                              AS( I ) = AA( I )\n   10                      CONTINUE\n                           LDAS = LDA\n                           DO 20 I = 1, LBB\n                              BS( I ) = BB( I )\n   20                      CONTINUE\n                           LDBS = LDB\n                           BLS = BETA\n                           DO 30 I = 1, LCC\n                              CS( I ) = CC( I )\n   30                      CONTINUE\n                           LDCS = LDC\n*\n*                          Call the subroutine.\n*\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                        TRANSA, TRANSB, M, N, K, ALPHA, LDA, LDB,\n     $                        BETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL ZGEMM( TRANSA, TRANSB, M, N, K, ALPHA,\n     $                                 AA, LDA, BB, LDB, BETA, CC, LDC )\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9994 )\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = TRANSA.EQ.TRANAS\n                           ISAME( 2 ) = TRANSB.EQ.TRANBS\n                           ISAME( 3 ) = MS.EQ.M\n                           ISAME( 4 ) = NS.EQ.N\n                           ISAME( 5 ) = KS.EQ.K\n                           ISAME( 6 ) = ALS.EQ.ALPHA\n                           ISAME( 7 ) = LZE( AS, AA, LAA )\n                           ISAME( 8 ) = LDAS.EQ.LDA\n                           ISAME( 9 ) = LZE( BS, BB, LBB )\n                           ISAME( 10 ) = LDBS.EQ.LDB\n                           ISAME( 11 ) = BLS.EQ.BETA\n                           IF( NULL )THEN\n                              ISAME( 12 ) = LZE( CS, CC, LCC )\n                           ELSE\n                              ISAME( 12 ) = LZERES( 'GE', ' ', M, N, CS,\n     $                                      CC, LDC )\n                           END IF\n                           ISAME( 13 ) = LDCS.EQ.LDC\n*\n*                          If data was incorrectly changed, report\n*                          and return.\n*\n                           SAME = .TRUE.\n                           DO 40 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   40                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 120\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n*\n*                             Check the result.\n*\n                              CALL ZMMCH( TRANSA, TRANSB, M, N, K,\n     $                                    ALPHA, A, NMAX, B, NMAX, BETA,\n     $                                    C, NMAX, CT, G, CC, LDC, EPS,\n     $                                    ERR, FATAL, NOUT, .TRUE. )\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 120\n                           END IF\n*\n   50                   CONTINUE\n*\n   60                CONTINUE\n*\n   70             CONTINUE\n*\n   80          CONTINUE\n*\n   90       CONTINUE\n*\n  100    CONTINUE\n*\n  110 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, TRANSA, TRANSB, M, N, K,\n     $   ALPHA, LDA, LDB, BETA, LDC\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(''', A1, ''',''', A1, ''',',\n     $      3( I3, ',' ), '(', F4.1, ',', F4.1, '), A,', I3, ', B,', I3,\n     $      ',(', F4.1, ',', F4.1, '), C,', I3, ').' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK1.\n*\n      END\n      SUBROUTINE ZCHK2( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests ZHEMM and ZSYMM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, ALS, BETA, BLS\n      DOUBLE PRECISION   ERR, ERRMAX\n      INTEGER            I, IA, IB, ICS, ICU, IM, IN, LAA, LBB, LCC,\n     $                   LDA, LDAS, LDB, LDBS, LDC, LDCS, M, MS, N, NA,\n     $                   NARGS, NC, NS\n      LOGICAL            CONJ, LEFT, NULL, RESET, SAME\n      CHARACTER*1        SIDE, SIDES, UPLO, UPLOS\n      CHARACTER*2        ICHS, ICHU\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZHEMM, ZMAKE, ZMMCH, ZSYMM\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHS/'LR'/, ICHU/'UL'/\n*     .. Executable Statements ..\n      CONJ = SNAME( 2: 3 ).EQ.'HE'\n*\n      NARGS = 12\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 100 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 90 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDC to 1 more than minimum value if room.\n            LDC = M\n            IF( LDC.LT.NMAX )\n     $         LDC = LDC + 1\n*           Skip tests if not enough room.\n            IF( LDC.GT.NMAX )\n     $         GO TO 90\n            LCC = LDC*N\n            NULL = N.LE.0.OR.M.LE.0\n*           Set LDB to 1 more than minimum value if room.\n            LDB = M\n            IF( LDB.LT.NMAX )\n     $         LDB = LDB + 1\n*           Skip tests if not enough room.\n            IF( LDB.GT.NMAX )\n     $         GO TO 90\n            LBB = LDB*N\n*\n*           Generate the matrix B.\n*\n            CALL ZMAKE( 'GE', ' ', ' ', M, N, B, NMAX, BB, LDB, RESET,\n     $                  ZERO )\n*\n            DO 80 ICS = 1, 2\n               SIDE = ICHS( ICS: ICS )\n               LEFT = SIDE.EQ.'L'\n*\n               IF( LEFT )THEN\n                  NA = M\n               ELSE\n                  NA = N\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = NA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 80\n               LAA = LDA*NA\n*\n               DO 70 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n*\n*                 Generate the hermitian or symmetric matrix A.\n*\n                  CALL ZMAKE( SNAME( 2: 3 ), UPLO, ' ', NA, NA, A, NMAX,\n     $                        AA, LDA, RESET, ZERO )\n*\n                  DO 60 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n                     DO 50 IB = 1, NBET\n                        BETA = BET( IB )\n*\n*                       Generate the matrix C.\n*\n                        CALL ZMAKE( 'GE', ' ', ' ', M, N, C, NMAX, CC,\n     $                              LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the\n*                       subroutine.\n*\n                        SIDES = SIDE\n                        UPLOS = UPLO\n                        MS = M\n                        NS = N\n                        ALS = ALPHA\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        DO 20 I = 1, LBB\n                           BS( I ) = BB( I )\n   20                   CONTINUE\n                        LDBS = LDB\n                        BLS = BETA\n                        DO 30 I = 1, LCC\n                           CS( I ) = CC( I )\n   30                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( TRACE )\n     $                     WRITE( NTRA, FMT = 9995 )NC, SNAME, SIDE,\n     $                     UPLO, M, N, ALPHA, LDA, LDB, BETA, LDC\n                        IF( REWI )\n     $                     REWIND NTRA\n                        IF( CONJ )THEN\n                           CALL ZHEMM( SIDE, UPLO, M, N, ALPHA, AA, LDA,\n     $                                 BB, LDB, BETA, CC, LDC )\n                        ELSE\n                           CALL ZSYMM( SIDE, UPLO, M, N, ALPHA, AA, LDA,\n     $                                 BB, LDB, BETA, CC, LDC )\n                        END IF\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9994 )\n                           FATAL = .TRUE.\n                           GO TO 110\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = SIDES.EQ.SIDE\n                        ISAME( 2 ) = UPLOS.EQ.UPLO\n                        ISAME( 3 ) = MS.EQ.M\n                        ISAME( 4 ) = NS.EQ.N\n                        ISAME( 5 ) = ALS.EQ.ALPHA\n                        ISAME( 6 ) = LZE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        ISAME( 8 ) = LZE( BS, BB, LBB )\n                        ISAME( 9 ) = LDBS.EQ.LDB\n                        ISAME( 10 ) = BLS.EQ.BETA\n                        IF( NULL )THEN\n                           ISAME( 11 ) = LZE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 11 ) = LZERES( 'GE', ' ', M, N, CS,\n     $                                   CC, LDC )\n                        END IF\n                        ISAME( 12 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 110\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result.\n*\n                           IF( LEFT )THEN\n                              CALL ZMMCH( 'N', 'N', M, N, M, ALPHA, A,\n     $                                    NMAX, B, NMAX, BETA, C, NMAX,\n     $                                    CT, G, CC, LDC, EPS, ERR,\n     $                                    FATAL, NOUT, .TRUE. )\n                           ELSE\n                              CALL ZMMCH( 'N', 'N', M, N, N, ALPHA, B,\n     $                                    NMAX, A, NMAX, BETA, C, NMAX,\n     $                                    CT, G, CC, LDC, EPS, ERR,\n     $                                    FATAL, NOUT, .TRUE. )\n                           END IF\n                           ERRMAX = MAX( ERRMAX, ERR )\n*                          If got really bad answer, report and\n*                          return.\n                           IF( FATAL )\n     $                        GO TO 110\n                        END IF\n*\n   50                CONTINUE\n*\n   60             CONTINUE\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 120\n*\n  110 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, SIDE, UPLO, M, N, ALPHA, LDA,\n     $   LDB, BETA, LDC\n*\n  120 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      '(', F4.1, ',', F4.1, '), A,', I3, ', B,', I3, ',(', F4.1,\n     $      ',', F4.1, '), C,', I3, ')    .' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK2.\n*\n      END\n      SUBROUTINE ZCHK3( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NMAX, A, AA, AS,\n     $                  B, BB, BS, CT, G, C )\n*\n*  Tests ZTRMM and ZTRSM.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   ONE = ( 1.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            NALF, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CT( NMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, ALS\n      DOUBLE PRECISION   ERR, ERRMAX\n      INTEGER            I, IA, ICD, ICS, ICT, ICU, IM, IN, J, LAA, LBB,\n     $                   LDA, LDAS, LDB, LDBS, M, MS, N, NA, NARGS, NC,\n     $                   NS\n      LOGICAL            LEFT, NULL, RESET, SAME\n      CHARACTER*1        DIAG, DIAGS, SIDE, SIDES, TRANAS, TRANSA, UPLO,\n     $                   UPLOS\n      CHARACTER*2        ICHD, ICHS, ICHU\n      CHARACTER*3        ICHT\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZMAKE, ZMMCH, ZTRMM, ZTRSM\n*     .. Intrinsic Functions ..\n      INTRINSIC          MAX\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHU/'UL'/, ICHT/'NTC'/, ICHD/'UN'/, ICHS/'LR'/\n*     .. Executable Statements ..\n*\n      NARGS = 11\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*     Set up zero matrix for ZMMCH.\n      DO 20 J = 1, NMAX\n         DO 10 I = 1, NMAX\n            C( I, J ) = ZERO\n   10    CONTINUE\n   20 CONTINUE\n*\n      DO 140 IM = 1, NIDIM\n         M = IDIM( IM )\n*\n         DO 130 IN = 1, NIDIM\n            N = IDIM( IN )\n*           Set LDB to 1 more than minimum value if room.\n            LDB = M\n            IF( LDB.LT.NMAX )\n     $         LDB = LDB + 1\n*           Skip tests if not enough room.\n            IF( LDB.GT.NMAX )\n     $         GO TO 130\n            LBB = LDB*N\n            NULL = M.LE.0.OR.N.LE.0\n*\n            DO 120 ICS = 1, 2\n               SIDE = ICHS( ICS: ICS )\n               LEFT = SIDE.EQ.'L'\n               IF( LEFT )THEN\n                  NA = M\n               ELSE\n                  NA = N\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = NA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 130\n               LAA = LDA*NA\n*\n               DO 110 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n*\n                  DO 100 ICT = 1, 3\n                     TRANSA = ICHT( ICT: ICT )\n*\n                     DO 90 ICD = 1, 2\n                        DIAG = ICHD( ICD: ICD )\n*\n                        DO 80 IA = 1, NALF\n                           ALPHA = ALF( IA )\n*\n*                          Generate the matrix A.\n*\n                           CALL ZMAKE( 'TR', UPLO, DIAG, NA, NA, A,\n     $                                 NMAX, AA, LDA, RESET, ZERO )\n*\n*                          Generate the matrix B.\n*\n                           CALL ZMAKE( 'GE', ' ', ' ', M, N, B, NMAX,\n     $                                 BB, LDB, RESET, ZERO )\n*\n                           NC = NC + 1\n*\n*                          Save every datum before calling the\n*                          subroutine.\n*\n                           SIDES = SIDE\n                           UPLOS = UPLO\n                           TRANAS = TRANSA\n                           DIAGS = DIAG\n                           MS = M\n                           NS = N\n                           ALS = ALPHA\n                           DO 30 I = 1, LAA\n                              AS( I ) = AA( I )\n   30                      CONTINUE\n                           LDAS = LDA\n                           DO 40 I = 1, LBB\n                              BS( I ) = BB( I )\n   40                      CONTINUE\n                           LDBS = LDB\n*\n*                          Call the subroutine.\n*\n                           IF( SNAME( 4: 5 ).EQ.'MM' )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           SIDE, UPLO, TRANSA, DIAG, M, N, ALPHA,\n     $                           LDA, LDB\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZTRMM( SIDE, UPLO, TRANSA, DIAG, M,\n     $                                    N, ALPHA, AA, LDA, BB, LDB )\n                           ELSE IF( SNAME( 4: 5 ).EQ.'SM' )THEN\n                              IF( TRACE )\n     $                           WRITE( NTRA, FMT = 9995 )NC, SNAME,\n     $                           SIDE, UPLO, TRANSA, DIAG, M, N, ALPHA,\n     $                           LDA, LDB\n                              IF( REWI )\n     $                           REWIND NTRA\n                              CALL ZTRSM( SIDE, UPLO, TRANSA, DIAG, M,\n     $                                    N, ALPHA, AA, LDA, BB, LDB )\n                           END IF\n*\n*                          Check if error-exit was taken incorrectly.\n*\n                           IF( .NOT.OK )THEN\n                              WRITE( NOUT, FMT = 9994 )\n                              FATAL = .TRUE.\n                              GO TO 150\n                           END IF\n*\n*                          See what data changed inside subroutines.\n*\n                           ISAME( 1 ) = SIDES.EQ.SIDE\n                           ISAME( 2 ) = UPLOS.EQ.UPLO\n                           ISAME( 3 ) = TRANAS.EQ.TRANSA\n                           ISAME( 4 ) = DIAGS.EQ.DIAG\n                           ISAME( 5 ) = MS.EQ.M\n                           ISAME( 6 ) = NS.EQ.N\n                           ISAME( 7 ) = ALS.EQ.ALPHA\n                           ISAME( 8 ) = LZE( AS, AA, LAA )\n                           ISAME( 9 ) = LDAS.EQ.LDA\n                           IF( NULL )THEN\n                              ISAME( 10 ) = LZE( BS, BB, LBB )\n                           ELSE\n                              ISAME( 10 ) = LZERES( 'GE', ' ', M, N, BS,\n     $                                      BB, LDB )\n                           END IF\n                           ISAME( 11 ) = LDBS.EQ.LDB\n*\n*                          If data was incorrectly changed, report and\n*                          return.\n*\n                           SAME = .TRUE.\n                           DO 50 I = 1, NARGS\n                              SAME = SAME.AND.ISAME( I )\n                              IF( .NOT.ISAME( I ) )\n     $                           WRITE( NOUT, FMT = 9998 )I\n   50                      CONTINUE\n                           IF( .NOT.SAME )THEN\n                              FATAL = .TRUE.\n                              GO TO 150\n                           END IF\n*\n                           IF( .NOT.NULL )THEN\n                              IF( SNAME( 4: 5 ).EQ.'MM' )THEN\n*\n*                                Check the result.\n*\n                                 IF( LEFT )THEN\n                                    CALL ZMMCH( TRANSA, 'N', M, N, M,\n     $                                          ALPHA, A, NMAX, B, NMAX,\n     $                                          ZERO, C, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .TRUE. )\n                                 ELSE\n                                    CALL ZMMCH( 'N', TRANSA, M, N, N,\n     $                                          ALPHA, B, NMAX, A, NMAX,\n     $                                          ZERO, C, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .TRUE. )\n                                 END IF\n                              ELSE IF( SNAME( 4: 5 ).EQ.'SM' )THEN\n*\n*                                Compute approximation to original\n*                                matrix.\n*\n                                 DO 70 J = 1, N\n                                    DO 60 I = 1, M\n                                       C( I, J ) = BB( I + ( J - 1 )*\n     $                                             LDB )\n                                       BB( I + ( J - 1 )*LDB ) = ALPHA*\n     $                                    B( I, J )\n   60                               CONTINUE\n   70                            CONTINUE\n*\n                                 IF( LEFT )THEN\n                                    CALL ZMMCH( TRANSA, 'N', M, N, M,\n     $                                          ONE, A, NMAX, C, NMAX,\n     $                                          ZERO, B, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .FALSE. )\n                                 ELSE\n                                    CALL ZMMCH( 'N', TRANSA, M, N, N,\n     $                                          ONE, C, NMAX, A, NMAX,\n     $                                          ZERO, B, NMAX, CT, G,\n     $                                          BB, LDB, EPS, ERR,\n     $                                          FATAL, NOUT, .FALSE. )\n                                 END IF\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 150\n                           END IF\n*\n   80                   CONTINUE\n*\n   90                CONTINUE\n*\n  100             CONTINUE\n*\n  110          CONTINUE\n*\n  120       CONTINUE\n*\n  130    CONTINUE\n*\n  140 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 160\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      WRITE( NOUT, FMT = 9995 )NC, SNAME, SIDE, UPLO, TRANSA, DIAG, M,\n     $   N, ALPHA, LDA, LDB\n*\n  160 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( 1X, I6, ': ', A6, '(', 4( '''', A1, ''',' ), 2( I3, ',' ),\n     $      '(', F4.1, ',', F4.1, '), A,', I3, ', B,', I3, ')         ',\n     $      '      .' )\n 9994 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK3.\n*\n      END\n      SUBROUTINE ZCHK4( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  A, AA, AS, B, BB, BS, C, CC, CS, CT, G )\n*\n*  Tests ZHERK and ZSYRK.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RONE, RZERO\n      PARAMETER          ( RONE = 1.0D0, RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, NMAX ), AA( NMAX*NMAX ), ALF( NALF ),\n     $                   AS( NMAX*NMAX ), B( NMAX, NMAX ),\n     $                   BB( NMAX*NMAX ), BET( NBET ), BS( NMAX*NMAX ),\n     $                   C( NMAX, NMAX ), CC( NMAX*NMAX ),\n     $                   CS( NMAX*NMAX ), CT( NMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, ALS, BETA, BETS\n      DOUBLE PRECISION   ERR, ERRMAX, RALPHA, RALS, RBETA, RBETS\n      INTEGER            I, IA, IB, ICT, ICU, IK, IN, J, JC, JJ, K, KS,\n     $                   LAA, LCC, LDA, LDAS, LDC, LDCS, LJ, MA, N, NA,\n     $                   NARGS, NC, NS\n      LOGICAL            CONJ, NULL, RESET, SAME, TRAN, UPPER\n      CHARACTER*1        TRANS, TRANSS, TRANST, UPLO, UPLOS\n      CHARACTER*2        ICHT, ICHU\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZHERK, ZMAKE, ZMMCH, ZSYRK\n*     .. Intrinsic Functions ..\n      INTRINSIC          DCMPLX, MAX, DBLE\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHT/'NC'/, ICHU/'UL'/\n*     .. Executable Statements ..\n      CONJ = SNAME( 2: 3 ).EQ.'HE'\n*\n      NARGS = 10\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 100 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDC to 1 more than minimum value if room.\n         LDC = N\n         IF( LDC.LT.NMAX )\n     $      LDC = LDC + 1\n*        Skip tests if not enough room.\n         IF( LDC.GT.NMAX )\n     $      GO TO 100\n         LCC = LDC*N\n*\n         DO 90 IK = 1, NIDIM\n            K = IDIM( IK )\n*\n            DO 80 ICT = 1, 2\n               TRANS = ICHT( ICT: ICT )\n               TRAN = TRANS.EQ.'C'\n               IF( TRAN.AND..NOT.CONJ )\n     $            TRANS = 'T'\n               IF( TRAN )THEN\n                  MA = K\n                  NA = N\n               ELSE\n                  MA = N\n                  NA = K\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = MA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 80\n               LAA = LDA*NA\n*\n*              Generate the matrix A.\n*\n               CALL ZMAKE( 'GE', ' ', ' ', MA, NA, A, NMAX, AA, LDA,\n     $                     RESET, ZERO )\n*\n               DO 70 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n                  UPPER = UPLO.EQ.'U'\n*\n                  DO 60 IA = 1, NALF\n                     ALPHA = ALF( IA )\n                     IF( CONJ )THEN\n                        RALPHA = DBLE( ALPHA )\n                        ALPHA = DCMPLX( RALPHA, RZERO )\n                     END IF\n*\n                     DO 50 IB = 1, NBET\n                        BETA = BET( IB )\n                        IF( CONJ )THEN\n                           RBETA = DBLE( BETA )\n                           BETA = DCMPLX( RBETA, RZERO )\n                        END IF\n                        NULL = N.LE.0\n                        IF( CONJ )\n     $                     NULL = NULL.OR.( ( K.LE.0.OR.RALPHA.EQ.\n     $                            RZERO ).AND.RBETA.EQ.RONE )\n*\n*                       Generate the matrix C.\n*\n                        CALL ZMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, C,\n     $                              NMAX, CC, LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        NS = N\n                        KS = K\n                        IF( CONJ )THEN\n                           RALS = RALPHA\n                        ELSE\n                           ALS = ALPHA\n                        END IF\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        IF( CONJ )THEN\n                           RBETS = RBETA\n                        ELSE\n                           BETS = BETA\n                        END IF\n                        DO 20 I = 1, LCC\n                           CS( I ) = CC( I )\n   20                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( CONJ )THEN\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO,\n     $                        TRANS, N, K, RALPHA, LDA, RBETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL ZHERK( UPLO, TRANS, N, K, RALPHA, AA,\n     $                                 LDA, RBETA, CC, LDC )\n                        ELSE\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO,\n     $                        TRANS, N, K, ALPHA, LDA, BETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL ZSYRK( UPLO, TRANS, N, K, ALPHA, AA,\n     $                                 LDA, BETA, CC, LDC )\n                        END IF\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9992 )\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLOS.EQ.UPLO\n                        ISAME( 2 ) = TRANSS.EQ.TRANS\n                        ISAME( 3 ) = NS.EQ.N\n                        ISAME( 4 ) = KS.EQ.K\n                        IF( CONJ )THEN\n                           ISAME( 5 ) = RALS.EQ.RALPHA\n                        ELSE\n                           ISAME( 5 ) = ALS.EQ.ALPHA\n                        END IF\n                        ISAME( 6 ) = LZE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        IF( CONJ )THEN\n                           ISAME( 8 ) = RBETS.EQ.RBETA\n                        ELSE\n                           ISAME( 8 ) = BETS.EQ.BETA\n                        END IF\n                        IF( NULL )THEN\n                           ISAME( 9 ) = LZE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 9 ) = LZERES( SNAME( 2: 3 ), UPLO, N,\n     $                                  N, CS, CC, LDC )\n                        END IF\n                        ISAME( 10 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 30 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   30                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 120\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result column by column.\n*\n                           IF( CONJ )THEN\n                              TRANST = 'C'\n                           ELSE\n                              TRANST = 'T'\n                           END IF\n                           JC = 1\n                           DO 40 J = 1, N\n                              IF( UPPER )THEN\n                                 JJ = 1\n                                 LJ = J\n                              ELSE\n                                 JJ = J\n                                 LJ = N - J + 1\n                              END IF\n                              IF( TRAN )THEN\n                                 CALL ZMMCH( TRANST, 'N', LJ, 1, K,\n     $                                       ALPHA, A( 1, JJ ), NMAX,\n     $                                       A( 1, J ), NMAX, BETA,\n     $                                       C( JJ, J ), NMAX, CT, G,\n     $                                       CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              ELSE\n                                 CALL ZMMCH( 'N', TRANST, LJ, 1, K,\n     $                                       ALPHA, A( JJ, 1 ), NMAX,\n     $                                       A( J, 1 ), NMAX, BETA,\n     $                                       C( JJ, J ), NMAX, CT, G,\n     $                                       CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              END IF\n                              IF( UPPER )THEN\n                                 JC = JC + LDC\n                              ELSE\n                                 JC = JC + LDC + 1\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 110\n   40                      CONTINUE\n                        END IF\n*\n   50                CONTINUE\n*\n   60             CONTINUE\n*\n   70          CONTINUE\n*\n   80       CONTINUE\n*\n   90    CONTINUE\n*\n  100 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 130\n*\n  110 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9995 )J\n*\n  120 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( CONJ )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, N, K, RALPHA,\n     $      LDA, RBETA, LDC\n      ELSE\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, TRANS, N, K, ALPHA,\n     $      LDA, BETA, LDC\n      END IF\n*\n  130 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      F4.1, ', A,', I3, ',', F4.1, ', C,', I3, ')               ',\n     $      '          .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      '(', F4.1, ',', F4.1, ') , A,', I3, ',(', F4.1, ',', F4.1,\n     $      '), C,', I3, ')          .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK4.\n*\n      END\n      SUBROUTINE ZCHK5( SNAME, EPS, THRESH, NOUT, NTRA, TRACE, REWI,\n     $                  FATAL, NIDIM, IDIM, NALF, ALF, NBET, BET, NMAX,\n     $                  AB, AA, AS, BB, BS, C, CC, CS, CT, G, W )\n*\n*  Tests ZHER2K and ZSYR2K.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   ONE = ( 1.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RONE, RZERO\n      PARAMETER          ( RONE = 1.0D0, RZERO = 0.0D0 )\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   EPS, THRESH\n      INTEGER            NALF, NBET, NIDIM, NMAX, NOUT, NTRA\n      LOGICAL            FATAL, REWI, TRACE\n      CHARACTER*6        SNAME\n*     .. Array Arguments ..\n      COMPLEX*16         AA( NMAX*NMAX ), AB( 2*NMAX*NMAX ),\n     $                   ALF( NALF ), AS( NMAX*NMAX ), BB( NMAX*NMAX ),\n     $                   BET( NBET ), BS( NMAX*NMAX ), C( NMAX, NMAX ),\n     $                   CC( NMAX*NMAX ), CS( NMAX*NMAX ), CT( NMAX ),\n     $                   W( 2*NMAX )\n      DOUBLE PRECISION   G( NMAX )\n      INTEGER            IDIM( NIDIM )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, ALS, BETA, BETS\n      DOUBLE PRECISION   ERR, ERRMAX, RBETA, RBETS\n      INTEGER            I, IA, IB, ICT, ICU, IK, IN, J, JC, JJ, JJAB,\n     $                   K, KS, LAA, LBB, LCC, LDA, LDAS, LDB, LDBS,\n     $                   LDC, LDCS, LJ, MA, N, NA, NARGS, NC, NS\n      LOGICAL            CONJ, NULL, RESET, SAME, TRAN, UPPER\n      CHARACTER*1        TRANS, TRANSS, TRANST, UPLO, UPLOS\n      CHARACTER*2        ICHT, ICHU\n*     .. Local Arrays ..\n      LOGICAL            ISAME( 13 )\n*     .. External Functions ..\n      LOGICAL            LZE, LZERES\n      EXTERNAL           LZE, LZERES\n*     .. External Subroutines ..\n      EXTERNAL           ZHER2K, ZMAKE, ZMMCH, ZSYR2K\n*     .. Intrinsic Functions ..\n      INTRINSIC          DCMPLX, DCONJG, MAX, DBLE\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Data statements ..\n      DATA               ICHT/'NC'/, ICHU/'UL'/\n*     .. Executable Statements ..\n      CONJ = SNAME( 2: 3 ).EQ.'HE'\n*\n      NARGS = 12\n      NC = 0\n      RESET = .TRUE.\n      ERRMAX = RZERO\n*\n      DO 130 IN = 1, NIDIM\n         N = IDIM( IN )\n*        Set LDC to 1 more than minimum value if room.\n         LDC = N\n         IF( LDC.LT.NMAX )\n     $      LDC = LDC + 1\n*        Skip tests if not enough room.\n         IF( LDC.GT.NMAX )\n     $      GO TO 130\n         LCC = LDC*N\n*\n         DO 120 IK = 1, NIDIM\n            K = IDIM( IK )\n*\n            DO 110 ICT = 1, 2\n               TRANS = ICHT( ICT: ICT )\n               TRAN = TRANS.EQ.'C'\n               IF( TRAN.AND..NOT.CONJ )\n     $            TRANS = 'T'\n               IF( TRAN )THEN\n                  MA = K\n                  NA = N\n               ELSE\n                  MA = N\n                  NA = K\n               END IF\n*              Set LDA to 1 more than minimum value if room.\n               LDA = MA\n               IF( LDA.LT.NMAX )\n     $            LDA = LDA + 1\n*              Skip tests if not enough room.\n               IF( LDA.GT.NMAX )\n     $            GO TO 110\n               LAA = LDA*NA\n*\n*              Generate the matrix A.\n*\n               IF( TRAN )THEN\n                  CALL ZMAKE( 'GE', ' ', ' ', MA, NA, AB, 2*NMAX, AA,\n     $                        LDA, RESET, ZERO )\n               ELSE\n                  CALL ZMAKE( 'GE', ' ', ' ', MA, NA, AB, NMAX, AA, LDA,\n     $                        RESET, ZERO )\n               END IF\n*\n*              Generate the matrix B.\n*\n               LDB = LDA\n               LBB = LAA\n               IF( TRAN )THEN\n                  CALL ZMAKE( 'GE', ' ', ' ', MA, NA, AB( K + 1 ),\n     $                        2*NMAX, BB, LDB, RESET, ZERO )\n               ELSE\n                  CALL ZMAKE( 'GE', ' ', ' ', MA, NA, AB( K*NMAX + 1 ),\n     $                        NMAX, BB, LDB, RESET, ZERO )\n               END IF\n*\n               DO 100 ICU = 1, 2\n                  UPLO = ICHU( ICU: ICU )\n                  UPPER = UPLO.EQ.'U'\n*\n                  DO 90 IA = 1, NALF\n                     ALPHA = ALF( IA )\n*\n                     DO 80 IB = 1, NBET\n                        BETA = BET( IB )\n                        IF( CONJ )THEN\n                           RBETA = DBLE( BETA )\n                           BETA = DCMPLX( RBETA, RZERO )\n                        END IF\n                        NULL = N.LE.0\n                        IF( CONJ )\n     $                     NULL = NULL.OR.( ( K.LE.0.OR.ALPHA.EQ.\n     $                            ZERO ).AND.RBETA.EQ.RONE )\n*\n*                       Generate the matrix C.\n*\n                        CALL ZMAKE( SNAME( 2: 3 ), UPLO, ' ', N, N, C,\n     $                              NMAX, CC, LDC, RESET, ZERO )\n*\n                        NC = NC + 1\n*\n*                       Save every datum before calling the subroutine.\n*\n                        UPLOS = UPLO\n                        TRANSS = TRANS\n                        NS = N\n                        KS = K\n                        ALS = ALPHA\n                        DO 10 I = 1, LAA\n                           AS( I ) = AA( I )\n   10                   CONTINUE\n                        LDAS = LDA\n                        DO 20 I = 1, LBB\n                           BS( I ) = BB( I )\n   20                   CONTINUE\n                        LDBS = LDB\n                        IF( CONJ )THEN\n                           RBETS = RBETA\n                        ELSE\n                           BETS = BETA\n                        END IF\n                        DO 30 I = 1, LCC\n                           CS( I ) = CC( I )\n   30                   CONTINUE\n                        LDCS = LDC\n*\n*                       Call the subroutine.\n*\n                        IF( CONJ )THEN\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9994 )NC, SNAME, UPLO,\n     $                        TRANS, N, K, ALPHA, LDA, LDB, RBETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL ZHER2K( UPLO, TRANS, N, K, ALPHA, AA,\n     $                                  LDA, BB, LDB, RBETA, CC, LDC )\n                        ELSE\n                           IF( TRACE )\n     $                        WRITE( NTRA, FMT = 9993 )NC, SNAME, UPLO,\n     $                        TRANS, N, K, ALPHA, LDA, LDB, BETA, LDC\n                           IF( REWI )\n     $                        REWIND NTRA\n                           CALL ZSYR2K( UPLO, TRANS, N, K, ALPHA, AA,\n     $                                  LDA, BB, LDB, BETA, CC, LDC )\n                        END IF\n*\n*                       Check if error-exit was taken incorrectly.\n*\n                        IF( .NOT.OK )THEN\n                           WRITE( NOUT, FMT = 9992 )\n                           FATAL = .TRUE.\n                           GO TO 150\n                        END IF\n*\n*                       See what data changed inside subroutines.\n*\n                        ISAME( 1 ) = UPLOS.EQ.UPLO\n                        ISAME( 2 ) = TRANSS.EQ.TRANS\n                        ISAME( 3 ) = NS.EQ.N\n                        ISAME( 4 ) = KS.EQ.K\n                        ISAME( 5 ) = ALS.EQ.ALPHA\n                        ISAME( 6 ) = LZE( AS, AA, LAA )\n                        ISAME( 7 ) = LDAS.EQ.LDA\n                        ISAME( 8 ) = LZE( BS, BB, LBB )\n                        ISAME( 9 ) = LDBS.EQ.LDB\n                        IF( CONJ )THEN\n                           ISAME( 10 ) = RBETS.EQ.RBETA\n                        ELSE\n                           ISAME( 10 ) = BETS.EQ.BETA\n                        END IF\n                        IF( NULL )THEN\n                           ISAME( 11 ) = LZE( CS, CC, LCC )\n                        ELSE\n                           ISAME( 11 ) = LZERES( 'HE', UPLO, N, N, CS,\n     $                                   CC, LDC )\n                        END IF\n                        ISAME( 12 ) = LDCS.EQ.LDC\n*\n*                       If data was incorrectly changed, report and\n*                       return.\n*\n                        SAME = .TRUE.\n                        DO 40 I = 1, NARGS\n                           SAME = SAME.AND.ISAME( I )\n                           IF( .NOT.ISAME( I ) )\n     $                        WRITE( NOUT, FMT = 9998 )I\n   40                   CONTINUE\n                        IF( .NOT.SAME )THEN\n                           FATAL = .TRUE.\n                           GO TO 150\n                        END IF\n*\n                        IF( .NOT.NULL )THEN\n*\n*                          Check the result column by column.\n*\n                           IF( CONJ )THEN\n                              TRANST = 'C'\n                           ELSE\n                              TRANST = 'T'\n                           END IF\n                           JJAB = 1\n                           JC = 1\n                           DO 70 J = 1, N\n                              IF( UPPER )THEN\n                                 JJ = 1\n                                 LJ = J\n                              ELSE\n                                 JJ = J\n                                 LJ = N - J + 1\n                              END IF\n                              IF( TRAN )THEN\n                                 DO 50 I = 1, K\n                                    W( I ) = ALPHA*AB( ( J - 1 )*2*\n     $                                       NMAX + K + I )\n                                    IF( CONJ )THEN\n                                       W( K + I ) = DCONJG( ALPHA )*\n     $                                              AB( ( J - 1 )*2*\n     $                                              NMAX + I )\n                                    ELSE\n                                       W( K + I ) = ALPHA*\n     $                                              AB( ( J - 1 )*2*\n     $                                              NMAX + I )\n                                    END IF\n   50                            CONTINUE\n                                 CALL ZMMCH( TRANST, 'N', LJ, 1, 2*K,\n     $                                       ONE, AB( JJAB ), 2*NMAX, W,\n     $                                       2*NMAX, BETA, C( JJ, J ),\n     $                                       NMAX, CT, G, CC( JC ), LDC,\n     $                                       EPS, ERR, FATAL, NOUT,\n     $                                       .TRUE. )\n                              ELSE\n                                 DO 60 I = 1, K\n                                    IF( CONJ )THEN\n                                       W( I ) = ALPHA*DCONJG( AB( ( K +\n     $                                          I - 1 )*NMAX + J ) )\n                                       W( K + I ) = DCONJG( ALPHA*\n     $                                              AB( ( I - 1 )*NMAX +\n     $                                              J ) )\n                                    ELSE\n                                       W( I ) = ALPHA*AB( ( K + I - 1 )*\n     $                                          NMAX + J )\n                                       W( K + I ) = ALPHA*\n     $                                              AB( ( I - 1 )*NMAX +\n     $                                              J )\n                                    END IF\n   60                            CONTINUE\n                                 CALL ZMMCH( 'N', 'N', LJ, 1, 2*K, ONE,\n     $                                       AB( JJ ), NMAX, W, 2*NMAX,\n     $                                       BETA, C( JJ, J ), NMAX, CT,\n     $                                       G, CC( JC ), LDC, EPS, ERR,\n     $                                       FATAL, NOUT, .TRUE. )\n                              END IF\n                              IF( UPPER )THEN\n                                 JC = JC + LDC\n                              ELSE\n                                 JC = JC + LDC + 1\n                                 IF( TRAN )\n     $                              JJAB = JJAB + 2*NMAX\n                              END IF\n                              ERRMAX = MAX( ERRMAX, ERR )\n*                             If got really bad answer, report and\n*                             return.\n                              IF( FATAL )\n     $                           GO TO 140\n   70                      CONTINUE\n                        END IF\n*\n   80                CONTINUE\n*\n   90             CONTINUE\n*\n  100          CONTINUE\n*\n  110       CONTINUE\n*\n  120    CONTINUE\n*\n  130 CONTINUE\n*\n*     Report result.\n*\n      IF( ERRMAX.LT.THRESH )THEN\n         WRITE( NOUT, FMT = 9999 )SNAME, NC\n      ELSE\n         WRITE( NOUT, FMT = 9997 )SNAME, NC, ERRMAX\n      END IF\n      GO TO 160\n*\n  140 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9995 )J\n*\n  150 CONTINUE\n      WRITE( NOUT, FMT = 9996 )SNAME\n      IF( CONJ )THEN\n         WRITE( NOUT, FMT = 9994 )NC, SNAME, UPLO, TRANS, N, K, ALPHA,\n     $      LDA, LDB, RBETA, LDC\n      ELSE\n         WRITE( NOUT, FMT = 9993 )NC, SNAME, UPLO, TRANS, N, K, ALPHA,\n     $      LDA, LDB, BETA, LDC\n      END IF\n*\n  160 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE COMPUTATIONAL TESTS (', I6, ' CALL',\n     $      'S)' )\n 9998 FORMAT( ' ******* FATAL ERROR - PARAMETER NUMBER ', I2, ' WAS CH',\n     $      'ANGED INCORRECTLY *******' )\n 9997 FORMAT( ' ', A6, ' COMPLETED THE COMPUTATIONAL TESTS (', I6, ' C',\n     $      'ALLS)', /' ******* BUT WITH MAXIMUM TEST RATIO', F8.2,\n     $      ' - SUSPECT *******' )\n 9996 FORMAT( ' ******* ', A6, ' FAILED ON CALL NUMBER:' )\n 9995 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n 9994 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      '(', F4.1, ',', F4.1, '), A,', I3, ', B,', I3, ',', F4.1,\n     $      ', C,', I3, ')           .' )\n 9993 FORMAT( 1X, I6, ': ', A6, '(', 2( '''', A1, ''',' ), 2( I3, ',' ),\n     $      '(', F4.1, ',', F4.1, '), A,', I3, ', B,', I3, ',(', F4.1,\n     $      ',', F4.1, '), C,', I3, ')    .' )\n 9992 FORMAT( ' ******* FATAL ERROR - ERROR-EXIT TAKEN ON VALID CALL *',\n     $      '******' )\n*\n*     End of ZCHK5.\n*\n      END\n      SUBROUTINE ZCHKE( ISNUM, SRNAMT, NOUT )\n*\n*  Tests the error exits from the Level 3 Blas.\n*  Requires a special version of the error-handling routine XERBLA.\n*  A, B and C should not need to be defined.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*  3-19-92:  Initialize ALPHA, BETA, RALPHA, and RBETA  (eca)\n*  3-19-92:  Fix argument 12 in calls to ZSYMM and ZHEMM\n*            with INFOT = 9  (eca)\n*  10-9-00:  Declared INTRINSIC DCMPLX (susan)\n*\n*     .. Scalar Arguments ..\n      INTEGER            ISNUM, NOUT\n      CHARACTER*6        SRNAMT\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUTC\n      LOGICAL            LERR, OK\n*     .. Parameters ..\n      REAL               ONE, TWO\n      PARAMETER          ( ONE = 1.0D0, TWO = 2.0D0 )\n*     .. Local Scalars ..\n      COMPLEX*16         ALPHA, BETA\n      DOUBLE PRECISION   RALPHA, RBETA\n*     .. Local Arrays ..\n      COMPLEX*16         A( 2, 1 ), B( 2, 1 ), C( 2, 1 )\n*     .. External Subroutines ..\n      EXTERNAL           ZGEMM, ZHEMM, ZHER2K, ZHERK, CHKXER, ZSYMM,\n     $                   ZSYR2K, ZSYRK, ZTRMM, ZTRSM\n*     .. Intrinsic Functions ..\n      INTRINSIC          DCMPLX\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUTC, OK, LERR\n*     .. Executable Statements ..\n*     OK is set to .FALSE. by the special version of XERBLA or by CHKXER\n*     if anything is wrong.\n      OK = .TRUE.\n*     LERR is set to .TRUE. by the special version of XERBLA each time\n*     it is called, and is then tested and re-set by CHKXER.\n      LERR = .FALSE.\n*\n*     Initialize ALPHA, BETA, RALPHA, and RBETA.\n*\n      ALPHA = DCMPLX( ONE, -ONE )\n      BETA = DCMPLX( TWO, -TWO )\n      RALPHA = ONE\n      RBETA = TWO\n*\n      GO TO ( 10, 20, 30, 40, 50, 60, 70, 80,\n     $        90 )ISNUM\n   10 INFOT = 1\n      CALL ZGEMM( '/', 'N', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 1\n      CALL ZGEMM( '/', 'C', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 1\n      CALL ZGEMM( '/', 'T', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZGEMM( 'N', '/', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZGEMM( 'C', '/', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZGEMM( 'T', '/', 0, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGEMM( 'N', 'N', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGEMM( 'N', 'C', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGEMM( 'N', 'T', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGEMM( 'C', 'N', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGEMM( 'C', 'C', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGEMM( 'C', 'T', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGEMM( 'T', 'N', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGEMM( 'T', 'C', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZGEMM( 'T', 'T', -1, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZGEMM( 'N', 'N', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZGEMM( 'N', 'C', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZGEMM( 'N', 'T', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZGEMM( 'C', 'N', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZGEMM( 'C', 'C', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZGEMM( 'C', 'T', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZGEMM( 'T', 'N', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZGEMM( 'T', 'C', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZGEMM( 'T', 'T', 0, -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGEMM( 'N', 'N', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGEMM( 'N', 'C', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGEMM( 'N', 'T', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGEMM( 'C', 'N', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGEMM( 'C', 'C', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGEMM( 'C', 'T', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGEMM( 'T', 'N', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGEMM( 'T', 'C', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZGEMM( 'T', 'T', 0, 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGEMM( 'N', 'N', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGEMM( 'N', 'C', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGEMM( 'N', 'T', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGEMM( 'C', 'N', 0, 0, 2, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGEMM( 'C', 'C', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGEMM( 'C', 'T', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGEMM( 'T', 'N', 0, 0, 2, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGEMM( 'T', 'C', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 8\n      CALL ZGEMM( 'T', 'T', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZGEMM( 'N', 'N', 0, 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZGEMM( 'C', 'N', 0, 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZGEMM( 'T', 'N', 0, 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZGEMM( 'N', 'C', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZGEMM( 'C', 'C', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZGEMM( 'T', 'C', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZGEMM( 'N', 'T', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZGEMM( 'C', 'T', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZGEMM( 'T', 'T', 0, 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL ZGEMM( 'N', 'N', 2, 0, 0, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL ZGEMM( 'N', 'C', 2, 0, 0, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL ZGEMM( 'N', 'T', 2, 0, 0, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL ZGEMM( 'C', 'N', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL ZGEMM( 'C', 'C', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL ZGEMM( 'C', 'T', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL ZGEMM( 'T', 'N', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL ZGEMM( 'T', 'C', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 13\n      CALL ZGEMM( 'T', 'T', 2, 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   20 INFOT = 1\n      CALL ZHEMM( '/', 'U', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZHEMM( 'L', '/', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHEMM( 'L', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHEMM( 'R', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHEMM( 'L', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHEMM( 'R', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHEMM( 'L', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHEMM( 'R', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHEMM( 'L', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHEMM( 'R', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHEMM( 'L', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHEMM( 'R', 'U', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHEMM( 'L', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHEMM( 'R', 'L', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZHEMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZHEMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZHEMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZHEMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZHEMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZHEMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZHEMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZHEMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   30 INFOT = 1\n      CALL ZSYMM( '/', 'U', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZSYMM( 'L', '/', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYMM( 'L', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYMM( 'R', 'U', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYMM( 'L', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYMM( 'R', 'L', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYMM( 'L', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYMM( 'R', 'U', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYMM( 'L', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYMM( 'R', 'L', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYMM( 'L', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYMM( 'R', 'U', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYMM( 'L', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYMM( 'R', 'L', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZSYMM( 'L', 'U', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZSYMM( 'R', 'U', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZSYMM( 'L', 'L', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZSYMM( 'R', 'L', 2, 0, ALPHA, A, 1, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   40 INFOT = 1\n      CALL ZTRMM( '/', 'U', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZTRMM( 'L', '/', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZTRMM( 'L', 'U', '/', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZTRMM( 'L', 'U', 'N', '/', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'L', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'L', 'U', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'L', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'R', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'R', 'U', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'R', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'L', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'L', 'L', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'L', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'R', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'R', 'L', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRMM( 'R', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'L', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'L', 'U', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'L', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'R', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'R', 'U', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'R', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'L', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'L', 'L', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'L', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'R', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'R', 'L', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRMM( 'R', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'L', 'U', 'C', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'R', 'U', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'R', 'U', 'C', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'R', 'U', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'L', 'L', 'C', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'R', 'L', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'R', 'L', 'C', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRMM( 'R', 'L', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'L', 'U', 'C', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'R', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'R', 'U', 'C', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'R', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'L', 'L', 'C', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'R', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'R', 'L', 'C', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRMM( 'R', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   50 INFOT = 1\n      CALL ZTRSM( '/', 'U', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZTRSM( 'L', '/', 'N', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZTRSM( 'L', 'U', '/', 'N', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZTRSM( 'L', 'U', 'N', '/', 0, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'L', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'L', 'U', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'L', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'R', 'U', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'R', 'U', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'R', 'U', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'L', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'L', 'L', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'L', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'R', 'L', 'N', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'R', 'L', 'C', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 5\n      CALL ZTRSM( 'R', 'L', 'T', 'N', -1, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'L', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'L', 'U', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'L', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'R', 'U', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'R', 'U', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'R', 'U', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'L', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'L', 'L', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'L', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'R', 'L', 'N', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'R', 'L', 'C', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 6\n      CALL ZTRSM( 'R', 'L', 'T', 'N', 0, -1, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'L', 'U', 'C', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'R', 'U', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'R', 'U', 'C', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'R', 'U', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'L', 'L', 'C', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'R', 'L', 'N', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'R', 'L', 'C', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZTRSM( 'R', 'L', 'T', 'N', 0, 2, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'L', 'U', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'L', 'U', 'C', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'L', 'U', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'R', 'U', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'R', 'U', 'C', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'R', 'U', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'L', 'L', 'N', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'L', 'L', 'C', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'L', 'L', 'T', 'N', 2, 0, ALPHA, A, 2, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'R', 'L', 'N', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'R', 'L', 'C', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 11\n      CALL ZTRSM( 'R', 'L', 'T', 'N', 2, 0, ALPHA, A, 1, B, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   60 INFOT = 1\n      CALL ZHERK( '/', 'N', 0, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZHERK( 'U', 'T', 0, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHERK( 'U', 'N', -1, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHERK( 'U', 'C', -1, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHERK( 'L', 'N', -1, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHERK( 'L', 'C', -1, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHERK( 'U', 'N', 0, -1, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHERK( 'U', 'C', 0, -1, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHERK( 'L', 'N', 0, -1, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHERK( 'L', 'C', 0, -1, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHERK( 'U', 'N', 2, 0, RALPHA, A, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHERK( 'U', 'C', 0, 2, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHERK( 'L', 'N', 2, 0, RALPHA, A, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHERK( 'L', 'C', 0, 2, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZHERK( 'U', 'N', 2, 0, RALPHA, A, 2, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZHERK( 'U', 'C', 2, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZHERK( 'L', 'N', 2, 0, RALPHA, A, 2, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZHERK( 'L', 'C', 2, 0, RALPHA, A, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   70 INFOT = 1\n      CALL ZSYRK( '/', 'N', 0, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZSYRK( 'U', 'C', 0, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYRK( 'U', 'N', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYRK( 'U', 'T', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYRK( 'L', 'N', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYRK( 'L', 'T', -1, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYRK( 'U', 'N', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYRK( 'U', 'T', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYRK( 'L', 'N', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYRK( 'L', 'T', 0, -1, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYRK( 'U', 'N', 2, 0, ALPHA, A, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYRK( 'U', 'T', 0, 2, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYRK( 'L', 'N', 2, 0, ALPHA, A, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYRK( 'L', 'T', 0, 2, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZSYRK( 'U', 'N', 2, 0, ALPHA, A, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZSYRK( 'U', 'T', 2, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZSYRK( 'L', 'N', 2, 0, ALPHA, A, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 10\n      CALL ZSYRK( 'L', 'T', 2, 0, ALPHA, A, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   80 INFOT = 1\n      CALL ZHER2K( '/', 'N', 0, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZHER2K( 'U', 'T', 0, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHER2K( 'U', 'N', -1, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHER2K( 'U', 'C', -1, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHER2K( 'L', 'N', -1, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZHER2K( 'L', 'C', -1, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHER2K( 'U', 'N', 0, -1, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHER2K( 'U', 'C', 0, -1, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHER2K( 'L', 'N', 0, -1, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZHER2K( 'L', 'C', 0, -1, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHER2K( 'U', 'N', 2, 0, ALPHA, A, 1, B, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHER2K( 'U', 'C', 0, 2, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHER2K( 'L', 'N', 2, 0, ALPHA, A, 1, B, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZHER2K( 'L', 'C', 0, 2, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZHER2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZHER2K( 'U', 'C', 0, 2, ALPHA, A, 2, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZHER2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 1, RBETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZHER2K( 'L', 'C', 0, 2, ALPHA, A, 2, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZHER2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 2, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZHER2K( 'U', 'C', 2, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZHER2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 2, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZHER2K( 'L', 'C', 2, 0, ALPHA, A, 1, B, 1, RBETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      GO TO 100\n   90 INFOT = 1\n      CALL ZSYR2K( '/', 'N', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 2\n      CALL ZSYR2K( 'U', 'C', 0, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYR2K( 'U', 'N', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYR2K( 'U', 'T', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYR2K( 'L', 'N', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 3\n      CALL ZSYR2K( 'L', 'T', -1, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYR2K( 'U', 'N', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYR2K( 'U', 'T', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYR2K( 'L', 'N', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 4\n      CALL ZSYR2K( 'L', 'T', 0, -1, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYR2K( 'U', 'N', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYR2K( 'U', 'T', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYR2K( 'L', 'N', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 7\n      CALL ZSYR2K( 'L', 'T', 0, 2, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZSYR2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZSYR2K( 'U', 'T', 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZSYR2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 1, BETA, C, 2 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 9\n      CALL ZSYR2K( 'L', 'T', 0, 2, ALPHA, A, 2, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZSYR2K( 'U', 'N', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZSYR2K( 'U', 'T', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZSYR2K( 'L', 'N', 2, 0, ALPHA, A, 2, B, 2, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n      INFOT = 12\n      CALL ZSYR2K( 'L', 'T', 2, 0, ALPHA, A, 1, B, 1, BETA, C, 1 )\n      CALL CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n  100 IF( OK )THEN\n         WRITE( NOUT, FMT = 9999 )SRNAMT\n      ELSE\n         WRITE( NOUT, FMT = 9998 )SRNAMT\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ', A6, ' PASSED THE TESTS OF ERROR-EXITS' )\n 9998 FORMAT( ' ******* ', A6, ' FAILED THE TESTS OF ERROR-EXITS *****',\n     $      '**' )\n*\n*     End of ZCHKE.\n*\n      END\n      SUBROUTINE ZMAKE( TYPE, UPLO, DIAG, M, N, A, NMAX, AA, LDA, RESET,\n     $                  TRANSL )\n*\n*  Generates values for an M by N matrix A.\n*  Stores the values in the array AA in the data structure required\n*  by the routine, with unwanted elements set to rogue value.\n*\n*  TYPE is 'GE', 'HE', 'SY' or 'TR'.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO, ONE\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ),\n     $                   ONE = ( 1.0D0, 0.0D0 ) )\n      COMPLEX*16         ROGUE\n      PARAMETER          ( ROGUE = ( -1.0D10, 1.0D10 ) )\n      DOUBLE PRECISION   RZERO\n      PARAMETER          ( RZERO = 0.0D0 )\n      DOUBLE PRECISION   RROGUE\n      PARAMETER          ( RROGUE = -1.0D10 )\n*     .. Scalar Arguments ..\n      COMPLEX*16         TRANSL\n      INTEGER            LDA, M, N, NMAX\n      LOGICAL            RESET\n      CHARACTER*1        DIAG, UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      COMPLEX*16         A( NMAX, * ), AA( * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J, JJ\n      LOGICAL            GEN, HER, LOWER, SYM, TRI, UNIT, UPPER\n*     .. External Functions ..\n      COMPLEX*16         ZBEG\n      EXTERNAL           ZBEG\n*     .. Intrinsic Functions ..\n      INTRINSIC          DCMPLX, DCONJG, DBLE\n*     .. Executable Statements ..\n      GEN = TYPE.EQ.'GE'\n      HER = TYPE.EQ.'HE'\n      SYM = TYPE.EQ.'SY'\n      TRI = TYPE.EQ.'TR'\n      UPPER = ( HER.OR.SYM.OR.TRI ).AND.UPLO.EQ.'U'\n      LOWER = ( HER.OR.SYM.OR.TRI ).AND.UPLO.EQ.'L'\n      UNIT = TRI.AND.DIAG.EQ.'U'\n*\n*     Generate data in array A.\n*\n      DO 20 J = 1, N\n         DO 10 I = 1, M\n            IF( GEN.OR.( UPPER.AND.I.LE.J ).OR.( LOWER.AND.I.GE.J ) )\n     $          THEN\n               A( I, J ) = ZBEG( RESET ) + TRANSL\n               IF( I.NE.J )THEN\n*                 Set some elements to zero\n                  IF( N.GT.3.AND.J.EQ.N/2 )\n     $               A( I, J ) = ZERO\n                  IF( HER )THEN\n                     A( J, I ) = DCONJG( A( I, J ) )\n                  ELSE IF( SYM )THEN\n                     A( J, I ) = A( I, J )\n                  ELSE IF( TRI )THEN\n                     A( J, I ) = ZERO\n                  END IF\n               END IF\n            END IF\n   10    CONTINUE\n         IF( HER )\n     $      A( J, J ) = DCMPLX( DBLE( A( J, J ) ), RZERO )\n         IF( TRI )\n     $      A( J, J ) = A( J, J ) + ONE\n         IF( UNIT )\n     $      A( J, J ) = ONE\n   20 CONTINUE\n*\n*     Store elements in array AS in data structure required by routine.\n*\n      IF( TYPE.EQ.'GE' )THEN\n         DO 50 J = 1, N\n            DO 30 I = 1, M\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   30       CONTINUE\n            DO 40 I = M + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   40       CONTINUE\n   50    CONTINUE\n      ELSE IF( TYPE.EQ.'HE'.OR.TYPE.EQ.'SY'.OR.TYPE.EQ.'TR' )THEN\n         DO 90 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IF( UNIT )THEN\n                  IEND = J - 1\n               ELSE\n                  IEND = J\n               END IF\n            ELSE\n               IF( UNIT )THEN\n                  IBEG = J + 1\n               ELSE\n                  IBEG = J\n               END IF\n               IEND = N\n            END IF\n            DO 60 I = 1, IBEG - 1\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   60       CONTINUE\n            DO 70 I = IBEG, IEND\n               AA( I + ( J - 1 )*LDA ) = A( I, J )\n   70       CONTINUE\n            DO 80 I = IEND + 1, LDA\n               AA( I + ( J - 1 )*LDA ) = ROGUE\n   80       CONTINUE\n            IF( HER )THEN\n               JJ = J + ( J - 1 )*LDA\n               AA( JJ ) = DCMPLX( DBLE( AA( JJ ) ), RROGUE )\n            END IF\n   90    CONTINUE\n      END IF\n      RETURN\n*\n*     End of ZMAKE.\n*\n      END\n      SUBROUTINE ZMMCH( TRANSA, TRANSB, M, N, KK, ALPHA, A, LDA, B, LDB,\n     $                  BETA, C, LDC, CT, G, CC, LDCC, EPS, ERR, FATAL,\n     $                  NOUT, MV )\n*\n*  Checks the results of the computational tests.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Parameters ..\n      COMPLEX*16         ZERO\n      PARAMETER          ( ZERO = ( 0.0D0, 0.0D0 ) )\n      DOUBLE PRECISION   RZERO, RONE\n      PARAMETER          ( RZERO = 0.0D0, RONE = 1.0D0 )\n*     .. Scalar Arguments ..\n      COMPLEX*16         ALPHA, BETA\n      DOUBLE PRECISION   EPS, ERR\n      INTEGER            KK, LDA, LDB, LDC, LDCC, M, N, NOUT\n      LOGICAL            FATAL, MV\n      CHARACTER*1        TRANSA, TRANSB\n*     .. Array Arguments ..\n      COMPLEX*16         A( LDA, * ), B( LDB, * ), C( LDC, * ),\n     $                   CC( LDCC, * ), CT( * )\n      DOUBLE PRECISION   G( * )\n*     .. Local Scalars ..\n      COMPLEX*16         CL\n      DOUBLE PRECISION   ERRI\n      INTEGER            I, J, K\n      LOGICAL            CTRANA, CTRANB, TRANA, TRANB\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, DIMAG, DCONJG, MAX, DBLE, SQRT\n*     .. Statement Functions ..\n      DOUBLE PRECISION   ABS1\n*     .. Statement Function definitions ..\n      ABS1( CL ) = ABS( DBLE( CL ) ) + ABS( DIMAG( CL ) )\n*     .. Executable Statements ..\n      TRANA = TRANSA.EQ.'T'.OR.TRANSA.EQ.'C'\n      TRANB = TRANSB.EQ.'T'.OR.TRANSB.EQ.'C'\n      CTRANA = TRANSA.EQ.'C'\n      CTRANB = TRANSB.EQ.'C'\n*\n*     Compute expected result, one column at a time, in CT using data\n*     in A, B and C.\n*     Compute gauges in G.\n*\n      DO 220 J = 1, N\n*\n         DO 10 I = 1, M\n            CT( I ) = ZERO\n            G( I ) = RZERO\n   10    CONTINUE\n         IF( .NOT.TRANA.AND..NOT.TRANB )THEN\n            DO 30 K = 1, KK\n               DO 20 I = 1, M\n                  CT( I ) = CT( I ) + A( I, K )*B( K, J )\n                  G( I ) = G( I ) + ABS1( A( I, K ) )*ABS1( B( K, J ) )\n   20          CONTINUE\n   30       CONTINUE\n         ELSE IF( TRANA.AND..NOT.TRANB )THEN\n            IF( CTRANA )THEN\n               DO 50 K = 1, KK\n                  DO 40 I = 1, M\n                     CT( I ) = CT( I ) + DCONJG( A( K, I ) )*B( K, J )\n                     G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                        ABS1( B( K, J ) )\n   40             CONTINUE\n   50          CONTINUE\n            ELSE\n               DO 70 K = 1, KK\n                  DO 60 I = 1, M\n                     CT( I ) = CT( I ) + A( K, I )*B( K, J )\n                     G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                        ABS1( B( K, J ) )\n   60             CONTINUE\n   70          CONTINUE\n            END IF\n         ELSE IF( .NOT.TRANA.AND.TRANB )THEN\n            IF( CTRANB )THEN\n               DO 90 K = 1, KK\n                  DO 80 I = 1, M\n                     CT( I ) = CT( I ) + A( I, K )*DCONJG( B( J, K ) )\n                     G( I ) = G( I ) + ABS1( A( I, K ) )*\n     $                        ABS1( B( J, K ) )\n   80             CONTINUE\n   90          CONTINUE\n            ELSE\n               DO 110 K = 1, KK\n                  DO 100 I = 1, M\n                     CT( I ) = CT( I ) + A( I, K )*B( J, K )\n                     G( I ) = G( I ) + ABS1( A( I, K ) )*\n     $                        ABS1( B( J, K ) )\n  100             CONTINUE\n  110          CONTINUE\n            END IF\n         ELSE IF( TRANA.AND.TRANB )THEN\n            IF( CTRANA )THEN\n               IF( CTRANB )THEN\n                  DO 130 K = 1, KK\n                     DO 120 I = 1, M\n                        CT( I ) = CT( I ) + DCONJG( A( K, I ) )*\n     $                            DCONJG( B( J, K ) )\n                        G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                           ABS1( B( J, K ) )\n  120                CONTINUE\n  130             CONTINUE\n               ELSE\n                  DO 150 K = 1, KK\n                     DO 140 I = 1, M\n                        CT( I ) = CT( I ) + DCONJG( A( K, I ) )*\n     $                            B( J, K )\n                        G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                           ABS1( B( J, K ) )\n  140                CONTINUE\n  150             CONTINUE\n               END IF\n            ELSE\n               IF( CTRANB )THEN\n                  DO 170 K = 1, KK\n                     DO 160 I = 1, M\n                        CT( I ) = CT( I ) + A( K, I )*\n     $                            DCONJG( B( J, K ) )\n                        G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                           ABS1( B( J, K ) )\n  160                CONTINUE\n  170             CONTINUE\n               ELSE\n                  DO 190 K = 1, KK\n                     DO 180 I = 1, M\n                        CT( I ) = CT( I ) + A( K, I )*B( J, K )\n                        G( I ) = G( I ) + ABS1( A( K, I ) )*\n     $                           ABS1( B( J, K ) )\n  180                CONTINUE\n  190             CONTINUE\n               END IF\n            END IF\n         END IF\n         DO 200 I = 1, M\n            CT( I ) = ALPHA*CT( I ) + BETA*C( I, J )\n            G( I ) = ABS1( ALPHA )*G( I ) +\n     $               ABS1( BETA )*ABS1( C( I, J ) )\n  200    CONTINUE\n*\n*        Compute the error ratio for this result.\n*\n         ERR = ZERO\n         DO 210 I = 1, M\n            ERRI = ABS1( CT( I ) - CC( I, J ) )/EPS\n            IF( G( I ).NE.RZERO )\n     $         ERRI = ERRI/G( I )\n            ERR = MAX( ERR, ERRI )\n            IF( ERR*SQRT( EPS ).GE.RONE )\n     $         GO TO 230\n  210    CONTINUE\n*\n  220 CONTINUE\n*\n*     If the loop completes, all results are at least half accurate.\n      GO TO 250\n*\n*     Report fatal error.\n*\n  230 FATAL = .TRUE.\n      WRITE( NOUT, FMT = 9999 )\n      DO 240 I = 1, M\n         IF( MV )THEN\n            WRITE( NOUT, FMT = 9998 )I, CT( I ), CC( I, J )\n         ELSE\n            WRITE( NOUT, FMT = 9998 )I, CC( I, J ), CT( I )\n         END IF\n  240 CONTINUE\n      IF( N.GT.1 )\n     $   WRITE( NOUT, FMT = 9997 )J\n*\n  250 CONTINUE\n      RETURN\n*\n 9999 FORMAT( ' ******* FATAL ERROR - COMPUTED RESULT IS LESS THAN HAL',\n     $      'F ACCURATE *******', /'                       EXPECTED RE',\n     $      'SULT                    COMPUTED RESULT' )\n 9998 FORMAT( 1X, I7, 2( '  (', G15.6, ',', G15.6, ')' ) )\n 9997 FORMAT( '      THESE ARE THE RESULTS FOR COLUMN ', I3 )\n*\n*     End of ZMMCH.\n*\n      END\n      LOGICAL FUNCTION LZE( RI, RJ, LR )\n*\n*  Tests if two arrays are identical.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LR\n*     .. Array Arguments ..\n      COMPLEX*16         RI( * ), RJ( * )\n*     .. Local Scalars ..\n      INTEGER            I\n*     .. Executable Statements ..\n      DO 10 I = 1, LR\n         IF( RI( I ).NE.RJ( I ) )\n     $      GO TO 20\n   10 CONTINUE\n      LZE = .TRUE.\n      GO TO 30\n   20 CONTINUE\n      LZE = .FALSE.\n   30 RETURN\n*\n*     End of LZE.\n*\n      END\n      LOGICAL FUNCTION LZERES( TYPE, UPLO, M, N, AA, AS, LDA )\n*\n*  Tests if selected elements in two arrays are equal.\n*\n*  TYPE is 'GE' or 'HE' or 'SY'.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            LDA, M, N\n      CHARACTER*1        UPLO\n      CHARACTER*2        TYPE\n*     .. Array Arguments ..\n      COMPLEX*16         AA( LDA, * ), AS( LDA, * )\n*     .. Local Scalars ..\n      INTEGER            I, IBEG, IEND, J\n      LOGICAL            UPPER\n*     .. Executable Statements ..\n      UPPER = UPLO.EQ.'U'\n      IF( TYPE.EQ.'GE' )THEN\n         DO 20 J = 1, N\n            DO 10 I = M + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   10       CONTINUE\n   20    CONTINUE\n      ELSE IF( TYPE.EQ.'HE'.OR.TYPE.EQ.'SY' )THEN\n         DO 50 J = 1, N\n            IF( UPPER )THEN\n               IBEG = 1\n               IEND = J\n            ELSE\n               IBEG = J\n               IEND = N\n            END IF\n            DO 30 I = 1, IBEG - 1\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   30       CONTINUE\n            DO 40 I = IEND + 1, LDA\n               IF( AA( I, J ).NE.AS( I, J ) )\n     $            GO TO 70\n   40       CONTINUE\n   50    CONTINUE\n      END IF\n*\n      LZERES = .TRUE.\n      GO TO 80\n   70 CONTINUE\n      LZERES = .FALSE.\n   80 RETURN\n*\n*     End of LZERES.\n*\n      END\n      COMPLEX*16     FUNCTION ZBEG( RESET )\n*\n*  Generates complex numbers as pairs of random numbers uniformly\n*  distributed between -0.5 and 0.5.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      LOGICAL            RESET\n*     .. Local Scalars ..\n      INTEGER            I, IC, J, MI, MJ\n*     .. Save statement ..\n      SAVE               I, IC, J, MI, MJ\n*     .. Intrinsic Functions ..\n      INTRINSIC          DCMPLX\n*     .. Executable Statements ..\n      IF( RESET )THEN\n*        Initialize local variables.\n         MI = 891\n         MJ = 457\n         I = 7\n         J = 7\n         IC = 0\n         RESET = .FALSE.\n      END IF\n*\n*     The sequence of values of I or J is bounded between 1 and 999.\n*     If initial I or J = 1,2,3,6,7 or 9, the period will be 50.\n*     If initial I or J = 4 or 8, the period will be 25.\n*     If initial I or J = 5, the period will be 10.\n*     IC is used to break up the period by skipping 1 value of I or J\n*     in 6.\n*\n      IC = IC + 1\n   10 I = I*MI\n      J = J*MJ\n      I = I - 1000*( I/1000 )\n      J = J - 1000*( J/1000 )\n      IF( IC.GE.5 )THEN\n         IC = 0\n         GO TO 10\n      END IF\n      ZBEG = DCMPLX( ( I - 500 )/1001.0D0, ( J - 500 )/1001.0D0 )\n      RETURN\n*\n*     End of ZBEG.\n*\n      END\n      DOUBLE PRECISION FUNCTION DDIFF( X, Y )\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   X, Y\n*     .. Executable Statements ..\n      DDIFF = X - Y\n      RETURN\n*\n*     End of DDIFF.\n*\n      END\n      SUBROUTINE CHKXER( SRNAMT, INFOT, NOUT, LERR, OK )\n*\n*  Tests whether XERBLA has detected an error when it should.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Executable Statements ..\n      IF( .NOT.LERR )THEN\n         WRITE( NOUT, FMT = 9999 )INFOT, SRNAMT\n         OK = .FALSE.\n      END IF\n      LERR = .FALSE.\n      RETURN\n*\n 9999 FORMAT( ' ***** ILLEGAL VALUE OF PARAMETER NUMBER ', I2, ' NOT D',\n     $      'ETECTED BY ', A6, ' *****' )\n*\n*     End of CHKXER.\n*\n      END\n      SUBROUTINE XERBLA( SRNAME, INFO )\n*\n*  This is a special version of XERBLA to be used only as part of\n*  the test program for testing error exits from the Level 3 BLAS\n*  routines.\n*\n*  XERBLA  is an error handler for the Level 3 BLAS routines.\n*\n*  It is called by the Level 3 BLAS routines if an input parameter is\n*  invalid.\n*\n*  Auxiliary routine for test program for Level 3 Blas.\n*\n*  -- Written on 8-February-1989.\n*     Jack Dongarra, Argonne National Laboratory.\n*     Iain Duff, AERE Harwell.\n*     Jeremy Du Croz, Numerical Algorithms Group Ltd.\n*     Sven Hammarling, Numerical Algorithms Group Ltd.\n*\n*     .. Scalar Arguments ..\n      INTEGER            INFO\n      CHARACTER*6        SRNAME\n*     .. Scalars in Common ..\n      INTEGER            INFOT, NOUT\n      LOGICAL            LERR, OK\n      CHARACTER*6        SRNAMT\n*     .. Common blocks ..\n      COMMON             /INFOC/INFOT, NOUT, OK, LERR\n      COMMON             /SRNAMC/SRNAMT\n*     .. Executable Statements ..\n      LERR = .TRUE.\n      IF( INFO.NE.INFOT )THEN\n         IF( INFOT.NE.0 )THEN\n            WRITE( NOUT, FMT = 9999 )INFO, INFOT\n         ELSE\n            WRITE( NOUT, FMT = 9997 )INFO\n         END IF\n         OK = .FALSE.\n      END IF\n      IF( SRNAME.NE.SRNAMT )THEN\n         WRITE( NOUT, FMT = 9998 )SRNAME, SRNAMT\n         OK = .FALSE.\n      END IF\n      RETURN\n*\n 9999 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6, ' INSTEAD',\n     $      ' OF ', I2, ' *******' )\n 9998 FORMAT( ' ******* XERBLA WAS CALLED WITH SRNAME = ', A6, ' INSTE',\n     $      'AD OF ', A6, ' *******' )\n 9997 FORMAT( ' ******* XERBLA WAS CALLED WITH INFO = ', I6,\n     $      ' *******' )\n*\n*     End of XERBLA\n*\n      END\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/blas/xerbla.cpp",
    "content": "\n#include <stdio.h>\n\n#if (defined __GNUC__) && (!defined __MINGW32__) && (!defined __CYGWIN__)\n#define EIGEN_WEAK_LINKING __attribute__ ((weak))\n#else\n#define EIGEN_WEAK_LINKING\n#endif\n\n#ifdef __cplusplus\nextern \"C\"\n{\n#endif\n\nEIGEN_WEAK_LINKING int xerbla_(const char * msg, int *info, int)\n{\n  printf(\"Eigen BLAS ERROR #%i: %s\\n\", *info, msg );\n  return 0;\n}\n\n#ifdef __cplusplus\n}\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/ci/CTest2JUnit.xsl",
    "content": "<xsl:stylesheet xmlns:xsl=\"http://www.w3.org/1999/XSL/Transform\" version=\"1.0\">\n<xsl:output method=\"xml\" indent=\"yes\"/>\n    <xsl:template match=\"/Site\">\n\t<xsl:variable name=\"Name\"><xsl:value-of select=\"@Name\"/></xsl:variable>\n\t<xsl:variable name=\"Hostname\"><xsl:value-of select=\"@Hostname\"/></xsl:variable>\n\t<xsl:variable name=\"TestCount\"><xsl:value-of select=\"count(//TestList/Test)\"/> </xsl:variable>\n\t<xsl:variable name=\"ErrorCount\"><xsl:value-of select=\"count(//TestList/Test[@Status='error'])\"/> </xsl:variable>\n\t<xsl:variable name=\"FailureCount\"><xsl:value-of select=\"count(//Testing/Test[@Status='failed'])\"/> </xsl:variable>\n\t<testsuite name=\"{$Name}\" hostname=\"{$Hostname}\" errors=\"0\" failures=\"{$FailureCount}\" tests=\"{$TestCount}\">\n\t    <xsl:variable name=\"BuildName\"><xsl:value-of select=\"@BuildName\"/></xsl:variable>\n\t    <xsl:variable name=\"BuildStamp\"><xsl:value-of select=\"@BuildStamp\"/></xsl:variable>\n\t    <xsl:variable name=\"Generator\"><xsl:value-of select=\"@Generator\"/></xsl:variable>\n\t    <xsl:variable name=\"CompilerName\"><xsl:value-of select=\"@CompilerName\"/></xsl:variable>\n\t    <xsl:variable name=\"OSName\"><xsl:value-of select=\"@OSName\"/></xsl:variable>\n\t    <xsl:variable name=\"OSRelease\"><xsl:value-of select=\"@OSRelease\"/></xsl:variable>\n\t    <xsl:variable name=\"OSVersion\"><xsl:value-of select=\"@OSVersion\"/></xsl:variable>\n\t    <xsl:variable name=\"OSPlatform\"><xsl:value-of select=\"@OSPlatform\"/></xsl:variable>\n\t    <xsl:variable name=\"Is64Bits\"><xsl:value-of select=\"@Is64Bits\"/></xsl:variable>\n\t    <xsl:variable name=\"VendorString\"><xsl:value-of select=\"@VendorString\"/></xsl:variable>\n\t    <xsl:variable name=\"VendorID\"><xsl:value-of select=\"@VendorID\"/></xsl:variable>\n\t    <xsl:variable name=\"FamilyID\"><xsl:value-of select=\"@FamilyID\"/></xsl:variable>\n\t    <xsl:variable name=\"ModelID\"><xsl:value-of select=\"@ModelID\"/></xsl:variable>\n\t    <xsl:variable name=\"ProcessorCacheSize\"><xsl:value-of select=\"@ProcessorCacheSize\"/></xsl:variable>\n\t    <xsl:variable name=\"NumberOfLogicalCPU\"><xsl:value-of select=\"@NumberOfLogicalCPU\"/></xsl:variable>\n\t    <xsl:variable name=\"NumberOfPhysicalCPU\"><xsl:value-of select=\"@NumberOfPhysicalCPU\"/></xsl:variable>\n\t    <xsl:variable name=\"TotalVirtualMemory\"><xsl:value-of select=\"@TotalVirtualMemory\"/></xsl:variable>\n\t    <xsl:variable name=\"TotalPhysicalMemory\"><xsl:value-of select=\"@TotalPhysicalMemory\"/></xsl:variable>\n\t    <xsl:variable name=\"LogicalProcessorsPerPhysical\"><xsl:value-of select=\"@LogicalProcessorsPerPhysical\"/></xsl:variable>\n\t    <xsl:variable name=\"ProcessorClockFrequency\"><xsl:value-of select=\"@ProcessorClockFrequency\"/></xsl:variable>\n\t    <properties>\n\t\t<property name=\"BuildName\" value=\"{$BuildName}\" />\n\t\t<property name=\"BuildStamp\" value=\"{$BuildStamp}\" />\n\t\t<property name=\"Name\" value=\"{$Name}\" />\n\t\t<property name=\"Generator\" value=\"{$Generator}\" />\n\t\t<property name=\"CompilerName\" value=\"{$CompilerName}\" />\n\t\t<property name=\"OSName\" value=\"{$OSName}\" />\n\t\t<property name=\"Hostname\" value=\"{$Hostname}\" />\n\t\t<property name=\"OSRelease\" value=\"{$OSRelease}\" />\n\t\t<property name=\"OSVersion\" value=\"{$OSVersion}\" />\n\t\t<property name=\"OSPlatform\" value=\"{$OSPlatform}\" />\n\t\t<property name=\"Is64Bits\" value=\"{$Is64Bits}\" />\n\t\t<property name=\"VendorString\" value=\"{$VendorString}\" />\n\t\t<property name=\"VendorID\" value=\"{$VendorID}\" />\n\t\t<property name=\"FamilyID\" value=\"{$FamilyID}\" />\n\t\t<property name=\"ModelID\" value=\"{$ModelID}\" />\n\t\t<property name=\"ProcessorCacheSize\" value=\"{$ProcessorCacheSize}\" />\n\t\t<property name=\"NumberOfLogicalCPU\" value=\"{$NumberOfLogicalCPU}\" />\n\t\t<property name=\"NumberOfPhysicalCPU\" value=\"{$NumberOfPhysicalCPU}\" />\n\t\t<property name=\"TotalVirtualMemory\" value=\"{$TotalVirtualMemory}\" />\n\t\t<property name=\"TotalPhysicalMemory\" value=\"{$TotalPhysicalMemory}\" />\n\t\t<property name=\"LogicalProcessorsPerPhysical\" value=\"{$LogicalProcessorsPerPhysical}\" />\n\t\t<property name=\"ProcessorClockFrequency\" value=\"{$ProcessorClockFrequency}\" />\n\t    </properties>\n\t    <xsl:apply-templates select=\"Testing/Test\"/>\n\n\t    <system-out>\n\t\tBuildName: <xsl:value-of select=\"$BuildName\" />\n\t\tBuildStamp: <xsl:value-of select=\"$BuildStamp\" />\n\t\tName: <xsl:value-of select=\"$Name\" />\n\t\tGenerator: <xsl:value-of select=\"$Generator\" />\n\t\tCompilerName: <xsl:value-of select=\"$CompilerName\" />\n\t\tOSName: <xsl:value-of select=\"$OSName\" />\n\t\tHostname: <xsl:value-of select=\"$Hostname\" />\n\t\tOSRelease: <xsl:value-of select=\"$OSRelease\" />\n\t\tOSVersion: <xsl:value-of select=\"$OSVersion\" />\n\t\tOSPlatform: <xsl:value-of select=\"$OSPlatform\" />\n\t\tIs64Bits: <xsl:value-of select=\"$Is64Bits\" />\n\t\tVendorString: <xsl:value-of select=\"$VendorString\" />\n\t\tVendorID: <xsl:value-of select=\"$VendorID\" />\n\t\tFamilyID: <xsl:value-of select=\"$FamilyID\" />\n\t\tModelID: <xsl:value-of select=\"$ModelID\" />\n\t\tProcessorCacheSize: <xsl:value-of select=\"$ProcessorCacheSize\" />\n\t\tNumberOfLogicalCPU: <xsl:value-of select=\"$NumberOfLogicalCPU\" />\n\t\tNumberOfPhysicalCPU: <xsl:value-of select=\"$NumberOfPhysicalCPU\" />\n\t\tTotalVirtualMemory: <xsl:value-of select=\"$TotalVirtualMemory\" />\n\t\tTotalPhysicalMemory: <xsl:value-of select=\"$TotalPhysicalMemory\" />\n\t\tLogicalProcessorsPerPhysical: <xsl:value-of select=\"$LogicalProcessorsPerPhysical\" />\n\t\tProcessorClockFrequency: <xsl:value-of select=\"$ProcessorClockFrequency\" />\n\t    </system-out>\n\t</testsuite>\n    </xsl:template>\n\n    <xsl:template match=\"Testing/Test\">\n\t<xsl:variable name=\"testcasename\"><xsl:value-of select= \"Name\"/></xsl:variable>\n\t<xsl:variable name=\"testclassname\"><xsl:value-of select= \" concat('this', substring(Path,2))\"/></xsl:variable>\n\t<xsl:variable name=\"exectime\">\n\t    <xsl:for-each select=\"Results/NamedMeasurement\">\n\t\t<xsl:if test=\"@name = 'Execution Time'\">\n\t\t    <xsl:value-of select=\".\"/>\n\t\t</xsl:if>\n\t    </xsl:for-each>\n\t</xsl:variable>\n\n\t<testcase name=\"{$testcasename}\" classname=\"{$testclassname}\" time=\"{$exectime}\">\n\t    <xsl:if test=\"@Status = 'passed'\">\n\t    </xsl:if>\n\t    <xsl:if test=\"@Status = 'failed'\">\n\t\t<xsl:variable name=\"failtype\">\n\t\t    <xsl:for-each select=\"Results/NamedMeasurement\">\n\t\t\t<xsl:if test=\"@name = 'Exit Code'\">\n\t\t\t    <xsl:value-of select=\".\"/>\n\t\t\t</xsl:if>\n\t\t    </xsl:for-each>\n\t\t</xsl:variable>\n\t\t<xsl:variable name=\"failcode\">\n\t\t    <xsl:for-each select=\"Results/NamedMeasurement\">\n\t\t\t<xsl:if test=\"@name = 'Exit Value'\">\n\t\t\t    <xsl:value-of select=\".\"/>\n\t\t\t</xsl:if>\n\t\t    </xsl:for-each>\n\t\t</xsl:variable>\n\t\t<failure message=\"{$failtype} ({$failcode})\"><xsl:value-of select=\"Results/Measurement/Value/text()\" /></failure>\n\t    </xsl:if>\n\t    <xsl:if test=\"@Status = 'notrun'\">\n\t\t<skipped><xsl:value-of select=\"Results/Measurement/Value/text()\" /></skipped>\n\t    </xsl:if>\n\t</testcase>\n    </xsl:template>\n\n</xsl:stylesheet>\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/ci/README.md",
    "content": "## Eigen CI infrastructure\n\nEigen's CI infrastructure uses two stages: A `build` stage to build the unit-test\nsuite and a `test` stage to run the unit-tests.\n\n### Build Stage\n\nThe build stage consists of the following jobs:\n\n| Job Name                                 | Arch      | OS             | Compiler   | C++11   |\n|------------------------------------------|-----------|----------------|------------|---------|\n| `build:x86-64:linux:gcc-4.8:cxx11-off`   | `x86-64`  | `Ubuntu 18.04` | `GCC-4.8`  | `Off`   |\n| `build:x86-64:linux:gcc-4.8:cxx11-on`    | `x86-64`  | `Ubuntu 18.04` | `GCC-4.8`  | `On`    |\n| `build:x86-64:linux:gcc-9:cxx11-off`     | `x86-64`  | `Ubuntu 18.04` | `GCC-9`    | `Off`   |\n| `build:x86-64:linux:gcc-9:cxx11-on`      | `x86-64`  | `Ubuntu 18.04` | `GCC-9`    | `On`    |\n| `build:x86-64:linux:gcc-10:cxx11-off`    | `x86-64`  | `Ubuntu 18.04` | `GCC-10`   | `Off`   |\n| `build:x86-64:linux:gcc-10:cxx11-on`     | `x86-64`  | `Ubuntu 18.04` | `GCC-10`   | `On`    |\n| `build:x86-64:linux:clang-10:cxx11-off`  | `x86-64`  | `Ubuntu 18.04` | `Clang-10` | `Off`   |\n| `build:x86-64:linux:clang-10:cxx11-on`   | `x86-64`  | `Ubuntu 18.04` | `Clang-10` | `On`    |\n| `build:aarch64:linux:gcc-10:cxx11-off`   | `AArch64` | `Ubuntu 18.04` | `GCC-10`   | `Off`   |\n| `build:aarch64:linux:gcc-10:cxx11-on`    | `AArch64` | `Ubuntu 18.04` | `GCC-10`   | `On`    |\n| `build:aarch64:linux:clang-10:cxx11-off` | `AArch64` | `Ubuntu 18.04` | `Clang-10` | `Off`   |\n| `build:aarch64:linux:clang-10:cxx11-on`  | `AArch64` | `Ubuntu 18.04` | `Clang-10` | `On`    |\n\n### Test stage\n\nIn principle every build-job has a corresponding test-job, however testing supported and unsupported modules is divided into separate jobs. The test jobs in detail:\n\n### Job dependecies\n\n| Job Name                                            | Arch      | OS             | Compiler   | C++11   | Module\n|-----------------------------------------------------|-----------|----------------|------------|---------|--------\n| `test:x86-64:linux:gcc-4.8:cxx11-off:official`      | `x86-64`  | `Ubuntu 18.04` | `GCC-4.8`  | `Off`   | `Official`\n| `test:x86-64:linux:gcc-4.8:cxx11-off:unsupported`   | `x86-64`  | `Ubuntu 18.04` | `GCC-4.8`  | `Off`   | `Unsupported`\n| `test:x86-64:linux:gcc-4.8:cxx11-on:official`       | `x86-64`  | `Ubuntu 18.04` | `GCC-4.8`  | `On`    | `Official`\n| `test:x86-64:linux:gcc-4.8:cxx11-on:unsupported`    | `x86-64`  | `Ubuntu 18.04` | `GCC-4.8`  | `On`    | `Unsupported`\n| `test:x86-64:linux:gcc-9:cxx11-off:official`        | `x86-64`  | `Ubuntu 18.04` | `GCC-9`    | `Off`   | `Official`\n| `test:x86-64:linux:gcc-9:cxx11-off:unsupported`     | `x86-64`  | `Ubuntu 18.04` | `GCC-9`    | `Off`   | `Unsupported`\n| `test:x86-64:linux:gcc-9:cxx11-on:official`         | `x86-64`  | `Ubuntu 18.04` | `GCC-9`    | `On`    | `Official`\n| `test:x86-64:linux:gcc-9:cxx11-on:unsupported`      | `x86-64`  | `Ubuntu 18.04` | `GCC-9`    | `On`    | `Unsupported`\n| `test:x86-64:linux:gcc-10:cxx11-off:official`       | `x86-64`  | `Ubuntu 18.04` | `GCC-10`   | `Off`   | `Official`\n| `test:x86-64:linux:gcc-10:cxx11-off:unsupported`    | `x86-64`  | `Ubuntu 18.04` | `GCC-10`   | `Off`   | `Unsupported`\n| `test:x86-64:linux:gcc-10:cxx11-on:official`        | `x86-64`  | `Ubuntu 18.04` | `GCC-10`   | `On`    | `Official`\n| `test:x86-64:linux:gcc-10:cxx11-on:unsupported`     | `x86-64`  | `Ubuntu 18.04` | `GCC-10`   | `On`    | `Unsupported`\n| `test:x86-64:linux:clang-10:cxx11-off:official`     | `x86-64`  | `Ubuntu 18.04` | `Clang-10` | `Off`   | `Official`\n| `test:x86-64:linux:clang-10:cxx11-off:unsupported`  | `x86-64`  | `Ubuntu 18.04` | `Clang-10` | `Off`   | `Unsupported`\n| `test:x86-64:linux:clang-10:cxx11-on:official`      | `x86-64`  | `Ubuntu 18.04` | `Clang-10` | `On`    | `Official`\n| `test:x86-64:linux:clang-10:cxx11-on:unsupported`   | `x86-64`  | `Ubuntu 18.04` | `Clang-10` | `On`    | `Unsupported`\n| `test:aarch64:linux:gcc-10:cxx11-off:official`      | `AArch64` | `Ubuntu 18.04` | `GCC-10`   | `Off`   | `Official`\n| `test:aarch64:linux:gcc-10:cxx11-off:unsupported`   | `AArch64` | `Ubuntu 18.04` | `GCC-10`   | `Off`   | `Unsupported`\n| `test:aarch64:linux:gcc-10:cxx11-on:official`       | `AArch64` | `Ubuntu 18.04` | `GCC-10`   | `On`    | `Official`\n| `test:aarch64:linux:gcc-10:cxx11-on:unsupported`    | `AArch64` | `Ubuntu 18.04` | `GCC-10`   | `On`    | `Unsupported`\n| `test:aarch64:linux:clang-10:cxx11-off:official`    | `AArch64` | `Ubuntu 18.04` | `Clang-10` | `Off`   | `Official`\n| `test:aarch64:linux:clang-10:cxx11-off:unsupported` | `AArch64` | `Ubuntu 18.04` | `Clang-10` | `Off`   | `Unsupported`\n| `test:aarch64:linux:clang-10:cxx11-on:official`     | `AArch64` | `Ubuntu 18.04` | `Clang-10` | `On`    | `Official`\n| `test:aarch64:linux:clang-10:cxx11-on:unsupported`  | `AArch64` | `Ubuntu 18.04` | `Clang-10` | `On`    | `Unsupported`\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/ci/test.gitlab-ci.yml",
    "content": ".test:linux:base:\n  stage: test\n  image: ubuntu:18.04\n  retry: 2\n  before_script:\n    - apt-get update -y\n    - apt-get install -y --no-install-recommends software-properties-common\n    - add-apt-repository -y ppa:ubuntu-toolchain-r/test\n    - apt-get update\n    - apt-get install --no-install-recommends -y ${EIGEN_CI_CXX_COMPILER}\n      ${EIGEN_CI_CC_COMPILER} cmake ninja-build xsltproc\n  script:\n    - export CXX=${EIGEN_CI_CXX_COMPILER}\n    - export CC=${EIGEN_CI_CC_COMPILER}\n    - cd ${BUILDDIR} && ctest --output-on-failure --no-compress-output\n      --build-no-clean -T test -L ${EIGEN_CI_TEST_LABEL}\n  after_script:\n    - apt-get update -y\n    - apt-get install --no-install-recommends -y xsltproc\n    - cd ${BUILDDIR}\n    - xsltproc ../ci/CTest2JUnit.xsl Testing/`head -n 1 < Testing/TAG`/Test.xml > \"JUnitTestResults_$CI_JOB_ID.xml\"\n  artifacts:\n    reports:\n      junit:\n        - ${BUILDDIR}/JUnitTestResults_$CI_JOB_ID.xml\n    expire_in: 5 days\n  only:\n    - schedules\n\n##### x86-64 ###################################################################\n# GCC-4.8\n.test:x86-64:linux:gcc-4.8:cxx11-off:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: g++-4.8\n    EIGEN_CI_CC_COMPILER: gcc-4.8\n  needs: [ \"build:x86-64:linux:gcc-4.8:cxx11-off\" ]\n  tags: \n    - eigen-runner\n    - linux\n    - x86-64\n\ntest:x86-64:linux:gcc-4.8:cxx11-off:official:\n  extends: .test:x86-64:linux:gcc-4.8:cxx11-off\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:x86-64:linux:gcc-4.8:cxx11-off:unsupported:\n  extends: .test:x86-64:linux:gcc-4.8:cxx11-off\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n.test:x86-64:linux:gcc-4.8:cxx11-on:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: g++-4.8\n    EIGEN_CI_CC_COMPILER: gcc-4.8\n  needs: [ \"build:x86-64:linux:gcc-4.8:cxx11-on\" ]\n  tags: \n    - eigen-runner\n    - linux\n    - x86-64\n\ntest:x86-64:linux:gcc-4.8:cxx11-on:official:\n  extends: .test:x86-64:linux:gcc-4.8:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:x86-64:linux:gcc-4.8:cxx11-on:unsupported:\n  extends: .test:x86-64:linux:gcc-4.8:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n# GCC-9\n.test:x86-64:linux:gcc-9:cxx11-off:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: g++-9\n    EIGEN_CI_CC_COMPILER: gcc-9\n  needs: [ \"build:x86-64:linux:gcc-9:cxx11-off\" ]\n  tags: \n    - eigen-runner\n    - linux\n    - x86-64\n\ntest:x86-64:linux:gcc-9:cxx11-off:official:\n  extends: .test:x86-64:linux:gcc-9:cxx11-off\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:x86-64:linux:gcc-9:cxx11-off:unsupported:\n  extends: .test:x86-64:linux:gcc-9:cxx11-off\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n.test:x86-64:linux:gcc-9:cxx11-on:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: g++-9\n    EIGEN_CI_CC_COMPILER: gcc-9\n  needs: [ \"build:x86-64:linux:gcc-9:cxx11-on\" ]\n  tags: \n    - eigen-runner\n    - linux\n    - x86-64\n\ntest:x86-64:linux:gcc-9:cxx11-on:official:\n  extends: .test:x86-64:linux:gcc-9:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:x86-64:linux:gcc-9:cxx11-on:unsupported:\n  extends: .test:x86-64:linux:gcc-9:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n# GCC-10\n.test:x86-64:linux:gcc-10:cxx11-off:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: g++-10\n    EIGEN_CI_CC_COMPILER: gcc-10\n  needs: [ \"build:x86-64:linux:gcc-10:cxx11-off\" ]\n  tags: \n    - eigen-runner\n    - linux\n    - x86-64\n\ntest:x86-64:linux:gcc-10:cxx11-off:official:\n  extends: .test:x86-64:linux:gcc-10:cxx11-off\n  allow_failure: true\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:x86-64:linux:gcc-10:cxx11-off:unsupported:\n  extends: .test:x86-64:linux:gcc-10:cxx11-off\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n.test:x86-64:linux:gcc-10:cxx11-on:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: g++-10\n    EIGEN_CI_CC_COMPILER: gcc-10\n  needs: [ \"build:x86-64:linux:gcc-10:cxx11-on\" ]\n  tags: \n    - eigen-runner\n    - linux\n    - x86-64\n\ntest:x86-64:linux:gcc-10:cxx11-on:official:\n  extends: .test:x86-64:linux:gcc-10:cxx11-on\n  allow_failure: true\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:x86-64:linux:gcc-10:cxx11-on:unsupported:\n  extends: .test:x86-64:linux:gcc-10:cxx11-on\n  allow_failure: true\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n# Clang 10\n.test:x86-64:linux:clang-10:cxx11-off:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: clang++-10\n    EIGEN_CI_CC_COMPILER: clang-10\n  needs: [ \"build:x86-64:linux:clang-10:cxx11-off\" ]\n  tags: \n    - eigen-runner\n    - linux\n    - x86-64\n\ntest:x86-64:linux:clang-10:cxx11-off:official:\n  extends: .test:x86-64:linux:clang-10:cxx11-off\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:x86-64:linux:clang-10:cxx11-off:unsupported:\n  extends: .test:x86-64:linux:clang-10:cxx11-off\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n.test:x86-64:linux:clang-10:cxx11-on:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: clang++-10\n    EIGEN_CI_CC_COMPILER: clang-10\n  needs: [ \"build:x86-64:linux:clang-10:cxx11-on\" ]\n  tags: \n    - eigen-runner\n    - linux\n    - x86-64\n\ntest:x86-64:linux:clang-10:cxx11-on:official:\n  extends: .test:x86-64:linux:clang-10:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:x86-64:linux:clang-10:cxx11-on:unsupported:\n  extends: .test:x86-64:linux:clang-10:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n##### AArch64 ##################################################################\n# GCC-10\n.test:aarch64:linux:gcc-10:cxx11-off:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: g++-10\n    EIGEN_CI_CC_COMPILER: gcc-10\n  needs: [ \"build:aarch64:linux:gcc-10:cxx11-off\" ]\n  tags: \n    - eigen-runner\n    - linux\n    - aarch64\n\ntest:aarch64:linux:gcc-10:cxx11-off:official:\n  extends: .test:aarch64:linux:gcc-10:cxx11-off\n  allow_failure: true\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:aarch64:linux:gcc-10:cxx11-off:unsupported:\n  extends: .test:aarch64:linux:gcc-10:cxx11-off\n  allow_failure: true\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n.test:aarch64:linux:gcc-10:cxx11-on:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: g++-10\n    EIGEN_CI_CC_COMPILER: gcc-10\n  needs: [ \"build:aarch64:linux:gcc-10:cxx11-on\" ]\n  tags: \n    - eigen-runner\n    - linux\n    - aarch64\n\ntest:aarch64:linux:gcc-10:cxx11-on:official:\n  extends: .test:aarch64:linux:gcc-10:cxx11-on\n  allow_failure: true\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:aarch64:linux:gcc-10:cxx11-on:unsupported:\n  extends: .test:aarch64:linux:gcc-10:cxx11-on\n  allow_failure: true\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n# Clang 10\n.test:aarch64:linux:clang-10:cxx11-off:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: clang++-10\n    EIGEN_CI_CC_COMPILER: clang-10\n  needs: [ \"build:aarch64:linux:clang-10:cxx11-off\" ]\n  tags: \n    - eigen-runner\n    - linux\n    - aarch64\n\ntest:aarch64:linux:clang-10:cxx11-off:official:\n  extends: .test:aarch64:linux:clang-10:cxx11-off\n  allow_failure: true\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:aarch64:linux:clang-10:cxx11-off:unsupported:\n  extends: .test:aarch64:linux:clang-10:cxx11-off\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n.test:aarch64:linux:clang-10:cxx11-on:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: clang++-10\n    EIGEN_CI_CC_COMPILER: clang-10\n  needs: [ \"build:aarch64:linux:clang-10:cxx11-on\" ]\n  tags: \n    - eigen-runner\n    - linux\n    - aarch64\n\ntest:aarch64:linux:clang-10:cxx11-on:official:\n  extends: .test:aarch64:linux:clang-10:cxx11-on\n  allow_failure: true\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:aarch64:linux:clang-10:cxx11-on:unsupported:\n  extends: .test:aarch64:linux:clang-10:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n##### ppc64le ##################################################################\n# GCC-10\n.test:ppc64le:linux:gcc-10:cxx11-off:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: g++-10\n    EIGEN_CI_CC_COMPILER: gcc-10\n  needs: [ \"build:ppc64le:linux:gcc-10:cxx11-off\" ]\n  allow_failure: true\n  tags: \n    - eigen-runner\n    - linux\n    - ppc64le\n\ntest:ppc64le:linux:gcc-10:cxx11-off:official:\n  extends: .test:ppc64le:linux:gcc-10:cxx11-off\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:ppc64le:linux:gcc-10:cxx11-off:unsupported:\n  extends: .test:ppc64le:linux:gcc-10:cxx11-off\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n.test:ppc64le:linux:gcc-10:cxx11-on:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: g++-10\n    EIGEN_CI_CC_COMPILER: gcc-10\n  needs: [ \"build:ppc64le:linux:gcc-10:cxx11-on\" ]\n  allow_failure: true\n  tags: \n    - eigen-runner\n    - linux\n    - ppc64le\n\ntest:ppc64le:linux:gcc-10:cxx11-on:official:\n  extends: .test:ppc64le:linux:gcc-10:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:ppc64le:linux:gcc-10:cxx11-on:unsupported:\n  extends: .test:ppc64le:linux:gcc-10:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n# # Clang 10\n.test:ppc64le:linux:clang-10:cxx11-off:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: clang++-10\n    EIGEN_CI_CC_COMPILER: clang-10\n  needs: [ \"build:ppc64le:linux:clang-10:cxx11-off\" ]\n  allow_failure: true\n  tags: \n    - eigen-runner\n    - linux\n    - ppc64le\n\ntest:ppc64le:linux:clang-10:cxx11-off:official:\n  extends: .test:ppc64le:linux:clang-10:cxx11-off\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:ppc64le:linux:clang-10:cxx11-off:unsupported:\n  extends: .test:ppc64le:linux:clang-10:cxx11-off\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n\n.test:ppc64le:linux:clang-10:cxx11-on:\n  extends: .test:linux:base\n  variables:\n    EIGEN_CI_CXX_COMPILER: clang++-10\n    EIGEN_CI_CC_COMPILER: clang-10\n  needs: [ \"build:ppc64le:linux:clang-10:cxx11-on\" ]\n  allow_failure: true\n  tags: \n    - eigen-runner\n    - linux\n    - ppc64le\n\ntest:ppc64le:linux:clang-10:cxx11-on:official:\n  extends: .test:ppc64le:linux:clang-10:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Official\"\n\ntest:ppc64le:linux:clang-10:cxx11-on:unsupported:\n  extends: .test:ppc64le:linux:clang-10:cxx11-on\n  variables:\n    EIGEN_CI_TEST_LABEL: \"Unsupported\"\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/ComputeCppCompilerChecks.cmake",
    "content": "cmake_minimum_required(VERSION 3.4.3)\n\nif(CMAKE_COMPILER_IS_GNUCXX)\n  if (CMAKE_CXX_COMPILER_VERSION VERSION_LESS 4.8)\n    message(FATAL_ERROR \"host compiler - gcc version must be > 4.8\")\n  endif()\nelseif (\"${CMAKE_CXX_COMPILER_ID}\" STREQUAL \"Clang\")\n  if (${CMAKE_CXX_COMPILER_VERSION} VERSION_LESS 3.6)\n    message(FATAL_ERROR \"host compiler - clang version must be > 3.6\")\n  endif()\nendif()\n\nif(MSVC)\n  set(ComputeCpp_STL_CHECK_SRC __STL_check)\n  file(WRITE ${CMAKE_CURRENT_BINARY_DIR}/${ComputeCpp_STL_CHECK_SRC}.cpp\n    \"#include <ios>\\n\"\n    \"int main() { return 0; }\\n\")\n  execute_process(\n    COMMAND ${ComputeCpp_DEVICE_COMPILER_EXECUTABLE}\n            ${COMPUTECPP_DEVICE_COMPILER_FLAGS}\n            -isystem ${ComputeCpp_INCLUDE_DIRS}\n            -o ${ComputeCpp_STL_CHECK_SRC}.sycl\n            -c ${ComputeCpp_STL_CHECK_SRC}.cpp\n    WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}\n    RESULT_VARIABLE ComputeCpp_STL_CHECK_RESULT\n    ERROR_QUIET\n    OUTPUT_QUIET)\n  if(NOT ${ComputeCpp_STL_CHECK_RESULT} EQUAL 0)\n    # Try disabling compiler version checks\n    execute_process(\n      COMMAND ${ComputeCpp_DEVICE_COMPILER_EXECUTABLE}\n              ${COMPUTECPP_DEVICE_COMPILER_FLAGS}\n              -D_ALLOW_COMPILER_AND_STL_VERSION_MISMATCH\n              -isystem ${ComputeCpp_INCLUDE_DIRS}\n              -o ${ComputeCpp_STL_CHECK_SRC}.cpp.sycl\n              -c ${ComputeCpp_STL_CHECK_SRC}.cpp\n      WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}\n      RESULT_VARIABLE ComputeCpp_STL_CHECK_RESULT\n      ERROR_QUIET\n      OUTPUT_QUIET)\n    if(NOT ${ComputeCpp_STL_CHECK_RESULT} EQUAL 0)\n      message(STATUS \"Device compiler cannot consume hosted STL headers. Using any parts of the STL will likely result in device compiler errors.\")\n    else()\n    message(STATUS \"Device compiler does not meet certain STL version requirements. Disabling version checks and hoping for the best.\")\n      list(APPEND COMPUTECPP_DEVICE_COMPILER_FLAGS -D_ALLOW_COMPILER_AND_STL_VERSION_MISMATCH)\n    endif()\n  endif()\n  file(REMOVE ${CMAKE_CURRENT_BINARY_DIR}/${ComputeCpp_STL_CHECK_SRC}.cpp\n              ${CMAKE_CURRENT_BINARY_DIR}/${ComputeCpp_STL_CHECK_SRC}.cpp.sycl)\nendif(MSVC)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/ComputeCppIRMap.cmake",
    "content": "cmake_minimum_required(VERSION 3.4.3)\n\n# These should match the types of IR output by compute++\nset(IR_MAP_spir bc)\nset(IR_MAP_spir64 bc)\nset(IR_MAP_spir32 bc)\nset(IR_MAP_spirv spv)\nset(IR_MAP_spirv64 spv)\nset(IR_MAP_spirv32 spv)\nset(IR_MAP_aorta-x86_64 o)\nset(IR_MAP_aorta-aarch64 o)\nset(IR_MAP_aorta-rcar-cve o)\nset(IR_MAP_custom-spir64 bc)\nset(IR_MAP_custom-spir32 bc)\nset(IR_MAP_custom-spirv64 spv)\nset(IR_MAP_custom-spirv32 spv)\nset(IR_MAP_ptx64 s)\nset(IR_MAP_amdgcn s)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/Eigen3Config.cmake.in",
    "content": "# This file exports the Eigen3::Eigen CMake target which should be passed to the\n# target_link_libraries command.\n\n@PACKAGE_INIT@\n\nif (NOT TARGET eigen)\n  include (\"${CMAKE_CURRENT_LIST_DIR}/Eigen3Targets.cmake\")\nendif ()\n\n# Legacy variables, do *not* use. May be removed in the future.\n\nset (EIGEN3_FOUND 1)\nset (EIGEN3_USE_FILE    \"${CMAKE_CURRENT_LIST_DIR}/UseEigen3.cmake\")\n\nset (EIGEN3_DEFINITIONS  \"@EIGEN_DEFINITIONS@\")\nset (EIGEN3_INCLUDE_DIR  \"@PACKAGE_EIGEN_INCLUDE_DIR@\")\nset (EIGEN3_INCLUDE_DIRS \"@PACKAGE_EIGEN_INCLUDE_DIR@\")\nset (EIGEN3_ROOT_DIR     \"@PACKAGE_EIGEN_ROOT_DIR@\")\n\nset (EIGEN3_VERSION_STRING \"@EIGEN_VERSION_STRING@\")\nset (EIGEN3_VERSION_MAJOR  \"@EIGEN_VERSION_MAJOR@\")\nset (EIGEN3_VERSION_MINOR  \"@EIGEN_VERSION_MINOR@\")\nset (EIGEN3_VERSION_PATCH  \"@EIGEN_VERSION_PATCH@\")\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/Eigen3ConfigLegacy.cmake.in",
    "content": "#                                               -*- cmake -*-\n#\n#  Eigen3Config.cmake(.in)\n\n# Use the following variables to compile and link against Eigen:\n#  EIGEN3_FOUND              - True if Eigen was found on your system\n#  EIGEN3_USE_FILE           - The file making Eigen usable\n#  EIGEN3_DEFINITIONS        - Definitions needed to build with Eigen\n#  EIGEN3_INCLUDE_DIR        - Directory where signature_of_eigen3_matrix_library can be found\n#  EIGEN3_INCLUDE_DIRS       - List of directories of Eigen and it's dependencies\n#  EIGEN3_ROOT_DIR           - The base directory of Eigen\n#  EIGEN3_VERSION_STRING     - A human-readable string containing the version\n#  EIGEN3_VERSION_MAJOR      - The major version of Eigen\n#  EIGEN3_VERSION_MINOR      - The minor version of Eigen\n#  EIGEN3_VERSION_PATCH      - The patch version of Eigen\n\n@PACKAGE_INIT@\n\nset ( EIGEN3_FOUND 1 )\nset ( EIGEN3_USE_FILE     \"${CMAKE_CURRENT_LIST_DIR}/UseEigen3.cmake\" )\n\nset ( EIGEN3_DEFINITIONS  \"@EIGEN_DEFINITIONS@\" )\nset ( EIGEN3_INCLUDE_DIR  \"@PACKAGE_EIGEN_INCLUDE_DIR@\" )\nset ( EIGEN3_INCLUDE_DIRS \"@PACKAGE_EIGEN_INCLUDE_DIR@\" )\nset ( EIGEN3_ROOT_DIR     \"@PACKAGE_EIGEN_ROOT_DIR@\" )\n\nset ( EIGEN3_VERSION_STRING \"@EIGEN_VERSION_STRING@\" )\nset ( EIGEN3_VERSION_MAJOR  \"@EIGEN_VERSION_MAJOR@\" )\nset ( EIGEN3_VERSION_MINOR  \"@EIGEN_VERSION_MINOR@\" )\nset ( EIGEN3_VERSION_PATCH  \"@EIGEN_VERSION_PATCH@\" )\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/EigenConfigureTesting.cmake",
    "content": "include(EigenTesting)\ninclude(CheckCXXSourceCompiles)\n\n# configure the \"site\" and \"buildname\" \nei_set_sitename()\n\n# retrieve and store the build string\nei_set_build_string()\n\nadd_custom_target(buildtests)\nadd_custom_target(check COMMAND \"ctest\")\nadd_dependencies(check buildtests)\n\n# check whether /bin/bash exists (disabled as not used anymore)\n# find_file(EIGEN_BIN_BASH_EXISTS \"/bin/bash\" PATHS \"/\" NO_DEFAULT_PATH)\n\n# This call activates testing and generates the DartConfiguration.tcl\ninclude(CTest)\n\nset(EIGEN_TEST_BUILD_FLAGS \"\" CACHE STRING \"Options passed to the build command of unit tests\")\nset(EIGEN_DASHBOARD_BUILD_TARGET \"buildtests\" CACHE STRING \"Target to be built in dashboard mode, default is buildtests\")\nset(EIGEN_CTEST_ERROR_EXCEPTION \"\" CACHE STRING \"Regular expression for build error messages to be filtered out\")\n\n# Overwrite default DartConfiguration.tcl such that ctest can build our unit tests.\n# Recall that our unit tests are not in the \"all\" target, so we have to explicitly ask ctest to build our custom 'buildtests' target.\n# At this stage, we can also add custom flags to the build tool through the user defined EIGEN_TEST_BUILD_FLAGS variable.\nfile(READ  \"${CMAKE_CURRENT_BINARY_DIR}/DartConfiguration.tcl\" EIGEN_DART_CONFIG_FILE)\n# try to grab the default flags\nstring(REGEX MATCH \"MakeCommand:.*-- (.*)\\nDefaultCTestConfigurationType\" EIGEN_DUMMY ${EIGEN_DART_CONFIG_FILE})\nif(NOT CMAKE_MATCH_1)\nstring(REGEX MATCH \"MakeCommand:.*[^c]make (.*)\\nDefaultCTestConfigurationType\" EIGEN_DUMMY ${EIGEN_DART_CONFIG_FILE})\nendif()\nstring(REGEX REPLACE \"MakeCommand:.*DefaultCTestConfigurationType\" \"MakeCommand: ${CMAKE_COMMAND} --build . --target ${EIGEN_DASHBOARD_BUILD_TARGET} --config \\\"\\${CTEST_CONFIGURATION_TYPE}\\\" -- ${CMAKE_MATCH_1} ${EIGEN_TEST_BUILD_FLAGS}\\nDefaultCTestConfigurationType\"\n       EIGEN_DART_CONFIG_FILE2 ${EIGEN_DART_CONFIG_FILE})\nfile(WRITE \"${CMAKE_CURRENT_BINARY_DIR}/DartConfiguration.tcl\" ${EIGEN_DART_CONFIG_FILE2})\n\nconfigure_file(${CMAKE_CURRENT_SOURCE_DIR}/CTestCustom.cmake.in ${CMAKE_BINARY_DIR}/CTestCustom.cmake)\n\n# some documentation of this function would be nice\nei_init_testing()\n\n# configure Eigen related testing options\noption(EIGEN_NO_ASSERTION_CHECKING \"Disable checking of assertions using exceptions\" OFF)\noption(EIGEN_DEBUG_ASSERTS \"Enable advanced debugging of assertions\" OFF)\n\nif(CMAKE_COMPILER_IS_GNUCXX)\n  option(EIGEN_COVERAGE_TESTING \"Enable/disable gcov\" OFF)\n  if(EIGEN_COVERAGE_TESTING)\n    set(COVERAGE_FLAGS \"-fprofile-arcs -ftest-coverage\")\n    set(CTEST_CUSTOM_COVERAGE_EXCLUDE \"/test/\")\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} ${COVERAGE_FLAGS}\")\n  endif()\n  \nelseif(MSVC)\n  set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} /D_CRT_SECURE_NO_WARNINGS /D_SCL_SECURE_NO_WARNINGS\")\nendif()\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/EigenDetermineOSVersion.cmake",
    "content": "# The utility function DetermineOSVersion aims at providing an\n# improved version of the CMake variable ${CMAKE_SYSTEM} on Windows\n# machines.\n#\n# Usage:\n#  include(EigenDetermineOSVersion)\n#  DetermineOSVersion(OS_VERSION)\n#  message(\"OS: ${OS_VERSION}\")\n\n# - A little helper variable which should not be directly called\nfunction(DetermineShortWindowsName WIN_VERSION win_num_version)\n   if    (${win_num_version} VERSION_EQUAL \"6.1\")\n       set(_version \"win7\")\n   elseif(${win_num_version} VERSION_EQUAL \"6.0\")\n       set(_version \"winVista\")\n   elseif(${win_num_version} VERSION_EQUAL \"5.2\")\n       set(_version \"winXpProf\")\n   elseif(${win_num_version} VERSION_EQUAL \"5.1\")\n       set(_version \"winXp\")\n   elseif(${win_num_version} VERSION_EQUAL \"5.0\")\n       set(_version \"win2000Prof\")\n   else()\n       set(_version \"unknownWin\")\n   endif()\n   set(${WIN_VERSION} ${_version} PARENT_SCOPE)\nendfunction()\n\nfunction(DetermineOSVersion OS_VERSION)\n  if (WIN32 AND CMAKE_HOST_SYSTEM_NAME MATCHES Windows)\n    file (TO_NATIVE_PATH \"$ENV{COMSPEC}\" SHELL)\n    exec_program( ${SHELL} ARGS \"/c\" \"ver\" OUTPUT_VARIABLE ver_output)\n\t\t\t\t\n      string(REGEX MATCHALL \"[0-9]+\"\n           ver_list \"${ver_output}\")\n      list(GET ver_list 0 _major)\t\t   \n      list(GET ver_list 1 _minor)\n\t\t\t\t\n    set(win_num_version ${_major}.${_minor})\n    DetermineShortWindowsName(win_version \"${win_num_version}\")\n    if(win_version)\n      set(${OS_VERSION} ${win_version} PARENT_SCOPE)\n    endif()\n  else()\n    set(${OS_VERSION} ${CMAKE_SYSTEM} PARENT_SCOPE)\n  endif()\nendfunction()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/EigenDetermineVSServicePack.cmake",
    "content": "include(CMakeDetermineVSServicePack)\n\n# The code is almost identical to the CMake version. The only difference is that we remove\n# _DetermineVSServicePack_FastCheckVersionWithCompiler which lead to errors on some systems.\nfunction(EigenDetermineVSServicePack _pack)\n    if(NOT DETERMINED_VS_SERVICE_PACK OR NOT ${_pack})\n        if(NOT DETERMINED_VS_SERVICE_PACK)\n            _DetermineVSServicePack_CheckVersionWithTryCompile(DETERMINED_VS_SERVICE_PACK _cl_version)\n            if(NOT DETERMINED_VS_SERVICE_PACK)\n                _DetermineVSServicePack_CheckVersionWithTryRun(DETERMINED_VS_SERVICE_PACK _cl_version)\n            endif()\n        endif()\n\n        if(DETERMINED_VS_SERVICE_PACK)\n            if(_cl_version)\n                # Call helper function to determine VS version\n                _DetermineVSServicePackFromCompiler(_sp \"${_cl_version}\")\n              \n                # temporary fix, until CMake catches up\n                if (NOT _sp)\n                    if(${_cl_version} VERSION_EQUAL \"17.00.50727.1\")\n                        set(_sp \"vc110\")\n                    elseif(${_cl_version} VERSION_EQUAL \"17.00.51106.1\")\n                        set(_sp \"vc110sp1\")\n                    elseif(${_cl_version} VERSION_EQUAL \"17.00.60315.1\")\n                        set(_sp \"vc110sp2\")\n                    elseif(${_cl_version} VERSION_EQUAL \"17.00.60610.1\")\n                        set(_sp \"vc110sp3\")\n                    else()\n                        set(_sp ${CMAKE_CXX_COMPILER_VERSION})\n                    endif()\n                endif()\n                \n                if(_sp)\n                    set(${_pack} ${_sp} CACHE INTERNAL\n                        \"The Visual Studio Release with Service Pack\")\n                endif()\n            endif()\n        endif()\n    endif()\nendfunction()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/EigenTesting.cmake",
    "content": "\nmacro(ei_add_property prop value)\n  get_property(previous GLOBAL PROPERTY ${prop})\n  if ((NOT previous) OR (previous STREQUAL \"\"))\n    set_property(GLOBAL PROPERTY ${prop} \"${value}\")\n  else()\n    set_property(GLOBAL PROPERTY ${prop} \"${previous} ${value}\")\n  endif()\nendmacro()\n\n#internal. See documentation of ei_add_test for details.\nmacro(ei_add_test_internal testname testname_with_suffix)\n  set(targetname ${testname_with_suffix})\n\n  if(EIGEN_ADD_TEST_FILENAME_EXTENSION)\n    set(filename ${testname}.${EIGEN_ADD_TEST_FILENAME_EXTENSION})\n  else()\n    set(filename ${testname}.cpp)\n  endif()\n\n  if(EIGEN_ADD_TEST_FILENAME_EXTENSION STREQUAL cu)\n    if(EIGEN_TEST_HIP)\n      hip_reset_flags()\n      hip_add_executable(${targetname} ${filename} HIPCC_OPTIONS \"-DEIGEN_USE_HIP ${ARGV2}\")\n    elseif(EIGEN_TEST_CUDA_CLANG)\n      set_source_files_properties(${filename} PROPERTIES LANGUAGE CXX)\n      \n      if(CUDA_64_BIT_DEVICE_CODE AND (EXISTS \"${CUDA_TOOLKIT_ROOT_DIR}/lib64\"))\n        link_directories(\"${CUDA_TOOLKIT_ROOT_DIR}/lib64\")\n      else()\n        link_directories(\"${CUDA_TOOLKIT_ROOT_DIR}/lib\")\n      endif()\n\n      if (${ARGC} GREATER 2)\n        add_executable(${targetname} ${filename})\n      else()\n        add_executable(${targetname} ${filename} OPTIONS ${ARGV2})\n      endif()\n      set(CUDA_CLANG_LINK_LIBRARIES \"cudart_static\" \"cuda\" \"dl\" \"pthread\")\n      if (CMAKE_SYSTEM_NAME STREQUAL \"Linux\")\n      set(CUDA_CLANG_LINK_LIBRARIES ${CUDA_CLANG_LINK_LIBRARIES} \"rt\")\n      endif()\n      target_link_libraries(${targetname} ${CUDA_CLANG_LINK_LIBRARIES})\n    else()\n      if (${ARGC} GREATER 2)\n        cuda_add_executable(${targetname} ${filename} OPTIONS ${ARGV2})\n      else()\n        cuda_add_executable(${targetname} ${filename})\n      endif()\n    endif()\n  else()\n    add_executable(${targetname} ${filename})\n  endif()\n\n  if (targetname MATCHES \"^eigen2_\")\n    add_dependencies(eigen2_buildtests ${targetname})\n  else()\n    add_dependencies(buildtests ${targetname})\n  endif()\n\n  if(EIGEN_NO_ASSERTION_CHECKING)\n    ei_add_target_property(${targetname} COMPILE_FLAGS \"-DEIGEN_NO_ASSERTION_CHECKING=1\")\n  else()\n    if(EIGEN_DEBUG_ASSERTS)\n      ei_add_target_property(${targetname} COMPILE_FLAGS \"-DEIGEN_DEBUG_ASSERTS=1\")\n    endif()\n  endif()\n\n  ei_add_target_property(${targetname} COMPILE_FLAGS \"-DEIGEN_TEST_MAX_SIZE=${EIGEN_TEST_MAX_SIZE}\")\n\n  if(MSVC)\n    ei_add_target_property(${targetname} COMPILE_FLAGS \"/bigobj\")\n  endif()\n\n  # let the user pass flags.\n  if(${ARGC} GREATER 2)\n    ei_add_target_property(${targetname} COMPILE_FLAGS \"${ARGV2}\")\n  endif()\n\n  if(EIGEN_TEST_CUSTOM_CXX_FLAGS)\n    ei_add_target_property(${targetname} COMPILE_FLAGS \"${EIGEN_TEST_CUSTOM_CXX_FLAGS}\")\n  endif()\n\n  if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO)\n    target_link_libraries(${targetname} ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO})\n  endif()\n  if(EXTERNAL_LIBS)\n    target_link_libraries(${targetname} ${EXTERNAL_LIBS})\n  endif()\n  if(EIGEN_TEST_CUSTOM_LINKER_FLAGS)\n    target_link_libraries(${targetname} ${EIGEN_TEST_CUSTOM_LINKER_FLAGS})\n  endif()\n\n  if(${ARGC} GREATER 3)\n    set(libs_to_link ${ARGV3})\n    # it could be that some cmake module provides a bad library string \" \"  (just spaces),\n    # and that severely breaks target_link_libraries (\"can't link to -l-lstdc++\" errors).\n    # so we check for strings containing only spaces.\n    string(STRIP \"${libs_to_link}\" libs_to_link_stripped)\n    string(LENGTH \"${libs_to_link_stripped}\" libs_to_link_stripped_length)\n    if(${libs_to_link_stripped_length} GREATER 0)\n      # notice: no double quotes around ${libs_to_link} here. It may be a list.\n      target_link_libraries(${targetname} ${libs_to_link})\n    endif()\n  endif()\n\n  add_test(${testname_with_suffix} \"${targetname}\")\n\n  # Specify target and test labels according to EIGEN_CURRENT_SUBPROJECT\n  get_property(current_subproject GLOBAL PROPERTY EIGEN_CURRENT_SUBPROJECT)\n  if ((current_subproject) AND (NOT (current_subproject STREQUAL \"\")))\n    set_property(TARGET ${targetname} PROPERTY LABELS \"Build${current_subproject}\")\n    add_dependencies(\"Build${current_subproject}\" ${targetname})\n    set_property(TEST ${testname_with_suffix} PROPERTY LABELS \"${current_subproject}\")\n  endif()\n  if(EIGEN_SYCL)\n    # Force include of the SYCL file at the end to avoid errors.\n    set_property(TARGET ${targetname} PROPERTY COMPUTECPP_INCLUDE_AFTER 1)\n    # Set COMPILE_FLAGS to COMPILE_DEFINITIONS instead to avoid having to duplicate the flags\n    # to the device compiler.\n    get_target_property(target_compile_flags ${targetname} COMPILE_FLAGS)\n    separate_arguments(target_compile_flags)\n    foreach(flag ${target_compile_flags})\n      if(${flag} MATCHES \"^-D.*\")\n        string(REPLACE \"-D\" \"\" definition_flag ${flag})\n        set_property(TARGET ${targetname} APPEND PROPERTY COMPILE_DEFINITIONS ${definition_flag})\n        list(REMOVE_ITEM target_compile_flags ${flag})\n      endif()\n    endforeach()\n    set_property(TARGET ${targetname} PROPERTY COMPILE_FLAGS ${target_compile_flags})\n    # Link against pthread and add sycl to target\n    set(THREADS_PREFER_PTHREAD_FLAG ON)\n    find_package(Threads REQUIRED)\n    target_link_libraries(${targetname} Threads::Threads)\n    add_sycl_to_target(TARGET ${targetname} SOURCES ${filename})\n  endif(EIGEN_SYCL)\nendmacro(ei_add_test_internal)\n# Macro to add a test\n#\n# the unique mandatory parameter testname must correspond to a file\n# <testname>.cpp which follows this pattern:\n#\n# #include \"main.h\"\n# void test_<testname>() { ... }\n#\n# Depending on the contents of that file, this macro can have 2 behaviors,\n# see below.\n#\n# The optional 2nd parameter is libraries to link to.\n#\n# A. Default behavior\n#\n# this macro adds an executable <testname> as well as a ctest test\n# named <testname> too.\n#\n# On platforms with bash simply run:\n#   \"ctest -V\" or \"ctest -V -R <testname>\"\n# On other platform use ctest as usual\n#\n# B. Multi-part behavior\n#\n# If the source file matches the regexp\n#    CALL_SUBTEST_[0-9]+|EIGEN_TEST_PART_[0-9]+\n# then it is interpreted as a multi-part test. The behavior then depends on the\n# CMake option EIGEN_SPLIT_LARGE_TESTS, which is ON by default.\n#\n# If EIGEN_SPLIT_LARGE_TESTS is OFF, the behavior is the same as in A (the multi-part\n# aspect is ignored).\n#\n# If EIGEN_SPLIT_LARGE_TESTS is ON, the test is split into multiple executables\n#   test_<testname>_<N>\n# where N runs from 1 to the greatest occurrence found in the source file. Each of these\n# executables is built passing -DEIGEN_TEST_PART_N. This allows to split large tests\n# into smaller executables.\n#\n# Moreover, targets <testname> are still generated, they\n# have the effect of building all the parts of the test.\n#\n# Again, ctest -R allows to run all matching tests.\nmacro(ei_add_test testname)\n  get_property(EIGEN_TESTS_LIST GLOBAL PROPERTY EIGEN_TESTS_LIST)\n  set(EIGEN_TESTS_LIST \"${EIGEN_TESTS_LIST}${testname}\\n\")\n  set_property(GLOBAL PROPERTY EIGEN_TESTS_LIST \"${EIGEN_TESTS_LIST}\")\n\n  if(EIGEN_ADD_TEST_FILENAME_EXTENSION)\n    set(filename ${testname}.${EIGEN_ADD_TEST_FILENAME_EXTENSION})\n  else()\n    set(filename ${testname}.cpp)\n  endif()\n\n  file(READ \"${filename}\" test_source)\n  string(REGEX MATCHALL \"CALL_SUBTEST_[0-9]+|EIGEN_TEST_PART_[0-9]+|EIGEN_SUFFIXES(;[0-9]+)+\"\n         occurrences \"${test_source}\")\n  string(REGEX REPLACE \"CALL_SUBTEST_|EIGEN_TEST_PART_|EIGEN_SUFFIXES\" \"\" suffixes \"${occurrences}\")\n  list(REMOVE_DUPLICATES suffixes)\n  set(explicit_suffixes \"\")\n  if( (NOT EIGEN_SPLIT_LARGE_TESTS) AND suffixes)\n    # Check whether we have EIGEN_TEST_PART_* statements, in which case we likely must enforce splitting.\n    # For instance, indexed_view activate a different c++ version for each part.\n    string(REGEX MATCHALL \"EIGEN_TEST_PART_[0-9]+\" occurrences \"${test_source}\")\n    string(REGEX REPLACE \"EIGEN_TEST_PART_\" \"\" explicit_suffixes \"${occurrences}\")\n    list(REMOVE_DUPLICATES explicit_suffixes)\n  endif()\n  if( (EIGEN_SPLIT_LARGE_TESTS AND suffixes) OR explicit_suffixes)\n    add_custom_target(${testname})\n    foreach(suffix ${suffixes})\n      ei_add_test_internal(${testname} ${testname}_${suffix}\n        \"${ARGV1} -DEIGEN_TEST_PART_${suffix}=1\" \"${ARGV2}\")\n      add_dependencies(${testname} ${testname}_${suffix})\n    endforeach()\n  else()\n    ei_add_test_internal(${testname} ${testname} \"${ARGV1} -DEIGEN_TEST_PART_ALL=1\" \"${ARGV2}\")\n  endif()\nendmacro()\n\n# adds a failtest, i.e. a test that succeed if the program fails to compile\n# note that the test runner for these is CMake itself, when passed -DEIGEN_FAILTEST=ON\n# so here we're just running CMake commands immediately, we're not adding any targets.\nmacro(ei_add_failtest testname)\n\n  set(test_target_ok ${testname}_ok)\n  set(test_target_ko ${testname}_ko)\n\n  # Add executables\n  add_executable(${test_target_ok} ${testname}.cpp)\n  add_executable(${test_target_ko} ${testname}.cpp)\n\n  # Remove them from the normal build process\n  set_target_properties(${test_target_ok} ${test_target_ko} PROPERTIES\n                        EXCLUDE_FROM_ALL TRUE\n                        EXCLUDE_FROM_DEFAULT_BUILD TRUE)\n\n  # Configure the failing test\n  target_compile_definitions(${test_target_ko} PRIVATE EIGEN_SHOULD_FAIL_TO_BUILD)\n\n  # Add the tests to ctest.\n  add_test(NAME ${test_target_ok}\n          COMMAND ${CMAKE_COMMAND} --build . --target ${test_target_ok} --config $<CONFIGURATION>\n          WORKING_DIRECTORY ${CMAKE_BINARY_DIR})\n  add_test(NAME ${test_target_ko}\n          COMMAND ${CMAKE_COMMAND} --build . --target ${test_target_ko} --config $<CONFIGURATION>\n          WORKING_DIRECTORY ${CMAKE_BINARY_DIR})\n\n  # Expect the second test to fail\n  set_tests_properties(${test_target_ko} PROPERTIES WILL_FAIL TRUE)\nendmacro()\n\n# print a summary of the different options\nmacro(ei_testing_print_summary)\n  message(STATUS \"************************************************************\")\n  message(STATUS \"***    Eigen's unit tests configuration summary          ***\")\n  message(STATUS \"************************************************************\")\n  message(STATUS \"\")\n  message(STATUS \"Build type:        ${CMAKE_BUILD_TYPE}\")\n  message(STATUS \"Build site:        ${SITE}\")\n  message(STATUS \"Build string:      ${BUILDNAME}\")\n  get_property(EIGEN_TESTING_SUMMARY GLOBAL PROPERTY EIGEN_TESTING_SUMMARY)\n  get_property(EIGEN_TESTED_BACKENDS GLOBAL PROPERTY EIGEN_TESTED_BACKENDS)\n  get_property(EIGEN_MISSING_BACKENDS GLOBAL PROPERTY EIGEN_MISSING_BACKENDS)\n  message(STATUS \"Enabled backends:  ${EIGEN_TESTED_BACKENDS}\")\n  message(STATUS \"Disabled backends: ${EIGEN_MISSING_BACKENDS}\")\n\n  if(EIGEN_DEFAULT_TO_ROW_MAJOR)\n    message(STATUS \"Default order:     Row-major\")\n  else()\n    message(STATUS \"Default order:     Column-major\")\n  endif()\n\n  if(EIGEN_TEST_NO_EXPLICIT_ALIGNMENT)\n    message(STATUS \"Explicit alignment (hence vectorization) disabled\")\n  elseif(EIGEN_TEST_NO_EXPLICIT_VECTORIZATION)\n    message(STATUS \"Explicit vectorization disabled (alignment kept enabled)\")\n  else()\n\n  message(STATUS \"Maximal matrix/vector size: ${EIGEN_TEST_MAX_SIZE}\")\n\n    if(EIGEN_TEST_SSE2)\n      message(STATUS \"SSE2:              ON\")\n    else()\n      message(STATUS \"SSE2:              Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_SSE3)\n      message(STATUS \"SSE3:              ON\")\n    else()\n      message(STATUS \"SSE3:              Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_SSSE3)\n      message(STATUS \"SSSE3:             ON\")\n    else()\n      message(STATUS \"SSSE3:             Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_SSE4_1)\n      message(STATUS \"SSE4.1:            ON\")\n    else()\n      message(STATUS \"SSE4.1:            Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_SSE4_2)\n      message(STATUS \"SSE4.2:            ON\")\n    else()\n      message(STATUS \"SSE4.2:            Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_AVX)\n      message(STATUS \"AVX:               ON\")\n    else()\n      message(STATUS \"AVX:               Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_AVX2)\n      message(STATUS \"AVX2:              ON\")\n    else()\n      message(STATUS \"AVX2:              Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_FMA)\n      message(STATUS \"FMA:               ON\")\n    else()\n      message(STATUS \"FMA:               Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_AVX512)\n      message(STATUS \"AVX512:            ON\")\n    else()\n      message(STATUS \"AVX512:            Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_AVX512DQ)\n      message(STATUS \"AVX512DQ:          ON\")\n    else()\n      message(STATUS \"AVX512DQ:          Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_ALTIVEC)\n      message(STATUS \"Altivec:           ON\")\n    else()\n      message(STATUS \"Altivec:           Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_VSX)\n      message(STATUS \"VSX:               ON\")\n    else()\n      message(STATUS \"VSX:               Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_MSA)\n      message(STATUS \"MIPS MSA:          ON\")\n    else()\n      message(STATUS \"MIPS MSA:          Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_NEON)\n      message(STATUS \"ARM NEON:          ON\")\n    else()\n      message(STATUS \"ARM NEON:          Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_NEON64)\n      message(STATUS \"ARMv8 NEON:        ON\")\n    else()\n      message(STATUS \"ARMv8 NEON:        Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_ZVECTOR)\n      message(STATUS \"S390X ZVECTOR:     ON\")\n    else()\n      message(STATUS \"S390X ZVECTOR:     Using architecture defaults\")\n    endif()\n\n    if(EIGEN_TEST_CXX11)\n      message(STATUS \"C++11:             ON\")\n    else()\n      message(STATUS \"C++11:             OFF\")\n    endif()\n\n    if(EIGEN_TEST_SYCL)\n      if(EIGEN_SYCL_TRISYCL)\n        message(STATUS \"SYCL:              ON (using triSYCL)\")\n      else()\n        message(STATUS \"SYCL:              ON (using computeCPP)\")\n      endif()\n    else()\n      message(STATUS \"SYCL:              OFF\")\n    endif()\n    if(EIGEN_TEST_CUDA)\n      if(EIGEN_TEST_CUDA_CLANG)\n        message(STATUS \"CUDA:              ON (using clang)\")\n      else()\n        message(STATUS \"CUDA:              ON (using nvcc)\")\n      endif()\n    else()\n      message(STATUS \"CUDA:              OFF\")\n    endif()\n    if(EIGEN_TEST_HIP)\n      message(STATUS \"HIP:               ON (using hipcc)\")\n    else()\n      message(STATUS \"HIP:               OFF\")\n    endif()\n\n  endif() # vectorization / alignment options\n\n  message(STATUS \"\\n${EIGEN_TESTING_SUMMARY}\")\n\n  message(STATUS \"************************************************************\")\nendmacro()\n\nmacro(ei_init_testing)\n  define_property(GLOBAL PROPERTY EIGEN_CURRENT_SUBPROJECT BRIEF_DOCS \" \" FULL_DOCS \" \")\n  define_property(GLOBAL PROPERTY EIGEN_TESTED_BACKENDS BRIEF_DOCS \" \" FULL_DOCS \" \")\n  define_property(GLOBAL PROPERTY EIGEN_MISSING_BACKENDS BRIEF_DOCS \" \" FULL_DOCS \" \")\n  define_property(GLOBAL PROPERTY EIGEN_TESTING_SUMMARY BRIEF_DOCS \" \" FULL_DOCS \" \")\n  define_property(GLOBAL PROPERTY EIGEN_TESTS_LIST BRIEF_DOCS \" \" FULL_DOCS \" \")\n\n  set_property(GLOBAL PROPERTY EIGEN_TESTED_BACKENDS \"\")\n  set_property(GLOBAL PROPERTY EIGEN_MISSING_BACKENDS \"\")\n  set_property(GLOBAL PROPERTY EIGEN_TESTING_SUMMARY \"\")\n  set_property(GLOBAL PROPERTY EIGEN_TESTS_LIST \"\")\n\n  define_property(GLOBAL PROPERTY EIGEN_FAILTEST_FAILURE_COUNT BRIEF_DOCS \" \" FULL_DOCS \" \")\n  define_property(GLOBAL PROPERTY EIGEN_FAILTEST_COUNT BRIEF_DOCS \" \" FULL_DOCS \" \")\n\n  set_property(GLOBAL PROPERTY EIGEN_FAILTEST_FAILURE_COUNT \"0\")\n  set_property(GLOBAL PROPERTY EIGEN_FAILTEST_COUNT \"0\")\n\n  # uncomment anytime you change the ei_get_compilerver_from_cxx_version_string macro\n  # ei_test_get_compilerver_from_cxx_version_string()\nendmacro()\n\nmacro(ei_set_sitename)\n  # if the sitename is not yet set, try to set it\n  if(NOT ${SITE} OR ${SITE} STREQUAL \"\")\n    set(eigen_computername $ENV{COMPUTERNAME})\n    set(eigen_hostname $ENV{HOSTNAME})\n    if(eigen_hostname)\n      set(SITE ${eigen_hostname})\n    elseif(eigen_computername)\n      set(SITE ${eigen_computername})\n    endif()\n  endif()\n  # in case it is already set, enforce lower case\n  if(SITE)\n    string(TOLOWER ${SITE} SITE)\n  endif()\nendmacro()\n\nmacro(ei_get_compilerver VAR)\n    if(MSVC)\n      # on windows system, we use a modified CMake script\n      include(EigenDetermineVSServicePack)\n      EigenDetermineVSServicePack( my_service_pack )\n\n      if( my_service_pack )\n        set(${VAR} ${my_service_pack})\n      else()\n        set(${VAR} \"na\")\n      endif()\n    elseif(${CMAKE_CXX_COMPILER_ID} MATCHES \"PGI\")\n      set(${VAR} \"${CMAKE_CXX_COMPILER_ID}-${CMAKE_CXX_COMPILER_VERSION}\")\n    else()\n    # on all other system we rely on ${CMAKE_CXX_COMPILER}\n    # supporting a \"--version\" or \"/version\" flag\n\n    if(WIN32 AND ${CMAKE_CXX_COMPILER_ID} EQUAL \"Intel\")\n      set(EIGEN_CXX_FLAG_VERSION \"/version\")\n    else()\n      set(EIGEN_CXX_FLAG_VERSION \"--version\")\n    endif()\n\n    execute_process(COMMAND ${CMAKE_CXX_COMPILER} ${EIGEN_CXX_FLAG_VERSION}\n                    OUTPUT_VARIABLE eigen_cxx_compiler_version_string OUTPUT_STRIP_TRAILING_WHITESPACE)\n    string(REGEX REPLACE \"[\\n\\r].*\"  \"\"  eigen_cxx_compiler_version_string  ${eigen_cxx_compiler_version_string})\n\n    ei_get_compilerver_from_cxx_version_string(\"${eigen_cxx_compiler_version_string}\" CNAME CVER)\n    set(${VAR} \"${CNAME}-${CVER}\")\n\n  endif()\nendmacro()\n\n# Extract compiler name and version from a raw version string\n# WARNING: if you edit thid macro, then please test it by  uncommenting\n# the testing macro call in ei_init_testing() of the EigenTesting.cmake file.\n# See also the ei_test_get_compilerver_from_cxx_version_string macro at the end of the file\nmacro(ei_get_compilerver_from_cxx_version_string VERSTRING CNAME CVER)\n  # extract possible compiler names\n  string(REGEX MATCH \"g\\\\+\\\\+\"      ei_has_gpp    ${VERSTRING})\n  string(REGEX MATCH \"llvm|LLVM\"    ei_has_llvm   ${VERSTRING})\n  string(REGEX MATCH \"gcc|GCC\"      ei_has_gcc    ${VERSTRING})\n  string(REGEX MATCH \"icpc|ICC\"     ei_has_icpc   ${VERSTRING})\n  string(REGEX MATCH \"clang|CLANG\"  ei_has_clang  ${VERSTRING})\n\n  # combine them\n  if((ei_has_llvm) AND (ei_has_gpp OR ei_has_gcc))\n    set(${CNAME} \"llvm-g++\")\n  elseif((ei_has_llvm) AND (ei_has_clang))\n    set(${CNAME} \"llvm-clang++\")\n  elseif(ei_has_clang)\n    set(${CNAME} \"clang++\")\n  elseif(ei_has_icpc)\n    set(${CNAME} \"icpc\")\n  elseif(ei_has_gpp OR ei_has_gcc)\n    set(${CNAME} \"g++\")\n  else()\n    set(${CNAME} \"_\")\n  endif()\n\n  # extract possible version numbers\n  # first try to extract 3 isolated numbers:\n  string(REGEX MATCH \" [0-9]+\\\\.[0-9]+\\\\.[0-9]+\" eicver ${VERSTRING})\n  if(NOT eicver)\n    # try to extract 2 isolated ones:\n    string(REGEX MATCH \" [0-9]+\\\\.[0-9]+\" eicver ${VERSTRING})\n    if(NOT eicver)\n      # try to extract 3:\n      string(REGEX MATCH \"[^0-9][0-9]+\\\\.[0-9]+\\\\.[0-9]+\" eicver ${VERSTRING})\n      if(NOT eicver)\n        # try to extract 2:\n        string(REGEX MATCH \"[^0-9][0-9]+\\\\.[0-9]+\" eicver ${VERSTRING})\n      else()\n        set(eicver \" _\")\n      endif()\n    endif()\n  endif()\n\n  string(REGEX REPLACE \".(.*)\" \"\\\\1\" ${CVER} ${eicver})\n\nendmacro()\n\nmacro(ei_get_cxxflags VAR)\n  set(${VAR} \"\")\n  ei_is_64bit_env(IS_64BIT_ENV)\n  if(EIGEN_TEST_NEON)\n    set(${VAR} NEON)\n  elseif(EIGEN_TEST_NEON64)\n    set(${VAR} NEON)\n  elseif(EIGEN_TEST_ZVECTOR)\n    set(${VAR} ZVECTOR)\n  elseif(EIGEN_TEST_VSX)\n    set(${VAR} VSX)\n  elseif(EIGEN_TEST_ALTIVEC)\n    set(${VAR} ALVEC)\n  elseif(EIGEN_TEST_FMA)\n    set(${VAR} FMA)\n  elseif(EIGEN_TEST_AVX)\n    set(${VAR} AVX)\n  elseif(EIGEN_TEST_SSE4_2)\n    set(${VAR} SSE42)\n  elseif(EIGEN_TEST_SSE4_1)\n    set(${VAR} SSE41)\n  elseif(EIGEN_TEST_SSSE3)\n    set(${VAR} SSSE3)\n  elseif(EIGEN_TEST_SSE3)\n    set(${VAR} SSE3)\n  elseif(EIGEN_TEST_SSE2 OR IS_64BIT_ENV)\n    set(${VAR} SSE2)\n  elseif(EIGEN_TEST_MSA)\n    set(${VAR} MSA)\n  endif()\n\n  if(EIGEN_TEST_OPENMP)\n    if (${VAR} STREQUAL \"\")\n      set(${VAR} OMP)\n    else()\n      set(${VAR} ${${VAR}}-OMP)\n    endif()\n  endif()\n\n  if(EIGEN_DEFAULT_TO_ROW_MAJOR)\n    if (${VAR} STREQUAL \"\")\n      set(${VAR} ROW)\n    else()\n      set(${VAR} ${${VAR}}-ROWMAJ)\n    endif()\n  endif()\nendmacro()\n\nmacro(ei_set_build_string)\n  ei_get_compilerver(LOCAL_COMPILER_VERSION)\n  ei_get_cxxflags(LOCAL_COMPILER_FLAGS)\n\n  include(EigenDetermineOSVersion)\n  DetermineOSVersion(OS_VERSION)\n\n  set(TMP_BUILD_STRING ${OS_VERSION}-${LOCAL_COMPILER_VERSION})\n\n  if (NOT ${LOCAL_COMPILER_FLAGS} STREQUAL  \"\")\n    set(TMP_BUILD_STRING ${TMP_BUILD_STRING}-${LOCAL_COMPILER_FLAGS})\n  endif()\n\n  if(EIGEN_TEST_EXTERNAL_BLAS)\n    set(TMP_BUILD_STRING ${TMP_BUILD_STRING}-external_blas)\n  endif()\n\n  ei_is_64bit_env(IS_64BIT_ENV)\n  if(NOT IS_64BIT_ENV)\n    set(TMP_BUILD_STRING ${TMP_BUILD_STRING}-32bit)\n  else()\n    set(TMP_BUILD_STRING ${TMP_BUILD_STRING}-64bit)\n  endif()\n\n  if(EIGEN_TEST_CXX11)\n    set(TMP_BUILD_STRING ${TMP_BUILD_STRING}-cxx11)\n  endif()\n\n  if(EIGEN_BUILD_STRING_SUFFIX)\n    set(TMP_BUILD_STRING ${TMP_BUILD_STRING}-${EIGEN_BUILD_STRING_SUFFIX})\n  endif()\n\n  string(TOLOWER ${TMP_BUILD_STRING} BUILDNAME)\nendmacro()\n\nmacro(ei_is_64bit_env VAR)\n  if(CMAKE_SIZEOF_VOID_P EQUAL 8)\n    set(${VAR} 1)\n  elseif(CMAKE_SIZEOF_VOID_P EQUAL 4)\n    set(${VAR} 0)\n  else()\n    message(WARNING \"Unsupported pointer size. Please contact the authors.\")\n  endif()\nendmacro()\n\n\n# helper macro for testing ei_get_compilerver_from_cxx_version_string\n# STR: raw version string\n# REFNAME: expected compiler name\n# REFVER: expected compiler version\nmacro(ei_test1_get_compilerver_from_cxx_version_string STR REFNAME REFVER)\n  ei_get_compilerver_from_cxx_version_string(${STR} CNAME CVER)\n  if((NOT ${REFNAME} STREQUAL ${CNAME}) OR (NOT ${REFVER} STREQUAL ${CVER}))\n    message(\"STATUS ei_get_compilerver_from_cxx_version_string error:\")\n    message(\"Expected \\\"${REFNAME}-${REFVER}\\\", got \\\"${CNAME}-${CVER}\\\"\")\n  endif()\nendmacro()\n\n# macro for testing ei_get_compilerver_from_cxx_version_string\n# feel free to add more version strings\nmacro(ei_test_get_compilerver_from_cxx_version_string)\n  ei_test1_get_compilerver_from_cxx_version_string(\"g++ (SUSE Linux) 4.5.3 20110428 [gcc-4_5-branch revision 173117]\" \"g++\" \"4.5.3\")\n  ei_test1_get_compilerver_from_cxx_version_string(\"c++ (GCC) 4.5.1 20100924 (Red Hat 4.5.1-4)\" \"g++\" \"4.5.1\")\n  ei_test1_get_compilerver_from_cxx_version_string(\"icpc (ICC) 11.0 20081105\" \"icpc\" \"11.0\")\n  ei_test1_get_compilerver_from_cxx_version_string(\"g++-3.4 (GCC) 3.4.6\" \"g++\" \"3.4.6\")\n  ei_test1_get_compilerver_from_cxx_version_string(\"SUSE Linux clang version 3.0 (branches/release_30 145598) (based on LLVM 3.0)\" \"llvm-clang++\" \"3.0\")\n  ei_test1_get_compilerver_from_cxx_version_string(\"icpc (ICC) 12.0.5 20110719\" \"icpc\" \"12.0.5\")\n  ei_test1_get_compilerver_from_cxx_version_string(\"Apple clang version 2.1 (tags/Apple/clang-163.7.1) (based on LLVM 3.0svn)\" \"llvm-clang++\" \"2.1\")\n  ei_test1_get_compilerver_from_cxx_version_string(\"i686-apple-darwin11-llvm-g++-4.2 (GCC) 4.2.1 (Based on Apple Inc. build 5658) (LLVM build 2335.15.00)\" \"llvm-g++\" \"4.2.1\")\n  ei_test1_get_compilerver_from_cxx_version_string(\"g++-mp-4.4 (GCC) 4.4.6\" \"g++\" \"4.4.6\")\n  ei_test1_get_compilerver_from_cxx_version_string(\"g++-mp-4.4 (GCC) 2011\" \"g++\" \"4.4\")\nendmacro()\n\n# Split all tests listed in EIGEN_TESTS_LIST into num_splits many targets\n# named buildtestspartN with N = { 0, ..., num_splits-1}.\n#\n# The intention behind the existance of this macro is the size of Eigen's\n# testsuite. Together with the relativly big compile-times building all tests\n# can take a substantial amount of time depending on the available hardware.\n# \n# The last buildtestspartN target will build possible remaining tests.\n#\n# An example:\n#\n#   EIGEN_TESTS_LIST= [ test1, test2, test3, test4, test5, test6, test7 ]\n#\n# A call to ei_split_testsuite(3) creates the following targets with dependencies\n#\n#   Target                      Dependencies\n#   ------                      ------------\n#   buildtestspart0             test1, test2\n#   buildtestspart1             test3, test4\n#   buildtestspart2             test5, test6, test7\n#\nmacro(ei_split_testsuite num_splits)\n  get_property(EIGEN_TESTS_LIST GLOBAL PROPERTY EIGEN_TESTS_LIST)\n\n  # Translate EIGEN_TESTS_LIST into a CMake list\n  string(REGEX REPLACE \"\\n\" \" \" EIGEN_TESTS_LIST \"${EIGEN_TESTS_LIST}\")\n  set(EIGEN_TESTS_LIST \"${EIGEN_TESTS_LIST}\")\n  separate_arguments(EIGEN_TESTS_LIST)\n\n  set(eigen_test_count \"0\")\n  foreach(t IN ITEMS ${EIGEN_TESTS_LIST})\n    math(EXPR eigen_test_count \"${eigen_test_count}+1\")\n  endforeach()\n\n  # Get number of tests per target\n  math(EXPR num_tests_per_target \"${eigen_test_count}/${num_splits} - ${eigen_test_count}/${num_splits} % 1\")\n\n  set(test_idx \"0\")\n  math(EXPR target_bound \"${num_splits}-1\")\n  foreach(part RANGE \"0\" \"${target_bound}\")\n    # Create target\n    set(current_target \"buildtestspart${part}\")\n    add_custom_target(\"${current_target}\")\n    math(EXPR upper_bound \"${test_idx} + ${num_tests_per_target} - 1\")\n    foreach(test_idx RANGE \"${test_idx}\" \"${upper_bound}\")\n      list(GET EIGEN_TESTS_LIST \"${test_idx}\" curr_test)\n      add_dependencies(\"${current_target}\" \"${curr_test}\")\n    endforeach()\n    math(EXPR test_idx \"${test_idx} + ${num_tests_per_target}\")\n  endforeach()\n  \n  # Handle the possibly remaining tests\n  math(EXPR test_idx \"${num_splits} * ${num_tests_per_target}\")\n  math(EXPR target_bound \"${eigen_test_count} - 1\")\n  foreach(test_idx RANGE \"${test_idx}\" \"${target_bound}\")\n    list(GET EIGEN_TESTS_LIST \"${test_idx}\" curr_test)\n    add_dependencies(\"${current_target}\" \"${curr_test}\")\n  endforeach()\nendmacro(ei_split_testsuite num_splits)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/EigenUninstall.cmake",
    "content": "################ CMake Uninstall Template #######################\n# CMake Template file for uninstallation of files\n# mentioned in 'install_manifest.txt'\n#\n# Used by uinstall target\n#################################################################\n\nset(MANIFEST \"${CMAKE_CURRENT_BINARY_DIR}/install_manifest.txt\")\n\nif(EXISTS ${MANIFEST})\n  message(STATUS \"============== Uninstalling Eigen  ===================\")\n\n  file(STRINGS ${MANIFEST} files)\n  foreach(file ${files})\n    if(EXISTS ${file})\n      message(STATUS \"Removing file: '${file}'\")\n\n      execute_process(\n        COMMAND ${CMAKE_COMMAND} -E remove ${file}\n        OUTPUT_VARIABLE rm_out\n        RESULT_VARIABLE rm_retval\n        )\n\n      if(NOT \"${rm_retval}\" STREQUAL 0)\n        message(FATAL_ERROR \"Failed to remove file: '${file}'.\")\n      endif()\n    else()\n      message(STATUS \"File '${file}' does not exist.\")\n    endif()\n  endforeach()\n\n  message(STATUS \"========== Finished Uninstalling Eigen  ==============\")\nelse()\n  message(STATUS \"Cannot find install manifest: '${MANIFEST}'\")\n  message(STATUS \"Probably make install has not been performed\")\n  message(STATUS \"   or install_manifest.txt has been deleted.\")\nendif()\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindAdolc.cmake",
    "content": "\nif (ADOLC_INCLUDES AND ADOLC_LIBRARIES)\n  set(ADOLC_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(ADOLC_INCLUDES\n  NAMES adolc/adtl.h\n  PATHS $ENV{ADOLCDIR} $ENV{ADOLCDIR}/include ${INCLUDE_INSTALL_DIR}\n)\n\nfind_library(ADOLC_LIBRARIES \n  adolc \n  PATHS $ENV{ADOLCDIR} ${LIB_INSTALL_DIR} \n  PATH_SUFFIXES lib lib64)\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(Adolc DEFAULT_MSG\n                                  ADOLC_INCLUDES ADOLC_LIBRARIES)\n\nmark_as_advanced(ADOLC_INCLUDES ADOLC_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindBLAS.cmake",
    "content": "###\n#\n# @copyright (c) 2009-2014 The University of Tennessee and The University\n#                          of Tennessee Research Foundation.\n#                          All rights reserved.\n# @copyright (c) 2012-2016 Inria. All rights reserved.\n# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved.\n#\n###\n#\n# - Find BLAS library\n# This module finds an installed fortran library that implements the BLAS\n# linear-algebra interface (see http://www.netlib.org/blas/).\n# The list of libraries searched for is taken\n# from the autoconf macro file, acx_blas.m4 (distributed at\n# http://ac-archive.sourceforge.net/ac-archive/acx_blas.html).\n#\n# This module sets the following variables:\n#  BLAS_FOUND - set to true if a library implementing the BLAS interface\n#    is found\n#  BLAS_LINKER_FLAGS - uncached list of required linker flags (excluding -l\n#    and -L).\n#  BLAS_COMPILER_FLAGS - uncached list of required compiler flags (including -I for mkl headers).\n#  BLAS_LIBRARIES - uncached list of libraries (using full path name) to\n#    link against to use BLAS\n#  BLAS95_LIBRARIES - uncached list of libraries (using full path name)\n#    to link against to use BLAS95 interface\n#  BLAS95_FOUND - set to true if a library implementing the BLAS f95 interface\n#    is found\n#  BLA_STATIC  if set on this determines what kind of linkage we do (static)\n#  BLA_VENDOR  if set checks only the specified vendor, if not set checks\n#     all the possibilities\n#  BLAS_VENDOR_FOUND stores the BLAS vendor found \n#  BLA_F95     if set on tries to find the f95 interfaces for BLAS/LAPACK\n# The user can give specific paths where to find the libraries adding cmake\n# options at configure (ex: cmake path/to/project -DBLAS_DIR=path/to/blas):\n#  BLAS_DIR            - Where to find the base directory of blas\n#  BLAS_INCDIR         - Where to find the header files\n#  BLAS_LIBDIR         - Where to find the library files\n# The module can also look for the following environment variables if paths\n# are not given as cmake variable: BLAS_DIR, BLAS_INCDIR, BLAS_LIBDIR\n# For MKL case and if no paths are given as hints, we will try to use the MKLROOT\n# environment variable\n#  BLAS_VERBOSE Print some additional information during BLAS libraries detection\n##########\n### List of vendors (BLA_VENDOR) valid in this module\n########## List of vendors (BLA_VENDOR) valid in this module\n##  Open (for OpenBlas), Eigen (for EigenBlas), Goto, ATLAS PhiPACK,\n##  CXML, DXML, SunPerf, SCSL, SGIMATH, IBMESSL, IBMESSLMT\n##  Intel10_32 (intel mkl v10 32 bit), Intel10_64lp (intel mkl v10 64 bit,lp thread model, lp64 model),\n##  Intel10_64lp_seq (intel mkl v10 64 bit,sequential code, lp64 model),\n##  Intel( older versions of mkl 32 and 64 bit),\n##  ACML, ACML_MP, ACML_GPU, Apple, NAS, Generic\n# C/CXX should be enabled to use Intel mkl\n###\n# We handle different modes to find the dependency\n#\n# - Detection if already installed on the system\n#   - BLAS libraries can be detected from different ways\n#     Here is the order of precedence:\n#     1) we look in cmake variable BLAS_LIBDIR or BLAS_DIR (we guess the libdirs) if defined\n#     2) we look in environment variable BLAS_LIBDIR or BLAS_DIR (we guess the libdirs) if defined\n#     3) we look in common environnment variables depending on the system (INCLUDE, C_INCLUDE_PATH, CPATH - LIB, DYLD_LIBRARY_PATH, LD_LIBRARY_PATH)\n#     4) we look in common system paths depending on the system, see for example paths contained in the following cmake variables:\n#       - CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES, CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES\n#       - CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES, CMAKE_C_IMPLICIT_LINK_DIRECTORIES\n#\n\n#=============================================================================\n# Copyright 2007-2009 Kitware, Inc.\n#\n# Distributed under the OSI-approved BSD License (the \"License\");\n# see accompanying file Copyright.txt for details.\n#\n# This software is distributed WITHOUT ANY WARRANTY; without even the\n# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.\n# See the License for more information.\n#=============================================================================\n# (To distribute this file outside of CMake, substitute the full\n#  License text for the above reference.)\n\n## Some macros to print status when search for headers and libs\n# This macro informs why the _lib_to_find file has not been found\nmacro(Print_Find_Library_Blas_Status _libname _lib_to_find)\n\n  # save _libname upper/lower case\n  string(TOUPPER ${_libname} LIBNAME)\n  string(TOLOWER ${_libname} libname)\n\n  # print status\n  #message(\" \")\n  if(${LIBNAME}_LIBDIR)\n    message(\"${Yellow}${LIBNAME}_LIBDIR is defined but ${_lib_to_find}\"\n      \"has not been found in ${ARGN}${ColourReset}\")\n  else()\n    if(${LIBNAME}_DIR)\n      message(\"${Yellow}${LIBNAME}_DIR is defined but ${_lib_to_find}\"\n\t\"has not been found in ${ARGN}${ColourReset}\")\n    else()\n      message(\"${Yellow}${_lib_to_find} not found.\"\n\t\"Nor ${LIBNAME}_DIR neither ${LIBNAME}_LIBDIR\"\n\t\"are defined so that we look for ${_lib_to_find} in\"\n\t\"system paths (Linux: LD_LIBRARY_PATH, Windows: LIB,\"\n\t\"Mac: DYLD_LIBRARY_PATH,\"\n\t\"CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES,\"\n\t\"CMAKE_C_IMPLICIT_LINK_DIRECTORIES)${ColourReset}\")\n      if(_lib_env)\n\tmessage(\"${Yellow}${_lib_to_find} has not been found in\"\n\t  \"${_lib_env}${ColourReset}\")\n      endif()\n    endif()\n  endif()\n  message(\"${BoldYellow}Please indicate where to find ${_lib_to_find}. You have three options:\\n\"\n    \"- Option 1: Provide the Installation directory of BLAS library with cmake option: -D${LIBNAME}_DIR=your/path/to/${libname}/\\n\"\n    \"- Option 2: Provide the directory where to find the library with cmake option: -D${LIBNAME}_LIBDIR=your/path/to/${libname}/lib/\\n\"\n    \"- Option 3: Update your environment variable (Linux: LD_LIBRARY_PATH, Windows: LIB, Mac: DYLD_LIBRARY_PATH)\\n\"\n    \"- Option 4: If your library provides a PkgConfig file, make sure pkg-config finds your library${ColourReset}\")\n\nendmacro()\n\n# This macro informs why the _lib_to_find file has not been found\nmacro(Print_Find_Library_Blas_CheckFunc_Status _name)\n\n  # save _libname upper/lower case\n  string(TOUPPER ${_name} FUNCNAME)\n  string(TOLOWER ${_name} funcname)\n\n  # print status\n  #message(\" \")\n  message(\"${Red}Libs have been found but check of symbol ${_name} failed \"\n    \"with following libraries ${ARGN}${ColourReset}\")\n  message(\"${BoldRed}Please open your error file CMakeFiles/CMakeError.log\"\n    \"to figure out why it fails${ColourReset}\")\n  #message(\" \")\n\nendmacro()\n\nif (NOT BLAS_FOUND)\n  set(BLAS_DIR \"\" CACHE PATH \"Installation directory of BLAS library\")\n  if (NOT BLAS_FIND_QUIETLY)\n    message(STATUS \"A cache variable, namely BLAS_DIR, has been set to specify the install directory of BLAS\")\n  endif()\nendif()\n\noption(BLAS_VERBOSE \"Print some additional information during BLAS libraries detection\" OFF)\nmark_as_advanced(BLAS_VERBOSE)\n\ninclude(CheckFunctionExists)\ninclude(CheckFortranFunctionExists)\n\nset(_blas_ORIG_CMAKE_FIND_LIBRARY_SUFFIXES ${CMAKE_FIND_LIBRARY_SUFFIXES})\n\n# Check the language being used\nget_property( _LANGUAGES_ GLOBAL PROPERTY ENABLED_LANGUAGES )\nif( _LANGUAGES_ MATCHES Fortran AND CMAKE_Fortran_COMPILER)\n  set( _CHECK_FORTRAN TRUE )\nelseif( (_LANGUAGES_ MATCHES C) OR (_LANGUAGES_ MATCHES CXX) )\n  set( _CHECK_FORTRAN FALSE )\nelse()\n  if(BLAS_FIND_REQUIRED)\n    message(FATAL_ERROR \"FindBLAS requires Fortran, C, or C++ to be enabled.\")\n  else()\n    message(STATUS \"Looking for BLAS... - NOT found (Unsupported languages)\")\n    return()\n  endif()\nendif()\n\nmacro(Check_Fortran_Libraries LIBRARIES _prefix _name _flags _list _thread)\n  # This macro checks for the existence of the combination of fortran libraries\n  # given by _list.  If the combination is found, this macro checks (using the\n  # Check_Fortran_Function_Exists macro) whether can link against that library\n  # combination using the name of a routine given by _name using the linker\n  # flags given by _flags.  If the combination of libraries is found and passes\n  # the link test, LIBRARIES is set to the list of complete library paths that\n  # have been found.  Otherwise, LIBRARIES is set to FALSE.\n\n  # N.B. _prefix is the prefix applied to the names of all cached variables that\n  # are generated internally and marked advanced by this macro.\n\n  set(_libdir ${ARGN})\n\n  set(_libraries_work TRUE)\n  set(${LIBRARIES})\n  set(_combined_name)\n  set(ENV_MKLROOT \"$ENV{MKLROOT}\")\n  set(ENV_BLAS_DIR \"$ENV{BLAS_DIR}\")\n  set(ENV_BLAS_LIBDIR \"$ENV{BLAS_LIBDIR}\")\n  if (NOT _libdir)\n    if (BLAS_LIBDIR)\n      list(APPEND _libdir \"${BLAS_LIBDIR}\")\n    elseif (BLAS_DIR)\n      list(APPEND _libdir \"${BLAS_DIR}\")\n      list(APPEND _libdir \"${BLAS_DIR}/lib\")\n      if(\"${CMAKE_SIZEOF_VOID_P}\" EQUAL \"8\")\n\tlist(APPEND _libdir \"${BLAS_DIR}/lib64\")\n\tlist(APPEND _libdir \"${BLAS_DIR}/lib/intel64\")\n      else()\n\tlist(APPEND _libdir \"${BLAS_DIR}/lib32\")\n\tlist(APPEND _libdir \"${BLAS_DIR}/lib/ia32\")\n      endif()\n    elseif(ENV_BLAS_LIBDIR)\n      list(APPEND _libdir \"${ENV_BLAS_LIBDIR}\")\n    elseif(ENV_BLAS_DIR)\n      list(APPEND _libdir \"${ENV_BLAS_DIR}\")\n      list(APPEND _libdir \"${ENV_BLAS_DIR}/lib\")\n      if(\"${CMAKE_SIZEOF_VOID_P}\" EQUAL \"8\")\n\tlist(APPEND _libdir \"${ENV_BLAS_DIR}/lib64\")\n\tlist(APPEND _libdir \"${ENV_BLAS_DIR}/lib/intel64\")\n      else()\n\tlist(APPEND _libdir \"${ENV_BLAS_DIR}/lib32\")\n\tlist(APPEND _libdir \"${ENV_BLAS_DIR}/lib/ia32\")\n      endif()\n    else()\n      if (ENV_MKLROOT)\n\tlist(APPEND _libdir \"${ENV_MKLROOT}/lib\")\n\tif(\"${CMAKE_SIZEOF_VOID_P}\" EQUAL \"8\")\n\t  list(APPEND _libdir \"${ENV_MKLROOT}/lib64\")\n\t  list(APPEND _libdir \"${ENV_MKLROOT}/lib/intel64\")\n\telse()\n\t  list(APPEND _libdir \"${ENV_MKLROOT}/lib32\")\n\t  list(APPEND _libdir \"${ENV_MKLROOT}/lib/ia32\")\n\tendif()\n      endif()\n      if (WIN32)\n\tstring(REPLACE \":\" \";\" _libdir2 \"$ENV{LIB}\")\n      elseif (APPLE)\n\tstring(REPLACE \":\" \";\" _libdir2 \"$ENV{DYLD_LIBRARY_PATH}\")\n      else ()\n\tstring(REPLACE \":\" \";\" _libdir2 \"$ENV{LD_LIBRARY_PATH}\")\n      endif ()\n      list(APPEND _libdir \"${_libdir2}\")\n      list(APPEND _libdir \"${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}\")\n      list(APPEND _libdir \"${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}\")\n    endif()\n  endif ()\n\n  if (BLAS_VERBOSE)\n    message(\"${Cyan}Try to find BLAS libraries: ${_list}\")\n  endif ()\n\n  foreach(_library ${_list})\n    set(_combined_name ${_combined_name}_${_library})\n\n    if(_libraries_work)\n      if (BLA_STATIC)\n\tif (WIN32)\n\t  set(CMAKE_FIND_LIBRARY_SUFFIXES .lib ${CMAKE_FIND_LIBRARY_SUFFIXES})\n\tendif ()\n\tif (APPLE)\n\t  set(CMAKE_FIND_LIBRARY_SUFFIXES .lib ${CMAKE_FIND_LIBRARY_SUFFIXES})\n\telse ()\n\t  set(CMAKE_FIND_LIBRARY_SUFFIXES .a ${CMAKE_FIND_LIBRARY_SUFFIXES})\n\tendif ()\n      else ()\n\tif (CMAKE_SYSTEM_NAME STREQUAL \"Linux\")\n\t  # for ubuntu's libblas3gf and liblapack3gf packages\n\t  set(CMAKE_FIND_LIBRARY_SUFFIXES ${CMAKE_FIND_LIBRARY_SUFFIXES} .so.3gf)\n\tendif ()\n      endif ()\n      find_library(${_prefix}_${_library}_LIBRARY\n\tNAMES ${_library}\n\tHINTS ${_libdir}\n\tNO_DEFAULT_PATH\n\t)\n      mark_as_advanced(${_prefix}_${_library}_LIBRARY)\n      # Print status if not found\n      # -------------------------\n      if (NOT ${_prefix}_${_library}_LIBRARY AND NOT BLAS_FIND_QUIETLY AND BLAS_VERBOSE)\n\tPrint_Find_Library_Blas_Status(blas ${_library} ${_libdir})\n      endif ()\n      set(${LIBRARIES} ${${LIBRARIES}} ${${_prefix}_${_library}_LIBRARY})\n      set(_libraries_work ${${_prefix}_${_library}_LIBRARY})\n    endif()\n  endforeach()\n\n  if(_libraries_work)\n    # Test this combination of libraries.\n    if (CMAKE_SYSTEM_NAME STREQUAL \"Linux\" AND BLA_STATIC)\n      list(INSERT ${LIBRARIES} 0 \"-Wl,--start-group\")\n      list(APPEND ${LIBRARIES} \"-Wl,--end-group\")\n    endif()\n    set(CMAKE_REQUIRED_LIBRARIES \"${_flags};${${LIBRARIES}};${_thread}\")\n    set(CMAKE_REQUIRED_FLAGS \"${BLAS_COMPILER_FLAGS}\")\n    if (BLAS_VERBOSE)\n      message(\"${Cyan}BLAS libs found for BLA_VENDOR ${BLA_VENDOR}.\"\n\t\"Try to compile symbol ${_name} with following libraries:\"\n\t\"${CMAKE_REQUIRED_LIBRARIES}\")\n    endif ()\n    if(NOT BLAS_FOUND)\n      unset(${_prefix}${_combined_name}_WORKS CACHE)\n    endif()\n    if (_CHECK_FORTRAN)\n      if (CMAKE_Fortran_COMPILER_ID STREQUAL \"GNU\")\n\tstring(REPLACE \"mkl_intel_lp64\" \"mkl_gf_lp64\" CMAKE_REQUIRED_LIBRARIES \"${CMAKE_REQUIRED_LIBRARIES}\")\n\tstring(REPLACE \"mkl_intel_ilp64\" \"mkl_gf_ilp64\" CMAKE_REQUIRED_LIBRARIES \"${CMAKE_REQUIRED_LIBRARIES}\")\n      endif()\n      check_fortran_function_exists(\"${_name}\" ${_prefix}${_combined_name}_WORKS)\n    else()\n      check_function_exists(\"${_name}_\" ${_prefix}${_combined_name}_WORKS)\n    endif()\n    mark_as_advanced(${_prefix}${_combined_name}_WORKS)\n    set(_libraries_work ${${_prefix}${_combined_name}_WORKS})\n    # Print status if not found\n    # -------------------------\n    if (NOT _libraries_work AND NOT BLAS_FIND_QUIETLY AND BLAS_VERBOSE)\n      Print_Find_Library_Blas_CheckFunc_Status(${_name} ${CMAKE_REQUIRED_LIBRARIES})\n    endif ()\n    set(CMAKE_REQUIRED_LIBRARIES)\n  endif()\n\n  if(_libraries_work)\n    set(${LIBRARIES} ${${LIBRARIES}} ${_thread})\n  else()\n    set(${LIBRARIES} FALSE)\n  endif()\n\nendmacro()\n\n\nset(BLAS_LINKER_FLAGS)\nset(BLAS_LIBRARIES)\nset(BLAS95_LIBRARIES)\nif ($ENV{BLA_VENDOR} MATCHES \".+\")\n  set(BLA_VENDOR $ENV{BLA_VENDOR})\nelse ()\n  if(NOT BLA_VENDOR)\n    set(BLA_VENDOR \"All\")\n  endif()\nendif ()\n\n#BLAS in intel mkl 10 library? (em64t 64bit)\nif (BLA_VENDOR MATCHES \"Intel*\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES OR BLA_VENDOR MATCHES \"Intel*\")\n    # Looking for include\n    # -------------------\n\n    # Add system include paths to search include\n    # ------------------------------------------\n    unset(_inc_env)\n    set(ENV_MKLROOT \"$ENV{MKLROOT}\")\n    set(ENV_BLAS_DIR \"$ENV{BLAS_DIR}\")\n    set(ENV_BLAS_INCDIR \"$ENV{BLAS_INCDIR}\")\n    if(ENV_BLAS_INCDIR)\n      list(APPEND _inc_env \"${ENV_BLAS_INCDIR}\")\n    elseif(ENV_BLAS_DIR)\n      list(APPEND _inc_env \"${ENV_BLAS_DIR}\")\n      list(APPEND _inc_env \"${ENV_BLAS_DIR}/include\")\n    else()\n      if (ENV_MKLROOT)\n\tlist(APPEND _inc_env \"${ENV_MKLROOT}/include\")\n      endif()\n      # system variables\n      if(WIN32)\n\tstring(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE}\")\n\tlist(APPEND _inc_env \"${_path_env}\")\n      else()\n\tstring(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE}\")\n\tlist(APPEND _inc_env \"${_path_env}\")\n\tstring(REPLACE \":\" \";\" _path_env \"$ENV{C_INCLUDE_PATH}\")\n\tlist(APPEND _inc_env \"${_path_env}\")\n\tstring(REPLACE \":\" \";\" _path_env \"$ENV{CPATH}\")\n\tlist(APPEND _inc_env \"${_path_env}\")\n\tstring(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE_PATH}\")\n\tlist(APPEND _inc_env \"${_path_env}\")\n      endif()\n    endif()\n    list(APPEND _inc_env \"${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}\")\n    list(APPEND _inc_env \"${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}\")\n    list(REMOVE_DUPLICATES _inc_env)\n\n    # set paths where to look for\n    set(PATH_TO_LOOK_FOR \"${_inc_env}\")\n\n    # Try to find the fftw header in the given paths\n    # -------------------------------------------------\n    # call cmake macro to find the header path\n    if(BLAS_INCDIR)\n      set(BLAS_mkl.h_DIRS \"BLAS_mkl.h_DIRS-NOTFOUND\")\n      find_path(BLAS_mkl.h_DIRS\n\tNAMES mkl.h\n\tHINTS ${BLAS_INCDIR})\n    else()\n      if(BLAS_DIR)\n\tset(BLAS_mkl.h_DIRS \"BLAS_mkl.h_DIRS-NOTFOUND\")\n\tfind_path(BLAS_mkl.h_DIRS\n\t  NAMES mkl.h\n\t  HINTS ${BLAS_DIR}\n\t  PATH_SUFFIXES \"include\")\n      else()\n\tset(BLAS_mkl.h_DIRS \"BLAS_mkl.h_DIRS-NOTFOUND\")\n\tfind_path(BLAS_mkl.h_DIRS\n\t  NAMES mkl.h\n\t  HINTS ${PATH_TO_LOOK_FOR})\n      endif()\n    endif()\n    mark_as_advanced(BLAS_mkl.h_DIRS)\n\n    # If found, add path to cmake variable\n    # ------------------------------------\n    if (BLAS_mkl.h_DIRS)\n      set(BLAS_INCLUDE_DIRS \"${BLAS_mkl.h_DIRS}\")\n    else ()\n      set(BLAS_INCLUDE_DIRS \"BLAS_INCLUDE_DIRS-NOTFOUND\")\n      if(NOT BLAS_FIND_QUIETLY)\n\tmessage(STATUS \"Looking for BLAS -- mkl.h not found\")\n      endif()\n    endif()\n\n    if (WIN32)\n      string(REPLACE \":\" \";\" _libdir \"$ENV{LIB}\")\n    elseif (APPLE)\n      string(REPLACE \":\" \";\" _libdir \"$ENV{DYLD_LIBRARY_PATH}\")\n    else ()\n      string(REPLACE \":\" \";\" _libdir \"$ENV{LD_LIBRARY_PATH}\")\n    endif ()\n    list(APPEND _libdir \"${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}\")\n    list(APPEND _libdir \"${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}\")\n    # libiomp5\n    # --------\n    set(OMP_iomp5_LIBRARY \"OMP_iomp5_LIBRARY-NOTFOUND\")\n    find_library(OMP_iomp5_LIBRARY\n      NAMES iomp5\n      HINTS ${_libdir}\n      )\n    mark_as_advanced(OMP_iomp5_LIBRARY)\n    set(OMP_LIB \"\")\n    # libgomp\n    # -------\n    set(OMP_gomp_LIBRARY \"OMP_gomp_LIBRARY-NOTFOUND\")\n    find_library(OMP_gomp_LIBRARY\n      NAMES gomp\n      HINTS ${_libdir}\n      )\n    mark_as_advanced(OMP_gomp_LIBRARY)\n    # choose one or another depending on the compilo\n    if (CMAKE_C_COMPILER_ID STREQUAL \"GNU\")\n      if (OMP_gomp_LIBRARY)\n\tset(OMP_LIB \"${OMP_gomp_LIBRARY}\")\n      endif()\n    else()\n      if (OMP_iomp5_LIBRARY)\n\tset(OMP_LIB \"${OMP_iomp5_LIBRARY}\")\n      endif()\n    endif()\n\n    if (UNIX AND NOT WIN32)\n      # m\n      find_library(M_LIBRARY\n\tNAMES m\n\tHINTS ${_libdir})\n      mark_as_advanced(M_LIBRARY)\n      if(M_LIBRARY)\n\tset(LM \"-lm\")\n      else()\n\tset(LM \"\")\n      endif()\n      # Fortran\n      set(LGFORTRAN \"\")\n      if (CMAKE_C_COMPILER_ID MATCHES \"GNU\")\n\tfind_library(\n\t  FORTRAN_gfortran_LIBRARY\n\t  NAMES gfortran\n\t  HINTS ${_libdir}\n\t  )\n\tmark_as_advanced(FORTRAN_gfortran_LIBRARY)\n\tif (FORTRAN_gfortran_LIBRARY)\n\t  set(LGFORTRAN \"${FORTRAN_gfortran_LIBRARY}\")\n\tendif()\n      elseif (CMAKE_C_COMPILER_ID MATCHES \"Intel\")\n\tfind_library(\n\t  FORTRAN_ifcore_LIBRARY\n\t  NAMES ifcore\n\t  HINTS ${_libdir}\n\t  )\n\tmark_as_advanced(FORTRAN_ifcore_LIBRARY)\n\tif (FORTRAN_ifcore_LIBRARY)\n\t  set(LGFORTRAN \"{FORTRAN_ifcore_LIBRARY}\")\n\tendif()\n      endif()\n      set(BLAS_COMPILER_FLAGS \"\")\n      if (NOT BLA_VENDOR STREQUAL \"Intel10_64lp_seq\")\n\tif (CMAKE_C_COMPILER_ID STREQUAL \"Intel\")\n\t  list(APPEND BLAS_COMPILER_FLAGS \"-openmp\")\n\tendif()\n\tif (CMAKE_C_COMPILER_ID STREQUAL \"GNU\")\n\t  list(APPEND BLAS_COMPILER_FLAGS \"-fopenmp\")\n\tendif()\n      endif()\n      if (CMAKE_C_COMPILER_ID STREQUAL \"GNU\")\n\tif (BLA_VENDOR STREQUAL \"Intel10_32\")\n\t  list(APPEND BLAS_COMPILER_FLAGS \"-m32\")\n\telse()\n\t  list(APPEND BLAS_COMPILER_FLAGS \"-m64\")\n\tendif()\n\tif (NOT BLA_VENDOR STREQUAL \"Intel10_64lp_seq\")\n\t  list(APPEND OMP_LIB \"-ldl\")\n\tendif()\n\tif (ENV_MKLROOT)\n\t  list(APPEND BLAS_COMPILER_FLAGS \"-I${ENV_MKLROOT}/include\")\n\tendif()\n      endif()\n\n      set(additional_flags \"\")\n      if (CMAKE_C_COMPILER_ID STREQUAL \"GNU\" AND CMAKE_SYSTEM_NAME STREQUAL \"Linux\")\n\tset(additional_flags \"-Wl,--no-as-needed\")\n      endif()\n    endif ()\n\n    if (_LANGUAGES_ MATCHES C OR _LANGUAGES_ MATCHES CXX)\n      if(BLAS_FIND_QUIETLY OR NOT BLAS_FIND_REQUIRED)\n\tfind_package(Threads)\n      else()\n\tfind_package(Threads REQUIRED)\n      endif()\n\n      set(BLAS_SEARCH_LIBS \"\")\n\n      if(BLA_F95)\n\n\tset(BLAS_mkl_SEARCH_SYMBOL SGEMM)\n\tset(_LIBRARIES BLAS95_LIBRARIES)\n\tif (WIN32)\n\t  if (BLA_STATIC)\n\t    set(BLAS_mkl_DLL_SUFFIX \"\")\n\t  else()\n\t    set(BLAS_mkl_DLL_SUFFIX \"_dll\")\n\t  endif()\n\n\t  # Find the main file (32-bit or 64-bit)\n\t  set(BLAS_SEARCH_LIBS_WIN_MAIN \"\")\n\t  if (BLA_VENDOR STREQUAL \"Intel10_32\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS_WIN_MAIN\n\t      \"mkl_blas95${BLAS_mkl_DLL_SUFFIX} mkl_intel_c${BLAS_mkl_DLL_SUFFIX}\")\n\t  endif()\n\t  if (BLA_VENDOR STREQUAL \"Intel10_64lp*\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS_WIN_MAIN\n\t      \"mkl_blas95_lp64${BLAS_mkl_DLL_SUFFIX} mkl_intel_lp64${BLAS_mkl_DLL_SUFFIX}\")\n\t  endif ()\n\n\t  # Add threading/sequential libs\n\t  set(BLAS_SEARCH_LIBS_WIN_THREAD \"\")\n\t  if (BLA_VENDOR STREQUAL \"*_seq\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS_WIN_THREAD\n\t      \"mkl_sequential${BLAS_mkl_DLL_SUFFIX}\")\n\t  endif()\n\t  if (NOT BLA_VENDOR STREQUAL \"*_seq\" OR BLA_VENDOR STREQUAL \"All\")\n\t    # old version\n\t    list(APPEND BLAS_SEARCH_LIBS_WIN_THREAD\n\t      \"libguide40 mkl_intel_thread${BLAS_mkl_DLL_SUFFIX}\")\n\t    # mkl >= 10.3\n\t    list(APPEND BLAS_SEARCH_LIBS_WIN_THREAD\n\t      \"libiomp5md mkl_intel_thread${BLAS_mkl_DLL_SUFFIX}\")\n\t  endif()\n\n\t  # Cartesian product of the above\n\t  foreach (MAIN ${BLAS_SEARCH_LIBS_WIN_MAIN})\n\t    foreach (THREAD ${BLAS_SEARCH_LIBS_WIN_THREAD})\n\t      list(APPEND BLAS_SEARCH_LIBS\n\t\t\"${MAIN} ${THREAD} mkl_core${BLAS_mkl_DLL_SUFFIX}\")\n\t    endforeach()\n\t  endforeach()\n\telse ()\n\t  if (BLA_VENDOR STREQUAL \"Intel10_32\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS\n\t      \"mkl_blas95 mkl_intel mkl_intel_thread mkl_core guide\")\n\t  endif ()\n\t  if (BLA_VENDOR STREQUAL \"Intel10_64lp\" OR BLA_VENDOR STREQUAL \"All\")\n\t    # old version\n\t    list(APPEND BLAS_SEARCH_LIBS\n\t      \"mkl_blas95 mkl_intel_lp64 mkl_intel_thread mkl_core guide\")\n\t    # mkl >= 10.3\n\t    if (CMAKE_C_COMPILER_ID STREQUAL \"Intel\")\n\t      list(APPEND BLAS_SEARCH_LIBS\n\t\t\"mkl_blas95_lp64 mkl_intel_lp64 mkl_intel_thread mkl_core\")\n\t    endif()\n\t    if (CMAKE_C_COMPILER_ID STREQUAL \"GNU\")\n\t      list(APPEND BLAS_SEARCH_LIBS\n\t\t\"mkl_blas95_lp64 mkl_intel_lp64 mkl_gnu_thread mkl_core\")\n\t    endif()\n\t  endif ()\n\t  if (BLA_VENDOR STREQUAL \"Intel10_64lp_seq\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS\n\t      \"mkl_intel_lp64 mkl_sequential mkl_core\")\n\t    if (BLA_VENDOR STREQUAL \"Intel10_64lp_seq\")\n\t      set(OMP_LIB \"\")\n\t    endif()\n\t  endif ()\n\tendif ()\n\n      else ()\n\n\tset(BLAS_mkl_SEARCH_SYMBOL sgemm)\n\tset(_LIBRARIES BLAS_LIBRARIES)\n\tif (WIN32)\n\t  if (BLA_STATIC)\n\t    set(BLAS_mkl_DLL_SUFFIX \"\")\n\t  else()\n\t    set(BLAS_mkl_DLL_SUFFIX \"_dll\")\n\t  endif()\n\n\t  # Find the main file (32-bit or 64-bit)\n\t  set(BLAS_SEARCH_LIBS_WIN_MAIN \"\")\n\t  if (BLA_VENDOR STREQUAL \"Intel10_32\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS_WIN_MAIN\n\t      \"mkl_intel_c${BLAS_mkl_DLL_SUFFIX}\")\n\t  endif()\n\t  if (BLA_VENDOR STREQUAL \"Intel10_64lp*\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS_WIN_MAIN\n\t      \"mkl_intel_lp64${BLAS_mkl_DLL_SUFFIX}\")\n\t  endif ()\n\n\t  # Add threading/sequential libs\n\t  set(BLAS_SEARCH_LIBS_WIN_THREAD \"\")\n\t  if (NOT BLA_VENDOR STREQUAL \"*_seq\" OR BLA_VENDOR STREQUAL \"All\")\n\t    # old version\n\t    list(APPEND BLAS_SEARCH_LIBS_WIN_THREAD\n\t      \"libguide40 mkl_intel_thread${BLAS_mkl_DLL_SUFFIX}\")\n\t    # mkl >= 10.3\n\t    list(APPEND BLAS_SEARCH_LIBS_WIN_THREAD\n\t      \"libiomp5md mkl_intel_thread${BLAS_mkl_DLL_SUFFIX}\")\n\t  endif()\n\t  if (BLA_VENDOR STREQUAL \"*_seq\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS_WIN_THREAD\n\t      \"mkl_sequential${BLAS_mkl_DLL_SUFFIX}\")\n\t  endif()\n\n\t  # Cartesian product of the above\n\t  foreach (MAIN ${BLAS_SEARCH_LIBS_WIN_MAIN})\n\t    foreach (THREAD ${BLAS_SEARCH_LIBS_WIN_THREAD})\n\t      list(APPEND BLAS_SEARCH_LIBS\n\t\t\"${MAIN} ${THREAD} mkl_core${BLAS_mkl_DLL_SUFFIX}\")\n\t    endforeach()\n\t  endforeach()\n\telse ()\n\t  if (BLA_VENDOR STREQUAL \"Intel10_32\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS\n\t      \"mkl_intel mkl_intel_thread mkl_core guide\")\n\t  endif ()\n\t  if (BLA_VENDOR STREQUAL \"Intel10_64lp\" OR BLA_VENDOR STREQUAL \"All\")\n\t    # old version\n\t    list(APPEND BLAS_SEARCH_LIBS\n\t      \"mkl_intel_lp64 mkl_intel_thread mkl_core guide\")\n\t    # mkl >= 10.3\n\t    if (CMAKE_C_COMPILER_ID STREQUAL \"Intel\")\n\t      list(APPEND BLAS_SEARCH_LIBS\n\t\t\"mkl_intel_lp64 mkl_intel_thread mkl_core\")\n\t    endif()\n\t    if (CMAKE_C_COMPILER_ID STREQUAL \"GNU\")\n\t      list(APPEND BLAS_SEARCH_LIBS\n\t\t\"mkl_intel_lp64 mkl_gnu_thread mkl_core\")\n\t    endif()\n\t  endif ()\n\t  if (BLA_VENDOR STREQUAL \"Intel10_64lp_seq\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS\n\t      \"mkl_intel_lp64 mkl_sequential mkl_core\")\n\t    if (BLA_VENDOR STREQUAL \"Intel10_64lp_seq\")\n\t      set(OMP_LIB \"\")\n\t    endif()\n\t  endif ()\n\t  #older vesions of intel mkl libs\n\t  if (BLA_VENDOR STREQUAL \"Intel\" OR BLA_VENDOR STREQUAL \"All\")\n\t    list(APPEND BLAS_SEARCH_LIBS\n\t      \"mkl\")\n\t    list(APPEND BLAS_SEARCH_LIBS\n\t      \"mkl_ia32\")\n\t    list(APPEND BLAS_SEARCH_LIBS\n\t      \"mkl_em64t\")\n\t  endif ()\n\tendif ()\n\n      endif ()\n\n      foreach (IT ${BLAS_SEARCH_LIBS})\n\tstring(REPLACE \" \" \";\" SEARCH_LIBS ${IT})\n\tif (${_LIBRARIES})\n\telse ()\n\t  check_fortran_libraries(\n\t    ${_LIBRARIES}\n\t    BLAS\n\t    ${BLAS_mkl_SEARCH_SYMBOL}\n\t    \"${additional_flags}\"\n\t    \"${SEARCH_LIBS}\"\n\t    \"${OMP_LIB};${CMAKE_THREAD_LIBS_INIT};${LM}\"\n\t    )\n\t  if(_LIBRARIES)\n\t    set(BLAS_LINKER_FLAGS \"${additional_flags}\")\n\t  endif()\n\tendif()\n      endforeach ()\n      if(NOT BLAS_FIND_QUIETLY)\n        if(${_LIBRARIES})\n          message(STATUS \"Looking for MKL BLAS: found\")\n        else()\n          message(STATUS \"Looking for MKL BLAS: not found\")\n        endif()\n      endif()\n      if (${_LIBRARIES} AND NOT BLAS_VENDOR_FOUND)\n          set (BLAS_VENDOR_FOUND \"Intel MKL\")\n      endif()\n    endif ()\n  endif()\nendif ()\n\n\nif (BLA_VENDOR STREQUAL \"Goto\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    # gotoblas (http://www.tacc.utexas.edu/tacc-projects/gotoblas2)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"goto2\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for Goto BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for Goto BLAS: not found\")\n      endif()\n    endif()\n  endif()\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"Goto\")\n  endif()\n\nendif ()\n\n\n# OpenBlas\nif (BLA_VENDOR STREQUAL \"Open\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    # openblas (http://www.openblas.net/)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"openblas\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for Open BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for Open BLAS: not found\")\n      endif()\n    endif()\n  endif()\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"Openblas\")\n  endif()\n\nendif ()\n\n\n# EigenBlas\nif (BLA_VENDOR STREQUAL \"Eigen\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    # eigenblas (http://eigen.tuxfamily.org/index.php?title=Main_Page)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"eigen_blas\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n\tmessage(STATUS \"Looking for Eigen BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for Eigen BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if(NOT BLAS_LIBRARIES)\n    # eigenblas (http://eigen.tuxfamily.org/index.php?title=Main_Page)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"eigen_blas_static\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for Eigen BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for Eigen BLAS: not found\")\n      endif()\n    endif()\n  endif()\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"Eigen\")\n  endif()\n\nendif ()\n\n\nif (BLA_VENDOR STREQUAL \"ATLAS\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    # BLAS in ATLAS library? (http://math-atlas.sourceforge.net/)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      dgemm\n      \"\"\n      \"f77blas;atlas\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for Atlas BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for Atlas BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"Atlas\")\n  endif()\n\nendif ()\n\n\n# BLAS in PhiPACK libraries? (requires generic BLAS lib, too)\nif (BLA_VENDOR STREQUAL \"PhiPACK\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"sgemm;dgemm;blas\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for PhiPACK BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for PhiPACK BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"PhiPACK\")\n  endif()\n\nendif ()\n\n\n# BLAS in Alpha CXML library?\nif (BLA_VENDOR STREQUAL \"CXML\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"cxml\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for CXML BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for CXML BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"CXML\")\n  endif()\n\nendif ()\n\n\n# BLAS in Alpha DXML library? (now called CXML, see above)\nif (BLA_VENDOR STREQUAL \"DXML\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"dxml\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for DXML BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for DXML BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"DXML\")\n  endif()\n  \nendif ()\n\n\n# BLAS in Sun Performance library?\nif (BLA_VENDOR STREQUAL \"SunPerf\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"-xlic_lib=sunperf\"\n      \"sunperf;sunmath\"\n      \"\"\n      )\n    if(BLAS_LIBRARIES)\n      set(BLAS_LINKER_FLAGS \"-xlic_lib=sunperf\")\n    endif()\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for SunPerf BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for SunPerf BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"SunPerf\")\n  endif()\n\nendif ()\n\n\n# BLAS in SCSL library?  (SGI/Cray Scientific Library)\nif (BLA_VENDOR STREQUAL \"SCSL\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"scsl\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for SCSL BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for SCSL BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"SunPerf\")\n  endif()\n\nendif ()\n\n\n# BLAS in SGIMATH library?\nif (BLA_VENDOR STREQUAL \"SGIMATH\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"complib.sgimath\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for SGIMATH BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for SGIMATH BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"SGIMATH\")\n  endif()\n\nendif ()\n\n\n# BLAS in IBM ESSL library (requires generic BLAS lib, too)\nif (BLA_VENDOR STREQUAL \"IBMESSL\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"essl;xlfmath;xlf90_r;blas\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for IBM ESSL BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for IBM ESSL BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"IBM ESSL\")\n  endif()\n\nendif ()\n\n# BLAS in IBM ESSL_MT library (requires generic BLAS lib, too)\nif (BLA_VENDOR STREQUAL \"IBMESSLMT\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"esslsmp;xlsmp;xlfmath;xlf90_r;blas\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for IBM ESSL MT BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for IBM ESSL MT BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"IBM ESSL MT\")\n  endif()\n\nendif ()\n\n\n#BLAS in acml library?\nif (BLA_VENDOR MATCHES \"ACML.*\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if( ((BLA_VENDOR STREQUAL \"ACML\") AND (NOT BLAS_ACML_LIB_DIRS)) OR\n      ((BLA_VENDOR STREQUAL \"ACML_MP\") AND (NOT BLAS_ACML_MP_LIB_DIRS)) OR\n      ((BLA_VENDOR STREQUAL \"ACML_GPU\") AND (NOT BLAS_ACML_GPU_LIB_DIRS)))\n\n    # try to find acml in \"standard\" paths\n    if( WIN32 )\n      file( GLOB _ACML_ROOT \"C:/AMD/acml*/ACML-EULA.txt\" )\n    else()\n      file( GLOB _ACML_ROOT \"/opt/acml*/ACML-EULA.txt\" )\n    endif()\n    if( WIN32 )\n      file( GLOB _ACML_GPU_ROOT \"C:/AMD/acml*/GPGPUexamples\" )\n    else()\n      file( GLOB _ACML_GPU_ROOT \"/opt/acml*/GPGPUexamples\" )\n    endif()\n    list(GET _ACML_ROOT 0 _ACML_ROOT)\n    list(GET _ACML_GPU_ROOT 0 _ACML_GPU_ROOT)\n\n    if( _ACML_ROOT )\n\n      get_filename_component( _ACML_ROOT ${_ACML_ROOT} PATH )\n      if( SIZEOF_INTEGER EQUAL 8 )\n\tset( _ACML_PATH_SUFFIX \"_int64\" )\n      else()\n\tset( _ACML_PATH_SUFFIX \"\" )\n      endif()\n      if( CMAKE_Fortran_COMPILER_ID STREQUAL \"Intel\" )\n\tset( _ACML_COMPILER32 \"ifort32\" )\n\tset( _ACML_COMPILER64 \"ifort64\" )\n      elseif( CMAKE_Fortran_COMPILER_ID STREQUAL \"SunPro\" )\n\tset( _ACML_COMPILER32 \"sun32\" )\n\tset( _ACML_COMPILER64 \"sun64\" )\n      elseif( CMAKE_Fortran_COMPILER_ID STREQUAL \"PGI\" )\n\tset( _ACML_COMPILER32 \"pgi32\" )\n\tif( WIN32 )\n\t  set( _ACML_COMPILER64 \"win64\" )\n\telse()\n\t  set( _ACML_COMPILER64 \"pgi64\" )\n\tendif()\n      elseif( CMAKE_Fortran_COMPILER_ID STREQUAL \"Open64\" )\n\t# 32 bit builds not supported on Open64 but for code simplicity\n\t# We'll just use the same directory twice\n\tset( _ACML_COMPILER32 \"open64_64\" )\n\tset( _ACML_COMPILER64 \"open64_64\" )\n      elseif( CMAKE_Fortran_COMPILER_ID STREQUAL \"NAG\" )\n\tset( _ACML_COMPILER32 \"nag32\" )\n\tset( _ACML_COMPILER64 \"nag64\" )\n      else()\n\tset( _ACML_COMPILER32 \"gfortran32\" )\n\tset( _ACML_COMPILER64 \"gfortran64\" )\n      endif()\n\n      if( BLA_VENDOR STREQUAL \"ACML_MP\" )\n\tset(_ACML_MP_LIB_DIRS\n\t  \"${_ACML_ROOT}/${_ACML_COMPILER32}_mp${_ACML_PATH_SUFFIX}/lib\"\n\t  \"${_ACML_ROOT}/${_ACML_COMPILER64}_mp${_ACML_PATH_SUFFIX}/lib\" )\n      else()\n\tset(_ACML_LIB_DIRS\n\t  \"${_ACML_ROOT}/${_ACML_COMPILER32}${_ACML_PATH_SUFFIX}/lib\"\n\t  \"${_ACML_ROOT}/${_ACML_COMPILER64}${_ACML_PATH_SUFFIX}/lib\" )\n      endif()\n\n    endif()\n\n  elseif(BLAS_${BLA_VENDOR}_LIB_DIRS)\n\n    set(_${BLA_VENDOR}_LIB_DIRS ${BLAS_${BLA_VENDOR}_LIB_DIRS})\n\n  endif()\n\n  if( BLA_VENDOR STREQUAL \"ACML_MP\" )\n    foreach( BLAS_ACML_MP_LIB_DIRS ${_ACML_MP_LIB_DIRS})\n      check_fortran_libraries (\n\tBLAS_LIBRARIES\n\tBLAS\n\tsgemm\n\t\"\" \"acml_mp;acml_mv\" \"\" ${BLAS_ACML_MP_LIB_DIRS}\n\t)\n      if( BLAS_LIBRARIES )\n\tbreak()\n      endif()\n    endforeach()\n  elseif( BLA_VENDOR STREQUAL \"ACML_GPU\" )\n    foreach( BLAS_ACML_GPU_LIB_DIRS ${_ACML_GPU_LIB_DIRS})\n      check_fortran_libraries (\n\tBLAS_LIBRARIES\n\tBLAS\n\tsgemm\n\t\"\" \"acml;acml_mv;CALBLAS\" \"\" ${BLAS_ACML_GPU_LIB_DIRS}\n\t)\n      if( BLAS_LIBRARIES )\n\tbreak()\n      endif()\n    endforeach()\n  else()\n    foreach( BLAS_ACML_LIB_DIRS ${_ACML_LIB_DIRS} )\n      check_fortran_libraries (\n\tBLAS_LIBRARIES\n\tBLAS\n\tsgemm\n\t\"\" \"acml;acml_mv\" \"\" ${BLAS_ACML_LIB_DIRS}\n\t)\n      if( BLAS_LIBRARIES )\n\tbreak()\n      endif()\n    endforeach()\n  endif()\n\n  # Either acml or acml_mp should be in LD_LIBRARY_PATH but not both\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"acml;acml_mv\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for ACML BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for ACML BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"acml_mp;acml_mv\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for ACML BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for ACML BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      sgemm\n      \"\"\n      \"acml;acml_mv;CALBLAS\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for ACML BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for ACML BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"ACML\")\n  endif()\n\nendif () # ACML\n\n\n# Apple BLAS library?\nif (BLA_VENDOR STREQUAL \"Apple\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if(NOT BLAS_LIBRARIES)\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      dgemm\n      \"\"\n      \"Accelerate\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for Apple BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for Apple BLAS: not found\")\n      endif()\n    endif()\n  endif()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"Apple Accelerate\")\n  endif()\n\nendif ()\n\n\nif (BLA_VENDOR STREQUAL \"NAS\" OR BLA_VENDOR STREQUAL \"All\")\n\n  if ( NOT BLAS_LIBRARIES )\n    check_fortran_libraries(\n      BLAS_LIBRARIES\n      BLAS\n      dgemm\n      \"\"\n      \"vecLib\"\n      \"\"\n      )\n    if(NOT BLAS_FIND_QUIETLY)\n      if(BLAS_LIBRARIES)\n\tmessage(STATUS \"Looking for NAS BLAS: found\")\n      else()\n\tmessage(STATUS \"Looking for NAS BLAS: not found\")\n      endif()\n    endif()\n  endif ()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"NAS\")\n  endif()\n\nendif ()\n\n\n# Generic BLAS library?\nif (BLA_VENDOR STREQUAL \"Generic\" OR BLA_VENDOR STREQUAL \"All\")\n\n  set(BLAS_SEARCH_LIBS \"blas;blas_LINUX;blas_MAC;blas_WINDOWS;refblas\")\n  foreach (SEARCH_LIB ${BLAS_SEARCH_LIBS})\n    if (BLAS_LIBRARIES)\n    else ()\n      check_fortran_libraries(\n\tBLAS_LIBRARIES\n\tBLAS\n\tsgemm\n\t\"\"\n\t\"${SEARCH_LIB}\"\n\t\"${LGFORTRAN}\"\n\t)\n      if(NOT BLAS_FIND_QUIETLY)\n\tif(BLAS_LIBRARIES)\n\t  message(STATUS \"Looking for Generic BLAS: found\")\n\telse()\n\t  message(STATUS \"Looking for Generic BLAS: not found\")\n\tendif()\n      endif()\n    endif()\n  endforeach ()\n\n  if (BLAS_LIBRARIES AND NOT BLAS_VENDOR_FOUND)\n      set (BLAS_VENDOR_FOUND \"Netlib or other Generic libblas\")\n  endif()\n\nendif ()\n\n\nif(BLA_F95)\n\n  if(BLAS95_LIBRARIES)\n    set(BLAS95_FOUND TRUE)\n  else()\n    set(BLAS95_FOUND FALSE)\n  endif()\n\n  if(NOT BLAS_FIND_QUIETLY)\n    if(BLAS95_FOUND)\n      message(STATUS \"A library with BLAS95 API found.\")\n      message(STATUS \"BLAS_LIBRARIES ${BLAS_LIBRARIES}\")\n    else()\n      message(WARNING \"BLA_VENDOR has been set to ${BLA_VENDOR} but blas 95 libraries could not be found or check of symbols failed.\"\n\t\"\\nPlease indicate where to find blas libraries. You have three options:\\n\"\n\t\"- Option 1: Provide the installation directory of BLAS library with cmake option: -DBLAS_DIR=your/path/to/blas\\n\"\n\t\"- Option 2: Provide the directory where to find BLAS libraries with cmake option: -DBLAS_LIBDIR=your/path/to/blas/libs\\n\"\n\t\"- Option 3: Update your environment variable (Linux: LD_LIBRARY_PATH, Windows: LIB, Mac: DYLD_LIBRARY_PATH)\\n\"\n\t\"\\nTo follow libraries detection more precisely you can activate a verbose mode with -DBLAS_VERBOSE=ON at cmake configure.\"\n\t\"\\nYou could also specify a BLAS vendor to look for by setting -DBLA_VENDOR=blas_vendor_name.\"\n\t\"\\nList of possible BLAS vendor: Goto, ATLAS PhiPACK, CXML, DXML, SunPerf, SCSL, SGIMATH, IBMESSL, Intel10_32 (intel mkl v10 32 bit),\"\n\t\"Intel10_64lp (intel mkl v10 64 bit, lp thread model, lp64 model), Intel10_64lp_seq (intel mkl v10 64 bit, sequential code, lp64 model),\"\n\t\"Intel( older versions of mkl 32 and 64 bit), ACML, ACML_MP, ACML_GPU, Apple, NAS, Generic\")\n      if(BLAS_FIND_REQUIRED)\n\tmessage(FATAL_ERROR\n\t  \"A required library with BLAS95 API not found. Please specify library location.\")\n      else()\n\tmessage(STATUS\n\t  \"A library with BLAS95 API not found. Please specify library location.\")\n      endif()\n    endif()\n  endif()\n\n  set(BLAS_FOUND TRUE)\n  set(BLAS_LIBRARIES \"${BLAS95_LIBRARIES}\")\n\nelse()\n\n  if(BLAS_LIBRARIES)\n    set(BLAS_FOUND TRUE)\n  else()\n    set(BLAS_FOUND FALSE)\n  endif()\n\n  if(NOT BLAS_FIND_QUIETLY)\n    if(BLAS_FOUND)\n      message(STATUS \"A library with BLAS API found.\")\n      message(STATUS \"BLAS_LIBRARIES ${BLAS_LIBRARIES}\")\n    else()\n      message(WARNING \"BLA_VENDOR has been set to ${BLA_VENDOR} but blas libraries could not be found or check of symbols failed.\"\n\t\"\\nPlease indicate where to find blas libraries. You have three options:\\n\"\n\t\"- Option 1: Provide the installation directory of BLAS library with cmake option: -DBLAS_DIR=your/path/to/blas\\n\"\n\t\"- Option 2: Provide the directory where to find BLAS libraries with cmake option: -DBLAS_LIBDIR=your/path/to/blas/libs\\n\"\n\t\"- Option 3: Update your environment variable (Linux: LD_LIBRARY_PATH, Windows: LIB, Mac: DYLD_LIBRARY_PATH)\\n\"\n\t\"\\nTo follow libraries detection more precisely you can activate a verbose mode with -DBLAS_VERBOSE=ON at cmake configure.\"\n\t\"\\nYou could also specify a BLAS vendor to look for by setting -DBLA_VENDOR=blas_vendor_name.\"\n\t\"\\nList of possible BLAS vendor: Goto, ATLAS PhiPACK, CXML, DXML, SunPerf, SCSL, SGIMATH, IBMESSL, Intel10_32 (intel mkl v10 32 bit),\"\n\t\"Intel10_64lp (intel mkl v10 64 bit, lp thread model, lp64 model), Intel10_64lp_seq (intel mkl v10 64 bit, sequential code, lp64 model),\"\n\t\"Intel( older versions of mkl 32 and 64 bit), ACML, ACML_MP, ACML_GPU, Apple, NAS, Generic\")\n      if(BLAS_FIND_REQUIRED)\n\tmessage(FATAL_ERROR\n\t  \"A required library with BLAS API not found. Please specify library location.\")\n      else()\n\tmessage(STATUS\n\t  \"A library with BLAS API not found. Please specify library location.\")\n      endif()\n    endif()\n  endif()\n\nendif()\n\nset(CMAKE_FIND_LIBRARY_SUFFIXES ${_blas_ORIG_CMAKE_FIND_LIBRARY_SUFFIXES})\n\nif (BLAS_FOUND)\n  list(GET BLAS_LIBRARIES 0 first_lib)\n  get_filename_component(first_lib_path \"${first_lib}\" PATH)\n  if (${first_lib_path} MATCHES \"(/lib(32|64)?$)|(/lib/intel64$|/lib/ia32$)\")\n    string(REGEX REPLACE \"(/lib(32|64)?$)|(/lib/intel64$|/lib/ia32$)\" \"\" not_cached_dir \"${first_lib_path}\")\n    set(BLAS_DIR_FOUND \"${not_cached_dir}\" CACHE PATH \"Installation directory of BLAS library\" FORCE)\n  else()\n    set(BLAS_DIR_FOUND \"${first_lib_path}\" CACHE PATH \"Installation directory of BLAS library\" FORCE)\n  endif()\nendif()\nmark_as_advanced(BLAS_DIR)\nmark_as_advanced(BLAS_DIR_FOUND)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindBLASEXT.cmake",
    "content": "###\n#\n# @copyright (c) 2009-2014 The University of Tennessee and The University\n#                          of Tennessee Research Foundation.\n#                          All rights reserved.\n# @copyright (c) 2012-2016 Inria. All rights reserved.\n# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved.\n#\n###\n#\n# - Find BLAS EXTENDED for MORSE projects: find include dirs and libraries\n#\n# This module allows to find BLAS libraries by calling the official FindBLAS module\n# and handles the creation of different library lists whether the user wishes to link\n# with a sequential BLAS or a multihreaded (BLAS_SEQ_LIBRARIES and BLAS_PAR_LIBRARIES).\n# BLAS is detected with a FindBLAS call then if the BLAS vendor is Intel10_64lp, ACML\n# or IBMESSLMT then the module attempts to find the corresponding multithreaded libraries.\n#\n# The following variables have been added to manage links with sequential or multithreaded\n# versions:\n#  BLAS_INCLUDE_DIRS  - BLAS include directories\n#  BLAS_LIBRARY_DIRS  - Link directories for BLAS libraries\n#  BLAS_SEQ_LIBRARIES - BLAS component libraries to be linked (sequential)\n#  BLAS_PAR_LIBRARIES - BLAS component libraries to be linked (multithreaded)\n\n#=============================================================================\n# Copyright 2012-2013 Inria\n# Copyright 2012-2013 Emmanuel Agullo\n# Copyright 2012-2013 Mathieu Faverge\n# Copyright 2012      Cedric Castagnede\n# Copyright 2013-2016 Florent Pruvost\n#\n# Distributed under the OSI-approved BSD License (the \"License\");\n# see accompanying file MORSE-Copyright.txt for details.\n#\n# This software is distributed WITHOUT ANY WARRANTY; without even the\n# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.\n# See the License for more information.\n#=============================================================================\n# (To distribute this file outside of Morse, substitute the full\n#  License text for the above reference.)\n\n# macro to factorize this call\nmacro(find_package_blas)\n  if(BLASEXT_FIND_REQUIRED)\n    if(BLASEXT_FIND_QUIETLY)\n      find_package(BLAS REQUIRED QUIET)\n    else()\n      find_package(BLAS REQUIRED)\n    endif()\n  else()\n    if(BLASEXT_FIND_QUIETLY)\n      find_package(BLAS QUIET)\n    else()\n      find_package(BLAS)\n    endif()\n  endif()\nendmacro()\n\n# add a cache variable to let the user specify the BLAS vendor\nset(BLA_VENDOR \"\" CACHE STRING \"list of possible BLAS vendor:\n    Open, Eigen, Goto, ATLAS PhiPACK, CXML, DXML, SunPerf, SCSL, SGIMATH, IBMESSL, IBMESSLMT,\n    Intel10_32 (intel mkl v10 32 bit),\n    Intel10_64lp (intel mkl v10 64 bit, lp thread model, lp64 model),\n    Intel10_64lp_seq (intel mkl v10 64 bit, sequential code, lp64 model),\n    Intel( older versions of mkl 32 and 64 bit),\n    ACML, ACML_MP, ACML_GPU, Apple, NAS, Generic\")\n\nif(NOT BLASEXT_FIND_QUIETLY)\n  message(STATUS \"In FindBLASEXT\")\n  message(STATUS \"If you want to force the use of one specific library, \"\n    \"\\n   please specify the BLAS vendor by setting -DBLA_VENDOR=blas_vendor_name\"\n    \"\\n   at cmake configure.\")\n  message(STATUS \"List of possible BLAS vendor: Goto, ATLAS PhiPACK, CXML, \"\n    \"\\n   DXML, SunPerf, SCSL, SGIMATH, IBMESSL, IBMESSLMT, Intel10_32 (intel mkl v10 32 bit),\"\n    \"\\n   Intel10_64lp (intel mkl v10 64 bit, lp thread model, lp64 model),\"\n    \"\\n   Intel10_64lp_seq (intel mkl v10 64 bit, sequential code, lp64 model),\"\n    \"\\n   Intel( older versions of mkl 32 and 64 bit),\"\n    \"\\n   ACML, ACML_MP, ACML_GPU, Apple, NAS, Generic\")\nendif()\n\nif (NOT BLAS_FOUND)\n  # First try to detect two cases:\n  # 1: only SEQ libs are handled\n  # 2: both SEQ and PAR libs are handled\n  find_package_blas()\nendif ()\n\n# detect the cases where SEQ and PAR libs are handled\nif(BLA_VENDOR STREQUAL \"All\" AND\n    (BLAS_mkl_core_LIBRARY OR BLAS_mkl_core_dll_LIBRARY)\n    )\n  set(BLA_VENDOR \"Intel\")\n  if(BLAS_mkl_intel_LIBRARY)\n    set(BLA_VENDOR \"Intel10_32\")\n  endif()\n  if(BLAS_mkl_intel_lp64_LIBRARY)\n    set(BLA_VENDOR \"Intel10_64lp\")\n  endif()\n  if(NOT BLASEXT_FIND_QUIETLY)\n    message(STATUS \"A BLAS library has been found (${BLAS_LIBRARIES}) but we\"\n      \"\\n   have also potentially detected some multithreaded BLAS libraries from the MKL.\"\n      \"\\n   We try to find both libraries lists (Sequential/Multithreaded).\")\n  endif()\n  set(BLAS_FOUND \"\")\nelseif(BLA_VENDOR STREQUAL \"All\" AND BLAS_acml_LIBRARY)\n  set(BLA_VENDOR \"ACML\")\n  if(NOT BLASEXT_FIND_QUIETLY)\n    message(STATUS \"A BLAS library has been found (${BLAS_LIBRARIES}) but we\"\n      \"\\n   have also potentially detected some multithreaded BLAS libraries from the ACML.\"\n      \"\\n   We try to find both libraries lists (Sequential/Multithreaded).\")\n  endif()\n  set(BLAS_FOUND \"\")\nelseif(BLA_VENDOR STREQUAL \"All\" AND BLAS_essl_LIBRARY)\n  set(BLA_VENDOR \"IBMESSL\")\n  if(NOT BLASEXT_FIND_QUIETLY)\n    message(STATUS \"A BLAS library has been found (${BLAS_LIBRARIES}) but we\"\n      \"\\n   have also potentially detected some multithreaded BLAS libraries from the ESSL.\"\n      \"\\n   We try to find both libraries lists (Sequential/Multithreaded).\")\n  endif()\n  set(BLAS_FOUND \"\")\nendif()\n\n# Intel case\nif(BLA_VENDOR MATCHES \"Intel*\")\n\n  ###\n  # look for include path if the BLAS vendor is Intel\n  ###\n\n  # gather system include paths\n  unset(_inc_env)\n  if(WIN32)\n    string(REPLACE \":\" \";\" _inc_env \"$ENV{INCLUDE}\")\n  else()\n    string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{C_INCLUDE_PATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{CPATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE_PATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n  endif()\n  list(APPEND _inc_env \"${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}\")\n  list(APPEND _inc_env \"${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}\")\n  set(ENV_MKLROOT \"$ENV{MKLROOT}\")\n  if (ENV_MKLROOT)\n    list(APPEND _inc_env \"${ENV_MKLROOT}/include\")\n  endif()\n  list(REMOVE_DUPLICATES _inc_env)\n\n  # find mkl.h inside known include paths\n  set(BLAS_mkl.h_INCLUDE_DIRS \"BLAS_mkl.h_INCLUDE_DIRS-NOTFOUND\")\n  if(BLAS_INCDIR)\n    set(BLAS_mkl.h_INCLUDE_DIRS \"BLAS_mkl.h_INCLUDE_DIRS-NOTFOUND\")\n    find_path(BLAS_mkl.h_INCLUDE_DIRS\n      NAMES mkl.h\n      HINTS ${BLAS_INCDIR})\n  else()\n    if(BLAS_DIR)\n      set(BLAS_mkl.h_INCLUDE_DIRS \"BLAS_mkl.h_INCLUDE_DIRS-NOTFOUND\")\n      find_path(BLAS_mkl.h_INCLUDE_DIRS\n\tNAMES mkl.h\n\tHINTS ${BLAS_DIR}\n\tPATH_SUFFIXES include)\n    else()\n      set(BLAS_mkl.h_INCLUDE_DIRS \"BLAS_mkl.h_INCLUDE_DIRS-NOTFOUND\")\n      find_path(BLAS_mkl.h_INCLUDE_DIRS\n\tNAMES mkl.h\n\tHINTS ${_inc_env})\n    endif()\n  endif()\n  mark_as_advanced(BLAS_mkl.h_INCLUDE_DIRS)\n  ## Print status if not found\n  ## -------------------------\n  #if (NOT BLAS_mkl.h_INCLUDE_DIRS AND MORSE_VERBOSE)\n  #    Print_Find_Header_Status(blas mkl.h)\n  #endif ()\n  set(BLAS_INCLUDE_DIRS \"\")\n  if(BLAS_mkl.h_INCLUDE_DIRS)\n    list(APPEND BLAS_INCLUDE_DIRS \"${BLAS_mkl.h_INCLUDE_DIRS}\" )\n  endif()\n\n  ###\n  # look for libs\n  ###\n  # if Intel 10 64 bit -> look for sequential and multithreaded versions\n  if(BLA_VENDOR MATCHES \"Intel10_64lp*\")\n\n    ## look for the sequential version\n    set(BLA_VENDOR \"Intel10_64lp_seq\")\n    if(NOT BLASEXT_FIND_QUIETLY)\n      message(STATUS \"Look for the sequential version Intel10_64lp_seq\")\n    endif()\n    find_package_blas()\n    if(BLAS_FOUND)\n      set(BLAS_SEQ_LIBRARIES \"${BLAS_LIBRARIES}\")\n    else()\n      set(BLAS_SEQ_LIBRARIES \"${BLAS_SEQ_LIBRARIES-NOTFOUND}\")\n    endif()\n\n    ## look for the multithreaded version\n    set(BLA_VENDOR \"Intel10_64lp\")\n    if(NOT BLASEXT_FIND_QUIETLY)\n      message(STATUS \"Look for the multithreaded version Intel10_64lp\")\n    endif()\n    find_package_blas()\n    if(BLAS_FOUND)\n      set(BLAS_PAR_LIBRARIES \"${BLAS_LIBRARIES}\")\n    else()\n      set(BLAS_PAR_LIBRARIES \"${BLAS_PAR_LIBRARIES-NOTFOUND}\")\n    endif()\n\n  else()\n\n    if(BLAS_FOUND)\n      set(BLAS_SEQ_LIBRARIES \"${BLAS_LIBRARIES}\")\n    else()\n      set(BLAS_SEQ_LIBRARIES \"${BLAS_SEQ_LIBRARIES-NOTFOUND}\")\n    endif()\n\n  endif()\n\n  # ACML case\nelseif(BLA_VENDOR MATCHES \"ACML*\")\n\n  ## look for the sequential version\n  set(BLA_VENDOR \"ACML\")\n  find_package_blas()\n  if(BLAS_FOUND)\n    set(BLAS_SEQ_LIBRARIES \"${BLAS_LIBRARIES}\")\n  else()\n    set(BLAS_SEQ_LIBRARIES \"${BLAS_SEQ_LIBRARIES-NOTFOUND}\")\n  endif()\n\n  ## look for the multithreaded version\n  set(BLA_VENDOR \"ACML_MP\")\n  find_package_blas()\n  if(BLAS_FOUND)\n    set(BLAS_PAR_LIBRARIES \"${BLAS_LIBRARIES}\")\n  else()\n    set(BLAS_PAR_LIBRARIES \"${BLAS_PAR_LIBRARIES-NOTFOUND}\")\n  endif()\n\n  # IBMESSL case\nelseif(BLA_VENDOR MATCHES \"IBMESSL*\")\n\n  ## look for the sequential version\n  set(BLA_VENDOR \"IBMESSL\")\n  find_package_blas()\n  if(BLAS_FOUND)\n    set(BLAS_SEQ_LIBRARIES \"${BLAS_LIBRARIES}\")\n  else()\n    set(BLAS_SEQ_LIBRARIES \"${BLAS_SEQ_LIBRARIES-NOTFOUND}\")\n  endif()\n\n  ## look for the multithreaded version\n  set(BLA_VENDOR \"IBMESSLMT\")\n  find_package_blas()\n  if(BLAS_FOUND)\n    set(BLAS_PAR_LIBRARIES \"${BLAS_LIBRARIES}\")\n  else()\n    set(BLAS_PAR_LIBRARIES \"${BLAS_PAR_LIBRARIES-NOTFOUND}\")\n  endif()\n\nelse()\n\n  if(BLAS_FOUND)\n    # define the SEQ libs as the BLAS_LIBRARIES\n    set(BLAS_SEQ_LIBRARIES \"${BLAS_LIBRARIES}\")\n  else()\n    set(BLAS_SEQ_LIBRARIES \"${BLAS_SEQ_LIBRARIES-NOTFOUND}\")\n  endif()\n  set(BLAS_PAR_LIBRARIES \"${BLAS_PAR_LIBRARIES-NOTFOUND}\")\n\nendif()\n\n\nif(BLAS_SEQ_LIBRARIES)\n  set(BLAS_LIBRARIES \"${BLAS_SEQ_LIBRARIES}\")\nendif()\n\n# extract libs paths\n# remark: because it is not given by find_package(BLAS)\nset(BLAS_LIBRARY_DIRS \"\")\nstring(REPLACE \" \" \";\" BLAS_LIBRARIES \"${BLAS_LIBRARIES}\")\nforeach(blas_lib ${BLAS_LIBRARIES})\n  if (EXISTS \"${blas_lib}\")\n    get_filename_component(a_blas_lib_dir \"${blas_lib}\" PATH)\n    list(APPEND BLAS_LIBRARY_DIRS \"${a_blas_lib_dir}\" )\n  else()\n    string(REPLACE \"-L\" \"\" blas_lib \"${blas_lib}\")\n    if (EXISTS \"${blas_lib}\")\n      list(APPEND BLAS_LIBRARY_DIRS \"${blas_lib}\" )\n    else()\n      get_filename_component(a_blas_lib_dir \"${blas_lib}\" PATH)\n      if (EXISTS \"${a_blas_lib_dir}\")\n\tlist(APPEND BLAS_LIBRARY_DIRS \"${a_blas_lib_dir}\" )\n      endif()\n    endif()\n  endif()\nendforeach()\nif (BLAS_LIBRARY_DIRS)\n  list(REMOVE_DUPLICATES BLAS_LIBRARY_DIRS)\nendif ()\n\n# check that BLAS has been found\n# ---------------------------------\ninclude(FindPackageHandleStandardArgs)\nif(BLA_VENDOR MATCHES \"Intel*\")\n  if(BLA_VENDOR MATCHES \"Intel10_64lp*\")\n    if(NOT BLASEXT_FIND_QUIETLY)\n      message(STATUS \"BLAS found is Intel MKL:\"\n\t\"\\n   we manage two lists of libs, one sequential and one parallel if found\"\n\t\"\\n   (see BLAS_SEQ_LIBRARIES and BLAS_PAR_LIBRARIES)\")\n      message(STATUS \"BLAS sequential libraries stored in BLAS_SEQ_LIBRARIES\")\n    endif()\n    find_package_handle_standard_args(BLAS DEFAULT_MSG\n      BLAS_SEQ_LIBRARIES\n      BLAS_LIBRARY_DIRS\n      BLAS_INCLUDE_DIRS)\n    if(BLAS_PAR_LIBRARIES)\n      if(NOT BLASEXT_FIND_QUIETLY)\n\tmessage(STATUS \"BLAS parallel libraries stored in BLAS_PAR_LIBRARIES\")\n      endif()\n      find_package_handle_standard_args(BLAS DEFAULT_MSG\n\tBLAS_PAR_LIBRARIES)\n    endif()\n  else()\n    if(NOT BLASEXT_FIND_QUIETLY)\n      message(STATUS \"BLAS sequential libraries stored in BLAS_SEQ_LIBRARIES\")\n    endif()\n    find_package_handle_standard_args(BLAS DEFAULT_MSG\n      BLAS_SEQ_LIBRARIES\n      BLAS_LIBRARY_DIRS\n      BLAS_INCLUDE_DIRS)\n  endif()\nelseif(BLA_VENDOR MATCHES \"ACML*\")\n  if(NOT BLASEXT_FIND_QUIETLY)\n    message(STATUS \"BLAS found is ACML:\"\n      \"\\n   we manage two lists of libs, one sequential and one parallel if found\"\n      \"\\n   (see BLAS_SEQ_LIBRARIES and BLAS_PAR_LIBRARIES)\")\n    message(STATUS \"BLAS sequential libraries stored in BLAS_SEQ_LIBRARIES\")\n  endif()\n  find_package_handle_standard_args(BLAS DEFAULT_MSG\n    BLAS_SEQ_LIBRARIES\n    BLAS_LIBRARY_DIRS)\n  if(BLAS_PAR_LIBRARIES)\n    if(NOT BLASEXT_FIND_QUIETLY)\n      message(STATUS \"BLAS parallel libraries stored in BLAS_PAR_LIBRARIES\")\n    endif()\n    find_package_handle_standard_args(BLAS DEFAULT_MSG\n      BLAS_PAR_LIBRARIES)\n  endif()\nelseif(BLA_VENDOR MATCHES \"IBMESSL*\")\n  if(NOT BLASEXT_FIND_QUIETLY)\n    message(STATUS \"BLAS found is ESSL:\"\n      \"\\n   we manage two lists of libs, one sequential and one parallel if found\"\n      \"\\n   (see BLAS_SEQ_LIBRARIES and BLAS_PAR_LIBRARIES)\")\n    message(STATUS \"BLAS sequential libraries stored in BLAS_SEQ_LIBRARIES\")\n  endif()\n  find_package_handle_standard_args(BLAS DEFAULT_MSG\n    BLAS_SEQ_LIBRARIES\n    BLAS_LIBRARY_DIRS)\n  if(BLAS_PAR_LIBRARIES)\n    if(NOT BLASEXT_FIND_QUIETLY)\n      message(STATUS \"BLAS parallel libraries stored in BLAS_PAR_LIBRARIES\")\n    endif()\n    find_package_handle_standard_args(BLAS DEFAULT_MSG\n      BLAS_PAR_LIBRARIES)\n  endif()\nelse()\n  if(NOT BLASEXT_FIND_QUIETLY)\n    message(STATUS \"BLAS sequential libraries stored in BLAS_SEQ_LIBRARIES\")\n  endif()\n  find_package_handle_standard_args(BLAS DEFAULT_MSG\n    BLAS_SEQ_LIBRARIES\n    BLAS_LIBRARY_DIRS)\nendif()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindCHOLMOD.cmake",
    "content": "# CHOLMOD lib usually requires linking to a blas and lapack library.\n# It is up to the user of this module to find a BLAS and link to it.\n\nif (CHOLMOD_INCLUDES AND CHOLMOD_LIBRARIES)\n  set(CHOLMOD_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(CHOLMOD_INCLUDES\n  NAMES\n  cholmod.h\n  PATHS\n  $ENV{CHOLMODDIR}\n  ${INCLUDE_INSTALL_DIR}\n  PATH_SUFFIXES\n  suitesparse\n  ufsparse\n)\n\nfind_library(CHOLMOD_LIBRARIES cholmod PATHS $ENV{CHOLMODDIR} ${LIB_INSTALL_DIR})\n\nif(CHOLMOD_LIBRARIES)\n\n  get_filename_component(CHOLMOD_LIBDIR ${CHOLMOD_LIBRARIES} PATH)\n\n  find_library(AMD_LIBRARY amd PATHS ${CHOLMOD_LIBDIR} $ENV{CHOLMODDIR} ${LIB_INSTALL_DIR})\n  if (AMD_LIBRARY)\n    set(CHOLMOD_LIBRARIES ${CHOLMOD_LIBRARIES} ${AMD_LIBRARY})\n  else ()\n    set(CHOLMOD_LIBRARIES FALSE)\n  endif ()\n\nendif()\n\nif(CHOLMOD_LIBRARIES)\n\n  find_library(COLAMD_LIBRARY colamd PATHS ${CHOLMOD_LIBDIR} $ENV{CHOLMODDIR} ${LIB_INSTALL_DIR})\n  if (COLAMD_LIBRARY)\n    set(CHOLMOD_LIBRARIES ${CHOLMOD_LIBRARIES} ${COLAMD_LIBRARY})\n  else ()\n    set(CHOLMOD_LIBRARIES FALSE)\n  endif ()\n\nendif()\n\nif(CHOLMOD_LIBRARIES)\n\n  find_library(CAMD_LIBRARY camd PATHS ${CHOLMOD_LIBDIR} $ENV{CHOLMODDIR} ${LIB_INSTALL_DIR})\n  if (CAMD_LIBRARY)\n    set(CHOLMOD_LIBRARIES ${CHOLMOD_LIBRARIES} ${CAMD_LIBRARY})\n  else ()\n    set(CHOLMOD_LIBRARIES FALSE)\n  endif ()\n\nendif()\n\nif(CHOLMOD_LIBRARIES)\n\n  find_library(CCOLAMD_LIBRARY ccolamd PATHS ${CHOLMOD_LIBDIR} $ENV{CHOLMODDIR} ${LIB_INSTALL_DIR})\n  if (CCOLAMD_LIBRARY)\n    set(CHOLMOD_LIBRARIES ${CHOLMOD_LIBRARIES} ${CCOLAMD_LIBRARY})\n  else ()\n    set(CHOLMOD_LIBRARIES FALSE)\n  endif ()\n\nendif()\n\nif(CHOLMOD_LIBRARIES)\n\n  find_library(CHOLMOD_METIS_LIBRARY metis PATHS ${CHOLMOD_LIBDIR} $ENV{CHOLMODDIR} ${LIB_INSTALL_DIR})\n  if (CHOLMOD_METIS_LIBRARY)\n    set(CHOLMOD_LIBRARIES ${CHOLMOD_LIBRARIES} ${CHOLMOD_METIS_LIBRARY})\n  endif ()\n\nendif()\n\nif(CHOLMOD_LIBRARIES)\n\n  find_library(SUITESPARSE_LIBRARY SuiteSparse PATHS ${CHOLMOD_LIBDIR} $ENV{CHOLMODDIR} ${LIB_INSTALL_DIR})\n  if (SUITESPARSE_LIBRARY)\n    set(CHOLMOD_LIBRARIES ${CHOLMOD_LIBRARIES} ${SUITESPARSE_LIBRARY})\n  endif ()\n  \nendif()\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(CHOLMOD DEFAULT_MSG\n                                  CHOLMOD_INCLUDES CHOLMOD_LIBRARIES)\n\nmark_as_advanced(CHOLMOD_INCLUDES CHOLMOD_LIBRARIES AMD_LIBRARY COLAMD_LIBRARY SUITESPARSE_LIBRARY CAMD_LIBRARY CCOLAMD_LIBRARY CHOLMOD_METIS_LIBRARY)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindComputeCpp.cmake",
    "content": "#.rst:\n# FindComputeCpp\n#---------------\n#\n#   Copyright 2016-2018 Codeplay Software Ltd.\n#\n#   Licensed under the Apache License, Version 2.0 (the \"License\");\n#   you may not use these files except in compliance with the License.\n#   You may obtain a copy of the License at\n#\n#       http://www.apache.org/licenses/LICENSE-2.0\n#\n#\n#   Unless required by applicable law or agreed to in writing, software\n#   distributed under the License is distributed on an \"AS IS\" BASIS,\n#   WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.\n#   See the License for the specific language governing permissions and\n#   limitations under the License.\n\n#########################\n#  FindComputeCpp.cmake\n#########################\n#\n#  Tools for finding and building with ComputeCpp.\n#\n#  User must define ComputeCpp_DIR pointing to the ComputeCpp\n#  installation.\n#\n#  Latest version of this file can be found at:\n#    https://github.com/codeplaysoftware/computecpp-sdk\n\ncmake_minimum_required(VERSION 3.4.3)\ninclude(FindPackageHandleStandardArgs)\ninclude(ComputeCppIRMap)\n\nset(COMPUTECPP_USER_FLAGS \"\" CACHE STRING \"User flags for compute++\")\nseparate_arguments(COMPUTECPP_USER_FLAGS)\nmark_as_advanced(COMPUTECPP_USER_FLAGS)\n\nset(COMPUTECPP_BITCODE \"spir64\" CACHE STRING\n  \"Bitcode type to use as SYCL target in compute++\")\nmark_as_advanced(COMPUTECPP_BITCODE)\n\nfind_package(OpenCL REQUIRED)\n\n# Find ComputeCpp package\n\nif(DEFINED ComputeCpp_DIR)\n  set(computecpp_find_hint ${ComputeCpp_DIR})\nelseif(DEFINED ENV{COMPUTECPP_DIR})\n  set(computecpp_find_hint $ENV{COMPUTECPP_DIR})\nendif()\n\n# Used for running executables on the host\nset(computecpp_host_find_hint ${computecpp_find_hint})\n\nif(CMAKE_CROSSCOMPILING)\n  # ComputeCpp_HOST_DIR is used to find executables that are run on the host\n  if(DEFINED ComputeCpp_HOST_DIR)\n    set(computecpp_host_find_hint ${ComputeCpp_HOST_DIR})\n  elseif(DEFINED ENV{COMPUTECPP_HOST_DIR})\n    set(computecpp_host_find_hint $ENV{COMPUTECPP_HOST_DIR})\n  endif()\nendif()\n\nfind_program(ComputeCpp_DEVICE_COMPILER_EXECUTABLE compute++\n  HINTS ${computecpp_host_find_hint}\n  PATH_SUFFIXES bin\n  NO_SYSTEM_ENVIRONMENT_PATH)\n\nfind_program(ComputeCpp_INFO_EXECUTABLE computecpp_info\n  HINTS ${computecpp_host_find_hint}\n  PATH_SUFFIXES bin\n  NO_SYSTEM_ENVIRONMENT_PATH)\n\nfind_library(COMPUTECPP_RUNTIME_LIBRARY\n  NAMES ComputeCpp ComputeCpp_vs2015\n  HINTS ${computecpp_find_hint}\n  PATH_SUFFIXES lib\n  DOC \"ComputeCpp Runtime Library\")\n\nfind_library(COMPUTECPP_RUNTIME_LIBRARY_DEBUG\n  NAMES ComputeCpp_d ComputeCpp ComputeCpp_vs2015_d\n  HINTS ${computecpp_find_hint}\n  PATH_SUFFIXES lib\n  DOC \"ComputeCpp Debug Runtime Library\")\n\nfind_path(ComputeCpp_INCLUDE_DIRS\n  NAMES \"CL/sycl.hpp\"\n  HINTS ${computecpp_find_hint}/include\n  DOC \"The ComputeCpp include directory\")\nget_filename_component(ComputeCpp_INCLUDE_DIRS ${ComputeCpp_INCLUDE_DIRS} ABSOLUTE)\n\nget_filename_component(computecpp_canonical_root_dir \"${ComputeCpp_INCLUDE_DIRS}/..\" ABSOLUTE)\nset(ComputeCpp_ROOT_DIR \"${computecpp_canonical_root_dir}\" CACHE PATH\n    \"The root of the ComputeCpp install\")\n\nif(NOT ComputeCpp_INFO_EXECUTABLE)\n  message(WARNING \"Can't find computecpp_info - check ComputeCpp_DIR\")\nelse()\n  execute_process(COMMAND ${ComputeCpp_INFO_EXECUTABLE} \"--dump-version\"\n    OUTPUT_VARIABLE ComputeCpp_VERSION\n    RESULT_VARIABLE ComputeCpp_INFO_EXECUTABLE_RESULT OUTPUT_STRIP_TRAILING_WHITESPACE)\n  if(NOT ComputeCpp_INFO_EXECUTABLE_RESULT EQUAL \"0\")\n    message(WARNING \"Package version - Error obtaining version!\")\n  endif()\n\n  execute_process(COMMAND ${ComputeCpp_INFO_EXECUTABLE} \"--dump-is-supported\"\n    OUTPUT_VARIABLE COMPUTECPP_PLATFORM_IS_SUPPORTED\n    RESULT_VARIABLE ComputeCpp_INFO_EXECUTABLE_RESULT OUTPUT_STRIP_TRAILING_WHITESPACE)\n  if(NOT ComputeCpp_INFO_EXECUTABLE_RESULT EQUAL \"0\")\n    message(WARNING \"platform - Error checking platform support!\")\n  else()\n    mark_as_advanced(COMPUTECPP_PLATFORM_IS_SUPPORTED)\n    if (COMPUTECPP_PLATFORM_IS_SUPPORTED)\n      message(STATUS \"platform - your system can support ComputeCpp\")\n    else()\n      message(STATUS \"platform - your system is not officially supported\")\n    endif()\n  endif()\nendif()\n\nfind_package_handle_standard_args(ComputeCpp\n  REQUIRED_VARS ComputeCpp_ROOT_DIR\n                ComputeCpp_DEVICE_COMPILER_EXECUTABLE\n                ComputeCpp_INFO_EXECUTABLE\n                COMPUTECPP_RUNTIME_LIBRARY\n                COMPUTECPP_RUNTIME_LIBRARY_DEBUG\n                ComputeCpp_INCLUDE_DIRS\n  VERSION_VAR ComputeCpp_VERSION)\nmark_as_advanced(ComputeCpp_ROOT_DIR\n                 ComputeCpp_DEVICE_COMPILER_EXECUTABLE\n                 ComputeCpp_INFO_EXECUTABLE\n                 COMPUTECPP_RUNTIME_LIBRARY\n                 COMPUTECPP_RUNTIME_LIBRARY_DEBUG\n                 ComputeCpp_INCLUDE_DIRS\n                 ComputeCpp_VERSION)\n\nif(NOT ComputeCpp_FOUND)\n  return()\nendif()\n\nlist(APPEND COMPUTECPP_DEVICE_COMPILER_FLAGS -O2 -mllvm -inline-threshold=1000 -intelspirmetadata)\nmark_as_advanced(COMPUTECPP_DEVICE_COMPILER_FLAGS)\n\nif(CMAKE_CROSSCOMPILING)\n  if(NOT COMPUTECPP_DONT_USE_TOOLCHAIN)\n    list(APPEND COMPUTECPP_DEVICE_COMPILER_FLAGS --gcc-toolchain=${COMPUTECPP_TOOLCHAIN_DIR})\n  endif()\n  list(APPEND COMPUTECPP_DEVICE_COMPILER_FLAGS --sysroot=${COMPUTECPP_SYSROOT_DIR})\n  list(APPEND COMPUTECPP_DEVICE_COMPILER_FLAGS -target ${COMPUTECPP_TARGET_TRIPLE})\nendif()\n\nlist(APPEND COMPUTECPP_DEVICE_COMPILER_FLAGS -sycl-target ${COMPUTECPP_BITCODE})\nmessage(STATUS \"compute++ flags - ${COMPUTECPP_DEVICE_COMPILER_FLAGS}\")\n\ninclude(ComputeCppCompilerChecks)\n\nif(NOT TARGET OpenCL::OpenCL)\n  add_library(OpenCL::OpenCL UNKNOWN IMPORTED)\n  set_target_properties(OpenCL::OpenCL PROPERTIES\n    IMPORTED_LOCATION             \"${OpenCL_LIBRARIES}\"\n    INTERFACE_INCLUDE_DIRECTORIES \"${OpenCL_INCLUDE_DIRS}\"\n  )\nendif()\n\nif(NOT TARGET ComputeCpp::ComputeCpp)\n  add_library(ComputeCpp::ComputeCpp UNKNOWN IMPORTED)\n  set_target_properties(ComputeCpp::ComputeCpp PROPERTIES\n    IMPORTED_LOCATION_DEBUG          \"${COMPUTECPP_RUNTIME_LIBRARY_DEBUG}\"\n    IMPORTED_LOCATION_RELWITHDEBINFO \"${COMPUTECPP_RUNTIME_LIBRARY}\"\n    IMPORTED_LOCATION                \"${COMPUTECPP_RUNTIME_LIBRARY}\"\n    INTERFACE_INCLUDE_DIRECTORIES    \"${ComputeCpp_INCLUDE_DIRS}\"\n    INTERFACE_LINK_LIBRARIES         \"OpenCL::OpenCL\"\n  )\nendif()\n\n# This property allows targets to specify that their sources should be\n# compiled with the integration header included after the user's\n# sources, not before (e.g. when an enum is used in a kernel name, this\n# is not technically valid SYCL code but can work with ComputeCpp)\ndefine_property(\n  TARGET PROPERTY COMPUTECPP_INCLUDE_AFTER\n  BRIEF_DOCS \"Include integration header after user source\"\n  FULL_DOCS \"Changes compiler arguments such that the source file is\n  actually the integration header, and the .cpp file is included on\n  the command line so that it is seen by the compiler first. Enables\n  non-standards-conformant SYCL code to compile with ComputeCpp.\"\n)\ndefine_property(\n  TARGET PROPERTY INTERFACE_COMPUTECPP_FLAGS\n  BRIEF_DOCS \"Interface compile flags to provide compute++\"\n  FULL_DOCS  \"Set additional compile flags to pass to compute++ when compiling\n  any target which links to this one.\"\n)\ndefine_property(\n  SOURCE PROPERTY COMPUTECPP_SOURCE_FLAGS\n  BRIEF_DOCS \"Source file compile flags for compute++\"\n  FULL_DOCS  \"Set additional compile flags for compiling the SYCL integration\n  header for the given source file.\"\n)\n\n####################\n#   __build_ir\n####################\n#\n#  Adds a custom target for running compute++ and adding a dependency for the\n#  resulting integration header and kernel binary.\n#\n#  TARGET : Name of the target.\n#  SOURCE : Source file to be compiled.\n#  COUNTER : Counter included in name of custom target. Different counter\n#       values prevent duplicated names of custom target when source files with\n#       the same name, but located in different directories, are used for the\n#       same target.\n#\nfunction(__build_ir)\n  set(options)\n  set(one_value_args\n    TARGET\n    SOURCE\n    COUNTER\n  )\n  set(multi_value_args)\n  cmake_parse_arguments(SDK_BUILD_IR\n    \"${options}\"\n    \"${one_value_args}\"\n    \"${multi_value_args}\"\n    ${ARGN}\n  )\n  get_filename_component(sourceFileName ${SDK_BUILD_IR_SOURCE} NAME)\n\n  # Set the path to the integration header.\n  # The .sycl filename must depend on the target so that different targets\n  # using the same source file will be generated with a different rule.\n  set(baseSyclName ${CMAKE_CURRENT_BINARY_DIR}/${SDK_BUILD_IR_TARGET}_${sourceFileName})\n  set(outputSyclFile ${baseSyclName}.sycl)\n  set(outputDeviceFile ${baseSyclName}.${IR_MAP_${COMPUTECPP_BITCODE}})\n  set(depFileName ${baseSyclName}.sycl.d)\n\n  set(include_directories \"$<TARGET_PROPERTY:${SDK_BUILD_IR_TARGET},INCLUDE_DIRECTORIES>\")\n  set(compile_definitions \"$<TARGET_PROPERTY:${SDK_BUILD_IR_TARGET},COMPILE_DEFINITIONS>\")\n  set(generated_include_directories\n    $<$<BOOL:${include_directories}>:-I\\\"$<JOIN:${include_directories},\\\"\\t-I\\\">\\\">)\n  set(generated_compile_definitions\n    $<$<BOOL:${compile_definitions}>:-D$<JOIN:${compile_definitions},\\t-D>>)\n\n  # Obtain language standard of the file\n  set(device_compiler_cxx_standard)\n  get_target_property(targetCxxStandard ${SDK_BUILD_IR_TARGET} CXX_STANDARD)\n  if (targetCxxStandard MATCHES 17)\n    set(device_compiler_cxx_standard \"-std=c++1z\")\n  elseif (targetCxxStandard MATCHES 14)\n    set(device_compiler_cxx_standard \"-std=c++14\")\n  elseif (targetCxxStandard MATCHES 11)\n    set(device_compiler_cxx_standard \"-std=c++11\")\n  elseif (targetCxxStandard MATCHES 98)\n    message(FATAL_ERROR \"SYCL applications cannot be compiled using C++98\")\n  else ()\n    set(device_compiler_cxx_standard \"\")\n  endif()\n\n  get_property(source_compile_flags\n    SOURCE ${SDK_BUILD_IR_SOURCE}\n    PROPERTY COMPUTECPP_SOURCE_FLAGS\n  )\n  separate_arguments(source_compile_flags)\n  if(source_compile_flags)\n    list(APPEND computecpp_source_flags ${source_compile_flags})\n  endif()\n\n  list(APPEND COMPUTECPP_DEVICE_COMPILER_FLAGS\n    ${device_compiler_cxx_standard}\n    ${COMPUTECPP_USER_FLAGS}\n    ${computecpp_source_flags}\n  )\n\n  set(ir_dependencies ${SDK_BUILD_IR_SOURCE})\n  get_target_property(target_libraries ${SDK_BUILD_IR_TARGET} LINK_LIBRARIES)\n  if(target_libraries)\n    foreach(library ${target_libraries})\n      if(TARGET ${library})\n        list(APPEND ir_dependencies ${library})\n      endif()\n    endforeach()\n  endif()\n\n  # Depfile support was only added in CMake 3.7\n  # CMake throws an error if it is unsupported by the generator (i. e. not ninja)\n  if((NOT CMAKE_VERSION VERSION_LESS 3.7.0) AND\n          CMAKE_GENERATOR MATCHES \"Ninja\")\n    file(RELATIVE_PATH relOutputFile ${CMAKE_BINARY_DIR} ${outputDeviceFile})\n    set(generate_depfile -MMD -MF ${depFileName} -MT ${relOutputFile})\n    set(enable_depfile DEPFILE ${depFileName})\n  endif()\n\n  # Add custom command for running compute++\n  add_custom_command(\n    OUTPUT ${outputDeviceFile} ${outputSyclFile}\n    COMMAND ${ComputeCpp_DEVICE_COMPILER_EXECUTABLE}\n            ${COMPUTECPP_DEVICE_COMPILER_FLAGS}\n            ${generated_include_directories}\n            ${generated_compile_definitions}\n            -sycl-ih ${outputSyclFile}\n            -o ${outputDeviceFile}\n            -c ${SDK_BUILD_IR_SOURCE}\n            ${generate_depfile}\n    DEPENDS ${ir_dependencies}\n    IMPLICIT_DEPENDS CXX ${SDK_BUILD_IR_SOURCE}\n    ${enable_depfile}\n    WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}\n    COMMENT \"Building ComputeCpp integration header file ${outputSyclFile}\")\n\n  # Name: (user-defined name)_(source file)_(counter)_ih\n  set(headerTargetName\n    ${SDK_BUILD_IR_TARGET}_${sourceFileName}_${SDK_BUILD_IR_COUNTER}_ih)\n\n  if(NOT MSVC)\n    # Add a custom target for the generated integration header\n    add_custom_target(${headerTargetName} DEPENDS ${outputDeviceFile} ${outputSyclFile})\n    add_dependencies(${SDK_BUILD_IR_TARGET} ${headerTargetName})\n  endif()\n\n  # This property can be set on a per-target basis to indicate that the\n  # integration header should appear after the main source listing\n  get_target_property(includeAfter ${SDK_ADD_SYCL_TARGET} COMPUTECPP_INCLUDE_AFTER)\n\n  if(includeAfter)\n    # Change the source file to the integration header - e.g.\n    # g++ -c source_file_name.cpp.sycl\n    get_target_property(current_sources ${SDK_BUILD_IR_TARGET} SOURCES)\n    # Remove absolute path to source file\n    list(REMOVE_ITEM current_sources ${SDK_BUILD_IR_SOURCE})\n    # Remove relative path to source file\n    string(REPLACE \"${CMAKE_CURRENT_SOURCE_DIR}/\" \"\"\n      rel_source_file ${SDK_BUILD_IR_SOURCE}\n    )\n    list(REMOVE_ITEM current_sources ${rel_source_file})\n    # Add SYCL header to source list\n    list(APPEND current_sources ${outputSyclFile})\n    set_property(TARGET ${SDK_BUILD_IR_TARGET}\n      PROPERTY SOURCES ${current_sources})\n    # CMake/gcc don't know what language a .sycl file is, so tell them\n    set_property(SOURCE ${outputSyclFile} PROPERTY LANGUAGE CXX)\n    set(includedFile ${SDK_BUILD_IR_SOURCE})\n    set(cppFile ${outputSyclFile})\n  else()\n    set_property(SOURCE ${outputSyclFile} PROPERTY HEADER_FILE_ONLY ON)\n    set(includedFile ${outputSyclFile})\n    set(cppFile ${SDK_BUILD_IR_SOURCE})\n  endif()\n\n  # Force inclusion of the integration header for the host compiler\n  if(MSVC)\n    # Group SYCL files inside Visual Studio\n    source_group(\"SYCL\" FILES ${outputSyclFile})\n\n    if(includeAfter)\n      # Allow the source file to be edited using Visual Studio.\n      # It will be added as a header file so it won't be compiled.\n      set_property(SOURCE ${SDK_BUILD_IR_SOURCE} PROPERTY HEADER_FILE_ONLY true)\n    endif()\n\n    # Add both source and the sycl files to the VS solution.\n    target_sources(${SDK_BUILD_IR_TARGET} PUBLIC ${SDK_BUILD_IR_SOURCE} ${outputSyclFile})\n\n    set(forceIncludeFlags \"/FI${includedFile} /TP\")\n  else()\n    set(forceIncludeFlags \"-include ${includedFile} -x c++\")\n  endif()\n\n  set_property(\n    SOURCE ${cppFile}\n    APPEND_STRING PROPERTY COMPILE_FLAGS \"${forceIncludeFlags}\"\n  )\n\nendfunction(__build_ir)\n\n#######################\n#  add_sycl_to_target\n#######################\n#\n#  Adds a SYCL compilation custom command associated with an existing\n#  target and sets a dependancy on that new command.\n#\n#  TARGET : Name of the target to add SYCL to.\n#  SOURCES : Source files to be compiled for SYCL.\n#\nfunction(add_sycl_to_target)\n  set(options)\n  set(one_value_args\n    TARGET\n  )\n  set(multi_value_args\n    SOURCES\n  )\n  cmake_parse_arguments(SDK_ADD_SYCL\n    \"${options}\"\n    \"${one_value_args}\"\n    \"${multi_value_args}\"\n    ${ARGN}\n  )\n\n  set_target_properties(${SDK_ADD_SYCL_TARGET} PROPERTIES LINKER_LANGUAGE CXX)\n\n  # If the CXX compiler is set to compute++ enable the driver.\n  get_filename_component(cmakeCxxCompilerFileName \"${CMAKE_CXX_COMPILER}\" NAME)\n  if(\"${cmakeCxxCompilerFileName}\" STREQUAL \"compute++\")\n    if(MSVC)\n      message(FATAL_ERROR \"The compiler driver is not supported by this system,\n                           revert the CXX compiler to your default host compiler.\")\n    endif()\n\n    get_target_property(includeAfter ${SDK_ADD_SYCL_TARGET} COMPUTECPP_INCLUDE_AFTER)\n    if(includeAfter)\n      list(APPEND COMPUTECPP_USER_FLAGS -fsycl-ih-last)\n    endif()\n    list(INSERT COMPUTECPP_DEVICE_COMPILER_FLAGS 0 -sycl-driver)\n    # Prepend COMPUTECPP_DEVICE_COMPILER_FLAGS and append COMPUTECPP_USER_FLAGS\n    foreach(prop COMPILE_OPTIONS INTERFACE_COMPILE_OPTIONS)\n      get_target_property(target_compile_options ${SDK_ADD_SYCL_TARGET} ${prop})\n      if(NOT target_compile_options)\n        set(target_compile_options \"\")\n      endif()\n      set_property(\n        TARGET ${SDK_ADD_SYCL_TARGET}\n        PROPERTY ${prop}\n        ${COMPUTECPP_DEVICE_COMPILER_FLAGS}\n        ${target_compile_options}\n        ${COMPUTECPP_USER_FLAGS}\n      )\n    endforeach()\n  else()\n    set(fileCounter 0)\n    list(INSERT COMPUTECPP_DEVICE_COMPILER_FLAGS 0 -sycl)\n    # Add custom target to run compute++ and generate the integration header\n    foreach(sourceFile ${SDK_ADD_SYCL_SOURCES})\n      if(NOT IS_ABSOLUTE ${sourceFile})\n        set(sourceFile \"${CMAKE_CURRENT_SOURCE_DIR}/${sourceFile}\")\n      endif()\n      __build_ir(\n        TARGET     ${SDK_ADD_SYCL_TARGET}\n        SOURCE     ${sourceFile}\n        COUNTER    ${fileCounter}\n      )\n      MATH(EXPR fileCounter \"${fileCounter} + 1\")\n    endforeach()\n  endif()\n\n  set_property(TARGET ${SDK_ADD_SYCL_TARGET}\n    APPEND PROPERTY LINK_LIBRARIES ComputeCpp::ComputeCpp)\n  set_property(TARGET ${SDK_ADD_SYCL_TARGET}\n    APPEND PROPERTY INTERFACE_LINK_LIBRARIES ComputeCpp::ComputeCpp)\nendfunction(add_sycl_to_target)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindEigen2.cmake",
    "content": "# - Try to find Eigen2 lib\n#\n# This module supports requiring a minimum version, e.g. you can do\n#   find_package(Eigen2 2.0.3)\n# to require version 2.0.3 to newer of Eigen2.\n#\n# Once done this will define\n#\n#  EIGEN2_FOUND - system has eigen lib with correct version\n#  EIGEN2_INCLUDE_DIR - the eigen include directory\n#  EIGEN2_VERSION - eigen version\n\n# Copyright (c) 2006, 2007 Montel Laurent, <montel@kde.org>\n# Copyright (c) 2008, 2009 Gael Guennebaud, <g.gael@free.fr>\n# Redistribution and use is allowed according to the terms of the BSD license.\n\nif(NOT Eigen2_FIND_VERSION)\n  if(NOT Eigen2_FIND_VERSION_MAJOR)\n    set(Eigen2_FIND_VERSION_MAJOR 2)\n  endif()\n  if(NOT Eigen2_FIND_VERSION_MINOR)\n    set(Eigen2_FIND_VERSION_MINOR 0)\n  endif()\n  if(NOT Eigen2_FIND_VERSION_PATCH)\n    set(Eigen2_FIND_VERSION_PATCH 0)\n  endif()\n\n  set(Eigen2_FIND_VERSION \"${Eigen2_FIND_VERSION_MAJOR}.${Eigen2_FIND_VERSION_MINOR}.${Eigen2_FIND_VERSION_PATCH}\")\nendif()\n\nmacro(_eigen2_check_version)\n  file(READ \"${EIGEN2_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h\" _eigen2_version_header)\n\n  string(REGEX MATCH \"define[ \\t]+EIGEN_WORLD_VERSION[ \\t]+([0-9]+)\" _eigen2_world_version_match \"${_eigen2_version_header}\")\n  set(EIGEN2_WORLD_VERSION \"${CMAKE_MATCH_1}\")\n  string(REGEX MATCH \"define[ \\t]+EIGEN_MAJOR_VERSION[ \\t]+([0-9]+)\" _eigen2_major_version_match \"${_eigen2_version_header}\")\n  set(EIGEN2_MAJOR_VERSION \"${CMAKE_MATCH_1}\")\n  string(REGEX MATCH \"define[ \\t]+EIGEN_MINOR_VERSION[ \\t]+([0-9]+)\" _eigen2_minor_version_match \"${_eigen2_version_header}\")\n  set(EIGEN2_MINOR_VERSION \"${CMAKE_MATCH_1}\")\n\n  set(EIGEN2_VERSION ${EIGEN2_WORLD_VERSION}.${EIGEN2_MAJOR_VERSION}.${EIGEN2_MINOR_VERSION})\n  if((${EIGEN2_WORLD_VERSION} NOTEQUAL 2) OR (${EIGEN2_MAJOR_VERSION} GREATER 10) OR (${EIGEN2_VERSION} VERSION_LESS ${Eigen2_FIND_VERSION}))\n    set(EIGEN2_VERSION_OK FALSE)\n  else()\n    set(EIGEN2_VERSION_OK TRUE)\n  endif()\n\n  if(NOT EIGEN2_VERSION_OK)\n\n    message(STATUS \"Eigen2 version ${EIGEN2_VERSION} found in ${EIGEN2_INCLUDE_DIR}, \"\n                   \"but at least version ${Eigen2_FIND_VERSION} is required\")\n  endif()\nendmacro()\n\nif (EIGEN2_INCLUDE_DIR)\n\n  # in cache already\n  _eigen2_check_version()\n  set(EIGEN2_FOUND ${EIGEN2_VERSION_OK})\n\nelse ()\n\nfind_path(EIGEN2_INCLUDE_DIR NAMES Eigen/Core\n     PATHS\n     ${INCLUDE_INSTALL_DIR}\n     ${KDE4_INCLUDE_DIR}\n     PATH_SUFFIXES eigen2\n   )\n\nif(EIGEN2_INCLUDE_DIR)\n  _eigen2_check_version()\nendif()\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(Eigen2 DEFAULT_MSG EIGEN2_INCLUDE_DIR EIGEN2_VERSION_OK)\n\nmark_as_advanced(EIGEN2_INCLUDE_DIR)\n\nendif()\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindEigen3.cmake",
    "content": "# - Try to find Eigen3 lib\n#\n# This module supports requiring a minimum version, e.g. you can do\n#   find_package(Eigen3 3.1.2)\n# to require version 3.1.2 or newer of Eigen3.\n#\n# Once done this will define\n#\n#  EIGEN3_FOUND - system has eigen lib with correct version\n#  EIGEN3_INCLUDE_DIR - the eigen include directory\n#  EIGEN3_VERSION - eigen version\n#\n# and the following imported target:\n#\n#  Eigen3::Eigen - The header-only Eigen library\n#\n# This module reads hints about search locations from \n# the following environment variables:\n#\n# EIGEN3_ROOT\n# EIGEN3_ROOT_DIR\n\n# Copyright (c) 2006, 2007 Montel Laurent, <montel@kde.org>\n# Copyright (c) 2008, 2009 Gael Guennebaud, <g.gael@free.fr>\n# Copyright (c) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n# Redistribution and use is allowed according to the terms of the 2-clause BSD license.\n\nif(NOT Eigen3_FIND_VERSION)\n  if(NOT Eigen3_FIND_VERSION_MAJOR)\n    set(Eigen3_FIND_VERSION_MAJOR 2)\n  endif()\n  if(NOT Eigen3_FIND_VERSION_MINOR)\n    set(Eigen3_FIND_VERSION_MINOR 91)\n  endif()\n  if(NOT Eigen3_FIND_VERSION_PATCH)\n    set(Eigen3_FIND_VERSION_PATCH 0)\n  endif()\n\n  set(Eigen3_FIND_VERSION \"${Eigen3_FIND_VERSION_MAJOR}.${Eigen3_FIND_VERSION_MINOR}.${Eigen3_FIND_VERSION_PATCH}\")\nendif()\n\nmacro(_eigen3_check_version)\n  file(READ \"${EIGEN3_INCLUDE_DIR}/Eigen/src/Core/util/Macros.h\" _eigen3_version_header)\n\n  string(REGEX MATCH \"define[ \\t]+EIGEN_WORLD_VERSION[ \\t]+([0-9]+)\" _eigen3_world_version_match \"${_eigen3_version_header}\")\n  set(EIGEN3_WORLD_VERSION \"${CMAKE_MATCH_1}\")\n  string(REGEX MATCH \"define[ \\t]+EIGEN_MAJOR_VERSION[ \\t]+([0-9]+)\" _eigen3_major_version_match \"${_eigen3_version_header}\")\n  set(EIGEN3_MAJOR_VERSION \"${CMAKE_MATCH_1}\")\n  string(REGEX MATCH \"define[ \\t]+EIGEN_MINOR_VERSION[ \\t]+([0-9]+)\" _eigen3_minor_version_match \"${_eigen3_version_header}\")\n  set(EIGEN3_MINOR_VERSION \"${CMAKE_MATCH_1}\")\n\n  set(EIGEN3_VERSION ${EIGEN3_WORLD_VERSION}.${EIGEN3_MAJOR_VERSION}.${EIGEN3_MINOR_VERSION})\n  if(${EIGEN3_VERSION} VERSION_LESS ${Eigen3_FIND_VERSION})\n    set(EIGEN3_VERSION_OK FALSE)\n  else()\n    set(EIGEN3_VERSION_OK TRUE)\n  endif()\n\n  if(NOT EIGEN3_VERSION_OK)\n\n    message(STATUS \"Eigen3 version ${EIGEN3_VERSION} found in ${EIGEN3_INCLUDE_DIR}, \"\n                   \"but at least version ${Eigen3_FIND_VERSION} is required\")\n  endif()\nendmacro()\n\nif (EIGEN3_INCLUDE_DIR)\n\n  # in cache already\n  _eigen3_check_version()\n  set(EIGEN3_FOUND ${EIGEN3_VERSION_OK})\n  set(Eigen3_FOUND ${EIGEN3_VERSION_OK})\n\nelse ()\n  \n  # search first if an Eigen3Config.cmake is available in the system,\n  # if successful this would set EIGEN3_INCLUDE_DIR and the rest of\n  # the script will work as usual\n  find_package(Eigen3 ${Eigen3_FIND_VERSION} NO_MODULE QUIET)\n\n  if(NOT EIGEN3_INCLUDE_DIR)\n    find_path(EIGEN3_INCLUDE_DIR NAMES signature_of_eigen3_matrix_library\n        HINTS\n        ENV EIGEN3_ROOT \n        ENV EIGEN3_ROOT_DIR\n        PATHS\n        ${CMAKE_INSTALL_PREFIX}/include\n        ${KDE4_INCLUDE_DIR}\n        PATH_SUFFIXES eigen3 eigen\n      )\n  endif()\n\n  if(EIGEN3_INCLUDE_DIR)\n    _eigen3_check_version()\n  endif()\n\n  include(FindPackageHandleStandardArgs)\n  find_package_handle_standard_args(Eigen3 DEFAULT_MSG EIGEN3_INCLUDE_DIR EIGEN3_VERSION_OK)\n\n  mark_as_advanced(EIGEN3_INCLUDE_DIR)\n\nendif()\n\nif(EIGEN3_FOUND AND NOT TARGET Eigen3::Eigen)\n  add_library(Eigen3::Eigen INTERFACE IMPORTED)\n  set_target_properties(Eigen3::Eigen PROPERTIES\n    INTERFACE_INCLUDE_DIRECTORIES \"${EIGEN3_INCLUDE_DIR}\")\nendif()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindFFTW.cmake",
    "content": "# - Find the FFTW library\n#\n# Usage:\n#   find_package(FFTW [REQUIRED] [QUIET] )\n#     \n# It sets the following variables:\n#   FFTW_FOUND               ... true if fftw is found on the system\n#   FFTW_LIBRARIES           ... full path to fftw library\n#   FFTW_INCLUDES            ... fftw include directory\n#\n# The following variables will be checked by the function\n#   FFTW_USE_STATIC_LIBS    ... if true, only static libraries are found\n#   FFTW_ROOT               ... if set, the libraries are exclusively searched\n#                               under this path\n#   FFTW_LIBRARY            ... fftw library to use\n#   FFTW_INCLUDE_DIR        ... fftw include directory\n#\n\n#If environment variable FFTWDIR is specified, it has same effect as FFTW_ROOT\nif( NOT FFTW_ROOT AND ENV{FFTWDIR} )\n  set( FFTW_ROOT $ENV{FFTWDIR} )\nendif()\n\n# Check if we can use PkgConfig\nfind_package(PkgConfig)\n\n#Determine from PKG\nif( PKG_CONFIG_FOUND AND NOT FFTW_ROOT )\n  pkg_check_modules( PKG_FFTW QUIET \"fftw3\" )\nendif()\n\n#Check whether to search static or dynamic libs\nset( CMAKE_FIND_LIBRARY_SUFFIXES_SAV ${CMAKE_FIND_LIBRARY_SUFFIXES} )\n\nif( ${FFTW_USE_STATIC_LIBS} )\n  set( CMAKE_FIND_LIBRARY_SUFFIXES ${CMAKE_STATIC_LIBRARY_SUFFIX} )\nelse()\n  set( CMAKE_FIND_LIBRARY_SUFFIXES ${CMAKE_SHARED_LIBRARY_SUFFIX} )\nendif()\n\nif( FFTW_ROOT )\n\n  #find libs\n  find_library(\n    FFTW_LIB\n    NAMES \"fftw3\"\n    PATHS ${FFTW_ROOT}\n    PATH_SUFFIXES \"lib\" \"lib64\"\n    NO_DEFAULT_PATH\n  )\n\n  find_library(\n    FFTWF_LIB\n    NAMES \"fftw3f\"\n    PATHS ${FFTW_ROOT}\n    PATH_SUFFIXES \"lib\" \"lib64\"\n    NO_DEFAULT_PATH\n  )\n\n  find_library(\n    FFTWL_LIB\n    NAMES \"fftw3l\"\n    PATHS ${FFTW_ROOT}\n    PATH_SUFFIXES \"lib\" \"lib64\"\n    NO_DEFAULT_PATH\n  )\n\n  #find includes\n  find_path(\n    FFTW_INCLUDES\n    NAMES \"fftw3.h\"\n    PATHS ${FFTW_ROOT}\n    PATH_SUFFIXES \"include\"\n    NO_DEFAULT_PATH\n  )\n\nelse()\n\n  find_library(\n    FFTW_LIB\n    NAMES \"fftw3\"\n    PATHS ${PKG_FFTW_LIBRARY_DIRS} ${LIB_INSTALL_DIR}\n  )\n\n  find_library(\n    FFTWF_LIB\n    NAMES \"fftw3f\"\n    PATHS ${PKG_FFTW_LIBRARY_DIRS} ${LIB_INSTALL_DIR}\n  )\n\n\n  find_library(\n    FFTWL_LIB\n    NAMES \"fftw3l\"\n    PATHS ${PKG_FFTW_LIBRARY_DIRS} ${LIB_INSTALL_DIR}\n  )\n\n  find_path(\n    FFTW_INCLUDES\n    NAMES \"fftw3.h\"\n    PATHS ${PKG_FFTW_INCLUDE_DIRS} ${INCLUDE_INSTALL_DIR}\n  )\n\nendif()\n\nset(FFTW_LIBRARIES ${FFTW_LIB} ${FFTWF_LIB})\n\nif(FFTWL_LIB)\n  set(FFTW_LIBRARIES ${FFTW_LIBRARIES} ${FFTWL_LIB})\nendif()\n\nset( CMAKE_FIND_LIBRARY_SUFFIXES ${CMAKE_FIND_LIBRARY_SUFFIXES_SAV} )\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(FFTW DEFAULT_MSG\n                                  FFTW_INCLUDES FFTW_LIBRARIES)\n\nmark_as_advanced(FFTW_INCLUDES FFTW_LIBRARIES FFTW_LIB FFTWF_LIB FFTWL_LIB)\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindGLEW.cmake",
    "content": "# Copyright (c) 2009 Boudewijn Rempt <boud@valdyas.org>                                                                                          \n#                                                                                                                                                \n# Redistribution and use is allowed according to the terms of the BSD license.                                                                   \n# For details see the accompanying COPYING-CMAKE-SCRIPTS file. \n# \n# - try to find glew library and include files\n#  GLEW_INCLUDE_DIR, where to find GL/glew.h, etc.\n#  GLEW_LIBRARIES, the libraries to link against\n#  GLEW_FOUND, If false, do not try to use GLEW.\n# Also defined, but not for general use are:\n#  GLEW_GLEW_LIBRARY = the full path to the glew library.\n\nif (WIN32)\n\n  if(CYGWIN)\n\n    find_path( GLEW_INCLUDE_DIR GL/glew.h)\n\n    find_library( GLEW_GLEW_LIBRARY glew32\n      ${OPENGL_LIBRARY_DIR}\n      /usr/lib/w32api\n      /usr/X11R6/lib\n    )\n\n\n  else(CYGWIN)\n  \n    find_path( GLEW_INCLUDE_DIR GL/glew.h\n      $ENV{GLEW_ROOT_PATH}/include\n    )\n\n    find_library( GLEW_GLEW_LIBRARY\n      NAMES glew glew32\n      PATHS\n      $ENV{GLEW_ROOT_PATH}/lib\n      ${OPENGL_LIBRARY_DIR}\n    )\n\n  endif(CYGWIN)\n\nelse (WIN32)\n\n  if (APPLE)\n# These values for Apple could probably do with improvement.\n    find_path( GLEW_INCLUDE_DIR glew.h\n      /System/Library/Frameworks/GLEW.framework/Versions/A/Headers\n      ${OPENGL_LIBRARY_DIR}\n    )\n    set(GLEW_GLEW_LIBRARY \"-framework GLEW\" CACHE STRING \"GLEW library for OSX\")\n    set(GLEW_cocoa_LIBRARY \"-framework Cocoa\" CACHE STRING \"Cocoa framework for OSX\")\n  else (APPLE)\n\n    find_path( GLEW_INCLUDE_DIR GL/glew.h\n      /usr/include/GL\n      /usr/openwin/share/include\n      /usr/openwin/include\n      /usr/X11R6/include\n      /usr/include/X11\n      /opt/graphics/OpenGL/include\n      /opt/graphics/OpenGL/contrib/libglew\n    )\n\n    find_library( GLEW_GLEW_LIBRARY GLEW\n      /usr/openwin/lib\n      /usr/X11R6/lib\n    )\n\n  endif (APPLE)\n\nendif (WIN32)\n\nset( GLEW_FOUND \"NO\" )\nif(GLEW_INCLUDE_DIR)\n  if(GLEW_GLEW_LIBRARY)\n    # Is -lXi and -lXmu required on all platforms that have it?\n    # If not, we need some way to figure out what platform we are on.\n    set( GLEW_LIBRARIES\n      ${GLEW_GLEW_LIBRARY}\n      ${GLEW_cocoa_LIBRARY}\n    )\n    set( GLEW_FOUND \"YES\" )\n\n#The following deprecated settings are for backwards compatibility with CMake1.4\n    set (GLEW_LIBRARY ${GLEW_LIBRARIES})\n    set (GLEW_INCLUDE_PATH ${GLEW_INCLUDE_DIR})\n\n  endif(GLEW_GLEW_LIBRARY)\nendif(GLEW_INCLUDE_DIR)\n\nif(GLEW_FOUND)\n  if(NOT GLEW_FIND_QUIETLY)\n    message(STATUS \"Found Glew: ${GLEW_LIBRARIES}\")\n  endif(NOT GLEW_FIND_QUIETLY)\nelse(GLEW_FOUND)\n  if(GLEW_FIND_REQUIRED)\n    message(FATAL_ERROR \"Could not find Glew\")\n  endif(GLEW_FIND_REQUIRED)\nendif(GLEW_FOUND)\n\nmark_as_advanced(\n  GLEW_INCLUDE_DIR\n  GLEW_GLEW_LIBRARY\n  GLEW_Xmu_LIBRARY\n  GLEW_Xi_LIBRARY\n)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindGMP.cmake",
    "content": "# Try to find the GNU Multiple Precision Arithmetic Library (GMP)\n# See http://gmplib.org/\n\nif (GMP_INCLUDES AND GMP_LIBRARIES)\n  set(GMP_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(GMP_INCLUDES\n  NAMES\n  gmp.h\n  PATHS\n  $ENV{GMPDIR}\n  ${INCLUDE_INSTALL_DIR}\n)\n\nfind_library(GMP_LIBRARIES gmp PATHS $ENV{GMPDIR} ${LIB_INSTALL_DIR})\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(GMP DEFAULT_MSG\n                                  GMP_INCLUDES GMP_LIBRARIES)\nmark_as_advanced(GMP_INCLUDES GMP_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindGSL.cmake",
    "content": "# Try to find gnu scientific library GSL\n# See \n# http://www.gnu.org/software/gsl/  and\n# http://gnuwin32.sourceforge.net/packages/gsl.htm\n#\n# Once run this will define: \n# \n# GSL_FOUND       = system has GSL lib\n#\n# GSL_LIBRARIES   = full path to the libraries\n#    on Unix/Linux with additional linker flags from \"gsl-config --libs\"\n# \n# CMAKE_GSL_CXX_FLAGS  = Unix compiler flags for GSL, essentially \"`gsl-config --cxxflags`\"\n#\n# GSL_INCLUDE_DIR      = where to find headers \n#\n# GSL_LINK_DIRECTORIES = link directories, useful for rpath on Unix\n# GSL_EXE_LINKER_FLAGS = rpath on Unix\n#\n# Felix Woelk 07/2004\n# Jan Woetzel\n#\n# www.mip.informatik.uni-kiel.de\n# --------------------------------\n\nif(WIN32)\n  # JW tested with gsl-1.8, Windows XP, MSVS 7.1\n  set(GSL_POSSIBLE_ROOT_DIRS\n    ${GSL_ROOT_DIR}\n    $ENV{GSL_ROOT_DIR}\n    ${GSL_DIR}\n    ${GSL_HOME}    \n    $ENV{GSL_DIR}\n    $ENV{GSL_HOME}\n    $ENV{EXTRA}\n    \"C:/Program Files/GnuWin32\"\n    )\n  find_path(GSL_INCLUDE_DIR\n    NAMES gsl/gsl_cdf.h gsl/gsl_randist.h\n    PATHS ${GSL_POSSIBLE_ROOT_DIRS}\n    PATH_SUFFIXES include\n    DOC \"GSL header include dir\"\n    )\n  \n  find_library(GSL_GSL_LIBRARY\n    NAMES libgsl.dll.a gsl libgsl\n    PATHS  ${GSL_POSSIBLE_ROOT_DIRS}\n    PATH_SUFFIXES lib\n    DOC \"GSL library\" )\n  \n  if(NOT GSL_GSL_LIBRARY)\n\tfind_file(GSL_GSL_LIBRARY\n\t\tNAMES libgsl.dll.a\n\t\tPATHS  ${GSL_POSSIBLE_ROOT_DIRS}\n\t\tPATH_SUFFIXES lib\n\t\tDOC \"GSL library\")\n  endif()\n  \n  find_library(GSL_GSLCBLAS_LIBRARY\n    NAMES libgslcblas.dll.a gslcblas libgslcblas\n    PATHS  ${GSL_POSSIBLE_ROOT_DIRS}\n    PATH_SUFFIXES lib\n    DOC \"GSL cblas library dir\" )\n  \n  if(NOT GSL_GSLCBLAS_LIBRARY)\n\tfind_file(GSL_GSLCBLAS_LIBRARY\n\t\tNAMES libgslcblas.dll.a\n\t\tPATHS  ${GSL_POSSIBLE_ROOT_DIRS}\n\t\tPATH_SUFFIXES lib\n\t\tDOC \"GSL library\")\n  endif()\n  \n  set(GSL_LIBRARIES ${GSL_GSL_LIBRARY})\n\n  #message(\"DBG\\n\"\n  #  \"GSL_GSL_LIBRARY=${GSL_GSL_LIBRARY}\\n\"\n  #  \"GSL_GSLCBLAS_LIBRARY=${GSL_GSLCBLAS_LIBRARY}\\n\"\n  #  \"GSL_LIBRARIES=${GSL_LIBRARIES}\")\n\n\nelse(WIN32)\n  \n  if(UNIX) \n    set(GSL_CONFIG_PREFER_PATH \n      \"$ENV{GSL_DIR}/bin\"\n      \"$ENV{GSL_DIR}\"\n      \"$ENV{GSL_HOME}/bin\" \n      \"$ENV{GSL_HOME}\" \n      CACHE STRING \"preferred path to GSL (gsl-config)\")\n    find_program(GSL_CONFIG gsl-config\n      ${GSL_CONFIG_PREFER_PATH}\n      /usr/bin/\n      )\n    # message(\"DBG GSL_CONFIG ${GSL_CONFIG}\")\n    \n    if (GSL_CONFIG) \n      # set CXXFLAGS to be fed into CXX_FLAGS by the user:\n      set(GSL_CXX_FLAGS \"`${GSL_CONFIG} --cflags`\")\n      \n      # set INCLUDE_DIRS to prefix+include\n      exec_program(${GSL_CONFIG}\n        ARGS --prefix\n        OUTPUT_VARIABLE GSL_PREFIX)\n      set(GSL_INCLUDE_DIR ${GSL_PREFIX}/include CACHE STRING INTERNAL)\n\n      # set link libraries and link flags\n      #set(GSL_LIBRARIES \"`${GSL_CONFIG} --libs`\")\n      exec_program(${GSL_CONFIG}\n        ARGS --libs\n        OUTPUT_VARIABLE GSL_LIBRARIES )\n        \n      # extract link dirs for rpath  \n      exec_program(${GSL_CONFIG}\n        ARGS --libs\n        OUTPUT_VARIABLE GSL_CONFIG_LIBS )\n      \n      # extract version\n      exec_program(${GSL_CONFIG}\n        ARGS --version\n        OUTPUT_VARIABLE GSL_FULL_VERSION )\n      \n      # split version as major/minor\n      string(REGEX MATCH \"(.)\\\\..*\" GSL_VERSION_MAJOR_ \"${GSL_FULL_VERSION}\")\n      set(GSL_VERSION_MAJOR ${CMAKE_MATCH_1})\n      string(REGEX MATCH \".\\\\.(.*)\" GSL_VERSION_MINOR_ \"${GSL_FULL_VERSION}\")\n      set(GSL_VERSION_MINOR ${CMAKE_MATCH_1})\n\n      # split off the link dirs (for rpath)\n      # use regular expression to match wildcard equivalent \"-L*<endchar>\"\n      # with <endchar> is a space or a semicolon\n      string(REGEX MATCHALL \"[-][L]([^ ;])+\" \n        GSL_LINK_DIRECTORIES_WITH_PREFIX \n        \"${GSL_CONFIG_LIBS}\" )\n      #      message(\"DBG  GSL_LINK_DIRECTORIES_WITH_PREFIX=${GSL_LINK_DIRECTORIES_WITH_PREFIX}\")\n\n      # remove prefix -L because we need the pure directory for LINK_DIRECTORIES\n      \n      if (GSL_LINK_DIRECTORIES_WITH_PREFIX)\n        string(REGEX REPLACE \"[-][L]\" \"\" GSL_LINK_DIRECTORIES ${GSL_LINK_DIRECTORIES_WITH_PREFIX} )\n      endif (GSL_LINK_DIRECTORIES_WITH_PREFIX)\n      set(GSL_EXE_LINKER_FLAGS \"-Wl,-rpath,${GSL_LINK_DIRECTORIES}\" CACHE STRING INTERNAL)\n      #      message(\"DBG  GSL_LINK_DIRECTORIES=${GSL_LINK_DIRECTORIES}\")\n      #      message(\"DBG  GSL_EXE_LINKER_FLAGS=${GSL_EXE_LINKER_FLAGS}\")\n\n      #      add_definitions(\"-DHAVE_GSL\")\n      #      set(GSL_DEFINITIONS \"-DHAVE_GSL\")\n      mark_as_advanced(\n        GSL_CXX_FLAGS\n        GSL_INCLUDE_DIR\n        GSL_LIBRARIES\n        GSL_LINK_DIRECTORIES\n        GSL_DEFINITIONS\n        )\n      message(STATUS \"Using GSL from ${GSL_PREFIX}\")\n      \n    else(GSL_CONFIG)\n      message(\"FindGSL.cmake: gsl-config not found. Please set it manually. GSL_CONFIG=${GSL_CONFIG}\")\n    endif(GSL_CONFIG)\n\n  endif(UNIX)\nendif(WIN32)\n\n\nif(GSL_LIBRARIES)\n  if(GSL_INCLUDE_DIR OR GSL_CXX_FLAGS)\n\n    set(GSL_FOUND 1)\n    \n  endif(GSL_INCLUDE_DIR OR GSL_CXX_FLAGS)\nendif(GSL_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindGoogleHash.cmake",
    "content": "\nif (GOOGLEHASH_INCLUDES AND GOOGLEHASH_LIBRARIES)\n  set(GOOGLEHASH_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(GOOGLEHASH_INCLUDES\n  NAMES\n  google/dense_hash_map\n  PATHS\n  ${INCLUDE_INSTALL_DIR}\n)\n\nif(GOOGLEHASH_INCLUDES)\n  # let's make sure it compiles with the current compiler\n  file(WRITE ${CMAKE_BINARY_DIR}/googlehash_test.cpp\n  \"#include <google/sparse_hash_map>\\n#include <google/dense_hash_map>\\nint main(int argc, char** argv) { google::dense_hash_map<int,float> a; google::sparse_hash_map<int,float> b; return 0;}\\n\")\n  try_compile(GOOGLEHASH_COMPILE ${CMAKE_BINARY_DIR} ${CMAKE_BINARY_DIR}/googlehash_test.cpp OUTPUT_VARIABLE GOOGLEHASH_COMPILE_RESULT)\nendif()\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(GoogleHash DEFAULT_MSG GOOGLEHASH_INCLUDES GOOGLEHASH_COMPILE)\n\nmark_as_advanced(GOOGLEHASH_INCLUDES)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindHWLOC.cmake",
    "content": "###\n#\n# @copyright (c) 2009-2014 The University of Tennessee and The University\n#                          of Tennessee Research Foundation.\n#                          All rights reserved.\n# @copyright (c) 2012-2014 Inria. All rights reserved.\n# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved.\n#\n###\n#\n# - Find HWLOC include dirs and libraries\n# Use this module by invoking find_package with the form:\n#  find_package(HWLOC\n#               [REQUIRED]) # Fail with error if hwloc is not found\n#\n# This module finds headers and hwloc library.\n# Results are reported in variables:\n#  HWLOC_FOUND           - True if headers and requested libraries were found\n#  HWLOC_INCLUDE_DIRS    - hwloc include directories\n#  HWLOC_LIBRARY_DIRS    - Link directories for hwloc libraries\n#  HWLOC_LIBRARIES       - hwloc component libraries to be linked\n#\n# The user can give specific paths where to find the libraries adding cmake\n# options at configure (ex: cmake path/to/project -DHWLOC_DIR=path/to/hwloc):\n#  HWLOC_DIR             - Where to find the base directory of hwloc\n#  HWLOC_INCDIR          - Where to find the header files\n#  HWLOC_LIBDIR          - Where to find the library files\n# The module can also look for the following environment variables if paths\n# are not given as cmake variable: HWLOC_DIR, HWLOC_INCDIR, HWLOC_LIBDIR\n\n#=============================================================================\n# Copyright 2012-2013 Inria\n# Copyright 2012-2013 Emmanuel Agullo\n# Copyright 2012-2013 Mathieu Faverge\n# Copyright 2012      Cedric Castagnede\n# Copyright 2013      Florent Pruvost\n#\n# Distributed under the OSI-approved BSD License (the \"License\");\n# see accompanying file MORSE-Copyright.txt for details.\n#\n# This software is distributed WITHOUT ANY WARRANTY; without even the\n# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.\n# See the License for more information.\n#=============================================================================\n# (To distribute this file outside of Morse, substitute the full\n#  License text for the above reference.)\n\ninclude(CheckStructHasMember)\ninclude(CheckCSourceCompiles)\n\nif (NOT HWLOC_FOUND)\n  set(HWLOC_DIR \"\" CACHE PATH \"Installation directory of HWLOC library\")\n  if (NOT HWLOC_FIND_QUIETLY)\n    message(STATUS \"A cache variable, namely HWLOC_DIR, has been set to specify the install directory of HWLOC\")\n  endif()\nendif()\n\nset(ENV_HWLOC_DIR \"$ENV{HWLOC_DIR}\")\nset(ENV_HWLOC_INCDIR \"$ENV{HWLOC_INCDIR}\")\nset(ENV_HWLOC_LIBDIR \"$ENV{HWLOC_LIBDIR}\")\nset(HWLOC_GIVEN_BY_USER \"FALSE\")\nif ( HWLOC_DIR OR ( HWLOC_INCDIR AND HWLOC_LIBDIR) OR ENV_HWLOC_DIR OR (ENV_HWLOC_INCDIR AND ENV_HWLOC_LIBDIR) )\n  set(HWLOC_GIVEN_BY_USER \"TRUE\")\nendif()\n\n# Optionally use pkg-config to detect include/library dirs (if pkg-config is available)\n# -------------------------------------------------------------------------------------\ninclude(FindPkgConfig)\nfind_package(PkgConfig QUIET)\nif( PKG_CONFIG_EXECUTABLE AND NOT HWLOC_GIVEN_BY_USER )\n\n  pkg_search_module(HWLOC hwloc)\n  if (NOT HWLOC_FIND_QUIETLY)\n    if (HWLOC_FOUND AND HWLOC_LIBRARIES)\n      message(STATUS \"Looking for HWLOC - found using PkgConfig\")\n      #if(NOT HWLOC_INCLUDE_DIRS)\n      #    message(\"${Magenta}HWLOC_INCLUDE_DIRS is empty using PkgConfig.\"\n      #        \"Perhaps the path to hwloc headers is already present in your\"\n      #        \"C(PLUS)_INCLUDE_PATH environment variable.${ColourReset}\")\n      #endif()\n    else()\n      message(STATUS \"${Magenta}Looking for HWLOC - not found using PkgConfig.\"\n\t\"\\n   Perhaps you should add the directory containing hwloc.pc to\"\n\t\"\\n   the PKG_CONFIG_PATH environment variable.${ColourReset}\")\n    endif()\n  endif()\n\nendif()\n\nif( (NOT PKG_CONFIG_EXECUTABLE) OR (PKG_CONFIG_EXECUTABLE AND NOT HWLOC_FOUND) OR (HWLOC_GIVEN_BY_USER) )\n\n  if (NOT HWLOC_FIND_QUIETLY)\n    message(STATUS \"Looking for HWLOC - PkgConfig not used\")\n  endif()\n\n  # Looking for include\n  # -------------------\n\n  # Add system include paths to search include\n  # ------------------------------------------\n  unset(_inc_env)\n  if(ENV_HWLOC_INCDIR)\n    list(APPEND _inc_env \"${ENV_HWLOC_INCDIR}\")\n  elseif(ENV_HWLOC_DIR)\n    list(APPEND _inc_env \"${ENV_HWLOC_DIR}\")\n    list(APPEND _inc_env \"${ENV_HWLOC_DIR}/include\")\n    list(APPEND _inc_env \"${ENV_HWLOC_DIR}/include/hwloc\")\n  else()\n    if(WIN32)\n      string(REPLACE \":\" \";\" _inc_env \"$ENV{INCLUDE}\")\n    else()\n      string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE}\")\n      list(APPEND _inc_env \"${_path_env}\")\n      string(REPLACE \":\" \";\" _path_env \"$ENV{C_INCLUDE_PATH}\")\n      list(APPEND _inc_env \"${_path_env}\")\n      string(REPLACE \":\" \";\" _path_env \"$ENV{CPATH}\")\n      list(APPEND _inc_env \"${_path_env}\")\n      string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE_PATH}\")\n      list(APPEND _inc_env \"${_path_env}\")\n    endif()\n  endif()\n  list(APPEND _inc_env \"${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}\")\n  list(APPEND _inc_env \"${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}\")\n  list(REMOVE_DUPLICATES _inc_env)\n\n  # set paths where to look for\n  set(PATH_TO_LOOK_FOR \"${_inc_env}\")\n\n  # Try to find the hwloc header in the given paths\n  # -------------------------------------------------\n  # call cmake macro to find the header path\n  if(HWLOC_INCDIR)\n    set(HWLOC_hwloc.h_DIRS \"HWLOC_hwloc.h_DIRS-NOTFOUND\")\n    find_path(HWLOC_hwloc.h_DIRS\n      NAMES hwloc.h\n      HINTS ${HWLOC_INCDIR})\n  else()\n    if(HWLOC_DIR)\n      set(HWLOC_hwloc.h_DIRS \"HWLOC_hwloc.h_DIRS-NOTFOUND\")\n      find_path(HWLOC_hwloc.h_DIRS\n\tNAMES hwloc.h\n\tHINTS ${HWLOC_DIR}\n\tPATH_SUFFIXES \"include\" \"include/hwloc\")\n    else()\n      set(HWLOC_hwloc.h_DIRS \"HWLOC_hwloc.h_DIRS-NOTFOUND\")\n      find_path(HWLOC_hwloc.h_DIRS\n\tNAMES hwloc.h\n\tHINTS ${PATH_TO_LOOK_FOR}\n\tPATH_SUFFIXES \"hwloc\")\n    endif()\n  endif()\n  mark_as_advanced(HWLOC_hwloc.h_DIRS)\n\n  # Add path to cmake variable\n  # ------------------------------------\n  if (HWLOC_hwloc.h_DIRS)\n    set(HWLOC_INCLUDE_DIRS \"${HWLOC_hwloc.h_DIRS}\")\n  else ()\n    set(HWLOC_INCLUDE_DIRS \"HWLOC_INCLUDE_DIRS-NOTFOUND\")\n    if(NOT HWLOC_FIND_QUIETLY)\n      message(STATUS \"Looking for hwloc -- hwloc.h not found\")\n    endif()\n  endif ()\n\n  if (HWLOC_INCLUDE_DIRS)\n    list(REMOVE_DUPLICATES HWLOC_INCLUDE_DIRS)\n  endif ()\n\n\n  # Looking for lib\n  # ---------------\n\n  # Add system library paths to search lib\n  # --------------------------------------\n  unset(_lib_env)\n  if(ENV_HWLOC_LIBDIR)\n    list(APPEND _lib_env \"${ENV_HWLOC_LIBDIR}\")\n  elseif(ENV_HWLOC_DIR)\n    list(APPEND _lib_env \"${ENV_HWLOC_DIR}\")\n    list(APPEND _lib_env \"${ENV_HWLOC_DIR}/lib\")\n  else()\n    if(WIN32)\n      string(REPLACE \":\" \";\" _lib_env \"$ENV{LIB}\")\n    else()\n      if(APPLE)\n\tstring(REPLACE \":\" \";\" _lib_env \"$ENV{DYLD_LIBRARY_PATH}\")\n      else()\n\tstring(REPLACE \":\" \";\" _lib_env \"$ENV{LD_LIBRARY_PATH}\")\n      endif()\n      list(APPEND _lib_env \"${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}\")\n      list(APPEND _lib_env \"${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}\")\n    endif()\n  endif()\n  list(REMOVE_DUPLICATES _lib_env)\n\n  # set paths where to look for\n  set(PATH_TO_LOOK_FOR \"${_lib_env}\")\n\n  # Try to find the hwloc lib in the given paths\n  # ----------------------------------------------\n\n  # call cmake macro to find the lib path\n  if(HWLOC_LIBDIR)\n    set(HWLOC_hwloc_LIBRARY \"HWLOC_hwloc_LIBRARY-NOTFOUND\")\n    find_library(HWLOC_hwloc_LIBRARY\n      NAMES hwloc\n      HINTS ${HWLOC_LIBDIR})\n  else()\n    if(HWLOC_DIR)\n      set(HWLOC_hwloc_LIBRARY \"HWLOC_hwloc_LIBRARY-NOTFOUND\")\n      find_library(HWLOC_hwloc_LIBRARY\n\tNAMES hwloc\n\tHINTS ${HWLOC_DIR}\n\tPATH_SUFFIXES lib lib32 lib64)\n    else()\n      set(HWLOC_hwloc_LIBRARY \"HWLOC_hwloc_LIBRARY-NOTFOUND\")\n      find_library(HWLOC_hwloc_LIBRARY\n\tNAMES hwloc\n\tHINTS ${PATH_TO_LOOK_FOR})\n    endif()\n  endif()\n  mark_as_advanced(HWLOC_hwloc_LIBRARY)\n\n  # If found, add path to cmake variable\n  # ------------------------------------\n  if (HWLOC_hwloc_LIBRARY)\n    get_filename_component(hwloc_lib_path ${HWLOC_hwloc_LIBRARY} PATH)\n    # set cmake variables (respects naming convention)\n    set(HWLOC_LIBRARIES    \"${HWLOC_hwloc_LIBRARY}\")\n    set(HWLOC_LIBRARY_DIRS \"${hwloc_lib_path}\")\n  else ()\n    set(HWLOC_LIBRARIES    \"HWLOC_LIBRARIES-NOTFOUND\")\n    set(HWLOC_LIBRARY_DIRS \"HWLOC_LIBRARY_DIRS-NOTFOUND\")\n    if(NOT HWLOC_FIND_QUIETLY)\n      message(STATUS \"Looking for hwloc -- lib hwloc not found\")\n    endif()\n  endif ()\n\n  if (HWLOC_LIBRARY_DIRS)\n    list(REMOVE_DUPLICATES HWLOC_LIBRARY_DIRS)\n  endif ()\n\n  # check a function to validate the find\n  if(HWLOC_LIBRARIES)\n\n    set(REQUIRED_INCDIRS)\n    set(REQUIRED_LIBDIRS)\n    set(REQUIRED_LIBS)\n\n    # HWLOC\n    if (HWLOC_INCLUDE_DIRS)\n      set(REQUIRED_INCDIRS \"${HWLOC_INCLUDE_DIRS}\")\n    endif()\n    if (HWLOC_LIBRARY_DIRS)\n      set(REQUIRED_LIBDIRS \"${HWLOC_LIBRARY_DIRS}\")\n    endif()\n    set(REQUIRED_LIBS \"${HWLOC_LIBRARIES}\")\n\n    # set required libraries for link\n    set(CMAKE_REQUIRED_INCLUDES \"${REQUIRED_INCDIRS}\")\n    set(CMAKE_REQUIRED_LIBRARIES)\n    foreach(lib_dir ${REQUIRED_LIBDIRS})\n      list(APPEND CMAKE_REQUIRED_LIBRARIES \"-L${lib_dir}\")\n    endforeach()\n    list(APPEND CMAKE_REQUIRED_LIBRARIES \"${REQUIRED_LIBS}\")\n    string(REGEX REPLACE \"^ -\" \"-\" CMAKE_REQUIRED_LIBRARIES \"${CMAKE_REQUIRED_LIBRARIES}\")\n\n    # test link\n    unset(HWLOC_WORKS CACHE)\n    include(CheckFunctionExists)\n    check_function_exists(hwloc_topology_init HWLOC_WORKS)\n    mark_as_advanced(HWLOC_WORKS)\n\n    if(NOT HWLOC_WORKS)\n      if(NOT HWLOC_FIND_QUIETLY)\n\tmessage(STATUS \"Looking for hwloc : test of hwloc_topology_init with hwloc library fails\")\n\tmessage(STATUS \"CMAKE_REQUIRED_LIBRARIES: ${CMAKE_REQUIRED_LIBRARIES}\")\n\tmessage(STATUS \"CMAKE_REQUIRED_INCLUDES: ${CMAKE_REQUIRED_INCLUDES}\")\n\tmessage(STATUS \"Check in CMakeFiles/CMakeError.log to figure out why it fails\")\n      endif()\n    endif()\n    set(CMAKE_REQUIRED_INCLUDES)\n    set(CMAKE_REQUIRED_FLAGS)\n    set(CMAKE_REQUIRED_LIBRARIES)\n  endif()\n\nendif()\n\nif (HWLOC_LIBRARIES)\n  if (HWLOC_LIBRARY_DIRS)\n    list(GET HWLOC_LIBRARY_DIRS 0 first_lib_path)\n  else()\n    list(GET HWLOC_LIBRARIES 0 first_lib)\n    get_filename_component(first_lib_path \"${first_lib}\" PATH)\n  endif()\n  if (${first_lib_path} MATCHES \"/lib(32|64)?$\")\n    string(REGEX REPLACE \"/lib(32|64)?$\" \"\" not_cached_dir \"${first_lib_path}\")\n    set(HWLOC_DIR_FOUND \"${not_cached_dir}\" CACHE PATH \"Installation directory of HWLOC library\" FORCE)\n  else()\n    set(HWLOC_DIR_FOUND \"${first_lib_path}\" CACHE PATH \"Installation directory of HWLOC library\" FORCE)\n  endif()\nendif()\nmark_as_advanced(HWLOC_DIR)\nmark_as_advanced(HWLOC_DIR_FOUND)\n\n# check that HWLOC has been found\n# -------------------------------\ninclude(FindPackageHandleStandardArgs)\nif (PKG_CONFIG_EXECUTABLE AND HWLOC_FOUND)\n  find_package_handle_standard_args(HWLOC DEFAULT_MSG\n    HWLOC_LIBRARIES)\nelse()\n  find_package_handle_standard_args(HWLOC DEFAULT_MSG\n    HWLOC_LIBRARIES\n    HWLOC_WORKS)\nendif()\n\nif (HWLOC_FOUND)\n  set(HWLOC_SAVE_CMAKE_REQUIRED_INCLUDES ${CMAKE_REQUIRED_INCLUDES})\n  list(APPEND CMAKE_REQUIRED_INCLUDES ${HWLOC_INCLUDE_DIRS})\n\n  # test headers to guess the version\n  check_struct_has_member( \"struct hwloc_obj\" parent hwloc.h HAVE_HWLOC_PARENT_MEMBER )\n  check_struct_has_member( \"struct hwloc_cache_attr_s\" size hwloc.h HAVE_HWLOC_CACHE_ATTR )\n  check_c_source_compiles( \"#include <hwloc.h>\n\t    int main(void) { hwloc_obj_t o; o->type = HWLOC_OBJ_PU; return 0;}\" HAVE_HWLOC_OBJ_PU)\n  include(CheckLibraryExists)\n  check_library_exists(${HWLOC_LIBRARIES} hwloc_bitmap_free \"\" HAVE_HWLOC_BITMAP)\n\n  set(CMAKE_REQUIRED_INCLUDES ${HWLOC_SAVE_CMAKE_REQUIRED_INCLUDES})\nendif()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindKLU.cmake",
    "content": "# KLU lib usually requires linking to a blas library.\n# It is up to the user of this module to find a BLAS and link to it.\n\nif (KLU_INCLUDES AND KLU_LIBRARIES)\n  set(KLU_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(KLU_INCLUDES\n  NAMES\n  klu.h\n  PATHS\n  $ENV{KLUDIR}\n  ${INCLUDE_INSTALL_DIR}\n  PATH_SUFFIXES\n  suitesparse\n  ufsparse\n)\n\nfind_library(KLU_LIBRARIES klu PATHS $ENV{KLUDIR} ${LIB_INSTALL_DIR})\n\nif(KLU_LIBRARIES)\n\n  if(NOT KLU_LIBDIR)\n    get_filename_component(KLU_LIBDIR ${KLU_LIBRARIES} PATH)\n  endif()\n\n  find_library(COLAMD_LIBRARY colamd PATHS ${KLU_LIBDIR} $ENV{KLUDIR} ${LIB_INSTALL_DIR})\n  if(COLAMD_LIBRARY)\n    set(KLU_LIBRARIES ${KLU_LIBRARIES} ${COLAMD_LIBRARY})\n  endif ()\n  \n  find_library(AMD_LIBRARY amd PATHS ${KLU_LIBDIR} $ENV{KLUDIR} ${LIB_INSTALL_DIR})\n  if(AMD_LIBRARY)\n    set(KLU_LIBRARIES ${KLU_LIBRARIES} ${AMD_LIBRARY})\n  endif ()\n\n  find_library(BTF_LIBRARY btf PATHS $ENV{KLU_LIBDIR} $ENV{KLUDIR} ${LIB_INSTALL_DIR})\n  if(BTF_LIBRARY)\n    set(KLU_LIBRARIES ${KLU_LIBRARIES} ${BTF_LIBRARY})\n  endif()\n\nendif()\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(KLU DEFAULT_MSG\n                                  KLU_INCLUDES KLU_LIBRARIES)\n\nmark_as_advanced(KLU_INCLUDES KLU_LIBRARIES AMD_LIBRARY COLAMD_LIBRARY BTF_LIBRARY)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindLAPACK.cmake",
    "content": "# Find LAPACK library\n#\n# This module finds an installed library that implements the LAPACK\n# linear-algebra interface (see http://www.netlib.org/lapack/).\n# The approach follows mostly that taken for the autoconf macro file, acx_lapack.m4\n# (distributed at http://ac-archive.sourceforge.net/ac-archive/acx_lapack.html).\n#\n# This module sets the following variables:\n#  LAPACK_FOUND - set to true if a library implementing the LAPACK interface\n#    is found\n#  LAPACK_INCLUDE_DIR - Directories containing the LAPACK header files\n#  LAPACK_DEFINITIONS - Compilation options to use LAPACK\n#  LAPACK_LINKER_FLAGS - Linker flags to use LAPACK (excluding -l\n#    and -L).\n#  LAPACK_LIBRARIES_DIR - Directories containing the LAPACK libraries.\n#     May be null if LAPACK_LIBRARIES contains libraries name using full path.\n#  LAPACK_LIBRARIES - List of libraries to link against LAPACK interface.\n#     May be null if the compiler supports auto-link (e.g. VC++).\n#  LAPACK_USE_FILE - The name of the cmake module to include to compile\n#     applications or libraries using LAPACK.\n#\n# This module was modified by CGAL team:\n# - find libraries for a C++ compiler, instead of Fortran\n# - added LAPACK_INCLUDE_DIR, LAPACK_DEFINITIONS and LAPACK_LIBRARIES_DIR\n# - removed LAPACK95_LIBRARIES\n\n\ninclude(CheckFunctionExists)\n\n# This macro checks for the existence of the combination of fortran libraries\n# given by _list.  If the combination is found, this macro checks (using the\n# check_function_exists macro) whether can link against that library\n# combination using the name of a routine given by _name using the linker\n# flags given by _flags.  If the combination of libraries is found and passes\n# the link test, LIBRARIES is set to the list of complete library paths that\n# have been found and DEFINITIONS to the required definitions.\n# Otherwise, LIBRARIES is set to FALSE.\n# N.B. _prefix is the prefix applied to the names of all cached variables that\n# are generated internally and marked advanced by this macro.\nmacro(check_lapack_libraries DEFINITIONS LIBRARIES _prefix _name _flags _list _blas _path)\n  #message(\"DEBUG: check_lapack_libraries(${_list} in ${_path} with ${_blas})\")\n\n  # Check for the existence of the libraries given by _list\n  set(_libraries_found TRUE)\n  set(_libraries_work FALSE)\n  set(${DEFINITIONS} \"\")\n  set(${LIBRARIES} \"\")\n  set(_combined_name)\n  foreach(_library ${_list})\n    set(_combined_name ${_combined_name}_${_library})\n\n    if(_libraries_found)\n      # search first in ${_path}\n      find_library(${_prefix}_${_library}_LIBRARY\n                  NAMES ${_library}\n                  PATHS ${_path} NO_DEFAULT_PATH\n                  )\n      # if not found, search in environment variables and system\n      if ( WIN32 )\n        find_library(${_prefix}_${_library}_LIBRARY\n                    NAMES ${_library}\n                    PATHS ENV LIB\n                    )\n      elseif ( APPLE )\n        find_library(${_prefix}_${_library}_LIBRARY\n                    NAMES ${_library}\n                    PATHS /usr/local/lib /usr/lib /usr/local/lib64 /usr/lib64 ENV DYLD_LIBRARY_PATH\n                    )\n      else ()\n        find_library(${_prefix}_${_library}_LIBRARY\n                    NAMES ${_library}\n                    PATHS /usr/local/lib /usr/lib /usr/local/lib64 /usr/lib64 ENV LD_LIBRARY_PATH\n                    )\n      endif()\n      mark_as_advanced(${_prefix}_${_library}_LIBRARY)\n      set(${LIBRARIES} ${${LIBRARIES}} ${${_prefix}_${_library}_LIBRARY})\n      set(_libraries_found ${${_prefix}_${_library}_LIBRARY})\n    endif()\n  endforeach()\n  if(_libraries_found)\n    set(_libraries_found ${${LIBRARIES}})\n  endif()\n\n  # Test this combination of libraries with the Fortran/f2c interface.\n  # We test the Fortran interface first as it is well standardized.\n  if(_libraries_found AND NOT _libraries_work)\n    set(${DEFINITIONS}  \"-D${_prefix}_USE_F2C\")\n    set(${LIBRARIES}    ${_libraries_found})\n    # Some C++ linkers require the f2c library to link with Fortran libraries.\n    # I do not know which ones, thus I just add the f2c library if it is available.\n    find_package( F2C QUIET )\n    if ( F2C_FOUND )\n      set(${DEFINITIONS}  ${${DEFINITIONS}} ${F2C_DEFINITIONS})\n      set(${LIBRARIES}    ${${LIBRARIES}} ${F2C_LIBRARIES})\n    endif()\n    set(CMAKE_REQUIRED_DEFINITIONS  ${${DEFINITIONS}})\n    set(CMAKE_REQUIRED_LIBRARIES    ${_flags} ${${LIBRARIES}} ${_blas})\n    #message(\"DEBUG: CMAKE_REQUIRED_DEFINITIONS = ${CMAKE_REQUIRED_DEFINITIONS}\")\n    #message(\"DEBUG: CMAKE_REQUIRED_LIBRARIES = ${CMAKE_REQUIRED_LIBRARIES}\")\n    # Check if function exists with f2c calling convention (ie a trailing underscore)\n    check_function_exists(${_name}_ ${_prefix}_${_name}_${_combined_name}_f2c_WORKS)\n    set(CMAKE_REQUIRED_DEFINITIONS} \"\")\n    set(CMAKE_REQUIRED_LIBRARIES    \"\")\n    mark_as_advanced(${_prefix}_${_name}_${_combined_name}_f2c_WORKS)\n    set(_libraries_work ${${_prefix}_${_name}_${_combined_name}_f2c_WORKS})\n  endif()\n\n  # If not found, test this combination of libraries with a C interface.\n  # A few implementations (ie ACML) provide a C interface. Unfortunately, there is no standard.\n  if(_libraries_found AND NOT _libraries_work)\n    set(${DEFINITIONS} \"\")\n    set(${LIBRARIES}   ${_libraries_found})\n    set(CMAKE_REQUIRED_DEFINITIONS \"\")\n    set(CMAKE_REQUIRED_LIBRARIES   ${_flags} ${${LIBRARIES}} ${_blas})\n    #message(\"DEBUG: CMAKE_REQUIRED_LIBRARIES = ${CMAKE_REQUIRED_LIBRARIES}\")\n    check_function_exists(${_name} ${_prefix}_${_name}${_combined_name}_WORKS)\n    set(CMAKE_REQUIRED_LIBRARIES \"\")\n    mark_as_advanced(${_prefix}_${_name}${_combined_name}_WORKS)\n    set(_libraries_work ${${_prefix}_${_name}${_combined_name}_WORKS})\n  endif()\n\n  # on failure\n  if(NOT _libraries_work)\n    set(${DEFINITIONS} \"\")\n    set(${LIBRARIES}   FALSE)\n  endif()\n  #message(\"DEBUG: ${DEFINITIONS} = ${${DEFINITIONS}}\")\n  #message(\"DEBUG: ${LIBRARIES} = ${${LIBRARIES}}\")\nendmacro()\n\n\n#\n# main\n#\n\n# LAPACK requires BLAS\nif(LAPACK_FIND_QUIETLY OR NOT LAPACK_FIND_REQUIRED)\n  find_package(BLAS)\nelse()\n  find_package(BLAS REQUIRED)\nendif()\n\nif (NOT BLAS_FOUND)\n\n  message(STATUS \"LAPACK requires BLAS.\")\n  set(LAPACK_FOUND FALSE)\n\n# Is it already configured?\nelseif (LAPACK_LIBRARIES_DIR OR LAPACK_LIBRARIES)\n\n  set(LAPACK_FOUND TRUE)\n\nelse()\n\n  # reset variables\n  set( LAPACK_INCLUDE_DIR \"\" )\n  set( LAPACK_DEFINITIONS \"\" )\n  set( LAPACK_LINKER_FLAGS \"\" ) # unused (yet)\n  set( LAPACK_LIBRARIES \"\" )\n  set( LAPACK_LIBRARIES_DIR \"\" )\n\n    #\n    # If Unix, search for LAPACK function in possible libraries\n    #\n\n    #intel mkl lapack?\n    if(NOT LAPACK_LIBRARIES)\n      check_lapack_libraries(\n      LAPACK_DEFINITIONS\n      LAPACK_LIBRARIES\n      LAPACK\n      cheev\n      \"\"\n      \"mkl_lapack\"\n      \"${BLAS_LIBRARIES}\"\n      \"${CGAL_TAUCS_LIBRARIES_DIR} ENV LAPACK_LIB_DIR\"\n      )\n    endif()\n\n    #acml lapack?\n    if(NOT LAPACK_LIBRARIES)\n      check_lapack_libraries(\n      LAPACK_DEFINITIONS\n      LAPACK_LIBRARIES\n      LAPACK\n      cheev\n      \"\"\n      \"acml\"\n      \"${BLAS_LIBRARIES}\"\n      \"${CGAL_TAUCS_LIBRARIES_DIR} ENV LAPACK_LIB_DIR\"\n      )\n    endif()\n\n    # Apple LAPACK library?\n    if(NOT LAPACK_LIBRARIES)\n      check_lapack_libraries(\n      LAPACK_DEFINITIONS\n      LAPACK_LIBRARIES\n      LAPACK\n      cheev\n      \"\"\n      \"Accelerate\"\n      \"${BLAS_LIBRARIES}\"\n      \"${CGAL_TAUCS_LIBRARIES_DIR} ENV LAPACK_LIB_DIR\"\n      )\n    endif()\n\n    if ( NOT LAPACK_LIBRARIES )\n      check_lapack_libraries(\n      LAPACK_DEFINITIONS\n      LAPACK_LIBRARIES\n      LAPACK\n      cheev\n      \"\"\n      \"vecLib\"\n      \"${BLAS_LIBRARIES}\"\n      \"${CGAL_TAUCS_LIBRARIES_DIR} ENV LAPACK_LIB_DIR\"\n      )\n    endif ()\n\n    # Generic LAPACK library?\n    # This configuration *must* be the last try as this library is notably slow.\n    if ( NOT LAPACK_LIBRARIES )\n      check_lapack_libraries(\n      LAPACK_DEFINITIONS\n      LAPACK_LIBRARIES\n      LAPACK\n      cheev\n      \"\"\n      \"lapack\"\n      \"${BLAS_LIBRARIES}\"\n      \"${CGAL_TAUCS_LIBRARIES_DIR} ENV LAPACK_LIB_DIR\"\n      )\n    endif()\n\n  if(LAPACK_LIBRARIES_DIR OR LAPACK_LIBRARIES)\n    set(LAPACK_FOUND TRUE)\n  else()\n    set(LAPACK_FOUND FALSE)\n  endif()\n\n  if(NOT LAPACK_FIND_QUIETLY)\n    if(LAPACK_FOUND)\n      message(STATUS \"A library with LAPACK API found.\")\n    else()\n      if(LAPACK_FIND_REQUIRED)\n        message(FATAL_ERROR \"A required library with LAPACK API not found. Please specify library location.\")\n      else()\n        message(STATUS \"A library with LAPACK API not found. Please specify library location.\")\n      endif()\n    endif()\n  endif()\n\n  # Add variables to cache\n  set( LAPACK_INCLUDE_DIR   \"${LAPACK_INCLUDE_DIR}\"\n                            CACHE PATH \"Directories containing the LAPACK header files\" FORCE )\n  set( LAPACK_DEFINITIONS   \"${LAPACK_DEFINITIONS}\"\n                            CACHE STRING \"Compilation options to use LAPACK\" FORCE )\n  set( LAPACK_LINKER_FLAGS  \"${LAPACK_LINKER_FLAGS}\"\n                            CACHE STRING \"Linker flags to use LAPACK\" FORCE )\n  set( LAPACK_LIBRARIES     \"${LAPACK_LIBRARIES}\"\n                            CACHE FILEPATH \"LAPACK libraries name\" FORCE )\n  set( LAPACK_LIBRARIES_DIR \"${LAPACK_LIBRARIES_DIR}\"\n                            CACHE PATH \"Directories containing the LAPACK libraries\" FORCE )\n\n  #message(\"DEBUG: LAPACK_INCLUDE_DIR = ${LAPACK_INCLUDE_DIR}\")\n  #message(\"DEBUG: LAPACK_DEFINITIONS = ${LAPACK_DEFINITIONS}\")\n  #message(\"DEBUG: LAPACK_LINKER_FLAGS = ${LAPACK_LINKER_FLAGS}\")\n  #message(\"DEBUG: LAPACK_LIBRARIES = ${LAPACK_LIBRARIES}\")\n  #message(\"DEBUG: LAPACK_LIBRARIES_DIR = ${LAPACK_LIBRARIES_DIR}\")\n  #message(\"DEBUG: LAPACK_FOUND = ${LAPACK_FOUND}\")\n\nendif()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindMPFR.cmake",
    "content": "# Try to find the MPFR library\n# See http://www.mpfr.org/\n#\n# This module supports requiring a minimum version, e.g. you can do\n#   find_package(MPFR 2.3.0)\n# to require version 2.3.0 to newer of MPFR.\n#\n# Once done this will define\n#\n#  MPFR_FOUND - system has MPFR lib with correct version\n#  MPFR_INCLUDES - the MPFR include directory\n#  MPFR_LIBRARIES - the MPFR library\n#  MPFR_VERSION - MPFR version\n\n# Copyright (c) 2006, 2007 Montel Laurent, <montel@kde.org>\n# Copyright (c) 2008, 2009 Gael Guennebaud, <g.gael@free.fr>\n# Copyright (c) 2010 Jitse Niesen, <jitse@maths.leeds.ac.uk>\n# Redistribution and use is allowed according to the terms of the BSD license.\n\n# Set MPFR_INCLUDES\n\nfind_path(MPFR_INCLUDES\n  NAMES\n  mpfr.h\n  PATHS\n  $ENV{GMPDIR}\n  ${INCLUDE_INSTALL_DIR}\n)\n\n# Set MPFR_FIND_VERSION to 1.0.0 if no minimum version is specified\n\nif(NOT MPFR_FIND_VERSION)\n  if(NOT MPFR_FIND_VERSION_MAJOR)\n    set(MPFR_FIND_VERSION_MAJOR 1)\n  endif()\n  if(NOT MPFR_FIND_VERSION_MINOR)\n    set(MPFR_FIND_VERSION_MINOR 0)\n  endif()\n  if(NOT MPFR_FIND_VERSION_PATCH)\n    set(MPFR_FIND_VERSION_PATCH 0)\n  endif()\n\n  set(MPFR_FIND_VERSION \"${MPFR_FIND_VERSION_MAJOR}.${MPFR_FIND_VERSION_MINOR}.${MPFR_FIND_VERSION_PATCH}\")\nendif()\n\n\nif(MPFR_INCLUDES)\n\n  # Set MPFR_VERSION\n  \n  file(READ \"${MPFR_INCLUDES}/mpfr.h\" _mpfr_version_header)\n  \n  string(REGEX MATCH \"define[ \\t]+MPFR_VERSION_MAJOR[ \\t]+([0-9]+)\" _mpfr_major_version_match \"${_mpfr_version_header}\")\n  set(MPFR_MAJOR_VERSION \"${CMAKE_MATCH_1}\")\n  string(REGEX MATCH \"define[ \\t]+MPFR_VERSION_MINOR[ \\t]+([0-9]+)\" _mpfr_minor_version_match \"${_mpfr_version_header}\")\n  set(MPFR_MINOR_VERSION \"${CMAKE_MATCH_1}\")\n  string(REGEX MATCH \"define[ \\t]+MPFR_VERSION_PATCHLEVEL[ \\t]+([0-9]+)\" _mpfr_patchlevel_version_match \"${_mpfr_version_header}\")\n  set(MPFR_PATCHLEVEL_VERSION \"${CMAKE_MATCH_1}\")\n  \n  set(MPFR_VERSION ${MPFR_MAJOR_VERSION}.${MPFR_MINOR_VERSION}.${MPFR_PATCHLEVEL_VERSION})\n  \n  # Check whether found version exceeds minimum version\n  \n  if(${MPFR_VERSION} VERSION_LESS ${MPFR_FIND_VERSION})\n    set(MPFR_VERSION_OK FALSE)\n    message(STATUS \"MPFR version ${MPFR_VERSION} found in ${MPFR_INCLUDES}, \"\n                   \"but at least version ${MPFR_FIND_VERSION} is required\")\n  else()\n    set(MPFR_VERSION_OK TRUE)\n  endif()\n\nendif()\n\n# Set MPFR_LIBRARIES\n\nfind_library(MPFR_LIBRARIES mpfr PATHS $ENV{GMPDIR} ${LIB_INSTALL_DIR})\n\n# Epilogue\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(MPFR DEFAULT_MSG\n                                  MPFR_INCLUDES MPFR_LIBRARIES MPFR_VERSION_OK)\nmark_as_advanced(MPFR_INCLUDES MPFR_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindMetis.cmake",
    "content": "###\n#\n# @copyright (c) 2009-2014 The University of Tennessee and The University\n#                          of Tennessee Research Foundation.\n#                          All rights reserved.\n# @copyright (c) 2012-2014 Inria. All rights reserved.\n# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved.\n#\n###\n#\n# - Find METIS include dirs and libraries\n# Use this module by invoking find_package with the form:\n#  find_package(METIS\n#               [REQUIRED]             # Fail with error if metis is not found\n#              )\n#\n# This module finds headers and metis library.\n# Results are reported in variables:\n#  METIS_FOUND           - True if headers and requested libraries were found\n#  METIS_INCLUDE_DIRS    - metis include directories\n#  METIS_LIBRARY_DIRS    - Link directories for metis libraries\n#  METIS_LIBRARIES       - metis component libraries to be linked\n#\n# The user can give specific paths where to find the libraries adding cmake\n# options at configure (ex: cmake path/to/project -DMETIS_DIR=path/to/metis):\n#  METIS_DIR             - Where to find the base directory of metis\n#  METIS_INCDIR          - Where to find the header files\n#  METIS_LIBDIR          - Where to find the library files\n# The module can also look for the following environment variables if paths\n# are not given as cmake variable: METIS_DIR, METIS_INCDIR, METIS_LIBDIR\n\n#=============================================================================\n# Copyright 2012-2013 Inria\n# Copyright 2012-2013 Emmanuel Agullo\n# Copyright 2012-2013 Mathieu Faverge\n# Copyright 2012      Cedric Castagnede\n# Copyright 2013      Florent Pruvost\n#\n# Distributed under the OSI-approved BSD License (the \"License\");\n# see accompanying file MORSE-Copyright.txt for details.\n#\n# This software is distributed WITHOUT ANY WARRANTY; without even the\n# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.\n# See the License for more information.\n#=============================================================================\n# (To distribute this file outside of Morse, substitute the full\n#  License text for the above reference.)\n\nif (NOT METIS_FOUND)\n  set(METIS_DIR \"\" CACHE PATH \"Installation directory of METIS library\")\n  if (NOT METIS_FIND_QUIETLY)\n    message(STATUS \"A cache variable, namely METIS_DIR, has been set to specify the install directory of METIS\")\n  endif()\nendif()\n\n# Looking for include\n# -------------------\n\n# Add system include paths to search include\n# ------------------------------------------\nunset(_inc_env)\nset(ENV_METIS_DIR \"$ENV{METIS_DIR}\")\nset(ENV_METIS_INCDIR \"$ENV{METIS_INCDIR}\")\nif(ENV_METIS_INCDIR)\n  list(APPEND _inc_env \"${ENV_METIS_INCDIR}\")\nelseif(ENV_METIS_DIR)\n  list(APPEND _inc_env \"${ENV_METIS_DIR}\")\n  list(APPEND _inc_env \"${ENV_METIS_DIR}/include\")\n  list(APPEND _inc_env \"${ENV_METIS_DIR}/include/metis\")\nelse()\n  if(WIN32)\n    string(REPLACE \":\" \";\" _inc_env \"$ENV{INCLUDE}\")\n  else()\n    string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{C_INCLUDE_PATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{CPATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE_PATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n  endif()\nendif()\nlist(APPEND _inc_env \"${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}\")\nlist(APPEND _inc_env \"${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}\")\nlist(REMOVE_DUPLICATES _inc_env)\n\n\n# Try to find the metis header in the given paths\n# -------------------------------------------------\n# call cmake macro to find the header path\nif(METIS_INCDIR)\n  set(METIS_metis.h_DIRS \"METIS_metis.h_DIRS-NOTFOUND\")\n  find_path(METIS_metis.h_DIRS\n    NAMES metis.h\n    HINTS ${METIS_INCDIR})\nelse()\n  if(METIS_DIR)\n    set(METIS_metis.h_DIRS \"METIS_metis.h_DIRS-NOTFOUND\")\n    find_path(METIS_metis.h_DIRS\n      NAMES metis.h\n      HINTS ${METIS_DIR}\n      PATH_SUFFIXES \"include\" \"include/metis\")\n  else()\n    set(METIS_metis.h_DIRS \"METIS_metis.h_DIRS-NOTFOUND\")\n    find_path(METIS_metis.h_DIRS\n      NAMES metis.h\n      HINTS ${_inc_env})\n  endif()\nendif()\nmark_as_advanced(METIS_metis.h_DIRS)\n\n\n# If found, add path to cmake variable\n# ------------------------------------\nif (METIS_metis.h_DIRS)\n  set(METIS_INCLUDE_DIRS \"${METIS_metis.h_DIRS}\")\nelse ()\n  set(METIS_INCLUDE_DIRS \"METIS_INCLUDE_DIRS-NOTFOUND\")\n  if(NOT METIS_FIND_QUIETLY)\n    message(STATUS \"Looking for metis -- metis.h not found\")\n  endif()\nendif()\n\n\n# Looking for lib\n# ---------------\n\n# Add system library paths to search lib\n# --------------------------------------\nunset(_lib_env)\nset(ENV_METIS_LIBDIR \"$ENV{METIS_LIBDIR}\")\nif(ENV_METIS_LIBDIR)\n  list(APPEND _lib_env \"${ENV_METIS_LIBDIR}\")\nelseif(ENV_METIS_DIR)\n  list(APPEND _lib_env \"${ENV_METIS_DIR}\")\n  list(APPEND _lib_env \"${ENV_METIS_DIR}/lib\")\nelse()\n  if(WIN32)\n    string(REPLACE \":\" \";\" _lib_env \"$ENV{LIB}\")\n  else()\n    if(APPLE)\n      string(REPLACE \":\" \";\" _lib_env \"$ENV{DYLD_LIBRARY_PATH}\")\n    else()\n      string(REPLACE \":\" \";\" _lib_env \"$ENV{LD_LIBRARY_PATH}\")\n    endif()\n    list(APPEND _lib_env \"${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}\")\n    list(APPEND _lib_env \"${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}\")\n  endif()\nendif()\nlist(REMOVE_DUPLICATES _lib_env)\n\n# Try to find the metis lib in the given paths\n# ----------------------------------------------\n# call cmake macro to find the lib path\nif(METIS_LIBDIR)\n  set(METIS_metis_LIBRARY \"METIS_metis_LIBRARY-NOTFOUND\")\n  find_library(METIS_metis_LIBRARY\n    NAMES metis\n    HINTS ${METIS_LIBDIR})\nelse()\n  if(METIS_DIR)\n    set(METIS_metis_LIBRARY \"METIS_metis_LIBRARY-NOTFOUND\")\n    find_library(METIS_metis_LIBRARY\n      NAMES metis\n      HINTS ${METIS_DIR}\n      PATH_SUFFIXES lib lib32 lib64)\n  else()\n    set(METIS_metis_LIBRARY \"METIS_metis_LIBRARY-NOTFOUND\")\n    find_library(METIS_metis_LIBRARY\n      NAMES metis\n      HINTS ${_lib_env})\n  endif()\nendif()\nmark_as_advanced(METIS_metis_LIBRARY)\n\n\n# If found, add path to cmake variable\n# ------------------------------------\nif (METIS_metis_LIBRARY)\n  get_filename_component(metis_lib_path \"${METIS_metis_LIBRARY}\" PATH)\n  # set cmake variables\n  set(METIS_LIBRARIES    \"${METIS_metis_LIBRARY}\")\n  set(METIS_LIBRARY_DIRS \"${metis_lib_path}\")\nelse ()\n  set(METIS_LIBRARIES    \"METIS_LIBRARIES-NOTFOUND\")\n  set(METIS_LIBRARY_DIRS \"METIS_LIBRARY_DIRS-NOTFOUND\")\n  if(NOT METIS_FIND_QUIETLY)\n    message(STATUS \"Looking for metis -- lib metis not found\")\n  endif()\nendif ()\n\n# check a function to validate the find\nif(METIS_LIBRARIES)\n\n  set(REQUIRED_INCDIRS)\n  set(REQUIRED_LIBDIRS)\n  set(REQUIRED_LIBS)\n\n  # METIS\n  if (METIS_INCLUDE_DIRS)\n    set(REQUIRED_INCDIRS  \"${METIS_INCLUDE_DIRS}\")\n  endif()\n  if (METIS_LIBRARY_DIRS)\n    set(REQUIRED_LIBDIRS \"${METIS_LIBRARY_DIRS}\")\n  endif()\n  set(REQUIRED_LIBS \"${METIS_LIBRARIES}\")\n  # m\n  find_library(M_LIBRARY NAMES m)\n  mark_as_advanced(M_LIBRARY)\n  if(M_LIBRARY)\n    list(APPEND REQUIRED_LIBS \"-lm\")\n  endif()\n\n  # set required libraries for link\n  set(CMAKE_REQUIRED_INCLUDES \"${REQUIRED_INCDIRS}\")\n  set(CMAKE_REQUIRED_LIBRARIES)\n  foreach(lib_dir ${REQUIRED_LIBDIRS})\n    list(APPEND CMAKE_REQUIRED_LIBRARIES \"-L${lib_dir}\")\n  endforeach()\n  list(APPEND CMAKE_REQUIRED_LIBRARIES \"${REQUIRED_LIBS}\")\n  string(REGEX REPLACE \"^ -\" \"-\" CMAKE_REQUIRED_LIBRARIES \"${CMAKE_REQUIRED_LIBRARIES}\")\n\n  # test link\n  unset(METIS_WORKS CACHE)\n  include(CheckFunctionExists)\n  check_function_exists(METIS_NodeND METIS_WORKS)\n  mark_as_advanced(METIS_WORKS)\n\n  if(NOT METIS_WORKS)\n    if(NOT METIS_FIND_QUIETLY)\n      message(STATUS \"Looking for METIS : test of METIS_NodeND with METIS library fails\")\n      message(STATUS \"CMAKE_REQUIRED_LIBRARIES: ${CMAKE_REQUIRED_LIBRARIES}\")\n      message(STATUS \"CMAKE_REQUIRED_INCLUDES: ${CMAKE_REQUIRED_INCLUDES}\")\n      message(STATUS \"Check in CMakeFiles/CMakeError.log to figure out why it fails\")\n    endif()\n  endif()\n  set(CMAKE_REQUIRED_INCLUDES)\n  set(CMAKE_REQUIRED_FLAGS)\n  set(CMAKE_REQUIRED_LIBRARIES)\nendif()\n\nif (METIS_LIBRARIES)\n  list(GET METIS_LIBRARIES 0 first_lib)\n  get_filename_component(first_lib_path \"${first_lib}\" PATH)\n  if (${first_lib_path} MATCHES \"/lib(32|64)?$\")\n    string(REGEX REPLACE \"/lib(32|64)?$\" \"\" not_cached_dir \"${first_lib_path}\")\n    set(METIS_DIR_FOUND \"${not_cached_dir}\" CACHE PATH \"Installation directory of METIS library\" FORCE)\n  else()\n    set(METIS_DIR_FOUND \"${first_lib_path}\" CACHE PATH \"Installation directory of METIS library\" FORCE)\n  endif()\nendif()\nmark_as_advanced(METIS_DIR)\nmark_as_advanced(METIS_DIR_FOUND)\n\n# check that METIS has been found\n# ---------------------------------\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(METIS DEFAULT_MSG\n  METIS_LIBRARIES\n  METIS_WORKS\n  METIS_INCLUDE_DIRS)\n#\n# TODO: Add possibility to check for specific functions in the library\n#\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindPTSCOTCH.cmake",
    "content": "###\n#\n# @copyright (c) 2009-2014 The University of Tennessee and The University\n#                          of Tennessee Research Foundation.\n#                          All rights reserved.\n# @copyright (c) 2012-2016 Inria. All rights reserved.\n# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved.\n#\n###\n#\n# - Find PTSCOTCH include dirs and libraries\n# Use this module by invoking find_package with the form:\n#  find_package(PTSCOTCH\n#               [REQUIRED]             # Fail with error if ptscotch is not found\n#               [COMPONENTS <comp1> <comp2> ...] # dependencies\n#              )\n#\n#  PTSCOTCH depends on the following libraries:\n#   - Threads\n#   - MPI\n#\n#  COMPONENTS can be some of the following:\n#   - ESMUMPS: to activate detection of PT-Scotch with the esmumps interface\n#\n# This module finds headers and ptscotch library.\n# Results are reported in variables:\n#  PTSCOTCH_FOUND            - True if headers and requested libraries were found\n#  PTSCOTCH_LINKER_FLAGS     - list of required linker flags (excluding -l and -L)\n#  PTSCOTCH_INCLUDE_DIRS     - ptscotch include directories\n#  PTSCOTCH_LIBRARY_DIRS     - Link directories for ptscotch libraries\n#  PTSCOTCH_LIBRARIES        - ptscotch component libraries to be linked\n#  PTSCOTCH_INCLUDE_DIRS_DEP - ptscotch + dependencies include directories\n#  PTSCOTCH_LIBRARY_DIRS_DEP - ptscotch + dependencies link directories\n#  PTSCOTCH_LIBRARIES_DEP    - ptscotch libraries + dependencies\n#  PTSCOTCH_INTSIZE          - Number of octets occupied by a SCOTCH_Num\n#\n# The user can give specific paths where to find the libraries adding cmake\n# options at configure (ex: cmake path/to/project -DPTSCOTCH=path/to/ptscotch):\n#  PTSCOTCH_DIR              - Where to find the base directory of ptscotch\n#  PTSCOTCH_INCDIR           - Where to find the header files\n#  PTSCOTCH_LIBDIR           - Where to find the library files\n# The module can also look for the following environment variables if paths\n# are not given as cmake variable: PTSCOTCH_DIR, PTSCOTCH_INCDIR, PTSCOTCH_LIBDIR\n\n#=============================================================================\n# Copyright 2012-2013 Inria\n# Copyright 2012-2013 Emmanuel Agullo\n# Copyright 2012-2013 Mathieu Faverge\n# Copyright 2012      Cedric Castagnede\n# Copyright 2013-2016 Florent Pruvost\n#\n# Distributed under the OSI-approved BSD License (the \"License\");\n# see accompanying file MORSE-Copyright.txt for details.\n#\n# This software is distributed WITHOUT ANY WARRANTY; without even the\n# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.\n# See the License for more information.\n#=============================================================================\n# (To distribute this file outside of Morse, substitute the full\n#  License text for the above reference.)\n\nif (NOT PTSCOTCH_FOUND)\n  set(PTSCOTCH_DIR \"\" CACHE PATH \"Installation directory of PTSCOTCH library\")\n  if (NOT PTSCOTCH_FIND_QUIETLY)\n    message(STATUS \"A cache variable, namely PTSCOTCH_DIR, has been set to specify the install directory of PTSCOTCH\")\n  endif()\nendif()\n\n# Set the version to find\nset(PTSCOTCH_LOOK_FOR_ESMUMPS OFF)\n\nif( PTSCOTCH_FIND_COMPONENTS )\n  foreach( component ${PTSCOTCH_FIND_COMPONENTS} )\n    if (${component} STREQUAL \"ESMUMPS\")\n      # means we look for esmumps library\n      set(PTSCOTCH_LOOK_FOR_ESMUMPS ON)\n    endif()\n  endforeach()\nendif()\n\n# PTSCOTCH depends on Threads, try to find it\nif (NOT THREADS_FOUND)\n  if (PTSCOTCH_FIND_REQUIRED)\n    find_package(Threads REQUIRED)\n  else()\n    find_package(Threads)\n  endif()\nendif()\n\n# PTSCOTCH depends on MPI, try to find it\nif (NOT MPI_FOUND)\n  if (PTSCOTCH_FIND_REQUIRED)\n    find_package(MPI REQUIRED)\n  else()\n    find_package(MPI)\n  endif()\nendif()\n\n# Looking for include\n# -------------------\n\n# Add system include paths to search include\n# ------------------------------------------\nunset(_inc_env)\nset(ENV_PTSCOTCH_DIR \"$ENV{PTSCOTCH_DIR}\")\nset(ENV_PTSCOTCH_INCDIR \"$ENV{PTSCOTCH_INCDIR}\")\nif(ENV_PTSCOTCH_INCDIR)\n  list(APPEND _inc_env \"${ENV_PTSCOTCH_INCDIR}\")\nelseif(ENV_PTSCOTCH_DIR)\n  list(APPEND _inc_env \"${ENV_PTSCOTCH_DIR}\")\n  list(APPEND _inc_env \"${ENV_PTSCOTCH_DIR}/include\")\n  list(APPEND _inc_env \"${ENV_PTSCOTCH_DIR}/include/ptscotch\")\nelse()\n  if(WIN32)\n    string(REPLACE \":\" \";\" _inc_env \"$ENV{INCLUDE}\")\n  else()\n    string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{C_INCLUDE_PATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{CPATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE_PATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n  endif()\nendif()\nlist(APPEND _inc_env \"${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}\")\nlist(APPEND _inc_env \"${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}\")\nlist(REMOVE_DUPLICATES _inc_env)\n\n\n# Try to find the ptscotch header in the given paths\n# -------------------------------------------------\n\nset(PTSCOTCH_hdrs_to_find \"ptscotch.h;scotch.h\")\n\n# call cmake macro to find the header path\nif(PTSCOTCH_INCDIR)\n  foreach(ptscotch_hdr ${PTSCOTCH_hdrs_to_find})\n    set(PTSCOTCH_${ptscotch_hdr}_DIRS \"PTSCOTCH_${ptscotch_hdr}_DIRS-NOTFOUND\")\n    find_path(PTSCOTCH_${ptscotch_hdr}_DIRS\n      NAMES ${ptscotch_hdr}\n      HINTS ${PTSCOTCH_INCDIR})\n    mark_as_advanced(PTSCOTCH_${ptscotch_hdr}_DIRS)\n  endforeach()\nelse()\n  if(PTSCOTCH_DIR)\n    foreach(ptscotch_hdr ${PTSCOTCH_hdrs_to_find})\n      set(PTSCOTCH_${ptscotch_hdr}_DIRS \"PTSCOTCH_${ptscotch_hdr}_DIRS-NOTFOUND\")\n      find_path(PTSCOTCH_${ptscotch_hdr}_DIRS\n\tNAMES ${ptscotch_hdr}\n\tHINTS ${PTSCOTCH_DIR}\n\tPATH_SUFFIXES \"include\" \"include/scotch\")\n      mark_as_advanced(PTSCOTCH_${ptscotch_hdr}_DIRS)\n    endforeach()\n  else()\n    foreach(ptscotch_hdr ${PTSCOTCH_hdrs_to_find})\n      set(PTSCOTCH_${ptscotch_hdr}_DIRS \"PTSCOTCH_${ptscotch_hdr}_DIRS-NOTFOUND\")\n      find_path(PTSCOTCH_${ptscotch_hdr}_DIRS\n\tNAMES ${ptscotch_hdr}\n\tHINTS ${_inc_env}\n\tPATH_SUFFIXES \"scotch\")\n      mark_as_advanced(PTSCOTCH_${ptscotch_hdr}_DIRS)\n    endforeach()\n  endif()\nendif()\n\n# If found, add path to cmake variable\n# ------------------------------------\nforeach(ptscotch_hdr ${PTSCOTCH_hdrs_to_find})\n  if (PTSCOTCH_${ptscotch_hdr}_DIRS)\n    list(APPEND PTSCOTCH_INCLUDE_DIRS \"${PTSCOTCH_${ptscotch_hdr}_DIRS}\")\n  else ()\n    set(PTSCOTCH_INCLUDE_DIRS \"PTSCOTCH_INCLUDE_DIRS-NOTFOUND\")\n    if (NOT PTSCOTCH_FIND_QUIETLY)\n      message(STATUS \"Looking for ptscotch -- ${ptscotch_hdr} not found\")\n    endif()\n  endif()\nendforeach()\nlist(REMOVE_DUPLICATES PTSCOTCH_INCLUDE_DIRS)\n\n# Looking for lib\n# ---------------\n\n# Add system library paths to search lib\n# --------------------------------------\nunset(_lib_env)\nset(ENV_PTSCOTCH_LIBDIR \"$ENV{PTSCOTCH_LIBDIR}\")\nif(ENV_PTSCOTCH_LIBDIR)\n  list(APPEND _lib_env \"${ENV_PTSCOTCH_LIBDIR}\")\nelseif(ENV_PTSCOTCH_DIR)\n  list(APPEND _lib_env \"${ENV_PTSCOTCH_DIR}\")\n  list(APPEND _lib_env \"${ENV_PTSCOTCH_DIR}/lib\")\nelse()\n  if(WIN32)\n    string(REPLACE \":\" \";\" _lib_env \"$ENV{LIB}\")\n  else()\n    if(APPLE)\n      string(REPLACE \":\" \";\" _lib_env \"$ENV{DYLD_LIBRARY_PATH}\")\n    else()\n      string(REPLACE \":\" \";\" _lib_env \"$ENV{LD_LIBRARY_PATH}\")\n    endif()\n    list(APPEND _lib_env \"${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}\")\n    list(APPEND _lib_env \"${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}\")\n  endif()\nendif()\nlist(REMOVE_DUPLICATES _lib_env)\n\n# Try to find the ptscotch lib in the given paths\n# ----------------------------------------------\n\nset(PTSCOTCH_libs_to_find \"ptscotch;ptscotcherr\")\nif (PTSCOTCH_LOOK_FOR_ESMUMPS)\n  list(INSERT PTSCOTCH_libs_to_find 0 \"ptesmumps\")\n  list(APPEND PTSCOTCH_libs_to_find   \"esmumps\"  )\nendif()\nlist(APPEND PTSCOTCH_libs_to_find \"scotch;scotcherr\")\n\n# call cmake macro to find the lib path\nif(PTSCOTCH_LIBDIR)\n  foreach(ptscotch_lib ${PTSCOTCH_libs_to_find})\n    set(PTSCOTCH_${ptscotch_lib}_LIBRARY \"PTSCOTCH_${ptscotch_lib}_LIBRARY-NOTFOUND\")\n    find_library(PTSCOTCH_${ptscotch_lib}_LIBRARY\n      NAMES ${ptscotch_lib}\n      HINTS ${PTSCOTCH_LIBDIR})\n  endforeach()\nelse()\n  if(PTSCOTCH_DIR)\n    foreach(ptscotch_lib ${PTSCOTCH_libs_to_find})\n      set(PTSCOTCH_${ptscotch_lib}_LIBRARY \"PTSCOTCH_${ptscotch_lib}_LIBRARY-NOTFOUND\")\n      find_library(PTSCOTCH_${ptscotch_lib}_LIBRARY\n\tNAMES ${ptscotch_lib}\n\tHINTS ${PTSCOTCH_DIR}\n\tPATH_SUFFIXES lib lib32 lib64)\n    endforeach()\n  else()\n    foreach(ptscotch_lib ${PTSCOTCH_libs_to_find})\n      set(PTSCOTCH_${ptscotch_lib}_LIBRARY \"PTSCOTCH_${ptscotch_lib}_LIBRARY-NOTFOUND\")\n      find_library(PTSCOTCH_${ptscotch_lib}_LIBRARY\n\tNAMES ${ptscotch_lib}\n\tHINTS ${_lib_env})\n    endforeach()\n  endif()\nendif()\n\nset(PTSCOTCH_LIBRARIES \"\")\nset(PTSCOTCH_LIBRARY_DIRS \"\")\n# If found, add path to cmake variable\n# ------------------------------------\nforeach(ptscotch_lib ${PTSCOTCH_libs_to_find})\n\n  if (PTSCOTCH_${ptscotch_lib}_LIBRARY)\n    get_filename_component(${ptscotch_lib}_lib_path \"${PTSCOTCH_${ptscotch_lib}_LIBRARY}\" PATH)\n    # set cmake variables\n    list(APPEND PTSCOTCH_LIBRARIES \"${PTSCOTCH_${ptscotch_lib}_LIBRARY}\")\n    list(APPEND PTSCOTCH_LIBRARY_DIRS \"${${ptscotch_lib}_lib_path}\")\n  else ()\n    list(APPEND PTSCOTCH_LIBRARIES \"${PTSCOTCH_${ptscotch_lib}_LIBRARY}\")\n    if (NOT PTSCOTCH_FIND_QUIETLY)\n      message(STATUS \"Looking for ptscotch -- lib ${ptscotch_lib} not found\")\n    endif()\n  endif ()\n\n  mark_as_advanced(PTSCOTCH_${ptscotch_lib}_LIBRARY)\n\nendforeach()\nlist(REMOVE_DUPLICATES PTSCOTCH_LIBRARY_DIRS)\n\n# check a function to validate the find\nif(PTSCOTCH_LIBRARIES)\n\n  set(REQUIRED_LDFLAGS)\n  set(REQUIRED_INCDIRS)\n  set(REQUIRED_LIBDIRS)\n  set(REQUIRED_LIBS)\n\n  # PTSCOTCH\n  if (PTSCOTCH_INCLUDE_DIRS)\n    set(REQUIRED_INCDIRS  \"${PTSCOTCH_INCLUDE_DIRS}\")\n  endif()\n  if (PTSCOTCH_LIBRARY_DIRS)\n    set(REQUIRED_LIBDIRS \"${PTSCOTCH_LIBRARY_DIRS}\")\n  endif()\n  set(REQUIRED_LIBS \"${PTSCOTCH_LIBRARIES}\")\n  # MPI\n  if (MPI_FOUND)\n    if (MPI_C_INCLUDE_PATH)\n      list(APPEND CMAKE_REQUIRED_INCLUDES \"${MPI_C_INCLUDE_PATH}\")\n    endif()\n    if (MPI_C_LINK_FLAGS)\n      if (${MPI_C_LINK_FLAGS} MATCHES \"  -\")\n\tstring(REGEX REPLACE \" -\" \"-\" MPI_C_LINK_FLAGS ${MPI_C_LINK_FLAGS})\n      endif()\n      list(APPEND REQUIRED_LDFLAGS \"${MPI_C_LINK_FLAGS}\")\n    endif()\n    list(APPEND REQUIRED_LIBS \"${MPI_C_LIBRARIES}\")\n  endif()\n  # THREADS\n  if(CMAKE_THREAD_LIBS_INIT)\n    list(APPEND REQUIRED_LIBS \"${CMAKE_THREAD_LIBS_INIT}\")\n  endif()\n  set(Z_LIBRARY \"Z_LIBRARY-NOTFOUND\")\n  find_library(Z_LIBRARY NAMES z)\n  mark_as_advanced(Z_LIBRARY)\n  if(Z_LIBRARY)\n    list(APPEND REQUIRED_LIBS \"-lz\")\n  endif()\n  set(M_LIBRARY \"M_LIBRARY-NOTFOUND\")\n  find_library(M_LIBRARY NAMES m)\n  mark_as_advanced(M_LIBRARY)\n  if(M_LIBRARY)\n    list(APPEND REQUIRED_LIBS \"-lm\")\n  endif()\n  set(RT_LIBRARY \"RT_LIBRARY-NOTFOUND\")\n  find_library(RT_LIBRARY NAMES rt)\n  mark_as_advanced(RT_LIBRARY)\n  if(RT_LIBRARY)\n    list(APPEND REQUIRED_LIBS \"-lrt\")\n  endif()\n\n  # set required libraries for link\n  set(CMAKE_REQUIRED_INCLUDES \"${REQUIRED_INCDIRS}\")\n  set(CMAKE_REQUIRED_LIBRARIES)\n  list(APPEND CMAKE_REQUIRED_LIBRARIES \"${REQUIRED_LDFLAGS}\")\n  foreach(lib_dir ${REQUIRED_LIBDIRS})\n    list(APPEND CMAKE_REQUIRED_LIBRARIES \"-L${lib_dir}\")\n  endforeach()\n  list(APPEND CMAKE_REQUIRED_LIBRARIES \"${REQUIRED_LIBS}\")\n  list(APPEND CMAKE_REQUIRED_FLAGS \"${REQUIRED_FLAGS}\")\n  string(REGEX REPLACE \"^ -\" \"-\" CMAKE_REQUIRED_LIBRARIES \"${CMAKE_REQUIRED_LIBRARIES}\")\n\n  # test link\n  unset(PTSCOTCH_WORKS CACHE)\n  include(CheckFunctionExists)\n  check_function_exists(SCOTCH_dgraphInit PTSCOTCH_WORKS)\n  mark_as_advanced(PTSCOTCH_WORKS)\n\n  if(PTSCOTCH_WORKS)\n    # save link with dependencies\n    set(PTSCOTCH_LIBRARIES_DEP \"${REQUIRED_LIBS}\")\n    set(PTSCOTCH_LIBRARY_DIRS_DEP \"${REQUIRED_LIBDIRS}\")\n    set(PTSCOTCH_INCLUDE_DIRS_DEP \"${REQUIRED_INCDIRS}\")\n    set(PTSCOTCH_LINKER_FLAGS \"${REQUIRED_LDFLAGS}\")\n    list(REMOVE_DUPLICATES PTSCOTCH_LIBRARY_DIRS_DEP)\n    list(REMOVE_DUPLICATES PTSCOTCH_INCLUDE_DIRS_DEP)\n    list(REMOVE_DUPLICATES PTSCOTCH_LINKER_FLAGS)\n  else()\n    if(NOT PTSCOTCH_FIND_QUIETLY)\n      message(STATUS \"Looking for PTSCOTCH : test of SCOTCH_dgraphInit with PTSCOTCH library fails\")\n      message(STATUS \"CMAKE_REQUIRED_LIBRARIES: ${CMAKE_REQUIRED_LIBRARIES}\")\n      message(STATUS \"CMAKE_REQUIRED_INCLUDES: ${CMAKE_REQUIRED_INCLUDES}\")\n      message(STATUS \"Check in CMakeFiles/CMakeError.log to figure out why it fails\")\n    endif()\n  endif()\n  set(CMAKE_REQUIRED_INCLUDES)\n  set(CMAKE_REQUIRED_FLAGS)\n  set(CMAKE_REQUIRED_LIBRARIES)\nendif()\n\nif (PTSCOTCH_LIBRARIES)\n  list(GET PTSCOTCH_LIBRARIES 0 first_lib)\n  get_filename_component(first_lib_path \"${first_lib}\" PATH)\n  if (${first_lib_path} MATCHES \"/lib(32|64)?$\")\n    string(REGEX REPLACE \"/lib(32|64)?$\" \"\" not_cached_dir \"${first_lib_path}\")\n    set(PTSCOTCH_DIR_FOUND \"${not_cached_dir}\" CACHE PATH \"Installation directory of PTSCOTCH library\" FORCE)\n  else()\n    set(PTSCOTCH_DIR_FOUND \"${first_lib_path}\" CACHE PATH \"Installation directory of PTSCOTCH library\" FORCE)\n  endif()\nendif()\nmark_as_advanced(PTSCOTCH_DIR)\nmark_as_advanced(PTSCOTCH_DIR_FOUND)\n\n# Check the size of SCOTCH_Num\n# ---------------------------------\nset(CMAKE_REQUIRED_INCLUDES ${PTSCOTCH_INCLUDE_DIRS})\n\ninclude(CheckCSourceRuns)\n#stdio.h and stdint.h should be included by scotch.h directly\nset(PTSCOTCH_C_TEST_SCOTCH_Num_4 \"\n#include <stdio.h>\n#include <stdint.h>\n#include <ptscotch.h>\nint main(int argc, char **argv) {\n  if (sizeof(SCOTCH_Num) == 4)\n    return 0;\n  else\n    return 1;\n}\n\")\n\nset(PTSCOTCH_C_TEST_SCOTCH_Num_8 \"\n#include <stdio.h>\n#include <stdint.h>\n#include <ptscotch.h>\nint main(int argc, char **argv) {\n  if (sizeof(SCOTCH_Num) == 8)\n    return 0;\n  else\n    return 1;\n}\n\")\ncheck_c_source_runs(\"${PTSCOTCH_C_TEST_SCOTCH_Num_4}\" PTSCOTCH_Num_4)\nif(NOT PTSCOTCH_Num_4)\n  check_c_source_runs(\"${PTSCOTCH_C_TEST_SCOTCH_Num_8}\" PTSCOTCH_Num_8)\n  if(NOT PTSCOTCH_Num_8)\n    set(PTSCOTCH_INTSIZE -1)\n  else()\n    set(PTSCOTCH_INTSIZE 8)\n  endif()\nelse()\n  set(PTSCOTCH_INTSIZE 4)\nendif()\nset(CMAKE_REQUIRED_INCLUDES \"\")\n\n# check that PTSCOTCH has been found\n# ---------------------------------\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(PTSCOTCH DEFAULT_MSG\n  PTSCOTCH_LIBRARIES\n  PTSCOTCH_WORKS)\n#\n# TODO: Add possibility to check for specific functions in the library\n#\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindPastix.cmake",
    "content": "###\n#\n# @copyright (c) 2009-2014 The University of Tennessee and The University\n#                          of Tennessee Research Foundation.\n#                          All rights reserved.\n# @copyright (c) 2012-2014 Inria. All rights reserved.\n# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved.\n#\n###\n#\n# - Find PASTIX include dirs and libraries\n# Use this module by invoking find_package with the form:\n#  find_package(PASTIX\n#               [REQUIRED] # Fail with error if pastix is not found\n#               [COMPONENTS <comp1> <comp2> ...] # dependencies\n#              )\n#\n#  PASTIX depends on the following libraries:\n#   - Threads, m, rt\n#   - MPI\n#   - HWLOC\n#   - BLAS\n#\n#  COMPONENTS are optional libraries PASTIX could be linked with,\n#  Use it to drive detection of a specific compilation chain\n#  COMPONENTS can be some of the following:\n#   - MPI: to activate detection of the parallel MPI version (default)\n#        it looks for Threads, HWLOC, BLAS, MPI and ScaLAPACK libraries\n#   - SEQ: to activate detection of the sequential version (exclude MPI version)\n#   - STARPU: to activate detection of StarPU version\n#   it looks for MPI version of StarPU (default behaviour)\n#   if SEQ and STARPU are given, it looks for a StarPU without MPI\n#   - STARPU_CUDA: to activate detection of StarPU with CUDA\n#   - STARPU_FXT: to activate detection of StarPU with FxT\n#   - SCOTCH: to activate detection of PASTIX linked with SCOTCH\n#   - PTSCOTCH: to activate detection of PASTIX linked with SCOTCH\n#   - METIS: to activate detection of PASTIX linked with SCOTCH\n#\n# This module finds headers and pastix library.\n# Results are reported in variables:\n#  PASTIX_FOUND            - True if headers and requested libraries were found\n#  PASTIX_LINKER_FLAGS     - list of required linker flags (excluding -l and -L)\n#  PASTIX_INCLUDE_DIRS     - pastix include directories\n#  PASTIX_LIBRARY_DIRS     - Link directories for pastix libraries\n#  PASTIX_LIBRARIES        - pastix libraries\n#  PASTIX_INCLUDE_DIRS_DEP - pastix + dependencies include directories\n#  PASTIX_LIBRARY_DIRS_DEP - pastix + dependencies link directories\n#  PASTIX_LIBRARIES_DEP    - pastix libraries + dependencies\n#\n# The user can give specific paths where to find the libraries adding cmake\n# options at configure (ex: cmake path/to/project -DPASTIX_DIR=path/to/pastix):\n#  PASTIX_DIR              - Where to find the base directory of pastix\n#  PASTIX_INCDIR           - Where to find the header files\n#  PASTIX_LIBDIR           - Where to find the library files\n# The module can also look for the following environment variables if paths\n# are not given as cmake variable: PASTIX_DIR, PASTIX_INCDIR, PASTIX_LIBDIR\n\n#=============================================================================\n# Copyright 2012-2013 Inria\n# Copyright 2012-2013 Emmanuel Agullo\n# Copyright 2012-2013 Mathieu Faverge\n# Copyright 2012      Cedric Castagnede\n# Copyright 2013      Florent Pruvost\n#\n# Distributed under the OSI-approved BSD License (the \"License\");\n# see accompanying file MORSE-Copyright.txt for details.\n#\n# This software is distributed WITHOUT ANY WARRANTY; without even the\n# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.\n# See the License for more information.\n#=============================================================================\n# (To distribute this file outside of Morse, substitute the full\n#  License text for the above reference.)\n\n\nif (NOT PASTIX_FOUND)\n  set(PASTIX_DIR \"\" CACHE PATH \"Installation directory of PASTIX library\")\n  if (NOT PASTIX_FIND_QUIETLY)\n    message(STATUS \"A cache variable, namely PASTIX_DIR, has been set to specify the install directory of PASTIX\")\n  endif()\nendif()\n\n# Set the version to find\nset(PASTIX_LOOK_FOR_MPI ON)\nset(PASTIX_LOOK_FOR_SEQ OFF)\nset(PASTIX_LOOK_FOR_STARPU OFF)\nset(PASTIX_LOOK_FOR_STARPU_CUDA OFF)\nset(PASTIX_LOOK_FOR_STARPU_FXT OFF)\nset(PASTIX_LOOK_FOR_SCOTCH ON)\nset(PASTIX_LOOK_FOR_PTSCOTCH OFF)\nset(PASTIX_LOOK_FOR_METIS OFF)\n\nif( PASTIX_FIND_COMPONENTS )\n  foreach( component ${PASTIX_FIND_COMPONENTS} )\n    if (${component} STREQUAL \"SEQ\")\n      # means we look for the sequential version of PaStiX (without MPI)\n      set(PASTIX_LOOK_FOR_SEQ ON)\n      set(PASTIX_LOOK_FOR_MPI OFF)\n    endif()\n    if (${component} STREQUAL \"MPI\")\n      # means we look for the MPI version of PaStiX (default)\n      set(PASTIX_LOOK_FOR_SEQ OFF)\n      set(PASTIX_LOOK_FOR_MPI ON)\n    endif()\n    if (${component} STREQUAL \"STARPU\")\n      # means we look for PaStiX with StarPU\n      set(PASTIX_LOOK_FOR_STARPU ON)\n    endif()\n    if (${component} STREQUAL \"STARPU_CUDA\")\n      # means we look for PaStiX with StarPU + CUDA\n      set(PASTIX_LOOK_FOR_STARPU ON)\n      set(PASTIX_LOOK_FOR_STARPU_CUDA ON)\n    endif()\n    if (${component} STREQUAL \"STARPU_FXT\")\n      # means we look for PaStiX with StarPU + FxT\n      set(PASTIX_LOOK_FOR_STARPU_FXT ON)\n    endif()\n    if (${component} STREQUAL \"SCOTCH\")\n      set(PASTIX_LOOK_FOR_SCOTCH ON)\n    endif()\n    if (${component} STREQUAL \"SCOTCH\")\n      set(PASTIX_LOOK_FOR_PTSCOTCH ON)\n    endif()\n    if (${component} STREQUAL \"METIS\")\n      set(PASTIX_LOOK_FOR_METIS ON)\n    endif()\n  endforeach()\nendif()\n\n# Dependencies detection\n# ----------------------\n\n\n# Required dependencies\n# ---------------------\n\nif (NOT PASTIX_FIND_QUIETLY)\n  message(STATUS \"Looking for PASTIX - Try to detect pthread\")\nendif()\nif (PASTIX_FIND_REQUIRED)\n  find_package(Threads REQUIRED QUIET)\nelse()\n  find_package(Threads QUIET)\nendif()\nset(PASTIX_EXTRA_LIBRARIES \"\")\nif( THREADS_FOUND )\n  list(APPEND PASTIX_EXTRA_LIBRARIES ${CMAKE_THREAD_LIBS_INIT})\nendif ()\n\n# Add math library to the list of extra\n# it normally exists on all common systems provided with a C compiler\nif (NOT PASTIX_FIND_QUIETLY)\n  message(STATUS \"Looking for PASTIX - Try to detect libm\")\nendif()\nset(PASTIX_M_LIBRARIES \"\")\nif(UNIX OR WIN32)\n  find_library(\n    PASTIX_M_m_LIBRARY\n    NAMES m\n    )\n  mark_as_advanced(PASTIX_M_m_LIBRARY)\n  if (PASTIX_M_m_LIBRARY)\n    list(APPEND PASTIX_M_LIBRARIES \"${PASTIX_M_m_LIBRARY}\")\n    list(APPEND PASTIX_EXTRA_LIBRARIES \"${PASTIX_M_m_LIBRARY}\")\n  else()\n    if (PASTIX_FIND_REQUIRED)\n      message(FATAL_ERROR \"Could NOT find libm on your system.\"\n\t\"Are you sure to a have a C compiler installed?\")\n    endif()\n  endif()\nendif()\n\n# Try to find librt (libposix4 - POSIX.1b Realtime Extensions library)\n# on Unix systems except Apple ones because it does not exist on it\nif (NOT PASTIX_FIND_QUIETLY)\n  message(STATUS \"Looking for PASTIX - Try to detect librt\")\nendif()\nset(PASTIX_RT_LIBRARIES \"\")\nif(UNIX AND NOT APPLE)\n  find_library(\n    PASTIX_RT_rt_LIBRARY\n    NAMES rt\n    )\n  mark_as_advanced(PASTIX_RT_rt_LIBRARY)\n  if (PASTIX_RT_rt_LIBRARY)\n    list(APPEND PASTIX_RT_LIBRARIES \"${PASTIX_RT_rt_LIBRARY}\")\n    list(APPEND PASTIX_EXTRA_LIBRARIES \"${PASTIX_RT_rt_LIBRARY}\")\n  else()\n    if (PASTIX_FIND_REQUIRED)\n      message(FATAL_ERROR \"Could NOT find librt on your system\")\n    endif()\n  endif()\nendif()\n\n# PASTIX depends on HWLOC\n#------------------------\nif (NOT PASTIX_FIND_QUIETLY)\n  message(STATUS \"Looking for PASTIX - Try to detect HWLOC\")\nendif()\nif (PASTIX_FIND_REQUIRED)\n  find_package(HWLOC REQUIRED QUIET)\nelse()\n  find_package(HWLOC QUIET)\nendif()\n\n# PASTIX depends on BLAS\n#-----------------------\nif (NOT PASTIX_FIND_QUIETLY)\n  message(STATUS \"Looking for PASTIX - Try to detect BLAS\")\nendif()\nif (PASTIX_FIND_REQUIRED)\n  find_package(BLASEXT REQUIRED QUIET)\nelse()\n  find_package(BLASEXT QUIET)\nendif()\n\n# Optional dependencies\n# ---------------------\n\n# PASTIX may depend on MPI\n#-------------------------\nif (NOT MPI_FOUND AND PASTIX_LOOK_FOR_MPI)\n  if (NOT PASTIX_FIND_QUIETLY)\n    message(STATUS \"Looking for PASTIX - Try to detect MPI\")\n  endif()\n  # allows to use an external mpi compilation by setting compilers with\n  # -DMPI_C_COMPILER=path/to/mpicc -DMPI_Fortran_COMPILER=path/to/mpif90\n  # at cmake configure\n  if(NOT MPI_C_COMPILER)\n    set(MPI_C_COMPILER mpicc)\n  endif()\n  if (PASTIX_FIND_REQUIRED AND PASTIX_FIND_REQUIRED_MPI)\n    find_package(MPI REQUIRED QUIET)\n  else()\n    find_package(MPI QUIET)\n  endif()\n  if (MPI_FOUND)\n    mark_as_advanced(MPI_LIBRARY)\n    mark_as_advanced(MPI_EXTRA_LIBRARY)\n  endif()\nendif ()\n\n# PASTIX may depend on STARPU\n#----------------------------\nif( NOT STARPU_FOUND AND PASTIX_LOOK_FOR_STARPU)\n\n  if (NOT PASTIX_FIND_QUIETLY)\n    message(STATUS \"Looking for PASTIX - Try to detect StarPU\")\n  endif()\n\n  set(PASTIX_STARPU_VERSION \"1.1\" CACHE STRING \"oldest STARPU version desired\")\n\n  # create list of components in order to make a single call to find_package(starpu...)\n  # we explicitly need a StarPU version built with hwloc\n  set(STARPU_COMPONENT_LIST \"HWLOC\")\n\n  # StarPU may depend on MPI\n  # allows to use an external mpi compilation by setting compilers with\n  # -DMPI_C_COMPILER=path/to/mpicc -DMPI_Fortran_COMPILER=path/to/mpif90\n  # at cmake configure\n  if (PASTIX_LOOK_FOR_MPI)\n    if(NOT MPI_C_COMPILER)\n      set(MPI_C_COMPILER mpicc)\n    endif()\n    list(APPEND STARPU_COMPONENT_LIST \"MPI\")\n  endif()\n  if (PASTIX_LOOK_FOR_STARPU_CUDA)\n    list(APPEND STARPU_COMPONENT_LIST \"CUDA\")\n  endif()\n  if (PASTIX_LOOK_FOR_STARPU_FXT)\n    list(APPEND STARPU_COMPONENT_LIST \"FXT\")\n  endif()\n  # set the list of optional dependencies we may discover\n  if (PASTIX_FIND_REQUIRED AND PASTIX_FIND_REQUIRED_STARPU)\n    find_package(STARPU ${PASTIX_STARPU_VERSION} REQUIRED\n      COMPONENTS ${STARPU_COMPONENT_LIST})\n  else()\n    find_package(STARPU ${PASTIX_STARPU_VERSION}\n      COMPONENTS ${STARPU_COMPONENT_LIST})\n  endif()\n\nendif()\n\n# PASTIX may depends on SCOTCH\n#-----------------------------\nif (NOT SCOTCH_FOUND AND PASTIX_LOOK_FOR_SCOTCH)\n  if (NOT PASTIX_FIND_QUIETLY)\n    message(STATUS \"Looking for PASTIX - Try to detect SCOTCH\")\n  endif()\n  if (PASTIX_FIND_REQUIRED AND PASTIX_FIND_REQUIRED_SCOTCH)\n    find_package(SCOTCH REQUIRED QUIET)\n  else()\n    find_package(SCOTCH QUIET)\n  endif()\nendif()\n\n# PASTIX may depends on PTSCOTCH\n#-------------------------------\nif (NOT PTSCOTCH_FOUND AND PASTIX_LOOK_FOR_PTSCOTCH)\n  if (NOT PASTIX_FIND_QUIETLY)\n    message(STATUS \"Looking for PASTIX - Try to detect PTSCOTCH\")\n  endif()\n  if (PASTIX_FIND_REQUIRED AND PASTIX_FIND_REQUIRED_PTSCOTCH)\n    find_package(PTSCOTCH REQUIRED QUIET)\n  else()\n    find_package(PTSCOTCH QUIET)\n  endif()\nendif()\n\n# PASTIX may depends on METIS\n#----------------------------\nif (NOT METIS_FOUND AND PASTIX_LOOK_FOR_METIS)\n  if (NOT PASTIX_FIND_QUIETLY)\n    message(STATUS \"Looking for PASTIX - Try to detect METIS\")\n  endif()\n  if (PASTIX_FIND_REQUIRED AND PASTIX_FIND_REQUIRED_METIS)\n    find_package(METIS REQUIRED QUIET)\n  else()\n    find_package(METIS QUIET)\n  endif()\nendif()\n\n# Error if pastix required and no partitioning lib found\nif (PASTIX_FIND_REQUIRED AND NOT SCOTCH_FOUND AND NOT PTSCOTCH_FOUND AND NOT METIS_FOUND)\n  message(FATAL_ERROR \"Could NOT find any partitioning library on your system\"\n    \" (install scotch, ptscotch or metis)\")\nendif()\n\n\n# Looking for PaStiX\n# ------------------\n\n# Looking for include\n# -------------------\n\n# Add system include paths to search include\n# ------------------------------------------\nunset(_inc_env)\nset(ENV_PASTIX_DIR \"$ENV{PASTIX_DIR}\")\nset(ENV_PASTIX_INCDIR \"$ENV{PASTIX_INCDIR}\")\nif(ENV_PASTIX_INCDIR)\n  list(APPEND _inc_env \"${ENV_PASTIX_INCDIR}\")\nelseif(ENV_PASTIX_DIR)\n  list(APPEND _inc_env \"${ENV_PASTIX_DIR}\")\n  list(APPEND _inc_env \"${ENV_PASTIX_DIR}/include\")\n  list(APPEND _inc_env \"${ENV_PASTIX_DIR}/include/pastix\")\nelse()\n  if(WIN32)\n    string(REPLACE \":\" \";\" _inc_env \"$ENV{INCLUDE}\")\n  else()\n    string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{C_INCLUDE_PATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{CPATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE_PATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n  endif()\nendif()\nlist(APPEND _inc_env \"${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}\")\nlist(APPEND _inc_env \"${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}\")\nlist(REMOVE_DUPLICATES _inc_env)\n\n\n# Try to find the pastix header in the given paths\n# ---------------------------------------------------\n# call cmake macro to find the header path\nif(PASTIX_INCDIR)\n  set(PASTIX_pastix.h_DIRS \"PASTIX_pastix.h_DIRS-NOTFOUND\")\n  find_path(PASTIX_pastix.h_DIRS\n    NAMES pastix.h\n    HINTS ${PASTIX_INCDIR})\nelse()\n  if(PASTIX_DIR)\n    set(PASTIX_pastix.h_DIRS \"PASTIX_pastix.h_DIRS-NOTFOUND\")\n    find_path(PASTIX_pastix.h_DIRS\n      NAMES pastix.h\n      HINTS ${PASTIX_DIR}\n      PATH_SUFFIXES \"include\" \"include/pastix\")\n  else()\n    set(PASTIX_pastix.h_DIRS \"PASTIX_pastix.h_DIRS-NOTFOUND\")\n    find_path(PASTIX_pastix.h_DIRS\n      NAMES pastix.h\n      HINTS ${_inc_env}\n      PATH_SUFFIXES \"pastix\")\n  endif()\nendif()\nmark_as_advanced(PASTIX_pastix.h_DIRS)\n\n# If found, add path to cmake variable\n# ------------------------------------\nif (PASTIX_pastix.h_DIRS)\n  set(PASTIX_INCLUDE_DIRS \"${PASTIX_pastix.h_DIRS}\")\nelse ()\n  set(PASTIX_INCLUDE_DIRS \"PASTIX_INCLUDE_DIRS-NOTFOUND\")\n  if(NOT PASTIX_FIND_QUIETLY)\n    message(STATUS \"Looking for pastix -- pastix.h not found\")\n  endif()\nendif()\n\n\n# Looking for lib\n# ---------------\n\n# Add system library paths to search lib\n# --------------------------------------\nunset(_lib_env)\nset(ENV_PASTIX_LIBDIR \"$ENV{PASTIX_LIBDIR}\")\nif(ENV_PASTIX_LIBDIR)\n  list(APPEND _lib_env \"${ENV_PASTIX_LIBDIR}\")\nelseif(ENV_PASTIX_DIR)\n  list(APPEND _lib_env \"${ENV_PASTIX_DIR}\")\n  list(APPEND _lib_env \"${ENV_PASTIX_DIR}/lib\")\nelse()\n  if(WIN32)\n    string(REPLACE \":\" \";\" _lib_env \"$ENV{LIB}\")\n  else()\n    if(APPLE)\n      string(REPLACE \":\" \";\" _lib_env \"$ENV{DYLD_LIBRARY_PATH}\")\n    else()\n      string(REPLACE \":\" \";\" _lib_env \"$ENV{LD_LIBRARY_PATH}\")\n    endif()\n    list(APPEND _lib_env \"${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}\")\n    list(APPEND _lib_env \"${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}\")\n  endif()\nendif()\nlist(REMOVE_DUPLICATES _lib_env)\n\n# Try to find the pastix lib in the given paths\n# ------------------------------------------------\n\n# create list of libs to find\nset(PASTIX_libs_to_find \"pastix_murge;pastix\")\n\n# call cmake macro to find the lib path\nif(PASTIX_LIBDIR)\n  foreach(pastix_lib ${PASTIX_libs_to_find})\n    set(PASTIX_${pastix_lib}_LIBRARY \"PASTIX_${pastix_lib}_LIBRARY-NOTFOUND\")\n    find_library(PASTIX_${pastix_lib}_LIBRARY\n      NAMES ${pastix_lib}\n      HINTS ${PASTIX_LIBDIR})\n  endforeach()\nelse()\n  if(PASTIX_DIR)\n    foreach(pastix_lib ${PASTIX_libs_to_find})\n      set(PASTIX_${pastix_lib}_LIBRARY \"PASTIX_${pastix_lib}_LIBRARY-NOTFOUND\")\n      find_library(PASTIX_${pastix_lib}_LIBRARY\n\tNAMES ${pastix_lib}\n\tHINTS ${PASTIX_DIR}\n\tPATH_SUFFIXES lib lib32 lib64)\n    endforeach()\n  else()\n    foreach(pastix_lib ${PASTIX_libs_to_find})\n      set(PASTIX_${pastix_lib}_LIBRARY \"PASTIX_${pastix_lib}_LIBRARY-NOTFOUND\")\n      find_library(PASTIX_${pastix_lib}_LIBRARY\n\tNAMES ${pastix_lib}\n\tHINTS ${_lib_env})\n    endforeach()\n  endif()\nendif()\n\n# If found, add path to cmake variable\n# ------------------------------------\nforeach(pastix_lib ${PASTIX_libs_to_find})\n\n  get_filename_component(${pastix_lib}_lib_path ${PASTIX_${pastix_lib}_LIBRARY} PATH)\n  # set cmake variables (respects naming convention)\n  if (PASTIX_LIBRARIES)\n    list(APPEND PASTIX_LIBRARIES \"${PASTIX_${pastix_lib}_LIBRARY}\")\n  else()\n    set(PASTIX_LIBRARIES \"${PASTIX_${pastix_lib}_LIBRARY}\")\n  endif()\n  if (PASTIX_LIBRARY_DIRS)\n    list(APPEND PASTIX_LIBRARY_DIRS \"${${pastix_lib}_lib_path}\")\n  else()\n    set(PASTIX_LIBRARY_DIRS \"${${pastix_lib}_lib_path}\")\n  endif()\n  mark_as_advanced(PASTIX_${pastix_lib}_LIBRARY)\n\nendforeach()\n\n# check a function to validate the find\nif(PASTIX_LIBRARIES)\n\n  set(REQUIRED_LDFLAGS)\n  set(REQUIRED_INCDIRS)\n  set(REQUIRED_LIBDIRS)\n  set(REQUIRED_LIBS)\n\n  # PASTIX\n  if (PASTIX_INCLUDE_DIRS)\n    set(REQUIRED_INCDIRS \"${PASTIX_INCLUDE_DIRS}\")\n  endif()\n  foreach(libdir ${PASTIX_LIBRARY_DIRS})\n    if (libdir)\n      list(APPEND REQUIRED_LIBDIRS \"${libdir}\")\n    endif()\n  endforeach()\n  set(REQUIRED_LIBS \"${PASTIX_LIBRARIES}\")\n  # STARPU\n  if (PASTIX_LOOK_FOR_STARPU AND STARPU_FOUND)\n    if (STARPU_INCLUDE_DIRS_DEP)\n      list(APPEND REQUIRED_INCDIRS \"${STARPU_INCLUDE_DIRS_DEP}\")\n    elseif (STARPU_INCLUDE_DIRS)\n      list(APPEND REQUIRED_INCDIRS \"${STARPU_INCLUDE_DIRS}\")\n    endif()\n    if(STARPU_LIBRARY_DIRS_DEP)\n      list(APPEND REQUIRED_LIBDIRS \"${STARPU_LIBRARY_DIRS_DEP}\")\n    elseif(STARPU_LIBRARY_DIRS)\n      list(APPEND REQUIRED_LIBDIRS \"${STARPU_LIBRARY_DIRS}\")\n    endif()\n    if (STARPU_LIBRARIES_DEP)\n      list(APPEND REQUIRED_LIBS \"${STARPU_LIBRARIES_DEP}\")\n    elseif (STARPU_LIBRARIES)\n      foreach(lib ${STARPU_LIBRARIES})\n\tif (EXISTS ${lib} OR ${lib} MATCHES \"^-\")\n\t  list(APPEND REQUIRED_LIBS \"${lib}\")\n\telse()\n\t  list(APPEND REQUIRED_LIBS \"-l${lib}\")\n\tendif()\n      endforeach()\n    endif()\n  endif()\n  # CUDA\n  if (PASTIX_LOOK_FOR_STARPU_CUDA AND CUDA_FOUND)\n    if (CUDA_INCLUDE_DIRS)\n      list(APPEND REQUIRED_INCDIRS \"${CUDA_INCLUDE_DIRS}\")\n    endif()\n    foreach(libdir ${CUDA_LIBRARY_DIRS})\n      if (libdir)\n\tlist(APPEND REQUIRED_LIBDIRS \"${libdir}\")\n      endif()\n    endforeach()\n    list(APPEND REQUIRED_LIBS \"${CUDA_CUBLAS_LIBRARIES};${CUDA_LIBRARIES}\")\n  endif()\n  # MPI\n  if (PASTIX_LOOK_FOR_MPI AND MPI_FOUND)\n    if (MPI_C_INCLUDE_PATH)\n      list(APPEND REQUIRED_INCDIRS \"${MPI_C_INCLUDE_PATH}\")\n    endif()\n    if (MPI_C_LINK_FLAGS)\n      if (${MPI_C_LINK_FLAGS} MATCHES \"  -\")\n\tstring(REGEX REPLACE \" -\" \"-\" MPI_C_LINK_FLAGS ${MPI_C_LINK_FLAGS})\n      endif()\n      list(APPEND REQUIRED_LDFLAGS \"${MPI_C_LINK_FLAGS}\")\n    endif()\n    list(APPEND REQUIRED_LIBS \"${MPI_C_LIBRARIES}\")\n  endif()\n  # HWLOC\n  if (HWLOC_FOUND)\n    if (HWLOC_INCLUDE_DIRS)\n      list(APPEND REQUIRED_INCDIRS \"${HWLOC_INCLUDE_DIRS}\")\n    endif()\n    foreach(libdir ${HWLOC_LIBRARY_DIRS})\n      if (libdir)\n\tlist(APPEND REQUIRED_LIBDIRS \"${libdir}\")\n      endif()\n    endforeach()\n    foreach(lib ${HWLOC_LIBRARIES})\n      if (EXISTS ${lib} OR ${lib} MATCHES \"^-\")\n\tlist(APPEND REQUIRED_LIBS \"${lib}\")\n      else()\n\tlist(APPEND REQUIRED_LIBS \"-l${lib}\")\n      endif()\n    endforeach()\n  endif()\n  # BLAS\n  if (BLAS_FOUND)\n    if (BLAS_INCLUDE_DIRS)\n      list(APPEND REQUIRED_INCDIRS \"${BLAS_INCLUDE_DIRS}\")\n    endif()\n    foreach(libdir ${BLAS_LIBRARY_DIRS})\n      if (libdir)\n\tlist(APPEND REQUIRED_LIBDIRS \"${libdir}\")\n      endif()\n    endforeach()\n    list(APPEND REQUIRED_LIBS \"${BLAS_LIBRARIES}\")\n    if (BLAS_LINKER_FLAGS)\n      list(APPEND REQUIRED_LDFLAGS \"${BLAS_LINKER_FLAGS}\")\n    endif()\n  endif()\n  # SCOTCH\n  if (PASTIX_LOOK_FOR_SCOTCH AND SCOTCH_FOUND)\n    if (SCOTCH_INCLUDE_DIRS)\n      list(APPEND REQUIRED_INCDIRS \"${SCOTCH_INCLUDE_DIRS}\")\n    endif()\n    foreach(libdir ${SCOTCH_LIBRARY_DIRS})\n      if (libdir)\n\tlist(APPEND REQUIRED_LIBDIRS \"${libdir}\")\n      endif()\n    endforeach()\n    list(APPEND REQUIRED_LIBS \"${SCOTCH_LIBRARIES}\")\n  endif()\n  # PTSCOTCH\n  if (PASTIX_LOOK_FOR_PTSCOTCH AND PTSCOTCH_FOUND)\n    if (PTSCOTCH_INCLUDE_DIRS)\n      list(APPEND REQUIRED_INCDIRS \"${PTSCOTCH_INCLUDE_DIRS}\")\n    endif()\n    foreach(libdir ${PTSCOTCH_LIBRARY_DIRS})\n      if (libdir)\n\tlist(APPEND REQUIRED_LIBDIRS \"${libdir}\")\n      endif()\n    endforeach()\n    list(APPEND REQUIRED_LIBS \"${PTSCOTCH_LIBRARIES}\")\n  endif()\n  # METIS\n  if (PASTIX_LOOK_FOR_METIS AND METIS_FOUND)\n    if (METIS_INCLUDE_DIRS)\n      list(APPEND REQUIRED_INCDIRS \"${METIS_INCLUDE_DIRS}\")\n    endif()\n    foreach(libdir ${METIS_LIBRARY_DIRS})\n      if (libdir)\n\tlist(APPEND REQUIRED_LIBDIRS \"${libdir}\")\n      endif()\n    endforeach()\n    list(APPEND REQUIRED_LIBS \"${METIS_LIBRARIES}\")\n  endif()\n  # Fortran\n  if (CMAKE_C_COMPILER_ID MATCHES \"GNU\")\n    find_library(\n      FORTRAN_gfortran_LIBRARY\n      NAMES gfortran\n      HINTS ${_lib_env}\n      )\n    mark_as_advanced(FORTRAN_gfortran_LIBRARY)\n    if (FORTRAN_gfortran_LIBRARY)\n      list(APPEND REQUIRED_LIBS \"${FORTRAN_gfortran_LIBRARY}\")\n    endif()\n  elseif (CMAKE_C_COMPILER_ID MATCHES \"Intel\")\n    find_library(\n      FORTRAN_ifcore_LIBRARY\n      NAMES ifcore\n      HINTS ${_lib_env}\n      )\n    mark_as_advanced(FORTRAN_ifcore_LIBRARY)\n    if (FORTRAN_ifcore_LIBRARY)\n      list(APPEND REQUIRED_LIBS \"${FORTRAN_ifcore_LIBRARY}\")\n    endif()\n  endif()\n  # EXTRA LIBS such that pthread, m, rt\n  list(APPEND REQUIRED_LIBS ${PASTIX_EXTRA_LIBRARIES})\n\n  # set required libraries for link\n  set(CMAKE_REQUIRED_INCLUDES \"${REQUIRED_INCDIRS}\")\n  set(CMAKE_REQUIRED_LIBRARIES)\n  list(APPEND CMAKE_REQUIRED_LIBRARIES \"${REQUIRED_LDFLAGS}\")\n  foreach(lib_dir ${REQUIRED_LIBDIRS})\n    list(APPEND CMAKE_REQUIRED_LIBRARIES \"-L${lib_dir}\")\n  endforeach()\n  list(APPEND CMAKE_REQUIRED_LIBRARIES \"${REQUIRED_LIBS}\")\n  list(APPEND CMAKE_REQUIRED_FLAGS \"${REQUIRED_FLAGS}\")\n  string(REGEX REPLACE \"^ -\" \"-\" CMAKE_REQUIRED_LIBRARIES \"${CMAKE_REQUIRED_LIBRARIES}\")\n\n  # test link\n  unset(PASTIX_WORKS CACHE)\n  include(CheckFunctionExists)\n  check_function_exists(pastix PASTIX_WORKS)\n  mark_as_advanced(PASTIX_WORKS)\n\n  if(PASTIX_WORKS)\n    # save link with dependencies\n    set(PASTIX_LIBRARIES_DEP \"${REQUIRED_LIBS}\")\n    set(PASTIX_LIBRARY_DIRS_DEP \"${REQUIRED_LIBDIRS}\")\n    set(PASTIX_INCLUDE_DIRS_DEP \"${REQUIRED_INCDIRS}\")\n    set(PASTIX_LINKER_FLAGS \"${REQUIRED_LDFLAGS}\")\n    list(REMOVE_DUPLICATES PASTIX_LIBRARY_DIRS_DEP)\n    list(REMOVE_DUPLICATES PASTIX_INCLUDE_DIRS_DEP)\n    list(REMOVE_DUPLICATES PASTIX_LINKER_FLAGS)\n  else()\n    if(NOT PASTIX_FIND_QUIETLY)\n      message(STATUS \"Looking for PASTIX : test of pastix() fails\")\n      message(STATUS \"CMAKE_REQUIRED_LIBRARIES: ${CMAKE_REQUIRED_LIBRARIES}\")\n      message(STATUS \"CMAKE_REQUIRED_INCLUDES: ${CMAKE_REQUIRED_INCLUDES}\")\n      message(STATUS \"Check in CMakeFiles/CMakeError.log to figure out why it fails\")\n      message(STATUS \"Maybe PASTIX is linked with specific libraries. \"\n\t\"Have you tried with COMPONENTS (MPI/SEQ, STARPU, STARPU_CUDA, SCOTCH, PTSCOTCH, METIS)? \"\n\t\"See the explanation in FindPASTIX.cmake.\")\n    endif()\n  endif()\n  set(CMAKE_REQUIRED_INCLUDES)\n  set(CMAKE_REQUIRED_FLAGS)\n  set(CMAKE_REQUIRED_LIBRARIES)\nendif()\n\nif (PASTIX_LIBRARIES)\n  list(GET PASTIX_LIBRARIES 0 first_lib)\n  get_filename_component(first_lib_path \"${first_lib}\" PATH)\n  if (${first_lib_path} MATCHES \"/lib(32|64)?$\")\n    string(REGEX REPLACE \"/lib(32|64)?$\" \"\" not_cached_dir \"${first_lib_path}\")\n    set(PASTIX_DIR_FOUND \"${not_cached_dir}\" CACHE PATH \"Installation directory of PASTIX library\" FORCE)\n  else()\n    set(PASTIX_DIR_FOUND \"${first_lib_path}\" CACHE PATH \"Installation directory of PASTIX library\" FORCE)\n  endif()\nendif()\nmark_as_advanced(PASTIX_DIR)\nmark_as_advanced(PASTIX_DIR_FOUND)\n\n# check that PASTIX has been found\n# ---------------------------------\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(PASTIX DEFAULT_MSG\n  PASTIX_LIBRARIES\n  PASTIX_WORKS)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindSPQR.cmake",
    "content": "# SPQR lib usually requires linking to a blas and lapack library.\n# It is up to the user of this module to find a BLAS and link to it.\n\n# SPQR lib requires Cholmod, colamd and amd as well. \n# FindCholmod.cmake can be used to find those packages before finding spqr\n\nif (SPQR_INCLUDES AND SPQR_LIBRARIES)\n  set(SPQR_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(SPQR_INCLUDES\n  NAMES\n  SuiteSparseQR.hpp\n  PATHS\n  $ENV{SPQRDIR}\n  ${INCLUDE_INSTALL_DIR}\n  PATH_SUFFIXES\n  suitesparse\n  ufsparse\n)\n\nfind_library(SPQR_LIBRARIES spqr $ENV{SPQRDIR} ${LIB_INSTALL_DIR})\n\nif(SPQR_LIBRARIES)\n\n  find_library(SUITESPARSE_LIBRARY SuiteSparse PATHS $ENV{SPQRDIR} ${LIB_INSTALL_DIR})\n  if (SUITESPARSE_LIBRARY)\n    set(SPQR_LIBRARIES ${SPQR_LIBRARIES} ${SUITESPARSE_LIBRARY})\n  endif()\n\n  find_library(CHOLMOD_LIBRARY cholmod PATHS $ENV{UMFPACK_LIBDIR} $ENV{UMFPACKDIR} ${LIB_INSTALL_DIR})\n  if(CHOLMOD_LIBRARY)\n    set(SPQR_LIBRARIES ${SPQR_LIBRARIES} ${CHOLMOD_LIBRARY})\n  endif()\n  \nendif()\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(SPQR DEFAULT_MSG SPQR_INCLUDES SPQR_LIBRARIES)\n\nmark_as_advanced(SPQR_INCLUDES SPQR_LIBRARIES)"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindScotch.cmake",
    "content": "###\n#\n# @copyright (c) 2009-2014 The University of Tennessee and The University\n#                          of Tennessee Research Foundation.\n#                          All rights reserved.\n# @copyright (c) 2012-2014 Inria. All rights reserved.\n# @copyright (c) 2012-2014 Bordeaux INP, CNRS (LaBRI UMR 5800), Inria, Univ. Bordeaux. All rights reserved.\n#\n###\n#\n# - Find SCOTCH include dirs and libraries\n# Use this module by invoking find_package with the form:\n#  find_package(SCOTCH\n#               [REQUIRED]             # Fail with error if scotch is not found\n#               [COMPONENTS <comp1> <comp2> ...] # dependencies\n#              )\n#\n#  COMPONENTS can be some of the following:\n#   - ESMUMPS: to activate detection of Scotch with the esmumps interface\n#\n# This module finds headers and scotch library.\n# Results are reported in variables:\n#  SCOTCH_FOUND           - True if headers and requested libraries were found\n#  SCOTCH_INCLUDE_DIRS    - scotch include directories\n#  SCOTCH_LIBRARY_DIRS    - Link directories for scotch libraries\n#  SCOTCH_LIBRARIES       - scotch component libraries to be linked\n#  SCOTCH_INTSIZE         - Number of octets occupied by a SCOTCH_Num\n#\n# The user can give specific paths where to find the libraries adding cmake\n# options at configure (ex: cmake path/to/project -DSCOTCH=path/to/scotch):\n#  SCOTCH_DIR             - Where to find the base directory of scotch\n#  SCOTCH_INCDIR          - Where to find the header files\n#  SCOTCH_LIBDIR          - Where to find the library files\n# The module can also look for the following environment variables if paths\n# are not given as cmake variable: SCOTCH_DIR, SCOTCH_INCDIR, SCOTCH_LIBDIR\n\n#=============================================================================\n# Copyright 2012-2013 Inria\n# Copyright 2012-2013 Emmanuel Agullo\n# Copyright 2012-2013 Mathieu Faverge\n# Copyright 2012      Cedric Castagnede\n# Copyright 2013      Florent Pruvost\n#\n# Distributed under the OSI-approved BSD License (the \"License\");\n# see accompanying file MORSE-Copyright.txt for details.\n#\n# This software is distributed WITHOUT ANY WARRANTY; without even the\n# implied warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.\n# See the License for more information.\n#=============================================================================\n# (To distribute this file outside of Morse, substitute the full\n#  License text for the above reference.)\n\nif (NOT SCOTCH_FOUND)\n  set(SCOTCH_DIR \"\" CACHE PATH \"Installation directory of SCOTCH library\")\n  if (NOT SCOTCH_FIND_QUIETLY)\n    message(STATUS \"A cache variable, namely SCOTCH_DIR, has been set to specify the install directory of SCOTCH\")\n  endif()\nendif()\n\n# Set the version to find\nset(SCOTCH_LOOK_FOR_ESMUMPS OFF)\n\nif( SCOTCH_FIND_COMPONENTS )\n  foreach( component ${SCOTCH_FIND_COMPONENTS} )\n    if (${component} STREQUAL \"ESMUMPS\")\n      # means we look for esmumps library\n      set(SCOTCH_LOOK_FOR_ESMUMPS ON)\n    endif()\n  endforeach()\nendif()\n\n# SCOTCH may depend on Threads, try to find it\nif (NOT THREADS_FOUND)\n  if (SCOTCH_FIND_REQUIRED)\n    find_package(Threads REQUIRED)\n  else()\n    find_package(Threads)\n  endif()\nendif()\n\n# Looking for include\n# -------------------\n\n# Add system include paths to search include\n# ------------------------------------------\nunset(_inc_env)\nset(ENV_SCOTCH_DIR \"$ENV{SCOTCH_DIR}\")\nset(ENV_SCOTCH_INCDIR \"$ENV{SCOTCH_INCDIR}\")\nif(ENV_SCOTCH_INCDIR)\n  list(APPEND _inc_env \"${ENV_SCOTCH_INCDIR}\")\nelseif(ENV_SCOTCH_DIR)\n  list(APPEND _inc_env \"${ENV_SCOTCH_DIR}\")\n  list(APPEND _inc_env \"${ENV_SCOTCH_DIR}/include\")\n  list(APPEND _inc_env \"${ENV_SCOTCH_DIR}/include/scotch\")\nelse()\n  if(WIN32)\n    string(REPLACE \":\" \";\" _inc_env \"$ENV{INCLUDE}\")\n  else()\n    string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{C_INCLUDE_PATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{CPATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n    string(REPLACE \":\" \";\" _path_env \"$ENV{INCLUDE_PATH}\")\n    list(APPEND _inc_env \"${_path_env}\")\n  endif()\nendif()\nlist(APPEND _inc_env \"${CMAKE_PLATFORM_IMPLICIT_INCLUDE_DIRECTORIES}\")\nlist(APPEND _inc_env \"${CMAKE_C_IMPLICIT_INCLUDE_DIRECTORIES}\")\nlist(REMOVE_DUPLICATES _inc_env)\n\n\n# Try to find the scotch header in the given paths\n# -------------------------------------------------\n# call cmake macro to find the header path\nif(SCOTCH_INCDIR)\n  set(SCOTCH_scotch.h_DIRS \"SCOTCH_scotch.h_DIRS-NOTFOUND\")\n  find_path(SCOTCH_scotch.h_DIRS\n    NAMES scotch.h\n    HINTS ${SCOTCH_INCDIR})\nelse()\n  if(SCOTCH_DIR)\n    set(SCOTCH_scotch.h_DIRS \"SCOTCH_scotch.h_DIRS-NOTFOUND\")\n    find_path(SCOTCH_scotch.h_DIRS\n      NAMES scotch.h\n      HINTS ${SCOTCH_DIR}\n      PATH_SUFFIXES \"include\" \"include/scotch\")\n  else()\n    set(SCOTCH_scotch.h_DIRS \"SCOTCH_scotch.h_DIRS-NOTFOUND\")\n    find_path(SCOTCH_scotch.h_DIRS\n      NAMES scotch.h\n      HINTS ${_inc_env}\n      PATH_SUFFIXES \"scotch\")\n  endif()\nendif()\nmark_as_advanced(SCOTCH_scotch.h_DIRS)\n\n# If found, add path to cmake variable\n# ------------------------------------\nif (SCOTCH_scotch.h_DIRS)\n  set(SCOTCH_INCLUDE_DIRS \"${SCOTCH_scotch.h_DIRS}\")\nelse ()\n  set(SCOTCH_INCLUDE_DIRS \"SCOTCH_INCLUDE_DIRS-NOTFOUND\")\n  if (NOT SCOTCH_FIND_QUIETLY)\n    message(STATUS \"Looking for scotch -- scotch.h not found\")\n  endif()\nendif()\nlist(REMOVE_DUPLICATES SCOTCH_INCLUDE_DIRS)\n\n# Looking for lib\n# ---------------\n\n# Add system library paths to search lib\n# --------------------------------------\nunset(_lib_env)\nset(ENV_SCOTCH_LIBDIR \"$ENV{SCOTCH_LIBDIR}\")\nif(ENV_SCOTCH_LIBDIR)\n  list(APPEND _lib_env \"${ENV_SCOTCH_LIBDIR}\")\nelseif(ENV_SCOTCH_DIR)\n  list(APPEND _lib_env \"${ENV_SCOTCH_DIR}\")\n  list(APPEND _lib_env \"${ENV_SCOTCH_DIR}/lib\")\nelse()\n  if(WIN32)\n    string(REPLACE \":\" \";\" _lib_env \"$ENV{LIB}\")\n  else()\n    if(APPLE)\n      string(REPLACE \":\" \";\" _lib_env \"$ENV{DYLD_LIBRARY_PATH}\")\n    else()\n      string(REPLACE \":\" \";\" _lib_env \"$ENV{LD_LIBRARY_PATH}\")\n    endif()\n    list(APPEND _lib_env \"${CMAKE_PLATFORM_IMPLICIT_LINK_DIRECTORIES}\")\n    list(APPEND _lib_env \"${CMAKE_C_IMPLICIT_LINK_DIRECTORIES}\")\n  endif()\nendif()\nlist(REMOVE_DUPLICATES _lib_env)\n\n# Try to find the scotch lib in the given paths\n# ----------------------------------------------\n\nset(SCOTCH_libs_to_find \"scotch;scotcherrexit\")\nif (SCOTCH_LOOK_FOR_ESMUMPS)\n  list(INSERT SCOTCH_libs_to_find 0 \"esmumps\")\nendif()\n\n# call cmake macro to find the lib path\nif(SCOTCH_LIBDIR)\n  foreach(scotch_lib ${SCOTCH_libs_to_find})\n    set(SCOTCH_${scotch_lib}_LIBRARY \"SCOTCH_${scotch_lib}_LIBRARY-NOTFOUND\")\n    find_library(SCOTCH_${scotch_lib}_LIBRARY\n      NAMES ${scotch_lib}\n      HINTS ${SCOTCH_LIBDIR})\n  endforeach()\nelse()\n  if(SCOTCH_DIR)\n    foreach(scotch_lib ${SCOTCH_libs_to_find})\n      set(SCOTCH_${scotch_lib}_LIBRARY \"SCOTCH_${scotch_lib}_LIBRARY-NOTFOUND\")\n      find_library(SCOTCH_${scotch_lib}_LIBRARY\n\tNAMES ${scotch_lib}\n\tHINTS ${SCOTCH_DIR}\n\tPATH_SUFFIXES lib lib32 lib64)\n    endforeach()\n  else()\n    foreach(scotch_lib ${SCOTCH_libs_to_find})\n      set(SCOTCH_${scotch_lib}_LIBRARY \"SCOTCH_${scotch_lib}_LIBRARY-NOTFOUND\")\n      find_library(SCOTCH_${scotch_lib}_LIBRARY\n\tNAMES ${scotch_lib}\n\tHINTS ${_lib_env})\n    endforeach()\n  endif()\nendif()\n\nset(SCOTCH_LIBRARIES \"\")\nset(SCOTCH_LIBRARY_DIRS \"\")\n# If found, add path to cmake variable\n# ------------------------------------\nforeach(scotch_lib ${SCOTCH_libs_to_find})\n\n  if (SCOTCH_${scotch_lib}_LIBRARY)\n    get_filename_component(${scotch_lib}_lib_path \"${SCOTCH_${scotch_lib}_LIBRARY}\" PATH)\n    # set cmake variables\n    list(APPEND SCOTCH_LIBRARIES \"${SCOTCH_${scotch_lib}_LIBRARY}\")\n    list(APPEND SCOTCH_LIBRARY_DIRS \"${${scotch_lib}_lib_path}\")\n  else ()\n    list(APPEND SCOTCH_LIBRARIES \"${SCOTCH_${scotch_lib}_LIBRARY}\")\n    if (NOT SCOTCH_FIND_QUIETLY)\n      message(STATUS \"Looking for scotch -- lib ${scotch_lib} not found\")\n    endif()\n  endif ()\n\n  mark_as_advanced(SCOTCH_${scotch_lib}_LIBRARY)\n\nendforeach()\nlist(REMOVE_DUPLICATES SCOTCH_LIBRARY_DIRS)\n\n# check a function to validate the find\nif(SCOTCH_LIBRARIES)\n\n  set(REQUIRED_INCDIRS)\n  set(REQUIRED_LIBDIRS)\n  set(REQUIRED_LIBS)\n\n  # SCOTCH\n  if (SCOTCH_INCLUDE_DIRS)\n    set(REQUIRED_INCDIRS  \"${SCOTCH_INCLUDE_DIRS}\")\n  endif()\n  if (SCOTCH_LIBRARY_DIRS)\n    set(REQUIRED_LIBDIRS \"${SCOTCH_LIBRARY_DIRS}\")\n  endif()\n  set(REQUIRED_LIBS \"${SCOTCH_LIBRARIES}\")\n  # THREADS\n  if(CMAKE_THREAD_LIBS_INIT)\n    list(APPEND REQUIRED_LIBS \"${CMAKE_THREAD_LIBS_INIT}\")\n  endif()\n  set(Z_LIBRARY \"Z_LIBRARY-NOTFOUND\")\n  find_library(Z_LIBRARY NAMES z)\n  mark_as_advanced(Z_LIBRARY)\n  if(Z_LIBRARY)\n    list(APPEND REQUIRED_LIBS \"-lz\")\n  endif()\n  set(M_LIBRARY \"M_LIBRARY-NOTFOUND\")\n  find_library(M_LIBRARY NAMES m)\n  mark_as_advanced(M_LIBRARY)\n  if(M_LIBRARY)\n    list(APPEND REQUIRED_LIBS \"-lm\")\n  endif()\n  set(RT_LIBRARY \"RT_LIBRARY-NOTFOUND\")\n  find_library(RT_LIBRARY NAMES rt)\n  mark_as_advanced(RT_LIBRARY)\n  if(RT_LIBRARY)\n    list(APPEND REQUIRED_LIBS \"-lrt\")\n  endif()\n\n  # set required libraries for link\n  set(CMAKE_REQUIRED_INCLUDES \"${REQUIRED_INCDIRS}\")\n  set(CMAKE_REQUIRED_LIBRARIES)\n  foreach(lib_dir ${REQUIRED_LIBDIRS})\n    list(APPEND CMAKE_REQUIRED_LIBRARIES \"-L${lib_dir}\")\n  endforeach()\n  list(APPEND CMAKE_REQUIRED_LIBRARIES \"${REQUIRED_LIBS}\")\n  string(REGEX REPLACE \"^ -\" \"-\" CMAKE_REQUIRED_LIBRARIES \"${CMAKE_REQUIRED_LIBRARIES}\")\n\n  # test link\n  unset(SCOTCH_WORKS CACHE)\n  include(CheckFunctionExists)\n  check_function_exists(SCOTCH_graphInit SCOTCH_WORKS)\n  mark_as_advanced(SCOTCH_WORKS)\n\n  if(SCOTCH_WORKS)\n    # save link with dependencies\n    set(SCOTCH_LIBRARIES \"${REQUIRED_LIBS}\")\n  else()\n    if(NOT SCOTCH_FIND_QUIETLY)\n      message(STATUS \"Looking for SCOTCH : test of SCOTCH_graphInit with SCOTCH library fails\")\n      message(STATUS \"CMAKE_REQUIRED_LIBRARIES: ${CMAKE_REQUIRED_LIBRARIES}\")\n      message(STATUS \"CMAKE_REQUIRED_INCLUDES: ${CMAKE_REQUIRED_INCLUDES}\")\n      message(STATUS \"Check in CMakeFiles/CMakeError.log to figure out why it fails\")\n    endif()\n  endif()\n  set(CMAKE_REQUIRED_INCLUDES)\n  set(CMAKE_REQUIRED_FLAGS)\n  set(CMAKE_REQUIRED_LIBRARIES)\nendif()\n\nif (SCOTCH_LIBRARIES)\n  list(GET SCOTCH_LIBRARIES 0 first_lib)\n  get_filename_component(first_lib_path \"${first_lib}\" PATH)\n  if (${first_lib_path} MATCHES \"/lib(32|64)?$\")\n    string(REGEX REPLACE \"/lib(32|64)?$\" \"\" not_cached_dir \"${first_lib_path}\")\n    set(SCOTCH_DIR_FOUND \"${not_cached_dir}\" CACHE PATH \"Installation directory of SCOTCH library\" FORCE)\n  else()\n    set(SCOTCH_DIR_FOUND \"${first_lib_path}\" CACHE PATH \"Installation directory of SCOTCH library\" FORCE)\n  endif()\nendif()\nmark_as_advanced(SCOTCH_DIR)\nmark_as_advanced(SCOTCH_DIR_FOUND)\n\n# Check the size of SCOTCH_Num\n# ---------------------------------\nset(CMAKE_REQUIRED_INCLUDES ${SCOTCH_INCLUDE_DIRS})\n\ninclude(CheckCSourceRuns)\n#stdio.h and stdint.h should be included by scotch.h directly\nset(SCOTCH_C_TEST_SCOTCH_Num_4 \"\n#include <stdio.h>\n#include <stdint.h>\n#include <scotch.h>\nint main(int argc, char **argv) {\n  if (sizeof(SCOTCH_Num) == 4)\n    return 0;\n  else\n    return 1;\n}\n\")\n\nset(SCOTCH_C_TEST_SCOTCH_Num_8 \"\n#include <stdio.h>\n#include <stdint.h>\n#include <scotch.h>\nint main(int argc, char **argv) {\n  if (sizeof(SCOTCH_Num) == 8)\n    return 0;\n  else\n    return 1;\n}\n\")\ncheck_c_source_runs(\"${SCOTCH_C_TEST_SCOTCH_Num_4}\" SCOTCH_Num_4)\nif(NOT SCOTCH_Num_4)\n  check_c_source_runs(\"${SCOTCH_C_TEST_SCOTCH_Num_8}\" SCOTCH_Num_8)\n  if(NOT SCOTCH_Num_8)\n    set(SCOTCH_INTSIZE -1)\n  else()\n    set(SCOTCH_INTSIZE 8)\n  endif()\nelse()\n  set(SCOTCH_INTSIZE 4)\nendif()\nset(CMAKE_REQUIRED_INCLUDES \"\")\n\n# check that SCOTCH has been found\n# ---------------------------------\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(SCOTCH DEFAULT_MSG\n  SCOTCH_LIBRARIES\n  SCOTCH_WORKS)\n#\n# TODO: Add possibility to check for specific functions in the library\n#\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindStandardMathLibrary.cmake",
    "content": "# - Try to find how to link to the standard math library, if anything at all is needed to do.\n# On most platforms this is automatic, but for example it's not automatic on QNX.\n#\n# Once done this will define\n#\n#  STANDARD_MATH_LIBRARY_FOUND - we found how to successfully link to the standard math library\n#  STANDARD_MATH_LIBRARY - the name of the standard library that one has to link to.\n#                            -- this will be left empty if it's automatic (most platforms).\n#                            -- this will be set to \"m\" on platforms where one must explicitly\n#                               pass the \"-lm\" linker flag.\n#\n# Copyright (c) 2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n#               2020 Susi Lehtola <susi.lehtola@gmail.com>\n# Redistribution and use is allowed according to the terms of the 2-clause BSD license.\n\n\ninclude(CheckCXXSourceCompiles)\n\n# a little test program for c++ math functions.\n# notice the std:: is required on some platforms such as QNX\n# notice the (void) is required if -Wall (-Wunused-value) is added to CMAKE_CXX_FLAG\n\n# We read in the arguments from standard input to avoid the compiler optimizing away the calls\nset(find_standard_math_library_test_program\n\"\n#include<cmath>\nint main(int argc, char **){\n  return int(std::sin(double(argc)) + std::log(double(argc)));\n}\")\n\n# first try compiling/linking the test program without any linker flags\n\nset(CMAKE_REQUIRED_FLAGS \"\")\nset(CMAKE_REQUIRED_LIBRARIES \"\")\nCHECK_CXX_SOURCE_COMPILES(\n  \"${find_standard_math_library_test_program}\"\n  standard_math_library_linked_to_automatically\n)\n\nif(standard_math_library_linked_to_automatically)\n\n  # the test program linked successfully without any linker flag.\n  set(STANDARD_MATH_LIBRARY \"\")\n  set(STANDARD_MATH_LIBRARY_FOUND TRUE)\n\nelse()\n\n  # the test program did not link successfully without any linker flag.\n  # This is a very uncommon case that so far we only saw on QNX. The next try is the\n  # standard name 'm' for the standard math library.\n\n  set(CMAKE_REQUIRED_LIBRARIES \"m\")\n  CHECK_CXX_SOURCE_COMPILES(\n    \"${find_standard_math_library_test_program}\"\n    standard_math_library_linked_to_as_m)\n\n  if(standard_math_library_linked_to_as_m)\n\n    # the test program linked successfully when linking to the 'm' library\n    set(STANDARD_MATH_LIBRARY \"m\")\n    set(STANDARD_MATH_LIBRARY_FOUND TRUE)\n\n  else()\n\n    # the test program still doesn't link successfully\n    set(STANDARD_MATH_LIBRARY_FOUND FALSE)\n\n  endif()\n\nendif()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindSuperLU.cmake",
    "content": "\n# Umfpack lib usually requires linking to a blas library.\n# It is up to the user of this module to find a BLAS and link to it.\n\nif (SUPERLU_INCLUDES AND SUPERLU_LIBRARIES)\n  set(SUPERLU_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(SUPERLU_INCLUDES\n  NAMES\n  supermatrix.h\n  PATHS\n  $ENV{SUPERLUDIR}\n  ${INCLUDE_INSTALL_DIR}\n  PATH_SUFFIXES\n  superlu\n  SRC\n)\n\nfind_library(SUPERLU_LIBRARIES\n  NAMES \"superlu_5.2.1\" \"superlu_5.2\" \"superlu_5.1.1\" \"superlu_5.1\" \"superlu_5.0\" \"superlu_4.3\" \"superlu_4.2\" \"superlu_4.1\" \"superlu_4.0\" \"superlu_3.1\" \"superlu_3.0\" \"superlu\"\n  PATHS $ENV{SUPERLUDIR} ${LIB_INSTALL_DIR}\n  PATH_SUFFIXES lib)\n\nif(SUPERLU_INCLUDES AND SUPERLU_LIBRARIES)\n\ninclude(CheckCXXSourceCompiles)\ninclude(CMakePushCheckState)\ncmake_push_check_state()\n\nset(CMAKE_REQUIRED_INCLUDES ${CMAKE_REQUIRED_INCLUDES} ${SUPERLU_INCLUDES})\n\n# check whether struct mem_usage_t is globally defined\ncheck_cxx_source_compiles(\"\ntypedef int int_t;\n#include <supermatrix.h>\n#include <slu_util.h>\nint main() {\n  mem_usage_t mem;\n  return 0;\n}\"\nSUPERLU_HAS_GLOBAL_MEM_USAGE_T)\n\n\ncheck_cxx_source_compiles(\"\ntypedef int int_t;\n#include <supermatrix.h>\n#include <superlu_enum_consts.h>\nint main() {\n  return SLU_SINGLE;\n}\"\nSUPERLU_HAS_CLEAN_ENUMS)\n\ncheck_cxx_source_compiles(\"\ntypedef int int_t;\n#include <supermatrix.h>\n#include <slu_util.h>\nint main(void)\n{\n  GlobalLU_t glu;\n  return 0;\n}\"\nSUPERLU_HAS_GLOBALLU_T)\n\nif(SUPERLU_HAS_GLOBALLU_T)\n  # at least 5.0\n  set(SUPERLU_VERSION_VAR \"5.0\")\nelseif(SUPERLU_HAS_CLEAN_ENUMS)\n  # at least 4.3\n  set(SUPERLU_VERSION_VAR \"4.3\")\nelseif(SUPERLU_HAS_GLOBAL_MEM_USAGE_T)\n  # at least 4.0\n  set(SUPERLU_VERSION_VAR \"4.0\")\nelse()\n  set(SUPERLU_VERSION_VAR \"3.0\")\nendif()\n\ncmake_pop_check_state()\n\nif(SuperLU_FIND_VERSION)\n  if(${SUPERLU_VERSION_VAR} VERSION_LESS ${SuperLU_FIND_VERSION})\n    set(SUPERLU_VERSION_OK FALSE)\n  else()\n    set(SUPERLU_VERSION_OK TRUE)\n  endif()\nelse()\n  set(SUPERLU_VERSION_OK TRUE)\nendif()\n\nendif()\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(SuperLU\n                                  REQUIRED_VARS SUPERLU_INCLUDES SUPERLU_LIBRARIES SUPERLU_VERSION_OK\n                                  VERSION_VAR SUPERLU_VERSION_VAR)\n\nmark_as_advanced(SUPERLU_INCLUDES SUPERLU_LIBRARIES)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindTriSYCL.cmake",
    "content": "#.rst:\n# FindTriSYCL\n#---------------\n#\n# TODO : insert Copyright and licence\n\n#########################\n#  FindTriSYCL.cmake\n#########################\n#\n#  Tools for finding and building with TriSYCL.\n#\n#  User must define TRISYCL_INCLUDE_DIR pointing to the triSYCL\n#  include directory.\n#\n#  Latest version of this file can be found at:\n#    https://github.com/triSYCL/triSYCL\n\n# Requite CMake version 3.5 or higher\ncmake_minimum_required (VERSION 3.5)\n\n# Check that a supported host compiler can be found\nif(CMAKE_COMPILER_IS_GNUCXX)\n  # Require at least gcc 5.4\n  if (CMAKE_CXX_COMPILER_VERSION VERSION_LESS 5.4)\n    message(FATAL_ERROR\n      \"host compiler - Not found! (gcc version must be at least 5.4)\")\n  else()\n    message(STATUS \"host compiler - gcc ${CMAKE_CXX_COMPILER_VERSION}\")\n  endif()\nelseif (\"${CMAKE_CXX_COMPILER_ID}\" STREQUAL \"Clang\")\n  # Require at least clang 3.9\n  if (${CMAKE_CXX_COMPILER_VERSION} VERSION_LESS 3.9)\n    message(FATAL_ERROR\n      \"host compiler - Not found! (clang version must be at least 3.9)\")\n  else()\n    message(STATUS \"host compiler - clang ${CMAKE_CXX_COMPILER_VERSION}\")\n  endif()\nelse()\n  message(WARNING\n    \"host compiler - Not found! (triSYCL supports GCC and Clang)\")\nendif()\n\n#triSYCL options\noption(TRISYCL_OPENMP \"triSYCL multi-threading with OpenMP\" ON)\noption(TRISYCL_OPENCL \"triSYCL OpenCL interoperability mode\" OFF)\noption(TRISYCL_NO_ASYNC \"triSYCL use synchronous kernel execution\" OFF)\noption(TRISYCL_DEBUG \"triSCYL use debug mode\" OFF)\noption(TRISYCL_DEBUG_STRUCTORS \"triSYCL trace of object lifetimes\" OFF)\noption(TRISYCL_TRACE_KERNEL \"triSYCL trace of kernel execution\" OFF)\n\nmark_as_advanced(TRISYCL_OPENMP)\nmark_as_advanced(TRISYCL_OPENCL)\nmark_as_advanced(TRISYCL_NO_ASYNC)\nmark_as_advanced(TRISYCL_DEBUG)\nmark_as_advanced(TRISYCL_DEBUG_STRUCTORS)\nmark_as_advanced(TRISYCL_TRACE_KERNEL)\n\n#triSYCL definitions\nset(CL_SYCL_LANGUAGE_VERSION 220 CACHE VERSION\n  \"Host language version to be used by trisYCL (default is: 220)\")\nset(TRISYCL_CL_LANGUAGE_VERSION 220 CACHE VERSION\n  \"Device language version to be used by trisYCL (default is: 220)\")\n#set(TRISYCL_COMPILE_OPTIONS \"-std=c++1z -Wall -Wextra\")\nset(CMAKE_CXX_STANDARD 14)\nset(CXX_STANDARD_REQUIRED ON)\n\n\n# Find OpenCL package\nif(TRISYCL_OPENCL)\n  find_package(OpenCL REQUIRED)\n  if(UNIX)\n    set(BOOST_COMPUTE_INCPATH /usr/include/compute CACHE PATH\n      \"Path to Boost.Compute headers (default is: /usr/include/compute)\")\n  endif()\nendif()\n\n# Find OpenMP package\nif(TRISYCL_OPENMP)\n  find_package(OpenMP REQUIRED)\nendif()\n\n# Find Boost\nfind_package(Boost 1.58 REQUIRED COMPONENTS chrono log)\n\n# If debug or trace we need boost log\nif(TRISYCL_DEBUG OR TRISYCL_DEBUG_STRUCTORS OR TRISYCL_TRACE_KERNEL)\n  set(LOG_NEEDED ON)\nelse()\n  set(LOG_NEEDED OFF)\nendif()\n\nfind_package(Threads REQUIRED)\n\n# Find triSYCL directory\nif(NOT TRISYCL_INCLUDE_DIR)\n  message(FATAL_ERROR\n    \"triSYCL include directory - Not found! (please set TRISYCL_INCLUDE_DIR\")\nelse()\n  message(STATUS \"triSYCL include directory - Found ${TRISYCL_INCLUDE_DIR}\")\nendif()\n\n#######################\n#  add_sycl_to_target\n#######################\n#\n#  Sets the proper flags and includes for the target compilation.\n#\n#  targetName : Name of the target to add a SYCL to.\n#  sourceFile : Source file to be compiled for SYCL.\n#  binaryDir : Intermediate directory to output the integration header.\n#\nfunction(add_sycl_to_target targetName sourceFile binaryDir)\n\n  # Add include directories to the \"#include <>\" paths\n  target_include_directories (${targetName} PUBLIC\n    ${TRISYCL_INCLUDE_DIR}\n    ${Boost_INCLUDE_DIRS}\n    $<$<BOOL:${TRISYCL_OPENCL}>:${OpenCL_INCLUDE_DIRS}>\n    $<$<BOOL:${TRISYCL_OPENCL}>:${BOOST_COMPUTE_INCPATH}>)\n\n\n  # Link dependencies\n  target_link_libraries(${targetName} PUBLIC\n    $<$<BOOL:${TRISYCL_OPENCL}>:${OpenCL_LIBRARIES}>\n    Threads::Threads\n    $<$<BOOL:${LOG_NEEDED}>:Boost::log>\n    Boost::chrono)\n\n\n  # Compile definitions\n  target_compile_definitions(${targetName} PUBLIC\n    $<$<BOOL:${TRISYCL_NO_ASYNC}>:TRISYCL_NO_ASYNC>\n    $<$<BOOL:${TRISYCL_OPENCL}>:TRISYCL_OPENCL>\n    $<$<BOOL:${TRISYCL_DEBUG}>:TRISYCL_DEBUG>\n    $<$<BOOL:${TRISYCL_DEBUG_STRUCTORS}>:TRISYCL_DEBUG_STRUCTORS>\n    $<$<BOOL:${TRISYCL_TRACE_KERNEL}>:TRISYCL_TRACE_KERNEL>\n    $<$<BOOL:${LOG_NEEDED}>:BOOST_LOG_DYN_LINK>)\n\n  # C++ and OpenMP requirements\n  target_compile_options(${targetName} PUBLIC\n    ${TRISYCL_COMPILE_OPTIONS}\n    $<$<BOOL:${TRISYCL_OPENMP}>:${OpenMP_CXX_FLAGS}>)\n\n  if(${TRISYCL_OPENMP} AND (NOT WIN32))\n    # Does not support generator expressions\n    set_target_properties(${targetName}\n      PROPERTIES\n      LINK_FLAGS ${OpenMP_CXX_FLAGS})\n  endif()\n\nendfunction()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/FindUMFPACK.cmake",
    "content": "# Umfpack lib usually requires linking to a blas library.\n# It is up to the user of this module to find a BLAS and link to it.\n\nif (UMFPACK_INCLUDES AND UMFPACK_LIBRARIES)\n  set(UMFPACK_FIND_QUIETLY TRUE)\nendif ()\n\nfind_path(UMFPACK_INCLUDES\n  NAMES\n  umfpack.h\n  PATHS\n  $ENV{UMFPACKDIR}\n  ${INCLUDE_INSTALL_DIR}\n  PATH_SUFFIXES\n  suitesparse\n  ufsparse\n)\n\nfind_library(UMFPACK_LIBRARIES umfpack PATHS $ENV{UMFPACKDIR} ${LIB_INSTALL_DIR})\n\nif(UMFPACK_LIBRARIES)\n\n  if(NOT UMFPACK_LIBDIR)\n    get_filename_component(UMFPACK_LIBDIR ${UMFPACK_LIBRARIES} PATH)\n  endif()\n\n  find_library(COLAMD_LIBRARY colamd PATHS ${UMFPACK_LIBDIR} $ENV{UMFPACKDIR} ${LIB_INSTALL_DIR})\n  if(COLAMD_LIBRARY)\n    set(UMFPACK_LIBRARIES ${UMFPACK_LIBRARIES} ${COLAMD_LIBRARY})\n  endif ()\n  \n  find_library(AMD_LIBRARY amd PATHS ${UMFPACK_LIBDIR} $ENV{UMFPACKDIR} ${LIB_INSTALL_DIR})\n  if(AMD_LIBRARY)\n    set(UMFPACK_LIBRARIES ${UMFPACK_LIBRARIES} ${AMD_LIBRARY})\n  endif ()\n\n  find_library(SUITESPARSE_LIBRARY SuiteSparse PATHS ${UMFPACK_LIBDIR} $ENV{UMFPACKDIR} ${LIB_INSTALL_DIR})\n  if(SUITESPARSE_LIBRARY)\n    set(UMFPACK_LIBRARIES ${UMFPACK_LIBRARIES} ${SUITESPARSE_LIBRARY})\n  endif ()\n\n  find_library(CHOLMOD_LIBRARY cholmod PATHS $ENV{UMFPACK_LIBDIR} $ENV{UMFPACKDIR} ${LIB_INSTALL_DIR})\n  if(CHOLMOD_LIBRARY)\n    set(UMFPACK_LIBRARIES ${UMFPACK_LIBRARIES} ${CHOLMOD_LIBRARY})\n  endif()\n\nendif()\n\ninclude(FindPackageHandleStandardArgs)\nfind_package_handle_standard_args(UMFPACK DEFAULT_MSG\n                                  UMFPACK_INCLUDES UMFPACK_LIBRARIES)\n\nmark_as_advanced(UMFPACK_INCLUDES UMFPACK_LIBRARIES AMD_LIBRARY COLAMD_LIBRARY CHOLMOD_LIBRARY SUITESPARSE_LIBRARY)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/RegexUtils.cmake",
    "content": "function(escape_string_as_regex _str_out _str_in)\n  string(REGEX REPLACE \"\\\\\\\\\" \"\\\\\\\\\\\\\\\\\" FILETEST2 \"${_str_in}\")\n  string(REGEX REPLACE \"([.$+*?|-])\" \"\\\\\\\\\\\\1\" FILETEST2 \"${FILETEST2}\")\n  string(REGEX REPLACE \"\\\\^\" \"\\\\\\\\^\" FILETEST2 \"${FILETEST2}\")\n  string(REGEX REPLACE \"\\\\(\" \"\\\\\\\\(\" FILETEST2 \"${FILETEST2}\")\n  string(REGEX REPLACE \"\\\\)\" \"\\\\\\\\)\" FILETEST2 \"${FILETEST2}\")\n  string(REGEX REPLACE \"\\\\[\" \"\\\\\\\\[\" FILETEST2 \"${FILETEST2}\")\n  string(REGEX REPLACE \"\\\\]\" \"\\\\\\\\]\" FILETEST2 \"${FILETEST2}\")\n  set(${_str_out} \"${FILETEST2}\" PARENT_SCOPE)\nendfunction()\n\nfunction(test_escape_string_as_regex)\n  set(test1 \"\\\\.^$-+*()[]?|\")\n  escape_string_as_regex(test2 \"${test1}\")\n  set(testRef \"\\\\\\\\\\\\.\\\\^\\\\$\\\\-\\\\+\\\\*\\\\(\\\\)\\\\[\\\\]\\\\?\\\\|\")\n  if(NOT test2 STREQUAL testRef)\n\tmessage(\"Error in the escape_string_for_regex function : \\n   ${test1} was escaped as ${test2}, should be ${testRef}\")\n  endif()\nendfunction()"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/cmake/UseEigen3.cmake",
    "content": "#                                               -*- cmake -*-\n#\n#  UseEigen3.cmake\n\nadd_definitions     ( ${EIGEN3_DEFINITIONS} )\ninclude_directories ( ${EIGEN3_INCLUDE_DIRS} )\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/debug/gdb/__init__.py",
    "content": "# Intentionally empty\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/debug/gdb/printers.py",
    "content": "# -*- coding: utf-8 -*-\n# This file is part of Eigen, a lightweight C++ template library\n# for linear algebra.\n#\n# Copyright (C) 2009 Benjamin Schindler <bschindler@inf.ethz.ch>\n#\n# This Source Code Form is subject to the terms of the Mozilla Public\n# License, v. 2.0. If a copy of the MPL was not distributed with this\n# file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n# Pretty printers for Eigen::Matrix\n# This is still pretty basic as the python extension to gdb is still pretty basic. \n# It cannot handle complex eigen types and it doesn't support many of the other eigen types\n# This code supports fixed size as well as dynamic size matrices\n\n# To use it:\n#\n# * Create a directory and put the file as well as an empty __init__.py in \n#   that directory.\n# * Create a ~/.gdbinit file, that contains the following:\n#      python\n#      import sys\n#      sys.path.insert(0, '/path/to/eigen/printer/directory')\n#      from printers import register_eigen_printers\n#      register_eigen_printers (None)\n#      end\n\nimport gdb\nimport re\nimport itertools\nfrom bisect import bisect_left\n\n# Basic row/column iteration code for use with Sparse and Dense matrices\nclass _MatrixEntryIterator(object):\n\t\n\tdef __init__ (self, rows, cols, rowMajor):\n\t\tself.rows = rows\n\t\tself.cols = cols\n\t\tself.currentRow = 0\n\t\tself.currentCol = 0\n\t\tself.rowMajor = rowMajor\n\n\tdef __iter__ (self):\n\t\treturn self\n\n\tdef next(self):\n                return self.__next__()  # Python 2.x compatibility\n\n\tdef __next__(self):\n\t\trow = self.currentRow\n\t\tcol = self.currentCol\n\t\tif self.rowMajor == 0:\n\t\t\tif self.currentCol >= self.cols:\n\t\t\t\traise StopIteration\n\t\t\t\t\n\t\t\tself.currentRow = self.currentRow + 1\n\t\t\tif self.currentRow >= self.rows:\n\t\t\t\tself.currentRow = 0\n\t\t\t\tself.currentCol = self.currentCol + 1\n\t\telse:\n\t\t\tif self.currentRow >= self.rows:\n\t\t\t\traise StopIteration\n\t\t\t\t\n\t\t\tself.currentCol = self.currentCol + 1\n\t\t\tif self.currentCol >= self.cols:\n\t\t\t\tself.currentCol = 0\n\t\t\t\tself.currentRow = self.currentRow + 1\n\n\t\treturn (row, col)\n\nclass EigenMatrixPrinter:\n\t\"Print Eigen Matrix or Array of some kind\"\n\n\tdef __init__(self, variety, val):\n\t\t\"Extract all the necessary information\"\n\t\t\n\t\t# Save the variety (presumably \"Matrix\" or \"Array\") for later usage\n\t\tself.variety = variety\n\t\t\n\t\t# The gdb extension does not support value template arguments - need to extract them by hand\n\t\ttype = val.type\n\t\tif type.code == gdb.TYPE_CODE_REF:\n\t\t\ttype = type.target()\n\t\tself.type = type.unqualified().strip_typedefs()\n\t\ttag = self.type.tag\n\t\tregex = re.compile('\\<.*\\>')\n\t\tm = regex.findall(tag)[0][1:-1]\n\t\ttemplate_params = m.split(',')\n\t\ttemplate_params = [x.replace(\" \", \"\") for x in template_params]\n\t\t\n\t\tif template_params[1] == '-0x00000000000000001' or template_params[1] == '-0x000000001' or template_params[1] == '-1':\n\t\t\tself.rows = val['m_storage']['m_rows']\n\t\telse:\n\t\t\tself.rows = int(template_params[1])\n\t\t\n\t\tif template_params[2] == '-0x00000000000000001' or template_params[2] == '-0x000000001' or template_params[2] == '-1':\n\t\t\tself.cols = val['m_storage']['m_cols']\n\t\telse:\n\t\t\tself.cols = int(template_params[2])\n\t\t\n\t\tself.options = 0 # default value\n\t\tif len(template_params) > 3:\n\t\t\tself.options = template_params[3];\n\t\t\n\t\tself.rowMajor = (int(self.options) & 0x1)\n\t\t\n\t\tself.innerType = self.type.template_argument(0)\n\t\t\n\t\tself.val = val\n\t\t\n\t\t# Fixed size matrices have a struct as their storage, so we need to walk through this\n\t\tself.data = self.val['m_storage']['m_data']\n\t\tif self.data.type.code == gdb.TYPE_CODE_STRUCT:\n\t\t\tself.data = self.data['array']\n\t\t\tself.data = self.data.cast(self.innerType.pointer())\n\t\t\t\n\tclass _iterator(_MatrixEntryIterator):\n\t\tdef __init__ (self, rows, cols, dataPtr, rowMajor):\n\t\t\tsuper(EigenMatrixPrinter._iterator, self).__init__(rows, cols, rowMajor)\n\n\t\t\tself.dataPtr = dataPtr\n\n\t\tdef __next__(self):\n\t\t\t\n\t\t\trow, col = super(EigenMatrixPrinter._iterator, self).__next__()\n\t\t\t\n\t\t\titem = self.dataPtr.dereference()\n\t\t\tself.dataPtr = self.dataPtr + 1\n\t\t\tif (self.cols == 1): #if it's a column vector\n\t\t\t\treturn ('[%d]' % (row,), item)\n\t\t\telif (self.rows == 1): #if it's a row vector\n\t\t\t\treturn ('[%d]' % (col,), item)\n\t\t\treturn ('[%d,%d]' % (row, col), item)\n\t\t\t\n\tdef children(self):\n\t\t\n\t\treturn self._iterator(self.rows, self.cols, self.data, self.rowMajor)\n\t\t\n\tdef to_string(self):\n\t\treturn \"Eigen::%s<%s,%d,%d,%s> (data ptr: %s)\" % (self.variety, self.innerType, self.rows, self.cols, \"RowMajor\" if self.rowMajor else  \"ColMajor\", self.data)\n\nclass EigenSparseMatrixPrinter:\n\t\"Print an Eigen SparseMatrix\"\n\n\tdef __init__(self, val):\n\t\t\"Extract all the necessary information\"\n\n\t\ttype = val.type\n\t\tif type.code == gdb.TYPE_CODE_REF:\n\t\t\ttype = type.target()\n\t\tself.type = type.unqualified().strip_typedefs()\n\t\ttag = self.type.tag\n\t\tregex = re.compile('\\<.*\\>')\n\t\tm = regex.findall(tag)[0][1:-1]\n\t\ttemplate_params = m.split(',')\n\t\ttemplate_params = [x.replace(\" \", \"\") for x in template_params]\n\n\t\tself.options = 0\n\t\tif len(template_params) > 1:\n\t\t\tself.options = template_params[1];\n\t\t\n\t\tself.rowMajor = (int(self.options) & 0x1)\n\t\t\n\t\tself.innerType = self.type.template_argument(0)\n\t\t\n\t\tself.val = val\n\n\t\tself.data = self.val['m_data']\n\t\tself.data = self.data.cast(self.innerType.pointer())\n\n\tclass _iterator(_MatrixEntryIterator):\n\t\tdef __init__ (self, rows, cols, val, rowMajor):\n\t\t\tsuper(EigenSparseMatrixPrinter._iterator, self).__init__(rows, cols, rowMajor)\n\n\t\t\tself.val = val\n\t\t\t\n\t\tdef __next__(self):\n\t\t\t\n\t\t\trow, col = super(EigenSparseMatrixPrinter._iterator, self).__next__()\n\t\t\t\t\n\t\t\t# repeat calculations from SparseMatrix.h:\n\t\t\touter = row if self.rowMajor else col\n\t\t\tinner = col if self.rowMajor else row\n\t\t\tstart = self.val['m_outerIndex'][outer]\n\t\t\tend = ((start + self.val['m_innerNonZeros'][outer]) if self.val['m_innerNonZeros'] else\n\t\t\t       self.val['m_outerIndex'][outer+1])\n\n\t\t\t# and from CompressedStorage.h:\n\t\t\tdata = self.val['m_data']\n\t\t\tif start >= end:\n\t\t\t\titem = 0\n\t\t\telif (end > start) and (inner == data['m_indices'][end-1]):\n\t\t\t\titem = data['m_values'][end-1]\n\t\t\telse:\n\t\t\t\t# create Python index list from the target range within m_indices\n\t\t\t\tindices = [data['m_indices'][x] for x in range(int(start), int(end)-1)]\n\t\t\t\t# find the index with binary search\n\t\t\t\tidx = int(start) + bisect_left(indices, inner)\n\t\t\t\tif ((idx < end) and (data['m_indices'][idx] == inner)):\n\t\t\t\t\titem = data['m_values'][idx]\n\t\t\t\telse:\n\t\t\t\t\titem = 0\n\n\t\t\treturn ('[%d,%d]' % (row, col), item)\n\n\tdef children(self):\n\t\tif self.data:\n\t\t\treturn self._iterator(self.rows(), self.cols(), self.val, self.rowMajor)\n\n\t\treturn iter([])   # empty matrix, for now\n\n\n\tdef rows(self):\n\t\treturn self.val['m_outerSize'] if self.rowMajor else self.val['m_innerSize']\n\n\tdef cols(self):\n\t\treturn self.val['m_innerSize'] if self.rowMajor else self.val['m_outerSize']\n\n\tdef to_string(self):\n\n\t\tif self.data:\n\t\t\tstatus = (\"not compressed\" if self.val['m_innerNonZeros'] else \"compressed\")\n\t\telse:\n\t\t\tstatus = \"empty\"\n\t\tdimensions  = \"%d x %d\" % (self.rows(), self.cols())\n\t\tlayout      = \"row\" if self.rowMajor else \"column\"\n\n\t\treturn \"Eigen::SparseMatrix<%s>, %s, %s major, %s\" % (\n\t\t\tself.innerType, dimensions, layout, status )\n\nclass EigenQuaternionPrinter:\n\t\"Print an Eigen Quaternion\"\n\t\n\tdef __init__(self, val):\n\t\t\"Extract all the necessary information\"\n\t\t# The gdb extension does not support value template arguments - need to extract them by hand\n\t\ttype = val.type\n\t\tif type.code == gdb.TYPE_CODE_REF:\n\t\t\ttype = type.target()\n\t\tself.type = type.unqualified().strip_typedefs()\n\t\tself.innerType = self.type.template_argument(0)\n\t\tself.val = val\n\t\t\n\t\t# Quaternions have a struct as their storage, so we need to walk through this\n\t\tself.data = self.val['m_coeffs']['m_storage']['m_data']['array']\n\t\tself.data = self.data.cast(self.innerType.pointer())\n\t\t\t\n\tclass _iterator:\n\t\tdef __init__ (self, dataPtr):\n\t\t\tself.dataPtr = dataPtr\n\t\t\tself.currentElement = 0\n\t\t\tself.elementNames = ['x', 'y', 'z', 'w']\n\t\t\t\n\t\tdef __iter__ (self):\n\t\t\treturn self\n\t\n\t\tdef next(self):\n\t\t\treturn self.__next__()  # Python 2.x compatibility\n\n\t\tdef __next__(self):\n\t\t\telement = self.currentElement\n\t\t\t\n\t\t\tif self.currentElement >= 4: #there are 4 elements in a quanternion\n\t\t\t\traise StopIteration\n\t\t\t\n\t\t\tself.currentElement = self.currentElement + 1\n\t\t\t\n\t\t\titem = self.dataPtr.dereference()\n\t\t\tself.dataPtr = self.dataPtr + 1\n\t\t\treturn ('[%s]' % (self.elementNames[element],), item)\n\t\t\t\n\tdef children(self):\n\t\t\n\t\treturn self._iterator(self.data)\n\t\n\tdef to_string(self):\n\t\treturn \"Eigen::Quaternion<%s> (data ptr: %s)\" % (self.innerType, self.data)\n\ndef build_eigen_dictionary ():\n\tpretty_printers_dict[re.compile('^Eigen::Quaternion<.*>$')] = lambda val: EigenQuaternionPrinter(val)\n\tpretty_printers_dict[re.compile('^Eigen::Matrix<.*>$')] = lambda val: EigenMatrixPrinter(\"Matrix\", val)\n\tpretty_printers_dict[re.compile('^Eigen::SparseMatrix<.*>$')] = lambda val: EigenSparseMatrixPrinter(val)\n\tpretty_printers_dict[re.compile('^Eigen::Array<.*>$')]  = lambda val: EigenMatrixPrinter(\"Array\",  val)\n\ndef register_eigen_printers(obj):\n\t\"Register eigen pretty-printers with objfile Obj\"\n\n\tif obj == None:\n\t\tobj = gdb\n\tobj.pretty_printers.append(lookup_function)\n\ndef lookup_function(val):\n\t\"Look-up and return a pretty-printer that can print va.\"\n\t\n\ttype = val.type\n\t\n\tif type.code == gdb.TYPE_CODE_REF:\n\t\ttype = type.target()\n\t\n\ttype = type.unqualified().strip_typedefs()\n\t\n\ttypename = type.tag\n\tif typename == None:\n\t\treturn None\n\t\n\tfor function in pretty_printers_dict:\n\t\tif function.search(typename):\n\t\t\treturn pretty_printers_dict[function](val)\n\t\n\treturn None\n\npretty_printers_dict = {}\n\nbuild_eigen_dictionary ()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/debug/msvc/eigen.natvis",
    "content": "<?xml version=\"1.0\" encoding=\"utf-8\"?>\n\n<AutoVisualizer xmlns=\"http://schemas.microsoft.com/vstudio/debugger/natvis/2010\">\n\n  <!-- Fixed x Fixed Matrix -->\n  <Type Name=\"Eigen::Matrix&lt;*,*,*,*,*,*&gt;\">      \n      <AlternativeType Name=\"Eigen::Array&lt;*,-1,-1,*,*,*&gt;\"/>\n      <DisplayString>[{$T2}, {$T3}] (fixed matrix)</DisplayString>\n      <Expand>\n        <ArrayItems Condition=\"Flags%2\"> <!-- row major layout -->\n          <Rank>2</Rank>\n          <Size>$i==0 ? $T2 : $T3</Size>\n          <ValuePointer>m_storage.m_data.array</ValuePointer>\n        </ArrayItems>\n        <ArrayItems Condition=\"!(Flags%2)\"> <!-- column major layout -->\n          <Direction>Backward</Direction>\n          <Rank>2</Rank>\n          <Size>$i==0 ? $T2 : $T3</Size>\n          <ValuePointer>m_storage.m_data.array</ValuePointer>\n        </ArrayItems>\n      </Expand>\n  </Type>\n  \n  <!-- 2 x 2 Matrix -->\n  <Type Name=\"Eigen::Matrix&lt;*,2,2,*,*,*&gt;\">      \n      <AlternativeType Name=\"Eigen::Array&lt;*,2,2,*,*,*&gt;\"/>\n      <DisplayString>[2, 2] (fixed matrix)</DisplayString>\n      <Expand>\n        <Synthetic Name=\"[row 0]\" Condition=\"Flags%2\">\n          <DisplayString>({m_storage.m_data.array[0]}, {m_storage.m_data.array[1]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 0]\" Condition=\"!(Flags%2)\">\n          <DisplayString>({m_storage.m_data.array[0]}, {m_storage.m_data.array[2]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 1]\" Condition=\"Flags%2\">\n          <DisplayString>({m_storage.m_data.array[2]}, {m_storage.m_data.array[3]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 1]\" Condition=\"!(Flags%2)\">\n          <DisplayString>({m_storage.m_data.array[1]}, {m_storage.m_data.array[3]})</DisplayString>\n        </Synthetic>        \n      </Expand>\n  </Type>\n  \n  <!-- 3 x 3 Matrix -->\n  <Type Name=\"Eigen::Matrix&lt;*,3,3,*,*,*&gt;\">      \n      <AlternativeType Name=\"Eigen::Array&lt;*,3,3,*,*,*&gt;\"/>\n      <DisplayString>[3, 3] (fixed matrix)</DisplayString>\n      <Expand>\n        <Synthetic Name=\"[row 0]\" Condition=\"Flags%2\">\n          <DisplayString>({m_storage.m_data.array[0]}, {m_storage.m_data.array[1]}, {m_storage.m_data.array[2]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 0]\" Condition=\"!(Flags%2)\">\n          <DisplayString>({m_storage.m_data.array[0]}, {m_storage.m_data.array[3]}, {m_storage.m_data.array[6]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 1]\" Condition=\"Flags%2\">\n          <DisplayString>({m_storage.m_data.array[3]}, {m_storage.m_data.array[4]}, {m_storage.m_data.array[5]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 1]\" Condition=\"!(Flags%2)\">\n          <DisplayString>({m_storage.m_data.array[1]}, {m_storage.m_data.array[4]}, {m_storage.m_data.array[7]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 2]\" Condition=\"Flags%2\">\n          <DisplayString>({m_storage.m_data.array[6]}, {m_storage.m_data.array[7]}, {m_storage.m_data.array[8]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 2]\" Condition=\"!(Flags%2)\">\n          <DisplayString>({m_storage.m_data.array[2]}, {m_storage.m_data.array[5]}, {m_storage.m_data.array[8]})</DisplayString>\n        </Synthetic>        \n      </Expand>\n  </Type>\n  \n  <!-- 4 x 4 Matrix -->\n  <Type Name=\"Eigen::Matrix&lt;*,4,4,*,*,*&gt;\">      \n      <AlternativeType Name=\"Eigen::Array&lt;*,4,4,*,*,*&gt;\"/>\n      <DisplayString>[4, 4] (fixed matrix)</DisplayString>\n      <Expand>\n        <Synthetic Name=\"[row 0]\" Condition=\"Flags%2\">\n          <DisplayString>({m_storage.m_data.array[0]}, {m_storage.m_data.array[1]}, {m_storage.m_data.array[2]}, {m_storage.m_data.array[3]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 0]\" Condition=\"!(Flags%2)\">\n          <DisplayString>({m_storage.m_data.array[0]}, {m_storage.m_data.array[4]}, {m_storage.m_data.array[8]}, {m_storage.m_data.array[12]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 1]\" Condition=\"Flags%2\">\n          <DisplayString>({m_storage.m_data.array[4]}, {m_storage.m_data.array[5]}, {m_storage.m_data.array[6]}, {m_storage.m_data.array[7]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 1]\" Condition=\"!(Flags%2)\">\n          <DisplayString>({m_storage.m_data.array[1]}, {m_storage.m_data.array[5]}, {m_storage.m_data.array[9]}, {m_storage.m_data.array[13]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 2]\" Condition=\"Flags%2\">\n          <DisplayString>({m_storage.m_data.array[8]}, {m_storage.m_data.array[9]}, {m_storage.m_data.array[10]}, {m_storage.m_data.array[11]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 2]\" Condition=\"!(Flags%2)\">\n          <DisplayString>({m_storage.m_data.array[2]}, {m_storage.m_data.array[6]}, {m_storage.m_data.array[10]}, {m_storage.m_data.array[14]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 3]\" Condition=\"Flags%2\">\n          <DisplayString>({m_storage.m_data.array[12]}, {m_storage.m_data.array[13]}, {m_storage.m_data.array[14]}, {m_storage.m_data.array[15]})</DisplayString>\n        </Synthetic>\n        <Synthetic Name=\"[row 3]\" Condition=\"!(Flags%2)\">\n          <DisplayString>({m_storage.m_data.array[3]}, {m_storage.m_data.array[7]}, {m_storage.m_data.array[11]}, {m_storage.m_data.array[15]})</DisplayString>\n        </Synthetic>        \n      </Expand>\n  </Type>  \n  \n  <!-- Dynamic x Dynamic Matrix -->\n  <Type Name=\"Eigen::Matrix&lt;*,-1,-1,*,*,*&gt;\">      \n      <AlternativeType Name=\"Eigen::Array&lt;*,-1,-1,*,*,*&gt;\"/>\n      <DisplayString Condition=\"m_storage.m_data == 0\">empty</DisplayString>\n      <DisplayString Condition=\"m_storage.m_data != 0\">[{m_storage.m_rows}, {m_storage.m_cols}] (dynamic matrix)</DisplayString>\n      <Expand>\n        <ArrayItems Condition=\"Flags%2\"> <!-- row major layout -->\n          <Rank>2</Rank>\n          <Size>$i==0 ? m_storage.m_rows : m_storage.m_cols</Size>\n          <ValuePointer>m_storage.m_data</ValuePointer>\n        </ArrayItems>\n        <ArrayItems Condition=\"!(Flags%2)\"> <!-- column major layout -->\n          <Direction>Backward</Direction>\n          <Rank>2</Rank>\n          <Size>$i==0 ? m_storage.m_rows : m_storage.m_cols</Size>\n          <ValuePointer>m_storage.m_data</ValuePointer>\n        </ArrayItems>\n      </Expand>\n  </Type>\n  \n  <!-- Fixed x Dynamic Matrix -->\n  <Type Name=\"Eigen::Matrix&lt;*,*,-1,*,*,*&gt;\">\n      <AlternativeType Name=\"Eigen::Array&lt;*,*,-1,*,*,*&gt;\"/>\n      <DisplayString Condition=\"m_storage.m_data == 0\">empty</DisplayString>\n      <DisplayString Condition=\"m_storage.m_data != 0\">[{$T2}, {m_storage.m_cols}] (dynamic column matrix)</DisplayString>\n      <Expand>\n        <ArrayItems Condition=\"Flags%2\"> <!-- row major layout -->\n          <Rank>2</Rank>\n          <Size>$i==0 ? $T2 : m_storage.m_cols</Size>\n          <ValuePointer>m_storage.m_data</ValuePointer>\n        </ArrayItems>\n        <ArrayItems Condition=\"!(Flags%2)\"> <!-- column major layout -->\n          <Direction>Backward</Direction>\n          <Rank>2</Rank>\n          <Size>$i==0 ? $T2 : m_storage.m_cols</Size>\n          <ValuePointer>m_storage.m_data</ValuePointer>\n        </ArrayItems>\n      </Expand>\n  </Type>\n  \n  <!-- Dynamic x Fixed Matrix -->\n  <Type Name=\"Eigen::Matrix&lt;*,-1,*,*,*,*&gt;\">\n      <AlternativeType Name=\"Eigen::Array&lt;*,-1,*,*,*,*&gt;\"/>\n      <DisplayString Condition=\"m_storage.m_data == 0\">empty</DisplayString>\n      <DisplayString Condition=\"m_storage.m_data != 0\">[{m_storage.m_rows}, {$T2}] (dynamic row matrix)</DisplayString>\n      <Expand>\n        <ArrayItems Condition=\"Flags%2\"> <!-- row major layout -->\n          <Rank>2</Rank>\n          <Size>$i==0 ? m_storage.m_rows : $T2</Size>\n          <ValuePointer>m_storage.m_data</ValuePointer>\n        </ArrayItems>\n        <ArrayItems Condition=\"!(Flags%2)\"> <!-- column major layout -->\n          <Direction>Backward</Direction>\n          <Rank>2</Rank>\n          <Size>$i==0 ? m_storage.m_rows : $T2</Size>\n          <ValuePointer>m_storage.m_data</ValuePointer>\n        </ArrayItems>\n      </Expand>\n  </Type>\n  \n  <!-- Dynamic Column Vector -->\n  <Type Name=\"Eigen::Matrix&lt;*,1,-1,*,*,*&gt;\">\n      <AlternativeType Name=\"Eigen::Array&lt;*,1,-1,*,*,*&gt;\"/>\n      <DisplayString Condition=\"m_storage.m_data == 0\">empty</DisplayString>\n      <DisplayString Condition=\"m_storage.m_data != 0\">[{m_storage.m_cols}] (dynamic column vector)</DisplayString>\n      <Expand>\n        <Item Name=\"[size]\">m_storage.m_cols</Item>\n        <ArrayItems>\n          <Size>m_storage.m_cols</Size>\n          <ValuePointer>m_storage.m_data</ValuePointer>\n        </ArrayItems>\n      </Expand>\n  </Type>\n  \n  <!-- Dynamic Row Vector -->\n  <Type Name=\"Eigen::Matrix&lt;*,-1,1,*,*,*&gt;\">\n      <AlternativeType Name=\"Eigen::Array&lt;*,-1,1,*,*,*&gt;\"/>\n      <DisplayString Condition=\"m_storage.m_data == 0\">empty</DisplayString>\n      <DisplayString Condition=\"m_storage.m_data != 0\">[{m_storage.m_rows}] (dynamic row vector)</DisplayString>\n      <Expand>\n        <Item Name=\"[size]\">m_storage.m_rows</Item>\n        <ArrayItems>\n          <Size>m_storage.m_rows</Size>\n          <ValuePointer>m_storage.m_data</ValuePointer>\n        </ArrayItems>\n      </Expand>\n  </Type>\n  \n  <!-- Fixed Vector -->\n  <Type Name=\"Eigen::Matrix&lt;*,1,1,*,*,*&gt;\">\n      <AlternativeType Name=\"Eigen::Array&lt;*,1,1,*,*,*&gt;\"/>\n      <DisplayString>[1] ({m_storage.m_data.array[0]})</DisplayString>\n      <Expand>\n        <Item Name=\"[x]\">m_storage.m_data.array[0]</Item>\n      </Expand>\n  </Type>\n  \n  <Type Name=\"Eigen::Matrix&lt;*,2,1,*,*,*&gt;\">\n      <AlternativeType Name=\"Eigen::Matrix&lt;*,1,2,*,*,*&gt;\"/>\n      <AlternativeType Name=\"Eigen::Array&lt;*,2,1,*,*,*&gt;\"/>\n      <AlternativeType Name=\"Eigen::Array&lt;*,1,2,*,*,*&gt;\"/>\n      <DisplayString>[2] ({m_storage.m_data.array[0]}, {m_storage.m_data.array[1]})</DisplayString>\n      <Expand>\n        <Item Name=\"[x]\">m_storage.m_data.array[0]</Item>\n        <Item Name=\"[y]\">m_storage.m_data.array[1]</Item>\n      </Expand>\n  </Type>\n  \n  <Type Name=\"Eigen::Matrix&lt;*,3,1,*,*,*&gt;\">\n      <AlternativeType Name=\"Eigen::Matrix&lt;*,1,3,*,*,*&gt;\"/>\n      <AlternativeType Name=\"Eigen::Array&lt;*,3,1,*,*,*&gt;\"/>\n      <AlternativeType Name=\"Eigen::Array&lt;*,1,3,*,*,*&gt;\"/>\n      <DisplayString>[3] ({m_storage.m_data.array[0]}, {m_storage.m_data.array[1]}, {m_storage.m_data.array[2]})</DisplayString>\n      <Expand>\n        <Item Name=\"[x]\">m_storage.m_data.array[0]</Item>\n        <Item Name=\"[y]\">m_storage.m_data.array[1]</Item>\n        <Item Name=\"[z]\">m_storage.m_data.array[2]</Item>\n      </Expand>\n  </Type>\n  \n    <Type Name=\"Eigen::Matrix&lt;*,4,1,*,*,*&gt;\">\n      <AlternativeType Name=\"Eigen::Matrix&lt;*,1,4,*,*,*&gt;\"/>\n      <AlternativeType Name=\"Eigen::Array&lt;*,4,1,*,*,*&gt;\"/>\n      <AlternativeType Name=\"Eigen::Array&lt;*,1,4,*,*,*&gt;\"/>\n      <DisplayString>[4] ({m_storage.m_data.array[0]}, {m_storage.m_data.array[1]}, {m_storage.m_data.array[2]}, {m_storage.m_data.array[3]})</DisplayString>\n      <Expand>\n        <Item Name=\"[x]\">m_storage.m_data.array[0]</Item>\n        <Item Name=\"[y]\">m_storage.m_data.array[1]</Item>\n        <Item Name=\"[z]\">m_storage.m_data.array[2]</Item>\n        <Item Name=\"[w]\">m_storage.m_data.array[3]</Item>\n      </Expand>\n  </Type>\n\n</AutoVisualizer>\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/CMakeLists.txt",
    "content": "project(EigenDemos)\n\nadd_custom_target(demos)\n\nif(NOT EIGEN_TEST_NOQT)\n  find_package(Qt4)\n  if(QT4_FOUND)\n    add_subdirectory(mandelbrot)\n    add_subdirectory(opengl)\n  else()\n    message(STATUS \"Qt4 not found, so disabling the mandelbrot and opengl demos\")\n  endif()\nendif()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/mandelbrot/CMakeLists.txt",
    "content": "find_package(Qt4 REQUIRED)\n\nset(CMAKE_INCLUDE_CURRENT_DIR ON)\n\nif (CMAKE_COMPILER_IS_GNUCXX)\n   set ( CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -O2\")\n   add_definitions ( \"-DNDEBUG\" )\nendif ()\n\ninclude_directories( ${QT_INCLUDE_DIR} )\n\nset(mandelbrot_SRCS\n    mandelbrot.cpp\n)\n\nqt4_automoc(${mandelbrot_SRCS})\n\nadd_executable(mandelbrot ${mandelbrot_SRCS})\nadd_dependencies(demos mandelbrot)\n\ntarget_link_libraries(mandelbrot ${QT_QTCORE_LIBRARY} ${QT_QTGUI_LIBRARY})\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/mandelbrot/README",
    "content": "*** Mandelbrot demo ***\n\nControls:\n* Left mouse button to center view at a point.\n* Drag vertically with left mouse button to zoom in and out.\n\nBe sure to enable SSE2 or AltiVec to improve performance.\n\nThe number of iterations, and the choice between single and double precision, are\ndetermined at runtime depending on the zoom level.\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/mandelbrot/mandelbrot.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"mandelbrot.h\"\n#include <iostream>\n#include<QtGui/QPainter>\n#include<QtGui/QImage>\n#include<QtGui/QMouseEvent>\n#include<QtCore/QTime>\n\nvoid MandelbrotWidget::resizeEvent(QResizeEvent *)\n{\n  if(size < width() * height())\n  {\n    std::cout << \"reallocate buffer\" << std::endl;\n    size = width() * height();\n    if(buffer) delete[]buffer;\n    buffer = new unsigned char[4*size];\n  }\n}\n\ntemplate<typename T> struct iters_before_test { enum { ret = 8 }; };\ntemplate<> struct iters_before_test<double> { enum { ret = 16 }; };\n\ntemplate<typename Real> void MandelbrotThread::render(int img_width, int img_height)\n{\n  enum { packetSize = Eigen::internal::packet_traits<Real>::size }; // number of reals in a Packet\n  typedef Eigen::Array<Real, packetSize, 1> Packet; // wrap a Packet as a vector\n\n  enum { iters_before_test = iters_before_test<Real>::ret };\n  max_iter = (max_iter / iters_before_test) * iters_before_test;\n  const int alignedWidth = (img_width/packetSize)*packetSize;\n  unsigned char *const buffer = widget->buffer;\n  const double xradius = widget->xradius;\n  const double yradius = xradius * img_height / img_width;\n  const int threadcount = widget->threadcount;\n  typedef Eigen::Array<Real, 2, 1> Vector2;\n  Vector2 start(widget->center.x() - widget->xradius, widget->center.y() - yradius);\n  Vector2 step(2*widget->xradius/img_width, 2*yradius/img_height);\n  total_iter = 0;\n\n  for(int y = id; y < img_height; y += threadcount)\n  {\n    int pix = y * img_width;\n\n    // for each pixel, we're going to do the iteration z := z^2 + c where z and c are complex numbers, \n    // starting with z = c = complex coord of the pixel. pzi and pzr denote the real and imaginary parts of z.\n    // pci and pcr denote the real and imaginary parts of c.\n\n    Packet pzi_start, pci_start;\n    for(int i = 0; i < packetSize; i++) pzi_start[i] = pci_start[i] = start.y() + y * step.y();\n\n    for(int x = 0; x < alignedWidth; x += packetSize, pix += packetSize)\n    {\n      Packet pcr, pci = pci_start, pzr, pzi = pzi_start, pzr_buf;\n      for(int i = 0; i < packetSize; i++) pzr[i] = pcr[i] = start.x() + (x+i) * step.x();\n\n      // do the iterations. Every iters_before_test iterations we check for divergence,\n      // in which case we can stop iterating.\n      int j = 0;\n      typedef Eigen::Matrix<int, packetSize, 1> Packeti;\n      Packeti pix_iter = Packeti::Zero(), // number of iteration per pixel in the packet\n              pix_dont_diverge; // whether or not each pixel has already diverged\n      do\n      {\n        for(int i = 0; i < iters_before_test/4; i++) // peel the inner loop by 4\n        {\n#         define ITERATE \\\n            pzr_buf = pzr; \\\n            pzr = pzr.square(); \\\n            pzr -= pzi.square(); \\\n            pzr += pcr; \\\n            pzi = (2*pzr_buf)*pzi; \\\n            pzi += pci;\n          ITERATE ITERATE ITERATE ITERATE\n        }\n        pix_dont_diverge = ((pzr.square() + pzi.square())\n                           .eval() // temporary fix as what follows is not yet vectorized by Eigen\n                           <= Packet::Constant(4))\n                                // the 4 here is not a magic value, it's a math fact that if\n                                // the square modulus is >4 then divergence is inevitable.\n                           .template cast<int>();\n        pix_iter += iters_before_test * pix_dont_diverge;\n        j++;\n        total_iter += iters_before_test * packetSize;\n      }\n      while(j < max_iter/iters_before_test && pix_dont_diverge.any()); // any() is not yet vectorized by Eigen\n\n      // compute pixel colors\n      for(int i = 0; i < packetSize; i++)\n      {\n        buffer[4*(pix+i)] = 255*pix_iter[i]/max_iter;\n        buffer[4*(pix+i)+1] = 0;\n        buffer[4*(pix+i)+2] = 0;\n      }\n    }\n\n    // if the width is not a multiple of packetSize, fill the remainder in black\n    for(int x = alignedWidth; x < img_width; x++, pix++)\n      buffer[4*pix] = buffer[4*pix+1] = buffer[4*pix+2] = 0;\n  }\n  return;\n}\n\nvoid MandelbrotThread::run()\n{\n  setTerminationEnabled(true);\n  double resolution = widget->xradius*2/widget->width();\n  max_iter = 128;\n  if(resolution < 1e-4f) max_iter += 128 * ( - 4 - std::log10(resolution));\n  int img_width = widget->width()/widget->draft;\n  int img_height = widget->height()/widget->draft;\n  single_precision = resolution > 1e-7f;\n\n  if(single_precision)\n    render<float>(img_width, img_height);\n  else\n    render<double>(img_width, img_height);\n}\n\nvoid MandelbrotWidget::paintEvent(QPaintEvent *)\n{\n  static float max_speed = 0;\n  long long total_iter = 0;\n\n  QTime time;\n  time.start();\n  for(int th = 0; th < threadcount; th++)\n    threads[th]->start(QThread::LowPriority);\n  for(int th = 0; th < threadcount; th++)\n  {\n    threads[th]->wait();\n    total_iter += threads[th]->total_iter;\n  }\n  int elapsed = time.elapsed();\n\n  if(draft == 1)\n  {\n    float speed = elapsed ? float(total_iter)*1000/elapsed : 0;\n    max_speed = std::max(max_speed, speed);\n    std::cout << threadcount << \" threads, \"\n              << elapsed << \" ms, \"\n              << speed << \" iters/s (max \" << max_speed << \")\" << std::endl;\n    int packetSize = threads[0]->single_precision\n                   ? int(Eigen::internal::packet_traits<float>::size)\n                   : int(Eigen::internal::packet_traits<double>::size);\n    setWindowTitle(QString(\"resolution \")+QString::number(xradius*2/width(), 'e', 2)\n                  +QString(\", %1 iterations per pixel, \").arg(threads[0]->max_iter)\n                  +(threads[0]->single_precision ? QString(\"single \") : QString(\"double \"))\n                  +QString(\"precision, \")\n                  +(packetSize==1 ? QString(\"no vectorization\")\n                                  : QString(\"vectorized (%1 per packet)\").arg(packetSize)));\n  }\n  \n  QImage image(buffer, width()/draft, height()/draft, QImage::Format_RGB32);\n  QPainter painter(this);\n  painter.drawImage(QPoint(0, 0), image.scaled(width(), height()));\n\n  if(draft>1)\n  {\n    draft /= 2;\n    setWindowTitle(QString(\"recomputing at 1/%1 resolution...\").arg(draft));\n    update();\n  }\n}\n\nvoid MandelbrotWidget::mousePressEvent(QMouseEvent *event)\n{\n  if( event->buttons() & Qt::LeftButton )\n  {\n    lastpos = event->pos();\n    double yradius = xradius * height() / width();\n    center = Eigen::Vector2d(center.x() + (event->pos().x() - width()/2) * xradius * 2 / width(),\n                             center.y() + (event->pos().y() - height()/2) * yradius * 2 / height());\n    draft = 16;\n    for(int th = 0; th < threadcount; th++)\n      threads[th]->terminate();\n    update();\n  }\n}\n\nvoid MandelbrotWidget::mouseMoveEvent(QMouseEvent *event)\n{\n  QPoint delta = event->pos() - lastpos;\n  lastpos = event->pos();\n  if( event->buttons() & Qt::LeftButton )\n  {\n    double t = 1 + 5 * double(delta.y()) / height();\n    if(t < 0.5) t = 0.5;\n    if(t > 2) t = 2;\n    xradius *= t;\n    draft = 16;\n    for(int th = 0; th < threadcount; th++)\n      threads[th]->terminate();\n    update();\n  }\n}\n\nint main(int argc, char *argv[])\n{\n  QApplication app(argc, argv);\n  MandelbrotWidget w;\n  w.show();\n  return app.exec();\n}\n\n#include \"mandelbrot.moc\"\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/mandelbrot/mandelbrot.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef MANDELBROT_H\n#define MANDELBROT_H\n\n#include <Eigen/Core>\n#include <QtGui/QApplication>\n#include <QtGui/QWidget>\n#include <QtCore/QThread>\n\nclass MandelbrotWidget;\n\nclass MandelbrotThread : public QThread\n{\n    friend class MandelbrotWidget;\n    MandelbrotWidget *widget;\n    long long total_iter;\n    int id, max_iter;\n    bool single_precision;\n\n  public:\n    MandelbrotThread(MandelbrotWidget *w, int i) : widget(w), id(i) {}\n    void run();\n    template<typename Real> void render(int img_width, int img_height);\n};\n\nclass MandelbrotWidget : public QWidget\n{\n    Q_OBJECT\n\n    friend class MandelbrotThread;\n    Eigen::Vector2d center;\n    double xradius;\n    int size;\n    unsigned char *buffer;\n    QPoint lastpos;\n    int draft;\n    MandelbrotThread **threads;\n    int threadcount;\n\n  protected:\n    void resizeEvent(QResizeEvent *);\n    void paintEvent(QPaintEvent *);\n    void mousePressEvent(QMouseEvent *event);\n    void mouseMoveEvent(QMouseEvent *event);\n\n  public:\n    MandelbrotWidget() : QWidget(), center(0,0), xradius(2),\n                         size(0), buffer(0), draft(16)\n    {\n      setAutoFillBackground(false);\n      threadcount = QThread::idealThreadCount();\n      threads = new MandelbrotThread*[threadcount];\n      for(int th = 0; th < threadcount; th++) threads[th] = new MandelbrotThread(this, th);\n    }\n    ~MandelbrotWidget()\n    {\n      if(buffer) delete[]buffer;\n      for(int th = 0; th < threadcount; th++) delete threads[th];\n      delete[] threads;\n    }\n};\n\n#endif // MANDELBROT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/mix_eigen_and_c/README",
    "content": "This is an example of how one can wrap some of Eigen into a C library.\n\nTo try this with GCC, do:\n\n  g++ -c binary_library.cpp -O2 -msse2 -I ../..\n  gcc example.c binary_library.o -o example -lstdc++\n  ./example\n\nTODO: add CMakeLists, add more explanations here\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/mix_eigen_and_c/binary_library.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// This C++ file compiles to binary code that can be linked to by your C program,\n// thanks to the extern \"C\" syntax used in the declarations in binary_library.h.\n\n#include \"binary_library.h\"\n\n#include <Eigen/Core>\n\nusing namespace Eigen;\n\n/************************* pointer conversion methods **********************************************/\n\n////// class MatrixXd //////\n\ninline MatrixXd& c_to_eigen(C_MatrixXd* ptr)\n{\n  return *reinterpret_cast<MatrixXd*>(ptr);\n}\n\ninline const MatrixXd& c_to_eigen(const C_MatrixXd* ptr)\n{\n  return *reinterpret_cast<const MatrixXd*>(ptr);\n}\n\ninline C_MatrixXd* eigen_to_c(MatrixXd& ref)\n{\n  return reinterpret_cast<C_MatrixXd*>(&ref);\n}\n\ninline const C_MatrixXd* eigen_to_c(const MatrixXd& ref)\n{\n  return reinterpret_cast<const C_MatrixXd*>(&ref);\n}\n\n////// class Map<MatrixXd> //////\n\ninline Map<MatrixXd>& c_to_eigen(C_Map_MatrixXd* ptr)\n{\n  return *reinterpret_cast<Map<MatrixXd>*>(ptr);\n}\n\ninline const Map<MatrixXd>& c_to_eigen(const C_Map_MatrixXd* ptr)\n{\n  return *reinterpret_cast<const Map<MatrixXd>*>(ptr);\n}\n\ninline C_Map_MatrixXd* eigen_to_c(Map<MatrixXd>& ref)\n{\n  return reinterpret_cast<C_Map_MatrixXd*>(&ref);\n}\n\ninline const C_Map_MatrixXd* eigen_to_c(const Map<MatrixXd>& ref)\n{\n  return reinterpret_cast<const C_Map_MatrixXd*>(&ref);\n}\n\n\n/************************* implementation of classes **********************************************/\n\n\n////// class MatrixXd //////\n\n\nC_MatrixXd* MatrixXd_new(int rows, int cols)\n{\n  return eigen_to_c(*new MatrixXd(rows,cols));\n}\n\nvoid MatrixXd_delete(C_MatrixXd *m)\n{\n  delete &c_to_eigen(m);\n}\n\ndouble* MatrixXd_data(C_MatrixXd *m)\n{\n  return c_to_eigen(m).data();\n}\n\nvoid MatrixXd_set_zero(C_MatrixXd *m)\n{\n  c_to_eigen(m).setZero();\n}\n\nvoid MatrixXd_resize(C_MatrixXd *m, int rows, int cols)\n{\n  c_to_eigen(m).resize(rows,cols);\n}\n\nvoid MatrixXd_copy(C_MatrixXd *dst, const C_MatrixXd *src)\n{\n  c_to_eigen(dst) = c_to_eigen(src);\n}\n\nvoid MatrixXd_copy_map(C_MatrixXd *dst, const C_Map_MatrixXd *src)\n{\n  c_to_eigen(dst) = c_to_eigen(src);\n}\n\nvoid MatrixXd_set_coeff(C_MatrixXd *m, int i, int j, double coeff)\n{\n  c_to_eigen(m)(i,j) = coeff;\n}\n\ndouble MatrixXd_get_coeff(const C_MatrixXd *m, int i, int j)\n{\n  return c_to_eigen(m)(i,j);\n}\n\nvoid MatrixXd_print(const C_MatrixXd *m)\n{\n  std::cout << c_to_eigen(m) << std::endl;\n}\n\nvoid MatrixXd_multiply(const C_MatrixXd *m1, const C_MatrixXd *m2, C_MatrixXd *result)\n{\n  c_to_eigen(result) = c_to_eigen(m1) * c_to_eigen(m2);\n}\n\nvoid MatrixXd_add(const C_MatrixXd *m1, const C_MatrixXd *m2, C_MatrixXd *result)\n{\n  c_to_eigen(result) = c_to_eigen(m1) + c_to_eigen(m2);\n}\n\n\n\n////// class Map_MatrixXd //////\n\n\nC_Map_MatrixXd* Map_MatrixXd_new(double *array, int rows, int cols)\n{\n  return eigen_to_c(*new Map<MatrixXd>(array,rows,cols));\n}\n\nvoid Map_MatrixXd_delete(C_Map_MatrixXd *m)\n{\n  delete &c_to_eigen(m);\n}\n\nvoid Map_MatrixXd_set_zero(C_Map_MatrixXd *m)\n{\n  c_to_eigen(m).setZero();\n}\n\nvoid Map_MatrixXd_copy(C_Map_MatrixXd *dst, const C_Map_MatrixXd *src)\n{\n  c_to_eigen(dst) = c_to_eigen(src);\n}\n\nvoid Map_MatrixXd_copy_matrix(C_Map_MatrixXd *dst, const C_MatrixXd *src)\n{\n  c_to_eigen(dst) = c_to_eigen(src);\n}\n\nvoid Map_MatrixXd_set_coeff(C_Map_MatrixXd *m, int i, int j, double coeff)\n{\n  c_to_eigen(m)(i,j) = coeff;\n}\n\ndouble Map_MatrixXd_get_coeff(const C_Map_MatrixXd *m, int i, int j)\n{\n  return c_to_eigen(m)(i,j);\n}\n\nvoid Map_MatrixXd_print(const C_Map_MatrixXd *m)\n{\n  std::cout << c_to_eigen(m) << std::endl;\n}\n\nvoid Map_MatrixXd_multiply(const C_Map_MatrixXd *m1, const C_Map_MatrixXd *m2, C_Map_MatrixXd *result)\n{\n  c_to_eigen(result) = c_to_eigen(m1) * c_to_eigen(m2);\n}\n\nvoid Map_MatrixXd_add(const C_Map_MatrixXd *m1, const C_Map_MatrixXd *m2, C_Map_MatrixXd *result)\n{\n  c_to_eigen(result) = c_to_eigen(m1) + c_to_eigen(m2);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/mix_eigen_and_c/binary_library.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// This is a pure C header, no C++ here.\n// The functions declared here will be implemented in C++ but\n// we don't have to know, because thanks to the extern \"C\" syntax,\n// they will be compiled to C object code.\n\n#ifdef __cplusplus\nextern \"C\"\n{\n#endif\n\n  // just dummy empty structs to give different pointer types,\n  // instead of using void* which would be type unsafe\n  struct C_MatrixXd {};\n  struct C_Map_MatrixXd {};\n\n  // the C_MatrixXd class, wraps some of the functionality\n  // of Eigen::MatrixXd.\n  struct C_MatrixXd* MatrixXd_new(int rows, int cols);\n  void    MatrixXd_delete     (struct C_MatrixXd *m);\n  double* MatrixXd_data       (struct C_MatrixXd *m);\n  void    MatrixXd_set_zero   (struct C_MatrixXd *m);\n  void    MatrixXd_resize     (struct C_MatrixXd *m, int rows, int cols);\n  void    MatrixXd_copy       (struct C_MatrixXd *dst,\n                               const struct C_MatrixXd *src);\n  void    MatrixXd_copy_map   (struct C_MatrixXd *dst,\n                               const struct C_Map_MatrixXd *src);  \n  void    MatrixXd_set_coeff  (struct C_MatrixXd *m,\n                               int i, int j, double coeff);\n  double  MatrixXd_get_coeff  (const struct C_MatrixXd *m,\n                               int i, int j);\n  void    MatrixXd_print      (const struct C_MatrixXd *m);\n  void    MatrixXd_add        (const struct C_MatrixXd *m1,\n                               const struct C_MatrixXd *m2,\n                               struct C_MatrixXd *result);  \n  void    MatrixXd_multiply   (const struct C_MatrixXd *m1,\n                               const struct C_MatrixXd *m2,\n                               struct C_MatrixXd *result);\n  \n  // the C_Map_MatrixXd class, wraps some of the functionality\n  // of Eigen::Map<MatrixXd>\n  struct C_Map_MatrixXd* Map_MatrixXd_new(double *array, int rows, int cols);\n  void   Map_MatrixXd_delete     (struct C_Map_MatrixXd *m);\n  void   Map_MatrixXd_set_zero   (struct C_Map_MatrixXd *m);\n  void   Map_MatrixXd_copy       (struct C_Map_MatrixXd *dst,\n                                  const struct C_Map_MatrixXd *src);\n  void   Map_MatrixXd_copy_matrix(struct C_Map_MatrixXd *dst,\n                                  const struct C_MatrixXd *src);  \n  void   Map_MatrixXd_set_coeff  (struct C_Map_MatrixXd *m,\n                                  int i, int j, double coeff);\n  double Map_MatrixXd_get_coeff  (const struct C_Map_MatrixXd *m,\n                                  int i, int j);\n  void   Map_MatrixXd_print      (const struct C_Map_MatrixXd *m);\n  void   Map_MatrixXd_add        (const struct C_Map_MatrixXd *m1,\n                                  const struct C_Map_MatrixXd *m2,\n                                  struct C_Map_MatrixXd *result);  \n  void   Map_MatrixXd_multiply   (const struct C_Map_MatrixXd *m1,\n                                  const struct C_Map_MatrixXd *m2,\n                                  struct C_Map_MatrixXd *result);\n\n#ifdef __cplusplus\n} // end extern \"C\"\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/mix_eigen_and_c/example.c",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"binary_library.h\"\n#include \"stdio.h\"\n\nvoid demo_MatrixXd()\n{\n  struct C_MatrixXd *matrix1, *matrix2, *result;\n  printf(\"*** demo_MatrixXd ***\\n\");\n  \n  matrix1 = MatrixXd_new(3, 3);\n  MatrixXd_set_zero(matrix1);\n  MatrixXd_set_coeff(matrix1, 0, 1, 2.5);\n  MatrixXd_set_coeff(matrix1, 1, 0, 1.4);\n  printf(\"Here is matrix1:\\n\");\n  MatrixXd_print(matrix1);\n\n  matrix2 = MatrixXd_new(3, 3);\n  MatrixXd_multiply(matrix1, matrix1, matrix2);\n  printf(\"Here is matrix1*matrix1:\\n\");\n  MatrixXd_print(matrix2);\n\n  MatrixXd_delete(matrix1);\n  MatrixXd_delete(matrix2);\n}\n\n// this helper function takes a plain C array and prints it in one line\nvoid print_array(double *array, int n)\n{\n  struct C_Map_MatrixXd *m = Map_MatrixXd_new(array, 1, n);\n  Map_MatrixXd_print(m);\n  Map_MatrixXd_delete(m);\n}\n\nvoid demo_Map_MatrixXd()\n{\n  struct C_Map_MatrixXd *map;\n  double array[5];\n  int i;\n  printf(\"*** demo_Map_MatrixXd ***\\n\");\n  \n  for(i = 0; i < 5; ++i) array[i] = i;\n  printf(\"Initially, the array is:\\n\");\n  print_array(array, 5);\n  \n  map = Map_MatrixXd_new(array, 5, 1);\n  Map_MatrixXd_add(map, map, map);\n  Map_MatrixXd_delete(map);\n\n  printf(\"Now the array is:\\n\");\n  print_array(array, 5);\n}\n\nint main()\n{\n  demo_MatrixXd();\n  demo_Map_MatrixXd();\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/opengl/CMakeLists.txt",
    "content": "find_package(Qt4)\nfind_package(OpenGL)\n\nif(QT4_FOUND AND OPENGL_FOUND)\n\n  set(QT_USE_QTOPENGL TRUE)\n  include(${QT_USE_FILE})\n\n  set(CMAKE_INCLUDE_CURRENT_DIR ON)\n\n  include_directories( ${QT_INCLUDE_DIR} )\n\n  set(quaternion_demo_SRCS  gpuhelper.cpp icosphere.cpp camera.cpp trackball.cpp quaternion_demo.cpp)\n\n  qt4_automoc(${quaternion_demo_SRCS})\n\n  add_executable(quaternion_demo ${quaternion_demo_SRCS})\n  add_dependencies(demos quaternion_demo)\n\n  target_link_libraries(quaternion_demo\n    ${QT_QTCORE_LIBRARY}    ${QT_QTGUI_LIBRARY}\n    ${QT_QTOPENGL_LIBRARY}  ${OPENGL_LIBRARIES} )\n\nelse()\n\n  message(STATUS \"OpenGL demo disabled because Qt4 and/or OpenGL have not been found.\")\n\nendif()"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/opengl/README",
    "content": "\nNavigation:\n left button:           rotate around the target\n middle button:         zoom\n left button + ctrl     quake rotate (rotate around camera position)\n middle button + ctrl   walk (progress along camera's z direction)\n left button:           pan (translate in the XY camera's plane)\n\nR : move the camera to initial position\nA : start/stop animation\nC : clear the animation\nG : add a key frame\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/opengl/camera.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"camera.h\"\n\n#include \"gpuhelper.h\"\n#include <GL/glu.h>\n\n#include \"Eigen/LU\"\nusing namespace Eigen;\n\nCamera::Camera()\n    : mViewIsUptodate(false), mProjIsUptodate(false)\n{\n    mViewMatrix.setIdentity();\n    \n    mFovY = M_PI/3.;\n    mNearDist = 1.;\n    mFarDist = 50000.;\n    \n    mVpX = 0;\n    mVpY = 0;\n\n    setPosition(Vector3f::Constant(100.));\n    setTarget(Vector3f::Zero());\n}\n\nCamera& Camera::operator=(const Camera& other)\n{\n    mViewIsUptodate = false;\n    mProjIsUptodate = false;\n    \n    mVpX = other.mVpX;\n    mVpY = other.mVpY;\n    mVpWidth = other.mVpWidth;\n    mVpHeight = other.mVpHeight;\n\n    mTarget = other.mTarget;\n    mFovY = other.mFovY;\n    mNearDist = other.mNearDist;\n    mFarDist = other.mFarDist;\n    \n    mViewMatrix = other.mViewMatrix;\n    mProjectionMatrix = other.mProjectionMatrix;\n\n    return *this;\n}\n\nCamera::Camera(const Camera& other)\n{\n    *this = other;\n}\n\nCamera::~Camera()\n{\n}\n\n\nvoid Camera::setViewport(uint offsetx, uint offsety, uint width, uint height)\n{\n    mVpX = offsetx;\n    mVpY = offsety;\n    mVpWidth = width;\n    mVpHeight = height;\n    \n    mProjIsUptodate = false;\n}\n\nvoid Camera::setViewport(uint width, uint height)\n{\n    mVpWidth = width;\n    mVpHeight = height;\n    \n    mProjIsUptodate = false;\n}\n\nvoid Camera::setFovY(float value)\n{\n    mFovY = value;\n    mProjIsUptodate = false;\n}\n\nVector3f Camera::direction(void) const\n{\n    return - (orientation() * Vector3f::UnitZ());\n}\nVector3f Camera::up(void) const\n{\n    return orientation() * Vector3f::UnitY();\n}\nVector3f Camera::right(void) const\n{\n    return orientation() * Vector3f::UnitX();\n}\n\nvoid Camera::setDirection(const Vector3f& newDirection)\n{\n    // TODO implement it computing the rotation between newDirection and current dir ?\n    Vector3f up = this->up();\n    \n    Matrix3f camAxes;\n\n    camAxes.col(2) = (-newDirection).normalized();\n    camAxes.col(0) = up.cross( camAxes.col(2) ).normalized();\n    camAxes.col(1) = camAxes.col(2).cross( camAxes.col(0) ).normalized();\n    setOrientation(Quaternionf(camAxes));\n    \n    mViewIsUptodate = false;\n}\n\nvoid Camera::setTarget(const Vector3f& target)\n{\n    mTarget = target;\n    if (!mTarget.isApprox(position()))\n    {\n        Vector3f newDirection = mTarget - position();\n        setDirection(newDirection.normalized());\n    }\n}\n\nvoid Camera::setPosition(const Vector3f& p)\n{\n    mFrame.position = p;\n    mViewIsUptodate = false;\n}\n\nvoid Camera::setOrientation(const Quaternionf& q)\n{\n    mFrame.orientation = q;\n    mViewIsUptodate = false;\n}\n\nvoid Camera::setFrame(const Frame& f)\n{\n  mFrame = f;\n  mViewIsUptodate = false;\n}\n\nvoid Camera::rotateAroundTarget(const Quaternionf& q)\n{\n    Matrix4f mrot, mt, mtm;\n    \n    // update the transform matrix\n    updateViewMatrix();\n    Vector3f t = mViewMatrix * mTarget;\n\n    mViewMatrix = Translation3f(t)\n                * q\n                * Translation3f(-t)\n                * mViewMatrix;\n    \n    Quaternionf qa(mViewMatrix.linear());\n    qa = qa.conjugate();\n    setOrientation(qa);\n    setPosition(- (qa * mViewMatrix.translation()) );\n\n    mViewIsUptodate = true;\n}\n\nvoid Camera::localRotate(const Quaternionf& q)\n{\n    float dist = (position() - mTarget).norm();\n    setOrientation(orientation() * q);\n    mTarget = position() + dist * direction();\n    mViewIsUptodate = false;\n}\n\nvoid Camera::zoom(float d)\n{\n    float dist = (position() - mTarget).norm();\n    if(dist > d)\n    {\n        setPosition(position() + direction() * d);\n        mViewIsUptodate = false;\n    }\n}\n\nvoid Camera::localTranslate(const Vector3f& t)\n{\n  Vector3f trans = orientation() * t;\n  setPosition( position() + trans );\n  setTarget( mTarget + trans );\n\n  mViewIsUptodate = false;\n}\n\nvoid Camera::updateViewMatrix(void) const\n{\n    if(!mViewIsUptodate)\n    {\n        Quaternionf q = orientation().conjugate();\n        mViewMatrix.linear() = q.toRotationMatrix();\n        mViewMatrix.translation() = - (mViewMatrix.linear() * position());\n\n        mViewIsUptodate = true;\n    }\n}\n\nconst Affine3f& Camera::viewMatrix(void) const\n{\n  updateViewMatrix();\n  return mViewMatrix;\n}\n\nvoid Camera::updateProjectionMatrix(void) const\n{\n  if(!mProjIsUptodate)\n  {\n    mProjectionMatrix.setIdentity();\n    float aspect = float(mVpWidth)/float(mVpHeight);\n    float theta = mFovY*0.5;\n    float range = mFarDist - mNearDist;\n    float invtan = 1./tan(theta);\n\n    mProjectionMatrix(0,0) = invtan / aspect;\n    mProjectionMatrix(1,1) = invtan;\n    mProjectionMatrix(2,2) = -(mNearDist + mFarDist) / range;\n    mProjectionMatrix(3,2) = -1;\n    mProjectionMatrix(2,3) = -2 * mNearDist * mFarDist / range;\n    mProjectionMatrix(3,3) = 0;\n    \n    mProjIsUptodate = true;\n  }\n}\n\nconst Matrix4f& Camera::projectionMatrix(void) const\n{\n  updateProjectionMatrix();\n  return mProjectionMatrix;\n}\n\nvoid Camera::activateGL(void)\n{\n  glViewport(vpX(), vpY(), vpWidth(), vpHeight());\n  gpu.loadMatrix(projectionMatrix(),GL_PROJECTION);\n  gpu.loadMatrix(viewMatrix().matrix(),GL_MODELVIEW);\n}\n\n\nVector3f Camera::unProject(const Vector2f& uv, float depth) const\n{\n    Matrix4f inv = mViewMatrix.inverse().matrix();\n    return unProject(uv, depth, inv);\n}\n\nVector3f Camera::unProject(const Vector2f& uv, float depth, const Matrix4f& invModelview) const\n{\n    updateViewMatrix();\n    updateProjectionMatrix();\n    \n    Vector3f a(2.*uv.x()/float(mVpWidth)-1., 2.*uv.y()/float(mVpHeight)-1., 1.);\n    a.x() *= depth/mProjectionMatrix(0,0);\n    a.y() *= depth/mProjectionMatrix(1,1);\n    a.z() = -depth;\n    // FIXME /\\/|\n    Vector4f b = invModelview * Vector4f(a.x(), a.y(), a.z(), 1.);\n    return Vector3f(b.x(), b.y(), b.z());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/opengl/camera.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CAMERA_H\n#define EIGEN_CAMERA_H\n\n#include <Eigen/Geometry>\n#include <QObject>\n// #include <frame.h>\n\nclass Frame\n{\n  public:\n    EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n    \n    inline Frame(const Eigen::Vector3f& pos = Eigen::Vector3f::Zero(),\n                 const Eigen::Quaternionf& o = Eigen::Quaternionf())\n      : orientation(o), position(pos)\n    {}\n    Frame lerp(float alpha, const Frame& other) const\n    {\n      return Frame((1.f-alpha)*position + alpha * other.position,\n                   orientation.slerp(alpha,other.orientation));\n    }\n\n    Eigen::Quaternionf orientation;\n    Eigen::Vector3f position;\n};\n\nclass Camera\n{\n  public:\n    EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n\n    Camera(void);\n    \n    Camera(const Camera& other);\n    \n    virtual ~Camera();\n    \n    Camera& operator=(const Camera& other);\n    \n    void setViewport(uint offsetx, uint offsety, uint width, uint height);\n    void setViewport(uint width, uint height);\n    \n    inline uint vpX(void) const { return mVpX; }\n    inline uint vpY(void) const { return mVpY; }\n    inline uint vpWidth(void) const { return mVpWidth; }\n    inline uint vpHeight(void) const { return mVpHeight; }\n\n    inline float fovY(void) const { return mFovY; }\n    void setFovY(float value);\n    \n    void setPosition(const Eigen::Vector3f& pos);\n    inline const Eigen::Vector3f& position(void) const { return mFrame.position; }\n\n    void setOrientation(const Eigen::Quaternionf& q);\n    inline const Eigen::Quaternionf& orientation(void) const { return mFrame.orientation; }\n\n    void setFrame(const Frame& f);\n    const Frame& frame(void) const { return mFrame; }\n    \n    void setDirection(const Eigen::Vector3f& newDirection);\n    Eigen::Vector3f direction(void) const;\n    void setUp(const Eigen::Vector3f& vectorUp);\n    Eigen::Vector3f up(void) const;\n    Eigen::Vector3f right(void) const;\n    \n    void setTarget(const Eigen::Vector3f& target);\n    inline const Eigen::Vector3f& target(void) { return mTarget; }\n    \n    const Eigen::Affine3f& viewMatrix(void) const;\n    const Eigen::Matrix4f& projectionMatrix(void) const;\n    \n    void rotateAroundTarget(const Eigen::Quaternionf& q);\n    void localRotate(const Eigen::Quaternionf& q);\n    void zoom(float d);\n    \n    void localTranslate(const Eigen::Vector3f& t);\n    \n    /** Setup OpenGL matrices and viewport */\n    void activateGL(void);\n    \n    Eigen::Vector3f unProject(const Eigen::Vector2f& uv, float depth, const Eigen::Matrix4f& invModelview) const;\n    Eigen::Vector3f unProject(const Eigen::Vector2f& uv, float depth) const;\n    \n  protected:\n    void updateViewMatrix(void) const;\n    void updateProjectionMatrix(void) const;\n\n  protected:\n\n    uint mVpX, mVpY;\n    uint mVpWidth, mVpHeight;\n\n    Frame mFrame;\n    \n    mutable Eigen::Affine3f mViewMatrix;\n    mutable Eigen::Matrix4f mProjectionMatrix;\n\n    mutable bool mViewIsUptodate;\n    mutable bool mProjIsUptodate;\n\n    // used by rotateAroundTarget\n    Eigen::Vector3f mTarget;\n    \n    float mFovY;\n    float mNearDist;\n    float mFarDist;\n};\n\n#endif // EIGEN_CAMERA_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/opengl/gpuhelper.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"gpuhelper.h\"\n#include \"icosphere.h\"\n#include <GL/glu.h>\n// PLEASE don't look at this old code... ;)\n\n#include <fstream>\n#include <algorithm>\n\nGpuHelper gpu;\n\nGpuHelper::GpuHelper()\n{\n    mVpWidth = mVpHeight = 0;\n    mCurrentMatrixTarget = 0;\n    mInitialized = false;\n}\n\nGpuHelper::~GpuHelper()\n{\n}\n\nvoid GpuHelper::pushProjectionMode2D(ProjectionMode2D pm)\n{\n    // switch to 2D projection\n    pushMatrix(Matrix4f::Identity(),GL_PROJECTION);\n\n    if(pm==PM_Normalized)\n    {\n        //glOrtho(-1., 1., -1., 1., 0., 1.);\n    }\n    else if(pm==PM_Viewport)\n    {\n        GLint vp[4];\n        glGetIntegerv(GL_VIEWPORT, vp);\n        glOrtho(0., vp[2], 0., vp[3], -1., 1.);\n    }\n\n    pushMatrix(Matrix4f::Identity(),GL_MODELVIEW);\n}\n\nvoid GpuHelper::popProjectionMode2D(void)\n{\n    popMatrix(GL_PROJECTION);\n    popMatrix(GL_MODELVIEW);\n}\n\nvoid GpuHelper::drawVector(const Vector3f& position, const Vector3f& vec, const Color& color, float aspect /* = 50.*/)\n{\n    static GLUquadricObj *cylindre = gluNewQuadric();\n    glColor4fv(color.data());\n    float length = vec.norm();\n    pushMatrix(GL_MODELVIEW);\n    glTranslatef(position.x(), position.y(), position.z());\n    Vector3f ax = Matrix3f::Identity().col(2).cross(vec);\n    ax.normalize();\n    Vector3f tmp = vec;\n    tmp.normalize();\n    float angle = 180.f/M_PI * acos(tmp.z());\n    if (angle>1e-3)\n        glRotatef(angle, ax.x(), ax.y(), ax.z());\n    gluCylinder(cylindre, length/aspect, length/aspect, 0.8*length, 10, 10);\n    glTranslatef(0.0,0.0,0.8*length);\n    gluCylinder(cylindre, 2.0*length/aspect, 0.0, 0.2*length, 10, 10);\n\n    popMatrix(GL_MODELVIEW);\n}\n\nvoid GpuHelper::drawVectorBox(const Vector3f& position, const Vector3f& vec, const Color& color, float aspect)\n{\n    static GLUquadricObj *cylindre = gluNewQuadric();\n    glColor4fv(color.data());\n    float length = vec.norm();\n    pushMatrix(GL_MODELVIEW);\n    glTranslatef(position.x(), position.y(), position.z());\n    Vector3f ax = Matrix3f::Identity().col(2).cross(vec);\n    ax.normalize();\n    Vector3f tmp = vec;\n    tmp.normalize();\n    float angle = 180.f/M_PI * acos(tmp.z());\n    if (angle>1e-3)\n        glRotatef(angle, ax.x(), ax.y(), ax.z());\n    gluCylinder(cylindre, length/aspect, length/aspect, 0.8*length, 10, 10);\n    glTranslatef(0.0,0.0,0.8*length);\n    glScalef(4.0*length/aspect,4.0*length/aspect,4.0*length/aspect);\n    drawUnitCube();\n    popMatrix(GL_MODELVIEW);\n}\n\nvoid GpuHelper::drawUnitCube(void)\n{\n    static float vertices[][3] = {\n        {-0.5,-0.5,-0.5},\n        { 0.5,-0.5,-0.5},\n        {-0.5, 0.5,-0.5},\n        { 0.5, 0.5,-0.5},\n        {-0.5,-0.5, 0.5},\n        { 0.5,-0.5, 0.5},\n        {-0.5, 0.5, 0.5},\n        { 0.5, 0.5, 0.5}};\n\n    glBegin(GL_QUADS);\n    glNormal3f(0,0,-1); glVertex3fv(vertices[0]); glVertex3fv(vertices[2]); glVertex3fv(vertices[3]); glVertex3fv(vertices[1]);\n    glNormal3f(0,0, 1); glVertex3fv(vertices[4]); glVertex3fv(vertices[5]); glVertex3fv(vertices[7]); glVertex3fv(vertices[6]);\n    glNormal3f(0,-1,0); glVertex3fv(vertices[0]); glVertex3fv(vertices[1]); glVertex3fv(vertices[5]); glVertex3fv(vertices[4]);\n    glNormal3f(0, 1,0); glVertex3fv(vertices[2]); glVertex3fv(vertices[6]); glVertex3fv(vertices[7]); glVertex3fv(vertices[3]);\n    glNormal3f(-1,0,0); glVertex3fv(vertices[0]); glVertex3fv(vertices[4]); glVertex3fv(vertices[6]); glVertex3fv(vertices[2]);\n    glNormal3f( 1,0,0); glVertex3fv(vertices[1]); glVertex3fv(vertices[3]); glVertex3fv(vertices[7]); glVertex3fv(vertices[5]);\n    glEnd();\n}\n\nvoid GpuHelper::drawUnitSphere(int level)\n{\n  static IcoSphere sphere;\n  sphere.draw(level);\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/opengl/gpuhelper.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_GPUHELPER_H\n#define EIGEN_GPUHELPER_H\n\n#include <Eigen/Geometry>\n#include <GL/gl.h>\n#include <vector>\n\nusing namespace Eigen;\n\ntypedef Vector4f Color;\n\nclass GpuHelper\n{\n  public:\n\n    GpuHelper();\n\n    ~GpuHelper();\n\n    enum ProjectionMode2D { PM_Normalized = 1, PM_Viewport = 2 };\n    void pushProjectionMode2D(ProjectionMode2D pm);\n    void popProjectionMode2D();\n\n    /** Multiply the OpenGL matrix \\a matrixTarget by the matrix \\a mat.\n        Essentially, this helper function automatically calls glMatrixMode(matrixTarget) if required\n        and does a proper call to the right glMultMatrix*() function according to the scalar type\n        and storage order.\n        \\warning glMatrixMode() must never be called directly. If your're unsure, use forceMatrixMode().\n        \\sa Matrix, loadMatrix(), forceMatrixMode()\n    */\n    template<typename Scalar, int _Flags>\n    void multMatrix(const Matrix<Scalar,4,4, _Flags, 4,4>& mat, GLenum matrixTarget);\n\n    /** Load the matrix \\a mat to the OpenGL matrix \\a matrixTarget.\n        Essentially, this helper function automatically calls glMatrixMode(matrixTarget) if required\n        and does a proper call to the right glLoadMatrix*() or glLoadIdentity() function according to the scalar type\n        and storage order.\n        \\warning glMatrixMode() must never be called directly. If your're unsure, use forceMatrixMode().\n        \\sa Matrix, multMatrix(), forceMatrixMode()\n    */\n    template<typename Scalar, int _Flags>\n    void loadMatrix(const Eigen::Matrix<Scalar,4,4, _Flags, 4,4>& mat, GLenum matrixTarget);\n\n    template<typename Scalar, typename Derived>\n    void loadMatrix(\n        const Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<Scalar>,Derived>&,\n        GLenum matrixTarget);\n\n    /** Make the matrix \\a matrixTarget the current OpenGL matrix target.\n        Call this function before loadMatrix() or multMatrix() if you cannot guarantee that glMatrixMode()\n        has never been called after the last loadMatrix() or multMatrix() calls.\n        \\todo provides a debug mode checking the sanity of the cached matrix mode.\n    */\n    inline void forceMatrixTarget(GLenum matrixTarget) {glMatrixMode(mCurrentMatrixTarget=matrixTarget);}\n\n    inline void setMatrixTarget(GLenum matrixTarget);\n\n    /** Push the OpenGL matrix \\a matrixTarget and load \\a mat.\n    */\n    template<typename Scalar, int _Flags>\n    inline void pushMatrix(const Matrix<Scalar,4,4, _Flags, 4,4>& mat, GLenum matrixTarget);\n\n    template<typename Scalar, typename Derived>\n    void pushMatrix(\n        const Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<Scalar>,Derived>&,\n        GLenum matrixTarget);\n\n    /** Push and clone the OpenGL matrix \\a matrixTarget\n    */\n    inline void pushMatrix(GLenum matrixTarget);\n\n    /** Pop the OpenGL matrix \\a matrixTarget\n    */\n    inline void popMatrix(GLenum matrixTarget);\n\n    void drawVector(const Vector3f& position, const Vector3f& vec, const Color& color, float aspect = 50.);\n    void drawVectorBox(const Vector3f& position, const Vector3f& vec, const Color& color, float aspect = 50.);\n    void drawUnitCube(void);\n    void drawUnitSphere(int level=0);\n\n    /// draw the \\a nofElement first elements\n    inline void draw(GLenum mode, uint nofElement);\n\n    /// draw a range of elements\n    inline void draw(GLenum mode, uint start, uint end);\n\n    /// draw an indexed subset\n    inline void draw(GLenum mode, const std::vector<uint>* pIndexes);\n\nprotected:\n\n    void update(void);\n\n    GLuint mColorBufferId;\n    int mVpWidth, mVpHeight;\n    GLenum mCurrentMatrixTarget;\n    bool mInitialized;\n};\n\n/** Singleton shortcut\n*/\nextern GpuHelper gpu;\n\n\n/** \\internal\n*/\ntemplate<bool RowMajor, int _Flags> struct GlMatrixHelper;\n\ntemplate<int _Flags> struct GlMatrixHelper<false,_Flags>\n{\n    static void loadMatrix(const Matrix<float, 4,4, _Flags, 4,4>&  mat) { glLoadMatrixf(mat.data()); }\n    static void loadMatrix(const Matrix<double,4,4, _Flags, 4,4>& mat) { glLoadMatrixd(mat.data()); }\n    static void multMatrix(const Matrix<float, 4,4, _Flags, 4,4>&  mat) { glMultMatrixf(mat.data()); }\n    static void multMatrix(const Matrix<double,4,4, _Flags, 4,4>& mat) { glMultMatrixd(mat.data()); }\n};\n\ntemplate<int _Flags> struct GlMatrixHelper<true,_Flags>\n{\n    static void loadMatrix(const Matrix<float, 4,4, _Flags, 4,4>&  mat) { glLoadMatrixf(mat.transpose().eval().data()); }\n    static void loadMatrix(const Matrix<double,4,4, _Flags, 4,4>& mat) { glLoadMatrixd(mat.transpose().eval().data()); }\n    static void multMatrix(const Matrix<float, 4,4, _Flags, 4,4>&  mat) { glMultMatrixf(mat.transpose().eval().data()); }\n    static void multMatrix(const Matrix<double,4,4, _Flags, 4,4>& mat) { glMultMatrixd(mat.transpose().eval().data()); }\n};\n\ninline void GpuHelper::setMatrixTarget(GLenum matrixTarget)\n{\n    if (matrixTarget != mCurrentMatrixTarget)\n        glMatrixMode(mCurrentMatrixTarget=matrixTarget);\n}\n\ntemplate<typename Scalar, int _Flags>\nvoid GpuHelper::multMatrix(const Matrix<Scalar,4,4, _Flags, 4,4>& mat, GLenum matrixTarget)\n{\n    setMatrixTarget(matrixTarget);\n    GlMatrixHelper<_Flags&Eigen::RowMajorBit, _Flags>::multMatrix(mat);\n}\n\ntemplate<typename Scalar, typename Derived>\nvoid GpuHelper::loadMatrix(\n    const Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<Scalar>,Derived>&,\n    GLenum matrixTarget)\n{\n    setMatrixTarget(matrixTarget);\n    glLoadIdentity();\n}\n\ntemplate<typename Scalar, int _Flags>\nvoid GpuHelper::loadMatrix(const Eigen::Matrix<Scalar,4,4, _Flags, 4,4>& mat, GLenum matrixTarget)\n{\n    setMatrixTarget(matrixTarget);\n    GlMatrixHelper<(_Flags&Eigen::RowMajorBit)!=0, _Flags>::loadMatrix(mat);\n}\n\ninline void GpuHelper::pushMatrix(GLenum matrixTarget)\n{\n    setMatrixTarget(matrixTarget);\n    glPushMatrix();\n}\n\ntemplate<typename Scalar, int _Flags>\ninline void GpuHelper::pushMatrix(const Matrix<Scalar,4,4, _Flags, 4,4>& mat, GLenum matrixTarget)\n{\n    pushMatrix(matrixTarget);\n    GlMatrixHelper<_Flags&Eigen::RowMajorBit,_Flags>::loadMatrix(mat);\n}\n\ntemplate<typename Scalar, typename Derived>\nvoid GpuHelper::pushMatrix(\n    const Eigen::CwiseNullaryOp<Eigen::internal::scalar_identity_op<Scalar>,Derived>&,\n    GLenum matrixTarget)\n{\n    pushMatrix(matrixTarget);\n    glLoadIdentity();\n}\n\ninline void GpuHelper::popMatrix(GLenum matrixTarget)\n{\n    setMatrixTarget(matrixTarget);\n    glPopMatrix();\n}\n\ninline void GpuHelper::draw(GLenum mode, uint nofElement)\n{\n    glDrawArrays(mode, 0, nofElement);\n}\n\n\ninline void GpuHelper::draw(GLenum mode, const std::vector<uint>* pIndexes)\n{\n    glDrawElements(mode, pIndexes->size(), GL_UNSIGNED_INT, &(pIndexes->front()));\n}\n\ninline void GpuHelper::draw(GLenum mode, uint start, uint end)\n{\n    glDrawArrays(mode, start, end-start);\n}\n\n#endif // EIGEN_GPUHELPER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/opengl/icosphere.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"icosphere.h\"\n\n#include <GL/gl.h>\n#include <map>\n\nusing namespace Eigen;\n\n//--------------------------------------------------------------------------------\n// icosahedron data\n//--------------------------------------------------------------------------------\n#define X .525731112119133606\n#define Z .850650808352039932\n\nstatic GLfloat vdata[12][3] = {\n   {-X, 0.0, Z}, {X, 0.0, Z}, {-X, 0.0, -Z}, {X, 0.0, -Z},\n   {0.0, Z, X}, {0.0, Z, -X}, {0.0, -Z, X}, {0.0, -Z, -X},\n   {Z, X, 0.0}, {-Z, X, 0.0}, {Z, -X, 0.0}, {-Z, -X, 0.0}\n};\n\nstatic GLint tindices[20][3] = {\n   {0,4,1}, {0,9,4}, {9,5,4}, {4,5,8}, {4,8,1},\n   {8,10,1}, {8,3,10}, {5,3,8}, {5,2,3}, {2,7,3},\n   {7,10,3}, {7,6,10}, {7,11,6}, {11,0,6}, {0,1,6},\n   {6,1,10}, {9,0,11}, {9,11,2}, {9,2,5}, {7,2,11} };\n//--------------------------------------------------------------------------------\n\nIcoSphere::IcoSphere(unsigned int levels)\n{\n  // init with an icosahedron\n  for (int i = 0; i < 12; i++)\n    mVertices.push_back(Map<Vector3f>(vdata[i]));\n  mIndices.push_back(new std::vector<int>);\n  std::vector<int>& indices = *mIndices.back();\n  for (int i = 0; i < 20; i++)\n  {\n    for (int k = 0; k < 3; k++)\n      indices.push_back(tindices[i][k]);\n  }\n  mListIds.push_back(0);\n\n  while(mIndices.size()<levels)\n    _subdivide();\n}\n\nconst std::vector<int>& IcoSphere::indices(int level) const\n{\n  while (level>=int(mIndices.size()))\n    const_cast<IcoSphere*>(this)->_subdivide();\n  return *mIndices[level];\n}\n\nvoid IcoSphere::_subdivide(void)\n{\n  typedef unsigned long long Key;\n  std::map<Key,int> edgeMap;\n  const std::vector<int>& indices = *mIndices.back();\n  mIndices.push_back(new std::vector<int>);\n  std::vector<int>& refinedIndices = *mIndices.back();\n  int end = indices.size();\n  for (int i=0; i<end; i+=3)\n  {\n    int ids0[3],  // indices of outer vertices\n        ids1[3];  // indices of edge vertices\n    for (int k=0; k<3; ++k)\n    {\n      int k1 = (k+1)%3;\n      int e0 = indices[i+k];\n      int e1 = indices[i+k1];\n      ids0[k] = e0;\n      if (e1>e0)\n        std::swap(e0,e1);\n      Key edgeKey = Key(e0) | (Key(e1)<<32);\n      std::map<Key,int>::iterator it = edgeMap.find(edgeKey);\n      if (it==edgeMap.end())\n      {\n        ids1[k] = mVertices.size();\n        edgeMap[edgeKey] = ids1[k];\n        mVertices.push_back( (mVertices[e0]+mVertices[e1]).normalized() );\n      }\n      else\n        ids1[k] = it->second;\n    }\n    refinedIndices.push_back(ids0[0]); refinedIndices.push_back(ids1[0]); refinedIndices.push_back(ids1[2]);\n    refinedIndices.push_back(ids0[1]); refinedIndices.push_back(ids1[1]); refinedIndices.push_back(ids1[0]);\n    refinedIndices.push_back(ids0[2]); refinedIndices.push_back(ids1[2]); refinedIndices.push_back(ids1[1]);\n    refinedIndices.push_back(ids1[0]); refinedIndices.push_back(ids1[1]); refinedIndices.push_back(ids1[2]);\n  }\n  mListIds.push_back(0);\n}\n\nvoid IcoSphere::draw(int level)\n{\n  while (level>=int(mIndices.size()))\n    const_cast<IcoSphere*>(this)->_subdivide();\n  if (mListIds[level]==0)\n  {\n    mListIds[level] = glGenLists(1);\n    glNewList(mListIds[level], GL_COMPILE);\n      glVertexPointer(3, GL_FLOAT, 0, mVertices[0].data());\n      glNormalPointer(GL_FLOAT, 0, mVertices[0].data());\n      glEnableClientState(GL_VERTEX_ARRAY);\n      glEnableClientState(GL_NORMAL_ARRAY);\n      glDrawElements(GL_TRIANGLES, mIndices[level]->size(), GL_UNSIGNED_INT, &(mIndices[level]->at(0)));\n      glDisableClientState(GL_VERTEX_ARRAY);\n      glDisableClientState(GL_NORMAL_ARRAY);\n    glEndList();\n  }\n  glCallList(mListIds[level]);\n}\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/opengl/icosphere.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ICOSPHERE_H\n#define EIGEN_ICOSPHERE_H\n\n#include <Eigen/Core>\n#include <vector>\n\nclass IcoSphere\n{\n  public:\n    IcoSphere(unsigned int levels=1);\n    const std::vector<Eigen::Vector3f>& vertices() const { return mVertices; }\n    const std::vector<int>& indices(int level) const;\n    void draw(int level);\n  protected:\n    void _subdivide();\n    std::vector<Eigen::Vector3f> mVertices;\n    std::vector<std::vector<int>*> mIndices;\n    std::vector<int> mListIds;\n};\n\n#endif // EIGEN_ICOSPHERE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/opengl/quaternion_demo.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"quaternion_demo.h\"\n#include \"icosphere.h\"\n\n#include <Eigen/Geometry>\n#include <Eigen/QR>\n#include <Eigen/LU>\n\n#include <iostream>\n#include <QEvent>\n#include <QMouseEvent>\n#include <QInputDialog>\n#include <QGridLayout>\n#include <QButtonGroup>\n#include <QRadioButton>\n#include <QDockWidget>\n#include <QPushButton>\n#include <QGroupBox>\n\nusing namespace Eigen;\n\nclass FancySpheres\n{\n  public:\n    EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n    \n    FancySpheres()\n    {\n      const int levels = 4;\n      const float scale = 0.33;\n      float radius = 100;\n      std::vector<int> parents;\n\n      // leval 0\n      mCenters.push_back(Vector3f::Zero());\n      parents.push_back(-1);\n      mRadii.push_back(radius);\n\n      // generate level 1 using icosphere vertices\n      radius *= 0.45;\n      {\n        float dist = mRadii[0]*0.9;\n        for (int i=0; i<12; ++i)\n        {\n          mCenters.push_back(mIcoSphere.vertices()[i] * dist);\n          mRadii.push_back(radius);\n          parents.push_back(0);\n        }\n      }\n\n      static const float angles [10] = {\n        0, 0,\n        M_PI, 0.*M_PI,\n        M_PI, 0.5*M_PI,\n        M_PI, 1.*M_PI,\n        M_PI, 1.5*M_PI\n      };\n\n      // generate other levels\n      int start = 1;\n      for (int l=1; l<levels; l++)\n      {\n        radius *= scale;\n        int end = mCenters.size();\n        for (int i=start; i<end; ++i)\n        {\n          Vector3f c = mCenters[i];\n          Vector3f ax0 = (c - mCenters[parents[i]]).normalized();\n          Vector3f ax1 = ax0.unitOrthogonal();\n          Quaternionf q;\n          q.setFromTwoVectors(Vector3f::UnitZ(), ax0);\n          Affine3f t = Translation3f(c) * q * Scaling(mRadii[i]+radius);\n          for (int j=0; j<5; ++j)\n          {\n            Vector3f newC = c + ( (AngleAxisf(angles[j*2+1], ax0)\n                                * AngleAxisf(angles[j*2+0] * (l==1 ? 0.35 : 0.5), ax1)) * ax0)\n                                * (mRadii[i] + radius*0.8);\n            mCenters.push_back(newC);\n            mRadii.push_back(radius);\n            parents.push_back(i);\n          }\n        }\n        start = end;\n      }\n    }\n\n    void draw()\n    {\n      int end = mCenters.size();\n      glEnable(GL_NORMALIZE);\n      for (int i=0; i<end; ++i)\n      {\n        Affine3f t = Translation3f(mCenters[i]) * Scaling(mRadii[i]);\n        gpu.pushMatrix(GL_MODELVIEW);\n        gpu.multMatrix(t.matrix(),GL_MODELVIEW);\n        mIcoSphere.draw(2);\n        gpu.popMatrix(GL_MODELVIEW);\n      }\n      glDisable(GL_NORMALIZE);\n    }\n  protected:\n    std::vector<Vector3f> mCenters;\n    std::vector<float> mRadii;\n    IcoSphere mIcoSphere;\n};\n\n\n// generic linear interpolation method\ntemplate<typename T> T lerp(float t, const T& a, const T& b)\n{\n  return a*(1-t) + b*t;\n}\n\n// quaternion slerp\ntemplate<> Quaternionf lerp(float t, const Quaternionf& a, const Quaternionf& b)\n{ return a.slerp(t,b); }\n\n// linear interpolation of a frame using the type OrientationType\n// to perform the interpolation of the orientations\ntemplate<typename OrientationType>\ninline static Frame lerpFrame(float alpha, const Frame& a, const Frame& b)\n{\n  return Frame(lerp(alpha,a.position,b.position),\n               Quaternionf(lerp(alpha,OrientationType(a.orientation),OrientationType(b.orientation))));\n}\n\ntemplate<typename _Scalar> class EulerAngles\n{\npublic:\n  enum { Dim = 3 };\n  typedef _Scalar Scalar;\n  typedef Matrix<Scalar,3,3> Matrix3;\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef Quaternion<Scalar> QuaternionType;\n\nprotected:\n\n  Vector3 m_angles;\n\npublic:\n\n  EulerAngles() {}\n  inline EulerAngles(Scalar a0, Scalar a1, Scalar a2) : m_angles(a0, a1, a2) {}\n  inline EulerAngles(const QuaternionType& q) { *this = q; }\n\n  const Vector3& coeffs() const { return m_angles; }\n  Vector3& coeffs() { return m_angles; }\n\n  EulerAngles& operator=(const QuaternionType& q)\n  {\n    Matrix3 m = q.toRotationMatrix();\n    return *this = m;\n  }\n\n  EulerAngles& operator=(const Matrix3& m)\n  {\n    // mat =  cy*cz          -cy*sz           sy\n    //        cz*sx*sy+cx*sz  cx*cz-sx*sy*sz -cy*sx\n    //       -cx*cz*sy+sx*sz  cz*sx+cx*sy*sz  cx*cy\n    m_angles.coeffRef(1) = std::asin(m.coeff(0,2));\n    m_angles.coeffRef(0) = std::atan2(-m.coeff(1,2),m.coeff(2,2));\n    m_angles.coeffRef(2) = std::atan2(-m.coeff(0,1),m.coeff(0,0));\n    return *this;\n  }\n\n  Matrix3 toRotationMatrix(void) const\n  {\n    Vector3 c = m_angles.array().cos();\n    Vector3 s = m_angles.array().sin();\n    Matrix3 res;\n    res <<  c.y()*c.z(),                    -c.y()*s.z(),                   s.y(),\n            c.z()*s.x()*s.y()+c.x()*s.z(),  c.x()*c.z()-s.x()*s.y()*s.z(),  -c.y()*s.x(),\n            -c.x()*c.z()*s.y()+s.x()*s.z(), c.z()*s.x()+c.x()*s.y()*s.z(),  c.x()*c.y();\n    return res;\n  }\n\n  operator QuaternionType() { return QuaternionType(toRotationMatrix()); }\n};\n\n// Euler angles slerp\ntemplate<> EulerAngles<float> lerp(float t, const EulerAngles<float>& a, const EulerAngles<float>& b)\n{\n  EulerAngles<float> res;\n  res.coeffs() = lerp(t, a.coeffs(), b.coeffs());\n  return res;\n}\n\n\nRenderingWidget::RenderingWidget()\n{\n  mAnimate = false;\n  mCurrentTrackingMode = TM_NO_TRACK;\n  mNavMode = NavTurnAround;\n  mLerpMode = LerpQuaternion;\n  mRotationMode = RotationStable;\n  mTrackball.setCamera(&mCamera);\n\n  // required to capture key press events\n  setFocusPolicy(Qt::ClickFocus);\n}\n\nvoid RenderingWidget::grabFrame(void)\n{\n    // ask user for a time\n    bool ok = false;\n    double t = 0;\n    if (!m_timeline.empty())\n      t = (--m_timeline.end())->first + 1.;\n    t = QInputDialog::getDouble(this, \"Eigen's RenderingWidget\", \"time value: \",\n      t, 0, 1e3, 1, &ok);\n    if (ok)\n    {\n      Frame aux;\n      aux.orientation = mCamera.viewMatrix().linear();\n      aux.position = mCamera.viewMatrix().translation();\n      m_timeline[t] = aux;\n    }\n}\n\nvoid RenderingWidget::drawScene()\n{\n  static FancySpheres sFancySpheres;\n  float length = 50;\n  gpu.drawVector(Vector3f::Zero(), length*Vector3f::UnitX(), Color(1,0,0,1));\n  gpu.drawVector(Vector3f::Zero(), length*Vector3f::UnitY(), Color(0,1,0,1));\n  gpu.drawVector(Vector3f::Zero(), length*Vector3f::UnitZ(), Color(0,0,1,1));\n\n  // draw the fractal object\n  float sqrt3 = std::sqrt(3.);\n  glLightfv(GL_LIGHT0, GL_AMBIENT, Vector4f(0.5,0.5,0.5,1).data());\n  glLightfv(GL_LIGHT0, GL_DIFFUSE, Vector4f(0.5,1,0.5,1).data());\n  glLightfv(GL_LIGHT0, GL_SPECULAR, Vector4f(1,1,1,1).data());\n  glLightfv(GL_LIGHT0, GL_POSITION, Vector4f(-sqrt3,-sqrt3,sqrt3,0).data());\n\n  glLightfv(GL_LIGHT1, GL_AMBIENT, Vector4f(0,0,0,1).data());\n  glLightfv(GL_LIGHT1, GL_DIFFUSE, Vector4f(1,0.5,0.5,1).data());\n  glLightfv(GL_LIGHT1, GL_SPECULAR, Vector4f(1,1,1,1).data());\n  glLightfv(GL_LIGHT1, GL_POSITION, Vector4f(-sqrt3,sqrt3,-sqrt3,0).data());\n\n  glMaterialfv(GL_FRONT_AND_BACK, GL_AMBIENT, Vector4f(0.7, 0.7, 0.7, 1).data());\n  glMaterialfv(GL_FRONT_AND_BACK, GL_DIFFUSE, Vector4f(0.8, 0.75, 0.6, 1).data());\n  glMaterialfv(GL_FRONT_AND_BACK, GL_SPECULAR, Vector4f(1, 1, 1, 1).data());\n  glMaterialf(GL_FRONT_AND_BACK, GL_SHININESS, 64);\n\n  glEnable(GL_LIGHTING);\n  glEnable(GL_LIGHT0);\n  glEnable(GL_LIGHT1);\n\n  sFancySpheres.draw();\n  glVertexPointer(3, GL_FLOAT, 0, mVertices[0].data());\n  glNormalPointer(GL_FLOAT, 0, mNormals[0].data());\n  glEnableClientState(GL_VERTEX_ARRAY);\n  glEnableClientState(GL_NORMAL_ARRAY);\n  glDrawArrays(GL_TRIANGLES, 0, mVertices.size());\n  glDisableClientState(GL_VERTEX_ARRAY);\n  glDisableClientState(GL_NORMAL_ARRAY);\n\n  glDisable(GL_LIGHTING);\n}\n\nvoid RenderingWidget::animate()\n{\n  m_alpha += double(m_timer.interval()) * 1e-3;\n\n  TimeLine::const_iterator hi = m_timeline.upper_bound(m_alpha);\n  TimeLine::const_iterator lo = hi;\n  --lo;\n\n  Frame currentFrame;\n\n  if(hi==m_timeline.end())\n  {\n    // end\n    currentFrame = lo->second;\n    stopAnimation();\n  }\n  else if(hi==m_timeline.begin())\n  {\n    // start\n    currentFrame = hi->second;\n  }\n  else\n  {\n    float s = (m_alpha - lo->first)/(hi->first - lo->first);\n    if (mLerpMode==LerpEulerAngles)\n      currentFrame = ::lerpFrame<EulerAngles<float> >(s, lo->second, hi->second);\n    else if (mLerpMode==LerpQuaternion)\n      currentFrame = ::lerpFrame<Eigen::Quaternionf>(s, lo->second, hi->second);\n    else\n    {\n      std::cerr << \"Invalid rotation interpolation mode (abort)\\n\";\n      exit(2);\n    }\n    currentFrame.orientation.coeffs().normalize();\n  }\n\n  currentFrame.orientation = currentFrame.orientation.inverse();\n  currentFrame.position = - (currentFrame.orientation * currentFrame.position);\n  mCamera.setFrame(currentFrame);\n\n  updateGL();\n}\n\nvoid RenderingWidget::keyPressEvent(QKeyEvent * e)\n{\n    switch(e->key())\n    {\n      case Qt::Key_Up:\n        mCamera.zoom(2);\n        break;\n      case Qt::Key_Down:\n        mCamera.zoom(-2);\n        break;\n      // add a frame\n      case Qt::Key_G:\n        grabFrame();\n        break;\n      // clear the time line\n      case Qt::Key_C:\n        m_timeline.clear();\n        break;\n      // move the camera to initial pos\n      case Qt::Key_R:\n        resetCamera();\n        break;\n      // start/stop the animation\n      case Qt::Key_A:\n        if (mAnimate)\n        {\n          stopAnimation();\n        }\n        else\n        {\n          m_alpha = 0;\n          connect(&m_timer, SIGNAL(timeout()), this, SLOT(animate()));\n          m_timer.start(1000/30);\n          mAnimate = true;\n        }\n        break;\n      default:\n        break;\n    }\n\n    updateGL();\n}\n\nvoid RenderingWidget::stopAnimation()\n{\n  disconnect(&m_timer, SIGNAL(timeout()), this, SLOT(animate()));\n  m_timer.stop();\n  mAnimate = false;\n  m_alpha = 0;\n}\n\nvoid RenderingWidget::mousePressEvent(QMouseEvent* e)\n{\n  mMouseCoords = Vector2i(e->pos().x(), e->pos().y());\n  bool fly = (mNavMode==NavFly) || (e->modifiers()&Qt::ControlModifier);\n  switch(e->button())\n  {\n    case Qt::LeftButton:\n      if(fly)\n      {\n        mCurrentTrackingMode = TM_LOCAL_ROTATE;\n        mTrackball.start(Trackball::Local);\n      }\n      else\n      {\n        mCurrentTrackingMode = TM_ROTATE_AROUND;\n        mTrackball.start(Trackball::Around);\n      }\n      mTrackball.track(mMouseCoords);\n      break;\n    case Qt::MidButton:\n      if(fly)\n        mCurrentTrackingMode = TM_FLY_Z;\n      else\n        mCurrentTrackingMode = TM_ZOOM;\n      break;\n    case Qt::RightButton:\n        mCurrentTrackingMode = TM_FLY_PAN;\n      break;\n    default:\n      break;\n  }\n}\nvoid RenderingWidget::mouseReleaseEvent(QMouseEvent*)\n{\n    mCurrentTrackingMode = TM_NO_TRACK;\n    updateGL();\n}\n\nvoid RenderingWidget::mouseMoveEvent(QMouseEvent* e)\n{\n    // tracking\n    if(mCurrentTrackingMode != TM_NO_TRACK)\n    {\n        float dx =   float(e->x() - mMouseCoords.x()) / float(mCamera.vpWidth());\n        float dy = - float(e->y() - mMouseCoords.y()) / float(mCamera.vpHeight());\n\n        // speedup the transformations\n        if(e->modifiers() & Qt::ShiftModifier)\n        {\n          dx *= 10.;\n          dy *= 10.;\n        }\n\n        switch(mCurrentTrackingMode)\n        {\n          case TM_ROTATE_AROUND:\n          case TM_LOCAL_ROTATE:\n            if (mRotationMode==RotationStable)\n            {\n              // use the stable trackball implementation mapping\n              // the 2D coordinates to 3D points on a sphere.\n              mTrackball.track(Vector2i(e->pos().x(), e->pos().y()));\n            }\n            else\n            {\n              // standard approach mapping the x and y displacements as rotations\n              // around the camera's X and Y axes.\n              Quaternionf q = AngleAxisf( dx*M_PI, Vector3f::UnitY())\n                            * AngleAxisf(-dy*M_PI, Vector3f::UnitX());\n              if (mCurrentTrackingMode==TM_LOCAL_ROTATE)\n                mCamera.localRotate(q);\n              else\n                mCamera.rotateAroundTarget(q);\n            }\n            break;\n          case TM_ZOOM :\n            mCamera.zoom(dy*100);\n            break;\n          case TM_FLY_Z :\n            mCamera.localTranslate(Vector3f(0, 0, -dy*200));\n            break;\n          case TM_FLY_PAN :\n            mCamera.localTranslate(Vector3f(dx*200, dy*200, 0));\n            break;\n          default:\n            break;\n        }\n\n        updateGL();\n    }\n\n    mMouseCoords = Vector2i(e->pos().x(), e->pos().y());\n}\n\nvoid RenderingWidget::paintGL()\n{\n  glEnable(GL_DEPTH_TEST);\n  glDisable(GL_CULL_FACE);\n  glPolygonMode(GL_FRONT_AND_BACK,GL_FILL);\n  glDisable(GL_COLOR_MATERIAL);\n  glDisable(GL_BLEND);\n  glDisable(GL_ALPHA_TEST);\n  glDisable(GL_TEXTURE_1D);\n  glDisable(GL_TEXTURE_2D);\n  glDisable(GL_TEXTURE_3D);\n\n  // Clear buffers\n  glClear(GL_COLOR_BUFFER_BIT | GL_DEPTH_BUFFER_BIT);\n\n  mCamera.activateGL();\n\n  drawScene();\n}\n\nvoid RenderingWidget::initializeGL()\n{\n  glClearColor(1., 1., 1., 0.);\n  glLightModeli(GL_LIGHT_MODEL_LOCAL_VIEWER, 1);\n  glDepthMask(GL_TRUE);\n  glColorMask(GL_TRUE, GL_TRUE, GL_TRUE, GL_TRUE);\n\n  mCamera.setPosition(Vector3f(-200, -200, -200));\n  mCamera.setTarget(Vector3f(0, 0, 0));\n  mInitFrame.orientation = mCamera.orientation().inverse();\n  mInitFrame.position = mCamera.viewMatrix().translation();\n}\n\nvoid RenderingWidget::resizeGL(int width, int height)\n{\n    mCamera.setViewport(width,height);\n}\n\nvoid RenderingWidget::setNavMode(int m)\n{\n  mNavMode = NavMode(m);\n}\n\nvoid RenderingWidget::setLerpMode(int m)\n{\n  mLerpMode = LerpMode(m);\n}\n\nvoid RenderingWidget::setRotationMode(int m)\n{\n  mRotationMode = RotationMode(m);\n}\n\nvoid RenderingWidget::resetCamera()\n{\n  if (mAnimate)\n    stopAnimation();\n  m_timeline.clear();\n  Frame aux0 = mCamera.frame();\n  aux0.orientation = aux0.orientation.inverse();\n  aux0.position = mCamera.viewMatrix().translation();\n  m_timeline[0] = aux0;\n\n  Vector3f currentTarget = mCamera.target();\n  mCamera.setTarget(Vector3f::Zero());\n\n  // compute the rotation duration to move the camera to the target\n  Frame aux1 = mCamera.frame();\n  aux1.orientation = aux1.orientation.inverse();\n  aux1.position = mCamera.viewMatrix().translation();\n  float duration = aux0.orientation.angularDistance(aux1.orientation) * 0.9;\n  if (duration<0.1) duration = 0.1;\n\n  // put the camera at that time step:\n  aux1 = aux0.lerp(duration/2,mInitFrame);\n  // and make it look at the target again\n  aux1.orientation = aux1.orientation.inverse();\n  aux1.position = - (aux1.orientation * aux1.position);\n  mCamera.setFrame(aux1);\n  mCamera.setTarget(Vector3f::Zero());\n\n  // add this camera keyframe\n  aux1.orientation = aux1.orientation.inverse();\n  aux1.position = mCamera.viewMatrix().translation();\n  m_timeline[duration] = aux1;\n\n  m_timeline[2] = mInitFrame;\n  m_alpha = 0;\n  animate();\n  connect(&m_timer, SIGNAL(timeout()), this, SLOT(animate()));\n  m_timer.start(1000/30);\n  mAnimate = true;\n}\n\nQWidget* RenderingWidget::createNavigationControlWidget()\n{\n  QWidget* panel = new QWidget();\n  QVBoxLayout* layout = new QVBoxLayout();\n\n  {\n    QPushButton* but = new QPushButton(\"reset\");\n    but->setToolTip(\"move the camera to initial position (with animation)\");\n    layout->addWidget(but);\n    connect(but, SIGNAL(clicked()), this, SLOT(resetCamera()));\n  }\n  {\n    // navigation mode\n    QGroupBox* box = new QGroupBox(\"navigation mode\");\n    QVBoxLayout* boxLayout = new QVBoxLayout;\n    QButtonGroup* group = new QButtonGroup(panel);\n    QRadioButton* but;\n    but = new QRadioButton(\"turn around\");\n    but->setToolTip(\"look around an object\");\n    group->addButton(but, NavTurnAround);\n    boxLayout->addWidget(but);\n    but = new QRadioButton(\"fly\");\n    but->setToolTip(\"free navigation like a spaceship\\n(this mode can also be enabled pressing the \\\"shift\\\" key)\");\n    group->addButton(but, NavFly);\n    boxLayout->addWidget(but);\n    group->button(mNavMode)->setChecked(true);\n    connect(group, SIGNAL(buttonClicked(int)), this, SLOT(setNavMode(int)));\n    box->setLayout(boxLayout);\n    layout->addWidget(box);\n  }\n  {\n    // track ball, rotation mode\n    QGroupBox* box = new QGroupBox(\"rotation mode\");\n    QVBoxLayout* boxLayout = new QVBoxLayout;\n    QButtonGroup* group = new QButtonGroup(panel);\n    QRadioButton* but;\n    but = new QRadioButton(\"stable trackball\");\n    group->addButton(but, RotationStable);\n    boxLayout->addWidget(but);\n    but->setToolTip(\"use the stable trackball implementation mapping\\nthe 2D coordinates to 3D points on a sphere\");\n    but = new QRadioButton(\"standard rotation\");\n    group->addButton(but, RotationStandard);\n    boxLayout->addWidget(but);\n    but->setToolTip(\"standard approach mapping the x and y displacements\\nas rotations around the camera's X and Y axes\");\n    group->button(mRotationMode)->setChecked(true);\n    connect(group, SIGNAL(buttonClicked(int)), this, SLOT(setRotationMode(int)));\n    box->setLayout(boxLayout);\n    layout->addWidget(box);\n  }\n  {\n    // interpolation mode\n    QGroupBox* box = new QGroupBox(\"spherical interpolation\");\n    QVBoxLayout* boxLayout = new QVBoxLayout;\n    QButtonGroup* group = new QButtonGroup(panel);\n    QRadioButton* but;\n    but = new QRadioButton(\"quaternion slerp\");\n    group->addButton(but, LerpQuaternion);\n    boxLayout->addWidget(but);\n    but->setToolTip(\"use quaternion spherical interpolation\\nto interpolate orientations\");\n    but = new QRadioButton(\"euler angles\");\n    group->addButton(but, LerpEulerAngles);\n    boxLayout->addWidget(but);\n    but->setToolTip(\"use Euler angles to interpolate orientations\");\n    group->button(mNavMode)->setChecked(true);\n    connect(group, SIGNAL(buttonClicked(int)), this, SLOT(setLerpMode(int)));\n    box->setLayout(boxLayout);\n    layout->addWidget(box);\n  }\n  layout->addItem(new QSpacerItem(0,0,QSizePolicy::Minimum,QSizePolicy::Expanding));\n  panel->setLayout(layout);\n  return panel;\n}\n\nQuaternionDemo::QuaternionDemo()\n{\n  mRenderingWidget = new RenderingWidget();\n  setCentralWidget(mRenderingWidget);\n\n  QDockWidget* panel = new QDockWidget(\"navigation\", this);\n  panel->setAllowedAreas((QFlags<Qt::DockWidgetArea>)(Qt::RightDockWidgetArea | Qt::LeftDockWidgetArea));\n  addDockWidget(Qt::RightDockWidgetArea, panel);\n  panel->setWidget(mRenderingWidget->createNavigationControlWidget());\n}\n\nint main(int argc, char *argv[])\n{\n  std::cout << \"Navigation:\\n\";\n  std::cout << \"  left button:           rotate around the target\\n\";\n  std::cout << \"  middle button:         zoom\\n\";\n  std::cout << \"  left button + ctrl     quake rotate (rotate around camera position)\\n\";\n  std::cout << \"  middle button + ctrl   walk (progress along camera's z direction)\\n\";\n  std::cout << \"  left button:           pan (translate in the XY camera's plane)\\n\\n\";\n  std::cout << \"R : move the camera to initial position\\n\";\n  std::cout << \"A : start/stop animation\\n\";\n  std::cout << \"C : clear the animation\\n\";\n  std::cout << \"G : add a key frame\\n\";\n\n  QApplication app(argc, argv);\n  QuaternionDemo demo;\n  demo.resize(600,500);\n  demo.show();\n  return app.exec();\n}\n\n#include \"quaternion_demo.moc\"\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/opengl/quaternion_demo.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_QUATERNION_DEMO_H\n#define EIGEN_QUATERNION_DEMO_H\n\n#include \"gpuhelper.h\"\n#include \"camera.h\"\n#include \"trackball.h\"\n#include <map>\n#include <QTimer>\n#include <QtGui/QApplication>\n#include <QtOpenGL/QGLWidget>\n#include <QtGui/QMainWindow>\n\nclass RenderingWidget : public QGLWidget\n{\n  Q_OBJECT\n\n    typedef std::map<float,Frame> TimeLine;\n    TimeLine m_timeline;\n    Frame lerpFrame(float t);\n\n    Frame mInitFrame;\n    bool mAnimate;\n    float m_alpha;\n\n    enum TrackMode {\n      TM_NO_TRACK=0, TM_ROTATE_AROUND, TM_ZOOM,\n      TM_LOCAL_ROTATE, TM_FLY_Z, TM_FLY_PAN\n    };\n\n    enum NavMode {\n      NavTurnAround,\n      NavFly\n    };\n\n    enum LerpMode {\n      LerpQuaternion,\n      LerpEulerAngles\n    };\n\n    enum RotationMode {\n      RotationStable,\n      RotationStandard\n    };\n\n    Camera mCamera;\n    TrackMode mCurrentTrackingMode;\n    NavMode mNavMode;\n    LerpMode mLerpMode;\n    RotationMode mRotationMode;\n    Vector2i mMouseCoords;\n    Trackball mTrackball;\n\n    QTimer m_timer;\n\n    void setupCamera();\n\n    std::vector<Vector3f> mVertices;\n    std::vector<Vector3f> mNormals;\n    std::vector<int> mIndices;\n\n  protected slots:\n\n    virtual void animate(void);\n    virtual void drawScene(void);\n\n    virtual void grabFrame(void);\n    virtual void stopAnimation();\n\n    virtual void setNavMode(int);\n    virtual void setLerpMode(int);\n    virtual void setRotationMode(int);\n    virtual void resetCamera();\n\n  protected:\n\n    virtual void initializeGL();\n    virtual void resizeGL(int width, int height);\n    virtual void paintGL();\n    \n    //--------------------------------------------------------------------------------\n    virtual void mousePressEvent(QMouseEvent * e);\n    virtual void mouseReleaseEvent(QMouseEvent * e);\n    virtual void mouseMoveEvent(QMouseEvent * e);\n    virtual void keyPressEvent(QKeyEvent * e);\n    //--------------------------------------------------------------------------------\n\n  public: \n    EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n    \n    RenderingWidget();\n    ~RenderingWidget() { }\n\n    QWidget* createNavigationControlWidget();\n};\n\nclass QuaternionDemo : public QMainWindow\n{\n  Q_OBJECT\n  public:\n    QuaternionDemo();\n  protected:\n    RenderingWidget* mRenderingWidget;\n};\n\n#endif // EIGEN_QUATERNION_DEMO_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/opengl/trackball.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"trackball.h\"\n#include \"camera.h\"\n\nusing namespace Eigen;\n\nvoid Trackball::track(const Vector2i& point2D)\n{\n  if (mpCamera==0)\n    return;\n  Vector3f newPoint3D;\n  bool newPointOk = mapToSphere(point2D, newPoint3D);\n\n  if (mLastPointOk && newPointOk)\n  {\n    Vector3f axis = mLastPoint3D.cross(newPoint3D).normalized();\n    float cos_angle = mLastPoint3D.dot(newPoint3D);\n    if ( std::abs(cos_angle) < 1.0 )\n    {\n      float angle = 2. * acos(cos_angle);\n      if (mMode==Around)\n        mpCamera->rotateAroundTarget(Quaternionf(AngleAxisf(angle, axis)));\n      else\n        mpCamera->localRotate(Quaternionf(AngleAxisf(-angle, axis)));\n    }\n  }\n\n  mLastPoint3D = newPoint3D;\n  mLastPointOk = newPointOk;\n}\n\nbool Trackball::mapToSphere(const Vector2i& p2, Vector3f& v3)\n{\n  if ((p2.x() >= 0) && (p2.x() <= int(mpCamera->vpWidth())) &&\n      (p2.y() >= 0) && (p2.y() <= int(mpCamera->vpHeight())) )\n  {\n    double x  = (double)(p2.x() - 0.5*mpCamera->vpWidth())  / (double)mpCamera->vpWidth();\n    double y  = (double)(0.5*mpCamera->vpHeight() - p2.y()) / (double)mpCamera->vpHeight();\n    double sinx         = sin(M_PI * x * 0.5);\n    double siny         = sin(M_PI * y * 0.5);\n    double sinx2siny2   = sinx * sinx + siny * siny;\n\n    v3.x() = sinx;\n    v3.y() = siny;\n    v3.z() = sinx2siny2 < 1.0 ? sqrt(1.0 - sinx2siny2) : 0.0;\n\n    return true;\n  }\n  else\n    return false;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/demos/opengl/trackball.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_TRACKBALL_H\n#define EIGEN_TRACKBALL_H\n\n#include <Eigen/Geometry>\n\nclass Camera;\n\nclass Trackball\n{\n  public:\n\n    enum Mode {Around, Local};\n\n    Trackball() : mpCamera(0) {}\n\n    void start(Mode m = Around) { mMode = m; mLastPointOk = false; }\n\n    void setCamera(Camera* pCam) { mpCamera = pCam; }\n\n    void track(const Eigen::Vector2i& newPoint2D);\n\n  protected:\n\n    bool mapToSphere( const Eigen::Vector2i& p2, Eigen::Vector3f& v3);\n\n    Camera* mpCamera;\n    Eigen::Vector3f mLastPoint3D;\n    Mode mMode;\n    bool mLastPointOk;\n\n};\n\n#endif // EIGEN_TRACKBALL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/AsciiQuickReference.txt",
    "content": "// A simple quickref for Eigen. Add anything that's missing.\n// Main author: Keir Mierle\n\n#include <Eigen/Dense>\n\nMatrix<double, 3, 3> A;               // Fixed rows and cols. Same as Matrix3d.\nMatrix<double, 3, Dynamic> B;         // Fixed rows, dynamic cols.\nMatrix<double, Dynamic, Dynamic> C;   // Full dynamic. Same as MatrixXd.\nMatrix<double, 3, 3, RowMajor> E;     // Row major; default is column-major.\nMatrix3f P, Q, R;                     // 3x3 float matrix.\nVector3f x, y, z;                     // 3x1 float matrix.\nRowVector3f a, b, c;                  // 1x3 float matrix.\nVectorXd v;                           // Dynamic column vector of doubles\ndouble s;                            \n\n// Basic usage\n// Eigen          // Matlab           // comments\nx.size()          // length(x)        // vector size\nC.rows()          // size(C,1)        // number of rows\nC.cols()          // size(C,2)        // number of columns\nx(i)              // x(i+1)           // Matlab is 1-based\nC(i,j)            // C(i+1,j+1)       //\n\nA.resize(4, 4);   // Runtime error if assertions are on.\nB.resize(4, 9);   // Runtime error if assertions are on.\nA.resize(3, 3);   // Ok; size didn't change.\nB.resize(3, 9);   // Ok; only dynamic cols changed.\n                  \nA << 1, 2, 3,     // Initialize A. The elements can also be\n     4, 5, 6,     // matrices, which are stacked along cols\n     7, 8, 9;     // and then the rows are stacked.\nB << A, A, A;     // B is three horizontally stacked A's.\nA.fill(10);       // Fill A with all 10's.\n\n// Eigen                                    // Matlab\nMatrixXd::Identity(rows,cols)               // eye(rows,cols)\nC.setIdentity(rows,cols)                    // C = eye(rows,cols)\nMatrixXd::Zero(rows,cols)                   // zeros(rows,cols)\nC.setZero(rows,cols)                        // C = zeros(rows,cols)\nMatrixXd::Ones(rows,cols)                   // ones(rows,cols)\nC.setOnes(rows,cols)                        // C = ones(rows,cols)\nMatrixXd::Random(rows,cols)                 // rand(rows,cols)*2-1            // MatrixXd::Random returns uniform random numbers in (-1, 1).\nC.setRandom(rows,cols)                      // C = rand(rows,cols)*2-1\nVectorXd::LinSpaced(size,low,high)          // linspace(low,high,size)'\nv.setLinSpaced(size,low,high)               // v = linspace(low,high,size)'\nVectorXi::LinSpaced(((hi-low)/step)+1,      // low:step:hi\n                    low,low+step*(size-1))  //\n\n\n// Matrix slicing and blocks. All expressions listed here are read/write.\n// Templated size versions are faster. Note that Matlab is 1-based (a size N\n// vector is x(1)...x(N)).\n/******************************************************************************/\n/*                  PLEASE HELP US IMPROVING THIS SECTION                     */\n/* Eigen 3.4 supports a much improved API for sub-matrices, including,        */\n/* slicing and indexing from arrays:                                          */\n/* http://eigen.tuxfamily.org/dox-devel/group__TutorialSlicingIndexing.html   */\n/******************************************************************************/\n// Eigen                           // Matlab\nx.head(n)                          // x(1:n)\nx.head<n>()                        // x(1:n)\nx.tail(n)                          // x(end - n + 1: end)\nx.tail<n>()                        // x(end - n + 1: end)\nx.segment(i, n)                    // x(i+1 : i+n)\nx.segment<n>(i)                    // x(i+1 : i+n)\nP.block(i, j, rows, cols)          // P(i+1 : i+rows, j+1 : j+cols)\nP.block<rows, cols>(i, j)          // P(i+1 : i+rows, j+1 : j+cols)\nP.row(i)                           // P(i+1, :)\nP.col(j)                           // P(:, j+1)\nP.leftCols<cols>()                 // P(:, 1:cols)\nP.leftCols(cols)                   // P(:, 1:cols)\nP.middleCols<cols>(j)              // P(:, j+1:j+cols)\nP.middleCols(j, cols)              // P(:, j+1:j+cols)\nP.rightCols<cols>()                // P(:, end-cols+1:end)\nP.rightCols(cols)                  // P(:, end-cols+1:end)\nP.topRows<rows>()                  // P(1:rows, :)\nP.topRows(rows)                    // P(1:rows, :)\nP.middleRows<rows>(i)              // P(i+1:i+rows, :)\nP.middleRows(i, rows)              // P(i+1:i+rows, :)\nP.bottomRows<rows>()               // P(end-rows+1:end, :)\nP.bottomRows(rows)                 // P(end-rows+1:end, :)\nP.topLeftCorner(rows, cols)        // P(1:rows, 1:cols)\nP.topRightCorner(rows, cols)       // P(1:rows, end-cols+1:end)\nP.bottomLeftCorner(rows, cols)     // P(end-rows+1:end, 1:cols)\nP.bottomRightCorner(rows, cols)    // P(end-rows+1:end, end-cols+1:end)\nP.topLeftCorner<rows,cols>()       // P(1:rows, 1:cols)\nP.topRightCorner<rows,cols>()      // P(1:rows, end-cols+1:end)\nP.bottomLeftCorner<rows,cols>()    // P(end-rows+1:end, 1:cols)\nP.bottomRightCorner<rows,cols>()   // P(end-rows+1:end, end-cols+1:end)\n\n// Of particular note is Eigen's swap function which is highly optimized.\n// Eigen                           // Matlab\nR.row(i) = P.col(j);               // R(i, :) = P(:, j)\nR.col(j1).swap(mat1.col(j2));      // R(:, [j1 j2]) = R(:, [j2, j1])\n\n// Views, transpose, etc;\n/******************************************************************************/\n/*                  PLEASE HELP US IMPROVING THIS SECTION                     */\n/* Eigen 3.4 supports a new API for reshaping:                                */\n/* http://eigen.tuxfamily.org/dox-devel/group__TutorialReshape.html           */\n/******************************************************************************/\n// Eigen                           // Matlab\nR.adjoint()                        // R'\nR.transpose()                      // R.' or conj(R')       // Read-write\nR.diagonal()                       // diag(R)               // Read-write\nx.asDiagonal()                     // diag(x)\nR.transpose().colwise().reverse()  // rot90(R)              // Read-write\nR.rowwise().reverse()              // fliplr(R)\nR.colwise().reverse()              // flipud(R)\nR.replicate(i,j)                   // repmat(P,i,j)\n\n\n// All the same as Matlab, but matlab doesn't have *= style operators.\n// Matrix-vector.  Matrix-matrix.   Matrix-scalar.\ny  = M*x;          R  = P*Q;        R  = P*s;\na  = b*M;          R  = P - Q;      R  = s*P;\na *= M;            R  = P + Q;      R  = P/s;\n                   R *= Q;          R  = s*P;\n                   R += Q;          R *= s;\n                   R -= Q;          R /= s;\n\n// Vectorized operations on each element independently\n// Eigen                       // Matlab\nR = P.cwiseProduct(Q);         // R = P .* Q\nR = P.array() * s.array();     // R = P .* s\nR = P.cwiseQuotient(Q);        // R = P ./ Q\nR = P.array() / Q.array();     // R = P ./ Q\nR = P.array() + s.array();     // R = P + s\nR = P.array() - s.array();     // R = P - s\nR.array() += s;                // R = R + s\nR.array() -= s;                // R = R - s\nR.array() < Q.array();         // R < Q\nR.array() <= Q.array();        // R <= Q\nR.cwiseInverse();              // 1 ./ P\nR.array().inverse();           // 1 ./ P\nR.array().sin()                // sin(P)\nR.array().cos()                // cos(P)\nR.array().pow(s)               // P .^ s\nR.array().square()             // P .^ 2\nR.array().cube()               // P .^ 3\nR.cwiseSqrt()                  // sqrt(P)\nR.array().sqrt()               // sqrt(P)\nR.array().exp()                // exp(P)\nR.array().log()                // log(P)\nR.cwiseMax(P)                  // max(R, P)\nR.array().max(P.array())       // max(R, P)\nR.cwiseMin(P)                  // min(R, P)\nR.array().min(P.array())       // min(R, P)\nR.cwiseAbs()                   // abs(P)\nR.array().abs()                // abs(P)\nR.cwiseAbs2()                  // abs(P.^2)\nR.array().abs2()               // abs(P.^2)\n(R.array() < s).select(P,Q );  // (R < s ? P : Q)\nR = (Q.array()==0).select(P,R) // R(Q==0) = P(Q==0)\nR = P.unaryExpr(ptr_fun(func)) // R = arrayfun(func, P)   // with: scalar func(const scalar &x);\n\n\n// Reductions.\nint r, c;\n// Eigen                  // Matlab\nR.minCoeff()              // min(R(:))\nR.maxCoeff()              // max(R(:))\ns = R.minCoeff(&r, &c)    // [s, i] = min(R(:)); [r, c] = ind2sub(size(R), i);\ns = R.maxCoeff(&r, &c)    // [s, i] = max(R(:)); [r, c] = ind2sub(size(R), i);\nR.sum()                   // sum(R(:))\nR.colwise().sum()         // sum(R)\nR.rowwise().sum()         // sum(R, 2) or sum(R')'\nR.prod()                  // prod(R(:))\nR.colwise().prod()        // prod(R)\nR.rowwise().prod()        // prod(R, 2) or prod(R')'\nR.trace()                 // trace(R)\nR.all()                   // all(R(:))\nR.colwise().all()         // all(R)\nR.rowwise().all()         // all(R, 2)\nR.any()                   // any(R(:))\nR.colwise().any()         // any(R)\nR.rowwise().any()         // any(R, 2)\n\n// Dot products, norms, etc.\n// Eigen                  // Matlab\nx.norm()                  // norm(x).    Note that norm(R) doesn't work in Eigen.\nx.squaredNorm()           // dot(x, x)   Note the equivalence is not true for complex\nx.dot(y)                  // dot(x, y)\nx.cross(y)                // cross(x, y) Requires #include <Eigen/Geometry>\n\n//// Type conversion\n// Eigen                  // Matlab\nA.cast<double>();         // double(A)\nA.cast<float>();          // single(A)\nA.cast<int>();            // int32(A)\nA.real();                 // real(A)\nA.imag();                 // imag(A)\n// if the original type equals destination type, no work is done\n\n// Note that for most operations Eigen requires all operands to have the same type:\nMatrixXf F = MatrixXf::Zero(3,3);\nA += F;                // illegal in Eigen. In Matlab A = A+F is allowed\nA += F.cast<double>(); // F converted to double and then added (generally, conversion happens on-the-fly)\n\n// Eigen can map existing memory into Eigen matrices.\nfloat array[3];\nVector3f::Map(array).fill(10);            // create a temporary Map over array and sets entries to 10\nint data[4] = {1, 2, 3, 4};\nMatrix2i mat2x2(data);                    // copies data into mat2x2\nMatrix2i::Map(data) = 2*mat2x2;           // overwrite elements of data with 2*mat2x2\nMatrixXi::Map(data, 2, 2) += mat2x2;      // adds mat2x2 to elements of data (alternative syntax if size is not know at compile time)\n\n// Solve Ax = b. Result stored in x. Matlab: x = A \\ b.\nx = A.ldlt().solve(b));  // A sym. p.s.d.    #include <Eigen/Cholesky>\nx = A.llt() .solve(b));  // A sym. p.d.      #include <Eigen/Cholesky>\nx = A.lu()  .solve(b));  // Stable and fast. #include <Eigen/LU>\nx = A.qr()  .solve(b));  // No pivoting.     #include <Eigen/QR>\nx = A.svd() .solve(b));  // Stable, slowest. #include <Eigen/SVD>\n// .ldlt() -> .matrixL() and .matrixD()\n// .llt()  -> .matrixL()\n// .lu()   -> .matrixL() and .matrixU()\n// .qr()   -> .matrixQ() and .matrixR()\n// .svd()  -> .matrixU(), .singularValues(), and .matrixV()\n\n// Eigenvalue problems\n// Eigen                          // Matlab\nA.eigenvalues();                  // eig(A);\nEigenSolver<Matrix3d> eig(A);     // [vec val] = eig(A)\neig.eigenvalues();                // diag(val)\neig.eigenvectors();               // vec\n// For self-adjoint matrices use SelfAdjointEigenSolver<>\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/B01_Experimental.dox",
    "content": "namespace Eigen {\n\n/** \\page Experimental Experimental parts of Eigen\n\n\\eigenAutoToc\n\n\\section Experimental_summary Summary\n\nWith the 2.0 release, Eigen's API is, to a large extent, stable. However, we wish to retain the freedom to make API incompatible changes. To that effect, we call many parts of Eigen \"experimental\" which means that they are not subject to API stability guarantee.\n\nOur goal is that for the 2.1 release (expected in July 2009) most of these parts become API-stable too.\n\nWe are aware that API stability is a major concern for our users. That's why it's a priority for us to reach it, but at the same time we're being serious about not calling Eigen API-stable too early.\n\nExperimental features may at any time:\n\\li be removed;\n\\li be subject to an API incompatible change;\n\\li introduce API or ABI incompatible changes in your own code if you let them affect your API or ABI.\n\n\\section Experimental_modules Experimental modules\n\nThe following modules are considered entirely experimental, and we make no firm API stability guarantee about them for the time being:\n\\li SVD\n\\li QR\n\\li Cholesky\n\\li Sparse\n\\li Geometry (this one should be mostly stable, but it's a little too early to make a formal guarantee)\n\n\\section Experimental_core Experimental parts of the Core module\n\nIn the Core module, the only classes subject to ABI stability guarantee (meaning that you can use it for data members in your public ABI) is:\n\\li Matrix\n\\li Map\n\nAll other classes offer no ABI guarantee, e.g. the layout of their data can be changed.\n\nThe only classes subject to (even partial) API stability guarantee (meaning that you can safely construct and use objects) are:\n\\li MatrixBase : partial API stability (see below)\n\\li Matrix : full API stability (except for experimental stuff inherited from MatrixBase)\n\\li Map : full API stability (except for experimental stuff inherited from MatrixBase)\n\nAll other classes offer no direct API guarantee, e.g. their methods can be changed; however notice that most classes inherit MatrixBase and that this is where most of their API comes from -- so in practice most of the API is stable.\n\nA few MatrixBase methods are considered experimental, hence not part of any API stability guarantee:\n\\li all methods documented as internal\n\\li all methods hidden in the Doxygen documentation\n\\li all methods marked as experimental\n\\li all methods defined in experimental modules\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/CMakeLists.txt",
    "content": "project(EigenDoc)\n\nset_directory_properties(PROPERTIES EXCLUDE_FROM_ALL TRUE)\n\nproject(EigenDoc)\n\nif(CMAKE_COMPILER_IS_GNUCXX)\n  if(CMAKE_SYSTEM_NAME MATCHES Linux)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -O1 -g1\")\n  endif()\nendif()\n\n# some examples and snippets needs c++11, so let's check it once\ncheck_cxx_compiler_flag(\"-std=c++11\" EIGEN_COMPILER_SUPPORT_CPP11)\n\noption(EIGEN_INTERNAL_DOCUMENTATION \"Build internal documentation\" OFF)\noption(EIGEN_DOC_USE_MATHJAX \"Use MathJax for rendering math in HTML docs\" ON)\n\n# Set some Doxygen flags\nset(EIGEN_DOXY_PROJECT_NAME             \"Eigen\")\nset(EIGEN_DOXY_OUTPUT_DIRECTORY_SUFFIX  \"\")\nset(EIGEN_DOXY_INPUT                    \"\\\"${Eigen_SOURCE_DIR}/Eigen\\\" \\\"${Eigen_SOURCE_DIR}/doc\\\"\")\nset(EIGEN_DOXY_HTML_COLORSTYLE_HUE      \"220\")\nset(EIGEN_DOXY_TAGFILES                 \"\")\n\nif(EIGEN_INTERNAL_DOCUMENTATION)\n  set(EIGEN_DOXY_INTERNAL                 \"YES\")\nelse()\n  set(EIGEN_DOXY_INTERNAL                 \"NO\")\nendif()\n\nif (EIGEN_DOC_USE_MATHJAX)\n  set(EIGEN_DOXY_USE_MATHJAX \"YES\")\nelse ()\n  set(EIGEN_DOXY_USE_MATHJAX \"NO\")\nendif()\n\nconfigure_file(\n  ${CMAKE_CURRENT_SOURCE_DIR}/Doxyfile.in\n  ${CMAKE_CURRENT_BINARY_DIR}/Doxyfile\n)\n\nset(EIGEN_DOXY_PROJECT_NAME             \"Eigen-unsupported\")\nset(EIGEN_DOXY_OUTPUT_DIRECTORY_SUFFIX  \"/unsupported\")\nset(EIGEN_DOXY_INPUT                    \"\\\"${Eigen_SOURCE_DIR}/unsupported/Eigen\\\" \\\"${Eigen_SOURCE_DIR}/unsupported/doc\\\"\")\nset(EIGEN_DOXY_HTML_COLORSTYLE_HUE      \"0\")\nset(EIGEN_DOXY_TAGFILES                 \"\\\"${Eigen_BINARY_DIR}/doc/Eigen.doxytags=..\\\"\")\n#set(EIGEN_DOXY_TAGFILES                 \"\")\n\nconfigure_file(\n  ${CMAKE_CURRENT_SOURCE_DIR}/Doxyfile.in\n  ${CMAKE_CURRENT_BINARY_DIR}/Doxyfile-unsupported\n)\n\nconfigure_file(\n  ${CMAKE_CURRENT_SOURCE_DIR}/eigendoxy_header.html.in\n  ${CMAKE_CURRENT_BINARY_DIR}/eigendoxy_header.html\n)\n\nconfigure_file(\n  ${CMAKE_CURRENT_SOURCE_DIR}/eigendoxy_footer.html.in\n  ${CMAKE_CURRENT_BINARY_DIR}/eigendoxy_footer.html\n)\n\nconfigure_file(\n  ${CMAKE_CURRENT_SOURCE_DIR}/eigendoxy_layout.xml.in\n  ${CMAKE_CURRENT_BINARY_DIR}/eigendoxy_layout.xml\n)\n\nconfigure_file(\n  ${Eigen_SOURCE_DIR}/unsupported/doc/eigendoxy_layout.xml.in\n  ${Eigen_BINARY_DIR}/doc/unsupported/eigendoxy_layout.xml\n)\n\nset(examples_targets \"\")\nset(snippets_targets \"\")\n\nadd_definitions(\"-DEIGEN_MAKING_DOCS\")\nadd_custom_target(all_examples)\n\nadd_subdirectory(examples)\nadd_subdirectory(special_examples)\nadd_subdirectory(snippets)\n\nadd_custom_target(\n  doc-eigen-prerequisites\n  ALL\n  COMMAND ${CMAKE_COMMAND} -E make_directory ${CMAKE_CURRENT_BINARY_DIR}/html/\n  COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/eigen_navtree_hacks.js           ${CMAKE_CURRENT_BINARY_DIR}/html/\n  COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/Eigen_Silly_Professor_64x64.png  ${CMAKE_CURRENT_BINARY_DIR}/html/\n  COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/ftv2pnode.png                    ${CMAKE_CURRENT_BINARY_DIR}/html/\n  COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/ftv2node.png                     ${CMAKE_CURRENT_BINARY_DIR}/html/\n  COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/AsciiQuickReference.txt          ${CMAKE_CURRENT_BINARY_DIR}/html/\n  WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}\n)\n\nadd_custom_target(\n  doc-unsupported-prerequisites\n  ALL\n  COMMAND ${CMAKE_COMMAND} -E make_directory ${Eigen_BINARY_DIR}/doc/html/unsupported\n  COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/eigen_navtree_hacks.js           ${CMAKE_CURRENT_BINARY_DIR}/html/unsupported/\n  COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/Eigen_Silly_Professor_64x64.png  ${CMAKE_CURRENT_BINARY_DIR}/html/unsupported/\n  COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/ftv2pnode.png                    ${CMAKE_CURRENT_BINARY_DIR}/html/unsupported/\n  COMMAND ${CMAKE_COMMAND} -E copy ${CMAKE_CURRENT_SOURCE_DIR}/ftv2node.png                     ${CMAKE_CURRENT_BINARY_DIR}/html/unsupported/\n  WORKING_DIRECTORY ${Eigen_BINARY_DIR}/doc\n)\n\nadd_dependencies(doc-eigen-prerequisites all_snippets all_examples)\nadd_dependencies(doc-unsupported-prerequisites unsupported_snippets unsupported_examples)\n\nadd_custom_target(doc ALL\n  COMMAND doxygen\n  COMMAND doxygen Doxyfile-unsupported\n  COMMAND ${CMAKE_COMMAND} -E copy ${Eigen_BINARY_DIR}/doc/html/group__TopicUnalignedArrayAssert.html ${Eigen_BINARY_DIR}/doc/html/TopicUnalignedArrayAssert.html\n  COMMAND ${CMAKE_COMMAND} -E rename html eigen-doc\n  COMMAND ${CMAKE_COMMAND} -E remove eigen-doc/eigen-doc.tgz eigen-doc/unsupported/_formulas.log eigen-doc/_formulas.log\n  COMMAND ${CMAKE_COMMAND} -E tar cfz eigen-doc.tgz eigen-doc\n  COMMAND ${CMAKE_COMMAND} -E rename eigen-doc.tgz eigen-doc/eigen-doc.tgz\n  COMMAND ${CMAKE_COMMAND} -E rename eigen-doc html\n  WORKING_DIRECTORY ${Eigen_BINARY_DIR}/doc)\n\nadd_dependencies(doc doc-eigen-prerequisites doc-unsupported-prerequisites)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/ClassHierarchy.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicClassHierarchy The class hierarchy\n\nThis page explains the design of the core classes in Eigen's class hierarchy and how they fit together. Casual\nusers probably need not concern themselves with these details, but it may be useful for both advanced users\nand Eigen developers.\n\n\\eigenAutoToc\n\n\n\\section TopicClassHierarchyPrinciples Principles\n\nEigen's class hierarchy is designed so that virtual functions are avoided where their overhead would\nsignificantly impair performance. Instead, Eigen achieves polymorphism with the Curiously Recurring Template\nPattern (CRTP). In this pattern, the base class (for instance, \\c MatrixBase) is in fact a template class, and\nthe derived class (for instance, \\c Matrix) inherits the base class with the derived class itself as a\ntemplate argument (in this case, \\c Matrix inherits from \\c MatrixBase&lt;Matrix&gt;). This allows Eigen to\nresolve the polymorphic function calls at compile time.\n\nIn addition, the design avoids multiple inheritance. One reason for this is that in our experience, some\ncompilers (like MSVC) fail to perform empty base class optimization, which is crucial for our fixed-size\ntypes.\n\n\n\\section TopicClassHierarchyCoreClasses The core classes\n\nThese are the classes that you need to know about if you want to write functions that accept or return Eigen\nobjects.\n\n  - Matrix means plain dense matrix. If \\c m is a \\c %Matrix, then, for instance, \\c m+m is no longer a \n    \\c %Matrix, it is a \"matrix expression\".\n  - MatrixBase means dense matrix expression. This means that a \\c %MatrixBase is something that can be\n    added, matrix-multiplied, LU-decomposed, QR-decomposed... All matrix expression classes, including \n    \\c %Matrix itself, inherit \\c %MatrixBase.\n  - Array means plain dense array. If \\c x is an \\c %Array, then, for instance, \\c x+x is no longer an \n    \\c %Array, it is an \"array expression\".\n  - ArrayBase means dense array expression. This means that an \\c %ArrayBase is something that can be\n    added, array-multiplied, and on which you can perform all sorts of array operations... All array\n    expression classes, including \\c %Array itself, inherit \\c %ArrayBase.\n  - DenseBase means dense (matrix or array) expression. Both \\c %ArrayBase and \\c %MatrixBase inherit\n    \\c %DenseBase. \\c %DenseBase is where all the methods go that apply to dense expressions regardless of\n    whether they are matrix or array expressions. For example, the \\link DenseBase::block() block(...) \\endlink\n    methods are in \\c %DenseBase.\n\n\\section TopicClassHierarchyBaseClasses Base classes\n\nThese classes serve as base classes for the five core classes mentioned above. They are more internal and so\nless interesting for users of the Eigen library.\n\n  - PlainObjectBase means dense (matrix or array) plain object, i.e. something that stores its own dense\n    array of coefficients. This is where, for instance, the \\link PlainObjectBase::resize() resize() \\endlink\n    methods go. \\c %PlainObjectBase is inherited by \\c %Matrix and by \\c %Array. But above, we said that \n    \\c %Matrix inherits \\c %MatrixBase and \\c %Array inherits \\c %ArrayBase. So does that mean multiple\n    inheritance? No, because \\c %PlainObjectBase \\e itself inherits \\c %MatrixBase or \\c %ArrayBase depending\n    on whether we are in the matrix or array case. When we said above that \\c %Matrix inherited \n    \\c %MatrixBase, we omitted to say it does so indirectly via \\c %PlainObjectBase. Same for \\c %Array.\n  - DenseCoeffsBase means something that has dense coefficient accessors. It is a base class for\n    \\c %DenseBase. The reason for \\c %DenseCoeffsBase to exist is that the set of available coefficient\n    accessors is very different depending on whether a dense expression has direct memory access or not (the\n    \\c DirectAccessBit flag). For example, if \\c x is a plain matrix, then \\c x has direct access, and \n    \\c x.transpose() and \\c x.block(...) also have direct access, because their coefficients can be read right\n    off memory, but for example, \\c x+x does not have direct memory access, because obtaining any of its\n    coefficients requires a computation (an addition), it can't be just read off memory.\n  - EigenBase means anything that can be evaluated into a plain dense matrix or array (even if that would\n    be a bad idea). \\c %EigenBase is really the absolute base class for anything that remotely looks like a\n    matrix or array. It is a base class for \\c %DenseCoeffsBase, so it sits below all our dense class\n    hierarchy, but it is not limited to dense expressions. For example, \\c %EigenBase is also inherited by\n    diagonal matrices, sparse matrices, etc...\n\n\n\\section TopicClassHierarchyInheritanceDiagrams Inheritance diagrams\n\nThe inheritance diagram for Matrix looks as follows:\n\n<pre>\nEigenBase&lt;%Matrix&gt;\n  <-- DenseCoeffsBase&lt;%Matrix&gt;    (direct access case)\n    <-- DenseBase&lt;%Matrix&gt;\n      <-- MatrixBase&lt;%Matrix&gt;\n        <-- PlainObjectBase&lt;%Matrix&gt;    (matrix case)\n          <-- Matrix\n</pre>\n\nThe inheritance diagram for Array looks as follows:\n\n<pre>\nEigenBase&lt;%Array&gt;\n  <-- DenseCoeffsBase&lt;%Array&gt;    (direct access case)\n    <-- DenseBase&lt;%Array&gt;\n      <-- ArrayBase&lt;%Array&gt;\n        <-- PlainObjectBase&lt;%Array&gt;    (array case)\n          <-- Array\n</pre>\n\nThe inheritance diagram for some other matrix expression class, here denoted by \\c SomeMatrixXpr, looks as\nfollows:\n\n<pre>\nEigenBase&lt;SomeMatrixXpr&gt;\n  <-- DenseCoeffsBase&lt;SomeMatrixXpr&gt;    (direct access or no direct access case)\n    <-- DenseBase&lt;SomeMatrixXpr&gt;\n      <-- MatrixBase&lt;SomeMatrixXpr&gt;\n        <-- SomeMatrixXpr\n</pre>\n\nThe inheritance diagram for some other array expression class, here denoted by \\c SomeArrayXpr, looks as\nfollows:\n\n<pre>\nEigenBase&lt;SomeArrayXpr&gt;\n  <-- DenseCoeffsBase&lt;SomeArrayXpr&gt;    (direct access or no direct access case)\n    <-- DenseBase&lt;SomeArrayXpr&gt;\n      <-- ArrayBase&lt;SomeArrayXpr&gt;\n        <-- SomeArrayXpr\n</pre>\n\nFinally, consider an example of something that is not a dense expression, for instance a diagonal matrix. The\ncorresponding inheritance diagram is:\n\n<pre>\nEigenBase&lt;%DiagonalMatrix&gt;\n  <-- DiagonalBase&lt;%DiagonalMatrix&gt;\n    <-- DiagonalMatrix\n</pre>\n\n\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/CoeffwiseMathFunctionsTable.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage CoeffwiseMathFunctions Catalog of coefficient-wise math functions\n\n\n<!-- <span style=\"font-size:300%; color:red; font-weight: 900;\">!WORK IN PROGRESS!</span> -->\n\nThis table presents a catalog of the coefficient-wise math functions supported by %Eigen.\nIn this table, \\c a, \\c b, refer to Array objects or expressions, and \\c m refers to a linear algebra Matrix/Vector object. Standard scalar types are abbreviated as follows:\n  - \\c int: \\c i32\n  - \\c float: \\c f\n  - \\c double: \\c d\n  - \\c std::complex<float>: \\c cf\n  - \\c std::complex<double>: \\c cd\n\nFor each row, the first column list the equivalent calls for arrays, and matrices when supported. Of course, all functions are available for matrices by first casting it as an array: \\c m.array().\n\nThe third column gives some hints in the underlying scalar implementation. In most cases, %Eigen does not implement itself the math function but relies on the STL for standard scalar types, or user-provided functions for custom scalar types.\nFor instance, some simply calls the respective function of the STL while preserving <a href=\"http://en.cppreference.com/w/cpp/language/adl\">argument-dependent lookup</a> for custom types.\nThe following:\n\\code\nusing std::foo;\nfoo(a[i]);\n\\endcode\nmeans that the STL's function \\c std::foo will be potentially called if it is compatible with the underlying scalar type. If not, then the user must ensure that an overload of the function foo is available for the given scalar type (usually defined in the same namespace as the given scalar type).\nThis also means that, unless specified, if the function \\c std::foo is available only in some recent c++ versions (e.g., c++11), then the respective %Eigen's function/method will be usable on standard types only if the compiler support the required c++ version.\n\n<table class=\"manual-hl\">\n<tr>\n<th>API</th><th>Description</th><th>Default scalar implementation</th><th>SIMD</th>\n</tr>\n<tr><td colspan=\"4\"></td></tr>\n<tr><th colspan=\"4\">Basic operations</th></tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_abs\n  a.\\link ArrayBase::abs abs\\endlink(); \\n\n  \\link Eigen::abs abs\\endlink(a); \\n\n  m.\\link MatrixBase::cwiseAbs cwiseAbs\\endlink();\n  </td>\n  <td>absolute value (\\f$ |a_i| \\f$) </td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/fabs\">std::abs</a>; \\n\n  abs(a[i]);\n  </td>\n  <td>SSE2, AVX (i32,f,d)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_inverse\n  a.\\link ArrayBase::inverse inverse\\endlink(); \\n\n  \\link Eigen::inverse inverse\\endlink(a); \\n\n  m.\\link MatrixBase::cwiseInverse cwiseInverse\\endlink();\n  </td>\n  <td>inverse value (\\f$ 1/a_i \\f$) </td>\n  <td class=\"code\">\n  1/a[i];\n  </td>\n  <td>All engines (f,d,fc,fd)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_conj\n  a.\\link ArrayBase::conjugate conjugate\\endlink(); \\n\n  \\link Eigen::conj conj\\endlink(a); \\n\n  m.\\link MatrixBase::conjugate conjugate\\endlink();\n  </td>\n  <td><a href=\"https://en.wikipedia.org/wiki/Complex_conjugate\">complex conjugate</a> (\\f$ \\bar{a_i} \\f$),\\n\n  no-op for real </td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/complex/conj\">std::conj</a>; \\n\n  conj(a[i]);\n  </td>\n  <td>All engines (fc,fd)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_arg\n  a.\\link ArrayBase::arg arg\\endlink(); \\n\n  \\link Eigen::arg arg\\endlink(a); \\n\n  m.\\link MatrixBase::cwiseArg cwiseArg\\endlink();\n  </td>\n  <td>phase angle of complex number</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/complex/arg\">std::arg</a>; \\n\n  arg(a[i]);\n  </td>\n  <td>All engines (fc,fd)</td>\n</tr>\n<tr>\n<th colspan=\"4\">Exponential functions</th>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_exp\n  a.\\link ArrayBase::exp exp\\endlink(); \\n\n  \\link Eigen::exp exp\\endlink(a);\n  </td>\n  <td>\\f$ e \\f$ raised to the given power (\\f$ e^{a_i} \\f$) </td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/exp\">std::exp</a>; \\n\n  exp(a[i]);\n  </td>\n  <td>SSE2, AVX (f,d)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_log\n  a.\\link ArrayBase::log log\\endlink(); \\n\n  \\link Eigen::log log\\endlink(a);\n  </td>\n  <td>natural (base \\f$ e \\f$) logarithm (\\f$ \\ln({a_i}) \\f$)</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/log\">std::log</a>; \\n\n  log(a[i]);\n  </td>\n  <td>SSE2, AVX (f)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_log1p\n  a.\\link ArrayBase::log1p log1p\\endlink(); \\n\n  \\link Eigen::log1p log1p\\endlink(a);\n  </td>\n  <td>natural (base \\f$ e \\f$) logarithm of 1 plus \\n the given number (\\f$ \\ln({1+a_i}) \\f$)</td>\n  <td>built-in generic implementation based on \\c log,\\n\n  plus \\c using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/log1p\">\\c std::log1p </a>; \\cpp11</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_log10\n  a.\\link ArrayBase::log10 log10\\endlink(); \\n\n  \\link Eigen::log10 log10\\endlink(a);\n  </td>\n  <td>base 10 logarithm (\\f$ \\log_{10}({a_i}) \\f$)</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/log10\">std::log10</a>; \\n\n  log10(a[i]);\n  </td>\n  <td></td>\n</tr>\n<tr>\n<th colspan=\"4\">Power functions</th>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_pow\n  a.\\link ArrayBase::pow pow\\endlink(b); \\n\n  \\link ArrayBase::pow(const Eigen::ArrayBase< Derived > &x, const Eigen::ArrayBase< ExponentDerived > &exponents) pow\\endlink(a,b);\n  </td>\n  <!-- For some reason Doxygen thinks that pow is in ArrayBase namespace -->\n  <td>raises a number to the given power (\\f$ a_i ^ {b_i} \\f$) \\n \\c a and \\c b can be either an array or scalar.</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/pow\">std::pow</a>; \\n\n  pow(a[i],b[i]);\\n\n  (plus builtin for integer types)</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_sqrt\n  a.\\link ArrayBase::sqrt sqrt\\endlink(); \\n\n  \\link Eigen::sqrt sqrt\\endlink(a);\\n\n  m.\\link MatrixBase::cwiseSqrt cwiseSqrt\\endlink();\n  </td>\n  <td>computes square root (\\f$ \\sqrt a_i \\f$)</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/sqrt\">std::sqrt</a>; \\n\n  sqrt(a[i]);</td>\n  <td>SSE2, AVX (f,d)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_rsqrt\n  a.\\link ArrayBase::rsqrt rsqrt\\endlink(); \\n\n  \\link Eigen::rsqrt rsqrt\\endlink(a);\n  </td>\n  <td><a href=\"https://en.wikipedia.org/wiki/Fast_inverse_square_root\">reciprocal square root</a> (\\f$ 1/{\\sqrt a_i} \\f$)</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/sqrt\">std::sqrt</a>; \\n\n  1/sqrt(a[i]); \\n\n  </td>\n  <td>SSE2, AVX, AltiVec, ZVector (f,d)\\n\n  (approx + 1 Newton iteration)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_square\n  a.\\link ArrayBase::square square\\endlink(); \\n\n  \\link Eigen::square square\\endlink(a);\n  </td>\n  <td>computes square power (\\f$ a_i^2 \\f$)</td>\n  <td class=\"code\">\n  a[i]*a[i]</td>\n  <td>All (i32,f,d,cf,cd)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_cube\n  a.\\link ArrayBase::cube cube\\endlink(); \\n\n  \\link Eigen::cube cube\\endlink(a);\n  </td>\n  <td>computes cubic power (\\f$ a_i^3 \\f$)</td>\n  <td class=\"code\">\n  a[i]*a[i]*a[i]</td>\n  <td>All (i32,f,d,cf,cd)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_abs2\n  a.\\link ArrayBase::abs2 abs2\\endlink(); \\n\n  \\link Eigen::abs2 abs2\\endlink(a);\\n\n  m.\\link MatrixBase::cwiseAbs2 cwiseAbs2\\endlink();\n  </td>\n  <td>computes the squared absolute value (\\f$ |a_i|^2 \\f$)</td>\n  <td class=\"code\">\n  real:    a[i]*a[i] \\n\n  complex:  real(a[i])*real(a[i]) \\n\n  &nbsp;&nbsp;&nbsp;&nbsp;&nbsp;&nbsp; + imag(a[i])*imag(a[i])</td>\n  <td>All (i32,f,d)</td>\n</tr>\n<tr>\n<th colspan=\"4\">Trigonometric functions</th>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_sin\n  a.\\link ArrayBase::sin sin\\endlink(); \\n\n  \\link Eigen::sin sin\\endlink(a);\n  </td>\n  <td>computes sine</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/sin\">std::sin</a>; \\n\n  sin(a[i]);</td>\n  <td>SSE2, AVX (f)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_cos\n  a.\\link ArrayBase::cos cos\\endlink(); \\n\n  \\link Eigen::cos cos\\endlink(a);\n  </td>\n  <td>computes cosine</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/cos\">std::cos</a>; \\n\n  cos(a[i]);</td>\n  <td>SSE2, AVX (f)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_tan\n  a.\\link ArrayBase::tan tan\\endlink(); \\n\n  \\link Eigen::tan tan\\endlink(a);\n  </td>\n  <td>computes tangent</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/tan\">std::tan</a>; \\n\n  tan(a[i]);</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_asin\n  a.\\link ArrayBase::asin asin\\endlink(); \\n\n  \\link Eigen::asin asin\\endlink(a);\n  </td>\n  <td>computes arc sine (\\f$ \\sin^{-1} a_i \\f$)</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/asin\">std::asin</a>; \\n\n  asin(a[i]);</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_acos\n  a.\\link ArrayBase::acos acos\\endlink(); \\n\n  \\link Eigen::acos acos\\endlink(a);\n  </td>\n  <td>computes arc cosine  (\\f$ \\cos^{-1} a_i \\f$)</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/acos\">std::acos</a>; \\n\n  acos(a[i]);</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_atan\n  a.\\link ArrayBase::atan atan\\endlink(); \\n\n  \\link Eigen::atan atan\\endlink(a);\n  </td>\n  <td>computes arc tangent (\\f$ \\tan^{-1} a_i \\f$)</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/atan\">std::atan</a>; \\n\n  atan(a[i]);</td>\n  <td></td>\n</tr>\n<tr>\n<th colspan=\"4\">Hyperbolic functions</th>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_sinh\n  a.\\link ArrayBase::sinh sinh\\endlink(); \\n\n  \\link Eigen::sinh sinh\\endlink(a);\n  </td>\n  <td>computes hyperbolic sine</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/sinh\">std::sinh</a>; \\n\n  sinh(a[i]);</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_cosh\n  a.\\link ArrayBase::cosh cohs\\endlink(); \\n\n  \\link Eigen::cosh cosh\\endlink(a);\n  </td>\n  <td>computes hyperbolic cosine</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/cosh\">std::cosh</a>; \\n\n  cosh(a[i]);</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_tanh\n  a.\\link ArrayBase::tanh tanh\\endlink(); \\n\n  \\link Eigen::tanh tanh\\endlink(a);\n  </td>\n  <td>computes hyperbolic tangent</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/tanh\">std::tanh</a>; \\n\n  tanh(a[i]);</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_asinh\n  a.\\link ArrayBase::asinh asinh\\endlink(); \\n\n  \\link Eigen::asinh asinh\\endlink(a);\n  </td>\n  <td>computes inverse hyperbolic sine</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/asinh\">std::asinh</a>; \\n\n  asinh(a[i]);</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_acosh\n  a.\\link ArrayBase::acosh cohs\\endlink(); \\n\n  \\link Eigen::acosh acosh\\endlink(a);\n  </td>\n  <td>computes hyperbolic cosine</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/acosh\">std::acosh</a>; \\n\n  acosh(a[i]);</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_atanh\n  a.\\link ArrayBase::atanh atanh\\endlink(); \\n\n  \\link Eigen::atanh atanh\\endlink(a);\n  </td>\n  <td>computes hyperbolic tangent</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/atanh\">std::atanh</a>; \\n\n  atanh(a[i]);</td>\n  <td></td>\n</tr>\n<tr>\n<th colspan=\"4\">Nearest integer floating point operations</th>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_ceil\n  a.\\link ArrayBase::ceil ceil\\endlink(); \\n\n  \\link Eigen::ceil ceil\\endlink(a);\n  </td>\n  <td>nearest integer not less than the given value</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/ceil\">std::ceil</a>; \\n\n  ceil(a[i]);</td>\n  <td>SSE4,AVX,ZVector (f,d)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_floor\n  a.\\link ArrayBase::floor floor\\endlink(); \\n\n  \\link Eigen::floor floor\\endlink(a);\n  </td>\n  <td>nearest integer not greater than the given value</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/floor\">std::floor</a>; \\n\n  floor(a[i]);</td>\n  <td>SSE4,AVX,ZVector (f,d)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_round\n  a.\\link ArrayBase::round round\\endlink(); \\n\n  \\link Eigen::round round\\endlink(a);\n  </td>\n  <td>nearest integer, \\n rounding away from zero in halfway cases</td>\n  <td>built-in generic implementation \\n based on \\c floor and \\c ceil,\\n\n  plus \\c using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/round\">\\c std::round </a>; \\cpp11</td>\n  <td>SSE4,AVX,ZVector (f,d)</td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_rint\n  a.\\link ArrayBase::rint rint\\endlink(); \\n\n  \\link Eigen::rint rint\\endlink(a);\n  </td>\n  <td>nearest integer, \\n rounding to nearest even in halfway cases</td>\n  <td>built-in generic implementation using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/rint\">\\c std::rint </a>; \\cpp11\n  or <a href=\"http://en.cppreference.com/w/c/numeric/math/rint\">\\c rintf </a>; </td>\n  <td>SSE4,AVX (f,d)</td>\n</tr>\n<tr>\n<th colspan=\"4\">Floating point manipulation functions</th>\n</tr>\n<tr>\n<th colspan=\"4\">Classification and comparison</th>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_isfinite\n  a.\\link ArrayBase::isFinite isFinite\\endlink(); \\n\n  \\link Eigen::isfinite isfinite\\endlink(a);\n  </td>\n  <td>checks if the given number has finite value</td>\n  <td>built-in generic implementation,\\n\n  plus \\c using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/isfinite\">\\c std::isfinite </a>; \\cpp11</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_isinf\n  a.\\link ArrayBase::isInf isInf\\endlink(); \\n\n  \\link Eigen::isinf isinf\\endlink(a);\n  </td>\n  <td>checks if the given number is infinite</td>\n  <td>built-in generic implementation,\\n\n  plus \\c using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/isinf\">\\c std::isinf </a>; \\cpp11</td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_isnan\n  a.\\link ArrayBase::isNaN isNaN\\endlink(); \\n\n  \\link Eigen::isnan isnan\\endlink(a);\n  </td>\n  <td>checks if the given number is not a number</td>\n  <td>built-in generic implementation,\\n\n  plus \\c using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/isnan\">\\c std::isnan </a>; \\cpp11</td>\n  <td></td>\n</tr>\n<tr>\n<th colspan=\"4\">Error and gamma functions</th>\n</tr>\n<tr> <td colspan=\"4\">  Require \\c \\#include \\c <unsupported/Eigen/SpecialFunctions> </td></tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_erf\n  a.\\link ArrayBase::erf erf\\endlink(); \\n\n  \\link Eigen::erf erf\\endlink(a);\n  </td>\n  <td>error function</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/erf\">std::erf</a>; \\cpp11 \\n\n  erf(a[i]);\n  </td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_erfc\n  a.\\link ArrayBase::erfc erfc\\endlink(); \\n\n  \\link Eigen::erfc erfc\\endlink(a);\n  </td>\n  <td>complementary error function</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/erfc\">std::erfc</a>; \\cpp11 \\n\n  erfc(a[i]);\n  </td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_lgamma\n  a.\\link ArrayBase::lgamma lgamma\\endlink(); \\n\n  \\link Eigen::lgamma lgamma\\endlink(a);\n  </td>\n  <td>natural logarithm of the gamma function</td>\n  <td class=\"code\">\n  using <a href=\"http://en.cppreference.com/w/cpp/numeric/math/lgamma\">std::lgamma</a>; \\cpp11 \\n\n  lgamma(a[i]);\n  </td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_digamma\n  a.\\link ArrayBase::digamma digamma\\endlink(); \\n\n  \\link Eigen::digamma digamma\\endlink(a);\n  </td>\n  <td><a href=\"https://en.wikipedia.org/wiki/Digamma_function\">logarithmic derivative of the gamma function</a></td>\n  <td>\n  built-in for float and double\n  </td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_igamma\n  \\link Eigen::igamma igamma\\endlink(a,x);\n  </td>\n  <td><a href=\"https://en.wikipedia.org/wiki/Incomplete_gamma_function\">lower incomplete gamma integral</a>\n  \\n \\f$ \\gamma(a_i,x_i)= \\frac{1}{|a_i|} \\int_{0}^{x_i}e^{\\text{-}t} t^{a_i-1} \\mathrm{d} t \\f$</td>\n  <td>\n  built-in for float and double,\\n but requires \\cpp11\n  </td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_igammac\n  \\link Eigen::igammac igammac\\endlink(a,x);\n  </td>\n  <td><a href=\"https://en.wikipedia.org/wiki/Incomplete_gamma_function\">upper incomplete gamma integral</a>\n  \\n \\f$ \\Gamma(a_i,x_i) = \\frac{1}{|a_i|} \\int_{x_i}^{\\infty}e^{\\text{-}t} t^{a_i-1} \\mathrm{d} t \\f$</td>\n  <td>\n  built-in for float and double,\\n but requires \\cpp11\n  </td>\n  <td></td>\n</tr>\n<tr>\n<th colspan=\"4\">Special functions</th>\n</tr>\n<tr> <td colspan=\"4\">  Require \\c \\#include \\c <unsupported/Eigen/SpecialFunctions> </td></tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_polygamma\n  \\link Eigen::polygamma polygamma\\endlink(n,x);\n  </td>\n  <td><a href=\"https://en.wikipedia.org/wiki/Polygamma_function\">n-th derivative of digamma at x</a></td>\n  <td>\n  built-in generic based on\\n <a href=\"#cwisetable_lgamma\">\\c lgamma </a>,\n  <a href=\"#cwisetable_digamma\"> \\c digamma </a>\n  and <a href=\"#cwisetable_zeta\">\\c zeta </a>.\n  </td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_betainc\n  \\link Eigen::betainc betainc\\endlink(a,b,x);\n  </td>\n  <td><a href=\"https://en.wikipedia.org/wiki/Beta_function#Incomplete_beta_function\">Incomplete beta function</a></td>\n  <td>\n  built-in for float and double,\\n but requires \\cpp11\n  </td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_zeta\n  \\link Eigen::zeta zeta\\endlink(a,b); \\n\n  a.\\link ArrayBase::zeta zeta\\endlink(b);\n  </td>\n  <td><a href=\"https://en.wikipedia.org/wiki/Hurwitz_zeta_function\">Hurwitz zeta function</a>\n  \\n \\f$ \\zeta(a_i,b_i)=\\sum_{k=0}^{\\infty}(b_i+k)^{\\text{-}a_i} \\f$</td>\n  <td>\n  built-in for float and double\n  </td>\n  <td></td>\n</tr>\n<tr>\n  <td class=\"code\">\n  \\anchor cwisetable_ndtri\n  a.\\link ArrayBase::ndtri ndtri\\endlink(); \\n\n  \\link Eigen::ndtri ndtri\\endlink(a);\n  </td>\n  <td>Inverse of the CDF of the Normal distribution function</td>\n  <td>\n  built-in for float and double\n  </td>\n  <td></td>\n</tr>\n<tr><td colspan=\"4\"></td></tr>\n</table>\n\n\\n\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/CustomizingEigen_CustomScalar.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicCustomizing_CustomScalar Using custom scalar types\n\\anchor user_defined_scalars\n\nBy default, Eigen currently supports standard floating-point types (\\c float, \\c double, \\c std::complex<float>, \\c std::complex<double>, \\c long \\c double), as well as all native integer types (e.g., \\c int, \\c unsigned \\c int, \\c short, etc.), and \\c bool.\nOn x86-64 systems, \\c long \\c double permits to locally enforces the use of x87 registers with extended accuracy (in comparison to SSE).\n\nIn order to add support for a custom type \\c T you need:\n-# make sure the common operator (+,-,*,/,etc.) are supported by the type \\c T\n-# add a specialization of struct Eigen::NumTraits<T> (see \\ref NumTraits)\n-# define the math functions that makes sense for your type. This includes standard ones like sqrt, pow, sin, tan, conj, real, imag, etc, as well as abs2 which is Eigen specific.\n     (see the file Eigen/src/Core/MathFunctions.h)\n\nThe math function should be defined in the same namespace than \\c T, or in the \\c std namespace though that second approach is not recommended.\n\nHere is a concrete example adding support for the Adolc's \\c adouble type. <a href=\"https://projects.coin-or.org/ADOL-C\">Adolc</a> is an automatic differentiation library. The type \\c adouble is basically a real value tracking the values of any number of partial derivatives.\n\n\\code\n#ifndef ADOLCSUPPORT_H\n#define ADOLCSUPPORT_H\n\n#define ADOLC_TAPELESS\n#include <adolc/adouble.h>\n#include <Eigen/Core>\n\nnamespace Eigen {\n\ntemplate<> struct NumTraits<adtl::adouble>\n : NumTraits<double> // permits to get the epsilon, dummy_precision, lowest, highest functions\n{\n  typedef adtl::adouble Real;\n  typedef adtl::adouble NonInteger;\n  typedef adtl::adouble Nested;\n\n  enum {\n    IsComplex = 0,\n    IsInteger = 0,\n    IsSigned = 1,\n    RequireInitialization = 1,\n    ReadCost = 1,\n    AddCost = 3,\n    MulCost = 3\n  };\n};\n\n}\n\nnamespace adtl {\n\ninline const adouble& conj(const adouble& x)  { return x; }\ninline const adouble& real(const adouble& x)  { return x; }\ninline adouble imag(const adouble&)    { return 0.; }\ninline adouble abs(const adouble&  x)  { return fabs(x); }\ninline adouble abs2(const adouble& x)  { return x*x; }\n\n}\n\n#endif // ADOLCSUPPORT_H\n\\endcode\n\nThis other example adds support for the \\c mpq_class type from <a href=\"https://gmplib.org/\">GMP</a>. It shows in particular how to change the way Eigen picks the best pivot during LU factorization. It selects the coefficient with the highest score, where the score is by default the absolute value of a number, but we can define a different score, for instance to prefer pivots with a more compact representation (this is an example, not a recommendation). Note that the scores should always be non-negative and only zero is allowed to have a score of zero. Also, this can interact badly with thresholds for inexact scalar types.\n\n\\code\n#include <gmpxx.h>\n#include <Eigen/Core>\n#include <boost/operators.hpp>\n\nnamespace Eigen {\n  template<> struct NumTraits<mpq_class> : GenericNumTraits<mpq_class>\n  {\n    typedef mpq_class Real;\n    typedef mpq_class NonInteger;\n    typedef mpq_class Nested;\n\n    static inline Real epsilon() { return 0; }\n    static inline Real dummy_precision() { return 0; }\n    static inline int digits10() { return 0; }\n\n    enum {\n      IsInteger = 0,\n      IsSigned = 1,\n      IsComplex = 0,\n      RequireInitialization = 1,\n      ReadCost = 6,\n      AddCost = 150,\n      MulCost = 100\n    };\n  };\n\n  namespace internal {\n\n    template<> struct scalar_score_coeff_op<mpq_class> {\n      struct result_type : boost::totally_ordered1<result_type> {\n        std::size_t len;\n        result_type(int i = 0) : len(i) {} // Eigen uses Score(0) and Score()\n        result_type(mpq_class const& q) :\n          len(mpz_size(q.get_num_mpz_t())+\n              mpz_size(q.get_den_mpz_t())-1) {}\n        friend bool operator<(result_type x, result_type y) {\n          // 0 is the worst possible pivot\n          if (x.len == 0) return y.len > 0;\n          if (y.len == 0) return false;\n          // Prefer a pivot with a small representation\n          return x.len > y.len;\n        }\n        friend bool operator==(result_type x, result_type y) {\n          // Only used to test if the score is 0\n          return x.len == y.len;\n        }\n      };\n      result_type operator()(mpq_class const& x) const { return x; }\n    };\n  }\n}\n\\endcode\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/CustomizingEigen_InheritingMatrix.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicCustomizing_InheritingMatrix Inheriting from Matrix\n\nBefore inheriting from Matrix, be really, I mean REALLY, sure that using\nEIGEN_MATRIX_PLUGIN is not what you really want (see previous section).\nIf you just need to add few members to Matrix, this is the way to go.\n\nAn example of when you actually need to inherit Matrix, is when you\nhave several layers of heritage such as \nMyVerySpecificVector1, MyVerySpecificVector2 -> MyVector1 -> Matrix and\nMyVerySpecificVector3, MyVerySpecificVector4 -> MyVector2 -> Matrix.\n\nIn order for your object to work within the %Eigen framework, you need to\ndefine a few members in your inherited class.\n\nHere is a minimalistic example:\n\n\\include CustomizingEigen_Inheritance.cpp\n\nOutput: \\verbinclude CustomizingEigen_Inheritance.out\n\nThis is the kind of error you can get if you don't provide those methods\n\\verbatim\nerror: no match for ‘operator=’ in ‘v = Eigen::operator*(\nconst Eigen::MatrixBase<Eigen::Matrix<double, -0x000000001, 1, 0, -0x000000001, 1> >::Scalar&, \nconst Eigen::MatrixBase<Eigen::Matrix<double, -0x000000001, 1> >::StorageBaseType&)\n(((const Eigen::MatrixBase<Eigen::Matrix<double, -0x000000001, 1> >::StorageBaseType&)\n((const Eigen::MatrixBase<Eigen::Matrix<double, -0x000000001, 1> >::StorageBaseType*)(& v))))’\n\\endverbatim\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/CustomizingEigen_NullaryExpr.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicCustomizing_NullaryExpr Matrix manipulation via nullary-expressions\n\n\nThe main purpose of the class CwiseNullaryOp is to define \\em procedural matrices such as constant or random matrices as returned by the Ones(), Zero(), Constant(), Identity() and Random() methods.\nNevertheless, with some imagination it is possible to accomplish very sophisticated matrix manipulation with minimal efforts such that \\ref TopicNewExpressionType \"implementing new expression\" is rarely needed.\n\n\\section NullaryExpr_Circulant Example 1: circulant matrix\n\nTo explore these possibilities let us start with the  \\em circulant example of the \\ref TopicNewExpressionType \"implementing new expression\" topic.\nLet us recall that a circulant matrix is a matrix where each column is the same as the\ncolumn to the left, except that it is cyclically shifted downwards.\nFor example, here is a 4-by-4 circulant matrix:\n\\f[ \\begin{bmatrix}\n    1 & 8 & 4 & 2 \\\\\n    2 & 1 & 8 & 4 \\\\\n    4 & 2 & 1 & 8 \\\\\n    8 & 4 & 2 & 1\n\\end{bmatrix} \\f]\nA circulant matrix is uniquely determined by its first column. We wish\nto write a function \\c makeCirculant which, given the first column,\nreturns an expression representing the circulant matrix.\n\nFor this exercise, the return type of \\c makeCirculant will be a CwiseNullaryOp that we need to instantiate with:\n1 - a proper \\c circulant_functor storing the input vector and implementing the adequate coefficient accessor \\c operator(i,j)\n2 - a template instantiation of class Matrix conveying compile-time information such as the scalar type, sizes, and preferred storage layout.\n\nCalling \\c ArgType the type of the input vector, we can construct the equivalent squared Matrix type as follows:\n\n\\snippet make_circulant2.cpp square\n\nThis little helper structure will help us to implement our \\c makeCirculant function as follows:\n\n\\snippet make_circulant2.cpp makeCirculant\n\nAs usual, our function takes as argument a \\c MatrixBase (see this \\ref TopicFunctionTakingEigenTypes \"page\" for more details).\nThen, the CwiseNullaryOp object is constructed through the DenseBase::NullaryExpr static method with the adequate runtime sizes.\n\nThen, we need to implement our \\c circulant_functor, which is a straightforward exercise:\n\n\\snippet make_circulant2.cpp circulant_func\n\nWe are now all set to try our new feature:\n\n\\snippet make_circulant2.cpp main\n\n\nIf all the fragments are combined, the following output is produced,\nshowing that the program works as expected:\n\n\\include make_circulant2.out\n\nThis implementation of \\c makeCirculant is much simpler than \\ref TopicNewExpressionType \"defining a new expression\" from scratch.\n\n\n\\section NullaryExpr_Indexing Example 2: indexing rows and columns\n\nThe goal here is to mimic MatLab's ability to index a matrix through two vectors of indices referencing the rows and columns to be picked respectively, like this:\n\n\\snippet nullary_indexing.out main1\n\nTo this end, let us first write a nullary-functor storing references to the input matrix and to the two arrays of indices, and implementing the required \\c operator()(i,j):\n\n\\snippet nullary_indexing.cpp functor\n\nThen, let's create an \\c indexing(A,rows,cols) function creating the nullary expression:\n\n\\snippet nullary_indexing.cpp function\n\nFinally, here is an example of how this function can be used:\n\n\\snippet nullary_indexing.cpp main1\n\nThis straightforward implementation is already quite powerful as the row or column index arrays can also be expressions to perform offsetting, modulo, striding, reverse, etc.\n\n\\snippet nullary_indexing.cpp main2\n\nand the output is:\n\n\\snippet nullary_indexing.out main2\n\n*/\n\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/CustomizingEigen_Plugins.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicCustomizing_Plugins Extending MatrixBase (and other classes)\n\nIn this section we will see how to add custom methods to MatrixBase. Since all expressions and matrix types inherit MatrixBase, adding a method to MatrixBase make it immediately available to all expressions ! A typical use case is, for instance, to make Eigen compatible with another API.\n\nYou certainly know that in C++ it is not possible to add methods to an existing class. So how that's possible ? Here the trick is to include in the declaration of MatrixBase a file defined by the preprocessor token \\c EIGEN_MATRIXBASE_PLUGIN:\n\\code\nclass MatrixBase {\n  // ...\n  #ifdef EIGEN_MATRIXBASE_PLUGIN\n  #include EIGEN_MATRIXBASE_PLUGIN\n  #endif\n};\n\\endcode\nTherefore to extend MatrixBase with your own methods you just have to create a file with your method declaration and define EIGEN_MATRIXBASE_PLUGIN before you include any Eigen's header file.\n\nYou can extend many of the other classes used in Eigen by defining similarly named preprocessor symbols. For instance, define \\c EIGEN_ARRAYBASE_PLUGIN if you want to extend the ArrayBase class. A full list of classes that can be extended in this way and the corresponding preprocessor symbols can be found on our page \\ref TopicPreprocessorDirectives.\n\nHere is an example of an extension file for adding methods to MatrixBase: \\n\n\\b MatrixBaseAddons.h\n\\code\ninline Scalar at(uint i, uint j) const { return this->operator()(i,j); }\ninline Scalar& at(uint i, uint j) { return this->operator()(i,j); }\ninline Scalar at(uint i) const { return this->operator[](i); }\ninline Scalar& at(uint i) { return this->operator[](i); }\n\ninline RealScalar squaredLength() const { return squaredNorm(); }\ninline RealScalar length() const { return norm(); }\ninline RealScalar invLength(void) const { return fast_inv_sqrt(squaredNorm()); }\n\ntemplate<typename OtherDerived>\ninline Scalar squaredDistanceTo(const MatrixBase<OtherDerived>& other) const\n{ return (derived() - other.derived()).squaredNorm(); }\n\ntemplate<typename OtherDerived>\ninline RealScalar distanceTo(const MatrixBase<OtherDerived>& other) const\n{ return internal::sqrt(derived().squaredDistanceTo(other)); }\n\ninline void scaleTo(RealScalar l) { RealScalar vl = norm(); if (vl>1e-9) derived() *= (l/vl); }\n\ninline Transpose<Derived> transposed() {return this->transpose();}\ninline const Transpose<Derived> transposed() const {return this->transpose();}\n\ninline uint minComponentId(void) const  { int i; this->minCoeff(&i); return i; }\ninline uint maxComponentId(void) const  { int i; this->maxCoeff(&i); return i; }\n\ntemplate<typename OtherDerived>\nvoid makeFloor(const MatrixBase<OtherDerived>& other) { derived() = derived().cwiseMin(other.derived()); }\ntemplate<typename OtherDerived>\nvoid makeCeil(const MatrixBase<OtherDerived>& other) { derived() = derived().cwiseMax(other.derived()); }\n\nconst CwiseBinaryOp<internal::scalar_sum_op<Scalar>, const Derived, const ConstantReturnType>\noperator+(const Scalar& scalar) const\n{ return CwiseBinaryOp<internal::scalar_sum_op<Scalar>, const Derived, const ConstantReturnType>(derived(), Constant(rows(),cols(),scalar)); }\n\nfriend const CwiseBinaryOp<internal::scalar_sum_op<Scalar>, const ConstantReturnType, Derived>\noperator+(const Scalar& scalar, const MatrixBase<Derived>& mat)\n{ return CwiseBinaryOp<internal::scalar_sum_op<Scalar>, const ConstantReturnType, Derived>(Constant(rows(),cols(),scalar), mat.derived()); }\n\\endcode\n\nThen one can the following declaration in the config.h or whatever prerequisites header file of his project:\n\\code\n#define EIGEN_MATRIXBASE_PLUGIN \"MatrixBaseAddons.h\"\n\\endcode\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/DenseDecompositionBenchmark.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage DenseDecompositionBenchmark Benchmark of dense decompositions\n\nThis page presents a speed comparison of the dense matrix decompositions offered by %Eigen for a wide range of square matrices and overconstrained problems.\n\nFor a more general overview on the features and numerical robustness of linear solvers and decompositions, check this \\link TopicLinearAlgebraDecompositions table \\endlink.\n\nThis benchmark has been run on a laptop equipped with an Intel core i7 \\@ 2,6 GHz, and compiled with clang with \\b AVX and \\b FMA instruction sets enabled but without multi-threading.\nIt uses \\b single \\b precision \\b float numbers. For double, you can get a good estimate by multiplying the timings by a factor 2.\n\nThe square matrices are symmetric, and for the overconstrained matrices, the reported timmings include the cost to compute the symmetric covariance matrix \\f$ A^T A \\f$ for the first four solvers based on Cholesky and LU, as denoted by the \\b * symbol (top-right corner part of the table).\nTimings are in \\b milliseconds, and factors are relative to the LLT decomposition which is the fastest but also the least general and robust.\n\n<table class=\"manual\">\n<tr><th>solver/size</th>\n  <th>8x8</th>  <th>100x100</th>  <th>1000x1000</th>  <th>4000x4000</th>  <th>10000x8</th>  <th>10000x100</th>  <th>10000x1000</th>  <th>10000x4000</th></tr>\n<tr><td>LLT</td><td>0.05</td><td>0.42</td><td>5.83</td><td>374.55</td><td>6.79 <sup><a href=\"#note_ls\">*</a></sup></td><td>30.15 <sup><a href=\"#note_ls\">*</a></sup></td><td>236.34 <sup><a href=\"#note_ls\">*</a></sup></td><td>3847.17 <sup><a href=\"#note_ls\">*</a></sup></td></tr>\n<tr class=\"alt\"><td>LDLT</td><td>0.07 (x1.3)</td><td>0.65 (x1.5)</td><td>26.86 (x4.6)</td><td>2361.18 (x6.3)</td><td>6.81 (x1) <sup><a href=\"#note_ls\">*</a></sup></td><td>31.91 (x1.1) <sup><a href=\"#note_ls\">*</a></sup></td><td>252.61 (x1.1) <sup><a href=\"#note_ls\">*</a></sup></td><td>5807.66 (x1.5) <sup><a href=\"#note_ls\">*</a></sup></td></tr>\n<tr><td>PartialPivLU</td><td>0.08 (x1.5)</td><td>0.69 (x1.6)</td><td>15.63 (x2.7)</td><td>709.32 (x1.9)</td><td>6.81 (x1) <sup><a href=\"#note_ls\">*</a></sup></td><td>31.32 (x1) <sup><a href=\"#note_ls\">*</a></sup></td><td>241.68 (x1) <sup><a href=\"#note_ls\">*</a></sup></td><td>4270.48 (x1.1) <sup><a href=\"#note_ls\">*</a></sup></td></tr>\n<tr class=\"alt\"><td>FullPivLU</td><td>0.1 (x1.9)</td><td>4.48 (x10.6)</td><td>281.33 (x48.2)</td><td>-</td><td>6.83 (x1) <sup><a href=\"#note_ls\">*</a></sup></td><td>32.67 (x1.1) <sup><a href=\"#note_ls\">*</a></sup></td><td>498.25 (x2.1) <sup><a href=\"#note_ls\">*</a></sup></td><td>-</td></tr>\n<tr><td>HouseholderQR</td><td>0.19 (x3.5)</td><td>2.18 (x5.2)</td><td>23.42 (x4)</td><td>1337.52 (x3.6)</td><td>34.26 (x5)</td><td>129.01 (x4.3)</td><td>377.37 (x1.6)</td><td>4839.1 (x1.3)</td></tr>\n<tr class=\"alt\"><td>ColPivHouseholderQR</td><td>0.23 (x4.3)</td><td>2.23 (x5.3)</td><td>103.34 (x17.7)</td><td>9987.16 (x26.7)</td><td>36.05 (x5.3)</td><td>163.18 (x5.4)</td><td>2354.08 (x10)</td><td>37860.5 (x9.8)</td></tr>\n<tr><td>CompleteOrthogonalDecomposition</td><td>0.23 (x4.3)</td><td>2.22 (x5.2)</td><td>99.44 (x17.1)</td><td>10555.3 (x28.2)</td><td>35.75 (x5.3)</td><td>169.39 (x5.6)</td><td>2150.56 (x9.1)</td><td>36981.8 (x9.6)</td></tr>\n<tr class=\"alt\"><td>FullPivHouseholderQR</td><td>0.23 (x4.3)</td><td>4.64 (x11)</td><td>289.1 (x49.6)</td><td>-</td><td>69.38 (x10.2)</td><td>446.73 (x14.8)</td><td>4852.12 (x20.5)</td><td>-</td></tr>\n<tr><td>JacobiSVD</td><td>1.01 (x18.6)</td><td>71.43 (x168.4)</td><td>-</td><td>-</td><td>113.81 (x16.7)</td><td>1179.66 (x39.1)</td><td>-</td><td>-</td></tr>\n<tr class=\"alt\"><td>BDCSVD</td><td>1.07 (x19.7)</td><td>21.83 (x51.5)</td><td>331.77 (x56.9)</td><td>18587.9 (x49.6)</td><td>110.53 (x16.3)</td><td>397.67 (x13.2)</td><td>2975 (x12.6)</td><td>48593.2 (x12.6)</td></tr>\n</table>\n\n<a name=\"note_ls\">\\b *: </a> This decomposition do not support direct least-square solving for over-constrained problems, and the reported timing include the cost to form the symmetric covariance matrix \\f$ A^T A \\f$.\n\n\\b Observations:\n + LLT is always the fastest solvers.\n + For largely over-constrained problems, the cost of Cholesky/LU decompositions is dominated by the computation of the symmetric covariance matrix.\n + For large problem sizes, only the decomposition implementing a cache-friendly blocking strategy scale well. Those include LLT, PartialPivLU, HouseholderQR, and BDCSVD. This explain why for a 4k x 4k matrix, HouseholderQR is faster than LDLT. In the future, LDLT and ColPivHouseholderQR will also implement blocking strategies.\n + CompleteOrthogonalDecomposition is based on ColPivHouseholderQR and they thus achieve the same level of performance.\n\nThe above table has been generated by the <a href=\"https://gitlab.com/libeigen/eigen/raw/master/bench/dense_solvers.cpp\">bench/dense_solvers.cpp</a> file, feel-free to hack it to generate a table matching your hardware, compiler, and favorite problem sizes.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/Doxyfile.in",
    "content": "# Doxyfile 1.8.1.1\n\n# This file describes the settings to be used by the documentation system\n# doxygen (www.doxygen.org) for a project.\n#\n# All text after a hash (#) is considered a comment and will be ignored.\n# The format is:\n#       TAG = value [value, ...]\n# For lists items can also be appended using:\n#       TAG += value [value, ...]\n# Values that contain spaces should be placed between quotes (\" \").\n\n#---------------------------------------------------------------------------\n# Project related configuration options\n#---------------------------------------------------------------------------\n\n# This tag specifies the encoding used for all characters in the config file\n# that follow. The default is UTF-8 which is also the encoding used for all\n# text before the first occurrence of this tag. Doxygen uses libiconv (or the\n# iconv built into libc) for the transcoding. See\n# http://www.gnu.org/software/libiconv for the list of possible encodings.\n\nDOXYFILE_ENCODING      = UTF-8\n\n# The PROJECT_NAME tag is a single word (or sequence of words) that should\n# identify the project. Note that if you do not use Doxywizard you need\n# to put quotes around the project name if it contains spaces.\n\nPROJECT_NAME           = ${EIGEN_DOXY_PROJECT_NAME}\n\n# The PROJECT_NUMBER tag can be used to enter a project or revision number.\n# This could be handy for archiving the generated documentation or\n# if some version control system is used.\n\n# EIGEN_VERSION is set in the root CMakeLists.txt\n\nPROJECT_NUMBER         = \"${EIGEN_VERSION}\"\n\n# Using the PROJECT_BRIEF tag one can provide an optional one line description\n# for a project that appears at the top of each page and should give viewer\n# a quick idea about the purpose of the project. Keep the description short.\n\nPROJECT_BRIEF          =\n\n# With the PROJECT_LOGO tag one can specify an logo or icon that is\n# included in the documentation. The maximum height of the logo should not\n# exceed 55 pixels and the maximum width should not exceed 200 pixels.\n# Doxygen will copy the logo to the output directory.\n\nPROJECT_LOGO           = \"${Eigen_SOURCE_DIR}/doc/Eigen_Silly_Professor_64x64.png\"\n\n# The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute)\n# base path where the generated documentation will be put.\n# If a relative path is entered, it will be relative to the location\n# where doxygen was started. If left blank the current directory will be used.\n\nOUTPUT_DIRECTORY       = \"${Eigen_BINARY_DIR}/doc${EIGEN_DOXY_OUTPUT_DIRECTORY_SUFFIX}\"\n\n# If the CREATE_SUBDIRS tag is set to YES, then doxygen will create\n# 4096 sub-directories (in 2 levels) under the output directory of each output\n# format and will distribute the generated files over these directories.\n# Enabling this option can be useful when feeding doxygen a huge amount of\n# source files, where putting all generated files in the same directory would\n# otherwise cause performance problems for the file system.\n\nCREATE_SUBDIRS         = NO\n\n# The OUTPUT_LANGUAGE tag is used to specify the language in which all\n# documentation generated by doxygen is written. Doxygen will use this\n# information to generate all constant output in the proper language.\n# The default language is English, other supported languages are:\n# Afrikaans, Arabic, Brazilian, Catalan, Chinese, Chinese-Traditional,\n# Croatian, Czech, Danish, Dutch, Esperanto, Farsi, Finnish, French, German,\n# Greek, Hungarian, Italian, Japanese, Japanese-en (Japanese with English\n# messages), Korean, Korean-en, Lithuanian, Norwegian, Macedonian, Persian,\n# Polish, Portuguese, Romanian, Russian, Serbian, Serbian-Cyrillic, Slovak,\n# Slovene, Spanish, Swedish, Ukrainian, and Vietnamese.\n\nOUTPUT_LANGUAGE        = English\n\n# If the BRIEF_MEMBER_DESC tag is set to YES (the default) Doxygen will\n# include brief member descriptions after the members that are listed in\n# the file and class documentation (similar to JavaDoc).\n# Set to NO to disable this.\n\nBRIEF_MEMBER_DESC      = YES\n\n# If the REPEAT_BRIEF tag is set to YES (the default) Doxygen will prepend\n# the brief description of a member or function before the detailed description.\n# Note: if both HIDE_UNDOC_MEMBERS and BRIEF_MEMBER_DESC are set to NO, the\n# brief descriptions will be completely suppressed.\n\nREPEAT_BRIEF           = YES\n\n# This tag implements a quasi-intelligent brief description abbreviator\n# that is used to form the text in various listings. Each string\n# in this list, if found as the leading text of the brief description, will be\n# stripped from the text and the result after processing the whole list, is\n# used as the annotated text. Otherwise, the brief description is used as-is.\n# If left blank, the following values are used (\"$name\" is automatically\n# replaced with the name of the entity): \"The $name class\" \"The $name widget\"\n# \"The $name file\" \"is\" \"provides\" \"specifies\" \"contains\"\n# \"represents\" \"a\" \"an\" \"the\"\n\nABBREVIATE_BRIEF       = \"The $name class\" \\\n                         \"The $name widget\" \\\n                         \"The $name file\" \\\n                         is \\\n                         provides \\\n                         specifies \\\n                         contains \\\n                         represents \\\n                         a \\\n                         an \\\n                         the\n\n# If the ALWAYS_DETAILED_SEC and REPEAT_BRIEF tags are both set to YES then\n# Doxygen will generate a detailed section even if there is only a brief\n# description.\n\nALWAYS_DETAILED_SEC    = NO\n\n# If the INLINE_INHERITED_MEMB tag is set to YES, doxygen will show all\n# inherited members of a class in the documentation of that class as if those\n# members were ordinary class members. Constructors, destructors and assignment\n# operators of the base classes will not be shown.\n\nINLINE_INHERITED_MEMB  = NO\n\n# If the FULL_PATH_NAMES tag is set to YES then Doxygen will prepend the full\n# path before files name in the file list and in the header files. If set\n# to NO the shortest path that makes the file name unique will be used.\n\nFULL_PATH_NAMES        = NO\n\n# If the FULL_PATH_NAMES tag is set to YES then the STRIP_FROM_PATH tag\n# can be used to strip a user-defined part of the path. Stripping is\n# only done if one of the specified strings matches the left-hand part of\n# the path. The tag can be used to show relative paths in the file list.\n# If left blank the directory from which doxygen is run is used as the\n# path to strip.\n\nSTRIP_FROM_PATH        =\n\n# The STRIP_FROM_INC_PATH tag can be used to strip a user-defined part of\n# the path mentioned in the documentation of a class, which tells\n# the reader which header file to include in order to use a class.\n# If left blank only the name of the header file containing the class\n# definition is used. Otherwise one should specify the include paths that\n# are normally passed to the compiler using the -I flag.\n\nSTRIP_FROM_INC_PATH    =\n\n# If the SHORT_NAMES tag is set to YES, doxygen will generate much shorter\n# (but less readable) file names. This can be useful if your file system\n# doesn't support long names like on DOS, Mac, or CD-ROM.\n\nSHORT_NAMES            = NO\n\n# If the JAVADOC_AUTOBRIEF tag is set to YES then Doxygen\n# will interpret the first line (until the first dot) of a JavaDoc-style\n# comment as the brief description. If set to NO, the JavaDoc\n# comments will behave just like regular Qt-style comments\n# (thus requiring an explicit @brief command for a brief description.)\n\nJAVADOC_AUTOBRIEF      = NO\n\n# If the QT_AUTOBRIEF tag is set to YES then Doxygen will\n# interpret the first line (until the first dot) of a Qt-style\n# comment as the brief description. If set to NO, the comments\n# will behave just like regular Qt-style comments (thus requiring\n# an explicit \\brief command for a brief description.)\n\nQT_AUTOBRIEF           = NO\n\n# The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make Doxygen\n# treat a multi-line C++ special comment block (i.e. a block of //! or ///\n# comments) as a brief description. This used to be the default behaviour.\n# The new default is to treat a multi-line C++ comment block as a detailed\n# description. Set this tag to YES if you prefer the old behaviour instead.\n\nMULTILINE_CPP_IS_BRIEF = NO\n\n# If the INHERIT_DOCS tag is set to YES (the default) then an undocumented\n# member inherits the documentation from any documented member that it\n# re-implements.\n\nINHERIT_DOCS           = YES\n\n# If the SEPARATE_MEMBER_PAGES tag is set to YES, then doxygen will produce\n# a new page for each member. If set to NO, the documentation of a member will\n# be part of the file/class/namespace that contains it.\n\nSEPARATE_MEMBER_PAGES  = NO\n\n# The TAB_SIZE tag can be used to set the number of spaces in a tab.\n# Doxygen uses this value to replace tabs by spaces in code fragments.\n\nTAB_SIZE               = 8\n\n# This tag can be used to specify a number of aliases that acts\n# as commands in the documentation. An alias has the form \"name=value\".\n# For example adding \"sideeffect=\\par Side Effects:\\n\" will allow you to\n# put the command \\sideeffect (or @sideeffect) in the documentation, which\n# will result in a user-defined paragraph with heading \"Side Effects:\".\n# You can put \\n's in the value part of an alias to insert newlines.\n\nALIASES                = \"only_for_vectors=This is only for vectors (either row-vectors or column-vectors), i.e. matrices which are known at compile-time to have either one row or one column.\" \\\n                         \"not_reentrant=\\warning This function is not re-entrant.\" \\\n                         \"array_module=This is defined in the %Array module. \\code #include <Eigen/Array> \\endcode\" \\\n                         \"cholesky_module=This is defined in the %Cholesky module. \\code #include <Eigen/Cholesky> \\endcode\" \\\n                         \"eigenvalues_module=This is defined in the %Eigenvalues module. \\code #include <Eigen/Eigenvalues> \\endcode\" \\\n                         \"geometry_module=This is defined in the %Geometry module. \\code #include <Eigen/Geometry> \\endcode\" \\\n                         \"householder_module=This is defined in the %Householder module. \\code #include <Eigen/Householder> \\endcode\" \\\n                         \"jacobi_module=This is defined in the %Jacobi module. \\code #include <Eigen/Jacobi> \\endcode\" \\\n                         \"lu_module=This is defined in the %LU module. \\code #include <Eigen/LU> \\endcode\" \\\n                         \"qr_module=This is defined in the %QR module. \\code #include <Eigen/QR> \\endcode\" \\\n                         \"svd_module=This is defined in the %SVD module. \\code #include <Eigen/SVD> \\endcode\" \\\n                         \"specialfunctions_module=This is defined in the \\b unsupported SpecialFunctions module. \\code #include <Eigen/SpecialFunctions> \\endcode\" \\\n                         \"label=\\bug\" \\\n                         \"matrixworld=<a href='#matrixonly' style='color:green;text-decoration: none;'>*</a>\" \\\n                         \"arrayworld=<a href='#arrayonly' style='color:blue;text-decoration: none;'>*</a>\" \\\n                         \"note_about_arbitrary_choice_of_solution=If there exists more than one solution, this method will arbitrarily choose one.\" \\\n                         \"note_about_using_kernel_to_study_multiple_solutions=If you need a complete analysis of the space of solutions, take the one solution obtained by this method and add to it elements of the kernel, as determined by kernel().\" \\\n                         \"note_about_checking_solutions=This method just tries to find as good a solution as possible. If you want to check whether a solution exists or if it is accurate, just call this function to get a result and then compute the error of this result, or use MatrixBase::isApprox() directly, for instance like this: \\code bool a_solution_exists = (A*result).isApprox(b, precision); \\endcode This method avoids dividing by zero, so that the non-existence of a solution doesn't by itself mean that you'll get \\c inf or \\c nan values.\" \\\n                         \"note_try_to_help_rvo=This function returns the result by value. In order to make that efficient, it is implemented as just a return statement using a special constructor, hopefully allowing the compiler to perform a RVO (return value optimization).\" \\\n                         \"nonstableyet=\\warning This is not considered to be part of the stable public API yet. Changes may happen in future releases. See \\ref Experimental \\\"Experimental parts of Eigen\\\"\" \\\n                         \"implsparsesolverconcept=This class follows the \\link TutorialSparseSolverConcept sparse solver concept \\endlink.\" \\\n                         \"blank= \" \\\n                         \"cpp11=<span class='cpp11'>[c++11]</span>\" \\\n                         \"cpp14=<span class='cpp14'>[c++14]</span>\" \\\n                         \"cpp17=<span class='cpp17'>[c++17]</span>\" \\\n                         \"newin{1}=<span class='newin3x'>New in %Eigen \\1.</span>\"\n                         \n\nALIASES += \"eigenAutoToc=  \"\nALIASES += \"eigenManualPage=\\defgroup\"\n\n# This tag can be used to specify a number of word-keyword mappings (TCL only).\n# A mapping has the form \"name=value\". For example adding\n# \"class=itcl::class\" will allow you to use the command class in the\n# itcl::class meaning.\n\nTCL_SUBST              =\n\n# Set the OPTIMIZE_OUTPUT_FOR_C tag to YES if your project consists of C\n# sources only. Doxygen will then generate output that is more tailored for C.\n# For instance, some of the names that are used will be different. The list\n# of all members will be omitted, etc.\n\nOPTIMIZE_OUTPUT_FOR_C  = NO\n\n# Set the OPTIMIZE_OUTPUT_JAVA tag to YES if your project consists of Java\n# sources only. Doxygen will then generate output that is more tailored for\n# Java. For instance, namespaces will be presented as packages, qualified\n# scopes will look different, etc.\n\nOPTIMIZE_OUTPUT_JAVA   = NO\n\n# Set the OPTIMIZE_FOR_FORTRAN tag to YES if your project consists of Fortran\n# sources only. Doxygen will then generate output that is more tailored for\n# Fortran.\n\nOPTIMIZE_FOR_FORTRAN   = NO\n\n# Set the OPTIMIZE_OUTPUT_VHDL tag to YES if your project consists of VHDL\n# sources. Doxygen will then generate output that is tailored for\n# VHDL.\n\nOPTIMIZE_OUTPUT_VHDL   = NO\n\n# Doxygen selects the parser to use depending on the extension of the files it\n# parses. With this tag you can assign which parser to use for a given extension.\n# Doxygen has a built-in mapping, but you can override or extend it using this\n# tag. The format is ext=language, where ext is a file extension, and language\n# is one of the parsers supported by doxygen: IDL, Java, Javascript, CSharp, C,\n# C++, D, PHP, Objective-C, Python, Fortran, VHDL, C, C++. For instance to make\n# doxygen treat .inc files as Fortran files (default is PHP), and .f files as C\n# (default is Fortran), use: inc=Fortran f=C. Note that for custom extensions\n# you also need to set FILE_PATTERNS otherwise the files are not read by doxygen.\n\nEXTENSION_MAPPING      = .h=C++ no_extension=C++\n\n# If MARKDOWN_SUPPORT is enabled (the default) then doxygen pre-processes all\n# comments according to the Markdown format, which allows for more readable\n# documentation. See http://daringfireball.net/projects/markdown/ for details.\n# The output of markdown processing is further processed by doxygen, so you\n# can mix doxygen, HTML, and XML commands with Markdown formatting.\n# Disable only in case of backward compatibilities issues.\n\nMARKDOWN_SUPPORT       = YES\n\n# If you use STL classes (i.e. std::string, std::vector, etc.) but do not want\n# to include (a tag file for) the STL sources as input, then you should\n# set this tag to YES in order to let doxygen match functions declarations and\n# definitions whose arguments contain STL classes (e.g. func(std::string); v.s.\n# func(std::string) {}). This also makes the inheritance and collaboration\n# diagrams that involve STL classes more complete and accurate.\n\nBUILTIN_STL_SUPPORT    = NO\n\n# If you use Microsoft's C++/CLI language, you should set this option to YES to\n# enable parsing support.\n\nCPP_CLI_SUPPORT        = NO\n\n# Set the SIP_SUPPORT tag to YES if your project consists of sip sources only.\n# Doxygen will parse them like normal C++ but will assume all classes use public\n# instead of private inheritance when no explicit protection keyword is present.\n\nSIP_SUPPORT            = NO\n\n# For Microsoft's IDL there are propget and propput attributes to indicate getter\n# and setter methods for a property. Setting this option to YES (the default)\n# will make doxygen replace the get and set methods by a property in the\n# documentation. This will only work if the methods are indeed getting or\n# setting a simple type. If this is not the case, or you want to show the\n# methods anyway, you should set this option to NO.\n\nIDL_PROPERTY_SUPPORT   = YES\n\n# If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC\n# tag is set to YES, then doxygen will reuse the documentation of the first\n# member in the group (if any) for the other members of the group. By default\n# all members of a group must be documented explicitly.\n\nDISTRIBUTE_GROUP_DOC   = YES\n\n# Set the SUBGROUPING tag to YES (the default) to allow class member groups of\n# the same type (for instance a group of public functions) to be put as a\n# subgroup of that type (e.g. under the Public Functions section). Set it to\n# NO to prevent subgrouping. Alternatively, this can be done per class using\n# the \\nosubgrouping command.\n\nSUBGROUPING            = YES\n\n# When the INLINE_GROUPED_CLASSES tag is set to YES, classes, structs and\n# unions are shown inside the group in which they are included (e.g. using\n# @ingroup) instead of on a separate page (for HTML and Man pages) or\n# section (for LaTeX and RTF).\n\nINLINE_GROUPED_CLASSES = NO\n\n# When the INLINE_SIMPLE_STRUCTS tag is set to YES, structs, classes, and\n# unions with only public data fields will be shown inline in the documentation\n# of the scope in which they are defined (i.e. file, namespace, or group\n# documentation), provided this scope is documented. If set to NO (the default),\n# structs, classes, and unions are shown on a separate page (for HTML and Man\n# pages) or section (for LaTeX and RTF).\n\nINLINE_SIMPLE_STRUCTS  = NO\n\n# When TYPEDEF_HIDES_STRUCT is enabled, a typedef of a struct, union, or enum\n# is documented as struct, union, or enum with the name of the typedef. So\n# typedef struct TypeS {} TypeT, will appear in the documentation as a struct\n# with name TypeT. When disabled the typedef will appear as a member of a file,\n# namespace, or class. And the struct will be named TypeS. This can typically\n# be useful for C code in case the coding convention dictates that all compound\n# types are typedef'ed and only the typedef is referenced, never the tag name.\n\nTYPEDEF_HIDES_STRUCT   = NO\n\n# The SYMBOL_CACHE_SIZE determines the size of the internal cache use to\n# determine which symbols to keep in memory and which to flush to disk.\n# When the cache is full, less often used symbols will be written to disk.\n# For small to medium size projects (<1000 input files) the default value is\n# probably good enough. For larger projects a too small cache size can cause\n# doxygen to be busy swapping symbols to and from disk most of the time\n# causing a significant performance penalty.\n# If the system has enough physical memory increasing the cache will improve the\n# performance by keeping more symbols in memory. Note that the value works on\n# a logarithmic scale so increasing the size by one will roughly double the\n# memory usage. The cache size is given by this formula:\n# 2^(16+SYMBOL_CACHE_SIZE). The valid range is 0..9, the default is 0,\n# corresponding to a cache size of 2^16 = 65536 symbols.\n\n# SYMBOL_CACHE_SIZE      = 0\n\n# Similar to the SYMBOL_CACHE_SIZE the size of the symbol lookup cache can be\n# set using LOOKUP_CACHE_SIZE. This cache is used to resolve symbols given\n# their name and scope. Since this can be an expensive process and often the\n# same symbol appear multiple times in the code, doxygen keeps a cache of\n# pre-resolved symbols. If the cache is too small doxygen will become slower.\n# If the cache is too large, memory is wasted. The cache size is given by this\n# formula: 2^(16+LOOKUP_CACHE_SIZE). The valid range is 0..9, the default is 0,\n# corresponding to a cache size of 2^16 = 65536 symbols.\n\nLOOKUP_CACHE_SIZE      = 0\n\n#---------------------------------------------------------------------------\n# Build related configuration options\n#---------------------------------------------------------------------------\n\n# If the EXTRACT_ALL tag is set to YES doxygen will assume all entities in\n# documentation are documented, even if no documentation was available.\n# Private class members and static file members will be hidden unless\n# the EXTRACT_PRIVATE and EXTRACT_STATIC tags are set to YES\n\nEXTRACT_ALL            = NO\n\n# If the EXTRACT_PRIVATE tag is set to YES all private members of a class\n# will be included in the documentation.\n\nEXTRACT_PRIVATE        = NO\n\n# If the EXTRACT_PACKAGE tag is set to YES all members with package or internal scope will be included in the documentation.\n\nEXTRACT_PACKAGE        = NO\n\n# If the EXTRACT_STATIC tag is set to YES all static members of a file\n# will be included in the documentation.\n\nEXTRACT_STATIC         = YES\n\n# If the EXTRACT_LOCAL_CLASSES tag is set to YES classes (and structs)\n# defined locally in source files will be included in the documentation.\n# If set to NO only classes defined in header files are included.\n\nEXTRACT_LOCAL_CLASSES  = NO\n\n# This flag is only useful for Objective-C code. When set to YES local\n# methods, which are defined in the implementation section but not in\n# the interface are included in the documentation.\n# If set to NO (the default) only methods in the interface are included.\n\nEXTRACT_LOCAL_METHODS  = NO\n\n# If this flag is set to YES, the members of anonymous namespaces will be\n# extracted and appear in the documentation as a namespace called\n# 'anonymous_namespace{file}', where file will be replaced with the base\n# name of the file that contains the anonymous namespace. By default\n# anonymous namespaces are hidden.\n\nEXTRACT_ANON_NSPACES   = NO\n\n# If the HIDE_UNDOC_MEMBERS tag is set to YES, Doxygen will hide all\n# undocumented members of documented classes, files or namespaces.\n# If set to NO (the default) these members will be included in the\n# various overviews, but no documentation section is generated.\n# This option has no effect if EXTRACT_ALL is enabled.\n\nHIDE_UNDOC_MEMBERS     = YES\n\n# If the HIDE_UNDOC_CLASSES tag is set to YES, Doxygen will hide all\n# undocumented classes that are normally visible in the class hierarchy.\n# If set to NO (the default) these classes will be included in the various\n# overviews. This option has no effect if EXTRACT_ALL is enabled.\n\nHIDE_UNDOC_CLASSES     = YES\n\n# If the HIDE_FRIEND_COMPOUNDS tag is set to YES, Doxygen will hide all\n# friend (class|struct|union) declarations.\n# If set to NO (the default) these declarations will be included in the\n# documentation.\n\nHIDE_FRIEND_COMPOUNDS  = YES\n\n# If the HIDE_IN_BODY_DOCS tag is set to YES, Doxygen will hide any\n# documentation blocks found inside the body of a function.\n# If set to NO (the default) these blocks will be appended to the\n# function's detailed documentation block.\n\nHIDE_IN_BODY_DOCS      = NO\n\n# The INTERNAL_DOCS tag determines if documentation\n# that is typed after a \\internal command is included. If the tag is set\n# to NO (the default) then the documentation will be excluded.\n# Set it to YES to include the internal documentation.\n\nINTERNAL_DOCS          = ${EIGEN_DOXY_INTERNAL}\n\n# If the CASE_SENSE_NAMES tag is set to NO then Doxygen will only generate\n# file names in lower-case letters. If set to YES upper-case letters are also\n# allowed. This is useful if you have classes or files whose names only differ\n# in case and if your file system supports case sensitive file names. Windows\n# and Mac users are advised to set this option to NO.\n\nCASE_SENSE_NAMES       = YES\n\n# If the HIDE_SCOPE_NAMES tag is set to NO (the default) then Doxygen\n# will show members with their full class and namespace scopes in the\n# documentation. If set to YES the scope will be hidden.\n\nHIDE_SCOPE_NAMES       = NO\n\n# If the SHOW_INCLUDE_FILES tag is set to YES (the default) then Doxygen\n# will put a list of the files that are included by a file in the documentation\n# of that file.\n\nSHOW_INCLUDE_FILES     = ${EIGEN_DOXY_INTERNAL}\n\n# If the FORCE_LOCAL_INCLUDES tag is set to YES then Doxygen\n# will list include files with double quotes in the documentation\n# rather than with sharp brackets.\n\nFORCE_LOCAL_INCLUDES   = NO\n\n# If the INLINE_INFO tag is set to YES (the default) then a tag [inline]\n# is inserted in the documentation for inline members.\n\nINLINE_INFO            = YES\n\n# If the SORT_MEMBER_DOCS tag is set to YES (the default) then doxygen\n# will sort the (detailed) documentation of file and class members\n# alphabetically by member name. If set to NO the members will appear in\n# declaration order.\n\nSORT_MEMBER_DOCS       = YES\n\n# If the SORT_BRIEF_DOCS tag is set to YES then doxygen will sort the\n# brief documentation of file, namespace and class members alphabetically\n# by member name. If set to NO (the default) the members will appear in\n# declaration order.\n\nSORT_BRIEF_DOCS        = YES\n\n# If the SORT_MEMBERS_CTORS_1ST tag is set to YES then doxygen\n# will sort the (brief and detailed) documentation of class members so that\n# constructors and destructors are listed first. If set to NO (the default)\n# the constructors will appear in the respective orders defined by\n# SORT_MEMBER_DOCS and SORT_BRIEF_DOCS.\n# This tag will be ignored for brief docs if SORT_BRIEF_DOCS is set to NO\n# and ignored for detailed docs if SORT_MEMBER_DOCS is set to NO.\n\nSORT_MEMBERS_CTORS_1ST = NO\n\n# If the SORT_GROUP_NAMES tag is set to YES then doxygen will sort the\n# hierarchy of group names into alphabetical order. If set to NO (the default)\n# the group names will appear in their defined order.\n\nSORT_GROUP_NAMES       = NO\n\n# If the SORT_BY_SCOPE_NAME tag is set to YES, the class list will be\n# sorted by fully-qualified names, including namespaces. If set to\n# NO (the default), the class list will be sorted only by class name,\n# not including the namespace part.\n# Note: This option is not very useful if HIDE_SCOPE_NAMES is set to YES.\n# Note: This option applies only to the class list, not to the\n# alphabetical list.\n\nSORT_BY_SCOPE_NAME     = NO\n\n# If the STRICT_PROTO_MATCHING option is enabled and doxygen fails to\n# do proper type resolution of all parameters of a function it will reject a\n# match between the prototype and the implementation of a member function even\n# if there is only one candidate or it is obvious which candidate to choose\n# by doing a simple string match. By disabling STRICT_PROTO_MATCHING doxygen\n# will still accept a match between prototype and implementation in such cases.\n\nSTRICT_PROTO_MATCHING  = NO\n\n# The GENERATE_TODOLIST tag can be used to enable (YES) or\n# disable (NO) the todo list. This list is created by putting \\todo\n# commands in the documentation.\n\nGENERATE_TODOLIST      = ${EIGEN_DOXY_INTERNAL}\n\n# The GENERATE_TESTLIST tag can be used to enable (YES) or\n# disable (NO) the test list. This list is created by putting \\test\n# commands in the documentation.\n\nGENERATE_TESTLIST      = NO\n\n# The GENERATE_BUGLIST tag can be used to enable (YES) or\n# disable (NO) the bug list. This list is created by putting \\bug\n# commands in the documentation.\n\nGENERATE_BUGLIST       = ${EIGEN_DOXY_INTERNAL}\n\n# The GENERATE_DEPRECATEDLIST tag can be used to enable (YES) or\n# disable (NO) the deprecated list. This list is created by putting\n# \\deprecated commands in the documentation.\n\nGENERATE_DEPRECATEDLIST= YES\n\n# The ENABLED_SECTIONS tag can be used to enable conditional\n# documentation sections, marked by \\if sectionname ... \\endif.\n\nENABLED_SECTIONS       =\n\n# The MAX_INITIALIZER_LINES tag determines the maximum number of lines\n# the initial value of a variable or macro consists of for it to appear in\n# the documentation. If the initializer consists of more lines than specified\n# here it will be hidden. Use a value of 0 to hide initializers completely.\n# The appearance of the initializer of individual variables and macros in the\n# documentation can be controlled using \\showinitializer or \\hideinitializer\n# command in the documentation regardless of this setting.\n\nMAX_INITIALIZER_LINES  = 0\n\n# Set the SHOW_USED_FILES tag to NO to disable the list of files generated\n# at the bottom of the documentation of classes and structs. If set to YES the\n# list will mention the files that were used to generate the documentation.\n\nSHOW_USED_FILES        = YES\n\n# Set the SHOW_FILES tag to NO to disable the generation of the Files page.\n# This will remove the Files entry from the Quick Index and from the\n# Folder Tree View (if specified). The default is YES.\n\nSHOW_FILES             = YES\n\n# Set the SHOW_NAMESPACES tag to NO to disable the generation of the\n# Namespaces page.\n# This will remove the Namespaces entry from the Quick Index\n# and from the Folder Tree View (if specified). The default is YES.\n\nSHOW_NAMESPACES        = NO\n\n# The FILE_VERSION_FILTER tag can be used to specify a program or script that\n# doxygen should invoke to get the current version for each file (typically from\n# the version control system). Doxygen will invoke the program by executing (via\n# popen()) the command <command> <input-file>, where <command> is the value of\n# the FILE_VERSION_FILTER tag, and <input-file> is the name of an input file\n# provided by doxygen. Whatever the program writes to standard output\n# is used as the file version. See the manual for examples.\n\nFILE_VERSION_FILTER    =\n\n# The LAYOUT_FILE tag can be used to specify a layout file which will be parsed\n# by doxygen. The layout file controls the global structure of the generated\n# output files in an output format independent way. To create the layout file\n# that represents doxygen's defaults, run doxygen with the -l option.\n# You can optionally specify a file name after the option, if omitted\n# DoxygenLayout.xml will be used as the name of the layout file.\n\nLAYOUT_FILE            = \"${Eigen_BINARY_DIR}/doc${EIGEN_DOXY_OUTPUT_DIRECTORY_SUFFIX}/eigendoxy_layout.xml\"\n\n# The CITE_BIB_FILES tag can be used to specify one or more bib files\n# containing the references data. This must be a list of .bib files. The\n# .bib extension is automatically appended if omitted. Using this command\n# requires the bibtex tool to be installed. See also\n# http://en.wikipedia.org/wiki/BibTeX for more info. For LaTeX the style\n# of the bibliography can be controlled using LATEX_BIB_STYLE. To use this\n# feature you need bibtex and perl available in the search path.\n\nCITE_BIB_FILES         =\n\n#---------------------------------------------------------------------------\n# configuration options related to warning and progress messages\n#---------------------------------------------------------------------------\n\n# The QUIET tag can be used to turn on/off the messages that are generated\n# by doxygen. Possible values are YES and NO. If left blank NO is used.\n\nQUIET                  = NO\n\n# The WARNINGS tag can be used to turn on/off the warning messages that are\n# generated by doxygen. Possible values are YES and NO. If left blank\n# NO is used.\n\nWARNINGS               = YES\n\n# If WARN_IF_UNDOCUMENTED is set to YES, then doxygen will generate warnings\n# for undocumented members. If EXTRACT_ALL is set to YES then this flag will\n# automatically be disabled.\n\nWARN_IF_UNDOCUMENTED   = NO\n\n# If WARN_IF_DOC_ERROR is set to YES, doxygen will generate warnings for\n# potential errors in the documentation, such as not documenting some\n# parameters in a documented function, or documenting parameters that\n# don't exist or using markup commands wrongly.\n\nWARN_IF_DOC_ERROR      = YES\n\n# The WARN_NO_PARAMDOC option can be enabled to get warnings for\n# functions that are documented, but have no documentation for their parameters\n# or return value. If set to NO (the default) doxygen will only warn about\n# wrong or incomplete parameter documentation, but not about the absence of\n# documentation.\n\nWARN_NO_PARAMDOC       = NO\n\n# The WARN_FORMAT tag determines the format of the warning messages that\n# doxygen can produce. The string should contain the $file, $line, and $text\n# tags, which will be replaced by the file and line number from which the\n# warning originated and the warning text. Optionally the format may contain\n# $version, which will be replaced by the version of the file (if it could\n# be obtained via FILE_VERSION_FILTER)\n\nWARN_FORMAT            = \"$file:$line: $text\"\n\n# The WARN_LOGFILE tag can be used to specify a file to which warning\n# and error messages should be written. If left blank the output is written\n# to stderr.\n\nWARN_LOGFILE           =\n\n#---------------------------------------------------------------------------\n# configuration options related to the input files\n#---------------------------------------------------------------------------\n\n# The INPUT tag can be used to specify the files and/or directories that contain\n# documented source files. You may enter file names like \"myfile.cpp\" or\n# directories like \"/usr/src/myproject\". Separate the files or directories\n# with spaces.\n\nINPUT                  = ${EIGEN_DOXY_INPUT}\n\n# This tag can be used to specify the character encoding of the source files\n# that doxygen parses. Internally doxygen uses the UTF-8 encoding, which is\n# also the default input encoding. Doxygen uses libiconv (or the iconv built\n# into libc) for the transcoding. See http://www.gnu.org/software/libiconv for\n# the list of possible encodings.\n\nINPUT_ENCODING         = UTF-8\n\n# If the value of the INPUT tag contains directories, you can use the\n# FILE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp\n# and *.h) to filter out the source-files in the directories. If left\n# blank the following patterns are tested:\n# *.c *.cc *.cxx *.cpp *.c++ *.d *.java *.ii *.ixx *.ipp *.i++ *.inl *.h *.hh\n# *.hxx *.hpp *.h++ *.idl *.odl *.cs *.php *.php3 *.inc *.m *.mm *.dox *.py\n# *.f90 *.f *.for *.vhd *.vhdl\n\nFILE_PATTERNS          = *\n\n# The RECURSIVE tag can be used to turn specify whether or not subdirectories\n# should be searched for input files as well. Possible values are YES and NO.\n# If left blank NO is used.\n\nRECURSIVE              = YES\n\n# The EXCLUDE tag can be used to specify files and/or directories that should be\n# excluded from the INPUT source files. This way you can easily exclude a\n# subdirectory from a directory tree whose root is specified with the INPUT tag.\n# Note that relative paths are relative to the directory from which doxygen is\n# run.\n\nEXCLUDE                = \"${Eigen_SOURCE_DIR}/Eigen/src/Core/products\" \\\n                         \"${Eigen_SOURCE_DIR}/Eigen/Eigen2Support\" \\\n                         \"${Eigen_SOURCE_DIR}/Eigen/src/Eigen2Support\" \\\n                         \"${Eigen_SOURCE_DIR}/doc/examples\" \\\n                         \"${Eigen_SOURCE_DIR}/doc/special_examples\" \\\n                         \"${Eigen_SOURCE_DIR}/doc/snippets\" \\\n                         \"${Eigen_SOURCE_DIR}/unsupported/doc/examples\" \\\n                         \"${Eigen_SOURCE_DIR}/unsupported/doc/snippets\"\n\n# Forward declarations of class templates cause the title of the main page for\n# the class template to not contain the template signature.  This only happens\n# when the \\class command is used to document the class.  Possibly caused\n# by https://github.com/doxygen/doxygen/issues/7698.  Confirmed fixed by\n# doxygen release 1.8.19.\n\nEXCLUDE += \"${Eigen_SOURCE_DIR}/Eigen/src/Core/util/ForwardDeclarations.h\"\n\n# The EXCLUDE_SYMLINKS tag can be used to select whether or not files or\n# directories that are symbolic links (a Unix file system feature) are excluded\n# from the input.\n\nEXCLUDE_SYMLINKS       = NO\n\n# If the value of the INPUT tag contains directories, you can use the\n# EXCLUDE_PATTERNS tag to specify one or more wildcard patterns to exclude\n# certain files from those directories. Note that the wildcards are matched\n# against the file with absolute path, so to exclude all test directories\n# for example use the pattern */test/*\n\nEXCLUDE_PATTERNS       = CMake* \\\n                         *.txt \\\n                         *.sh \\\n                         *.orig \\\n                         *.diff \\\n                         diff \\\n                         *~ \\\n                         *. \\\n                         *.sln \\\n                         *.sdf \\\n                         *.tmp \\\n                         *.vcxproj \\\n                         *.filters \\\n                         *.user \\\n                         *.suo\n\n# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names\n# (namespaces, classes, functions, etc.) that should be excluded from the\n# output. The symbol name can be a fully qualified name, a word, or if the\n# wildcard * is used, a substring. Examples: ANamespace, AClass,\n# AClass::ANamespace, ANamespace::*Test\n\nEXCLUDE_SYMBOLS        = internal::* \\\n                         Flagged* \\\n                         *InnerIterator* \\\n                         DenseStorage<* \\\n                         \n\n# The EXAMPLE_PATH tag can be used to specify one or more files or\n# directories that contain example code fragments that are included (see\n# the \\include command).\n\nEXAMPLE_PATH           = \"${Eigen_SOURCE_DIR}/doc/snippets\" \\\n                         \"${Eigen_BINARY_DIR}/doc/snippets\" \\\n                         \"${Eigen_SOURCE_DIR}/doc/examples\" \\\n                         \"${Eigen_BINARY_DIR}/doc/examples\" \\\n                         \"${Eigen_SOURCE_DIR}/doc/special_examples\" \\\n                         \"${Eigen_BINARY_DIR}/doc/special_examples\" \\\n                         \"${Eigen_SOURCE_DIR}/unsupported/doc/snippets\" \\\n                         \"${Eigen_BINARY_DIR}/unsupported/doc/snippets\" \\\n                         \"${Eigen_SOURCE_DIR}/unsupported/doc/examples\" \\\n                         \"${Eigen_BINARY_DIR}/unsupported/doc/examples\"\n\n# If the value of the EXAMPLE_PATH tag contains directories, you can use the\n# EXAMPLE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp\n# and *.h) to filter out the source-files in the directories. If left\n# blank all files are included.\n\nEXAMPLE_PATTERNS       = *\n\n# If the EXAMPLE_RECURSIVE tag is set to YES then subdirectories will be\n# searched for input files to be used with the \\include or \\dontinclude\n# commands irrespective of the value of the RECURSIVE tag.\n# Possible values are YES and NO. If left blank NO is used.\n\nEXAMPLE_RECURSIVE      = NO\n\n# The IMAGE_PATH tag can be used to specify one or more files or\n# directories that contain image that are included in the documentation (see\n# the \\image command).\n\nIMAGE_PATH             = ${Eigen_BINARY_DIR}/doc/html\n\n# The INPUT_FILTER tag can be used to specify a program that doxygen should\n# invoke to filter for each input file. Doxygen will invoke the filter program\n# by executing (via popen()) the command <filter> <input-file>, where <filter>\n# is the value of the INPUT_FILTER tag, and <input-file> is the name of an\n# input file. Doxygen will then use the output that the filter program writes\n# to standard output.\n# If FILTER_PATTERNS is specified, this tag will be\n# ignored.\n\nINPUT_FILTER           =\n\n# The FILTER_PATTERNS tag can be used to specify filters on a per file pattern\n# basis.\n# Doxygen will compare the file name with each pattern and apply the\n# filter if there is a match.\n# The filters are a list of the form:\n# pattern=filter (like *.cpp=my_cpp_filter). See INPUT_FILTER for further\n# info on how filters are used. If FILTER_PATTERNS is empty or if\n# non of the patterns match the file name, INPUT_FILTER is applied.\n\nFILTER_PATTERNS        =\n\n# If the FILTER_SOURCE_FILES tag is set to YES, the input filter (if set using\n# INPUT_FILTER) will be used to filter the input files when producing source\n# files to browse (i.e. when SOURCE_BROWSER is set to YES).\n\nFILTER_SOURCE_FILES    = NO\n\n# The FILTER_SOURCE_PATTERNS tag can be used to specify source filters per file\n# pattern. A pattern will override the setting for FILTER_PATTERN (if any)\n# and it is also possible to disable source filtering for a specific pattern\n# using *.ext= (so without naming a filter). This option only has effect when\n# FILTER_SOURCE_FILES is enabled.\n\nFILTER_SOURCE_PATTERNS =\n\n#---------------------------------------------------------------------------\n# configuration options related to source browsing\n#---------------------------------------------------------------------------\n\n# If the SOURCE_BROWSER tag is set to YES then a list of source files will\n# be generated. Documented entities will be cross-referenced with these sources.\n# Note: To get rid of all source code in the generated output, make sure also\n# VERBATIM_HEADERS is set to NO.\n\nSOURCE_BROWSER         = NO\n\n# Setting the INLINE_SOURCES tag to YES will include the body\n# of functions and classes directly in the documentation.\n\nINLINE_SOURCES         = NO\n\n# Setting the STRIP_CODE_COMMENTS tag to YES (the default) will instruct\n# doxygen to hide any special comment blocks from generated source code\n# fragments. Normal C, C++ and Fortran comments will always remain visible.\n\nSTRIP_CODE_COMMENTS    = YES\n\n# If the REFERENCED_BY_RELATION tag is set to YES\n# then for each documented function all documented\n# functions referencing it will be listed.\n\nREFERENCED_BY_RELATION = NO\n\n# If the REFERENCES_RELATION tag is set to YES\n# then for each documented function all documented entities\n# called/used by that function will be listed.\n\nREFERENCES_RELATION    = NO\n\n# If the REFERENCES_LINK_SOURCE tag is set to YES (the default)\n# and SOURCE_BROWSER tag is set to YES, then the hyperlinks from\n# functions in REFERENCES_RELATION and REFERENCED_BY_RELATION lists will\n# link to the source code.\n# Otherwise they will link to the documentation.\n\nREFERENCES_LINK_SOURCE = YES\n\n# If the USE_HTAGS tag is set to YES then the references to source code\n# will point to the HTML generated by the htags(1) tool instead of doxygen\n# built-in source browser. The htags tool is part of GNU's global source\n# tagging system (see http://www.gnu.org/software/global/global.html). You\n# will need version 4.8.6 or higher.\n\nUSE_HTAGS              = NO\n\n# If the VERBATIM_HEADERS tag is set to YES (the default) then Doxygen\n# will generate a verbatim copy of the header file for each class for\n# which an include is specified. Set to NO to disable this.\n\nVERBATIM_HEADERS       = YES\n\n#---------------------------------------------------------------------------\n# configuration options related to the alphabetical class index\n#---------------------------------------------------------------------------\n\n# If the ALPHABETICAL_INDEX tag is set to YES, an alphabetical index\n# of all compounds will be generated. Enable this if the project\n# contains a lot of classes, structs, unions or interfaces.\n\nALPHABETICAL_INDEX     = NO\n\n# If the alphabetical index is enabled (see ALPHABETICAL_INDEX) then\n# the COLS_IN_ALPHA_INDEX tag can be used to specify the number of columns\n# in which this list will be split (can be a number in the range [1..20])\n\nCOLS_IN_ALPHA_INDEX    = 5\n\n# In case all classes in a project start with a common prefix, all\n# classes will be put under the same header in the alphabetical index.\n# The IGNORE_PREFIX tag can be used to specify one or more prefixes that\n# should be ignored while generating the index headers.\n\nIGNORE_PREFIX          =\n\n#---------------------------------------------------------------------------\n# configuration options related to the HTML output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_HTML tag is set to YES (the default) Doxygen will\n# generate HTML output.\n\nGENERATE_HTML          = YES\n\n# The HTML_OUTPUT tag is used to specify where the HTML docs will be put.\n# If a relative path is entered the value of OUTPUT_DIRECTORY will be\n# put in front of it. If left blank `html' will be used as the default path.\n\nHTML_OUTPUT            = \"${Eigen_BINARY_DIR}/doc/html${EIGEN_DOXY_OUTPUT_DIRECTORY_SUFFIX}\"\n\n# The HTML_FILE_EXTENSION tag can be used to specify the file extension for\n# each generated HTML page (for example: .htm,.php,.asp). If it is left blank\n# doxygen will generate files with .html extension.\n\nHTML_FILE_EXTENSION    = .html\n\n# The HTML_HEADER tag can be used to specify a personal HTML header for\n# each generated HTML page. If it is left blank doxygen will generate a\n# standard header. Note that when using a custom header you are responsible\n#  for the proper inclusion of any scripts and style sheets that doxygen\n# needs, which is dependent on the configuration options used.\n# It is advised to generate a default header using \"doxygen -w html\n# header.html footer.html stylesheet.css YourConfigFile\" and then modify\n# that header. Note that the header is subject to change so you typically\n# have to redo this when upgrading to a newer version of doxygen or when\n# changing the value of configuration settings such as GENERATE_TREEVIEW!\n\nHTML_HEADER            = \"${Eigen_BINARY_DIR}/doc/eigendoxy_header.html\"\n\n# The HTML_FOOTER tag can be used to specify a personal HTML footer for\n# each generated HTML page. If it is left blank doxygen will generate a\n# standard footer.\n\nHTML_FOOTER            = \"${Eigen_BINARY_DIR}/doc/eigendoxy_footer.html\"\n\n# The HTML_STYLESHEET tag can be used to specify a user-defined cascading\n# style sheet that is used by each HTML page. It can be used to\n# fine-tune the look of the HTML output. If the tag is left blank doxygen\n# will generate a default style sheet. Note that doxygen will try to copy\n# the style sheet file to the HTML output directory, so don't put your own\n# style sheet in the HTML output directory as well, or it will be erased!\n\nHTML_STYLESHEET        = \n\n# The HTML_EXTRA_FILES tag can be used to specify one or more extra images or\n# other source files which should be copied to the HTML output directory. Note\n# that these files will be copied to the base HTML output directory. Use the\n# $relpath$ marker in the HTML_HEADER and/or HTML_FOOTER files to load these\n# files. In the HTML_STYLESHEET file, use the file name only. Also note that\n# the files will be copied as-is; there are no commands or markers available.\n\nHTML_EXTRA_FILES       = \"${Eigen_SOURCE_DIR}/doc/eigendoxy.css\"\n\n# The HTML_COLORSTYLE_HUE tag controls the color of the HTML output.\n# Doxygen will adjust the colors in the style sheet and background images\n# according to this color. Hue is specified as an angle on a colorwheel,\n# see http://en.wikipedia.org/wiki/Hue for more information.\n# For instance the value 0 represents red, 60 is yellow, 120 is green,\n# 180 is cyan, 240 is blue, 300 purple, and 360 is red again.\n# The allowed range is 0 to 359.\n# The default is 220.\n\nHTML_COLORSTYLE_HUE    = ${EIGEN_DOXY_HTML_COLORSTYLE_HUE}\n\n# The HTML_COLORSTYLE_SAT tag controls the purity (or saturation) of\n# the colors in the HTML output. For a value of 0 the output will use\n# grayscales only. A value of 255 will produce the most vivid colors.\n\nHTML_COLORSTYLE_SAT    = 100\n\n# The HTML_COLORSTYLE_GAMMA tag controls the gamma correction applied to\n# the luminance component of the colors in the HTML output. Values below\n# 100 gradually make the output lighter, whereas values above 100 make\n# the output darker. The value divided by 100 is the actual gamma applied,\n# so 80 represents a gamma of 0.8, The value 220 represents a gamma of 2.2,\n# and 100 does not change the gamma.\n\nHTML_COLORSTYLE_GAMMA  = 80\n\n# If the HTML_TIMESTAMP tag is set to YES then the footer of each generated HTML\n# page will contain the date and time when the page was generated. Setting\n# this to NO can help when comparing the output of multiple runs.\n\nHTML_TIMESTAMP         = YES\n\n# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML\n# documentation will contain sections that can be hidden and shown after the\n# page has loaded.\n\nHTML_DYNAMIC_SECTIONS  = YES\n\n# With HTML_INDEX_NUM_ENTRIES one can control the preferred number of\n# entries shown in the various tree structured indices initially; the user\n# can expand and collapse entries dynamically later on. Doxygen will expand\n# the tree to such a level that at most the specified number of entries are\n# visible (unless a fully collapsed tree already exceeds this amount).\n# So setting the number of entries 1 will produce a full collapsed tree by\n# default. 0 is a special value representing an infinite number of entries\n# and will result in a full expanded tree by default.\n\nHTML_INDEX_NUM_ENTRIES = 100\n\n# If the GENERATE_DOCSET tag is set to YES, additional index files\n# will be generated that can be used as input for Apple's Xcode 3\n# integrated development environment, introduced with OSX 10.5 (Leopard).\n# To create a documentation set, doxygen will generate a Makefile in the\n# HTML output directory. Running make will produce the docset in that\n# directory and running \"make install\" will install the docset in\n# ~/Library/Developer/Shared/Documentation/DocSets so that Xcode will find\n# it at startup.\n# See http://developer.apple.com/tools/creatingdocsetswithdoxygen.html\n# for more information.\n\nGENERATE_DOCSET        = NO\n\n# When GENERATE_DOCSET tag is set to YES, this tag determines the name of the\n# feed. A documentation feed provides an umbrella under which multiple\n# documentation sets from a single provider (such as a company or product suite)\n# can be grouped.\n\nDOCSET_FEEDNAME        = \"Doxygen generated docs\"\n\n# When GENERATE_DOCSET tag is set to YES, this tag specifies a string that\n# should uniquely identify the documentation set bundle. This should be a\n# reverse domain-name style string, e.g. com.mycompany.MyDocSet. Doxygen\n# will append .docset to the name.\n\nDOCSET_BUNDLE_ID       = org.doxygen.Project\n\n# When GENERATE_PUBLISHER_ID tag specifies a string that should uniquely identify\n# the documentation publisher. This should be a reverse domain-name style\n# string, e.g. com.mycompany.MyDocSet.documentation.\n\nDOCSET_PUBLISHER_ID    = org.doxygen.Publisher\n\n# The GENERATE_PUBLISHER_NAME tag identifies the documentation publisher.\n\nDOCSET_PUBLISHER_NAME  = Publisher\n\n# If the GENERATE_HTMLHELP tag is set to YES, additional index files\n# will be generated that can be used as input for tools like the\n# Microsoft HTML help workshop to generate a compiled HTML help file (.chm)\n# of the generated HTML documentation.\n\nGENERATE_HTMLHELP      = NO\n\n# If the GENERATE_HTMLHELP tag is set to YES, the CHM_FILE tag can\n# be used to specify the file name of the resulting .chm file. You\n# can add a path in front of the file if the result should not be\n# written to the html output directory.\n\nCHM_FILE               =\n\n# If the GENERATE_HTMLHELP tag is set to YES, the HHC_LOCATION tag can\n# be used to specify the location (absolute path including file name) of\n# the HTML help compiler (hhc.exe). If non-empty doxygen will try to run\n# the HTML help compiler on the generated index.hhp.\n\nHHC_LOCATION           =\n\n# If the GENERATE_HTMLHELP tag is set to YES, the GENERATE_CHI flag\n# controls if a separate .chi index file is generated (YES) or that\n# it should be included in the master .chm file (NO).\n\nGENERATE_CHI           = NO\n\n# If the GENERATE_HTMLHELP tag is set to YES, the CHM_INDEX_ENCODING\n# is used to encode HtmlHelp index (hhk), content (hhc) and project file\n# content.\n\nCHM_INDEX_ENCODING     =\n\n# If the GENERATE_HTMLHELP tag is set to YES, the BINARY_TOC flag\n# controls whether a binary table of contents is generated (YES) or a\n# normal table of contents (NO) in the .chm file.\n\nBINARY_TOC             = NO\n\n# The TOC_EXPAND flag can be set to YES to add extra items for group members\n# to the contents of the HTML help documentation and to the tree view.\n\nTOC_EXPAND             = NO\n\n# If the GENERATE_QHP tag is set to YES and both QHP_NAMESPACE and\n# QHP_VIRTUAL_FOLDER are set, an additional index file will be generated\n# that can be used as input for Qt's qhelpgenerator to generate a\n# Qt Compressed Help (.qch) of the generated HTML documentation.\n\nGENERATE_QHP           = NO\n\n# If the QHG_LOCATION tag is specified, the QCH_FILE tag can\n# be used to specify the file name of the resulting .qch file.\n# The path specified is relative to the HTML output folder.\n\nQCH_FILE               =\n\n# The QHP_NAMESPACE tag specifies the namespace to use when generating\n# Qt Help Project output. For more information please see\n# http://doc.trolltech.com/qthelpproject.html#namespace\n\nQHP_NAMESPACE          = org.doxygen.Project\n\n# The QHP_VIRTUAL_FOLDER tag specifies the namespace to use when generating\n# Qt Help Project output. For more information please see\n# http://doc.trolltech.com/qthelpproject.html#virtual-folders\n\nQHP_VIRTUAL_FOLDER     = doc\n\n# If QHP_CUST_FILTER_NAME is set, it specifies the name of a custom filter to\n# add. For more information please see\n# http://doc.trolltech.com/qthelpproject.html#custom-filters\n\nQHP_CUST_FILTER_NAME   =\n\n# The QHP_CUST_FILT_ATTRS tag specifies the list of the attributes of the\n# custom filter to add. For more information please see\n# <a href=\"http://doc.trolltech.com/qthelpproject.html#custom-filters\">\n# Qt Help Project / Custom Filters</a>.\n\nQHP_CUST_FILTER_ATTRS  =\n\n# The QHP_SECT_FILTER_ATTRS tag specifies the list of the attributes this\n# project's\n# filter section matches.\n# <a href=\"http://doc.trolltech.com/qthelpproject.html#filter-attributes\">\n# Qt Help Project / Filter Attributes</a>.\n\nQHP_SECT_FILTER_ATTRS  =\n\n# If the GENERATE_QHP tag is set to YES, the QHG_LOCATION tag can\n# be used to specify the location of Qt's qhelpgenerator.\n# If non-empty doxygen will try to run qhelpgenerator on the generated\n# .qhp file.\n\nQHG_LOCATION           =\n\n# If the GENERATE_ECLIPSEHELP tag is set to YES, additional index files\n#  will be generated, which together with the HTML files, form an Eclipse help\n# plugin. To install this plugin and make it available under the help contents\n# menu in Eclipse, the contents of the directory containing the HTML and XML\n# files needs to be copied into the plugins directory of eclipse. The name of\n# the directory within the plugins directory should be the same as\n# the ECLIPSE_DOC_ID value. After copying Eclipse needs to be restarted before\n# the help appears.\n\nGENERATE_ECLIPSEHELP   = NO\n\n# A unique identifier for the eclipse help plugin. When installing the plugin\n# the directory name containing the HTML and XML files should also have\n# this name.\n\nECLIPSE_DOC_ID         = org.doxygen.Project\n\n# The DISABLE_INDEX tag can be used to turn on/off the condensed index (tabs)\n# at top of each HTML page. The value NO (the default) enables the index and\n# the value YES disables it. Since the tabs have the same information as the\n# navigation tree you can set this option to NO if you already set\n# GENERATE_TREEVIEW to YES.\n\nDISABLE_INDEX          = YES\n\n# The GENERATE_TREEVIEW tag is used to specify whether a tree-like index\n# structure should be generated to display hierarchical information.\n# If the tag value is set to YES, a side panel will be generated\n# containing a tree-like index structure (just like the one that\n# is generated for HTML Help). For this to work a browser that supports\n# JavaScript, DHTML, CSS and frames is required (i.e. any modern browser).\n# Windows users are probably better off using the HTML help feature.\n# Since the tree basically has the same information as the tab index you\n# could consider to set DISABLE_INDEX to NO when enabling this option.\n\nGENERATE_TREEVIEW      = YES\n\n# The ENUM_VALUES_PER_LINE tag can be used to set the number of enum values\n# (range [0,1..20]) that doxygen will group on one line in the generated HTML\n# documentation. Note that a value of 0 will completely suppress the enum\n# values from appearing in the overview section.\n\nENUM_VALUES_PER_LINE   = 1\n\n# If the treeview is enabled (see GENERATE_TREEVIEW) then this tag can be\n# used to set the initial width (in pixels) of the frame in which the tree\n# is shown.\n\nTREEVIEW_WIDTH         = 250\n\n# When the EXT_LINKS_IN_WINDOW option is set to YES doxygen will open\n# links to external symbols imported via tag files in a separate window.\n\nEXT_LINKS_IN_WINDOW    = NO\n\n# Use this tag to change the font size of Latex formulas included\n# as images in the HTML documentation. The default is 10. Note that\n# when you change the font size after a successful doxygen run you need\n# to manually remove any form_*.png images from the HTML output directory\n# to force them to be regenerated.\n\nFORMULA_FONTSIZE       = 12\n\n# Use the FORMULA_TRANPARENT tag to determine whether or not the images\n# generated for formulas are transparent PNGs. Transparent PNGs are\n# not supported properly for IE 6.0, but are supported on all modern browsers.\n# Note that when changing this option you need to delete any form_*.png files\n# in the HTML output before the changes have effect.\n\nFORMULA_TRANSPARENT    = YES\n\n# Enable the USE_MATHJAX option to render LaTeX formulas using MathJax\n# (see http://www.mathjax.org) which uses client side Javascript for the\n# rendering instead of using prerendered bitmaps. Use this if you do not\n# have LaTeX installed or if you want to formulas look prettier in the HTML\n# output. When enabled you may also need to install MathJax separately and\n# configure the path to it using the MATHJAX_RELPATH option.\n\nUSE_MATHJAX            = @EIGEN_DOXY_USE_MATHJAX@\n\n# When MathJax is enabled you need to specify the location relative to the\n# HTML output directory using the MATHJAX_RELPATH option. The destination\n# directory should contain the MathJax.js script. For instance, if the mathjax\n# directory is located at the same level as the HTML output directory, then\n# MATHJAX_RELPATH should be ../mathjax. The default value points to\n# the MathJax Content Delivery Network so you can quickly see the result without\n# installing MathJax.\n# However, it is strongly recommended to install a local\n# copy of MathJax from http://www.mathjax.org before deployment.\n\nMATHJAX_RELPATH        = https://cdn.mathjax.org/mathjax/latest\n\n# The MATHJAX_EXTENSIONS tag can be used to specify one or MathJax extension\n# names that should be enabled during MathJax rendering.\n\nMATHJAX_EXTENSIONS     = TeX/AMSmath TeX/AMSsymbols\n\n# When the SEARCHENGINE tag is enabled doxygen will generate a search box\n# for the HTML output. The underlying search engine uses javascript\n# and DHTML and should work on any modern browser. Note that when using\n# HTML help (GENERATE_HTMLHELP), Qt help (GENERATE_QHP), or docsets\n# (GENERATE_DOCSET) there is already a search function so this one should\n# typically be disabled. For large projects the javascript based search engine\n# can be slow, then enabling SERVER_BASED_SEARCH may provide a better solution.\n\nSEARCHENGINE           = YES\n\n# When the SERVER_BASED_SEARCH tag is enabled the search engine will be\n# implemented using a PHP enabled web server instead of at the web client\n# using Javascript. Doxygen will generate the search PHP script and index\n# file to put on the web server. The advantage of the server\n# based approach is that it scales better to large projects and allows\n# full text search. The disadvantages are that it is more difficult to setup\n# and does not have live searching capabilities.\n\nSERVER_BASED_SEARCH    = NO\n\n#---------------------------------------------------------------------------\n# configuration options related to the LaTeX output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_LATEX tag is set to YES (the default) Doxygen will\n# generate Latex output.\n\nGENERATE_LATEX         = NO\n\n# The LATEX_OUTPUT tag is used to specify where the LaTeX docs will be put.\n# If a relative path is entered the value of OUTPUT_DIRECTORY will be\n# put in front of it. If left blank `latex' will be used as the default path.\n\nLATEX_OUTPUT           = latex\n\n# The LATEX_CMD_NAME tag can be used to specify the LaTeX command name to be\n# invoked. If left blank `latex' will be used as the default command name.\n# Note that when enabling USE_PDFLATEX this option is only used for\n# generating bitmaps for formulas in the HTML output, but not in the\n# Makefile that is written to the output directory.\n\nLATEX_CMD_NAME         = latex\n\n# The MAKEINDEX_CMD_NAME tag can be used to specify the command name to\n# generate index for LaTeX. If left blank `makeindex' will be used as the\n# default command name.\n\nMAKEINDEX_CMD_NAME     = makeindex\n\n# If the COMPACT_LATEX tag is set to YES Doxygen generates more compact\n# LaTeX documents. This may be useful for small projects and may help to\n# save some trees in general.\n\nCOMPACT_LATEX          = NO\n\n# The PAPER_TYPE tag can be used to set the paper type that is used\n# by the printer. Possible values are: a4, letter, legal and\n# executive. If left blank a4wide will be used.\n\nPAPER_TYPE             = a4wide\n\n# The EXTRA_PACKAGES tag can be to specify one or more names of LaTeX\n# packages that should be included in the LaTeX output.\n\nEXTRA_PACKAGES         = amssymb \\\n                         amsmath\n\n# The LATEX_HEADER tag can be used to specify a personal LaTeX header for\n# the generated latex document. The header should contain everything until\n# the first chapter. If it is left blank doxygen will generate a\n# standard header. Notice: only use this tag if you know what you are doing!\n\nLATEX_HEADER           =\n\n# The LATEX_FOOTER tag can be used to specify a personal LaTeX footer for\n# the generated latex document. The footer should contain everything after\n# the last chapter. If it is left blank doxygen will generate a\n# standard footer. Notice: only use this tag if you know what you are doing!\n\nLATEX_FOOTER           =\n\n# If the PDF_HYPERLINKS tag is set to YES, the LaTeX that is generated\n# is prepared for conversion to pdf (using ps2pdf). The pdf file will\n# contain links (just like the HTML output) instead of page references\n# This makes the output suitable for online browsing using a pdf viewer.\n\nPDF_HYPERLINKS         = NO\n\n# If the USE_PDFLATEX tag is set to YES, pdflatex will be used instead of\n# plain latex in the generated Makefile. Set this option to YES to get a\n# higher quality PDF documentation.\n\nUSE_PDFLATEX           = NO\n\n# If the LATEX_BATCHMODE tag is set to YES, doxygen will add the \\\\batchmode.\n# command to the generated LaTeX files. This will instruct LaTeX to keep\n# running if errors occur, instead of asking the user for help.\n# This option is also used when generating formulas in HTML.\n\nLATEX_BATCHMODE        = NO\n\n# If LATEX_HIDE_INDICES is set to YES then doxygen will not\n# include the index chapters (such as File Index, Compound Index, etc.)\n# in the output.\n\nLATEX_HIDE_INDICES     = NO\n\n# If LATEX_SOURCE_CODE is set to YES then doxygen will include\n# source code with syntax highlighting in the LaTeX output.\n# Note that which sources are shown also depends on other settings\n# such as SOURCE_BROWSER.\n\nLATEX_SOURCE_CODE      = NO\n\n# The LATEX_BIB_STYLE tag can be used to specify the style to use for the\n# bibliography, e.g. plainnat, or ieeetr. The default style is \"plain\". See\n# http://en.wikipedia.org/wiki/BibTeX for more info.\n\nLATEX_BIB_STYLE        = plain\n\n#---------------------------------------------------------------------------\n# configuration options related to the RTF output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_RTF tag is set to YES Doxygen will generate RTF output\n# The RTF output is optimized for Word 97 and may not look very pretty with\n# other RTF readers or editors.\n\nGENERATE_RTF           = NO\n\n# The RTF_OUTPUT tag is used to specify where the RTF docs will be put.\n# If a relative path is entered the value of OUTPUT_DIRECTORY will be\n# put in front of it. If left blank `rtf' will be used as the default path.\n\nRTF_OUTPUT             = rtf\n\n# If the COMPACT_RTF tag is set to YES Doxygen generates more compact\n# RTF documents. This may be useful for small projects and may help to\n# save some trees in general.\n\nCOMPACT_RTF            = NO\n\n# If the RTF_HYPERLINKS tag is set to YES, the RTF that is generated\n# will contain hyperlink fields. The RTF file will\n# contain links (just like the HTML output) instead of page references.\n# This makes the output suitable for online browsing using WORD or other\n# programs which support those fields.\n# Note: wordpad (write) and others do not support links.\n\nRTF_HYPERLINKS         = NO\n\n# Load style sheet definitions from file. Syntax is similar to doxygen's\n# config file, i.e. a series of assignments. You only have to provide\n# replacements, missing definitions are set to their default value.\n\nRTF_STYLESHEET_FILE    =\n\n# Set optional variables used in the generation of an rtf document.\n# Syntax is similar to doxygen's config file.\n\nRTF_EXTENSIONS_FILE    =\n\n#---------------------------------------------------------------------------\n# configuration options related to the man page output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_MAN tag is set to YES (the default) Doxygen will\n# generate man pages\n\nGENERATE_MAN           = NO\n\n# The MAN_OUTPUT tag is used to specify where the man pages will be put.\n# If a relative path is entered the value of OUTPUT_DIRECTORY will be\n# put in front of it. If left blank `man' will be used as the default path.\n\nMAN_OUTPUT             = man\n\n# The MAN_EXTENSION tag determines the extension that is added to\n# the generated man pages (default is the subroutine's section .3)\n\nMAN_EXTENSION          = .3\n\n# If the MAN_LINKS tag is set to YES and Doxygen generates man output,\n# then it will generate one additional man file for each entity\n# documented in the real man page(s). These additional files\n# only source the real man page, but without them the man command\n# would be unable to find the correct page. The default is NO.\n\nMAN_LINKS              = NO\n\n#---------------------------------------------------------------------------\n# configuration options related to the XML output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_XML tag is set to YES Doxygen will\n# generate an XML file that captures the structure of\n# the code including all documentation.\n\nGENERATE_XML           = NO\n\n# The XML_OUTPUT tag is used to specify where the XML pages will be put.\n# If a relative path is entered the value of OUTPUT_DIRECTORY will be\n# put in front of it. If left blank `xml' will be used as the default path.\n\nXML_OUTPUT             = xml\n\n# The XML_SCHEMA tag can be used to specify an XML schema,\n# which can be used by a validating XML parser to check the\n# syntax of the XML files.\n\n# XML_SCHEMA             =\n\n# The XML_DTD tag can be used to specify an XML DTD,\n# which can be used by a validating XML parser to check the\n# syntax of the XML files.\n\n# XML_DTD                =\n\n# If the XML_PROGRAMLISTING tag is set to YES Doxygen will\n# dump the program listings (including syntax highlighting\n# and cross-referencing information) to the XML output. Note that\n# enabling this will significantly increase the size of the XML output.\n\nXML_PROGRAMLISTING     = YES\n\n#---------------------------------------------------------------------------\n# configuration options for the AutoGen Definitions output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_AUTOGEN_DEF tag is set to YES Doxygen will\n# generate an AutoGen Definitions (see autogen.sf.net) file\n# that captures the structure of the code including all\n# documentation. Note that this feature is still experimental\n# and incomplete at the moment.\n\nGENERATE_AUTOGEN_DEF   = NO\n\n#---------------------------------------------------------------------------\n# configuration options related to the Perl module output\n#---------------------------------------------------------------------------\n\n# If the GENERATE_PERLMOD tag is set to YES Doxygen will\n# generate a Perl module file that captures the structure of\n# the code including all documentation. Note that this\n# feature is still experimental and incomplete at the\n# moment.\n\nGENERATE_PERLMOD       = NO\n\n# If the PERLMOD_LATEX tag is set to YES Doxygen will generate\n# the necessary Makefile rules, Perl scripts and LaTeX code to be able\n# to generate PDF and DVI output from the Perl module output.\n\nPERLMOD_LATEX          = NO\n\n# If the PERLMOD_PRETTY tag is set to YES the Perl module output will be\n# nicely formatted so it can be parsed by a human reader.\n# This is useful\n# if you want to understand what is going on.\n# On the other hand, if this\n# tag is set to NO the size of the Perl module output will be much smaller\n# and Perl will parse it just the same.\n\nPERLMOD_PRETTY         = YES\n\n# The names of the make variables in the generated doxyrules.make file\n# are prefixed with the string contained in PERLMOD_MAKEVAR_PREFIX.\n# This is useful so different doxyrules.make files included by the same\n# Makefile don't overwrite each other's variables.\n\nPERLMOD_MAKEVAR_PREFIX =\n\n#---------------------------------------------------------------------------\n# Configuration options related to the preprocessor\n#---------------------------------------------------------------------------\n\n# If the ENABLE_PREPROCESSING tag is set to YES (the default) Doxygen will\n# evaluate all C-preprocessor directives found in the sources and include\n# files.\n\nENABLE_PREPROCESSING   = YES\n\n# If the MACRO_EXPANSION tag is set to YES Doxygen will expand all macro\n# names in the source code. If set to NO (the default) only conditional\n# compilation will be performed. Macro expansion can be done in a controlled\n# way by setting EXPAND_ONLY_PREDEF to YES.\n\nMACRO_EXPANSION        = YES\n\n# If the EXPAND_ONLY_PREDEF and MACRO_EXPANSION tags are both set to YES\n# then the macro expansion is limited to the macros specified with the\n# PREDEFINED and EXPAND_AS_DEFINED tags.\n\nEXPAND_ONLY_PREDEF     = YES\n\n# If the SEARCH_INCLUDES tag is set to YES (the default) the includes files\n# pointed to by INCLUDE_PATH will be searched when a #include is found.\n\nSEARCH_INCLUDES        = YES\n\n# The INCLUDE_PATH tag can be used to specify one or more directories that\n# contain include files that are not input files but should be processed by\n# the preprocessor.\n\nINCLUDE_PATH           = \"${Eigen_SOURCE_DIR}/Eigen/src/plugins\"\n\n# You can use the INCLUDE_FILE_PATTERNS tag to specify one or more wildcard\n# patterns (like *.h and *.hpp) to filter out the header-files in the\n# directories. If left blank, the patterns specified with FILE_PATTERNS will\n# be used.\n\nINCLUDE_FILE_PATTERNS  =\n\n# The PREDEFINED tag can be used to specify one or more macro names that\n# are defined before the preprocessor is started (similar to the -D option of\n# gcc). The argument of the tag is a list of macros of the form: name\n# or name=definition (no spaces). If the definition and the = are\n# omitted =1 is assumed. To prevent a macro definition from being\n# undefined via #undef or recursively expanded use the := operator\n# instead of the = operator.\n\nPREDEFINED             = EIGEN_EMPTY_STRUCT \\\n                         EIGEN_PARSED_BY_DOXYGEN \\\n                         EIGEN_VECTORIZE \\\n                         EIGEN_QT_SUPPORT \\\n                         EIGEN_STRONG_INLINE=inline \\\n                         EIGEN_DEVICE_FUNC= \\\n                         EIGEN_HAS_CXX11=1 \\\n                         EIGEN_HAS_CXX11_MATH=1 \\\n                         \"EIGEN_MAKE_CWISE_BINARY_OP(METHOD,FUNCTOR)=template<typename OtherDerived> const CwiseBinaryOp<FUNCTOR<Scalar>, const Derived, const OtherDerived> METHOD(const EIGEN_CURRENT_STORAGE_BASE_CLASS<OtherDerived> &other) const;\" \\\n                         \"EIGEN_CWISE_PRODUCT_RETURN_TYPE(LHS,RHS)=CwiseBinaryOp<internal::scalar_product_op<LHS::Scalar,RHS::Scalar>, const LHS, const RHS>\"\\\n                         \"EIGEN_CAT2(a,b)= a ## b\"\\\n                         \"EIGEN_CAT(a,b)=EIGEN_CAT2(a,b)\"\\\n                         \"EIGEN_CWISE_BINARY_RETURN_TYPE(LHS,RHS,OPNAME)=CwiseBinaryOp<EIGEN_CAT(EIGEN_CAT(internal::scalar_,OPNAME),_op)<LHS::Scalar, RHS::Scalar>, const LHS, const RHS>\"\\\n                         \"EIGEN_ALIGN_TO_BOUNDARY(x)=\"\\\n                         DOXCOMMA=,\n\n\n# If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then\n# this tag can be used to specify a list of macro names that should be expanded.\n# The macro definition that is found in the sources will be used.\n# Use the PREDEFINED tag if you want to use a different macro definition that\n# overrules the definition found in the source code.\n\nEXPAND_AS_DEFINED      = EIGEN_MAKE_TYPEDEFS \\\n                         EIGEN_MAKE_FIXED_TYPEDEFS \\\n                         EIGEN_MAKE_TYPEDEFS_ALL_SIZES \\\n                         EIGEN_MAKE_ARRAY_TYPEDEFS \\\n                         EIGEN_MAKE_ARRAY_FIXED_TYPEDEFS \\\n                         EIGEN_MAKE_ARRAY_TYPEDEFS_ALL_SIZES \\\n                         EIGEN_CWISE_UNOP_RETURN_TYPE \\\n                         EIGEN_CWISE_BINOP_RETURN_TYPE \\\n                         EIGEN_CURRENT_STORAGE_BASE_CLASS \\\n                         EIGEN_MATHFUNC_IMPL \\\n                         _EIGEN_GENERIC_PUBLIC_INTERFACE \\\n                         EIGEN_ARRAY_DECLARE_GLOBAL_UNARY \\\n                         EIGEN_EMPTY \\\n                         EIGEN_EULER_ANGLES_TYPEDEFS \\\n                         EIGEN_EULER_ANGLES_SINGLE_TYPEDEF \\\n                         EIGEN_EULER_SYSTEM_TYPEDEF \\\n                         EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY \\\n                         EIGEN_MATRIX_FUNCTION \\\n                         EIGEN_MATRIX_FUNCTION_1 \\\n                         EIGEN_DOC_UNARY_ADDONS \\\n                         EIGEN_DOC_BLOCK_ADDONS_NOT_INNER_PANEL \\\n                         EIGEN_DOC_BLOCK_ADDONS_INNER_PANEL_IF\n\n\n# If the SKIP_FUNCTION_MACROS tag is set to YES (the default) then\n# doxygen's preprocessor will remove all references to function-like macros\n# that are alone on a line, have an all uppercase name, and do not end with a\n# semicolon, because these will confuse the parser if not removed.\n\nSKIP_FUNCTION_MACROS   = YES\n\n#---------------------------------------------------------------------------\n# Configuration::additions related to external references\n#---------------------------------------------------------------------------\n\n# The TAGFILES option can be used to specify one or more tagfiles. For each\n# tag file the location of the external documentation should be added. The\n# format of a tag file without this location is as follows:\n#\n# TAGFILES = file1 file2 ...\n# Adding location for the tag files is done as follows:\n#\n# TAGFILES = file1=loc1 \"file2 = loc2\" ...\n# where \"loc1\" and \"loc2\" can be relative or absolute paths\n# or URLs. Note that each tag file must have a unique name (where the name does\n# NOT include the path). If a tag file is not located in the directory in which\n# doxygen is run, you must also specify the path to the tagfile here.\n\nTAGFILES               = ${EIGEN_DOXY_TAGFILES}\n# \"${Eigen_BINARY_DIR}/doc/eigen-unsupported.doxytags =unsupported\"\n\n# When a file name is specified after GENERATE_TAGFILE, doxygen will create\n# a tag file that is based on the input files it reads.\n\nGENERATE_TAGFILE       = \"${Eigen_BINARY_DIR}/doc/${EIGEN_DOXY_PROJECT_NAME}.doxytags\"\n\n# If the ALLEXTERNALS tag is set to YES all external classes will be listed\n# in the class index. If set to NO only the inherited external classes\n# will be listed.\n\nALLEXTERNALS           = NO\n\n# If the EXTERNAL_GROUPS tag is set to YES all external groups will be listed\n# in the modules index. If set to NO, only the current project's groups will\n# be listed.\n\nEXTERNAL_GROUPS        = NO\n\n# The PERL_PATH should be the absolute path and name of the perl script\n# interpreter (i.e. the result of `which perl').\n\nPERL_PATH              = /usr/bin/perl\n\n#---------------------------------------------------------------------------\n# Configuration options related to the dot tool\n#---------------------------------------------------------------------------\n\n# If the CLASS_DIAGRAMS tag is set to YES (the default) Doxygen will\n# generate a inheritance diagram (in HTML, RTF and LaTeX) for classes with base\n# or super classes. Setting the tag to NO turns the diagrams off. Note that\n# this option also works with HAVE_DOT disabled, but it is recommended to\n# install and use dot, since it yields more powerful graphs.\n\nCLASS_DIAGRAMS         = YES\n\n# You can define message sequence charts within doxygen comments using the \\msc\n# command. Doxygen will then run the mscgen tool (see\n# http://www.mcternan.me.uk/mscgen/) to produce the chart and insert it in the\n# documentation. The MSCGEN_PATH tag allows you to specify the directory where\n# the mscgen tool resides. If left empty the tool is assumed to be found in the\n# default search path.\n\nMSCGEN_PATH            =\n\n# If set to YES, the inheritance and collaboration graphs will hide\n# inheritance and usage relations if the target is undocumented\n# or is not a class.\n\nHIDE_UNDOC_RELATIONS   = NO\n\n# If you set the HAVE_DOT tag to YES then doxygen will assume the dot tool is\n# available from the path. This tool is part of Graphviz, a graph visualization\n# toolkit from AT&T and Lucent Bell Labs. The other options in this section\n# have no effect if this option is set to NO (the default)\n\nHAVE_DOT               = YES\n\n# The DOT_NUM_THREADS specifies the number of dot invocations doxygen is\n# allowed to run in parallel. When set to 0 (the default) doxygen will\n# base this on the number of processors available in the system. You can set it\n# explicitly to a value larger than 0 to get control over the balance\n# between CPU load and processing speed.\n\nDOT_NUM_THREADS        = 0\n\n# By default doxygen will use the Helvetica font for all dot files that\n# doxygen generates. When you want a differently looking font you can specify\n# the font name using DOT_FONTNAME. You need to make sure dot is able to find\n# the font, which can be done by putting it in a standard location or by setting\n# the DOTFONTPATH environment variable or by setting DOT_FONTPATH to the\n# directory containing the font.\n\nDOT_FONTNAME           = \n\n# The DOT_FONTSIZE tag can be used to set the size of the font of dot graphs.\n# The default size is 10pt.\n\nDOT_FONTSIZE           = 10\n\n# By default doxygen will tell dot to use the Helvetica font.\n# If you specify a different font using DOT_FONTNAME you can use DOT_FONTPATH to\n# set the path where dot can find it.\n\nDOT_FONTPATH           =\n\n# If the CLASS_GRAPH and HAVE_DOT tags are set to YES then doxygen\n# will generate a graph for each documented class showing the direct and\n# indirect inheritance relations. Setting this tag to YES will force the\n# CLASS_DIAGRAMS tag to NO.\n\nCLASS_GRAPH            = YES\n\n# If the COLLABORATION_GRAPH and HAVE_DOT tags are set to YES then doxygen\n# will generate a graph for each documented class showing the direct and\n# indirect implementation dependencies (inheritance, containment, and\n# class references variables) of the class with other documented classes.\n\nCOLLABORATION_GRAPH    = NO\n\n# If the GROUP_GRAPHS and HAVE_DOT tags are set to YES then doxygen\n# will generate a graph for groups, showing the direct groups dependencies\n\nGROUP_GRAPHS           = NO\n\n# If the UML_LOOK tag is set to YES doxygen will generate inheritance and\n# collaboration diagrams in a style similar to the OMG's Unified Modeling\n# Language.\n\nUML_LOOK               = YES\n\n# If the UML_LOOK tag is enabled, the fields and methods are shown inside\n# the class node. If there are many fields or methods and many nodes the\n# graph may become too big to be useful. The UML_LIMIT_NUM_FIELDS\n# threshold limits the number of items for each type to make the size more\n# manageable. Set this to 0 for no limit. Note that the threshold may be\n# exceeded by 50% before the limit is enforced.\n\nUML_LIMIT_NUM_FIELDS   = 10\n\n# If set to YES, the inheritance and collaboration graphs will show the\n# relations between templates and their instances.\n\nTEMPLATE_RELATIONS     = NO\n\n# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDE_GRAPH, and HAVE_DOT\n# tags are set to YES then doxygen will generate a graph for each documented\n# file showing the direct and indirect include dependencies of the file with\n# other documented files.\n\nINCLUDE_GRAPH          = NO\n\n# If the ENABLE_PREPROCESSING, SEARCH_INCLUDES, INCLUDED_BY_GRAPH, and\n# HAVE_DOT tags are set to YES then doxygen will generate a graph for each\n# documented header file showing the documented files that directly or\n# indirectly include this file.\n\nINCLUDED_BY_GRAPH      = NO\n\n# If the CALL_GRAPH and HAVE_DOT options are set to YES then\n# doxygen will generate a call dependency graph for every global function\n# or class method. Note that enabling this option will significantly increase\n# the time of a run. So in most cases it will be better to enable call graphs\n# for selected functions only using the \\callgraph command.\n\nCALL_GRAPH             = NO\n\n# If the CALLER_GRAPH and HAVE_DOT tags are set to YES then\n# doxygen will generate a caller dependency graph for every global function\n# or class method. Note that enabling this option will significantly increase\n# the time of a run. So in most cases it will be better to enable caller\n# graphs for selected functions only using the \\callergraph command.\n\nCALLER_GRAPH           = NO\n\n# If the GRAPHICAL_HIERARCHY and HAVE_DOT tags are set to YES then doxygen\n# will generate a graphical hierarchy of all classes instead of a textual one.\n\nGRAPHICAL_HIERARCHY    = NO\n\n# If the DIRECTORY_GRAPH and HAVE_DOT tags are set to YES\n# then doxygen will show the dependencies a directory has on other directories\n# in a graphical way. The dependency relations are determined by the #include\n# relations between the files in the directories.\n\nDIRECTORY_GRAPH        = NO\n\n# The DOT_IMAGE_FORMAT tag can be used to set the image format of the images\n# generated by dot. Possible values are svg, png, jpg, or gif.\n# If left blank png will be used. If you choose svg you need to set\n# HTML_FILE_EXTENSION to xhtml in order to make the SVG files\n# visible in IE 9+ (other browsers do not have this requirement).\n\nDOT_IMAGE_FORMAT       = png\n\n# If DOT_IMAGE_FORMAT is set to svg, then this option can be set to YES to\n# enable generation of interactive SVG images that allow zooming and panning.\n# Note that this requires a modern browser other than Internet Explorer.\n# Tested and working are Firefox, Chrome, Safari, and Opera. For IE 9+ you\n# need to set HTML_FILE_EXTENSION to xhtml in order to make the SVG files\n# visible. Older versions of IE do not have SVG support.\n\nINTERACTIVE_SVG        = NO\n\n# The tag DOT_PATH can be used to specify the path where the dot tool can be\n# found. If left blank, it is assumed the dot tool can be found in the path.\n\nDOT_PATH               =\n\n# The DOTFILE_DIRS tag can be used to specify one or more directories that\n# contain dot files that are included in the documentation (see the\n# \\dotfile command).\n\nDOTFILE_DIRS           =\n\n# The MSCFILE_DIRS tag can be used to specify one or more directories that\n# contain msc files that are included in the documentation (see the\n# \\mscfile command).\n\nMSCFILE_DIRS           =\n\n# The DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of\n# nodes that will be shown in the graph. If the number of nodes in a graph\n# becomes larger than this value, doxygen will truncate the graph, which is\n# visualized by representing a node as a red box. Note that doxygen if the\n# number of direct children of the root node in a graph is already larger than\n# DOT_GRAPH_MAX_NODES then the graph will not be shown at all. Also note\n# that the size of a graph can be further restricted by MAX_DOT_GRAPH_DEPTH.\n\nDOT_GRAPH_MAX_NODES    = 50\n\n# The MAX_DOT_GRAPH_DEPTH tag can be used to set the maximum depth of the\n# graphs generated by dot. A depth value of 3 means that only nodes reachable\n# from the root by following a path via at most 3 edges will be shown. Nodes\n# that lay further from the root node will be omitted. Note that setting this\n# option to 1 or 2 may greatly reduce the computation time needed for large\n# code bases. Also note that the size of a graph can be further restricted by\n# DOT_GRAPH_MAX_NODES. Using a depth of 0 means no depth restriction.\n\nMAX_DOT_GRAPH_DEPTH    = 0\n\n# Set the DOT_TRANSPARENT tag to YES to generate images with a transparent\n# background. This is disabled by default, because dot on Windows does not\n# seem to support this out of the box. Warning: Depending on the platform used,\n# enabling this option may lead to badly anti-aliased labels on the edges of\n# a graph (i.e. they become hard to read).\n\nDOT_TRANSPARENT        = NO\n\n# Set the DOT_MULTI_TARGETS tag to YES allow dot to generate multiple output\n# files in one run (i.e. multiple -o and -T options on the command line). This\n# makes dot run faster, but since only newer versions of dot (>1.8.10)\n# support this, this feature is disabled by default.\n\nDOT_MULTI_TARGETS      = NO\n\n# If the GENERATE_LEGEND tag is set to YES (the default) Doxygen will\n# generate a legend page explaining the meaning of the various boxes and\n# arrows in the dot generated graphs.\n\nGENERATE_LEGEND        = YES\n\n# If the DOT_CLEANUP tag is set to YES (the default) Doxygen will\n# remove the intermediate dot files that are used to generate\n# the various graphs.\n\nDOT_CLEANUP            = YES\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/FixedSizeVectorizable.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TopicFixedSizeVectorizable Fixed-size vectorizable %Eigen objects\n\nThe goal of this page is to explain what we mean by \"fixed-size vectorizable\".\n\n\\section FixedSizeVectorizable_summary Executive Summary\n\nAn Eigen object is called \"fixed-size vectorizable\" if it has fixed size and that size is a multiple of 16 bytes.\n\nExamples include:\n\\li Eigen::Vector2d\n\\li Eigen::Vector4d\n\\li Eigen::Vector4f\n\\li Eigen::Matrix2d\n\\li Eigen::Matrix2f\n\\li Eigen::Matrix4d\n\\li Eigen::Matrix4f\n\\li Eigen::Affine3d\n\\li Eigen::Affine3f\n\\li Eigen::Quaterniond\n\\li Eigen::Quaternionf\n\n\\section FixedSizeVectorizable_explanation Explanation\n\nFirst, \"fixed-size\" should be clear: an %Eigen object has fixed size if its number of rows and its number of columns are fixed at compile-time. So for example \\ref Matrix3f has fixed size, but \\ref MatrixXf doesn't (the opposite of fixed-size is dynamic-size).\n\nThe array of coefficients of a fixed-size %Eigen object is a plain \"static array\", it is not dynamically allocated. For example, the data behind a \\ref Matrix4f is just a \"float array[16]\".\n\nFixed-size objects are typically very small, which means that we want to handle them with zero runtime overhead -- both in terms of memory usage and of speed.\n\nNow, vectorization works with 128-bit packets (e.g., SSE, AltiVec, NEON), 256-bit packets (e.g., AVX), or 512-bit packets (e.g., AVX512). Moreover, for performance reasons, these packets are most efficiently read and written if they have the same alignment as the packet size, that is 16 bytes, 32 bytes, and 64 bytes respectively.\n\nSo it turns out that the best way that fixed-size %Eigen objects can be vectorized, is if their size is a multiple of 16 bytes (or more). %Eigen will then request 16-byte alignment (or more) for these objects, and henceforth rely on these objects being aligned to achieve maximal efficiency.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/FunctionsTakingEigenTypes.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicFunctionTakingEigenTypes Writing Functions Taking %Eigen Types as Parameters\n\n%Eigen's use of expression templates results in potentially every expression being of a different type. If you pass such an expression to a function taking a parameter of type Matrix, your expression will implicitly be evaluated into a temporary Matrix, which will then be passed to the function. This means that you lose the benefit of expression templates. Concretely, this has two drawbacks:\n \\li The evaluation into a temporary may be useless and inefficient;\n \\li This only allows the function to read from the expression, not to write to it.\n\nFortunately, all this myriad of expression types have in common that they all inherit a few common, templated base classes. By letting your function take templated parameters of these base types, you can let them play nicely with %Eigen's expression templates.\n\n\\eigenAutoToc\n\n\\section TopicFirstExamples Some First Examples\n\nThis section will provide simple examples for different types of objects %Eigen is offering. Before starting with the actual examples, we need to recapitulate which base objects we can work with (see also \\ref TopicClassHierarchy).\n\n \\li MatrixBase: The common base class for all dense matrix expressions (as opposed to array expressions, as opposed to sparse and special matrix classes). Use it in functions that are meant to work only on dense matrices.\n \\li ArrayBase: The common base class for all dense array expressions (as opposed to matrix expressions, etc). Use it in functions that are meant to work only on arrays.\n \\li DenseBase: The common base class for all dense matrix expression, that is, the base class for both \\c MatrixBase and \\c ArrayBase. It can be used in functions that are meant to work on both matrices and arrays.\n \\li EigenBase: The base class unifying all types of objects that can be evaluated into dense matrices or arrays, for example special matrix classes such as diagonal matrices, permutation matrices, etc. It can be used in functions that are meant to work on any such general type.\n\n<b> %EigenBase Example </b><br/><br/>\nPrints the dimensions of the most generic object present in %Eigen. It could be any matrix expressions, any dense or sparse matrix and any array.\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include function_taking_eigenbase.cpp\n</td>\n<td>\n\\verbinclude function_taking_eigenbase.out\n</td></tr></table>\n<b> %DenseBase Example </b><br/><br/>\nPrints a sub-block of the dense expression. Accepts any dense matrix or array expression, but no sparse objects and no special matrix classes such as DiagonalMatrix.\n\\code\ntemplate <typename Derived>\nvoid print_block(const DenseBase<Derived>& b, int x, int y, int r, int c)\n{\n  std::cout << \"block: \" << b.block(x,y,r,c) << std::endl;\n}\n\\endcode\n<b> %ArrayBase Example </b><br/><br/>\nPrints the maximum coefficient of the array or array-expression.\n\\code\ntemplate <typename Derived>\nvoid print_max_coeff(const ArrayBase<Derived> &a)\n{\n  std::cout << \"max: \" << a.maxCoeff() << std::endl;\n}\n\\endcode\n<b> %MatrixBase Example </b><br/><br/>\nPrints the inverse condition number of the given matrix or matrix-expression.\n\\code\ntemplate <typename Derived>\nvoid print_inv_cond(const MatrixBase<Derived>& a)\n{\n  const typename JacobiSVD<typename Derived::PlainObject>::SingularValuesType&\n    sing_vals = a.jacobiSvd().singularValues();\n  std::cout << \"inv cond: \" << sing_vals(sing_vals.size()-1) / sing_vals(0) << std::endl;\n}\n\\endcode\n<b> Multiple templated arguments example </b><br/><br/>\nCalculate the Euclidean distance between two points.\n\\code\ntemplate <typename DerivedA,typename DerivedB>\ntypename DerivedA::Scalar squaredist(const MatrixBase<DerivedA>& p1,const MatrixBase<DerivedB>& p2)\n{\n  return (p1-p2).squaredNorm();\n}\n\\endcode\nNotice that we used two template parameters, one per argument. This permits the function to handle inputs of different types, e.g.,\n\\code\nsquaredist(v1,2*v2)\n\\endcode\nwhere the first argument \\c v1 is a vector and the second argument \\c 2*v2 is an expression.\n<br/><br/>\n\nThese examples are just intended to give the reader a first impression of how functions can be written which take a plain and constant Matrix or Array argument. They are also intended to give the reader an idea about the most common base classes being the optimal candidates for functions. In the next section we will look in more detail at an example and the different ways it can be implemented, while discussing each implementation's problems and advantages. For the discussion below, Matrix and Array as well as MatrixBase and ArrayBase can be exchanged and all arguments still hold.\n\n\n\\section TopicUsingRefClass How to write generic, but non-templated function?\n\nIn all the previous examples, the functions had to be template functions. This approach allows to write very generic code, but it is often desirable to write non templated functions and still keep some level of genericity to avoid stupid copies of the arguments. The typical example is to write functions accepting both a MatrixXf or a block of a MatrixXf. This is exactly the purpose of the Ref class. Here is a simple example:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include function_taking_ref.cpp\n</td>\n<td>\n\\verbinclude function_taking_ref.out\n</td></tr></table>\nIn the first two calls to inv_cond, no copy occur because the memory layout of the arguments matches the memory layout accepted by Ref<MatrixXf>. However, in the last call, we have a generic expression that will be automatically evaluated into a temporary MatrixXf by the Ref<> object.\n\nA Ref object can also be writable. Here is an example of a function computing the covariance matrix of two input matrices where each row is an observation:\n\\code\nvoid cov(const Ref<const MatrixXf> x, const Ref<const MatrixXf> y, Ref<MatrixXf> C)\n{\n  const float num_observations = static_cast<float>(x.rows());\n  const RowVectorXf x_mean = x.colwise().sum() / num_observations;\n  const RowVectorXf y_mean = y.colwise().sum() / num_observations;\n  C = (x.rowwise() - x_mean).transpose() * (y.rowwise() - y_mean) / num_observations;\n}\n\\endcode\nand here are two examples calling cov without any copy:\n\\code\nMatrixXf m1, m2, m3\ncov(m1, m2, m3);\ncov(m1.leftCols<3>(), m2.leftCols<3>(), m3.topLeftCorner<3,3>());\n\\endcode\nThe Ref<> class has two other optional template arguments allowing to control the kind of memory layout that can be accepted without any copy. See the class Ref documentation for the details.\n\n\\section TopicPlainFunctionsWorking In which cases do functions taking plain Matrix or Array arguments work?\n\nWithout using template functions, and without the Ref class, a naive implementation of the previous cov function might look like this\n\\code\nMatrixXf cov(const MatrixXf& x, const MatrixXf& y)\n{\n  const float num_observations = static_cast<float>(x.rows());\n  const RowVectorXf x_mean = x.colwise().sum() / num_observations;\n  const RowVectorXf y_mean = y.colwise().sum() / num_observations;\n  return (x.rowwise() - x_mean).transpose() * (y.rowwise() - y_mean) / num_observations;\n}\n\\endcode\nand contrary to what one might think at first, this implementation is fine unless you require a generic implementation that works with double matrices too and unless you do not care about temporary objects. Why is that the case? Where are temporaries involved? How can code as given below compile?\n\\code\nMatrixXf x,y,z;\nMatrixXf C = cov(x,y+z);\n\\endcode\nIn this special case, the example is fine and will be working because both parameters are declared as \\e const references. The compiler creates a temporary and evaluates the expression x+z into this temporary. Once the function is processed, the temporary is released and the result is assigned to C.\n\n\\b Note: Functions taking \\e const references to Matrix (or Array) can process expressions at the cost of temporaries.\n\n\n\\section TopicPlainFunctionsFailing In which cases do functions taking a plain Matrix or Array argument fail?\n\nHere, we consider a slightly modified version of the function given above. This time, we do not want to return the result but pass an additional non-const parameter which allows us to store the result. A first naive implementation might look as follows.\n\\code\n// Note: This code is flawed!\nvoid cov(const MatrixXf& x, const MatrixXf& y, MatrixXf& C)\n{\n  const float num_observations = static_cast<float>(x.rows());\n  const RowVectorXf x_mean = x.colwise().sum() / num_observations;\n  const RowVectorXf y_mean = y.colwise().sum() / num_observations;\n  C = (x.rowwise() - x_mean).transpose() * (y.rowwise() - y_mean) / num_observations;\n}\n\\endcode\nWhen trying to execute the following code\n\\code\nMatrixXf C = MatrixXf::Zero(3,6);\ncov(x,y, C.block(0,0,3,3));\n\\endcode\nthe compiler will fail, because it is not possible to convert the expression returned by \\c MatrixXf::block() into a non-const \\c MatrixXf&. This is the case because the compiler wants to protect you from writing your result to a temporary object. In this special case this protection is not intended -- we want to write to a temporary object. So how can we overcome this problem? \n\nThe solution which is preferred at the moment is based on a little \\em hack. One needs to pass a const reference to the matrix and internally the constness needs to be cast away. The correct implementation for C98 compliant compilers would be\n\\code\ntemplate <typename Derived, typename OtherDerived>\nvoid cov(const MatrixBase<Derived>& x, const MatrixBase<Derived>& y, MatrixBase<OtherDerived> const & C)\n{\n  typedef typename Derived::Scalar Scalar;\n  typedef typename internal::plain_row_type<Derived>::type RowVectorType;\n\n  const Scalar num_observations = static_cast<Scalar>(x.rows());\n\n  const RowVectorType x_mean = x.colwise().sum() / num_observations;\n  const RowVectorType y_mean = y.colwise().sum() / num_observations;\n\n  const_cast< MatrixBase<OtherDerived>& >(C) =\n    (x.rowwise() - x_mean).transpose() * (y.rowwise() - y_mean) / num_observations;\n}\n\\endcode\nThe implementation above does now not only work with temporary expressions but it also allows to use the function with matrices of arbitrary floating point scalar types.\n\n\\b Note: The const cast hack will only work with templated functions. It will not work with the MatrixXf implementation because it is not possible to cast a Block expression to a Matrix reference!\n\n\n\n\\section TopicResizingInGenericImplementations How to resize matrices in generic implementations?\n\nOne might think we are done now, right? This is not completely true because in order for our covariance function to be generically applicable, we want the following code to work\n\\code\nMatrixXf x = MatrixXf::Random(100,3);\nMatrixXf y = MatrixXf::Random(100,3);\nMatrixXf C;\ncov(x, y, C);\n\\endcode\nThis is not the case anymore, when we are using an implementation taking MatrixBase as a parameter. In general, %Eigen supports automatic resizing but it is not possible to do so on expressions. Why should resizing of a matrix Block be allowed? It is a reference to a sub-matrix and we definitely don't want to resize that. So how can we incorporate resizing if we cannot resize on MatrixBase? The solution is to resize the derived object as in this implementation.\n\\code\ntemplate <typename Derived, typename OtherDerived>\nvoid cov(const MatrixBase<Derived>& x, const MatrixBase<Derived>& y, MatrixBase<OtherDerived> const & C_)\n{\n  typedef typename Derived::Scalar Scalar;\n  typedef typename internal::plain_row_type<Derived>::type RowVectorType;\n\n  const Scalar num_observations = static_cast<Scalar>(x.rows());\n\n  const RowVectorType x_mean = x.colwise().sum() / num_observations;\n  const RowVectorType y_mean = y.colwise().sum() / num_observations;\n\n  MatrixBase<OtherDerived>& C = const_cast< MatrixBase<OtherDerived>& >(C_);\n  \n  C.derived().resize(x.cols(),x.cols()); // resize the derived object\n  C = (x.rowwise() - x_mean).transpose() * (y.rowwise() - y_mean) / num_observations;\n}\n\\endcode\nThis implementation is now working for parameters being expressions and for parameters being matrices and having the wrong size. Resizing the expressions does not do any harm in this case unless they actually require resizing. That means, passing an expression with the wrong dimensions will result in a run-time error (in debug mode only) while passing expressions of the correct size will just work fine.\n\n\\b Note: In the above discussion the terms Matrix and Array and MatrixBase and ArrayBase can be exchanged and all arguments still hold.\n\n\\section TopicSummary Summary\n\n  - To summarize, the implementation of functions taking non-writable (const referenced) objects is not a big issue and does not lead to problematic situations in terms of compiling and running your program. However, a naive implementation is likely to introduce unnecessary temporary objects in your code. In order to avoid evaluating parameters into temporaries, pass them as (const) references to MatrixBase or ArrayBase (so templatize your function).\n\n  - Functions taking writable (non-const) parameters must take const references and cast away constness within the function body.\n\n  - Functions that take as parameters MatrixBase (or ArrayBase) objects, and potentially need to resize them (in the case where they are resizable), must call resize() on the derived class, as returned by derived().\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/HiPerformance.dox",
    "content": "\nnamespace Eigen {\n\n/** \\page TopicWritingEfficientProductExpression Writing efficient matrix product expressions\n\nIn general achieving good performance with Eigen does no require any special effort:\nsimply write your expressions in the most high level way. This is especially true\nfor small fixed size matrices. For large matrices, however, it might be useful to\ntake some care when writing your expressions in order to minimize useless evaluations\nand optimize the performance.\nIn this page we will give a brief overview of the Eigen's internal mechanism to simplify\nand evaluate complex product expressions, and discuss the current limitations.\nIn particular we will focus on expressions matching level 2 and 3 BLAS routines, i.e,\nall kind of matrix products and triangular solvers.\n\nIndeed, in Eigen we have implemented a set of highly optimized routines which are very similar\nto BLAS's ones. Unlike BLAS, those routines are made available to user via a high level and\nnatural API. Each of these routines can compute in a single evaluation a wide variety of expressions.\nGiven an expression, the challenge is then to map it to a minimal set of routines.\nAs explained latter, this mechanism has some limitations, and knowing them will allow\nyou to write faster code by making your expressions more Eigen friendly.\n\n\\section GEMM General Matrix-Matrix product (GEMM)\n\nLet's start with the most common primitive: the matrix product of general dense matrices.\nIn the BLAS world this corresponds to the GEMM routine. Our equivalent primitive can\nperform the following operation:\n\\f$ C.noalias() += \\alpha op1(A) op2(B) \\f$\nwhere A, B, and C are column and/or row major matrices (or sub-matrices),\nalpha is a scalar value, and op1, op2 can be transpose, adjoint, conjugate, or the identity.\nWhen Eigen detects a matrix product, it analyzes both sides of the product to extract a\nunique scalar factor alpha, and for each side, its effective storage order, shape, and conjugation states.\nMore precisely each side is simplified by iteratively removing trivial expressions such as scalar multiple,\nnegation and conjugation. Transpose and Block expressions are not evaluated and they only modify the storage order\nand shape. All other expressions are immediately evaluated.\nFor instance, the following expression:\n\\code m1.noalias() -= s4 * (s1 * m2.adjoint() * (-(s3*m3).conjugate()*s2))  \\endcode\nis automatically simplified to:\n\\code m1.noalias() += (s1*s2*conj(s3)*s4) * m2.adjoint() * m3.conjugate() \\endcode\nwhich exactly matches our GEMM routine.\n\n\\subsection GEMM_Limitations Limitations\nUnfortunately, this simplification mechanism is not perfect yet and not all expressions which could be\nhandled by a single GEMM-like call are correctly detected.\n<table class=\"manual\" style=\"width:100%\">\n<tr>\n<th>Not optimal expression</th>\n<th>Evaluated as</th>\n<th>Optimal version (single evaluation)</th>\n<th>Comments</th>\n</tr>\n<tr>\n<td>\\code\nm1 += m2 * m3; \\endcode</td>\n<td>\\code\ntemp = m2 * m3;\nm1 += temp; \\endcode</td>\n<td>\\code\nm1.noalias() += m2 * m3; \\endcode</td>\n<td>Use .noalias() to tell Eigen the result and right-hand-sides do not alias. \n    Otherwise the product m2 * m3 is evaluated into a temporary.</td>\n</tr>\n<tr class=\"alt\">\n<td></td>\n<td></td>\n<td>\\code\nm1.noalias() += s1 * (m2 * m3); \\endcode</td>\n<td>This is a special feature of Eigen. Here the product between a scalar\n    and a matrix product does not evaluate the matrix product but instead it\n    returns a matrix product expression tracking the scalar scaling factor. <br>\n    Without this optimization, the matrix product would be evaluated into a\n    temporary as in the next example.</td>\n</tr>\n<tr>\n<td>\\code\nm1.noalias() += (m2 * m3).adjoint(); \\endcode</td>\n<td>\\code\ntemp = m2 * m3;\nm1 += temp.adjoint(); \\endcode</td>\n<td>\\code\nm1.noalias() += m3.adjoint()\n*              * m2.adjoint(); \\endcode</td>\n<td>This is because the product expression has the EvalBeforeNesting bit which\n    enforces the evaluation of the product by the Tranpose expression.</td>\n</tr>\n<tr class=\"alt\">\n<td>\\code\nm1 = m1 + m2 * m3; \\endcode</td>\n<td>\\code\ntemp = m2 * m3;\nm1 = m1 + temp; \\endcode</td>\n<td>\\code m1.noalias() += m2 * m3; \\endcode</td>\n<td>Here there is no way to detect at compile time that the two m1 are the same,\n    and so the matrix product will be immediately evaluated.</td>\n</tr>\n<tr>\n<td>\\code\nm1.noalias() = m4 + m2 * m3; \\endcode</td>\n<td>\\code\ntemp = m2 * m3;\nm1 = m4 + temp; \\endcode</td>\n<td>\\code\nm1 = m4;\nm1.noalias() += m2 * m3; \\endcode</td>\n<td>First of all, here the .noalias() in the first expression is useless because\n    m2*m3 will be evaluated anyway. However, note how this expression can be rewritten\n    so that no temporary is required. (tip: for very small fixed size matrix\n    it is slightly better to rewrite it like this: m1.noalias() = m2 * m3; m1 += m4;</td>\n</tr>\n<tr class=\"alt\">\n<td>\\code\nm1.noalias() += (s1*m2).block(..) * m3; \\endcode</td>\n<td>\\code\ntemp = (s1*m2).block(..);\nm1 += temp * m3; \\endcode</td>\n<td>\\code\nm1.noalias() += s1 * m2.block(..) * m3; \\endcode</td>\n<td>This is because our expression analyzer is currently not able to extract trivial\n    expressions nested in a Block expression. Therefore the nested scalar\n    multiple cannot be properly extracted.</td>\n</tr>\n</table>\n\nOf course all these remarks hold for all other kind of products involving triangular or selfadjoint matrices.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/InplaceDecomposition.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage InplaceDecomposition Inplace matrix decompositions\n\nStarting from %Eigen 3.3, the LU, Cholesky, and QR decompositions can operate \\em inplace, that is, directly within the given input matrix.\nThis feature is especially useful when dealing with huge matrices, and or when the available memory is very limited (embedded systems).\n\nTo this end, the respective decomposition class must be instantiated with a Ref<> matrix type, and the decomposition object must be constructed with the input matrix as argument. As an example, let us consider an inplace LU decomposition with partial pivoting.\n\nLet's start with the basic inclusions, and declaration of a 2x2 matrix \\c A:\n\n<table class=\"example\">\n<tr><th>code</th><th>output</th></tr>\n<tr>\n  <td>\\snippet TutorialInplaceLU.cpp init\n  </td>\n  <td>\\snippet TutorialInplaceLU.out init\n  </td>\n</tr>\n</table>\n\nNo surprise here! Then, let's declare our inplace LU object \\c lu, and check the content of the matrix \\c A:\n\n<table class=\"example\">\n<tr>\n  <td>\\snippet TutorialInplaceLU.cpp declaration\n  </td>\n  <td>\\snippet TutorialInplaceLU.out declaration\n  </td>\n</tr>\n</table>\n\nHere, the \\c lu object computes and stores the \\c L and \\c U factors within the memory held by the matrix \\c A.\nThe coefficients of \\c A have thus been destroyed during the factorization, and replaced by the L and U factors as one can verify:\n\n<table class=\"example\">\n<tr>\n  <td>\\snippet TutorialInplaceLU.cpp matrixLU\n  </td>\n  <td>\\snippet TutorialInplaceLU.out matrixLU\n  </td>\n</tr>\n</table>\n\nThen, one can use the \\c lu object as usual, for instance to solve the Ax=b problem:\n<table class=\"example\">\n<tr>\n  <td>\\snippet TutorialInplaceLU.cpp solve\n  </td>\n  <td>\\snippet TutorialInplaceLU.out solve\n  </td>\n</tr>\n</table>\n\nHere, since the content of the original matrix \\c A has been lost, we had to declared a new matrix \\c A0 to verify the result.\n\nSince the memory is shared between \\c A and \\c lu, modifying the matrix \\c A will make \\c lu invalid.\nThis can easily be verified by modifying the content of \\c A and trying to solve the initial problem again:\n\n<table class=\"example\">\n<tr>\n  <td>\\snippet TutorialInplaceLU.cpp modifyA\n  </td>\n  <td>\\snippet TutorialInplaceLU.out modifyA\n  </td>\n</tr>\n</table>\n\nNote that there is no shared pointer under the hood, it is the \\b responsibility \\b of \\b the \\b user to keep the input matrix \\c A in life as long as \\c lu is living.\n\nIf one wants to update the factorization with the modified A, one has to call the compute method as usual:\n<table class=\"example\">\n<tr>\n  <td>\\snippet TutorialInplaceLU.cpp recompute\n  </td>\n  <td>\\snippet TutorialInplaceLU.out recompute\n  </td>\n</tr>\n</table>\n\nNote that calling compute does not change the memory which is referenced by the \\c lu object. Therefore, if the compute method is called with another matrix \\c A1 different than \\c A, then the content of \\c A1 won't be modified. This is still the content of \\c A that will be used to store the L and U factors of the matrix \\c A1.\nThis can easily be verified as follows:\n<table class=\"example\">\n<tr>\n  <td>\\snippet TutorialInplaceLU.cpp recompute_bis0\n </td>\n  <td>\\snippet TutorialInplaceLU.out recompute_bis0\n </td>\n</tr>\n</table>\nThe matrix \\c A1 is unchanged, and one can thus solve A1*x=b, and directly check the residual without any copy of \\c A1:\n<table class=\"example\">\n<tr>\n  <td>\\snippet TutorialInplaceLU.cpp recompute_bis1\n  </td>\n  <td>\\snippet TutorialInplaceLU.out recompute_bis1\n </td>\n</tr>\n</table>\n\n\nHere is the list of matrix decompositions supporting this inplace mechanism:\n\n- class LLT\n- class LDLT\n- class PartialPivLU\n- class FullPivLU\n- class HouseholderQR\n- class ColPivHouseholderQR\n- class FullPivHouseholderQR\n- class CompleteOrthogonalDecomposition\n\n*/\n\n}"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/InsideEigenExample.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicInsideEigenExample What happens inside Eigen, on a simple example\n\n\\eigenAutoToc\n\n<hr>\n\n\nConsider the following example program:\n\n\\code\n#include<Eigen/Core>\n\nint main()\n{\n  int size = 50;\n  // VectorXf is a vector of floats, with dynamic size.\n  Eigen::VectorXf u(size), v(size), w(size);\n  u = v + w;\n}\n\\endcode\n\nThe goal of this page is to understand how Eigen compiles it, assuming that SSE2 vectorization is enabled (GCC option -msse2).\n\n\\section WhyInteresting Why it's interesting\n\nMaybe you think, that the above example program is so simple, that compiling it shouldn't involve anything interesting. So before starting, let us explain what is nontrivial in compiling it correctly -- that is, producing optimized code -- so that the complexity of Eigen, that we'll explain here, is really useful.\n\nLook at the line of code\n\\code\n  u = v + w;   //   (*)\n\\endcode\n\nThe first important thing about compiling it, is that the arrays should be traversed only once, like\n\\code\n  for(int i = 0; i < size; i++) u[i] = v[i] + w[i];\n\\endcode\nThe problem is that if we make a naive C++ library where the VectorXf class has an operator+ returning a VectorXf, then the line of code (*) will amount to:\n\\code\n  VectorXf tmp = v + w;\n  VectorXf u = tmp;\n\\endcode\nObviously, the introduction of the temporary \\a tmp here is useless. It has a very bad effect on performance, first because the creation of \\a tmp requires a dynamic memory allocation in this context, and second as there are now two for loops:\n\\code\n  for(int i = 0; i < size; i++) tmp[i] = v[i] + w[i];\n  for(int i = 0; i < size; i++) u[i] = tmp[i];\n\\endcode\nTraversing the arrays twice instead of once is terrible for performance, as it means that we do many redundant memory accesses.\n\nThe second important thing about compiling the above program, is to make correct use of SSE2 instructions. Notice that Eigen also supports AltiVec and that all the discussion that we make here applies also to AltiVec.\n\nSSE2, like AltiVec, is a set of instructions allowing to perform computations on packets of 128 bits at once. Since a float is 32 bits, this means that SSE2 instructions can handle 4 floats at once. This means that, if correctly used, they can make our computation go up to 4x faster.\n\nHowever, in the above program, we have chosen size=50, so our vectors consist of 50 float's, and 50 is not a multiple of 4. This means that we cannot hope to do all of that computation using SSE2 instructions. The second best thing, to which we should aim, is to handle the 48 first coefficients with SSE2 instructions, since 48 is the biggest multiple of 4 below 50, and then handle separately, without SSE2, the 49th and 50th coefficients. Something like this:\n\n\\code\n  for(int i = 0; i < 4*(size/4); i+=4) u.packet(i)  = v.packet(i) + w.packet(i);\n  for(int i = 4*(size/4); i < size; i++) u[i] = v[i] + w[i];\n\\endcode\n\nSo let us look line by line at our example program, and let's follow Eigen as it compiles it.\n\n\\section ConstructingVectors Constructing vectors\n\nLet's analyze the first line:\n\n\\code\n  Eigen::VectorXf u(size), v(size), w(size);\n\\endcode\n\nFirst of all, VectorXf is the following typedef:\n\\code\n  typedef Matrix<float, Dynamic, 1> VectorXf;\n\\endcode\n\nThe class template Matrix is declared in src/Core/util/ForwardDeclarations.h with 6 template parameters, but the last 3 are automatically determined by the first 3. So you don't need to worry about them for now. Here, Matrix\\<float, Dynamic, 1\\> means a matrix of floats, with a dynamic number of rows and 1 column.\n\nThe Matrix class inherits a base class, MatrixBase. Don't worry about it, for now it suffices to say that MatrixBase is what unifies matrices/vectors and all the expressions types -- more on that below.\n\nWhen we do\n\\code\n  Eigen::VectorXf u(size);\n\\endcode\nthe constructor that is called is Matrix::Matrix(int), in src/Core/Matrix.h. Besides some assertions, all it does is to construct the \\a m_storage member, which is of type DenseStorage\\<float, Dynamic, Dynamic, 1\\>.\n\nYou may wonder, isn't it overengineering to have the storage in a separate class? The reason is that the Matrix class template covers all kinds of matrices and vector: both fixed-size and dynamic-size. The storage method is not the same in these two cases. For fixed-size, the matrix coefficients are stored as a plain member array. For dynamic-size, the coefficients will be stored as a pointer to a dynamically-allocated array. Because of this, we need to abstract storage away from the Matrix class. That's DenseStorage.\n\nLet's look at this constructor, in src/Core/DenseStorage.h. You can see that there are many partial template specializations of DenseStorages here, treating separately the cases where dimensions are Dynamic or fixed at compile-time. The partial specialization that we are looking at is:\n\\code\ntemplate<typename T, int _Cols> class DenseStorage<T, Dynamic, Dynamic, _Cols>\n\\endcode\n\nHere, the constructor called is DenseStorage::DenseStorage(int size, int rows, int columns)\nwith size=50, rows=50, columns=1.\n\nHere is this constructor:\n\\code\ninline DenseStorage(int size, int rows, int) : m_data(internal::aligned_new<T>(size)), m_rows(rows) {}\n\\endcode\n\nHere, the \\a m_data member is the actual array of coefficients of the matrix. As you see, it is dynamically allocated. Rather than calling new[] or malloc(), as you can see, we have our own internal::aligned_new defined in src/Core/util/Memory.h. What it does is that if vectorization is enabled, then it uses a platform-specific call to allocate a 128-bit-aligned array, as that is very useful for vectorization with both SSE2 and AltiVec. If vectorization is disabled, it amounts to the standard new[].\n\nAs you can see, the constructor also sets the \\a m_rows member to \\a size. Notice that there is no \\a m_columns member: indeed, in this partial specialization of DenseStorage, we know the number of columns at compile-time, since the _Cols template parameter is different from Dynamic. Namely, in our case, _Cols is 1, which is to say that our vector is just a matrix with 1 column. Hence, there is no need to store the number of columns as a runtime variable.\n\nWhen you call VectorXf::data() to get the pointer to the array of coefficients, it returns DenseStorage::data() which returns the \\a m_data member.\n\nWhen you call VectorXf::size() to get the size of the vector, this is actually a method in the base class MatrixBase. It determines that the vector is a column-vector, since ColsAtCompileTime==1 (this comes from the template parameters in the typedef VectorXf). It deduces that the size is the number of rows, so it returns VectorXf::rows(), which returns DenseStorage::rows(), which returns the \\a m_rows member, which was set to \\a size by the constructor.\n\n\\section ConstructionOfSumXpr Construction of the sum expression\n\nNow that our vectors are constructed, let's move on to the next line:\n\n\\code\nu = v + w;\n\\endcode\n\nThe executive summary is that operator+ returns a \"sum of vectors\" expression, but doesn't actually perform the computation. It is the operator=, whose call occurs thereafter, that does the computation.\n\nLet us now see what Eigen does when it sees this:\n\n\\code\nv + w\n\\endcode\n\nHere, v and w are of type VectorXf, which is a typedef for a specialization of Matrix (as we explained above), which is a subclass of MatrixBase. So what is being called is\n\n\\code\nMatrixBase::operator+(const MatrixBase&)\n\\endcode\n\nThe return type of this operator is\n\\code\nCwiseBinaryOp<internal::scalar_sum_op<float>, VectorXf, VectorXf>\n\\endcode\nThe CwiseBinaryOp class is our first encounter with an expression template. As we said, the operator+ doesn't by itself perform any computation, it just returns an abstract \"sum of vectors\" expression. Since there are also \"difference of vectors\" and \"coefficient-wise product of vectors\" expressions, we unify them all as \"coefficient-wise binary operations\", which we abbreviate as \"CwiseBinaryOp\". \"Coefficient-wise\" means that the operations is performed coefficient by coefficient. \"binary\" means that there are two operands -- we are adding two vectors with one another.\n\nNow you might ask, what if we did something like\n\n\\code\nv + w + u;\n\\endcode\n\nThe first v + w would return a CwiseBinaryOp as above, so in order for this to compile, we'd need to define an operator+ also in the class CwiseBinaryOp... at this point it starts looking like a nightmare: are we going to have to define all operators in each of the expression classes (as you guessed, CwiseBinaryOp is only one of many) ? This looks like a dead end!\n\nThe solution is that CwiseBinaryOp itself, as well as Matrix and all the other expression types, is a subclass of MatrixBase. So it is enough to define once and for all the operators in class MatrixBase.\n\nSince MatrixBase is the common base class of different subclasses, the aspects that depend on the subclass must be abstracted from MatrixBase. This is called polymorphism.\n\nThe classical approach to polymorphism in C++ is by means of virtual functions. This is dynamic polymorphism. Here we don't want dynamic polymorphism because the whole design of Eigen is based around the assumption that all the complexity, all the abstraction, gets resolved at compile-time. This is crucial: if the abstraction can't get resolved at compile-time, Eigen's compile-time optimization mechanisms become useless, not to mention that if that abstraction has to be resolved at runtime it'll incur an overhead by itself.\n\nHere, what we want is to have a single class MatrixBase as the base of many subclasses, in such a way that each MatrixBase object (be it a matrix, or vector, or any kind of expression) knows at compile-time (as opposed to run-time) of which particular subclass it is an object (i.e. whether it is a matrix, or an expression, and what kind of expression).\n\nThe solution is the <a href=\"http://en.wikipedia.org/wiki/Curiously_Recurring_Template_Pattern\">Curiously Recurring Template Pattern</a>. Let's do the break now. Hopefully you can read this wikipedia page during the break if needed, but it won't be allowed during the exam.\n\nIn short, MatrixBase takes a template parameter \\a Derived. Whenever we define a subclass Subclass, we actually make Subclass inherit MatrixBase\\<Subclass\\>. The point is that different subclasses inherit different MatrixBase types. Thanks to this, whenever we have an object of a subclass, and we call on it some MatrixBase method, we still remember even from inside the MatrixBase method which particular subclass we're talking about.\n\nThis means that we can put almost all the methods and operators in the base class MatrixBase, and have only the bare minimum in the subclasses. If you look at the subclasses in Eigen, like for instance the CwiseBinaryOp class, they have very few methods. There are coeff() and sometimes coeffRef() methods for access to the coefficients, there are rows() and cols() methods returning the number of rows and columns, but there isn't much more than that. All the meat is in MatrixBase, so it only needs to be coded once for all kinds of expressions, matrices, and vectors.\n\nSo let's end this digression and come back to the piece of code from our example program that we were currently analyzing,\n\n\\code\nv + w\n\\endcode\n\nNow that MatrixBase is a good friend, let's write fully the prototype of the operator+ that gets called here (this code is from src/Core/MatrixBase.h):\n\n\\code\ntemplate<typename Derived>\nclass MatrixBase\n{\n  // ...\n\n  template<typename OtherDerived>\n  const CwiseBinaryOp<internal::scalar_sum_op<typename internal::traits<Derived>::Scalar>, Derived, OtherDerived>\n  operator+(const MatrixBase<OtherDerived> &other) const;\n\n  // ...\n};\n\\endcode\n\nHere of course, \\a Derived and \\a OtherDerived are VectorXf.\n\nAs we said, CwiseBinaryOp is also used for other operations such as substration, so it takes another template parameter determining the operation that will be applied to coefficients. This template parameter is a functor, that is, a class in which we have an operator() so it behaves like a function. Here, the functor used is internal::scalar_sum_op. It is defined in src/Core/Functors.h.\n\nLet us now explain the internal::traits here. The internal::scalar_sum_op class takes one template parameter: the type of the numbers to handle. Here of course we want to pass the scalar type (a.k.a. numeric type) of VectorXf, which is \\c float. How do we determine which is the scalar type of \\a Derived ? Throughout Eigen, all matrix and expression types define a typedef \\a Scalar which gives its scalar type. For example, VectorXf::Scalar is a typedef for \\c float. So here, if life was easy, we could find the numeric type of \\a Derived as just\n\\code\ntypename Derived::Scalar\n\\endcode\nUnfortunately, we can't do that here, as the compiler would complain that the type Derived hasn't yet been defined. So we use a workaround: in src/Core/util/ForwardDeclarations.h, we declared (not defined!) all our subclasses, like Matrix, and we also declared the following class template:\n\\code\ntemplate<typename T> struct internal::traits;\n\\endcode\nIn src/Core/Matrix.h, right \\em before the definition of class Matrix, we define a partial specialization of internal::traits for T=Matrix\\<any template parameters\\>. In this specialization of internal::traits, we define the Scalar typedef. So when we actually define Matrix, it is legal to refer to \"typename internal::traits\\<Matrix\\>::Scalar\".\n\nAnyway, we have declared our operator+. In our case, where \\a Derived and \\a OtherDerived are VectorXf, the above declaration amounts to:\n\\code\nclass MatrixBase<VectorXf>\n{\n  // ...\n\n  const CwiseBinaryOp<internal::scalar_sum_op<float>, VectorXf, VectorXf>\n  operator+(const MatrixBase<VectorXf> &other) const;\n\n  // ...\n};\n\\endcode\n\nLet's now jump to src/Core/CwiseBinaryOp.h to see how it is defined. As you can see there, all it does is to return a CwiseBinaryOp object, and this object is just storing references to the left-hand-side and right-hand-side expressions -- here, these are the vectors \\a v and \\a w. Well, the CwiseBinaryOp object is also storing an instance of the (empty) functor class, but you shouldn't worry about it as that is a minor implementation detail.\n\nThus, the operator+ hasn't performed any actual computation. To summarize, the operation \\a v + \\a w just returned an object of type CwiseBinaryOp which did nothing else than just storing references to \\a v and \\a w.\n\n\\section Assignment The assignment\n\n<div class=\"warningbox\">\n<strong>PLEASE HELP US IMPROVING THIS SECTION.</strong>\nThis page reflects how %Eigen worked until 3.2, but since %Eigen 3.3 the assignment is more sophisticated as it involves an Assignment expression, and the creation of so called evaluator which are responsible for the evaluation of each kind of expressions.\n</div>\n\nAt this point, the expression \\a v + \\a w has finished evaluating, so, in the process of compiling the line of code\n\\code\nu = v + w;\n\\endcode\nwe now enter the operator=.\n\nWhat operator= is being called here? The vector u is an object of class VectorXf, i.e. Matrix. In src/Core/Matrix.h, inside the definition of class Matrix, we see this:\n\\code\n    template<typename OtherDerived>\n    inline Matrix& operator=(const MatrixBase<OtherDerived>& other)\n    {\n      eigen_assert(m_storage.data()!=0 && \"you cannot use operator= with a non initialized matrix (instead use set()\");\n      return Base::operator=(other.derived());\n    }\n\\endcode\nHere, Base is a typedef for MatrixBase\\<Matrix\\>. So, what is being called is the operator= of MatrixBase. Let's see its prototype in src/Core/MatrixBase.h:\n\\code\n    template<typename OtherDerived>\n    Derived& operator=(const MatrixBase<OtherDerived>& other);\n\\endcode\nHere, \\a Derived is VectorXf (since u is a VectorXf) and \\a OtherDerived is CwiseBinaryOp. More specifically, as explained in the previous section, \\a OtherDerived is:\n\\code\nCwiseBinaryOp<internal::scalar_sum_op<float>, VectorXf, VectorXf>\n\\endcode\nSo the full prototype of the operator= being called is:\n\\code\nVectorXf& MatrixBase<VectorXf>::operator=(const MatrixBase<CwiseBinaryOp<internal::scalar_sum_op<float>, VectorXf, VectorXf> > & other);\n\\endcode\nThis operator= literally reads \"copying a sum of two VectorXf's into another VectorXf\".\n\nLet's now look at the implementation of this operator=. It resides in the file src/Core/Assign.h.\n\nWhat we can see there is:\n\\code\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\ninline Derived& MatrixBase<Derived>\n  ::operator=(const MatrixBase<OtherDerived>& other)\n{\n  return internal::assign_selector<Derived,OtherDerived>::run(derived(), other.derived());\n}\n\\endcode\n\nOK so our next task is to understand internal::assign_selector :)\n\nHere is its declaration (all that is still in the same file src/Core/Assign.h)\n\\code\ntemplate<typename Derived, typename OtherDerived,\n         bool EvalBeforeAssigning = int(OtherDerived::Flags) & EvalBeforeAssigningBit,\n         bool NeedToTranspose = Derived::IsVectorAtCompileTime\n                && OtherDerived::IsVectorAtCompileTime\n                && int(Derived::RowsAtCompileTime) == int(OtherDerived::ColsAtCompileTime)\n                && int(Derived::ColsAtCompileTime) == int(OtherDerived::RowsAtCompileTime)\n                && int(Derived::SizeAtCompileTime) != 1>\nstruct internal::assign_selector;\n\\endcode\n\nSo internal::assign_selector takes 4 template parameters, but the 2 last ones are automatically determined by the 2 first ones.\n\nEvalBeforeAssigning is here to enforce the EvalBeforeAssigningBit. As explained <a href=\"TopicLazyEvaluation.html\">here</a>, certain expressions have this flag which makes them automatically evaluate into temporaries before assigning them to another expression. This is the case of the Product expression, in order to avoid strange aliasing effects when doing \"m = m * m;\" However, of course here our CwiseBinaryOp expression doesn't have the EvalBeforeAssigningBit: we said since the beginning that we didn't want a temporary to be introduced here. So if you go to src/Core/CwiseBinaryOp.h, you'll see that the Flags in internal::traits\\<CwiseBinaryOp\\> don't include the EvalBeforeAssigningBit. The Flags member of CwiseBinaryOp is then imported from the internal::traits by the EIGEN_GENERIC_PUBLIC_INTERFACE macro. Anyway, here the template parameter EvalBeforeAssigning has the value \\c false.\n\nNeedToTranspose is here for the case where the user wants to copy a row-vector into a column-vector. We allow this as a special exception to the general rule that in assignments we require the dimesions to match. Anyway, here both the left-hand and right-hand sides are column vectors, in the sense that ColsAtCompileTime is equal to 1. So NeedToTranspose is \\c false too.\n\nSo, here we are in the partial specialization:\n\\code\ninternal::assign_selector<Derived, OtherDerived, false, false>\n\\endcode\n\nHere's how it is defined:\n\\code\ntemplate<typename Derived, typename OtherDerived>\nstruct internal::assign_selector<Derived,OtherDerived,false,false> {\n  static Derived& run(Derived& dst, const OtherDerived& other) { return dst.lazyAssign(other.derived()); }\n};\n\\endcode\n\nOK so now our next job is to understand how lazyAssign works :)\n\n\\code\ntemplate<typename Derived>\ntemplate<typename OtherDerived>\ninline Derived& MatrixBase<Derived>\n  ::lazyAssign(const MatrixBase<OtherDerived>& other)\n{\n  EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Derived,OtherDerived)\n  eigen_assert(rows() == other.rows() && cols() == other.cols());\n  internal::assign_impl<Derived, OtherDerived>::run(derived(),other.derived());\n  return derived();\n}\n\\endcode\n\nWhat do we see here? Some assertions, and then the only interesting line is:\n\\code\n  internal::assign_impl<Derived, OtherDerived>::run(derived(),other.derived());\n\\endcode\n\nOK so now we want to know what is inside internal::assign_impl.\n\nHere is its declaration:\n\\code\ntemplate<typename Derived1, typename Derived2,\n         int Vectorization = internal::assign_traits<Derived1, Derived2>::Vectorization,\n         int Unrolling = internal::assign_traits<Derived1, Derived2>::Unrolling>\nstruct internal::assign_impl;\n\\endcode\nAgain, internal::assign_selector takes 4 template parameters, but the 2 last ones are automatically determined by the 2 first ones.\n\nThese two parameters \\a Vectorization and \\a Unrolling are determined by a helper class internal::assign_traits. Its job is to determine which vectorization strategy to use (that is \\a Vectorization) and which unrolling strategy to use (that is \\a Unrolling).\n\nWe'll not enter into the details of how these strategies are chosen (this is in the implementation of internal::assign_traits at the top of the same file). Let's just say that here \\a Vectorization has the value \\a LinearVectorization, and \\a Unrolling has the value \\a NoUnrolling (the latter is obvious since our vectors have dynamic size so there's no way to unroll the loop at compile-time).\n\nSo the partial specialization of internal::assign_impl that we're looking at is:\n\\code\ninternal::assign_impl<Derived1, Derived2, LinearVectorization, NoUnrolling>\n\\endcode\n\nHere is how it's defined:\n\\code\ntemplate<typename Derived1, typename Derived2>\nstruct internal::assign_impl<Derived1, Derived2, LinearVectorization, NoUnrolling>\n{\n  static void run(Derived1 &dst, const Derived2 &src)\n  {\n    const int size = dst.size();\n    const int packetSize = internal::packet_traits<typename Derived1::Scalar>::size;\n    const int alignedStart = internal::assign_traits<Derived1,Derived2>::DstIsAligned ? 0\n                           : internal::first_aligned(&dst.coeffRef(0), size);\n    const int alignedEnd = alignedStart + ((size-alignedStart)/packetSize)*packetSize;\n\n    for(int index = 0; index < alignedStart; index++)\n      dst.copyCoeff(index, src);\n\n    for(int index = alignedStart; index < alignedEnd; index += packetSize)\n    {\n      dst.template copyPacket<Derived2, Aligned, internal::assign_traits<Derived1,Derived2>::SrcAlignment>(index, src);\n    }\n\n    for(int index = alignedEnd; index < size; index++)\n      dst.copyCoeff(index, src);\n  }\n};\n\\endcode\n\nHere's how it works. \\a LinearVectorization means that the left-hand and right-hand side expression can be accessed linearly i.e. you can refer to their coefficients by one integer \\a index, as opposed to having to refer to its coefficients by two integers \\a row, \\a column.\n\nAs we said at the beginning, vectorization works with blocks of 4 floats. Here, \\a PacketSize is 4.\n\nThere are two potential problems that we need to deal with:\n\\li first, vectorization works much better if the packets are 128-bit-aligned. This is especially important for write access. So when writing to the coefficients of \\a dst, we want to group these coefficients by packets of 4 such that each of these packets is 128-bit-aligned. In general, this requires to skip a few coefficients at the beginning of \\a dst. This is the purpose of \\a alignedStart. We then copy these first few coefficients one by one, not by packets. However, in our case, the \\a dst expression is a VectorXf and remember that in the construction of the vectors we allocated aligned arrays. Thanks to \\a DstIsAligned, Eigen remembers that without having to do any runtime check, so \\a alignedStart is zero and this part is avoided altogether.\n\\li second, the number of coefficients to copy is not in general a multiple of \\a packetSize. Here, there are 50 coefficients to copy and \\a packetSize is 4. So we'll have to copy the last 2 coefficients one by one, not by packets. Here, \\a alignedEnd is 48.\n\nNow come the actual loops.\n\nFirst, the vectorized part: the 48 first coefficients out of 50 will be copied by packets of 4:\n\\code\n  for(int index = alignedStart; index < alignedEnd; index += packetSize)\n  {\n    dst.template copyPacket<Derived2, Aligned, internal::assign_traits<Derived1,Derived2>::SrcAlignment>(index, src);\n  }\n\\endcode\n\nWhat is copyPacket? It is defined in src/Core/Coeffs.h:\n\\code\ntemplate<typename Derived>\ntemplate<typename OtherDerived, int StoreMode, int LoadMode>\ninline void MatrixBase<Derived>::copyPacket(int index, const MatrixBase<OtherDerived>& other)\n{\n  eigen_internal_assert(index >= 0 && index < size());\n  derived().template writePacket<StoreMode>(index,\n    other.derived().template packet<LoadMode>(index));\n}\n\\endcode\n\nOK, what are writePacket() and packet() here?\n\nFirst, writePacket() here is a method on the left-hand side VectorXf. So we go to src/Core/Matrix.h to look at its definition:\n\\code\ntemplate<int StoreMode>\ninline void writePacket(int index, const PacketScalar& x)\n{\n  internal::pstoret<Scalar, PacketScalar, StoreMode>(m_storage.data() + index, x);\n}\n\\endcode\nHere, \\a StoreMode is \\a #Aligned, indicating that we are doing a 128-bit-aligned write access, \\a PacketScalar is a type representing a \"SSE packet of 4 floats\" and internal::pstoret is a function writing such a packet in memory. Their definitions are architecture-specific, we find them in src/Core/arch/SSE/PacketMath.h:\n\nThe line in src/Core/arch/SSE/PacketMath.h that determines the PacketScalar type (via a typedef in Matrix.h) is:\n\\code\ntemplate<> struct internal::packet_traits<float>  { typedef __m128  type; enum {size=4}; };\n\\endcode\nHere, __m128 is a SSE-specific type. Notice that the enum \\a size here is what was used to define \\a packetSize above.\n\nAnd here is the implementation of internal::pstoret:\n\\code\ntemplate<> inline void internal::pstore(float*  to, const __m128&  from) { _mm_store_ps(to, from); }\n\\endcode\nHere, __mm_store_ps is a SSE-specific intrinsic function, representing a single SSE instruction. The difference between internal::pstore and internal::pstoret is that internal::pstoret is a dispatcher handling both the aligned and unaligned cases, you find its definition in src/Core/GenericPacketMath.h:\n\\code\ntemplate<typename Scalar, typename Packet, int LoadMode>\ninline void internal::pstoret(Scalar* to, const Packet& from)\n{\n  if(LoadMode == Aligned)\n    internal::pstore(to, from);\n  else\n    internal::pstoreu(to, from);\n}\n\\endcode\n\nOK, that explains how writePacket() works. Now let's look into the packet() call. Remember that we are analyzing this line of code inside copyPacket():\n\\code\nderived().template writePacket<StoreMode>(index,\n    other.derived().template packet<LoadMode>(index));\n\\endcode\n\nHere, \\a other is our sum expression \\a v + \\a w. The .derived() is just casting from MatrixBase to the subclass which here is CwiseBinaryOp. So let's go to src/Core/CwiseBinaryOp.h:\n\\code\nclass CwiseBinaryOp\n{\n  // ...\n    template<int LoadMode>\n    inline PacketScalar packet(int index) const\n    {\n      return m_functor.packetOp(m_lhs.template packet<LoadMode>(index), m_rhs.template packet<LoadMode>(index));\n    }\n};\n\\endcode\nHere, \\a m_lhs is the vector \\a v, and \\a m_rhs is the vector \\a w. So the packet() function here is Matrix::packet(). The template parameter \\a LoadMode is \\a #Aligned. So we're looking at\n\\code\nclass Matrix\n{\n  // ...\n    template<int LoadMode>\n    inline PacketScalar packet(int index) const\n    {\n      return internal::ploadt<Scalar, LoadMode>(m_storage.data() + index);\n    }\n};\n\\endcode\nWe let you look up the definition of internal::ploadt in GenericPacketMath.h and the internal::pload in src/Core/arch/SSE/PacketMath.h. It is very similar to the above for internal::pstore.\n\nLet's go back to CwiseBinaryOp::packet(). Once the packets from the vectors \\a v and \\a w have been returned, what does this function do? It calls m_functor.packetOp() on them. What is m_functor? Here we must remember what particular template specialization of CwiseBinaryOp we're dealing with:\n\\code\nCwiseBinaryOp<internal::scalar_sum_op<float>, VectorXf, VectorXf>\n\\endcode\nSo m_functor is an object of the empty class internal::scalar_sum_op<float>. As we mentioned above, don't worry about why we constructed an object of this empty class at all -- it's an implementation detail, the point is that some other functors need to store member data.\n\nAnyway, internal::scalar_sum_op is defined in src/Core/Functors.h:\n\\code\ntemplate<typename Scalar> struct internal::scalar_sum_op EIGEN_EMPTY_STRUCT {\n  inline const Scalar operator() (const Scalar& a, const Scalar& b) const { return a + b; }\n  template<typename PacketScalar>\n  inline const PacketScalar packetOp(const PacketScalar& a, const PacketScalar& b) const\n  { return internal::padd(a,b); }\n};\n\\endcode\nAs you can see, all what packetOp() does is to call internal::padd on the two packets. Here is the definition of internal::padd from src/Core/arch/SSE/PacketMath.h:\n\\code\ntemplate<> inline __m128  internal::padd(const __m128&  a, const __m128&  b) { return _mm_add_ps(a,b); }\n\\endcode\nHere, _mm_add_ps is a SSE-specific intrinsic function, representing a single SSE instruction.\n\nTo summarize, the loop\n\\code\n  for(int index = alignedStart; index < alignedEnd; index += packetSize)\n  {\n    dst.template copyPacket<Derived2, Aligned, internal::assign_traits<Derived1,Derived2>::SrcAlignment>(index, src);\n  }\n\\endcode\nhas been compiled to the following code: for \\a index going from 0 to the 11 ( = 48/4 - 1), read the i-th packet (of 4 floats) from the vector v and the i-th packet from the vector w using two __mm_load_ps SSE instructions, then add them together using a __mm_add_ps instruction, then store the result using a __mm_store_ps instruction.\n\nThere remains the second loop handling the last few (here, the last 2) coefficients:\n\\code\n  for(int index = alignedEnd; index < size; index++)\n    dst.copyCoeff(index, src);\n\\endcode\nHowever, it works just like the one we just explained, it is just simpler because there is no SSE vectorization involved here. copyPacket() becomes copyCoeff(), packet() becomes coeff(), writePacket() becomes coeffRef(). If you followed us this far, you can probably understand this part by yourself.\n\nWe see that all the C++ abstraction of Eigen goes away during compilation and that we indeed are precisely controlling which assembly instructions we emit. Such is the beauty of C++! Since we have such precise control over the emitted assembly instructions, but such complex logic to choose the right instructions, we can say that Eigen really behaves like an optimizing compiler. If you prefer, you could say that Eigen behaves like a script for the compiler. In a sense, C++ template metaprogramming is scripting the compiler -- and it's been shown that this scripting language is Turing-complete. See <a href=\"http://en.wikipedia.org/wiki/Template_metaprogramming\"> Wikipedia</a>.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/LeastSquares.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage LeastSquares Solving linear least squares systems\n\nThis page describes how to solve linear least squares systems using %Eigen. An overdetermined system\nof equations, say \\a Ax = \\a b, has no solutions. In this case, it makes sense to search for the\nvector \\a x which is closest to being a solution, in the sense that the difference \\a Ax - \\a b is\nas small as possible. This \\a x is called the least square solution (if the Euclidean norm is used).\n\nThe three methods discussed on this page are the SVD decomposition, the QR decomposition and normal\nequations. Of these, the SVD decomposition is generally the most accurate but the slowest, normal\nequations is the fastest but least accurate, and the QR decomposition is in between.\n\n\\eigenAutoToc\n\n\n\\section LeastSquaresSVD Using the SVD decomposition\n\nThe \\link BDCSVD::solve() solve() \\endlink method in the BDCSVD class can be directly used to\nsolve linear squares systems. It is not enough to compute only the singular values (the default for\nthis class); you also need the singular vectors but the thin SVD decomposition suffices for\ncomputing least squares solutions:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include TutorialLinAlgSVDSolve.cpp </td>\n  <td>\\verbinclude TutorialLinAlgSVDSolve.out </td>\n</tr>\n</table>\n\nThis is example from the page \\link TutorialLinearAlgebra Linear algebra and decompositions \\endlink.\n\n\n\\section LeastSquaresQR Using the QR decomposition\n\nThe solve() method in QR decomposition classes also computes the least squares solution. There are\nthree QR decomposition classes: HouseholderQR (no pivoting, so fast but unstable),\nColPivHouseholderQR (column pivoting, thus a bit slower but more accurate) and FullPivHouseholderQR\n(full pivoting, so slowest and most stable). Here is an example with column pivoting:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include LeastSquaresQR.cpp </td>\n  <td>\\verbinclude LeastSquaresQR.out </td>\n</tr>\n</table>\n\n\n\\section LeastSquaresNormalEquations Using normal equations\n\nFinding the least squares solution of \\a Ax = \\a b is equivalent to solving the normal equation\n<i>A</i><sup>T</sup><i>Ax</i> = <i>A</i><sup>T</sup><i>b</i>. This leads to the following code\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include LeastSquaresNormalEquations.cpp </td>\n  <td>\\verbinclude LeastSquaresNormalEquations.out </td>\n</tr>\n</table>\n\nIf the matrix \\a A is ill-conditioned, then this is not a good method, because the condition number\nof <i>A</i><sup>T</sup><i>A</i> is the square of the condition number of \\a A. This means that you\nlose twice as many digits using normal equation than if you use the other methods.\n\n*/\n\n}"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/Manual.dox",
    "content": "\n// This file strutures pages and modules into a convenient hierarchical structure.\n\nnamespace Eigen {\n\n/** \\page UserManual_CustomizingEigen Extending/Customizing Eigen\n  %Eigen can be extended in several ways, for instance, by defining global methods, by inserting custom methods within main %Eigen's classes through the \\ref TopicCustomizing_Plugins \"plugin\" mechanism, by adding support to \\ref TopicCustomizing_CustomScalar \"custom scalar types\" etc. See below for the respective sub-topics.\n  - \\subpage TopicCustomizing_Plugins\n  - \\subpage TopicCustomizing_InheritingMatrix\n  - \\subpage TopicCustomizing_CustomScalar\n  - \\subpage TopicCustomizing_NullaryExpr\n  - \\subpage TopicNewExpressionType\n  \\sa \\ref TopicPreprocessorDirectives\n*/\n\n\n/** \\page UserManual_Generalities General topics\n  - \\subpage TopicFunctionTakingEigenTypes\n  - \\subpage TopicPreprocessorDirectives\n  - \\subpage TopicAssertions\n  - \\subpage TopicMultiThreading\n  - \\subpage TopicUsingBlasLapack\n  - \\subpage TopicUsingIntelMKL\n  - \\subpage TopicCUDA\n  - \\subpage TopicPitfalls\n  - \\subpage TopicTemplateKeyword\n  - \\subpage UserManual_UnderstandingEigen\n  - \\subpage TopicCMakeGuide\n*/\n\n/** \\page UserManual_UnderstandingEigen Understanding Eigen\n  - \\subpage TopicInsideEigenExample\n  - \\subpage TopicClassHierarchy\n  - \\subpage TopicLazyEvaluation\n*/\n\n/** \\page UnclassifiedPages Unclassified pages\n  - \\subpage TopicResizing\n  - \\subpage TopicVectorization\n  - \\subpage TopicEigenExpressionTemplates\n  - \\subpage TopicScalarTypes\n  - \\subpage GettingStarted\n  - \\subpage TutorialSparse_example_details\n  - \\subpage TopicWritingEfficientProductExpression\n  - \\subpage Experimental\n*/\n\n\n/** \\defgroup Support_modules Support modules\n  * Category of modules which add support for external libraries.\n  */\n\n\n/** \\defgroup DenseMatrixManipulation_chapter Dense matrix and array manipulation */\n/** \\defgroup DenseMatrixManipulation_Alignement Alignment issues */\n/** \\defgroup DenseMatrixManipulation_Reference Reference */\n\n/** \\addtogroup TutorialMatrixClass\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TutorialMatrixArithmetic\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TutorialArrayClass\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TutorialBlockOperations\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TutorialSlicingIndexing\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TutorialAdvancedInitialization\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TutorialReductionsVisitorsBroadcasting\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TutorialReshape\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TutorialSTL\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TutorialMapClass\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TopicAliasing\n    \\ingroup DenseMatrixManipulation_chapter */\n/** \\addtogroup TopicStorageOrders\n    \\ingroup DenseMatrixManipulation_chapter */\n\n/** \\addtogroup DenseMatrixManipulation_Alignement\n    \\ingroup DenseMatrixManipulation_chapter        */\n/**     \\addtogroup TopicUnalignedArrayAssert\n        \\ingroup DenseMatrixManipulation_Alignement */\n/**     \\addtogroup TopicFixedSizeVectorizable\n        \\ingroup DenseMatrixManipulation_Alignement */\n/**     \\addtogroup TopicStructHavingEigenMembers\n        \\ingroup DenseMatrixManipulation_Alignement */\n/**     \\addtogroup TopicStlContainers\n        \\ingroup DenseMatrixManipulation_Alignement */\n/**     \\addtogroup TopicPassingByValue\n        \\ingroup DenseMatrixManipulation_Alignement */\n/**     \\addtogroup TopicWrongStackAlignment\n        \\ingroup DenseMatrixManipulation_Alignement */\n    \n/** \\addtogroup DenseMatrixManipulation_Reference\n    \\ingroup DenseMatrixManipulation_chapter       */\n/**     \\addtogroup Core_Module\n        \\ingroup DenseMatrixManipulation_Reference */  \n/**     \\addtogroup Jacobi_Module\n        \\ingroup DenseMatrixManipulation_Reference */ \n/**     \\addtogroup Householder_Module\n        \\ingroup DenseMatrixManipulation_Reference */ \n\n/** \\addtogroup CoeffwiseMathFunctions\n    \\ingroup DenseMatrixManipulation_chapter */\n\n/** \\addtogroup QuickRefPage\n    \\ingroup DenseMatrixManipulation_chapter */\n\n\n/** \\defgroup DenseLinearSolvers_chapter Dense linear problems and decompositions */\n/** \\defgroup DenseLinearSolvers_Reference Reference */\n\n/** \\addtogroup TutorialLinearAlgebra\n    \\ingroup DenseLinearSolvers_chapter */\n/** \\addtogroup TopicLinearAlgebraDecompositions\n    \\ingroup DenseLinearSolvers_chapter */\n/** \\addtogroup LeastSquares \n    \\ingroup DenseLinearSolvers_chapter */\n/** \\addtogroup InplaceDecomposition\n    \\ingroup DenseLinearSolvers_chapter */\n/** \\addtogroup DenseDecompositionBenchmark\n    \\ingroup DenseLinearSolvers_chapter */\n\n/** \\addtogroup DenseLinearSolvers_Reference\n    \\ingroup DenseLinearSolvers_chapter */\n/** \\addtogroup Cholesky_Module\n    \\ingroup DenseLinearSolvers_Reference */\n/** \\addtogroup LU_Module\n    \\ingroup DenseLinearSolvers_Reference */\n/** \\addtogroup QR_Module\n    \\ingroup DenseLinearSolvers_Reference */\n/** \\addtogroup SVD_Module\n    \\ingroup DenseLinearSolvers_Reference*/\n/** \\addtogroup Eigenvalues_Module\n    \\ingroup DenseLinearSolvers_Reference */\n\n\n\n\n/** \\defgroup Sparse_chapter Sparse linear algebra */\n/** \\defgroup Sparse_Reference Reference */\n\n/** \\addtogroup TutorialSparse\n    \\ingroup Sparse_chapter */\n/** \\addtogroup TopicSparseSystems\n    \\ingroup Sparse_chapter */\n/** \\addtogroup MatrixfreeSolverExample\n    \\ingroup Sparse_chapter */\n\n/** \\addtogroup Sparse_Reference\n    \\ingroup Sparse_chapter */\n/** \\addtogroup SparseCore_Module\n    \\ingroup Sparse_Reference */\n/** \\addtogroup OrderingMethods_Module\n    \\ingroup Sparse_Reference */\n/** \\addtogroup SparseCholesky_Module\n    \\ingroup Sparse_Reference */\n/** \\addtogroup SparseLU_Module\n    \\ingroup Sparse_Reference */\n/** \\addtogroup SparseQR_Module\n    \\ingroup Sparse_Reference */\n/** \\addtogroup IterativeLinearSolvers_Module\n    \\ingroup Sparse_Reference */\n/** \\addtogroup Sparse_Module\n    \\ingroup Sparse_Reference */\n/** \\addtogroup Support_modules\n    \\ingroup Sparse_Reference */    \n\n/** \\addtogroup SparseQuickRefPage\n    \\ingroup Sparse_chapter */\n\n\n/** \\defgroup Geometry_chapter Geometry */\n/** \\defgroup Geometry_Reference Reference */\n\n/** \\addtogroup TutorialGeometry\n    \\ingroup Geometry_chapter */\n    \n/** \\addtogroup Geometry_Reference\n    \\ingroup Geometry_chapter */\n/** \\addtogroup Geometry_Module\n    \\ingroup Geometry_Reference */\n/** \\addtogroup Splines_Module\n    \\ingroup Geometry_Reference */\n\n/** \\internal \\brief Namespace containing low-level routines from the %Eigen library. */\nnamespace internal {}\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/MatrixfreeSolverExample.dox",
    "content": "\nnamespace Eigen {\n\n/**\n\n\\eigenManualPage MatrixfreeSolverExample Matrix-free solvers\n\nIterative solvers such as ConjugateGradient and BiCGSTAB can be used in a matrix free context. To this end, user must provide a wrapper class inheriting EigenBase<> and implementing the following methods:\n - \\c Index \\c rows() and \\c Index \\c cols(): returns number of rows and columns respectively\n - \\c operator* with your type and an %Eigen dense column vector (its actual implementation goes in a specialization of the internal::generic_product_impl class)\n\n\\c Eigen::internal::traits<> must also be specialized for the wrapper type.\n\nHere is a complete example wrapping an Eigen::SparseMatrix:\n\\include matrixfree_cg.cpp\nOutput: \\verbinclude matrixfree_cg.out\n\n*/\n\n}"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/NewExpressionType.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicNewExpressionType Adding a new expression type\n\n<!--<span style=\"font-size:130%; color:red; font-weight: 900;\"></span>-->\n\\warning\nDisclaimer: this page is tailored to very advanced users who are not afraid of dealing with some %Eigen's internal aspects.\nIn most cases, a custom expression can be avoided by either using custom \\ref MatrixBase::unaryExpr \"unary\" or \\ref MatrixBase::binaryExpr \"binary\" functors,\nwhile extremely complex matrix manipulations can be achieved by a nullary functors as described in the \\ref TopicCustomizing_NullaryExpr \"previous page\".\n\nThis page describes with the help of an example how to implement a new\nlight-weight expression type in %Eigen. This consists of three parts:\nthe expression type itself, a traits class containing compile-time\ninformation about the expression, and the evaluator class which is\nused to evaluate the expression to a matrix.\n\n\\b TO \\b DO: Write a page explaining the design, with details on\nvectorization etc., and refer to that page here.\n\n\n\\eigenAutoToc\n\n\\section TopicSetting The setting\n\nA circulant matrix is a matrix where each column is the same as the\ncolumn to the left, except that it is cyclically shifted downwards.\nFor example, here is a 4-by-4 circulant matrix:\n\\f[ \\begin{bmatrix} \n    1 & 8 & 4 & 2 \\\\ \n    2 & 1 & 8 & 4 \\\\\n    4 & 2 & 1 & 8 \\\\\n    8 & 4 & 2 & 1\n\\end{bmatrix} \\f]\nA circulant matrix is uniquely determined by its first column. We wish\nto write a function \\c makeCirculant which, given the first column,\nreturns an expression representing the circulant matrix.\n\nFor simplicity, we restrict the \\c makeCirculant function to dense\nmatrices. It may make sense to also allow arrays, or sparse matrices,\nbut we will not do so here. We also do not want to support\nvectorization.\n\n\n\\section TopicPreamble Getting started\n\nWe will present the file implementing the \\c makeCirculant function\npart by part. We start by including the appropriate header files and\nforward declaring the expression class, which we will call\n\\c Circulant. The \\c makeCirculant function will return an object of\nthis type. The class \\c Circulant is in fact a class template; the\ntemplate argument \\c ArgType refers to the type of the vector passed\nto the \\c makeCirculant function.\n\n\\include make_circulant.cpp.preamble\n\n\n\\section TopicTraits The traits class\n\nFor every expression class \\c X, there should be a traits class \n\\c Traits<X> in the \\c Eigen::internal namespace containing\ninformation about \\c X known as compile time.\n\nAs explained in \\ref TopicSetting, we designed the \\c Circulant\nexpression class to refer to dense matrices. The entries of the\ncirculant matrix have the same type as the entries of the vector\npassed to the \\c makeCirculant function. The type used to index the\nentries is also the same. Again for simplicity, we will only return\ncolumn-major matrices. Finally, the circulant matrix is a square\nmatrix (number of rows equals number of columns), and the number of\nrows equals the number of rows of the column vector passed to the\n\\c makeCirculant function. If this is a dynamic-size vector, then the\nsize of the circulant matrix is not known at compile-time.\n\nThis leads to the following code:\n\n\\include make_circulant.cpp.traits\n\n\n\\section TopicExpression The expression class\n\nThe next step is to define the expression class itself. In our case,\nwe want to inherit from \\c MatrixBase in order to expose the interface\nfor dense matrices. In the constructor, we check that we are passed a\ncolumn vector (see \\ref TopicAssertions) and we store the vector from\nwhich we are going to build the circulant matrix in the member\nvariable \\c m_arg. Finally, the expression class should compute the\nsize of the corresponding circulant matrix. As explained above, this\nis a square matrix with as many columns as the vector used to\nconstruct the matrix.\n\n\\b TO \\b DO: What about the \\c Nested typedef? It seems to be\nnecessary; is this only temporary?\n\n\\include make_circulant.cpp.expression\n\n\n\\section TopicEvaluator The evaluator\n\nThe last big fragment implements the evaluator for the \\c Circulant\nexpression. The evaluator computes the entries of the circulant\nmatrix; this is done in the \\c .coeff() member function. The entries\nare computed by finding the corresponding entry of the vector from\nwhich the circulant matrix is constructed. Getting this entry may\nactually be non-trivial when the circulant matrix is constructed from\na vector which is given by a complicated expression, so we use the\nevaluator which corresponds to the vector.\n\nThe \\c CoeffReadCost constant records the cost of computing an entry\nof the circulant matrix; we ignore the index computation and say that\nthis is the same as the cost of computing an entry of the vector from\nwhich the circulant matrix is constructed.\n\nIn the constructor, we save the evaluator for the column vector which\ndefined the circulant matrix. We also save the size of that vector;\nremember that we can query an expression object to find the size but\nnot the evaluator. \n\n\\include make_circulant.cpp.evaluator\n\n\n\\section TopicEntry The entry point\n\nAfter all this, the \\c makeCirculant function is very simple. It\nsimply creates an expression object and returns it.\n\n\\include make_circulant.cpp.entry\n\n\n\\section TopicMain A simple main function for testing\n\nFinally, a short \\c main function that shows how the \\c makeCirculant\nfunction can be called.\n\n\\include make_circulant.cpp.main\n\nIf all the fragments are combined, the following output is produced,\nshowing that the program works as expected:\n\n\\include make_circulant.out\n\n*/\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/Overview.dox",
    "content": "namespace Eigen {\n\n/** \\mainpage notitle\n\nThis is the API documentation for Eigen3. You can <a href=\"eigen-doc.tgz\">download</a> it as a tgz archive for offline reading.\n\nFor a first contact with Eigen, the best place is to have a look at the \\link GettingStarted getting started \\endlink page that show you how to write and compile your first program with Eigen.\n\nThen, the \\b quick \\b reference \\b pages give you a quite complete description of the API in a very condensed format that is specially useful to recall the syntax of a particular feature, or to have a quick look at the API. They currently cover the two following feature sets, and more will come in the future:\n  - \\link QuickRefPage [QuickRef] Dense matrix and array manipulations \\endlink\n  - \\link SparseQuickRefPage [QuickRef] Sparse linear algebra \\endlink\n\nYou're a MatLab user? There is also a <a href=\"AsciiQuickReference.txt\">short ASCII reference</a> with Matlab translations.\n  \nThe \\b main \\b documentation is organized into \\em chapters covering different domains of features.\nThey are themselves composed of \\em user \\em manual pages describing the different features in a comprehensive way, and \\em reference pages that gives you access to the API documentation through the related Eigen's \\em modules and \\em classes.\n\nUnder the \\subpage UserManual_CustomizingEigen section, you will find discussions and examples on extending %Eigen's features and supporting custom scalar types.\n\nUnder the \\subpage UserManual_Generalities section, you will find documentation on more general topics such as preprocessor directives, controlling assertions, multi-threading, MKL support, some Eigen's internal insights, and much more...\n\nFinally, do not miss the search engine, useful to quickly get to the documentation of a given class or function.\n\nWant more? Checkout the <a href=\"unsupported/index.html\">\\em unsupported \\em modules </a> documentation.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/PassingByValue.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TopicPassingByValue Passing Eigen objects by value to functions\n\nPassing objects by value is almost always a very bad idea in C++, as this means useless copies, and one should pass them by reference instead.\n\nWith %Eigen, this is even more important: passing \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen objects\" by value is not only inefficient, it can be illegal or make your program crash! And the reason is that these %Eigen objects have alignment modifiers that aren't respected when they are passed by value.\n\nFor example, a function like this, where \\c v is passed by value:\n\n\\code\nvoid my_function(Eigen::Vector2d v);\n\\endcode\n\nneeds to be rewritten as follows, passing \\c v by const reference:\n\n\\code\nvoid my_function(const Eigen::Vector2d& v);\n\\endcode\n\nLikewise if you have a class having an %Eigen object as member:\n\n\\code\nstruct Foo\n{\n  Eigen::Vector2d v;\n};\nvoid my_function(Foo v);\n\\endcode\n\nThis function also needs to be rewritten like this:\n\\code\nvoid my_function(const Foo& v);\n\\endcode\n\nNote that on the other hand, there is no problem with functions that return objects by value.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/Pitfalls.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicPitfalls Common pitfalls\n\n\n\\section TopicPitfalls_template_keyword Compilation error with template methods\n\nSee this \\link TopicTemplateKeyword page \\endlink.\n\n\n\\section TopicPitfalls_aliasing Aliasing\n\nDon't miss this \\link TopicAliasing page \\endlink on aliasing,\nespecially if you got wrong results in statements where the destination appears on the right hand side of the expression.\n\n\n\\section TopicPitfalls_alignment_issue Alignment Issues (runtime assertion)\n\n%Eigen does explicit vectorization, and while that is appreciated by many users, that also leads to some issues in special situations where data alignment is compromised.\nIndeed, prior to C++17,  C++ does not have quite good enough support for explicit data alignment.\nIn that case your program hits an assertion failure (that is, a \"controlled crash\") with a message that tells you to consult this page:\n\\code\nhttp://eigen.tuxfamily.org/dox/group__TopicUnalignedArrayAssert.html\n\\endcode\nHave a look at \\link TopicUnalignedArrayAssert it \\endlink and see for yourself if that's something that you can cope with.\nIt contains detailed information about how to deal with each known cause for that issue.\n\nNow what if you don't care about vectorization and so don't want to be annoyed with these alignment issues? Then read \\link getrid how to get rid of them \\endlink.\n\n\n\\section TopicPitfalls_auto_keyword C++11 and the auto keyword\n\nIn short: do not use the auto keywords with %Eigen's expressions, unless you are 100% sure about what you are doing. In particular, do not use the auto keyword as a replacement for a \\c Matrix<> type. Here is an example:\n\n\\code\nMatrixXd A, B;\nauto C = A*B;\nfor(...) { ... w = C * v;  ...}\n\\endcode\n\nIn this example, the type of C is not a \\c MatrixXd but an abstract expression representing a matrix product and storing references to \\c A and \\c B.\nTherefore, the product of \\c A*B will be carried out multiple times, once per iteration of the for loop.\nMoreover, if the coefficients of `A` or `B` change during the iteration, then `C` will evaluate to different values as in the following example:\n\n\\code\nMatrixXd A = ..., B = ...;\nauto C = A*B;\nMatrixXd R1 = C;\nA = ...;\nMatrixXd R2 = C;\n\\endcode\nfor which we end up with `R1` &ne; `R2`.\n\n\nHere is another example leading to a segfault:\n\\code\nauto C = ((A+B).eval()).transpose();\n// do something with C\n\\endcode\nThe problem is that \\c eval() returns a temporary object (in this case a \\c MatrixXd) which is then referenced by the \\c Transpose<> expression.\nHowever, this temporary is deleted right after the first line, and then the \\c C expression references a dead object.\nOne possible fix consists in applying \\c eval() on the whole expression:\n\\code\nauto C = (A+B).transpose().eval();\n\\endcode\n\nThe same issue might occur when sub expressions are automatically evaluated by %Eigen as in the following example:\n\\code\nVectorXd u, v;\nauto C = u + (A*v).normalized();\n// do something with C\n\\endcode\nHere the \\c normalized() method has to evaluate the expensive product \\c A*v to avoid evaluating it twice.\nAgain, one possible fix is to call \\c .eval() on the whole expression:\n\\code\nauto C = (u + (A*v).normalized()).eval();\n\\endcode\nIn this case, \\c C will be a regular \\c VectorXd object.\nNote that DenseBase::eval() is smart enough to avoid copies when the underlying expression is already a plain \\c Matrix<>.\n\n\n\\section TopicPitfalls_header_issues Header Issues (failure to compile)\n\nWith all libraries, one must check the documentation for which header to include.\nThe same is true with %Eigen, but slightly worse: with %Eigen, a method in a class may require an additional \\c \\#include over what the class itself requires!\nFor example, if you want to use the \\c cross() method on a vector (it computes a cross-product) then you need to:\n\\code\n#include<Eigen/Geometry>\n\\endcode\nWe try to always document this, but do tell us if we forgot an occurrence.\n\n\n\\section TopicPitfalls_ternary_operator Ternary operator\n\nIn short: avoid the use of the ternary operator <code>(COND ? THEN : ELSE)</code> with %Eigen's expressions for the \\c THEN and \\c ELSE statements.\nTo see why, let's consider the following example:\n\\code\nVector3f A;\nA << 1, 2, 3;\nVector3f B = ((1 < 0) ? (A.reverse()) : A);\n\\endcode\nThis example will return <code>B = 3, 2, 1</code>. Do you see why?\nThe reason is that in c++ the type of the \\c ELSE statement is inferred from the type of the \\c THEN expression such that both match.\nSince \\c THEN is a <code>Reverse<Vector3f></code>, the \\c ELSE statement A is converted to a <code>Reverse<Vector3f></code>, and the compiler thus generates:\n\\code\nVector3f B = ((1 < 0) ? (A.reverse()) : Reverse<Vector3f>(A));\n\\endcode\nIn this very particular case, a workaround would be to call A.reverse().eval() for the \\c THEN statement, but the safest and fastest is really to avoid this ternary operator with %Eigen's expressions and use a if/else construct.\n\n\n\\section TopicPitfalls_pass_by_value Pass-by-value\n\nIf you don't know why passing-by-value is wrong with %Eigen, read this \\link TopicPassingByValue page \\endlink first.\n\nWhile you may be extremely careful and use care to make sure that all of your code that explicitly uses %Eigen types is pass-by-reference you have to watch out for templates which define the argument types at compile time.\n\nIf a template has a function that takes arguments pass-by-value, and the relevant template parameter ends up being an %Eigen type, then you will of course have the same alignment problems that you would in an explicitly defined function passing %Eigen types by reference.\n\nUsing %Eigen types with other third party libraries or even the STL can present the same problem.\n<code>boost::bind</code> for example uses pass-by-value to store arguments in the returned functor.\nThis will of course be a problem.\n\nThere are at least two ways around this:\n  - If the value you are passing is guaranteed to be around for the life of the functor, you can use boost::ref() to wrap the value as you pass it to boost::bind. Generally this is not a solution for values on the stack as if the functor ever gets passed to a lower or independent scope, the object may be gone by the time it's attempted to be used.\n  - The other option is to make your functions take a reference counted pointer like boost::shared_ptr as the argument. This avoids needing to worry about managing the lifetime of the object being passed.\n\n\n\\section TopicPitfalls_matrix_bool Matrices with boolean coefficients\n\nThe current behaviour of using \\c Matrix with boolean coefficients is inconsistent and likely to change in future versions of Eigen, so please use it carefully!\n\nA simple example for such an inconsistency is \n\n\\code\ntemplate<int Size>\nvoid foo() {\n  Eigen::Matrix<bool, Size, Size> A, B, C;\n  A.setOnes();\n  B.setOnes();\n\n  C = A * B - A * B;\n  std::cout << C << \"\\n\";\n}\n\\endcode\n\nsince calling \\c foo<3>() prints the zero matrix while calling \\c foo<10>() prints the identity matrix.\n\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/PreprocessorDirectives.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicPreprocessorDirectives Preprocessor directives\n\nYou can control some aspects of %Eigen by defining the preprocessor tokens using \\c \\#define. These macros\nshould be defined before any %Eigen headers are included. Often they are best set in the project options.\n\nThis page lists the preprocessor tokens recognized by %Eigen.\n\n\\eigenAutoToc\n\n\n\\section TopicPreprocessorDirectivesMajor Macros with major effects\n\nThese macros have a major effect and typically break the API (Application Programming Interface) and/or the\nABI (Application Binary Interface). This can be rather dangerous: if parts of your program are compiled with\none option, and other parts (or libraries that you use) are compiled with another option, your program may\nfail to link or exhibit subtle bugs. Nevertheless, these options can be useful for people who know what they\nare doing.\n\n - \\b EIGEN2_SUPPORT and \\b EIGEN2_SUPPORT_STAGEnn_xxx are disabled starting from the 3.3 release.\n   Defining one of these will raise a compile-error. If you need to compile Eigen2 code,\n   <a href=\"http://eigen.tuxfamily.org/index.php?title=Eigen2\">check this site</a>.\n - \\b EIGEN_DEFAULT_DENSE_INDEX_TYPE - the type for column and row indices in matrices, vectors and array\n   (DenseBase::Index). Set to \\c std::ptrdiff_t by default.\n - \\b EIGEN_DEFAULT_IO_FORMAT - the IOFormat to use when printing a matrix if no %IOFormat is specified.\n   Defaults to the %IOFormat constructed by the default constructor IOFormat::IOFormat().\n - \\b EIGEN_INITIALIZE_MATRICES_BY_ZERO - if defined, all entries of newly constructed matrices and arrays are\n   initialized to zero, as are new entries in matrices and arrays after resizing. Not defined by default.\n   \\warning The unary (resp. binary) constructor of \\c 1x1 (resp. \\c 2x1 or \\c 1x2) fixed size matrices is\n   always interpreted as an initialization constructor where the argument(s) are the coefficient values\n   and not the sizes. For instance, \\code Vector2d v(2,1); \\endcode will create a vector with coeficients [2,1],\n   and \\b not a \\c 2x1 vector initialized with zeros (i.e., [0,0]). If such cases might occur, then it is\n   recommended to use the default constructor with a explicit call to resize:\n   \\code\n   Matrix<?,SizeAtCompileTime,1> v;\n   v.resize(size);\n   Matrix<?,RowsAtCompileTime,ColsAtCompileTime> m;\n   m.resize(rows,cols);\n   \\endcode\n - \\b EIGEN_INITIALIZE_MATRICES_BY_NAN - if defined, all entries of newly constructed matrices and arrays are\n   initialized to NaN, as are new entries in matrices and arrays after resizing. This option is especially\n   useful for debugging purpose, though a memory tool like <a href=\"http://valgrind.org/\">valgrind</a> is\n   preferable. Not defined by default.\n   \\warning See the documentation of \\c EIGEN_INITIALIZE_MATRICES_BY_ZERO for a discussion on a limitations\n   of these macros when applied to \\c 1x1, \\c 1x2, and \\c 2x1 fixed-size matrices.\n - \\b EIGEN_NO_AUTOMATIC_RESIZING - if defined, the matrices (or arrays) on both sides of an assignment \n   <tt>a = b</tt> have to be of the same size; otherwise, %Eigen automatically resizes \\c a so that it is of\n   the correct size. Not defined by default.\n\n\n\\section TopicPreprocessorDirectivesCppVersion C++ standard features\n\nBy default, %Eigen strive to automatically detect and enable language features at compile-time based on\nthe information provided by the compiler.\n\n - \\b EIGEN_MAX_CPP_VER - disables usage of C++ features requiring a version greater than EIGEN_MAX_CPP_VER.\n   Possible values are: 03, 11, 14, 17, etc. If not defined (the default), %Eigen enables all features supported\n   by the compiler.\n\nIndividual features can be explicitly enabled or disabled by defining the following token to 0 or 1 respectively.\nFor instance, one might limit the C++ version to C++03 by defining EIGEN_MAX_CPP_VER=03, but still enable C99 math\nfunctions by defining EIGEN_HAS_C99_MATH=1.\n\n - \\b EIGEN_HAS_C99_MATH - controls the usage of C99 math functions such as erf, erfc, lgamma, etc.\n   Automatic detection disabled if EIGEN_MAX_CPP_VER<11.\n - \\b EIGEN_HAS_CXX11_MATH - controls the implementation of some functions such as round, logp1, isinf, isnan, etc.\n   Automatic detection disabled if EIGEN_MAX_CPP_VER<11.\n - \\b EIGEN_HAS_RVALUE_REFERENCES - defines whether rvalue references are supported\n   Automatic detection disabled if EIGEN_MAX_CPP_VER<11.\n - \\b EIGEN_HAS_STD_RESULT_OF - defines whether std::result_of is supported\n   Automatic detection disabled if EIGEN_MAX_CPP_VER<11.\n - \\b EIGEN_HAS_VARIADIC_TEMPLATES - defines whether variadic templates are supported\n   Automatic detection disabled if EIGEN_MAX_CPP_VER<11.\n - \\b EIGEN_HAS_CONSTEXPR - defines whether relaxed const expression are supported\n   Automatic detection disabled if EIGEN_MAX_CPP_VER<14.\n - \\b EIGEN_HAS_CXX11_CONTAINERS - defines whether STL's containers follows C++11 specifications\n   Automatic detection disabled if EIGEN_MAX_CPP_VER<11.\n - \\b EIGEN_HAS_CXX11_NOEXCEPT - defines whether noexcept is supported\n   Automatic detection disabled if EIGEN_MAX_CPP_VER<11.\n - \\b EIGEN_NO_IO - Disables any usage and support for `<iostreams>`.\n\n\\section TopicPreprocessorDirectivesAssertions Assertions\n\nThe %Eigen library contains many assertions to guard against programming errors, both at compile time and at\nrun time. However, these assertions do cost time and can thus be turned off.\n\n - \\b EIGEN_NO_DEBUG - disables %Eigen's assertions if defined. Not defined by default, unless the\n   \\c NDEBUG macro is defined (this is a standard C++ macro which disables all asserts). \n - \\b EIGEN_NO_STATIC_ASSERT - if defined, compile-time static assertions are replaced by runtime assertions; \n   this saves compilation time. Not defined by default.\n - \\b eigen_assert - macro with one argument that is used inside %Eigen for assertions. By default, it is\n   basically defined to be \\c assert, which aborts the program if the assertion is violated. Redefine this\n   macro if you want to do something else, like throwing an exception.\n - \\b EIGEN_MPL2_ONLY - disable non MPL2 compatible features, or in other words disable the features which\n   are still under the LGPL.\n\n\n\\section TopicPreprocessorDirectivesPerformance Alignment, vectorization and performance tweaking\n\n - \\b \\c EIGEN_MALLOC_ALREADY_ALIGNED - Can be set to 0 or 1 to tell whether default system \\c malloc already\n   returns aligned buffers. In not defined, then this information is automatically deduced from the compiler\n   and system preprocessor tokens.\n - \\b \\c EIGEN_MAX_ALIGN_BYTES - Must be a power of two, or 0. Defines an upper bound on the memory boundary in bytes on which dynamically and statically allocated data may be aligned by %Eigen. If not defined, a default value is automatically computed based on architecture, compiler, and OS.\n This option is typically used to enforce binary compatibility between code/libraries compiled with different SIMD options. For instance, one may compile AVX code and enforce ABI compatibility with existing SSE code by defining \\c EIGEN_MAX_ALIGN_BYTES=16. In the other way round, since by default AVX implies 32 bytes alignment for best performance, one can compile SSE code to be ABI compatible with AVX code by defining \\c EIGEN_MAX_ALIGN_BYTES=32.\n - \\b \\c EIGEN_MAX_STATIC_ALIGN_BYTES - Same as \\c EIGEN_MAX_ALIGN_BYTES but for statically allocated data only. By default, if only  \\c EIGEN_MAX_ALIGN_BYTES is defined, then \\c EIGEN_MAX_STATIC_ALIGN_BYTES == \\c EIGEN_MAX_ALIGN_BYTES, otherwise a default value is automatically computed based on architecture, compiler, and OS (can be smaller than the default value of EIGEN_MAX_ALIGN_BYTES on architectures that do not support stack alignment).\n Let us emphasize that \\c EIGEN_MAX_*_ALIGN_BYTES define only a diserable upper bound. In practice data is aligned to largest power-of-two common divisor of \\c EIGEN_MAX_STATIC_ALIGN_BYTES and the size of the data, such that memory is not wasted.\n - \\b \\c EIGEN_DONT_PARALLELIZE - if defined, this disables multi-threading. This is only relevant if you enabled OpenMP.\n   See \\ref TopicMultiThreading for details.\n - \\b \\c EIGEN_DONT_VECTORIZE - disables explicit vectorization when defined. Not defined by default, unless \n   alignment is disabled by %Eigen's platform test or the user defining \\c EIGEN_DONT_ALIGN.\n - \\b \\c EIGEN_UNALIGNED_VECTORIZE - disables/enables vectorization with unaligned stores. Default is 1 (enabled).\n   If set to 0 (disabled), then expression for which the destination cannot be aligned are not vectorized (e.g., unaligned\n   small fixed size vectors or matrices)\n - \\b \\c EIGEN_FAST_MATH - enables some optimizations which might affect the accuracy of the result. This currently\n   enables the SSE vectorization of sin() and cos(), and speedups sqrt() for single precision. Defined to 1 by default.\n   Define it to 0 to disable.\n - \\b \\c EIGEN_UNROLLING_LIMIT - defines the size of a loop to enable meta unrolling. Set it to zero to disable\n   unrolling. The size of a loop here is expressed in %Eigen's own notion of \"number of FLOPS\", it does not\n   correspond to the number of iterations or the number of instructions. The default is value 110.\n - \\b \\c EIGEN_STACK_ALLOCATION_LIMIT - defines the maximum bytes for a buffer to be allocated on the stack. For internal\n   temporary buffers, dynamic memory allocation is employed as a fall back. For fixed-size matrices or arrays, exceeding\n   this threshold raises a compile time assertion. Use 0 to set no limit. Default is 128 KB.\n - \\b \\c EIGEN_NO_CUDA - disables CUDA support when defined. Might be useful in .cu files for which Eigen is used on the host only,\n   and never called from device code.\n - \\b \\c EIGEN_STRONG_INLINE - This macro is used to qualify critical functions and methods that we expect the compiler to inline.\n   By default it is defined to \\c __forceinline for MSVC and ICC, and to \\c inline for other compilers. A tipical usage is to\n   define it to \\c inline for MSVC users wanting faster compilation times, at the risk of performance degradations in some rare\n   cases for which MSVC inliner fails to do a good job.\n - \\b \\c EIGEN_DEFAULT_L1_CACHE_SIZE - Sets the default L1 cache size that is used in Eigen's GEBP kernel when the correct cache size cannot be determined at runtime.\n - \\b \\c EIGEN_DEFAULT_L2_CACHE_SIZE - Sets the default L2 cache size that is used in Eigen's GEBP kernel when the correct cache size cannot be determined at runtime.\n - \\b \\c EIGEN_DEFAULT_L3_CACHE_SIZE - Sets the default L3 cache size that is used in Eigen's GEBP kernel when the correct cache size cannot be determined at runtime.\n\n - \\c EIGEN_DONT_ALIGN - Deprecated, it is a synonym for \\c EIGEN_MAX_ALIGN_BYTES=0. It disables alignment completely. %Eigen will not try to align its objects and does not expect that any objects passed to it are aligned. This will turn off vectorization if \\b \\c EIGEN_UNALIGNED_VECTORIZE=1. Not defined by default.\n - \\c EIGEN_DONT_ALIGN_STATICALLY - Deprecated, it is a synonym for \\c EIGEN_MAX_STATIC_ALIGN_BYTES=0. It disables alignment of arrays on the stack. Not defined by default, unless \\c EIGEN_DONT_ALIGN is defined.\n\n\n\\section TopicPreprocessorDirectivesPlugins Plugins\n\nIt is possible to add new methods to many fundamental classes in %Eigen by writing a plugin. As explained in\nthe section \\ref TopicCustomizing_Plugins, the plugin is specified by defining a \\c EIGEN_xxx_PLUGIN macro. The\nfollowing macros are supported; none of them are defined by default.\n\n - \\b EIGEN_ARRAY_PLUGIN - filename of plugin for extending the Array class.\n - \\b EIGEN_ARRAYBASE_PLUGIN - filename of plugin for extending the ArrayBase class.\n - \\b EIGEN_CWISE_PLUGIN - filename of plugin for extending the Cwise class.\n - \\b EIGEN_DENSEBASE_PLUGIN - filename of plugin for extending the DenseBase class.\n - \\b EIGEN_DYNAMICSPARSEMATRIX_PLUGIN - filename of plugin for extending the DynamicSparseMatrix class.\n - \\b EIGEN_FUNCTORS_PLUGIN - filename of plugin for adding new functors and specializations of functor_traits.\n - \\b EIGEN_MAPBASE_PLUGIN - filename of plugin for extending the MapBase class.\n - \\b EIGEN_MATRIX_PLUGIN - filename of plugin for extending the Matrix class.\n - \\b EIGEN_MATRIXBASE_PLUGIN - filename of plugin for extending the MatrixBase class.\n - \\b EIGEN_PLAINOBJECTBASE_PLUGIN - filename of plugin for extending the PlainObjectBase class.\n - \\b EIGEN_QUATERNION_PLUGIN - filename of plugin for extending the Quaternion class.\n - \\b EIGEN_QUATERNIONBASE_PLUGIN - filename of plugin for extending the QuaternionBase class.\n - \\b EIGEN_SPARSEMATRIX_PLUGIN - filename of plugin for extending the SparseMatrix class.\n - \\b EIGEN_SPARSEMATRIXBASE_PLUGIN - filename of plugin for extending the SparseMatrixBase class.\n - \\b EIGEN_SPARSEVECTOR_PLUGIN - filename of plugin for extending the SparseVector class.\n - \\b EIGEN_TRANSFORM_PLUGIN - filename of plugin for extending the Transform class.\n - \\b EIGEN_VECTORWISEOP_PLUGIN - filename of plugin for extending the VectorwiseOp class.\n\n\\section TopicPreprocessorDirectivesDevelopers Macros for Eigen developers\n\nThese macros are mainly meant for people developing %Eigen and for testing purposes. Even though, they might be useful for power users and the curious for debugging and testing purpose, they \\b should \\b not \\b be \\b used by real-word code.\n\n - \\b EIGEN_DEFAULT_TO_ROW_MAJOR - when defined, the default storage order for matrices becomes row-major\n   instead of column-major. Not defined by default.\n - \\b EIGEN_INTERNAL_DEBUGGING - if defined, enables assertions in %Eigen's internal routines. This is useful\n   for debugging %Eigen itself. Not defined by default.\n - \\b EIGEN_NO_MALLOC - if defined, any request from inside the %Eigen to allocate memory from the heap\n   results in an assertion failure. This is useful to check that some routine does not allocate memory\n   dynamically. Not defined by default.\n - \\b EIGEN_RUNTIME_NO_MALLOC - if defined, a new switch is introduced which can be turned on and off by\n   calling <tt>set_is_malloc_allowed(bool)</tt>. If malloc is not allowed and %Eigen tries to allocate memory\n   dynamically anyway, an assertion failure results. Not defined by default.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/QuickReference.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage QuickRefPage Quick reference guide\n\n\\eigenAutoToc\n\n<hr>\n\n<a href=\"#\" class=\"top\">top</a>\n\\section QuickRef_Headers Modules and Header files\n\nThe Eigen library is divided in a Core module and several additional modules. Each module has a corresponding header file which has to be included in order to use the module. The \\c %Dense and \\c Eigen header files are provided to conveniently gain access to several modules at once.\n\n<table class=\"manual\">\n<tr><th>Module</th><th>Header file</th><th>Contents</th></tr>\n<tr            ><td>\\link Core_Module Core \\endlink</td><td>\\code#include <Eigen/Core>\\endcode</td><td>Matrix and Array classes, basic linear algebra (including triangular and selfadjoint products), array manipulation</td></tr>\n<tr class=\"alt\"><td>\\link Geometry_Module Geometry \\endlink</td><td>\\code#include <Eigen/Geometry>\\endcode</td><td>Transform, Translation, Scaling, Rotation2D and 3D rotations (Quaternion, AngleAxis)</td></tr>\n<tr            ><td>\\link LU_Module LU \\endlink</td><td>\\code#include <Eigen/LU>\\endcode</td><td>Inverse, determinant, LU decompositions with solver (FullPivLU, PartialPivLU)</td></tr>\n<tr class=\"alt\"><td>\\link Cholesky_Module Cholesky \\endlink</td><td>\\code#include <Eigen/Cholesky>\\endcode</td><td>LLT and LDLT Cholesky factorization with solver</td></tr>\n<tr            ><td>\\link Householder_Module Householder \\endlink</td><td>\\code#include <Eigen/Householder>\\endcode</td><td>Householder transformations; this module is used by several linear algebra modules</td></tr>\n<tr class=\"alt\"><td>\\link SVD_Module SVD \\endlink</td><td>\\code#include <Eigen/SVD>\\endcode</td><td>SVD decompositions with least-squares solver (JacobiSVD, BDCSVD)</td></tr>\n<tr            ><td>\\link QR_Module QR \\endlink</td><td>\\code#include <Eigen/QR>\\endcode</td><td>QR decomposition with solver (HouseholderQR, ColPivHouseholderQR, FullPivHouseholderQR)</td></tr>\n<tr class=\"alt\"><td>\\link Eigenvalues_Module Eigenvalues \\endlink</td><td>\\code#include <Eigen/Eigenvalues>\\endcode</td><td>Eigenvalue, eigenvector decompositions (EigenSolver, SelfAdjointEigenSolver, ComplexEigenSolver)</td></tr>\n<tr            ><td>\\link Sparse_Module Sparse \\endlink</td><td>\\code#include <Eigen/Sparse>\\endcode</td><td>%Sparse matrix storage and related basic linear algebra (SparseMatrix, SparseVector) \\n (see \\ref SparseQuickRefPage for details on sparse modules)</td></tr>\n<tr class=\"alt\"><td></td><td>\\code#include <Eigen/Dense>\\endcode</td><td>Includes Core, Geometry, LU, Cholesky, SVD, QR, and Eigenvalues header files</td></tr>\n<tr            ><td></td><td>\\code#include <Eigen/Eigen>\\endcode</td><td>Includes %Dense and %Sparse header files (the whole Eigen library)</td></tr>\n</table>\n\n<a href=\"#\" class=\"top\">top</a>\n\\section QuickRef_Types Array, matrix and vector types\n\n\n\\b Recall: Eigen provides two kinds of dense objects: mathematical matrices and vectors which are both represented by the template class Matrix, and general 1D and 2D arrays represented by the template class Array:\n\\code\ntypedef Matrix<Scalar, RowsAtCompileTime, ColsAtCompileTime, Options> MyMatrixType;\ntypedef Array<Scalar, RowsAtCompileTime, ColsAtCompileTime, Options> MyArrayType;\n\\endcode\n\n\\li \\c Scalar is the scalar type of the coefficients (e.g., \\c float, \\c double, \\c bool, \\c int, etc.).\n\\li \\c RowsAtCompileTime and \\c ColsAtCompileTime are the number of rows and columns of the matrix as known at compile-time or \\c Dynamic.\n\\li \\c Options can be \\c ColMajor or \\c RowMajor, default is \\c ColMajor. (see class Matrix for more options)\n\nAll combinations are allowed: you can have a matrix with a fixed number of rows and a dynamic number of columns, etc. The following are all valid:\n\\code\nMatrix<double, 6, Dynamic>                  // Dynamic number of columns (heap allocation)\nMatrix<double, Dynamic, 2>                  // Dynamic number of rows (heap allocation)\nMatrix<double, Dynamic, Dynamic, RowMajor>  // Fully dynamic, row major (heap allocation)\nMatrix<double, 13, 3>                       // Fully fixed (usually allocated on stack)\n\\endcode\n\nIn most cases, you can simply use one of the convenience typedefs for \\ref matrixtypedefs \"matrices\" and \\ref arraytypedefs \"arrays\". Some examples:\n<table class=\"example\">\n<tr><th>Matrices</th><th>Arrays</th></tr>\n<tr><td>\\code\nMatrix<float,Dynamic,Dynamic>   <=>   MatrixXf\nMatrix<double,Dynamic,1>        <=>   VectorXd\nMatrix<int,1,Dynamic>           <=>   RowVectorXi\nMatrix<float,3,3>               <=>   Matrix3f\nMatrix<float,4,1>               <=>   Vector4f\n\\endcode</td><td>\\code\nArray<float,Dynamic,Dynamic>    <=>   ArrayXXf\nArray<double,Dynamic,1>         <=>   ArrayXd\nArray<int,1,Dynamic>            <=>   RowArrayXi\nArray<float,3,3>                <=>   Array33f\nArray<float,4,1>                <=>   Array4f\n\\endcode</td></tr>\n</table>\n\nConversion between the matrix and array worlds:\n\\code\nArray44f a1, a2;\nMatrix4f m1, m2;\nm1 = a1 * a2;                     // coeffwise product, implicit conversion from array to matrix.\na1 = m1 * m2;                     // matrix product, implicit conversion from matrix to array.\na2 = a1 + m1.array();             // mixing array and matrix is forbidden\nm2 = a1.matrix() + m1;            // and explicit conversion is required.\nArrayWrapper<Matrix4f> m1a(m1);   // m1a is an alias for m1.array(), they share the same coefficients\nMatrixWrapper<Array44f> a1m(a1);\n\\endcode\n\nIn the rest of this document we will use the following symbols to emphasize the features which are specifics to a given kind of object:\n\\li <a name=\"matrixonly\"></a>\\matrixworld linear algebra matrix and vector only\n\\li <a name=\"arrayonly\"></a>\\arrayworld array objects only\n\n\\subsection QuickRef_Basics Basic matrix manipulation\n\n<table class=\"manual\">\n<tr><th></th><th>1D objects</th><th>2D objects</th><th>Notes</th></tr>\n<tr><td>Constructors</td>\n<td>\\code\nVector4d  v4;\nVector2f  v1(x, y);\nArray3i   v2(x, y, z);\nVector4d  v3(x, y, z, w);\n\nVectorXf  v5; // empty object\nArrayXf   v6(size);\n\\endcode</td><td>\\code\nMatrix4f  m1;\n\n\n\n\nMatrixXf  m5; // empty object\nMatrixXf  m6(nb_rows, nb_columns);\n\\endcode</td><td class=\"note\">\nBy default, the coefficients \\n are left uninitialized</td></tr>\n<tr class=\"alt\"><td>Comma initializer</td>\n<td>\\code\nVector3f  v1;     v1 << x, y, z;\nArrayXf   v2(4);  v2 << 1, 2, 3, 4;\n\n\\endcode</td><td>\\code\nMatrix3f  m1;   m1 << 1, 2, 3,\n                      4, 5, 6,\n                      7, 8, 9;\n\\endcode</td><td></td></tr>\n\n<tr><td>Comma initializer (bis)</td>\n<td colspan=\"2\">\n\\include Tutorial_commainit_02.cpp\n</td>\n<td>\noutput:\n\\verbinclude Tutorial_commainit_02.out\n</td>\n</tr>\n\n<tr class=\"alt\"><td>Runtime info</td>\n<td>\\code\nvector.size();\n\nvector.innerStride();\nvector.data();\n\\endcode</td><td>\\code\nmatrix.rows();          matrix.cols();\nmatrix.innerSize();     matrix.outerSize();\nmatrix.innerStride();   matrix.outerStride();\nmatrix.data();\n\\endcode</td><td class=\"note\">Inner/Outer* are storage order dependent</td></tr>\n<tr><td>Compile-time info</td>\n<td colspan=\"2\">\\code\nObjectType::Scalar              ObjectType::RowsAtCompileTime\nObjectType::RealScalar          ObjectType::ColsAtCompileTime\nObjectType::Index               ObjectType::SizeAtCompileTime\n\\endcode</td><td></td></tr>\n<tr class=\"alt\"><td>Resizing</td>\n<td>\\code\nvector.resize(size);\n\n\nvector.resizeLike(other_vector);\nvector.conservativeResize(size);\n\\endcode</td><td>\\code\nmatrix.resize(nb_rows, nb_cols);\nmatrix.resize(Eigen::NoChange, nb_cols);\nmatrix.resize(nb_rows, Eigen::NoChange);\nmatrix.resizeLike(other_matrix);\nmatrix.conservativeResize(nb_rows, nb_cols);\n\\endcode</td><td class=\"note\">no-op if the new sizes match,<br/>otherwise data are lost<br/><br/>resizing with data preservation</td></tr>\n\n<tr><td>Coeff access with \\n range checking</td>\n<td>\\code\nvector(i)     vector.x()\nvector[i]     vector.y()\n              vector.z()\n              vector.w()\n\\endcode</td><td>\\code\nmatrix(i,j)\n\\endcode</td><td class=\"note\">Range checking is disabled if \\n NDEBUG or EIGEN_NO_DEBUG is defined</td></tr>\n\n<tr class=\"alt\"><td>Coeff access without \\n range checking</td>\n<td>\\code\nvector.coeff(i)\nvector.coeffRef(i)\n\\endcode</td><td>\\code\nmatrix.coeff(i,j)\nmatrix.coeffRef(i,j)\n\\endcode</td><td></td></tr>\n\n<tr><td>Assignment/copy</td>\n<td colspan=\"2\">\\code\nobject = expression;\nobject_of_float = expression_of_double.cast<float>();\n\\endcode</td><td class=\"note\">the destination is automatically resized (if possible)</td></tr>\n\n</table>\n\n\\subsection QuickRef_PredefMat Predefined Matrices\n\n<table class=\"manual\">\n<tr>\n  <th>Fixed-size matrix or vector</th>\n  <th>Dynamic-size matrix</th>\n  <th>Dynamic-size vector</th>\n</tr>\n<tr style=\"border-bottom-style: none;\">\n  <td>\n\\code\ntypedef {Matrix3f|Array33f} FixedXD;\nFixedXD x;\n\nx = FixedXD::Zero();\nx = FixedXD::Ones();\nx = FixedXD::Constant(value);\nx = FixedXD::Random();\nx = FixedXD::LinSpaced(size, low, high);\n\nx.setZero();\nx.setOnes();\nx.setConstant(value);\nx.setRandom();\nx.setLinSpaced(size, low, high);\n\\endcode\n  </td>\n  <td>\n\\code\ntypedef {MatrixXf|ArrayXXf} Dynamic2D;\nDynamic2D x;\n\nx = Dynamic2D::Zero(rows, cols);\nx = Dynamic2D::Ones(rows, cols);\nx = Dynamic2D::Constant(rows, cols, value);\nx = Dynamic2D::Random(rows, cols);\nN/A\n\nx.setZero(rows, cols);\nx.setOnes(rows, cols);\nx.setConstant(rows, cols, value);\nx.setRandom(rows, cols);\nN/A\n\\endcode\n  </td>\n  <td>\n\\code\ntypedef {VectorXf|ArrayXf} Dynamic1D;\nDynamic1D x;\n\nx = Dynamic1D::Zero(size);\nx = Dynamic1D::Ones(size);\nx = Dynamic1D::Constant(size, value);\nx = Dynamic1D::Random(size);\nx = Dynamic1D::LinSpaced(size, low, high);\n\nx.setZero(size);\nx.setOnes(size);\nx.setConstant(size, value);\nx.setRandom(size);\nx.setLinSpaced(size, low, high);\n\\endcode\n  </td>\n</tr>\n\n<tr><td colspan=\"3\">Identity and \\link MatrixBase::Unit basis vectors \\endlink \\matrixworld</td></tr>\n<tr style=\"border-bottom-style: none;\">\n  <td>\n\\code\nx = FixedXD::Identity();\nx.setIdentity();\n\nVector3f::UnitX() // 1 0 0\nVector3f::UnitY() // 0 1 0\nVector3f::UnitZ() // 0 0 1\nVector4f::Unit(i)\nx.setUnit(i);\n\\endcode\n  </td>\n  <td>\n\\code\nx = Dynamic2D::Identity(rows, cols);\nx.setIdentity(rows, cols);\n\n\n\nN/A\n\\endcode\n  </td>\n  <td>\\code\nN/A\n\n\nVectorXf::Unit(size,i)\nx.setUnit(size,i);\nVectorXf::Unit(4,1) == Vector4f(0,1,0,0)\n                    == Vector4f::UnitY()\n\\endcode\n  </td>\n</tr>\n</table>\n\nNote that it is allowed to call any of the \\c set* functions to a dynamic-sized vector or matrix without passing new sizes.\nFor instance:\n\\code\nMatrixXi M(3,3);\nM.setIdentity();\n\\endcode\n\n\\subsection QuickRef_Map Mapping external arrays\n\n<table class=\"manual\">\n<tr>\n<td>Contiguous \\n memory</td>\n<td>\\code\nfloat data[] = {1,2,3,4};\nMap<Vector3f> v1(data);       // uses v1 as a Vector3f object\nMap<ArrayXf>  v2(data,3);     // uses v2 as a ArrayXf object\nMap<Array22f> m1(data);       // uses m1 as a Array22f object\nMap<MatrixXf> m2(data,2,2);   // uses m2 as a MatrixXf object\n\\endcode</td>\n</tr>\n<tr>\n<td>Typical usage \\n of strides</td>\n<td>\\code\nfloat data[] = {1,2,3,4,5,6,7,8,9};\nMap<VectorXf,0,InnerStride<2> >  v1(data,3);                      // = [1,3,5]\nMap<VectorXf,0,InnerStride<> >   v2(data,3,InnerStride<>(3));     // = [1,4,7]\nMap<MatrixXf,0,OuterStride<3> >  m2(data,2,3);                    // both lines     |1,4,7|\nMap<MatrixXf,0,OuterStride<> >   m1(data,2,3,OuterStride<>(3));   // are equal to:  |2,5,8|\n\\endcode</td>\n</tr>\n</table>\n\n\n<a href=\"#\" class=\"top\">top</a>\n\\section QuickRef_ArithmeticOperators Arithmetic Operators\n\n<table class=\"manual\">\n<tr><td>\nadd \\n subtract</td><td>\\code\nmat3 = mat1 + mat2;           mat3 += mat1;\nmat3 = mat1 - mat2;           mat3 -= mat1;\\endcode\n</td></tr>\n<tr class=\"alt\"><td>\nscalar product</td><td>\\code\nmat3 = mat1 * s1;             mat3 *= s1;           mat3 = s1 * mat1;\nmat3 = mat1 / s1;             mat3 /= s1;\\endcode\n</td></tr>\n<tr><td>\nmatrix/vector \\n products \\matrixworld</td><td>\\code\ncol2 = mat1 * col1;\nrow2 = row1 * mat1;           row1 *= mat1;\nmat3 = mat1 * mat2;           mat3 *= mat1; \\endcode\n</td></tr>\n<tr class=\"alt\"><td>\ntransposition \\n adjoint \\matrixworld</td><td>\\code\nmat1 = mat2.transpose();      mat1.transposeInPlace();\nmat1 = mat2.adjoint();        mat1.adjointInPlace();\n\\endcode\n</td></tr>\n<tr><td>\n\\link MatrixBase::dot dot \\endlink product \\n inner product \\matrixworld</td><td>\\code\nscalar = vec1.dot(vec2);\nscalar = col1.adjoint() * col2;\nscalar = (col1.adjoint() * col2).value();\\endcode\n</td></tr>\n<tr class=\"alt\"><td>\nouter product \\matrixworld</td><td>\\code\nmat = col1 * col2.transpose();\\endcode\n</td></tr>\n\n<tr><td>\n\\link MatrixBase::norm() norm \\endlink \\n \\link MatrixBase::normalized() normalization \\endlink \\matrixworld</td><td>\\code\nscalar = vec1.norm();         scalar = vec1.squaredNorm()\nvec2 = vec1.normalized();     vec1.normalize(); // inplace \\endcode\n</td></tr>\n\n<tr class=\"alt\"><td>\n\\link MatrixBase::cross() cross product \\endlink \\matrixworld</td><td>\\code\n#include <Eigen/Geometry>\nvec3 = vec1.cross(vec2);\\endcode</td></tr>\n</table>\n\n<a href=\"#\" class=\"top\">top</a>\n\\section QuickRef_Coeffwise Coefficient-wise \\& Array operators\n\nIn addition to the aforementioned operators, Eigen supports numerous coefficient-wise operator and functions.\nMost of them unambiguously makes sense in array-world\\arrayworld. The following operators are readily available for arrays,\nor available through .array() for vectors and matrices:\n\n<table class=\"manual\">\n<tr><td>Arithmetic operators</td><td>\\code\narray1 * array2     array1 / array2     array1 *= array2    array1 /= array2\narray1 + scalar     array1 - scalar     array1 += scalar    array1 -= scalar\n\\endcode</td></tr>\n<tr><td>Comparisons</td><td>\\code\narray1 < array2     array1 > array2     array1 < scalar     array1 > scalar\narray1 <= array2    array1 >= array2    array1 <= scalar    array1 >= scalar\narray1 == array2    array1 != array2    array1 == scalar    array1 != scalar\narray1.min(array2)  array1.max(array2)  array1.min(scalar)  array1.max(scalar)\n\\endcode</td></tr>\n<tr><td>Trigo, power, and \\n misc functions \\n and the STL-like variants</td><td>\\code\narray1.abs2()\narray1.abs()                  abs(array1)\narray1.sqrt()                 sqrt(array1)\narray1.log()                  log(array1)\narray1.log10()                log10(array1)\narray1.exp()                  exp(array1)\narray1.pow(array2)            pow(array1,array2)\narray1.pow(scalar)            pow(array1,scalar)\n                              pow(scalar,array2)\narray1.square()\narray1.cube()\narray1.inverse()\n\narray1.sin()                  sin(array1)\narray1.cos()                  cos(array1)\narray1.tan()                  tan(array1)\narray1.asin()                 asin(array1)\narray1.acos()                 acos(array1)\narray1.atan()                 atan(array1)\narray1.sinh()                 sinh(array1)\narray1.cosh()                 cosh(array1)\narray1.tanh()                 tanh(array1)\narray1.arg()                  arg(array1)\n\narray1.floor()                floor(array1)\narray1.ceil()                 ceil(array1)\narray1.round()                round(aray1)\n\narray1.isFinite()             isfinite(array1)\narray1.isInf()                isinf(array1)\narray1.isNaN()                isnan(array1)\n\\endcode\n</td></tr>\n</table>\n\n\nThe following coefficient-wise operators are available for all kind of expressions (matrices, vectors, and arrays), and for both real or complex scalar types:\n\n<table class=\"manual\">\n<tr><th>Eigen's API</th><th>STL-like APIs\\arrayworld </th><th>Comments</th></tr>\n<tr><td>\\code\nmat1.real()\nmat1.imag()\nmat1.conjugate()\n\\endcode\n</td><td>\\code\nreal(array1)\nimag(array1)\nconj(array1)\n\\endcode\n</td><td>\n\\code\n // read-write, no-op for real expressions\n // read-only for real, read-write for complexes\n // no-op for real expressions\n\\endcode\n</td></tr>\n</table>\n\nSome coefficient-wise operators are readily available for for matrices and vectors through the following cwise* methods:\n<table class=\"manual\">\n<tr><th>Matrix API \\matrixworld</th><th>Via Array conversions</th></tr>\n<tr><td>\\code\nmat1.cwiseMin(mat2)         mat1.cwiseMin(scalar)\nmat1.cwiseMax(mat2)         mat1.cwiseMax(scalar)\nmat1.cwiseAbs2()\nmat1.cwiseAbs()\nmat1.cwiseSqrt()\nmat1.cwiseInverse()\nmat1.cwiseProduct(mat2)\nmat1.cwiseQuotient(mat2)\nmat1.cwiseEqual(mat2)       mat1.cwiseEqual(scalar)\nmat1.cwiseNotEqual(mat2)\n\\endcode\n</td><td>\\code\nmat1.array().min(mat2.array())    mat1.array().min(scalar)\nmat1.array().max(mat2.array())    mat1.array().max(scalar)\nmat1.array().abs2()\nmat1.array().abs()\nmat1.array().sqrt()\nmat1.array().inverse()\nmat1.array() * mat2.array()\nmat1.array() / mat2.array()\nmat1.array() == mat2.array()      mat1.array() == scalar\nmat1.array() != mat2.array()\n\\endcode</td></tr>\n</table>\nThe main difference between the two API is that the one based on cwise* methods returns an expression in the matrix world,\nwhile the second one (based on .array()) returns an array expression.\nRecall that .array() has no cost, it only changes the available API and interpretation of the data.\n\nIt is also very simple to apply any user defined function \\c foo using DenseBase::unaryExpr together with <a href=\"http://en.cppreference.com/w/cpp/utility/functional/ptr_fun\">std::ptr_fun</a> (c++03, deprecated or removed in newer C++ versions), <a href=\"http://en.cppreference.com/w/cpp/utility/functional/ref\">std::ref</a> (c++11), or <a href=\"http://en.cppreference.com/w/cpp/language/lambda\">lambdas</a> (c++11):\n\\code\nmat1.unaryExpr(std::ptr_fun(foo));\nmat1.unaryExpr(std::ref(foo));\nmat1.unaryExpr([](double x) { return foo(x); });\n\\endcode\n\nPlease note that it's not possible to pass a raw function pointer to \\c unaryExpr, so please warp it as shown above.\n\n<a href=\"#\" class=\"top\">top</a>\n\\section QuickRef_Reductions Reductions\n\nEigen provides several reduction methods such as:\n\\link DenseBase::minCoeff() minCoeff() \\endlink, \\link DenseBase::maxCoeff() maxCoeff() \\endlink,\n\\link DenseBase::sum() sum() \\endlink, \\link DenseBase::prod() prod() \\endlink,\n\\link MatrixBase::trace() trace() \\endlink \\matrixworld,\n\\link MatrixBase::norm() norm() \\endlink \\matrixworld, \\link MatrixBase::squaredNorm() squaredNorm() \\endlink \\matrixworld,\n\\link DenseBase::all() all() \\endlink, and \\link DenseBase::any() any() \\endlink.\nAll reduction operations can be done matrix-wise,\n\\link DenseBase::colwise() column-wise \\endlink or\n\\link DenseBase::rowwise() row-wise \\endlink. Usage example:\n<table class=\"manual\">\n<tr><td rowspan=\"3\" style=\"border-right-style:dashed;vertical-align:middle\">\\code\n      5 3 1\nmat = 2 7 8\n      9 4 6 \\endcode\n</td> <td>\\code mat.minCoeff(); \\endcode</td><td>\\code 1 \\endcode</td></tr>\n<tr class=\"alt\"><td>\\code mat.colwise().minCoeff(); \\endcode</td><td>\\code 2 3 1 \\endcode</td></tr>\n<tr style=\"vertical-align:middle\"><td>\\code mat.rowwise().minCoeff(); \\endcode</td><td>\\code\n1\n2\n4\n\\endcode</td></tr>\n</table>\n\nSpecial versions of \\link DenseBase::minCoeff(IndexType*,IndexType*) const minCoeff \\endlink and \\link DenseBase::maxCoeff(IndexType*,IndexType*) const maxCoeff \\endlink:\n\\code\nint i, j;\ns = vector.minCoeff(&i);        // s == vector[i]\ns = matrix.maxCoeff(&i, &j);    // s == matrix(i,j)\n\\endcode\nTypical use cases of all() and any():\n\\code\nif((array1 > 0).all()) ...      // if all coefficients of array1 are greater than 0 ...\nif((array1 < array2).any()) ... // if there exist a pair i,j such that array1(i,j) < array2(i,j) ...\n\\endcode\n\n\n<a href=\"#\" class=\"top\">top</a>\\section QuickRef_Blocks Sub-matrices\n\n<div class=\"warningbox\">\n<strong>PLEASE HELP US IMPROVING THIS SECTION.</strong>\n%Eigen 3.4 supports a much improved API for sub-matrices, including,\nslicing and indexing from arrays: \\ref TutorialSlicingIndexing\n</div>\n\nRead-write access to a \\link DenseBase::col(Index) column \\endlink\nor a \\link DenseBase::row(Index) row \\endlink of a matrix (or array):\n\\code\nmat1.row(i) = mat2.col(j);\nmat1.col(j1).swap(mat1.col(j2));\n\\endcode\n\nRead-write access to sub-vectors:\n<table class=\"manual\">\n<tr>\n<th>Default versions</th>\n<th>Optimized versions when the size \\n is known at compile time</th></tr>\n<th></th>\n\n<tr><td>\\code vec1.head(n)\\endcode</td><td>\\code vec1.head<n>()\\endcode</td><td>the first \\c n coeffs </td></tr>\n<tr><td>\\code vec1.tail(n)\\endcode</td><td>\\code vec1.tail<n>()\\endcode</td><td>the last \\c n coeffs </td></tr>\n<tr><td>\\code vec1.segment(pos,n)\\endcode</td><td>\\code vec1.segment<n>(pos)\\endcode</td>\n    <td>the \\c n coeffs in the \\n range [\\c pos : \\c pos + \\c n - 1]</td></tr>\n<tr class=\"alt\"><td colspan=\"3\">\n\nRead-write access to sub-matrices:</td></tr>\n<tr>\n  <td>\\code mat1.block(i,j,rows,cols)\\endcode\n      \\link DenseBase::block(Index,Index,Index,Index) (more) \\endlink</td>\n  <td>\\code mat1.block<rows,cols>(i,j)\\endcode\n      \\link DenseBase::block(Index,Index) (more) \\endlink</td>\n  <td>the \\c rows x \\c cols sub-matrix \\n starting from position (\\c i,\\c j)</td></tr>\n<tr><td>\\code\n mat1.topLeftCorner(rows,cols)\n mat1.topRightCorner(rows,cols)\n mat1.bottomLeftCorner(rows,cols)\n mat1.bottomRightCorner(rows,cols)\\endcode\n <td>\\code\n mat1.topLeftCorner<rows,cols>()\n mat1.topRightCorner<rows,cols>()\n mat1.bottomLeftCorner<rows,cols>()\n mat1.bottomRightCorner<rows,cols>()\\endcode\n <td>the \\c rows x \\c cols sub-matrix \\n taken in one of the four corners</td></tr>\n <tr><td>\\code\n mat1.topRows(rows)\n mat1.bottomRows(rows)\n mat1.leftCols(cols)\n mat1.rightCols(cols)\\endcode\n <td>\\code\n mat1.topRows<rows>()\n mat1.bottomRows<rows>()\n mat1.leftCols<cols>()\n mat1.rightCols<cols>()\\endcode\n <td>specialized versions of block() \\n when the block fit two corners</td></tr>\n</table>\n\n\n\n<a href=\"#\" class=\"top\">top</a>\\section QuickRef_Misc Miscellaneous operations\n\n<div class=\"warningbox\">\n<strong>PLEASE HELP US IMPROVING THIS SECTION.</strong>\n%Eigen 3.4 supports a new API for reshaping: \\ref TutorialReshape\n</div>\n\n\\subsection QuickRef_Reverse Reverse\nVectors, rows, and/or columns of a matrix can be reversed (see DenseBase::reverse(), DenseBase::reverseInPlace(), VectorwiseOp::reverse()).\n\\code\nvec.reverse()           mat.colwise().reverse()   mat.rowwise().reverse()\nvec.reverseInPlace()\n\\endcode\n\n\\subsection QuickRef_Replicate Replicate\nVectors, matrices, rows, and/or columns can be replicated in any direction (see DenseBase::replicate(), VectorwiseOp::replicate())\n\\code\nvec.replicate(times)                                          vec.replicate<Times>\nmat.replicate(vertical_times, horizontal_times)               mat.replicate<VerticalTimes, HorizontalTimes>()\nmat.colwise().replicate(vertical_times, horizontal_times)     mat.colwise().replicate<VerticalTimes, HorizontalTimes>()\nmat.rowwise().replicate(vertical_times, horizontal_times)     mat.rowwise().replicate<VerticalTimes, HorizontalTimes>()\n\\endcode\n\n\n<a href=\"#\" class=\"top\">top</a>\\section QuickRef_DiagTriSymm Diagonal, Triangular, and Self-adjoint matrices\n(matrix world \\matrixworld)\n\n\\subsection QuickRef_Diagonal Diagonal matrices\n\n<table class=\"example\">\n<tr><th>Operation</th><th>Code</th></tr>\n<tr><td>\nview a vector \\link MatrixBase::asDiagonal() as a diagonal matrix \\endlink \\n </td><td>\\code\nmat1 = vec1.asDiagonal();\\endcode\n</td></tr>\n<tr><td>\nDeclare a diagonal matrix</td><td>\\code\nDiagonalMatrix<Scalar,SizeAtCompileTime> diag1(size);\ndiag1.diagonal() = vector;\\endcode\n</td></tr>\n<tr><td>Access the \\link MatrixBase::diagonal() diagonal \\endlink and \\link MatrixBase::diagonal(Index) super/sub diagonals \\endlink of a matrix as a vector (read/write)</td>\n <td>\\code\nvec1 = mat1.diagonal();        mat1.diagonal() = vec1;      // main diagonal\nvec1 = mat1.diagonal(+n);      mat1.diagonal(+n) = vec1;    // n-th super diagonal\nvec1 = mat1.diagonal(-n);      mat1.diagonal(-n) = vec1;    // n-th sub diagonal\nvec1 = mat1.diagonal<1>();     mat1.diagonal<1>() = vec1;   // first super diagonal\nvec1 = mat1.diagonal<-2>();    mat1.diagonal<-2>() = vec1;  // second sub diagonal\n\\endcode</td>\n</tr>\n\n<tr><td>Optimized products and inverse</td>\n <td>\\code\nmat3  = scalar * diag1 * mat1;\nmat3 += scalar * mat1 * vec1.asDiagonal();\nmat3 = vec1.asDiagonal().inverse() * mat1\nmat3 = mat1 * diag1.inverse()\n\\endcode</td>\n</tr>\n\n</table>\n\n\\subsection QuickRef_TriangularView Triangular views\n\nTriangularView gives a view on a triangular part of a dense matrix and allows to perform optimized operations on it. The opposite triangular part is never referenced and can be used to store other information.\n\n\\note The .triangularView() template member function requires the \\c template keyword if it is used on an\nobject of a type that depends on a template parameter; see \\ref TopicTemplateKeyword for details.\n\n<table class=\"example\">\n<tr><th>Operation</th><th>Code</th></tr>\n<tr><td>\nReference to a triangular with optional \\n\nunit or null diagonal (read/write):\n</td><td>\\code\nm.triangularView<Xxx>()\n\\endcode \\n\n\\c Xxx = ::Upper, ::Lower, ::StrictlyUpper, ::StrictlyLower, ::UnitUpper, ::UnitLower\n</td></tr>\n<tr><td>\nWriting to a specific triangular part:\\n (only the referenced triangular part is evaluated)\n</td><td>\\code\nm1.triangularView<Eigen::Lower>() = m2 + m3 \\endcode\n</td></tr>\n<tr><td>\nConversion to a dense matrix setting the opposite triangular part to zero:\n</td><td>\\code\nm2 = m1.triangularView<Eigen::UnitUpper>()\\endcode\n</td></tr>\n<tr><td>\nProducts:\n</td><td>\\code\nm3 += s1 * m1.adjoint().triangularView<Eigen::UnitUpper>() * m2\nm3 -= s1 * m2.conjugate() * m1.adjoint().triangularView<Eigen::Lower>() \\endcode\n</td></tr>\n<tr><td>\nSolving linear equations:\\n\n\\f$ M_2 := L_1^{-1} M_2 \\f$ \\n\n\\f$ M_3 := {L_1^*}^{-1} M_3 \\f$ \\n\n\\f$ M_4 := M_4 U_1^{-1} \\f$\n</td><td>\\n \\code\nL1.triangularView<Eigen::UnitLower>().solveInPlace(M2)\nL1.triangularView<Eigen::Lower>().adjoint().solveInPlace(M3)\nU1.triangularView<Eigen::Upper>().solveInPlace<OnTheRight>(M4)\\endcode\n</td></tr>\n</table>\n\n\\subsection QuickRef_SelfadjointMatrix Symmetric/selfadjoint views\n\nJust as for triangular matrix, you can reference any triangular part of a square matrix to see it as a selfadjoint\nmatrix and perform special and optimized operations. Again the opposite triangular part is never referenced and can be\nused to store other information.\n\n\\note The .selfadjointView() template member function requires the \\c template keyword if it is used on an\nobject of a type that depends on a template parameter; see \\ref TopicTemplateKeyword for details.\n\n<table class=\"example\">\n<tr><th>Operation</th><th>Code</th></tr>\n<tr><td>\nConversion to a dense matrix:\n</td><td>\\code\nm2 = m.selfadjointView<Eigen::Lower>();\\endcode\n</td></tr>\n<tr><td>\nProduct with another general matrix or vector:\n</td><td>\\code\nm3  = s1 * m1.conjugate().selfadjointView<Eigen::Upper>() * m3;\nm3 -= s1 * m3.adjoint() * m1.selfadjointView<Eigen::Lower>();\\endcode\n</td></tr>\n<tr><td>\nRank 1 and rank K update: \\n\n\\f$ upper(M_1) \\mathrel{{+}{=}} s_1 M_2 M_2^* \\f$ \\n\n\\f$ lower(M_1) \\mathbin{{-}{=}} M_2^* M_2 \\f$\n</td><td>\\n \\code\nM1.selfadjointView<Eigen::Upper>().rankUpdate(M2,s1);\nM1.selfadjointView<Eigen::Lower>().rankUpdate(M2.adjoint(),-1); \\endcode\n</td></tr>\n<tr><td>\nRank 2 update: (\\f$ M \\mathrel{{+}{=}} s u v^* + s v u^* \\f$)\n</td><td>\\code\nM.selfadjointView<Eigen::Upper>().rankUpdate(u,v,s);\n\\endcode\n</td></tr>\n<tr><td>\nSolving linear equations:\\n(\\f$ M_2 := M_1^{-1} M_2 \\f$)\n</td><td>\\code\n// via a standard Cholesky factorization\nm2 = m1.selfadjointView<Eigen::Upper>().llt().solve(m2);\n// via a Cholesky factorization with pivoting\nm2 = m1.selfadjointView<Eigen::Lower>().ldlt().solve(m2);\n\\endcode\n</td></tr>\n</table>\n\n*/\n\n/*\n<table class=\"tutorial_code\">\n<tr><td>\n\\link MatrixBase::asDiagonal() make a diagonal matrix \\endlink \\n from a vector </td><td>\\code\nmat1 = vec1.asDiagonal();\\endcode\n</td></tr>\n<tr><td>\nDeclare a diagonal matrix</td><td>\\code\nDiagonalMatrix<Scalar,SizeAtCompileTime> diag1(size);\ndiag1.diagonal() = vector;\\endcode\n</td></tr>\n<tr><td>Access \\link MatrixBase::diagonal() the diagonal and super/sub diagonals of a matrix \\endlink as a vector (read/write)</td>\n <td>\\code\nvec1 = mat1.diagonal();            mat1.diagonal() = vec1;      // main diagonal\nvec1 = mat1.diagonal(+n);          mat1.diagonal(+n) = vec1;    // n-th super diagonal\nvec1 = mat1.diagonal(-n);          mat1.diagonal(-n) = vec1;    // n-th sub diagonal\nvec1 = mat1.diagonal<1>();         mat1.diagonal<1>() = vec1;   // first super diagonal\nvec1 = mat1.diagonal<-2>();        mat1.diagonal<-2>() = vec1;  // second sub diagonal\n\\endcode</td>\n</tr>\n\n<tr><td>View on a triangular part of a matrix (read/write)</td>\n <td>\\code\nmat2 = mat1.triangularView<Xxx>();\n// Xxx = Upper, Lower, StrictlyUpper, StrictlyLower, UnitUpper, UnitLower\nmat1.triangularView<Upper>() = mat2 + mat3; // only the upper part is evaluated and referenced\n\\endcode</td></tr>\n\n<tr><td>View a triangular part as a symmetric/self-adjoint matrix (read/write)</td>\n <td>\\code\nmat2 = mat1.selfadjointView<Xxx>();     // Xxx = Upper or Lower\nmat1.selfadjointView<Upper>() = mat2 + mat2.adjoint();  // evaluated and write to the upper triangular part only\n\\endcode</td></tr>\n\n</table>\n\nOptimized products:\n\\code\nmat3 += scalar * vec1.asDiagonal() * mat1\nmat3 += scalar * mat1 * vec1.asDiagonal()\nmat3.noalias() += scalar * mat1.triangularView<Xxx>() * mat2\nmat3.noalias() += scalar * mat2 * mat1.triangularView<Xxx>()\nmat3.noalias() += scalar * mat1.selfadjointView<Upper or Lower>() * mat2\nmat3.noalias() += scalar * mat2 * mat1.selfadjointView<Upper or Lower>()\nmat1.selfadjointView<Upper or Lower>().rankUpdate(mat2);\nmat1.selfadjointView<Upper or Lower>().rankUpdate(mat2.adjoint(), scalar);\n\\endcode\n\nInverse products: (all are optimized)\n\\code\nmat3 = vec1.asDiagonal().inverse() * mat1\nmat3 = mat1 * diag1.inverse()\nmat1.triangularView<Xxx>().solveInPlace(mat2)\nmat1.triangularView<Xxx>().solveInPlace<OnTheRight>(mat2)\nmat2 = mat1.selfadjointView<Upper or Lower>().llt().solve(mat2)\n\\endcode\n\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/QuickStartGuide.dox",
    "content": "namespace Eigen {\n\n/** \\page GettingStarted Getting started\n\n\\eigenAutoToc\n\nThis is a very short guide on how to get started with Eigen. It has a dual purpose. It serves as a minimal introduction to the Eigen library for people who want to start coding as soon as possible. You can also read this page as the first part of the Tutorial, which explains the library in more detail; in this case you will continue with \\ref TutorialMatrixClass.\n\n\\section GettingStartedInstallation How to \"install\" Eigen?\n\nIn order to use Eigen, you just need to download and extract Eigen's source code (see <a href=\"http://eigen.tuxfamily.org/index.php?title=Main_Page#Download\">the wiki</a> for download instructions). In fact, the header files in the \\c Eigen subdirectory are the only files required to compile programs using Eigen. The header files are the same for all platforms. It is not necessary to use CMake or install anything.\n\n\n\\section GettingStartedFirstProgram A simple first program\n\nHere is a rather simple program to get you started.\n\n\\include QuickStart_example.cpp\n\nWe will explain the program after telling you how to compile it.\n\n\n\\section GettingStartedCompiling Compiling and running your first program\n\nThere is no library to link to. The only thing that you need to keep in mind when compiling the above program is that the compiler must be able to find the Eigen header files. The directory in which you placed Eigen's source code must be in the include path. With GCC you use the -I option to achieve this, so you can compile the program with a command like this:\n\n\\code g++ -I /path/to/eigen/ my_program.cpp -o my_program \\endcode\n\nOn Linux or Mac OS X, another option is to symlink or copy the Eigen folder into /usr/local/include/. This way, you can compile the program with:\n\n\\code g++ my_program.cpp -o my_program \\endcode\n\nWhen you run the program, it produces the following output:\n\n\\include QuickStart_example.out\n\n\n\\section GettingStartedExplanation Explanation of the first program\n\nThe Eigen header files define many types, but for simple applications it may be enough to use only the \\c MatrixXd type. This represents a matrix of arbitrary size (hence the \\c X in \\c MatrixXd), in which every entry is a \\c double (hence the \\c d in \\c MatrixXd). See the \\ref QuickRef_Types \"quick reference guide\" for an overview of the different types you can use to represent a matrix.\n\nThe \\c Eigen/Dense header file defines all member functions for the MatrixXd type and related types (see also the \\ref QuickRef_Headers \"table of header files\"). All classes and functions defined in this header file (and other Eigen header files) are in the \\c Eigen namespace. \n\nThe first line of the \\c main function declares a variable of type \\c MatrixXd and specifies that it is a matrix with 2 rows and 2 columns (the entries are not initialized). The statement <tt>m(0,0) = 3</tt> sets the entry in the top-left corner to 3. You need to use round parentheses to refer to entries in the matrix. As usual in computer science, the index of the first index is 0, as opposed to the convention in mathematics that the first index is 1.\n\nThe following three statements sets the other three entries. The final line outputs the matrix \\c m to the standard output stream.\n\n\n\\section GettingStartedExample2 Example 2: Matrices and vectors\n\nHere is another example, which combines matrices with vectors. Concentrate on the left-hand program for now; we will talk about the right-hand program later.\n\n<table class=\"manual\">\n<tr><th>Size set at run time:</th><th>Size set at compile time:</th></tr>\n<tr><td>\n\\include QuickStart_example2_dynamic.cpp\n</td>\n<td>\n\\include QuickStart_example2_fixed.cpp\n</td></tr></table>\n\nThe output is as follows:\n\n\\include QuickStart_example2_dynamic.out\n\n\n\\section GettingStartedExplanation2 Explanation of the second example\n\nThe second example starts by declaring a 3-by-3 matrix \\c m which is initialized using the \\link DenseBase::Random(Index,Index) Random() \\endlink method with random values between -1 and 1. The next line applies a linear mapping such that the values are between 10 and 110. The function call \\link DenseBase::Constant(Index,Index,const Scalar&) MatrixXd::Constant\\endlink(3,3,1.2) returns a 3-by-3 matrix expression having all coefficients equal to 1.2. The rest is standard arithmetic.\n\nThe next line of the \\c main function introduces a new type: \\c VectorXd. This represents a (column) vector of arbitrary size. Here, the vector \\c v is created to contain \\c 3 coefficients which are left uninitialized. The one but last line uses the so-called comma-initializer, explained in \\ref TutorialAdvancedInitialization, to set all coefficients of the vector \\c v to be as follows:\n\n\\f[\nv =\n\\begin{bmatrix}\n  1 \\\\\n  2 \\\\\n  3\n\\end{bmatrix}.\n\\f]\n\nThe final line of the program multiplies the matrix \\c m with the vector \\c v and outputs the result.\n\nNow look back at the second example program. We presented two versions of it. In the version in the left column, the matrix is of type \\c MatrixXd which represents matrices of arbitrary size. The version in the right column is similar, except that the matrix is of type \\c Matrix3d, which represents matrices of a fixed size (here 3-by-3). Because the type already encodes the size of the matrix, it is not necessary to specify the size in the constructor; compare <tt>MatrixXd m(3,3)</tt> with <tt>Matrix3d m</tt>. Similarly, we have \\c VectorXd on the left (arbitrary size) versus \\c Vector3d on the right (fixed size). Note that here the coefficients of vector \\c v are directly set in the constructor, though the same syntax of the left example could be used too.\n\nThe use of fixed-size matrices and vectors has two advantages. The compiler emits better (faster) code because it knows the size of the matrices and vectors. Specifying the size in the type also allows for more rigorous checking at compile-time. For instance, the compiler will complain if you try to multiply a \\c Matrix4d (a 4-by-4 matrix) with a \\c Vector3d (a vector of size 3). However, the use of many types increases compilation time and the size of the executable. The size of the matrix may also not be known at compile-time. A rule of thumb is to use fixed-size matrices for size 4-by-4 and smaller.\n\n\n\\section GettingStartedConclusion Where to go from here?\n\nIt's worth taking the time to read the  \\ref TutorialMatrixClass \"long tutorial\".\n\nHowever if you think you don't need it, you can directly use the classes documentation and our \\ref QuickRefPage.\n\n\\li \\b Next: \\ref TutorialMatrixClass\n\n*/\n\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/SparseLinearSystems.dox",
    "content": "namespace Eigen {\n/** \\eigenManualPage TopicSparseSystems Solving Sparse Linear Systems\nIn Eigen, there are several methods available to solve linear systems when the coefficient matrix is sparse. Because of the special representation of this class of matrices, special care should be taken in order to get a good performance. See \\ref TutorialSparse for a detailed introduction about sparse matrices in Eigen. This page lists the sparse solvers available in Eigen. The main steps that are common to all these linear solvers are introduced as well. Depending on the properties of the matrix, the desired accuracy, the end-user is able to tune those steps in order to improve the performance of its code. Note that it is not required to know deeply what's hiding behind these steps: the last section presents a benchmark routine that can be easily used to get an insight on the performance of all the available solvers. \n\n\\eigenAutoToc\n\n\\section TutorialSparseSolverList List of sparse solvers\n\n%Eigen currently provides a wide set of built-in solvers, as well as wrappers to external solver libraries.\nThey are summarized in the following tables:\n\n\\subsection TutorialSparseSolverList_Direct Built-in direct solvers\n\n<table class=\"manual\">\n<tr><th>Class</th><th>Solver kind</th><th>Matrix kind</th><th>Features related to performance</th>\n    <th>License</th><th class=\"width20em\"><p>Notes</p></th></tr>\n\n<tr><td>SimplicialLLT \\n <tt>\\#include<Eigen/\\link SparseCholesky_Module SparseCholesky\\endlink></tt></td><td>Direct LLt factorization</td><td>SPD</td><td>Fill-in reducing</td>\n    <td>LGPL</td>\n    <td>SimplicialLDLT is often preferable</td></tr>\n\n<tr><td>SimplicialLDLT \\n <tt>\\#include<Eigen/\\link SparseCholesky_Module SparseCholesky\\endlink></tt></td><td>Direct LDLt factorization</td><td>SPD</td><td>Fill-in reducing</td>\n    <td>LGPL</td>\n    <td>Recommended for very sparse and not too large problems (e.g., 2D Poisson eq.)</td></tr>\n\n<tr><td>SparseLU \\n <tt>\\#include<Eigen/\\link SparseLU_Module SparseLU\\endlink></tt></td> <td>LU factorization </td>\n    <td>Square </td><td>Fill-in reducing, Leverage fast dense algebra</td>\n    <td>MPL2</td>\n    <td>optimized for small and large problems with irregular patterns </td></tr>\n\n<tr><td>SparseQR \\n <tt>\\#include<Eigen/\\link SparseQR_Module SparseQR\\endlink></tt></td> <td> QR factorization</td>\n    <td>Any, rectangular</td><td> Fill-in reducing</td>\n    <td>MPL2</td>\n    <td>recommended for least-square problems, has a basic rank-revealing feature</td></tr>\n </table>\n\n\\subsection TutorialSparseSolverList_Iterative Built-in iterative solvers\n\n<table class=\"manual\">\n<tr><th>Class</th><th>Solver kind</th><th>Matrix kind</th><th>Supported preconditioners, [default]</th>\n    <th>License</th><th class=\"width20em\"><p>Notes</p></th></tr>\n\n<tr><td>ConjugateGradient \\n <tt>\\#include<Eigen/\\link IterativeLinearSolvers_Module IterativeLinearSolvers\\endlink></tt></td> <td>Classic iterative CG</td><td>SPD</td>\n    <td>IdentityPreconditioner, [DiagonalPreconditioner], IncompleteCholesky</td>\n    <td>MPL2</td>\n    <td>Recommended for large symmetric problems (e.g., 3D Poisson eq.)</td></tr>\n\n<tr><td>LeastSquaresConjugateGradient \\n <tt>\\#include<Eigen/\\link IterativeLinearSolvers_Module IterativeLinearSolvers\\endlink></tt></td><td>CG for rectangular least-square problem</td><td>Rectangular</td>\n    <td>IdentityPreconditioner, [LeastSquareDiagonalPreconditioner]</td>\n    <td>MPL2</td>\n    <td>Solve for min |A'Ax-b|^2 without forming A'A</td></tr>\n\n<tr><td>BiCGSTAB \\n <tt>\\#include<Eigen/\\link IterativeLinearSolvers_Module IterativeLinearSolvers\\endlink></tt></td><td>Iterative stabilized bi-conjugate gradient</td><td>Square</td>\n    <td>IdentityPreconditioner, [DiagonalPreconditioner], IncompleteLUT</td>\n    <td>MPL2</td>\n    <td>To speedup the convergence, try it with the \\ref IncompleteLUT preconditioner.</td></tr>\n</table>\n\n\\subsection TutorialSparseSolverList_Wrapper Wrappers to external solvers\n\n<table class=\"manual\">\n<tr><th>Class</th><th>Module</th><th>Solver kind</th><th>Matrix kind</th><th>Features related to performance</th>\n    <th>Dependencies,License</th><th class=\"width20em\"><p>Notes</p></th></tr>\n<tr><td>PastixLLT \\n PastixLDLT \\n PastixLU</td><td>\\link PaStiXSupport_Module PaStiXSupport \\endlink</td><td>Direct LLt, LDLt, LU factorizations</td><td>SPD \\n SPD \\n Square</td><td>Fill-in reducing, Leverage fast dense algebra, Multithreading</td>\n    <td>Requires the <a href=\"http://pastix.gforge.inria.fr\">PaStiX</a> package, \\b CeCILL-C </td>\n    <td>optimized for tough problems and symmetric patterns</td></tr>\n<tr><td>CholmodSupernodalLLT</td><td>\\link CholmodSupport_Module CholmodSupport \\endlink</td><td>Direct LLt factorization</td><td>SPD</td><td>Fill-in reducing, Leverage fast dense algebra</td>\n    <td>Requires the <a href=\"http://www.suitesparse.com\">SuiteSparse</a> package, \\b GPL </td>\n    <td></td></tr>\n<tr><td>UmfPackLU</td><td>\\link UmfPackSupport_Module UmfPackSupport \\endlink</td><td>Direct LU factorization</td><td>Square</td><td>Fill-in reducing, Leverage fast dense algebra</td>\n    <td>Requires the <a href=\"http://www.suitesparse.com\">SuiteSparse</a> package, \\b GPL </td>\n    <td></td></tr>\n<tr><td>KLU</td><td>\\link KLUSupport_Module KLUSupport \\endlink</td><td>Direct LU factorization</td><td>Square</td><td>Fill-in reducing, suitted for circuit simulation</td>\n    <td>Requires the <a href=\"http://www.suitesparse.com\">SuiteSparse</a> package, \\b GPL </td>\n    <td></td></tr>\n<tr><td>SuperLU</td><td>\\link SuperLUSupport_Module SuperLUSupport \\endlink</td><td>Direct LU factorization</td><td>Square</td><td>Fill-in reducing, Leverage fast dense algebra</td>\n    <td>Requires the <a href=\"http://crd-legacy.lbl.gov/~xiaoye/SuperLU/\">SuperLU</a> library, (BSD-like)</td>\n    <td></td></tr>\n<tr><td>SPQR</td><td>\\link SPQRSupport_Module SPQRSupport \\endlink  </td> <td> QR factorization </td> \n    <td> Any, rectangular</td><td>fill-in reducing, multithreaded, fast dense algebra</td>\n    <td> requires the <a href=\"http://www.suitesparse.com\">SuiteSparse</a> package, \\b GPL </td><td>recommended for linear least-squares problems, has a rank-revealing feature</tr>\n<tr><td>PardisoLLT \\n PardisoLDLT \\n PardisoLU</td><td>\\link PardisoSupport_Module PardisoSupport \\endlink</td><td>Direct LLt, LDLt, LU factorizations</td><td>SPD \\n SPD \\n Square</td><td>Fill-in reducing, Leverage fast dense algebra, Multithreading</td>\n    <td>Requires the <a href=\"http://eigen.tuxfamily.org/Counter/redirect_to_mkl.php\">Intel MKL</a> package, \\b Proprietary </td>\n    <td>optimized for tough problems patterns, see also \\link TopicUsingIntelMKL using MKL with Eigen \\endlink</td></tr>\n</table>\n\nHere \\c SPD means symmetric positive definite.\n\n\\section TutorialSparseSolverConcept Sparse solver concept\n\nAll these solvers follow the same general concept.\nHere is a typical and general example:\n\\code\n#include <Eigen/RequiredModuleName>\n// ...\nSparseMatrix<double> A;\n// fill A\nVectorXd b, x;\n// fill b\n// solve Ax = b\nSolverClassName<SparseMatrix<double> > solver;\nsolver.compute(A);\nif(solver.info()!=Success) {\n  // decomposition failed\n  return;\n}\nx = solver.solve(b);\nif(solver.info()!=Success) {\n  // solving failed\n  return;\n}\n// solve for another right hand side:\nx1 = solver.solve(b1);\n\\endcode\n\nFor \\c SPD solvers, a second optional template argument allows to specify which triangular part have to be used, e.g.:\n\n\\code\n#include <Eigen/IterativeLinearSolvers>\n\nConjugateGradient<SparseMatrix<double>, Eigen::Upper> solver;\nx = solver.compute(A).solve(b);\n\\endcode\nIn the above example, only the upper triangular part of the input matrix A is considered for solving. The opposite triangle might either be empty or contain arbitrary values.\n\nIn the case where multiple problems with the same sparsity pattern have to be solved, then the \"compute\" step can be decomposed as follow:\n\\code\nSolverClassName<SparseMatrix<double> > solver;\nsolver.analyzePattern(A);   // for this step the numerical values of A are not used\nsolver.factorize(A);\nx1 = solver.solve(b1);\nx2 = solver.solve(b2);\n...\nA = ...;                    // modify the values of the nonzeros of A, the nonzeros pattern must stay unchanged\nsolver.factorize(A);\nx1 = solver.solve(b1);\nx2 = solver.solve(b2);\n...\n\\endcode\nThe compute() method is equivalent to calling both analyzePattern() and factorize().\n\nEach solver provides some specific features, such as determinant, access to the factors, controls of the iterations, and so on.\nMore details are available in the documentations of the respective classes.\n\nFinally, most of the iterative solvers, can also be used in a \\b matrix-free context, see the following \\link MatrixfreeSolverExample example \\endlink.\n\n\\section TheSparseCompute The Compute Step\nIn the compute() function, the matrix is generally factorized: LLT for self-adjoint matrices, LDLT for general hermitian matrices, LU for non hermitian matrices and QR for rectangular matrices. These are the results of using direct solvers. For this class of solvers precisely, the compute step is further subdivided into analyzePattern() and factorize(). \n\nThe goal of analyzePattern() is to reorder the nonzero elements of the matrix, such that the factorization step creates less fill-in. This step exploits only the structure of the matrix. Hence, the results of this step can be used for other linear systems where the matrix has the same structure. Note however that sometimes, some external solvers (like SuperLU) require that the values of the matrix are set in this step, for instance to equilibrate the rows and columns of the matrix. In this situation, the results of this step should not be used with other matrices.\n\nEigen provides a limited set of methods to reorder the matrix in this step, either built-in (COLAMD, AMD) or external (METIS). These methods are set in template parameter list of the solver :\n\\code\nDirectSolverClassName<SparseMatrix<double>, OrderingMethod<IndexType> > solver;\n\\endcode \n\nSee the \\link OrderingMethods_Module OrderingMethods module \\endlink for the list of available methods and the associated options. \n\nIn factorize(), the factors of the coefficient matrix are computed. This step should be called each time the values of the matrix change. However, the structural pattern of the matrix should not change between multiple calls. \n\nFor iterative solvers, the compute step is used to eventually setup a preconditioner. For instance, with the ILUT preconditioner, the incomplete factors L and U are computed in this step. Remember that, basically, the goal of the preconditioner is to speedup the convergence of an iterative method by solving a modified linear system where the coefficient matrix has more clustered eigenvalues. For real problems, an iterative solver should always be used with a preconditioner. In Eigen, a preconditioner is  selected by simply adding it as a template parameter to the iterative solver object. \n\\code\nIterativeSolverClassName<SparseMatrix<double>, PreconditionerName<SparseMatrix<double> > solver; \n\\endcode\nThe member function preconditioner() returns a read-write reference to the preconditioner \n to directly interact with it. See the \\link IterativeLinearSolvers_Module Iterative solvers module \\endlink and the documentation of each class for the list of available methods.\n\n\\section TheSparseSolve The Solve step\nThe solve() function computes the solution of the linear systems with one or many right hand sides.\n\\code\nX = solver.solve(B);\n\\endcode \nHere, B  can be a vector or a matrix where the columns form the different right hand sides. The solve() function can be called several times as well, for instance when all the right hand sides are not available at once. \n\\code\nx1 = solver.solve(b1);\n// Get the second right hand side b2\nx2 = solver.solve(b2); \n//  ...\n\\endcode\nFor direct methods, the solution are computed at the machine precision. Sometimes, the solution need not be too accurate. In this case, the iterative methods are more suitable and the desired accuracy can be set before the solve step using \\b setTolerance(). For all the available functions, please, refer to the documentation of the \\link IterativeLinearSolvers_Module Iterative solvers module \\endlink. \n\n\\section BenchmarkRoutine\nMost of the time, all you need is to know how much time it will take to solve your system, and hopefully, what is the most suitable solver. In Eigen, we provide a benchmark routine that can be used for this purpose. It is very easy to use. In the build directory, navigate to bench/spbench and compile the routine by typing \\b make \\e spbenchsolver. Run it with --help option to get the list of all available options. Basically, the matrices to test should be in <a href=\"http://math.nist.gov/MatrixMarket/formats.html\">MatrixMarket Coordinate format</a>, and the routine returns the statistics from all available solvers in Eigen.\n\nTo export your matrices and right-hand-side vectors in the matrix-market format, you can the the unsupported SparseExtra module:\n\\code\n#include <unsupported/Eigen/SparseExtra>\n...\nEigen::saveMarket(A, \"filename.mtx\");\nEigen::saveMarket(A, \"filename_SPD.mtx\", Eigen::Symmetric); // if A is symmetric-positive-definite\nEigen::saveMarketVector(B, \"filename_b.mtx\");\n\\endcode\n\nThe following table gives an example of XML statistics from several Eigen built-in and external solvers. \n<TABLE border=\"1\">\n <TR><TH>Matrix <TH> N <TH> NNZ <TH>  <TH > UMFPACK <TH > SUPERLU <TH > PASTIX LU <TH >BiCGSTAB <TH > BiCGSTAB+ILUT <TH >GMRES+ILUT<TH > LDLT <TH> CHOLMOD LDLT <TH > PASTIX LDLT <TH > LLT <TH > CHOLMOD SP LLT <TH > CHOLMOD LLT <TH > PASTIX LLT <TH> CG</TR>\n<TR><TH rowspan=\"4\">vector_graphics <TD rowspan=\"4\"> 12855 <TD rowspan=\"4\"> 72069 <TH>Compute Time <TD>0.0254549<TD>0.0215677<TD>0.0701827<TD>0.000153388<TD>0.0140107<TD>0.0153709<TD>0.0101601<TD style=\"background-color:red\">0.00930502<TD>0.0649689\n<TR><TH>Solve Time <TD>0.00337835<TD>0.000951826<TD>0.00484373<TD>0.0374886<TD>0.0046445<TD>0.00847754<TD>0.000541813<TD style=\"background-color:red\">0.000293696<TD>0.00485376\n<TR><TH>Total Time <TD>0.0288333<TD>0.0225195<TD>0.0750265<TD>0.037642<TD>0.0186552<TD>0.0238484<TD>0.0107019<TD style=\"background-color:red\">0.00959871<TD>0.0698227\n<TR><TH>Error(Iter) <TD> 1.299e-16 <TD> 2.04207e-16 <TD> 4.83393e-15 <TD> 3.94856e-11 (80)  <TD> 1.03861e-12 (3)  <TD> 5.81088e-14 (6)  <TD> 1.97578e-16 <TD> 1.83927e-16 <TD> 4.24115e-15\n<TR><TH rowspan=\"4\">poisson_SPD <TD rowspan=\"4\"> 19788 <TD rowspan=\"4\"> 308232 <TH>Compute Time <TD>0.425026<TD>1.82378<TD>0.617367<TD>0.000478921<TD>1.34001<TD>1.33471<TD>0.796419<TD>0.857573<TD>0.473007<TD>0.814826<TD style=\"background-color:red\">0.184719<TD>0.861555<TD>0.470559<TD>0.000458188\n<TR><TH>Solve Time <TD>0.0280053<TD>0.0194402<TD>0.0268747<TD>0.249437<TD>0.0548444<TD>0.0926991<TD>0.00850204<TD>0.0053171<TD>0.0258932<TD>0.00874603<TD style=\"background-color:red\">0.00578155<TD>0.00530361<TD>0.0248942<TD>0.239093\n<TR><TH>Total Time <TD>0.453031<TD>1.84322<TD>0.644241<TD>0.249916<TD>1.39486<TD>1.42741<TD>0.804921<TD>0.862891<TD>0.4989<TD>0.823572<TD style=\"background-color:red\">0.190501<TD>0.866859<TD>0.495453<TD>0.239551\n<TR><TH>Error(Iter) <TD> 4.67146e-16 <TD> 1.068e-15 <TD> 1.3397e-15 <TD> 6.29233e-11 (201)  <TD> 3.68527e-11 (6)  <TD> 3.3168e-15 (16)  <TD> 1.86376e-15 <TD> 1.31518e-16 <TD> 1.42593e-15 <TD> 3.45361e-15 <TD> 3.14575e-16 <TD> 2.21723e-15 <TD> 7.21058e-16 <TD> 9.06435e-12 (261) \n<TR><TH rowspan=\"4\">sherman2 <TD rowspan=\"4\"> 1080 <TD rowspan=\"4\"> 23094 <TH>Compute Time <TD style=\"background-color:red\">0.00631754<TD>0.015052<TD>0.0247514 <TD> -<TD>0.0214425<TD>0.0217988\n<TR><TH>Solve Time <TD style=\"background-color:red\">0.000478424<TD>0.000337998<TD>0.0010291 <TD> -<TD>0.00243152<TD>0.00246152\n<TR><TH>Total Time <TD style=\"background-color:red\">0.00679597<TD>0.01539<TD>0.0257805 <TD> -<TD>0.023874<TD>0.0242603\n<TR><TH>Error(Iter) <TD> 1.83099e-15 <TD> 8.19351e-15 <TD> 2.625e-14 <TD> 1.3678e+69 (1080)  <TD> 4.1911e-12 (7)  <TD> 5.0299e-13 (12) \n<TR><TH rowspan=\"4\">bcsstk01_SPD <TD rowspan=\"4\"> 48 <TD rowspan=\"4\"> 400 <TH>Compute Time <TD>0.000169079<TD>0.00010789<TD>0.000572538<TD>1.425e-06<TD>9.1612e-05<TD>8.3985e-05<TD style=\"background-color:red\">5.6489e-05<TD>7.0913e-05<TD>0.000468251<TD>5.7389e-05<TD>8.0212e-05<TD>5.8394e-05<TD>0.000463017<TD>1.333e-06\n<TR><TH>Solve Time <TD>1.2288e-05<TD>1.1124e-05<TD>0.000286387<TD>8.5896e-05<TD>1.6381e-05<TD>1.6984e-05<TD style=\"background-color:red\">3.095e-06<TD>4.115e-06<TD>0.000325438<TD>3.504e-06<TD>7.369e-06<TD>3.454e-06<TD>0.000294095<TD>6.0516e-05\n<TR><TH>Total Time <TD>0.000181367<TD>0.000119014<TD>0.000858925<TD>8.7321e-05<TD>0.000107993<TD>0.000100969<TD style=\"background-color:red\">5.9584e-05<TD>7.5028e-05<TD>0.000793689<TD>6.0893e-05<TD>8.7581e-05<TD>6.1848e-05<TD>0.000757112<TD>6.1849e-05\n<TR><TH>Error(Iter) <TD> 1.03474e-16 <TD> 2.23046e-16 <TD> 2.01273e-16 <TD> 4.87455e-07 (48)  <TD> 1.03553e-16 (2)  <TD> 3.55965e-16 (2)  <TD> 2.48189e-16 <TD> 1.88808e-16 <TD> 1.97976e-16 <TD> 2.37248e-16 <TD> 1.82701e-16 <TD> 2.71474e-16 <TD> 2.11322e-16 <TD> 3.547e-09 (48) \n<TR><TH rowspan=\"4\">sherman1 <TD rowspan=\"4\"> 1000 <TD rowspan=\"4\"> 3750 <TH>Compute Time <TD>0.00228805<TD>0.00209231<TD>0.00528268<TD>9.846e-06<TD>0.00163522<TD>0.00162155<TD>0.000789259<TD style=\"background-color:red\">0.000804495<TD>0.00438269\n<TR><TH>Solve Time <TD>0.000213788<TD>9.7983e-05<TD>0.000938831<TD>0.00629835<TD>0.000361764<TD>0.00078794<TD>4.3989e-05<TD style=\"background-color:red\">2.5331e-05<TD>0.000917166\n<TR><TH>Total Time <TD>0.00250184<TD>0.00219029<TD>0.00622151<TD>0.0063082<TD>0.00199698<TD>0.00240949<TD>0.000833248<TD style=\"background-color:red\">0.000829826<TD>0.00529986\n<TR><TH>Error(Iter) <TD> 1.16839e-16 <TD> 2.25968e-16 <TD> 2.59116e-16 <TD> 3.76779e-11 (248)  <TD> 4.13343e-11 (4)  <TD> 2.22347e-14 (10)  <TD> 2.05861e-16 <TD> 1.83555e-16 <TD> 1.02917e-15\n<TR><TH rowspan=\"4\">young1c <TD rowspan=\"4\"> 841 <TD rowspan=\"4\"> 4089 <TH>Compute Time <TD>0.00235843<TD style=\"background-color:red\">0.00217228<TD>0.00568075<TD>1.2735e-05<TD>0.00264866<TD>0.00258236\n<TR><TH>Solve Time <TD>0.000329599<TD style=\"background-color:red\">0.000168634<TD>0.00080118<TD>0.0534738<TD>0.00187193<TD>0.00450211\n<TR><TH>Total Time <TD>0.00268803<TD style=\"background-color:red\">0.00234091<TD>0.00648193<TD>0.0534865<TD>0.00452059<TD>0.00708447\n<TR><TH>Error(Iter) <TD> 1.27029e-16 <TD> 2.81321e-16 <TD> 5.0492e-15 <TD> 8.0507e-11 (706)  <TD> 3.00447e-12 (8)  <TD> 1.46532e-12 (16) \n<TR><TH rowspan=\"4\">mhd1280b <TD rowspan=\"4\"> 1280 <TD rowspan=\"4\"> 22778 <TH>Compute Time <TD>0.00234898<TD>0.00207079<TD>0.00570918<TD>2.5976e-05<TD>0.00302563<TD>0.00298036<TD>0.00144525<TD style=\"background-color:red\">0.000919922<TD>0.00426444\n<TR><TH>Solve Time <TD>0.00103392<TD>0.000211911<TD>0.00105<TD>0.0110432<TD>0.000628287<TD>0.00392089<TD>0.000138303<TD style=\"background-color:red\">6.2446e-05<TD>0.00097564\n<TR><TH>Total Time <TD>0.0033829<TD>0.0022827<TD>0.00675918<TD>0.0110692<TD>0.00365392<TD>0.00690124<TD>0.00158355<TD style=\"background-color:red\">0.000982368<TD>0.00524008\n<TR><TH>Error(Iter) <TD> 1.32953e-16 <TD> 3.08646e-16 <TD> 6.734e-16 <TD> 8.83132e-11 (40)  <TD> 1.51153e-16 (1)  <TD> 6.08556e-16 (8)  <TD> 1.89264e-16 <TD> 1.97477e-16 <TD> 6.68126e-09\n<TR><TH rowspan=\"4\">crashbasis <TD rowspan=\"4\"> 160000 <TD rowspan=\"4\"> 1750416 <TH>Compute Time <TD>3.2019<TD>5.7892<TD>15.7573<TD style=\"background-color:red\">0.00383515<TD>3.1006<TD>3.09921\n<TR><TH>Solve Time <TD>0.261915<TD>0.106225<TD>0.402141<TD style=\"background-color:red\">1.49089<TD>0.24888<TD>0.443673\n<TR><TH>Total Time <TD>3.46381<TD>5.89542<TD>16.1594<TD style=\"background-color:red\">1.49473<TD>3.34948<TD>3.54288\n<TR><TH>Error(Iter) <TD> 1.76348e-16 <TD> 4.58395e-16 <TD> 1.67982e-14 <TD> 8.64144e-11 (61)  <TD> 8.5996e-12 (2)  <TD> 6.04042e-14 (5) \n\n</TABLE>\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/SparseQuickReference.dox",
    "content": "namespace Eigen {\n/** \\eigenManualPage SparseQuickRefPage Quick reference guide for sparse matrices\n\\eigenAutoToc\n\n<hr>\n\nIn this page, we give a quick summary of the main operations available for sparse matrices in the class SparseMatrix. First, it is recommended to read  the introductory tutorial at \\ref TutorialSparse. The important point to have in mind when working on sparse matrices is how they are stored : \ni.e either row major or column major. The default is column major. Most arithmetic operations on sparse matrices will assert that they have the same storage order. \n\n\\section SparseMatrixInit Sparse Matrix Initialization\n<table class=\"manual\">\n<tr><th> Category </th> <th> Operations</th> <th>Notes</th></tr>\n<tr><td>Constructor</td>\n<td>\n\\code\n  SparseMatrix<double> sm1(1000,1000); \n  SparseMatrix<std::complex<double>,RowMajor> sm2;\n\\endcode\n</td> <td> Default is ColMajor</td> </tr>\n<tr class=\"alt\">\n<td> Resize/Reserve</td>\n<td> \n \\code\n    sm1.resize(m,n);      // Change sm1 to a m x n matrix.\n    sm1.reserve(nnz);     // Allocate room for nnz nonzeros elements.   \n  \\endcode \n</td>\n<td> Note that when calling reserve(), it is not required that nnz is the exact number of nonzero elements in the final matrix. However, an exact estimation will avoid multiple reallocations during the insertion phase. </td>\n</tr>\n<tr> \n<td> Assignment </td>\n<td> \n\\code \n  SparseMatrix<double,Colmajor> sm1;\n // Initialize sm2 with sm1.\n  SparseMatrix<double,Rowmajor> sm2(sm1), sm3;        \n  // Assignment and evaluations modify the storage order.\n  sm3 = sm1; \n \\endcode\n</td>\n<td> The copy constructor can be used to convert from a storage order to another</td>\n</tr>\n<tr class=\"alt\">\n<td> Element-wise Insertion</td>\n<td>\n\\code \n// Insert a new element; \n sm1.insert(i, j) = v_ij;  \n\n// Update the value v_ij\n sm1.coeffRef(i,j) = v_ij;\n sm1.coeffRef(i,j) += v_ij;\n sm1.coeffRef(i,j) -= v_ij;\n\\endcode\n</td>\n<td> insert() assumes that the element does not already exist; otherwise, use coeffRef()</td>\n</tr>\n<tr> \n<td> Batch insertion</td>\n<td>\n\\code\n  std::vector< Eigen::Triplet<double> > tripletList;\n  tripletList.reserve(estimation_of_entries);\n  // -- Fill tripletList with nonzero elements...\n  sm1.setFromTriplets(TripletList.begin(), TripletList.end());\n\\endcode\n</td>\n<td>A complete example is available at \\link TutorialSparseFilling Triplet Insertion \\endlink.</td>\n</tr>\n<tr class=\"alt\"> \n<td> Constant or Random Insertion</td>\n<td>\n\\code\nsm1.setZero();\n\\endcode\n</td>\n<td>Remove all non-zero coefficients</td>\n</tr>\n</table>\n\n\n\\section SparseBasicInfos Matrix properties\nBeyond the basic functions rows() and cols(), there are some useful functions that are available to easily get some information from the matrix. \n<table class=\"manual\">\n<tr>\n  <td> \\code\n  sm1.rows();         // Number of rows\n  sm1.cols();         // Number of columns \n  sm1.nonZeros();     // Number of non zero values   \n  sm1.outerSize();    // Number of columns (resp. rows) for a column major (resp. row major )\n  sm1.innerSize();    // Number of rows (resp. columns) for a row major (resp. column major)\n  sm1.norm();         // Euclidian norm of the matrix\n  sm1.squaredNorm();  // Squared norm of the matrix\n  sm1.blueNorm();\n  sm1.isVector();     // Check if sm1 is a sparse vector or a sparse matrix\n  sm1.isCompressed(); // Check if sm1 is in compressed form\n  ...\n  \\endcode </td>\n</tr>\n</table>\n\n\\section SparseBasicOps Arithmetic operations\nIt is easy to perform arithmetic operations on sparse matrices provided that the dimensions are adequate and that the matrices have the same storage order. Note that the evaluation can always be done in a matrix with a different storage order. In the following, \\b sm denotes a sparse matrix, \\b dm a dense matrix and \\b dv a dense vector.\n<table class=\"manual\">\n<tr><th> Operations </th> <th> Code </th> <th> Notes </th></tr>\n\n<tr>\n  <td> add subtract </td> \n  <td> \\code\n  sm3 = sm1 + sm2; \n  sm3 = sm1 - sm2;\n  sm2 += sm1; \n  sm2 -= sm1; \\endcode\n  </td>\n  <td> \n  sm1 and sm2 should have the same storage order\n  </td> \n</tr>\n\n<tr class=\"alt\"><td>\n  scalar product</td><td>\\code\n  sm3 = sm1 * s1;   sm3 *= s1; \n  sm3 = s1 * sm1 + s2 * sm2; sm3 /= s1;\\endcode\n  </td>\n  <td>\n    Many combinations are possible if the dimensions and the storage order agree.\n</tr>\n\n<tr>\n  <td> %Sparse %Product </td>\n  <td> \\code\n  sm3 = sm1 * sm2;\n  dm2 = sm1 * dm1;\n  dv2 = sm1 * dv1;\n  \\endcode </td>\n  <td>\n  </td>\n</tr> \n\n<tr class='alt'>\n  <td> transposition, adjoint</td>\n  <td> \\code\n  sm2 = sm1.transpose();\n  sm2 = sm1.adjoint();\n  \\endcode </td>\n  <td>\n  Note that the transposition change the storage order. There is no support for transposeInPlace().\n  </td>\n</tr> \n<tr>\n<td> Permutation </td>\n<td> \n\\code \nperm.indices();      // Reference to the vector of indices\nsm1.twistedBy(perm); // Permute rows and columns\nsm2 = sm1 * perm;    // Permute the columns\nsm2 = perm * sm1;    // Permute the columns\n\\endcode \n</td>\n<td> \n\n</td>\n</tr>\n<tr>\n  <td>\n  Component-wise ops\n  </td>\n  <td>\\code \n  sm1.cwiseProduct(sm2);\n  sm1.cwiseQuotient(sm2);\n  sm1.cwiseMin(sm2);\n  sm1.cwiseMax(sm2);\n  sm1.cwiseAbs();\n  sm1.cwiseSqrt();\n  \\endcode</td>\n  <td>\n  sm1 and sm2 should have the same storage order\n  </td>\n</tr>\n</table>\n\n\\section sparseotherops Other supported operations\n<table class=\"manual\">\n<tr><th style=\"min-width:initial\"> Code </th> <th> Notes</th> </tr>\n<tr><td colspan=\"2\">Sub-matrices</td></tr>\n<tr>\n<td> \n\\code \n  sm1.block(startRow, startCol, rows, cols); \n  sm1.block(startRow, startCol); \n  sm1.topLeftCorner(rows, cols); \n  sm1.topRightCorner(rows, cols);\n  sm1.bottomLeftCorner( rows, cols);\n  sm1.bottomRightCorner( rows, cols);\n  \\endcode\n</td><td>\nContrary to dense matrices, here <strong>all these methods are read-only</strong>.\\n\nSee \\ref TutorialSparse_SubMatrices and below for read-write sub-matrices.\n</td>\n</tr>\n<tr class=\"alt\"><td colspan=\"2\"> Range </td></tr>\n<tr class=\"alt\">\n<td> \n\\code \n  sm1.innerVector(outer);           // RW\n  sm1.innerVectors(start, size);    // RW\n  sm1.leftCols(size);               // RW\n  sm2.rightCols(size);              // RO because sm2 is row-major\n  sm1.middleRows(start, numRows);   // RO because sm1 is column-major\n  sm1.middleCols(start, numCols);   // RW\n  sm1.col(j);                       // RW\n\\endcode\n</td>\n<td>\nA inner vector is either a row (for row-major) or a column (for column-major).\\n\nAs stated earlier, for a read-write sub-matrix (RW), the evaluation can be done in a matrix with different storage order.\n</td>\n</tr>\n<tr><td colspan=\"2\"> Triangular and selfadjoint views</td></tr>\n<tr>\n<td> \n\\code\n  sm2 = sm1.triangularview<Lower>();\n  sm2 = sm1.selfadjointview<Lower>();\n\\endcode\n</td>\n<td> Several combination between triangular views and blocks views are possible\n\\code \n  \\endcode </td>\n</tr>\n<tr class=\"alt\"><td colspan=\"2\">Triangular solve </td></tr>\n<tr class=\"alt\">\n<td> \n\\code \n dv2 = sm1.triangularView<Upper>().solve(dv1);\n dv2 = sm1.topLeftCorner(size, size)\n          .triangularView<Lower>().solve(dv1);\n\\endcode \n</td>\n<td> For general sparse solve, Use any suitable module described at \\ref TopicSparseSystems </td>\n</tr>\n<tr><td colspan=\"2\"> Low-level API</td></tr>\n<tr>\n<td>\n\\code\nsm1.valuePtr();      // Pointer to the values\nsm1.innerIndexPtr();  // Pointer to the indices.\nsm1.outerIndexPtr(); // Pointer to the beginning of each inner vector\n\\endcode\n</td>\n<td>\nIf the matrix is not in compressed form, makeCompressed() should be called before.\\n\nNote that these functions are mostly provided for interoperability purposes with external libraries.\\n\nA better access to the values of the matrix is done by using the InnerIterator class as described in \\link TutorialSparse the Tutorial Sparse \\endlink section</td>\n</tr>\n<tr class=\"alt\"><td colspan=\"2\">Mapping external buffers</td></tr>\n<tr class=\"alt\">\n<td>\n\\code\nint outerIndexPtr[cols+1];\nint innerIndices[nnz];\ndouble values[nnz];\nMap<SparseMatrix<double> > sm1(rows,cols,nnz,outerIndexPtr, // read-write\n                               innerIndices,values);\nMap<const SparseMatrix<double> > sm2(...);                  // read-only\n\\endcode\n</td>\n<td>As for dense matrices, class Map<SparseMatrixType> can be used to see external buffers as an %Eigen's SparseMatrix object. </td>\n</tr>\n</table>\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/StlContainers.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TopicStlContainers Using STL Containers with Eigen\n\n\\eigenAutoToc\n\n\\section StlContainers_summary Executive summary\n\nIf you're compiling in \\cpp17 mode only with a sufficiently recent compiler (e.g., GCC>=7, clang>=5, MSVC>=19.12), then everything is taken care by the compiler and you can stop reading.\n\nOtherwise, using STL containers on \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen types\", or classes having members of such types, requires the use of an over-aligned allocator.\nThat is, an allocator capable of allocating buffers with 16, 32, or even 64 bytes alignment.\n%Eigen does provide one ready for use: aligned_allocator.\n\nPrior to \\cpp11, if you want to use the `std::vector` container, then you also have to <code> \\#include <Eigen/StdVector> </code>.\n\nThese issues arise only with \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen types\" and \\ref TopicStructHavingEigenMembers \"structures having such Eigen objects as member\".\nFor other %Eigen types, such as Vector3f or MatrixXd, no special care is needed when using STL containers.\n\n\\section allocator Using an aligned allocator\n\nSTL containers take an optional template parameter, the allocator type. When using STL containers on \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen types\", you need tell the container to use an allocator that will always allocate memory at 16-byte-aligned (or more) locations. Fortunately, %Eigen does provide such an allocator: Eigen::aligned_allocator.\n\nFor example, instead of\n\\code\nstd::map<int, Eigen::Vector4d>\n\\endcode\nyou need to use\n\\code\nstd::map<int, Eigen::Vector4d, std::less<int>, \n         Eigen::aligned_allocator<std::pair<const int, Eigen::Vector4d> > >\n\\endcode\nNote that the third parameter `std::less<int>` is just the default value, but we have to include it because we want to specify the fourth parameter, which is the allocator type.\n\n\\section StlContainers_vector The case of std::vector\n\nThis section is for c++98/03 users only. \\cpp11 (or above) users can stop reading here.\n\nSo in c++98/03, the situation with `std::vector` is more complicated because of a bug in the standard (explanation below).\nTo workaround the issue, we had to specialize it for the Eigen::aligned_allocator type.\nIn practice you \\b must use the Eigen::aligned_allocator (not another aligned allocator), \\b and \\#include <Eigen/StdVector>.\n\nHere is an example:\n\\code\n#include<Eigen/StdVector>\n/* ... */\nstd::vector<Eigen::Vector4f,Eigen::aligned_allocator<Eigen::Vector4f> >\n\\endcode\n\n<span class=\"note\">\\b Explanation: The `resize()` method of `std::vector` takes a `value_type` argument (defaulting to `value_type()`). So with `std::vector<Eigen::Vector4d>`, some Eigen::Vector4d objects will be passed by value, which discards any alignment modifiers, so a Eigen::Vector4d can be created at an unaligned location.\nIn order to avoid that, the only solution we saw was to specialize `std::vector` to make it work on a slight modification of, here, Eigen::Vector4d, that is able to deal properly with this situation.\n</span>\n\n\\subsection vector_spec An alternative - specializing std::vector for Eigen types\n\nAs an alternative to the recommended approach described above, you have the option to specialize std::vector for Eigen types requiring alignment. \nThe advantage is that you won't need to declare std::vector all over with Eigen::aligned_allocator. One drawback on the other hand side is that\nthe specialization needs to be defined before all code pieces in which e.g. `std::vector<Vector2d>` is used. Otherwise, without knowing the specialization\nthe compiler will compile that particular instance with the default `std::allocator` and you program is most likely to crash.\n\nHere is an example:\n\\code\n#include<Eigen/StdVector>\n/* ... */\nEIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Matrix2d)\nstd::vector<Eigen::Vector2d>\n\\endcode\n\n\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/StorageOrders.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TopicStorageOrders Storage orders\n\nThere are two different storage orders for matrices and two-dimensional arrays: column-major and row-major.\nThis page explains these storage orders and how to specify which one should be used.\n\n\\eigenAutoToc\n\n\n\\section TopicStorageOrdersIntro Column-major and row-major storage\n\nThe entries of a matrix form a two-dimensional grid. However, when the matrix is stored in memory, the entries\nhave to somehow be laid out linearly. There are two main ways to do this, by row and by column.\n\nWe say that a matrix is stored in \\b row-major order if it is stored row by row. The entire first row is\nstored first, followed by the entire second row, and so on. Consider for example the matrix\n\n\\f[\nA = \\begin{bmatrix}\n8 & 2 & 2 & 9 \\\\\n9 & 1 & 4 & 4 \\\\\n3 & 5 & 4 & 5\n\\end{bmatrix}.\n\\f]\n\nIf this matrix is stored in row-major order, then the entries are laid out in memory as follows:\n\n\\code 8 2 2 9 9 1 4 4 3 5 4 5 \\endcode\n\nOn the other hand, a matrix is stored in \\b column-major order if it is stored column by column, starting with\nthe entire first column, followed by the entire second column, and so on. If the above matrix is stored in\ncolumn-major order, it is laid out as follows:\n\n\\code 8 9 3 2 1 5 2 4 4 9 4 5 \\endcode\n\nThis example is illustrated by the following Eigen code. It uses the PlainObjectBase::data() function, which\nreturns a pointer to the memory location of the first entry of the matrix.\n\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include TopicStorageOrders_example.cpp\n</td>\n<td>\n\\verbinclude TopicStorageOrders_example.out\n</td></tr></table>\n\n\n\\section TopicStorageOrdersInEigen Storage orders in Eigen\n\nThe storage order of a matrix or a two-dimensional array can be set by specifying the \\c Options template\nparameter for Matrix or Array. As \\ref TutorialMatrixClass explains, the %Matrix class template has six\ntemplate parameters, of which three are compulsory (\\c Scalar, \\c RowsAtCompileTime and \\c ColsAtCompileTime)\nand three are optional (\\c Options, \\c MaxRowsAtCompileTime and \\c MaxColsAtCompileTime). If the \\c Options\nparameter is set to \\c RowMajor, then the matrix or array is stored in row-major order; if it is set to \n\\c ColMajor, then it is stored in column-major order. This mechanism is used in the above Eigen program to\nspecify the storage order.\n\nIf the storage order is not specified, then Eigen defaults to storing the entry in column-major. This is also\nthe case if one of the convenience typedefs (\\c Matrix3f, \\c ArrayXXd, etc.) is used.\n\nMatrices and arrays using one storage order can be assigned to matrices and arrays using the other storage\norder, as happens in the above program when \\c Arowmajor is initialized using \\c Acolmajor. Eigen will reorder\nthe entries automatically. More generally, row-major and column-major matrices can be mixed in an expression\nas we want.\n\n\n\\section TopicStorageOrdersWhich Which storage order to choose?\n\nSo, which storage order should you use in your program? There is no simple answer to this question; it depends\non your application. Here are some points to keep in mind:\n\n  - Your users may expect you to use a specific storage order. Alternatively, you may use other libraries than\n    Eigen, and these other libraries may expect a certain storage order. In these cases it may be easiest and\n    fastest to use this storage order in your whole program.\n  - Algorithms that traverse a matrix row by row will go faster when the matrix is stored in row-major order\n    because of better data locality. Similarly, column-by-column traversal is faster for column-major\n    matrices. It may be worthwhile to experiment a bit to find out what is faster for your particular\n    application.\n  - The default in Eigen is column-major. Naturally, most of the development and testing of the Eigen library\n    is thus done with column-major matrices. This means that, even though we aim to support column-major and\n    row-major storage orders transparently, the Eigen library may well work best with column-major matrices.\n\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/StructHavingEigenMembers.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TopicStructHavingEigenMembers Structures Having Eigen Members\n\n\\eigenAutoToc\n\n\\section StructHavingEigenMembers_summary Executive Summary\n\n\nIf you define a structure having members of \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen types\", you must ensure that calling operator new on it allocates properly aligned buffers.\nIf you're compiling in \\cpp17 mode only with a sufficiently recent compiler (e.g., GCC>=7, clang>=5, MSVC>=19.12), then everything is taken care by the compiler and you can stop reading.\n\nOtherwise, you have to overload its `operator new` so that it generates properly aligned pointers (e.g., 32-bytes-aligned for Vector4d and AVX).\nFortunately, %Eigen provides you with a macro `EIGEN_MAKE_ALIGNED_OPERATOR_NEW` that does that for you.\n\n\\section StructHavingEigenMembers_what What kind of code needs to be changed?\n\nThe kind of code that needs to be changed is this:\n\n\\code\nclass Foo\n{\n  ...\n  Eigen::Vector2d v;\n  ...\n};\n\n...\n\nFoo *foo = new Foo;\n\\endcode\n\nIn other words: you have a class that has as a member a \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen object\", and then you dynamically create an object of that class.\n\n\\section StructHavingEigenMembers_how How should such code be modified?\n\nVery easy, you just need to put a `EIGEN_MAKE_ALIGNED_OPERATOR_NEW` macro in a public part of your class, like this:\n\n\\code\nclass Foo\n{\n  ...\n  Eigen::Vector4d v;\n  ...\npublic:\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n};\n\n...\n\nFoo *foo = new Foo;\n\\endcode\n\nThis macro makes `new Foo` always return an aligned pointer.\n\nIn \\cpp17, this macro is empty.\n\nIf this approach is too intrusive, see also the \\ref StructHavingEigenMembers_othersolutions \"other solutions\".\n\n\\section StructHavingEigenMembers_why Why is this needed?\n\nOK let's say that your code looks like this:\n\n\\code\nclass Foo\n{\n  ...\n  Eigen::Vector4d v;\n  ...\n};\n\n...\n\nFoo *foo = new Foo;\n\\endcode\n\nA Eigen::Vector4d consists of 4 doubles, which is 256 bits.\nThis is exactly the size of an AVX register, which makes it possible to use AVX for all sorts of operations on this vector.\nBut AVX instructions (at least the ones that %Eigen uses, which are the fast ones) require 256-bit alignment.\nOtherwise you get a segmentation fault.\n\nFor this reason, %Eigen takes care by itself to require 256-bit alignment for Eigen::Vector4d, by doing two things:\n\\li %Eigen requires 256-bit alignment for the Eigen::Vector4d's array (of 4 doubles). With \\cpp11 this is done with the <a href=\"https://en.cppreference.com/w/cpp/keyword/alignas\">alignas</a> keyword, or compiler's extensions for c++98/03.\n\\li %Eigen overloads the `operator new` of Eigen::Vector4d so it will always return 256-bit aligned pointers. (removed in \\cpp17)\n\nThus, normally, you don't have to worry about anything, %Eigen handles alignment of operator new for you...\n\n... except in one case. When you have a `class Foo` like above, and you dynamically allocate a new `Foo` as above, then, since `Foo` doesn't have aligned `operator new`, the returned pointer foo is not necessarily 256-bit aligned.\n\nThe alignment attribute of the member `v` is then relative to the start of the class `Foo`. If the `foo` pointer wasn't aligned, then `foo->v` won't be aligned either!\n\nThe solution is to let `class Foo` have an aligned `operator new`, as we showed in the previous section.\n\nThis explanation also holds for SSE/NEON/MSA/Altivec/VSX targets, which require 16-bytes alignment, and AVX512 which requires 64-bytes alignment for fixed-size objects multiple of 64 bytes (e.g., Eigen::Matrix4d).\n\n\\section StructHavingEigenMembers_movetotop Should I then put all the members of Eigen types at the beginning of my class?\n\nThat's not required. Since %Eigen takes care of declaring adequate alignment, all members that need it are automatically aligned relatively to the class. So code like this works fine:\n\n\\code\nclass Foo\n{\n  double x;\n  Eigen::Vector4d v;\npublic:\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n};\n\\endcode\n\nThat said, as usual, it is recommended to sort the members so that alignment does not waste memory.\nIn the above example, with AVX, the compiler will have to reserve 24 empty bytes between `x` and `v`.\n\n\n\\section StructHavingEigenMembers_dynamicsize What about dynamic-size matrices and vectors?\n\nDynamic-size matrices and vectors, such as Eigen::VectorXd, allocate dynamically their own array of coefficients, so they take care of requiring absolute alignment automatically. So they don't cause this issue. The issue discussed here is only with \\ref TopicFixedSizeVectorizable  \"fixed-size vectorizable matrices and vectors\".\n\n\n\\section StructHavingEigenMembers_bugineigen So is this a bug in Eigen?\n\nNo, it's not our bug. It's more like an inherent problem of the c++ language specification that has been solved in c++17 through the feature known as <a href=\"http://wg21.link/p0035r4\">dynamic memory allocation for over-aligned data</a>.\n\n\n\\section StructHavingEigenMembers_conditional What if I want to do this conditionally (depending on template parameters) ?\n\nFor this situation, we offer the macro `EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)`.\nIt will generate aligned operators like `EIGEN_MAKE_ALIGNED_OPERATOR_NEW` if `NeedsToAlign` is true.\nIt will generate operators with the default alignment if `NeedsToAlign` is false.\nIn \\cpp17, this macro is empty.\n\nExample:\n\n\\code\ntemplate<int n> class Foo\n{\n  typedef Eigen::Matrix<float,n,1> Vector;\n  enum { NeedsToAlign = (sizeof(Vector)%16)==0 };\n  ...\n  Vector v;\n  ...\npublic:\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(NeedsToAlign)\n};\n\n...\n\nFoo<4> *foo4 = new Foo<4>; // foo4 is guaranteed to be 128bit-aligned\nFoo<3> *foo3 = new Foo<3>; // foo3 has only the system default alignment guarantee\n\\endcode\n\n\n\\section StructHavingEigenMembers_othersolutions Other solutions\n\nIn case putting the `EIGEN_MAKE_ALIGNED_OPERATOR_NEW` macro everywhere is too intrusive, there exists at least two other solutions.\n\n\\subsection othersolutions1 Disabling alignment\n\nThe first is to disable alignment requirement for the fixed size members:\n\\code\nclass Foo\n{\n  ...\n  Eigen::Matrix<double,4,1,Eigen::DontAlign> v;\n  ...\n};\n\\endcode\nThis `v` is fully compatible with aligned Eigen::Vector4d.\nThis has only for effect to make load/stores to `v` more expensive (usually slightly, but that's hardware dependent).\n\n\n\\subsection othersolutions2 Private structure\n\nThe second consist in storing the fixed-size objects into a private struct which will be dynamically allocated at the construction time of the main object:\n\n\\code\nstruct Foo_d\n{\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n  Vector4d v;\n  ...\n};\n\n\nstruct Foo {\n  Foo() { init_d(); }\n  ~Foo() { delete d; }\n  void bar()\n  {\n    // use d->v instead of v\n    ...\n  }\nprivate:\n  void init_d() { d = new Foo_d; }\n  Foo_d* d;\n};\n\\endcode\n\nThe clear advantage here is that the class `Foo` remains unchanged regarding alignment issues.\nThe drawback is that an additional heap allocation will be required whatsoever.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TemplateKeyword.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicTemplateKeyword The template and typename keywords in C++\n\nThere are two uses for the \\c template and \\c typename keywords in C++. One of them is fairly well known\namongst programmers: to define templates. The other use is more obscure: to specify that an expression refers\nto a template function or a type. This regularly trips up programmers that use the %Eigen library, often\nleading to error messages from the compiler that are difficult to understand, such as \"expected expression\" or\n\"no match for operator<\".\n\n\\eigenAutoToc\n\n\n\\section TopicTemplateKeywordToDefineTemplates Using the template and typename keywords to define templates\n\nThe \\c template and \\c typename keywords are routinely used to define templates. This is not the topic of this\npage as we assume that the reader is aware of this (otherwise consult a C++ book). The following example\nshould illustrate this use of the \\c template keyword.\n\n\\code\ntemplate <typename T>\nbool isPositive(T x)\n{\n    return x > 0;\n}\n\\endcode\n\nWe could just as well have written <tt>template &lt;class T&gt;</tt>; the keywords \\c typename and \\c class have the\nsame meaning in this context.\n\n\n\\section TopicTemplateKeywordExample An example showing the second use of the template keyword\n\nLet us illustrate the second use of the \\c template keyword with an example. Suppose we want to write a\nfunction which copies all entries in the upper triangular part of a matrix into another matrix, while keeping\nthe lower triangular part unchanged. A straightforward implementation would be as follows:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include TemplateKeyword_simple.cpp\n</td>\n<td>\n\\verbinclude TemplateKeyword_simple.out\n</td></tr></table>\n\nThat works fine, but it is not very flexible. First, it only works with dynamic-size matrices of\nsingle-precision floats; the function \\c copyUpperTriangularPart() does not accept static-size matrices or\nmatrices with double-precision numbers. Second, if you use an expression such as\n<tt>mat.topLeftCorner(3,3)</tt> as the parameter \\c src, then this is copied into a temporary variable of type\nMatrixXf; this copy can be avoided.\n\nAs explained in \\ref TopicFunctionTakingEigenTypes, both issues can be resolved by making \n\\c copyUpperTriangularPart() accept any object of type MatrixBase. This leads to the following code:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include TemplateKeyword_flexible.cpp\n</td>\n<td>\n\\verbinclude TemplateKeyword_flexible.out\n</td></tr></table>\n\nThe one line in the body of the function \\c copyUpperTriangularPart() shows the second, more obscure use of\nthe \\c template keyword in C++.  Even though it may look strange, the \\c template keywords are necessary\naccording to the standard. Without it, the compiler may reject the code with an error message like \"no match\nfor operator<\".\n\n\n\\section TopicTemplateKeywordExplanation Explanation\n\nThe reason that the \\c template keyword is necessary in the last example has to do with the rules for how\ntemplates are supposed to be compiled in C++. The compiler has to check the code for correct syntax at the\npoint where the template is defined, without knowing the actual value of the template arguments (\\c Derived1\nand \\c Derived2 in the example). That means that the compiler cannot know that <tt>dst.triangularView</tt> is\na member template and that the following &lt; symbol is part of the delimiter for the template\nparameter. Another possibility would be that <tt>dst.triangularView</tt> is a member variable with the &lt;\nsymbol referring to the <tt>operator&lt;()</tt> function. In fact, the compiler should choose the second\npossibility, according to the standard. If <tt>dst.triangularView</tt> is a member template (as in our case),\nthe programmer should specify this explicitly with the \\c template keyword and write <tt>dst.template\ntriangularView</tt>.\n\nThe precise rules are rather complicated, but ignoring some subtleties we can summarize them as follows:\n- A <em>dependent name</em> is name that depends (directly or indirectly) on a template parameter. In the\n  example, \\c dst is a dependent name because it is of type <tt>MatrixBase&lt;Derived1&gt;</tt> which depends\n  on the template parameter \\c Derived1.\n- If the code contains either one of the constructs <tt>xxx.yyy</tt> or <tt>xxx-&gt;yyy</tt> and \\c xxx is a\n  dependent name and \\c yyy refers to a member template, then the \\c template keyword must be used before \n  \\c yyy, leading to <tt>xxx.template yyy</tt> or <tt>xxx-&gt;template yyy</tt>.\n- If the code contains the construct <tt>xxx::yyy</tt> and \\c xxx is a dependent name and \\c yyy refers to a\n  member typedef, then the \\c typename keyword must be used before the whole construct, leading to\n  <tt>typename xxx::yyy</tt>.\n\nAs an example where the \\c typename keyword is required, consider the following code in \\ref TutorialSparse\nfor iterating over the non-zero entries of a sparse matrix type:\n\n\\code\nSparseMatrixType mat(rows,cols);\nfor (int k=0; k<mat.outerSize(); ++k)\n  for (SparseMatrixType::InnerIterator it(mat,k); it; ++it)\n  {\n    /* ... */\n  }\n\\endcode\n\nIf \\c SparseMatrixType depends on a template parameter, then the \\c typename keyword is required:\n\n\\code\ntemplate <typename T>\nvoid iterateOverSparseMatrix(const SparseMatrix<T>& mat;\n{\n  for (int k=0; k<m1.outerSize(); ++k)\n    for (typename SparseMatrix<T>::InnerIterator it(mat,k); it; ++it)\n    {\n      /* ... */\n    }\n}\n\\endcode\n\n\n\\section TopicTemplateKeywordResources Resources for further reading\n\nFor more information and a fuller explanation of this topic, the reader may consult the following sources:\n- The book \"C++ Template Metaprogramming\" by David Abrahams and Aleksey Gurtovoy contains a very good\n  explanation in Appendix B (\"The typename and template Keywords\") which formed the basis for this page.\n- http://pages.cs.wisc.edu/~driscoll/typename.html\n- http://www.parashift.com/c++-faq-lite/templates.html#faq-35.18\n- http://www.comeaucomputing.com/techtalk/templates/#templateprefix\n- http://www.comeaucomputing.com/techtalk/templates/#typename\n\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TopicAliasing.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TopicAliasing Aliasing\n\nIn %Eigen, aliasing refers to assignment statement in which the same matrix (or array or vector) appears on the\nleft and on the right of the assignment operators. Statements like <tt>mat = 2 * mat;</tt> or <tt>mat =\nmat.transpose();</tt> exhibit aliasing. The aliasing in the first example is harmless, but the aliasing in the\nsecond example leads to unexpected results. This page explains what aliasing is, when it is harmful, and what\nto do about it.\n\n\\eigenAutoToc\n\n\n\\section TopicAliasingExamples Examples\n\nHere is a simple example exhibiting aliasing:\n\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include TopicAliasing_block.cpp\n</td>\n<td>\n\\verbinclude TopicAliasing_block.out\n</td></tr></table>\n\nThe output is not what one would expect. The problem is the assignment\n\\code\nmat.bottomRightCorner(2,2) = mat.topLeftCorner(2,2);\n\\endcode\nThis assignment exhibits aliasing: the coefficient \\c mat(1,1) appears both in the block\n<tt>mat.bottomRightCorner(2,2)</tt> on the left-hand side of the assignment and the block\n<tt>mat.topLeftCorner(2,2)</tt> on the right-hand side. After the assignment, the (2,2) entry in the bottom\nright corner should have the value of \\c mat(1,1) before the assignment, which is 5. However, the output shows\nthat \\c mat(2,2) is actually 1. The problem is that %Eigen uses lazy evaluation (see \n\\ref TopicEigenExpressionTemplates) for <tt>mat.topLeftCorner(2,2)</tt>. The result is similar to\n\\code\nmat(1,1) = mat(0,0);\nmat(1,2) = mat(0,1);\nmat(2,1) = mat(1,0);\nmat(2,2) = mat(1,1);\n\\endcode\nThus, \\c mat(2,2) is assigned the \\e new value of \\c mat(1,1) instead of the old value. The next section\nexplains how to solve this problem by calling \\link DenseBase::eval() eval()\\endlink.\n\nAliasing occurs more naturally when trying to shrink a matrix. For example, the expressions <tt>vec =\nvec.head(n)</tt> and <tt>mat = mat.block(i,j,r,c)</tt> exhibit aliasing.\n\nIn general, aliasing cannot be detected at compile time: if \\c mat in the first example were a bit bigger,\nthen the blocks would not overlap, and there would be no aliasing problem. However, %Eigen does detect some\ninstances of aliasing, albeit at run time.  The following example exhibiting aliasing was mentioned in \\ref\nTutorialMatrixArithmetic :\n\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include tut_arithmetic_transpose_aliasing.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_transpose_aliasing.out\n</td></tr></table>\n\nAgain, the output shows the aliasing issue. However, by default %Eigen uses a run-time assertion to detect this\nand exits with a message like\n\n\\verbatim\nvoid Eigen::DenseBase<Derived>::checkTransposeAliasing(const OtherDerived&) const \n[with OtherDerived = Eigen::Transpose<Eigen::Matrix<int, 2, 2, 0, 2, 2> >, Derived = Eigen::Matrix<int, 2, 2, 0, 2, 2>]: \nAssertion `(!internal::check_transpose_aliasing_selector<Scalar,internal::blas_traits<Derived>::IsTransposed,OtherDerived>::run(internal::extract_data(derived()), other)) \n&& \"aliasing detected during transposition, use transposeInPlace() or evaluate the rhs into a temporary using .eval()\"' failed.\n\\endverbatim\n\nThe user can turn %Eigen's run-time assertions like the one to detect this aliasing problem off by defining the\nEIGEN_NO_DEBUG macro, and the above program was compiled with this macro turned off in order to illustrate the\naliasing problem. See \\ref TopicAssertions for more information about %Eigen's run-time assertions.\n\n\n\\section TopicAliasingSolution Resolving aliasing issues\n\nIf you understand the cause of the aliasing issue, then it is obvious what must happen to solve it: %Eigen has\nto evaluate the right-hand side fully into a temporary matrix/array and then assign it to the left-hand\nside. The function \\link DenseBase::eval() eval() \\endlink does precisely that.\n\nFor example, here is the corrected version of the first example above:\n\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include TopicAliasing_block_correct.cpp\n</td>\n<td>\n\\verbinclude TopicAliasing_block_correct.out\n</td></tr></table>\n\nNow, \\c mat(2,2) equals 5 after the assignment, as it should be.\n\nThe same solution also works for the second example, with the transpose: simply replace the line \n<tt>a = a.transpose();</tt> with <tt>a = a.transpose().eval();</tt>. However, in this common case there is a\nbetter solution. %Eigen provides the special-purpose function \n\\link DenseBase::transposeInPlace() transposeInPlace() \\endlink which replaces a matrix by its transpose. \nThis is shown below:\n\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include tut_arithmetic_transpose_inplace.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_transpose_inplace.out\n</td></tr></table>\n\nIf an xxxInPlace() function is available, then it is best to use it, because it indicates more clearly what you\nare doing. This may also allow %Eigen to optimize more aggressively. These are some of the xxxInPlace()\nfunctions provided: \n\n<table class=\"manual\">\n<tr><th>Original function</th><th>In-place function</th></tr>\n<tr> <td> MatrixBase::adjoint() </td> <td> MatrixBase::adjointInPlace() </td> </tr>\n<tr class=\"alt\"> <td> DenseBase::reverse() </td> <td> DenseBase::reverseInPlace() </td> </tr>\n<tr> <td> LDLT::solve() </td> <td> LDLT::solveInPlace() </td> </tr>\n<tr class=\"alt\"> <td> LLT::solve() </td> <td> LLT::solveInPlace() </td> </tr>\n<tr> <td> TriangularView::solve() </td> <td> TriangularView::solveInPlace() </td> </tr>\n<tr class=\"alt\"> <td> DenseBase::transpose() </td> <td> DenseBase::transposeInPlace() </td> </tr>\n</table>\n\nIn the special case where a matrix or vector is shrunk using an expression like <tt>vec = vec.head(n)</tt>,\nyou can use \\link PlainObjectBase::conservativeResize() conservativeResize() \\endlink.\n\n\n\\section TopicAliasingCwise Aliasing and component-wise operations\n\nAs explained above, it may be dangerous if the same matrix or array occurs on both the left-hand side and the\nright-hand side of an assignment operator, and it is then often necessary to evaluate the right-hand side\nexplicitly. However, applying component-wise operations (such as matrix addition, scalar multiplication and\narray multiplication) is safe. \n\nThe following example has only component-wise operations. Thus, there is no need for \\link DenseBase::eval()\neval() \\endlink even though the same matrix appears on both sides of the assignments.\n\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include TopicAliasing_cwise.cpp\n</td>\n<td>\n\\verbinclude TopicAliasing_cwise.out\n</td></tr></table>\n\nIn general, an assignment is safe if the (i,j) entry of the expression on the right-hand side depends only on\nthe (i,j) entry of the matrix or array on the left-hand side and not on any other entries. In that case it is\nnot necessary to evaluate the right-hand side explicitly.\n\n\n\\section TopicAliasingMatrixMult Aliasing and matrix multiplication\n\nMatrix multiplication is the only operation in %Eigen that assumes aliasing by default, <strong>under the\ncondition that the destination matrix is not resized</strong>.\nThus, if \\c matA is a \\b squared matrix, then the statement <tt>matA = matA * matA;</tt> is safe.\nAll other operations in %Eigen assume that there are no aliasing problems,\neither because the result is assigned to a different matrix or because it is a component-wise operation.\n\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include TopicAliasing_mult1.cpp\n</td>\n<td>\n\\verbinclude TopicAliasing_mult1.out\n</td></tr></table>\n\nHowever, this comes at a price. When executing the expression <tt>matA = matA * matA</tt>, %Eigen evaluates the\nproduct in a temporary matrix which is assigned to \\c matA after the computation. This is fine. But %Eigen does\nthe same when the product is assigned to a different matrix (e.g., <tt>matB = matA * matA</tt>). In that case,\nit is more efficient to evaluate the product directly into \\c matB instead of evaluating it first into a\ntemporary matrix and copying that matrix to \\c matB.\n\nThe user can indicate with the \\link MatrixBase::noalias() noalias()\\endlink function that there is no\naliasing, as follows: <tt>matB.noalias() = matA * matA</tt>. This allows %Eigen to evaluate the matrix product\n<tt>matA * matA</tt> directly into \\c matB.\n\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include TopicAliasing_mult2.cpp\n</td>\n<td>\n\\verbinclude TopicAliasing_mult2.out\n</td></tr></table>\n\nOf course, you should not use \\c noalias() when there is in fact aliasing taking place. If you do, then you\nmay get wrong results:\n\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include TopicAliasing_mult3.cpp\n</td>\n<td>\n\\verbinclude TopicAliasing_mult3.out\n</td></tr></table>\n\nMoreover, starting in Eigen 3.3, aliasing is \\b not assumed if the destination matrix is resized and the product is not directly assigned to the destination.\nTherefore, the following example is also wrong:\n\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include TopicAliasing_mult4.cpp\n</td>\n<td>\n\\verbinclude TopicAliasing_mult4.out\n</td></tr></table>\n\nAs for any aliasing issue, you can resolve it by explicitly evaluating the expression prior to assignment:\n<table class=\"example\">\n<tr><th>Example</th><th>Output</th></tr>\n<tr><td>\n\\include TopicAliasing_mult5.cpp\n</td>\n<td>\n\\verbinclude TopicAliasing_mult5.out\n</td></tr></table>\n\n\\section TopicAliasingSummary Summary\n\nAliasing occurs when the same matrix or array coefficients appear both on the left- and the right-hand side of\nan assignment operator.\n - Aliasing is harmless with coefficient-wise computations; this includes scalar multiplication and matrix or\n   array addition.\n - When you multiply two matrices, %Eigen assumes that aliasing occurs. If you know that there is no aliasing,\n   then you can use \\link MatrixBase::noalias() noalias()\\endlink.\n - In all other situations, %Eigen assumes that there is no aliasing issue and thus gives the wrong result if\n   aliasing does in fact occur. To prevent this, you have to use \\link DenseBase::eval() eval() \\endlink or\n   one of the xxxInPlace() functions.\n\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TopicAssertions.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicAssertions Assertions\n\n\\eigenAutoToc\n\n\\section PlainAssert Assertions\n\nThe macro eigen_assert is defined to be \\c eigen_plain_assert by default. We use eigen_plain_assert instead of \\c assert to work around a known bug for GCC <= 4.3. Basically, eigen_plain_assert \\a is \\c assert.\n\n\\subsection RedefineAssert Redefining assertions\n\nBoth eigen_assert and eigen_plain_assert are defined in Macros.h. Defining eigen_assert indirectly gives you a chance to change its behavior. You can redefine this macro if you want to do something else such as throwing an exception, and fall back to its default behavior with eigen_plain_assert. The code below tells Eigen to throw an std::runtime_error:\n\n\\code\n#include <stdexcept>\n#undef eigen_assert\n#define eigen_assert(x) \\\n  if (!(x)) { throw (std::runtime_error(\"Put your message here\")); }\n\\endcode\n\n\\subsection DisableAssert Disabling assertions\n\nAssertions cost run time and can be turned off. You can suppress eigen_assert by defining \\c EIGEN_NO_DEBUG \\b before including Eigen headers. \\c EIGEN_NO_DEBUG is undefined by default unless \\c NDEBUG is defined.\n\n\\section StaticAssert Static assertions\n\nStatic assertions are not standardized until C++11. However, in the Eigen library, there are many conditions can and should be detectedat compile time. For instance, we use static assertions to prevent the code below from compiling.\n\n\\code\nMatrix3d()  + Matrix4d();   // adding matrices of different sizes\nMatrix4cd() * Vector3cd();  // invalid product known at compile time\n\\endcode\n\nStatic assertions are defined in StaticAssert.h. If there is native static_assert, we use it. Otherwise, we have implemented an assertion macro that can show a limited range of messages.\n\nOne can easily come up with static assertions without messages, such as:\n\n\\code\n#define STATIC_ASSERT(x) \\\n  switch(0) { case 0: case x:; }\n\\endcode\n\nHowever, the example above obviously cannot tell why the assertion failed. Therefore, we define a \\c struct in namespace Eigen::internal to handle available messages.\n\n\\code\ntemplate<bool condition>\nstruct static_assertion {};\n\ntemplate<>\nstruct static_assertion<true>\n{\n  enum {\n    YOU_TRIED_CALLING_A_VECTOR_METHOD_ON_A_MATRIX,\n    YOU_MIXED_VECTORS_OF_DIFFERENT_SIZES,\n    // see StaticAssert.h for all enums.\n  };\n};\n\\endcode\n\nAnd then, we define EIGEN_STATIC_ASSERT(CONDITION,MSG) to access Eigen::internal::static_assertion<bool(CONDITION)>::MSG. If the condition evaluates into \\c false, your compiler displays a lot of messages explaining there is no MSG in static_assert<false>. Nevertheless, this is \\a not in what we are interested. As you can see, all members of static_assert<true> are ALL_CAPS_AND_THEY_ARE_SHOUTING.\n\n\\warning\nWhen using this macro, MSG should be a member of static_assertion<true>, or the static assertion \\b always fails.\nCurrently, it can only be used in function scope.\n\n\\subsection DerivedStaticAssert Derived static assertions\n\nThere are other macros derived from EIGEN_STATIC_ASSERT to enhance readability. Their names are self-explanatory.\n\n- \\b EIGEN_STATIC_ASSERT_FIXED_SIZE(TYPE) - passes if \\a TYPE is fixed size.\n- \\b EIGEN_STATIC_ASSERT_DYNAMIC_SIZE(TYPE) - passes if \\a TYPE is dynamic size.\n- \\b EIGEN_STATIC_ASSERT_LVALUE(Derived) - failes if \\a Derived is read-only.\n- \\b EIGEN_STATIC_ASSERT_ARRAYXPR(Derived) - passes if \\a Derived is an array expression.\n- <b>EIGEN_STATIC_ASSERT_SAME_XPR_KIND(Derived1, Derived2)</b> - failes if the two expressions are an array one and a matrix one.\n\nBecause Eigen handles both fixed-size and dynamic-size expressions, some conditions cannot be clearly determined at compile time. We classify them into strict assertions and permissive assertions.\n\n\\subsubsection StrictAssertions Strict assertions\n\nThese assertions fail if the condition <b>may not</b> be met. For example, MatrixXd may not be a vector, so it fails EIGEN_STATIC_ASSERT_VECTOR_ONLY.\n\n- \\b EIGEN_STATIC_ASSERT_VECTOR_ONLY(TYPE) - passes if \\a TYPE must be a vector type.\n- <b>EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(TYPE, SIZE)</b> - passes if \\a TYPE must be a vector of the given size.\n- <b>EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(TYPE, ROWS, COLS)</b> - passes if \\a TYPE must be a matrix with given rows and columns.\n\n\\subsubsection PermissiveAssertions Permissive assertions\n\nThese assertions fail if the condition \\b cannot be met. For example, MatrixXd and Matrix4d may have the same size, so they pass EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE.\n\n- \\b EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(TYPE0,TYPE1) - fails if the two vector expression types must have different sizes.\n- \\b EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(TYPE0,TYPE1) - fails if the two matrix expression types must have different sizes.\n- \\b EIGEN_STATIC_ASSERT_SIZE_1x1(TYPE) - fails if \\a TYPE cannot be an 1x1 expression.\n\nSee StaticAssert.h for details such as what messages they throw.\n\n\\subsection DisableStaticAssert Disabling static assertions\n\nIf \\c EIGEN_NO_STATIC_ASSERT is defined, static assertions turn into <tt>eigen_assert</tt>'s, working like:\n\n\\code\n#define EIGEN_STATIC_ASSERT(CONDITION,MSG) eigen_assert((CONDITION) && #MSG);\n\\endcode\n\nThis saves compile time but consumes more run time. \\c EIGEN_NO_STATIC_ASSERT is undefined by default.\n\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TopicCMakeGuide.dox",
    "content": "namespace Eigen {\n\n/**\n\n\\page TopicCMakeGuide Using %Eigen in CMake Projects\n\n%Eigen provides native CMake support which allows the library to be easily\nused in CMake projects.\n\n\\note %CMake 3.0 (or later) is required to enable this functionality.\n\n%Eigen exports a CMake target called `Eigen3::Eigen` which can be imported\nusing the `find_package` CMake command and used by calling\n`target_link_libraries` as in the following example:\n\\code{.cmake}\ncmake_minimum_required (VERSION 3.0)\nproject (myproject)\n\nfind_package (Eigen3 3.3 REQUIRED NO_MODULE)\n\nadd_executable (example example.cpp)\ntarget_link_libraries (example Eigen3::Eigen)\n\\endcode\n\nThe above code snippet must be placed in a file called `CMakeLists.txt` alongside\n`example.cpp`. After running\n\\code{.sh}\n$ cmake path-to-example-directory\n\\endcode\nCMake will produce project files that generate an executable called `example`\nwhich requires at least version 3.3 of %Eigen. Here, `path-to-example-directory`\nis the path to the directory that contains both `CMakeLists.txt` and\n`example.cpp`.\n\nDo not forget to set the <a href=\"https://cmake.org/cmake/help/v3.7/variable/CMAKE_PREFIX_PATH.html\">\\c CMAKE_PREFIX_PATH </a> variable if Eigen is not installed in a default location or if you want to pick a specific version. For instance:\n\\code{.sh}\n$ cmake path-to-example-directory -DCMAKE_PREFIX_PATH=$HOME/mypackages\n\\endcode\nAn alternative is to set the \\c Eigen3_DIR cmake's variable to the respective path containing the \\c Eigen3*.cmake files. For instance:\n\\code{.sh}\n$ cmake path-to-example-directory -DEigen3_DIR=$HOME/mypackages/share/eigen3/cmake/\n\\endcode\n\nIf the `REQUIRED` option is omitted when locating %Eigen using\n`find_package`, one can check whether the package was found as follows:\n\\code{.cmake}\nfind_package (Eigen3 3.3 NO_MODULE)\n\nif (TARGET Eigen3::Eigen)\n  # Use the imported target\nendif (TARGET Eigen3::Eigen)\n\\endcode\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TopicEigenExpressionTemplates.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicEigenExpressionTemplates Expression templates in Eigen\n\n\nTODO: write this dox page!\n\nIs linked from the tutorial on arithmetic ops.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TopicLazyEvaluation.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicLazyEvaluation Lazy Evaluation and Aliasing\n\nExecutive summary: %Eigen has intelligent compile-time mechanisms to enable lazy evaluation and removing temporaries where appropriate.\nIt will handle aliasing automatically in most cases, for example with matrix products. The automatic behavior can be overridden\nmanually by using the MatrixBase::eval() and MatrixBase::noalias() methods.\n\nWhen you write a line of code involving a complex expression such as\n\n\\code mat1 = mat2 + mat3 * (mat4 + mat5);\n\\endcode\n\n%Eigen determines automatically, for each sub-expression, whether to evaluate it into a temporary variable. Indeed, in certain cases it is better to evaluate a sub-expression into a temporary variable, while in other cases it is better to avoid that.\n\nA traditional math library without expression templates always evaluates all sub-expressions into temporaries. So with this code,\n\n\\code vec1 = vec2 + vec3;\n\\endcode\n\na traditional library would evaluate \\c vec2 + vec3 into a temporary \\c vec4 and then copy \\c vec4  into \\c vec1. This is of course inefficient: the arrays are traversed twice, so there are a lot of useless load/store operations.\n\nExpression-templates-based libraries can avoid evaluating sub-expressions into temporaries, which in many cases results in large speed improvements.\nThis is called <i>lazy evaluation</i> as an expression is getting evaluated as late as possible.\nIn %Eigen <b>all expressions are lazy-evaluated</b>.\nMore precisely, an expression starts to be evaluated once it is assigned to a matrix.\nUntil then nothing happens beyond constructing the abstract expression tree.\nIn contrast to most other expression-templates-based libraries, however, <b>%Eigen might choose to evaluate some sub-expressions into temporaries</b>.\nThere are two reasons for that: first, pure lazy evaluation is not always a good choice for performance; second, pure lazy evaluation can be very dangerous, for example with matrix products: doing <tt>mat = mat*mat</tt> gives a wrong result if the matrix product is directly evaluated within the destination matrix, because of the way matrix product works.\n\nFor these reasons, %Eigen has intelligent compile-time mechanisms to determine automatically which sub-expression should be evaluated into a temporary variable.\n\nSo in the basic example,\n\n\\code mat1 = mat2 + mat3;\n\\endcode\n\n%Eigen chooses not to introduce any temporary. Thus the arrays are traversed only once, producing optimized code.\nIf you really want to force immediate evaluation, use \\link MatrixBase::eval() eval()\\endlink:\n\n\\code mat1 = (mat2 + mat3).eval();\n\\endcode\n\nHere is now a more involved example:\n\n\\code mat1 = -mat2 + mat3 + 5 * mat4;\n\\endcode\n\nHere again %Eigen won't introduce any temporary, thus producing a single <b>fused</b> evaluation loop, which is clearly the correct choice.\n\n\\section TopicLazyEvaluationWhichExpr Which sub-expressions are evaluated into temporaries?\n\nThe default evaluation strategy is to fuse the operations in a single loop, and %Eigen will choose it except in a few circumstances.\n\n<b>The first circumstance</b> in which %Eigen chooses to evaluate a sub-expression is when it sees an assignment <tt>a = b;</tt> and the expression \\c b has the evaluate-before-assigning \\link flags flag\\endlink.\nThe most important example of such an expression is the \\link Product matrix product expression\\endlink. For example, when you do\n\n\\code mat = mat * mat;\n\\endcode\n\n%Eigen will evaluate <tt>mat * mat</tt> into a temporary matrix, and then copies it into the original \\c mat.\nThis guarantees a correct result as we saw above that lazy evaluation gives wrong results with matrix products.\nIt also doesn't cost much, as the cost of the matrix product itself is much higher.\nNote that this temporary is introduced at evaluation time only, that is, within operator= in this example.\nThe expression <tt>mat * mat</tt> still return a abstract product type.\n\nWhat if you know that the result does no alias the operand of the product and want to force lazy evaluation? Then use \\link MatrixBase::noalias() .noalias()\\endlink instead. Here is an example:\n\n\\code mat1.noalias() = mat2 * mat2;\n\\endcode\n\nHere, since we know that mat2 is not the same matrix as mat1, we know that lazy evaluation is not dangerous, so we may force lazy evaluation. Concretely, the effect of noalias() here is to bypass the evaluate-before-assigning \\link flags flag\\endlink.\n\n<b>The second circumstance</b> in which %Eigen chooses to evaluate a sub-expression, is when it sees a nested expression such as <tt>a + b</tt> where \\c b is already an expression having the evaluate-before-nesting \\link flags flag\\endlink.\nAgain, the most important example of such an expression is the \\link Product matrix product expression\\endlink.\nFor example, when you do\n\n\\code mat1 = mat2 * mat3 + mat4 * mat5;\n\\endcode\n\nthe products <tt>mat2 * mat3</tt> and <tt>mat4 * mat5</tt> gets evaluated separately into temporary matrices before being summed up in <tt>mat1</tt>.\nIndeed, to be efficient matrix products need to be evaluated within a destination matrix at hand, and not as simple \"dot products\".\nFor small matrices, however, you might want to enforce a \"dot-product\" based lazy evaluation with lazyProduct().\nAgain, it is important to understand that those temporaries are created at evaluation time only, that is in operator =.\nSee TopicPitfalls_auto_keyword for common pitfalls regarding this remark.\n\n<b>The third circumstance</b> in which %Eigen chooses to evaluate a sub-expression, is when its cost model shows that the total cost of an operation is reduced if a sub-expression gets evaluated into a temporary.\nIndeed, in certain cases, an intermediate result is sufficiently costly to compute and is reused sufficiently many times, that is worth \"caching\". Here is an example:\n\n\\code mat1 = mat2 * (mat3 + mat4);\n\\endcode\n\nHere, provided the matrices have at least 2 rows and 2 columns, each coefficient of the expression <tt>mat3 + mat4</tt> is going to be used several times in the matrix product. Instead of computing the sum every time, it is much better to compute it once and store it in a temporary variable. %Eigen understands this and evaluates <tt>mat3 + mat4</tt> into a temporary variable before evaluating the product.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TopicLinearAlgebraDecompositions.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TopicLinearAlgebraDecompositions Catalogue of dense decompositions\n\nThis page presents a catalogue of the dense matrix decompositions offered by Eigen.\nFor an introduction on linear solvers and decompositions, check this \\link TutorialLinearAlgebra page \\endlink.\nTo get an overview of the true relative speed of the different decompositions, check this \\link DenseDecompositionBenchmark benchmark \\endlink.\n\n\\section TopicLinAlgBigTable Catalogue of decompositions offered by Eigen\n\n<table class=\"manual-vl\">\n    <tr>\n        <th class=\"meta\"></th>\n        <th class=\"meta\" colspan=\"5\">Generic information, not Eigen-specific</th>\n        <th class=\"meta\" colspan=\"3\">Eigen-specific</th>\n    </tr>\n\n    <tr>\n        <th>Decomposition</th>\n        <th>Requirements on the matrix</th>\n        <th>Speed</th>\n        <th>Algorithm reliability and accuracy</th>\n        <th>Rank-revealing</th>\n        <th>Allows to compute (besides linear solving)</th>\n        <th>Linear solver provided by Eigen</th>\n        <th>Maturity of Eigen's implementation</th>\n        <th>Optimizations</th>\n    </tr>\n\n    <tr>\n        <td>PartialPivLU</td>\n        <td>Invertible</td>\n        <td>Fast</td>\n        <td>Depends on condition number</td>\n        <td>-</td>\n        <td>-</td>\n        <td>Yes</td>\n        <td>Excellent</td>\n        <td>Blocking, Implicit MT</td>\n    </tr>\n\n    <tr class=\"alt\">\n        <td>FullPivLU</td>\n        <td>-</td>\n        <td>Slow</td>\n        <td>Proven</td>\n        <td>Yes</td>\n        <td>-</td>\n        <td>Yes</td>\n        <td>Excellent</td>\n        <td>-</td>\n    </tr>\n\n    <tr>\n        <td>HouseholderQR</td>\n        <td>-</td>\n        <td>Fast</td>\n        <td>Depends on condition number</td>\n        <td>-</td>\n        <td>Orthogonalization</td>\n        <td>Yes</td>\n        <td>Excellent</td>\n        <td>Blocking</td>\n    </tr>\n\n    <tr class=\"alt\">\n        <td>ColPivHouseholderQR</td>\n        <td>-</td>\n        <td>Fast</td>\n        <td>Good</td>\n        <td>Yes</td>\n        <td>Orthogonalization</td>\n        <td>Yes</td>\n        <td>Excellent</td>\n        <td><em>Soon: blocking</em></td>\n    </tr>\n\n    <tr>\n        <td>FullPivHouseholderQR</td>\n        <td>-</td>\n        <td>Slow</td>\n        <td>Proven</td>\n        <td>Yes</td>\n        <td>Orthogonalization</td>\n        <td>Yes</td>\n        <td>Average</td>\n        <td>-</td>\n    </tr>\n\n    <tr class=\"alt\">\n        <td>LLT</td>\n        <td>Positive definite</td>\n        <td>Very fast</td>\n        <td>Depends on condition number</td>\n        <td>-</td>\n        <td>-</td>\n        <td>Yes</td>\n        <td>Excellent</td>\n        <td>Blocking</td>\n    </tr>\n\n    <tr>\n        <td>LDLT</td>\n        <td>Positive or negative semidefinite<sup><a href=\"#note1\">1</a></sup></td>\n        <td>Very fast</td>\n        <td>Good</td>\n        <td>-</td>\n        <td>-</td>\n        <td>Yes</td>\n        <td>Excellent</td>\n        <td><em>Soon: blocking</em></td>\n    </tr>\n\n    <tr><th class=\"inter\" colspan=\"9\">\\n Singular values and eigenvalues decompositions</th></tr>\n\n    <tr>\n        <td>BDCSVD (divide \\& conquer)</td>\n        <td>-</td>\n        <td>One of the fastest SVD algorithms</td>\n        <td>Excellent</td>\n        <td>Yes</td>\n        <td>Singular values/vectors, least squares</td>\n        <td>Yes (and does least squares)</td>\n        <td>Excellent</td>\n        <td>Blocked bidiagonalization</td>\n    </tr>\n\n    <tr>\n        <td>JacobiSVD (two-sided)</td>\n        <td>-</td>\n        <td>Slow (but fast for small matrices)</td>\n        <td>Proven<sup><a href=\"#note3\">3</a></sup></td>\n        <td>Yes</td>\n        <td>Singular values/vectors, least squares</td>\n        <td>Yes (and does least squares)</td>\n        <td>Excellent</td>\n        <td>R-SVD</td>\n    </tr>\n\n    <tr class=\"alt\">\n        <td>SelfAdjointEigenSolver</td>\n        <td>Self-adjoint</td>\n        <td>Fast-average<sup><a href=\"#note2\">2</a></sup></td>\n        <td>Good</td>\n        <td>Yes</td>\n        <td>Eigenvalues/vectors</td>\n        <td>-</td>\n        <td>Excellent</td>\n        <td><em>Closed forms for 2x2 and 3x3</em></td>\n    </tr>\n\n    <tr>\n        <td>ComplexEigenSolver</td>\n        <td>Square</td>\n        <td>Slow-very slow<sup><a href=\"#note2\">2</a></sup></td>\n        <td>Depends on condition number</td>\n        <td>Yes</td>\n        <td>Eigenvalues/vectors</td>\n        <td>-</td>\n        <td>Average</td>\n        <td>-</td>\n    </tr>\n\n    <tr class=\"alt\">\n        <td>EigenSolver</td>\n        <td>Square and real</td>\n        <td>Average-slow<sup><a href=\"#note2\">2</a></sup></td>\n        <td>Depends on condition number</td>\n        <td>Yes</td>\n        <td>Eigenvalues/vectors</td>\n        <td>-</td>\n        <td>Average</td>\n        <td>-</td>\n    </tr>\n\n    <tr>\n        <td>GeneralizedSelfAdjointEigenSolver</td>\n        <td>Square</td>\n        <td>Fast-average<sup><a href=\"#note2\">2</a></sup></td>\n        <td>Depends on condition number</td>\n        <td>-</td>\n        <td>Generalized eigenvalues/vectors</td>\n        <td>-</td>\n        <td>Good</td>\n        <td>-</td>\n    </tr>\n\n    <tr><th class=\"inter\" colspan=\"9\">\\n Helper decompositions</th></tr>\n\n    <tr>\n        <td>RealSchur</td>\n        <td>Square and real</td>\n        <td>Average-slow<sup><a href=\"#note2\">2</a></sup></td>\n        <td>Depends on condition number</td>\n        <td>Yes</td>\n        <td>-</td>\n        <td>-</td>\n        <td>Average</td>\n        <td>-</td>\n    </tr>\n\n    <tr class=\"alt\">\n        <td>ComplexSchur</td>\n        <td>Square</td>\n        <td>Slow-very slow<sup><a href=\"#note2\">2</a></sup></td>\n        <td>Depends on condition number</td>\n        <td>Yes</td>\n        <td>-</td>\n        <td>-</td>\n        <td>Average</td>\n        <td>-</td>\n    </tr>\n\n    <tr class=\"alt\">\n        <td>Tridiagonalization</td>\n        <td>Self-adjoint</td>\n        <td>Fast</td>\n        <td>Good</td>\n        <td>-</td>\n        <td>-</td>\n        <td>-</td>\n        <td>Good</td>\n        <td><em>Soon: blocking</em></td>\n    </tr>\n\n    <tr>\n        <td>HessenbergDecomposition</td>\n        <td>Square</td>\n        <td>Average</td>\n        <td>Good</td>\n        <td>-</td>\n        <td>-</td>\n        <td>-</td>\n        <td>Good</td>\n        <td><em>Soon: blocking</em></td>\n    </tr>\n\n</table>\n\n\\b Notes:\n<ul>\n<li><a name=\"note1\">\\b 1: </a>There exist two variants of the LDLT algorithm. Eigen's one produces a pure diagonal D matrix, and therefore it cannot handle indefinite matrices, unlike Lapack's one which produces a block diagonal D matrix.</li>\n<li><a name=\"note2\">\\b 2: </a>Eigenvalues, SVD and Schur decompositions rely on iterative algorithms. Their convergence speed depends on how well the eigenvalues are separated.</li>\n<li><a name=\"note3\">\\b 3: </a>Our JacobiSVD is two-sided, making for proven and optimal precision for square matrices. For non-square matrices, we have to use a QR preconditioner first. The default choice, ColPivHouseholderQR, is already very reliable, but if you want it to be proven, use FullPivHouseholderQR instead.\n</ul>\n\n\\section TopicLinAlgTerminology Terminology\n\n<dl>\n  <dt><b>Selfadjoint</b></dt>\n    <dd>For a real matrix, selfadjoint is a synonym for symmetric. For a complex matrix, selfadjoint is a synonym for \\em hermitian.\n        More generally, a matrix \\f$ A \\f$ is selfadjoint if and only if it is equal to its adjoint \\f$ A^* \\f$. The adjoint is also called the \\em conjugate \\em transpose. </dd>\n  <dt><b>Positive/negative definite</b></dt>\n    <dd>A selfadjoint matrix \\f$ A \\f$ is positive definite if \\f$ v^* A v > 0 \\f$ for any non zero vector \\f$ v \\f$.\n        In the same vein, it is negative definite if \\f$ v^* A v < 0 \\f$ for any non zero vector \\f$ v \\f$ </dd>\n  <dt><b>Positive/negative semidefinite</b></dt>\n    <dd>A selfadjoint matrix \\f$ A \\f$ is positive semi-definite if \\f$ v^* A v \\ge 0 \\f$ for any non zero vector \\f$ v \\f$.\n        In the same vein, it is negative semi-definite if \\f$ v^* A v \\le 0 \\f$ for any non zero vector \\f$ v \\f$ </dd>\n\n  <dt><b>Blocking</b></dt>\n    <dd>Means the algorithm can work per block, whence guaranteeing a good scaling of the performance for large matrices.</dd>\n  <dt><b>Implicit Multi Threading (MT)</b></dt>\n    <dd>Means the algorithm can take advantage of multicore processors via OpenMP. \"Implicit\" means the algortihm itself is not parallelized, but that it relies on parallelized matrix-matrix product routines.</dd>\n  <dt><b>Explicit Multi Threading (MT)</b></dt>\n    <dd>Means the algorithm is explicitly parallelized to take advantage of multicore processors via OpenMP.</dd>\n  <dt><b>Meta-unroller</b></dt>\n    <dd>Means the algorithm is automatically and explicitly unrolled for very small fixed size matrices.</dd>\n  <dt><b></b></dt>\n    <dd></dd>\n</dl>\n\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TopicMultithreading.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicMultiThreading Eigen and multi-threading\n\n\\section TopicMultiThreading_MakingEigenMT Make Eigen run in parallel\n\nSome %Eigen's algorithms can exploit the multiple cores present in your hardware.\nTo this end, it is enough to enable OpenMP on your compiler, for instance:\n - GCC: \\c -fopenmp\n - ICC: \\c -openmp\n - MSVC: check the respective option in the build properties.\n\nYou can control the number of threads that will be used using either the OpenMP API or %Eigen's API using the following priority:\n\\code\n OMP_NUM_THREADS=n ./my_program\n omp_set_num_threads(n);\n Eigen::setNbThreads(n);\n\\endcode\nUnless `setNbThreads` has been called, %Eigen uses the number of threads specified by OpenMP.\nYou can restore this behavior by calling `setNbThreads(0);`.\nYou can query the number of threads that will be used with:\n\\code\nn = Eigen::nbThreads( );\n\\endcode\nYou can disable %Eigen's multi threading at compile time by defining the \\link TopicPreprocessorDirectivesPerformance EIGEN_DONT_PARALLELIZE \\endlink preprocessor token.\n\nCurrently, the following algorithms can make use of multi-threading:\n - general dense matrix - matrix products\n - PartialPivLU\n - row-major-sparse * dense vector/matrix products\n - ConjugateGradient with \\c Lower|Upper as the \\c UpLo template parameter.\n - BiCGSTAB with a row-major sparse matrix format.\n - LeastSquaresConjugateGradient\n\n\\warning On most OS it is <strong>very important</strong> to limit the number of threads to the number of physical cores, otherwise significant slowdowns are expected, especially for operations involving dense matrices.\n\nIndeed, the principle of hyper-threading is to run multiple threads (in most cases 2) on a single core in an interleaved manner.\nHowever, %Eigen's matrix-matrix product kernel is fully optimized and already exploits nearly 100% of the CPU capacity.\nConsequently, there is no room for running multiple such threads on a single core, and the performance would drops significantly because of cache pollution and other sources of overheads.\nAt this stage of reading you're probably wondering why %Eigen does not limit itself to the number of physical cores?\nThis is simply because OpenMP does not allow to know the number of physical cores, and thus %Eigen will launch as many threads as <i>cores</i> reported by OpenMP.\n\n\\section TopicMultiThreading_UsingEigenWithMT Using Eigen in a multi-threaded application\n\nIn the case your own application is multithreaded, and multiple threads make calls to %Eigen, then you have to initialize %Eigen by calling the following routine \\b before creating the threads:\n\\code\n#include <Eigen/Core>\n\nint main(int argc, char** argv)\n{\n  Eigen::initParallel();\n  \n  ...\n}\n\\endcode\n\n\\note With %Eigen 3.3, and a fully C++11 compliant compiler (i.e., <a href=\"http://en.cppreference.com/w/cpp/language/storage_duration#Static_local_variables\">thread-safe static local variable initialization</a>), then calling \\c initParallel() is optional.\n\n\\warning Note that all functions generating random matrices are \\b not re-entrant nor thread-safe. Those include DenseBase::Random(), and DenseBase::setRandom() despite a call to `Eigen::initParallel()`. This is because these functions are based on `std::rand` which is not re-entrant.\nFor thread-safe random generator, we recommend the use of c++11 random generators (\\link DenseBase::NullaryExpr(Index, const CustomNullaryOp&) example \\endlink) or `boost::random`.\n\nIn the case your application is parallelized with OpenMP, you might want to disable %Eigen's own parallelization as detailed in the previous section.\n\n\\warning Using OpenMP with custom scalar types that might throw exceptions can lead to unexpected behaviour in the event of throwing.\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TopicResizing.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicResizing Resizing\n\n\nTODO: write this dox page!\n\nIs linked from the tutorial on the Matrix class.\n\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TopicScalarTypes.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicScalarTypes Scalar types\n\n\nTODO: write this dox page!\n\nIs linked from the tutorial on the Matrix class.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TopicVectorization.dox",
    "content": "namespace Eigen {\n\n/** \\page TopicVectorization Vectorization\n\n\nTODO: write this dox page!\n\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TutorialAdvancedInitialization.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialAdvancedInitialization Advanced initialization\n\nThis page discusses several advanced methods for initializing matrices. It gives more details on the\ncomma-initializer, which was introduced before. It also explains how to get special matrices such as the\nidentity matrix and the zero matrix.\n\n\\eigenAutoToc\n\n\\section TutorialAdvancedInitializationCommaInitializer The comma initializer\n\nEigen offers a comma initializer syntax which allows the user to easily set all the coefficients of a matrix,\nvector or array. Simply list the coefficients, starting at the top-left corner and moving from left to right\nand from the top to the bottom. The size of the object needs to be specified beforehand. If you list too few\nor too many coefficients, Eigen will complain.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_commainit_01.cpp\n</td>\n<td>\n\\verbinclude Tutorial_commainit_01.out\n</td></tr></table>\n\nMoreover, the elements of the initialization list may themselves be vectors or matrices. A common use is\nto join vectors or matrices together. For example, here is how to join two row vectors together. Remember\nthat you have to set the size before you can use the comma initializer.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_AdvancedInitialization_Join.cpp\n</td>\n<td>\n\\verbinclude Tutorial_AdvancedInitialization_Join.out\n</td></tr></table>\n\nWe can use the same technique to initialize matrices with a block structure.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_AdvancedInitialization_Block.cpp\n</td>\n<td>\n\\verbinclude Tutorial_AdvancedInitialization_Block.out\n</td></tr></table>\n\nThe comma initializer can also be used to fill block expressions such as <tt>m.row(i)</tt>. Here is a more\ncomplicated way to get the same result as in the first example above:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_commainit_01b.cpp\n</td>\n<td>\n\\verbinclude Tutorial_commainit_01b.out\n</td></tr></table>\n\n\n\\section TutorialAdvancedInitializationSpecialMatrices Special matrices and arrays\n\nThe Matrix and Array classes have static methods like \\link DenseBase::Zero() Zero()\\endlink, which can be\nused to initialize all coefficients to zero. There are three variants. The first variant takes no arguments\nand can only be used for fixed-size objects. If you want to initialize a dynamic-size object to zero, you need\nto specify the size. Thus, the second variant requires one argument and can be used for one-dimensional\ndynamic-size objects, while the third variant requires two arguments and can be used for two-dimensional\nobjects. All three variants are illustrated in the following example:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_AdvancedInitialization_Zero.cpp\n</td>\n<td>\n\\verbinclude Tutorial_AdvancedInitialization_Zero.out\n</td></tr></table>\n\nSimilarly, the static method \\link DenseBase::Constant() Constant\\endlink(value) sets all coefficients to \\c value.\nIf the size of the object needs to be specified, the additional arguments go before the \\c value\nargument, as in <tt>MatrixXd::Constant(rows, cols, value)</tt>. The method \\link DenseBase::Random() Random()\n\\endlink fills the matrix or array with random coefficients. The identity matrix can be obtained by calling\n\\link MatrixBase::Identity() Identity()\\endlink; this method is only available for Matrix, not for Array,\nbecause \"identity matrix\" is a linear algebra concept.  The method\n\\link DenseBase::LinSpaced LinSpaced\\endlink(size, low, high) is only available for vectors and\none-dimensional arrays; it yields a vector of the specified size whose coefficients are equally spaced between\n\\c low and \\c high. The method \\c LinSpaced() is illustrated in the following example, which prints a table\nwith angles in degrees, the corresponding angle in radians, and their sine and cosine.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_AdvancedInitialization_LinSpaced.cpp\n</td>\n<td>\n\\verbinclude Tutorial_AdvancedInitialization_LinSpaced.out\n</td></tr></table>\n\nThis example shows that objects like the ones returned by LinSpaced() can be assigned to variables (and\nexpressions). Eigen defines utility functions like \\link DenseBase::setZero() setZero()\\endlink, \n\\link MatrixBase::setIdentity() \\endlink and \\link DenseBase::setLinSpaced() \\endlink to do this\nconveniently. The following example contrasts three ways to construct the matrix\n\\f$ J = \\bigl[ \\begin{smallmatrix} O & I \\\\ I & O \\end{smallmatrix} \\bigr] \\f$: using static methods and\nassignment, using static methods and the comma-initializer, or using the setXxx() methods.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_AdvancedInitialization_ThreeWays.cpp\n</td>\n<td>\n\\verbinclude Tutorial_AdvancedInitialization_ThreeWays.out\n</td></tr></table>\n\nA summary of all pre-defined matrix, vector and array objects can be found in the \\ref QuickRefPage.\n\n\n\\section TutorialAdvancedInitializationTemporaryObjects Usage as temporary objects\n\nAs shown above, static methods as Zero() and Constant() can be used to initialize variables at the time of\ndeclaration or at the right-hand side of an assignment operator. You can think of these methods as returning a\nmatrix or array; in fact, they return so-called \\ref TopicEigenExpressionTemplates \"expression objects\" which\nevaluate to a matrix or array when needed, so that this syntax does not incur any overhead.\n\nThese expressions can also be used as a temporary object. The second example in\nthe \\ref GettingStarted guide, which we reproduce here, already illustrates this.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include QuickStart_example2_dynamic.cpp\n</td>\n<td>\n\\verbinclude QuickStart_example2_dynamic.out\n</td></tr></table>\n\nThe expression <tt>m + MatrixXf::Constant(3,3,1.2)</tt> constructs the 3-by-3 matrix expression with all its coefficients\nequal to 1.2 plus the corresponding coefficient of \\a m.\n\nThe comma-initializer, too, can also be used to construct temporary objects. The following example constructs a random\nmatrix of size 2-by-3, and then multiplies this matrix on the left with \n\\f$ \\bigl[ \\begin{smallmatrix} 0 & 1 \\\\ 1 & 0 \\end{smallmatrix} \\bigr] \\f$.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_AdvancedInitialization_CommaTemporary.cpp\n</td>\n<td>\n\\verbinclude Tutorial_AdvancedInitialization_CommaTemporary.out\n</td></tr></table>\n\nThe \\link CommaInitializer::finished() finished() \\endlink method is necessary here to get the actual matrix\nobject once the comma initialization of our temporary submatrix is done.\n\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TutorialArrayClass.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialArrayClass The Array class and coefficient-wise operations\n\nThis page aims to provide an overview and explanations on how to use\nEigen's Array class.\n\n\\eigenAutoToc\n  \n\\section TutorialArrayClassIntro What is the Array class?\n\nThe Array class provides general-purpose arrays, as opposed to the Matrix class which\nis intended for linear algebra. Furthermore, the Array class provides an easy way to\nperform coefficient-wise operations, which might not have a linear algebraic meaning,\nsuch as adding a constant to every coefficient in the array or multiplying two arrays coefficient-wise.\n\n\n\\section TutorialArrayClassTypes Array types\nArray is a class template taking the same template parameters as Matrix.\nAs with Matrix, the first three template parameters are mandatory:\n\\code\nArray<typename Scalar, int RowsAtCompileTime, int ColsAtCompileTime>\n\\endcode\nThe last three template parameters are optional. Since this is exactly the same as for Matrix,\nwe won't explain it again here and just refer to \\ref TutorialMatrixClass.\n\nEigen also provides typedefs for some common cases, in a way that is similar to the Matrix typedefs\nbut with some slight differences, as the word \"array\" is used for both 1-dimensional and 2-dimensional arrays.\nWe adopt the convention that typedefs of the form ArrayNt stand for 1-dimensional arrays, where N and t are\nthe size and the scalar type, as in the Matrix typedefs explained on \\ref TutorialMatrixClass \"this page\". For 2-dimensional arrays, we\nuse typedefs of the form ArrayNNt. Some examples are shown in the following table:\n\n<table class=\"manual\">\n  <tr>\n    <th>Type </th>\n    <th>Typedef </th>\n  </tr>\n  <tr>\n    <td> \\code Array<float,Dynamic,1> \\endcode </td>\n    <td> \\code ArrayXf \\endcode </td>\n  </tr>\n  <tr>\n    <td> \\code Array<float,3,1> \\endcode </td>\n    <td> \\code Array3f \\endcode </td>\n  </tr>\n  <tr>\n    <td> \\code Array<double,Dynamic,Dynamic> \\endcode </td>\n    <td> \\code ArrayXXd \\endcode </td>\n  </tr>\n  <tr>\n    <td> \\code Array<double,3,3> \\endcode </td>\n    <td> \\code Array33d \\endcode </td>\n  </tr>\n</table>\n\n\n\\section TutorialArrayClassAccess Accessing values inside an Array\n\nThe parenthesis operator is overloaded to provide write and read access to the coefficients of an array, just as with matrices.\nFurthermore, the \\c << operator can be used to initialize arrays (via the comma initializer) or to print them.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ArrayClass_accessors.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ArrayClass_accessors.out\n</td></tr></table>\n\nFor more information about the comma initializer, see \\ref TutorialAdvancedInitialization.\n\n\n\\section TutorialArrayClassAddSub Addition and subtraction\n\nAdding and subtracting two arrays is the same as for matrices.\nThe operation is valid if both arrays have the same size, and the addition or subtraction is done coefficient-wise.\n\nArrays also support expressions of the form <tt>array + scalar</tt> which add a scalar to each coefficient in the array.\nThis provides a functionality that is not directly available for Matrix objects.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ArrayClass_addition.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ArrayClass_addition.out\n</td></tr></table>\n\n\n\\section TutorialArrayClassMult Array multiplication\n\nFirst of all, of course you can multiply an array by a scalar, this works in the same way as matrices. Where arrays\nare fundamentally different from matrices, is when you multiply two together. Matrices interpret\nmultiplication as matrix product and arrays interpret multiplication as coefficient-wise product. Thus, two \narrays can be multiplied if and only if they have the same dimensions.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ArrayClass_mult.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ArrayClass_mult.out\n</td></tr></table>\n\n\n\\section TutorialArrayClassCwiseOther Other coefficient-wise operations\n\nThe Array class defines other coefficient-wise operations besides the addition, subtraction and multiplication\noperators described above. For example, the \\link ArrayBase::abs() .abs() \\endlink method takes the absolute\nvalue of each coefficient, while \\link ArrayBase::sqrt() .sqrt() \\endlink computes the square root of the\ncoefficients. If you have two arrays of the same size, you can call \\link ArrayBase::min(const Eigen::ArrayBase<OtherDerived>&) const .min(.) \\endlink to\nconstruct the array whose coefficients are the minimum of the corresponding coefficients of the two given\narrays. These operations are illustrated in the following example.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ArrayClass_cwise_other.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ArrayClass_cwise_other.out\n</td></tr></table>\n\nMore coefficient-wise operations can be found in the \\ref QuickRefPage.\n\n\n\\section TutorialArrayClassConvert Converting between array and matrix expressions\n\nWhen should you use objects of the Matrix class and when should you use objects of the Array class? You cannot\napply Matrix operations on arrays, or Array operations on matrices. Thus, if you need to do linear algebraic\noperations such as matrix multiplication, then you should use matrices; if you need to do coefficient-wise\noperations, then you should use arrays. However, sometimes it is not that simple, but you need to use both\nMatrix and Array operations. In that case, you need to convert a matrix to an array or reversely. This gives\naccess to all operations regardless of the choice of declaring objects as arrays or as matrices.\n\n\\link MatrixBase Matrix expressions \\endlink have an \\link MatrixBase::array() .array() \\endlink method that\n'converts' them into \\link ArrayBase array expressions\\endlink, so that coefficient-wise operations\ncan be applied easily. Conversely, \\link ArrayBase array expressions \\endlink\nhave a \\link ArrayBase::matrix() .matrix() \\endlink method. As with all Eigen expression abstractions,\nthis doesn't have any runtime cost (provided that you let your compiler optimize).\nBoth \\link MatrixBase::array() .array() \\endlink and \\link ArrayBase::matrix() .matrix() \\endlink \ncan be used as rvalues and as lvalues.\n\nMixing matrices and arrays in an expression is forbidden with Eigen. For instance, you cannot add a matrix and\narray directly; the operands of a \\c + operator should either both be matrices or both be arrays. However,\nit is easy to convert from one to the other with \\link MatrixBase::array() .array() \\endlink and \n\\link ArrayBase::matrix() .matrix()\\endlink. The exception to this rule is the assignment operator: it is\nallowed to assign a matrix expression to an array variable, or to assign an array expression to a matrix\nvariable.\n\nThe following example shows how to use array operations on a Matrix object by employing the \n\\link MatrixBase::array() .array() \\endlink method. For example, the statement \n<tt>result = m.array() * n.array()</tt> takes two matrices \\c m and \\c n, converts them both to an array, uses\n* to multiply them coefficient-wise and assigns the result to the matrix variable \\c result (this is legal\nbecause Eigen allows assigning array expressions to matrix variables). \n\nAs a matter of fact, this usage case is so common that Eigen provides a \\link MatrixBase::cwiseProduct const\n.cwiseProduct(.) \\endlink method for matrices to compute the coefficient-wise product. This is also shown in\nthe example program.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ArrayClass_interop_matrix.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ArrayClass_interop_matrix.out\n</td></tr></table>\n\nSimilarly, if \\c array1 and \\c array2 are arrays, then the expression <tt>array1.matrix() * array2.matrix()</tt>\ncomputes their matrix product.\n\nHere is a more advanced example. The expression <tt>(m.array() + 4).matrix() * m</tt> adds 4 to every\ncoefficient in the matrix \\c m and then computes the matrix product of the result with \\c m. Similarly, the\nexpression <tt>(m.array() * n.array()).matrix() * m</tt> computes the coefficient-wise product of the matrices\n\\c m and \\c n and then the matrix product of the result with \\c m.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ArrayClass_interop.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ArrayClass_interop.out\n</td></tr></table>\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TutorialBlockOperations.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialBlockOperations Block operations\n\nThis page explains the essentials of block operations.\nA block is a rectangular part of a matrix or array. Blocks expressions can be used both\nas rvalues and as lvalues. As usual with Eigen expressions, this abstraction has zero runtime cost\nprovided that you let your compiler optimize.\n\n\\eigenAutoToc\n\n\\section TutorialBlockOperationsUsing Using block operations\n\nThe most general block operation in Eigen is called \\link DenseBase::block() .block() \\endlink.\nThere are two versions, whose syntax is as follows:\n\n<table class=\"manual\">\n<tr><th>\\b %Block \\b operation</td>\n<th>Version constructing a \\n dynamic-size block expression</th>\n<th>Version constructing a \\n fixed-size block expression</th></tr>\n<tr><td>%Block of size <tt>(p,q)</tt>, starting at <tt>(i,j)</tt></td>\n    <td>\\code\nmatrix.block(i,j,p,q);\\endcode </td>\n    <td>\\code \nmatrix.block<p,q>(i,j);\\endcode </td>\n</tr>\n</table>\n\nAs always in Eigen, indices start at 0.\n\nBoth versions can be used on fixed-size and dynamic-size matrices and arrays.\nThese two expressions are semantically equivalent.\nThe only difference is that the fixed-size version will typically give you faster code if the block size is small,\nbut requires this size to be known at compile time.\n\nThe following program uses the dynamic-size and fixed-size versions to print the values of several blocks inside a\nmatrix.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_BlockOperations_print_block.cpp\n</td>\n<td>\n\\verbinclude Tutorial_BlockOperations_print_block.out\n</td></tr></table>\n\nIn the above example the \\link DenseBase::block() .block() \\endlink function was employed as a \\em rvalue, i.e.\nit was only read from. However, blocks can also be used as \\em lvalues, meaning that you can assign to a block.\n\nThis is illustrated in the following example. This example also demonstrates blocks in arrays, which works exactly like the above-demonstrated blocks in matrices.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_BlockOperations_block_assignment.cpp\n</td>\n<td>\n\\verbinclude Tutorial_BlockOperations_block_assignment.out\n</td></tr></table>\n\nWhile the \\link DenseBase::block() .block() \\endlink method can be used for any block operation, there are\nother methods for special cases, providing more specialized API and/or better performance. On the topic of performance, all what\nmatters is that you give Eigen as much information as possible at compile time. For example, if your block is a single whole column in a matrix,\nusing the specialized \\link DenseBase::col() .col() \\endlink function described below lets Eigen know that, which can give it optimization opportunities.\n\nThe rest of this page describes these specialized methods.\n\n\\section TutorialBlockOperationsSyntaxColumnRows Columns and rows\n\nIndividual columns and rows are special cases of blocks. Eigen provides methods to easily address them:\n\\link DenseBase::col() .col() \\endlink and \\link DenseBase::row() .row()\\endlink.\n\n<table class=\"manual\">\n<tr><th>%Block operation</th>\n<th>Method</th>\n<tr><td>i<sup>th</sup> row\n                    \\link DenseBase::row() * \\endlink</td>\n    <td>\\code\nmatrix.row(i);\\endcode </td>\n</tr>\n<tr><td>j<sup>th</sup> column\n                    \\link DenseBase::col() * \\endlink</td>\n    <td>\\code\nmatrix.col(j);\\endcode </td>\n</tr>\n</table>\n\nThe argument for \\p col() and \\p row() is the index of the column or row to be accessed. As always in Eigen, indices start at 0.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_BlockOperations_colrow.cpp\n</td>\n<td>\n\\verbinclude Tutorial_BlockOperations_colrow.out\n</td></tr></table>\n\nThat example also demonstrates that block expressions (here columns) can be used in arithmetic like any other expression.\n\n\n\\section TutorialBlockOperationsSyntaxCorners Corner-related operations\n\nEigen also provides special methods for blocks that are flushed against one of the corners or sides of a\nmatrix or array. For instance, \\link DenseBase::topLeftCorner() .topLeftCorner() \\endlink can be used to refer\nto a block in the top-left corner of a matrix.\n\nThe different possibilities are summarized in the following table:\n\n<table class=\"manual\">\n<tr><th>%Block \\b operation</td>\n<th>Version constructing a \\n dynamic-size block expression</th>\n<th>Version constructing a \\n fixed-size block expression</th></tr>\n<tr><td>Top-left p by q block \\link DenseBase::topLeftCorner() * \\endlink</td>\n    <td>\\code\nmatrix.topLeftCorner(p,q);\\endcode </td>\n    <td>\\code \nmatrix.topLeftCorner<p,q>();\\endcode </td>\n</tr>\n<tr><td>Bottom-left p by q block\n              \\link DenseBase::bottomLeftCorner() * \\endlink</td>\n    <td>\\code\nmatrix.bottomLeftCorner(p,q);\\endcode </td>\n    <td>\\code \nmatrix.bottomLeftCorner<p,q>();\\endcode </td>\n</tr>\n<tr><td>Top-right p by q block\n              \\link DenseBase::topRightCorner() * \\endlink</td>\n    <td>\\code\nmatrix.topRightCorner(p,q);\\endcode </td>\n    <td>\\code \nmatrix.topRightCorner<p,q>();\\endcode </td>\n</tr>\n<tr><td>Bottom-right p by q block\n               \\link DenseBase::bottomRightCorner() * \\endlink</td>\n    <td>\\code\nmatrix.bottomRightCorner(p,q);\\endcode </td>\n    <td>\\code \nmatrix.bottomRightCorner<p,q>();\\endcode </td>\n</tr>\n<tr><td>%Block containing the first q rows\n                   \\link DenseBase::topRows() * \\endlink</td>\n    <td>\\code\nmatrix.topRows(q);\\endcode </td>\n    <td>\\code \nmatrix.topRows<q>();\\endcode </td>\n</tr>\n<tr><td>%Block containing the last q rows\n                    \\link DenseBase::bottomRows() * \\endlink</td>\n    <td>\\code\nmatrix.bottomRows(q);\\endcode </td>\n    <td>\\code \nmatrix.bottomRows<q>();\\endcode </td>\n</tr>\n<tr><td>%Block containing the first p columns\n                    \\link DenseBase::leftCols() * \\endlink</td>\n    <td>\\code\nmatrix.leftCols(p);\\endcode </td>\n    <td>\\code \nmatrix.leftCols<p>();\\endcode </td>\n</tr>\n<tr><td>%Block containing the last q columns\n                    \\link DenseBase::rightCols() * \\endlink</td>\n    <td>\\code\nmatrix.rightCols(q);\\endcode </td>\n    <td>\\code \nmatrix.rightCols<q>();\\endcode </td>\n</tr>\n</table>\n\nHere is a simple example illustrating the use of the operations presented above:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_BlockOperations_corner.cpp\n</td>\n<td>\n\\verbinclude Tutorial_BlockOperations_corner.out\n</td></tr></table>\n\n\n\\section TutorialBlockOperationsSyntaxVectors Block operations for vectors\n\nEigen also provides a set of block operations designed specifically for the special case of vectors and one-dimensional arrays:\n\n<table class=\"manual\">\n<tr><th> %Block operation</th>\n<th>Version constructing a \\n dynamic-size block expression</th>\n<th>Version constructing a \\n fixed-size block expression</th></tr>\n<tr><td>%Block containing the first \\p n elements \n                    \\link DenseBase::head() * \\endlink</td>\n    <td>\\code\nvector.head(n);\\endcode </td>\n    <td>\\code \nvector.head<n>();\\endcode </td>\n</tr>\n<tr><td>%Block containing the last \\p n elements\n                    \\link DenseBase::tail() * \\endlink</td>\n    <td>\\code\nvector.tail(n);\\endcode </td>\n    <td>\\code \nvector.tail<n>();\\endcode </td>\n</tr>\n<tr><td>%Block containing \\p n elements, starting at position \\p i\n                    \\link DenseBase::segment() * \\endlink</td>\n    <td>\\code\nvector.segment(i,n);\\endcode </td>\n    <td>\\code \nvector.segment<n>(i);\\endcode </td>\n</tr>\n</table>\n\n\nAn example is presented below:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_BlockOperations_vector.cpp\n</td>\n<td>\n\\verbinclude Tutorial_BlockOperations_vector.out\n</td></tr></table>\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TutorialGeometry.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialGeometry Space transformations\n\nIn this page, we will introduce the many possibilities offered by the \\ref Geometry_Module \"geometry module\" to deal with 2D and 3D rotations and projective or affine transformations.\n\n\\eigenAutoToc\n\nEigen's Geometry module provides two different kinds of geometric transformations:\n  - Abstract transformations, such as rotations (represented by \\ref AngleAxis \"angle and axis\" or by a \\ref Quaternion \"quaternion\"), \\ref Translation \"translations\", \\ref Scaling \"scalings\". These transformations are NOT represented as matrices, but you can nevertheless mix them with matrices and vectors in expressions, and convert them to matrices if you wish.\n  - Projective or affine transformation matrices: see the Transform class. These are really matrices.\n\n\\note If you are working with OpenGL 4x4 matrices then Affine3f and Affine3d are what you want. Since Eigen defaults to column-major storage, you can directly use the Transform::data() method to pass your transformation matrix to OpenGL.\n\nYou can construct a Transform from an abstract transformation, like this:\n\\code\n  Transform t(AngleAxis(angle,axis));\n\\endcode\nor like this:\n\\code\n  Transform t;\n  t = AngleAxis(angle,axis);\n\\endcode\nBut note that unfortunately, because of how C++ works, you can \\b not do this:\n\\code\n  Transform t = AngleAxis(angle,axis);\n\\endcode\n<span class=\"note\">\\b Explanation: In the C++ language, this would require Transform to have a non-explicit conversion constructor from AngleAxis, but we really don't want to allow implicit casting here.\n</span>\n\n\\section TutorialGeoElementaryTransformations Transformation types\n\n<table class=\"manual\">\n<tr><th>Transformation type</th><th>Typical initialization code</th></tr>\n<tr><td>\n\\ref Rotation2D \"2D rotation\" from an angle</td><td>\\code\nRotation2D<float> rot2(angle_in_radian);\\endcode</td></tr>\n<tr class=\"alt\"><td>\n3D rotation as an \\ref AngleAxis \"angle + axis\"</td><td>\\code\nAngleAxis<float> aa(angle_in_radian, Vector3f(ax,ay,az));\\endcode\n<span class=\"note\">The axis vector must be normalized.</span></td></tr>\n<tr><td>\n3D rotation as a \\ref Quaternion \"quaternion\"</td><td>\\code\nQuaternion<float> q;  q = AngleAxis<float>(angle_in_radian, axis);\\endcode</td></tr>\n<tr class=\"alt\"><td>\nN-D Scaling</td><td>\\code\nScaling(sx, sy)\nScaling(sx, sy, sz)\nScaling(s)\nScaling(vecN)\\endcode</td></tr>\n<tr><td>\nN-D Translation</td><td>\\code\nTranslation<float,2>(tx, ty)\nTranslation<float,3>(tx, ty, tz)\nTranslation<float,N>(s)\nTranslation<float,N>(vecN)\\endcode</td></tr>\n<tr class=\"alt\"><td>\nN-D \\ref TutorialGeoTransform \"Affine transformation\"</td><td>\\code\nTransform<float,N,Affine> t = concatenation_of_any_transformations;\nTransform<float,3,Affine> t = Translation3f(p) * AngleAxisf(a,axis) * Scaling(s);\\endcode</td></tr>\n<tr><td>\nN-D Linear transformations \\n\n<em class=note>(pure rotations, \\n scaling, etc.)</em></td><td>\\code\nMatrix<float,N> t = concatenation_of_rotations_and_scalings;\nMatrix<float,2> t = Rotation2Df(a) * Scaling(s);\nMatrix<float,3> t = AngleAxisf(a,axis) * Scaling(s);\\endcode</td></tr>\n</table>\n\n<strong>Notes on rotations</strong>\\n To transform more than a single vector the preferred\nrepresentations are rotation matrices, while for other usages Quaternion is the\nrepresentation of choice as they are compact, fast and stable. Finally Rotation2D and\nAngleAxis are mainly convenient types to create other rotation objects.\n\n<strong>Notes on Translation and Scaling</strong>\\n Like AngleAxis, these classes were\ndesigned to simplify the creation/initialization of linear (Matrix) and affine (Transform)\ntransformations. Nevertheless, unlike AngleAxis which is inefficient to use, these classes\nmight still be interesting to write generic and efficient algorithms taking as input any\nkind of transformations.\n\nAny of the above transformation types can be converted to any other types of the same nature,\nor to a more generic type. Here are some additional examples:\n<table class=\"manual\">\n<tr><td>\\code\nRotation2Df r;  r  = Matrix2f(..);       // assumes a pure rotation matrix\nAngleAxisf aa;  aa = Quaternionf(..);\nAngleAxisf aa;  aa = Matrix3f(..);       // assumes a pure rotation matrix\nMatrix2f m;     m  = Rotation2Df(..);\nMatrix3f m;     m  = Quaternionf(..);       Matrix3f m;   m = Scaling(..);\nAffine3f m;     m  = AngleAxis3f(..);       Affine3f m;   m = Scaling(..);\nAffine3f m;     m  = Translation3f(..);     Affine3f m;   m = Matrix3f(..);\n\\endcode</td></tr>\n</table>\n\n\n<a href=\"#\" class=\"top\">top</a>\\section TutorialGeoCommontransformationAPI Common API across transformation types\n\nTo some extent, Eigen's \\ref Geometry_Module \"geometry module\" allows you to write\ngeneric algorithms working on any kind of transformation representations:\n<table class=\"manual\">\n<tr><td>\nConcatenation of two transformations</td><td>\\code\ngen1 * gen2;\\endcode</td></tr>\n<tr class=\"alt\"><td>Apply the transformation to a vector</td><td>\\code\nvec2 = gen1 * vec1;\\endcode</td></tr>\n<tr><td>Get the inverse of the transformation</td><td>\\code\ngen2 = gen1.inverse();\\endcode</td></tr>\n<tr class=\"alt\"><td>Spherical interpolation \\n (Rotation2D and Quaternion only)</td><td>\\code\nrot3 = rot1.slerp(alpha,rot2);\\endcode</td></tr>\n</table>\n\n\n\n<a href=\"#\" class=\"top\">top</a>\\section TutorialGeoTransform Affine transformations\nGeneric affine transformations are represented by the Transform class which internally\nis a (Dim+1)^2 matrix. In Eigen we have chosen to not distinghish between points and\nvectors such that all points are actually represented by displacement vectors from the\norigin ( \\f$ \\mathbf{p} \\equiv \\mathbf{p}-0 \\f$ ). With that in mind, real points and\nvector distinguish when the transformation is applied.\n<table class=\"manual\">\n<tr><td>\nApply the transformation to a \\b point </td><td>\\code\nVectorNf p1, p2;\np2 = t * p1;\\endcode</td></tr>\n<tr class=\"alt\"><td>\nApply the transformation to a \\b vector </td><td>\\code\nVectorNf vec1, vec2;\nvec2 = t.linear() * vec1;\\endcode</td></tr>\n<tr><td>\nApply a \\em general transformation \\n to a \\b normal \\b vector \\n\n</td><td>\\code\nVectorNf n1, n2;\nMatrixNf normalMatrix = t.linear().inverse().transpose();\nn2 = (normalMatrix * n1).normalized();\\endcode</td></tr>\n<tr><td colspan=\"2\">(See subject 5.27 of this <a href=\"http://www.faqs.org/faqs/graphics/algorithms-faq\">faq</a> for the explanations)</td></tr>\n<tr class=\"alt\"><td>\nApply a transformation with \\em pure \\em rotation \\n to a \\b normal \\b vector\n(no scaling, no shear)</td><td>\\code\nn2 = t.linear() * n1;\\endcode</td></tr>\n<tr><td>\nOpenGL compatibility \\b 3D </td><td>\\code\nglLoadMatrixf(t.data());\\endcode</td></tr>\n<tr class=\"alt\"><td>\nOpenGL compatibility \\b 2D </td><td>\\code\nAffine3f aux(Affine3f::Identity());\naux.linear().topLeftCorner<2,2>() = t.linear();\naux.translation().start<2>() = t.translation();\nglLoadMatrixf(aux.data());\\endcode</td></tr>\n</table>\n\n\\b Component \\b accessors\n<table class=\"manual\">\n<tr><td>\nfull read-write access to the internal matrix</td><td>\\code\nt.matrix() = matN1xN1;    // N1 means N+1\nmatN1xN1 = t.matrix();\n\\endcode</td></tr>\n<tr class=\"alt\"><td>\ncoefficient accessors</td><td>\\code\nt(i,j) = scalar;   <=>   t.matrix()(i,j) = scalar;\nscalar = t(i,j);   <=>   scalar = t.matrix()(i,j);\n\\endcode</td></tr>\n<tr><td>\ntranslation part</td><td>\\code\nt.translation() = vecN;\nvecN = t.translation();\n\\endcode</td></tr>\n<tr class=\"alt\"><td>\nlinear part</td><td>\\code\nt.linear() = matNxN;\nmatNxN = t.linear();\n\\endcode</td></tr>\n<tr><td>\nextract the rotation matrix</td><td>\\code\nmatNxN = t.rotation();\n\\endcode</td></tr>\n</table>\n\n\n\\b Transformation \\b creation \\n\nWhile transformation objects can be created and updated concatenating elementary transformations,\nthe Transform class also features a procedural API:\n<table class=\"manual\">\n<tr><th></th><th>procedural API</th><th>equivalent natural API </th></tr>\n<tr><td>Translation</td><td>\\code\nt.translate(Vector_(tx,ty,..));\nt.pretranslate(Vector_(tx,ty,..));\n\\endcode</td><td>\\code\nt *= Translation_(tx,ty,..);\nt = Translation_(tx,ty,..) * t;\n\\endcode</td></tr>\n<tr class=\"alt\"><td>\\b Rotation \\n <em class=\"note\">In 2D and for the procedural API, any_rotation can also \\n be an angle in radian</em></td><td>\\code\nt.rotate(any_rotation);\nt.prerotate(any_rotation);\n\\endcode</td><td>\\code\nt *= any_rotation;\nt = any_rotation * t;\n\\endcode</td></tr>\n<tr><td>Scaling</td><td>\\code\nt.scale(Vector_(sx,sy,..));\nt.scale(s);\nt.prescale(Vector_(sx,sy,..));\nt.prescale(s);\n\\endcode</td><td>\\code\nt *= Scaling(sx,sy,..);\nt *= Scaling(s);\nt = Scaling(sx,sy,..) * t;\nt = Scaling(s) * t;\n\\endcode</td></tr>\n<tr class=\"alt\"><td>Shear transformation \\n ( \\b 2D \\b only ! )</td><td>\\code\nt.shear(sx,sy);\nt.preshear(sx,sy);\n\\endcode</td><td></td></tr>\n</table>\n\nNote that in both API, any many transformations can be concatenated in a single expression as shown in the two following equivalent examples:\n<table class=\"manual\">\n<tr><td>\\code\nt.pretranslate(..).rotate(..).translate(..).scale(..);\n\\endcode</td></tr>\n<tr><td>\\code\nt = Translation_(..) * t * RotationType(..) * Translation_(..) * Scaling(..);\n\\endcode</td></tr>\n</table>\n\n\n\n<a href=\"#\" class=\"top\">top</a>\\section TutorialGeoEulerAngles Euler angles\n<table class=\"manual\">\n<tr><td style=\"max-width:30em;\">\nEuler angles might be convenient to create rotation objects.\nOn the other hand, since there exist 24 different conventions, they are pretty confusing to use. This example shows how\nto create a rotation matrix according to the 2-1-2 convention.</td><td>\\code\nMatrix3f m;\nm = AngleAxisf(angle1, Vector3f::UnitZ())\n *  * AngleAxisf(angle2, Vector3f::UnitY())\n *  * AngleAxisf(angle3, Vector3f::UnitZ());\n\\endcode</td></tr>\n</table>\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TutorialLinearAlgebra.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialLinearAlgebra Linear algebra and decompositions\n\nThis page explains how to solve linear systems, compute various decompositions such as LU,\nQR, %SVD, eigendecompositions... After reading this page, don't miss our\n\\link TopicLinearAlgebraDecompositions catalogue \\endlink of dense matrix decompositions.\n\n\\eigenAutoToc\n\n\\section TutorialLinAlgBasicSolve Basic linear solving\n\n\\b The \\b problem: You have a system of equations, that you have written as a single matrix equation\n    \\f[ Ax \\: = \\: b \\f]\nWhere \\a A and \\a b are matrices (\\a b could be a vector, as a special case). You want to find a solution \\a x.\n\n\\b The \\b solution: You can choose between various decompositions, depending on what your matrix \\a A looks like,\nand depending on whether you favor speed or accuracy. However, let's start with an example that works in all cases,\nand is a good compromise:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include TutorialLinAlgExSolveColPivHouseholderQR.cpp </td>\n  <td>\\verbinclude TutorialLinAlgExSolveColPivHouseholderQR.out </td>\n</tr>\n</table>\n\nIn this example, the colPivHouseholderQr() method returns an object of class ColPivHouseholderQR. Since here the\nmatrix is of type Matrix3f, this line could have been replaced by:\n\\code\nColPivHouseholderQR<Matrix3f> dec(A);\nVector3f x = dec.solve(b);\n\\endcode\n\nHere, ColPivHouseholderQR is a QR decomposition with column pivoting. It's a good compromise for this tutorial, as it\nworks for all matrices while being quite fast. Here is a table of some other decompositions that you can choose from,\ndepending on your matrix and the trade-off you want to make:\n\n<table class=\"manual\">\n    <tr>\n        <th>Decomposition</th>\n        <th>Method</th>\n        <th>Requirements<br/>on the matrix</th>\n        <th>Speed<br/> (small-to-medium)</th>\n        <th>Speed<br/> (large)</th>\n        <th>Accuracy</th>\n    </tr>\n    <tr>\n        <td>PartialPivLU</td>\n        <td>partialPivLu()</td>\n        <td>Invertible</td>\n        <td>++</td>\n        <td>++</td>\n        <td>+</td>\n    </tr>\n    <tr class=\"alt\">\n        <td>FullPivLU</td>\n        <td>fullPivLu()</td>\n        <td>None</td>\n        <td>-</td>\n        <td>- -</td>\n        <td>+++</td>\n    </tr>\n    <tr>\n        <td>HouseholderQR</td>\n        <td>householderQr()</td>\n        <td>None</td>\n        <td>++</td>\n        <td>++</td>\n        <td>+</td>\n    </tr>\n    <tr class=\"alt\">\n        <td>ColPivHouseholderQR</td>\n        <td>colPivHouseholderQr()</td>\n        <td>None</td>\n        <td>+</td>\n        <td>-</td>\n        <td>+++</td>\n    </tr>\n    <tr>\n        <td>FullPivHouseholderQR</td>\n        <td>fullPivHouseholderQr()</td>\n        <td>None</td>\n        <td>-</td>\n        <td>- -</td>\n        <td>+++</td>\n    </tr>\n    <tr class=\"alt\">\n        <td>CompleteOrthogonalDecomposition</td>\n        <td>completeOrthogonalDecomposition()</td>\n        <td>None</td>\n        <td>+</td>\n        <td>-</td>\n        <td>+++</td>\n    </tr>\n    <tr class=\"alt\">\n        <td>LLT</td>\n        <td>llt()</td>\n        <td>Positive definite</td>\n        <td>+++</td>\n        <td>+++</td>\n        <td>+</td>\n    </tr>\n    <tr>\n        <td>LDLT</td>\n        <td>ldlt()</td>\n        <td>Positive or negative<br/> semidefinite</td>\n        <td>+++</td>\n        <td>+</td>\n        <td>++</td>\n    </tr>\n    <tr class=\"alt\">\n        <td>BDCSVD</td>\n        <td>bdcSvd()</td>\n        <td>None</td>\n        <td>-</td>\n        <td>-</td>\n        <td>+++</td>\n    </tr>\n    <tr class=\"alt\">\n        <td>JacobiSVD</td>\n        <td>jacobiSvd()</td>\n        <td>None</td>\n        <td>-</td>\n        <td>- - -</td>\n        <td>+++</td>\n    </tr>\n</table>\nTo get an overview of the true relative speed of the different decompositions, check this \\link DenseDecompositionBenchmark benchmark \\endlink.\n\nAll of these decompositions offer a solve() method that works as in the above example.\n\nFor example, if your matrix is positive definite, the above table says that a very good\nchoice is then the LLT or LDLT decomposition. Here's an example, also demonstrating that using a general\nmatrix (not a vector) as right hand side is possible.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include TutorialLinAlgExSolveLDLT.cpp </td>\n  <td>\\verbinclude TutorialLinAlgExSolveLDLT.out </td>\n</tr>\n</table>\n\nFor a \\ref TopicLinearAlgebraDecompositions \"much more complete table\" comparing all decompositions supported by Eigen (notice that Eigen\nsupports many other decompositions), see our special page on\n\\ref TopicLinearAlgebraDecompositions \"this topic\".\n\n\\section TutorialLinAlgSolutionExists Checking if a solution really exists\n\nOnly you know what error margin you want to allow for a solution to be considered valid.\nSo Eigen lets you do this computation for yourself, if you want to, as in this example:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include TutorialLinAlgExComputeSolveError.cpp </td>\n  <td>\\verbinclude TutorialLinAlgExComputeSolveError.out </td>\n</tr>\n</table>\n\n\\section TutorialLinAlgEigensolving Computing eigenvalues and eigenvectors\n\nYou need an eigendecomposition here, see available such decompositions on \\ref TopicLinearAlgebraDecompositions \"this page\".\nMake sure to check if your matrix is self-adjoint, as is often the case in these problems. Here's an example using\nSelfAdjointEigenSolver, it could easily be adapted to general matrices using EigenSolver or ComplexEigenSolver.\n\nThe computation of eigenvalues and eigenvectors does not necessarily converge, but such failure to converge is\nvery rare. The call to info() is to check for this possibility.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include TutorialLinAlgSelfAdjointEigenSolver.cpp </td>\n  <td>\\verbinclude TutorialLinAlgSelfAdjointEigenSolver.out </td>\n</tr>\n</table>\n\n\\section TutorialLinAlgInverse Computing inverse and determinant\n\nFirst of all, make sure that you really want this. While inverse and determinant are fundamental mathematical concepts,\nin \\em numerical linear algebra they are not as popular as in pure mathematics. Inverse computations are often\nadvantageously replaced by solve() operations, and the determinant is often \\em not a good way of checking if a matrix\nis invertible.\n\nHowever, for \\em very \\em small matrices, the above is not true, and inverse and determinant can be very useful.\n\nWhile certain decompositions, such as PartialPivLU and FullPivLU, offer inverse() and determinant() methods, you can also\ncall inverse() and determinant() directly on a matrix. If your matrix is of a very small fixed size (at most 4x4) this\nallows Eigen to avoid performing a LU decomposition, and instead use formulas that are more efficient on such small matrices.\n\nHere is an example:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include TutorialLinAlgInverseDeterminant.cpp </td>\n  <td>\\verbinclude TutorialLinAlgInverseDeterminant.out </td>\n</tr>\n</table>\n\n\\section TutorialLinAlgLeastsquares Least squares solving\n\nThe most accurate method to do least squares solving is with a SVD decomposition.\nEigen provides two implementations.\nThe recommended one is the BDCSVD class, which scale well for large problems\nand automatically fall-back to the JacobiSVD class for smaller problems.\nFor both classes, their solve() method is doing least-squares solving.\n\nHere is an example:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include TutorialLinAlgSVDSolve.cpp </td>\n  <td>\\verbinclude TutorialLinAlgSVDSolve.out </td>\n</tr>\n</table>\n\nAnother methods, potentially faster but less reliable, are to use a Cholesky decomposition of the\nnormal matrix or a QR decomposition. Our page on \\link LeastSquares least squares solving \\endlink\nhas more details.\n\n\n\\section TutorialLinAlgSeparateComputation Separating the computation from the construction\n\nIn the above examples, the decomposition was computed at the same time that the decomposition object was constructed.\nThere are however situations where you might want to separate these two things, for example if you don't know,\nat the time of the construction, the matrix that you will want to decompose; or if you want to reuse an existing\ndecomposition object.\n\nWhat makes this possible is that:\n\\li all decompositions have a default constructor,\n\\li all decompositions have a compute(matrix) method that does the computation, and that may be called again\n    on an already-computed decomposition, reinitializing it.\n\nFor example:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include TutorialLinAlgComputeTwice.cpp </td>\n  <td>\\verbinclude TutorialLinAlgComputeTwice.out </td>\n</tr>\n</table>\n\nFinally, you can tell the decomposition constructor to preallocate storage for decomposing matrices of a given size,\nso that when you subsequently decompose such matrices, no dynamic memory allocation is performed (of course, if you\nare using fixed-size matrices, no dynamic memory allocation happens at all). This is done by just\npassing the size to the decomposition constructor, as in this example:\n\\code\nHouseholderQR<MatrixXf> qr(50,50);\nMatrixXf A = MatrixXf::Random(50,50);\nqr.compute(A); // no dynamic memory allocation\n\\endcode\n\n\\section TutorialLinAlgRankRevealing Rank-revealing decompositions\n\nCertain decompositions are rank-revealing, i.e. are able to compute the rank of a matrix. These are typically\nalso the decompositions that behave best in the face of a non-full-rank matrix (which in the square case means a\nsingular matrix). On \\ref TopicLinearAlgebraDecompositions \"this table\" you can see for all our decompositions\nwhether they are rank-revealing or not.\n\nRank-revealing decompositions offer at least a rank() method. They can also offer convenience methods such as isInvertible(),\nand some are also providing methods to compute the kernel (null-space) and image (column-space) of the matrix, as is the\ncase with FullPivLU:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include TutorialLinAlgRankRevealing.cpp </td>\n  <td>\\verbinclude TutorialLinAlgRankRevealing.out </td>\n</tr>\n</table>\n\nOf course, any rank computation depends on the choice of an arbitrary threshold, since practically no\nfloating-point matrix is \\em exactly rank-deficient. Eigen picks a sensible default threshold, which depends\non the decomposition but is typically the diagonal size times machine epsilon. While this is the best default we\ncould pick, only you know what is the right threshold for your application. You can set this by calling setThreshold()\non your decomposition object before calling rank() or any other method that needs to use such a threshold.\nThe decomposition itself, i.e. the compute() method, is independent of the threshold. You don't need to recompute the\ndecomposition after you've changed the threshold.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n  <td>\\include TutorialLinAlgSetThreshold.cpp </td>\n  <td>\\verbinclude TutorialLinAlgSetThreshold.out </td>\n</tr>\n</table>\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TutorialMapClass.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialMapClass Interfacing with raw buffers: the Map class\n\nThis page explains how to work with \"raw\" C/C++ arrays.\nThis can be useful in a variety of contexts, particularly when \"importing\" vectors and matrices from other libraries into %Eigen.\n\n\\eigenAutoToc\n\n\\section TutorialMapIntroduction Introduction\n\nOccasionally you may have a pre-defined array of numbers that you want to use within %Eigen as a vector or matrix. While one option is to make a copy of the data, most commonly you probably want to re-use this memory as an %Eigen type. Fortunately, this is very easy with the Map class.\n\n\\section TutorialMapTypes Map types and declaring Map variables\n\nA Map object has a type defined by its %Eigen equivalent:\n\\code\nMap<Matrix<typename Scalar, int RowsAtCompileTime, int ColsAtCompileTime> >\n\\endcode\nNote that, in this default case, a Map requires just a single template parameter.  \n\nTo construct a Map variable, you need two other pieces of information: a pointer to the region of memory defining the array of coefficients, and the desired shape of the matrix or vector.  For example, to define a matrix of \\c float with sizes determined at compile time, you might do the following:\n\\code\nMap<MatrixXf> mf(pf,rows,columns);\n\\endcode\nwhere \\c pf is a \\c float \\c * pointing to the array of memory.  A fixed-size read-only vector of integers might be declared as\n\\code\nMap<const Vector4i> mi(pi);\n\\endcode\nwhere \\c pi is an \\c int \\c *. In this case the size does not have to be passed to the constructor, because it is already specified by the Matrix/Array type.\n\nNote that Map does not have a default constructor; you \\em must pass a pointer to initialize the object. However, you can work around this requirement (see \\ref TutorialMapPlacementNew).\n\nMap is flexible enough to accommodate a variety of different data representations.  There are two other (optional) template parameters:\n\\code\nMap<typename MatrixType,\n    int MapOptions,\n    typename StrideType>\n\\endcode\n\\li \\c MapOptions specifies whether the pointer is \\c #Aligned, or \\c #Unaligned.  The default is \\c #Unaligned.\n\\li \\c StrideType allows you to specify a custom layout for the memory array, using the Stride class.  One example would be to specify that the data array is organized in row-major format:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n<td>\\include Tutorial_Map_rowmajor.cpp </td>\n<td>\\verbinclude Tutorial_Map_rowmajor.out </td>\n</table>\nHowever, Stride is even more flexible than this; for details, see the documentation for the Map and Stride classes.\n\n\\section TutorialMapUsing Using Map variables\n\nYou can use a Map object just like any other %Eigen type:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n<td>\\include Tutorial_Map_using.cpp </td>\n<td>\\verbinclude Tutorial_Map_using.out </td>\n</table>\n\nAll %Eigen functions are written to accept Map objects just like other %Eigen types. However, when writing your own functions taking %Eigen types, this does \\em not happen automatically: a Map type is not identical to its Dense equivalent.  See \\ref TopicFunctionTakingEigenTypes for details.\n\n\\section TutorialMapPlacementNew Changing the mapped array\n\nIt is possible to change the array of a Map object after declaration, using the C++ \"placement new\" syntax:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n<td>\\include Map_placement_new.cpp </td>\n<td>\\verbinclude Map_placement_new.out </td>\n</table>\nDespite appearances, this does not invoke the memory allocator, because the syntax specifies the location for storing the result.\n\nThis syntax makes it possible to declare a Map object without first knowing the mapped array's location in memory:\n\\code\nMap<Matrix3f> A(NULL);  // don't try to use this matrix yet!\nVectorXf b(n_matrices);\nfor (int i = 0; i < n_matrices; i++)\n{\n  new (&A) Map<Matrix3f>(get_matrix_pointer(i));\n  b(i) = A.trace();\n}\n\\endcode\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TutorialMatrixArithmetic.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialMatrixArithmetic Matrix and vector arithmetic\n\nThis page aims to provide an overview and some details on how to perform arithmetic\nbetween matrices, vectors and scalars with Eigen.\n\n\\eigenAutoToc\n\n\\section TutorialArithmeticIntroduction Introduction\n\nEigen offers matrix/vector arithmetic operations either through overloads of common C++ arithmetic operators such as +, -, *,\nor through special methods such as dot(), cross(), etc.\nFor the Matrix class (matrices and vectors), operators are only overloaded to support\nlinear-algebraic operations. For example, \\c matrix1 \\c * \\c matrix2 means matrix-matrix product,\nand \\c vector \\c + \\c scalar is just not allowed. If you want to perform all kinds of array operations,\nnot linear algebra, see the \\ref TutorialArrayClass \"next page\".\n\n\\section TutorialArithmeticAddSub Addition and subtraction\n\nThe left hand side and right hand side must, of course, have the same numbers of rows and of columns. They must\nalso have the same \\c Scalar type, as Eigen doesn't do automatic type promotion. The operators at hand here are:\n\\li binary operator + as in \\c a+b\n\\li binary operator - as in \\c a-b\n\\li unary operator - as in \\c -a\n\\li compound operator += as in \\c a+=b\n\\li compound operator -= as in \\c a-=b\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_arithmetic_add_sub.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_add_sub.out\n</td></tr></table>\n\n\\section TutorialArithmeticScalarMulDiv Scalar multiplication and division\n\nMultiplication and division by a scalar is very simple too. The operators at hand here are:\n\\li binary operator * as in \\c matrix*scalar\n\\li binary operator * as in \\c scalar*matrix\n\\li binary operator / as in \\c matrix/scalar\n\\li compound operator *= as in \\c matrix*=scalar\n\\li compound operator /= as in \\c matrix/=scalar\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_arithmetic_scalar_mul_div.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_scalar_mul_div.out\n</td></tr></table>\n\n\n\\section TutorialArithmeticMentionXprTemplates A note about expression templates\n\nThis is an advanced topic that we explain on \\ref TopicEigenExpressionTemplates \"this page\",\nbut it is useful to just mention it now. In Eigen, arithmetic operators such as \\c operator+ don't\nperform any computation by themselves, they just return an \"expression object\" describing the computation to be\nperformed. The actual computation happens later, when the whole expression is evaluated, typically in \\c operator=.\nWhile this might sound heavy, any modern optimizing compiler is able to optimize away that abstraction and\nthe result is perfectly optimized code. For example, when you do:\n\\code\nVectorXf a(50), b(50), c(50), d(50);\n...\na = 3*b + 4*c + 5*d;\n\\endcode\nEigen compiles it to just one for loop, so that the arrays are traversed only once. Simplifying (e.g. ignoring\nSIMD optimizations), this loop looks like this:\n\\code\nfor(int i = 0; i < 50; ++i)\n  a[i] = 3*b[i] + 4*c[i] + 5*d[i];\n\\endcode\nThus, you should not be afraid of using relatively large arithmetic expressions with Eigen: it only gives Eigen\nmore opportunities for optimization.\n\n\\section TutorialArithmeticTranspose Transposition and conjugation\n\nThe transpose \\f$ a^T \\f$, conjugate \\f$ \\bar{a} \\f$, and adjoint (i.e., conjugate transpose) \\f$ a^* \\f$ of a matrix or vector \\f$ a \\f$ are obtained by the member functions \\link DenseBase::transpose() transpose()\\endlink, \\link MatrixBase::conjugate() conjugate()\\endlink, and \\link MatrixBase::adjoint() adjoint()\\endlink, respectively.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_arithmetic_transpose_conjugate.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_transpose_conjugate.out\n</td></tr></table>\n\nFor real matrices, \\c conjugate() is a no-operation, and so \\c adjoint() is equivalent to \\c transpose().\n\nAs for basic arithmetic operators, \\c transpose() and \\c adjoint() simply return a proxy object without doing the actual transposition. If you do <tt>b = a.transpose()</tt>, then the transpose is evaluated at the same time as the result is written into \\c b. However, there is a complication here. If you do <tt>a = a.transpose()</tt>, then Eigen starts writing the result into \\c a before the evaluation of the transpose is finished. Therefore, the instruction <tt>a = a.transpose()</tt> does not replace \\c a with its transpose, as one would expect:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_arithmetic_transpose_aliasing.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_transpose_aliasing.out\n</td></tr></table>\nThis is the so-called \\ref TopicAliasing \"aliasing issue\". In \"debug mode\", i.e., when \\ref TopicAssertions \"assertions\" have not been disabled, such common pitfalls are automatically detected. \n\nFor \\em in-place transposition, as for instance in <tt>a = a.transpose()</tt>, simply use the \\link DenseBase::transposeInPlace() transposeInPlace()\\endlink  function:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_arithmetic_transpose_inplace.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_transpose_inplace.out\n</td></tr></table>\nThere is also the \\link MatrixBase::adjointInPlace() adjointInPlace()\\endlink function for complex matrices.\n\n\\section TutorialArithmeticMatrixMul Matrix-matrix and matrix-vector multiplication\n\nMatrix-matrix multiplication is again done with \\c operator*. Since vectors are a special\ncase of matrices, they are implicitly handled there too, so matrix-vector product is really just a special\ncase of matrix-matrix product, and so is vector-vector outer product. Thus, all these cases are handled by just\ntwo operators:\n\\li binary operator * as in \\c a*b\n\\li compound operator *= as in \\c a*=b (this multiplies on the right: \\c a*=b is equivalent to <tt>a = a*b</tt>)\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_arithmetic_matrix_mul.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_matrix_mul.out\n</td></tr></table>\n\nNote: if you read the above paragraph on expression templates and are worried that doing \\c m=m*m might cause\naliasing issues, be reassured for now: Eigen treats matrix multiplication as a special case and takes care of\nintroducing a temporary here, so it will compile \\c m=m*m as:\n\\code\ntmp = m*m;\nm = tmp;\n\\endcode\nIf you know your matrix product can be safely evaluated into the destination matrix without aliasing issue, then you can use the \\link MatrixBase::noalias() noalias()\\endlink function to avoid the temporary, e.g.:\n\\code\nc.noalias() += a * b;\n\\endcode\nFor more details on this topic, see the page on \\ref TopicAliasing \"aliasing\".\n\n\\b Note: for BLAS users worried about performance, expressions such as <tt>c.noalias() -= 2 * a.adjoint() * b;</tt> are fully optimized and trigger a single gemm-like function call.\n\n\\section TutorialArithmeticDotAndCross Dot product and cross product\n\nFor dot product and cross product, you need the \\link MatrixBase::dot() dot()\\endlink and \\link MatrixBase::cross() cross()\\endlink methods. Of course, the dot product can also be obtained as a 1x1 matrix as u.adjoint()*v.\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_arithmetic_dot_cross.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_dot_cross.out\n</td></tr></table>\n\nRemember that cross product is only for vectors of size 3. Dot product is for vectors of any sizes.\nWhen using complex numbers, Eigen's dot product is conjugate-linear in the first variable and linear in the\nsecond variable.\n\n\\section TutorialArithmeticRedux Basic arithmetic reduction operations\nEigen also provides some reduction operations to reduce a given matrix or vector to a single value such as the sum (computed by \\link DenseBase::sum() sum()\\endlink), product (\\link DenseBase::prod() prod()\\endlink), or the maximum (\\link DenseBase::maxCoeff() maxCoeff()\\endlink) and minimum (\\link DenseBase::minCoeff() minCoeff()\\endlink) of all its coefficients.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_arithmetic_redux_basic.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_redux_basic.out\n</td></tr></table>\n\nThe \\em trace of a matrix, as returned by the function \\link MatrixBase::trace() trace()\\endlink, is the sum of the diagonal coefficients and can also be computed as efficiently using <tt>a.diagonal().sum()</tt>, as we will see later on.\n\nThere also exist variants of the \\c minCoeff and \\c maxCoeff functions returning the coordinates of the respective coefficient via the arguments:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_arithmetic_redux_minmax.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_redux_minmax.out\n</td></tr></table>\n\n\n\\section TutorialArithmeticValidity Validity of operations\nEigen checks the validity of the operations that you perform. When possible,\nit checks them at compile time, producing compilation errors. These error messages can be long and ugly,\nbut Eigen writes the important message in UPPERCASE_LETTERS_SO_IT_STANDS_OUT. For example:\n\\code\n  Matrix3f m;\n  Vector4f v;\n  v = m*v;      // Compile-time error: YOU_MIXED_MATRICES_OF_DIFFERENT_SIZES\n\\endcode\n\nOf course, in many cases, for example when checking dynamic sizes, the check cannot be performed at compile time.\nEigen then uses runtime assertions. This means that the program will abort with an error message when executing an illegal operation if it is run in \"debug mode\", and it will probably crash if assertions are turned off.\n\n\\code\n  MatrixXf m(3,3);\n  VectorXf v(4);\n  v = m * v; // Run-time assertion failure here: \"invalid matrix product\"\n\\endcode\n\nFor more details on this topic, see \\ref TopicAssertions \"this page\".\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TutorialMatrixClass.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialMatrixClass The Matrix class\n\n\\eigenAutoToc\n\nIn Eigen, all matrices and vectors are objects of the Matrix template class.\nVectors are just a special case of matrices, with either 1 row or 1 column.\n\n\\section TutorialMatrixFirst3Params The first three template parameters of Matrix\n\nThe Matrix class takes six template parameters, but for now it's enough to\nlearn about the first three first parameters. The three remaining parameters have default\nvalues, which for now we will leave untouched, and which we\n\\ref TutorialMatrixOptTemplParams \"discuss below\".\n\nThe three mandatory template parameters of Matrix are:\n\\code\nMatrix<typename Scalar, int RowsAtCompileTime, int ColsAtCompileTime>\n\\endcode\n\\li \\c Scalar is the scalar type, i.e. the type of the coefficients.\n    That is, if you want a matrix of floats, choose \\c float here.\n    See \\ref TopicScalarTypes \"Scalar types\" for a list of all supported\n    scalar types and for how to extend support to new types.\n\\li \\c RowsAtCompileTime and \\c ColsAtCompileTime are the number of rows\n    and columns of the matrix as known at compile time (see \n    \\ref TutorialMatrixDynamic \"below\" for what to do if the number is not\n    known at compile time).\n\nWe offer a lot of convenience typedefs to cover the usual cases. For example, \\c Matrix4f is\na 4x4 matrix of floats. Here is how it is defined by Eigen:\n\\code\ntypedef Matrix<float, 4, 4> Matrix4f;\n\\endcode\nWe discuss \\ref TutorialMatrixTypedefs \"below\" these convenience typedefs.\n\n\\section TutorialMatrixVectors Vectors\n\nAs mentioned above, in Eigen, vectors are just a special case of\nmatrices, with either 1 row or 1 column. The case where they have 1 column is the most common;\nsuch vectors are called column-vectors, often abbreviated as just vectors. In the other case\nwhere they have 1 row, they are called row-vectors.\n\nFor example, the convenience typedef \\c Vector3f is a (column) vector of 3 floats. It is defined as follows by Eigen:\n\\code\ntypedef Matrix<float, 3, 1> Vector3f;\n\\endcode\nWe also offer convenience typedefs for row-vectors, for example:\n\\code\ntypedef Matrix<int, 1, 2> RowVector2i;\n\\endcode\n\n\\section TutorialMatrixDynamic The special value Dynamic\n\nOf course, Eigen is not limited to matrices whose dimensions are known at compile time.\nThe \\c RowsAtCompileTime and \\c ColsAtCompileTime template parameters can take the special\nvalue \\c Dynamic which indicates that the size is unknown at compile time, so must\nbe handled as a run-time variable. In Eigen terminology, such a size is referred to as a\n\\em dynamic \\em size; while a size that is known at compile time is called a\n\\em fixed \\em size. For example, the convenience typedef \\c MatrixXd, meaning\na matrix of doubles with dynamic size, is defined as follows:\n\\code\ntypedef Matrix<double, Dynamic, Dynamic> MatrixXd;\n\\endcode\nAnd similarly, we define a self-explanatory typedef \\c VectorXi as follows:\n\\code\ntypedef Matrix<int, Dynamic, 1> VectorXi;\n\\endcode\nYou can perfectly have e.g. a fixed number of rows with a dynamic number of columns, as in:\n\\code\nMatrix<float, 3, Dynamic>\n\\endcode\n\n\\section TutorialMatrixConstructors Constructors\n\nA default constructor is always available, never performs any dynamic memory allocation, and never initializes the matrix coefficients. You can do:\n\\code\nMatrix3f a;\nMatrixXf b;\n\\endcode\nHere,\n\\li \\c a is a 3-by-3 matrix, with a plain float[9] array of uninitialized coefficients,\n\\li \\c b is a dynamic-size matrix whose size is currently 0-by-0, and whose array of\ncoefficients hasn't yet been allocated at all.\n\nConstructors taking sizes are also available. For matrices, the number of rows is always passed first.\nFor vectors, just pass the vector size. They allocate the array of coefficients\nwith the given size, but don't initialize the coefficients themselves:\n\\code\nMatrixXf a(10,15);\nVectorXf b(30);\n\\endcode\nHere,\n\\li \\c a is a 10x15 dynamic-size matrix, with allocated but currently uninitialized coefficients.\n\\li \\c b is a dynamic-size vector of size 30, with allocated but currently uninitialized coefficients.\n\nIn order to offer a uniform API across fixed-size and dynamic-size matrices, it is legal to use these\nconstructors on fixed-size matrices, even if passing the sizes is useless in this case. So this is legal:\n\\code\nMatrix3f a(3,3);\n\\endcode\nand is a no-operation.\n\nMatrices and vectors can also be initialized from lists of coefficients.\nPrior to C++11, this feature is limited to small fixed-size column or vectors up to size 4:\n\\code\nVector2d a(5.0, 6.0);\nVector3d b(5.0, 6.0, 7.0);\nVector4d c(5.0, 6.0, 7.0, 8.0);\n\\endcode\n\nIf C++11 is enabled, fixed-size column or row vectors of arbitrary size can be initialized by passing an arbitrary number of coefficients:\n\\code\nVector2i a(1, 2);                      // A column vector containing the elements {1, 2}\nMatrix<int, 5, 1> b {1, 2, 3, 4, 5};   // A row-vector containing the elements {1, 2, 3, 4, 5}\nMatrix<int, 1, 5> c = {1, 2, 3, 4, 5}; // A column vector containing the elements {1, 2, 3, 4, 5}\n\\endcode\n\nIn the general case of matrices and vectors with either fixed or runtime sizes,\ncoefficients have to be grouped by rows and passed as an initializer list of initializer list (\\link Matrix::Matrix(const std::initializer_list<std::initializer_list<Scalar>>&) details \\endlink):\n\\code\nMatrixXi a {      // construct a 2x2 matrix\n      {1, 2},     // first row\n      {3, 4}      // second row\n};\nMatrix<double, 2, 3> b {\n      {2, 3, 4},\n      {5, 6, 7},\n};\n\\endcode\n\nFor column or row vectors, implicit transposition is allowed.\nThis means that a column vector can be initialized from a single row:\n\\code\nVectorXd a {{1.5, 2.5, 3.5}};             // A column-vector with 3 coefficients\nRowVectorXd b {{1.0, 2.0, 3.0, 4.0}};     // A row-vector with 4 coefficients\n\\endcode\n\n\\section TutorialMatrixCoeffAccessors Coefficient accessors\n\nThe primary coefficient accessors and mutators in Eigen are the overloaded parenthesis operators.\nFor matrices, the row index is always passed first. For vectors, just pass one index.\nThe numbering starts at 0. This example is self-explanatory:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_matrix_coefficient_accessors.cpp\n</td>\n<td>\n\\verbinclude tut_matrix_coefficient_accessors.out\n</td></tr></table>\n\nNote that the syntax <tt> m(index) </tt>\nis not restricted to vectors, it is also available for general matrices, meaning index-based access\nin the array of coefficients. This however depends on the matrix's storage order. All Eigen matrices default to\ncolumn-major storage order, but this can be changed to row-major, see \\ref TopicStorageOrders \"Storage orders\".\n\nThe operator[] is also overloaded for index-based access in vectors, but keep in mind that C++ doesn't allow operator[] to\ntake more than one argument. We restrict operator[] to vectors, because an awkwardness in the C++ language\nwould make matrix[i,j] compile to the same thing as matrix[j] !\n\n\\section TutorialMatrixCommaInitializer Comma-initialization\n\n%Matrix and vector coefficients can be conveniently set using the so-called \\em comma-initializer syntax.\nFor now, it is enough to know this example:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n<td>\\include Tutorial_commainit_01.cpp </td>\n<td>\\verbinclude Tutorial_commainit_01.out </td>\n</tr></table>\n\n\nThe right-hand side can also contain matrix expressions as discussed in \\ref TutorialAdvancedInitialization \"this page\".\n\n\\section TutorialMatrixSizesResizing Resizing\n\nThe current size of a matrix can be retrieved by \\link EigenBase::rows() rows()\\endlink, \\link EigenBase::cols() cols() \\endlink and \\link EigenBase::size() size()\\endlink. These methods return the number of rows, the number of columns and the number of coefficients, respectively. Resizing a dynamic-size matrix is done by the \\link PlainObjectBase::resize(Index,Index) resize() \\endlink method.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n<td>\\include tut_matrix_resize.cpp </td>\n<td>\\verbinclude tut_matrix_resize.out </td>\n</tr></table>\n\nThe resize() method is a no-operation if the actual matrix size doesn't change; otherwise it is destructive: the values of the coefficients may change.\nIf you want a conservative variant of resize() which does not change the coefficients, use \\link PlainObjectBase::conservativeResize() conservativeResize()\\endlink, see \\ref TopicResizing \"this page\" for more details.\n\nAll these methods are still available on fixed-size matrices, for the sake of API uniformity. Of course, you can't actually\nresize a fixed-size matrix. Trying to change a fixed size to an actually different value will trigger an assertion failure;\nbut the following code is legal:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n<td>\\include tut_matrix_resize_fixed_size.cpp </td>\n<td>\\verbinclude tut_matrix_resize_fixed_size.out </td>\n</tr></table>\n\n\n\\section TutorialMatrixAssignment Assignment and resizing\n\nAssignment is the action of copying a matrix into another, using \\c operator=. Eigen resizes the matrix on the left-hand side automatically so that it matches the size of the matrix on the right-hand size. For example:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr>\n<td>\\include tut_matrix_assignment_resizing.cpp </td>\n<td>\\verbinclude tut_matrix_assignment_resizing.out </td>\n</tr></table>\n\nOf course, if the left-hand side is of fixed size, resizing it is not allowed.\n\nIf you do not want this automatic resizing to happen (for example for debugging purposes), you can disable it, see\n\\ref TopicResizing \"this page\".\n\n\n\\section TutorialMatrixFixedVsDynamic Fixed vs. Dynamic size\n\nWhen should one use fixed sizes (e.g. \\c Matrix4f), and when should one prefer dynamic sizes (e.g. \\c MatrixXf)?\nThe simple answer is: use fixed\nsizes for very small sizes where you can, and use dynamic sizes for larger sizes or where you have to. For small sizes,\nespecially for sizes smaller than (roughly) 16, using fixed sizes is hugely beneficial\nto performance, as it allows Eigen to avoid dynamic memory allocation and to unroll\nloops. Internally, a fixed-size Eigen matrix is just a plain array, i.e. doing\n\\code Matrix4f mymatrix; \\endcode\nreally amounts to just doing\n\\code float mymatrix[16]; \\endcode\nso this really has zero runtime cost. By contrast, the array of a dynamic-size matrix\nis always allocated on the heap, so doing\n\\code MatrixXf mymatrix(rows,columns); \\endcode\namounts to doing\n\\code float *mymatrix = new float[rows*columns]; \\endcode\nand in addition to that, the MatrixXf object stores its number of rows and columns as\nmember variables.\n\nThe limitation of using fixed sizes, of course, is that this is only possible\nwhen you know the sizes at compile time. Also, for large enough sizes, say for sizes\ngreater than (roughly) 32, the performance benefit of using fixed sizes becomes negligible.\nWorse, trying to create a very large matrix using fixed sizes inside a function could result in a\nstack overflow, since Eigen will try to allocate the array automatically as a local variable, and\nthis is normally done on the stack.\nFinally, depending on circumstances, Eigen can also be more aggressive trying to vectorize\n(use SIMD instructions) when dynamic sizes are used, see \\ref TopicVectorization \"Vectorization\".\n\n\\section TutorialMatrixOptTemplParams Optional template parameters\n\nWe mentioned at the beginning of this page that the Matrix class takes six template parameters,\nbut so far we only discussed the first three. The remaining three parameters are optional. Here is\nthe complete list of template parameters:\n\\code\nMatrix<typename Scalar,\n       int RowsAtCompileTime,\n       int ColsAtCompileTime,\n       int Options = 0,\n       int MaxRowsAtCompileTime = RowsAtCompileTime,\n       int MaxColsAtCompileTime = ColsAtCompileTime>\n\\endcode\n\\li \\c Options is a bit field. Here, we discuss only one bit: \\c RowMajor. It specifies that the matrices\n      of this type use row-major storage order; by default, the storage order is column-major. See the page on\n      \\ref TopicStorageOrders \"storage orders\". For example, this type means row-major 3x3 matrices:\n      \\code\n      Matrix<float, 3, 3, RowMajor>\n      \\endcode\n\\li \\c MaxRowsAtCompileTime and \\c MaxColsAtCompileTime are useful when you want to specify that, even though\n      the exact sizes of your matrices are not known at compile time, a fixed upper bound is known at\n      compile time. The biggest reason why you might want to do that is to avoid dynamic memory allocation.\n      For example the following matrix type uses a plain array of 12 floats, without dynamic memory allocation:\n      \\code\n      Matrix<float, Dynamic, Dynamic, 0, 3, 4>\n      \\endcode\n\n\\section TutorialMatrixTypedefs Convenience typedefs\n\nEigen defines the following Matrix typedefs:\n\\li MatrixNt for Matrix<type, N, N>. For example, MatrixXi for Matrix<int, Dynamic, Dynamic>.\n\\li VectorNt for Matrix<type, N, 1>. For example, Vector2f for Matrix<float, 2, 1>.\n\\li RowVectorNt for Matrix<type, 1, N>. For example, RowVector3d for Matrix<double, 1, 3>.\n\nWhere:\n\\li N can be any one of \\c 2, \\c 3, \\c 4, or \\c X (meaning \\c Dynamic).\n\\li t can be any one of \\c i (meaning int), \\c f (meaning float), \\c d (meaning double),\n      \\c cf (meaning complex<float>), or \\c cd (meaning complex<double>). The fact that typedefs are only\n    defined for these five types doesn't mean that they are the only supported scalar types. For example,\n    all standard integer types are supported, see \\ref TopicScalarTypes \"Scalar types\".\n\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TutorialReductionsVisitorsBroadcasting.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialReductionsVisitorsBroadcasting Reductions, visitors and broadcasting\n\nThis page explains Eigen's reductions, visitors and broadcasting and how they are used with\n\\link MatrixBase matrices \\endlink and \\link ArrayBase arrays \\endlink.\n\n\\eigenAutoToc\n\n\\section TutorialReductionsVisitorsBroadcastingReductions Reductions\nIn Eigen, a reduction is a function taking a matrix or array, and returning a single\nscalar value. One of the most used reductions is \\link DenseBase::sum() .sum() \\endlink,\nreturning the sum of all the coefficients inside a given matrix or array.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include tut_arithmetic_redux_basic.cpp\n</td>\n<td>\n\\verbinclude tut_arithmetic_redux_basic.out\n</td></tr></table>\n\nThe \\em trace of a matrix, as returned by the function \\c trace(), is the sum of the diagonal coefficients and can equivalently be computed <tt>a.diagonal().sum()</tt>.\n\n\n\\subsection TutorialReductionsVisitorsBroadcastingReductionsNorm Norm computations\n\nThe (Euclidean a.k.a. \\f$\\ell^2\\f$) squared norm of a vector can be obtained \\link MatrixBase::squaredNorm() squaredNorm() \\endlink. It is equal to the dot product of the vector by itself, and equivalently to the sum of squared absolute values of its coefficients.\n\nEigen also provides the \\link MatrixBase::norm() norm() \\endlink method, which returns the square root of \\link MatrixBase::squaredNorm() squaredNorm() \\endlink.\n\nThese operations can also operate on matrices; in that case, a n-by-p matrix is seen as a vector of size (n*p), so for example the \\link MatrixBase::norm() norm() \\endlink method returns the \"Frobenius\" or \"Hilbert-Schmidt\" norm. We refrain from speaking of the \\f$\\ell^2\\f$ norm of a matrix because that can mean different things.\n\nIf you want other coefficient-wise \\f$\\ell^p\\f$ norms, use the \\link MatrixBase::lpNorm lpNorm<p>() \\endlink method. The template parameter \\a p can take the special value \\a Infinity if you want the \\f$\\ell^\\infty\\f$ norm, which is the maximum of the absolute values of the coefficients.\n\nThe following example demonstrates these methods.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ReductionsVisitorsBroadcasting_reductions_norm.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ReductionsVisitorsBroadcasting_reductions_norm.out\n</td></tr></table>\n\n\\b Operator \\b norm: The 1-norm and \\f$\\infty\\f$-norm <a href=\"https://en.wikipedia.org/wiki/Operator_norm\">matrix operator norms</a> can easily be computed as follows:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ReductionsVisitorsBroadcasting_reductions_operatornorm.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ReductionsVisitorsBroadcasting_reductions_operatornorm.out\n</td></tr></table>\nSee below for more explanations on the syntax of these expressions.\n\n\\subsection TutorialReductionsVisitorsBroadcastingReductionsBool Boolean reductions\n\nThe following reductions operate on boolean values:\n  - \\link DenseBase::all() all() \\endlink returns \\b true if all of the coefficients in a given Matrix or Array evaluate to \\b true .\n  - \\link DenseBase::any() any() \\endlink returns \\b true if at least one of the coefficients in a given Matrix or Array evaluates to \\b true .\n  - \\link DenseBase::count() count() \\endlink returns the number of coefficients in a given Matrix or Array that evaluate to  \\b true.\n\nThese are typically used in conjunction with the coefficient-wise comparison and equality operators provided by Array. For instance, <tt>array > 0</tt> is an %Array of the same size as \\c array , with \\b true at those positions where the corresponding coefficient of \\c array is positive. Thus, <tt>(array > 0).all()</tt> tests whether all coefficients of \\c array are positive. This can be seen in the following example:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ReductionsVisitorsBroadcasting_reductions_bool.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ReductionsVisitorsBroadcasting_reductions_bool.out\n</td></tr></table>\n\n\\subsection TutorialReductionsVisitorsBroadcastingReductionsUserdefined User defined reductions\n\nTODO\n\nIn the meantime you can have a look at the DenseBase::redux() function.\n\n\\section TutorialReductionsVisitorsBroadcastingVisitors Visitors\nVisitors are useful when one wants to obtain the location of a coefficient inside \na Matrix or Array. The simplest examples are \n\\link MatrixBase::maxCoeff() maxCoeff(&x,&y) \\endlink and \n\\link MatrixBase::minCoeff() minCoeff(&x,&y)\\endlink, which can be used to find\nthe location of the greatest or smallest coefficient in a Matrix or \nArray.\n\nThe arguments passed to a visitor are pointers to the variables where the\nrow and column position are to be stored. These variables should be of type\n\\link Eigen::Index Index \\endlink, as shown below:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ReductionsVisitorsBroadcasting_visitors.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ReductionsVisitorsBroadcasting_visitors.out\n</td></tr></table>\n\nBoth functions also return the value of the minimum or maximum coefficient.\n\n\\section TutorialReductionsVisitorsBroadcastingPartialReductions Partial reductions\nPartial reductions are reductions that can operate column- or row-wise on a Matrix or \nArray, applying the reduction operation on each column or row and \nreturning a column or row vector with the corresponding values. Partial reductions are applied \nwith \\link DenseBase::colwise() colwise() \\endlink or \\link DenseBase::rowwise() rowwise() \\endlink.\n\nA simple example is obtaining the maximum of the elements \nin each column in a given matrix, storing the result in a row vector:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ReductionsVisitorsBroadcasting_colwise.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ReductionsVisitorsBroadcasting_colwise.out\n</td></tr></table>\n\nThe same operation can be performed row-wise:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ReductionsVisitorsBroadcasting_rowwise.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ReductionsVisitorsBroadcasting_rowwise.out\n</td></tr></table>\n\n<b>Note that column-wise operations return a row vector, while row-wise operations return a column vector.</b>\n\n\\subsection TutorialReductionsVisitorsBroadcastingPartialReductionsCombined Combining partial reductions with other operations\nIt is also possible to use the result of a partial reduction to do further processing.\nHere is another example that finds the column whose sum of elements is the maximum\n within a matrix. With column-wise partial reductions this can be coded as:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ReductionsVisitorsBroadcasting_maxnorm.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ReductionsVisitorsBroadcasting_maxnorm.out\n</td></tr></table>\n\nThe previous example applies the \\link DenseBase::sum() sum() \\endlink reduction on each column\nthough the \\link DenseBase::colwise() colwise() \\endlink visitor, obtaining a new matrix whose\nsize is 1x4.\n\nTherefore, if\n\\f[\n\\mbox{m} = \\begin{bmatrix} 1 & 2 & 6 & 9 \\\\\n                    3 & 1 & 7 & 2 \\end{bmatrix}\n\\f]\n\nthen\n\n\\f[\n\\mbox{m.colwise().sum()} = \\begin{bmatrix} 4 & 3 & 13 & 11 \\end{bmatrix}\n\\f]\n\nThe \\link DenseBase::maxCoeff() maxCoeff() \\endlink reduction is finally applied \nto obtain the column index where the maximum sum is found, \nwhich is the column index 2 (third column) in this case.\n\n\n\\section TutorialReductionsVisitorsBroadcastingBroadcasting Broadcasting\nThe concept behind broadcasting is similar to partial reductions, with the difference that broadcasting \nconstructs an expression where a vector (column or row) is interpreted as a matrix by replicating it in \none direction.\n\nA simple example is to add a certain column vector to each column in a matrix. \nThis can be accomplished with:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple.out\n</td></tr></table>\n\nWe can interpret the instruction <tt>mat.colwise() += v</tt> in two equivalent ways. It adds the vector \\c v\nto every column of the matrix. Alternatively, it can be interpreted as repeating the vector \\c v four times to\nform a four-by-two matrix which is then added to \\c mat:\n\\f[\n\\begin{bmatrix} 1 & 2 & 6 & 9 \\\\ 3 & 1 & 7 & 2 \\end{bmatrix}\n+ \\begin{bmatrix} 0 & 0 & 0 & 0 \\\\ 1 & 1 & 1 & 1 \\end{bmatrix}\n= \\begin{bmatrix} 1 & 2 & 6 & 9 \\\\ 4 & 2 & 8 & 3 \\end{bmatrix}.\n\\f]\nThe operators <tt>-=</tt>, <tt>+</tt> and <tt>-</tt> can also be used column-wise and row-wise. On arrays, we \ncan also use the operators <tt>*=</tt>, <tt>/=</tt>, <tt>*</tt> and <tt>/</tt> to perform coefficient-wise \nmultiplication and division column-wise or row-wise. These operators are not available on matrices because it\nis not clear what they would do. If you want multiply column 0 of a matrix \\c mat with \\c v(0), column 1 with \n\\c v(1), and so on, then use <tt>mat = mat * v.asDiagonal()</tt>.\n\nIt is important to point out that the vector to be added column-wise or row-wise must be of type Vector,\nand cannot be a Matrix. If this is not met then you will get compile-time error. This also means that\nbroadcasting operations can only be applied with an object of type Vector, when operating with Matrix.\nThe same applies for the Array class, where the equivalent for VectorXf is ArrayXf. As always, you should\nnot mix arrays and matrices in the same expression.\n\nTo perform the same operation row-wise we can do:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple_rowwise.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple_rowwise.out\n</td></tr></table>\n\n\\subsection TutorialReductionsVisitorsBroadcastingBroadcastingCombined Combining broadcasting with other operations\nBroadcasting can also be combined with other operations, such as Matrix or Array operations, \nreductions and partial reductions.\n\nNow that broadcasting, reductions and partial reductions have been introduced, we can dive into a more advanced example that finds\nthe nearest neighbour of a vector <tt>v</tt> within the columns of matrix <tt>m</tt>. The Euclidean distance will be used in this example,\ncomputing the squared Euclidean distance with the partial reduction named \\link MatrixBase::squaredNorm() squaredNorm() \\endlink:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_ReductionsVisitorsBroadcasting_broadcast_1nn.cpp\n</td>\n<td>\n\\verbinclude Tutorial_ReductionsVisitorsBroadcasting_broadcast_1nn.out\n</td></tr></table>\n\nThe line that does the job is \n\\code\n  (m.colwise() - v).colwise().squaredNorm().minCoeff(&index);\n\\endcode\n\nWe will go step by step to understand what is happening:\n\n  - <tt>m.colwise() - v</tt> is a broadcasting operation, subtracting <tt>v</tt> from each column in <tt>m</tt>. The result of this operation\nis a new matrix whose size is the same as matrix <tt>m</tt>: \\f[\n  \\mbox{m.colwise() - v} = \n  \\begin{bmatrix}\n    -1 & 21 & 4 & 7 \\\\\n     0 & 8  & 4 & -1\n  \\end{bmatrix}\n\\f]\n\n  - <tt>(m.colwise() - v).colwise().squaredNorm()</tt> is a partial reduction, computing the squared norm column-wise. The result of\nthis operation is a row vector where each coefficient is the squared Euclidean distance between each column in <tt>m</tt> and <tt>v</tt>: \\f[\n  \\mbox{(m.colwise() - v).colwise().squaredNorm()} =\n  \\begin{bmatrix}\n     1 & 505 & 32 & 50\n  \\end{bmatrix}\n\\f]\n\n  - Finally, <tt>minCoeff(&index)</tt> is used to obtain the index of the column in <tt>m</tt> that is closest to <tt>v</tt> in terms of Euclidean\ndistance.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TutorialReshape.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialReshape Reshape\n\nSince the version 3.4, %Eigen exposes convenient methods to reshape a matrix to another matrix of different sizes or vector.\nAll cases are handled via the DenseBase::reshaped(NRowsType,NColsType) and DenseBase::reshaped() functions.\nThose functions do not perform in-place reshaping, but instead return a <i> view </i> on the input expression.\n\n\\eigenAutoToc\n\n\\section TutorialReshapeMat2Mat Reshaped 2D views\n\nThe more general reshaping transformation is handled via: `reshaped(nrows,ncols)`.\nHere is an example reshaping a 4x4 matrix to a 2x8 one:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include MatrixBase_reshaped_int_int.cpp\n</td>\n<td>\n\\verbinclude MatrixBase_reshaped_int_int.out\n</td></tr></table>\n\nBy default, the input coefficients are always interpreted in column-major order regardless of the storage order of the input expression.\nFor more control on ordering, compile-time sizes, and automatic size deduction, please see de documentation of DenseBase::reshaped(NRowsType,NColsType) that contains all the details with many examples.\n\n\n\\section TutorialReshapeMat2Vec 1D linear views\n\nA very common usage of reshaping is to create a 1D linear view over a given 2D matrix or expression.\nIn this case, sizes can be deduced and thus omitted as in the following example:\n\n<table class=\"example\">\n<tr><th>Example:</th></tr>\n<tr><td>\n\\include MatrixBase_reshaped_to_vector.cpp\n</td></tr>\n<tr><th>Output:</th></tr>\n<tr><td>\n\\verbinclude MatrixBase_reshaped_to_vector.out\n</td></tr></table>\n\nThis shortcut always returns a column vector and by default input coefficients are always interpreted in column-major order.\nAgain, see the documentation of DenseBase::reshaped() for more control on the ordering.\n\n\\section TutorialReshapeInPlace\n\nThe above examples create reshaped views, but what about reshaping inplace a given matrix?\nOf course this task in only conceivable for matrix and arrays having runtime dimensions.\nIn many cases, this can be accomplished via PlainObjectBase::resize(Index,Index):\n\n<table class=\"example\">\n<tr><th>Example:</th></tr>\n<tr><td>\n\\include Tutorial_reshaped_vs_resize_1.cpp\n</td></tr>\n<tr><th>Output:</th></tr>\n<tr><td>\n\\verbinclude Tutorial_reshaped_vs_resize_1.out\n</td></tr></table>\n\nHowever beware that unlike \\c reshaped, the result of \\c resize depends on the input storage order.\nIt thus behaves similarly to `reshaped<AutoOrder>`:\n\n<table class=\"example\">\n<tr><th>Example:</th></tr>\n<tr><td>\n\\include Tutorial_reshaped_vs_resize_2.cpp\n</td></tr>\n<tr><th>Output:</th></tr>\n<tr><td>\n\\verbinclude Tutorial_reshaped_vs_resize_2.out\n</td></tr></table>\n\nFinally, assigning a reshaped matrix to itself is currently not supported and will result to undefined-behavior because of \\link TopicAliasing aliasing \\endlink.\nThe following is forbidden: \\code A = A.reshaped(2,8); \\endcode\nThis is OK: \\code A = A.reshaped(2,8).eval(); \\endcode\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TutorialSTL.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialSTL STL iterators and algorithms\n\nSince the version 3.4, %Eigen's dense matrices and arrays provide STL compatible iterators.\nAs demonstrated below, this makes them naturally compatible with range-for-loops and STL's algorithms.\n\n\\eigenAutoToc\n\n\\section TutorialSTLVectors Iterating over 1D arrays and vectors \n\nAny dense 1D expressions exposes the pair of `begin()/end()` methods to iterate over them.\n\nThis directly enables c++11 range for loops:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_range_for_loop_1d_cxx11.cpp\n</td>\n<td>\n\\verbinclude Tutorial_range_for_loop_1d_cxx11.out\n</td></tr></table>\n\nOne dimensional expressions can also easily be passed to STL algorithms:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_std_sort.cpp\n</td>\n<td>\n\\verbinclude Tutorial_std_sort.out\n</td></tr></table>\n\nSimilar to `std::vector`, 1D expressions also exposes the pair of `cbegin()/cend()` methods to conveniently get const iterators on non-const object.\n\n\\section TutorialSTLMatrices Iterating over coefficients of 2D arrays and matrices\n\nSTL iterators are intrinsically designed to iterate over 1D structures.\nThis is why `begin()/end()` methods are disabled for 2D expressions.\nIterating over all coefficients of a 2D expressions is still easily accomplished by creating a 1D linear view through `reshaped()`:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_range_for_loop_2d_cxx11.cpp\n</td>\n<td>\n\\verbinclude Tutorial_range_for_loop_2d_cxx11.out\n</td></tr></table>\n\n\\section TutorialSTLRowsColumns Iterating over rows or columns of 2D arrays and matrices\n\nIt is also possible to get iterators over rows or columns of 2D expressions.\nThose are available through the `rowwise()` and `colwise()` proxies.\nHere is an example sorting each row of a matrix:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Tutorial_std_sort_rows_cxx11.cpp\n</td>\n<td>\n\\verbinclude Tutorial_std_sort_rows_cxx11.out\n</td></tr></table>\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TutorialSlicingIndexing.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialSlicingIndexing Slicing and Indexing\n\nThis page presents the numerous possibilities offered by `operator()` to index sub-set of rows and columns.\nThis API has been introduced in %Eigen 3.4.\nIt supports all the feature proposed by the \\link TutorialBlockOperations block API \\endlink, and much more.\nIn particular, it supports \\b slicing that consists in taking a set of rows, columns, or elements, uniformly spaced within a matrix or indexed from an array of indices.\n\n\\eigenAutoToc\n\n\\section TutorialSlicingOverview Overview\n\nAll the aforementioned operations are handled through the generic DenseBase::operator()(const RowIndices&, const ColIndices&) method.\nEach argument can be:\n  - An integer indexing a single row or column, including symbolic indices.\n  - The symbol Eigen::all representing the whole set of respective rows or columns in increasing order.\n  - An ArithmeticSequence as constructed by the Eigen::seq, Eigen::seqN, or Eigen::lastN functions.\n  - Any 1D vector/array of integers including %Eigen's vector/array, expressions, std::vector, std::array, as well as plain C arrays: `int[N]`.\n\nMore generally, it can accepts any object exposing the following two member functions:\n  \\code\n  <integral type> operator[](<integral type>) const;\n  <integral type> size() const;\n  \\endcode\nwhere `<integral type>` stands for any integer type compatible with Eigen::Index (i.e. `std::ptrdiff_t`).\n\n\\section TutorialSlicingBasic Basic slicing\n\nTaking a set of rows, columns, or elements, uniformly spaced within a matrix or vector is achieved through the Eigen::seq or Eigen::seqN functions where \"seq\" stands for arithmetic sequence. Their signatures are summarized below:\n\n<table class=\"manual\">\n<tr>\n  <th>function</th>\n  <th>description</th>\n  <th>example</th>\n</tr>\n<tr>\n  <td>\\code seq(firstIdx,lastIdx) \\endcode</td>\n  <td>represents the sequence of integers ranging from \\c firstIdx to \\c lastIdx</td>\n  <td>\\code seq(2,5) <=> {2,3,4,5} \\endcode</td>\n</tr>\n<tr>\n  <td>\\code seq(firstIdx,lastIdx,incr) \\endcode</td>\n  <td>same but using the increment \\c incr to advance from one index to the next</td>\n  <td>\\code seq(2,8,2) <=> {2,4,6,8} \\endcode</td>\n</tr>\n<tr>\n  <td>\\code seqN(firstIdx,size) \\endcode</td>\n  <td>represents the sequence of \\c size integers starting from \\c firstIdx</td>\n  <td>\\code seqN(2,5) <=> {2,3,4,5,6} \\endcode</td>\n</tr>\n<tr>\n  <td>\\code seqN(firstIdx,size,incr) \\endcode</td>\n  <td>same but using the increment \\c incr to advance from one index to the next</td>\n  <td>\\code seqN(2,3,3) <=> {2,5,8} \\endcode</td>\n</tr>\n</table>\n\nThe \\c firstIdx and \\c lastIdx parameters can also be defined with the help of the Eigen::last symbol representing the index of the last row, column or element of the underlying matrix/vector once the arithmetic sequence is passed to it through operator().\nHere are some examples for a 2D array/matrix \\c A and a 1D array/vector \\c v.\n<table class=\"manual\">\n<tr>\n  <th>Intent</th>\n  <th>Code</th>\n  <th>Block-API equivalence</th>\n</tr>\n<tr>\n  <td>Bottom-left corner starting at row \\c i with \\c n columns</td>\n  <td>\\code A(seq(i,last), seqN(0,n)) \\endcode</td>\n  <td>\\code A.bottomLeftCorner(A.rows()-i,n) \\endcode</td>\n</tr>\n<tr>\n  <td>%Block starting at \\c i,j having \\c m rows, and \\c n columns</td>\n  <td>\\code A(seqN(i,m), seqN(i,n) \\endcode</td>\n  <td>\\code A.block(i,j,m,n) \\endcode</td>\n</tr>\n<tr>\n  <td>%Block starting at \\c i0,j0 and ending at \\c i1,j1</td>\n  <td>\\code A(seq(i0,i1), seq(j0,j1) \\endcode</td>\n  <td>\\code A.block(i0,j0,i1-i0+1,j1-j0+1) \\endcode</td>\n</tr>\n<tr>\n  <td>Even columns of A</td>\n  <td>\\code A(all, seq(0,last,2)) \\endcode</td>\n  <td></td>\n</tr>\n<tr>\n  <td>First \\c n odd rows A</td>\n  <td>\\code A(seqN(1,n,2), all) \\endcode</td>\n  <td></td>\n</tr>\n<tr>\n  <td>The last past one column</td>\n  <td>\\code A(all, last-1) \\endcode</td>\n  <td>\\code A.col(A.cols()-2) \\endcode</td>\n</tr>\n<tr>\n  <td>The middle row</td>\n  <td>\\code A(last/2,all) \\endcode</td>\n  <td>\\code A.row((A.rows()-1)/2) \\endcode</td>\n</tr>\n<tr>\n  <td>Last elements of v starting at i</td>\n  <td>\\code v(seq(i,last)) \\endcode</td>\n  <td>\\code v.tail(v.size()-i) \\endcode</td>\n</tr>\n<tr>\n  <td>Last \\c n elements of v</td>\n  <td>\\code v(seq(last+1-n,last)) \\endcode</td>\n  <td>\\code v.tail(n) \\endcode</td>\n</tr>\n</table>\n\nAs seen in the last exemple, referencing the <i> last n </i> elements (or rows/columns) is a bit cumbersome to write.\nThis becomes even more tricky and error prone with a non-default increment.\nHere comes \\link Eigen::lastN(SizeType) Eigen::lastN(size) \\endlink, and \\link Eigen::lastN(SizeType,IncrType) Eigen::lastN(size,incr) \\endlink:\n\n<table class=\"manual\">\n<tr>\n  <th>Intent</th>\n  <th>Code</th>\n  <th>Block-API equivalence</th>\n</tr>\n<tr>\n  <td>Last \\c n elements of v</td>\n  <td>\\code v(lastN(n)) \\endcode</td>\n  <td>\\code v.tail(n) \\endcode</td>\n</tr>\n<tr>\n  <td>Bottom-right corner of A of size \\c m times \\c n</td>\n  <td>\\code v(lastN(m), lastN(n)) \\endcode</td>\n  <td>\\code A.bottomRightCorner(m,n) \\endcode</td>\n</tr>\n<tr>\n  <td>Bottom-right corner of A of size \\c m times \\c n</td>\n  <td>\\code v(lastN(m), lastN(n)) \\endcode</td>\n  <td>\\code A.bottomRightCorner(m,n) \\endcode</td>\n</tr>\n<tr>\n  <td>Last \\c n columns taking 1 column over 3</td>\n  <td>\\code A(all, lastN(n,3)) \\endcode</td>\n  <td></td>\n</tr>\n</table>\n\n\\section TutorialSlicingFixed Compile time size and increment\n\nIn terms of performance, %Eigen and the compiler can take advantage of compile-time size and increment.\nTo this end, you can enforce compile-time parameters using Eigen::fix<val>.\nSuch compile-time value can be combined with the Eigen::last symbol:\n\\code v(seq(last-fix<7>, last-fix<2>))\n\\endcode\nIn this example %Eigen knowns at compile-time that the returned expression has 6 elements.\nIt is equivalent to:\n\\code v(seqN(last-7, fix<6>))\n\\endcode\n\nWe can revisit the <i>even columns of A</i> example as follows:\n\\code A(all, seq(0,last,fix<2>))\n\\endcode\n\n\n\\section TutorialSlicingReverse Reverse order\n\nRow/column indices can also be enumerated in decreasing order using a negative increment.\nFor instance, one over two columns of A from the column 20 to 10:\n\\code A(all, seq(20, 10, fix<-2>))\n\\endcode\nThe last \\c n rows starting from the last one:\n\\code A(seqN(last, n, fix<-1>), all)\n\\endcode\nYou can also use the ArithmeticSequence::reverse() method to reverse its order.\nThe previous example can thus also be written as:\n\\code A(lastN(n).reverse(), all)\n\\endcode\n\n\n\\section TutorialSlicingArray Array of indices\n\nThe generic `operator()` can also takes as input an arbitrary list of row or column indices stored as either an `ArrayXi`, a `std::vector<int>`, `std::array<int,N>`, etc.\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Slicing_stdvector_cxx11.cpp\n</td>\n<td>\n\\verbinclude Slicing_stdvector_cxx11.out\n</td></tr></table>\n\nYou can also directly pass a static array:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Slicing_rawarray_cxx11.cpp\n</td>\n<td>\n\\verbinclude Slicing_rawarray_cxx11.out\n</td></tr></table>\n\nor expressions:\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Slicing_arrayexpr.cpp\n</td>\n<td>\n\\verbinclude Slicing_arrayexpr.out\n</td></tr></table>\n\nWhen passing an object with a compile-time size such as `Array4i`, `std::array<int,N>`, or a static array, then the returned expression also exhibit compile-time dimensions.\n\n\\section TutorialSlicingCustomArray Custom index list\n\nMore generally, `operator()` can accept as inputs any object \\c ind of type \\c T compatible with:\n\\code\nIndex s = ind.size(); or Index s = size(ind);\nIndex i;\ni = ind[i];\n\\endcode\n\nThis means you can easily build your own fancy sequence generator and pass it to `operator()`.\nHere is an exemple enlarging a given matrix while padding the additional first rows and columns through repetition:\n\n<table class=\"example\">\n<tr><th>Example:</th><th>Output:</th></tr>\n<tr><td>\n\\include Slicing_custom_padding_cxx11.cpp\n</td>\n<td>\n\\verbinclude Slicing_custom_padding_cxx11.out\n</td></tr></table>\n\n<br>\n\n*/\n\n/*\nTODO add:\nso_repeat_inner.cpp\nso_repeleme.cpp\n*/\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TutorialSparse.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TutorialSparse Sparse matrix manipulations\n\n\\eigenAutoToc\n\nManipulating and solving sparse problems involves various modules which are summarized below:\n\n<table class=\"manual\">\n<tr><th>Module</th><th>Header file</th><th>Contents</th></tr>\n<tr><td>\\link SparseCore_Module SparseCore \\endlink</td><td>\\code#include <Eigen/SparseCore>\\endcode</td><td>SparseMatrix and SparseVector classes, matrix assembly, basic sparse linear algebra (including sparse triangular solvers)</td></tr>\n<tr><td>\\link SparseCholesky_Module SparseCholesky \\endlink</td><td>\\code#include <Eigen/SparseCholesky>\\endcode</td><td>Direct sparse LLT and LDLT Cholesky factorization to solve sparse self-adjoint positive definite problems</td></tr>\n<tr><td>\\link SparseLU_Module SparseLU \\endlink</td><td>\\code #include<Eigen/SparseLU> \\endcode</td>\n<td>%Sparse LU factorization to solve general square sparse systems</td></tr>\n<tr><td>\\link SparseQR_Module SparseQR \\endlink</td><td>\\code #include<Eigen/SparseQR>\\endcode </td><td>%Sparse QR factorization for solving sparse linear least-squares problems</td></tr>\n<tr><td>\\link IterativeLinearSolvers_Module IterativeLinearSolvers \\endlink</td><td>\\code#include <Eigen/IterativeLinearSolvers>\\endcode</td><td>Iterative solvers to solve large general linear square problems (including self-adjoint positive definite problems)</td></tr>\n<tr><td>\\link Sparse_Module Sparse \\endlink</td><td>\\code#include <Eigen/Sparse>\\endcode</td><td>Includes all the above modules</td></tr>\n</table>\n\n\\section TutorialSparseIntro Sparse matrix format\n\nIn many applications (e.g., finite element methods) it is common to deal with very large matrices where only a few coefficients are different from zero.  In such cases, memory consumption can be reduced and performance increased by using a specialized representation storing only the nonzero coefficients. Such a matrix is called a sparse matrix.\n\n\\b The \\b %SparseMatrix \\b class\n\nThe class SparseMatrix is the main sparse matrix representation of Eigen's sparse module; it offers high performance and low memory usage.\nIt implements a more versatile variant of the widely-used Compressed Column (or Row) Storage scheme.\nIt consists of four compact arrays:\n - \\c Values: stores the coefficient values of the non-zeros.\n - \\c InnerIndices: stores the row (resp. column) indices of the non-zeros.\n - \\c OuterStarts: stores for each column (resp. row) the index of the first non-zero in the previous two arrays.\n - \\c InnerNNZs: stores the number of non-zeros of each column (resp. row).\nThe word \\c inner refers to an \\em inner \\em vector that is a column for a column-major matrix, or a row for a row-major matrix.\nThe word \\c outer refers to the other direction.\n\nThis storage scheme is better explained on an example. The following matrix\n<table class=\"manual\">\n<tr><td> 0</td><td>3</td><td> 0</td><td>0</td><td> 0</td></tr>\n<tr><td>22</td><td>0</td><td> 0</td><td>0</td><td>17</td></tr>\n<tr><td> 7</td><td>5</td><td> 0</td><td>1</td><td> 0</td></tr>\n<tr><td> 0</td><td>0</td><td> 0</td><td>0</td><td> 0</td></tr>\n<tr><td> 0</td><td>0</td><td>14</td><td>0</td><td> 8</td></tr>\n</table>\n\nand one of its possible sparse, \\b column \\b major representation:\n<table class=\"manual\">\n<tr><td>Values:</td>        <td>22</td><td>7</td><td>_</td><td>3</td><td>5</td><td>14</td><td>_</td><td>_</td><td>1</td><td>_</td><td>17</td><td>8</td></tr>\n<tr><td>InnerIndices:</td>  <td> 1</td><td>2</td><td>_</td><td>0</td><td>2</td><td> 4</td><td>_</td><td>_</td><td>2</td><td>_</td><td> 1</td><td>4</td></tr>\n</table>\n<table class=\"manual\">\n<tr><td>OuterStarts:</td><td>0</td><td>3</td><td>5</td><td>8</td><td>10</td><td>\\em 12 </td></tr>\n<tr><td>InnerNNZs:</td>    <td>2</td><td>2</td><td>1</td><td>1</td><td> 2</td><td></td></tr>\n</table>\n\nCurrently the elements of a given inner vector are guaranteed to be always sorted by increasing inner indices.\nThe \\c \"_\" indicates available free space to quickly insert new elements.\nAssuming no reallocation is needed, the insertion of a random element is therefore in O(nnz_j) where nnz_j is the number of nonzeros of the respective inner vector.\nOn the other hand, inserting elements with increasing inner indices in a given inner vector is much more efficient since this only requires to increase the respective \\c InnerNNZs entry that is a O(1) operation.\n\nThe case where no empty space is available is a special case, and is referred as the \\em compressed mode.\nIt corresponds to the widely used Compressed Column (or Row) Storage schemes (CCS or CRS).\nAny SparseMatrix can be turned to this form by calling the SparseMatrix::makeCompressed() function.\nIn this case, one can remark that the \\c InnerNNZs array is redundant with \\c OuterStarts because we the equality: \\c InnerNNZs[j] = \\c OuterStarts[j+1]-\\c OuterStarts[j].\nTherefore, in practice a call to SparseMatrix::makeCompressed() frees this buffer.\n\nIt is worth noting that most of our wrappers to external libraries requires compressed matrices as inputs.\n\nThe results of %Eigen's operations always produces \\b compressed sparse matrices.\nOn the other hand, the insertion of a new element into a SparseMatrix converts this later to the \\b uncompressed mode.\n\nHere is the previous matrix represented in compressed mode:\n<table class=\"manual\">\n<tr><td>Values:</td>        <td>22</td><td>7</td><td>3</td><td>5</td><td>14</td><td>1</td><td>17</td><td>8</td></tr>\n<tr><td>InnerIndices:</td>  <td> 1</td><td>2</td><td>0</td><td>2</td><td> 4</td><td>2</td><td> 1</td><td>4</td></tr>\n</table>\n<table class=\"manual\">\n<tr><td>OuterStarts:</td><td>0</td><td>2</td><td>4</td><td>5</td><td>6</td><td>\\em 8 </td></tr>\n</table>\n\nA SparseVector is a special case of a SparseMatrix where only the \\c Values and \\c InnerIndices arrays are stored.\nThere is no notion of compressed/uncompressed mode for a SparseVector.\n\n\n\\section TutorialSparseExample First example\n\nBefore describing each individual class, let's start with the following typical example: solving the Laplace equation \\f$ \\Delta u = 0 \\f$ on a regular 2D grid using a finite difference scheme and Dirichlet boundary conditions.\nSuch problem can be mathematically expressed as a linear problem of the form \\f$ Ax=b \\f$ where \\f$ x \\f$ is the vector of \\c m unknowns (in our case, the values of the pixels), \\f$ b \\f$ is the right hand side vector resulting from the boundary conditions, and \\f$ A \\f$ is an \\f$ m \\times m \\f$ matrix containing only a few non-zero elements resulting from the discretization of the Laplacian operator.\n\n<table class=\"manual\">\n<tr><td>\n\\include Tutorial_sparse_example.cpp\n</td>\n<td>\n\\image html Tutorial_sparse_example.jpeg\n</td></tr></table>\n\nIn this example, we start by defining a column-major sparse matrix type of double \\c SparseMatrix<double>, and a triplet list of the same scalar type \\c  Triplet<double>. A triplet is a simple object representing a non-zero entry as the triplet: \\c row index, \\c column index, \\c value.\n\nIn the main function, we declare a list \\c coefficients of triplets (as a std vector) and the right hand side vector \\f$ b \\f$ which are filled by the \\a buildProblem function.\nThe raw and flat list of non-zero entries is then converted to a true SparseMatrix object \\c A.\nNote that the elements of the list do not have to be sorted, and possible duplicate entries will be summed up.\n\nThe last step consists of effectively solving the assembled problem.\nSince the resulting matrix \\c A is symmetric by construction, we can perform a direct Cholesky factorization via the SimplicialLDLT class which behaves like its LDLT counterpart for dense objects.\n\nThe resulting vector \\c x contains the pixel values as a 1D array which is saved to a jpeg file shown on the right of the code above.\n\nDescribing the \\a buildProblem and \\a save functions is out of the scope of this tutorial. They are given \\ref TutorialSparse_example_details \"here\" for the curious and reproducibility purpose.\n\n\n\n\n\\section TutorialSparseSparseMatrix The SparseMatrix class\n\n\\b %Matrix \\b and \\b vector \\b properties \\n\n\nThe SparseMatrix and SparseVector classes take three template arguments:\n * the scalar type (e.g., double)\n * the storage order (ColMajor or RowMajor, the default is ColMajor)\n * the inner index type (default is \\c int).\n\nAs for dense Matrix objects, constructors takes the size of the object.\nHere are some examples:\n\n\\code\nSparseMatrix<std::complex<float> > mat(1000,2000);         // declares a 1000x2000 column-major compressed sparse matrix of complex<float>\nSparseMatrix<double,RowMajor> mat(1000,2000);              // declares a 1000x2000 row-major compressed sparse matrix of double\nSparseVector<std::complex<float> > vec(1000);              // declares a column sparse vector of complex<float> of size 1000\nSparseVector<double,RowMajor> vec(1000);                   // declares a row sparse vector of double of size 1000\n\\endcode\n\nIn the rest of the tutorial, \\c mat and \\c vec represent any sparse-matrix and sparse-vector objects, respectively.\n\nThe dimensions of a matrix can be queried using the following functions:\n<table class=\"manual\">\n<tr><td>Standard \\n dimensions</td><td>\\code\nmat.rows()\nmat.cols()\\endcode</td>\n<td>\\code\nvec.size() \\endcode</td>\n</tr>\n<tr><td>Sizes along the \\n inner/outer dimensions</td><td>\\code\nmat.innerSize()\nmat.outerSize()\\endcode</td>\n<td></td>\n</tr>\n<tr><td>Number of non \\n zero coefficients</td><td>\\code\nmat.nonZeros() \\endcode</td>\n<td>\\code\nvec.nonZeros() \\endcode</td></tr>\n</table>\n\n\n\\b Iterating \\b over \\b the \\b nonzero \\b coefficients \\n\n\nRandom access to the elements of a sparse object can be done through the \\c coeffRef(i,j) function.\nHowever, this function involves a quite expensive binary search.\nIn most cases, one only wants to iterate over the non-zeros elements. This is achieved by a standard loop over the outer dimension, and then by iterating over the non-zeros of the current inner vector via an InnerIterator. Thus, the non-zero entries have to be visited in the same order than the storage order.\nHere is an example:\n<table class=\"manual\">\n<tr><td>\n\\code\nSparseMatrix<double> mat(rows,cols);\nfor (int k=0; k<mat.outerSize(); ++k)\n  for (SparseMatrix<double>::InnerIterator it(mat,k); it; ++it)\n  {\n    it.value();\n    it.row();   // row index\n    it.col();   // col index (here it is equal to k)\n    it.index(); // inner index, here it is equal to it.row()\n  }\n\\endcode\n</td><td>\n\\code\nSparseVector<double> vec(size);\nfor (SparseVector<double>::InnerIterator it(vec); it; ++it)\n{\n  it.value(); // == vec[ it.index() ]\n  it.index();\n}\n\\endcode\n</td></tr>\n</table>\nFor a writable expression, the referenced value can be modified using the valueRef() function.\nIf the type of the sparse matrix or vector depends on a template parameter, then the \\c typename keyword is\nrequired to indicate that \\c InnerIterator denotes a type; see \\ref TopicTemplateKeyword for details.\n\n\n\\section TutorialSparseFilling Filling a sparse matrix\n\nBecause of the special storage scheme of a SparseMatrix, special care has to be taken when adding new nonzero entries.\nFor instance, the cost of a single purely random insertion into a SparseMatrix is \\c O(nnz), where \\c nnz is the current number of non-zero coefficients.\n\nThe simplest way to create a sparse matrix while guaranteeing good performance is thus to first build a list of so-called \\em triplets, and then convert it to a SparseMatrix.\n\nHere is a typical usage example:\n\\code\ntypedef Eigen::Triplet<double> T;\nstd::vector<T> tripletList;\ntripletList.reserve(estimation_of_entries);\nfor(...)\n{\n  // ...\n  tripletList.push_back(T(i,j,v_ij));\n}\nSparseMatrixType mat(rows,cols);\nmat.setFromTriplets(tripletList.begin(), tripletList.end());\n// mat is ready to go!\n\\endcode\nThe \\c std::vector of triplets might contain the elements in arbitrary order, and might even contain duplicated elements that will be summed up by setFromTriplets().\nSee the SparseMatrix::setFromTriplets() function and class Triplet for more details.\n\n\nIn some cases, however, slightly higher performance, and lower memory consumption can be reached by directly inserting the non-zeros into the destination matrix.\nA typical scenario of this approach is illustrated below:\n\\code\n1: SparseMatrix<double> mat(rows,cols);         // default is column major\n2: mat.reserve(VectorXi::Constant(cols,6));\n3: for each i,j such that v_ij != 0\n4:   mat.insert(i,j) = v_ij;                    // alternative: mat.coeffRef(i,j) += v_ij;\n5: mat.makeCompressed();                        // optional\n\\endcode\n\n- The key ingredient here is the line 2 where we reserve room for 6 non-zeros per column. In many cases, the number of non-zeros per column or row can easily be known in advance. If it varies significantly for each inner vector, then it is possible to specify a reserve size for each inner vector by providing a vector object with an operator[](int j) returning the reserve size of the \\c j-th inner vector (e.g., via a VectorXi or std::vector<int>). If only a rought estimate of the number of nonzeros per inner-vector can be obtained, it is highly recommended to overestimate it rather than the opposite. If this line is omitted, then the first insertion of a new element will reserve room for 2 elements per inner vector.\n- The line 4 performs a sorted insertion. In this example, the ideal case is when the \\c j-th column is not full and contains non-zeros whose inner-indices are smaller than \\c i. In this case, this operation boils down to trivial O(1) operation.\n- When calling insert(i,j) the element \\c i \\c ,j must not already exists, otherwise use the coeffRef(i,j) method that will allow to, e.g., accumulate values. This method first performs a binary search and finally calls insert(i,j) if the element does not already exist. It is more flexible than insert() but also more costly.\n- The line 5 suppresses the remaining empty space and transforms the matrix into a compressed column storage.\n\n\n\n\\section TutorialSparseFeatureSet Supported operators and functions\n\nBecause of their special storage format, sparse matrices cannot offer the same level of flexibility than dense matrices.\nIn Eigen's sparse module we chose to expose only the subset of the dense matrix API which can be efficiently implemented.\nIn the following \\em sm denotes a sparse matrix, \\em sv a sparse vector, \\em dm a dense matrix, and \\em dv a dense vector.\n\n\\subsection TutorialSparse_BasicOps Basic operations\n\n%Sparse expressions support most of the unary and binary coefficient wise operations:\n\\code\nsm1.real()   sm1.imag()   -sm1                    0.5*sm1\nsm1+sm2      sm1-sm2      sm1.cwiseProduct(sm2)\n\\endcode\nHowever, <strong>a strong restriction is that the storage orders must match</strong>. For instance, in the following example:\n\\code\nsm4 = sm1 + sm2 + sm3;\n\\endcode\nsm1, sm2, and sm3 must all be row-major or all column-major.\nOn the other hand, there is no restriction on the target matrix sm4.\nFor instance, this means that for computing \\f$ A^T + A \\f$, the matrix \\f$ A^T \\f$ must be evaluated into a temporary matrix of compatible storage order:\n\\code\nSparseMatrix<double> A, B;\nB = SparseMatrix<double>(A.transpose()) + A;\n\\endcode\n\nBinary coefficient wise operators can also mix sparse and dense expressions:\n\\code\nsm2 = sm1.cwiseProduct(dm1);\ndm2 = sm1 + dm1;\ndm2 = dm1 - sm1;\n\\endcode\nPerformance-wise, the adding/subtracting sparse and dense matrices is better performed in two steps. For instance, instead of doing <tt>dm2 = sm1 + dm1</tt>, better write:\n\\code\ndm2 = dm1;\ndm2 += sm1;\n\\endcode\nThis version has the advantage to fully exploit the higher performance of dense storage (no indirection, SIMD, etc.), and to pay the cost of slow sparse evaluation on the few non-zeros of the sparse matrix only.\n\n\n%Sparse expressions also support transposition:\n\\code\nsm1 = sm2.transpose();\nsm1 = sm2.adjoint();\n\\endcode\nHowever, there is no transposeInPlace() method.\n\n\n\\subsection TutorialSparse_Products Matrix products\n\n%Eigen supports various kind of sparse matrix products which are summarize below:\n  - \\b sparse-dense:\n    \\code\ndv2 = sm1 * dv1;\ndm2 = dm1 * sm1.adjoint();\ndm2 = 2. * sm1 * dm1;\n    \\endcode\n  - \\b symmetric \\b sparse-dense. The product of a sparse symmetric matrix with a dense matrix (or vector) can also be optimized by specifying the symmetry with selfadjointView():\n    \\code\ndm2 = sm1.selfadjointView<>() * dm1;        // if all coefficients of A are stored\ndm2 = A.selfadjointView<Upper>() * dm1;     // if only the upper part of A is stored\ndm2 = A.selfadjointView<Lower>() * dm1;     // if only the lower part of A is stored\n    \\endcode\n  - \\b sparse-sparse. For sparse-sparse products, two different algorithms are available. The default one is conservative and preserve the explicit zeros that might appear:\n    \\code\nsm3 = sm1 * sm2;\nsm3 = 4 * sm1.adjoint() * sm2;\n    \\endcode\n    The second algorithm prunes on the fly the explicit zeros, or the values smaller than a given threshold. It is enabled and controlled through the prune() functions:\n    \\code\nsm3 = (sm1 * sm2).pruned();                  // removes numerical zeros\nsm3 = (sm1 * sm2).pruned(ref);               // removes elements much smaller than ref\nsm3 = (sm1 * sm2).pruned(ref,epsilon);       // removes elements smaller than ref*epsilon\n    \\endcode\n\n  - \\b permutations. Finally, permutations can be applied to sparse matrices too:\n    \\code\nPermutationMatrix<Dynamic,Dynamic> P = ...;\nsm2 = P * sm1;\nsm2 = sm1 * P.inverse();\nsm2 = sm1.transpose() * P;\n    \\endcode\n\n\n\\subsection TutorialSparse_SubMatrices Block operations\n\nRegarding read-access, sparse matrices expose the same API than for dense matrices to access to sub-matrices such as blocks, columns, and rows. See \\ref TutorialBlockOperations for a detailed introduction.\nHowever, for performance reasons, writing to a sub-sparse-matrix is much more limited, and currently only contiguous sets of columns (resp. rows) of a column-major (resp. row-major) SparseMatrix are writable. Moreover, this information has to be known at compile-time, leaving out methods such as <tt>block(...)</tt> and <tt>corner*(...)</tt>. The available API for write-access to a SparseMatrix are summarized below:\n\\code\nSparseMatrix<double,ColMajor> sm1;\nsm1.col(j) = ...;\nsm1.leftCols(ncols) = ...;\nsm1.middleCols(j,ncols) = ...;\nsm1.rightCols(ncols) = ...;\n\nSparseMatrix<double,RowMajor> sm2;\nsm2.row(i) = ...;\nsm2.topRows(nrows) = ...;\nsm2.middleRows(i,nrows) = ...;\nsm2.bottomRows(nrows) = ...;\n\\endcode\n\nIn addition, sparse matrices expose the SparseMatrixBase::innerVector() and SparseMatrixBase::innerVectors() methods, which are aliases to the col/middleCols methods for a column-major storage, and to the row/middleRows methods for a row-major storage.\n\n\\subsection TutorialSparse_TriangularSelfadjoint Triangular and selfadjoint views\n\nJust as with dense matrices, the triangularView() function can be used to address a triangular part of the matrix, and perform triangular solves with a dense right hand side:\n\\code\ndm2 = sm1.triangularView<Lower>(dm1);\ndv2 = sm1.transpose().triangularView<Upper>(dv1);\n\\endcode\n\nThe selfadjointView() function permits various operations:\n - optimized sparse-dense matrix products:\n    \\code\ndm2 = sm1.selfadjointView<>() * dm1;        // if all coefficients of A are stored\ndm2 = A.selfadjointView<Upper>() * dm1;     // if only the upper part of A is stored\ndm2 = A.selfadjointView<Lower>() * dm1;     // if only the lower part of A is stored\n    \\endcode\n - copy of triangular parts:\n    \\code\nsm2 = sm1.selfadjointView<Upper>();                               // makes a full selfadjoint matrix from the upper triangular part\nsm2.selfadjointView<Lower>() = sm1.selfadjointView<Upper>();      // copies the upper triangular part to the lower triangular part\n    \\endcode\n - application of symmetric permutations:\n \\code\nPermutationMatrix<Dynamic,Dynamic> P = ...;\nsm2 = A.selfadjointView<Upper>().twistedBy(P);                                // compute P S P' from the upper triangular part of A, and make it a full matrix\nsm2.selfadjointView<Lower>() = A.selfadjointView<Lower>().twistedBy(P);       // compute P S P' from the lower triangular part of A, and then only compute the lower part\n \\endcode\n\nPlease, refer to the \\link SparseQuickRefPage Quick Reference \\endlink  guide for the list of supported operations. The list of linear solvers available is \\link TopicSparseSystems here. \\endlink\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/TutorialSparse_example_details.dox",
    "content": "/**\n\\page TutorialSparse_example_details\n\\include Tutorial_sparse_example_details.cpp\n*/\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/UnalignedArrayAssert.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TopicUnalignedArrayAssert Explanation of the assertion on unaligned arrays\n\nHello! You are seeing this webpage because your program terminated on an assertion failure like this one:\n<pre>\nmy_program: path/to/eigen/Eigen/src/Core/DenseStorage.h:44:\nEigen::internal::matrix_array<T, Size, MatrixOptions, Align>::internal::matrix_array()\n[with T = double, int Size = 2, int MatrixOptions = 2, bool Align = true]:\nAssertion `(reinterpret_cast<size_t>(array) & (sizemask)) == 0 && \"this assertion\nis explained here: http://eigen.tuxfamily.org/dox-devel/group__TopicUnalignedArrayAssert.html\n**** READ THIS WEB PAGE !!! ****\"' failed.\n</pre>\n\nThere are 4 known causes for this issue.\nIf you can target \\cpp17 only with a recent compiler (e.g., GCC>=7, clang>=5, MSVC>=19.12), then you're lucky: enabling c++17 should be enough (if not, please <a href=\"http://eigen.tuxfamily.org/bz/\">report</a> to us).\nOtherwise, please read on to understand those issues and learn how to fix them.\n\n\\eigenAutoToc\n\n\\section where Where in my own code is the cause of the problem?\n\nFirst of all, you need to find out where in your own code this assertion was triggered from. At first glance, the error message doesn't look helpful, as it refers to a file inside Eigen! However, since your program crashed, if you can reproduce the crash, you can get a backtrace using any debugger. For example, if you're using GCC, you can use the GDB debugger as follows:\n\\code\n$ gdb ./my_program          # Start GDB on your program\n> run                       # Start running your program\n...                         # Now reproduce the crash!\n> bt                        # Obtain the backtrace\n\\endcode\nNow that you know precisely where in your own code the problem is happening, read on to understand what you need to change.\n\n\\section c1 Cause 1: Structures having Eigen objects as members\n\nIf you have code like this,\n\n\\code\nclass Foo\n{\n  //...\n  Eigen::Vector4d v;\n  //...\n};\n//...\nFoo *foo = new Foo;\n\\endcode\n\nthen you need to read this separate page: \\ref TopicStructHavingEigenMembers \"Structures Having Eigen Members\".\n\nNote that here, Eigen::Vector4d is only used as an example, more generally the issue arises for all \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen types\".\n\n\\section c2 Cause 2: STL Containers or manual memory allocation\n\nIf you use STL Containers such as std::vector, std::map, ..., with %Eigen objects, or with classes containing %Eigen objects, like this,\n\n\\code\nstd::vector<Eigen::Matrix2d> my_vector;\nstruct my_class { ... Eigen::Matrix2d m; ... };\nstd::map<int, my_class> my_map;\n\\endcode\n\nthen you need to read this separate page: \\ref TopicStlContainers \"Using STL Containers with Eigen\".\n\nNote that here, Eigen::Matrix2d is only used as an example, more generally the issue arises for all \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen types\" and \\ref TopicStructHavingEigenMembers \"structures having such Eigen objects as member\".\n\nThe same issue will be exhibited by any classes/functions by-passing operator new to allocate memory, that is, by performing custom memory allocation followed by calls to the placement new operator. This is for instance typically the case of \\c `std::make_shared` or `std::allocate_shared` for which is the solution is to use an \\ref aligned_allocator \"aligned allocator\" as detailed in the \\ref TopicStlContainers \"solution for STL containers\".\n\n\\section c3 Cause 3: Passing Eigen objects by value\n\nIf some function in your code is getting an %Eigen object passed by value, like this,\n\n\\code\nvoid func(Eigen::Vector4d v);\n\\endcode\n\nthen you need to read this separate page: \\ref TopicPassingByValue \"Passing Eigen objects by value to functions\".\n\nNote that here, Eigen::Vector4d is only used as an example, more generally the issue arises for all \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen types\".\n\n\\section c4 Cause 4: Compiler making a wrong assumption on stack alignment (for instance GCC on Windows)\n\nThis is a must-read for people using GCC on Windows (like MinGW or TDM-GCC). If you have this assertion failure in an innocent function declaring a local variable like this:\n\n\\code\nvoid foo()\n{\n  Eigen::Quaternionf q;\n  //...\n}\n\\endcode\n\nthen you need to read this separate page: \\ref TopicWrongStackAlignment \"Compiler making a wrong assumption on stack alignment\".\n\nNote that here, Eigen::Quaternionf is only used as an example, more generally the issue arises for all \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen types\".\n\n\n\\section explanation General explanation of this assertion\n\n\\ref TopicFixedSizeVectorizable \"Fixed-size vectorizable Eigen objects\" must absolutely be created at properly aligned locations, otherwise SIMD instructions addressing them will crash.\nFor instance, SSE/NEON/MSA/Altivec/VSX targets will require 16-byte-alignment, whereas AVX and AVX512 targets may require up to 32 and 64 byte alignment respectively.\n\n%Eigen normally takes care of these alignment issues for you, by setting an alignment attribute on them and by overloading their `operator new`.\n\nHowever there are a few corner cases where these alignment settings get overridden: they are the possible causes for this assertion.\n\n\\section getrid I don't care about optimal vectorization, how do I get rid of that stuff?\n\nThree possibilities:\n<ul>\n  <li>Use the \\c DontAlign option to Matrix, Array, Quaternion, etc. objects that gives you trouble. This way %Eigen won't try to over-align them, and thus won\"t assume any special alignment. On the down side, you will pay the cost of unaligned loads/stores for them, but on modern CPUs, the overhead is either null or marginal. See \\link StructHavingEigenMembers_othersolutions here \\endlink for an example.</li>\n  <li>Define \\link TopicPreprocessorDirectivesPerformance EIGEN_MAX_STATIC_ALIGN_BYTES \\endlink to 0. That disables all 16-byte (and above) static alignment code, while keeping 16-byte (or above) heap alignment. This has the effect of\n      vectorizing fixed-size objects (like Matrix4d) through unaligned stores (as controlled by \\link TopicPreprocessorDirectivesPerformance EIGEN_UNALIGNED_VECTORIZE \\endlink), while keeping unchanged the vectorization of dynamic-size objects\n      (like MatrixXd). On 64 bytes systems, you might also define it 16 to disable only 32 and 64 bytes of over-alignment. But do note that this breaks ABI compatibility with the default behavior of static alignment.</li>\n  <li>Or define both \\link TopicPreprocessorDirectivesPerformance  EIGEN_DONT_VECTORIZE \\endlink and `EIGEN_DISABLE_UNALIGNED_ARRAY_ASSERT`. This keeps the\n      16-byte (or above) alignment code and thus preserves ABI compatibility, but completely disables vectorization.</li>\n</ul>\n\nIf you want to know why defining `EIGEN_DONT_VECTORIZE` does not by itself disable 16-byte (or above) alignment and the assertion, here's the explanation:\n\nIt doesn't disable the assertion, because otherwise code that runs fine without vectorization would suddenly crash when enabling vectorization.\nIt doesn't disable 16-byte (or above) alignment, because that would mean that vectorized and non-vectorized code are not mutually ABI-compatible. This ABI compatibility is very important, even for people who develop only an in-house application, as for instance one may want to have in the same application a vectorized path and a non-vectorized path.\n\n\\section checkmycode How can I check my code is safe regarding alignment issues?\n\nUnfortunately, there is no possibility in c++ to detect any of the aforementioned shortcoming at compile time (though static analyzers are becoming more and more powerful and could detect some of them).\nEven at runtime, all we can do is to catch invalid unaligned allocation and trigger the explicit assertion mentioned at the beginning of this page.\nTherefore, if your program runs fine on a given system with some given compilation flags, then this does not guarantee that your code is safe. For instance, on most 64 bits systems buffer are aligned on 16 bytes boundary and so, if you do not enable AVX instruction set, then your code will run fine. On the other hand, the same code may assert if moving to a more exotic platform, or enabling AVX instructions that required 32 bytes alignment by default.\n\nThe situation is not hopeless though. Assuming your code is well covered by unit test, then you can check its alignment safety by linking it to a custom malloc library returning 8 bytes aligned buffers only. This way all alignment shortcomings should pop-up. To this end, you must also compile your program with \\link TopicPreprocessorDirectivesPerformance EIGEN_MALLOC_ALREADY_ALIGNED=0 \\endlink.\n\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/UsingBlasLapackBackends.dox",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n Copyright (C) 2011-2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Documentation on the use of BLAS/LAPACK libraries through Eigen\n ********************************************************************************\n*/\n\nnamespace Eigen {\n\n/** \\page TopicUsingBlasLapack Using BLAS/LAPACK from %Eigen\n\n\nSince %Eigen version 3.3 and later, any F77 compatible BLAS or LAPACK libraries can be used as backends for dense matrix products and dense matrix decompositions.\nFor instance, one can use <a href=\"http://eigen.tuxfamily.org/Counter/redirect_to_mkl.php\">Intel® MKL</a>, Apple's Accelerate framework on OSX, <a href=\"http://www.openblas.net/\">OpenBLAS</a>, <a href=\"http://www.netlib.org/lapack\">Netlib LAPACK</a>, etc.\n\nDo not miss this \\link TopicUsingIntelMKL page \\endlink for further discussions on the specific use of Intel® MKL (also includes VML, PARDISO, etc.)\n\nIn order to use an external BLAS and/or LAPACK library, you must link you own application to the respective libraries and their dependencies.\nFor LAPACK, you must also link to the standard <a href=\"http://www.netlib.org/lapack/lapacke.html\">Lapacke</a> library, which is used as a convenient think layer between %Eigen's C++ code and LAPACK F77 interface. Then you must activate their usage by defining one or multiple of the following macros (\\b before including any %Eigen's header):\n\n\\note For Mac users, in order to use the lapack version shipped with the Accelerate framework, you also need the lapacke library.\nUsing <a href=\"https://www.macports.org/\">MacPorts</a>, this is as easy as:\n\\code\nsudo port install lapack\n\\endcode\nand then use the following link flags: \\c -framework \\c Accelerate \\c /opt/local/lib/lapack/liblapacke.dylib\n\n<table class=\"manual\">\n<tr><td>\\c EIGEN_USE_BLAS </td><td>Enables the use of external BLAS level 2 and 3 routines (compatible with any F77 BLAS interface)</td></tr>\n<tr class=\"alt\"><td>\\c EIGEN_USE_LAPACKE </td><td>Enables the use of external Lapack routines via the <a href=\"http://www.netlib.org/lapack/lapacke.html\">Lapacke</a> C interface to Lapack (compatible with any F77 LAPACK interface)</td></tr>\n<tr><td>\\c EIGEN_USE_LAPACKE_STRICT </td><td>Same as \\c EIGEN_USE_LAPACKE but algorithms of lower numerical robustness are disabled. \\n This currently concerns only JacobiSVD which otherwise would be replaced by \\c gesvd that is less robust than Jacobi rotations.</td></tr>\n</table>\n\nWhen doing so, a number of %Eigen's algorithms are silently substituted with calls to BLAS or LAPACK routines.\nThese substitutions apply only for \\b Dynamic \\b or \\b large enough objects with one of the following four standard scalar types: \\c float, \\c double, \\c complex<float>, and \\c complex<double>.\nOperations on other scalar types or mixing reals and complexes will continue to use the built-in algorithms.\n\nThe breadth of %Eigen functionality that can be substituted is listed in the table below.\n<table class=\"manual\">\n<tr><th>Functional domain</th><th>Code example</th><th>BLAS/LAPACK routines</th></tr>\n<tr><td>Matrix-matrix operations \\n \\c EIGEN_USE_BLAS </td><td>\\code\nm1*m2.transpose();\nm1.selfadjointView<Lower>()*m2;\nm1*m2.triangularView<Upper>();\nm1.selfadjointView<Lower>().rankUpdate(m2,1.0);\n\\endcode</td><td>\\code\n?gemm\n?symm/?hemm\n?trmm\ndsyrk/ssyrk\n\\endcode</td></tr>\n<tr class=\"alt\"><td>Matrix-vector operations \\n \\c EIGEN_USE_BLAS </td><td>\\code\nm1.adjoint()*b;\nm1.selfadjointView<Lower>()*b;\nm1.triangularView<Upper>()*b;\n\\endcode</td><td>\\code\n?gemv\n?symv/?hemv\n?trmv\n\\endcode</td></tr>\n<tr><td>LU decomposition \\n \\c EIGEN_USE_LAPACKE \\n \\c EIGEN_USE_LAPACKE_STRICT </td><td>\\code\nv1 = m1.lu().solve(v2);\n\\endcode</td><td>\\code\n?getrf\n\\endcode</td></tr>\n<tr class=\"alt\"><td>Cholesky decomposition \\n \\c EIGEN_USE_LAPACKE \\n \\c EIGEN_USE_LAPACKE_STRICT </td><td>\\code\nv1 = m2.selfadjointView<Upper>().llt().solve(v2);\n\\endcode</td><td>\\code\n?potrf\n\\endcode</td></tr>\n<tr><td>QR decomposition \\n \\c EIGEN_USE_LAPACKE \\n \\c EIGEN_USE_LAPACKE_STRICT </td><td>\\code\nm1.householderQr();\nm1.colPivHouseholderQr();\n\\endcode</td><td>\\code\n?geqrf\n?geqp3\n\\endcode</td></tr>\n<tr class=\"alt\"><td>Singular value decomposition \\n \\c EIGEN_USE_LAPACKE </td><td>\\code\nJacobiSVD<MatrixXd> svd;\nsvd.compute(m1, ComputeThinV);\n\\endcode</td><td>\\code\n?gesvd\n\\endcode</td></tr>\n<tr><td>Eigen-value decompositions \\n \\c EIGEN_USE_LAPACKE \\n \\c EIGEN_USE_LAPACKE_STRICT </td><td>\\code\nEigenSolver<MatrixXd> es(m1);\nComplexEigenSolver<MatrixXcd> ces(m1);\nSelfAdjointEigenSolver<MatrixXd> saes(m1+m1.transpose());\nGeneralizedSelfAdjointEigenSolver<MatrixXd>\n    gsaes(m1+m1.transpose(),m2+m2.transpose());\n\\endcode</td><td>\\code\n?gees\n?gees\n?syev/?heev\n?syev/?heev,\n?potrf\n\\endcode</td></tr>\n<tr class=\"alt\"><td>Schur decomposition \\n \\c EIGEN_USE_LAPACKE \\n \\c EIGEN_USE_LAPACKE_STRICT </td><td>\\code\nRealSchur<MatrixXd> schurR(m1);\nComplexSchur<MatrixXcd> schurC(m1);\n\\endcode</td><td>\\code\n?gees\n\\endcode</td></tr>\n</table>\nIn the examples, m1 and m2 are dense matrices and v1 and v2 are dense vectors.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/UsingIntelMKL.dox",
    "content": "/*\n Copyright (c) 2011, Intel Corporation. All rights reserved.\n Copyright (C) 2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n\n Redistribution and use in source and binary forms, with or without modification,\n are permitted provided that the following conditions are met:\n\n * Redistributions of source code must retain the above copyright notice, this\n   list of conditions and the following disclaimer.\n * Redistributions in binary form must reproduce the above copyright notice,\n   this list of conditions and the following disclaimer in the documentation\n   and/or other materials provided with the distribution.\n * Neither the name of Intel Corporation nor the names of its contributors may\n   be used to endorse or promote products derived from this software without\n   specific prior written permission.\n\n THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\" AND\n ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED\n WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR\n ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES\n (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON\n ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT\n (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS\n SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n\n ********************************************************************************\n *   Content : Documentation on the use of Intel MKL through Eigen\n ********************************************************************************\n*/\n\nnamespace Eigen {\n\n/** \\page TopicUsingIntelMKL Using Intel® MKL from %Eigen\n\n<!-- \\section TopicUsingIntelMKL_Intro Eigen and Intel® Math Kernel Library (Intel® MKL) -->\n\nSince %Eigen version 3.1 and later, users can benefit from built-in Intel® Math Kernel Library (MKL) optimizations with an installed copy of Intel MKL 10.3 (or later).\n\n<a href=\"http://eigen.tuxfamily.org/Counter/redirect_to_mkl.php\"> Intel MKL </a> provides highly optimized multi-threaded mathematical routines for x86-compatible architectures.\nIntel MKL is available on Linux, Mac and Windows for both Intel64 and IA32 architectures.\n\n\\note\nIntel® MKL is a proprietary software and it is the responsibility of users to buy or register for community (free) Intel MKL licenses for their products. Moreover, the license of the user product has to allow linking to proprietary software that excludes any unmodified versions of the GPL.\n\nUsing Intel MKL through %Eigen is easy:\n-# define the \\c EIGEN_USE_MKL_ALL macro before including any %Eigen's header\n-# link your program to MKL libraries (see the <a href=\"http://software.intel.com/en-us/articles/intel-mkl-link-line-advisor/\">MKL linking advisor</a>)\n-# on a 64bits system, you must use the LP64 interface (not the ILP64 one)\n\nWhen doing so, a number of %Eigen's algorithms are silently substituted with calls to Intel MKL routines.\nThese substitutions apply only for \\b Dynamic \\b or \\b large enough objects with one of the following four standard scalar types: \\c float, \\c double, \\c complex<float>, and \\c complex<double>.\nOperations on other scalar types or mixing reals and complexes will continue to use the built-in algorithms.\n\nIn addition you can choose which parts will be substituted by defining one or multiple of the following macros:\n\n<table class=\"manual\">\n<tr><td>\\c EIGEN_USE_BLAS </td><td>Enables the use of external BLAS level 2 and 3 routines</td></tr>\n<tr class=\"alt\"><td>\\c EIGEN_USE_LAPACKE </td><td>Enables the use of external Lapack routines via the <a href=\"http://www.netlib.org/lapack/lapacke.html\">Lapacke</a> C interface to Lapack</td></tr>\n<tr><td>\\c EIGEN_USE_LAPACKE_STRICT </td><td>Same as \\c EIGEN_USE_LAPACKE but algorithm of lower robustness are disabled. \\n This currently concerns only JacobiSVD which otherwise would be replaced by \\c gesvd that is less robust than Jacobi rotations.</td></tr>\n<tr class=\"alt\"><td>\\c EIGEN_USE_MKL_VML </td><td>Enables the use of Intel VML (vector operations)</td></tr>\n<tr><td>\\c EIGEN_USE_MKL_ALL </td><td>Defines \\c EIGEN_USE_BLAS, \\c EIGEN_USE_LAPACKE, and \\c EIGEN_USE_MKL_VML </td></tr>\n</table>\n\nThe \\c EIGEN_USE_BLAS and \\c EIGEN_USE_LAPACKE* macros can be combined with \\c EIGEN_USE_MKL to explicitly tell Eigen that the underlying BLAS/Lapack implementation is Intel MKL.\nThe main effect is to enable MKL direct call feature (\\c MKL_DIRECT_CALL).\nThis may help to increase performance of some MKL BLAS (?GEMM, ?GEMV, ?TRSM, ?AXPY and ?DOT) and LAPACK (LU, Cholesky and QR) routines for very small matrices.\nMKL direct call can be disabled by defining \\c EIGEN_MKL_NO_DIRECT_CALL.\n\n\nNote that the BLAS and LAPACKE backends can be enabled for any F77 compatible BLAS and LAPACK libraries. See this \\link TopicUsingBlasLapack page \\endlink for the details.\n\nFinally, the PARDISO sparse solver shipped with Intel MKL can be used through the \\ref PardisoLU, \\ref PardisoLLT and \\ref PardisoLDLT classes of the \\ref PardisoSupport_Module.\n\nThe following table summarizes the list of functions covered by \\c EIGEN_USE_MKL_VML:\n<table class=\"manual\">\n<tr><th>Code example</th><th>MKL routines</th></tr>\n<tr><td>\\code\nv2=v1.array().sin();\nv2=v1.array().asin();\nv2=v1.array().cos();\nv2=v1.array().acos();\nv2=v1.array().tan();\nv2=v1.array().exp();\nv2=v1.array().log();\nv2=v1.array().sqrt();\nv2=v1.array().square();\nv2=v1.array().pow(1.5);\n\\endcode</td><td>\\code\nv?Sin\nv?Asin\nv?Cos\nv?Acos\nv?Tan\nv?Exp\nv?Ln\nv?Sqrt\nv?Sqr\nv?Powx\n\\endcode</td></tr>\n</table>\nIn the examples, v1 and v2 are dense vectors.\n\n\n\\section TopicUsingIntelMKL_Links Links\n- Intel MKL can be purchased and downloaded <a href=\"http://eigen.tuxfamily.org/Counter/redirect_to_mkl.php\">here</a>.\n- Intel MKL is also bundled with <a href=\"http://software.intel.com/en-us/articles/intel-composer-xe/\">Intel Composer XE</a>.\n\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/UsingNVCC.dox",
    "content": "\nnamespace Eigen {\n\n/** \\page TopicCUDA Using Eigen in CUDA kernels\n\nStaring from CUDA 5.5 and Eigen 3.3, it is possible to use Eigen's matrices, vectors, and arrays for fixed size within CUDA kernels. This is especially useful when working on numerous but small problems. By default, when Eigen's headers are included within a .cu file compiled by nvcc most Eigen's functions and methods are prefixed by the \\c __device__ \\c __host__ keywords making them callable from both host and device code.\nThis support can be disabled by defining \\c EIGEN_NO_CUDA before including any Eigen's header.\nThis might be useful to disable some warnings when a .cu file makes use of Eigen on the host side only.\nHowever, in both cases, host's SIMD vectorization has to be disabled in .cu files.\nIt is thus \\b strongly \\b recommended to properly move all costly host computation from your .cu files to regular .cpp files.\n\nKnown issues:\n\n - \\c nvcc with MS Visual Studio does not work (patch welcome)\n \n - \\c nvcc 5.5 with gcc-4.7 (or greater) has issues with the standard \\c \\<limits\\> header file. To workaround this, you can add the following before including any other files:\n   \\code\n    // workaround issue between gcc >= 4.7 and cuda 5.5\n    #if (defined __GNUC__) && (__GNUC__>4 || __GNUC_MINOR__>=7)\n      #undef _GLIBCXX_ATOMIC_BUILTINS\n      #undef _GLIBCXX_USE_INT128\n    #endif\n   \\endcode\n   \n - On 64bits system Eigen uses \\c long \\c int as the default type for indexes and sizes. On CUDA device, it would make sense to default to 32 bits \\c int.\n   However, to keep host and CUDA code compatible, this cannot be done automatically by %Eigen, and the user is thus required to define \\c EIGEN_DEFAULT_DENSE_INDEX_TYPE to \\c int throughout his code (or only for CUDA code if there is no interaction between host and CUDA code through %Eigen's object).\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/WrongStackAlignment.dox",
    "content": "namespace Eigen {\n\n/** \\eigenManualPage TopicWrongStackAlignment Compiler making a wrong assumption on stack alignment\n\n<h4>It appears that this was a GCC bug that has been fixed in GCC 4.5.\nIf you hit this issue, please upgrade to GCC 4.5 and report to us, so we can update this page.</h4>\n\nThis is an issue that, so far, we met only with GCC on Windows: for instance, MinGW and TDM-GCC.\n\nBy default, in a function like this,\n\n\\code\nvoid foo()\n{\n  Eigen::Quaternionf q;\n  //...\n}\n\\endcode\n\nGCC assumes that the stack is already 16-byte-aligned so that the object \\a q will be created at a 16-byte-aligned location. For this reason, it doesn't take any special care to explicitly align the object \\a q, as Eigen requires.\n\nThe problem is that, in some particular cases, this assumption can be wrong on Windows, where the stack is only guaranteed to have 4-byte alignment. Indeed, even though GCC takes care of aligning the stack in the main function and does its best to keep it aligned, when a function is called from another thread or from a binary compiled with another compiler, the stack alignment can be corrupted. This results in the object 'q' being created at an unaligned location, making your program crash with the \\ref TopicUnalignedArrayAssert \"assertion on unaligned arrays\". So far we found the three following solutions.\n\n\n\\section sec_sol1 Local solution\n\nA local solution is to mark such a function with this attribute:\n\\code\n__attribute__((force_align_arg_pointer)) void foo()\n{\n  Eigen::Quaternionf q;\n  //...\n}\n\\endcode\nRead <a href=\"http://gcc.gnu.org/onlinedocs/gcc-4.4.0/gcc/Function-Attributes.html#Function-Attributes\">this GCC documentation</a> to understand what this does. Of course this should only be done on GCC on Windows, so for portability you'll have to encapsulate this in a macro which you leave empty on other platforms. The advantage of this solution is that you can finely select which function might have a corrupted stack alignment. Of course on the downside this has to be done for every such function, so you may prefer one of the following two global solutions.\n\n\n\\section sec_sol2 Global solutions\n\nA global solution is to edit your project so that when compiling with GCC on Windows, you pass this option to GCC:\n\\code\n-mincoming-stack-boundary=2\n\\endcode\nExplanation: this tells GCC that the stack is only required to be aligned to 2^2=4 bytes, so that GCC now knows that it really must take extra care to honor the 16 byte alignment of \\ref TopicFixedSizeVectorizable \"fixed-size vectorizable Eigen types\" when needed.\n\nAnother global solution is to pass this option to gcc:\n\\code\n-mstackrealign\n\\endcode\nwhich has the same effect than adding the \\c force_align_arg_pointer attribute to all functions.\n\nThese global solutions are easy to use, but note that they may slowdown your program because they lead to extra prologue/epilogue instructions for every function.\n\n*/\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/eigen_navtree_hacks.js",
    "content": "\n// generate a table of contents in the side-nav based on the h1/h2 tags of the current page.\nfunction generate_autotoc() {\n  var headers = $(\"h1, h2\");\n  if(headers.length > 1) {\n    var toc = $(\"#side-nav\").append('<div id=\"nav-toc\" class=\"toc\"><h3>Table of contents</h3></div>');\n    toc = $(\"#nav-toc\");\n    var footer  = $(\"#nav-path\");\n    var footerHeight = footer.height();\n    toc = toc.append('<ul></ul>');\n    toc = toc.find('ul');\n    var indices = new Array();\n    indices[0] = 0;\n    indices[1] = 0;\n\n    var h1counts = $(\"h1\").length;\n    headers.each(function(i) {\n      var current = $(this);\n      var levelTag = current[0].tagName.charAt(1);\n      if(h1counts==0)\n        levelTag--;\n      var cur_id = current.attr(\"id\");\n\n      indices[levelTag-1]+=1;  \n      var prefix = indices[0];\n      if (levelTag >1) {\n        prefix+=\".\"+indices[1];\n      }\n        \n      // Uncomment to add number prefixes\n      // current.html(prefix + \"   \" + current.html());\n      for(var l = levelTag; l < 2; ++l){\n          indices[l] = 0;\n      }\n\n      if(cur_id == undefined) {\n        current.attr('id', 'title' + i);\n        current.addClass('anchor');\n        toc.append(\"<li class='level\" + levelTag + \"'><a id='link\" + i + \"' href='#title\" +\n                    i + \"' title='\" + current.prop(\"tagName\") + \"'>\" + current.text() + \"</a></li>\");\n      } else {\n        toc.append(\"<li class='level\" + levelTag + \"'><a id='\" + cur_id + \"' href='#title\" +\n                    i + \"' title='\" + current.prop(\"tagName\") + \"'>\" + current.text() + \"</a></li>\");\n      }\n    });\n    resizeHeight();\n  }\n}\n\n\nvar global_navtree_object;\n\n// Overloaded to remove links to sections/subsections\nfunction getNode(o, po)\n{\n  po.childrenVisited = true;\n  var l = po.childrenData.length-1;\n  for (var i in po.childrenData) {\n    var nodeData = po.childrenData[i];\n    if((!nodeData[1]) ||  (nodeData[1].indexOf('#')==-1)) // <- we added this line\n      po.children[i] = newNode(o, po, nodeData[0], nodeData[1], nodeData[2], i==l);\n  }\n}\n\n// Overloaded to adjust the size of the navtree wrt the toc\nfunction resizeHeight() \n{\n  var header  = $(\"#top\");\n  var sidenav = $(\"#side-nav\");\n  var content = $(\"#doc-content\");\n  var navtree = $(\"#nav-tree\");\n  var footer  = $(\"#nav-path\");\n  var toc     = $(\"#nav-toc\");\n\n  var headerHeight = header.outerHeight();\n  var footerHeight = footer.outerHeight();\n  var tocHeight    = toc.height();\n  var windowHeight = $(window).height() - headerHeight - footerHeight;\n  content.css({height:windowHeight + \"px\"});\n  navtree.css({height:(windowHeight-tocHeight) + \"px\"});\n  sidenav.css({height:windowHeight + \"px\"});\n}\n\n// Overloaded to save the root node into global_navtree_object\nfunction initNavTree(toroot,relpath)\n{\n  var o = new Object();\n  global_navtree_object = o; // <- we added this line\n  o.toroot = toroot;\n  o.node = new Object();\n  o.node.li = document.getElementById(\"nav-tree-contents\");\n  o.node.childrenData = NAVTREE;\n  o.node.children = new Array();\n  o.node.childrenUL = document.createElement(\"ul\");\n  o.node.getChildrenUL = function() { return o.node.childrenUL; };\n  o.node.li.appendChild(o.node.childrenUL);\n  o.node.depth = 0;\n  o.node.relpath = relpath;\n  o.node.expanded = false;\n  o.node.isLast = true;\n  o.node.plus_img = document.createElement(\"img\");\n  o.node.plus_img.src = relpath+\"ftv2pnode.png\";\n  o.node.plus_img.width = 16;\n  o.node.plus_img.height = 22;\n\n  if (localStorageSupported()) {\n    var navSync = $('#nav-sync');\n    if (cachedLink()) {\n      showSyncOff(navSync,relpath);\n      navSync.removeClass('sync');\n    } else {\n      showSyncOn(navSync,relpath);\n    }\n    navSync.click(function(){ toggleSyncButton(relpath); });\n  }\n\n  navTo(o,toroot,window.location.hash,relpath);\n\n  $(window).bind('hashchange', function(){\n     if (window.location.hash && window.location.hash.length>1){\n       var a;\n       if ($(location).attr('hash')){\n         var clslink=stripPath($(location).attr('pathname'))+':'+\n                               $(location).attr('hash').substring(1);\n         a=$('.item a[class$=\"'+clslink+'\"]');\n       }\n       if (a==null || !$(a).parent().parent().hasClass('selected')){\n         $('.item').removeClass('selected');\n         $('.item').removeAttr('id');\n       }\n       var link=stripPath2($(location).attr('pathname'));\n       navTo(o,link,$(location).attr('hash'),relpath);\n     } else if (!animationInProgress) {\n       $('#doc-content').scrollTop(0);\n       $('.item').removeClass('selected');\n       $('.item').removeAttr('id');\n       navTo(o,toroot,window.location.hash,relpath);\n     }\n  })\n\n  $(window).on(\"load\", showRoot);\n}\n\n// return false if the the node has no children at all, or has only section/subsection children\nfunction checkChildrenData(node) {\n  if (!(typeof(node.childrenData)==='string')) {\n    for (var i in node.childrenData) {\n      var url = node.childrenData[i][1];\n      if(url.indexOf(\"#\")==-1)\n        return true;\n    }\n    return false;\n  }\n  return (node.childrenData);\n}\n\n// Modified to:\n// 1 - remove the root node \n// 2 - remove the section/subsection children\nfunction createIndent(o,domNode,node,level)\n{\n  var level=-2; // <- we replaced level=-1 by level=-2\n  var n = node;\n  while (n.parentNode) { level++; n=n.parentNode; }\n  if (checkChildrenData(node)) { // <- we modified this line to use checkChildrenData(node) instead of node.childrenData\n    var imgNode = document.createElement(\"span\");\n    imgNode.className = 'arrow';\n    imgNode.style.paddingLeft=(16*level).toString()+'px';\n    imgNode.innerHTML=arrowRight;\n    node.plus_img = imgNode;\n    node.expandToggle = document.createElement(\"a\");\n    node.expandToggle.href = \"javascript:void(0)\";\n    node.expandToggle.onclick = function() {\n      if (node.expanded) {\n        $(node.getChildrenUL()).slideUp(\"fast\");\n        node.plus_img.innerHTML=arrowRight;\n        node.expanded = false;\n      } else {\n        expandNode(o, node, false, false);\n      }\n    }\n    node.expandToggle.appendChild(imgNode);\n    domNode.appendChild(node.expandToggle);\n  } else {\n    var span = document.createElement(\"span\");\n    span.className = 'arrow';\n    span.style.width   = 16*(level+1)+'px';\n    span.innerHTML = '&#160;';\n    domNode.appendChild(span);\n  }\n}\n\n// Overloaded to automatically expand the selected node\nfunction selectAndHighlight(hash,n)\n{\n  var a;\n  if (hash) {\n    var link=stripPath($(location).attr('pathname'))+':'+hash.substring(1);\n    a=$('.item a[class$=\"'+link+'\"]');\n  }\n  if (a && a.length) {\n    a.parent().parent().addClass('selected');\n    a.parent().parent().attr('id','selected');\n    highlightAnchor();\n  } else if (n) {\n    $(n.itemDiv).addClass('selected');\n    $(n.itemDiv).attr('id','selected');\n  }\n  if ($('#nav-tree-contents .item:first').hasClass('selected')) {\n    $('#nav-sync').css('top','30px');\n  } else {\n    $('#nav-sync').css('top','5px');\n  }\n  expandNode(global_navtree_object, n, true, true); // <- we added this line\n  showRoot();\n}\n\n\n$(document).ready(function() {\n  \n  generate_autotoc();\n  \n  (function (){ // wait until the first \"selected\" element has been created\n    try {\n      \n      // this line will triger an exception if there is no #selected element, i.e., before the tree structure is complete.\n      document.getElementById(\"selected\").className = \"item selected\";\n      \n      // ok, the default tree has been created, we can keep going...\n      \n      // expand the \"Chapters\" node\n      if(window.location.href.indexOf('unsupported')==-1)\n        expandNode(global_navtree_object, global_navtree_object.node.children[0].children[2], true, true);\n      else\n        expandNode(global_navtree_object, global_navtree_object.node.children[0].children[1], true, true);\n      \n      // Hide the root node \"Eigen\"\n      $(document.getElementsByClassName('index.html')[0]).parent().parent().css({display:\"none\"});\n      \n    } catch (err) {\n      setTimeout(arguments.callee, 10);\n    }\n  })();\n\n  $(window).on(\"load\", resizeHeight);\n});\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/eigendoxy.css",
    "content": "\n/******** Eigen specific CSS code ************/\n\n/**** Styles removing elements ****/\n\n/* remove the \"modules|classes\" link for module pages (they are already in the TOC) */\ndiv.summary {\n  display:none;\n}\n\n/* remove */\ndiv.contents hr {\n  display:none;\n}\n\n/**** ****/\n\np, dl.warning, dl.attention, dl.note\n{\n  max-width:60em;\n  text-align:justify;\n}\n\nli {\n  max-width:55em;\n  text-align:justify;  \n}\n\nimg {\n  border: 0;\n}\n\ndiv.fragment {\n  display:table; /* this allows the element to be larger than its parent */\n  padding: 0pt;\n}\npre.fragment {\n  border: 1px solid #cccccc;\n\n  margin: 2px 0px 2px 0px;\n  padding: 3px 5px 3px 5px;\n}\n\n\n\n/* Common style for all Eigen's tables */\n\ntable.example, table.manual, table.manual-vl, table.manual-hl {\n    max-width:100%;\n    border-collapse: collapse;\n    border-style: solid;\n    border-width: 1px;\n    border-color: #cccccc;\n    font-size: 1em;\n    \n    box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15);\n    -moz-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15);\n    -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15);\n}\n\ntable.example th, table.manual th, table.manual-vl th, table.manual-hl th {\n  padding: 0.5em 0.5em 0.5em 0.5em;\n  text-align: left;\n  padding-right: 1em;\n  color: #555555;\n  background-color: #F4F4E5;\n  \n  background-image: -webkit-gradient(linear,center top,center bottom,from(#FFFFFF), color-stop(0.3,#FFFFFF), color-stop(0.30,#FFFFFF), color-stop(0.98,#F4F4E5), to(#ECECDE));\n  background-image: -moz-linear-gradient(center top, #FFFFFF 0%, #FFFFFF 30%, #F4F4E5 98%, #ECECDE);\n  filter: progid:DXImageTransform.Microsoft.gradient(startColorstr='#FFFFFF', endColorstr='#F4F4E5');\n}\n\ntable.example td, table.manual td, table.manual-vl td, table.manual-hl td {\n  vertical-align:top;\n  border-width: 1px;\n  border-color: #cccccc;\n}\n\n/* header of headers */\ntable th.meta {\n  text-align:center;\n  font-size: 1.2em;\n  background-color:#FFFFFF;\n}\n\n/* intermediate header */\ntable th.inter {\n  text-align:left;\n  background-color:#FFFFFF;\n  background-image:none;\n  border-style:solid solid solid solid;\n  border-width: 1px;\n\tborder-color: #cccccc;\n}\n\n/** class for example / output tables **/\n\ntable.example {\n}\n\ntable.example th {\n}\n\ntable.example td {\n  padding: 0.5em 0.5em 0.5em 0.5em;\n  vertical-align:top;\n}\n\n/* standard class for the manual */\n\ntable.manual, table.manual-vl, table.manual-hl {\n    padding: 0.2em 0em 0.5em 0em;\n}\n\ntable.manual th, table.manual-vl th, table.manual-hl th {\n  margin: 0em 0em 0.3em 0em;\n}\n\ntable.manual td, table.manual-vl td, table.manual-hl td {\n  padding: 0.3em 0.5em 0.3em 0.5em;\n  vertical-align:top;\n  border-width: 1px;\n}\n\ntable.manual td.alt, table.manual tr.alt, table.manual-vl td.alt, table.manual-vl tr.alt {\n  background-color: #F4F4E5;\n}\n\ntable.manual-vl th, table.manual-vl td, table.manual-vl td.alt {\n  border-color: #cccccc;\n  border-width: 1px;\n  border-style: none solid none solid;\n}\n\ntable.manual-vl th.inter {\n  border-style: solid solid solid solid;\n}\n\ntable.manual-hl td {\n  border-color: #cccccc;\n  border-width: 1px;\n  border-style: solid none solid none;\n}\n\ntable td.code {\n  font-family: monospace;\n}\n\nh2 {\n  margin-top:2em;\n  border-style: none none solid none;\n  border-width: 1px;\n  border-color: #cccccc;\n}\n\n/**** Table of content in the side-nav ****/\n\n\ndiv.toc {\n  margin:0;\n  padding: 0.3em 0 0 0;\n  width:100%;\n  float:none;\n  position:absolute;\n  bottom:0;\n  border-radius:0px;\n  border-style: solid none none none;\n  max-height:50%;\n  overflow-y: scroll;\n}\n\ndiv.toc h3 {\n  margin-left: 0.5em;\n  margin-bottom: 0.2em;\n}\n\ndiv.toc ul {\n  margin: 0.2em 0 0.4em 0.5em;\n}\n\nspan.cpp11,span.cpp14,span.cpp17 {\n  color: #119911;\n  font-weight: bold;\n}\n\n.newin3x {\n  color: #a37c1a;\n  font-weight: bold;\n}\n\ndiv.warningbox {\n  max-width:60em;\n  border-style: solid solid solid solid;\n  border-color: red;\n  border-width: 3px;\n}\n\n/**** old Eigen's styles ****/\n\n\ntable.tutorial_code td {\n  border-color: transparent; /* required for Firefox */\n  padding: 3pt 5pt 3pt 5pt;\n  vertical-align: top;\n}\n\n\n/* Whenever doxygen meets a '\\n' or a '<BR/>', it will put \n * the text containing the character into a <p class=\"starttd\">.\n * This little hack together with table.tutorial_code td.note\n * aims at fixing this issue. */\ntable.tutorial_code td.note p.starttd {\n  margin: 0px;\n  border: none;\n  padding: 0px;\n}\n\ndiv.eimainmenu {\n  text-align:     center;\n}\n\n/* center version number on main page */\nh3.version { \n  text-align:     center;\n}\n\n\ntd.width20em p.endtd {\n  width:  20em;\n}\n\n/* needed for huge screens */\n.ui-resizable-e {\n  background-repeat: repeat-y;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/eigendoxy_footer.html.in",
    "content": "<!-- start footer part -->\n<!--BEGIN GENERATE_TREEVIEW-->\n<div id=\"nav-path\" class=\"navpath\"><!-- id is needed for treeview function! -->\n  <ul>\n    $navpath\n    <li class=\"footer\">$generatedby\n    <a href=\"http://www.doxygen.org/index.html\">\n    <img class=\"footer\" src=\"$relpath^doxygen.png\" alt=\"doxygen\"/></a> $doxygenversion </li>\n  </ul>\n</div>\n<!--END GENERATE_TREEVIEW-->\n<!--BEGIN !GENERATE_TREEVIEW-->\n<hr class=\"footer\"/><address class=\"footer\"><small>\n$generatedby &#160;<a href=\"http://www.doxygen.org/index.html\">\n<img class=\"footer\" src=\"$relpath^doxygen.png\" alt=\"doxygen\"/>\n</a> $doxygenversion\n</small></address>\n<!--END !GENERATE_TREEVIEW-->\n\n</body>\n</html>\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/eigendoxy_header.html.in",
    "content": "<!DOCTYPE html PUBLIC \"-//W3C//DTD XHTML 1.0 Transitional//EN\" \"http://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd\">\n<html xmlns=\"http://www.w3.org/1999/xhtml\">\n<head>\n<meta http-equiv=\"Content-Type\" content=\"text/xhtml;charset=UTF-8\"/>\n<meta http-equiv=\"X-UA-Compatible\" content=\"IE=9\"/>\n<meta name=\"generator\" content=\"Doxygen $doxygenversion\"/>\n<meta name=\"viewport\" content=\"width=device-width, initial-scale=1\"/>\n<!--BEGIN PROJECT_NAME--><title>$projectname: $title</title><!--END PROJECT_NAME-->\n<!--BEGIN !PROJECT_NAME--><title>$title</title><!--END !PROJECT_NAME-->\n<link href=\"$relpath^tabs.css\" rel=\"stylesheet\" type=\"text/css\"/>\n<script type=\"text/javascript\" src=\"$relpath^jquery.js\"></script>\n<script type=\"text/javascript\" src=\"$relpath^dynsections.js\"></script>\n$treeview\n$search\n$mathjax\n<link href=\"$relpath^$stylesheet\" rel=\"stylesheet\" type=\"text/css\" />\n<link href=\"$relpath$eigendoxy.css\" rel=\"stylesheet\" type=\"text/css\">\n<!-- $extrastylesheet -->\n<script type=\"text/javascript\" src=\"$relpath$eigen_navtree_hacks.js\"></script>\n\n</head>\n<body>\n\n<div style=\"background:#FFDDDD;font-size:120%;text-align:center;margin:0;padding:5px\">Please, help us to better know about our user community by answering the following short survey:  <a href=\"https://forms.gle/wpyrxWi18ox9Z5ae9\">https://forms.gle/wpyrxWi18ox9Z5ae9</a></div>\n\n<div id=\"top\"><!-- do not remove this div, it is closed by doxygen! -->\n\n<!--BEGIN TITLEAREA-->\n<div id=\"titlearea\">\n<table cellspacing=\"0\" cellpadding=\"0\">\n <tbody>\n <tr style=\"height: 56px;\">\n  <!--BEGIN PROJECT_LOGO-->\n  <td id=\"projectlogo\"><img alt=\"Logo\" src=\"$relpath^$projectlogo\"/></td>\n  <!--END PROJECT_LOGO-->\n  <!--BEGIN PROJECT_NAME-->\n  <td id=\"projectalign\" style=\"padding-left: 0.5em;\">\n   <div id=\"projectname\"><a href=\"http://eigen.tuxfamily.org\">$projectname</a>\n   <!--BEGIN PROJECT_NUMBER-->&#160;<span id=\"projectnumber\">$projectnumber</span><!--END PROJECT_NUMBER-->\n   </div>\n   <!--BEGIN PROJECT_BRIEF--><div id=\"projectbrief\">$projectbrief</div><!--END PROJECT_BRIEF-->\n  </td>\n  <!--END PROJECT_NAME-->\n  <!--BEGIN !PROJECT_NAME-->\n   <!--BEGIN PROJECT_BRIEF-->\n    <td id=\"projectalign\" style=\"padding-left: 0.5em;\">\n    <div id=\"projectbrief\">$projectbrief</div>\n    </td>\n   <!--END PROJECT_BRIEF-->\n  <!--END !PROJECT_NAME-->\n  <!--BEGIN DISABLE_INDEX-->\n   <!--BEGIN SEARCHENGINE-->\n   <td>$searchbox</td>\n   <!--END SEARCHENGINE-->\n  <!--END DISABLE_INDEX-->\n </tr>\n </tbody>\n</table>\n</div>\n<!--END TITLEAREA-->\n<!-- end header part -->\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/eigendoxy_layout.xml.in",
    "content": "<?xml version=\"1.0\"?>\n<doxygenlayout version=\"1.0\">\n  <!-- Navigation index tabs for HTML output -->\n  <navindex>\n    <tab type=\"user\" url=\"index.html\" title=\"Overview\" />\n    <tab type=\"user\" url=\"@ref GettingStarted\" title=\"Getting started\" />\n    <tab type=\"modules\" visible=\"yes\" title=\"Chapters\" intro=\"\"/>\n    <tab type=\"mainpage\" visible=\"yes\" title=\"\"/>\n    <tab type=\"classlist\" visible=\"yes\" title=\"\" intro=\"\"/>\n<!--     <tab type=\"classmembers\" visible=\"yes\" title=\"\" intro=\"\"/> -->\n  </navindex>\n\n  <!-- Layout definition for a class page -->\n  <class>\n    <briefdescription visible=\"no\"/>\n    <includes visible=\"$SHOW_INCLUDE_FILES\"/>\n    <detaileddescription title=\"\"/>\n    <inheritancegraph visible=\"$CLASS_GRAPH\"/>\n    <collaborationgraph visible=\"$COLLABORATION_GRAPH\"/>\n    <allmemberslink visible=\"yes\"/>\n    <memberdecl>\n      <nestedclasses visible=\"yes\" title=\"\"/>\n      <publictypes title=\"\"/>\n      <publicslots title=\"\"/>\n      <signals title=\"\"/>\n      <publicmethods title=\"\"/>\n      <publicstaticmethods title=\"\"/>\n      <publicattributes title=\"\"/>\n      <publicstaticattributes title=\"\"/>\n      <protectedtypes title=\"\"/>\n      <protectedslots title=\"\"/>\n      <protectedmethods title=\"\"/>\n      <protectedstaticmethods title=\"\"/>\n      <protectedattributes title=\"\"/>\n      <protectedstaticattributes title=\"\"/>\n      <packagetypes title=\"\"/>\n      <packagemethods title=\"\"/>\n      <packagestaticmethods title=\"\"/>\n      <packageattributes title=\"\"/>\n      <packagestaticattributes title=\"\"/>\n      <properties title=\"\"/>\n      <events title=\"\"/>\n      <privatetypes title=\"\"/>\n      <privateslots title=\"\"/>\n      <privatemethods title=\"\"/>\n      <privatestaticmethods title=\"\"/>\n      <privateattributes title=\"\"/>\n      <privatestaticattributes title=\"\"/>\n      <friends title=\"\"/>\n      <related title=\"\" subtitle=\"\"/>\n      <membergroups visible=\"yes\"/>\n    </memberdecl>\n    \n    <memberdef>\n      <inlineclasses title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <constructors title=\"\"/>\n      <functions title=\"\"/>\n      <related title=\"\"/>\n      <variables title=\"\"/>\n      <properties title=\"\"/>\n      <events title=\"\"/>\n    </memberdef>\n    <usedfiles visible=\"$SHOW_USED_FILES\"/>\n    <authorsection visible=\"yes\"/>\n  </class>\n\n  <!-- Layout definition for a namespace page -->\n  <namespace>\n    <briefdescription visible=\"yes\"/>\n    <memberdecl>\n      <nestednamespaces visible=\"yes\" title=\"\"/>\n      <classes visible=\"yes\" title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n      <membergroups visible=\"yes\"/>\n    </memberdecl>\n    <detaileddescription title=\"\"/>\n    <memberdef>\n      <inlineclasses title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n    </memberdef>\n    <authorsection visible=\"yes\"/>\n  </namespace>\n\n  <!-- Layout definition for a file page -->\n  <file>\n    <briefdescription visible=\"yes\"/>\n    <includes visible=\"$SHOW_INCLUDE_FILES\"/>\n    <includegraph visible=\"$INCLUDE_GRAPH\"/>\n    <includedbygraph visible=\"$INCLUDED_BY_GRAPH\"/>\n    <sourcelink visible=\"yes\"/>\n    <memberdecl>\n      <classes visible=\"yes\" title=\"\"/>\n      <namespaces visible=\"yes\" title=\"\"/>\n      <defines title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n      <membergroups visible=\"yes\"/>\n    </memberdecl>\n    <detaileddescription title=\"\"/>\n    <memberdef>\n      <inlineclasses title=\"\"/>\n      <defines title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n    </memberdef>\n    <authorsection/>\n  </file>\n\n  <!-- Layout definition for a group page -->\n  <group>\n    <briefdescription visible=\"no\"/>\n    <detaileddescription title=\"\"/>\n    <groupgraph visible=\"$GROUP_GRAPHS\"/>\n    <memberdecl>\n      <nestedgroups visible=\"yes\" title=\"\"/>\n      <dirs visible=\"yes\" title=\"\"/>\n      <files visible=\"yes\" title=\"\"/>\n      <namespaces visible=\"yes\" title=\"\"/>\n      <classes visible=\"yes\" title=\"\"/>\n      <defines title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <enumvalues title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n      <signals title=\"\"/>\n      <publicslots title=\"\"/>\n      <protectedslots title=\"\"/>\n      <privateslots title=\"\"/>\n      <events title=\"\"/>\n      <properties title=\"\"/>\n      <friends title=\"\"/>\n      <membergroups visible=\"yes\"/>\n    </memberdecl>\n    \n    <memberdef>\n      <pagedocs/>\n      <inlineclasses title=\"\"/>\n      <defines title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <enumvalues title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n      <signals title=\"\"/>\n      <publicslots title=\"\"/>\n      <protectedslots title=\"\"/>\n      <privateslots title=\"\"/>\n      <events title=\"\"/>\n      <properties title=\"\"/>\n      <friends title=\"\"/>\n    </memberdef>\n    <authorsection visible=\"yes\"/>\n  </group>\n\n  <!-- Layout definition for a directory page -->\n  <directory>\n    <briefdescription visible=\"yes\"/>\n    <directorygraph visible=\"yes\"/>\n    <memberdecl>\n      <dirs visible=\"yes\"/>\n      <files visible=\"yes\"/>\n    </memberdecl>\n    <detaileddescription title=\"\"/>\n  </directory>\n</doxygenlayout>\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/eigendoxy_tabs.css",
    "content": ".tabs, .tabs2, .tabs3 {\n    background-image: url('tab_b.png');\n    width: 100%;\n    z-index: 101;\n    font-size: 13px;\n}\n\n.tabs2 {\n    font-size: 10px;\n}\n.tabs3 {\n    font-size: 9px;\n}\n\n.tablist {\n    margin: 0;\n    padding: 0;\n    display: table;\n}\n\n.tablist li {\n    float: left;\n    display: table-cell;\n    background-image: url('tab_b.png');\n    line-height: 36px;\n    list-style: none;\n}\n\n.tablist a {\n    display: block;\n    padding: 0 20px;\n    font-weight: bold;\n    background-image:url('tab_s.png');\n    background-repeat:no-repeat;\n    background-position:right;\n    color: #283A5D;\n    text-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9);\n    text-decoration: none;\n    outline: none;\n}\n\n.tabs3 .tablist a {\n    padding: 0 10px;\n}\n\n.tablist a:hover {\n    background-image: url('tab_h.png');\n    background-repeat:repeat-x;\n    color: #fff;\n    text-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0);\n    text-decoration: none;\n}\n\n.tablist li.current a {\n    background-image: url('tab_a.png');\n    background-repeat:repeat-x;\n    color: #fff;\n    text-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/.krazy",
    "content": "EXCLUDE copyright\nEXCLUDE license\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/CMakeLists.txt",
    "content": "file(GLOB examples_SRCS \"*.cpp\")\n\nforeach(example_src ${examples_SRCS})\n  get_filename_component(example ${example_src} NAME_WE)\n  add_executable(${example} ${example_src})\n  if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO)\n    target_link_libraries(${example} ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO})\n  endif()\n  add_custom_command(\n    TARGET ${example}\n    POST_BUILD\n    COMMAND ${example}\n    ARGS >${CMAKE_CURRENT_BINARY_DIR}/${example}.out\n  )\n  add_dependencies(all_examples ${example})\nendforeach()\n\nif(EIGEN_COMPILER_SUPPORT_CPP11)\nei_add_target_property(nullary_indexing COMPILE_FLAGS \"-std=c++11\")\nendif()"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/CustomizingEigen_Inheritance.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\n\nclass MyVectorType : public Eigen::VectorXd\n{\npublic:\n    MyVectorType(void):Eigen::VectorXd() {}\n\n    // This constructor allows you to construct MyVectorType from Eigen expressions\n    template<typename OtherDerived>\n    MyVectorType(const Eigen::MatrixBase<OtherDerived>& other)\n        : Eigen::VectorXd(other)\n    { }\n\n    // This method allows you to assign Eigen expressions to MyVectorType\n    template<typename OtherDerived>\n    MyVectorType& operator=(const Eigen::MatrixBase <OtherDerived>& other)\n    {\n        this->Eigen::VectorXd::operator=(other);\n        return *this;\n    }\n};\n\nint main()\n{\n  MyVectorType v = MyVectorType::Ones(4);\n  v(2) += 10;\n  v = 2 * v;\n  std::cout << v.transpose() << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Cwise_erf.cpp",
    "content": "#include <Eigen/Core>\n#include <unsupported/Eigen/SpecialFunctions>\n#include <iostream>\nusing namespace Eigen;\nint main()\n{\n  Array4d v(-0.5,2,0,-7);\n  std::cout << v.erf() << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Cwise_erfc.cpp",
    "content": "#include <Eigen/Core>\n#include <unsupported/Eigen/SpecialFunctions>\n#include <iostream>\nusing namespace Eigen;\nint main()\n{\n  Array4d v(-0.5,2,0,-7);\n  std::cout << v.erfc() << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Cwise_lgamma.cpp",
    "content": "#include <Eigen/Core>\n#include <unsupported/Eigen/SpecialFunctions>\n#include <iostream>\nusing namespace Eigen;\nint main()\n{\n  Array4d v(0.5,10,0,-1);\n  std::cout << v.lgamma() << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/DenseBase_middleCols_int.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main(void)\n{\n    int const N = 5;\n    MatrixXi A(N,N);\n    A.setRandom();\n    cout << \"A =\\n\" << A << '\\n' << endl;\n    cout << \"A(1..3,:) =\\n\" << A.middleCols(1,3) << endl;\n    return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/DenseBase_middleRows_int.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main(void)\n{\n    int const N = 5;\n    MatrixXi A(N,N);\n    A.setRandom();\n    cout << \"A =\\n\" << A << '\\n' << endl;\n    cout << \"A(2..3,:) =\\n\" << A.middleRows(2,2) << endl;\n    return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/DenseBase_template_int_middleCols.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main(void)\n{\n    int const N = 5;\n    MatrixXi A(N,N);\n    A.setRandom();\n    cout << \"A =\\n\" << A << '\\n' << endl;\n    cout << \"A(:,1..3) =\\n\" << A.middleCols<3>(1) << endl;\n    return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/DenseBase_template_int_middleRows.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main(void)\n{\n    int const N = 5;\n    MatrixXi A(N,N);\n    A.setRandom();\n    cout << \"A =\\n\" << A << '\\n' << endl;\n    cout << \"A(1..3,:) =\\n\" << A.middleRows<3>(1) << endl;\n    return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/QuickStart_example.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing Eigen::MatrixXd;\n\nint main()\n{\n  MatrixXd m(2,2);\n  m(0,0) = 3;\n  m(1,0) = 2.5;\n  m(0,1) = -1;\n  m(1,1) = m(1,0) + m(0,1);\n  std::cout << m << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/QuickStart_example2_dynamic.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  MatrixXd m = MatrixXd::Random(3,3);\n  m = (m + MatrixXd::Constant(3,3,1.2)) * 50;\n  cout << \"m =\" << endl << m << endl;\n  VectorXd v(3);\n  v << 1, 2, 3;\n  cout << \"m * v =\" << endl << m * v << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/QuickStart_example2_fixed.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  Matrix3d m = Matrix3d::Random();\n  m = (m + Matrix3d::Constant(1.2)) * 50;\n  cout << \"m =\" << endl << m << endl;\n  Vector3d v(1,2,3);\n  \n  cout << \"m * v =\" << endl << m * v << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/TemplateKeyword_flexible.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace Eigen;\n\ntemplate <typename Derived1, typename Derived2>\nvoid copyUpperTriangularPart(MatrixBase<Derived1>& dst, const MatrixBase<Derived2>& src)\n{\n  /* Note the 'template' keywords in the following line! */\n  dst.template triangularView<Upper>() = src.template triangularView<Upper>();\n}\n\nint main()\n{\n  MatrixXi m1 = MatrixXi::Ones(5,5);\n  MatrixXi m2 = MatrixXi::Random(4,4);\n  std::cout << \"m2 before copy:\" << std::endl;\n  std::cout << m2 << std::endl << std::endl;\n  copyUpperTriangularPart(m2, m1.topLeftCorner(4,4));\n  std::cout << \"m2 after copy:\" << std::endl;\n  std::cout << m2 << std::endl << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/TemplateKeyword_simple.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace Eigen;\n\nvoid copyUpperTriangularPart(MatrixXf& dst, const MatrixXf& src)\n{\n  dst.triangularView<Upper>() = src.triangularView<Upper>();\n}\n\nint main()\n{\n  MatrixXf m1 = MatrixXf::Ones(4,4);\n  MatrixXf m2 = MatrixXf::Random(4,4);\n  std::cout << \"m2 before copy:\" << std::endl;\n  std::cout << m2 << std::endl << std::endl;\n  copyUpperTriangularPart(m2, m1);\n  std::cout << \"m2 after copy:\" << std::endl;\n  std::cout << m2 << std::endl << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/TutorialInplaceLU.cpp",
    "content": "#include <iostream>\nstruct init {\n  init() { std::cout << \"[\" << \"init\" << \"]\" << std::endl; }\n};\ninit init_obj;\n// [init]\n#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n  MatrixXd A(2,2);\n  A << 2, -1, 1, 3;\n  cout << \"Here is the input matrix A before decomposition:\\n\" << A << endl;\ncout << \"[init]\" << endl;\n\ncout << \"[declaration]\" << endl;\n  PartialPivLU<Ref<MatrixXd> > lu(A);\n  cout << \"Here is the input matrix A after decomposition:\\n\" << A << endl;\ncout << \"[declaration]\" << endl;\n\ncout << \"[matrixLU]\" << endl;\n  cout << \"Here is the matrix storing the L and U factors:\\n\" << lu.matrixLU() << endl;\ncout << \"[matrixLU]\" << endl;\n\ncout << \"[solve]\" << endl;\n  MatrixXd A0(2,2); A0 << 2, -1, 1, 3;\n  VectorXd b(2);    b << 1, 2;\n  VectorXd x = lu.solve(b);\n  cout << \"Residual: \" << (A0 * x - b).norm() << endl;\ncout << \"[solve]\" << endl;\n\ncout << \"[modifyA]\" << endl;\n  A << 3, 4, -2, 1;\n  x = lu.solve(b);\n  cout << \"Residual: \" << (A0 * x - b).norm() << endl;\ncout << \"[modifyA]\" << endl;\n\ncout << \"[recompute]\" << endl;\n  A0 = A; // save A\n  lu.compute(A);\n  x = lu.solve(b);\n  cout << \"Residual: \" << (A0 * x - b).norm() << endl;\ncout << \"[recompute]\" << endl;\n\ncout << \"[recompute_bis0]\" << endl;\n  MatrixXd A1(2,2);\n  A1 << 5,-2,3,4;\n  lu.compute(A1);\n  cout << \"Here is the input matrix A1 after decomposition:\\n\" << A1 << endl;\ncout << \"[recompute_bis0]\" << endl;\n\ncout << \"[recompute_bis1]\" << endl;\n  x = lu.solve(b);\n  cout << \"Residual: \" << (A1 * x - b).norm() << endl;\ncout << \"[recompute_bis1]\" << endl;\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/TutorialLinAlgComputeTwice.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n   Matrix2f A, b;\n   LLT<Matrix2f> llt;\n   A << 2, -1, -1, 3;\n   b << 1, 2, 3, 1;\n   cout << \"Here is the matrix A:\\n\" << A << endl;\n   cout << \"Here is the right hand side b:\\n\" << b << endl;\n   cout << \"Computing LLT decomposition...\" << endl;\n   llt.compute(A);\n   cout << \"The solution is:\\n\" << llt.solve(b) << endl;\n   A(1,1)++;\n   cout << \"The matrix A is now:\\n\" << A << endl;\n   cout << \"Computing LLT decomposition...\" << endl;\n   llt.compute(A);\n   cout << \"The solution is now:\\n\" << llt.solve(b) << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/TutorialLinAlgExComputeSolveError.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n   MatrixXd A = MatrixXd::Random(100,100);\n   MatrixXd b = MatrixXd::Random(100,50);\n   MatrixXd x = A.fullPivLu().solve(b);\n   double relative_error = (A*x - b).norm() / b.norm(); // norm() is L2 norm\n   cout << \"The relative error is:\\n\" << relative_error << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/TutorialLinAlgExSolveColPivHouseholderQR.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n   Matrix3f A;\n   Vector3f b;\n   A << 1,2,3,  4,5,6,  7,8,10;\n   b << 3, 3, 4;\n   cout << \"Here is the matrix A:\\n\" << A << endl;\n   cout << \"Here is the vector b:\\n\" << b << endl;\n   Vector3f x = A.colPivHouseholderQr().solve(b);\n   cout << \"The solution is:\\n\" << x << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/TutorialLinAlgExSolveLDLT.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n   Matrix2f A, b;\n   A << 2, -1, -1, 3;\n   b << 1, 2, 3, 1;\n   cout << \"Here is the matrix A:\\n\" << A << endl;\n   cout << \"Here is the right hand side b:\\n\" << b << endl;\n   Matrix2f x = A.ldlt().solve(b);\n   cout << \"The solution is:\\n\" << x << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/TutorialLinAlgInverseDeterminant.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n   Matrix3f A;\n   A << 1, 2, 1,\n        2, 1, 0,\n        -1, 1, 2;\n   cout << \"Here is the matrix A:\\n\" << A << endl;\n   cout << \"The determinant of A is \" << A.determinant() << endl;\n   cout << \"The inverse of A is:\\n\" << A.inverse() << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/TutorialLinAlgRankRevealing.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n   Matrix3f A;\n   A << 1, 2, 5,\n        2, 1, 4,\n        3, 0, 3;\n   cout << \"Here is the matrix A:\\n\" << A << endl;\n   FullPivLU<Matrix3f> lu_decomp(A);\n   cout << \"The rank of A is \" << lu_decomp.rank() << endl;\n   cout << \"Here is a matrix whose columns form a basis of the null-space of A:\\n\"\n        << lu_decomp.kernel() << endl;\n   cout << \"Here is a matrix whose columns form a basis of the column-space of A:\\n\"\n        << lu_decomp.image(A) << endl; // yes, have to pass the original A\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/TutorialLinAlgSVDSolve.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n   MatrixXf A = MatrixXf::Random(3, 2);\n   cout << \"Here is the matrix A:\\n\" << A << endl;\n   VectorXf b = VectorXf::Random(3);\n   cout << \"Here is the right hand side b:\\n\" << b << endl;\n   cout << \"The least-squares solution is:\\n\"\n        << A.bdcSvd(ComputeThinU | ComputeThinV).solve(b) << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/TutorialLinAlgSelfAdjointEigenSolver.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n   Matrix2f A;\n   A << 1, 2, 2, 3;\n   cout << \"Here is the matrix A:\\n\" << A << endl;\n   SelfAdjointEigenSolver<Matrix2f> eigensolver(A);\n   if (eigensolver.info() != Success) abort();\n   cout << \"The eigenvalues of A are:\\n\" << eigensolver.eigenvalues() << endl;\n   cout << \"Here's a matrix whose columns are eigenvectors of A \\n\"\n        << \"corresponding to these eigenvalues:\\n\"\n        << eigensolver.eigenvectors() << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/TutorialLinAlgSetThreshold.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n   Matrix2d A;\n   A << 2, 1,\n        2, 0.9999999999;\n   FullPivLU<Matrix2d> lu(A);\n   cout << \"By default, the rank of A is found to be \" << lu.rank() << endl;\n   lu.setThreshold(1e-5);\n   cout << \"With threshold 1e-5, the rank of A is found to be \" << lu.rank() << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_ArrayClass_accessors.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  ArrayXXf  m(2,2);\n  \n  // assign some values coefficient by coefficient\n  m(0,0) = 1.0; m(0,1) = 2.0;\n  m(1,0) = 3.0; m(1,1) = m(0,1) + m(1,0);\n  \n  // print values to standard output\n  cout << m << endl << endl;\n \n  // using the comma-initializer is also allowed\n  m << 1.0,2.0,\n       3.0,4.0;\n     \n  // print values to standard output\n  cout << m << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_ArrayClass_addition.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  ArrayXXf a(3,3);\n  ArrayXXf b(3,3);\n  a << 1,2,3,\n       4,5,6,\n       7,8,9;\n  b << 1,2,3,\n       1,2,3,\n       1,2,3;\n       \n  // Adding two arrays\n  cout << \"a + b = \" << endl << a + b << endl << endl;\n\n  // Subtracting a scalar from an array\n  cout << \"a - 2 = \" << endl << a - 2 << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_ArrayClass_cwise_other.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  ArrayXf a = ArrayXf::Random(5);\n  a *= 2;\n  cout << \"a =\" << endl \n       << a << endl;\n  cout << \"a.abs() =\" << endl \n       << a.abs() << endl;\n  cout << \"a.abs().sqrt() =\" << endl \n       << a.abs().sqrt() << endl;\n  cout << \"a.min(a.abs().sqrt()) =\" << endl \n       << a.min(a.abs().sqrt()) << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_ArrayClass_interop.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  MatrixXf m(2,2);\n  MatrixXf n(2,2);\n  MatrixXf result(2,2);\n\n  m << 1,2,\n       3,4;\n  n << 5,6,\n       7,8;\n  \n  result = (m.array() + 4).matrix() * m;\n  cout << \"-- Combination 1: --\" << endl << result << endl << endl;\n  result = (m.array() * n.array()).matrix() * m;\n  cout << \"-- Combination 2: --\" << endl << result << endl << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_ArrayClass_interop_matrix.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  MatrixXf m(2,2);\n  MatrixXf n(2,2);\n  MatrixXf result(2,2);\n\n  m << 1,2,\n       3,4;\n  n << 5,6,\n       7,8;\n\n  result = m * n;\n  cout << \"-- Matrix m*n: --\" << endl << result << endl << endl;\n  result = m.array() * n.array();\n  cout << \"-- Array m*n: --\" << endl << result << endl << endl;\n  result = m.cwiseProduct(n);\n  cout << \"-- With cwiseProduct: --\" << endl << result << endl << endl;\n  result = m.array() + 4;\n  cout << \"-- Array m + 4: --\" << endl << result << endl << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_ArrayClass_mult.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  ArrayXXf a(2,2);\n  ArrayXXf b(2,2);\n  a << 1,2,\n       3,4;\n  b << 5,6,\n       7,8;\n  cout << \"a * b = \" << endl << a * b << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_BlockOperations_block_assignment.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n  Array22f m;\n  m << 1,2,\n       3,4;\n  Array44f a = Array44f::Constant(0.6);\n  cout << \"Here is the array a:\" << endl << a << endl << endl;\n  a.block<2,2>(1,1) = m;\n  cout << \"Here is now a with m copied into its central 2x2 block:\" << endl << a << endl << endl;\n  a.block(0,0,2,3) = a.block(2,1,2,3);\n  cout << \"Here is now a with bottom-right 2x3 block copied into top-left 2x3 block:\" << endl << a << endl << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_BlockOperations_colrow.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace std;\n\nint main()\n{\n  Eigen::MatrixXf m(3,3);\n  m << 1,2,3,\n       4,5,6,\n       7,8,9;\n  cout << \"Here is the matrix m:\" << endl << m << endl;\n  cout << \"2nd Row: \" << m.row(1) << endl;\n  m.col(2) += 3 * m.col(0);\n  cout << \"After adding 3 times the first column into the third column, the matrix m is:\\n\";\n  cout << m << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_BlockOperations_corner.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace std;\n\nint main()\n{\n  Eigen::Matrix4f m;\n  m << 1, 2, 3, 4,\n       5, 6, 7, 8,\n       9, 10,11,12,\n       13,14,15,16;\n  cout << \"m.leftCols(2) =\" << endl << m.leftCols(2) << endl << endl;\n  cout << \"m.bottomRows<2>() =\" << endl << m.bottomRows<2>() << endl << endl;\n  m.topLeftCorner(1,3) = m.bottomRightCorner(3,1).transpose();\n  cout << \"After assignment, m = \" << endl << m << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_BlockOperations_print_block.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace std;\n\nint main()\n{\n  Eigen::MatrixXf m(4,4);\n  m <<  1, 2, 3, 4,\n        5, 6, 7, 8,\n        9,10,11,12,\n       13,14,15,16;\n  cout << \"Block in the middle\" << endl;\n  cout << m.block<2,2>(1,1) << endl << endl;\n  for (int i = 1; i <= 3; ++i)\n  {\n    cout << \"Block of size \" << i << \"x\" << i << endl;\n    cout << m.block(0,0,i,i) << endl << endl;\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_BlockOperations_vector.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace std;\n\nint main()\n{\n  Eigen::ArrayXf v(6);\n  v << 1, 2, 3, 4, 5, 6;\n  cout << \"v.head(3) =\" << endl << v.head(3) << endl << endl;\n  cout << \"v.tail<3>() = \" << endl << v.tail<3>() << endl << endl;\n  v.segment(1,4) *= 2;\n  cout << \"after 'v.segment(1,4) *= 2', v =\" << endl << v << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_PartialLU_solve.cpp",
    "content": "#include <Eigen/Core>\n#include <Eigen/LU>\n#include <iostream>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n   Matrix3f A;\n   Vector3f b;\n   A << 1,2,3,  4,5,6,  7,8,10;\n   b << 3, 3, 4;\n   cout << \"Here is the matrix A:\" << endl << A << endl;\n   cout << \"Here is the vector b:\" << endl << b << endl;\n   Vector3f x = A.lu().solve(b);\n   cout << \"The solution is:\" << endl << x << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_1nn.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n  Eigen::MatrixXf m(2,4);\n  Eigen::VectorXf v(2);\n  \n  m << 1, 23, 6, 9,\n       3, 11, 7, 2;\n       \n  v << 2,\n       3;\n\n  MatrixXf::Index index;\n  // find nearest neighbour\n  (m.colwise() - v).colwise().squaredNorm().minCoeff(&index);\n\n  cout << \"Nearest neighbour is column \" << index << \":\" << endl;\n  cout << m.col(index) << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nint main()\n{\n  Eigen::MatrixXf mat(2,4);\n  Eigen::VectorXf v(2);\n  \n  mat << 1, 2, 6, 9,\n         3, 1, 7, 2;\n         \n  v << 0,\n       1;\n       \n  //add v to each column of m\n  mat.colwise() += v;\n  \n  std::cout << \"Broadcasting result: \" << std::endl;\n  std::cout << mat << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_broadcast_simple_rowwise.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nint main()\n{\n  Eigen::MatrixXf mat(2,4);\n  Eigen::VectorXf v(4);\n  \n  mat << 1, 2, 6, 9,\n         3, 1, 7, 2;\n         \n  v << 0,1,2,3;\n       \n  //add v to each row of m\n  mat.rowwise() += v.transpose();\n  \n  std::cout << \"Broadcasting result: \" << std::endl;\n  std::cout << mat << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_colwise.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nint main()\n{\n  Eigen::MatrixXf mat(2,4);\n  mat << 1, 2, 6, 9,\n         3, 1, 7, 2;\n  \n  std::cout << \"Column's maximum: \" << std::endl\n   << mat.colwise().maxCoeff() << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_maxnorm.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\nint main()\n{\n  MatrixXf mat(2,4);\n  mat << 1, 2, 6, 9,\n         3, 1, 7, 2;\n  \n  MatrixXf::Index   maxIndex;\n  float maxNorm = mat.colwise().sum().maxCoeff(&maxIndex);\n  \n  std::cout << \"Maximum sum at position \" << maxIndex << std::endl;\n\n  std::cout << \"The corresponding vector is: \" << std::endl;\n  std::cout << mat.col( maxIndex ) << std::endl;\n  std::cout << \"And its sum is is: \" << maxNorm << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_bool.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n  ArrayXXf a(2,2);\n  \n  a << 1,2,\n       3,4;\n\n  cout << \"(a > 0).all()   = \" << (a > 0).all() << endl;\n  cout << \"(a > 0).any()   = \" << (a > 0).any() << endl;\n  cout << \"(a > 0).count() = \" << (a > 0).count() << endl;\n  cout << endl;\n  cout << \"(a > 2).all()   = \" << (a > 2).all() << endl;\n  cout << \"(a > 2).any()   = \" << (a > 2).any() << endl;\n  cout << \"(a > 2).count() = \" << (a > 2).count() << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_norm.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n  VectorXf v(2);\n  MatrixXf m(2,2), n(2,2);\n  \n  v << -1,\n       2;\n  \n  m << 1,-2,\n       -3,4;\n\n  cout << \"v.squaredNorm() = \" << v.squaredNorm() << endl;\n  cout << \"v.norm() = \" << v.norm() << endl;\n  cout << \"v.lpNorm<1>() = \" << v.lpNorm<1>() << endl;\n  cout << \"v.lpNorm<Infinity>() = \" << v.lpNorm<Infinity>() << endl;\n\n  cout << endl;\n  cout << \"m.squaredNorm() = \" << m.squaredNorm() << endl;\n  cout << \"m.norm() = \" << m.norm() << endl;\n  cout << \"m.lpNorm<1>() = \" << m.lpNorm<1>() << endl;\n  cout << \"m.lpNorm<Infinity>() = \" << m.lpNorm<Infinity>() << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_reductions_operatornorm.cpp",
    "content": "#include <Eigen/Dense>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  MatrixXf m(2,2);\n  m << 1,-2,\n       -3,4;\n\n  cout << \"1-norm(m)     = \" << m.cwiseAbs().colwise().sum().maxCoeff()\n       << \" == \"             << m.colwise().lpNorm<1>().maxCoeff() << endl;\n\n  cout << \"infty-norm(m) = \" << m.cwiseAbs().rowwise().sum().maxCoeff()\n       << \" == \"             << m.rowwise().lpNorm<1>().maxCoeff() << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_rowwise.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nint main()\n{\n  Eigen::MatrixXf mat(2,4);\n  mat << 1, 2, 6, 9,\n         3, 1, 7, 2;\n  \n  std::cout << \"Row's maximum: \" << std::endl\n   << mat.rowwise().maxCoeff() << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_ReductionsVisitorsBroadcasting_visitors.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nusing namespace Eigen;\n\nint main()\n{\n  Eigen::MatrixXf m(2,2);\n  \n  m << 1, 2,\n       3, 4;\n\n  //get location of maximum\n  MatrixXf::Index maxRow, maxCol;\n  float max = m.maxCoeff(&maxRow, &maxCol);\n\n  //get location of minimum\n  MatrixXf::Index minRow, minCol;\n  float min = m.minCoeff(&minRow, &minCol);\n\n  cout << \"Max: \" << max <<  \", at: \" <<\n     maxRow << \",\" << maxCol << endl;\n  cout << \"Min: \" << min << \", at: \" <<\n     minRow << \",\" << minCol << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_simple_example_dynamic_size.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\n\nusing namespace Eigen;\n\nint main()\n{\n  for (int size=1; size<=4; ++size)\n  {\n    MatrixXi m(size,size+1);         // a (size)x(size+1)-matrix of int's\n    for (int j=0; j<m.cols(); ++j)   // loop over columns\n      for (int i=0; i<m.rows(); ++i) // loop over rows\n        m(i,j) = i+j*size;           // to access matrix coefficients,\n                                     // use operator()(int,int)\n    std::cout << m << \"\\n\\n\";\n  }\n\n  VectorXf v(4); // a vector of 4 float's\n  // to access vector coefficients, use either operator () or operator []\n  v[0] = 1; v[1] = 2; v(2) = 3; v(3) = 4;\n  std::cout << \"\\nv:\\n\" << v << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/Tutorial_simple_example_fixed_size.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\n\nusing namespace Eigen;\n\nint main()\n{\n  Matrix3f m3;\n  m3 << 1, 2, 3, 4, 5, 6, 7, 8, 9;\n  Matrix4f m4 = Matrix4f::Identity();\n  Vector4i v4(1, 2, 3, 4);\n\n  std::cout << \"m3\\n\" << m3 << \"\\nm4:\\n\"\n    << m4 << \"\\nv4:\\n\" << v4 << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/class_Block.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\nusing namespace Eigen;\nusing namespace std;\n\ntemplate<typename Derived>\nEigen::Block<Derived>\ntopLeftCorner(MatrixBase<Derived>& m, int rows, int cols)\n{\n  return Eigen::Block<Derived>(m.derived(), 0, 0, rows, cols);\n}\n\ntemplate<typename Derived>\nconst Eigen::Block<const Derived>\ntopLeftCorner(const MatrixBase<Derived>& m, int rows, int cols)\n{\n  return Eigen::Block<const Derived>(m.derived(), 0, 0, rows, cols);\n}\n\nint main(int, char**)\n{\n  Matrix4d m = Matrix4d::Identity();\n  cout << topLeftCorner(4*m, 2, 3) << endl; // calls the const version\n  topLeftCorner(m, 2, 3) *= 5;              // calls the non-const version\n  cout << \"Now the matrix m is:\" << endl << m << endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/class_CwiseBinaryOp.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\nusing namespace Eigen;\nusing namespace std;\n\n// define a custom template binary functor\ntemplate<typename Scalar> struct MakeComplexOp {\n  EIGEN_EMPTY_STRUCT_CTOR(MakeComplexOp)\n  typedef complex<Scalar> result_type;\n  complex<Scalar> operator()(const Scalar& a, const Scalar& b) const { return complex<Scalar>(a,b); }\n};\n\nint main(int, char**)\n{\n  Matrix4d m1 = Matrix4d::Random(), m2 = Matrix4d::Random();\n  cout << m1.binaryExpr(m2, MakeComplexOp<double>()) << endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/class_CwiseUnaryOp.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\nusing namespace Eigen;\nusing namespace std;\n\n// define a custom template unary functor\ntemplate<typename Scalar>\nstruct CwiseClampOp {\n  CwiseClampOp(const Scalar& inf, const Scalar& sup) : m_inf(inf), m_sup(sup) {}\n  const Scalar operator()(const Scalar& x) const { return x<m_inf ? m_inf : (x>m_sup ? m_sup : x); }\n  Scalar m_inf, m_sup;\n};\n\nint main(int, char**)\n{\n  Matrix4d m1 = Matrix4d::Random();\n  cout << m1 << endl << \"becomes: \" << endl << m1.unaryExpr(CwiseClampOp<double>(-0.5,0.5)) << endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/class_CwiseUnaryOp_ptrfun.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\nusing namespace Eigen;\nusing namespace std;\n\n// define function to be applied coefficient-wise\ndouble ramp(double x)\n{\n  if (x > 0)\n    return x;\n  else \n    return 0;\n}\n\nint main(int, char**)\n{\n  Matrix4d m1 = Matrix4d::Random();\n  cout << m1 << endl << \"becomes: \" << endl << m1.unaryExpr(ptr_fun(ramp)) << endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/class_FixedBlock.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\nusing namespace Eigen;\nusing namespace std;\n\ntemplate<typename Derived>\nEigen::Block<Derived, 2, 2>\ntopLeft2x2Corner(MatrixBase<Derived>& m)\n{\n  return Eigen::Block<Derived, 2, 2>(m.derived(), 0, 0);\n}\n\ntemplate<typename Derived>\nconst Eigen::Block<const Derived, 2, 2>\ntopLeft2x2Corner(const MatrixBase<Derived>& m)\n{\n  return Eigen::Block<const Derived, 2, 2>(m.derived(), 0, 0);\n}\n\nint main(int, char**)\n{\n  Matrix3d m = Matrix3d::Identity();\n  cout << topLeft2x2Corner(4*m) << endl; // calls the const version\n  topLeft2x2Corner(m) *= 2;              // calls the non-const version\n  cout << \"Now the matrix m is:\" << endl << m << endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/class_FixedReshaped.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\nusing namespace Eigen;\nusing namespace std;\n\ntemplate<typename Derived>\nEigen::Reshaped<Derived, 4, 2>\nreshape_helper(MatrixBase<Derived>& m)\n{\n  return Eigen::Reshaped<Derived, 4, 2>(m.derived());\n}\n\nint main(int, char**)\n{\n  MatrixXd m(2, 4);\n  m << 1, 2, 3, 4,\n       5, 6, 7, 8;\n  MatrixXd n = reshape_helper(m);\n  cout << \"matrix m is:\" << endl << m << endl;\n  cout << \"matrix n is:\" << endl << n << endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/class_FixedVectorBlock.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\nusing namespace Eigen;\nusing namespace std;\n\ntemplate<typename Derived>\nEigen::VectorBlock<Derived, 2>\nfirstTwo(MatrixBase<Derived>& v)\n{\n  return Eigen::VectorBlock<Derived, 2>(v.derived(), 0);\n}\n\ntemplate<typename Derived>\nconst Eigen::VectorBlock<const Derived, 2>\nfirstTwo(const MatrixBase<Derived>& v)\n{\n  return Eigen::VectorBlock<const Derived, 2>(v.derived(), 0);\n}\n\nint main(int, char**)\n{\n  Matrix<int,1,6> v; v << 1,2,3,4,5,6;\n  cout << firstTwo(4*v) << endl; // calls the const version\n  firstTwo(v) *= 2;              // calls the non-const version\n  cout << \"Now the vector v is:\" << endl << v << endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/class_Reshaped.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\nusing namespace std;\nusing namespace Eigen;\n\ntemplate<typename Derived>\nconst Reshaped<const Derived>\nreshape_helper(const MatrixBase<Derived>& m, int rows, int cols)\n{\n  return Reshaped<const Derived>(m.derived(), rows, cols);\n}\n\nint main(int, char**)\n{\n  MatrixXd m(3, 4);\n  m << 1, 4, 7, 10,\n       2, 5, 8, 11,\n       3, 6, 9, 12;\n  cout << m << endl;\n  Ref<const MatrixXd> n = reshape_helper(m, 2, 6);\n  cout << \"Matrix m is:\" << endl << m << endl;\n  cout << \"Matrix n is:\" << endl << n << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/class_VectorBlock.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\nusing namespace Eigen;\nusing namespace std;\n\ntemplate<typename Derived>\nEigen::VectorBlock<Derived>\nsegmentFromRange(MatrixBase<Derived>& v, int start, int end)\n{\n  return Eigen::VectorBlock<Derived>(v.derived(), start, end-start);\n}\n\ntemplate<typename Derived>\nconst Eigen::VectorBlock<const Derived>\nsegmentFromRange(const MatrixBase<Derived>& v, int start, int end)\n{\n  return Eigen::VectorBlock<const Derived>(v.derived(), start, end-start);\n}\n\nint main(int, char**)\n{\n  Matrix<int,1,6> v; v << 1,2,3,4,5,6;\n  cout << segmentFromRange(2*v, 2, 4) << endl; // calls the const version\n  segmentFromRange(v, 1, 3) *= 5;              // calls the non-const version\n  cout << \"Now the vector v is:\" << endl << v << endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/function_taking_eigenbase.cpp",
    "content": "#include <iostream>\n#include <Eigen/Core>\nusing namespace Eigen;\n\ntemplate <typename Derived>\nvoid print_size(const EigenBase<Derived>& b)\n{\n  std::cout << \"size (rows, cols): \" << b.size() << \" (\" << b.rows()\n            << \", \" << b.cols() << \")\" << std::endl;\n}\n\nint main()\n{\n    Vector3f v;\n    print_size(v);\n    // v.asDiagonal() returns a 3x3 diagonal matrix pseudo-expression\n    print_size(v.asDiagonal());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/function_taking_ref.cpp",
    "content": "#include <iostream>\n#include <Eigen/SVD>\nusing namespace Eigen;\nusing namespace std;\n\nfloat inv_cond(const Ref<const MatrixXf>& a)\n{\n  const VectorXf sing_vals = a.jacobiSvd().singularValues();\n  return sing_vals(sing_vals.size()-1) / sing_vals(0);\n}\n\nint main()\n{\n  Matrix4f m = Matrix4f::Random();\n  cout << \"matrix m:\" << endl << m << endl << endl;\n  cout << \"inv_cond(m):          \" << inv_cond(m)                      << endl;\n  cout << \"inv_cond(m(1:3,1:3)): \" << inv_cond(m.topLeftCorner(3,3))   << endl;\n  cout << \"inv_cond(m+I):        \" << inv_cond(m+Matrix4f::Identity()) << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/make_circulant.cpp",
    "content": "/*\nThis program is presented in several fragments in the doc page.\nEvery fragment is in its own file; this file simply combines them.\n*/\n\n#include \"make_circulant.cpp.preamble\"\n#include \"make_circulant.cpp.traits\"\n#include \"make_circulant.cpp.expression\"\n#include \"make_circulant.cpp.evaluator\"\n#include \"make_circulant.cpp.entry\"\n#include \"make_circulant.cpp.main\"\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/make_circulant.cpp.entry",
    "content": "template <class ArgType>\nCirculant<ArgType> makeCirculant(const Eigen::MatrixBase<ArgType>& arg)\n{\n  return Circulant<ArgType>(arg.derived());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/make_circulant.cpp.evaluator",
    "content": "namespace Eigen {\n  namespace internal {\n    template<typename ArgType>\n    struct evaluator<Circulant<ArgType> >\n      : evaluator_base<Circulant<ArgType> >\n    {\n      typedef Circulant<ArgType> XprType;\n      typedef typename nested_eval<ArgType, XprType::ColsAtCompileTime>::type ArgTypeNested;\n      typedef typename remove_all<ArgTypeNested>::type ArgTypeNestedCleaned;\n      typedef typename XprType::CoeffReturnType CoeffReturnType;\n\n      enum { \n        CoeffReadCost = evaluator<ArgTypeNestedCleaned>::CoeffReadCost,\n        Flags = Eigen::ColMajor \n      };\n      \n      evaluator(const XprType& xpr)\n        : m_argImpl(xpr.m_arg), m_rows(xpr.rows())\n      { }\n\n      CoeffReturnType coeff(Index row, Index col) const\n      {\n        Index index = row - col;\n        if (index < 0) index += m_rows;\n        return m_argImpl.coeff(index);\n      }\n\n      evaluator<ArgTypeNestedCleaned> m_argImpl;\n      const Index m_rows;\n    };\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/make_circulant.cpp.expression",
    "content": "template <class ArgType>\nclass Circulant : public Eigen::MatrixBase<Circulant<ArgType> >\n{\npublic:\n  Circulant(const ArgType& arg)\n    : m_arg(arg)\n  { \n    EIGEN_STATIC_ASSERT(ArgType::ColsAtCompileTime == 1,\n                        YOU_TRIED_CALLING_A_VECTOR_METHOD_ON_A_MATRIX);\n  }\n\n  typedef typename Eigen::internal::ref_selector<Circulant>::type Nested; \n\n  typedef Eigen::Index Index;\n  Index rows() const { return m_arg.rows(); }\n  Index cols() const { return m_arg.rows(); }\n\n  typedef typename Eigen::internal::ref_selector<ArgType>::type ArgTypeNested;\n  ArgTypeNested m_arg;\n};\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/make_circulant.cpp.main",
    "content": "int main()\n{\n  Eigen::VectorXd vec(4);\n  vec << 1, 2, 4, 8;\n  Eigen::MatrixXd mat;\n  mat = makeCirculant(vec);\n  std::cout << mat << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/make_circulant.cpp.preamble",
    "content": "#include <Eigen/Core>\n#include <iostream>\n\ntemplate <class ArgType> class Circulant;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/make_circulant.cpp.traits",
    "content": "namespace Eigen {\n  namespace internal {\n    template <class ArgType>\n    struct traits<Circulant<ArgType> >\n    {\n      typedef Eigen::Dense StorageKind;\n      typedef Eigen::MatrixXpr XprKind;\n      typedef typename ArgType::StorageIndex StorageIndex;\n      typedef typename ArgType::Scalar Scalar;\n      enum { \n        Flags = Eigen::ColMajor,\n        RowsAtCompileTime = ArgType::RowsAtCompileTime,\n        ColsAtCompileTime = ArgType::RowsAtCompileTime,\n        MaxRowsAtCompileTime = ArgType::MaxRowsAtCompileTime,\n        MaxColsAtCompileTime = ArgType::MaxRowsAtCompileTime\n      };\n    };\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/make_circulant2.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\n\nusing namespace Eigen;\n\n// [circulant_func]\ntemplate<class ArgType>\nclass circulant_functor {\n  const ArgType &m_vec;\npublic:\n  circulant_functor(const ArgType& arg) : m_vec(arg) {}\n\n  const typename ArgType::Scalar& operator() (Index row, Index col) const {\n    Index index = row - col;\n    if (index < 0) index += m_vec.size();\n    return m_vec(index);\n  }\n};\n// [circulant_func]\n\n// [square]\ntemplate<class ArgType>\nstruct circulant_helper {\n  typedef Matrix<typename ArgType::Scalar,\n                 ArgType::SizeAtCompileTime,\n                 ArgType::SizeAtCompileTime,\n                 ColMajor,\n                 ArgType::MaxSizeAtCompileTime,\n                 ArgType::MaxSizeAtCompileTime> MatrixType;\n};\n// [square]\n\n// [makeCirculant]\ntemplate <class ArgType>\nCwiseNullaryOp<circulant_functor<ArgType>, typename circulant_helper<ArgType>::MatrixType>\nmakeCirculant(const Eigen::MatrixBase<ArgType>& arg)\n{\n  typedef typename circulant_helper<ArgType>::MatrixType MatrixType;\n  return MatrixType::NullaryExpr(arg.size(), arg.size(), circulant_functor<ArgType>(arg.derived()));\n}\n// [makeCirculant]\n\n// [main]\nint main()\n{\n  Eigen::VectorXd vec(4);\n  vec << 1, 2, 4, 8;\n  Eigen::MatrixXd mat;\n  mat = makeCirculant(vec);\n  std::cout << mat << std::endl;\n}\n// [main]\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/matrixfree_cg.cpp",
    "content": "#include <iostream>\n#include <Eigen/Core>\n#include <Eigen/Dense>\n#include <Eigen/IterativeLinearSolvers>\n#include <unsupported/Eigen/IterativeSolvers>\n\nclass MatrixReplacement;\nusing Eigen::SparseMatrix;\n\nnamespace Eigen {\nnamespace internal {\n  // MatrixReplacement looks-like a SparseMatrix, so let's inherits its traits:\n  template<>\n  struct traits<MatrixReplacement> :  public Eigen::internal::traits<Eigen::SparseMatrix<double> >\n  {};\n}\n}\n\n// Example of a matrix-free wrapper from a user type to Eigen's compatible type\n// For the sake of simplicity, this example simply wrap a Eigen::SparseMatrix.\nclass MatrixReplacement : public Eigen::EigenBase<MatrixReplacement> {\npublic:\n  // Required typedefs, constants, and method:\n  typedef double Scalar;\n  typedef double RealScalar;\n  typedef int StorageIndex;\n  enum {\n    ColsAtCompileTime = Eigen::Dynamic,\n    MaxColsAtCompileTime = Eigen::Dynamic,\n    IsRowMajor = false\n  };\n\n  Index rows() const { return mp_mat->rows(); }\n  Index cols() const { return mp_mat->cols(); }\n\n  template<typename Rhs>\n  Eigen::Product<MatrixReplacement,Rhs,Eigen::AliasFreeProduct> operator*(const Eigen::MatrixBase<Rhs>& x) const {\n    return Eigen::Product<MatrixReplacement,Rhs,Eigen::AliasFreeProduct>(*this, x.derived());\n  }\n\n  // Custom API:\n  MatrixReplacement() : mp_mat(0) {}\n\n  void attachMyMatrix(const SparseMatrix<double> &mat) {\n    mp_mat = &mat;\n  }\n  const SparseMatrix<double> my_matrix() const { return *mp_mat; }\n\nprivate:\n  const SparseMatrix<double> *mp_mat;\n};\n\n\n// Implementation of MatrixReplacement * Eigen::DenseVector though a specialization of internal::generic_product_impl:\nnamespace Eigen {\nnamespace internal {\n\n  template<typename Rhs>\n  struct generic_product_impl<MatrixReplacement, Rhs, SparseShape, DenseShape, GemvProduct> // GEMV stands for matrix-vector\n  : generic_product_impl_base<MatrixReplacement,Rhs,generic_product_impl<MatrixReplacement,Rhs> >\n  {\n    typedef typename Product<MatrixReplacement,Rhs>::Scalar Scalar;\n\n    template<typename Dest>\n    static void scaleAndAddTo(Dest& dst, const MatrixReplacement& lhs, const Rhs& rhs, const Scalar& alpha)\n    {\n      // This method should implement \"dst += alpha * lhs * rhs\" inplace,\n      // however, for iterative solvers, alpha is always equal to 1, so let's not bother about it.\n      assert(alpha==Scalar(1) && \"scaling is not implemented\");\n      EIGEN_ONLY_USED_FOR_DEBUG(alpha);\n\n      // Here we could simply call dst.noalias() += lhs.my_matrix() * rhs,\n      // but let's do something fancier (and less efficient):\n      for(Index i=0; i<lhs.cols(); ++i)\n        dst += rhs(i) * lhs.my_matrix().col(i);\n    }\n  };\n\n}\n}\n\nint main()\n{\n  int n = 10;\n  Eigen::SparseMatrix<double> S = Eigen::MatrixXd::Random(n,n).sparseView(0.5,1);\n  S = S.transpose()*S;\n\n  MatrixReplacement A;\n  A.attachMyMatrix(S);\n\n  Eigen::VectorXd b(n), x;\n  b.setRandom();\n\n  // Solve Ax = b using various iterative solver with matrix-free version:\n  {\n    Eigen::ConjugateGradient<MatrixReplacement, Eigen::Lower|Eigen::Upper, Eigen::IdentityPreconditioner> cg;\n    cg.compute(A);\n    x = cg.solve(b);\n    std::cout << \"CG:       #iterations: \" << cg.iterations() << \", estimated error: \" << cg.error() << std::endl;\n  }\n\n  {\n    Eigen::BiCGSTAB<MatrixReplacement, Eigen::IdentityPreconditioner> bicg;\n    bicg.compute(A);\n    x = bicg.solve(b);\n    std::cout << \"BiCGSTAB: #iterations: \" << bicg.iterations() << \", estimated error: \" << bicg.error() << std::endl;\n  }\n\n  {\n    Eigen::GMRES<MatrixReplacement, Eigen::IdentityPreconditioner> gmres;\n    gmres.compute(A);\n    x = gmres.solve(b);\n    std::cout << \"GMRES:    #iterations: \" << gmres.iterations() << \", estimated error: \" << gmres.error() << std::endl;\n  }\n\n  {\n    Eigen::DGMRES<MatrixReplacement, Eigen::IdentityPreconditioner> gmres;\n    gmres.compute(A);\n    x = gmres.solve(b);\n    std::cout << \"DGMRES:   #iterations: \" << gmres.iterations() << \", estimated error: \" << gmres.error() << std::endl;\n  }\n\n  {\n    Eigen::MINRES<MatrixReplacement, Eigen::Lower|Eigen::Upper, Eigen::IdentityPreconditioner> minres;\n    minres.compute(A);\n    x = minres.solve(b);\n    std::cout << \"MINRES:   #iterations: \" << minres.iterations() << \", estimated error: \" << minres.error() << std::endl;\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/nullary_indexing.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\n\nusing namespace Eigen;\n\n// [functor]\ntemplate<class ArgType, class RowIndexType, class ColIndexType>\nclass indexing_functor {\n  const ArgType &m_arg;\n  const RowIndexType &m_rowIndices;\n  const ColIndexType &m_colIndices;\npublic:\n  typedef Matrix<typename ArgType::Scalar,\n                 RowIndexType::SizeAtCompileTime,\n                 ColIndexType::SizeAtCompileTime,\n                 ArgType::Flags&RowMajorBit?RowMajor:ColMajor,\n                 RowIndexType::MaxSizeAtCompileTime,\n                 ColIndexType::MaxSizeAtCompileTime> MatrixType;\n\n  indexing_functor(const ArgType& arg, const RowIndexType& row_indices, const ColIndexType& col_indices)\n    : m_arg(arg), m_rowIndices(row_indices), m_colIndices(col_indices)\n  {}\n\n  const typename ArgType::Scalar& operator() (Index row, Index col) const {\n    return m_arg(m_rowIndices[row], m_colIndices[col]);\n  }\n};\n// [functor]\n\n// [function]\ntemplate <class ArgType, class RowIndexType, class ColIndexType>\nCwiseNullaryOp<indexing_functor<ArgType,RowIndexType,ColIndexType>, typename indexing_functor<ArgType,RowIndexType,ColIndexType>::MatrixType>\nmat_indexing(const Eigen::MatrixBase<ArgType>& arg, const RowIndexType& row_indices, const ColIndexType& col_indices)\n{\n  typedef indexing_functor<ArgType,RowIndexType,ColIndexType> Func;\n  typedef typename Func::MatrixType MatrixType;\n  return MatrixType::NullaryExpr(row_indices.size(), col_indices.size(), Func(arg.derived(), row_indices, col_indices));\n}\n// [function]\n\n\nint main()\n{\n  std::cout << \"[main1]\\n\";\n  Eigen::MatrixXi A = Eigen::MatrixXi::Random(4,4);\n  Array3i ri(1,2,1);\n  ArrayXi ci(6); ci << 3,2,1,0,0,2;\n  Eigen::MatrixXi B = mat_indexing(A, ri, ci);\n  std::cout << \"A =\" << std::endl;\n  std::cout << A << std::endl << std::endl;\n  std::cout << \"A([\" << ri.transpose() << \"], [\" << ci.transpose() << \"]) =\" << std::endl;\n  std::cout << B << std::endl;\n  std::cout << \"[main1]\\n\";\n\n  std::cout << \"[main2]\\n\";\n  B =  mat_indexing(A, ri+1, ci);\n  std::cout << \"A(ri+1,ci) =\" << std::endl;\n  std::cout << B << std::endl << std::endl;\n#if EIGEN_COMP_CXXVER >= 11\n  B =  mat_indexing(A, ArrayXi::LinSpaced(13,0,12).unaryExpr([](int x){return x%4;}), ArrayXi::LinSpaced(4,0,3));\n  std::cout << \"A(ArrayXi::LinSpaced(13,0,12).unaryExpr([](int x){return x%4;}), ArrayXi::LinSpaced(4,0,3)) =\" << std::endl;\n  std::cout << B << std::endl << std::endl;\n#endif\n  std::cout << \"[main2]\\n\";\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/tut_arithmetic_add_sub.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace Eigen;\n\nint main()\n{\n  Matrix2d a;\n  a << 1, 2,\n       3, 4;\n  MatrixXd b(2,2);\n  b << 2, 3,\n       1, 4;\n  std::cout << \"a + b =\\n\" << a + b << std::endl;\n  std::cout << \"a - b =\\n\" << a - b << std::endl;\n  std::cout << \"Doing a += b;\" << std::endl;\n  a += b;\n  std::cout << \"Now a =\\n\" << a << std::endl;\n  Vector3d v(1,2,3);\n  Vector3d w(1,0,0);\n  std::cout << \"-v + w - v =\\n\" << -v + w - v << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/tut_arithmetic_dot_cross.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace Eigen;\nusing namespace std;\nint main()\n{\n  Vector3d v(1,2,3);\n  Vector3d w(0,1,2);\n\n  cout << \"Dot product: \" << v.dot(w) << endl;\n  double dp = v.adjoint()*w; // automatic conversion of the inner product to a scalar\n  cout << \"Dot product via a matrix product: \" << dp << endl;\n  cout << \"Cross product:\\n\" << v.cross(w) << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/tut_arithmetic_matrix_mul.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace Eigen;\nint main()\n{\n  Matrix2d mat;\n  mat << 1, 2,\n         3, 4;\n  Vector2d u(-1,1), v(2,0);\n  std::cout << \"Here is mat*mat:\\n\" << mat*mat << std::endl;\n  std::cout << \"Here is mat*u:\\n\" << mat*u << std::endl;\n  std::cout << \"Here is u^T*mat:\\n\" << u.transpose()*mat << std::endl;\n  std::cout << \"Here is u^T*v:\\n\" << u.transpose()*v << std::endl;\n  std::cout << \"Here is u*v^T:\\n\" << u*v.transpose() << std::endl;\n  std::cout << \"Let's multiply mat by itself\" << std::endl;\n  mat = mat*mat;\n  std::cout << \"Now mat is mat:\\n\" << mat << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/tut_arithmetic_redux_basic.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace std;\nint main()\n{\n  Eigen::Matrix2d mat;\n  mat << 1, 2,\n         3, 4;\n  cout << \"Here is mat.sum():       \" << mat.sum()       << endl;\n  cout << \"Here is mat.prod():      \" << mat.prod()      << endl;\n  cout << \"Here is mat.mean():      \" << mat.mean()      << endl;\n  cout << \"Here is mat.minCoeff():  \" << mat.minCoeff()  << endl;\n  cout << \"Here is mat.maxCoeff():  \" << mat.maxCoeff()  << endl;\n  cout << \"Here is mat.trace():     \" << mat.trace()     << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/tut_arithmetic_scalar_mul_div.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace Eigen;\n\nint main()\n{\n  Matrix2d a;\n  a << 1, 2,\n       3, 4;\n  Vector3d v(1,2,3);\n  std::cout << \"a * 2.5 =\\n\" << a * 2.5 << std::endl;\n  std::cout << \"0.1 * v =\\n\" << 0.1 * v << std::endl;\n  std::cout << \"Doing v *= 2;\" << std::endl;\n  v *= 2;\n  std::cout << \"Now v =\\n\" << v << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/tut_matrix_coefficient_accessors.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace Eigen;\n\nint main()\n{\n  MatrixXd m(2,2);\n  m(0,0) = 3;\n  m(1,0) = 2.5;\n  m(0,1) = -1;\n  m(1,1) = m(1,0) + m(0,1);\n  std::cout << \"Here is the matrix m:\\n\" << m << std::endl;\n  VectorXd v(2);\n  v(0) = 4;\n  v(1) = v(0) - 1;\n  std::cout << \"Here is the vector v:\\n\" << v << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/tut_matrix_resize.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace Eigen;\n\nint main()\n{\n  MatrixXd m(2,5);\n  m.resize(4,3);\n  std::cout << \"The matrix m is of size \"\n            << m.rows() << \"x\" << m.cols() << std::endl;\n  std::cout << \"It has \" << m.size() << \" coefficients\" << std::endl;\n  VectorXd v(2);\n  v.resize(5);\n  std::cout << \"The vector v is of size \" << v.size() << std::endl;\n  std::cout << \"As a matrix, v is of size \"\n            << v.rows() << \"x\" << v.cols() << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/examples/tut_matrix_resize_fixed_size.cpp",
    "content": "#include <iostream>\n#include <Eigen/Dense>\n\nusing namespace Eigen;\n\nint main()\n{\n  Matrix4d m;\n  m.resize(4,4); // no operation\n  std::cout << \"The matrix m is of size \"\n            << m.rows() << \"x\" << m.cols() << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/.krazy",
    "content": "EXCLUDE copyright\nEXCLUDE license\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/AngleAxis_mimic_euler.cpp",
    "content": "Matrix3f m;\nm = AngleAxisf(0.25*M_PI, Vector3f::UnitX())\n  * AngleAxisf(0.5*M_PI,  Vector3f::UnitY())\n  * AngleAxisf(0.33*M_PI, Vector3f::UnitZ());\ncout << m << endl << \"is unitary: \" << m.isUnitary() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Array_initializer_list_23_cxx11.cpp",
    "content": "ArrayXXi a {\n  {1, 2, 3},\n  {3, 4, 5}\n};\ncout << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Array_initializer_list_vector_cxx11.cpp",
    "content": "Array<int, Dynamic, 1> v {{1, 2, 3, 4, 5}};\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Array_variadic_ctor_cxx11.cpp",
    "content": "Array<int, 1, 6> a(1, 2, 3, 4, 5, 6);\nArray<int, 3, 1> b {1, 2, 3};\ncout << a << \"\\n\\n\" << b << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/BiCGSTAB_simple.cpp",
    "content": "  int n = 10000;\n  VectorXd x(n), b(n);\n  SparseMatrix<double> A(n,n);\n  /* ... fill A and b ... */ \n  BiCGSTAB<SparseMatrix<double> > solver;\n  solver.compute(A);\n  x = solver.solve(b);\n  std::cout << \"#iterations:     \" << solver.iterations() << std::endl;\n  std::cout << \"estimated error: \" << solver.error()      << std::endl;\n  /* ... update b ... */\n  x = solver.solve(b); // solve again\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/BiCGSTAB_step_by_step.cpp",
    "content": "  int n = 10000;\n  VectorXd x(n), b(n);\n  SparseMatrix<double> A(n,n);\n  /* ... fill A and b ... */ \n  BiCGSTAB<SparseMatrix<double> > solver(A);\n  // start from a random solution\n  x = VectorXd::Random(n);\n  solver.setMaxIterations(1);\n  int i = 0;\n  do {\n    x = solver.solveWithGuess(b,x);\n    std::cout << i << \" : \" << solver.error() << std::endl;\n    ++i;\n  } while (solver.info()!=Success && i<100);\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/CMakeLists.txt",
    "content": "file(GLOB snippets_SRCS \"*.cpp\")\n\nadd_custom_target(all_snippets)\n\nforeach(snippet_src ${snippets_SRCS})\n  get_filename_component(snippet ${snippet_src} NAME_WE)\n  set(compile_snippet_target compile_${snippet})\n  set(compile_snippet_src ${compile_snippet_target}.cpp)\n  if((NOT ${snippet_src} MATCHES \"cxx11\") OR EIGEN_COMPILER_SUPPORT_CPP11)\n    file(READ ${snippet_src} snippet_source_code)\n    configure_file(${CMAKE_CURRENT_SOURCE_DIR}/compile_snippet.cpp.in\n                  ${CMAKE_CURRENT_BINARY_DIR}/${compile_snippet_src})\n    add_executable(${compile_snippet_target}\n                  ${CMAKE_CURRENT_BINARY_DIR}/${compile_snippet_src})\n    if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO)\n      target_link_libraries(${compile_snippet_target} ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO})\n    endif()\n    if(${snippet_src} MATCHES \"cxx11\")\n      set_target_properties(${compile_snippet_target} PROPERTIES COMPILE_FLAGS \"-std=c++11\")\n    endif()\n    if(${snippet_src} MATCHES \"deprecated\")\n      set_target_properties(${compile_snippet_target} PROPERTIES COMPILE_FLAGS \"-DEIGEN_NO_DEPRECATED_WARNING\")\n    endif()\n    add_custom_command(\n      TARGET ${compile_snippet_target}\n      POST_BUILD\n      COMMAND ${compile_snippet_target}\n      ARGS >${CMAKE_CURRENT_BINARY_DIR}/${snippet}.out\n    )\n    add_dependencies(all_snippets ${compile_snippet_target})\n    set_source_files_properties(${CMAKE_CURRENT_BINARY_DIR}/${compile_snippet_src}\n                                PROPERTIES OBJECT_DEPENDS ${snippet_src})\n  else()\n    message(\"skip snippet ${snippet_src} because compiler does not support C++11\")\n  endif()\nendforeach()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/ColPivHouseholderQR_solve.cpp",
    "content": "Matrix3f m = Matrix3f::Random();\nMatrix3f y = Matrix3f::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the matrix y:\" << endl << y << endl;\nMatrix3f x;\nx = m.colPivHouseholderQr().solve(y);\nassert(y.isApprox(m*x));\ncout << \"Here is a solution x to the equation mx=y:\" << endl << x << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/ComplexEigenSolver_compute.cpp",
    "content": "MatrixXcf A = MatrixXcf::Random(4,4);\ncout << \"Here is a random 4x4 matrix, A:\" << endl << A << endl << endl;\n\nComplexEigenSolver<MatrixXcf> ces;\nces.compute(A);\ncout << \"The eigenvalues of A are:\" << endl << ces.eigenvalues() << endl;\ncout << \"The matrix of eigenvectors, V, is:\" << endl << ces.eigenvectors() << endl << endl;\n\ncomplex<float> lambda = ces.eigenvalues()[0];\ncout << \"Consider the first eigenvalue, lambda = \" << lambda << endl;\nVectorXcf v = ces.eigenvectors().col(0);\ncout << \"If v is the corresponding eigenvector, then lambda * v = \" << endl << lambda * v << endl;\ncout << \"... and A * v = \" << endl << A * v << endl << endl;\n\ncout << \"Finally, V * D * V^(-1) = \" << endl\n     << ces.eigenvectors() * ces.eigenvalues().asDiagonal() * ces.eigenvectors().inverse() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/ComplexEigenSolver_eigenvalues.cpp",
    "content": "MatrixXcf ones = MatrixXcf::Ones(3,3);\nComplexEigenSolver<MatrixXcf> ces(ones, /* computeEigenvectors = */ false);\ncout << \"The eigenvalues of the 3x3 matrix of ones are:\" \n     << endl << ces.eigenvalues() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/ComplexEigenSolver_eigenvectors.cpp",
    "content": "MatrixXcf ones = MatrixXcf::Ones(3,3);\nComplexEigenSolver<MatrixXcf> ces(ones);\ncout << \"The first eigenvector of the 3x3 matrix of ones is:\" \n     << endl << ces.eigenvectors().col(1) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/ComplexSchur_compute.cpp",
    "content": "MatrixXcf A = MatrixXcf::Random(4,4);\nComplexSchur<MatrixXcf> schur(4);\nschur.compute(A);\ncout << \"The matrix T in the decomposition of A is:\" << endl << schur.matrixT() << endl;\nschur.compute(A.inverse());\ncout << \"The matrix T in the decomposition of A^(-1) is:\" << endl << schur.matrixT() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/ComplexSchur_matrixT.cpp",
    "content": "MatrixXcf A = MatrixXcf::Random(4,4);\ncout << \"Here is a random 4x4 matrix, A:\" << endl << A << endl << endl;\nComplexSchur<MatrixXcf> schurOfA(A, false); // false means do not compute U\ncout << \"The triangular matrix T is:\" << endl << schurOfA.matrixT() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/ComplexSchur_matrixU.cpp",
    "content": "MatrixXcf A = MatrixXcf::Random(4,4);\ncout << \"Here is a random 4x4 matrix, A:\" << endl << A << endl << endl;\nComplexSchur<MatrixXcf> schurOfA(A);\ncout << \"The unitary matrix U is:\" << endl << schurOfA.matrixU() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_abs.cpp",
    "content": "Array3d v(1,-2,-3);\ncout << v.abs() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_abs2.cpp",
    "content": "Array3d v(1,-2,-3);\ncout << v.abs2() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_acos.cpp",
    "content": "Array3d v(0, sqrt(2.)/2, 1);\ncout << v.acos() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_arg.cpp",
    "content": "ArrayXcf v = ArrayXcf::Random(3);\ncout << v << endl << endl;\ncout << arg(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_array_power_array.cpp",
    "content": "Array<double,1,3> x(8,25,3),\n                  e(1./3.,0.5,2.);\ncout << \"[\" << x << \"]^[\" << e << \"] = \" << x.pow(e) << endl; // using ArrayBase::pow\ncout << \"[\" << x << \"]^[\" << e << \"] = \" << pow(x,e) << endl; // using Eigen::pow\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_asin.cpp",
    "content": "Array3d v(0, sqrt(2.)/2, 1);\ncout << v.asin() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_atan.cpp",
    "content": "ArrayXd v = ArrayXd::LinSpaced(5,0,1);\ncout << v.atan() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_boolean_and.cpp",
    "content": "Array3d v(-1,2,1), w(-3,2,3);\ncout << ((v<w) && (v<0)) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_boolean_not.cpp",
    "content": "Array3d v(1,2,3);\nv(1) *= 0.0/0.0;\nv(2) /= 0.0;\ncout << v << endl << endl;\ncout << !isfinite(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_boolean_or.cpp",
    "content": "Array3d v(-1,2,1), w(-3,2,3);\ncout << ((v<w) || (v<0)) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_boolean_xor.cpp",
    "content": "Array3d v(-1,2,1), w(-3,2,3);\ncout << ((v<w) ^ (v<0)) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_ceil.cpp",
    "content": "ArrayXd v = ArrayXd::LinSpaced(7,-2,2);\ncout << v << endl << endl;\ncout << ceil(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_cos.cpp",
    "content": "Array3d v(M_PI, M_PI/2, M_PI/3);\ncout << v.cos() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_cosh.cpp",
    "content": "ArrayXd v = ArrayXd::LinSpaced(5,0,1);\ncout << cosh(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_cube.cpp",
    "content": "Array3d v(2,3,4);\ncout << v.cube() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_equal_equal.cpp",
    "content": "Array3d v(1,2,3), w(3,2,1);\ncout << (v==w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_exp.cpp",
    "content": "Array3d v(1,2,3);\ncout << v.exp() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_floor.cpp",
    "content": "ArrayXd v = ArrayXd::LinSpaced(7,-2,2);\ncout << v << endl << endl;\ncout << floor(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_greater.cpp",
    "content": "Array3d v(1,2,3), w(3,2,1);\ncout << (v>w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_greater_equal.cpp",
    "content": "Array3d v(1,2,3), w(3,2,1);\ncout << (v>=w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_inverse.cpp",
    "content": "Array3d v(2,3,4);\ncout << v.inverse() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_isFinite.cpp",
    "content": "Array3d v(1,2,3);\nv(1) *= 0.0/0.0;\nv(2) /= 0.0;\ncout << v << endl << endl;\ncout << isfinite(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_isInf.cpp",
    "content": "Array3d v(1,2,3);\nv(1) *= 0.0/0.0;\nv(2) /= 0.0;\ncout << v << endl << endl;\ncout << isinf(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_isNaN.cpp",
    "content": "Array3d v(1,2,3);\nv(1) *= 0.0/0.0;\nv(2) /= 0.0;\ncout << v << endl << endl;\ncout << isnan(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_less.cpp",
    "content": "Array3d v(1,2,3), w(3,2,1);\ncout << (v<w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_less_equal.cpp",
    "content": "Array3d v(1,2,3), w(3,2,1);\ncout << (v<=w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_log.cpp",
    "content": "Array3d v(1,2,3);\ncout << v.log() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_log10.cpp",
    "content": "Array4d v(-1,0,1,2);\ncout << log10(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_max.cpp",
    "content": "Array3d v(2,3,4), w(4,2,3);\ncout << v.max(w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_min.cpp",
    "content": "Array3d v(2,3,4), w(4,2,3);\ncout << v.min(w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_minus.cpp",
    "content": "Array3d v(1,2,3);\ncout << v-5 << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_minus_equal.cpp",
    "content": "Array3d v(1,2,3);\nv -= 5;\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_not_equal.cpp",
    "content": "Array3d v(1,2,3), w(3,2,1);\ncout << (v!=w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_plus.cpp",
    "content": "Array3d v(1,2,3);\ncout << v+5 << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_plus_equal.cpp",
    "content": "Array3d v(1,2,3);\nv += 5;\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_pow.cpp",
    "content": "Array3d v(8,27,64);\ncout << v.pow(0.333333) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_product.cpp",
    "content": "Array33i a = Array33i::Random(), b = Array33i::Random();\nArray33i c = a * b;\ncout << \"a:\\n\" << a << \"\\nb:\\n\" << b << \"\\nc:\\n\" << c << endl;\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_quotient.cpp",
    "content": "Array3d v(2,3,4), w(4,2,3);\ncout << v/w << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_rint.cpp",
    "content": "ArrayXd v = ArrayXd::LinSpaced(7,-2,2);\ncout << v << endl << endl;\ncout << rint(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_round.cpp",
    "content": "ArrayXd v = ArrayXd::LinSpaced(7,-2,2);\ncout << v << endl << endl;\ncout << round(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_scalar_power_array.cpp",
    "content": "Array<double,1,3> e(2,-3,1./3.);\ncout << \"10^[\" << e << \"] = \" << pow(10,e) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_sign.cpp",
    "content": "Array3d v(-3,5,0);\ncout << v.sign() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_sin.cpp",
    "content": "Array3d v(M_PI, M_PI/2, M_PI/3);\ncout << v.sin() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_sinh.cpp",
    "content": "ArrayXd v = ArrayXd::LinSpaced(5,0,1);\ncout << sinh(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_slash_equal.cpp",
    "content": "Array3d v(3,2,4), w(5,4,2);\nv /= w;\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_sqrt.cpp",
    "content": "Array3d v(1,2,4);\ncout << v.sqrt() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_square.cpp",
    "content": "Array3d v(2,3,4);\ncout << v.square() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_tan.cpp",
    "content": "Array3d v(M_PI, M_PI/2, M_PI/3);\ncout << v.tan() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_tanh.cpp",
    "content": "ArrayXd v = ArrayXd::LinSpaced(5,0,1);\ncout << tanh(v) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Cwise_times_equal.cpp",
    "content": "Array3d v(1,2,3), w(2,3,0);\nv *= w;\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/DenseBase_LinSpaced.cpp",
    "content": "cout << VectorXi::LinSpaced(4,7,10).transpose() << endl;\ncout << VectorXd::LinSpaced(5,0.0,1.0).transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/DenseBase_LinSpacedInt.cpp",
    "content": "cout << \"Even spacing inputs:\" << endl;\ncout << VectorXi::LinSpaced(8,1,4).transpose() << endl;\ncout << VectorXi::LinSpaced(8,1,8).transpose() << endl;\ncout << VectorXi::LinSpaced(8,1,15).transpose() << endl;\ncout << \"Uneven spacing inputs:\" << endl;\ncout << VectorXi::LinSpaced(8,1,7).transpose() << endl;\ncout << VectorXi::LinSpaced(8,1,9).transpose() << endl;\ncout << VectorXi::LinSpaced(8,1,16).transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/DenseBase_LinSpaced_seq_deprecated.cpp",
    "content": "cout << VectorXi::LinSpaced(Sequential,4,7,10).transpose() << endl;\ncout << VectorXd::LinSpaced(Sequential,5,0.0,1.0).transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/DenseBase_setLinSpaced.cpp",
    "content": "VectorXf v;\nv.setLinSpaced(5,0.5f,1.5f);\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/DirectionWise_hnormalized.cpp",
    "content": "Matrix4Xd M = Matrix4Xd::Random(4,5);\nProjective3d P(Matrix4d::Random());\ncout << \"The matrix M is:\" << endl << M << endl << endl;\ncout << \"M.colwise().hnormalized():\" << endl << M.colwise().hnormalized() << endl << endl;\ncout << \"P*M:\" << endl << P*M << endl << endl;\ncout << \"(P*M).colwise().hnormalized():\" << endl << (P*M).colwise().hnormalized() << endl << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/DirectionWise_replicate.cpp",
    "content": "MatrixXi m = MatrixXi::Random(2,3);\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"m.colwise().replicate<3>() = ...\" << endl;\ncout << m.colwise().replicate<3>() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/DirectionWise_replicate_int.cpp",
    "content": "Vector3i v = Vector3i::Random();\ncout << \"Here is the vector v:\" << endl << v << endl;\ncout << \"v.rowwise().replicate(5) = ...\" << endl;\ncout << v.rowwise().replicate(5) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/EigenSolver_EigenSolver_MatrixType.cpp",
    "content": "MatrixXd A = MatrixXd::Random(6,6);\ncout << \"Here is a random 6x6 matrix, A:\" << endl << A << endl << endl;\n\nEigenSolver<MatrixXd> es(A);\ncout << \"The eigenvalues of A are:\" << endl << es.eigenvalues() << endl;\ncout << \"The matrix of eigenvectors, V, is:\" << endl << es.eigenvectors() << endl << endl;\n\ncomplex<double> lambda = es.eigenvalues()[0];\ncout << \"Consider the first eigenvalue, lambda = \" << lambda << endl;\nVectorXcd v = es.eigenvectors().col(0);\ncout << \"If v is the corresponding eigenvector, then lambda * v = \" << endl << lambda * v << endl;\ncout << \"... and A * v = \" << endl << A.cast<complex<double> >() * v << endl << endl;\n\nMatrixXcd D = es.eigenvalues().asDiagonal();\nMatrixXcd V = es.eigenvectors();\ncout << \"Finally, V * D * V^(-1) = \" << endl << V * D * V.inverse() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/EigenSolver_compute.cpp",
    "content": "EigenSolver<MatrixXf> es;\nMatrixXf A = MatrixXf::Random(4,4);\nes.compute(A, /* computeEigenvectors = */ false);\ncout << \"The eigenvalues of A are: \" << es.eigenvalues().transpose() << endl;\nes.compute(A + MatrixXf::Identity(4,4), false); // re-use es to compute eigenvalues of A+I\ncout << \"The eigenvalues of A+I are: \" << es.eigenvalues().transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/EigenSolver_eigenvalues.cpp",
    "content": "MatrixXd ones = MatrixXd::Ones(3,3);\nEigenSolver<MatrixXd> es(ones, false);\ncout << \"The eigenvalues of the 3x3 matrix of ones are:\" \n     << endl << es.eigenvalues() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/EigenSolver_eigenvectors.cpp",
    "content": "MatrixXd ones = MatrixXd::Ones(3,3);\nEigenSolver<MatrixXd> es(ones);\ncout << \"The first eigenvector of the 3x3 matrix of ones is:\"\n     << endl << es.eigenvectors().col(0) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/EigenSolver_pseudoEigenvectors.cpp",
    "content": "MatrixXd A = MatrixXd::Random(6,6);\ncout << \"Here is a random 6x6 matrix, A:\" << endl << A << endl << endl;\n\nEigenSolver<MatrixXd> es(A);\nMatrixXd D = es.pseudoEigenvalueMatrix();\nMatrixXd V = es.pseudoEigenvectors();\ncout << \"The pseudo-eigenvalue matrix D is:\" << endl << D << endl;\ncout << \"The pseudo-eigenvector matrix V is:\" << endl << V << endl;\ncout << \"Finally, V * D * V^(-1) = \" << endl << V * D * V.inverse() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/FullPivHouseholderQR_solve.cpp",
    "content": "Matrix3f m = Matrix3f::Random();\nMatrix3f y = Matrix3f::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the matrix y:\" << endl << y << endl;\nMatrix3f x;\nx = m.fullPivHouseholderQr().solve(y);\nassert(y.isApprox(m*x));\ncout << \"Here is a solution x to the equation mx=y:\" << endl << x << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/FullPivLU_image.cpp",
    "content": "Matrix3d m;\nm << 1,1,0,\n     1,3,2,\n     0,1,1;\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Notice that the middle column is the sum of the two others, so the \"\n     << \"columns are linearly dependent.\" << endl;\ncout << \"Here is a matrix whose columns have the same span but are linearly independent:\"\n     << endl << m.fullPivLu().image(m) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/FullPivLU_kernel.cpp",
    "content": "MatrixXf m = MatrixXf::Random(3,5);\ncout << \"Here is the matrix m:\" << endl << m << endl;\nMatrixXf ker = m.fullPivLu().kernel();\ncout << \"Here is a matrix whose columns form a basis of the kernel of m:\"\n     << endl << ker << endl;\ncout << \"By definition of the kernel, m*ker is zero:\"\n     << endl << m*ker << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/FullPivLU_solve.cpp",
    "content": "Matrix<float,2,3> m = Matrix<float,2,3>::Random();\nMatrix2f y = Matrix2f::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the matrix y:\" << endl << y << endl;\nMatrix<float,3,2> x = m.fullPivLu().solve(y);\nif((m*x).isApprox(y))\n{\n  cout << \"Here is a solution x to the equation mx=y:\" << endl << x << endl;\n}\nelse\n  cout << \"The equation mx=y does not have any solution.\" << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/GeneralizedEigenSolver.cpp",
    "content": "GeneralizedEigenSolver<MatrixXf> ges;\nMatrixXf A = MatrixXf::Random(4,4);\nMatrixXf B = MatrixXf::Random(4,4);\nges.compute(A, B);\ncout << \"The (complex) numerators of the generalzied eigenvalues are: \" << ges.alphas().transpose() << endl;\ncout << \"The (real) denominatore of the generalzied eigenvalues are: \" << ges.betas().transpose() << endl;\ncout << \"The (complex) generalzied eigenvalues are (alphas./beta): \" << ges.eigenvalues().transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/HessenbergDecomposition_compute.cpp",
    "content": "MatrixXcf A = MatrixXcf::Random(4,4);\nHessenbergDecomposition<MatrixXcf> hd(4);\nhd.compute(A);\ncout << \"The matrix H in the decomposition of A is:\" << endl << hd.matrixH() << endl;\nhd.compute(2*A); // re-use hd to compute and store decomposition of 2A\ncout << \"The matrix H in the decomposition of 2A is:\" << endl << hd.matrixH() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/HessenbergDecomposition_matrixH.cpp",
    "content": "Matrix4f A = MatrixXf::Random(4,4);\ncout << \"Here is a random 4x4 matrix:\" << endl << A << endl;\nHessenbergDecomposition<MatrixXf> hessOfA(A);\nMatrixXf H = hessOfA.matrixH();\ncout << \"The Hessenberg matrix H is:\" << endl << H << endl;\nMatrixXf Q = hessOfA.matrixQ();\ncout << \"The orthogonal matrix Q is:\" << endl << Q << endl;\ncout << \"Q H Q^T is:\" << endl << Q * H * Q.transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/HessenbergDecomposition_packedMatrix.cpp",
    "content": "Matrix4d A = Matrix4d::Random(4,4);\ncout << \"Here is a random 4x4 matrix:\" << endl << A << endl;\nHessenbergDecomposition<Matrix4d> hessOfA(A);\nMatrix4d pm = hessOfA.packedMatrix();\ncout << \"The packed matrix M is:\" << endl << pm << endl;\ncout << \"The upper Hessenberg part corresponds to the matrix H, which is:\" \n     << endl << hessOfA.matrixH() << endl;\nVector3d hc = hessOfA.householderCoefficients();\ncout << \"The vector of Householder coefficients is:\" << endl << hc << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/HouseholderQR_householderQ.cpp",
    "content": "MatrixXf A(MatrixXf::Random(5,3)), thinQ(MatrixXf::Identity(5,3)), Q;\nA.setRandom();\nHouseholderQR<MatrixXf> qr(A);\nQ = qr.householderQ();\nthinQ = qr.householderQ() * thinQ;\nstd::cout << \"The complete unitary matrix Q is:\\n\" << Q << \"\\n\\n\";\nstd::cout << \"The thin matrix Q is:\\n\" << thinQ << \"\\n\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/HouseholderQR_solve.cpp",
    "content": "typedef Matrix<float,3,3> Matrix3x3;\nMatrix3x3 m = Matrix3x3::Random();\nMatrix3f y = Matrix3f::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the matrix y:\" << endl << y << endl;\nMatrix3f x;\nx = m.householderQr().solve(y);\nassert(y.isApprox(m*x));\ncout << \"Here is a solution x to the equation mx=y:\" << endl << x << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/HouseholderSequence_HouseholderSequence.cpp",
    "content": "Matrix3d v = Matrix3d::Random();\ncout << \"The matrix v is:\" << endl;\ncout << v << endl;\n\nVector3d v0(1, v(1,0), v(2,0));\ncout << \"The first Householder vector is: v_0 = \" << v0.transpose() << endl;\nVector3d v1(0, 1, v(2,1));\ncout << \"The second Householder vector is: v_1 = \" << v1.transpose()  << endl;\nVector3d v2(0, 0, 1);\ncout << \"The third Householder vector is: v_2 = \" << v2.transpose() << endl;\n\nVector3d h = Vector3d::Random();\ncout << \"The Householder coefficients are: h = \" << h.transpose() << endl;\n\nMatrix3d H0 = Matrix3d::Identity() - h(0) * v0 * v0.adjoint();\ncout << \"The first Householder reflection is represented by H_0 = \" << endl;\ncout << H0 << endl;\nMatrix3d H1 = Matrix3d::Identity() - h(1) * v1 * v1.adjoint();\ncout << \"The second Householder reflection is represented by H_1 = \" << endl;\ncout << H1 << endl;\nMatrix3d H2 = Matrix3d::Identity() - h(2) * v2 * v2.adjoint();\ncout << \"The third Householder reflection is represented by H_2 = \" << endl;\ncout << H2 << endl;\ncout << \"Their product is H_0 H_1 H_2 = \" << endl;\ncout << H0 * H1 * H2 << endl;\n\nHouseholderSequence<Matrix3d, Vector3d> hhSeq(v, h);\nMatrix3d hhSeqAsMatrix(hhSeq);\ncout << \"If we construct a HouseholderSequence from v and h\" << endl;\ncout << \"and convert it to a matrix, we get:\" << endl;\ncout << hhSeqAsMatrix << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/IOFormat.cpp",
    "content": "std::string sep = \"\\n----------------------------------------\\n\";\nMatrix3d m1;\nm1 << 1.111111, 2, 3.33333, 4, 5, 6, 7, 8.888888, 9;\n\nIOFormat CommaInitFmt(StreamPrecision, DontAlignCols, \", \", \", \", \"\", \"\", \" << \", \";\");\nIOFormat CleanFmt(4, 0, \", \", \"\\n\", \"[\", \"]\");\nIOFormat OctaveFmt(StreamPrecision, 0, \", \", \";\\n\", \"\", \"\", \"[\", \"]\");\nIOFormat HeavyFmt(FullPrecision, 0, \", \", \";\\n\", \"[\", \"]\", \"[\", \"]\");\n\nstd::cout << m1 << sep;\nstd::cout << m1.format(CommaInitFmt) << sep;\nstd::cout << m1.format(CleanFmt) << sep;\nstd::cout << m1.format(OctaveFmt) << sep;\nstd::cout << m1.format(HeavyFmt) << sep;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/JacobiSVD_basic.cpp",
    "content": "MatrixXf m = MatrixXf::Random(3,2);\ncout << \"Here is the matrix m:\" << endl << m << endl;\nJacobiSVD<MatrixXf> svd(m, ComputeThinU | ComputeThinV);\ncout << \"Its singular values are:\" << endl << svd.singularValues() << endl;\ncout << \"Its left singular vectors are the columns of the thin U matrix:\" << endl << svd.matrixU() << endl;\ncout << \"Its right singular vectors are the columns of the thin V matrix:\" << endl << svd.matrixV() << endl;\nVector3f rhs(1, 0, 0);\ncout << \"Now consider this rhs vector:\" << endl << rhs << endl;\ncout << \"A least-squares solution of m*x = rhs is:\" << endl << svd.solve(rhs) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Jacobi_makeGivens.cpp",
    "content": "Vector2f v = Vector2f::Random();\nJacobiRotation<float> G;\nG.makeGivens(v.x(), v.y());\ncout << \"Here is the vector v:\" << endl << v << endl;\nv.applyOnTheLeft(0, 1, G.adjoint());\ncout << \"Here is the vector J' * v:\" << endl << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Jacobi_makeJacobi.cpp",
    "content": "Matrix2f m = Matrix2f::Random();\nm = (m + m.adjoint()).eval();\nJacobiRotation<float> J;\nJ.makeJacobi(m, 0, 1);\ncout << \"Here is the matrix m:\" << endl << m << endl;\nm.applyOnTheLeft(0, 1, J.adjoint());\nm.applyOnTheRight(0, 1, J);\ncout << \"Here is the matrix J' * m * J:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/LLT_example.cpp",
    "content": "MatrixXd A(3,3);\nA << 4,-1,2, -1,6,0, 2,0,5;\ncout << \"The matrix A is\" << endl << A << endl;\n\nLLT<MatrixXd> lltOfA(A); // compute the Cholesky decomposition of A\nMatrixXd L = lltOfA.matrixL(); // retrieve factor L  in the decomposition\n// The previous two lines can also be written as \"L = A.llt().matrixL()\"\n\ncout << \"The Cholesky factor L is\" << endl << L << endl;\ncout << \"To check this, let us compute L * L.transpose()\" << endl;\ncout << L * L.transpose() << endl;\ncout << \"This should equal the matrix A\" << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/LLT_solve.cpp",
    "content": "typedef Matrix<float,Dynamic,2> DataMatrix;\n// let's generate some samples on the 3D plane of equation z = 2x+3y (with some noise)\nDataMatrix samples = DataMatrix::Random(12,2);\nVectorXf elevations = 2*samples.col(0) + 3*samples.col(1) + VectorXf::Random(12)*0.1;\n// and let's solve samples * [x y]^T = elevations in least square sense:\nMatrix<float,2,1> xy\n = (samples.adjoint() * samples).llt().solve((samples.adjoint()*elevations));\ncout << xy << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/LeastSquaresNormalEquations.cpp",
    "content": "MatrixXf A = MatrixXf::Random(3, 2);\nVectorXf b = VectorXf::Random(3);\ncout << \"The solution using normal equations is:\\n\"\n     << (A.transpose() * A).ldlt().solve(A.transpose() * b) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/LeastSquaresQR.cpp",
    "content": "MatrixXf A = MatrixXf::Random(3, 2);\nVectorXf b = VectorXf::Random(3);\ncout << \"The solution using the QR decomposition is:\\n\"\n     << A.colPivHouseholderQr().solve(b) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Map_general_stride.cpp",
    "content": "int array[24];\nfor(int i = 0; i < 24; ++i) array[i] = i;\ncout << Map<MatrixXi, 0, Stride<Dynamic,2> >\n         (array, 3, 3, Stride<Dynamic,2>(8, 2))\n     << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Map_inner_stride.cpp",
    "content": "int array[12];\nfor(int i = 0; i < 12; ++i) array[i] = i;\ncout << Map<VectorXi, 0, InnerStride<2> >\n         (array, 6) // the inner stride has already been passed as template parameter\n     << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Map_outer_stride.cpp",
    "content": "int array[12];\nfor(int i = 0; i < 12; ++i) array[i] = i;\ncout << Map<MatrixXi, 0, OuterStride<> >(array, 3, 3, OuterStride<>(4)) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Map_placement_new.cpp",
    "content": "int data[] = {1,2,3,4,5,6,7,8,9};\nMap<RowVectorXi> v(data,4);\ncout << \"The mapped vector v is: \" << v << \"\\n\";\nnew (&v) Map<RowVectorXi>(data+4,5);\ncout << \"Now v is: \" << v << \"\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Map_simple.cpp",
    "content": "int array[9];\nfor(int i = 0; i < 9; ++i) array[i] = i;\ncout << Map<Matrix3i>(array) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_adjoint.cpp",
    "content": "Matrix2cf m = Matrix2cf::Random();\ncout << \"Here is the 2x2 complex matrix m:\" << endl << m << endl;\ncout << \"Here is the adjoint of m:\" << endl << m.adjoint() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_all.cpp",
    "content": "Vector3f boxMin(Vector3f::Zero()), boxMax(Vector3f::Ones());\nVector3f p0 = Vector3f::Random(), p1 = Vector3f::Random().cwiseAbs();\n// let's check if p0 and p1 are inside the axis aligned box defined by the corners boxMin,boxMax:\ncout << \"Is (\" << p0.transpose() << \") inside the box: \"\n     << ((boxMin.array()<p0.array()).all() && (boxMax.array()>p0.array()).all()) << endl;\ncout << \"Is (\" << p1.transpose() << \") inside the box: \"\n     << ((boxMin.array()<p1.array()).all() && (boxMax.array()>p1.array()).all()) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_applyOnTheLeft.cpp",
    "content": "Matrix3f A = Matrix3f::Random(3,3), B;\nB << 0,1,0,  \n     0,0,1,  \n     1,0,0;\ncout << \"At start, A = \" << endl << A << endl;\nA.applyOnTheLeft(B); \ncout << \"After applyOnTheLeft, A = \" << endl << A << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_applyOnTheRight.cpp",
    "content": "Matrix3f A = Matrix3f::Random(3,3), B;\nB << 0,1,0,  \n     0,0,1,  \n     1,0,0;\ncout << \"At start, A = \" << endl << A << endl;\nA *= B;\ncout << \"After A *= B, A = \" << endl << A << endl;\nA.applyOnTheRight(B);  // equivalent to A *= B\ncout << \"After applyOnTheRight, A = \" << endl << A << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_array.cpp",
    "content": "Vector3d v(1,2,3);\nv.array() += 3;\nv.array() -= 2;\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_array_const.cpp",
    "content": "Vector3d v(-1,2,-3);\ncout << \"the absolute values:\" << endl << v.array().abs() << endl;\ncout << \"the absolute values plus one:\" << endl << v.array().abs()+1 << endl;\ncout << \"sum of the squares: \" << v.array().square().sum() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_asDiagonal.cpp",
    "content": "cout << Matrix3i(Vector3i(2,5,6).asDiagonal()) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_block_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.block<2,2>(1,1):\" << endl << m.block<2,2>(1,1) << endl;\nm.block<2,2>(1,1).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_block_int_int_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.block(1, 1, 2, 2):\" << endl << m.block(1, 1, 2, 2) << endl;\nm.block(1, 1, 2, 2).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_bottomLeftCorner_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.bottomLeftCorner(2, 2):\" << endl;\ncout << m.bottomLeftCorner(2, 2) << endl;\nm.bottomLeftCorner(2, 2).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_bottomRightCorner_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.bottomRightCorner(2, 2):\" << endl;\ncout << m.bottomRightCorner(2, 2) << endl;\nm.bottomRightCorner(2, 2).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_bottomRows_int.cpp",
    "content": "Array44i a = Array44i::Random();\ncout << \"Here is the array a:\" << endl << a << endl;\ncout << \"Here is a.bottomRows(2):\" << endl;\ncout << a.bottomRows(2) << endl;\na.bottomRows(2).setZero();\ncout << \"Now the array a is:\" << endl << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_cast.cpp",
    "content": "Matrix2d md = Matrix2d::Identity() * 0.45;\nMatrix2f mf = Matrix2f::Identity();\ncout << md + mf.cast<double>() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_col.cpp",
    "content": "Matrix3d m = Matrix3d::Identity();\nm.col(1) = Vector3d(4,5,6);\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_colwise.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the sum of each column:\" << endl << m.colwise().sum() << endl;\ncout << \"Here is the maximum absolute value of each column:\"\n     << endl << m.cwiseAbs().colwise().maxCoeff() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_colwise_iterator_cxx11.cpp",
    "content": "Matrix3i m = Matrix3i::Random();\ncout << \"Here is the initial matrix m:\" << endl << m << endl;\nint i = -1;\nfor(auto c: m.colwise()) {\n  c *= i;\n  ++i;\n}\ncout << \"Here is the matrix m after the for-range-loop:\" << endl << m << endl;\nauto cols = m.colwise();\nauto it = std::find_if(cols.cbegin(), cols.cend(),\n                       [](Matrix3i::ConstColXpr x) { return x.squaredNorm() == 0; });\ncout << \"The first empty column is: \" << distance(cols.cbegin(),it) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_computeInverseAndDetWithCheck.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\nMatrix3d inverse;\nbool invertible;\ndouble determinant;\nm.computeInverseAndDetWithCheck(inverse,determinant,invertible);\ncout << \"Its determinant is \" << determinant << endl;\nif(invertible) {\n  cout << \"It is invertible, and its inverse is:\" << endl << inverse << endl;\n}\nelse {\n  cout << \"It is not invertible.\" << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_computeInverseWithCheck.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\nMatrix3d inverse;\nbool invertible;\nm.computeInverseWithCheck(inverse,invertible);\nif(invertible) {\n  cout << \"It is invertible, and its inverse is:\" << endl << inverse << endl;\n}\nelse {\n  cout << \"It is not invertible.\" << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_cwiseAbs.cpp",
    "content": "MatrixXd m(2,3);\nm << 2, -4, 6,   \n     -5, 1, 0;\ncout << m.cwiseAbs() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_cwiseAbs2.cpp",
    "content": "MatrixXd m(2,3);\nm << 2, -4, 6,   \n     -5, 1, 0;\ncout << m.cwiseAbs2() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_cwiseArg.cpp",
    "content": "MatrixXcf v = MatrixXcf::Random(2, 3);\ncout << v << endl << endl;\ncout << v.cwiseArg() << endl;"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_cwiseEqual.cpp",
    "content": "MatrixXi m(2,2);\nm << 1, 0,\n     1, 1;\ncout << \"Comparing m with identity matrix:\" << endl;\ncout << m.cwiseEqual(MatrixXi::Identity(2,2)) << endl;\nIndex count = m.cwiseEqual(MatrixXi::Identity(2,2)).count();\ncout << \"Number of coefficients that are equal: \" << count << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_cwiseInverse.cpp",
    "content": "MatrixXd m(2,3);\nm << 2, 0.5, 1,   \n     3, 0.25, 1;\ncout << m.cwiseInverse() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_cwiseMax.cpp",
    "content": "Vector3d v(2,3,4), w(4,2,3);\ncout << v.cwiseMax(w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_cwiseMin.cpp",
    "content": "Vector3d v(2,3,4), w(4,2,3);\ncout << v.cwiseMin(w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_cwiseNotEqual.cpp",
    "content": "MatrixXi m(2,2);\nm << 1, 0,\n     1, 1;\ncout << \"Comparing m with identity matrix:\" << endl;\ncout << m.cwiseNotEqual(MatrixXi::Identity(2,2)) << endl;\nIndex count = m.cwiseNotEqual(MatrixXi::Identity(2,2)).count();\ncout << \"Number of coefficients that are not equal: \" << count << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_cwiseProduct.cpp",
    "content": "Matrix3i a = Matrix3i::Random(), b = Matrix3i::Random();\nMatrix3i c = a.cwiseProduct(b);\ncout << \"a:\\n\" << a << \"\\nb:\\n\" << b << \"\\nc:\\n\" << c << endl;\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_cwiseQuotient.cpp",
    "content": "Vector3d v(2,3,4), w(4,2,3);\ncout << v.cwiseQuotient(w) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_cwiseSign.cpp",
    "content": "MatrixXd m(2,3);\nm <<  2, -4, 6,\n     -5,  1, 0;\ncout << m.cwiseSign() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_cwiseSqrt.cpp",
    "content": "Vector3d v(1,2,4);\ncout << v.cwiseSqrt() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_diagonal.cpp",
    "content": "Matrix3i m = Matrix3i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here are the coefficients on the main diagonal of m:\" << endl\n     << m.diagonal() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_diagonal_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here are the coefficients on the 1st super-diagonal and 2nd sub-diagonal of m:\" << endl\n     << m.diagonal(1).transpose() << endl\n     << m.diagonal(-2).transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_diagonal_template_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here are the coefficients on the 1st super-diagonal and 2nd sub-diagonal of m:\" << endl\n     << m.diagonal<1>().transpose() << endl\n     << m.diagonal<-2>().transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_eigenvalues.cpp",
    "content": "MatrixXd ones = MatrixXd::Ones(3,3);\nVectorXcd eivals = ones.eigenvalues();\ncout << \"The eigenvalues of the 3x3 matrix of ones are:\" << endl << eivals << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_end_int.cpp",
    "content": "RowVector4i v = RowVector4i::Random();\ncout << \"Here is the vector v:\" << endl << v << endl;\ncout << \"Here is v.tail(2):\" << endl << v.tail(2) << endl;\nv.tail(2).setZero();\ncout << \"Now the vector v is:\" << endl << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_eval.cpp",
    "content": "Matrix2f M = Matrix2f::Random();\nMatrix2f m;\nm = M;\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Now we want to copy a column into a row.\" << endl;\ncout << \"If we do m.col(1) = m.row(0), then m becomes:\" << endl;\nm.col(1) = m.row(0);\ncout << m << endl << \"which is wrong!\" << endl;\ncout << \"Now let us instead do m.col(1) = m.row(0).eval(). Then m becomes\" << endl;\nm = M;\nm.col(1) = m.row(0).eval();\ncout << m << endl << \"which is right.\" << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_fixedBlock_int_int.cpp",
    "content": "Matrix4d m = Vector4d(1,2,3,4).asDiagonal();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.fixed<2, 2>(2, 2):\" << endl << m.block<2, 2>(2, 2) << endl;\nm.block<2, 2>(2, 0) = m.block<2, 2>(2, 2);\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_hnormalized.cpp",
    "content": "Vector4d v = Vector4d::Random();\nProjective3d P(Matrix4d::Random());\ncout << \"v                   = \" << v.transpose() << \"]^T\" << endl;\ncout << \"v.hnormalized()     = \" << v.hnormalized().transpose() << \"]^T\" << endl;\ncout << \"P*v                 = \" << (P*v).transpose() << \"]^T\" << endl;\ncout << \"(P*v).hnormalized() = \" << (P*v).hnormalized().transpose() << \"]^T\" << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_homogeneous.cpp",
    "content": "Vector3d v = Vector3d::Random(), w;\nProjective3d P(Matrix4d::Random());\ncout << \"v                                   = [\" << v.transpose() << \"]^T\" << endl;\ncout << \"h.homogeneous()                     = [\" << v.homogeneous().transpose() << \"]^T\" << endl;\ncout << \"(P * v.homogeneous())               = [\" << (P * v.homogeneous()).transpose() << \"]^T\" << endl;\ncout << \"(P * v.homogeneous()).hnormalized() = [\" << (P * v.homogeneous()).eval().hnormalized().transpose() << \"]^T\" << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_identity.cpp",
    "content": "cout << Matrix<double, 3, 4>::Identity() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_identity_int_int.cpp",
    "content": "cout << MatrixXd::Identity(4, 3) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_inverse.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Its inverse is:\" << endl << m.inverse() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_isDiagonal.cpp",
    "content": "Matrix3d m = 10000 * Matrix3d::Identity();\nm(0,2) = 1;\ncout << \"Here's the matrix m:\" << endl << m << endl;\ncout << \"m.isDiagonal() returns: \" << m.isDiagonal() << endl;\ncout << \"m.isDiagonal(1e-3) returns: \" << m.isDiagonal(1e-3) << endl;\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_isIdentity.cpp",
    "content": "Matrix3d m = Matrix3d::Identity();\nm(0,2) = 1e-4;\ncout << \"Here's the matrix m:\" << endl << m << endl;\ncout << \"m.isIdentity() returns: \" << m.isIdentity() << endl;\ncout << \"m.isIdentity(1e-3) returns: \" << m.isIdentity(1e-3) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_isOnes.cpp",
    "content": "Matrix3d m = Matrix3d::Ones();\nm(0,2) += 1e-4;\ncout << \"Here's the matrix m:\" << endl << m << endl;\ncout << \"m.isOnes() returns: \" << m.isOnes() << endl;\ncout << \"m.isOnes(1e-3) returns: \" << m.isOnes(1e-3) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_isOrthogonal.cpp",
    "content": "Vector3d v(1,0,0);\nVector3d w(1e-4,0,1);\ncout << \"Here's the vector v:\" << endl << v << endl;\ncout << \"Here's the vector w:\" << endl << w << endl;\ncout << \"v.isOrthogonal(w) returns: \" << v.isOrthogonal(w) << endl;\ncout << \"v.isOrthogonal(w,1e-3) returns: \" << v.isOrthogonal(w,1e-3) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_isUnitary.cpp",
    "content": "Matrix3d m = Matrix3d::Identity();\nm(0,2) = 1e-4;\ncout << \"Here's the matrix m:\" << endl << m << endl;\ncout << \"m.isUnitary() returns: \" << m.isUnitary() << endl;\ncout << \"m.isUnitary(1e-3) returns: \" << m.isUnitary(1e-3) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_isZero.cpp",
    "content": "Matrix3d m = Matrix3d::Zero();\nm(0,2) = 1e-4;\ncout << \"Here's the matrix m:\" << endl << m << endl;\ncout << \"m.isZero() returns: \" << m.isZero() << endl;\ncout << \"m.isZero(1e-3) returns: \" << m.isZero(1e-3) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_leftCols_int.cpp",
    "content": "Array44i a = Array44i::Random();\ncout << \"Here is the array a:\" << endl << a << endl;\ncout << \"Here is a.leftCols(2):\" << endl;\ncout << a.leftCols(2) << endl;\na.leftCols(2).setZero();\ncout << \"Now the array a is:\" << endl << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_noalias.cpp",
    "content": "Matrix2d a, b, c; a << 1,2,3,4; b << 5,6,7,8;\nc.noalias() = a * b; // this computes the product directly to c\ncout << c << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_ones.cpp",
    "content": "cout << Matrix2d::Ones() << endl;\ncout << 6 * RowVector4i::Ones() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_ones_int.cpp",
    "content": "cout << 6 * RowVectorXi::Ones(4) << endl;\ncout << VectorXf::Ones(2) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_ones_int_int.cpp",
    "content": "cout << MatrixXi::Ones(2,3) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_operatorNorm.cpp",
    "content": "MatrixXd ones = MatrixXd::Ones(3,3);\ncout << \"The operator norm of the 3x3 matrix of ones is \"\n     << ones.operatorNorm() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_prod.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the product of all the coefficients:\" << endl << m.prod() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_random.cpp",
    "content": "cout << 100 * Matrix2i::Random() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_random_int.cpp",
    "content": "cout << VectorXi::Random(2) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_random_int_int.cpp",
    "content": "cout << MatrixXi::Random(2,3) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_replicate.cpp",
    "content": "MatrixXi m = MatrixXi::Random(2,3);\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"m.replicate<3,2>() = ...\" << endl;\ncout << m.replicate<3,2>() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_replicate_int_int.cpp",
    "content": "Vector3i v = Vector3i::Random();\ncout << \"Here is the vector v:\" << endl << v << endl;\ncout << \"v.replicate(2,5) = ...\" << endl;\ncout << v.replicate(2,5) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_reshaped_auto.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.reshaped(2, AutoSize):\" << endl << m.reshaped(2, AutoSize) << endl;\ncout << \"Here is m.reshaped<RowMajor>(AutoSize, fix<8>):\" << endl << m.reshaped<RowMajor>(AutoSize, fix<8>) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_reshaped_fixed.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.reshaped(fix<2>,fix<8>):\" << endl << m.reshaped(fix<2>,fix<8>) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_reshaped_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.reshaped(2, 8):\" << endl << m.reshaped(2, 8) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_reshaped_to_vector.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.reshaped().transpose():\" << endl << m.reshaped().transpose() << endl;\ncout << \"Here is m.reshaped<RowMajor>().transpose():  \" << endl << m.reshaped<RowMajor>().transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_reverse.cpp",
    "content": "MatrixXi m = MatrixXi::Random(3,4);\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the reverse of m:\" << endl << m.reverse() << endl;\ncout << \"Here is the coefficient (1,0) in the reverse of m:\" << endl\n     << m.reverse()(1,0) << endl;\ncout << \"Let us overwrite this coefficient with the value 4.\" << endl;\nm.reverse()(1,0) = 4;\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_rightCols_int.cpp",
    "content": "Array44i a = Array44i::Random();\ncout << \"Here is the array a:\" << endl << a << endl;\ncout << \"Here is a.rightCols(2):\" << endl;\ncout << a.rightCols(2) << endl;\na.rightCols(2).setZero();\ncout << \"Now the array a is:\" << endl << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_row.cpp",
    "content": "Matrix3d m = Matrix3d::Identity();\nm.row(1) = Vector3d(4,5,6);\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_rowwise.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the sum of each row:\" << endl << m.rowwise().sum() << endl;\ncout << \"Here is the maximum absolute value of each row:\"\n     << endl << m.cwiseAbs().rowwise().maxCoeff() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_segment_int_int.cpp",
    "content": "RowVector4i v = RowVector4i::Random();\ncout << \"Here is the vector v:\" << endl << v << endl;\ncout << \"Here is v.segment(1, 2):\" << endl << v.segment(1, 2) << endl;\nv.segment(1, 2).setZero();\ncout << \"Now the vector v is:\" << endl << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_select.cpp",
    "content": "MatrixXi m(3, 3);\nm << 1, 2, 3,\n     4, 5, 6,\n     7, 8, 9;\nm = (m.array() >= 5).select(-m, m);\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_selfadjointView.cpp",
    "content": "Matrix3i m = Matrix3i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the symmetric matrix extracted from the upper part of m:\" << endl\n     << Matrix3i(m.selfadjointView<Upper>()) << endl;\ncout << \"Here is the symmetric matrix extracted from the lower part of m:\" << endl\n     << Matrix3i(m.selfadjointView<Lower>()) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_set.cpp",
    "content": "Matrix3i m1;\nm1 << 1, 2, 3,\n      4, 5, 6,\n      7, 8, 9;\ncout << m1 << endl << endl;\nMatrix3i m2 = Matrix3i::Identity();\nm2.block(0,0, 2,2) << 10, 11, 12, 13;\ncout << m2 << endl << endl;\nVector2i v1;\nv1 << 14, 15;\nm2 << v1.transpose(), 16,\n      v1, m1.block(1,1,2,2);\ncout << m2 << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_setIdentity.cpp",
    "content": "Matrix4i m = Matrix4i::Zero();\nm.block<3,3>(1,0).setIdentity();\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_setOnes.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\nm.row(1).setOnes();\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_setRandom.cpp",
    "content": "Matrix4i m = Matrix4i::Zero();\nm.col(1).setRandom();\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_setZero.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\nm.row(1).setZero();\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_start_int.cpp",
    "content": "RowVector4i v = RowVector4i::Random();\ncout << \"Here is the vector v:\" << endl << v << endl;\ncout << \"Here is v.head(2):\" << endl << v.head(2) << endl;\nv.head(2).setZero();\ncout << \"Now the vector v is:\" << endl << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_template_int_bottomRows.cpp",
    "content": "Array44i a = Array44i::Random();\ncout << \"Here is the array a:\" << endl << a << endl;\ncout << \"Here is a.bottomRows<2>():\" << endl;\ncout << a.bottomRows<2>() << endl;\na.bottomRows<2>().setZero();\ncout << \"Now the array a is:\" << endl << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_template_int_end.cpp",
    "content": "RowVector4i v = RowVector4i::Random();\ncout << \"Here is the vector v:\" << endl << v << endl;\ncout << \"Here is v.tail(2):\" << endl << v.tail<2>() << endl;\nv.tail<2>().setZero();\ncout << \"Now the vector v is:\" << endl << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_template_int_int_block_int_int_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the block:\" << endl << m.block<2, Dynamic>(1, 1, 2, 3) << endl;\nm.block<2, Dynamic>(1, 1, 2, 3).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_template_int_int_bottomLeftCorner.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.bottomLeftCorner<2,2>():\" << endl;\ncout << m.bottomLeftCorner<2,2>() << endl;\nm.bottomLeftCorner<2,2>().setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_template_int_int_bottomLeftCorner_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.bottomLeftCorner<2,Dynamic>(2,2):\" << endl;\ncout << m.bottomLeftCorner<2,Dynamic>(2,2) << endl;\nm.bottomLeftCorner<2,Dynamic>(2,2).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_template_int_int_bottomRightCorner.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.bottomRightCorner<2,2>():\" << endl;\ncout << m.bottomRightCorner<2,2>() << endl;\nm.bottomRightCorner<2,2>().setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_template_int_int_bottomRightCorner_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.bottomRightCorner<2,Dynamic>(2,2):\" << endl;\ncout << m.bottomRightCorner<2,Dynamic>(2,2) << endl;\nm.bottomRightCorner<2,Dynamic>(2,2).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_template_int_int_topLeftCorner.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.topLeftCorner<2,2>():\" << endl;\ncout << m.topLeftCorner<2,2>() << endl;\nm.topLeftCorner<2,2>().setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_template_int_int_topLeftCorner_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.topLeftCorner<2,Dynamic>(2,2):\" << endl;\ncout << m.topLeftCorner<2,Dynamic>(2,2) << endl;\nm.topLeftCorner<2,Dynamic>(2,2).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_template_int_int_topRightCorner.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.topRightCorner<2,2>():\" << endl;\ncout << m.topRightCorner<2,2>() << endl;\nm.topRightCorner<2,2>().setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_template_int_int_topRightCorner_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.topRightCorner<2,Dynamic>(2,2):\" << endl;\ncout << m.topRightCorner<2,Dynamic>(2,2) << endl;\nm.topRightCorner<2,Dynamic>(2,2).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_template_int_leftCols.cpp",
    "content": "Array44i a = Array44i::Random();\ncout << \"Here is the array a:\" << endl << a << endl;\ncout << \"Here is a.leftCols<2>():\" << endl;\ncout << a.leftCols<2>() << endl;\na.leftCols<2>().setZero();\ncout << \"Now the array a is:\" << endl << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_template_int_rightCols.cpp",
    "content": "Array44i a = Array44i::Random();\ncout << \"Here is the array a:\" << endl << a << endl;\ncout << \"Here is a.rightCols<2>():\" << endl;\ncout << a.rightCols<2>() << endl;\na.rightCols<2>().setZero();\ncout << \"Now the array a is:\" << endl << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_template_int_segment.cpp",
    "content": "RowVector4i v = RowVector4i::Random();\ncout << \"Here is the vector v:\" << endl << v << endl;\ncout << \"Here is v.segment<2>(1):\" << endl << v.segment<2>(1) << endl;\nv.segment<2>(2).setZero();\ncout << \"Now the vector v is:\" << endl << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_template_int_start.cpp",
    "content": "RowVector4i v = RowVector4i::Random();\ncout << \"Here is the vector v:\" << endl << v << endl;\ncout << \"Here is v.head(2):\" << endl << v.head<2>() << endl;\nv.head<2>().setZero();\ncout << \"Now the vector v is:\" << endl << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_template_int_topRows.cpp",
    "content": "Array44i a = Array44i::Random();\ncout << \"Here is the array a:\" << endl << a << endl;\ncout << \"Here is a.topRows<2>():\" << endl;\ncout << a.topRows<2>() << endl;\na.topRows<2>().setZero();\ncout << \"Now the array a is:\" << endl << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_topLeftCorner_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.topLeftCorner(2, 2):\" << endl;\ncout << m.topLeftCorner(2, 2) << endl;\nm.topLeftCorner(2, 2).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_topRightCorner_int_int.cpp",
    "content": "Matrix4i m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.topRightCorner(2, 2):\" << endl;\ncout << m.topRightCorner(2, 2) << endl;\nm.topRightCorner(2, 2).setZero();\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_topRows_int.cpp",
    "content": "Array44i a = Array44i::Random();\ncout << \"Here is the array a:\" << endl << a << endl;\ncout << \"Here is a.topRows(2):\" << endl;\ncout << a.topRows(2) << endl;\na.topRows(2).setZero();\ncout << \"Now the array a is:\" << endl << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_transpose.cpp",
    "content": "Matrix2i m = Matrix2i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the transpose of m:\" << endl << m.transpose() << endl;\ncout << \"Here is the coefficient (1,0) in the transpose of m:\" << endl\n     << m.transpose()(1,0) << endl;\ncout << \"Let us overwrite this coefficient with the value 0.\" << endl;\nm.transpose()(1,0) = 0;\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_triangularView.cpp",
    "content": "Matrix3i m = Matrix3i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the upper-triangular matrix extracted from m:\" << endl\n     << Matrix3i(m.triangularView<Eigen::Upper>()) << endl;\ncout << \"Here is the strictly-upper-triangular matrix extracted from m:\" << endl\n     << Matrix3i(m.triangularView<Eigen::StrictlyUpper>()) << endl;\ncout << \"Here is the unit-lower-triangular matrix extracted from m:\" << endl\n     << Matrix3i(m.triangularView<Eigen::UnitLower>()) << endl;\n// FIXME need to implement output for triangularViews (Bug 885)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_zero.cpp",
    "content": "cout << Matrix2d::Zero() << endl;\ncout << RowVector4i::Zero() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_zero_int.cpp",
    "content": "cout << RowVectorXi::Zero(4) << endl;\ncout << VectorXf::Zero(2) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/MatrixBase_zero_int_int.cpp",
    "content": "cout << MatrixXi::Zero(2,3) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Matrix_Map_stride.cpp",
    "content": "Matrix4i A;\nA << 1,  2,  3,  4,\n     5,  6,  7,  8,\n     9, 10, 11, 12,\n    13, 14, 15, 16;\n\nstd::cout << Matrix2i::Map(&A(1,1),Stride<8,2>()) << std::endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Matrix_initializer_list_23_cxx11.cpp",
    "content": "MatrixXd m {\n  {1, 2, 3},\n  {4, 5, 6}\n};\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Matrix_initializer_list_vector_cxx11.cpp",
    "content": "VectorXi v {{1, 2}};\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Matrix_resize_NoChange_int.cpp",
    "content": "MatrixXd m(3,4);\nm.resize(NoChange, 5);\ncout << \"m: \" << m.rows() << \" rows, \" << m.cols() << \" cols\" << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Matrix_resize_int.cpp",
    "content": "VectorXd v(10);\nv.resize(3);\nRowVector3d w;\nw.resize(3); // this is legal, but has no effect\ncout << \"v: \" << v.rows() << \" rows, \" << v.cols() << \" cols\" << endl;\ncout << \"w: \" << w.rows() << \" rows, \" << w.cols() << \" cols\" << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Matrix_resize_int_NoChange.cpp",
    "content": "MatrixXd m(3,4);\nm.resize(5, NoChange);\ncout << \"m: \" << m.rows() << \" rows, \" << m.cols() << \" cols\" << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Matrix_resize_int_int.cpp",
    "content": "MatrixXd m(2,3);\nm << 1,2,3,4,5,6;\ncout << \"here's the 2x3 matrix m:\" << endl << m << endl;\ncout << \"let's resize m to 3x2. This is a conservative resizing because 2*3==3*2.\" << endl;\nm.resize(3,2);\ncout << \"here's the 3x2 matrix m:\" << endl << m << endl;\ncout << \"now let's resize m to size 2x2. This is NOT a conservative resizing, so it becomes uninitialized:\" << endl;\nm.resize(2,2);\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Matrix_setConstant_int.cpp",
    "content": "VectorXf v;\nv.setConstant(3, 5);\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Matrix_setConstant_int_int.cpp",
    "content": "MatrixXf m;\nm.setConstant(3, 3, 5);\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Matrix_setIdentity_int_int.cpp",
    "content": "MatrixXf m;\nm.setIdentity(3, 3);\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Matrix_setOnes_int.cpp",
    "content": "VectorXf v;\nv.setOnes(3);\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Matrix_setOnes_int_int.cpp",
    "content": "MatrixXf m;\nm.setOnes(3, 3);\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Matrix_setRandom_int.cpp",
    "content": "VectorXf v;\nv.setRandom(3);\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Matrix_setRandom_int_int.cpp",
    "content": "MatrixXf m;\nm.setRandom(3, 3);\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Matrix_setZero_int.cpp",
    "content": "VectorXf v;\nv.setZero(3);\ncout << v << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Matrix_setZero_int_int.cpp",
    "content": "MatrixXf m;\nm.setZero(3, 3);\ncout << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Matrix_variadic_ctor_cxx11.cpp",
    "content": "Matrix<int, 1, 6> a(1, 2, 3, 4, 5, 6);\nMatrix<int, 3, 1> b {1, 2, 3};\ncout << a << \"\\n\\n\" << b << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/PartialPivLU_solve.cpp",
    "content": "MatrixXd A = MatrixXd::Random(3,3);\nMatrixXd B = MatrixXd::Random(3,2);\ncout << \"Here is the invertible matrix A:\" << endl << A << endl;\ncout << \"Here is the matrix B:\" << endl << B << endl;\nMatrixXd X = A.lu().solve(B);\ncout << \"Here is the (unique) solution X to the equation AX=B:\" << endl << X << endl;\ncout << \"Relative error: \" << (A*X-B).norm() / B.norm() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/PartialRedux_count.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\nMatrix<ptrdiff_t, 3, 1> res = (m.array() >= 0.5).rowwise().count();\ncout << \"Here is the count of elements larger or equal than 0.5 of each row:\" << endl;\ncout << res << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/PartialRedux_maxCoeff.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the maximum of each column:\" << endl << m.colwise().maxCoeff() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/PartialRedux_minCoeff.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the minimum of each column:\" << endl << m.colwise().minCoeff() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/PartialRedux_norm.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the norm of each column:\" << endl << m.colwise().norm() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/PartialRedux_prod.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the product of each row:\" << endl << m.rowwise().prod() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/PartialRedux_squaredNorm.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the square norm of each row:\" << endl << m.rowwise().squaredNorm() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/PartialRedux_sum.cpp",
    "content": "Matrix3d m = Matrix3d::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the sum of each row:\" << endl << m.rowwise().sum() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/RealQZ_compute.cpp",
    "content": "MatrixXf A = MatrixXf::Random(4,4);\nMatrixXf B = MatrixXf::Random(4,4);\nRealQZ<MatrixXf> qz(4); // preallocate space for 4x4 matrices\nqz.compute(A,B);  // A = Q S Z,  B = Q T Z\n\n// print original matrices and result of decomposition\ncout << \"A:\\n\" << A << \"\\n\" << \"B:\\n\" << B << \"\\n\";\ncout << \"S:\\n\" << qz.matrixS() << \"\\n\" << \"T:\\n\" << qz.matrixT() << \"\\n\";\ncout << \"Q:\\n\" << qz.matrixQ() << \"\\n\" << \"Z:\\n\" << qz.matrixZ() << \"\\n\";\n\n// verify precision\ncout << \"\\nErrors:\"\n  << \"\\n|A-QSZ|: \" << (A-qz.matrixQ()*qz.matrixS()*qz.matrixZ()).norm()\n  << \", |B-QTZ|: \" << (B-qz.matrixQ()*qz.matrixT()*qz.matrixZ()).norm()\n  << \"\\n|QQ* - I|: \" << (qz.matrixQ()*qz.matrixQ().adjoint() - MatrixXf::Identity(4,4)).norm()\n  << \", |ZZ* - I|: \" << (qz.matrixZ()*qz.matrixZ().adjoint() - MatrixXf::Identity(4,4)).norm()\n  << \"\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/RealSchur_RealSchur_MatrixType.cpp",
    "content": "MatrixXd A = MatrixXd::Random(6,6);\ncout << \"Here is a random 6x6 matrix, A:\" << endl << A << endl << endl;\n\nRealSchur<MatrixXd> schur(A);\ncout << \"The orthogonal matrix U is:\" << endl << schur.matrixU() << endl;\ncout << \"The quasi-triangular matrix T is:\" << endl << schur.matrixT() << endl << endl;\n\nMatrixXd U = schur.matrixU();\nMatrixXd T = schur.matrixT();\ncout << \"U * T * U^T = \" << endl << U * T * U.transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/RealSchur_compute.cpp",
    "content": "MatrixXf A = MatrixXf::Random(4,4);\nRealSchur<MatrixXf> schur(4);\nschur.compute(A, /* computeU = */ false);\ncout << \"The matrix T in the decomposition of A is:\" << endl << schur.matrixT() << endl;\nschur.compute(A.inverse(), /* computeU = */ false);\ncout << \"The matrix T in the decomposition of A^(-1) is:\" << endl << schur.matrixT() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/SelfAdjointEigenSolver_SelfAdjointEigenSolver.cpp",
    "content": "SelfAdjointEigenSolver<Matrix4f> es;\nMatrix4f X = Matrix4f::Random(4,4);\nMatrix4f A = X + X.transpose();\nes.compute(A);\ncout << \"The eigenvalues of A are: \" << es.eigenvalues().transpose() << endl;\nes.compute(A + Matrix4f::Identity(4,4)); // re-use es to compute eigenvalues of A+I\ncout << \"The eigenvalues of A+I are: \" << es.eigenvalues().transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/SelfAdjointEigenSolver_SelfAdjointEigenSolver_MatrixType.cpp",
    "content": "MatrixXd X = MatrixXd::Random(5,5);\nMatrixXd A = X + X.transpose();\ncout << \"Here is a random symmetric 5x5 matrix, A:\" << endl << A << endl << endl;\n\nSelfAdjointEigenSolver<MatrixXd> es(A);\ncout << \"The eigenvalues of A are:\" << endl << es.eigenvalues() << endl;\ncout << \"The matrix of eigenvectors, V, is:\" << endl << es.eigenvectors() << endl << endl;\n\ndouble lambda = es.eigenvalues()[0];\ncout << \"Consider the first eigenvalue, lambda = \" << lambda << endl;\nVectorXd v = es.eigenvectors().col(0);\ncout << \"If v is the corresponding eigenvector, then lambda * v = \" << endl << lambda * v << endl;\ncout << \"... and A * v = \" << endl << A * v << endl << endl;\n\nMatrixXd D = es.eigenvalues().asDiagonal();\nMatrixXd V = es.eigenvectors();\ncout << \"Finally, V * D * V^(-1) = \" << endl << V * D * V.inverse() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/SelfAdjointEigenSolver_SelfAdjointEigenSolver_MatrixType2.cpp",
    "content": "MatrixXd X = MatrixXd::Random(5,5);\nMatrixXd A = X + X.transpose();\ncout << \"Here is a random symmetric matrix, A:\" << endl << A << endl;\nX = MatrixXd::Random(5,5);\nMatrixXd B = X * X.transpose();\ncout << \"and a random postive-definite matrix, B:\" << endl << B << endl << endl;\n\nGeneralizedSelfAdjointEigenSolver<MatrixXd> es(A,B);\ncout << \"The eigenvalues of the pencil (A,B) are:\" << endl << es.eigenvalues() << endl;\ncout << \"The matrix of eigenvectors, V, is:\" << endl << es.eigenvectors() << endl << endl;\n\ndouble lambda = es.eigenvalues()[0];\ncout << \"Consider the first eigenvalue, lambda = \" << lambda << endl;\nVectorXd v = es.eigenvectors().col(0);\ncout << \"If v is the corresponding eigenvector, then A * v = \" << endl << A * v << endl;\ncout << \"... and lambda * B * v = \" << endl << lambda * B * v << endl << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/SelfAdjointEigenSolver_compute_MatrixType.cpp",
    "content": "SelfAdjointEigenSolver<MatrixXf> es(4);\nMatrixXf X = MatrixXf::Random(4,4);\nMatrixXf A = X + X.transpose();\nes.compute(A);\ncout << \"The eigenvalues of A are: \" << es.eigenvalues().transpose() << endl;\nes.compute(A + MatrixXf::Identity(4,4)); // re-use es to compute eigenvalues of A+I\ncout << \"The eigenvalues of A+I are: \" << es.eigenvalues().transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/SelfAdjointEigenSolver_compute_MatrixType2.cpp",
    "content": "MatrixXd X = MatrixXd::Random(5,5);\nMatrixXd A = X * X.transpose();\nX = MatrixXd::Random(5,5);\nMatrixXd B = X * X.transpose();\n\nGeneralizedSelfAdjointEigenSolver<MatrixXd> es(A,B,EigenvaluesOnly);\ncout << \"The eigenvalues of the pencil (A,B) are:\" << endl << es.eigenvalues() << endl;\nes.compute(B,A,false);\ncout << \"The eigenvalues of the pencil (B,A) are:\" << endl << es.eigenvalues() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/SelfAdjointEigenSolver_eigenvalues.cpp",
    "content": "MatrixXd ones = MatrixXd::Ones(3,3);\nSelfAdjointEigenSolver<MatrixXd> es(ones);\ncout << \"The eigenvalues of the 3x3 matrix of ones are:\" \n     << endl << es.eigenvalues() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/SelfAdjointEigenSolver_eigenvectors.cpp",
    "content": "MatrixXd ones = MatrixXd::Ones(3,3);\nSelfAdjointEigenSolver<MatrixXd> es(ones);\ncout << \"The first eigenvector of the 3x3 matrix of ones is:\" \n     << endl << es.eigenvectors().col(1) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/SelfAdjointEigenSolver_operatorInverseSqrt.cpp",
    "content": "MatrixXd X = MatrixXd::Random(4,4);\nMatrixXd A = X * X.transpose();\ncout << \"Here is a random positive-definite matrix, A:\" << endl << A << endl << endl;\n\nSelfAdjointEigenSolver<MatrixXd> es(A);\ncout << \"The inverse square root of A is: \" << endl;\ncout << es.operatorInverseSqrt() << endl;\ncout << \"We can also compute it with operatorSqrt() and inverse(). That yields: \" << endl;\ncout << es.operatorSqrt().inverse() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/SelfAdjointEigenSolver_operatorSqrt.cpp",
    "content": "MatrixXd X = MatrixXd::Random(4,4);\nMatrixXd A = X * X.transpose();\ncout << \"Here is a random positive-definite matrix, A:\" << endl << A << endl << endl;\n\nSelfAdjointEigenSolver<MatrixXd> es(A);\nMatrixXd sqrtA = es.operatorSqrt();\ncout << \"The square root of A is: \" << endl << sqrtA << endl;\ncout << \"If we square this, we get: \" << endl << sqrtA*sqrtA << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/SelfAdjointView_eigenvalues.cpp",
    "content": "MatrixXd ones = MatrixXd::Ones(3,3);\nVectorXd eivals = ones.selfadjointView<Lower>().eigenvalues();\ncout << \"The eigenvalues of the 3x3 matrix of ones are:\" << endl << eivals << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/SelfAdjointView_operatorNorm.cpp",
    "content": "MatrixXd ones = MatrixXd::Ones(3,3);\ncout << \"The operator norm of the 3x3 matrix of ones is \"\n     << ones.selfadjointView<Lower>().operatorNorm() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Slicing_arrayexpr.cpp",
    "content": "ArrayXi ind(5); ind<<4,2,5,5,3;\nMatrixXi A = MatrixXi::Random(4,6);\ncout << \"Initial matrix A:\\n\" << A << \"\\n\\n\";\ncout << \"A(all,ind-1):\\n\" << A(all,ind-1) << \"\\n\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Slicing_custom_padding_cxx11.cpp",
    "content": "struct pad {\n  Index size() const { return out_size; }\n  Index operator[] (Index i) const { return std::max<Index>(0,i-(out_size-in_size)); }\n  Index in_size, out_size;\n};\n\nMatrix3i A;\nA.reshaped() = VectorXi::LinSpaced(9,1,9);\ncout << \"Initial matrix A:\\n\" << A << \"\\n\\n\";\nMatrixXi B(5,5);\nB = A(pad{3,5}, pad{3,5});\ncout << \"A(pad{3,N}, pad{3,N}):\\n\" << B << \"\\n\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Slicing_rawarray_cxx11.cpp",
    "content": "#if EIGEN_HAS_STATIC_ARRAY_TEMPLATE\nMatrixXi A = MatrixXi::Random(4,6);\ncout << \"Initial matrix A:\\n\" << A << \"\\n\\n\";\ncout << \"A(all,{4,2,5,5,3}):\\n\" << A(all,{4,2,5,5,3}) << \"\\n\\n\";\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Slicing_stdvector_cxx11.cpp",
    "content": "std::vector<int> ind{4,2,5,5,3};\nMatrixXi A = MatrixXi::Random(4,6);\ncout << \"Initial matrix A:\\n\" << A << \"\\n\\n\";\ncout << \"A(all,ind):\\n\" << A(all,ind) << \"\\n\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/SparseMatrix_coeffs.cpp",
    "content": "SparseMatrix<double> A(3,3);\nA.insert(1,2) = 0;\nA.insert(0,1) = 1;\nA.insert(2,0) = 2;\nA.makeCompressed();\ncout << \"The matrix A is:\" << endl << MatrixXd(A) << endl;\ncout << \"it has \" << A.nonZeros() << \" stored non zero coefficients that are: \" << A.coeffs().transpose() << endl;\nA.coeffs() += 10;\ncout << \"After adding 10 to every stored non zero coefficient, the matrix A is:\" << endl << MatrixXd(A) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/TopicAliasing_block.cpp",
    "content": "MatrixXi mat(3,3); \nmat << 1, 2, 3,   4, 5, 6,   7, 8, 9;\ncout << \"Here is the matrix mat:\\n\" << mat << endl;\n\n// This assignment shows the aliasing problem\nmat.bottomRightCorner(2,2) = mat.topLeftCorner(2,2);\ncout << \"After the assignment, mat = \\n\" << mat << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/TopicAliasing_block_correct.cpp",
    "content": "MatrixXi mat(3,3); \nmat << 1, 2, 3,   4, 5, 6,   7, 8, 9;\ncout << \"Here is the matrix mat:\\n\" << mat << endl;\n\n// The eval() solves the aliasing problem\nmat.bottomRightCorner(2,2) = mat.topLeftCorner(2,2).eval();\ncout << \"After the assignment, mat = \\n\" << mat << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/TopicAliasing_cwise.cpp",
    "content": "MatrixXf mat(2,2); \nmat << 1, 2,  4, 7;\ncout << \"Here is the matrix mat:\\n\" << mat << endl << endl;\n\nmat = 2 * mat;\ncout << \"After 'mat = 2 * mat', mat = \\n\" << mat << endl << endl;\n\n\nmat = mat - MatrixXf::Identity(2,2);\ncout << \"After the subtraction, it becomes\\n\" << mat << endl << endl;\n\n\nArrayXXf arr = mat;\narr = arr.square();\ncout << \"After squaring, it becomes\\n\" << arr << endl << endl;\n\n// Combining all operations in one statement:\nmat << 1, 2,  4, 7;\nmat = (2 * mat - MatrixXf::Identity(2,2)).array().square();\ncout << \"Doing everything at once yields\\n\" << mat << endl << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/TopicAliasing_mult1.cpp",
    "content": "MatrixXf matA(2,2); \nmatA << 2, 0,  0, 2;\nmatA = matA * matA;\ncout << matA;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/TopicAliasing_mult2.cpp",
    "content": "MatrixXf matA(2,2), matB(2,2); \nmatA << 2, 0,  0, 2;\n\n// Simple but not quite as efficient\nmatB = matA * matA;\ncout << matB << endl << endl;\n\n// More complicated but also more efficient\nmatB.noalias() = matA * matA;\ncout << matB;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/TopicAliasing_mult3.cpp",
    "content": "MatrixXf matA(2,2); \nmatA << 2, 0,  0, 2;\nmatA.noalias() = matA * matA;\ncout << matA;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/TopicAliasing_mult4.cpp",
    "content": "MatrixXf A(2,2), B(3,2);\nB << 2, 0,  0, 3, 1, 1;\nA << 2, 0, 0, -2;\nA = (B * A).cwiseAbs();\ncout << A;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/TopicAliasing_mult5.cpp",
    "content": "MatrixXf A(2,2), B(3,2);\nB << 2, 0,  0, 3, 1, 1;\nA << 2, 0, 0, -2;\nA = (B * A).eval().cwiseAbs();\ncout << A;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/TopicStorageOrders_example.cpp",
    "content": "Matrix<int, 3, 4, ColMajor> Acolmajor;\nAcolmajor << 8, 2, 2, 9,\n             9, 1, 4, 4,\n\t     3, 5, 4, 5;\ncout << \"The matrix A:\" << endl;\ncout << Acolmajor << endl << endl; \n\ncout << \"In memory (column-major):\" << endl;\nfor (int i = 0; i < Acolmajor.size(); i++)\n  cout << *(Acolmajor.data() + i) << \"  \";\ncout << endl << endl;\n\nMatrix<int, 3, 4, RowMajor> Arowmajor = Acolmajor;\ncout << \"In memory (row-major):\" << endl;\nfor (int i = 0; i < Arowmajor.size(); i++)\n  cout << *(Arowmajor.data() + i) << \"  \";\ncout << endl;\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Triangular_solve.cpp",
    "content": "Matrix3d m = Matrix3d::Zero();\nm.triangularView<Eigen::Upper>().setOnes();\ncout << \"Here is the matrix m:\\n\" << m << endl;\nMatrix3d n = Matrix3d::Ones();\nn.triangularView<Eigen::Lower>() *= 2;\ncout << \"Here is the matrix n:\\n\" << n << endl;\ncout << \"And now here is m.inverse()*n, taking advantage of the fact that\"\n        \" m is upper-triangular:\\n\"\n     << m.triangularView<Eigen::Upper>().solve(n) << endl;\ncout << \"And this is n*m.inverse():\\n\"\n     << m.triangularView<Eigen::Upper>().solve<Eigen::OnTheRight>(n);\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tridiagonalization_Tridiagonalization_MatrixType.cpp",
    "content": "MatrixXd X = MatrixXd::Random(5,5);\nMatrixXd A = X + X.transpose();\ncout << \"Here is a random symmetric 5x5 matrix:\" << endl << A << endl << endl;\nTridiagonalization<MatrixXd> triOfA(A);\nMatrixXd Q = triOfA.matrixQ();\ncout << \"The orthogonal matrix Q is:\" << endl << Q << endl;\nMatrixXd T = triOfA.matrixT();\ncout << \"The tridiagonal matrix T is:\" << endl << T << endl << endl;\ncout << \"Q * T * Q^T = \" << endl << Q * T * Q.transpose() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tridiagonalization_compute.cpp",
    "content": "Tridiagonalization<MatrixXf> tri;\nMatrixXf X = MatrixXf::Random(4,4);\nMatrixXf A = X + X.transpose();\ntri.compute(A);\ncout << \"The matrix T in the tridiagonal decomposition of A is: \" << endl;\ncout << tri.matrixT() << endl;\ntri.compute(2*A); // re-use tri to compute eigenvalues of 2A\ncout << \"The matrix T in the tridiagonal decomposition of 2A is: \" << endl;\ncout << tri.matrixT() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tridiagonalization_decomposeInPlace.cpp",
    "content": "MatrixXd X = MatrixXd::Random(5,5);\nMatrixXd A = X + X.transpose();\ncout << \"Here is a random symmetric 5x5 matrix:\" << endl << A << endl << endl;\n\nVectorXd diag(5);\nVectorXd subdiag(4);\ninternal::tridiagonalization_inplace(A, diag, subdiag, true);\ncout << \"The orthogonal matrix Q is:\" << endl << A << endl;\ncout << \"The diagonal of the tridiagonal matrix T is:\" << endl << diag << endl;\ncout << \"The subdiagonal of the tridiagonal matrix T is:\" << endl << subdiag << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tridiagonalization_diagonal.cpp",
    "content": "MatrixXcd X = MatrixXcd::Random(4,4);\nMatrixXcd A = X + X.adjoint();\ncout << \"Here is a random self-adjoint 4x4 matrix:\" << endl << A << endl << endl;\n\nTridiagonalization<MatrixXcd> triOfA(A);\nMatrixXd T = triOfA.matrixT();\ncout << \"The tridiagonal matrix T is:\" << endl << T << endl << endl;\n\ncout << \"We can also extract the diagonals of T directly ...\" << endl;\nVectorXd diag = triOfA.diagonal();\ncout << \"The diagonal is:\" << endl << diag << endl; \nVectorXd subdiag = triOfA.subDiagonal();\ncout << \"The subdiagonal is:\" << endl << subdiag << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tridiagonalization_householderCoefficients.cpp",
    "content": "Matrix4d X = Matrix4d::Random(4,4);\nMatrix4d A = X + X.transpose();\ncout << \"Here is a random symmetric 4x4 matrix:\" << endl << A << endl;\nTridiagonalization<Matrix4d> triOfA(A);\nVector3d hc = triOfA.householderCoefficients();\ncout << \"The vector of Householder coefficients is:\" << endl << hc << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tridiagonalization_packedMatrix.cpp",
    "content": "Matrix4d X = Matrix4d::Random(4,4);\nMatrix4d A = X + X.transpose();\ncout << \"Here is a random symmetric 4x4 matrix:\" << endl << A << endl;\nTridiagonalization<Matrix4d> triOfA(A);\nMatrix4d pm = triOfA.packedMatrix();\ncout << \"The packed matrix M is:\" << endl << pm << endl;\ncout << \"The diagonal and subdiagonal corresponds to the matrix T, which is:\" \n     << endl << triOfA.matrixT() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_AdvancedInitialization_Block.cpp",
    "content": "MatrixXf matA(2, 2);\nmatA << 1, 2, 3, 4;\nMatrixXf matB(4, 4);\nmatB << matA, matA/10, matA/10, matA;\nstd::cout << matB << std::endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_AdvancedInitialization_CommaTemporary.cpp",
    "content": "MatrixXf mat = MatrixXf::Random(2, 3);\nstd::cout << mat << std::endl << std::endl;\nmat = (MatrixXf(2,2) << 0, 1, 1, 0).finished() * mat;\nstd::cout << mat << std::endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_AdvancedInitialization_Join.cpp",
    "content": "RowVectorXd vec1(3);\nvec1 << 1, 2, 3;\nstd::cout << \"vec1 = \" << vec1 << std::endl;\n\nRowVectorXd vec2(4);\nvec2 << 1, 4, 9, 16;\nstd::cout << \"vec2 = \" << vec2 << std::endl;\n\nRowVectorXd joined(7);\njoined << vec1, vec2;\nstd::cout << \"joined = \" << joined << std::endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_AdvancedInitialization_LinSpaced.cpp",
    "content": "ArrayXXf table(10, 4);\ntable.col(0) = ArrayXf::LinSpaced(10, 0, 90);\ntable.col(1) = M_PI / 180 * table.col(0);\ntable.col(2) = table.col(1).sin();\ntable.col(3) = table.col(1).cos();\nstd::cout << \"  Degrees   Radians      Sine    Cosine\\n\";\nstd::cout << table << std::endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_AdvancedInitialization_ThreeWays.cpp",
    "content": "const int size = 6;\nMatrixXd mat1(size, size);\nmat1.topLeftCorner(size/2, size/2)     = MatrixXd::Zero(size/2, size/2);\nmat1.topRightCorner(size/2, size/2)    = MatrixXd::Identity(size/2, size/2);\nmat1.bottomLeftCorner(size/2, size/2)  = MatrixXd::Identity(size/2, size/2);\nmat1.bottomRightCorner(size/2, size/2) = MatrixXd::Zero(size/2, size/2);\nstd::cout << mat1 << std::endl << std::endl;\n\nMatrixXd mat2(size, size);\nmat2.topLeftCorner(size/2, size/2).setZero();\nmat2.topRightCorner(size/2, size/2).setIdentity();\nmat2.bottomLeftCorner(size/2, size/2).setIdentity();\nmat2.bottomRightCorner(size/2, size/2).setZero();\nstd::cout << mat2 << std::endl << std::endl;\n\nMatrixXd mat3(size, size);\nmat3 << MatrixXd::Zero(size/2, size/2), MatrixXd::Identity(size/2, size/2),\n        MatrixXd::Identity(size/2, size/2), MatrixXd::Zero(size/2, size/2);\nstd::cout << mat3 << std::endl;\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_AdvancedInitialization_Zero.cpp",
    "content": "std::cout << \"A fixed-size array:\\n\";\nArray33f a1 = Array33f::Zero();\nstd::cout << a1 << \"\\n\\n\";\n\n\nstd::cout << \"A one-dimensional dynamic-size array:\\n\";\nArrayXf a2 = ArrayXf::Zero(3);\nstd::cout << a2 << \"\\n\\n\";\n\n\nstd::cout << \"A two-dimensional dynamic-size array:\\n\";\nArrayXXf a3 = ArrayXXf::Zero(3, 4);\nstd::cout << a3 << \"\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_Map_rowmajor.cpp",
    "content": "int array[8];\nfor(int i = 0; i < 8; ++i) array[i] = i;\ncout << \"Column-major:\\n\" << Map<Matrix<int,2,4> >(array) << endl;\ncout << \"Row-major:\\n\" << Map<Matrix<int,2,4,RowMajor> >(array) << endl;\ncout << \"Row-major using stride:\\n\" <<\n  Map<Matrix<int,2,4>, Unaligned, Stride<1,4> >(array) << endl;\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_Map_using.cpp",
    "content": "typedef Matrix<float,1,Dynamic> MatrixType;\ntypedef Map<MatrixType> MapType;\ntypedef Map<const MatrixType> MapTypeConst;   // a read-only map\nconst int n_dims = 5;\n  \nMatrixType m1(n_dims), m2(n_dims);\nm1.setRandom();\nm2.setRandom();\nfloat *p = &m2(0);  // get the address storing the data for m2\nMapType m2map(p,m2.size());   // m2map shares data with m2\nMapTypeConst m2mapconst(p,m2.size());  // a read-only accessor for m2\n\ncout << \"m1: \" << m1 << endl;\ncout << \"m2: \" << m2 << endl;\ncout << \"Squared euclidean distance: \" << (m1-m2).squaredNorm() << endl;\ncout << \"Squared euclidean distance, using map: \" <<\n  (m1-m2map).squaredNorm() << endl;\nm2map(3) = 7;   // this will change m2, since they share the same array\ncout << \"Updated m2: \" << m2 << endl;\ncout << \"m2 coefficient 2, constant accessor: \" << m2mapconst(2) << endl;\n/* m2mapconst(2) = 5; */   // this yields a compile-time error\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_ReshapeMat2Mat.cpp",
    "content": "MatrixXf M1(2,6);    // Column-major storage\nM1 << 1, 2, 3,  4,  5,  6,\n      7, 8, 9, 10, 11, 12;\n\nMap<MatrixXf> M2(M1.data(), 6,2);\ncout << \"M2:\" << endl << M2 << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_ReshapeMat2Vec.cpp",
    "content": "MatrixXf M1(3,3);    // Column-major storage\nM1 << 1, 2, 3,\n      4, 5, 6,\n      7, 8, 9;\n\nMap<RowVectorXf> v1(M1.data(), M1.size());\ncout << \"v1:\" << endl << v1 << endl;\n\nMatrix<float,Dynamic,Dynamic,RowMajor> M2(M1);\nMap<RowVectorXf> v2(M2.data(), M2.size());\ncout << \"v2:\" << endl << v2 << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_SlicingCol.cpp",
    "content": "MatrixXf M1 = MatrixXf::Random(3,8);\ncout << \"Column major input:\" << endl << M1 << \"\\n\";\nMap<MatrixXf,0,OuterStride<> > M2(M1.data(), M1.rows(), (M1.cols()+2)/3, OuterStride<>(M1.outerStride()*3));\ncout << \"1 column over 3:\" << endl << M2 << \"\\n\";\n\ntypedef Matrix<float,Dynamic,Dynamic,RowMajor> RowMajorMatrixXf;\nRowMajorMatrixXf M3(M1);\ncout << \"Row major input:\" << endl << M3 << \"\\n\";\nMap<RowMajorMatrixXf,0,Stride<Dynamic,3> > M4(M3.data(), M3.rows(), (M3.cols()+2)/3,\n                                              Stride<Dynamic,3>(M3.outerStride(),3));\ncout << \"1 column over 3:\" << endl << M4 << \"\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_SlicingVec.cpp",
    "content": "RowVectorXf v = RowVectorXf::LinSpaced(20,0,19);\ncout << \"Input:\" << endl << v << endl;\nMap<RowVectorXf,0,InnerStride<2> > v2(v.data(), v.size()/2);\ncout << \"Even:\" << v2 << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_commainit_01.cpp",
    "content": "Matrix3f m;\nm << 1, 2, 3,\n     4, 5, 6,\n     7, 8, 9;\nstd::cout << m;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_commainit_01b.cpp",
    "content": "Matrix3f m;\nm.row(0) << 1, 2, 3;\nm.block(1,0,2,2) << 4, 5, 7, 8;\nm.col(2).tail(2) << 6, 9;\t\t    \nstd::cout << m;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_commainit_02.cpp",
    "content": "int rows=5, cols=5;\nMatrixXf m(rows,cols);\nm << (Matrix3f() << 1, 2, 3, 4, 5, 6, 7, 8, 9).finished(),\n     MatrixXf::Zero(3,cols-3),\n     MatrixXf::Zero(rows-3,3),\n     MatrixXf::Identity(rows-3,cols-3);\ncout << m;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_range_for_loop_1d_cxx11.cpp",
    "content": "VectorXi v = VectorXi::Random(4);\ncout << \"Here is the vector v:\\n\";\nfor(auto x : v) cout << x << \" \";\ncout << \"\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_range_for_loop_2d_cxx11.cpp",
    "content": "Matrix2i A = Matrix2i::Random();\ncout << \"Here are the coeffs of the 2x2 matrix A:\\n\";\nfor(auto x : A.reshaped())\n  cout << x << \" \";\ncout << \"\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_reshaped_vs_resize_1.cpp",
    "content": "MatrixXi m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.reshaped(2, 8):\" << endl << m.reshaped(2, 8) << endl;\nm.resize(2,8);\ncout << \"Here is the matrix m after m.resize(2,8):\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_reshaped_vs_resize_2.cpp",
    "content": "Matrix<int,Dynamic,Dynamic,RowMajor> m = Matrix4i::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is m.reshaped(2, 8):\" << endl << m.reshaped(2, 8) << endl;\ncout << \"Here is m.reshaped<AutoOrder>(2, 8):\" << endl << m.reshaped<AutoOrder>(2, 8) << endl;\nm.resize(2,8);\ncout << \"Here is the matrix m after m.resize(2,8):\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_solve_matrix_inverse.cpp",
    "content": "Matrix3f A;\nVector3f b;\nA << 1,2,3,  4,5,6,  7,8,10;\nb << 3, 3, 4;\nVector3f x = A.inverse() * b;\ncout << \"The solution is:\" << endl << x << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_solve_multiple_rhs.cpp",
    "content": "Matrix3f A(3,3);\nA << 1,2,3,  4,5,6,  7,8,10;\nMatrix<float,3,2> B;\nB << 3,1, 3,1, 4,1;\nMatrix<float,3,2> X;\nX = A.fullPivLu().solve(B);\ncout << \"The solution with right-hand side (3,3,4) is:\" << endl;\ncout << X.col(0) << endl;\ncout << \"The solution with right-hand side (1,1,1) is:\" << endl;\ncout << X.col(1) << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_solve_reuse_decomposition.cpp",
    "content": "Matrix3f A(3,3);\nA << 1,2,3,  4,5,6,  7,8,10;\nPartialPivLU<Matrix3f> luOfA(A); // compute LU decomposition of A\nVector3f b;\nb << 3,3,4;\nVector3f x;\nx = luOfA.solve(b);\ncout << \"The solution with right-hand side (3,3,4) is:\" << endl;\ncout << x << endl;\nb << 1,1,1;\nx = luOfA.solve(b);\ncout << \"The solution with right-hand side (1,1,1) is:\" << endl;\ncout << x << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_solve_singular.cpp",
    "content": "Matrix3f A;\nVector3f b;\nA << 1,2,3,  4,5,6,  7,8,9;\nb << 3, 3, 4;\ncout << \"Here is the matrix A:\" << endl << A << endl;\ncout << \"Here is the vector b:\" << endl << b << endl;\nVector3f x;\nx = A.lu().solve(b);\ncout << \"The solution is:\" << endl << x << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_solve_triangular.cpp",
    "content": "Matrix3f A;\nVector3f b;\nA << 1,2,3,  0,5,6,  0,0,10;\nb << 3, 3, 4;\ncout << \"Here is the matrix A:\" << endl << A << endl;\ncout << \"Here is the vector b:\" << endl << b << endl;\nVector3f x = A.triangularView<Upper>().solve(b);\ncout << \"The solution is:\" << endl << x << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_solve_triangular_inplace.cpp",
    "content": "Matrix3f A;\nVector3f b;\nA << 1,2,3,  0,5,6,  0,0,10;\nb << 3, 3, 4;\nA.triangularView<Upper>().solveInPlace(b);\ncout << \"The solution is:\" << endl << b << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_std_sort.cpp",
    "content": "Array4i v = Array4i::Random().abs();\ncout << \"Here is the initial vector v:\\n\" << v.transpose() << \"\\n\";\nstd::sort(v.begin(), v.end());\ncout << \"Here is the sorted vector v:\\n\" << v.transpose() << \"\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Tutorial_std_sort_rows_cxx11.cpp",
    "content": "ArrayXXi A = ArrayXXi::Random(4,4).abs();\ncout << \"Here is the initial matrix A:\\n\" << A << \"\\n\";\nfor(auto row : A.rowwise())\n  std::sort(row.begin(), row.end());\ncout << \"Here is the sorted matrix A:\\n\" << A << \"\\n\";\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/VectorwiseOp_homogeneous.cpp",
    "content": "Matrix3Xd M = Matrix3Xd::Random(3,5);\nProjective3d P(Matrix4d::Random());\ncout << \"The matrix M is:\" << endl << M << endl << endl;\ncout << \"M.colwise().homogeneous():\" << endl << M.colwise().homogeneous() << endl << endl;\ncout << \"P * M.colwise().homogeneous():\" << endl << P * M.colwise().homogeneous() << endl << endl;\ncout << \"P * M.colwise().homogeneous().hnormalized(): \" << endl << (P * M.colwise().homogeneous()).colwise().hnormalized() << endl << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/Vectorwise_reverse.cpp",
    "content": "MatrixXi m = MatrixXi::Random(3,4);\ncout << \"Here is the matrix m:\" << endl << m << endl;\ncout << \"Here is the rowwise reverse of m:\" << endl << m.rowwise().reverse() << endl;\ncout << \"Here is the colwise reverse of m:\" << endl << m.colwise().reverse() << endl;\n\ncout << \"Here is the coefficient (1,0) in the rowise reverse of m:\" << endl\n<< m.rowwise().reverse()(1,0) << endl;\ncout << \"Let us overwrite this coefficient with the value 4.\" << endl;\n//m.colwise().reverse()(1,0) = 4;\ncout << \"Now the matrix m is:\" << endl << m << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/class_FullPivLU.cpp",
    "content": "typedef Matrix<double, 5, 3> Matrix5x3;\ntypedef Matrix<double, 5, 5> Matrix5x5;\nMatrix5x3 m = Matrix5x3::Random();\ncout << \"Here is the matrix m:\" << endl << m << endl;\nEigen::FullPivLU<Matrix5x3> lu(m);\ncout << \"Here is, up to permutations, its LU decomposition matrix:\"\n     << endl << lu.matrixLU() << endl;\ncout << \"Here is the L part:\" << endl;\nMatrix5x5 l = Matrix5x5::Identity();\nl.block<5,3>(0,0).triangularView<StrictlyLower>() = lu.matrixLU();\ncout << l << endl;\ncout << \"Here is the U part:\" << endl;\nMatrix5x3 u = lu.matrixLU().triangularView<Upper>();\ncout << u << endl;\ncout << \"Let us now reconstruct the original matrix m:\" << endl;\ncout << lu.permutationP().inverse() * l * u * lu.permutationQ().inverse() << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/compile_snippet.cpp.in",
    "content": "static bool eigen_did_assert = false;\n#define eigen_assert(X) if(!eigen_did_assert && !(X)){ std::cout << \"### Assertion raised in \" << __FILE__ << \":\" << __LINE__ << \":\\n\" #X << \"\\n### The following would happen without assertions:\\n\"; eigen_did_assert = true;}\n\n#include <iostream>\n#include <Eigen/Eigen>\n\n#ifndef M_PI\n#define M_PI 3.1415926535897932384626433832795\n#endif\n\n\nusing namespace Eigen;\nusing namespace std;\n\nint main(int, char**)\n{\n  cout.precision(3);\n// intentionally remove indentation of snippet\n{\n${snippet_source_code}\n}\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/tut_arithmetic_redux_minmax.cpp",
    "content": "  Matrix3f m = Matrix3f::Random();\n  std::ptrdiff_t i, j;\n  float minOfM = m.minCoeff(&i,&j);\n  cout << \"Here is the matrix m:\\n\" << m << endl;\n  cout << \"Its minimum coefficient (\" << minOfM \n       << \") is at position (\" << i << \",\" << j << \")\\n\\n\";\n\n  RowVector4i v = RowVector4i::Random();\n  int maxOfV = v.maxCoeff(&i);\n  cout << \"Here is the vector v: \" << v << endl;\n  cout << \"Its maximum coefficient (\" << maxOfV \n       << \") is at position \" << i << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/tut_arithmetic_transpose_aliasing.cpp",
    "content": "Matrix2i a; a << 1, 2, 3, 4;\ncout << \"Here is the matrix a:\\n\" << a << endl;\n\na = a.transpose(); // !!! do NOT do this !!!\ncout << \"and the result of the aliasing effect:\\n\" << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/tut_arithmetic_transpose_conjugate.cpp",
    "content": "MatrixXcf a = MatrixXcf::Random(2,2);\ncout << \"Here is the matrix a\\n\" << a << endl;\n\ncout << \"Here is the matrix a^T\\n\" << a.transpose() << endl;\n\n\ncout << \"Here is the conjugate of a\\n\" << a.conjugate() << endl;\n\n\ncout << \"Here is the matrix a^*\\n\" << a.adjoint() << endl;\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/tut_arithmetic_transpose_inplace.cpp",
    "content": "MatrixXf a(2,3); a << 1, 2, 3, 4, 5, 6;\ncout << \"Here is the initial matrix a:\\n\" << a << endl;\n\n\na.transposeInPlace();\ncout << \"and after being transposed:\\n\" << a << endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/snippets/tut_matrix_assignment_resizing.cpp",
    "content": "MatrixXf a(2,2);\nstd::cout << \"a is of size \" << a.rows() << \"x\" << a.cols() << std::endl;\nMatrixXf b(3,3);\na = b;\nstd::cout << \"a is now of size \" << a.rows() << \"x\" << a.cols() << std::endl;\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/special_examples/CMakeLists.txt",
    "content": "if(NOT EIGEN_TEST_NOQT)\n  find_package(Qt4)\n  if(QT4_FOUND)\n    include(${QT_USE_FILE})\n  endif()\nendif()\n\nif(QT4_FOUND)\n  add_executable(Tutorial_sparse_example Tutorial_sparse_example.cpp Tutorial_sparse_example_details.cpp)\n  target_link_libraries(Tutorial_sparse_example ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO} ${QT_QTCORE_LIBRARY} ${QT_QTGUI_LIBRARY})\n\n  add_custom_command(\n    TARGET Tutorial_sparse_example\n    POST_BUILD\n    COMMAND ${CMAKE_COMMAND} -E make_directory ${CMAKE_CURRENT_BINARY_DIR}/../html/\n    COMMAND Tutorial_sparse_example ARGS ${CMAKE_CURRENT_BINARY_DIR}/../html/Tutorial_sparse_example.jpeg\n  )\n\n  add_dependencies(all_examples Tutorial_sparse_example)\nendif()\n\nif(EIGEN_COMPILER_SUPPORT_CPP11)\n  add_executable(random_cpp11 random_cpp11.cpp)\n  target_link_libraries(random_cpp11 ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO})\n  add_dependencies(all_examples random_cpp11)\n  ei_add_target_property(random_cpp11 COMPILE_FLAGS \"-std=c++11\")\n\n  add_custom_command(\n    TARGET random_cpp11\n    POST_BUILD\n    COMMAND random_cpp11\n    ARGS >${CMAKE_CURRENT_BINARY_DIR}/random_cpp11.out\n  )\nendif()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/special_examples/Tutorial_sparse_example.cpp",
    "content": "#include <Eigen/Sparse>\n#include <vector>\n#include <iostream>\n\ntypedef Eigen::SparseMatrix<double> SpMat; // declares a column-major sparse matrix type of double\ntypedef Eigen::Triplet<double> T;\n\nvoid buildProblem(std::vector<T>& coefficients, Eigen::VectorXd& b, int n);\nvoid saveAsBitmap(const Eigen::VectorXd& x, int n, const char* filename);\n\nint main(int argc, char** argv)\n{\n  if(argc!=2) {\n    std::cerr << \"Error: expected one and only one argument.\\n\";\n    return -1;\n  }\n  \n  int n = 300;  // size of the image\n  int m = n*n;  // number of unknowns (=number of pixels)\n\n  // Assembly:\n  std::vector<T> coefficients;            // list of non-zeros coefficients\n  Eigen::VectorXd b(m);                   // the right hand side-vector resulting from the constraints\n  buildProblem(coefficients, b, n);\n\n  SpMat A(m,m);\n  A.setFromTriplets(coefficients.begin(), coefficients.end());\n\n  // Solving:\n  Eigen::SimplicialCholesky<SpMat> chol(A);  // performs a Cholesky factorization of A\n  Eigen::VectorXd x = chol.solve(b);         // use the factorization to solve for the given right hand side\n\n  // Export the result to a file:\n  saveAsBitmap(x, n, argv[1]);\n\n  return 0;\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/special_examples/Tutorial_sparse_example_details.cpp",
    "content": "#include <Eigen/Sparse>\n#include <vector>\n#include <QImage>\n\ntypedef Eigen::SparseMatrix<double> SpMat; // declares a column-major sparse matrix type of double\ntypedef Eigen::Triplet<double> T;\n\nvoid insertCoefficient(int id, int i, int j, double w, std::vector<T>& coeffs,\n                       Eigen::VectorXd& b, const Eigen::VectorXd& boundary)\n{\n  int n = int(boundary.size());\n  int id1 = i+j*n;\n\n        if(i==-1 || i==n) b(id) -= w * boundary(j); // constrained coefficient\n  else  if(j==-1 || j==n) b(id) -= w * boundary(i); // constrained coefficient\n  else  coeffs.push_back(T(id,id1,w));              // unknown coefficient\n}\n\nvoid buildProblem(std::vector<T>& coefficients, Eigen::VectorXd& b, int n)\n{\n  b.setZero();\n  Eigen::ArrayXd boundary = Eigen::ArrayXd::LinSpaced(n, 0,M_PI).sin().pow(2);\n  for(int j=0; j<n; ++j)\n  {\n    for(int i=0; i<n; ++i)\n    {\n      int id = i+j*n;\n      insertCoefficient(id, i-1,j, -1, coefficients, b, boundary);\n      insertCoefficient(id, i+1,j, -1, coefficients, b, boundary);\n      insertCoefficient(id, i,j-1, -1, coefficients, b, boundary);\n      insertCoefficient(id, i,j+1, -1, coefficients, b, boundary);\n      insertCoefficient(id, i,j,    4, coefficients, b, boundary);\n    }\n  }\n}\n\nvoid saveAsBitmap(const Eigen::VectorXd& x, int n, const char* filename)\n{\n  Eigen::Array<unsigned char,Eigen::Dynamic,Eigen::Dynamic> bits = (x*255).cast<unsigned char>();\n  QImage img(bits.data(), n,n,QImage::Format_Indexed8);\n  img.setColorCount(256);\n  for(int i=0;i<256;i++) img.setColor(i,qRgb(i,i,i));\n  img.save(filename);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/special_examples/random_cpp11.cpp",
    "content": "#include <Eigen/Core>\n#include <iostream>\n#include <random>\n\nusing namespace Eigen;\n\nint main() {\n  std::default_random_engine generator;\n  std::poisson_distribution<int> distribution(4.1);\n  auto poisson = [&] () {return distribution(generator);};\n\n  RowVectorXi v = RowVectorXi::NullaryExpr(10, poisson );\n  std::cout << v << \"\\n\";\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/doc/tutorial.cpp",
    "content": "#include <Eigen/Array>\n\nint main(int argc, char *argv[])\n{\n  std::cout.precision(2);\n\n  // demo static functions\n  Eigen::Matrix3f m3 = Eigen::Matrix3f::Random();\n  Eigen::Matrix4f m4 = Eigen::Matrix4f::Identity();\n\n  std::cout << \"*** Step 1 ***\\nm3:\\n\" << m3 << \"\\nm4:\\n\" << m4 << std::endl;\n\n  // demo non-static set... functions\n  m4.setZero();\n  m3.diagonal().setOnes();\n  \n  std::cout << \"*** Step 2 ***\\nm3:\\n\" << m3 << \"\\nm4:\\n\" << m4 << std::endl;\n\n  // demo fixed-size block() expression as lvalue and as rvalue\n  m4.block<3,3>(0,1) = m3;\n  m3.row(2) = m4.block<1,3>(2,0);\n\n  std::cout << \"*** Step 3 ***\\nm3:\\n\" << m3 << \"\\nm4:\\n\" << m4 << std::endl;\n\n  // demo dynamic-size block()\n  {\n    int rows = 3, cols = 3;\n    m4.block(0,1,3,3).setIdentity();\n    std::cout << \"*** Step 4 ***\\nm4:\\n\" << m4 << std::endl;\n  }\n\n  // demo vector blocks\n  m4.diagonal().block(1,2).setOnes();\n  std::cout << \"*** Step 5 ***\\nm4.diagonal():\\n\" << m4.diagonal() << std::endl;\n  std::cout << \"m4.diagonal().start(3)\\n\" << m4.diagonal().start(3) << std::endl;\n\n  // demo coeff-wise operations\n  m4 = m4.cwise()*m4;\n  m3 = m3.cwise().cos();\n  std::cout << \"*** Step 6 ***\\nm3:\\n\" << m3 << \"\\nm4:\\n\" << m4 << std::endl;\n\n  // sums of coefficients\n  std::cout << \"*** Step 7 ***\\n m4.sum(): \" << m4.sum() << std::endl;\n  std::cout << \"m4.col(2).sum(): \" << m4.col(2).sum() << std::endl;\n  std::cout << \"m4.colwise().sum():\\n\" << m4.colwise().sum() << std::endl;\n  std::cout << \"m4.rowwise().sum():\\n\" << m4.rowwise().sum() << std::endl;\n\n  // demo intelligent auto-evaluation\n  m4 = m4 * m4; // auto-evaluates so no aliasing problem (performance penalty is low)\n  Eigen::Matrix4f other = (m4 * m4).lazy(); // forces lazy evaluation\n  m4 = m4 + m4; // here Eigen goes for lazy evaluation, as with most expressions\n  m4 = -m4 + m4 + 5 * m4; // same here, Eigen chooses lazy evaluation for all that.\n  m4 = m4 * (m4 + m4); // here Eigen chooses to first evaluate m4 + m4 into a temporary.\n                       // indeed, here it is an optimization to cache this intermediate result.\n  m3 = m3 * m4.block<3,3>(1,1); // here Eigen chooses NOT to evaluate block() into a temporary\n    // because accessing coefficients of that block expression is not more costly than accessing\n    // coefficients of a plain matrix.\n  m4 = m4 * m4.transpose(); // same here, lazy evaluation of the transpose.\n  m4 = m4 * m4.transpose().eval(); // forces immediate evaluation of the transpose\n\n  std::cout << \"*** Step 8 ***\\nm3:\\n\" << m3 << \"\\nm4:\\n\" << m4 << std::endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/eigen3.pc.in",
    "content": "prefix=@CMAKE_INSTALL_PREFIX@\nexec_prefix=${prefix}\n\nName: Eigen3\nDescription: A C++ template library for linear algebra: vectors, matrices, and related algorithms\nRequires:\nVersion: @EIGEN_VERSION_NUMBER@\nLibs:\nCflags: -I${prefix}/@INCLUDE_INSTALL_DIR@\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/CMakeLists.txt",
    "content": "\nei_add_failtest(\"failtest_sanity_check\")\n\nei_add_failtest(\"block_nonconst_ctor_on_const_xpr_0\")\nei_add_failtest(\"block_nonconst_ctor_on_const_xpr_1\")\nei_add_failtest(\"block_nonconst_ctor_on_const_xpr_2\")\nei_add_failtest(\"transpose_nonconst_ctor_on_const_xpr\")\nei_add_failtest(\"diagonal_nonconst_ctor_on_const_xpr\")\nei_add_failtest(\"cwiseunaryview_nonconst_ctor_on_const_xpr\")\nei_add_failtest(\"triangularview_nonconst_ctor_on_const_xpr\")\nei_add_failtest(\"selfadjointview_nonconst_ctor_on_const_xpr\")\n\nei_add_failtest(\"const_qualified_block_method_retval_0\")\nei_add_failtest(\"const_qualified_block_method_retval_1\")\nei_add_failtest(\"const_qualified_transpose_method_retval\")\nei_add_failtest(\"const_qualified_diagonal_method_retval\")\n\nei_add_failtest(\"map_nonconst_ctor_on_const_ptr_0\")\nei_add_failtest(\"map_nonconst_ctor_on_const_ptr_1\")\nei_add_failtest(\"map_nonconst_ctor_on_const_ptr_2\")\nei_add_failtest(\"map_nonconst_ctor_on_const_ptr_3\")\nei_add_failtest(\"map_nonconst_ctor_on_const_ptr_4\")\n\nei_add_failtest(\"map_on_const_type_actually_const_0\")\nei_add_failtest(\"map_on_const_type_actually_const_1\")\nei_add_failtest(\"block_on_const_type_actually_const_0\")\nei_add_failtest(\"block_on_const_type_actually_const_1\")\nei_add_failtest(\"transpose_on_const_type_actually_const\")\nei_add_failtest(\"diagonal_on_const_type_actually_const\")\nei_add_failtest(\"cwiseunaryview_on_const_type_actually_const\")\nei_add_failtest(\"triangularview_on_const_type_actually_const\")\nei_add_failtest(\"selfadjointview_on_const_type_actually_const\")\n\nei_add_failtest(\"ref_1\")\nei_add_failtest(\"ref_2\")\nei_add_failtest(\"ref_3\")\nei_add_failtest(\"ref_4\")\nei_add_failtest(\"ref_5\")\n\nei_add_failtest(\"swap_1\")\nei_add_failtest(\"swap_2\")\n\nei_add_failtest(\"ternary_1\")\nei_add_failtest(\"ternary_2\")\n\nei_add_failtest(\"sparse_ref_1\")\nei_add_failtest(\"sparse_ref_2\")\nei_add_failtest(\"sparse_ref_3\")\nei_add_failtest(\"sparse_ref_4\")\nei_add_failtest(\"sparse_ref_5\")\n\nei_add_failtest(\"sparse_storage_mismatch\")\n\nei_add_failtest(\"partialpivlu_int\")\nei_add_failtest(\"fullpivlu_int\")\nei_add_failtest(\"llt_int\")\nei_add_failtest(\"ldlt_int\")\nei_add_failtest(\"qr_int\")\nei_add_failtest(\"colpivqr_int\")\nei_add_failtest(\"fullpivqr_int\")\nei_add_failtest(\"jacobisvd_int\")\nei_add_failtest(\"bdcsvd_int\")\nei_add_failtest(\"eigensolver_int\")\nei_add_failtest(\"eigensolver_cplx\")\n\nif(EIGEN_TEST_CXX11)\n  ei_add_failtest(\"initializer_list_1\")\n  ei_add_failtest(\"initializer_list_2\")\nendif()\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/bdcsvd_int.cpp",
    "content": "#include \"../Eigen/SVD\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR int\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  BDCSVD<Matrix<SCALAR,Dynamic,Dynamic> > qr(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/block_nonconst_ctor_on_const_xpr_0.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    Block<Matrix3d,3,3> b(m,0,0);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/block_nonconst_ctor_on_const_xpr_1.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    Block<Matrix3d> b(m,0,0,3,3);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/block_nonconst_ctor_on_const_xpr_2.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    // row/column constructor\n    Block<Matrix3d,3,1> b(m,0);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/block_on_const_type_actually_const_0.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(){\n    Matrix3f m;\n    Block<CV_QUALIFIER Matrix3f>(m, 0, 0, 3, 3).coeffRef(0, 0) = 1.0f;\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/block_on_const_type_actually_const_1.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(){\n    MatrixXf m;\n    Block<CV_QUALIFIER MatrixXf, 3, 3>(m, 0, 0).coeffRef(0, 0) = 1.0f;\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/colpivqr_int.cpp",
    "content": "#include \"../Eigen/QR\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR int\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  ColPivHouseholderQR<Matrix<SCALAR,Dynamic,Dynamic> > qr(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/const_qualified_block_method_retval_0.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    Block<Matrix3d,3,3> b(m.block<3,3>(0,0));\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/const_qualified_block_method_retval_1.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    Block<Matrix3d> b(m.block(0,0,3,3));\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/const_qualified_diagonal_method_retval.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    Diagonal<Matrix3d> b(m.diagonal());\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/const_qualified_transpose_method_retval.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    Transpose<Matrix3d> b(m.transpose());\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/cwiseunaryview_nonconst_ctor_on_const_xpr.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    CwiseUnaryView<internal::scalar_real_ref_op<double>,Matrix3d> t(m);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/cwiseunaryview_on_const_type_actually_const.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(){\n    MatrixXf m;\n    CwiseUnaryView<internal::scalar_real_ref_op<double>,CV_QUALIFIER MatrixXf>(m).coeffRef(0, 0) = 1.0f;\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/diagonal_nonconst_ctor_on_const_xpr.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    Diagonal<Matrix3d> d(m);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/diagonal_on_const_type_actually_const.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(){\n    MatrixXf m;\n    Diagonal<CV_QUALIFIER MatrixXf>(m).coeffRef(0) = 1.0f;\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/eigensolver_cplx.cpp",
    "content": "#include \"../Eigen/Eigenvalues\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR std::complex<double>\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  EigenSolver<Matrix<SCALAR,Dynamic,Dynamic> > eig(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/eigensolver_int.cpp",
    "content": "#include \"../Eigen/Eigenvalues\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR int\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  EigenSolver<Matrix<SCALAR,Dynamic,Dynamic> > eig(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/failtest_sanity_check.cpp",
    "content": "#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\nThis is just some text that won't compile as a C++ file, as a basic sanity check for failtest.\n#else\nint main() {}\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/fullpivlu_int.cpp",
    "content": "#include \"../Eigen/LU\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR int\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  FullPivLU<Matrix<SCALAR,Dynamic,Dynamic> > lu(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/fullpivqr_int.cpp",
    "content": "#include \"../Eigen/QR\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR int\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  FullPivHouseholderQR<Matrix<SCALAR,Dynamic,Dynamic> > qr(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/initializer_list_1.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define ROWS Dynamic\n#else\n#define ROWS 3\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  Matrix<int, ROWS, 1> {1, 2, 3};\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/initializer_list_2.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define ROWS Dynamic\n#define COLS Dynamic\n#else\n#define ROWS 3\n#define COLS 1\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  Matrix<int, ROWS, COLS> {1, 2, 3};\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/jacobisvd_int.cpp",
    "content": "#include \"../Eigen/SVD\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR int\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  JacobiSVD<Matrix<SCALAR,Dynamic,Dynamic> > qr(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/ldlt_int.cpp",
    "content": "#include \"../Eigen/Cholesky\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR int\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  LDLT<Matrix<SCALAR,Dynamic,Dynamic> > ldlt(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/llt_int.cpp",
    "content": "#include \"../Eigen/Cholesky\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR int\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  LLT<Matrix<SCALAR,Dynamic,Dynamic> > llt(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/map_nonconst_ctor_on_const_ptr_0.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER float *ptr){\n    Map<Matrix3f> m(ptr);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/map_nonconst_ctor_on_const_ptr_1.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER float *ptr, DenseIndex size){\n    Map<ArrayXf> m(ptr, size);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/map_nonconst_ctor_on_const_ptr_2.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER float *ptr, DenseIndex rows, DenseIndex cols){\n    Map<MatrixXf> m(ptr, rows, cols);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/map_nonconst_ctor_on_const_ptr_3.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER float *ptr, DenseIndex rows, DenseIndex cols){\n    Map<MatrixXf, Aligned, InnerStride<2> > m(ptr, rows, cols, InnerStride<2>());\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/map_nonconst_ctor_on_const_ptr_4.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER\n#else\n#define CV_QUALIFIER const\n#endif\n\nusing namespace Eigen;\n\nvoid foo(const float *ptr, DenseIndex rows, DenseIndex cols){\n    Map<CV_QUALIFIER MatrixXf, Unaligned, OuterStride<> > m(ptr, rows, cols, OuterStride<>(2));\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/map_on_const_type_actually_const_0.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(float *ptr){\n    Map<CV_QUALIFIER MatrixXf>(ptr, 1, 1).coeffRef(0,0) = 1.0f;\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/map_on_const_type_actually_const_1.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(float *ptr){\n    Map<CV_QUALIFIER Vector3f>(ptr).coeffRef(0) = 1.0f;\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/partialpivlu_int.cpp",
    "content": "#include \"../Eigen/LU\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR int\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  PartialPivLU<Matrix<SCALAR,Dynamic,Dynamic> > lu(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/qr_int.cpp",
    "content": "#include \"../Eigen/QR\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define SCALAR int\n#else\n#define SCALAR float\n#endif\n\nusing namespace Eigen;\n\nint main()\n{\n  HouseholderQR<Matrix<SCALAR,Dynamic,Dynamic> > qr(Matrix<SCALAR,Dynamic,Dynamic>::Random(10,10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/ref_1.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid call_ref(Ref<VectorXf> a) { }\n\nint main()\n{\n  VectorXf a(10);\n  CV_QUALIFIER VectorXf& ac(a);\n  call_ref(ac);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/ref_2.cpp",
    "content": "#include \"../Eigen/Core\"\n\nusing namespace Eigen;\n\nvoid call_ref(Ref<VectorXf> a) { }\n\nint main()\n{\n  MatrixXf A(10,10);\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n  call_ref(A.row(3));\n#else\n  call_ref(A.col(3));\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/ref_3.cpp",
    "content": "#include \"../Eigen/Core\"\n\nusing namespace Eigen;\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\nvoid call_ref(Ref<VectorXf> a) { }\n#else\nvoid call_ref(const Ref<const VectorXf> &a) { }\n#endif\n\nint main()\n{\n  VectorXf a(10);\n  call_ref(a+a);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/ref_4.cpp",
    "content": "#include \"../Eigen/Core\"\n\nusing namespace Eigen;\n\nvoid call_ref(Ref<MatrixXf,0,OuterStride<> > a) {}\n\nint main()\n{\n  MatrixXf A(10,10);\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n  call_ref(A.transpose());\n#else\n  call_ref(A);\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/ref_5.cpp",
    "content": "#include \"../Eigen/Core\"\n\nusing namespace Eigen;\n\nvoid call_ref(Ref<VectorXf> a) { }\n\nint main()\n{\n  VectorXf a(10);\n  DenseBase<VectorXf> &ac(a);\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n  call_ref(ac);\n#else\n  call_ref(ac.derived());\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/selfadjointview_nonconst_ctor_on_const_xpr.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    SelfAdjointView<Matrix3d,Upper> t(m);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/selfadjointview_on_const_type_actually_const.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(){\n    MatrixXf m;\n    SelfAdjointView<CV_QUALIFIER MatrixXf,Upper>(m).coeffRef(0, 0) = 1.0f;\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/sparse_ref_1.cpp",
    "content": "#include \"../Eigen/Sparse\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid call_ref(Ref<SparseMatrix<float> > a) { }\n\nint main()\n{\n  SparseMatrix<float> a(10,10);\n  CV_QUALIFIER SparseMatrix<float>& ac(a);\n  call_ref(ac);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/sparse_ref_2.cpp",
    "content": "#include \"../Eigen/Sparse\"\n\nusing namespace Eigen;\n\nvoid call_ref(Ref<SparseMatrix<float> > a) { }\n\nint main()\n{\n  SparseMatrix<float> A(10,10);\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n  call_ref(A.row(3));\n#else\n  call_ref(A.col(3));\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/sparse_ref_3.cpp",
    "content": "#include \"../Eigen/Sparse\"\n\nusing namespace Eigen;\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\nvoid call_ref(Ref<SparseMatrix<float> > a) { }\n#else\nvoid call_ref(const Ref<const SparseMatrix<float> > &a) { }\n#endif\n\nint main()\n{\n  SparseMatrix<float> a(10,10);\n  call_ref(a+a);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/sparse_ref_4.cpp",
    "content": "#include \"../Eigen/Sparse\"\n\nusing namespace Eigen;\n\nvoid call_ref(Ref<SparseMatrix<float> > a) {}\n\nint main()\n{\n  SparseMatrix<float> A(10,10);\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n  call_ref(A.transpose());\n#else\n  call_ref(A);\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/sparse_ref_5.cpp",
    "content": "#include \"../Eigen/Sparse\"\n\nusing namespace Eigen;\n\nvoid call_ref(Ref<SparseMatrix<float> > a) { }\n\nint main()\n{\n  SparseMatrix<float> a(10,10);\n  SparseMatrixBase<SparseMatrix<float> > &ac(a);\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n  call_ref(ac);\n#else\n  call_ref(ac.derived());\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/sparse_storage_mismatch.cpp",
    "content": "#include \"../Eigen/Sparse\"\nusing namespace Eigen;\n\ntypedef SparseMatrix<double,ColMajor> Mat1;\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\ntypedef SparseMatrix<double,RowMajor> Mat2;\n#else\ntypedef SparseMatrix<double,ColMajor> Mat2;\n#endif\n\nint main()\n{\n  Mat1 a(10,10);\n  Mat2 b(10,10);\n  a += b;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/swap_1.cpp",
    "content": "#include \"../Eigen/Core\"\n\nusing namespace Eigen;\n\nint main()\n{\n  VectorXf a(10), b(10);\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n  const DenseBase<VectorXf> &ac(a);\n#else\n  DenseBase<VectorXf> &ac(a);\n#endif\n  b.swap(ac);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/swap_2.cpp",
    "content": "#include \"../Eigen/Core\"\n\nusing namespace Eigen;\n\nint main()\n{\n  VectorXf a(10), b(10);\n  VectorXf const &ac(a);\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n  b.swap(ac);\n#else\n  b.swap(ac.const_cast_derived());\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/ternary_1.cpp",
    "content": "#include \"../Eigen/Core\"\n\nusing namespace Eigen;\n\nint main(int argc,char **)\n{\n  VectorXf a(10), b(10);\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n  b = argc>1 ? 2*a : -a;\n#else\n  b = argc>1 ? 2*a : VectorXf(-a);\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/ternary_2.cpp",
    "content": "#include \"../Eigen/Core\"\n\nusing namespace Eigen;\n\nint main(int argc,char **)\n{\n  VectorXf a(10), b(10);\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n  b = argc>1 ? 2*a : a+a;\n#else\n  b = argc>1 ? VectorXf(2*a) : VectorXf(a+a);\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/transpose_nonconst_ctor_on_const_xpr.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n    Transpose<Matrix3d> t(m);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/transpose_on_const_type_actually_const.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(){\n    MatrixXf m;\n    Transpose<CV_QUALIFIER MatrixXf>(m).coeffRef(0, 0) = 1.0f;\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/triangularview_nonconst_ctor_on_const_xpr.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(CV_QUALIFIER Matrix3d &m){\n  TriangularView<Matrix3d,Upper> t(m);\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/failtest/triangularview_on_const_type_actually_const.cpp",
    "content": "#include \"../Eigen/Core\"\n\n#ifdef EIGEN_SHOULD_FAIL_TO_BUILD\n#define CV_QUALIFIER const\n#else\n#define CV_QUALIFIER\n#endif\n\nusing namespace Eigen;\n\nvoid foo(){\n    MatrixXf m;\n    TriangularView<CV_QUALIFIER MatrixXf,Upper>(m).coeffRef(0, 0) = 1.0f;\n}\n\nint main() {}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/CMakeLists.txt",
    "content": "\nproject(EigenLapack CXX)\n\ninclude(CheckLanguage)\ncheck_language(Fortran)\nif(CMAKE_Fortran_COMPILER)\n  enable_language(Fortran)\n  set(EIGEN_Fortran_COMPILER_WORKS ON)\nelse()\n  set(EIGEN_Fortran_COMPILER_WORKS OFF)\nendif()\n\nadd_custom_target(lapack)\ninclude_directories(../blas)\n\nset(EigenLapack_SRCS\nsingle.cpp double.cpp complex_single.cpp complex_double.cpp ../blas/xerbla.cpp\n)\n\nif(EIGEN_Fortran_COMPILER_WORKS)\n\nset(EigenLapack_SRCS  ${EigenLapack_SRCS}\n  slarft.f  dlarft.f  clarft.f  zlarft.f\n  slarfb.f  dlarfb.f  clarfb.f  zlarfb.f\n  slarfg.f  dlarfg.f  clarfg.f  zlarfg.f\n  slarf.f   dlarf.f   clarf.f   zlarf.f\n  sladiv.f  dladiv.f  cladiv.f  zladiv.f\n  ilaslr.f  iladlr.f  ilaclr.f  ilazlr.f\n  ilaslc.f  iladlc.f  ilaclc.f  ilazlc.f\n  dlapy2.f  dlapy3.f  slapy2.f  slapy3.f\n  clacgv.f  zlacgv.f\n  slamch.f  dlamch.f\n  second_NONE.f dsecnd_NONE.f\n)\n\noption(EIGEN_ENABLE_LAPACK_TESTS OFF \"Enable the Lapack unit tests\")\n\nif(EIGEN_ENABLE_LAPACK_TESTS)\n\n  get_filename_component(eigen_full_path_to_reference_lapack \"./reference/\" ABSOLUTE)\n  if(NOT EXISTS ${eigen_full_path_to_reference_lapack})\n    # Download lapack and install sources and testing at the right place\n    message(STATUS \"Download lapack_addons_3.4.1.tgz...\")\n    \n    file(DOWNLOAD \"http://downloads.tuxfamily.org/eigen/lapack_addons_3.4.1.tgz\"\n                  \"${CMAKE_CURRENT_SOURCE_DIR}/lapack_addons_3.4.1.tgz\"\n                  INACTIVITY_TIMEOUT 15\n                  TIMEOUT 240\n                  STATUS download_status\n                  EXPECTED_MD5 ab5742640617e3221a873aba44bbdc93\n                  SHOW_PROGRESS)\n                  \n    message(STATUS ${download_status})\n    list(GET download_status 0 download_status_num)\n    set(download_status_num 0)\n    if(download_status_num EQUAL 0)\n      message(STATUS \"Setup lapack reference and lapack unit tests\")\n      execute_process(COMMAND tar xzf  \"lapack_addons_3.4.1.tgz\" WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR})\n    else()\n      message(STATUS \"Download of lapack_addons_3.4.1.tgz failed, LAPACK unit tests won't be enabled\")\n      set(EIGEN_ENABLE_LAPACK_TESTS false)\n    endif()\n                  \n  endif()\n  \n  get_filename_component(eigen_full_path_to_reference_lapack \"./reference/\" ABSOLUTE)\n  if(EXISTS ${eigen_full_path_to_reference_lapack})\n    set(EigenLapack_funcfilenames\n        ssyev.f   dsyev.f   csyev.f   zsyev.f\n        spotrf.f  dpotrf.f  cpotrf.f  zpotrf.f\n        spotrs.f  dpotrs.f  cpotrs.f  zpotrs.f\n        sgetrf.f  dgetrf.f  cgetrf.f  zgetrf.f\n        sgetrs.f  dgetrs.f  cgetrs.f  zgetrs.f)\n    \n    file(GLOB ReferenceLapack_SRCS0 RELATIVE ${CMAKE_CURRENT_SOURCE_DIR} \"reference/*.f\")\n    foreach(filename1 IN LISTS ReferenceLapack_SRCS0)\n      string(REPLACE \"reference/\" \"\" filename ${filename1})\n      list(FIND EigenLapack_SRCS ${filename} id1)\n      list(FIND EigenLapack_funcfilenames ${filename} id2)\n      if((id1 EQUAL -1) AND (id2 EQUAL -1))\n        set(ReferenceLapack_SRCS ${ReferenceLapack_SRCS} reference/${filename})\n      endif()\n    endforeach()\n  endif()\n  \n  \nendif()\n\nendif()\n\nadd_library(eigen_lapack_static ${EigenLapack_SRCS} ${ReferenceLapack_SRCS})\nadd_library(eigen_lapack SHARED ${EigenLapack_SRCS})\n\ntarget_link_libraries(eigen_lapack  eigen_blas)\n\nif(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO)\n  target_link_libraries(eigen_lapack_static ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO})\n  target_link_libraries(eigen_lapack        ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO})\nendif()\n\nadd_dependencies(lapack eigen_lapack eigen_lapack_static)\n\ninstall(TARGETS eigen_lapack eigen_lapack_static\n        RUNTIME DESTINATION bin\n        LIBRARY DESTINATION lib\n        ARCHIVE DESTINATION lib)\n\n        \n        \nget_filename_component(eigen_full_path_to_testing_lapack \"./testing/\" ABSOLUTE)\nif(EXISTS ${eigen_full_path_to_testing_lapack})\n  \n  # The following comes from lapack/TESTING/CMakeLists.txt\n  # Get Python\n  find_package(PythonInterp)\n  message(STATUS \"Looking for Python found - ${PYTHONINTERP_FOUND}\")\n  if (PYTHONINTERP_FOUND)\n    message(STATUS \"Using Python version ${PYTHON_VERSION_STRING}\")\n  endif()\n\n  set(LAPACK_SOURCE_DIR ${CMAKE_CURRENT_SOURCE_DIR})\n  set(LAPACK_BINARY_DIR ${CMAKE_CURRENT_BINARY_DIR})\n  set(BUILD_SINGLE      true)\n  set(BUILD_DOUBLE      true)\n  set(BUILD_COMPLEX     true)\n  set(BUILD_COMPLEX16E  true)\n  \n  if(MSVC_VERSION)\n#  string(REPLACE \"/STACK:10000000\" \"/STACK:900000000000000000\"\n#    CMAKE_EXE_LINKER_FLAGS \"${CMAKE_EXE_LINKER_FLAGS}\")\n  string(REGEX REPLACE \"(.*)/STACK:(.*) (.*)\" \"\\\\1/STACK:900000000000000000 \\\\3\"\n    CMAKE_EXE_LINKER_FLAGS \"${CMAKE_EXE_LINKER_FLAGS}\")\n  endif()\n  file(MAKE_DIRECTORY \"${LAPACK_BINARY_DIR}/TESTING\")\n  add_subdirectory(testing/MATGEN)\n  add_subdirectory(testing/LIN)\n  add_subdirectory(testing/EIG)\n  macro(add_lapack_test output input target)\n    set(TEST_INPUT \"${LAPACK_SOURCE_DIR}/testing/${input}\")\n    set(TEST_OUTPUT \"${LAPACK_BINARY_DIR}/TESTING/${output}\")\n    string(REPLACE \".\" \"_\" input_name ${input})\n    set(testName \"${target}_${input_name}\")\n    if(EXISTS \"${TEST_INPUT}\")\n      add_test(NAME LAPACK-${testName}\n        COMMAND \"${CMAKE_COMMAND}\"\n        -DTEST=$<TARGET_FILE:${target}>\n        -DINPUT=${TEST_INPUT} \n        -DOUTPUT=${TEST_OUTPUT} \n        -DINTDIR=${CMAKE_CFG_INTDIR}\n        -P \"${LAPACK_SOURCE_DIR}/testing/runtest.cmake\")\n    endif()\n  endmacro()\n\n  if (BUILD_SINGLE)\n  add_lapack_test(stest.out stest.in xlintsts)\n  #\n  # ======== SINGLE RFP LIN TESTS ========================\n  add_lapack_test(stest_rfp.out stest_rfp.in xlintstrfs)\n  #\n  #\n  # ======== SINGLE EIG TESTS ===========================\n  #\n\n  add_lapack_test(snep.out nep.in xeigtsts)\n\n\n  add_lapack_test(ssep.out sep.in xeigtsts)\n\n\n  add_lapack_test(ssvd.out svd.in xeigtsts)\n\n\n  add_lapack_test(sec.out sec.in xeigtsts)\n\n\n  add_lapack_test(sed.out sed.in xeigtsts)\n\n\n  add_lapack_test(sgg.out sgg.in xeigtsts)\n\n\n  add_lapack_test(sgd.out sgd.in xeigtsts)\n\n\n  add_lapack_test(ssb.out ssb.in xeigtsts)\n\n\n  add_lapack_test(ssg.out ssg.in xeigtsts)\n\n\n  add_lapack_test(sbal.out sbal.in xeigtsts)\n\n\n  add_lapack_test(sbak.out sbak.in xeigtsts)\n\n\n  add_lapack_test(sgbal.out sgbal.in xeigtsts)\n\n\n  add_lapack_test(sgbak.out sgbak.in xeigtsts)\n\n\n  add_lapack_test(sbb.out sbb.in xeigtsts)\n\n\n  add_lapack_test(sglm.out glm.in xeigtsts)\n\n\n  add_lapack_test(sgqr.out gqr.in xeigtsts)\n\n\n  add_lapack_test(sgsv.out gsv.in xeigtsts)\n\n\n  add_lapack_test(scsd.out csd.in xeigtsts)\n\n\n  add_lapack_test(slse.out lse.in xeigtsts)\n  endif()\n\n  if (BUILD_DOUBLE)\n  #\n  # ======== DOUBLE LIN TESTS ===========================\n  add_lapack_test(dtest.out dtest.in xlintstd)\n  #\n  # ======== DOUBLE RFP LIN TESTS ========================\n  add_lapack_test(dtest_rfp.out dtest_rfp.in xlintstrfd)\n  #\n  # ======== DOUBLE EIG TESTS ===========================\n\n  add_lapack_test(dnep.out nep.in xeigtstd)\n\n\n  add_lapack_test(dsep.out sep.in xeigtstd)\n\n\n  add_lapack_test(dsvd.out svd.in xeigtstd)\n\n\n  add_lapack_test(dec.out dec.in xeigtstd)\n\n\n  add_lapack_test(ded.out ded.in xeigtstd)\n\n\n  add_lapack_test(dgg.out dgg.in xeigtstd)\n\n\n  add_lapack_test(dgd.out dgd.in xeigtstd)\n\n\n  add_lapack_test(dsb.out dsb.in xeigtstd)\n\n\n  add_lapack_test(dsg.out dsg.in xeigtstd)\n\n\n  add_lapack_test(dbal.out dbal.in xeigtstd)\n\n\n  add_lapack_test(dbak.out dbak.in xeigtstd)\n\n\n  add_lapack_test(dgbal.out dgbal.in xeigtstd)\n\n\n  add_lapack_test(dgbak.out dgbak.in xeigtstd)\n\n\n  add_lapack_test(dbb.out dbb.in xeigtstd)\n\n\n  add_lapack_test(dglm.out glm.in xeigtstd)\n\n\n  add_lapack_test(dgqr.out gqr.in xeigtstd)\n\n\n  add_lapack_test(dgsv.out gsv.in xeigtstd)\n\n\n  add_lapack_test(dcsd.out csd.in xeigtstd)\n\n\n  add_lapack_test(dlse.out lse.in xeigtstd)\n  endif()\n\n  if (BUILD_COMPLEX)\n  add_lapack_test(ctest.out ctest.in xlintstc)\n  #\n  # ======== COMPLEX RFP LIN TESTS ========================\n  add_lapack_test(ctest_rfp.out ctest_rfp.in xlintstrfc)\n  #\n  # ======== COMPLEX EIG TESTS ===========================\n\n  add_lapack_test(cnep.out nep.in xeigtstc)\n\n\n  add_lapack_test(csep.out sep.in xeigtstc)\n\n\n  add_lapack_test(csvd.out svd.in xeigtstc)\n\n\n  add_lapack_test(cec.out cec.in xeigtstc)\n\n\n  add_lapack_test(ced.out ced.in xeigtstc)\n\n\n  add_lapack_test(cgg.out cgg.in xeigtstc)\n\n\n  add_lapack_test(cgd.out cgd.in xeigtstc)\n\n\n  add_lapack_test(csb.out csb.in xeigtstc)\n\n\n  add_lapack_test(csg.out csg.in xeigtstc)\n\n\n  add_lapack_test(cbal.out cbal.in xeigtstc)\n\n\n  add_lapack_test(cbak.out cbak.in xeigtstc)\n\n\n  add_lapack_test(cgbal.out cgbal.in xeigtstc)\n\n\n  add_lapack_test(cgbak.out cgbak.in xeigtstc)\n\n\n  add_lapack_test(cbb.out cbb.in xeigtstc)\n\n\n  add_lapack_test(cglm.out glm.in xeigtstc)\n\n\n  add_lapack_test(cgqr.out gqr.in xeigtstc)\n\n\n  add_lapack_test(cgsv.out gsv.in xeigtstc)\n\n\n  add_lapack_test(ccsd.out csd.in xeigtstc)\n\n\n  add_lapack_test(clse.out lse.in xeigtstc)\n  endif()\n\n  if (BUILD_COMPLEX16)\n  #\n  # ======== COMPLEX16 LIN TESTS ========================\n  add_lapack_test(ztest.out ztest.in xlintstz)\n  #\n  # ======== COMPLEX16 RFP LIN TESTS ========================\n  add_lapack_test(ztest_rfp.out ztest_rfp.in xlintstrfz)\n  #\n  # ======== COMPLEX16 EIG TESTS ===========================\n\n  add_lapack_test(znep.out nep.in xeigtstz)\n\n\n  add_lapack_test(zsep.out sep.in xeigtstz)\n\n\n  add_lapack_test(zsvd.out svd.in xeigtstz)\n\n\n  add_lapack_test(zec.out zec.in xeigtstz)\n\n\n  add_lapack_test(zed.out zed.in xeigtstz)\n\n\n  add_lapack_test(zgg.out zgg.in xeigtstz)\n\n\n  add_lapack_test(zgd.out zgd.in xeigtstz)\n\n\n  add_lapack_test(zsb.out zsb.in xeigtstz)\n\n\n  add_lapack_test(zsg.out zsg.in xeigtstz)\n\n\n  add_lapack_test(zbal.out zbal.in xeigtstz)\n\n\n  add_lapack_test(zbak.out zbak.in xeigtstz)\n\n\n  add_lapack_test(zgbal.out zgbal.in xeigtstz)\n\n\n  add_lapack_test(zgbak.out zgbak.in xeigtstz)\n\n\n  add_lapack_test(zbb.out zbb.in xeigtstz)\n\n\n  add_lapack_test(zglm.out glm.in xeigtstz)\n\n\n  add_lapack_test(zgqr.out gqr.in xeigtstz)\n\n\n  add_lapack_test(zgsv.out gsv.in xeigtstz)\n\n\n  add_lapack_test(zcsd.out csd.in xeigtstz)\n\n\n  add_lapack_test(zlse.out lse.in xeigtstz)\n  endif()\n\n\n  if (BUILD_SIMPLE)\n      if (BUILD_DOUBLE)\n  #\n  # ======== SINGLE-DOUBLE PROTO LIN TESTS ==============\n          add_lapack_test(dstest.out dstest.in xlintstds)\n      endif()\n  endif()\n\n\n  if (BUILD_COMPLEX)\n      if (BUILD_COMPLEX16)\n  #\n  # ======== COMPLEX-COMPLEX16 LIN TESTS ========================\n          add_lapack_test(zctest.out zctest.in xlintstzc)\n      endif()\n  endif()\n\n  # ==============================================================================\n\n  execute_process(COMMAND ${CMAKE_COMMAND} -E copy ${LAPACK_SOURCE_DIR}/testing/lapack_testing.py ${LAPACK_BINARY_DIR})\n  add_test(\n    NAME LAPACK_Test_Summary\n    WORKING_DIRECTORY ${LAPACK_BINARY_DIR}\n    COMMAND ${PYTHON_EXECUTABLE} \"lapack_testing.py\"\n  )\n\nendif()\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/cholesky.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010-2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"lapack_common.h\"\n#include <Eigen/Cholesky>\n\n// POTRF computes the Cholesky factorization of a real symmetric positive definite matrix A.\nEIGEN_LAPACK_FUNC(potrf,(char* uplo, int *n, RealScalar *pa, int *lda, int *info))\n{\n  *info = 0;\n        if(UPLO(*uplo)==INVALID) *info = -1;\n  else  if(*n<0)                 *info = -2;\n  else  if(*lda<std::max(1,*n))  *info = -4;\n  if(*info!=0)\n  {\n    int e = -*info;\n    return xerbla_(SCALAR_SUFFIX_UP\"POTRF\", &e, 6);\n  }\n\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  MatrixType A(a,*n,*n,*lda);\n  int ret;\n  if(UPLO(*uplo)==UP) ret = int(internal::llt_inplace<Scalar, Upper>::blocked(A));\n  else                ret = int(internal::llt_inplace<Scalar, Lower>::blocked(A));\n\n  if(ret>=0)\n    *info = ret+1;\n  \n  return 0;\n}\n\n// POTRS solves a system of linear equations A*X = B with a symmetric\n// positive definite matrix A using the Cholesky factorization\n// A = U**T*U or A = L*L**T computed by DPOTRF.\nEIGEN_LAPACK_FUNC(potrs,(char* uplo, int *n, int *nrhs, RealScalar *pa, int *lda, RealScalar *pb, int *ldb, int *info))\n{\n  *info = 0;\n        if(UPLO(*uplo)==INVALID) *info = -1;\n  else  if(*n<0)                 *info = -2;\n  else  if(*nrhs<0)              *info = -3;\n  else  if(*lda<std::max(1,*n))  *info = -5;\n  else  if(*ldb<std::max(1,*n))  *info = -7;\n  if(*info!=0)\n  {\n    int e = -*info;\n    return xerbla_(SCALAR_SUFFIX_UP\"POTRS\", &e, 6);\n  }\n\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  Scalar* b = reinterpret_cast<Scalar*>(pb);\n  MatrixType A(a,*n,*n,*lda);\n  MatrixType B(b,*n,*nrhs,*ldb);\n\n  if(UPLO(*uplo)==UP)\n  {\n    A.triangularView<Upper>().adjoint().solveInPlace(B);\n    A.triangularView<Upper>().solveInPlace(B);\n  }\n  else\n  {\n    A.triangularView<Lower>().solveInPlace(B);\n    A.triangularView<Lower>().adjoint().solveInPlace(B);\n  }\n\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/clacgv.f",
    "content": "*> \\brief \\b CLACGV\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download CLACGV + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/clacgv.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/clacgv.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/clacgv.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE CLACGV( N, X, INCX )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            INCX, N\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX            X( * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> CLACGV conjugates a complex vector of length N.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The length of the vector X.  N >= 0.\n*> \\endverbatim\n*>\n*> \\param[in,out] X\n*> \\verbatim\n*>          X is COMPLEX array, dimension\n*>                         (1+(N-1)*abs(INCX))\n*>          On entry, the vector of length N to be conjugated.\n*>          On exit, X is overwritten with conjg(X).\n*> \\endverbatim\n*>\n*> \\param[in] INCX\n*> \\verbatim\n*>          INCX is INTEGER\n*>          The spacing between successive elements of X.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complexOTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE CLACGV( N, X, INCX )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      INTEGER            INCX, N\n*     ..\n*     .. Array Arguments ..\n      COMPLEX            X( * )\n*     ..\n*\n* =====================================================================\n*\n*     .. Local Scalars ..\n      INTEGER            I, IOFF\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          CONJG\n*     ..\n*     .. Executable Statements ..\n*\n      IF( INCX.EQ.1 ) THEN\n         DO 10 I = 1, N\n            X( I ) = CONJG( X( I ) )\n   10    CONTINUE\n      ELSE\n         IOFF = 1\n         IF( INCX.LT.0 )\n     $      IOFF = 1 - ( N-1 )*INCX\n         DO 20 I = 1, N\n            X( IOFF ) = CONJG( X( IOFF ) )\n            IOFF = IOFF + INCX\n   20    CONTINUE\n      END IF\n      RETURN\n*\n*     End of CLACGV\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/cladiv.f",
    "content": "*> \\brief \\b CLADIV\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download CLADIV + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/cladiv.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/cladiv.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/cladiv.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       COMPLEX FUNCTION CLADIV( X, Y )\n* \n*       .. Scalar Arguments ..\n*       COMPLEX            X, Y\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> CLADIV := X / Y, where X and Y are complex.  The computation of X / Y\n*> will not overflow on an intermediary step unless the results\n*> overflows.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] X\n*> \\verbatim\n*>          X is COMPLEX\n*> \\endverbatim\n*>\n*> \\param[in] Y\n*> \\verbatim\n*>          Y is COMPLEX\n*>          The complex scalars X and Y.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complexOTHERauxiliary\n*\n*  =====================================================================\n      COMPLEX FUNCTION CLADIV( X, Y )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      COMPLEX            X, Y\n*     ..\n*\n*  =====================================================================\n*\n*     .. Local Scalars ..\n      REAL               ZI, ZR\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           SLADIV\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          AIMAG, CMPLX, REAL\n*     ..\n*     .. Executable Statements ..\n*\n      CALL SLADIV( REAL( X ), AIMAG( X ), REAL( Y ), AIMAG( Y ), ZR,\n     $             ZI )\n      CLADIV = CMPLX( ZR, ZI )\n*\n      RETURN\n*\n*     End of CLADIV\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/clarf.f",
    "content": "*> \\brief \\b CLARF\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download CLARF + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/clarf.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/clarf.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/clarf.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE CLARF( SIDE, M, N, V, INCV, TAU, C, LDC, WORK )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          SIDE\n*       INTEGER            INCV, LDC, M, N\n*       COMPLEX            TAU\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX            C( LDC, * ), V( * ), WORK( * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> CLARF applies a complex elementary reflector H to a complex M-by-N\n*> matrix C, from either the left or the right. H is represented in the\n*> form\n*>\n*>       H = I - tau * v * v**H\n*>\n*> where tau is a complex scalar and v is a complex vector.\n*>\n*> If tau = 0, then H is taken to be the unit matrix.\n*>\n*> To apply H**H (the conjugate transpose of H), supply conjg(tau) instead\n*> tau.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] SIDE\n*> \\verbatim\n*>          SIDE is CHARACTER*1\n*>          = 'L': form  H * C\n*>          = 'R': form  C * H\n*> \\endverbatim\n*>\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is COMPLEX array, dimension\n*>                     (1 + (M-1)*abs(INCV)) if SIDE = 'L'\n*>                  or (1 + (N-1)*abs(INCV)) if SIDE = 'R'\n*>          The vector v in the representation of H. V is not used if\n*>          TAU = 0.\n*> \\endverbatim\n*>\n*> \\param[in] INCV\n*> \\verbatim\n*>          INCV is INTEGER\n*>          The increment between elements of v. INCV <> 0.\n*> \\endverbatim\n*>\n*> \\param[in] TAU\n*> \\verbatim\n*>          TAU is COMPLEX\n*>          The value tau in the representation of H.\n*> \\endverbatim\n*>\n*> \\param[in,out] C\n*> \\verbatim\n*>          C is COMPLEX array, dimension (LDC,N)\n*>          On entry, the M-by-N matrix C.\n*>          On exit, C is overwritten by the matrix H * C if SIDE = 'L',\n*>          or C * H if SIDE = 'R'.\n*> \\endverbatim\n*>\n*> \\param[in] LDC\n*> \\verbatim\n*>          LDC is INTEGER\n*>          The leading dimension of the array C. LDC >= max(1,M).\n*> \\endverbatim\n*>\n*> \\param[out] WORK\n*> \\verbatim\n*>          WORK is COMPLEX array, dimension\n*>                         (N) if SIDE = 'L'\n*>                      or (M) if SIDE = 'R'\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complexOTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE CLARF( SIDE, M, N, V, INCV, TAU, C, LDC, WORK )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      CHARACTER          SIDE\n      INTEGER            INCV, LDC, M, N\n      COMPLEX            TAU\n*     ..\n*     .. Array Arguments ..\n      COMPLEX            C( LDC, * ), V( * ), WORK( * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      COMPLEX            ONE, ZERO\n      PARAMETER          ( ONE = ( 1.0E+0, 0.0E+0 ),\n     $                   ZERO = ( 0.0E+0, 0.0E+0 ) )\n*     ..\n*     .. Local Scalars ..\n      LOGICAL            APPLYLEFT\n      INTEGER            I, LASTV, LASTC\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           CGEMV, CGERC\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      INTEGER            ILACLR, ILACLC\n      EXTERNAL           LSAME, ILACLR, ILACLC\n*     ..\n*     .. Executable Statements ..\n*\n      APPLYLEFT = LSAME( SIDE, 'L' )\n      LASTV = 0\n      LASTC = 0\n      IF( TAU.NE.ZERO ) THEN\n!     Set up variables for scanning V.  LASTV begins pointing to the end\n!     of V.\n         IF( APPLYLEFT ) THEN\n            LASTV = M\n         ELSE\n            LASTV = N\n         END IF\n         IF( INCV.GT.0 ) THEN\n            I = 1 + (LASTV-1) * INCV\n         ELSE\n            I = 1\n         END IF\n!     Look for the last non-zero row in V.\n         DO WHILE( LASTV.GT.0 .AND. V( I ).EQ.ZERO )\n            LASTV = LASTV - 1\n            I = I - INCV\n         END DO\n         IF( APPLYLEFT ) THEN\n!     Scan for the last non-zero column in C(1:lastv,:).\n            LASTC = ILACLC(LASTV, N, C, LDC)\n         ELSE\n!     Scan for the last non-zero row in C(:,1:lastv).\n            LASTC = ILACLR(M, LASTV, C, LDC)\n         END IF\n      END IF\n!     Note that lastc.eq.0 renders the BLAS operations null; no special\n!     case is needed at this level.\n      IF( APPLYLEFT ) THEN\n*\n*        Form  H * C\n*\n         IF( LASTV.GT.0 ) THEN\n*\n*           w(1:lastc,1) := C(1:lastv,1:lastc)**H * v(1:lastv,1)\n*\n            CALL CGEMV( 'Conjugate transpose', LASTV, LASTC, ONE,\n     $           C, LDC, V, INCV, ZERO, WORK, 1 )\n*\n*           C(1:lastv,1:lastc) := C(...) - v(1:lastv,1) * w(1:lastc,1)**H\n*\n            CALL CGERC( LASTV, LASTC, -TAU, V, INCV, WORK, 1, C, LDC )\n         END IF\n      ELSE\n*\n*        Form  C * H\n*\n         IF( LASTV.GT.0 ) THEN\n*\n*           w(1:lastc,1) := C(1:lastc,1:lastv) * v(1:lastv,1)\n*\n            CALL CGEMV( 'No transpose', LASTC, LASTV, ONE, C, LDC,\n     $           V, INCV, ZERO, WORK, 1 )\n*\n*           C(1:lastc,1:lastv) := C(...) - w(1:lastc,1) * v(1:lastv,1)**H\n*\n            CALL CGERC( LASTC, LASTV, -TAU, WORK, 1, V, INCV, C, LDC )\n         END IF\n      END IF\n      RETURN\n*\n*     End of CLARF\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/clarfb.f",
    "content": "*> \\brief \\b CLARFB\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download CLARFB + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/clarfb.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/clarfb.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/clarfb.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE CLARFB( SIDE, TRANS, DIRECT, STOREV, M, N, K, V, LDV,\n*                          T, LDT, C, LDC, WORK, LDWORK )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          DIRECT, SIDE, STOREV, TRANS\n*       INTEGER            K, LDC, LDT, LDV, LDWORK, M, N\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX            C( LDC, * ), T( LDT, * ), V( LDV, * ),\n*      $                   WORK( LDWORK, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> CLARFB applies a complex block reflector H or its transpose H**H to a\n*> complex M-by-N matrix C, from either the left or the right.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] SIDE\n*> \\verbatim\n*>          SIDE is CHARACTER*1\n*>          = 'L': apply H or H**H from the Left\n*>          = 'R': apply H or H**H from the Right\n*> \\endverbatim\n*>\n*> \\param[in] TRANS\n*> \\verbatim\n*>          TRANS is CHARACTER*1\n*>          = 'N': apply H (No transpose)\n*>          = 'C': apply H**H (Conjugate transpose)\n*> \\endverbatim\n*>\n*> \\param[in] DIRECT\n*> \\verbatim\n*>          DIRECT is CHARACTER*1\n*>          Indicates how H is formed from a product of elementary\n*>          reflectors\n*>          = 'F': H = H(1) H(2) . . . H(k) (Forward)\n*>          = 'B': H = H(k) . . . H(2) H(1) (Backward)\n*> \\endverbatim\n*>\n*> \\param[in] STOREV\n*> \\verbatim\n*>          STOREV is CHARACTER*1\n*>          Indicates how the vectors which define the elementary\n*>          reflectors are stored:\n*>          = 'C': Columnwise\n*>          = 'R': Rowwise\n*> \\endverbatim\n*>\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] K\n*> \\verbatim\n*>          K is INTEGER\n*>          The order of the matrix T (= the number of elementary\n*>          reflectors whose product defines the block reflector).\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is COMPLEX array, dimension\n*>                                (LDV,K) if STOREV = 'C'\n*>                                (LDV,M) if STOREV = 'R' and SIDE = 'L'\n*>                                (LDV,N) if STOREV = 'R' and SIDE = 'R'\n*>          The matrix V. See Further Details.\n*> \\endverbatim\n*>\n*> \\param[in] LDV\n*> \\verbatim\n*>          LDV is INTEGER\n*>          The leading dimension of the array V.\n*>          If STOREV = 'C' and SIDE = 'L', LDV >= max(1,M);\n*>          if STOREV = 'C' and SIDE = 'R', LDV >= max(1,N);\n*>          if STOREV = 'R', LDV >= K.\n*> \\endverbatim\n*>\n*> \\param[in] T\n*> \\verbatim\n*>          T is COMPLEX array, dimension (LDT,K)\n*>          The triangular K-by-K matrix T in the representation of the\n*>          block reflector.\n*> \\endverbatim\n*>\n*> \\param[in] LDT\n*> \\verbatim\n*>          LDT is INTEGER\n*>          The leading dimension of the array T. LDT >= K.\n*> \\endverbatim\n*>\n*> \\param[in,out] C\n*> \\verbatim\n*>          C is COMPLEX array, dimension (LDC,N)\n*>          On entry, the M-by-N matrix C.\n*>          On exit, C is overwritten by H*C or H**H*C or C*H or C*H**H.\n*> \\endverbatim\n*>\n*> \\param[in] LDC\n*> \\verbatim\n*>          LDC is INTEGER\n*>          The leading dimension of the array C. LDC >= max(1,M).\n*> \\endverbatim\n*>\n*> \\param[out] WORK\n*> \\verbatim\n*>          WORK is COMPLEX array, dimension (LDWORK,K)\n*> \\endverbatim\n*>\n*> \\param[in] LDWORK\n*> \\verbatim\n*>          LDWORK is INTEGER\n*>          The leading dimension of the array WORK.\n*>          If SIDE = 'L', LDWORK >= max(1,N);\n*>          if SIDE = 'R', LDWORK >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complexOTHERauxiliary\n*\n*> \\par Further Details:\n*  =====================\n*>\n*> \\verbatim\n*>\n*>  The shape of the matrix V and the storage of the vectors which define\n*>  the H(i) is best illustrated by the following example with n = 5 and\n*>  k = 3. The elements equal to 1 are not stored; the corresponding\n*>  array elements are modified but restored on exit. The rest of the\n*>  array is not used.\n*>\n*>  DIRECT = 'F' and STOREV = 'C':         DIRECT = 'F' and STOREV = 'R':\n*>\n*>               V = (  1       )                 V = (  1 v1 v1 v1 v1 )\n*>                   ( v1  1    )                     (     1 v2 v2 v2 )\n*>                   ( v1 v2  1 )                     (        1 v3 v3 )\n*>                   ( v1 v2 v3 )\n*>                   ( v1 v2 v3 )\n*>\n*>  DIRECT = 'B' and STOREV = 'C':         DIRECT = 'B' and STOREV = 'R':\n*>\n*>               V = ( v1 v2 v3 )                 V = ( v1 v1  1       )\n*>                   ( v1 v2 v3 )                     ( v2 v2 v2  1    )\n*>                   (  1 v2 v3 )                     ( v3 v3 v3 v3  1 )\n*>                   (     1 v3 )\n*>                   (        1 )\n*> \\endverbatim\n*>\n*  =====================================================================\n      SUBROUTINE CLARFB( SIDE, TRANS, DIRECT, STOREV, M, N, K, V, LDV,\n     $                   T, LDT, C, LDC, WORK, LDWORK )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      CHARACTER          DIRECT, SIDE, STOREV, TRANS\n      INTEGER            K, LDC, LDT, LDV, LDWORK, M, N\n*     ..\n*     .. Array Arguments ..\n      COMPLEX            C( LDC, * ), T( LDT, * ), V( LDV, * ),\n     $                   WORK( LDWORK, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      COMPLEX            ONE\n      PARAMETER          ( ONE = ( 1.0E+0, 0.0E+0 ) )\n*     ..\n*     .. Local Scalars ..\n      CHARACTER          TRANST\n      INTEGER            I, J, LASTV, LASTC\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      INTEGER            ILACLR, ILACLC\n      EXTERNAL           LSAME, ILACLR, ILACLC\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           CCOPY, CGEMM, CLACGV, CTRMM\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          CONJG\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick return if possible\n*\n      IF( M.LE.0 .OR. N.LE.0 )\n     $   RETURN\n*\n      IF( LSAME( TRANS, 'N' ) ) THEN\n         TRANST = 'C'\n      ELSE\n         TRANST = 'N'\n      END IF\n*\n      IF( LSAME( STOREV, 'C' ) ) THEN\n*\n         IF( LSAME( DIRECT, 'F' ) ) THEN\n*\n*           Let  V =  ( V1 )    (first K rows)\n*                     ( V2 )\n*           where  V1  is unit lower triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**H * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILACLR( M, K, V, LDV ) )\n               LASTC = ILACLC( LASTV, N, C, LDC )\n*\n*              W := C**H * V  =  (C1**H * V1 + C2**H * V2)  (stored in WORK)\n*\n*              W := C1**H\n*\n               DO 10 J = 1, K\n                  CALL CCOPY( LASTC, C( J, 1 ), LDC, WORK( 1, J ), 1 )\n                  CALL CLACGV( LASTC, WORK( 1, J ), 1 )\n   10          CONTINUE\n*\n*              W := W * V1\n*\n               CALL CTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2**H *V2\n*\n                  CALL CGEMM( 'Conjugate transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K, ONE, C( K+1, 1 ), LDC,\n     $                 V( K+1, 1 ), LDV, ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**H  or  W * T\n*\n               CALL CTRMM( 'Right', 'Upper', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V * W**H\n*\n               IF( M.GT.K ) THEN\n*\n*                 C2 := C2 - V2 * W**H\n*\n                  CALL CGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTV-K, LASTC, K, -ONE, V( K+1, 1 ), LDV,\n     $                 WORK, LDWORK, ONE, C( K+1, 1 ), LDC )\n               END IF\n*\n*              W := W * V1**H\n*\n               CALL CTRMM( 'Right', 'Lower', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W**H\n*\n               DO 30 J = 1, K\n                  DO 20 I = 1, LASTC\n                     C( J, I ) = C( J, I ) - CONJG( WORK( I, J ) )\n   20             CONTINUE\n   30          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**H  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILACLR( N, K, V, LDV ) )\n               LASTC = ILACLR( M, LASTV, C, LDC )\n*\n*              W := C * V  =  (C1*V1 + C2*V2)  (stored in WORK)\n*\n*              W := C1\n*\n               DO 40 J = 1, K\n                  CALL CCOPY( LASTC, C( 1, J ), 1, WORK( 1, J ), 1 )\n   40          CONTINUE\n*\n*              W := W * V1\n*\n               CALL CTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2 * V2\n*\n                  CALL CGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C( 1, K+1 ), LDC, V( K+1, 1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**H\n*\n               CALL CTRMM( 'Right', 'Upper', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V**H\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - W * V2**H\n*\n                  CALL CGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTC, LASTV-K, K,\n     $                 -ONE, WORK, LDWORK, V( K+1, 1 ), LDV,\n     $                 ONE, C( 1, K+1 ), LDC )\n               END IF\n*\n*              W := W * V1**H\n*\n               CALL CTRMM( 'Right', 'Lower', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 60 J = 1, K\n                  DO 50 I = 1, LASTC\n                     C( I, J ) = C( I, J ) - WORK( I, J )\n   50             CONTINUE\n   60          CONTINUE\n            END IF\n*\n         ELSE\n*\n*           Let  V =  ( V1 )\n*                     ( V2 )    (last K rows)\n*           where  V2  is unit upper triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**H * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILACLR( M, K, V, LDV ) )\n               LASTC = ILACLC( LASTV, N, C, LDC )\n*\n*              W := C**H * V  =  (C1**H * V1 + C2**H * V2)  (stored in WORK)\n*\n*              W := C2**H\n*\n               DO 70 J = 1, K\n                  CALL CCOPY( LASTC, C( LASTV-K+J, 1 ), LDC,\n     $                 WORK( 1, J ), 1 )\n                  CALL CLACGV( LASTC, WORK( 1, J ), 1 )\n   70          CONTINUE\n*\n*              W := W * V2\n*\n               CALL CTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1**H*V1\n*\n                  CALL CGEMM( 'Conjugate transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**H  or  W * T\n*\n               CALL CTRMM( 'Right', 'Lower', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V * W**H\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - V1 * W**H\n*\n                  CALL CGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTV-K, LASTC, K, -ONE, V, LDV, WORK, LDWORK,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2**H\n*\n               CALL CTRMM( 'Right', 'Upper', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W**H\n*\n               DO 90 J = 1, K\n                  DO 80 I = 1, LASTC\n                     C( LASTV-K+J, I ) = C( LASTV-K+J, I ) -\n     $                               CONJG( WORK( I, J ) )\n   80             CONTINUE\n   90          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**H  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILACLR( N, K, V, LDV ) )\n               LASTC = ILACLR( M, LASTV, C, LDC )\n*\n*              W := C * V  =  (C1*V1 + C2*V2)  (stored in WORK)\n*\n*              W := C2\n*\n               DO 100 J = 1, K\n                  CALL CCOPY( LASTC, C( 1, LASTV-K+J ), 1,\n     $                 WORK( 1, J ), 1 )\n  100          CONTINUE\n*\n*              W := W * V2\n*\n               CALL CTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1 * V1\n*\n                  CALL CGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C, LDC, V, LDV, ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**H\n*\n               CALL CTRMM( 'Right', 'Lower', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V**H\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - W * V1**H\n*\n                  CALL CGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTC, LASTV-K, K, -ONE, WORK, LDWORK, V, LDV,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2**H\n*\n               CALL CTRMM( 'Right', 'Upper', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W\n*\n               DO 120 J = 1, K\n                  DO 110 I = 1, LASTC\n                     C( I, LASTV-K+J ) = C( I, LASTV-K+J )\n     $                    - WORK( I, J )\n  110             CONTINUE\n  120          CONTINUE\n            END IF\n         END IF\n*\n      ELSE IF( LSAME( STOREV, 'R' ) ) THEN\n*\n         IF( LSAME( DIRECT, 'F' ) ) THEN\n*\n*           Let  V =  ( V1  V2 )    (V1: first K columns)\n*           where  V1  is unit upper triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**H * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILACLC( K, M, V, LDV ) )\n               LASTC = ILACLC( LASTV, N, C, LDC )\n*\n*              W := C**H * V**H  =  (C1**H * V1**H + C2**H * V2**H) (stored in WORK)\n*\n*              W := C1**H\n*\n               DO 130 J = 1, K\n                  CALL CCOPY( LASTC, C( J, 1 ), LDC, WORK( 1, J ), 1 )\n                  CALL CLACGV( LASTC, WORK( 1, J ), 1 )\n  130          CONTINUE\n*\n*              W := W * V1**H\n*\n               CALL CTRMM( 'Right', 'Upper', 'Conjugate transpose',\n     $                     'Unit', LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2**H*V2**H\n*\n                  CALL CGEMM( 'Conjugate transpose',\n     $                 'Conjugate transpose', LASTC, K, LASTV-K,\n     $                 ONE, C( K+1, 1 ), LDC, V( 1, K+1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**H  or  W * T\n*\n               CALL CTRMM( 'Right', 'Upper', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V**H * W**H\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - V2**H * W**H\n*\n                  CALL CGEMM( 'Conjugate transpose',\n     $                 'Conjugate transpose', LASTV-K, LASTC, K,\n     $                 -ONE, V( 1, K+1 ), LDV, WORK, LDWORK,\n     $                 ONE, C( K+1, 1 ), LDC )\n               END IF\n*\n*              W := W * V1\n*\n               CALL CTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W**H\n*\n               DO 150 J = 1, K\n                  DO 140 I = 1, LASTC\n                     C( J, I ) = C( J, I ) - CONJG( WORK( I, J ) )\n  140             CONTINUE\n  150          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**H  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILACLC( K, N, V, LDV ) )\n               LASTC = ILACLR( M, LASTV, C, LDC )\n*\n*              W := C * V**H  =  (C1*V1**H + C2*V2**H)  (stored in WORK)\n*\n*              W := C1\n*\n               DO 160 J = 1, K\n                  CALL CCOPY( LASTC, C( 1, J ), 1, WORK( 1, J ), 1 )\n  160          CONTINUE\n*\n*              W := W * V1**H\n*\n               CALL CTRMM( 'Right', 'Upper', 'Conjugate transpose',\n     $                     'Unit', LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2 * V2**H\n*\n                  CALL CGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTC, K, LASTV-K, ONE, C( 1, K+1 ), LDC,\n     $                 V( 1, K+1 ), LDV, ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**H\n*\n               CALL CTRMM( 'Right', 'Upper', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - W * V2\n*\n                  CALL CGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, LASTV-K, K,\n     $                 -ONE, WORK, LDWORK, V( 1, K+1 ), LDV,\n     $                 ONE, C( 1, K+1 ), LDC )\n               END IF\n*\n*              W := W * V1\n*\n               CALL CTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 180 J = 1, K\n                  DO 170 I = 1, LASTC\n                     C( I, J ) = C( I, J ) - WORK( I, J )\n  170             CONTINUE\n  180          CONTINUE\n*\n            END IF\n*\n         ELSE\n*\n*           Let  V =  ( V1  V2 )    (V2: last K columns)\n*           where  V2  is unit lower triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**H * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILACLC( K, M, V, LDV ) )\n               LASTC = ILACLC( LASTV, N, C, LDC )\n*\n*              W := C**H * V**H  =  (C1**H * V1**H + C2**H * V2**H) (stored in WORK)\n*\n*              W := C2**H\n*\n               DO 190 J = 1, K\n                  CALL CCOPY( LASTC, C( LASTV-K+J, 1 ), LDC,\n     $                 WORK( 1, J ), 1 )\n                  CALL CLACGV( LASTC, WORK( 1, J ), 1 )\n  190          CONTINUE\n*\n*              W := W * V2**H\n*\n               CALL CTRMM( 'Right', 'Lower', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1**H * V1**H\n*\n                  CALL CGEMM( 'Conjugate transpose',\n     $                 'Conjugate transpose', LASTC, K, LASTV-K,\n     $                 ONE, C, LDC, V, LDV, ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**H  or  W * T\n*\n               CALL CTRMM( 'Right', 'Lower', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V**H * W**H\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - V1**H * W**H\n*\n                  CALL CGEMM( 'Conjugate transpose',\n     $                 'Conjugate transpose', LASTV-K, LASTC, K,\n     $                 -ONE, V, LDV, WORK, LDWORK, ONE, C, LDC )\n               END IF\n*\n*              W := W * V2\n*\n               CALL CTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W**H\n*\n               DO 210 J = 1, K\n                  DO 200 I = 1, LASTC\n                     C( LASTV-K+J, I ) = C( LASTV-K+J, I ) -\n     $                               CONJG( WORK( I, J ) )\n  200             CONTINUE\n  210          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**H  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILACLC( K, N, V, LDV ) )\n               LASTC = ILACLR( M, LASTV, C, LDC )\n*\n*              W := C * V**H  =  (C1*V1**H + C2*V2**H)  (stored in WORK)\n*\n*              W := C2\n*\n               DO 220 J = 1, K\n                  CALL CCOPY( LASTC, C( 1, LASTV-K+J ), 1,\n     $                 WORK( 1, J ), 1 )\n  220          CONTINUE\n*\n*              W := W * V2**H\n*\n               CALL CTRMM( 'Right', 'Lower', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1 * V1**H\n*\n                  CALL CGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV, ONE,\n     $                 WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**H\n*\n               CALL CTRMM( 'Right', 'Lower', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - W * V1\n*\n                  CALL CGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, LASTV-K, K, -ONE, WORK, LDWORK, V, LDV,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2\n*\n               CALL CTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 240 J = 1, K\n                  DO 230 I = 1, LASTC\n                     C( I, LASTV-K+J ) = C( I, LASTV-K+J )\n     $                    - WORK( I, J )\n  230             CONTINUE\n  240          CONTINUE\n*\n            END IF\n*\n         END IF\n      END IF\n*\n      RETURN\n*\n*     End of CLARFB\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/clarfg.f",
    "content": "*> \\brief \\b CLARFG\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download CLARFG + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/clarfg.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/clarfg.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/clarfg.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE CLARFG( N, ALPHA, X, INCX, TAU )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            INCX, N\n*       COMPLEX            ALPHA, TAU\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX            X( * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> CLARFG generates a complex elementary reflector H of order n, such\n*> that\n*>\n*>       H**H * ( alpha ) = ( beta ),   H**H * H = I.\n*>              (   x   )   (   0  )\n*>\n*> where alpha and beta are scalars, with beta real, and x is an\n*> (n-1)-element complex vector. H is represented in the form\n*>\n*>       H = I - tau * ( 1 ) * ( 1 v**H ) ,\n*>                     ( v )\n*>\n*> where tau is a complex scalar and v is a complex (n-1)-element\n*> vector. Note that H is not hermitian.\n*>\n*> If the elements of x are all zero and alpha is real, then tau = 0\n*> and H is taken to be the unit matrix.\n*>\n*> Otherwise  1 <= real(tau) <= 2  and  abs(tau-1) <= 1 .\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The order of the elementary reflector.\n*> \\endverbatim\n*>\n*> \\param[in,out] ALPHA\n*> \\verbatim\n*>          ALPHA is COMPLEX\n*>          On entry, the value alpha.\n*>          On exit, it is overwritten with the value beta.\n*> \\endverbatim\n*>\n*> \\param[in,out] X\n*> \\verbatim\n*>          X is COMPLEX array, dimension\n*>                         (1+(N-2)*abs(INCX))\n*>          On entry, the vector x.\n*>          On exit, it is overwritten with the vector v.\n*> \\endverbatim\n*>\n*> \\param[in] INCX\n*> \\verbatim\n*>          INCX is INTEGER\n*>          The increment between elements of X. INCX > 0.\n*> \\endverbatim\n*>\n*> \\param[out] TAU\n*> \\verbatim\n*>          TAU is COMPLEX\n*>          The value tau.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complexOTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE CLARFG( N, ALPHA, X, INCX, TAU )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      INTEGER            INCX, N\n      COMPLEX            ALPHA, TAU\n*     ..\n*     .. Array Arguments ..\n      COMPLEX            X( * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      REAL               ONE, ZERO\n      PARAMETER          ( ONE = 1.0E+0, ZERO = 0.0E+0 )\n*     ..\n*     .. Local Scalars ..\n      INTEGER            J, KNT\n      REAL               ALPHI, ALPHR, BETA, RSAFMN, SAFMIN, XNORM\n*     ..\n*     .. External Functions ..\n      REAL               SCNRM2, SLAMCH, SLAPY3\n      COMPLEX            CLADIV\n      EXTERNAL           SCNRM2, SLAMCH, SLAPY3, CLADIV\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, AIMAG, CMPLX, REAL, SIGN\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           CSCAL, CSSCAL\n*     ..\n*     .. Executable Statements ..\n*\n      IF( N.LE.0 ) THEN\n         TAU = ZERO\n         RETURN\n      END IF\n*\n      XNORM = SCNRM2( N-1, X, INCX )\n      ALPHR = REAL( ALPHA )\n      ALPHI = AIMAG( ALPHA )\n*\n      IF( XNORM.EQ.ZERO .AND. ALPHI.EQ.ZERO ) THEN\n*\n*        H  =  I\n*\n         TAU = ZERO\n      ELSE\n*\n*        general case\n*\n         BETA = -SIGN( SLAPY3( ALPHR, ALPHI, XNORM ), ALPHR )\n         SAFMIN = SLAMCH( 'S' ) / SLAMCH( 'E' )\n         RSAFMN = ONE / SAFMIN\n*\n         KNT = 0\n         IF( ABS( BETA ).LT.SAFMIN ) THEN\n*\n*           XNORM, BETA may be inaccurate; scale X and recompute them\n*\n   10       CONTINUE\n            KNT = KNT + 1\n            CALL CSSCAL( N-1, RSAFMN, X, INCX )\n            BETA = BETA*RSAFMN\n            ALPHI = ALPHI*RSAFMN\n            ALPHR = ALPHR*RSAFMN\n            IF( ABS( BETA ).LT.SAFMIN )\n     $         GO TO 10\n*\n*           New BETA is at most 1, at least SAFMIN\n*\n            XNORM = SCNRM2( N-1, X, INCX )\n            ALPHA = CMPLX( ALPHR, ALPHI )\n            BETA = -SIGN( SLAPY3( ALPHR, ALPHI, XNORM ), ALPHR )\n         END IF\n         TAU = CMPLX( ( BETA-ALPHR ) / BETA, -ALPHI / BETA )\n         ALPHA = CLADIV( CMPLX( ONE ), ALPHA-BETA )\n         CALL CSCAL( N-1, ALPHA, X, INCX )\n*\n*        If ALPHA is subnormal, it may lose relative accuracy\n*\n         DO 20 J = 1, KNT\n            BETA = BETA*SAFMIN\n 20      CONTINUE\n         ALPHA = BETA\n      END IF\n*\n      RETURN\n*\n*     End of CLARFG\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/clarft.f",
    "content": "*> \\brief \\b CLARFT\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download CLARFT + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/clarft.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/clarft.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/clarft.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE CLARFT( DIRECT, STOREV, N, K, V, LDV, TAU, T, LDT )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          DIRECT, STOREV\n*       INTEGER            K, LDT, LDV, N\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX            T( LDT, * ), TAU( * ), V( LDV, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> CLARFT forms the triangular factor T of a complex block reflector H\n*> of order n, which is defined as a product of k elementary reflectors.\n*>\n*> If DIRECT = 'F', H = H(1) H(2) . . . H(k) and T is upper triangular;\n*>\n*> If DIRECT = 'B', H = H(k) . . . H(2) H(1) and T is lower triangular.\n*>\n*> If STOREV = 'C', the vector which defines the elementary reflector\n*> H(i) is stored in the i-th column of the array V, and\n*>\n*>    H  =  I - V * T * V**H\n*>\n*> If STOREV = 'R', the vector which defines the elementary reflector\n*> H(i) is stored in the i-th row of the array V, and\n*>\n*>    H  =  I - V**H * T * V\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] DIRECT\n*> \\verbatim\n*>          DIRECT is CHARACTER*1\n*>          Specifies the order in which the elementary reflectors are\n*>          multiplied to form the block reflector:\n*>          = 'F': H = H(1) H(2) . . . H(k) (Forward)\n*>          = 'B': H = H(k) . . . H(2) H(1) (Backward)\n*> \\endverbatim\n*>\n*> \\param[in] STOREV\n*> \\verbatim\n*>          STOREV is CHARACTER*1\n*>          Specifies how the vectors which define the elementary\n*>          reflectors are stored (see also Further Details):\n*>          = 'C': columnwise\n*>          = 'R': rowwise\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The order of the block reflector H. N >= 0.\n*> \\endverbatim\n*>\n*> \\param[in] K\n*> \\verbatim\n*>          K is INTEGER\n*>          The order of the triangular factor T (= the number of\n*>          elementary reflectors). K >= 1.\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is COMPLEX array, dimension\n*>                               (LDV,K) if STOREV = 'C'\n*>                               (LDV,N) if STOREV = 'R'\n*>          The matrix V. See further details.\n*> \\endverbatim\n*>\n*> \\param[in] LDV\n*> \\verbatim\n*>          LDV is INTEGER\n*>          The leading dimension of the array V.\n*>          If STOREV = 'C', LDV >= max(1,N); if STOREV = 'R', LDV >= K.\n*> \\endverbatim\n*>\n*> \\param[in] TAU\n*> \\verbatim\n*>          TAU is COMPLEX array, dimension (K)\n*>          TAU(i) must contain the scalar factor of the elementary\n*>          reflector H(i).\n*> \\endverbatim\n*>\n*> \\param[out] T\n*> \\verbatim\n*>          T is COMPLEX array, dimension (LDT,K)\n*>          The k by k triangular factor T of the block reflector.\n*>          If DIRECT = 'F', T is upper triangular; if DIRECT = 'B', T is\n*>          lower triangular. The rest of the array is not used.\n*> \\endverbatim\n*>\n*> \\param[in] LDT\n*> \\verbatim\n*>          LDT is INTEGER\n*>          The leading dimension of the array T. LDT >= K.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup complexOTHERauxiliary\n*\n*> \\par Further Details:\n*  =====================\n*>\n*> \\verbatim\n*>\n*>  The shape of the matrix V and the storage of the vectors which define\n*>  the H(i) is best illustrated by the following example with n = 5 and\n*>  k = 3. The elements equal to 1 are not stored.\n*>\n*>  DIRECT = 'F' and STOREV = 'C':         DIRECT = 'F' and STOREV = 'R':\n*>\n*>               V = (  1       )                 V = (  1 v1 v1 v1 v1 )\n*>                   ( v1  1    )                     (     1 v2 v2 v2 )\n*>                   ( v1 v2  1 )                     (        1 v3 v3 )\n*>                   ( v1 v2 v3 )\n*>                   ( v1 v2 v3 )\n*>\n*>  DIRECT = 'B' and STOREV = 'C':         DIRECT = 'B' and STOREV = 'R':\n*>\n*>               V = ( v1 v2 v3 )                 V = ( v1 v1  1       )\n*>                   ( v1 v2 v3 )                     ( v2 v2 v2  1    )\n*>                   (  1 v2 v3 )                     ( v3 v3 v3 v3  1 )\n*>                   (     1 v3 )\n*>                   (        1 )\n*> \\endverbatim\n*>\n*  =====================================================================\n      SUBROUTINE CLARFT( DIRECT, STOREV, N, K, V, LDV, TAU, T, LDT )\n*\n*  -- LAPACK auxiliary routine (version 3.4.1) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*     .. Scalar Arguments ..\n      CHARACTER          DIRECT, STOREV\n      INTEGER            K, LDT, LDV, N\n*     ..\n*     .. Array Arguments ..\n      COMPLEX            T( LDT, * ), TAU( * ), V( LDV, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      COMPLEX            ONE, ZERO\n      PARAMETER          ( ONE = ( 1.0E+0, 0.0E+0 ),\n     $                   ZERO = ( 0.0E+0, 0.0E+0 ) )\n*     ..\n*     .. Local Scalars ..\n      INTEGER            I, J, PREVLASTV, LASTV\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           CGEMV, CLACGV, CTRMV\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      EXTERNAL           LSAME\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick return if possible\n*\n      IF( N.EQ.0 )\n     $   RETURN\n*\n      IF( LSAME( DIRECT, 'F' ) ) THEN\n         PREVLASTV = N\n         DO I = 1, K\n            PREVLASTV = MAX( PREVLASTV, I )\n            IF( TAU( I ).EQ.ZERO ) THEN\n*\n*              H(i)  =  I\n*\n               DO J = 1, I\n                  T( J, I ) = ZERO\n               END DO\n            ELSE\n*\n*              general case\n*\n               IF( LSAME( STOREV, 'C' ) ) THEN\n*                 Skip any trailing zeros.\n                  DO LASTV = N, I+1, -1\n                     IF( V( LASTV, I ).NE.ZERO ) EXIT\n                  END DO\n                  DO J = 1, I-1\n                     T( J, I ) = -TAU( I ) * CONJG( V( I , J ) )\n                  END DO                     \n                  J = MIN( LASTV, PREVLASTV )\n*\n*                 T(1:i-1,i) := - tau(i) * V(i:j,1:i-1)**H * V(i:j,i)\n*\n                  CALL CGEMV( 'Conjugate transpose', J-I, I-1,\n     $                        -TAU( I ), V( I+1, 1 ), LDV, \n     $                        V( I+1, I ), 1,\n     $                        ONE, T( 1, I ), 1 )\n               ELSE\n*                 Skip any trailing zeros.\n                  DO LASTV = N, I+1, -1\n                     IF( V( I, LASTV ).NE.ZERO ) EXIT\n                  END DO\n                  DO J = 1, I-1\n                     T( J, I ) = -TAU( I ) * V( J , I )\n                  END DO                     \n                  J = MIN( LASTV, PREVLASTV )\n*\n*                 T(1:i-1,i) := - tau(i) * V(1:i-1,i:j) * V(i,i:j)**H\n*\n                  CALL CGEMM( 'N', 'C', I-1, 1, J-I, -TAU( I ),\n     $                        V( 1, I+1 ), LDV, V( I, I+1 ), LDV,\n     $                        ONE, T( 1, I ), LDT )                  \n               END IF\n*\n*              T(1:i-1,i) := T(1:i-1,1:i-1) * T(1:i-1,i)\n*\n               CALL CTRMV( 'Upper', 'No transpose', 'Non-unit', I-1, T,\n     $                     LDT, T( 1, I ), 1 )\n               T( I, I ) = TAU( I )\n               IF( I.GT.1 ) THEN\n                  PREVLASTV = MAX( PREVLASTV, LASTV )\n               ELSE\n                  PREVLASTV = LASTV\n               END IF\n            END IF\n         END DO\n      ELSE\n         PREVLASTV = 1\n         DO I = K, 1, -1\n            IF( TAU( I ).EQ.ZERO ) THEN\n*\n*              H(i)  =  I\n*\n               DO J = I, K\n                  T( J, I ) = ZERO\n               END DO\n            ELSE\n*\n*              general case\n*\n               IF( I.LT.K ) THEN\n                  IF( LSAME( STOREV, 'C' ) ) THEN\n*                    Skip any leading zeros.\n                     DO LASTV = 1, I-1\n                        IF( V( LASTV, I ).NE.ZERO ) EXIT\n                     END DO\n                     DO J = I+1, K\n                        T( J, I ) = -TAU( I ) * CONJG( V( N-K+I , J ) )\n                     END DO                        \n                     J = MAX( LASTV, PREVLASTV )\n*\n*                    T(i+1:k,i) = -tau(i) * V(j:n-k+i,i+1:k)**H * V(j:n-k+i,i)\n*\n                     CALL CGEMV( 'Conjugate transpose', N-K+I-J, K-I,\n     $                           -TAU( I ), V( J, I+1 ), LDV, V( J, I ),\n     $                           1, ONE, T( I+1, I ), 1 )\n                  ELSE\n*                    Skip any leading zeros.\n                     DO LASTV = 1, I-1\n                        IF( V( I, LASTV ).NE.ZERO ) EXIT\n                     END DO\n                     DO J = I+1, K\n                        T( J, I ) = -TAU( I ) * V( J, N-K+I )\n                     END DO                      \n                     J = MAX( LASTV, PREVLASTV )\n*\n*                    T(i+1:k,i) = -tau(i) * V(i+1:k,j:n-k+i) * V(i,j:n-k+i)**H\n*\n                     CALL CGEMM( 'N', 'C', K-I, 1, N-K+I-J, -TAU( I ),\n     $                           V( I+1, J ), LDV, V( I, J ), LDV,\n     $                           ONE, T( I+1, I ), LDT )                     \n                  END IF\n*\n*                 T(i+1:k,i) := T(i+1:k,i+1:k) * T(i+1:k,i)\n*\n                  CALL CTRMV( 'Lower', 'No transpose', 'Non-unit', K-I,\n     $                        T( I+1, I+1 ), LDT, T( I+1, I ), 1 )\n                  IF( I.GT.1 ) THEN\n                     PREVLASTV = MIN( PREVLASTV, LASTV )\n                  ELSE\n                     PREVLASTV = LASTV\n                  END IF\n               END IF\n               T( I, I ) = TAU( I )\n            END IF\n         END DO\n      END IF\n      RETURN\n*\n*     End of CLARFT\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/complex_double.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define SCALAR        std::complex<double>\n#define SCALAR_SUFFIX z\n#define SCALAR_SUFFIX_UP \"Z\"\n#define REAL_SCALAR_SUFFIX d\n#define ISCOMPLEX     1\n\n#include \"cholesky.cpp\"\n#include \"lu.cpp\"\n#include \"svd.cpp\"\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/complex_single.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define SCALAR        std::complex<float>\n#define SCALAR_SUFFIX c\n#define SCALAR_SUFFIX_UP \"C\"\n#define REAL_SCALAR_SUFFIX s\n#define ISCOMPLEX     1\n\n#include \"cholesky.cpp\"\n#include \"lu.cpp\"\n#include \"svd.cpp\"\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/dladiv.f",
    "content": "*> \\brief \\b DLADIV\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download DLADIV + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/dladiv.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/dladiv.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/dladiv.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE DLADIV( A, B, C, D, P, Q )\n* \n*       .. Scalar Arguments ..\n*       DOUBLE PRECISION   A, B, C, D, P, Q\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> DLADIV performs complex division in  real arithmetic\n*>\n*>                       a + i*b\n*>            p + i*q = ---------\n*>                       c + i*d\n*>\n*> The algorithm is due to Robert L. Smith and can be found\n*> in D. Knuth, The art of Computer Programming, Vol.2, p.195\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] A\n*> \\verbatim\n*>          A is DOUBLE PRECISION\n*> \\endverbatim\n*>\n*> \\param[in] B\n*> \\verbatim\n*>          B is DOUBLE PRECISION\n*> \\endverbatim\n*>\n*> \\param[in] C\n*> \\verbatim\n*>          C is DOUBLE PRECISION\n*> \\endverbatim\n*>\n*> \\param[in] D\n*> \\verbatim\n*>          D is DOUBLE PRECISION\n*>          The scalars a, b, c, and d in the above expression.\n*> \\endverbatim\n*>\n*> \\param[out] P\n*> \\verbatim\n*>          P is DOUBLE PRECISION\n*> \\endverbatim\n*>\n*> \\param[out] Q\n*> \\verbatim\n*>          Q is DOUBLE PRECISION\n*>          The scalars p and q in the above expression.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE DLADIV( A, B, C, D, P, Q )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   A, B, C, D, P, Q\n*     ..\n*\n*  =====================================================================\n*\n*     .. Local Scalars ..\n      DOUBLE PRECISION   E, F\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS\n*     ..\n*     .. Executable Statements ..\n*\n      IF( ABS( D ).LT.ABS( C ) ) THEN\n         E = D / C\n         F = C + D*E\n         P = ( A+B*E ) / F\n         Q = ( B-A*E ) / F\n      ELSE\n         E = C / D\n         F = D + C*E\n         P = ( B+A*E ) / F\n         Q = ( -A+B*E ) / F\n      END IF\n*\n      RETURN\n*\n*     End of DLADIV\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/dlamch.f",
    "content": "*> \\brief \\b DLAMCH\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*      DOUBLE PRECISION FUNCTION DLAMCH( CMACH )\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> DLAMCH determines double precision machine parameters.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] CMACH\n*> \\verbatim\n*>          Specifies the value to be returned by DLAMCH:\n*>          = 'E' or 'e',   DLAMCH := eps\n*>          = 'S' or 's ,   DLAMCH := sfmin\n*>          = 'B' or 'b',   DLAMCH := base\n*>          = 'P' or 'p',   DLAMCH := eps*base\n*>          = 'N' or 'n',   DLAMCH := t\n*>          = 'R' or 'r',   DLAMCH := rnd\n*>          = 'M' or 'm',   DLAMCH := emin\n*>          = 'U' or 'u',   DLAMCH := rmin\n*>          = 'L' or 'l',   DLAMCH := emax\n*>          = 'O' or 'o',   DLAMCH := rmax\n*>          where\n*>          eps   = relative machine precision\n*>          sfmin = safe minimum, such that 1/sfmin does not overflow\n*>          base  = base of the machine\n*>          prec  = eps*base\n*>          t     = number of (base) digits in the mantissa\n*>          rnd   = 1.0 when rounding occurs in addition, 0.0 otherwise\n*>          emin  = minimum exponent before (gradual) underflow\n*>          rmin  = underflow threshold - base**(emin-1)\n*>          emax  = largest exponent before overflow\n*>          rmax  = overflow threshold  - (base**emax)*(1-eps)\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      DOUBLE PRECISION FUNCTION DLAMCH( CMACH )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      CHARACTER          CMACH\n*     ..\n*\n* =====================================================================\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ONE, ZERO\n      PARAMETER          ( ONE = 1.0D+0, ZERO = 0.0D+0 )\n*     ..\n*     .. Local Scalars ..\n      DOUBLE PRECISION   RND, EPS, SFMIN, SMALL, RMACH\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      EXTERNAL           LSAME\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          DIGITS, EPSILON, HUGE, MAXEXPONENT,\n     $                   MINEXPONENT, RADIX, TINY\n*     ..\n*     .. Executable Statements ..\n*\n*\n*     Assume rounding, not chopping. Always.\n*\n      RND = ONE\n*\n      IF( ONE.EQ.RND ) THEN\n         EPS = EPSILON(ZERO) * 0.5\n      ELSE\n         EPS = EPSILON(ZERO)\n      END IF\n*\n      IF( LSAME( CMACH, 'E' ) ) THEN\n         RMACH = EPS\n      ELSE IF( LSAME( CMACH, 'S' ) ) THEN\n         SFMIN = TINY(ZERO)\n         SMALL = ONE / HUGE(ZERO)\n         IF( SMALL.GE.SFMIN ) THEN\n*\n*           Use SMALL plus a bit, to avoid the possibility of rounding\n*           causing overflow when computing  1/sfmin.\n*\n            SFMIN = SMALL*( ONE+EPS )\n         END IF\n         RMACH = SFMIN\n      ELSE IF( LSAME( CMACH, 'B' ) ) THEN\n         RMACH = RADIX(ZERO)\n      ELSE IF( LSAME( CMACH, 'P' ) ) THEN\n         RMACH = EPS * RADIX(ZERO)\n      ELSE IF( LSAME( CMACH, 'N' ) ) THEN\n         RMACH = DIGITS(ZERO)\n      ELSE IF( LSAME( CMACH, 'R' ) ) THEN\n         RMACH = RND\n      ELSE IF( LSAME( CMACH, 'M' ) ) THEN\n         RMACH = MINEXPONENT(ZERO)\n      ELSE IF( LSAME( CMACH, 'U' ) ) THEN\n         RMACH = tiny(zero)\n      ELSE IF( LSAME( CMACH, 'L' ) ) THEN\n         RMACH = MAXEXPONENT(ZERO)\n      ELSE IF( LSAME( CMACH, 'O' ) ) THEN\n         RMACH = HUGE(ZERO)\n      ELSE\n         RMACH = ZERO\n      END IF\n*\n      DLAMCH = RMACH\n      RETURN\n*\n*     End of DLAMCH\n*\n      END\n************************************************************************\n*> \\brief \\b DLAMC3\n*> \\details\n*> \\b Purpose:\n*> \\verbatim\n*> DLAMC3  is intended to force  A  and  B  to be stored prior to doing\n*> the addition of  A  and  B ,  for use in situations where optimizers\n*> might hold one of these in a register.\n*> \\endverbatim\n*> \\author LAPACK is a software package provided by Univ. of Tennessee, Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..\n*> \\date November 2011\n*> \\ingroup auxOTHERauxiliary\n*>\n*> \\param[in] A\n*> \\verbatim\n*>          A is a DOUBLE PRECISION\n*> \\endverbatim\n*>\n*> \\param[in] B\n*> \\verbatim\n*>          B is a DOUBLE PRECISION\n*>          The values A and B.\n*> \\endverbatim\n*>\n      DOUBLE PRECISION FUNCTION DLAMC3( A, B )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*     Univ. of Tennessee, Univ. of California Berkeley and NAG Ltd..\n*     November 2010\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   A, B\n*     ..\n* =====================================================================\n*\n*     .. Executable Statements ..\n*\n      DLAMC3 = A + B\n*\n      RETURN\n*\n*     End of DLAMC3\n*\n      END\n*\n************************************************************************\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/dlapy2.f",
    "content": "*> \\brief \\b DLAPY2\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download DLAPY2 + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/dlapy2.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/dlapy2.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/dlapy2.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       DOUBLE PRECISION FUNCTION DLAPY2( X, Y )\n* \n*       .. Scalar Arguments ..\n*       DOUBLE PRECISION   X, Y\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> DLAPY2 returns sqrt(x**2+y**2), taking care not to cause unnecessary\n*> overflow.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] X\n*> \\verbatim\n*>          X is DOUBLE PRECISION\n*> \\endverbatim\n*>\n*> \\param[in] Y\n*> \\verbatim\n*>          Y is DOUBLE PRECISION\n*>          X and Y specify the values x and y.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      DOUBLE PRECISION FUNCTION DLAPY2( X, Y )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   X, Y\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO\n      PARAMETER          ( ZERO = 0.0D0 )\n      DOUBLE PRECISION   ONE\n      PARAMETER          ( ONE = 1.0D0 )\n*     ..\n*     .. Local Scalars ..\n      DOUBLE PRECISION   W, XABS, YABS, Z\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN, SQRT\n*     ..\n*     .. Executable Statements ..\n*\n      XABS = ABS( X )\n      YABS = ABS( Y )\n      W = MAX( XABS, YABS )\n      Z = MIN( XABS, YABS )\n      IF( Z.EQ.ZERO ) THEN\n         DLAPY2 = W\n      ELSE\n         DLAPY2 = W*SQRT( ONE+( Z / W )**2 )\n      END IF\n      RETURN\n*\n*     End of DLAPY2\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/dlapy3.f",
    "content": "*> \\brief \\b DLAPY3\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download DLAPY3 + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/dlapy3.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/dlapy3.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/dlapy3.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       DOUBLE PRECISION FUNCTION DLAPY3( X, Y, Z )\n* \n*       .. Scalar Arguments ..\n*       DOUBLE PRECISION   X, Y, Z\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> DLAPY3 returns sqrt(x**2+y**2+z**2), taking care not to cause\n*> unnecessary overflow.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] X\n*> \\verbatim\n*>          X is DOUBLE PRECISION\n*> \\endverbatim\n*>\n*> \\param[in] Y\n*> \\verbatim\n*>          Y is DOUBLE PRECISION\n*> \\endverbatim\n*>\n*> \\param[in] Z\n*> \\verbatim\n*>          Z is DOUBLE PRECISION\n*>          X, Y and Z specify the values x, y and z.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      DOUBLE PRECISION FUNCTION DLAPY3( X, Y, Z )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      DOUBLE PRECISION   X, Y, Z\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ZERO\n      PARAMETER          ( ZERO = 0.0D0 )\n*     ..\n*     .. Local Scalars ..\n      DOUBLE PRECISION   W, XABS, YABS, ZABS\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, SQRT\n*     ..\n*     .. Executable Statements ..\n*\n      XABS = ABS( X )\n      YABS = ABS( Y )\n      ZABS = ABS( Z )\n      W = MAX( XABS, YABS, ZABS )\n      IF( W.EQ.ZERO ) THEN\n*     W can be zero for max(0,nan,0)\n*     adding all three entries together will make sure\n*     NaN will not disappear.\n         DLAPY3 =  XABS + YABS + ZABS\n      ELSE\n         DLAPY3 = W*SQRT( ( XABS / W )**2+( YABS / W )**2+\n     $            ( ZABS / W )**2 )\n      END IF\n      RETURN\n*\n*     End of DLAPY3\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/dlarf.f",
    "content": "*> \\brief \\b DLARF\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download DLARF + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/dlarf.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/dlarf.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/dlarf.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE DLARF( SIDE, M, N, V, INCV, TAU, C, LDC, WORK )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          SIDE\n*       INTEGER            INCV, LDC, M, N\n*       DOUBLE PRECISION   TAU\n*       ..\n*       .. Array Arguments ..\n*       DOUBLE PRECISION   C( LDC, * ), V( * ), WORK( * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> DLARF applies a real elementary reflector H to a real m by n matrix\n*> C, from either the left or the right. H is represented in the form\n*>\n*>       H = I - tau * v * v**T\n*>\n*> where tau is a real scalar and v is a real vector.\n*>\n*> If tau = 0, then H is taken to be the unit matrix.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] SIDE\n*> \\verbatim\n*>          SIDE is CHARACTER*1\n*>          = 'L': form  H * C\n*>          = 'R': form  C * H\n*> \\endverbatim\n*>\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is DOUBLE PRECISION array, dimension\n*>                     (1 + (M-1)*abs(INCV)) if SIDE = 'L'\n*>                  or (1 + (N-1)*abs(INCV)) if SIDE = 'R'\n*>          The vector v in the representation of H. V is not used if\n*>          TAU = 0.\n*> \\endverbatim\n*>\n*> \\param[in] INCV\n*> \\verbatim\n*>          INCV is INTEGER\n*>          The increment between elements of v. INCV <> 0.\n*> \\endverbatim\n*>\n*> \\param[in] TAU\n*> \\verbatim\n*>          TAU is DOUBLE PRECISION\n*>          The value tau in the representation of H.\n*> \\endverbatim\n*>\n*> \\param[in,out] C\n*> \\verbatim\n*>          C is DOUBLE PRECISION array, dimension (LDC,N)\n*>          On entry, the m by n matrix C.\n*>          On exit, C is overwritten by the matrix H * C if SIDE = 'L',\n*>          or C * H if SIDE = 'R'.\n*> \\endverbatim\n*>\n*> \\param[in] LDC\n*> \\verbatim\n*>          LDC is INTEGER\n*>          The leading dimension of the array C. LDC >= max(1,M).\n*> \\endverbatim\n*>\n*> \\param[out] WORK\n*> \\verbatim\n*>          WORK is DOUBLE PRECISION array, dimension\n*>                         (N) if SIDE = 'L'\n*>                      or (M) if SIDE = 'R'\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup doubleOTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE DLARF( SIDE, M, N, V, INCV, TAU, C, LDC, WORK )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      CHARACTER          SIDE\n      INTEGER            INCV, LDC, M, N\n      DOUBLE PRECISION   TAU\n*     ..\n*     .. Array Arguments ..\n      DOUBLE PRECISION   C( LDC, * ), V( * ), WORK( * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ONE, ZERO\n      PARAMETER          ( ONE = 1.0D+0, ZERO = 0.0D+0 )\n*     ..\n*     .. Local Scalars ..\n      LOGICAL            APPLYLEFT\n      INTEGER            I, LASTV, LASTC\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           DGEMV, DGER\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      INTEGER            ILADLR, ILADLC\n      EXTERNAL           LSAME, ILADLR, ILADLC\n*     ..\n*     .. Executable Statements ..\n*\n      APPLYLEFT = LSAME( SIDE, 'L' )\n      LASTV = 0\n      LASTC = 0\n      IF( TAU.NE.ZERO ) THEN\n!     Set up variables for scanning V.  LASTV begins pointing to the end\n!     of V.\n         IF( APPLYLEFT ) THEN\n            LASTV = M\n         ELSE\n            LASTV = N\n         END IF\n         IF( INCV.GT.0 ) THEN\n            I = 1 + (LASTV-1) * INCV\n         ELSE\n            I = 1\n         END IF\n!     Look for the last non-zero row in V.\n         DO WHILE( LASTV.GT.0 .AND. V( I ).EQ.ZERO )\n            LASTV = LASTV - 1\n            I = I - INCV\n         END DO\n         IF( APPLYLEFT ) THEN\n!     Scan for the last non-zero column in C(1:lastv,:).\n            LASTC = ILADLC(LASTV, N, C, LDC)\n         ELSE\n!     Scan for the last non-zero row in C(:,1:lastv).\n            LASTC = ILADLR(M, LASTV, C, LDC)\n         END IF\n      END IF\n!     Note that lastc.eq.0 renders the BLAS operations null; no special\n!     case is needed at this level.\n      IF( APPLYLEFT ) THEN\n*\n*        Form  H * C\n*\n         IF( LASTV.GT.0 ) THEN\n*\n*           w(1:lastc,1) := C(1:lastv,1:lastc)**T * v(1:lastv,1)\n*\n            CALL DGEMV( 'Transpose', LASTV, LASTC, ONE, C, LDC, V, INCV,\n     $           ZERO, WORK, 1 )\n*\n*           C(1:lastv,1:lastc) := C(...) - v(1:lastv,1) * w(1:lastc,1)**T\n*\n            CALL DGER( LASTV, LASTC, -TAU, V, INCV, WORK, 1, C, LDC )\n         END IF\n      ELSE\n*\n*        Form  C * H\n*\n         IF( LASTV.GT.0 ) THEN\n*\n*           w(1:lastc,1) := C(1:lastc,1:lastv) * v(1:lastv,1)\n*\n            CALL DGEMV( 'No transpose', LASTC, LASTV, ONE, C, LDC,\n     $           V, INCV, ZERO, WORK, 1 )\n*\n*           C(1:lastc,1:lastv) := C(...) - w(1:lastc,1) * v(1:lastv,1)**T\n*\n            CALL DGER( LASTC, LASTV, -TAU, WORK, 1, V, INCV, C, LDC )\n         END IF\n      END IF\n      RETURN\n*\n*     End of DLARF\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/dlarfb.f",
    "content": "*> \\brief \\b DLARFB\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download DLARFB + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/dlarfb.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/dlarfb.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/dlarfb.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE DLARFB( SIDE, TRANS, DIRECT, STOREV, M, N, K, V, LDV,\n*                          T, LDT, C, LDC, WORK, LDWORK )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          DIRECT, SIDE, STOREV, TRANS\n*       INTEGER            K, LDC, LDT, LDV, LDWORK, M, N\n*       ..\n*       .. Array Arguments ..\n*       DOUBLE PRECISION   C( LDC, * ), T( LDT, * ), V( LDV, * ),\n*      $                   WORK( LDWORK, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> DLARFB applies a real block reflector H or its transpose H**T to a\n*> real m by n matrix C, from either the left or the right.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] SIDE\n*> \\verbatim\n*>          SIDE is CHARACTER*1\n*>          = 'L': apply H or H**T from the Left\n*>          = 'R': apply H or H**T from the Right\n*> \\endverbatim\n*>\n*> \\param[in] TRANS\n*> \\verbatim\n*>          TRANS is CHARACTER*1\n*>          = 'N': apply H (No transpose)\n*>          = 'T': apply H**T (Transpose)\n*> \\endverbatim\n*>\n*> \\param[in] DIRECT\n*> \\verbatim\n*>          DIRECT is CHARACTER*1\n*>          Indicates how H is formed from a product of elementary\n*>          reflectors\n*>          = 'F': H = H(1) H(2) . . . H(k) (Forward)\n*>          = 'B': H = H(k) . . . H(2) H(1) (Backward)\n*> \\endverbatim\n*>\n*> \\param[in] STOREV\n*> \\verbatim\n*>          STOREV is CHARACTER*1\n*>          Indicates how the vectors which define the elementary\n*>          reflectors are stored:\n*>          = 'C': Columnwise\n*>          = 'R': Rowwise\n*> \\endverbatim\n*>\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] K\n*> \\verbatim\n*>          K is INTEGER\n*>          The order of the matrix T (= the number of elementary\n*>          reflectors whose product defines the block reflector).\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is DOUBLE PRECISION array, dimension\n*>                                (LDV,K) if STOREV = 'C'\n*>                                (LDV,M) if STOREV = 'R' and SIDE = 'L'\n*>                                (LDV,N) if STOREV = 'R' and SIDE = 'R'\n*>          The matrix V. See Further Details.\n*> \\endverbatim\n*>\n*> \\param[in] LDV\n*> \\verbatim\n*>          LDV is INTEGER\n*>          The leading dimension of the array V.\n*>          If STOREV = 'C' and SIDE = 'L', LDV >= max(1,M);\n*>          if STOREV = 'C' and SIDE = 'R', LDV >= max(1,N);\n*>          if STOREV = 'R', LDV >= K.\n*> \\endverbatim\n*>\n*> \\param[in] T\n*> \\verbatim\n*>          T is DOUBLE PRECISION array, dimension (LDT,K)\n*>          The triangular k by k matrix T in the representation of the\n*>          block reflector.\n*> \\endverbatim\n*>\n*> \\param[in] LDT\n*> \\verbatim\n*>          LDT is INTEGER\n*>          The leading dimension of the array T. LDT >= K.\n*> \\endverbatim\n*>\n*> \\param[in,out] C\n*> \\verbatim\n*>          C is DOUBLE PRECISION array, dimension (LDC,N)\n*>          On entry, the m by n matrix C.\n*>          On exit, C is overwritten by H*C or H**T*C or C*H or C*H**T.\n*> \\endverbatim\n*>\n*> \\param[in] LDC\n*> \\verbatim\n*>          LDC is INTEGER\n*>          The leading dimension of the array C. LDC >= max(1,M).\n*> \\endverbatim\n*>\n*> \\param[out] WORK\n*> \\verbatim\n*>          WORK is DOUBLE PRECISION array, dimension (LDWORK,K)\n*> \\endverbatim\n*>\n*> \\param[in] LDWORK\n*> \\verbatim\n*>          LDWORK is INTEGER\n*>          The leading dimension of the array WORK.\n*>          If SIDE = 'L', LDWORK >= max(1,N);\n*>          if SIDE = 'R', LDWORK >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup doubleOTHERauxiliary\n*\n*> \\par Further Details:\n*  =====================\n*>\n*> \\verbatim\n*>\n*>  The shape of the matrix V and the storage of the vectors which define\n*>  the H(i) is best illustrated by the following example with n = 5 and\n*>  k = 3. The elements equal to 1 are not stored; the corresponding\n*>  array elements are modified but restored on exit. The rest of the\n*>  array is not used.\n*>\n*>  DIRECT = 'F' and STOREV = 'C':         DIRECT = 'F' and STOREV = 'R':\n*>\n*>               V = (  1       )                 V = (  1 v1 v1 v1 v1 )\n*>                   ( v1  1    )                     (     1 v2 v2 v2 )\n*>                   ( v1 v2  1 )                     (        1 v3 v3 )\n*>                   ( v1 v2 v3 )\n*>                   ( v1 v2 v3 )\n*>\n*>  DIRECT = 'B' and STOREV = 'C':         DIRECT = 'B' and STOREV = 'R':\n*>\n*>               V = ( v1 v2 v3 )                 V = ( v1 v1  1       )\n*>                   ( v1 v2 v3 )                     ( v2 v2 v2  1    )\n*>                   (  1 v2 v3 )                     ( v3 v3 v3 v3  1 )\n*>                   (     1 v3 )\n*>                   (        1 )\n*> \\endverbatim\n*>\n*  =====================================================================\n      SUBROUTINE DLARFB( SIDE, TRANS, DIRECT, STOREV, M, N, K, V, LDV,\n     $                   T, LDT, C, LDC, WORK, LDWORK )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      CHARACTER          DIRECT, SIDE, STOREV, TRANS\n      INTEGER            K, LDC, LDT, LDV, LDWORK, M, N\n*     ..\n*     .. Array Arguments ..\n      DOUBLE PRECISION   C( LDC, * ), T( LDT, * ), V( LDV, * ),\n     $                   WORK( LDWORK, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ONE\n      PARAMETER          ( ONE = 1.0D+0 )\n*     ..\n*     .. Local Scalars ..\n      CHARACTER          TRANST\n      INTEGER            I, J, LASTV, LASTC\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      INTEGER            ILADLR, ILADLC\n      EXTERNAL           LSAME, ILADLR, ILADLC\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           DCOPY, DGEMM, DTRMM\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick return if possible\n*\n      IF( M.LE.0 .OR. N.LE.0 )\n     $   RETURN\n*\n      IF( LSAME( TRANS, 'N' ) ) THEN\n         TRANST = 'T'\n      ELSE\n         TRANST = 'N'\n      END IF\n*\n      IF( LSAME( STOREV, 'C' ) ) THEN\n*\n         IF( LSAME( DIRECT, 'F' ) ) THEN\n*\n*           Let  V =  ( V1 )    (first K rows)\n*                     ( V2 )\n*           where  V1  is unit lower triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**T * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILADLR( M, K, V, LDV ) )\n               LASTC = ILADLC( LASTV, N, C, LDC )\n*\n*              W := C**T * V  =  (C1**T * V1 + C2**T * V2)  (stored in WORK)\n*\n*              W := C1**T\n*\n               DO 10 J = 1, K\n                  CALL DCOPY( LASTC, C( J, 1 ), LDC, WORK( 1, J ), 1 )\n   10          CONTINUE\n*\n*              W := W * V1\n*\n               CALL DTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2**T *V2\n*\n                  CALL DGEMM( 'Transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C( K+1, 1 ), LDC, V( K+1, 1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**T  or  W * T\n*\n               CALL DTRMM( 'Right', 'Upper', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V * W**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - V2 * W**T\n*\n                  CALL DGEMM( 'No transpose', 'Transpose',\n     $                 LASTV-K, LASTC, K,\n     $                 -ONE, V( K+1, 1 ), LDV, WORK, LDWORK, ONE,\n     $                 C( K+1, 1 ), LDC )\n               END IF\n*\n*              W := W * V1**T\n*\n               CALL DTRMM( 'Right', 'Lower', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W**T\n*\n               DO 30 J = 1, K\n                  DO 20 I = 1, LASTC\n                     C( J, I ) = C( J, I ) - WORK( I, J )\n   20             CONTINUE\n   30          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**T  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILADLR( N, K, V, LDV ) )\n               LASTC = ILADLR( M, LASTV, C, LDC )\n*\n*              W := C * V  =  (C1*V1 + C2*V2)  (stored in WORK)\n*\n*              W := C1\n*\n               DO 40 J = 1, K\n                  CALL DCOPY( LASTC, C( 1, J ), 1, WORK( 1, J ), 1 )\n   40          CONTINUE\n*\n*              W := W * V1\n*\n               CALL DTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2 * V2\n*\n                  CALL DGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C( 1, K+1 ), LDC, V( K+1, 1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**T\n*\n               CALL DTRMM( 'Right', 'Upper', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - W * V2**T\n*\n                  CALL DGEMM( 'No transpose', 'Transpose',\n     $                 LASTC, LASTV-K, K,\n     $                 -ONE, WORK, LDWORK, V( K+1, 1 ), LDV, ONE,\n     $                 C( 1, K+1 ), LDC )\n               END IF\n*\n*              W := W * V1**T\n*\n               CALL DTRMM( 'Right', 'Lower', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 60 J = 1, K\n                  DO 50 I = 1, LASTC\n                     C( I, J ) = C( I, J ) - WORK( I, J )\n   50             CONTINUE\n   60          CONTINUE\n            END IF\n*\n         ELSE\n*\n*           Let  V =  ( V1 )\n*                     ( V2 )    (last K rows)\n*           where  V2  is unit upper triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**T * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILADLR( M, K, V, LDV ) )\n               LASTC = ILADLC( LASTV, N, C, LDC )\n*\n*              W := C**T * V  =  (C1**T * V1 + C2**T * V2)  (stored in WORK)\n*\n*              W := C2**T\n*\n               DO 70 J = 1, K\n                  CALL DCOPY( LASTC, C( LASTV-K+J, 1 ), LDC,\n     $                 WORK( 1, J ), 1 )\n   70          CONTINUE\n*\n*              W := W * V2\n*\n               CALL DTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1**T*V1\n*\n                  CALL DGEMM( 'Transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**T  or  W * T\n*\n               CALL DTRMM( 'Right', 'Lower', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V * W**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - V1 * W**T\n*\n                  CALL DGEMM( 'No transpose', 'Transpose',\n     $                 LASTV-K, LASTC, K, -ONE, V, LDV, WORK, LDWORK,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2**T\n*\n               CALL DTRMM( 'Right', 'Upper', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W**T\n*\n               DO 90 J = 1, K\n                  DO 80 I = 1, LASTC\n                     C( LASTV-K+J, I ) = C( LASTV-K+J, I ) - WORK(I, J)\n   80             CONTINUE\n   90          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**T  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILADLR( N, K, V, LDV ) )\n               LASTC = ILADLR( M, LASTV, C, LDC )\n*\n*              W := C * V  =  (C1*V1 + C2*V2)  (stored in WORK)\n*\n*              W := C2\n*\n               DO 100 J = 1, K\n                  CALL DCOPY( LASTC, C( 1, N-K+J ), 1, WORK( 1, J ), 1 )\n  100          CONTINUE\n*\n*              W := W * V2\n*\n               CALL DTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1 * V1\n*\n                  CALL DGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**T\n*\n               CALL DTRMM( 'Right', 'Lower', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - W * V1**T\n*\n                  CALL DGEMM( 'No transpose', 'Transpose',\n     $                 LASTC, LASTV-K, K, -ONE, WORK, LDWORK, V, LDV,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2**T\n*\n               CALL DTRMM( 'Right', 'Upper', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W\n*\n               DO 120 J = 1, K\n                  DO 110 I = 1, LASTC\n                     C( I, LASTV-K+J ) = C( I, LASTV-K+J ) - WORK(I, J)\n  110             CONTINUE\n  120          CONTINUE\n            END IF\n         END IF\n*\n      ELSE IF( LSAME( STOREV, 'R' ) ) THEN\n*\n         IF( LSAME( DIRECT, 'F' ) ) THEN\n*\n*           Let  V =  ( V1  V2 )    (V1: first K columns)\n*           where  V1  is unit upper triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**T * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILADLC( K, M, V, LDV ) )\n               LASTC = ILADLC( LASTV, N, C, LDC )\n*\n*              W := C**T * V**T  =  (C1**T * V1**T + C2**T * V2**T) (stored in WORK)\n*\n*              W := C1**T\n*\n               DO 130 J = 1, K\n                  CALL DCOPY( LASTC, C( J, 1 ), LDC, WORK( 1, J ), 1 )\n  130          CONTINUE\n*\n*              W := W * V1**T\n*\n               CALL DTRMM( 'Right', 'Upper', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2**T*V2**T\n*\n                  CALL DGEMM( 'Transpose', 'Transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C( K+1, 1 ), LDC, V( 1, K+1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**T  or  W * T\n*\n               CALL DTRMM( 'Right', 'Upper', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V**T * W**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - V2**T * W**T\n*\n                  CALL DGEMM( 'Transpose', 'Transpose',\n     $                 LASTV-K, LASTC, K,\n     $                 -ONE, V( 1, K+1 ), LDV, WORK, LDWORK,\n     $                 ONE, C( K+1, 1 ), LDC )\n               END IF\n*\n*              W := W * V1\n*\n               CALL DTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W**T\n*\n               DO 150 J = 1, K\n                  DO 140 I = 1, LASTC\n                     C( J, I ) = C( J, I ) - WORK( I, J )\n  140             CONTINUE\n  150          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**T  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILADLC( K, N, V, LDV ) )\n               LASTC = ILADLR( M, LASTV, C, LDC )\n*\n*              W := C * V**T  =  (C1*V1**T + C2*V2**T)  (stored in WORK)\n*\n*              W := C1\n*\n               DO 160 J = 1, K\n                  CALL DCOPY( LASTC, C( 1, J ), 1, WORK( 1, J ), 1 )\n  160          CONTINUE\n*\n*              W := W * V1**T\n*\n               CALL DTRMM( 'Right', 'Upper', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2 * V2**T\n*\n                  CALL DGEMM( 'No transpose', 'Transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C( 1, K+1 ), LDC, V( 1, K+1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**T\n*\n               CALL DTRMM( 'Right', 'Upper', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - W * V2\n*\n                  CALL DGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, LASTV-K, K,\n     $                 -ONE, WORK, LDWORK, V( 1, K+1 ), LDV,\n     $                 ONE, C( 1, K+1 ), LDC )\n               END IF\n*\n*              W := W * V1\n*\n               CALL DTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 180 J = 1, K\n                  DO 170 I = 1, LASTC\n                     C( I, J ) = C( I, J ) - WORK( I, J )\n  170             CONTINUE\n  180          CONTINUE\n*\n            END IF\n*\n         ELSE\n*\n*           Let  V =  ( V1  V2 )    (V2: last K columns)\n*           where  V2  is unit lower triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**T * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILADLC( K, M, V, LDV ) )\n               LASTC = ILADLC( LASTV, N, C, LDC )\n*\n*              W := C**T * V**T  =  (C1**T * V1**T + C2**T * V2**T) (stored in WORK)\n*\n*              W := C2**T\n*\n               DO 190 J = 1, K\n                  CALL DCOPY( LASTC, C( LASTV-K+J, 1 ), LDC,\n     $                 WORK( 1, J ), 1 )\n  190          CONTINUE\n*\n*              W := W * V2**T\n*\n               CALL DTRMM( 'Right', 'Lower', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1**T * V1**T\n*\n                  CALL DGEMM( 'Transpose', 'Transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**T  or  W * T\n*\n               CALL DTRMM( 'Right', 'Lower', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V**T * W**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - V1**T * W**T\n*\n                  CALL DGEMM( 'Transpose', 'Transpose',\n     $                 LASTV-K, LASTC, K, -ONE, V, LDV, WORK, LDWORK,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2\n*\n               CALL DTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W**T\n*\n               DO 210 J = 1, K\n                  DO 200 I = 1, LASTC\n                     C( LASTV-K+J, I ) = C( LASTV-K+J, I ) - WORK(I, J)\n  200             CONTINUE\n  210          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**T  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILADLC( K, N, V, LDV ) )\n               LASTC = ILADLR( M, LASTV, C, LDC )\n*\n*              W := C * V**T  =  (C1*V1**T + C2*V2**T)  (stored in WORK)\n*\n*              W := C2\n*\n               DO 220 J = 1, K\n                  CALL DCOPY( LASTC, C( 1, LASTV-K+J ), 1,\n     $                 WORK( 1, J ), 1 )\n  220          CONTINUE\n*\n*              W := W * V2**T\n*\n               CALL DTRMM( 'Right', 'Lower', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1 * V1**T\n*\n                  CALL DGEMM( 'No transpose', 'Transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**T\n*\n               CALL DTRMM( 'Right', 'Lower', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - W * V1\n*\n                  CALL DGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, LASTV-K, K, -ONE, WORK, LDWORK, V, LDV,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2\n*\n               CALL DTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 240 J = 1, K\n                  DO 230 I = 1, LASTC\n                     C( I, LASTV-K+J ) = C( I, LASTV-K+J ) - WORK(I, J)\n  230             CONTINUE\n  240          CONTINUE\n*\n            END IF\n*\n         END IF\n      END IF\n*\n      RETURN\n*\n*     End of DLARFB\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/dlarfg.f",
    "content": "*> \\brief \\b DLARFG\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download DLARFG + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/dlarfg.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/dlarfg.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/dlarfg.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE DLARFG( N, ALPHA, X, INCX, TAU )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            INCX, N\n*       DOUBLE PRECISION   ALPHA, TAU\n*       ..\n*       .. Array Arguments ..\n*       DOUBLE PRECISION   X( * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> DLARFG generates a real elementary reflector H of order n, such\n*> that\n*>\n*>       H * ( alpha ) = ( beta ),   H**T * H = I.\n*>           (   x   )   (   0  )\n*>\n*> where alpha and beta are scalars, and x is an (n-1)-element real\n*> vector. H is represented in the form\n*>\n*>       H = I - tau * ( 1 ) * ( 1 v**T ) ,\n*>                     ( v )\n*>\n*> where tau is a real scalar and v is a real (n-1)-element\n*> vector.\n*>\n*> If the elements of x are all zero, then tau = 0 and H is taken to be\n*> the unit matrix.\n*>\n*> Otherwise  1 <= tau <= 2.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The order of the elementary reflector.\n*> \\endverbatim\n*>\n*> \\param[in,out] ALPHA\n*> \\verbatim\n*>          ALPHA is DOUBLE PRECISION\n*>          On entry, the value alpha.\n*>          On exit, it is overwritten with the value beta.\n*> \\endverbatim\n*>\n*> \\param[in,out] X\n*> \\verbatim\n*>          X is DOUBLE PRECISION array, dimension\n*>                         (1+(N-2)*abs(INCX))\n*>          On entry, the vector x.\n*>          On exit, it is overwritten with the vector v.\n*> \\endverbatim\n*>\n*> \\param[in] INCX\n*> \\verbatim\n*>          INCX is INTEGER\n*>          The increment between elements of X. INCX > 0.\n*> \\endverbatim\n*>\n*> \\param[out] TAU\n*> \\verbatim\n*>          TAU is DOUBLE PRECISION\n*>          The value tau.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup doubleOTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE DLARFG( N, ALPHA, X, INCX, TAU )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      INTEGER            INCX, N\n      DOUBLE PRECISION   ALPHA, TAU\n*     ..\n*     .. Array Arguments ..\n      DOUBLE PRECISION   X( * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ONE, ZERO\n      PARAMETER          ( ONE = 1.0D+0, ZERO = 0.0D+0 )\n*     ..\n*     .. Local Scalars ..\n      INTEGER            J, KNT\n      DOUBLE PRECISION   BETA, RSAFMN, SAFMIN, XNORM\n*     ..\n*     .. External Functions ..\n      DOUBLE PRECISION   DLAMCH, DLAPY2, DNRM2\n      EXTERNAL           DLAMCH, DLAPY2, DNRM2\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, SIGN\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           DSCAL\n*     ..\n*     .. Executable Statements ..\n*\n      IF( N.LE.1 ) THEN\n         TAU = ZERO\n         RETURN\n      END IF\n*\n      XNORM = DNRM2( N-1, X, INCX )\n*\n      IF( XNORM.EQ.ZERO ) THEN\n*\n*        H  =  I\n*\n         TAU = ZERO\n      ELSE\n*\n*        general case\n*\n         BETA = -SIGN( DLAPY2( ALPHA, XNORM ), ALPHA )\n         SAFMIN = DLAMCH( 'S' ) / DLAMCH( 'E' )\n         KNT = 0\n         IF( ABS( BETA ).LT.SAFMIN ) THEN\n*\n*           XNORM, BETA may be inaccurate; scale X and recompute them\n*\n            RSAFMN = ONE / SAFMIN\n   10       CONTINUE\n            KNT = KNT + 1\n            CALL DSCAL( N-1, RSAFMN, X, INCX )\n            BETA = BETA*RSAFMN\n            ALPHA = ALPHA*RSAFMN\n            IF( ABS( BETA ).LT.SAFMIN )\n     $         GO TO 10\n*\n*           New BETA is at most 1, at least SAFMIN\n*\n            XNORM = DNRM2( N-1, X, INCX )\n            BETA = -SIGN( DLAPY2( ALPHA, XNORM ), ALPHA )\n         END IF\n         TAU = ( BETA-ALPHA ) / BETA\n         CALL DSCAL( N-1, ONE / ( ALPHA-BETA ), X, INCX )\n*\n*        If ALPHA is subnormal, it may lose relative accuracy\n*\n         DO 20 J = 1, KNT\n            BETA = BETA*SAFMIN\n 20      CONTINUE\n         ALPHA = BETA\n      END IF\n*\n      RETURN\n*\n*     End of DLARFG\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/dlarft.f",
    "content": "*> \\brief \\b DLARFT\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download DLARFT + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/dlarft.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/dlarft.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/dlarft.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE DLARFT( DIRECT, STOREV, N, K, V, LDV, TAU, T, LDT )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          DIRECT, STOREV\n*       INTEGER            K, LDT, LDV, N\n*       ..\n*       .. Array Arguments ..\n*       DOUBLE PRECISION   T( LDT, * ), TAU( * ), V( LDV, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> DLARFT forms the triangular factor T of a real block reflector H\n*> of order n, which is defined as a product of k elementary reflectors.\n*>\n*> If DIRECT = 'F', H = H(1) H(2) . . . H(k) and T is upper triangular;\n*>\n*> If DIRECT = 'B', H = H(k) . . . H(2) H(1) and T is lower triangular.\n*>\n*> If STOREV = 'C', the vector which defines the elementary reflector\n*> H(i) is stored in the i-th column of the array V, and\n*>\n*>    H  =  I - V * T * V**T\n*>\n*> If STOREV = 'R', the vector which defines the elementary reflector\n*> H(i) is stored in the i-th row of the array V, and\n*>\n*>    H  =  I - V**T * T * V\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] DIRECT\n*> \\verbatim\n*>          DIRECT is CHARACTER*1\n*>          Specifies the order in which the elementary reflectors are\n*>          multiplied to form the block reflector:\n*>          = 'F': H = H(1) H(2) . . . H(k) (Forward)\n*>          = 'B': H = H(k) . . . H(2) H(1) (Backward)\n*> \\endverbatim\n*>\n*> \\param[in] STOREV\n*> \\verbatim\n*>          STOREV is CHARACTER*1\n*>          Specifies how the vectors which define the elementary\n*>          reflectors are stored (see also Further Details):\n*>          = 'C': columnwise\n*>          = 'R': rowwise\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The order of the block reflector H. N >= 0.\n*> \\endverbatim\n*>\n*> \\param[in] K\n*> \\verbatim\n*>          K is INTEGER\n*>          The order of the triangular factor T (= the number of\n*>          elementary reflectors). K >= 1.\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is DOUBLE PRECISION array, dimension\n*>                               (LDV,K) if STOREV = 'C'\n*>                               (LDV,N) if STOREV = 'R'\n*>          The matrix V. See further details.\n*> \\endverbatim\n*>\n*> \\param[in] LDV\n*> \\verbatim\n*>          LDV is INTEGER\n*>          The leading dimension of the array V.\n*>          If STOREV = 'C', LDV >= max(1,N); if STOREV = 'R', LDV >= K.\n*> \\endverbatim\n*>\n*> \\param[in] TAU\n*> \\verbatim\n*>          TAU is DOUBLE PRECISION array, dimension (K)\n*>          TAU(i) must contain the scalar factor of the elementary\n*>          reflector H(i).\n*> \\endverbatim\n*>\n*> \\param[out] T\n*> \\verbatim\n*>          T is DOUBLE PRECISION array, dimension (LDT,K)\n*>          The k by k triangular factor T of the block reflector.\n*>          If DIRECT = 'F', T is upper triangular; if DIRECT = 'B', T is\n*>          lower triangular. The rest of the array is not used.\n*> \\endverbatim\n*>\n*> \\param[in] LDT\n*> \\verbatim\n*>          LDT is INTEGER\n*>          The leading dimension of the array T. LDT >= K.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup doubleOTHERauxiliary\n*\n*> \\par Further Details:\n*  =====================\n*>\n*> \\verbatim\n*>\n*>  The shape of the matrix V and the storage of the vectors which define\n*>  the H(i) is best illustrated by the following example with n = 5 and\n*>  k = 3. The elements equal to 1 are not stored.\n*>\n*>  DIRECT = 'F' and STOREV = 'C':         DIRECT = 'F' and STOREV = 'R':\n*>\n*>               V = (  1       )                 V = (  1 v1 v1 v1 v1 )\n*>                   ( v1  1    )                     (     1 v2 v2 v2 )\n*>                   ( v1 v2  1 )                     (        1 v3 v3 )\n*>                   ( v1 v2 v3 )\n*>                   ( v1 v2 v3 )\n*>\n*>  DIRECT = 'B' and STOREV = 'C':         DIRECT = 'B' and STOREV = 'R':\n*>\n*>               V = ( v1 v2 v3 )                 V = ( v1 v1  1       )\n*>                   ( v1 v2 v3 )                     ( v2 v2 v2  1    )\n*>                   (  1 v2 v3 )                     ( v3 v3 v3 v3  1 )\n*>                   (     1 v3 )\n*>                   (        1 )\n*> \\endverbatim\n*>\n*  =====================================================================\n      SUBROUTINE DLARFT( DIRECT, STOREV, N, K, V, LDV, TAU, T, LDT )\n*\n*  -- LAPACK auxiliary routine (version 3.4.1) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*     .. Scalar Arguments ..\n      CHARACTER          DIRECT, STOREV\n      INTEGER            K, LDT, LDV, N\n*     ..\n*     .. Array Arguments ..\n      DOUBLE PRECISION   T( LDT, * ), TAU( * ), V( LDV, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ONE, ZERO\n      PARAMETER          ( ONE = 1.0D+0, ZERO = 0.0D+0 )\n*     ..\n*     .. Local Scalars ..\n      INTEGER            I, J, PREVLASTV, LASTV\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           DGEMV, DTRMV\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      EXTERNAL           LSAME\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick return if possible\n*\n      IF( N.EQ.0 )\n     $   RETURN\n*\n      IF( LSAME( DIRECT, 'F' ) ) THEN\n         PREVLASTV = N\n         DO I = 1, K\n            PREVLASTV = MAX( I, PREVLASTV )\n            IF( TAU( I ).EQ.ZERO ) THEN\n*\n*              H(i)  =  I\n*\n               DO J = 1, I\n                  T( J, I ) = ZERO\n               END DO\n            ELSE\n*\n*              general case\n*\n               IF( LSAME( STOREV, 'C' ) ) THEN\n*                 Skip any trailing zeros.\n                  DO LASTV = N, I+1, -1\n                     IF( V( LASTV, I ).NE.ZERO ) EXIT\n                  END DO\n                  DO J = 1, I-1\n                     T( J, I ) = -TAU( I ) * V( I , J )\n                  END DO   \n                  J = MIN( LASTV, PREVLASTV )\n*\n*                 T(1:i-1,i) := - tau(i) * V(i:j,1:i-1)**T * V(i:j,i)\n*\n                  CALL DGEMV( 'Transpose', J-I, I-1, -TAU( I ), \n     $                        V( I+1, 1 ), LDV, V( I+1, I ), 1, ONE, \n     $                        T( 1, I ), 1 )\n               ELSE\n*                 Skip any trailing zeros.\n                  DO LASTV = N, I+1, -1\n                     IF( V( I, LASTV ).NE.ZERO ) EXIT\n                  END DO\n                  DO J = 1, I-1\n                     T( J, I ) = -TAU( I ) * V( J , I )\n                  END DO   \n                  J = MIN( LASTV, PREVLASTV )\n*\n*                 T(1:i-1,i) := - tau(i) * V(1:i-1,i:j) * V(i,i:j)**T\n*\n                  CALL DGEMV( 'No transpose', I-1, J-I, -TAU( I ),\n     $                        V( 1, I+1 ), LDV, V( I, I+1 ), LDV, ONE,\n     $                        T( 1, I ), 1 )\n               END IF\n*\n*              T(1:i-1,i) := T(1:i-1,1:i-1) * T(1:i-1,i)\n*\n               CALL DTRMV( 'Upper', 'No transpose', 'Non-unit', I-1, T,\n     $                     LDT, T( 1, I ), 1 )\n               T( I, I ) = TAU( I )\n               IF( I.GT.1 ) THEN\n                  PREVLASTV = MAX( PREVLASTV, LASTV )\n               ELSE\n                  PREVLASTV = LASTV\n               END IF\n            END IF\n         END DO\n      ELSE\n         PREVLASTV = 1\n         DO I = K, 1, -1\n            IF( TAU( I ).EQ.ZERO ) THEN\n*\n*              H(i)  =  I\n*\n               DO J = I, K\n                  T( J, I ) = ZERO\n               END DO\n            ELSE\n*\n*              general case\n*\n               IF( I.LT.K ) THEN\n                  IF( LSAME( STOREV, 'C' ) ) THEN\n*                    Skip any leading zeros.\n                     DO LASTV = 1, I-1\n                        IF( V( LASTV, I ).NE.ZERO ) EXIT\n                     END DO\n                     DO J = I+1, K\n                        T( J, I ) = -TAU( I ) * V( N-K+I , J )\n                     END DO   \n                     J = MAX( LASTV, PREVLASTV )\n*\n*                    T(i+1:k,i) = -tau(i) * V(j:n-k+i,i+1:k)**T * V(j:n-k+i,i)\n*\n                     CALL DGEMV( 'Transpose', N-K+I-J, K-I, -TAU( I ),\n     $                           V( J, I+1 ), LDV, V( J, I ), 1, ONE,\n     $                           T( I+1, I ), 1 )\n                  ELSE\n*                    Skip any leading zeros.\n                     DO LASTV = 1, I-1\n                        IF( V( I, LASTV ).NE.ZERO ) EXIT\n                     END DO\n                     DO J = I+1, K\n                        T( J, I ) = -TAU( I ) * V( J, N-K+I )\n                     END DO   \n                     J = MAX( LASTV, PREVLASTV )\n*\n*                    T(i+1:k,i) = -tau(i) * V(i+1:k,j:n-k+i) * V(i,j:n-k+i)**T\n*\n                     CALL DGEMV( 'No transpose', K-I, N-K+I-J,\n     $                    -TAU( I ), V( I+1, J ), LDV, V( I, J ), LDV,\n     $                    ONE, T( I+1, I ), 1 )\n                  END IF\n*\n*                 T(i+1:k,i) := T(i+1:k,i+1:k) * T(i+1:k,i)\n*\n                  CALL DTRMV( 'Lower', 'No transpose', 'Non-unit', K-I,\n     $                        T( I+1, I+1 ), LDT, T( I+1, I ), 1 )\n                  IF( I.GT.1 ) THEN\n                     PREVLASTV = MIN( PREVLASTV, LASTV )\n                  ELSE\n                     PREVLASTV = LASTV\n                  END IF\n               END IF\n               T( I, I ) = TAU( I )\n            END IF\n         END DO\n      END IF\n      RETURN\n*\n*     End of DLARFT\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/double.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define SCALAR        double\n#define SCALAR_SUFFIX d\n#define SCALAR_SUFFIX_UP \"D\"\n#define ISCOMPLEX     0\n\n#include \"cholesky.cpp\"\n#include \"lu.cpp\"\n#include \"eigenvalues.cpp\"\n#include \"svd.cpp\"\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/dsecnd_NONE.f",
    "content": "*> \\brief \\b DSECND returns nothing\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*      DOUBLE PRECISION FUNCTION DSECND( )\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*>  DSECND returns nothing instead of returning the user time for a process in seconds.\n*>  If you are using that routine, it means that neither EXTERNAL ETIME,\n*>  EXTERNAL ETIME_, INTERNAL ETIME, INTERNAL CPU_TIME is available  on\n*>  your machine.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      DOUBLE PRECISION FUNCTION DSECND( )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n* =====================================================================\n*\n      DSECND = 0.0D+0\n      RETURN\n*\n*     End of DSECND\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/eigenvalues.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"lapack_common.h\"\n#include <Eigen/Eigenvalues>\n\n// computes eigen values and vectors of a general N-by-N matrix A\nEIGEN_LAPACK_FUNC(syev,(char *jobz, char *uplo, int* n, Scalar* a, int *lda, Scalar* w, Scalar* /*work*/, int* lwork, int *info))\n{\n  // TODO exploit the work buffer\n  bool query_size = *lwork==-1;\n  \n  *info = 0;\n        if(*jobz!='N' && *jobz!='V')                    *info = -1;\n  else  if(UPLO(*uplo)==INVALID)                        *info = -2;\n  else  if(*n<0)                                        *info = -3;\n  else  if(*lda<std::max(1,*n))                         *info = -5;\n  else  if((!query_size) && *lwork<std::max(1,3**n-1))  *info = -8;\n    \n  if(*info!=0)\n  {\n    int e = -*info;\n    return xerbla_(SCALAR_SUFFIX_UP\"SYEV \", &e, 6);\n  }\n  \n  if(query_size)\n  {\n    *lwork = 0;\n    return 0;\n  }\n  \n  if(*n==0)\n    return 0;\n  \n  PlainMatrixType mat(*n,*n);\n  if(UPLO(*uplo)==UP) mat = matrix(a,*n,*n,*lda).adjoint();\n  else                mat = matrix(a,*n,*n,*lda);\n  \n  bool computeVectors = *jobz=='V' || *jobz=='v';\n  SelfAdjointEigenSolver<PlainMatrixType> eig(mat,computeVectors?ComputeEigenvectors:EigenvaluesOnly);\n  \n  if(eig.info()==NoConvergence)\n  {\n    make_vector(w,*n).setZero();\n    if(computeVectors)\n      matrix(a,*n,*n,*lda).setIdentity();\n    //*info = 1;\n    return 0;\n  }\n  \n  make_vector(w,*n) = eig.eigenvalues();\n  if(computeVectors)\n    matrix(a,*n,*n,*lda) = eig.eigenvectors();\n  \n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/ilaclc.f",
    "content": "*> \\brief \\b ILACLC\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ILACLC + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/ilaclc.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/ilaclc.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/ilaclc.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       INTEGER FUNCTION ILACLC( M, N, A, LDA )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            M, N, LDA\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX            A( LDA, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ILACLC scans A for its last non-zero column.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] A\n*> \\verbatim\n*>          A is COMPLEX array, dimension (LDA,N)\n*>          The m by n matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] LDA\n*> \\verbatim\n*>          LDA is INTEGER\n*>          The leading dimension of the array A. LDA >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complexOTHERauxiliary\n*\n*  =====================================================================\n      INTEGER FUNCTION ILACLC( M, N, A, LDA )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      INTEGER            M, N, LDA\n*     ..\n*     .. Array Arguments ..\n      COMPLEX            A( LDA, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      COMPLEX          ZERO\n      PARAMETER ( ZERO = (0.0E+0, 0.0E+0) )\n*     ..\n*     .. Local Scalars ..\n      INTEGER I\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick test for the common case where one corner is non-zero.\n      IF( N.EQ.0 ) THEN\n         ILACLC = N\n      ELSE IF( A(1, N).NE.ZERO .OR. A(M, N).NE.ZERO ) THEN\n         ILACLC = N\n      ELSE\n*     Now scan each column from the end, returning with the first non-zero.\n         DO ILACLC = N, 1, -1\n            DO I = 1, M\n               IF( A(I, ILACLC).NE.ZERO ) RETURN\n            END DO\n         END DO\n      END IF\n      RETURN\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/ilaclr.f",
    "content": "*> \\brief \\b ILACLR\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ILACLR + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/ilaclr.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/ilaclr.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/ilaclr.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       INTEGER FUNCTION ILACLR( M, N, A, LDA )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            M, N, LDA\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX            A( LDA, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ILACLR scans A for its last non-zero row.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] A\n*> \\verbatim\n*>          A is array, dimension (LDA,N)\n*>          The m by n matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] LDA\n*> \\verbatim\n*>          LDA is INTEGER\n*>          The leading dimension of the array A. LDA >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup complexOTHERauxiliary\n*\n*  =====================================================================\n      INTEGER FUNCTION ILACLR( M, N, A, LDA )\n*\n*  -- LAPACK auxiliary routine (version 3.4.1) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*     .. Scalar Arguments ..\n      INTEGER            M, N, LDA\n*     ..\n*     .. Array Arguments ..\n      COMPLEX            A( LDA, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      COMPLEX          ZERO\n      PARAMETER ( ZERO = (0.0E+0, 0.0E+0) )\n*     ..\n*     .. Local Scalars ..\n      INTEGER I, J\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick test for the common case where one corner is non-zero.\n      IF( M.EQ.0 ) THEN\n         ILACLR = M\n      ELSE IF( A(M, 1).NE.ZERO .OR. A(M, N).NE.ZERO ) THEN\n         ILACLR = M\n      ELSE\n*     Scan up each column tracking the last zero row seen.\n         ILACLR = 0\n         DO J = 1, N\n            I=M\n            DO WHILE((A(MAX(I,1),J).EQ.ZERO).AND.(I.GE.1))\n               I=I-1\n            ENDDO\n            ILACLR = MAX( ILACLR, I )\n         END DO\n      END IF\n      RETURN\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/iladlc.f",
    "content": "*> \\brief \\b ILADLC\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ILADLC + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/iladlc.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/iladlc.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/iladlc.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       INTEGER FUNCTION ILADLC( M, N, A, LDA )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            M, N, LDA\n*       ..\n*       .. Array Arguments ..\n*       DOUBLE PRECISION   A( LDA, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ILADLC scans A for its last non-zero column.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] A\n*> \\verbatim\n*>          A is DOUBLE PRECISION array, dimension (LDA,N)\n*>          The m by n matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] LDA\n*> \\verbatim\n*>          LDA is INTEGER\n*>          The leading dimension of the array A. LDA >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      INTEGER FUNCTION ILADLC( M, N, A, LDA )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      INTEGER            M, N, LDA\n*     ..\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( LDA, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      DOUBLE PRECISION ZERO\n      PARAMETER ( ZERO = 0.0D+0 )\n*     ..\n*     .. Local Scalars ..\n      INTEGER I\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick test for the common case where one corner is non-zero.\n      IF( N.EQ.0 ) THEN\n         ILADLC = N\n      ELSE IF( A(1, N).NE.ZERO .OR. A(M, N).NE.ZERO ) THEN\n         ILADLC = N\n      ELSE\n*     Now scan each column from the end, returning with the first non-zero.\n         DO ILADLC = N, 1, -1\n            DO I = 1, M\n               IF( A(I, ILADLC).NE.ZERO ) RETURN\n            END DO\n         END DO\n      END IF\n      RETURN\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/iladlr.f",
    "content": "*> \\brief \\b ILADLR\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ILADLR + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/iladlr.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/iladlr.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/iladlr.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       INTEGER FUNCTION ILADLR( M, N, A, LDA )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            M, N, LDA\n*       ..\n*       .. Array Arguments ..\n*       DOUBLE PRECISION   A( LDA, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ILADLR scans A for its last non-zero row.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] A\n*> \\verbatim\n*>          A is DOUBLE PRECISION array, dimension (LDA,N)\n*>          The m by n matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] LDA\n*> \\verbatim\n*>          LDA is INTEGER\n*>          The leading dimension of the array A. LDA >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      INTEGER FUNCTION ILADLR( M, N, A, LDA )\n*\n*  -- LAPACK auxiliary routine (version 3.4.1) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*     .. Scalar Arguments ..\n      INTEGER            M, N, LDA\n*     ..\n*     .. Array Arguments ..\n      DOUBLE PRECISION   A( LDA, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      DOUBLE PRECISION ZERO\n      PARAMETER ( ZERO = 0.0D+0 )\n*     ..\n*     .. Local Scalars ..\n      INTEGER I, J\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick test for the common case where one corner is non-zero.\n      IF( M.EQ.0 ) THEN\n         ILADLR = M\n      ELSE IF( A(M, 1).NE.ZERO .OR. A(M, N).NE.ZERO ) THEN\n         ILADLR = M\n      ELSE\n*     Scan up each column tracking the last zero row seen.\n         ILADLR = 0\n         DO J = 1, N\n            I=M\n            DO WHILE((A(MAX(I,1),J).EQ.ZERO).AND.(I.GE.1))\n               I=I-1\n            ENDDO\n            ILADLR = MAX( ILADLR, I )\n         END DO\n      END IF\n      RETURN\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/ilaslc.f",
    "content": "*> \\brief \\b ILASLC\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ILASLC + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/ilaslc.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/ilaslc.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/ilaslc.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       INTEGER FUNCTION ILASLC( M, N, A, LDA )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            M, N, LDA\n*       ..\n*       .. Array Arguments ..\n*       REAL               A( LDA, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ILASLC scans A for its last non-zero column.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] A\n*> \\verbatim\n*>          A is REAL array, dimension (LDA,N)\n*>          The m by n matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] LDA\n*> \\verbatim\n*>          LDA is INTEGER\n*>          The leading dimension of the array A. LDA >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup realOTHERauxiliary\n*\n*  =====================================================================\n      INTEGER FUNCTION ILASLC( M, N, A, LDA )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      INTEGER            M, N, LDA\n*     ..\n*     .. Array Arguments ..\n      REAL               A( LDA, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      REAL             ZERO\n      PARAMETER ( ZERO = 0.0D+0 )\n*     ..\n*     .. Local Scalars ..\n      INTEGER I\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick test for the common case where one corner is non-zero.\n      IF( N.EQ.0 ) THEN\n         ILASLC = N\n      ELSE IF( A(1, N).NE.ZERO .OR. A(M, N).NE.ZERO ) THEN\n         ILASLC = N\n      ELSE\n*     Now scan each column from the end, returning with the first non-zero.\n         DO ILASLC = N, 1, -1\n            DO I = 1, M\n               IF( A(I, ILASLC).NE.ZERO ) RETURN\n            END DO\n         END DO\n      END IF\n      RETURN\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/ilaslr.f",
    "content": "*> \\brief \\b ILASLR\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ILASLR + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/ilaslr.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/ilaslr.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/ilaslr.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       INTEGER FUNCTION ILASLR( M, N, A, LDA )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            M, N, LDA\n*       ..\n*       .. Array Arguments ..\n*       REAL               A( LDA, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ILASLR scans A for its last non-zero row.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] A\n*> \\verbatim\n*>          A is REAL array, dimension (LDA,N)\n*>          The m by n matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] LDA\n*> \\verbatim\n*>          LDA is INTEGER\n*>          The leading dimension of the array A. LDA >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup realOTHERauxiliary\n*\n*  =====================================================================\n      INTEGER FUNCTION ILASLR( M, N, A, LDA )\n*\n*  -- LAPACK auxiliary routine (version 3.4.1) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*     .. Scalar Arguments ..\n      INTEGER            M, N, LDA\n*     ..\n*     .. Array Arguments ..\n      REAL               A( LDA, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      REAL             ZERO\n      PARAMETER ( ZERO = 0.0E+0 )\n*     ..\n*     .. Local Scalars ..\n      INTEGER I, J\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick test for the common case where one corner is non-zero.\n      IF( M.EQ.0 ) THEN\n         ILASLR = M\n      ELSEIF( A(M, 1).NE.ZERO .OR. A(M, N).NE.ZERO ) THEN\n         ILASLR = M\n      ELSE\n*     Scan up each column tracking the last zero row seen.\n         ILASLR = 0\n         DO J = 1, N\n            I=M\n            DO WHILE((A(MAX(I,1),J).EQ.ZERO).AND.(I.GE.1))\n               I=I-1\n            ENDDO\n            ILASLR = MAX( ILASLR, I )\n         END DO\n      END IF\n      RETURN\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/ilazlc.f",
    "content": "*> \\brief \\b ILAZLC\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ILAZLC + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/ilazlc.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/ilazlc.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/ilazlc.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       INTEGER FUNCTION ILAZLC( M, N, A, LDA )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            M, N, LDA\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX*16         A( LDA, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ILAZLC scans A for its last non-zero column.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] A\n*> \\verbatim\n*>          A is COMPLEX*16 array, dimension (LDA,N)\n*>          The m by n matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] LDA\n*> \\verbatim\n*>          LDA is INTEGER\n*>          The leading dimension of the array A. LDA >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complex16OTHERauxiliary\n*\n*  =====================================================================\n      INTEGER FUNCTION ILAZLC( M, N, A, LDA )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      INTEGER            M, N, LDA\n*     ..\n*     .. Array Arguments ..\n      COMPLEX*16         A( LDA, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      COMPLEX*16       ZERO\n      PARAMETER ( ZERO = (0.0D+0, 0.0D+0) )\n*     ..\n*     .. Local Scalars ..\n      INTEGER I\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick test for the common case where one corner is non-zero.\n      IF( N.EQ.0 ) THEN\n         ILAZLC = N\n      ELSE IF( A(1, N).NE.ZERO .OR. A(M, N).NE.ZERO ) THEN\n         ILAZLC = N\n      ELSE\n*     Now scan each column from the end, returning with the first non-zero.\n         DO ILAZLC = N, 1, -1\n            DO I = 1, M\n               IF( A(I, ILAZLC).NE.ZERO ) RETURN\n            END DO\n         END DO\n      END IF\n      RETURN\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/ilazlr.f",
    "content": "*> \\brief \\b ILAZLR\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ILAZLR + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/ilazlr.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/ilazlr.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/ilazlr.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       INTEGER FUNCTION ILAZLR( M, N, A, LDA )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            M, N, LDA\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX*16         A( LDA, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ILAZLR scans A for its last non-zero row.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] A\n*> \\verbatim\n*>          A is COMPLEX*16 array, dimension (LDA,N)\n*>          The m by n matrix A.\n*> \\endverbatim\n*>\n*> \\param[in] LDA\n*> \\verbatim\n*>          LDA is INTEGER\n*>          The leading dimension of the array A. LDA >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup complex16OTHERauxiliary\n*\n*  =====================================================================\n      INTEGER FUNCTION ILAZLR( M, N, A, LDA )\n*\n*  -- LAPACK auxiliary routine (version 3.4.1) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*     .. Scalar Arguments ..\n      INTEGER            M, N, LDA\n*     ..\n*     .. Array Arguments ..\n      COMPLEX*16         A( LDA, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      COMPLEX*16       ZERO\n      PARAMETER ( ZERO = (0.0D+0, 0.0D+0) )\n*     ..\n*     .. Local Scalars ..\n      INTEGER I, J\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick test for the common case where one corner is non-zero.\n      IF( M.EQ.0 ) THEN\n         ILAZLR = M\n      ELSE IF( A(M, 1).NE.ZERO .OR. A(M, N).NE.ZERO ) THEN\n         ILAZLR = M\n      ELSE\n*     Scan up each column tracking the last zero row seen.\n         ILAZLR = 0\n         DO J = 1, N\n            I=M\n            DO WHILE((A(MAX(I,1),J).EQ.ZERO).AND.(I.GE.1))\n               I=I-1\n            ENDDO\n            ILAZLR = MAX( ILAZLR, I )\n         END DO\n      END IF\n      RETURN\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/lapack_common.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_LAPACK_COMMON_H\n#define EIGEN_LAPACK_COMMON_H\n\n#include \"../blas/common.h\"\n#include \"../Eigen/src/misc/lapack.h\"\n\n#define EIGEN_LAPACK_FUNC(FUNC,ARGLIST)               \\\n  extern \"C\" { int EIGEN_BLAS_FUNC(FUNC) ARGLIST; }   \\\n  int EIGEN_BLAS_FUNC(FUNC) ARGLIST\n\ntypedef Eigen::Map<Eigen::Transpositions<Eigen::Dynamic,Eigen::Dynamic,int> > PivotsType;\n\n#if ISCOMPLEX\n#define EIGEN_LAPACK_ARG_IF_COMPLEX(X) X,\n#else\n#define EIGEN_LAPACK_ARG_IF_COMPLEX(X)\n#endif\n\n\n#endif // EIGEN_LAPACK_COMMON_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/lu.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010-2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"common.h\"\n#include <Eigen/LU>\n\n// computes an LU factorization of a general M-by-N matrix A using partial pivoting with row interchanges\nEIGEN_LAPACK_FUNC(getrf,(int *m, int *n, RealScalar *pa, int *lda, int *ipiv, int *info))\n{\n  *info = 0;\n        if(*m<0)                  *info = -1;\n  else  if(*n<0)                  *info = -2;\n  else  if(*lda<std::max(1,*m))   *info = -4;\n  if(*info!=0)\n  {\n    int e = -*info;\n    return xerbla_(SCALAR_SUFFIX_UP\"GETRF\", &e, 6);\n  }\n\n  if(*m==0 || *n==0)\n    return 0;\n\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  int nb_transpositions;\n  int ret = int(Eigen::internal::partial_lu_impl<Scalar,ColMajor,int>\n                     ::blocked_lu(*m, *n, a, *lda, ipiv, nb_transpositions));\n\n  for(int i=0; i<std::min(*m,*n); ++i)\n    ipiv[i]++;\n\n  if(ret>=0)\n    *info = ret+1;\n\n  return 0;\n}\n\n//GETRS solves a system of linear equations\n//    A * X = B  or  A' * X = B\n//  with a general N-by-N matrix A using the LU factorization computed  by GETRF\nEIGEN_LAPACK_FUNC(getrs,(char *trans, int *n, int *nrhs, RealScalar *pa, int *lda, int *ipiv, RealScalar *pb, int *ldb, int *info))\n{\n  *info = 0;\n        if(OP(*trans)==INVALID)  *info = -1;\n  else  if(*n<0)                 *info = -2;\n  else  if(*nrhs<0)              *info = -3;\n  else  if(*lda<std::max(1,*n))  *info = -5;\n  else  if(*ldb<std::max(1,*n))  *info = -8;\n  if(*info!=0)\n  {\n    int e = -*info;\n    return xerbla_(SCALAR_SUFFIX_UP\"GETRS\", &e, 6);\n  }\n\n  Scalar* a = reinterpret_cast<Scalar*>(pa);\n  Scalar* b = reinterpret_cast<Scalar*>(pb);\n  MatrixType lu(a,*n,*n,*lda);\n  MatrixType B(b,*n,*nrhs,*ldb);\n\n  for(int i=0; i<*n; ++i)\n    ipiv[i]--;\n  if(OP(*trans)==NOTR)\n  {\n    B = PivotsType(ipiv,*n) * B;\n    lu.triangularView<UnitLower>().solveInPlace(B);\n    lu.triangularView<Upper>().solveInPlace(B);\n  }\n  else if(OP(*trans)==TR)\n  {\n    lu.triangularView<Upper>().transpose().solveInPlace(B);\n    lu.triangularView<UnitLower>().transpose().solveInPlace(B);\n    B = PivotsType(ipiv,*n).transpose() * B;\n  }\n  else if(OP(*trans)==ADJ)\n  {\n    lu.triangularView<Upper>().adjoint().solveInPlace(B);\n    lu.triangularView<UnitLower>().adjoint().solveInPlace(B);\n    B = PivotsType(ipiv,*n).transpose() * B;\n  }\n  for(int i=0; i<*n; ++i)\n    ipiv[i]++;\n\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/second_NONE.f",
    "content": "*> \\brief \\b SECOND returns nothing\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*      REAL FUNCTION SECOND( )\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*>  SECOND returns nothing instead of returning the user time for a process in seconds.\n*>  If you are using that routine, it means that neither EXTERNAL ETIME,\n*>  EXTERNAL ETIME_, INTERNAL ETIME, INTERNAL CPU_TIME is available  on\n*>  your machine.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      REAL FUNCTION SECOND( )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n* =====================================================================\n*\n      SECOND = 0.0E+0\n      RETURN\n*\n*     End of SECOND\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/single.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define SCALAR        float\n#define SCALAR_SUFFIX s\n#define SCALAR_SUFFIX_UP \"S\"\n#define ISCOMPLEX     0\n\n#include \"cholesky.cpp\"\n#include \"lu.cpp\"\n#include \"eigenvalues.cpp\"\n#include \"svd.cpp\"\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/sladiv.f",
    "content": "*> \\brief \\b SLADIV\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download SLADIV + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/sladiv.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/sladiv.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/sladiv.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE SLADIV( A, B, C, D, P, Q )\n* \n*       .. Scalar Arguments ..\n*       REAL               A, B, C, D, P, Q\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> SLADIV performs complex division in  real arithmetic\n*>\n*>                       a + i*b\n*>            p + i*q = ---------\n*>                       c + i*d\n*>\n*> The algorithm is due to Robert L. Smith and can be found\n*> in D. Knuth, The art of Computer Programming, Vol.2, p.195\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] A\n*> \\verbatim\n*>          A is REAL\n*> \\endverbatim\n*>\n*> \\param[in] B\n*> \\verbatim\n*>          B is REAL\n*> \\endverbatim\n*>\n*> \\param[in] C\n*> \\verbatim\n*>          C is REAL\n*> \\endverbatim\n*>\n*> \\param[in] D\n*> \\verbatim\n*>          D is REAL\n*>          The scalars a, b, c, and d in the above expression.\n*> \\endverbatim\n*>\n*> \\param[out] P\n*> \\verbatim\n*>          P is REAL\n*> \\endverbatim\n*>\n*> \\param[out] Q\n*> \\verbatim\n*>          Q is REAL\n*>          The scalars p and q in the above expression.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE SLADIV( A, B, C, D, P, Q )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      REAL               A, B, C, D, P, Q\n*     ..\n*\n*  =====================================================================\n*\n*     .. Local Scalars ..\n      REAL               E, F\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS\n*     ..\n*     .. Executable Statements ..\n*\n      IF( ABS( D ).LT.ABS( C ) ) THEN\n         E = D / C\n         F = C + D*E\n         P = ( A+B*E ) / F\n         Q = ( B-A*E ) / F\n      ELSE\n         E = C / D\n         F = D + C*E\n         P = ( B+A*E ) / F\n         Q = ( -A+B*E ) / F\n      END IF\n*\n      RETURN\n*\n*     End of SLADIV\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/slamch.f",
    "content": "*> \\brief \\b SLAMCH\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*  Definition:\n*  ===========\n*\n*      REAL             FUNCTION SLAMCH( CMACH )\n*\n*     .. Scalar Arguments ..\n*      CHARACTER          CMACH\n*     ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> SLAMCH determines single precision machine parameters.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] CMACH\n*> \\verbatim\n*>          Specifies the value to be returned by SLAMCH:\n*>          = 'E' or 'e',   SLAMCH := eps\n*>          = 'S' or 's ,   SLAMCH := sfmin\n*>          = 'B' or 'b',   SLAMCH := base\n*>          = 'P' or 'p',   SLAMCH := eps*base\n*>          = 'N' or 'n',   SLAMCH := t\n*>          = 'R' or 'r',   SLAMCH := rnd\n*>          = 'M' or 'm',   SLAMCH := emin\n*>          = 'U' or 'u',   SLAMCH := rmin\n*>          = 'L' or 'l',   SLAMCH := emax\n*>          = 'O' or 'o',   SLAMCH := rmax\n*>          where\n*>          eps   = relative machine precision\n*>          sfmin = safe minimum, such that 1/sfmin does not overflow\n*>          base  = base of the machine\n*>          prec  = eps*base\n*>          t     = number of (base) digits in the mantissa\n*>          rnd   = 1.0 when rounding occurs in addition, 0.0 otherwise\n*>          emin  = minimum exponent before (gradual) underflow\n*>          rmin  = underflow threshold - base**(emin-1)\n*>          emax  = largest exponent before overflow\n*>          rmax  = overflow threshold  - (base**emax)*(1-eps)\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      REAL             FUNCTION SLAMCH( CMACH )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      CHARACTER          CMACH\n*     ..\n*\n* =====================================================================\n*\n*     .. Parameters ..\n      REAL               ONE, ZERO\n      PARAMETER          ( ONE = 1.0E+0, ZERO = 0.0E+0 )\n*     ..\n*     .. Local Scalars ..\n      REAL               RND, EPS, SFMIN, SMALL, RMACH\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      EXTERNAL           LSAME\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          DIGITS, EPSILON, HUGE, MAXEXPONENT,\n     $                   MINEXPONENT, RADIX, TINY\n*     ..\n*     .. Executable Statements ..\n*\n*\n*     Assume rounding, not chopping. Always.\n*\n      RND = ONE\n*\n      IF( ONE.EQ.RND ) THEN\n         EPS = EPSILON(ZERO) * 0.5\n      ELSE\n         EPS = EPSILON(ZERO)\n      END IF\n*\n      IF( LSAME( CMACH, 'E' ) ) THEN\n         RMACH = EPS\n      ELSE IF( LSAME( CMACH, 'S' ) ) THEN\n         SFMIN = TINY(ZERO)\n         SMALL = ONE / HUGE(ZERO)\n         IF( SMALL.GE.SFMIN ) THEN\n*\n*           Use SMALL plus a bit, to avoid the possibility of rounding\n*           causing overflow when computing  1/sfmin.\n*\n            SFMIN = SMALL*( ONE+EPS )\n         END IF\n         RMACH = SFMIN\n      ELSE IF( LSAME( CMACH, 'B' ) ) THEN\n         RMACH = RADIX(ZERO)\n      ELSE IF( LSAME( CMACH, 'P' ) ) THEN\n         RMACH = EPS * RADIX(ZERO)\n      ELSE IF( LSAME( CMACH, 'N' ) ) THEN\n         RMACH = DIGITS(ZERO)\n      ELSE IF( LSAME( CMACH, 'R' ) ) THEN\n         RMACH = RND\n      ELSE IF( LSAME( CMACH, 'M' ) ) THEN\n         RMACH = MINEXPONENT(ZERO)\n      ELSE IF( LSAME( CMACH, 'U' ) ) THEN\n         RMACH = tiny(zero)\n      ELSE IF( LSAME( CMACH, 'L' ) ) THEN\n         RMACH = MAXEXPONENT(ZERO)\n      ELSE IF( LSAME( CMACH, 'O' ) ) THEN\n         RMACH = HUGE(ZERO)\n      ELSE\n         RMACH = ZERO\n      END IF\n*\n      SLAMCH = RMACH\n      RETURN\n*\n*     End of SLAMCH\n*\n      END\n************************************************************************\n*> \\brief \\b SLAMC3\n*> \\details\n*> \\b Purpose:\n*> \\verbatim\n*> SLAMC3  is intended to force  A  and  B  to be stored prior to doing\n*> the addition of  A  and  B ,  for use in situations where optimizers\n*> might hold one of these in a register.\n*> \\endverbatim\n*> \\author LAPACK is a software package provided by Univ. of Tennessee, Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..\n*> \\date November 2011\n*> \\ingroup auxOTHERauxiliary\n*>\n*> \\param[in] A\n*> \\verbatim\n*> \\endverbatim\n*>\n*> \\param[in] B\n*> \\verbatim\n*>          The values A and B.\n*> \\endverbatim\n*>\n*\n      REAL             FUNCTION SLAMC3( A, B )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*     Univ. of Tennessee, Univ. of California Berkeley and NAG Ltd..\n*     November 2010\n*\n*     .. Scalar Arguments ..\n      REAL               A, B\n*     ..\n* =====================================================================\n*\n*     .. Executable Statements ..\n*\n      SLAMC3 = A + B\n*\n      RETURN\n*\n*     End of SLAMC3\n*\n      END\n*\n************************************************************************\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/slapy2.f",
    "content": "*> \\brief \\b SLAPY2\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download SLAPY2 + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/slapy2.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/slapy2.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/slapy2.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       REAL             FUNCTION SLAPY2( X, Y )\n* \n*       .. Scalar Arguments ..\n*       REAL               X, Y\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> SLAPY2 returns sqrt(x**2+y**2), taking care not to cause unnecessary\n*> overflow.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] X\n*> \\verbatim\n*>          X is REAL\n*> \\endverbatim\n*>\n*> \\param[in] Y\n*> \\verbatim\n*>          Y is REAL\n*>          X and Y specify the values x and y.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      REAL             FUNCTION SLAPY2( X, Y )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      REAL               X, Y\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      REAL               ZERO\n      PARAMETER          ( ZERO = 0.0E0 )\n      REAL               ONE\n      PARAMETER          ( ONE = 1.0E0 )\n*     ..\n*     .. Local Scalars ..\n      REAL               W, XABS, YABS, Z\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, MIN, SQRT\n*     ..\n*     .. Executable Statements ..\n*\n      XABS = ABS( X )\n      YABS = ABS( Y )\n      W = MAX( XABS, YABS )\n      Z = MIN( XABS, YABS )\n      IF( Z.EQ.ZERO ) THEN\n         SLAPY2 = W\n      ELSE\n         SLAPY2 = W*SQRT( ONE+( Z / W )**2 )\n      END IF\n      RETURN\n*\n*     End of SLAPY2\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/slapy3.f",
    "content": "*> \\brief \\b SLAPY3\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download SLAPY3 + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/slapy3.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/slapy3.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/slapy3.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       REAL             FUNCTION SLAPY3( X, Y, Z )\n* \n*       .. Scalar Arguments ..\n*       REAL               X, Y, Z\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> SLAPY3 returns sqrt(x**2+y**2+z**2), taking care not to cause\n*> unnecessary overflow.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] X\n*> \\verbatim\n*>          X is REAL\n*> \\endverbatim\n*>\n*> \\param[in] Y\n*> \\verbatim\n*>          Y is REAL\n*> \\endverbatim\n*>\n*> \\param[in] Z\n*> \\verbatim\n*>          Z is REAL\n*>          X, Y and Z specify the values x, y and z.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup auxOTHERauxiliary\n*\n*  =====================================================================\n      REAL             FUNCTION SLAPY3( X, Y, Z )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      REAL               X, Y, Z\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      REAL               ZERO\n      PARAMETER          ( ZERO = 0.0E0 )\n*     ..\n*     .. Local Scalars ..\n      REAL               W, XABS, YABS, ZABS\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, MAX, SQRT\n*     ..\n*     .. Executable Statements ..\n*\n      XABS = ABS( X )\n      YABS = ABS( Y )\n      ZABS = ABS( Z )\n      W = MAX( XABS, YABS, ZABS )\n      IF( W.EQ.ZERO ) THEN\n*     W can be zero for max(0,nan,0)\n*     adding all three entries together will make sure\n*     NaN will not disappear.\n         SLAPY3 =  XABS + YABS + ZABS\n      ELSE\n         SLAPY3 = W*SQRT( ( XABS / W )**2+( YABS / W )**2+\n     $            ( ZABS / W )**2 )\n      END IF\n      RETURN\n*\n*     End of SLAPY3\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/slarf.f",
    "content": "*> \\brief \\b SLARF\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download SLARF + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/slarf.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/slarf.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/slarf.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE SLARF( SIDE, M, N, V, INCV, TAU, C, LDC, WORK )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          SIDE\n*       INTEGER            INCV, LDC, M, N\n*       REAL               TAU\n*       ..\n*       .. Array Arguments ..\n*       REAL               C( LDC, * ), V( * ), WORK( * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> SLARF applies a real elementary reflector H to a real m by n matrix\n*> C, from either the left or the right. H is represented in the form\n*>\n*>       H = I - tau * v * v**T\n*>\n*> where tau is a real scalar and v is a real vector.\n*>\n*> If tau = 0, then H is taken to be the unit matrix.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] SIDE\n*> \\verbatim\n*>          SIDE is CHARACTER*1\n*>          = 'L': form  H * C\n*>          = 'R': form  C * H\n*> \\endverbatim\n*>\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is REAL array, dimension\n*>                     (1 + (M-1)*abs(INCV)) if SIDE = 'L'\n*>                  or (1 + (N-1)*abs(INCV)) if SIDE = 'R'\n*>          The vector v in the representation of H. V is not used if\n*>          TAU = 0.\n*> \\endverbatim\n*>\n*> \\param[in] INCV\n*> \\verbatim\n*>          INCV is INTEGER\n*>          The increment between elements of v. INCV <> 0.\n*> \\endverbatim\n*>\n*> \\param[in] TAU\n*> \\verbatim\n*>          TAU is REAL\n*>          The value tau in the representation of H.\n*> \\endverbatim\n*>\n*> \\param[in,out] C\n*> \\verbatim\n*>          C is REAL array, dimension (LDC,N)\n*>          On entry, the m by n matrix C.\n*>          On exit, C is overwritten by the matrix H * C if SIDE = 'L',\n*>          or C * H if SIDE = 'R'.\n*> \\endverbatim\n*>\n*> \\param[in] LDC\n*> \\verbatim\n*>          LDC is INTEGER\n*>          The leading dimension of the array C. LDC >= max(1,M).\n*> \\endverbatim\n*>\n*> \\param[out] WORK\n*> \\verbatim\n*>          WORK is REAL array, dimension\n*>                         (N) if SIDE = 'L'\n*>                      or (M) if SIDE = 'R'\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup realOTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE SLARF( SIDE, M, N, V, INCV, TAU, C, LDC, WORK )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      CHARACTER          SIDE\n      INTEGER            INCV, LDC, M, N\n      REAL               TAU\n*     ..\n*     .. Array Arguments ..\n      REAL               C( LDC, * ), V( * ), WORK( * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      REAL               ONE, ZERO\n      PARAMETER          ( ONE = 1.0E+0, ZERO = 0.0E+0 )\n*     ..\n*     .. Local Scalars ..\n      LOGICAL            APPLYLEFT\n      INTEGER            I, LASTV, LASTC\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           SGEMV, SGER\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      INTEGER            ILASLR, ILASLC\n      EXTERNAL           LSAME, ILASLR, ILASLC\n*     ..\n*     .. Executable Statements ..\n*\n      APPLYLEFT = LSAME( SIDE, 'L' )\n      LASTV = 0\n      LASTC = 0\n      IF( TAU.NE.ZERO ) THEN\n!     Set up variables for scanning V.  LASTV begins pointing to the end\n!     of V.\n         IF( APPLYLEFT ) THEN\n            LASTV = M\n         ELSE\n            LASTV = N\n         END IF\n         IF( INCV.GT.0 ) THEN\n            I = 1 + (LASTV-1) * INCV\n         ELSE\n            I = 1\n         END IF\n!     Look for the last non-zero row in V.\n         DO WHILE( LASTV.GT.0 .AND. V( I ).EQ.ZERO )\n            LASTV = LASTV - 1\n            I = I - INCV\n         END DO\n         IF( APPLYLEFT ) THEN\n!     Scan for the last non-zero column in C(1:lastv,:).\n            LASTC = ILASLC(LASTV, N, C, LDC)\n         ELSE\n!     Scan for the last non-zero row in C(:,1:lastv).\n            LASTC = ILASLR(M, LASTV, C, LDC)\n         END IF\n      END IF\n!     Note that lastc.eq.0 renders the BLAS operations null; no special\n!     case is needed at this level.\n      IF( APPLYLEFT ) THEN\n*\n*        Form  H * C\n*\n         IF( LASTV.GT.0 ) THEN\n*\n*           w(1:lastc,1) := C(1:lastv,1:lastc)**T * v(1:lastv,1)\n*\n            CALL SGEMV( 'Transpose', LASTV, LASTC, ONE, C, LDC, V, INCV,\n     $           ZERO, WORK, 1 )\n*\n*           C(1:lastv,1:lastc) := C(...) - v(1:lastv,1) * w(1:lastc,1)**T\n*\n            CALL SGER( LASTV, LASTC, -TAU, V, INCV, WORK, 1, C, LDC )\n         END IF\n      ELSE\n*\n*        Form  C * H\n*\n         IF( LASTV.GT.0 ) THEN\n*\n*           w(1:lastc,1) := C(1:lastc,1:lastv) * v(1:lastv,1)\n*\n            CALL SGEMV( 'No transpose', LASTC, LASTV, ONE, C, LDC,\n     $           V, INCV, ZERO, WORK, 1 )\n*\n*           C(1:lastc,1:lastv) := C(...) - w(1:lastc,1) * v(1:lastv,1)**T\n*\n            CALL SGER( LASTC, LASTV, -TAU, WORK, 1, V, INCV, C, LDC )\n         END IF\n      END IF\n      RETURN\n*\n*     End of SLARF\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/slarfb.f",
    "content": "*> \\brief \\b SLARFB\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download SLARFB + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/slarfb.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/slarfb.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/slarfb.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE SLARFB( SIDE, TRANS, DIRECT, STOREV, M, N, K, V, LDV,\n*                          T, LDT, C, LDC, WORK, LDWORK )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          DIRECT, SIDE, STOREV, TRANS\n*       INTEGER            K, LDC, LDT, LDV, LDWORK, M, N\n*       ..\n*       .. Array Arguments ..\n*       REAL               C( LDC, * ), T( LDT, * ), V( LDV, * ),\n*      $                   WORK( LDWORK, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> SLARFB applies a real block reflector H or its transpose H**T to a\n*> real m by n matrix C, from either the left or the right.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] SIDE\n*> \\verbatim\n*>          SIDE is CHARACTER*1\n*>          = 'L': apply H or H**T from the Left\n*>          = 'R': apply H or H**T from the Right\n*> \\endverbatim\n*>\n*> \\param[in] TRANS\n*> \\verbatim\n*>          TRANS is CHARACTER*1\n*>          = 'N': apply H (No transpose)\n*>          = 'T': apply H**T (Transpose)\n*> \\endverbatim\n*>\n*> \\param[in] DIRECT\n*> \\verbatim\n*>          DIRECT is CHARACTER*1\n*>          Indicates how H is formed from a product of elementary\n*>          reflectors\n*>          = 'F': H = H(1) H(2) . . . H(k) (Forward)\n*>          = 'B': H = H(k) . . . H(2) H(1) (Backward)\n*> \\endverbatim\n*>\n*> \\param[in] STOREV\n*> \\verbatim\n*>          STOREV is CHARACTER*1\n*>          Indicates how the vectors which define the elementary\n*>          reflectors are stored:\n*>          = 'C': Columnwise\n*>          = 'R': Rowwise\n*> \\endverbatim\n*>\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] K\n*> \\verbatim\n*>          K is INTEGER\n*>          The order of the matrix T (= the number of elementary\n*>          reflectors whose product defines the block reflector).\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is REAL array, dimension\n*>                                (LDV,K) if STOREV = 'C'\n*>                                (LDV,M) if STOREV = 'R' and SIDE = 'L'\n*>                                (LDV,N) if STOREV = 'R' and SIDE = 'R'\n*>          The matrix V. See Further Details.\n*> \\endverbatim\n*>\n*> \\param[in] LDV\n*> \\verbatim\n*>          LDV is INTEGER\n*>          The leading dimension of the array V.\n*>          If STOREV = 'C' and SIDE = 'L', LDV >= max(1,M);\n*>          if STOREV = 'C' and SIDE = 'R', LDV >= max(1,N);\n*>          if STOREV = 'R', LDV >= K.\n*> \\endverbatim\n*>\n*> \\param[in] T\n*> \\verbatim\n*>          T is REAL array, dimension (LDT,K)\n*>          The triangular k by k matrix T in the representation of the\n*>          block reflector.\n*> \\endverbatim\n*>\n*> \\param[in] LDT\n*> \\verbatim\n*>          LDT is INTEGER\n*>          The leading dimension of the array T. LDT >= K.\n*> \\endverbatim\n*>\n*> \\param[in,out] C\n*> \\verbatim\n*>          C is REAL array, dimension (LDC,N)\n*>          On entry, the m by n matrix C.\n*>          On exit, C is overwritten by H*C or H**T*C or C*H or C*H**T.\n*> \\endverbatim\n*>\n*> \\param[in] LDC\n*> \\verbatim\n*>          LDC is INTEGER\n*>          The leading dimension of the array C. LDC >= max(1,M).\n*> \\endverbatim\n*>\n*> \\param[out] WORK\n*> \\verbatim\n*>          WORK is REAL array, dimension (LDWORK,K)\n*> \\endverbatim\n*>\n*> \\param[in] LDWORK\n*> \\verbatim\n*>          LDWORK is INTEGER\n*>          The leading dimension of the array WORK.\n*>          If SIDE = 'L', LDWORK >= max(1,N);\n*>          if SIDE = 'R', LDWORK >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup realOTHERauxiliary\n*\n*> \\par Further Details:\n*  =====================\n*>\n*> \\verbatim\n*>\n*>  The shape of the matrix V and the storage of the vectors which define\n*>  the H(i) is best illustrated by the following example with n = 5 and\n*>  k = 3. The elements equal to 1 are not stored; the corresponding\n*>  array elements are modified but restored on exit. The rest of the\n*>  array is not used.\n*>\n*>  DIRECT = 'F' and STOREV = 'C':         DIRECT = 'F' and STOREV = 'R':\n*>\n*>               V = (  1       )                 V = (  1 v1 v1 v1 v1 )\n*>                   ( v1  1    )                     (     1 v2 v2 v2 )\n*>                   ( v1 v2  1 )                     (        1 v3 v3 )\n*>                   ( v1 v2 v3 )\n*>                   ( v1 v2 v3 )\n*>\n*>  DIRECT = 'B' and STOREV = 'C':         DIRECT = 'B' and STOREV = 'R':\n*>\n*>               V = ( v1 v2 v3 )                 V = ( v1 v1  1       )\n*>                   ( v1 v2 v3 )                     ( v2 v2 v2  1    )\n*>                   (  1 v2 v3 )                     ( v3 v3 v3 v3  1 )\n*>                   (     1 v3 )\n*>                   (        1 )\n*> \\endverbatim\n*>\n*  =====================================================================\n      SUBROUTINE SLARFB( SIDE, TRANS, DIRECT, STOREV, M, N, K, V, LDV,\n     $                   T, LDT, C, LDC, WORK, LDWORK )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      CHARACTER          DIRECT, SIDE, STOREV, TRANS\n      INTEGER            K, LDC, LDT, LDV, LDWORK, M, N\n*     ..\n*     .. Array Arguments ..\n      REAL               C( LDC, * ), T( LDT, * ), V( LDV, * ),\n     $                   WORK( LDWORK, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      REAL               ONE\n      PARAMETER          ( ONE = 1.0E+0 )\n*     ..\n*     .. Local Scalars ..\n      CHARACTER          TRANST\n      INTEGER            I, J, LASTV, LASTC\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      INTEGER            ILASLR, ILASLC\n      EXTERNAL           LSAME, ILASLR, ILASLC\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           SCOPY, SGEMM, STRMM\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick return if possible\n*\n      IF( M.LE.0 .OR. N.LE.0 )\n     $   RETURN\n*\n      IF( LSAME( TRANS, 'N' ) ) THEN\n         TRANST = 'T'\n      ELSE\n         TRANST = 'N'\n      END IF\n*\n      IF( LSAME( STOREV, 'C' ) ) THEN\n*\n         IF( LSAME( DIRECT, 'F' ) ) THEN\n*\n*           Let  V =  ( V1 )    (first K rows)\n*                     ( V2 )\n*           where  V1  is unit lower triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**T * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILASLR( M, K, V, LDV ) )\n               LASTC = ILASLC( LASTV, N, C, LDC )\n*\n*              W := C**T * V  =  (C1**T * V1 + C2**T * V2)  (stored in WORK)\n*\n*              W := C1**T\n*\n               DO 10 J = 1, K\n                  CALL SCOPY( LASTC, C( J, 1 ), LDC, WORK( 1, J ), 1 )\n   10          CONTINUE\n*\n*              W := W * V1\n*\n               CALL STRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2**T *V2\n*\n                  CALL SGEMM( 'Transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C( K+1, 1 ), LDC, V( K+1, 1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**T  or  W * T\n*\n               CALL STRMM( 'Right', 'Upper', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V * W**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - V2 * W**T\n*\n                  CALL SGEMM( 'No transpose', 'Transpose',\n     $                 LASTV-K, LASTC, K,\n     $                 -ONE, V( K+1, 1 ), LDV, WORK, LDWORK, ONE,\n     $                 C( K+1, 1 ), LDC )\n               END IF\n*\n*              W := W * V1**T\n*\n               CALL STRMM( 'Right', 'Lower', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W**T\n*\n               DO 30 J = 1, K\n                  DO 20 I = 1, LASTC\n                     C( J, I ) = C( J, I ) - WORK( I, J )\n   20             CONTINUE\n   30          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**T  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILASLR( N, K, V, LDV ) )\n               LASTC = ILASLR( M, LASTV, C, LDC )\n*\n*              W := C * V  =  (C1*V1 + C2*V2)  (stored in WORK)\n*\n*              W := C1\n*\n               DO 40 J = 1, K\n                  CALL SCOPY( LASTC, C( 1, J ), 1, WORK( 1, J ), 1 )\n   40          CONTINUE\n*\n*              W := W * V1\n*\n               CALL STRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2 * V2\n*\n                  CALL SGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C( 1, K+1 ), LDC, V( K+1, 1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**T\n*\n               CALL STRMM( 'Right', 'Upper', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - W * V2**T\n*\n                  CALL SGEMM( 'No transpose', 'Transpose',\n     $                 LASTC, LASTV-K, K,\n     $                 -ONE, WORK, LDWORK, V( K+1, 1 ), LDV, ONE,\n     $                 C( 1, K+1 ), LDC )\n               END IF\n*\n*              W := W * V1**T\n*\n               CALL STRMM( 'Right', 'Lower', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 60 J = 1, K\n                  DO 50 I = 1, LASTC\n                     C( I, J ) = C( I, J ) - WORK( I, J )\n   50             CONTINUE\n   60          CONTINUE\n            END IF\n*\n         ELSE\n*\n*           Let  V =  ( V1 )\n*                     ( V2 )    (last K rows)\n*           where  V2  is unit upper triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**T * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILASLR( M, K, V, LDV ) )\n               LASTC = ILASLC( LASTV, N, C, LDC )\n*\n*              W := C**T * V  =  (C1**T * V1 + C2**T * V2)  (stored in WORK)\n*\n*              W := C2**T\n*\n               DO 70 J = 1, K\n                  CALL SCOPY( LASTC, C( LASTV-K+J, 1 ), LDC,\n     $                 WORK( 1, J ), 1 )\n   70          CONTINUE\n*\n*              W := W * V2\n*\n               CALL STRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1**T*V1\n*\n                  CALL SGEMM( 'Transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**T  or  W * T\n*\n               CALL STRMM( 'Right', 'Lower', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V * W**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - V1 * W**T\n*\n                  CALL SGEMM( 'No transpose', 'Transpose',\n     $                 LASTV-K, LASTC, K, -ONE, V, LDV, WORK, LDWORK,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2**T\n*\n               CALL STRMM( 'Right', 'Upper', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W**T\n*\n               DO 90 J = 1, K\n                  DO 80 I = 1, LASTC\n                     C( LASTV-K+J, I ) = C( LASTV-K+J, I ) - WORK(I, J)\n   80             CONTINUE\n   90          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**T  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILASLR( N, K, V, LDV ) )\n               LASTC = ILASLR( M, LASTV, C, LDC )\n*\n*              W := C * V  =  (C1*V1 + C2*V2)  (stored in WORK)\n*\n*              W := C2\n*\n               DO 100 J = 1, K\n                  CALL SCOPY( LASTC, C( 1, N-K+J ), 1, WORK( 1, J ), 1 )\n  100          CONTINUE\n*\n*              W := W * V2\n*\n               CALL STRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1 * V1\n*\n                  CALL SGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**T\n*\n               CALL STRMM( 'Right', 'Lower', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - W * V1**T\n*\n                  CALL SGEMM( 'No transpose', 'Transpose',\n     $                 LASTC, LASTV-K, K, -ONE, WORK, LDWORK, V, LDV,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2**T\n*\n               CALL STRMM( 'Right', 'Upper', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W\n*\n               DO 120 J = 1, K\n                  DO 110 I = 1, LASTC\n                     C( I, LASTV-K+J ) = C( I, LASTV-K+J ) - WORK(I, J)\n  110             CONTINUE\n  120          CONTINUE\n            END IF\n         END IF\n*\n      ELSE IF( LSAME( STOREV, 'R' ) ) THEN\n*\n         IF( LSAME( DIRECT, 'F' ) ) THEN\n*\n*           Let  V =  ( V1  V2 )    (V1: first K columns)\n*           where  V1  is unit upper triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**T * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILASLC( K, M, V, LDV ) )\n               LASTC = ILASLC( LASTV, N, C, LDC )\n*\n*              W := C**T * V**T  =  (C1**T * V1**T + C2**T * V2**T) (stored in WORK)\n*\n*              W := C1**T\n*\n               DO 130 J = 1, K\n                  CALL SCOPY( LASTC, C( J, 1 ), LDC, WORK( 1, J ), 1 )\n  130          CONTINUE\n*\n*              W := W * V1**T\n*\n               CALL STRMM( 'Right', 'Upper', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2**T*V2**T\n*\n                  CALL SGEMM( 'Transpose', 'Transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C( K+1, 1 ), LDC, V( 1, K+1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**T  or  W * T\n*\n               CALL STRMM( 'Right', 'Upper', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V**T * W**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - V2**T * W**T\n*\n                  CALL SGEMM( 'Transpose', 'Transpose',\n     $                 LASTV-K, LASTC, K,\n     $                 -ONE, V( 1, K+1 ), LDV, WORK, LDWORK,\n     $                 ONE, C( K+1, 1 ), LDC )\n               END IF\n*\n*              W := W * V1\n*\n               CALL STRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W**T\n*\n               DO 150 J = 1, K\n                  DO 140 I = 1, LASTC\n                     C( J, I ) = C( J, I ) - WORK( I, J )\n  140             CONTINUE\n  150          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**T  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILASLC( K, N, V, LDV ) )\n               LASTC = ILASLR( M, LASTV, C, LDC )\n*\n*              W := C * V**T  =  (C1*V1**T + C2*V2**T)  (stored in WORK)\n*\n*              W := C1\n*\n               DO 160 J = 1, K\n                  CALL SCOPY( LASTC, C( 1, J ), 1, WORK( 1, J ), 1 )\n  160          CONTINUE\n*\n*              W := W * V1**T\n*\n               CALL STRMM( 'Right', 'Upper', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2 * V2**T\n*\n                  CALL SGEMM( 'No transpose', 'Transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C( 1, K+1 ), LDC, V( 1, K+1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**T\n*\n               CALL STRMM( 'Right', 'Upper', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - W * V2\n*\n                  CALL SGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, LASTV-K, K,\n     $                 -ONE, WORK, LDWORK, V( 1, K+1 ), LDV,\n     $                 ONE, C( 1, K+1 ), LDC )\n               END IF\n*\n*              W := W * V1\n*\n               CALL STRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 180 J = 1, K\n                  DO 170 I = 1, LASTC\n                     C( I, J ) = C( I, J ) - WORK( I, J )\n  170             CONTINUE\n  180          CONTINUE\n*\n            END IF\n*\n         ELSE\n*\n*           Let  V =  ( V1  V2 )    (V2: last K columns)\n*           where  V2  is unit lower triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**T * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILASLC( K, M, V, LDV ) )\n               LASTC = ILASLC( LASTV, N, C, LDC )\n*\n*              W := C**T * V**T  =  (C1**T * V1**T + C2**T * V2**T) (stored in WORK)\n*\n*              W := C2**T\n*\n               DO 190 J = 1, K\n                  CALL SCOPY( LASTC, C( LASTV-K+J, 1 ), LDC,\n     $                 WORK( 1, J ), 1 )\n  190          CONTINUE\n*\n*              W := W * V2**T\n*\n               CALL STRMM( 'Right', 'Lower', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1**T * V1**T\n*\n                  CALL SGEMM( 'Transpose', 'Transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**T  or  W * T\n*\n               CALL STRMM( 'Right', 'Lower', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V**T * W**T\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - V1**T * W**T\n*\n                  CALL SGEMM( 'Transpose', 'Transpose',\n     $                 LASTV-K, LASTC, K, -ONE, V, LDV, WORK, LDWORK,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2\n*\n               CALL STRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W**T\n*\n               DO 210 J = 1, K\n                  DO 200 I = 1, LASTC\n                     C( LASTV-K+J, I ) = C( LASTV-K+J, I ) - WORK(I, J)\n  200             CONTINUE\n  210          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**T  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILASLC( K, N, V, LDV ) )\n               LASTC = ILASLR( M, LASTV, C, LDC )\n*\n*              W := C * V**T  =  (C1*V1**T + C2*V2**T)  (stored in WORK)\n*\n*              W := C2\n*\n               DO 220 J = 1, K\n                  CALL SCOPY( LASTC, C( 1, LASTV-K+J ), 1,\n     $                 WORK( 1, J ), 1 )\n  220          CONTINUE\n*\n*              W := W * V2**T\n*\n               CALL STRMM( 'Right', 'Lower', 'Transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1 * V1**T\n*\n                  CALL SGEMM( 'No transpose', 'Transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**T\n*\n               CALL STRMM( 'Right', 'Lower', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - W * V1\n*\n                  CALL SGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, LASTV-K, K, -ONE, WORK, LDWORK, V, LDV,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2\n*\n               CALL STRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 240 J = 1, K\n                  DO 230 I = 1, LASTC\n                     C( I, LASTV-K+J ) = C( I, LASTV-K+J )\n     $                    - WORK( I, J )\n  230             CONTINUE\n  240          CONTINUE\n*\n            END IF\n*\n         END IF\n      END IF\n*\n      RETURN\n*\n*     End of SLARFB\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/slarfg.f",
    "content": "*> \\brief \\b SLARFG\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download SLARFG + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/slarfg.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/slarfg.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/slarfg.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE SLARFG( N, ALPHA, X, INCX, TAU )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            INCX, N\n*       REAL               ALPHA, TAU\n*       ..\n*       .. Array Arguments ..\n*       REAL               X( * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> SLARFG generates a real elementary reflector H of order n, such\n*> that\n*>\n*>       H * ( alpha ) = ( beta ),   H**T * H = I.\n*>           (   x   )   (   0  )\n*>\n*> where alpha and beta are scalars, and x is an (n-1)-element real\n*> vector. H is represented in the form\n*>\n*>       H = I - tau * ( 1 ) * ( 1 v**T ) ,\n*>                     ( v )\n*>\n*> where tau is a real scalar and v is a real (n-1)-element\n*> vector.\n*>\n*> If the elements of x are all zero, then tau = 0 and H is taken to be\n*> the unit matrix.\n*>\n*> Otherwise  1 <= tau <= 2.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The order of the elementary reflector.\n*> \\endverbatim\n*>\n*> \\param[in,out] ALPHA\n*> \\verbatim\n*>          ALPHA is REAL\n*>          On entry, the value alpha.\n*>          On exit, it is overwritten with the value beta.\n*> \\endverbatim\n*>\n*> \\param[in,out] X\n*> \\verbatim\n*>          X is REAL array, dimension\n*>                         (1+(N-2)*abs(INCX))\n*>          On entry, the vector x.\n*>          On exit, it is overwritten with the vector v.\n*> \\endverbatim\n*>\n*> \\param[in] INCX\n*> \\verbatim\n*>          INCX is INTEGER\n*>          The increment between elements of X. INCX > 0.\n*> \\endverbatim\n*>\n*> \\param[out] TAU\n*> \\verbatim\n*>          TAU is REAL\n*>          The value tau.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup realOTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE SLARFG( N, ALPHA, X, INCX, TAU )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      INTEGER            INCX, N\n      REAL               ALPHA, TAU\n*     ..\n*     .. Array Arguments ..\n      REAL               X( * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      REAL               ONE, ZERO\n      PARAMETER          ( ONE = 1.0E+0, ZERO = 0.0E+0 )\n*     ..\n*     .. Local Scalars ..\n      INTEGER            J, KNT\n      REAL               BETA, RSAFMN, SAFMIN, XNORM\n*     ..\n*     .. External Functions ..\n      REAL               SLAMCH, SLAPY2, SNRM2\n      EXTERNAL           SLAMCH, SLAPY2, SNRM2\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, SIGN\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           SSCAL\n*     ..\n*     .. Executable Statements ..\n*\n      IF( N.LE.1 ) THEN\n         TAU = ZERO\n         RETURN\n      END IF\n*\n      XNORM = SNRM2( N-1, X, INCX )\n*\n      IF( XNORM.EQ.ZERO ) THEN\n*\n*        H  =  I\n*\n         TAU = ZERO\n      ELSE\n*\n*        general case\n*\n         BETA = -SIGN( SLAPY2( ALPHA, XNORM ), ALPHA )\n         SAFMIN = SLAMCH( 'S' ) / SLAMCH( 'E' )\n         KNT = 0\n         IF( ABS( BETA ).LT.SAFMIN ) THEN\n*\n*           XNORM, BETA may be inaccurate; scale X and recompute them\n*\n            RSAFMN = ONE / SAFMIN\n   10       CONTINUE\n            KNT = KNT + 1\n            CALL SSCAL( N-1, RSAFMN, X, INCX )\n            BETA = BETA*RSAFMN\n            ALPHA = ALPHA*RSAFMN\n            IF( ABS( BETA ).LT.SAFMIN )\n     $         GO TO 10\n*\n*           New BETA is at most 1, at least SAFMIN\n*\n            XNORM = SNRM2( N-1, X, INCX )\n            BETA = -SIGN( SLAPY2( ALPHA, XNORM ), ALPHA )\n         END IF\n         TAU = ( BETA-ALPHA ) / BETA\n         CALL SSCAL( N-1, ONE / ( ALPHA-BETA ), X, INCX )\n*\n*        If ALPHA is subnormal, it may lose relative accuracy\n*\n         DO 20 J = 1, KNT\n            BETA = BETA*SAFMIN\n 20      CONTINUE\n         ALPHA = BETA\n      END IF\n*\n      RETURN\n*\n*     End of SLARFG\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/slarft.f",
    "content": "*> \\brief \\b SLARFT\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download SLARFT + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/slarft.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/slarft.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/slarft.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE SLARFT( DIRECT, STOREV, N, K, V, LDV, TAU, T, LDT )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          DIRECT, STOREV\n*       INTEGER            K, LDT, LDV, N\n*       ..\n*       .. Array Arguments ..\n*       REAL               T( LDT, * ), TAU( * ), V( LDV, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> SLARFT forms the triangular factor T of a real block reflector H\n*> of order n, which is defined as a product of k elementary reflectors.\n*>\n*> If DIRECT = 'F', H = H(1) H(2) . . . H(k) and T is upper triangular;\n*>\n*> If DIRECT = 'B', H = H(k) . . . H(2) H(1) and T is lower triangular.\n*>\n*> If STOREV = 'C', the vector which defines the elementary reflector\n*> H(i) is stored in the i-th column of the array V, and\n*>\n*>    H  =  I - V * T * V**T\n*>\n*> If STOREV = 'R', the vector which defines the elementary reflector\n*> H(i) is stored in the i-th row of the array V, and\n*>\n*>    H  =  I - V**T * T * V\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] DIRECT\n*> \\verbatim\n*>          DIRECT is CHARACTER*1\n*>          Specifies the order in which the elementary reflectors are\n*>          multiplied to form the block reflector:\n*>          = 'F': H = H(1) H(2) . . . H(k) (Forward)\n*>          = 'B': H = H(k) . . . H(2) H(1) (Backward)\n*> \\endverbatim\n*>\n*> \\param[in] STOREV\n*> \\verbatim\n*>          STOREV is CHARACTER*1\n*>          Specifies how the vectors which define the elementary\n*>          reflectors are stored (see also Further Details):\n*>          = 'C': columnwise\n*>          = 'R': rowwise\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The order of the block reflector H. N >= 0.\n*> \\endverbatim\n*>\n*> \\param[in] K\n*> \\verbatim\n*>          K is INTEGER\n*>          The order of the triangular factor T (= the number of\n*>          elementary reflectors). K >= 1.\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is REAL array, dimension\n*>                               (LDV,K) if STOREV = 'C'\n*>                               (LDV,N) if STOREV = 'R'\n*>          The matrix V. See further details.\n*> \\endverbatim\n*>\n*> \\param[in] LDV\n*> \\verbatim\n*>          LDV is INTEGER\n*>          The leading dimension of the array V.\n*>          If STOREV = 'C', LDV >= max(1,N); if STOREV = 'R', LDV >= K.\n*> \\endverbatim\n*>\n*> \\param[in] TAU\n*> \\verbatim\n*>          TAU is REAL array, dimension (K)\n*>          TAU(i) must contain the scalar factor of the elementary\n*>          reflector H(i).\n*> \\endverbatim\n*>\n*> \\param[out] T\n*> \\verbatim\n*>          T is REAL array, dimension (LDT,K)\n*>          The k by k triangular factor T of the block reflector.\n*>          If DIRECT = 'F', T is upper triangular; if DIRECT = 'B', T is\n*>          lower triangular. The rest of the array is not used.\n*> \\endverbatim\n*>\n*> \\param[in] LDT\n*> \\verbatim\n*>          LDT is INTEGER\n*>          The leading dimension of the array T. LDT >= K.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup realOTHERauxiliary\n*\n*> \\par Further Details:\n*  =====================\n*>\n*> \\verbatim\n*>\n*>  The shape of the matrix V and the storage of the vectors which define\n*>  the H(i) is best illustrated by the following example with n = 5 and\n*>  k = 3. The elements equal to 1 are not stored.\n*>\n*>  DIRECT = 'F' and STOREV = 'C':         DIRECT = 'F' and STOREV = 'R':\n*>\n*>               V = (  1       )                 V = (  1 v1 v1 v1 v1 )\n*>                   ( v1  1    )                     (     1 v2 v2 v2 )\n*>                   ( v1 v2  1 )                     (        1 v3 v3 )\n*>                   ( v1 v2 v3 )\n*>                   ( v1 v2 v3 )\n*>\n*>  DIRECT = 'B' and STOREV = 'C':         DIRECT = 'B' and STOREV = 'R':\n*>\n*>               V = ( v1 v2 v3 )                 V = ( v1 v1  1       )\n*>                   ( v1 v2 v3 )                     ( v2 v2 v2  1    )\n*>                   (  1 v2 v3 )                     ( v3 v3 v3 v3  1 )\n*>                   (     1 v3 )\n*>                   (        1 )\n*> \\endverbatim\n*>\n*  =====================================================================\n      SUBROUTINE SLARFT( DIRECT, STOREV, N, K, V, LDV, TAU, T, LDT )\n*\n*  -- LAPACK auxiliary routine (version 3.4.1) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*     .. Scalar Arguments ..\n      CHARACTER          DIRECT, STOREV\n      INTEGER            K, LDT, LDV, N\n*     ..\n*     .. Array Arguments ..\n      REAL               T( LDT, * ), TAU( * ), V( LDV, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      REAL               ONE, ZERO\n      PARAMETER          ( ONE = 1.0E+0, ZERO = 0.0E+0 )\n*     ..\n*     .. Local Scalars ..\n      INTEGER            I, J, PREVLASTV, LASTV\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           SGEMV, STRMV\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      EXTERNAL           LSAME\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick return if possible\n*\n      IF( N.EQ.0 )\n     $   RETURN\n*\n      IF( LSAME( DIRECT, 'F' ) ) THEN\n         PREVLASTV = N\n         DO I = 1, K\n            PREVLASTV = MAX( I, PREVLASTV )\n            IF( TAU( I ).EQ.ZERO ) THEN\n*\n*              H(i)  =  I\n*\n               DO J = 1, I\n                  T( J, I ) = ZERO\n               END DO\n            ELSE\n*\n*              general case\n*\n               IF( LSAME( STOREV, 'C' ) ) THEN\n*                 Skip any trailing zeros.\n                  DO LASTV = N, I+1, -1\n                     IF( V( LASTV, I ).NE.ZERO ) EXIT\n                  END DO\n                  DO J = 1, I-1\n                     T( J, I ) = -TAU( I ) * V( I , J )\n                  END DO   \n                  J = MIN( LASTV, PREVLASTV )\n*\n*                 T(1:i-1,i) := - tau(i) * V(i:j,1:i-1)**T * V(i:j,i)\n*\n                  CALL SGEMV( 'Transpose', J-I, I-1, -TAU( I ),\n     $                        V( I+1, 1 ), LDV, V( I+1, I ), 1, ONE,\n     $                        T( 1, I ), 1 )\n               ELSE\n*                 Skip any trailing zeros.\n                  DO LASTV = N, I+1, -1\n                     IF( V( I, LASTV ).NE.ZERO ) EXIT\n                  END DO\n                  DO J = 1, I-1\n                     T( J, I ) = -TAU( I ) * V( J , I )\n                  END DO   \n                  J = MIN( LASTV, PREVLASTV )\n*\n*                 T(1:i-1,i) := - tau(i) * V(1:i-1,i:j) * V(i,i:j)**T\n*\n                  CALL SGEMV( 'No transpose', I-1, J-I, -TAU( I ),\n     $                        V( 1, I+1 ), LDV, V( I, I+1 ), LDV, \n     $                        ONE, T( 1, I ), 1 )\n               END IF\n*\n*              T(1:i-1,i) := T(1:i-1,1:i-1) * T(1:i-1,i)\n*\n               CALL STRMV( 'Upper', 'No transpose', 'Non-unit', I-1, T,\n     $                     LDT, T( 1, I ), 1 )\n               T( I, I ) = TAU( I )\n               IF( I.GT.1 ) THEN\n                  PREVLASTV = MAX( PREVLASTV, LASTV )\n               ELSE\n                  PREVLASTV = LASTV\n               END IF\n            END IF\n         END DO\n      ELSE\n         PREVLASTV = 1\n         DO I = K, 1, -1\n            IF( TAU( I ).EQ.ZERO ) THEN\n*\n*              H(i)  =  I\n*\n               DO J = I, K\n                  T( J, I ) = ZERO\n               END DO\n            ELSE\n*\n*              general case\n*\n               IF( I.LT.K ) THEN\n                  IF( LSAME( STOREV, 'C' ) ) THEN\n*                    Skip any leading zeros.\n                     DO LASTV = 1, I-1\n                        IF( V( LASTV, I ).NE.ZERO ) EXIT\n                     END DO\n                     DO J = I+1, K\n                        T( J, I ) = -TAU( I ) * V( N-K+I , J )\n                     END DO   \n                     J = MAX( LASTV, PREVLASTV )\n*\n*                    T(i+1:k,i) = -tau(i) * V(j:n-k+i,i+1:k)**T * V(j:n-k+i,i)\n*\n                     CALL SGEMV( 'Transpose', N-K+I-J, K-I, -TAU( I ),\n     $                           V( J, I+1 ), LDV, V( J, I ), 1, ONE,\n     $                           T( I+1, I ), 1 )\n                  ELSE\n*                    Skip any leading zeros.\n                     DO LASTV = 1, I-1\n                        IF( V( I, LASTV ).NE.ZERO ) EXIT\n                     END DO\n                     DO J = I+1, K\n                        T( J, I ) = -TAU( I ) * V( J, N-K+I )\n                     END DO   \n                     J = MAX( LASTV, PREVLASTV )\n*\n*                    T(i+1:k,i) = -tau(i) * V(i+1:k,j:n-k+i) * V(i,j:n-k+i)**T\n*\n                     CALL SGEMV( 'No transpose', K-I, N-K+I-J,\n     $                    -TAU( I ), V( I+1, J ), LDV, V( I, J ), LDV,\n     $                    ONE, T( I+1, I ), 1 )\n                  END IF\n*\n*                 T(i+1:k,i) := T(i+1:k,i+1:k) * T(i+1:k,i)\n*\n                  CALL STRMV( 'Lower', 'No transpose', 'Non-unit', K-I,\n     $                        T( I+1, I+1 ), LDT, T( I+1, I ), 1 )\n                  IF( I.GT.1 ) THEN\n                     PREVLASTV = MIN( PREVLASTV, LASTV )\n                  ELSE\n                     PREVLASTV = LASTV\n                  END IF\n               END IF\n               T( I, I ) = TAU( I )\n            END IF\n         END DO\n      END IF\n      RETURN\n*\n*     End of SLARFT\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/svd.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"lapack_common.h\"\n#include <Eigen/SVD>\n\n// computes the singular values/vectors a general M-by-N matrix A using divide-and-conquer\nEIGEN_LAPACK_FUNC(gesdd,(char *jobz, int *m, int* n, Scalar* a, int *lda, RealScalar *s, Scalar *u, int *ldu, Scalar *vt, int *ldvt, Scalar* /*work*/, int* lwork,\n                         EIGEN_LAPACK_ARG_IF_COMPLEX(RealScalar */*rwork*/) int * /*iwork*/, int *info))\n{\n  // TODO exploit the work buffer\n  bool query_size = *lwork==-1;\n  int diag_size = (std::min)(*m,*n);\n  \n  *info = 0;\n        if(*jobz!='A' && *jobz!='S' && *jobz!='O' && *jobz!='N')  *info = -1;\n  else  if(*m<0)                                                  *info = -2;\n  else  if(*n<0)                                                  *info = -3;\n  else  if(*lda<std::max(1,*m))                                   *info = -5;\n  else  if(*lda<std::max(1,*m))                                   *info = -8;\n  else  if(*ldu <1 || (*jobz=='A' && *ldu <*m)\n                   || (*jobz=='O' && *m<*n && *ldu<*m))           *info = -8;\n  else  if(*ldvt<1 || (*jobz=='A' && *ldvt<*n)\n                   || (*jobz=='S' && *ldvt<diag_size)\n                   || (*jobz=='O' && *m>=*n && *ldvt<*n))         *info = -10;\n  \n  if(*info!=0)\n  {\n    int e = -*info;\n    return xerbla_(SCALAR_SUFFIX_UP\"GESDD \", &e, 6);\n  }\n  \n  if(query_size)\n  {\n    *lwork = 0;\n    return 0;\n  }\n  \n  if(*n==0 || *m==0)\n    return 0;\n  \n  PlainMatrixType mat(*m,*n);\n  mat = matrix(a,*m,*n,*lda);\n  \n  int option = *jobz=='A' ? ComputeFullU|ComputeFullV\n             : *jobz=='S' ? ComputeThinU|ComputeThinV\n             : *jobz=='O' ? ComputeThinU|ComputeThinV\n             : 0;\n\n  BDCSVD<PlainMatrixType> svd(mat,option);\n  \n  make_vector(s,diag_size) = svd.singularValues().head(diag_size);\n\n  if(*jobz=='A')\n  {\n    matrix(u,*m,*m,*ldu)   = svd.matrixU();\n    matrix(vt,*n,*n,*ldvt) = svd.matrixV().adjoint();\n  }\n  else if(*jobz=='S')\n  {\n    matrix(u,*m,diag_size,*ldu)   = svd.matrixU();\n    matrix(vt,diag_size,*n,*ldvt) = svd.matrixV().adjoint();\n  }\n  else if(*jobz=='O' && *m>=*n)\n  {\n    matrix(a,*m,*n,*lda)   = svd.matrixU();\n    matrix(vt,*n,*n,*ldvt) = svd.matrixV().adjoint();\n  }\n  else if(*jobz=='O')\n  {\n    matrix(u,*m,*m,*ldu)        = svd.matrixU();\n    matrix(a,diag_size,*n,*lda) = svd.matrixV().adjoint();\n  }\n    \n  return 0;\n}\n\n// computes the singular values/vectors a general M-by-N matrix A using two sided jacobi algorithm\nEIGEN_LAPACK_FUNC(gesvd,(char *jobu, char *jobv, int *m, int* n, Scalar* a, int *lda, RealScalar *s, Scalar *u, int *ldu, Scalar *vt, int *ldvt, Scalar* /*work*/, int* lwork,\n                         EIGEN_LAPACK_ARG_IF_COMPLEX(RealScalar */*rwork*/) int *info))\n{\n  // TODO exploit the work buffer\n  bool query_size = *lwork==-1;\n  int diag_size = (std::min)(*m,*n);\n  \n  *info = 0;\n        if( *jobu!='A' && *jobu!='S' && *jobu!='O' && *jobu!='N') *info = -1;\n  else  if((*jobv!='A' && *jobv!='S' && *jobv!='O' && *jobv!='N')\n           || (*jobu=='O' && *jobv=='O'))                         *info = -2;\n  else  if(*m<0)                                                  *info = -3;\n  else  if(*n<0)                                                  *info = -4;\n  else  if(*lda<std::max(1,*m))                                   *info = -6;\n  else  if(*ldu <1 || ((*jobu=='A' || *jobu=='S') && *ldu<*m))    *info = -9;\n  else  if(*ldvt<1 || (*jobv=='A' && *ldvt<*n)\n                   || (*jobv=='S' && *ldvt<diag_size))            *info = -11;\n  \n  if(*info!=0)\n  {\n    int e = -*info;\n    return xerbla_(SCALAR_SUFFIX_UP\"GESVD \", &e, 6);\n  }\n  \n  if(query_size)\n  {\n    *lwork = 0;\n    return 0;\n  }\n  \n  if(*n==0 || *m==0)\n    return 0;\n  \n  PlainMatrixType mat(*m,*n);\n  mat = matrix(a,*m,*n,*lda);\n  \n  int option = (*jobu=='A' ? ComputeFullU : *jobu=='S' || *jobu=='O' ? ComputeThinU : 0)\n             | (*jobv=='A' ? ComputeFullV : *jobv=='S' || *jobv=='O' ? ComputeThinV : 0);\n  \n  JacobiSVD<PlainMatrixType> svd(mat,option);\n  \n  make_vector(s,diag_size) = svd.singularValues().head(diag_size);\n  {\n        if(*jobu=='A') matrix(u,*m,*m,*ldu)           = svd.matrixU();\n  else  if(*jobu=='S') matrix(u,*m,diag_size,*ldu)    = svd.matrixU();\n  else  if(*jobu=='O') matrix(a,*m,diag_size,*lda)    = svd.matrixU();\n  }\n  {\n        if(*jobv=='A') matrix(vt,*n,*n,*ldvt)         = svd.matrixV().adjoint();\n  else  if(*jobv=='S') matrix(vt,diag_size,*n,*ldvt)  = svd.matrixV().adjoint();\n  else  if(*jobv=='O') matrix(a,diag_size,*n,*lda)    = svd.matrixV().adjoint();\n  }\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/zlacgv.f",
    "content": "*> \\brief \\b ZLACGV\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ZLACGV + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/zlacgv.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/zlacgv.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/zlacgv.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE ZLACGV( N, X, INCX )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            INCX, N\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX*16         X( * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ZLACGV conjugates a complex vector of length N.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The length of the vector X.  N >= 0.\n*> \\endverbatim\n*>\n*> \\param[in,out] X\n*> \\verbatim\n*>          X is COMPLEX*16 array, dimension\n*>                         (1+(N-1)*abs(INCX))\n*>          On entry, the vector of length N to be conjugated.\n*>          On exit, X is overwritten with conjg(X).\n*> \\endverbatim\n*>\n*> \\param[in] INCX\n*> \\verbatim\n*>          INCX is INTEGER\n*>          The spacing between successive elements of X.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complex16OTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE ZLACGV( N, X, INCX )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      INTEGER            INCX, N\n*     ..\n*     .. Array Arguments ..\n      COMPLEX*16         X( * )\n*     ..\n*\n* =====================================================================\n*\n*     .. Local Scalars ..\n      INTEGER            I, IOFF\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          DCONJG\n*     ..\n*     .. Executable Statements ..\n*\n      IF( INCX.EQ.1 ) THEN\n         DO 10 I = 1, N\n            X( I ) = DCONJG( X( I ) )\n   10    CONTINUE\n      ELSE\n         IOFF = 1\n         IF( INCX.LT.0 )\n     $      IOFF = 1 - ( N-1 )*INCX\n         DO 20 I = 1, N\n            X( IOFF ) = DCONJG( X( IOFF ) )\n            IOFF = IOFF + INCX\n   20    CONTINUE\n      END IF\n      RETURN\n*\n*     End of ZLACGV\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/zladiv.f",
    "content": "*> \\brief \\b ZLADIV\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ZLADIV + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/zladiv.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/zladiv.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/zladiv.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       COMPLEX*16     FUNCTION ZLADIV( X, Y )\n* \n*       .. Scalar Arguments ..\n*       COMPLEX*16         X, Y\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ZLADIV := X / Y, where X and Y are complex.  The computation of X / Y\n*> will not overflow on an intermediary step unless the results\n*> overflows.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] X\n*> \\verbatim\n*>          X is COMPLEX*16\n*> \\endverbatim\n*>\n*> \\param[in] Y\n*> \\verbatim\n*>          Y is COMPLEX*16\n*>          The complex scalars X and Y.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complex16OTHERauxiliary\n*\n*  =====================================================================\n      COMPLEX*16     FUNCTION ZLADIV( X, Y )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      COMPLEX*16         X, Y\n*     ..\n*\n*  =====================================================================\n*\n*     .. Local Scalars ..\n      DOUBLE PRECISION   ZI, ZR\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           DLADIV\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          DBLE, DCMPLX, DIMAG\n*     ..\n*     .. Executable Statements ..\n*\n      CALL DLADIV( DBLE( X ), DIMAG( X ), DBLE( Y ), DIMAG( Y ), ZR,\n     $             ZI )\n      ZLADIV = DCMPLX( ZR, ZI )\n*\n      RETURN\n*\n*     End of ZLADIV\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/zlarf.f",
    "content": "*> \\brief \\b ZLARF\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ZLARF + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/zlarf.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/zlarf.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/zlarf.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE ZLARF( SIDE, M, N, V, INCV, TAU, C, LDC, WORK )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          SIDE\n*       INTEGER            INCV, LDC, M, N\n*       COMPLEX*16         TAU\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX*16         C( LDC, * ), V( * ), WORK( * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ZLARF applies a complex elementary reflector H to a complex M-by-N\n*> matrix C, from either the left or the right. H is represented in the\n*> form\n*>\n*>       H = I - tau * v * v**H\n*>\n*> where tau is a complex scalar and v is a complex vector.\n*>\n*> If tau = 0, then H is taken to be the unit matrix.\n*>\n*> To apply H**H, supply conjg(tau) instead\n*> tau.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] SIDE\n*> \\verbatim\n*>          SIDE is CHARACTER*1\n*>          = 'L': form  H * C\n*>          = 'R': form  C * H\n*> \\endverbatim\n*>\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is COMPLEX*16 array, dimension\n*>                     (1 + (M-1)*abs(INCV)) if SIDE = 'L'\n*>                  or (1 + (N-1)*abs(INCV)) if SIDE = 'R'\n*>          The vector v in the representation of H. V is not used if\n*>          TAU = 0.\n*> \\endverbatim\n*>\n*> \\param[in] INCV\n*> \\verbatim\n*>          INCV is INTEGER\n*>          The increment between elements of v. INCV <> 0.\n*> \\endverbatim\n*>\n*> \\param[in] TAU\n*> \\verbatim\n*>          TAU is COMPLEX*16\n*>          The value tau in the representation of H.\n*> \\endverbatim\n*>\n*> \\param[in,out] C\n*> \\verbatim\n*>          C is COMPLEX*16 array, dimension (LDC,N)\n*>          On entry, the M-by-N matrix C.\n*>          On exit, C is overwritten by the matrix H * C if SIDE = 'L',\n*>          or C * H if SIDE = 'R'.\n*> \\endverbatim\n*>\n*> \\param[in] LDC\n*> \\verbatim\n*>          LDC is INTEGER\n*>          The leading dimension of the array C. LDC >= max(1,M).\n*> \\endverbatim\n*>\n*> \\param[out] WORK\n*> \\verbatim\n*>          WORK is COMPLEX*16 array, dimension\n*>                         (N) if SIDE = 'L'\n*>                      or (M) if SIDE = 'R'\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complex16OTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE ZLARF( SIDE, M, N, V, INCV, TAU, C, LDC, WORK )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      CHARACTER          SIDE\n      INTEGER            INCV, LDC, M, N\n      COMPLEX*16         TAU\n*     ..\n*     .. Array Arguments ..\n      COMPLEX*16         C( LDC, * ), V( * ), WORK( * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      COMPLEX*16         ONE, ZERO\n      PARAMETER          ( ONE = ( 1.0D+0, 0.0D+0 ),\n     $                   ZERO = ( 0.0D+0, 0.0D+0 ) )\n*     ..\n*     .. Local Scalars ..\n      LOGICAL            APPLYLEFT\n      INTEGER            I, LASTV, LASTC\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           ZGEMV, ZGERC\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      INTEGER            ILAZLR, ILAZLC\n      EXTERNAL           LSAME, ILAZLR, ILAZLC\n*     ..\n*     .. Executable Statements ..\n*\n      APPLYLEFT = LSAME( SIDE, 'L' )\n      LASTV = 0\n      LASTC = 0\n      IF( TAU.NE.ZERO ) THEN\n*     Set up variables for scanning V.  LASTV begins pointing to the end\n*     of V.\n         IF( APPLYLEFT ) THEN\n            LASTV = M\n         ELSE\n            LASTV = N\n         END IF\n         IF( INCV.GT.0 ) THEN\n            I = 1 + (LASTV-1) * INCV\n         ELSE\n            I = 1\n         END IF\n*     Look for the last non-zero row in V.\n         DO WHILE( LASTV.GT.0 .AND. V( I ).EQ.ZERO )\n            LASTV = LASTV - 1\n            I = I - INCV\n         END DO\n         IF( APPLYLEFT ) THEN\n*     Scan for the last non-zero column in C(1:lastv,:).\n            LASTC = ILAZLC(LASTV, N, C, LDC)\n         ELSE\n*     Scan for the last non-zero row in C(:,1:lastv).\n            LASTC = ILAZLR(M, LASTV, C, LDC)\n         END IF\n      END IF\n*     Note that lastc.eq.0 renders the BLAS operations null; no special\n*     case is needed at this level.\n      IF( APPLYLEFT ) THEN\n*\n*        Form  H * C\n*\n         IF( LASTV.GT.0 ) THEN\n*\n*           w(1:lastc,1) := C(1:lastv,1:lastc)**H * v(1:lastv,1)\n*\n            CALL ZGEMV( 'Conjugate transpose', LASTV, LASTC, ONE,\n     $           C, LDC, V, INCV, ZERO, WORK, 1 )\n*\n*           C(1:lastv,1:lastc) := C(...) - v(1:lastv,1) * w(1:lastc,1)**H\n*\n            CALL ZGERC( LASTV, LASTC, -TAU, V, INCV, WORK, 1, C, LDC )\n         END IF\n      ELSE\n*\n*        Form  C * H\n*\n         IF( LASTV.GT.0 ) THEN\n*\n*           w(1:lastc,1) := C(1:lastc,1:lastv) * v(1:lastv,1)\n*\n            CALL ZGEMV( 'No transpose', LASTC, LASTV, ONE, C, LDC,\n     $           V, INCV, ZERO, WORK, 1 )\n*\n*           C(1:lastc,1:lastv) := C(...) - w(1:lastc,1) * v(1:lastv,1)**H\n*\n            CALL ZGERC( LASTC, LASTV, -TAU, WORK, 1, V, INCV, C, LDC )\n         END IF\n      END IF\n      RETURN\n*\n*     End of ZLARF\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/zlarfb.f",
    "content": "*> \\brief \\b ZLARFB\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ZLARFB + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/zlarfb.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/zlarfb.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/zlarfb.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE ZLARFB( SIDE, TRANS, DIRECT, STOREV, M, N, K, V, LDV,\n*                          T, LDT, C, LDC, WORK, LDWORK )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          DIRECT, SIDE, STOREV, TRANS\n*       INTEGER            K, LDC, LDT, LDV, LDWORK, M, N\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX*16         C( LDC, * ), T( LDT, * ), V( LDV, * ),\n*      $                   WORK( LDWORK, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ZLARFB applies a complex block reflector H or its transpose H**H to a\n*> complex M-by-N matrix C, from either the left or the right.\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] SIDE\n*> \\verbatim\n*>          SIDE is CHARACTER*1\n*>          = 'L': apply H or H**H from the Left\n*>          = 'R': apply H or H**H from the Right\n*> \\endverbatim\n*>\n*> \\param[in] TRANS\n*> \\verbatim\n*>          TRANS is CHARACTER*1\n*>          = 'N': apply H (No transpose)\n*>          = 'C': apply H**H (Conjugate transpose)\n*> \\endverbatim\n*>\n*> \\param[in] DIRECT\n*> \\verbatim\n*>          DIRECT is CHARACTER*1\n*>          Indicates how H is formed from a product of elementary\n*>          reflectors\n*>          = 'F': H = H(1) H(2) . . . H(k) (Forward)\n*>          = 'B': H = H(k) . . . H(2) H(1) (Backward)\n*> \\endverbatim\n*>\n*> \\param[in] STOREV\n*> \\verbatim\n*>          STOREV is CHARACTER*1\n*>          Indicates how the vectors which define the elementary\n*>          reflectors are stored:\n*>          = 'C': Columnwise\n*>          = 'R': Rowwise\n*> \\endverbatim\n*>\n*> \\param[in] M\n*> \\verbatim\n*>          M is INTEGER\n*>          The number of rows of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The number of columns of the matrix C.\n*> \\endverbatim\n*>\n*> \\param[in] K\n*> \\verbatim\n*>          K is INTEGER\n*>          The order of the matrix T (= the number of elementary\n*>          reflectors whose product defines the block reflector).\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is COMPLEX*16 array, dimension\n*>                                (LDV,K) if STOREV = 'C'\n*>                                (LDV,M) if STOREV = 'R' and SIDE = 'L'\n*>                                (LDV,N) if STOREV = 'R' and SIDE = 'R'\n*>          See Further Details.\n*> \\endverbatim\n*>\n*> \\param[in] LDV\n*> \\verbatim\n*>          LDV is INTEGER\n*>          The leading dimension of the array V.\n*>          If STOREV = 'C' and SIDE = 'L', LDV >= max(1,M);\n*>          if STOREV = 'C' and SIDE = 'R', LDV >= max(1,N);\n*>          if STOREV = 'R', LDV >= K.\n*> \\endverbatim\n*>\n*> \\param[in] T\n*> \\verbatim\n*>          T is COMPLEX*16 array, dimension (LDT,K)\n*>          The triangular K-by-K matrix T in the representation of the\n*>          block reflector.\n*> \\endverbatim\n*>\n*> \\param[in] LDT\n*> \\verbatim\n*>          LDT is INTEGER\n*>          The leading dimension of the array T. LDT >= K.\n*> \\endverbatim\n*>\n*> \\param[in,out] C\n*> \\verbatim\n*>          C is COMPLEX*16 array, dimension (LDC,N)\n*>          On entry, the M-by-N matrix C.\n*>          On exit, C is overwritten by H*C or H**H*C or C*H or C*H**H.\n*> \\endverbatim\n*>\n*> \\param[in] LDC\n*> \\verbatim\n*>          LDC is INTEGER\n*>          The leading dimension of the array C. LDC >= max(1,M).\n*> \\endverbatim\n*>\n*> \\param[out] WORK\n*> \\verbatim\n*>          WORK is COMPLEX*16 array, dimension (LDWORK,K)\n*> \\endverbatim\n*>\n*> \\param[in] LDWORK\n*> \\verbatim\n*>          LDWORK is INTEGER\n*>          The leading dimension of the array WORK.\n*>          If SIDE = 'L', LDWORK >= max(1,N);\n*>          if SIDE = 'R', LDWORK >= max(1,M).\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complex16OTHERauxiliary\n*\n*> \\par Further Details:\n*  =====================\n*>\n*> \\verbatim\n*>\n*>  The shape of the matrix V and the storage of the vectors which define\n*>  the H(i) is best illustrated by the following example with n = 5 and\n*>  k = 3. The elements equal to 1 are not stored; the corresponding\n*>  array elements are modified but restored on exit. The rest of the\n*>  array is not used.\n*>\n*>  DIRECT = 'F' and STOREV = 'C':         DIRECT = 'F' and STOREV = 'R':\n*>\n*>               V = (  1       )                 V = (  1 v1 v1 v1 v1 )\n*>                   ( v1  1    )                     (     1 v2 v2 v2 )\n*>                   ( v1 v2  1 )                     (        1 v3 v3 )\n*>                   ( v1 v2 v3 )\n*>                   ( v1 v2 v3 )\n*>\n*>  DIRECT = 'B' and STOREV = 'C':         DIRECT = 'B' and STOREV = 'R':\n*>\n*>               V = ( v1 v2 v3 )                 V = ( v1 v1  1       )\n*>                   ( v1 v2 v3 )                     ( v2 v2 v2  1    )\n*>                   (  1 v2 v3 )                     ( v3 v3 v3 v3  1 )\n*>                   (     1 v3 )\n*>                   (        1 )\n*> \\endverbatim\n*>\n*  =====================================================================\n      SUBROUTINE ZLARFB( SIDE, TRANS, DIRECT, STOREV, M, N, K, V, LDV,\n     $                   T, LDT, C, LDC, WORK, LDWORK )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      CHARACTER          DIRECT, SIDE, STOREV, TRANS\n      INTEGER            K, LDC, LDT, LDV, LDWORK, M, N\n*     ..\n*     .. Array Arguments ..\n      COMPLEX*16         C( LDC, * ), T( LDT, * ), V( LDV, * ),\n     $                   WORK( LDWORK, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      COMPLEX*16         ONE\n      PARAMETER          ( ONE = ( 1.0D+0, 0.0D+0 ) )\n*     ..\n*     .. Local Scalars ..\n      CHARACTER          TRANST\n      INTEGER            I, J, LASTV, LASTC\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      INTEGER            ILAZLR, ILAZLC\n      EXTERNAL           LSAME, ILAZLR, ILAZLC\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           ZCOPY, ZGEMM, ZLACGV, ZTRMM\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          DCONJG\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick return if possible\n*\n      IF( M.LE.0 .OR. N.LE.0 )\n     $   RETURN\n*\n      IF( LSAME( TRANS, 'N' ) ) THEN\n         TRANST = 'C'\n      ELSE\n         TRANST = 'N'\n      END IF\n*\n      IF( LSAME( STOREV, 'C' ) ) THEN\n*\n         IF( LSAME( DIRECT, 'F' ) ) THEN\n*\n*           Let  V =  ( V1 )    (first K rows)\n*                     ( V2 )\n*           where  V1  is unit lower triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**H * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILAZLR( M, K, V, LDV ) )\n               LASTC = ILAZLC( LASTV, N, C, LDC )\n*\n*              W := C**H * V  =  (C1**H * V1 + C2**H * V2)  (stored in WORK)\n*\n*              W := C1**H\n*\n               DO 10 J = 1, K\n                  CALL ZCOPY( LASTC, C( J, 1 ), LDC, WORK( 1, J ), 1 )\n                  CALL ZLACGV( LASTC, WORK( 1, J ), 1 )\n   10          CONTINUE\n*\n*              W := W * V1\n*\n               CALL ZTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2**H *V2\n*\n                  CALL ZGEMM( 'Conjugate transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K, ONE, C( K+1, 1 ), LDC,\n     $                 V( K+1, 1 ), LDV, ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**H  or  W * T\n*\n               CALL ZTRMM( 'Right', 'Upper', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V * W**H\n*\n               IF( M.GT.K ) THEN\n*\n*                 C2 := C2 - V2 * W**H\n*\n                  CALL ZGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTV-K, LASTC, K,\n     $                 -ONE, V( K+1, 1 ), LDV, WORK, LDWORK,\n     $                 ONE, C( K+1, 1 ), LDC )\n               END IF\n*\n*              W := W * V1**H\n*\n               CALL ZTRMM( 'Right', 'Lower', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W**H\n*\n               DO 30 J = 1, K\n                  DO 20 I = 1, LASTC\n                     C( J, I ) = C( J, I ) - DCONJG( WORK( I, J ) )\n   20             CONTINUE\n   30          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**H  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILAZLR( N, K, V, LDV ) )\n               LASTC = ILAZLR( M, LASTV, C, LDC )\n*\n*              W := C * V  =  (C1*V1 + C2*V2)  (stored in WORK)\n*\n*              W := C1\n*\n               DO 40 J = 1, K\n                  CALL ZCOPY( LASTC, C( 1, J ), 1, WORK( 1, J ), 1 )\n   40          CONTINUE\n*\n*              W := W * V1\n*\n               CALL ZTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2 * V2\n*\n                  CALL ZGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C( 1, K+1 ), LDC, V( K+1, 1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**H\n*\n               CALL ZTRMM( 'Right', 'Upper', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V**H\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - W * V2**H\n*\n                  CALL ZGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTC, LASTV-K, K,\n     $                 -ONE, WORK, LDWORK, V( K+1, 1 ), LDV,\n     $                 ONE, C( 1, K+1 ), LDC )\n               END IF\n*\n*              W := W * V1**H\n*\n               CALL ZTRMM( 'Right', 'Lower', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 60 J = 1, K\n                  DO 50 I = 1, LASTC\n                     C( I, J ) = C( I, J ) - WORK( I, J )\n   50             CONTINUE\n   60          CONTINUE\n            END IF\n*\n         ELSE\n*\n*           Let  V =  ( V1 )\n*                     ( V2 )    (last K rows)\n*           where  V2  is unit upper triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**H * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILAZLR( M, K, V, LDV ) )\n               LASTC = ILAZLC( LASTV, N, C, LDC )\n*\n*              W := C**H * V  =  (C1**H * V1 + C2**H * V2)  (stored in WORK)\n*\n*              W := C2**H\n*\n               DO 70 J = 1, K\n                  CALL ZCOPY( LASTC, C( LASTV-K+J, 1 ), LDC,\n     $                 WORK( 1, J ), 1 )\n                  CALL ZLACGV( LASTC, WORK( 1, J ), 1 )\n   70          CONTINUE\n*\n*              W := W * V2\n*\n               CALL ZTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1**H*V1\n*\n                  CALL ZGEMM( 'Conjugate transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C, LDC, V, LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**H  or  W * T\n*\n               CALL ZTRMM( 'Right', 'Lower', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V * W**H\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - V1 * W**H\n*\n                  CALL ZGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTV-K, LASTC, K,\n     $                 -ONE, V, LDV, WORK, LDWORK,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2**H\n*\n               CALL ZTRMM( 'Right', 'Upper', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W**H\n*\n               DO 90 J = 1, K\n                  DO 80 I = 1, LASTC\n                     C( LASTV-K+J, I ) = C( LASTV-K+J, I ) -\n     $                               DCONJG( WORK( I, J ) )\n   80             CONTINUE\n   90          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**H  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILAZLR( N, K, V, LDV ) )\n               LASTC = ILAZLR( M, LASTV, C, LDC )\n*\n*              W := C * V  =  (C1*V1 + C2*V2)  (stored in WORK)\n*\n*              W := C2\n*\n               DO 100 J = 1, K\n                  CALL ZCOPY( LASTC, C( 1, LASTV-K+J ), 1,\n     $                 WORK( 1, J ), 1 )\n  100          CONTINUE\n*\n*              W := W * V2\n*\n               CALL ZTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1 * V1\n*\n                  CALL ZGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, K, LASTV-K,\n     $                 ONE, C, LDC, V, LDV, ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**H\n*\n               CALL ZTRMM( 'Right', 'Lower', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V**H\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - W * V1**H\n*\n                  CALL ZGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTC, LASTV-K, K, -ONE, WORK, LDWORK, V, LDV,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2**H\n*\n               CALL ZTRMM( 'Right', 'Upper', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V( LASTV-K+1, 1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W\n*\n               DO 120 J = 1, K\n                  DO 110 I = 1, LASTC\n                     C( I, LASTV-K+J ) = C( I, LASTV-K+J )\n     $                    - WORK( I, J )\n  110             CONTINUE\n  120          CONTINUE\n            END IF\n         END IF\n*\n      ELSE IF( LSAME( STOREV, 'R' ) ) THEN\n*\n         IF( LSAME( DIRECT, 'F' ) ) THEN\n*\n*           Let  V =  ( V1  V2 )    (V1: first K columns)\n*           where  V1  is unit upper triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**H * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILAZLC( K, M, V, LDV ) )\n               LASTC = ILAZLC( LASTV, N, C, LDC )\n*\n*              W := C**H * V**H  =  (C1**H * V1**H + C2**H * V2**H) (stored in WORK)\n*\n*              W := C1**H\n*\n               DO 130 J = 1, K\n                  CALL ZCOPY( LASTC, C( J, 1 ), LDC, WORK( 1, J ), 1 )\n                  CALL ZLACGV( LASTC, WORK( 1, J ), 1 )\n  130          CONTINUE\n*\n*              W := W * V1**H\n*\n               CALL ZTRMM( 'Right', 'Upper', 'Conjugate transpose',\n     $                     'Unit', LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2**H*V2**H\n*\n                  CALL ZGEMM( 'Conjugate transpose',\n     $                 'Conjugate transpose', LASTC, K, LASTV-K,\n     $                 ONE, C( K+1, 1 ), LDC, V( 1, K+1 ), LDV,\n     $                 ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**H  or  W * T\n*\n               CALL ZTRMM( 'Right', 'Upper', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V**H * W**H\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - V2**H * W**H\n*\n                  CALL ZGEMM( 'Conjugate transpose',\n     $                 'Conjugate transpose', LASTV-K, LASTC, K,\n     $                 -ONE, V( 1, K+1 ), LDV, WORK, LDWORK,\n     $                 ONE, C( K+1, 1 ), LDC )\n               END IF\n*\n*              W := W * V1\n*\n               CALL ZTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W**H\n*\n               DO 150 J = 1, K\n                  DO 140 I = 1, LASTC\n                     C( J, I ) = C( J, I ) - DCONJG( WORK( I, J ) )\n  140             CONTINUE\n  150          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**H  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILAZLC( K, N, V, LDV ) )\n               LASTC = ILAZLR( M, LASTV, C, LDC )\n*\n*              W := C * V**H  =  (C1*V1**H + C2*V2**H)  (stored in WORK)\n*\n*              W := C1\n*\n               DO 160 J = 1, K\n                  CALL ZCOPY( LASTC, C( 1, J ), 1, WORK( 1, J ), 1 )\n  160          CONTINUE\n*\n*              W := W * V1**H\n*\n               CALL ZTRMM( 'Right', 'Upper', 'Conjugate transpose',\n     $                     'Unit', LASTC, K, ONE, V, LDV, WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C2 * V2**H\n*\n                  CALL ZGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTC, K, LASTV-K, ONE, C( 1, K+1 ), LDC,\n     $                 V( 1, K+1 ), LDV, ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**H\n*\n               CALL ZTRMM( 'Right', 'Upper', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C2 := C2 - W * V2\n*\n                  CALL ZGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, LASTV-K, K,\n     $                 -ONE, WORK, LDWORK, V( 1, K+1 ), LDV,\n     $                 ONE, C( 1, K+1 ), LDC )\n               END IF\n*\n*              W := W * V1\n*\n               CALL ZTRMM( 'Right', 'Upper', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V, LDV, WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 180 J = 1, K\n                  DO 170 I = 1, LASTC\n                     C( I, J ) = C( I, J ) - WORK( I, J )\n  170             CONTINUE\n  180          CONTINUE\n*\n            END IF\n*\n         ELSE\n*\n*           Let  V =  ( V1  V2 )    (V2: last K columns)\n*           where  V2  is unit lower triangular.\n*\n            IF( LSAME( SIDE, 'L' ) ) THEN\n*\n*              Form  H * C  or  H**H * C  where  C = ( C1 )\n*                                                    ( C2 )\n*\n               LASTV = MAX( K, ILAZLC( K, M, V, LDV ) )\n               LASTC = ILAZLC( LASTV, N, C, LDC )\n*\n*              W := C**H * V**H  =  (C1**H * V1**H + C2**H * V2**H) (stored in WORK)\n*\n*              W := C2**H\n*\n               DO 190 J = 1, K\n                  CALL ZCOPY( LASTC, C( LASTV-K+J, 1 ), LDC,\n     $                 WORK( 1, J ), 1 )\n                  CALL ZLACGV( LASTC, WORK( 1, J ), 1 )\n  190          CONTINUE\n*\n*              W := W * V2**H\n*\n               CALL ZTRMM( 'Right', 'Lower', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1**H * V1**H\n*\n                  CALL ZGEMM( 'Conjugate transpose',\n     $                 'Conjugate transpose', LASTC, K, LASTV-K,\n     $                 ONE, C, LDC, V, LDV, ONE, WORK, LDWORK )\n               END IF\n*\n*              W := W * T**H  or  W * T\n*\n               CALL ZTRMM( 'Right', 'Lower', TRANST, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - V**H * W**H\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - V1**H * W**H\n*\n                  CALL ZGEMM( 'Conjugate transpose',\n     $                 'Conjugate transpose', LASTV-K, LASTC, K,\n     $                 -ONE, V, LDV, WORK, LDWORK, ONE, C, LDC )\n               END IF\n*\n*              W := W * V2\n*\n               CALL ZTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C2 := C2 - W**H\n*\n               DO 210 J = 1, K\n                  DO 200 I = 1, LASTC\n                     C( LASTV-K+J, I ) = C( LASTV-K+J, I ) -\n     $                               DCONJG( WORK( I, J ) )\n  200             CONTINUE\n  210          CONTINUE\n*\n            ELSE IF( LSAME( SIDE, 'R' ) ) THEN\n*\n*              Form  C * H  or  C * H**H  where  C = ( C1  C2 )\n*\n               LASTV = MAX( K, ILAZLC( K, N, V, LDV ) )\n               LASTC = ILAZLR( M, LASTV, C, LDC )\n*\n*              W := C * V**H  =  (C1*V1**H + C2*V2**H)  (stored in WORK)\n*\n*              W := C2\n*\n               DO 220 J = 1, K\n                  CALL ZCOPY( LASTC, C( 1, LASTV-K+J ), 1,\n     $                 WORK( 1, J ), 1 )\n  220          CONTINUE\n*\n*              W := W * V2**H\n*\n               CALL ZTRMM( 'Right', 'Lower', 'Conjugate transpose',\n     $              'Unit', LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n               IF( LASTV.GT.K ) THEN\n*\n*                 W := W + C1 * V1**H\n*\n                  CALL ZGEMM( 'No transpose', 'Conjugate transpose',\n     $                 LASTC, K, LASTV-K, ONE, C, LDC, V, LDV, ONE,\n     $                 WORK, LDWORK )\n               END IF\n*\n*              W := W * T  or  W * T**H\n*\n               CALL ZTRMM( 'Right', 'Lower', TRANS, 'Non-unit',\n     $              LASTC, K, ONE, T, LDT, WORK, LDWORK )\n*\n*              C := C - W * V\n*\n               IF( LASTV.GT.K ) THEN\n*\n*                 C1 := C1 - W * V1\n*\n                  CALL ZGEMM( 'No transpose', 'No transpose',\n     $                 LASTC, LASTV-K, K, -ONE, WORK, LDWORK, V, LDV,\n     $                 ONE, C, LDC )\n               END IF\n*\n*              W := W * V2\n*\n               CALL ZTRMM( 'Right', 'Lower', 'No transpose', 'Unit',\n     $              LASTC, K, ONE, V( 1, LASTV-K+1 ), LDV,\n     $              WORK, LDWORK )\n*\n*              C1 := C1 - W\n*\n               DO 240 J = 1, K\n                  DO 230 I = 1, LASTC\n                     C( I, LASTV-K+J ) = C( I, LASTV-K+J )\n     $                    - WORK( I, J )\n  230             CONTINUE\n  240          CONTINUE\n*\n            END IF\n*\n         END IF\n      END IF\n*\n      RETURN\n*\n*     End of ZLARFB\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/zlarfg.f",
    "content": "*> \\brief \\b ZLARFG\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ZLARFG + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/zlarfg.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/zlarfg.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/zlarfg.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE ZLARFG( N, ALPHA, X, INCX, TAU )\n* \n*       .. Scalar Arguments ..\n*       INTEGER            INCX, N\n*       COMPLEX*16         ALPHA, TAU\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX*16         X( * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ZLARFG generates a complex elementary reflector H of order n, such\n*> that\n*>\n*>       H**H * ( alpha ) = ( beta ),   H**H * H = I.\n*>              (   x   )   (   0  )\n*>\n*> where alpha and beta are scalars, with beta real, and x is an\n*> (n-1)-element complex vector. H is represented in the form\n*>\n*>       H = I - tau * ( 1 ) * ( 1 v**H ) ,\n*>                     ( v )\n*>\n*> where tau is a complex scalar and v is a complex (n-1)-element\n*> vector. Note that H is not hermitian.\n*>\n*> If the elements of x are all zero and alpha is real, then tau = 0\n*> and H is taken to be the unit matrix.\n*>\n*> Otherwise  1 <= real(tau) <= 2  and  abs(tau-1) <= 1 .\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The order of the elementary reflector.\n*> \\endverbatim\n*>\n*> \\param[in,out] ALPHA\n*> \\verbatim\n*>          ALPHA is COMPLEX*16\n*>          On entry, the value alpha.\n*>          On exit, it is overwritten with the value beta.\n*> \\endverbatim\n*>\n*> \\param[in,out] X\n*> \\verbatim\n*>          X is COMPLEX*16 array, dimension\n*>                         (1+(N-2)*abs(INCX))\n*>          On entry, the vector x.\n*>          On exit, it is overwritten with the vector v.\n*> \\endverbatim\n*>\n*> \\param[in] INCX\n*> \\verbatim\n*>          INCX is INTEGER\n*>          The increment between elements of X. INCX > 0.\n*> \\endverbatim\n*>\n*> \\param[out] TAU\n*> \\verbatim\n*>          TAU is COMPLEX*16\n*>          The value tau.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date November 2011\n*\n*> \\ingroup complex16OTHERauxiliary\n*\n*  =====================================================================\n      SUBROUTINE ZLARFG( N, ALPHA, X, INCX, TAU )\n*\n*  -- LAPACK auxiliary routine (version 3.4.0) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     November 2011\n*\n*     .. Scalar Arguments ..\n      INTEGER            INCX, N\n      COMPLEX*16         ALPHA, TAU\n*     ..\n*     .. Array Arguments ..\n      COMPLEX*16         X( * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      DOUBLE PRECISION   ONE, ZERO\n      PARAMETER          ( ONE = 1.0D+0, ZERO = 0.0D+0 )\n*     ..\n*     .. Local Scalars ..\n      INTEGER            J, KNT\n      DOUBLE PRECISION   ALPHI, ALPHR, BETA, RSAFMN, SAFMIN, XNORM\n*     ..\n*     .. External Functions ..\n      DOUBLE PRECISION   DLAMCH, DLAPY3, DZNRM2\n      COMPLEX*16         ZLADIV\n      EXTERNAL           DLAMCH, DLAPY3, DZNRM2, ZLADIV\n*     ..\n*     .. Intrinsic Functions ..\n      INTRINSIC          ABS, DBLE, DCMPLX, DIMAG, SIGN\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           ZDSCAL, ZSCAL\n*     ..\n*     .. Executable Statements ..\n*\n      IF( N.LE.0 ) THEN\n         TAU = ZERO\n         RETURN\n      END IF\n*\n      XNORM = DZNRM2( N-1, X, INCX )\n      ALPHR = DBLE( ALPHA )\n      ALPHI = DIMAG( ALPHA )\n*\n      IF( XNORM.EQ.ZERO .AND. ALPHI.EQ.ZERO ) THEN\n*\n*        H  =  I\n*\n         TAU = ZERO\n      ELSE\n*\n*        general case\n*\n         BETA = -SIGN( DLAPY3( ALPHR, ALPHI, XNORM ), ALPHR )\n         SAFMIN = DLAMCH( 'S' ) / DLAMCH( 'E' )\n         RSAFMN = ONE / SAFMIN\n*\n         KNT = 0\n         IF( ABS( BETA ).LT.SAFMIN ) THEN\n*\n*           XNORM, BETA may be inaccurate; scale X and recompute them\n*\n   10       CONTINUE\n            KNT = KNT + 1\n            CALL ZDSCAL( N-1, RSAFMN, X, INCX )\n            BETA = BETA*RSAFMN\n            ALPHI = ALPHI*RSAFMN\n            ALPHR = ALPHR*RSAFMN\n            IF( ABS( BETA ).LT.SAFMIN )\n     $         GO TO 10\n*\n*           New BETA is at most 1, at least SAFMIN\n*\n            XNORM = DZNRM2( N-1, X, INCX )\n            ALPHA = DCMPLX( ALPHR, ALPHI )\n            BETA = -SIGN( DLAPY3( ALPHR, ALPHI, XNORM ), ALPHR )\n         END IF\n         TAU = DCMPLX( ( BETA-ALPHR ) / BETA, -ALPHI / BETA )\n         ALPHA = ZLADIV( DCMPLX( ONE ), ALPHA-BETA )\n         CALL ZSCAL( N-1, ALPHA, X, INCX )\n*\n*        If ALPHA is subnormal, it may lose relative accuracy\n*\n         DO 20 J = 1, KNT\n            BETA = BETA*SAFMIN\n 20      CONTINUE\n         ALPHA = BETA\n      END IF\n*\n      RETURN\n*\n*     End of ZLARFG\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/lapack/zlarft.f",
    "content": "*> \\brief \\b ZLARFT\n*\n*  =========== DOCUMENTATION ===========\n*\n* Online html documentation available at \n*            http://www.netlib.org/lapack/explore-html/ \n*\n*> \\htmlonly\n*> Download ZLARFT + dependencies \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.tgz?format=tgz&filename=/lapack/lapack_routine/zlarft.f\"> \n*> [TGZ]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.zip?format=zip&filename=/lapack/lapack_routine/zlarft.f\"> \n*> [ZIP]</a> \n*> <a href=\"http://www.netlib.org/cgi-bin/netlibfiles.txt?format=txt&filename=/lapack/lapack_routine/zlarft.f\"> \n*> [TXT]</a>\n*> \\endhtmlonly \n*\n*  Definition:\n*  ===========\n*\n*       SUBROUTINE ZLARFT( DIRECT, STOREV, N, K, V, LDV, TAU, T, LDT )\n* \n*       .. Scalar Arguments ..\n*       CHARACTER          DIRECT, STOREV\n*       INTEGER            K, LDT, LDV, N\n*       ..\n*       .. Array Arguments ..\n*       COMPLEX*16         T( LDT, * ), TAU( * ), V( LDV, * )\n*       ..\n*  \n*\n*> \\par Purpose:\n*  =============\n*>\n*> \\verbatim\n*>\n*> ZLARFT forms the triangular factor T of a complex block reflector H\n*> of order n, which is defined as a product of k elementary reflectors.\n*>\n*> If DIRECT = 'F', H = H(1) H(2) . . . H(k) and T is upper triangular;\n*>\n*> If DIRECT = 'B', H = H(k) . . . H(2) H(1) and T is lower triangular.\n*>\n*> If STOREV = 'C', the vector which defines the elementary reflector\n*> H(i) is stored in the i-th column of the array V, and\n*>\n*>    H  =  I - V * T * V**H\n*>\n*> If STOREV = 'R', the vector which defines the elementary reflector\n*> H(i) is stored in the i-th row of the array V, and\n*>\n*>    H  =  I - V**H * T * V\n*> \\endverbatim\n*\n*  Arguments:\n*  ==========\n*\n*> \\param[in] DIRECT\n*> \\verbatim\n*>          DIRECT is CHARACTER*1\n*>          Specifies the order in which the elementary reflectors are\n*>          multiplied to form the block reflector:\n*>          = 'F': H = H(1) H(2) . . . H(k) (Forward)\n*>          = 'B': H = H(k) . . . H(2) H(1) (Backward)\n*> \\endverbatim\n*>\n*> \\param[in] STOREV\n*> \\verbatim\n*>          STOREV is CHARACTER*1\n*>          Specifies how the vectors which define the elementary\n*>          reflectors are stored (see also Further Details):\n*>          = 'C': columnwise\n*>          = 'R': rowwise\n*> \\endverbatim\n*>\n*> \\param[in] N\n*> \\verbatim\n*>          N is INTEGER\n*>          The order of the block reflector H. N >= 0.\n*> \\endverbatim\n*>\n*> \\param[in] K\n*> \\verbatim\n*>          K is INTEGER\n*>          The order of the triangular factor T (= the number of\n*>          elementary reflectors). K >= 1.\n*> \\endverbatim\n*>\n*> \\param[in] V\n*> \\verbatim\n*>          V is COMPLEX*16 array, dimension\n*>                               (LDV,K) if STOREV = 'C'\n*>                               (LDV,N) if STOREV = 'R'\n*>          The matrix V. See further details.\n*> \\endverbatim\n*>\n*> \\param[in] LDV\n*> \\verbatim\n*>          LDV is INTEGER\n*>          The leading dimension of the array V.\n*>          If STOREV = 'C', LDV >= max(1,N); if STOREV = 'R', LDV >= K.\n*> \\endverbatim\n*>\n*> \\param[in] TAU\n*> \\verbatim\n*>          TAU is COMPLEX*16 array, dimension (K)\n*>          TAU(i) must contain the scalar factor of the elementary\n*>          reflector H(i).\n*> \\endverbatim\n*>\n*> \\param[out] T\n*> \\verbatim\n*>          T is COMPLEX*16 array, dimension (LDT,K)\n*>          The k by k triangular factor T of the block reflector.\n*>          If DIRECT = 'F', T is upper triangular; if DIRECT = 'B', T is\n*>          lower triangular. The rest of the array is not used.\n*> \\endverbatim\n*>\n*> \\param[in] LDT\n*> \\verbatim\n*>          LDT is INTEGER\n*>          The leading dimension of the array T. LDT >= K.\n*> \\endverbatim\n*\n*  Authors:\n*  ========\n*\n*> \\author Univ. of Tennessee \n*> \\author Univ. of California Berkeley \n*> \\author Univ. of Colorado Denver \n*> \\author NAG Ltd. \n*\n*> \\date April 2012\n*\n*> \\ingroup complex16OTHERauxiliary\n*\n*> \\par Further Details:\n*  =====================\n*>\n*> \\verbatim\n*>\n*>  The shape of the matrix V and the storage of the vectors which define\n*>  the H(i) is best illustrated by the following example with n = 5 and\n*>  k = 3. The elements equal to 1 are not stored.\n*>\n*>  DIRECT = 'F' and STOREV = 'C':         DIRECT = 'F' and STOREV = 'R':\n*>\n*>               V = (  1       )                 V = (  1 v1 v1 v1 v1 )\n*>                   ( v1  1    )                     (     1 v2 v2 v2 )\n*>                   ( v1 v2  1 )                     (        1 v3 v3 )\n*>                   ( v1 v2 v3 )\n*>                   ( v1 v2 v3 )\n*>\n*>  DIRECT = 'B' and STOREV = 'C':         DIRECT = 'B' and STOREV = 'R':\n*>\n*>               V = ( v1 v2 v3 )                 V = ( v1 v1  1       )\n*>                   ( v1 v2 v3 )                     ( v2 v2 v2  1    )\n*>                   (  1 v2 v3 )                     ( v3 v3 v3 v3  1 )\n*>                   (     1 v3 )\n*>                   (        1 )\n*> \\endverbatim\n*>\n*  =====================================================================\n      SUBROUTINE ZLARFT( DIRECT, STOREV, N, K, V, LDV, TAU, T, LDT )\n*\n*  -- LAPACK auxiliary routine (version 3.4.1) --\n*  -- LAPACK is a software package provided by Univ. of Tennessee,    --\n*  -- Univ. of California Berkeley, Univ. of Colorado Denver and NAG Ltd..--\n*     April 2012\n*\n*     .. Scalar Arguments ..\n      CHARACTER          DIRECT, STOREV\n      INTEGER            K, LDT, LDV, N\n*     ..\n*     .. Array Arguments ..\n      COMPLEX*16         T( LDT, * ), TAU( * ), V( LDV, * )\n*     ..\n*\n*  =====================================================================\n*\n*     .. Parameters ..\n      COMPLEX*16         ONE, ZERO\n      PARAMETER          ( ONE = ( 1.0D+0, 0.0D+0 ),\n     $                   ZERO = ( 0.0D+0, 0.0D+0 ) )\n*     ..\n*     .. Local Scalars ..\n      INTEGER            I, J, PREVLASTV, LASTV\n*     ..\n*     .. External Subroutines ..\n      EXTERNAL           ZGEMV, ZLACGV, ZTRMV\n*     ..\n*     .. External Functions ..\n      LOGICAL            LSAME\n      EXTERNAL           LSAME\n*     ..\n*     .. Executable Statements ..\n*\n*     Quick return if possible\n*\n      IF( N.EQ.0 )\n     $   RETURN\n*\n      IF( LSAME( DIRECT, 'F' ) ) THEN\n         PREVLASTV = N\n         DO I = 1, K\n            PREVLASTV = MAX( PREVLASTV, I )\n            IF( TAU( I ).EQ.ZERO ) THEN\n*\n*              H(i)  =  I\n*\n               DO J = 1, I\n                  T( J, I ) = ZERO\n               END DO\n            ELSE\n*\n*              general case\n*\n               IF( LSAME( STOREV, 'C' ) ) THEN\n*                 Skip any trailing zeros.\n                  DO LASTV = N, I+1, -1\n                     IF( V( LASTV, I ).NE.ZERO ) EXIT\n                  END DO\n                  DO J = 1, I-1\n                     T( J, I ) = -TAU( I ) * CONJG( V( I , J ) )\n                  END DO                     \n                  J = MIN( LASTV, PREVLASTV )\n*\n*                 T(1:i-1,i) := - tau(i) * V(i:j,1:i-1)**H * V(i:j,i)\n*\n                  CALL ZGEMV( 'Conjugate transpose', J-I, I-1,\n     $                        -TAU( I ), V( I+1, 1 ), LDV, \n     $                        V( I+1, I ), 1, ONE, T( 1, I ), 1 )\n               ELSE\n*                 Skip any trailing zeros.\n                  DO LASTV = N, I+1, -1\n                     IF( V( I, LASTV ).NE.ZERO ) EXIT\n                  END DO\n                  DO J = 1, I-1\n                     T( J, I ) = -TAU( I ) * V( J , I )\n                  END DO                     \n                  J = MIN( LASTV, PREVLASTV )\n*\n*                 T(1:i-1,i) := - tau(i) * V(1:i-1,i:j) * V(i,i:j)**H\n*\n                  CALL ZGEMM( 'N', 'C', I-1, 1, J-I, -TAU( I ),\n     $                        V( 1, I+1 ), LDV, V( I, I+1 ), LDV,\n     $                        ONE, T( 1, I ), LDT )                  \n               END IF\n*\n*              T(1:i-1,i) := T(1:i-1,1:i-1) * T(1:i-1,i)\n*\n               CALL ZTRMV( 'Upper', 'No transpose', 'Non-unit', I-1, T,\n     $                     LDT, T( 1, I ), 1 )\n               T( I, I ) = TAU( I )\n               IF( I.GT.1 ) THEN\n                  PREVLASTV = MAX( PREVLASTV, LASTV )\n               ELSE\n                  PREVLASTV = LASTV\n               END IF\n             END IF\n         END DO\n      ELSE\n         PREVLASTV = 1\n         DO I = K, 1, -1\n            IF( TAU( I ).EQ.ZERO ) THEN\n*\n*              H(i)  =  I\n*\n               DO J = I, K\n                  T( J, I ) = ZERO\n               END DO\n            ELSE\n*\n*              general case\n*\n               IF( I.LT.K ) THEN\n                  IF( LSAME( STOREV, 'C' ) ) THEN\n*                    Skip any leading zeros.\n                     DO LASTV = 1, I-1\n                        IF( V( LASTV, I ).NE.ZERO ) EXIT\n                     END DO\n                     DO J = I+1, K\n                        T( J, I ) = -TAU( I ) * CONJG( V( N-K+I , J ) )\n                     END DO                        \n                     J = MAX( LASTV, PREVLASTV )\n*\n*                    T(i+1:k,i) = -tau(i) * V(j:n-k+i,i+1:k)**H * V(j:n-k+i,i)\n*\n                     CALL ZGEMV( 'Conjugate transpose', N-K+I-J, K-I,\n     $                           -TAU( I ), V( J, I+1 ), LDV, V( J, I ),\n     $                           1, ONE, T( I+1, I ), 1 )\n                  ELSE\n*                    Skip any leading zeros.\n                     DO LASTV = 1, I-1\n                        IF( V( I, LASTV ).NE.ZERO ) EXIT\n                     END DO\n                     DO J = I+1, K\n                        T( J, I ) = -TAU( I ) * V( J, N-K+I )\n                     END DO                                           \n                     J = MAX( LASTV, PREVLASTV )\n*\n*                    T(i+1:k,i) = -tau(i) * V(i+1:k,j:n-k+i) * V(i,j:n-k+i)**H\n*\n                     CALL ZGEMM( 'N', 'C', K-I, 1, N-K+I-J, -TAU( I ),\n     $                           V( I+1, J ), LDV, V( I, J ), LDV,\n     $                           ONE, T( I+1, I ), LDT )                     \n                  END IF\n*\n*                 T(i+1:k,i) := T(i+1:k,i+1:k) * T(i+1:k,i)\n*\n                  CALL ZTRMV( 'Lower', 'No transpose', 'Non-unit', K-I,\n     $                        T( I+1, I+1 ), LDT, T( I+1, I ), 1 )\n                  IF( I.GT.1 ) THEN\n                     PREVLASTV = MIN( PREVLASTV, LASTV )\n                  ELSE\n                     PREVLASTV = LASTV\n                  END IF\n               END IF\n               T( I, I ) = TAU( I )\n            END IF\n         END DO\n      END IF\n      RETURN\n*\n*     End of ZLARFT\n*\n      END\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/scripts/CMakeLists.txt",
    "content": "get_property(EIGEN_TESTS_LIST GLOBAL PROPERTY EIGEN_TESTS_LIST)\nconfigure_file(buildtests.in ${CMAKE_BINARY_DIR}/buildtests.sh @ONLY)\n\nconfigure_file(check.in ${CMAKE_BINARY_DIR}/check.sh COPYONLY)\nconfigure_file(debug.in ${CMAKE_BINARY_DIR}/debug.sh COPYONLY)\nconfigure_file(release.in ${CMAKE_BINARY_DIR}/release.sh COPYONLY)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/scripts/cdashtesting.cmake.in",
    "content": "\nset(CTEST_SOURCE_DIRECTORY  \"@CMAKE_SOURCE_DIR@\")\nset(CTEST_BINARY_DIRECTORY  \"@CMAKE_BINARY_DIR@\")\nset(CTEST_CMAKE_GENERATOR   \"@CMAKE_GENERATOR@\")\nset(CTEST_BUILD_NAME        \"@BUILDNAME@\")\nset(CTEST_SITE              \"@SITE@\")\n\nset(MODEL Experimental)\nif(${CTEST_SCRIPT_ARG} MATCHES Nightly)\n  set(MODEL Nightly)\nelseif(${CTEST_SCRIPT_ARG} MATCHES Continuous)\n  set(MODEL Continuous)\nendif()\n\nfind_program(CTEST_GIT_COMMAND NAMES git)\nset(CTEST_UPDATE_COMMAND \"${CTEST_GIT_COMMAND}\")\n\nctest_start(${MODEL} ${CTEST_SOURCE_DIRECTORY} ${CTEST_BINARY_DIRECTORY})\n\nctest_update(SOURCE \"${CTEST_SOURCE_DIRECTORY}\")\nctest_submit(PARTS Update Notes)\n\n# to get CTEST_PROJECT_SUBPROJECTS definition:\ninclude(\"${CTEST_SOURCE_DIRECTORY}/CTestConfig.cmake\")\n\nforeach(subproject ${CTEST_PROJECT_SUBPROJECTS})\n  message(\"\")\n  message(\"Process ${subproject}\")\n  \n  set_property(GLOBAL PROPERTY SubProject ${subproject})\n  set_property(GLOBAL PROPERTY Label ${subproject})\n\n  ctest_configure(BUILD ${CTEST_BINARY_DIRECTORY} SOURCE ${CTEST_SOURCE_DIRECTORY} )\n  ctest_submit(PARTS Configure)\n\n  set(CTEST_BUILD_TARGET \"Build${subproject}\")\n  message(\"Build ${CTEST_BUILD_TARGET}\")\n  ctest_build(BUILD \"${CTEST_BINARY_DIRECTORY}\" APPEND)\n  # builds target ${CTEST_BUILD_TARGET}\n  ctest_submit(PARTS Build)\n\n  ctest_test(BUILD \"${CTEST_BINARY_DIRECTORY}\" INCLUDE_LABEL \"${subproject}\" )\n  # runs only tests that have a LABELS property matching \"${subproject}\"\n  \n  ctest_coverage(BUILD \"${CTEST_BINARY_DIRECTORY}\" LABELS \"${subproject}\" )\n  \n  ctest_submit(PARTS Test)\n  \nendforeach()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/scripts/check.in",
    "content": "#!/bin/bash\n# check : shorthand for make and ctest -R\n\nif [[ $# != 1 || $1 == *help ]]\nthen\n  echo \"usage: $0 regexp\"\n  echo \"  Builds and runs tests matching the regexp.\"\n  echo \"  The EIGEN_MAKE_ARGS environment variable allows to pass args to 'make'.\"\n  echo \"    For example, to launch 5 concurrent builds, use EIGEN_MAKE_ARGS='-j5'\"\n  echo \"  The EIGEN_CTEST_ARGS environment variable allows to pass args to 'ctest'.\"\n  echo \"    For example, with CTest 2.8, you can use EIGEN_CTEST_ARGS='-j5'.\"\n  exit 0\nfi\n\nif [ -n \"${EIGEN_CTEST_ARGS:+x}\" ]\nthen\n  ./buildtests.sh \"$1\" && ctest -R \"$1\" ${EIGEN_CTEST_ARGS}\nelse\n  ./buildtests.sh \"$1\" && ctest -R \"$1\"\nfi\nexit $?\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/scripts/debug.in",
    "content": "#!/bin/sh\n\ncmake -DCMAKE_BUILD_TYPE=Debug .\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/scripts/eigen_gen_credits.cpp",
    "content": "#include <string>\n#include <sstream>\n#include <iostream>\n#include <fstream>\n#include <iomanip>\n#include <map>\n#include <list>\n\nusing namespace std;\n\n// this function takes a line that may contain a name and/or email address,\n// and returns just the name, while fixing the \"bad cases\".\nstd::string contributor_name(const std::string& line)\n{\n  string result;\n\n  // let's first take care of the case of isolated email addresses, like\n  // \"user@localhost.localdomain\" entries\n  if(line.find(\"markb@localhost.localdomain\") != string::npos)\n  {\n    return \"Mark Borgerding\";\n  }\n\n  if(line.find(\"kayhman@contact.intra.cea.fr\") != string::npos)\n  {\n    return \"Guillaume Saupin\";\n  }\n\n  // from there on we assume that we have a entry of the form\n  // either:\n  //   Bla bli Blurp\n  // or:\n  //   Bla bli Blurp <bblurp@email.com>\n  \n  size_t position_of_email_address = line.find_first_of('<');\n  if(position_of_email_address != string::npos)\n  {\n    // there is an e-mail address in <...>.\n    \n    // Hauke once committed as \"John Smith\", fix that.\n    if(line.find(\"hauke.heibel\") != string::npos)\n      result = \"Hauke Heibel\";\n    else\n    {\n      // just remove the e-mail address\n      result = line.substr(0, position_of_email_address);\n    }\n  }\n  else\n  {\n    // there is no e-mail address in <...>.\n    \n    if(line.find(\"convert-repo\") != string::npos)\n      result = \"\";\n    else\n      result = line;\n  }\n\n  // remove trailing spaces\n  size_t length = result.length();\n  while(length >= 1 && result[length-1] == ' ') result.erase(--length);\n\n  return result;\n}\n\n// parses hg churn output to generate a contributors map.\nmap<string,int> contributors_map_from_churn_output(const char *filename)\n{\n  map<string,int> contributors_map;\n\n  string line;\n  ifstream churn_out;\n  churn_out.open(filename, ios::in);\n  while(!getline(churn_out,line).eof())\n  {\n    // remove the histograms \"******\" that hg churn may draw at the end of some lines\n    size_t first_star = line.find_first_of('*');\n    if(first_star != string::npos) line.erase(first_star);\n    \n    // remove trailing spaces\n    size_t length = line.length();\n    while(length >= 1 && line[length-1] == ' ') line.erase(--length);\n\n    // now the last space indicates where the number starts\n    size_t last_space = line.find_last_of(' ');\n    \n    // get the number (of changesets or of modified lines for each contributor)\n    int number;\n    istringstream(line.substr(last_space+1)) >> number;\n\n    // get the name of the contributor\n    line.erase(last_space);    \n    string name = contributor_name(line);\n    \n    map<string,int>::iterator it = contributors_map.find(name);\n    // if new contributor, insert\n    if(it == contributors_map.end())\n      contributors_map.insert(pair<string,int>(name, number));\n    // if duplicate, just add the number\n    else\n      it->second += number;\n  }\n  churn_out.close();\n\n  return contributors_map;\n}\n\n// find the last name, i.e. the last word.\n// for \"van den Schbling\" types of last names, that's not a problem, that's actually what we want.\nstring lastname(const string& name)\n{\n  size_t last_space = name.find_last_of(' ');\n  if(last_space >= name.length()-1) return name;\n  else return name.substr(last_space+1);\n}\n\nstruct contributor\n{\n  string name;\n  int changedlines;\n  int changesets;\n  string url;\n  string misc;\n  \n  contributor() : changedlines(0), changesets(0) {}\n  \n  bool operator < (const contributor& other)\n  {\n    return lastname(name).compare(lastname(other.name)) < 0;\n  }\n};\n\nvoid add_online_info_into_contributors_list(list<contributor>& contributors_list, const char *filename)\n{\n  string line;\n  ifstream online_info;\n  online_info.open(filename, ios::in);\n  while(!getline(online_info,line).eof())\n  {\n    string hgname, realname, url, misc;\n    \n    size_t last_bar = line.find_last_of('|');\n    if(last_bar == string::npos) continue;\n    if(last_bar < line.length())\n      misc = line.substr(last_bar+1);\n    line.erase(last_bar);\n    \n    last_bar = line.find_last_of('|');\n    if(last_bar == string::npos) continue;\n    if(last_bar < line.length())\n      url = line.substr(last_bar+1);\n    line.erase(last_bar);\n\n    last_bar = line.find_last_of('|');\n    if(last_bar == string::npos) continue;\n    if(last_bar < line.length())\n      realname = line.substr(last_bar+1);\n    line.erase(last_bar);\n\n    hgname = line;\n    \n    // remove the example line\n    if(hgname.find(\"MercurialName\") != string::npos) continue;\n    \n    list<contributor>::iterator it;\n    for(it=contributors_list.begin(); it != contributors_list.end() && it->name != hgname; ++it)\n    {}\n    \n    if(it == contributors_list.end())\n    {\n      contributor c;\n      c.name = realname;\n      c.url = url;\n      c.misc = misc;\n      contributors_list.push_back(c);\n    }\n    else\n    {\n      it->name = realname;\n      it->url = url;\n      it->misc = misc;\n    }\n  }\n}\n\nint main()\n{\n  // parse the hg churn output files\n  map<string,int> contributors_map_for_changedlines = contributors_map_from_churn_output(\"churn-changedlines.out\");\n  //map<string,int> contributors_map_for_changesets = contributors_map_from_churn_output(\"churn-changesets.out\");\n  \n  // merge into the contributors list\n  list<contributor> contributors_list;\n  map<string,int>::iterator it;\n  for(it=contributors_map_for_changedlines.begin(); it != contributors_map_for_changedlines.end(); ++it)\n  {\n    contributor c;\n    c.name = it->first;\n    c.changedlines = it->second;\n    c.changesets = 0; //contributors_map_for_changesets.find(it->first)->second;\n    contributors_list.push_back(c);\n  }\n  \n  add_online_info_into_contributors_list(contributors_list, \"online-info.out\");\n  \n  contributors_list.sort();\n  \n  cout << \"{| cellpadding=\\\"5\\\"\\n\";\n  cout << \"!\\n\";\n  cout << \"! Lines changed\\n\";\n  cout << \"!\\n\";\n\n  list<contributor>::iterator itc;\n  int i = 0;\n  for(itc=contributors_list.begin(); itc != contributors_list.end(); ++itc)\n  {\n    if(itc->name.length() == 0) continue;\n    if(i%2) cout << \"|-\\n\";\n    else cout << \"|- style=\\\"background:#FFFFD0\\\"\\n\";\n    if(itc->url.length())\n      cout << \"| [\" << itc->url << \" \" << itc->name << \"]\\n\";\n    else\n      cout << \"| \" << itc->name << \"\\n\";\n    if(itc->changedlines)\n      cout << \"| \" << itc->changedlines << \"\\n\";\n    else\n      cout << \"| (no information)\\n\";\n    cout << \"| \" << itc->misc << \"\\n\";\n    i++;\n  }\n  cout << \"|}\" << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/scripts/eigen_gen_docs",
    "content": "#!/bin/sh\n\n# configuration\n# You should call this script with USER set as you want, else some default\n# will be used\nUSER=${USER:-'orzel'}\nUPLOAD_DIR=dox-devel\n\n#ulimit -v 1024000\n\n# step 1 : build\nrm build/doc/html -Rf\nmkdir build -p\n(cd build && cmake .. && make doc) || { echo \"make failed\"; exit 1; }\n\n#step 2 : upload\n# (the '/' at the end of path is very important, see rsync documentation)\nrsync -az --no-p --delete build/doc/html/ $USER@ssh.tuxfamily.org:eigen/eigen.tuxfamily.org-web/htdocs/$UPLOAD_DIR/ || { echo \"upload failed\"; exit 1; }\n\n#step 3 : fix the perm\nssh $USER@ssh.tuxfamily.org \"chmod -R g+w /home/eigen/eigen.tuxfamily.org-web/htdocs/$UPLOAD_DIR\" || { echo \"perm failed\"; exit 1; }\n\necho \"Uploaded successfully\"\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/scripts/eigen_gen_split_test_help.cmake",
    "content": "#!cmake -P\nfile(WRITE split_test_helper.h \"\")\nforeach(i RANGE 1 999)\n  file(APPEND split_test_helper.h\n    \"#if defined(EIGEN_TEST_PART_${i}) || defined(EIGEN_TEST_PART_ALL)\\n\"\n    \"#define CALL_SUBTEST_${i}(FUNC) CALL_SUBTEST(FUNC)\\n\"\n    \"#else\\n\"\n    \"#define CALL_SUBTEST_${i}(FUNC)\\n\"\n    \"#endif\\n\\n\"\n  )\nendforeach()"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/scripts/eigen_monitor_perf.sh",
    "content": "#!/bin/bash\n\n# This is a script example to automatically update and upload performance unit tests.\n# The following five variables must be adjusted to match your settings.\n\nUSER='ggael'\nUPLOAD_DIR=perf_monitoring/ggaelmacbook26\nEIGEN_SOURCE_PATH=$HOME/Eigen/eigen\nexport PREFIX=\"haswell-fma\"\nexport CXX_FLAGS=\"-mfma -w\"\n\n####\n\nBENCH_PATH=$EIGEN_SOURCE_PATH/bench/perf_monitoring/$PREFIX\nPREVPATH=$(pwd)\ncd $EIGEN_SOURCE_PATH/bench/perf_monitoring && ./runall.sh \"Haswell 2.6GHz, FMA, Apple's clang\" \"$@\"\ncd $PREVPATH || exit 1\n\nALLFILES=\"$BENCH_PATH/*.png $BENCH_PATH/*.html $BENCH_PATH/index.html $BENCH_PATH/s1.js $BENCH_PATH/s2.js\"\n\n# (the '/' at the end of path is very important, see rsync documentation)\nrsync -az --no-p --delete $ALLFILES $USER@ssh.tuxfamily.org:eigen/eigen.tuxfamily.org-web/htdocs/$UPLOAD_DIR/ || { echo \"upload failed\"; exit 1; }\n\n# fix the perm\nssh $USER@ssh.tuxfamily.org \"chmod -R g+w /home/eigen/eigen.tuxfamily.org-web/htdocs/perf_monitoring\" || { echo \"perm failed\"; exit 1; }\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/scripts/release.in",
    "content": "#!/bin/sh\n\ncmake -DCMAKE_BUILD_TYPE=Release .\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/scripts/relicense.py",
    "content": "# This file is part of Eigen, a lightweight C++ template library\n# for linear algebra.\n#\n# Copyright (C) 2012 Keir Mierle <mierle@gmail.com>\n#\n# This Source Code Form is subject to the terms of the Mozilla\n# Public License v. 2.0. If a copy of the MPL was not distributed\n# with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n#\n# Author: mierle@gmail.com (Keir Mierle)\n#\n# Make the long-awaited conversion to MPL.\n\nlgpl3_header = '''\n// Eigen is free software; you can redistribute it and/or\n// modify it under the terms of the GNU Lesser General Public\n// License as published by the Free Software Foundation; either\n// version 3 of the License, or (at your option) any later version.\n//\n// Alternatively, you can redistribute it and/or\n// modify it under the terms of the GNU General Public License as\n// published by the Free Software Foundation; either version 2 of\n// the License, or (at your option) any later version.\n//\n// Eigen is distributed in the hope that it will be useful, but WITHOUT ANY\n// WARRANTY; without even the implied warranty of MERCHANTABILITY or FITNESS\n// FOR A PARTICULAR PURPOSE. See the GNU Lesser General Public License or the\n// GNU General Public License for more details.\n//\n// You should have received a copy of the GNU Lesser General Public\n// License and a copy of the GNU General Public License along with\n// Eigen. If not, see <http://www.gnu.org/licenses/>.\n'''\n\nmpl2_header = \"\"\"\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\"\"\"\n\nimport os\nimport sys\n\nexclusions = set(['relicense.py'])\n\ndef update(text):\n  if text.find(lgpl3_header) == -1:\n    return text, False\n  return text.replace(lgpl3_header, mpl2_header), True\n\nrootdir = sys.argv[1]\nfor root, sub_folders, files in os.walk(rootdir):\n    for basename in files:\n        if basename in exclusions:\n          print 'SKIPPED', filename\n          continue\n        filename = os.path.join(root, basename)\n        fo = file(filename)\n        text = fo.read()\n        fo.close()\n\n        text, updated = update(text)\n        if updated:\n          fo = file(filename, \"w\")\n          fo.write(text)\n          fo.close()\n          print 'UPDATED', filename\n        else:\n          print '       ', filename\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/signature_of_eigen3_matrix_library",
    "content": "This file is just there as a signature to help identify directories containing Eigen3. When writing a script looking for Eigen3, just look for this file. This is especially useful to help disambiguate with Eigen2...\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/AnnoyingScalar.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011-2018 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_TEST_ANNOYING_SCALAR_H\n#define EIGEN_TEST_ANNOYING_SCALAR_H\n\n#include <ostream>\n\n#if EIGEN_COMP_GNUC\n#pragma GCC diagnostic ignored \"-Wshadow\"\n#endif\n\n#ifndef EIGEN_TEST_ANNOYING_SCALAR_DONT_THROW\nstruct my_exception\n{\n  my_exception() {}\n  ~my_exception() {}\n};\n#endif\n\n// An AnnoyingScalar is a pseudo scalar type that:\n// - can randomly through an exception in operator +\n// - randomly allocate on the heap or initialize a reference to itself making it non trivially copyable, nor movable, nor relocatable.\n\nclass AnnoyingScalar\n{\n  public:\n    AnnoyingScalar()                { init(); *v = 0;  }\n    AnnoyingScalar(long double _v)  { init(); *v = _v; }\n    AnnoyingScalar(double _v)       { init(); *v = _v; }\n    AnnoyingScalar(float _v)        { init(); *v = _v; }\n    AnnoyingScalar(int _v)          { init(); *v = _v; }\n    AnnoyingScalar(long _v)         { init(); *v = _v; }\n    #if EIGEN_HAS_CXX11\n    AnnoyingScalar(long long _v)    { init(); *v = _v; }\n    #endif\n    AnnoyingScalar(const AnnoyingScalar& other) { init(); *v = *(other.v); }\n    ~AnnoyingScalar() {\n      if(v!=&data)\n        delete v;\n      instances--;\n    }\n\n    void init() {\n      if(internal::random<bool>())\n        v = new float;\n      else\n        v = &data;\n      instances++;\n    }\n\n    AnnoyingScalar operator+(const AnnoyingScalar& other) const\n    {\n      #ifndef EIGEN_TEST_ANNOYING_SCALAR_DONT_THROW\n      countdown--;\n      if(countdown<=0 && !dont_throw)\n        throw my_exception();\n      #endif\n      return AnnoyingScalar(*v+*other.v);\n    }\n\n    AnnoyingScalar operator-() const\n    { return AnnoyingScalar(-*v); }\n    \n    AnnoyingScalar operator-(const AnnoyingScalar& other) const\n    { return AnnoyingScalar(*v-*other.v); }\n    \n    AnnoyingScalar operator*(const AnnoyingScalar& other) const\n    { return AnnoyingScalar((*v)*(*other.v)); }\n\n    AnnoyingScalar operator/(const AnnoyingScalar& other) const\n    { return AnnoyingScalar((*v)/(*other.v)); }\n    \n    AnnoyingScalar& operator+=(const AnnoyingScalar& other) { *v += *other.v; return *this; }\n    AnnoyingScalar& operator-=(const AnnoyingScalar& other) { *v -= *other.v; return *this; }\n    AnnoyingScalar& operator*=(const AnnoyingScalar& other) { *v *= *other.v; return *this; }\n    AnnoyingScalar& operator/=(const AnnoyingScalar& other) { *v /= *other.v; return *this; }\n    AnnoyingScalar& operator= (const AnnoyingScalar& other) { *v  = *other.v; return *this; }\n  \n    bool operator==(const AnnoyingScalar& other) const { return *v == *other.v; }\n    bool operator!=(const AnnoyingScalar& other) const { return *v != *other.v; }\n    bool operator<=(const AnnoyingScalar& other) const { return *v <= *other.v; }\n    bool operator< (const AnnoyingScalar& other) const { return *v <  *other.v; }\n    bool operator>=(const AnnoyingScalar& other) const { return *v >= *other.v; }\n    bool operator> (const AnnoyingScalar& other) const { return *v >  *other.v; }\n    \n    float* v;\n    float data;\n    static int instances;\n#ifndef EIGEN_TEST_ANNOYING_SCALAR_DONT_THROW\n    static int countdown;\n    static bool dont_throw;\n#endif\n};\n\nAnnoyingScalar real(const AnnoyingScalar &x) { return x; }\nAnnoyingScalar imag(const AnnoyingScalar & ) { return 0; }\nAnnoyingScalar conj(const AnnoyingScalar &x) { return x; }\nAnnoyingScalar sqrt(const AnnoyingScalar &x) { return std::sqrt(*x.v); }\nAnnoyingScalar abs (const AnnoyingScalar &x) { return std::abs(*x.v); }\nAnnoyingScalar cos (const AnnoyingScalar &x) { return std::cos(*x.v); }\nAnnoyingScalar sin (const AnnoyingScalar &x) { return std::sin(*x.v); }\nAnnoyingScalar acos(const AnnoyingScalar &x) { return std::acos(*x.v); }\nAnnoyingScalar atan2(const AnnoyingScalar &y,const AnnoyingScalar &x) { return std::atan2(*y.v,*x.v); }\n\nstd::ostream& operator<<(std::ostream& stream,const AnnoyingScalar& x) {\n  stream << (*(x.v));\n  return stream;\n}\n\nint AnnoyingScalar::instances = 0;\n\n#ifndef EIGEN_TEST_ANNOYING_SCALAR_DONT_THROW\nint AnnoyingScalar::countdown = 0;\nbool AnnoyingScalar::dont_throw = false;\n#endif\n\nnamespace Eigen {\ntemplate<>\nstruct NumTraits<AnnoyingScalar> : NumTraits<float>\n{\n  enum {\n    RequireInitialization = true\n  };\n  typedef AnnoyingScalar Real;\n  typedef AnnoyingScalar Nested;\n  typedef AnnoyingScalar Literal;\n  typedef AnnoyingScalar NonInteger;\n};\n\ntemplate<> inline AnnoyingScalar test_precision<AnnoyingScalar>() { return test_precision<float>(); }\n\nnamespace internal {\n  template<> double cast(const AnnoyingScalar& x) { return double(*x.v); }\n  template<> float  cast(const AnnoyingScalar& x) { return *x.v; }\n}\n\n}\n\nAnnoyingScalar get_test_precision(const AnnoyingScalar&)\n{ return Eigen::test_precision<AnnoyingScalar>(); }\n\nAnnoyingScalar test_relative_error(const AnnoyingScalar &a, const AnnoyingScalar &b)\n{ return test_relative_error(*a.v, *b.v); }\n\ninline bool test_isApprox(const AnnoyingScalar &a, const AnnoyingScalar &b)\n{ return internal::isApprox(*a.v, *b.v, test_precision<float>()); }\n\ninline bool test_isMuchSmallerThan(const AnnoyingScalar &a, const AnnoyingScalar &b)\n{ return test_isMuchSmallerThan(*a.v, *b.v); }\n\n#endif // EIGEN_TEST_ANNOYING_SCALAR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/CMakeLists.txt",
    "content": "# The file split_test_helper.h was generated at first run,\n# it is now included in test/\nif(EXISTS ${CMAKE_CURRENT_BINARY_DIR}/split_test_helper.h)\n  file(REMOVE ${CMAKE_CURRENT_BINARY_DIR}/split_test_helper.h)\nendif()\n\n# check if we have a Fortran compiler\ninclude(CheckLanguage)\ncheck_language(Fortran)\nif(CMAKE_Fortran_COMPILER)\n  enable_language(Fortran)\n  set(EIGEN_Fortran_COMPILER_WORKS ON)\nelse()\n  set(EIGEN_Fortran_COMPILER_WORKS OFF)\n  # search for a default Lapack library to complete Eigen's one\n  find_package(LAPACK QUIET)\nendif()\n\n# TODO do the same for EXTERNAL_LAPACK\noption(EIGEN_TEST_EXTERNAL_BLAS \"Use external BLAS library for testsuite\" OFF)\nif(EIGEN_TEST_EXTERNAL_BLAS)\n  find_package(BLAS REQUIRED)\n  message(STATUS \"BLAS_COMPILER_FLAGS: ${BLAS_COMPILER_FLAGS}\")\n  add_definitions(\"-DEIGEN_USE_BLAS\") # is adding  ${BLAS_COMPILER_FLAGS} necessary?\n  list(APPEND EXTERNAL_LIBS \"${BLAS_LIBRARIES}\")\nendif()\n\n# configure blas/lapack (use Eigen's ones)\nset(EIGEN_BLAS_LIBRARIES eigen_blas)\nset(EIGEN_LAPACK_LIBRARIES eigen_lapack)\n\nset(EIGEN_TEST_MATRIX_DIR \"\" CACHE STRING \"Enable testing of realword sparse matrices contained in the specified path\")\nif(EIGEN_TEST_MATRIX_DIR)\n  if(NOT WIN32)\n    message(STATUS \"Test realworld sparse matrices: ${EIGEN_TEST_MATRIX_DIR}\")\n    add_definitions( -DTEST_REAL_CASES=\"${EIGEN_TEST_MATRIX_DIR}\" )\n  else()\n    message(STATUS \"REAL CASES CAN NOT BE CURRENTLY TESTED ON WIN32\")\n  endif()\nendif()\n\nset(SPARSE_LIBS \" \")\n\nfind_package(CHOLMOD)\nif(CHOLMOD_FOUND)\n  add_definitions(\"-DEIGEN_CHOLMOD_SUPPORT\")\n  include_directories(${CHOLMOD_INCLUDES})\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${CHOLMOD_LIBRARIES} ${EIGEN_BLAS_LIBRARIES} ${EIGEN_LAPACK_LIBRARIES})\n  set(CHOLMOD_ALL_LIBS  ${CHOLMOD_LIBRARIES} ${EIGEN_BLAS_LIBRARIES} ${EIGEN_LAPACK_LIBRARIES})\n  ei_add_property(EIGEN_TESTED_BACKENDS \"CHOLMOD, \")\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS \"CHOLMOD, \")\nendif()\n\nfind_package(UMFPACK)\nif(UMFPACK_FOUND)\n  add_definitions(\"-DEIGEN_UMFPACK_SUPPORT\")\n  include_directories(${UMFPACK_INCLUDES})\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${UMFPACK_LIBRARIES} ${EIGEN_BLAS_LIBRARIES})\n  set(UMFPACK_ALL_LIBS ${UMFPACK_LIBRARIES} ${EIGEN_BLAS_LIBRARIES})\n  ei_add_property(EIGEN_TESTED_BACKENDS \"UMFPACK, \")\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS \"UMFPACK, \")\nendif()\n\nfind_package(KLU)\nif(KLU_FOUND)\n  add_definitions(\"-DEIGEN_KLU_SUPPORT\")\n  include_directories(${KLU_INCLUDES})\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${KLU_LIBRARIES} ${EIGEN_BLAS_LIBRARIES})\n  set(KLU_ALL_LIBS ${KLU_LIBRARIES} ${EIGEN_BLAS_LIBRARIES})\n  ei_add_property(EIGEN_TESTED_BACKENDS \"KLU, \")\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS \"KLU, \")\nendif()\n\nfind_package(SuperLU 4.0)\nif(SuperLU_FOUND)\n  add_definitions(\"-DEIGEN_SUPERLU_SUPPORT\")\n  include_directories(${SUPERLU_INCLUDES})\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${SUPERLU_LIBRARIES} ${EIGEN_BLAS_LIBRARIES})\n  set(SUPERLU_ALL_LIBS ${SUPERLU_LIBRARIES} ${EIGEN_BLAS_LIBRARIES})\n  ei_add_property(EIGEN_TESTED_BACKENDS  \"SuperLU, \")\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS  \"SuperLU, \")\nendif()\n\n\nfind_package(PASTIX QUIET COMPONENTS METIS SEQ)\n# check that the PASTIX found is a version without MPI\nfind_path(PASTIX_pastix_nompi.h_INCLUDE_DIRS\n  NAMES pastix_nompi.h\n  HINTS ${PASTIX_INCLUDE_DIRS}\n)\nif (NOT PASTIX_pastix_nompi.h_INCLUDE_DIRS)\n  message(STATUS \"A version of Pastix has been found but pastix_nompi.h does not exist in the include directory.\"\n                 \" Because Eigen tests require a version without MPI, we disable the Pastix backend.\")\nendif()\nif(PASTIX_FOUND AND PASTIX_pastix_nompi.h_INCLUDE_DIRS)\n  add_definitions(\"-DEIGEN_PASTIX_SUPPORT\")\n  include_directories(${PASTIX_INCLUDE_DIRS_DEP})\n  if(SCOTCH_FOUND)\n    include_directories(${SCOTCH_INCLUDE_DIRS})\n    set(PASTIX_LIBRARIES ${PASTIX_LIBRARIES} ${SCOTCH_LIBRARIES})\n  elseif(METIS_FOUND)\n    include_directories(${METIS_INCLUDE_DIRS})\n    set(PASTIX_LIBRARIES ${PASTIX_LIBRARIES} ${METIS_LIBRARIES})\n  else()\n    ei_add_property(EIGEN_MISSING_BACKENDS  \"PaStiX, \")\n  endif()\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${PASTIX_LIBRARIES_DEP} ${ORDERING_LIBRARIES})\n  set(PASTIX_ALL_LIBS ${PASTIX_LIBRARIES_DEP})\n  ei_add_property(EIGEN_TESTED_BACKENDS  \"PaStiX, \")\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS  \"PaStiX, \")\nendif()\n\nif(METIS_FOUND)\n  add_definitions(\"-DEIGEN_METIS_SUPPORT\")\n  include_directories(${METIS_INCLUDE_DIRS})\n  ei_add_property(EIGEN_TESTED_BACKENDS \"METIS, \")\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS \"METIS, \")\nendif()\n\nfind_package(SPQR)\nif(SPQR_FOUND AND CHOLMOD_FOUND AND (EIGEN_Fortran_COMPILER_WORKS OR LAPACK_FOUND) )\n  add_definitions(\"-DEIGEN_SPQR_SUPPORT\")\n  include_directories(${SPQR_INCLUDES})\n  set(SPQR_ALL_LIBS ${SPQR_LIBRARIES} ${CHOLMOD_LIBRARIES} ${EIGEN_LAPACK_LIBRARIES} ${EIGEN_BLAS_LIBRARIES} ${LAPACK_LIBRARIES})\n  set(SPARSE_LIBS ${SPARSE_LIBS} ${SPQR_ALL_LIBS})\n  ei_add_property(EIGEN_TESTED_BACKENDS \"SPQR, \")\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS \"SPQR, \")\nendif()\n\noption(EIGEN_TEST_NOQT \"Disable Qt support in unit tests\" OFF)\nif(NOT EIGEN_TEST_NOQT)\n  find_package(Qt4)\n  if(QT4_FOUND)\n    include(${QT_USE_FILE})\n    ei_add_property(EIGEN_TESTED_BACKENDS  \"Qt4 support, \")\n  else()\n    ei_add_property(EIGEN_MISSING_BACKENDS  \"Qt4 support, \")\n  endif()\nendif()\n\nif(TEST_LIB)\n  add_definitions(\"-DEIGEN_EXTERN_INSTANTIATIONS=1\")\nendif()\n\nset_property(GLOBAL PROPERTY EIGEN_CURRENT_SUBPROJECT \"Official\")\nadd_custom_target(BuildOfficial)\n\nei_add_test(rand)\nei_add_test(meta)\nei_add_test(numext)\nei_add_test(sizeof)\nei_add_test(dynalloc)\nei_add_test(nomalloc)\nei_add_test(first_aligned)\nei_add_test(type_alias)\nei_add_test(nullary)\nei_add_test(mixingtypes)\nei_add_test(io)\nei_add_test(packetmath \"-DEIGEN_FAST_MATH=1\")\nei_add_test(unalignedassert)\nei_add_test(vectorization_logic)\nei_add_test(basicstuff)\nei_add_test(constructor)\nei_add_test(linearstructure)\nei_add_test(integer_types)\nei_add_test(unalignedcount)\nif(NOT EIGEN_TEST_NO_EXCEPTIONS AND NOT EIGEN_TEST_OPENMP)\n  ei_add_test(exceptions)\nendif()\nei_add_test(redux)\nei_add_test(visitor)\nei_add_test(block)\nei_add_test(corners)\nei_add_test(symbolic_index)\nei_add_test(indexed_view)\nei_add_test(reshape)\nei_add_test(swap)\nei_add_test(resize)\nei_add_test(conservative_resize)\nei_add_test(product_small)\nei_add_test(product_large)\nei_add_test(product_extra)\nei_add_test(diagonalmatrices)\nei_add_test(adjoint)\nei_add_test(diagonal)\nei_add_test(miscmatrices)\nei_add_test(commainitializer)\nei_add_test(smallvectors)\nei_add_test(mapped_matrix)\nei_add_test(mapstride)\nei_add_test(mapstaticmethods)\nei_add_test(array_cwise)\nei_add_test(array_for_matrix)\nei_add_test(array_replicate)\nei_add_test(array_reverse)\nei_add_test(ref)\nei_add_test(is_same_dense)\nei_add_test(triangular)\nei_add_test(selfadjoint)\nei_add_test(product_selfadjoint)\nei_add_test(product_symm)\nei_add_test(product_syrk)\nei_add_test(product_trmv)\nei_add_test(product_trmm)\nei_add_test(product_trsolve)\nei_add_test(product_mmtr)\nei_add_test(product_notemporary)\nei_add_test(stable_norm)\nei_add_test(permutationmatrices)\nei_add_test(bandmatrix)\nei_add_test(cholesky)\nei_add_test(lu)\nei_add_test(determinant)\nei_add_test(inverse)\nei_add_test(qr)\nei_add_test(qr_colpivoting)\nei_add_test(qr_fullpivoting)\nei_add_test(upperbidiagonalization)\nei_add_test(hessenberg)\nei_add_test(schur_real)\nei_add_test(schur_complex)\nei_add_test(eigensolver_selfadjoint)\nei_add_test(eigensolver_generic)\nei_add_test(eigensolver_complex)\nei_add_test(real_qz)\nei_add_test(eigensolver_generalized_real)\nei_add_test(jacobi)\nei_add_test(jacobisvd)\nei_add_test(bdcsvd)\nei_add_test(householder)\nei_add_test(geo_orthomethods)\nei_add_test(geo_quaternion)\nei_add_test(geo_eulerangles)\nei_add_test(geo_parametrizedline)\nei_add_test(geo_alignedbox)\nei_add_test(geo_hyperplane)\nei_add_test(geo_transformations)\nei_add_test(geo_homogeneous)\nei_add_test(stdvector)\nei_add_test(stdvector_overload)\nei_add_test(stdlist)\nei_add_test(stdlist_overload)\nei_add_test(stddeque)\nei_add_test(stddeque_overload)\nei_add_test(sparse_basic)\nei_add_test(sparse_block)\nei_add_test(sparse_vector)\nei_add_test(sparse_product)\nei_add_test(sparse_ref)\nei_add_test(sparse_solvers)\nei_add_test(sparse_permutations)\nei_add_test(simplicial_cholesky)\nei_add_test(conjugate_gradient)\nei_add_test(incomplete_cholesky)\nei_add_test(bicgstab)\nei_add_test(lscg)\nei_add_test(sparselu)\nei_add_test(sparseqr)\nei_add_test(umeyama)\nei_add_test(nesting_ops \"${CMAKE_CXX_FLAGS_DEBUG}\")\nei_add_test(nestbyvalue)\nei_add_test(zerosized)\nei_add_test(dontalign)\nei_add_test(evaluators)\nif(NOT EIGEN_TEST_NO_EXCEPTIONS)\n  ei_add_test(sizeoverflow)\nendif()\nei_add_test(prec_inverse_4x4)\nei_add_test(vectorwiseop)\nei_add_test(special_numbers)\nei_add_test(rvalue_types)\nei_add_test(dense_storage)\nei_add_test(ctorleak)\nei_add_test(mpl2only)\nei_add_test(inplace_decomposition)\nei_add_test(half_float)\nei_add_test(bfloat16_float)\nei_add_test(array_of_string)\nei_add_test(num_dimensions)\nei_add_test(stl_iterators)\nei_add_test(blasutil)\nif(EIGEN_TEST_CXX11)\n  ei_add_test(initializer_list_construction)\n  ei_add_test(diagonal_matrix_variadic_ctor)\nendif()\n\nadd_executable(bug1213 bug1213.cpp bug1213_main.cpp)\n\ncheck_cxx_compiler_flag(\"-ffast-math\" COMPILER_SUPPORT_FASTMATH)\nif(COMPILER_SUPPORT_FASTMATH)\n  set(EIGEN_FASTMATH_FLAGS \"-ffast-math\")\nelse()\n  check_cxx_compiler_flag(\"/fp:fast\" COMPILER_SUPPORT_FPFAST)\n  if(COMPILER_SUPPORT_FPFAST)\n    set(EIGEN_FASTMATH_FLAGS \"/fp:fast\")\n  endif()\nendif()\n\nei_add_test(fastmath \" ${EIGEN_FASTMATH_FLAGS} \")\n\n# # ei_add_test(denseLM)\n\nif(QT4_FOUND)\n  ei_add_test(qtvector \"\" \"${QT_QTCORE_LIBRARY}\")\nendif()\n\nif(UMFPACK_FOUND)\n  ei_add_test(umfpack_support \"\" \"${UMFPACK_ALL_LIBS}\")\nendif()\n\nif(KLU_FOUND OR SuiteSparse_FOUND)\n  ei_add_test(klu_support \"\" \"${KLU_ALL_LIBS}\")\nendif()\n\nif(SUPERLU_FOUND)\n  ei_add_test(superlu_support \"\" \"${SUPERLU_ALL_LIBS}\")\nendif()\n\nif(CHOLMOD_FOUND)\n  ei_add_test(cholmod_support \"\" \"${CHOLMOD_ALL_LIBS}\")\nendif()\n\nif(PARDISO_FOUND)\n  ei_add_test(pardiso_support \"\" \"${PARDISO_ALL_LIBS}\")\nendif()\n\nif(PASTIX_FOUND AND (SCOTCH_FOUND OR METIS_FOUND))\n  ei_add_test(pastix_support \"\" \"${PASTIX_ALL_LIBS}\")\nendif()\n\nif(SPQR_FOUND AND CHOLMOD_FOUND)\n  ei_add_test(spqr_support \"\" \"${SPQR_ALL_LIBS}\")\nendif()\n\nif(METIS_FOUND)\nei_add_test(metis_support \"\" \"${METIS_LIBRARIES}\")\nendif()\n\nstring(TOLOWER \"${CMAKE_CXX_COMPILER}\" cmake_cxx_compiler_tolower)\nif(cmake_cxx_compiler_tolower MATCHES \"qcc\")\n  set(CXX_IS_QCC \"ON\")\nendif()\n\nei_add_property(EIGEN_TESTING_SUMMARY \"CXX:               ${CMAKE_CXX_COMPILER}\\n\")\nif(CMAKE_COMPILER_IS_GNUCXX AND NOT CXX_IS_QCC)\n  execute_process(COMMAND ${CMAKE_CXX_COMPILER} --version COMMAND head -n 1 OUTPUT_VARIABLE EIGEN_CXX_VERSION_STRING OUTPUT_STRIP_TRAILING_WHITESPACE)\n  ei_add_property(EIGEN_TESTING_SUMMARY \"CXX_VERSION:       ${EIGEN_CXX_VERSION_STRING}\\n\")\nendif()\nei_add_property(EIGEN_TESTING_SUMMARY \"CXX_FLAGS:         ${CMAKE_CXX_FLAGS}\\n\")\nif (EIGEN_TEST_CUSTOM_CXX_FLAGS)\n  ei_add_property(EIGEN_TESTING_SUMMARY \"Custom CXX flags:  ${EIGEN_TEST_CUSTOM_CXX_FLAGS}\\n\")\nendif()\nei_add_property(EIGEN_TESTING_SUMMARY \"Sparse lib flags:  ${SPARSE_LIBS}\\n\")\n\noption(EIGEN_TEST_EIGEN2 \"Run whole Eigen2 test suite against EIGEN2_SUPPORT\" OFF)\nmark_as_advanced(EIGEN_TEST_EIGEN2)\nif(EIGEN_TEST_EIGEN2)\n  message(WARNING \"The Eigen2 test suite has been removed\")\nendif()\n\n# boost MP unit test\nfind_package(Boost 1.53.0)\nif(Boost_FOUND)\n  include_directories(${Boost_INCLUDE_DIRS})\n  ei_add_test(boostmultiprec \"\" \"${Boost_LIBRARIES}\")\n  ei_add_property(EIGEN_TESTED_BACKENDS \"Boost.Multiprecision, \")\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS \"Boost.Multiprecision, \")\nendif()\n\n\n# CUDA unit tests\noption(EIGEN_TEST_CUDA \"Enable CUDA support in unit tests\" OFF)\noption(EIGEN_TEST_CUDA_CLANG \"Use clang instead of nvcc to compile the CUDA tests\" OFF)\n\nif(EIGEN_TEST_CUDA_CLANG AND NOT CMAKE_CXX_COMPILER MATCHES \"clang\")\n  message(WARNING \"EIGEN_TEST_CUDA_CLANG is set, but CMAKE_CXX_COMPILER does not appear to be clang.\")\nendif()\n\nif(EIGEN_TEST_CUDA)\n\nfind_package(CUDA 5.0)\nif(CUDA_FOUND)\n  \n  set(CUDA_PROPAGATE_HOST_FLAGS OFF)\n  \n  set(EIGEN_CUDA_RELAXED_CONSTEXPR \"--expt-relaxed-constexpr\")\n  if (${CUDA_VERSION} STREQUAL \"7.0\")\n    set(EIGEN_CUDA_RELAXED_CONSTEXPR \"--relaxed-constexpr\")\n  endif()\n  \n  if(\"${CMAKE_CXX_COMPILER_ID}\" STREQUAL \"Clang\") \n    set(CUDA_NVCC_FLAGS \"-ccbin ${CMAKE_C_COMPILER}\" CACHE STRING \"nvcc flags\" FORCE)\n  endif()\n  if(EIGEN_TEST_CUDA_CLANG)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -std=c++11\")\n    string(APPEND CMAKE_CXX_FLAGS \" --cuda-path=${CUDA_TOOLKIT_ROOT_DIR}\")\n    foreach(GPU IN LISTS EIGEN_CUDA_COMPUTE_ARCH)\n      string(APPEND CMAKE_CXX_FLAGS \" --cuda-gpu-arch=sm_${GPU}\")\n    endforeach()\n  else()\n    foreach(GPU IN LISTS EIGEN_CUDA_COMPUTE_ARCH)\n      string(APPEND CUDA_NVCC_FLAGS \" -gencode arch=compute_${GPU},code=sm_${GPU}\")\n    endforeach()\n  endif()\n  string(APPEND CUDA_NVCC_FLAGS \" ${EIGEN_CUDA_RELAXED_CONSTEXPR}\")\n  set(EIGEN_ADD_TEST_FILENAME_EXTENSION  \"cu\")\n  \n  ei_add_test(gpu_basic)\n  \n  unset(EIGEN_ADD_TEST_FILENAME_EXTENSION)\n\nendif()\n\nendif()\n\n\n# HIP unit tests\noption(EIGEN_TEST_HIP \"Add HIP support.\" OFF)\nif (EIGEN_TEST_HIP)\n\n  set(HIP_PATH \"/opt/rocm/hip\" CACHE STRING \"Path to the HIP installation.\")\n\n  if (EXISTS ${HIP_PATH})\n    \n    list(APPEND CMAKE_MODULE_PATH ${HIP_PATH}/cmake) \n\n    find_package(HIP REQUIRED)\n    if (HIP_FOUND)\n\n      execute_process(COMMAND ${HIP_PATH}/bin/hipconfig --platform OUTPUT_VARIABLE HIP_PLATFORM)\n\n      if ((${HIP_PLATFORM} STREQUAL \"hcc\") OR (${HIP_PLATFORM} STREQUAL \"amd\"))\n\n\tinclude_directories(${HIP_PATH}/include)\n\n\tset(EIGEN_ADD_TEST_FILENAME_EXTENSION  \"cu\")\n\tei_add_test(gpu_basic)\n\tunset(EIGEN_ADD_TEST_FILENAME_EXTENSION)\n\t\n      elseif ((${HIP_PLATFORM} STREQUAL \"nvcc\") OR (${HIP_PLATFORM} STREQUAL \"nvidia\"))\n\tmessage(FATAL_ERROR \"HIP_PLATFORM = nvcc is not supported within Eigen\")\n      else ()\n\tmessage(FATAL_ERROR \"Unknown HIP_PLATFORM = ${HIP_PLATFORM}\")\n      endif() \n    endif()\n  else ()\n    message(FATAL_ERROR \"EIGEN_TEST_HIP is ON, but the specified HIP_PATH (${HIP_PATH}) does not exist\")\n  endif()\nendif()\n\ncmake_dependent_option(EIGEN_TEST_BUILD_DOCUMENTATION \"Test building the doxygen documentation\" OFF \"EIGEN_BUILD_DOC\" OFF)\nif(EIGEN_TEST_BUILD_DOCUMENTATION)\n  add_dependencies(buildtests doc)\nendif()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/MovableScalar.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2020 Sebastien Boisvert <seb@boisvert.info>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MISC_MOVABLE_SCALAR_H\n#define EIGEN_MISC_MOVABLE_SCALAR_H\n\n#include <vector>\n\nnamespace Eigen\n{\ntemplate <typename Scalar, typename Base = std::vector<Scalar>>\nstruct MovableScalar : public Base\n{\n  MovableScalar() = default;\n  ~MovableScalar() = default;\n  MovableScalar(const MovableScalar&) = default;\n  MovableScalar(MovableScalar&& other) = default;\n  MovableScalar& operator=(const MovableScalar&) = default;\n  MovableScalar& operator=(MovableScalar&& other) = default;\n  MovableScalar(Scalar scalar) : Base(100, scalar) {}\n\n  operator Scalar() const { return this->size() > 0 ? this->back() : Scalar(); }\n};\n\ntemplate<> struct NumTraits<MovableScalar<float>> : GenericNumTraits<float> {};\n}\n\n#endif\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/adjoint.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_STATIC_ASSERT\n\n#include \"main.h\"\n\ntemplate<bool IsInteger> struct adjoint_specific;\n\ntemplate<> struct adjoint_specific<true> {\n  template<typename Vec, typename Mat, typename Scalar>\n  static void run(const Vec& v1, const Vec& v2, Vec& v3, const Mat& square, Scalar s1, Scalar s2) {\n    VERIFY(test_isApproxWithRef((s1 * v1 + s2 * v2).dot(v3),     numext::conj(s1) * v1.dot(v3) + numext::conj(s2) * v2.dot(v3), 0));\n    VERIFY(test_isApproxWithRef(v3.dot(s1 * v1 + s2 * v2),       s1*v3.dot(v1)+s2*v3.dot(v2), 0));\n    \n    // check compatibility of dot and adjoint\n    VERIFY(test_isApproxWithRef(v1.dot(square * v2), (square.adjoint() * v1).dot(v2), 0));\n  }\n};\n\ntemplate<> struct adjoint_specific<false> {\n  template<typename Vec, typename Mat, typename Scalar>\n  static void run(const Vec& v1, const Vec& v2, Vec& v3, const Mat& square, Scalar s1, Scalar s2) {\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    using std::abs;\n    \n    RealScalar ref = NumTraits<Scalar>::IsInteger ? RealScalar(0) : (std::max)((s1 * v1 + s2 * v2).norm(),v3.norm());\n    VERIFY(test_isApproxWithRef((s1 * v1 + s2 * v2).dot(v3),     numext::conj(s1) * v1.dot(v3) + numext::conj(s2) * v2.dot(v3), ref));\n    VERIFY(test_isApproxWithRef(v3.dot(s1 * v1 + s2 * v2),       s1*v3.dot(v1)+s2*v3.dot(v2), ref));\n  \n    VERIFY_IS_APPROX(v1.squaredNorm(),                v1.norm() * v1.norm());\n    // check normalized() and normalize()\n    VERIFY_IS_APPROX(v1, v1.norm() * v1.normalized());\n    v3 = v1;\n    v3.normalize();\n    VERIFY_IS_APPROX(v1, v1.norm() * v3);\n    VERIFY_IS_APPROX(v3, v1.normalized());\n    VERIFY_IS_APPROX(v3.norm(), RealScalar(1));\n\n    // check null inputs\n    VERIFY_IS_APPROX((v1*0).normalized(), (v1*0));\n#if (!EIGEN_ARCH_i386) || defined(EIGEN_VECTORIZE)\n    RealScalar very_small = (std::numeric_limits<RealScalar>::min)();\n    VERIFY( (v1*very_small).norm() == 0 );\n    VERIFY_IS_APPROX((v1*very_small).normalized(), (v1*very_small));\n    v3 = v1*very_small;\n    v3.normalize();\n    VERIFY_IS_APPROX(v3, (v1*very_small));\n#endif\n    \n    // check compatibility of dot and adjoint\n    ref = NumTraits<Scalar>::IsInteger ? 0 : (std::max)((std::max)(v1.norm(),v2.norm()),(std::max)((square * v2).norm(),(square.adjoint() * v1).norm()));\n    VERIFY(internal::isMuchSmallerThan(abs(v1.dot(square * v2) - (square.adjoint() * v1).dot(v2)), ref, test_precision<Scalar>()));\n    \n    // check that Random().normalized() works: tricky as the random xpr must be evaluated by\n    // normalized() in order to produce a consistent result.\n    VERIFY_IS_APPROX(Vec::Random(v1.size()).normalized().norm(), RealScalar(1));\n  }\n};\n\ntemplate<typename MatrixType> void adjoint(const MatrixType& m)\n{\n  /* this test covers the following files:\n     Transpose.h Conjugate.h Dot.h\n  */\n  using std::abs;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> SquareMatrixType;\n  const Index PacketSize = internal::packet_traits<Scalar>::size;\n  \n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols),\n             square = SquareMatrixType::Random(rows, rows);\n  VectorType v1 = VectorType::Random(rows),\n             v2 = VectorType::Random(rows),\n             v3 = VectorType::Random(rows),\n             vzero = VectorType::Zero(rows);\n\n  Scalar s1 = internal::random<Scalar>(),\n         s2 = internal::random<Scalar>();\n\n  // check basic compatibility of adjoint, transpose, conjugate\n  VERIFY_IS_APPROX(m1.transpose().conjugate().adjoint(),    m1);\n  VERIFY_IS_APPROX(m1.adjoint().conjugate().transpose(),    m1);\n\n  // check multiplicative behavior\n  VERIFY_IS_APPROX((m1.adjoint() * m2).adjoint(),           m2.adjoint() * m1);\n  VERIFY_IS_APPROX((s1 * m1).adjoint(),                     numext::conj(s1) * m1.adjoint());\n\n  // check basic properties of dot, squaredNorm\n  VERIFY_IS_APPROX(numext::conj(v1.dot(v2)),               v2.dot(v1));\n  VERIFY_IS_APPROX(numext::real(v1.dot(v1)),               v1.squaredNorm());\n  \n  adjoint_specific<NumTraits<Scalar>::IsInteger>::run(v1, v2, v3, square, s1, s2);\n  \n  VERIFY_IS_MUCH_SMALLER_THAN(abs(vzero.dot(v1)),  static_cast<RealScalar>(1));\n  \n  // like in testBasicStuff, test operator() to check const-qualification\n  Index r = internal::random<Index>(0, rows-1),\n      c = internal::random<Index>(0, cols-1);\n  VERIFY_IS_APPROX(m1.conjugate()(r,c), numext::conj(m1(r,c)));\n  VERIFY_IS_APPROX(m1.adjoint()(c,r), numext::conj(m1(r,c)));\n\n  // check inplace transpose\n  m3 = m1;\n  m3.transposeInPlace();\n  VERIFY_IS_APPROX(m3,m1.transpose());\n  m3.transposeInPlace();\n  VERIFY_IS_APPROX(m3,m1);\n  \n  if(PacketSize<m3.rows() && PacketSize<m3.cols())\n  {\n    m3 = m1;\n    Index i = internal::random<Index>(0,m3.rows()-PacketSize);\n    Index j = internal::random<Index>(0,m3.cols()-PacketSize);\n    m3.template block<PacketSize,PacketSize>(i,j).transposeInPlace();\n    VERIFY_IS_APPROX( (m3.template block<PacketSize,PacketSize>(i,j)), (m1.template block<PacketSize,PacketSize>(i,j).transpose()) );\n    m3.template block<PacketSize,PacketSize>(i,j).transposeInPlace();\n    VERIFY_IS_APPROX(m3,m1);\n  }\n\n  // check inplace adjoint\n  m3 = m1;\n  m3.adjointInPlace();\n  VERIFY_IS_APPROX(m3,m1.adjoint());\n  m3.transposeInPlace();\n  VERIFY_IS_APPROX(m3,m1.conjugate());\n\n  // check mixed dot product\n  typedef Matrix<RealScalar, MatrixType::RowsAtCompileTime, 1> RealVectorType;\n  RealVectorType rv1 = RealVectorType::Random(rows);\n  VERIFY_IS_APPROX(v1.dot(rv1.template cast<Scalar>()), v1.dot(rv1));\n  VERIFY_IS_APPROX(rv1.template cast<Scalar>().dot(v1), rv1.dot(v1));\n\n  VERIFY( is_same_type(m1,m1.template conjugateIf<false>()) );\n  VERIFY( is_same_type(m1.conjugate(),m1.template conjugateIf<true>()) );\n}\n\ntemplate<int>\nvoid adjoint_extra()\n{\n  MatrixXcf a(10,10), b(10,10);\n  VERIFY_RAISES_ASSERT(a = a.transpose());\n  VERIFY_RAISES_ASSERT(a = a.transpose() + b);\n  VERIFY_RAISES_ASSERT(a = b + a.transpose());\n  VERIFY_RAISES_ASSERT(a = a.conjugate().transpose());\n  VERIFY_RAISES_ASSERT(a = a.adjoint());\n  VERIFY_RAISES_ASSERT(a = a.adjoint() + b);\n  VERIFY_RAISES_ASSERT(a = b + a.adjoint());\n\n  // no assertion should be triggered for these cases:\n  a.transpose() = a.transpose();\n  a.transpose() += a.transpose();\n  a.transpose() += a.transpose() + b;\n  a.transpose() = a.adjoint();\n  a.transpose() += a.adjoint();\n  a.transpose() += a.adjoint() + b;\n\n  // regression tests for check_for_aliasing\n  MatrixXd c(10,10);\n  c = 1.0 * MatrixXd::Ones(10,10) + c;\n  c = MatrixXd::Ones(10,10) * 1.0 + c;\n  c = c + MatrixXd::Ones(10,10) .cwiseProduct( MatrixXd::Zero(10,10) );\n  c = MatrixXd::Ones(10,10) * MatrixXd::Zero(10,10);\n\n  // regression for bug 1646\n  for (int j = 0; j < 10; ++j) {\n    c.col(j).head(j) = c.row(j).head(j);\n  }\n\n  for (int j = 0; j < 10; ++j) {\n    c.col(j) = c.row(j);\n  }\n\n  a.conservativeResize(1,1);\n  a = a.transpose();\n\n  a.conservativeResize(0,0);\n  a = a.transpose();\n}\n\nEIGEN_DECLARE_TEST(adjoint)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( adjoint(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( adjoint(Matrix3d()) );\n    CALL_SUBTEST_3( adjoint(Matrix4f()) );\n    \n    CALL_SUBTEST_4( adjoint(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2), internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))) );\n    CALL_SUBTEST_5( adjoint(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( adjoint(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    \n    // Complement for 128 bits vectorization:\n    CALL_SUBTEST_8( adjoint(Matrix2d()) );\n    CALL_SUBTEST_9( adjoint(Matrix<int,4,4>()) );\n    \n    // 256 bits vectorization:\n    CALL_SUBTEST_10( adjoint(Matrix<float,8,8>()) );\n    CALL_SUBTEST_11( adjoint(Matrix<double,4,4>()) );\n    CALL_SUBTEST_12( adjoint(Matrix<int,8,8>()) );\n  }\n  // test a large static matrix only once\n  CALL_SUBTEST_7( adjoint(Matrix<float, 100, 100>()) );\n\n  CALL_SUBTEST_13( adjoint_extra<0>() );\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/array_cwise.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n\n// Test the corner cases of pow(x, y) for real types.\ntemplate<typename Scalar>\nvoid pow_test() {\n  const Scalar zero = Scalar(0);\n  const Scalar eps = Eigen::NumTraits<Scalar>::epsilon();\n  const Scalar one = Scalar(1);\n  const Scalar two = Scalar(2);\n  const Scalar three = Scalar(3);\n  const Scalar sqrt_half = Scalar(std::sqrt(0.5));\n  const Scalar sqrt2 = Scalar(std::sqrt(2));\n  const Scalar inf = Eigen::NumTraits<Scalar>::infinity();\n  const Scalar nan = Eigen::NumTraits<Scalar>::quiet_NaN();\n  const Scalar denorm_min = std::numeric_limits<Scalar>::denorm_min();\n  const Scalar min = (std::numeric_limits<Scalar>::min)();\n  const Scalar max = (std::numeric_limits<Scalar>::max)();\n  const Scalar max_exp = (static_cast<Scalar>(int(Eigen::NumTraits<Scalar>::max_exponent())) * Scalar(EIGEN_LN2)) / eps;\n\n  const static Scalar abs_vals[] = {zero,\n                                    denorm_min,\n                                    min,\n                                    eps,\n                                    sqrt_half,\n                                    one,\n                                    sqrt2,\n                                    two,\n                                    three,\n                                    max_exp,\n                                    max,\n                                    inf,\n                                    nan};\n  const int abs_cases = 13;\n  const int num_cases = 2*abs_cases * 2*abs_cases;\n  // Repeat the same value to make sure we hit the vectorized path.\n  const int num_repeats = 32;\n  Array<Scalar, Dynamic, Dynamic> x(num_repeats, num_cases);\n  Array<Scalar, Dynamic, Dynamic> y(num_repeats, num_cases);\n  int count = 0;\n  for (int i = 0; i < abs_cases; ++i) {\n    const Scalar abs_x = abs_vals[i];\n    for (int sign_x = 0; sign_x < 2; ++sign_x) {\n      Scalar x_case = sign_x == 0 ? -abs_x : abs_x;\n      for (int j = 0; j < abs_cases; ++j) {\n        const Scalar abs_y = abs_vals[j];\n        for (int sign_y = 0; sign_y < 2; ++sign_y) {\n          Scalar y_case = sign_y == 0 ? -abs_y : abs_y;\n          for (int repeat = 0; repeat < num_repeats; ++repeat) {\n            x(repeat, count) = x_case;\n            y(repeat, count) = y_case;\n          }\n          ++count;\n        }\n      }\n    }\n  }\n\n  Array<Scalar, Dynamic, Dynamic> actual = x.pow(y);\n  const Scalar tol = test_precision<Scalar>();\n  bool all_pass = true;\n  for (int i = 0; i < 1; ++i) {\n    for (int j = 0; j < num_cases; ++j) {\n      Scalar e = static_cast<Scalar>(std::pow(x(i,j), y(i,j)));\n      Scalar a = actual(i, j);\n      bool fail = !(a==e) && !internal::isApprox(a, e, tol) && !((numext::isnan)(a) && (numext::isnan)(e));\n      all_pass &= !fail;\n      if (fail) {\n        std::cout << \"pow(\" << x(i,j) << \",\" << y(i,j) << \")   =   \" << a << \" !=  \" << e << std::endl;\n      }\n    }\n  }\n  VERIFY(all_pass);\n}\n\ntemplate<typename ArrayType> void array(const ArrayType& m)\n{\n  typedef typename ArrayType::Scalar Scalar;\n  typedef typename ArrayType::RealScalar RealScalar;\n  typedef Array<Scalar, ArrayType::RowsAtCompileTime, 1> ColVectorType;\n  typedef Array<Scalar, 1, ArrayType::ColsAtCompileTime> RowVectorType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  ArrayType m1 = ArrayType::Random(rows, cols),\n             m2 = ArrayType::Random(rows, cols),\n             m3(rows, cols);\n  ArrayType m4 = m1; // copy constructor\n  VERIFY_IS_APPROX(m1, m4);\n\n  ColVectorType cv1 = ColVectorType::Random(rows);\n  RowVectorType rv1 = RowVectorType::Random(cols);\n\n  Scalar  s1 = internal::random<Scalar>(),\n          s2 = internal::random<Scalar>();\n\n  // scalar addition\n  VERIFY_IS_APPROX(m1 + s1, s1 + m1);\n  VERIFY_IS_APPROX(m1 + s1, ArrayType::Constant(rows,cols,s1) + m1);\n  VERIFY_IS_APPROX(s1 - m1, (-m1)+s1 );\n  VERIFY_IS_APPROX(m1 - s1, m1 - ArrayType::Constant(rows,cols,s1));\n  VERIFY_IS_APPROX(s1 - m1, ArrayType::Constant(rows,cols,s1) - m1);\n  VERIFY_IS_APPROX((m1*Scalar(2)) - s2, (m1+m1) - ArrayType::Constant(rows,cols,s2) );\n  m3 = m1;\n  m3 += s2;\n  VERIFY_IS_APPROX(m3, m1 + s2);\n  m3 = m1;\n  m3 -= s1;\n  VERIFY_IS_APPROX(m3, m1 - s1);\n\n  // scalar operators via Maps\n  m3 = m1;\n  ArrayType::Map(m1.data(), m1.rows(), m1.cols()) -= ArrayType::Map(m2.data(), m2.rows(), m2.cols());\n  VERIFY_IS_APPROX(m1, m3 - m2);\n\n  m3 = m1;\n  ArrayType::Map(m1.data(), m1.rows(), m1.cols()) += ArrayType::Map(m2.data(), m2.rows(), m2.cols());\n  VERIFY_IS_APPROX(m1, m3 + m2);\n\n  m3 = m1;\n  ArrayType::Map(m1.data(), m1.rows(), m1.cols()) *= ArrayType::Map(m2.data(), m2.rows(), m2.cols());\n  VERIFY_IS_APPROX(m1, m3 * m2);\n\n  m3 = m1;\n  m2 = ArrayType::Random(rows,cols);\n  m2 = (m2==0).select(1,m2);\n  ArrayType::Map(m1.data(), m1.rows(), m1.cols()) /= ArrayType::Map(m2.data(), m2.rows(), m2.cols());\n  VERIFY_IS_APPROX(m1, m3 / m2);\n\n  // reductions\n  VERIFY_IS_APPROX(m1.abs().colwise().sum().sum(), m1.abs().sum());\n  VERIFY_IS_APPROX(m1.abs().rowwise().sum().sum(), m1.abs().sum());\n  using std::abs;\n  VERIFY_IS_MUCH_SMALLER_THAN(abs(m1.colwise().sum().sum() - m1.sum()), m1.abs().sum());\n  VERIFY_IS_MUCH_SMALLER_THAN(abs(m1.rowwise().sum().sum() - m1.sum()), m1.abs().sum());\n  if (!internal::isMuchSmallerThan(abs(m1.sum() - (m1+m2).sum()), m1.abs().sum(), test_precision<Scalar>()))\n      VERIFY_IS_NOT_APPROX(((m1+m2).rowwise().sum()).sum(), m1.sum());\n  VERIFY_IS_APPROX(m1.colwise().sum(), m1.colwise().redux(internal::scalar_sum_op<Scalar,Scalar>()));\n\n  // vector-wise ops\n  m3 = m1;\n  VERIFY_IS_APPROX(m3.colwise() += cv1, m1.colwise() + cv1);\n  m3 = m1;\n  VERIFY_IS_APPROX(m3.colwise() -= cv1, m1.colwise() - cv1);\n  m3 = m1;\n  VERIFY_IS_APPROX(m3.rowwise() += rv1, m1.rowwise() + rv1);\n  m3 = m1;\n  VERIFY_IS_APPROX(m3.rowwise() -= rv1, m1.rowwise() - rv1);\n\n  // Conversion from scalar\n  VERIFY_IS_APPROX((m3 = s1), ArrayType::Constant(rows,cols,s1));\n  VERIFY_IS_APPROX((m3 = 1),  ArrayType::Constant(rows,cols,1));\n  VERIFY_IS_APPROX((m3.topLeftCorner(rows,cols) = 1),  ArrayType::Constant(rows,cols,1));\n  typedef Array<Scalar,\n                ArrayType::RowsAtCompileTime==Dynamic?2:ArrayType::RowsAtCompileTime,\n                ArrayType::ColsAtCompileTime==Dynamic?2:ArrayType::ColsAtCompileTime,\n                ArrayType::Options> FixedArrayType;\n  {\n    FixedArrayType f1(s1);\n    VERIFY_IS_APPROX(f1, FixedArrayType::Constant(s1));\n    FixedArrayType f2(numext::real(s1));\n    VERIFY_IS_APPROX(f2, FixedArrayType::Constant(numext::real(s1)));\n    FixedArrayType f3((int)100*numext::real(s1));\n    VERIFY_IS_APPROX(f3, FixedArrayType::Constant((int)100*numext::real(s1)));\n    f1.setRandom();\n    FixedArrayType f4(f1.data());\n    VERIFY_IS_APPROX(f4, f1);\n  }\n  #if EIGEN_HAS_CXX11\n  {\n    FixedArrayType f1{s1};\n    VERIFY_IS_APPROX(f1, FixedArrayType::Constant(s1));\n    FixedArrayType f2{numext::real(s1)};\n    VERIFY_IS_APPROX(f2, FixedArrayType::Constant(numext::real(s1)));\n    FixedArrayType f3{(int)100*numext::real(s1)};\n    VERIFY_IS_APPROX(f3, FixedArrayType::Constant((int)100*numext::real(s1)));\n    f1.setRandom();\n    FixedArrayType f4{f1.data()};\n    VERIFY_IS_APPROX(f4, f1);\n  }\n  #endif\n\n  // pow\n  VERIFY_IS_APPROX(m1.pow(2), m1.square());\n  VERIFY_IS_APPROX(pow(m1,2), m1.square());\n  VERIFY_IS_APPROX(m1.pow(3), m1.cube());\n  VERIFY_IS_APPROX(pow(m1,3), m1.cube());\n  VERIFY_IS_APPROX((-m1).pow(3), -m1.cube());\n  VERIFY_IS_APPROX(pow(2*m1,3), 8*m1.cube());\n  ArrayType exponents = ArrayType::Constant(rows, cols, RealScalar(2));\n  VERIFY_IS_APPROX(Eigen::pow(m1,exponents), m1.square());\n  VERIFY_IS_APPROX(m1.pow(exponents), m1.square());\n  VERIFY_IS_APPROX(Eigen::pow(2*m1,exponents), 4*m1.square());\n  VERIFY_IS_APPROX((2*m1).pow(exponents), 4*m1.square());\n  VERIFY_IS_APPROX(Eigen::pow(m1,2*exponents), m1.square().square());\n  VERIFY_IS_APPROX(m1.pow(2*exponents), m1.square().square());\n  VERIFY_IS_APPROX(Eigen::pow(m1(0,0), exponents), ArrayType::Constant(rows,cols,m1(0,0)*m1(0,0)));\n\n  // Check possible conflicts with 1D ctor\n  typedef Array<Scalar, Dynamic, 1> OneDArrayType;\n  {\n    OneDArrayType o1(rows);\n    VERIFY(o1.size()==rows);\n    OneDArrayType o2(static_cast<int>(rows));\n    VERIFY(o2.size()==rows);\n  }\n  #if EIGEN_HAS_CXX11\n  {\n    OneDArrayType o1{rows};\n    VERIFY(o1.size()==rows);\n    OneDArrayType o4{int(rows)};\n    VERIFY(o4.size()==rows);\n  }\n  #endif\n  // Check possible conflicts with 2D ctor\n  typedef Array<Scalar, Dynamic, Dynamic> TwoDArrayType;\n  typedef Array<Scalar, 2, 1> ArrayType2;\n  {\n    TwoDArrayType o1(rows,cols);\n    VERIFY(o1.rows()==rows);\n    VERIFY(o1.cols()==cols);\n    TwoDArrayType o2(static_cast<int>(rows),static_cast<int>(cols));\n    VERIFY(o2.rows()==rows);\n    VERIFY(o2.cols()==cols);\n\n    ArrayType2 o3(rows,cols);\n    VERIFY(o3(0)==Scalar(rows) && o3(1)==Scalar(cols));\n    ArrayType2 o4(static_cast<int>(rows),static_cast<int>(cols));\n    VERIFY(o4(0)==Scalar(rows) && o4(1)==Scalar(cols));\n  }\n  #if EIGEN_HAS_CXX11\n  {\n    TwoDArrayType o1{rows,cols};\n    VERIFY(o1.rows()==rows);\n    VERIFY(o1.cols()==cols);\n    TwoDArrayType o2{int(rows),int(cols)};\n    VERIFY(o2.rows()==rows);\n    VERIFY(o2.cols()==cols);\n\n    ArrayType2 o3{rows,cols};\n    VERIFY(o3(0)==Scalar(rows) && o3(1)==Scalar(cols));\n    ArrayType2 o4{int(rows),int(cols)};\n    VERIFY(o4(0)==Scalar(rows) && o4(1)==Scalar(cols));\n  }\n  #endif\n}\n\ntemplate<typename ArrayType> void comparisons(const ArrayType& m)\n{\n  using std::abs;\n  typedef typename ArrayType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  Index r = internal::random<Index>(0, rows-1),\n        c = internal::random<Index>(0, cols-1);\n\n  ArrayType m1 = ArrayType::Random(rows, cols),\n            m2 = ArrayType::Random(rows, cols),\n            m3(rows, cols),\n            m4 = m1;\n\n  m4 = (m4.abs()==Scalar(0)).select(1,m4);\n\n  VERIFY(((m1 + Scalar(1)) > m1).all());\n  VERIFY(((m1 - Scalar(1)) < m1).all());\n  if (rows*cols>1)\n  {\n    m3 = m1;\n    m3(r,c) += 1;\n    VERIFY(! (m1 < m3).all() );\n    VERIFY(! (m1 > m3).all() );\n  }\n  VERIFY(!(m1 > m2 && m1 < m2).any());\n  VERIFY((m1 <= m2 || m1 >= m2).all());\n\n  // comparisons array to scalar\n  VERIFY( (m1 != (m1(r,c)+1) ).any() );\n  VERIFY( (m1 >  (m1(r,c)-1) ).any() );\n  VERIFY( (m1 <  (m1(r,c)+1) ).any() );\n  VERIFY( (m1 ==  m1(r,c)    ).any() );\n\n  // comparisons scalar to array\n  VERIFY( ( (m1(r,c)+1) != m1).any() );\n  VERIFY( ( (m1(r,c)-1) <  m1).any() );\n  VERIFY( ( (m1(r,c)+1) >  m1).any() );\n  VERIFY( (  m1(r,c)    == m1).any() );\n\n  // test Select\n  VERIFY_IS_APPROX( (m1<m2).select(m1,m2), m1.cwiseMin(m2) );\n  VERIFY_IS_APPROX( (m1>m2).select(m1,m2), m1.cwiseMax(m2) );\n  Scalar mid = (m1.cwiseAbs().minCoeff() + m1.cwiseAbs().maxCoeff())/Scalar(2);\n  for (int j=0; j<cols; ++j)\n  for (int i=0; i<rows; ++i)\n    m3(i,j) = abs(m1(i,j))<mid ? 0 : m1(i,j);\n  VERIFY_IS_APPROX( (m1.abs()<ArrayType::Constant(rows,cols,mid))\n                        .select(ArrayType::Zero(rows,cols),m1), m3);\n  // shorter versions:\n  VERIFY_IS_APPROX( (m1.abs()<ArrayType::Constant(rows,cols,mid))\n                        .select(0,m1), m3);\n  VERIFY_IS_APPROX( (m1.abs()>=ArrayType::Constant(rows,cols,mid))\n                        .select(m1,0), m3);\n  // even shorter version:\n  VERIFY_IS_APPROX( (m1.abs()<mid).select(0,m1), m3);\n\n  // count\n  VERIFY(((m1.abs()+1)>RealScalar(0.1)).count() == rows*cols);\n\n  // and/or\n  VERIFY( (m1<RealScalar(0) && m1>RealScalar(0)).count() == 0);\n  VERIFY( (m1<RealScalar(0) || m1>=RealScalar(0)).count() == rows*cols);\n  RealScalar a = m1.abs().mean();\n  VERIFY( (m1<-a || m1>a).count() == (m1.abs()>a).count());\n\n  typedef Array<Index, Dynamic, 1> ArrayOfIndices;\n\n  // TODO allows colwise/rowwise for array\n  VERIFY_IS_APPROX(((m1.abs()+1)>RealScalar(0.1)).colwise().count(), ArrayOfIndices::Constant(cols,rows).transpose());\n  VERIFY_IS_APPROX(((m1.abs()+1)>RealScalar(0.1)).rowwise().count(), ArrayOfIndices::Constant(rows, cols));\n}\n\ntemplate<typename ArrayType> void array_real(const ArrayType& m)\n{\n  using std::abs;\n  using std::sqrt;\n  typedef typename ArrayType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  ArrayType m1 = ArrayType::Random(rows, cols),\n            m2 = ArrayType::Random(rows, cols),\n            m3(rows, cols),\n            m4 = m1;\n\n  m4 = (m4.abs()==Scalar(0)).select(Scalar(1),m4);\n\n  Scalar  s1 = internal::random<Scalar>();\n\n  // these tests are mostly to check possible compilation issues with free-functions.\n  VERIFY_IS_APPROX(m1.sin(), sin(m1));\n  VERIFY_IS_APPROX(m1.cos(), cos(m1));\n  VERIFY_IS_APPROX(m1.tan(), tan(m1));\n  VERIFY_IS_APPROX(m1.asin(), asin(m1));\n  VERIFY_IS_APPROX(m1.acos(), acos(m1));\n  VERIFY_IS_APPROX(m1.atan(), atan(m1));\n  VERIFY_IS_APPROX(m1.sinh(), sinh(m1));\n  VERIFY_IS_APPROX(m1.cosh(), cosh(m1));\n  VERIFY_IS_APPROX(m1.tanh(), tanh(m1));\n#if EIGEN_HAS_CXX11_MATH\n  VERIFY_IS_APPROX(m1.tanh().atanh(), atanh(tanh(m1)));\n  VERIFY_IS_APPROX(m1.sinh().asinh(), asinh(sinh(m1)));\n  VERIFY_IS_APPROX(m1.cosh().acosh(), acosh(cosh(m1)));\n#endif\n  VERIFY_IS_APPROX(m1.logistic(), logistic(m1));\n\n  VERIFY_IS_APPROX(m1.arg(), arg(m1));\n  VERIFY_IS_APPROX(m1.round(), round(m1));\n  VERIFY_IS_APPROX(m1.rint(), rint(m1));\n  VERIFY_IS_APPROX(m1.floor(), floor(m1));\n  VERIFY_IS_APPROX(m1.ceil(), ceil(m1));\n  VERIFY((m1.isNaN() == (Eigen::isnan)(m1)).all());\n  VERIFY((m1.isInf() == (Eigen::isinf)(m1)).all());\n  VERIFY((m1.isFinite() == (Eigen::isfinite)(m1)).all());\n  VERIFY_IS_APPROX(m4.inverse(), inverse(m4));\n  VERIFY_IS_APPROX(m1.abs(), abs(m1));\n  VERIFY_IS_APPROX(m1.abs2(), abs2(m1));\n  VERIFY_IS_APPROX(m1.square(), square(m1));\n  VERIFY_IS_APPROX(m1.cube(), cube(m1));\n  VERIFY_IS_APPROX(cos(m1+RealScalar(3)*m2), cos((m1+RealScalar(3)*m2).eval()));\n  VERIFY_IS_APPROX(m1.sign(), sign(m1));\n  VERIFY((m1.sqrt().sign().isNaN() == (Eigen::isnan)(sign(sqrt(m1)))).all());\n\n  // avoid inf and NaNs so verification doesn't fail\n  m3 = m4.abs();\n  VERIFY_IS_APPROX(m3.sqrt(), sqrt(abs(m3)));\n  VERIFY_IS_APPROX(m3.rsqrt(), Scalar(1)/sqrt(abs(m3)));\n  VERIFY_IS_APPROX(rsqrt(m3), Scalar(1)/sqrt(abs(m3)));\n  VERIFY_IS_APPROX(m3.log(), log(m3));\n  VERIFY_IS_APPROX(m3.log1p(), log1p(m3));\n  VERIFY_IS_APPROX(m3.log10(), log10(m3));\n  VERIFY_IS_APPROX(m3.log2(), log2(m3));\n\n\n  VERIFY((!(m1>m2) == (m1<=m2)).all());\n\n  VERIFY_IS_APPROX(sin(m1.asin()), m1);\n  VERIFY_IS_APPROX(cos(m1.acos()), m1);\n  VERIFY_IS_APPROX(tan(m1.atan()), m1);\n  VERIFY_IS_APPROX(sinh(m1), Scalar(0.5)*(exp(m1)-exp(-m1)));\n  VERIFY_IS_APPROX(cosh(m1), Scalar(0.5)*(exp(m1)+exp(-m1)));\n  VERIFY_IS_APPROX(tanh(m1), (Scalar(0.5)*(exp(m1)-exp(-m1)))/(Scalar(0.5)*(exp(m1)+exp(-m1))));\n  VERIFY_IS_APPROX(logistic(m1), (Scalar(1)/(Scalar(1)+exp(-m1))));\n  VERIFY_IS_APPROX(arg(m1), ((m1<Scalar(0)).template cast<Scalar>())*Scalar(std::acos(Scalar(-1))));\n  VERIFY((round(m1) <= ceil(m1) && round(m1) >= floor(m1)).all());\n  VERIFY((rint(m1) <= ceil(m1) && rint(m1) >= floor(m1)).all());\n  VERIFY(((ceil(m1) - round(m1)) <= Scalar(0.5) || (round(m1) - floor(m1)) <= Scalar(0.5)).all());\n  VERIFY(((ceil(m1) - round(m1)) <= Scalar(1.0) && (round(m1) - floor(m1)) <= Scalar(1.0)).all());\n  VERIFY(((ceil(m1) - rint(m1)) <= Scalar(0.5) || (rint(m1) - floor(m1)) <= Scalar(0.5)).all());\n  VERIFY(((ceil(m1) - rint(m1)) <= Scalar(1.0) && (rint(m1) - floor(m1)) <= Scalar(1.0)).all());\n  VERIFY((Eigen::isnan)((m1*Scalar(0))/Scalar(0)).all());\n  VERIFY((Eigen::isinf)(m4/Scalar(0)).all());\n  VERIFY(((Eigen::isfinite)(m1) && (!(Eigen::isfinite)(m1*Scalar(0)/Scalar(0))) && (!(Eigen::isfinite)(m4/Scalar(0)))).all());\n  VERIFY_IS_APPROX(inverse(inverse(m4)),m4);\n  VERIFY((abs(m1) == m1 || abs(m1) == -m1).all());\n  VERIFY_IS_APPROX(m3, sqrt(abs2(m3)));\n  VERIFY_IS_APPROX(m1.absolute_difference(m2), (m1 > m2).select(m1 - m2, m2 - m1));\n  VERIFY_IS_APPROX( m1.sign(), -(-m1).sign() );\n  VERIFY_IS_APPROX( m1*m1.sign(),m1.abs());\n  VERIFY_IS_APPROX(m1.sign() * m1.abs(), m1);\n\n  VERIFY_IS_APPROX(numext::abs2(numext::real(m1)) + numext::abs2(numext::imag(m1)), numext::abs2(m1));\n  VERIFY_IS_APPROX(numext::abs2(Eigen::real(m1)) + numext::abs2(Eigen::imag(m1)), numext::abs2(m1));\n  if(!NumTraits<Scalar>::IsComplex)\n    VERIFY_IS_APPROX(numext::real(m1), m1);\n\n  // shift argument of logarithm so that it is not zero\n  Scalar smallNumber = NumTraits<Scalar>::dummy_precision();\n  VERIFY_IS_APPROX((m3 + smallNumber).log() , log(abs(m3) + smallNumber));\n  VERIFY_IS_APPROX((m3 + smallNumber + Scalar(1)).log() , log1p(abs(m3) + smallNumber));\n\n  VERIFY_IS_APPROX(m1.exp() * m2.exp(), exp(m1+m2));\n  VERIFY_IS_APPROX(m1.exp(), exp(m1));\n  VERIFY_IS_APPROX(m1.exp() / m2.exp(),(m1-m2).exp());\n\n  VERIFY_IS_APPROX(m1.expm1(), expm1(m1));\n  VERIFY_IS_APPROX((m3 + smallNumber).exp() - Scalar(1), expm1(abs(m3) + smallNumber));\n\n  VERIFY_IS_APPROX(m3.pow(RealScalar(0.5)), m3.sqrt());\n  VERIFY_IS_APPROX(pow(m3,RealScalar(0.5)), m3.sqrt());\n\n  VERIFY_IS_APPROX(m3.pow(RealScalar(-0.5)), m3.rsqrt());\n  VERIFY_IS_APPROX(pow(m3,RealScalar(-0.5)), m3.rsqrt());\n\n  // Avoid inf and NaN.\n  m3 = (m1.square()<NumTraits<Scalar>::epsilon()).select(Scalar(1),m3);\n  VERIFY_IS_APPROX(m3.pow(RealScalar(-2)), m3.square().inverse());\n  pow_test<Scalar>();\n\n  VERIFY_IS_APPROX(log10(m3), log(m3)/numext::log(Scalar(10)));\n  VERIFY_IS_APPROX(log2(m3), log(m3)/numext::log(Scalar(2)));\n\n  // scalar by array division\n  const RealScalar tiny = sqrt(std::numeric_limits<RealScalar>::epsilon());\n  s1 += Scalar(tiny);\n  m1 += ArrayType::Constant(rows,cols,Scalar(tiny));\n  VERIFY_IS_APPROX(s1/m1, s1 * m1.inverse());\n\n  // check inplace transpose\n  m3 = m1;\n  m3.transposeInPlace();\n  VERIFY_IS_APPROX(m3, m1.transpose());\n  m3.transposeInPlace();\n  VERIFY_IS_APPROX(m3, m1);\n}\n\ntemplate<typename ArrayType> void array_complex(const ArrayType& m)\n{\n  typedef typename ArrayType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  ArrayType m1 = ArrayType::Random(rows, cols),\n            m2(rows, cols),\n            m4 = m1;\n\n  m4.real() = (m4.real().abs()==RealScalar(0)).select(RealScalar(1),m4.real());\n  m4.imag() = (m4.imag().abs()==RealScalar(0)).select(RealScalar(1),m4.imag());\n\n  Array<RealScalar, -1, -1> m3(rows, cols);\n\n  for (Index i = 0; i < m.rows(); ++i)\n    for (Index j = 0; j < m.cols(); ++j)\n      m2(i,j) = sqrt(m1(i,j));\n\n  // these tests are mostly to check possible compilation issues with free-functions.\n  VERIFY_IS_APPROX(m1.sin(), sin(m1));\n  VERIFY_IS_APPROX(m1.cos(), cos(m1));\n  VERIFY_IS_APPROX(m1.tan(), tan(m1));\n  VERIFY_IS_APPROX(m1.sinh(), sinh(m1));\n  VERIFY_IS_APPROX(m1.cosh(), cosh(m1));\n  VERIFY_IS_APPROX(m1.tanh(), tanh(m1));\n  VERIFY_IS_APPROX(m1.logistic(), logistic(m1));\n  VERIFY_IS_APPROX(m1.arg(), arg(m1));\n  VERIFY((m1.isNaN() == (Eigen::isnan)(m1)).all());\n  VERIFY((m1.isInf() == (Eigen::isinf)(m1)).all());\n  VERIFY((m1.isFinite() == (Eigen::isfinite)(m1)).all());\n  VERIFY_IS_APPROX(m4.inverse(), inverse(m4));\n  VERIFY_IS_APPROX(m1.log(), log(m1));\n  VERIFY_IS_APPROX(m1.log10(), log10(m1));\n  VERIFY_IS_APPROX(m1.log2(), log2(m1));\n  VERIFY_IS_APPROX(m1.abs(), abs(m1));\n  VERIFY_IS_APPROX(m1.abs2(), abs2(m1));\n  VERIFY_IS_APPROX(m1.sqrt(), sqrt(m1));\n  VERIFY_IS_APPROX(m1.square(), square(m1));\n  VERIFY_IS_APPROX(m1.cube(), cube(m1));\n  VERIFY_IS_APPROX(cos(m1+RealScalar(3)*m2), cos((m1+RealScalar(3)*m2).eval()));\n  VERIFY_IS_APPROX(m1.sign(), sign(m1));\n\n\n  VERIFY_IS_APPROX(m1.exp() * m2.exp(), exp(m1+m2));\n  VERIFY_IS_APPROX(m1.exp(), exp(m1));\n  VERIFY_IS_APPROX(m1.exp() / m2.exp(),(m1-m2).exp());\n\n  VERIFY_IS_APPROX(m1.expm1(), expm1(m1));\n  VERIFY_IS_APPROX(expm1(m1), exp(m1) - 1.);\n  // Check for larger magnitude complex numbers that expm1 matches exp - 1.\n  VERIFY_IS_APPROX(expm1(10. * m1), exp(10. * m1) - 1.);\n\n  VERIFY_IS_APPROX(sinh(m1), 0.5*(exp(m1)-exp(-m1)));\n  VERIFY_IS_APPROX(cosh(m1), 0.5*(exp(m1)+exp(-m1)));\n  VERIFY_IS_APPROX(tanh(m1), (0.5*(exp(m1)-exp(-m1)))/(0.5*(exp(m1)+exp(-m1))));\n  VERIFY_IS_APPROX(logistic(m1), (1.0/(1.0 + exp(-m1))));\n\n  for (Index i = 0; i < m.rows(); ++i)\n    for (Index j = 0; j < m.cols(); ++j)\n      m3(i,j) = std::atan2(m1(i,j).imag(), m1(i,j).real());\n  VERIFY_IS_APPROX(arg(m1), m3);\n\n  std::complex<RealScalar> zero(0.0,0.0);\n  VERIFY((Eigen::isnan)(m1*zero/zero).all());\n#if EIGEN_COMP_MSVC\n  // msvc complex division is not robust\n  VERIFY((Eigen::isinf)(m4/RealScalar(0)).all());\n#else\n#if EIGEN_COMP_CLANG\n  // clang's complex division is notoriously broken too\n  if((numext::isinf)(m4(0,0)/RealScalar(0))) {\n#endif\n    VERIFY((Eigen::isinf)(m4/zero).all());\n#if EIGEN_COMP_CLANG\n  }\n  else\n  {\n    VERIFY((Eigen::isinf)(m4.real()/zero.real()).all());\n  }\n#endif\n#endif // MSVC\n\n  VERIFY(((Eigen::isfinite)(m1) && (!(Eigen::isfinite)(m1*zero/zero)) && (!(Eigen::isfinite)(m1/zero))).all());\n\n  VERIFY_IS_APPROX(inverse(inverse(m4)),m4);\n  VERIFY_IS_APPROX(conj(m1.conjugate()), m1);\n  VERIFY_IS_APPROX(abs(m1), sqrt(square(m1.real())+square(m1.imag())));\n  VERIFY_IS_APPROX(abs(m1), sqrt(abs2(m1)));\n  VERIFY_IS_APPROX(log10(m1), log(m1)/log(10));\n  VERIFY_IS_APPROX(log2(m1), log(m1)/log(2));\n\n  VERIFY_IS_APPROX( m1.sign(), -(-m1).sign() );\n  VERIFY_IS_APPROX( m1.sign() * m1.abs(), m1);\n\n  // scalar by array division\n  Scalar  s1 = internal::random<Scalar>();\n  const RealScalar tiny = std::sqrt(std::numeric_limits<RealScalar>::epsilon());\n  s1 += Scalar(tiny);\n  m1 += ArrayType::Constant(rows,cols,Scalar(tiny));\n  VERIFY_IS_APPROX(s1/m1, s1 * m1.inverse());\n\n  // check inplace transpose\n  m2 = m1;\n  m2.transposeInPlace();\n  VERIFY_IS_APPROX(m2, m1.transpose());\n  m2.transposeInPlace();\n  VERIFY_IS_APPROX(m2, m1);\n  // Check vectorized inplace transpose.\n  ArrayType m5 = ArrayType::Random(131, 131);\n  ArrayType m6 = m5;\n  m6.transposeInPlace();\n  VERIFY_IS_APPROX(m6, m5.transpose());\n}\n\ntemplate<typename ArrayType> void min_max(const ArrayType& m)\n{\n  typedef typename ArrayType::Scalar Scalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  ArrayType m1 = ArrayType::Random(rows, cols);\n\n  // min/max with array\n  Scalar maxM1 = m1.maxCoeff();\n  Scalar minM1 = m1.minCoeff();\n\n  VERIFY_IS_APPROX(ArrayType::Constant(rows,cols, minM1), (m1.min)(ArrayType::Constant(rows,cols, minM1)));\n  VERIFY_IS_APPROX(m1, (m1.min)(ArrayType::Constant(rows,cols, maxM1)));\n\n  VERIFY_IS_APPROX(ArrayType::Constant(rows,cols, maxM1), (m1.max)(ArrayType::Constant(rows,cols, maxM1)));\n  VERIFY_IS_APPROX(m1, (m1.max)(ArrayType::Constant(rows,cols, minM1)));\n\n  // min/max with scalar input\n  VERIFY_IS_APPROX(ArrayType::Constant(rows,cols, minM1), (m1.min)( minM1));\n  VERIFY_IS_APPROX(m1, (m1.min)( maxM1));\n\n  VERIFY_IS_APPROX(ArrayType::Constant(rows,cols, maxM1), (m1.max)( maxM1));\n  VERIFY_IS_APPROX(m1, (m1.max)( minM1));\n\n\n  // min/max with various NaN propagation options.\n  if (m1.size() > 1 && !NumTraits<Scalar>::IsInteger) {\n    m1(0,0) = NumTraits<Scalar>::quiet_NaN();\n    maxM1 = m1.template maxCoeff<PropagateNaN>();\n    minM1 = m1.template minCoeff<PropagateNaN>();\n    VERIFY((numext::isnan)(maxM1));\n    VERIFY((numext::isnan)(minM1));\n\n    maxM1 = m1.template maxCoeff<PropagateNumbers>();\n    minM1 = m1.template minCoeff<PropagateNumbers>();\n    VERIFY(!(numext::isnan)(maxM1));\n    VERIFY(!(numext::isnan)(minM1));\n  }\n}\n\nEIGEN_DECLARE_TEST(array_cwise)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( array(Array<float, 1, 1>()) );\n    CALL_SUBTEST_2( array(Array22f()) );\n    CALL_SUBTEST_3( array(Array44d()) );\n    CALL_SUBTEST_4( array(ArrayXXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_5( array(ArrayXXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( array(ArrayXXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( array(Array<Index,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( comparisons(Array<float, 1, 1>()) );\n    CALL_SUBTEST_2( comparisons(Array22f()) );\n    CALL_SUBTEST_3( comparisons(Array44d()) );\n    CALL_SUBTEST_5( comparisons(ArrayXXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( comparisons(ArrayXXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( min_max(Array<float, 1, 1>()) );\n    CALL_SUBTEST_2( min_max(Array22f()) );\n    CALL_SUBTEST_3( min_max(Array44d()) );\n    CALL_SUBTEST_5( min_max(ArrayXXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( min_max(ArrayXXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( array_real(Array<float, 1, 1>()) );\n    CALL_SUBTEST_2( array_real(Array22f()) );\n    CALL_SUBTEST_3( array_real(Array44d()) );\n    CALL_SUBTEST_5( array_real(ArrayXXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_7( array_real(Array<Eigen::half, 32, 32>()) );\n    CALL_SUBTEST_8( array_real(Array<Eigen::bfloat16, 32, 32>()) );\n  }\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_4( array_complex(ArrayXXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n\n  VERIFY((internal::is_same< internal::global_math_functions_filtering_base<int>::type, int >::value));\n  VERIFY((internal::is_same< internal::global_math_functions_filtering_base<float>::type, float >::value));\n  VERIFY((internal::is_same< internal::global_math_functions_filtering_base<Array2i>::type, ArrayBase<Array2i> >::value));\n  typedef CwiseUnaryOp<internal::scalar_abs_op<double>, ArrayXd > Xpr;\n  VERIFY((internal::is_same< internal::global_math_functions_filtering_base<Xpr>::type,\n                           ArrayBase<Xpr>\n                         >::value));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/array_for_matrix.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void array_for_matrix(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> ColVectorType;\n  typedef Matrix<Scalar, 1, MatrixType::ColsAtCompileTime> RowVectorType; \n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols);\n\n  ColVectorType cv1 = ColVectorType::Random(rows);\n  RowVectorType rv1 = RowVectorType::Random(cols);\n  \n  Scalar  s1 = internal::random<Scalar>(),\n          s2 = internal::random<Scalar>();\n          \n  // scalar addition\n  VERIFY_IS_APPROX(m1.array() + s1, s1 + m1.array());\n  VERIFY_IS_APPROX((m1.array() + s1).matrix(), MatrixType::Constant(rows,cols,s1) + m1);\n  VERIFY_IS_APPROX(((m1*Scalar(2)).array() - s2).matrix(), (m1+m1) - MatrixType::Constant(rows,cols,s2) );\n  m3 = m1;\n  m3.array() += s2;\n  VERIFY_IS_APPROX(m3, (m1.array() + s2).matrix());\n  m3 = m1;\n  m3.array() -= s1;\n  VERIFY_IS_APPROX(m3, (m1.array() - s1).matrix());\n\n  // reductions\n  VERIFY_IS_MUCH_SMALLER_THAN(m1.colwise().sum().sum() - m1.sum(), m1.squaredNorm());\n  VERIFY_IS_MUCH_SMALLER_THAN(m1.rowwise().sum().sum() - m1.sum(), m1.squaredNorm());\n  VERIFY_IS_MUCH_SMALLER_THAN(m1.colwise().sum() + m2.colwise().sum() - (m1+m2).colwise().sum(), (m1+m2).squaredNorm());\n  VERIFY_IS_MUCH_SMALLER_THAN(m1.rowwise().sum() - m2.rowwise().sum() - (m1-m2).rowwise().sum(), (m1-m2).squaredNorm());\n  VERIFY_IS_APPROX(m1.colwise().sum(), m1.colwise().redux(internal::scalar_sum_op<Scalar,Scalar>()));\n\n  // vector-wise ops\n  m3 = m1;\n  VERIFY_IS_APPROX(m3.colwise() += cv1, m1.colwise() + cv1);\n  m3 = m1;\n  VERIFY_IS_APPROX(m3.colwise() -= cv1, m1.colwise() - cv1);\n  m3 = m1;\n  VERIFY_IS_APPROX(m3.rowwise() += rv1, m1.rowwise() + rv1);\n  m3 = m1;\n  VERIFY_IS_APPROX(m3.rowwise() -= rv1, m1.rowwise() - rv1);\n  \n  // empty objects\n  VERIFY_IS_APPROX((m1.template block<0,Dynamic>(0,0,0,cols).colwise().sum()), RowVectorType::Zero(cols));\n  VERIFY_IS_APPROX((m1.template block<Dynamic,0>(0,0,rows,0).rowwise().sum()), ColVectorType::Zero(rows));\n  VERIFY_IS_APPROX((m1.template block<0,Dynamic>(0,0,0,cols).colwise().prod()), RowVectorType::Ones(cols));\n  VERIFY_IS_APPROX((m1.template block<Dynamic,0>(0,0,rows,0).rowwise().prod()), ColVectorType::Ones(rows));\n\n  VERIFY_IS_APPROX(m1.block(0,0,0,cols).colwise().sum(), RowVectorType::Zero(cols));\n  VERIFY_IS_APPROX(m1.block(0,0,rows,0).rowwise().sum(), ColVectorType::Zero(rows));\n  VERIFY_IS_APPROX(m1.block(0,0,0,cols).colwise().prod(), RowVectorType::Ones(cols));\n  VERIFY_IS_APPROX(m1.block(0,0,rows,0).rowwise().prod(), ColVectorType::Ones(rows));\n  \n  // verify the const accessors exist\n  const Scalar& ref_m1 = m.matrix().array().coeffRef(0);\n  const Scalar& ref_m2 = m.matrix().array().coeffRef(0,0);\n  const Scalar& ref_a1 = m.array().matrix().coeffRef(0);\n  const Scalar& ref_a2 = m.array().matrix().coeffRef(0,0);\n  VERIFY(&ref_a1 == &ref_m1);\n  VERIFY(&ref_a2 == &ref_m2);\n\n  // Check write accessors:\n  m1.array().coeffRef(0,0) = 1;\n  VERIFY_IS_APPROX(m1(0,0),Scalar(1));\n  m1.array()(0,0) = 2;\n  VERIFY_IS_APPROX(m1(0,0),Scalar(2));\n  m1.array().matrix().coeffRef(0,0) = 3;\n  VERIFY_IS_APPROX(m1(0,0),Scalar(3));\n  m1.array().matrix()(0,0) = 4;\n  VERIFY_IS_APPROX(m1(0,0),Scalar(4));\n}\n\ntemplate<typename MatrixType> void comparisons(const MatrixType& m)\n{\n  using std::abs;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  Index r = internal::random<Index>(0, rows-1),\n        c = internal::random<Index>(0, cols-1);\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols);\n\n  VERIFY(((m1.array() + Scalar(1)) > m1.array()).all());\n  VERIFY(((m1.array() - Scalar(1)) < m1.array()).all());\n  if (rows*cols>1)\n  {\n    m3 = m1;\n    m3(r,c) += 1;\n    VERIFY(! (m1.array() < m3.array()).all() );\n    VERIFY(! (m1.array() > m3.array()).all() );\n  }\n\n  // comparisons to scalar\n  VERIFY( (m1.array() != (m1(r,c)+1) ).any() );\n  VERIFY( (m1.array() > (m1(r,c)-1) ).any() );\n  VERIFY( (m1.array() < (m1(r,c)+1) ).any() );\n  VERIFY( (m1.array() == m1(r,c) ).any() );\n  VERIFY( m1.cwiseEqual(m1(r,c)).any() );\n\n  // test Select\n  VERIFY_IS_APPROX( (m1.array()<m2.array()).select(m1,m2), m1.cwiseMin(m2) );\n  VERIFY_IS_APPROX( (m1.array()>m2.array()).select(m1,m2), m1.cwiseMax(m2) );\n  Scalar mid = (m1.cwiseAbs().minCoeff() + m1.cwiseAbs().maxCoeff())/Scalar(2);\n  for (int j=0; j<cols; ++j)\n  for (int i=0; i<rows; ++i)\n    m3(i,j) = abs(m1(i,j))<mid ? 0 : m1(i,j);\n  VERIFY_IS_APPROX( (m1.array().abs()<MatrixType::Constant(rows,cols,mid).array())\n                        .select(MatrixType::Zero(rows,cols),m1), m3);\n  // shorter versions:\n  VERIFY_IS_APPROX( (m1.array().abs()<MatrixType::Constant(rows,cols,mid).array())\n                        .select(0,m1), m3);\n  VERIFY_IS_APPROX( (m1.array().abs()>=MatrixType::Constant(rows,cols,mid).array())\n                        .select(m1,0), m3);\n  // even shorter version:\n  VERIFY_IS_APPROX( (m1.array().abs()<mid).select(0,m1), m3);\n\n  // count\n  VERIFY(((m1.array().abs()+1)>RealScalar(0.1)).count() == rows*cols);\n\n  // and/or\n  VERIFY( ((m1.array()<RealScalar(0)).matrix() && (m1.array()>RealScalar(0)).matrix()).count() == 0);\n  VERIFY( ((m1.array()<RealScalar(0)).matrix() || (m1.array()>=RealScalar(0)).matrix()).count() == rows*cols);\n  RealScalar a = m1.cwiseAbs().mean();\n  VERIFY( ((m1.array()<-a).matrix() || (m1.array()>a).matrix()).count() == (m1.cwiseAbs().array()>a).count());\n\n  typedef Matrix<Index, Dynamic, 1> VectorOfIndices;\n\n  // TODO allows colwise/rowwise for array\n  VERIFY_IS_APPROX(((m1.array().abs()+1)>RealScalar(0.1)).matrix().colwise().count(), VectorOfIndices::Constant(cols,rows).transpose());\n  VERIFY_IS_APPROX(((m1.array().abs()+1)>RealScalar(0.1)).matrix().rowwise().count(), VectorOfIndices::Constant(rows, cols));\n}\n\ntemplate<typename VectorType> void lpNorm(const VectorType& v)\n{\n  using std::sqrt;\n  typedef typename VectorType::RealScalar RealScalar;\n  VectorType u = VectorType::Random(v.size());\n\n  if(v.size()==0)\n  {\n    VERIFY_IS_APPROX(u.template lpNorm<Infinity>(), RealScalar(0));\n    VERIFY_IS_APPROX(u.template lpNorm<1>(), RealScalar(0));\n    VERIFY_IS_APPROX(u.template lpNorm<2>(), RealScalar(0));\n    VERIFY_IS_APPROX(u.template lpNorm<5>(), RealScalar(0));\n  }\n  else\n  {\n    VERIFY_IS_APPROX(u.template lpNorm<Infinity>(), u.cwiseAbs().maxCoeff());\n  }\n\n  VERIFY_IS_APPROX(u.template lpNorm<1>(), u.cwiseAbs().sum());\n  VERIFY_IS_APPROX(u.template lpNorm<2>(), sqrt(u.array().abs().square().sum()));\n  VERIFY_IS_APPROX(numext::pow(u.template lpNorm<5>(), typename VectorType::RealScalar(5)), u.array().abs().pow(5).sum());\n}\n\ntemplate<typename MatrixType> void cwise_min_max(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols);\n\n  // min/max with array\n  Scalar maxM1 = m1.maxCoeff();\n  Scalar minM1 = m1.minCoeff();\n\n  VERIFY_IS_APPROX(MatrixType::Constant(rows,cols, minM1), m1.cwiseMin(MatrixType::Constant(rows,cols, minM1)));\n  VERIFY_IS_APPROX(m1, m1.cwiseMin(MatrixType::Constant(rows,cols, maxM1)));\n\n  VERIFY_IS_APPROX(MatrixType::Constant(rows,cols, maxM1), m1.cwiseMax(MatrixType::Constant(rows,cols, maxM1)));\n  VERIFY_IS_APPROX(m1, m1.cwiseMax(MatrixType::Constant(rows,cols, minM1)));\n\n  // min/max with scalar input\n  VERIFY_IS_APPROX(MatrixType::Constant(rows,cols, minM1), m1.cwiseMin( minM1));\n  VERIFY_IS_APPROX(m1, m1.cwiseMin(maxM1));\n  VERIFY_IS_APPROX(-m1, (-m1).cwiseMin(-minM1));\n  VERIFY_IS_APPROX(-m1.array(), ((-m1).array().min)( -minM1));\n\n  VERIFY_IS_APPROX(MatrixType::Constant(rows,cols, maxM1), m1.cwiseMax( maxM1));\n  VERIFY_IS_APPROX(m1, m1.cwiseMax(minM1));\n  VERIFY_IS_APPROX(-m1, (-m1).cwiseMax(-maxM1));\n  VERIFY_IS_APPROX(-m1.array(), ((-m1).array().max)(-maxM1));\n\n  VERIFY_IS_APPROX(MatrixType::Constant(rows,cols, minM1).array(), (m1.array().min)( minM1));\n  VERIFY_IS_APPROX(m1.array(), (m1.array().min)( maxM1));\n\n  VERIFY_IS_APPROX(MatrixType::Constant(rows,cols, maxM1).array(), (m1.array().max)( maxM1));\n  VERIFY_IS_APPROX(m1.array(), (m1.array().max)( minM1));\n\n}\n\ntemplate<typename MatrixTraits> void resize(const MatrixTraits& t)\n{\n  typedef typename MatrixTraits::Scalar Scalar;\n  typedef Matrix<Scalar,Dynamic,Dynamic> MatrixType;\n  typedef Array<Scalar,Dynamic,Dynamic> Array2DType;\n  typedef Matrix<Scalar,Dynamic,1> VectorType;\n  typedef Array<Scalar,Dynamic,1> Array1DType;\n\n  Index rows = t.rows(), cols = t.cols();\n\n  MatrixType m(rows,cols);\n  VectorType v(rows);\n  Array2DType a2(rows,cols);\n  Array1DType a1(rows);\n\n  m.array().resize(rows+1,cols+1);\n  VERIFY(m.rows()==rows+1 && m.cols()==cols+1);\n  a2.matrix().resize(rows+1,cols+1);\n  VERIFY(a2.rows()==rows+1 && a2.cols()==cols+1);\n  v.array().resize(cols);\n  VERIFY(v.size()==cols);\n  a1.matrix().resize(cols);\n  VERIFY(a1.size()==cols);\n}\n\ntemplate<int>\nvoid regression_bug_654()\n{\n  ArrayXf a = RowVectorXf(3);\n  VectorXf v = Array<float,1,Dynamic>(3);\n}\n\n// Check propagation of LvalueBit through Array/Matrix-Wrapper\ntemplate<int>\nvoid regrrssion_bug_1410()\n{\n  const Matrix4i M;\n  const Array4i A;\n  ArrayWrapper<const Matrix4i> MA = M.array();\n  MA.row(0);\n  MatrixWrapper<const Array4i> AM = A.matrix();\n  AM.row(0);\n\n  VERIFY((internal::traits<ArrayWrapper<const Matrix4i> >::Flags&LvalueBit)==0);\n  VERIFY((internal::traits<MatrixWrapper<const Array4i> >::Flags&LvalueBit)==0);\n\n  VERIFY((internal::traits<ArrayWrapper<Matrix4i> >::Flags&LvalueBit)==LvalueBit);\n  VERIFY((internal::traits<MatrixWrapper<Array4i> >::Flags&LvalueBit)==LvalueBit);\n}\n\nEIGEN_DECLARE_TEST(array_for_matrix)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( array_for_matrix(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( array_for_matrix(Matrix2f()) );\n    CALL_SUBTEST_3( array_for_matrix(Matrix4d()) );\n    CALL_SUBTEST_4( array_for_matrix(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_5( array_for_matrix(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( array_for_matrix(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( comparisons(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( comparisons(Matrix2f()) );\n    CALL_SUBTEST_3( comparisons(Matrix4d()) );\n    CALL_SUBTEST_5( comparisons(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( comparisons(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( cwise_min_max(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( cwise_min_max(Matrix2f()) );\n    CALL_SUBTEST_3( cwise_min_max(Matrix4d()) );\n    CALL_SUBTEST_5( cwise_min_max(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( cwise_min_max(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( lpNorm(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( lpNorm(Vector2f()) );\n    CALL_SUBTEST_7( lpNorm(Vector3d()) );\n    CALL_SUBTEST_8( lpNorm(Vector4f()) );\n    CALL_SUBTEST_5( lpNorm(VectorXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_4( lpNorm(VectorXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  CALL_SUBTEST_5( lpNorm(VectorXf(0)) );\n  CALL_SUBTEST_4( lpNorm(VectorXcf(0)) );\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_4( resize(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_5( resize(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( resize(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  CALL_SUBTEST_6( regression_bug_654<0>() );\n  CALL_SUBTEST_6( regrrssion_bug_1410<0>() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/array_of_string.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\nEIGEN_DECLARE_TEST(array_of_string)\n{\n  typedef Array<std::string,1,Dynamic> ArrayXs;\n  ArrayXs a1(3), a2(3), a3(3), a3ref(3);\n  a1 << \"one\", \"two\", \"three\";\n  a2 << \"1\", \"2\", \"3\";\n  a3ref << \"one (1)\", \"two (2)\", \"three (3)\";\n  std::stringstream s1;\n  s1 << a1;\n  VERIFY_IS_EQUAL(s1.str(), std::string(\"  one    two  three\"));\n  a3 = a1 + std::string(\" (\") + a2 + std::string(\")\");\n  VERIFY((a3==a3ref).all());\n\n  a3 = a1;\n  a3 += std::string(\" (\") + a2 + std::string(\")\");\n  VERIFY((a3==a3ref).all());\n\n  a1.swap(a3);\n  VERIFY((a1==a3ref).all());\n  VERIFY((a3!=a3ref).all());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/array_replicate.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void replicate(const MatrixType& m)\n{\n  /* this test covers the following files:\n     Replicate.cpp\n  */\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n  typedef Matrix<Scalar, Dynamic, Dynamic> MatrixX;\n  typedef Matrix<Scalar, Dynamic, 1> VectorX;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols);\n\n  VectorType v1 = VectorType::Random(rows);\n\n  MatrixX x1, x2;\n  VectorX vx1;\n\n  int  f1 = internal::random<int>(1,10),\n       f2 = internal::random<int>(1,10);\n\n  x1.resize(rows*f1,cols*f2);\n  for(int j=0; j<f2; j++)\n  for(int i=0; i<f1; i++)\n    x1.block(i*rows,j*cols,rows,cols) = m1;\n  VERIFY_IS_APPROX(x1, m1.replicate(f1,f2));\n\n  x2.resize(2*rows,3*cols);\n  x2 << m2, m2, m2,\n        m2, m2, m2;\n  VERIFY_IS_APPROX(x2, (m2.template replicate<2,3>()));\n  \n  x2.resize(rows,3*cols);\n  x2 << m2, m2, m2;\n  VERIFY_IS_APPROX(x2, (m2.template replicate<1,3>()));\n  \n  vx1.resize(3*rows,cols);\n  vx1 << m2, m2, m2;\n  VERIFY_IS_APPROX(vx1+vx1, vx1+(m2.template replicate<3,1>()));\n  \n  vx1=m2+(m2.colwise().replicate(1));\n  \n  if(m2.cols()==1)\n    VERIFY_IS_APPROX(m2.coeff(0), (m2.template replicate<3,1>().coeff(m2.rows())));\n\n  x2.resize(rows,f1);\n  for (int j=0; j<f1; ++j)\n    x2.col(j) = v1;\n  VERIFY_IS_APPROX(x2, v1.rowwise().replicate(f1));\n\n  vx1.resize(rows*f2);\n  for (int j=0; j<f2; ++j)\n    vx1.segment(j*rows,rows) = v1;\n  VERIFY_IS_APPROX(vx1, v1.colwise().replicate(f2));\n}\n\nEIGEN_DECLARE_TEST(array_replicate)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( replicate(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( replicate(Vector2f()) );\n    CALL_SUBTEST_3( replicate(Vector3d()) );\n    CALL_SUBTEST_4( replicate(Vector4f()) );\n    CALL_SUBTEST_5( replicate(VectorXf(16)) );\n    CALL_SUBTEST_6( replicate(VectorXcd(10)) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/array_reverse.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2009 Ricard Marxer <email@ricardmarxer.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <iostream>\n\nusing namespace std;\n\ntemplate<typename MatrixType> void reverse(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  // this test relies a lot on Random.h, and there's not much more that we can do\n  // to test it, hence I consider that we will have tested Random.h\n  MatrixType m1 = MatrixType::Random(rows, cols), m2;\n  VectorType v1 = VectorType::Random(rows);\n\n  MatrixType m1_r = m1.reverse();\n  // Verify that MatrixBase::reverse() works\n  for ( int i = 0; i < rows; i++ ) {\n    for ( int j = 0; j < cols; j++ ) {\n      VERIFY_IS_APPROX(m1_r(i, j), m1(rows - 1 - i, cols - 1 - j));\n    }\n  }\n\n  Reverse<MatrixType> m1_rd(m1);\n  // Verify that a Reverse default (in both directions) of an expression works\n  for ( int i = 0; i < rows; i++ ) {\n    for ( int j = 0; j < cols; j++ ) {\n      VERIFY_IS_APPROX(m1_rd(i, j), m1(rows - 1 - i, cols - 1 - j));\n    }\n  }\n\n  Reverse<MatrixType, BothDirections> m1_rb(m1);\n  // Verify that a Reverse in both directions of an expression works\n  for ( int i = 0; i < rows; i++ ) {\n    for ( int j = 0; j < cols; j++ ) {\n      VERIFY_IS_APPROX(m1_rb(i, j), m1(rows - 1 - i, cols - 1 - j));\n    }\n  }\n\n  Reverse<MatrixType, Vertical> m1_rv(m1);\n  // Verify that a Reverse in the vertical directions of an expression works\n  for ( int i = 0; i < rows; i++ ) {\n    for ( int j = 0; j < cols; j++ ) {\n      VERIFY_IS_APPROX(m1_rv(i, j), m1(rows - 1 - i, j));\n    }\n  }\n\n  Reverse<MatrixType, Horizontal> m1_rh(m1);\n  // Verify that a Reverse in the horizontal directions of an expression works\n  for ( int i = 0; i < rows; i++ ) {\n    for ( int j = 0; j < cols; j++ ) {\n      VERIFY_IS_APPROX(m1_rh(i, j), m1(i, cols - 1 - j));\n    }\n  }\n\n  VectorType v1_r = v1.reverse();\n  // Verify that a VectorType::reverse() of an expression works\n  for ( int i = 0; i < rows; i++ ) {\n    VERIFY_IS_APPROX(v1_r(i), v1(rows - 1 - i));\n  }\n\n  MatrixType m1_cr = m1.colwise().reverse();\n  // Verify that PartialRedux::reverse() works (for colwise())\n  for ( int i = 0; i < rows; i++ ) {\n    for ( int j = 0; j < cols; j++ ) {\n      VERIFY_IS_APPROX(m1_cr(i, j), m1(rows - 1 - i, j));\n    }\n  }\n\n  MatrixType m1_rr = m1.rowwise().reverse();\n  // Verify that PartialRedux::reverse() works (for rowwise())\n  for ( int i = 0; i < rows; i++ ) {\n    for ( int j = 0; j < cols; j++ ) {\n      VERIFY_IS_APPROX(m1_rr(i, j), m1(i, cols - 1 - j));\n    }\n  }\n\n  Scalar x = internal::random<Scalar>();\n\n  Index r = internal::random<Index>(0, rows-1),\n        c = internal::random<Index>(0, cols-1);\n\n  m1.reverse()(r, c) = x;\n  VERIFY_IS_APPROX(x, m1(rows - 1 - r, cols - 1 - c));\n  \n  m2 = m1;\n  m2.reverseInPlace();\n  VERIFY_IS_APPROX(m2,m1.reverse().eval());\n  \n  m2 = m1;\n  m2.col(0).reverseInPlace();\n  VERIFY_IS_APPROX(m2.col(0),m1.col(0).reverse().eval());\n  \n  m2 = m1;\n  m2.row(0).reverseInPlace();\n  VERIFY_IS_APPROX(m2.row(0),m1.row(0).reverse().eval());\n  \n  m2 = m1;\n  m2.rowwise().reverseInPlace();\n  VERIFY_IS_APPROX(m2,m1.rowwise().reverse().eval());\n  \n  m2 = m1;\n  m2.colwise().reverseInPlace();\n  VERIFY_IS_APPROX(m2,m1.colwise().reverse().eval());\n\n  m1.colwise().reverse()(r, c) = x;\n  VERIFY_IS_APPROX(x, m1(rows - 1 - r, c));\n\n  m1.rowwise().reverse()(r, c) = x;\n  VERIFY_IS_APPROX(x, m1(r, cols - 1 - c));\n}\n\ntemplate<int>\nvoid array_reverse_extra()\n{\n  Vector4f x; x << 1, 2, 3, 4;\n  Vector4f y; y << 4, 3, 2, 1;\n  VERIFY(x.reverse()[1] == 3);\n  VERIFY(x.reverse() == y);\n}\n\n// Simpler version of reverseInPlace leveraging a bug\n// in clang 6/7 with -O2 and AVX or AVX512 enabled.\n// This simpler version ensure that the clang bug is not simply hidden\n// through mis-inlining of reverseInPlace or other minor changes.\ntemplate<typename MatrixType>\nEIGEN_DONT_INLINE\nvoid bug1684_job1(MatrixType& m1, MatrixType& m2)\n{\n  m2 = m1;\n  m2.col(0).swap(m2.col(3));\n  m2.col(1).swap(m2.col(2));\n}\n\ntemplate<typename MatrixType>\nEIGEN_DONT_INLINE\nvoid bug1684_job2(MatrixType& m1, MatrixType& m2)\n{\n  m2 = m1; // load m1/m2 in AVX registers\n  m1.col(0) = m2.col(3); // perform 128 bits moves\n  m1.col(1) = m2.col(2);\n  m1.col(2) = m2.col(1);\n  m1.col(3) = m2.col(0);\n}\n\ntemplate<typename MatrixType>\nEIGEN_DONT_INLINE\nvoid bug1684_job3(MatrixType& m1, MatrixType& m2)\n{\n  m2 = m1;\n  Vector4f tmp;\n  tmp = m2.col(0);\n  m2.col(0) = m2.col(3);\n  m2.col(3) = tmp;\n  tmp = m2.col(1);\n  m2.col(1) = m2.col(2);\n  m2.col(2) = tmp;\n  \n}\n\ntemplate<int>\nvoid bug1684()\n{\n  Matrix4f m1 = Matrix4f::Random();\n  Matrix4f m2 = Matrix4f::Random();\n  bug1684_job1(m1,m2);\n  VERIFY_IS_APPROX(m2, m1.rowwise().reverse().eval());\n  bug1684_job2(m1,m2);\n  VERIFY_IS_APPROX(m2, m1.rowwise().reverse().eval());\n  // This one still fail after our swap's workaround,\n  // but I expect users not to implement their own swap.\n  // bug1684_job3(m1,m2);\n  // VERIFY_IS_APPROX(m2, m1.rowwise().reverse().eval());\n}\n\nEIGEN_DECLARE_TEST(array_reverse)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( reverse(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( reverse(Matrix2f()) );\n    CALL_SUBTEST_3( reverse(Matrix4f()) );\n    CALL_SUBTEST_4( reverse(Matrix4d()) );\n    CALL_SUBTEST_5( reverse(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( reverse(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_7( reverse(MatrixXcd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_8( reverse(Matrix<float, 100, 100>()) );\n    CALL_SUBTEST_9( reverse(Matrix<float,Dynamic,Dynamic,RowMajor>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_3( bug1684<0>() );\n  }\n  CALL_SUBTEST_3( array_reverse_extra<0>() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/bandmatrix.cpp",
    "content": "// This file is triangularView of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void bandmatrix(const MatrixType& _m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrixType;\n\n  Index rows = _m.rows();\n  Index cols = _m.cols();\n  Index supers = _m.supers();\n  Index subs = _m.subs();\n\n  MatrixType m(rows,cols,supers,subs);\n\n  DenseMatrixType dm1(rows,cols);\n  dm1.setZero();\n\n  m.diagonal().setConstant(123);\n  dm1.diagonal().setConstant(123);\n  for (int i=1; i<=m.supers();++i)\n  {\n    m.diagonal(i).setConstant(static_cast<RealScalar>(i));\n    dm1.diagonal(i).setConstant(static_cast<RealScalar>(i));\n  }\n  for (int i=1; i<=m.subs();++i)\n  {\n    m.diagonal(-i).setConstant(-static_cast<RealScalar>(i));\n    dm1.diagonal(-i).setConstant(-static_cast<RealScalar>(i));\n  }\n  //std::cerr << m.m_data << \"\\n\\n\" << m.toDense() << \"\\n\\n\" << dm1 << \"\\n\\n\\n\\n\";\n  VERIFY_IS_APPROX(dm1,m.toDenseMatrix());\n\n  for (int i=0; i<cols; ++i)\n  {\n    m.col(i).setConstant(static_cast<RealScalar>(i+1));\n    dm1.col(i).setConstant(static_cast<RealScalar>(i+1));\n  }\n  Index d = (std::min)(rows,cols);\n  Index a = std::max<Index>(0,cols-d-supers);\n  Index b = std::max<Index>(0,rows-d-subs);\n  if(a>0) dm1.block(0,d+supers,rows,a).setZero();\n  dm1.block(0,supers+1,cols-supers-1-a,cols-supers-1-a).template triangularView<Upper>().setZero();\n  dm1.block(subs+1,0,rows-subs-1-b,rows-subs-1-b).template triangularView<Lower>().setZero();\n  if(b>0) dm1.block(d+subs,0,b,cols).setZero();\n  //std::cerr << m.m_data << \"\\n\\n\" << m.toDense() << \"\\n\\n\" << dm1 << \"\\n\\n\";\n  VERIFY_IS_APPROX(dm1,m.toDenseMatrix());\n\n}\n\nusing Eigen::internal::BandMatrix;\n\nEIGEN_DECLARE_TEST(bandmatrix)\n{\n  for(int i = 0; i < 10*g_repeat ; i++) {\n    Index rows = internal::random<Index>(1,10);\n    Index cols = internal::random<Index>(1,10);\n    Index sups = internal::random<Index>(0,cols-1);\n    Index subs = internal::random<Index>(0,rows-1);\n    CALL_SUBTEST(bandmatrix(BandMatrix<float>(rows,cols,sups,subs)) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/basicstuff.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_STATIC_ASSERT\n\n#include \"main.h\"\n#include \"random_without_cast_overflow.h\"\n\ntemplate<typename MatrixType> void basicStuff(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> SquareMatrixType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  // this test relies a lot on Random.h, and there's not much more that we can do\n  // to test it, hence I consider that we will have tested Random.h\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols),\n             mzero = MatrixType::Zero(rows, cols),\n             square = Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime>::Random(rows, rows);\n  VectorType v1 = VectorType::Random(rows),\n             vzero = VectorType::Zero(rows);\n  SquareMatrixType sm1 = SquareMatrixType::Random(rows,rows), sm2(rows,rows);\n\n  Scalar x = 0;\n  while(x == Scalar(0)) x = internal::random<Scalar>();\n\n  Index r = internal::random<Index>(0, rows-1),\n        c = internal::random<Index>(0, cols-1);\n\n  m1.coeffRef(r,c) = x;\n  VERIFY_IS_APPROX(x, m1.coeff(r,c));\n  m1(r,c) = x;\n  VERIFY_IS_APPROX(x, m1(r,c));\n  v1.coeffRef(r) = x;\n  VERIFY_IS_APPROX(x, v1.coeff(r));\n  v1(r) = x;\n  VERIFY_IS_APPROX(x, v1(r));\n  v1[r] = x;\n  VERIFY_IS_APPROX(x, v1[r]);\n\n  // test fetching with various index types.\n  Index r1 = internal::random<Index>(0, numext::mini(Index(127),rows-1));\n  x = v1(static_cast<char>(r1));\n  x = v1(static_cast<signed char>(r1));\n  x = v1(static_cast<unsigned char>(r1));\n  x = v1(static_cast<signed short>(r1));\n  x = v1(static_cast<unsigned short>(r1));\n  x = v1(static_cast<signed int>(r1));\n  x = v1(static_cast<unsigned int>(r1));\n  x = v1(static_cast<signed long>(r1));\n  x = v1(static_cast<unsigned long>(r1));\n#if EIGEN_HAS_CXX11\n  x = v1(static_cast<long long int>(r1));\n  x = v1(static_cast<unsigned long long int>(r1));\n#endif\n\n  VERIFY_IS_APPROX(               v1,    v1);\n  VERIFY_IS_NOT_APPROX(           v1,    2*v1);\n  VERIFY_IS_MUCH_SMALLER_THAN(    vzero, v1);\n  VERIFY_IS_MUCH_SMALLER_THAN(  vzero, v1.squaredNorm());\n  VERIFY_IS_NOT_MUCH_SMALLER_THAN(v1,    v1);\n  VERIFY_IS_APPROX(               vzero, v1-v1);\n  VERIFY_IS_APPROX(               m1,    m1);\n  VERIFY_IS_NOT_APPROX(           m1,    2*m1);\n  VERIFY_IS_MUCH_SMALLER_THAN(    mzero, m1);\n  VERIFY_IS_NOT_MUCH_SMALLER_THAN(m1,    m1);\n  VERIFY_IS_APPROX(               mzero, m1-m1);\n\n  // always test operator() on each read-only expression class,\n  // in order to check const-qualifiers.\n  // indeed, if an expression class (here Zero) is meant to be read-only,\n  // hence has no _write() method, the corresponding MatrixBase method (here zero())\n  // should return a const-qualified object so that it is the const-qualified\n  // operator() that gets called, which in turn calls _read().\n  VERIFY_IS_MUCH_SMALLER_THAN(MatrixType::Zero(rows,cols)(r,c), static_cast<Scalar>(1));\n\n  // now test copying a row-vector into a (column-)vector and conversely.\n  square.col(r) = square.row(r).eval();\n  Matrix<Scalar, 1, MatrixType::RowsAtCompileTime> rv(rows);\n  Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> cv(rows);\n  rv = square.row(r);\n  cv = square.col(r);\n\n  VERIFY_IS_APPROX(rv, cv.transpose());\n\n  if(cols!=1 && rows!=1 && MatrixType::SizeAtCompileTime!=Dynamic)\n  {\n    VERIFY_RAISES_ASSERT(m1 = (m2.block(0,0, rows-1, cols-1)));\n  }\n\n  if(cols!=1 && rows!=1)\n  {\n    VERIFY_RAISES_ASSERT(m1[0]);\n    VERIFY_RAISES_ASSERT((m1+m1)[0]);\n  }\n\n  VERIFY_IS_APPROX(m3 = m1,m1);\n  MatrixType m4;\n  VERIFY_IS_APPROX(m4 = m1,m1);\n\n  m3.real() = m1.real();\n  VERIFY_IS_APPROX(static_cast<const MatrixType&>(m3).real(), static_cast<const MatrixType&>(m1).real());\n  VERIFY_IS_APPROX(static_cast<const MatrixType&>(m3).real(), m1.real());\n\n  // check == / != operators\n  VERIFY(m1==m1);\n  VERIFY(m1!=m2);\n  VERIFY(!(m1==m2));\n  VERIFY(!(m1!=m1));\n  m1 = m2;\n  VERIFY(m1==m2);\n  VERIFY(!(m1!=m2));\n\n  // check automatic transposition\n  sm2.setZero();\n  for(Index i=0;i<rows;++i)\n    sm2.col(i) = sm1.row(i);\n  VERIFY_IS_APPROX(sm2,sm1.transpose());\n\n  sm2.setZero();\n  for(Index i=0;i<rows;++i)\n    sm2.col(i).noalias() = sm1.row(i);\n  VERIFY_IS_APPROX(sm2,sm1.transpose());\n\n  sm2.setZero();\n  for(Index i=0;i<rows;++i)\n    sm2.col(i).noalias() += sm1.row(i);\n  VERIFY_IS_APPROX(sm2,sm1.transpose());\n\n  sm2.setZero();\n  for(Index i=0;i<rows;++i)\n    sm2.col(i).noalias() -= sm1.row(i);\n  VERIFY_IS_APPROX(sm2,-sm1.transpose());\n\n  // check ternary usage\n  {\n    bool b = internal::random<int>(0,10)>5;\n    m3 = b ? m1 : m2;\n    if(b) VERIFY_IS_APPROX(m3,m1);\n    else  VERIFY_IS_APPROX(m3,m2);\n    m3 = b ? -m1 : m2;\n    if(b) VERIFY_IS_APPROX(m3,-m1);\n    else  VERIFY_IS_APPROX(m3,m2);\n    m3 = b ? m1 : -m2;\n    if(b) VERIFY_IS_APPROX(m3,m1);\n    else  VERIFY_IS_APPROX(m3,-m2);\n  }\n}\n\ntemplate<typename MatrixType> void basicStuffComplex(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<RealScalar, MatrixType::RowsAtCompileTime, MatrixType::ColsAtCompileTime> RealMatrixType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  Scalar s1 = internal::random<Scalar>(),\n         s2 = internal::random<Scalar>();\n\n  VERIFY(numext::real(s1)==numext::real_ref(s1));\n  VERIFY(numext::imag(s1)==numext::imag_ref(s1));\n  numext::real_ref(s1) = numext::real(s2);\n  numext::imag_ref(s1) = numext::imag(s2);\n  VERIFY(internal::isApprox(s1, s2, NumTraits<RealScalar>::epsilon()));\n  // extended precision in Intel FPUs means that s1 == s2 in the line above is not guaranteed.\n\n  RealMatrixType rm1 = RealMatrixType::Random(rows,cols),\n                 rm2 = RealMatrixType::Random(rows,cols);\n  MatrixType cm(rows,cols);\n  cm.real() = rm1;\n  cm.imag() = rm2;\n  VERIFY_IS_APPROX(static_cast<const MatrixType&>(cm).real(), rm1);\n  VERIFY_IS_APPROX(static_cast<const MatrixType&>(cm).imag(), rm2);\n  rm1.setZero();\n  rm2.setZero();\n  rm1 = cm.real();\n  rm2 = cm.imag();\n  VERIFY_IS_APPROX(static_cast<const MatrixType&>(cm).real(), rm1);\n  VERIFY_IS_APPROX(static_cast<const MatrixType&>(cm).imag(), rm2);\n  cm.real().setZero();\n  VERIFY(static_cast<const MatrixType&>(cm).real().isZero());\n  VERIFY(!static_cast<const MatrixType&>(cm).imag().isZero());\n}\n\ntemplate<typename SrcScalar, typename TgtScalar>\nstruct casting_test {\n  static void run() {\n    Matrix<SrcScalar,4,4> m;\n    for (int i=0; i<m.rows(); ++i) {\n      for (int j=0; j<m.cols(); ++j) {\n        m(i, j) = internal::random_without_cast_overflow<SrcScalar,TgtScalar>::value();\n      }\n    }\n    Matrix<TgtScalar,4,4> n = m.template cast<TgtScalar>();\n    for (int i=0; i<m.rows(); ++i) {\n      for (int j=0; j<m.cols(); ++j) {\n        VERIFY_IS_APPROX(n(i, j), (internal::cast<SrcScalar,TgtScalar>(m(i, j))));\n      }\n    }\n  }\n};\n\ntemplate<typename SrcScalar, typename EnableIf = void>\nstruct casting_test_runner {\n  static void run() {\n    casting_test<SrcScalar, bool>::run();\n    casting_test<SrcScalar, int8_t>::run();\n    casting_test<SrcScalar, uint8_t>::run();\n    casting_test<SrcScalar, int16_t>::run();\n    casting_test<SrcScalar, uint16_t>::run();\n    casting_test<SrcScalar, int32_t>::run();\n    casting_test<SrcScalar, uint32_t>::run();\n#if EIGEN_HAS_CXX11\n    casting_test<SrcScalar, int64_t>::run();\n    casting_test<SrcScalar, uint64_t>::run();\n#endif\n    casting_test<SrcScalar, half>::run();\n    casting_test<SrcScalar, bfloat16>::run();\n    casting_test<SrcScalar, float>::run();\n    casting_test<SrcScalar, double>::run();\n    casting_test<SrcScalar, std::complex<float> >::run();\n    casting_test<SrcScalar, std::complex<double> >::run();\n  }\n};\n\ntemplate<typename SrcScalar>\nstruct casting_test_runner<SrcScalar, typename internal::enable_if<(NumTraits<SrcScalar>::IsComplex)>::type>\n{\n  static void run() {\n    // Only a few casts from std::complex<T> are defined.\n    casting_test<SrcScalar, half>::run();\n    casting_test<SrcScalar, bfloat16>::run();\n    casting_test<SrcScalar, std::complex<float> >::run();\n    casting_test<SrcScalar, std::complex<double> >::run();\n  }\n};\n\nvoid casting_all() {\n  casting_test_runner<bool>::run();\n  casting_test_runner<int8_t>::run();\n  casting_test_runner<uint8_t>::run();\n  casting_test_runner<int16_t>::run();\n  casting_test_runner<uint16_t>::run();\n  casting_test_runner<int32_t>::run();\n  casting_test_runner<uint32_t>::run();\n#if EIGEN_HAS_CXX11\n  casting_test_runner<int64_t>::run();\n  casting_test_runner<uint64_t>::run();\n#endif\n  casting_test_runner<half>::run();\n  casting_test_runner<bfloat16>::run();\n  casting_test_runner<float>::run();\n  casting_test_runner<double>::run();\n  casting_test_runner<std::complex<float> >::run();\n  casting_test_runner<std::complex<double> >::run();\n}\n\ntemplate <typename Scalar>\nvoid fixedSizeMatrixConstruction()\n{\n  Scalar raw[4];\n  for(int k=0; k<4; ++k)\n    raw[k] = internal::random<Scalar>();\n\n  {\n    Matrix<Scalar,4,1> m(raw);\n    Array<Scalar,4,1> a(raw);\n    for(int k=0; k<4; ++k) VERIFY(m(k) == raw[k]);\n    for(int k=0; k<4; ++k) VERIFY(a(k) == raw[k]);\n    VERIFY_IS_EQUAL(m,(Matrix<Scalar,4,1>(raw[0],raw[1],raw[2],raw[3])));\n    VERIFY((a==(Array<Scalar,4,1>(raw[0],raw[1],raw[2],raw[3]))).all());\n  }\n  {\n    Matrix<Scalar,3,1> m(raw);\n    Array<Scalar,3,1> a(raw);\n    for(int k=0; k<3; ++k) VERIFY(m(k) == raw[k]);\n    for(int k=0; k<3; ++k) VERIFY(a(k) == raw[k]);\n    VERIFY_IS_EQUAL(m,(Matrix<Scalar,3,1>(raw[0],raw[1],raw[2])));\n    VERIFY((a==Array<Scalar,3,1>(raw[0],raw[1],raw[2])).all());\n  }\n  {\n    Matrix<Scalar,2,1> m(raw), m2( (DenseIndex(raw[0])), (DenseIndex(raw[1])) );\n    Array<Scalar,2,1> a(raw),  a2( (DenseIndex(raw[0])), (DenseIndex(raw[1])) );\n    for(int k=0; k<2; ++k) VERIFY(m(k) == raw[k]);\n    for(int k=0; k<2; ++k) VERIFY(a(k) == raw[k]);\n    VERIFY_IS_EQUAL(m,(Matrix<Scalar,2,1>(raw[0],raw[1])));\n    VERIFY((a==Array<Scalar,2,1>(raw[0],raw[1])).all());\n    for(int k=0; k<2; ++k) VERIFY(m2(k) == DenseIndex(raw[k]));\n    for(int k=0; k<2; ++k) VERIFY(a2(k) == DenseIndex(raw[k]));\n  }\n  {\n    Matrix<Scalar,1,2> m(raw),\n                       m2( (DenseIndex(raw[0])), (DenseIndex(raw[1])) ),\n                       m3( (int(raw[0])), (int(raw[1])) ),\n                       m4( (float(raw[0])), (float(raw[1])) );\n    Array<Scalar,1,2> a(raw),  a2( (DenseIndex(raw[0])), (DenseIndex(raw[1])) );\n    for(int k=0; k<2; ++k) VERIFY(m(k) == raw[k]);\n    for(int k=0; k<2; ++k) VERIFY(a(k) == raw[k]);\n    VERIFY_IS_EQUAL(m,(Matrix<Scalar,1,2>(raw[0],raw[1])));\n    VERIFY((a==Array<Scalar,1,2>(raw[0],raw[1])).all());\n    for(int k=0; k<2; ++k) VERIFY(m2(k) == DenseIndex(raw[k]));\n    for(int k=0; k<2; ++k) VERIFY(a2(k) == DenseIndex(raw[k]));\n    for(int k=0; k<2; ++k) VERIFY(m3(k) == int(raw[k]));\n    for(int k=0; k<2; ++k) VERIFY((m4(k)) == Scalar(float(raw[k])));\n  }\n  {\n    Matrix<Scalar,1,1> m(raw), m1(raw[0]), m2( (DenseIndex(raw[0])) ), m3( (int(raw[0])) );\n    Array<Scalar,1,1> a(raw), a1(raw[0]), a2( (DenseIndex(raw[0])) );\n    VERIFY(m(0) == raw[0]);\n    VERIFY(a(0) == raw[0]);\n    VERIFY(m1(0) == raw[0]);\n    VERIFY(a1(0) == raw[0]);\n    VERIFY(m2(0) == DenseIndex(raw[0]));\n    VERIFY(a2(0) == DenseIndex(raw[0]));\n    VERIFY(m3(0) == int(raw[0]));\n    VERIFY_IS_EQUAL(m,(Matrix<Scalar,1,1>(raw[0])));\n    VERIFY((a==Array<Scalar,1,1>(raw[0])).all());\n  }\n}\n\nEIGEN_DECLARE_TEST(basicstuff)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( basicStuff(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( basicStuff(Matrix4d()) );\n    CALL_SUBTEST_3( basicStuff(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_4( basicStuff(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_5( basicStuff(MatrixXcd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( basicStuff(Matrix<float, 100, 100>()) );\n    CALL_SUBTEST_7( basicStuff(Matrix<long double,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE),internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_8( casting_all() );\n\n    CALL_SUBTEST_3( basicStuffComplex(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_5( basicStuffComplex(MatrixXcd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n\n  CALL_SUBTEST_1(fixedSizeMatrixConstruction<unsigned char>());\n  CALL_SUBTEST_1(fixedSizeMatrixConstruction<float>());\n  CALL_SUBTEST_1(fixedSizeMatrixConstruction<double>());\n  CALL_SUBTEST_1(fixedSizeMatrixConstruction<int>());\n  CALL_SUBTEST_1(fixedSizeMatrixConstruction<long int>());\n  CALL_SUBTEST_1(fixedSizeMatrixConstruction<std::ptrdiff_t>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/bdcsvd.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Gauthier Brun <brun.gauthier@gmail.com>\n// Copyright (C) 2013 Nicolas Carre <nicolas.carre@ensimag.fr>\n// Copyright (C) 2013 Jean Ceccato <jean.ceccato@ensimag.fr>\n// Copyright (C) 2013 Pierre Zoppitelli <pierre.zoppitelli@ensimag.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/\n\n// discard stack allocation as that too bypasses malloc\n#define EIGEN_STACK_ALLOCATION_LIMIT 0\n#define EIGEN_RUNTIME_NO_MALLOC\n\n#include \"main.h\"\n#include <Eigen/SVD>\n#include <iostream>\n#include <Eigen/LU>\n\n\n#define SVD_DEFAULT(M) BDCSVD<M>\n#define SVD_FOR_MIN_NORM(M) BDCSVD<M>\n#include \"svd_common.h\"\n\n// Check all variants of JacobiSVD\ntemplate<typename MatrixType>\nvoid bdcsvd(const MatrixType& a = MatrixType(), bool pickrandom = true)\n{\n  MatrixType m;\n  if(pickrandom) {\n    m.resizeLike(a);\n    svd_fill_random(m);\n  }\n  else\n    m = a;\n\n  CALL_SUBTEST(( svd_test_all_computation_options<BDCSVD<MatrixType> >(m, false)  ));\n}\n\ntemplate<typename MatrixType>\nvoid bdcsvd_method()\n{\n  enum { Size = MatrixType::RowsAtCompileTime };\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef Matrix<RealScalar, Size, 1> RealVecType;\n  MatrixType m = MatrixType::Identity();\n  VERIFY_IS_APPROX(m.bdcSvd().singularValues(), RealVecType::Ones());\n  VERIFY_RAISES_ASSERT(m.bdcSvd().matrixU());\n  VERIFY_RAISES_ASSERT(m.bdcSvd().matrixV());\n  VERIFY_IS_APPROX(m.bdcSvd(ComputeFullU|ComputeFullV).solve(m), m);\n  VERIFY_IS_APPROX(m.bdcSvd(ComputeFullU|ComputeFullV).transpose().solve(m), m);\n  VERIFY_IS_APPROX(m.bdcSvd(ComputeFullU|ComputeFullV).adjoint().solve(m), m);\n}\n\n// compare the Singular values returned with Jacobi and Bdc\ntemplate<typename MatrixType> \nvoid compare_bdc_jacobi(const MatrixType& a = MatrixType(), unsigned int computationOptions = 0)\n{\n  MatrixType m = MatrixType::Random(a.rows(), a.cols());\n  BDCSVD<MatrixType> bdc_svd(m);\n  JacobiSVD<MatrixType> jacobi_svd(m);\n  VERIFY_IS_APPROX(bdc_svd.singularValues(), jacobi_svd.singularValues());\n  if(computationOptions & ComputeFullU) VERIFY_IS_APPROX(bdc_svd.matrixU(), jacobi_svd.matrixU());\n  if(computationOptions & ComputeThinU) VERIFY_IS_APPROX(bdc_svd.matrixU(), jacobi_svd.matrixU());\n  if(computationOptions & ComputeFullV) VERIFY_IS_APPROX(bdc_svd.matrixV(), jacobi_svd.matrixV());\n  if(computationOptions & ComputeThinV) VERIFY_IS_APPROX(bdc_svd.matrixV(), jacobi_svd.matrixV());\n}\n\nEIGEN_DECLARE_TEST(bdcsvd)\n{\n  CALL_SUBTEST_3(( svd_verify_assert<BDCSVD<Matrix3f>  >(Matrix3f()) ));\n  CALL_SUBTEST_4(( svd_verify_assert<BDCSVD<Matrix4d>  >(Matrix4d()) ));\n  CALL_SUBTEST_7(( svd_verify_assert<BDCSVD<MatrixXf>  >(MatrixXf(10,12)) ));\n  CALL_SUBTEST_8(( svd_verify_assert<BDCSVD<MatrixXcd> >(MatrixXcd(7,5)) ));\n  \n  CALL_SUBTEST_101(( svd_all_trivial_2x2(bdcsvd<Matrix2cd>) ));\n  CALL_SUBTEST_102(( svd_all_trivial_2x2(bdcsvd<Matrix2d>) ));\n\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_3(( bdcsvd<Matrix3f>() ));\n    CALL_SUBTEST_4(( bdcsvd<Matrix4d>() ));\n    CALL_SUBTEST_5(( bdcsvd<Matrix<float,3,5> >() ));\n\n    int r = internal::random<int>(1, EIGEN_TEST_MAX_SIZE/2),\n        c = internal::random<int>(1, EIGEN_TEST_MAX_SIZE/2);\n    \n    TEST_SET_BUT_UNUSED_VARIABLE(r)\n    TEST_SET_BUT_UNUSED_VARIABLE(c)\n    \n    CALL_SUBTEST_6((  bdcsvd(Matrix<double,Dynamic,2>(r,2)) ));\n    CALL_SUBTEST_7((  bdcsvd(MatrixXf(r,c)) ));\n    CALL_SUBTEST_7((  compare_bdc_jacobi(MatrixXf(r,c)) ));\n    CALL_SUBTEST_10(( bdcsvd(MatrixXd(r,c)) ));\n    CALL_SUBTEST_10(( compare_bdc_jacobi(MatrixXd(r,c)) ));\n    CALL_SUBTEST_8((  bdcsvd(MatrixXcd(r,c)) ));\n    CALL_SUBTEST_8((  compare_bdc_jacobi(MatrixXcd(r,c)) ));\n\n    // Test on inf/nan matrix\n    CALL_SUBTEST_7(  (svd_inf_nan<BDCSVD<MatrixXf>, MatrixXf>()) );\n    CALL_SUBTEST_10( (svd_inf_nan<BDCSVD<MatrixXd>, MatrixXd>()) );\n  }\n\n  // test matrixbase method\n  CALL_SUBTEST_1(( bdcsvd_method<Matrix2cd>() ));\n  CALL_SUBTEST_3(( bdcsvd_method<Matrix3f>() ));\n\n  // Test problem size constructors\n  CALL_SUBTEST_7( BDCSVD<MatrixXf>(10,10) );\n\n  // Check that preallocation avoids subsequent mallocs\n  // Disabled because not supported by BDCSVD\n  // CALL_SUBTEST_9( svd_preallocate<void>() );\n\n  CALL_SUBTEST_2( svd_underoverflow<void>() );\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/bfloat16_float.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <sstream>\n#include <memory>\n#include <math.h>\n\n#include \"main.h\"\n\n#include <Eigen/src/Core/arch/Default/BFloat16.h>\n\n#define VERIFY_BFLOAT16_BITS_EQUAL(h, bits) \\\n  VERIFY_IS_EQUAL((numext::bit_cast<numext::uint16_t>(h)), (static_cast<numext::uint16_t>(bits)))\n\n// Make sure it's possible to forward declare Eigen::bfloat16\nnamespace Eigen {\nstruct bfloat16;\n}\n\nusing Eigen::bfloat16;\n\nfloat BinaryToFloat(uint32_t sign, uint32_t exponent, uint32_t high_mantissa,\n                    uint32_t low_mantissa) {\n  float dest;\n  uint32_t src = (sign << 31) + (exponent << 23) + (high_mantissa << 16) + low_mantissa;\n  memcpy(static_cast<void*>(&dest),\n         static_cast<const void*>(&src), sizeof(dest));\n  return dest;\n}\n\nvoid test_truncate(float input, float expected_truncation, float expected_rounding){\n  bfloat16 truncated = Eigen::bfloat16_impl::truncate_to_bfloat16(input);\n  bfloat16 rounded = Eigen::bfloat16_impl::float_to_bfloat16_rtne<false>(input);\n  if ((numext::isnan)(input)){\n    VERIFY((numext::isnan)(static_cast<float>(truncated)) || (numext::isinf)(static_cast<float>(truncated)));\n    VERIFY((numext::isnan)(static_cast<float>(rounded)) || (numext::isinf)(static_cast<float>(rounded)));\n    return;\n  }\n  VERIFY_IS_EQUAL(expected_truncation, static_cast<float>(truncated));\n  VERIFY_IS_EQUAL(expected_rounding, static_cast<float>(rounded));\n}\n\ntemplate<typename T>\n void test_roundtrip() {\n  // Representable T round trip via bfloat16\n  VERIFY_IS_EQUAL((internal::cast<bfloat16,T>(internal::cast<T,bfloat16>(-std::numeric_limits<T>::infinity()))), -std::numeric_limits<T>::infinity());\n  VERIFY_IS_EQUAL((internal::cast<bfloat16,T>(internal::cast<T,bfloat16>(std::numeric_limits<T>::infinity()))), std::numeric_limits<T>::infinity());\n  VERIFY_IS_EQUAL((internal::cast<bfloat16,T>(internal::cast<T,bfloat16>(T(-1.0)))), T(-1.0));\n  VERIFY_IS_EQUAL((internal::cast<bfloat16,T>(internal::cast<T,bfloat16>(T(-0.5)))), T(-0.5));\n  VERIFY_IS_EQUAL((internal::cast<bfloat16,T>(internal::cast<T,bfloat16>(T(-0.0)))), T(-0.0));\n  VERIFY_IS_EQUAL((internal::cast<bfloat16,T>(internal::cast<T,bfloat16>(T(1.0)))), T(1.0));\n  VERIFY_IS_EQUAL((internal::cast<bfloat16,T>(internal::cast<T,bfloat16>(T(0.5)))), T(0.5));\n  VERIFY_IS_EQUAL((internal::cast<bfloat16,T>(internal::cast<T,bfloat16>(T(0.0)))), T(0.0));\n}\n\nvoid test_conversion()\n{\n  using Eigen::bfloat16_impl::__bfloat16_raw;\n\n  // Round-trip casts\n  VERIFY_IS_EQUAL(\n    numext::bit_cast<bfloat16>(numext::bit_cast<numext::uint16_t>(bfloat16(1.0f))),\n    bfloat16(1.0f));\n  VERIFY_IS_EQUAL(\n    numext::bit_cast<bfloat16>(numext::bit_cast<numext::uint16_t>(bfloat16(0.5f))),\n    bfloat16(0.5f));\n  VERIFY_IS_EQUAL(\n    numext::bit_cast<bfloat16>(numext::bit_cast<numext::uint16_t>(bfloat16(-0.33333f))),\n    bfloat16(-0.33333f));\n   VERIFY_IS_EQUAL(\n    numext::bit_cast<bfloat16>(numext::bit_cast<numext::uint16_t>(bfloat16(0.0f))),\n    bfloat16(0.0f));\n\n  // Conversion from float.\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(1.0f), 0x3f80);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(0.5f), 0x3f00);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(0.33333f), 0x3eab);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(3.38e38f), 0x7f7e);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(3.40e38f), 0x7f80);  // Becomes infinity.\n\n  // Verify round-to-nearest-even behavior.\n  float val1 = static_cast<float>(bfloat16(__bfloat16_raw(0x3c00)));\n  float val2 = static_cast<float>(bfloat16(__bfloat16_raw(0x3c01)));\n  float val3 = static_cast<float>(bfloat16(__bfloat16_raw(0x3c02)));\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(0.5f * (val1 + val2)), 0x3c00);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(0.5f * (val2 + val3)), 0x3c02);\n\n  // Conversion from int.\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(-1), 0xbf80);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(0), 0x0000);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(1), 0x3f80);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(2), 0x4000);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(3), 0x4040);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(12), 0x4140);\n\n  // Conversion from bool.\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(false), 0x0000);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(true), 0x3f80);\n\n  // Conversion to bool\n  VERIFY_IS_EQUAL(static_cast<bool>(bfloat16(3)), true);\n  VERIFY_IS_EQUAL(static_cast<bool>(bfloat16(0.33333f)), true);\n  VERIFY_IS_EQUAL(bfloat16(-0.0), false);\n  VERIFY_IS_EQUAL(static_cast<bool>(bfloat16(0.0)), false);\n\n  // Explicit conversion to float.\n  VERIFY_IS_EQUAL(static_cast<float>(bfloat16(__bfloat16_raw(0x0000))), 0.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(bfloat16(__bfloat16_raw(0x3f80))), 1.0f);\n\n  // Implicit conversion to float\n  VERIFY_IS_EQUAL(bfloat16(__bfloat16_raw(0x0000)), 0.0f);\n  VERIFY_IS_EQUAL(bfloat16(__bfloat16_raw(0x3f80)), 1.0f);\n\n  // Zero representations\n  VERIFY_IS_EQUAL(bfloat16(0.0f), bfloat16(0.0f));\n  VERIFY_IS_EQUAL(bfloat16(-0.0f), bfloat16(0.0f));\n  VERIFY_IS_EQUAL(bfloat16(-0.0f), bfloat16(-0.0f));\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(0.0f), 0x0000);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(-0.0f), 0x8000);\n\n  // Flush denormals to zero\n  for (float denorm = -std::numeric_limits<float>::denorm_min();\n       denorm < std::numeric_limits<float>::denorm_min();\n       denorm = nextafterf(denorm, 1.0f)) {\n    bfloat16 bf_trunc = Eigen::bfloat16_impl::truncate_to_bfloat16(denorm);\n    VERIFY_IS_EQUAL(static_cast<float>(bf_trunc), 0.0f);\n\n    // Implicit conversion of denormls to bool is correct\n    VERIFY_IS_EQUAL(static_cast<bool>(bfloat16(denorm)), false);\n    VERIFY_IS_EQUAL(bfloat16(denorm), false);\n\n    if (std::signbit(denorm)) {\n      VERIFY_BFLOAT16_BITS_EQUAL(bf_trunc, 0x8000);\n    } else {\n      VERIFY_BFLOAT16_BITS_EQUAL(bf_trunc, 0x0000);\n    }\n    bfloat16 bf_round = Eigen::bfloat16_impl::float_to_bfloat16_rtne<false>(denorm);\n    VERIFY_IS_EQUAL(static_cast<float>(bf_round), 0.0f);\n    if (std::signbit(denorm)) {\n      VERIFY_BFLOAT16_BITS_EQUAL(bf_round, 0x8000);\n    } else {\n      VERIFY_BFLOAT16_BITS_EQUAL(bf_round, 0x0000);\n    }\n  }\n\n  // Default is zero\n  VERIFY_IS_EQUAL(static_cast<float>(bfloat16()), 0.0f);\n\n  // Representable floats round trip via bfloat16\n  test_roundtrip<float>();\n  test_roundtrip<double>();\n  test_roundtrip<std::complex<float> >();\n  test_roundtrip<std::complex<double> >();\n\n  // Truncate test\n  test_truncate(\n      BinaryToFloat(0, 0x80, 0x48, 0xf5c3),\n      BinaryToFloat(0, 0x80, 0x48, 0x0000),\n      BinaryToFloat(0, 0x80, 0x49, 0x0000));\n  test_truncate(\n      BinaryToFloat(1, 0x80, 0x48, 0xf5c3),\n      BinaryToFloat(1, 0x80, 0x48, 0x0000),\n      BinaryToFloat(1, 0x80, 0x49, 0x0000));\n  test_truncate(\n      BinaryToFloat(0, 0x80, 0x48, 0x8000),\n      BinaryToFloat(0, 0x80, 0x48, 0x0000),\n      BinaryToFloat(0, 0x80, 0x48, 0x0000));\n  test_truncate(\n      BinaryToFloat(0, 0xff, 0x00, 0x0001),\n      BinaryToFloat(0, 0xff, 0x40, 0x0000),\n      BinaryToFloat(0, 0xff, 0x40, 0x0000));\n  test_truncate(\n      BinaryToFloat(0, 0xff, 0x7f, 0xffff),\n      BinaryToFloat(0, 0xff, 0x40, 0x0000),\n      BinaryToFloat(0, 0xff, 0x40, 0x0000));\n  test_truncate(\n      BinaryToFloat(1, 0x80, 0x48, 0xc000),\n      BinaryToFloat(1, 0x80, 0x48, 0x0000),\n      BinaryToFloat(1, 0x80, 0x49, 0x0000));\n  test_truncate(\n      BinaryToFloat(0, 0x80, 0x48, 0x0000),\n      BinaryToFloat(0, 0x80, 0x48, 0x0000),\n      BinaryToFloat(0, 0x80, 0x48, 0x0000));\n  test_truncate(\n      BinaryToFloat(0, 0x80, 0x48, 0x4000),\n      BinaryToFloat(0, 0x80, 0x48, 0x0000),\n      BinaryToFloat(0, 0x80, 0x48, 0x0000));\n  test_truncate(\n      BinaryToFloat(0, 0x80, 0x48, 0x8000),\n      BinaryToFloat(0, 0x80, 0x48, 0x0000),\n      BinaryToFloat(0, 0x80, 0x48, 0x0000));\n  test_truncate(\n      BinaryToFloat(0, 0x00, 0x48, 0x8000),\n      BinaryToFloat(0, 0x00, 0x00, 0x0000),\n      BinaryToFloat(0, 0x00, 0x00, 0x0000));\n  test_truncate(\n      BinaryToFloat(0, 0x00, 0x7f, 0xc000),\n      BinaryToFloat(0, 0x00, 0x00, 0x0000),\n      BinaryToFloat(0, 0x00, 0x00, 0x0000));\n\n  // Conversion\n  Array<float,1,100> a;\n  for (int i = 0; i < 100; i++) a(i) = i + 1.25;\n  Array<bfloat16,1,100> b = a.cast<bfloat16>();\n  Array<float,1,100> c = b.cast<float>();\n  for (int i = 0; i < 100; ++i) {\n    VERIFY_LE(numext::abs(c(i) - a(i)), a(i) / 128);\n  }\n\n  // Epsilon\n  VERIFY_LE(1.0f, static_cast<float>((std::numeric_limits<bfloat16>::epsilon)() + bfloat16(1.0f)));\n  VERIFY_IS_EQUAL(1.0f, static_cast<float>((std::numeric_limits<bfloat16>::epsilon)() / bfloat16(2.0f) + bfloat16(1.0f)));\n\n  // Negate\n  VERIFY_IS_EQUAL(static_cast<float>(-bfloat16(3.0f)), -3.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(-bfloat16(-4.5f)), 4.5f);\n\n\n#if !EIGEN_COMP_MSVC\n  // Visual Studio errors out on divisions by 0\n  VERIFY((numext::isnan)(static_cast<float>(bfloat16(0.0 / 0.0))));\n  VERIFY((numext::isinf)(static_cast<float>(bfloat16(1.0 / 0.0))));\n  VERIFY((numext::isinf)(static_cast<float>(bfloat16(-1.0 / 0.0))));\n\n  // Visual Studio errors out on divisions by 0\n  VERIFY((numext::isnan)(bfloat16(0.0 / 0.0)));\n  VERIFY((numext::isinf)(bfloat16(1.0 / 0.0)));\n  VERIFY((numext::isinf)(bfloat16(-1.0 / 0.0)));\n#endif\n\n  // NaNs and infinities.\n  VERIFY(!(numext::isinf)(static_cast<float>(bfloat16(3.38e38f))));  // Largest finite number.\n  VERIFY(!(numext::isnan)(static_cast<float>(bfloat16(0.0f))));\n  VERIFY((numext::isinf)(static_cast<float>(bfloat16(__bfloat16_raw(0xff80)))));\n  VERIFY((numext::isnan)(static_cast<float>(bfloat16(__bfloat16_raw(0xffc0)))));\n  VERIFY((numext::isinf)(static_cast<float>(bfloat16(__bfloat16_raw(0x7f80)))));\n  VERIFY((numext::isnan)(static_cast<float>(bfloat16(__bfloat16_raw(0x7fc0)))));\n\n  // Exactly same checks as above, just directly on the bfloat16 representation.\n  VERIFY(!(numext::isinf)(bfloat16(__bfloat16_raw(0x7bff))));\n  VERIFY(!(numext::isnan)(bfloat16(__bfloat16_raw(0x0000))));\n  VERIFY((numext::isinf)(bfloat16(__bfloat16_raw(0xff80))));\n  VERIFY((numext::isnan)(bfloat16(__bfloat16_raw(0xffc0))));\n  VERIFY((numext::isinf)(bfloat16(__bfloat16_raw(0x7f80))));\n  VERIFY((numext::isnan)(bfloat16(__bfloat16_raw(0x7fc0))));\n\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(BinaryToFloat(0x0, 0xff, 0x40, 0x0)), 0x7fc0);\n  VERIFY_BFLOAT16_BITS_EQUAL(bfloat16(BinaryToFloat(0x1, 0xff, 0x40, 0x0)), 0xffc0);\n  VERIFY_BFLOAT16_BITS_EQUAL(Eigen::bfloat16_impl::truncate_to_bfloat16(\n                               BinaryToFloat(0x0, 0xff, 0x40, 0x0)),\n                             0x7fc0);\n  VERIFY_BFLOAT16_BITS_EQUAL(Eigen::bfloat16_impl::truncate_to_bfloat16(\n                               BinaryToFloat(0x1, 0xff, 0x40, 0x0)),\n                             0xffc0);\n}\n\nvoid test_numtraits()\n{\n  std::cout << \"epsilon       = \" << NumTraits<bfloat16>::epsilon() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(NumTraits<bfloat16>::epsilon()) << \")\" << std::endl;\n  std::cout << \"highest       = \" << NumTraits<bfloat16>::highest() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(NumTraits<bfloat16>::highest()) << \")\" << std::endl;\n  std::cout << \"lowest        = \" << NumTraits<bfloat16>::lowest() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(NumTraits<bfloat16>::lowest()) << \")\" << std::endl;\n  std::cout << \"min           = \" << (std::numeric_limits<bfloat16>::min)() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>((std::numeric_limits<bfloat16>::min)()) << \")\" << std::endl;\n  std::cout << \"denorm min    = \" << (std::numeric_limits<bfloat16>::denorm_min)() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>((std::numeric_limits<bfloat16>::denorm_min)()) << \")\" << std::endl;\n  std::cout << \"infinity      = \" << NumTraits<bfloat16>::infinity() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(NumTraits<bfloat16>::infinity()) << \")\" << std::endl;\n  std::cout << \"quiet nan     = \" << NumTraits<bfloat16>::quiet_NaN() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(NumTraits<bfloat16>::quiet_NaN()) << \")\" << std::endl;\n  std::cout << \"signaling nan = \" << std::numeric_limits<bfloat16>::signaling_NaN() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(std::numeric_limits<bfloat16>::signaling_NaN()) << \")\" << std::endl;\n\n  VERIFY(NumTraits<bfloat16>::IsSigned);\n\n  VERIFY_IS_EQUAL(\n    numext::bit_cast<numext::uint16_t>(std::numeric_limits<bfloat16>::infinity()),\n    numext::bit_cast<numext::uint16_t>(bfloat16(std::numeric_limits<float>::infinity())) );\n  // There is no guarantee that casting a 32-bit NaN to bfloat16 has a precise\n  // bit pattern.  We test that it is in fact a NaN, then test the signaling\n  // bit (msb of significand is 1 for quiet, 0 for signaling).\n  const numext::uint16_t BFLOAT16_QUIET_BIT = 0x0040;\n  VERIFY(\n    (numext::isnan)(std::numeric_limits<bfloat16>::quiet_NaN())\n    && (numext::isnan)(bfloat16(std::numeric_limits<float>::quiet_NaN()))\n    && ((numext::bit_cast<numext::uint16_t>(std::numeric_limits<bfloat16>::quiet_NaN()) & BFLOAT16_QUIET_BIT) > 0)\n    && ((numext::bit_cast<numext::uint16_t>(bfloat16(std::numeric_limits<float>::quiet_NaN())) & BFLOAT16_QUIET_BIT) > 0) );\n  // After a cast to bfloat16, a signaling NaN may become non-signaling. Thus,\n  // we check that both are NaN, and that only the `numeric_limits` version is\n  // signaling.\n  VERIFY(\n    (numext::isnan)(std::numeric_limits<bfloat16>::signaling_NaN())\n    && (numext::isnan)(bfloat16(std::numeric_limits<float>::signaling_NaN()))\n    && ((numext::bit_cast<numext::uint16_t>(std::numeric_limits<bfloat16>::signaling_NaN()) & BFLOAT16_QUIET_BIT) == 0) );\n\n  VERIFY( (std::numeric_limits<bfloat16>::min)() > bfloat16(0.f) );\n  VERIFY( (std::numeric_limits<bfloat16>::denorm_min)() > bfloat16(0.f) );\n  VERIFY_IS_EQUAL( (std::numeric_limits<bfloat16>::denorm_min)()/bfloat16(2), bfloat16(0.f) );\n}\n\nvoid test_arithmetic()\n{\n  VERIFY_IS_EQUAL(static_cast<float>(bfloat16(2) + bfloat16(2)), 4);\n  VERIFY_IS_EQUAL(static_cast<float>(bfloat16(2) + bfloat16(-2)), 0);\n  VERIFY_IS_APPROX(static_cast<float>(bfloat16(0.33333f) + bfloat16(0.66667f)), 1.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(bfloat16(2.0f) * bfloat16(-5.5f)), -11.0f);\n  VERIFY_IS_APPROX(static_cast<float>(bfloat16(1.0f) / bfloat16(3.0f)), 0.3339f);\n  VERIFY_IS_EQUAL(static_cast<float>(-bfloat16(4096.0f)), -4096.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(-bfloat16(-4096.0f)), 4096.0f);\n}\n\nvoid test_comparison()\n{\n  VERIFY(bfloat16(1.0f) > bfloat16(0.5f));\n  VERIFY(bfloat16(0.5f) < bfloat16(1.0f));\n  VERIFY(!(bfloat16(1.0f) < bfloat16(0.5f)));\n  VERIFY(!(bfloat16(0.5f) > bfloat16(1.0f)));\n\n  VERIFY(!(bfloat16(4.0f) > bfloat16(4.0f)));\n  VERIFY(!(bfloat16(4.0f) < bfloat16(4.0f)));\n\n  VERIFY(!(bfloat16(0.0f) < bfloat16(-0.0f)));\n  VERIFY(!(bfloat16(-0.0f) < bfloat16(0.0f)));\n  VERIFY(!(bfloat16(0.0f) > bfloat16(-0.0f)));\n  VERIFY(!(bfloat16(-0.0f) > bfloat16(0.0f)));\n\n  VERIFY(bfloat16(0.2f) > bfloat16(-1.0f));\n  VERIFY(bfloat16(-1.0f) < bfloat16(0.2f));\n  VERIFY(bfloat16(-16.0f) < bfloat16(-15.0f));\n\n  VERIFY(bfloat16(1.0f) == bfloat16(1.0f));\n  VERIFY(bfloat16(1.0f) != bfloat16(2.0f));\n\n  // Comparisons with NaNs and infinities.\n#if !EIGEN_COMP_MSVC\n  // Visual Studio errors out on divisions by 0\n  VERIFY(!(bfloat16(0.0 / 0.0) == bfloat16(0.0 / 0.0)));\n  VERIFY(bfloat16(0.0 / 0.0) != bfloat16(0.0 / 0.0));\n\n  VERIFY(!(bfloat16(1.0) == bfloat16(0.0 / 0.0)));\n  VERIFY(!(bfloat16(1.0) < bfloat16(0.0 / 0.0)));\n  VERIFY(!(bfloat16(1.0) > bfloat16(0.0 / 0.0)));\n  VERIFY(bfloat16(1.0) != bfloat16(0.0 / 0.0));\n\n  VERIFY(bfloat16(1.0) < bfloat16(1.0 / 0.0));\n  VERIFY(bfloat16(1.0) > bfloat16(-1.0 / 0.0));\n#endif\n}\n\nvoid test_basic_functions()\n{\n  VERIFY_IS_EQUAL(static_cast<float>(numext::abs(bfloat16(3.5f))), 3.5f);\n  VERIFY_IS_EQUAL(static_cast<float>(abs(bfloat16(3.5f))), 3.5f);\n  VERIFY_IS_EQUAL(static_cast<float>(numext::abs(bfloat16(-3.5f))), 3.5f);\n  VERIFY_IS_EQUAL(static_cast<float>(abs(bfloat16(-3.5f))), 3.5f);\n\n  VERIFY_IS_EQUAL(static_cast<float>(numext::floor(bfloat16(3.5f))), 3.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(floor(bfloat16(3.5f))), 3.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(numext::floor(bfloat16(-3.5f))), -4.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(floor(bfloat16(-3.5f))), -4.0f);\n\n  VERIFY_IS_EQUAL(static_cast<float>(numext::ceil(bfloat16(3.5f))), 4.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(ceil(bfloat16(3.5f))), 4.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(numext::ceil(bfloat16(-3.5f))), -3.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(ceil(bfloat16(-3.5f))), -3.0f);\n\n  VERIFY_IS_APPROX(static_cast<float>(numext::sqrt(bfloat16(0.0f))), 0.0f);\n  VERIFY_IS_APPROX(static_cast<float>(sqrt(bfloat16(0.0f))), 0.0f);\n  VERIFY_IS_APPROX(static_cast<float>(numext::sqrt(bfloat16(4.0f))), 2.0f);\n  VERIFY_IS_APPROX(static_cast<float>(sqrt(bfloat16(4.0f))), 2.0f);\n\n  VERIFY_IS_APPROX(static_cast<float>(numext::pow(bfloat16(0.0f), bfloat16(1.0f))), 0.0f);\n  VERIFY_IS_APPROX(static_cast<float>(pow(bfloat16(0.0f), bfloat16(1.0f))), 0.0f);\n  VERIFY_IS_APPROX(static_cast<float>(numext::pow(bfloat16(2.0f), bfloat16(2.0f))), 4.0f);\n  VERIFY_IS_APPROX(static_cast<float>(pow(bfloat16(2.0f), bfloat16(2.0f))), 4.0f);\n\n  VERIFY_IS_EQUAL(static_cast<float>(numext::exp(bfloat16(0.0f))), 1.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(exp(bfloat16(0.0f))), 1.0f);\n  VERIFY_IS_APPROX(static_cast<float>(numext::exp(bfloat16(EIGEN_PI))), 20.f + static_cast<float>(EIGEN_PI));\n  VERIFY_IS_APPROX(static_cast<float>(exp(bfloat16(EIGEN_PI))), 20.f + static_cast<float>(EIGEN_PI));\n\n  VERIFY_IS_EQUAL(static_cast<float>(numext::expm1(bfloat16(0.0f))), 0.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(expm1(bfloat16(0.0f))), 0.0f);\n  VERIFY_IS_APPROX(static_cast<float>(numext::expm1(bfloat16(2.0f))), 6.375f);\n  VERIFY_IS_APPROX(static_cast<float>(expm1(bfloat16(2.0f))), 6.375f);\n\n  VERIFY_IS_EQUAL(static_cast<float>(numext::log(bfloat16(1.0f))), 0.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(log(bfloat16(1.0f))), 0.0f);\n  VERIFY_IS_APPROX(static_cast<float>(numext::log(bfloat16(10.0f))), 2.296875f);\n  VERIFY_IS_APPROX(static_cast<float>(log(bfloat16(10.0f))), 2.296875f);\n\n  VERIFY_IS_EQUAL(static_cast<float>(numext::log1p(bfloat16(0.0f))), 0.0f);\n  VERIFY_IS_EQUAL(static_cast<float>(log1p(bfloat16(0.0f))), 0.0f);\n  VERIFY_IS_APPROX(static_cast<float>(numext::log1p(bfloat16(10.0f))), 2.390625f);\n  VERIFY_IS_APPROX(static_cast<float>(log1p(bfloat16(10.0f))), 2.390625f);\n}\n\nvoid test_trigonometric_functions()\n{\n  VERIFY_IS_APPROX(numext::cos(bfloat16(0.0f)), bfloat16(cosf(0.0f)));\n  VERIFY_IS_APPROX(cos(bfloat16(0.0f)), bfloat16(cosf(0.0f)));\n  VERIFY_IS_APPROX(numext::cos(bfloat16(EIGEN_PI)), bfloat16(cosf(EIGEN_PI)));\n  // VERIFY_IS_APPROX(numext::cos(bfloat16(EIGEN_PI/2)), bfloat16(cosf(EIGEN_PI/2)));\n  // VERIFY_IS_APPROX(numext::cos(bfloat16(3*EIGEN_PI/2)), bfloat16(cosf(3*EIGEN_PI/2)));\n  VERIFY_IS_APPROX(numext::cos(bfloat16(3.5f)), bfloat16(cosf(3.5f)));\n\n  VERIFY_IS_APPROX(numext::sin(bfloat16(0.0f)), bfloat16(sinf(0.0f)));\n  VERIFY_IS_APPROX(sin(bfloat16(0.0f)), bfloat16(sinf(0.0f)));\n  // VERIFY_IS_APPROX(numext::sin(bfloat16(EIGEN_PI)), bfloat16(sinf(EIGEN_PI)));\n  VERIFY_IS_APPROX(numext::sin(bfloat16(EIGEN_PI/2)), bfloat16(sinf(EIGEN_PI/2)));\n  VERIFY_IS_APPROX(numext::sin(bfloat16(3*EIGEN_PI/2)), bfloat16(sinf(3*EIGEN_PI/2)));\n  VERIFY_IS_APPROX(numext::sin(bfloat16(3.5f)), bfloat16(sinf(3.5f)));\n\n  VERIFY_IS_APPROX(numext::tan(bfloat16(0.0f)), bfloat16(tanf(0.0f)));\n  VERIFY_IS_APPROX(tan(bfloat16(0.0f)), bfloat16(tanf(0.0f)));\n  // VERIFY_IS_APPROX(numext::tan(bfloat16(EIGEN_PI)), bfloat16(tanf(EIGEN_PI)));\n  // VERIFY_IS_APPROX(numext::tan(bfloat16(EIGEN_PI/2)), bfloat16(tanf(EIGEN_PI/2)));\n  // VERIFY_IS_APPROX(numext::tan(bfloat16(3*EIGEN_PI/2)), bfloat16(tanf(3*EIGEN_PI/2)));\n  VERIFY_IS_APPROX(numext::tan(bfloat16(3.5f)), bfloat16(tanf(3.5f)));\n}\n\nvoid test_array()\n{\n  typedef Array<bfloat16,1,Dynamic> ArrayXh;\n  Index size = internal::random<Index>(1,10);\n  Index i = internal::random<Index>(0,size-1);\n  ArrayXh a1 = ArrayXh::Random(size), a2 = ArrayXh::Random(size);\n  VERIFY_IS_APPROX( a1+a1, bfloat16(2)*a1 );\n  VERIFY( (a1.abs() >= bfloat16(0)).all() );\n  VERIFY_IS_APPROX( (a1*a1).sqrt(), a1.abs() );\n\n  VERIFY( ((a1.min)(a2) <= (a1.max)(a2)).all() );\n  a1(i) = bfloat16(-10.);\n  VERIFY_IS_EQUAL( a1.minCoeff(), bfloat16(-10.) );\n  a1(i) = bfloat16(10.);\n  VERIFY_IS_EQUAL( a1.maxCoeff(), bfloat16(10.) );\n\n  std::stringstream ss;\n  ss << a1;\n}\n\nvoid test_product()\n{\n  typedef Matrix<bfloat16,Dynamic,Dynamic> MatrixXh;\n  Index rows  = internal::random<Index>(1,EIGEN_TEST_MAX_SIZE);\n  Index cols  = internal::random<Index>(1,EIGEN_TEST_MAX_SIZE);\n  Index depth = internal::random<Index>(1,EIGEN_TEST_MAX_SIZE);\n  MatrixXh Ah = MatrixXh::Random(rows,depth);\n  MatrixXh Bh = MatrixXh::Random(depth,cols);\n  MatrixXh Ch = MatrixXh::Random(rows,cols);\n  MatrixXf Af = Ah.cast<float>();\n  MatrixXf Bf = Bh.cast<float>();\n  MatrixXf Cf = Ch.cast<float>();\n  VERIFY_IS_APPROX(Ch.noalias()+=Ah*Bh, (Cf.noalias()+=Af*Bf).cast<bfloat16>());\n}\n\nEIGEN_DECLARE_TEST(bfloat16_float)\n{\n  CALL_SUBTEST(test_numtraits());\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST(test_conversion());\n    CALL_SUBTEST(test_arithmetic());\n    CALL_SUBTEST(test_comparison());\n    CALL_SUBTEST(test_basic_functions());\n    CALL_SUBTEST(test_trigonometric_functions());\n    CALL_SUBTEST(test_array());\n    CALL_SUBTEST(test_product());\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/bicgstab.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"sparse_solver.h\"\n#include <Eigen/IterativeLinearSolvers>\n\ntemplate<typename T, typename I_> void test_bicgstab_T()\n{\n  BiCGSTAB<SparseMatrix<T,0,I_>, DiagonalPreconditioner<T> >     bicgstab_colmajor_diag;\n  BiCGSTAB<SparseMatrix<T,0,I_>, IdentityPreconditioner    >     bicgstab_colmajor_I;\n  BiCGSTAB<SparseMatrix<T,0,I_>, IncompleteLUT<T,I_> >              bicgstab_colmajor_ilut;\n  //BiCGSTAB<SparseMatrix<T>, SSORPreconditioner<T> >     bicgstab_colmajor_ssor;\n\n  bicgstab_colmajor_diag.setTolerance(NumTraits<T>::epsilon()*4);\n  bicgstab_colmajor_ilut.setTolerance(NumTraits<T>::epsilon()*4);\n  \n  CALL_SUBTEST( check_sparse_square_solving(bicgstab_colmajor_diag)  );\n//   CALL_SUBTEST( check_sparse_square_solving(bicgstab_colmajor_I)     );\n  CALL_SUBTEST( check_sparse_square_solving(bicgstab_colmajor_ilut)     );\n  //CALL_SUBTEST( check_sparse_square_solving(bicgstab_colmajor_ssor)     );\n}\n\nEIGEN_DECLARE_TEST(bicgstab)\n{\n  CALL_SUBTEST_1((test_bicgstab_T<double,int>()) );\n  CALL_SUBTEST_2((test_bicgstab_T<std::complex<double>, int>()));\n  CALL_SUBTEST_3((test_bicgstab_T<double,long int>()));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/blasutil.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2020 Everton Constantino <everton.constantino@ibm.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/\n\n#include \"main.h\"\n\n// Disable \"ignoring attributes on template argument\"\n// for packet_traits<Packet*>\n// => The only workaround would be to wrap _m128 and the likes\n//    within wrappers.\n#if EIGEN_GNUC_AT_LEAST(6,0)\n    #pragma GCC diagnostic ignored \"-Wignored-attributes\"\n#endif\n\n#define GET(i,j) (StorageOrder == RowMajor ? (i)*stride + (j) : (i) + (j)*stride)\n#define SCATTER(i,j,k) (StorageOrder == RowMajor ? ((i)+(k))*stride + (j) : (i) + ((j)+(k))*stride)\n\ntemplate<typename Scalar, typename Packet>\nvoid compare(const Packet& a, const Packet& b)\n{\n    int pktsz = internal::packet_traits<Scalar>::size;\n    Scalar *buffA = new Scalar[pktsz];\n    Scalar *buffB = new Scalar[pktsz];\n\n    internal::pstoreu<Scalar, Packet>(buffA, a);\n    internal::pstoreu<Scalar, Packet>(buffB, b);\n\n    for(int i = 0; i < pktsz; i++)\n    {\n        VERIFY_IS_EQUAL(buffA[i], buffB[i]);\n    }\n\n    delete[] buffA;\n    delete[] buffB;\n}\n\ntemplate<typename Scalar, int StorageOrder, int n>\nstruct PacketBlockSet\n{\n    typedef typename internal::packet_traits<Scalar>::type Packet;\n\n    void setPacketBlock(internal::PacketBlock<Packet,n>& block, Scalar value)\n    {\n        for(int idx = 0; idx < n; idx++)\n        {\n            block.packet[idx] = internal::pset1<Packet>(value);\n        }\n    }\n\n    void comparePacketBlock(Scalar *data, int i, int j, int stride, internal::PacketBlock<Packet, n>& block)\n    {\n        for(int idx = 0; idx < n; idx++)\n        {\n            Packet line = internal::ploadu<Packet>(data + SCATTER(i,j,idx));\n            compare<Scalar, Packet>(block.packet[idx], line);\n        }\n    }\n};\n\ntemplate<typename Scalar, int StorageOrder, int BlockSize>\nvoid run_bdmp_spec_1()\n{\n    typedef internal::blas_data_mapper<Scalar, int, StorageOrder> BlasDataMapper;\n    int packetSize = internal::packet_traits<Scalar>::size;\n    int minSize = std::max<int>(packetSize, BlockSize);\n    typedef typename internal::packet_traits<Scalar>::type Packet;\n\n    int szm = internal::random<int>(minSize,500), szn = internal::random<int>(minSize,500);\n    int stride = StorageOrder == RowMajor ? szn : szm;\n    Scalar *d = new Scalar[szn*szm];\n\n    // Initializing with random entries\n    for(int i = 0; i < szm*szn; i++)\n    {\n        d[i] = internal::random<Scalar>(static_cast<Scalar>(3), static_cast<Scalar>(10));\n    }\n\n    BlasDataMapper bdm(d, stride);\n\n    // Testing operator()\n    for(int i = 0; i < szm; i++)\n    {\n        for(int j = 0; j < szn; j++)\n        {\n            VERIFY_IS_EQUAL(d[GET(i,j)], bdm(i,j));\n        }\n    }\n\n    // Testing getSubMapper and getLinearMapper\n    int i0 = internal::random<int>(0,szm-2);\n    int j0 = internal::random<int>(0,szn-2);\n    for(int i = i0; i < szm; i++)\n    {\n        for(int j = j0; j < szn; j++)\n        {\n            const BlasDataMapper& bdmSM = bdm.getSubMapper(i0,j0);\n            const internal::BlasLinearMapper<Scalar, int, 0>& bdmLM = bdm.getLinearMapper(i0,j0);\n\n            Scalar v = bdmSM(i - i0, j - j0);\n            Scalar vd = d[GET(i,j)];\n            VERIFY_IS_EQUAL(vd, v);\n            VERIFY_IS_EQUAL(vd, bdmLM(GET(i-i0, j-j0)));\n        }\n    }\n\n    // Testing loadPacket\n    for(int i = 0; i < szm - minSize; i++)\n    {\n        for(int j = 0; j < szn - minSize; j++)\n        {\n            Packet pktBDM = bdm.template loadPacket<Packet>(i,j);\n            Packet pktD = internal::ploadu<Packet>(d + GET(i,j));\n\n            compare<Scalar, Packet>(pktBDM, pktD);\n        }\n    }\n\n    // Testing gatherPacket\n    Scalar *buff = new Scalar[packetSize];\n    for(int i = 0; i < szm - minSize; i++)\n    {\n        for(int j = 0; j < szn - minSize; j++)\n        {\n            Packet p = bdm.template gatherPacket<Packet>(i,j);\n            internal::pstoreu<Scalar, Packet>(buff, p);\n\n            for(int k = 0; k < packetSize; k++)\n            {\n                VERIFY_IS_EQUAL(d[SCATTER(i,j,k)], buff[k]);\n            }\n\n        }\n    }\n    delete[] buff;\n\n    // Testing scatterPacket\n    for(int i = 0; i < szm - minSize; i++)\n    {\n        for(int j = 0; j < szn - minSize; j++)\n        {\n            Packet p = internal::pset1<Packet>(static_cast<Scalar>(1));\n            bdm.template scatterPacket<Packet>(i,j,p);\n            for(int k = 0; k < packetSize; k++)\n            {\n                VERIFY_IS_EQUAL(d[SCATTER(i,j,k)], static_cast<Scalar>(1));\n            }\n        }\n    }\n\n    //Testing storePacketBlock\n    internal::PacketBlock<Packet, BlockSize> block;\n\n    PacketBlockSet<Scalar, StorageOrder, BlockSize> pbs;\n    pbs.setPacketBlock(block, static_cast<Scalar>(2));\n\n    for(int i = 0; i < szm - minSize; i++)\n    {\n        for(int j = 0; j < szn - minSize; j++)\n        {\n            bdm.template storePacketBlock<Packet, BlockSize>(i, j, block);\n\n            pbs.comparePacketBlock(d, i, j, stride, block);\n        }\n    }\n\n    delete[] d;\n}\n\ntemplate<typename Scalar>\nvoid run_test()\n{\n    run_bdmp_spec_1<Scalar, RowMajor, 1>();\n    run_bdmp_spec_1<Scalar, ColMajor, 1>();\n    run_bdmp_spec_1<Scalar, RowMajor, 2>();\n    run_bdmp_spec_1<Scalar, ColMajor, 2>();\n    run_bdmp_spec_1<Scalar, RowMajor, 4>();\n    run_bdmp_spec_1<Scalar, ColMajor, 4>();\n    run_bdmp_spec_1<Scalar, RowMajor, 8>();\n    run_bdmp_spec_1<Scalar, ColMajor, 8>();\n    run_bdmp_spec_1<Scalar, RowMajor, 16>();\n    run_bdmp_spec_1<Scalar, ColMajor, 16>();\n}\n\nEIGEN_DECLARE_TEST(blasutil)\n{\n    for(int i = 0; i < g_repeat; i++)\n    {\n        CALL_SUBTEST_1(run_test<numext::int8_t>());\n        CALL_SUBTEST_2(run_test<numext::int16_t>());\n        CALL_SUBTEST_3(run_test<numext::int32_t>());\n\n// TODO: Replace this by a call to numext::int64_t as soon as we have a way to\n// detect the typedef for int64_t on all platforms\n#if EIGEN_HAS_CXX11\n        CALL_SUBTEST_4(run_test<signed long long>());\n#else\n        CALL_SUBTEST_4(run_test<signed long>());\n#endif\n\n        CALL_SUBTEST_5(run_test<float_t>());\n        CALL_SUBTEST_6(run_test<double_t>());\n        CALL_SUBTEST_7(run_test<std::complex<float> >());\n        CALL_SUBTEST_8(run_test<std::complex<double> >());\n    }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/block.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_STATIC_ASSERT // otherwise we fail at compile time on unused paths\n#include \"main.h\"\n\ntemplate<typename MatrixType, typename Index, typename Scalar>\ntypename Eigen::internal::enable_if<!NumTraits<typename MatrixType::Scalar>::IsComplex,typename MatrixType::Scalar>::type\nblock_real_only(const MatrixType &m1, Index r1, Index r2, Index c1, Index c2, const Scalar& s1) {\n  // check cwise-Functions:\n  VERIFY_IS_APPROX(m1.row(r1).cwiseMax(s1), m1.cwiseMax(s1).row(r1));\n  VERIFY_IS_APPROX(m1.col(c1).cwiseMin(s1), m1.cwiseMin(s1).col(c1));\n\n  VERIFY_IS_APPROX(m1.block(r1,c1,r2-r1+1,c2-c1+1).cwiseMin(s1), m1.cwiseMin(s1).block(r1,c1,r2-r1+1,c2-c1+1));\n  VERIFY_IS_APPROX(m1.block(r1,c1,r2-r1+1,c2-c1+1).cwiseMax(s1), m1.cwiseMax(s1).block(r1,c1,r2-r1+1,c2-c1+1));\n  \n  return Scalar(0);\n}\n\ntemplate<typename MatrixType, typename Index, typename Scalar>\ntypename Eigen::internal::enable_if<NumTraits<typename MatrixType::Scalar>::IsComplex,typename MatrixType::Scalar>::type\nblock_real_only(const MatrixType &, Index, Index, Index, Index, const Scalar&) {\n  return Scalar(0);\n}\n\n// Check at compile-time that T1==T2, and at runtime-time that a==b\ntemplate<typename T1,typename T2>\ntypename internal::enable_if<internal::is_same<T1,T2>::value,bool>::type\nis_same_block(const T1& a, const T2& b)\n{\n  return a.isApprox(b);\n}\n\ntemplate<typename MatrixType> void block(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n  typedef Matrix<Scalar, 1, MatrixType::ColsAtCompileTime> RowVectorType;\n  typedef Matrix<Scalar, Dynamic, Dynamic, MatrixType::IsRowMajor?RowMajor:ColMajor> DynamicMatrixType;\n  typedef Matrix<Scalar, Dynamic, 1> DynamicVectorType;\n  \n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m1_copy = m1,\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols),\n             ones = MatrixType::Ones(rows, cols);\n  VectorType v1 = VectorType::Random(rows);\n\n  Scalar s1 = internal::random<Scalar>();\n\n  Index r1 = internal::random<Index>(0,rows-1);\n  Index r2 = internal::random<Index>(r1,rows-1);\n  Index c1 = internal::random<Index>(0,cols-1);\n  Index c2 = internal::random<Index>(c1,cols-1);\n\n  block_real_only(m1, r1, r2, c1, c1, s1);\n\n  //check row() and col()\n  VERIFY_IS_EQUAL(m1.col(c1).transpose(), m1.transpose().row(c1));\n  //check operator(), both constant and non-constant, on row() and col()\n  m1 = m1_copy;\n  m1.row(r1) += s1 * m1_copy.row(r2);\n  VERIFY_IS_APPROX(m1.row(r1), m1_copy.row(r1) + s1 * m1_copy.row(r2));\n  // check nested block xpr on lhs\n  m1.row(r1).row(0) += s1 * m1_copy.row(r2);\n  VERIFY_IS_APPROX(m1.row(r1), m1_copy.row(r1) + Scalar(2) * s1 * m1_copy.row(r2));\n  m1 = m1_copy;\n  m1.col(c1) += s1 * m1_copy.col(c2);\n  VERIFY_IS_APPROX(m1.col(c1), m1_copy.col(c1) + s1 * m1_copy.col(c2));\n  m1.col(c1).col(0) += s1 * m1_copy.col(c2);\n  VERIFY_IS_APPROX(m1.col(c1), m1_copy.col(c1) + Scalar(2) * s1 * m1_copy.col(c2));\n  \n  \n  //check block()\n  Matrix<Scalar,Dynamic,Dynamic> b1(1,1); b1(0,0) = m1(r1,c1);\n\n  RowVectorType br1(m1.block(r1,0,1,cols));\n  VectorType bc1(m1.block(0,c1,rows,1));\n  VERIFY_IS_EQUAL(b1, m1.block(r1,c1,1,1));\n  VERIFY_IS_EQUAL(m1.row(r1), br1);\n  VERIFY_IS_EQUAL(m1.col(c1), bc1);\n  //check operator(), both constant and non-constant, on block()\n  m1.block(r1,c1,r2-r1+1,c2-c1+1) = s1 * m2.block(0, 0, r2-r1+1,c2-c1+1);\n  m1.block(r1,c1,r2-r1+1,c2-c1+1)(r2-r1,c2-c1) = m2.block(0, 0, r2-r1+1,c2-c1+1)(0,0);\n\n  const Index BlockRows = 2;\n  const Index BlockCols = 5;\n\n  if (rows>=5 && cols>=8)\n  {\n    // test fixed block() as lvalue\n    m1.template block<BlockRows,BlockCols>(1,1) *= s1;\n    // test operator() on fixed block() both as constant and non-constant\n    m1.template block<BlockRows,BlockCols>(1,1)(0, 3) = m1.template block<2,5>(1,1)(1,2);\n    // check that fixed block() and block() agree\n    Matrix<Scalar,Dynamic,Dynamic> b = m1.template block<BlockRows,BlockCols>(3,3);\n    VERIFY_IS_EQUAL(b, m1.block(3,3,BlockRows,BlockCols));\n\n    // same tests with mixed fixed/dynamic size\n    m1.template block<BlockRows,Dynamic>(1,1,BlockRows,BlockCols) *= s1;\n    m1.template block<BlockRows,Dynamic>(1,1,BlockRows,BlockCols)(0,3) = m1.template block<2,5>(1,1)(1,2);\n    Matrix<Scalar,Dynamic,Dynamic> b2 = m1.template block<Dynamic,BlockCols>(3,3,2,5);\n    VERIFY_IS_EQUAL(b2, m1.block(3,3,BlockRows,BlockCols));\n\n    VERIFY(is_same_block(m1.block(3,3,BlockRows,BlockCols), m1.block(3,3,fix<Dynamic>(BlockRows),fix<Dynamic>(BlockCols))));\n    VERIFY(is_same_block(m1.template block<BlockRows,Dynamic>(1,1,BlockRows,BlockCols), m1.block(1,1,fix<BlockRows>,BlockCols)));\n    VERIFY(is_same_block(m1.template block<BlockRows,BlockCols>(1,1,BlockRows,BlockCols), m1.block(1,1,fix<BlockRows>(),fix<BlockCols>)));\n    VERIFY(is_same_block(m1.template block<BlockRows,BlockCols>(1,1,BlockRows,BlockCols), m1.block(1,1,fix<BlockRows>,fix<BlockCols>(BlockCols))));\n  }\n\n  if (rows>2)\n  {\n    // test sub vectors\n    VERIFY_IS_EQUAL(v1.template head<2>(), v1.block(0,0,2,1));\n    VERIFY_IS_EQUAL(v1.template head<2>(), v1.head(2));\n    VERIFY_IS_EQUAL(v1.template head<2>(), v1.segment(0,2));\n    VERIFY_IS_EQUAL(v1.template head<2>(), v1.template segment<2>(0));\n    Index i = rows-2;\n    VERIFY_IS_EQUAL(v1.template tail<2>(), v1.block(i,0,2,1));\n    VERIFY_IS_EQUAL(v1.template tail<2>(), v1.tail(2));\n    VERIFY_IS_EQUAL(v1.template tail<2>(), v1.segment(i,2));\n    VERIFY_IS_EQUAL(v1.template tail<2>(), v1.template segment<2>(i));\n    i = internal::random<Index>(0,rows-2);\n    VERIFY_IS_EQUAL(v1.segment(i,2), v1.template segment<2>(i));\n  }\n\n  // stress some basic stuffs with block matrices\n  VERIFY(numext::real(ones.col(c1).sum()) == RealScalar(rows));\n  VERIFY(numext::real(ones.row(r1).sum()) == RealScalar(cols));\n\n  VERIFY(numext::real(ones.col(c1).dot(ones.col(c2))) == RealScalar(rows));\n  VERIFY(numext::real(ones.row(r1).dot(ones.row(r2))) == RealScalar(cols));\n  \n  // check that linear acccessors works on blocks\n  m1 = m1_copy;\n  if((MatrixType::Flags&RowMajorBit)==0)\n    VERIFY_IS_EQUAL(m1.leftCols(c1).coeff(r1+c1*rows), m1(r1,c1));\n  else\n    VERIFY_IS_EQUAL(m1.topRows(r1).coeff(c1+r1*cols), m1(r1,c1));\n  \n\n  // now test some block-inside-of-block.\n  \n  // expressions with direct access\n  VERIFY_IS_EQUAL( (m1.block(r1,c1,rows-r1,cols-c1).block(r2-r1,c2-c1,rows-r2,cols-c2)) , (m1.block(r2,c2,rows-r2,cols-c2)) );\n  VERIFY_IS_EQUAL( (m1.block(r1,c1,r2-r1+1,c2-c1+1).row(0)) , (m1.row(r1).segment(c1,c2-c1+1)) );\n  VERIFY_IS_EQUAL( (m1.block(r1,c1,r2-r1+1,c2-c1+1).col(0)) , (m1.col(c1).segment(r1,r2-r1+1)) );\n  VERIFY_IS_EQUAL( (m1.block(r1,c1,r2-r1+1,c2-c1+1).transpose().col(0)) , (m1.row(r1).segment(c1,c2-c1+1)).transpose() );\n  VERIFY_IS_EQUAL( (m1.transpose().block(c1,r1,c2-c1+1,r2-r1+1).col(0)) , (m1.row(r1).segment(c1,c2-c1+1)).transpose() );\n\n  // expressions without direct access\n  VERIFY_IS_APPROX( ((m1+m2).block(r1,c1,rows-r1,cols-c1).block(r2-r1,c2-c1,rows-r2,cols-c2)) , ((m1+m2).block(r2,c2,rows-r2,cols-c2)) );\n  VERIFY_IS_APPROX( ((m1+m2).block(r1,c1,r2-r1+1,c2-c1+1).row(0)) , ((m1+m2).row(r1).segment(c1,c2-c1+1)) );\n  VERIFY_IS_APPROX( ((m1+m2).block(r1,c1,r2-r1+1,c2-c1+1).row(0)) , ((m1+m2).eval().row(r1).segment(c1,c2-c1+1)) );\n  VERIFY_IS_APPROX( ((m1+m2).block(r1,c1,r2-r1+1,c2-c1+1).col(0)) , ((m1+m2).col(c1).segment(r1,r2-r1+1)) );\n  VERIFY_IS_APPROX( ((m1+m2).block(r1,c1,r2-r1+1,c2-c1+1).transpose().col(0)) , ((m1+m2).row(r1).segment(c1,c2-c1+1)).transpose() );\n  VERIFY_IS_APPROX( ((m1+m2).transpose().block(c1,r1,c2-c1+1,r2-r1+1).col(0)) , ((m1+m2).row(r1).segment(c1,c2-c1+1)).transpose() );\n  VERIFY_IS_APPROX( ((m1+m2).template block<Dynamic,1>(r1,c1,r2-r1+1,1)) , ((m1+m2).eval().col(c1).eval().segment(r1,r2-r1+1)) );\n  VERIFY_IS_APPROX( ((m1+m2).template block<1,Dynamic>(r1,c1,1,c2-c1+1)) , ((m1+m2).eval().row(r1).eval().segment(c1,c2-c1+1)) );\n  VERIFY_IS_APPROX( ((m1+m2).transpose().template block<1,Dynamic>(c1,r1,1,r2-r1+1)) , ((m1+m2).eval().col(c1).eval().segment(r1,r2-r1+1)).transpose() );\n  VERIFY_IS_APPROX( (m1+m2).row(r1).eval(), (m1+m2).eval().row(r1) );\n  VERIFY_IS_APPROX( (m1+m2).adjoint().col(r1).eval(), (m1+m2).adjoint().eval().col(r1) );\n  VERIFY_IS_APPROX( (m1+m2).adjoint().row(c1).eval(), (m1+m2).adjoint().eval().row(c1) );\n  VERIFY_IS_APPROX( (m1*1).row(r1).segment(c1,c2-c1+1).eval(), m1.row(r1).eval().segment(c1,c2-c1+1).eval() );\n  VERIFY_IS_APPROX( m1.col(c1).reverse().segment(r1,r2-r1+1).eval(),m1.col(c1).reverse().eval().segment(r1,r2-r1+1).eval() );\n\n  VERIFY_IS_APPROX( (m1*1).topRows(r1),  m1.topRows(r1) );\n  VERIFY_IS_APPROX( (m1*1).leftCols(c1), m1.leftCols(c1) );\n  VERIFY_IS_APPROX( (m1*1).transpose().topRows(c1), m1.transpose().topRows(c1) );\n  VERIFY_IS_APPROX( (m1*1).transpose().leftCols(r1), m1.transpose().leftCols(r1) );\n  VERIFY_IS_APPROX( (m1*1).transpose().middleRows(c1,c2-c1+1), m1.transpose().middleRows(c1,c2-c1+1) );\n  VERIFY_IS_APPROX( (m1*1).transpose().middleCols(r1,r2-r1+1), m1.transpose().middleCols(r1,r2-r1+1) );\n\n  // evaluation into plain matrices from expressions with direct access (stress MapBase)\n  DynamicMatrixType dm;\n  DynamicVectorType dv;\n  dm.setZero();\n  dm = m1.block(r1,c1,rows-r1,cols-c1).block(r2-r1,c2-c1,rows-r2,cols-c2);\n  VERIFY_IS_EQUAL(dm, (m1.block(r2,c2,rows-r2,cols-c2)));\n  dm.setZero();\n  dv.setZero();\n  dm = m1.block(r1,c1,r2-r1+1,c2-c1+1).row(0).transpose();\n  dv = m1.row(r1).segment(c1,c2-c1+1);\n  VERIFY_IS_EQUAL(dv, dm);\n  dm.setZero();\n  dv.setZero();\n  dm = m1.col(c1).segment(r1,r2-r1+1);\n  dv = m1.block(r1,c1,r2-r1+1,c2-c1+1).col(0);\n  VERIFY_IS_EQUAL(dv, dm);\n  dm.setZero();\n  dv.setZero();\n  dm = m1.block(r1,c1,r2-r1+1,c2-c1+1).transpose().col(0);\n  dv = m1.row(r1).segment(c1,c2-c1+1);\n  VERIFY_IS_EQUAL(dv, dm);\n  dm.setZero();\n  dv.setZero();\n  dm = m1.row(r1).segment(c1,c2-c1+1).transpose();\n  dv = m1.transpose().block(c1,r1,c2-c1+1,r2-r1+1).col(0);\n  VERIFY_IS_EQUAL(dv, dm);\n\n  VERIFY_IS_EQUAL( (m1.template block<Dynamic,1>(1,0,0,1)), m1.block(1,0,0,1));\n  VERIFY_IS_EQUAL( (m1.template block<1,Dynamic>(0,1,1,0)), m1.block(0,1,1,0));\n  VERIFY_IS_EQUAL( ((m1*1).template block<Dynamic,1>(1,0,0,1)), m1.block(1,0,0,1));\n  VERIFY_IS_EQUAL( ((m1*1).template block<1,Dynamic>(0,1,1,0)), m1.block(0,1,1,0));\n\n  if (rows>=2 && cols>=2)\n  {\n    VERIFY_RAISES_ASSERT( m1 += m1.col(0) );\n    VERIFY_RAISES_ASSERT( m1 -= m1.col(0) );\n    VERIFY_RAISES_ASSERT( m1.array() *= m1.col(0).array() );\n    VERIFY_RAISES_ASSERT( m1.array() /= m1.col(0).array() );\n  }\n\n  VERIFY_IS_EQUAL( m1.template subVector<Horizontal>(r1), m1.row(r1) );\n  VERIFY_IS_APPROX( (m1+m1).template subVector<Horizontal>(r1), (m1+m1).row(r1) );\n  VERIFY_IS_EQUAL( m1.template subVector<Vertical>(c1), m1.col(c1) );\n  VERIFY_IS_APPROX( (m1+m1).template subVector<Vertical>(c1), (m1+m1).col(c1) );\n  VERIFY_IS_EQUAL( m1.template subVectors<Horizontal>(), m1.rows() );\n  VERIFY_IS_EQUAL( m1.template subVectors<Vertical>(), m1.cols() );\n\n  if (rows>=2 || cols>=2) {\n    VERIFY_IS_EQUAL( int(m1.middleCols(0,0).IsRowMajor), int(m1.IsRowMajor) );\n    VERIFY_IS_EQUAL( m1.middleCols(0,0).outerSize(), m1.IsRowMajor ? rows : 0);\n    VERIFY_IS_EQUAL( m1.middleCols(0,0).innerSize(), m1.IsRowMajor ? 0 : rows);\n\n    VERIFY_IS_EQUAL( int(m1.middleRows(0,0).IsRowMajor), int(m1.IsRowMajor) );\n    VERIFY_IS_EQUAL( m1.middleRows(0,0).outerSize(), m1.IsRowMajor ? 0 : cols);\n    VERIFY_IS_EQUAL( m1.middleRows(0,0).innerSize(), m1.IsRowMajor ? cols : 0);\n  }\n}\n\n\ntemplate<typename MatrixType>\nvoid compare_using_data_and_stride(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n  Index size = m.size();\n  Index innerStride = m.innerStride();\n  Index outerStride = m.outerStride();\n  Index rowStride = m.rowStride();\n  Index colStride = m.colStride();\n  const typename MatrixType::Scalar* data = m.data();\n\n  for(int j=0;j<cols;++j)\n    for(int i=0;i<rows;++i)\n      VERIFY(m.coeff(i,j) == data[i*rowStride + j*colStride]);\n\n  if(!MatrixType::IsVectorAtCompileTime)\n  {\n    for(int j=0;j<cols;++j)\n      for(int i=0;i<rows;++i)\n        VERIFY(m.coeff(i,j) == data[(MatrixType::Flags&RowMajorBit)\n                                     ? i*outerStride + j*innerStride\n                                     : j*outerStride + i*innerStride]);\n  }\n\n  if(MatrixType::IsVectorAtCompileTime)\n  {\n    VERIFY(innerStride == int((&m.coeff(1))-(&m.coeff(0))));\n    for (int i=0;i<size;++i)\n      VERIFY(m.coeff(i) == data[i*innerStride]);\n  }\n}\n\ntemplate<typename MatrixType>\nvoid data_and_stride(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  Index r1 = internal::random<Index>(0,rows-1);\n  Index r2 = internal::random<Index>(r1,rows-1);\n  Index c1 = internal::random<Index>(0,cols-1);\n  Index c2 = internal::random<Index>(c1,cols-1);\n\n  MatrixType m1 = MatrixType::Random(rows, cols);\n  compare_using_data_and_stride(m1.block(r1, c1, r2-r1+1, c2-c1+1));\n  compare_using_data_and_stride(m1.transpose().block(c1, r1, c2-c1+1, r2-r1+1));\n  compare_using_data_and_stride(m1.row(r1));\n  compare_using_data_and_stride(m1.col(c1));\n  compare_using_data_and_stride(m1.row(r1).transpose());\n  compare_using_data_and_stride(m1.col(c1).transpose());\n}\n\nEIGEN_DECLARE_TEST(block)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( block(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_1( block(Matrix<float, 1, Dynamic>(internal::random(2,50))) );\n    CALL_SUBTEST_1( block(Matrix<float, Dynamic, 1>(internal::random(2,50))) );\n    CALL_SUBTEST_2( block(Matrix4d()) );\n    CALL_SUBTEST_3( block(MatrixXcf(internal::random(2,50), internal::random(2,50))) );\n    CALL_SUBTEST_4( block(MatrixXi(internal::random(2,50), internal::random(2,50))) );\n    CALL_SUBTEST_5( block(MatrixXcd(internal::random(2,50), internal::random(2,50))) );\n    CALL_SUBTEST_6( block(MatrixXf(internal::random(2,50), internal::random(2,50))) );\n    CALL_SUBTEST_7( block(Matrix<int,Dynamic,Dynamic,RowMajor>(internal::random(2,50), internal::random(2,50))) );\n\n    CALL_SUBTEST_8( block(Matrix<float,Dynamic,4>(3, 4)) );\n\n#ifndef EIGEN_DEFAULT_TO_ROW_MAJOR\n    CALL_SUBTEST_6( data_and_stride(MatrixXf(internal::random(5,50), internal::random(5,50))) );\n    CALL_SUBTEST_7( data_and_stride(Matrix<int,Dynamic,Dynamic,RowMajor>(internal::random(5,50), internal::random(5,50))) );\n#endif\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/boostmultiprec.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <sstream>\n\n#ifdef EIGEN_TEST_MAX_SIZE\n#undef EIGEN_TEST_MAX_SIZE\n#endif\n\n#define EIGEN_TEST_MAX_SIZE 50\n\n#ifdef EIGEN_TEST_PART_1\n#include \"cholesky.cpp\"\n#endif\n\n#ifdef EIGEN_TEST_PART_2\n#include \"lu.cpp\"\n#endif\n\n#ifdef EIGEN_TEST_PART_3\n#include \"qr.cpp\"\n#endif\n\n#ifdef EIGEN_TEST_PART_4\n#include \"qr_colpivoting.cpp\"\n#endif\n\n#ifdef EIGEN_TEST_PART_5\n#include \"qr_fullpivoting.cpp\"\n#endif\n\n#ifdef EIGEN_TEST_PART_6\n#include \"eigensolver_selfadjoint.cpp\"\n#endif\n\n#ifdef EIGEN_TEST_PART_7\n#include \"eigensolver_generic.cpp\"\n#endif\n\n#ifdef EIGEN_TEST_PART_8\n#include \"eigensolver_generalized_real.cpp\"\n#endif\n\n#ifdef EIGEN_TEST_PART_9\n#include \"jacobisvd.cpp\"\n#endif\n\n#ifdef EIGEN_TEST_PART_10\n#include \"bdcsvd.cpp\"\n#endif\n\n#ifdef EIGEN_TEST_PART_11\n#include \"simplicial_cholesky.cpp\"\n#endif\n\n#include <Eigen/Dense>\n\n#undef min\n#undef max\n#undef isnan\n#undef isinf\n#undef isfinite\n#undef I\n\n#include <boost/serialization/nvp.hpp>\n#include <boost/multiprecision/cpp_dec_float.hpp>\n#include <boost/multiprecision/number.hpp>\n#include <boost/math/special_functions.hpp>\n#include <boost/math/complex.hpp>\n\nnamespace mp = boost::multiprecision;\ntypedef mp::number<mp::cpp_dec_float<100>, mp::et_on> Real;\n\nnamespace Eigen {\n  template<> struct NumTraits<Real> : GenericNumTraits<Real> {\n    static inline Real dummy_precision() { return 1e-50; }\n  };\n\n  template<typename T1,typename T2,typename T3,typename T4,typename T5>\n  struct NumTraits<boost::multiprecision::detail::expression<T1,T2,T3,T4,T5> > : NumTraits<Real> {};\n\n  template<>\n  Real test_precision<Real>() { return 1e-50; }\n\n  // needed in C++93 mode where number does not support explicit cast.\n  namespace internal {\n    template<typename NewType>\n    struct cast_impl<Real,NewType> {\n      static inline NewType run(const Real& x) {\n        return x.template convert_to<NewType>();\n      }\n    };\n\n    template<>\n    struct cast_impl<Real,std::complex<Real> > {\n      static inline std::complex<Real>  run(const Real& x) {\n        return std::complex<Real>(x);\n      }\n    };\n  }\n}\n\nnamespace boost {\nnamespace multiprecision {\n  // to make ADL works as expected:\n  using boost::math::isfinite;\n  using boost::math::isnan;\n  using boost::math::isinf;\n  using boost::math::copysign;\n  using boost::math::hypot;\n\n  // The following is needed for std::complex<Real>:\n  Real fabs(const Real& a) { return abs EIGEN_NOT_A_MACRO (a); }\n  Real fmax(const Real& a, const Real& b) { using std::max; return max(a,b); }\n\n  // some specialization for the unit tests:\n  inline bool test_isMuchSmallerThan(const Real& a, const Real& b) {\n    return internal::isMuchSmallerThan(a, b, test_precision<Real>());\n  }\n\n  inline bool test_isApprox(const Real& a, const Real& b) {\n    return internal::isApprox(a, b, test_precision<Real>());\n  }\n\n  inline bool test_isApproxOrLessThan(const Real& a, const Real& b) {\n    return internal::isApproxOrLessThan(a, b, test_precision<Real>());\n  }\n\n  Real get_test_precision(const Real&) {\n    return test_precision<Real>();\n  }\n\n  Real test_relative_error(const Real &a, const Real &b) {\n    using Eigen::numext::abs2;\n    return sqrt(abs2<Real>(a-b)/Eigen::numext::mini<Real>(abs2(a),abs2(b)));\n  }\n}\n}\n\nnamespace Eigen {\n\n}\n\nEIGEN_DECLARE_TEST(boostmultiprec)\n{\n  typedef Matrix<Real,Dynamic,Dynamic> Mat;\n  typedef Matrix<std::complex<Real>,Dynamic,Dynamic> MatC;\n\n  std::cout << \"NumTraits<Real>::epsilon()         = \" << NumTraits<Real>::epsilon() << std::endl;\n  std::cout << \"NumTraits<Real>::dummy_precision() = \" << NumTraits<Real>::dummy_precision() << std::endl;\n  std::cout << \"NumTraits<Real>::lowest()          = \" << NumTraits<Real>::lowest() << std::endl;\n  std::cout << \"NumTraits<Real>::highest()         = \" << NumTraits<Real>::highest() << std::endl;\n  std::cout << \"NumTraits<Real>::digits10()        = \" << NumTraits<Real>::digits10() << std::endl;\n\n  // check stream output\n  {\n    Mat A(10,10);\n    A.setRandom();\n    std::stringstream ss;\n    ss << A;\n  }\n  {\n    MatC A(10,10);\n    A.setRandom();\n    std::stringstream ss;\n    ss << A;\n  }\n\n  for(int i = 0; i < g_repeat; i++) {\n    int s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE);\n\n    CALL_SUBTEST_1( cholesky(Mat(s,s)) );\n\n    CALL_SUBTEST_2( lu_non_invertible<Mat>() );\n    CALL_SUBTEST_2( lu_invertible<Mat>() );\n    CALL_SUBTEST_2( lu_non_invertible<MatC>() );\n    CALL_SUBTEST_2( lu_invertible<MatC>() );\n\n    CALL_SUBTEST_3( qr(Mat(internal::random<int>(1,EIGEN_TEST_MAX_SIZE),internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_3( qr_invertible<Mat>() );\n\n    CALL_SUBTEST_4( qr<Mat>() );\n    CALL_SUBTEST_4( cod<Mat>() );\n    CALL_SUBTEST_4( qr_invertible<Mat>() );\n\n    CALL_SUBTEST_5( qr<Mat>() );\n    CALL_SUBTEST_5( qr_invertible<Mat>() );\n\n    CALL_SUBTEST_6( selfadjointeigensolver(Mat(s,s)) );\n\n    CALL_SUBTEST_7( eigensolver(Mat(s,s)) );\n\n    CALL_SUBTEST_8( generalized_eigensolver_real(Mat(s,s)) );\n\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n  }\n\n  CALL_SUBTEST_9(( jacobisvd(Mat(internal::random<int>(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE), internal::random<int>(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/2))) ));\n  CALL_SUBTEST_10(( bdcsvd(Mat(internal::random<int>(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE), internal::random<int>(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/2))) ));\n\n  CALL_SUBTEST_11(( test_simplicial_cholesky_T<Real,int,ColMajor>() ));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/bug1213.cpp",
    "content": "\n// This anonymous enum is essential to trigger the linking issue\nenum {\n  Foo\n};\n\n#include \"bug1213.h\"\n\nbool bug1213_1(const Eigen::Vector3f& x)\n{\n  return bug1213_2(x);\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/bug1213.h",
    "content": "\n#include <Eigen/Core>\n\ntemplate<typename T, int dim>\nbool bug1213_2(const Eigen::Matrix<T,dim,1>& x);\n\nbool bug1213_1(const Eigen::Vector3f& x);\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/bug1213_main.cpp",
    "content": "\n// This is a regression unit regarding a weird linking issue with gcc.\n\n#include \"bug1213.h\"\n\nint main()\n{\n  return 0;\n}\n\n\ntemplate<typename T, int dim>\nbool bug1213_2(const Eigen::Matrix<T,dim,1>& )\n{\n  return true;\n}\n\ntemplate bool bug1213_2<float,3>(const Eigen::Vector3f&);\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/cholesky.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define TEST_ENABLE_TEMPORARY_TRACKING\n\n#include \"main.h\"\n#include <Eigen/Cholesky>\n#include <Eigen/QR>\n#include \"solverbase.h\"\n\ntemplate<typename MatrixType, int UpLo>\ntypename MatrixType::RealScalar matrix_l1_norm(const MatrixType& m) {\n  if(m.cols()==0) return typename MatrixType::RealScalar(0);\n  MatrixType symm = m.template selfadjointView<UpLo>();\n  return symm.cwiseAbs().colwise().sum().maxCoeff();\n}\n\ntemplate<typename MatrixType,template <typename,int> class CholType> void test_chol_update(const MatrixType& symm)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n\n  MatrixType symmLo = symm.template triangularView<Lower>();\n  MatrixType symmUp = symm.template triangularView<Upper>();\n  MatrixType symmCpy = symm;\n\n  CholType<MatrixType,Lower> chollo(symmLo);\n  CholType<MatrixType,Upper> cholup(symmUp);\n\n  for (int k=0; k<10; ++k)\n  {\n    VectorType vec = VectorType::Random(symm.rows());\n    RealScalar sigma = internal::random<RealScalar>();\n    symmCpy += sigma * vec * vec.adjoint();\n\n    // we are doing some downdates, so it might be the case that the matrix is not SPD anymore\n    CholType<MatrixType,Lower> chol(symmCpy);\n    if(chol.info()!=Success)\n      break;\n\n    chollo.rankUpdate(vec, sigma);\n    VERIFY_IS_APPROX(symmCpy, chollo.reconstructedMatrix());\n\n    cholup.rankUpdate(vec, sigma);\n    VERIFY_IS_APPROX(symmCpy, cholup.reconstructedMatrix());\n  }\n}\n\ntemplate<typename MatrixType> void cholesky(const MatrixType& m)\n{\n  /* this test covers the following files:\n     LLT.h LDLT.h\n  */\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> SquareMatrixType;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n\n  MatrixType a0 = MatrixType::Random(rows,cols);\n  VectorType vecB = VectorType::Random(rows), vecX(rows);\n  MatrixType matB = MatrixType::Random(rows,cols), matX(rows,cols);\n  SquareMatrixType symm =  a0 * a0.adjoint();\n  // let's make sure the matrix is not singular or near singular\n  for (int k=0; k<3; ++k)\n  {\n    MatrixType a1 = MatrixType::Random(rows,cols);\n    symm += a1 * a1.adjoint();\n  }\n\n  {\n    STATIC_CHECK(( internal::is_same<typename LLT<MatrixType,Lower>::StorageIndex,int>::value ));\n    STATIC_CHECK(( internal::is_same<typename LLT<MatrixType,Upper>::StorageIndex,int>::value ));\n\n    SquareMatrixType symmUp = symm.template triangularView<Upper>();\n    SquareMatrixType symmLo = symm.template triangularView<Lower>();\n\n    LLT<SquareMatrixType,Lower> chollo(symmLo);\n    VERIFY_IS_APPROX(symm, chollo.reconstructedMatrix());\n\n    check_solverbase<VectorType, VectorType>(symm, chollo, rows, rows, 1);\n    check_solverbase<MatrixType, MatrixType>(symm, chollo, rows, cols, rows);\n\n    const MatrixType symmLo_inverse = chollo.solve(MatrixType::Identity(rows,cols));\n    RealScalar rcond = (RealScalar(1) / matrix_l1_norm<MatrixType, Lower>(symmLo)) /\n                             matrix_l1_norm<MatrixType, Lower>(symmLo_inverse);\n    RealScalar rcond_est = chollo.rcond();\n    // Verify that the estimated condition number is within a factor of 10 of the\n    // truth.\n    VERIFY(rcond_est >= rcond / 10 && rcond_est <= rcond * 10);\n\n    // test the upper mode\n    LLT<SquareMatrixType,Upper> cholup(symmUp);\n    VERIFY_IS_APPROX(symm, cholup.reconstructedMatrix());\n    vecX = cholup.solve(vecB);\n    VERIFY_IS_APPROX(symm * vecX, vecB);\n    matX = cholup.solve(matB);\n    VERIFY_IS_APPROX(symm * matX, matB);\n\n    // Verify that the estimated condition number is within a factor of 10 of the\n    // truth.\n    const MatrixType symmUp_inverse = cholup.solve(MatrixType::Identity(rows,cols));\n    rcond = (RealScalar(1) / matrix_l1_norm<MatrixType, Upper>(symmUp)) /\n                             matrix_l1_norm<MatrixType, Upper>(symmUp_inverse);\n    rcond_est = cholup.rcond();\n    VERIFY(rcond_est >= rcond / 10 && rcond_est <= rcond * 10);\n\n\n    MatrixType neg = -symmLo;\n    chollo.compute(neg);\n    VERIFY(neg.size()==0 || chollo.info()==NumericalIssue);\n\n    VERIFY_IS_APPROX(MatrixType(chollo.matrixL().transpose().conjugate()), MatrixType(chollo.matrixU()));\n    VERIFY_IS_APPROX(MatrixType(chollo.matrixU().transpose().conjugate()), MatrixType(chollo.matrixL()));\n    VERIFY_IS_APPROX(MatrixType(cholup.matrixL().transpose().conjugate()), MatrixType(cholup.matrixU()));\n    VERIFY_IS_APPROX(MatrixType(cholup.matrixU().transpose().conjugate()), MatrixType(cholup.matrixL()));\n\n    // test some special use cases of SelfCwiseBinaryOp:\n    MatrixType m1 = MatrixType::Random(rows,cols), m2(rows,cols);\n    m2 = m1;\n    m2 += symmLo.template selfadjointView<Lower>().llt().solve(matB);\n    VERIFY_IS_APPROX(m2, m1 + symmLo.template selfadjointView<Lower>().llt().solve(matB));\n    m2 = m1;\n    m2 -= symmLo.template selfadjointView<Lower>().llt().solve(matB);\n    VERIFY_IS_APPROX(m2, m1 - symmLo.template selfadjointView<Lower>().llt().solve(matB));\n    m2 = m1;\n    m2.noalias() += symmLo.template selfadjointView<Lower>().llt().solve(matB);\n    VERIFY_IS_APPROX(m2, m1 + symmLo.template selfadjointView<Lower>().llt().solve(matB));\n    m2 = m1;\n    m2.noalias() -= symmLo.template selfadjointView<Lower>().llt().solve(matB);\n    VERIFY_IS_APPROX(m2, m1 - symmLo.template selfadjointView<Lower>().llt().solve(matB));\n  }\n\n  // LDLT\n  {\n    STATIC_CHECK(( internal::is_same<typename LDLT<MatrixType,Lower>::StorageIndex,int>::value ));\n    STATIC_CHECK(( internal::is_same<typename LDLT<MatrixType,Upper>::StorageIndex,int>::value ));\n\n    int sign = internal::random<int>()%2 ? 1 : -1;\n\n    if(sign == -1)\n    {\n      symm = -symm; // test a negative matrix\n    }\n\n    SquareMatrixType symmUp = symm.template triangularView<Upper>();\n    SquareMatrixType symmLo = symm.template triangularView<Lower>();\n\n    LDLT<SquareMatrixType,Lower> ldltlo(symmLo);\n    VERIFY(ldltlo.info()==Success);\n    VERIFY_IS_APPROX(symm, ldltlo.reconstructedMatrix());\n\n    check_solverbase<VectorType, VectorType>(symm, ldltlo, rows, rows, 1);\n    check_solverbase<MatrixType, MatrixType>(symm, ldltlo, rows, cols, rows);\n\n    const MatrixType symmLo_inverse = ldltlo.solve(MatrixType::Identity(rows,cols));\n    RealScalar rcond = (RealScalar(1) / matrix_l1_norm<MatrixType, Lower>(symmLo)) /\n                             matrix_l1_norm<MatrixType, Lower>(symmLo_inverse);\n    RealScalar rcond_est = ldltlo.rcond();\n    // Verify that the estimated condition number is within a factor of 10 of the\n    // truth.\n    VERIFY(rcond_est >= rcond / 10 && rcond_est <= rcond * 10);\n\n\n    LDLT<SquareMatrixType,Upper> ldltup(symmUp);\n    VERIFY(ldltup.info()==Success);\n    VERIFY_IS_APPROX(symm, ldltup.reconstructedMatrix());\n    vecX = ldltup.solve(vecB);\n    VERIFY_IS_APPROX(symm * vecX, vecB);\n    matX = ldltup.solve(matB);\n    VERIFY_IS_APPROX(symm * matX, matB);\n\n    // Verify that the estimated condition number is within a factor of 10 of the\n    // truth.\n    const MatrixType symmUp_inverse = ldltup.solve(MatrixType::Identity(rows,cols));\n    rcond = (RealScalar(1) / matrix_l1_norm<MatrixType, Upper>(symmUp)) /\n                             matrix_l1_norm<MatrixType, Upper>(symmUp_inverse);\n    rcond_est = ldltup.rcond();\n    VERIFY(rcond_est >= rcond / 10 && rcond_est <= rcond * 10);\n\n    VERIFY_IS_APPROX(MatrixType(ldltlo.matrixL().transpose().conjugate()), MatrixType(ldltlo.matrixU()));\n    VERIFY_IS_APPROX(MatrixType(ldltlo.matrixU().transpose().conjugate()), MatrixType(ldltlo.matrixL()));\n    VERIFY_IS_APPROX(MatrixType(ldltup.matrixL().transpose().conjugate()), MatrixType(ldltup.matrixU()));\n    VERIFY_IS_APPROX(MatrixType(ldltup.matrixU().transpose().conjugate()), MatrixType(ldltup.matrixL()));\n\n    if(MatrixType::RowsAtCompileTime==Dynamic)\n    {\n      // note : each inplace permutation requires a small temporary vector (mask)\n\n      // check inplace solve\n      matX = matB;\n      VERIFY_EVALUATION_COUNT(matX = ldltlo.solve(matX), 0);\n      VERIFY_IS_APPROX(matX, ldltlo.solve(matB).eval());\n\n\n      matX = matB;\n      VERIFY_EVALUATION_COUNT(matX = ldltup.solve(matX), 0);\n      VERIFY_IS_APPROX(matX, ldltup.solve(matB).eval());\n    }\n\n    // restore\n    if(sign == -1)\n      symm = -symm;\n\n    // check matrices coming from linear constraints with Lagrange multipliers\n    if(rows>=3)\n    {\n      SquareMatrixType A = symm;\n      Index c = internal::random<Index>(0,rows-2);\n      A.bottomRightCorner(c,c).setZero();\n      // Make sure a solution exists:\n      vecX.setRandom();\n      vecB = A * vecX;\n      vecX.setZero();\n      ldltlo.compute(A);\n      VERIFY_IS_APPROX(A, ldltlo.reconstructedMatrix());\n      vecX = ldltlo.solve(vecB);\n      VERIFY_IS_APPROX(A * vecX, vecB);\n    }\n\n    // check non-full rank matrices\n    if(rows>=3)\n    {\n      Index r = internal::random<Index>(1,rows-1);\n      Matrix<Scalar,Dynamic,Dynamic> a = Matrix<Scalar,Dynamic,Dynamic>::Random(rows,r);\n      SquareMatrixType A = a * a.adjoint();\n      // Make sure a solution exists:\n      vecX.setRandom();\n      vecB = A * vecX;\n      vecX.setZero();\n      ldltlo.compute(A);\n      VERIFY_IS_APPROX(A, ldltlo.reconstructedMatrix());\n      vecX = ldltlo.solve(vecB);\n      VERIFY_IS_APPROX(A * vecX, vecB);\n    }\n\n    // check matrices with a wide spectrum\n    if(rows>=3)\n    {\n      using std::pow;\n      using std::sqrt;\n      RealScalar s = (std::min)(16,std::numeric_limits<RealScalar>::max_exponent10/8);\n      Matrix<Scalar,Dynamic,Dynamic> a = Matrix<Scalar,Dynamic,Dynamic>::Random(rows,rows);\n      Matrix<RealScalar,Dynamic,1> d =  Matrix<RealScalar,Dynamic,1>::Random(rows);\n      for(Index k=0; k<rows; ++k)\n        d(k) = d(k)*pow(RealScalar(10),internal::random<RealScalar>(-s,s));\n      SquareMatrixType A = a * d.asDiagonal() * a.adjoint();\n      // Make sure a solution exists:\n      vecX.setRandom();\n      vecB = A * vecX;\n      vecX.setZero();\n      ldltlo.compute(A);\n      VERIFY_IS_APPROX(A, ldltlo.reconstructedMatrix());\n      vecX = ldltlo.solve(vecB);\n\n      if(ldltlo.vectorD().real().cwiseAbs().minCoeff()>RealScalar(0))\n      {\n        VERIFY_IS_APPROX(A * vecX,vecB);\n      }\n      else\n      {\n        RealScalar large_tol =  sqrt(test_precision<RealScalar>());\n        VERIFY((A * vecX).isApprox(vecB, large_tol));\n\n        ++g_test_level;\n        VERIFY_IS_APPROX(A * vecX,vecB);\n        --g_test_level;\n      }\n    }\n  }\n\n  // update/downdate\n  CALL_SUBTEST(( test_chol_update<SquareMatrixType,LLT>(symm)  ));\n  CALL_SUBTEST(( test_chol_update<SquareMatrixType,LDLT>(symm) ));\n}\n\ntemplate<typename MatrixType> void cholesky_cplx(const MatrixType& m)\n{\n  // classic test\n  cholesky(m);\n\n  // test mixing real/scalar types\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<RealScalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> RealMatrixType;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n\n  RealMatrixType a0 = RealMatrixType::Random(rows,cols);\n  VectorType vecB = VectorType::Random(rows), vecX(rows);\n  MatrixType matB = MatrixType::Random(rows,cols), matX(rows,cols);\n  RealMatrixType symm =  a0 * a0.adjoint();\n  // let's make sure the matrix is not singular or near singular\n  for (int k=0; k<3; ++k)\n  {\n    RealMatrixType a1 = RealMatrixType::Random(rows,cols);\n    symm += a1 * a1.adjoint();\n  }\n\n  {\n    RealMatrixType symmLo = symm.template triangularView<Lower>();\n\n    LLT<RealMatrixType,Lower> chollo(symmLo);\n    VERIFY_IS_APPROX(symm, chollo.reconstructedMatrix());\n\n    check_solverbase<VectorType, VectorType>(symm, chollo, rows, rows, 1);\n    //check_solverbase<MatrixType, MatrixType>(symm, chollo, rows, cols, rows);\n  }\n\n  // LDLT\n  {\n    int sign = internal::random<int>()%2 ? 1 : -1;\n\n    if(sign == -1)\n    {\n      symm = -symm; // test a negative matrix\n    }\n\n    RealMatrixType symmLo = symm.template triangularView<Lower>();\n\n    LDLT<RealMatrixType,Lower> ldltlo(symmLo);\n    VERIFY(ldltlo.info()==Success);\n    VERIFY_IS_APPROX(symm, ldltlo.reconstructedMatrix());\n\n    check_solverbase<VectorType, VectorType>(symm, ldltlo, rows, rows, 1);\n    //check_solverbase<MatrixType, MatrixType>(symm, ldltlo, rows, cols, rows);\n  }\n}\n\n// regression test for bug 241\ntemplate<typename MatrixType> void cholesky_bug241(const MatrixType& m)\n{\n  eigen_assert(m.rows() == 2 && m.cols() == 2);\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n\n  MatrixType matA;\n  matA << 1, 1, 1, 1;\n  VectorType vecB;\n  vecB << 1, 1;\n  VectorType vecX = matA.ldlt().solve(vecB);\n  VERIFY_IS_APPROX(matA * vecX, vecB);\n}\n\n// LDLT is not guaranteed to work for indefinite matrices, but happens to work fine if matrix is diagonal.\n// This test checks that LDLT reports correctly that matrix is indefinite.\n// See http://forum.kde.org/viewtopic.php?f=74&t=106942 and bug 736\ntemplate<typename MatrixType> void cholesky_definiteness(const MatrixType& m)\n{\n  eigen_assert(m.rows() == 2 && m.cols() == 2);\n  MatrixType mat;\n  LDLT<MatrixType> ldlt(2);\n\n  {\n    mat << 1, 0, 0, -1;\n    ldlt.compute(mat);\n    VERIFY(ldlt.info()==Success);\n    VERIFY(!ldlt.isNegative());\n    VERIFY(!ldlt.isPositive());\n    VERIFY_IS_APPROX(mat,ldlt.reconstructedMatrix());\n  }\n  {\n    mat << 1, 2, 2, 1;\n    ldlt.compute(mat);\n    VERIFY(ldlt.info()==Success);\n    VERIFY(!ldlt.isNegative());\n    VERIFY(!ldlt.isPositive());\n    VERIFY_IS_APPROX(mat,ldlt.reconstructedMatrix());\n  }\n  {\n    mat << 0, 0, 0, 0;\n    ldlt.compute(mat);\n    VERIFY(ldlt.info()==Success);\n    VERIFY(ldlt.isNegative());\n    VERIFY(ldlt.isPositive());\n    VERIFY_IS_APPROX(mat,ldlt.reconstructedMatrix());\n  }\n  {\n    mat << 0, 0, 0, 1;\n    ldlt.compute(mat);\n    VERIFY(ldlt.info()==Success);\n    VERIFY(!ldlt.isNegative());\n    VERIFY(ldlt.isPositive());\n    VERIFY_IS_APPROX(mat,ldlt.reconstructedMatrix());\n  }\n  {\n    mat << -1, 0, 0, 0;\n    ldlt.compute(mat);\n    VERIFY(ldlt.info()==Success);\n    VERIFY(ldlt.isNegative());\n    VERIFY(!ldlt.isPositive());\n    VERIFY_IS_APPROX(mat,ldlt.reconstructedMatrix());\n  }\n}\n\ntemplate<typename>\nvoid cholesky_faillure_cases()\n{\n  MatrixXd mat;\n  LDLT<MatrixXd> ldlt;\n\n  {\n    mat.resize(2,2);\n    mat << 0, 1, 1, 0;\n    ldlt.compute(mat);\n    VERIFY_IS_NOT_APPROX(mat,ldlt.reconstructedMatrix());\n    VERIFY(ldlt.info()==NumericalIssue);\n  }\n#if (!EIGEN_ARCH_i386) || defined(EIGEN_VECTORIZE_SSE2)\n  {\n    mat.resize(3,3);\n    mat << -1, -3, 3,\n           -3, -8.9999999999999999999, 1,\n            3, 1, 0;\n    ldlt.compute(mat);\n    VERIFY(ldlt.info()==NumericalIssue);\n    VERIFY_IS_NOT_APPROX(mat,ldlt.reconstructedMatrix());\n  }\n#endif\n  {\n    mat.resize(3,3);\n    mat <<  1, 2, 3,\n            2, 4, 1,\n            3, 1, 0;\n    ldlt.compute(mat);\n    VERIFY(ldlt.info()==NumericalIssue);\n    VERIFY_IS_NOT_APPROX(mat,ldlt.reconstructedMatrix());\n  }\n\n  {\n    mat.resize(8,8);\n    mat <<  0.1, 0, -0.1, 0, 0, 0, 1, 0,\n            0, 4.24667, 0, 2.00333, 0, 0, 0, 0,\n            -0.1, 0, 0.2, 0, -0.1, 0, 0, 0,\n            0, 2.00333, 0, 8.49333, 0, 2.00333, 0, 0,\n            0, 0, -0.1, 0, 0.1, 0, 0, 1,\n            0, 0, 0, 2.00333, 0, 4.24667, 0, 0,\n            1, 0, 0, 0, 0, 0, 0, 0,\n            0, 0, 0, 0, 1, 0, 0, 0;\n    ldlt.compute(mat);\n    VERIFY(ldlt.info()==NumericalIssue);\n    VERIFY_IS_NOT_APPROX(mat,ldlt.reconstructedMatrix());\n  }\n\n  // bug 1479\n  {\n    mat.resize(4,4);\n    mat <<  1, 2, 0, 1,\n            2, 4, 0, 2,\n            0, 0, 0, 1,\n            1, 2, 1, 1;\n    ldlt.compute(mat);\n    VERIFY(ldlt.info()==NumericalIssue);\n    VERIFY_IS_NOT_APPROX(mat,ldlt.reconstructedMatrix());\n  }\n}\n\ntemplate<typename MatrixType> void cholesky_verify_assert()\n{\n  MatrixType tmp;\n\n  LLT<MatrixType> llt;\n  VERIFY_RAISES_ASSERT(llt.matrixL())\n  VERIFY_RAISES_ASSERT(llt.matrixU())\n  VERIFY_RAISES_ASSERT(llt.solve(tmp))\n  VERIFY_RAISES_ASSERT(llt.transpose().solve(tmp))\n  VERIFY_RAISES_ASSERT(llt.adjoint().solve(tmp))\n  VERIFY_RAISES_ASSERT(llt.solveInPlace(tmp))\n\n  LDLT<MatrixType> ldlt;\n  VERIFY_RAISES_ASSERT(ldlt.matrixL())\n  VERIFY_RAISES_ASSERT(ldlt.transpositionsP())\n  VERIFY_RAISES_ASSERT(ldlt.vectorD())\n  VERIFY_RAISES_ASSERT(ldlt.isPositive())\n  VERIFY_RAISES_ASSERT(ldlt.isNegative())\n  VERIFY_RAISES_ASSERT(ldlt.solve(tmp))\n  VERIFY_RAISES_ASSERT(ldlt.transpose().solve(tmp))\n  VERIFY_RAISES_ASSERT(ldlt.adjoint().solve(tmp))\n  VERIFY_RAISES_ASSERT(ldlt.solveInPlace(tmp))\n}\n\nEIGEN_DECLARE_TEST(cholesky)\n{\n  int s = 0;\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( cholesky(Matrix<double,1,1>()) );\n    CALL_SUBTEST_3( cholesky(Matrix2d()) );\n    CALL_SUBTEST_3( cholesky_bug241(Matrix2d()) );\n    CALL_SUBTEST_3( cholesky_definiteness(Matrix2d()) );\n    CALL_SUBTEST_4( cholesky(Matrix3f()) );\n    CALL_SUBTEST_5( cholesky(Matrix4d()) );\n\n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE);\n    CALL_SUBTEST_2( cholesky(MatrixXd(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n\n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2);\n    CALL_SUBTEST_6( cholesky_cplx(MatrixXcd(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n  }\n  // empty matrix, regression test for Bug 785:\n  CALL_SUBTEST_2( cholesky(MatrixXd(0,0)) );\n\n  // This does not work yet:\n  // CALL_SUBTEST_2( cholesky(Matrix<double,0,0>()) );\n\n  CALL_SUBTEST_4( cholesky_verify_assert<Matrix3f>() );\n  CALL_SUBTEST_7( cholesky_verify_assert<Matrix3d>() );\n  CALL_SUBTEST_8( cholesky_verify_assert<MatrixXf>() );\n  CALL_SUBTEST_2( cholesky_verify_assert<MatrixXd>() );\n\n  // Test problem size constructors\n  CALL_SUBTEST_9( LLT<MatrixXf>(10) );\n  CALL_SUBTEST_9( LDLT<MatrixXf>(10) );\n\n  CALL_SUBTEST_2( cholesky_faillure_cases<void>() );\n\n  TEST_SET_BUT_UNUSED_VARIABLE(nb_temporaries)\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/cholmod_support.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS\n#include \"sparse_solver.h\"\n\n#include <Eigen/CholmodSupport>\n\ntemplate<typename SparseType> void test_cholmod_ST()\n{\n  CholmodDecomposition<SparseType, Lower> g_chol_colmajor_lower; g_chol_colmajor_lower.setMode(CholmodSupernodalLLt);\n  CholmodDecomposition<SparseType, Upper> g_chol_colmajor_upper; g_chol_colmajor_upper.setMode(CholmodSupernodalLLt);\n  CholmodDecomposition<SparseType, Lower> g_llt_colmajor_lower;  g_llt_colmajor_lower.setMode(CholmodSimplicialLLt);\n  CholmodDecomposition<SparseType, Upper> g_llt_colmajor_upper;  g_llt_colmajor_upper.setMode(CholmodSimplicialLLt);\n  CholmodDecomposition<SparseType, Lower> g_ldlt_colmajor_lower; g_ldlt_colmajor_lower.setMode(CholmodLDLt);\n  CholmodDecomposition<SparseType, Upper> g_ldlt_colmajor_upper; g_ldlt_colmajor_upper.setMode(CholmodLDLt);\n  \n  CholmodSupernodalLLT<SparseType, Lower> chol_colmajor_lower;\n  CholmodSupernodalLLT<SparseType, Upper> chol_colmajor_upper;\n  CholmodSimplicialLLT<SparseType, Lower> llt_colmajor_lower;\n  CholmodSimplicialLLT<SparseType, Upper> llt_colmajor_upper;\n  CholmodSimplicialLDLT<SparseType, Lower> ldlt_colmajor_lower;\n  CholmodSimplicialLDLT<SparseType, Upper> ldlt_colmajor_upper;\n\n  check_sparse_spd_solving(g_chol_colmajor_lower);\n  check_sparse_spd_solving(g_chol_colmajor_upper);\n  check_sparse_spd_solving(g_llt_colmajor_lower);\n  check_sparse_spd_solving(g_llt_colmajor_upper);\n  check_sparse_spd_solving(g_ldlt_colmajor_lower);\n  check_sparse_spd_solving(g_ldlt_colmajor_upper);\n  \n  check_sparse_spd_solving(chol_colmajor_lower);\n  check_sparse_spd_solving(chol_colmajor_upper);\n  check_sparse_spd_solving(llt_colmajor_lower);\n  check_sparse_spd_solving(llt_colmajor_upper);\n  check_sparse_spd_solving(ldlt_colmajor_lower);\n  check_sparse_spd_solving(ldlt_colmajor_upper);\n\n  check_sparse_spd_determinant(chol_colmajor_lower);\n  check_sparse_spd_determinant(chol_colmajor_upper);\n  check_sparse_spd_determinant(llt_colmajor_lower);\n  check_sparse_spd_determinant(llt_colmajor_upper);\n  check_sparse_spd_determinant(ldlt_colmajor_lower);\n  check_sparse_spd_determinant(ldlt_colmajor_upper);\n}\n\ntemplate<typename T, int flags, typename IdxType> void test_cholmod_T()\n{\n    test_cholmod_ST<SparseMatrix<T, flags, IdxType> >();\n}\n\nEIGEN_DECLARE_TEST(cholmod_support)\n{\n  CALL_SUBTEST_11( (test_cholmod_T<double              , ColMajor, int >()) );\n  CALL_SUBTEST_12( (test_cholmod_T<double              , ColMajor, long>()) );\n  CALL_SUBTEST_13( (test_cholmod_T<double              , RowMajor, int >()) );\n  CALL_SUBTEST_14( (test_cholmod_T<double              , RowMajor, long>()) );\n  CALL_SUBTEST_21( (test_cholmod_T<std::complex<double>, ColMajor, int >()) );\n  CALL_SUBTEST_22( (test_cholmod_T<std::complex<double>, ColMajor, long>()) );\n  // TODO complex row-major matrices do not work at the moment:\n  // CALL_SUBTEST_23( (test_cholmod_T<std::complex<double>, RowMajor, int >()) );\n  // CALL_SUBTEST_24( (test_cholmod_T<std::complex<double>, RowMajor, long>()) );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/commainitializer.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n\ntemplate<int M1, int M2, int N1, int N2>\nvoid test_blocks()\n{\n  Matrix<int, M1+M2, N1+N2> m_fixed;\n  MatrixXi m_dynamic(M1+M2, N1+N2);\n\n  Matrix<int, M1, N1> mat11; mat11.setRandom();\n  Matrix<int, M1, N2> mat12; mat12.setRandom();\n  Matrix<int, M2, N1> mat21; mat21.setRandom();\n  Matrix<int, M2, N2> mat22; mat22.setRandom();\n\n  MatrixXi matx11 = mat11, matx12 = mat12, matx21 = mat21, matx22 = mat22;\n\n  {\n    VERIFY_IS_EQUAL((m_fixed << mat11, mat12, mat21, matx22).finished(), (m_dynamic << mat11, matx12, mat21, matx22).finished());\n    VERIFY_IS_EQUAL((m_fixed.template topLeftCorner<M1,N1>()), mat11);\n    VERIFY_IS_EQUAL((m_fixed.template topRightCorner<M1,N2>()), mat12);\n    VERIFY_IS_EQUAL((m_fixed.template bottomLeftCorner<M2,N1>()), mat21);\n    VERIFY_IS_EQUAL((m_fixed.template bottomRightCorner<M2,N2>()), mat22);\n    VERIFY_IS_EQUAL((m_fixed << mat12, mat11, matx21, mat22).finished(), (m_dynamic << mat12, matx11, matx21, mat22).finished());\n  }\n\n  if(N1 > 0)\n  {\n    if(M1 > 0)\n    {\n      VERIFY_RAISES_ASSERT((m_fixed << mat11, mat12, mat11, mat21, mat22));\n    }\n    if(M2 > 0)\n    {\n      VERIFY_RAISES_ASSERT((m_fixed << mat11, mat12, mat21, mat21, mat22));\n    }\n  }\n  else\n  {\n    // allow insertion of zero-column blocks:\n    VERIFY_IS_EQUAL((m_fixed << mat11, mat12, mat11, mat11, mat21, mat21, mat22).finished(), (m_dynamic << mat12, mat22).finished());\n  }\n  if(M1 != M2)\n  {\n    VERIFY_RAISES_ASSERT((m_fixed << mat11, mat21, mat12, mat22));\n  }\n}\n\n\ntemplate<int depth, int N=0>\nstruct test_block_recursion\n{\n  static void run()\n  {\n    test_block_recursion<depth-1, N>::run();\n    test_block_recursion<depth-1, N + (1 << (depth-1))>::run();\n  }\n};\n\ntemplate<int N>\nstruct test_block_recursion<0,N>\n{\n  static void run() {\n    test_blocks<(N>>6)&3, (N>>4)&3, (N>>2)&3, N & 3>();\n  }\n};\n\nvoid test_basics() {\n  Matrix3d m3;\n  Matrix4d m4;\n\n  VERIFY_RAISES_ASSERT( (m3 << 1, 2, 3, 4, 5, 6, 7, 8) );\n  \n  #ifndef _MSC_VER\n  VERIFY_RAISES_ASSERT( (m3 << 1, 2, 3, 4, 5, 6, 7, 8, 9, 10) );\n  #endif\n\n  double data[] = {1, 2, 3, 4, 5, 6, 7, 8, 9};\n  Matrix3d ref = Map<Matrix<double,3,3,RowMajor> >(data);\n\n  m3 = Matrix3d::Random();\n  m3 << 1, 2, 3, 4, 5, 6, 7, 8, 9;\n  VERIFY_IS_APPROX(m3, ref );\n\n  Vector3d vec[3];\n  vec[0] << 1, 4, 7;\n  vec[1] << 2, 5, 8;\n  vec[2] << 3, 6, 9;\n  m3 = Matrix3d::Random();\n  m3 << vec[0], vec[1], vec[2];\n  VERIFY_IS_APPROX(m3, ref);\n\n  vec[0] << 1, 2, 3;\n  vec[1] << 4, 5, 6;\n  vec[2] << 7, 8, 9;\n  m3 = Matrix3d::Random();\n  m3 << vec[0].transpose(),\n        4, 5, 6,\n        vec[2].transpose();\n  VERIFY_IS_APPROX(m3, ref);\n}\n\nEIGEN_DECLARE_TEST(commainitializer)\n{\n\n  CALL_SUBTEST_1(test_basics());\n\n  // recursively test all block-sizes from 0 to 3:\n  CALL_SUBTEST_2(test_block_recursion<8>::run());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/conjugate_gradient.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"sparse_solver.h\"\n#include <Eigen/IterativeLinearSolvers>\n\ntemplate<typename T, typename I_> void test_conjugate_gradient_T()\n{\n  typedef SparseMatrix<T,0,I_> SparseMatrixType;\n  ConjugateGradient<SparseMatrixType, Lower      > cg_colmajor_lower_diag;\n  ConjugateGradient<SparseMatrixType, Upper      > cg_colmajor_upper_diag;\n  ConjugateGradient<SparseMatrixType, Lower|Upper> cg_colmajor_loup_diag;\n  ConjugateGradient<SparseMatrixType, Lower, IdentityPreconditioner> cg_colmajor_lower_I;\n  ConjugateGradient<SparseMatrixType, Upper, IdentityPreconditioner> cg_colmajor_upper_I;\n\n  CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_lower_diag)  );\n  CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_upper_diag)  );\n  CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_loup_diag)   );\n  CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_lower_I)     );\n  CALL_SUBTEST( check_sparse_spd_solving(cg_colmajor_upper_I)     );\n}\n\nEIGEN_DECLARE_TEST(conjugate_gradient)\n{\n  CALL_SUBTEST_1(( test_conjugate_gradient_T<double,int>() ));\n  CALL_SUBTEST_2(( test_conjugate_gradient_T<std::complex<double>, int>() ));\n  CALL_SUBTEST_3(( test_conjugate_gradient_T<double,long int>() ));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/conservative_resize.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/Core>\n#include \"AnnoyingScalar.h\"\n\nusing namespace Eigen;\n\ntemplate <typename Scalar, int Storage>\nvoid run_matrix_tests()\n{\n  typedef Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Storage> MatrixType;\n\n  MatrixType m, n;\n\n  // boundary cases ...\n  m = n = MatrixType::Random(50,50);\n  m.conservativeResize(1,50);\n  VERIFY_IS_APPROX(m, n.block(0,0,1,50));\n\n  m = n = MatrixType::Random(50,50);\n  m.conservativeResize(50,1);\n  VERIFY_IS_APPROX(m, n.block(0,0,50,1));\n\n  m = n = MatrixType::Random(50,50);\n  m.conservativeResize(50,50);\n  VERIFY_IS_APPROX(m, n.block(0,0,50,50));\n\n  // random shrinking ...\n  for (int i=0; i<25; ++i)\n  {\n    const Index rows = internal::random<Index>(1,50);\n    const Index cols = internal::random<Index>(1,50);\n    m = n = MatrixType::Random(50,50);\n    m.conservativeResize(rows,cols);\n    VERIFY_IS_APPROX(m, n.block(0,0,rows,cols));\n  }\n\n  // random growing with zeroing ...\n  for (int i=0; i<25; ++i)\n  {\n    const Index rows = internal::random<Index>(50,75);\n    const Index cols = internal::random<Index>(50,75);\n    m = n = MatrixType::Random(50,50);\n    m.conservativeResizeLike(MatrixType::Zero(rows,cols));\n    VERIFY_IS_APPROX(m.block(0,0,n.rows(),n.cols()), n);\n    VERIFY( rows<=50 || m.block(50,0,rows-50,cols).sum() == Scalar(0) );\n    VERIFY( cols<=50 || m.block(0,50,rows,cols-50).sum() == Scalar(0) );\n  }\n}\n\ntemplate <typename Scalar>\nvoid run_vector_tests()\n{\n  typedef Matrix<Scalar, 1, Eigen::Dynamic> VectorType;\n\n  VectorType m, n;\n\n  // boundary cases ...\n  m = n = VectorType::Random(50);\n  m.conservativeResize(1);\n  VERIFY_IS_APPROX(m, n.segment(0,1));\n\n  m = n = VectorType::Random(50);\n  m.conservativeResize(50);\n  VERIFY_IS_APPROX(m, n.segment(0,50));\n  \n  m = n = VectorType::Random(50);\n  m.conservativeResize(m.rows(),1);\n  VERIFY_IS_APPROX(m, n.segment(0,1));\n\n  m = n = VectorType::Random(50);\n  m.conservativeResize(m.rows(),50);\n  VERIFY_IS_APPROX(m, n.segment(0,50));\n\n  // random shrinking ...\n  for (int i=0; i<50; ++i)\n  {\n    const int size = internal::random<int>(1,50);\n    m = n = VectorType::Random(50);\n    m.conservativeResize(size);\n    VERIFY_IS_APPROX(m, n.segment(0,size));\n    \n    m = n = VectorType::Random(50);\n    m.conservativeResize(m.rows(), size);\n    VERIFY_IS_APPROX(m, n.segment(0,size));\n  }\n\n  // random growing with zeroing ...\n  for (int i=0; i<50; ++i)\n  {\n    const int size = internal::random<int>(50,100);\n    m = n = VectorType::Random(50);\n    m.conservativeResizeLike(VectorType::Zero(size));\n    VERIFY_IS_APPROX(m.segment(0,50), n);\n    VERIFY( size<=50 || m.segment(50,size-50).sum() == Scalar(0) );\n    \n    m = n = VectorType::Random(50);\n    m.conservativeResizeLike(Matrix<Scalar,Dynamic,Dynamic>::Zero(1,size));\n    VERIFY_IS_APPROX(m.segment(0,50), n);\n    VERIFY( size<=50 || m.segment(50,size-50).sum() == Scalar(0) );\n  }\n}\n\n// Basic memory leak check with a non-copyable scalar type\ntemplate<int> void noncopyable()\n{\n  typedef Eigen::Matrix<AnnoyingScalar,Dynamic,1> VectorType;\n  typedef Eigen::Matrix<AnnoyingScalar,Dynamic,Dynamic> MatrixType;\n  \n  {\n    AnnoyingScalar::dont_throw = true;\n    int n = 50;\n    VectorType v0(n), v1(n);\n    MatrixType m0(n,n), m1(n,n), m2(n,n);\n    v0.setOnes(); v1.setOnes();\n    m0.setOnes(); m1.setOnes(); m2.setOnes();\n    VERIFY(m0==m1);\n    m0.conservativeResize(2*n,2*n);\n    VERIFY(m0.topLeftCorner(n,n) == m1);\n    \n    VERIFY(v0.head(n) == v1);\n    v0.conservativeResize(2*n);\n    VERIFY(v0.head(n) == v1);\n  }\n  VERIFY(AnnoyingScalar::instances==0 && \"global memory leak detected in noncopyable\");\n}\n\nEIGEN_DECLARE_TEST(conservative_resize)\n{\n  for(int i=0; i<g_repeat; ++i)\n  {\n    CALL_SUBTEST_1((run_matrix_tests<int, Eigen::RowMajor>()));\n    CALL_SUBTEST_1((run_matrix_tests<int, Eigen::ColMajor>()));\n    CALL_SUBTEST_2((run_matrix_tests<float, Eigen::RowMajor>()));\n    CALL_SUBTEST_2((run_matrix_tests<float, Eigen::ColMajor>()));\n    CALL_SUBTEST_3((run_matrix_tests<double, Eigen::RowMajor>()));\n    CALL_SUBTEST_3((run_matrix_tests<double, Eigen::ColMajor>()));\n    CALL_SUBTEST_4((run_matrix_tests<std::complex<float>, Eigen::RowMajor>()));\n    CALL_SUBTEST_4((run_matrix_tests<std::complex<float>, Eigen::ColMajor>()));\n    CALL_SUBTEST_5((run_matrix_tests<std::complex<double>, Eigen::RowMajor>()));\n    CALL_SUBTEST_5((run_matrix_tests<std::complex<double>, Eigen::ColMajor>()));\n\n    CALL_SUBTEST_1((run_vector_tests<int>()));\n    CALL_SUBTEST_2((run_vector_tests<float>()));\n    CALL_SUBTEST_3((run_vector_tests<double>()));\n    CALL_SUBTEST_4((run_vector_tests<std::complex<float> >()));\n    CALL_SUBTEST_5((run_vector_tests<std::complex<double> >()));\n\n    AnnoyingScalar::dont_throw = true;\n    CALL_SUBTEST_6(( run_vector_tests<AnnoyingScalar>() ));\n    CALL_SUBTEST_6(( noncopyable<0>() ));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/constructor.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2017 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#define TEST_ENABLE_TEMPORARY_TRACKING\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> struct Wrapper\n{\n  MatrixType m_mat;\n  inline Wrapper(const MatrixType &x) : m_mat(x) {}\n  inline operator const MatrixType& () const { return m_mat; }\n  inline operator MatrixType& () { return m_mat; }\n};\n\nenum my_sizes { M = 12, N = 7};\n\ntemplate<typename MatrixType> void ctor_init1(const MatrixType& m)\n{\n  // Check logic in PlainObjectBase::_init1\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m0 = MatrixType::Random(rows,cols);\n\n  VERIFY_EVALUATION_COUNT( MatrixType m1(m0), 1);\n  VERIFY_EVALUATION_COUNT( MatrixType m2(m0+m0), 1);\n  VERIFY_EVALUATION_COUNT( MatrixType m2(m0.block(0,0,rows,cols)) , 1);\n\n  Wrapper<MatrixType> wrapper(m0);\n  VERIFY_EVALUATION_COUNT( MatrixType m3(wrapper) , 1);\n}\n\n\nEIGEN_DECLARE_TEST(constructor)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( ctor_init1(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_1( ctor_init1(Matrix4d()) );\n    CALL_SUBTEST_1( ctor_init1(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_1( ctor_init1(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  {\n    Matrix<Index,1,1> a(123);\n    VERIFY_IS_EQUAL(a[0], 123);\n  }\n  {\n    Matrix<Index,1,1> a(123.0);\n    VERIFY_IS_EQUAL(a[0], 123);\n  }\n  {\n    Matrix<float,1,1> a(123);\n    VERIFY_IS_EQUAL(a[0], 123.f);\n  }\n  {\n    Array<Index,1,1> a(123);\n    VERIFY_IS_EQUAL(a[0], 123);\n  }\n  {\n    Array<Index,1,1> a(123.0);\n    VERIFY_IS_EQUAL(a[0], 123);\n  }\n  {\n    Array<float,1,1> a(123);\n    VERIFY_IS_EQUAL(a[0], 123.f);\n  }\n  {\n    Array<Index,3,3> a(123);\n    VERIFY_IS_EQUAL(a(4), 123);\n  }\n  {\n    Array<Index,3,3> a(123.0);\n    VERIFY_IS_EQUAL(a(4), 123);\n  }\n  {\n    Array<float,3,3> a(123);\n    VERIFY_IS_EQUAL(a(4), 123.f);\n  }\n  {\n    MatrixXi m1(M,N);\n    VERIFY_IS_EQUAL(m1.rows(),M);\n    VERIFY_IS_EQUAL(m1.cols(),N);\n    ArrayXXi a1(M,N);\n    VERIFY_IS_EQUAL(a1.rows(),M);\n    VERIFY_IS_EQUAL(a1.cols(),N);\n    VectorXi v1(M);\n    VERIFY_IS_EQUAL(v1.size(),M);\n    ArrayXi a2(M);\n    VERIFY_IS_EQUAL(a2.size(),M);\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/corners.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#define COMPARE_CORNER(A,B) \\\n  VERIFY_IS_EQUAL(matrix.A, matrix.B); \\\n  VERIFY_IS_EQUAL(const_matrix.A, const_matrix.B);\n\ntemplate<typename MatrixType> void corners(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  Index r = internal::random<Index>(1,rows);\n  Index c = internal::random<Index>(1,cols);\n\n  MatrixType matrix = MatrixType::Random(rows,cols);\n  const MatrixType const_matrix = MatrixType::Random(rows,cols);\n\n  COMPARE_CORNER(topLeftCorner(r,c), block(0,0,r,c));\n  COMPARE_CORNER(topRightCorner(r,c), block(0,cols-c,r,c));\n  COMPARE_CORNER(bottomLeftCorner(r,c), block(rows-r,0,r,c));\n  COMPARE_CORNER(bottomRightCorner(r,c), block(rows-r,cols-c,r,c));\n\n  Index sr = internal::random<Index>(1,rows) - 1;\n  Index nr = internal::random<Index>(1,rows-sr);\n  Index sc = internal::random<Index>(1,cols) - 1;\n  Index nc = internal::random<Index>(1,cols-sc);\n\n  COMPARE_CORNER(topRows(r), block(0,0,r,cols));\n  COMPARE_CORNER(middleRows(sr,nr), block(sr,0,nr,cols));\n  COMPARE_CORNER(bottomRows(r), block(rows-r,0,r,cols));\n  COMPARE_CORNER(leftCols(c), block(0,0,rows,c));\n  COMPARE_CORNER(middleCols(sc,nc), block(0,sc,rows,nc));\n  COMPARE_CORNER(rightCols(c), block(0,cols-c,rows,c));\n}\n\ntemplate<typename MatrixType, int CRows, int CCols, int SRows, int SCols> void corners_fixedsize()\n{\n  MatrixType matrix = MatrixType::Random();\n  const MatrixType const_matrix = MatrixType::Random();\n\n  enum {\n    rows = MatrixType::RowsAtCompileTime,\n    cols = MatrixType::ColsAtCompileTime,\n    r = CRows,\n    c = CCols,\n\tsr = SRows,\n\tsc = SCols\n  };\n\n  VERIFY_IS_EQUAL((matrix.template topLeftCorner<r,c>()), (matrix.template block<r,c>(0,0)));\n  VERIFY_IS_EQUAL((matrix.template topRightCorner<r,c>()), (matrix.template block<r,c>(0,cols-c)));\n  VERIFY_IS_EQUAL((matrix.template bottomLeftCorner<r,c>()), (matrix.template block<r,c>(rows-r,0)));\n  VERIFY_IS_EQUAL((matrix.template bottomRightCorner<r,c>()), (matrix.template block<r,c>(rows-r,cols-c)));\n\n  VERIFY_IS_EQUAL((matrix.template topLeftCorner<r,c>()), (matrix.template topLeftCorner<r,Dynamic>(r,c)));\n  VERIFY_IS_EQUAL((matrix.template topRightCorner<r,c>()), (matrix.template topRightCorner<r,Dynamic>(r,c)));\n  VERIFY_IS_EQUAL((matrix.template bottomLeftCorner<r,c>()), (matrix.template bottomLeftCorner<r,Dynamic>(r,c)));\n  VERIFY_IS_EQUAL((matrix.template bottomRightCorner<r,c>()), (matrix.template bottomRightCorner<r,Dynamic>(r,c)));\n\n  VERIFY_IS_EQUAL((matrix.template topLeftCorner<r,c>()), (matrix.template topLeftCorner<Dynamic,c>(r,c)));\n  VERIFY_IS_EQUAL((matrix.template topRightCorner<r,c>()), (matrix.template topRightCorner<Dynamic,c>(r,c)));\n  VERIFY_IS_EQUAL((matrix.template bottomLeftCorner<r,c>()), (matrix.template bottomLeftCorner<Dynamic,c>(r,c)));\n  VERIFY_IS_EQUAL((matrix.template bottomRightCorner<r,c>()), (matrix.template bottomRightCorner<Dynamic,c>(r,c)));\n\n  VERIFY_IS_EQUAL((matrix.template topRows<r>()), (matrix.template block<r,cols>(0,0)));\n  VERIFY_IS_EQUAL((matrix.template middleRows<r>(sr)), (matrix.template block<r,cols>(sr,0)));\n  VERIFY_IS_EQUAL((matrix.template bottomRows<r>()), (matrix.template block<r,cols>(rows-r,0)));\n  VERIFY_IS_EQUAL((matrix.template leftCols<c>()), (matrix.template block<rows,c>(0,0)));\n  VERIFY_IS_EQUAL((matrix.template middleCols<c>(sc)), (matrix.template block<rows,c>(0,sc)));\n  VERIFY_IS_EQUAL((matrix.template rightCols<c>()), (matrix.template block<rows,c>(0,cols-c)));\n\n  VERIFY_IS_EQUAL((const_matrix.template topLeftCorner<r,c>()), (const_matrix.template block<r,c>(0,0)));\n  VERIFY_IS_EQUAL((const_matrix.template topRightCorner<r,c>()), (const_matrix.template block<r,c>(0,cols-c)));\n  VERIFY_IS_EQUAL((const_matrix.template bottomLeftCorner<r,c>()), (const_matrix.template block<r,c>(rows-r,0)));\n  VERIFY_IS_EQUAL((const_matrix.template bottomRightCorner<r,c>()), (const_matrix.template block<r,c>(rows-r,cols-c)));\n\n  VERIFY_IS_EQUAL((const_matrix.template topLeftCorner<r,c>()), (const_matrix.template topLeftCorner<r,Dynamic>(r,c)));\n  VERIFY_IS_EQUAL((const_matrix.template topRightCorner<r,c>()), (const_matrix.template topRightCorner<r,Dynamic>(r,c)));\n  VERIFY_IS_EQUAL((const_matrix.template bottomLeftCorner<r,c>()), (const_matrix.template bottomLeftCorner<r,Dynamic>(r,c)));\n  VERIFY_IS_EQUAL((const_matrix.template bottomRightCorner<r,c>()), (const_matrix.template bottomRightCorner<r,Dynamic>(r,c)));\n\n  VERIFY_IS_EQUAL((const_matrix.template topLeftCorner<r,c>()), (const_matrix.template topLeftCorner<Dynamic,c>(r,c)));\n  VERIFY_IS_EQUAL((const_matrix.template topRightCorner<r,c>()), (const_matrix.template topRightCorner<Dynamic,c>(r,c)));\n  VERIFY_IS_EQUAL((const_matrix.template bottomLeftCorner<r,c>()), (const_matrix.template bottomLeftCorner<Dynamic,c>(r,c)));\n  VERIFY_IS_EQUAL((const_matrix.template bottomRightCorner<r,c>()), (const_matrix.template bottomRightCorner<Dynamic,c>(r,c)));\n\n  VERIFY_IS_EQUAL((const_matrix.template topRows<r>()), (const_matrix.template block<r,cols>(0,0)));\n  VERIFY_IS_EQUAL((const_matrix.template middleRows<r>(sr)), (const_matrix.template block<r,cols>(sr,0)));\n  VERIFY_IS_EQUAL((const_matrix.template bottomRows<r>()), (const_matrix.template block<r,cols>(rows-r,0)));\n  VERIFY_IS_EQUAL((const_matrix.template leftCols<c>()), (const_matrix.template block<rows,c>(0,0)));\n  VERIFY_IS_EQUAL((const_matrix.template middleCols<c>(sc)), (const_matrix.template block<rows,c>(0,sc)));\n  VERIFY_IS_EQUAL((const_matrix.template rightCols<c>()), (const_matrix.template block<rows,c>(0,cols-c)));\n}\n\nEIGEN_DECLARE_TEST(corners)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( corners(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( corners(Matrix4d()) );\n    CALL_SUBTEST_3( corners(Matrix<int,10,12>()) );\n    CALL_SUBTEST_4( corners(MatrixXcf(5, 7)) );\n    CALL_SUBTEST_5( corners(MatrixXf(21, 20)) );\n\n    CALL_SUBTEST_1(( corners_fixedsize<Matrix<float, 1, 1>, 1, 1, 0, 0>() ));\n    CALL_SUBTEST_2(( corners_fixedsize<Matrix4d,2,2,1,1>() ));\n    CALL_SUBTEST_3(( corners_fixedsize<Matrix<int,10,12>,4,7,5,2>() ));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/ctorleak.cpp",
    "content": "#include \"main.h\"\n\n#include <exception>  // std::exception\n\nstruct Foo\n{\n  static Index object_count;\n  static Index object_limit;\n  int dummy;\n\n  Foo() : dummy(0)\n  {\n#ifdef EIGEN_EXCEPTIONS\n    // TODO: Is this the correct way to handle this?\n    if (Foo::object_count > Foo::object_limit) { std::cout << \"\\nThrow!\\n\"; throw Foo::Fail(); }\n#endif\n\t  std::cout << '+';\n    ++Foo::object_count;\n  }\n\n  ~Foo()\n  {\n\t  std::cout << '-';\n    --Foo::object_count;\n  }\n\n  class Fail : public std::exception {};\n};\n\nIndex Foo::object_count = 0;\nIndex Foo::object_limit = 0;\n\n#undef EIGEN_TEST_MAX_SIZE\n#define EIGEN_TEST_MAX_SIZE 3\n\nEIGEN_DECLARE_TEST(ctorleak)\n{\n  typedef Matrix<Foo, Dynamic, Dynamic> MatrixX;\n  typedef Matrix<Foo, Dynamic, 1> VectorX;\n  \n  Foo::object_count = 0;\n  for(int i = 0; i < g_repeat; i++) {\n    Index rows = internal::random<Index>(2,EIGEN_TEST_MAX_SIZE), cols = internal::random<Index>(2,EIGEN_TEST_MAX_SIZE);\n    Foo::object_limit = rows*cols;\n    {\n    MatrixX r(rows, cols);\n    Foo::object_limit = r.size()+internal::random<Index>(0, rows*cols - 2);\n    std::cout << \"object_limit =\" << Foo::object_limit << std::endl;\n#ifdef EIGEN_EXCEPTIONS\n    try\n    {\n#endif\n      if(internal::random<bool>()) {\n        std::cout <<       \"\\nMatrixX m(\" << rows << \", \" << cols << \");\\n\";\n        MatrixX m(rows, cols);\n      }\n      else {\n        std::cout <<       \"\\nMatrixX m(r);\\n\";\n        MatrixX m(r);\n      }\n#ifdef EIGEN_EXCEPTIONS\n      VERIFY(false);  // not reached if exceptions are enabled\n    }\n    catch (const Foo::Fail&) { /* ignore */ }\n#endif\n    }\n    VERIFY_IS_EQUAL(Index(0), Foo::object_count);\n\n    {\n      Foo::object_limit = (rows+1)*(cols+1);\n      MatrixX A(rows, cols);\n      VERIFY_IS_EQUAL(Foo::object_count, rows*cols);\n      VectorX v=A.row(0);\n      VERIFY_IS_EQUAL(Foo::object_count, (rows+1)*cols);\n      v = A.col(0);\n      VERIFY_IS_EQUAL(Foo::object_count, rows*(cols+1));\n    }\n    VERIFY_IS_EQUAL(Index(0), Foo::object_count);\n  }\n  std::cout << \"\\n\";\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/denseLM.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Desire Nuentsa <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <iostream>\n#include <fstream>\n#include <iomanip>\n\n#include \"main.h\"\n#include <Eigen/LevenbergMarquardt>\nusing namespace std;\nusing namespace Eigen;\n\ntemplate<typename Scalar>\nstruct DenseLM : DenseFunctor<Scalar>\n{\n  typedef DenseFunctor<Scalar> Base;\n  typedef typename Base::JacobianType JacobianType;\n  typedef Matrix<Scalar,Dynamic,1> VectorType;\n  \n  DenseLM(int n, int m) : DenseFunctor<Scalar>(n,m) \n  { }\n \n  VectorType model(const VectorType& uv, VectorType& x)\n  {\n    VectorType y; // Should change to use expression template\n    int m = Base::values(); \n    int n = Base::inputs();\n    eigen_assert(uv.size()%2 == 0);\n    eigen_assert(uv.size() == n);\n    eigen_assert(x.size() == m);\n    y.setZero(m);\n    int half = n/2;\n    VectorBlock<const VectorType> u(uv, 0, half);\n    VectorBlock<const VectorType> v(uv, half, half);\n    for (int j = 0; j < m; j++)\n    {\n      for (int i = 0; i < half; i++)\n        y(j) += u(i)*std::exp(-(x(j)-i)*(x(j)-i)/(v(i)*v(i)));\n    }\n    return y;\n    \n  }\n  void initPoints(VectorType& uv_ref, VectorType& x)\n  {\n    m_x = x;\n    m_y = this->model(uv_ref, x);\n  }\n  \n  int operator()(const VectorType& uv, VectorType& fvec)\n  {\n    \n    int m = Base::values(); \n    int n = Base::inputs();\n    eigen_assert(uv.size()%2 == 0);\n    eigen_assert(uv.size() == n);\n    eigen_assert(fvec.size() == m);\n    int half = n/2;\n    VectorBlock<const VectorType> u(uv, 0, half);\n    VectorBlock<const VectorType> v(uv, half, half);\n    for (int j = 0; j < m; j++)\n    {\n      fvec(j) = m_y(j);\n      for (int i = 0; i < half; i++)\n      {\n        fvec(j) -= u(i) *std::exp(-(m_x(j)-i)*(m_x(j)-i)/(v(i)*v(i)));\n      }\n    }\n    \n    return 0;\n  }\n  int df(const VectorType& uv, JacobianType& fjac)\n  {\n    int m = Base::values(); \n    int n = Base::inputs();\n    eigen_assert(n == uv.size());\n    eigen_assert(fjac.rows() == m);\n    eigen_assert(fjac.cols() == n);\n    int half = n/2;\n    VectorBlock<const VectorType> u(uv, 0, half);\n    VectorBlock<const VectorType> v(uv, half, half);\n    for (int j = 0; j < m; j++)\n    {\n      for (int i = 0; i < half; i++)\n      {\n        fjac.coeffRef(j,i) = -std::exp(-(m_x(j)-i)*(m_x(j)-i)/(v(i)*v(i)));\n        fjac.coeffRef(j,i+half) = -2.*u(i)*(m_x(j)-i)*(m_x(j)-i)/(std::pow(v(i),3)) * std::exp(-(m_x(j)-i)*(m_x(j)-i)/(v(i)*v(i)));\n      }\n    }\n    return 0;\n  }\n  VectorType m_x, m_y; //Data Points\n};\n\ntemplate<typename FunctorType, typename VectorType>\nint test_minimizeLM(FunctorType& functor, VectorType& uv)\n{\n  LevenbergMarquardt<FunctorType> lm(functor);\n  LevenbergMarquardtSpace::Status info; \n  \n  info = lm.minimize(uv);\n  \n  VERIFY_IS_EQUAL(info, 1);\n  //FIXME Check other parameters\n  return info;\n}\n\ntemplate<typename FunctorType, typename VectorType>\nint test_lmder(FunctorType& functor, VectorType& uv)\n{\n  typedef typename VectorType::Scalar Scalar;\n  LevenbergMarquardtSpace::Status info; \n  LevenbergMarquardt<FunctorType> lm(functor);\n  info = lm.lmder1(uv);\n  \n  VERIFY_IS_EQUAL(info, 1);\n  //FIXME Check other parameters\n  return info;\n}\n\ntemplate<typename FunctorType, typename VectorType>\nint test_minimizeSteps(FunctorType& functor, VectorType& uv)\n{\n  LevenbergMarquardtSpace::Status info;   \n  LevenbergMarquardt<FunctorType> lm(functor);\n  info = lm.minimizeInit(uv);\n  if (info==LevenbergMarquardtSpace::ImproperInputParameters)\n      return info;\n  do \n  {\n    info = lm.minimizeOneStep(uv);\n  } while (info==LevenbergMarquardtSpace::Running);\n  \n  VERIFY_IS_EQUAL(info, 1);\n  //FIXME Check other parameters\n  return info;\n}\n\ntemplate<typename T>\nvoid test_denseLM_T()\n{\n  typedef Matrix<T,Dynamic,1> VectorType;\n  \n  int inputs = 10; \n  int values = 1000; \n  DenseLM<T> dense_gaussian(inputs, values);\n  VectorType uv(inputs),uv_ref(inputs);\n  VectorType x(values);\n  \n  // Generate the reference solution \n  uv_ref << -2, 1, 4 ,8, 6, 1.8, 1.2, 1.1, 1.9 , 3;\n  \n  //Generate the reference data points\n  x.setRandom();\n  x = 10*x;\n  x.array() += 10;\n  dense_gaussian.initPoints(uv_ref, x);\n  \n  // Generate the initial parameters \n  VectorBlock<VectorType> u(uv, 0, inputs/2); \n  VectorBlock<VectorType> v(uv, inputs/2, inputs/2);\n  \n  // Solve the optimization problem\n  \n  //Solve in one go\n  u.setOnes(); v.setOnes();\n  test_minimizeLM(dense_gaussian, uv);\n  \n  //Solve until the machine precision\n  u.setOnes(); v.setOnes();\n  test_lmder(dense_gaussian, uv); \n  \n  // Solve step by step\n  v.setOnes(); u.setOnes();\n  test_minimizeSteps(dense_gaussian, uv);\n  \n}\n\nEIGEN_DECLARE_TEST(denseLM)\n{\n  CALL_SUBTEST_2(test_denseLM_T<double>());\n  \n  // CALL_SUBTEST_2(test_sparseLM_T<std::complex<double>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/dense_storage.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/Core>\n\ntemplate <typename T, int Rows, int Cols>\nvoid dense_storage_copy()\n{\n  static const int Size = ((Rows==Dynamic || Cols==Dynamic) ? Dynamic : Rows*Cols);\n  typedef DenseStorage<T,Size, Rows,Cols, 0> DenseStorageType;\n  \n  const int rows = (Rows==Dynamic) ? 4 : Rows;\n  const int cols = (Cols==Dynamic) ? 3 : Cols;\n  const int size = rows*cols;\n  DenseStorageType reference(size, rows, cols);\n  T* raw_reference = reference.data();\n  for (int i=0; i<size; ++i)\n    raw_reference[i] = static_cast<T>(i);\n    \n  DenseStorageType copied_reference(reference);\n  const T* raw_copied_reference = copied_reference.data();\n  for (int i=0; i<size; ++i)\n    VERIFY_IS_EQUAL(raw_reference[i], raw_copied_reference[i]);\n}\n\ntemplate <typename T, int Rows, int Cols>\nvoid dense_storage_assignment()\n{\n  static const int Size = ((Rows==Dynamic || Cols==Dynamic) ? Dynamic : Rows*Cols);\n  typedef DenseStorage<T,Size, Rows,Cols, 0> DenseStorageType;\n  \n  const int rows = (Rows==Dynamic) ? 4 : Rows;\n  const int cols = (Cols==Dynamic) ? 3 : Cols;\n  const int size = rows*cols;\n  DenseStorageType reference(size, rows, cols);\n  T* raw_reference = reference.data();\n  for (int i=0; i<size; ++i)\n    raw_reference[i] = static_cast<T>(i);\n    \n  DenseStorageType copied_reference;\n  copied_reference = reference;\n  const T* raw_copied_reference = copied_reference.data();\n  for (int i=0; i<size; ++i)\n    VERIFY_IS_EQUAL(raw_reference[i], raw_copied_reference[i]);\n}\n\ntemplate<typename T, int Size, std::size_t Alignment>\nvoid dense_storage_alignment()\n{\n  #if EIGEN_HAS_ALIGNAS\n  \n  struct alignas(Alignment) Empty1 {};\n  VERIFY_IS_EQUAL(std::alignment_of<Empty1>::value, Alignment);\n\n  struct EIGEN_ALIGN_TO_BOUNDARY(Alignment) Empty2 {};\n  VERIFY_IS_EQUAL(std::alignment_of<Empty2>::value, Alignment);\n\n  struct Nested1 { EIGEN_ALIGN_TO_BOUNDARY(Alignment) T data[Size]; };\n  VERIFY_IS_EQUAL(std::alignment_of<Nested1>::value, Alignment);\n\n  VERIFY_IS_EQUAL( (std::alignment_of<internal::plain_array<T,Size,AutoAlign,Alignment> >::value), Alignment);\n\n  const std::size_t default_alignment = internal::compute_default_alignment<T,Size>::value;\n\n  VERIFY_IS_EQUAL( (std::alignment_of<DenseStorage<T,Size,1,1,AutoAlign> >::value), default_alignment);\n  VERIFY_IS_EQUAL( (std::alignment_of<Matrix<T,Size,1,AutoAlign> >::value), default_alignment);\n  struct Nested2 { Matrix<T,Size,1,AutoAlign> mat; };\n  VERIFY_IS_EQUAL(std::alignment_of<Nested2>::value, default_alignment);\n\n  #endif\n}\n\nEIGEN_DECLARE_TEST(dense_storage)\n{\n  dense_storage_copy<int,Dynamic,Dynamic>();  \n  dense_storage_copy<int,Dynamic,3>();\n  dense_storage_copy<int,4,Dynamic>();\n  dense_storage_copy<int,4,3>();\n\n  dense_storage_copy<float,Dynamic,Dynamic>();\n  dense_storage_copy<float,Dynamic,3>();\n  dense_storage_copy<float,4,Dynamic>();  \n  dense_storage_copy<float,4,3>();\n  \n  dense_storage_assignment<int,Dynamic,Dynamic>();  \n  dense_storage_assignment<int,Dynamic,3>();\n  dense_storage_assignment<int,4,Dynamic>();\n  dense_storage_assignment<int,4,3>();\n\n  dense_storage_assignment<float,Dynamic,Dynamic>();\n  dense_storage_assignment<float,Dynamic,3>();\n  dense_storage_assignment<float,4,Dynamic>();  \n  dense_storage_assignment<float,4,3>(); \n\n  dense_storage_alignment<float,16,8>();\n  dense_storage_alignment<float,16,16>();\n  dense_storage_alignment<float,16,32>();\n  dense_storage_alignment<float,16,64>();\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/determinant.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/LU>\n\ntemplate<typename MatrixType> void determinant(const MatrixType& m)\n{\n  /* this test covers the following files:\n     Determinant.h\n  */\n  Index size = m.rows();\n\n  MatrixType m1(size, size), m2(size, size);\n  m1.setRandom();\n  m2.setRandom();\n  typedef typename MatrixType::Scalar Scalar;\n  Scalar x = internal::random<Scalar>();\n  VERIFY_IS_APPROX(MatrixType::Identity(size, size).determinant(), Scalar(1));\n  VERIFY_IS_APPROX((m1*m2).eval().determinant(), m1.determinant() * m2.determinant());\n  if(size==1) return;\n  Index i = internal::random<Index>(0, size-1);\n  Index j;\n  do {\n    j = internal::random<Index>(0, size-1);\n  } while(j==i);\n  m2 = m1;\n  m2.row(i).swap(m2.row(j));\n  VERIFY_IS_APPROX(m2.determinant(), -m1.determinant());\n  m2 = m1;\n  m2.col(i).swap(m2.col(j));\n  VERIFY_IS_APPROX(m2.determinant(), -m1.determinant());\n  VERIFY_IS_APPROX(m2.determinant(), m2.transpose().determinant());\n  VERIFY_IS_APPROX(numext::conj(m2.determinant()), m2.adjoint().determinant());\n  m2 = m1;\n  m2.row(i) += x*m2.row(j);\n  VERIFY_IS_APPROX(m2.determinant(), m1.determinant());\n  m2 = m1;\n  m2.row(i) *= x;\n  VERIFY_IS_APPROX(m2.determinant(), m1.determinant() * x);\n  \n  // check empty matrix\n  VERIFY_IS_APPROX(m2.block(0,0,0,0).determinant(), Scalar(1));\n}\n\nEIGEN_DECLARE_TEST(determinant)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    int s = 0;\n    CALL_SUBTEST_1( determinant(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( determinant(Matrix<double, 2, 2>()) );\n    CALL_SUBTEST_3( determinant(Matrix<double, 3, 3>()) );\n    CALL_SUBTEST_4( determinant(Matrix<double, 4, 4>()) );\n    CALL_SUBTEST_5( determinant(Matrix<std::complex<double>, 10, 10>()) );\n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4);\n    CALL_SUBTEST_6( determinant(MatrixXd(s, s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/diagonal.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void diagonal(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols);\n\n  Scalar s1 = internal::random<Scalar>();\n\n  //check diagonal()\n  VERIFY_IS_APPROX(m1.diagonal(), m1.transpose().diagonal());\n  m2.diagonal() = 2 * m1.diagonal();\n  m2.diagonal()[0] *= 3;\n\n  if (rows>2)\n  {\n    enum {\n      N1 = MatrixType::RowsAtCompileTime>2 ?  2 : 0,\n      N2 = MatrixType::RowsAtCompileTime>1 ? -1 : 0\n    };\n\n    // check sub/super diagonal\n    if(MatrixType::SizeAtCompileTime!=Dynamic)\n    {\n      VERIFY(m1.template diagonal<N1>().RowsAtCompileTime == m1.diagonal(N1).size());\n      VERIFY(m1.template diagonal<N2>().RowsAtCompileTime == m1.diagonal(N2).size());\n    }\n\n    m2.template diagonal<N1>() = 2 * m1.template diagonal<N1>();\n    VERIFY_IS_APPROX(m2.template diagonal<N1>(), static_cast<Scalar>(2) * m1.diagonal(N1));\n    m2.template diagonal<N1>()[0] *= 3;\n    VERIFY_IS_APPROX(m2.template diagonal<N1>()[0], static_cast<Scalar>(6) * m1.template diagonal<N1>()[0]);\n\n\n    m2.template diagonal<N2>() = 2 * m1.template diagonal<N2>();\n    m2.template diagonal<N2>()[0] *= 3;\n    VERIFY_IS_APPROX(m2.template diagonal<N2>()[0], static_cast<Scalar>(6) * m1.template diagonal<N2>()[0]);\n\n    m2.diagonal(N1) = 2 * m1.diagonal(N1);\n    VERIFY_IS_APPROX(m2.template diagonal<N1>(), static_cast<Scalar>(2) * m1.diagonal(N1));\n    m2.diagonal(N1)[0] *= 3;\n    VERIFY_IS_APPROX(m2.diagonal(N1)[0], static_cast<Scalar>(6) * m1.diagonal(N1)[0]);\n\n    m2.diagonal(N2) = 2 * m1.diagonal(N2);\n    VERIFY_IS_APPROX(m2.template diagonal<N2>(), static_cast<Scalar>(2) * m1.diagonal(N2));\n    m2.diagonal(N2)[0] *= 3;\n    VERIFY_IS_APPROX(m2.diagonal(N2)[0], static_cast<Scalar>(6) * m1.diagonal(N2)[0]);\n\n    m2.diagonal(N2).x() = s1;\n    VERIFY_IS_APPROX(m2.diagonal(N2).x(), s1);\n    m2.diagonal(N2).coeffRef(0) = Scalar(2)*s1;\n    VERIFY_IS_APPROX(m2.diagonal(N2).coeff(0), Scalar(2)*s1);\n  }\n\n  VERIFY( m1.diagonal( cols).size()==0 );\n  VERIFY( m1.diagonal(-rows).size()==0 );\n}\n\ntemplate<typename MatrixType> void diagonal_assert(const MatrixType& m) {\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols);\n\n  if (rows>=2 && cols>=2)\n  {\n    VERIFY_RAISES_ASSERT( m1 += m1.diagonal() );\n    VERIFY_RAISES_ASSERT( m1 -= m1.diagonal() );\n    VERIFY_RAISES_ASSERT( m1.array() *= m1.diagonal().array() );\n    VERIFY_RAISES_ASSERT( m1.array() /= m1.diagonal().array() );\n  }\n\n  VERIFY_RAISES_ASSERT( m1.diagonal(cols+1) );\n  VERIFY_RAISES_ASSERT( m1.diagonal(-(rows+1)) );\n}\n\nEIGEN_DECLARE_TEST(diagonal)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( diagonal(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_1( diagonal(Matrix<float, 4, 9>()) );\n    CALL_SUBTEST_1( diagonal(Matrix<float, 7, 3>()) );\n    CALL_SUBTEST_2( diagonal(Matrix4d()) );\n    CALL_SUBTEST_2( diagonal(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_2( diagonal(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_2( diagonal(MatrixXcd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_1( diagonal(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_1( diagonal(Matrix<float,Dynamic,4>(3, 4)) );\n    CALL_SUBTEST_1( diagonal_assert(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/diagonal_matrix_variadic_ctor.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2019 David Tellenbach <david.tellenbach@tellnotes.org>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_STATIC_ASSERT\n\n#include \"main.h\"\n\ntemplate <typename Scalar>\nvoid assertionTest()\n{\n  typedef DiagonalMatrix<Scalar, 5> DiagMatrix5;\n  typedef DiagonalMatrix<Scalar, 7> DiagMatrix7;\n  typedef DiagonalMatrix<Scalar, Dynamic> DiagMatrixX;\n\n  Scalar raw[6];\n  for (int i = 0; i < 6; ++i) {\n    raw[i] = internal::random<Scalar>();\n  }\n\n  VERIFY_RAISES_ASSERT((DiagMatrix5{raw[0], raw[1], raw[2], raw[3]}));\n  VERIFY_RAISES_ASSERT((DiagMatrix5{raw[0], raw[1], raw[3]}));\n  VERIFY_RAISES_ASSERT((DiagMatrix7{raw[0], raw[1], raw[2], raw[3]}));\n\n  VERIFY_RAISES_ASSERT((DiagMatrixX {\n    {raw[0], raw[1], raw[2]},\n    {raw[3], raw[4], raw[5]}\n  }));\n}\n\n#define VERIFY_IMPLICIT_CONVERSION_3(DIAGTYPE, V0, V1, V2) \\\n  DIAGTYPE d(V0, V1, V2);                                  \\\n  DIAGTYPE::DenseMatrixType Dense = d.toDenseMatrix();     \\\n  VERIFY_IS_APPROX(Dense(0, 0), (Scalar)V0);               \\\n  VERIFY_IS_APPROX(Dense(1, 1), (Scalar)V1);               \\\n  VERIFY_IS_APPROX(Dense(2, 2), (Scalar)V2);\n\n#define VERIFY_IMPLICIT_CONVERSION_4(DIAGTYPE, V0, V1, V2, V3) \\\n  DIAGTYPE d(V0, V1, V2, V3);                                  \\\n  DIAGTYPE::DenseMatrixType Dense = d.toDenseMatrix();         \\\n  VERIFY_IS_APPROX(Dense(0, 0), (Scalar)V0);                   \\\n  VERIFY_IS_APPROX(Dense(1, 1), (Scalar)V1);                   \\\n  VERIFY_IS_APPROX(Dense(2, 2), (Scalar)V2);                   \\\n  VERIFY_IS_APPROX(Dense(3, 3), (Scalar)V3);\n\n#define VERIFY_IMPLICIT_CONVERSION_5(DIAGTYPE, V0, V1, V2, V3, V4) \\\n  DIAGTYPE d(V0, V1, V2, V3, V4);                                  \\\n  DIAGTYPE::DenseMatrixType Dense = d.toDenseMatrix();             \\\n  VERIFY_IS_APPROX(Dense(0, 0), (Scalar)V0);                       \\\n  VERIFY_IS_APPROX(Dense(1, 1), (Scalar)V1);                       \\\n  VERIFY_IS_APPROX(Dense(2, 2), (Scalar)V2);                       \\\n  VERIFY_IS_APPROX(Dense(3, 3), (Scalar)V3);                       \\\n  VERIFY_IS_APPROX(Dense(4, 4), (Scalar)V4);\n\ntemplate<typename Scalar>\nvoid constructorTest()\n{\n  typedef DiagonalMatrix<Scalar, 0> DiagonalMatrix0;\n  typedef DiagonalMatrix<Scalar, 3> DiagonalMatrix3;\n  typedef DiagonalMatrix<Scalar, 4> DiagonalMatrix4;\n  typedef DiagonalMatrix<Scalar, Dynamic> DiagonalMatrixX;\n\n  Scalar raw[7];\n  for (int k = 0; k < 7; ++k) raw[k] = internal::random<Scalar>();\n\n  // Fixed-sized matrices\n  {\n    DiagonalMatrix0 a {{}};\n    VERIFY(a.rows() == 0);\n    VERIFY(a.cols() == 0);\n    typename DiagonalMatrix0::DenseMatrixType m = a.toDenseMatrix();\n    for (Index k = 0; k < a.rows(); ++k) VERIFY(m(k, k) == raw[k]);\n  }\n  {\n    DiagonalMatrix3 a {{raw[0], raw[1], raw[2]}};\n    VERIFY(a.rows() == 3);\n    VERIFY(a.cols() == 3);\n    typename DiagonalMatrix3::DenseMatrixType m = a.toDenseMatrix();\n    for (Index k = 0; k < a.rows(); ++k) VERIFY(m(k, k) == raw[k]);\n  }\n  {\n    DiagonalMatrix4 a {{raw[0], raw[1], raw[2], raw[3]}};\n    VERIFY(a.rows() == 4);\n    VERIFY(a.cols() == 4);\n    typename DiagonalMatrix4::DenseMatrixType m = a.toDenseMatrix();\n    for (Index k = 0; k < a.rows(); ++k) VERIFY(m(k, k) == raw[k]);\n  }\n\n  // dynamically sized matrices\n  {\n    DiagonalMatrixX a{{}};\n    VERIFY(a.rows() == 0);\n    VERIFY(a.rows() == 0);\n    typename DiagonalMatrixX::DenseMatrixType m = a.toDenseMatrix();\n    for (Index k = 0; k < a.rows(); ++k) VERIFY(m(k, k) == raw[k]);\n  }\n  {\n    DiagonalMatrixX a{{raw[0], raw[1], raw[2], raw[3], raw[4], raw[5], raw[6]}};\n    VERIFY(a.rows() == 7);\n    VERIFY(a.rows() == 7);\n    typename DiagonalMatrixX::DenseMatrixType m = a.toDenseMatrix();\n    for (Index k = 0; k < a.rows(); ++k) VERIFY(m(k, k) == raw[k]);\n  }\n}\n\ntemplate<>\nvoid constructorTest<float>()\n{\n  typedef float Scalar;\n\n  typedef DiagonalMatrix<Scalar, 0> DiagonalMatrix0;\n  typedef DiagonalMatrix<Scalar, 3> DiagonalMatrix3;\n  typedef DiagonalMatrix<Scalar, 4> DiagonalMatrix4;\n  typedef DiagonalMatrix<Scalar, 5> DiagonalMatrix5;\n  typedef DiagonalMatrix<Scalar, Dynamic> DiagonalMatrixX;\n\n  Scalar raw[7];\n  for (int k = 0; k < 7; ++k) raw[k] = internal::random<Scalar>();\n\n  // Fixed-sized matrices\n  {\n    DiagonalMatrix0 a {{}};\n    VERIFY(a.rows() == 0);\n    VERIFY(a.cols() == 0);\n    typename DiagonalMatrix0::DenseMatrixType m = a.toDenseMatrix();\n    for (Index k = 0; k < a.rows(); ++k) VERIFY(m(k, k) == raw[k]);\n  }\n  {\n    DiagonalMatrix3 a {{raw[0], raw[1], raw[2]}};\n    VERIFY(a.rows() == 3);\n    VERIFY(a.cols() == 3);\n    typename DiagonalMatrix3::DenseMatrixType m = a.toDenseMatrix();\n    for (Index k = 0; k < a.rows(); ++k) VERIFY(m(k, k) == raw[k]);\n  }\n  {\n    DiagonalMatrix4 a {{raw[0], raw[1], raw[2], raw[3]}};\n    VERIFY(a.rows() == 4);\n    VERIFY(a.cols() == 4);\n    typename DiagonalMatrix4::DenseMatrixType m = a.toDenseMatrix();\n    for (Index k = 0; k < a.rows(); ++k) VERIFY(m(k, k) == raw[k]);\n  }\n\n  // dynamically sized matrices\n  {\n    DiagonalMatrixX a{{}};\n    VERIFY(a.rows() == 0);\n    VERIFY(a.rows() == 0);\n    typename DiagonalMatrixX::DenseMatrixType m = a.toDenseMatrix();\n    for (Index k = 0; k < a.rows(); ++k) VERIFY(m(k, k) == raw[k]);\n  }\n  {\n    DiagonalMatrixX a{{raw[0], raw[1], raw[2], raw[3], raw[4], raw[5], raw[6]}};\n    VERIFY(a.rows() == 7);\n    VERIFY(a.rows() == 7);\n    typename DiagonalMatrixX::DenseMatrixType m = a.toDenseMatrix();\n    for (Index k = 0; k < a.rows(); ++k) VERIFY(m(k, k) == raw[k]);\n  }\n  { VERIFY_IMPLICIT_CONVERSION_3(DiagonalMatrix3, 1.2647, 2.56f, -3); }\n  { VERIFY_IMPLICIT_CONVERSION_4(DiagonalMatrix4, 1.2647, 2.56f, -3, 3.23f); }\n  { VERIFY_IMPLICIT_CONVERSION_5(DiagonalMatrix5, 1.2647, 2.56f, -3, 3.23f, 2); }\n}\n\nEIGEN_DECLARE_TEST(diagonal_matrix_variadic_ctor)\n{\n  CALL_SUBTEST_1(assertionTest<unsigned char>());\n  CALL_SUBTEST_1(assertionTest<float>());\n  CALL_SUBTEST_1(assertionTest<Index>());\n  CALL_SUBTEST_1(assertionTest<int>());\n  CALL_SUBTEST_1(assertionTest<long int>());\n  CALL_SUBTEST_1(assertionTest<std::ptrdiff_t>());\n  CALL_SUBTEST_1(assertionTest<std::complex<double>>());\n\n  CALL_SUBTEST_2(constructorTest<unsigned char>());\n  CALL_SUBTEST_2(constructorTest<float>());\n  CALL_SUBTEST_2(constructorTest<Index>());\n  CALL_SUBTEST_2(constructorTest<int>());\n  CALL_SUBTEST_2(constructorTest<long int>());\n  CALL_SUBTEST_2(constructorTest<std::ptrdiff_t>());\n  CALL_SUBTEST_2(constructorTest<std::complex<double>>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/diagonalmatrices.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\nusing namespace std;\ntemplate<typename MatrixType> void diagonalmatrices(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  enum { Rows = MatrixType::RowsAtCompileTime, Cols = MatrixType::ColsAtCompileTime };\n  typedef Matrix<Scalar, Rows, 1> VectorType;\n  typedef Matrix<Scalar, 1, Cols> RowVectorType;\n  typedef Matrix<Scalar, Rows, Rows> SquareMatrixType;\n  typedef Matrix<Scalar, Dynamic, Dynamic> DynMatrixType;\n  typedef DiagonalMatrix<Scalar, Rows> LeftDiagonalMatrix;\n  typedef DiagonalMatrix<Scalar, Cols> RightDiagonalMatrix;\n  typedef Matrix<Scalar, Rows==Dynamic?Dynamic:2*Rows, Cols==Dynamic?Dynamic:2*Cols> BigMatrix;\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols);\n  VectorType v1 = VectorType::Random(rows),\n             v2 = VectorType::Random(rows);\n  RowVectorType rv1 = RowVectorType::Random(cols),\n             rv2 = RowVectorType::Random(cols);\n\n  LeftDiagonalMatrix ldm1(v1), ldm2(v2);\n  RightDiagonalMatrix rdm1(rv1), rdm2(rv2);\n  \n  Scalar s1 = internal::random<Scalar>();\n\n  SquareMatrixType sq_m1 (v1.asDiagonal());\n  VERIFY_IS_APPROX(sq_m1, v1.asDiagonal().toDenseMatrix());\n  sq_m1 = v1.asDiagonal();\n  VERIFY_IS_APPROX(sq_m1, v1.asDiagonal().toDenseMatrix());\n  SquareMatrixType sq_m2 = v1.asDiagonal();\n  VERIFY_IS_APPROX(sq_m1, sq_m2);\n  \n  ldm1 = v1.asDiagonal();\n  LeftDiagonalMatrix ldm3(v1);\n  VERIFY_IS_APPROX(ldm1.diagonal(), ldm3.diagonal());\n  LeftDiagonalMatrix ldm4 = v1.asDiagonal();\n  VERIFY_IS_APPROX(ldm1.diagonal(), ldm4.diagonal());\n  \n  sq_m1.block(0,0,rows,rows) = ldm1;\n  VERIFY_IS_APPROX(sq_m1, ldm1.toDenseMatrix());\n  sq_m1.transpose() = ldm1;\n  VERIFY_IS_APPROX(sq_m1, ldm1.toDenseMatrix());\n  \n  Index i = internal::random<Index>(0, rows-1);\n  Index j = internal::random<Index>(0, cols-1);\n  \n  VERIFY_IS_APPROX( ((ldm1 * m1)(i,j))  , ldm1.diagonal()(i) * m1(i,j) );\n  VERIFY_IS_APPROX( ((ldm1 * (m1+m2))(i,j))  , ldm1.diagonal()(i) * (m1+m2)(i,j) );\n  VERIFY_IS_APPROX( ((m1 * rdm1)(i,j))  , rdm1.diagonal()(j) * m1(i,j) );\n  VERIFY_IS_APPROX( ((v1.asDiagonal() * m1)(i,j))  , v1(i) * m1(i,j) );\n  VERIFY_IS_APPROX( ((m1 * rv1.asDiagonal())(i,j))  , rv1(j) * m1(i,j) );\n  VERIFY_IS_APPROX( (((v1+v2).asDiagonal() * m1)(i,j))  , (v1+v2)(i) * m1(i,j) );\n  VERIFY_IS_APPROX( (((v1+v2).asDiagonal() * (m1+m2))(i,j))  , (v1+v2)(i) * (m1+m2)(i,j) );\n  VERIFY_IS_APPROX( ((m1 * (rv1+rv2).asDiagonal())(i,j))  , (rv1+rv2)(j) * m1(i,j) );\n  VERIFY_IS_APPROX( (((m1+m2) * (rv1+rv2).asDiagonal())(i,j))  , (rv1+rv2)(j) * (m1+m2)(i,j) );\n  \n  if(rows>1)\n  {\n    DynMatrixType tmp = m1.topRows(rows/2), res;\n    VERIFY_IS_APPROX( (res = m1.topRows(rows/2) * rv1.asDiagonal()), tmp * rv1.asDiagonal() );\n    VERIFY_IS_APPROX( (res = v1.head(rows/2).asDiagonal()*m1.topRows(rows/2)), v1.head(rows/2).asDiagonal()*tmp );\n  }\n\n  BigMatrix big;\n  big.setZero(2*rows, 2*cols);\n  \n  big.block(i,j,rows,cols) = m1;\n  big.block(i,j,rows,cols) = v1.asDiagonal() * big.block(i,j,rows,cols);\n  \n  VERIFY_IS_APPROX((big.block(i,j,rows,cols)) , v1.asDiagonal() * m1 );\n  \n  big.block(i,j,rows,cols) = m1;\n  big.block(i,j,rows,cols) = big.block(i,j,rows,cols) * rv1.asDiagonal();\n  VERIFY_IS_APPROX((big.block(i,j,rows,cols)) , m1 * rv1.asDiagonal() );\n  \n  \n  // scalar multiple\n  VERIFY_IS_APPROX(LeftDiagonalMatrix(ldm1*s1).diagonal(), ldm1.diagonal() * s1);\n  VERIFY_IS_APPROX(LeftDiagonalMatrix(s1*ldm1).diagonal(), s1 * ldm1.diagonal());\n  \n  VERIFY_IS_APPROX(m1 * (rdm1 * s1), (m1 * rdm1) * s1);\n  VERIFY_IS_APPROX(m1 * (s1 * rdm1), (m1 * rdm1) * s1);\n  \n  // Diagonal to dense\n  sq_m1.setRandom();\n  sq_m2 = sq_m1;\n  VERIFY_IS_APPROX( (sq_m1 += (s1*v1).asDiagonal()), sq_m2 += (s1*v1).asDiagonal().toDenseMatrix() );\n  VERIFY_IS_APPROX( (sq_m1 -= (s1*v1).asDiagonal()), sq_m2 -= (s1*v1).asDiagonal().toDenseMatrix() );\n  VERIFY_IS_APPROX( (sq_m1 = (s1*v1).asDiagonal()), (s1*v1).asDiagonal().toDenseMatrix() );\n\n  sq_m1.setRandom();\n  sq_m2 = v1.asDiagonal();\n  sq_m2 = sq_m1 * sq_m2;\n  VERIFY_IS_APPROX( (sq_m1*v1.asDiagonal()).col(i), sq_m2.col(i) );\n  VERIFY_IS_APPROX( (sq_m1*v1.asDiagonal()).row(i), sq_m2.row(i) );\n\n  sq_m1 = v1.asDiagonal();\n  sq_m2 = v2.asDiagonal();\n  SquareMatrixType sq_m3 = v1.asDiagonal();\n  VERIFY_IS_APPROX( sq_m3 = v1.asDiagonal() + v2.asDiagonal(), sq_m1 + sq_m2);\n  VERIFY_IS_APPROX( sq_m3 = v1.asDiagonal() - v2.asDiagonal(), sq_m1 - sq_m2);\n  VERIFY_IS_APPROX( sq_m3 = v1.asDiagonal() - 2*v2.asDiagonal() + v1.asDiagonal(), sq_m1 - 2*sq_m2 + sq_m1);\n}\n\ntemplate<typename MatrixType> void as_scalar_product(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n  typedef Matrix<Scalar, Dynamic, Dynamic> DynMatrixType;\n  typedef Matrix<Scalar, Dynamic, 1> DynVectorType;\n  typedef Matrix<Scalar, 1, Dynamic> DynRowVectorType;\n\n  Index rows = m.rows();\n  Index depth = internal::random<Index>(1,EIGEN_TEST_MAX_SIZE);\n\n  VectorType v1 = VectorType::Random(rows);  \n  DynVectorType     dv1  = DynVectorType::Random(depth);\n  DynRowVectorType  drv1 = DynRowVectorType::Random(depth);\n  DynMatrixType     dm1  = dv1;\n  DynMatrixType     drm1 = drv1;\n  \n  Scalar s = v1(0);\n\n  VERIFY_IS_APPROX( v1.asDiagonal() * drv1, s*drv1 );\n  VERIFY_IS_APPROX( dv1 * v1.asDiagonal(), dv1*s );\n\n  VERIFY_IS_APPROX( v1.asDiagonal() * drm1, s*drm1 );\n  VERIFY_IS_APPROX( dm1 * v1.asDiagonal(), dm1*s );\n}\n\ntemplate<int>\nvoid bug987()\n{\n  Matrix3Xd points = Matrix3Xd::Random(3, 3);\n  Vector2d diag = Vector2d::Random();\n  Matrix2Xd tmp1 = points.topRows<2>(), res1, res2;\n  VERIFY_IS_APPROX( res1 = diag.asDiagonal() * points.topRows<2>(), res2 = diag.asDiagonal() * tmp1 );\n  Matrix2d tmp2 = points.topLeftCorner<2,2>();\n  VERIFY_IS_APPROX(( res1 = points.topLeftCorner<2,2>()*diag.asDiagonal()) , res2 = tmp2*diag.asDiagonal() );\n}\n\nEIGEN_DECLARE_TEST(diagonalmatrices)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( diagonalmatrices(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_1( as_scalar_product(Matrix<float, 1, 1>()) );\n\n    CALL_SUBTEST_2( diagonalmatrices(Matrix3f()) );\n    CALL_SUBTEST_3( diagonalmatrices(Matrix<double,3,3,RowMajor>()) );\n    CALL_SUBTEST_4( diagonalmatrices(Matrix4d()) );\n    CALL_SUBTEST_5( diagonalmatrices(Matrix<float,4,4,RowMajor>()) );\n    CALL_SUBTEST_6( diagonalmatrices(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( as_scalar_product(MatrixXcf(1,1)) );\n    CALL_SUBTEST_7( diagonalmatrices(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_8( diagonalmatrices(Matrix<double,Dynamic,Dynamic,RowMajor>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_9( diagonalmatrices(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_9( diagonalmatrices(MatrixXf(1,1)) );\n    CALL_SUBTEST_9( as_scalar_product(MatrixXf(1,1)) );\n  }\n  CALL_SUBTEST_10( bug987<0>() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/dontalign.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#if defined EIGEN_TEST_PART_1 || defined EIGEN_TEST_PART_2 || defined EIGEN_TEST_PART_3 || defined EIGEN_TEST_PART_4\n#define EIGEN_DONT_ALIGN\n#elif defined EIGEN_TEST_PART_5 || defined EIGEN_TEST_PART_6 || defined EIGEN_TEST_PART_7 || defined EIGEN_TEST_PART_8\n#define EIGEN_DONT_ALIGN_STATICALLY\n#endif\n\n#include \"main.h\"\n#include <Eigen/Dense>\n\ntemplate<typename MatrixType>\nvoid dontalign(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> SquareMatrixType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType a = MatrixType::Random(rows,cols);\n  SquareMatrixType square = SquareMatrixType::Random(rows,rows);\n  VectorType v = VectorType::Random(rows);\n\n  VERIFY_IS_APPROX(v, square * square.colPivHouseholderQr().solve(v));\n  square = square.inverse().eval();\n  a = square * a;\n  square = square*square;\n  v = square * v;\n  v = a.adjoint() * v;\n  VERIFY(square.determinant() != Scalar(0));\n\n  // bug 219: MapAligned() was giving an assert with EIGEN_DONT_ALIGN, because Map Flags were miscomputed\n  Scalar* array = internal::aligned_new<Scalar>(rows);\n  v = VectorType::MapAligned(array, rows);\n  internal::aligned_delete(array, rows);\n}\n\nEIGEN_DECLARE_TEST(dontalign)\n{\n#if defined EIGEN_TEST_PART_1 || defined EIGEN_TEST_PART_5\n  dontalign(Matrix3d());\n  dontalign(Matrix4f());\n#elif defined EIGEN_TEST_PART_2 || defined EIGEN_TEST_PART_6\n  dontalign(Matrix3cd());\n  dontalign(Matrix4cf());\n#elif defined EIGEN_TEST_PART_3 || defined EIGEN_TEST_PART_7\n  dontalign(Matrix<float, 32, 32>());\n  dontalign(Matrix<std::complex<float>, 32, 32>());\n#elif defined EIGEN_TEST_PART_4 || defined EIGEN_TEST_PART_8\n  dontalign(MatrixXd(32, 32));\n  dontalign(MatrixXcf(32, 32));\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/dynalloc.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#if EIGEN_MAX_ALIGN_BYTES>0\n#define ALIGNMENT EIGEN_MAX_ALIGN_BYTES\n#else\n#define ALIGNMENT 1\n#endif\n\ntypedef Matrix<float,16,1> Vector16f;\ntypedef Matrix<float,8,1> Vector8f;\n\nvoid check_handmade_aligned_malloc()\n{\n  for(int i = 1; i < 1000; i++)\n  {\n    char *p = (char*)internal::handmade_aligned_malloc(i);\n    VERIFY(internal::UIntPtr(p)%ALIGNMENT==0);\n    // if the buffer is wrongly allocated this will give a bad write --> check with valgrind\n    for(int j = 0; j < i; j++) p[j]=0;\n    internal::handmade_aligned_free(p);\n  }\n}\n\nvoid check_aligned_malloc()\n{\n  for(int i = ALIGNMENT; i < 1000; i++)\n  {\n    char *p = (char*)internal::aligned_malloc(i);\n    VERIFY(internal::UIntPtr(p)%ALIGNMENT==0);\n    // if the buffer is wrongly allocated this will give a bad write --> check with valgrind\n    for(int j = 0; j < i; j++) p[j]=0;\n    internal::aligned_free(p);\n  }\n}\n\nvoid check_aligned_new()\n{\n  for(int i = ALIGNMENT; i < 1000; i++)\n  {\n    float *p = internal::aligned_new<float>(i);\n    VERIFY(internal::UIntPtr(p)%ALIGNMENT==0);\n    // if the buffer is wrongly allocated this will give a bad write --> check with valgrind\n    for(int j = 0; j < i; j++) p[j]=0;\n    internal::aligned_delete(p,i);\n  }\n}\n\nvoid check_aligned_stack_alloc()\n{\n  for(int i = ALIGNMENT; i < 400; i++)\n  {\n    ei_declare_aligned_stack_constructed_variable(float,p,i,0);\n    VERIFY(internal::UIntPtr(p)%ALIGNMENT==0);\n    // if the buffer is wrongly allocated this will give a bad write --> check with valgrind\n    for(int j = 0; j < i; j++) p[j]=0;\n  }\n}\n\n\n// test compilation with both a struct and a class...\nstruct MyStruct\n{\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n  char dummychar;\n  Vector16f avec;\n};\n\nclass MyClassA\n{\n  public:\n    EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n    char dummychar;\n    Vector16f avec;\n};\n\ntemplate<typename T> void check_dynaligned()\n{\n  // TODO have to be updated once we support multiple alignment values\n  if(T::SizeAtCompileTime % ALIGNMENT == 0)\n  {\n    T* obj = new T;\n    VERIFY(T::NeedsToAlign==1);\n    VERIFY(internal::UIntPtr(obj)%ALIGNMENT==0);\n    delete obj;\n  }\n}\n\ntemplate<typename T> void check_custom_new_delete()\n{\n  {\n    T* t = new T;\n    delete t;\n  }\n  \n  {\n    std::size_t N = internal::random<std::size_t>(1,10);\n    T* t = new T[N];\n    delete[] t;\n  }\n  \n#if EIGEN_MAX_ALIGN_BYTES>0 && (!EIGEN_HAS_CXX17_OVERALIGN)\n  {\n    T* t = static_cast<T *>((T::operator new)(sizeof(T)));\n    (T::operator delete)(t, sizeof(T));\n  }\n  \n  {\n    T* t = static_cast<T *>((T::operator new)(sizeof(T)));\n    (T::operator delete)(t);\n  }\n#endif\n}\n\nEIGEN_DECLARE_TEST(dynalloc)\n{\n  // low level dynamic memory allocation\n  CALL_SUBTEST(check_handmade_aligned_malloc());\n  CALL_SUBTEST(check_aligned_malloc());\n  CALL_SUBTEST(check_aligned_new());\n  CALL_SUBTEST(check_aligned_stack_alloc());\n\n  for (int i=0; i<g_repeat*100; ++i)\n  {\n    CALL_SUBTEST( check_custom_new_delete<Vector4f>() );\n    CALL_SUBTEST( check_custom_new_delete<Vector2f>() );\n    CALL_SUBTEST( check_custom_new_delete<Matrix4f>() );\n    CALL_SUBTEST( check_custom_new_delete<MatrixXi>() );\n  }\n  \n  // check static allocation, who knows ?\n  #if EIGEN_MAX_STATIC_ALIGN_BYTES\n  for (int i=0; i<g_repeat*100; ++i)\n  {\n    CALL_SUBTEST(check_dynaligned<Vector4f>() );\n    CALL_SUBTEST(check_dynaligned<Vector2d>() );\n    CALL_SUBTEST(check_dynaligned<Matrix4f>() );\n    CALL_SUBTEST(check_dynaligned<Vector4d>() );\n    CALL_SUBTEST(check_dynaligned<Vector4i>() );\n    CALL_SUBTEST(check_dynaligned<Vector8f>() );\n    CALL_SUBTEST(check_dynaligned<Vector16f>() );\n  }\n\n  {\n    MyStruct foo0;  VERIFY(internal::UIntPtr(foo0.avec.data())%ALIGNMENT==0);\n    MyClassA fooA;  VERIFY(internal::UIntPtr(fooA.avec.data())%ALIGNMENT==0);\n  }\n  \n  // dynamic allocation, single object\n  for (int i=0; i<g_repeat*100; ++i)\n  {\n    MyStruct *foo0 = new MyStruct();  VERIFY(internal::UIntPtr(foo0->avec.data())%ALIGNMENT==0);\n    MyClassA *fooA = new MyClassA();  VERIFY(internal::UIntPtr(fooA->avec.data())%ALIGNMENT==0);\n    delete foo0;\n    delete fooA;\n  }\n\n  // dynamic allocation, array\n  const int N = 10;\n  for (int i=0; i<g_repeat*100; ++i)\n  {\n    MyStruct *foo0 = new MyStruct[N];  VERIFY(internal::UIntPtr(foo0->avec.data())%ALIGNMENT==0);\n    MyClassA *fooA = new MyClassA[N];  VERIFY(internal::UIntPtr(fooA->avec.data())%ALIGNMENT==0);\n    delete[] foo0;\n    delete[] fooA;\n  }\n  #endif\n  \n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/eigen2support.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN2_SUPPORT\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void eigen2support(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m3(rows, cols);\n\n  Scalar  s1 = internal::random<Scalar>(),\n          s2 = internal::random<Scalar>();\n\n  // scalar addition\n  VERIFY_IS_APPROX(m1.cwise() + s1, s1 + m1.cwise());\n  VERIFY_IS_APPROX(m1.cwise() + s1, MatrixType::Constant(rows,cols,s1) + m1);\n  VERIFY_IS_APPROX((m1*Scalar(2)).cwise() - s2, (m1+m1) - MatrixType::Constant(rows,cols,s2) );\n  m3 = m1;\n  m3.cwise() += s2;\n  VERIFY_IS_APPROX(m3, m1.cwise() + s2);\n  m3 = m1;\n  m3.cwise() -= s1;\n  VERIFY_IS_APPROX(m3, m1.cwise() - s1);\n\n  VERIFY_IS_EQUAL((m1.corner(TopLeft,1,1)), (m1.block(0,0,1,1)));\n  VERIFY_IS_EQUAL((m1.template corner<1,1>(TopLeft)), (m1.template block<1,1>(0,0)));\n  VERIFY_IS_EQUAL((m1.col(0).start(1)), (m1.col(0).segment(0,1)));\n  VERIFY_IS_EQUAL((m1.col(0).template start<1>()), (m1.col(0).segment(0,1)));\n  VERIFY_IS_EQUAL((m1.col(0).end(1)), (m1.col(0).segment(rows-1,1)));\n  VERIFY_IS_EQUAL((m1.col(0).template end<1>()), (m1.col(0).segment(rows-1,1)));\n  \n  using std::cos;\n  using numext::real;\n  using numext::abs2;\n  VERIFY_IS_EQUAL(ei_cos(s1), cos(s1));\n  VERIFY_IS_EQUAL(ei_real(s1), real(s1));\n  VERIFY_IS_EQUAL(ei_abs2(s1), abs2(s1));\n\n  m1.minor(0,0);\n}\n\nEIGEN_DECLARE_TEST(eigen2support)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( eigen2support(Matrix<double,1,1>()) );\n    CALL_SUBTEST_2( eigen2support(MatrixXd(1,1)) );\n    CALL_SUBTEST_4( eigen2support(Matrix3f()) );\n    CALL_SUBTEST_5( eigen2support(Matrix4d()) );\n    CALL_SUBTEST_2( eigen2support(MatrixXf(200,200)) );\n    CALL_SUBTEST_6( eigen2support(MatrixXcd(100,100)) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/eigensolver_complex.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <limits>\n#include <Eigen/Eigenvalues>\n#include <Eigen/LU>\n\ntemplate<typename MatrixType> bool find_pivot(typename MatrixType::Scalar tol, MatrixType &diffs, Index col=0)\n{\n  bool match = diffs.diagonal().sum() <= tol;\n  if(match || col==diffs.cols())\n  {\n    return match;\n  }\n  else\n  {\n    Index n = diffs.cols();\n    std::vector<std::pair<Index,Index> > transpositions;\n    for(Index i=col; i<n; ++i)\n    {\n      Index best_index(0);\n      if(diffs.col(col).segment(col,n-i).minCoeff(&best_index) > tol)\n        break;\n      \n      best_index += col;\n      \n      diffs.row(col).swap(diffs.row(best_index));\n      if(find_pivot(tol,diffs,col+1)) return true;\n      diffs.row(col).swap(diffs.row(best_index));\n      \n      // move current pivot to the end\n      diffs.row(n-(i-col)-1).swap(diffs.row(best_index));\n      transpositions.push_back(std::pair<Index,Index>(n-(i-col)-1,best_index));\n    }\n    // restore\n    for(Index k=transpositions.size()-1; k>=0; --k)\n      diffs.row(transpositions[k].first).swap(diffs.row(transpositions[k].second));\n  }\n  return false;\n}\n\n/* Check that two column vectors are approximately equal up to permutations.\n * Initially, this method checked that the k-th power sums are equal for all k = 1, ..., vec1.rows(),\n * however this strategy is numerically inacurate because of numerical cancellation issues.\n */\ntemplate<typename VectorType>\nvoid verify_is_approx_upto_permutation(const VectorType& vec1, const VectorType& vec2)\n{\n  typedef typename VectorType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  VERIFY(vec1.cols() == 1);\n  VERIFY(vec2.cols() == 1);\n  VERIFY(vec1.rows() == vec2.rows());\n  \n  Index n = vec1.rows();\n  RealScalar tol = test_precision<RealScalar>()*test_precision<RealScalar>()*numext::maxi(vec1.squaredNorm(),vec2.squaredNorm());\n  Matrix<RealScalar,Dynamic,Dynamic> diffs = (vec1.rowwise().replicate(n) - vec2.rowwise().replicate(n).transpose()).cwiseAbs2();\n  \n  VERIFY( find_pivot(tol, diffs) );\n}\n\n\ntemplate<typename MatrixType> void eigensolver(const MatrixType& m)\n{\n  /* this test covers the following files:\n     ComplexEigenSolver.h, and indirectly ComplexSchur.h\n  */\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  MatrixType a = MatrixType::Random(rows,cols);\n  MatrixType symmA =  a.adjoint() * a;\n\n  ComplexEigenSolver<MatrixType> ei0(symmA);\n  VERIFY_IS_EQUAL(ei0.info(), Success);\n  VERIFY_IS_APPROX(symmA * ei0.eigenvectors(), ei0.eigenvectors() * ei0.eigenvalues().asDiagonal());\n\n  ComplexEigenSolver<MatrixType> ei1(a);\n  VERIFY_IS_EQUAL(ei1.info(), Success);\n  VERIFY_IS_APPROX(a * ei1.eigenvectors(), ei1.eigenvectors() * ei1.eigenvalues().asDiagonal());\n  // Note: If MatrixType is real then a.eigenvalues() uses EigenSolver and thus\n  // another algorithm so results may differ slightly\n  verify_is_approx_upto_permutation(a.eigenvalues(), ei1.eigenvalues());\n\n  ComplexEigenSolver<MatrixType> ei2;\n  ei2.setMaxIterations(ComplexSchur<MatrixType>::m_maxIterationsPerRow * rows).compute(a);\n  VERIFY_IS_EQUAL(ei2.info(), Success);\n  VERIFY_IS_EQUAL(ei2.eigenvectors(), ei1.eigenvectors());\n  VERIFY_IS_EQUAL(ei2.eigenvalues(), ei1.eigenvalues());\n  if (rows > 2) {\n    ei2.setMaxIterations(1).compute(a);\n    VERIFY_IS_EQUAL(ei2.info(), NoConvergence);\n    VERIFY_IS_EQUAL(ei2.getMaxIterations(), 1);\n  }\n\n  ComplexEigenSolver<MatrixType> eiNoEivecs(a, false);\n  VERIFY_IS_EQUAL(eiNoEivecs.info(), Success);\n  VERIFY_IS_APPROX(ei1.eigenvalues(), eiNoEivecs.eigenvalues());\n\n  // Regression test for issue #66\n  MatrixType z = MatrixType::Zero(rows,cols);\n  ComplexEigenSolver<MatrixType> eiz(z);\n  VERIFY((eiz.eigenvalues().cwiseEqual(0)).all());\n\n  MatrixType id = MatrixType::Identity(rows, cols);\n  VERIFY_IS_APPROX(id.operatorNorm(), RealScalar(1));\n\n  if (rows > 1 && rows < 20)\n  {\n    // Test matrix with NaN\n    a(0,0) = std::numeric_limits<typename MatrixType::RealScalar>::quiet_NaN();\n    ComplexEigenSolver<MatrixType> eiNaN(a);\n    VERIFY_IS_EQUAL(eiNaN.info(), NoConvergence);\n  }\n\n  // regression test for bug 1098\n  {\n    ComplexEigenSolver<MatrixType> eig(a.adjoint() * a);\n    eig.compute(a.adjoint() * a);\n  }\n\n  // regression test for bug 478\n  {\n    a.setZero();\n    ComplexEigenSolver<MatrixType> ei3(a);\n    VERIFY_IS_EQUAL(ei3.info(), Success);\n    VERIFY_IS_MUCH_SMALLER_THAN(ei3.eigenvalues().norm(),RealScalar(1));\n    VERIFY((ei3.eigenvectors().transpose()*ei3.eigenvectors().transpose()).eval().isIdentity());\n  }\n}\n\ntemplate<typename MatrixType> void eigensolver_verify_assert(const MatrixType& m)\n{\n  ComplexEigenSolver<MatrixType> eig;\n  VERIFY_RAISES_ASSERT(eig.eigenvectors());\n  VERIFY_RAISES_ASSERT(eig.eigenvalues());\n\n  MatrixType a = MatrixType::Random(m.rows(),m.cols());\n  eig.compute(a, false);\n  VERIFY_RAISES_ASSERT(eig.eigenvectors());\n}\n\nEIGEN_DECLARE_TEST(eigensolver_complex)\n{\n  int s = 0;\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( eigensolver(Matrix4cf()) );\n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4);\n    CALL_SUBTEST_2( eigensolver(MatrixXcd(s,s)) );\n    CALL_SUBTEST_3( eigensolver(Matrix<std::complex<float>, 1, 1>()) );\n    CALL_SUBTEST_4( eigensolver(Matrix3f()) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n  }\n  CALL_SUBTEST_1( eigensolver_verify_assert(Matrix4cf()) );\n  s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4);\n  CALL_SUBTEST_2( eigensolver_verify_assert(MatrixXcd(s,s)) );\n  CALL_SUBTEST_3( eigensolver_verify_assert(Matrix<std::complex<float>, 1, 1>()) );\n  CALL_SUBTEST_4( eigensolver_verify_assert(Matrix3f()) );\n\n  // Test problem size constructors\n  CALL_SUBTEST_5(ComplexEigenSolver<MatrixXf> tmp(s));\n  \n  TEST_SET_BUT_UNUSED_VARIABLE(s)\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/eigensolver_generalized_real.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012-2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_RUNTIME_NO_MALLOC\n#include \"main.h\"\n#include <limits>\n#include <Eigen/Eigenvalues>\n#include <Eigen/LU>\n\ntemplate<typename MatrixType> void generalized_eigensolver_real(const MatrixType& m)\n{\n  /* this test covers the following files:\n     GeneralizedEigenSolver.h\n  */\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef std::complex<Scalar> ComplexScalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n\n  MatrixType a = MatrixType::Random(rows,cols);\n  MatrixType b = MatrixType::Random(rows,cols);\n  MatrixType a1 = MatrixType::Random(rows,cols);\n  MatrixType b1 = MatrixType::Random(rows,cols);\n  MatrixType spdA =  a.adjoint() * a + a1.adjoint() * a1;\n  MatrixType spdB =  b.adjoint() * b + b1.adjoint() * b1;\n\n  // lets compare to GeneralizedSelfAdjointEigenSolver\n  {\n    GeneralizedSelfAdjointEigenSolver<MatrixType> symmEig(spdA, spdB);\n    GeneralizedEigenSolver<MatrixType> eig(spdA, spdB);\n\n    VERIFY_IS_EQUAL(eig.eigenvalues().imag().cwiseAbs().maxCoeff(), 0);\n\n    VectorType realEigenvalues = eig.eigenvalues().real();\n    std::sort(realEigenvalues.data(), realEigenvalues.data()+realEigenvalues.size());\n    VERIFY_IS_APPROX(realEigenvalues, symmEig.eigenvalues());\n\n    // check eigenvectors\n    typename GeneralizedEigenSolver<MatrixType>::EigenvectorsType D = eig.eigenvalues().asDiagonal();\n    typename GeneralizedEigenSolver<MatrixType>::EigenvectorsType V = eig.eigenvectors();\n    VERIFY_IS_APPROX(spdA*V, spdB*V*D);\n  }\n\n  // non symmetric case:\n  {\n    GeneralizedEigenSolver<MatrixType> eig(rows);\n    // TODO enable full-prealocation of required memory, this probably requires an in-place mode for HessenbergDecomposition\n    //Eigen::internal::set_is_malloc_allowed(false);\n    eig.compute(a,b);\n    //Eigen::internal::set_is_malloc_allowed(true);\n    for(Index k=0; k<cols; ++k)\n    {\n      Matrix<ComplexScalar,Dynamic,Dynamic> tmp = (eig.betas()(k)*a).template cast<ComplexScalar>() - eig.alphas()(k)*b;\n      if(tmp.size()>1 && tmp.norm()>(std::numeric_limits<Scalar>::min)())\n        tmp /= tmp.norm();\n      VERIFY_IS_MUCH_SMALLER_THAN( std::abs(tmp.determinant()), Scalar(1) );\n    }\n    // check eigenvectors\n    typename GeneralizedEigenSolver<MatrixType>::EigenvectorsType D = eig.eigenvalues().asDiagonal();\n    typename GeneralizedEigenSolver<MatrixType>::EigenvectorsType V = eig.eigenvectors();\n    VERIFY_IS_APPROX(a*V, b*V*D);\n  }\n\n  // regression test for bug 1098\n  {\n    GeneralizedSelfAdjointEigenSolver<MatrixType> eig1(a.adjoint() * a,b.adjoint() * b);\n    eig1.compute(a.adjoint() * a,b.adjoint() * b);\n    GeneralizedEigenSolver<MatrixType> eig2(a.adjoint() * a,b.adjoint() * b);\n    eig2.compute(a.adjoint() * a,b.adjoint() * b);\n  }\n\n  // check without eigenvectors\n  {\n    GeneralizedEigenSolver<MatrixType> eig1(spdA, spdB, true);\n    GeneralizedEigenSolver<MatrixType> eig2(spdA, spdB, false);\n    VERIFY_IS_APPROX(eig1.eigenvalues(), eig2.eigenvalues());\n  }\n}\n\nEIGEN_DECLARE_TEST(eigensolver_generalized_real)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    int s = 0;\n    CALL_SUBTEST_1( generalized_eigensolver_real(Matrix4f()) );\n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4);\n    CALL_SUBTEST_2( generalized_eigensolver_real(MatrixXd(s,s)) );\n\n    // some trivial but implementation-wise special cases\n    CALL_SUBTEST_2( generalized_eigensolver_real(MatrixXd(1,1)) );\n    CALL_SUBTEST_2( generalized_eigensolver_real(MatrixXd(2,2)) );\n    CALL_SUBTEST_3( generalized_eigensolver_real(Matrix<double,1,1>()) );\n    CALL_SUBTEST_4( generalized_eigensolver_real(Matrix2d()) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/eigensolver_generic.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010,2012 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <limits>\n#include <Eigen/Eigenvalues>\n\ntemplate<typename EigType,typename MatType>\nvoid check_eigensolver_for_given_mat(const EigType &eig, const MatType& a)\n{\n  typedef typename NumTraits<typename MatType::Scalar>::Real RealScalar;\n  typedef Matrix<RealScalar, MatType::RowsAtCompileTime, 1> RealVectorType;\n  typedef typename std::complex<RealScalar> Complex;\n  Index n = a.rows();\n  VERIFY_IS_EQUAL(eig.info(), Success);\n  VERIFY_IS_APPROX(a * eig.pseudoEigenvectors(), eig.pseudoEigenvectors() * eig.pseudoEigenvalueMatrix());\n  VERIFY_IS_APPROX(a.template cast<Complex>() * eig.eigenvectors(),\n                   eig.eigenvectors() * eig.eigenvalues().asDiagonal());\n  VERIFY_IS_APPROX(eig.eigenvectors().colwise().norm(), RealVectorType::Ones(n).transpose());\n  VERIFY_IS_APPROX(a.eigenvalues(), eig.eigenvalues());\n}\n\ntemplate<typename MatrixType> void eigensolver(const MatrixType& m)\n{\n  /* this test covers the following files:\n     EigenSolver.h\n  */\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef typename std::complex<RealScalar> Complex;\n\n  MatrixType a = MatrixType::Random(rows,cols);\n  MatrixType a1 = MatrixType::Random(rows,cols);\n  MatrixType symmA =  a.adjoint() * a + a1.adjoint() * a1;\n\n  EigenSolver<MatrixType> ei0(symmA);\n  VERIFY_IS_EQUAL(ei0.info(), Success);\n  VERIFY_IS_APPROX(symmA * ei0.pseudoEigenvectors(), ei0.pseudoEigenvectors() * ei0.pseudoEigenvalueMatrix());\n  VERIFY_IS_APPROX((symmA.template cast<Complex>()) * (ei0.pseudoEigenvectors().template cast<Complex>()),\n    (ei0.pseudoEigenvectors().template cast<Complex>()) * (ei0.eigenvalues().asDiagonal()));\n\n  EigenSolver<MatrixType> ei1(a);\n  CALL_SUBTEST( check_eigensolver_for_given_mat(ei1,a) );\n\n  EigenSolver<MatrixType> ei2;\n  ei2.setMaxIterations(RealSchur<MatrixType>::m_maxIterationsPerRow * rows).compute(a);\n  VERIFY_IS_EQUAL(ei2.info(), Success);\n  VERIFY_IS_EQUAL(ei2.eigenvectors(), ei1.eigenvectors());\n  VERIFY_IS_EQUAL(ei2.eigenvalues(), ei1.eigenvalues());\n  if (rows > 2) {\n    ei2.setMaxIterations(1).compute(a);\n    VERIFY_IS_EQUAL(ei2.info(), NoConvergence);\n    VERIFY_IS_EQUAL(ei2.getMaxIterations(), 1);\n  }\n\n  EigenSolver<MatrixType> eiNoEivecs(a, false);\n  VERIFY_IS_EQUAL(eiNoEivecs.info(), Success);\n  VERIFY_IS_APPROX(ei1.eigenvalues(), eiNoEivecs.eigenvalues());\n  VERIFY_IS_APPROX(ei1.pseudoEigenvalueMatrix(), eiNoEivecs.pseudoEigenvalueMatrix());\n\n  MatrixType id = MatrixType::Identity(rows, cols);\n  VERIFY_IS_APPROX(id.operatorNorm(), RealScalar(1));\n\n  if (rows > 2 && rows < 20)\n  {\n    // Test matrix with NaN\n    a(0,0) = std::numeric_limits<typename MatrixType::RealScalar>::quiet_NaN();\n    EigenSolver<MatrixType> eiNaN(a);\n    VERIFY_IS_NOT_EQUAL(eiNaN.info(), Success);\n  }\n\n  // regression test for bug 1098\n  {\n    EigenSolver<MatrixType> eig(a.adjoint() * a);\n    eig.compute(a.adjoint() * a);\n  }\n\n  // regression test for bug 478\n  {\n    a.setZero();\n    EigenSolver<MatrixType> ei3(a);\n    VERIFY_IS_EQUAL(ei3.info(), Success);\n    VERIFY_IS_MUCH_SMALLER_THAN(ei3.eigenvalues().norm(),RealScalar(1));\n    VERIFY((ei3.eigenvectors().transpose()*ei3.eigenvectors().transpose()).eval().isIdentity());\n  }\n}\n\ntemplate<typename MatrixType> void eigensolver_verify_assert(const MatrixType& m)\n{\n  EigenSolver<MatrixType> eig;\n  VERIFY_RAISES_ASSERT(eig.eigenvectors());\n  VERIFY_RAISES_ASSERT(eig.pseudoEigenvectors());\n  VERIFY_RAISES_ASSERT(eig.pseudoEigenvalueMatrix());\n  VERIFY_RAISES_ASSERT(eig.eigenvalues());\n\n  MatrixType a = MatrixType::Random(m.rows(),m.cols());\n  eig.compute(a, false);\n  VERIFY_RAISES_ASSERT(eig.eigenvectors());\n  VERIFY_RAISES_ASSERT(eig.pseudoEigenvectors());\n}\n\n\ntemplate<typename CoeffType>\nMatrix<typename CoeffType::Scalar,Dynamic,Dynamic>\nmake_companion(const CoeffType& coeffs)\n{\n  Index n = coeffs.size()-1;\n  Matrix<typename CoeffType::Scalar,Dynamic,Dynamic> res(n,n);\n  res.setZero();\n\tres.row(0) = -coeffs.tail(n) / coeffs(0);\n\tres.diagonal(-1).setOnes();\n  return res;\n}\n\ntemplate<int>\nvoid eigensolver_generic_extra()\n{\n  {\n    // regression test for bug 793\n    MatrixXd a(3,3);\n    a << 0,  0,  1,\n        1,  1, 1,\n        1, 1e+200,  1;\n    Eigen::EigenSolver<MatrixXd> eig(a);\n    double scale = 1e-200; // scale to avoid overflow during the comparisons\n    VERIFY_IS_APPROX(a * eig.pseudoEigenvectors()*scale, eig.pseudoEigenvectors() * eig.pseudoEigenvalueMatrix()*scale);\n    VERIFY_IS_APPROX(a * eig.eigenvectors()*scale, eig.eigenvectors() * eig.eigenvalues().asDiagonal()*scale);\n  }\n  {\n    // check a case where all eigenvalues are null.\n    MatrixXd a(2,2);\n    a << 1,  1,\n        -1, -1;\n    Eigen::EigenSolver<MatrixXd> eig(a);\n    VERIFY_IS_APPROX(eig.pseudoEigenvectors().squaredNorm(), 2.);\n    VERIFY_IS_APPROX((a * eig.pseudoEigenvectors()).norm()+1., 1.);\n    VERIFY_IS_APPROX((eig.pseudoEigenvectors() * eig.pseudoEigenvalueMatrix()).norm()+1., 1.);\n    VERIFY_IS_APPROX((a * eig.eigenvectors()).norm()+1., 1.);\n    VERIFY_IS_APPROX((eig.eigenvectors() * eig.eigenvalues().asDiagonal()).norm()+1., 1.);\n  }\n\n  // regression test for bug 933\n  {\n    {\n      VectorXd coeffs(5); coeffs << 1, -3, -175, -225, 2250;\n      MatrixXd C = make_companion(coeffs);\n      EigenSolver<MatrixXd> eig(C);\n      CALL_SUBTEST( check_eigensolver_for_given_mat(eig,C) );\n    }\n    {\n      // this test is tricky because it requires high accuracy in smallest eigenvalues\n      VectorXd coeffs(5); coeffs << 6.154671e-15, -1.003870e-10, -9.819570e-01, 3.995715e+03, 2.211511e+08;\n      MatrixXd C = make_companion(coeffs);\n      EigenSolver<MatrixXd> eig(C);\n      CALL_SUBTEST( check_eigensolver_for_given_mat(eig,C) );\n      Index n = C.rows();\n      for(Index i=0;i<n;++i)\n      {\n        typedef std::complex<double> Complex;\n        MatrixXcd ac = C.cast<Complex>();\n        ac.diagonal().array() -= eig.eigenvalues()(i);\n        VectorXd sv = ac.jacobiSvd().singularValues();\n        // comparing to sv(0) is not enough here to catch the \"bug\",\n        // the hard-coded 1.0 is important!\n        VERIFY_IS_MUCH_SMALLER_THAN(sv(n-1), 1.0);\n      }\n    }\n  }\n  // regression test for bug 1557\n  {\n    // this test is interesting because it contains zeros on the diagonal.\n    MatrixXd A_bug1557(3,3);\n    A_bug1557 << 0, 0, 0, 1, 0, 0.5887907064808635127, 0, 1, 0;\n    EigenSolver<MatrixXd> eig(A_bug1557);\n    CALL_SUBTEST( check_eigensolver_for_given_mat(eig,A_bug1557) );\n  }\n\n  // regression test for bug 1174\n  {\n    Index n = 12;\n    MatrixXf A_bug1174(n,n);\n    A_bug1174 <<  262144, 0, 0, 262144, 786432, 0, 0, 0, 0, 0, 0, 786432,\n                  262144, 0, 0, 262144, 786432, 0, 0, 0, 0, 0, 0, 786432,\n                  262144, 0, 0, 262144, 786432, 0, 0, 0, 0, 0, 0, 786432,\n                  262144, 0, 0, 262144, 786432, 0, 0, 0, 0, 0, 0, 786432,\n                  0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,\n                  0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,\n                  0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,\n                  0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,\n                  0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,\n                  0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,\n                  0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0,\n                  0, 262144, 262144, 0, 0, 262144, 262144, 262144, 262144, 262144, 262144, 0;\n    EigenSolver<MatrixXf> eig(A_bug1174);\n    CALL_SUBTEST( check_eigensolver_for_given_mat(eig,A_bug1174) );\n  }\n}\n\nEIGEN_DECLARE_TEST(eigensolver_generic)\n{\n  int s = 0;\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( eigensolver(Matrix4f()) );\n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4);\n    CALL_SUBTEST_2( eigensolver(MatrixXd(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n\n    // some trivial but implementation-wise tricky cases\n    CALL_SUBTEST_2( eigensolver(MatrixXd(1,1)) );\n    CALL_SUBTEST_2( eigensolver(MatrixXd(2,2)) );\n    CALL_SUBTEST_3( eigensolver(Matrix<double,1,1>()) );\n    CALL_SUBTEST_4( eigensolver(Matrix2d()) );\n  }\n\n  CALL_SUBTEST_1( eigensolver_verify_assert(Matrix4f()) );\n  s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4);\n  CALL_SUBTEST_2( eigensolver_verify_assert(MatrixXd(s,s)) );\n  CALL_SUBTEST_3( eigensolver_verify_assert(Matrix<double,1,1>()) );\n  CALL_SUBTEST_4( eigensolver_verify_assert(Matrix2d()) );\n\n  // Test problem size constructors\n  CALL_SUBTEST_5(EigenSolver<MatrixXf> tmp(s));\n\n  // regression test for bug 410\n  CALL_SUBTEST_2(\n  {\n     MatrixXd A(1,1);\n     A(0,0) = std::sqrt(-1.); // is Not-a-Number\n     Eigen::EigenSolver<MatrixXd> solver(A);\n     VERIFY_IS_EQUAL(solver.info(), NumericalIssue);\n  }\n  );\n  \n  CALL_SUBTEST_2( eigensolver_generic_extra<0>() );\n  \n  TEST_SET_BUT_UNUSED_VARIABLE(s)\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/eigensolver_selfadjoint.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include \"svd_fill.h\"\n#include <limits>\n#include <Eigen/Eigenvalues>\n#include <Eigen/SparseCore>\n\n\ntemplate<typename MatrixType> void selfadjointeigensolver_essential_check(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  RealScalar eival_eps = numext::mini<RealScalar>(test_precision<RealScalar>(),  NumTraits<Scalar>::dummy_precision()*20000);\n  \n  SelfAdjointEigenSolver<MatrixType> eiSymm(m);\n  VERIFY_IS_EQUAL(eiSymm.info(), Success);\n\n  RealScalar scaling = m.cwiseAbs().maxCoeff();\n\n  if(scaling<(std::numeric_limits<RealScalar>::min)())\n  {\n    VERIFY(eiSymm.eigenvalues().cwiseAbs().maxCoeff() <= (std::numeric_limits<RealScalar>::min)());\n  }\n  else\n  {\n    VERIFY_IS_APPROX((m.template selfadjointView<Lower>() * eiSymm.eigenvectors())/scaling,\n                     (eiSymm.eigenvectors() * eiSymm.eigenvalues().asDiagonal())/scaling);\n  }\n  VERIFY_IS_APPROX(m.template selfadjointView<Lower>().eigenvalues(), eiSymm.eigenvalues());\n  VERIFY_IS_UNITARY(eiSymm.eigenvectors());\n\n  if(m.cols()<=4)\n  {\n    SelfAdjointEigenSolver<MatrixType> eiDirect;\n    eiDirect.computeDirect(m);  \n    VERIFY_IS_EQUAL(eiDirect.info(), Success);\n    if(! eiSymm.eigenvalues().isApprox(eiDirect.eigenvalues(), eival_eps) )\n    {\n      std::cerr << \"reference eigenvalues: \" << eiSymm.eigenvalues().transpose() << \"\\n\"\n                << \"obtained eigenvalues:  \" << eiDirect.eigenvalues().transpose() << \"\\n\"\n                << \"diff:                  \" << (eiSymm.eigenvalues()-eiDirect.eigenvalues()).transpose() << \"\\n\"\n                << \"error (eps):           \" << (eiSymm.eigenvalues()-eiDirect.eigenvalues()).norm() / eiSymm.eigenvalues().norm() << \"  (\" << eival_eps << \")\\n\";\n    }\n    if(scaling<(std::numeric_limits<RealScalar>::min)())\n    {\n      VERIFY(eiDirect.eigenvalues().cwiseAbs().maxCoeff() <= (std::numeric_limits<RealScalar>::min)());\n    }\n    else\n    {\n      VERIFY_IS_APPROX(eiSymm.eigenvalues()/scaling, eiDirect.eigenvalues()/scaling);\n      VERIFY_IS_APPROX((m.template selfadjointView<Lower>() * eiDirect.eigenvectors())/scaling,\n                       (eiDirect.eigenvectors() * eiDirect.eigenvalues().asDiagonal())/scaling);\n      VERIFY_IS_APPROX(m.template selfadjointView<Lower>().eigenvalues()/scaling, eiDirect.eigenvalues()/scaling);\n    }\n\n    VERIFY_IS_UNITARY(eiDirect.eigenvectors());\n  }\n}\n\ntemplate<typename MatrixType> void selfadjointeigensolver(const MatrixType& m)\n{\n  /* this test covers the following files:\n     EigenSolver.h, SelfAdjointEigenSolver.h (and indirectly: Tridiagonalization.h)\n  */\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  RealScalar largerEps = 10*test_precision<RealScalar>();\n\n  MatrixType a = MatrixType::Random(rows,cols);\n  MatrixType a1 = MatrixType::Random(rows,cols);\n  MatrixType symmA =  a.adjoint() * a + a1.adjoint() * a1;\n  MatrixType symmC = symmA;\n  \n  svd_fill_random(symmA,Symmetric);\n\n  symmA.template triangularView<StrictlyUpper>().setZero();\n  symmC.template triangularView<StrictlyUpper>().setZero();\n\n  MatrixType b = MatrixType::Random(rows,cols);\n  MatrixType b1 = MatrixType::Random(rows,cols);\n  MatrixType symmB = b.adjoint() * b + b1.adjoint() * b1;\n  symmB.template triangularView<StrictlyUpper>().setZero();\n  \n  CALL_SUBTEST( selfadjointeigensolver_essential_check(symmA) );\n\n  SelfAdjointEigenSolver<MatrixType> eiSymm(symmA);\n  // generalized eigen pb\n  GeneralizedSelfAdjointEigenSolver<MatrixType> eiSymmGen(symmC, symmB);\n\n  SelfAdjointEigenSolver<MatrixType> eiSymmNoEivecs(symmA, false);\n  VERIFY_IS_EQUAL(eiSymmNoEivecs.info(), Success);\n  VERIFY_IS_APPROX(eiSymm.eigenvalues(), eiSymmNoEivecs.eigenvalues());\n  \n  // generalized eigen problem Ax = lBx\n  eiSymmGen.compute(symmC, symmB,Ax_lBx);\n  VERIFY_IS_EQUAL(eiSymmGen.info(), Success);\n  VERIFY((symmC.template selfadjointView<Lower>() * eiSymmGen.eigenvectors()).isApprox(\n          symmB.template selfadjointView<Lower>() * (eiSymmGen.eigenvectors() * eiSymmGen.eigenvalues().asDiagonal()), largerEps));\n\n  // generalized eigen problem BAx = lx\n  eiSymmGen.compute(symmC, symmB,BAx_lx);\n  VERIFY_IS_EQUAL(eiSymmGen.info(), Success);\n  VERIFY((symmB.template selfadjointView<Lower>() * (symmC.template selfadjointView<Lower>() * eiSymmGen.eigenvectors())).isApprox(\n         (eiSymmGen.eigenvectors() * eiSymmGen.eigenvalues().asDiagonal()), largerEps));\n\n  // generalized eigen problem ABx = lx\n  eiSymmGen.compute(symmC, symmB,ABx_lx);\n  VERIFY_IS_EQUAL(eiSymmGen.info(), Success);\n  VERIFY((symmC.template selfadjointView<Lower>() * (symmB.template selfadjointView<Lower>() * eiSymmGen.eigenvectors())).isApprox(\n         (eiSymmGen.eigenvectors() * eiSymmGen.eigenvalues().asDiagonal()), largerEps));\n\n\n  eiSymm.compute(symmC);\n  MatrixType sqrtSymmA = eiSymm.operatorSqrt();\n  VERIFY_IS_APPROX(MatrixType(symmC.template selfadjointView<Lower>()), sqrtSymmA*sqrtSymmA);\n  VERIFY_IS_APPROX(sqrtSymmA, symmC.template selfadjointView<Lower>()*eiSymm.operatorInverseSqrt());\n\n  MatrixType id = MatrixType::Identity(rows, cols);\n  VERIFY_IS_APPROX(id.template selfadjointView<Lower>().operatorNorm(), RealScalar(1));\n\n  SelfAdjointEigenSolver<MatrixType> eiSymmUninitialized;\n  VERIFY_RAISES_ASSERT(eiSymmUninitialized.info());\n  VERIFY_RAISES_ASSERT(eiSymmUninitialized.eigenvalues());\n  VERIFY_RAISES_ASSERT(eiSymmUninitialized.eigenvectors());\n  VERIFY_RAISES_ASSERT(eiSymmUninitialized.operatorSqrt());\n  VERIFY_RAISES_ASSERT(eiSymmUninitialized.operatorInverseSqrt());\n\n  eiSymmUninitialized.compute(symmA, false);\n  VERIFY_RAISES_ASSERT(eiSymmUninitialized.eigenvectors());\n  VERIFY_RAISES_ASSERT(eiSymmUninitialized.operatorSqrt());\n  VERIFY_RAISES_ASSERT(eiSymmUninitialized.operatorInverseSqrt());\n\n  // test Tridiagonalization's methods\n  Tridiagonalization<MatrixType> tridiag(symmC);\n  VERIFY_IS_APPROX(tridiag.diagonal(), tridiag.matrixT().diagonal());\n  VERIFY_IS_APPROX(tridiag.subDiagonal(), tridiag.matrixT().template diagonal<-1>());\n  Matrix<RealScalar,Dynamic,Dynamic> T = tridiag.matrixT();\n  if(rows>1 && cols>1) {\n    // FIXME check that upper and lower part are 0:\n    //VERIFY(T.topRightCorner(rows-2, cols-2).template triangularView<Upper>().isZero());\n  }\n  VERIFY_IS_APPROX(tridiag.diagonal(), T.diagonal());\n  VERIFY_IS_APPROX(tridiag.subDiagonal(), T.template diagonal<1>());\n  VERIFY_IS_APPROX(MatrixType(symmC.template selfadjointView<Lower>()), tridiag.matrixQ() * tridiag.matrixT().eval() * MatrixType(tridiag.matrixQ()).adjoint());\n  VERIFY_IS_APPROX(MatrixType(symmC.template selfadjointView<Lower>()), tridiag.matrixQ() * tridiag.matrixT() * tridiag.matrixQ().adjoint());\n  \n  // Test computation of eigenvalues from tridiagonal matrix\n  if(rows > 1)\n  {\n    SelfAdjointEigenSolver<MatrixType> eiSymmTridiag;\n    eiSymmTridiag.computeFromTridiagonal(tridiag.matrixT().diagonal(), tridiag.matrixT().diagonal(-1), ComputeEigenvectors);\n    VERIFY_IS_APPROX(eiSymm.eigenvalues(), eiSymmTridiag.eigenvalues());\n    VERIFY_IS_APPROX(tridiag.matrixT(), eiSymmTridiag.eigenvectors().real() * eiSymmTridiag.eigenvalues().asDiagonal() * eiSymmTridiag.eigenvectors().real().transpose());\n  }\n\n  if (rows > 1 && rows < 20)\n  {\n    // Test matrix with NaN\n    symmC(0,0) = std::numeric_limits<typename MatrixType::RealScalar>::quiet_NaN();\n    SelfAdjointEigenSolver<MatrixType> eiSymmNaN(symmC);\n    VERIFY_IS_EQUAL(eiSymmNaN.info(), NoConvergence);\n  }\n\n  // regression test for bug 1098\n  {\n    SelfAdjointEigenSolver<MatrixType> eig(a.adjoint() * a);\n    eig.compute(a.adjoint() * a);\n  }\n\n  // regression test for bug 478\n  {\n    a.setZero();\n    SelfAdjointEigenSolver<MatrixType> ei3(a);\n    VERIFY_IS_EQUAL(ei3.info(), Success);\n    VERIFY_IS_MUCH_SMALLER_THAN(ei3.eigenvalues().norm(),RealScalar(1));\n    VERIFY((ei3.eigenvectors().transpose()*ei3.eigenvectors().transpose()).eval().isIdentity());\n  }\n}\n\ntemplate<int>\nvoid bug_854()\n{\n  Matrix3d m;\n  m << 850.961, 51.966, 0,\n       51.966, 254.841, 0,\n            0,       0, 0;\n  selfadjointeigensolver_essential_check(m);\n}\n\ntemplate<int>\nvoid bug_1014()\n{\n  Matrix3d m;\n  m <<        0.11111111111111114658, 0, 0,\n       0,     0.11111111111111109107, 0,\n       0, 0,  0.11111111111111107719;\n  selfadjointeigensolver_essential_check(m);\n}\n\ntemplate<int>\nvoid bug_1225()\n{\n  Matrix3d m1, m2;\n  m1.setRandom();\n  m1 = m1*m1.transpose();\n  m2 = m1.triangularView<Upper>();\n  SelfAdjointEigenSolver<Matrix3d> eig1(m1);\n  SelfAdjointEigenSolver<Matrix3d> eig2(m2.selfadjointView<Upper>());\n  VERIFY_IS_APPROX(eig1.eigenvalues(), eig2.eigenvalues());\n}\n\ntemplate<int>\nvoid bug_1204()\n{\n  SparseMatrix<double> A(2,2);\n  A.setIdentity();\n  SelfAdjointEigenSolver<Eigen::SparseMatrix<double> > eig(A);\n}\n\nEIGEN_DECLARE_TEST(eigensolver_selfadjoint)\n{\n  int s = 0;\n  for(int i = 0; i < g_repeat; i++) {\n    // trivial test for 1x1 matrices:\n    CALL_SUBTEST_1( selfadjointeigensolver(Matrix<float, 1, 1>()));\n    CALL_SUBTEST_1( selfadjointeigensolver(Matrix<double, 1, 1>()));\n    // very important to test 3x3 and 2x2 matrices since we provide special paths for them\n    CALL_SUBTEST_12( selfadjointeigensolver(Matrix2f()) );\n    CALL_SUBTEST_12( selfadjointeigensolver(Matrix2d()) );\n    CALL_SUBTEST_13( selfadjointeigensolver(Matrix3f()) );\n    CALL_SUBTEST_13( selfadjointeigensolver(Matrix3d()) );\n    CALL_SUBTEST_2( selfadjointeigensolver(Matrix4d()) );\n    \n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4);\n    CALL_SUBTEST_3( selfadjointeigensolver(MatrixXf(s,s)) );\n    CALL_SUBTEST_4( selfadjointeigensolver(MatrixXd(s,s)) );\n    CALL_SUBTEST_5( selfadjointeigensolver(MatrixXcd(s,s)) );\n    CALL_SUBTEST_9( selfadjointeigensolver(Matrix<std::complex<double>,Dynamic,Dynamic,RowMajor>(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n\n    // some trivial but implementation-wise tricky cases\n    CALL_SUBTEST_4( selfadjointeigensolver(MatrixXd(1,1)) );\n    CALL_SUBTEST_4( selfadjointeigensolver(MatrixXd(2,2)) );\n    CALL_SUBTEST_6( selfadjointeigensolver(Matrix<double,1,1>()) );\n    CALL_SUBTEST_7( selfadjointeigensolver(Matrix<double,2,2>()) );\n  }\n  \n  CALL_SUBTEST_13( bug_854<0>() );\n  CALL_SUBTEST_13( bug_1014<0>() );\n  CALL_SUBTEST_13( bug_1204<0>() );\n  CALL_SUBTEST_13( bug_1225<0>() );\n\n  // Test problem size constructors\n  s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4);\n  CALL_SUBTEST_8(SelfAdjointEigenSolver<MatrixXf> tmp1(s));\n  CALL_SUBTEST_8(Tridiagonalization<MatrixXf> tmp2(s));\n  \n  TEST_SET_BUT_UNUSED_VARIABLE(s)\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/evaluator_common.h",
    "content": ""
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/evaluators.cpp",
    "content": "\n#include \"main.h\"\n\nnamespace Eigen {\n\n  template<typename Lhs,typename Rhs>\n  const Product<Lhs,Rhs>\n  prod(const Lhs& lhs, const Rhs& rhs)\n  {\n    return Product<Lhs,Rhs>(lhs,rhs);\n  }\n\n  template<typename Lhs,typename Rhs>\n  const Product<Lhs,Rhs,LazyProduct>\n  lazyprod(const Lhs& lhs, const Rhs& rhs)\n  {\n    return Product<Lhs,Rhs,LazyProduct>(lhs,rhs);\n  }\n  \n  template<typename DstXprType, typename SrcXprType>\n  EIGEN_STRONG_INLINE\n  DstXprType& copy_using_evaluator(const EigenBase<DstXprType> &dst, const SrcXprType &src)\n  {\n    call_assignment(dst.const_cast_derived(), src.derived(), internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar>());\n    return dst.const_cast_derived();\n  }\n  \n  template<typename DstXprType, template <typename> class StorageBase, typename SrcXprType>\n  EIGEN_STRONG_INLINE\n  const DstXprType& copy_using_evaluator(const NoAlias<DstXprType, StorageBase>& dst, const SrcXprType &src)\n  {\n    call_assignment(dst, src.derived(), internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar>());\n    return dst.expression();\n  }\n  \n  template<typename DstXprType, typename SrcXprType>\n  EIGEN_STRONG_INLINE\n  DstXprType& copy_using_evaluator(const PlainObjectBase<DstXprType> &dst, const SrcXprType &src)\n  {\n    #ifdef EIGEN_NO_AUTOMATIC_RESIZING\n    eigen_assert((dst.size()==0 || (IsVectorAtCompileTime ? (dst.size() == src.size())\n                                                          : (dst.rows() == src.rows() && dst.cols() == src.cols())))\n                && \"Size mismatch. Automatic resizing is disabled because EIGEN_NO_AUTOMATIC_RESIZING is defined\");\n  #else\n    dst.const_cast_derived().resizeLike(src.derived());\n  #endif\n    \n    call_assignment(dst.const_cast_derived(), src.derived(), internal::assign_op<typename DstXprType::Scalar,typename SrcXprType::Scalar>());\n    return dst.const_cast_derived();\n  }\n\n  template<typename DstXprType, typename SrcXprType>\n  void add_assign_using_evaluator(const DstXprType& dst, const SrcXprType& src)\n  {\n    typedef typename DstXprType::Scalar Scalar;\n    call_assignment(const_cast<DstXprType&>(dst), src.derived(), internal::add_assign_op<Scalar,typename SrcXprType::Scalar>());\n  }\n\n  template<typename DstXprType, typename SrcXprType>\n  void subtract_assign_using_evaluator(const DstXprType& dst, const SrcXprType& src)\n  {\n    typedef typename DstXprType::Scalar Scalar;\n    call_assignment(const_cast<DstXprType&>(dst), src.derived(), internal::sub_assign_op<Scalar,typename SrcXprType::Scalar>());\n  }\n\n  template<typename DstXprType, typename SrcXprType>\n  void multiply_assign_using_evaluator(const DstXprType& dst, const SrcXprType& src)\n  {\n    typedef typename DstXprType::Scalar Scalar;\n    call_assignment(dst.const_cast_derived(), src.derived(), internal::mul_assign_op<Scalar,typename SrcXprType::Scalar>());\n  }\n\n  template<typename DstXprType, typename SrcXprType>\n  void divide_assign_using_evaluator(const DstXprType& dst, const SrcXprType& src)\n  {\n    typedef typename DstXprType::Scalar Scalar;\n    call_assignment(dst.const_cast_derived(), src.derived(), internal::div_assign_op<Scalar,typename SrcXprType::Scalar>());\n  }\n  \n  template<typename DstXprType, typename SrcXprType>\n  void swap_using_evaluator(const DstXprType& dst, const SrcXprType& src)\n  {\n    typedef typename DstXprType::Scalar Scalar;\n    call_assignment(dst.const_cast_derived(), src.const_cast_derived(), internal::swap_assign_op<Scalar>());\n  }\n\n  namespace internal {\n    template<typename Dst, template <typename> class StorageBase, typename Src, typename Func>\n    EIGEN_DEVICE_FUNC void call_assignment(const NoAlias<Dst,StorageBase>& dst, const Src& src, const Func& func)\n    {\n      call_assignment_no_alias(dst.expression(), src, func);\n    }\n\n    template<typename Dst, template <typename> class StorageBase, typename Src, typename Func>\n    EIGEN_DEVICE_FUNC void call_restricted_packet_assignment(const NoAlias<Dst,StorageBase>& dst, const Src& src, const Func& func)\n    {\n      call_restricted_packet_assignment_no_alias(dst.expression(), src, func);\n    }\n  }\n  \n}\n\ntemplate<typename XprType> long get_cost(const XprType& ) { return Eigen::internal::evaluator<XprType>::CoeffReadCost; }\n\nusing namespace std;\n\n#define VERIFY_IS_APPROX_EVALUATOR(DEST,EXPR) VERIFY_IS_APPROX(copy_using_evaluator(DEST,(EXPR)), (EXPR).eval());\n#define VERIFY_IS_APPROX_EVALUATOR2(DEST,EXPR,REF) VERIFY_IS_APPROX(copy_using_evaluator(DEST,(EXPR)), (REF).eval());\n\nEIGEN_DECLARE_TEST(evaluators)\n{\n  // Testing Matrix evaluator and Transpose\n  Vector2d v = Vector2d::Random();\n  const Vector2d v_const(v);\n  Vector2d v2;\n  RowVector2d w;\n\n  VERIFY_IS_APPROX_EVALUATOR(v2, v);\n  VERIFY_IS_APPROX_EVALUATOR(v2, v_const);\n\n  // Testing Transpose\n  VERIFY_IS_APPROX_EVALUATOR(w, v.transpose()); // Transpose as rvalue\n  VERIFY_IS_APPROX_EVALUATOR(w, v_const.transpose());\n\n  copy_using_evaluator(w.transpose(), v); // Transpose as lvalue\n  VERIFY_IS_APPROX(w,v.transpose().eval());\n\n  copy_using_evaluator(w.transpose(), v_const);\n  VERIFY_IS_APPROX(w,v_const.transpose().eval());\n\n  // Testing Array evaluator\n  {\n    ArrayXXf a(2,3);\n    ArrayXXf b(3,2);\n    a << 1,2,3, 4,5,6;\n    const ArrayXXf a_const(a);\n\n    VERIFY_IS_APPROX_EVALUATOR(b, a.transpose());\n\n    VERIFY_IS_APPROX_EVALUATOR(b, a_const.transpose());\n\n    // Testing CwiseNullaryOp evaluator\n    copy_using_evaluator(w, RowVector2d::Random());\n    VERIFY((w.array() >= -1).all() && (w.array() <= 1).all()); // not easy to test ...\n\n    VERIFY_IS_APPROX_EVALUATOR(w, RowVector2d::Zero());\n\n    VERIFY_IS_APPROX_EVALUATOR(w, RowVector2d::Constant(3));\n    \n    // mix CwiseNullaryOp and transpose\n    VERIFY_IS_APPROX_EVALUATOR(w, Vector2d::Zero().transpose());\n  }\n\n  {\n    // test product expressions\n    int s = internal::random<int>(1,100);\n    MatrixXf a(s,s), b(s,s), c(s,s), d(s,s);\n    a.setRandom();\n    b.setRandom();\n    c.setRandom();\n    d.setRandom();\n    VERIFY_IS_APPROX_EVALUATOR(d, (a + b));\n    VERIFY_IS_APPROX_EVALUATOR(d, (a + b).transpose());\n    VERIFY_IS_APPROX_EVALUATOR2(d, prod(a,b), a*b);\n    VERIFY_IS_APPROX_EVALUATOR2(d.noalias(), prod(a,b), a*b);\n    VERIFY_IS_APPROX_EVALUATOR2(d, prod(a,b) + c, a*b + c);\n    VERIFY_IS_APPROX_EVALUATOR2(d, s * prod(a,b), s * a*b);\n    VERIFY_IS_APPROX_EVALUATOR2(d, prod(a,b).transpose(), (a*b).transpose());\n    VERIFY_IS_APPROX_EVALUATOR2(d, prod(a,b) + prod(b,c), a*b + b*c);\n\n    // check that prod works even with aliasing present\n    c = a*a;\n    copy_using_evaluator(a, prod(a,a));\n    VERIFY_IS_APPROX(a,c);\n\n    // check compound assignment of products\n    d = c;\n    add_assign_using_evaluator(c.noalias(), prod(a,b));\n    d.noalias() += a*b;\n    VERIFY_IS_APPROX(c, d);\n\n    d = c;\n    subtract_assign_using_evaluator(c.noalias(), prod(a,b));\n    d.noalias() -= a*b;\n    VERIFY_IS_APPROX(c, d);\n  }\n\n  {\n    // test product with all possible sizes\n    int s = internal::random<int>(1,100);\n    Matrix<float,      1,      1> m11, res11;  m11.setRandom(1,1);\n    Matrix<float,      1,      4> m14, res14;  m14.setRandom(1,4);\n    Matrix<float,      1,Dynamic> m1X, res1X;  m1X.setRandom(1,s);\n    Matrix<float,      4,      1> m41, res41;  m41.setRandom(4,1);\n    Matrix<float,      4,      4> m44, res44;  m44.setRandom(4,4);\n    Matrix<float,      4,Dynamic> m4X, res4X;  m4X.setRandom(4,s);\n    Matrix<float,Dynamic,      1> mX1, resX1;  mX1.setRandom(s,1);\n    Matrix<float,Dynamic,      4> mX4, resX4;  mX4.setRandom(s,4);\n    Matrix<float,Dynamic,Dynamic> mXX, resXX;  mXX.setRandom(s,s);\n\n    VERIFY_IS_APPROX_EVALUATOR2(res11, prod(m11,m11), m11*m11);\n    VERIFY_IS_APPROX_EVALUATOR2(res11, prod(m14,m41), m14*m41);\n    VERIFY_IS_APPROX_EVALUATOR2(res11, prod(m1X,mX1), m1X*mX1);\n    VERIFY_IS_APPROX_EVALUATOR2(res14, prod(m11,m14), m11*m14);\n    VERIFY_IS_APPROX_EVALUATOR2(res14, prod(m14,m44), m14*m44);\n    VERIFY_IS_APPROX_EVALUATOR2(res14, prod(m1X,mX4), m1X*mX4);\n    VERIFY_IS_APPROX_EVALUATOR2(res1X, prod(m11,m1X), m11*m1X);\n    VERIFY_IS_APPROX_EVALUATOR2(res1X, prod(m14,m4X), m14*m4X);\n    VERIFY_IS_APPROX_EVALUATOR2(res1X, prod(m1X,mXX), m1X*mXX);\n    VERIFY_IS_APPROX_EVALUATOR2(res41, prod(m41,m11), m41*m11);\n    VERIFY_IS_APPROX_EVALUATOR2(res41, prod(m44,m41), m44*m41);\n    VERIFY_IS_APPROX_EVALUATOR2(res41, prod(m4X,mX1), m4X*mX1);\n    VERIFY_IS_APPROX_EVALUATOR2(res44, prod(m41,m14), m41*m14);\n    VERIFY_IS_APPROX_EVALUATOR2(res44, prod(m44,m44), m44*m44);\n    VERIFY_IS_APPROX_EVALUATOR2(res44, prod(m4X,mX4), m4X*mX4);\n    VERIFY_IS_APPROX_EVALUATOR2(res4X, prod(m41,m1X), m41*m1X);\n    VERIFY_IS_APPROX_EVALUATOR2(res4X, prod(m44,m4X), m44*m4X);\n    VERIFY_IS_APPROX_EVALUATOR2(res4X, prod(m4X,mXX), m4X*mXX);\n    VERIFY_IS_APPROX_EVALUATOR2(resX1, prod(mX1,m11), mX1*m11);\n    VERIFY_IS_APPROX_EVALUATOR2(resX1, prod(mX4,m41), mX4*m41);\n    VERIFY_IS_APPROX_EVALUATOR2(resX1, prod(mXX,mX1), mXX*mX1);\n    VERIFY_IS_APPROX_EVALUATOR2(resX4, prod(mX1,m14), mX1*m14);\n    VERIFY_IS_APPROX_EVALUATOR2(resX4, prod(mX4,m44), mX4*m44);\n    VERIFY_IS_APPROX_EVALUATOR2(resX4, prod(mXX,mX4), mXX*mX4);\n    VERIFY_IS_APPROX_EVALUATOR2(resXX, prod(mX1,m1X), mX1*m1X);\n    VERIFY_IS_APPROX_EVALUATOR2(resXX, prod(mX4,m4X), mX4*m4X);\n    VERIFY_IS_APPROX_EVALUATOR2(resXX, prod(mXX,mXX), mXX*mXX);\n  }\n\n  {\n    ArrayXXf a(2,3);\n    ArrayXXf b(3,2);\n    a << 1,2,3, 4,5,6;\n    const ArrayXXf a_const(a);\n    \n    // this does not work because Random is eval-before-nested: \n    // copy_using_evaluator(w, Vector2d::Random().transpose());\n\n    // test CwiseUnaryOp\n    VERIFY_IS_APPROX_EVALUATOR(v2, 3 * v);\n    VERIFY_IS_APPROX_EVALUATOR(w, (3 * v).transpose());\n    VERIFY_IS_APPROX_EVALUATOR(b, (a + 3).transpose());\n    VERIFY_IS_APPROX_EVALUATOR(b, (2 * a_const + 3).transpose());\n\n    // test CwiseBinaryOp\n    VERIFY_IS_APPROX_EVALUATOR(v2, v + Vector2d::Ones());\n    VERIFY_IS_APPROX_EVALUATOR(w, (v + Vector2d::Ones()).transpose().cwiseProduct(RowVector2d::Constant(3)));\n\n    // dynamic matrices and arrays\n    MatrixXd mat1(6,6), mat2(6,6);\n    VERIFY_IS_APPROX_EVALUATOR(mat1, MatrixXd::Identity(6,6));\n    VERIFY_IS_APPROX_EVALUATOR(mat2, mat1);\n    copy_using_evaluator(mat2.transpose(), mat1);\n    VERIFY_IS_APPROX(mat2.transpose(), mat1);\n\n    ArrayXXd arr1(6,6), arr2(6,6);\n    VERIFY_IS_APPROX_EVALUATOR(arr1, ArrayXXd::Constant(6,6, 3.0));\n    VERIFY_IS_APPROX_EVALUATOR(arr2, arr1);\n    \n    // test automatic resizing\n    mat2.resize(3,3);\n    VERIFY_IS_APPROX_EVALUATOR(mat2, mat1);\n    arr2.resize(9,9);\n    VERIFY_IS_APPROX_EVALUATOR(arr2, arr1);\n\n    // test direct traversal\n    Matrix3f m3;\n    Array33f a3;\n    VERIFY_IS_APPROX_EVALUATOR(m3, Matrix3f::Identity());  // matrix, nullary\n    // TODO: find a way to test direct traversal with array\n    VERIFY_IS_APPROX_EVALUATOR(m3.transpose(), Matrix3f::Identity().transpose());  // transpose\n    VERIFY_IS_APPROX_EVALUATOR(m3, 2 * Matrix3f::Identity());  // unary\n    VERIFY_IS_APPROX_EVALUATOR(m3, Matrix3f::Identity() + Matrix3f::Zero());  // binary\n    VERIFY_IS_APPROX_EVALUATOR(m3.block(0,0,2,2), Matrix3f::Identity().block(1,1,2,2));  // block\n\n    // test linear traversal\n    VERIFY_IS_APPROX_EVALUATOR(m3, Matrix3f::Zero());  // matrix, nullary\n    VERIFY_IS_APPROX_EVALUATOR(a3, Array33f::Zero());  // array\n    VERIFY_IS_APPROX_EVALUATOR(m3.transpose(), Matrix3f::Zero().transpose());  // transpose\n    VERIFY_IS_APPROX_EVALUATOR(m3, 2 * Matrix3f::Zero());  // unary\n    VERIFY_IS_APPROX_EVALUATOR(m3, Matrix3f::Zero() + m3);  // binary  \n\n    // test inner vectorization\n    Matrix4f m4, m4src = Matrix4f::Random();\n    Array44f a4, a4src = Matrix4f::Random();\n    VERIFY_IS_APPROX_EVALUATOR(m4, m4src);  // matrix\n    VERIFY_IS_APPROX_EVALUATOR(a4, a4src);  // array\n    VERIFY_IS_APPROX_EVALUATOR(m4.transpose(), m4src.transpose());  // transpose\n    // TODO: find out why Matrix4f::Zero() does not allow inner vectorization\n    VERIFY_IS_APPROX_EVALUATOR(m4, 2 * m4src);  // unary\n    VERIFY_IS_APPROX_EVALUATOR(m4, m4src + m4src);  // binary\n\n    // test linear vectorization\n    MatrixXf mX(6,6), mXsrc = MatrixXf::Random(6,6);\n    ArrayXXf aX(6,6), aXsrc = ArrayXXf::Random(6,6);\n    VERIFY_IS_APPROX_EVALUATOR(mX, mXsrc);  // matrix\n    VERIFY_IS_APPROX_EVALUATOR(aX, aXsrc);  // array\n    VERIFY_IS_APPROX_EVALUATOR(mX.transpose(), mXsrc.transpose());  // transpose\n    VERIFY_IS_APPROX_EVALUATOR(mX, MatrixXf::Zero(6,6));  // nullary\n    VERIFY_IS_APPROX_EVALUATOR(mX, 2 * mXsrc);  // unary\n    VERIFY_IS_APPROX_EVALUATOR(mX, mXsrc + mXsrc);  // binary\n\n    // test blocks and slice vectorization\n    VERIFY_IS_APPROX_EVALUATOR(m4, (mXsrc.block<4,4>(1,0)));\n    VERIFY_IS_APPROX_EVALUATOR(aX, ArrayXXf::Constant(10, 10, 3.0).block(2, 3, 6, 6));\n\n    Matrix4f m4ref = m4;\n    copy_using_evaluator(m4.block(1, 1, 2, 3), m3.bottomRows(2));\n    m4ref.block(1, 1, 2, 3) = m3.bottomRows(2);\n    VERIFY_IS_APPROX(m4, m4ref);\n\n    mX.setIdentity(20,20);\n    MatrixXf mXref = MatrixXf::Identity(20,20);\n    mXsrc = MatrixXf::Random(9,12);\n    copy_using_evaluator(mX.block(4, 4, 9, 12), mXsrc);\n    mXref.block(4, 4, 9, 12) = mXsrc;\n    VERIFY_IS_APPROX(mX, mXref);\n\n    // test Map\n    const float raw[3] = {1,2,3};\n    float buffer[3] = {0,0,0};\n    Vector3f v3;\n    Array3f a3f;\n    VERIFY_IS_APPROX_EVALUATOR(v3, Map<const Vector3f>(raw));\n    VERIFY_IS_APPROX_EVALUATOR(a3f, Map<const Array3f>(raw));\n    Vector3f::Map(buffer) = 2*v3;\n    VERIFY(buffer[0] == 2);\n    VERIFY(buffer[1] == 4);\n    VERIFY(buffer[2] == 6);\n\n    // test CwiseUnaryView\n    mat1.setRandom();\n    mat2.setIdentity();\n    MatrixXcd matXcd(6,6), matXcd_ref(6,6);\n    copy_using_evaluator(matXcd.real(), mat1);\n    copy_using_evaluator(matXcd.imag(), mat2);\n    matXcd_ref.real() = mat1;\n    matXcd_ref.imag() = mat2;\n    VERIFY_IS_APPROX(matXcd, matXcd_ref);\n\n    // test Select\n    VERIFY_IS_APPROX_EVALUATOR(aX, (aXsrc > 0).select(aXsrc, -aXsrc));\n\n    // test Replicate\n    mXsrc = MatrixXf::Random(6, 6);\n    VectorXf vX = VectorXf::Random(6);\n    mX.resize(6, 6);\n    VERIFY_IS_APPROX_EVALUATOR(mX, mXsrc.colwise() + vX);\n    matXcd.resize(12, 12);\n    VERIFY_IS_APPROX_EVALUATOR(matXcd, matXcd_ref.replicate(2,2));\n    VERIFY_IS_APPROX_EVALUATOR(matXcd, (matXcd_ref.replicate<2,2>()));\n\n    // test partial reductions\n    VectorXd vec1(6);\n    VERIFY_IS_APPROX_EVALUATOR(vec1, mat1.rowwise().sum());\n    VERIFY_IS_APPROX_EVALUATOR(vec1, mat1.colwise().sum().transpose());\n\n    // test MatrixWrapper and ArrayWrapper\n    mat1.setRandom(6,6);\n    arr1.setRandom(6,6);\n    VERIFY_IS_APPROX_EVALUATOR(mat2, arr1.matrix());\n    VERIFY_IS_APPROX_EVALUATOR(arr2, mat1.array());\n    VERIFY_IS_APPROX_EVALUATOR(mat2, (arr1 + 2).matrix());\n    VERIFY_IS_APPROX_EVALUATOR(arr2, mat1.array() + 2);\n    mat2.array() = arr1 * arr1;\n    VERIFY_IS_APPROX(mat2, (arr1 * arr1).matrix());\n    arr2.matrix() = MatrixXd::Identity(6,6);\n    VERIFY_IS_APPROX(arr2, MatrixXd::Identity(6,6).array());\n\n    // test Reverse\n    VERIFY_IS_APPROX_EVALUATOR(arr2, arr1.reverse());\n    VERIFY_IS_APPROX_EVALUATOR(arr2, arr1.colwise().reverse());\n    VERIFY_IS_APPROX_EVALUATOR(arr2, arr1.rowwise().reverse());\n    arr2.reverse() = arr1;\n    VERIFY_IS_APPROX(arr2, arr1.reverse());\n    mat2.array() = mat1.array().reverse();\n    VERIFY_IS_APPROX(mat2.array(), mat1.array().reverse());\n\n    // test Diagonal\n    VERIFY_IS_APPROX_EVALUATOR(vec1, mat1.diagonal());\n    vec1.resize(5);\n    VERIFY_IS_APPROX_EVALUATOR(vec1, mat1.diagonal(1));\n    VERIFY_IS_APPROX_EVALUATOR(vec1, mat1.diagonal<-1>());\n    vec1.setRandom();\n\n    mat2 = mat1;\n    copy_using_evaluator(mat1.diagonal(1), vec1);\n    mat2.diagonal(1) = vec1;\n    VERIFY_IS_APPROX(mat1, mat2);\n\n    copy_using_evaluator(mat1.diagonal<-1>(), mat1.diagonal(1));\n    mat2.diagonal<-1>() = mat2.diagonal(1);\n    VERIFY_IS_APPROX(mat1, mat2);\n  }\n  \n  {\n    // test swapping\n    MatrixXd mat1, mat2, mat1ref, mat2ref;\n    mat1ref = mat1 = MatrixXd::Random(6, 6);\n    mat2ref = mat2 = 2 * mat1 + MatrixXd::Identity(6, 6);\n    swap_using_evaluator(mat1, mat2);\n    mat1ref.swap(mat2ref);\n    VERIFY_IS_APPROX(mat1, mat1ref);\n    VERIFY_IS_APPROX(mat2, mat2ref);\n\n    swap_using_evaluator(mat1.block(0, 0, 3, 3), mat2.block(3, 3, 3, 3));\n    mat1ref.block(0, 0, 3, 3).swap(mat2ref.block(3, 3, 3, 3));\n    VERIFY_IS_APPROX(mat1, mat1ref);\n    VERIFY_IS_APPROX(mat2, mat2ref);\n\n    swap_using_evaluator(mat1.row(2), mat2.col(3).transpose());\n    mat1.row(2).swap(mat2.col(3).transpose());\n    VERIFY_IS_APPROX(mat1, mat1ref);\n    VERIFY_IS_APPROX(mat2, mat2ref);\n  }\n\n  {\n    // test compound assignment\n    const Matrix4d mat_const = Matrix4d::Random(); \n    Matrix4d mat, mat_ref;\n    mat = mat_ref = Matrix4d::Identity();\n    add_assign_using_evaluator(mat, mat_const);\n    mat_ref += mat_const;\n    VERIFY_IS_APPROX(mat, mat_ref);\n\n    subtract_assign_using_evaluator(mat.row(1), 2*mat.row(2));\n    mat_ref.row(1) -= 2*mat_ref.row(2);\n    VERIFY_IS_APPROX(mat, mat_ref);\n\n    const ArrayXXf arr_const = ArrayXXf::Random(5,3); \n    ArrayXXf arr, arr_ref;\n    arr = arr_ref = ArrayXXf::Constant(5, 3, 0.5);\n    multiply_assign_using_evaluator(arr, arr_const);\n    arr_ref *= arr_const;\n    VERIFY_IS_APPROX(arr, arr_ref);\n\n    divide_assign_using_evaluator(arr.row(1), arr.row(2) + 1);\n    arr_ref.row(1) /= (arr_ref.row(2) + 1);\n    VERIFY_IS_APPROX(arr, arr_ref);\n  }\n  \n  {\n    // test triangular shapes\n    MatrixXd A = MatrixXd::Random(6,6), B(6,6), C(6,6), D(6,6);\n    A.setRandom();B.setRandom();\n    VERIFY_IS_APPROX_EVALUATOR2(B, A.triangularView<Upper>(), MatrixXd(A.triangularView<Upper>()));\n    \n    A.setRandom();B.setRandom();\n    VERIFY_IS_APPROX_EVALUATOR2(B, A.triangularView<UnitLower>(), MatrixXd(A.triangularView<UnitLower>()));\n    \n    A.setRandom();B.setRandom();\n    VERIFY_IS_APPROX_EVALUATOR2(B, A.triangularView<UnitUpper>(), MatrixXd(A.triangularView<UnitUpper>()));\n    \n    A.setRandom();B.setRandom();\n    C = B; C.triangularView<Upper>() = A;\n    copy_using_evaluator(B.triangularView<Upper>(), A);\n    VERIFY(B.isApprox(C) && \"copy_using_evaluator(B.triangularView<Upper>(), A)\");\n    \n    A.setRandom();B.setRandom();\n    C = B; C.triangularView<Lower>() = A.triangularView<Lower>();\n    copy_using_evaluator(B.triangularView<Lower>(), A.triangularView<Lower>());\n    VERIFY(B.isApprox(C) && \"copy_using_evaluator(B.triangularView<Lower>(), A.triangularView<Lower>())\");\n    \n    \n    A.setRandom();B.setRandom();\n    C = B; C.triangularView<Lower>() = A.triangularView<Upper>().transpose();\n    copy_using_evaluator(B.triangularView<Lower>(), A.triangularView<Upper>().transpose());\n    VERIFY(B.isApprox(C) && \"copy_using_evaluator(B.triangularView<Lower>(), A.triangularView<Lower>().transpose())\");\n    \n    \n    A.setRandom();B.setRandom(); C = B; D = A;\n    C.triangularView<Upper>().swap(D.triangularView<Upper>());\n    swap_using_evaluator(B.triangularView<Upper>(), A.triangularView<Upper>());\n    VERIFY(B.isApprox(C) && \"swap_using_evaluator(B.triangularView<Upper>(), A.triangularView<Upper>())\");\n    \n    \n    VERIFY_IS_APPROX_EVALUATOR2(B, prod(A.triangularView<Upper>(),A), MatrixXd(A.triangularView<Upper>()*A));\n    \n    VERIFY_IS_APPROX_EVALUATOR2(B, prod(A.selfadjointView<Upper>(),A), MatrixXd(A.selfadjointView<Upper>()*A));\n  }\n\n  {\n    // test diagonal shapes\n    VectorXd d = VectorXd::Random(6);\n    MatrixXd A = MatrixXd::Random(6,6), B(6,6);\n    A.setRandom();B.setRandom();\n    \n    VERIFY_IS_APPROX_EVALUATOR2(B, lazyprod(d.asDiagonal(),A), MatrixXd(d.asDiagonal()*A));\n    VERIFY_IS_APPROX_EVALUATOR2(B, lazyprod(A,d.asDiagonal()), MatrixXd(A*d.asDiagonal()));\n  }\n\n  {\n    // test CoeffReadCost\n    Matrix4d a, b;\n    VERIFY_IS_EQUAL( get_cost(a), 1 );\n    VERIFY_IS_EQUAL( get_cost(a+b), 3);\n    VERIFY_IS_EQUAL( get_cost(2*a+b), 4);\n    VERIFY_IS_EQUAL( get_cost(a*b), 1);\n    VERIFY_IS_EQUAL( get_cost(a.lazyProduct(b)), 15);\n    VERIFY_IS_EQUAL( get_cost(a*(a*b)), 1);\n    VERIFY_IS_EQUAL( get_cost(a.lazyProduct(a*b)), 15);\n    VERIFY_IS_EQUAL( get_cost(a*(a+b)), 1);\n    VERIFY_IS_EQUAL( get_cost(a.lazyProduct(a+b)), 15);\n  }\n\n  // regression test for PR 544 and bug 1622 (introduced in #71609c4)\n  {\n    // test restricted_packet_assignment with an unaligned destination\n    const size_t M = 2;\n    const size_t K = 2;\n    const size_t N = 5;\n    float *destMem = new float[(M*N) + 1];\n    float *dest = (internal::UIntPtr(destMem)%EIGEN_MAX_ALIGN_BYTES) == 0 ? destMem+1 : destMem;\n\n    const Matrix<float, Dynamic, Dynamic, RowMajor> a = Matrix<float, Dynamic, Dynamic, RowMajor>::Random(M, K);\n    const Matrix<float, Dynamic, Dynamic, RowMajor> b = Matrix<float, Dynamic, Dynamic, RowMajor>::Random(K, N);\n    \n    Map<Matrix<float, Dynamic, Dynamic, RowMajor> > z(dest, M, N);;\n    Product<Matrix<float, Dynamic, Dynamic, RowMajor>, Matrix<float, Dynamic, Dynamic, RowMajor>, LazyProduct> tmp(a,b);\n    internal::call_restricted_packet_assignment(z.noalias(), tmp.derived(), internal::assign_op<float, float>());\n    \n    VERIFY_IS_APPROX(z, a*b);\n    delete[] destMem;\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/exceptions.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n// Various sanity tests with exceptions and non trivially copyable scalar type.\n//  - no memory leak when a custom scalar type trow an exceptions\n//  - todo: complete the list of tests!\n\n#define EIGEN_STACK_ALLOCATION_LIMIT 100000000\n\n#include \"main.h\"\n#include \"AnnoyingScalar.h\"\n\n#define CHECK_MEMLEAK(OP) {                                 \\\n    AnnoyingScalar::countdown = 100;                        \\\n    int before = AnnoyingScalar::instances;                 \\\n    bool exception_thrown = false;                          \\\n    try { OP; }                                             \\\n    catch (my_exception) {                                  \\\n      exception_thrown = true;                              \\\n      VERIFY(AnnoyingScalar::instances==before && \"memory leak detected in \" && EIGEN_MAKESTRING(OP)); \\\n    } \\\n    VERIFY( (AnnoyingScalar::dont_throw) || (exception_thrown && \" no exception thrown in \" && EIGEN_MAKESTRING(OP)) ); \\\n  }\n\nEIGEN_DECLARE_TEST(exceptions)\n{\n  typedef Eigen::Matrix<AnnoyingScalar,Dynamic,1> VectorType;\n  typedef Eigen::Matrix<AnnoyingScalar,Dynamic,Dynamic> MatrixType;\n  \n  {\n    AnnoyingScalar::dont_throw = false;\n    int n = 50;\n    VectorType v0(n), v1(n);\n    MatrixType m0(n,n), m1(n,n), m2(n,n);\n    v0.setOnes(); v1.setOnes();\n    m0.setOnes(); m1.setOnes(); m2.setOnes();\n    CHECK_MEMLEAK(v0 = m0 * m1 * v1);\n    CHECK_MEMLEAK(m2 = m0 * m1 * m2);\n    CHECK_MEMLEAK((v0+v1).dot(v0+v1));\n  }\n  VERIFY(AnnoyingScalar::instances==0 && \"global memory leak detected in \" && EIGEN_MAKESTRING(OP));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/fastmath.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\nvoid check(bool b, bool ref)\n{\n  std::cout << b;\n  if(b==ref)\n    std::cout << \" OK  \";\n  else\n    std::cout << \" BAD \";\n}\n\n#if EIGEN_COMP_MSVC && EIGEN_COMP_MSVC < 1800\nnamespace std {\n  template<typename T> bool (isfinite)(T x) { return _finite(x); }\n  template<typename T> bool (isnan)(T x) { return _isnan(x); }\n  template<typename T> bool (isinf)(T x) { return _fpclass(x)==_FPCLASS_NINF || _fpclass(x)==_FPCLASS_PINF; }\n}\n#endif\n\ntemplate<typename T>\nvoid check_inf_nan(bool dryrun) {\n  Matrix<T,Dynamic,1> m(10);\n  m.setRandom();\n  m(3) = std::numeric_limits<T>::quiet_NaN();\n\n  if(dryrun)\n  {\n    std::cout << \"std::isfinite(\" << m(3) << \") = \"; check((std::isfinite)(m(3)),false); std::cout << \"  ; numext::isfinite = \"; check((numext::isfinite)(m(3)), false); std::cout << \"\\n\";\n    std::cout << \"std::isinf(\" << m(3) << \")    = \"; check((std::isinf)(m(3)),false);    std::cout << \"  ; numext::isinf    = \"; check((numext::isinf)(m(3)), false); std::cout << \"\\n\";\n    std::cout << \"std::isnan(\" << m(3) << \")    = \"; check((std::isnan)(m(3)),true);     std::cout << \"  ; numext::isnan    = \"; check((numext::isnan)(m(3)), true); std::cout << \"\\n\";\n    std::cout << \"allFinite: \"; check(m.allFinite(), 0); std::cout << \"\\n\";\n    std::cout << \"hasNaN:    \"; check(m.hasNaN(), 1);    std::cout << \"\\n\";\n    std::cout << \"\\n\";\n  }\n  else\n  {\n    if( (std::isfinite)(m(3))) g_test_level=1;  VERIFY( !(numext::isfinite)(m(3)) ); g_test_level=0;\n    if( (std::isinf)   (m(3))) g_test_level=1;  VERIFY( !(numext::isinf)(m(3)) );    g_test_level=0;\n    if(!(std::isnan)   (m(3))) g_test_level=1;  VERIFY(  (numext::isnan)(m(3)) );    g_test_level=0;\n    if( (std::isfinite)(m(3))) g_test_level=1;  VERIFY( !m.allFinite() );            g_test_level=0;\n    if(!(std::isnan)   (m(3))) g_test_level=1;  VERIFY(  m.hasNaN() );               g_test_level=0;\n  }\n  T hidden_zero = (std::numeric_limits<T>::min)()*(std::numeric_limits<T>::min)();\n  m(4) /= hidden_zero;\n  if(dryrun)\n  {\n    std::cout << \"std::isfinite(\" << m(4) << \") = \"; check((std::isfinite)(m(4)),false); std::cout << \"  ; numext::isfinite = \"; check((numext::isfinite)(m(4)), false); std::cout << \"\\n\";\n    std::cout << \"std::isinf(\" << m(4) << \")    = \"; check((std::isinf)(m(4)),true);     std::cout << \"  ; numext::isinf    = \"; check((numext::isinf)(m(4)), true); std::cout << \"\\n\";\n    std::cout << \"std::isnan(\" << m(4) << \")    = \"; check((std::isnan)(m(4)),false);    std::cout << \"  ; numext::isnan    = \"; check((numext::isnan)(m(4)), false); std::cout << \"\\n\";\n    std::cout << \"allFinite: \"; check(m.allFinite(), 0); std::cout << \"\\n\";\n    std::cout << \"hasNaN:    \"; check(m.hasNaN(), 1);    std::cout << \"\\n\";\n    std::cout << \"\\n\";\n  }\n  else\n  {\n    if( (std::isfinite)(m(3))) g_test_level=1;  VERIFY( !(numext::isfinite)(m(4)) );  g_test_level=0;\n    if(!(std::isinf)   (m(3))) g_test_level=1;  VERIFY(  (numext::isinf)(m(4)) );     g_test_level=0;\n    if( (std::isnan)   (m(3))) g_test_level=1;  VERIFY( !(numext::isnan)(m(4)) );     g_test_level=0;\n    if( (std::isfinite)(m(3))) g_test_level=1;  VERIFY( !m.allFinite() );             g_test_level=0;\n    if(!(std::isnan)   (m(3))) g_test_level=1;  VERIFY(  m.hasNaN() );                g_test_level=0;\n  }\n  m(3) = 0;\n  if(dryrun)\n  {\n    std::cout << \"std::isfinite(\" << m(3) << \") = \"; check((std::isfinite)(m(3)),true); std::cout << \"  ; numext::isfinite = \"; check((numext::isfinite)(m(3)), true); std::cout << \"\\n\";\n    std::cout << \"std::isinf(\" << m(3) << \")    = \"; check((std::isinf)(m(3)),false);   std::cout << \"  ; numext::isinf    = \"; check((numext::isinf)(m(3)), false); std::cout << \"\\n\";\n    std::cout << \"std::isnan(\" << m(3) << \")    = \"; check((std::isnan)(m(3)),false);   std::cout << \"  ; numext::isnan    = \"; check((numext::isnan)(m(3)), false); std::cout << \"\\n\";\n    std::cout << \"allFinite: \"; check(m.allFinite(), 0); std::cout << \"\\n\";\n    std::cout << \"hasNaN:    \"; check(m.hasNaN(), 0);    std::cout << \"\\n\";\n    std::cout << \"\\n\\n\";\n  }\n  else\n  {\n    if(!(std::isfinite)(m(3))) g_test_level=1;  VERIFY(  (numext::isfinite)(m(3)) );  g_test_level=0;\n    if( (std::isinf)   (m(3))) g_test_level=1;  VERIFY( !(numext::isinf)(m(3)) );     g_test_level=0;\n    if( (std::isnan)   (m(3))) g_test_level=1;  VERIFY( !(numext::isnan)(m(3)) );     g_test_level=0;\n    if( (std::isfinite)(m(3))) g_test_level=1;  VERIFY( !m.allFinite() );             g_test_level=0;\n    if( (std::isnan)   (m(3))) g_test_level=1;  VERIFY( !m.hasNaN() );                g_test_level=0;\n  }\n}\n\nEIGEN_DECLARE_TEST(fastmath) {\n  std::cout << \"*** float *** \\n\\n\"; check_inf_nan<float>(true);\n  std::cout << \"*** double ***\\n\\n\"; check_inf_nan<double>(true);\n  std::cout << \"*** long double *** \\n\\n\"; check_inf_nan<long double>(true);\n\n  check_inf_nan<float>(false);\n  check_inf_nan<double>(false);\n  check_inf_nan<long double>(false);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/first_aligned.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename Scalar>\nvoid test_first_aligned_helper(Scalar *array, int size)\n{\n  const int packet_size = sizeof(Scalar) * internal::packet_traits<Scalar>::size;\n  VERIFY(((size_t(array) + sizeof(Scalar) * internal::first_default_aligned(array, size)) % packet_size) == 0);\n}\n\ntemplate<typename Scalar>\nvoid test_none_aligned_helper(Scalar *array, int size)\n{\n  EIGEN_UNUSED_VARIABLE(array);\n  EIGEN_UNUSED_VARIABLE(size);\n  VERIFY(internal::packet_traits<Scalar>::size == 1 || internal::first_default_aligned(array, size) == size);\n}\n\nstruct some_non_vectorizable_type { float x; };\n\nEIGEN_DECLARE_TEST(first_aligned)\n{\n  EIGEN_ALIGN16 float array_float[100];\n  test_first_aligned_helper(array_float, 50);\n  test_first_aligned_helper(array_float+1, 50);\n  test_first_aligned_helper(array_float+2, 50);\n  test_first_aligned_helper(array_float+3, 50);\n  test_first_aligned_helper(array_float+4, 50);\n  test_first_aligned_helper(array_float+5, 50);\n  \n  EIGEN_ALIGN16 double array_double[100];\n  test_first_aligned_helper(array_double, 50);\n  test_first_aligned_helper(array_double+1, 50);\n  test_first_aligned_helper(array_double+2, 50);\n  \n  double *array_double_plus_4_bytes = (double*)(internal::UIntPtr(array_double)+4);\n  test_none_aligned_helper(array_double_plus_4_bytes, 50);\n  test_none_aligned_helper(array_double_plus_4_bytes+1, 50);\n  \n  some_non_vectorizable_type array_nonvec[100];\n  test_first_aligned_helper(array_nonvec, 100);\n  test_none_aligned_helper(array_nonvec, 100);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/geo_alignedbox.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/Geometry>\n\nusing namespace std;\n\n// NOTE the following workaround was needed on some 32 bits builds to kill extra precision of x87 registers.\n// It seems that it is not needed anymore, but let's keep it here, just in case...\n\ntemplate<typename T> EIGEN_DONT_INLINE\nvoid kill_extra_precision(T& /* x */) {\n  // This one worked but triggered a warning:\n  /* eigen_assert((void*)(&x) != (void*)0); */\n  // An alternative could be:\n  /* volatile T tmp = x; */\n  /* x = tmp; */\n}\n\n\ntemplate<typename BoxType> void alignedbox(const BoxType& box)\n{\n  /* this test covers the following files:\n     AlignedBox.h\n  */\n  typedef typename BoxType::Scalar Scalar;\n  typedef NumTraits<Scalar> ScalarTraits;\n  typedef typename ScalarTraits::Real RealScalar;\n  typedef Matrix<Scalar, BoxType::AmbientDimAtCompileTime, 1> VectorType;\n\n  const Index dim = box.dim();\n\n  VectorType p0 = VectorType::Random(dim);\n  VectorType p1 = VectorType::Random(dim);\n  while( p1 == p0 ){\n      p1 =  VectorType::Random(dim); }\n  RealScalar s1 = internal::random<RealScalar>(0,1);\n\n  BoxType b0(dim);\n  BoxType b1(VectorType::Random(dim),VectorType::Random(dim));\n  BoxType b2;\n\n  kill_extra_precision(b1);\n  kill_extra_precision(p0);\n  kill_extra_precision(p1);\n\n  b0.extend(p0);\n  b0.extend(p1);\n  VERIFY(b0.contains(p0*s1+(Scalar(1)-s1)*p1));\n  VERIFY(b0.contains(b0.center()));\n  VERIFY_IS_APPROX(b0.center(),(p0+p1)/Scalar(2));\n\n  (b2 = b0).extend(b1);\n  VERIFY(b2.contains(b0));\n  VERIFY(b2.contains(b1));\n  VERIFY_IS_APPROX(b2.clamp(b0), b0);\n\n  // intersection\n  BoxType box1(VectorType::Random(dim));\n  box1.extend(VectorType::Random(dim));\n  BoxType box2(VectorType::Random(dim));\n  box2.extend(VectorType::Random(dim));\n\n  VERIFY(box1.intersects(box2) == !box1.intersection(box2).isEmpty());\n\n  // alignment -- make sure there is no memory alignment assertion\n  BoxType *bp0 = new BoxType(dim);\n  BoxType *bp1 = new BoxType(dim);\n  bp0->extend(*bp1);\n  delete bp0;\n  delete bp1;\n\n  // sampling\n  for( int i=0; i<10; ++i )\n  {\n      VectorType r = b0.sample();\n      VERIFY(b0.contains(r));\n  }\n\n}\n\ntemplate<typename BoxType> void alignedboxTranslatable(const BoxType& box)\n{\n  typedef typename BoxType::Scalar Scalar;\n  typedef Matrix<Scalar, BoxType::AmbientDimAtCompileTime, 1> VectorType;\n  typedef Transform<Scalar, BoxType::AmbientDimAtCompileTime, Isometry> IsometryTransform;\n  typedef Transform<Scalar, BoxType::AmbientDimAtCompileTime, Affine> AffineTransform;\n\n  alignedbox(box);\n\n  const VectorType Ones = VectorType::Ones();\n  const VectorType UnitX = VectorType::UnitX();\n  const Index dim = box.dim();\n\n  // box((-1, -1, -1), (1, 1, 1))\n  BoxType a(-Ones, Ones);\n\n  VERIFY_IS_APPROX(a.sizes(), Ones * Scalar(2));\n\n  BoxType b = a;\n  VectorType translate = Ones;\n  translate[0] = Scalar(2);\n  b.translate(translate);\n  // translate by (2, 1, 1) -> box((1, 0, 0), (3, 2, 2))\n\n  VERIFY_IS_APPROX(b.sizes(), Ones * Scalar(2));\n  VERIFY_IS_APPROX((b.min)(), UnitX);\n  VERIFY_IS_APPROX((b.max)(), Ones * Scalar(2) + UnitX);\n\n  // Test transform\n\n  IsometryTransform tf = IsometryTransform::Identity();\n  tf.translation() = -translate;\n\n  BoxType c = b.transformed(tf);\n  // translate by (-2, -1, -1) -> box((-1, -1, -1), (1, 1, 1))\n  VERIFY_IS_APPROX(c.sizes(), a.sizes());\n  VERIFY_IS_APPROX((c.min)(), (a.min)());\n  VERIFY_IS_APPROX((c.max)(), (a.max)());\n\n  c.transform(tf);\n  // translate by (-2, -1, -1) -> box((-3, -2, -2), (-1, 0, 0))\n  VERIFY_IS_APPROX(c.sizes(), a.sizes());\n  VERIFY_IS_APPROX((c.min)(), Ones * Scalar(-2) - UnitX);\n  VERIFY_IS_APPROX((c.max)(), -UnitX);\n\n  // Scaling\n\n  AffineTransform atf = AffineTransform::Identity();\n  atf.scale(Scalar(3));\n  c.transform(atf);\n  // scale by 3 -> box((-9, -6, -6), (-3, 0, 0))\n  VERIFY_IS_APPROX(c.sizes(), Scalar(3) * a.sizes());\n  VERIFY_IS_APPROX((c.min)(), Ones * Scalar(-6) - UnitX * Scalar(3));\n  VERIFY_IS_APPROX((c.max)(), UnitX * Scalar(-3));\n\n  atf = AffineTransform::Identity();\n  atf.scale(Scalar(-3));\n  c.transform(atf);\n  // scale by -3 -> box((27, 18, 18), (9, 0, 0))\n  VERIFY_IS_APPROX(c.sizes(), Scalar(9) * a.sizes());\n  VERIFY_IS_APPROX((c.min)(), UnitX * Scalar(9));\n  VERIFY_IS_APPROX((c.max)(), Ones * Scalar(18) + UnitX * Scalar(9));\n\n  // Check identity transform within numerical precision.\n  BoxType transformedC = c.transformed(IsometryTransform::Identity());\n  VERIFY_IS_APPROX(transformedC, c);\n\n  for (size_t i = 0; i < 10; ++i)\n  {\n    VectorType minCorner;\n    VectorType maxCorner;\n    for (Index d = 0; d < dim; ++d)\n    {\n      minCorner[d] = internal::random<Scalar>(-10,10);\n      maxCorner[d] = minCorner[d] + internal::random<Scalar>(0, 10);\n    }\n\n    c = BoxType(minCorner, maxCorner);\n\n    translate = VectorType::Random();\n    c.translate(translate);\n\n    VERIFY_IS_APPROX((c.min)(), minCorner + translate);\n    VERIFY_IS_APPROX((c.max)(), maxCorner + translate);\n  }\n}\n\ntemplate<typename Scalar, typename Rotation>\nRotation rotate2D(Scalar angle) {\n  return Rotation2D<Scalar>(angle);\n}\n\ntemplate<typename Scalar, typename Rotation>\nRotation rotate2DIntegral(typename NumTraits<Scalar>::NonInteger angle) {\n  typedef typename NumTraits<Scalar>::NonInteger NonInteger;\n  return Rotation2D<NonInteger>(angle).toRotationMatrix().\n      template cast<Scalar>();\n}\n\ntemplate<typename Scalar, typename Rotation>\nRotation rotate3DZAxis(Scalar angle) {\n  return AngleAxis<Scalar>(angle, Matrix<Scalar, 3, 1>(0, 0, 1));\n}\n\ntemplate<typename Scalar, typename Rotation>\nRotation rotate3DZAxisIntegral(typename NumTraits<Scalar>::NonInteger angle) {\n  typedef typename NumTraits<Scalar>::NonInteger NonInteger;\n  return AngleAxis<NonInteger>(angle, Matrix<NonInteger, 3, 1>(0, 0, 1)).\n      toRotationMatrix().template cast<Scalar>();\n}\n\ntemplate<typename Scalar, typename Rotation>\nRotation rotate4DZWAxis(Scalar angle) {\n  Rotation result = Matrix<Scalar, 4, 4>::Identity();\n  result.block(0, 0, 3, 3) = rotate3DZAxis<Scalar, AngleAxisd>(angle).toRotationMatrix();\n  return result;\n}\n\ntemplate <typename MatrixType>\nMatrixType randomRotationMatrix()\n{\n  // algorithm from\n  // https://www.isprs-ann-photogramm-remote-sens-spatial-inf-sci.net/III-7/103/2016/isprs-annals-III-7-103-2016.pdf\n  const MatrixType rand = MatrixType::Random();\n  const MatrixType q = rand.householderQr().householderQ();\n  const JacobiSVD<MatrixType> svd = q.jacobiSvd(ComputeFullU | ComputeFullV);\n  const typename MatrixType::Scalar det = (svd.matrixU() * svd.matrixV().transpose()).determinant();\n  MatrixType diag = rand.Identity();\n  diag(MatrixType::RowsAtCompileTime - 1, MatrixType::ColsAtCompileTime - 1) = det;\n  const MatrixType rotation = svd.matrixU() * diag * svd.matrixV().transpose();\n  return rotation;\n}\n\ntemplate <typename Scalar, int Dim>\nMatrix<Scalar, Dim, (1<<Dim)> boxGetCorners(const Matrix<Scalar, Dim, 1>& min_, const Matrix<Scalar, Dim, 1>& max_)\n{\n  Matrix<Scalar, Dim, (1<<Dim) > result;\n  for(Index i=0; i<(1<<Dim); ++i)\n  {\n    for(Index j=0; j<Dim; ++j)\n      result(j,i) = (i & (1<<j)) ? min_(j) : max_(j);\n  }\n  return result;\n}\n\ntemplate<typename BoxType, typename Rotation> void alignedboxRotatable(\n    const BoxType& box,\n    Rotation (*rotate)(typename NumTraits<typename BoxType::Scalar>::NonInteger /*_angle*/))\n{\n  alignedboxTranslatable(box);\n\n  typedef typename BoxType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::NonInteger NonInteger;\n  typedef Matrix<Scalar, BoxType::AmbientDimAtCompileTime, 1> VectorType;\n  typedef Transform<Scalar, BoxType::AmbientDimAtCompileTime, Isometry> IsometryTransform;\n  typedef Transform<Scalar, BoxType::AmbientDimAtCompileTime, Affine> AffineTransform;\n\n  const VectorType Zero = VectorType::Zero();\n  const VectorType Ones = VectorType::Ones();\n  const VectorType UnitX = VectorType::UnitX();\n  const VectorType UnitY = VectorType::UnitY();\n  // this is vector (0, 0, -1, -1, -1, ...), i.e. with zeros at first and second dimensions\n  const VectorType UnitZ = Ones - UnitX - UnitY;\n\n  // in this kind of comments the 3D case values will be illustrated\n  // box((-1, -1, -1), (1, 1, 1))\n  BoxType a(-Ones, Ones);\n\n  // to allow templating this test for both 2D and 3D cases, we always set all\n  // but the first coordinate to the same value; so basically 3D case works as\n  // if you were looking at the scene from top\n\n  VectorType minPoint = -2 * Ones;\n  minPoint[0] = -3;\n  VectorType maxPoint = Zero;\n  maxPoint[0] = -1;\n  BoxType c(minPoint, maxPoint);\n  // box((-3, -2, -2), (-1, 0, 0))\n\n  IsometryTransform tf2 = IsometryTransform::Identity();\n  // for some weird reason the following statement has to be put separate from\n  // the following rotate call, otherwise precision problems arise...\n  Rotation rot = rotate(NonInteger(EIGEN_PI));\n  tf2.rotate(rot);\n\n  c.transform(tf2);\n  // rotate by 180 deg around origin -> box((1, 0, -2), (3, 2, 0))\n\n  VERIFY_IS_APPROX(c.sizes(), a.sizes());\n  VERIFY_IS_APPROX((c.min)(), UnitX - UnitZ * Scalar(2));\n  VERIFY_IS_APPROX((c.max)(), UnitX * Scalar(3) + UnitY * Scalar(2));\n\n  rot = rotate(NonInteger(EIGEN_PI / 2));\n  tf2.setIdentity();\n  tf2.rotate(rot);\n\n  c.transform(tf2);\n  // rotate by 90 deg around origin ->  box((-2, 1, -2), (0, 3, 0))\n\n  VERIFY_IS_APPROX(c.sizes(), a.sizes());\n  VERIFY_IS_APPROX((c.min)(), Ones * Scalar(-2) + UnitY * Scalar(3));\n  VERIFY_IS_APPROX((c.max)(), UnitY * Scalar(3));\n\n  // box((-1, -1, -1), (1, 1, 1))\n  AffineTransform atf = AffineTransform::Identity();\n  atf.linearExt()(0, 1) = Scalar(1);\n  c = BoxType(-Ones, Ones);\n  c.transform(atf);\n  // 45 deg shear in x direction -> box((-2, -1, -1), (2, 1, 1))\n\n  VERIFY_IS_APPROX(c.sizes(), Ones * Scalar(2) + UnitX * Scalar(2));\n  VERIFY_IS_APPROX((c.min)(), -Ones - UnitX);\n  VERIFY_IS_APPROX((c.max)(), Ones + UnitX);\n}\n\ntemplate<typename BoxType, typename Rotation> void alignedboxNonIntegralRotatable(\n    const BoxType& box,\n    Rotation (*rotate)(typename NumTraits<typename BoxType::Scalar>::NonInteger /*_angle*/))\n{\n  alignedboxRotatable(box, rotate);\n\n  typedef typename BoxType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::NonInteger NonInteger;\n  enum { Dim = BoxType::AmbientDimAtCompileTime };\n  typedef Matrix<Scalar, Dim, 1> VectorType;\n  typedef Matrix<Scalar, Dim, (1 << Dim)> CornersType;\n  typedef Transform<Scalar, Dim, Isometry> IsometryTransform;\n  typedef Transform<Scalar, Dim, Affine> AffineTransform;\n\n  const Index dim = box.dim();\n  const VectorType Zero = VectorType::Zero();\n  const VectorType Ones = VectorType::Ones();\n\n  VectorType minPoint = -2 * Ones;\n  minPoint[1] = 1;\n  VectorType maxPoint = Zero;\n  maxPoint[1] = 3;\n  BoxType c(minPoint, maxPoint);\n  // ((-2, 1, -2), (0, 3, 0))\n\n  VectorType cornerBL = (c.min)();\n  VectorType cornerTR = (c.max)();\n  VectorType cornerBR = (c.min)(); cornerBR[0] = cornerTR[0];\n  VectorType cornerTL = (c.max)(); cornerTL[0] = cornerBL[0];\n\n  NonInteger angle = NonInteger(EIGEN_PI/3);\n  Rotation rot = rotate(angle);\n  IsometryTransform tf2;\n  tf2.setIdentity();\n  tf2.rotate(rot);\n\n  c.transform(tf2);\n  // rotate by 60 deg ->  box((-3.59, -1.23, -2), (-0.86, 1.5, 0))\n\n  cornerBL = tf2 * cornerBL;\n  cornerBR = tf2 * cornerBR;\n  cornerTL = tf2 * cornerTL;\n  cornerTR = tf2 * cornerTR;\n\n  VectorType minCorner = Ones * Scalar(-2);\n  VectorType maxCorner = Zero;\n  minCorner[0] = (min)((min)(cornerBL[0], cornerBR[0]), (min)(cornerTL[0], cornerTR[0]));\n  maxCorner[0] = (max)((max)(cornerBL[0], cornerBR[0]), (max)(cornerTL[0], cornerTR[0]));\n  minCorner[1] = (min)((min)(cornerBL[1], cornerBR[1]), (min)(cornerTL[1], cornerTR[1]));\n  maxCorner[1] = (max)((max)(cornerBL[1], cornerBR[1]), (max)(cornerTL[1], cornerTR[1]));\n\n  for (Index d = 2; d < dim; ++d)\n    VERIFY_IS_APPROX(c.sizes()[d], Scalar(2));\n\n  VERIFY_IS_APPROX((c.min)(), minCorner);\n  VERIFY_IS_APPROX((c.max)(), maxCorner);\n\n  VectorType minCornerValue = Ones * Scalar(-2);\n  VectorType maxCornerValue = Zero;\n  minCornerValue[0] = Scalar(Scalar(-sqrt(2*2 + 3*3)) * Scalar(cos(Scalar(atan(2.0/3.0)) - angle/2)));\n  minCornerValue[1] = Scalar(Scalar(-sqrt(1*1 + 2*2)) * Scalar(sin(Scalar(atan(2.0/1.0)) - angle/2)));\n  maxCornerValue[0] = Scalar(-sin(angle));\n  maxCornerValue[1] = Scalar(3 * cos(angle));\n  VERIFY_IS_APPROX((c.min)(), minCornerValue);\n  VERIFY_IS_APPROX((c.max)(), maxCornerValue);\n\n  // randomized test - translate and rotate the box and compare to a box made of transformed vertices\n  for (size_t i = 0; i < 10; ++i)\n  {\n    for (Index d = 0; d < dim; ++d)\n    {\n      minCorner[d] = internal::random<Scalar>(-10,10);\n      maxCorner[d] = minCorner[d] + internal::random<Scalar>(0, 10);\n    }\n\n    c = BoxType(minCorner, maxCorner);\n\n    CornersType corners = boxGetCorners(minCorner, maxCorner);\n\n    typename AffineTransform::LinearMatrixType rotation =\n        randomRotationMatrix<typename AffineTransform::LinearMatrixType>();\n\n    tf2.setIdentity();\n    tf2.rotate(rotation);\n    tf2.translate(VectorType::Random());\n\n    c.transform(tf2);\n    corners = tf2 * corners;\n\n    minCorner = corners.rowwise().minCoeff();\n    maxCorner = corners.rowwise().maxCoeff();\n\n    VERIFY_IS_APPROX((c.min)(), minCorner);\n    VERIFY_IS_APPROX((c.max)(), maxCorner);\n  }\n\n  // randomized test - transform the box with a random affine matrix and compare to a box made of transformed vertices\n  for (size_t i = 0; i < 10; ++i)\n  {\n    for (Index d = 0; d < dim; ++d)\n    {\n      minCorner[d] = internal::random<Scalar>(-10,10);\n      maxCorner[d] = minCorner[d] + internal::random<Scalar>(0, 10);\n    }\n\n    c = BoxType(minCorner, maxCorner);\n\n    CornersType corners = boxGetCorners(minCorner, maxCorner);\n\n    AffineTransform atf = AffineTransform::Identity();\n    atf.linearExt() = AffineTransform::LinearPart::Random();\n    atf.translate(VectorType::Random());\n\n    c.transform(atf);\n    corners = atf * corners;\n\n    minCorner = corners.rowwise().minCoeff();\n    maxCorner = corners.rowwise().maxCoeff();\n\n    VERIFY_IS_APPROX((c.min)(), minCorner);\n    VERIFY_IS_APPROX((c.max)(), maxCorner);\n  }\n}\n\ntemplate<typename BoxType>\nvoid alignedboxCastTests(const BoxType& box)\n{\n  // casting\n  typedef typename BoxType::Scalar Scalar;\n  typedef Matrix<Scalar, BoxType::AmbientDimAtCompileTime, 1> VectorType;\n\n  const Index dim = box.dim();\n\n  VectorType p0 = VectorType::Random(dim);\n  VectorType p1 = VectorType::Random(dim);\n\n  BoxType b0(dim);\n\n  b0.extend(p0);\n  b0.extend(p1);\n\n  const int Dim = BoxType::AmbientDimAtCompileTime;\n  typedef typename GetDifferentType<Scalar>::type OtherScalar;\n  AlignedBox<OtherScalar,Dim> hp1f = b0.template cast<OtherScalar>();\n  VERIFY_IS_APPROX(hp1f.template cast<Scalar>(),b0);\n  AlignedBox<Scalar,Dim> hp1d = b0.template cast<Scalar>();\n  VERIFY_IS_APPROX(hp1d.template cast<Scalar>(),b0);\n}\n\n\nvoid specificTest1()\n{\n    Vector2f m; m << -1.0f, -2.0f;\n    Vector2f M; M <<  1.0f,  5.0f;\n\n    typedef AlignedBox2f  BoxType;\n    BoxType box( m, M );\n\n    Vector2f sides = M-m;\n    VERIFY_IS_APPROX(sides, box.sizes() );\n    VERIFY_IS_APPROX(sides[1], box.sizes()[1] );\n    VERIFY_IS_APPROX(sides[1], box.sizes().maxCoeff() );\n    VERIFY_IS_APPROX(sides[0], box.sizes().minCoeff() );\n\n    VERIFY_IS_APPROX( 14.0f, box.volume() );\n    VERIFY_IS_APPROX( 53.0f, box.diagonal().squaredNorm() );\n    VERIFY_IS_APPROX( std::sqrt( 53.0f ), box.diagonal().norm() );\n\n    VERIFY_IS_APPROX( m, box.corner( BoxType::BottomLeft ) );\n    VERIFY_IS_APPROX( M, box.corner( BoxType::TopRight ) );\n    Vector2f bottomRight; bottomRight << M[0], m[1];\n    Vector2f topLeft; topLeft << m[0], M[1];\n    VERIFY_IS_APPROX( bottomRight, box.corner( BoxType::BottomRight ) );\n    VERIFY_IS_APPROX( topLeft, box.corner( BoxType::TopLeft ) );\n}\n\n\nvoid specificTest2()\n{\n    Vector3i m; m << -1, -2, 0;\n    Vector3i M; M <<  1,  5, 3;\n\n    typedef AlignedBox3i  BoxType;\n    BoxType box( m, M );\n\n    Vector3i sides = M-m;\n    VERIFY_IS_APPROX(sides, box.sizes() );\n    VERIFY_IS_APPROX(sides[1], box.sizes()[1] );\n    VERIFY_IS_APPROX(sides[1], box.sizes().maxCoeff() );\n    VERIFY_IS_APPROX(sides[0], box.sizes().minCoeff() );\n\n    VERIFY_IS_APPROX( 42, box.volume() );\n    VERIFY_IS_APPROX( 62, box.diagonal().squaredNorm() );\n\n    VERIFY_IS_APPROX( m, box.corner( BoxType::BottomLeftFloor ) );\n    VERIFY_IS_APPROX( M, box.corner( BoxType::TopRightCeil ) );\n    Vector3i bottomRightFloor; bottomRightFloor << M[0], m[1], m[2];\n    Vector3i topLeftFloor; topLeftFloor << m[0], M[1], m[2];\n    VERIFY_IS_APPROX( bottomRightFloor, box.corner( BoxType::BottomRightFloor ) );\n    VERIFY_IS_APPROX( topLeftFloor, box.corner( BoxType::TopLeftFloor ) );\n}\n\n\nEIGEN_DECLARE_TEST(geo_alignedbox)\n{\n  for(int i = 0; i < g_repeat; i++)\n  {\n    CALL_SUBTEST_1( (alignedboxNonIntegralRotatable<AlignedBox2f, Rotation2Df>(AlignedBox2f(), &rotate2D)) );\n    CALL_SUBTEST_2( alignedboxCastTests(AlignedBox2f()) );\n\n    CALL_SUBTEST_3( (alignedboxNonIntegralRotatable<AlignedBox3f, AngleAxisf>(AlignedBox3f(), &rotate3DZAxis)) );\n    CALL_SUBTEST_4( alignedboxCastTests(AlignedBox3f()) );\n\n    CALL_SUBTEST_5( (alignedboxNonIntegralRotatable<AlignedBox4d, Matrix4d>(AlignedBox4d(), &rotate4DZWAxis)) );\n    CALL_SUBTEST_6( alignedboxCastTests(AlignedBox4d()) );\n\n    CALL_SUBTEST_7( alignedboxTranslatable(AlignedBox1d()) );\n    CALL_SUBTEST_8( alignedboxCastTests(AlignedBox1d()) );\n\n    CALL_SUBTEST_9( alignedboxTranslatable(AlignedBox1i()) );\n    CALL_SUBTEST_10( (alignedboxRotatable<AlignedBox2i, Matrix2i>(AlignedBox2i(), &rotate2DIntegral<int, Matrix2i>)) );\n    CALL_SUBTEST_11( (alignedboxRotatable<AlignedBox3i, Matrix3i>(AlignedBox3i(), &rotate3DZAxisIntegral<int, Matrix3i>)) );\n\n    CALL_SUBTEST_14( alignedbox(AlignedBox<double,Dynamic>(4)) );\n  }\n  CALL_SUBTEST_12( specificTest1() );\n  CALL_SUBTEST_13( specificTest2() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/geo_eulerangles.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/Geometry>\n#include <Eigen/LU>\n#include <Eigen/SVD>\n\n\ntemplate<typename Scalar>\nvoid verify_euler(const Matrix<Scalar,3,1>& ea, int i, int j, int k)\n{\n  typedef Matrix<Scalar,3,3> Matrix3;\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef AngleAxis<Scalar> AngleAxisx;\n  using std::abs;\n  Matrix3 m(AngleAxisx(ea[0], Vector3::Unit(i)) * AngleAxisx(ea[1], Vector3::Unit(j)) * AngleAxisx(ea[2], Vector3::Unit(k)));\n  Vector3 eabis = m.eulerAngles(i, j, k);\n  Matrix3 mbis(AngleAxisx(eabis[0], Vector3::Unit(i)) * AngleAxisx(eabis[1], Vector3::Unit(j)) * AngleAxisx(eabis[2], Vector3::Unit(k))); \n  VERIFY_IS_APPROX(m,  mbis); \n  /* If I==K, and ea[1]==0, then there no unique solution. */ \n  /* The remark apply in the case where I!=K, and |ea[1]| is close to pi/2. */ \n  if( (i!=k || ea[1]!=0) && (i==k || !internal::isApprox(abs(ea[1]),Scalar(EIGEN_PI/2),test_precision<Scalar>())) ) \n    VERIFY((ea-eabis).norm() <= test_precision<Scalar>());\n  \n  // approx_or_less_than does not work for 0\n  VERIFY(0 < eabis[0] || test_isMuchSmallerThan(eabis[0], Scalar(1)));\n  VERIFY_IS_APPROX_OR_LESS_THAN(eabis[0], Scalar(EIGEN_PI));\n  VERIFY_IS_APPROX_OR_LESS_THAN(-Scalar(EIGEN_PI), eabis[1]);\n  VERIFY_IS_APPROX_OR_LESS_THAN(eabis[1], Scalar(EIGEN_PI));\n  VERIFY_IS_APPROX_OR_LESS_THAN(-Scalar(EIGEN_PI), eabis[2]);\n  VERIFY_IS_APPROX_OR_LESS_THAN(eabis[2], Scalar(EIGEN_PI));\n}\n\ntemplate<typename Scalar> void check_all_var(const Matrix<Scalar,3,1>& ea)\n{\n  verify_euler(ea, 0,1,2);\n  verify_euler(ea, 0,1,0);\n  verify_euler(ea, 0,2,1);\n  verify_euler(ea, 0,2,0);\n\n  verify_euler(ea, 1,2,0);\n  verify_euler(ea, 1,2,1);\n  verify_euler(ea, 1,0,2);\n  verify_euler(ea, 1,0,1);\n\n  verify_euler(ea, 2,0,1);\n  verify_euler(ea, 2,0,2);\n  verify_euler(ea, 2,1,0);\n  verify_euler(ea, 2,1,2);\n}\n\ntemplate<typename Scalar> void eulerangles()\n{\n  typedef Matrix<Scalar,3,3> Matrix3;\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef Array<Scalar,3,1> Array3;\n  typedef Quaternion<Scalar> Quaternionx;\n  typedef AngleAxis<Scalar> AngleAxisx;\n\n  Scalar a = internal::random<Scalar>(-Scalar(EIGEN_PI), Scalar(EIGEN_PI));\n  Quaternionx q1;\n  q1 = AngleAxisx(a, Vector3::Random().normalized());\n  Matrix3 m;\n  m = q1;\n  \n  Vector3 ea = m.eulerAngles(0,1,2);\n  check_all_var(ea);\n  ea = m.eulerAngles(0,1,0);\n  check_all_var(ea);\n  \n  // Check with purely random Quaternion:\n  q1.coeffs() = Quaternionx::Coefficients::Random().normalized();\n  m = q1;\n  ea = m.eulerAngles(0,1,2);\n  check_all_var(ea);\n  ea = m.eulerAngles(0,1,0);\n  check_all_var(ea);\n  \n  // Check with random angles in range [0:pi]x[-pi:pi]x[-pi:pi].\n  ea = (Array3::Random() + Array3(1,0,0))*Scalar(EIGEN_PI)*Array3(0.5,1,1);\n  check_all_var(ea);\n  \n  ea[2] = ea[0] = internal::random<Scalar>(0,Scalar(EIGEN_PI));\n  check_all_var(ea);\n  \n  ea[0] = ea[1] = internal::random<Scalar>(0,Scalar(EIGEN_PI));\n  check_all_var(ea);\n  \n  ea[1] = 0;\n  check_all_var(ea);\n  \n  ea.head(2).setZero();\n  check_all_var(ea);\n  \n  ea.setZero();\n  check_all_var(ea);\n}\n\nEIGEN_DECLARE_TEST(geo_eulerangles)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( eulerangles<float>() );\n    CALL_SUBTEST_2( eulerangles<double>() );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/geo_homogeneous.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/Geometry>\n\ntemplate<typename Scalar,int Size> void homogeneous(void)\n{\n  /* this test covers the following files:\n     Homogeneous.h\n  */\n\n  typedef Matrix<Scalar,Size,Size> MatrixType;\n  typedef Matrix<Scalar,Size,1, ColMajor> VectorType;\n\n  typedef Matrix<Scalar,Size+1,Size> HMatrixType;\n  typedef Matrix<Scalar,Size+1,1> HVectorType;\n\n  typedef Matrix<Scalar,Size,Size+1>   T1MatrixType;\n  typedef Matrix<Scalar,Size+1,Size+1> T2MatrixType;\n  typedef Matrix<Scalar,Size+1,Size> T3MatrixType;\n\n  VectorType v0 = VectorType::Random(),\n             ones = VectorType::Ones();\n\n  HVectorType hv0 = HVectorType::Random();\n\n  MatrixType m0 = MatrixType::Random();\n\n  HMatrixType hm0 = HMatrixType::Random();\n\n  hv0 << v0, 1;\n  VERIFY_IS_APPROX(v0.homogeneous(), hv0);\n  VERIFY_IS_APPROX(v0, hv0.hnormalized());\n  \n  VERIFY_IS_APPROX(v0.homogeneous().sum(), hv0.sum());\n  VERIFY_IS_APPROX(v0.homogeneous().minCoeff(), hv0.minCoeff());\n  VERIFY_IS_APPROX(v0.homogeneous().maxCoeff(), hv0.maxCoeff());\n\n  hm0 << m0, ones.transpose();\n  VERIFY_IS_APPROX(m0.colwise().homogeneous(), hm0);\n  VERIFY_IS_APPROX(m0, hm0.colwise().hnormalized());\n  hm0.row(Size-1).setRandom();\n  for(int j=0; j<Size; ++j)\n    m0.col(j) = hm0.col(j).head(Size) / hm0(Size,j);\n  VERIFY_IS_APPROX(m0, hm0.colwise().hnormalized());\n\n  T1MatrixType t1 = T1MatrixType::Random();\n  VERIFY_IS_APPROX(t1 * (v0.homogeneous().eval()), t1 * v0.homogeneous());\n  VERIFY_IS_APPROX(t1 * (m0.colwise().homogeneous().eval()), t1 * m0.colwise().homogeneous());\n\n  T2MatrixType t2 = T2MatrixType::Random();\n  VERIFY_IS_APPROX(t2 * (v0.homogeneous().eval()), t2 * v0.homogeneous());\n  VERIFY_IS_APPROX(t2 * (m0.colwise().homogeneous().eval()), t2 * m0.colwise().homogeneous());\n  VERIFY_IS_APPROX(t2 * (v0.homogeneous().asDiagonal()), t2 * hv0.asDiagonal());\n  VERIFY_IS_APPROX((v0.homogeneous().asDiagonal()) * t2, hv0.asDiagonal() * t2);\n\n  VERIFY_IS_APPROX((v0.transpose().rowwise().homogeneous().eval()) * t2,\n                    v0.transpose().rowwise().homogeneous() * t2);\n  VERIFY_IS_APPROX((m0.transpose().rowwise().homogeneous().eval()) * t2,\n                    m0.transpose().rowwise().homogeneous() * t2);\n\n  T3MatrixType t3 = T3MatrixType::Random();\n  VERIFY_IS_APPROX((v0.transpose().rowwise().homogeneous().eval()) * t3,\n                    v0.transpose().rowwise().homogeneous() * t3);\n  VERIFY_IS_APPROX((m0.transpose().rowwise().homogeneous().eval()) * t3,\n                    m0.transpose().rowwise().homogeneous() * t3);\n\n  // test product with a Transform object\n  Transform<Scalar, Size, Affine> aff;\n  Transform<Scalar, Size, AffineCompact> caff;\n  Transform<Scalar, Size, Projective> proj;\n  Matrix<Scalar, Size, Dynamic>   pts;\n  Matrix<Scalar, Size+1, Dynamic> pts1, pts2;\n\n  aff.affine().setRandom();\n  proj = caff = aff;\n  pts.setRandom(Size,internal::random<int>(1,20));\n  \n  pts1 = pts.colwise().homogeneous();\n  VERIFY_IS_APPROX(aff  * pts.colwise().homogeneous(), (aff  * pts1).colwise().hnormalized());\n  VERIFY_IS_APPROX(caff * pts.colwise().homogeneous(), (caff * pts1).colwise().hnormalized());\n  VERIFY_IS_APPROX(proj * pts.colwise().homogeneous(), (proj * pts1));\n\n  VERIFY_IS_APPROX((aff  * pts1).colwise().hnormalized(),  aff  * pts);\n  VERIFY_IS_APPROX((caff * pts1).colwise().hnormalized(), caff * pts);\n  \n  pts2 = pts1;\n  pts2.row(Size).setRandom();\n  VERIFY_IS_APPROX((aff  * pts2).colwise().hnormalized(), aff  * pts2.colwise().hnormalized());\n  VERIFY_IS_APPROX((caff * pts2).colwise().hnormalized(), caff * pts2.colwise().hnormalized());\n  VERIFY_IS_APPROX((proj * pts2).colwise().hnormalized(), (proj * pts2.colwise().hnormalized().colwise().homogeneous()).colwise().hnormalized());\n  \n  // Test combination of homogeneous\n  \n  VERIFY_IS_APPROX( (t2 * v0.homogeneous()).hnormalized(),\n                       (t2.template topLeftCorner<Size,Size>() * v0 + t2.template topRightCorner<Size,1>())\n                     / ((t2.template bottomLeftCorner<1,Size>()*v0).value() + t2(Size,Size)) );\n  \n  VERIFY_IS_APPROX( (t2 * pts.colwise().homogeneous()).colwise().hnormalized(),\n                    (Matrix<Scalar, Size+1, Dynamic>(t2 * pts1).colwise().hnormalized()) );\n  \n  VERIFY_IS_APPROX( (t2 .lazyProduct( v0.homogeneous() )).hnormalized(), (t2 * v0.homogeneous()).hnormalized() );\n  VERIFY_IS_APPROX( (t2 .lazyProduct  ( pts.colwise().homogeneous() )).colwise().hnormalized(), (t2 * pts1).colwise().hnormalized() );\n  \n  VERIFY_IS_APPROX( (v0.transpose().homogeneous() .lazyProduct( t2 )).hnormalized(), (v0.transpose().homogeneous()*t2).hnormalized() );\n  VERIFY_IS_APPROX( (pts.transpose().rowwise().homogeneous() .lazyProduct( t2 )).rowwise().hnormalized(), (pts1.transpose()*t2).rowwise().hnormalized() );\n\n  VERIFY_IS_APPROX( (t2.template triangularView<Lower>() * v0.homogeneous()).eval(), (t2.template triangularView<Lower>()*hv0) );\n}\n\nEIGEN_DECLARE_TEST(geo_homogeneous)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(( homogeneous<float,1>() ));\n    CALL_SUBTEST_2(( homogeneous<double,3>() ));\n    CALL_SUBTEST_3(( homogeneous<double,8>() ));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/geo_hyperplane.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/Geometry>\n#include <Eigen/LU>\n#include <Eigen/QR>\n\ntemplate<typename HyperplaneType> void hyperplane(const HyperplaneType& _plane)\n{\n  /* this test covers the following files:\n     Hyperplane.h\n  */\n  using std::abs;\n  const Index dim = _plane.dim();\n  enum { Options = HyperplaneType::Options };\n  typedef typename HyperplaneType::Scalar Scalar;\n  typedef typename HyperplaneType::RealScalar RealScalar;\n  typedef Matrix<Scalar, HyperplaneType::AmbientDimAtCompileTime, 1> VectorType;\n  typedef Matrix<Scalar, HyperplaneType::AmbientDimAtCompileTime,\n                         HyperplaneType::AmbientDimAtCompileTime> MatrixType;\n\n  VectorType p0 = VectorType::Random(dim);\n  VectorType p1 = VectorType::Random(dim);\n\n  VectorType n0 = VectorType::Random(dim).normalized();\n  VectorType n1 = VectorType::Random(dim).normalized();\n\n  HyperplaneType pl0(n0, p0);\n  HyperplaneType pl1(n1, p1);\n  HyperplaneType pl2 = pl1;\n\n  Scalar s0 = internal::random<Scalar>();\n  Scalar s1 = internal::random<Scalar>();\n\n  VERIFY_IS_APPROX( n1.dot(n1), Scalar(1) );\n\n  VERIFY_IS_MUCH_SMALLER_THAN( pl0.absDistance(p0), Scalar(1) );\n  if(numext::abs2(s0)>RealScalar(1e-6))\n    VERIFY_IS_APPROX( pl1.signedDistance(p1 + n1 * s0), s0);\n  else\n    VERIFY_IS_MUCH_SMALLER_THAN( abs(pl1.signedDistance(p1 + n1 * s0) - s0), Scalar(1) );\n  VERIFY_IS_MUCH_SMALLER_THAN( pl1.signedDistance(pl1.projection(p0)), Scalar(1) );\n  VERIFY_IS_MUCH_SMALLER_THAN( pl1.absDistance(p1 +  pl1.normal().unitOrthogonal() * s1), Scalar(1) );\n\n  // transform\n  if (!NumTraits<Scalar>::IsComplex)\n  {\n    MatrixType rot = MatrixType::Random(dim,dim).householderQr().householderQ();\n    DiagonalMatrix<Scalar,HyperplaneType::AmbientDimAtCompileTime> scaling(VectorType::Random());\n    Translation<Scalar,HyperplaneType::AmbientDimAtCompileTime> translation(VectorType::Random());\n    \n    while(scaling.diagonal().cwiseAbs().minCoeff()<RealScalar(1e-4)) scaling.diagonal() = VectorType::Random();\n\n    pl2 = pl1;\n    VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot).absDistance(rot * p1), Scalar(1) );\n    pl2 = pl1;\n    VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot,Isometry).absDistance(rot * p1), Scalar(1) );\n    pl2 = pl1;\n    VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot*scaling).absDistance((rot*scaling) * p1), Scalar(1) );\n    VERIFY_IS_APPROX( pl2.normal().norm(), RealScalar(1) );\n    pl2 = pl1;\n    VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot*scaling*translation)\n                                  .absDistance((rot*scaling*translation) * p1), Scalar(1) );\n    VERIFY_IS_APPROX( pl2.normal().norm(), RealScalar(1) );\n    pl2 = pl1;\n    VERIFY_IS_MUCH_SMALLER_THAN( pl2.transform(rot*translation,Isometry)\n                                 .absDistance((rot*translation) * p1), Scalar(1) );\n    VERIFY_IS_APPROX( pl2.normal().norm(), RealScalar(1) );\n  }\n\n  // casting\n  const int Dim = HyperplaneType::AmbientDimAtCompileTime;\n  typedef typename GetDifferentType<Scalar>::type OtherScalar;\n  Hyperplane<OtherScalar,Dim,Options> hp1f = pl1.template cast<OtherScalar>();\n  VERIFY_IS_APPROX(hp1f.template cast<Scalar>(),pl1);\n  Hyperplane<Scalar,Dim,Options> hp1d = pl1.template cast<Scalar>();\n  VERIFY_IS_APPROX(hp1d.template cast<Scalar>(),pl1);\n}\n\ntemplate<typename Scalar> void lines()\n{\n  using std::abs;\n  typedef Hyperplane<Scalar, 2> HLine;\n  typedef ParametrizedLine<Scalar, 2> PLine;\n  typedef Matrix<Scalar,2,1> Vector;\n  typedef Matrix<Scalar,3,1> CoeffsType;\n\n  for(int i = 0; i < 10; i++)\n  {\n    Vector center = Vector::Random();\n    Vector u = Vector::Random();\n    Vector v = Vector::Random();\n    Scalar a = internal::random<Scalar>();\n    while (abs(a-1) < Scalar(1e-4)) a = internal::random<Scalar>();\n    while (u.norm() < Scalar(1e-4)) u = Vector::Random();\n    while (v.norm() < Scalar(1e-4)) v = Vector::Random();\n\n    HLine line_u = HLine::Through(center + u, center + a*u);\n    HLine line_v = HLine::Through(center + v, center + a*v);\n\n    // the line equations should be normalized so that a^2+b^2=1\n    VERIFY_IS_APPROX(line_u.normal().norm(), Scalar(1));\n    VERIFY_IS_APPROX(line_v.normal().norm(), Scalar(1));\n\n    Vector result = line_u.intersection(line_v);\n\n    // the lines should intersect at the point we called \"center\"\n    if(abs(a-1) > Scalar(1e-2) && abs(v.normalized().dot(u.normalized()))<Scalar(0.9))\n      VERIFY_IS_APPROX(result, center);\n\n    // check conversions between two types of lines\n    PLine pl(line_u); // gcc 3.3 will crash if we don't name this variable.\n    HLine line_u2(pl);\n    CoeffsType converted_coeffs = line_u2.coeffs();\n    if(line_u2.normal().dot(line_u.normal())<Scalar(0))\n      converted_coeffs = -line_u2.coeffs();\n    VERIFY(line_u.coeffs().isApprox(converted_coeffs));\n  }\n}\n\ntemplate<typename Scalar> void planes()\n{\n  using std::abs;\n  typedef Hyperplane<Scalar, 3> Plane;\n  typedef Matrix<Scalar,3,1> Vector;\n\n  for(int i = 0; i < 10; i++)\n  {\n    Vector v0 = Vector::Random();\n    Vector v1(v0), v2(v0);\n    if(internal::random<double>(0,1)>0.25)\n      v1 += Vector::Random();\n    if(internal::random<double>(0,1)>0.25)\n      v2 += v1 * std::pow(internal::random<Scalar>(0,1),internal::random<int>(1,16));\n    if(internal::random<double>(0,1)>0.25)\n      v2 += Vector::Random() * std::pow(internal::random<Scalar>(0,1),internal::random<int>(1,16));\n\n    Plane p0 = Plane::Through(v0, v1, v2);\n\n    VERIFY_IS_APPROX(p0.normal().norm(), Scalar(1));\n    VERIFY_IS_MUCH_SMALLER_THAN(p0.absDistance(v0), Scalar(1));\n    VERIFY_IS_MUCH_SMALLER_THAN(p0.absDistance(v1), Scalar(1));\n    VERIFY_IS_MUCH_SMALLER_THAN(p0.absDistance(v2), Scalar(1));\n  }\n}\n\ntemplate<typename Scalar> void hyperplane_alignment()\n{\n  typedef Hyperplane<Scalar,3,AutoAlign> Plane3a;\n  typedef Hyperplane<Scalar,3,DontAlign> Plane3u;\n\n  EIGEN_ALIGN_MAX Scalar array1[4];\n  EIGEN_ALIGN_MAX Scalar array2[4];\n  EIGEN_ALIGN_MAX Scalar array3[4+1];\n  Scalar* array3u = array3+1;\n\n  Plane3a *p1 = ::new(reinterpret_cast<void*>(array1)) Plane3a;\n  Plane3u *p2 = ::new(reinterpret_cast<void*>(array2)) Plane3u;\n  Plane3u *p3 = ::new(reinterpret_cast<void*>(array3u)) Plane3u;\n  \n  p1->coeffs().setRandom();\n  *p2 = *p1;\n  *p3 = *p1;\n\n  VERIFY_IS_APPROX(p1->coeffs(), p2->coeffs());\n  VERIFY_IS_APPROX(p1->coeffs(), p3->coeffs());\n  \n  #if defined(EIGEN_VECTORIZE) && EIGEN_MAX_STATIC_ALIGN_BYTES > 0\n  if(internal::packet_traits<Scalar>::Vectorizable && internal::packet_traits<Scalar>::size<=4)\n    VERIFY_RAISES_ASSERT((::new(reinterpret_cast<void*>(array3u)) Plane3a));\n  #endif\n}\n\n\nEIGEN_DECLARE_TEST(geo_hyperplane)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( hyperplane(Hyperplane<float,2>()) );\n    CALL_SUBTEST_2( hyperplane(Hyperplane<float,3>()) );\n    CALL_SUBTEST_2( hyperplane(Hyperplane<float,3,DontAlign>()) );\n    CALL_SUBTEST_2( hyperplane_alignment<float>() );\n    CALL_SUBTEST_3( hyperplane(Hyperplane<double,4>()) );\n    CALL_SUBTEST_4( hyperplane(Hyperplane<std::complex<double>,5>()) );\n    CALL_SUBTEST_1( lines<float>() );\n    CALL_SUBTEST_3( lines<double>() );\n    CALL_SUBTEST_2( planes<float>() );\n    CALL_SUBTEST_5( planes<double>() );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/geo_orthomethods.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/Geometry>\n#include <Eigen/LU>\n#include <Eigen/SVD>\n\n/* this test covers the following files:\n   Geometry/OrthoMethods.h\n*/\n\ntemplate<typename Scalar> void orthomethods_3()\n{\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar,3,3> Matrix3;\n  typedef Matrix<Scalar,3,1> Vector3;\n\n  typedef Matrix<Scalar,4,1> Vector4;\n\n  Vector3 v0 = Vector3::Random(),\n          v1 = Vector3::Random(),\n          v2 = Vector3::Random();\n\n  // cross product\n  VERIFY_IS_MUCH_SMALLER_THAN(v1.cross(v2).dot(v1), Scalar(1));\n  VERIFY_IS_MUCH_SMALLER_THAN(v1.dot(v1.cross(v2)), Scalar(1));\n  VERIFY_IS_MUCH_SMALLER_THAN(v1.cross(v2).dot(v2), Scalar(1));\n  VERIFY_IS_MUCH_SMALLER_THAN(v2.dot(v1.cross(v2)), Scalar(1));\n  VERIFY_IS_MUCH_SMALLER_THAN(v1.cross(Vector3::Random()).dot(v1), Scalar(1));\n  Matrix3 mat3;\n  mat3 << v0.normalized(),\n         (v0.cross(v1)).normalized(),\n         (v0.cross(v1).cross(v0)).normalized();\n  VERIFY(mat3.isUnitary());\n  \n  mat3.setRandom();\n  VERIFY_IS_APPROX(v0.cross(mat3*v1), -(mat3*v1).cross(v0));\n  VERIFY_IS_APPROX(v0.cross(mat3.lazyProduct(v1)), -(mat3.lazyProduct(v1)).cross(v0));\n\n  // colwise/rowwise cross product\n  mat3.setRandom();\n  Vector3 vec3 = Vector3::Random();\n  Matrix3 mcross;\n  int i = internal::random<int>(0,2);\n  mcross = mat3.colwise().cross(vec3);\n  VERIFY_IS_APPROX(mcross.col(i), mat3.col(i).cross(vec3));\n  \n  VERIFY_IS_MUCH_SMALLER_THAN((mat3.adjoint() * mat3.colwise().cross(vec3)).diagonal().cwiseAbs().sum(), Scalar(1));\n  VERIFY_IS_MUCH_SMALLER_THAN((mat3.adjoint() * mat3.colwise().cross(Vector3::Random())).diagonal().cwiseAbs().sum(), Scalar(1));\n  \n  VERIFY_IS_MUCH_SMALLER_THAN((vec3.adjoint() * mat3.colwise().cross(vec3)).cwiseAbs().sum(), Scalar(1));\n  VERIFY_IS_MUCH_SMALLER_THAN((vec3.adjoint() * Matrix3::Random().colwise().cross(vec3)).cwiseAbs().sum(), Scalar(1));\n  \n  mcross = mat3.rowwise().cross(vec3);\n  VERIFY_IS_APPROX(mcross.row(i), mat3.row(i).cross(vec3));\n\n  // cross3\n  Vector4 v40 = Vector4::Random(),\n          v41 = Vector4::Random(),\n          v42 = Vector4::Random();\n  v40.w() = v41.w() = v42.w() = 0;\n  v42.template head<3>() = v40.template head<3>().cross(v41.template head<3>());\n  VERIFY_IS_APPROX(v40.cross3(v41), v42);\n  VERIFY_IS_MUCH_SMALLER_THAN(v40.cross3(Vector4::Random()).dot(v40), Scalar(1));\n  \n  // check mixed product\n  typedef Matrix<RealScalar, 3, 1> RealVector3;\n  RealVector3 rv1 = RealVector3::Random();\n  VERIFY_IS_APPROX(v1.cross(rv1.template cast<Scalar>()), v1.cross(rv1));\n  VERIFY_IS_APPROX(rv1.template cast<Scalar>().cross(v1), rv1.cross(v1));\n}\n\ntemplate<typename Scalar, int Size> void orthomethods(int size=Size)\n{\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar,Size,1> VectorType;\n  typedef Matrix<Scalar,3,Size> Matrix3N;\n  typedef Matrix<Scalar,Size,3> MatrixN3;\n  typedef Matrix<Scalar,3,1> Vector3;\n\n  VectorType v0 = VectorType::Random(size);\n\n  // unitOrthogonal\n  VERIFY_IS_MUCH_SMALLER_THAN(v0.unitOrthogonal().dot(v0), Scalar(1));\n  VERIFY_IS_APPROX(v0.unitOrthogonal().norm(), RealScalar(1));\n\n  if (size>=3)\n  {\n    v0.template head<2>().setZero();\n    v0.tail(size-2).setRandom();\n\n    VERIFY_IS_MUCH_SMALLER_THAN(v0.unitOrthogonal().dot(v0), Scalar(1));\n    VERIFY_IS_APPROX(v0.unitOrthogonal().norm(), RealScalar(1));\n  }\n\n  // colwise/rowwise cross product\n  Vector3 vec3 = Vector3::Random();\n  int i = internal::random<int>(0,size-1);\n\n  Matrix3N mat3N(3,size), mcross3N(3,size);\n  mat3N.setRandom();\n  mcross3N = mat3N.colwise().cross(vec3);\n  VERIFY_IS_APPROX(mcross3N.col(i), mat3N.col(i).cross(vec3));\n\n  MatrixN3 matN3(size,3), mcrossN3(size,3);\n  matN3.setRandom();\n  mcrossN3 = matN3.rowwise().cross(vec3);\n  VERIFY_IS_APPROX(mcrossN3.row(i), matN3.row(i).cross(vec3));\n}\n\nEIGEN_DECLARE_TEST(geo_orthomethods)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( orthomethods_3<float>() );\n    CALL_SUBTEST_2( orthomethods_3<double>() );\n    CALL_SUBTEST_4( orthomethods_3<std::complex<double> >() );\n    CALL_SUBTEST_1( (orthomethods<float,2>()) );\n    CALL_SUBTEST_2( (orthomethods<double,2>()) );\n    CALL_SUBTEST_1( (orthomethods<float,3>()) );\n    CALL_SUBTEST_2( (orthomethods<double,3>()) );\n    CALL_SUBTEST_3( (orthomethods<float,7>()) );\n    CALL_SUBTEST_4( (orthomethods<std::complex<double>,8>()) );\n    CALL_SUBTEST_5( (orthomethods<float,Dynamic>(36)) );\n    CALL_SUBTEST_6( (orthomethods<double,Dynamic>(35)) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/geo_parametrizedline.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/Geometry>\n#include <Eigen/LU>\n#include <Eigen/QR>\n\ntemplate<typename LineType> void parametrizedline(const LineType& _line)\n{\n  /* this test covers the following files:\n     ParametrizedLine.h\n  */\n  using std::abs;\n  const Index dim = _line.dim();\n  typedef typename LineType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar, LineType::AmbientDimAtCompileTime, 1> VectorType;\n  typedef Hyperplane<Scalar,LineType::AmbientDimAtCompileTime> HyperplaneType;\n  typedef Matrix<Scalar, HyperplaneType::AmbientDimAtCompileTime,\n                         HyperplaneType::AmbientDimAtCompileTime> MatrixType;\n\n  VectorType p0 = VectorType::Random(dim);\n  VectorType p1 = VectorType::Random(dim);\n\n  VectorType d0 = VectorType::Random(dim).normalized();\n\n  LineType l0(p0, d0);\n\n  Scalar s0 = internal::random<Scalar>();\n  Scalar s1 = abs(internal::random<Scalar>());\n\n  VERIFY_IS_MUCH_SMALLER_THAN( l0.distance(p0), RealScalar(1) );\n  VERIFY_IS_MUCH_SMALLER_THAN( l0.distance(p0+s0*d0), RealScalar(1) );\n  VERIFY_IS_APPROX( (l0.projection(p1)-p1).norm(), l0.distance(p1) );\n  VERIFY_IS_MUCH_SMALLER_THAN( l0.distance(l0.projection(p1)), RealScalar(1) );\n  VERIFY_IS_APPROX( Scalar(l0.distance((p0+s0*d0) + d0.unitOrthogonal() * s1)), s1 );\n\n  // casting\n  const int Dim = LineType::AmbientDimAtCompileTime;\n  typedef typename GetDifferentType<Scalar>::type OtherScalar;\n  ParametrizedLine<OtherScalar,Dim> hp1f = l0.template cast<OtherScalar>();\n  VERIFY_IS_APPROX(hp1f.template cast<Scalar>(),l0);\n  ParametrizedLine<Scalar,Dim> hp1d = l0.template cast<Scalar>();\n  VERIFY_IS_APPROX(hp1d.template cast<Scalar>(),l0);\n\n  // intersections\n  VectorType p2 = VectorType::Random(dim);\n  VectorType n2 = VectorType::Random(dim).normalized();\n  HyperplaneType hp(p2,n2);\n  Scalar t = l0.intersectionParameter(hp);\n  VectorType pi = l0.pointAt(t);\n  VERIFY_IS_MUCH_SMALLER_THAN(hp.signedDistance(pi), RealScalar(1));\n  VERIFY_IS_MUCH_SMALLER_THAN(l0.distance(pi), RealScalar(1));\n  VERIFY_IS_APPROX(l0.intersectionPoint(hp), pi);\n\n  // transform\n  if (!NumTraits<Scalar>::IsComplex)\n  {\n    MatrixType rot = MatrixType::Random(dim,dim).householderQr().householderQ();\n    DiagonalMatrix<Scalar,LineType::AmbientDimAtCompileTime> scaling(VectorType::Random());\n    Translation<Scalar,LineType::AmbientDimAtCompileTime> translation(VectorType::Random());\n\n    while(scaling.diagonal().cwiseAbs().minCoeff()<RealScalar(1e-4)) scaling.diagonal() = VectorType::Random();\n\n    LineType l1 = l0;\n    VectorType p3 = l0.pointAt(Scalar(1));\n    VERIFY_IS_MUCH_SMALLER_THAN( l1.transform(rot).distance(rot * p3), Scalar(1) );\n    l1 = l0;\n    VERIFY_IS_MUCH_SMALLER_THAN( l1.transform(rot,Isometry).distance(rot * p3), Scalar(1) );\n    l1 = l0;\n    VERIFY_IS_MUCH_SMALLER_THAN( l1.transform(rot*scaling).distance((rot*scaling) * p3), Scalar(1) );\n    l1 = l0;\n    VERIFY_IS_MUCH_SMALLER_THAN( l1.transform(rot*scaling*translation)\n                                   .distance((rot*scaling*translation) * p3), Scalar(1) );\n    l1 = l0;\n    VERIFY_IS_MUCH_SMALLER_THAN( l1.transform(rot*translation,Isometry)\n                                   .distance((rot*translation) * p3), Scalar(1) );\n  }\n\n}\n\ntemplate<typename Scalar> void parametrizedline_alignment()\n{\n  typedef ParametrizedLine<Scalar,4,AutoAlign> Line4a;\n  typedef ParametrizedLine<Scalar,4,DontAlign> Line4u;\n\n  EIGEN_ALIGN_MAX Scalar array1[16];\n  EIGEN_ALIGN_MAX Scalar array2[16];\n  EIGEN_ALIGN_MAX Scalar array3[16+1];\n  Scalar* array3u = array3+1;\n\n  Line4a *p1 = ::new(reinterpret_cast<void*>(array1)) Line4a;\n  Line4u *p2 = ::new(reinterpret_cast<void*>(array2)) Line4u;\n  Line4u *p3 = ::new(reinterpret_cast<void*>(array3u)) Line4u;\n  \n  p1->origin().setRandom();\n  p1->direction().setRandom();\n  *p2 = *p1;\n  *p3 = *p1;\n\n  VERIFY_IS_APPROX(p1->origin(), p2->origin());\n  VERIFY_IS_APPROX(p1->origin(), p3->origin());\n  VERIFY_IS_APPROX(p1->direction(), p2->direction());\n  VERIFY_IS_APPROX(p1->direction(), p3->direction());\n  \n  #if defined(EIGEN_VECTORIZE) && EIGEN_MAX_STATIC_ALIGN_BYTES>0\n  if(internal::packet_traits<Scalar>::Vectorizable && internal::packet_traits<Scalar>::size<=4)\n    VERIFY_RAISES_ASSERT((::new(reinterpret_cast<void*>(array3u)) Line4a));\n  #endif\n}\n\nEIGEN_DECLARE_TEST(geo_parametrizedline)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( parametrizedline(ParametrizedLine<float,2>()) );\n    CALL_SUBTEST_2( parametrizedline(ParametrizedLine<float,3>()) );\n    CALL_SUBTEST_2( parametrizedline_alignment<float>() );\n    CALL_SUBTEST_3( parametrizedline(ParametrizedLine<double,4>()) );\n    CALL_SUBTEST_3( parametrizedline_alignment<double>() );\n    CALL_SUBTEST_4( parametrizedline(ParametrizedLine<std::complex<double>,5>()) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/geo_quaternion.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Mathieu Gautier <mathieu.gautier@cea.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/Geometry>\n#include <Eigen/LU>\n#include <Eigen/SVD>\n#include \"AnnoyingScalar.h\"\n\ntemplate<typename T> T bounded_acos(T v)\n{\n  using std::acos;\n  using std::min;\n  using std::max;\n  return acos((max)(T(-1),(min)(v,T(1))));\n}\n\ntemplate<typename QuatType> void check_slerp(const QuatType& q0, const QuatType& q1)\n{\n  using std::abs;\n  typedef typename QuatType::Scalar Scalar;\n  typedef AngleAxis<Scalar> AA;\n\n  Scalar largeEps = test_precision<Scalar>();\n\n  Scalar theta_tot = AA(q1*q0.inverse()).angle();\n  if(theta_tot>Scalar(EIGEN_PI))\n    theta_tot = Scalar(2.)*Scalar(EIGEN_PI)-theta_tot;\n  for(Scalar t=0; t<=Scalar(1.001); t+=Scalar(0.1))\n  {\n    QuatType q = q0.slerp(t,q1);\n    Scalar theta = AA(q*q0.inverse()).angle();\n    VERIFY(abs(q.norm() - 1) < largeEps);\n    if(theta_tot==0)  VERIFY(theta_tot==0);\n    else              VERIFY(abs(theta - t * theta_tot) < largeEps);\n  }\n}\n\ntemplate<typename Scalar, int Options> void quaternion(void)\n{\n  /* this test covers the following files:\n     Quaternion.h\n  */\n  using std::abs;\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef Matrix<Scalar,3,3> Matrix3;\n  typedef Quaternion<Scalar,Options> Quaternionx;\n  typedef AngleAxis<Scalar> AngleAxisx;\n\n  Scalar largeEps = test_precision<Scalar>();\n  if (internal::is_same<Scalar,float>::value)\n    largeEps = Scalar(1e-3);\n\n  Scalar eps = internal::random<Scalar>() * Scalar(1e-2);\n\n  Vector3 v0 = Vector3::Random(),\n          v1 = Vector3::Random(),\n          v2 = Vector3::Random(),\n          v3 = Vector3::Random();\n\n  Scalar  a = internal::random<Scalar>(-Scalar(EIGEN_PI), Scalar(EIGEN_PI)),\n          b = internal::random<Scalar>(-Scalar(EIGEN_PI), Scalar(EIGEN_PI));\n\n  // Quaternion: Identity(), setIdentity();\n  Quaternionx q1, q2;\n  q2.setIdentity();\n  VERIFY_IS_APPROX(Quaternionx(Quaternionx::Identity()).coeffs(), q2.coeffs());\n  q1.coeffs().setRandom();\n  VERIFY_IS_APPROX(q1.coeffs(), (q1*q2).coeffs());\n\n#ifndef EIGEN_NO_IO\n  // Printing\n  std::ostringstream ss;\n  ss << q2;\n  VERIFY(ss.str() == \"0i + 0j + 0k + 1\");\n#endif\n\n  // concatenation\n  q1 *= q2;\n\n  q1 = AngleAxisx(a, v0.normalized());\n  q2 = AngleAxisx(a, v1.normalized());\n\n  // angular distance\n  Scalar refangle = abs(AngleAxisx(q1.inverse()*q2).angle());\n  if (refangle>Scalar(EIGEN_PI))\n    refangle = Scalar(2)*Scalar(EIGEN_PI) - refangle;\n\n  if((q1.coeffs()-q2.coeffs()).norm() > Scalar(10)*largeEps)\n  {\n    VERIFY_IS_MUCH_SMALLER_THAN(abs(q1.angularDistance(q2) - refangle), Scalar(1));\n  }\n\n  // rotation matrix conversion\n  VERIFY_IS_APPROX(q1 * v2, q1.toRotationMatrix() * v2);\n  VERIFY_IS_APPROX(q1 * q2 * v2,\n    q1.toRotationMatrix() * q2.toRotationMatrix() * v2);\n\n  VERIFY(  (q2*q1).isApprox(q1*q2, largeEps)\n        || !(q2 * q1 * v2).isApprox(q1.toRotationMatrix() * q2.toRotationMatrix() * v2));\n\n  q2 = q1.toRotationMatrix();\n  VERIFY_IS_APPROX(q1*v1,q2*v1);\n\n  Matrix3 rot1(q1);\n  VERIFY_IS_APPROX(q1*v1,rot1*v1);\n  Quaternionx q3(rot1.transpose()*rot1);\n  VERIFY_IS_APPROX(q3*v1,v1);\n\n\n  // angle-axis conversion\n  AngleAxisx aa = AngleAxisx(q1);\n  VERIFY_IS_APPROX(q1 * v1, Quaternionx(aa) * v1);\n\n  // Do not execute the test if the rotation angle is almost zero, or\n  // the rotation axis and v1 are almost parallel.\n  if (abs(aa.angle()) > Scalar(5)*test_precision<Scalar>()\n      && (aa.axis() - v1.normalized()).norm() < Scalar(1.99)\n      && (aa.axis() + v1.normalized()).norm() < Scalar(1.99))\n  {\n    VERIFY_IS_NOT_APPROX(q1 * v1, Quaternionx(AngleAxisx(aa.angle()*2,aa.axis())) * v1);\n  }\n\n  // from two vector creation\n  VERIFY_IS_APPROX( v2.normalized(),(q2.setFromTwoVectors(v1, v2)*v1).normalized());\n  VERIFY_IS_APPROX( v1.normalized(),(q2.setFromTwoVectors(v1, v1)*v1).normalized());\n  VERIFY_IS_APPROX(-v1.normalized(),(q2.setFromTwoVectors(v1,-v1)*v1).normalized());\n  if (internal::is_same<Scalar,double>::value)\n  {\n    v3 = (v1.array()+eps).matrix();\n    VERIFY_IS_APPROX( v3.normalized(),(q2.setFromTwoVectors(v1, v3)*v1).normalized());\n    VERIFY_IS_APPROX(-v3.normalized(),(q2.setFromTwoVectors(v1,-v3)*v1).normalized());\n  }\n\n  // from two vector creation static function\n  VERIFY_IS_APPROX( v2.normalized(),(Quaternionx::FromTwoVectors(v1, v2)*v1).normalized());\n  VERIFY_IS_APPROX( v1.normalized(),(Quaternionx::FromTwoVectors(v1, v1)*v1).normalized());\n  VERIFY_IS_APPROX(-v1.normalized(),(Quaternionx::FromTwoVectors(v1,-v1)*v1).normalized());\n  if (internal::is_same<Scalar,double>::value)\n  {\n    v3 = (v1.array()+eps).matrix();\n    VERIFY_IS_APPROX( v3.normalized(),(Quaternionx::FromTwoVectors(v1, v3)*v1).normalized());\n    VERIFY_IS_APPROX(-v3.normalized(),(Quaternionx::FromTwoVectors(v1,-v3)*v1).normalized());\n  }\n\n  // inverse and conjugate\n  VERIFY_IS_APPROX(q1 * (q1.inverse() * v1), v1);\n  VERIFY_IS_APPROX(q1 * (q1.conjugate() * v1), v1);\n\n  // test casting\n  Quaternion<float> q1f = q1.template cast<float>();\n  VERIFY_IS_APPROX(q1f.template cast<Scalar>(),q1);\n  Quaternion<double> q1d = q1.template cast<double>();\n  VERIFY_IS_APPROX(q1d.template cast<Scalar>(),q1);\n\n  // test bug 369 - improper alignment.\n  Quaternionx *q = new Quaternionx;\n  delete q;\n\n  q1 = Quaternionx::UnitRandom();\n  q2 = Quaternionx::UnitRandom();\n  check_slerp(q1,q2);\n\n  q1 = AngleAxisx(b, v1.normalized());\n  q2 = AngleAxisx(b+Scalar(EIGEN_PI), v1.normalized());\n  check_slerp(q1,q2);\n\n  q1 = AngleAxisx(b,  v1.normalized());\n  q2 = AngleAxisx(-b, -v1.normalized());\n  check_slerp(q1,q2);\n\n  q1 = Quaternionx::UnitRandom();\n  q2.coeffs() = -q1.coeffs();\n  check_slerp(q1,q2);\n}\n\ntemplate<typename Scalar> void mapQuaternion(void){\n  typedef Map<Quaternion<Scalar>, Aligned> MQuaternionA;\n  typedef Map<const Quaternion<Scalar>, Aligned> MCQuaternionA;\n  typedef Map<Quaternion<Scalar> > MQuaternionUA;\n  typedef Map<const Quaternion<Scalar> > MCQuaternionUA;\n  typedef Quaternion<Scalar> Quaternionx;\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef AngleAxis<Scalar> AngleAxisx;\n  \n  Vector3 v0 = Vector3::Random(),\n          v1 = Vector3::Random();\n  Scalar  a = internal::random<Scalar>(-Scalar(EIGEN_PI), Scalar(EIGEN_PI));\n\n  EIGEN_ALIGN_MAX Scalar array1[4];\n  EIGEN_ALIGN_MAX Scalar array2[4];\n  EIGEN_ALIGN_MAX Scalar array3[4+1];\n  Scalar* array3unaligned = array3+1;\n  \n  MQuaternionA    mq1(array1);\n  MCQuaternionA   mcq1(array1);\n  MQuaternionA    mq2(array2);\n  MQuaternionUA   mq3(array3unaligned);\n  MCQuaternionUA  mcq3(array3unaligned);\n\n//  std::cerr << array1 << \" \" << array2 << \" \" << array3 << \"\\n\";\n  mq1 = AngleAxisx(a, v0.normalized());\n  mq2 = mq1;\n  mq3 = mq1;\n\n  Quaternionx q1 = mq1;\n  Quaternionx q2 = mq2;\n  Quaternionx q3 = mq3;\n  Quaternionx q4 = MCQuaternionUA(array3unaligned);\n\n  VERIFY_IS_APPROX(q1.coeffs(), q2.coeffs());\n  VERIFY_IS_APPROX(q1.coeffs(), q3.coeffs());\n  VERIFY_IS_APPROX(q4.coeffs(), q3.coeffs());\n  #ifdef EIGEN_VECTORIZE\n  if(internal::packet_traits<Scalar>::Vectorizable)\n    VERIFY_RAISES_ASSERT((MQuaternionA(array3unaligned)));\n  #endif\n    \n  VERIFY_IS_APPROX(mq1 * (mq1.inverse() * v1), v1);\n  VERIFY_IS_APPROX(mq1 * (mq1.conjugate() * v1), v1);\n  \n  VERIFY_IS_APPROX(mcq1 * (mcq1.inverse() * v1), v1);\n  VERIFY_IS_APPROX(mcq1 * (mcq1.conjugate() * v1), v1);\n  \n  VERIFY_IS_APPROX(mq3 * (mq3.inverse() * v1), v1);\n  VERIFY_IS_APPROX(mq3 * (mq3.conjugate() * v1), v1);\n  \n  VERIFY_IS_APPROX(mcq3 * (mcq3.inverse() * v1), v1);\n  VERIFY_IS_APPROX(mcq3 * (mcq3.conjugate() * v1), v1);\n  \n  VERIFY_IS_APPROX(mq1*mq2, q1*q2);\n  VERIFY_IS_APPROX(mq3*mq2, q3*q2);\n  VERIFY_IS_APPROX(mcq1*mq2, q1*q2);\n  VERIFY_IS_APPROX(mcq3*mq2, q3*q2);\n\n  // Bug 1461, compilation issue with Map<const Quat>::w(), and other reference/constness checks:\n  VERIFY_IS_APPROX(mcq3.coeffs().x() + mcq3.coeffs().y() + mcq3.coeffs().z() + mcq3.coeffs().w(), mcq3.coeffs().sum());\n  VERIFY_IS_APPROX(mcq3.x() + mcq3.y() + mcq3.z() + mcq3.w(), mcq3.coeffs().sum());\n  mq3.w() = 1;\n  const Quaternionx& cq3(q3);\n  VERIFY( &cq3.x() == &q3.x() );\n  const MQuaternionUA& cmq3(mq3);\n  VERIFY( &cmq3.x() == &mq3.x() );\n  // FIXME the following should be ok. The problem is that currently the LValueBit flag\n  // is used to determine whether we can return a coeff by reference or not, which is not enough for Map<const ...>.\n  //const MCQuaternionUA& cmcq3(mcq3);\n  //VERIFY( &cmcq3.x() == &mcq3.x() );\n\n  // test cast\n  {\n    Quaternion<float> q1f = mq1.template cast<float>();\n    VERIFY_IS_APPROX(q1f.template cast<Scalar>(),mq1);\n    Quaternion<double> q1d = mq1.template cast<double>();\n    VERIFY_IS_APPROX(q1d.template cast<Scalar>(),mq1);\n  }\n}\n\ntemplate<typename Scalar> void quaternionAlignment(void){\n  typedef Quaternion<Scalar,AutoAlign> QuaternionA;\n  typedef Quaternion<Scalar,DontAlign> QuaternionUA;\n\n  EIGEN_ALIGN_MAX Scalar array1[4];\n  EIGEN_ALIGN_MAX Scalar array2[4];\n  EIGEN_ALIGN_MAX Scalar array3[4+1];\n  Scalar* arrayunaligned = array3+1;\n\n  QuaternionA *q1 = ::new(reinterpret_cast<void*>(array1)) QuaternionA;\n  QuaternionUA *q2 = ::new(reinterpret_cast<void*>(array2)) QuaternionUA;\n  QuaternionUA *q3 = ::new(reinterpret_cast<void*>(arrayunaligned)) QuaternionUA;\n\n  q1->coeffs().setRandom();\n  *q2 = *q1;\n  *q3 = *q1;\n\n  VERIFY_IS_APPROX(q1->coeffs(), q2->coeffs());\n  VERIFY_IS_APPROX(q1->coeffs(), q3->coeffs());\n  #if defined(EIGEN_VECTORIZE) && EIGEN_MAX_STATIC_ALIGN_BYTES>0\n  if(internal::packet_traits<Scalar>::Vectorizable && internal::packet_traits<Scalar>::size<=4)\n    VERIFY_RAISES_ASSERT((::new(reinterpret_cast<void*>(arrayunaligned)) QuaternionA));\n  #endif\n}\n\ntemplate<typename PlainObjectType> void check_const_correctness(const PlainObjectType&)\n{\n  // there's a lot that we can't test here while still having this test compile!\n  // the only possible approach would be to run a script trying to compile stuff and checking that it fails.\n  // CMake can help with that.\n\n  // verify that map-to-const don't have LvalueBit\n  typedef typename internal::add_const<PlainObjectType>::type ConstPlainObjectType;\n  VERIFY( !(internal::traits<Map<ConstPlainObjectType> >::Flags & LvalueBit) );\n  VERIFY( !(internal::traits<Map<ConstPlainObjectType, Aligned> >::Flags & LvalueBit) );\n  VERIFY( !(Map<ConstPlainObjectType>::Flags & LvalueBit) );\n  VERIFY( !(Map<ConstPlainObjectType, Aligned>::Flags & LvalueBit) );\n}\n\n#if EIGEN_HAS_RVALUE_REFERENCES\n\n// Regression for bug 1573\nstruct MovableClass {\n  // The following line is a workaround for gcc 4.7 and 4.8 (see bug 1573 comments).\n  static_assert(std::is_nothrow_move_constructible<Quaternionf>::value,\"\");\n  MovableClass() = default;\n  MovableClass(const MovableClass&) = default;\n  MovableClass(MovableClass&&) noexcept = default;\n  MovableClass& operator=(const MovableClass&) = default;\n  MovableClass& operator=(MovableClass&&) = default;\n  Quaternionf m_quat;\n};\n\n#endif\n\nEIGEN_DECLARE_TEST(geo_quaternion)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(( quaternion<float,AutoAlign>() ));\n    CALL_SUBTEST_1( check_const_correctness(Quaternionf()) );\n    CALL_SUBTEST_1(( quaternion<float,DontAlign>() ));\n    CALL_SUBTEST_1(( quaternionAlignment<float>() ));\n    CALL_SUBTEST_1( mapQuaternion<float>() );\n\n    CALL_SUBTEST_2(( quaternion<double,AutoAlign>() ));\n    CALL_SUBTEST_2( check_const_correctness(Quaterniond()) );\n    CALL_SUBTEST_2(( quaternion<double,DontAlign>() ));\n    CALL_SUBTEST_2(( quaternionAlignment<double>() ));\n    CALL_SUBTEST_2( mapQuaternion<double>() );\n\n    AnnoyingScalar::dont_throw = true;\n    CALL_SUBTEST_3(( quaternion<AnnoyingScalar,AutoAlign>() ));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/geo_transformations.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/Geometry>\n#include <Eigen/LU>\n#include <Eigen/SVD>\n\ntemplate<typename T>\nMatrix<T,2,1> angleToVec(T a)\n{\n  return Matrix<T,2,1>(std::cos(a), std::sin(a));\n}\n\n// This permits to workaround a bug in clang/llvm code generation.\ntemplate<typename T>\nEIGEN_DONT_INLINE\nvoid dont_over_optimize(T& x) { volatile typename T::Scalar tmp = x(0); x(0) = tmp; }\n\ntemplate<typename Scalar, int Mode, int Options> void non_projective_only()\n{\n    /* this test covers the following files:\n     Cross.h Quaternion.h, Transform.cpp\n  */\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef Quaternion<Scalar> Quaternionx;\n  typedef AngleAxis<Scalar> AngleAxisx;\n  typedef Transform<Scalar,3,Mode,Options> Transform3;\n  typedef DiagonalMatrix<Scalar,3> AlignedScaling3;\n  typedef Translation<Scalar,3> Translation3;\n\n  Vector3 v0 = Vector3::Random(),\n          v1 = Vector3::Random();\n\n  Transform3 t0, t1, t2;\n\n  Scalar a = internal::random<Scalar>(-Scalar(EIGEN_PI), Scalar(EIGEN_PI));\n\n  Quaternionx q1, q2;\n\n  q1 = AngleAxisx(a, v0.normalized());\n\n  t0 = Transform3::Identity();\n  VERIFY_IS_APPROX(t0.matrix(), Transform3::MatrixType::Identity());\n\n  t0.linear() = q1.toRotationMatrix();\n\n  v0 << 50, 2, 1;\n  t0.scale(v0);\n\n  VERIFY_IS_APPROX( (t0 * Vector3(1,0,0)).template head<3>().norm(), v0.x());\n\n  t0.setIdentity();\n  t1.setIdentity();\n  v1 << 1, 2, 3;\n  t0.linear() = q1.toRotationMatrix();\n  t0.pretranslate(v0);\n  t0.scale(v1);\n  t1.linear() = q1.conjugate().toRotationMatrix();\n  t1.prescale(v1.cwiseInverse());\n  t1.translate(-v0);\n\n  VERIFY((t0 * t1).matrix().isIdentity(test_precision<Scalar>()));\n\n  t1.fromPositionOrientationScale(v0, q1, v1);\n  VERIFY_IS_APPROX(t1.matrix(), t0.matrix());\n  VERIFY_IS_APPROX(t1*v1, t0*v1);\n\n  // translation * vector\n  t0.setIdentity();\n  t0.translate(v0);\n  VERIFY_IS_APPROX((t0 * v1).template head<3>(), Translation3(v0) * v1);\n\n  // AlignedScaling * vector\n  t0.setIdentity();\n  t0.scale(v0);\n  VERIFY_IS_APPROX((t0 * v1).template head<3>(), AlignedScaling3(v0) * v1);\n}\n\ntemplate<typename Scalar, int Mode, int Options> void transformations()\n{\n  /* this test covers the following files:\n     Cross.h Quaternion.h, Transform.cpp\n  */\n  using std::cos;\n  using std::abs;\n  typedef Matrix<Scalar,3,3> Matrix3;\n  typedef Matrix<Scalar,4,4> Matrix4;\n  typedef Matrix<Scalar,2,1> Vector2;\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef Matrix<Scalar,4,1> Vector4;\n  typedef Quaternion<Scalar> Quaternionx;\n  typedef AngleAxis<Scalar> AngleAxisx;\n  typedef Transform<Scalar,2,Mode,Options> Transform2;\n  typedef Transform<Scalar,3,Mode,Options> Transform3;\n  typedef typename Transform3::MatrixType MatrixType;\n  typedef DiagonalMatrix<Scalar,3> AlignedScaling3;\n  typedef Translation<Scalar,2> Translation2;\n  typedef Translation<Scalar,3> Translation3;\n\n  Vector3 v0 = Vector3::Random(),\n          v1 = Vector3::Random();\n  Matrix3 matrot1, m;\n\n  Scalar a = internal::random<Scalar>(-Scalar(EIGEN_PI), Scalar(EIGEN_PI));\n  Scalar s0 = internal::random<Scalar>(), s1 = internal::random<Scalar>();\n  \n  while(v0.norm() < test_precision<Scalar>()) v0 = Vector3::Random();\n  while(v1.norm() < test_precision<Scalar>()) v1 = Vector3::Random();\n\n  VERIFY_IS_APPROX(v0, AngleAxisx(a, v0.normalized()) * v0);\n  VERIFY_IS_APPROX(-v0, AngleAxisx(Scalar(EIGEN_PI), v0.unitOrthogonal()) * v0);\n  if(abs(cos(a)) > test_precision<Scalar>())\n  {\n    VERIFY_IS_APPROX(cos(a)*v0.squaredNorm(), v0.dot(AngleAxisx(a, v0.unitOrthogonal()) * v0));\n  }\n  m = AngleAxisx(a, v0.normalized()).toRotationMatrix().adjoint();\n  VERIFY_IS_APPROX(Matrix3::Identity(), m * AngleAxisx(a, v0.normalized()));\n  VERIFY_IS_APPROX(Matrix3::Identity(), AngleAxisx(a, v0.normalized()) * m);\n\n  Quaternionx q1, q2;\n  q1 = AngleAxisx(a, v0.normalized());\n  q2 = AngleAxisx(a, v1.normalized());\n\n  // rotation matrix conversion\n  matrot1 = AngleAxisx(Scalar(0.1), Vector3::UnitX())\n          * AngleAxisx(Scalar(0.2), Vector3::UnitY())\n          * AngleAxisx(Scalar(0.3), Vector3::UnitZ());\n  VERIFY_IS_APPROX(matrot1 * v1,\n       AngleAxisx(Scalar(0.1), Vector3(1,0,0)).toRotationMatrix()\n    * (AngleAxisx(Scalar(0.2), Vector3(0,1,0)).toRotationMatrix()\n    * (AngleAxisx(Scalar(0.3), Vector3(0,0,1)).toRotationMatrix() * v1)));\n\n  // angle-axis conversion\n  AngleAxisx aa = AngleAxisx(q1);\n  VERIFY_IS_APPROX(q1 * v1, Quaternionx(aa) * v1);\n  \n  // The following test is stable only if 2*angle != angle and v1 is not colinear with axis\n  if( (abs(aa.angle()) > test_precision<Scalar>()) && (abs(aa.axis().dot(v1.normalized()))<(Scalar(1)-Scalar(4)*test_precision<Scalar>())) )\n  {\n    VERIFY( !(q1 * v1).isApprox(Quaternionx(AngleAxisx(aa.angle()*2,aa.axis())) * v1) );\n  }\n\n  aa.fromRotationMatrix(aa.toRotationMatrix());\n  VERIFY_IS_APPROX(q1 * v1, Quaternionx(aa) * v1);\n  // The following test is stable only if 2*angle != angle and v1 is not colinear with axis\n  if( (abs(aa.angle()) > test_precision<Scalar>()) && (abs(aa.axis().dot(v1.normalized()))<(Scalar(1)-Scalar(4)*test_precision<Scalar>())) )\n  {\n    VERIFY( !(q1 * v1).isApprox(Quaternionx(AngleAxisx(aa.angle()*2,aa.axis())) * v1) );\n  }\n\n  // AngleAxis\n  VERIFY_IS_APPROX(AngleAxisx(a,v1.normalized()).toRotationMatrix(),\n    Quaternionx(AngleAxisx(a,v1.normalized())).toRotationMatrix());\n\n  AngleAxisx aa1;\n  m = q1.toRotationMatrix();\n  aa1 = m;\n  VERIFY_IS_APPROX(AngleAxisx(m).toRotationMatrix(),\n    Quaternionx(m).toRotationMatrix());\n\n  // Transform\n  // TODO complete the tests !\n  a = 0;\n  while (abs(a)<Scalar(0.1))\n    a = internal::random<Scalar>(-Scalar(0.4)*Scalar(EIGEN_PI), Scalar(0.4)*Scalar(EIGEN_PI));\n  q1 = AngleAxisx(a, v0.normalized());\n  Transform3 t0, t1, t2;\n\n  // first test setIdentity() and Identity()\n  t0.setIdentity();\n  VERIFY_IS_APPROX(t0.matrix(), Transform3::MatrixType::Identity());\n  t0.matrix().setZero();\n  t0 = Transform3::Identity();\n  VERIFY_IS_APPROX(t0.matrix(), Transform3::MatrixType::Identity());\n\n  t0.setIdentity();\n  t1.setIdentity();\n  v1 << 1, 2, 3;\n  t0.linear() = q1.toRotationMatrix();\n  t0.pretranslate(v0);\n  t0.scale(v1);\n  t1.linear() = q1.conjugate().toRotationMatrix();\n  t1.prescale(v1.cwiseInverse());\n  t1.translate(-v0);\n\n  VERIFY((t0 * t1).matrix().isIdentity(test_precision<Scalar>()));\n\n  t1.fromPositionOrientationScale(v0, q1, v1);\n  VERIFY_IS_APPROX(t1.matrix(), t0.matrix());\n\n  t0.setIdentity(); t0.scale(v0).rotate(q1.toRotationMatrix());\n  t1.setIdentity(); t1.scale(v0).rotate(q1);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  t0.setIdentity(); t0.scale(v0).rotate(AngleAxisx(q1));\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  VERIFY_IS_APPROX(t0.scale(a).matrix(), t1.scale(Vector3::Constant(a)).matrix());\n  VERIFY_IS_APPROX(t0.prescale(a).matrix(), t1.prescale(Vector3::Constant(a)).matrix());\n\n  // More transform constructors, operator=, operator*=\n\n  Matrix3 mat3 = Matrix3::Random();\n  Matrix4 mat4;\n  mat4 << mat3 , Vector3::Zero() , Vector4::Zero().transpose();\n  Transform3 tmat3(mat3), tmat4(mat4);\n  if(Mode!=int(AffineCompact))\n    tmat4.matrix()(3,3) = Scalar(1);\n  VERIFY_IS_APPROX(tmat3.matrix(), tmat4.matrix());\n\n  Scalar a3 = internal::random<Scalar>(-Scalar(EIGEN_PI), Scalar(EIGEN_PI));\n  Vector3 v3 = Vector3::Random().normalized();\n  AngleAxisx aa3(a3, v3);\n  Transform3 t3(aa3);\n  Transform3 t4;\n  t4 = aa3;\n  VERIFY_IS_APPROX(t3.matrix(), t4.matrix());\n  t4.rotate(AngleAxisx(-a3,v3));\n  VERIFY_IS_APPROX(t4.matrix(), MatrixType::Identity());\n  t4 *= aa3;\n  VERIFY_IS_APPROX(t3.matrix(), t4.matrix());\n\n  do {\n    v3 = Vector3::Random();\n    dont_over_optimize(v3);\n  } while (v3.cwiseAbs().minCoeff()<NumTraits<Scalar>::epsilon());\n  Translation3 tv3(v3);\n  Transform3 t5(tv3);\n  t4 = tv3;\n  VERIFY_IS_APPROX(t5.matrix(), t4.matrix());\n  t4.translate((-v3).eval());\n  VERIFY_IS_APPROX(t4.matrix(), MatrixType::Identity());\n  t4 *= tv3;\n  VERIFY_IS_APPROX(t5.matrix(), t4.matrix());\n\n  AlignedScaling3 sv3(v3);\n  Transform3 t6(sv3);\n  t4 = sv3;\n  VERIFY_IS_APPROX(t6.matrix(), t4.matrix());\n  t4.scale(v3.cwiseInverse());\n  VERIFY_IS_APPROX(t4.matrix(), MatrixType::Identity());\n  t4 *= sv3;\n  VERIFY_IS_APPROX(t6.matrix(), t4.matrix());\n\n  // matrix * transform\n  VERIFY_IS_APPROX((t3.matrix()*t4).matrix(), (t3*t4).matrix());\n\n  // chained Transform product\n  VERIFY_IS_APPROX(((t3*t4)*t5).matrix(), (t3*(t4*t5)).matrix());\n\n  // check that Transform product doesn't have aliasing problems\n  t5 = t4;\n  t5 = t5*t5;\n  VERIFY_IS_APPROX(t5, t4*t4);\n\n  // 2D transformation\n  Transform2 t20, t21;\n  Vector2 v20 = Vector2::Random();\n  Vector2 v21 = Vector2::Random();\n  for (int k=0; k<2; ++k)\n    if (abs(v21[k])<Scalar(1e-3)) v21[k] = Scalar(1e-3);\n  t21.setIdentity();\n  t21.linear() = Rotation2D<Scalar>(a).toRotationMatrix();\n  VERIFY_IS_APPROX(t20.fromPositionOrientationScale(v20,a,v21).matrix(),\n    t21.pretranslate(v20).scale(v21).matrix());\n\n  t21.setIdentity();\n  t21.linear() = Rotation2D<Scalar>(-a).toRotationMatrix();\n  VERIFY( (t20.fromPositionOrientationScale(v20,a,v21)\n        * (t21.prescale(v21.cwiseInverse()).translate(-v20))).matrix().isIdentity(test_precision<Scalar>()) );\n\n  // Transform - new API\n  // 3D\n  t0.setIdentity();\n  t0.rotate(q1).scale(v0).translate(v0);\n  // mat * aligned scaling and mat * translation\n  t1 = (Matrix3(q1) * AlignedScaling3(v0)) * Translation3(v0);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  t1 = (Matrix3(q1) * Eigen::Scaling(v0)) * Translation3(v0);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  t1 = (q1 * Eigen::Scaling(v0)) * Translation3(v0);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  // mat * transformation and aligned scaling * translation\n  t1 = Matrix3(q1) * (AlignedScaling3(v0) * Translation3(v0));\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n\n  t0.setIdentity();\n  t0.scale(s0).translate(v0);\n  t1 = Eigen::Scaling(s0) * Translation3(v0);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  t0.prescale(s0);\n  t1 = Eigen::Scaling(s0) * t1;\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  \n  t0 = t3;\n  t0.scale(s0);\n  t1 = t3 * Eigen::Scaling(s0,s0,s0);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  t0.prescale(s0);\n  t1 = Eigen::Scaling(s0,s0,s0) * t1;\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  t0 = t3;\n  t0.scale(s0);\n  t1 = t3 * Eigen::Scaling(s0);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  t0.prescale(s0);\n  t1 = Eigen::Scaling(s0) * t1;\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  t0.setIdentity();\n  t0.prerotate(q1).prescale(v0).pretranslate(v0);\n  // translation * aligned scaling and transformation * mat\n  t1 = (Translation3(v0) * AlignedScaling3(v0)) * Transform3(q1);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  // scaling * mat and translation * mat\n  t1 = Translation3(v0) * (AlignedScaling3(v0) * Transform3(q1));\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  t0.setIdentity();\n  t0.scale(v0).translate(v0).rotate(q1);\n  // translation * mat and aligned scaling * transformation\n  t1 = AlignedScaling3(v0) * (Translation3(v0) * Transform3(q1));\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  // transformation * aligned scaling\n  t0.scale(v0);\n  t1 *= AlignedScaling3(v0);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  t1 = AlignedScaling3(v0) * (Translation3(v0) * Transform3(q1));\n  t1 = t1 * v0.asDiagonal();\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  // transformation * translation\n  t0.translate(v0);\n  t1 = t1 * Translation3(v0);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n  // translation * transformation\n  t0.pretranslate(v0);\n  t1 = Translation3(v0) * t1;\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  // transform * quaternion\n  t0.rotate(q1);\n  t1 = t1 * q1;\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  // translation * quaternion\n  t0.translate(v1).rotate(q1);\n  t1 = t1 * (Translation3(v1) * q1);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  // aligned scaling * quaternion\n  t0.scale(v1).rotate(q1);\n  t1 = t1 * (AlignedScaling3(v1) * q1);\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  // quaternion * transform\n  t0.prerotate(q1);\n  t1 = q1 * t1;\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  // quaternion * translation\n  t0.rotate(q1).translate(v1);\n  t1 = t1 * (q1 * Translation3(v1));\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  // quaternion * aligned scaling\n  t0.rotate(q1).scale(v1);\n  t1 = t1 * (q1 * AlignedScaling3(v1));\n  VERIFY_IS_APPROX(t0.matrix(), t1.matrix());\n\n  // test transform inversion\n  t0.setIdentity();\n  t0.translate(v0);\n  do {\n    t0.linear().setRandom();\n  } while(t0.linear().jacobiSvd().singularValues()(2)<test_precision<Scalar>());\n  Matrix4 t044 = Matrix4::Zero();\n  t044(3,3) = 1;\n  t044.block(0,0,t0.matrix().rows(),4) = t0.matrix();\n  VERIFY_IS_APPROX(t0.inverse(Affine).matrix(), t044.inverse().block(0,0,t0.matrix().rows(),4));\n  t0.setIdentity();\n  t0.translate(v0).rotate(q1);\n  t044 = Matrix4::Zero();\n  t044(3,3) = 1;\n  t044.block(0,0,t0.matrix().rows(),4) = t0.matrix();\n  VERIFY_IS_APPROX(t0.inverse(Isometry).matrix(), t044.inverse().block(0,0,t0.matrix().rows(),4));\n\n  Matrix3 mat_rotation, mat_scaling;\n  t0.setIdentity();\n  t0.translate(v0).rotate(q1).scale(v1);\n  t0.computeRotationScaling(&mat_rotation, &mat_scaling);\n  VERIFY_IS_APPROX(t0.linear(), mat_rotation * mat_scaling);\n  VERIFY_IS_APPROX(mat_rotation*mat_rotation.adjoint(), Matrix3::Identity());\n  VERIFY_IS_APPROX(mat_rotation.determinant(), Scalar(1));\n  t0.computeScalingRotation(&mat_scaling, &mat_rotation);\n  VERIFY_IS_APPROX(t0.linear(), mat_scaling * mat_rotation);\n  VERIFY_IS_APPROX(mat_rotation*mat_rotation.adjoint(), Matrix3::Identity());\n  VERIFY_IS_APPROX(mat_rotation.determinant(), Scalar(1));\n\n  // test casting\n  Transform<float,3,Mode> t1f = t1.template cast<float>();\n  VERIFY_IS_APPROX(t1f.template cast<Scalar>(),t1);\n  Transform<double,3,Mode> t1d = t1.template cast<double>();\n  VERIFY_IS_APPROX(t1d.template cast<Scalar>(),t1);\n\n  Translation3 tr1(v0);\n  Translation<float,3> tr1f = tr1.template cast<float>();\n  VERIFY_IS_APPROX(tr1f.template cast<Scalar>(),tr1);\n  Translation<double,3> tr1d = tr1.template cast<double>();\n  VERIFY_IS_APPROX(tr1d.template cast<Scalar>(),tr1);\n\n  AngleAxis<float> aa1f = aa1.template cast<float>();\n  VERIFY_IS_APPROX(aa1f.template cast<Scalar>(),aa1);\n  AngleAxis<double> aa1d = aa1.template cast<double>();\n  VERIFY_IS_APPROX(aa1d.template cast<Scalar>(),aa1);\n\n  Rotation2D<Scalar> r2d1(internal::random<Scalar>());\n  Rotation2D<float> r2d1f = r2d1.template cast<float>();\n  VERIFY_IS_APPROX(r2d1f.template cast<Scalar>(),r2d1);\n  Rotation2D<double> r2d1d = r2d1.template cast<double>();\n  VERIFY_IS_APPROX(r2d1d.template cast<Scalar>(),r2d1);\n  \n  for(int k=0; k<100; ++k)\n  {\n    Scalar angle = internal::random<Scalar>(-100,100);\n    Rotation2D<Scalar> rot2(angle);\n    VERIFY( rot2.smallestPositiveAngle() >= 0 );\n    VERIFY( rot2.smallestPositiveAngle() <= Scalar(2)*Scalar(EIGEN_PI) );\n    VERIFY_IS_APPROX( angleToVec(rot2.smallestPositiveAngle()), angleToVec(rot2.angle()) );\n    \n    VERIFY( rot2.smallestAngle() >= -Scalar(EIGEN_PI) );\n    VERIFY( rot2.smallestAngle() <=  Scalar(EIGEN_PI) );\n    VERIFY_IS_APPROX( angleToVec(rot2.smallestAngle()), angleToVec(rot2.angle()) );\n\n    Matrix<Scalar,2,2> rot2_as_mat(rot2);\n    Rotation2D<Scalar> rot3(rot2_as_mat);\n    VERIFY_IS_APPROX( angleToVec(rot2.smallestAngle()),  angleToVec(rot3.angle()) );\n  }\n\n  s0 = internal::random<Scalar>(-100,100);\n  s1 = internal::random<Scalar>(-100,100);\n  Rotation2D<Scalar> R0(s0), R1(s1);\n  \n  t20 = Translation2(v20) * (R0 * Eigen::Scaling(s0));\n  t21 = Translation2(v20) * R0 * Eigen::Scaling(s0);\n  VERIFY_IS_APPROX(t20,t21);\n  \n  t20 = Translation2(v20) * (R0 * R0.inverse() * Eigen::Scaling(s0));\n  t21 = Translation2(v20) * Eigen::Scaling(s0);\n  VERIFY_IS_APPROX(t20,t21);\n  \n  VERIFY_IS_APPROX(s0, (R0.slerp(0, R1)).angle());\n  VERIFY_IS_APPROX( angleToVec(R1.smallestPositiveAngle()), angleToVec((R0.slerp(1, R1)).smallestPositiveAngle()) );\n  VERIFY_IS_APPROX(R0.smallestPositiveAngle(), (R0.slerp(0.5, R0)).smallestPositiveAngle());\n\n  if(std::cos(s0)>0)\n    VERIFY_IS_MUCH_SMALLER_THAN((R0.slerp(0.5, R0.inverse())).smallestAngle(), Scalar(1));\n  else\n    VERIFY_IS_APPROX(Scalar(EIGEN_PI), (R0.slerp(0.5, R0.inverse())).smallestPositiveAngle());\n  \n  // Check path length\n  Scalar l = 0;\n  int path_steps = 100;\n  for(int k=0; k<path_steps; ++k)\n  {\n    Scalar a1 = R0.slerp(Scalar(k)/Scalar(path_steps), R1).angle();\n    Scalar a2 = R0.slerp(Scalar(k+1)/Scalar(path_steps), R1).angle();\n    l += std::abs(a2-a1);\n  }\n  VERIFY(l<=Scalar(EIGEN_PI)*(Scalar(1)+NumTraits<Scalar>::epsilon()*Scalar(path_steps/2)));\n  \n  // check basic features\n  {\n    Rotation2D<Scalar> r1;           // default ctor\n    r1 = Rotation2D<Scalar>(s0);     // copy assignment\n    VERIFY_IS_APPROX(r1.angle(),s0);\n    Rotation2D<Scalar> r2(r1);       // copy ctor\n    VERIFY_IS_APPROX(r2.angle(),s0);\n  }\n\n  {\n    Transform3 t32(Matrix4::Random()), t33, t34;\n    t34 = t33 = t32;\n    t32.scale(v0);\n    t33*=AlignedScaling3(v0);\n    VERIFY_IS_APPROX(t32.matrix(), t33.matrix());\n    t33 = t34 * AlignedScaling3(v0);\n    VERIFY_IS_APPROX(t32.matrix(), t33.matrix());\n  }\n\n}\n\ntemplate<typename A1, typename A2, typename P, typename Q, typename V, typename H>\nvoid transform_associativity_left(const A1& a1, const A2& a2, const P& p, const Q& q, const V& v, const H& h)\n{\n  VERIFY_IS_APPROX( q*(a1*v), (q*a1)*v );\n  VERIFY_IS_APPROX( q*(a2*v), (q*a2)*v );\n  VERIFY_IS_APPROX( q*(p*h).hnormalized(),  ((q*p)*h).hnormalized() );\n}\n\ntemplate<typename A1, typename A2, typename P, typename Q, typename V, typename H>\nvoid transform_associativity2(const A1& a1, const A2& a2, const P& p, const Q& q, const V& v, const H& h)\n{\n  VERIFY_IS_APPROX( a1*(q*v), (a1*q)*v );\n  VERIFY_IS_APPROX( a2*(q*v), (a2*q)*v );\n  VERIFY_IS_APPROX( p *(q*v).homogeneous(), (p *q)*v.homogeneous() );\n\n  transform_associativity_left(a1, a2,p, q, v, h);\n}\n\ntemplate<typename Scalar, int Dim, int Options,typename RotationType>\nvoid transform_associativity(const RotationType& R)\n{\n  typedef Matrix<Scalar,Dim,1> VectorType;\n  typedef Matrix<Scalar,Dim+1,1> HVectorType;\n  typedef Matrix<Scalar,Dim,Dim> LinearType;\n  typedef Matrix<Scalar,Dim+1,Dim+1> MatrixType;\n  typedef Transform<Scalar,Dim,AffineCompact,Options> AffineCompactType;\n  typedef Transform<Scalar,Dim,Affine,Options> AffineType;\n  typedef Transform<Scalar,Dim,Projective,Options> ProjectiveType;\n  typedef DiagonalMatrix<Scalar,Dim> ScalingType;\n  typedef Translation<Scalar,Dim> TranslationType;\n\n  AffineCompactType A1c; A1c.matrix().setRandom();\n  AffineCompactType A2c; A2c.matrix().setRandom();\n  AffineType A1(A1c);\n  AffineType A2(A2c);\n  ProjectiveType P1; P1.matrix().setRandom();\n  VectorType v1 = VectorType::Random();\n  VectorType v2 = VectorType::Random();\n  HVectorType h1 = HVectorType::Random();\n  Scalar s1 = internal::random<Scalar>();\n  LinearType L = LinearType::Random();\n  MatrixType M = MatrixType::Random();\n\n  CALL_SUBTEST( transform_associativity2(A1c, A1, P1, A2, v2, h1) );\n  CALL_SUBTEST( transform_associativity2(A1c, A1, P1, A2c, v2, h1) );\n  CALL_SUBTEST( transform_associativity2(A1c, A1, P1, v1.asDiagonal(), v2, h1) );\n  CALL_SUBTEST( transform_associativity2(A1c, A1, P1, ScalingType(v1), v2, h1) );\n  CALL_SUBTEST( transform_associativity2(A1c, A1, P1, Scaling(v1), v2, h1) );\n  CALL_SUBTEST( transform_associativity2(A1c, A1, P1, Scaling(s1), v2, h1) );\n  CALL_SUBTEST( transform_associativity2(A1c, A1, P1, TranslationType(v1), v2, h1) );\n  CALL_SUBTEST( transform_associativity_left(A1c, A1, P1, L, v2, h1) );\n  CALL_SUBTEST( transform_associativity2(A1c, A1, P1, R, v2, h1) );\n\n  VERIFY_IS_APPROX( A1*(M*h1), (A1*M)*h1 );\n  VERIFY_IS_APPROX( A1c*(M*h1), (A1c*M)*h1 );\n  VERIFY_IS_APPROX( P1*(M*h1), (P1*M)*h1 );\n\n  VERIFY_IS_APPROX( M*(A1*h1), (M*A1)*h1 );\n  VERIFY_IS_APPROX( M*(A1c*h1), (M*A1c)*h1 );\n  VERIFY_IS_APPROX( M*(P1*h1),  ((M*P1)*h1) );\n}\n\ntemplate<typename Scalar> void transform_alignment()\n{\n  typedef Transform<Scalar,3,Projective,AutoAlign> Projective3a;\n  typedef Transform<Scalar,3,Projective,DontAlign> Projective3u;\n\n  EIGEN_ALIGN_MAX Scalar array1[16];\n  EIGEN_ALIGN_MAX Scalar array2[16];\n  EIGEN_ALIGN_MAX Scalar array3[16+1];\n  Scalar* array3u = array3+1;\n\n  Projective3a *p1 = ::new(reinterpret_cast<void*>(array1)) Projective3a;\n  Projective3u *p2 = ::new(reinterpret_cast<void*>(array2)) Projective3u;\n  Projective3u *p3 = ::new(reinterpret_cast<void*>(array3u)) Projective3u;\n  \n  p1->matrix().setRandom();\n  *p2 = *p1;\n  *p3 = *p1;\n\n  VERIFY_IS_APPROX(p1->matrix(), p2->matrix());\n  VERIFY_IS_APPROX(p1->matrix(), p3->matrix());\n  \n  VERIFY_IS_APPROX( (*p1) * (*p1), (*p2)*(*p3));\n  \n  #if defined(EIGEN_VECTORIZE) && EIGEN_MAX_STATIC_ALIGN_BYTES>0\n  if(internal::packet_traits<Scalar>::Vectorizable)\n    VERIFY_RAISES_ASSERT((::new(reinterpret_cast<void*>(array3u)) Projective3a));\n  #endif\n}\n\ntemplate<typename Scalar, int Dim, int Options> void transform_products()\n{\n  typedef Matrix<Scalar,Dim+1,Dim+1> Mat;\n  typedef Transform<Scalar,Dim,Projective,Options> Proj;\n  typedef Transform<Scalar,Dim,Affine,Options> Aff;\n  typedef Transform<Scalar,Dim,AffineCompact,Options> AffC;\n\n  Proj p; p.matrix().setRandom();\n  Aff a; a.linear().setRandom(); a.translation().setRandom();\n  AffC ac = a;\n\n  Mat p_m(p.matrix()), a_m(a.matrix());\n\n  VERIFY_IS_APPROX((p*p).matrix(), p_m*p_m);\n  VERIFY_IS_APPROX((a*a).matrix(), a_m*a_m);\n  VERIFY_IS_APPROX((p*a).matrix(), p_m*a_m);\n  VERIFY_IS_APPROX((a*p).matrix(), a_m*p_m);\n  VERIFY_IS_APPROX((ac*a).matrix(), a_m*a_m);\n  VERIFY_IS_APPROX((a*ac).matrix(), a_m*a_m);\n  VERIFY_IS_APPROX((p*ac).matrix(), p_m*a_m);\n  VERIFY_IS_APPROX((ac*p).matrix(), a_m*p_m);\n}\n\ntemplate<typename Scalar, int Mode, int Options> void transformations_no_scale()\n{\n     /* this test covers the following files:\n     Cross.h Quaternion.h, Transform.h\n  */\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef Matrix<Scalar,4,1> Vector4;\n  typedef Quaternion<Scalar> Quaternionx;\n  typedef AngleAxis<Scalar> AngleAxisx;\n  typedef Transform<Scalar,3,Mode,Options> Transform3;\n  typedef Translation<Scalar,3> Translation3;\n  typedef Matrix<Scalar,4,4> Matrix4;\n\n  Vector3 v0 = Vector3::Random(),\n          v1 = Vector3::Random();\n\n  Transform3 t0, t1, t2;\n\n  Scalar a = internal::random<Scalar>(-Scalar(EIGEN_PI), Scalar(EIGEN_PI));\n\n  Quaternionx q1, q2;\n\n  q1 = AngleAxisx(a, v0.normalized());\n\n  t0 = Transform3::Identity();\n  VERIFY_IS_APPROX(t0.matrix(), Transform3::MatrixType::Identity());\n\n  t0.setIdentity();\n  t1.setIdentity();\n  v1 = Vector3::Ones();\n  t0.linear() = q1.toRotationMatrix();\n  t0.pretranslate(v0);\n  t1.linear() = q1.conjugate().toRotationMatrix();\n  t1.translate(-v0);\n\n  VERIFY((t0 * t1).matrix().isIdentity(test_precision<Scalar>()));\n\n  t1.fromPositionOrientationScale(v0, q1, v1);\n  VERIFY_IS_APPROX(t1.matrix(), t0.matrix());\n  VERIFY_IS_APPROX(t1*v1, t0*v1);\n\n  // translation * vector\n  t0.setIdentity();\n  t0.translate(v0);\n  VERIFY_IS_APPROX((t0 * v1).template head<3>(), Translation3(v0) * v1);\n\n  // Conversion to matrix.\n  Transform3 t3;\n  t3.linear() = q1.toRotationMatrix();\n  t3.translation() = v1;\n  Matrix4 m3 = t3.matrix();\n  VERIFY((m3 * m3.inverse()).isIdentity(test_precision<Scalar>()));\n  // Verify implicit last row is initialized.\n  VERIFY_IS_APPROX(Vector4(m3.row(3)), Vector4(0.0, 0.0, 0.0, 1.0));\n\n  VERIFY_IS_APPROX(t3.rotation(), t3.linear());\n  if(Mode==Isometry)\n    VERIFY(t3.rotation().data()==t3.linear().data());\n}\n\ntemplate<typename Scalar, int Mode, int Options> void transformations_computed_scaling_continuity()\n{\n  typedef Matrix<Scalar, 3, 1> Vector3;\n  typedef Transform<Scalar, 3, Mode, Options> Transform3;\n  typedef Matrix<Scalar, 3, 3> Matrix3;\n\n  // Given: two transforms that differ by '2*eps'.\n  Scalar eps(1e-3);\n  Vector3 v0 = Vector3::Random().normalized(),\n    v1 = Vector3::Random().normalized(),\n    v3 = Vector3::Random().normalized();\n  Transform3 t0, t1;\n  // The interesting case is when their determinants have different signs.\n  Matrix3 rank2 = 50 * v0 * v0.adjoint() + 20 * v1 * v1.adjoint();\n  t0.linear() = rank2 + eps * v3 * v3.adjoint();\n  t1.linear() = rank2 - eps * v3 * v3.adjoint();\n\n  // When: computing the rotation-scaling parts\n  Matrix3 r0, s0, r1, s1;\n  t0.computeRotationScaling(&r0, &s0);\n  t1.computeRotationScaling(&r1, &s1);\n\n  // Then: the scaling parts should differ by no more than '2*eps'.\n  const Scalar c(2.1); // 2 + room for rounding errors\n  VERIFY((s0 - s1).norm() < c * eps);\n}\n\nEIGEN_DECLARE_TEST(geo_transformations)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(( transformations<double,Affine,AutoAlign>() ));\n    CALL_SUBTEST_1(( non_projective_only<double,Affine,AutoAlign>() ));\n    CALL_SUBTEST_1(( transformations_computed_scaling_continuity<double,Affine,AutoAlign>() ));   \n    \n    CALL_SUBTEST_2(( transformations<float,AffineCompact,AutoAlign>() ));\n    CALL_SUBTEST_2(( non_projective_only<float,AffineCompact,AutoAlign>() ));\n    CALL_SUBTEST_2(( transform_alignment<float>() ));\n    \n    CALL_SUBTEST_3(( transformations<double,Projective,AutoAlign>() ));\n    CALL_SUBTEST_3(( transformations<double,Projective,DontAlign>() ));\n    CALL_SUBTEST_3(( transform_alignment<double>() ));\n\n    CALL_SUBTEST_4(( transformations<float,Affine,RowMajor|AutoAlign>() ));\n    CALL_SUBTEST_4(( non_projective_only<float,Affine,RowMajor>() ));\n    \n    CALL_SUBTEST_5(( transformations<double,AffineCompact,RowMajor|AutoAlign>() ));\n    CALL_SUBTEST_5(( non_projective_only<double,AffineCompact,RowMajor>() ));\n\n    CALL_SUBTEST_6(( transformations<double,Projective,RowMajor|AutoAlign>() ));\n    CALL_SUBTEST_6(( transformations<double,Projective,RowMajor|DontAlign>() ));\n\n\n    CALL_SUBTEST_7(( transform_products<double,3,RowMajor|AutoAlign>() ));\n    CALL_SUBTEST_7(( transform_products<float,2,AutoAlign>() ));\n\n    CALL_SUBTEST_8(( transform_associativity<double,2,ColMajor>(Rotation2D<double>(internal::random<double>()*double(EIGEN_PI))) ));\n    CALL_SUBTEST_8(( transform_associativity<double,3,ColMajor>(Quaterniond::UnitRandom()) ));\n\n    CALL_SUBTEST_9(( transformations_no_scale<double,Affine,AutoAlign>() ));\n    CALL_SUBTEST_9(( transformations_no_scale<double,Isometry,AutoAlign>() ));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/gpu_basic.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015-2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// workaround issue between gcc >= 4.7 and cuda 5.5\n#if (defined __GNUC__) && (__GNUC__>4 || __GNUC_MINOR__>=7)\n  #undef _GLIBCXX_ATOMIC_BUILTINS\n  #undef _GLIBCXX_USE_INT128\n#endif\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int\n\n#include \"main.h\"\n#include \"gpu_common.h\"\n\n// Check that dense modules can be properly parsed by nvcc\n#include <Eigen/Dense>\n\n// struct Foo{\n//   EIGEN_DEVICE_FUNC\n//   void operator()(int i, const float* mats, float* vecs) const {\n//     using namespace Eigen;\n//   //   Matrix3f M(data);\n//   //   Vector3f x(data+9);\n//   //   Map<Vector3f>(data+9) = M.inverse() * x;\n//     Matrix3f M(mats+i/16);\n//     Vector3f x(vecs+i*3);\n//   //   using std::min;\n//   //   using std::sqrt;\n//     Map<Vector3f>(vecs+i*3) << x.minCoeff(), 1, 2;// / x.dot(x);//(M.inverse() *  x) / x.x();\n//     //x = x*2 + x.y() * x + x * x.maxCoeff() - x / x.sum();\n//   }\n// };\n\ntemplate<typename T>\nstruct coeff_wise {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const\n  {\n    using namespace Eigen;\n    T x1(in+i);\n    T x2(in+i+1);\n    T x3(in+i+2);\n    Map<T> res(out+i*T::MaxSizeAtCompileTime);\n    \n    res.array() += (in[0] * x1 + x2).array() * x3.array();\n  }\n};\n\ntemplate<typename T>\nstruct complex_sqrt {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const\n  {\n    using namespace Eigen;\n    typedef typename T::Scalar ComplexType;\n    typedef typename T::Scalar::value_type ValueType;\n    const int num_special_inputs = 18;\n    \n    if (i == 0) {\n      const ValueType nan = std::numeric_limits<ValueType>::quiet_NaN();\n      typedef Eigen::Vector<ComplexType, num_special_inputs> SpecialInputs;\n      SpecialInputs special_in;\n      special_in.setZero();\n      int idx = 0;\n      special_in[idx++] = ComplexType(0, 0);\n      special_in[idx++] = ComplexType(-0, 0);\n      special_in[idx++] = ComplexType(0, -0);\n      special_in[idx++] = ComplexType(-0, -0);\n      // GCC's fallback sqrt implementation fails for inf inputs.\n      // It is called when _GLIBCXX_USE_C99_COMPLEX is false or if\n      // clang includes the GCC header (which temporarily disables\n      // _GLIBCXX_USE_C99_COMPLEX)\n      #if !defined(_GLIBCXX_COMPLEX) || \\\n        (_GLIBCXX_USE_C99_COMPLEX && !defined(__CLANG_CUDA_WRAPPERS_COMPLEX))\n      const ValueType inf = std::numeric_limits<ValueType>::infinity();\n      special_in[idx++] = ComplexType(1.0, inf);\n      special_in[idx++] = ComplexType(nan, inf);\n      special_in[idx++] = ComplexType(1.0, -inf);\n      special_in[idx++] = ComplexType(nan, -inf);\n      special_in[idx++] = ComplexType(-inf, 1.0);\n      special_in[idx++] = ComplexType(inf, 1.0);\n      special_in[idx++] = ComplexType(-inf, -1.0);\n      special_in[idx++] = ComplexType(inf, -1.0);\n      special_in[idx++] = ComplexType(-inf, nan);\n      special_in[idx++] = ComplexType(inf, nan);\n      #endif\n      special_in[idx++] = ComplexType(1.0, nan);\n      special_in[idx++] = ComplexType(nan, 1.0);\n      special_in[idx++] = ComplexType(nan, -1.0);\n      special_in[idx++] = ComplexType(nan, nan);\n      \n      Map<SpecialInputs> special_out(out);\n      special_out = special_in.cwiseSqrt();\n    }\n    \n    T x1(in + i);\n    Map<T> res(out + num_special_inputs + i*T::MaxSizeAtCompileTime);\n    res = x1.cwiseSqrt();\n  }\n};\n\ntemplate<typename T>\nstruct complex_operators {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const\n  {\n    using namespace Eigen;\n    typedef typename T::Scalar ComplexType;\n    typedef typename T::Scalar::value_type ValueType;\n    const int num_scalar_operators = 24;\n    const int num_vector_operators = 23;  // no unary + operator.\n    int out_idx = i * (num_scalar_operators + num_vector_operators * T::MaxSizeAtCompileTime);\n    \n    // Scalar operators.\n    const ComplexType a = in[i];\n    const ComplexType b = in[i + 1];\n    \n    out[out_idx++] = +a;\n    out[out_idx++] = -a;\n    \n    out[out_idx++] = a + b;\n    out[out_idx++] = a + numext::real(b);\n    out[out_idx++] = numext::real(a) + b;\n    out[out_idx++] = a - b;\n    out[out_idx++] = a - numext::real(b);\n    out[out_idx++] = numext::real(a) - b;\n    out[out_idx++] = a * b;\n    out[out_idx++] = a * numext::real(b);\n    out[out_idx++] = numext::real(a) * b;\n    out[out_idx++] = a / b;\n    out[out_idx++] = a / numext::real(b);\n    out[out_idx++] = numext::real(a) / b;\n    \n    out[out_idx] = a; out[out_idx++] += b;\n    out[out_idx] = a; out[out_idx++] -= b;\n    out[out_idx] = a; out[out_idx++] *= b;\n    out[out_idx] = a; out[out_idx++] /= b;\n    \n    const ComplexType true_value = ComplexType(ValueType(1), ValueType(0));\n    const ComplexType false_value = ComplexType(ValueType(0), ValueType(0));\n    out[out_idx++] = (a == b ? true_value : false_value);\n    out[out_idx++] = (a == numext::real(b) ? true_value : false_value);\n    out[out_idx++] = (numext::real(a) == b ? true_value : false_value);\n    out[out_idx++] = (a != b ? true_value : false_value);\n    out[out_idx++] = (a != numext::real(b) ? true_value : false_value);\n    out[out_idx++] = (numext::real(a) != b ? true_value : false_value);\n    \n    // Vector versions.\n    T x1(in + i);\n    T x2(in + i + 1);\n    const int res_size = T::MaxSizeAtCompileTime * num_scalar_operators;\n    const int size = T::MaxSizeAtCompileTime;\n    int block_idx = 0;\n    \n    Map<VectorX<ComplexType>> res(out + out_idx, res_size);\n    res.segment(block_idx, size) = -x1;\n    block_idx += size;\n    \n    res.segment(block_idx, size) = x1 + x2;\n    block_idx += size;\n    res.segment(block_idx, size) = x1 + x2.real();\n    block_idx += size;\n    res.segment(block_idx, size) = x1.real() + x2;\n    block_idx += size;\n    res.segment(block_idx, size) = x1 - x2;\n    block_idx += size;\n    res.segment(block_idx, size) = x1 - x2.real();\n    block_idx += size;\n    res.segment(block_idx, size) = x1.real() - x2;\n    block_idx += size;\n    res.segment(block_idx, size) = x1.array() * x2.array();\n    block_idx += size;\n    res.segment(block_idx, size) = x1.array() * x2.real().array();\n    block_idx += size;\n    res.segment(block_idx, size) = x1.real().array() * x2.array();\n    block_idx += size;\n    res.segment(block_idx, size) = x1.array() / x2.array();\n    block_idx += size;\n    res.segment(block_idx, size) = x1.array() / x2.real().array();\n    block_idx += size;\n    res.segment(block_idx, size) = x1.real().array() / x2.array();\n    block_idx += size;\n    \n    res.segment(block_idx, size) = x1; res.segment(block_idx, size) += x2;\n    block_idx += size;\n    res.segment(block_idx, size) = x1; res.segment(block_idx, size) -= x2;\n    block_idx += size;\n    res.segment(block_idx, size) = x1; res.segment(block_idx, size).array() *= x2.array();\n    block_idx += size;\n    res.segment(block_idx, size) = x1; res.segment(block_idx, size).array() /= x2.array();\n    block_idx += size;\n\n    // Equality comparisons currently not functional on device\n    //   (std::equal_to<T> is host-only).\n    // const T true_vector = T::Constant(true_value);\n    // const T false_vector = T::Constant(false_value);\n    // res.segment(block_idx, size) = (x1 == x2 ? true_vector : false_vector);\n    // block_idx += size;\n    // res.segment(block_idx, size) = (x1 == x2.real() ? true_vector : false_vector);\n    // block_idx += size;\n    // res.segment(block_idx, size) = (x1.real() == x2 ? true_vector : false_vector);\n    // block_idx += size;\n    // res.segment(block_idx, size) = (x1 != x2 ? true_vector : false_vector);\n    // block_idx += size;\n    // res.segment(block_idx, size) = (x1 != x2.real() ? true_vector : false_vector);\n    // block_idx += size;\n    // res.segment(block_idx, size) = (x1.real() != x2 ? true_vector : false_vector);\n    // block_idx += size;\n  }\n};\n\ntemplate<typename T>\nstruct replicate {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const\n  {\n    using namespace Eigen;\n    T x1(in+i);\n    int step   = x1.size() * 4;\n    int stride = 3 * step;\n    \n    typedef Map<Array<typename T::Scalar,Dynamic,Dynamic> > MapType;\n    MapType(out+i*stride+0*step, x1.rows()*2, x1.cols()*2) = x1.replicate(2,2);\n    MapType(out+i*stride+1*step, x1.rows()*3, x1.cols()) = in[i] * x1.colwise().replicate(3);\n    MapType(out+i*stride+2*step, x1.rows(), x1.cols()*3) = in[i] * x1.rowwise().replicate(3);\n  }\n};\n\ntemplate<typename T>\nstruct alloc_new_delete {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const\n  {\n    int offset = 2*i*T::MaxSizeAtCompileTime;\n    T* x = new T(in + offset);\n    Eigen::Map<T> u(out + offset);\n    u = *x;\n    delete x;\n    \n    offset += T::MaxSizeAtCompileTime;\n    T* y = new T[1];\n    y[0] = T(in + offset);\n    Eigen::Map<T> v(out + offset);\n    v = y[0];    \n    delete[] y;\n  }\n};\n\ntemplate<typename T>\nstruct redux {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const\n  {\n    using namespace Eigen;\n    int N = 10;\n    T x1(in+i);\n    out[i*N+0] = x1.minCoeff();\n    out[i*N+1] = x1.maxCoeff();\n    out[i*N+2] = x1.sum();\n    out[i*N+3] = x1.prod();\n    out[i*N+4] = x1.matrix().squaredNorm();\n    out[i*N+5] = x1.matrix().norm();\n    out[i*N+6] = x1.colwise().sum().maxCoeff();\n    out[i*N+7] = x1.rowwise().maxCoeff().sum();\n    out[i*N+8] = x1.matrix().colwise().squaredNorm().sum();\n  }\n};\n\ntemplate<typename T1, typename T2>\nstruct prod_test {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T1::Scalar* in, typename T1::Scalar* out) const\n  {\n    using namespace Eigen;\n    typedef Matrix<typename T1::Scalar, T1::RowsAtCompileTime, T2::ColsAtCompileTime> T3;\n    T1 x1(in+i);\n    T2 x2(in+i+1);\n    Map<T3> res(out+i*T3::MaxSizeAtCompileTime);\n    res += in[i] * x1 * x2;\n  }\n};\n\ntemplate<typename T1, typename T2>\nstruct diagonal {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T1::Scalar* in, typename T1::Scalar* out) const\n  {\n    using namespace Eigen;\n    T1 x1(in+i);\n    Map<T2> res(out+i*T2::MaxSizeAtCompileTime);\n    res += x1.diagonal();\n  }\n};\n\ntemplate<typename T>\nstruct eigenvalues_direct {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const\n  {\n    using namespace Eigen;\n    typedef Matrix<typename T::Scalar, T::RowsAtCompileTime, 1> Vec;\n    T M(in+i);\n    Map<Vec> res(out+i*Vec::MaxSizeAtCompileTime);\n    T A = M*M.adjoint();\n    SelfAdjointEigenSolver<T> eig;\n    eig.computeDirect(A);\n    res = eig.eigenvalues();\n  }\n};\n\ntemplate<typename T>\nstruct eigenvalues {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const\n  {\n    using namespace Eigen;\n    typedef Matrix<typename T::Scalar, T::RowsAtCompileTime, 1> Vec;\n    T M(in+i);\n    Map<Vec> res(out+i*Vec::MaxSizeAtCompileTime);\n    T A = M*M.adjoint();\n    SelfAdjointEigenSolver<T> eig;\n    eig.compute(A);\n    res = eig.eigenvalues();\n  }\n};\n\ntemplate<typename T>\nstruct matrix_inverse {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const typename T::Scalar* in, typename T::Scalar* out) const\n  {\n    using namespace Eigen;\n    T M(in+i);\n    Map<T> res(out+i*T::MaxSizeAtCompileTime);\n    res = M.inverse();\n  }\n};\n\ntemplate<typename Type1, typename Type2>\nbool verifyIsApproxWithInfsNans(const Type1& a, const Type2& b, typename Type1::Scalar* = 0) // Enabled for Eigen's type only\n{\n  if (a.rows() != b.rows()) {\n    return false;\n  }\n  if (a.cols() != b.cols()) {\n    return false;\n  }\n  for (Index r = 0; r < a.rows(); ++r) {\n    for (Index c = 0; c < a.cols(); ++c) {\n      if (a(r, c) != b(r, c)\n          && !((numext::isnan)(a(r, c)) && (numext::isnan)(b(r, c))) \n          && !test_isApprox(a(r, c), b(r, c))) {\n        return false;\n      }\n    }\n  }\n  return true;\n}\n\ntemplate<typename Kernel, typename Input, typename Output>\nvoid test_with_infs_nans(const Kernel& ker, int n, const Input& in, Output& out)\n{\n  Output out_ref, out_gpu;\n  #if !defined(EIGEN_GPU_COMPILE_PHASE)\n  out_ref = out_gpu = out;\n  #else\n  EIGEN_UNUSED_VARIABLE(in);\n  EIGEN_UNUSED_VARIABLE(out);\n  #endif\n  run_on_cpu (ker, n, in,  out_ref);\n  run_on_gpu(ker, n, in, out_gpu);\n  #if !defined(EIGEN_GPU_COMPILE_PHASE)\n  verifyIsApproxWithInfsNans(out_ref, out_gpu);\n  #endif\n}\n\nEIGEN_DECLARE_TEST(gpu_basic)\n{\n  ei_test_init_gpu();\n  \n  int nthreads = 100;\n  Eigen::VectorXf in, out;\n  Eigen::VectorXcf cfin, cfout;\n  \n  #if !defined(EIGEN_GPU_COMPILE_PHASE)\n  int data_size = nthreads * 512;\n  in.setRandom(data_size);\n  out.setConstant(data_size, -1);\n  cfin.setRandom(data_size);\n  cfout.setConstant(data_size, -1);\n  #endif\n  \n  CALL_SUBTEST( run_and_compare_to_gpu(coeff_wise<Vector3f>(), nthreads, in, out) );\n  CALL_SUBTEST( run_and_compare_to_gpu(coeff_wise<Array44f>(), nthreads, in, out) );\n\n#if !defined(EIGEN_USE_HIP)\n  // FIXME\n  // These subtests result in a compile failure on the HIP platform\n  //\n  //  eigen-upstream/Eigen/src/Core/Replicate.h:61:65: error:\n  //           base class 'internal::dense_xpr_base<Replicate<Array<float, 4, 1, 0, 4, 1>, -1, -1> >::type'\n  //           (aka 'ArrayBase<Eigen::Replicate<Eigen::Array<float, 4, 1, 0, 4, 1>, -1, -1> >') has protected default constructor\n  CALL_SUBTEST( run_and_compare_to_gpu(replicate<Array4f>(), nthreads, in, out) );\n  CALL_SUBTEST( run_and_compare_to_gpu(replicate<Array33f>(), nthreads, in, out) );\n\n  // HIP does not support new/delete on device.\n  CALL_SUBTEST( run_and_compare_to_gpu(alloc_new_delete<Vector3f>(), nthreads, in, out) );\n#endif\n  \n  CALL_SUBTEST( run_and_compare_to_gpu(redux<Array4f>(), nthreads, in, out) );\n  CALL_SUBTEST( run_and_compare_to_gpu(redux<Matrix3f>(), nthreads, in, out) );\n  \n  CALL_SUBTEST( run_and_compare_to_gpu(prod_test<Matrix3f,Matrix3f>(), nthreads, in, out) );\n  CALL_SUBTEST( run_and_compare_to_gpu(prod_test<Matrix4f,Vector4f>(), nthreads, in, out) );\n  \n  CALL_SUBTEST( run_and_compare_to_gpu(diagonal<Matrix3f,Vector3f>(), nthreads, in, out) );\n  CALL_SUBTEST( run_and_compare_to_gpu(diagonal<Matrix4f,Vector4f>(), nthreads, in, out) );\n\n  CALL_SUBTEST( run_and_compare_to_gpu(matrix_inverse<Matrix2f>(), nthreads, in, out) );\n  CALL_SUBTEST( run_and_compare_to_gpu(matrix_inverse<Matrix3f>(), nthreads, in, out) );\n  CALL_SUBTEST( run_and_compare_to_gpu(matrix_inverse<Matrix4f>(), nthreads, in, out) );\n  \n  CALL_SUBTEST( run_and_compare_to_gpu(eigenvalues_direct<Matrix3f>(), nthreads, in, out) );\n  CALL_SUBTEST( run_and_compare_to_gpu(eigenvalues_direct<Matrix2f>(), nthreads, in, out) );\n\n  // Test std::complex.\n  CALL_SUBTEST( run_and_compare_to_gpu(complex_operators<Vector3cf>(), nthreads, cfin, cfout) );\n  CALL_SUBTEST( test_with_infs_nans(complex_sqrt<Vector3cf>(), nthreads, cfin, cfout) );\n\n#if defined(__NVCC__)\n  // FIXME\n  // These subtests compiles only with nvcc and fail with HIPCC and clang-cuda\n  CALL_SUBTEST( run_and_compare_to_gpu(eigenvalues<Matrix4f>(), nthreads, in, out) );\n  typedef Matrix<float,6,6> Matrix6f;\n  CALL_SUBTEST( run_and_compare_to_gpu(eigenvalues<Matrix6f>(), nthreads, in, out) );\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/gpu_common.h",
    "content": "#ifndef EIGEN_TEST_GPU_COMMON_H\n#define EIGEN_TEST_GPU_COMMON_H\n\n#ifdef EIGEN_USE_HIP\n  #include <hip/hip_runtime.h>\n  #include <hip/hip_runtime_api.h>\n#else\n  #include <cuda.h>\n  #include <cuda_runtime.h>\n  #include <cuda_runtime_api.h>\n#endif\n\n#include <iostream>\n\n#define EIGEN_USE_GPU\n#include <unsupported/Eigen/CXX11/src/Tensor/TensorGpuHipCudaDefines.h>\n\n#if !defined(__CUDACC__) && !defined(__HIPCC__)\ndim3 threadIdx, blockDim, blockIdx;\n#endif\n\ntemplate<typename Kernel, typename Input, typename Output>\nvoid run_on_cpu(const Kernel& ker, int n, const Input& in, Output& out)\n{\n  for(int i=0; i<n; i++)\n    ker(i, in.data(), out.data());\n}\n\n\ntemplate<typename Kernel, typename Input, typename Output>\n__global__\nEIGEN_HIP_LAUNCH_BOUNDS_1024\nvoid run_on_gpu_meta_kernel(const Kernel ker, int n, const Input* in, Output* out)\n{\n  int i = threadIdx.x + blockIdx.x*blockDim.x;\n  if(i<n) {\n    ker(i, in, out);\n  }\n}\n\n\ntemplate<typename Kernel, typename Input, typename Output>\nvoid run_on_gpu(const Kernel& ker, int n, const Input& in, Output& out)\n{\n  typename Input::Scalar*  d_in;\n  typename Output::Scalar* d_out;\n  std::ptrdiff_t in_bytes  = in.size()  * sizeof(typename Input::Scalar);\n  std::ptrdiff_t out_bytes = out.size() * sizeof(typename Output::Scalar);\n  \n  gpuMalloc((void**)(&d_in),  in_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n  \n  gpuMemcpy(d_in,  in.data(),  in_bytes,  gpuMemcpyHostToDevice);\n  gpuMemcpy(d_out, out.data(), out_bytes, gpuMemcpyHostToDevice);\n  \n  // Simple and non-optimal 1D mapping assuming n is not too large\n  // That's only for unit testing!\n  dim3 Blocks(128);\n  dim3 Grids( (n+int(Blocks.x)-1)/int(Blocks.x) );\n\n  gpuDeviceSynchronize();\n  \n#ifdef EIGEN_USE_HIP\n  hipLaunchKernelGGL(HIP_KERNEL_NAME(run_on_gpu_meta_kernel<Kernel,\n\t\t\t\t     typename std::decay<decltype(*d_in)>::type,\n\t\t\t\t     typename std::decay<decltype(*d_out)>::type>), \n\t\t     dim3(Grids), dim3(Blocks), 0, 0, ker, n, d_in, d_out);\n#else\n  run_on_gpu_meta_kernel<<<Grids,Blocks>>>(ker, n, d_in, d_out);\n#endif\n  // Pre-launch errors.\n  gpuError_t err = gpuGetLastError();\n  if (err != gpuSuccess) {\n    printf(\"%s: %s\\n\", gpuGetErrorName(err), gpuGetErrorString(err));\n    gpu_assert(false);\n  }\n  \n  // Kernel execution errors.\n  err = gpuDeviceSynchronize();\n  if (err != gpuSuccess) {\n    printf(\"%s: %s\\n\", gpuGetErrorName(err), gpuGetErrorString(err));\n    gpu_assert(false);\n  }\n  \n  \n  // check inputs have not been modified\n  gpuMemcpy(const_cast<typename Input::Scalar*>(in.data()),  d_in,  in_bytes,  gpuMemcpyDeviceToHost);\n  gpuMemcpy(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost);\n  \n  gpuFree(d_in);\n  gpuFree(d_out);\n}\n\n\ntemplate<typename Kernel, typename Input, typename Output>\nvoid run_and_compare_to_gpu(const Kernel& ker, int n, const Input& in, Output& out)\n{\n  Input  in_ref,  in_gpu;\n  Output out_ref, out_gpu;\n  #if !defined(EIGEN_GPU_COMPILE_PHASE)\n  in_ref = in_gpu = in;\n  out_ref = out_gpu = out;\n  #else\n  EIGEN_UNUSED_VARIABLE(in);\n  EIGEN_UNUSED_VARIABLE(out);\n  #endif\n  run_on_cpu (ker, n, in_ref,  out_ref);\n  run_on_gpu(ker, n, in_gpu, out_gpu);\n  #if !defined(EIGEN_GPU_COMPILE_PHASE)\n  VERIFY_IS_APPROX(in_ref, in_gpu);\n  VERIFY_IS_APPROX(out_ref, out_gpu);\n  #endif\n}\n\nstruct compile_time_device_info {\n  EIGEN_DEVICE_FUNC\n  void operator()(int i, const int* /*in*/, int* info) const\n  {\n    if (i == 0) {\n      EIGEN_UNUSED_VARIABLE(info)\n      #if defined(__CUDA_ARCH__)\n      info[0] = int(__CUDA_ARCH__ +0);\n      #endif\n      #if defined(EIGEN_HIP_DEVICE_COMPILE)\n      info[1] = int(EIGEN_HIP_DEVICE_COMPILE +0);\n      #endif\n    }\n  }\n};\n\nvoid ei_test_init_gpu()\n{\n  int device = 0;\n  gpuDeviceProp_t deviceProp;\n  gpuGetDeviceProperties(&deviceProp, device);\n\n  ArrayXi dummy(1), info(10);\n  info = -1;\n  run_on_gpu(compile_time_device_info(),10,dummy,info);\n\n\n  std::cout << \"GPU compile-time info:\\n\";\n  \n  #ifdef EIGEN_CUDACC\n  std::cout << \"  EIGEN_CUDACC:                 \" << int(EIGEN_CUDACC) << \"\\n\";\n  #endif\n  \n  #ifdef EIGEN_CUDA_SDK_VER\n  std::cout << \"  EIGEN_CUDA_SDK_VER:             \" << int(EIGEN_CUDA_SDK_VER) << \"\\n\";\n  #endif\n\n  #ifdef EIGEN_COMP_NVCC\n  std::cout << \"  EIGEN_COMP_NVCC:             \" << int(EIGEN_COMP_NVCC) << \"\\n\";\n  #endif\n  \n  #ifdef EIGEN_HIPCC\n  std::cout << \"  EIGEN_HIPCC:                 \" << int(EIGEN_HIPCC) << \"\\n\";\n  #endif\n\n  std::cout << \"  EIGEN_CUDA_ARCH:             \" << info[0] << \"\\n\";  \n  std::cout << \"  EIGEN_HIP_DEVICE_COMPILE:    \" << info[1] << \"\\n\";\n\n  std::cout << \"GPU device info:\\n\";\n  std::cout << \"  name:                        \" << deviceProp.name << \"\\n\";\n  std::cout << \"  capability:                  \" << deviceProp.major << \".\" << deviceProp.minor << \"\\n\";\n  std::cout << \"  multiProcessorCount:         \" << deviceProp.multiProcessorCount << \"\\n\";\n  std::cout << \"  maxThreadsPerMultiProcessor: \" << deviceProp.maxThreadsPerMultiProcessor << \"\\n\";\n  std::cout << \"  warpSize:                    \" << deviceProp.warpSize << \"\\n\";\n  std::cout << \"  regsPerBlock:                \" << deviceProp.regsPerBlock << \"\\n\";\n  std::cout << \"  concurrentKernels:           \" << deviceProp.concurrentKernels << \"\\n\";\n  std::cout << \"  clockRate:                   \" << deviceProp.clockRate << \"\\n\";\n  std::cout << \"  canMapHostMemory:            \" << deviceProp.canMapHostMemory << \"\\n\";\n  std::cout << \"  computeMode:                 \" << deviceProp.computeMode << \"\\n\";\n}\n\n#endif // EIGEN_TEST_GPU_COMMON_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/half_float.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <sstream>\n\n#include \"main.h\"\n\n#include <Eigen/src/Core/arch/Default/Half.h>\n\n#define VERIFY_HALF_BITS_EQUAL(h, bits) \\\n  VERIFY_IS_EQUAL((numext::bit_cast<numext::uint16_t>(h)), (static_cast<numext::uint16_t>(bits)))\n\n// Make sure it's possible to forward declare Eigen::half\nnamespace Eigen {\nstruct half;\n}\n\nusing Eigen::half;\n\nvoid test_conversion()\n{\n  using Eigen::half_impl::__half_raw;\n\n  // Round-trip bit-cast with uint16.\n  VERIFY_IS_EQUAL(\n    numext::bit_cast<half>(numext::bit_cast<numext::uint16_t>(half(1.0f))),\n    half(1.0f));\n  VERIFY_IS_EQUAL(\n    numext::bit_cast<half>(numext::bit_cast<numext::uint16_t>(half(0.5f))),\n    half(0.5f));\n  VERIFY_IS_EQUAL(\n    numext::bit_cast<half>(numext::bit_cast<numext::uint16_t>(half(-0.33333f))),\n    half(-0.33333f));\n   VERIFY_IS_EQUAL(\n    numext::bit_cast<half>(numext::bit_cast<numext::uint16_t>(half(0.0f))),\n    half(0.0f));\n\n  // Conversion from float.\n  VERIFY_HALF_BITS_EQUAL(half(1.0f), 0x3c00);\n  VERIFY_HALF_BITS_EQUAL(half(0.5f), 0x3800);\n  VERIFY_HALF_BITS_EQUAL(half(0.33333f), 0x3555);\n  VERIFY_HALF_BITS_EQUAL(half(0.0f), 0x0000);\n  VERIFY_HALF_BITS_EQUAL(half(-0.0f), 0x8000);\n  VERIFY_HALF_BITS_EQUAL(half(65504.0f), 0x7bff);\n  VERIFY_HALF_BITS_EQUAL(half(65536.0f), 0x7c00);  // Becomes infinity.\n\n  // Denormals.\n  VERIFY_HALF_BITS_EQUAL(half(-5.96046e-08f), 0x8001);\n  VERIFY_HALF_BITS_EQUAL(half(5.96046e-08f), 0x0001);\n  VERIFY_HALF_BITS_EQUAL(half(1.19209e-07f), 0x0002);\n\n  // Verify round-to-nearest-even behavior.\n  float val1 = float(half(__half_raw(0x3c00)));\n  float val2 = float(half(__half_raw(0x3c01)));\n  float val3 = float(half(__half_raw(0x3c02)));\n  VERIFY_HALF_BITS_EQUAL(half(0.5f * (val1 + val2)), 0x3c00);\n  VERIFY_HALF_BITS_EQUAL(half(0.5f * (val2 + val3)), 0x3c02);\n\n  // Conversion from int.\n  VERIFY_HALF_BITS_EQUAL(half(-1), 0xbc00);\n  VERIFY_HALF_BITS_EQUAL(half(0), 0x0000);\n  VERIFY_HALF_BITS_EQUAL(half(1), 0x3c00);\n  VERIFY_HALF_BITS_EQUAL(half(2), 0x4000);\n  VERIFY_HALF_BITS_EQUAL(half(3), 0x4200);\n\n  // Conversion from bool.\n  VERIFY_HALF_BITS_EQUAL(half(false), 0x0000);\n  VERIFY_HALF_BITS_EQUAL(half(true), 0x3c00);\n\n  // Conversion to float.\n  VERIFY_IS_EQUAL(float(half(__half_raw(0x0000))), 0.0f);\n  VERIFY_IS_EQUAL(float(half(__half_raw(0x3c00))), 1.0f);\n\n  // Denormals.\n  VERIFY_IS_APPROX(float(half(__half_raw(0x8001))), -5.96046e-08f);\n  VERIFY_IS_APPROX(float(half(__half_raw(0x0001))), 5.96046e-08f);\n  VERIFY_IS_APPROX(float(half(__half_raw(0x0002))), 1.19209e-07f);\n\n  // NaNs and infinities.\n  VERIFY(!(numext::isinf)(float(half(65504.0f))));  // Largest finite number.\n  VERIFY(!(numext::isnan)(float(half(0.0f))));\n  VERIFY((numext::isinf)(float(half(__half_raw(0xfc00)))));\n  VERIFY((numext::isnan)(float(half(__half_raw(0xfc01)))));\n  VERIFY((numext::isinf)(float(half(__half_raw(0x7c00)))));\n  VERIFY((numext::isnan)(float(half(__half_raw(0x7c01)))));\n\n#if !EIGEN_COMP_MSVC\n  // Visual Studio errors out on divisions by 0\n  VERIFY((numext::isnan)(float(half(0.0 / 0.0))));\n  VERIFY((numext::isinf)(float(half(1.0 / 0.0))));\n  VERIFY((numext::isinf)(float(half(-1.0 / 0.0))));\n#endif\n\n  // Exactly same checks as above, just directly on the half representation.\n  VERIFY(!(numext::isinf)(half(__half_raw(0x7bff))));\n  VERIFY(!(numext::isnan)(half(__half_raw(0x0000))));\n  VERIFY((numext::isinf)(half(__half_raw(0xfc00))));\n  VERIFY((numext::isnan)(half(__half_raw(0xfc01))));\n  VERIFY((numext::isinf)(half(__half_raw(0x7c00))));\n  VERIFY((numext::isnan)(half(__half_raw(0x7c01))));\n\n#if !EIGEN_COMP_MSVC\n  // Visual Studio errors out on divisions by 0\n  VERIFY((numext::isnan)(half(0.0 / 0.0)));\n  VERIFY((numext::isinf)(half(1.0 / 0.0)));\n  VERIFY((numext::isinf)(half(-1.0 / 0.0)));\n#endif\n\n  // Conversion to bool\n  VERIFY(!static_cast<bool>(half(0.0)));\n  VERIFY(!static_cast<bool>(half(-0.0)));\n  VERIFY(static_cast<bool>(half(__half_raw(0x7bff))));\n  VERIFY(static_cast<bool>(half(-0.33333)));\n  VERIFY(static_cast<bool>(half(1.0)));\n  VERIFY(static_cast<bool>(half(-1.0)));\n  VERIFY(static_cast<bool>(half(-5.96046e-08f)));\n}\n\nvoid test_numtraits()\n{\n  std::cout << \"epsilon       = \" << NumTraits<half>::epsilon() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(NumTraits<half>::epsilon()) << \")\" << std::endl;\n  std::cout << \"highest       = \" << NumTraits<half>::highest() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(NumTraits<half>::highest()) << \")\" << std::endl;\n  std::cout << \"lowest        = \" << NumTraits<half>::lowest() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(NumTraits<half>::lowest()) << \")\" << std::endl;\n  std::cout << \"min           = \" << (std::numeric_limits<half>::min)() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(half((std::numeric_limits<half>::min)())) << \")\" << std::endl;\n  std::cout << \"denorm min    = \" << (std::numeric_limits<half>::denorm_min)() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(half((std::numeric_limits<half>::denorm_min)())) << \")\" << std::endl;\n  std::cout << \"infinity      = \" << NumTraits<half>::infinity() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(NumTraits<half>::infinity()) << \")\" << std::endl;\n  std::cout << \"quiet nan     = \" << NumTraits<half>::quiet_NaN() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(NumTraits<half>::quiet_NaN()) << \")\" << std::endl;\n  std::cout << \"signaling nan = \" << std::numeric_limits<half>::signaling_NaN() << \"  (0x\" << std::hex << numext::bit_cast<numext::uint16_t>(std::numeric_limits<half>::signaling_NaN()) << \")\" << std::endl;\n\n  VERIFY(NumTraits<half>::IsSigned);\n\n  VERIFY_IS_EQUAL(\n    numext::bit_cast<numext::uint16_t>(std::numeric_limits<half>::infinity()),\n    numext::bit_cast<numext::uint16_t>(half(std::numeric_limits<float>::infinity())) );\n  // There is no guarantee that casting a 32-bit NaN to 16-bit has a precise\n  // bit pattern.  We test that it is in fact a NaN, then test the signaling\n  // bit (msb of significand is 1 for quiet, 0 for signaling).\n  const numext::uint16_t HALF_QUIET_BIT = 0x0200;\n  VERIFY(\n    (numext::isnan)(std::numeric_limits<half>::quiet_NaN())\n    && (numext::isnan)(half(std::numeric_limits<float>::quiet_NaN()))\n    && ((numext::bit_cast<numext::uint16_t>(std::numeric_limits<half>::quiet_NaN()) & HALF_QUIET_BIT) > 0)\n    && ((numext::bit_cast<numext::uint16_t>(half(std::numeric_limits<float>::quiet_NaN())) & HALF_QUIET_BIT) > 0) );\n  // After a cast to half, a signaling NaN may become non-signaling\n  // (e.g. in the case of casting float to native __fp16). Thus, we check that\n  // both are NaN, and that only the `numeric_limits` version is signaling.\n  VERIFY(\n    (numext::isnan)(std::numeric_limits<half>::signaling_NaN())\n    && (numext::isnan)(half(std::numeric_limits<float>::signaling_NaN()))\n    && ((numext::bit_cast<numext::uint16_t>(std::numeric_limits<half>::signaling_NaN()) & HALF_QUIET_BIT) == 0) );\n\n  VERIFY( (std::numeric_limits<half>::min)() > half(0.f) );\n  VERIFY( (std::numeric_limits<half>::denorm_min)() > half(0.f) );\n  VERIFY( (std::numeric_limits<half>::min)()/half(2) > half(0.f) );\n  VERIFY_IS_EQUAL( (std::numeric_limits<half>::denorm_min)()/half(2), half(0.f) );\n}\n\nvoid test_arithmetic()\n{\n  VERIFY_IS_EQUAL(float(half(2) + half(2)), 4);\n  VERIFY_IS_EQUAL(float(half(2) + half(-2)), 0);\n  VERIFY_IS_APPROX(float(half(0.33333f) + half(0.66667f)), 1.0f);\n  VERIFY_IS_EQUAL(float(half(2.0f) * half(-5.5f)), -11.0f);\n  VERIFY_IS_APPROX(float(half(1.0f) / half(3.0f)), 0.33333f);\n  VERIFY_IS_EQUAL(float(-half(4096.0f)), -4096.0f);\n  VERIFY_IS_EQUAL(float(-half(-4096.0f)), 4096.0f);\n  \n  half x(3);\n  half y = ++x;\n  VERIFY_IS_EQUAL(x, half(4));\n  VERIFY_IS_EQUAL(y, half(4));\n  y = --x;\n  VERIFY_IS_EQUAL(x, half(3));\n  VERIFY_IS_EQUAL(y, half(3));\n  y = x++;\n  VERIFY_IS_EQUAL(x, half(4));\n  VERIFY_IS_EQUAL(y, half(3));\n  y = x--;\n  VERIFY_IS_EQUAL(x, half(3));\n  VERIFY_IS_EQUAL(y, half(4));\n}\n\nvoid test_comparison()\n{\n  VERIFY(half(1.0f) > half(0.5f));\n  VERIFY(half(0.5f) < half(1.0f));\n  VERIFY(!(half(1.0f) < half(0.5f)));\n  VERIFY(!(half(0.5f) > half(1.0f)));\n\n  VERIFY(!(half(4.0f) > half(4.0f)));\n  VERIFY(!(half(4.0f) < half(4.0f)));\n\n  VERIFY(!(half(0.0f) < half(-0.0f)));\n  VERIFY(!(half(-0.0f) < half(0.0f)));\n  VERIFY(!(half(0.0f) > half(-0.0f)));\n  VERIFY(!(half(-0.0f) > half(0.0f)));\n\n  VERIFY(half(0.2f) > half(-1.0f));\n  VERIFY(half(-1.0f) < half(0.2f));\n  VERIFY(half(-16.0f) < half(-15.0f));\n\n  VERIFY(half(1.0f) == half(1.0f));\n  VERIFY(half(1.0f) != half(2.0f));\n\n  // Comparisons with NaNs and infinities.\n#if !EIGEN_COMP_MSVC\n  // Visual Studio errors out on divisions by 0\n  VERIFY(!(half(0.0 / 0.0) == half(0.0 / 0.0)));\n  VERIFY(half(0.0 / 0.0) != half(0.0 / 0.0));\n\n  VERIFY(!(half(1.0) == half(0.0 / 0.0)));\n  VERIFY(!(half(1.0) < half(0.0 / 0.0)));\n  VERIFY(!(half(1.0) > half(0.0 / 0.0)));\n  VERIFY(half(1.0) != half(0.0 / 0.0));\n\n  VERIFY(half(1.0) < half(1.0 / 0.0));\n  VERIFY(half(1.0) > half(-1.0 / 0.0));\n#endif\n}\n\nvoid test_basic_functions()\n{\n  VERIFY_IS_EQUAL(float(numext::abs(half(3.5f))), 3.5f);\n  VERIFY_IS_EQUAL(float(abs(half(3.5f))), 3.5f);\n  VERIFY_IS_EQUAL(float(numext::abs(half(-3.5f))), 3.5f);\n  VERIFY_IS_EQUAL(float(abs(half(-3.5f))), 3.5f);\n\n  VERIFY_IS_EQUAL(float(numext::floor(half(3.5f))), 3.0f);\n  VERIFY_IS_EQUAL(float(floor(half(3.5f))), 3.0f);\n  VERIFY_IS_EQUAL(float(numext::floor(half(-3.5f))), -4.0f);\n  VERIFY_IS_EQUAL(float(floor(half(-3.5f))), -4.0f);\n\n  VERIFY_IS_EQUAL(float(numext::ceil(half(3.5f))), 4.0f);\n  VERIFY_IS_EQUAL(float(ceil(half(3.5f))), 4.0f);\n  VERIFY_IS_EQUAL(float(numext::ceil(half(-3.5f))), -3.0f);\n  VERIFY_IS_EQUAL(float(ceil(half(-3.5f))), -3.0f);\n\n  VERIFY_IS_APPROX(float(numext::sqrt(half(0.0f))), 0.0f);\n  VERIFY_IS_APPROX(float(sqrt(half(0.0f))), 0.0f);\n  VERIFY_IS_APPROX(float(numext::sqrt(half(4.0f))), 2.0f);\n  VERIFY_IS_APPROX(float(sqrt(half(4.0f))), 2.0f);\n\n  VERIFY_IS_APPROX(float(numext::pow(half(0.0f), half(1.0f))), 0.0f);\n  VERIFY_IS_APPROX(float(pow(half(0.0f), half(1.0f))), 0.0f);\n  VERIFY_IS_APPROX(float(numext::pow(half(2.0f), half(2.0f))), 4.0f);\n  VERIFY_IS_APPROX(float(pow(half(2.0f), half(2.0f))), 4.0f);\n\n  VERIFY_IS_EQUAL(float(numext::exp(half(0.0f))), 1.0f);\n  VERIFY_IS_EQUAL(float(exp(half(0.0f))), 1.0f);\n  VERIFY_IS_APPROX(float(numext::exp(half(EIGEN_PI))), 20.f + float(EIGEN_PI));\n  VERIFY_IS_APPROX(float(exp(half(EIGEN_PI))), 20.f + float(EIGEN_PI));\n\n  VERIFY_IS_EQUAL(float(numext::expm1(half(0.0f))), 0.0f);\n  VERIFY_IS_EQUAL(float(expm1(half(0.0f))), 0.0f);\n  VERIFY_IS_APPROX(float(numext::expm1(half(2.0f))), 6.3890561f);\n  VERIFY_IS_APPROX(float(expm1(half(2.0f))), 6.3890561f);\n\n  VERIFY_IS_EQUAL(float(numext::log(half(1.0f))), 0.0f);\n  VERIFY_IS_EQUAL(float(log(half(1.0f))), 0.0f);\n  VERIFY_IS_APPROX(float(numext::log(half(10.0f))), 2.30273f);\n  VERIFY_IS_APPROX(float(log(half(10.0f))), 2.30273f);\n\n  VERIFY_IS_EQUAL(float(numext::log1p(half(0.0f))), 0.0f);\n  VERIFY_IS_EQUAL(float(log1p(half(0.0f))), 0.0f);\n  VERIFY_IS_APPROX(float(numext::log1p(half(10.0f))), 2.3978953f);\n  VERIFY_IS_APPROX(float(log1p(half(10.0f))), 2.3978953f);\n  \n  VERIFY_IS_APPROX(numext::fmod(half(5.3f), half(2.0f)), half(1.3f));\n  VERIFY_IS_APPROX(fmod(half(5.3f), half(2.0f)), half(1.3f));\n  VERIFY_IS_APPROX(numext::fmod(half(-18.5f), half(-4.2f)), half(-1.7f));\n  VERIFY_IS_APPROX(fmod(half(-18.5f), half(-4.2f)), half(-1.7f));\n}\n\nvoid test_trigonometric_functions()\n{\n  VERIFY_IS_APPROX(numext::cos(half(0.0f)), half(cosf(0.0f)));\n  VERIFY_IS_APPROX(cos(half(0.0f)), half(cosf(0.0f)));\n  VERIFY_IS_APPROX(numext::cos(half(EIGEN_PI)), half(cosf(EIGEN_PI)));\n  // VERIFY_IS_APPROX(numext::cos(half(EIGEN_PI/2)), half(cosf(EIGEN_PI/2)));\n  // VERIFY_IS_APPROX(numext::cos(half(3*EIGEN_PI/2)), half(cosf(3*EIGEN_PI/2)));\n  VERIFY_IS_APPROX(numext::cos(half(3.5f)), half(cosf(3.5f)));\n\n  VERIFY_IS_APPROX(numext::sin(half(0.0f)), half(sinf(0.0f)));\n  VERIFY_IS_APPROX(sin(half(0.0f)), half(sinf(0.0f)));\n  //  VERIFY_IS_APPROX(numext::sin(half(EIGEN_PI)), half(sinf(EIGEN_PI)));\n  VERIFY_IS_APPROX(numext::sin(half(EIGEN_PI/2)), half(sinf(EIGEN_PI/2)));\n  VERIFY_IS_APPROX(numext::sin(half(3*EIGEN_PI/2)), half(sinf(3*EIGEN_PI/2)));\n  VERIFY_IS_APPROX(numext::sin(half(3.5f)), half(sinf(3.5f)));\n\n  VERIFY_IS_APPROX(numext::tan(half(0.0f)), half(tanf(0.0f)));\n  VERIFY_IS_APPROX(tan(half(0.0f)), half(tanf(0.0f)));\n  //  VERIFY_IS_APPROX(numext::tan(half(EIGEN_PI)), half(tanf(EIGEN_PI)));\n  //  VERIFY_IS_APPROX(numext::tan(half(EIGEN_PI/2)), half(tanf(EIGEN_PI/2)));\n  //VERIFY_IS_APPROX(numext::tan(half(3*EIGEN_PI/2)), half(tanf(3*EIGEN_PI/2)));\n  VERIFY_IS_APPROX(numext::tan(half(3.5f)), half(tanf(3.5f)));\n}\n\nvoid test_array()\n{\n  typedef Array<half,1,Dynamic> ArrayXh;\n  Index size = internal::random<Index>(1,10);\n  Index i = internal::random<Index>(0,size-1);\n  ArrayXh a1 = ArrayXh::Random(size), a2 = ArrayXh::Random(size);\n  VERIFY_IS_APPROX( a1+a1, half(2)*a1 );\n  VERIFY( (a1.abs() >= half(0)).all() );\n  VERIFY_IS_APPROX( (a1*a1).sqrt(), a1.abs() );\n\n  VERIFY( ((a1.min)(a2) <= (a1.max)(a2)).all() );\n  a1(i) = half(-10.);\n  VERIFY_IS_EQUAL( a1.minCoeff(), half(-10.) );\n  a1(i) = half(10.);\n  VERIFY_IS_EQUAL( a1.maxCoeff(), half(10.) );\n\n  std::stringstream ss;\n  ss << a1;\n}\n\nvoid test_product()\n{\n  typedef Matrix<half,Dynamic,Dynamic> MatrixXh;\n  Index rows  = internal::random<Index>(1,EIGEN_TEST_MAX_SIZE);\n  Index cols  = internal::random<Index>(1,EIGEN_TEST_MAX_SIZE);\n  Index depth = internal::random<Index>(1,EIGEN_TEST_MAX_SIZE);\n  MatrixXh Ah = MatrixXh::Random(rows,depth);\n  MatrixXh Bh = MatrixXh::Random(depth,cols);\n  MatrixXh Ch = MatrixXh::Random(rows,cols);\n  MatrixXf Af = Ah.cast<float>();\n  MatrixXf Bf = Bh.cast<float>();\n  MatrixXf Cf = Ch.cast<float>();\n  VERIFY_IS_APPROX(Ch.noalias()+=Ah*Bh, (Cf.noalias()+=Af*Bf).cast<half>());\n}\n\nEIGEN_DECLARE_TEST(half_float)\n{\n  CALL_SUBTEST(test_numtraits());\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST(test_conversion());\n    CALL_SUBTEST(test_arithmetic());\n    CALL_SUBTEST(test_comparison());\n    CALL_SUBTEST(test_basic_functions());\n    CALL_SUBTEST(test_trigonometric_functions());\n    CALL_SUBTEST(test_array());\n    CALL_SUBTEST(test_product());\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/hessenberg.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2010 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/Eigenvalues>\n\ntemplate<typename Scalar,int Size> void hessenberg(int size = Size)\n{\n  typedef Matrix<Scalar,Size,Size> MatrixType;\n\n  // Test basic functionality: A = U H U* and H is Hessenberg\n  for(int counter = 0; counter < g_repeat; ++counter) {\n    MatrixType m = MatrixType::Random(size,size);\n    HessenbergDecomposition<MatrixType> hess(m);\n    MatrixType Q = hess.matrixQ();\n    MatrixType H = hess.matrixH();\n    VERIFY_IS_APPROX(m, Q * H * Q.adjoint());\n    for(int row = 2; row < size; ++row) {\n      for(int col = 0; col < row-1; ++col) {\n\tVERIFY(H(row,col) == (typename MatrixType::Scalar)0);\n      }\n    }\n  }\n\n  // Test whether compute() and constructor returns same result\n  MatrixType A = MatrixType::Random(size, size);\n  HessenbergDecomposition<MatrixType> cs1;\n  cs1.compute(A);\n  HessenbergDecomposition<MatrixType> cs2(A);\n  VERIFY_IS_EQUAL(cs1.matrixH().eval(), cs2.matrixH().eval());\n  MatrixType cs1Q = cs1.matrixQ();\n  MatrixType cs2Q = cs2.matrixQ();  \n  VERIFY_IS_EQUAL(cs1Q, cs2Q);\n\n  // Test assertions for when used uninitialized\n  HessenbergDecomposition<MatrixType> hessUninitialized;\n  VERIFY_RAISES_ASSERT( hessUninitialized.matrixH() );\n  VERIFY_RAISES_ASSERT( hessUninitialized.matrixQ() );\n  VERIFY_RAISES_ASSERT( hessUninitialized.householderCoefficients() );\n  VERIFY_RAISES_ASSERT( hessUninitialized.packedMatrix() );\n\n  // TODO: Add tests for packedMatrix() and householderCoefficients()\n}\n\nEIGEN_DECLARE_TEST(hessenberg)\n{\n  CALL_SUBTEST_1(( hessenberg<std::complex<double>,1>() ));\n  CALL_SUBTEST_2(( hessenberg<std::complex<double>,2>() ));\n  CALL_SUBTEST_3(( hessenberg<std::complex<float>,4>() ));\n  CALL_SUBTEST_4(( hessenberg<float,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)) ));\n  CALL_SUBTEST_5(( hessenberg<std::complex<double>,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)) ));\n\n  // Test problem size constructors\n  CALL_SUBTEST_6(HessenbergDecomposition<MatrixXf>(10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/householder.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/QR>\n\ntemplate<typename MatrixType> void householder(const MatrixType& m)\n{\n  static bool even = true;\n  even = !even;\n  /* this test covers the following files:\n     Householder.h\n  */\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n  typedef Matrix<Scalar, internal::decrement_size<MatrixType::RowsAtCompileTime>::ret, 1> EssentialVectorType;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> SquareMatrixType;\n  typedef Matrix<Scalar, Dynamic, MatrixType::ColsAtCompileTime> HBlockMatrixType;\n  typedef Matrix<Scalar, Dynamic, 1> HCoeffsVectorType;\n\n  typedef Matrix<Scalar, MatrixType::ColsAtCompileTime, MatrixType::RowsAtCompileTime> TMatrixType;\n  \n  Matrix<Scalar, EIGEN_SIZE_MAX(MatrixType::RowsAtCompileTime,MatrixType::ColsAtCompileTime), 1> _tmp((std::max)(rows,cols));\n  Scalar* tmp = &_tmp.coeffRef(0,0);\n\n  Scalar beta;\n  RealScalar alpha;\n  EssentialVectorType essential;\n\n  VectorType v1 = VectorType::Random(rows), v2;\n  v2 = v1;\n  v1.makeHouseholder(essential, beta, alpha);\n  v1.applyHouseholderOnTheLeft(essential,beta,tmp);\n  VERIFY_IS_APPROX(v1.norm(), v2.norm());\n  if(rows>=2) VERIFY_IS_MUCH_SMALLER_THAN(v1.tail(rows-1).norm(), v1.norm());\n  v1 = VectorType::Random(rows);\n  v2 = v1;\n  v1.applyHouseholderOnTheLeft(essential,beta,tmp);\n  VERIFY_IS_APPROX(v1.norm(), v2.norm());\n\n  // reconstruct householder matrix:\n  SquareMatrixType id, H1, H2;\n  id.setIdentity(rows, rows);\n  H1 = H2 = id;\n  VectorType vv(rows);\n  vv << Scalar(1), essential;\n  H1.applyHouseholderOnTheLeft(essential, beta, tmp);\n  H2.applyHouseholderOnTheRight(essential, beta, tmp);\n  VERIFY_IS_APPROX(H1, H2);\n  VERIFY_IS_APPROX(H1, id - beta * vv*vv.adjoint());\n\n  MatrixType m1(rows, cols),\n             m2(rows, cols);\n\n  v1 = VectorType::Random(rows);\n  if(even) v1.tail(rows-1).setZero();\n  m1.colwise() = v1;\n  m2 = m1;\n  m1.col(0).makeHouseholder(essential, beta, alpha);\n  m1.applyHouseholderOnTheLeft(essential,beta,tmp);\n  VERIFY_IS_APPROX(m1.norm(), m2.norm());\n  if(rows>=2) VERIFY_IS_MUCH_SMALLER_THAN(m1.block(1,0,rows-1,cols).norm(), m1.norm());\n  VERIFY_IS_MUCH_SMALLER_THAN(numext::imag(m1(0,0)), numext::real(m1(0,0)));\n  VERIFY_IS_APPROX(numext::real(m1(0,0)), alpha);\n\n  v1 = VectorType::Random(rows);\n  if(even) v1.tail(rows-1).setZero();\n  SquareMatrixType m3(rows,rows), m4(rows,rows);\n  m3.rowwise() = v1.transpose();\n  m4 = m3;\n  m3.row(0).makeHouseholder(essential, beta, alpha);\n  m3.applyHouseholderOnTheRight(essential.conjugate(),beta,tmp);\n  VERIFY_IS_APPROX(m3.norm(), m4.norm());\n  if(rows>=2) VERIFY_IS_MUCH_SMALLER_THAN(m3.block(0,1,rows,rows-1).norm(), m3.norm());\n  VERIFY_IS_MUCH_SMALLER_THAN(numext::imag(m3(0,0)), numext::real(m3(0,0)));\n  VERIFY_IS_APPROX(numext::real(m3(0,0)), alpha);\n\n  // test householder sequence on the left with a shift\n\n  Index shift = internal::random<Index>(0, std::max<Index>(rows-2,0));\n  Index brows = rows - shift;\n  m1.setRandom(rows, cols);\n  HBlockMatrixType hbm = m1.block(shift,0,brows,cols);\n  HouseholderQR<HBlockMatrixType> qr(hbm);\n  m2 = m1;\n  m2.block(shift,0,brows,cols) = qr.matrixQR();\n  HCoeffsVectorType hc = qr.hCoeffs().conjugate();\n  HouseholderSequence<MatrixType, HCoeffsVectorType> hseq(m2, hc);\n  hseq.setLength(hc.size()).setShift(shift);\n  VERIFY(hseq.length() == hc.size());\n  VERIFY(hseq.shift() == shift);\n  \n  MatrixType m5 = m2;\n  m5.block(shift,0,brows,cols).template triangularView<StrictlyLower>().setZero();\n  VERIFY_IS_APPROX(hseq * m5, m1); // test applying hseq directly\n  m3 = hseq;\n  VERIFY_IS_APPROX(m3 * m5, m1); // test evaluating hseq to a dense matrix, then applying\n  \n  SquareMatrixType hseq_mat = hseq;\n  SquareMatrixType hseq_mat_conj = hseq.conjugate();\n  SquareMatrixType hseq_mat_adj = hseq.adjoint();\n  SquareMatrixType hseq_mat_trans = hseq.transpose();\n  SquareMatrixType m6 = SquareMatrixType::Random(rows, rows);\n  VERIFY_IS_APPROX(hseq_mat.adjoint(),    hseq_mat_adj);\n  VERIFY_IS_APPROX(hseq_mat.conjugate(),  hseq_mat_conj);\n  VERIFY_IS_APPROX(hseq_mat.transpose(),  hseq_mat_trans);\n  VERIFY_IS_APPROX(hseq * m6,             hseq_mat * m6);\n  VERIFY_IS_APPROX(hseq.adjoint() * m6,   hseq_mat_adj * m6);\n  VERIFY_IS_APPROX(hseq.conjugate() * m6, hseq_mat_conj * m6);\n  VERIFY_IS_APPROX(hseq.transpose() * m6, hseq_mat_trans * m6);\n  VERIFY_IS_APPROX(m6 * hseq,             m6 * hseq_mat);\n  VERIFY_IS_APPROX(m6 * hseq.adjoint(),   m6 * hseq_mat_adj);\n  VERIFY_IS_APPROX(m6 * hseq.conjugate(), m6 * hseq_mat_conj);\n  VERIFY_IS_APPROX(m6 * hseq.transpose(), m6 * hseq_mat_trans);\n\n  // test householder sequence on the right with a shift\n\n  TMatrixType tm2 = m2.transpose();\n  HouseholderSequence<TMatrixType, HCoeffsVectorType, OnTheRight> rhseq(tm2, hc);\n  rhseq.setLength(hc.size()).setShift(shift);\n  VERIFY_IS_APPROX(rhseq * m5, m1); // test applying rhseq directly\n  m3 = rhseq;\n  VERIFY_IS_APPROX(m3 * m5, m1); // test evaluating rhseq to a dense matrix, then applying\n}\n\nEIGEN_DECLARE_TEST(householder)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( householder(Matrix<double,2,2>()) );\n    CALL_SUBTEST_2( householder(Matrix<float,2,3>()) );\n    CALL_SUBTEST_3( householder(Matrix<double,3,5>()) );\n    CALL_SUBTEST_4( householder(Matrix<float,4,4>()) );\n    CALL_SUBTEST_5( householder(MatrixXd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE),internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_6( householder(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE),internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_7( householder(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE),internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_8( householder(Matrix<double,1,1>()) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/incomplete_cholesky.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015-2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n// #define EIGEN_DONT_VECTORIZE\n// #define EIGEN_MAX_ALIGN_BYTES 0\n#include \"sparse_solver.h\"\n#include <Eigen/IterativeLinearSolvers>\n#include <unsupported/Eigen/IterativeSolvers>\n\ntemplate<typename T, typename I_> void test_incomplete_cholesky_T()\n{\n  typedef SparseMatrix<T,0,I_> SparseMatrixType;\n  ConjugateGradient<SparseMatrixType, Lower, IncompleteCholesky<T, Lower, AMDOrdering<I_> > >        cg_illt_lower_amd;\n  ConjugateGradient<SparseMatrixType, Lower, IncompleteCholesky<T, Lower, NaturalOrdering<I_> > >    cg_illt_lower_nat;\n  ConjugateGradient<SparseMatrixType, Upper, IncompleteCholesky<T, Upper, AMDOrdering<I_> > >        cg_illt_upper_amd;\n  ConjugateGradient<SparseMatrixType, Upper, IncompleteCholesky<T, Upper, NaturalOrdering<I_> > >    cg_illt_upper_nat;\n  ConjugateGradient<SparseMatrixType, Upper|Lower, IncompleteCholesky<T, Lower, AMDOrdering<I_> > >  cg_illt_uplo_amd;\n  \n\n  CALL_SUBTEST( check_sparse_spd_solving(cg_illt_lower_amd) );\n  CALL_SUBTEST( check_sparse_spd_solving(cg_illt_lower_nat) );\n  CALL_SUBTEST( check_sparse_spd_solving(cg_illt_upper_amd) );\n  CALL_SUBTEST( check_sparse_spd_solving(cg_illt_upper_nat) );\n  CALL_SUBTEST( check_sparse_spd_solving(cg_illt_uplo_amd) );\n}\n\ntemplate<int>\nvoid bug1150()\n{\n  // regression for bug 1150\n  for(int N = 1; N<20; ++N)\n  {\n    Eigen::MatrixXd b( N, N );\n    b.setOnes();\n\n    Eigen::SparseMatrix<double> m( N, N );\n    m.reserve(Eigen::VectorXi::Constant(N,4));\n    for( int i = 0; i < N; ++i )\n    {\n        m.insert( i, i ) = 1;\n        m.coeffRef( i, i / 2 ) = 2;\n        m.coeffRef( i, i / 3 ) = 2;\n        m.coeffRef( i, i / 4 ) = 2;\n    }\n\n    Eigen::SparseMatrix<double> A;\n    A = m * m.transpose();\n\n    Eigen::ConjugateGradient<Eigen::SparseMatrix<double>,\n        Eigen::Lower | Eigen::Upper,\n        Eigen::IncompleteCholesky<double> > solver( A );\n    VERIFY(solver.preconditioner().info() == Eigen::Success);\n    VERIFY(solver.info() == Eigen::Success);\n  }\n}\n\nEIGEN_DECLARE_TEST(incomplete_cholesky)\n{\n  CALL_SUBTEST_1(( test_incomplete_cholesky_T<double,int>() ));\n  CALL_SUBTEST_2(( test_incomplete_cholesky_T<std::complex<double>, int>() ));\n  CALL_SUBTEST_3(( test_incomplete_cholesky_T<double,long int>() ));\n\n  CALL_SUBTEST_1(( bug1150<0>() ));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/indexed_view.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2017 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifdef EIGEN_TEST_PART_2\n// Make sure we also check c++11 max implementation\n#define EIGEN_MAX_CPP_VER 11\n#endif\n\n#ifdef EIGEN_TEST_PART_3\n// Make sure we also check c++98 max implementation\n#define EIGEN_MAX_CPP_VER 03\n\n// We need to disable this warning when compiling with c++11 while limiting Eigen to c++98\n// Ideally we would rather configure the compiler to build in c++98 mode but this needs\n// to be done at the CMakeLists.txt level.\n#if defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8))\n  #pragma GCC diagnostic ignored \"-Wdeprecated\"\n#endif\n\n#if defined(__GNUC__) && (__GNUC__ >=9)\n  #pragma GCC diagnostic ignored \"-Wdeprecated-copy\"\n#endif\n#if defined(__clang__) && (__clang_major__ >= 10)\n  #pragma clang diagnostic ignored \"-Wdeprecated-copy\"\n#endif\n\n#endif\n\n#include <valarray>\n#include <vector>\n#include \"main.h\"\n\n#if EIGEN_HAS_CXX11\n#include <array>\n#endif\n\ntypedef std::pair<Index,Index> IndexPair;\n\nint encode(Index i, Index j) {\n  return int(i*100 + j);\n}\n\nIndexPair decode(Index ij) {\n  return IndexPair(ij / 100, ij % 100);\n}\n\ntemplate<typename T>\nbool match(const T& xpr, std::string ref, std::string str_xpr = \"\") {\n  EIGEN_UNUSED_VARIABLE(str_xpr);\n  std::stringstream str;\n  str << xpr;\n  if(!(str.str() == ref))\n    std::cout << str_xpr << \"\\n\" << xpr << \"\\n\\n\";\n  return str.str() == ref;\n}\n\n#define MATCH(X,R) match(X, R, #X)\n\ntemplate<typename T1,typename T2>\ntypename internal::enable_if<internal::is_same<T1,T2>::value,bool>::type\nis_same_eq(const T1& a, const T2& b)\n{\n  return (a == b).all();\n}\n\ntemplate<typename T1,typename T2>\nbool is_same_seq(const T1& a, const T2& b)\n{\n  bool ok = a.first()==b.first() && a.size() == b.size() && Index(a.incrObject())==Index(b.incrObject());;\n  if(!ok)\n  {\n    std::cerr << \"seqN(\" << a.first() << \", \" << a.size() << \", \" << Index(a.incrObject()) << \") != \";\n    std::cerr << \"seqN(\" << b.first() << \", \" << b.size() << \", \" << Index(b.incrObject()) << \")\\n\";\n  }\n  return ok;\n}\n\ntemplate<typename T1,typename T2>\ntypename internal::enable_if<internal::is_same<T1,T2>::value,bool>::type\nis_same_seq_type(const T1& a, const T2& b)\n{\n  return is_same_seq(a,b);\n}\n\n\n\n#define VERIFY_EQ_INT(A,B) VERIFY_IS_APPROX(int(A),int(B))\n\n// C++03 does not allow local or unnamed enums as index\nenum DummyEnum { XX=0, YY=1 };\n\nvoid check_indexed_view()\n{\n  Index n = 10;\n\n  ArrayXd a = ArrayXd::LinSpaced(n,0,n-1);\n  Array<double,1,Dynamic> b = a.transpose();\n\n  #if EIGEN_COMP_CXXVER>=14\n  ArrayXXi A = ArrayXXi::NullaryExpr(n,n, std::ref(encode));\n  #else\n  ArrayXXi A = ArrayXXi::NullaryExpr(n,n, std::ptr_fun(&encode));\n  #endif\n\n  for(Index i=0; i<n; ++i)\n    for(Index j=0; j<n; ++j)\n      VERIFY( decode(A(i,j)) == IndexPair(i,j) );\n\n  Array4i eii(4); eii << 3, 1, 6, 5;\n  std::valarray<int> vali(4); Map<ArrayXi>(&vali[0],4) = eii;\n  std::vector<int> veci(4); Map<ArrayXi>(veci.data(),4) = eii;\n\n  VERIFY( MATCH( A(3, seq(9,3,-1)),\n    \"309  308  307  306  305  304  303\")\n  );\n\n  VERIFY( MATCH( A(seqN(2,5), seq(9,3,-1)),\n    \"209  208  207  206  205  204  203\\n\"\n    \"309  308  307  306  305  304  303\\n\"\n    \"409  408  407  406  405  404  403\\n\"\n    \"509  508  507  506  505  504  503\\n\"\n    \"609  608  607  606  605  604  603\")\n  );\n\n  VERIFY( MATCH( A(seqN(2,5), 5),\n    \"205\\n\"\n    \"305\\n\"\n    \"405\\n\"\n    \"505\\n\"\n    \"605\")\n  );\n\n  VERIFY( MATCH( A(seqN(last,5,-1), seq(2,last)),\n    \"902  903  904  905  906  907  908  909\\n\"\n    \"802  803  804  805  806  807  808  809\\n\"\n    \"702  703  704  705  706  707  708  709\\n\"\n    \"602  603  604  605  606  607  608  609\\n\"\n    \"502  503  504  505  506  507  508  509\")\n  );\n\n  VERIFY( MATCH( A(eii, veci),\n    \"303  301  306  305\\n\"\n    \"103  101  106  105\\n\"\n    \"603  601  606  605\\n\"\n    \"503  501  506  505\")\n  );\n\n  VERIFY( MATCH( A(eii, all),\n    \"300  301  302  303  304  305  306  307  308  309\\n\"\n    \"100  101  102  103  104  105  106  107  108  109\\n\"\n    \"600  601  602  603  604  605  606  607  608  609\\n\"\n    \"500  501  502  503  504  505  506  507  508  509\")\n  );\n\n  // take row number 3, and repeat it 5 times\n  VERIFY( MATCH( A(seqN(3,5,0), all),\n    \"300  301  302  303  304  305  306  307  308  309\\n\"\n    \"300  301  302  303  304  305  306  307  308  309\\n\"\n    \"300  301  302  303  304  305  306  307  308  309\\n\"\n    \"300  301  302  303  304  305  306  307  308  309\\n\"\n    \"300  301  302  303  304  305  306  307  308  309\")\n  );\n\n  VERIFY( MATCH( a(seqN(3,3),0), \"3\\n4\\n5\" ) );\n  VERIFY( MATCH( a(seq(3,5)), \"3\\n4\\n5\" ) );\n  VERIFY( MATCH( a(seqN(3,3,1)), \"3\\n4\\n5\" ) );\n  VERIFY( MATCH( a(seqN(5,3,-1)), \"5\\n4\\n3\" ) );\n\n  VERIFY( MATCH( b(0,seqN(3,3)), \"3  4  5\" ) );\n  VERIFY( MATCH( b(seq(3,5)), \"3  4  5\" ) );\n  VERIFY( MATCH( b(seqN(3,3,1)), \"3  4  5\" ) );\n  VERIFY( MATCH( b(seqN(5,3,-1)), \"5  4  3\" ) );\n\n  VERIFY( MATCH( b(all), \"0  1  2  3  4  5  6  7  8  9\" ) );\n  VERIFY( MATCH( b(eii), \"3  1  6  5\" ) );\n\n  Array44i B;\n  B.setRandom();\n  VERIFY( (A(seqN(2,5), 5)).ColsAtCompileTime == 1);\n  VERIFY( (A(seqN(2,5), 5)).RowsAtCompileTime == Dynamic);\n  VERIFY_EQ_INT( (A(seqN(2,5), 5)).InnerStrideAtCompileTime , A.InnerStrideAtCompileTime);\n  VERIFY_EQ_INT( (A(seqN(2,5), 5)).OuterStrideAtCompileTime , A.col(5).OuterStrideAtCompileTime);\n\n  VERIFY_EQ_INT( (A(5,seqN(2,5))).InnerStrideAtCompileTime , A.row(5).InnerStrideAtCompileTime);\n  VERIFY_EQ_INT( (A(5,seqN(2,5))).OuterStrideAtCompileTime , A.row(5).OuterStrideAtCompileTime);\n  VERIFY_EQ_INT( (B(1,seqN(1,2))).InnerStrideAtCompileTime , B.row(1).InnerStrideAtCompileTime);\n  VERIFY_EQ_INT( (B(1,seqN(1,2))).OuterStrideAtCompileTime , B.row(1).OuterStrideAtCompileTime);\n\n  VERIFY_EQ_INT( (A(seqN(2,5), seq(1,3))).InnerStrideAtCompileTime , A.InnerStrideAtCompileTime);\n  VERIFY_EQ_INT( (A(seqN(2,5), seq(1,3))).OuterStrideAtCompileTime , A.OuterStrideAtCompileTime);\n  VERIFY_EQ_INT( (B(seqN(1,2), seq(1,3))).InnerStrideAtCompileTime , B.InnerStrideAtCompileTime);\n  VERIFY_EQ_INT( (B(seqN(1,2), seq(1,3))).OuterStrideAtCompileTime , B.OuterStrideAtCompileTime);\n  VERIFY_EQ_INT( (A(seqN(2,5,2), seq(1,3,2))).InnerStrideAtCompileTime , Dynamic);\n  VERIFY_EQ_INT( (A(seqN(2,5,2), seq(1,3,2))).OuterStrideAtCompileTime , Dynamic);\n  VERIFY_EQ_INT( (A(seqN(2,5,fix<2>), seq(1,3,fix<3>))).InnerStrideAtCompileTime , 2);\n  VERIFY_EQ_INT( (A(seqN(2,5,fix<2>), seq(1,3,fix<3>))).OuterStrideAtCompileTime , Dynamic);\n  VERIFY_EQ_INT( (B(seqN(1,2,fix<2>), seq(1,3,fix<3>))).InnerStrideAtCompileTime , 2);\n  VERIFY_EQ_INT( (B(seqN(1,2,fix<2>), seq(1,3,fix<3>))).OuterStrideAtCompileTime , 3*4);\n\n  VERIFY_EQ_INT( (A(seqN(2,fix<5>), seqN(1,fix<3>))).RowsAtCompileTime, 5);\n  VERIFY_EQ_INT( (A(seqN(2,fix<5>), seqN(1,fix<3>))).ColsAtCompileTime, 3);\n  VERIFY_EQ_INT( (A(seqN(2,fix<5>(5)), seqN(1,fix<3>(3)))).RowsAtCompileTime, 5);\n  VERIFY_EQ_INT( (A(seqN(2,fix<5>(5)), seqN(1,fix<3>(3)))).ColsAtCompileTime, 3);\n  VERIFY_EQ_INT( (A(seqN(2,fix<Dynamic>(5)), seqN(1,fix<Dynamic>(3)))).RowsAtCompileTime, Dynamic);\n  VERIFY_EQ_INT( (A(seqN(2,fix<Dynamic>(5)), seqN(1,fix<Dynamic>(3)))).ColsAtCompileTime, Dynamic);\n  VERIFY_EQ_INT( (A(seqN(2,fix<Dynamic>(5)), seqN(1,fix<Dynamic>(3)))).rows(), 5);\n  VERIFY_EQ_INT( (A(seqN(2,fix<Dynamic>(5)), seqN(1,fix<Dynamic>(3)))).cols(), 3);\n\n  VERIFY( is_same_seq_type( seqN(2,5,fix<-1>), seqN(2,5,fix<-1>(-1)) ) );\n  VERIFY( is_same_seq_type( seqN(2,5), seqN(2,5,fix<1>(1)) ) );\n  VERIFY( is_same_seq_type( seqN(2,5,3), seqN(2,5,fix<DynamicIndex>(3)) ) );\n  VERIFY( is_same_seq_type( seq(2,7,fix<3>), seqN(2,2,fix<3>) ) );\n  VERIFY( is_same_seq_type( seqN(2,fix<Dynamic>(5),3), seqN(2,5,fix<DynamicIndex>(3)) ) );\n  VERIFY( is_same_seq_type( seqN(2,fix<5>(5),fix<-2>), seqN(2,fix<5>,fix<-2>()) ) );\n\n  VERIFY( is_same_seq_type( seq(2,fix<5>), seqN(2,4) ) );\n#if EIGEN_HAS_CXX11\n  VERIFY( is_same_seq_type( seq(fix<2>,fix<5>), seqN(fix<2>,fix<4>) ) );\n  VERIFY( is_same_seq( seqN(2,std::integral_constant<int,5>(),std::integral_constant<int,-2>()), seqN(2,fix<5>,fix<-2>()) ) );\n  VERIFY( is_same_seq( seq(std::integral_constant<int,1>(),std::integral_constant<int,5>(),std::integral_constant<int,2>()),\n                       seq(fix<1>,fix<5>,fix<2>()) ) );\n  VERIFY( is_same_seq_type( seqN(2,std::integral_constant<int,5>(),std::integral_constant<int,-2>()), seqN(2,fix<5>,fix<-2>()) ) );\n  VERIFY( is_same_seq_type( seq(std::integral_constant<int,1>(),std::integral_constant<int,5>(),std::integral_constant<int,2>()),\n                            seq(fix<1>,fix<5>,fix<2>()) ) );\n\n  VERIFY( is_same_seq_type( seqN(2,std::integral_constant<int,5>()), seqN(2,fix<5>) ) );\n  VERIFY( is_same_seq_type( seq(std::integral_constant<int,1>(),std::integral_constant<int,5>()), seq(fix<1>,fix<5>) ) );\n#else\n  // sorry, no compile-time size recovery in c++98/03\n  VERIFY( is_same_seq( seq(fix<2>,fix<5>), seqN(fix<2>,fix<4>) ) );\n#endif\n\n  VERIFY( (A(seqN(2,fix<5>), 5)).RowsAtCompileTime == 5);\n  VERIFY( (A(4, all)).ColsAtCompileTime == Dynamic);\n  VERIFY( (A(4, all)).RowsAtCompileTime == 1);\n  VERIFY( (B(1, all)).ColsAtCompileTime == 4);\n  VERIFY( (B(1, all)).RowsAtCompileTime == 1);\n  VERIFY( (B(all,1)).ColsAtCompileTime == 1);\n  VERIFY( (B(all,1)).RowsAtCompileTime == 4);\n\n  VERIFY(int( (A(all, eii)).ColsAtCompileTime) == int(eii.SizeAtCompileTime));\n  VERIFY_EQ_INT( (A(eii, eii)).Flags&DirectAccessBit, (unsigned int)(0));\n  VERIFY_EQ_INT( (A(eii, eii)).InnerStrideAtCompileTime, 0);\n  VERIFY_EQ_INT( (A(eii, eii)).OuterStrideAtCompileTime, 0);\n\n  VERIFY_IS_APPROX( A(seq(n-1,2,-2), seqN(n-1-6,3,-1)), A(seq(last,2,fix<-2>), seqN(last-6,3,fix<-1>)) );\n\n  VERIFY_IS_APPROX( A(seq(n-1,2,-2), seqN(n-1-6,4)), A(seq(last,2,-2), seqN(last-6,4)) );\n  VERIFY_IS_APPROX( A(seq(n-1-6,n-1-2), seqN(n-1-6,4)), A(seq(last-6,last-2), seqN(6+last-6-6,4)) );\n  VERIFY_IS_APPROX( A(seq((n-1)/2,(n)/2+3), seqN(2,4)), A(seq(last/2,(last+1)/2+3), seqN(last+2-last,4)) );\n  VERIFY_IS_APPROX( A(seq(n-2,2,-2), seqN(n-8,4)), A(seq(lastp1-2,2,-2), seqN(lastp1-8,4)) );\n\n  // Check all combinations of seq:\n  VERIFY_IS_APPROX( A(seq(1,n-1-2,2), seq(1,n-1-2,2)), A(seq(1,last-2,2), seq(1,last-2,fix<2>)) );\n  VERIFY_IS_APPROX( A(seq(n-1-5,n-1-2,2), seq(n-1-5,n-1-2,2)), A(seq(last-5,last-2,2), seq(last-5,last-2,fix<2>)) );\n  VERIFY_IS_APPROX( A(seq(n-1-5,7,2), seq(n-1-5,7,2)), A(seq(last-5,7,2), seq(last-5,7,fix<2>)) );\n  VERIFY_IS_APPROX( A(seq(1,n-1-2), seq(n-1-5,7)), A(seq(1,last-2), seq(last-5,7)) );\n  VERIFY_IS_APPROX( A(seq(n-1-5,n-1-2), seq(n-1-5,n-1-2)), A(seq(last-5,last-2), seq(last-5,last-2)) );\n\n  VERIFY_IS_APPROX( A.col(A.cols()-1), A(all,last) );\n  VERIFY_IS_APPROX( A(A.rows()-2, A.cols()/2), A(last-1, lastp1/2) );\n  VERIFY_IS_APPROX( a(a.size()-2), a(last-1) );\n  VERIFY_IS_APPROX( a(a.size()/2), a((last+1)/2) );\n\n  // Check fall-back to Block\n  {\n    VERIFY( is_same_eq(A.col(0), A(all,0)) );\n    VERIFY( is_same_eq(A.row(0), A(0,all)) );\n    VERIFY( is_same_eq(A.block(0,0,2,2), A(seqN(0,2),seq(0,1))) );\n    VERIFY( is_same_eq(A.middleRows(2,4), A(seqN(2,4),all)) );\n    VERIFY( is_same_eq(A.middleCols(2,4), A(all,seqN(2,4))) );\n\n    VERIFY( is_same_eq(A.col(A.cols()-1), A(all,last)) );\n\n    const ArrayXXi& cA(A);\n    VERIFY( is_same_eq(cA.col(0), cA(all,0)) );\n    VERIFY( is_same_eq(cA.row(0), cA(0,all)) );\n    VERIFY( is_same_eq(cA.block(0,0,2,2), cA(seqN(0,2),seq(0,1))) );\n    VERIFY( is_same_eq(cA.middleRows(2,4), cA(seqN(2,4),all)) );\n    VERIFY( is_same_eq(cA.middleCols(2,4), cA(all,seqN(2,4))) );\n\n    VERIFY( is_same_eq(a.head(4), a(seq(0,3))) );\n    VERIFY( is_same_eq(a.tail(4), a(seqN(last-3,4))) );\n    VERIFY( is_same_eq(a.tail(4), a(seq(lastp1-4,last))) );\n    VERIFY( is_same_eq(a.segment<4>(3), a(seqN(3,fix<4>))) );\n  }\n\n  ArrayXXi A1=A, A2 = ArrayXXi::Random(4,4);\n  ArrayXi range25(4); range25 << 3,2,4,5;\n  A1(seqN(3,4),seq(2,5)) = A2;\n  VERIFY_IS_APPROX( A1.block(3,2,4,4), A2 );\n  A1 = A;\n  A2.setOnes();\n  A1(seq(6,3,-1),range25) = A2;\n  VERIFY_IS_APPROX( A1.block(3,2,4,4), A2 );\n\n  // check reverse\n  {\n    VERIFY( is_same_seq_type( seq(3,7).reverse(), seqN(7,5,fix<-1>)  ) );\n    VERIFY( is_same_seq_type( seq(7,3,fix<-2>).reverse(), seqN(3,3,fix<2>)  ) );\n    VERIFY_IS_APPROX( a(seqN(2,last/2).reverse()), a(seqN(2+(last/2-1)*1,last/2,fix<-1>)) );\n    VERIFY_IS_APPROX( a(seqN(last/2,fix<4>).reverse()),a(seqN(last/2,fix<4>)).reverse() );\n    VERIFY_IS_APPROX( A(seq(last-5,last-1,2).reverse(), seqN(last-3,3,fix<-2>).reverse()),\n                      A(seq(last-5,last-1,2), seqN(last-3,3,fix<-2>)).reverse() );\n  }\n\n#if EIGEN_HAS_CXX11\n  // check lastN\n  VERIFY_IS_APPROX( a(lastN(3)), a.tail(3) );\n  VERIFY( MATCH( a(lastN(3)), \"7\\n8\\n9\" ) );\n  VERIFY_IS_APPROX( a(lastN(fix<3>())), a.tail<3>() );\n  VERIFY( MATCH( a(lastN(3,2)), \"5\\n7\\n9\" ) );\n  VERIFY( MATCH( a(lastN(3,fix<2>())), \"5\\n7\\n9\" ) );\n  VERIFY( a(lastN(fix<3>())).SizeAtCompileTime == 3 );\n\n  VERIFY( (A(all, std::array<int,4>{{1,3,2,4}})).ColsAtCompileTime == 4);\n\n  VERIFY_IS_APPROX( (A(std::array<int,3>{{1,3,5}}, std::array<int,4>{{9,6,3,0}})), A(seqN(1,3,2), seqN(9,4,-3)) );\n\n#if EIGEN_HAS_STATIC_ARRAY_TEMPLATE\n  VERIFY_IS_APPROX( A({3, 1, 6, 5}, all), A(std::array<int,4>{{3, 1, 6, 5}}, all) );\n  VERIFY_IS_APPROX( A(all,{3, 1, 6, 5}), A(all,std::array<int,4>{{3, 1, 6, 5}}) );\n  VERIFY_IS_APPROX( A({1,3,5},{3, 1, 6, 5}), A(std::array<int,3>{{1,3,5}},std::array<int,4>{{3, 1, 6, 5}}) );\n\n  VERIFY_IS_EQUAL( A({1,3,5},{3, 1, 6, 5}).RowsAtCompileTime, 3 );\n  VERIFY_IS_EQUAL( A({1,3,5},{3, 1, 6, 5}).ColsAtCompileTime, 4 );\n\n  VERIFY_IS_APPROX( a({3, 1, 6, 5}), a(std::array<int,4>{{3, 1, 6, 5}}) );\n  VERIFY_IS_EQUAL( a({1,3,5}).SizeAtCompileTime, 3 );\n\n  VERIFY_IS_APPROX( b({3, 1, 6, 5}), b(std::array<int,4>{{3, 1, 6, 5}}) );\n  VERIFY_IS_EQUAL( b({1,3,5}).SizeAtCompileTime, 3 );\n#endif\n\n#endif\n\n  // check mat(i,j) with weird types for i and j\n  {\n    VERIFY_IS_APPROX( A(B.RowsAtCompileTime-1, 1), A(3,1) );\n    VERIFY_IS_APPROX( A(B.RowsAtCompileTime, 1), A(4,1) );\n    VERIFY_IS_APPROX( A(B.RowsAtCompileTime-1, B.ColsAtCompileTime-1), A(3,3) );\n    VERIFY_IS_APPROX( A(B.RowsAtCompileTime, B.ColsAtCompileTime), A(4,4) );\n    const Index I_ = 3, J_ = 4;\n    VERIFY_IS_APPROX( A(I_,J_), A(3,4) );\n  }\n\n  // check extended block API\n  {\n    VERIFY( is_same_eq( A.block<3,4>(1,1), A.block(1,1,fix<3>,fix<4>)) );\n    VERIFY( is_same_eq( A.block<3,4>(1,1,3,4), A.block(1,1,fix<3>(),fix<4>(4))) );\n    VERIFY( is_same_eq( A.block<3,Dynamic>(1,1,3,4), A.block(1,1,fix<3>,4)) );\n    VERIFY( is_same_eq( A.block<Dynamic,4>(1,1,3,4), A.block(1,1,fix<Dynamic>(3),fix<4>)) );\n    VERIFY( is_same_eq( A.block(1,1,3,4), A.block(1,1,fix<Dynamic>(3),fix<Dynamic>(4))) );\n\n    VERIFY( is_same_eq( A.topLeftCorner<3,4>(), A.topLeftCorner(fix<3>,fix<4>)) );\n    VERIFY( is_same_eq( A.bottomLeftCorner<3,4>(), A.bottomLeftCorner(fix<3>,fix<4>)) );\n    VERIFY( is_same_eq( A.bottomRightCorner<3,4>(), A.bottomRightCorner(fix<3>,fix<4>)) );\n    VERIFY( is_same_eq( A.topRightCorner<3,4>(), A.topRightCorner(fix<3>,fix<4>)) );\n\n    VERIFY( is_same_eq( A.leftCols<3>(), A.leftCols(fix<3>)) );\n    VERIFY( is_same_eq( A.rightCols<3>(), A.rightCols(fix<3>)) );\n    VERIFY( is_same_eq( A.middleCols<3>(1), A.middleCols(1,fix<3>)) );\n\n    VERIFY( is_same_eq( A.topRows<3>(), A.topRows(fix<3>)) );\n    VERIFY( is_same_eq( A.bottomRows<3>(), A.bottomRows(fix<3>)) );\n    VERIFY( is_same_eq( A.middleRows<3>(1), A.middleRows(1,fix<3>)) );\n\n    VERIFY( is_same_eq( a.segment<3>(1), a.segment(1,fix<3>)) );\n    VERIFY( is_same_eq( a.head<3>(), a.head(fix<3>)) );\n    VERIFY( is_same_eq( a.tail<3>(), a.tail(fix<3>)) );\n\n    const ArrayXXi& cA(A);\n    VERIFY( is_same_eq( cA.block<Dynamic,4>(1,1,3,4), cA.block(1,1,fix<Dynamic>(3),fix<4>)) );\n\n    VERIFY( is_same_eq( cA.topLeftCorner<3,4>(), cA.topLeftCorner(fix<3>,fix<4>)) );\n    VERIFY( is_same_eq( cA.bottomLeftCorner<3,4>(), cA.bottomLeftCorner(fix<3>,fix<4>)) );\n    VERIFY( is_same_eq( cA.bottomRightCorner<3,4>(), cA.bottomRightCorner(fix<3>,fix<4>)) );\n    VERIFY( is_same_eq( cA.topRightCorner<3,4>(), cA.topRightCorner(fix<3>,fix<4>)) );\n\n    VERIFY( is_same_eq( cA.leftCols<3>(), cA.leftCols(fix<3>)) );\n    VERIFY( is_same_eq( cA.rightCols<3>(), cA.rightCols(fix<3>)) );\n    VERIFY( is_same_eq( cA.middleCols<3>(1), cA.middleCols(1,fix<3>)) );\n\n    VERIFY( is_same_eq( cA.topRows<3>(), cA.topRows(fix<3>)) );\n    VERIFY( is_same_eq( cA.bottomRows<3>(), cA.bottomRows(fix<3>)) );\n    VERIFY( is_same_eq( cA.middleRows<3>(1), cA.middleRows(1,fix<3>)) );\n  }\n\n  // Check compilation of enums as index type:\n  a(XX) = 1;\n  A(XX,YY) = 1;\n  // Anonymous enums only work with C++11\n#if EIGEN_HAS_CXX11\n  enum { X=0, Y=1 };\n  a(X) = 1;\n  A(X,Y) = 1;\n  A(XX,Y) = 1;\n  A(X,YY) = 1;\n#endif\n\n  // Check compilation of varying integer types as index types:\n  Index i = n/2;\n  short i_short(i);\n  std::size_t i_sizet(i);\n  VERIFY_IS_EQUAL( a(i), a.coeff(i_short) );\n  VERIFY_IS_EQUAL( a(i), a.coeff(i_sizet) );\n\n  VERIFY_IS_EQUAL( A(i,i), A.coeff(i_short, i_short) );\n  VERIFY_IS_EQUAL( A(i,i), A.coeff(i_short, i) );\n  VERIFY_IS_EQUAL( A(i,i), A.coeff(i, i_short) );\n  VERIFY_IS_EQUAL( A(i,i), A.coeff(i, i_sizet) );\n  VERIFY_IS_EQUAL( A(i,i), A.coeff(i_sizet, i) );\n  VERIFY_IS_EQUAL( A(i,i), A.coeff(i_sizet, i_short) );\n  VERIFY_IS_EQUAL( A(i,i), A.coeff(5, i_sizet) );\n\n  // Regression test for Max{Rows,Cols}AtCompileTime\n  {\n    Matrix3i A3 = Matrix3i::Random();\n    ArrayXi ind(5); ind << 1,1,1,1,1;\n    VERIFY_IS_EQUAL( A3(ind,ind).eval(), MatrixXi::Constant(5,5,A3(1,1)) );\n  }\n\n  // Regression for bug 1736\n  {\n    VERIFY_IS_APPROX(A(all, eii).col(0).eval(), A.col(eii(0)));\n    A(all, eii).col(0) = A.col(eii(0));\n  }\n\n  // bug 1815: IndexedView should allow linear access\n  {\n    VERIFY( MATCH( b(eii)(0), \"3\" ) );\n    VERIFY( MATCH( a(eii)(0), \"3\" ) );\n    VERIFY( MATCH( A(1,eii)(0), \"103\"));\n    VERIFY( MATCH( A(eii,1)(0), \"301\"));\n    VERIFY( MATCH( A(1,all)(1), \"101\"));\n    VERIFY( MATCH( A(all,1)(1), \"101\"));\n  }\n\n#if EIGEN_HAS_CXX11\n  //Bug IndexView with a single static row should be RowMajor:\n  {\n    // A(1, seq(0,2,1)).cwiseAbs().colwise().replicate(2).eval();\n    STATIC_CHECK(( (internal::evaluator<decltype( A(1,seq(0,2,1)) )>::Flags & RowMajorBit) == RowMajorBit ));\n  }\n#endif\n\n}\n\nEIGEN_DECLARE_TEST(indexed_view)\n{\n//   for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( check_indexed_view() );\n    CALL_SUBTEST_2( check_indexed_view() );\n    CALL_SUBTEST_3( check_indexed_view() );\n//   }\n\n  // static checks of some internals:\n  STATIC_CHECK(( internal::is_valid_index_type<int>::value ));\n  STATIC_CHECK(( internal::is_valid_index_type<unsigned int>::value ));\n  STATIC_CHECK(( internal::is_valid_index_type<short>::value ));\n  STATIC_CHECK(( internal::is_valid_index_type<std::ptrdiff_t>::value ));\n  STATIC_CHECK(( internal::is_valid_index_type<std::size_t>::value ));\n  STATIC_CHECK(( !internal::valid_indexed_view_overload<int,int>::value ));\n  STATIC_CHECK(( !internal::valid_indexed_view_overload<int,std::ptrdiff_t>::value ));\n  STATIC_CHECK(( !internal::valid_indexed_view_overload<std::ptrdiff_t,int>::value ));\n  STATIC_CHECK(( !internal::valid_indexed_view_overload<std::size_t,int>::value ));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/initializer_list_construction.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2019 David Tellenbach <david.tellenbach@tellnotes.org>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_STATIC_ASSERT\n\n#include \"main.h\"\n\ntemplate<typename Scalar, bool is_integer = NumTraits<Scalar>::IsInteger>\nstruct TestMethodDispatching {\n  static void run() {}\n};\n\ntemplate<typename Scalar>\nstruct TestMethodDispatching<Scalar, 1> {\n  static void run()\n  {\n    {\n      Matrix<Scalar, Dynamic, Dynamic> m {3, 4};\n      Array<Scalar, Dynamic, Dynamic> a {3, 4};\n      VERIFY(m.rows() == 3);\n      VERIFY(m.cols() == 4);\n      VERIFY(a.rows() == 3);\n      VERIFY(a.cols() == 4);\n    }\n    {\n      Matrix<Scalar, 1, 2> m {3, 4};\n      Array<Scalar, 1, 2> a {3, 4};\n      VERIFY(m(0) == 3);\n      VERIFY(m(1) == 4);\n      VERIFY(a(0) == 3);\n      VERIFY(a(1) == 4);\n    }\n    {\n      Matrix<Scalar, 2, 1> m {3, 4};\n      Array<Scalar, 2, 1> a {3, 4};\n      VERIFY(m(0) == 3);\n      VERIFY(m(1) == 4);\n      VERIFY(a(0) == 3);\n      VERIFY(a(1) == 4);\n    }\n  }\n};\n\ntemplate<typename Vec4, typename Vec5> void fixedsizeVariadicVectorConstruction2()\n{\n  {\n    Vec4 ref = Vec4::Random();\n    Vec4 v{ ref[0], ref[1], ref[2], ref[3] };\n    VERIFY_IS_APPROX(v, ref);\n    VERIFY_IS_APPROX(v, (Vec4( ref[0], ref[1], ref[2], ref[3] )));\n    VERIFY_IS_APPROX(v, (Vec4({ref[0], ref[1], ref[2], ref[3]})));\n\n    Vec4 v2 = { ref[0], ref[1], ref[2], ref[3] };\n    VERIFY_IS_APPROX(v2, ref);\n  }\n  {\n    Vec5 ref = Vec5::Random();\n    Vec5 v{ ref[0], ref[1], ref[2], ref[3], ref[4] };\n    VERIFY_IS_APPROX(v, ref);\n    VERIFY_IS_APPROX(v, (Vec5( ref[0], ref[1], ref[2], ref[3], ref[4] )));\n    VERIFY_IS_APPROX(v, (Vec5({ref[0], ref[1], ref[2], ref[3], ref[4]})));\n\n    Vec5 v2 = { ref[0], ref[1], ref[2], ref[3], ref[4] };\n    VERIFY_IS_APPROX(v2, ref);\n  }\n}\n\n#define CHECK_MIXSCALAR_V5_APPROX(V, A0, A1, A2, A3, A4) { \\\n  VERIFY_IS_APPROX(V[0], Scalar(A0) ); \\\n  VERIFY_IS_APPROX(V[1], Scalar(A1) ); \\\n  VERIFY_IS_APPROX(V[2], Scalar(A2) ); \\\n  VERIFY_IS_APPROX(V[3], Scalar(A3) ); \\\n  VERIFY_IS_APPROX(V[4], Scalar(A4) ); \\\n}\n\n#define CHECK_MIXSCALAR_V5(VEC5, A0, A1, A2, A3, A4) { \\\n  typedef VEC5::Scalar Scalar; \\\n  VEC5 v = { A0 , A1 , A2 , A3 , A4 }; \\\n  CHECK_MIXSCALAR_V5_APPROX(v, A0 , A1 , A2 , A3 , A4); \\\n}\n\ntemplate<int> void fixedsizeVariadicVectorConstruction3()\n{\n  typedef Matrix<double,5,1> Vec5;\n  typedef Array<float,5,1> Arr5;\n  CHECK_MIXSCALAR_V5(Vec5, 1, 2., -3, 4.121, 5.53252);\n  CHECK_MIXSCALAR_V5(Arr5, 1, 2., 3.12f, 4.121, 5.53252);\n}\n\ntemplate<typename Scalar> void fixedsizeVariadicVectorConstruction()\n{\n  CALL_SUBTEST(( fixedsizeVariadicVectorConstruction2<Matrix<Scalar,4,1>, Matrix<Scalar,5,1> >() ));\n  CALL_SUBTEST(( fixedsizeVariadicVectorConstruction2<Matrix<Scalar,1,4>, Matrix<Scalar,1,5> >() ));\n  CALL_SUBTEST(( fixedsizeVariadicVectorConstruction2<Array<Scalar,4,1>,  Array<Scalar,5,1>  >() ));\n  CALL_SUBTEST(( fixedsizeVariadicVectorConstruction2<Array<Scalar,1,4>,  Array<Scalar,1,5>  >() ));\n}\n\n\ntemplate<typename Scalar> void initializerListVectorConstruction()\n{\n  Scalar raw[4];\n  for(int k = 0; k < 4; ++k) {\n    raw[k] = internal::random<Scalar>();\n  }\n  {\n    Matrix<Scalar, 4, 1> m { {raw[0]}, {raw[1]},{raw[2]},{raw[3]} };\n    Array<Scalar, 4, 1> a { {raw[0]}, {raw[1]}, {raw[2]}, {raw[3]} };\n    for(int k = 0; k < 4; ++k) {\n      VERIFY(m(k) == raw[k]);\n    }\n    for(int k = 0; k < 4; ++k) {\n      VERIFY(a(k) == raw[k]);\n    }\n    VERIFY_IS_EQUAL(m, (Matrix<Scalar,4,1>({ {raw[0]}, {raw[1]}, {raw[2]}, {raw[3]} })));\n    VERIFY((a == (Array<Scalar,4,1>({ {raw[0]}, {raw[1]}, {raw[2]}, {raw[3]} }))).all());\n  }\n  {\n    Matrix<Scalar, 1, 4> m { {raw[0], raw[1], raw[2], raw[3]} };\n    Array<Scalar, 1, 4> a { {raw[0], raw[1], raw[2], raw[3]} };\n    for(int k = 0; k < 4; ++k) {\n      VERIFY(m(k) == raw[k]);\n    }\n    for(int k = 0; k < 4; ++k) {\n      VERIFY(a(k) == raw[k]);\n    }\n    VERIFY_IS_EQUAL(m, (Matrix<Scalar, 1, 4>({{raw[0],raw[1],raw[2],raw[3]}})));\n    VERIFY((a == (Array<Scalar, 1, 4>({{raw[0],raw[1],raw[2],raw[3]}}))).all());\n  }\n  {\n    Matrix<Scalar, 4, Dynamic> m { {raw[0]}, {raw[1]}, {raw[2]}, {raw[3]} };\n    Array<Scalar, 4, Dynamic> a { {raw[0]}, {raw[1]}, {raw[2]}, {raw[3]} };\n    for(int k=0; k < 4; ++k) {\n      VERIFY(m(k) == raw[k]);\n    }\n    for(int k=0; k < 4; ++k) {\n      VERIFY(a(k) == raw[k]);\n    }\n    VERIFY_IS_EQUAL(m, (Matrix<Scalar, 4, Dynamic>({ {raw[0]}, {raw[1]}, {raw[2]}, {raw[3]} })));\n    VERIFY((a == (Array<Scalar, 4, Dynamic>({ {raw[0]}, {raw[1]}, {raw[2]}, {raw[3]} }))).all());\n  }\n  {\n    Matrix<Scalar, Dynamic, 4> m {{raw[0],raw[1],raw[2],raw[3]}};\n    Array<Scalar, Dynamic, 4> a {{raw[0],raw[1],raw[2],raw[3]}};\n    for(int k=0; k < 4; ++k) {\n      VERIFY(m(k) == raw[k]);\n    }\n    for(int k=0; k < 4; ++k) {\n      VERIFY(a(k) == raw[k]);\n    }\n    VERIFY_IS_EQUAL(m, (Matrix<Scalar, Dynamic, 4>({{raw[0],raw[1],raw[2],raw[3]}})));\n    VERIFY((a == (Array<Scalar, Dynamic, 4>({{raw[0],raw[1],raw[2],raw[3]}}))).all());\n  }\n}\n\ntemplate<typename Scalar> void initializerListMatrixConstruction()\n{\n  const Index RowsAtCompileTime = 5;\n  const Index ColsAtCompileTime = 4;\n  const Index SizeAtCompileTime = RowsAtCompileTime * ColsAtCompileTime;\n\n  Scalar raw[SizeAtCompileTime];\n  for (int i = 0; i < SizeAtCompileTime; ++i) {\n    raw[i] = internal::random<Scalar>();\n  }\n  {\n    Matrix<Scalar, Dynamic, Dynamic> m {};\n    VERIFY(m.cols() == 0);\n    VERIFY(m.rows() == 0);\n    VERIFY_IS_EQUAL(m, (Matrix<Scalar, Dynamic, Dynamic>()));\n  }\n  {\n    Matrix<Scalar, 5, 4> m {\n      {raw[0], raw[1], raw[2], raw[3]},\n      {raw[4], raw[5], raw[6], raw[7]},\n      {raw[8], raw[9], raw[10], raw[11]},\n      {raw[12], raw[13], raw[14], raw[15]},\n      {raw[16], raw[17], raw[18], raw[19]}\n    };\n\n    Matrix<Scalar, 5, 4> m2;\n    m2 << raw[0], raw[1], raw[2], raw[3],\n          raw[4], raw[5], raw[6], raw[7],\n          raw[8], raw[9], raw[10], raw[11],\n          raw[12], raw[13], raw[14], raw[15],\n          raw[16], raw[17], raw[18], raw[19];\n\n    int k = 0;\n    for(int i = 0; i < RowsAtCompileTime; ++i) {\n      for (int j = 0; j < ColsAtCompileTime; ++j) {\n        VERIFY(m(i, j) == raw[k]);\n        ++k;\n      }\n    }\n    VERIFY_IS_EQUAL(m, m2);\n  }\n  {\n    Matrix<Scalar, Dynamic, Dynamic> m{\n      {raw[0], raw[1], raw[2], raw[3]},\n      {raw[4], raw[5], raw[6], raw[7]},\n      {raw[8], raw[9], raw[10], raw[11]},\n      {raw[12], raw[13], raw[14], raw[15]},\n      {raw[16], raw[17], raw[18], raw[19]}\n    };\n\n    VERIFY(m.cols() == 4);\n    VERIFY(m.rows() == 5);\n    int k = 0;\n    for(int i = 0; i < RowsAtCompileTime; ++i) {\n      for (int j = 0; j < ColsAtCompileTime; ++j) {\n        VERIFY(m(i, j) == raw[k]);\n        ++k;\n      }\n    }\n\n    Matrix<Scalar, Dynamic, Dynamic> m2(RowsAtCompileTime, ColsAtCompileTime);\n    k = 0;\n    for(int i = 0; i < RowsAtCompileTime; ++i) {\n      for (int j = 0; j < ColsAtCompileTime; ++j) {\n        m2(i, j) = raw[k];\n        ++k;\n      }\n    }\n    VERIFY_IS_EQUAL(m, m2);\n  }\n}\n\ntemplate<typename Scalar> void initializerListArrayConstruction()\n{\n  const Index RowsAtCompileTime = 5;\n  const Index ColsAtCompileTime = 4;\n  const Index SizeAtCompileTime = RowsAtCompileTime * ColsAtCompileTime;\n\n  Scalar raw[SizeAtCompileTime];\n  for (int i = 0; i < SizeAtCompileTime; ++i) {\n    raw[i] = internal::random<Scalar>();\n  }\n  {\n    Array<Scalar, Dynamic, Dynamic> a {};\n    VERIFY(a.cols() == 0);\n    VERIFY(a.rows() == 0);\n  }\n  {\n    Array<Scalar, 5, 4> m {\n      {raw[0], raw[1], raw[2], raw[3]},\n      {raw[4], raw[5], raw[6], raw[7]},\n      {raw[8], raw[9], raw[10], raw[11]},\n      {raw[12], raw[13], raw[14], raw[15]},\n      {raw[16], raw[17], raw[18], raw[19]}\n    };\n\n    Array<Scalar, 5, 4> m2;\n    m2 << raw[0], raw[1], raw[2], raw[3],\n          raw[4], raw[5], raw[6], raw[7],\n          raw[8], raw[9], raw[10], raw[11],\n          raw[12], raw[13], raw[14], raw[15],\n          raw[16], raw[17], raw[18], raw[19];\n\n    int k = 0;\n    for(int i = 0; i < RowsAtCompileTime; ++i) {\n      for (int j = 0; j < ColsAtCompileTime; ++j) {\n        VERIFY(m(i, j) == raw[k]);\n        ++k;\n      }\n    }\n    VERIFY_IS_APPROX(m, m2);\n  }\n  {\n    Array<Scalar, Dynamic, Dynamic> m {\n      {raw[0], raw[1], raw[2], raw[3]},\n      {raw[4], raw[5], raw[6], raw[7]},\n      {raw[8], raw[9], raw[10], raw[11]},\n      {raw[12], raw[13], raw[14], raw[15]},\n      {raw[16], raw[17], raw[18], raw[19]}\n    };\n\n    VERIFY(m.cols() == 4);\n    VERIFY(m.rows() == 5);\n    int k = 0;\n    for(int i = 0; i < RowsAtCompileTime; ++i) {\n      for (int j = 0; j < ColsAtCompileTime; ++j) {\n        VERIFY(m(i, j) == raw[k]);\n        ++k;\n      }\n    }\n\n    Array<Scalar, Dynamic, Dynamic> m2(RowsAtCompileTime, ColsAtCompileTime);\n    k = 0;\n    for(int i = 0; i < RowsAtCompileTime; ++i) {\n      for (int j = 0; j < ColsAtCompileTime; ++j) {\n        m2(i, j) = raw[k];\n        ++k;\n      }\n    }\n    VERIFY_IS_APPROX(m, m2);\n  }\n}\n\ntemplate<typename Scalar> void dynamicVectorConstruction()\n{\n  const Index size = 4;\n  Scalar raw[size];\n  for (int i = 0; i < size; ++i) {\n    raw[i] = internal::random<Scalar>();\n  }\n\n  typedef Matrix<Scalar, Dynamic, 1>  VectorX;\n\n  {\n    VectorX v {{raw[0], raw[1], raw[2], raw[3]}};\n    for (int i = 0; i < size; ++i) {\n      VERIFY(v(i) == raw[i]);\n    }\n    VERIFY(v.rows() == size);\n    VERIFY(v.cols() == 1);\n    VERIFY_IS_EQUAL(v, (VectorX {{raw[0], raw[1], raw[2], raw[3]}}));\n  }\n\n  {\n    VERIFY_RAISES_ASSERT((VectorX {raw[0], raw[1], raw[2], raw[3]}));\n  }\n  {\n    VERIFY_RAISES_ASSERT((VectorX  {\n      {raw[0], raw[1], raw[2], raw[3]},\n      {raw[0], raw[1], raw[2], raw[3]},\n    }));\n  }\n}\n\nEIGEN_DECLARE_TEST(initializer_list_construction)\n{\n  CALL_SUBTEST_1(initializerListVectorConstruction<unsigned char>());\n  CALL_SUBTEST_1(initializerListVectorConstruction<float>());\n  CALL_SUBTEST_1(initializerListVectorConstruction<double>());\n  CALL_SUBTEST_1(initializerListVectorConstruction<int>());\n  CALL_SUBTEST_1(initializerListVectorConstruction<long int>());\n  CALL_SUBTEST_1(initializerListVectorConstruction<std::ptrdiff_t>());\n  CALL_SUBTEST_1(initializerListVectorConstruction<std::complex<double>>());\n  CALL_SUBTEST_1(initializerListVectorConstruction<std::complex<float>>());\n\n  CALL_SUBTEST_2(initializerListMatrixConstruction<unsigned char>());\n  CALL_SUBTEST_2(initializerListMatrixConstruction<float>());\n  CALL_SUBTEST_2(initializerListMatrixConstruction<double>());\n  CALL_SUBTEST_2(initializerListMatrixConstruction<int>());\n  CALL_SUBTEST_2(initializerListMatrixConstruction<long int>());\n  CALL_SUBTEST_2(initializerListMatrixConstruction<std::ptrdiff_t>());\n  CALL_SUBTEST_2(initializerListMatrixConstruction<std::complex<double>>());\n  CALL_SUBTEST_2(initializerListMatrixConstruction<std::complex<float>>());\n\n  CALL_SUBTEST_3(initializerListArrayConstruction<unsigned char>());\n  CALL_SUBTEST_3(initializerListArrayConstruction<float>());\n  CALL_SUBTEST_3(initializerListArrayConstruction<double>());\n  CALL_SUBTEST_3(initializerListArrayConstruction<int>());\n  CALL_SUBTEST_3(initializerListArrayConstruction<long int>());\n  CALL_SUBTEST_3(initializerListArrayConstruction<std::ptrdiff_t>());\n  CALL_SUBTEST_3(initializerListArrayConstruction<std::complex<double>>());\n  CALL_SUBTEST_3(initializerListArrayConstruction<std::complex<float>>());\n\n  CALL_SUBTEST_4(fixedsizeVariadicVectorConstruction<unsigned char>());\n  CALL_SUBTEST_4(fixedsizeVariadicVectorConstruction<float>());\n  CALL_SUBTEST_4(fixedsizeVariadicVectorConstruction<double>());\n  CALL_SUBTEST_4(fixedsizeVariadicVectorConstruction<int>());\n  CALL_SUBTEST_4(fixedsizeVariadicVectorConstruction<long int>());\n  CALL_SUBTEST_4(fixedsizeVariadicVectorConstruction<std::ptrdiff_t>());\n  CALL_SUBTEST_4(fixedsizeVariadicVectorConstruction<std::complex<double>>());\n  CALL_SUBTEST_4(fixedsizeVariadicVectorConstruction<std::complex<float>>());\n  CALL_SUBTEST_4(fixedsizeVariadicVectorConstruction3<0>());\n\n  CALL_SUBTEST_5(TestMethodDispatching<int>::run());\n  CALL_SUBTEST_5(TestMethodDispatching<long int>::run());\n\n  CALL_SUBTEST_6(dynamicVectorConstruction<unsigned char>());\n  CALL_SUBTEST_6(dynamicVectorConstruction<float>());\n  CALL_SUBTEST_6(dynamicVectorConstruction<double>());\n  CALL_SUBTEST_6(dynamicVectorConstruction<int>());\n  CALL_SUBTEST_6(dynamicVectorConstruction<long int>());\n  CALL_SUBTEST_6(dynamicVectorConstruction<std::ptrdiff_t>());\n  CALL_SUBTEST_6(dynamicVectorConstruction<std::complex<double>>());\n  CALL_SUBTEST_6(dynamicVectorConstruction<std::complex<float>>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/inplace_decomposition.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/LU>\n#include <Eigen/Cholesky>\n#include <Eigen/QR>\n\n// This file test inplace decomposition through Ref<>, as supported by Cholesky, LU, and QR decompositions.\n\ntemplate<typename DecType,typename MatrixType> void inplace(bool square = false, bool SPD = false)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> RhsType;\n  typedef Matrix<Scalar, MatrixType::ColsAtCompileTime, 1> ResType;\n\n  Index rows = MatrixType::RowsAtCompileTime==Dynamic ? internal::random<Index>(2,EIGEN_TEST_MAX_SIZE/2) : Index(MatrixType::RowsAtCompileTime);\n  Index cols = MatrixType::ColsAtCompileTime==Dynamic ? (square?rows:internal::random<Index>(2,rows))    : Index(MatrixType::ColsAtCompileTime);\n\n  MatrixType A = MatrixType::Random(rows,cols);\n  RhsType b = RhsType::Random(rows);\n  ResType x(cols);\n\n  if(SPD)\n  {\n    assert(square);\n    A.topRows(cols) = A.topRows(cols).adjoint() * A.topRows(cols);\n    A.diagonal().array() += 1e-3;\n  }\n\n  MatrixType A0 = A;\n  MatrixType A1 = A;\n\n  DecType dec(A);\n\n  // Check that the content of A has been modified\n  VERIFY_IS_NOT_APPROX( A, A0 );\n\n  // Check that the decomposition is correct:\n  if(rows==cols)\n  {\n    VERIFY_IS_APPROX( A0 * (x = dec.solve(b)), b );\n  }\n  else\n  {\n    VERIFY_IS_APPROX( A0.transpose() * A0 * (x = dec.solve(b)), A0.transpose() * b );\n  }\n\n  // Check that modifying A breaks the current dec:\n  A.setRandom();\n  if(rows==cols)\n  {\n    VERIFY_IS_NOT_APPROX( A0 * (x = dec.solve(b)), b );\n  }\n  else\n  {\n    VERIFY_IS_NOT_APPROX( A0.transpose() * A0 * (x = dec.solve(b)), A0.transpose() * b );\n  }\n\n  // Check that calling compute(A1) does not modify A1:\n  A = A0;\n  dec.compute(A1);\n  VERIFY_IS_EQUAL(A0,A1);\n  VERIFY_IS_NOT_APPROX( A, A0 );\n  if(rows==cols)\n  {\n    VERIFY_IS_APPROX( A0 * (x = dec.solve(b)), b );\n  }\n  else\n  {\n    VERIFY_IS_APPROX( A0.transpose() * A0 * (x = dec.solve(b)), A0.transpose() * b );\n  }\n}\n\n\nEIGEN_DECLARE_TEST(inplace_decomposition)\n{\n  EIGEN_UNUSED typedef Matrix<double,4,3> Matrix43d;\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(( inplace<LLT<Ref<MatrixXd> >, MatrixXd>(true,true) ));\n    CALL_SUBTEST_1(( inplace<LLT<Ref<Matrix4d> >, Matrix4d>(true,true) ));\n\n    CALL_SUBTEST_2(( inplace<LDLT<Ref<MatrixXd> >, MatrixXd>(true,true) ));\n    CALL_SUBTEST_2(( inplace<LDLT<Ref<Matrix4d> >, Matrix4d>(true,true) ));\n\n    CALL_SUBTEST_3(( inplace<PartialPivLU<Ref<MatrixXd> >, MatrixXd>(true,false) ));\n    CALL_SUBTEST_3(( inplace<PartialPivLU<Ref<Matrix4d> >, Matrix4d>(true,false) ));\n\n    CALL_SUBTEST_4(( inplace<FullPivLU<Ref<MatrixXd> >, MatrixXd>(true,false) ));\n    CALL_SUBTEST_4(( inplace<FullPivLU<Ref<Matrix4d> >, Matrix4d>(true,false) ));\n\n    CALL_SUBTEST_5(( inplace<HouseholderQR<Ref<MatrixXd> >, MatrixXd>(false,false) ));\n    CALL_SUBTEST_5(( inplace<HouseholderQR<Ref<Matrix43d> >, Matrix43d>(false,false) ));\n\n    CALL_SUBTEST_6(( inplace<ColPivHouseholderQR<Ref<MatrixXd> >, MatrixXd>(false,false) ));\n    CALL_SUBTEST_6(( inplace<ColPivHouseholderQR<Ref<Matrix43d> >, Matrix43d>(false,false) ));\n\n    CALL_SUBTEST_7(( inplace<FullPivHouseholderQR<Ref<MatrixXd> >, MatrixXd>(false,false) ));\n    CALL_SUBTEST_7(( inplace<FullPivHouseholderQR<Ref<Matrix43d> >, Matrix43d>(false,false) ));\n\n    CALL_SUBTEST_8(( inplace<CompleteOrthogonalDecomposition<Ref<MatrixXd> >, MatrixXd>(false,false) ));\n    CALL_SUBTEST_8(( inplace<CompleteOrthogonalDecomposition<Ref<Matrix43d> >, Matrix43d>(false,false) ));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/integer_types.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_STATIC_ASSERT\n\n#include \"main.h\"\n\n#undef VERIFY_IS_APPROX\n#define VERIFY_IS_APPROX(a, b) VERIFY((a)==(b));\n#undef VERIFY_IS_NOT_APPROX\n#define VERIFY_IS_NOT_APPROX(a, b) VERIFY((a)!=(b));\n\ntemplate<typename MatrixType> void signed_integer_type_tests(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  enum { is_signed = (Scalar(-1) > Scalar(0)) ? 0 : 1 };\n  VERIFY(is_signed == 1);\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             mzero = MatrixType::Zero(rows, cols);\n\n  do {\n    m1 = MatrixType::Random(rows, cols);\n  } while(m1 == mzero || m1 == m2);\n\n  // check linear structure\n\n  Scalar s1;\n  do {\n    s1 = internal::random<Scalar>();\n  } while(s1 == 0);\n\n  VERIFY_IS_EQUAL(-(-m1),                  m1);\n  VERIFY_IS_EQUAL(-m2+m1+m2,               m1);\n  VERIFY_IS_EQUAL((-m1+m2)*s1,             -s1*m1+s1*m2);\n}\n\ntemplate<typename MatrixType> void integer_type_tests(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  VERIFY(NumTraits<Scalar>::IsInteger);\n  enum { is_signed = (Scalar(-1) > Scalar(0)) ? 0 : 1 };\n  VERIFY(int(NumTraits<Scalar>::IsSigned) == is_signed);\n\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  // this test relies a lot on Random.h, and there's not much more that we can do\n  // to test it, hence I consider that we will have tested Random.h\n  MatrixType m1(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols),\n             mzero = MatrixType::Zero(rows, cols);\n\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> SquareMatrixType;\n  SquareMatrixType identity = SquareMatrixType::Identity(rows, rows),\n                   square = SquareMatrixType::Random(rows, rows);\n  VectorType v1(rows),\n             v2 = VectorType::Random(rows),\n             vzero = VectorType::Zero(rows);\n\n  do {\n    m1 = MatrixType::Random(rows, cols);\n  } while(m1 == mzero || m1 == m2);\n\n  do {\n    v1 = VectorType::Random(rows);\n  } while(v1 == vzero || v1 == v2);\n\n  VERIFY_IS_APPROX(               v1,    v1);\n  VERIFY_IS_NOT_APPROX(           v1,    2*v1);\n  VERIFY_IS_APPROX(               vzero, v1-v1);\n  VERIFY_IS_APPROX(               m1,    m1);\n  VERIFY_IS_NOT_APPROX(           m1,    2*m1);\n  VERIFY_IS_APPROX(               mzero, m1-m1);\n\n  VERIFY_IS_APPROX(m3 = m1,m1);\n  MatrixType m4;\n  VERIFY_IS_APPROX(m4 = m1,m1);\n\n  m3.real() = m1.real();\n  VERIFY_IS_APPROX(static_cast<const MatrixType&>(m3).real(), static_cast<const MatrixType&>(m1).real());\n  VERIFY_IS_APPROX(static_cast<const MatrixType&>(m3).real(), m1.real());\n\n  // check == / != operators\n  VERIFY(m1==m1);\n  VERIFY(m1!=m2);\n  VERIFY(!(m1==m2));\n  VERIFY(!(m1!=m1));\n  m1 = m2;\n  VERIFY(m1==m2);\n  VERIFY(!(m1!=m2));\n\n  // check linear structure\n\n  Scalar s1;\n  do {\n    s1 = internal::random<Scalar>();\n  } while(s1 == 0);\n\n  VERIFY_IS_EQUAL(m1+m1,                   2*m1);\n  VERIFY_IS_EQUAL(m1+m2-m1,                m2);\n  VERIFY_IS_EQUAL(m1*s1,                   s1*m1);\n  VERIFY_IS_EQUAL((m1+m2)*s1,              s1*m1+s1*m2);\n  m3 = m2; m3 += m1;\n  VERIFY_IS_EQUAL(m3,                      m1+m2);\n  m3 = m2; m3 -= m1;\n  VERIFY_IS_EQUAL(m3,                      m2-m1);\n  m3 = m2; m3 *= s1;\n  VERIFY_IS_EQUAL(m3,                      s1*m2);\n\n  // check matrix product.\n\n  VERIFY_IS_APPROX(identity * m1, m1);\n  VERIFY_IS_APPROX(square * (m1 + m2), square * m1 + square * m2);\n  VERIFY_IS_APPROX((m1 + m2).transpose() * square, m1.transpose() * square + m2.transpose() * square);\n  VERIFY_IS_APPROX((m1 * m2.transpose()) * m1, m1 * (m2.transpose() * m1));\n}\n\ntemplate<int>\nvoid integer_types_extra()\n{\n  VERIFY_IS_EQUAL(int(internal::scalar_div_cost<int>::value), 8);\n  VERIFY_IS_EQUAL(int(internal::scalar_div_cost<unsigned int>::value), 8);\n  if(sizeof(long)>sizeof(int)) {\n    VERIFY(int(internal::scalar_div_cost<long>::value) > int(internal::scalar_div_cost<int>::value));\n    VERIFY(int(internal::scalar_div_cost<unsigned long>::value) > int(internal::scalar_div_cost<int>::value));\n  }\n}\n\nEIGEN_DECLARE_TEST(integer_types)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( integer_type_tests(Matrix<unsigned int, 1, 1>()) );\n    CALL_SUBTEST_1( integer_type_tests(Matrix<unsigned long, 3, 4>()) );\n\n    CALL_SUBTEST_2( integer_type_tests(Matrix<long, 2, 2>()) );\n    CALL_SUBTEST_2( signed_integer_type_tests(Matrix<long, 2, 2>()) );\n\n    CALL_SUBTEST_3( integer_type_tests(Matrix<char, 2, Dynamic>(2, 10)) );\n    CALL_SUBTEST_3( signed_integer_type_tests(Matrix<signed char, 2, Dynamic>(2, 10)) );\n\n    CALL_SUBTEST_4( integer_type_tests(Matrix<unsigned char, 3, 3>()) );\n    CALL_SUBTEST_4( integer_type_tests(Matrix<unsigned char, Dynamic, Dynamic>(20, 20)) );\n\n    CALL_SUBTEST_5( integer_type_tests(Matrix<short, Dynamic, 4>(7, 4)) );\n    CALL_SUBTEST_5( signed_integer_type_tests(Matrix<short, Dynamic, 4>(7, 4)) );\n\n    CALL_SUBTEST_6( integer_type_tests(Matrix<unsigned short, 4, 4>()) );\n\n#if EIGEN_HAS_CXX11\n    CALL_SUBTEST_7( integer_type_tests(Matrix<long long, 11, 13>()) );\n    CALL_SUBTEST_7( signed_integer_type_tests(Matrix<long long, 11, 13>()) );\n\n    CALL_SUBTEST_8( integer_type_tests(Matrix<unsigned long long, Dynamic, 5>(1, 5)) );\n#endif\n  }\n  CALL_SUBTEST_9( integer_types_extra<0>() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/inverse.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/LU>\n\ntemplate<typename MatrixType>\nvoid inverse_for_fixed_size(const MatrixType&, typename internal::enable_if<MatrixType::SizeAtCompileTime==Dynamic>::type* = 0)\n{\n}\n\ntemplate<typename MatrixType>\nvoid inverse_for_fixed_size(const MatrixType& m1, typename internal::enable_if<MatrixType::SizeAtCompileTime!=Dynamic>::type* = 0)\n{\n  using std::abs;\n\n  MatrixType m2, identity = MatrixType::Identity();\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar, MatrixType::ColsAtCompileTime, 1> VectorType;\n  \n  //computeInverseAndDetWithCheck tests\n  //First: an invertible matrix\n  bool invertible;\n  Scalar det;\n\n  m2.setZero();\n  m1.computeInverseAndDetWithCheck(m2, det, invertible);\n  VERIFY(invertible);\n  VERIFY_IS_APPROX(identity, m1*m2);\n  VERIFY_IS_APPROX(det, m1.determinant());\n\n  m2.setZero();\n  m1.computeInverseWithCheck(m2, invertible);\n  VERIFY(invertible);\n  VERIFY_IS_APPROX(identity, m1*m2);\n\n  //Second: a rank one matrix (not invertible, except for 1x1 matrices)\n  VectorType v3 = VectorType::Random();\n  MatrixType m3 = v3*v3.transpose(), m4;\n  m3.computeInverseAndDetWithCheck(m4, det, invertible);\n  VERIFY( m1.rows()==1 ? invertible : !invertible );\n  VERIFY_IS_MUCH_SMALLER_THAN(abs(det-m3.determinant()), RealScalar(1));\n  m3.computeInverseWithCheck(m4, invertible);\n  VERIFY( m1.rows()==1 ? invertible : !invertible );\n  \n  // check with submatrices\n  {\n    Matrix<Scalar, MatrixType::RowsAtCompileTime+1, MatrixType::RowsAtCompileTime+1, MatrixType::Options> m5;\n    m5.setRandom();\n    m5.topLeftCorner(m1.rows(),m1.rows()) = m1;\n    m2 = m5.template topLeftCorner<MatrixType::RowsAtCompileTime,MatrixType::ColsAtCompileTime>().inverse();\n    VERIFY_IS_APPROX( (m5.template topLeftCorner<MatrixType::RowsAtCompileTime,MatrixType::ColsAtCompileTime>()), m2.inverse() );\n  }\n}\n\ntemplate<typename MatrixType> void inverse(const MatrixType& m)\n{\n  /* this test covers the following files:\n     Inverse.h\n  */\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  typedef typename MatrixType::Scalar Scalar;\n\n  MatrixType m1(rows, cols),\n             m2(rows, cols),\n             identity = MatrixType::Identity(rows, rows);\n  createRandomPIMatrixOfRank(rows,rows,rows,m1);\n  m2 = m1.inverse();\n  VERIFY_IS_APPROX(m1, m2.inverse() );\n\n  VERIFY_IS_APPROX((Scalar(2)*m2).inverse(), m2.inverse()*Scalar(0.5));\n\n  VERIFY_IS_APPROX(identity, m1.inverse() * m1 );\n  VERIFY_IS_APPROX(identity, m1 * m1.inverse() );\n\n  VERIFY_IS_APPROX(m1, m1.inverse().inverse() );\n\n  // since for the general case we implement separately row-major and col-major, test that\n  VERIFY_IS_APPROX(MatrixType(m1.transpose().inverse()), MatrixType(m1.inverse().transpose()));\n\n  inverse_for_fixed_size(m1);\n\n  // check in-place inversion\n  if(MatrixType::RowsAtCompileTime>=2 && MatrixType::RowsAtCompileTime<=4)\n  {\n    // in-place is forbidden\n    VERIFY_RAISES_ASSERT(m1 = m1.inverse());\n  }\n  else\n  {\n    m2 = m1.inverse();\n    m1 = m1.inverse();\n    VERIFY_IS_APPROX(m1,m2);\n  }\n}\n\ntemplate<typename Scalar>\nvoid inverse_zerosized()\n{\n  Matrix<Scalar,Dynamic,Dynamic> A(0,0);\n  {\n    Matrix<Scalar,0,1> b, x;\n    x = A.inverse() * b;\n  }\n  {\n    Matrix<Scalar,Dynamic,Dynamic> b(0,1), x;\n    x = A.inverse() * b;\n    VERIFY_IS_EQUAL(x.rows(), 0);\n    VERIFY_IS_EQUAL(x.cols(), 1);\n  }\n}\n\nEIGEN_DECLARE_TEST(inverse)\n{\n  int s = 0;\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( inverse(Matrix<double,1,1>()) );\n    CALL_SUBTEST_2( inverse(Matrix2d()) );\n    CALL_SUBTEST_3( inverse(Matrix3f()) );\n    CALL_SUBTEST_4( inverse(Matrix4f()) );\n    CALL_SUBTEST_4( inverse(Matrix<float,4,4,DontAlign>()) );\n    \n    s = internal::random<int>(50,320); \n    CALL_SUBTEST_5( inverse(MatrixXf(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n    CALL_SUBTEST_5( inverse_zerosized<float>() );\n    \n    s = internal::random<int>(25,100);\n    CALL_SUBTEST_6( inverse(MatrixXcd(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n    \n    CALL_SUBTEST_7( inverse(Matrix4d()) );\n    CALL_SUBTEST_7( inverse(Matrix<double,4,4,DontAlign>()) );\n\n    CALL_SUBTEST_8( inverse(Matrix4cd()) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/io.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2019 Joel Holdsworth <joel.holdsworth@vcatechnology.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <sstream>\n\n#include \"main.h\"\n\ntemplate<typename Scalar>\nstruct check_ostream_impl\n{\n  static void run()\n  {\n    const Array<Scalar,1,1> array(123);\n    std::ostringstream ss;\n    ss << array;\n    VERIFY(ss.str() == \"123\");\n\n    check_ostream_impl< std::complex<Scalar> >::run();\n  };\n};\n\ntemplate<>\nstruct check_ostream_impl<bool>\n{\n  static void run()\n  {\n    const Array<bool,1,2> array(1, 0);\n    std::ostringstream ss;\n    ss << array;\n    VERIFY(ss.str() == \"1  0\");\n  };\n};\n\ntemplate<typename Scalar>\nstruct check_ostream_impl< std::complex<Scalar> >\n{\n  static void run()\n  {\n    const Array<std::complex<Scalar>,1,1> array(std::complex<Scalar>(12, 34));\n    std::ostringstream ss;\n    ss << array;\n    VERIFY(ss.str() == \"(12,34)\");\n  };\n};\n\ntemplate<typename Scalar>\nstatic void check_ostream()\n{\n  check_ostream_impl<Scalar>::run();\n}\n\nEIGEN_DECLARE_TEST(rand)\n{\n  CALL_SUBTEST(check_ostream<bool>());\n  CALL_SUBTEST(check_ostream<float>());\n  CALL_SUBTEST(check_ostream<double>());\n  CALL_SUBTEST(check_ostream<Eigen::numext::int8_t>());\n  CALL_SUBTEST(check_ostream<Eigen::numext::uint8_t>());\n  CALL_SUBTEST(check_ostream<Eigen::numext::int16_t>());\n  CALL_SUBTEST(check_ostream<Eigen::numext::uint16_t>());\n  CALL_SUBTEST(check_ostream<Eigen::numext::int32_t>());\n  CALL_SUBTEST(check_ostream<Eigen::numext::uint32_t>());\n  CALL_SUBTEST(check_ostream<Eigen::numext::int64_t>());\n  CALL_SUBTEST(check_ostream<Eigen::numext::uint64_t>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/is_same_dense.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\nusing internal::is_same_dense;\n\nEIGEN_DECLARE_TEST(is_same_dense)\n{\n  typedef Matrix<double,Dynamic,Dynamic,ColMajor> ColMatrixXd;\n  typedef Matrix<std::complex<double>,Dynamic,Dynamic,ColMajor> ColMatrixXcd;\n  ColMatrixXd m1(10,10);\n  ColMatrixXcd m2(10,10);\n  Ref<ColMatrixXd> ref_m1(m1);\n  Ref<ColMatrixXd,0, Stride<Dynamic,Dynamic> >  ref_m2_real(m2.real());\n  Ref<const ColMatrixXd> const_ref_m1(m1);\n\n  VERIFY(is_same_dense(m1,m1));\n  VERIFY(is_same_dense(m1,ref_m1));\n  VERIFY(is_same_dense(const_ref_m1,m1));\n  VERIFY(is_same_dense(const_ref_m1,ref_m1));\n  \n  VERIFY(is_same_dense(m1.block(0,0,m1.rows(),m1.cols()),m1));\n  VERIFY(!is_same_dense(m1.row(0),m1.col(0)));\n  \n  Ref<const ColMatrixXd> const_ref_m1_row(m1.row(1));\n  VERIFY(!is_same_dense(m1.row(1),const_ref_m1_row));\n  \n  Ref<const ColMatrixXd> const_ref_m1_col(m1.col(1));\n  VERIFY(is_same_dense(m1.col(1),const_ref_m1_col));\n\n\n  VERIFY(!is_same_dense(m1, ref_m2_real));\n  VERIFY(!is_same_dense(m2, ref_m2_real));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/jacobi.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/SVD>\n\ntemplate<typename MatrixType, typename JacobiScalar>\nvoid jacobi(const MatrixType& m = MatrixType())\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  enum {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime\n  };\n\n  typedef Matrix<JacobiScalar, 2, 1> JacobiVector;\n\n  const MatrixType a(MatrixType::Random(rows, cols));\n\n  JacobiVector v = JacobiVector::Random().normalized();\n  JacobiScalar c = v.x(), s = v.y();\n  JacobiRotation<JacobiScalar> rot(c, s);\n\n  {\n    Index p = internal::random<Index>(0, rows-1);\n    Index q;\n    do {\n      q = internal::random<Index>(0, rows-1);\n    } while (q == p);\n\n    MatrixType b = a;\n    b.applyOnTheLeft(p, q, rot);\n    VERIFY_IS_APPROX(b.row(p), c * a.row(p) + numext::conj(s) * a.row(q));\n    VERIFY_IS_APPROX(b.row(q), -s * a.row(p) + numext::conj(c) * a.row(q));\n  }\n\n  {\n    Index p = internal::random<Index>(0, cols-1);\n    Index q;\n    do {\n      q = internal::random<Index>(0, cols-1);\n    } while (q == p);\n\n    MatrixType b = a;\n    b.applyOnTheRight(p, q, rot);\n    VERIFY_IS_APPROX(b.col(p), c * a.col(p) - s * a.col(q));\n    VERIFY_IS_APPROX(b.col(q), numext::conj(s) * a.col(p) + numext::conj(c) * a.col(q));\n  }\n}\n\nEIGEN_DECLARE_TEST(jacobi)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(( jacobi<Matrix3f, float>() ));\n    CALL_SUBTEST_2(( jacobi<Matrix4d, double>() ));\n    CALL_SUBTEST_3(( jacobi<Matrix4cf, float>() ));\n    CALL_SUBTEST_3(( jacobi<Matrix4cf, std::complex<float> >() ));\n\n    int r = internal::random<int>(2, internal::random<int>(1,EIGEN_TEST_MAX_SIZE)/2),\n        c = internal::random<int>(2, internal::random<int>(1,EIGEN_TEST_MAX_SIZE)/2);\n    CALL_SUBTEST_4(( jacobi<MatrixXf, float>(MatrixXf(r,c)) ));\n    CALL_SUBTEST_5(( jacobi<MatrixXcd, double>(MatrixXcd(r,c)) ));\n    CALL_SUBTEST_5(( jacobi<MatrixXcd, std::complex<double> >(MatrixXcd(r,c)) ));\n    // complex<float> is really important to test as it is the only way to cover conjugation issues in certain unaligned paths\n    CALL_SUBTEST_6(( jacobi<MatrixXcf, float>(MatrixXcf(r,c)) ));\n    CALL_SUBTEST_6(( jacobi<MatrixXcf, std::complex<float> >(MatrixXcf(r,c)) ));\n    \n    TEST_SET_BUT_UNUSED_VARIABLE(r);\n    TEST_SET_BUT_UNUSED_VARIABLE(c);\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/jacobisvd.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// discard stack allocation as that too bypasses malloc\n#define EIGEN_STACK_ALLOCATION_LIMIT 0\n#define EIGEN_RUNTIME_NO_MALLOC\n#include \"main.h\"\n#include <Eigen/SVD>\n\n#define SVD_DEFAULT(M) JacobiSVD<M>\n#define SVD_FOR_MIN_NORM(M) JacobiSVD<M,ColPivHouseholderQRPreconditioner>\n#include \"svd_common.h\"\n\n// Check all variants of JacobiSVD\ntemplate<typename MatrixType>\nvoid jacobisvd(const MatrixType& a = MatrixType(), bool pickrandom = true)\n{\n  MatrixType m = a;\n  if(pickrandom)\n    svd_fill_random(m);\n\n  CALL_SUBTEST(( svd_test_all_computation_options<JacobiSVD<MatrixType, FullPivHouseholderQRPreconditioner> >(m, true)  )); // check full only\n  CALL_SUBTEST(( svd_test_all_computation_options<JacobiSVD<MatrixType, ColPivHouseholderQRPreconditioner>  >(m, false) ));\n  CALL_SUBTEST(( svd_test_all_computation_options<JacobiSVD<MatrixType, HouseholderQRPreconditioner>        >(m, false) ));\n  if(m.rows()==m.cols())\n    CALL_SUBTEST(( svd_test_all_computation_options<JacobiSVD<MatrixType, NoQRPreconditioner>               >(m, false) ));\n}\n\ntemplate<typename MatrixType> void jacobisvd_verify_assert(const MatrixType& m)\n{\n  svd_verify_assert<JacobiSVD<MatrixType> >(m);\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  enum {\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime\n  };\n\n\n  MatrixType a = MatrixType::Zero(rows, cols);\n  a.setZero();\n\n  if (ColsAtCompileTime == Dynamic)\n  {\n    JacobiSVD<MatrixType, FullPivHouseholderQRPreconditioner> svd_fullqr;\n    VERIFY_RAISES_ASSERT(svd_fullqr.compute(a, ComputeFullU|ComputeThinV))\n    VERIFY_RAISES_ASSERT(svd_fullqr.compute(a, ComputeThinU|ComputeThinV))\n    VERIFY_RAISES_ASSERT(svd_fullqr.compute(a, ComputeThinU|ComputeFullV))\n  }\n}\n\ntemplate<typename MatrixType>\nvoid jacobisvd_method()\n{\n  enum { Size = MatrixType::RowsAtCompileTime };\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef Matrix<RealScalar, Size, 1> RealVecType;\n  MatrixType m = MatrixType::Identity();\n  VERIFY_IS_APPROX(m.jacobiSvd().singularValues(), RealVecType::Ones());\n  VERIFY_RAISES_ASSERT(m.jacobiSvd().matrixU());\n  VERIFY_RAISES_ASSERT(m.jacobiSvd().matrixV());\n  VERIFY_IS_APPROX(m.jacobiSvd(ComputeFullU|ComputeFullV).solve(m), m);\n  VERIFY_IS_APPROX(m.jacobiSvd(ComputeFullU|ComputeFullV).transpose().solve(m), m);\n  VERIFY_IS_APPROX(m.jacobiSvd(ComputeFullU|ComputeFullV).adjoint().solve(m), m);\n}\n\nnamespace Foo {\n// older compiler require a default constructor for Bar\n// cf: https://stackoverflow.com/questions/7411515/\nclass Bar {public: Bar() {}};\nbool operator<(const Bar&, const Bar&) { return true; }\n}\n// regression test for a very strange MSVC issue for which simply\n// including SVDBase.h messes up with std::max and custom scalar type\nvoid msvc_workaround()\n{\n  const Foo::Bar a;\n  const Foo::Bar b;\n  std::max EIGEN_NOT_A_MACRO (a,b);\n}\n\nEIGEN_DECLARE_TEST(jacobisvd)\n{\n  CALL_SUBTEST_3(( jacobisvd_verify_assert(Matrix3f()) ));\n  CALL_SUBTEST_4(( jacobisvd_verify_assert(Matrix4d()) ));\n  CALL_SUBTEST_7(( jacobisvd_verify_assert(MatrixXf(10,12)) ));\n  CALL_SUBTEST_8(( jacobisvd_verify_assert(MatrixXcd(7,5)) ));\n  \n  CALL_SUBTEST_11(svd_all_trivial_2x2(jacobisvd<Matrix2cd>));\n  CALL_SUBTEST_12(svd_all_trivial_2x2(jacobisvd<Matrix2d>));\n\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_3(( jacobisvd<Matrix3f>() ));\n    CALL_SUBTEST_4(( jacobisvd<Matrix4d>() ));\n    CALL_SUBTEST_5(( jacobisvd<Matrix<float,3,5> >() ));\n    CALL_SUBTEST_6(( jacobisvd<Matrix<double,Dynamic,2> >(Matrix<double,Dynamic,2>(10,2)) ));\n\n    int r = internal::random<int>(1, 30),\n        c = internal::random<int>(1, 30);\n    \n    TEST_SET_BUT_UNUSED_VARIABLE(r)\n    TEST_SET_BUT_UNUSED_VARIABLE(c)\n    \n    CALL_SUBTEST_10(( jacobisvd<MatrixXd>(MatrixXd(r,c)) ));\n    CALL_SUBTEST_7(( jacobisvd<MatrixXf>(MatrixXf(r,c)) ));\n    CALL_SUBTEST_8(( jacobisvd<MatrixXcd>(MatrixXcd(r,c)) ));\n    (void) r;\n    (void) c;\n\n    // Test on inf/nan matrix\n    CALL_SUBTEST_7(  (svd_inf_nan<JacobiSVD<MatrixXf>, MatrixXf>()) );\n    CALL_SUBTEST_10( (svd_inf_nan<JacobiSVD<MatrixXd>, MatrixXd>()) );\n\n    // bug1395 test compile-time vectors as input\n    CALL_SUBTEST_13(( jacobisvd_verify_assert(Matrix<double,6,1>()) ));\n    CALL_SUBTEST_13(( jacobisvd_verify_assert(Matrix<double,1,6>()) ));\n    CALL_SUBTEST_13(( jacobisvd_verify_assert(Matrix<double,Dynamic,1>(r)) ));\n    CALL_SUBTEST_13(( jacobisvd_verify_assert(Matrix<double,1,Dynamic>(c)) ));\n  }\n\n  CALL_SUBTEST_7(( jacobisvd<MatrixXf>(MatrixXf(internal::random<int>(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/2), internal::random<int>(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/2))) ));\n  CALL_SUBTEST_8(( jacobisvd<MatrixXcd>(MatrixXcd(internal::random<int>(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/3), internal::random<int>(EIGEN_TEST_MAX_SIZE/4, EIGEN_TEST_MAX_SIZE/3))) ));\n\n  // test matrixbase method\n  CALL_SUBTEST_1(( jacobisvd_method<Matrix2cd>() ));\n  CALL_SUBTEST_3(( jacobisvd_method<Matrix3f>() ));\n\n  // Test problem size constructors\n  CALL_SUBTEST_7( JacobiSVD<MatrixXf>(10,10) );\n\n  // Check that preallocation avoids subsequent mallocs\n  CALL_SUBTEST_9( svd_preallocate<void>() );\n\n  CALL_SUBTEST_2( svd_underoverflow<void>() );\n\n  msvc_workaround();\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/klu_support.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS\n#include \"sparse_solver.h\"\n\n#include <Eigen/KLUSupport>\n\ntemplate<typename T> void test_klu_support_T()\n{\n  KLU<SparseMatrix<T, ColMajor> > klu_colmajor;\n  KLU<SparseMatrix<T, RowMajor> > klu_rowmajor;\n  \n  check_sparse_square_solving(klu_colmajor);\n  check_sparse_square_solving(klu_rowmajor);\n  \n  //check_sparse_square_determinant(umfpack_colmajor);\n  //check_sparse_square_determinant(umfpack_rowmajor);\n}\n\nEIGEN_DECLARE_TEST(klu_support)\n{\n  CALL_SUBTEST_1(test_klu_support_T<double>());\n  CALL_SUBTEST_2(test_klu_support_T<std::complex<double> >());\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/linearstructure.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\nstatic bool g_called;\n#define EIGEN_SCALAR_BINARY_OP_PLUGIN { g_called |= (!internal::is_same<LhsScalar,RhsScalar>::value); }\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void linearStructure(const MatrixType& m)\n{\n  using std::abs;\n  /* this test covers the following files:\n     CwiseUnaryOp.h, CwiseBinaryOp.h, SelfCwiseBinaryOp.h \n  */\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  // this test relies a lot on Random.h, and there's not much more that we can do\n  // to test it, hence I consider that we will have tested Random.h\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols);\n\n  Scalar s1 = internal::random<Scalar>();\n  while (abs(s1)<RealScalar(1e-3)) s1 = internal::random<Scalar>();\n\n  Index r = internal::random<Index>(0, rows-1),\n        c = internal::random<Index>(0, cols-1);\n\n  VERIFY_IS_APPROX(-(-m1),                  m1);\n  VERIFY_IS_APPROX(m1+m1,                   2*m1);\n  VERIFY_IS_APPROX(m1+m2-m1,                m2);\n  VERIFY_IS_APPROX(-m2+m1+m2,               m1);\n  VERIFY_IS_APPROX(m1*s1,                   s1*m1);\n  VERIFY_IS_APPROX((m1+m2)*s1,              s1*m1+s1*m2);\n  VERIFY_IS_APPROX((-m1+m2)*s1,             -s1*m1+s1*m2);\n  m3 = m2; m3 += m1;\n  VERIFY_IS_APPROX(m3,                      m1+m2);\n  m3 = m2; m3 -= m1;\n  VERIFY_IS_APPROX(m3,                      m2-m1);\n  m3 = m2; m3 *= s1;\n  VERIFY_IS_APPROX(m3,                      s1*m2);\n  if(!NumTraits<Scalar>::IsInteger)\n  {\n    m3 = m2; m3 /= s1;\n    VERIFY_IS_APPROX(m3,                    m2/s1);\n  }\n\n  // again, test operator() to check const-qualification\n  VERIFY_IS_APPROX((-m1)(r,c), -(m1(r,c)));\n  VERIFY_IS_APPROX((m1-m2)(r,c), (m1(r,c))-(m2(r,c)));\n  VERIFY_IS_APPROX((m1+m2)(r,c), (m1(r,c))+(m2(r,c)));\n  VERIFY_IS_APPROX((s1*m1)(r,c), s1*(m1(r,c)));\n  VERIFY_IS_APPROX((m1*s1)(r,c), (m1(r,c))*s1);\n  if(!NumTraits<Scalar>::IsInteger)\n    VERIFY_IS_APPROX((m1/s1)(r,c), (m1(r,c))/s1);\n\n  // use .block to disable vectorization and compare to the vectorized version\n  VERIFY_IS_APPROX(m1+m1.block(0,0,rows,cols), m1+m1);\n  VERIFY_IS_APPROX(m1.cwiseProduct(m1.block(0,0,rows,cols)), m1.cwiseProduct(m1));\n  VERIFY_IS_APPROX(m1 - m1.block(0,0,rows,cols), m1 - m1);\n  VERIFY_IS_APPROX(m1.block(0,0,rows,cols) * s1, m1 * s1);\n}\n\n// Make sure that complex * real and real * complex are properly optimized\ntemplate<typename MatrixType> void real_complex(DenseIndex rows = MatrixType::RowsAtCompileTime, DenseIndex cols = MatrixType::ColsAtCompileTime)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  \n  RealScalar s = internal::random<RealScalar>();\n  MatrixType m1 = MatrixType::Random(rows, cols);\n  \n  g_called = false;\n  VERIFY_IS_APPROX(s*m1, Scalar(s)*m1);\n  VERIFY(g_called && \"real * matrix<complex> not properly optimized\");\n  \n  g_called = false;\n  VERIFY_IS_APPROX(m1*s, m1*Scalar(s));\n  VERIFY(g_called && \"matrix<complex> * real not properly optimized\");\n  \n  g_called = false;\n  VERIFY_IS_APPROX(m1/s, m1/Scalar(s));\n  VERIFY(g_called && \"matrix<complex> / real not properly optimized\");\n\n  g_called = false;\n  VERIFY_IS_APPROX(s+m1.array(), Scalar(s)+m1.array());\n  VERIFY(g_called && \"real + matrix<complex> not properly optimized\");\n\n  g_called = false;\n  VERIFY_IS_APPROX(m1.array()+s, m1.array()+Scalar(s));\n  VERIFY(g_called && \"matrix<complex> + real not properly optimized\");\n\n  g_called = false;\n  VERIFY_IS_APPROX(s-m1.array(), Scalar(s)-m1.array());\n  VERIFY(g_called && \"real - matrix<complex> not properly optimized\");\n\n  g_called = false;\n  VERIFY_IS_APPROX(m1.array()-s, m1.array()-Scalar(s));\n  VERIFY(g_called && \"matrix<complex> - real not properly optimized\");\n}\n\ntemplate<int>\nvoid linearstructure_overflow()\n{\n  // make sure that /=scalar and /scalar do not overflow\n  // rational: 1.0/4.94e-320 overflow, but m/4.94e-320 should not\n  Matrix4d m2, m3;\n  m3 = m2 =  Matrix4d::Random()*1e-20;\n  m2 = m2 / 4.9e-320;\n  VERIFY_IS_APPROX(m2.cwiseQuotient(m2), Matrix4d::Ones());\n  m3 /= 4.9e-320;\n  VERIFY_IS_APPROX(m3.cwiseQuotient(m3), Matrix4d::Ones());\n}\n\nEIGEN_DECLARE_TEST(linearstructure)\n{\n  g_called = true;\n  VERIFY(g_called); // avoid `unneeded-internal-declaration` warning.\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( linearStructure(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( linearStructure(Matrix2f()) );\n    CALL_SUBTEST_3( linearStructure(Vector3d()) );\n    CALL_SUBTEST_4( linearStructure(Matrix4d()) );\n    CALL_SUBTEST_5( linearStructure(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2), internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))) );\n    CALL_SUBTEST_6( linearStructure(MatrixXf (internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_7( linearStructure(MatrixXi (internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_8( linearStructure(MatrixXcd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2), internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))) );\n    CALL_SUBTEST_9( linearStructure(ArrayXXf (internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_10( linearStructure(ArrayXXcf (internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    \n    CALL_SUBTEST_11( real_complex<Matrix4cd>() );\n    CALL_SUBTEST_11( real_complex<MatrixXcf>(10,10) );\n    CALL_SUBTEST_11( real_complex<ArrayXXcf>(10,10) );\n  }\n  CALL_SUBTEST_4( linearstructure_overflow<0>() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/lscg.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"sparse_solver.h\"\n#include <Eigen/IterativeLinearSolvers>\n\ntemplate<typename T> void test_lscg_T()\n{\n  LeastSquaresConjugateGradient<SparseMatrix<T> > lscg_colmajor_diag;\n  LeastSquaresConjugateGradient<SparseMatrix<T>, IdentityPreconditioner> lscg_colmajor_I;\n  LeastSquaresConjugateGradient<SparseMatrix<T,RowMajor> > lscg_rowmajor_diag;\n  LeastSquaresConjugateGradient<SparseMatrix<T,RowMajor>, IdentityPreconditioner> lscg_rowmajor_I;\n\n  CALL_SUBTEST( check_sparse_square_solving(lscg_colmajor_diag)  );\n  CALL_SUBTEST( check_sparse_square_solving(lscg_colmajor_I)     );\n  \n  CALL_SUBTEST( check_sparse_leastsquare_solving(lscg_colmajor_diag)  );\n  CALL_SUBTEST( check_sparse_leastsquare_solving(lscg_colmajor_I)     );\n\n  CALL_SUBTEST( check_sparse_square_solving(lscg_rowmajor_diag)  );\n  CALL_SUBTEST( check_sparse_square_solving(lscg_rowmajor_I)     );\n\n  CALL_SUBTEST( check_sparse_leastsquare_solving(lscg_rowmajor_diag)  );\n  CALL_SUBTEST( check_sparse_leastsquare_solving(lscg_rowmajor_I)     );\n}\n\nEIGEN_DECLARE_TEST(lscg)\n{\n  CALL_SUBTEST_1(test_lscg_T<double>());\n  CALL_SUBTEST_2(test_lscg_T<std::complex<double> >());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/lu.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/LU>\n#include \"solverbase.h\"\nusing namespace std;\n\ntemplate<typename MatrixType>\ntypename MatrixType::RealScalar matrix_l1_norm(const MatrixType& m) {\n  return m.cwiseAbs().colwise().sum().maxCoeff();\n}\n\ntemplate<typename MatrixType> void lu_non_invertible()\n{\n  STATIC_CHECK(( internal::is_same<typename FullPivLU<MatrixType>::StorageIndex,int>::value ));\n\n  typedef typename MatrixType::RealScalar RealScalar;\n  /* this test covers the following files:\n     LU.h\n  */\n  Index rows, cols, cols2;\n  if(MatrixType::RowsAtCompileTime==Dynamic)\n  {\n    rows = internal::random<Index>(2,EIGEN_TEST_MAX_SIZE);\n  }\n  else\n  {\n    rows = MatrixType::RowsAtCompileTime;\n  }\n  if(MatrixType::ColsAtCompileTime==Dynamic)\n  {\n    cols = internal::random<Index>(2,EIGEN_TEST_MAX_SIZE);\n    cols2 = internal::random<int>(2,EIGEN_TEST_MAX_SIZE);\n  }\n  else\n  {\n    cols2 = cols = MatrixType::ColsAtCompileTime;\n  }\n\n  enum {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime\n  };\n  typedef typename internal::kernel_retval_base<FullPivLU<MatrixType> >::ReturnType KernelMatrixType;\n  typedef typename internal::image_retval_base<FullPivLU<MatrixType> >::ReturnType ImageMatrixType;\n  typedef Matrix<typename MatrixType::Scalar, ColsAtCompileTime, ColsAtCompileTime>\n          CMatrixType;\n  typedef Matrix<typename MatrixType::Scalar, RowsAtCompileTime, RowsAtCompileTime>\n          RMatrixType;\n\n  Index rank = internal::random<Index>(1, (std::min)(rows, cols)-1);\n\n  // The image of the zero matrix should consist of a single (zero) column vector\n  VERIFY((MatrixType::Zero(rows,cols).fullPivLu().image(MatrixType::Zero(rows,cols)).cols() == 1));\n\n  // The kernel of the zero matrix is the entire space, and thus is an invertible matrix of dimensions cols.\n  KernelMatrixType kernel = MatrixType::Zero(rows,cols).fullPivLu().kernel();\n  VERIFY((kernel.fullPivLu().isInvertible()));\n\n  MatrixType m1(rows, cols), m3(rows, cols2);\n  CMatrixType m2(cols, cols2);\n  createRandomPIMatrixOfRank(rank, rows, cols, m1);\n\n  FullPivLU<MatrixType> lu;\n\n  // The special value 0.01 below works well in tests. Keep in mind that we're only computing the rank\n  // of singular values are either 0 or 1.\n  // So it's not clear at all that the epsilon should play any role there.\n  lu.setThreshold(RealScalar(0.01));\n  lu.compute(m1);\n\n  MatrixType u(rows,cols);\n  u = lu.matrixLU().template triangularView<Upper>();\n  RMatrixType l = RMatrixType::Identity(rows,rows);\n  l.block(0,0,rows,(std::min)(rows,cols)).template triangularView<StrictlyLower>()\n    = lu.matrixLU().block(0,0,rows,(std::min)(rows,cols));\n\n  VERIFY_IS_APPROX(lu.permutationP() * m1 * lu.permutationQ(), l*u);\n\n  KernelMatrixType m1kernel = lu.kernel();\n  ImageMatrixType m1image = lu.image(m1);\n\n  VERIFY_IS_APPROX(m1, lu.reconstructedMatrix());\n  VERIFY(rank == lu.rank());\n  VERIFY(cols - lu.rank() == lu.dimensionOfKernel());\n  VERIFY(!lu.isInjective());\n  VERIFY(!lu.isInvertible());\n  VERIFY(!lu.isSurjective());\n  VERIFY_IS_MUCH_SMALLER_THAN((m1 * m1kernel), m1);\n  VERIFY(m1image.fullPivLu().rank() == rank);\n  VERIFY_IS_APPROX(m1 * m1.adjoint() * m1image, m1image);\n\n  check_solverbase<CMatrixType, MatrixType>(m1, lu, rows, cols, cols2);\n\n  m2 = CMatrixType::Random(cols,cols2);\n  m3 = m1*m2;\n  m2 = CMatrixType::Random(cols,cols2);\n  // test that the code, which does resize(), may be applied to an xpr\n  m2.block(0,0,m2.rows(),m2.cols()) = lu.solve(m3);\n  VERIFY_IS_APPROX(m3, m1*m2);\n}\n\ntemplate<typename MatrixType> void lu_invertible()\n{\n  /* this test covers the following files:\n     FullPivLU.h\n  */\n  typedef typename NumTraits<typename MatrixType::Scalar>::Real RealScalar;\n  Index size = MatrixType::RowsAtCompileTime;\n  if( size==Dynamic)\n    size = internal::random<Index>(1,EIGEN_TEST_MAX_SIZE);\n\n  MatrixType m1(size, size), m2(size, size), m3(size, size);\n  FullPivLU<MatrixType> lu;\n  lu.setThreshold(RealScalar(0.01));\n  do {\n    m1 = MatrixType::Random(size,size);\n    lu.compute(m1);\n  } while(!lu.isInvertible());\n\n  VERIFY_IS_APPROX(m1, lu.reconstructedMatrix());\n  VERIFY(0 == lu.dimensionOfKernel());\n  VERIFY(lu.kernel().cols() == 1); // the kernel() should consist of a single (zero) column vector\n  VERIFY(size == lu.rank());\n  VERIFY(lu.isInjective());\n  VERIFY(lu.isSurjective());\n  VERIFY(lu.isInvertible());\n  VERIFY(lu.image(m1).fullPivLu().isInvertible());\n\n  check_solverbase<MatrixType, MatrixType>(m1, lu, size, size, size);\n\n  MatrixType m1_inverse = lu.inverse();\n  m3 = MatrixType::Random(size,size);\n  m2 = lu.solve(m3);\n  VERIFY_IS_APPROX(m2, m1_inverse*m3);\n\n  RealScalar rcond = (RealScalar(1) / matrix_l1_norm(m1)) / matrix_l1_norm(m1_inverse);\n  const RealScalar rcond_est = lu.rcond();\n  // Verify that the estimated condition number is within a factor of 10 of the\n  // truth.\n  VERIFY(rcond_est > rcond / 10 && rcond_est < rcond * 10);\n\n  // Regression test for Bug 302\n  MatrixType m4 = MatrixType::Random(size,size);\n  VERIFY_IS_APPROX(lu.solve(m3*m4), lu.solve(m3)*m4);\n}\n\ntemplate<typename MatrixType> void lu_partial_piv(Index size = MatrixType::ColsAtCompileTime)\n{\n  /* this test covers the following files:\n     PartialPivLU.h\n  */\n  typedef typename NumTraits<typename MatrixType::Scalar>::Real RealScalar;\n\n  MatrixType m1(size, size), m2(size, size), m3(size, size);\n  m1.setRandom();\n  PartialPivLU<MatrixType> plu(m1);\n\n  STATIC_CHECK(( internal::is_same<typename PartialPivLU<MatrixType>::StorageIndex,int>::value ));\n\n  VERIFY_IS_APPROX(m1, plu.reconstructedMatrix());\n\n  check_solverbase<MatrixType, MatrixType>(m1, plu, size, size, size);\n\n  MatrixType m1_inverse = plu.inverse();\n  m3 = MatrixType::Random(size,size);\n  m2 = plu.solve(m3);\n  VERIFY_IS_APPROX(m2, m1_inverse*m3);\n\n  RealScalar rcond = (RealScalar(1) / matrix_l1_norm(m1)) / matrix_l1_norm(m1_inverse);\n  const RealScalar rcond_est = plu.rcond();\n  // Verify that the estimate is within a factor of 10 of the truth.\n  VERIFY(rcond_est > rcond / 10 && rcond_est < rcond * 10);\n}\n\ntemplate<typename MatrixType> void lu_verify_assert()\n{\n  MatrixType tmp;\n\n  FullPivLU<MatrixType> lu;\n  VERIFY_RAISES_ASSERT(lu.matrixLU())\n  VERIFY_RAISES_ASSERT(lu.permutationP())\n  VERIFY_RAISES_ASSERT(lu.permutationQ())\n  VERIFY_RAISES_ASSERT(lu.kernel())\n  VERIFY_RAISES_ASSERT(lu.image(tmp))\n  VERIFY_RAISES_ASSERT(lu.solve(tmp))\n  VERIFY_RAISES_ASSERT(lu.transpose().solve(tmp))\n  VERIFY_RAISES_ASSERT(lu.adjoint().solve(tmp))\n  VERIFY_RAISES_ASSERT(lu.determinant())\n  VERIFY_RAISES_ASSERT(lu.rank())\n  VERIFY_RAISES_ASSERT(lu.dimensionOfKernel())\n  VERIFY_RAISES_ASSERT(lu.isInjective())\n  VERIFY_RAISES_ASSERT(lu.isSurjective())\n  VERIFY_RAISES_ASSERT(lu.isInvertible())\n  VERIFY_RAISES_ASSERT(lu.inverse())\n\n  PartialPivLU<MatrixType> plu;\n  VERIFY_RAISES_ASSERT(plu.matrixLU())\n  VERIFY_RAISES_ASSERT(plu.permutationP())\n  VERIFY_RAISES_ASSERT(plu.solve(tmp))\n  VERIFY_RAISES_ASSERT(plu.transpose().solve(tmp))\n  VERIFY_RAISES_ASSERT(plu.adjoint().solve(tmp))\n  VERIFY_RAISES_ASSERT(plu.determinant())\n  VERIFY_RAISES_ASSERT(plu.inverse())\n}\n\nEIGEN_DECLARE_TEST(lu)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( lu_non_invertible<Matrix3f>() );\n    CALL_SUBTEST_1( lu_invertible<Matrix3f>() );\n    CALL_SUBTEST_1( lu_verify_assert<Matrix3f>() );\n    CALL_SUBTEST_1( lu_partial_piv<Matrix3f>() );\n\n    CALL_SUBTEST_2( (lu_non_invertible<Matrix<double, 4, 6> >()) );\n    CALL_SUBTEST_2( (lu_verify_assert<Matrix<double, 4, 6> >()) );\n    CALL_SUBTEST_2( lu_partial_piv<Matrix2d>() );\n    CALL_SUBTEST_2( lu_partial_piv<Matrix4d>() );\n    CALL_SUBTEST_2( (lu_partial_piv<Matrix<double,6,6> >()) );\n\n    CALL_SUBTEST_3( lu_non_invertible<MatrixXf>() );\n    CALL_SUBTEST_3( lu_invertible<MatrixXf>() );\n    CALL_SUBTEST_3( lu_verify_assert<MatrixXf>() );\n\n    CALL_SUBTEST_4( lu_non_invertible<MatrixXd>() );\n    CALL_SUBTEST_4( lu_invertible<MatrixXd>() );\n    CALL_SUBTEST_4( lu_partial_piv<MatrixXd>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)) );\n    CALL_SUBTEST_4( lu_verify_assert<MatrixXd>() );\n\n    CALL_SUBTEST_5( lu_non_invertible<MatrixXcf>() );\n    CALL_SUBTEST_5( lu_invertible<MatrixXcf>() );\n    CALL_SUBTEST_5( lu_verify_assert<MatrixXcf>() );\n\n    CALL_SUBTEST_6( lu_non_invertible<MatrixXcd>() );\n    CALL_SUBTEST_6( lu_invertible<MatrixXcd>() );\n    CALL_SUBTEST_6( lu_partial_piv<MatrixXcd>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)) );\n    CALL_SUBTEST_6( lu_verify_assert<MatrixXcd>() );\n\n    CALL_SUBTEST_7(( lu_non_invertible<Matrix<float,Dynamic,16> >() ));\n\n    // Test problem size constructors\n    CALL_SUBTEST_9( PartialPivLU<MatrixXf>(10) );\n    CALL_SUBTEST_9( FullPivLU<MatrixXf>(10, 20); );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/main.h",
    "content": "\n// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <cstdlib>\n#include <cerrno>\n#include <ctime>\n#include <iostream>\n#include <fstream>\n#include <string>\n#include <sstream>\n#include <vector>\n#include <typeinfo>\n#include <functional>\n\n// The following includes of STL headers have to be done _before_ the\n// definition of macros min() and max().  The reason is that many STL\n// implementations will not work properly as the min and max symbols collide\n// with the STL functions std:min() and std::max().  The STL headers may check\n// for the macro definition of min/max and issue a warning or undefine the\n// macros.\n//\n// Still, Windows defines min() and max() in windef.h as part of the regular\n// Windows system interfaces and many other Windows APIs depend on these\n// macros being available.  To prevent the macro expansion of min/max and to\n// make Eigen compatible with the Windows environment all function calls of\n// std::min() and std::max() have to be written with parenthesis around the\n// function name.\n//\n// All STL headers used by Eigen should be included here.  Because main.h is\n// included before any Eigen header and because the STL headers are guarded\n// against multiple inclusions, no STL header will see our own min/max macro\n// definitions.\n#include <limits>\n#include <algorithm>\n// Disable ICC's std::complex operator specializations so we can use our own.\n#define _OVERRIDE_COMPLEX_SPECIALIZATION_ 1\n#include <complex>\n#include <deque>\n#include <queue>\n#include <cassert>\n#include <list>\n#if __cplusplus >= 201103L || (defined(_MSVC_LANG) && _MSVC_LANG >= 201103L)\n#include <random>\n#include <chrono>\n#ifdef EIGEN_USE_THREADS\n#include <future>\n#endif\n#endif\n\n// Same for cuda_fp16.h\n#if defined(__CUDACC__) && !defined(EIGEN_NO_CUDA)\n  // Means the compiler is either nvcc or clang with CUDA enabled\n  #define EIGEN_CUDACC __CUDACC__\n#endif\n#if defined(EIGEN_CUDACC)\n#include <cuda.h>\n  #define EIGEN_CUDA_SDK_VER (CUDA_VERSION * 10)\n#else\n  #define EIGEN_CUDA_SDK_VER 0\n#endif\n#if EIGEN_CUDA_SDK_VER >= 70500\n#include <cuda_fp16.h>\n#endif\n\n// To test that all calls from Eigen code to std::min() and std::max() are\n// protected by parenthesis against macro expansion, the min()/max() macros\n// are defined here and any not-parenthesized min/max call will cause a\n// compiler error.\n#if !defined(__HIPCC__) && !defined(EIGEN_USE_SYCL)\n  //\n  // HIP header files include the following files\n  //  <thread>\n  //  <regex>\n  //  <unordered_map>\n  // which seem to contain not-parenthesized calls to \"max\"/\"min\", triggering the following check and causing the compile to fail\n  //\n  // Including those header files before the following macro definition for \"min\" / \"max\", only partially resolves the issue\n  // This is because other HIP header files also define \"isnan\" / \"isinf\" / \"isfinite\" functions, which are needed in other\n  // headers.\n  //\n  // So instead choosing to simply disable this check for HIP\n  //\n  #define min(A,B) please_protect_your_min_with_parentheses\n  #define max(A,B) please_protect_your_max_with_parentheses\n  #define isnan(X) please_protect_your_isnan_with_parentheses\n  #define isinf(X) please_protect_your_isinf_with_parentheses\n  #define isfinite(X) please_protect_your_isfinite_with_parentheses\n#endif\n\n\n// test possible conflicts\nstruct real {};\nstruct imag {};\n\n#ifdef M_PI\n#undef M_PI\n#endif\n#define M_PI please_use_EIGEN_PI_instead_of_M_PI\n\n#define FORBIDDEN_IDENTIFIER (this_identifier_is_forbidden_to_avoid_clashes) this_identifier_is_forbidden_to_avoid_clashes\n// B0 is defined in POSIX header termios.h\n#define B0 FORBIDDEN_IDENTIFIER\n// `I` may be defined by complex.h:\n#define I  FORBIDDEN_IDENTIFIER\n\n// Unit tests calling Eigen's blas library must preserve the default blocking size\n// to avoid troubles.\n#ifndef EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS\n#define EIGEN_DEBUG_SMALL_PRODUCT_BLOCKS\n#endif\n\n// shuts down ICC's remark #593: variable \"XXX\" was set but never used\n#define TEST_SET_BUT_UNUSED_VARIABLE(X) EIGEN_UNUSED_VARIABLE(X)\n\n#ifdef TEST_ENABLE_TEMPORARY_TRACKING\n\nstatic long int nb_temporaries;\nstatic long int nb_temporaries_on_assert = -1;\n\ninline void on_temporary_creation(long int size) {\n  // here's a great place to set a breakpoint when debugging failures in this test!\n  if(size!=0) nb_temporaries++;\n  if(nb_temporaries_on_assert>0) assert(nb_temporaries<nb_temporaries_on_assert);\n}\n\n#define EIGEN_DENSE_STORAGE_CTOR_PLUGIN { on_temporary_creation(size); }\n\n#define VERIFY_EVALUATION_COUNT(XPR,N) {\\\n    nb_temporaries = 0; \\\n    XPR; \\\n    if(nb_temporaries!=(N)) { std::cerr << \"nb_temporaries == \" << nb_temporaries << \"\\n\"; }\\\n    VERIFY( (#XPR) && nb_temporaries==(N) ); \\\n  }\n\n#endif\n\n#include \"split_test_helper.h\"\n\n#ifdef NDEBUG\n#undef NDEBUG\n#endif\n\n// On windows CE, NDEBUG is automatically defined <assert.h> if NDEBUG is not defined.\n#ifndef DEBUG\n#define DEBUG\n#endif\n\n// bounds integer values for AltiVec\n#if defined(__ALTIVEC__) || defined(__VSX__)\n#define EIGEN_MAKING_DOCS\n#endif\n\n#define DEFAULT_REPEAT 10\n\nnamespace Eigen\n{\n  static std::vector<std::string> g_test_stack;\n  // level == 0 <=> abort if test fail\n  // level >= 1 <=> warning message to std::cerr if test fail\n  static int g_test_level = 0;\n  static int g_repeat = 1;\n  static unsigned int g_seed = 0;\n  static bool g_has_set_repeat = false, g_has_set_seed = false;\n\n  class EigenTest\n  {\n  public:\n    EigenTest() : m_func(0) {}\n    EigenTest(const char* a_name, void (*func)(void))\n      : m_name(a_name), m_func(func)\n    {\n      get_registered_tests().push_back(this);\n    }\n    const std::string& name() const { return m_name; }\n    void operator()() const { m_func(); }\n\n    static const std::vector<EigenTest*>& all() { return get_registered_tests(); }\n  protected:\n    static std::vector<EigenTest*>& get_registered_tests()\n    {\n      static std::vector<EigenTest*>* ms_registered_tests = new std::vector<EigenTest*>();\n      return *ms_registered_tests;\n    }\n    std::string m_name;\n    void (*m_func)(void);\n  };\n\n  // Declare and register a test, e.g.:\n  //    EIGEN_DECLARE_TEST(mytest) { ... }\n  // will create a function:\n  //    void test_mytest() { ... }\n  // that will be automatically called.\n  #define EIGEN_DECLARE_TEST(X) \\\n    void EIGEN_CAT(test_,X) (); \\\n    static EigenTest EIGEN_CAT(test_handler_,X) (EIGEN_MAKESTRING(X), & EIGEN_CAT(test_,X)); \\\n    void EIGEN_CAT(test_,X) ()\n}\n\n#define TRACK std::cerr << __FILE__ << \" \" << __LINE__ << std::endl\n// #define TRACK while()\n\n#define EIGEN_DEFAULT_IO_FORMAT IOFormat(4, 0, \"  \", \"\\n\", \"\", \"\", \"\", \"\")\n\n#if (defined(_CPPUNWIND) || defined(__EXCEPTIONS)) && !defined(__CUDA_ARCH__) && !defined(__HIP_DEVICE_COMPILE__) && !defined(__SYCL_DEVICE_ONLY__)\n  #define EIGEN_EXCEPTIONS\n#endif\n\n#ifndef EIGEN_NO_ASSERTION_CHECKING\n\n  namespace Eigen\n  {\n    static const bool should_raise_an_assert = false;\n\n    // Used to avoid to raise two exceptions at a time in which\n    // case the exception is not properly caught.\n    // This may happen when a second exceptions is triggered in a destructor.\n    static bool no_more_assert = false;\n    static bool report_on_cerr_on_assert_failure = true;\n\n    struct eigen_assert_exception\n    {\n      eigen_assert_exception(void) {}\n      ~eigen_assert_exception() { Eigen::no_more_assert = false; }\n    };\n\n    struct eigen_static_assert_exception\n    {\n      eigen_static_assert_exception(void) {}\n      ~eigen_static_assert_exception() { Eigen::no_more_assert = false; }\n    };\n  }\n  // If EIGEN_DEBUG_ASSERTS is defined and if no assertion is triggered while\n  // one should have been, then the list of executed assertions is printed out.\n  //\n  // EIGEN_DEBUG_ASSERTS is not enabled by default as it\n  // significantly increases the compilation time\n  // and might even introduce side effects that would hide\n  // some memory errors.\n  #ifdef EIGEN_DEBUG_ASSERTS\n\n    namespace Eigen\n    {\n      namespace internal\n      {\n        static bool push_assert = false;\n      }\n      static std::vector<std::string> eigen_assert_list;\n    }\n    #define eigen_assert(a)                       \\\n      if( (!(a)) && (!no_more_assert) )     \\\n      { \\\n        if(report_on_cerr_on_assert_failure) \\\n          std::cerr <<  #a << \" \" __FILE__ << \"(\" << __LINE__ << \")\\n\"; \\\n        Eigen::no_more_assert = true;       \\\n        EIGEN_THROW_X(Eigen::eigen_assert_exception()); \\\n      }                                     \\\n      else if (Eigen::internal::push_assert)       \\\n      {                                     \\\n        eigen_assert_list.push_back(std::string(EIGEN_MAKESTRING(__FILE__) \" (\" EIGEN_MAKESTRING(__LINE__) \") : \" #a) ); \\\n      }\n\n    #ifdef EIGEN_EXCEPTIONS\n    #define VERIFY_RAISES_ASSERT(a)                                                   \\\n      {                                                                               \\\n        Eigen::no_more_assert = false;                                                \\\n        Eigen::eigen_assert_list.clear();                                             \\\n        Eigen::internal::push_assert = true;                                          \\\n        Eigen::report_on_cerr_on_assert_failure = false;                              \\\n        try {                                                                         \\\n          a;                                                                          \\\n          std::cerr << \"One of the following asserts should have been triggered:\\n\";  \\\n          for (uint ai=0 ; ai<eigen_assert_list.size() ; ++ai)                        \\\n            std::cerr << \"  \" << eigen_assert_list[ai] << \"\\n\";                       \\\n          VERIFY(Eigen::should_raise_an_assert && # a);                               \\\n        } catch (Eigen::eigen_assert_exception) {                                     \\\n          Eigen::internal::push_assert = false; VERIFY(true);                         \\\n        }                                                                             \\\n        Eigen::report_on_cerr_on_assert_failure = true;                               \\\n        Eigen::internal::push_assert = false;                                         \\\n      }\n    #endif //EIGEN_EXCEPTIONS\n\n  #elif !defined(__CUDACC__) && !defined(__HIPCC__) && !defined(SYCL_DEVICE_ONLY) // EIGEN_DEBUG_ASSERTS\n    // see bug 89. The copy_bool here is working around a bug in gcc <= 4.3\n    #define eigen_assert(a) \\\n      if( (!Eigen::internal::copy_bool(a)) && (!no_more_assert) )\\\n      {                                       \\\n        Eigen::no_more_assert = true;         \\\n        if(report_on_cerr_on_assert_failure)  \\\n          eigen_plain_assert(a);              \\\n        else                                  \\\n          EIGEN_THROW_X(Eigen::eigen_assert_exception()); \\\n      }\n\n    #ifdef EIGEN_EXCEPTIONS\n      #define VERIFY_RAISES_ASSERT(a) {                           \\\n        Eigen::no_more_assert = false;                            \\\n        Eigen::report_on_cerr_on_assert_failure = false;          \\\n        try {                                                     \\\n          a;                                                      \\\n          VERIFY(Eigen::should_raise_an_assert && # a);           \\\n        }                                                         \\\n        catch (Eigen::eigen_assert_exception&) { VERIFY(true); }  \\\n        Eigen::report_on_cerr_on_assert_failure = true;           \\\n      }\n    #endif // EIGEN_EXCEPTIONS\n  #endif // EIGEN_DEBUG_ASSERTS\n\n  #if defined(TEST_CHECK_STATIC_ASSERTIONS) && defined(EIGEN_EXCEPTIONS)\n    #define EIGEN_STATIC_ASSERT(a,MSG) \\\n      if( (!Eigen::internal::copy_bool(a)) && (!no_more_assert) )\\\n      {                                       \\\n        Eigen::no_more_assert = true;         \\\n        if(report_on_cerr_on_assert_failure)  \\\n          eigen_plain_assert((a) && #MSG);      \\\n        else                                  \\\n          EIGEN_THROW_X(Eigen::eigen_static_assert_exception()); \\\n      }\n    #define VERIFY_RAISES_STATIC_ASSERT(a) {                    \\\n      Eigen::no_more_assert = false;                            \\\n      Eigen::report_on_cerr_on_assert_failure = false;          \\\n      try {                                                     \\\n        a;                                                      \\\n        VERIFY(Eigen::should_raise_an_assert && # a);           \\\n      }                                                         \\\n      catch (Eigen::eigen_static_assert_exception&) { VERIFY(true); }  \\\n      Eigen::report_on_cerr_on_assert_failure = true;           \\\n    }\n  #endif // TEST_CHECK_STATIC_ASSERTIONS\n\n#ifndef VERIFY_RAISES_ASSERT\n  #define VERIFY_RAISES_ASSERT(a) \\\n    std::cout << \"Can't VERIFY_RAISES_ASSERT( \" #a \" ) with exceptions disabled\\n\";\n#endif\n#ifndef VERIFY_RAISES_STATIC_ASSERT\n  #define VERIFY_RAISES_STATIC_ASSERT(a) \\\n    std::cout << \"Can't VERIFY_RAISES_STATIC_ASSERT( \" #a \" ) with exceptions disabled\\n\";\n#endif\n\n  #if !defined(__CUDACC__) && !defined(__HIPCC__) && !defined(SYCL_DEVICE_ONLY)\n  #define EIGEN_USE_CUSTOM_ASSERT\n  #endif\n\n#else // EIGEN_NO_ASSERTION_CHECKING\n\n  #define VERIFY_RAISES_ASSERT(a) {}\n  #define VERIFY_RAISES_STATIC_ASSERT(a) {}\n\n#endif // EIGEN_NO_ASSERTION_CHECKING\n\n#define EIGEN_INTERNAL_DEBUGGING\n#include <Eigen/QR> // required for createRandomPIMatrixOfRank\n\ninline void verify_impl(bool condition, const char *testname, const char *file, int line, const char *condition_as_string)\n{\n  if (!condition)\n  {\n    if(Eigen::g_test_level>0)\n      std::cerr << \"WARNING: \";\n    std::cerr << \"Test \" << testname << \" failed in \" << file << \" (\" << line << \")\"\n      << std::endl << \"    \" << condition_as_string << std::endl;\n    std::cerr << \"Stack:\\n\";\n    const int test_stack_size = static_cast<int>(Eigen::g_test_stack.size());\n    for(int i=test_stack_size-1; i>=0; --i)\n      std::cerr << \"  - \" << Eigen::g_test_stack[i] << \"\\n\";\n    std::cerr << \"\\n\";\n    if(Eigen::g_test_level==0)\n      abort();\n  }\n}\n\n#define VERIFY(a) ::verify_impl(a, g_test_stack.back().c_str(), __FILE__, __LINE__, EIGEN_MAKESTRING(a))\n\n#define VERIFY_GE(a, b) ::verify_impl(a >= b, g_test_stack.back().c_str(), __FILE__, __LINE__, EIGEN_MAKESTRING(a >= b))\n#define VERIFY_LE(a, b) ::verify_impl(a <= b, g_test_stack.back().c_str(), __FILE__, __LINE__, EIGEN_MAKESTRING(a <= b))\n\n\n#define VERIFY_IS_EQUAL(a, b) VERIFY(test_is_equal(a, b, true))\n#define VERIFY_IS_NOT_EQUAL(a, b) VERIFY(test_is_equal(a, b, false))\n#define VERIFY_IS_APPROX(a, b) VERIFY(verifyIsApprox(a, b))\n#define VERIFY_IS_NOT_APPROX(a, b) VERIFY(!test_isApprox(a, b))\n#define VERIFY_IS_MUCH_SMALLER_THAN(a, b) VERIFY(test_isMuchSmallerThan(a, b))\n#define VERIFY_IS_NOT_MUCH_SMALLER_THAN(a, b) VERIFY(!test_isMuchSmallerThan(a, b))\n#define VERIFY_IS_APPROX_OR_LESS_THAN(a, b) VERIFY(test_isApproxOrLessThan(a, b))\n#define VERIFY_IS_NOT_APPROX_OR_LESS_THAN(a, b) VERIFY(!test_isApproxOrLessThan(a, b))\n\n#define VERIFY_IS_UNITARY(a) VERIFY(test_isUnitary(a))\n\n#define STATIC_CHECK(COND) EIGEN_STATIC_ASSERT( (COND) , EIGEN_INTERNAL_ERROR_PLEASE_FILE_A_BUG_REPORT )\n\n#define CALL_SUBTEST(FUNC) do { \\\n    g_test_stack.push_back(EIGEN_MAKESTRING(FUNC)); \\\n    FUNC; \\\n    g_test_stack.pop_back(); \\\n  } while (0)\n\n\nnamespace Eigen {\n\ntemplate<typename T1,typename T2>\ntypename internal::enable_if<internal::is_same<T1,T2>::value,bool>::type\nis_same_type(const T1&, const T2&)\n{\n  return true;\n}\n\ntemplate<typename T> inline typename NumTraits<T>::Real test_precision() { return NumTraits<T>::dummy_precision(); }\ntemplate<> inline float test_precision<float>() { return 1e-3f; }\ntemplate<> inline double test_precision<double>() { return 1e-6; }\ntemplate<> inline long double test_precision<long double>() { return 1e-6l; }\ntemplate<> inline float test_precision<std::complex<float> >() { return test_precision<float>(); }\ntemplate<> inline double test_precision<std::complex<double> >() { return test_precision<double>(); }\ntemplate<> inline long double test_precision<std::complex<long double> >() { return test_precision<long double>(); }\n\n#define EIGEN_TEST_SCALAR_TEST_OVERLOAD(TYPE)                             \\\n  inline bool test_isApprox(TYPE a, TYPE b)                               \\\n  { return internal::isApprox(a, b, test_precision<TYPE>()); }            \\\n  inline bool test_isMuchSmallerThan(TYPE a, TYPE b)                      \\\n  { return internal::isMuchSmallerThan(a, b, test_precision<TYPE>()); }   \\\n  inline bool test_isApproxOrLessThan(TYPE a, TYPE b)                     \\\n  { return internal::isApproxOrLessThan(a, b, test_precision<TYPE>()); }\n\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(short)\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(unsigned short)\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(int)\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(unsigned int)\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(long)\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(unsigned long)\n#if EIGEN_HAS_CXX11\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(long long)\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(unsigned long long)\n#endif\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(float)\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(double)\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(half)\nEIGEN_TEST_SCALAR_TEST_OVERLOAD(bfloat16)\n\n#undef EIGEN_TEST_SCALAR_TEST_OVERLOAD\n\n#ifndef EIGEN_TEST_NO_COMPLEX\ninline bool test_isApprox(const std::complex<float>& a, const std::complex<float>& b)\n{ return internal::isApprox(a, b, test_precision<std::complex<float> >()); }\ninline bool test_isMuchSmallerThan(const std::complex<float>& a, const std::complex<float>& b)\n{ return internal::isMuchSmallerThan(a, b, test_precision<std::complex<float> >()); }\n\ninline bool test_isApprox(const std::complex<double>& a, const std::complex<double>& b)\n{ return internal::isApprox(a, b, test_precision<std::complex<double> >()); }\ninline bool test_isMuchSmallerThan(const std::complex<double>& a, const std::complex<double>& b)\n{ return internal::isMuchSmallerThan(a, b, test_precision<std::complex<double> >()); }\n\n#ifndef EIGEN_TEST_NO_LONGDOUBLE\ninline bool test_isApprox(const std::complex<long double>& a, const std::complex<long double>& b)\n{ return internal::isApprox(a, b, test_precision<std::complex<long double> >()); }\ninline bool test_isMuchSmallerThan(const std::complex<long double>& a, const std::complex<long double>& b)\n{ return internal::isMuchSmallerThan(a, b, test_precision<std::complex<long double> >()); }\n#endif\n#endif\n\n#ifndef EIGEN_TEST_NO_LONGDOUBLE\ninline bool test_isApprox(const long double& a, const long double& b)\n{\n    bool ret = internal::isApprox(a, b, test_precision<long double>());\n    if (!ret) std::cerr\n        << std::endl << \"    actual   = \" << a\n        << std::endl << \"    expected = \" << b << std::endl << std::endl;\n    return ret;\n}\n\ninline bool test_isMuchSmallerThan(const long double& a, const long double& b)\n{ return internal::isMuchSmallerThan(a, b, test_precision<long double>()); }\ninline bool test_isApproxOrLessThan(const long double& a, const long double& b)\n{ return internal::isApproxOrLessThan(a, b, test_precision<long double>()); }\n#endif // EIGEN_TEST_NO_LONGDOUBLE\n\n// test_relative_error returns the relative difference between a and b as a real scalar as used in isApprox.\ntemplate<typename T1,typename T2>\ntypename NumTraits<typename T1::RealScalar>::NonInteger test_relative_error(const EigenBase<T1> &a, const EigenBase<T2> &b)\n{\n  using std::sqrt;\n  typedef typename NumTraits<typename T1::RealScalar>::NonInteger RealScalar;\n  typename internal::nested_eval<T1,2>::type ea(a.derived());\n  typename internal::nested_eval<T2,2>::type eb(b.derived());\n  return sqrt(RealScalar((ea-eb).cwiseAbs2().sum()) / RealScalar((std::min)(eb.cwiseAbs2().sum(),ea.cwiseAbs2().sum())));\n}\n\ntemplate<typename T1,typename T2>\ntypename T1::RealScalar test_relative_error(const T1 &a, const T2 &b, const typename T1::Coefficients* = 0)\n{\n  return test_relative_error(a.coeffs(), b.coeffs());\n}\n\ntemplate<typename T1,typename T2>\ntypename T1::Scalar test_relative_error(const T1 &a, const T2 &b, const typename T1::MatrixType* = 0)\n{\n  return test_relative_error(a.matrix(), b.matrix());\n}\n\ntemplate<typename S, int D>\nS test_relative_error(const Translation<S,D> &a, const Translation<S,D> &b)\n{\n  return test_relative_error(a.vector(), b.vector());\n}\n\ntemplate <typename S, int D, int O>\nS test_relative_error(const ParametrizedLine<S,D,O> &a, const ParametrizedLine<S,D,O> &b)\n{\n  return (std::max)(test_relative_error(a.origin(), b.origin()), test_relative_error(a.origin(), b.origin()));\n}\n\ntemplate <typename S, int D>\nS test_relative_error(const AlignedBox<S,D> &a, const AlignedBox<S,D> &b)\n{\n  return (std::max)(test_relative_error((a.min)(), (b.min)()), test_relative_error((a.max)(), (b.max)()));\n}\n\ntemplate<typename Derived> class SparseMatrixBase;\ntemplate<typename T1,typename T2>\ntypename T1::RealScalar test_relative_error(const MatrixBase<T1> &a, const SparseMatrixBase<T2> &b)\n{\n  return test_relative_error(a,b.toDense());\n}\n\ntemplate<typename Derived> class SparseMatrixBase;\ntemplate<typename T1,typename T2>\ntypename T1::RealScalar test_relative_error(const SparseMatrixBase<T1> &a, const MatrixBase<T2> &b)\n{\n  return test_relative_error(a.toDense(),b);\n}\n\ntemplate<typename Derived> class SparseMatrixBase;\ntemplate<typename T1,typename T2>\ntypename T1::RealScalar test_relative_error(const SparseMatrixBase<T1> &a, const SparseMatrixBase<T2> &b)\n{\n  return test_relative_error(a.toDense(),b.toDense());\n}\n\ntemplate<typename T1,typename T2>\ntypename NumTraits<typename NumTraits<T1>::Real>::NonInteger test_relative_error(const T1 &a, const T2 &b, typename internal::enable_if<internal::is_arithmetic<typename NumTraits<T1>::Real>::value, T1>::type* = 0)\n{\n  typedef typename NumTraits<typename NumTraits<T1>::Real>::NonInteger RealScalar;\n  return numext::sqrt(RealScalar(numext::abs2(a-b))/(numext::mini)(RealScalar(numext::abs2(a)),RealScalar(numext::abs2(b))));\n}\n\ntemplate<typename T>\nT test_relative_error(const Rotation2D<T> &a, const Rotation2D<T> &b)\n{\n  return test_relative_error(a.angle(), b.angle());\n}\n\ntemplate<typename T>\nT test_relative_error(const AngleAxis<T> &a, const AngleAxis<T> &b)\n{\n  return (std::max)(test_relative_error(a.angle(), b.angle()), test_relative_error(a.axis(), b.axis()));\n}\n\ntemplate<typename Type1, typename Type2>\ninline bool test_isApprox(const Type1& a, const Type2& b, typename Type1::Scalar* = 0) // Enabled for Eigen's type only\n{\n  return a.isApprox(b, test_precision<typename Type1::Scalar>());\n}\n\n// get_test_precision is a small wrapper to test_precision allowing to return the scalar precision for either scalars or expressions\ntemplate<typename T>\ntypename NumTraits<typename T::Scalar>::Real get_test_precision(const T&, const typename T::Scalar* = 0)\n{\n  return test_precision<typename NumTraits<typename T::Scalar>::Real>();\n}\n\ntemplate<typename T>\ntypename NumTraits<T>::Real get_test_precision(const T&,typename internal::enable_if<internal::is_arithmetic<typename NumTraits<T>::Real>::value, T>::type* = 0)\n{\n  return test_precision<typename NumTraits<T>::Real>();\n}\n\n// verifyIsApprox is a wrapper to test_isApprox that outputs the relative difference magnitude if the test fails.\ntemplate<typename Type1, typename Type2>\ninline bool verifyIsApprox(const Type1& a, const Type2& b)\n{\n  bool ret = test_isApprox(a,b);\n  if(!ret)\n  {\n    std::cerr << \"Difference too large wrt tolerance \" << get_test_precision(a)  << \", relative error is: \" << test_relative_error(a,b) << std::endl;\n  }\n  return ret;\n}\n\n// The idea behind this function is to compare the two scalars a and b where\n// the scalar ref is a hint about the expected order of magnitude of a and b.\n// WARNING: the scalar a and b must be positive\n// Therefore, if for some reason a and b are very small compared to ref,\n// we won't issue a false negative.\n// This test could be: abs(a-b) <= eps * ref\n// However, it seems that simply comparing a+ref and b+ref is more sensitive to true error.\ntemplate<typename Scalar,typename ScalarRef>\ninline bool test_isApproxWithRef(const Scalar& a, const Scalar& b, const ScalarRef& ref)\n{\n  return test_isApprox(a+ref, b+ref);\n}\n\ntemplate<typename Derived1, typename Derived2>\ninline bool test_isMuchSmallerThan(const MatrixBase<Derived1>& m1,\n                                   const MatrixBase<Derived2>& m2)\n{\n  return m1.isMuchSmallerThan(m2, test_precision<typename internal::traits<Derived1>::Scalar>());\n}\n\ntemplate<typename Derived>\ninline bool test_isMuchSmallerThan(const MatrixBase<Derived>& m,\n                                   const typename NumTraits<typename internal::traits<Derived>::Scalar>::Real& s)\n{\n  return m.isMuchSmallerThan(s, test_precision<typename internal::traits<Derived>::Scalar>());\n}\n\ntemplate<typename Derived>\ninline bool test_isUnitary(const MatrixBase<Derived>& m)\n{\n  return m.isUnitary(test_precision<typename internal::traits<Derived>::Scalar>());\n}\n\n// Forward declaration to avoid ICC warning\ntemplate<typename T, typename U>\nbool test_is_equal(const T& actual, const U& expected, bool expect_equal=true);\n\ntemplate<typename T, typename U>\nbool test_is_equal(const T& actual, const U& expected, bool expect_equal)\n{\n    if ((actual==expected) == expect_equal)\n        return true;\n    // false:\n    std::cerr\n        << \"\\n    actual   = \" << actual\n        << \"\\n    expected \" << (expect_equal ? \"= \" : \"!=\") << expected << \"\\n\\n\";\n    return false;\n}\n\n/** Creates a random Partial Isometry matrix of given rank.\n  *\n  * A partial isometry is a matrix all of whose singular values are either 0 or 1.\n  * This is very useful to test rank-revealing algorithms.\n  */\n// Forward declaration to avoid ICC warning\ntemplate<typename MatrixType>\nvoid createRandomPIMatrixOfRank(Index desired_rank, Index rows, Index cols, MatrixType& m);\ntemplate<typename MatrixType>\nvoid createRandomPIMatrixOfRank(Index desired_rank, Index rows, Index cols, MatrixType& m)\n{\n  typedef typename internal::traits<MatrixType>::Scalar Scalar;\n  enum { Rows = MatrixType::RowsAtCompileTime, Cols = MatrixType::ColsAtCompileTime };\n\n  typedef Matrix<Scalar, Dynamic, 1> VectorType;\n  typedef Matrix<Scalar, Rows, Rows> MatrixAType;\n  typedef Matrix<Scalar, Cols, Cols> MatrixBType;\n\n  if(desired_rank == 0)\n  {\n    m.setZero(rows,cols);\n    return;\n  }\n\n  if(desired_rank == 1)\n  {\n    // here we normalize the vectors to get a partial isometry\n    m = VectorType::Random(rows).normalized() * VectorType::Random(cols).normalized().transpose();\n    return;\n  }\n\n  MatrixAType a = MatrixAType::Random(rows,rows);\n  MatrixType d = MatrixType::Identity(rows,cols);\n  MatrixBType  b = MatrixBType::Random(cols,cols);\n\n  // set the diagonal such that only desired_rank non-zero entries reamain\n  const Index diag_size = (std::min)(d.rows(),d.cols());\n  if(diag_size != desired_rank)\n    d.diagonal().segment(desired_rank, diag_size-desired_rank) = VectorType::Zero(diag_size-desired_rank);\n\n  HouseholderQR<MatrixAType> qra(a);\n  HouseholderQR<MatrixBType> qrb(b);\n  m = qra.householderQ() * d * qrb.householderQ();\n}\n\n// Forward declaration to avoid ICC warning\ntemplate<typename PermutationVectorType>\nvoid randomPermutationVector(PermutationVectorType& v, Index size);\ntemplate<typename PermutationVectorType>\nvoid randomPermutationVector(PermutationVectorType& v, Index size)\n{\n  typedef typename PermutationVectorType::Scalar Scalar;\n  v.resize(size);\n  for(Index i = 0; i < size; ++i) v(i) = Scalar(i);\n  if(size == 1) return;\n  for(Index n = 0; n < 3 * size; ++n)\n  {\n    Index i = internal::random<Index>(0, size-1);\n    Index j;\n    do j = internal::random<Index>(0, size-1); while(j==i);\n    std::swap(v(i), v(j));\n  }\n}\n\ntemplate<typename T> bool isNotNaN(const T& x)\n{\n  return x==x;\n}\n\ntemplate<typename T> bool isPlusInf(const T& x)\n{\n  return x > NumTraits<T>::highest();\n}\n\ntemplate<typename T> bool isMinusInf(const T& x)\n{\n  return x < NumTraits<T>::lowest();\n}\n\n} // end namespace Eigen\n\ntemplate<typename T> struct GetDifferentType;\n\ntemplate<> struct GetDifferentType<float> { typedef double type; };\ntemplate<> struct GetDifferentType<double> { typedef float type; };\ntemplate<typename T> struct GetDifferentType<std::complex<T> >\n{ typedef std::complex<typename GetDifferentType<T>::type> type; };\n\n// Forward declaration to avoid ICC warning\ntemplate<typename T> std::string type_name();\ntemplate<typename T> std::string type_name()                    { return \"other\"; }\ntemplate<> std::string type_name<float>()                       { return \"float\"; }\ntemplate<> std::string type_name<double>()                      { return \"double\"; }\ntemplate<> std::string type_name<long double>()                 { return \"long double\"; }\ntemplate<> std::string type_name<int>()                         { return \"int\"; }\ntemplate<> std::string type_name<std::complex<float> >()        { return \"complex<float>\"; }\ntemplate<> std::string type_name<std::complex<double> >()       { return \"complex<double>\"; }\ntemplate<> std::string type_name<std::complex<long double> >()  { return \"complex<long double>\"; }\ntemplate<> std::string type_name<std::complex<int> >()          { return \"complex<int>\"; }\n\nusing namespace Eigen;\n\ninline void set_repeat_from_string(const char *str)\n{\n  errno = 0;\n  g_repeat = int(strtoul(str, 0, 10));\n  if(errno || g_repeat <= 0)\n  {\n    std::cout << \"Invalid repeat value \" << str << std::endl;\n    exit(EXIT_FAILURE);\n  }\n  g_has_set_repeat = true;\n}\n\ninline void set_seed_from_string(const char *str)\n{\n  errno = 0;\n  g_seed = int(strtoul(str, 0, 10));\n  if(errno || g_seed == 0)\n  {\n    std::cout << \"Invalid seed value \" << str << std::endl;\n    exit(EXIT_FAILURE);\n  }\n  g_has_set_seed = true;\n}\n\nint main(int argc, char *argv[])\n{\n    g_has_set_repeat = false;\n    g_has_set_seed = false;\n    bool need_help = false;\n\n    for(int i = 1; i < argc; i++)\n    {\n      if(argv[i][0] == 'r')\n      {\n        if(g_has_set_repeat)\n        {\n          std::cout << \"Argument \" << argv[i] << \" conflicting with a former argument\" << std::endl;\n          return 1;\n        }\n        set_repeat_from_string(argv[i]+1);\n      }\n      else if(argv[i][0] == 's')\n      {\n        if(g_has_set_seed)\n        {\n          std::cout << \"Argument \" << argv[i] << \" conflicting with a former argument\" << std::endl;\n          return 1;\n        }\n         set_seed_from_string(argv[i]+1);\n      }\n      else\n      {\n        need_help = true;\n      }\n    }\n\n    if(need_help)\n    {\n      std::cout << \"This test application takes the following optional arguments:\" << std::endl;\n      std::cout << \"  rN     Repeat each test N times (default: \" << DEFAULT_REPEAT << \")\" << std::endl;\n      std::cout << \"  sN     Use N as seed for random numbers (default: based on current time)\" << std::endl;\n      std::cout << std::endl;\n      std::cout << \"If defined, the environment variables EIGEN_REPEAT and EIGEN_SEED\" << std::endl;\n      std::cout << \"will be used as default values for these parameters.\" << std::endl;\n      return 1;\n    }\n\n    char *env_EIGEN_REPEAT = getenv(\"EIGEN_REPEAT\");\n    if(!g_has_set_repeat && env_EIGEN_REPEAT)\n      set_repeat_from_string(env_EIGEN_REPEAT);\n    char *env_EIGEN_SEED = getenv(\"EIGEN_SEED\");\n    if(!g_has_set_seed && env_EIGEN_SEED)\n      set_seed_from_string(env_EIGEN_SEED);\n\n    if(!g_has_set_seed) g_seed = (unsigned int) time(NULL);\n    if(!g_has_set_repeat) g_repeat = DEFAULT_REPEAT;\n\n    std::cout << \"Initializing random number generator with seed \" << g_seed << std::endl;\n    std::stringstream ss;\n    ss << \"Seed: \" << g_seed;\n    g_test_stack.push_back(ss.str());\n    srand(g_seed);\n    std::cout << \"Repeating each test \" << g_repeat << \" times\" << std::endl;\n\n    VERIFY(EigenTest::all().size()>0);\n\n    for(std::size_t i=0; i<EigenTest::all().size(); ++i)\n    {\n      const EigenTest& current_test = *EigenTest::all()[i];\n      Eigen::g_test_stack.push_back(current_test.name());\n      current_test();\n      Eigen::g_test_stack.pop_back();\n    }\n\n    return 0;\n}\n\n// These warning are disabled here such that they are still ON when parsing Eigen's header files.\n#if defined __INTEL_COMPILER\n  // remark #383: value copied to temporary, reference to temporary used\n  //  -> this warning is raised even for legal usage as: g_test_stack.push_back(\"foo\"); where g_test_stack is a std::vector<std::string>\n  // remark #1418: external function definition with no prior declaration\n  //  -> this warning is raised for all our test functions. Declaring them static would fix the issue.\n  // warning #279: controlling expression is constant\n  // remark #1572: floating-point equality and inequality comparisons are unreliable\n  #pragma warning disable 279 383 1418 1572\n#endif\n\n#ifdef _MSC_VER\n  // 4503 - decorated name length exceeded, name was truncated\n  #pragma warning( disable : 4503)\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/mapped_matrix.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_NO_STATIC_ASSERT\n#define EIGEN_NO_STATIC_ASSERT // turn static asserts into runtime asserts in order to check them\n#endif\n\n#include \"main.h\"\n\n#define EIGEN_TESTMAP_MAX_SIZE 256\n\ntemplate<typename VectorType> void map_class_vector(const VectorType& m)\n{\n  typedef typename VectorType::Scalar Scalar;\n\n  Index size = m.size();\n\n  Scalar* array1 = internal::aligned_new<Scalar>(size);\n  Scalar* array2 = internal::aligned_new<Scalar>(size);\n  Scalar* array3 = new Scalar[size+1];\n  Scalar* array3unaligned = (internal::UIntPtr(array3)%EIGEN_MAX_ALIGN_BYTES) == 0 ? array3+1 : array3;\n  Scalar  array4[EIGEN_TESTMAP_MAX_SIZE];\n\n  Map<VectorType, AlignedMax>(array1, size) = VectorType::Random(size);\n  Map<VectorType, AlignedMax>(array2, size) = Map<VectorType,AlignedMax>(array1, size);\n  Map<VectorType>(array3unaligned, size) = Map<VectorType>(array1, size);\n  Map<VectorType>(array4, size)          = Map<VectorType,AlignedMax>(array1, size);\n  VectorType ma1 = Map<VectorType, AlignedMax>(array1, size);\n  VectorType ma2 = Map<VectorType, AlignedMax>(array2, size);\n  VectorType ma3 = Map<VectorType>(array3unaligned, size);\n  VectorType ma4 = Map<VectorType>(array4, size);\n  VERIFY_IS_EQUAL(ma1, ma2);\n  VERIFY_IS_EQUAL(ma1, ma3);\n  VERIFY_IS_EQUAL(ma1, ma4);\n  #ifdef EIGEN_VECTORIZE\n  if(internal::packet_traits<Scalar>::Vectorizable && size>=AlignedMax)\n    VERIFY_RAISES_ASSERT((Map<VectorType,AlignedMax>(array3unaligned, size)))\n  #endif\n\n  internal::aligned_delete(array1, size);\n  internal::aligned_delete(array2, size);\n  delete[] array3;\n}\n\ntemplate<typename MatrixType> void map_class_matrix(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index rows = m.rows(), cols = m.cols(), size = rows*cols;\n  Scalar s1 = internal::random<Scalar>();\n\n  // array1 and array2 -> aligned heap allocation\n  Scalar* array1 = internal::aligned_new<Scalar>(size);\n  for(int i = 0; i < size; i++) array1[i] = Scalar(1);\n  Scalar* array2 = internal::aligned_new<Scalar>(size);\n  for(int i = 0; i < size; i++) array2[i] = Scalar(1);\n  // array3unaligned -> unaligned pointer to heap\n  Scalar* array3 = new Scalar[size+1];\n  Index sizep1 = size + 1; // <- without this temporary MSVC 2103 generates bad code\n  for(Index i = 0; i < sizep1; i++) array3[i] = Scalar(1);\n  Scalar* array3unaligned = (internal::UIntPtr(array3)%EIGEN_MAX_ALIGN_BYTES) == 0 ? array3+1 : array3;\n  Scalar array4[256];\n  if(size<=256)\n    for(int i = 0; i < size; i++) array4[i] = Scalar(1);\n  \n  Map<MatrixType> map1(array1, rows, cols);\n  Map<MatrixType, AlignedMax> map2(array2, rows, cols);\n  Map<MatrixType> map3(array3unaligned, rows, cols);\n  Map<MatrixType> map4(array4, rows, cols);\n  \n  VERIFY_IS_EQUAL(map1, MatrixType::Ones(rows,cols));\n  VERIFY_IS_EQUAL(map2, MatrixType::Ones(rows,cols));\n  VERIFY_IS_EQUAL(map3, MatrixType::Ones(rows,cols));\n  map1 = MatrixType::Random(rows,cols);\n  map2 = map1;\n  map3 = map1;\n  MatrixType ma1 = map1;\n  MatrixType ma2 = map2;\n  MatrixType ma3 = map3;\n  VERIFY_IS_EQUAL(map1, map2);\n  VERIFY_IS_EQUAL(map1, map3);\n  VERIFY_IS_EQUAL(ma1, ma2);\n  VERIFY_IS_EQUAL(ma1, ma3);\n  VERIFY_IS_EQUAL(ma1, map3);\n  \n  VERIFY_IS_APPROX(s1*map1, s1*map2);\n  VERIFY_IS_APPROX(s1*ma1, s1*ma2);\n  VERIFY_IS_EQUAL(s1*ma1, s1*ma3);\n  VERIFY_IS_APPROX(s1*map1, s1*map3);\n  \n  map2 *= s1;\n  map3 *= s1;\n  VERIFY_IS_APPROX(s1*map1, map2);\n  VERIFY_IS_APPROX(s1*map1, map3);\n  \n  if(size<=256)\n  {\n    VERIFY_IS_EQUAL(map4, MatrixType::Ones(rows,cols));\n    map4 = map1;\n    MatrixType ma4 = map4;\n    VERIFY_IS_EQUAL(map1, map4);\n    VERIFY_IS_EQUAL(ma1, map4);\n    VERIFY_IS_EQUAL(ma1, ma4);\n    VERIFY_IS_APPROX(s1*map1, s1*map4);\n    \n    map4 *= s1;\n    VERIFY_IS_APPROX(s1*map1, map4);\n  }\n\n  internal::aligned_delete(array1, size);\n  internal::aligned_delete(array2, size);\n  delete[] array3;\n}\n\ntemplate<typename VectorType> void map_static_methods(const VectorType& m)\n{\n  typedef typename VectorType::Scalar Scalar;\n\n  Index size = m.size();\n\n  Scalar* array1 = internal::aligned_new<Scalar>(size);\n  Scalar* array2 = internal::aligned_new<Scalar>(size);\n  Scalar* array3 = new Scalar[size+1];\n  Scalar* array3unaligned = internal::UIntPtr(array3)%EIGEN_MAX_ALIGN_BYTES == 0 ? array3+1 : array3;\n\n  VectorType::MapAligned(array1, size) = VectorType::Random(size);\n  VectorType::Map(array2, size) = VectorType::Map(array1, size);\n  VectorType::Map(array3unaligned, size) = VectorType::Map(array1, size);\n  VectorType ma1 = VectorType::Map(array1, size);\n  VectorType ma2 = VectorType::MapAligned(array2, size);\n  VectorType ma3 = VectorType::Map(array3unaligned, size);\n  VERIFY_IS_EQUAL(ma1, ma2);\n  VERIFY_IS_EQUAL(ma1, ma3);\n\n  internal::aligned_delete(array1, size);\n  internal::aligned_delete(array2, size);\n  delete[] array3;\n}\n\ntemplate<typename PlainObjectType> void check_const_correctness(const PlainObjectType&)\n{\n  // there's a lot that we can't test here while still having this test compile!\n  // the only possible approach would be to run a script trying to compile stuff and checking that it fails.\n  // CMake can help with that.\n\n  // verify that map-to-const don't have LvalueBit\n  typedef typename internal::add_const<PlainObjectType>::type ConstPlainObjectType;\n  VERIFY( !(internal::traits<Map<ConstPlainObjectType> >::Flags & LvalueBit) );\n  VERIFY( !(internal::traits<Map<ConstPlainObjectType, AlignedMax> >::Flags & LvalueBit) );\n  VERIFY( !(Map<ConstPlainObjectType>::Flags & LvalueBit) );\n  VERIFY( !(Map<ConstPlainObjectType, AlignedMax>::Flags & LvalueBit) );\n}\n\ntemplate<typename Scalar>\nvoid map_not_aligned_on_scalar()\n{\n  typedef Matrix<Scalar,Dynamic,Dynamic> MatrixType;\n  Index size = 11;\n  Scalar* array1 = internal::aligned_new<Scalar>((size+1)*(size+1)+1);\n  Scalar* array2 = reinterpret_cast<Scalar*>(sizeof(Scalar)/2+std::size_t(array1));\n  Map<MatrixType,0,OuterStride<> > map2(array2, size, size, OuterStride<>(size+1));\n  MatrixType m2 = MatrixType::Random(size,size);\n  map2 = m2;\n  VERIFY_IS_EQUAL(m2, map2);\n  \n  typedef Matrix<Scalar,Dynamic,1> VectorType;\n  Map<VectorType> map3(array2, size);\n  MatrixType v3 = VectorType::Random(size);\n  map3 = v3;\n  VERIFY_IS_EQUAL(v3, map3);\n  \n  internal::aligned_delete(array1, (size+1)*(size+1)+1);\n}\n\nEIGEN_DECLARE_TEST(mapped_matrix)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( map_class_vector(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_1( check_const_correctness(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( map_class_vector(Vector4d()) );\n    CALL_SUBTEST_2( map_class_vector(VectorXd(13)) );\n    CALL_SUBTEST_2( check_const_correctness(Matrix4d()) );\n    CALL_SUBTEST_3( map_class_vector(RowVector4f()) );\n    CALL_SUBTEST_4( map_class_vector(VectorXcf(8)) );\n    CALL_SUBTEST_5( map_class_vector(VectorXi(12)) );\n    CALL_SUBTEST_5( check_const_correctness(VectorXi(12)) );\n\n    CALL_SUBTEST_1( map_class_matrix(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( map_class_matrix(Matrix4d()) );\n    CALL_SUBTEST_11( map_class_matrix(Matrix<float,3,5>()) );\n    CALL_SUBTEST_4( map_class_matrix(MatrixXcf(internal::random<int>(1,10),internal::random<int>(1,10))) );\n    CALL_SUBTEST_5( map_class_matrix(MatrixXi(internal::random<int>(1,10),internal::random<int>(1,10))) );\n\n    CALL_SUBTEST_6( map_static_methods(Matrix<double, 1, 1>()) );\n    CALL_SUBTEST_7( map_static_methods(Vector3f()) );\n    CALL_SUBTEST_8( map_static_methods(RowVector3d()) );\n    CALL_SUBTEST_9( map_static_methods(VectorXcd(8)) );\n    CALL_SUBTEST_10( map_static_methods(VectorXf(12)) );\n    CALL_SUBTEST_11( map_not_aligned_on_scalar<double>() );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/mapstaticmethods.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n// GCC<=4.8 has spurious shadow warnings, because `ptr` re-appears inside template instantiations\n// workaround: put these in an anonymous namespace\nnamespace {\nfloat *ptr;\nconst float *const_ptr;\n}\n\ntemplate<typename PlainObjectType,\n         bool IsDynamicSize = PlainObjectType::SizeAtCompileTime == Dynamic,\n         bool IsVector = PlainObjectType::IsVectorAtCompileTime\n>\nstruct mapstaticmethods_impl {};\n\ntemplate<typename PlainObjectType, bool IsVector>\nstruct mapstaticmethods_impl<PlainObjectType, false, IsVector>\n{\n  static void run(const PlainObjectType& m)\n  {\n    mapstaticmethods_impl<PlainObjectType, true, IsVector>::run(m);\n\n    int i = internal::random<int>(2,5), j = internal::random<int>(2,5);\n\n    PlainObjectType::Map(ptr).setZero();\n    PlainObjectType::MapAligned(ptr).setZero();\n    PlainObjectType::Map(const_ptr).sum();\n    PlainObjectType::MapAligned(const_ptr).sum();\n\n    PlainObjectType::Map(ptr, InnerStride<>(i)).setZero();\n    PlainObjectType::MapAligned(ptr, InnerStride<>(i)).setZero();\n    PlainObjectType::Map(const_ptr, InnerStride<>(i)).sum();\n    PlainObjectType::MapAligned(const_ptr, InnerStride<>(i)).sum();\n\n    PlainObjectType::Map(ptr, InnerStride<2>()).setZero();\n    PlainObjectType::MapAligned(ptr, InnerStride<3>()).setZero();\n    PlainObjectType::Map(const_ptr, InnerStride<4>()).sum();\n    PlainObjectType::MapAligned(const_ptr, InnerStride<5>()).sum();\n\n    PlainObjectType::Map(ptr, OuterStride<>(i)).setZero();\n    PlainObjectType::MapAligned(ptr, OuterStride<>(i)).setZero();\n    PlainObjectType::Map(const_ptr, OuterStride<>(i)).sum();\n    PlainObjectType::MapAligned(const_ptr, OuterStride<>(i)).sum();\n\n    PlainObjectType::Map(ptr, OuterStride<2>()).setZero();\n    PlainObjectType::MapAligned(ptr, OuterStride<3>()).setZero();\n    PlainObjectType::Map(const_ptr, OuterStride<4>()).sum();\n    PlainObjectType::MapAligned(const_ptr, OuterStride<5>()).sum();\n\n    PlainObjectType::Map(ptr, Stride<Dynamic, Dynamic>(i,j)).setZero();\n    PlainObjectType::MapAligned(ptr, Stride<2,Dynamic>(2,i)).setZero();\n    PlainObjectType::Map(const_ptr, Stride<Dynamic,3>(i,3)).sum();\n    PlainObjectType::MapAligned(const_ptr, Stride<Dynamic, Dynamic>(i,j)).sum();\n\n    PlainObjectType::Map(ptr, Stride<2,3>()).setZero();\n    PlainObjectType::MapAligned(ptr, Stride<3,4>()).setZero();\n    PlainObjectType::Map(const_ptr, Stride<2,4>()).sum();\n    PlainObjectType::MapAligned(const_ptr, Stride<5,3>()).sum();\n  }\n};\n\ntemplate<typename PlainObjectType>\nstruct mapstaticmethods_impl<PlainObjectType, true, false>\n{\n  static void run(const PlainObjectType& m)\n  {\n    Index rows = m.rows(), cols = m.cols();\n\n    int i = internal::random<int>(2,5), j = internal::random<int>(2,5);\n\n    PlainObjectType::Map(ptr, rows, cols).setZero();\n    PlainObjectType::MapAligned(ptr, rows, cols).setZero();\n    PlainObjectType::Map(const_ptr, rows, cols).sum();\n    PlainObjectType::MapAligned(const_ptr, rows, cols).sum();\n\n    PlainObjectType::Map(ptr, rows, cols, InnerStride<>(i)).setZero();\n    PlainObjectType::MapAligned(ptr, rows, cols, InnerStride<>(i)).setZero();\n    PlainObjectType::Map(const_ptr, rows, cols, InnerStride<>(i)).sum();\n    PlainObjectType::MapAligned(const_ptr, rows, cols, InnerStride<>(i)).sum();\n\n    PlainObjectType::Map(ptr, rows, cols, InnerStride<2>()).setZero();\n    PlainObjectType::MapAligned(ptr, rows, cols, InnerStride<3>()).setZero();\n    PlainObjectType::Map(const_ptr, rows, cols, InnerStride<4>()).sum();\n    PlainObjectType::MapAligned(const_ptr, rows, cols, InnerStride<5>()).sum();\n\n    PlainObjectType::Map(ptr, rows, cols, OuterStride<>(i)).setZero();\n    PlainObjectType::MapAligned(ptr, rows, cols, OuterStride<>(i)).setZero();\n    PlainObjectType::Map(const_ptr, rows, cols, OuterStride<>(i)).sum();\n    PlainObjectType::MapAligned(const_ptr, rows, cols, OuterStride<>(i)).sum();\n\n    PlainObjectType::Map(ptr, rows, cols, OuterStride<2>()).setZero();\n    PlainObjectType::MapAligned(ptr, rows, cols, OuterStride<3>()).setZero();\n    PlainObjectType::Map(const_ptr, rows, cols, OuterStride<4>()).sum();\n    PlainObjectType::MapAligned(const_ptr, rows, cols, OuterStride<5>()).sum();\n\n    PlainObjectType::Map(ptr, rows, cols, Stride<Dynamic, Dynamic>(i,j)).setZero();\n    PlainObjectType::MapAligned(ptr, rows, cols, Stride<2,Dynamic>(2,i)).setZero();\n    PlainObjectType::Map(const_ptr, rows, cols, Stride<Dynamic,3>(i,3)).sum();\n    PlainObjectType::MapAligned(const_ptr, rows, cols, Stride<Dynamic, Dynamic>(i,j)).sum();\n\n    PlainObjectType::Map(ptr, rows, cols, Stride<2,3>()).setZero();\n    PlainObjectType::MapAligned(ptr, rows, cols, Stride<3,4>()).setZero();\n    PlainObjectType::Map(const_ptr, rows, cols, Stride<2,4>()).sum();\n    PlainObjectType::MapAligned(const_ptr, rows, cols, Stride<5,3>()).sum();\n  }\n};\n\ntemplate<typename PlainObjectType>\nstruct mapstaticmethods_impl<PlainObjectType, true, true>\n{\n  static void run(const PlainObjectType& v)\n  {\n    Index size = v.size();\n\n    int i = internal::random<int>(2,5);\n\n    PlainObjectType::Map(ptr, size).setZero();\n    PlainObjectType::MapAligned(ptr, size).setZero();\n    PlainObjectType::Map(const_ptr, size).sum();\n    PlainObjectType::MapAligned(const_ptr, size).sum();\n\n    PlainObjectType::Map(ptr, size, InnerStride<>(i)).setZero();\n    PlainObjectType::MapAligned(ptr, size, InnerStride<>(i)).setZero();\n    PlainObjectType::Map(const_ptr, size, InnerStride<>(i)).sum();\n    PlainObjectType::MapAligned(const_ptr, size, InnerStride<>(i)).sum();\n\n    PlainObjectType::Map(ptr, size, InnerStride<2>()).setZero();\n    PlainObjectType::MapAligned(ptr, size, InnerStride<3>()).setZero();\n    PlainObjectType::Map(const_ptr, size, InnerStride<4>()).sum();\n    PlainObjectType::MapAligned(const_ptr, size, InnerStride<5>()).sum();\n  }\n};\n\ntemplate<typename PlainObjectType>\nvoid mapstaticmethods(const PlainObjectType& m)\n{\n  mapstaticmethods_impl<PlainObjectType>::run(m);\n  VERIFY(true); // just to avoid 'unused function' warning\n}\n\nEIGEN_DECLARE_TEST(mapstaticmethods)\n{\n  ptr = internal::aligned_new<float>(1000);\n  for(int i = 0; i < 1000; i++) ptr[i] = float(i);\n\n  const_ptr = ptr;\n\n  CALL_SUBTEST_1(( mapstaticmethods(Matrix<float, 1, 1>()) ));\n  CALL_SUBTEST_1(( mapstaticmethods(Vector2f()) ));\n  CALL_SUBTEST_2(( mapstaticmethods(Vector3f()) ));\n  CALL_SUBTEST_2(( mapstaticmethods(Matrix2f()) ));\n  CALL_SUBTEST_3(( mapstaticmethods(Matrix4f()) ));\n  CALL_SUBTEST_3(( mapstaticmethods(Array4f()) ));\n  CALL_SUBTEST_4(( mapstaticmethods(Array3f()) ));\n  CALL_SUBTEST_4(( mapstaticmethods(Array33f()) ));\n  CALL_SUBTEST_5(( mapstaticmethods(Array44f()) ));\n  CALL_SUBTEST_5(( mapstaticmethods(VectorXf(1)) ));\n  CALL_SUBTEST_5(( mapstaticmethods(VectorXf(8)) ));\n  CALL_SUBTEST_6(( mapstaticmethods(MatrixXf(1,1)) ));\n  CALL_SUBTEST_6(( mapstaticmethods(MatrixXf(5,7)) ));\n  CALL_SUBTEST_7(( mapstaticmethods(ArrayXf(1)) ));\n  CALL_SUBTEST_7(( mapstaticmethods(ArrayXf(5)) ));\n  CALL_SUBTEST_8(( mapstaticmethods(ArrayXXf(1,1)) ));\n  CALL_SUBTEST_8(( mapstaticmethods(ArrayXXf(8,6)) ));\n\n  internal::aligned_delete(ptr, 1000);\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/mapstride.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<int Alignment,typename VectorType> void map_class_vector(const VectorType& m)\n{\n  typedef typename VectorType::Scalar Scalar;\n\n  Index size = m.size();\n\n  VectorType v = VectorType::Random(size);\n\n  Index arraysize = 3*size;\n  \n  Scalar* a_array = internal::aligned_new<Scalar>(arraysize+1);\n  Scalar* array = a_array;\n  if(Alignment!=Aligned)\n    array = (Scalar*)(internal::IntPtr(a_array) + (internal::packet_traits<Scalar>::AlignedOnScalar?sizeof(Scalar):sizeof(typename NumTraits<Scalar>::Real)));\n\n  {\n    Map<VectorType, Alignment, InnerStride<3> > map(array, size);\n    map = v;\n    for(int i = 0; i < size; ++i)\n    {\n      VERIFY(array[3*i] == v[i]);\n      VERIFY(map[i] == v[i]);\n    }\n  }\n\n  {\n    Map<VectorType, Unaligned, InnerStride<Dynamic> > map(array, size, InnerStride<Dynamic>(2));\n    map = v;\n    for(int i = 0; i < size; ++i)\n    {\n      VERIFY(array[2*i] == v[i]);\n      VERIFY(map[i] == v[i]);\n    }\n  }\n\n  internal::aligned_delete(a_array, arraysize+1);\n}\n\ntemplate<int Alignment,typename MatrixType> void map_class_matrix(const MatrixType& _m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index rows = _m.rows(), cols = _m.cols();\n\n  MatrixType m = MatrixType::Random(rows,cols);\n  Scalar s1 = internal::random<Scalar>();\n\n  Index arraysize = 4*(rows+4)*(cols+4);\n\n  Scalar* a_array1 = internal::aligned_new<Scalar>(arraysize+1);\n  Scalar* array1 = a_array1;\n  if(Alignment!=Aligned)\n    array1 = (Scalar*)(internal::IntPtr(a_array1) + (internal::packet_traits<Scalar>::AlignedOnScalar?sizeof(Scalar):sizeof(typename NumTraits<Scalar>::Real)));\n\n  Scalar a_array2[256];\n  Scalar* array2 = a_array2;\n  if(Alignment!=Aligned)\n    array2 = (Scalar*)(internal::IntPtr(a_array2) + (internal::packet_traits<Scalar>::AlignedOnScalar?sizeof(Scalar):sizeof(typename NumTraits<Scalar>::Real)));\n  else\n    array2 = (Scalar*)(((internal::UIntPtr(a_array2)+EIGEN_MAX_ALIGN_BYTES-1)/EIGEN_MAX_ALIGN_BYTES)*EIGEN_MAX_ALIGN_BYTES);\n  Index maxsize2 = a_array2 - array2 + 256;\n  \n  // test no inner stride and some dynamic outer stride\n  for(int k=0; k<2; ++k)\n  {\n    if(k==1 && (m.innerSize()+1)*m.outerSize() > maxsize2)\n      break;\n    Scalar* array = (k==0 ? array1 : array2);\n    \n    Map<MatrixType, Alignment, OuterStride<Dynamic> > map(array, rows, cols, OuterStride<Dynamic>(m.innerSize()+1));\n    map = m;\n    VERIFY(map.outerStride() == map.innerSize()+1);\n    for(int i = 0; i < m.outerSize(); ++i)\n      for(int j = 0; j < m.innerSize(); ++j)\n      {\n        VERIFY(array[map.outerStride()*i+j] == m.coeffByOuterInner(i,j));\n        VERIFY(map.coeffByOuterInner(i,j) == m.coeffByOuterInner(i,j));\n      }\n    VERIFY_IS_APPROX(s1*map,s1*m);\n    map *= s1;\n    VERIFY_IS_APPROX(map,s1*m);\n  }\n\n  // test no inner stride and an outer stride of +4. This is quite important as for fixed-size matrices,\n  // this allows to hit the special case where it's vectorizable.\n  for(int k=0; k<2; ++k)\n  {\n    if(k==1 && (m.innerSize()+4)*m.outerSize() > maxsize2)\n      break;\n    Scalar* array = (k==0 ? array1 : array2);\n    \n    enum {\n      InnerSize = MatrixType::InnerSizeAtCompileTime,\n      OuterStrideAtCompileTime = InnerSize==Dynamic ? Dynamic : InnerSize+4\n    };\n    Map<MatrixType, Alignment, OuterStride<OuterStrideAtCompileTime> >\n      map(array, rows, cols, OuterStride<OuterStrideAtCompileTime>(m.innerSize()+4));\n    map = m;\n    VERIFY(map.outerStride() == map.innerSize()+4);\n    for(int i = 0; i < m.outerSize(); ++i)\n      for(int j = 0; j < m.innerSize(); ++j)\n      {\n        VERIFY(array[map.outerStride()*i+j] == m.coeffByOuterInner(i,j));\n        VERIFY(map.coeffByOuterInner(i,j) == m.coeffByOuterInner(i,j));\n      }\n    VERIFY_IS_APPROX(s1*map,s1*m);\n    map *= s1;\n    VERIFY_IS_APPROX(map,s1*m);\n  }\n\n  // test both inner stride and outer stride\n  for(int k=0; k<2; ++k)\n  {\n    if(k==1 && (2*m.innerSize()+1)*(m.outerSize()*2) > maxsize2)\n      break;\n    Scalar* array = (k==0 ? array1 : array2);\n    \n    Map<MatrixType, Alignment, Stride<Dynamic,Dynamic> > map(array, rows, cols, Stride<Dynamic,Dynamic>(2*m.innerSize()+1, 2));\n    map = m;\n    VERIFY(map.outerStride() == 2*map.innerSize()+1);\n    VERIFY(map.innerStride() == 2);\n    for(int i = 0; i < m.outerSize(); ++i)\n      for(int j = 0; j < m.innerSize(); ++j)\n      {\n        VERIFY(array[map.outerStride()*i+map.innerStride()*j] == m.coeffByOuterInner(i,j));\n        VERIFY(map.coeffByOuterInner(i,j) == m.coeffByOuterInner(i,j));\n      }\n    VERIFY_IS_APPROX(s1*map,s1*m);\n    map *= s1;\n    VERIFY_IS_APPROX(map,s1*m);\n  }\n\n  // test inner stride and no outer stride\n  for(int k=0; k<2; ++k)\n  {\n    if(k==1 && (m.innerSize()*2)*m.outerSize() > maxsize2)\n      break;\n    Scalar* array = (k==0 ? array1 : array2);\n\n    Map<MatrixType, Alignment, InnerStride<Dynamic> > map(array, rows, cols, InnerStride<Dynamic>(2));\n    map = m;\n    VERIFY(map.outerStride() == map.innerSize()*2);\n    for(int i = 0; i < m.outerSize(); ++i)\n      for(int j = 0; j < m.innerSize(); ++j)\n      {\n        VERIFY(array[map.innerSize()*i*2+j*2] == m.coeffByOuterInner(i,j));\n        VERIFY(map.coeffByOuterInner(i,j) == m.coeffByOuterInner(i,j));\n      }\n    VERIFY_IS_APPROX(s1*map,s1*m);\n    map *= s1;\n    VERIFY_IS_APPROX(map,s1*m);\n  }\n\n  // test negative strides\n  {\n    Matrix<Scalar,Dynamic,1>::Map(a_array1, arraysize+1).setRandom();\n    Index outerstride = m.innerSize()+4;\n    Scalar* array = array1;\n\n    {\n      Map<MatrixType, Alignment, OuterStride<> > map1(array, rows, cols, OuterStride<>( outerstride));\n      Map<MatrixType, Unaligned, OuterStride<> > map2(array+(m.outerSize()-1)*outerstride, rows, cols, OuterStride<>(-outerstride));\n      if(MatrixType::IsRowMajor)  VERIFY_IS_APPROX(map1.colwise().reverse(), map2);\n      else                        VERIFY_IS_APPROX(map1.rowwise().reverse(), map2);\n    }\n\n    {\n      Map<MatrixType, Alignment, OuterStride<> > map1(array, rows, cols, OuterStride<>( outerstride));\n      Map<MatrixType, Unaligned, Stride<Dynamic,Dynamic> > map2(array+(m.outerSize()-1)*outerstride+m.innerSize()-1, rows, cols, Stride<Dynamic,Dynamic>(-outerstride,-1));\n      VERIFY_IS_APPROX(map1.reverse(), map2);\n    }\n\n    {\n      Map<MatrixType, Alignment, OuterStride<> > map1(array, rows, cols, OuterStride<>( outerstride));\n      Map<MatrixType, Unaligned, Stride<Dynamic,-1> > map2(array+(m.outerSize()-1)*outerstride+m.innerSize()-1, rows, cols, Stride<Dynamic,-1>(-outerstride,-1));\n      VERIFY_IS_APPROX(map1.reverse(), map2);\n    }\n  }\n\n  internal::aligned_delete(a_array1, arraysize+1);\n}\n\n// Additional tests for inner-stride but no outer-stride\ntemplate<int>\nvoid bug1453()\n{\n  const int data[] = {0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 26, 27, 28, 29, 30, 31};\n  typedef Matrix<int,Dynamic,Dynamic,RowMajor> RowMatrixXi;\n  typedef Matrix<int,2,3,ColMajor> ColMatrix23i;\n  typedef Matrix<int,3,2,ColMajor> ColMatrix32i;\n  typedef Matrix<int,2,3,RowMajor> RowMatrix23i;\n  typedef Matrix<int,3,2,RowMajor> RowMatrix32i;\n\n  VERIFY_IS_APPROX(MatrixXi::Map(data, 2, 3, InnerStride<2>()), MatrixXi::Map(data, 2, 3, Stride<4,2>()));\n  VERIFY_IS_APPROX(MatrixXi::Map(data, 2, 3, InnerStride<>(2)), MatrixXi::Map(data, 2, 3, Stride<4,2>()));\n  VERIFY_IS_APPROX(MatrixXi::Map(data, 3, 2, InnerStride<2>()), MatrixXi::Map(data, 3, 2, Stride<6,2>()));\n  VERIFY_IS_APPROX(MatrixXi::Map(data, 3, 2, InnerStride<>(2)), MatrixXi::Map(data, 3, 2, Stride<6,2>()));\n\n  VERIFY_IS_APPROX(RowMatrixXi::Map(data, 2, 3, InnerStride<2>()), RowMatrixXi::Map(data, 2, 3, Stride<6,2>()));\n  VERIFY_IS_APPROX(RowMatrixXi::Map(data, 2, 3, InnerStride<>(2)), RowMatrixXi::Map(data, 2, 3, Stride<6,2>()));\n  VERIFY_IS_APPROX(RowMatrixXi::Map(data, 3, 2, InnerStride<2>()), RowMatrixXi::Map(data, 3, 2, Stride<4,2>()));\n  VERIFY_IS_APPROX(RowMatrixXi::Map(data, 3, 2, InnerStride<>(2)), RowMatrixXi::Map(data, 3, 2, Stride<4,2>()));\n\n  VERIFY_IS_APPROX(ColMatrix23i::Map(data, InnerStride<2>()), MatrixXi::Map(data, 2, 3, Stride<4,2>()));\n  VERIFY_IS_APPROX(ColMatrix23i::Map(data, InnerStride<>(2)), MatrixXi::Map(data, 2, 3, Stride<4,2>()));\n  VERIFY_IS_APPROX(ColMatrix32i::Map(data, InnerStride<2>()), MatrixXi::Map(data, 3, 2, Stride<6,2>()));\n  VERIFY_IS_APPROX(ColMatrix32i::Map(data, InnerStride<>(2)), MatrixXi::Map(data, 3, 2, Stride<6,2>()));\n\n  VERIFY_IS_APPROX(RowMatrix23i::Map(data, InnerStride<2>()), RowMatrixXi::Map(data, 2, 3, Stride<6,2>()));\n  VERIFY_IS_APPROX(RowMatrix23i::Map(data, InnerStride<>(2)), RowMatrixXi::Map(data, 2, 3, Stride<6,2>()));\n  VERIFY_IS_APPROX(RowMatrix32i::Map(data, InnerStride<2>()), RowMatrixXi::Map(data, 3, 2, Stride<4,2>()));\n  VERIFY_IS_APPROX(RowMatrix32i::Map(data, InnerStride<>(2)), RowMatrixXi::Map(data, 3, 2, Stride<4,2>()));\n}\n\nEIGEN_DECLARE_TEST(mapstride)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    int maxn = 3;\n    CALL_SUBTEST_1( map_class_vector<Aligned>(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_1( map_class_vector<Unaligned>(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( map_class_vector<Aligned>(Vector4d()) );\n    CALL_SUBTEST_2( map_class_vector<Unaligned>(Vector4d()) );\n    CALL_SUBTEST_3( map_class_vector<Aligned>(RowVector4f()) );\n    CALL_SUBTEST_3( map_class_vector<Unaligned>(RowVector4f()) );\n    CALL_SUBTEST_4( map_class_vector<Aligned>(VectorXcf(internal::random<int>(1,maxn))) );\n    CALL_SUBTEST_4( map_class_vector<Unaligned>(VectorXcf(internal::random<int>(1,maxn))) );\n    CALL_SUBTEST_5( map_class_vector<Aligned>(VectorXi(internal::random<int>(1,maxn))) );\n    CALL_SUBTEST_5( map_class_vector<Unaligned>(VectorXi(internal::random<int>(1,maxn))) );\n\n    CALL_SUBTEST_1( map_class_matrix<Aligned>(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_1( map_class_matrix<Unaligned>(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( map_class_matrix<Aligned>(Matrix4d()) );\n    CALL_SUBTEST_2( map_class_matrix<Unaligned>(Matrix4d()) );\n    CALL_SUBTEST_3( map_class_matrix<Aligned>(Matrix<float,3,5>()) );\n    CALL_SUBTEST_3( map_class_matrix<Unaligned>(Matrix<float,3,5>()) );\n    CALL_SUBTEST_3( map_class_matrix<Aligned>(Matrix<float,4,8>()) );\n    CALL_SUBTEST_3( map_class_matrix<Unaligned>(Matrix<float,4,8>()) );\n    CALL_SUBTEST_4( map_class_matrix<Aligned>(MatrixXcf(internal::random<int>(1,maxn),internal::random<int>(1,maxn))) );\n    CALL_SUBTEST_4( map_class_matrix<Unaligned>(MatrixXcf(internal::random<int>(1,maxn),internal::random<int>(1,maxn))) );\n    CALL_SUBTEST_5( map_class_matrix<Aligned>(MatrixXi(internal::random<int>(1,maxn),internal::random<int>(1,maxn))) );\n    CALL_SUBTEST_5( map_class_matrix<Unaligned>(MatrixXi(internal::random<int>(1,maxn),internal::random<int>(1,maxn))) );\n    CALL_SUBTEST_6( map_class_matrix<Aligned>(MatrixXcd(internal::random<int>(1,maxn),internal::random<int>(1,maxn))) );\n    CALL_SUBTEST_6( map_class_matrix<Unaligned>(MatrixXcd(internal::random<int>(1,maxn),internal::random<int>(1,maxn))) );\n\n    CALL_SUBTEST_5( bug1453<0>() );\n    \n    TEST_SET_BUT_UNUSED_VARIABLE(maxn);\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/meta.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename From, typename To>\nbool check_is_convertible(const From&, const To&)\n{\n  return internal::is_convertible<From,To>::value;\n}\n\nstruct FooReturnType {\n  typedef int ReturnType;\n};\n\nstruct MyInterface {\n  virtual void func() = 0;\n  virtual ~MyInterface() {}\n};\nstruct MyImpl : public MyInterface {\n  void func() {}\n};\n\nEIGEN_DECLARE_TEST(meta)\n{\n  VERIFY((internal::conditional<(3<4),internal::true_type, internal::false_type>::type::value));\n  VERIFY(( internal::is_same<float,float>::value));\n  VERIFY((!internal::is_same<float,double>::value));\n  VERIFY((!internal::is_same<float,float&>::value));\n  VERIFY((!internal::is_same<float,const float&>::value));\n\n  VERIFY(( internal::is_same<float,internal::remove_all<const float&>::type >::value));\n  VERIFY(( internal::is_same<float,internal::remove_all<const float*>::type >::value));\n  VERIFY(( internal::is_same<float,internal::remove_all<const float*&>::type >::value));\n  VERIFY(( internal::is_same<float,internal::remove_all<float**>::type >::value));\n  VERIFY(( internal::is_same<float,internal::remove_all<float**&>::type >::value));\n  VERIFY(( internal::is_same<float,internal::remove_all<float* const *&>::type >::value));\n  VERIFY(( internal::is_same<float,internal::remove_all<float* const>::type >::value));\n\n  // test add_const\n  VERIFY(( internal::is_same< internal::add_const<float>::type, const float >::value));\n  VERIFY(( internal::is_same< internal::add_const<float*>::type, float* const>::value));\n  VERIFY(( internal::is_same< internal::add_const<float const*>::type, float const* const>::value));\n  VERIFY(( internal::is_same< internal::add_const<float&>::type, float& >::value));\n\n  // test remove_const\n  VERIFY(( internal::is_same< internal::remove_const<float const* const>::type, float const* >::value));\n  VERIFY(( internal::is_same< internal::remove_const<float const*>::type, float const* >::value));\n  VERIFY(( internal::is_same< internal::remove_const<float* const>::type, float* >::value));\n\n  // test add_const_on_value_type\n  VERIFY(( internal::is_same< internal::add_const_on_value_type<float&>::type, float const& >::value));\n  VERIFY(( internal::is_same< internal::add_const_on_value_type<float*>::type, float const* >::value));\n\n  VERIFY(( internal::is_same< internal::add_const_on_value_type<float>::type, const float >::value));\n  VERIFY(( internal::is_same< internal::add_const_on_value_type<const float>::type, const float >::value));\n\n  VERIFY(( internal::is_same< internal::add_const_on_value_type<const float* const>::type, const float* const>::value));\n  VERIFY(( internal::is_same< internal::add_const_on_value_type<float* const>::type, const float* const>::value));\n\n  VERIFY(( internal::is_same<float,internal::remove_reference<float&>::type >::value));\n  VERIFY(( internal::is_same<const float,internal::remove_reference<const float&>::type >::value));\n  VERIFY(( internal::is_same<float,internal::remove_pointer<float*>::type >::value));\n  VERIFY(( internal::is_same<const float,internal::remove_pointer<const float*>::type >::value));\n  VERIFY(( internal::is_same<float,internal::remove_pointer<float* const >::type >::value));\n\n\n  // is_convertible\n  STATIC_CHECK(( internal::is_convertible<float,double>::value ));\n  STATIC_CHECK(( internal::is_convertible<int,double>::value ));\n  STATIC_CHECK(( internal::is_convertible<int, short>::value ));\n  STATIC_CHECK(( internal::is_convertible<short, int>::value ));\n  STATIC_CHECK(( internal::is_convertible<double,int>::value ));\n  STATIC_CHECK(( internal::is_convertible<double,std::complex<double> >::value ));\n  STATIC_CHECK((!internal::is_convertible<std::complex<double>,double>::value ));\n  STATIC_CHECK(( internal::is_convertible<Array33f,Matrix3f>::value ));\n  STATIC_CHECK(( internal::is_convertible<Matrix3f&,Matrix3f>::value ));\n  STATIC_CHECK(( internal::is_convertible<Matrix3f&,Matrix3f&>::value ));\n  STATIC_CHECK(( internal::is_convertible<Matrix3f&,const Matrix3f&>::value ));\n  STATIC_CHECK(( internal::is_convertible<const Matrix3f&,Matrix3f>::value ));\n  STATIC_CHECK(( internal::is_convertible<const Matrix3f&,const Matrix3f&>::value ));\n  STATIC_CHECK((!internal::is_convertible<const Matrix3f&,Matrix3f&>::value ));\n  STATIC_CHECK((!internal::is_convertible<const Matrix3f,Matrix3f&>::value ));\n  STATIC_CHECK(!( internal::is_convertible<Matrix3f,Matrix3f&>::value ));\n\n  STATIC_CHECK(!( internal::is_convertible<int,int&>::value ));\n  STATIC_CHECK(( internal::is_convertible<const int,const int& >::value ));\n\n  //STATIC_CHECK((!internal::is_convertible<Matrix3f,Matrix3d>::value )); //does not even compile because the conversion is prevented by a static assertion\n  STATIC_CHECK((!internal::is_convertible<Array33f,int>::value ));\n  STATIC_CHECK((!internal::is_convertible<MatrixXf,float>::value ));\n  {\n    float f = 0.0f;\n    MatrixXf A, B;\n    VectorXf a, b;\n    VERIFY(( check_is_convertible(a.dot(b), f) ));\n    VERIFY(( check_is_convertible(a.transpose()*b, f) ));\n    VERIFY((!check_is_convertible(A*B, f) ));\n    VERIFY(( check_is_convertible(A*B, A) ));\n  }\n\n  #if (EIGEN_COMP_GNUC  && EIGEN_COMP_GNUC  <=  99) \\\n   || (EIGEN_COMP_CLANG && EIGEN_COMP_CLANG <= 909) \\\n   || (EIGEN_COMP_MSVC  && EIGEN_COMP_MSVC  <=1914)\n  // See http://eigen.tuxfamily.org/bz/show_bug.cgi?id=1752,\n  // basically, a fix in the c++ standard breaks our c++98 implementation\n  // of is_convertible for abstract classes.\n  // So the following tests are expected to fail with recent compilers.\n\n  STATIC_CHECK(( !internal::is_convertible<MyInterface, MyImpl>::value ));\n  #if (!EIGEN_COMP_GNUC_STRICT) || (EIGEN_GNUC_AT_LEAST(4,8))\n  // GCC prior to 4.8 fails to compile this test:\n  // error: cannot allocate an object of abstract type 'MyInterface'\n  // In other word, it does not obey SFINAE.\n  // Nevertheless, we don't really care about supporting abstract type as scalar type!\n  STATIC_CHECK(( !internal::is_convertible<MyImpl, MyInterface>::value ));\n  #endif\n  STATIC_CHECK((  internal::is_convertible<MyImpl, const MyInterface&>::value ));\n\n  #endif\n\n  {\n    int i = 0;\n    VERIFY(( check_is_convertible(fix<3>(), i) ));\n    VERIFY((!check_is_convertible(i, fix<DynamicIndex>()) ));\n  }\n\n\n  VERIFY((  internal::has_ReturnType<FooReturnType>::value ));\n  VERIFY((  internal::has_ReturnType<ScalarBinaryOpTraits<int,int> >::value ));\n  VERIFY(( !internal::has_ReturnType<MatrixXf>::value ));\n  VERIFY(( !internal::has_ReturnType<int>::value ));\n\n  VERIFY(internal::meta_sqrt<1>::ret == 1);\n  #define VERIFY_META_SQRT(X) VERIFY(internal::meta_sqrt<X>::ret == int(std::sqrt(double(X))))\n  VERIFY_META_SQRT(2);\n  VERIFY_META_SQRT(3);\n  VERIFY_META_SQRT(4);\n  VERIFY_META_SQRT(5);\n  VERIFY_META_SQRT(6);\n  VERIFY_META_SQRT(8);\n  VERIFY_META_SQRT(9);\n  VERIFY_META_SQRT(15);\n  VERIFY_META_SQRT(16);\n  VERIFY_META_SQRT(17);\n  VERIFY_META_SQRT(255);\n  VERIFY_META_SQRT(256);\n  VERIFY_META_SQRT(257);\n  VERIFY_META_SQRT(1023);\n  VERIFY_META_SQRT(1024);\n  VERIFY_META_SQRT(1025);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/metis_support.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"sparse_solver.h\"\n#include <Eigen/SparseLU>\n#include <Eigen/MetisSupport>\n#include <unsupported/Eigen/SparseExtra>\n\ntemplate<typename T> void test_metis_T()\n{\n  SparseLU<SparseMatrix<T, ColMajor>, MetisOrdering<int> > sparselu_metis;\n  \n  check_sparse_square_solving(sparselu_metis); \n}\n\nEIGEN_DECLARE_TEST(metis_support)\n{\n  CALL_SUBTEST_1(test_metis_T<double>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/miscmatrices.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void miscMatrices(const MatrixType& m)\n{\n  /* this test covers the following files:\n     DiagonalMatrix.h Ones.h\n  */\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  Index r = internal::random<Index>(0, rows-1), r2 = internal::random<Index>(0, rows-1), c = internal::random<Index>(0, cols-1);\n  VERIFY_IS_APPROX(MatrixType::Ones(rows,cols)(r,c), static_cast<Scalar>(1));\n  MatrixType m1 = MatrixType::Ones(rows,cols);\n  VERIFY_IS_APPROX(m1(r,c), static_cast<Scalar>(1));\n  VectorType v1 = VectorType::Random(rows);\n  v1[0];\n  Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime>\n  square(v1.asDiagonal());\n  if(r==r2) VERIFY_IS_APPROX(square(r,r2), v1[r]);\n  else VERIFY_IS_MUCH_SMALLER_THAN(square(r,r2), static_cast<Scalar>(1));\n  square = MatrixType::Zero(rows, rows);\n  square.diagonal() = VectorType::Ones(rows);\n  VERIFY_IS_APPROX(square, MatrixType::Identity(rows, rows));\n}\n\nEIGEN_DECLARE_TEST(miscmatrices)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( miscMatrices(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( miscMatrices(Matrix4d()) );\n    CALL_SUBTEST_3( miscMatrices(MatrixXcf(3, 3)) );\n    CALL_SUBTEST_4( miscMatrices(MatrixXi(8, 12)) );\n    CALL_SUBTEST_5( miscMatrices(MatrixXcd(20, 20)) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/mixingtypes.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#if defined(EIGEN_TEST_PART_7)\n\n#ifndef EIGEN_NO_STATIC_ASSERT\n#define EIGEN_NO_STATIC_ASSERT // turn static asserts into runtime asserts in order to check them\n#endif\n\n// ignore double-promotion diagnostic for clang and gcc, if we check for static assertion anyway:\n// TODO do the same for MSVC?\n#if defined(__clang__)\n#  if (__clang_major__ * 100 + __clang_minor__) >= 308\n#    pragma clang diagnostic ignored \"-Wdouble-promotion\"\n#  endif\n#elif defined(__GNUC__)\n  // TODO is there a minimal GCC version for this? At least g++-4.7 seems to be fine with this.\n#  pragma GCC diagnostic ignored \"-Wdouble-promotion\"\n#endif\n\n#endif\n\n\n\n#if defined(EIGEN_TEST_PART_1) || defined(EIGEN_TEST_PART_2) || defined(EIGEN_TEST_PART_3)\n\n#ifndef EIGEN_DONT_VECTORIZE\n#define EIGEN_DONT_VECTORIZE\n#endif\n\n#endif\n\nstatic bool g_called;\n#define EIGEN_SCALAR_BINARY_OP_PLUGIN { g_called |= (!internal::is_same<LhsScalar,RhsScalar>::value); }\n\n#include \"main.h\"\n\nusing namespace std;\n\n#define VERIFY_MIX_SCALAR(XPR,REF) \\\n  g_called = false; \\\n  VERIFY_IS_APPROX(XPR,REF); \\\n  VERIFY( g_called && #XPR\" not properly optimized\");\n\ntemplate<int SizeAtCompileType>\nvoid raise_assertion(Index size = SizeAtCompileType)\n{\n  // VERIFY_RAISES_ASSERT(mf+md); // does not even compile\n  Matrix<float, SizeAtCompileType, 1> vf; vf.setRandom(size);\n  Matrix<double, SizeAtCompileType, 1> vd; vd.setRandom(size);\n  VERIFY_RAISES_ASSERT(vf=vd);\n  VERIFY_RAISES_ASSERT(vf+=vd);\n  VERIFY_RAISES_ASSERT(vf-=vd);\n  VERIFY_RAISES_ASSERT(vd=vf);\n  VERIFY_RAISES_ASSERT(vd+=vf);\n  VERIFY_RAISES_ASSERT(vd-=vf);\n\n  //   vd.asDiagonal() * mf;    // does not even compile\n  //   vcd.asDiagonal() * mf;   // does not even compile\n\n#if 0 // we get other compilation errors here than just static asserts\n  VERIFY_RAISES_ASSERT(vd.dot(vf));\n#endif\n}\n\n\ntemplate<int SizeAtCompileType> void mixingtypes(int size = SizeAtCompileType)\n{\n  typedef std::complex<float>   CF;\n  typedef std::complex<double>  CD;\n  typedef Matrix<float, SizeAtCompileType, SizeAtCompileType> Mat_f;\n  typedef Matrix<double, SizeAtCompileType, SizeAtCompileType> Mat_d;\n  typedef Matrix<std::complex<float>, SizeAtCompileType, SizeAtCompileType> Mat_cf;\n  typedef Matrix<std::complex<double>, SizeAtCompileType, SizeAtCompileType> Mat_cd;\n  typedef Matrix<float, SizeAtCompileType, 1> Vec_f;\n  typedef Matrix<double, SizeAtCompileType, 1> Vec_d;\n  typedef Matrix<std::complex<float>, SizeAtCompileType, 1> Vec_cf;\n  typedef Matrix<std::complex<double>, SizeAtCompileType, 1> Vec_cd;\n\n  Mat_f mf    = Mat_f::Random(size,size);\n  Mat_d md    = mf.template cast<double>();\n  //Mat_d rd    = md;\n  Mat_cf mcf  = Mat_cf::Random(size,size);\n  Mat_cd mcd  = mcf.template cast<complex<double> >();\n  Mat_cd rcd = mcd;\n  Vec_f vf    = Vec_f::Random(size,1);\n  Vec_d vd    = vf.template cast<double>();\n  Vec_cf vcf  = Vec_cf::Random(size,1);\n  Vec_cd vcd  = vcf.template cast<complex<double> >();\n  float           sf  = internal::random<float>();\n  double          sd  = internal::random<double>();\n  complex<float>  scf = internal::random<complex<float> >();\n  complex<double> scd = internal::random<complex<double> >();\n\n  mf+mf;\n\n  float  epsf = std::sqrt(std::numeric_limits<float> ::min EIGEN_EMPTY ());\n  double epsd = std::sqrt(std::numeric_limits<double>::min EIGEN_EMPTY ());\n\n  while(std::abs(sf )<epsf) sf  = internal::random<float>();\n  while(std::abs(sd )<epsd) sd  = internal::random<double>();\n  while(std::abs(scf)<epsf) scf = internal::random<CF>();\n  while(std::abs(scd)<epsd) scd = internal::random<CD>();\n\n  // check scalar products\n  VERIFY_MIX_SCALAR(vcf * sf , vcf * complex<float>(sf));\n  VERIFY_MIX_SCALAR(sd * vcd , complex<double>(sd) * vcd);\n  VERIFY_MIX_SCALAR(vf * scf , vf.template cast<complex<float> >() * scf);\n  VERIFY_MIX_SCALAR(scd * vd , scd * vd.template cast<complex<double> >());\n\n  VERIFY_MIX_SCALAR(vcf * 2 , vcf * complex<float>(2));\n  VERIFY_MIX_SCALAR(vcf * 2.1 , vcf * complex<float>(2.1));\n  VERIFY_MIX_SCALAR(2 * vcf, vcf * complex<float>(2));\n  VERIFY_MIX_SCALAR(2.1 * vcf , vcf * complex<float>(2.1));\n\n  // check scalar quotients\n  VERIFY_MIX_SCALAR(vcf / sf , vcf / complex<float>(sf));\n  VERIFY_MIX_SCALAR(vf / scf , vf.template cast<complex<float> >() / scf);\n  VERIFY_MIX_SCALAR(vf.array()  / scf, vf.template cast<complex<float> >().array() / scf);\n  VERIFY_MIX_SCALAR(scd / vd.array() , scd / vd.template cast<complex<double> >().array());\n\n  // check scalar increment\n  VERIFY_MIX_SCALAR(vcf.array() + sf , vcf.array() + complex<float>(sf));\n  VERIFY_MIX_SCALAR(sd  + vcd.array(), complex<double>(sd) + vcd.array());\n  VERIFY_MIX_SCALAR(vf.array()  + scf, vf.template cast<complex<float> >().array() + scf);\n  VERIFY_MIX_SCALAR(scd + vd.array() , scd + vd.template cast<complex<double> >().array());\n\n  // check scalar subtractions\n  VERIFY_MIX_SCALAR(vcf.array() - sf , vcf.array() - complex<float>(sf));\n  VERIFY_MIX_SCALAR(sd  - vcd.array(), complex<double>(sd) - vcd.array());\n  VERIFY_MIX_SCALAR(vf.array()  - scf, vf.template cast<complex<float> >().array() - scf);\n  VERIFY_MIX_SCALAR(scd - vd.array() , scd - vd.template cast<complex<double> >().array());\n\n  // check scalar powers\n  VERIFY_MIX_SCALAR( pow(vcf.array(), sf),        Eigen::pow(vcf.array(), complex<float>(sf)) );\n  VERIFY_MIX_SCALAR( vcf.array().pow(sf) ,        Eigen::pow(vcf.array(), complex<float>(sf)) );\n  VERIFY_MIX_SCALAR( pow(sd, vcd.array()),        Eigen::pow(complex<double>(sd), vcd.array()) );\n  VERIFY_MIX_SCALAR( Eigen::pow(vf.array(), scf), Eigen::pow(vf.template cast<complex<float> >().array(), scf) );\n  VERIFY_MIX_SCALAR( vf.array().pow(scf) ,        Eigen::pow(vf.template cast<complex<float> >().array(), scf) );\n  VERIFY_MIX_SCALAR( Eigen::pow(scd, vd.array()), Eigen::pow(scd, vd.template cast<complex<double> >().array()) );\n\n  // check dot product\n  vf.dot(vf);\n  VERIFY_IS_APPROX(vcf.dot(vf), vcf.dot(vf.template cast<complex<float> >()));\n\n  // check diagonal product\n  VERIFY_IS_APPROX(vf.asDiagonal() * mcf, vf.template cast<complex<float> >().asDiagonal() * mcf);\n  VERIFY_IS_APPROX(vcd.asDiagonal() * md, vcd.asDiagonal() * md.template cast<complex<double> >());\n  VERIFY_IS_APPROX(mcf * vf.asDiagonal(), mcf * vf.template cast<complex<float> >().asDiagonal());\n  VERIFY_IS_APPROX(md * vcd.asDiagonal(), md.template cast<complex<double> >() * vcd.asDiagonal());\n\n  // check inner product\n  VERIFY_IS_APPROX((vf.transpose() * vcf).value(), (vf.template cast<complex<float> >().transpose() * vcf).value());\n\n  // check outer product\n  VERIFY_IS_APPROX((vf * vcf.transpose()).eval(), (vf.template cast<complex<float> >() * vcf.transpose()).eval());\n\n  // coeff wise product\n\n  VERIFY_IS_APPROX((vf * vcf.transpose()).eval(), (vf.template cast<complex<float> >() * vcf.transpose()).eval());\n\n  Mat_cd mcd2 = mcd;\n  VERIFY_IS_APPROX(mcd.array() *= md.array(), mcd2.array() *= md.array().template cast<std::complex<double> >());\n  \n  // check matrix-matrix products\n  VERIFY_IS_APPROX(sd*md*mcd, (sd*md).template cast<CD>().eval()*mcd);\n  VERIFY_IS_APPROX(sd*mcd*md, sd*mcd*md.template cast<CD>());\n  VERIFY_IS_APPROX(scd*md*mcd, scd*md.template cast<CD>().eval()*mcd);\n  VERIFY_IS_APPROX(scd*mcd*md, scd*mcd*md.template cast<CD>());\n\n  VERIFY_IS_APPROX(sf*mf*mcf, sf*mf.template cast<CF>()*mcf);\n  VERIFY_IS_APPROX(sf*mcf*mf, sf*mcf*mf.template cast<CF>());\n  VERIFY_IS_APPROX(scf*mf*mcf, scf*mf.template cast<CF>()*mcf);\n  VERIFY_IS_APPROX(scf*mcf*mf, scf*mcf*mf.template cast<CF>());\n\n  VERIFY_IS_APPROX(sd*md.adjoint()*mcd, (sd*md).template cast<CD>().eval().adjoint()*mcd);\n  VERIFY_IS_APPROX(sd*mcd.adjoint()*md, sd*mcd.adjoint()*md.template cast<CD>());\n  VERIFY_IS_APPROX(sd*md.adjoint()*mcd.adjoint(), (sd*md).template cast<CD>().eval().adjoint()*mcd.adjoint());\n  VERIFY_IS_APPROX(sd*mcd.adjoint()*md.adjoint(), sd*mcd.adjoint()*md.template cast<CD>().adjoint());\n  VERIFY_IS_APPROX(sd*md*mcd.adjoint(), (sd*md).template cast<CD>().eval()*mcd.adjoint());\n  VERIFY_IS_APPROX(sd*mcd*md.adjoint(), sd*mcd*md.template cast<CD>().adjoint());\n\n  VERIFY_IS_APPROX(sf*mf.adjoint()*mcf, (sf*mf).template cast<CF>().eval().adjoint()*mcf);\n  VERIFY_IS_APPROX(sf*mcf.adjoint()*mf, sf*mcf.adjoint()*mf.template cast<CF>());\n  VERIFY_IS_APPROX(sf*mf.adjoint()*mcf.adjoint(), (sf*mf).template cast<CF>().eval().adjoint()*mcf.adjoint());\n  VERIFY_IS_APPROX(sf*mcf.adjoint()*mf.adjoint(), sf*mcf.adjoint()*mf.template cast<CF>().adjoint());\n  VERIFY_IS_APPROX(sf*mf*mcf.adjoint(), (sf*mf).template cast<CF>().eval()*mcf.adjoint());\n  VERIFY_IS_APPROX(sf*mcf*mf.adjoint(), sf*mcf*mf.template cast<CF>().adjoint());\n\n  VERIFY_IS_APPROX(sf*mf*vcf, (sf*mf).template cast<CF>().eval()*vcf);\n  VERIFY_IS_APPROX(scf*mf*vcf,(scf*mf.template cast<CF>()).eval()*vcf);\n  VERIFY_IS_APPROX(sf*mcf*vf, sf*mcf*vf.template cast<CF>());\n  VERIFY_IS_APPROX(scf*mcf*vf,scf*mcf*vf.template cast<CF>());\n\n  VERIFY_IS_APPROX(sf*vcf.adjoint()*mf,  sf*vcf.adjoint()*mf.template cast<CF>().eval());\n  VERIFY_IS_APPROX(scf*vcf.adjoint()*mf, scf*vcf.adjoint()*mf.template cast<CF>().eval());\n  VERIFY_IS_APPROX(sf*vf.adjoint()*mcf,  sf*vf.adjoint().template cast<CF>().eval()*mcf);\n  VERIFY_IS_APPROX(scf*vf.adjoint()*mcf, scf*vf.adjoint().template cast<CF>().eval()*mcf);\n\n  VERIFY_IS_APPROX(sd*md*vcd, (sd*md).template cast<CD>().eval()*vcd);\n  VERIFY_IS_APPROX(scd*md*vcd,(scd*md.template cast<CD>()).eval()*vcd);\n  VERIFY_IS_APPROX(sd*mcd*vd, sd*mcd*vd.template cast<CD>().eval());\n  VERIFY_IS_APPROX(scd*mcd*vd,scd*mcd*vd.template cast<CD>().eval());\n\n  VERIFY_IS_APPROX(sd*vcd.adjoint()*md,  sd*vcd.adjoint()*md.template cast<CD>().eval());\n  VERIFY_IS_APPROX(scd*vcd.adjoint()*md, scd*vcd.adjoint()*md.template cast<CD>().eval());\n  VERIFY_IS_APPROX(sd*vd.adjoint()*mcd,  sd*vd.adjoint().template cast<CD>().eval()*mcd);\n  VERIFY_IS_APPROX(scd*vd.adjoint()*mcd, scd*vd.adjoint().template cast<CD>().eval()*mcd);\n\n  VERIFY_IS_APPROX( sd*vcd.adjoint()*md.template triangularView<Upper>(),  sd*vcd.adjoint()*md.template cast<CD>().eval().template triangularView<Upper>());\n  VERIFY_IS_APPROX(scd*vcd.adjoint()*md.template triangularView<Lower>(), scd*vcd.adjoint()*md.template cast<CD>().eval().template triangularView<Lower>());\n  VERIFY_IS_APPROX( sd*vcd.adjoint()*md.transpose().template triangularView<Upper>(),  sd*vcd.adjoint()*md.transpose().template cast<CD>().eval().template triangularView<Upper>());\n  VERIFY_IS_APPROX(scd*vcd.adjoint()*md.transpose().template triangularView<Lower>(), scd*vcd.adjoint()*md.transpose().template cast<CD>().eval().template triangularView<Lower>());\n  VERIFY_IS_APPROX( sd*vd.adjoint()*mcd.template triangularView<Lower>(),  sd*vd.adjoint().template cast<CD>().eval()*mcd.template triangularView<Lower>());\n  VERIFY_IS_APPROX(scd*vd.adjoint()*mcd.template triangularView<Upper>(), scd*vd.adjoint().template cast<CD>().eval()*mcd.template triangularView<Upper>());\n  VERIFY_IS_APPROX( sd*vd.adjoint()*mcd.transpose().template triangularView<Lower>(),  sd*vd.adjoint().template cast<CD>().eval()*mcd.transpose().template triangularView<Lower>());\n  VERIFY_IS_APPROX(scd*vd.adjoint()*mcd.transpose().template triangularView<Upper>(), scd*vd.adjoint().template cast<CD>().eval()*mcd.transpose().template triangularView<Upper>());\n\n  // Not supported yet: trmm\n//   VERIFY_IS_APPROX(sd*mcd*md.template triangularView<Lower>(),  sd*mcd*md.template cast<CD>().eval().template triangularView<Lower>());\n//   VERIFY_IS_APPROX(scd*mcd*md.template triangularView<Upper>(), scd*mcd*md.template cast<CD>().eval().template triangularView<Upper>());\n//   VERIFY_IS_APPROX(sd*md*mcd.template triangularView<Lower>(),  sd*md.template cast<CD>().eval()*mcd.template triangularView<Lower>());\n//   VERIFY_IS_APPROX(scd*md*mcd.template triangularView<Upper>(), scd*md.template cast<CD>().eval()*mcd.template triangularView<Upper>());\n\n  // Not supported yet: symv\n//   VERIFY_IS_APPROX(sd*vcd.adjoint()*md.template selfadjointView<Upper>(),  sd*vcd.adjoint()*md.template cast<CD>().eval().template selfadjointView<Upper>());\n//   VERIFY_IS_APPROX(scd*vcd.adjoint()*md.template selfadjointView<Lower>(), scd*vcd.adjoint()*md.template cast<CD>().eval().template selfadjointView<Lower>());\n//   VERIFY_IS_APPROX(sd*vd.adjoint()*mcd.template selfadjointView<Lower>(),  sd*vd.adjoint().template cast<CD>().eval()*mcd.template selfadjointView<Lower>());\n//   VERIFY_IS_APPROX(scd*vd.adjoint()*mcd.template selfadjointView<Upper>(), scd*vd.adjoint().template cast<CD>().eval()*mcd.template selfadjointView<Upper>());\n\n  // Not supported yet: symm\n//   VERIFY_IS_APPROX(sd*vcd.adjoint()*md.template selfadjointView<Upper>(),  sd*vcd.adjoint()*md.template cast<CD>().eval().template selfadjointView<Upper>());\n//   VERIFY_IS_APPROX(scd*vcd.adjoint()*md.template selfadjointView<Upper>(), scd*vcd.adjoint()*md.template cast<CD>().eval().template selfadjointView<Upper>());\n//   VERIFY_IS_APPROX(sd*vd.adjoint()*mcd.template selfadjointView<Upper>(),  sd*vd.adjoint().template cast<CD>().eval()*mcd.template selfadjointView<Upper>());\n//   VERIFY_IS_APPROX(scd*vd.adjoint()*mcd.template selfadjointView<Upper>(), scd*vd.adjoint().template cast<CD>().eval()*mcd.template selfadjointView<Upper>());\n\n  rcd.setZero();\n  VERIFY_IS_APPROX(Mat_cd(rcd.template triangularView<Upper>() = sd * mcd * md),\n                   Mat_cd((sd * mcd * md.template cast<CD>().eval()).template triangularView<Upper>()));\n  VERIFY_IS_APPROX(Mat_cd(rcd.template triangularView<Upper>() = sd * md * mcd),\n                   Mat_cd((sd * md.template cast<CD>().eval() * mcd).template triangularView<Upper>()));\n  VERIFY_IS_APPROX(Mat_cd(rcd.template triangularView<Upper>() = scd * mcd * md),\n                   Mat_cd((scd * mcd * md.template cast<CD>().eval()).template triangularView<Upper>()));\n  VERIFY_IS_APPROX(Mat_cd(rcd.template triangularView<Upper>() = scd * md * mcd),\n                   Mat_cd((scd * md.template cast<CD>().eval() * mcd).template triangularView<Upper>()));\n\n\n  VERIFY_IS_APPROX( md.array()  * mcd.array(), md.template cast<CD>().eval().array() * mcd.array() );\n  VERIFY_IS_APPROX( mcd.array() * md.array(),  mcd.array() * md.template cast<CD>().eval().array() );\n\n  VERIFY_IS_APPROX( md.array()  + mcd.array(), md.template cast<CD>().eval().array() + mcd.array() );\n  VERIFY_IS_APPROX( mcd.array() + md.array(),  mcd.array() + md.template cast<CD>().eval().array() );\n\n  VERIFY_IS_APPROX( md.array()  - mcd.array(), md.template cast<CD>().eval().array() - mcd.array() );\n  VERIFY_IS_APPROX( mcd.array() - md.array(),  mcd.array() - md.template cast<CD>().eval().array() );\n\n  if(mcd.array().abs().minCoeff()>epsd)\n  {\n    VERIFY_IS_APPROX( md.array() / mcd.array(), md.template cast<CD>().eval().array() / mcd.array() );\n  }\n  if(md.array().abs().minCoeff()>epsd)\n  {\n    VERIFY_IS_APPROX( mcd.array() / md.array(), mcd.array() / md.template cast<CD>().eval().array() );\n  }\n\n  if(md.array().abs().minCoeff()>epsd || mcd.array().abs().minCoeff()>epsd)\n  {\n    VERIFY_IS_APPROX( md.array().pow(mcd.array()), md.template cast<CD>().eval().array().pow(mcd.array()) );\n    VERIFY_IS_APPROX( mcd.array().pow(md.array()),  mcd.array().pow(md.template cast<CD>().eval().array()) );\n\n    VERIFY_IS_APPROX( pow(md.array(),mcd.array()), md.template cast<CD>().eval().array().pow(mcd.array()) );\n    VERIFY_IS_APPROX( pow(mcd.array(),md.array()),  mcd.array().pow(md.template cast<CD>().eval().array()) );\n  }\n\n  rcd = mcd;\n  VERIFY_IS_APPROX( rcd = md, md.template cast<CD>().eval() );\n  rcd = mcd;\n  VERIFY_IS_APPROX( rcd += md, mcd + md.template cast<CD>().eval() );\n  rcd = mcd;\n  VERIFY_IS_APPROX( rcd -= md, mcd - md.template cast<CD>().eval() );\n  rcd = mcd;\n  VERIFY_IS_APPROX( rcd.array() *= md.array(), mcd.array() * md.template cast<CD>().eval().array() );\n  rcd = mcd;\n  if(md.array().abs().minCoeff()>epsd)\n  {\n    VERIFY_IS_APPROX( rcd.array() /= md.array(), mcd.array() / md.template cast<CD>().eval().array() );\n  }\n\n  rcd = mcd;\n  VERIFY_IS_APPROX( rcd.noalias() += md + mcd*md, mcd + (md.template cast<CD>().eval()) + mcd*(md.template cast<CD>().eval()));\n\n  VERIFY_IS_APPROX( rcd.noalias()  = md*md,       ((md*md).eval().template cast<CD>()) );\n  rcd = mcd;\n  VERIFY_IS_APPROX( rcd.noalias() += md*md, mcd + ((md*md).eval().template cast<CD>()) );\n  rcd = mcd;\n  VERIFY_IS_APPROX( rcd.noalias() -= md*md, mcd - ((md*md).eval().template cast<CD>()) );\n\n  VERIFY_IS_APPROX( rcd.noalias()  = mcd + md*md,       mcd + ((md*md).eval().template cast<CD>()) );\n  rcd = mcd;\n  VERIFY_IS_APPROX( rcd.noalias() += mcd + md*md, mcd + mcd + ((md*md).eval().template cast<CD>()) );\n  rcd = mcd;\n  VERIFY_IS_APPROX( rcd.noalias() -= mcd + md*md,           - ((md*md).eval().template cast<CD>()) );\n}\n\nEIGEN_DECLARE_TEST(mixingtypes)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(mixingtypes<3>());\n    CALL_SUBTEST_2(mixingtypes<4>());\n    CALL_SUBTEST_3(mixingtypes<Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)));\n\n    CALL_SUBTEST_4(mixingtypes<3>());\n    CALL_SUBTEST_5(mixingtypes<4>());\n    CALL_SUBTEST_6(mixingtypes<Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)));\n    CALL_SUBTEST_7(raise_assertion<Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)));\n  }\n  CALL_SUBTEST_7(raise_assertion<0>());\n  CALL_SUBTEST_7(raise_assertion<3>());\n  CALL_SUBTEST_7(raise_assertion<4>());\n  CALL_SUBTEST_7(raise_assertion<Dynamic>(0));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/mpl2only.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MPL2_ONLY\n#define EIGEN_MPL2_ONLY\n#endif\n#include <Eigen/Dense>\n#include <Eigen/SparseCore>\n#include <Eigen/SparseLU>\n#include <Eigen/SparseQR>\n#include <Eigen/Sparse>\n#include <Eigen/IterativeLinearSolvers>\n#include <Eigen/Eigen>\n\nint main()\n{\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/nestbyvalue.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2019 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define TEST_ENABLE_TEMPORARY_TRACKING\n\n#include \"main.h\"\n\ntypedef NestByValue<MatrixXd> CpyMatrixXd;\ntypedef CwiseBinaryOp<internal::scalar_sum_op<double,double>,const CpyMatrixXd,const CpyMatrixXd> XprType;\n\nXprType get_xpr_with_temps(const MatrixXd& a)\n{\n  MatrixXd t1 = a.rowwise().reverse();\n  MatrixXd t2 = a+a;\n  return t1.nestByValue() + t2.nestByValue();\n}\n\nEIGEN_DECLARE_TEST(nestbyvalue)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    Index rows = internal::random<Index>(1,EIGEN_TEST_MAX_SIZE);\n    Index cols = internal::random<Index>(1,EIGEN_TEST_MAX_SIZE);\n    MatrixXd a = MatrixXd(rows,cols);\n    nb_temporaries = 0;\n    XprType x = get_xpr_with_temps(a);\n    VERIFY_IS_EQUAL(nb_temporaries,6);\n    MatrixXd b = x;\n    VERIFY_IS_EQUAL(nb_temporaries,6+1);\n    VERIFY_IS_APPROX(b, a.rowwise().reverse().eval() + (a+a).eval());\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/nesting_ops.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Hauke Heibel <hauke.heibel@gmail.com>\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define TEST_ENABLE_TEMPORARY_TRACKING\n\n#include \"main.h\"\n\ntemplate <int N, typename XprType>\nvoid use_n_times(const XprType &xpr)\n{\n  typename internal::nested_eval<XprType,N>::type mat(xpr);\n  typename XprType::PlainObject res(mat.rows(), mat.cols());\n  nb_temporaries--; // remove res\n  res.setZero();\n  for(int i=0; i<N; ++i)\n    res += mat;\n}\n\ntemplate <int N, typename ReferenceType, typename XprType>\nbool verify_eval_type(const XprType &, const ReferenceType&)\n{\n  typedef typename internal::nested_eval<XprType,N>::type EvalType;\n  return internal::is_same<typename internal::remove_all<EvalType>::type, typename internal::remove_all<ReferenceType>::type>::value;\n}\n\ntemplate <typename MatrixType> void run_nesting_ops_1(const MatrixType& _m)\n{\n  typename internal::nested_eval<MatrixType,2>::type m(_m);\n\n  // Make really sure that we are in debug mode!\n  VERIFY_RAISES_ASSERT(eigen_assert(false));\n\n  // The only intention of these tests is to ensure that this code does\n  // not trigger any asserts or segmentation faults... more to come.\n  VERIFY_IS_APPROX( (m.transpose() * m).diagonal().sum(), (m.transpose() * m).diagonal().sum() );\n  VERIFY_IS_APPROX( (m.transpose() * m).diagonal().array().abs().sum(), (m.transpose() * m).diagonal().array().abs().sum() );\n\n  VERIFY_IS_APPROX( (m.transpose() * m).array().abs().sum(), (m.transpose() * m).array().abs().sum() );\n}\n\ntemplate <typename MatrixType> void run_nesting_ops_2(const MatrixType& _m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  Index rows = _m.rows();\n  Index cols = _m.cols();\n  MatrixType m1 = MatrixType::Random(rows,cols);\n  Matrix<Scalar,MatrixType::RowsAtCompileTime,MatrixType::ColsAtCompileTime,ColMajor> m2;\n\n  if((MatrixType::SizeAtCompileTime==Dynamic))\n  {\n    VERIFY_EVALUATION_COUNT( use_n_times<1>(m1 + m1*m1), 1 );\n    VERIFY_EVALUATION_COUNT( use_n_times<10>(m1 + m1*m1), 1 );\n\n    VERIFY_EVALUATION_COUNT( use_n_times<1>(m1.template triangularView<Lower>().solve(m1.col(0))), 1 );\n    VERIFY_EVALUATION_COUNT( use_n_times<10>(m1.template triangularView<Lower>().solve(m1.col(0))), 1 );\n\n    VERIFY_EVALUATION_COUNT( use_n_times<1>(Scalar(2)*m1.template triangularView<Lower>().solve(m1.col(0))), 2 ); // FIXME could be one by applying the scaling in-place on the solve result\n    VERIFY_EVALUATION_COUNT( use_n_times<1>(m1.col(0)+m1.template triangularView<Lower>().solve(m1.col(0))), 2 ); // FIXME could be one by adding m1.col() inplace\n    VERIFY_EVALUATION_COUNT( use_n_times<10>(m1.col(0)+m1.template triangularView<Lower>().solve(m1.col(0))), 2 );\n  }\n\n  {\n    VERIFY( verify_eval_type<10>(m1, m1) );\n    if(!NumTraits<Scalar>::IsComplex)\n    {\n      VERIFY( verify_eval_type<3>(2*m1, 2*m1) );\n      VERIFY( verify_eval_type<4>(2*m1, m1) );\n    }\n    else\n    {\n      VERIFY( verify_eval_type<2>(2*m1, 2*m1) );\n      VERIFY( verify_eval_type<3>(2*m1, m1) );\n    }\n    VERIFY( verify_eval_type<2>(m1+m1, m1+m1) );\n    VERIFY( verify_eval_type<3>(m1+m1, m1) );\n    VERIFY( verify_eval_type<1>(m1*m1.transpose(), m2) );\n    VERIFY( verify_eval_type<1>(m1*(m1+m1).transpose(), m2) );\n    VERIFY( verify_eval_type<2>(m1*m1.transpose(), m2) );\n    VERIFY( verify_eval_type<1>(m1+m1*m1, m1) );\n\n    VERIFY( verify_eval_type<1>(m1.template triangularView<Lower>().solve(m1), m1) );\n    VERIFY( verify_eval_type<1>(m1+m1.template triangularView<Lower>().solve(m1), m1) );\n  }\n}\n\n\nEIGEN_DECLARE_TEST(nesting_ops)\n{\n  CALL_SUBTEST_1(run_nesting_ops_1(MatrixXf::Random(25,25)));\n  CALL_SUBTEST_2(run_nesting_ops_1(MatrixXcd::Random(25,25)));\n  CALL_SUBTEST_3(run_nesting_ops_1(Matrix4f::Random()));\n  CALL_SUBTEST_4(run_nesting_ops_1(Matrix2d::Random()));\n\n  Index s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE);\n  CALL_SUBTEST_1( run_nesting_ops_2(MatrixXf(s,s)) );\n  CALL_SUBTEST_2( run_nesting_ops_2(MatrixXcd(s,s)) );\n  CALL_SUBTEST_3( run_nesting_ops_2(Matrix4f()) );\n  CALL_SUBTEST_4( run_nesting_ops_2(Matrix2d()) );\n  TEST_SET_BUT_UNUSED_VARIABLE(s)\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/nomalloc.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// discard stack allocation as that too bypasses malloc\n#define EIGEN_STACK_ALLOCATION_LIMIT 0\n// heap allocation will raise an assert if enabled at runtime\n#define EIGEN_RUNTIME_NO_MALLOC\n\n#include \"main.h\"\n#include <Eigen/Cholesky>\n#include <Eigen/Eigenvalues>\n#include <Eigen/LU>\n#include <Eigen/QR>\n#include <Eigen/SVD>\n\ntemplate<typename MatrixType> void nomalloc(const MatrixType& m)\n{\n  /* this test check no dynamic memory allocation are issued with fixed-size matrices\n  */\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols);\n\n  Scalar s1 = internal::random<Scalar>();\n\n  Index r = internal::random<Index>(0, rows-1),\n        c = internal::random<Index>(0, cols-1);\n\n  VERIFY_IS_APPROX((m1+m2)*s1,              s1*m1+s1*m2);\n  VERIFY_IS_APPROX((m1+m2)(r,c), (m1(r,c))+(m2(r,c)));\n  VERIFY_IS_APPROX(m1.cwiseProduct(m1.block(0,0,rows,cols)), (m1.array()*m1.array()).matrix());\n  VERIFY_IS_APPROX((m1*m1.transpose())*m2,  m1*(m1.transpose()*m2));\n  \n  m2.col(0).noalias() = m1 * m1.col(0);\n  m2.col(0).noalias() -= m1.adjoint() * m1.col(0);\n  m2.col(0).noalias() -= m1 * m1.row(0).adjoint();\n  m2.col(0).noalias() -= m1.adjoint() * m1.row(0).adjoint();\n\n  m2.row(0).noalias() = m1.row(0) * m1;\n  m2.row(0).noalias() -= m1.row(0) * m1.adjoint();\n  m2.row(0).noalias() -= m1.col(0).adjoint() * m1;\n  m2.row(0).noalias() -= m1.col(0).adjoint() * m1.adjoint();\n  VERIFY_IS_APPROX(m2,m2);\n  \n  m2.col(0).noalias() = m1.template triangularView<Upper>() * m1.col(0);\n  m2.col(0).noalias() -= m1.adjoint().template triangularView<Upper>() * m1.col(0);\n  m2.col(0).noalias() -= m1.template triangularView<Upper>() * m1.row(0).adjoint();\n  m2.col(0).noalias() -= m1.adjoint().template triangularView<Upper>() * m1.row(0).adjoint();\n\n  m2.row(0).noalias() = m1.row(0) * m1.template triangularView<Upper>();\n  m2.row(0).noalias() -= m1.row(0) * m1.adjoint().template triangularView<Upper>();\n  m2.row(0).noalias() -= m1.col(0).adjoint() * m1.template triangularView<Upper>();\n  m2.row(0).noalias() -= m1.col(0).adjoint() * m1.adjoint().template triangularView<Upper>();\n  VERIFY_IS_APPROX(m2,m2);\n  \n  m2.col(0).noalias() = m1.template selfadjointView<Upper>() * m1.col(0);\n  m2.col(0).noalias() -= m1.adjoint().template selfadjointView<Upper>() * m1.col(0);\n  m2.col(0).noalias() -= m1.template selfadjointView<Upper>() * m1.row(0).adjoint();\n  m2.col(0).noalias() -= m1.adjoint().template selfadjointView<Upper>() * m1.row(0).adjoint();\n\n  m2.row(0).noalias() = m1.row(0) * m1.template selfadjointView<Upper>();\n  m2.row(0).noalias() -= m1.row(0) * m1.adjoint().template selfadjointView<Upper>();\n  m2.row(0).noalias() -= m1.col(0).adjoint() * m1.template selfadjointView<Upper>();\n  m2.row(0).noalias() -= m1.col(0).adjoint() * m1.adjoint().template selfadjointView<Upper>();\n  VERIFY_IS_APPROX(m2,m2);\n  \n  m2.template selfadjointView<Lower>().rankUpdate(m1.col(0),-1);\n  m2.template selfadjointView<Upper>().rankUpdate(m1.row(0),-1);\n  m2.template selfadjointView<Lower>().rankUpdate(m1.col(0), m1.col(0)); // rank-2\n\n  // The following fancy matrix-matrix products are not safe yet regarding static allocation\n  m2.template selfadjointView<Lower>().rankUpdate(m1);\n  m2 += m2.template triangularView<Upper>() * m1;\n  m2.template triangularView<Upper>() = m2 * m2;\n  m1 += m1.template selfadjointView<Lower>() * m2;\n  VERIFY_IS_APPROX(m2,m2);\n}\n\ntemplate<typename Scalar>\nvoid ctms_decompositions()\n{\n  const int maxSize = 16;\n  const int size    = 12;\n\n  typedef Eigen::Matrix<Scalar,\n                        Eigen::Dynamic, Eigen::Dynamic,\n                        0,\n                        maxSize, maxSize> Matrix;\n\n  typedef Eigen::Matrix<Scalar,\n                        Eigen::Dynamic, 1,\n                        0,\n                        maxSize, 1> Vector;\n\n  typedef Eigen::Matrix<std::complex<Scalar>,\n                        Eigen::Dynamic, Eigen::Dynamic,\n                        0,\n                        maxSize, maxSize> ComplexMatrix;\n\n  const Matrix A(Matrix::Random(size, size)), B(Matrix::Random(size, size));\n  Matrix X(size,size);\n  const ComplexMatrix complexA(ComplexMatrix::Random(size, size));\n  const Matrix saA = A.adjoint() * A;\n  const Vector b(Vector::Random(size));\n  Vector x(size);\n\n  // Cholesky module\n  Eigen::LLT<Matrix>  LLT;  LLT.compute(A);\n  X = LLT.solve(B);\n  x = LLT.solve(b);\n  Eigen::LDLT<Matrix> LDLT; LDLT.compute(A);\n  X = LDLT.solve(B);\n  x = LDLT.solve(b);\n\n  // Eigenvalues module\n  Eigen::HessenbergDecomposition<ComplexMatrix> hessDecomp;        hessDecomp.compute(complexA);\n  Eigen::ComplexSchur<ComplexMatrix>            cSchur(size);      cSchur.compute(complexA);\n  Eigen::ComplexEigenSolver<ComplexMatrix>      cEigSolver;        cEigSolver.compute(complexA);\n  Eigen::EigenSolver<Matrix>                    eigSolver;         eigSolver.compute(A);\n  Eigen::SelfAdjointEigenSolver<Matrix>         saEigSolver(size); saEigSolver.compute(saA);\n  Eigen::Tridiagonalization<Matrix>             tridiag;           tridiag.compute(saA);\n\n  // LU module\n  Eigen::PartialPivLU<Matrix> ppLU; ppLU.compute(A);\n  X = ppLU.solve(B);\n  x = ppLU.solve(b);\n  Eigen::FullPivLU<Matrix>    fpLU; fpLU.compute(A);\n  X = fpLU.solve(B);\n  x = fpLU.solve(b);\n\n  // QR module\n  Eigen::HouseholderQR<Matrix>        hQR;  hQR.compute(A);\n  X = hQR.solve(B);\n  x = hQR.solve(b);\n  Eigen::ColPivHouseholderQR<Matrix>  cpQR; cpQR.compute(A);\n  X = cpQR.solve(B);\n  x = cpQR.solve(b);\n  Eigen::FullPivHouseholderQR<Matrix> fpQR; fpQR.compute(A);\n  // FIXME X = fpQR.solve(B);\n  x = fpQR.solve(b);\n\n  // SVD module\n  Eigen::JacobiSVD<Matrix> jSVD; jSVD.compute(A, ComputeFullU | ComputeFullV);\n}\n\nvoid test_zerosized() {\n  // default constructors:\n  Eigen::MatrixXd A;\n  Eigen::VectorXd v;\n  // explicit zero-sized:\n  Eigen::ArrayXXd A0(0,0);\n  Eigen::ArrayXd v0(0);\n\n  // assigning empty objects to each other:\n  A=A0;\n  v=v0;\n}\n\ntemplate<typename MatrixType> void test_reference(const MatrixType& m) {\n  typedef typename MatrixType::Scalar Scalar;\n  enum { Flag          =  MatrixType::IsRowMajor ? Eigen::RowMajor : Eigen::ColMajor};\n  enum { TransposeFlag = !MatrixType::IsRowMajor ? Eigen::RowMajor : Eigen::ColMajor};\n  Index rows = m.rows(), cols=m.cols();\n  typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, Flag         > MatrixX;\n  typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic, TransposeFlag> MatrixXT;\n  // Dynamic reference:\n  typedef Eigen::Ref<const MatrixX  > Ref;\n  typedef Eigen::Ref<const MatrixXT > RefT;\n\n  Ref r1(m);\n  Ref r2(m.block(rows/3, cols/4, rows/2, cols/2));\n  RefT r3(m.transpose());\n  RefT r4(m.topLeftCorner(rows/2, cols/2).transpose());\n\n  VERIFY_RAISES_ASSERT(RefT r5(m));\n  VERIFY_RAISES_ASSERT(Ref r6(m.transpose()));\n  VERIFY_RAISES_ASSERT(Ref r7(Scalar(2) * m));\n\n  // Copy constructors shall also never malloc\n  Ref r8 = r1;\n  RefT r9 = r3;\n\n  // Initializing from a compatible Ref shall also never malloc\n  Eigen::Ref<const MatrixX, Unaligned, Stride<Dynamic, Dynamic> > r10=r8, r11=m;\n\n  // Initializing from an incompatible Ref will malloc:\n  typedef Eigen::Ref<const MatrixX, Aligned> RefAligned;\n  VERIFY_RAISES_ASSERT(RefAligned r12=r10);\n  VERIFY_RAISES_ASSERT(Ref r13=r10); // r10 has more dynamic strides\n\n}\n\nEIGEN_DECLARE_TEST(nomalloc)\n{\n  // create some dynamic objects\n  Eigen::MatrixXd M1 = MatrixXd::Random(3,3);\n  Ref<const MatrixXd> R1 = 2.0*M1; // Ref requires temporary\n\n  // from here on prohibit malloc:\n  Eigen::internal::set_is_malloc_allowed(false);\n\n  // check that our operator new is indeed called:\n  VERIFY_RAISES_ASSERT(MatrixXd dummy(MatrixXd::Random(3,3)));\n  CALL_SUBTEST_1(nomalloc(Matrix<float, 1, 1>()) );\n  CALL_SUBTEST_2(nomalloc(Matrix4d()) );\n  CALL_SUBTEST_3(nomalloc(Matrix<float,32,32>()) );\n  \n  // Check decomposition modules with dynamic matrices that have a known compile-time max size (ctms)\n  CALL_SUBTEST_4(ctms_decompositions<float>());\n\n  CALL_SUBTEST_5(test_zerosized());\n\n  CALL_SUBTEST_6(test_reference(Matrix<float,32,32>()));\n  CALL_SUBTEST_7(test_reference(R1));\n  CALL_SUBTEST_8(Ref<MatrixXd> R2 = M1.topRows<2>(); test_reference(R2));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/nullary.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010-2011 Jitse Niesen <jitse@maths.leeds.ac.uk>\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType>\nbool equalsIdentity(const MatrixType& A)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  Scalar zero = static_cast<Scalar>(0);\n\n  bool offDiagOK = true;\n  for (Index i = 0; i < A.rows(); ++i) {\n    for (Index j = i+1; j < A.cols(); ++j) {\n      offDiagOK = offDiagOK && (A(i,j) == zero);\n    }\n  }\n  for (Index i = 0; i < A.rows(); ++i) {\n    for (Index j = 0; j < (std::min)(i, A.cols()); ++j) {\n      offDiagOK = offDiagOK && (A(i,j) == zero);\n    }\n  }\n\n  bool diagOK = (A.diagonal().array() == 1).all();\n  return offDiagOK && diagOK;\n\n}\n\ntemplate<typename VectorType>\nvoid check_extremity_accuracy(const VectorType &v, const typename VectorType::Scalar &low, const typename VectorType::Scalar &high)\n{\n  typedef typename VectorType::Scalar Scalar;\n  typedef typename VectorType::RealScalar RealScalar;\n\n  RealScalar prec = internal::is_same<RealScalar,float>::value ? NumTraits<RealScalar>::dummy_precision()*10 : NumTraits<RealScalar>::dummy_precision()/10;\n  Index size = v.size();\n\n  if(size<20)\n    return;\n\n  for (int i=0; i<size; ++i)\n  {\n    if(i<5 || i>size-6)\n    {\n      Scalar ref = (low*RealScalar(size-i-1))/RealScalar(size-1) + (high*RealScalar(i))/RealScalar(size-1);\n      if(std::abs(ref)>1)\n      {\n        if(!internal::isApprox(v(i), ref, prec))\n          std::cout << v(i) << \" != \" << ref << \"  ; relative error: \" << std::abs((v(i)-ref)/ref) << \"  ; required precision: \" << prec << \"  ; range: \" << low << \",\" << high << \"  ; i: \" << i << \"\\n\";\n        VERIFY(internal::isApprox(v(i), (low*RealScalar(size-i-1))/RealScalar(size-1) + (high*RealScalar(i))/RealScalar(size-1), prec));\n      }\n    }\n  }\n}\n\ntemplate<typename VectorType>\nvoid testVectorType(const VectorType& base)\n{\n  typedef typename VectorType::Scalar Scalar;\n  typedef typename VectorType::RealScalar RealScalar;\n\n  const Index size = base.size();\n  \n  Scalar high = internal::random<Scalar>(-500,500);\n  Scalar low = (size == 1 ? high : internal::random<Scalar>(-500,500));\n  if (numext::real(low)>numext::real(high)) std::swap(low,high);\n\n  // check low==high\n  if(internal::random<float>(0.f,1.f)<0.05f)\n    low = high;\n  // check abs(low) >> abs(high)\n  else if(size>2 && std::numeric_limits<RealScalar>::max_exponent10>0 && internal::random<float>(0.f,1.f)<0.1f)\n    low = -internal::random<Scalar>(1,2) * RealScalar(std::pow(RealScalar(10),std::numeric_limits<RealScalar>::max_exponent10/2));\n\n  const Scalar step = ((size == 1) ? 1 : (high-low)/RealScalar(size-1));\n\n  // check whether the result yields what we expect it to do\n  VectorType m(base);\n  m.setLinSpaced(size,low,high);\n\n  if(!NumTraits<Scalar>::IsInteger)\n  {\n    VectorType n(size);\n    for (int i=0; i<size; ++i)\n      n(i) = low+RealScalar(i)*step;\n    VERIFY_IS_APPROX(m,n);\n\n    CALL_SUBTEST( check_extremity_accuracy(m, low, high) );\n  }\n\n  RealScalar range_length = numext::real(high-low);\n  if((!NumTraits<Scalar>::IsInteger) || (range_length>=size && (Index(range_length)%(size-1))==0) || (Index(range_length+1)<size && (size%Index(range_length+1))==0))\n  {\n    VectorType n(size);\n    if((!NumTraits<Scalar>::IsInteger) || (range_length>=size))\n      for (int i=0; i<size; ++i)\n        n(i) = size==1 ? low : (low + ((high-low)*Scalar(i))/RealScalar(size-1));\n    else\n      for (int i=0; i<size; ++i)\n        n(i) = size==1 ? low : low + Scalar((double(range_length+1)*double(i))/double(size));\n    VERIFY_IS_APPROX(m,n);\n\n    // random access version\n    m = VectorType::LinSpaced(size,low,high);\n    VERIFY_IS_APPROX(m,n);\n    VERIFY( internal::isApprox(m(m.size()-1),high) );\n    VERIFY( size==1 || internal::isApprox(m(0),low) );\n    VERIFY_IS_EQUAL(m(m.size()-1) , high);\n    if(!NumTraits<Scalar>::IsInteger)\n      CALL_SUBTEST( check_extremity_accuracy(m, low, high) );\n  }\n\n  VERIFY( numext::real(m(m.size()-1)) <= numext::real(high) );\n  VERIFY( (m.array().real() <= numext::real(high)).all() );\n  VERIFY( (m.array().real() >= numext::real(low)).all() );\n\n\n  VERIFY( numext::real(m(m.size()-1)) >= numext::real(low) );\n  if(size>=1)\n  {\n    VERIFY( internal::isApprox(m(0),low) );\n    VERIFY_IS_EQUAL(m(0) , low);\n  }\n\n  // check whether everything works with row and col major vectors\n  Matrix<Scalar,Dynamic,1> row_vector(size);\n  Matrix<Scalar,1,Dynamic> col_vector(size);\n  row_vector.setLinSpaced(size,low,high);\n  col_vector.setLinSpaced(size,low,high);\n  // when using the extended precision (e.g., FPU) the relative error might exceed 1 bit\n  // when computing the squared sum in isApprox, thus the 2x factor.\n  VERIFY( row_vector.isApprox(col_vector.transpose(), RealScalar(2)*NumTraits<Scalar>::epsilon()));\n\n  Matrix<Scalar,Dynamic,1> size_changer(size+50);\n  size_changer.setLinSpaced(size,low,high);\n  VERIFY( size_changer.size() == size );\n\n  typedef Matrix<Scalar,1,1> ScalarMatrix;\n  ScalarMatrix scalar;\n  scalar.setLinSpaced(1,low,high);\n  VERIFY_IS_APPROX( scalar, ScalarMatrix::Constant(high) );\n  VERIFY_IS_APPROX( ScalarMatrix::LinSpaced(1,low,high), ScalarMatrix::Constant(high) );\n\n  // regression test for bug 526 (linear vectorized transversal)\n  if (size > 1 && (!NumTraits<Scalar>::IsInteger)) {\n    m.tail(size-1).setLinSpaced(low, high);\n    VERIFY_IS_APPROX(m(size-1), high);\n  }\n\n  // regression test for bug 1383 (LinSpaced with empty size/range)\n  {\n    Index n0 = VectorType::SizeAtCompileTime==Dynamic ? 0 : VectorType::SizeAtCompileTime;\n    low = internal::random<Scalar>();\n    m = VectorType::LinSpaced(n0,low,low-RealScalar(1));\n    VERIFY(m.size()==n0);\n\n    if(VectorType::SizeAtCompileTime==Dynamic)\n    {\n      VERIFY_IS_EQUAL(VectorType::LinSpaced(n0,0,Scalar(n0-1)).sum(),Scalar(0));\n      VERIFY_IS_EQUAL(VectorType::LinSpaced(n0,low,low-RealScalar(1)).sum(),Scalar(0));\n    }\n\n    m.setLinSpaced(n0,0,Scalar(n0-1));\n    VERIFY(m.size()==n0);\n    m.setLinSpaced(n0,low,low-RealScalar(1));\n    VERIFY(m.size()==n0);\n\n    // empty range only:\n    VERIFY_IS_APPROX(VectorType::LinSpaced(size,low,low),VectorType::Constant(size,low));\n    m.setLinSpaced(size,low,low);\n    VERIFY_IS_APPROX(m,VectorType::Constant(size,low));\n\n    if(NumTraits<Scalar>::IsInteger)\n    {\n      VERIFY_IS_APPROX( VectorType::LinSpaced(size,low,low+Scalar(size-1)), VectorType::LinSpaced(size,low+Scalar(size-1),low).reverse() );\n\n      if(VectorType::SizeAtCompileTime==Dynamic)\n      {\n        // Check negative multiplicator path:\n        for(Index k=1; k<5; ++k)\n          VERIFY_IS_APPROX( VectorType::LinSpaced(size,low,low+Scalar((size-1)*k)), VectorType::LinSpaced(size,low+Scalar((size-1)*k),low).reverse() );\n        // Check negative divisor path:\n        for(Index k=1; k<5; ++k)\n          VERIFY_IS_APPROX( VectorType::LinSpaced(size*k,low,low+Scalar(size-1)), VectorType::LinSpaced(size*k,low+Scalar(size-1),low).reverse() );\n      }\n    }\n  }\n\n  // test setUnit()\n  if(m.size()>0)\n  {\n    for(Index k=0; k<10; ++k)\n    {\n      Index i = internal::random<Index>(0,m.size()-1);\n      m.setUnit(i);\n      VERIFY_IS_APPROX( m, VectorType::Unit(m.size(), i) );\n    }\n    if(VectorType::SizeAtCompileTime==Dynamic)\n    {\n      Index i = internal::random<Index>(0,2*m.size()-1);\n      m.setUnit(2*m.size(),i);\n      VERIFY_IS_APPROX( m, VectorType::Unit(m.size(),i) );\n    }\n  }\n\n}\n\ntemplate<typename MatrixType>\nvoid testMatrixType(const MatrixType& m)\n{\n  using std::abs;\n  const Index rows = m.rows();\n  const Index cols = m.cols();\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n\n  Scalar s1;\n  do {\n    s1 = internal::random<Scalar>();\n  } while(abs(s1)<RealScalar(1e-5) && (!NumTraits<Scalar>::IsInteger));\n\n  MatrixType A;\n  A.setIdentity(rows, cols);\n  VERIFY(equalsIdentity(A));\n  VERIFY(equalsIdentity(MatrixType::Identity(rows, cols)));\n\n\n  A = MatrixType::Constant(rows,cols,s1);\n  Index i = internal::random<Index>(0,rows-1);\n  Index j = internal::random<Index>(0,cols-1);\n  VERIFY_IS_APPROX( MatrixType::Constant(rows,cols,s1)(i,j), s1 );\n  VERIFY_IS_APPROX( MatrixType::Constant(rows,cols,s1).coeff(i,j), s1 );\n  VERIFY_IS_APPROX( A(i,j), s1 );\n}\n\ntemplate<int>\nvoid bug79()\n{\n  // Assignment of a RowVectorXd to a MatrixXd (regression test for bug #79).\n  VERIFY( (MatrixXd(RowVectorXd::LinSpaced(3, 0, 1)) - RowVector3d(0, 0.5, 1)).norm() < std::numeric_limits<double>::epsilon() );\n}\n\ntemplate<int>\nvoid bug1630()\n{\n  Array4d x4 = Array4d::LinSpaced(0.0, 1.0);\n  Array3d x3(Array4d::LinSpaced(0.0, 1.0).head(3));\n  VERIFY_IS_APPROX(x4.head(3), x3);\n}\n\ntemplate<int>\nvoid nullary_overflow()\n{\n  // Check possible overflow issue\n  int n = 60000;\n  ArrayXi a1(n), a2(n);\n  a1.setLinSpaced(n, 0, n-1);\n  for(int i=0; i<n; ++i)\n    a2(i) = i;\n  VERIFY_IS_APPROX(a1,a2);\n}\n\ntemplate<int>\nvoid nullary_internal_logic()\n{\n  // check some internal logic\n  VERIFY((  internal::has_nullary_operator<internal::scalar_constant_op<double> >::value ));\n  VERIFY(( !internal::has_unary_operator<internal::scalar_constant_op<double> >::value ));\n  VERIFY(( !internal::has_binary_operator<internal::scalar_constant_op<double> >::value ));\n  VERIFY((  internal::functor_has_linear_access<internal::scalar_constant_op<double> >::ret ));\n\n  VERIFY(( !internal::has_nullary_operator<internal::scalar_identity_op<double> >::value ));\n  VERIFY(( !internal::has_unary_operator<internal::scalar_identity_op<double> >::value ));\n  VERIFY((  internal::has_binary_operator<internal::scalar_identity_op<double> >::value ));\n  VERIFY(( !internal::functor_has_linear_access<internal::scalar_identity_op<double> >::ret ));\n\n  VERIFY(( !internal::has_nullary_operator<internal::linspaced_op<float> >::value ));\n  VERIFY((  internal::has_unary_operator<internal::linspaced_op<float> >::value ));\n  VERIFY(( !internal::has_binary_operator<internal::linspaced_op<float> >::value ));\n  VERIFY((  internal::functor_has_linear_access<internal::linspaced_op<float> >::ret ));\n\n  // Regression unit test for a weird MSVC bug.\n  // Search \"nullary_wrapper_workaround_msvc\" in CoreEvaluators.h for the details.\n  // See also traits<Ref>::match.\n  {\n    MatrixXf A = MatrixXf::Random(3,3);\n    Ref<const MatrixXf> R = 2.0*A;\n    VERIFY_IS_APPROX(R, A+A);\n\n    Ref<const MatrixXf> R1 = MatrixXf::Random(3,3)+A;\n\n    VectorXi V = VectorXi::Random(3);\n    Ref<const VectorXi> R2 = VectorXi::LinSpaced(3,1,3)+V;\n    VERIFY_IS_APPROX(R2, V+Vector3i(1,2,3));\n\n    VERIFY((  internal::has_nullary_operator<internal::scalar_constant_op<float> >::value ));\n    VERIFY(( !internal::has_unary_operator<internal::scalar_constant_op<float> >::value ));\n    VERIFY(( !internal::has_binary_operator<internal::scalar_constant_op<float> >::value ));\n    VERIFY((  internal::functor_has_linear_access<internal::scalar_constant_op<float> >::ret ));\n\n    VERIFY(( !internal::has_nullary_operator<internal::linspaced_op<int> >::value ));\n    VERIFY((  internal::has_unary_operator<internal::linspaced_op<int> >::value ));\n    VERIFY(( !internal::has_binary_operator<internal::linspaced_op<int> >::value ));\n    VERIFY((  internal::functor_has_linear_access<internal::linspaced_op<int> >::ret ));\n  }\n}\n\nEIGEN_DECLARE_TEST(nullary)\n{\n  CALL_SUBTEST_1( testMatrixType(Matrix2d()) );\n  CALL_SUBTEST_2( testMatrixType(MatrixXcf(internal::random<int>(1,300),internal::random<int>(1,300))) );\n  CALL_SUBTEST_3( testMatrixType(MatrixXf(internal::random<int>(1,300),internal::random<int>(1,300))) );\n  \n  for(int i = 0; i < g_repeat*10; i++) {\n    CALL_SUBTEST_3( testVectorType(VectorXcd(internal::random<int>(1,30000))) );\n    CALL_SUBTEST_4( testVectorType(VectorXd(internal::random<int>(1,30000))) );\n    CALL_SUBTEST_5( testVectorType(Vector4d()) );  // regression test for bug 232\n    CALL_SUBTEST_6( testVectorType(Vector3d()) );\n    CALL_SUBTEST_7( testVectorType(VectorXf(internal::random<int>(1,30000))) );\n    CALL_SUBTEST_8( testVectorType(Vector3f()) );\n    CALL_SUBTEST_8( testVectorType(Vector4f()) );\n    CALL_SUBTEST_8( testVectorType(Matrix<float,8,1>()) );\n    CALL_SUBTEST_8( testVectorType(Matrix<float,1,1>()) );\n\n    CALL_SUBTEST_9( testVectorType(VectorXi(internal::random<int>(1,10))) );\n    CALL_SUBTEST_9( testVectorType(VectorXi(internal::random<int>(9,300))) );\n    CALL_SUBTEST_9( testVectorType(Matrix<int,1,1>()) );\n  }\n\n  CALL_SUBTEST_6( bug79<0>() );\n  CALL_SUBTEST_6( bug1630<0>() );\n  CALL_SUBTEST_9( nullary_overflow<0>() );\n  CALL_SUBTEST_10( nullary_internal_logic<0>() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/num_dimensions.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2018 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/SparseCore>\n\ntemplate<int ExpectedDim,typename Xpr>\nvoid check_dim(const Xpr& ) {\n  STATIC_CHECK( Xpr::NumDimensions == ExpectedDim );\n}\n\n#if EIGEN_HAS_CXX11\ntemplate<template <typename,int,int> class Object>\nvoid map_num_dimensions()\n{\n  typedef Object<double, 1, 1> ArrayScalarType;\n  typedef Object<double, 2, 1> ArrayVectorType;\n  typedef Object<double, 1, 2> TransposeArrayVectorType;\n  typedef Object<double, 2, 2> ArrayType;\n  typedef Object<double, Eigen::Dynamic, 1> DynamicArrayVectorType;\n  typedef Object<double, 1, Eigen::Dynamic> DynamicTransposeArrayVectorType;\n  typedef Object<double, Eigen::Dynamic, Eigen::Dynamic> DynamicArrayType;\n\n  STATIC_CHECK(ArrayScalarType::NumDimensions == 0);\n  STATIC_CHECK(ArrayVectorType::NumDimensions == 1);\n  STATIC_CHECK(TransposeArrayVectorType::NumDimensions == 1);\n  STATIC_CHECK(ArrayType::NumDimensions == 2);\n  STATIC_CHECK(DynamicArrayVectorType::NumDimensions == 1);\n  STATIC_CHECK(DynamicTransposeArrayVectorType::NumDimensions == 1);\n  STATIC_CHECK(DynamicArrayType::NumDimensions == 2);\n\n  typedef Eigen::Map<ArrayScalarType> ArrayScalarMap;\n  typedef Eigen::Map<ArrayVectorType> ArrayVectorMap;\n  typedef Eigen::Map<TransposeArrayVectorType> TransposeArrayVectorMap;\n  typedef Eigen::Map<ArrayType> ArrayMap;\n  typedef Eigen::Map<DynamicArrayVectorType> DynamicArrayVectorMap;\n  typedef Eigen::Map<DynamicTransposeArrayVectorType> DynamicTransposeArrayVectorMap;\n  typedef Eigen::Map<DynamicArrayType> DynamicArrayMap;\n\n  STATIC_CHECK(ArrayScalarMap::NumDimensions == 0);\n  STATIC_CHECK(ArrayVectorMap::NumDimensions == 1);\n  STATIC_CHECK(TransposeArrayVectorMap::NumDimensions == 1);\n  STATIC_CHECK(ArrayMap::NumDimensions == 2);\n  STATIC_CHECK(DynamicArrayVectorMap::NumDimensions == 1);\n  STATIC_CHECK(DynamicTransposeArrayVectorMap::NumDimensions == 1);\n  STATIC_CHECK(DynamicArrayMap::NumDimensions == 2);\n}\n\ntemplate<typename Scalar, int Rows, int Cols>\nusing TArray = Array<Scalar,Rows,Cols>;\n\ntemplate<typename Scalar, int Rows, int Cols>\nusing TMatrix = Matrix<Scalar,Rows,Cols>;\n\n#endif\n\nEIGEN_DECLARE_TEST(num_dimensions)\n{\n  int n = 10;\n  ArrayXXd A(n,n);\n  CALL_SUBTEST( check_dim<2>(A) );\n  CALL_SUBTEST( check_dim<2>(A.block(1,1,2,2)) );\n  CALL_SUBTEST( check_dim<1>(A.col(1)) );\n  CALL_SUBTEST( check_dim<1>(A.row(1)) );\n\n  MatrixXd M(n,n);\n  CALL_SUBTEST( check_dim<0>(M.row(1)*M.col(1)) );\n\n  SparseMatrix<double> S(n,n);\n  CALL_SUBTEST( check_dim<2>(S) );\n  CALL_SUBTEST( check_dim<2>(S.block(1,1,2,2)) );\n  CALL_SUBTEST( check_dim<1>(S.col(1)) );\n  CALL_SUBTEST( check_dim<1>(S.row(1)) );\n\n  SparseVector<double> s(n);\n  CALL_SUBTEST( check_dim<1>(s) );\n  CALL_SUBTEST( check_dim<1>(s.head(2)) );\n  \n\n  #if EIGEN_HAS_CXX11\n  CALL_SUBTEST( map_num_dimensions<TArray>() );\n  CALL_SUBTEST( map_num_dimensions<TMatrix>() );\n  #endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/numext.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2017 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename T, typename U>\nbool check_if_equal_or_nans(const T& actual, const U& expected) {\n  return ((actual == expected) || ((numext::isnan)(actual) && (numext::isnan)(expected)));\n}\n\ntemplate<typename T, typename U>\nbool check_if_equal_or_nans(const std::complex<T>& actual, const std::complex<U>& expected) {\n  return check_if_equal_or_nans(numext::real(actual), numext::real(expected))\n         && check_if_equal_or_nans(numext::imag(actual), numext::imag(expected));\n}\n\ntemplate<typename T, typename U>\nbool test_is_equal_or_nans(const T& actual, const U& expected)\n{\n    if (check_if_equal_or_nans(actual, expected)) {\n      return true;\n    }\n\n    // false:\n    std::cerr\n        << \"\\n    actual   = \" << actual\n        << \"\\n    expected = \" << expected << \"\\n\\n\";\n    return false;\n}\n\n#define VERIFY_IS_EQUAL_OR_NANS(a, b) VERIFY(test_is_equal_or_nans(a, b))\n\ntemplate<typename T>\nvoid check_abs() {\n  typedef typename NumTraits<T>::Real Real;\n  Real zero(0);\n\n  if(NumTraits<T>::IsSigned)\n    VERIFY_IS_EQUAL(numext::abs(-T(1)), T(1));\n  VERIFY_IS_EQUAL(numext::abs(T(0)), T(0));\n  VERIFY_IS_EQUAL(numext::abs(T(1)), T(1));\n\n  for(int k=0; k<100; ++k)\n  {\n    T x = internal::random<T>();\n    if(!internal::is_same<T,bool>::value)\n      x = x/Real(2);\n    if(NumTraits<T>::IsSigned)\n    {\n      VERIFY_IS_EQUAL(numext::abs(x), numext::abs(-x));\n      VERIFY( numext::abs(-x) >= zero );\n    }\n    VERIFY( numext::abs(x) >= zero );\n    VERIFY_IS_APPROX( numext::abs2(x), numext::abs2(numext::abs(x)) );\n  }\n}\n\ntemplate<typename T>\nstruct check_sqrt_impl {\n  static void run() {\n    for (int i=0; i<1000; ++i) {\n      const T x = numext::abs(internal::random<T>());\n      const T sqrtx = numext::sqrt(x);\n      VERIFY_IS_APPROX(sqrtx*sqrtx, x);\n    }\n\n    // Corner cases.\n    const T zero = T(0);\n    const T one = T(1);\n    const T inf = std::numeric_limits<T>::infinity();\n    const T nan = std::numeric_limits<T>::quiet_NaN();\n    VERIFY_IS_EQUAL(numext::sqrt(zero), zero);\n    VERIFY_IS_EQUAL(numext::sqrt(inf), inf);\n    VERIFY((numext::isnan)(numext::sqrt(nan)));\n    VERIFY((numext::isnan)(numext::sqrt(-one)));\n  }\n};\n\ntemplate<typename T>\nstruct check_sqrt_impl<std::complex<T>  > {\n  static void run() {\n    typedef typename std::complex<T> ComplexT;\n\n    for (int i=0; i<1000; ++i) {\n      const ComplexT x = internal::random<ComplexT>();\n      const ComplexT sqrtx = numext::sqrt(x);\n      VERIFY_IS_APPROX(sqrtx*sqrtx, x);\n    }\n\n    // Corner cases.\n    const T zero = T(0);\n    const T one = T(1);\n    const T inf = std::numeric_limits<T>::infinity();\n    const T nan = std::numeric_limits<T>::quiet_NaN();\n\n    // Set of corner cases from https://en.cppreference.com/w/cpp/numeric/complex/sqrt\n    const int kNumCorners = 20;\n    const ComplexT corners[kNumCorners][2] = {\n      {ComplexT(zero, zero), ComplexT(zero, zero)},\n      {ComplexT(-zero, zero), ComplexT(zero, zero)},\n      {ComplexT(zero, -zero), ComplexT(zero, zero)},\n      {ComplexT(-zero, -zero), ComplexT(zero, zero)},\n      {ComplexT(one, inf), ComplexT(inf, inf)},\n      {ComplexT(nan, inf), ComplexT(inf, inf)},\n      {ComplexT(one, -inf), ComplexT(inf, -inf)},\n      {ComplexT(nan, -inf), ComplexT(inf, -inf)},\n      {ComplexT(-inf, one), ComplexT(zero, inf)},\n      {ComplexT(inf, one), ComplexT(inf, zero)},\n      {ComplexT(-inf, -one), ComplexT(zero, -inf)},\n      {ComplexT(inf, -one), ComplexT(inf, -zero)},\n      {ComplexT(-inf, nan), ComplexT(nan, inf)},\n      {ComplexT(inf, nan), ComplexT(inf, nan)},\n      {ComplexT(zero, nan), ComplexT(nan, nan)},\n      {ComplexT(one, nan), ComplexT(nan, nan)},\n      {ComplexT(nan, zero), ComplexT(nan, nan)},\n      {ComplexT(nan, one), ComplexT(nan, nan)},\n      {ComplexT(nan, -one), ComplexT(nan, nan)},\n      {ComplexT(nan, nan), ComplexT(nan, nan)},\n    };\n\n    for (int i=0; i<kNumCorners; ++i) {\n      const ComplexT& x = corners[i][0];\n      const ComplexT sqrtx = corners[i][1];\n      VERIFY_IS_EQUAL_OR_NANS(numext::sqrt(x), sqrtx);\n    }\n  }\n};\n\ntemplate<typename T>\nvoid check_sqrt() {\n  check_sqrt_impl<T>::run();\n}\n\ntemplate<typename T>\nstruct check_rsqrt_impl {\n  static void run() {\n    const T zero = T(0);\n    const T one = T(1);\n    const T inf = std::numeric_limits<T>::infinity();\n    const T nan = std::numeric_limits<T>::quiet_NaN();\n\n    for (int i=0; i<1000; ++i) {\n      const T x = numext::abs(internal::random<T>());\n      const T rsqrtx = numext::rsqrt(x);\n      const T invx = one / x;\n      VERIFY_IS_APPROX(rsqrtx*rsqrtx, invx);\n    }\n\n    // Corner cases.\n    VERIFY_IS_EQUAL(numext::rsqrt(zero), inf);\n    VERIFY_IS_EQUAL(numext::rsqrt(inf), zero);\n    VERIFY((numext::isnan)(numext::rsqrt(nan)));\n    VERIFY((numext::isnan)(numext::rsqrt(-one)));\n  }\n};\n\ntemplate<typename T>\nstruct check_rsqrt_impl<std::complex<T> > {\n  static void run() {\n    typedef typename std::complex<T> ComplexT;\n    const T zero = T(0);\n    const T one = T(1);\n    const T inf = std::numeric_limits<T>::infinity();\n    const T nan = std::numeric_limits<T>::quiet_NaN();\n\n    for (int i=0; i<1000; ++i) {\n      const ComplexT x = internal::random<ComplexT>();\n      const ComplexT invx = ComplexT(one, zero) / x;\n      const ComplexT rsqrtx = numext::rsqrt(x);\n      VERIFY_IS_APPROX(rsqrtx*rsqrtx, invx);\n    }\n\n    // GCC and MSVC differ in their treatment of 1/(0 + 0i)\n    //   GCC/clang = (inf, nan)\n    //   MSVC = (nan, nan)\n    // and 1 / (x + inf i)\n    //   GCC/clang = (0, 0)\n    //   MSVC = (nan, nan)\n    #if (EIGEN_COMP_GNUC)\n    {\n      const int kNumCorners = 20;\n      const ComplexT corners[kNumCorners][2] = {\n        // Only consistent across GCC, clang\n        {ComplexT(zero, zero), ComplexT(zero, zero)},\n        {ComplexT(-zero, zero), ComplexT(zero, zero)},\n        {ComplexT(zero, -zero), ComplexT(zero, zero)},\n        {ComplexT(-zero, -zero), ComplexT(zero, zero)},\n        {ComplexT(one, inf), ComplexT(inf, inf)},\n        {ComplexT(nan, inf), ComplexT(inf, inf)},\n        {ComplexT(one, -inf), ComplexT(inf, -inf)},\n        {ComplexT(nan, -inf), ComplexT(inf, -inf)},\n        // Consistent across GCC, clang, MSVC\n        {ComplexT(-inf, one), ComplexT(zero, inf)},\n        {ComplexT(inf, one), ComplexT(inf, zero)},\n        {ComplexT(-inf, -one), ComplexT(zero, -inf)},\n        {ComplexT(inf, -one), ComplexT(inf, -zero)},\n        {ComplexT(-inf, nan), ComplexT(nan, inf)},\n        {ComplexT(inf, nan), ComplexT(inf, nan)},\n        {ComplexT(zero, nan), ComplexT(nan, nan)},\n        {ComplexT(one, nan), ComplexT(nan, nan)},\n        {ComplexT(nan, zero), ComplexT(nan, nan)},\n        {ComplexT(nan, one), ComplexT(nan, nan)},\n        {ComplexT(nan, -one), ComplexT(nan, nan)},\n        {ComplexT(nan, nan), ComplexT(nan, nan)},\n      };\n\n      for (int i=0; i<kNumCorners; ++i) {\n        const ComplexT& x = corners[i][0];\n        const ComplexT rsqrtx = ComplexT(one, zero) / corners[i][1];\n        VERIFY_IS_EQUAL_OR_NANS(numext::rsqrt(x), rsqrtx);\n      }\n    }\n    #endif\n  }\n};\n\ntemplate<typename T>\nvoid check_rsqrt() {\n  check_rsqrt_impl<T>::run();\n}\n\nEIGEN_DECLARE_TEST(numext) {\n  for(int k=0; k<g_repeat; ++k)\n  {\n    CALL_SUBTEST( check_abs<bool>() );\n    CALL_SUBTEST( check_abs<signed char>() );\n    CALL_SUBTEST( check_abs<unsigned char>() );\n    CALL_SUBTEST( check_abs<short>() );\n    CALL_SUBTEST( check_abs<unsigned short>() );\n    CALL_SUBTEST( check_abs<int>() );\n    CALL_SUBTEST( check_abs<unsigned int>() );\n    CALL_SUBTEST( check_abs<long>() );\n    CALL_SUBTEST( check_abs<unsigned long>() );\n    CALL_SUBTEST( check_abs<half>() );\n    CALL_SUBTEST( check_abs<bfloat16>() );\n    CALL_SUBTEST( check_abs<float>() );\n    CALL_SUBTEST( check_abs<double>() );\n    CALL_SUBTEST( check_abs<long double>() );\n\n    CALL_SUBTEST( check_abs<std::complex<float> >() );\n    CALL_SUBTEST( check_abs<std::complex<double> >() );\n\n    CALL_SUBTEST( check_sqrt<float>() );\n    CALL_SUBTEST( check_sqrt<double>() );\n    CALL_SUBTEST( check_sqrt<std::complex<float> >() );\n    CALL_SUBTEST( check_sqrt<std::complex<double> >() );\n    \n    CALL_SUBTEST( check_rsqrt<float>() );\n    CALL_SUBTEST( check_rsqrt<double>() );\n    CALL_SUBTEST( check_rsqrt<std::complex<float> >() );\n    CALL_SUBTEST( check_rsqrt<std::complex<double> >() );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/packetmath.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"packetmath_test_shared.h\"\n#include \"random_without_cast_overflow.h\"\n\ntemplate <typename T>\ninline T REF_ADD(const T& a, const T& b) {\n  return a + b;\n}\ntemplate <typename T>\ninline T REF_SUB(const T& a, const T& b) {\n  return a - b;\n}\ntemplate <typename T>\ninline T REF_MUL(const T& a, const T& b) {\n  return a * b;\n}\ntemplate <typename T>\ninline T REF_DIV(const T& a, const T& b) {\n  return a / b;\n}\ntemplate <typename T>\ninline T REF_ABS_DIFF(const T& a, const T& b) {\n  return a > b ? a - b : b - a;\n}\n\n// Specializations for bool.\ntemplate <>\ninline bool REF_ADD(const bool& a, const bool& b) {\n  return a || b;\n}\ntemplate <>\ninline bool REF_SUB(const bool& a, const bool& b) {\n  return a ^ b;\n}\ntemplate <>\ninline bool REF_MUL(const bool& a, const bool& b) {\n  return a && b;\n}\n\ntemplate <typename T>\ninline T REF_FREXP(const T& x, T& exp) {\n  int iexp;\n  EIGEN_USING_STD(frexp)\n  const T out = static_cast<T>(frexp(x, &iexp));\n  exp = static_cast<T>(iexp);\n  return out;\n}\n\ntemplate <typename T>\ninline T REF_LDEXP(const T& x, const T& exp) {\n  EIGEN_USING_STD(ldexp)\n  return static_cast<T>(ldexp(x, static_cast<int>(exp)));\n}\n\n// Uses pcast to cast from one array to another.\ntemplate <typename SrcPacket, typename TgtPacket, int SrcCoeffRatio, int TgtCoeffRatio>\nstruct pcast_array;\n\ntemplate <typename SrcPacket, typename TgtPacket, int TgtCoeffRatio>\nstruct pcast_array<SrcPacket, TgtPacket, 1, TgtCoeffRatio> {\n  typedef typename internal::unpacket_traits<SrcPacket>::type SrcScalar;\n  typedef typename internal::unpacket_traits<TgtPacket>::type TgtScalar;\n  static void cast(const SrcScalar* src, size_t size, TgtScalar* dst) {\n    static const int SrcPacketSize = internal::unpacket_traits<SrcPacket>::size;\n    static const int TgtPacketSize = internal::unpacket_traits<TgtPacket>::size;\n    size_t i;\n    for (i = 0; i < size && i + SrcPacketSize <= size; i += TgtPacketSize) {\n      internal::pstoreu(dst + i, internal::pcast<SrcPacket, TgtPacket>(internal::ploadu<SrcPacket>(src + i)));\n    }\n    // Leftovers that cannot be loaded into a packet.\n    for (; i < size; ++i) {\n      dst[i] = static_cast<TgtScalar>(src[i]);\n    }\n  }\n};\n\ntemplate <typename SrcPacket, typename TgtPacket>\nstruct pcast_array<SrcPacket, TgtPacket, 2, 1> {\n  static void cast(const typename internal::unpacket_traits<SrcPacket>::type* src, size_t size,\n                   typename internal::unpacket_traits<TgtPacket>::type* dst) {\n    static const int SrcPacketSize = internal::unpacket_traits<SrcPacket>::size;\n    static const int TgtPacketSize = internal::unpacket_traits<TgtPacket>::size;\n    for (size_t i = 0; i < size; i += TgtPacketSize) {\n      SrcPacket a = internal::ploadu<SrcPacket>(src + i);\n      SrcPacket b = internal::ploadu<SrcPacket>(src + i + SrcPacketSize);\n      internal::pstoreu(dst + i, internal::pcast<SrcPacket, TgtPacket>(a, b));\n    }\n  }\n};\n\ntemplate <typename SrcPacket, typename TgtPacket>\nstruct pcast_array<SrcPacket, TgtPacket, 4, 1> {\n  static void cast(const typename internal::unpacket_traits<SrcPacket>::type* src, size_t size,\n                   typename internal::unpacket_traits<TgtPacket>::type* dst) {\n    static const int SrcPacketSize = internal::unpacket_traits<SrcPacket>::size;\n    static const int TgtPacketSize = internal::unpacket_traits<TgtPacket>::size;\n    for (size_t i = 0; i < size; i += TgtPacketSize) {\n      SrcPacket a = internal::ploadu<SrcPacket>(src + i);\n      SrcPacket b = internal::ploadu<SrcPacket>(src + i + SrcPacketSize);\n      SrcPacket c = internal::ploadu<SrcPacket>(src + i + 2 * SrcPacketSize);\n      SrcPacket d = internal::ploadu<SrcPacket>(src + i + 3 * SrcPacketSize);\n      internal::pstoreu(dst + i, internal::pcast<SrcPacket, TgtPacket>(a, b, c, d));\n    }\n  }\n};\n\ntemplate <typename SrcPacket, typename TgtPacket>\nstruct pcast_array<SrcPacket, TgtPacket, 8, 1> {\n  static void cast(const typename internal::unpacket_traits<SrcPacket>::type* src, size_t size,\n                   typename internal::unpacket_traits<TgtPacket>::type* dst) {\n    static const int SrcPacketSize = internal::unpacket_traits<SrcPacket>::size;\n    static const int TgtPacketSize = internal::unpacket_traits<TgtPacket>::size;\n    for (size_t i = 0; i < size; i += TgtPacketSize) {\n      SrcPacket a = internal::ploadu<SrcPacket>(src + i);\n      SrcPacket b = internal::ploadu<SrcPacket>(src + i + SrcPacketSize);\n      SrcPacket c = internal::ploadu<SrcPacket>(src + i + 2 * SrcPacketSize);\n      SrcPacket d = internal::ploadu<SrcPacket>(src + i + 3 * SrcPacketSize);\n      SrcPacket e = internal::ploadu<SrcPacket>(src + i + 4 * SrcPacketSize);\n      SrcPacket f = internal::ploadu<SrcPacket>(src + i + 5 * SrcPacketSize);\n      SrcPacket g = internal::ploadu<SrcPacket>(src + i + 6 * SrcPacketSize);\n      SrcPacket h = internal::ploadu<SrcPacket>(src + i + 7 * SrcPacketSize);\n      internal::pstoreu(dst + i, internal::pcast<SrcPacket, TgtPacket>(a, b, c, d, e, f, g, h));\n    }\n  }\n};\n\ntemplate <typename SrcPacket, typename TgtPacket, int SrcCoeffRatio, int TgtCoeffRatio, bool CanCast = false>\nstruct test_cast_helper;\n\ntemplate <typename SrcPacket, typename TgtPacket, int SrcCoeffRatio, int TgtCoeffRatio>\nstruct test_cast_helper<SrcPacket, TgtPacket, SrcCoeffRatio, TgtCoeffRatio, false> {\n  static void run() {}\n};\n\ntemplate <typename SrcPacket, typename TgtPacket, int SrcCoeffRatio, int TgtCoeffRatio>\nstruct test_cast_helper<SrcPacket, TgtPacket, SrcCoeffRatio, TgtCoeffRatio, true> {\n  static void run() {\n    typedef typename internal::unpacket_traits<SrcPacket>::type SrcScalar;\n    typedef typename internal::unpacket_traits<TgtPacket>::type TgtScalar;\n    static const int SrcPacketSize = internal::unpacket_traits<SrcPacket>::size;\n    static const int TgtPacketSize = internal::unpacket_traits<TgtPacket>::size;\n    static const int BlockSize = SrcPacketSize * SrcCoeffRatio;\n    eigen_assert(BlockSize == TgtPacketSize * TgtCoeffRatio && \"Packet sizes and cast ratios are mismatched.\");\n\n    static const int DataSize = 10 * BlockSize;\n    EIGEN_ALIGN_MAX SrcScalar data1[DataSize];\n    EIGEN_ALIGN_MAX TgtScalar data2[DataSize];\n    EIGEN_ALIGN_MAX TgtScalar ref[DataSize];\n\n    // Construct a packet of scalars that will not overflow when casting\n    for (int i = 0; i < DataSize; ++i) {\n      data1[i] = internal::random_without_cast_overflow<SrcScalar, TgtScalar>::value();\n    }\n\n    for (int i = 0; i < DataSize; ++i) {\n      ref[i] = static_cast<const TgtScalar>(data1[i]);\n    }\n\n    pcast_array<SrcPacket, TgtPacket, SrcCoeffRatio, TgtCoeffRatio>::cast(data1, DataSize, data2);\n\n    VERIFY(test::areApprox(ref, data2, DataSize) && \"internal::pcast<>\");\n  }\n};\n\ntemplate <typename SrcPacket, typename TgtPacket>\nstruct test_cast {\n  static void run() {\n    typedef typename internal::unpacket_traits<SrcPacket>::type SrcScalar;\n    typedef typename internal::unpacket_traits<TgtPacket>::type TgtScalar;\n    typedef typename internal::type_casting_traits<SrcScalar, TgtScalar> TypeCastingTraits;\n    static const int SrcCoeffRatio = TypeCastingTraits::SrcCoeffRatio;\n    static const int TgtCoeffRatio = TypeCastingTraits::TgtCoeffRatio;\n    static const int SrcPacketSize = internal::unpacket_traits<SrcPacket>::size;\n    static const int TgtPacketSize = internal::unpacket_traits<TgtPacket>::size;\n    static const bool HasCast =\n        internal::unpacket_traits<SrcPacket>::vectorizable && internal::unpacket_traits<TgtPacket>::vectorizable &&\n        TypeCastingTraits::VectorizedCast && (SrcPacketSize * SrcCoeffRatio == TgtPacketSize * TgtCoeffRatio);\n    test_cast_helper<SrcPacket, TgtPacket, SrcCoeffRatio, TgtCoeffRatio, HasCast>::run();\n  }\n};\n\ntemplate <typename SrcPacket, typename TgtScalar,\n          typename TgtPacket = typename internal::packet_traits<TgtScalar>::type,\n          bool Vectorized = internal::packet_traits<TgtScalar>::Vectorizable,\n          bool HasHalf = !internal::is_same<typename internal::unpacket_traits<TgtPacket>::half, TgtPacket>::value>\nstruct test_cast_runner;\n\ntemplate <typename SrcPacket, typename TgtScalar, typename TgtPacket>\nstruct test_cast_runner<SrcPacket, TgtScalar, TgtPacket, true, false> {\n  static void run() { test_cast<SrcPacket, TgtPacket>::run(); }\n};\n\ntemplate <typename SrcPacket, typename TgtScalar, typename TgtPacket>\nstruct test_cast_runner<SrcPacket, TgtScalar, TgtPacket, true, true> {\n  static void run() {\n    test_cast<SrcPacket, TgtPacket>::run();\n    test_cast_runner<SrcPacket, TgtScalar, typename internal::unpacket_traits<TgtPacket>::half>::run();\n  }\n};\n\ntemplate <typename SrcPacket, typename TgtScalar, typename TgtPacket>\nstruct test_cast_runner<SrcPacket, TgtScalar, TgtPacket, false, false> {\n  static void run() {}\n};\n\ntemplate <typename Scalar, typename Packet, typename EnableIf = void>\nstruct packetmath_pcast_ops_runner {\n  static void run() {\n    test_cast_runner<Packet, float>::run();\n    test_cast_runner<Packet, double>::run();\n    test_cast_runner<Packet, int8_t>::run();\n    test_cast_runner<Packet, uint8_t>::run();\n    test_cast_runner<Packet, int16_t>::run();\n    test_cast_runner<Packet, uint16_t>::run();\n    test_cast_runner<Packet, int32_t>::run();\n    test_cast_runner<Packet, uint32_t>::run();\n    test_cast_runner<Packet, int64_t>::run();\n    test_cast_runner<Packet, uint64_t>::run();\n    test_cast_runner<Packet, bool>::run();\n    test_cast_runner<Packet, std::complex<float> >::run();\n    test_cast_runner<Packet, std::complex<double> >::run();\n    test_cast_runner<Packet, half>::run();\n    test_cast_runner<Packet, bfloat16>::run();\n  }\n};\n\n// Only some types support cast from std::complex<>.\ntemplate <typename Scalar, typename Packet>\nstruct packetmath_pcast_ops_runner<Scalar, Packet, typename internal::enable_if<NumTraits<Scalar>::IsComplex>::type> {\n  static void run() {\n    test_cast_runner<Packet, std::complex<float> >::run();\n    test_cast_runner<Packet, std::complex<double> >::run();\n    test_cast_runner<Packet, half>::run();\n    test_cast_runner<Packet, bfloat16>::run();\n  }\n};\n\ntemplate <typename Scalar, typename Packet>\nvoid packetmath_boolean_mask_ops() {\n  const int PacketSize = internal::unpacket_traits<Packet>::size;\n  const int size = 2 * PacketSize;\n  EIGEN_ALIGN_MAX Scalar data1[size];\n  EIGEN_ALIGN_MAX Scalar data2[size];\n  EIGEN_ALIGN_MAX Scalar ref[size];\n\n  for (int i = 0; i < size; ++i) {\n    data1[i] = internal::random<Scalar>();\n  }\n  CHECK_CWISE1(internal::ptrue, internal::ptrue);\n  CHECK_CWISE2_IF(true, internal::pandnot, internal::pandnot);\n  for (int i = 0; i < PacketSize; ++i) {\n    data1[i] = Scalar(i);\n    data1[i + PacketSize] = internal::random<bool>() ? data1[i] : Scalar(0);\n  }\n\n  CHECK_CWISE2_IF(true, internal::pcmp_eq, internal::pcmp_eq);\n\n  //Test (-0) == (0) for signed operations\n  for (int i = 0; i < PacketSize; ++i) {\n    data1[i] = Scalar(-0.0);\n    data1[i + PacketSize] = internal::random<bool>() ? data1[i] : Scalar(0);\n  }\n  CHECK_CWISE2_IF(true, internal::pcmp_eq, internal::pcmp_eq);\n\n  //Test NaN\n  for (int i = 0; i < PacketSize; ++i) {\n    data1[i] = NumTraits<Scalar>::quiet_NaN();\n    data1[i + PacketSize] = internal::random<bool>() ? data1[i] : Scalar(0);\n  }\n  CHECK_CWISE2_IF(true, internal::pcmp_eq, internal::pcmp_eq);\n}\n\n// Packet16b representing bool does not support ptrue, pandnot or pcmp_eq, since the scalar path\n// (for some compilers) compute the bitwise and with 0x1 of the results to keep the value in [0,1].\ntemplate<>\nvoid packetmath_boolean_mask_ops<bool, internal::packet_traits<bool>::type>() {}\n\ntemplate <typename Scalar, typename Packet>\nvoid packetmath_minus_zero_add() {\n  const int PacketSize = internal::unpacket_traits<Packet>::size;\n  const int size = 2 * PacketSize;\n  EIGEN_ALIGN_MAX Scalar data1[size];\n  EIGEN_ALIGN_MAX Scalar data2[size];\n  EIGEN_ALIGN_MAX Scalar ref[size];\n\n  for (int i = 0; i < PacketSize; ++i) {\n    data1[i] = Scalar(-0.0);\n    data1[i + PacketSize] = Scalar(-0.0);\n  }\n  CHECK_CWISE2_IF(internal::packet_traits<Scalar>::HasAdd, REF_ADD, internal::padd);\n}\n\n// Ensure optimization barrier compiles and doesn't modify contents.\n// Only applies to raw types, so will not work for std::complex, Eigen::half\n// or Eigen::bfloat16. For those you would need to refer to an underlying\n// storage element.\ntemplate<typename Packet, typename EnableIf = void>\nstruct eigen_optimization_barrier_test {\n  static void run() {}\n};\n\ntemplate<typename Packet>\nstruct eigen_optimization_barrier_test<Packet, typename internal::enable_if<\n    !NumTraits<Packet>::IsComplex &&\n    !internal::is_same<Packet, Eigen::half>::value &&\n    !internal::is_same<Packet, Eigen::bfloat16>::value\n  >::type> {\n  static void run() {\n    typedef typename internal::unpacket_traits<Packet>::type Scalar;\n    Scalar s = internal::random<Scalar>();\n    Packet barrier = internal::pset1<Packet>(s);\n    EIGEN_OPTIMIZATION_BARRIER(barrier);\n    eigen_assert(s == internal::pfirst(barrier) && \"EIGEN_OPTIMIZATION_BARRIER\");\n  }\n};\n\ntemplate <typename Scalar, typename Packet>\nvoid packetmath() {\n  typedef internal::packet_traits<Scalar> PacketTraits;\n  const int PacketSize = internal::unpacket_traits<Packet>::size;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  if (g_first_pass)\n    std::cerr << \"=== Testing packet of type '\" << typeid(Packet).name() << \"' and scalar type '\"\n              << typeid(Scalar).name() << \"' and size '\" << PacketSize << \"' ===\\n\";\n\n  const int max_size = PacketSize > 4 ? PacketSize : 4;\n  const int size = PacketSize * max_size;\n  EIGEN_ALIGN_MAX Scalar data1[size];\n  EIGEN_ALIGN_MAX Scalar data2[size];\n  EIGEN_ALIGN_MAX Scalar data3[size];\n  EIGEN_ALIGN_MAX Scalar ref[size];\n  RealScalar refvalue = RealScalar(0);\n\n  eigen_optimization_barrier_test<Packet>::run();\n  eigen_optimization_barrier_test<Scalar>::run();\n\n  for (int i = 0; i < size; ++i) {\n    data1[i] = internal::random<Scalar>() / RealScalar(PacketSize);\n    data2[i] = internal::random<Scalar>() / RealScalar(PacketSize);\n    refvalue = (std::max)(refvalue, numext::abs(data1[i]));\n  }\n\n  internal::pstore(data2, internal::pload<Packet>(data1));\n  VERIFY(test::areApprox(data1, data2, PacketSize) && \"aligned load/store\");\n\n  for (int offset = 0; offset < PacketSize; ++offset) {\n    internal::pstore(data2, internal::ploadu<Packet>(data1 + offset));\n    VERIFY(test::areApprox(data1 + offset, data2, PacketSize) && \"internal::ploadu\");\n  }\n\n  for (int offset = 0; offset < PacketSize; ++offset) {\n    internal::pstoreu(data2 + offset, internal::pload<Packet>(data1));\n    VERIFY(test::areApprox(data1, data2 + offset, PacketSize) && \"internal::pstoreu\");\n  }\n\n  if (internal::unpacket_traits<Packet>::masked_load_available) {\n    test::packet_helper<internal::unpacket_traits<Packet>::masked_load_available, Packet> h;\n    unsigned long long max_umask = (0x1ull << PacketSize);\n\n    for (int offset = 0; offset < PacketSize; ++offset) {\n      for (unsigned long long umask = 0; umask < max_umask; ++umask) {\n        h.store(data2, h.load(data1 + offset, umask));\n        for (int k = 0; k < PacketSize; ++k) data3[k] = ((umask & (0x1ull << k)) >> k) ? data1[k + offset] : Scalar(0);\n        VERIFY(test::areApprox(data3, data2, PacketSize) && \"internal::ploadu masked\");\n      }\n    }\n  }\n\n  if (internal::unpacket_traits<Packet>::masked_store_available) {\n    test::packet_helper<internal::unpacket_traits<Packet>::masked_store_available, Packet> h;\n    unsigned long long max_umask = (0x1ull << PacketSize);\n\n    for (int offset = 0; offset < PacketSize; ++offset) {\n      for (unsigned long long umask = 0; umask < max_umask; ++umask) {\n        internal::pstore(data2, internal::pset1<Packet>(Scalar(0)));\n        h.store(data2, h.loadu(data1 + offset), umask);\n        for (int k = 0; k < PacketSize; ++k) data3[k] = ((umask & (0x1ull << k)) >> k) ? data1[k + offset] : Scalar(0);\n        VERIFY(test::areApprox(data3, data2, PacketSize) && \"internal::pstoreu masked\");\n      }\n    }\n  }\n\n  VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasAdd);\n  VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasSub);\n  VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasMul);\n\n  CHECK_CWISE2_IF(PacketTraits::HasAdd, REF_ADD, internal::padd);\n  CHECK_CWISE2_IF(PacketTraits::HasSub, REF_SUB, internal::psub);\n  CHECK_CWISE2_IF(PacketTraits::HasMul, REF_MUL, internal::pmul);\n  CHECK_CWISE2_IF(PacketTraits::HasDiv, REF_DIV, internal::pdiv);\n\n  if (PacketTraits::HasNegate) CHECK_CWISE1(internal::negate, internal::pnegate);\n  CHECK_CWISE1(numext::conj, internal::pconj);\n\n  for (int offset = 0; offset < 3; ++offset) {\n    for (int i = 0; i < PacketSize; ++i) ref[i] = data1[offset];\n    internal::pstore(data2, internal::pset1<Packet>(data1[offset]));\n    VERIFY(test::areApprox(ref, data2, PacketSize) && \"internal::pset1\");\n  }\n\n  {\n    for (int i = 0; i < PacketSize * 4; ++i) ref[i] = data1[i / PacketSize];\n    Packet A0, A1, A2, A3;\n    internal::pbroadcast4<Packet>(data1, A0, A1, A2, A3);\n    internal::pstore(data2 + 0 * PacketSize, A0);\n    internal::pstore(data2 + 1 * PacketSize, A1);\n    internal::pstore(data2 + 2 * PacketSize, A2);\n    internal::pstore(data2 + 3 * PacketSize, A3);\n    VERIFY(test::areApprox(ref, data2, 4 * PacketSize) && \"internal::pbroadcast4\");\n  }\n\n  {\n    for (int i = 0; i < PacketSize * 2; ++i) ref[i] = data1[i / PacketSize];\n    Packet A0, A1;\n    internal::pbroadcast2<Packet>(data1, A0, A1);\n    internal::pstore(data2 + 0 * PacketSize, A0);\n    internal::pstore(data2 + 1 * PacketSize, A1);\n    VERIFY(test::areApprox(ref, data2, 2 * PacketSize) && \"internal::pbroadcast2\");\n  }\n\n  VERIFY(internal::isApprox(data1[0], internal::pfirst(internal::pload<Packet>(data1))) && \"internal::pfirst\");\n\n  if (PacketSize > 1) {\n    // apply different offsets to check that ploaddup is robust to unaligned inputs\n    for (int offset = 0; offset < 4; ++offset) {\n      for (int i = 0; i < PacketSize / 2; ++i) ref[2 * i + 0] = ref[2 * i + 1] = data1[offset + i];\n      internal::pstore(data2, internal::ploaddup<Packet>(data1 + offset));\n      VERIFY(test::areApprox(ref, data2, PacketSize) && \"ploaddup\");\n    }\n  }\n\n  if (PacketSize > 2) {\n    // apply different offsets to check that ploadquad is robust to unaligned inputs\n    for (int offset = 0; offset < 4; ++offset) {\n      for (int i = 0; i < PacketSize / 4; ++i)\n        ref[4 * i + 0] = ref[4 * i + 1] = ref[4 * i + 2] = ref[4 * i + 3] = data1[offset + i];\n      internal::pstore(data2, internal::ploadquad<Packet>(data1 + offset));\n      VERIFY(test::areApprox(ref, data2, PacketSize) && \"ploadquad\");\n    }\n  }\n\n  ref[0] = Scalar(0);\n  for (int i = 0; i < PacketSize; ++i) ref[0] += data1[i];\n  VERIFY(test::isApproxAbs(ref[0], internal::predux(internal::pload<Packet>(data1)), refvalue) && \"internal::predux\");\n\n  if (PacketSize == 8 && internal::unpacket_traits<typename internal::unpacket_traits<Packet>::half>::size ==\n                             4)  // so far, predux_half_downto4 is only required in such a case\n  {\n    int HalfPacketSize = PacketSize > 4 ? PacketSize / 2 : PacketSize;\n    for (int i = 0; i < HalfPacketSize; ++i) ref[i] = Scalar(0);\n    for (int i = 0; i < PacketSize; ++i) ref[i % HalfPacketSize] += data1[i];\n    internal::pstore(data2, internal::predux_half_dowto4(internal::pload<Packet>(data1)));\n    VERIFY(test::areApprox(ref, data2, HalfPacketSize) && \"internal::predux_half_dowto4\");\n  }\n\n  ref[0] = Scalar(1);\n  for (int i = 0; i < PacketSize; ++i) ref[0] = REF_MUL(ref[0], data1[i]);\n  VERIFY(internal::isApprox(ref[0], internal::predux_mul(internal::pload<Packet>(data1))) && \"internal::predux_mul\");\n\n  for (int i = 0; i < PacketSize; ++i) ref[i] = data1[PacketSize - i - 1];\n  internal::pstore(data2, internal::preverse(internal::pload<Packet>(data1)));\n  VERIFY(test::areApprox(ref, data2, PacketSize) && \"internal::preverse\");\n\n  internal::PacketBlock<Packet> kernel;\n  for (int i = 0; i < PacketSize; ++i) {\n    kernel.packet[i] = internal::pload<Packet>(data1 + i * PacketSize);\n  }\n  ptranspose(kernel);\n  for (int i = 0; i < PacketSize; ++i) {\n    internal::pstore(data2, kernel.packet[i]);\n    for (int j = 0; j < PacketSize; ++j) {\n      VERIFY(test::isApproxAbs(data2[j], data1[i + j * PacketSize], refvalue) && \"ptranspose\");\n    }\n  }\n\n  if (PacketTraits::HasBlend) {\n    Packet thenPacket = internal::pload<Packet>(data1);\n    Packet elsePacket = internal::pload<Packet>(data2);\n    EIGEN_ALIGN_MAX internal::Selector<PacketSize> selector;\n    for (int i = 0; i < PacketSize; ++i) {\n      selector.select[i] = i;\n    }\n\n    Packet blend = internal::pblend(selector, thenPacket, elsePacket);\n    EIGEN_ALIGN_MAX Scalar result[size];\n    internal::pstore(result, blend);\n    for (int i = 0; i < PacketSize; ++i) {\n      VERIFY(test::isApproxAbs(result[i], (selector.select[i] ? data1[i] : data2[i]), refvalue));\n    }\n  }\n\n  {\n    for (int i = 0; i < PacketSize; ++i) {\n      // \"if\" mask\n      unsigned char v = internal::random<bool>() ? 0xff : 0;\n      char* bytes = (char*)(data1 + i);\n      for (int k = 0; k < int(sizeof(Scalar)); ++k) {\n        bytes[k] = v;\n      }\n      // \"then\" packet\n      data1[i + PacketSize] = internal::random<Scalar>();\n      // \"else\" packet\n      data1[i + 2 * PacketSize] = internal::random<Scalar>();\n    }\n    CHECK_CWISE3_IF(true, internal::pselect, internal::pselect);\n  }\n\n  for (int i = 0; i < size; ++i) {\n    data1[i] = internal::random<Scalar>();\n  }\n  CHECK_CWISE1(internal::pzero, internal::pzero);\n  CHECK_CWISE2_IF(true, internal::por, internal::por);\n  CHECK_CWISE2_IF(true, internal::pxor, internal::pxor);\n  CHECK_CWISE2_IF(true, internal::pand, internal::pand);\n\n  packetmath_boolean_mask_ops<Scalar, Packet>();\n  packetmath_pcast_ops_runner<Scalar, Packet>::run();\n  packetmath_minus_zero_add<Scalar, Packet>();\n\n  for (int i = 0; i < size; ++i) {\n    data1[i] = numext::abs(internal::random<Scalar>());\n  }\n  CHECK_CWISE1_IF(PacketTraits::HasSqrt, numext::sqrt, internal::psqrt);\n  CHECK_CWISE1_IF(PacketTraits::HasRsqrt, numext::rsqrt, internal::prsqrt);\n}\n\n// Notice that this definition works for complex types as well.\n// c++11 has std::log2 for real, but not for complex types.\ntemplate <typename Scalar>\nScalar log2(Scalar x) {\n  return Scalar(EIGEN_LOG2E) * std::log(x);\n}\n\ntemplate <typename Scalar, typename Packet>\nvoid packetmath_real() {\n  typedef internal::packet_traits<Scalar> PacketTraits;\n  const int PacketSize = internal::unpacket_traits<Packet>::size;\n\n  const int size = PacketSize * 4;\n  EIGEN_ALIGN_MAX Scalar data1[PacketSize * 4];\n  EIGEN_ALIGN_MAX Scalar data2[PacketSize * 4];\n  EIGEN_ALIGN_MAX Scalar ref[PacketSize * 4];\n\n  for (int i = 0; i < size; ++i) {\n    data1[i] = Scalar(internal::random<double>(0, 1) * std::pow(10., internal::random<double>(-6, 6)));\n    data2[i] = Scalar(internal::random<double>(0, 1) * std::pow(10., internal::random<double>(-6, 6)));\n  }\n\n  if (internal::random<float>(0, 1) < 0.1f) data1[internal::random<int>(0, PacketSize)] = Scalar(0);\n\n  CHECK_CWISE1_IF(PacketTraits::HasLog, std::log, internal::plog);\n  CHECK_CWISE1_IF(PacketTraits::HasLog, log2, internal::plog2);\n  CHECK_CWISE1_IF(PacketTraits::HasRsqrt, numext::rsqrt, internal::prsqrt);\n\n  for (int i = 0; i < size; ++i) {\n    data1[i] = Scalar(internal::random<double>(-1, 1) * std::pow(10., internal::random<double>(-3, 3)));\n    data2[i] = Scalar(internal::random<double>(-1, 1) * std::pow(10., internal::random<double>(-3, 3)));\n  }\n  CHECK_CWISE1_IF(PacketTraits::HasSin, std::sin, internal::psin);\n  CHECK_CWISE1_IF(PacketTraits::HasCos, std::cos, internal::pcos);\n  CHECK_CWISE1_IF(PacketTraits::HasTan, std::tan, internal::ptan);\n\n  CHECK_CWISE1_EXACT_IF(PacketTraits::HasRound, numext::round, internal::pround);\n  CHECK_CWISE1_EXACT_IF(PacketTraits::HasCeil, numext::ceil, internal::pceil);\n  CHECK_CWISE1_EXACT_IF(PacketTraits::HasFloor, numext::floor, internal::pfloor);\n  CHECK_CWISE1_EXACT_IF(PacketTraits::HasRint, numext::rint, internal::print);\n  \n  // Rounding edge cases.\n  if (PacketTraits::HasRound || PacketTraits::HasCeil || PacketTraits::HasFloor || PacketTraits::HasRint) {\n    typedef typename internal::make_integer<Scalar>::type IntType;\n    // Start with values that cannot fit inside an integer, work down to less than one.\n    Scalar val = numext::mini(\n        Scalar(2) * static_cast<Scalar>(NumTraits<IntType>::highest()),\n        NumTraits<Scalar>::highest());\n    std::vector<Scalar> values;\n    while (val > Scalar(0.25)) {\n      // Cover both even and odd, positive and negative cases.\n      values.push_back(val);\n      values.push_back(val + Scalar(0.3));\n      values.push_back(val + Scalar(0.5));\n      values.push_back(val + Scalar(0.8));\n      values.push_back(val + Scalar(1));\n      values.push_back(val + Scalar(1.3));\n      values.push_back(val + Scalar(1.5));\n      values.push_back(val + Scalar(1.8));\n      values.push_back(-val);\n      values.push_back(-val - Scalar(0.3));\n      values.push_back(-val - Scalar(0.5));\n      values.push_back(-val - Scalar(0.8));\n      values.push_back(-val - Scalar(1));\n      values.push_back(-val - Scalar(1.3));\n      values.push_back(-val - Scalar(1.5));\n      values.push_back(-val - Scalar(1.8));\n      values.push_back(Scalar(-1.5) + val);  // Bug 1785.\n      val = val / Scalar(2);\n    }\n    values.push_back(NumTraits<Scalar>::infinity());\n    values.push_back(-NumTraits<Scalar>::infinity());\n    values.push_back(NumTraits<Scalar>::quiet_NaN());\n    \n    for (size_t k=0; k<values.size(); ++k) {\n      data1[0] = values[k];\n      CHECK_CWISE1_EXACT_IF(PacketTraits::HasRound, numext::round, internal::pround);\n      CHECK_CWISE1_EXACT_IF(PacketTraits::HasCeil, numext::ceil, internal::pceil);\n      CHECK_CWISE1_EXACT_IF(PacketTraits::HasFloor, numext::floor, internal::pfloor);\n      CHECK_CWISE1_EXACT_IF(PacketTraits::HasRint, numext::rint, internal::print);\n    }\n  }\n\n  for (int i = 0; i < size; ++i) {\n    data1[i] = Scalar(internal::random<double>(-1, 1));\n    data2[i] = Scalar(internal::random<double>(-1, 1));\n  }\n  CHECK_CWISE1_IF(PacketTraits::HasASin, std::asin, internal::pasin);\n  CHECK_CWISE1_IF(PacketTraits::HasACos, std::acos, internal::pacos);\n\n  for (int i = 0; i < size; ++i) {\n    data1[i] = Scalar(internal::random<double>(-87, 88));\n    data2[i] = Scalar(internal::random<double>(-87, 88));\n  }\n  CHECK_CWISE1_IF(PacketTraits::HasExp, std::exp, internal::pexp);\n  \n  CHECK_CWISE1_BYREF1_IF(PacketTraits::HasExp, REF_FREXP, internal::pfrexp);\n  if (PacketTraits::HasExp) {\n    // Check denormals:\n    for (int j=0; j<3; ++j) {\n      data1[0] = Scalar(std::ldexp(1, NumTraits<Scalar>::min_exponent()-j));\n      CHECK_CWISE1_BYREF1_IF(PacketTraits::HasExp, REF_FREXP, internal::pfrexp);\n      data1[0] = -data1[0];\n      CHECK_CWISE1_BYREF1_IF(PacketTraits::HasExp, REF_FREXP, internal::pfrexp);\n    }\n    \n    // zero\n    data1[0] = Scalar(0);\n    CHECK_CWISE1_BYREF1_IF(PacketTraits::HasExp, REF_FREXP, internal::pfrexp);\n    \n    // inf and NaN only compare output fraction, not exponent.\n    test::packet_helper<PacketTraits::HasExp,Packet> h;\n    Packet pout;\n    Scalar sout;\n    Scalar special[] = { NumTraits<Scalar>::infinity(), \n                        -NumTraits<Scalar>::infinity(),\n                         NumTraits<Scalar>::quiet_NaN()};\n    for (int i=0; i<3; ++i) {\n      data1[0] = special[i];\n      ref[0] = Scalar(REF_FREXP(data1[0], ref[PacketSize]));\n      h.store(data2, internal::pfrexp(h.load(data1), h.forward_reference(pout, sout)));\n      VERIFY(test::areApprox(ref, data2, 1) && \"internal::pfrexp\");\n    }\n  }\n  \n  for (int i = 0; i < PacketSize; ++i) {\n    data1[i] = Scalar(internal::random<double>(-1, 1));\n    data2[i] = Scalar(internal::random<double>(-1, 1));\n  }\n  for (int i = 0; i < PacketSize; ++i) {\n    data1[i+PacketSize] = Scalar(internal::random<int>(-4, 4));\n    data2[i+PacketSize] = Scalar(internal::random<double>(-4, 4));\n  }\n  CHECK_CWISE2_IF(PacketTraits::HasExp, REF_LDEXP, internal::pldexp);\n  if (PacketTraits::HasExp) {\n    data1[0] = Scalar(-1);\n    // underflow to zero\n    data1[PacketSize] = Scalar(NumTraits<Scalar>::min_exponent()-55);\n    CHECK_CWISE2_IF(PacketTraits::HasExp, REF_LDEXP, internal::pldexp);\n    // overflow to inf\n    data1[PacketSize] = Scalar(NumTraits<Scalar>::max_exponent()+10);\n    CHECK_CWISE2_IF(PacketTraits::HasExp, REF_LDEXP, internal::pldexp);\n    // NaN stays NaN\n    data1[0] = NumTraits<Scalar>::quiet_NaN();\n    CHECK_CWISE2_IF(PacketTraits::HasExp, REF_LDEXP, internal::pldexp);\n    VERIFY((numext::isnan)(data2[0]));\n    // inf stays inf\n    data1[0] = NumTraits<Scalar>::infinity();\n    data1[PacketSize] = Scalar(NumTraits<Scalar>::min_exponent()-10);\n    CHECK_CWISE2_IF(PacketTraits::HasExp, REF_LDEXP, internal::pldexp);\n    // zero stays zero\n    data1[0] = Scalar(0);\n    data1[PacketSize] = Scalar(NumTraits<Scalar>::max_exponent()+10);\n    CHECK_CWISE2_IF(PacketTraits::HasExp, REF_LDEXP, internal::pldexp);\n    // Small number big exponent.\n    data1[0] = Scalar(std::ldexp(Scalar(1.0), NumTraits<Scalar>::min_exponent()-1));\n    data1[PacketSize] = Scalar(-NumTraits<Scalar>::min_exponent()\n                               +NumTraits<Scalar>::max_exponent());\n    CHECK_CWISE2_IF(PacketTraits::HasExp, REF_LDEXP, internal::pldexp);\n    // Big number small exponent.\n    data1[0] = Scalar(std::ldexp(Scalar(1.0), NumTraits<Scalar>::max_exponent()-1));\n    data1[PacketSize] = Scalar(+NumTraits<Scalar>::min_exponent()\n                               -NumTraits<Scalar>::max_exponent());\n    CHECK_CWISE2_IF(PacketTraits::HasExp, REF_LDEXP, internal::pldexp);\n  }\n\n  for (int i = 0; i < size; ++i) {\n    data1[i] = Scalar(internal::random<double>(-1, 1) * std::pow(10., internal::random<double>(-6, 6)));\n    data2[i] = Scalar(internal::random<double>(-1, 1) * std::pow(10., internal::random<double>(-6, 6)));\n  }\n  data1[0] = Scalar(1e-20);\n  CHECK_CWISE1_IF(PacketTraits::HasTanh, std::tanh, internal::ptanh);\n  if (PacketTraits::HasExp && PacketSize >= 2) {\n    const Scalar small = NumTraits<Scalar>::epsilon();\n    data1[0] = NumTraits<Scalar>::quiet_NaN();\n    data1[1] = small;\n    test::packet_helper<PacketTraits::HasExp, Packet> h;\n    h.store(data2, internal::pexp(h.load(data1)));\n    VERIFY((numext::isnan)(data2[0]));\n    // TODO(rmlarsen): Re-enable for bfloat16.\n    if (!internal::is_same<Scalar, bfloat16>::value) {\n      VERIFY_IS_APPROX(std::exp(small), data2[1]);\n    }\n\n    data1[0] = -small;\n    data1[1] = Scalar(0);\n    h.store(data2, internal::pexp(h.load(data1)));\n    // TODO(rmlarsen): Re-enable for bfloat16.\n    if (!internal::is_same<Scalar, bfloat16>::value) {\n      VERIFY_IS_APPROX(std::exp(-small), data2[0]);\n    }\n    VERIFY_IS_EQUAL(std::exp(Scalar(0)), data2[1]);\n\n    data1[0] = (std::numeric_limits<Scalar>::min)();\n    data1[1] = -(std::numeric_limits<Scalar>::min)();\n    h.store(data2, internal::pexp(h.load(data1)));\n    VERIFY_IS_APPROX(std::exp((std::numeric_limits<Scalar>::min)()), data2[0]);\n    VERIFY_IS_APPROX(std::exp(-(std::numeric_limits<Scalar>::min)()), data2[1]);\n\n    data1[0] = std::numeric_limits<Scalar>::denorm_min();\n    data1[1] = -std::numeric_limits<Scalar>::denorm_min();\n    h.store(data2, internal::pexp(h.load(data1)));\n    VERIFY_IS_APPROX(std::exp(std::numeric_limits<Scalar>::denorm_min()), data2[0]);\n    VERIFY_IS_APPROX(std::exp(-std::numeric_limits<Scalar>::denorm_min()), data2[1]);\n  }\n\n  if (PacketTraits::HasTanh) {\n    // NOTE this test migh fail with GCC prior to 6.3, see MathFunctionsImpl.h for details.\n    data1[0] = NumTraits<Scalar>::quiet_NaN();\n    test::packet_helper<internal::packet_traits<Scalar>::HasTanh, Packet> h;\n    h.store(data2, internal::ptanh(h.load(data1)));\n    VERIFY((numext::isnan)(data2[0]));\n  }\n\n  if (PacketTraits::HasExp) {\n    internal::scalar_logistic_op<Scalar> logistic;\n    for (int i = 0; i < size; ++i) {\n      data1[i] = Scalar(internal::random<double>(-20, 20));\n    }\n\n    test::packet_helper<PacketTraits::HasExp, Packet> h;\n    h.store(data2, logistic.packetOp(h.load(data1)));\n    for (int i = 0; i < PacketSize; ++i) {\n      VERIFY_IS_APPROX(data2[i], logistic(data1[i]));\n    }\n  }\n\n#if EIGEN_HAS_C99_MATH && (EIGEN_COMP_CXXVER >= 11)\n  data1[0] = NumTraits<Scalar>::infinity();\n  data1[1] = Scalar(-1);\n  CHECK_CWISE1_IF(PacketTraits::HasLog1p, std::log1p, internal::plog1p);\n  data1[0] = NumTraits<Scalar>::infinity();\n  data1[1] = -NumTraits<Scalar>::infinity();\n  CHECK_CWISE1_IF(PacketTraits::HasExpm1, std::expm1, internal::pexpm1);\n#endif\n\n  if (PacketSize >= 2) {\n    data1[0] = NumTraits<Scalar>::quiet_NaN();\n    data1[1] = NumTraits<Scalar>::epsilon();\n    if (PacketTraits::HasLog) {\n      test::packet_helper<PacketTraits::HasLog, Packet> h;\n      h.store(data2, internal::plog(h.load(data1)));\n      VERIFY((numext::isnan)(data2[0]));\n      // TODO(cantonios): Re-enable for bfloat16.\n      if (!internal::is_same<Scalar, bfloat16>::value) {\n        VERIFY_IS_APPROX(std::log(data1[1]), data2[1]);\n      }\n\n      data1[0] = -NumTraits<Scalar>::epsilon();\n      data1[1] = Scalar(0);\n      h.store(data2, internal::plog(h.load(data1)));\n      VERIFY((numext::isnan)(data2[0]));\n      VERIFY_IS_EQUAL(std::log(Scalar(0)), data2[1]);\n\n      data1[0] = (std::numeric_limits<Scalar>::min)();\n      data1[1] = -(std::numeric_limits<Scalar>::min)();\n      h.store(data2, internal::plog(h.load(data1)));\n      // TODO(cantonios): Re-enable for bfloat16.\n      if (!internal::is_same<Scalar, bfloat16>::value) {\n        VERIFY_IS_APPROX(std::log((std::numeric_limits<Scalar>::min)()), data2[0]);\n      }\n      VERIFY((numext::isnan)(data2[1]));\n\n      // Note: 32-bit arm always flushes denorms to zero.\n#if !EIGEN_ARCH_ARM\n      if (std::numeric_limits<Scalar>::has_denorm == std::denorm_present) {\n        data1[0] = std::numeric_limits<Scalar>::denorm_min();\n        data1[1] = -std::numeric_limits<Scalar>::denorm_min();\n        h.store(data2, internal::plog(h.load(data1)));\n        // TODO(rmlarsen): Reenable.\n        //        VERIFY_IS_EQUAL(std::log(std::numeric_limits<Scalar>::denorm_min()), data2[0]);\n        VERIFY((numext::isnan)(data2[1]));\n      }\n#endif\n\n      data1[0] = Scalar(-1.0f);\n      h.store(data2, internal::plog(h.load(data1)));\n      VERIFY((numext::isnan)(data2[0]));\n\n      data1[0] = NumTraits<Scalar>::infinity();\n      h.store(data2, internal::plog(h.load(data1)));\n      VERIFY((numext::isinf)(data2[0]));\n    }\n    if (PacketTraits::HasLog1p) {\n      test::packet_helper<PacketTraits::HasLog1p, Packet> h;\n      data1[0] = Scalar(-2);\n      data1[1] = -NumTraits<Scalar>::infinity();\n      h.store(data2, internal::plog1p(h.load(data1)));\n      VERIFY((numext::isnan)(data2[0]));\n      VERIFY((numext::isnan)(data2[1]));\n    }\n    if (PacketTraits::HasSqrt) {\n      test::packet_helper<PacketTraits::HasSqrt, Packet> h;\n      data1[0] = Scalar(-1.0f);\n      if (std::numeric_limits<Scalar>::has_denorm == std::denorm_present) {\n        data1[1] = -std::numeric_limits<Scalar>::denorm_min();\n      } else {\n        data1[1] = -NumTraits<Scalar>::epsilon();\n      }\n      h.store(data2, internal::psqrt(h.load(data1)));\n      VERIFY((numext::isnan)(data2[0]));\n      VERIFY((numext::isnan)(data2[1]));\n    }\n    // TODO(rmlarsen): Re-enable for half and bfloat16.\n    if (PacketTraits::HasCos\n        && !internal::is_same<Scalar, half>::value\n        && !internal::is_same<Scalar, bfloat16>::value) {\n      test::packet_helper<PacketTraits::HasCos, Packet> h;\n      for (Scalar k = Scalar(1); k < Scalar(10000) / NumTraits<Scalar>::epsilon(); k *= Scalar(2)) {\n        for (int k1 = 0; k1 <= 1; ++k1) {\n          data1[0] = Scalar((2 * double(k) + k1) * double(EIGEN_PI) / 2 * internal::random<double>(0.8, 1.2));\n          data1[1] = Scalar((2 * double(k) + 2 + k1) * double(EIGEN_PI) / 2 * internal::random<double>(0.8, 1.2));\n          h.store(data2, internal::pcos(h.load(data1)));\n          h.store(data2 + PacketSize, internal::psin(h.load(data1)));\n          VERIFY(data2[0] <= Scalar(1.) && data2[0] >= Scalar(-1.));\n          VERIFY(data2[1] <= Scalar(1.) && data2[1] >= Scalar(-1.));\n          VERIFY(data2[PacketSize + 0] <= Scalar(1.) && data2[PacketSize + 0] >= Scalar(-1.));\n          VERIFY(data2[PacketSize + 1] <= Scalar(1.) && data2[PacketSize + 1] >= Scalar(-1.));\n\n          VERIFY_IS_APPROX(data2[0], std::cos(data1[0]));\n          VERIFY_IS_APPROX(data2[1], std::cos(data1[1]));\n          VERIFY_IS_APPROX(data2[PacketSize + 0], std::sin(data1[0]));\n          VERIFY_IS_APPROX(data2[PacketSize + 1], std::sin(data1[1]));\n\n          VERIFY_IS_APPROX(numext::abs2(data2[0]) + numext::abs2(data2[PacketSize + 0]), Scalar(1));\n          VERIFY_IS_APPROX(numext::abs2(data2[1]) + numext::abs2(data2[PacketSize + 1]), Scalar(1));\n        }\n      }\n\n      data1[0] = NumTraits<Scalar>::infinity();\n      data1[1] = -NumTraits<Scalar>::infinity();\n      h.store(data2, internal::psin(h.load(data1)));\n      VERIFY((numext::isnan)(data2[0]));\n      VERIFY((numext::isnan)(data2[1]));\n\n      h.store(data2, internal::pcos(h.load(data1)));\n      VERIFY((numext::isnan)(data2[0]));\n      VERIFY((numext::isnan)(data2[1]));\n\n      data1[0] = NumTraits<Scalar>::quiet_NaN();\n      h.store(data2, internal::psin(h.load(data1)));\n      VERIFY((numext::isnan)(data2[0]));\n      h.store(data2, internal::pcos(h.load(data1)));\n      VERIFY((numext::isnan)(data2[0]));\n\n      data1[0] = -Scalar(0.);\n      h.store(data2, internal::psin(h.load(data1)));\n      VERIFY(internal::biteq(data2[0], data1[0]));\n      h.store(data2, internal::pcos(h.load(data1)));\n      VERIFY_IS_EQUAL(data2[0], Scalar(1));\n    }\n  }\n}\n\n#define CAST_CHECK_CWISE1_IF(COND, REFOP, POP, SCALAR, REFTYPE) if(COND) { \\\n  test::packet_helper<COND,Packet> h; \\\n  for (int i=0; i<PacketSize; ++i) \\\n    ref[i] = SCALAR(REFOP(static_cast<REFTYPE>(data1[i]))); \\\n  h.store(data2, POP(h.load(data1))); \\\n  VERIFY(test::areApprox(ref, data2, PacketSize) && #POP); \\\n}\n\ntemplate <typename Scalar>\nScalar propagate_nan_max(const Scalar& a, const Scalar& b) {\n  if ((numext::isnan)(a)) return a;\n  if ((numext::isnan)(b)) return b;\n  return (numext::maxi)(a,b);\n}\n\ntemplate <typename Scalar>\nScalar propagate_nan_min(const Scalar& a, const Scalar& b) {\n  if ((numext::isnan)(a)) return a;\n  if ((numext::isnan)(b)) return b;\n  return (numext::mini)(a,b);\n}\n\ntemplate <typename Scalar>\nScalar propagate_number_max(const Scalar& a, const Scalar& b) {\n  if ((numext::isnan)(a)) return b;\n  if ((numext::isnan)(b)) return a;\n  return (numext::maxi)(a,b);\n}\n\ntemplate <typename Scalar>\nScalar propagate_number_min(const Scalar& a, const Scalar& b) {\n  if ((numext::isnan)(a)) return b;\n  if ((numext::isnan)(b)) return a;\n  return (numext::mini)(a,b);\n}\n\ntemplate <typename Scalar, typename Packet>\nvoid packetmath_notcomplex() {\n  typedef internal::packet_traits<Scalar> PacketTraits;\n  const int PacketSize = internal::unpacket_traits<Packet>::size;\n\n  EIGEN_ALIGN_MAX Scalar data1[PacketSize * 4];\n  EIGEN_ALIGN_MAX Scalar data2[PacketSize * 4];\n  EIGEN_ALIGN_MAX Scalar ref[PacketSize * 4];\n\n  Array<Scalar, Dynamic, 1>::Map(data1, PacketSize * 4).setRandom();\n\n  VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasMin);\n  VERIFY((!PacketTraits::Vectorizable) || PacketTraits::HasMax);\n\n  CHECK_CWISE2_IF(PacketTraits::HasMin, (std::min), internal::pmin);\n  CHECK_CWISE2_IF(PacketTraits::HasMax, (std::max), internal::pmax);\n\n  CHECK_CWISE2_IF(PacketTraits::HasMin, propagate_number_min, internal::pmin<PropagateNumbers>);\n  CHECK_CWISE2_IF(PacketTraits::HasMax, propagate_number_max, internal::pmax<PropagateNumbers>);\n  CHECK_CWISE1(numext::abs, internal::pabs);\n  CHECK_CWISE2_IF(PacketTraits::HasAbsDiff, REF_ABS_DIFF, internal::pabsdiff);\n\n  ref[0] = data1[0];\n  for (int i = 0; i < PacketSize; ++i) ref[0] = internal::pmin(ref[0], data1[i]);\n  VERIFY(internal::isApprox(ref[0], internal::predux_min(internal::pload<Packet>(data1))) && \"internal::predux_min\");\n  ref[0] = data1[0];\n  for (int i = 0; i < PacketSize; ++i) ref[0] = internal::pmax(ref[0], data1[i]);\n  VERIFY(internal::isApprox(ref[0], internal::predux_max(internal::pload<Packet>(data1))) && \"internal::predux_max\");\n\n  for (int i = 0; i < PacketSize; ++i) ref[i] = data1[0] + Scalar(i);\n  internal::pstore(data2, internal::plset<Packet>(data1[0]));\n  VERIFY(test::areApprox(ref, data2, PacketSize) && \"internal::plset\");\n\n  {\n    unsigned char* data1_bits = reinterpret_cast<unsigned char*>(data1);\n    // predux_all - not needed yet\n    // for (unsigned int i=0; i<PacketSize*sizeof(Scalar); ++i) data1_bits[i] = 0xff;\n    // VERIFY(internal::predux_all(internal::pload<Packet>(data1)) && \"internal::predux_all(1111)\");\n    // for(int k=0; k<PacketSize; ++k)\n    // {\n    //   for (unsigned int i=0; i<sizeof(Scalar); ++i) data1_bits[k*sizeof(Scalar)+i] = 0x0;\n    //   VERIFY( (!internal::predux_all(internal::pload<Packet>(data1))) && \"internal::predux_all(0101)\");\n    //   for (unsigned int i=0; i<sizeof(Scalar); ++i) data1_bits[k*sizeof(Scalar)+i] = 0xff;\n    // }\n\n    // predux_any\n    for (unsigned int i = 0; i < PacketSize * sizeof(Scalar); ++i) data1_bits[i] = 0x0;\n    VERIFY((!internal::predux_any(internal::pload<Packet>(data1))) && \"internal::predux_any(0000)\");\n    for (int k = 0; k < PacketSize; ++k) {\n      for (unsigned int i = 0; i < sizeof(Scalar); ++i) data1_bits[k * sizeof(Scalar) + i] = 0xff;\n      VERIFY(internal::predux_any(internal::pload<Packet>(data1)) && \"internal::predux_any(0101)\");\n      for (unsigned int i = 0; i < sizeof(Scalar); ++i) data1_bits[k * sizeof(Scalar) + i] = 0x00;\n    }\n  }\n\n\n  // Test NaN propagation.\n  if (!NumTraits<Scalar>::IsInteger) {\n    // Test reductions with no NaNs.\n    ref[0] = data1[0];\n    for (int i = 0; i < PacketSize; ++i) ref[0] = internal::pmin<PropagateNumbers>(ref[0], data1[i]);\n    VERIFY(internal::isApprox(ref[0], internal::predux_min<PropagateNumbers>(internal::pload<Packet>(data1))) && \"internal::predux_min<PropagateNumbers>\");\n    ref[0] = data1[0];\n    for (int i = 0; i < PacketSize; ++i) ref[0] = internal::pmin<PropagateNaN>(ref[0], data1[i]);\n    VERIFY(internal::isApprox(ref[0], internal::predux_min<PropagateNaN>(internal::pload<Packet>(data1))) && \"internal::predux_min<PropagateNaN>\");\n    ref[0] = data1[0];\n    for (int i = 0; i < PacketSize; ++i) ref[0] = internal::pmax<PropagateNumbers>(ref[0], data1[i]);\n    VERIFY(internal::isApprox(ref[0], internal::predux_max<PropagateNumbers>(internal::pload<Packet>(data1))) && \"internal::predux_max<PropagateNumbers>\");\n    ref[0] = data1[0];\n    for (int i = 0; i < PacketSize; ++i) ref[0] = internal::pmax<PropagateNaN>(ref[0], data1[i]);\n    VERIFY(internal::isApprox(ref[0], internal::predux_max<PropagateNaN>(internal::pload<Packet>(data1))) && \"internal::predux_max<PropagateNumbers>\");\n    // A single NaN.\n    const size_t index = std::numeric_limits<size_t>::quiet_NaN() % PacketSize;\n    data1[index] = NumTraits<Scalar>::quiet_NaN();\n    VERIFY(PacketSize==1 || !(numext::isnan)(internal::predux_min<PropagateNumbers>(internal::pload<Packet>(data1))));\n    VERIFY((numext::isnan)(internal::predux_min<PropagateNaN>(internal::pload<Packet>(data1))));\n    VERIFY(PacketSize==1 || !(numext::isnan)(internal::predux_max<PropagateNumbers>(internal::pload<Packet>(data1))));\n    VERIFY((numext::isnan)(internal::predux_max<PropagateNaN>(internal::pload<Packet>(data1))));\n    // All NaNs.\n    for (int i = 0; i < 4 * PacketSize; ++i) data1[i] = NumTraits<Scalar>::quiet_NaN();\n    VERIFY((numext::isnan)(internal::predux_min<PropagateNumbers>(internal::pload<Packet>(data1))));\n    VERIFY((numext::isnan)(internal::predux_min<PropagateNaN>(internal::pload<Packet>(data1))));\n    VERIFY((numext::isnan)(internal::predux_max<PropagateNumbers>(internal::pload<Packet>(data1))));\n    VERIFY((numext::isnan)(internal::predux_max<PropagateNaN>(internal::pload<Packet>(data1))));\n\n    // Test NaN propagation for coefficient-wise min and max.\n    for (int i = 0; i < PacketSize; ++i) {\n      data1[i] = internal::random<bool>() ? NumTraits<Scalar>::quiet_NaN() : Scalar(0);\n      data1[i + PacketSize] = internal::random<bool>() ? NumTraits<Scalar>::quiet_NaN() : Scalar(0);\n    }\n    // Note: NaN propagation is implementation defined for pmin/pmax, so we do not test it here.\n    CHECK_CWISE2_IF(PacketTraits::HasMin, propagate_number_min, (internal::pmin<PropagateNumbers>));\n    CHECK_CWISE2_IF(PacketTraits::HasMax, propagate_number_max, internal::pmax<PropagateNumbers>);\n    CHECK_CWISE2_IF(PacketTraits::HasMin, propagate_nan_min, (internal::pmin<PropagateNaN>));\n    CHECK_CWISE2_IF(PacketTraits::HasMax, propagate_nan_max, internal::pmax<PropagateNaN>);\n  }\n}\n\ntemplate <typename Scalar, typename Packet, bool ConjLhs, bool ConjRhs>\nvoid test_conj_helper(Scalar* data1, Scalar* data2, Scalar* ref, Scalar* pval) {\n  const int PacketSize = internal::unpacket_traits<Packet>::size;\n\n  internal::conj_if<ConjLhs> cj0;\n  internal::conj_if<ConjRhs> cj1;\n  internal::conj_helper<Scalar, Scalar, ConjLhs, ConjRhs> cj;\n  internal::conj_helper<Packet, Packet, ConjLhs, ConjRhs> pcj;\n\n  for (int i = 0; i < PacketSize; ++i) {\n    ref[i] = cj0(data1[i]) * cj1(data2[i]);\n    VERIFY(internal::isApprox(ref[i], cj.pmul(data1[i], data2[i])) && \"conj_helper pmul\");\n  }\n  internal::pstore(pval, pcj.pmul(internal::pload<Packet>(data1), internal::pload<Packet>(data2)));\n  VERIFY(test::areApprox(ref, pval, PacketSize) && \"conj_helper pmul\");\n\n  for (int i = 0; i < PacketSize; ++i) {\n    Scalar tmp = ref[i];\n    ref[i] += cj0(data1[i]) * cj1(data2[i]);\n    VERIFY(internal::isApprox(ref[i], cj.pmadd(data1[i], data2[i], tmp)) && \"conj_helper pmadd\");\n  }\n  internal::pstore(\n      pval, pcj.pmadd(internal::pload<Packet>(data1), internal::pload<Packet>(data2), internal::pload<Packet>(pval)));\n  VERIFY(test::areApprox(ref, pval, PacketSize) && \"conj_helper pmadd\");\n}\n\ntemplate <typename Scalar, typename Packet>\nvoid packetmath_complex() {\n  typedef internal::packet_traits<Scalar> PacketTraits;\n  typedef typename Scalar::value_type RealScalar;\n  const int PacketSize = internal::unpacket_traits<Packet>::size;\n\n  const int size = PacketSize * 4;\n  EIGEN_ALIGN_MAX Scalar data1[PacketSize * 4];\n  EIGEN_ALIGN_MAX Scalar data2[PacketSize * 4];\n  EIGEN_ALIGN_MAX Scalar ref[PacketSize * 4];\n  EIGEN_ALIGN_MAX Scalar pval[PacketSize * 4];\n\n  for (int i = 0; i < size; ++i) {\n    data1[i] = internal::random<Scalar>() * Scalar(1e2);\n    data2[i] = internal::random<Scalar>() * Scalar(1e2);\n  }\n\n  test_conj_helper<Scalar, Packet, false, false>(data1, data2, ref, pval);\n  test_conj_helper<Scalar, Packet, false, true>(data1, data2, ref, pval);\n  test_conj_helper<Scalar, Packet, true, false>(data1, data2, ref, pval);\n  test_conj_helper<Scalar, Packet, true, true>(data1, data2, ref, pval);\n\n  // Test pcplxflip.\n  {\n    for (int i = 0; i < PacketSize; ++i) ref[i] = Scalar(std::imag(data1[i]), std::real(data1[i]));\n    internal::pstore(pval, internal::pcplxflip(internal::pload<Packet>(data1)));\n    VERIFY(test::areApprox(ref, pval, PacketSize) && \"pcplxflip\");\n  }\n\n  if (PacketTraits::HasSqrt) {\n    for (int i = 0; i < size; ++i) {\n      data1[i] = Scalar(internal::random<RealScalar>(), internal::random<RealScalar>());\n    }\n    CHECK_CWISE1_N(numext::sqrt, internal::psqrt, size);\n\n    // Test misc. corner cases.\n    const RealScalar zero = RealScalar(0);\n    const RealScalar one = RealScalar(1);\n    const RealScalar inf = std::numeric_limits<RealScalar>::infinity();\n    const RealScalar nan = std::numeric_limits<RealScalar>::quiet_NaN();\n    data1[0] = Scalar(zero, zero);\n    data1[1] = Scalar(-zero, zero);\n    data1[2] = Scalar(one, zero);\n    data1[3] = Scalar(zero, one);\n    CHECK_CWISE1_N(numext::sqrt, internal::psqrt, 4);\n    data1[0] = Scalar(-one, zero);\n    data1[1] = Scalar(zero, -one);\n    data1[2] = Scalar(one, one);\n    data1[3] = Scalar(-one, -one);\n    CHECK_CWISE1_N(numext::sqrt, internal::psqrt, 4);\n    data1[0] = Scalar(inf, zero);\n    data1[1] = Scalar(zero, inf);\n    data1[2] = Scalar(-inf, zero);\n    data1[3] = Scalar(zero, -inf);\n    CHECK_CWISE1_N(numext::sqrt, internal::psqrt, 4);\n    data1[0] = Scalar(inf, inf);\n    data1[1] = Scalar(-inf, inf);\n    data1[2] = Scalar(inf, -inf);\n    data1[3] = Scalar(-inf, -inf);\n    CHECK_CWISE1_N(numext::sqrt, internal::psqrt, 4);\n    data1[0] = Scalar(nan, zero);\n    data1[1] = Scalar(zero, nan);\n    data1[2] = Scalar(nan, one);\n    data1[3] = Scalar(one, nan);\n    CHECK_CWISE1_N(numext::sqrt, internal::psqrt, 4);\n    data1[0] = Scalar(nan, nan);\n    data1[1] = Scalar(inf, nan);\n    data1[2] = Scalar(nan, inf);\n    data1[3] = Scalar(-inf, nan);\n    CHECK_CWISE1_N(numext::sqrt, internal::psqrt, 4);\n  }\n}\n\ntemplate <typename Scalar, typename Packet>\nvoid packetmath_scatter_gather() {\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  const int PacketSize = internal::unpacket_traits<Packet>::size;\n  EIGEN_ALIGN_MAX Scalar data1[PacketSize];\n  RealScalar refvalue = RealScalar(0);\n  for (int i = 0; i < PacketSize; ++i) {\n    data1[i] = internal::random<Scalar>() / RealScalar(PacketSize);\n  }\n\n  int stride = internal::random<int>(1, 20);\n\n  // Buffer of zeros.\n  EIGEN_ALIGN_MAX Scalar buffer[PacketSize * 20] = {};\n\n  Packet packet = internal::pload<Packet>(data1);\n  internal::pscatter<Scalar, Packet>(buffer, packet, stride);\n\n  for (int i = 0; i < PacketSize * 20; ++i) {\n    if ((i % stride) == 0 && i < stride * PacketSize) {\n      VERIFY(test::isApproxAbs(buffer[i], data1[i / stride], refvalue) && \"pscatter\");\n    } else {\n      VERIFY(test::isApproxAbs(buffer[i], Scalar(0), refvalue) && \"pscatter\");\n    }\n  }\n\n  for (int i = 0; i < PacketSize * 7; ++i) {\n    buffer[i] = internal::random<Scalar>() / RealScalar(PacketSize);\n  }\n  packet = internal::pgather<Scalar, Packet>(buffer, 7);\n  internal::pstore(data1, packet);\n  for (int i = 0; i < PacketSize; ++i) {\n    VERIFY(test::isApproxAbs(data1[i], buffer[i * 7], refvalue) && \"pgather\");\n  }\n}\n\nnamespace Eigen {\nnamespace test {\n\ntemplate <typename Scalar, typename PacketType>\nstruct runall<Scalar, PacketType, false, false> {  // i.e. float or double\n  static void run() {\n    packetmath<Scalar, PacketType>();\n    packetmath_scatter_gather<Scalar, PacketType>();\n    packetmath_notcomplex<Scalar, PacketType>();\n    packetmath_real<Scalar, PacketType>();\n  }\n};\n\ntemplate <typename Scalar, typename PacketType>\nstruct runall<Scalar, PacketType, false, true> {  // i.e. int\n  static void run() {\n    packetmath<Scalar, PacketType>();\n    packetmath_scatter_gather<Scalar, PacketType>();\n    packetmath_notcomplex<Scalar, PacketType>();\n  }\n};\n\ntemplate <typename Scalar, typename PacketType>\nstruct runall<Scalar, PacketType, true, false> {  // i.e. complex\n  static void run() {\n    packetmath<Scalar, PacketType>();\n    packetmath_scatter_gather<Scalar, PacketType>();\n    packetmath_complex<Scalar, PacketType>();\n  }\n};\n\n}  // namespace test\n}  // namespace Eigen\n\nEIGEN_DECLARE_TEST(packetmath) {\n  g_first_pass = true;\n  for (int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(test::runner<float>::run());\n    CALL_SUBTEST_2(test::runner<double>::run());\n    CALL_SUBTEST_3(test::runner<int8_t>::run());\n    CALL_SUBTEST_4(test::runner<uint8_t>::run());\n    CALL_SUBTEST_5(test::runner<int16_t>::run());\n    CALL_SUBTEST_6(test::runner<uint16_t>::run());\n    CALL_SUBTEST_7(test::runner<int32_t>::run());\n    CALL_SUBTEST_8(test::runner<uint32_t>::run());\n    CALL_SUBTEST_9(test::runner<int64_t>::run());\n    CALL_SUBTEST_10(test::runner<uint64_t>::run());\n    CALL_SUBTEST_11(test::runner<std::complex<float> >::run());\n    CALL_SUBTEST_12(test::runner<std::complex<double> >::run());\n    CALL_SUBTEST_13(test::runner<half>::run());\n    CALL_SUBTEST_14((packetmath<bool, internal::packet_traits<bool>::type>()));\n    CALL_SUBTEST_15(test::runner<bfloat16>::run());\n    g_first_pass = false;\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/packetmath_test_shared.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <typeinfo>\n\n#if defined __GNUC__ && __GNUC__>=6\n  #pragma GCC diagnostic ignored \"-Wignored-attributes\"\n#endif\n// using namespace Eigen;\n\nbool g_first_pass = true;\n\nnamespace Eigen {\nnamespace internal {\n\ntemplate<typename T> T negate(const T& x) { return -x; }\n\ntemplate<typename T>\nMap<const Array<unsigned char,sizeof(T),1> >\nbits(const T& x) {\n  return Map<const Array<unsigned char,sizeof(T),1> >(reinterpret_cast<const unsigned char *>(&x));\n}\n\n// The following implement bitwise operations on floating point types\ntemplate<typename T,typename Bits,typename Func>\nT apply_bit_op(Bits a, Bits b, Func f) {\n  Array<unsigned char,sizeof(T),1> data;\n  T res;\n  for(Index i = 0; i < data.size(); ++i)\n    data[i] = f(a[i], b[i]);\n  // Note: The reinterpret_cast works around GCC's class-memaccess warnings:\n  std::memcpy(reinterpret_cast<unsigned char*>(&res), data.data(), sizeof(T));\n  return res;\n}\n\n#define EIGEN_TEST_MAKE_BITWISE2(OP,FUNC,T)             \\\n  template<> T EIGEN_CAT(p,OP)(const T& a,const T& b) { \\\n    return apply_bit_op<T>(bits(a),bits(b),FUNC);     \\\n  }\n\n#define EIGEN_TEST_MAKE_BITWISE(OP,FUNC)                  \\\n  EIGEN_TEST_MAKE_BITWISE2(OP,FUNC,float)                 \\\n  EIGEN_TEST_MAKE_BITWISE2(OP,FUNC,double)                \\\n  EIGEN_TEST_MAKE_BITWISE2(OP,FUNC,half)                  \\\n  EIGEN_TEST_MAKE_BITWISE2(OP,FUNC,bfloat16)              \\\n  EIGEN_TEST_MAKE_BITWISE2(OP,FUNC,std::complex<float>)   \\\n  EIGEN_TEST_MAKE_BITWISE2(OP,FUNC,std::complex<double>)\n\nEIGEN_TEST_MAKE_BITWISE(xor,std::bit_xor<unsigned char>())\nEIGEN_TEST_MAKE_BITWISE(and,std::bit_and<unsigned char>())\nEIGEN_TEST_MAKE_BITWISE(or, std::bit_or<unsigned char>())\nstruct bit_andnot{\n  template<typename T> T\n  operator()(T a, T b) const { return a & (~b); }\n};\nEIGEN_TEST_MAKE_BITWISE(andnot, bit_andnot())\ntemplate<typename T>\nbool biteq(T a, T b) {\n  return (bits(a) == bits(b)).all();\n}\n\n}\n\nnamespace test {\n\n// NOTE: we disable inlining for this function to workaround a GCC issue when using -O3 and the i387 FPU.\ntemplate<typename Scalar> EIGEN_DONT_INLINE\nbool isApproxAbs(const Scalar& a, const Scalar& b, const typename NumTraits<Scalar>::Real& refvalue)\n{\n  return internal::isMuchSmallerThan(a-b, refvalue);\n}\n\ntemplate<typename Scalar>\ninline void print_mismatch(const Scalar* ref, const Scalar* vec, int size) {\n  std::cout << \"ref: [\" << Map<const Matrix<Scalar,1,Dynamic> >(ref,size) << \"]\" << \" != vec: [\" << Map<const Matrix<Scalar,1,Dynamic> >(vec,size) << \"]\\n\";\n}\n\ntemplate<typename Scalar> bool areApproxAbs(const Scalar* a, const Scalar* b, int size, const typename NumTraits<Scalar>::Real& refvalue)\n{\n  for (int i=0; i<size; ++i)\n  {\n    if (!isApproxAbs(a[i],b[i],refvalue))\n    {\n      print_mismatch(a, b, size);\n      return false;\n    }\n  }\n  return true;\n}\n\ntemplate<typename Scalar> bool areApprox(const Scalar* a, const Scalar* b, int size)\n{\n  for (int i=0; i<size; ++i)\n  {\n    if ( a[i]!=b[i] && !internal::isApprox(a[i],b[i]) \n         && !((numext::isnan)(a[i]) && (numext::isnan)(b[i])) )\n    {\n      print_mismatch(a, b, size);\n      return false;\n    }\n  }\n  return true;\n}\n\ntemplate<typename Scalar> bool areEqual(const Scalar* a, const Scalar* b, int size)\n{\n  for (int i=0; i<size; ++i)\n  {\n    if ( (a[i] != b[i]) && !((numext::isnan)(a[i]) && (numext::isnan)(b[i])) )\n    {\n      print_mismatch(a, b, size);\n      return false;\n    }\n  }\n  return true;\n}\n\n#define CHECK_CWISE1(REFOP, POP) { \\\n  for (int i=0; i<PacketSize; ++i) \\\n    ref[i] = REFOP(data1[i]); \\\n  internal::pstore(data2, POP(internal::pload<Packet>(data1))); \\\n  VERIFY(test::areApprox(ref, data2, PacketSize) && #POP); \\\n}\n\n// Checks component-wise for input of size N. All of data1, data2, and ref\n// should have size at least ceil(N/PacketSize)*PacketSize to avoid memory\n// access errors.\n#define CHECK_CWISE1_N(REFOP, POP, N) { \\\n  for (int i=0; i<N; ++i) \\\n    ref[i] = REFOP(data1[i]); \\\n  for (int j=0; j<N; j+=PacketSize) \\\n    internal::pstore(data2 + j, POP(internal::pload<Packet>(data1 + j))); \\\n  VERIFY(test::areApprox(ref, data2, N) && #POP); \\\n}\n\ntemplate<bool Cond,typename Packet>\nstruct packet_helper\n{\n  template<typename T>\n  inline Packet load(const T* from) const { return internal::pload<Packet>(from); }\n\n  template<typename T>\n  inline Packet loadu(const T* from) const { return internal::ploadu<Packet>(from); }\n\n  template<typename T>\n  inline Packet load(const T* from, unsigned long long umask) const { return internal::ploadu<Packet>(from, umask); }\n\n  template<typename T>\n  inline void store(T* to, const Packet& x) const { internal::pstore(to,x); }\n\n  template<typename T>\n  inline void store(T* to, const Packet& x, unsigned long long umask) const { internal::pstoreu(to, x, umask); }\n\n  template<typename T>\n  inline Packet& forward_reference(Packet& packet, T& /*scalar*/) const { return packet; }\n};\n\ntemplate<typename Packet>\nstruct packet_helper<false,Packet>\n{\n  template<typename T>\n  inline T load(const T* from) const { return *from; }\n\n  template<typename T>\n  inline T loadu(const T* from) const { return *from; }\n\n  template<typename T>\n  inline T load(const T* from, unsigned long long) const { return *from; }\n\n  template<typename T>\n  inline void store(T* to, const T& x) const { *to = x; }\n\n  template<typename T>\n  inline void store(T* to, const T& x, unsigned long long) const { *to = x; }\n\n  template<typename T>\n  inline T& forward_reference(Packet& /*packet*/, T& scalar) const { return scalar; }\n};\n\n#define CHECK_CWISE1_IF(COND, REFOP, POP) if(COND) { \\\n  test::packet_helper<COND,Packet> h; \\\n  for (int i=0; i<PacketSize; ++i) \\\n    ref[i] = Scalar(REFOP(data1[i])); \\\n  h.store(data2, POP(h.load(data1))); \\\n  VERIFY(test::areApprox(ref, data2, PacketSize) && #POP); \\\n}\n\n#define CHECK_CWISE1_EXACT_IF(COND, REFOP, POP) if(COND) { \\\n  test::packet_helper<COND,Packet> h; \\\n  for (int i=0; i<PacketSize; ++i) \\\n    ref[i] = Scalar(REFOP(data1[i])); \\\n  h.store(data2, POP(h.load(data1))); \\\n  VERIFY(test::areEqual(ref, data2, PacketSize) && #POP); \\\n}\n\n#define CHECK_CWISE2_IF(COND, REFOP, POP) if(COND) { \\\n  test::packet_helper<COND,Packet> h; \\\n  for (int i=0; i<PacketSize; ++i) \\\n    ref[i] = Scalar(REFOP(data1[i], data1[i+PacketSize]));     \\\n  h.store(data2, POP(h.load(data1),h.load(data1+PacketSize))); \\\n  VERIFY(test::areApprox(ref, data2, PacketSize) && #POP); \\\n}\n\n// One input, one output by reference.\n#define CHECK_CWISE1_BYREF1_IF(COND, REFOP, POP) if(COND) { \\\n  test::packet_helper<COND,Packet> h; \\\n  for (int i=0; i<PacketSize; ++i) \\\n    ref[i] = Scalar(REFOP(data1[i], ref[i+PacketSize]));     \\\n  Packet pout; \\\n  Scalar sout; \\\n  h.store(data2, POP(h.load(data1), h.forward_reference(pout, sout))); \\\n  h.store(data2+PacketSize, h.forward_reference(pout, sout)); \\\n  VERIFY(test::areApprox(ref, data2, 2 * PacketSize) && #POP); \\\n}\n\n#define CHECK_CWISE3_IF(COND, REFOP, POP) if (COND) {                      \\\n  test::packet_helper<COND, Packet> h;                                     \\\n  for (int i = 0; i < PacketSize; ++i)                                     \\\n    ref[i] = Scalar(REFOP(data1[i], data1[i + PacketSize],                 \\\n                          data1[i + 2 * PacketSize]));                     \\\n  h.store(data2, POP(h.load(data1), h.load(data1 + PacketSize),            \\\n                     h.load(data1 + 2 * PacketSize)));                     \\\n  VERIFY(test::areApprox(ref, data2, PacketSize) && #POP);                 \\\n}\n\n// Specialize the runall struct in your test file by defining run().\ntemplate<\n  typename Scalar,\n  typename PacketType,\n  bool IsComplex = NumTraits<Scalar>::IsComplex,\n  bool IsInteger = NumTraits<Scalar>::IsInteger>\nstruct runall;\n\ntemplate<\n  typename Scalar,\n  typename PacketType = typename internal::packet_traits<Scalar>::type,\n  bool Vectorized = internal::packet_traits<Scalar>::Vectorizable,\n  bool HasHalf = !internal::is_same<typename internal::unpacket_traits<PacketType>::half,PacketType>::value >\nstruct runner;\n\ntemplate<typename Scalar,typename PacketType>\nstruct runner<Scalar,PacketType,true,true>\n{\n  static void run() {\n    runall<Scalar,PacketType>::run();\n    runner<Scalar,typename internal::unpacket_traits<PacketType>::half>::run();\n  }\n};\n\ntemplate<typename Scalar,typename PacketType>\nstruct runner<Scalar,PacketType,true,false>\n{\n  static void run() {\n    runall<Scalar,PacketType>::run();\n  }\n};\n\ntemplate<typename Scalar,typename PacketType>\nstruct runner<Scalar,PacketType,false,false>\n{\n  static void run() {\n    runall<Scalar,PacketType>::run();\n  }\n};\n\n}\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/pardiso_support.cpp",
    "content": "/* \n   Intel Copyright (C) ....\n*/\n\n#include \"sparse_solver.h\"\n#include <Eigen/PardisoSupport>\n\ntemplate<typename T> void test_pardiso_T()\n{\n  PardisoLLT < SparseMatrix<T, RowMajor>, Lower> pardiso_llt_lower;\n  PardisoLLT < SparseMatrix<T, RowMajor>, Upper> pardiso_llt_upper;\n  PardisoLDLT < SparseMatrix<T, RowMajor>, Lower> pardiso_ldlt_lower;\n  PardisoLDLT < SparseMatrix<T, RowMajor>, Upper> pardiso_ldlt_upper;\n  PardisoLU  < SparseMatrix<T, RowMajor> > pardiso_lu;\n\n  check_sparse_spd_solving(pardiso_llt_lower);\n  check_sparse_spd_solving(pardiso_llt_upper);\n  check_sparse_spd_solving(pardiso_ldlt_lower);\n  check_sparse_spd_solving(pardiso_ldlt_upper);\n  check_sparse_square_solving(pardiso_lu);\n}\n\nEIGEN_DECLARE_TEST(pardiso_support)\n{\n  CALL_SUBTEST_1(test_pardiso_T<float>());\n  CALL_SUBTEST_2(test_pardiso_T<double>());\n  CALL_SUBTEST_3(test_pardiso_T< std::complex<float> >());\n  CALL_SUBTEST_4(test_pardiso_T< std::complex<double> >());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/pastix_support.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS\n#include \"sparse_solver.h\"\n#include <Eigen/PaStiXSupport>\n#include <unsupported/Eigen/SparseExtra>\n\n\ntemplate<typename T> void test_pastix_T()\n{\n  PastixLLT< SparseMatrix<T, ColMajor>, Eigen::Lower > pastix_llt_lower;\n  PastixLDLT< SparseMatrix<T, ColMajor>, Eigen::Lower > pastix_ldlt_lower;\n  PastixLLT< SparseMatrix<T, ColMajor>, Eigen::Upper > pastix_llt_upper;\n  PastixLDLT< SparseMatrix<T, ColMajor>, Eigen::Upper > pastix_ldlt_upper;\n  PastixLU< SparseMatrix<T, ColMajor> > pastix_lu;\n\n  check_sparse_spd_solving(pastix_llt_lower);\n  check_sparse_spd_solving(pastix_ldlt_lower);\n  check_sparse_spd_solving(pastix_llt_upper);\n  check_sparse_spd_solving(pastix_ldlt_upper);\n  check_sparse_square_solving(pastix_lu);\n\n  // Some compilation check:\n  pastix_llt_lower.iparm();\n  pastix_llt_lower.dparm();\n  pastix_ldlt_lower.iparm();\n  pastix_ldlt_lower.dparm();\n  pastix_lu.iparm();\n  pastix_lu.dparm();\n}\n\n// There is no support for selfadjoint matrices with PaStiX. \n// Complex symmetric matrices should pass though\ntemplate<typename T> void test_pastix_T_LU()\n{\n  PastixLU< SparseMatrix<T, ColMajor> > pastix_lu;\n  check_sparse_square_solving(pastix_lu);\n}\n\nEIGEN_DECLARE_TEST(pastix_support)\n{\n  CALL_SUBTEST_1(test_pastix_T<float>());\n  CALL_SUBTEST_2(test_pastix_T<double>());\n  CALL_SUBTEST_3( (test_pastix_T_LU<std::complex<float> >()) );\n  CALL_SUBTEST_4(test_pastix_T_LU<std::complex<double> >());\n} \n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/permutationmatrices.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define TEST_ENABLE_TEMPORARY_TRACKING\n  \n#include \"main.h\"\n\nusing namespace std;\ntemplate<typename MatrixType> void permutationmatrices(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  enum { Rows = MatrixType::RowsAtCompileTime, Cols = MatrixType::ColsAtCompileTime,\n         Options = MatrixType::Options };\n  typedef PermutationMatrix<Rows> LeftPermutationType;\n  typedef Transpositions<Rows> LeftTranspositionsType;\n  typedef Matrix<int, Rows, 1> LeftPermutationVectorType;\n  typedef Map<LeftPermutationType> MapLeftPerm;\n  typedef PermutationMatrix<Cols> RightPermutationType;\n  typedef Transpositions<Cols> RightTranspositionsType;\n  typedef Matrix<int, Cols, 1> RightPermutationVectorType;\n  typedef Map<RightPermutationType> MapRightPerm;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m_original = MatrixType::Random(rows,cols);\n  LeftPermutationVectorType lv;\n  randomPermutationVector(lv, rows);\n  LeftPermutationType lp(lv);\n  RightPermutationVectorType rv;\n  randomPermutationVector(rv, cols);\n  RightPermutationType rp(rv);\n  LeftTranspositionsType lt(lv);\n  RightTranspositionsType rt(rv);\n  MatrixType m_permuted = MatrixType::Random(rows,cols);\n  \n  VERIFY_EVALUATION_COUNT(m_permuted = lp * m_original * rp, 1); // 1 temp for sub expression \"lp * m_original\"\n\n  for (int i=0; i<rows; i++)\n    for (int j=0; j<cols; j++)\n        VERIFY_IS_APPROX(m_permuted(lv(i),j), m_original(i,rv(j)));\n\n  Matrix<Scalar,Rows,Rows> lm(lp);\n  Matrix<Scalar,Cols,Cols> rm(rp);\n\n  VERIFY_IS_APPROX(m_permuted, lm*m_original*rm);\n  \n  m_permuted = m_original;\n  VERIFY_EVALUATION_COUNT(m_permuted = lp * m_permuted * rp, 1);\n  VERIFY_IS_APPROX(m_permuted, lm*m_original*rm);\n\n  LeftPermutationType lpi;\n  lpi = lp.inverse();\n  VERIFY_IS_APPROX(lpi*m_permuted,lp.inverse()*m_permuted);\n\n  VERIFY_IS_APPROX(lp.inverse()*m_permuted*rp.inverse(), m_original);\n  VERIFY_IS_APPROX(lv.asPermutation().inverse()*m_permuted*rv.asPermutation().inverse(), m_original);\n  VERIFY_IS_APPROX(MapLeftPerm(lv.data(),lv.size()).inverse()*m_permuted*MapRightPerm(rv.data(),rv.size()).inverse(), m_original);\n  \n  VERIFY((lp*lp.inverse()).toDenseMatrix().isIdentity());\n  VERIFY((lv.asPermutation()*lv.asPermutation().inverse()).toDenseMatrix().isIdentity());\n  VERIFY((MapLeftPerm(lv.data(),lv.size())*MapLeftPerm(lv.data(),lv.size()).inverse()).toDenseMatrix().isIdentity());\n\n  LeftPermutationVectorType lv2;\n  randomPermutationVector(lv2, rows);\n  LeftPermutationType lp2(lv2);\n  Matrix<Scalar,Rows,Rows> lm2(lp2);\n  VERIFY_IS_APPROX((lp*lp2).toDenseMatrix().template cast<Scalar>(), lm*lm2);\n  VERIFY_IS_APPROX((lv.asPermutation()*lv2.asPermutation()).toDenseMatrix().template cast<Scalar>(), lm*lm2);\n  VERIFY_IS_APPROX((MapLeftPerm(lv.data(),lv.size())*MapLeftPerm(lv2.data(),lv2.size())).toDenseMatrix().template cast<Scalar>(), lm*lm2);\n\n  LeftPermutationType identityp;\n  identityp.setIdentity(rows);\n  VERIFY_IS_APPROX(m_original, identityp*m_original);\n  \n  // check inplace permutations\n  m_permuted = m_original;\n  VERIFY_EVALUATION_COUNT(m_permuted.noalias()= lp.inverse() * m_permuted, 1); // 1 temp to allocate the mask\n  VERIFY_IS_APPROX(m_permuted, lp.inverse()*m_original);\n  \n  m_permuted = m_original;\n  VERIFY_EVALUATION_COUNT(m_permuted.noalias() = m_permuted * rp.inverse(), 1); // 1 temp to allocate the mask\n  VERIFY_IS_APPROX(m_permuted, m_original*rp.inverse());\n  \n  m_permuted = m_original;\n  VERIFY_EVALUATION_COUNT(m_permuted.noalias() = lp * m_permuted, 1); // 1 temp to allocate the mask\n  VERIFY_IS_APPROX(m_permuted, lp*m_original);\n  \n  m_permuted = m_original;\n  VERIFY_EVALUATION_COUNT(m_permuted.noalias() = m_permuted * rp, 1); // 1 temp to allocate the mask\n  VERIFY_IS_APPROX(m_permuted, m_original*rp);\n\n  if(rows>1 && cols>1)\n  {\n    lp2 = lp;\n    Index i = internal::random<Index>(0, rows-1);\n    Index j;\n    do j = internal::random<Index>(0, rows-1); while(j==i);\n    lp2.applyTranspositionOnTheLeft(i, j);\n    lm = lp;\n    lm.row(i).swap(lm.row(j));\n    VERIFY_IS_APPROX(lm, lp2.toDenseMatrix().template cast<Scalar>());\n\n    RightPermutationType rp2 = rp;\n    i = internal::random<Index>(0, cols-1);\n    do j = internal::random<Index>(0, cols-1); while(j==i);\n    rp2.applyTranspositionOnTheRight(i, j);\n    rm = rp;\n    rm.col(i).swap(rm.col(j));\n    VERIFY_IS_APPROX(rm, rp2.toDenseMatrix().template cast<Scalar>());\n  }\n\n  {\n    // simple compilation check\n    Matrix<Scalar, Cols, Cols> A = rp;\n    Matrix<Scalar, Cols, Cols> B = rp.transpose();\n    VERIFY_IS_APPROX(A, B.transpose());\n  }\n\n  m_permuted = m_original;\n  lp = lt;\n  rp = rt;\n  VERIFY_EVALUATION_COUNT(m_permuted = lt * m_permuted * rt, 1);\n  VERIFY_IS_APPROX(m_permuted, lp*m_original*rp.transpose());\n  \n  VERIFY_IS_APPROX(lt.inverse()*m_permuted*rt.inverse(), m_original);\n\n  // Check inplace transpositions\n  m_permuted = m_original;\n  VERIFY_IS_APPROX(m_permuted = lt * m_permuted, lp * m_original);\n  m_permuted = m_original;\n  VERIFY_IS_APPROX(m_permuted = lt.inverse() * m_permuted, lp.inverse() * m_original);\n  m_permuted = m_original;\n  VERIFY_IS_APPROX(m_permuted = m_permuted * rt, m_original * rt);\n  m_permuted = m_original;\n  VERIFY_IS_APPROX(m_permuted = m_permuted * rt.inverse(), m_original * rt.inverse());\n}\n\ntemplate<typename T>\nvoid bug890()\n{\n  typedef Matrix<T, Dynamic, Dynamic> MatrixType;\n  typedef Matrix<T, Dynamic, 1> VectorType;\n  typedef Stride<Dynamic,Dynamic> S;\n  typedef Map<MatrixType, Aligned, S> MapType;\n  typedef PermutationMatrix<Dynamic> Perm;\n  \n  VectorType v1(2), v2(2), op(4), rhs(2);\n  v1 << 666,667;\n  op << 1,0,0,1;\n  rhs << 42,42;\n  \n  Perm P(2);\n  P.indices() << 1, 0;\n\n  MapType(v1.data(),2,1,S(1,1)) = P * MapType(rhs.data(),2,1,S(1,1));\n  VERIFY_IS_APPROX(v1, (P * rhs).eval());\n\n  MapType(v1.data(),2,1,S(1,1)) = P.inverse() * MapType(rhs.data(),2,1,S(1,1));\n  VERIFY_IS_APPROX(v1, (P.inverse() * rhs).eval());\n}\n\nEIGEN_DECLARE_TEST(permutationmatrices)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( permutationmatrices(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( permutationmatrices(Matrix3f()) );\n    CALL_SUBTEST_3( permutationmatrices(Matrix<double,3,3,RowMajor>()) );\n    CALL_SUBTEST_4( permutationmatrices(Matrix4d()) );\n    CALL_SUBTEST_5( permutationmatrices(Matrix<double,40,60>()) );\n    CALL_SUBTEST_6( permutationmatrices(Matrix<double,Dynamic,Dynamic,RowMajor>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_7( permutationmatrices(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  CALL_SUBTEST_5( bug890<double>() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/prec_inverse_4x4.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/LU>\n#include <algorithm>\n\ntemplate<typename MatrixType> void inverse_permutation_4x4()\n{\n  typedef typename MatrixType::Scalar Scalar;\n  Vector4i indices(0,1,2,3);\n  for(int i = 0; i < 24; ++i)\n  {\n    MatrixType m = PermutationMatrix<4>(indices);\n    MatrixType inv = m.inverse();\n    double error = double( (m*inv-MatrixType::Identity()).norm() / NumTraits<Scalar>::epsilon() );\n    EIGEN_DEBUG_VAR(error)\n    VERIFY(error == 0.0);\n    std::next_permutation(indices.data(),indices.data()+4);\n  }\n}\n\ntemplate<typename MatrixType> void inverse_general_4x4(int repeat)\n{\n  using std::abs;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  double error_sum = 0., error_max = 0.;\n  for(int i = 0; i < repeat; ++i)\n  {\n    MatrixType m;\n    RealScalar absdet;\n    do {\n      m = MatrixType::Random();\n      absdet = abs(m.determinant());\n    } while(absdet < NumTraits<Scalar>::epsilon());\n    MatrixType inv = m.inverse();\n    double error = double( (m*inv-MatrixType::Identity()).norm() * absdet / NumTraits<Scalar>::epsilon() );\n    error_sum += error;\n    error_max = (std::max)(error_max, error);\n  }\n  std::cerr << \"inverse_general_4x4, Scalar = \" << type_name<Scalar>() << std::endl;\n  double error_avg = error_sum / repeat;\n  EIGEN_DEBUG_VAR(error_avg);\n  EIGEN_DEBUG_VAR(error_max);\n   // FIXME that 1.25 used to be a 1.0 until the NumTraits changes on 28 April 2010, what's going wrong??\n   // FIXME that 1.25 used to be 1.2 until we tested gcc 4.1 on 30 June 2010 and got 1.21.\n  VERIFY(error_avg < (NumTraits<Scalar>::IsComplex ? 8.0 : 1.25));\n  VERIFY(error_max < (NumTraits<Scalar>::IsComplex ? 64.0 : 20.0));\n\n  {\n    int s = 5;//internal::random<int>(4,10);\n    int i = 0;//internal::random<int>(0,s-4);\n    int j = 0;//internal::random<int>(0,s-4);\n    Matrix<Scalar,5,5> mat(s,s);\n    mat.setRandom();\n    MatrixType submat = mat.template block<4,4>(i,j);\n    MatrixType mat_inv = mat.template block<4,4>(i,j).inverse();\n    VERIFY_IS_APPROX(mat_inv, submat.inverse());\n    mat.template block<4,4>(i,j) = submat.inverse();\n    VERIFY_IS_APPROX(mat_inv, (mat.template block<4,4>(i,j)));\n  }\n}\n\nEIGEN_DECLARE_TEST(prec_inverse_4x4)\n{\n  CALL_SUBTEST_1((inverse_permutation_4x4<Matrix4f>()));\n  CALL_SUBTEST_1(( inverse_general_4x4<Matrix4f>(200000 * g_repeat) ));\n  CALL_SUBTEST_1(( inverse_general_4x4<Matrix<float,4,4,RowMajor> >(200000 * g_repeat) ));\n\n  CALL_SUBTEST_2((inverse_permutation_4x4<Matrix<double,4,4,RowMajor> >()));\n  CALL_SUBTEST_2(( inverse_general_4x4<Matrix<double,4,4,ColMajor> >(200000 * g_repeat) ));\n  CALL_SUBTEST_2(( inverse_general_4x4<Matrix<double,4,4,RowMajor> >(200000 * g_repeat) ));\n\n  CALL_SUBTEST_3((inverse_permutation_4x4<Matrix4cf>()));\n  CALL_SUBTEST_3((inverse_general_4x4<Matrix4cf>(50000 * g_repeat)));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/product.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/QR>\n\ntemplate<typename Derived1, typename Derived2>\nbool areNotApprox(const MatrixBase<Derived1>& m1, const MatrixBase<Derived2>& m2, typename Derived1::RealScalar epsilon = NumTraits<typename Derived1::RealScalar>::dummy_precision())\n{\n  return !((m1-m2).cwiseAbs2().maxCoeff() < epsilon * epsilon\n                          * (std::max)(m1.cwiseAbs2().maxCoeff(), m2.cwiseAbs2().maxCoeff()));\n}\n\ntemplate<typename MatrixType> void product(const MatrixType& m)\n{\n  /* this test covers the following files:\n     Identity.h Product.h\n  */\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> RowVectorType;\n  typedef Matrix<Scalar, MatrixType::ColsAtCompileTime, 1> ColVectorType;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> RowSquareMatrixType;\n  typedef Matrix<Scalar, MatrixType::ColsAtCompileTime, MatrixType::ColsAtCompileTime> ColSquareMatrixType;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::ColsAtCompileTime,\n                         MatrixType::Flags&RowMajorBit?ColMajor:RowMajor> OtherMajorMatrixType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  // this test relies a lot on Random.h, and there's not much more that we can do\n  // to test it, hence I consider that we will have tested Random.h\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols);\n  RowSquareMatrixType\n             identity = RowSquareMatrixType::Identity(rows, rows),\n             square = RowSquareMatrixType::Random(rows, rows),\n             res = RowSquareMatrixType::Random(rows, rows);\n  ColSquareMatrixType\n             square2 = ColSquareMatrixType::Random(cols, cols),\n             res2 = ColSquareMatrixType::Random(cols, cols);\n  RowVectorType v1 = RowVectorType::Random(rows);\n  ColVectorType vc2 = ColVectorType::Random(cols), vcres(cols);\n  OtherMajorMatrixType tm1 = m1;\n\n  Scalar s1 = internal::random<Scalar>();\n\n  Index r  = internal::random<Index>(0, rows-1),\n        c  = internal::random<Index>(0, cols-1),\n        c2 = internal::random<Index>(0, cols-1);\n\n  // begin testing Product.h: only associativity for now\n  // (we use Transpose.h but this doesn't count as a test for it)\n  VERIFY_IS_APPROX((m1*m1.transpose())*m2,  m1*(m1.transpose()*m2));\n  m3 = m1;\n  m3 *= m1.transpose() * m2;\n  VERIFY_IS_APPROX(m3,                      m1 * (m1.transpose()*m2));\n  VERIFY_IS_APPROX(m3,                      m1 * (m1.transpose()*m2));\n\n  // continue testing Product.h: distributivity\n  VERIFY_IS_APPROX(square*(m1 + m2),        square*m1+square*m2);\n  VERIFY_IS_APPROX(square*(m1 - m2),        square*m1-square*m2);\n\n  // continue testing Product.h: compatibility with ScalarMultiple.h\n  VERIFY_IS_APPROX(s1*(square*m1),          (s1*square)*m1);\n  VERIFY_IS_APPROX(s1*(square*m1),          square*(m1*s1));\n\n  // test Product.h together with Identity.h\n  VERIFY_IS_APPROX(v1,                      identity*v1);\n  VERIFY_IS_APPROX(v1.transpose(),          v1.transpose() * identity);\n  // again, test operator() to check const-qualification\n  VERIFY_IS_APPROX(MatrixType::Identity(rows, cols)(r,c), static_cast<Scalar>(r==c));\n\n  if (rows!=cols)\n     VERIFY_RAISES_ASSERT(m3 = m1*m1);\n\n  // test the previous tests were not screwed up because operator* returns 0\n  // (we use the more accurate default epsilon)\n  if (!NumTraits<Scalar>::IsInteger && (std::min)(rows,cols)>1)\n  {\n    VERIFY(areNotApprox(m1.transpose()*m2,m2.transpose()*m1));\n  }\n\n  // test optimized operator+= path\n  res = square;\n  res.noalias() += m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, square + m1 * m2.transpose());\n  if (!NumTraits<Scalar>::IsInteger && (std::min)(rows,cols)>1)\n  {\n    VERIFY(areNotApprox(res,square + m2 * m1.transpose()));\n  }\n  vcres = vc2;\n  vcres.noalias() += m1.transpose() * v1;\n  VERIFY_IS_APPROX(vcres, vc2 + m1.transpose() * v1);\n\n  // test optimized operator-= path\n  res = square;\n  res.noalias() -= m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, square - (m1 * m2.transpose()));\n  if (!NumTraits<Scalar>::IsInteger && (std::min)(rows,cols)>1)\n  {\n    VERIFY(areNotApprox(res,square - m2 * m1.transpose()));\n  }\n  vcres = vc2;\n  vcres.noalias() -= m1.transpose() * v1;\n  VERIFY_IS_APPROX(vcres, vc2 - m1.transpose() * v1);\n\n  // test scaled products\n  res = square;\n  res.noalias() = s1 * m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, ((s1*m1).eval() * m2.transpose()));\n  res = square;\n  res.noalias() += s1 * m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, square + ((s1*m1).eval() * m2.transpose()));\n  res = square;\n  res.noalias() -= s1 * m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, square - ((s1*m1).eval() * m2.transpose()));\n\n  // test d ?= a+b*c rules\n  res.noalias() = square + m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, square + m1 * m2.transpose());\n  res.noalias() += square + m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, 2*(square + m1 * m2.transpose()));\n  res.noalias() -= square + m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, square + m1 * m2.transpose());\n\n  // test d ?= a-b*c rules\n  res.noalias() = square - m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, square - m1 * m2.transpose());\n  res.noalias() += square - m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, 2*(square - m1 * m2.transpose()));\n  res.noalias() -= square - m1 * m2.transpose();\n  VERIFY_IS_APPROX(res, square - m1 * m2.transpose());\n\n\n  tm1 = m1;\n  VERIFY_IS_APPROX(tm1.transpose() * v1, m1.transpose() * v1);\n  VERIFY_IS_APPROX(v1.transpose() * tm1, v1.transpose() * m1);\n\n  // test submatrix and matrix/vector product\n  for (int i=0; i<rows; ++i)\n    res.row(i) = m1.row(i) * m2.transpose();\n  VERIFY_IS_APPROX(res, m1 * m2.transpose());\n  // the other way round:\n  for (int i=0; i<rows; ++i)\n    res.col(i) = m1 * m2.transpose().col(i);\n  VERIFY_IS_APPROX(res, m1 * m2.transpose());\n\n  res2 = square2;\n  res2.noalias() += m1.transpose() * m2;\n  VERIFY_IS_APPROX(res2, square2 + m1.transpose() * m2);\n  if (!NumTraits<Scalar>::IsInteger && (std::min)(rows,cols)>1)\n  {\n    VERIFY(areNotApprox(res2,square2 + m2.transpose() * m1));\n  }\n\n  VERIFY_IS_APPROX(res.col(r).noalias() = square.adjoint() * square.col(r), (square.adjoint() * square.col(r)).eval());\n  VERIFY_IS_APPROX(res.col(r).noalias() = square * square.col(r), (square * square.col(r)).eval());\n\n  // vector at runtime (see bug 1166)\n  {\n    RowSquareMatrixType ref(square);\n    ColSquareMatrixType ref2(square2);\n    ref = res = square;\n    VERIFY_IS_APPROX(res.block(0,0,1,rows).noalias() = m1.col(0).transpose() * square.transpose(),            (ref.row(0) = m1.col(0).transpose() * square.transpose()));\n    VERIFY_IS_APPROX(res.block(0,0,1,rows).noalias() = m1.block(0,0,rows,1).transpose() * square.transpose(), (ref.row(0) = m1.col(0).transpose() * square.transpose()));\n    VERIFY_IS_APPROX(res.block(0,0,1,rows).noalias() = m1.col(0).transpose() * square,                        (ref.row(0) = m1.col(0).transpose() * square));\n    VERIFY_IS_APPROX(res.block(0,0,1,rows).noalias() = m1.block(0,0,rows,1).transpose() * square,             (ref.row(0) = m1.col(0).transpose() * square));\n    ref2 = res2 = square2;\n    VERIFY_IS_APPROX(res2.block(0,0,1,cols).noalias() = m1.row(0) * square2.transpose(),                      (ref2.row(0) = m1.row(0) * square2.transpose()));\n    VERIFY_IS_APPROX(res2.block(0,0,1,cols).noalias() = m1.block(0,0,1,cols) * square2.transpose(),           (ref2.row(0) = m1.row(0) * square2.transpose()));\n    VERIFY_IS_APPROX(res2.block(0,0,1,cols).noalias() = m1.row(0) * square2,                                  (ref2.row(0) = m1.row(0) * square2));\n    VERIFY_IS_APPROX(res2.block(0,0,1,cols).noalias() = m1.block(0,0,1,cols) * square2,                       (ref2.row(0) = m1.row(0) * square2));\n  }\n\n  // vector.block() (see bug 1283)\n  {\n    RowVectorType w1(rows);\n    VERIFY_IS_APPROX(square * v1.block(0,0,rows,1), square * v1);\n    VERIFY_IS_APPROX(w1.noalias() = square * v1.block(0,0,rows,1), square * v1);\n    VERIFY_IS_APPROX(w1.block(0,0,rows,1).noalias() = square * v1.block(0,0,rows,1), square * v1);\n\n    Matrix<Scalar,1,MatrixType::ColsAtCompileTime> w2(cols);\n    VERIFY_IS_APPROX(vc2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2);\n    VERIFY_IS_APPROX(w2.noalias() = vc2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2);\n    VERIFY_IS_APPROX(w2.block(0,0,1,cols).noalias() = vc2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2);\n\n    vc2 = square2.block(0,0,1,cols).transpose();\n    VERIFY_IS_APPROX(square2.block(0,0,1,cols) * square2, vc2.transpose() * square2);\n    VERIFY_IS_APPROX(w2.noalias() = square2.block(0,0,1,cols) * square2, vc2.transpose() * square2);\n    VERIFY_IS_APPROX(w2.block(0,0,1,cols).noalias() = square2.block(0,0,1,cols) * square2, vc2.transpose() * square2);\n\n    vc2 = square2.block(0,0,cols,1);\n    VERIFY_IS_APPROX(square2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2);\n    VERIFY_IS_APPROX(w2.noalias() = square2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2);\n    VERIFY_IS_APPROX(w2.block(0,0,1,cols).noalias() = square2.block(0,0,cols,1).transpose() * square2, vc2.transpose() * square2);\n  }\n\n  // inner product\n  {\n    Scalar x = square2.row(c) * square2.col(c2);\n    VERIFY_IS_APPROX(x, square2.row(c).transpose().cwiseProduct(square2.col(c2)).sum());\n  }\n\n  // outer product\n  {\n    VERIFY_IS_APPROX(m1.col(c) * m1.row(r), m1.block(0,c,rows,1) * m1.block(r,0,1,cols));\n    VERIFY_IS_APPROX(m1.row(r).transpose() * m1.col(c).transpose(), m1.block(r,0,1,cols).transpose() * m1.block(0,c,rows,1).transpose());\n    VERIFY_IS_APPROX(m1.block(0,c,rows,1) * m1.row(r), m1.block(0,c,rows,1) * m1.block(r,0,1,cols));\n    VERIFY_IS_APPROX(m1.col(c) * m1.block(r,0,1,cols), m1.block(0,c,rows,1) * m1.block(r,0,1,cols));\n    VERIFY_IS_APPROX(m1.leftCols(1) * m1.row(r), m1.block(0,0,rows,1) * m1.block(r,0,1,cols));\n    VERIFY_IS_APPROX(m1.col(c) * m1.topRows(1), m1.block(0,c,rows,1) * m1.block(0,0,1,cols));\n  }\n\n  // Aliasing\n  {\n    ColVectorType x(cols); x.setRandom();\n    ColVectorType z(x);\n    ColVectorType y(cols); y.setZero();\n    ColSquareMatrixType A(cols,cols); A.setRandom();\n    // CwiseBinaryOp\n    VERIFY_IS_APPROX(x = y + A*x, A*z);\n    x = z;\n    VERIFY_IS_APPROX(x = y - A*x, A*(-z));\n    x = z;\n    // CwiseUnaryOp\n    VERIFY_IS_APPROX(x = Scalar(1.)*(A*x), A*z);\n  }\n\n  // regression for blas_trais\n  {\n    VERIFY_IS_APPROX(square * (square*square).transpose(), square * square.transpose() * square.transpose());\n    VERIFY_IS_APPROX(square * (-(square*square)), -square * square * square);\n    VERIFY_IS_APPROX(square * (s1*(square*square)), s1 * square * square * square);\n    VERIFY_IS_APPROX(square * (square*square).conjugate(), square * square.conjugate() * square.conjugate());\n  }\n\n  // destination with a non-default inner-stride\n  // see bug 1741\n  if(!MatrixType::IsRowMajor)\n  {\n    typedef Matrix<Scalar,Dynamic,Dynamic> MatrixX;\n    MatrixX buffer(2*rows,2*rows);\n    Map<RowSquareMatrixType,0,Stride<Dynamic,2> > map1(buffer.data(),rows,rows,Stride<Dynamic,2>(2*rows,2));\n    buffer.setZero();\n    VERIFY_IS_APPROX(map1 = m1 * m2.transpose(), (m1 * m2.transpose()).eval());\n    buffer.setZero();\n    VERIFY_IS_APPROX(map1.noalias() = m1 * m2.transpose(), (m1 * m2.transpose()).eval());\n    buffer.setZero();\n    VERIFY_IS_APPROX(map1.noalias() += m1 * m2.transpose(), (m1 * m2.transpose()).eval());\n  }\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/product_extra.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void product_extra(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, 1, Dynamic> RowVectorType;\n  typedef Matrix<Scalar, Dynamic, 1> ColVectorType;\n  typedef Matrix<Scalar, Dynamic, Dynamic,\n                         MatrixType::Flags&RowMajorBit> OtherMajorMatrixType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols),\n             mzero = MatrixType::Zero(rows, cols),\n             identity = MatrixType::Identity(rows, rows),\n             square = MatrixType::Random(rows, rows),\n             res = MatrixType::Random(rows, rows),\n             square2 = MatrixType::Random(cols, cols),\n             res2 = MatrixType::Random(cols, cols);\n  RowVectorType v1 = RowVectorType::Random(rows), vrres(rows);\n  ColVectorType vc2 = ColVectorType::Random(cols), vcres(cols);\n  OtherMajorMatrixType tm1 = m1;\n\n  Scalar s1 = internal::random<Scalar>(),\n         s2 = internal::random<Scalar>(),\n         s3 = internal::random<Scalar>();\n\n  VERIFY_IS_APPROX(m3.noalias() = m1 * m2.adjoint(),                 m1 * m2.adjoint().eval());\n  VERIFY_IS_APPROX(m3.noalias() = m1.adjoint() * square.adjoint(),   m1.adjoint().eval() * square.adjoint().eval());\n  VERIFY_IS_APPROX(m3.noalias() = m1.adjoint() * m2,                 m1.adjoint().eval() * m2);\n  VERIFY_IS_APPROX(m3.noalias() = (s1 * m1.adjoint()) * m2,          (s1 * m1.adjoint()).eval() * m2);\n  VERIFY_IS_APPROX(m3.noalias() = ((s1 * m1).adjoint()) * m2,        (numext::conj(s1) * m1.adjoint()).eval() * m2);\n  VERIFY_IS_APPROX(m3.noalias() = (- m1.adjoint() * s1) * (s3 * m2), (- m1.adjoint()  * s1).eval() * (s3 * m2).eval());\n  VERIFY_IS_APPROX(m3.noalias() = (s2 * m1.adjoint() * s1) * m2,     (s2 * m1.adjoint()  * s1).eval() * m2);\n  VERIFY_IS_APPROX(m3.noalias() = (-m1*s2) * s1*m2.adjoint(),        (-m1*s2).eval() * (s1*m2.adjoint()).eval());\n\n  // a very tricky case where a scale factor has to be automatically conjugated:\n  VERIFY_IS_APPROX( m1.adjoint() * (s1*m2).conjugate(), (m1.adjoint()).eval() * ((s1*m2).conjugate()).eval());\n\n\n  // test all possible conjugate combinations for the four matrix-vector product cases:\n\n  VERIFY_IS_APPROX((-m1.conjugate() * s2) * (s1 * vc2),\n                   (-m1.conjugate()*s2).eval() * (s1 * vc2).eval());\n  VERIFY_IS_APPROX((-m1 * s2) * (s1 * vc2.conjugate()),\n                   (-m1*s2).eval() * (s1 * vc2.conjugate()).eval());\n  VERIFY_IS_APPROX((-m1.conjugate() * s2) * (s1 * vc2.conjugate()),\n                   (-m1.conjugate()*s2).eval() * (s1 * vc2.conjugate()).eval());\n\n  VERIFY_IS_APPROX((s1 * vc2.transpose()) * (-m1.adjoint() * s2),\n                   (s1 * vc2.transpose()).eval() * (-m1.adjoint()*s2).eval());\n  VERIFY_IS_APPROX((s1 * vc2.adjoint()) * (-m1.transpose() * s2),\n                   (s1 * vc2.adjoint()).eval() * (-m1.transpose()*s2).eval());\n  VERIFY_IS_APPROX((s1 * vc2.adjoint()) * (-m1.adjoint() * s2),\n                   (s1 * vc2.adjoint()).eval() * (-m1.adjoint()*s2).eval());\n\n  VERIFY_IS_APPROX((-m1.adjoint() * s2) * (s1 * v1.transpose()),\n                   (-m1.adjoint()*s2).eval() * (s1 * v1.transpose()).eval());\n  VERIFY_IS_APPROX((-m1.transpose() * s2) * (s1 * v1.adjoint()),\n                   (-m1.transpose()*s2).eval() * (s1 * v1.adjoint()).eval());\n  VERIFY_IS_APPROX((-m1.adjoint() * s2) * (s1 * v1.adjoint()),\n                   (-m1.adjoint()*s2).eval() * (s1 * v1.adjoint()).eval());\n\n  VERIFY_IS_APPROX((s1 * v1) * (-m1.conjugate() * s2),\n                   (s1 * v1).eval() * (-m1.conjugate()*s2).eval());\n  VERIFY_IS_APPROX((s1 * v1.conjugate()) * (-m1 * s2),\n                   (s1 * v1.conjugate()).eval() * (-m1*s2).eval());\n  VERIFY_IS_APPROX((s1 * v1.conjugate()) * (-m1.conjugate() * s2),\n                   (s1 * v1.conjugate()).eval() * (-m1.conjugate()*s2).eval());\n\n  VERIFY_IS_APPROX((-m1.adjoint() * s2) * (s1 * v1.adjoint()),\n                   (-m1.adjoint()*s2).eval() * (s1 * v1.adjoint()).eval());\n\n  // test the vector-matrix product with non aligned starts\n  Index i = internal::random<Index>(0,m1.rows()-2);\n  Index j = internal::random<Index>(0,m1.cols()-2);\n  Index r = internal::random<Index>(1,m1.rows()-i);\n  Index c = internal::random<Index>(1,m1.cols()-j);\n  Index i2 = internal::random<Index>(0,m1.rows()-1);\n  Index j2 = internal::random<Index>(0,m1.cols()-1);\n\n  VERIFY_IS_APPROX(m1.col(j2).adjoint() * m1.block(0,j,m1.rows(),c), m1.col(j2).adjoint().eval() * m1.block(0,j,m1.rows(),c).eval());\n  VERIFY_IS_APPROX(m1.block(i,0,r,m1.cols()) * m1.row(i2).adjoint(), m1.block(i,0,r,m1.cols()).eval() * m1.row(i2).adjoint().eval());\n\n  // test negative strides\n  {\n    Map<MatrixType,Unaligned,Stride<Dynamic,Dynamic> > map1(&m1(rows-1,cols-1), rows, cols, Stride<Dynamic,Dynamic>(-m1.outerStride(),-1));\n    Map<MatrixType,Unaligned,Stride<Dynamic,Dynamic> > map2(&m2(rows-1,cols-1), rows, cols, Stride<Dynamic,Dynamic>(-m2.outerStride(),-1));\n    Map<RowVectorType,Unaligned,InnerStride<-1> > mapv1(&v1(v1.size()-1), v1.size(), InnerStride<-1>(-1));\n    Map<ColVectorType,Unaligned,InnerStride<-1> > mapvc2(&vc2(vc2.size()-1), vc2.size(), InnerStride<-1>(-1));\n    VERIFY_IS_APPROX(MatrixType(map1), m1.reverse());\n    VERIFY_IS_APPROX(MatrixType(map2), m2.reverse());\n    VERIFY_IS_APPROX(m3.noalias() = MatrixType(map1) * MatrixType(map2).adjoint(), m1.reverse() * m2.reverse().adjoint());\n    VERIFY_IS_APPROX(m3.noalias() = map1 * map2.adjoint(), m1.reverse() * m2.reverse().adjoint());\n    VERIFY_IS_APPROX(map1 * vc2, m1.reverse() * vc2);\n    VERIFY_IS_APPROX(m1 * mapvc2, m1 * mapvc2);\n    VERIFY_IS_APPROX(map1.adjoint() * v1.transpose(), m1.adjoint().reverse() * v1.transpose());\n    VERIFY_IS_APPROX(m1.adjoint() * mapv1.transpose(), m1.adjoint() * v1.reverse().transpose());\n  }\n  \n  // regression test\n  MatrixType tmp = m1 * m1.adjoint() * s1;\n  VERIFY_IS_APPROX(tmp, m1 * m1.adjoint() * s1);\n\n  // regression test for bug 1343, assignment to arrays\n  Array<Scalar,Dynamic,1> a1 = m1 * vc2;\n  VERIFY_IS_APPROX(a1.matrix(),m1*vc2);\n  Array<Scalar,Dynamic,1> a2 = s1 * (m1 * vc2);\n  VERIFY_IS_APPROX(a2.matrix(),s1*m1*vc2);\n  Array<Scalar,1,Dynamic> a3 = v1 * m1;\n  VERIFY_IS_APPROX(a3.matrix(),v1*m1);\n  Array<Scalar,Dynamic,Dynamic> a4 = m1 * m2.adjoint();\n  VERIFY_IS_APPROX(a4.matrix(),m1*m2.adjoint());\n}\n\n// Regression test for bug reported at http://forum.kde.org/viewtopic.php?f=74&t=96947\nvoid mat_mat_scalar_scalar_product()\n{\n  Eigen::Matrix2Xd dNdxy(2, 3);\n  dNdxy << -0.5, 0.5, 0,\n           -0.3, 0, 0.3;\n  double det = 6.0, wt = 0.5;\n  VERIFY_IS_APPROX(dNdxy.transpose()*dNdxy*det*wt, det*wt*dNdxy.transpose()*dNdxy);\n}\n\ntemplate <typename MatrixType> \nvoid zero_sized_objects(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  const int PacketSize  = internal::packet_traits<Scalar>::size;\n  const int PacketSize1 = PacketSize>1 ?  PacketSize-1 : 1;\n  Index rows = m.rows();\n  Index cols = m.cols();\n  \n  {\n    MatrixType res, a(rows,0), b(0,cols);\n    VERIFY_IS_APPROX( (res=a*b), MatrixType::Zero(rows,cols) );\n    VERIFY_IS_APPROX( (res=a*a.transpose()), MatrixType::Zero(rows,rows) );\n    VERIFY_IS_APPROX( (res=b.transpose()*b), MatrixType::Zero(cols,cols) );\n    VERIFY_IS_APPROX( (res=b.transpose()*a.transpose()), MatrixType::Zero(cols,rows) );\n  }\n  \n  {\n    MatrixType res, a(rows,cols), b(cols,0);\n    res = a*b;\n    VERIFY(res.rows()==rows && res.cols()==0);\n    b.resize(0,rows);\n    res = b*a;\n    VERIFY(res.rows()==0 && res.cols()==cols);\n  }\n  \n  {\n    Matrix<Scalar,PacketSize,0> a;\n    Matrix<Scalar,0,1> b;\n    Matrix<Scalar,PacketSize,1> res;\n    VERIFY_IS_APPROX( (res=a*b), MatrixType::Zero(PacketSize,1) );\n    VERIFY_IS_APPROX( (res=a.lazyProduct(b)), MatrixType::Zero(PacketSize,1) );\n  }\n  \n  {\n    Matrix<Scalar,PacketSize1,0> a;\n    Matrix<Scalar,0,1> b;\n    Matrix<Scalar,PacketSize1,1> res;\n    VERIFY_IS_APPROX( (res=a*b), MatrixType::Zero(PacketSize1,1) );\n    VERIFY_IS_APPROX( (res=a.lazyProduct(b)), MatrixType::Zero(PacketSize1,1) );\n  }\n  \n  {\n    Matrix<Scalar,PacketSize,Dynamic> a(PacketSize,0);\n    Matrix<Scalar,Dynamic,1> b(0,1);\n    Matrix<Scalar,PacketSize,1> res;\n    VERIFY_IS_APPROX( (res=a*b), MatrixType::Zero(PacketSize,1) );\n    VERIFY_IS_APPROX( (res=a.lazyProduct(b)), MatrixType::Zero(PacketSize,1) );\n  }\n  \n  {\n    Matrix<Scalar,PacketSize1,Dynamic> a(PacketSize1,0);\n    Matrix<Scalar,Dynamic,1> b(0,1);\n    Matrix<Scalar,PacketSize1,1> res;\n    VERIFY_IS_APPROX( (res=a*b), MatrixType::Zero(PacketSize1,1) );\n    VERIFY_IS_APPROX( (res=a.lazyProduct(b)), MatrixType::Zero(PacketSize1,1) );\n  }\n}\n\ntemplate<int>\nvoid bug_127()\n{\n  // Bug 127\n  //\n  // a product of the form lhs*rhs with\n  //\n  // lhs:\n  // rows = 1, cols = 4\n  // RowsAtCompileTime = 1, ColsAtCompileTime = -1\n  // MaxRowsAtCompileTime = 1, MaxColsAtCompileTime = 5\n  //\n  // rhs:\n  // rows = 4, cols = 0\n  // RowsAtCompileTime = -1, ColsAtCompileTime = -1\n  // MaxRowsAtCompileTime = 5, MaxColsAtCompileTime = 1\n  //\n  // was failing on a runtime assertion, because it had been mis-compiled as a dot product because Product.h was using the\n  // max-sizes to detect size 1 indicating vectors, and that didn't account for 0-sized object with max-size 1.\n\n  Matrix<float,1,Dynamic,RowMajor,1,5> a(1,4);\n  Matrix<float,Dynamic,Dynamic,ColMajor,5,1> b(4,0);\n  a*b;\n}\n\ntemplate<int> void bug_817()\n{\n  ArrayXXf B = ArrayXXf::Random(10,10), C;\n  VectorXf x = VectorXf::Random(10);\n  C = (x.transpose()*B.matrix());\n  B = (x.transpose()*B.matrix());\n  VERIFY_IS_APPROX(B,C);\n}\n\ntemplate<int>\nvoid unaligned_objects()\n{\n  // Regression test for the bug reported here:\n  // http://forum.kde.org/viewtopic.php?f=74&t=107541\n  // Recall the matrix*vector kernel avoid unaligned loads by loading two packets and then reassemble then.\n  // There was a mistake in the computation of the valid range for fully unaligned objects: in some rare cases,\n  // memory was read outside the allocated matrix memory. Though the values were not used, this might raise segfault.\n  for(int m=450;m<460;++m)\n  {\n    for(int n=8;n<12;++n)\n    {\n      MatrixXf M(m, n);\n      VectorXf v1(n), r1(500);\n      RowVectorXf v2(m), r2(16);\n\n      M.setRandom();\n      v1.setRandom();\n      v2.setRandom();\n      for(int o=0; o<4; ++o)\n      {\n        r1.segment(o,m).noalias() = M * v1;\n        VERIFY_IS_APPROX(r1.segment(o,m), M * MatrixXf(v1));\n        r2.segment(o,n).noalias() = v2 * M;\n        VERIFY_IS_APPROX(r2.segment(o,n), MatrixXf(v2) * M);\n      }\n    }\n  }\n}\n\ntemplate<typename T>\nEIGEN_DONT_INLINE\nIndex test_compute_block_size(Index m, Index n, Index k)\n{\n  Index mc(m), nc(n), kc(k);\n  internal::computeProductBlockingSizes<T,T>(kc, mc, nc);\n  return kc+mc+nc;\n}\n\ntemplate<typename T>\nIndex compute_block_size()\n{\n  Index ret = 0;\n  ret += test_compute_block_size<T>(0,1,1);\n  ret += test_compute_block_size<T>(1,0,1);\n  ret += test_compute_block_size<T>(1,1,0);\n  ret += test_compute_block_size<T>(0,0,1);\n  ret += test_compute_block_size<T>(0,1,0);\n  ret += test_compute_block_size<T>(1,0,0);\n  ret += test_compute_block_size<T>(0,0,0);\n  return ret;\n}\n\ntemplate<typename>\nvoid aliasing_with_resize()\n{\n  Index m = internal::random<Index>(10,50);\n  Index n = internal::random<Index>(10,50);\n  MatrixXd A, B, C(m,n), D(m,m);\n  VectorXd a, b, c(n);\n  C.setRandom();\n  D.setRandom();\n  c.setRandom();\n  double s = internal::random<double>(1,10);\n\n  A = C;\n  B = A * A.transpose();\n  A = A * A.transpose();\n  VERIFY_IS_APPROX(A,B);\n\n  A = C;\n  B = (A * A.transpose())/s;\n  A = (A * A.transpose())/s;\n  VERIFY_IS_APPROX(A,B);\n\n  A = C;\n  B = (A * A.transpose()) + D;\n  A = (A * A.transpose()) + D;\n  VERIFY_IS_APPROX(A,B);\n\n  A = C;\n  B = D + (A * A.transpose());\n  A = D + (A * A.transpose());\n  VERIFY_IS_APPROX(A,B);\n\n  A = C;\n  B = s * (A * A.transpose());\n  A = s * (A * A.transpose());\n  VERIFY_IS_APPROX(A,B);\n\n  A = C;\n  a = c;\n  b = (A * a)/s;\n  a = (A * a)/s;\n  VERIFY_IS_APPROX(a,b);\n}\n\ntemplate<int>\nvoid bug_1308()\n{\n  int n = 10;\n  MatrixXd r(n,n);\n  VectorXd v = VectorXd::Random(n);\n  r = v * RowVectorXd::Ones(n);\n  VERIFY_IS_APPROX(r, v.rowwise().replicate(n));\n  r = VectorXd::Ones(n) * v.transpose();\n  VERIFY_IS_APPROX(r, v.rowwise().replicate(n).transpose());\n\n  Matrix4d ones44 = Matrix4d::Ones();\n  Matrix4d m44 = Matrix4d::Ones() * Matrix4d::Ones();\n  VERIFY_IS_APPROX(m44,Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(m44.noalias()=ones44*Matrix4d::Ones(), Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(m44.noalias()=ones44.transpose()*Matrix4d::Ones(), Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(m44.noalias()=Matrix4d::Ones()*ones44, Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(m44.noalias()=Matrix4d::Ones()*ones44.transpose(), Matrix4d::Constant(4));\n\n  typedef Matrix<double,4,4,RowMajor> RMatrix4d;\n  RMatrix4d r44 = Matrix4d::Ones() * Matrix4d::Ones();\n  VERIFY_IS_APPROX(r44,Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(r44.noalias()=ones44*Matrix4d::Ones(), Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(r44.noalias()=ones44.transpose()*Matrix4d::Ones(), Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(r44.noalias()=Matrix4d::Ones()*ones44, Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(r44.noalias()=Matrix4d::Ones()*ones44.transpose(), Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(r44.noalias()=ones44*RMatrix4d::Ones(), Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(r44.noalias()=ones44.transpose()*RMatrix4d::Ones(), Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(r44.noalias()=RMatrix4d::Ones()*ones44, Matrix4d::Constant(4));\n  VERIFY_IS_APPROX(r44.noalias()=RMatrix4d::Ones()*ones44.transpose(), Matrix4d::Constant(4));\n\n//   RowVector4d r4;\n  m44.setOnes();\n  r44.setZero();\n  VERIFY_IS_APPROX(r44.noalias() += m44.row(0).transpose() * RowVector4d::Ones(), ones44);\n  r44.setZero();\n  VERIFY_IS_APPROX(r44.noalias() += m44.col(0) * RowVector4d::Ones(), ones44);\n  r44.setZero();\n  VERIFY_IS_APPROX(r44.noalias() += Vector4d::Ones() * m44.row(0), ones44);\n  r44.setZero();\n  VERIFY_IS_APPROX(r44.noalias() += Vector4d::Ones() * m44.col(0).transpose(), ones44);\n}\n\nEIGEN_DECLARE_TEST(product_extra)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( product_extra(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_2( product_extra(MatrixXd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_2( mat_mat_scalar_scalar_product() );\n    CALL_SUBTEST_3( product_extra(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2), internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))) );\n    CALL_SUBTEST_4( product_extra(MatrixXcd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2), internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))) );\n    CALL_SUBTEST_1( zero_sized_objects(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n  CALL_SUBTEST_5( bug_127<0>() );\n  CALL_SUBTEST_5( bug_817<0>() );\n  CALL_SUBTEST_5( bug_1308<0>() );\n  CALL_SUBTEST_6( unaligned_objects<0>() );\n  CALL_SUBTEST_7( compute_block_size<float>() );\n  CALL_SUBTEST_7( compute_block_size<double>() );\n  CALL_SUBTEST_7( compute_block_size<std::complex<double> >() );\n  CALL_SUBTEST_8( aliasing_with_resize<void>() );\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/product_large.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"product.h\"\n#include <Eigen/LU>\n\ntemplate<typename T>\nvoid test_aliasing()\n{\n  int rows = internal::random<int>(1,12);\n  int cols = internal::random<int>(1,12);\n  typedef Matrix<T,Dynamic,Dynamic> MatrixType;\n  typedef Matrix<T,Dynamic,1> VectorType;\n  VectorType x(cols); x.setRandom();\n  VectorType z(x);\n  VectorType y(rows); y.setZero();\n  MatrixType A(rows,cols); A.setRandom();\n  // CwiseBinaryOp\n  VERIFY_IS_APPROX(x = y + A*x, A*z);     // OK because \"y + A*x\" is marked as \"assume-aliasing\"\n  x = z;\n  // CwiseUnaryOp\n  VERIFY_IS_APPROX(x = T(1.)*(A*x), A*z); // OK because 1*(A*x) is replaced by (1*A*x) which is a Product<> expression\n  x = z;\n  // VERIFY_IS_APPROX(x = y-A*x, -A*z);   // Not OK in 3.3 because x is resized before A*x gets evaluated\n  x = z;\n}\n\ntemplate<int>\nvoid product_large_regressions()\n{\n  {\n    // test a specific issue in DiagonalProduct\n    int N = 1000000;\n    VectorXf v = VectorXf::Ones(N);\n    MatrixXf m = MatrixXf::Ones(N,3);\n    m = (v+v).asDiagonal() * m;\n    VERIFY_IS_APPROX(m, MatrixXf::Constant(N,3,2));\n  }\n\n  {\n    // test deferred resizing in Matrix::operator=\n    MatrixXf a = MatrixXf::Random(10,4), b = MatrixXf::Random(4,10), c = a;\n    VERIFY_IS_APPROX((a = a * b), (c * b).eval());\n  }\n\n  {\n    // check the functions to setup blocking sizes compile and do not segfault\n    // FIXME check they do what they are supposed to do !!\n    std::ptrdiff_t l1 = internal::random<int>(10000,20000);\n    std::ptrdiff_t l2 = internal::random<int>(100000,200000);\n    std::ptrdiff_t l3 = internal::random<int>(1000000,2000000);\n    setCpuCacheSizes(l1,l2,l3);\n    VERIFY(l1==l1CacheSize());\n    VERIFY(l2==l2CacheSize());\n    std::ptrdiff_t k1 = internal::random<int>(10,100)*16;\n    std::ptrdiff_t m1 = internal::random<int>(10,100)*16;\n    std::ptrdiff_t n1 = internal::random<int>(10,100)*16;\n    // only makes sure it compiles fine\n    internal::computeProductBlockingSizes<float,float,std::ptrdiff_t>(k1,m1,n1,1);\n  }\n\n  {\n    // test regression in row-vector by matrix (bad Map type)\n    MatrixXf mat1(10,32); mat1.setRandom();\n    MatrixXf mat2(32,32); mat2.setRandom();\n    MatrixXf r1 = mat1.row(2)*mat2.transpose();\n    VERIFY_IS_APPROX(r1, (mat1.row(2)*mat2.transpose()).eval());\n\n    MatrixXf r2 = mat1.row(2)*mat2;\n    VERIFY_IS_APPROX(r2, (mat1.row(2)*mat2).eval());\n  }\n\n  {\n    Eigen::MatrixXd A(10,10), B, C;\n    A.setRandom();\n    C = A;\n    for(int k=0; k<79; ++k)\n      C = C * A;\n    B.noalias() = (((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)) * ((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)))\n                * (((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)) * ((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)));\n    VERIFY_IS_APPROX(B,C);\n  }\n}\n\ntemplate<int>\nvoid bug_1622() {\n  typedef Matrix<double, 2, -1, 0, 2, -1> Mat2X;\n  Mat2X x(2,2); x.setRandom();\n  MatrixXd y(2,2); y.setRandom();\n  const Mat2X K1 = x * y.inverse();\n  const Matrix2d K2 = x * y.inverse();\n  VERIFY_IS_APPROX(K1,K2);\n}\n\nEIGEN_DECLARE_TEST(product_large)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( product(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_2( product(MatrixXd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_2( product(MatrixXd(internal::random<int>(1,10), internal::random<int>(1,10))) );\n\n    CALL_SUBTEST_3( product(MatrixXi(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n    CALL_SUBTEST_4( product(MatrixXcf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2), internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))) );\n    CALL_SUBTEST_5( product(Matrix<float,Dynamic,Dynamic,RowMajor>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n\n    CALL_SUBTEST_1( test_aliasing<float>() );\n\n    CALL_SUBTEST_6( bug_1622<1>() );\n  }\n\n  CALL_SUBTEST_6( product_large_regressions<0>() );\n\n  // Regression test for bug 714:\n#if defined EIGEN_HAS_OPENMP\n  omp_set_dynamic(1);\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_6( product(Matrix<float,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  }\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/product_mmtr.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010-2017 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#define CHECK_MMTR(DEST, TRI, OP) {                   \\\n    ref3 = DEST;                                      \\\n    ref2 = ref1 = DEST;                               \\\n    DEST.template triangularView<TRI>() OP;           \\\n    ref1 OP;                                          \\\n    ref2.template triangularView<TRI>()               \\\n      = ref1.template triangularView<TRI>();          \\\n    VERIFY_IS_APPROX(DEST,ref2);                      \\\n    \\\n    DEST = ref3;                                      \\\n    ref3 = ref2;                                      \\\n    ref3.diagonal() = DEST.diagonal();                \\\n    DEST.template triangularView<TRI|ZeroDiag>() OP;  \\\n    VERIFY_IS_APPROX(DEST,ref3);                      \\\n  }\n\ntemplate<typename Scalar> void mmtr(int size)\n{\n  typedef Matrix<Scalar,Dynamic,Dynamic,ColMajor> MatrixColMaj;\n  typedef Matrix<Scalar,Dynamic,Dynamic,RowMajor> MatrixRowMaj;\n\n  DenseIndex othersize = internal::random<DenseIndex>(1,200);\n  \n  MatrixColMaj matc = MatrixColMaj::Zero(size, size);\n  MatrixRowMaj matr = MatrixRowMaj::Zero(size, size);\n  MatrixColMaj ref1(size, size), ref2(size, size), ref3(size,size);\n  \n  MatrixColMaj soc(size,othersize); soc.setRandom();\n  MatrixColMaj osc(othersize,size); osc.setRandom();\n  MatrixRowMaj sor(size,othersize); sor.setRandom();\n  MatrixRowMaj osr(othersize,size); osr.setRandom();\n  MatrixColMaj sqc(size,size); sqc.setRandom();\n  MatrixRowMaj sqr(size,size); sqr.setRandom();\n  \n  Scalar s = internal::random<Scalar>();\n  \n  CHECK_MMTR(matc, Lower, = s*soc*sor.adjoint());\n  CHECK_MMTR(matc, Upper, = s*(soc*soc.adjoint()));\n  CHECK_MMTR(matr, Lower, = s*soc*soc.adjoint());\n  CHECK_MMTR(matr, Upper, = soc*(s*sor.adjoint()));\n  \n  CHECK_MMTR(matc, Lower, += s*soc*soc.adjoint());\n  CHECK_MMTR(matc, Upper, += s*(soc*sor.transpose()));\n  CHECK_MMTR(matr, Lower, += s*sor*soc.adjoint());\n  CHECK_MMTR(matr, Upper, += soc*(s*soc.adjoint()));\n  \n  CHECK_MMTR(matc, Lower, -= s*soc*soc.adjoint());\n  CHECK_MMTR(matc, Upper, -= s*(osc.transpose()*osc.conjugate()));\n  CHECK_MMTR(matr, Lower, -= s*soc*soc.adjoint());\n  CHECK_MMTR(matr, Upper, -= soc*(s*soc.adjoint()));\n  \n  CHECK_MMTR(matc, Lower, -= s*sqr*sqc.template triangularView<Upper>());\n  CHECK_MMTR(matc, Upper, = s*sqc*sqr.template triangularView<Upper>());\n  CHECK_MMTR(matc, Lower, += s*sqr*sqc.template triangularView<Lower>());\n  CHECK_MMTR(matc, Upper, = s*sqc*sqc.template triangularView<Lower>());\n  \n  CHECK_MMTR(matc, Lower, = (s*sqr).template triangularView<Upper>()*sqc);\n  CHECK_MMTR(matc, Upper, -= (s*sqc).template triangularView<Upper>()*sqc);\n  CHECK_MMTR(matc, Lower, = (s*sqr).template triangularView<Lower>()*sqc);\n  CHECK_MMTR(matc, Upper, += (s*sqc).template triangularView<Lower>()*sqc);\n\n  // check aliasing\n  ref2 = ref1 = matc;\n  ref1 = sqc.adjoint() * matc * sqc;\n  ref2.template triangularView<Upper>() = ref1.template triangularView<Upper>();\n  matc.template triangularView<Upper>() = sqc.adjoint() * matc * sqc;\n  VERIFY_IS_APPROX(matc, ref2);\n\n  ref2 = ref1 = matc;\n  ref1 = sqc * matc * sqc.adjoint();\n  ref2.template triangularView<Lower>() = ref1.template triangularView<Lower>();\n  matc.template triangularView<Lower>() = sqc * matc * sqc.adjoint();\n  VERIFY_IS_APPROX(matc, ref2);\n\n  // destination with a non-default inner-stride\n  // see bug 1741\n  {\n    typedef Matrix<Scalar,Dynamic,Dynamic> MatrixX;\n    MatrixX buffer(2*size,2*size);\n    Map<MatrixColMaj,0,Stride<Dynamic,Dynamic> > map1(buffer.data(),size,size,Stride<Dynamic,Dynamic>(2*size,2));\n    buffer.setZero();\n    CHECK_MMTR(map1, Lower, = s*soc*sor.adjoint());\n  }\n}\n\nEIGEN_DECLARE_TEST(product_mmtr)\n{\n  for(int i = 0; i < g_repeat ; i++)\n  {\n    CALL_SUBTEST_1((mmtr<float>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_2((mmtr<double>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_3((mmtr<std::complex<float> >(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))));\n    CALL_SUBTEST_4((mmtr<std::complex<double> >(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/product_notemporary.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define TEST_ENABLE_TEMPORARY_TRACKING\n\n#include \"main.h\"\n\ntemplate<typename Dst, typename Lhs, typename Rhs>\nvoid check_scalar_multiple3(Dst &dst, const Lhs& A, const Rhs& B)\n{\n  VERIFY_EVALUATION_COUNT( (dst.noalias()  = A * B), 0);\n  VERIFY_IS_APPROX( dst, (A.eval() * B.eval()).eval() );\n  VERIFY_EVALUATION_COUNT( (dst.noalias() += A * B), 0);\n  VERIFY_IS_APPROX( dst, 2*(A.eval() * B.eval()).eval() );\n  VERIFY_EVALUATION_COUNT( (dst.noalias() -= A * B), 0);\n  VERIFY_IS_APPROX( dst, (A.eval() * B.eval()).eval() );\n}\n\ntemplate<typename Dst, typename Lhs, typename Rhs, typename S2>\nvoid check_scalar_multiple2(Dst &dst, const Lhs& A, const Rhs& B, S2 s2)\n{\n  CALL_SUBTEST( check_scalar_multiple3(dst, A,    B) );\n  CALL_SUBTEST( check_scalar_multiple3(dst, A,   -B) );\n  CALL_SUBTEST( check_scalar_multiple3(dst, A, s2*B) );\n  CALL_SUBTEST( check_scalar_multiple3(dst, A, B*s2) );\n  CALL_SUBTEST( check_scalar_multiple3(dst, A, (B*s2).conjugate()) );\n}\n\ntemplate<typename Dst, typename Lhs, typename Rhs, typename S1, typename S2>\nvoid check_scalar_multiple1(Dst &dst, const Lhs& A, const Rhs& B, S1 s1, S2 s2)\n{\n  CALL_SUBTEST( check_scalar_multiple2(dst,    A, B, s2) );\n  CALL_SUBTEST( check_scalar_multiple2(dst,   -A, B, s2) );\n  CALL_SUBTEST( check_scalar_multiple2(dst, s1*A, B, s2) );\n  CALL_SUBTEST( check_scalar_multiple2(dst, A*s1, B, s2) );\n  CALL_SUBTEST( check_scalar_multiple2(dst, (A*s1).conjugate(), B, s2) );\n}\n\ntemplate<typename MatrixType> void product_notemporary(const MatrixType& m)\n{\n  /* This test checks the number of temporaries created\n   * during the evaluation of a complex expression */\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef Matrix<Scalar, 1, Dynamic> RowVectorType;\n  typedef Matrix<Scalar, Dynamic, 1> ColVectorType;\n  typedef Matrix<Scalar, Dynamic, Dynamic, ColMajor> ColMajorMatrixType;\n  typedef Matrix<Scalar, Dynamic, Dynamic, RowMajor> RowMajorMatrixType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  ColMajorMatrixType m1 = MatrixType::Random(rows, cols),\n                     m2 = MatrixType::Random(rows, cols),\n                     m3(rows, cols);\n  RowVectorType rv1 = RowVectorType::Random(rows), rvres(rows);\n  ColVectorType cv1 = ColVectorType::Random(cols), cvres(cols);\n  RowMajorMatrixType rm3(rows, cols);\n\n  Scalar s1 = internal::random<Scalar>(),\n         s2 = internal::random<Scalar>(),\n         s3 = internal::random<Scalar>();\n\n  Index c0 = internal::random<Index>(4,cols-8),\n        c1 = internal::random<Index>(8,cols-c0),\n        r0 = internal::random<Index>(4,cols-8),\n        r1 = internal::random<Index>(8,rows-r0);\n\n  VERIFY_EVALUATION_COUNT( m3 = (m1 * m2.adjoint()), 1);\n  VERIFY_EVALUATION_COUNT( m3 = (m1 * m2.adjoint()).transpose(), 1);\n  VERIFY_EVALUATION_COUNT( m3.noalias() = m1 * m2.adjoint(), 0);\n\n  VERIFY_EVALUATION_COUNT( m3 = s1 * (m1 * m2.transpose()), 1);\n//   VERIFY_EVALUATION_COUNT( m3 = m3 + s1 * (m1 * m2.transpose()), 1);\n  VERIFY_EVALUATION_COUNT( m3.noalias() = s1 * (m1 * m2.transpose()), 0);\n\n  VERIFY_EVALUATION_COUNT( m3 = m3 + (m1 * m2.adjoint()), 1);\n  VERIFY_EVALUATION_COUNT( m3 = m3 - (m1 * m2.adjoint()), 1);\n\n  VERIFY_EVALUATION_COUNT( m3 = m3 + (m1 * m2.adjoint()).transpose(), 1);\n  VERIFY_EVALUATION_COUNT( m3.noalias() = m3 + m1 * m2.transpose(), 0);\n  VERIFY_EVALUATION_COUNT( m3.noalias() += m3 + m1 * m2.transpose(), 0);\n  VERIFY_EVALUATION_COUNT( m3.noalias() -= m3 + m1 * m2.transpose(), 0);\n  VERIFY_EVALUATION_COUNT( m3.noalias() =  m3 - m1 * m2.transpose(), 0);\n  VERIFY_EVALUATION_COUNT( m3.noalias() += m3 - m1 * m2.transpose(), 0);\n  VERIFY_EVALUATION_COUNT( m3.noalias() -= m3 - m1 * m2.transpose(), 0);\n\n  VERIFY_EVALUATION_COUNT( m3.noalias() = s1 * m1 * s2 * m2.adjoint(), 0);\n  VERIFY_EVALUATION_COUNT( m3.noalias() = s1 * m1 * s2 * (m1*s3+m2*s2).adjoint(), 1);\n  VERIFY_EVALUATION_COUNT( m3.noalias() = (s1 * m1).adjoint() * s2 * m2, 0);\n  VERIFY_EVALUATION_COUNT( m3.noalias() += s1 * (-m1*s3).adjoint() * (s2 * m2 * s3), 0);\n  VERIFY_EVALUATION_COUNT( m3.noalias() -= s1 * (m1.transpose() * m2), 0);\n\n  VERIFY_EVALUATION_COUNT(( m3.block(r0,r0,r1,r1).noalias() += -m1.block(r0,c0,r1,c1) * (s2*m2.block(r0,c0,r1,c1)).adjoint() ), 0);\n  VERIFY_EVALUATION_COUNT(( m3.block(r0,r0,r1,r1).noalias() -= s1 * m1.block(r0,c0,r1,c1) * m2.block(c0,r0,c1,r1) ), 0);\n\n  // NOTE this is because the Block expression is not handled yet by our expression analyser\n  VERIFY_EVALUATION_COUNT(( m3.block(r0,r0,r1,r1).noalias() = s1 * m1.block(r0,c0,r1,c1) * (s1*m2).block(c0,r0,c1,r1) ), 1);\n\n  VERIFY_EVALUATION_COUNT( m3.noalias() -= (s1 * m1).template triangularView<Lower>() * m2, 0);\n  VERIFY_EVALUATION_COUNT( rm3.noalias() = (s1 * m1.adjoint()).template triangularView<Upper>() * (m2+m2), 1);\n  VERIFY_EVALUATION_COUNT( rm3.noalias() = (s1 * m1.adjoint()).template triangularView<UnitUpper>() * m2.adjoint(), 0);\n\n  VERIFY_EVALUATION_COUNT( m3.template triangularView<Upper>() = (m1 * m2.adjoint()), 0);\n  VERIFY_EVALUATION_COUNT( m3.template triangularView<Upper>() -= (m1 * m2.adjoint()), 0);\n\n  // NOTE this is because the blas_traits require innerstride==1 to avoid a temporary, but that doesn't seem to be actually needed for the triangular products\n  VERIFY_EVALUATION_COUNT( rm3.col(c0).noalias() = (s1 * m1.adjoint()).template triangularView<UnitUpper>() * (s2*m2.row(c0)).adjoint(), 1);\n\n  VERIFY_EVALUATION_COUNT( m1.template triangularView<Lower>().solveInPlace(m3), 0);\n  VERIFY_EVALUATION_COUNT( m1.adjoint().template triangularView<Lower>().solveInPlace(m3.transpose()), 0);\n\n  VERIFY_EVALUATION_COUNT( m3.noalias() -= (s1 * m1).adjoint().template selfadjointView<Lower>() * (-m2*s3).adjoint(), 0);\n  VERIFY_EVALUATION_COUNT( m3.noalias() = s2 * m2.adjoint() * (s1 * m1.adjoint()).template selfadjointView<Upper>(), 0);\n  VERIFY_EVALUATION_COUNT( rm3.noalias() = (s1 * m1.adjoint()).template selfadjointView<Lower>() * m2.adjoint(), 0);\n\n  // NOTE this is because the blas_traits require innerstride==1 to avoid a temporary, but that doesn't seem to be actually needed for the triangular products\n  VERIFY_EVALUATION_COUNT( m3.col(c0).noalias() = (s1 * m1).adjoint().template selfadjointView<Lower>() * (-m2.row(c0)*s3).adjoint(), 1);\n  VERIFY_EVALUATION_COUNT( m3.col(c0).noalias() -= (s1 * m1).adjoint().template selfadjointView<Upper>() * (-m2.row(c0)*s3).adjoint(), 1);\n\n  VERIFY_EVALUATION_COUNT( m3.block(r0,c0,r1,c1).noalias() += m1.block(r0,r0,r1,r1).template selfadjointView<Upper>() * (s1*m2.block(r0,c0,r1,c1)), 0);\n  VERIFY_EVALUATION_COUNT( m3.block(r0,c0,r1,c1).noalias() = m1.block(r0,r0,r1,r1).template selfadjointView<Upper>() * m2.block(r0,c0,r1,c1), 0);\n\n  VERIFY_EVALUATION_COUNT( m3.template selfadjointView<Lower>().rankUpdate(m2.adjoint()), 0);\n\n  // Here we will get 1 temporary for each resize operation of the lhs operator; resize(r1,c1) would lead to zero temporaries\n  m3.resize(1,1);\n  VERIFY_EVALUATION_COUNT( m3.noalias() = m1.block(r0,r0,r1,r1).template selfadjointView<Lower>() * m2.block(r0,c0,r1,c1), 1);\n  m3.resize(1,1);\n  VERIFY_EVALUATION_COUNT( m3.noalias() = m1.block(r0,r0,r1,r1).template triangularView<UnitUpper>()  * m2.block(r0,c0,r1,c1), 1);\n\n  // Zero temporaries for lazy products ...\n  m3.setRandom(rows,cols);\n  VERIFY_EVALUATION_COUNT( Scalar tmp = 0; tmp += Scalar(RealScalar(1)) /  (m3.transpose().lazyProduct(m3)).diagonal().sum(), 0 );\n  VERIFY_EVALUATION_COUNT( m3.noalias() = m1.conjugate().lazyProduct(m2.conjugate()), 0);\n\n  // ... and even no temporary for even deeply (>=2) nested products\n  VERIFY_EVALUATION_COUNT( Scalar tmp = 0; tmp += Scalar(RealScalar(1)) /  (m3.transpose() * m3).diagonal().sum(), 0 );\n  VERIFY_EVALUATION_COUNT( Scalar tmp = 0; tmp += Scalar(RealScalar(1)) /  (m3.transpose() * m3).diagonal().array().abs().sum(), 0 );\n\n  // Zero temporaries for ... CoeffBasedProductMode\n  VERIFY_EVALUATION_COUNT( m3.col(0).template head<5>() * m3.col(0).transpose() + m3.col(0).template head<5>() * m3.col(0).transpose(), 0 );\n\n  // Check matrix * vectors\n  VERIFY_EVALUATION_COUNT( cvres.noalias() = m1 * cv1, 0 );\n  VERIFY_EVALUATION_COUNT( cvres.noalias() -= m1 * cv1, 0 );\n  VERIFY_EVALUATION_COUNT( cvres.noalias() -= m1 * m2.col(0), 0 );\n  VERIFY_EVALUATION_COUNT( cvres.noalias() -= m1 * rv1.adjoint(), 0 );\n  VERIFY_EVALUATION_COUNT( cvres.noalias() -= m1 * m2.row(0).transpose(), 0 );\n\n  VERIFY_EVALUATION_COUNT( cvres.noalias() = (m1+m1) * cv1, 0 );\n  VERIFY_EVALUATION_COUNT( cvres.noalias() = (rm3+rm3) * cv1, 0 );\n  VERIFY_EVALUATION_COUNT( cvres.noalias() = (m1+m1) * (m1*cv1), 1 );\n  VERIFY_EVALUATION_COUNT( cvres.noalias() = (rm3+rm3) * (m1*cv1), 1 );\n\n  // Check outer products\n  #ifdef EIGEN_ALLOCA\n  bool temp_via_alloca = m3.rows()*sizeof(Scalar) <= EIGEN_STACK_ALLOCATION_LIMIT;\n  #else\n  bool temp_via_alloca = false;\n  #endif\n  m3 = cv1 * rv1;\n  VERIFY_EVALUATION_COUNT( m3.noalias() = cv1 * rv1, 0 );\n  VERIFY_EVALUATION_COUNT( m3.noalias() = (cv1+cv1) * (rv1+rv1), temp_via_alloca ? 0 : 1 );\n  VERIFY_EVALUATION_COUNT( m3.noalias() = (m1*cv1) * (rv1), 1 );\n  VERIFY_EVALUATION_COUNT( m3.noalias() += (m1*cv1) * (rv1), 1 );\n  rm3 = cv1 * rv1;\n  VERIFY_EVALUATION_COUNT( rm3.noalias() = cv1 * rv1, 0 );\n  VERIFY_EVALUATION_COUNT( rm3.noalias() = (cv1+cv1) * (rv1+rv1), temp_via_alloca ? 0 : 1 );\n  VERIFY_EVALUATION_COUNT( rm3.noalias() = (cv1) * (rv1 * m1), 1 );\n  VERIFY_EVALUATION_COUNT( rm3.noalias() -= (cv1) * (rv1 * m1), 1 );\n  VERIFY_EVALUATION_COUNT( rm3.noalias() = (m1*cv1) * (rv1 * m1), 2 );\n  VERIFY_EVALUATION_COUNT( rm3.noalias() += (m1*cv1) * (rv1 * m1), 2 );\n\n  // Check nested products\n  VERIFY_EVALUATION_COUNT( cvres.noalias() = m1.adjoint() * m1 * cv1, 1 );\n  VERIFY_EVALUATION_COUNT( rvres.noalias() = rv1 * (m1 * m2.adjoint()), 1 );\n\n  // exhaustively check all scalar multiple combinations:\n  {\n    // Generic path:\n    check_scalar_multiple1(m3, m1, m2, s1, s2);\n    // Force fall back to coeff-based:\n    typename ColMajorMatrixType::BlockXpr m3_blck = m3.block(r0,r0,1,1);\n    check_scalar_multiple1(m3_blck, m1.block(r0,c0,1,1), m2.block(c0,r0,1,1), s1, s2);\n  }\n}\n\nEIGEN_DECLARE_TEST(product_notemporary)\n{\n  int s;\n  for(int i = 0; i < g_repeat; i++) {\n    s = internal::random<int>(16,EIGEN_TEST_MAX_SIZE);\n    CALL_SUBTEST_1( product_notemporary(MatrixXf(s, s)) );\n    CALL_SUBTEST_2( product_notemporary(MatrixXd(s, s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n    \n    s = internal::random<int>(16,EIGEN_TEST_MAX_SIZE/2);\n    CALL_SUBTEST_3( product_notemporary(MatrixXcf(s,s)) );\n    CALL_SUBTEST_4( product_notemporary(MatrixXcd(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/product_selfadjoint.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void product_selfadjoint(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n  typedef Matrix<Scalar, 1, MatrixType::RowsAtCompileTime> RowVectorType;\n\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, Dynamic, RowMajor> RhsMatrixType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3;\n  VectorType v1 = VectorType::Random(rows),\n             v2 = VectorType::Random(rows),\n             v3(rows);\n  RowVectorType r1 = RowVectorType::Random(rows),\n                r2 = RowVectorType::Random(rows);\n  RhsMatrixType m4 = RhsMatrixType::Random(rows,10);\n\n  Scalar s1 = internal::random<Scalar>(),\n         s2 = internal::random<Scalar>(),\n         s3 = internal::random<Scalar>();\n\n  m1 = (m1.adjoint() + m1).eval();\n\n  // rank2 update\n  m2 = m1.template triangularView<Lower>();\n  m2.template selfadjointView<Lower>().rankUpdate(v1,v2);\n  VERIFY_IS_APPROX(m2, (m1 + v1 * v2.adjoint()+ v2 * v1.adjoint()).template triangularView<Lower>().toDenseMatrix());\n\n  m2 = m1.template triangularView<Upper>();\n  m2.template selfadjointView<Upper>().rankUpdate(-v1,s2*v2,s3);\n  VERIFY_IS_APPROX(m2, (m1 + (s3*(-v1)*(s2*v2).adjoint()+numext::conj(s3)*(s2*v2)*(-v1).adjoint())).template triangularView<Upper>().toDenseMatrix());\n\n  m2 = m1.template triangularView<Upper>();\n  m2.template selfadjointView<Upper>().rankUpdate(-s2*r1.adjoint(),r2.adjoint()*s3,s1);\n  VERIFY_IS_APPROX(m2, (m1 + s1*(-s2*r1.adjoint())*(r2.adjoint()*s3).adjoint() + numext::conj(s1)*(r2.adjoint()*s3) * (-s2*r1.adjoint()).adjoint()).template triangularView<Upper>().toDenseMatrix());\n\n  if (rows>1)\n  {\n    m2 = m1.template triangularView<Lower>();\n    m2.block(1,1,rows-1,cols-1).template selfadjointView<Lower>().rankUpdate(v1.tail(rows-1),v2.head(cols-1));\n    m3 = m1;\n    m3.block(1,1,rows-1,cols-1) += v1.tail(rows-1) * v2.head(cols-1).adjoint()+ v2.head(cols-1) * v1.tail(rows-1).adjoint();\n    VERIFY_IS_APPROX(m2, m3.template triangularView<Lower>().toDenseMatrix());\n  }\n}\n\nEIGEN_DECLARE_TEST(product_selfadjoint)\n{\n  int s = 0;\n  for(int i = 0; i < g_repeat ; i++) {\n    CALL_SUBTEST_1( product_selfadjoint(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( product_selfadjoint(Matrix<float, 2, 2>()) );\n    CALL_SUBTEST_3( product_selfadjoint(Matrix3d()) );\n    \n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2);\n    CALL_SUBTEST_4( product_selfadjoint(MatrixXcf(s, s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n    \n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2);\n    CALL_SUBTEST_5( product_selfadjoint(MatrixXcd(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n    \n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE);\n    CALL_SUBTEST_6( product_selfadjoint(MatrixXd(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n    \n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE);\n    CALL_SUBTEST_7( product_selfadjoint(Matrix<float,Dynamic,Dynamic,RowMajor>(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/product_small.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_STATIC_ASSERT\n#include \"product.h\"\n#include <Eigen/LU>\n\n// regression test for bug 447\ntemplate<int>\nvoid product1x1()\n{\n  Matrix<float,1,3> matAstatic;\n  Matrix<float,3,1> matBstatic;\n  matAstatic.setRandom();\n  matBstatic.setRandom();\n  VERIFY_IS_APPROX( (matAstatic * matBstatic).coeff(0,0), \n                    matAstatic.cwiseProduct(matBstatic.transpose()).sum() );\n\n  MatrixXf matAdynamic(1,3);\n  MatrixXf matBdynamic(3,1);\n  matAdynamic.setRandom();\n  matBdynamic.setRandom();\n  VERIFY_IS_APPROX( (matAdynamic * matBdynamic).coeff(0,0), \n                    matAdynamic.cwiseProduct(matBdynamic.transpose()).sum() );\n}\n\ntemplate<typename TC, typename TA, typename TB>\nconst TC& ref_prod(TC &C, const TA &A, const TB &B)\n{\n  for(Index i=0;i<C.rows();++i)\n    for(Index j=0;j<C.cols();++j)\n      for(Index k=0;k<A.cols();++k)\n        C.coeffRef(i,j) += A.coeff(i,k) * B.coeff(k,j);\n  return C;\n}\n\ntemplate<typename T, int Rows, int Cols, int Depth, int OC, int OA, int OB>\ntypename internal::enable_if<! ( (Rows ==1&&Depth!=1&&OA==ColMajor)\n                              || (Depth==1&&Rows !=1&&OA==RowMajor)\n                              || (Cols ==1&&Depth!=1&&OB==RowMajor)\n                              || (Depth==1&&Cols !=1&&OB==ColMajor)\n                              || (Rows ==1&&Cols !=1&&OC==ColMajor)\n                              || (Cols ==1&&Rows !=1&&OC==RowMajor)),void>::type\ntest_lazy_single(int rows, int cols, int depth)\n{\n  Matrix<T,Rows,Depth,OA> A(rows,depth); A.setRandom();\n  Matrix<T,Depth,Cols,OB> B(depth,cols); B.setRandom();\n  Matrix<T,Rows,Cols,OC>  C(rows,cols);  C.setRandom();\n  Matrix<T,Rows,Cols,OC>  D(C);\n  VERIFY_IS_APPROX(C+=A.lazyProduct(B), ref_prod(D,A,B));\n}\n\nvoid test_dynamic_bool()\n{\n  int rows = internal::random<int>(1,64);\n  int cols = internal::random<int>(1,64);\n  int depth = internal::random<int>(1,65);\n\n  typedef Matrix<bool,Dynamic,Dynamic> MatrixX;\n  MatrixX A(rows,depth); A.setRandom();\n  MatrixX B(depth,cols); B.setRandom();\n  MatrixX C(rows,cols);  C.setRandom();\n  MatrixX D(C);\n  for(Index i=0;i<C.rows();++i)\n    for(Index j=0;j<C.cols();++j)\n      for(Index k=0;k<A.cols();++k)\n       D.coeffRef(i,j) |= A.coeff(i,k) & B.coeff(k,j);\n  C += A * B;\n  VERIFY_IS_EQUAL(C, D);\n\n  MatrixX E = B.transpose();\n  for(Index i=0;i<B.rows();++i)\n    for(Index j=0;j<B.cols();++j)\n      VERIFY_IS_EQUAL(B(i,j), E(j,i));\n}\n\ntemplate<typename T, int Rows, int Cols, int Depth, int OC, int OA, int OB>\ntypename internal::enable_if<  ( (Rows ==1&&Depth!=1&&OA==ColMajor)\n                              || (Depth==1&&Rows !=1&&OA==RowMajor)\n                              || (Cols ==1&&Depth!=1&&OB==RowMajor)\n                              || (Depth==1&&Cols !=1&&OB==ColMajor)\n                              || (Rows ==1&&Cols !=1&&OC==ColMajor)\n                              || (Cols ==1&&Rows !=1&&OC==RowMajor)),void>::type\ntest_lazy_single(int, int, int)\n{\n}\n\ntemplate<typename T, int Rows, int Cols, int Depth>\nvoid test_lazy_all_layout(int rows=Rows, int cols=Cols, int depth=Depth)\n{\n  CALL_SUBTEST(( test_lazy_single<T,Rows,Cols,Depth,ColMajor,ColMajor,ColMajor>(rows,cols,depth) ));\n  CALL_SUBTEST(( test_lazy_single<T,Rows,Cols,Depth,RowMajor,ColMajor,ColMajor>(rows,cols,depth) ));\n  CALL_SUBTEST(( test_lazy_single<T,Rows,Cols,Depth,ColMajor,RowMajor,ColMajor>(rows,cols,depth) ));\n  CALL_SUBTEST(( test_lazy_single<T,Rows,Cols,Depth,RowMajor,RowMajor,ColMajor>(rows,cols,depth) ));\n  CALL_SUBTEST(( test_lazy_single<T,Rows,Cols,Depth,ColMajor,ColMajor,RowMajor>(rows,cols,depth) ));\n  CALL_SUBTEST(( test_lazy_single<T,Rows,Cols,Depth,RowMajor,ColMajor,RowMajor>(rows,cols,depth) ));\n  CALL_SUBTEST(( test_lazy_single<T,Rows,Cols,Depth,ColMajor,RowMajor,RowMajor>(rows,cols,depth) ));\n  CALL_SUBTEST(( test_lazy_single<T,Rows,Cols,Depth,RowMajor,RowMajor,RowMajor>(rows,cols,depth) ));\n}  \n\ntemplate<typename T>\nvoid test_lazy_l1()\n{\n  int rows = internal::random<int>(1,12);\n  int cols = internal::random<int>(1,12);\n  int depth = internal::random<int>(1,12);\n\n  // Inner\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,1,1>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,1,2>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,1,3>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,1,8>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,1,9>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,1,-1>(1,1,depth) ));\n\n  // Outer\n  CALL_SUBTEST(( test_lazy_all_layout<T,2,1,1>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,2,1>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,2,2,1>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,3,3,1>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,4,1>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,8,1>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,-1,1>(4,cols) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,7,-1,1>(7,cols) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,-1,8,1>(rows) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,-1,3,1>(rows) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,-1,-1,1>(rows,cols) ));\n}\n\ntemplate<typename T>\nvoid test_lazy_l2()\n{\n  int rows = internal::random<int>(1,12);\n  int cols = internal::random<int>(1,12);\n  int depth = internal::random<int>(1,12);\n\n  // mat-vec\n  CALL_SUBTEST(( test_lazy_all_layout<T,2,1,2>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,2,1,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,1,2>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,1,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,5,1,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,1,5>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,1,6>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,6,1,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,8,1,8>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,-1,1,4>(rows) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,1,-1>(4,1,depth) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,-1,1,-1>(rows,1,depth) ));\n\n  // vec-mat\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,2,2>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,2,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,4,2>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,4,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,5,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,4,5>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,4,6>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,6,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,8,8>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,-1, 4>(1,cols) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1, 4,-1>(1,4,depth) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,1,-1,-1>(1,cols,depth) ));\n}\n\ntemplate<typename T>\nvoid test_lazy_l3()\n{\n  int rows = internal::random<int>(1,12);\n  int cols = internal::random<int>(1,12);\n  int depth = internal::random<int>(1,12);\n  // mat-mat\n  CALL_SUBTEST(( test_lazy_all_layout<T,2,4,2>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,2,6,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,3,2>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,8,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,5,6,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,2,5>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,7,6>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,6,8,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,8,3,8>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,-1,6,4>(rows) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,3,-1>(4,3,depth) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,-1,6,-1>(rows,6,depth) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,8,2,2>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,5,2,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,4,2>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,8,4,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,6,5,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,4,5>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,3,4,6>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,2,6,4>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,7,8,8>() ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,8,-1, 4>(8,cols) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,3, 4,-1>(3,4,depth) ));\n  CALL_SUBTEST(( test_lazy_all_layout<T,4,-1,-1>(4,cols,depth) ));\n}\n\ntemplate<typename T,int N,int M,int K>\nvoid test_linear_but_not_vectorizable()\n{\n  // Check tricky cases for which the result of the product is a vector and thus must exhibit the LinearBit flag,\n  // but is not vectorizable along the linear dimension.\n  Index n = N==Dynamic ? internal::random<Index>(1,32) : N;\n  Index m = M==Dynamic ? internal::random<Index>(1,32) : M;\n  Index k = K==Dynamic ? internal::random<Index>(1,32) : K;\n\n  {\n    Matrix<T,N,M+1> A; A.setRandom(n,m+1);\n    Matrix<T,M*2,K> B; B.setRandom(m*2,k);\n    Matrix<T,1,K> C;\n    Matrix<T,1,K> R;\n\n    C.noalias() = A.template topLeftCorner<1,M>() * (B.template topRows<M>()+B.template bottomRows<M>());\n    R.noalias() = A.template topLeftCorner<1,M>() * (B.template topRows<M>()+B.template bottomRows<M>()).eval();\n    VERIFY_IS_APPROX(C,R);\n  }\n\n  {\n    Matrix<T,M+1,N,RowMajor> A; A.setRandom(m+1,n);\n    Matrix<T,K,M*2,RowMajor> B; B.setRandom(k,m*2);\n    Matrix<T,K,1> C;\n    Matrix<T,K,1> R;\n\n    C.noalias() = (B.template leftCols<M>()+B.template rightCols<M>())        * A.template topLeftCorner<M,1>();\n    R.noalias() = (B.template leftCols<M>()+B.template rightCols<M>()).eval() * A.template topLeftCorner<M,1>();\n    VERIFY_IS_APPROX(C,R);\n  }\n}\n\ntemplate<int Rows>\nvoid bug_1311()\n{\n  Matrix< double, Rows, 2 > A;  A.setRandom();\n  Vector2d b = Vector2d::Random() ;\n  Matrix<double,Rows,1> res;\n  res.noalias() = 1. * (A * b);\n  VERIFY_IS_APPROX(res, A*b);\n  res.noalias() = 1.*A * b;\n  VERIFY_IS_APPROX(res, A*b);\n  res.noalias() = (1.*A).lazyProduct(b);\n  VERIFY_IS_APPROX(res, A*b);\n  res.noalias() = (1.*A).lazyProduct(1.*b);\n  VERIFY_IS_APPROX(res, A*b);\n  res.noalias() = (A).lazyProduct(1.*b);\n  VERIFY_IS_APPROX(res, A*b);\n}\n\ntemplate<int>\nvoid product_small_regressions()\n{\n  {\n    // test compilation of (outer_product) * vector\n    Vector3f v = Vector3f::Random();\n    VERIFY_IS_APPROX( (v * v.transpose()) * v, (v * v.transpose()).eval() * v);\n  }\n  \n  {\n    // regression test for pull-request #93\n    Eigen::Matrix<double, 1, 1> A;  A.setRandom();\n    Eigen::Matrix<double, 18, 1> B; B.setRandom();\n    Eigen::Matrix<double, 1, 18> C; C.setRandom();\n    VERIFY_IS_APPROX(B * A.inverse(), B * A.inverse()[0]);\n    VERIFY_IS_APPROX(A.inverse() * C, A.inverse()[0] * C);\n  }\n\n  {\n    Eigen::Matrix<double, 10, 10> A, B, C;\n    A.setRandom();\n    C = A;\n    for(int k=0; k<79; ++k)\n      C = C * A;\n    B.noalias() = (((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)) * ((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)))\n                * (((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)) * ((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A))*((A*A)*(A*A)));\n    VERIFY_IS_APPROX(B,C);\n  }\n}\n\nEIGEN_DECLARE_TEST(product_small)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( product(Matrix<float, 3, 2>()) );\n    CALL_SUBTEST_2( product(Matrix<int, 3, 17>()) );\n    CALL_SUBTEST_8( product(Matrix<double, 3, 17>()) );\n    CALL_SUBTEST_3( product(Matrix3d()) );\n    CALL_SUBTEST_4( product(Matrix4d()) );\n    CALL_SUBTEST_5( product(Matrix4f()) );\n    CALL_SUBTEST_6( product1x1<0>() );\n\n    CALL_SUBTEST_11( test_lazy_l1<float>() );\n    CALL_SUBTEST_12( test_lazy_l2<float>() );\n    CALL_SUBTEST_13( test_lazy_l3<float>() );\n\n    CALL_SUBTEST_21( test_lazy_l1<double>() );\n    CALL_SUBTEST_22( test_lazy_l2<double>() );\n    CALL_SUBTEST_23( test_lazy_l3<double>() );\n\n    CALL_SUBTEST_31( test_lazy_l1<std::complex<float> >() );\n    CALL_SUBTEST_32( test_lazy_l2<std::complex<float> >() );\n    CALL_SUBTEST_33( test_lazy_l3<std::complex<float> >() );\n\n    CALL_SUBTEST_41( test_lazy_l1<std::complex<double> >() );\n    CALL_SUBTEST_42( test_lazy_l2<std::complex<double> >() );\n    CALL_SUBTEST_43( test_lazy_l3<std::complex<double> >() );\n\n    CALL_SUBTEST_7(( test_linear_but_not_vectorizable<float,2,1,Dynamic>() ));\n    CALL_SUBTEST_7(( test_linear_but_not_vectorizable<float,3,1,Dynamic>() ));\n    CALL_SUBTEST_7(( test_linear_but_not_vectorizable<float,2,1,16>() ));\n\n    CALL_SUBTEST_6( bug_1311<3>() );\n    CALL_SUBTEST_6( bug_1311<5>() );\n\n    CALL_SUBTEST_9( test_dynamic_bool() );\n  }\n\n  CALL_SUBTEST_6( product_small_regressions<0>() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/product_symm.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename Scalar, int Size, int OtherSize> void symm(int size = Size, int othersize = OtherSize)\n{\n  typedef Matrix<Scalar, Size, Size> MatrixType;\n  typedef Matrix<Scalar, Size, OtherSize> Rhs1;\n  typedef Matrix<Scalar, OtherSize, Size> Rhs2;\n  enum { order = OtherSize==1 ? 0 : RowMajor };\n  typedef Matrix<Scalar, Size, OtherSize,order> Rhs3;\n\n  Index rows = size;\n  Index cols = size;\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols), m3;\n\n  m1 = (m1+m1.adjoint()).eval();\n\n  Rhs1 rhs1 = Rhs1::Random(cols, othersize), rhs12(cols, othersize), rhs13(cols, othersize);\n  Rhs2 rhs2 = Rhs2::Random(othersize, rows), rhs22(othersize, rows), rhs23(othersize, rows);\n  Rhs3 rhs3 = Rhs3::Random(cols, othersize), rhs32(cols, othersize), rhs33(cols, othersize);\n\n  Scalar s1 = internal::random<Scalar>(),\n         s2 = internal::random<Scalar>();\n\n  m2 = m1.template triangularView<Lower>();\n  m3 = m2.template selfadjointView<Lower>();\n  VERIFY_IS_EQUAL(m1, m3);\n  VERIFY_IS_APPROX(rhs12 = (s1*m2).template selfadjointView<Lower>() * (s2*rhs1),\n                   rhs13 = (s1*m1) * (s2*rhs1));\n\n  VERIFY_IS_APPROX(rhs12 = (s1*m2).transpose().template selfadjointView<Upper>() * (s2*rhs1),\n                   rhs13 = (s1*m1.transpose()) * (s2*rhs1));\n\n  VERIFY_IS_APPROX(rhs12 = (s1*m2).template selfadjointView<Lower>().transpose() * (s2*rhs1),\n                   rhs13 = (s1*m1.transpose()) * (s2*rhs1));\n\n  VERIFY_IS_APPROX(rhs12 = (s1*m2).conjugate().template selfadjointView<Lower>() * (s2*rhs1),\n                   rhs13 = (s1*m1).conjugate() * (s2*rhs1));\n\n  VERIFY_IS_APPROX(rhs12 = (s1*m2).template selfadjointView<Lower>().conjugate() * (s2*rhs1),\n                   rhs13 = (s1*m1).conjugate() * (s2*rhs1));\n\n  VERIFY_IS_APPROX(rhs12 = (s1*m2).adjoint().template selfadjointView<Upper>() * (s2*rhs1),\n                   rhs13 = (s1*m1).adjoint() * (s2*rhs1));\n\n  VERIFY_IS_APPROX(rhs12 = (s1*m2).template selfadjointView<Lower>().adjoint() * (s2*rhs1),\n                   rhs13 = (s1*m1).adjoint() * (s2*rhs1));\n\n  m2 = m1.template triangularView<Upper>(); rhs12.setRandom(); rhs13 = rhs12;\n  m3 = m2.template selfadjointView<Upper>();\n  VERIFY_IS_EQUAL(m1, m3);\n  VERIFY_IS_APPROX(rhs12 += (s1*m2).template selfadjointView<Upper>() * (s2*rhs1),\n                   rhs13 += (s1*m1) * (s2*rhs1));\n\n  m2 = m1.template triangularView<Lower>();\n  VERIFY_IS_APPROX(rhs12 = (s1*m2).template selfadjointView<Lower>() * (s2*rhs2.adjoint()),\n                   rhs13 = (s1*m1) * (s2*rhs2.adjoint()));\n\n  m2 = m1.template triangularView<Upper>();\n  VERIFY_IS_APPROX(rhs12 = (s1*m2).template selfadjointView<Upper>() * (s2*rhs2.adjoint()),\n                   rhs13 = (s1*m1) * (s2*rhs2.adjoint()));\n\n  m2 = m1.template triangularView<Upper>();\n  VERIFY_IS_APPROX(rhs12 = (s1*m2.adjoint()).template selfadjointView<Lower>() * (s2*rhs2.adjoint()),\n                   rhs13 = (s1*m1.adjoint()) * (s2*rhs2.adjoint()));\n\n  // test row major = <...>\n  m2 = m1.template triangularView<Lower>(); rhs32.setRandom(); rhs13 = rhs32;\n  VERIFY_IS_APPROX(rhs32.noalias() -= (s1*m2).template selfadjointView<Lower>() * (s2*rhs3),\n                   rhs13 -= (s1*m1) * (s2 * rhs3));\n\n  m2 = m1.template triangularView<Upper>();\n  VERIFY_IS_APPROX(rhs32.noalias() = (s1*m2.adjoint()).template selfadjointView<Lower>() * (s2*rhs3).conjugate(),\n                   rhs13 = (s1*m1.adjoint()) * (s2*rhs3).conjugate());\n\n\n  m2 = m1.template triangularView<Upper>(); rhs13 = rhs12;\n  VERIFY_IS_APPROX(rhs12.noalias() += s1 * ((m2.adjoint()).template selfadjointView<Lower>() * (s2*rhs3).conjugate()),\n                   rhs13 += (s1*m1.adjoint()) * (s2*rhs3).conjugate());\n\n  m2 = m1.template triangularView<Lower>();\n  VERIFY_IS_APPROX(rhs22 = (rhs2) * (m2).template selfadjointView<Lower>(), rhs23 = (rhs2) * (m1));\n  VERIFY_IS_APPROX(rhs22 = (s2*rhs2) * (s1*m2).template selfadjointView<Lower>(), rhs23 = (s2*rhs2) * (s1*m1));\n\n  // destination with a non-default inner-stride\n  // see bug 1741\n  {\n    typedef Matrix<Scalar,Dynamic,Dynamic> MatrixX;\n    MatrixX buffer(2*cols,2*othersize);\n    Map<Rhs1,0,Stride<Dynamic,2> > map1(buffer.data(),cols,othersize,Stride<Dynamic,2>(2*rows,2));\n    buffer.setZero();\n    VERIFY_IS_APPROX( map1.noalias()  = (s1*m2).template selfadjointView<Lower>() * (s2*rhs1),\n                      rhs13 = (s1*m1) * (s2*rhs1));\n\n    Map<Rhs2,0,Stride<Dynamic,2> > map2(buffer.data(),rhs22.rows(),rhs22.cols(),Stride<Dynamic,2>(2*rhs22.outerStride(),2));\n    buffer.setZero();\n    VERIFY_IS_APPROX(map2 = (rhs2) * (m2).template selfadjointView<Lower>(), rhs23 = (rhs2) * (m1));\n  }\n}\n\nEIGEN_DECLARE_TEST(product_symm)\n{\n  for(int i = 0; i < g_repeat ; i++)\n  {\n    CALL_SUBTEST_1(( symm<float,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE),internal::random<int>(1,EIGEN_TEST_MAX_SIZE)) ));\n    CALL_SUBTEST_2(( symm<double,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE),internal::random<int>(1,EIGEN_TEST_MAX_SIZE)) ));\n    CALL_SUBTEST_3(( symm<std::complex<float>,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2),internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2)) ));\n    CALL_SUBTEST_4(( symm<std::complex<double>,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2),internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2)) ));\n\n    CALL_SUBTEST_5(( symm<float,Dynamic,1>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)) ));\n    CALL_SUBTEST_6(( symm<double,Dynamic,1>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)) ));\n    CALL_SUBTEST_7(( symm<std::complex<float>,Dynamic,1>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)) ));\n    CALL_SUBTEST_8(( symm<std::complex<double>,Dynamic,1>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE)) ));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/product_syrk.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void syrk(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::ColsAtCompileTime, RowMajor> RMatrixType;\n  typedef Matrix<Scalar, MatrixType::ColsAtCompileTime, Dynamic> Rhs1;\n  typedef Matrix<Scalar, Dynamic, MatrixType::RowsAtCompileTime> Rhs2;\n  typedef Matrix<Scalar, MatrixType::ColsAtCompileTime, Dynamic,RowMajor> Rhs3;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3 = MatrixType::Random(rows, cols);\n  RMatrixType rm2 = MatrixType::Random(rows, cols);\n\n  Rhs1 rhs1 = Rhs1::Random(internal::random<int>(1,320), cols); Rhs1 rhs11 = Rhs1::Random(rhs1.rows(), cols);\n  Rhs2 rhs2 = Rhs2::Random(rows, internal::random<int>(1,320)); Rhs2 rhs22 = Rhs2::Random(rows, rhs2.cols());\n  Rhs3 rhs3 = Rhs3::Random(internal::random<int>(1,320), rows);\n\n  Scalar s1 = internal::random<Scalar>();\n  \n  Index c = internal::random<Index>(0,cols-1);\n\n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template selfadjointView<Lower>().rankUpdate(rhs2,s1)._expression()),\n                   ((s1 * rhs2 * rhs2.adjoint()).eval().template triangularView<Lower>().toDenseMatrix()));\n  m2.setZero();\n  VERIFY_IS_APPROX(((m2.template triangularView<Lower>() += s1 * rhs2  * rhs22.adjoint()).nestedExpression()),\n                   ((s1 * rhs2 * rhs22.adjoint()).eval().template triangularView<Lower>().toDenseMatrix()));\n\n  \n  m2.setZero();\n  VERIFY_IS_APPROX(m2.template selfadjointView<Upper>().rankUpdate(rhs2,s1)._expression(),\n                   (s1 * rhs2 * rhs2.adjoint()).eval().template triangularView<Upper>().toDenseMatrix());\n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template triangularView<Upper>() += s1 * rhs22 * rhs2.adjoint()).nestedExpression(),\n                   (s1 * rhs22 * rhs2.adjoint()).eval().template triangularView<Upper>().toDenseMatrix());\n\n  \n  m2.setZero();\n  VERIFY_IS_APPROX(m2.template selfadjointView<Lower>().rankUpdate(rhs1.adjoint(),s1)._expression(),\n                   (s1 * rhs1.adjoint() * rhs1).eval().template triangularView<Lower>().toDenseMatrix());\n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template triangularView<Lower>() += s1 * rhs11.adjoint() * rhs1).nestedExpression(),\n                   (s1 * rhs11.adjoint() * rhs1).eval().template triangularView<Lower>().toDenseMatrix());\n  \n  \n  m2.setZero();\n  VERIFY_IS_APPROX(m2.template selfadjointView<Upper>().rankUpdate(rhs1.adjoint(),s1)._expression(),\n                   (s1 * rhs1.adjoint() * rhs1).eval().template triangularView<Upper>().toDenseMatrix());\n  VERIFY_IS_APPROX((m2.template triangularView<Upper>() = s1 * rhs1.adjoint() * rhs11).nestedExpression(),\n                   (s1 * rhs1.adjoint() * rhs11).eval().template triangularView<Upper>().toDenseMatrix());\n\n  \n  m2.setZero();\n  VERIFY_IS_APPROX(m2.template selfadjointView<Lower>().rankUpdate(rhs3.adjoint(),s1)._expression(),\n                   (s1 * rhs3.adjoint() * rhs3).eval().template triangularView<Lower>().toDenseMatrix());\n\n  m2.setZero();\n  VERIFY_IS_APPROX(m2.template selfadjointView<Upper>().rankUpdate(rhs3.adjoint(),s1)._expression(),\n                   (s1 * rhs3.adjoint() * rhs3).eval().template triangularView<Upper>().toDenseMatrix());\n                   \n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template selfadjointView<Lower>().rankUpdate(m1.col(c),s1)._expression()),\n                   ((s1 * m1.col(c) * m1.col(c).adjoint()).eval().template triangularView<Lower>().toDenseMatrix()));\n                   \n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template selfadjointView<Upper>().rankUpdate(m1.col(c),s1)._expression()),\n                   ((s1 * m1.col(c) * m1.col(c).adjoint()).eval().template triangularView<Upper>().toDenseMatrix()));\n  rm2.setZero();\n  VERIFY_IS_APPROX((rm2.template selfadjointView<Upper>().rankUpdate(m1.col(c),s1)._expression()),\n                   ((s1 * m1.col(c) * m1.col(c).adjoint()).eval().template triangularView<Upper>().toDenseMatrix()));\n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template triangularView<Upper>() += s1 * m3.col(c) * m1.col(c).adjoint()).nestedExpression(),\n                   ((s1 * m3.col(c) * m1.col(c).adjoint()).eval().template triangularView<Upper>().toDenseMatrix()));\n  rm2.setZero();\n  VERIFY_IS_APPROX((rm2.template triangularView<Upper>() += s1 * m1.col(c) * m3.col(c).adjoint()).nestedExpression(),\n                   ((s1 * m1.col(c) * m3.col(c).adjoint()).eval().template triangularView<Upper>().toDenseMatrix()));\n  \n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template selfadjointView<Lower>().rankUpdate(m1.col(c).conjugate(),s1)._expression()),\n                   ((s1 * m1.col(c).conjugate() * m1.col(c).conjugate().adjoint()).eval().template triangularView<Lower>().toDenseMatrix()));\n                   \n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template selfadjointView<Upper>().rankUpdate(m1.col(c).conjugate(),s1)._expression()),\n                   ((s1 * m1.col(c).conjugate() * m1.col(c).conjugate().adjoint()).eval().template triangularView<Upper>().toDenseMatrix()));\n  \n  \n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template selfadjointView<Lower>().rankUpdate(m1.row(c),s1)._expression()),\n                   ((s1 * m1.row(c).transpose() * m1.row(c).transpose().adjoint()).eval().template triangularView<Lower>().toDenseMatrix()));\n  rm2.setZero();\n  VERIFY_IS_APPROX((rm2.template selfadjointView<Lower>().rankUpdate(m1.row(c),s1)._expression()),\n                   ((s1 * m1.row(c).transpose() * m1.row(c).transpose().adjoint()).eval().template triangularView<Lower>().toDenseMatrix()));\n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template triangularView<Lower>() += s1 * m3.row(c).transpose() * m1.row(c).transpose().adjoint()).nestedExpression(),\n                   ((s1 * m3.row(c).transpose() * m1.row(c).transpose().adjoint()).eval().template triangularView<Lower>().toDenseMatrix()));\n  rm2.setZero();\n  VERIFY_IS_APPROX((rm2.template triangularView<Lower>() += s1 * m3.row(c).transpose() * m1.row(c).transpose().adjoint()).nestedExpression(),\n                   ((s1 * m3.row(c).transpose() * m1.row(c).transpose().adjoint()).eval().template triangularView<Lower>().toDenseMatrix()));\n  \n  \n  m2.setZero();\n  VERIFY_IS_APPROX((m2.template selfadjointView<Upper>().rankUpdate(m1.row(c).adjoint(),s1)._expression()),\n                   ((s1 * m1.row(c).adjoint() * m1.row(c).adjoint().adjoint()).eval().template triangularView<Upper>().toDenseMatrix()));\n\n  // destination with a non-default inner-stride\n  // see bug 1741\n  {\n    typedef Matrix<Scalar,Dynamic,Dynamic> MatrixX;\n    MatrixX buffer(2*rows,2*cols);\n    Map<MatrixType,0,Stride<Dynamic,2> > map1(buffer.data(),rows,cols,Stride<Dynamic,2>(2*rows,2));\n    buffer.setZero();\n    VERIFY_IS_APPROX((map1.template selfadjointView<Lower>().rankUpdate(rhs2,s1)._expression()),\n                      ((s1 * rhs2 * rhs2.adjoint()).eval().template triangularView<Lower>().toDenseMatrix()));\n  }\n}\n\nEIGEN_DECLARE_TEST(product_syrk)\n{\n  for(int i = 0; i < g_repeat ; i++)\n  {\n    int s;\n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE);\n    CALL_SUBTEST_1( syrk(MatrixXf(s, s)) );\n    CALL_SUBTEST_2( syrk(MatrixXd(s, s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n    \n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2);\n    CALL_SUBTEST_3( syrk(MatrixXcf(s, s)) );\n    CALL_SUBTEST_4( syrk(MatrixXcd(s, s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/product_trmm.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename T>\nint get_random_size()\n{\n  const int factor = NumTraits<T>::ReadCost;\n  const int max_test_size = EIGEN_TEST_MAX_SIZE>2*factor ? EIGEN_TEST_MAX_SIZE/factor : EIGEN_TEST_MAX_SIZE;\n  return internal::random<int>(1,max_test_size);\n}\n\ntemplate<typename Scalar, int Mode, int TriOrder, int OtherOrder, int ResOrder, int OtherCols>\nvoid trmm(int rows=get_random_size<Scalar>(),\n          int cols=get_random_size<Scalar>(),\n          int otherCols = OtherCols==Dynamic?get_random_size<Scalar>():OtherCols)\n{\n  typedef Matrix<Scalar,Dynamic,Dynamic,TriOrder> TriMatrix;\n  typedef Matrix<Scalar,Dynamic,OtherCols,OtherCols==1?ColMajor:OtherOrder> OnTheRight;\n  typedef Matrix<Scalar,OtherCols,Dynamic,OtherCols==1?RowMajor:OtherOrder> OnTheLeft;\n  \n  typedef Matrix<Scalar,Dynamic,OtherCols,OtherCols==1?ColMajor:ResOrder> ResXS;\n  typedef Matrix<Scalar,OtherCols,Dynamic,OtherCols==1?RowMajor:ResOrder> ResSX;\n\n  TriMatrix  mat(rows,cols), tri(rows,cols), triTr(cols,rows), s1tri(rows,cols), s1triTr(cols,rows);\n  \n  OnTheRight  ge_right(cols,otherCols);\n  OnTheLeft   ge_left(otherCols,rows);\n  ResSX       ge_sx, ge_sx_save;\n  ResXS       ge_xs, ge_xs_save;\n\n  Scalar s1 = internal::random<Scalar>(),\n         s2 = internal::random<Scalar>();\n\n  mat.setRandom();\n  tri = mat.template triangularView<Mode>();\n  triTr = mat.transpose().template triangularView<Mode>();\n  s1tri = (s1*mat).template triangularView<Mode>();\n  s1triTr = (s1*mat).transpose().template triangularView<Mode>();\n  ge_right.setRandom();\n  ge_left.setRandom();\n\n  VERIFY_IS_APPROX( ge_xs = mat.template triangularView<Mode>() * ge_right, tri * ge_right);\n  VERIFY_IS_APPROX( ge_sx = ge_left * mat.template triangularView<Mode>(), ge_left * tri);\n  \n  VERIFY_IS_APPROX( ge_xs.noalias() = mat.template triangularView<Mode>() * ge_right, tri * ge_right);\n  VERIFY_IS_APPROX( ge_sx.noalias() = ge_left * mat.template triangularView<Mode>(), ge_left * tri);\n\n  if((Mode&UnitDiag)==0)\n    VERIFY_IS_APPROX( ge_xs.noalias() = (s1*mat.adjoint()).template triangularView<Mode>() * (s2*ge_left.transpose()), s1*triTr.conjugate() * (s2*ge_left.transpose()));\n  \n  VERIFY_IS_APPROX( ge_xs.noalias() = (s1*mat.transpose()).template triangularView<Mode>() * (s2*ge_left.transpose()), s1triTr * (s2*ge_left.transpose()));\n  VERIFY_IS_APPROX( ge_sx.noalias() = (s2*ge_left) * (s1*mat).template triangularView<Mode>(), (s2*ge_left)*s1tri);\n\n  VERIFY_IS_APPROX( ge_sx.noalias() = ge_right.transpose() * mat.adjoint().template triangularView<Mode>(), ge_right.transpose() * triTr.conjugate());\n  VERIFY_IS_APPROX( ge_sx.noalias() = ge_right.adjoint() * mat.adjoint().template triangularView<Mode>(), ge_right.adjoint() * triTr.conjugate());\n  \n  ge_xs_save = ge_xs;\n  if((Mode&UnitDiag)==0)\n    VERIFY_IS_APPROX( (ge_xs_save + s1*triTr.conjugate() * (s2*ge_left.adjoint())).eval(), ge_xs.noalias() += (s1*mat.adjoint()).template triangularView<Mode>() * (s2*ge_left.adjoint()) );\n  ge_xs_save = ge_xs;\n  VERIFY_IS_APPROX( (ge_xs_save + s1triTr * (s2*ge_left.adjoint())).eval(), ge_xs.noalias() += (s1*mat.transpose()).template triangularView<Mode>() * (s2*ge_left.adjoint()) );\n  ge_sx.setRandom();\n  ge_sx_save = ge_sx;\n  if((Mode&UnitDiag)==0)\n    VERIFY_IS_APPROX( ge_sx_save - (ge_right.adjoint() * (-s1 * triTr).conjugate()).eval(), ge_sx.noalias() -= (ge_right.adjoint() * (-s1 * mat).adjoint().template triangularView<Mode>()).eval());\n  \n  if((Mode&UnitDiag)==0)\n    VERIFY_IS_APPROX( ge_xs = (s1*mat).adjoint().template triangularView<Mode>() * ge_left.adjoint(), numext::conj(s1) * triTr.conjugate() * ge_left.adjoint());\n  VERIFY_IS_APPROX( ge_xs = (s1*mat).transpose().template triangularView<Mode>() * ge_left.adjoint(), s1triTr * ge_left.adjoint());\n\n  // TODO check with sub-matrix expressions ?\n\n  // destination with a non-default inner-stride\n  // see bug 1741\n  {\n    VERIFY_IS_APPROX( ge_xs.noalias() = mat.template triangularView<Mode>() * ge_right, tri * ge_right);\n    typedef Matrix<Scalar,Dynamic,Dynamic> MatrixX;\n    MatrixX buffer(2*ge_xs.rows(),2*ge_xs.cols());\n    Map<ResXS,0,Stride<Dynamic,2> > map1(buffer.data(),ge_xs.rows(),ge_xs.cols(),Stride<Dynamic,2>(2*ge_xs.outerStride(),2));\n    buffer.setZero();\n    VERIFY_IS_APPROX( map1.noalias() = mat.template triangularView<Mode>() * ge_right, tri * ge_right);\n  }\n}\n\ntemplate<typename Scalar, int Mode, int TriOrder>\nvoid trmv(int rows=get_random_size<Scalar>(), int cols=get_random_size<Scalar>())\n{\n  trmm<Scalar,Mode,TriOrder,ColMajor,ColMajor,1>(rows,cols,1);\n}\n\ntemplate<typename Scalar, int Mode, int TriOrder, int OtherOrder, int ResOrder>\nvoid trmm(int rows=get_random_size<Scalar>(), int cols=get_random_size<Scalar>(), int otherCols = get_random_size<Scalar>())\n{\n  trmm<Scalar,Mode,TriOrder,OtherOrder,ResOrder,Dynamic>(rows,cols,otherCols);\n}\n\n#define CALL_ALL_ORDERS(NB,SCALAR,MODE)                                             \\\n  EIGEN_CAT(CALL_SUBTEST_,NB)((trmm<SCALAR, MODE, ColMajor,ColMajor,ColMajor>()));  \\\n  EIGEN_CAT(CALL_SUBTEST_,NB)((trmm<SCALAR, MODE, ColMajor,ColMajor,RowMajor>()));  \\\n  EIGEN_CAT(CALL_SUBTEST_,NB)((trmm<SCALAR, MODE, ColMajor,RowMajor,ColMajor>()));  \\\n  EIGEN_CAT(CALL_SUBTEST_,NB)((trmm<SCALAR, MODE, ColMajor,RowMajor,RowMajor>()));  \\\n  EIGEN_CAT(CALL_SUBTEST_,NB)((trmm<SCALAR, MODE, RowMajor,ColMajor,ColMajor>()));  \\\n  EIGEN_CAT(CALL_SUBTEST_,NB)((trmm<SCALAR, MODE, RowMajor,ColMajor,RowMajor>()));  \\\n  EIGEN_CAT(CALL_SUBTEST_,NB)((trmm<SCALAR, MODE, RowMajor,RowMajor,ColMajor>()));  \\\n  EIGEN_CAT(CALL_SUBTEST_,NB)((trmm<SCALAR, MODE, RowMajor,RowMajor,RowMajor>()));  \\\n  \\\n  EIGEN_CAT(CALL_SUBTEST_1,NB)((trmv<SCALAR, MODE, ColMajor>()));                   \\\n  EIGEN_CAT(CALL_SUBTEST_1,NB)((trmv<SCALAR, MODE, RowMajor>()));\n\n  \n#define CALL_ALL(NB,SCALAR)                 \\\n  CALL_ALL_ORDERS(EIGEN_CAT(1,NB),SCALAR,Upper)          \\\n  CALL_ALL_ORDERS(EIGEN_CAT(2,NB),SCALAR,UnitUpper)      \\\n  CALL_ALL_ORDERS(EIGEN_CAT(3,NB),SCALAR,StrictlyUpper)  \\\n  CALL_ALL_ORDERS(EIGEN_CAT(1,NB),SCALAR,Lower)          \\\n  CALL_ALL_ORDERS(EIGEN_CAT(2,NB),SCALAR,UnitLower)      \\\n  CALL_ALL_ORDERS(EIGEN_CAT(3,NB),SCALAR,StrictlyLower)\n  \n\nEIGEN_DECLARE_TEST(product_trmm)\n{\n  for(int i = 0; i < g_repeat ; i++)\n  {\n    CALL_ALL(1,float);                //  EIGEN_SUFFIXES;11;111;21;121;31;131\n    CALL_ALL(2,double);               //  EIGEN_SUFFIXES;12;112;22;122;32;132\n    CALL_ALL(3,std::complex<float>);  //  EIGEN_SUFFIXES;13;113;23;123;33;133\n    CALL_ALL(4,std::complex<double>); //  EIGEN_SUFFIXES;14;114;24;124;34;134\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/product_trmv.cpp",
    "content": "// This file is triangularView of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void trmv(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n\n  RealScalar largerEps = 10*test_precision<RealScalar>();\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m3(rows, cols);\n  VectorType v1 = VectorType::Random(rows);\n\n  Scalar s1 = internal::random<Scalar>();\n\n  m1 = MatrixType::Random(rows, cols);\n\n  // check with a column-major matrix\n  m3 = m1.template triangularView<Eigen::Lower>();\n  VERIFY((m3 * v1).isApprox(m1.template triangularView<Eigen::Lower>() * v1, largerEps));\n  m3 = m1.template triangularView<Eigen::Upper>();\n  VERIFY((m3 * v1).isApprox(m1.template triangularView<Eigen::Upper>() * v1, largerEps));\n  m3 = m1.template triangularView<Eigen::UnitLower>();\n  VERIFY((m3 * v1).isApprox(m1.template triangularView<Eigen::UnitLower>() * v1, largerEps));\n  m3 = m1.template triangularView<Eigen::UnitUpper>();\n  VERIFY((m3 * v1).isApprox(m1.template triangularView<Eigen::UnitUpper>() * v1, largerEps));\n\n  // check conjugated and scalar multiple expressions (col-major)\n  m3 = m1.template triangularView<Eigen::Lower>();\n  VERIFY(((s1*m3).conjugate() * v1).isApprox((s1*m1).conjugate().template triangularView<Eigen::Lower>() * v1, largerEps));\n  m3 = m1.template triangularView<Eigen::Upper>();\n  VERIFY((m3.conjugate() * v1.conjugate()).isApprox(m1.conjugate().template triangularView<Eigen::Upper>() * v1.conjugate(), largerEps));\n\n  // check with a row-major matrix\n  m3 = m1.template triangularView<Eigen::Upper>();\n  VERIFY((m3.transpose() * v1).isApprox(m1.transpose().template triangularView<Eigen::Lower>() * v1, largerEps));\n  m3 = m1.template triangularView<Eigen::Lower>();\n  VERIFY((m3.transpose() * v1).isApprox(m1.transpose().template triangularView<Eigen::Upper>() * v1, largerEps));\n  m3 = m1.template triangularView<Eigen::UnitUpper>();\n  VERIFY((m3.transpose() * v1).isApprox(m1.transpose().template triangularView<Eigen::UnitLower>() * v1, largerEps));\n  m3 = m1.template triangularView<Eigen::UnitLower>();\n  VERIFY((m3.transpose() * v1).isApprox(m1.transpose().template triangularView<Eigen::UnitUpper>() * v1, largerEps));\n\n  // check conjugated and scalar multiple expressions (row-major)\n  m3 = m1.template triangularView<Eigen::Upper>();\n  VERIFY((m3.adjoint() * v1).isApprox(m1.adjoint().template triangularView<Eigen::Lower>() * v1, largerEps));\n  m3 = m1.template triangularView<Eigen::Lower>();\n  VERIFY((m3.adjoint() * (s1*v1.conjugate())).isApprox(m1.adjoint().template triangularView<Eigen::Upper>() * (s1*v1.conjugate()), largerEps));\n  m3 = m1.template triangularView<Eigen::UnitUpper>();\n\n  // check transposed cases:\n  m3 = m1.template triangularView<Eigen::Lower>();\n  VERIFY((v1.transpose() * m3).isApprox(v1.transpose() * m1.template triangularView<Eigen::Lower>(), largerEps));\n  VERIFY((v1.adjoint() * m3).isApprox(v1.adjoint() * m1.template triangularView<Eigen::Lower>(), largerEps));\n  VERIFY((v1.adjoint() * m3.adjoint()).isApprox(v1.adjoint() * m1.template triangularView<Eigen::Lower>().adjoint(), largerEps));\n\n  // TODO check with sub-matrices\n}\n\nEIGEN_DECLARE_TEST(product_trmv)\n{\n  int s = 0;\n  for(int i = 0; i < g_repeat ; i++) {\n    CALL_SUBTEST_1( trmv(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( trmv(Matrix<float, 2, 2>()) );\n    CALL_SUBTEST_3( trmv(Matrix3d()) );\n    \n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2);\n    CALL_SUBTEST_4( trmv(MatrixXcf(s,s)) );\n    CALL_SUBTEST_5( trmv(MatrixXcd(s,s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n    \n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE);\n    CALL_SUBTEST_6( trmv(Matrix<float,Dynamic,Dynamic,RowMajor>(s, s)) );\n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/product_trsolve.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#define VERIFY_TRSM(TRI,XB) { \\\n    (XB).setRandom(); ref = (XB); \\\n    (TRI).solveInPlace(XB); \\\n    VERIFY_IS_APPROX((TRI).toDenseMatrix() * (XB), ref); \\\n    (XB).setRandom(); ref = (XB); \\\n    (XB) = (TRI).solve(XB); \\\n    VERIFY_IS_APPROX((TRI).toDenseMatrix() * (XB), ref); \\\n  }\n\n#define VERIFY_TRSM_ONTHERIGHT(TRI,XB) { \\\n    (XB).setRandom(); ref = (XB); \\\n    (TRI).transpose().template solveInPlace<OnTheRight>(XB.transpose()); \\\n    VERIFY_IS_APPROX((XB).transpose() * (TRI).transpose().toDenseMatrix(), ref.transpose()); \\\n    (XB).setRandom(); ref = (XB); \\\n    (XB).transpose() = (TRI).transpose().template solve<OnTheRight>(XB.transpose()); \\\n    VERIFY_IS_APPROX((XB).transpose() * (TRI).transpose().toDenseMatrix(), ref.transpose()); \\\n  }\n\ntemplate<typename Scalar,int Size, int Cols> void trsolve(int size=Size,int cols=Cols)\n{\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  Matrix<Scalar,Size,Size,ColMajor> cmLhs(size,size);\n  Matrix<Scalar,Size,Size,RowMajor> rmLhs(size,size);\n\n  enum {  colmajor = Size==1 ? RowMajor : ColMajor,\n          rowmajor = Cols==1 ? ColMajor : RowMajor };\n  Matrix<Scalar,Size,Cols,colmajor> cmRhs(size,cols);\n  Matrix<Scalar,Size,Cols,rowmajor> rmRhs(size,cols);\n  Matrix<Scalar,Dynamic,Dynamic,colmajor> ref(size,cols);\n\n  cmLhs.setRandom(); cmLhs *= static_cast<RealScalar>(0.1); cmLhs.diagonal().array() += static_cast<RealScalar>(1);\n  rmLhs.setRandom(); rmLhs *= static_cast<RealScalar>(0.1); rmLhs.diagonal().array() += static_cast<RealScalar>(1);\n\n  VERIFY_TRSM(cmLhs.conjugate().template triangularView<Lower>(), cmRhs);\n  VERIFY_TRSM(cmLhs.adjoint()  .template triangularView<Lower>(), cmRhs);\n  VERIFY_TRSM(cmLhs            .template triangularView<Upper>(), cmRhs);\n  VERIFY_TRSM(cmLhs            .template triangularView<Lower>(), rmRhs);\n  VERIFY_TRSM(cmLhs.conjugate().template triangularView<Upper>(), rmRhs);\n  VERIFY_TRSM(cmLhs.adjoint()  .template triangularView<Upper>(), rmRhs);\n\n  VERIFY_TRSM(cmLhs.conjugate().template triangularView<UnitLower>(), cmRhs);\n  VERIFY_TRSM(cmLhs            .template triangularView<UnitUpper>(), rmRhs);\n\n  VERIFY_TRSM(rmLhs            .template triangularView<Lower>(), cmRhs);\n  VERIFY_TRSM(rmLhs.conjugate().template triangularView<UnitUpper>(), rmRhs);\n\n\n  VERIFY_TRSM_ONTHERIGHT(cmLhs.conjugate().template triangularView<Lower>(), cmRhs);\n  VERIFY_TRSM_ONTHERIGHT(cmLhs            .template triangularView<Upper>(), cmRhs);\n  VERIFY_TRSM_ONTHERIGHT(cmLhs            .template triangularView<Lower>(), rmRhs);\n  VERIFY_TRSM_ONTHERIGHT(cmLhs.conjugate().template triangularView<Upper>(), rmRhs);\n\n  VERIFY_TRSM_ONTHERIGHT(cmLhs.conjugate().template triangularView<UnitLower>(), cmRhs);\n  VERIFY_TRSM_ONTHERIGHT(cmLhs            .template triangularView<UnitUpper>(), rmRhs);\n\n  VERIFY_TRSM_ONTHERIGHT(rmLhs            .template triangularView<Lower>(), cmRhs);\n  VERIFY_TRSM_ONTHERIGHT(rmLhs.conjugate().template triangularView<UnitUpper>(), rmRhs);\n\n  int c = internal::random<int>(0,cols-1);\n  VERIFY_TRSM(rmLhs.template triangularView<Lower>(), rmRhs.col(c));\n  VERIFY_TRSM(cmLhs.template triangularView<Lower>(), rmRhs.col(c));\n\n  // destination with a non-default inner-stride\n  // see bug 1741\n  {\n    typedef Matrix<Scalar,Dynamic,Dynamic> MatrixX;\n    MatrixX buffer(2*cmRhs.rows(),2*cmRhs.cols());\n    Map<Matrix<Scalar,Size,Cols,colmajor>,0,Stride<Dynamic,2> > map1(buffer.data(),cmRhs.rows(),cmRhs.cols(),Stride<Dynamic,2>(2*cmRhs.outerStride(),2));\n    Map<Matrix<Scalar,Size,Cols,rowmajor>,0,Stride<Dynamic,2> > map2(buffer.data(),rmRhs.rows(),rmRhs.cols(),Stride<Dynamic,2>(2*rmRhs.outerStride(),2));\n    buffer.setZero();\n    VERIFY_TRSM(cmLhs.conjugate().template triangularView<Lower>(), map1);\n    buffer.setZero();\n    VERIFY_TRSM(cmLhs            .template triangularView<Lower>(), map2);\n  }\n\n  if(Size==Dynamic)\n  {\n    cmLhs.resize(0,0);\n    cmRhs.resize(0,cmRhs.cols());\n    Matrix<Scalar,Size,Cols,colmajor> res = cmLhs.template triangularView<Lower>().solve(cmRhs);\n    VERIFY_IS_EQUAL(res.rows(),0);\n    VERIFY_IS_EQUAL(res.cols(),cmRhs.cols());\n    res = cmRhs;\n    cmLhs.template triangularView<Lower>().solveInPlace(res);\n    VERIFY_IS_EQUAL(res.rows(),0);\n    VERIFY_IS_EQUAL(res.cols(),cmRhs.cols());\n  }\n}\n\nEIGEN_DECLARE_TEST(product_trsolve)\n{\n  for(int i = 0; i < g_repeat ; i++)\n  {\n    // matrices\n    CALL_SUBTEST_1((trsolve<float,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE),internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_2((trsolve<double,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE),internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_3((trsolve<std::complex<float>,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2),internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))));\n    CALL_SUBTEST_4((trsolve<std::complex<double>,Dynamic,Dynamic>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2),internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))));\n\n    // vectors\n    CALL_SUBTEST_5((trsolve<float,Dynamic,1>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_6((trsolve<double,Dynamic,1>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_7((trsolve<std::complex<float>,Dynamic,1>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_8((trsolve<std::complex<double>,Dynamic,1>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    \n    // meta-unrollers\n    CALL_SUBTEST_9((trsolve<float,4,1>()));\n    CALL_SUBTEST_10((trsolve<double,4,1>()));\n    CALL_SUBTEST_11((trsolve<std::complex<float>,4,1>()));\n    CALL_SUBTEST_12((trsolve<float,1,1>()));\n    CALL_SUBTEST_13((trsolve<float,1,2>()));\n    CALL_SUBTEST_14((trsolve<float,3,1>()));\n    \n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/qr.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/QR>\n#include \"solverbase.h\"\n\ntemplate<typename MatrixType> void qr(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> MatrixQType;\n\n  MatrixType a = MatrixType::Random(rows,cols);\n  HouseholderQR<MatrixType> qrOfA(a);\n\n  MatrixQType q = qrOfA.householderQ();\n  VERIFY_IS_UNITARY(q);\n\n  MatrixType r = qrOfA.matrixQR().template triangularView<Upper>();\n  VERIFY_IS_APPROX(a, qrOfA.householderQ() * r);\n}\n\ntemplate<typename MatrixType, int Cols2> void qr_fixedsize()\n{\n  enum { Rows = MatrixType::RowsAtCompileTime, Cols = MatrixType::ColsAtCompileTime };\n  typedef typename MatrixType::Scalar Scalar;\n  Matrix<Scalar,Rows,Cols> m1 = Matrix<Scalar,Rows,Cols>::Random();\n  HouseholderQR<Matrix<Scalar,Rows,Cols> > qr(m1);\n\n  Matrix<Scalar,Rows,Cols> r = qr.matrixQR();\n  // FIXME need better way to construct trapezoid\n  for(int i = 0; i < Rows; i++) for(int j = 0; j < Cols; j++) if(i>j) r(i,j) = Scalar(0);\n\n  VERIFY_IS_APPROX(m1, qr.householderQ() * r);\n\n  check_solverbase<Matrix<Scalar,Cols,Cols2>, Matrix<Scalar,Rows,Cols2> >(m1, qr, Rows, Cols, Cols2);\n}\n\ntemplate<typename MatrixType> void qr_invertible()\n{\n  using std::log;\n  using std::abs;\n  using std::pow;\n  using std::max;\n  typedef typename NumTraits<typename MatrixType::Scalar>::Real RealScalar;\n  typedef typename MatrixType::Scalar Scalar;\n\n  STATIC_CHECK(( internal::is_same<typename HouseholderQR<MatrixType>::StorageIndex,int>::value ));\n\n  int size = internal::random<int>(10,50);\n\n  MatrixType m1(size, size), m2(size, size), m3(size, size);\n  m1 = MatrixType::Random(size,size);\n\n  if (internal::is_same<RealScalar,float>::value)\n  {\n    // let's build a matrix more stable to inverse\n    MatrixType a = MatrixType::Random(size,size*4);\n    m1 += a * a.adjoint();\n  }\n\n  HouseholderQR<MatrixType> qr(m1);\n\n  check_solverbase<MatrixType, MatrixType>(m1, qr, size, size, size);\n\n  // now construct a matrix with prescribed determinant\n  m1.setZero();\n  for(int i = 0; i < size; i++) m1(i,i) = internal::random<Scalar>();\n  RealScalar absdet = abs(m1.diagonal().prod());\n  m3 = qr.householderQ(); // get a unitary\n  m1 = m3 * m1 * m3;\n  qr.compute(m1);\n  VERIFY_IS_APPROX(log(absdet), qr.logAbsDeterminant());\n  // This test is tricky if the determinant becomes too small.\n  // Since we generate random numbers with magnitude range [0,1], the average determinant is 0.5^size\n  VERIFY_IS_MUCH_SMALLER_THAN( abs(absdet-qr.absDeterminant()), numext::maxi(RealScalar(pow(0.5,size)),numext::maxi<RealScalar>(abs(absdet),abs(qr.absDeterminant()))) );\n  \n}\n\ntemplate<typename MatrixType> void qr_verify_assert()\n{\n  MatrixType tmp;\n\n  HouseholderQR<MatrixType> qr;\n  VERIFY_RAISES_ASSERT(qr.matrixQR())\n  VERIFY_RAISES_ASSERT(qr.solve(tmp))\n  VERIFY_RAISES_ASSERT(qr.transpose().solve(tmp))\n  VERIFY_RAISES_ASSERT(qr.adjoint().solve(tmp))\n  VERIFY_RAISES_ASSERT(qr.householderQ())\n  VERIFY_RAISES_ASSERT(qr.absDeterminant())\n  VERIFY_RAISES_ASSERT(qr.logAbsDeterminant())\n}\n\nEIGEN_DECLARE_TEST(qr)\n{\n  for(int i = 0; i < g_repeat; i++) {\n   CALL_SUBTEST_1( qr(MatrixXf(internal::random<int>(1,EIGEN_TEST_MAX_SIZE),internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n   CALL_SUBTEST_2( qr(MatrixXcd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2),internal::random<int>(1,EIGEN_TEST_MAX_SIZE/2))) );\n   CALL_SUBTEST_3(( qr_fixedsize<Matrix<float,3,4>, 2 >() ));\n   CALL_SUBTEST_4(( qr_fixedsize<Matrix<double,6,2>, 4 >() ));\n   CALL_SUBTEST_5(( qr_fixedsize<Matrix<double,2,5>, 7 >() ));\n   CALL_SUBTEST_11( qr(Matrix<float,1,1>()) );\n  }\n\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( qr_invertible<MatrixXf>() );\n    CALL_SUBTEST_6( qr_invertible<MatrixXd>() );\n    CALL_SUBTEST_7( qr_invertible<MatrixXcf>() );\n    CALL_SUBTEST_8( qr_invertible<MatrixXcd>() );\n  }\n\n  CALL_SUBTEST_9(qr_verify_assert<Matrix3f>());\n  CALL_SUBTEST_10(qr_verify_assert<Matrix3d>());\n  CALL_SUBTEST_1(qr_verify_assert<MatrixXf>());\n  CALL_SUBTEST_6(qr_verify_assert<MatrixXd>());\n  CALL_SUBTEST_7(qr_verify_assert<MatrixXcf>());\n  CALL_SUBTEST_8(qr_verify_assert<MatrixXcd>());\n\n  // Test problem size constructors\n  CALL_SUBTEST_12(HouseholderQR<MatrixXf>(10, 20));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/qr_colpivoting.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/QR>\n#include <Eigen/SVD>\n#include \"solverbase.h\"\n\ntemplate <typename MatrixType>\nvoid cod() {\n  STATIC_CHECK(( internal::is_same<typename CompleteOrthogonalDecomposition<MatrixType>::StorageIndex,int>::value ));\n\n  Index rows = internal::random<Index>(2, EIGEN_TEST_MAX_SIZE);\n  Index cols = internal::random<Index>(2, EIGEN_TEST_MAX_SIZE);\n  Index cols2 = internal::random<Index>(2, EIGEN_TEST_MAX_SIZE);\n  Index rank = internal::random<Index>(1, (std::min)(rows, cols) - 1);\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime,\n                 MatrixType::RowsAtCompileTime>\n      MatrixQType;\n  MatrixType matrix;\n  createRandomPIMatrixOfRank(rank, rows, cols, matrix);\n  CompleteOrthogonalDecomposition<MatrixType> cod(matrix);\n  VERIFY(rank == cod.rank());\n  VERIFY(cols - cod.rank() == cod.dimensionOfKernel());\n  VERIFY(!cod.isInjective());\n  VERIFY(!cod.isInvertible());\n  VERIFY(!cod.isSurjective());\n\n  MatrixQType q = cod.householderQ();\n  VERIFY_IS_UNITARY(q);\n\n  MatrixType z = cod.matrixZ();\n  VERIFY_IS_UNITARY(z);\n\n  MatrixType t;\n  t.setZero(rows, cols);\n  t.topLeftCorner(rank, rank) =\n      cod.matrixT().topLeftCorner(rank, rank).template triangularView<Upper>();\n\n  MatrixType c = q * t * z * cod.colsPermutation().inverse();\n  VERIFY_IS_APPROX(matrix, c);\n\n  check_solverbase<MatrixType, MatrixType>(matrix, cod, rows, cols, cols2);\n\n  // Verify that we get the same minimum-norm solution as the SVD.\n  MatrixType exact_solution = MatrixType::Random(cols, cols2);\n  MatrixType rhs = matrix * exact_solution;\n  MatrixType cod_solution = cod.solve(rhs);\n  JacobiSVD<MatrixType> svd(matrix, ComputeThinU | ComputeThinV);\n  MatrixType svd_solution = svd.solve(rhs);\n  VERIFY_IS_APPROX(cod_solution, svd_solution);\n\n  MatrixType pinv = cod.pseudoInverse();\n  VERIFY_IS_APPROX(cod_solution, pinv * rhs);\n}\n\ntemplate <typename MatrixType, int Cols2>\nvoid cod_fixedsize() {\n  enum {\n    Rows = MatrixType::RowsAtCompileTime,\n    Cols = MatrixType::ColsAtCompileTime\n  };\n  typedef typename MatrixType::Scalar Scalar;\n  typedef CompleteOrthogonalDecomposition<Matrix<Scalar, Rows, Cols> > COD;\n  int rank = internal::random<int>(1, (std::min)(int(Rows), int(Cols)) - 1);\n  Matrix<Scalar, Rows, Cols> matrix;\n  createRandomPIMatrixOfRank(rank, Rows, Cols, matrix);\n  COD cod(matrix);\n  VERIFY(rank == cod.rank());\n  VERIFY(Cols - cod.rank() == cod.dimensionOfKernel());\n  VERIFY(cod.isInjective() == (rank == Rows));\n  VERIFY(cod.isSurjective() == (rank == Cols));\n  VERIFY(cod.isInvertible() == (cod.isInjective() && cod.isSurjective()));\n\n  check_solverbase<Matrix<Scalar, Cols, Cols2>, Matrix<Scalar, Rows, Cols2> >(matrix, cod, Rows, Cols, Cols2);\n\n  // Verify that we get the same minimum-norm solution as the SVD.\n  Matrix<Scalar, Cols, Cols2> exact_solution;\n  exact_solution.setRandom(Cols, Cols2);\n  Matrix<Scalar, Rows, Cols2> rhs = matrix * exact_solution;\n  Matrix<Scalar, Cols, Cols2> cod_solution = cod.solve(rhs);\n  JacobiSVD<MatrixType> svd(matrix, ComputeFullU | ComputeFullV);\n  Matrix<Scalar, Cols, Cols2> svd_solution = svd.solve(rhs);\n  VERIFY_IS_APPROX(cod_solution, svd_solution);\n\n  typename Inverse<COD>::PlainObject pinv = cod.pseudoInverse();\n  VERIFY_IS_APPROX(cod_solution, pinv * rhs);\n}\n\ntemplate<typename MatrixType> void qr()\n{\n  using std::sqrt;\n\n  STATIC_CHECK(( internal::is_same<typename ColPivHouseholderQR<MatrixType>::StorageIndex,int>::value ));\n\n  Index rows = internal::random<Index>(2,EIGEN_TEST_MAX_SIZE), cols = internal::random<Index>(2,EIGEN_TEST_MAX_SIZE), cols2 = internal::random<Index>(2,EIGEN_TEST_MAX_SIZE);\n  Index rank = internal::random<Index>(1, (std::min)(rows, cols)-1);\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> MatrixQType;\n  MatrixType m1;\n  createRandomPIMatrixOfRank(rank,rows,cols,m1);\n  ColPivHouseholderQR<MatrixType> qr(m1);\n  VERIFY_IS_EQUAL(rank, qr.rank());\n  VERIFY_IS_EQUAL(cols - qr.rank(), qr.dimensionOfKernel());\n  VERIFY(!qr.isInjective());\n  VERIFY(!qr.isInvertible());\n  VERIFY(!qr.isSurjective());\n\n  MatrixQType q = qr.householderQ();\n  VERIFY_IS_UNITARY(q);\n\n  MatrixType r = qr.matrixQR().template triangularView<Upper>();\n  MatrixType c = q * r * qr.colsPermutation().inverse();\n  VERIFY_IS_APPROX(m1, c);\n\n  // Verify that the absolute value of the diagonal elements in R are\n  // non-increasing until they reach the singularity threshold.\n  RealScalar threshold =\n      sqrt(RealScalar(rows)) * numext::abs(r(0, 0)) * NumTraits<Scalar>::epsilon();\n  for (Index i = 0; i < (std::min)(rows, cols) - 1; ++i) {\n    RealScalar x = numext::abs(r(i, i));\n    RealScalar y = numext::abs(r(i + 1, i + 1));\n    if (x < threshold && y < threshold) continue;\n    if (!test_isApproxOrLessThan(y, x)) {\n      for (Index j = 0; j < (std::min)(rows, cols); ++j) {\n        std::cout << \"i = \" << j << \", |r_ii| = \" << numext::abs(r(j, j)) << std::endl;\n      }\n      std::cout << \"Failure at i=\" << i << \", rank=\" << rank\n                << \", threshold=\" << threshold << std::endl;\n    }\n    VERIFY_IS_APPROX_OR_LESS_THAN(y, x);\n  }\n\n  check_solverbase<MatrixType, MatrixType>(m1, qr, rows, cols, cols2);\n\n  {\n    MatrixType m2, m3;\n    Index size = rows;\n    do {\n      m1 = MatrixType::Random(size,size);\n      qr.compute(m1);\n    } while(!qr.isInvertible());\n    MatrixType m1_inv = qr.inverse();\n    m3 = m1 * MatrixType::Random(size,cols2);\n    m2 = qr.solve(m3);\n    VERIFY_IS_APPROX(m2, m1_inv*m3);\n  }\n}\n\ntemplate<typename MatrixType, int Cols2> void qr_fixedsize()\n{\n  using std::sqrt;\n  using std::abs;\n  enum { Rows = MatrixType::RowsAtCompileTime, Cols = MatrixType::ColsAtCompileTime };\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  int rank = internal::random<int>(1, (std::min)(int(Rows), int(Cols))-1);\n  Matrix<Scalar,Rows,Cols> m1;\n  createRandomPIMatrixOfRank(rank,Rows,Cols,m1);\n  ColPivHouseholderQR<Matrix<Scalar,Rows,Cols> > qr(m1);\n  VERIFY_IS_EQUAL(rank, qr.rank());\n  VERIFY_IS_EQUAL(Cols - qr.rank(), qr.dimensionOfKernel());\n  VERIFY_IS_EQUAL(qr.isInjective(), (rank == Rows));\n  VERIFY_IS_EQUAL(qr.isSurjective(), (rank == Cols));\n  VERIFY_IS_EQUAL(qr.isInvertible(), (qr.isInjective() && qr.isSurjective()));\n\n  Matrix<Scalar,Rows,Cols> r = qr.matrixQR().template triangularView<Upper>();\n  Matrix<Scalar,Rows,Cols> c = qr.householderQ() * r * qr.colsPermutation().inverse();\n  VERIFY_IS_APPROX(m1, c);\n\n  check_solverbase<Matrix<Scalar,Cols,Cols2>, Matrix<Scalar,Rows,Cols2> >(m1, qr, Rows, Cols, Cols2);\n\n  // Verify that the absolute value of the diagonal elements in R are\n  // non-increasing until they reache the singularity threshold.\n  RealScalar threshold =\n      sqrt(RealScalar(Rows)) * (std::abs)(r(0, 0)) * NumTraits<Scalar>::epsilon();\n  for (Index i = 0; i < (std::min)(int(Rows), int(Cols)) - 1; ++i) {\n    RealScalar x = numext::abs(r(i, i));\n    RealScalar y = numext::abs(r(i + 1, i + 1));\n    if (x < threshold && y < threshold) continue;\n    if (!test_isApproxOrLessThan(y, x)) {\n      for (Index j = 0; j < (std::min)(int(Rows), int(Cols)); ++j) {\n        std::cout << \"i = \" << j << \", |r_ii| = \" << numext::abs(r(j, j)) << std::endl;\n      }\n      std::cout << \"Failure at i=\" << i << \", rank=\" << rank\n                << \", threshold=\" << threshold << std::endl;\n    }\n    VERIFY_IS_APPROX_OR_LESS_THAN(y, x);\n  }\n}\n\n// This test is meant to verify that pivots are chosen such that\n// even for a graded matrix, the diagonal of R falls of roughly\n// monotonically until it reaches the threshold for singularity.\n// We use the so-called Kahan matrix, which is a famous counter-example\n// for rank-revealing QR. See\n// http://www.netlib.org/lapack/lawnspdf/lawn176.pdf\n// page 3 for more detail.\ntemplate<typename MatrixType> void qr_kahan_matrix()\n{\n  using std::sqrt;\n  using std::abs;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n\n  Index rows = 300, cols = rows;\n\n  MatrixType m1;\n  m1.setZero(rows,cols);\n  RealScalar s = std::pow(NumTraits<RealScalar>::epsilon(), 1.0 / rows);\n  RealScalar c = std::sqrt(1 - s*s);\n  RealScalar pow_s_i(1.0); // pow(s,i)\n  for (Index i = 0; i < rows; ++i) {\n    m1(i, i) = pow_s_i;\n    m1.row(i).tail(rows - i - 1) = -pow_s_i * c * MatrixType::Ones(1, rows - i - 1);\n    pow_s_i *= s;\n  }\n  m1 = (m1 + m1.transpose()).eval();\n  ColPivHouseholderQR<MatrixType> qr(m1);\n  MatrixType r = qr.matrixQR().template triangularView<Upper>();\n\n  RealScalar threshold =\n      std::sqrt(RealScalar(rows)) * numext::abs(r(0, 0)) * NumTraits<Scalar>::epsilon();\n  for (Index i = 0; i < (std::min)(rows, cols) - 1; ++i) {\n    RealScalar x = numext::abs(r(i, i));\n    RealScalar y = numext::abs(r(i + 1, i + 1));\n    if (x < threshold && y < threshold) continue;\n    if (!test_isApproxOrLessThan(y, x)) {\n      for (Index j = 0; j < (std::min)(rows, cols); ++j) {\n        std::cout << \"i = \" << j << \", |r_ii| = \" << numext::abs(r(j, j)) << std::endl;\n      }\n      std::cout << \"Failure at i=\" << i << \", rank=\" << qr.rank()\n                << \", threshold=\" << threshold << std::endl;\n    }\n    VERIFY_IS_APPROX_OR_LESS_THAN(y, x);\n  }\n}\n\ntemplate<typename MatrixType> void qr_invertible()\n{\n  using std::log;\n  using std::abs;\n  typedef typename NumTraits<typename MatrixType::Scalar>::Real RealScalar;\n  typedef typename MatrixType::Scalar Scalar;\n\n  int size = internal::random<int>(10,50);\n\n  MatrixType m1(size, size), m2(size, size), m3(size, size);\n  m1 = MatrixType::Random(size,size);\n\n  if (internal::is_same<RealScalar,float>::value)\n  {\n    // let's build a matrix more stable to inverse\n    MatrixType a = MatrixType::Random(size,size*2);\n    m1 += a * a.adjoint();\n  }\n\n  ColPivHouseholderQR<MatrixType> qr(m1);\n\n  check_solverbase<MatrixType, MatrixType>(m1, qr, size, size, size);\n\n  // now construct a matrix with prescribed determinant\n  m1.setZero();\n  for(int i = 0; i < size; i++) m1(i,i) = internal::random<Scalar>();\n  RealScalar absdet = abs(m1.diagonal().prod());\n  m3 = qr.householderQ(); // get a unitary\n  m1 = m3 * m1 * m3;\n  qr.compute(m1);\n  VERIFY_IS_APPROX(absdet, qr.absDeterminant());\n  VERIFY_IS_APPROX(log(absdet), qr.logAbsDeterminant());\n}\n\ntemplate<typename MatrixType> void qr_verify_assert()\n{\n  MatrixType tmp;\n\n  ColPivHouseholderQR<MatrixType> qr;\n  VERIFY_RAISES_ASSERT(qr.matrixQR())\n  VERIFY_RAISES_ASSERT(qr.solve(tmp))\n  VERIFY_RAISES_ASSERT(qr.transpose().solve(tmp))\n  VERIFY_RAISES_ASSERT(qr.adjoint().solve(tmp))\n  VERIFY_RAISES_ASSERT(qr.householderQ())\n  VERIFY_RAISES_ASSERT(qr.dimensionOfKernel())\n  VERIFY_RAISES_ASSERT(qr.isInjective())\n  VERIFY_RAISES_ASSERT(qr.isSurjective())\n  VERIFY_RAISES_ASSERT(qr.isInvertible())\n  VERIFY_RAISES_ASSERT(qr.inverse())\n  VERIFY_RAISES_ASSERT(qr.absDeterminant())\n  VERIFY_RAISES_ASSERT(qr.logAbsDeterminant())\n}\n\ntemplate<typename MatrixType> void cod_verify_assert()\n{\n  MatrixType tmp;\n\n  CompleteOrthogonalDecomposition<MatrixType> cod;\n  VERIFY_RAISES_ASSERT(cod.matrixQTZ())\n  VERIFY_RAISES_ASSERT(cod.solve(tmp))\n  VERIFY_RAISES_ASSERT(cod.transpose().solve(tmp))\n  VERIFY_RAISES_ASSERT(cod.adjoint().solve(tmp))\n  VERIFY_RAISES_ASSERT(cod.householderQ())\n  VERIFY_RAISES_ASSERT(cod.dimensionOfKernel())\n  VERIFY_RAISES_ASSERT(cod.isInjective())\n  VERIFY_RAISES_ASSERT(cod.isSurjective())\n  VERIFY_RAISES_ASSERT(cod.isInvertible())\n  VERIFY_RAISES_ASSERT(cod.pseudoInverse())\n  VERIFY_RAISES_ASSERT(cod.absDeterminant())\n  VERIFY_RAISES_ASSERT(cod.logAbsDeterminant())\n}\n\nEIGEN_DECLARE_TEST(qr_colpivoting)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( qr<MatrixXf>() );\n    CALL_SUBTEST_2( qr<MatrixXd>() );\n    CALL_SUBTEST_3( qr<MatrixXcd>() );\n    CALL_SUBTEST_4(( qr_fixedsize<Matrix<float,3,5>, 4 >() ));\n    CALL_SUBTEST_5(( qr_fixedsize<Matrix<double,6,2>, 3 >() ));\n    CALL_SUBTEST_5(( qr_fixedsize<Matrix<double,1,1>, 1 >() ));\n  }\n\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( cod<MatrixXf>() );\n    CALL_SUBTEST_2( cod<MatrixXd>() );\n    CALL_SUBTEST_3( cod<MatrixXcd>() );\n    CALL_SUBTEST_4(( cod_fixedsize<Matrix<float,3,5>, 4 >() ));\n    CALL_SUBTEST_5(( cod_fixedsize<Matrix<double,6,2>, 3 >() ));\n    CALL_SUBTEST_5(( cod_fixedsize<Matrix<double,1,1>, 1 >() ));\n  }\n\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( qr_invertible<MatrixXf>() );\n    CALL_SUBTEST_2( qr_invertible<MatrixXd>() );\n    CALL_SUBTEST_6( qr_invertible<MatrixXcf>() );\n    CALL_SUBTEST_3( qr_invertible<MatrixXcd>() );\n  }\n\n  CALL_SUBTEST_7(qr_verify_assert<Matrix3f>());\n  CALL_SUBTEST_8(qr_verify_assert<Matrix3d>());\n  CALL_SUBTEST_1(qr_verify_assert<MatrixXf>());\n  CALL_SUBTEST_2(qr_verify_assert<MatrixXd>());\n  CALL_SUBTEST_6(qr_verify_assert<MatrixXcf>());\n  CALL_SUBTEST_3(qr_verify_assert<MatrixXcd>());\n\n  CALL_SUBTEST_7(cod_verify_assert<Matrix3f>());\n  CALL_SUBTEST_8(cod_verify_assert<Matrix3d>());\n  CALL_SUBTEST_1(cod_verify_assert<MatrixXf>());\n  CALL_SUBTEST_2(cod_verify_assert<MatrixXd>());\n  CALL_SUBTEST_6(cod_verify_assert<MatrixXcf>());\n  CALL_SUBTEST_3(cod_verify_assert<MatrixXcd>());\n\n  // Test problem size constructors\n  CALL_SUBTEST_9(ColPivHouseholderQR<MatrixXf>(10, 20));\n\n  CALL_SUBTEST_1( qr_kahan_matrix<MatrixXf>() );\n  CALL_SUBTEST_2( qr_kahan_matrix<MatrixXd>() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/qr_fullpivoting.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/QR>\n#include \"solverbase.h\"\n\ntemplate<typename MatrixType> void qr()\n{\n  STATIC_CHECK(( internal::is_same<typename FullPivHouseholderQR<MatrixType>::StorageIndex,int>::value ));\n\n  static const int Rows = MatrixType::RowsAtCompileTime, Cols = MatrixType::ColsAtCompileTime;\n  Index max_size = EIGEN_TEST_MAX_SIZE;\n  Index min_size = numext::maxi(1,EIGEN_TEST_MAX_SIZE/10);\n  Index rows  = Rows == Dynamic ? internal::random<Index>(min_size,max_size) : Rows,\n        cols  = Cols == Dynamic ? internal::random<Index>(min_size,max_size) : Cols,\n        cols2 = Cols == Dynamic ? internal::random<Index>(min_size,max_size) : Cols,\n        rank  = internal::random<Index>(1, (std::min)(rows, cols)-1);\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> MatrixQType;\n  MatrixType m1;\n  createRandomPIMatrixOfRank(rank,rows,cols,m1);\n  FullPivHouseholderQR<MatrixType> qr(m1);\n  VERIFY_IS_EQUAL(rank, qr.rank());\n  VERIFY_IS_EQUAL(cols - qr.rank(), qr.dimensionOfKernel());\n  VERIFY(!qr.isInjective());\n  VERIFY(!qr.isInvertible());\n  VERIFY(!qr.isSurjective());\n\n  MatrixType r = qr.matrixQR();\n  \n  MatrixQType q = qr.matrixQ();\n  VERIFY_IS_UNITARY(q);\n  \n  // FIXME need better way to construct trapezoid\n  for(int i = 0; i < rows; i++) for(int j = 0; j < cols; j++) if(i>j) r(i,j) = Scalar(0);\n\n  MatrixType c = qr.matrixQ() * r * qr.colsPermutation().inverse();\n\n  VERIFY_IS_APPROX(m1, c);\n  \n  // stress the ReturnByValue mechanism\n  MatrixType tmp;\n  VERIFY_IS_APPROX(tmp.noalias() = qr.matrixQ() * r, (qr.matrixQ() * r).eval());\n  \n  check_solverbase<MatrixType, MatrixType>(m1, qr, rows, cols, cols2);\n\n  {\n    MatrixType m2, m3;\n    Index size = rows;\n    do {\n      m1 = MatrixType::Random(size,size);\n      qr.compute(m1);\n    } while(!qr.isInvertible());\n    MatrixType m1_inv = qr.inverse();\n    m3 = m1 * MatrixType::Random(size,cols2);\n    m2 = qr.solve(m3);\n    VERIFY_IS_APPROX(m2, m1_inv*m3);\n  }\n}\n\ntemplate<typename MatrixType> void qr_invertible()\n{\n  using std::log;\n  using std::abs;\n  typedef typename NumTraits<typename MatrixType::Scalar>::Real RealScalar;\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index max_size = numext::mini(50,EIGEN_TEST_MAX_SIZE);\n  Index min_size = numext::maxi(1,EIGEN_TEST_MAX_SIZE/10);\n  Index size = internal::random<Index>(min_size,max_size);\n\n  MatrixType m1(size, size), m2(size, size), m3(size, size);\n  m1 = MatrixType::Random(size,size);\n\n  if (internal::is_same<RealScalar,float>::value)\n  {\n    // let's build a matrix more stable to inverse\n    MatrixType a = MatrixType::Random(size,size*2);\n    m1 += a * a.adjoint();\n  }\n\n  FullPivHouseholderQR<MatrixType> qr(m1);\n  VERIFY(qr.isInjective());\n  VERIFY(qr.isInvertible());\n  VERIFY(qr.isSurjective());\n\n  check_solverbase<MatrixType, MatrixType>(m1, qr, size, size, size);\n\n  // now construct a matrix with prescribed determinant\n  m1.setZero();\n  for(int i = 0; i < size; i++) m1(i,i) = internal::random<Scalar>();\n  RealScalar absdet = abs(m1.diagonal().prod());\n  m3 = qr.matrixQ(); // get a unitary\n  m1 = m3 * m1 * m3;\n  qr.compute(m1);\n  VERIFY_IS_APPROX(absdet, qr.absDeterminant());\n  VERIFY_IS_APPROX(log(absdet), qr.logAbsDeterminant());\n}\n\ntemplate<typename MatrixType> void qr_verify_assert()\n{\n  MatrixType tmp;\n\n  FullPivHouseholderQR<MatrixType> qr;\n  VERIFY_RAISES_ASSERT(qr.matrixQR())\n  VERIFY_RAISES_ASSERT(qr.solve(tmp))\n  VERIFY_RAISES_ASSERT(qr.transpose().solve(tmp))\n  VERIFY_RAISES_ASSERT(qr.adjoint().solve(tmp))\n  VERIFY_RAISES_ASSERT(qr.matrixQ())\n  VERIFY_RAISES_ASSERT(qr.dimensionOfKernel())\n  VERIFY_RAISES_ASSERT(qr.isInjective())\n  VERIFY_RAISES_ASSERT(qr.isSurjective())\n  VERIFY_RAISES_ASSERT(qr.isInvertible())\n  VERIFY_RAISES_ASSERT(qr.inverse())\n  VERIFY_RAISES_ASSERT(qr.absDeterminant())\n  VERIFY_RAISES_ASSERT(qr.logAbsDeterminant())\n}\n\nEIGEN_DECLARE_TEST(qr_fullpivoting)\n{\n  for(int i = 0; i < 1; i++) {\n    CALL_SUBTEST_5( qr<Matrix3f>() );\n    CALL_SUBTEST_6( qr<Matrix3d>() );\n    CALL_SUBTEST_8( qr<Matrix2f>() );\n    CALL_SUBTEST_1( qr<MatrixXf>() );\n    CALL_SUBTEST_2( qr<MatrixXd>() );\n    CALL_SUBTEST_3( qr<MatrixXcd>() );\n  }\n\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( qr_invertible<MatrixXf>() );\n    CALL_SUBTEST_2( qr_invertible<MatrixXd>() );\n    CALL_SUBTEST_4( qr_invertible<MatrixXcf>() );\n    CALL_SUBTEST_3( qr_invertible<MatrixXcd>() );\n  }\n\n  CALL_SUBTEST_5(qr_verify_assert<Matrix3f>());\n  CALL_SUBTEST_6(qr_verify_assert<Matrix3d>());\n  CALL_SUBTEST_1(qr_verify_assert<MatrixXf>());\n  CALL_SUBTEST_2(qr_verify_assert<MatrixXd>());\n  CALL_SUBTEST_4(qr_verify_assert<MatrixXcf>());\n  CALL_SUBTEST_3(qr_verify_assert<MatrixXcd>());\n\n  // Test problem size constructors\n  CALL_SUBTEST_7(FullPivHouseholderQR<MatrixXf>(10, 20));\n  CALL_SUBTEST_7((FullPivHouseholderQR<Matrix<float,10,20> >(10,20)));\n  CALL_SUBTEST_7((FullPivHouseholderQR<Matrix<float,10,20> >(Matrix<float,10,20>::Random())));\n  CALL_SUBTEST_7((FullPivHouseholderQR<Matrix<float,20,10> >(20,10)));\n  CALL_SUBTEST_7((FullPivHouseholderQR<Matrix<float,20,10> >(Matrix<float,20,10>::Random())));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/qtvector.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_WORK_AROUND_QT_BUG_CALLING_WRONG_OPERATOR_NEW_FIXED_IN_QT_4_5\n\n#include \"main.h\"\n#include <QtCore/QVector>\n#include <Eigen/Geometry>\n#include <Eigen/QtAlignedMalloc>\n\ntemplate<typename MatrixType>\nvoid check_qtvector_matrix(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n  MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols);\n  QVector<MatrixType> v(10, MatrixType(rows,cols)), w(20, y);\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], y);\n  }\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.fill(y,22);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n  VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(MatrixType));\n\n  // do a lot of push_back such that the vector gets internally resized\n  // (with memory reallocation)\n  MatrixType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(int i=23; i<v.size(); ++i)\n  {\n    VERIFY(v[i]==w[(i-23)%w.size()]);\n  }\n}\n\ntemplate<typename TransformType>\nvoid check_qtvector_transform(const TransformType&)\n{\n  typedef typename TransformType::MatrixType MatrixType;\n  TransformType x(MatrixType::Random()), y(MatrixType::Random());\n  QVector<TransformType> v(10), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.fill(y,22);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n  VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(TransformType));\n\n  // do a lot of push_back such that the vector gets internally resized\n  // (with memory reallocation)\n  TransformType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; int(i)<v.size(); ++i)\n  {\n    VERIFY(v[i].matrix()==w[(i-23)%w.size()].matrix());\n  }\n}\n\ntemplate<typename QuaternionType>\nvoid check_qtvector_quaternion(const QuaternionType&)\n{\n  typedef typename QuaternionType::Coefficients Coefficients;\n  QuaternionType x(Coefficients::Random()), y(Coefficients::Random());\n  QVector<QuaternionType> v(10), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.fill(y,22);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n  VERIFY((size_t)&(v[22]) == (size_t)&(v[21]) + sizeof(QuaternionType));\n\n  // do a lot of push_back such that the vector gets internally resized\n  // (with memory reallocation)\n  QuaternionType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; int(i)<v.size(); ++i)\n  {\n    VERIFY(v[i].coeffs()==w[(i-23)%w.size()].coeffs());\n  }\n}\n\nEIGEN_DECLARE_TEST(qtvector)\n{\n  // some non vectorizable fixed sizes\n  CALL_SUBTEST(check_qtvector_matrix(Vector2f()));\n  CALL_SUBTEST(check_qtvector_matrix(Matrix3f()));\n  CALL_SUBTEST(check_qtvector_matrix(Matrix3d()));\n\n  // some vectorizable fixed sizes\n  CALL_SUBTEST(check_qtvector_matrix(Matrix2f()));\n  CALL_SUBTEST(check_qtvector_matrix(Vector4f()));\n  CALL_SUBTEST(check_qtvector_matrix(Matrix4f()));\n  CALL_SUBTEST(check_qtvector_matrix(Matrix4d()));\n\n  // some dynamic sizes\n  CALL_SUBTEST(check_qtvector_matrix(MatrixXd(1,1)));\n  CALL_SUBTEST(check_qtvector_matrix(VectorXd(20)));\n  CALL_SUBTEST(check_qtvector_matrix(RowVectorXf(20)));\n  CALL_SUBTEST(check_qtvector_matrix(MatrixXcf(10,10)));\n\n  // some Transform\n  CALL_SUBTEST(check_qtvector_transform(Affine2f()));\n  CALL_SUBTEST(check_qtvector_transform(Affine3f()));\n  CALL_SUBTEST(check_qtvector_transform(Affine3d()));\n  //CALL_SUBTEST(check_qtvector_transform(Transform4d()));\n\n  // some Quaternion\n  CALL_SUBTEST(check_qtvector_quaternion(Quaternionf()));\n  CALL_SUBTEST(check_qtvector_quaternion(Quaternionf()));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/rand.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntypedef long long int64;\n\ntemplate<typename Scalar> Scalar check_in_range(Scalar x, Scalar y)\n{\n  Scalar r = internal::random<Scalar>(x,y);\n  VERIFY(r>=x);\n  if(y>=x)\n  {\n    VERIFY(r<=y);\n  }\n  return r;\n}\n\ntemplate<typename Scalar> void check_all_in_range(Scalar x, Scalar y)\n{\n  Array<int,1,Dynamic> mask(y-x+1);\n  mask.fill(0);\n  long n = (y-x+1)*32;\n  for(long k=0; k<n; ++k)\n  {\n    mask( check_in_range(x,y)-x )++;\n  }\n  for(Index i=0; i<mask.size(); ++i)\n    if(mask(i)==0)\n      std::cout << \"WARNING: value \" << x+i << \" not reached.\" << std::endl;\n  VERIFY( (mask>0).all() );\n}\n\ntemplate<typename Scalar> void check_histogram(Scalar x, Scalar y, int bins)\n{\n  Array<int,1,Dynamic> hist(bins);\n  hist.fill(0);\n  int f = 100000;\n  int n = bins*f;\n  int64 range = int64(y)-int64(x);\n  int divisor = int((range+1)/bins);\n  assert(((range+1)%bins)==0);\n  for(int k=0; k<n; ++k)\n  {\n    Scalar r = check_in_range(x,y);\n    hist( int((int64(r)-int64(x))/divisor) )++;\n  }\n  VERIFY( (((hist.cast<double>()/double(f))-1.0).abs()<0.03).all() );\n}\n\nEIGEN_DECLARE_TEST(rand)\n{\n  long long_ref = NumTraits<long>::highest()/10;\n  signed char char_offset = (std::min)(g_repeat,64);\n  signed char short_offset = (std::min)(g_repeat,16000);\n\n  for(int i = 0; i < g_repeat*10000; i++) {\n    CALL_SUBTEST(check_in_range<float>(10,11));\n    CALL_SUBTEST(check_in_range<float>(1.24234523,1.24234523));\n    CALL_SUBTEST(check_in_range<float>(-1,1));\n    CALL_SUBTEST(check_in_range<float>(-1432.2352,-1432.2352));\n\n    CALL_SUBTEST(check_in_range<double>(10,11));\n    CALL_SUBTEST(check_in_range<double>(1.24234523,1.24234523));\n    CALL_SUBTEST(check_in_range<double>(-1,1));\n    CALL_SUBTEST(check_in_range<double>(-1432.2352,-1432.2352));\n\n    CALL_SUBTEST(check_in_range<int>(0,-1));\n    CALL_SUBTEST(check_in_range<short>(0,-1));\n    CALL_SUBTEST(check_in_range<long>(0,-1));\n    CALL_SUBTEST(check_in_range<int>(-673456,673456));\n    CALL_SUBTEST(check_in_range<int>(-RAND_MAX+10,RAND_MAX-10));\n    CALL_SUBTEST(check_in_range<short>(-24345,24345));\n    CALL_SUBTEST(check_in_range<long>(-long_ref,long_ref));\n  }\n\n  CALL_SUBTEST(check_all_in_range<signed char>(11,11));\n  CALL_SUBTEST(check_all_in_range<signed char>(11,11+char_offset));\n  CALL_SUBTEST(check_all_in_range<signed char>(-5,5));\n  CALL_SUBTEST(check_all_in_range<signed char>(-11-char_offset,-11));\n  CALL_SUBTEST(check_all_in_range<signed char>(-126,-126+char_offset));\n  CALL_SUBTEST(check_all_in_range<signed char>(126-char_offset,126));\n  CALL_SUBTEST(check_all_in_range<signed char>(-126,126));\n\n  CALL_SUBTEST(check_all_in_range<short>(11,11));\n  CALL_SUBTEST(check_all_in_range<short>(11,11+short_offset));\n  CALL_SUBTEST(check_all_in_range<short>(-5,5));\n  CALL_SUBTEST(check_all_in_range<short>(-11-short_offset,-11));\n  CALL_SUBTEST(check_all_in_range<short>(-24345,-24345+short_offset));\n  CALL_SUBTEST(check_all_in_range<short>(24345,24345+short_offset));\n\n  CALL_SUBTEST(check_all_in_range<int>(11,11));\n  CALL_SUBTEST(check_all_in_range<int>(11,11+g_repeat));\n  CALL_SUBTEST(check_all_in_range<int>(-5,5));\n  CALL_SUBTEST(check_all_in_range<int>(-11-g_repeat,-11));\n  CALL_SUBTEST(check_all_in_range<int>(-673456,-673456+g_repeat));\n  CALL_SUBTEST(check_all_in_range<int>(673456,673456+g_repeat));\n\n  CALL_SUBTEST(check_all_in_range<long>(11,11));\n  CALL_SUBTEST(check_all_in_range<long>(11,11+g_repeat));\n  CALL_SUBTEST(check_all_in_range<long>(-5,5));\n  CALL_SUBTEST(check_all_in_range<long>(-11-g_repeat,-11));\n  CALL_SUBTEST(check_all_in_range<long>(-long_ref,-long_ref+g_repeat));\n  CALL_SUBTEST(check_all_in_range<long>( long_ref, long_ref+g_repeat));\n\n  CALL_SUBTEST(check_histogram<int>(-5,5,11));\n  int bins = 100;\n  CALL_SUBTEST(check_histogram<int>(-3333,-3333+bins*(3333/bins)-1,bins));\n  bins = 1000;\n  CALL_SUBTEST(check_histogram<int>(-RAND_MAX+10,-RAND_MAX+10+bins*(RAND_MAX/bins)-1,bins));\n  CALL_SUBTEST(check_histogram<int>(-RAND_MAX+10,-int64(RAND_MAX)+10+bins*(2*int64(RAND_MAX)/bins)-1,bins));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/random_without_cast_overflow.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2020 C. Antonio Sanchez <cantonios@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// Utilities for generating random numbers without overflows, which might\n// otherwise result in undefined behavior.\n\nnamespace Eigen {\nnamespace internal {\n\n// Default implementation assuming SrcScalar fits into TgtScalar.\ntemplate <typename SrcScalar, typename TgtScalar, typename EnableIf = void>\nstruct random_without_cast_overflow {\n  static SrcScalar value() { return internal::random<SrcScalar>(); }\n};\n\n// Signed to unsigned integer widening cast.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<NumTraits<SrcScalar>::IsInteger && NumTraits<TgtScalar>::IsInteger &&\n                                 !NumTraits<TgtScalar>::IsSigned &&\n                                 (std::numeric_limits<SrcScalar>::digits < std::numeric_limits<TgtScalar>::digits ||\n                                  (std::numeric_limits<SrcScalar>::digits == std::numeric_limits<TgtScalar>::digits &&\n                                   NumTraits<SrcScalar>::IsSigned))>::type> {\n  static SrcScalar value() {\n    SrcScalar a = internal::random<SrcScalar>();\n    return a < SrcScalar(0) ? -(a + 1) : a;\n  }\n};\n\n// Integer to unsigned narrowing cast.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<\n        NumTraits<SrcScalar>::IsInteger && NumTraits<TgtScalar>::IsInteger && !NumTraits<SrcScalar>::IsSigned &&\n        (std::numeric_limits<SrcScalar>::digits > std::numeric_limits<TgtScalar>::digits)>::type> {\n  static SrcScalar value() {\n    TgtScalar b = internal::random<TgtScalar>();\n    return static_cast<SrcScalar>(b < TgtScalar(0) ? -(b + 1) : b);\n  }\n};\n\n// Integer to signed narrowing cast.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<\n        NumTraits<SrcScalar>::IsInteger && NumTraits<TgtScalar>::IsInteger && NumTraits<SrcScalar>::IsSigned &&\n        (std::numeric_limits<SrcScalar>::digits > std::numeric_limits<TgtScalar>::digits)>::type> {\n  static SrcScalar value() { return static_cast<SrcScalar>(internal::random<TgtScalar>()); }\n};\n\n// Unsigned to signed integer narrowing cast.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<NumTraits<SrcScalar>::IsInteger && NumTraits<TgtScalar>::IsInteger &&\n                                 !NumTraits<SrcScalar>::IsSigned && NumTraits<TgtScalar>::IsSigned &&\n                                 (std::numeric_limits<SrcScalar>::digits ==\n                                  std::numeric_limits<TgtScalar>::digits)>::type> {\n  static SrcScalar value() { return internal::random<SrcScalar>() / 2; }\n};\n\n// Floating-point to integer, full precision.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<\n        !NumTraits<SrcScalar>::IsInteger && !NumTraits<SrcScalar>::IsComplex && NumTraits<TgtScalar>::IsInteger &&\n        (std::numeric_limits<TgtScalar>::digits <= std::numeric_limits<SrcScalar>::digits)>::type> {\n  static SrcScalar value() { return static_cast<SrcScalar>(internal::random<TgtScalar>()); }\n};\n\n// Floating-point to integer, narrowing precision.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<\n        !NumTraits<SrcScalar>::IsInteger && !NumTraits<SrcScalar>::IsComplex && NumTraits<TgtScalar>::IsInteger &&\n        (std::numeric_limits<TgtScalar>::digits > std::numeric_limits<SrcScalar>::digits)>::type> {\n  static SrcScalar value() {\n    // NOTE: internal::random<T>() is limited by RAND_MAX, so random<int64_t> is always within that range.\n    // This prevents us from simply shifting bits, which would result in only 0 or -1.\n    // Instead, keep least-significant K bits and sign.\n    static const TgtScalar KeepMask = (static_cast<TgtScalar>(1) << std::numeric_limits<SrcScalar>::digits) - 1;\n    const TgtScalar a = internal::random<TgtScalar>();\n    return static_cast<SrcScalar>(a > TgtScalar(0) ? (a & KeepMask) : -(a & KeepMask));\n  }\n};\n\n// Integer to floating-point, re-use above logic.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<NumTraits<SrcScalar>::IsInteger && !NumTraits<TgtScalar>::IsInteger &&\n                                 !NumTraits<TgtScalar>::IsComplex>::type> {\n  static SrcScalar value() {\n    return static_cast<SrcScalar>(random_without_cast_overflow<TgtScalar, SrcScalar>::value());\n  }\n};\n\n// Floating-point narrowing conversion.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<!NumTraits<SrcScalar>::IsInteger && !NumTraits<SrcScalar>::IsComplex &&\n                                 !NumTraits<TgtScalar>::IsInteger && !NumTraits<TgtScalar>::IsComplex &&\n                                 (std::numeric_limits<SrcScalar>::digits >\n                                  std::numeric_limits<TgtScalar>::digits)>::type> {\n  static SrcScalar value() { return static_cast<SrcScalar>(internal::random<TgtScalar>()); }\n};\n\n// Complex to non-complex.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<NumTraits<SrcScalar>::IsComplex && !NumTraits<TgtScalar>::IsComplex>::type> {\n  typedef typename NumTraits<SrcScalar>::Real SrcReal;\n  static SrcScalar value() { return SrcScalar(random_without_cast_overflow<SrcReal, TgtScalar>::value(), 0); }\n};\n\n// Non-complex to complex.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<!NumTraits<SrcScalar>::IsComplex && NumTraits<TgtScalar>::IsComplex>::type> {\n  typedef typename NumTraits<TgtScalar>::Real TgtReal;\n  static SrcScalar value() { return random_without_cast_overflow<SrcScalar, TgtReal>::value(); }\n};\n\n// Complex to complex.\ntemplate <typename SrcScalar, typename TgtScalar>\nstruct random_without_cast_overflow<\n    SrcScalar, TgtScalar,\n    typename internal::enable_if<NumTraits<SrcScalar>::IsComplex && NumTraits<TgtScalar>::IsComplex>::type> {\n  typedef typename NumTraits<SrcScalar>::Real SrcReal;\n  typedef typename NumTraits<TgtScalar>::Real TgtReal;\n  static SrcScalar value() {\n    return SrcScalar(random_without_cast_overflow<SrcReal, TgtReal>::value(),\n                     random_without_cast_overflow<SrcReal, TgtReal>::value());\n  }\n};\n\n}  // namespace internal\n}  // namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/real_qz.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Alexey Korepanov <kaikaikai@yandex.ru>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_RUNTIME_NO_MALLOC\n#include \"main.h\"\n#include <limits>\n#include <Eigen/Eigenvalues>\n\ntemplate<typename MatrixType> void real_qz(const MatrixType& m)\n{\n  /* this test covers the following files:\n     RealQZ.h\n  */\n  using std::abs;\n  typedef typename MatrixType::Scalar Scalar;\n  \n  Index dim = m.cols();\n  \n  MatrixType A = MatrixType::Random(dim,dim),\n             B = MatrixType::Random(dim,dim);\n\n\n  // Regression test for bug 985: Randomly set rows or columns to zero\n  Index k=internal::random<Index>(0, dim-1);\n  switch(internal::random<int>(0,10)) {\n  case 0:\n    A.row(k).setZero(); break;\n  case 1:\n    A.col(k).setZero(); break;\n  case 2:\n    B.row(k).setZero(); break;\n  case 3:\n    B.col(k).setZero(); break;\n  default:\n    break;\n  }\n\n  RealQZ<MatrixType> qz(dim);\n  // TODO enable full-prealocation of required memory, this probably requires an in-place mode for HessenbergDecomposition\n  //Eigen::internal::set_is_malloc_allowed(false);\n  qz.compute(A,B);\n  //Eigen::internal::set_is_malloc_allowed(true);\n  \n  VERIFY_IS_EQUAL(qz.info(), Success);\n  // check for zeros\n  bool all_zeros = true;\n  for (Index i=0; i<A.cols(); i++)\n    for (Index j=0; j<i; j++) {\n      if (abs(qz.matrixT()(i,j))!=Scalar(0.0))\n      {\n        std::cerr << \"Error: T(\" << i << \",\" << j << \") = \" << qz.matrixT()(i,j) << std::endl;\n        all_zeros = false;\n      }\n      if (j<i-1 && abs(qz.matrixS()(i,j))!=Scalar(0.0))\n      {\n        std::cerr << \"Error: S(\" << i << \",\" << j << \") = \" << qz.matrixS()(i,j) << std::endl;\n        all_zeros = false;\n      }\n      if (j==i-1 && j>0 && abs(qz.matrixS()(i,j))!=Scalar(0.0) && abs(qz.matrixS()(i-1,j-1))!=Scalar(0.0))\n      {\n        std::cerr << \"Error: S(\" << i << \",\" << j << \") = \" << qz.matrixS()(i,j)  << \" && S(\" << i-1 << \",\" << j-1 << \") = \" << qz.matrixS()(i-1,j-1) << std::endl;\n        all_zeros = false;\n      }\n    }\n  VERIFY_IS_EQUAL(all_zeros, true);\n  VERIFY_IS_APPROX(qz.matrixQ()*qz.matrixS()*qz.matrixZ(), A);\n  VERIFY_IS_APPROX(qz.matrixQ()*qz.matrixT()*qz.matrixZ(), B);\n  VERIFY_IS_APPROX(qz.matrixQ()*qz.matrixQ().adjoint(), MatrixType::Identity(dim,dim));\n  VERIFY_IS_APPROX(qz.matrixZ()*qz.matrixZ().adjoint(), MatrixType::Identity(dim,dim));\n}\n\nEIGEN_DECLARE_TEST(real_qz)\n{\n  int s = 0;\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( real_qz(Matrix4f()) );\n    s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4);\n    CALL_SUBTEST_2( real_qz(MatrixXd(s,s)) );\n\n    // some trivial but implementation-wise tricky cases\n    CALL_SUBTEST_2( real_qz(MatrixXd(1,1)) );\n    CALL_SUBTEST_2( real_qz(MatrixXd(2,2)) );\n    CALL_SUBTEST_3( real_qz(Matrix<double,1,1>()) );\n    CALL_SUBTEST_4( real_qz(Matrix2d()) );\n  }\n  \n  TEST_SET_BUT_UNUSED_VARIABLE(s)\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/redux.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define TEST_ENABLE_TEMPORARY_TRACKING\n#define EIGEN_CACHEFRIENDLY_PRODUCT_THRESHOLD 8\n// ^^ see bug 1449\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void matrixRedux(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols);\n\n  // The entries of m1 are uniformly distributed in [0,1], so m1.prod() is very small. This may lead to test\n  // failures if we underflow into denormals. Thus, we scale so that entries are close to 1.\n  MatrixType m1_for_prod = MatrixType::Ones(rows, cols) + RealScalar(0.2) * m1;\n\n  Matrix<Scalar, MatrixType::RowsAtCompileTime, MatrixType::RowsAtCompileTime> m2(rows,rows);\n  m2.setRandom();\n\n  VERIFY_IS_MUCH_SMALLER_THAN(MatrixType::Zero(rows, cols).sum(), Scalar(1));\n  VERIFY_IS_APPROX(MatrixType::Ones(rows, cols).sum(), Scalar(float(rows*cols))); // the float() here to shut up excessive MSVC warning about int->complex conversion being lossy\n  Scalar s(0), p(1), minc(numext::real(m1.coeff(0))), maxc(numext::real(m1.coeff(0)));\n  for(int j = 0; j < cols; j++)\n  for(int i = 0; i < rows; i++)\n  {\n    s += m1(i,j);\n    p *= m1_for_prod(i,j);\n    minc = (std::min)(numext::real(minc), numext::real(m1(i,j)));\n    maxc = (std::max)(numext::real(maxc), numext::real(m1(i,j)));\n  }\n  const Scalar mean = s/Scalar(RealScalar(rows*cols));\n\n  VERIFY_IS_APPROX(m1.sum(), s);\n  VERIFY_IS_APPROX(m1.mean(), mean);\n  VERIFY_IS_APPROX(m1_for_prod.prod(), p);\n  VERIFY_IS_APPROX(m1.real().minCoeff(), numext::real(minc));\n  VERIFY_IS_APPROX(m1.real().maxCoeff(), numext::real(maxc));\n  \n  // test that partial reduction works if nested expressions is forced to evaluate early\n  VERIFY_IS_APPROX((m1.matrix() * m1.matrix().transpose())       .cwiseProduct(m2.matrix()).rowwise().sum().sum(), \n                   (m1.matrix() * m1.matrix().transpose()).eval().cwiseProduct(m2.matrix()).rowwise().sum().sum());\n\n  // test slice vectorization assuming assign is ok\n  Index r0 = internal::random<Index>(0,rows-1);\n  Index c0 = internal::random<Index>(0,cols-1);\n  Index r1 = internal::random<Index>(r0+1,rows)-r0;\n  Index c1 = internal::random<Index>(c0+1,cols)-c0;\n  VERIFY_IS_APPROX(m1.block(r0,c0,r1,c1).sum(), m1.block(r0,c0,r1,c1).eval().sum());\n  VERIFY_IS_APPROX(m1.block(r0,c0,r1,c1).mean(), m1.block(r0,c0,r1,c1).eval().mean());\n  VERIFY_IS_APPROX(m1_for_prod.block(r0,c0,r1,c1).prod(), m1_for_prod.block(r0,c0,r1,c1).eval().prod());\n  VERIFY_IS_APPROX(m1.block(r0,c0,r1,c1).real().minCoeff(), m1.block(r0,c0,r1,c1).real().eval().minCoeff());\n  VERIFY_IS_APPROX(m1.block(r0,c0,r1,c1).real().maxCoeff(), m1.block(r0,c0,r1,c1).real().eval().maxCoeff());\n\n  // regression for bug 1090\n  const int R1 = MatrixType::RowsAtCompileTime>=2 ? MatrixType::RowsAtCompileTime/2 : 6;\n  const int C1 = MatrixType::ColsAtCompileTime>=2 ? MatrixType::ColsAtCompileTime/2 : 6;\n  if(R1<=rows-r0 && C1<=cols-c0)\n  {\n    VERIFY_IS_APPROX( (m1.template block<R1,C1>(r0,c0).sum()), m1.block(r0,c0,R1,C1).sum() );\n  }\n  \n  // test empty objects\n  VERIFY_IS_APPROX(m1.block(r0,c0,0,0).sum(),   Scalar(0));\n  VERIFY_IS_APPROX(m1.block(r0,c0,0,0).prod(),  Scalar(1));\n\n  // test nesting complex expression\n  VERIFY_EVALUATION_COUNT( (m1.matrix()*m1.matrix().transpose()).sum(), (MatrixType::IsVectorAtCompileTime && MatrixType::SizeAtCompileTime!=1 ? 0 : 1) );\n  VERIFY_EVALUATION_COUNT( ((m1.matrix()*m1.matrix().transpose())+m2).sum(),(MatrixType::IsVectorAtCompileTime && MatrixType::SizeAtCompileTime!=1 ? 0 : 1));\n}\n\ntemplate<typename VectorType> void vectorRedux(const VectorType& w)\n{\n  using std::abs;\n  typedef typename VectorType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  Index size = w.size();\n\n  VectorType v = VectorType::Random(size);\n  VectorType v_for_prod = VectorType::Ones(size) + Scalar(0.2) * v; // see comment above declaration of m1_for_prod\n\n  for(int i = 1; i < size; i++)\n  {\n    Scalar s(0), p(1);\n    RealScalar minc(numext::real(v.coeff(0))), maxc(numext::real(v.coeff(0)));\n    for(int j = 0; j < i; j++)\n    {\n      s += v[j];\n      p *= v_for_prod[j];\n      minc = (std::min)(minc, numext::real(v[j]));\n      maxc = (std::max)(maxc, numext::real(v[j]));\n    }\n    VERIFY_IS_MUCH_SMALLER_THAN(abs(s - v.head(i).sum()), Scalar(1));\n    VERIFY_IS_APPROX(p, v_for_prod.head(i).prod());\n    VERIFY_IS_APPROX(minc, v.real().head(i).minCoeff());\n    VERIFY_IS_APPROX(maxc, v.real().head(i).maxCoeff());\n  }\n\n  for(int i = 0; i < size-1; i++)\n  {\n    Scalar s(0), p(1);\n    RealScalar minc(numext::real(v.coeff(i))), maxc(numext::real(v.coeff(i)));\n    for(int j = i; j < size; j++)\n    {\n      s += v[j];\n      p *= v_for_prod[j];\n      minc = (std::min)(minc, numext::real(v[j]));\n      maxc = (std::max)(maxc, numext::real(v[j]));\n    }\n    VERIFY_IS_MUCH_SMALLER_THAN(abs(s - v.tail(size-i).sum()), Scalar(1));\n    VERIFY_IS_APPROX(p, v_for_prod.tail(size-i).prod());\n    VERIFY_IS_APPROX(minc, v.real().tail(size-i).minCoeff());\n    VERIFY_IS_APPROX(maxc, v.real().tail(size-i).maxCoeff());\n  }\n\n  for(int i = 0; i < size/2; i++)\n  {\n    Scalar s(0), p(1);\n    RealScalar minc(numext::real(v.coeff(i))), maxc(numext::real(v.coeff(i)));\n    for(int j = i; j < size-i; j++)\n    {\n      s += v[j];\n      p *= v_for_prod[j];\n      minc = (std::min)(minc, numext::real(v[j]));\n      maxc = (std::max)(maxc, numext::real(v[j]));\n    }\n    VERIFY_IS_MUCH_SMALLER_THAN(abs(s - v.segment(i, size-2*i).sum()), Scalar(1));\n    VERIFY_IS_APPROX(p, v_for_prod.segment(i, size-2*i).prod());\n    VERIFY_IS_APPROX(minc, v.real().segment(i, size-2*i).minCoeff());\n    VERIFY_IS_APPROX(maxc, v.real().segment(i, size-2*i).maxCoeff());\n  }\n  \n  // test empty objects\n  VERIFY_IS_APPROX(v.head(0).sum(),   Scalar(0));\n  VERIFY_IS_APPROX(v.tail(0).prod(),  Scalar(1));\n  VERIFY_RAISES_ASSERT(v.head(0).mean());\n  VERIFY_RAISES_ASSERT(v.head(0).minCoeff());\n  VERIFY_RAISES_ASSERT(v.head(0).maxCoeff());\n}\n\nEIGEN_DECLARE_TEST(redux)\n{\n  // the max size cannot be too large, otherwise reduxion operations obviously generate large errors.\n  int maxsize = (std::min)(100,EIGEN_TEST_MAX_SIZE);\n  TEST_SET_BUT_UNUSED_VARIABLE(maxsize);\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( matrixRedux(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_1( matrixRedux(Array<float, 1, 1>()) );\n    CALL_SUBTEST_2( matrixRedux(Matrix2f()) );\n    CALL_SUBTEST_2( matrixRedux(Array2f()) );\n    CALL_SUBTEST_2( matrixRedux(Array22f()) );\n    CALL_SUBTEST_3( matrixRedux(Matrix4d()) );\n    CALL_SUBTEST_3( matrixRedux(Array4d()) );\n    CALL_SUBTEST_3( matrixRedux(Array44d()) );\n    CALL_SUBTEST_4( matrixRedux(MatrixXcf(internal::random<int>(1,maxsize), internal::random<int>(1,maxsize))) );\n    CALL_SUBTEST_4( matrixRedux(ArrayXXcf(internal::random<int>(1,maxsize), internal::random<int>(1,maxsize))) );\n    CALL_SUBTEST_5( matrixRedux(MatrixXd (internal::random<int>(1,maxsize), internal::random<int>(1,maxsize))) );\n    CALL_SUBTEST_5( matrixRedux(ArrayXXd (internal::random<int>(1,maxsize), internal::random<int>(1,maxsize))) );\n    CALL_SUBTEST_6( matrixRedux(MatrixXi (internal::random<int>(1,maxsize), internal::random<int>(1,maxsize))) );\n    CALL_SUBTEST_6( matrixRedux(ArrayXXi (internal::random<int>(1,maxsize), internal::random<int>(1,maxsize))) );\n  }\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_7( vectorRedux(Vector4f()) );\n    CALL_SUBTEST_7( vectorRedux(Array4f()) );\n    CALL_SUBTEST_5( vectorRedux(VectorXd(internal::random<int>(1,maxsize))) );\n    CALL_SUBTEST_5( vectorRedux(ArrayXd(internal::random<int>(1,maxsize))) );\n    CALL_SUBTEST_8( vectorRedux(VectorXf(internal::random<int>(1,maxsize))) );\n    CALL_SUBTEST_8( vectorRedux(ArrayXf(internal::random<int>(1,maxsize))) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/ref.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 20013 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// This unit test cannot be easily written to work with EIGEN_DEFAULT_TO_ROW_MAJOR\n#ifdef EIGEN_DEFAULT_TO_ROW_MAJOR\n#undef EIGEN_DEFAULT_TO_ROW_MAJOR\n#endif\n\n#define TEST_ENABLE_TEMPORARY_TRACKING\n#define TEST_CHECK_STATIC_ASSERTIONS\n#include \"main.h\"\n\n// test Ref.h\n\n// Deal with i387 extended precision\n#if EIGEN_ARCH_i386 && !(EIGEN_ARCH_x86_64)\n\n#if EIGEN_COMP_GNUC_STRICT && EIGEN_GNUC_AT_LEAST(4,4)\n#pragma GCC optimize (\"-ffloat-store\")\n#else\n#undef VERIFY_IS_EQUAL\n#define VERIFY_IS_EQUAL(X,Y) VERIFY_IS_APPROX(X,Y)\n#endif\n\n#endif\n\ntemplate<typename MatrixType> void ref_matrix(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef Matrix<Scalar,Dynamic,Dynamic,MatrixType::Options> DynMatrixType;\n  typedef Matrix<RealScalar,Dynamic,Dynamic,MatrixType::Options> RealDynMatrixType;\n  \n  typedef Ref<MatrixType> RefMat;\n  typedef Ref<DynMatrixType> RefDynMat;\n  typedef Ref<const DynMatrixType> ConstRefDynMat;\n  typedef Ref<RealDynMatrixType , 0, Stride<Dynamic,Dynamic> > RefRealMatWithStride;\n\n  Index rows = m.rows(), cols = m.cols();\n  \n  MatrixType  m1 = MatrixType::Random(rows, cols),\n              m2 = m1;\n  \n  Index i = internal::random<Index>(0,rows-1);\n  Index j = internal::random<Index>(0,cols-1);\n  Index brows = internal::random<Index>(1,rows-i);\n  Index bcols = internal::random<Index>(1,cols-j);\n  \n  RefMat rm0 = m1;\n  VERIFY_IS_EQUAL(rm0, m1);\n  RefDynMat rm1 = m1;\n  VERIFY_IS_EQUAL(rm1, m1);\n  RefDynMat rm2 = m1.block(i,j,brows,bcols);\n  VERIFY_IS_EQUAL(rm2, m1.block(i,j,brows,bcols));\n  rm2.setOnes();\n  m2.block(i,j,brows,bcols).setOnes();\n  VERIFY_IS_EQUAL(m1, m2);\n  \n  m2.block(i,j,brows,bcols).setRandom();\n  rm2 = m2.block(i,j,brows,bcols);\n  VERIFY_IS_EQUAL(m1, m2);\n  \n  ConstRefDynMat rm3 = m1.block(i,j,brows,bcols);\n  m1.block(i,j,brows,bcols) *= 2;\n  m2.block(i,j,brows,bcols) *= 2;\n  VERIFY_IS_EQUAL(rm3, m2.block(i,j,brows,bcols));\n  RefRealMatWithStride rm4 = m1.real();\n  VERIFY_IS_EQUAL(rm4, m2.real());\n  rm4.array() += 1;\n  m2.real().array() += 1;\n  VERIFY_IS_EQUAL(m1, m2);\n}\n\ntemplate<typename VectorType> void ref_vector(const VectorType& m)\n{\n  typedef typename VectorType::Scalar Scalar;\n  typedef typename VectorType::RealScalar RealScalar;\n  typedef Matrix<Scalar,Dynamic,1,VectorType::Options> DynMatrixType;\n  typedef Matrix<Scalar,Dynamic,Dynamic,ColMajor> MatrixType;\n  typedef Matrix<RealScalar,Dynamic,1,VectorType::Options> RealDynMatrixType;\n  \n  typedef Ref<VectorType> RefMat;\n  typedef Ref<DynMatrixType> RefDynMat;\n  typedef Ref<const DynMatrixType> ConstRefDynMat;\n  typedef Ref<RealDynMatrixType , 0, InnerStride<> > RefRealMatWithStride;\n  typedef Ref<DynMatrixType , 0, InnerStride<> > RefMatWithStride;\n\n  Index size = m.size();\n  \n  VectorType  v1 = VectorType::Random(size),\n              v2 = v1;\n  MatrixType mat1 = MatrixType::Random(size,size),\n             mat2 = mat1,\n             mat3 = MatrixType::Random(size,size);\n  \n  Index i = internal::random<Index>(0,size-1);\n  Index bsize = internal::random<Index>(1,size-i);\n  \n  { RefMat    rm0 = v1;                   VERIFY_IS_EQUAL(rm0, v1); }\n  { RefMat    rm0 = v1.block(0,0,size,1); VERIFY_IS_EQUAL(rm0, v1); }\n  { RefDynMat rv1 = v1;                   VERIFY_IS_EQUAL(rv1, v1); }\n  { RefDynMat rv1 = v1.block(0,0,size,1); VERIFY_IS_EQUAL(rv1, v1); }\n  { VERIFY_RAISES_ASSERT( RefMat    rm0 = v1.block(0, 0, size, 0); EIGEN_UNUSED_VARIABLE(rm0); ); }\n  if(VectorType::SizeAtCompileTime!=1)\n  { VERIFY_RAISES_ASSERT( RefDynMat rv1 = v1.block(0, 0, size, 0); EIGEN_UNUSED_VARIABLE(rv1); ); }\n\n  RefDynMat rv2 = v1.segment(i,bsize);\n  VERIFY_IS_EQUAL(rv2, v1.segment(i,bsize));\n  rv2.setOnes();\n  v2.segment(i,bsize).setOnes();\n  VERIFY_IS_EQUAL(v1, v2);\n  \n  v2.segment(i,bsize).setRandom();\n  rv2 = v2.segment(i,bsize);\n  VERIFY_IS_EQUAL(v1, v2);\n  \n  ConstRefDynMat rm3 = v1.segment(i,bsize);\n  v1.segment(i,bsize) *= 2;\n  v2.segment(i,bsize) *= 2;\n  VERIFY_IS_EQUAL(rm3, v2.segment(i,bsize));\n  \n  RefRealMatWithStride rm4 = v1.real();\n  VERIFY_IS_EQUAL(rm4, v2.real());\n  rm4.array() += 1;\n  v2.real().array() += 1;\n  VERIFY_IS_EQUAL(v1, v2);\n  \n  RefMatWithStride rm5 = mat1.row(i).transpose();\n  VERIFY_IS_EQUAL(rm5, mat1.row(i).transpose());\n  rm5.array() += 1;\n  mat2.row(i).array() += 1;\n  VERIFY_IS_EQUAL(mat1, mat2);\n  rm5.noalias() = rm4.transpose() * mat3;\n  mat2.row(i) = v2.real().transpose() * mat3;\n  VERIFY_IS_APPROX(mat1, mat2);\n}\n\ntemplate<typename Scalar, int Rows, int Cols>\nvoid ref_vector_fixed_sizes()\n{\n  typedef Matrix<Scalar,Rows,Cols,RowMajor> RowMajorMatrixType;\n  typedef Matrix<Scalar,Rows,Cols,ColMajor> ColMajorMatrixType;\n  typedef Matrix<Scalar,1,Cols> RowVectorType;\n  typedef Matrix<Scalar,Rows,1> ColVectorType;\n  typedef Matrix<Scalar,Cols,1> RowVectorTransposeType;\n  typedef Matrix<Scalar,1,Rows> ColVectorTransposeType;\n  typedef Stride<Dynamic, Dynamic> DynamicStride;\n\n  RowMajorMatrixType mr = RowMajorMatrixType::Random();\n  ColMajorMatrixType mc = ColMajorMatrixType::Random();\n\n  Index i = internal::random<Index>(0,Rows-1);\n  Index j = internal::random<Index>(0,Cols-1);\n\n  // Reference ith row.\n  Ref<RowVectorType, 0, DynamicStride> mr_ri = mr.row(i);\n  VERIFY_IS_EQUAL(mr_ri, mr.row(i));\n  Ref<RowVectorType, 0, DynamicStride> mc_ri = mc.row(i);\n  VERIFY_IS_EQUAL(mc_ri, mc.row(i));\n\n  // Reference jth col.\n  Ref<ColVectorType, 0, DynamicStride> mr_cj = mr.col(j);\n  VERIFY_IS_EQUAL(mr_cj, mr.col(j));\n  Ref<ColVectorType, 0, DynamicStride> mc_cj = mc.col(j);\n  VERIFY_IS_EQUAL(mc_cj, mc.col(j));\n\n  // Reference the transpose of row i.\n  Ref<RowVectorTransposeType, 0, DynamicStride> mr_rit = mr.row(i);\n  VERIFY_IS_EQUAL(mr_rit, mr.row(i).transpose());\n  Ref<RowVectorTransposeType, 0, DynamicStride> mc_rit = mc.row(i);\n  VERIFY_IS_EQUAL(mc_rit, mc.row(i).transpose());\n\n  // Reference the transpose of col j.\n  Ref<ColVectorTransposeType, 0, DynamicStride> mr_cjt = mr.col(j);\n  VERIFY_IS_EQUAL(mr_cjt, mr.col(j).transpose());\n  Ref<ColVectorTransposeType, 0, DynamicStride> mc_cjt = mc.col(j);\n  VERIFY_IS_EQUAL(mc_cjt, mc.col(j).transpose());\n  \n  // Const references without strides.\n  Ref<const RowVectorType> cmr_ri = mr.row(i);\n  VERIFY_IS_EQUAL(cmr_ri, mr.row(i));\n  Ref<const RowVectorType> cmc_ri = mc.row(i);\n  VERIFY_IS_EQUAL(cmc_ri, mc.row(i));\n\n  Ref<const ColVectorType> cmr_cj = mr.col(j);\n  VERIFY_IS_EQUAL(cmr_cj, mr.col(j));\n  Ref<const ColVectorType> cmc_cj = mc.col(j);\n  VERIFY_IS_EQUAL(cmc_cj, mc.col(j));\n\n  Ref<const RowVectorTransposeType> cmr_rit = mr.row(i);\n  VERIFY_IS_EQUAL(cmr_rit, mr.row(i).transpose());\n  Ref<const RowVectorTransposeType> cmc_rit = mc.row(i);\n  VERIFY_IS_EQUAL(cmc_rit, mc.row(i).transpose());\n\n  Ref<const ColVectorTransposeType> cmr_cjt = mr.col(j);\n  VERIFY_IS_EQUAL(cmr_cjt, mr.col(j).transpose());\n  Ref<const ColVectorTransposeType> cmc_cjt = mc.col(j);\n  VERIFY_IS_EQUAL(cmc_cjt, mc.col(j).transpose());\n}\n\ntemplate<typename PlainObjectType> void check_const_correctness(const PlainObjectType&)\n{\n  // verify that ref-to-const don't have LvalueBit\n  typedef typename internal::add_const<PlainObjectType>::type ConstPlainObjectType;\n  VERIFY( !(internal::traits<Ref<ConstPlainObjectType> >::Flags & LvalueBit) );\n  VERIFY( !(internal::traits<Ref<ConstPlainObjectType, Aligned> >::Flags & LvalueBit) );\n  VERIFY( !(Ref<ConstPlainObjectType>::Flags & LvalueBit) );\n  VERIFY( !(Ref<ConstPlainObjectType, Aligned>::Flags & LvalueBit) );\n}\n\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_1(Ref<VectorXf> a, const B &b) { VERIFY_IS_EQUAL(a,b); }\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_2(const Ref<const VectorXf>& a, const B &b) { VERIFY_IS_EQUAL(a,b); }\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_3(Ref<VectorXf,0,InnerStride<> > a, const B &b) { VERIFY_IS_EQUAL(a,b); }\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_4(const Ref<const VectorXf,0,InnerStride<> >& a, const B &b) { VERIFY_IS_EQUAL(a,b); }\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_5(Ref<MatrixXf,0,OuterStride<> > a, const B &b) { VERIFY_IS_EQUAL(a,b); }\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_6(const Ref<const MatrixXf,0,OuterStride<> >& a, const B &b) { VERIFY_IS_EQUAL(a,b); }\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_7(Ref<Matrix<float,Dynamic,3> > a, const B &b) { VERIFY_IS_EQUAL(a,b); }\n\nvoid call_ref()\n{\n  VectorXcf ca  = VectorXcf::Random(10);\n  VectorXf a    = VectorXf::Random(10);\n  RowVectorXf b = RowVectorXf::Random(10);\n  MatrixXf A    = MatrixXf::Random(10,10);\n  RowVector3f c = RowVector3f::Random();\n  const VectorXf& ac(a);\n  VectorBlock<VectorXf> ab(a,0,3);\n  const VectorBlock<VectorXf> abc(a,0,3);\n  \n\n  VERIFY_EVALUATION_COUNT( call_ref_1(a,a), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_1(b,b.transpose()), 0);\n//   call_ref_1(ac,a<c);           // does not compile because ac is const\n  VERIFY_EVALUATION_COUNT( call_ref_1(ab,ab), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_1(a.head(4),a.head(4)), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_1(abc,abc), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_1(A.col(3),A.col(3)), 0);\n//   call_ref_1(A.row(3),A.row(3));    // does not compile because innerstride!=1\n  VERIFY_EVALUATION_COUNT( call_ref_3(A.row(3),A.row(3).transpose()), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_4(A.row(3),A.row(3).transpose()), 0);\n//   call_ref_1(a+a, a+a);          // does not compile for obvious reason\n\n  MatrixXf tmp = A*A.col(1);\n  VERIFY_EVALUATION_COUNT( call_ref_2(A*A.col(1), tmp), 1);     // evaluated into a temp\n  VERIFY_EVALUATION_COUNT( call_ref_2(ac.head(5),ac.head(5)), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(ac,ac), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(a,a), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(ab,ab), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(a.head(4),a.head(4)), 0);\n  tmp = a+a;\n  VERIFY_EVALUATION_COUNT( call_ref_2(a+a,tmp), 1);            // evaluated into a temp\n  VERIFY_EVALUATION_COUNT( call_ref_2(ca.imag(),ca.imag()), 1);      // evaluated into a temp\n\n  VERIFY_EVALUATION_COUNT( call_ref_4(ac.head(5),ac.head(5)), 0);\n  tmp = a+a;\n  VERIFY_EVALUATION_COUNT( call_ref_4(a+a,tmp), 1);           // evaluated into a temp\n  VERIFY_EVALUATION_COUNT( call_ref_4(ca.imag(),ca.imag()), 0);\n\n  VERIFY_EVALUATION_COUNT( call_ref_5(a,a), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_5(a.head(3),a.head(3)), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_5(A,A), 0);\n//   call_ref_5(A.transpose(),A.transpose());   // does not compile because storage order does not match\n  VERIFY_EVALUATION_COUNT( call_ref_5(A.block(1,1,2,2),A.block(1,1,2,2)), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_5(b,b), 0);             // storage order do not match, but this is a degenerate case that should work\n  VERIFY_EVALUATION_COUNT( call_ref_5(a.row(3),a.row(3)), 0);\n\n  VERIFY_EVALUATION_COUNT( call_ref_6(a,a), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_6(a.head(3),a.head(3)), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_6(A.row(3),A.row(3)), 1);           // evaluated into a temp thouth it could be avoided by viewing it as a 1xn matrix\n  tmp = A+A;\n  VERIFY_EVALUATION_COUNT( call_ref_6(A+A,tmp), 1);                // evaluated into a temp\n  VERIFY_EVALUATION_COUNT( call_ref_6(A,A), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_6(A.transpose(),A.transpose()), 1);      // evaluated into a temp because the storage orders do not match\n  VERIFY_EVALUATION_COUNT( call_ref_6(A.block(1,1,2,2),A.block(1,1,2,2)), 0);\n  \n  VERIFY_EVALUATION_COUNT( call_ref_7(c,c), 0);\n}\n\ntypedef Matrix<double,Dynamic,Dynamic,RowMajor> RowMatrixXd;\nint test_ref_overload_fun1(Ref<MatrixXd> )       { return 1; }\nint test_ref_overload_fun1(Ref<RowMatrixXd> )    { return 2; }\nint test_ref_overload_fun1(Ref<MatrixXf> )       { return 3; }\n\nint test_ref_overload_fun2(Ref<const MatrixXd> ) { return 4; }\nint test_ref_overload_fun2(Ref<const MatrixXf> ) { return 5; }\n\nvoid test_ref_ambiguous(const Ref<const ArrayXd> &A, Ref<ArrayXd> B)\n{\n  B = A;\n  B = A - A;\n}\n\n// See also bug 969\nvoid test_ref_overloads()\n{\n  MatrixXd Ad, Bd;\n  RowMatrixXd rAd, rBd;\n  VERIFY( test_ref_overload_fun1(Ad)==1 );\n  VERIFY( test_ref_overload_fun1(rAd)==2 );\n  \n  MatrixXf Af, Bf;\n  VERIFY( test_ref_overload_fun2(Ad)==4 );\n  VERIFY( test_ref_overload_fun2(Ad+Bd)==4 );\n  VERIFY( test_ref_overload_fun2(Af+Bf)==5 );\n  \n  ArrayXd A, B;\n  test_ref_ambiguous(A, B);\n}\n\nvoid test_ref_fixed_size_assert()\n{\n  Vector4f v4 = Vector4f::Random();\n  VectorXf vx = VectorXf::Random(10);\n  VERIFY_RAISES_STATIC_ASSERT( Ref<Vector3f> y = v4; (void)y; );\n  VERIFY_RAISES_STATIC_ASSERT( Ref<Vector3f> y = vx.head<4>(); (void)y; );\n  VERIFY_RAISES_STATIC_ASSERT( Ref<const Vector3f> y = v4; (void)y; );\n  VERIFY_RAISES_STATIC_ASSERT( Ref<const Vector3f> y = vx.head<4>(); (void)y; );\n  VERIFY_RAISES_STATIC_ASSERT( Ref<const Vector3f> y = 2*v4; (void)y; );\n}\n\nEIGEN_DECLARE_TEST(ref)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( ref_vector(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_1( check_const_correctness(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( ref_vector(Vector4d()) );\n    CALL_SUBTEST_2( check_const_correctness(Matrix4d()) );\n    CALL_SUBTEST_3( ref_vector(Vector4cf()) );\n    CALL_SUBTEST_4( ref_vector(VectorXcf(8)) );\n    CALL_SUBTEST_5( ref_vector(VectorXi(12)) );\n    CALL_SUBTEST_5( check_const_correctness(VectorXi(12)) );\n\n    CALL_SUBTEST_1( ref_matrix(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( ref_matrix(Matrix4d()) );\n    CALL_SUBTEST_1( ref_matrix(Matrix<float,3,5>()) );\n    CALL_SUBTEST_4( ref_matrix(MatrixXcf(internal::random<int>(1,10),internal::random<int>(1,10))) );\n    CALL_SUBTEST_4( ref_matrix(Matrix<std::complex<double>,10,15>()) );\n    CALL_SUBTEST_5( ref_matrix(MatrixXi(internal::random<int>(1,10),internal::random<int>(1,10))) );\n    CALL_SUBTEST_6( call_ref() );\n\n    CALL_SUBTEST_8( (ref_vector_fixed_sizes<float,3,5>()) );\n    CALL_SUBTEST_8( (ref_vector_fixed_sizes<float,15,10>()) );\n  }\n  \n  CALL_SUBTEST_7( test_ref_overloads() );\n  CALL_SUBTEST_7( test_ref_fixed_size_assert() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/reshape.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2017 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2014 yoco <peter.xiau@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename T1,typename T2>\ntypename internal::enable_if<internal::is_same<T1,T2>::value,bool>::type\nis_same_eq(const T1& a, const T2& b)\n{\n  return (a.array() == b.array()).all();\n}\n\ntemplate <int Order,typename MatType>\nvoid check_auto_reshape4x4(MatType m)\n{\n  internal::VariableAndFixedInt<MatType::SizeAtCompileTime==Dynamic?-1: 1>  v1( 1);\n  internal::VariableAndFixedInt<MatType::SizeAtCompileTime==Dynamic?-1: 2>  v2( 2);\n  internal::VariableAndFixedInt<MatType::SizeAtCompileTime==Dynamic?-1: 4>  v4( 4);\n  internal::VariableAndFixedInt<MatType::SizeAtCompileTime==Dynamic?-1: 8>  v8( 8);\n  internal::VariableAndFixedInt<MatType::SizeAtCompileTime==Dynamic?-1:16> v16(16);\n\n  VERIFY(is_same_eq(m.template reshaped<Order>( 1,       AutoSize), m.template reshaped<Order>( 1, 16)));\n  VERIFY(is_same_eq(m.template reshaped<Order>(AutoSize, 16      ), m.template reshaped<Order>( 1, 16)));\n  VERIFY(is_same_eq(m.template reshaped<Order>( 2,       AutoSize), m.template reshaped<Order>( 2,  8)));\n  VERIFY(is_same_eq(m.template reshaped<Order>(AutoSize, 8       ), m.template reshaped<Order>( 2,  8)));\n  VERIFY(is_same_eq(m.template reshaped<Order>( 4,       AutoSize), m.template reshaped<Order>( 4,  4)));\n  VERIFY(is_same_eq(m.template reshaped<Order>(AutoSize, 4       ), m.template reshaped<Order>( 4,  4)));\n  VERIFY(is_same_eq(m.template reshaped<Order>( 8,       AutoSize), m.template reshaped<Order>( 8,  2)));\n  VERIFY(is_same_eq(m.template reshaped<Order>(AutoSize, 2       ), m.template reshaped<Order>( 8,  2)));\n  VERIFY(is_same_eq(m.template reshaped<Order>(16,       AutoSize), m.template reshaped<Order>(16,  1)));\n  VERIFY(is_same_eq(m.template reshaped<Order>(AutoSize, 1       ), m.template reshaped<Order>(16,  1)));\n\n  VERIFY(is_same_eq(m.template reshaped<Order>(fix< 1>,   AutoSize),  m.template reshaped<Order>(fix< 1>, v16    )));\n  VERIFY(is_same_eq(m.template reshaped<Order>(AutoSize,  fix<16> ),  m.template reshaped<Order>( v1,     fix<16>)));\n  VERIFY(is_same_eq(m.template reshaped<Order>(fix< 2>,   AutoSize),  m.template reshaped<Order>(fix< 2>, v8     )));\n  VERIFY(is_same_eq(m.template reshaped<Order>(AutoSize,  fix< 8> ),  m.template reshaped<Order>( v2,     fix< 8>)));\n  VERIFY(is_same_eq(m.template reshaped<Order>(fix< 4>,   AutoSize),  m.template reshaped<Order>(fix< 4>, v4     )));\n  VERIFY(is_same_eq(m.template reshaped<Order>(AutoSize,  fix< 4> ),  m.template reshaped<Order>( v4,     fix< 4>)));\n  VERIFY(is_same_eq(m.template reshaped<Order>(fix< 8>,   AutoSize),  m.template reshaped<Order>(fix< 8>, v2     )));\n  VERIFY(is_same_eq(m.template reshaped<Order>(AutoSize,  fix< 2> ),  m.template reshaped<Order>( v8,     fix< 2>)));\n  VERIFY(is_same_eq(m.template reshaped<Order>(fix<16>,   AutoSize),  m.template reshaped<Order>(fix<16>, v1     )));\n  VERIFY(is_same_eq(m.template reshaped<Order>(AutoSize,  fix< 1> ),  m.template reshaped<Order>(v16,     fix< 1>)));\n}\n\ntemplate <typename MatType>\nvoid check_direct_access_reshape4x4(MatType , internal::FixedInt<RowMajorBit>) {}\n\ntemplate <typename MatType>\nvoid check_direct_access_reshape4x4(MatType m, internal::FixedInt<0>) {\n  VERIFY_IS_EQUAL(m.reshaped( 1, 16).data(), m.data());\n  VERIFY_IS_EQUAL(m.reshaped( 1, 16).innerStride(), 1);\n\n  VERIFY_IS_EQUAL(m.reshaped( 2, 8).data(), m.data());\n  VERIFY_IS_EQUAL(m.reshaped( 2, 8).innerStride(), 1);\n  VERIFY_IS_EQUAL(m.reshaped( 2, 8).outerStride(), 2);\n}\n\n// just test a 4x4 matrix, enumerate all combination manually\ntemplate <typename MatType>\nvoid reshape4x4(MatType m)\n{\n  typedef typename MatType::Scalar Scalar;\n\n  internal::VariableAndFixedInt<MatType::SizeAtCompileTime==Dynamic?-1: 1>  v1( 1);\n  internal::VariableAndFixedInt<MatType::SizeAtCompileTime==Dynamic?-1: 2>  v2( 2);\n  internal::VariableAndFixedInt<MatType::SizeAtCompileTime==Dynamic?-1: 4>  v4( 4);\n  internal::VariableAndFixedInt<MatType::SizeAtCompileTime==Dynamic?-1: 8>  v8( 8);\n  internal::VariableAndFixedInt<MatType::SizeAtCompileTime==Dynamic?-1:16> v16(16);\n\n  if((MatType::Flags&RowMajorBit)==0)\n  {\n    typedef Map<MatrixXi> MapMat;\n    // dynamic\n    VERIFY_IS_EQUAL((m.reshaped( 1, 16)), MapMat(m.data(),  1, 16));\n    VERIFY_IS_EQUAL((m.reshaped( 2,  8)), MapMat(m.data(),  2,  8));\n    VERIFY_IS_EQUAL((m.reshaped( 4,  4)), MapMat(m.data(),  4,  4));\n    VERIFY_IS_EQUAL((m.reshaped( 8,  2)), MapMat(m.data(),  8,  2));\n    VERIFY_IS_EQUAL((m.reshaped(16,  1)), MapMat(m.data(), 16,  1));\n\n    // static\n    VERIFY_IS_EQUAL(m.reshaped(fix< 1>, fix<16>), MapMat(m.data(),  1, 16));\n    VERIFY_IS_EQUAL(m.reshaped(fix< 2>, fix< 8>), MapMat(m.data(),  2,  8));\n    VERIFY_IS_EQUAL(m.reshaped(fix< 4>, fix< 4>), MapMat(m.data(),  4,  4));\n    VERIFY_IS_EQUAL(m.reshaped(fix< 8>, fix< 2>), MapMat(m.data(),  8,  2));\n    VERIFY_IS_EQUAL(m.reshaped(fix<16>, fix< 1>), MapMat(m.data(), 16,  1));\n\n\n    // reshape chain\n    VERIFY_IS_EQUAL(\n      (m\n      .reshaped( 1, 16)\n      .reshaped(fix< 2>,fix< 8>)\n      .reshaped(16,  1)\n      .reshaped(fix< 8>,fix< 2>)\n      .reshaped( 2,  8)\n      .reshaped(fix< 1>,fix<16>)\n      .reshaped( 4,  4)\n      .reshaped(fix<16>,fix< 1>)\n      .reshaped( 8,  2)\n      .reshaped(fix< 4>,fix< 4>)\n      ),\n      MapMat(m.data(), 4,  4)\n    );\n  }\n\n  VERIFY(is_same_eq(m.reshaped( 1,       AutoSize), m.reshaped( 1, 16)));\n  VERIFY(is_same_eq(m.reshaped(AutoSize, 16),       m.reshaped( 1, 16)));\n  VERIFY(is_same_eq(m.reshaped( 2,       AutoSize), m.reshaped( 2,  8)));\n  VERIFY(is_same_eq(m.reshaped(AutoSize, 8),        m.reshaped( 2,  8)));\n  VERIFY(is_same_eq(m.reshaped( 4,       AutoSize), m.reshaped( 4,  4)));\n  VERIFY(is_same_eq(m.reshaped(AutoSize, 4),        m.reshaped( 4,  4)));\n  VERIFY(is_same_eq(m.reshaped( 8,       AutoSize), m.reshaped( 8,  2)));\n  VERIFY(is_same_eq(m.reshaped(AutoSize, 2),        m.reshaped( 8,  2)));\n  VERIFY(is_same_eq(m.reshaped(16,       AutoSize), m.reshaped(16,  1)));\n  VERIFY(is_same_eq(m.reshaped(AutoSize,  1),       m.reshaped(16,  1)));\n\n  VERIFY(is_same_eq(m.reshaped(fix< 1>,   AutoSize),  m.reshaped(fix< 1>, v16)));\n  VERIFY(is_same_eq(m.reshaped(AutoSize,  fix<16>),   m.reshaped( v1,     fix<16>)));\n  VERIFY(is_same_eq(m.reshaped(fix< 2>,   AutoSize),  m.reshaped(fix< 2>, v8)));\n  VERIFY(is_same_eq(m.reshaped(AutoSize,  fix< 8>),   m.reshaped( v2,     fix< 8>)));\n  VERIFY(is_same_eq(m.reshaped(fix< 4>,   AutoSize),  m.reshaped(fix< 4>, v4)));\n  VERIFY(is_same_eq(m.reshaped(AutoSize,  fix< 4>),   m.reshaped( v4,     fix< 4>)));\n  VERIFY(is_same_eq(m.reshaped(fix< 8>,   AutoSize),  m.reshaped(fix< 8>, v2)));\n  VERIFY(is_same_eq(m.reshaped(AutoSize,  fix< 2>),   m.reshaped( v8,     fix< 2>)));\n  VERIFY(is_same_eq(m.reshaped(fix<16>,   AutoSize),  m.reshaped(fix<16>, v1)));\n  VERIFY(is_same_eq(m.reshaped(AutoSize,  fix< 1>),   m.reshaped(v16,     fix< 1>)));\n\n  check_auto_reshape4x4<ColMajor> (m);\n  check_auto_reshape4x4<RowMajor> (m);\n  check_auto_reshape4x4<AutoOrder>(m);\n  check_auto_reshape4x4<ColMajor> (m.transpose());\n  check_auto_reshape4x4<ColMajor> (m.transpose());\n  check_auto_reshape4x4<AutoOrder>(m.transpose());\n\n  check_direct_access_reshape4x4(m,fix<MatType::Flags&RowMajorBit>);\n\n  if((MatType::Flags&RowMajorBit)==0)\n  {\n    VERIFY_IS_EQUAL(m.template reshaped<ColMajor>(2,8),m.reshaped(2,8));\n    VERIFY_IS_EQUAL(m.template reshaped<ColMajor>(2,8),m.template reshaped<AutoOrder>(2,8));\n    VERIFY_IS_EQUAL(m.transpose().template reshaped<RowMajor>(2,8),m.transpose().template reshaped<AutoOrder>(2,8));\n  }\n  else\n  {\n    VERIFY_IS_EQUAL(m.template reshaped<ColMajor>(2,8),m.reshaped(2,8));\n    VERIFY_IS_EQUAL(m.template reshaped<RowMajor>(2,8),m.template reshaped<AutoOrder>(2,8));\n    VERIFY_IS_EQUAL(m.transpose().template reshaped<ColMajor>(2,8),m.transpose().template reshaped<AutoOrder>(2,8));\n    VERIFY_IS_EQUAL(m.transpose().reshaped(2,8),m.transpose().template reshaped<AutoOrder>(2,8));\n  }\n\n  MatrixXi m28r1 = m.template reshaped<RowMajor>(2,8);\n  MatrixXi m28r2 = m.transpose().template reshaped<ColMajor>(8,2).transpose();\n  VERIFY_IS_EQUAL( m28r1, m28r2);\n\n  VERIFY(is_same_eq(m.reshaped(v16,fix<1>), m.reshaped()));\n  VERIFY_IS_EQUAL(m.reshaped(16,1).eval(), m.reshaped().eval());\n  VERIFY_IS_EQUAL(m.reshaped(1,16).eval(), m.reshaped().transpose().eval());\n  VERIFY_IS_EQUAL(m.reshaped().reshaped(2,8), m.reshaped(2,8));\n  VERIFY_IS_EQUAL(m.reshaped().reshaped(4,4), m.reshaped(4,4));\n  VERIFY_IS_EQUAL(m.reshaped().reshaped(8,2), m.reshaped(8,2));\n\n  VERIFY_IS_EQUAL(m.reshaped(), m.template reshaped<ColMajor>());\n  VERIFY_IS_EQUAL(m.transpose().reshaped(), m.template reshaped<RowMajor>());\n  VERIFY_IS_EQUAL(m.template reshaped<RowMajor>(AutoSize,fix<1>), m.template reshaped<RowMajor>());\n  VERIFY_IS_EQUAL(m.template reshaped<AutoOrder>(AutoSize,fix<1>), m.template reshaped<AutoOrder>());\n\n  VERIFY(is_same_eq(m.reshaped(AutoSize,fix<1>), m.reshaped()));\n  VERIFY_IS_EQUAL(m.template reshaped<RowMajor>(fix<1>,AutoSize), m.transpose().reshaped().transpose());\n\n  // check assignment\n  {\n    Matrix<Scalar,Dynamic,1> m1x(m.size()); m1x.setRandom();\n    VERIFY_IS_APPROX(m.reshaped() = m1x, m1x);\n    VERIFY_IS_APPROX(m, m1x.reshaped(4,4));\n    \n    Matrix<Scalar,Dynamic,Dynamic> m28(2,8); m28.setRandom();\n    VERIFY_IS_APPROX(m.reshaped(2,8) = m28, m28);\n    VERIFY_IS_APPROX(m, m28.reshaped(4,4));\n    VERIFY_IS_APPROX(m.template reshaped<RowMajor>(2,8) = m28, m28);\n\n    Matrix<Scalar,Dynamic,Dynamic> m24(2,4); m24.setRandom();\n    VERIFY_IS_APPROX(m(seq(0,last,2),all).reshaped(2,4) = m24, m24);\n\n    // check constness:\n    m.reshaped(2,8).nestedExpression() = m;\n  }\n}\n\nEIGEN_DECLARE_TEST(reshape)\n{\n  typedef Matrix<int,Dynamic,Dynamic,RowMajor> RowMatrixXi;\n  typedef Matrix<int,4,4,RowMajor> RowMatrix4i;\n  MatrixXi mx = MatrixXi::Random(4, 4);\n  Matrix4i m4 = Matrix4i::Random(4, 4);\n  RowMatrixXi rmx = RowMatrixXi::Random(4, 4);\n  RowMatrix4i rm4 = RowMatrix4i::Random(4, 4);\n\n  // test dynamic-size matrix\n  CALL_SUBTEST(reshape4x4(mx));\n  // test static-size matrix\n  CALL_SUBTEST(reshape4x4(m4));\n  // test dynamic-size const matrix\n  CALL_SUBTEST(reshape4x4(static_cast<const MatrixXi>(mx)));\n  // test static-size const matrix\n  CALL_SUBTEST(reshape4x4(static_cast<const Matrix4i>(m4)));\n\n  CALL_SUBTEST(reshape4x4(rmx));\n  CALL_SUBTEST(reshape4x4(rm4));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/resize.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Keir Mierle <mierle@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<DenseIndex rows, DenseIndex cols>\nvoid resizeLikeTest()\n{\n  MatrixXf A(rows, cols);\n  MatrixXf B;\n  Matrix<double, rows, cols> C;\n  B.resizeLike(A);\n  C.resizeLike(B);  // Shouldn't crash.\n  VERIFY(B.rows() == rows && B.cols() == cols);\n\n  VectorXf x(rows);\n  RowVectorXf y;\n  y.resizeLike(x);\n  VERIFY(y.rows() == 1 && y.cols() == rows);\n\n  y.resize(cols);\n  x.resizeLike(y);\n  VERIFY(x.rows() == cols && x.cols() == 1);\n}\n\nvoid resizeLikeTest12() { resizeLikeTest<1,2>(); }\nvoid resizeLikeTest1020() { resizeLikeTest<10,20>(); }\nvoid resizeLikeTest31() { resizeLikeTest<3,1>(); }\n\nEIGEN_DECLARE_TEST(resize)\n{\n  CALL_SUBTEST(resizeLikeTest12() );\n  CALL_SUBTEST(resizeLikeTest1020() );\n  CALL_SUBTEST(resizeLikeTest31() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/rvalue_types.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_RUNTIME_NO_MALLOC\n\n#include \"main.h\"\n#if EIGEN_HAS_CXX11\n#include \"MovableScalar.h\"\n#endif\n\n#include <Eigen/Core>\n\nusing internal::UIntPtr;\n\n// A Scalar that asserts for uninitialized access.\ntemplate<typename T>\nclass SafeScalar {\n public:\n  SafeScalar() : initialized_(false) {}\n  SafeScalar(const SafeScalar& other) {\n    *this = other;\n  }\n  SafeScalar& operator=(const SafeScalar& other) {\n    val_ = T(other);\n    initialized_ = true;\n    return *this;\n  }\n  \n  SafeScalar(T val) : val_(val), initialized_(true) {}\n  SafeScalar& operator=(T val) {\n    val_ = val;\n    initialized_ = true;\n  }\n  \n  operator T() const {\n    VERIFY(initialized_ && \"Uninitialized access.\");\n    return val_;\n  }\n \n private:\n  T val_;\n  bool initialized_;\n};\n\n#if EIGEN_HAS_RVALUE_REFERENCES\ntemplate <typename MatrixType>\nvoid rvalue_copyassign(const MatrixType& m)\n{\n\n  typedef typename internal::traits<MatrixType>::Scalar Scalar;\n  \n  // create a temporary which we are about to destroy by moving\n  MatrixType tmp = m;\n  UIntPtr src_address = reinterpret_cast<UIntPtr>(tmp.data());\n  \n  Eigen::internal::set_is_malloc_allowed(false); // moving from an rvalue reference shall never allocate\n  // move the temporary to n\n  MatrixType n = std::move(tmp);\n  UIntPtr dst_address = reinterpret_cast<UIntPtr>(n.data());\n  if (MatrixType::RowsAtCompileTime==Dynamic|| MatrixType::ColsAtCompileTime==Dynamic)\n  {\n    // verify that we actually moved the guts\n    VERIFY_IS_EQUAL(src_address, dst_address);\n    VERIFY_IS_EQUAL(tmp.size(), 0);\n    VERIFY_IS_EQUAL(reinterpret_cast<UIntPtr>(tmp.data()), UIntPtr(0));\n  }\n\n  // verify that the content did not change\n  Scalar abs_diff = (m-n).array().abs().sum();\n  VERIFY_IS_EQUAL(abs_diff, Scalar(0));\n  Eigen::internal::set_is_malloc_allowed(true);\n}\ntemplate<typename TranspositionsType>\nvoid rvalue_transpositions(Index rows)\n{\n  typedef typename TranspositionsType::IndicesType PermutationVectorType;\n\n  PermutationVectorType vec;\n  randomPermutationVector(vec, rows);\n  TranspositionsType t0(vec);\n\n  Eigen::internal::set_is_malloc_allowed(false); // moving from an rvalue reference shall never allocate\n\n  UIntPtr t0_address = reinterpret_cast<UIntPtr>(t0.indices().data());\n\n  // Move constructors:\n  TranspositionsType t1 = std::move(t0);\n  UIntPtr t1_address = reinterpret_cast<UIntPtr>(t1.indices().data());\n  VERIFY_IS_EQUAL(t0_address, t1_address);\n  // t0 must be de-allocated:\n  VERIFY_IS_EQUAL(t0.size(), 0);\n  VERIFY_IS_EQUAL(reinterpret_cast<UIntPtr>(t0.indices().data()), UIntPtr(0));\n\n\n  // Move assignment:\n  t0 = std::move(t1);\n  t0_address = reinterpret_cast<UIntPtr>(t0.indices().data());\n  VERIFY_IS_EQUAL(t0_address, t1_address);\n  // t1 must be de-allocated:\n  VERIFY_IS_EQUAL(t1.size(), 0);\n  VERIFY_IS_EQUAL(reinterpret_cast<UIntPtr>(t1.indices().data()), UIntPtr(0));\n\n  Eigen::internal::set_is_malloc_allowed(true);\n}\n\ntemplate <typename MatrixType>\nvoid rvalue_move(const MatrixType& m)\n{\n    // lvalue reference is copied\n    MatrixType b(m);\n    VERIFY_IS_EQUAL(b, m);\n\n    // lvalue reference is copied\n    MatrixType c{m};\n    VERIFY_IS_EQUAL(c, m);\n\n    // lvalue reference is copied\n    MatrixType d = m;\n    VERIFY_IS_EQUAL(d, m);\n\n    // rvalue reference is moved - copy constructor.\n    MatrixType e_src(m);\n    VERIFY_IS_EQUAL(e_src, m);\n    MatrixType e_dst(std::move(e_src));\n    VERIFY_IS_EQUAL(e_dst, m);\n\n    // rvalue reference is moved - copy constructor.\n    MatrixType f_src(m);\n    VERIFY_IS_EQUAL(f_src, m);\n    MatrixType f_dst = std::move(f_src);\n    VERIFY_IS_EQUAL(f_dst, m);\n    \n    // rvalue reference is moved - copy assignment.\n    MatrixType g_src(m);\n    VERIFY_IS_EQUAL(g_src, m);\n    MatrixType g_dst;\n    g_dst = std::move(g_src);\n    VERIFY_IS_EQUAL(g_dst, m);\n}\n#else\ntemplate <typename MatrixType>\nvoid rvalue_copyassign(const MatrixType&) {}\ntemplate<typename TranspositionsType>\nvoid rvalue_transpositions(Index) {}\ntemplate <typename MatrixType>\nvoid rvalue_move(const MatrixType&) {}\n#endif\n\nEIGEN_DECLARE_TEST(rvalue_types)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(rvalue_copyassign( MatrixXf::Random(50,50).eval() ));\n    CALL_SUBTEST_1(rvalue_copyassign( ArrayXXf::Random(50,50).eval() ));\n\n    CALL_SUBTEST_1(rvalue_copyassign( Matrix<float,1,Dynamic>::Random(50).eval() ));\n    CALL_SUBTEST_1(rvalue_copyassign( Array<float,1,Dynamic>::Random(50).eval() ));\n\n    CALL_SUBTEST_1(rvalue_copyassign( Matrix<float,Dynamic,1>::Random(50).eval() ));\n    CALL_SUBTEST_1(rvalue_copyassign( Array<float,Dynamic,1>::Random(50).eval() ));\n\n    CALL_SUBTEST_2(rvalue_copyassign( Array<float,2,1>::Random().eval() ));\n    CALL_SUBTEST_2(rvalue_copyassign( Array<float,3,1>::Random().eval() ));\n    CALL_SUBTEST_2(rvalue_copyassign( Array<float,4,1>::Random().eval() ));\n\n    CALL_SUBTEST_2(rvalue_copyassign( Array<float,2,2>::Random().eval() ));\n    CALL_SUBTEST_2(rvalue_copyassign( Array<float,3,3>::Random().eval() ));\n    CALL_SUBTEST_2(rvalue_copyassign( Array<float,4,4>::Random().eval() ));\n  \n    CALL_SUBTEST_3((rvalue_transpositions<PermutationMatrix<Dynamic, Dynamic, int> >(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_3((rvalue_transpositions<PermutationMatrix<Dynamic, Dynamic, Index> >(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_4((rvalue_transpositions<Transpositions<Dynamic, Dynamic, int> >(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n    CALL_SUBTEST_4((rvalue_transpositions<Transpositions<Dynamic, Dynamic, Index> >(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))));\n\n#if EIGEN_HAS_CXX11\n    CALL_SUBTEST_5(rvalue_move(Eigen::Matrix<MovableScalar<float>,1,3>::Random().eval()));\n    CALL_SUBTEST_5(rvalue_move(Eigen::Matrix<SafeScalar<float>,1,3>::Random().eval()));\n    CALL_SUBTEST_5(rvalue_move(Eigen::Matrix<SafeScalar<float>,Eigen::Dynamic,Eigen::Dynamic>::Random(1,3).eval()));\n#endif\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/schur_complex.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010,2012 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <limits>\n#include <Eigen/Eigenvalues>\n\ntemplate<typename MatrixType> void schur(int size = MatrixType::ColsAtCompileTime)\n{\n  typedef typename ComplexSchur<MatrixType>::ComplexScalar ComplexScalar;\n  typedef typename ComplexSchur<MatrixType>::ComplexMatrixType ComplexMatrixType;\n\n  // Test basic functionality: T is triangular and A = U T U*\n  for(int counter = 0; counter < g_repeat; ++counter) {\n    MatrixType A = MatrixType::Random(size, size);\n    ComplexSchur<MatrixType> schurOfA(A);\n    VERIFY_IS_EQUAL(schurOfA.info(), Success);\n    ComplexMatrixType U = schurOfA.matrixU();\n    ComplexMatrixType T = schurOfA.matrixT();\n    for(int row = 1; row < size; ++row) {\n      for(int col = 0; col < row; ++col) {\n        VERIFY(T(row,col) == (typename MatrixType::Scalar)0);\n      }\n    }\n    VERIFY_IS_APPROX(A.template cast<ComplexScalar>(), U * T * U.adjoint());\n  }\n\n  // Test asserts when not initialized\n  ComplexSchur<MatrixType> csUninitialized;\n  VERIFY_RAISES_ASSERT(csUninitialized.matrixT());\n  VERIFY_RAISES_ASSERT(csUninitialized.matrixU());\n  VERIFY_RAISES_ASSERT(csUninitialized.info());\n  \n  // Test whether compute() and constructor returns same result\n  MatrixType A = MatrixType::Random(size, size);\n  ComplexSchur<MatrixType> cs1;\n  cs1.compute(A);\n  ComplexSchur<MatrixType> cs2(A);\n  VERIFY_IS_EQUAL(cs1.info(), Success);\n  VERIFY_IS_EQUAL(cs2.info(), Success);\n  VERIFY_IS_EQUAL(cs1.matrixT(), cs2.matrixT());\n  VERIFY_IS_EQUAL(cs1.matrixU(), cs2.matrixU());\n\n  // Test maximum number of iterations\n  ComplexSchur<MatrixType> cs3;\n  cs3.setMaxIterations(ComplexSchur<MatrixType>::m_maxIterationsPerRow * size).compute(A);\n  VERIFY_IS_EQUAL(cs3.info(), Success);\n  VERIFY_IS_EQUAL(cs3.matrixT(), cs1.matrixT());\n  VERIFY_IS_EQUAL(cs3.matrixU(), cs1.matrixU());\n  cs3.setMaxIterations(1).compute(A);\n  VERIFY_IS_EQUAL(cs3.info(), size > 1 ? NoConvergence : Success);\n  VERIFY_IS_EQUAL(cs3.getMaxIterations(), 1);\n\n  MatrixType Atriangular = A;\n  Atriangular.template triangularView<StrictlyLower>().setZero(); \n  cs3.setMaxIterations(1).compute(Atriangular); // triangular matrices do not need any iterations\n  VERIFY_IS_EQUAL(cs3.info(), Success);\n  VERIFY_IS_EQUAL(cs3.matrixT(), Atriangular.template cast<ComplexScalar>());\n  VERIFY_IS_EQUAL(cs3.matrixU(), ComplexMatrixType::Identity(size, size));\n\n  // Test computation of only T, not U\n  ComplexSchur<MatrixType> csOnlyT(A, false);\n  VERIFY_IS_EQUAL(csOnlyT.info(), Success);\n  VERIFY_IS_EQUAL(cs1.matrixT(), csOnlyT.matrixT());\n  VERIFY_RAISES_ASSERT(csOnlyT.matrixU());\n\n  if (size > 1 && size < 20)\n  {\n    // Test matrix with NaN\n    A(0,0) = std::numeric_limits<typename MatrixType::RealScalar>::quiet_NaN();\n    ComplexSchur<MatrixType> csNaN(A);\n    VERIFY_IS_EQUAL(csNaN.info(), NoConvergence);\n  }\n}\n\nEIGEN_DECLARE_TEST(schur_complex)\n{\n  CALL_SUBTEST_1(( schur<Matrix4cd>() ));\n  CALL_SUBTEST_2(( schur<MatrixXcf>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4)) ));\n  CALL_SUBTEST_3(( schur<Matrix<std::complex<float>, 1, 1> >() ));\n  CALL_SUBTEST_4(( schur<Matrix<float, 3, 3, Eigen::RowMajor> >() ));\n\n  // Test problem size constructors\n  CALL_SUBTEST_5(ComplexSchur<MatrixXf>(10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/schur_real.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010,2012 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <limits>\n#include <Eigen/Eigenvalues>\n\ntemplate<typename MatrixType> void verifyIsQuasiTriangular(const MatrixType& T)\n{\n  const Index size = T.cols();\n  typedef typename MatrixType::Scalar Scalar;\n\n  // Check T is lower Hessenberg\n  for(int row = 2; row < size; ++row) {\n    for(int col = 0; col < row - 1; ++col) {\n      VERIFY(T(row,col) == Scalar(0));\n    }\n  }\n\n  // Check that any non-zero on the subdiagonal is followed by a zero and is\n  // part of a 2x2 diagonal block with imaginary eigenvalues.\n  for(int row = 1; row < size; ++row) {\n    if (T(row,row-1) != Scalar(0)) {\n      VERIFY(row == size-1 || T(row+1,row) == 0);\n      Scalar tr = T(row-1,row-1) + T(row,row);\n      Scalar det = T(row-1,row-1) * T(row,row) - T(row-1,row) * T(row,row-1);\n      VERIFY(4 * det > tr * tr);\n    }\n  }\n}\n\ntemplate<typename MatrixType> void schur(int size = MatrixType::ColsAtCompileTime)\n{\n  // Test basic functionality: T is quasi-triangular and A = U T U*\n  for(int counter = 0; counter < g_repeat; ++counter) {\n    MatrixType A = MatrixType::Random(size, size);\n    RealSchur<MatrixType> schurOfA(A);\n    VERIFY_IS_EQUAL(schurOfA.info(), Success);\n    MatrixType U = schurOfA.matrixU();\n    MatrixType T = schurOfA.matrixT();\n    verifyIsQuasiTriangular(T);\n    VERIFY_IS_APPROX(A, U * T * U.transpose());\n  }\n\n  // Test asserts when not initialized\n  RealSchur<MatrixType> rsUninitialized;\n  VERIFY_RAISES_ASSERT(rsUninitialized.matrixT());\n  VERIFY_RAISES_ASSERT(rsUninitialized.matrixU());\n  VERIFY_RAISES_ASSERT(rsUninitialized.info());\n  \n  // Test whether compute() and constructor returns same result\n  MatrixType A = MatrixType::Random(size, size);\n  RealSchur<MatrixType> rs1;\n  rs1.compute(A);\n  RealSchur<MatrixType> rs2(A);\n  VERIFY_IS_EQUAL(rs1.info(), Success);\n  VERIFY_IS_EQUAL(rs2.info(), Success);\n  VERIFY_IS_EQUAL(rs1.matrixT(), rs2.matrixT());\n  VERIFY_IS_EQUAL(rs1.matrixU(), rs2.matrixU());\n\n  // Test maximum number of iterations\n  RealSchur<MatrixType> rs3;\n  rs3.setMaxIterations(RealSchur<MatrixType>::m_maxIterationsPerRow * size).compute(A);\n  VERIFY_IS_EQUAL(rs3.info(), Success);\n  VERIFY_IS_EQUAL(rs3.matrixT(), rs1.matrixT());\n  VERIFY_IS_EQUAL(rs3.matrixU(), rs1.matrixU());\n  if (size > 2) {\n    rs3.setMaxIterations(1).compute(A);\n    VERIFY_IS_EQUAL(rs3.info(), NoConvergence);\n    VERIFY_IS_EQUAL(rs3.getMaxIterations(), 1);\n  }\n\n  MatrixType Atriangular = A;\n  Atriangular.template triangularView<StrictlyLower>().setZero(); \n  rs3.setMaxIterations(1).compute(Atriangular); // triangular matrices do not need any iterations\n  VERIFY_IS_EQUAL(rs3.info(), Success);\n  VERIFY_IS_APPROX(rs3.matrixT(), Atriangular); // approx because of scaling...\n  VERIFY_IS_EQUAL(rs3.matrixU(), MatrixType::Identity(size, size));\n\n  // Test computation of only T, not U\n  RealSchur<MatrixType> rsOnlyT(A, false);\n  VERIFY_IS_EQUAL(rsOnlyT.info(), Success);\n  VERIFY_IS_EQUAL(rs1.matrixT(), rsOnlyT.matrixT());\n  VERIFY_RAISES_ASSERT(rsOnlyT.matrixU());\n\n  if (size > 2 && size < 20)\n  {\n    // Test matrix with NaN\n    A(0,0) = std::numeric_limits<typename MatrixType::Scalar>::quiet_NaN();\n    RealSchur<MatrixType> rsNaN(A);\n    VERIFY_IS_EQUAL(rsNaN.info(), NoConvergence);\n  }\n}\n\nEIGEN_DECLARE_TEST(schur_real)\n{\n  CALL_SUBTEST_1(( schur<Matrix4f>() ));\n  CALL_SUBTEST_2(( schur<MatrixXd>(internal::random<int>(1,EIGEN_TEST_MAX_SIZE/4)) ));\n  CALL_SUBTEST_3(( schur<Matrix<float, 1, 1> >() ));\n  CALL_SUBTEST_4(( schur<Matrix<double, 3, 3, Eigen::RowMajor> >() ));\n\n  // Test problem size constructors\n  CALL_SUBTEST_5(RealSchur<MatrixXf>(10));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/selfadjoint.cpp",
    "content": "// This file is triangularView of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define TEST_CHECK_STATIC_ASSERTIONS\n#include \"main.h\"\n\n// This file tests the basic selfadjointView API,\n// the related products and decompositions are tested in specific files.\n\ntemplate<typename MatrixType> void selfadjoint(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols),\n             m4(rows, cols);\n\n  m1.diagonal() = m1.diagonal().real().template cast<Scalar>();\n\n  // check selfadjoint to dense\n  m3 = m1.template selfadjointView<Upper>();\n  VERIFY_IS_APPROX(MatrixType(m3.template triangularView<Upper>()), MatrixType(m1.template triangularView<Upper>()));\n  VERIFY_IS_APPROX(m3, m3.adjoint());\n\n  m3 = m1.template selfadjointView<Lower>();\n  VERIFY_IS_APPROX(MatrixType(m3.template triangularView<Lower>()), MatrixType(m1.template triangularView<Lower>()));\n  VERIFY_IS_APPROX(m3, m3.adjoint());\n\n  m3 = m1.template selfadjointView<Upper>();\n  m4 = m2;\n  m4 += m1.template selfadjointView<Upper>();\n  VERIFY_IS_APPROX(m4, m2+m3);\n\n  m3 = m1.template selfadjointView<Lower>();\n  m4 = m2;\n  m4 -= m1.template selfadjointView<Lower>();\n  VERIFY_IS_APPROX(m4, m2-m3);\n\n  VERIFY_RAISES_STATIC_ASSERT(m2.template selfadjointView<StrictlyUpper>());\n  VERIFY_RAISES_STATIC_ASSERT(m2.template selfadjointView<UnitLower>());\n}\n\nvoid bug_159()\n{\n  Matrix3d m = Matrix3d::Random().selfadjointView<Lower>();\n  EIGEN_UNUSED_VARIABLE(m)\n}\n\nEIGEN_DECLARE_TEST(selfadjoint)\n{\n  for(int i = 0; i < g_repeat ; i++)\n  {\n    int s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE);\n\n    CALL_SUBTEST_1( selfadjoint(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( selfadjoint(Matrix<float, 2, 2>()) );\n    CALL_SUBTEST_3( selfadjoint(Matrix3cf()) );\n    CALL_SUBTEST_4( selfadjoint(MatrixXcd(s,s)) );\n    CALL_SUBTEST_5( selfadjoint(Matrix<float,Dynamic,Dynamic,RowMajor>(s, s)) );\n    \n    TEST_SET_BUT_UNUSED_VARIABLE(s)\n  }\n  \n  CALL_SUBTEST_1( bug_159() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/simplicial_cholesky.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"sparse_solver.h\"\n\ntemplate<typename T, typename I_, int flag> void test_simplicial_cholesky_T()\n{\n  typedef SparseMatrix<T,flag,I_> SparseMatrixType;\n  SimplicialCholesky<SparseMatrixType, Lower> chol_colmajor_lower_amd;\n  SimplicialCholesky<SparseMatrixType, Upper> chol_colmajor_upper_amd;\n  SimplicialLLT<     SparseMatrixType, Lower> llt_colmajor_lower_amd;\n  SimplicialLLT<     SparseMatrixType, Upper> llt_colmajor_upper_amd;\n  SimplicialLDLT<    SparseMatrixType, Lower> ldlt_colmajor_lower_amd;\n  SimplicialLDLT<    SparseMatrixType, Upper> ldlt_colmajor_upper_amd;\n  SimplicialLDLT<    SparseMatrixType, Lower, NaturalOrdering<I_> > ldlt_colmajor_lower_nat;\n  SimplicialLDLT<    SparseMatrixType, Upper, NaturalOrdering<I_> > ldlt_colmajor_upper_nat;\n\n  check_sparse_spd_solving(chol_colmajor_lower_amd);\n  check_sparse_spd_solving(chol_colmajor_upper_amd);\n  check_sparse_spd_solving(llt_colmajor_lower_amd);\n  check_sparse_spd_solving(llt_colmajor_upper_amd);\n  check_sparse_spd_solving(ldlt_colmajor_lower_amd);\n  check_sparse_spd_solving(ldlt_colmajor_upper_amd);\n  \n  check_sparse_spd_determinant(chol_colmajor_lower_amd);\n  check_sparse_spd_determinant(chol_colmajor_upper_amd);\n  check_sparse_spd_determinant(llt_colmajor_lower_amd);\n  check_sparse_spd_determinant(llt_colmajor_upper_amd);\n  check_sparse_spd_determinant(ldlt_colmajor_lower_amd);\n  check_sparse_spd_determinant(ldlt_colmajor_upper_amd);\n  \n  check_sparse_spd_solving(ldlt_colmajor_lower_nat, (std::min)(300,EIGEN_TEST_MAX_SIZE), 1000);\n  check_sparse_spd_solving(ldlt_colmajor_upper_nat, (std::min)(300,EIGEN_TEST_MAX_SIZE), 1000);\n}\n\nEIGEN_DECLARE_TEST(simplicial_cholesky)\n{\n  CALL_SUBTEST_11(( test_simplicial_cholesky_T<double,               int, ColMajor>() ));\n  CALL_SUBTEST_12(( test_simplicial_cholesky_T<std::complex<double>, int, ColMajor>() ));\n  CALL_SUBTEST_13(( test_simplicial_cholesky_T<double,          long int, ColMajor>() ));\n  CALL_SUBTEST_21(( test_simplicial_cholesky_T<double,               int, RowMajor>() ));\n  CALL_SUBTEST_22(( test_simplicial_cholesky_T<std::complex<double>, int, RowMajor>() ));\n  CALL_SUBTEST_23(( test_simplicial_cholesky_T<double,          long int, RowMajor>() ));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/sizeof.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void verifySizeOf(const MatrixType&)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  if (MatrixType::RowsAtCompileTime!=Dynamic && MatrixType::ColsAtCompileTime!=Dynamic)\n    VERIFY_IS_EQUAL(std::ptrdiff_t(sizeof(MatrixType)),std::ptrdiff_t(sizeof(Scalar))*std::ptrdiff_t(MatrixType::SizeAtCompileTime));\n  else\n    VERIFY_IS_EQUAL(sizeof(MatrixType),sizeof(Scalar*) + 2 * sizeof(Index));\n}\n\nEIGEN_DECLARE_TEST(sizeof)\n{\n  CALL_SUBTEST(verifySizeOf(Matrix<float, 1, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 2, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 3, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 4, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 5, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 6, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 7, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 8, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 9, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 10, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 11, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Array<float, 12, 1>()) );\n  CALL_SUBTEST(verifySizeOf(Vector2d()) );\n  CALL_SUBTEST(verifySizeOf(Vector4f()) );\n  CALL_SUBTEST(verifySizeOf(Matrix4d()) );\n  CALL_SUBTEST(verifySizeOf(Matrix<double, 4, 2>()) );\n  CALL_SUBTEST(verifySizeOf(Matrix<bool, 7, 5>()) );\n  CALL_SUBTEST(verifySizeOf(MatrixXcf(3, 3)) );\n  CALL_SUBTEST(verifySizeOf(MatrixXi(8, 12)) );\n  CALL_SUBTEST(verifySizeOf(MatrixXcd(20, 20)) );\n  CALL_SUBTEST(verifySizeOf(Matrix<float, 100, 100>()) );\n  \n  VERIFY(sizeof(std::complex<float>) == 2*sizeof(float));\n  VERIFY(sizeof(std::complex<double>) == 2*sizeof(double));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/sizeoverflow.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#define VERIFY_THROWS_BADALLOC(a) {                           \\\n    bool threw = false;                                       \\\n    try {                                                     \\\n      a;                                                      \\\n    }                                                         \\\n    catch (std::bad_alloc&) { threw = true; }                 \\\n    VERIFY(threw && \"should have thrown bad_alloc: \" #a);     \\\n  }\n\ntemplate<typename MatrixType>\nvoid triggerMatrixBadAlloc(Index rows, Index cols)\n{\n  VERIFY_THROWS_BADALLOC( MatrixType m(rows, cols) );\n  VERIFY_THROWS_BADALLOC( MatrixType m; m.resize(rows, cols) );\n  VERIFY_THROWS_BADALLOC( MatrixType m; m.conservativeResize(rows, cols) );\n}\n\ntemplate<typename VectorType>\nvoid triggerVectorBadAlloc(Index size)\n{\n  VERIFY_THROWS_BADALLOC( VectorType v(size) );\n  VERIFY_THROWS_BADALLOC( VectorType v; v.resize(size) );\n  VERIFY_THROWS_BADALLOC( VectorType v; v.conservativeResize(size) );\n}\n\nEIGEN_DECLARE_TEST(sizeoverflow)\n{\n  // there are 2 levels of overflow checking. first in PlainObjectBase.h we check for overflow in rows*cols computations.\n  // this is tested in tests of the form times_itself_gives_0 * times_itself_gives_0\n  // Then in Memory.h we check for overflow in size * sizeof(T) computations.\n  // this is tested in tests of the form times_4_gives_0 * sizeof(float)\n  \n  size_t times_itself_gives_0 = size_t(1) << (8 * sizeof(Index) / 2);\n  VERIFY(times_itself_gives_0 * times_itself_gives_0 == 0);\n\n  size_t times_4_gives_0 = size_t(1) << (8 * sizeof(Index) - 2);\n  VERIFY(times_4_gives_0 * 4 == 0);\n\n  size_t times_8_gives_0 = size_t(1) << (8 * sizeof(Index) - 3);\n  VERIFY(times_8_gives_0 * 8 == 0);\n\n  triggerMatrixBadAlloc<MatrixXf>(times_itself_gives_0, times_itself_gives_0);\n  triggerMatrixBadAlloc<MatrixXf>(times_itself_gives_0 / 4, times_itself_gives_0);\n  triggerMatrixBadAlloc<MatrixXf>(times_4_gives_0, 1);\n\n  triggerMatrixBadAlloc<MatrixXd>(times_itself_gives_0, times_itself_gives_0);\n  triggerMatrixBadAlloc<MatrixXd>(times_itself_gives_0 / 8, times_itself_gives_0);\n  triggerMatrixBadAlloc<MatrixXd>(times_8_gives_0, 1);\n  \n  triggerVectorBadAlloc<VectorXf>(times_4_gives_0);\n  \n  triggerVectorBadAlloc<VectorXd>(times_8_gives_0);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/smallvectors.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_STATIC_ASSERT\n#include \"main.h\"\n\ntemplate<typename Scalar> void smallVectors()\n{\n  typedef Matrix<Scalar, 1, 2> V2;\n  typedef Matrix<Scalar, 3, 1> V3;\n  typedef Matrix<Scalar, 1, 4> V4;\n  typedef Matrix<Scalar, Dynamic, 1> VX;\n  Scalar x1 = internal::random<Scalar>(),\n         x2 = internal::random<Scalar>(),\n         x3 = internal::random<Scalar>(),\n         x4 = internal::random<Scalar>();\n  V2 v2(x1, x2);\n  V3 v3(x1, x2, x3);\n  V4 v4(x1, x2, x3, x4);\n  VERIFY_IS_APPROX(x1, v2.x());\n  VERIFY_IS_APPROX(x1, v3.x());\n  VERIFY_IS_APPROX(x1, v4.x());\n  VERIFY_IS_APPROX(x2, v2.y());\n  VERIFY_IS_APPROX(x2, v3.y());\n  VERIFY_IS_APPROX(x2, v4.y());\n  VERIFY_IS_APPROX(x3, v3.z());\n  VERIFY_IS_APPROX(x3, v4.z());\n  VERIFY_IS_APPROX(x4, v4.w());\n\n  if (!NumTraits<Scalar>::IsInteger)\n  {\n    VERIFY_RAISES_ASSERT(V3(2, 1))\n    VERIFY_RAISES_ASSERT(V3(3, 2))\n    VERIFY_RAISES_ASSERT(V3(Scalar(3), 1))\n    VERIFY_RAISES_ASSERT(V3(3, Scalar(1)))\n    VERIFY_RAISES_ASSERT(V3(Scalar(3), Scalar(1)))\n    VERIFY_RAISES_ASSERT(V3(Scalar(123), Scalar(123)))\n\n    VERIFY_RAISES_ASSERT(V4(1, 3))\n    VERIFY_RAISES_ASSERT(V4(2, 4))\n    VERIFY_RAISES_ASSERT(V4(1, Scalar(4)))\n    VERIFY_RAISES_ASSERT(V4(Scalar(1), 4))\n    VERIFY_RAISES_ASSERT(V4(Scalar(1), Scalar(4)))\n    VERIFY_RAISES_ASSERT(V4(Scalar(123), Scalar(123)))\n\n    VERIFY_RAISES_ASSERT(VX(3, 2))\n    VERIFY_RAISES_ASSERT(VX(Scalar(3), 1))\n    VERIFY_RAISES_ASSERT(VX(3, Scalar(1)))\n    VERIFY_RAISES_ASSERT(VX(Scalar(3), Scalar(1)))\n    VERIFY_RAISES_ASSERT(VX(Scalar(123), Scalar(123)))\n  }\n}\n\nEIGEN_DECLARE_TEST(smallvectors)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST(smallVectors<int>() );\n    CALL_SUBTEST(smallVectors<float>() );\n    CALL_SUBTEST(smallVectors<double>() );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/solverbase.h",
    "content": "#ifndef TEST_SOLVERBASE_H\n#define TEST_SOLVERBASE_H\n\ntemplate<typename DstType, typename RhsType, typename MatrixType, typename SolverType>\nvoid check_solverbase(const MatrixType& matrix, const SolverType& solver, Index rows, Index cols, Index cols2)\n{\n  // solve\n  DstType m2               = DstType::Random(cols,cols2);\n  RhsType m3               = matrix*m2;\n  DstType solver_solution  = DstType::Random(cols,cols2);\n  solver._solve_impl(m3, solver_solution);\n  VERIFY_IS_APPROX(m3, matrix*solver_solution);\n  solver_solution          = DstType::Random(cols,cols2);\n  solver_solution          = solver.solve(m3);\n  VERIFY_IS_APPROX(m3, matrix*solver_solution);\n  // test solve with transposed\n  m3                       = RhsType::Random(rows,cols2);\n  m2                       = matrix.transpose()*m3;\n  RhsType solver_solution2 = RhsType::Random(rows,cols2);\n  solver.template _solve_impl_transposed<false>(m2, solver_solution2);\n  VERIFY_IS_APPROX(m2, matrix.transpose()*solver_solution2);\n  solver_solution2         = RhsType::Random(rows,cols2);\n  solver_solution2         = solver.transpose().solve(m2);\n  VERIFY_IS_APPROX(m2, matrix.transpose()*solver_solution2);\n  // test solve with conjugate transposed\n  m3                       = RhsType::Random(rows,cols2);\n  m2                       = matrix.adjoint()*m3;\n  solver_solution2         = RhsType::Random(rows,cols2);\n  solver.template _solve_impl_transposed<true>(m2, solver_solution2);\n  VERIFY_IS_APPROX(m2, matrix.adjoint()*solver_solution2);\n  solver_solution2         = RhsType::Random(rows,cols2);\n  solver_solution2         = solver.adjoint().solve(m2);\n  VERIFY_IS_APPROX(m2, matrix.adjoint()*solver_solution2);\n}\n\n#endif // TEST_SOLVERBASE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/sparse.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_TESTSPARSE_H\n#define EIGEN_TESTSPARSE_H\n\n#define EIGEN_YES_I_KNOW_SPARSE_MODULE_IS_NOT_STABLE_YET\n\n#include \"main.h\"\n\n#if EIGEN_HAS_CXX11\n\n#ifdef min\n#undef min\n#endif\n\n#ifdef max\n#undef max\n#endif\n\n#include <unordered_map>\n#define EIGEN_UNORDERED_MAP_SUPPORT\n\n#endif\n\n#ifdef EIGEN_GOOGLEHASH_SUPPORT\n  #include <google/sparse_hash_map>\n#endif\n\n#include <Eigen/Cholesky>\n#include <Eigen/LU>\n#include <Eigen/Sparse>\n\nenum {\n  ForceNonZeroDiag = 1,\n  MakeLowerTriangular = 2,\n  MakeUpperTriangular = 4,\n  ForceRealDiag = 8\n};\n\n/* Initializes both a sparse and dense matrix with same random values,\n * and a ratio of \\a density non zero entries.\n * \\param flags is a union of ForceNonZeroDiag, MakeLowerTriangular and MakeUpperTriangular\n *        allowing to control the shape of the matrix.\n * \\param zeroCoords and nonzeroCoords allows to get the coordinate lists of the non zero,\n *        and zero coefficients respectively.\n */\ntemplate<typename Scalar,int Opt1,int Opt2,typename StorageIndex> void\ninitSparse(double density,\n           Matrix<Scalar,Dynamic,Dynamic,Opt1>& refMat,\n           SparseMatrix<Scalar,Opt2,StorageIndex>& sparseMat,\n           int flags = 0,\n           std::vector<Matrix<StorageIndex,2,1> >* zeroCoords = 0,\n           std::vector<Matrix<StorageIndex,2,1> >* nonzeroCoords = 0)\n{\n  enum { IsRowMajor = SparseMatrix<Scalar,Opt2,StorageIndex>::IsRowMajor };\n  sparseMat.setZero();\n  //sparseMat.reserve(int(refMat.rows()*refMat.cols()*density));\n  sparseMat.reserve(VectorXi::Constant(IsRowMajor ? refMat.rows() : refMat.cols(), int((1.5*density)*(IsRowMajor?refMat.cols():refMat.rows()))));\n  \n  for(Index j=0; j<sparseMat.outerSize(); j++)\n  {\n    //sparseMat.startVec(j);\n    for(Index i=0; i<sparseMat.innerSize(); i++)\n    {\n      Index ai(i), aj(j);\n      if(IsRowMajor)\n        std::swap(ai,aj);\n      Scalar v = (internal::random<double>(0,1) < density) ? internal::random<Scalar>() : Scalar(0);\n      if ((flags&ForceNonZeroDiag) && (i==j))\n      {\n        // FIXME: the following is too conservative\n        v = internal::random<Scalar>()*Scalar(3.);\n        v = v*v;\n        if(numext::real(v)>0) v += Scalar(5);\n        else                  v -= Scalar(5);\n      }\n      if ((flags & MakeLowerTriangular) && aj>ai)\n        v = Scalar(0);\n      else if ((flags & MakeUpperTriangular) && aj<ai)\n        v = Scalar(0);\n\n      if ((flags&ForceRealDiag) && (i==j))\n        v = numext::real(v);\n\n      if (v!=Scalar(0))\n      {\n        //sparseMat.insertBackByOuterInner(j,i) = v;\n        sparseMat.insertByOuterInner(j,i) = v;\n        if (nonzeroCoords)\n          nonzeroCoords->push_back(Matrix<StorageIndex,2,1> (ai,aj));\n      }\n      else if (zeroCoords)\n      {\n        zeroCoords->push_back(Matrix<StorageIndex,2,1> (ai,aj));\n      }\n      refMat(ai,aj) = v;\n    }\n  }\n  //sparseMat.finalize();\n}\n\ntemplate<typename Scalar,int Opt1,int Opt2,typename Index> void\ninitSparse(double density,\n           Matrix<Scalar,Dynamic,Dynamic, Opt1>& refMat,\n           DynamicSparseMatrix<Scalar, Opt2, Index>& sparseMat,\n           int flags = 0,\n           std::vector<Matrix<Index,2,1> >* zeroCoords = 0,\n           std::vector<Matrix<Index,2,1> >* nonzeroCoords = 0)\n{\n  enum { IsRowMajor = DynamicSparseMatrix<Scalar,Opt2,Index>::IsRowMajor };\n  sparseMat.setZero();\n  sparseMat.reserve(int(refMat.rows()*refMat.cols()*density));\n  for(int j=0; j<sparseMat.outerSize(); j++)\n  {\n    sparseMat.startVec(j); // not needed for DynamicSparseMatrix\n    for(int i=0; i<sparseMat.innerSize(); i++)\n    {\n      int ai(i), aj(j);\n      if(IsRowMajor)\n        std::swap(ai,aj);\n      Scalar v = (internal::random<double>(0,1) < density) ? internal::random<Scalar>() : Scalar(0);\n      if ((flags&ForceNonZeroDiag) && (i==j))\n      {\n        v = internal::random<Scalar>()*Scalar(3.);\n        v = v*v + Scalar(5.);\n      }\n      if ((flags & MakeLowerTriangular) && aj>ai)\n        v = Scalar(0);\n      else if ((flags & MakeUpperTriangular) && aj<ai)\n        v = Scalar(0);\n\n      if ((flags&ForceRealDiag) && (i==j))\n        v = numext::real(v);\n\n      if (v!=Scalar(0))\n      {\n        sparseMat.insertBackByOuterInner(j,i) = v;\n        if (nonzeroCoords)\n          nonzeroCoords->push_back(Matrix<Index,2,1> (ai,aj));\n      }\n      else if (zeroCoords)\n      {\n        zeroCoords->push_back(Matrix<Index,2,1> (ai,aj));\n      }\n      refMat(ai,aj) = v;\n    }\n  }\n  sparseMat.finalize();\n}\n\ntemplate<typename Scalar,int Options,typename Index> void\ninitSparse(double density,\n           Matrix<Scalar,Dynamic,1>& refVec,\n           SparseVector<Scalar,Options,Index>& sparseVec,\n           std::vector<int>* zeroCoords = 0,\n           std::vector<int>* nonzeroCoords = 0)\n{\n  sparseVec.reserve(int(refVec.size()*density));\n  sparseVec.setZero();\n  for(int i=0; i<refVec.size(); i++)\n  {\n    Scalar v = (internal::random<double>(0,1) < density) ? internal::random<Scalar>() : Scalar(0);\n    if (v!=Scalar(0))\n    {\n      sparseVec.insertBack(i) = v;\n      if (nonzeroCoords)\n        nonzeroCoords->push_back(i);\n    }\n    else if (zeroCoords)\n        zeroCoords->push_back(i);\n    refVec[i] = v;\n  }\n}\n\ntemplate<typename Scalar,int Options,typename Index> void\ninitSparse(double density,\n           Matrix<Scalar,1,Dynamic>& refVec,\n           SparseVector<Scalar,Options,Index>& sparseVec,\n           std::vector<int>* zeroCoords = 0,\n           std::vector<int>* nonzeroCoords = 0)\n{\n  sparseVec.reserve(int(refVec.size()*density));\n  sparseVec.setZero();\n  for(int i=0; i<refVec.size(); i++)\n  {\n    Scalar v = (internal::random<double>(0,1) < density) ? internal::random<Scalar>() : Scalar(0);\n    if (v!=Scalar(0))\n    {\n      sparseVec.insertBack(i) = v;\n      if (nonzeroCoords)\n        nonzeroCoords->push_back(i);\n    }\n    else if (zeroCoords)\n        zeroCoords->push_back(i);\n    refVec[i] = v;\n  }\n}\n\n\n#include <unsupported/Eigen/SparseExtra>\n#endif // EIGEN_TESTSPARSE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/sparseLM.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Desire Nuentsa <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2012 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n#include <iostream>\n#include <fstream>\n#include <iomanip>\n\n#include \"main.h\"\n#include <Eigen/LevenbergMarquardt>\n\nusing namespace std;\nusing namespace Eigen;\n\ntemplate <typename Scalar>\nstruct sparseGaussianTest : SparseFunctor<Scalar, int>\n{\n  typedef Matrix<Scalar,Dynamic,1> VectorType;\n  typedef SparseFunctor<Scalar,int> Base;\n  typedef typename Base::JacobianType JacobianType;\n  sparseGaussianTest(int inputs, int values) : SparseFunctor<Scalar,int>(inputs,values)\n  { }\n  \n  VectorType model(const VectorType& uv, VectorType& x)\n  {\n    VectorType y; //Change this to use expression template\n    int m = Base::values(); \n    int n = Base::inputs();\n    eigen_assert(uv.size()%2 == 0);\n    eigen_assert(uv.size() == n);\n    eigen_assert(x.size() == m);\n    y.setZero(m);\n    int half = n/2;\n    VectorBlock<const VectorType> u(uv, 0, half);\n    VectorBlock<const VectorType> v(uv, half, half);\n    Scalar coeff;\n    for (int j = 0; j < m; j++)\n    {\n      for (int i = 0; i < half; i++) \n      {\n        coeff = (x(j)-i)/v(i);\n        coeff *= coeff;\n        if (coeff < 1. && coeff > 0.)\n          y(j) += u(i)*std::pow((1-coeff), 2);\n      }\n    }\n    return y;\n  }\n  void initPoints(VectorType& uv_ref, VectorType& x)\n  {\n    m_x = x;\n    m_y = this->model(uv_ref,x);\n  }\n  int operator()(const VectorType& uv, VectorType& fvec)\n  {\n    int m = Base::values(); \n    int n = Base::inputs();\n    eigen_assert(uv.size()%2 == 0);\n    eigen_assert(uv.size() == n);\n    int half = n/2;\n    VectorBlock<const VectorType> u(uv, 0, half);\n    VectorBlock<const VectorType> v(uv, half, half);\n    fvec = m_y;\n    Scalar coeff;\n    for (int j = 0; j < m; j++)\n    {\n      for (int i = 0; i < half; i++)\n      {\n        coeff = (m_x(j)-i)/v(i);\n        coeff *= coeff;\n        if (coeff < 1. && coeff > 0.)\n          fvec(j) -= u(i)*std::pow((1-coeff), 2);\n      }\n    }\n    return 0;\n  }\n  \n  int df(const VectorType& uv, JacobianType& fjac)\n  {\n    int m = Base::values(); \n    int n = Base::inputs();\n    eigen_assert(n == uv.size());\n    eigen_assert(fjac.rows() == m);\n    eigen_assert(fjac.cols() == n);\n    int half = n/2;\n    VectorBlock<const VectorType> u(uv, 0, half);\n    VectorBlock<const VectorType> v(uv, half, half);\n    Scalar coeff;\n    \n    //Derivatives with respect to u\n    for (int col = 0; col < half; col++)\n    {\n      for (int row = 0; row < m; row++)\n      {\n        coeff = (m_x(row)-col)/v(col);\n          coeff = coeff*coeff;\n        if(coeff < 1. && coeff > 0.)\n        {\n          fjac.coeffRef(row,col) = -(1-coeff)*(1-coeff);\n        }\n      }\n    }\n    //Derivatives with respect to v\n    for (int col = 0; col < half; col++)\n    {\n      for (int row = 0; row < m; row++)\n      {\n        coeff = (m_x(row)-col)/v(col);\n        coeff = coeff*coeff;\n        if(coeff < 1. && coeff > 0.)\n        {\n          fjac.coeffRef(row,col+half) = -4 * (u(col)/v(col))*coeff*(1-coeff);\n        }\n      }\n    }\n    return 0;\n  }\n  \n  VectorType m_x, m_y; //Data points\n};\n\n\ntemplate<typename T>\nvoid test_sparseLM_T()\n{\n  typedef Matrix<T,Dynamic,1> VectorType;\n  \n  int inputs = 10;\n  int values = 2000;\n  sparseGaussianTest<T> sparse_gaussian(inputs, values);\n  VectorType uv(inputs),uv_ref(inputs);\n  VectorType x(values);\n  // Generate the reference solution \n  uv_ref << -2, 1, 4 ,8, 6, 1.8, 1.2, 1.1, 1.9 , 3;\n  //Generate the reference data points\n  x.setRandom();\n  x = 10*x;\n  x.array() += 10;\n  sparse_gaussian.initPoints(uv_ref, x);\n  \n  \n  // Generate the initial parameters \n  VectorBlock<VectorType> u(uv, 0, inputs/2); \n  VectorBlock<VectorType> v(uv, inputs/2, inputs/2);\n  v.setOnes();\n  //Generate u or Solve for u from v\n  u.setOnes();\n  \n  // Solve the optimization problem\n  LevenbergMarquardt<sparseGaussianTest<T> > lm(sparse_gaussian);\n  int info;\n//   info = lm.minimize(uv);\n  \n  VERIFY_IS_EQUAL(info,1);\n    // Do a step by step solution and save the residual \n  int maxiter = 200;\n  int iter = 0;\n  MatrixXd Err(values, maxiter);\n  MatrixXd Mod(values, maxiter);\n  LevenbergMarquardtSpace::Status status; \n  status = lm.minimizeInit(uv);\n  if (status==LevenbergMarquardtSpace::ImproperInputParameters)\n      return ;\n\n}\nEIGEN_DECLARE_TEST(sparseLM)\n{\n  CALL_SUBTEST_1(test_sparseLM_T<double>());\n  \n  // CALL_SUBTEST_2(test_sparseLM_T<std::complex<double>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/sparse_basic.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2008 Daniel Gomez Ferro <dgomezferro@gmail.com>\n// Copyright (C) 2013 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_TEST_INCLUDED_FROM_SPARSE_EXTRA\nstatic long g_realloc_count = 0;\n#define EIGEN_SPARSE_COMPRESSED_STORAGE_REALLOCATE_PLUGIN g_realloc_count++;\n\nstatic long g_dense_op_sparse_count = 0;\n#define EIGEN_SPARSE_ASSIGNMENT_FROM_DENSE_OP_SPARSE_PLUGIN g_dense_op_sparse_count++;\n#define EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_ADD_DENSE_PLUGIN g_dense_op_sparse_count+=10;\n#define EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_SUB_DENSE_PLUGIN g_dense_op_sparse_count+=20;\n#endif\n\n#include \"sparse.h\"\n\ntemplate<typename SparseMatrixType> void sparse_basic(const SparseMatrixType& ref)\n{\n  typedef typename SparseMatrixType::StorageIndex StorageIndex;\n  typedef Matrix<StorageIndex,2,1> Vector2;\n  \n  const Index rows = ref.rows();\n  const Index cols = ref.cols();\n  //const Index inner = ref.innerSize();\n  //const Index outer = ref.outerSize();\n\n  typedef typename SparseMatrixType::Scalar Scalar;\n  typedef typename SparseMatrixType::RealScalar RealScalar;\n  enum { Flags = SparseMatrixType::Flags };\n\n  double density = (std::max)(8./(rows*cols), 0.01);\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n  Scalar eps = 1e-6;\n\n  Scalar s1 = internal::random<Scalar>();\n  {\n    SparseMatrixType m(rows, cols);\n    DenseMatrix refMat = DenseMatrix::Zero(rows, cols);\n    DenseVector vec1 = DenseVector::Random(rows);\n\n    std::vector<Vector2> zeroCoords;\n    std::vector<Vector2> nonzeroCoords;\n    initSparse<Scalar>(density, refMat, m, 0, &zeroCoords, &nonzeroCoords);\n\n    // test coeff and coeffRef\n    for (std::size_t i=0; i<zeroCoords.size(); ++i)\n    {\n      VERIFY_IS_MUCH_SMALLER_THAN( m.coeff(zeroCoords[i].x(),zeroCoords[i].y()), eps );\n      if(internal::is_same<SparseMatrixType,SparseMatrix<Scalar,Flags> >::value)\n        VERIFY_RAISES_ASSERT( m.coeffRef(zeroCoords[i].x(),zeroCoords[i].y()) = 5 );\n    }\n    VERIFY_IS_APPROX(m, refMat);\n\n    if(!nonzeroCoords.empty()) {\n      m.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5);\n      refMat.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5);\n    }\n\n    VERIFY_IS_APPROX(m, refMat);\n\n      // test assertion\n      VERIFY_RAISES_ASSERT( m.coeffRef(-1,1) = 0 );\n      VERIFY_RAISES_ASSERT( m.coeffRef(0,m.cols()) = 0 );\n    }\n\n    // test insert (inner random)\n    {\n      DenseMatrix m1(rows,cols);\n      m1.setZero();\n      SparseMatrixType m2(rows,cols);\n      bool call_reserve = internal::random<int>()%2;\n      Index nnz = internal::random<int>(1,int(rows)/2);\n      if(call_reserve)\n      {\n        if(internal::random<int>()%2)\n          m2.reserve(VectorXi::Constant(m2.outerSize(), int(nnz)));\n        else\n          m2.reserve(m2.outerSize() * nnz);\n      }\n      g_realloc_count = 0;\n      for (Index j=0; j<cols; ++j)\n      {\n        for (Index k=0; k<nnz; ++k)\n        {\n          Index i = internal::random<Index>(0,rows-1);\n          if (m1.coeff(i,j)==Scalar(0))\n            m2.insert(i,j) = m1(i,j) = internal::random<Scalar>();\n        }\n      }\n      \n      if(call_reserve && !SparseMatrixType::IsRowMajor)\n      {\n        VERIFY(g_realloc_count==0);\n      }\n      \n      m2.finalize();\n      VERIFY_IS_APPROX(m2,m1);\n    }\n\n    // test insert (fully random)\n    {\n      DenseMatrix m1(rows,cols);\n      m1.setZero();\n      SparseMatrixType m2(rows,cols);\n      if(internal::random<int>()%2)\n        m2.reserve(VectorXi::Constant(m2.outerSize(), 2));\n      for (int k=0; k<rows*cols; ++k)\n      {\n        Index i = internal::random<Index>(0,rows-1);\n        Index j = internal::random<Index>(0,cols-1);\n        if ((m1.coeff(i,j)==Scalar(0)) && (internal::random<int>()%2))\n          m2.insert(i,j) = m1(i,j) = internal::random<Scalar>();\n        else\n        {\n          Scalar v = internal::random<Scalar>();\n          m2.coeffRef(i,j) += v;\n          m1(i,j) += v;\n        }\n      }\n      VERIFY_IS_APPROX(m2,m1);\n    }\n    \n    // test insert (un-compressed)\n    for(int mode=0;mode<4;++mode)\n    {\n      DenseMatrix m1(rows,cols);\n      m1.setZero();\n      SparseMatrixType m2(rows,cols);\n      VectorXi r(VectorXi::Constant(m2.outerSize(), ((mode%2)==0) ? int(m2.innerSize()) : std::max<int>(1,int(m2.innerSize())/8)));\n      m2.reserve(r);\n      for (Index k=0; k<rows*cols; ++k)\n      {\n        Index i = internal::random<Index>(0,rows-1);\n        Index j = internal::random<Index>(0,cols-1);\n        if (m1.coeff(i,j)==Scalar(0))\n          m2.insert(i,j) = m1(i,j) = internal::random<Scalar>();\n        if(mode==3)\n          m2.reserve(r);\n      }\n      if(internal::random<int>()%2)\n        m2.makeCompressed();\n      VERIFY_IS_APPROX(m2,m1);\n    }\n\n  // test basic computations\n  {\n    DenseMatrix refM1 = DenseMatrix::Zero(rows, cols);\n    DenseMatrix refM2 = DenseMatrix::Zero(rows, cols);\n    DenseMatrix refM3 = DenseMatrix::Zero(rows, cols);\n    DenseMatrix refM4 = DenseMatrix::Zero(rows, cols);\n    SparseMatrixType m1(rows, cols);\n    SparseMatrixType m2(rows, cols);\n    SparseMatrixType m3(rows, cols);\n    SparseMatrixType m4(rows, cols);\n    initSparse<Scalar>(density, refM1, m1);\n    initSparse<Scalar>(density, refM2, m2);\n    initSparse<Scalar>(density, refM3, m3);\n    initSparse<Scalar>(density, refM4, m4);\n\n    if(internal::random<bool>())\n      m1.makeCompressed();\n\n    Index m1_nnz = m1.nonZeros();\n\n    VERIFY_IS_APPROX(m1*s1, refM1*s1);\n    VERIFY_IS_APPROX(m1+m2, refM1+refM2);\n    VERIFY_IS_APPROX(m1+m2+m3, refM1+refM2+refM3);\n    VERIFY_IS_APPROX(m3.cwiseProduct(m1+m2), refM3.cwiseProduct(refM1+refM2));\n    VERIFY_IS_APPROX(m1*s1-m2, refM1*s1-refM2);\n    VERIFY_IS_APPROX(m4=m1/s1, refM1/s1);\n    VERIFY_IS_EQUAL(m4.nonZeros(), m1_nnz);\n\n    if(SparseMatrixType::IsRowMajor)\n      VERIFY_IS_APPROX(m1.innerVector(0).dot(refM2.row(0)), refM1.row(0).dot(refM2.row(0)));\n    else\n      VERIFY_IS_APPROX(m1.innerVector(0).dot(refM2.col(0)), refM1.col(0).dot(refM2.col(0)));\n\n    DenseVector rv = DenseVector::Random(m1.cols());\n    DenseVector cv = DenseVector::Random(m1.rows());\n    Index r = internal::random<Index>(0,m1.rows()-2);\n    Index c = internal::random<Index>(0,m1.cols()-1);\n    VERIFY_IS_APPROX(( m1.template block<1,Dynamic>(r,0,1,m1.cols()).dot(rv)) , refM1.row(r).dot(rv));\n    VERIFY_IS_APPROX(m1.row(r).dot(rv), refM1.row(r).dot(rv));\n    VERIFY_IS_APPROX(m1.col(c).dot(cv), refM1.col(c).dot(cv));\n\n    VERIFY_IS_APPROX(m1.conjugate(), refM1.conjugate());\n    VERIFY_IS_APPROX(m1.real(), refM1.real());\n\n    refM4.setRandom();\n    // sparse cwise* dense\n    VERIFY_IS_APPROX(m3.cwiseProduct(refM4), refM3.cwiseProduct(refM4));\n    // dense cwise* sparse\n    VERIFY_IS_APPROX(refM4.cwiseProduct(m3), refM4.cwiseProduct(refM3));\n//     VERIFY_IS_APPROX(m3.cwise()/refM4, refM3.cwise()/refM4);\n\n    // mixed sparse-dense\n    VERIFY_IS_APPROX(refM4 + m3, refM4 + refM3);\n    VERIFY_IS_APPROX(m3 + refM4, refM3 + refM4);\n    VERIFY_IS_APPROX(refM4 - m3, refM4 - refM3);\n    VERIFY_IS_APPROX(m3 - refM4, refM3 - refM4);\n    VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + RealScalar(0.5)*m3).eval(), RealScalar(0.5)*refM4 + RealScalar(0.5)*refM3);\n    VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + m3*RealScalar(0.5)).eval(), RealScalar(0.5)*refM4 + RealScalar(0.5)*refM3);\n    VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + m3.cwiseProduct(m3)).eval(), RealScalar(0.5)*refM4 + refM3.cwiseProduct(refM3));\n\n    VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + RealScalar(0.5)*m3).eval(), RealScalar(0.5)*refM4 + RealScalar(0.5)*refM3);\n    VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + m3*RealScalar(0.5)).eval(), RealScalar(0.5)*refM4 + RealScalar(0.5)*refM3);\n    VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + (m3+m3)).eval(), RealScalar(0.5)*refM4 + (refM3+refM3));\n    VERIFY_IS_APPROX(((refM3+m3)+RealScalar(0.5)*m3).eval(), RealScalar(0.5)*refM3 + (refM3+refM3));\n    VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + (refM3+m3)).eval(), RealScalar(0.5)*refM4 + (refM3+refM3));\n    VERIFY_IS_APPROX((RealScalar(0.5)*refM4 + (m3+refM3)).eval(), RealScalar(0.5)*refM4 + (refM3+refM3));\n\n\n    VERIFY_IS_APPROX(m1.sum(), refM1.sum());\n\n    m4 = m1; refM4 = m4;\n\n    VERIFY_IS_APPROX(m1*=s1, refM1*=s1);\n    VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz);\n    VERIFY_IS_APPROX(m1/=s1, refM1/=s1);\n    VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz);\n\n    VERIFY_IS_APPROX(m1+=m2, refM1+=refM2);\n    VERIFY_IS_APPROX(m1-=m2, refM1-=refM2);\n\n    refM3 = refM1;\n    \n    VERIFY_IS_APPROX(refM1+=m2, refM3+=refM2);\n    VERIFY_IS_APPROX(refM1-=m2, refM3-=refM2);\n\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1 =m2+refM4, refM3 =refM2+refM4);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,10);\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1+=m2+refM4, refM3+=refM2+refM4);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,1);\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1-=m2+refM4, refM3-=refM2+refM4);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,1);\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1 =refM4+m2, refM3 =refM2+refM4);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,1);\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1+=refM4+m2, refM3+=refM2+refM4);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,1);\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1-=refM4+m2, refM3-=refM2+refM4);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,1);\n\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1 =m2-refM4, refM3 =refM2-refM4);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,20);\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1+=m2-refM4, refM3+=refM2-refM4);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,1);\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1-=m2-refM4, refM3-=refM2-refM4);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,1);\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1 =refM4-m2, refM3 =refM4-refM2);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,1);\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1+=refM4-m2, refM3+=refM4-refM2);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,1);\n    g_dense_op_sparse_count=0; VERIFY_IS_APPROX(refM1-=refM4-m2, refM3-=refM4-refM2);  VERIFY_IS_EQUAL(g_dense_op_sparse_count,1);\n    refM3 = m3;\n\n    if (rows>=2 && cols>=2)\n    {\n      VERIFY_RAISES_ASSERT( m1 += m1.innerVector(0) );\n      VERIFY_RAISES_ASSERT( m1 -= m1.innerVector(0) );\n      VERIFY_RAISES_ASSERT( refM1 -= m1.innerVector(0) );\n      VERIFY_RAISES_ASSERT( refM1 += m1.innerVector(0) );\n    }\n    m1 = m4; refM1 = refM4;\n\n    // test aliasing\n    VERIFY_IS_APPROX((m1 = -m1), (refM1 = -refM1));\n    VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz);\n    m1 = m4; refM1 = refM4;\n    VERIFY_IS_APPROX((m1 = m1.transpose()), (refM1 = refM1.transpose().eval()));\n    VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz);\n    m1 = m4; refM1 = refM4;\n    VERIFY_IS_APPROX((m1 = -m1.transpose()), (refM1 = -refM1.transpose().eval()));\n    VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz);\n    m1 = m4; refM1 = refM4;\n    VERIFY_IS_APPROX((m1 += -m1), (refM1 += -refM1));\n    VERIFY_IS_EQUAL(m1.nonZeros(), m1_nnz);\n    m1 = m4; refM1 = refM4;\n\n    if(m1.isCompressed())\n    {\n      VERIFY_IS_APPROX(m1.coeffs().sum(), m1.sum());\n      m1.coeffs() += s1;\n      for(Index j = 0; j<m1.outerSize(); ++j)\n        for(typename SparseMatrixType::InnerIterator it(m1,j); it; ++it)\n          refM1(it.row(), it.col()) += s1;\n      VERIFY_IS_APPROX(m1, refM1);\n    }\n\n    // and/or\n    {\n      typedef SparseMatrix<bool, SparseMatrixType::Options, typename SparseMatrixType::StorageIndex> SpBool;\n      SpBool mb1 = m1.real().template cast<bool>();\n      SpBool mb2 = m2.real().template cast<bool>();\n      VERIFY_IS_EQUAL(mb1.template cast<int>().sum(), refM1.real().template cast<bool>().count());\n      VERIFY_IS_EQUAL((mb1 && mb2).template cast<int>().sum(), (refM1.real().template cast<bool>() && refM2.real().template cast<bool>()).count());\n      VERIFY_IS_EQUAL((mb1 || mb2).template cast<int>().sum(), (refM1.real().template cast<bool>() || refM2.real().template cast<bool>()).count());\n      SpBool mb3 = mb1 && mb2;\n      if(mb1.coeffs().all() && mb2.coeffs().all())\n      {\n        VERIFY_IS_EQUAL(mb3.nonZeros(), (refM1.real().template cast<bool>() && refM2.real().template cast<bool>()).count());\n      }\n    }\n  }\n\n  // test reverse iterators\n  {\n    DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols);\n    SparseMatrixType m2(rows, cols);\n    initSparse<Scalar>(density, refMat2, m2);\n    std::vector<Scalar> ref_value(m2.innerSize());\n    std::vector<Index> ref_index(m2.innerSize());\n    if(internal::random<bool>())\n      m2.makeCompressed();\n    for(Index j = 0; j<m2.outerSize(); ++j)\n    {\n      Index count_forward = 0;\n\n      for(typename SparseMatrixType::InnerIterator it(m2,j); it; ++it)\n      {\n        ref_value[ref_value.size()-1-count_forward] = it.value();\n        ref_index[ref_index.size()-1-count_forward] = it.index();\n        count_forward++;\n      }\n      Index count_reverse = 0;\n      for(typename SparseMatrixType::ReverseInnerIterator it(m2,j); it; --it)\n      {\n        VERIFY_IS_APPROX( std::abs(ref_value[ref_value.size()-count_forward+count_reverse])+1, std::abs(it.value())+1);\n        VERIFY_IS_EQUAL( ref_index[ref_index.size()-count_forward+count_reverse] , it.index());\n        count_reverse++;\n      }\n      VERIFY_IS_EQUAL(count_forward, count_reverse);\n    }\n  }\n\n  // test transpose\n  {\n    DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols);\n    SparseMatrixType m2(rows, cols);\n    initSparse<Scalar>(density, refMat2, m2);\n    VERIFY_IS_APPROX(m2.transpose().eval(), refMat2.transpose().eval());\n    VERIFY_IS_APPROX(m2.transpose(), refMat2.transpose());\n\n    VERIFY_IS_APPROX(SparseMatrixType(m2.adjoint()), refMat2.adjoint());\n    \n    // check isApprox handles opposite storage order\n    typename Transpose<SparseMatrixType>::PlainObject m3(m2);\n    VERIFY(m2.isApprox(m3));\n  }\n\n  // test prune\n  {\n    SparseMatrixType m2(rows, cols);\n    DenseMatrix refM2(rows, cols);\n    refM2.setZero();\n    int countFalseNonZero = 0;\n    int countTrueNonZero = 0;\n    m2.reserve(VectorXi::Constant(m2.outerSize(), int(m2.innerSize())));\n    for (Index j=0; j<m2.cols(); ++j)\n    {\n      for (Index i=0; i<m2.rows(); ++i)\n      {\n        float x = internal::random<float>(0,1);\n        if (x<0.1f)\n        {\n          // do nothing\n        }\n        else if (x<0.5f)\n        {\n          countFalseNonZero++;\n          m2.insert(i,j) = Scalar(0);\n        }\n        else\n        {\n          countTrueNonZero++;\n          m2.insert(i,j) = Scalar(1);\n          refM2(i,j) = Scalar(1);\n        }\n      }\n    }\n    if(internal::random<bool>())\n      m2.makeCompressed();\n    VERIFY(countFalseNonZero+countTrueNonZero == m2.nonZeros());\n    if(countTrueNonZero>0)\n      VERIFY_IS_APPROX(m2, refM2);\n    m2.prune(Scalar(1));\n    VERIFY(countTrueNonZero==m2.nonZeros());\n    VERIFY_IS_APPROX(m2, refM2);\n  }\n\n  // test setFromTriplets\n  {\n    typedef Triplet<Scalar,StorageIndex> TripletType;\n    std::vector<TripletType> triplets;\n    Index ntriplets = rows*cols;\n    triplets.reserve(ntriplets);\n    DenseMatrix refMat_sum  = DenseMatrix::Zero(rows,cols);\n    DenseMatrix refMat_prod = DenseMatrix::Zero(rows,cols);\n    DenseMatrix refMat_last = DenseMatrix::Zero(rows,cols);\n\n    for(Index i=0;i<ntriplets;++i)\n    {\n      StorageIndex r = internal::random<StorageIndex>(0,StorageIndex(rows-1));\n      StorageIndex c = internal::random<StorageIndex>(0,StorageIndex(cols-1));\n      Scalar v = internal::random<Scalar>();\n      triplets.push_back(TripletType(r,c,v));\n      refMat_sum(r,c) += v;\n      if(std::abs(refMat_prod(r,c))==0)\n        refMat_prod(r,c) = v;\n      else\n        refMat_prod(r,c) *= v;\n      refMat_last(r,c) = v;\n    }\n    SparseMatrixType m(rows,cols);\n    m.setFromTriplets(triplets.begin(), triplets.end());\n    VERIFY_IS_APPROX(m, refMat_sum);\n\n    m.setFromTriplets(triplets.begin(), triplets.end(), std::multiplies<Scalar>());\n    VERIFY_IS_APPROX(m, refMat_prod);\n#if (EIGEN_COMP_CXXVER >= 11)\n    m.setFromTriplets(triplets.begin(), triplets.end(), [] (Scalar,Scalar b) { return b; });\n    VERIFY_IS_APPROX(m, refMat_last);\n#endif\n  }\n  \n  // test Map\n  {\n    DenseMatrix refMat2(rows, cols), refMat3(rows, cols);\n    SparseMatrixType m2(rows, cols), m3(rows, cols);\n    initSparse<Scalar>(density, refMat2, m2);\n    initSparse<Scalar>(density, refMat3, m3);\n    {\n      Map<SparseMatrixType> mapMat2(m2.rows(), m2.cols(), m2.nonZeros(), m2.outerIndexPtr(), m2.innerIndexPtr(), m2.valuePtr(), m2.innerNonZeroPtr());\n      Map<SparseMatrixType> mapMat3(m3.rows(), m3.cols(), m3.nonZeros(), m3.outerIndexPtr(), m3.innerIndexPtr(), m3.valuePtr(), m3.innerNonZeroPtr());\n      VERIFY_IS_APPROX(mapMat2+mapMat3, refMat2+refMat3);\n      VERIFY_IS_APPROX(mapMat2+mapMat3, refMat2+refMat3);\n    }\n    {\n      MappedSparseMatrix<Scalar,SparseMatrixType::Options,StorageIndex> mapMat2(m2.rows(), m2.cols(), m2.nonZeros(), m2.outerIndexPtr(), m2.innerIndexPtr(), m2.valuePtr(), m2.innerNonZeroPtr());\n      MappedSparseMatrix<Scalar,SparseMatrixType::Options,StorageIndex> mapMat3(m3.rows(), m3.cols(), m3.nonZeros(), m3.outerIndexPtr(), m3.innerIndexPtr(), m3.valuePtr(), m3.innerNonZeroPtr());\n      VERIFY_IS_APPROX(mapMat2+mapMat3, refMat2+refMat3);\n      VERIFY_IS_APPROX(mapMat2+mapMat3, refMat2+refMat3);\n    }\n\n    Index i = internal::random<Index>(0,rows-1);\n    Index j = internal::random<Index>(0,cols-1);\n    m2.coeffRef(i,j) = 123;\n    if(internal::random<bool>())\n      m2.makeCompressed();\n    Map<SparseMatrixType> mapMat2(rows, cols, m2.nonZeros(), m2.outerIndexPtr(), m2.innerIndexPtr(), m2.valuePtr(),  m2.innerNonZeroPtr());\n    VERIFY_IS_EQUAL(m2.coeff(i,j),Scalar(123));\n    VERIFY_IS_EQUAL(mapMat2.coeff(i,j),Scalar(123));\n    mapMat2.coeffRef(i,j) = -123;\n    VERIFY_IS_EQUAL(m2.coeff(i,j),Scalar(-123));\n  }\n\n  // test triangularView\n  {\n    DenseMatrix refMat2(rows, cols), refMat3(rows, cols);\n    SparseMatrixType m2(rows, cols), m3(rows, cols);\n    initSparse<Scalar>(density, refMat2, m2);\n    refMat3 = refMat2.template triangularView<Lower>();\n    m3 = m2.template triangularView<Lower>();\n    VERIFY_IS_APPROX(m3, refMat3);\n\n    refMat3 = refMat2.template triangularView<Upper>();\n    m3 = m2.template triangularView<Upper>();\n    VERIFY_IS_APPROX(m3, refMat3);\n\n    {\n      refMat3 = refMat2.template triangularView<UnitUpper>();\n      m3 = m2.template triangularView<UnitUpper>();\n      VERIFY_IS_APPROX(m3, refMat3);\n\n      refMat3 = refMat2.template triangularView<UnitLower>();\n      m3 = m2.template triangularView<UnitLower>();\n      VERIFY_IS_APPROX(m3, refMat3);\n    }\n\n    refMat3 = refMat2.template triangularView<StrictlyUpper>();\n    m3 = m2.template triangularView<StrictlyUpper>();\n    VERIFY_IS_APPROX(m3, refMat3);\n\n    refMat3 = refMat2.template triangularView<StrictlyLower>();\n    m3 = m2.template triangularView<StrictlyLower>();\n    VERIFY_IS_APPROX(m3, refMat3);\n\n    // check sparse-triangular to dense\n    refMat3 = m2.template triangularView<StrictlyUpper>();\n    VERIFY_IS_APPROX(refMat3, DenseMatrix(refMat2.template triangularView<StrictlyUpper>()));\n  }\n  \n  // test selfadjointView\n  if(!SparseMatrixType::IsRowMajor)\n  {\n    DenseMatrix refMat2(rows, rows), refMat3(rows, rows);\n    SparseMatrixType m2(rows, rows), m3(rows, rows);\n    initSparse<Scalar>(density, refMat2, m2);\n    refMat3 = refMat2.template selfadjointView<Lower>();\n    m3 = m2.template selfadjointView<Lower>();\n    VERIFY_IS_APPROX(m3, refMat3);\n\n    refMat3 += refMat2.template selfadjointView<Lower>();\n    m3 += m2.template selfadjointView<Lower>();\n    VERIFY_IS_APPROX(m3, refMat3);\n\n    refMat3 -= refMat2.template selfadjointView<Lower>();\n    m3 -= m2.template selfadjointView<Lower>();\n    VERIFY_IS_APPROX(m3, refMat3);\n\n    // selfadjointView only works for square matrices:\n    SparseMatrixType m4(rows, rows+1);\n    VERIFY_RAISES_ASSERT(m4.template selfadjointView<Lower>());\n    VERIFY_RAISES_ASSERT(m4.template selfadjointView<Upper>());\n  }\n  \n  // test sparseView\n  {\n    DenseMatrix refMat2 = DenseMatrix::Zero(rows, rows);\n    SparseMatrixType m2(rows, rows);\n    initSparse<Scalar>(density, refMat2, m2);\n    VERIFY_IS_APPROX(m2.eval(), refMat2.sparseView().eval());\n\n    // sparse view on expressions:\n    VERIFY_IS_APPROX((s1*m2).eval(), (s1*refMat2).sparseView().eval());\n    VERIFY_IS_APPROX((m2+m2).eval(), (refMat2+refMat2).sparseView().eval());\n    VERIFY_IS_APPROX((m2*m2).eval(), (refMat2.lazyProduct(refMat2)).sparseView().eval());\n    VERIFY_IS_APPROX((m2*m2).eval(), (refMat2*refMat2).sparseView().eval());\n  }\n\n  // test diagonal\n  {\n    DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols);\n    SparseMatrixType m2(rows, cols);\n    initSparse<Scalar>(density, refMat2, m2);\n    VERIFY_IS_APPROX(m2.diagonal(), refMat2.diagonal().eval());\n    DenseVector d = m2.diagonal();\n    VERIFY_IS_APPROX(d, refMat2.diagonal().eval());\n    d = m2.diagonal().array();\n    VERIFY_IS_APPROX(d, refMat2.diagonal().eval());\n    VERIFY_IS_APPROX(const_cast<const SparseMatrixType&>(m2).diagonal(), refMat2.diagonal().eval());\n    \n    initSparse<Scalar>(density, refMat2, m2, ForceNonZeroDiag);\n    m2.diagonal()      += refMat2.diagonal();\n    refMat2.diagonal() += refMat2.diagonal();\n    VERIFY_IS_APPROX(m2, refMat2);\n  }\n  \n  // test diagonal to sparse\n  {\n    DenseVector d = DenseVector::Random(rows);\n    DenseMatrix refMat2 = d.asDiagonal();\n    SparseMatrixType m2;\n    m2 = d.asDiagonal();\n    VERIFY_IS_APPROX(m2, refMat2);\n    SparseMatrixType m3(d.asDiagonal());\n    VERIFY_IS_APPROX(m3, refMat2);\n    refMat2 += d.asDiagonal();\n    m2 += d.asDiagonal();\n    VERIFY_IS_APPROX(m2, refMat2);\n    m2.setZero();       m2 += d.asDiagonal();\n    refMat2.setZero();  refMat2 += d.asDiagonal();\n    VERIFY_IS_APPROX(m2, refMat2);\n    m2.setZero();       m2 -= d.asDiagonal();\n    refMat2.setZero();  refMat2 -= d.asDiagonal();\n    VERIFY_IS_APPROX(m2, refMat2);\n\n    initSparse<Scalar>(density, refMat2, m2);\n    m2.makeCompressed();\n    m2 += d.asDiagonal();\n    refMat2 += d.asDiagonal();\n    VERIFY_IS_APPROX(m2, refMat2);\n\n    initSparse<Scalar>(density, refMat2, m2);\n    m2.makeCompressed();\n    VectorXi res(rows);\n    for(Index i=0; i<rows; ++i)\n      res(i) = internal::random<int>(0,3);\n    m2.reserve(res);\n    m2 -= d.asDiagonal();\n    refMat2 -= d.asDiagonal();\n    VERIFY_IS_APPROX(m2, refMat2);\n  }\n  \n  // test conservative resize\n  {\n      std::vector< std::pair<StorageIndex,StorageIndex> > inc;\n      if(rows > 3 && cols > 2)\n        inc.push_back(std::pair<StorageIndex,StorageIndex>(-3,-2));\n      inc.push_back(std::pair<StorageIndex,StorageIndex>(0,0));\n      inc.push_back(std::pair<StorageIndex,StorageIndex>(3,2));\n      inc.push_back(std::pair<StorageIndex,StorageIndex>(3,0));\n      inc.push_back(std::pair<StorageIndex,StorageIndex>(0,3));\n      inc.push_back(std::pair<StorageIndex,StorageIndex>(0,-1));\n      inc.push_back(std::pair<StorageIndex,StorageIndex>(-1,0));\n      inc.push_back(std::pair<StorageIndex,StorageIndex>(-1,-1));\n\n      for(size_t i = 0; i< inc.size(); i++) {\n        StorageIndex incRows = inc[i].first;\n        StorageIndex incCols = inc[i].second;\n        SparseMatrixType m1(rows, cols);\n        DenseMatrix refMat1 = DenseMatrix::Zero(rows, cols);\n        initSparse<Scalar>(density, refMat1, m1);\n\n        SparseMatrixType m2 = m1;\n        m2.makeCompressed();\n\n        m1.conservativeResize(rows+incRows, cols+incCols);\n        m2.conservativeResize(rows+incRows, cols+incCols);\n        refMat1.conservativeResize(rows+incRows, cols+incCols);\n        if (incRows > 0) refMat1.bottomRows(incRows).setZero();\n        if (incCols > 0) refMat1.rightCols(incCols).setZero();\n\n        VERIFY_IS_APPROX(m1, refMat1);\n        VERIFY_IS_APPROX(m2, refMat1);\n\n        // Insert new values\n        if (incRows > 0) \n          m1.insert(m1.rows()-1, 0) = refMat1(refMat1.rows()-1, 0) = 1;\n        if (incCols > 0) \n          m1.insert(0, m1.cols()-1) = refMat1(0, refMat1.cols()-1) = 1;\n\n        VERIFY_IS_APPROX(m1, refMat1);\n\n\n      }\n  }\n\n  // test Identity matrix\n  {\n    DenseMatrix refMat1 = DenseMatrix::Identity(rows, rows);\n    SparseMatrixType m1(rows, rows);\n    m1.setIdentity();\n    VERIFY_IS_APPROX(m1, refMat1);\n    for(int k=0; k<rows*rows/4; ++k)\n    {\n      Index i = internal::random<Index>(0,rows-1);\n      Index j = internal::random<Index>(0,rows-1);\n      Scalar v = internal::random<Scalar>();\n      m1.coeffRef(i,j) = v;\n      refMat1.coeffRef(i,j) = v;\n      VERIFY_IS_APPROX(m1, refMat1);\n      if(internal::random<Index>(0,10)<2)\n        m1.makeCompressed();\n    }\n    m1.setIdentity();\n    refMat1.setIdentity();\n    VERIFY_IS_APPROX(m1, refMat1);\n  }\n\n  // test array/vector of InnerIterator\n  {\n    typedef typename SparseMatrixType::InnerIterator IteratorType;\n\n    DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols);\n    SparseMatrixType m2(rows, cols);\n    initSparse<Scalar>(density, refMat2, m2);\n    IteratorType static_array[2];\n    static_array[0] = IteratorType(m2,0);\n    static_array[1] = IteratorType(m2,m2.outerSize()-1);\n    VERIFY( static_array[0] || m2.innerVector(static_array[0].outer()).nonZeros() == 0 );\n    VERIFY( static_array[1] || m2.innerVector(static_array[1].outer()).nonZeros() == 0 );\n    if(static_array[0] && static_array[1])\n    {\n      ++(static_array[1]);\n      static_array[1] = IteratorType(m2,0);\n      VERIFY( static_array[1] );\n      VERIFY( static_array[1].index() == static_array[0].index() );\n      VERIFY( static_array[1].outer() == static_array[0].outer() );\n      VERIFY( static_array[1].value() == static_array[0].value() );\n    }\n\n    std::vector<IteratorType> iters(2);\n    iters[0] = IteratorType(m2,0);\n    iters[1] = IteratorType(m2,m2.outerSize()-1);\n  }\n\n  // test reserve with empty rows/columns\n  {\n    SparseMatrixType m1(0,cols);\n    m1.reserve(ArrayXi::Constant(m1.outerSize(),1));\n    SparseMatrixType m2(rows,0);\n    m2.reserve(ArrayXi::Constant(m2.outerSize(),1));\n  }\n}\n\n\ntemplate<typename SparseMatrixType>\nvoid big_sparse_triplet(Index rows, Index cols, double density) {\n  typedef typename SparseMatrixType::StorageIndex StorageIndex;\n  typedef typename SparseMatrixType::Scalar Scalar;\n  typedef Triplet<Scalar,Index> TripletType;\n  std::vector<TripletType> triplets;\n  double nelements = density * rows*cols;\n  VERIFY(nelements>=0 && nelements < static_cast<double>(NumTraits<StorageIndex>::highest()));\n  Index ntriplets = Index(nelements);\n  triplets.reserve(ntriplets);\n  Scalar sum = Scalar(0);\n  for(Index i=0;i<ntriplets;++i)\n  {\n    Index r = internal::random<Index>(0,rows-1);\n    Index c = internal::random<Index>(0,cols-1);\n    // use positive values to prevent numerical cancellation errors in sum\n    Scalar v = numext::abs(internal::random<Scalar>());\n    triplets.push_back(TripletType(r,c,v));\n    sum += v;\n  }\n  SparseMatrixType m(rows,cols);\n  m.setFromTriplets(triplets.begin(), triplets.end());\n  VERIFY(m.nonZeros() <= ntriplets);\n  VERIFY_IS_APPROX(sum, m.sum());\n}\n\ntemplate<int>\nvoid bug1105()\n{\n  // Regression test for bug 1105\n  int n = Eigen::internal::random<int>(200,600);\n  SparseMatrix<std::complex<double>,0, long> mat(n, n);\n  std::complex<double> val;\n\n  for(int i=0; i<n; ++i)\n  {\n    mat.coeffRef(i, i%(n/10)) = val;\n    VERIFY(mat.data().allocatedSize()<20*n);\n  }\n}\n\n#ifndef EIGEN_SPARSE_TEST_INCLUDED_FROM_SPARSE_EXTRA\n\nEIGEN_DECLARE_TEST(sparse_basic)\n{\n  g_dense_op_sparse_count = 0;  // Suppresses compiler warning.\n  for(int i = 0; i < g_repeat; i++) {\n    int r = Eigen::internal::random<int>(1,200), c = Eigen::internal::random<int>(1,200);\n    if(Eigen::internal::random<int>(0,4) == 0) {\n      r = c; // check square matrices in 25% of tries\n    }\n    EIGEN_UNUSED_VARIABLE(r+c);\n    CALL_SUBTEST_1(( sparse_basic(SparseMatrix<double>(1, 1)) ));\n    CALL_SUBTEST_1(( sparse_basic(SparseMatrix<double>(8, 8)) ));\n    CALL_SUBTEST_2(( sparse_basic(SparseMatrix<std::complex<double>, ColMajor>(r, c)) ));\n    CALL_SUBTEST_2(( sparse_basic(SparseMatrix<std::complex<double>, RowMajor>(r, c)) ));\n    CALL_SUBTEST_1(( sparse_basic(SparseMatrix<double>(r, c)) ));\n    CALL_SUBTEST_5(( sparse_basic(SparseMatrix<double,ColMajor,long int>(r, c)) ));\n    CALL_SUBTEST_5(( sparse_basic(SparseMatrix<double,RowMajor,long int>(r, c)) ));\n    \n    r = Eigen::internal::random<int>(1,100);\n    c = Eigen::internal::random<int>(1,100);\n    if(Eigen::internal::random<int>(0,4) == 0) {\n      r = c; // check square matrices in 25% of tries\n    }\n    \n    CALL_SUBTEST_6(( sparse_basic(SparseMatrix<double,ColMajor,short int>(short(r), short(c))) ));\n    CALL_SUBTEST_6(( sparse_basic(SparseMatrix<double,RowMajor,short int>(short(r), short(c))) ));\n  }\n\n  // Regression test for bug 900: (manually insert higher values here, if you have enough RAM):\n  CALL_SUBTEST_3((big_sparse_triplet<SparseMatrix<float, RowMajor, int> >(10000, 10000, 0.125)));\n  CALL_SUBTEST_4((big_sparse_triplet<SparseMatrix<double, ColMajor, long int> >(10000, 10000, 0.125)));\n\n  CALL_SUBTEST_7( bug1105<0>() );\n}\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/sparse_block.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"sparse.h\"\n#include \"AnnoyingScalar.h\"\n\ntemplate<typename T>\ntypename Eigen::internal::enable_if<(T::Flags&RowMajorBit)==RowMajorBit, typename T::RowXpr>::type\ninnervec(T& A, Index i)\n{\n  return A.row(i);\n}\n\ntemplate<typename T>\ntypename Eigen::internal::enable_if<(T::Flags&RowMajorBit)==0, typename T::ColXpr>::type\ninnervec(T& A, Index i)\n{\n  return A.col(i);\n}\n\ntemplate<typename SparseMatrixType> void sparse_block(const SparseMatrixType& ref)\n{\n  const Index rows = ref.rows();\n  const Index cols = ref.cols();\n  const Index inner = ref.innerSize();\n  const Index outer = ref.outerSize();\n\n  typedef typename SparseMatrixType::Scalar Scalar;\n  typedef typename SparseMatrixType::RealScalar RealScalar;\n  typedef typename SparseMatrixType::StorageIndex StorageIndex;\n\n  double density = (std::max)(8./(rows*cols), 0.01);\n  typedef Matrix<Scalar,Dynamic,Dynamic,SparseMatrixType::IsRowMajor?RowMajor:ColMajor> DenseMatrix;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n  typedef Matrix<Scalar,1,Dynamic> RowDenseVector;\n  typedef SparseVector<Scalar> SparseVectorType;\n\n  Scalar s1 = internal::random<Scalar>();\n  {\n    SparseMatrixType m(rows, cols);\n    DenseMatrix refMat = DenseMatrix::Zero(rows, cols);\n    initSparse<Scalar>(density, refMat, m);\n\n    VERIFY_IS_APPROX(m, refMat);\n\n    // test InnerIterators and Block expressions\n    for (int t=0; t<10; ++t)\n    {\n      Index j = internal::random<Index>(0,cols-2);\n      Index i = internal::random<Index>(0,rows-2);\n      Index w = internal::random<Index>(1,cols-j);\n      Index h = internal::random<Index>(1,rows-i);\n\n      VERIFY_IS_APPROX(m.block(i,j,h,w), refMat.block(i,j,h,w));\n      for(Index c=0; c<w; c++)\n      {\n        VERIFY_IS_APPROX(m.block(i,j,h,w).col(c), refMat.block(i,j,h,w).col(c));\n        for(Index r=0; r<h; r++)\n        {\n          VERIFY_IS_APPROX(m.block(i,j,h,w).col(c).coeff(r), refMat.block(i,j,h,w).col(c).coeff(r));\n          VERIFY_IS_APPROX(m.block(i,j,h,w).coeff(r,c), refMat.block(i,j,h,w).coeff(r,c));\n        }\n      }\n      for(Index r=0; r<h; r++)\n      {\n        VERIFY_IS_APPROX(m.block(i,j,h,w).row(r), refMat.block(i,j,h,w).row(r));\n        for(Index c=0; c<w; c++)\n        {\n          VERIFY_IS_APPROX(m.block(i,j,h,w).row(r).coeff(c), refMat.block(i,j,h,w).row(r).coeff(c));\n          VERIFY_IS_APPROX(m.block(i,j,h,w).coeff(r,c), refMat.block(i,j,h,w).coeff(r,c));\n        }\n      }\n      \n      VERIFY_IS_APPROX(m.middleCols(j,w), refMat.middleCols(j,w));\n      VERIFY_IS_APPROX(m.middleRows(i,h), refMat.middleRows(i,h));\n      for(Index r=0; r<h; r++)\n      {\n        VERIFY_IS_APPROX(m.middleCols(j,w).row(r), refMat.middleCols(j,w).row(r));\n        VERIFY_IS_APPROX(m.middleRows(i,h).row(r), refMat.middleRows(i,h).row(r));\n        for(Index c=0; c<w; c++)\n        {\n          VERIFY_IS_APPROX(m.col(c).coeff(r), refMat.col(c).coeff(r));\n          VERIFY_IS_APPROX(m.row(r).coeff(c), refMat.row(r).coeff(c));\n          \n          VERIFY_IS_APPROX(m.middleCols(j,w).coeff(r,c), refMat.middleCols(j,w).coeff(r,c));\n          VERIFY_IS_APPROX(m.middleRows(i,h).coeff(r,c), refMat.middleRows(i,h).coeff(r,c));\n          if(m.middleCols(j,w).coeff(r,c) != Scalar(0))\n          {\n            VERIFY_IS_APPROX(m.middleCols(j,w).coeffRef(r,c), refMat.middleCols(j,w).coeff(r,c));\n          }\n          if(m.middleRows(i,h).coeff(r,c) != Scalar(0))\n          {\n            VERIFY_IS_APPROX(m.middleRows(i,h).coeff(r,c), refMat.middleRows(i,h).coeff(r,c));\n          }\n        }\n      }\n      for(Index c=0; c<w; c++)\n      {\n        VERIFY_IS_APPROX(m.middleCols(j,w).col(c), refMat.middleCols(j,w).col(c));\n        VERIFY_IS_APPROX(m.middleRows(i,h).col(c), refMat.middleRows(i,h).col(c));\n      }\n    }\n\n    for(Index c=0; c<cols; c++)\n    {\n      VERIFY_IS_APPROX(m.col(c) + m.col(c), (m + m).col(c));\n      VERIFY_IS_APPROX(m.col(c) + m.col(c), refMat.col(c) + refMat.col(c));\n    }\n\n    for(Index r=0; r<rows; r++)\n    {\n      VERIFY_IS_APPROX(m.row(r) + m.row(r), (m + m).row(r));\n      VERIFY_IS_APPROX(m.row(r) + m.row(r), refMat.row(r) + refMat.row(r));\n    }\n  }\n\n  // test innerVector()\n  {\n    DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols);\n    SparseMatrixType m2(rows, cols);\n    initSparse<Scalar>(density, refMat2, m2);\n    Index j0 = internal::random<Index>(0,outer-1);\n    Index j1 = internal::random<Index>(0,outer-1);\n    Index r0 = internal::random<Index>(0,rows-1);\n    Index c0 = internal::random<Index>(0,cols-1);\n\n    VERIFY_IS_APPROX(m2.innerVector(j0), innervec(refMat2,j0));\n    VERIFY_IS_APPROX(m2.innerVector(j0)+m2.innerVector(j1), innervec(refMat2,j0)+innervec(refMat2,j1));\n\n    m2.innerVector(j0) *= Scalar(2);\n    innervec(refMat2,j0) *= Scalar(2);\n    VERIFY_IS_APPROX(m2, refMat2);\n\n    m2.row(r0) *= Scalar(3);\n    refMat2.row(r0) *= Scalar(3);\n    VERIFY_IS_APPROX(m2, refMat2);\n\n    m2.col(c0) *= Scalar(4);\n    refMat2.col(c0) *= Scalar(4);\n    VERIFY_IS_APPROX(m2, refMat2);\n\n    m2.row(r0) /= Scalar(3);\n    refMat2.row(r0) /= Scalar(3);\n    VERIFY_IS_APPROX(m2, refMat2);\n\n    m2.col(c0) /= Scalar(4);\n    refMat2.col(c0) /= Scalar(4);\n    VERIFY_IS_APPROX(m2, refMat2);\n\n    SparseVectorType v1;\n    VERIFY_IS_APPROX(v1 = m2.col(c0) * 4, refMat2.col(c0)*4);\n    VERIFY_IS_APPROX(v1 = m2.row(r0) * 4, refMat2.row(r0).transpose()*4);\n\n    SparseMatrixType m3(rows,cols);\n    m3.reserve(VectorXi::Constant(outer,int(inner/2)));\n    for(Index j=0; j<outer; ++j)\n      for(Index k=0; k<(std::min)(j,inner); ++k)\n        m3.insertByOuterInner(j,k) = internal::convert_index<StorageIndex>(k+1);\n    for(Index j=0; j<(std::min)(outer, inner); ++j)\n    {\n      VERIFY(j==numext::real(m3.innerVector(j).nonZeros()));\n      if(j>0)\n        VERIFY(RealScalar(j)==numext::real(m3.innerVector(j).lastCoeff()));\n    }\n    m3.makeCompressed();\n    for(Index j=0; j<(std::min)(outer, inner); ++j)\n    {\n      VERIFY(j==numext::real(m3.innerVector(j).nonZeros()));\n      if(j>0)\n        VERIFY(RealScalar(j)==numext::real(m3.innerVector(j).lastCoeff()));\n    }\n\n    VERIFY(m3.innerVector(j0).nonZeros() == m3.transpose().innerVector(j0).nonZeros());\n\n//     m2.innerVector(j0) = 2*m2.innerVector(j1);\n//     refMat2.col(j0) = 2*refMat2.col(j1);\n//     VERIFY_IS_APPROX(m2, refMat2);\n  }\n\n  // test innerVectors()\n  {\n    DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols);\n    SparseMatrixType m2(rows, cols);\n    initSparse<Scalar>(density, refMat2, m2);\n    if(internal::random<float>(0,1)>0.5f) m2.makeCompressed();\n    Index j0 = internal::random<Index>(0,outer-2);\n    Index j1 = internal::random<Index>(0,outer-2);\n    Index n0 = internal::random<Index>(1,outer-(std::max)(j0,j1));\n    if(SparseMatrixType::IsRowMajor)\n      VERIFY_IS_APPROX(m2.innerVectors(j0,n0), refMat2.block(j0,0,n0,cols));\n    else\n      VERIFY_IS_APPROX(m2.innerVectors(j0,n0), refMat2.block(0,j0,rows,n0));\n    if(SparseMatrixType::IsRowMajor)\n      VERIFY_IS_APPROX(m2.innerVectors(j0,n0)+m2.innerVectors(j1,n0),\n                       refMat2.middleRows(j0,n0)+refMat2.middleRows(j1,n0));\n    else\n      VERIFY_IS_APPROX(m2.innerVectors(j0,n0)+m2.innerVectors(j1,n0),\n                      refMat2.block(0,j0,rows,n0)+refMat2.block(0,j1,rows,n0));\n    \n    VERIFY_IS_APPROX(m2, refMat2);\n    \n    VERIFY(m2.innerVectors(j0,n0).nonZeros() == m2.transpose().innerVectors(j0,n0).nonZeros());\n    \n    m2.innerVectors(j0,n0) = m2.innerVectors(j0,n0) + m2.innerVectors(j1,n0);\n    if(SparseMatrixType::IsRowMajor)\n      refMat2.middleRows(j0,n0) = (refMat2.middleRows(j0,n0) + refMat2.middleRows(j1,n0)).eval();\n    else\n      refMat2.middleCols(j0,n0) = (refMat2.middleCols(j0,n0) + refMat2.middleCols(j1,n0)).eval();\n    \n    VERIFY_IS_APPROX(m2, refMat2);\n  }\n\n  // test generic blocks\n  {\n    DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols);\n    SparseMatrixType m2(rows, cols);\n    initSparse<Scalar>(density, refMat2, m2);\n    Index j0 = internal::random<Index>(0,outer-2);\n    Index j1 = internal::random<Index>(0,outer-2);\n    Index n0 = internal::random<Index>(1,outer-(std::max)(j0,j1));\n    if(SparseMatrixType::IsRowMajor)\n      VERIFY_IS_APPROX(m2.block(j0,0,n0,cols), refMat2.block(j0,0,n0,cols));\n    else\n      VERIFY_IS_APPROX(m2.block(0,j0,rows,n0), refMat2.block(0,j0,rows,n0));\n    \n    if(SparseMatrixType::IsRowMajor)\n      VERIFY_IS_APPROX(m2.block(j0,0,n0,cols)+m2.block(j1,0,n0,cols),\n                      refMat2.block(j0,0,n0,cols)+refMat2.block(j1,0,n0,cols));\n    else\n      VERIFY_IS_APPROX(m2.block(0,j0,rows,n0)+m2.block(0,j1,rows,n0),\n                      refMat2.block(0,j0,rows,n0)+refMat2.block(0,j1,rows,n0));\n      \n    Index i = internal::random<Index>(0,m2.outerSize()-1);\n    if(SparseMatrixType::IsRowMajor) {\n      m2.innerVector(i) = m2.innerVector(i) * s1;\n      refMat2.row(i) = refMat2.row(i) * s1;\n      VERIFY_IS_APPROX(m2,refMat2);\n    } else {\n      m2.innerVector(i) = m2.innerVector(i) * s1;\n      refMat2.col(i) = refMat2.col(i) * s1;\n      VERIFY_IS_APPROX(m2,refMat2);\n    }\n    \n    Index r0 = internal::random<Index>(0,rows-2);\n    Index c0 = internal::random<Index>(0,cols-2);\n    Index r1 = internal::random<Index>(1,rows-r0);\n    Index c1 = internal::random<Index>(1,cols-c0);\n    \n    VERIFY_IS_APPROX(DenseVector(m2.col(c0)), refMat2.col(c0));\n    VERIFY_IS_APPROX(m2.col(c0), refMat2.col(c0));\n    \n    VERIFY_IS_APPROX(RowDenseVector(m2.row(r0)), refMat2.row(r0));\n    VERIFY_IS_APPROX(m2.row(r0), refMat2.row(r0));\n\n    VERIFY_IS_APPROX(m2.block(r0,c0,r1,c1), refMat2.block(r0,c0,r1,c1));\n    VERIFY_IS_APPROX((2*m2).block(r0,c0,r1,c1), (2*refMat2).block(r0,c0,r1,c1));\n\n    if(m2.nonZeros()>0)\n    {\n      VERIFY_IS_APPROX(m2, refMat2);\n      SparseMatrixType m3(rows, cols);\n      DenseMatrix refMat3(rows, cols); refMat3.setZero();\n      Index n = internal::random<Index>(1,10);\n      for(Index k=0; k<n; ++k)\n      {\n        Index o1 = internal::random<Index>(0,outer-1);\n        Index o2 = internal::random<Index>(0,outer-1);\n        if(SparseMatrixType::IsRowMajor)\n        {\n          m3.innerVector(o1) = m2.row(o2);\n          refMat3.row(o1) = refMat2.row(o2);\n        }\n        else\n        {\n          m3.innerVector(o1) = m2.col(o2);\n          refMat3.col(o1) = refMat2.col(o2);\n        }\n        if(internal::random<bool>())\n          m3.makeCompressed();\n      }\n      if(m3.nonZeros()>0)\n      VERIFY_IS_APPROX(m3, refMat3);\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(sparse_block)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    int r = Eigen::internal::random<int>(1,200), c = Eigen::internal::random<int>(1,200);\n    if(Eigen::internal::random<int>(0,4) == 0) {\n      r = c; // check square matrices in 25% of tries\n    }\n    EIGEN_UNUSED_VARIABLE(r+c);\n    CALL_SUBTEST_1(( sparse_block(SparseMatrix<double>(1, 1)) ));\n    CALL_SUBTEST_1(( sparse_block(SparseMatrix<double>(8, 8)) ));\n    CALL_SUBTEST_1(( sparse_block(SparseMatrix<double>(r, c)) ));\n    CALL_SUBTEST_2(( sparse_block(SparseMatrix<std::complex<double>, ColMajor>(r, c)) ));\n    CALL_SUBTEST_2(( sparse_block(SparseMatrix<std::complex<double>, RowMajor>(r, c)) ));\n    \n    CALL_SUBTEST_3(( sparse_block(SparseMatrix<double,ColMajor,long int>(r, c)) ));\n    CALL_SUBTEST_3(( sparse_block(SparseMatrix<double,RowMajor,long int>(r, c)) ));\n    \n    r = Eigen::internal::random<int>(1,100);\n    c = Eigen::internal::random<int>(1,100);\n    if(Eigen::internal::random<int>(0,4) == 0) {\n      r = c; // check square matrices in 25% of tries\n    }\n    \n    CALL_SUBTEST_4(( sparse_block(SparseMatrix<double,ColMajor,short int>(short(r), short(c))) ));\n    CALL_SUBTEST_4(( sparse_block(SparseMatrix<double,RowMajor,short int>(short(r), short(c))) ));\n\n    AnnoyingScalar::dont_throw = true;\n    CALL_SUBTEST_5((  sparse_block(SparseMatrix<AnnoyingScalar>(r,c)) ));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/sparse_permutations.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\nstatic long int nb_transposed_copies;\n#define EIGEN_SPARSE_TRANSPOSED_COPY_PLUGIN {nb_transposed_copies++;}\n#define VERIFY_TRANSPOSITION_COUNT(XPR,N) {\\\n    nb_transposed_copies = 0; \\\n    XPR; \\\n    if(nb_transposed_copies!=N) std::cerr << \"nb_transposed_copies == \" << nb_transposed_copies << \"\\n\"; \\\n    VERIFY( (#XPR) && nb_transposed_copies==N ); \\\n  }\n\n#include \"sparse.h\"\n\ntemplate<typename T>\nbool is_sorted(const T& mat) {\n  for(Index k = 0; k<mat.outerSize(); ++k)\n  {\n    Index prev = -1;\n    for(typename T::InnerIterator it(mat,k); it; ++it)\n    {\n      if(prev>=it.index())\n        return false;\n      prev = it.index();\n    }\n  }\n  return true;\n}\n\ntemplate<typename T>\ntypename internal::nested_eval<T,1>::type eval(const T &xpr)\n{\n  VERIFY( int(internal::nested_eval<T,1>::type::Flags&RowMajorBit) == int(internal::evaluator<T>::Flags&RowMajorBit) );\n  return xpr;\n}\n\ntemplate<int OtherStorage, typename SparseMatrixType> void sparse_permutations(const SparseMatrixType& ref)\n{\n  const Index rows = ref.rows();\n  const Index cols = ref.cols();\n  typedef typename SparseMatrixType::Scalar Scalar;\n  typedef typename SparseMatrixType::StorageIndex StorageIndex;\n  typedef SparseMatrix<Scalar, OtherStorage, StorageIndex> OtherSparseMatrixType;\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  typedef Matrix<StorageIndex,Dynamic,1> VectorI;\n//   bool IsRowMajor1 = SparseMatrixType::IsRowMajor;\n//   bool IsRowMajor2 = OtherSparseMatrixType::IsRowMajor;\n  \n  double density = (std::max)(8./(rows*cols), 0.01);\n  \n  SparseMatrixType mat(rows, cols), up(rows,cols), lo(rows,cols);\n  OtherSparseMatrixType res;\n  DenseMatrix mat_d = DenseMatrix::Zero(rows, cols), up_sym_d, lo_sym_d, res_d;\n  \n  initSparse<Scalar>(density, mat_d, mat, 0);\n\n  up = mat.template triangularView<Upper>();\n  lo = mat.template triangularView<Lower>();\n  \n  up_sym_d = mat_d.template selfadjointView<Upper>();\n  lo_sym_d = mat_d.template selfadjointView<Lower>();\n  \n  VERIFY_IS_APPROX(mat, mat_d);\n  VERIFY_IS_APPROX(up, DenseMatrix(mat_d.template triangularView<Upper>()));\n  VERIFY_IS_APPROX(lo, DenseMatrix(mat_d.template triangularView<Lower>()));\n  \n  PermutationMatrix<Dynamic> p, p_null;\n  VectorI pi;\n  randomPermutationVector(pi, cols);\n  p.indices() = pi;\n\n  VERIFY( is_sorted( ::eval(mat*p) ));\n  VERIFY( is_sorted( res = mat*p ));\n  VERIFY_TRANSPOSITION_COUNT( ::eval(mat*p), 0);\n  //VERIFY_TRANSPOSITION_COUNT( res = mat*p, IsRowMajor ? 1 : 0 );\n  res_d = mat_d*p;\n  VERIFY(res.isApprox(res_d) && \"mat*p\");\n\n  VERIFY( is_sorted( ::eval(p*mat) ));\n  VERIFY( is_sorted( res = p*mat ));\n  VERIFY_TRANSPOSITION_COUNT( ::eval(p*mat), 0);\n  res_d = p*mat_d;\n  VERIFY(res.isApprox(res_d) && \"p*mat\");\n\n  VERIFY( is_sorted( (mat*p).eval() ));\n  VERIFY( is_sorted( res = mat*p.inverse() ));\n  VERIFY_TRANSPOSITION_COUNT( ::eval(mat*p.inverse()), 0);\n  res_d = mat*p.inverse();\n  VERIFY(res.isApprox(res_d) && \"mat*inv(p)\");\n\n  VERIFY( is_sorted( (p*mat+p*mat).eval() ));\n  VERIFY( is_sorted( res = p.inverse()*mat ));\n  VERIFY_TRANSPOSITION_COUNT( ::eval(p.inverse()*mat), 0);\n  res_d = p.inverse()*mat_d;\n  VERIFY(res.isApprox(res_d) && \"inv(p)*mat\");\n\n  VERIFY( is_sorted( (p * mat * p.inverse()).eval() ));\n  VERIFY( is_sorted( res = mat.twistedBy(p) ));\n  VERIFY_TRANSPOSITION_COUNT( ::eval(p * mat * p.inverse()), 0);\n  res_d = (p * mat_d) * p.inverse();\n  VERIFY(res.isApprox(res_d) && \"p*mat*inv(p)\");\n\n  \n  VERIFY( is_sorted( res = mat.template selfadjointView<Upper>().twistedBy(p_null) ));\n  res_d = up_sym_d;\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint upper to full\");\n  \n  VERIFY( is_sorted( res = mat.template selfadjointView<Lower>().twistedBy(p_null) ));\n  res_d = lo_sym_d;\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint lower to full\");\n  \n  \n  VERIFY( is_sorted( res = up.template selfadjointView<Upper>().twistedBy(p_null) ));\n  res_d = up_sym_d;\n  VERIFY(res.isApprox(res_d) && \"upper selfadjoint to full\");\n  \n  VERIFY( is_sorted( res = lo.template selfadjointView<Lower>().twistedBy(p_null) ));\n  res_d = lo_sym_d;\n  VERIFY(res.isApprox(res_d) && \"lower selfadjoint full\");\n\n\n  VERIFY( is_sorted( res = mat.template selfadjointView<Upper>() ));\n  res_d = up_sym_d;\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint upper to full\");\n\n  VERIFY( is_sorted( res = mat.template selfadjointView<Lower>() ));\n  res_d = lo_sym_d;\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint lower to full\");\n\n  VERIFY( is_sorted( res = up.template selfadjointView<Upper>() ));\n  res_d = up_sym_d;\n  VERIFY(res.isApprox(res_d) && \"upper selfadjoint to full\");\n\n  VERIFY( is_sorted( res = lo.template selfadjointView<Lower>() ));\n  res_d = lo_sym_d;\n  VERIFY(res.isApprox(res_d) && \"lower selfadjoint full\");\n\n\n  res.template selfadjointView<Upper>() = mat.template selfadjointView<Upper>();\n  res_d = up_sym_d.template triangularView<Upper>();\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint upper to upper\");\n\n  res.template selfadjointView<Lower>() = mat.template selfadjointView<Upper>();\n  res_d = up_sym_d.template triangularView<Lower>();\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint upper to lower\");\n\n  res.template selfadjointView<Upper>() = mat.template selfadjointView<Lower>();\n  res_d = lo_sym_d.template triangularView<Upper>();\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint lower to upper\");\n\n  res.template selfadjointView<Lower>() = mat.template selfadjointView<Lower>();\n  res_d = lo_sym_d.template triangularView<Lower>();\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint lower to lower\");\n\n  \n  \n  res.template selfadjointView<Upper>() = mat.template selfadjointView<Upper>().twistedBy(p);\n  res_d = ((p * up_sym_d) * p.inverse()).eval().template triangularView<Upper>();\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint upper twisted to upper\");\n  \n  res.template selfadjointView<Upper>() = mat.template selfadjointView<Lower>().twistedBy(p);\n  res_d = ((p * lo_sym_d) * p.inverse()).eval().template triangularView<Upper>();\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint lower twisted to upper\");\n  \n  res.template selfadjointView<Lower>() = mat.template selfadjointView<Lower>().twistedBy(p);\n  res_d = ((p * lo_sym_d) * p.inverse()).eval().template triangularView<Lower>();\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint lower twisted to lower\");\n  \n  res.template selfadjointView<Lower>() = mat.template selfadjointView<Upper>().twistedBy(p);\n  res_d = ((p * up_sym_d) * p.inverse()).eval().template triangularView<Lower>();\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint upper twisted to lower\");\n  \n  \n  res.template selfadjointView<Upper>() = up.template selfadjointView<Upper>().twistedBy(p);\n  res_d = ((p * up_sym_d) * p.inverse()).eval().template triangularView<Upper>();\n  VERIFY(res.isApprox(res_d) && \"upper selfadjoint twisted to upper\");\n  \n  res.template selfadjointView<Upper>() = lo.template selfadjointView<Lower>().twistedBy(p);\n  res_d = ((p * lo_sym_d) * p.inverse()).eval().template triangularView<Upper>();\n  VERIFY(res.isApprox(res_d) && \"lower selfadjoint twisted to upper\");\n  \n  res.template selfadjointView<Lower>() = lo.template selfadjointView<Lower>().twistedBy(p);\n  res_d = ((p * lo_sym_d) * p.inverse()).eval().template triangularView<Lower>();\n  VERIFY(res.isApprox(res_d) && \"lower selfadjoint twisted to lower\");\n  \n  res.template selfadjointView<Lower>() = up.template selfadjointView<Upper>().twistedBy(p);\n  res_d = ((p * up_sym_d) * p.inverse()).eval().template triangularView<Lower>();\n  VERIFY(res.isApprox(res_d) && \"upper selfadjoint twisted to lower\");\n\n  \n  VERIFY( is_sorted( res = mat.template selfadjointView<Upper>().twistedBy(p) ));\n  res_d = (p * up_sym_d) * p.inverse();\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint upper twisted to full\");\n  \n  VERIFY( is_sorted( res = mat.template selfadjointView<Lower>().twistedBy(p) ));\n  res_d = (p * lo_sym_d) * p.inverse();\n  VERIFY(res.isApprox(res_d) && \"full selfadjoint lower twisted to full\");\n  \n  VERIFY( is_sorted( res = up.template selfadjointView<Upper>().twistedBy(p) ));\n  res_d = (p * up_sym_d) * p.inverse();\n  VERIFY(res.isApprox(res_d) && \"upper selfadjoint twisted to full\");\n  \n  VERIFY( is_sorted( res = lo.template selfadjointView<Lower>().twistedBy(p) ));\n  res_d = (p * lo_sym_d) * p.inverse();\n  VERIFY(res.isApprox(res_d) && \"lower selfadjoint twisted to full\");\n}\n\ntemplate<typename Scalar> void sparse_permutations_all(int size)\n{\n  CALL_SUBTEST(( sparse_permutations<ColMajor>(SparseMatrix<Scalar, ColMajor>(size,size)) ));\n  CALL_SUBTEST(( sparse_permutations<ColMajor>(SparseMatrix<Scalar, RowMajor>(size,size)) ));\n  CALL_SUBTEST(( sparse_permutations<RowMajor>(SparseMatrix<Scalar, ColMajor>(size,size)) ));\n  CALL_SUBTEST(( sparse_permutations<RowMajor>(SparseMatrix<Scalar, RowMajor>(size,size)) ));\n}\n\nEIGEN_DECLARE_TEST(sparse_permutations)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    int s = Eigen::internal::random<int>(1,50);\n    CALL_SUBTEST_1((  sparse_permutations_all<double>(s) ));\n    CALL_SUBTEST_2((  sparse_permutations_all<std::complex<double> >(s) ));\n  }\n\n  VERIFY((internal::is_same<internal::permutation_matrix_product<SparseMatrix<double>,OnTheRight,false,SparseShape>::ReturnType,\n                            internal::nested_eval<Product<SparseMatrix<double>,PermutationMatrix<Dynamic,Dynamic>,AliasFreeProduct>,1>::type>::value));\n\n  VERIFY((internal::is_same<internal::permutation_matrix_product<SparseMatrix<double>,OnTheLeft,false,SparseShape>::ReturnType,\n                            internal::nested_eval<Product<PermutationMatrix<Dynamic,Dynamic>,SparseMatrix<double>,AliasFreeProduct>,1>::type>::value));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/sparse_product.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#if defined(_MSC_VER) && (_MSC_VER==1800)\n// This unit test takes forever to compile in Release mode with MSVC 2013,\n// multiple hours. So let's switch off optimization for this one.\n#pragma optimize(\"\",off)\n#endif\n\nstatic long int nb_temporaries;\n\ninline void on_temporary_creation() {\n  // here's a great place to set a breakpoint when debugging failures in this test!\n  nb_temporaries++;\n}\n\n#define EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN { on_temporary_creation(); }\n\n#include \"sparse.h\"\n\n#define VERIFY_EVALUATION_COUNT(XPR,N) {\\\n    nb_temporaries = 0; \\\n    CALL_SUBTEST( XPR ); \\\n    if(nb_temporaries!=N) std::cerr << \"nb_temporaries == \" << nb_temporaries << \"\\n\"; \\\n    VERIFY( (#XPR) && nb_temporaries==N ); \\\n  }\n\n\n\ntemplate<typename SparseMatrixType> void sparse_product()\n{\n  typedef typename SparseMatrixType::StorageIndex StorageIndex;\n  Index n = 100;\n  const Index rows  = internal::random<Index>(1,n);\n  const Index cols  = internal::random<Index>(1,n);\n  const Index depth = internal::random<Index>(1,n);\n  typedef typename SparseMatrixType::Scalar Scalar;\n  enum { Flags = SparseMatrixType::Flags };\n\n  double density = (std::max)(8./(rows*cols), 0.2);\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n  typedef Matrix<Scalar,1,Dynamic> RowDenseVector;\n  typedef SparseVector<Scalar,0,StorageIndex> ColSpVector;\n  typedef SparseVector<Scalar,RowMajor,StorageIndex> RowSpVector;\n\n  Scalar s1 = internal::random<Scalar>();\n  Scalar s2 = internal::random<Scalar>();\n\n  // test matrix-matrix product\n  {\n    DenseMatrix refMat2  = DenseMatrix::Zero(rows, depth);\n    DenseMatrix refMat2t = DenseMatrix::Zero(depth, rows);\n    DenseMatrix refMat3  = DenseMatrix::Zero(depth, cols);\n    DenseMatrix refMat3t = DenseMatrix::Zero(cols, depth);\n    DenseMatrix refMat4  = DenseMatrix::Zero(rows, cols);\n    DenseMatrix refMat4t = DenseMatrix::Zero(cols, rows);\n    DenseMatrix refMat5  = DenseMatrix::Random(depth, cols);\n    DenseMatrix refMat6  = DenseMatrix::Random(rows, rows);\n    DenseMatrix dm4 = DenseMatrix::Zero(rows, rows);\n//     DenseVector dv1 = DenseVector::Random(rows);\n    SparseMatrixType m2 (rows, depth);\n    SparseMatrixType m2t(depth, rows);\n    SparseMatrixType m3 (depth, cols);\n    SparseMatrixType m3t(cols, depth);\n    SparseMatrixType m4 (rows, cols);\n    SparseMatrixType m4t(cols, rows);\n    SparseMatrixType m6(rows, rows);\n    initSparse(density, refMat2,  m2);\n    initSparse(density, refMat2t, m2t);\n    initSparse(density, refMat3,  m3);\n    initSparse(density, refMat3t, m3t);\n    initSparse(density, refMat4,  m4);\n    initSparse(density, refMat4t, m4t);\n    initSparse(density, refMat6, m6);\n\n//     int c = internal::random<int>(0,depth-1);\n\n    // sparse * sparse\n    VERIFY_IS_APPROX(m4=m2*m3, refMat4=refMat2*refMat3);\n    VERIFY_IS_APPROX(m4=m2t.transpose()*m3, refMat4=refMat2t.transpose()*refMat3);\n    VERIFY_IS_APPROX(m4=m2t.transpose()*m3t.transpose(), refMat4=refMat2t.transpose()*refMat3t.transpose());\n    VERIFY_IS_APPROX(m4=m2*m3t.transpose(), refMat4=refMat2*refMat3t.transpose());\n\n    VERIFY_IS_APPROX(m4 = m2*m3/s1, refMat4 = refMat2*refMat3/s1);\n    VERIFY_IS_APPROX(m4 = m2*m3*s1, refMat4 = refMat2*refMat3*s1);\n    VERIFY_IS_APPROX(m4 = s2*m2*m3*s1, refMat4 = s2*refMat2*refMat3*s1);\n    VERIFY_IS_APPROX(m4 = (m2+m2)*m3, refMat4 = (refMat2+refMat2)*refMat3);\n    VERIFY_IS_APPROX(m4 = m2*m3.leftCols(cols/2), refMat4 = refMat2*refMat3.leftCols(cols/2));\n    VERIFY_IS_APPROX(m4 = m2*(m3+m3).leftCols(cols/2), refMat4 = refMat2*(refMat3+refMat3).leftCols(cols/2));\n\n    VERIFY_IS_APPROX(m4=(m2*m3).pruned(0), refMat4=refMat2*refMat3);\n    VERIFY_IS_APPROX(m4=(m2t.transpose()*m3).pruned(0), refMat4=refMat2t.transpose()*refMat3);\n    VERIFY_IS_APPROX(m4=(m2t.transpose()*m3t.transpose()).pruned(0), refMat4=refMat2t.transpose()*refMat3t.transpose());\n    VERIFY_IS_APPROX(m4=(m2*m3t.transpose()).pruned(0), refMat4=refMat2*refMat3t.transpose());\n\n#ifndef EIGEN_SPARSE_PRODUCT_IGNORE_TEMPORARY_COUNT\n    // make sure the right product implementation is called:\n    if((!SparseMatrixType::IsRowMajor) && m2.rows()<=m3.cols())\n    {\n      VERIFY_EVALUATION_COUNT(m4 = m2*m3, 2); // 2 for transposing and get a sorted result.\n      VERIFY_EVALUATION_COUNT(m4 = (m2*m3).pruned(0), 1);\n      VERIFY_EVALUATION_COUNT(m4 = (m2*m3).eval().pruned(0), 4);\n    }\n#endif\n\n    // and that pruning is effective:\n    {\n      DenseMatrix Ad(2,2);\n      Ad << -1, 1, 1, 1;\n      SparseMatrixType As(Ad.sparseView()), B(2,2);\n      VERIFY_IS_EQUAL( (As*As.transpose()).eval().nonZeros(), 4);\n      VERIFY_IS_EQUAL( (Ad*Ad.transpose()).eval().sparseView().eval().nonZeros(), 2);\n      VERIFY_IS_EQUAL( (As*As.transpose()).pruned(1e-6).eval().nonZeros(), 2);\n    }\n\n    // dense ?= sparse * sparse\n    VERIFY_IS_APPROX(dm4 =m2*m3, refMat4 =refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4+=m2*m3, refMat4+=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4-=m2*m3, refMat4-=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4 =m2t.transpose()*m3, refMat4 =refMat2t.transpose()*refMat3);\n    VERIFY_IS_APPROX(dm4+=m2t.transpose()*m3, refMat4+=refMat2t.transpose()*refMat3);\n    VERIFY_IS_APPROX(dm4-=m2t.transpose()*m3, refMat4-=refMat2t.transpose()*refMat3);\n    VERIFY_IS_APPROX(dm4 =m2t.transpose()*m3t.transpose(), refMat4 =refMat2t.transpose()*refMat3t.transpose());\n    VERIFY_IS_APPROX(dm4+=m2t.transpose()*m3t.transpose(), refMat4+=refMat2t.transpose()*refMat3t.transpose());\n    VERIFY_IS_APPROX(dm4-=m2t.transpose()*m3t.transpose(), refMat4-=refMat2t.transpose()*refMat3t.transpose());\n    VERIFY_IS_APPROX(dm4 =m2*m3t.transpose(), refMat4 =refMat2*refMat3t.transpose());\n    VERIFY_IS_APPROX(dm4+=m2*m3t.transpose(), refMat4+=refMat2*refMat3t.transpose());\n    VERIFY_IS_APPROX(dm4-=m2*m3t.transpose(), refMat4-=refMat2*refMat3t.transpose());\n    VERIFY_IS_APPROX(dm4 = m2*m3*s1, refMat4 = refMat2*refMat3*s1);\n\n    // test aliasing\n    m4 = m2; refMat4 = refMat2;\n    VERIFY_IS_APPROX(m4=m4*m3, refMat4=refMat4*refMat3);\n\n    // sparse * dense matrix\n    VERIFY_IS_APPROX(dm4=m2*refMat3, refMat4=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4=m2*refMat3t.transpose(), refMat4=refMat2*refMat3t.transpose());\n    VERIFY_IS_APPROX(dm4=m2t.transpose()*refMat3, refMat4=refMat2t.transpose()*refMat3);\n    VERIFY_IS_APPROX(dm4=m2t.transpose()*refMat3t.transpose(), refMat4=refMat2t.transpose()*refMat3t.transpose());\n\n    VERIFY_IS_APPROX(dm4=m2*refMat3, refMat4=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4=dm4+m2*refMat3, refMat4=refMat4+refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4+=m2*refMat3, refMat4+=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4-=m2*refMat3, refMat4-=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4.noalias()+=m2*refMat3, refMat4+=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4.noalias()-=m2*refMat3, refMat4-=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4=m2*(refMat3+refMat3), refMat4=refMat2*(refMat3+refMat3));\n    VERIFY_IS_APPROX(dm4=m2t.transpose()*(refMat3+refMat5)*0.5, refMat4=refMat2t.transpose()*(refMat3+refMat5)*0.5);\n\n    // sparse * dense vector\n    VERIFY_IS_APPROX(dm4.col(0)=m2*refMat3.col(0), refMat4.col(0)=refMat2*refMat3.col(0));\n    VERIFY_IS_APPROX(dm4.col(0)=m2*refMat3t.transpose().col(0), refMat4.col(0)=refMat2*refMat3t.transpose().col(0));\n    VERIFY_IS_APPROX(dm4.col(0)=m2t.transpose()*refMat3.col(0), refMat4.col(0)=refMat2t.transpose()*refMat3.col(0));\n    VERIFY_IS_APPROX(dm4.col(0)=m2t.transpose()*refMat3t.transpose().col(0), refMat4.col(0)=refMat2t.transpose()*refMat3t.transpose().col(0));\n\n    // dense * sparse\n    VERIFY_IS_APPROX(dm4=refMat2*m3, refMat4=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4=dm4+refMat2*m3, refMat4=refMat4+refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4+=refMat2*m3, refMat4+=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4-=refMat2*m3, refMat4-=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4.noalias()+=refMat2*m3, refMat4+=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4.noalias()-=refMat2*m3, refMat4-=refMat2*refMat3);\n    VERIFY_IS_APPROX(dm4=refMat2*m3t.transpose(), refMat4=refMat2*refMat3t.transpose());\n    VERIFY_IS_APPROX(dm4=refMat2t.transpose()*m3, refMat4=refMat2t.transpose()*refMat3);\n    VERIFY_IS_APPROX(dm4=refMat2t.transpose()*m3t.transpose(), refMat4=refMat2t.transpose()*refMat3t.transpose());\n\n    // sparse * dense and dense * sparse outer product\n    {\n      Index c  = internal::random<Index>(0,depth-1);\n      Index r  = internal::random<Index>(0,rows-1);\n      Index c1 = internal::random<Index>(0,cols-1);\n      Index r1 = internal::random<Index>(0,depth-1);\n      DenseMatrix dm5  = DenseMatrix::Random(depth, cols);\n\n      VERIFY_IS_APPROX( m4=m2.col(c)*dm5.col(c1).transpose(), refMat4=refMat2.col(c)*dm5.col(c1).transpose());\n      VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count());\n      VERIFY_IS_APPROX( m4=m2.middleCols(c,1)*dm5.col(c1).transpose(), refMat4=refMat2.col(c)*dm5.col(c1).transpose());\n      VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count());\n      VERIFY_IS_APPROX(dm4=m2.col(c)*dm5.col(c1).transpose(), refMat4=refMat2.col(c)*dm5.col(c1).transpose());\n\n      VERIFY_IS_APPROX(m4=dm5.col(c1)*m2.col(c).transpose(), refMat4=dm5.col(c1)*refMat2.col(c).transpose());\n      VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count());\n      VERIFY_IS_APPROX(m4=dm5.col(c1)*m2.middleCols(c,1).transpose(), refMat4=dm5.col(c1)*refMat2.col(c).transpose());\n      VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count());\n      VERIFY_IS_APPROX(dm4=dm5.col(c1)*m2.col(c).transpose(), refMat4=dm5.col(c1)*refMat2.col(c).transpose());\n\n      VERIFY_IS_APPROX( m4=dm5.row(r1).transpose()*m2.col(c).transpose(), refMat4=dm5.row(r1).transpose()*refMat2.col(c).transpose());\n      VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count());\n      VERIFY_IS_APPROX(dm4=dm5.row(r1).transpose()*m2.col(c).transpose(), refMat4=dm5.row(r1).transpose()*refMat2.col(c).transpose());\n\n      VERIFY_IS_APPROX( m4=m2.row(r).transpose()*dm5.col(c1).transpose(), refMat4=refMat2.row(r).transpose()*dm5.col(c1).transpose());\n      VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count());\n      VERIFY_IS_APPROX( m4=m2.middleRows(r,1).transpose()*dm5.col(c1).transpose(), refMat4=refMat2.row(r).transpose()*dm5.col(c1).transpose());\n      VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count());\n      VERIFY_IS_APPROX(dm4=m2.row(r).transpose()*dm5.col(c1).transpose(), refMat4=refMat2.row(r).transpose()*dm5.col(c1).transpose());\n\n      VERIFY_IS_APPROX( m4=dm5.col(c1)*m2.row(r), refMat4=dm5.col(c1)*refMat2.row(r));\n      VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count());\n      VERIFY_IS_APPROX( m4=dm5.col(c1)*m2.middleRows(r,1), refMat4=dm5.col(c1)*refMat2.row(r));\n      VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count());\n      VERIFY_IS_APPROX(dm4=dm5.col(c1)*m2.row(r), refMat4=dm5.col(c1)*refMat2.row(r));\n\n      VERIFY_IS_APPROX( m4=dm5.row(r1).transpose()*m2.row(r), refMat4=dm5.row(r1).transpose()*refMat2.row(r));\n      VERIFY_IS_EQUAL(m4.nonZeros(), (refMat4.array()!=0).count());\n      VERIFY_IS_APPROX(dm4=dm5.row(r1).transpose()*m2.row(r), refMat4=dm5.row(r1).transpose()*refMat2.row(r));\n    }\n\n    VERIFY_IS_APPROX(m6=m6*m6, refMat6=refMat6*refMat6);\n\n    // sparse matrix * sparse vector\n    ColSpVector cv0(cols), cv1;\n    DenseVector dcv0(cols), dcv1;\n    initSparse(2*density,dcv0, cv0);\n\n    RowSpVector rv0(depth), rv1;\n    RowDenseVector drv0(depth), drv1(rv1);\n    initSparse(2*density,drv0, rv0);\n\n    VERIFY_IS_APPROX(cv1=m3*cv0, dcv1=refMat3*dcv0);\n    VERIFY_IS_APPROX(rv1=rv0*m3, drv1=drv0*refMat3);\n    VERIFY_IS_APPROX(cv1=m3t.adjoint()*cv0, dcv1=refMat3t.adjoint()*dcv0);\n    VERIFY_IS_APPROX(cv1=rv0*m3, dcv1=drv0*refMat3);\n    VERIFY_IS_APPROX(rv1=m3*cv0, drv1=refMat3*dcv0);\n  }\n\n  // test matrix - diagonal product\n  {\n    DenseMatrix refM2 = DenseMatrix::Zero(rows, cols);\n    DenseMatrix refM3 = DenseMatrix::Zero(rows, cols);\n    DenseMatrix d3 = DenseMatrix::Zero(rows, cols);\n    DiagonalMatrix<Scalar,Dynamic> d1(DenseVector::Random(cols));\n    DiagonalMatrix<Scalar,Dynamic> d2(DenseVector::Random(rows));\n    SparseMatrixType m2(rows, cols);\n    SparseMatrixType m3(rows, cols);\n    initSparse<Scalar>(density, refM2, m2);\n    initSparse<Scalar>(density, refM3, m3);\n    VERIFY_IS_APPROX(m3=m2*d1, refM3=refM2*d1);\n    VERIFY_IS_APPROX(m3=m2.transpose()*d2, refM3=refM2.transpose()*d2);\n    VERIFY_IS_APPROX(m3=d2*m2, refM3=d2*refM2);\n    VERIFY_IS_APPROX(m3=d1*m2.transpose(), refM3=d1*refM2.transpose());\n\n    // also check with a SparseWrapper:\n    DenseVector v1 = DenseVector::Random(cols);\n    DenseVector v2 = DenseVector::Random(rows);\n    DenseVector v3 = DenseVector::Random(rows);\n    VERIFY_IS_APPROX(m3=m2*v1.asDiagonal(), refM3=refM2*v1.asDiagonal());\n    VERIFY_IS_APPROX(m3=m2.transpose()*v2.asDiagonal(), refM3=refM2.transpose()*v2.asDiagonal());\n    VERIFY_IS_APPROX(m3=v2.asDiagonal()*m2, refM3=v2.asDiagonal()*refM2);\n    VERIFY_IS_APPROX(m3=v1.asDiagonal()*m2.transpose(), refM3=v1.asDiagonal()*refM2.transpose());\n\n    VERIFY_IS_APPROX(m3=v2.asDiagonal()*m2*v1.asDiagonal(), refM3=v2.asDiagonal()*refM2*v1.asDiagonal());\n\n    VERIFY_IS_APPROX(v2=m2*v1.asDiagonal()*v1, refM2*v1.asDiagonal()*v1);\n    VERIFY_IS_APPROX(v3=v2.asDiagonal()*m2*v1, v2.asDiagonal()*refM2*v1);\n\n    // evaluate to a dense matrix to check the .row() and .col() iterator functions\n    VERIFY_IS_APPROX(d3=m2*d1, refM3=refM2*d1);\n    VERIFY_IS_APPROX(d3=m2.transpose()*d2, refM3=refM2.transpose()*d2);\n    VERIFY_IS_APPROX(d3=d2*m2, refM3=d2*refM2);\n    VERIFY_IS_APPROX(d3=d1*m2.transpose(), refM3=d1*refM2.transpose());\n  }\n\n  // test self-adjoint and triangular-view products\n  {\n    DenseMatrix b = DenseMatrix::Random(rows, rows);\n    DenseMatrix x = DenseMatrix::Random(rows, rows);\n    DenseMatrix refX = DenseMatrix::Random(rows, rows);\n    DenseMatrix refUp = DenseMatrix::Zero(rows, rows);\n    DenseMatrix refLo = DenseMatrix::Zero(rows, rows);\n    DenseMatrix refS = DenseMatrix::Zero(rows, rows);\n    DenseMatrix refA = DenseMatrix::Zero(rows, rows);\n    SparseMatrixType mUp(rows, rows);\n    SparseMatrixType mLo(rows, rows);\n    SparseMatrixType mS(rows, rows);\n    SparseMatrixType mA(rows, rows);\n    initSparse<Scalar>(density, refA, mA);\n    do {\n      initSparse<Scalar>(density, refUp, mUp, ForceRealDiag|/*ForceNonZeroDiag|*/MakeUpperTriangular);\n    } while (refUp.isZero());\n    refLo = refUp.adjoint();\n    mLo = mUp.adjoint();\n    refS = refUp + refLo;\n    refS.diagonal() *= 0.5;\n    mS = mUp + mLo;\n    // TODO be able to address the diagonal....\n    for (int k=0; k<mS.outerSize(); ++k)\n      for (typename SparseMatrixType::InnerIterator it(mS,k); it; ++it)\n        if (it.index() == k)\n          it.valueRef() *= Scalar(0.5);\n\n    VERIFY_IS_APPROX(refS.adjoint(), refS);\n    VERIFY_IS_APPROX(mS.adjoint(), mS);\n    VERIFY_IS_APPROX(mS, refS);\n    VERIFY_IS_APPROX(x=mS*b, refX=refS*b);\n\n    // sparse selfadjointView with dense matrices\n    VERIFY_IS_APPROX(x=mUp.template selfadjointView<Upper>()*b, refX=refS*b);\n    VERIFY_IS_APPROX(x=mLo.template selfadjointView<Lower>()*b, refX=refS*b);\n    VERIFY_IS_APPROX(x=mS.template selfadjointView<Upper|Lower>()*b, refX=refS*b);\n\n    VERIFY_IS_APPROX(x=b * mUp.template selfadjointView<Upper>(),       refX=b*refS);\n    VERIFY_IS_APPROX(x=b * mLo.template selfadjointView<Lower>(),       refX=b*refS);\n    VERIFY_IS_APPROX(x=b * mS.template selfadjointView<Upper|Lower>(),  refX=b*refS);\n\n    VERIFY_IS_APPROX(x.noalias()+=mUp.template selfadjointView<Upper>()*b, refX+=refS*b);\n    VERIFY_IS_APPROX(x.noalias()-=mLo.template selfadjointView<Lower>()*b, refX-=refS*b);\n    VERIFY_IS_APPROX(x.noalias()+=mS.template selfadjointView<Upper|Lower>()*b, refX+=refS*b);\n\n    // sparse selfadjointView with sparse matrices\n    SparseMatrixType mSres(rows,rows);\n    VERIFY_IS_APPROX(mSres = mLo.template selfadjointView<Lower>()*mS,\n                     refX = refLo.template selfadjointView<Lower>()*refS);\n    VERIFY_IS_APPROX(mSres = mS * mLo.template selfadjointView<Lower>(),\n                     refX = refS * refLo.template selfadjointView<Lower>());\n\n    // sparse triangularView with dense matrices\n    VERIFY_IS_APPROX(x=mA.template triangularView<Upper>()*b, refX=refA.template triangularView<Upper>()*b);\n    VERIFY_IS_APPROX(x=mA.template triangularView<Lower>()*b, refX=refA.template triangularView<Lower>()*b);\n    VERIFY_IS_APPROX(x=b*mA.template triangularView<Upper>(), refX=b*refA.template triangularView<Upper>());\n    VERIFY_IS_APPROX(x=b*mA.template triangularView<Lower>(), refX=b*refA.template triangularView<Lower>());\n\n    // sparse triangularView with sparse matrices\n    VERIFY_IS_APPROX(mSres = mA.template triangularView<Lower>()*mS,   refX = refA.template triangularView<Lower>()*refS);\n    VERIFY_IS_APPROX(mSres = mS * mA.template triangularView<Lower>(), refX = refS * refA.template triangularView<Lower>());\n    VERIFY_IS_APPROX(mSres = mA.template triangularView<Upper>()*mS,   refX = refA.template triangularView<Upper>()*refS);\n    VERIFY_IS_APPROX(mSres = mS * mA.template triangularView<Upper>(), refX = refS * refA.template triangularView<Upper>());\n  }\n}\n\n// New test for Bug in SparseTimeDenseProduct\ntemplate<typename SparseMatrixType, typename DenseMatrixType> void sparse_product_regression_test()\n{\n  // This code does not compile with afflicted versions of the bug\n  SparseMatrixType sm1(3,2);\n  DenseMatrixType m2(2,2);\n  sm1.setZero();\n  m2.setZero();\n\n  DenseMatrixType m3 = sm1*m2;\n\n\n  // This code produces a segfault with afflicted versions of another SparseTimeDenseProduct\n  // bug\n\n  SparseMatrixType sm2(20000,2);\n  sm2.setZero();\n  DenseMatrixType m4(sm2*m2);\n\n  VERIFY_IS_APPROX( m4(0,0), 0.0 );\n}\n\ntemplate<typename Scalar>\nvoid bug_942()\n{\n  typedef Matrix<Scalar, Dynamic, 1>     Vector;\n  typedef SparseMatrix<Scalar, ColMajor> ColSpMat;\n  typedef SparseMatrix<Scalar, RowMajor> RowSpMat;\n  ColSpMat cmA(1,1);\n  cmA.insert(0,0) = 1;\n\n  RowSpMat rmA(1,1);\n  rmA.insert(0,0) = 1;\n\n  Vector d(1);\n  d[0] = 2;\n\n  double res = 2;\n\n  VERIFY_IS_APPROX( ( cmA*d.asDiagonal() ).eval().coeff(0,0), res );\n  VERIFY_IS_APPROX( ( d.asDiagonal()*rmA ).eval().coeff(0,0), res );\n  VERIFY_IS_APPROX( ( rmA*d.asDiagonal() ).eval().coeff(0,0), res );\n  VERIFY_IS_APPROX( ( d.asDiagonal()*cmA ).eval().coeff(0,0), res );\n}\n\ntemplate<typename Real>\nvoid test_mixing_types()\n{\n  typedef std::complex<Real> Cplx;\n  typedef SparseMatrix<Real> SpMatReal;\n  typedef SparseMatrix<Cplx> SpMatCplx;\n  typedef SparseMatrix<Cplx,RowMajor> SpRowMatCplx;\n  typedef Matrix<Real,Dynamic,Dynamic> DenseMatReal;\n  typedef Matrix<Cplx,Dynamic,Dynamic> DenseMatCplx;\n\n  Index n = internal::random<Index>(1,100);\n  double density = (std::max)(8./(n*n), 0.2);\n\n  SpMatReal sR1(n,n);\n  SpMatCplx sC1(n,n), sC2(n,n), sC3(n,n);\n  SpRowMatCplx sCR(n,n);\n  DenseMatReal dR1(n,n);\n  DenseMatCplx dC1(n,n), dC2(n,n), dC3(n,n);\n\n  initSparse<Real>(density, dR1, sR1);\n  initSparse<Cplx>(density, dC1, sC1);\n  initSparse<Cplx>(density, dC2, sC2);\n\n  VERIFY_IS_APPROX( sC2 = (sR1 * sC1),                         dC3 = dR1.template cast<Cplx>() * dC1 );\n  VERIFY_IS_APPROX( sC2 = (sC1 * sR1),                         dC3 = dC1 * dR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( sC2 = (sR1.transpose() * sC1),             dC3 = dR1.template cast<Cplx>().transpose() * dC1 );\n  VERIFY_IS_APPROX( sC2 = (sC1.transpose() * sR1),             dC3 = dC1.transpose() * dR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( sC2 = (sR1 * sC1.transpose()),             dC3 = dR1.template cast<Cplx>() * dC1.transpose() );\n  VERIFY_IS_APPROX( sC2 = (sC1 * sR1.transpose()),             dC3 = dC1 * dR1.template cast<Cplx>().transpose() );\n  VERIFY_IS_APPROX( sC2 = (sR1.transpose() * sC1.transpose()), dC3 = dR1.template cast<Cplx>().transpose() * dC1.transpose() );\n  VERIFY_IS_APPROX( sC2 = (sC1.transpose() * sR1.transpose()), dC3 = dC1.transpose() * dR1.template cast<Cplx>().transpose() );\n\n  VERIFY_IS_APPROX( sCR = (sR1 * sC1),                         dC3 = dR1.template cast<Cplx>() * dC1 );\n  VERIFY_IS_APPROX( sCR = (sC1 * sR1),                         dC3 = dC1 * dR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( sCR = (sR1.transpose() * sC1),             dC3 = dR1.template cast<Cplx>().transpose() * dC1 );\n  VERIFY_IS_APPROX( sCR = (sC1.transpose() * sR1),             dC3 = dC1.transpose() * dR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( sCR = (sR1 * sC1.transpose()),             dC3 = dR1.template cast<Cplx>() * dC1.transpose() );\n  VERIFY_IS_APPROX( sCR = (sC1 * sR1.transpose()),             dC3 = dC1 * dR1.template cast<Cplx>().transpose() );\n  VERIFY_IS_APPROX( sCR = (sR1.transpose() * sC1.transpose()), dC3 = dR1.template cast<Cplx>().transpose() * dC1.transpose() );\n  VERIFY_IS_APPROX( sCR = (sC1.transpose() * sR1.transpose()), dC3 = dC1.transpose() * dR1.template cast<Cplx>().transpose() );\n\n\n  VERIFY_IS_APPROX( sC2 = (sR1 * sC1).pruned(),                         dC3 = dR1.template cast<Cplx>() * dC1 );\n  VERIFY_IS_APPROX( sC2 = (sC1 * sR1).pruned(),                         dC3 = dC1 * dR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( sC2 = (sR1.transpose() * sC1).pruned(),             dC3 = dR1.template cast<Cplx>().transpose() * dC1 );\n  VERIFY_IS_APPROX( sC2 = (sC1.transpose() * sR1).pruned(),             dC3 = dC1.transpose() * dR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( sC2 = (sR1 * sC1.transpose()).pruned(),             dC3 = dR1.template cast<Cplx>() * dC1.transpose() );\n  VERIFY_IS_APPROX( sC2 = (sC1 * sR1.transpose()).pruned(),             dC3 = dC1 * dR1.template cast<Cplx>().transpose() );\n  VERIFY_IS_APPROX( sC2 = (sR1.transpose() * sC1.transpose()).pruned(), dC3 = dR1.template cast<Cplx>().transpose() * dC1.transpose() );\n  VERIFY_IS_APPROX( sC2 = (sC1.transpose() * sR1.transpose()).pruned(), dC3 = dC1.transpose() * dR1.template cast<Cplx>().transpose() );\n\n  VERIFY_IS_APPROX( sCR = (sR1 * sC1).pruned(),                         dC3 = dR1.template cast<Cplx>() * dC1 );\n  VERIFY_IS_APPROX( sCR = (sC1 * sR1).pruned(),                         dC3 = dC1 * dR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( sCR = (sR1.transpose() * sC1).pruned(),             dC3 = dR1.template cast<Cplx>().transpose() * dC1 );\n  VERIFY_IS_APPROX( sCR = (sC1.transpose() * sR1).pruned(),             dC3 = dC1.transpose() * dR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( sCR = (sR1 * sC1.transpose()).pruned(),             dC3 = dR1.template cast<Cplx>() * dC1.transpose() );\n  VERIFY_IS_APPROX( sCR = (sC1 * sR1.transpose()).pruned(),             dC3 = dC1 * dR1.template cast<Cplx>().transpose() );\n  VERIFY_IS_APPROX( sCR = (sR1.transpose() * sC1.transpose()).pruned(), dC3 = dR1.template cast<Cplx>().transpose() * dC1.transpose() );\n  VERIFY_IS_APPROX( sCR = (sC1.transpose() * sR1.transpose()).pruned(), dC3 = dC1.transpose() * dR1.template cast<Cplx>().transpose() );\n\n\n  VERIFY_IS_APPROX( dC2 = (sR1 * sC1),                         dC3 = dR1.template cast<Cplx>() * dC1 );\n  VERIFY_IS_APPROX( dC2 = (sC1 * sR1),                         dC3 = dC1 * dR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( dC2 = (sR1.transpose() * sC1),             dC3 = dR1.template cast<Cplx>().transpose() * dC1 );\n  VERIFY_IS_APPROX( dC2 = (sC1.transpose() * sR1),             dC3 = dC1.transpose() * dR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( dC2 = (sR1 * sC1.transpose()),             dC3 = dR1.template cast<Cplx>() * dC1.transpose() );\n  VERIFY_IS_APPROX( dC2 = (sC1 * sR1.transpose()),             dC3 = dC1 * dR1.template cast<Cplx>().transpose() );\n  VERIFY_IS_APPROX( dC2 = (sR1.transpose() * sC1.transpose()), dC3 = dR1.template cast<Cplx>().transpose() * dC1.transpose() );\n  VERIFY_IS_APPROX( dC2 = (sC1.transpose() * sR1.transpose()), dC3 = dC1.transpose() * dR1.template cast<Cplx>().transpose() );\n\n\n  VERIFY_IS_APPROX( dC2 = dR1 * sC1, dC3 = dR1.template cast<Cplx>() * sC1 );\n  VERIFY_IS_APPROX( dC2 = sR1 * dC1, dC3 = sR1.template cast<Cplx>() * dC1 );\n  VERIFY_IS_APPROX( dC2 = dC1 * sR1, dC3 = dC1 * sR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( dC2 = sC1 * dR1, dC3 = sC1 * dR1.template cast<Cplx>() );\n\n  VERIFY_IS_APPROX( dC2 = dR1.row(0) * sC1, dC3 = dR1.template cast<Cplx>().row(0) * sC1 );\n  VERIFY_IS_APPROX( dC2 = sR1 * dC1.col(0), dC3 = sR1.template cast<Cplx>() * dC1.col(0) );\n  VERIFY_IS_APPROX( dC2 = dC1.row(0) * sR1, dC3 = dC1.row(0) * sR1.template cast<Cplx>() );\n  VERIFY_IS_APPROX( dC2 = sC1 * dR1.col(0), dC3 = sC1 * dR1.template cast<Cplx>().col(0) );\n}\n\nEIGEN_DECLARE_TEST(sparse_product)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( (sparse_product<SparseMatrix<double,ColMajor> >()) );\n    CALL_SUBTEST_1( (sparse_product<SparseMatrix<double,RowMajor> >()) );\n    CALL_SUBTEST_1( (bug_942<double>()) );\n    CALL_SUBTEST_2( (sparse_product<SparseMatrix<std::complex<double>, ColMajor > >()) );\n    CALL_SUBTEST_2( (sparse_product<SparseMatrix<std::complex<double>, RowMajor > >()) );\n    CALL_SUBTEST_3( (sparse_product<SparseMatrix<float,ColMajor,long int> >()) );\n    CALL_SUBTEST_4( (sparse_product_regression_test<SparseMatrix<double,RowMajor>, Matrix<double, Dynamic, Dynamic, RowMajor> >()) );\n\n    CALL_SUBTEST_5( (test_mixing_types<float>()) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/sparse_ref.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 20015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// This unit test cannot be easily written to work with EIGEN_DEFAULT_TO_ROW_MAJOR\n#ifdef EIGEN_DEFAULT_TO_ROW_MAJOR\n#undef EIGEN_DEFAULT_TO_ROW_MAJOR\n#endif\n\nstatic long int nb_temporaries;\n\ninline void on_temporary_creation() {\n  // here's a great place to set a breakpoint when debugging failures in this test!\n  nb_temporaries++;\n}\n\n#define EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN { on_temporary_creation(); }\n\n#include \"main.h\"\n#include <Eigen/SparseCore>\n\n#define VERIFY_EVALUATION_COUNT(XPR,N) {\\\n    nb_temporaries = 0; \\\n    CALL_SUBTEST( XPR ); \\\n    if(nb_temporaries!=N) std::cerr << \"nb_temporaries == \" << nb_temporaries << \"\\n\"; \\\n    VERIFY( (#XPR) && nb_temporaries==N ); \\\n  }\n\ntemplate<typename PlainObjectType> void check_const_correctness(const PlainObjectType&)\n{\n  // verify that ref-to-const don't have LvalueBit\n  typedef typename internal::add_const<PlainObjectType>::type ConstPlainObjectType;\n  VERIFY( !(internal::traits<Ref<ConstPlainObjectType> >::Flags & LvalueBit) );\n  VERIFY( !(internal::traits<Ref<ConstPlainObjectType, Aligned> >::Flags & LvalueBit) );\n  VERIFY( !(Ref<ConstPlainObjectType>::Flags & LvalueBit) );\n  VERIFY( !(Ref<ConstPlainObjectType, Aligned>::Flags & LvalueBit) );\n}\n\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_1(Ref<SparseMatrix<float> > a, const B &b) { VERIFY_IS_EQUAL(a.toDense(),b.toDense()); }\n\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_2(const Ref<const SparseMatrix<float> >& a, const B &b) { VERIFY_IS_EQUAL(a.toDense(),b.toDense()); }\n\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_3(const Ref<const SparseMatrix<float>, StandardCompressedFormat>& a, const B &b) {\n  VERIFY(a.isCompressed());\n  VERIFY_IS_EQUAL(a.toDense(),b.toDense());\n}\n\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_4(Ref<SparseVector<float> > a, const B &b) { VERIFY_IS_EQUAL(a.toDense(),b.toDense()); }\n\ntemplate<typename B>\nEIGEN_DONT_INLINE void call_ref_5(const Ref<const SparseVector<float> >& a, const B &b) { VERIFY_IS_EQUAL(a.toDense(),b.toDense()); }\n\nvoid call_ref()\n{\n  SparseMatrix<float>               A = MatrixXf::Random(10,10).sparseView(0.5,1);\n  SparseMatrix<float,RowMajor>      B = MatrixXf::Random(10,10).sparseView(0.5,1);\n  SparseMatrix<float>               C = MatrixXf::Random(10,10).sparseView(0.5,1);\n  C.reserve(VectorXi::Constant(C.outerSize(), 2));\n  const SparseMatrix<float>&        Ac(A);\n  Block<SparseMatrix<float> >       Ab(A,0,1, 3,3);\n  const Block<SparseMatrix<float> > Abc(A,0,1,3,3);\n  SparseVector<float>               vc =  VectorXf::Random(10).sparseView(0.5,1);\n  SparseVector<float,RowMajor>      vr =  VectorXf::Random(10).sparseView(0.5,1);\n  SparseMatrix<float> AA = A*A;\n  \n\n  VERIFY_EVALUATION_COUNT( call_ref_1(A, A),  0);\n//   VERIFY_EVALUATION_COUNT( call_ref_1(Ac, Ac),  0); // does not compile on purpose\n  VERIFY_EVALUATION_COUNT( call_ref_2(A, A),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_3(A, A),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(A.transpose(), A.transpose()),  1);\n  VERIFY_EVALUATION_COUNT( call_ref_3(A.transpose(), A.transpose()),  1);\n  VERIFY_EVALUATION_COUNT( call_ref_2(Ac,Ac), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_3(Ac,Ac), 0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(A+A,2*Ac), 1);\n  VERIFY_EVALUATION_COUNT( call_ref_3(A+A,2*Ac), 1);\n  VERIFY_EVALUATION_COUNT( call_ref_2(B, B),  1);\n  VERIFY_EVALUATION_COUNT( call_ref_3(B, B),  1);\n  VERIFY_EVALUATION_COUNT( call_ref_2(B.transpose(), B.transpose()),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_3(B.transpose(), B.transpose()),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(A*A, AA),  3);\n  VERIFY_EVALUATION_COUNT( call_ref_3(A*A, AA),  3);\n  \n  VERIFY(!C.isCompressed());\n  VERIFY_EVALUATION_COUNT( call_ref_3(C, C),  1);\n  \n  Ref<SparseMatrix<float> > Ar(A);\n  VERIFY_IS_APPROX(Ar+Ar, A+A);\n  VERIFY_EVALUATION_COUNT( call_ref_1(Ar, A),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(Ar, A),  0);\n  \n  Ref<SparseMatrix<float,RowMajor> > Br(B);\n  VERIFY_EVALUATION_COUNT( call_ref_1(Br.transpose(), Br.transpose()),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(Br, Br),  1);\n  VERIFY_EVALUATION_COUNT( call_ref_2(Br.transpose(), Br.transpose()),  0);\n  \n  Ref<const SparseMatrix<float> > Arc(A);\n//   VERIFY_EVALUATION_COUNT( call_ref_1(Arc, Arc),  0); // does not compile on purpose\n  VERIFY_EVALUATION_COUNT( call_ref_2(Arc, Arc),  0);\n  \n  VERIFY_EVALUATION_COUNT( call_ref_2(A.middleCols(1,3), A.middleCols(1,3)),  0);\n  \n  VERIFY_EVALUATION_COUNT( call_ref_2(A.col(2), A.col(2)),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(vc, vc),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(vr.transpose(), vr.transpose()),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_2(vr, vr.transpose()),  0);\n  \n  VERIFY_EVALUATION_COUNT( call_ref_2(A.block(1,1,3,3), A.block(1,1,3,3)),  1); // should be 0 (allocate starts/nnz only)\n\n  VERIFY_EVALUATION_COUNT( call_ref_4(vc, vc),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_4(vr, vr.transpose()),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_5(vc, vc),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_5(vr, vr.transpose()),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_4(A.col(2), A.col(2)),  0);\n  VERIFY_EVALUATION_COUNT( call_ref_5(A.col(2), A.col(2)),  0);\n  // VERIFY_EVALUATION_COUNT( call_ref_4(A.row(2), A.row(2).transpose()),  1); // does not compile on purpose\n  VERIFY_EVALUATION_COUNT( call_ref_5(A.row(2), A.row(2).transpose()),  1);\n}\n\nEIGEN_DECLARE_TEST(sparse_ref)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( check_const_correctness(SparseMatrix<float>()) );\n    CALL_SUBTEST_1( check_const_correctness(SparseMatrix<double,RowMajor>()) );\n    CALL_SUBTEST_2( call_ref() );\n\n    CALL_SUBTEST_3( check_const_correctness(SparseVector<float>()) );\n    CALL_SUBTEST_3( check_const_correctness(SparseVector<double,RowMajor>()) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/sparse_solver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"sparse.h\"\n#include <Eigen/SparseCore>\n#include <Eigen/SparseLU>\n#include <sstream>\n\ntemplate<typename Solver, typename Rhs, typename Guess,typename Result>\nvoid solve_with_guess(IterativeSolverBase<Solver>& solver, const MatrixBase<Rhs>& b, const Guess& g, Result &x) {\n  if(internal::random<bool>())\n  {\n    // With a temporary through evaluator<SolveWithGuess>\n    x = solver.derived().solveWithGuess(b,g) + Result::Zero(x.rows(), x.cols());\n  }\n  else\n  {\n    // direct evaluation within x through Assignment<Result,SolveWithGuess>\n    x = solver.derived().solveWithGuess(b.derived(),g);\n  }\n}\n\ntemplate<typename Solver, typename Rhs, typename Guess,typename Result>\nvoid solve_with_guess(SparseSolverBase<Solver>& solver, const MatrixBase<Rhs>& b, const Guess& , Result& x) {\n  if(internal::random<bool>())\n    x = solver.derived().solve(b) + Result::Zero(x.rows(), x.cols());\n  else\n    x = solver.derived().solve(b);\n}\n\ntemplate<typename Solver, typename Rhs, typename Guess,typename Result>\nvoid solve_with_guess(SparseSolverBase<Solver>& solver, const SparseMatrixBase<Rhs>& b, const Guess& , Result& x) {\n  x = solver.derived().solve(b);\n}\n\ntemplate<typename Solver, typename Rhs, typename DenseMat, typename DenseRhs>\nvoid check_sparse_solving(Solver& solver, const typename Solver::MatrixType& A, const Rhs& b, const DenseMat& dA, const DenseRhs& db)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  typedef typename Mat::StorageIndex StorageIndex;\n\n  DenseRhs refX = dA.householderQr().solve(db);\n  {\n    Rhs x(A.cols(), b.cols());\n    Rhs oldb = b;\n\n    solver.compute(A);\n    if (solver.info() != Success)\n    {\n      std::cerr << \"ERROR | sparse solver testing, factorization failed (\" << typeid(Solver).name() << \")\\n\";\n      VERIFY(solver.info() == Success);\n    }\n    x = solver.solve(b);\n    if (solver.info() != Success)\n    {\n      std::cerr << \"WARNING: sparse solver testing: solving failed (\" << typeid(Solver).name() << \")\\n\";\n      // dump call stack:\n      g_test_level++; \n      VERIFY(solver.info() == Success);\n      g_test_level--;\n      return;\n    }\n    VERIFY(oldb.isApprox(b) && \"sparse solver testing: the rhs should not be modified!\");\n    VERIFY(x.isApprox(refX,test_precision<Scalar>()));\n\n    x.setZero();\n    solve_with_guess(solver, b, x, x);\n    VERIFY(solver.info() == Success && \"solving failed when using solve_with_guess API\");\n    VERIFY(oldb.isApprox(b) && \"sparse solver testing: the rhs should not be modified!\");\n    VERIFY(x.isApprox(refX,test_precision<Scalar>()));\n    \n    x.setZero();\n    // test the analyze/factorize API\n    solver.analyzePattern(A);\n    solver.factorize(A);\n    VERIFY(solver.info() == Success && \"factorization failed when using analyzePattern/factorize API\");\n    x = solver.solve(b);\n    VERIFY(solver.info() == Success && \"solving failed when using analyzePattern/factorize API\");\n    VERIFY(oldb.isApprox(b) && \"sparse solver testing: the rhs should not be modified!\");\n    VERIFY(x.isApprox(refX,test_precision<Scalar>()));\n    \n    x.setZero();\n    // test with Map\n    MappedSparseMatrix<Scalar,Mat::Options,StorageIndex> Am(A.rows(), A.cols(), A.nonZeros(), const_cast<StorageIndex*>(A.outerIndexPtr()), const_cast<StorageIndex*>(A.innerIndexPtr()), const_cast<Scalar*>(A.valuePtr()));\n    solver.compute(Am);\n    VERIFY(solver.info() == Success && \"factorization failed when using Map\");\n    DenseRhs dx(refX);\n    dx.setZero();\n    Map<DenseRhs> xm(dx.data(), dx.rows(), dx.cols());\n    Map<const DenseRhs> bm(db.data(), db.rows(), db.cols());\n    xm = solver.solve(bm);\n    VERIFY(solver.info() == Success && \"solving failed when using Map\");\n    VERIFY(oldb.isApprox(bm) && \"sparse solver testing: the rhs should not be modified!\");\n    VERIFY(xm.isApprox(refX,test_precision<Scalar>()));\n  }\n  \n  // if not too large, do some extra check:\n  if(A.rows()<2000)\n  {\n    // test initialization ctor\n    {\n      Rhs x(b.rows(), b.cols());\n      Solver solver2(A);\n      VERIFY(solver2.info() == Success);\n      x = solver2.solve(b);\n      VERIFY(x.isApprox(refX,test_precision<Scalar>()));\n    }\n\n    // test dense Block as the result and rhs:\n    {\n      DenseRhs x(refX.rows(), refX.cols());\n      DenseRhs oldb(db);\n      x.setZero();\n      x.block(0,0,x.rows(),x.cols()) = solver.solve(db.block(0,0,db.rows(),db.cols()));\n      VERIFY(oldb.isApprox(db) && \"sparse solver testing: the rhs should not be modified!\");\n      VERIFY(x.isApprox(refX,test_precision<Scalar>()));\n    }\n\n    // test uncompressed inputs\n    {\n      Mat A2 = A;\n      A2.reserve((ArrayXf::Random(A.outerSize())+2).template cast<typename Mat::StorageIndex>().eval());\n      solver.compute(A2);\n      Rhs x = solver.solve(b);\n      VERIFY(x.isApprox(refX,test_precision<Scalar>()));\n    }\n\n    // test expression as input\n    {\n      solver.compute(0.5*(A+A));\n      Rhs x = solver.solve(b);\n      VERIFY(x.isApprox(refX,test_precision<Scalar>()));\n\n      Solver solver2(0.5*(A+A));\n      Rhs x2 = solver2.solve(b);\n      VERIFY(x2.isApprox(refX,test_precision<Scalar>()));\n    }\n  }\n}\n\n// specialization of generic check_sparse_solving for SuperLU in order to also test adjoint and transpose solves\ntemplate<typename Scalar, typename Rhs, typename DenseMat, typename DenseRhs>\nvoid check_sparse_solving(Eigen::SparseLU<Eigen::SparseMatrix<Scalar> >& solver, const typename Eigen::SparseMatrix<Scalar>& A, const Rhs& b, const DenseMat& dA, const DenseRhs& db)\n{\n  typedef typename Eigen::SparseMatrix<Scalar> Mat;\n  typedef typename Mat::StorageIndex StorageIndex;\n  typedef typename Eigen::SparseLU<Eigen::SparseMatrix<Scalar> > Solver;\n\n  // reference solutions computed by dense QR solver\n  DenseRhs refX1 = dA.householderQr().solve(db); // solution of A x = db\n  DenseRhs refX2 = dA.transpose().householderQr().solve(db); // solution of A^T * x = db (use transposed matrix A^T)\n  DenseRhs refX3 = dA.adjoint().householderQr().solve(db);  // solution of A^* * x = db (use adjoint matrix A^*)\n\n\n  {\n    Rhs x1(A.cols(), b.cols());\n    Rhs x2(A.cols(), b.cols());\n    Rhs x3(A.cols(), b.cols());\n    Rhs oldb = b;\n\n    solver.compute(A);\n    if (solver.info() != Success)\n    {\n      std::cerr << \"ERROR | sparse solver testing, factorization failed (\" << typeid(Solver).name() << \")\\n\";\n      VERIFY(solver.info() == Success);\n    }\n    x1 = solver.solve(b);\n    if (solver.info() != Success)\n    {\n      std::cerr << \"WARNING | sparse solver testing: solving failed (\" << typeid(Solver).name() << \")\\n\";\n      return;\n    }\n    VERIFY(oldb.isApprox(b,0.0) && \"sparse solver testing: the rhs should not be modified!\");\n    VERIFY(x1.isApprox(refX1,test_precision<Scalar>()));\n\n    // test solve with transposed\n    x2 = solver.transpose().solve(b);\n    VERIFY(oldb.isApprox(b) && \"sparse solver testing: the rhs should not be modified!\");\n    VERIFY(x2.isApprox(refX2,test_precision<Scalar>()));\n\n\n    // test solve with adjoint\n    //solver.template _solve_impl_transposed<true>(b, x3);\n    x3 = solver.adjoint().solve(b);\n    VERIFY(oldb.isApprox(b,0.0) && \"sparse solver testing: the rhs should not be modified!\");\n    VERIFY(x3.isApprox(refX3,test_precision<Scalar>()));\n\n    x1.setZero();\n    solve_with_guess(solver, b, x1, x1);\n    VERIFY(solver.info() == Success && \"solving failed when using analyzePattern/factorize API\");\n    VERIFY(oldb.isApprox(b,0.0) && \"sparse solver testing: the rhs should not be modified!\");\n    VERIFY(x1.isApprox(refX1,test_precision<Scalar>()));\n\n    x1.setZero();\n    x2.setZero();\n    x3.setZero();\n    // test the analyze/factorize API\n    solver.analyzePattern(A);\n    solver.factorize(A);\n    VERIFY(solver.info() == Success && \"factorization failed when using analyzePattern/factorize API\");\n    x1 = solver.solve(b);\n    x2 = solver.transpose().solve(b);\n    x3 = solver.adjoint().solve(b);\n\n    VERIFY(solver.info() == Success && \"solving failed when using analyzePattern/factorize API\");\n    VERIFY(oldb.isApprox(b,0.0) && \"sparse solver testing: the rhs should not be modified!\");\n    VERIFY(x1.isApprox(refX1,test_precision<Scalar>()));\n    VERIFY(x2.isApprox(refX2,test_precision<Scalar>()));\n    VERIFY(x3.isApprox(refX3,test_precision<Scalar>()));\n\n    x1.setZero();\n    // test with Map\n    MappedSparseMatrix<Scalar,Mat::Options,StorageIndex> Am(A.rows(), A.cols(), A.nonZeros(), const_cast<StorageIndex*>(A.outerIndexPtr()), const_cast<StorageIndex*>(A.innerIndexPtr()), const_cast<Scalar*>(A.valuePtr()));\n    solver.compute(Am);\n    VERIFY(solver.info() == Success && \"factorization failed when using Map\");\n    DenseRhs dx(refX1);\n    dx.setZero();\n    Map<DenseRhs> xm(dx.data(), dx.rows(), dx.cols());\n    Map<const DenseRhs> bm(db.data(), db.rows(), db.cols());\n    xm = solver.solve(bm);\n    VERIFY(solver.info() == Success && \"solving failed when using Map\");\n    VERIFY(oldb.isApprox(bm,0.0) && \"sparse solver testing: the rhs should not be modified!\");\n    VERIFY(xm.isApprox(refX1,test_precision<Scalar>()));\n  }\n\n  // if not too large, do some extra check:\n  if(A.rows()<2000)\n  {\n    // test initialization ctor\n    {\n      Rhs x(b.rows(), b.cols());\n      Solver solver2(A);\n      VERIFY(solver2.info() == Success);\n      x = solver2.solve(b);\n      VERIFY(x.isApprox(refX1,test_precision<Scalar>()));\n    }\n\n    // test dense Block as the result and rhs:\n    {\n      DenseRhs x(refX1.rows(), refX1.cols());\n      DenseRhs oldb(db);\n      x.setZero();\n      x.block(0,0,x.rows(),x.cols()) = solver.solve(db.block(0,0,db.rows(),db.cols()));\n      VERIFY(oldb.isApprox(db,0.0) && \"sparse solver testing: the rhs should not be modified!\");\n      VERIFY(x.isApprox(refX1,test_precision<Scalar>()));\n    }\n\n    // test uncompressed inputs\n    {\n      Mat A2 = A;\n      A2.reserve((ArrayXf::Random(A.outerSize())+2).template cast<typename Mat::StorageIndex>().eval());\n      solver.compute(A2);\n      Rhs x = solver.solve(b);\n      VERIFY(x.isApprox(refX1,test_precision<Scalar>()));\n    }\n\n    // test expression as input\n    {\n      solver.compute(0.5*(A+A));\n      Rhs x = solver.solve(b);\n      VERIFY(x.isApprox(refX1,test_precision<Scalar>()));\n\n      Solver solver2(0.5*(A+A));\n      Rhs x2 = solver2.solve(b);\n      VERIFY(x2.isApprox(refX1,test_precision<Scalar>()));\n    }\n  }\n}\n\n\ntemplate<typename Solver, typename Rhs>\nvoid check_sparse_solving_real_cases(Solver& solver, const typename Solver::MatrixType& A, const Rhs& b, const typename Solver::MatrixType& fullA, const Rhs& refX)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  typedef typename Mat::RealScalar RealScalar;\n  \n  Rhs x(A.cols(), b.cols());\n\n  solver.compute(A);\n  if (solver.info() != Success)\n  {\n    std::cerr << \"ERROR | sparse solver testing, factorization failed (\" << typeid(Solver).name() << \")\\n\";\n    VERIFY(solver.info() == Success);\n  }\n  x = solver.solve(b);\n  \n  if (solver.info() != Success)\n  {\n    std::cerr << \"WARNING | sparse solver testing, solving failed (\" << typeid(Solver).name() << \")\\n\";\n    return;\n  }\n  \n  RealScalar res_error = (fullA*x-b).norm()/b.norm();  \n  VERIFY( (res_error <= test_precision<Scalar>() ) && \"sparse solver failed without noticing it\"); \n\n  \n  if(refX.size() != 0 && (refX - x).norm()/refX.norm() > test_precision<Scalar>())\n  {\n    std::cerr << \"WARNING | found solution is different from the provided reference one\\n\";\n  }\n  \n}\ntemplate<typename Solver, typename DenseMat>\nvoid check_sparse_determinant(Solver& solver, const typename Solver::MatrixType& A, const DenseMat& dA)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  \n  solver.compute(A);\n  if (solver.info() != Success)\n  {\n    std::cerr << \"WARNING | sparse solver testing: factorization failed (check_sparse_determinant)\\n\";\n    return;\n  }\n\n  Scalar refDet = dA.determinant();\n  VERIFY_IS_APPROX(refDet,solver.determinant());\n}\ntemplate<typename Solver, typename DenseMat>\nvoid check_sparse_abs_determinant(Solver& solver, const typename Solver::MatrixType& A, const DenseMat& dA)\n{\n  using std::abs;\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  \n  solver.compute(A);\n  if (solver.info() != Success)\n  {\n    std::cerr << \"WARNING | sparse solver testing: factorization failed (check_sparse_abs_determinant)\\n\";\n    return;\n  }\n\n  Scalar refDet = abs(dA.determinant());\n  VERIFY_IS_APPROX(refDet,solver.absDeterminant());\n}\n\ntemplate<typename Solver, typename DenseMat>\nint generate_sparse_spd_problem(Solver& , typename Solver::MatrixType& A, typename Solver::MatrixType& halfA, DenseMat& dA, int maxSize = 300)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n\n  int size = internal::random<int>(1,maxSize);\n  double density = (std::max)(8./(size*size), 0.01);\n\n  Mat M(size, size);\n  DenseMatrix dM(size, size);\n\n  initSparse<Scalar>(density, dM, M, ForceNonZeroDiag);\n\n  A = M * M.adjoint();\n  dA = dM * dM.adjoint();\n  \n  halfA.resize(size,size);\n  if(Solver::UpLo==(Lower|Upper))\n    halfA = A;\n  else\n    halfA.template selfadjointView<Solver::UpLo>().rankUpdate(M);\n  \n  return size;\n}\n\n\n#ifdef TEST_REAL_CASES\ntemplate<typename Scalar>\ninline std::string get_matrixfolder()\n{\n  std::string mat_folder = TEST_REAL_CASES; \n  if( internal::is_same<Scalar, std::complex<float> >::value || internal::is_same<Scalar, std::complex<double> >::value )\n    mat_folder  = mat_folder + static_cast<std::string>(\"/complex/\");\n  else\n    mat_folder = mat_folder + static_cast<std::string>(\"/real/\");\n  return mat_folder;\n}\nstd::string sym_to_string(int sym)\n{\n  if(sym==Symmetric) return \"Symmetric \";\n  if(sym==SPD)       return \"SPD \";\n  return \"\";\n}\ntemplate<typename Derived>\nstd::string solver_stats(const IterativeSolverBase<Derived> &solver)\n{\n  std::stringstream ss;\n  ss << solver.iterations() << \" iters, error: \" << solver.error();\n  return ss.str();\n}\ntemplate<typename Derived>\nstd::string solver_stats(const SparseSolverBase<Derived> &/*solver*/)\n{\n  return \"\";\n}\n#endif\n\ntemplate<typename Solver> void check_sparse_spd_solving(Solver& solver, int maxSize = (std::min)(300,EIGEN_TEST_MAX_SIZE), int maxRealWorldSize = 100000)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  typedef typename Mat::StorageIndex StorageIndex;\n  typedef SparseMatrix<Scalar,ColMajor, StorageIndex> SpMat;\n  typedef SparseVector<Scalar, 0, StorageIndex> SpVec;\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n\n  // generate the problem\n  Mat A, halfA;\n  DenseMatrix dA;\n  for (int i = 0; i < g_repeat; i++) {\n    int size = generate_sparse_spd_problem(solver, A, halfA, dA, maxSize);\n\n    // generate the right hand sides\n    int rhsCols = internal::random<int>(1,16);\n    double density = (std::max)(8./(size*rhsCols), 0.1);\n    SpMat B(size,rhsCols);\n    DenseVector b = DenseVector::Random(size);\n    DenseMatrix dB(size,rhsCols);\n    initSparse<Scalar>(density, dB, B, ForceNonZeroDiag);\n    SpVec c = B.col(0);\n    DenseVector dc = dB.col(0);\n  \n    CALL_SUBTEST( check_sparse_solving(solver, A,     b,  dA, b)  );\n    CALL_SUBTEST( check_sparse_solving(solver, halfA, b,  dA, b)  );\n    CALL_SUBTEST( check_sparse_solving(solver, A,     dB, dA, dB) );\n    CALL_SUBTEST( check_sparse_solving(solver, halfA, dB, dA, dB) );\n    CALL_SUBTEST( check_sparse_solving(solver, A,     B,  dA, dB) );\n    CALL_SUBTEST( check_sparse_solving(solver, halfA, B,  dA, dB) );\n    CALL_SUBTEST( check_sparse_solving(solver, A,     c,  dA, dc) );\n    CALL_SUBTEST( check_sparse_solving(solver, halfA, c,  dA, dc) );\n    \n    // check only once\n    if(i==0)\n    {\n      b = DenseVector::Zero(size);\n      check_sparse_solving(solver, A, b, dA, b);\n    }\n  }\n  \n  // First, get the folder \n#ifdef TEST_REAL_CASES\n  // Test real problems with double precision only\n  if (internal::is_same<typename NumTraits<Scalar>::Real, double>::value)\n  {\n    std::string mat_folder = get_matrixfolder<Scalar>();\n    MatrixMarketIterator<Scalar> it(mat_folder);\n    for (; it; ++it)\n    {\n      if (it.sym() == SPD){\n        A = it.matrix();\n        if(A.diagonal().size() <= maxRealWorldSize)\n        {\n          DenseVector b = it.rhs();\n          DenseVector refX = it.refX();\n          PermutationMatrix<Dynamic, Dynamic, StorageIndex> pnull;\n          halfA.resize(A.rows(), A.cols());\n          if(Solver::UpLo == (Lower|Upper))\n            halfA = A;\n          else\n            halfA.template selfadjointView<Solver::UpLo>() = A.template triangularView<Eigen::Lower>().twistedBy(pnull);\n          \n          std::cout << \"INFO | Testing \" << sym_to_string(it.sym()) << \"sparse problem \" << it.matname()\n                  << \" (\" << A.rows() << \"x\" << A.cols() << \") using \" << typeid(Solver).name() << \"...\" << std::endl;\n          CALL_SUBTEST( check_sparse_solving_real_cases(solver, A,     b, A, refX) );\n          std::string stats = solver_stats(solver);\n          if(stats.size()>0)\n            std::cout << \"INFO |  \" << stats << std::endl;\n          CALL_SUBTEST( check_sparse_solving_real_cases(solver, halfA, b, A, refX) );\n        }\n        else\n        {\n          std::cout << \"INFO | Skip sparse problem \\\"\" << it.matname() << \"\\\" (too large)\" << std::endl;\n        }\n      }\n    }\n  }\n#else\n  EIGEN_UNUSED_VARIABLE(maxRealWorldSize);\n#endif\n}\n\ntemplate<typename Solver> void check_sparse_spd_determinant(Solver& solver)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n\n  // generate the problem\n  Mat A, halfA;\n  DenseMatrix dA;\n  generate_sparse_spd_problem(solver, A, halfA, dA, 30);\n  \n  for (int i = 0; i < g_repeat; i++) {\n    check_sparse_determinant(solver, A,     dA);\n    check_sparse_determinant(solver, halfA, dA );\n  }\n}\n\ntemplate<typename Solver, typename DenseMat>\nIndex generate_sparse_square_problem(Solver&, typename Solver::MatrixType& A, DenseMat& dA, int maxSize = 300, int options = ForceNonZeroDiag)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n\n  Index size = internal::random<int>(1,maxSize);\n  double density = (std::max)(8./(size*size), 0.01);\n  \n  A.resize(size,size);\n  dA.resize(size,size);\n\n  initSparse<Scalar>(density, dA, A, options);\n  \n  return size;\n}\n\n\nstruct prune_column {\n  Index m_col;\n  prune_column(Index col) : m_col(col) {}\n  template<class Scalar>\n  bool operator()(Index, Index col, const Scalar&) const {\n    return col != m_col;\n  }\n};\n\n\ntemplate<typename Solver> void check_sparse_square_solving(Solver& solver, int maxSize = 300, int maxRealWorldSize = 100000, bool checkDeficient = false)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  typedef SparseMatrix<Scalar,ColMajor, typename Mat::StorageIndex> SpMat;\n  typedef SparseVector<Scalar, 0, typename Mat::StorageIndex> SpVec;\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n\n  int rhsCols = internal::random<int>(1,16);\n\n  Mat A;\n  DenseMatrix dA;\n  for (int i = 0; i < g_repeat; i++) {\n    Index size = generate_sparse_square_problem(solver, A, dA, maxSize);\n\n    A.makeCompressed();\n    DenseVector b = DenseVector::Random(size);\n    DenseMatrix dB(size,rhsCols);\n    SpMat B(size,rhsCols);\n    double density = (std::max)(8./(size*rhsCols), 0.1);\n    initSparse<Scalar>(density, dB, B, ForceNonZeroDiag);\n    B.makeCompressed();\n    SpVec c = B.col(0);\n    DenseVector dc = dB.col(0);\n    CALL_SUBTEST(check_sparse_solving(solver, A, b,  dA, b));\n    CALL_SUBTEST(check_sparse_solving(solver, A, dB, dA, dB));\n    CALL_SUBTEST(check_sparse_solving(solver, A, B,  dA, dB));\n    CALL_SUBTEST(check_sparse_solving(solver, A, c,  dA, dc));\n    \n    // check only once\n    if(i==0)\n    {\n      CALL_SUBTEST(b = DenseVector::Zero(size); check_sparse_solving(solver, A, b, dA, b));\n    }\n    // regression test for Bug 792 (structurally rank deficient matrices):\n    if(checkDeficient && size>1) {\n      Index col = internal::random<int>(0,int(size-1));\n      A.prune(prune_column(col));\n      solver.compute(A);\n      VERIFY_IS_EQUAL(solver.info(), NumericalIssue);\n    }\n  }\n  \n  // First, get the folder \n#ifdef TEST_REAL_CASES\n  // Test real problems with double precision only\n  if (internal::is_same<typename NumTraits<Scalar>::Real, double>::value)\n  {\n    std::string mat_folder = get_matrixfolder<Scalar>();\n    MatrixMarketIterator<Scalar> it(mat_folder);\n    for (; it; ++it)\n    {\n      A = it.matrix();\n      if(A.diagonal().size() <= maxRealWorldSize)\n      {\n        DenseVector b = it.rhs();\n        DenseVector refX = it.refX();\n        std::cout << \"INFO | Testing \" << sym_to_string(it.sym()) << \"sparse problem \" << it.matname()\n                  << \" (\" << A.rows() << \"x\" << A.cols() << \") using \" << typeid(Solver).name() << \"...\" << std::endl;\n        CALL_SUBTEST(check_sparse_solving_real_cases(solver, A, b, A, refX));\n        std::string stats = solver_stats(solver);\n        if(stats.size()>0)\n          std::cout << \"INFO |  \" << stats << std::endl;\n      }\n      else\n      {\n        std::cout << \"INFO | SKIP sparse problem \\\"\" << it.matname() << \"\\\" (too large)\" << std::endl;\n      }\n    }\n  }\n#else\n  EIGEN_UNUSED_VARIABLE(maxRealWorldSize);\n#endif\n\n}\n\ntemplate<typename Solver> void check_sparse_square_determinant(Solver& solver)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  \n  for (int i = 0; i < g_repeat; i++) {\n    // generate the problem\n    Mat A;\n    DenseMatrix dA;\n    \n    int size = internal::random<int>(1,30);\n    dA.setRandom(size,size);\n    \n    dA = (dA.array().abs()<0.3).select(0,dA);\n    dA.diagonal() = (dA.diagonal().array()==0).select(1,dA.diagonal());\n    A = dA.sparseView();\n    A.makeCompressed();\n  \n    check_sparse_determinant(solver, A, dA);\n  }\n}\n\ntemplate<typename Solver> void check_sparse_square_abs_determinant(Solver& solver)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n\n  for (int i = 0; i < g_repeat; i++) {\n    // generate the problem\n    Mat A;\n    DenseMatrix dA;\n    generate_sparse_square_problem(solver, A, dA, 30);\n    A.makeCompressed();\n    check_sparse_abs_determinant(solver, A, dA);\n  }\n}\n\ntemplate<typename Solver, typename DenseMat>\nvoid generate_sparse_leastsquare_problem(Solver&, typename Solver::MatrixType& A, DenseMat& dA, int maxSize = 300, int options = ForceNonZeroDiag)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n\n  int rows = internal::random<int>(1,maxSize);\n  int cols = internal::random<int>(1,rows);\n  double density = (std::max)(8./(rows*cols), 0.01);\n  \n  A.resize(rows,cols);\n  dA.resize(rows,cols);\n\n  initSparse<Scalar>(density, dA, A, options);\n}\n\ntemplate<typename Solver> void check_sparse_leastsquare_solving(Solver& solver)\n{\n  typedef typename Solver::MatrixType Mat;\n  typedef typename Mat::Scalar Scalar;\n  typedef SparseMatrix<Scalar,ColMajor, typename Mat::StorageIndex> SpMat;\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n\n  int rhsCols = internal::random<int>(1,16);\n\n  Mat A;\n  DenseMatrix dA;\n  for (int i = 0; i < g_repeat; i++) {\n    generate_sparse_leastsquare_problem(solver, A, dA);\n\n    A.makeCompressed();\n    DenseVector b = DenseVector::Random(A.rows());\n    DenseMatrix dB(A.rows(),rhsCols);\n    SpMat B(A.rows(),rhsCols);\n    double density = (std::max)(8./(A.rows()*rhsCols), 0.1);\n    initSparse<Scalar>(density, dB, B, ForceNonZeroDiag);\n    B.makeCompressed();\n    check_sparse_solving(solver, A, b,  dA, b);\n    check_sparse_solving(solver, A, dB, dA, dB);\n    check_sparse_solving(solver, A, B,  dA, dB);\n    \n    // check only once\n    if(i==0)\n    {\n      b = DenseVector::Zero(A.rows());\n      check_sparse_solving(solver, A, b, dA, b);\n    }\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/sparse_solvers.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"sparse.h\"\n\ntemplate<typename Scalar> void\ninitSPD(double density,\n        Matrix<Scalar,Dynamic,Dynamic>& refMat,\n        SparseMatrix<Scalar>& sparseMat)\n{\n  Matrix<Scalar,Dynamic,Dynamic> aux(refMat.rows(),refMat.cols());\n  initSparse(density,refMat,sparseMat);\n  refMat = refMat * refMat.adjoint();\n  for (int k=0; k<2; ++k)\n  {\n    initSparse(density,aux,sparseMat,ForceNonZeroDiag);\n    refMat += aux * aux.adjoint();\n  }\n  sparseMat.setZero();\n  for (int j=0 ; j<sparseMat.cols(); ++j)\n    for (int i=j ; i<sparseMat.rows(); ++i)\n      if (refMat(i,j)!=Scalar(0))\n        sparseMat.insert(i,j) = refMat(i,j);\n  sparseMat.finalize();\n}\n\ntemplate<typename Scalar> void sparse_solvers(int rows, int cols)\n{\n  double density = (std::max)(8./(rows*cols), 0.01);\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n  // Scalar eps = 1e-6;\n\n  DenseVector vec1 = DenseVector::Random(rows);\n\n  std::vector<Vector2i> zeroCoords;\n  std::vector<Vector2i> nonzeroCoords;\n\n  // test triangular solver\n  {\n    DenseVector vec2 = vec1, vec3 = vec1;\n    SparseMatrix<Scalar> m2(rows, cols);\n    DenseMatrix refMat2 = DenseMatrix::Zero(rows, cols);\n\n    // lower - dense\n    initSparse<Scalar>(density, refMat2, m2, ForceNonZeroDiag|MakeLowerTriangular, &zeroCoords, &nonzeroCoords);\n    VERIFY_IS_APPROX(refMat2.template triangularView<Lower>().solve(vec2),\n                     m2.template triangularView<Lower>().solve(vec3));\n\n    // upper - dense\n    initSparse<Scalar>(density, refMat2, m2, ForceNonZeroDiag|MakeUpperTriangular, &zeroCoords, &nonzeroCoords);\n    VERIFY_IS_APPROX(refMat2.template triangularView<Upper>().solve(vec2),\n                     m2.template triangularView<Upper>().solve(vec3));\n    VERIFY_IS_APPROX(refMat2.conjugate().template triangularView<Upper>().solve(vec2),\n                     m2.conjugate().template triangularView<Upper>().solve(vec3));\n    {\n      SparseMatrix<Scalar> cm2(m2);\n      //Index rows, Index cols, Index nnz, Index* outerIndexPtr, Index* innerIndexPtr, Scalar* valuePtr\n      MappedSparseMatrix<Scalar> mm2(rows, cols, cm2.nonZeros(), cm2.outerIndexPtr(), cm2.innerIndexPtr(), cm2.valuePtr());\n      VERIFY_IS_APPROX(refMat2.conjugate().template triangularView<Upper>().solve(vec2),\n                       mm2.conjugate().template triangularView<Upper>().solve(vec3));\n    }\n\n    // lower - transpose\n    initSparse<Scalar>(density, refMat2, m2, ForceNonZeroDiag|MakeLowerTriangular, &zeroCoords, &nonzeroCoords);\n    VERIFY_IS_APPROX(refMat2.transpose().template triangularView<Upper>().solve(vec2),\n                     m2.transpose().template triangularView<Upper>().solve(vec3));\n\n    // upper - transpose\n    initSparse<Scalar>(density, refMat2, m2, ForceNonZeroDiag|MakeUpperTriangular, &zeroCoords, &nonzeroCoords);\n    VERIFY_IS_APPROX(refMat2.transpose().template triangularView<Lower>().solve(vec2),\n                     m2.transpose().template triangularView<Lower>().solve(vec3));\n\n    SparseMatrix<Scalar> matB(rows, rows);\n    DenseMatrix refMatB = DenseMatrix::Zero(rows, rows);\n\n    // lower - sparse\n    initSparse<Scalar>(density, refMat2, m2, ForceNonZeroDiag|MakeLowerTriangular);\n    initSparse<Scalar>(density, refMatB, matB);\n    refMat2.template triangularView<Lower>().solveInPlace(refMatB);\n    m2.template triangularView<Lower>().solveInPlace(matB);\n    VERIFY_IS_APPROX(matB.toDense(), refMatB);\n\n    // upper - sparse\n    initSparse<Scalar>(density, refMat2, m2, ForceNonZeroDiag|MakeUpperTriangular);\n    initSparse<Scalar>(density, refMatB, matB);\n    refMat2.template triangularView<Upper>().solveInPlace(refMatB);\n    m2.template triangularView<Upper>().solveInPlace(matB);\n    VERIFY_IS_APPROX(matB, refMatB);\n\n    // test deprecated API\n    initSparse<Scalar>(density, refMat2, m2, ForceNonZeroDiag|MakeLowerTriangular, &zeroCoords, &nonzeroCoords);\n    VERIFY_IS_APPROX(refMat2.template triangularView<Lower>().solve(vec2),\n                     m2.template triangularView<Lower>().solve(vec3));\n\n    // test empty triangular matrix\n    {\n      m2.resize(0,0);\n      refMatB.resize(0,refMatB.cols());\n      DenseMatrix res = m2.template triangularView<Lower>().solve(refMatB);\n      VERIFY_IS_EQUAL(res.rows(),0);\n      VERIFY_IS_EQUAL(res.cols(),refMatB.cols());\n      res = refMatB;\n      m2.template triangularView<Lower>().solveInPlace(res);\n      VERIFY_IS_EQUAL(res.rows(),0);\n      VERIFY_IS_EQUAL(res.cols(),refMatB.cols());\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(sparse_solvers)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(sparse_solvers<double>(8, 8) );\n    int s = internal::random<int>(1,300);\n    CALL_SUBTEST_2(sparse_solvers<std::complex<double> >(s,s) );\n    CALL_SUBTEST_1(sparse_solvers<double>(s,s) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/sparse_vector.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"sparse.h\"\n\ntemplate<typename Scalar,typename StorageIndex> void sparse_vector(int rows, int cols)\n{\n  double densityMat = (std::max)(8./(rows*cols), 0.01);\n  double densityVec = (std::max)(8./(rows), 0.1);\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n  typedef SparseVector<Scalar,0,StorageIndex> SparseVectorType;\n  typedef SparseMatrix<Scalar,0,StorageIndex> SparseMatrixType;\n  Scalar eps = 1e-6;\n\n  SparseMatrixType m1(rows,rows);\n  SparseVectorType v1(rows), v2(rows), v3(rows);\n  DenseMatrix refM1 = DenseMatrix::Zero(rows, rows);\n  DenseVector refV1 = DenseVector::Random(rows),\n              refV2 = DenseVector::Random(rows),\n              refV3 = DenseVector::Random(rows);\n\n  std::vector<int> zerocoords, nonzerocoords;\n  initSparse<Scalar>(densityVec, refV1, v1, &zerocoords, &nonzerocoords);\n  initSparse<Scalar>(densityMat, refM1, m1);\n\n  initSparse<Scalar>(densityVec, refV2, v2);\n  initSparse<Scalar>(densityVec, refV3, v3);\n\n  Scalar s1 = internal::random<Scalar>();\n\n  // test coeff and coeffRef\n  for (unsigned int i=0; i<zerocoords.size(); ++i)\n  {\n    VERIFY_IS_MUCH_SMALLER_THAN( v1.coeff(zerocoords[i]), eps );\n    //VERIFY_RAISES_ASSERT( v1.coeffRef(zerocoords[i]) = 5 );\n  }\n  {\n    VERIFY(int(nonzerocoords.size()) == v1.nonZeros());\n    int j=0;\n    for (typename SparseVectorType::InnerIterator it(v1); it; ++it,++j)\n    {\n      VERIFY(nonzerocoords[j]==it.index());\n      VERIFY(it.value()==v1.coeff(it.index()));\n      VERIFY(it.value()==refV1.coeff(it.index()));\n    }\n  }\n  VERIFY_IS_APPROX(v1, refV1);\n  \n  // test coeffRef with reallocation\n  {\n    SparseVectorType v4(rows);\n    DenseVector v5 = DenseVector::Zero(rows);\n    for(int k=0; k<rows; ++k)\n    {\n      int i = internal::random<int>(0,rows-1);\n      Scalar v = internal::random<Scalar>();\n      v4.coeffRef(i) += v;\n      v5.coeffRef(i) += v;\n    }\n    VERIFY_IS_APPROX(v4,v5);\n  }\n\n  v1.coeffRef(nonzerocoords[0]) = Scalar(5);\n  refV1.coeffRef(nonzerocoords[0]) = Scalar(5);\n  VERIFY_IS_APPROX(v1, refV1);\n\n  VERIFY_IS_APPROX(v1+v2, refV1+refV2);\n  VERIFY_IS_APPROX(v1+v2+v3, refV1+refV2+refV3);\n\n  VERIFY_IS_APPROX(v1*s1-v2, refV1*s1-refV2);\n\n  VERIFY_IS_APPROX(v1*=s1, refV1*=s1);\n  VERIFY_IS_APPROX(v1/=s1, refV1/=s1);\n\n  VERIFY_IS_APPROX(v1+=v2, refV1+=refV2);\n  VERIFY_IS_APPROX(v1-=v2, refV1-=refV2);\n\n  VERIFY_IS_APPROX(v1.dot(v2), refV1.dot(refV2));\n  VERIFY_IS_APPROX(v1.dot(refV2), refV1.dot(refV2));\n\n  VERIFY_IS_APPROX(m1*v2, refM1*refV2);\n  VERIFY_IS_APPROX(v1.dot(m1*v2), refV1.dot(refM1*refV2));\n  {\n    int i = internal::random<int>(0,rows-1);\n    VERIFY_IS_APPROX(v1.dot(m1.col(i)), refV1.dot(refM1.col(i)));\n  }\n\n\n  VERIFY_IS_APPROX(v1.squaredNorm(), refV1.squaredNorm());\n  \n  VERIFY_IS_APPROX(v1.blueNorm(), refV1.blueNorm());\n\n  // test aliasing\n  VERIFY_IS_APPROX((v1 = -v1), (refV1 = -refV1));\n  VERIFY_IS_APPROX((v1 = v1.transpose()), (refV1 = refV1.transpose().eval()));\n  VERIFY_IS_APPROX((v1 += -v1), (refV1 += -refV1));\n  \n  // sparse matrix to sparse vector\n  SparseMatrixType mv1;\n  VERIFY_IS_APPROX((mv1=v1),v1);\n  VERIFY_IS_APPROX(mv1,(v1=mv1));\n  VERIFY_IS_APPROX(mv1,(v1=mv1.transpose()));\n  \n  // check copy to dense vector with transpose\n  refV3.resize(0);\n  VERIFY_IS_APPROX(refV3 = v1.transpose(),v1.toDense()); \n  VERIFY_IS_APPROX(DenseVector(v1),v1.toDense()); \n\n  // test conservative resize\n  {\n    std::vector<StorageIndex> inc;\n    if(rows > 3)\n      inc.push_back(-3);\n    inc.push_back(0);\n    inc.push_back(3);\n    inc.push_back(1);\n    inc.push_back(10);\n\n    for(std::size_t i = 0; i< inc.size(); i++) {\n      StorageIndex incRows = inc[i];\n      SparseVectorType vec1(rows);\n      DenseVector refVec1 = DenseVector::Zero(rows);\n      initSparse<Scalar>(densityVec, refVec1, vec1);\n\n      vec1.conservativeResize(rows+incRows);\n      refVec1.conservativeResize(rows+incRows);\n      if (incRows > 0) refVec1.tail(incRows).setZero();\n\n      VERIFY_IS_APPROX(vec1, refVec1);\n\n      // Insert new values\n      if (incRows > 0)\n        vec1.insert(vec1.rows()-1) = refVec1(refVec1.rows()-1) = 1;\n\n      VERIFY_IS_APPROX(vec1, refVec1);\n    }\n  }\n\n}\n\nEIGEN_DECLARE_TEST(sparse_vector)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    int r = Eigen::internal::random<int>(1,500), c = Eigen::internal::random<int>(1,500);\n    if(Eigen::internal::random<int>(0,4) == 0) {\n      r = c; // check square matrices in 25% of tries\n    }\n    EIGEN_UNUSED_VARIABLE(r+c);\n\n    CALL_SUBTEST_1(( sparse_vector<double,int>(8, 8) ));\n    CALL_SUBTEST_2(( sparse_vector<std::complex<double>, int>(r, c) ));\n    CALL_SUBTEST_1(( sparse_vector<double,long int>(r, c) ));\n    CALL_SUBTEST_1(( sparse_vector<double,short>(r, c) ));\n  }\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/sparselu.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// SparseLU solve does not accept column major matrices for the destination.\n// However, as expected, the generic check_sparse_square_solving routines produces row-major\n// rhs and destination matrices when compiled with EIGEN_DEFAULT_TO_ROW_MAJOR\n\n#ifdef EIGEN_DEFAULT_TO_ROW_MAJOR\n#undef EIGEN_DEFAULT_TO_ROW_MAJOR\n#endif\n\n#include \"sparse_solver.h\"\n#include <Eigen/SparseLU>\n#include <unsupported/Eigen/SparseExtra>\n\ntemplate<typename T> void test_sparselu_T()\n{\n  SparseLU<SparseMatrix<T, ColMajor> /*, COLAMDOrdering<int>*/ > sparselu_colamd; // COLAMDOrdering is the default\n  SparseLU<SparseMatrix<T, ColMajor>, AMDOrdering<int> > sparselu_amd; \n  SparseLU<SparseMatrix<T, ColMajor, long int>, NaturalOrdering<long int> > sparselu_natural;\n  \n  check_sparse_square_solving(sparselu_colamd,  300, 100000, true); \n  check_sparse_square_solving(sparselu_amd,     300,  10000, true);\n  check_sparse_square_solving(sparselu_natural, 300,   2000, true);\n  \n  check_sparse_square_abs_determinant(sparselu_colamd);\n  check_sparse_square_abs_determinant(sparselu_amd);\n  \n  check_sparse_square_determinant(sparselu_colamd);\n  check_sparse_square_determinant(sparselu_amd);\n}\n\nEIGEN_DECLARE_TEST(sparselu)\n{\n  CALL_SUBTEST_1(test_sparselu_T<float>()); \n  CALL_SUBTEST_2(test_sparselu_T<double>());\n  CALL_SUBTEST_3(test_sparselu_T<std::complex<float> >()); \n  CALL_SUBTEST_4(test_sparselu_T<std::complex<double> >());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/sparseqr.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Desire Nuentsa Wakam <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n#include \"sparse.h\"\n#include <Eigen/SparseQR>\n\ntemplate<typename MatrixType,typename DenseMat>\nint generate_sparse_rectangular_problem(MatrixType& A, DenseMat& dA, int maxRows = 300, int maxCols = 150)\n{\n  eigen_assert(maxRows >= maxCols);\n  typedef typename MatrixType::Scalar Scalar;\n  int rows = internal::random<int>(1,maxRows);\n  int cols = internal::random<int>(1,maxCols);\n  double density = (std::max)(8./(rows*cols), 0.01);\n  \n  A.resize(rows,cols);\n  dA.resize(rows,cols);\n  initSparse<Scalar>(density, dA, A,ForceNonZeroDiag);\n  A.makeCompressed();\n  int nop = internal::random<int>(0, internal::random<double>(0,1) > 0.5 ? cols/2 : 0);\n  for(int k=0; k<nop; ++k)\n  {\n    int j0 = internal::random<int>(0,cols-1);\n    int j1 = internal::random<int>(0,cols-1);\n    Scalar s = internal::random<Scalar>();\n    A.col(j0)  = s * A.col(j1);\n    dA.col(j0) = s * dA.col(j1);\n  }\n  \n//   if(rows<cols) {\n//     A.conservativeResize(cols,cols);\n//     dA.conservativeResize(cols,cols);\n//     dA.bottomRows(cols-rows).setZero();\n//   }\n  \n  return rows;\n}\n\ntemplate<typename Scalar> void test_sparseqr_scalar()\n{\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef SparseMatrix<Scalar,ColMajor> MatrixType; \n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMat;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n  MatrixType A;\n  DenseMat dA;\n  DenseVector refX,x,b; \n  SparseQR<MatrixType, COLAMDOrdering<int> > solver; \n  generate_sparse_rectangular_problem(A,dA);\n  \n  b = dA * DenseVector::Random(A.cols());\n  solver.compute(A);\n\n  // Q should be MxM\n  VERIFY_IS_EQUAL(solver.matrixQ().rows(), A.rows());\n  VERIFY_IS_EQUAL(solver.matrixQ().cols(), A.rows());\n\n  // R should be MxN\n  VERIFY_IS_EQUAL(solver.matrixR().rows(), A.rows());\n  VERIFY_IS_EQUAL(solver.matrixR().cols(), A.cols());\n\n  // Q and R can be multiplied\n  DenseMat recoveredA = solver.matrixQ()\n                      * DenseMat(solver.matrixR().template triangularView<Upper>())\n                      * solver.colsPermutation().transpose();\n  VERIFY_IS_EQUAL(recoveredA.rows(), A.rows());\n  VERIFY_IS_EQUAL(recoveredA.cols(), A.cols());\n\n  // and in the full rank case the original matrix is recovered\n  if (solver.rank() == A.cols())\n  {\n      VERIFY_IS_APPROX(A, recoveredA);\n  }\n\n  if(internal::random<float>(0,1)>0.5f)\n    solver.factorize(A);  // this checks that calling analyzePattern is not needed if the pattern do not change.\n  if (solver.info() != Success)\n  {\n    std::cerr << \"sparse QR factorization failed\\n\";\n    exit(0);\n    return;\n  }\n  x = solver.solve(b);\n  if (solver.info() != Success)\n  {\n    std::cerr << \"sparse QR factorization failed\\n\";\n    exit(0);\n    return;\n  }\n\n  // Compare with a dense QR solver\n  ColPivHouseholderQR<DenseMat> dqr(dA);\n  refX = dqr.solve(b);\n  \n  bool rank_deficient = A.cols()>A.rows() || dqr.rank()<A.cols();\n  if(rank_deficient)\n  {\n    // rank deficient problem -> we might have to increase the threshold\n    // to get a correct solution.\n    RealScalar th = RealScalar(20)*dA.colwise().norm().maxCoeff()*(A.rows()+A.cols()) * NumTraits<RealScalar>::epsilon();\n    for(Index k=0; (k<16) && !test_isApprox(A*x,b); ++k)\n    {\n      th *= RealScalar(10);\n      solver.setPivotThreshold(th);\n      solver.compute(A);\n      x = solver.solve(b);\n    }\n  }\n\n  VERIFY_IS_APPROX(A * x, b);\n  \n  // For rank deficient problem, the estimated rank might\n  // be slightly off, so let's only raise a warning in such cases.\n  if(rank_deficient) ++g_test_level;\n  VERIFY_IS_EQUAL(solver.rank(), dqr.rank());\n  if(rank_deficient) --g_test_level;\n\n  if(solver.rank()==A.cols()) // full rank\n    VERIFY_IS_APPROX(x, refX);\n//   else\n//     VERIFY((dA * refX - b).norm() * 2 > (A * x - b).norm() );\n\n  // Compute explicitly the matrix Q\n  MatrixType Q, QtQ, idM;\n  Q = solver.matrixQ();\n  //Check  ||Q' * Q - I ||\n  QtQ = Q * Q.adjoint();\n  idM.resize(Q.rows(), Q.rows()); idM.setIdentity();\n  VERIFY(idM.isApprox(QtQ));\n  \n  // Q to dense\n  DenseMat dQ;\n  dQ = solver.matrixQ();\n  VERIFY_IS_APPROX(Q, dQ);\n}\nEIGEN_DECLARE_TEST(sparseqr)\n{\n  for(int i=0; i<g_repeat; ++i)\n  {\n    CALL_SUBTEST_1(test_sparseqr_scalar<double>());\n    CALL_SUBTEST_2(test_sparseqr_scalar<std::complex<double> >());\n  }\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/special_numbers.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename Scalar> void special_numbers()\n{\n  typedef Matrix<Scalar, Dynamic,Dynamic> MatType;\n  int rows = internal::random<int>(1,300);\n  int cols = internal::random<int>(1,300);\n  \n  Scalar nan = std::numeric_limits<Scalar>::quiet_NaN();\n  Scalar inf = std::numeric_limits<Scalar>::infinity();\n  Scalar s1 = internal::random<Scalar>();\n  \n  MatType m1    = MatType::Random(rows,cols),\n          mnan  = MatType::Random(rows,cols),\n          minf  = MatType::Random(rows,cols),\n          mboth = MatType::Random(rows,cols);\n          \n  int n = internal::random<int>(1,10);\n  for(int k=0; k<n; ++k)\n  {\n    mnan(internal::random<int>(0,rows-1), internal::random<int>(0,cols-1)) = nan;\n    minf(internal::random<int>(0,rows-1), internal::random<int>(0,cols-1)) = inf;\n  }\n  mboth = mnan + minf;\n  \n  VERIFY(!m1.hasNaN());\n  VERIFY(m1.allFinite());\n  \n  VERIFY(mnan.hasNaN());\n  VERIFY((s1*mnan).hasNaN());\n  VERIFY(!minf.hasNaN());\n  VERIFY(!(2*minf).hasNaN());\n  VERIFY(mboth.hasNaN());\n  VERIFY(mboth.array().hasNaN());\n  \n  VERIFY(!mnan.allFinite());\n  VERIFY(!minf.allFinite());\n  VERIFY(!(minf-mboth).allFinite());\n  VERIFY(!mboth.allFinite());\n  VERIFY(!mboth.array().allFinite());\n}\n\nEIGEN_DECLARE_TEST(special_numbers)\n{\n  for(int i = 0; i < 10*g_repeat; i++) {\n    CALL_SUBTEST_1( special_numbers<float>() );\n    CALL_SUBTEST_1( special_numbers<double>() );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/split_test_helper.h",
    "content": "#if defined(EIGEN_TEST_PART_1) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_1(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_1(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_2) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_2(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_2(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_3) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_3(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_3(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_4) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_4(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_4(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_5) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_5(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_5(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_6) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_6(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_6(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_7) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_7(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_7(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_8) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_8(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_8(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_9) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_9(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_9(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_10) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_10(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_10(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_11) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_11(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_11(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_12) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_12(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_12(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_13) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_13(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_13(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_14) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_14(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_14(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_15) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_15(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_15(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_16) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_16(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_16(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_17) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_17(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_17(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_18) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_18(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_18(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_19) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_19(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_19(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_20) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_20(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_20(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_21) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_21(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_21(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_22) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_22(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_22(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_23) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_23(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_23(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_24) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_24(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_24(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_25) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_25(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_25(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_26) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_26(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_26(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_27) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_27(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_27(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_28) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_28(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_28(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_29) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_29(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_29(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_30) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_30(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_30(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_31) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_31(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_31(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_32) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_32(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_32(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_33) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_33(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_33(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_34) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_34(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_34(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_35) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_35(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_35(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_36) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_36(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_36(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_37) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_37(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_37(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_38) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_38(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_38(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_39) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_39(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_39(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_40) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_40(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_40(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_41) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_41(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_41(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_42) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_42(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_42(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_43) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_43(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_43(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_44) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_44(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_44(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_45) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_45(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_45(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_46) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_46(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_46(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_47) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_47(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_47(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_48) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_48(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_48(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_49) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_49(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_49(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_50) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_50(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_50(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_51) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_51(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_51(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_52) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_52(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_52(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_53) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_53(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_53(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_54) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_54(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_54(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_55) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_55(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_55(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_56) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_56(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_56(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_57) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_57(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_57(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_58) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_58(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_58(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_59) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_59(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_59(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_60) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_60(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_60(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_61) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_61(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_61(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_62) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_62(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_62(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_63) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_63(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_63(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_64) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_64(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_64(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_65) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_65(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_65(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_66) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_66(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_66(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_67) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_67(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_67(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_68) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_68(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_68(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_69) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_69(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_69(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_70) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_70(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_70(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_71) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_71(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_71(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_72) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_72(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_72(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_73) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_73(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_73(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_74) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_74(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_74(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_75) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_75(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_75(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_76) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_76(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_76(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_77) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_77(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_77(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_78) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_78(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_78(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_79) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_79(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_79(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_80) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_80(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_80(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_81) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_81(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_81(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_82) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_82(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_82(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_83) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_83(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_83(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_84) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_84(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_84(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_85) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_85(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_85(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_86) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_86(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_86(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_87) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_87(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_87(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_88) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_88(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_88(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_89) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_89(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_89(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_90) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_90(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_90(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_91) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_91(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_91(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_92) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_92(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_92(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_93) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_93(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_93(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_94) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_94(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_94(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_95) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_95(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_95(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_96) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_96(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_96(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_97) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_97(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_97(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_98) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_98(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_98(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_99) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_99(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_99(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_100) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_100(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_100(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_101) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_101(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_101(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_102) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_102(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_102(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_103) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_103(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_103(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_104) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_104(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_104(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_105) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_105(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_105(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_106) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_106(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_106(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_107) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_107(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_107(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_108) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_108(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_108(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_109) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_109(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_109(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_110) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_110(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_110(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_111) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_111(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_111(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_112) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_112(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_112(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_113) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_113(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_113(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_114) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_114(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_114(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_115) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_115(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_115(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_116) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_116(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_116(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_117) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_117(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_117(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_118) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_118(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_118(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_119) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_119(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_119(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_120) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_120(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_120(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_121) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_121(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_121(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_122) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_122(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_122(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_123) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_123(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_123(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_124) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_124(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_124(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_125) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_125(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_125(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_126) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_126(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_126(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_127) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_127(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_127(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_128) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_128(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_128(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_129) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_129(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_129(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_130) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_130(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_130(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_131) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_131(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_131(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_132) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_132(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_132(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_133) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_133(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_133(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_134) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_134(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_134(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_135) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_135(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_135(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_136) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_136(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_136(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_137) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_137(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_137(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_138) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_138(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_138(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_139) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_139(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_139(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_140) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_140(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_140(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_141) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_141(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_141(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_142) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_142(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_142(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_143) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_143(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_143(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_144) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_144(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_144(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_145) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_145(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_145(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_146) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_146(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_146(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_147) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_147(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_147(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_148) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_148(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_148(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_149) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_149(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_149(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_150) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_150(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_150(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_151) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_151(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_151(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_152) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_152(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_152(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_153) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_153(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_153(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_154) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_154(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_154(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_155) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_155(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_155(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_156) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_156(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_156(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_157) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_157(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_157(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_158) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_158(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_158(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_159) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_159(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_159(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_160) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_160(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_160(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_161) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_161(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_161(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_162) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_162(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_162(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_163) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_163(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_163(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_164) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_164(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_164(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_165) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_165(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_165(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_166) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_166(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_166(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_167) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_167(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_167(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_168) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_168(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_168(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_169) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_169(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_169(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_170) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_170(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_170(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_171) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_171(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_171(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_172) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_172(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_172(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_173) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_173(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_173(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_174) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_174(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_174(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_175) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_175(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_175(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_176) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_176(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_176(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_177) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_177(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_177(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_178) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_178(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_178(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_179) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_179(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_179(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_180) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_180(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_180(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_181) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_181(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_181(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_182) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_182(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_182(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_183) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_183(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_183(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_184) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_184(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_184(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_185) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_185(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_185(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_186) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_186(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_186(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_187) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_187(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_187(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_188) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_188(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_188(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_189) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_189(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_189(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_190) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_190(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_190(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_191) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_191(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_191(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_192) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_192(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_192(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_193) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_193(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_193(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_194) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_194(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_194(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_195) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_195(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_195(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_196) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_196(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_196(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_197) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_197(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_197(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_198) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_198(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_198(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_199) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_199(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_199(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_200) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_200(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_200(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_201) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_201(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_201(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_202) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_202(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_202(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_203) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_203(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_203(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_204) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_204(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_204(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_205) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_205(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_205(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_206) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_206(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_206(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_207) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_207(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_207(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_208) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_208(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_208(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_209) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_209(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_209(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_210) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_210(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_210(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_211) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_211(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_211(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_212) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_212(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_212(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_213) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_213(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_213(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_214) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_214(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_214(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_215) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_215(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_215(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_216) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_216(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_216(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_217) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_217(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_217(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_218) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_218(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_218(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_219) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_219(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_219(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_220) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_220(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_220(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_221) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_221(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_221(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_222) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_222(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_222(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_223) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_223(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_223(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_224) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_224(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_224(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_225) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_225(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_225(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_226) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_226(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_226(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_227) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_227(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_227(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_228) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_228(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_228(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_229) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_229(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_229(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_230) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_230(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_230(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_231) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_231(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_231(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_232) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_232(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_232(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_233) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_233(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_233(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_234) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_234(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_234(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_235) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_235(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_235(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_236) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_236(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_236(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_237) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_237(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_237(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_238) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_238(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_238(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_239) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_239(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_239(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_240) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_240(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_240(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_241) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_241(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_241(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_242) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_242(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_242(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_243) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_243(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_243(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_244) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_244(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_244(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_245) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_245(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_245(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_246) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_246(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_246(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_247) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_247(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_247(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_248) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_248(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_248(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_249) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_249(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_249(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_250) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_250(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_250(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_251) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_251(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_251(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_252) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_252(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_252(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_253) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_253(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_253(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_254) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_254(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_254(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_255) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_255(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_255(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_256) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_256(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_256(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_257) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_257(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_257(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_258) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_258(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_258(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_259) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_259(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_259(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_260) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_260(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_260(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_261) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_261(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_261(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_262) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_262(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_262(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_263) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_263(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_263(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_264) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_264(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_264(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_265) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_265(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_265(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_266) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_266(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_266(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_267) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_267(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_267(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_268) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_268(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_268(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_269) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_269(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_269(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_270) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_270(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_270(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_271) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_271(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_271(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_272) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_272(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_272(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_273) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_273(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_273(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_274) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_274(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_274(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_275) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_275(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_275(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_276) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_276(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_276(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_277) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_277(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_277(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_278) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_278(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_278(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_279) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_279(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_279(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_280) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_280(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_280(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_281) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_281(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_281(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_282) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_282(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_282(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_283) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_283(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_283(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_284) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_284(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_284(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_285) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_285(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_285(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_286) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_286(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_286(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_287) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_287(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_287(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_288) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_288(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_288(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_289) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_289(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_289(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_290) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_290(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_290(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_291) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_291(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_291(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_292) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_292(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_292(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_293) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_293(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_293(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_294) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_294(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_294(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_295) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_295(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_295(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_296) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_296(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_296(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_297) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_297(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_297(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_298) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_298(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_298(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_299) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_299(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_299(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_300) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_300(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_300(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_301) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_301(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_301(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_302) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_302(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_302(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_303) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_303(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_303(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_304) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_304(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_304(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_305) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_305(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_305(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_306) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_306(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_306(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_307) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_307(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_307(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_308) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_308(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_308(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_309) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_309(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_309(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_310) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_310(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_310(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_311) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_311(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_311(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_312) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_312(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_312(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_313) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_313(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_313(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_314) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_314(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_314(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_315) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_315(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_315(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_316) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_316(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_316(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_317) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_317(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_317(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_318) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_318(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_318(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_319) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_319(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_319(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_320) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_320(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_320(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_321) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_321(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_321(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_322) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_322(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_322(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_323) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_323(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_323(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_324) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_324(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_324(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_325) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_325(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_325(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_326) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_326(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_326(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_327) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_327(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_327(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_328) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_328(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_328(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_329) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_329(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_329(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_330) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_330(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_330(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_331) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_331(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_331(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_332) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_332(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_332(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_333) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_333(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_333(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_334) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_334(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_334(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_335) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_335(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_335(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_336) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_336(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_336(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_337) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_337(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_337(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_338) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_338(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_338(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_339) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_339(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_339(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_340) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_340(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_340(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_341) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_341(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_341(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_342) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_342(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_342(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_343) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_343(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_343(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_344) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_344(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_344(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_345) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_345(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_345(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_346) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_346(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_346(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_347) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_347(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_347(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_348) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_348(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_348(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_349) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_349(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_349(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_350) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_350(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_350(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_351) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_351(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_351(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_352) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_352(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_352(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_353) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_353(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_353(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_354) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_354(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_354(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_355) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_355(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_355(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_356) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_356(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_356(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_357) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_357(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_357(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_358) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_358(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_358(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_359) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_359(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_359(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_360) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_360(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_360(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_361) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_361(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_361(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_362) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_362(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_362(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_363) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_363(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_363(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_364) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_364(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_364(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_365) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_365(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_365(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_366) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_366(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_366(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_367) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_367(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_367(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_368) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_368(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_368(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_369) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_369(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_369(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_370) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_370(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_370(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_371) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_371(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_371(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_372) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_372(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_372(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_373) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_373(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_373(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_374) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_374(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_374(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_375) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_375(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_375(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_376) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_376(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_376(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_377) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_377(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_377(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_378) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_378(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_378(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_379) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_379(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_379(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_380) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_380(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_380(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_381) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_381(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_381(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_382) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_382(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_382(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_383) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_383(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_383(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_384) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_384(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_384(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_385) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_385(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_385(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_386) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_386(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_386(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_387) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_387(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_387(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_388) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_388(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_388(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_389) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_389(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_389(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_390) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_390(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_390(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_391) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_391(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_391(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_392) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_392(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_392(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_393) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_393(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_393(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_394) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_394(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_394(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_395) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_395(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_395(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_396) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_396(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_396(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_397) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_397(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_397(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_398) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_398(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_398(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_399) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_399(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_399(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_400) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_400(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_400(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_401) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_401(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_401(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_402) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_402(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_402(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_403) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_403(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_403(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_404) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_404(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_404(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_405) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_405(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_405(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_406) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_406(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_406(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_407) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_407(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_407(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_408) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_408(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_408(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_409) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_409(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_409(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_410) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_410(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_410(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_411) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_411(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_411(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_412) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_412(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_412(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_413) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_413(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_413(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_414) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_414(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_414(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_415) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_415(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_415(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_416) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_416(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_416(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_417) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_417(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_417(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_418) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_418(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_418(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_419) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_419(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_419(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_420) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_420(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_420(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_421) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_421(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_421(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_422) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_422(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_422(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_423) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_423(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_423(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_424) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_424(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_424(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_425) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_425(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_425(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_426) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_426(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_426(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_427) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_427(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_427(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_428) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_428(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_428(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_429) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_429(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_429(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_430) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_430(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_430(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_431) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_431(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_431(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_432) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_432(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_432(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_433) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_433(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_433(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_434) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_434(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_434(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_435) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_435(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_435(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_436) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_436(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_436(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_437) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_437(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_437(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_438) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_438(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_438(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_439) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_439(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_439(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_440) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_440(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_440(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_441) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_441(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_441(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_442) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_442(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_442(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_443) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_443(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_443(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_444) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_444(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_444(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_445) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_445(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_445(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_446) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_446(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_446(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_447) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_447(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_447(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_448) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_448(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_448(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_449) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_449(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_449(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_450) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_450(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_450(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_451) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_451(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_451(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_452) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_452(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_452(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_453) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_453(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_453(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_454) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_454(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_454(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_455) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_455(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_455(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_456) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_456(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_456(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_457) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_457(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_457(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_458) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_458(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_458(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_459) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_459(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_459(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_460) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_460(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_460(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_461) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_461(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_461(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_462) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_462(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_462(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_463) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_463(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_463(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_464) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_464(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_464(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_465) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_465(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_465(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_466) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_466(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_466(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_467) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_467(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_467(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_468) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_468(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_468(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_469) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_469(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_469(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_470) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_470(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_470(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_471) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_471(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_471(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_472) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_472(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_472(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_473) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_473(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_473(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_474) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_474(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_474(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_475) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_475(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_475(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_476) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_476(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_476(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_477) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_477(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_477(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_478) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_478(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_478(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_479) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_479(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_479(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_480) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_480(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_480(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_481) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_481(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_481(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_482) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_482(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_482(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_483) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_483(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_483(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_484) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_484(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_484(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_485) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_485(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_485(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_486) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_486(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_486(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_487) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_487(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_487(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_488) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_488(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_488(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_489) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_489(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_489(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_490) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_490(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_490(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_491) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_491(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_491(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_492) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_492(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_492(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_493) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_493(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_493(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_494) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_494(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_494(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_495) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_495(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_495(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_496) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_496(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_496(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_497) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_497(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_497(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_498) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_498(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_498(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_499) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_499(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_499(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_500) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_500(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_500(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_501) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_501(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_501(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_502) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_502(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_502(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_503) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_503(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_503(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_504) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_504(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_504(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_505) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_505(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_505(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_506) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_506(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_506(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_507) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_507(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_507(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_508) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_508(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_508(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_509) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_509(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_509(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_510) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_510(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_510(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_511) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_511(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_511(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_512) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_512(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_512(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_513) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_513(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_513(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_514) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_514(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_514(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_515) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_515(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_515(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_516) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_516(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_516(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_517) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_517(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_517(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_518) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_518(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_518(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_519) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_519(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_519(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_520) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_520(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_520(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_521) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_521(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_521(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_522) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_522(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_522(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_523) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_523(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_523(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_524) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_524(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_524(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_525) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_525(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_525(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_526) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_526(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_526(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_527) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_527(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_527(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_528) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_528(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_528(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_529) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_529(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_529(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_530) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_530(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_530(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_531) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_531(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_531(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_532) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_532(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_532(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_533) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_533(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_533(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_534) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_534(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_534(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_535) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_535(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_535(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_536) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_536(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_536(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_537) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_537(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_537(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_538) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_538(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_538(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_539) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_539(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_539(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_540) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_540(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_540(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_541) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_541(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_541(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_542) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_542(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_542(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_543) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_543(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_543(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_544) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_544(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_544(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_545) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_545(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_545(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_546) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_546(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_546(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_547) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_547(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_547(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_548) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_548(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_548(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_549) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_549(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_549(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_550) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_550(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_550(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_551) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_551(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_551(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_552) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_552(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_552(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_553) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_553(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_553(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_554) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_554(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_554(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_555) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_555(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_555(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_556) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_556(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_556(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_557) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_557(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_557(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_558) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_558(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_558(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_559) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_559(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_559(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_560) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_560(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_560(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_561) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_561(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_561(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_562) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_562(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_562(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_563) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_563(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_563(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_564) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_564(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_564(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_565) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_565(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_565(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_566) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_566(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_566(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_567) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_567(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_567(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_568) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_568(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_568(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_569) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_569(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_569(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_570) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_570(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_570(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_571) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_571(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_571(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_572) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_572(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_572(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_573) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_573(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_573(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_574) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_574(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_574(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_575) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_575(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_575(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_576) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_576(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_576(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_577) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_577(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_577(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_578) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_578(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_578(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_579) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_579(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_579(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_580) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_580(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_580(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_581) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_581(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_581(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_582) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_582(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_582(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_583) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_583(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_583(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_584) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_584(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_584(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_585) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_585(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_585(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_586) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_586(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_586(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_587) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_587(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_587(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_588) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_588(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_588(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_589) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_589(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_589(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_590) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_590(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_590(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_591) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_591(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_591(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_592) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_592(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_592(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_593) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_593(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_593(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_594) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_594(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_594(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_595) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_595(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_595(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_596) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_596(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_596(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_597) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_597(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_597(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_598) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_598(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_598(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_599) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_599(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_599(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_600) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_600(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_600(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_601) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_601(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_601(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_602) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_602(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_602(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_603) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_603(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_603(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_604) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_604(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_604(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_605) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_605(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_605(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_606) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_606(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_606(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_607) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_607(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_607(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_608) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_608(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_608(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_609) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_609(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_609(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_610) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_610(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_610(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_611) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_611(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_611(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_612) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_612(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_612(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_613) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_613(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_613(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_614) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_614(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_614(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_615) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_615(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_615(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_616) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_616(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_616(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_617) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_617(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_617(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_618) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_618(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_618(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_619) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_619(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_619(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_620) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_620(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_620(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_621) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_621(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_621(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_622) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_622(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_622(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_623) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_623(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_623(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_624) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_624(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_624(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_625) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_625(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_625(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_626) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_626(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_626(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_627) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_627(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_627(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_628) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_628(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_628(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_629) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_629(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_629(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_630) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_630(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_630(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_631) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_631(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_631(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_632) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_632(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_632(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_633) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_633(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_633(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_634) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_634(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_634(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_635) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_635(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_635(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_636) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_636(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_636(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_637) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_637(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_637(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_638) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_638(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_638(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_639) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_639(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_639(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_640) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_640(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_640(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_641) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_641(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_641(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_642) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_642(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_642(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_643) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_643(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_643(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_644) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_644(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_644(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_645) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_645(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_645(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_646) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_646(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_646(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_647) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_647(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_647(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_648) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_648(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_648(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_649) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_649(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_649(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_650) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_650(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_650(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_651) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_651(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_651(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_652) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_652(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_652(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_653) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_653(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_653(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_654) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_654(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_654(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_655) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_655(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_655(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_656) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_656(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_656(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_657) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_657(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_657(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_658) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_658(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_658(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_659) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_659(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_659(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_660) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_660(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_660(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_661) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_661(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_661(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_662) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_662(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_662(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_663) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_663(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_663(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_664) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_664(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_664(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_665) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_665(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_665(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_666) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_666(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_666(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_667) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_667(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_667(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_668) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_668(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_668(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_669) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_669(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_669(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_670) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_670(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_670(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_671) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_671(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_671(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_672) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_672(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_672(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_673) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_673(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_673(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_674) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_674(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_674(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_675) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_675(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_675(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_676) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_676(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_676(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_677) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_677(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_677(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_678) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_678(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_678(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_679) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_679(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_679(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_680) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_680(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_680(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_681) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_681(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_681(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_682) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_682(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_682(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_683) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_683(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_683(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_684) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_684(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_684(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_685) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_685(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_685(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_686) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_686(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_686(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_687) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_687(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_687(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_688) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_688(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_688(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_689) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_689(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_689(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_690) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_690(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_690(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_691) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_691(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_691(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_692) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_692(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_692(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_693) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_693(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_693(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_694) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_694(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_694(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_695) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_695(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_695(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_696) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_696(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_696(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_697) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_697(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_697(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_698) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_698(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_698(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_699) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_699(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_699(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_700) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_700(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_700(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_701) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_701(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_701(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_702) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_702(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_702(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_703) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_703(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_703(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_704) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_704(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_704(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_705) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_705(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_705(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_706) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_706(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_706(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_707) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_707(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_707(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_708) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_708(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_708(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_709) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_709(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_709(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_710) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_710(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_710(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_711) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_711(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_711(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_712) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_712(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_712(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_713) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_713(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_713(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_714) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_714(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_714(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_715) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_715(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_715(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_716) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_716(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_716(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_717) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_717(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_717(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_718) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_718(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_718(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_719) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_719(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_719(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_720) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_720(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_720(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_721) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_721(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_721(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_722) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_722(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_722(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_723) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_723(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_723(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_724) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_724(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_724(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_725) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_725(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_725(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_726) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_726(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_726(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_727) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_727(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_727(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_728) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_728(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_728(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_729) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_729(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_729(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_730) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_730(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_730(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_731) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_731(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_731(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_732) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_732(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_732(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_733) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_733(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_733(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_734) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_734(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_734(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_735) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_735(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_735(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_736) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_736(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_736(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_737) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_737(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_737(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_738) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_738(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_738(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_739) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_739(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_739(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_740) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_740(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_740(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_741) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_741(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_741(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_742) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_742(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_742(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_743) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_743(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_743(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_744) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_744(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_744(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_745) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_745(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_745(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_746) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_746(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_746(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_747) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_747(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_747(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_748) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_748(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_748(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_749) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_749(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_749(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_750) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_750(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_750(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_751) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_751(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_751(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_752) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_752(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_752(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_753) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_753(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_753(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_754) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_754(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_754(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_755) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_755(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_755(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_756) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_756(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_756(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_757) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_757(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_757(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_758) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_758(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_758(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_759) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_759(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_759(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_760) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_760(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_760(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_761) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_761(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_761(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_762) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_762(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_762(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_763) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_763(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_763(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_764) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_764(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_764(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_765) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_765(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_765(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_766) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_766(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_766(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_767) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_767(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_767(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_768) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_768(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_768(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_769) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_769(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_769(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_770) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_770(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_770(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_771) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_771(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_771(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_772) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_772(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_772(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_773) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_773(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_773(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_774) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_774(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_774(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_775) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_775(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_775(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_776) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_776(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_776(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_777) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_777(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_777(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_778) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_778(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_778(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_779) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_779(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_779(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_780) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_780(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_780(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_781) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_781(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_781(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_782) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_782(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_782(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_783) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_783(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_783(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_784) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_784(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_784(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_785) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_785(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_785(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_786) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_786(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_786(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_787) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_787(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_787(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_788) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_788(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_788(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_789) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_789(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_789(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_790) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_790(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_790(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_791) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_791(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_791(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_792) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_792(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_792(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_793) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_793(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_793(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_794) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_794(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_794(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_795) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_795(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_795(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_796) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_796(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_796(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_797) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_797(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_797(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_798) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_798(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_798(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_799) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_799(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_799(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_800) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_800(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_800(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_801) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_801(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_801(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_802) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_802(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_802(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_803) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_803(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_803(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_804) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_804(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_804(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_805) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_805(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_805(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_806) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_806(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_806(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_807) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_807(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_807(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_808) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_808(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_808(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_809) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_809(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_809(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_810) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_810(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_810(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_811) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_811(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_811(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_812) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_812(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_812(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_813) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_813(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_813(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_814) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_814(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_814(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_815) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_815(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_815(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_816) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_816(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_816(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_817) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_817(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_817(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_818) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_818(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_818(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_819) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_819(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_819(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_820) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_820(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_820(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_821) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_821(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_821(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_822) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_822(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_822(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_823) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_823(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_823(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_824) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_824(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_824(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_825) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_825(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_825(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_826) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_826(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_826(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_827) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_827(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_827(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_828) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_828(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_828(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_829) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_829(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_829(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_830) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_830(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_830(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_831) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_831(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_831(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_832) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_832(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_832(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_833) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_833(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_833(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_834) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_834(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_834(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_835) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_835(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_835(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_836) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_836(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_836(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_837) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_837(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_837(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_838) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_838(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_838(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_839) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_839(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_839(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_840) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_840(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_840(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_841) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_841(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_841(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_842) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_842(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_842(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_843) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_843(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_843(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_844) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_844(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_844(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_845) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_845(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_845(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_846) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_846(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_846(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_847) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_847(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_847(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_848) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_848(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_848(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_849) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_849(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_849(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_850) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_850(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_850(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_851) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_851(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_851(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_852) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_852(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_852(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_853) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_853(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_853(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_854) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_854(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_854(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_855) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_855(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_855(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_856) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_856(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_856(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_857) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_857(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_857(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_858) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_858(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_858(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_859) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_859(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_859(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_860) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_860(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_860(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_861) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_861(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_861(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_862) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_862(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_862(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_863) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_863(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_863(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_864) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_864(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_864(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_865) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_865(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_865(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_866) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_866(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_866(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_867) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_867(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_867(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_868) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_868(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_868(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_869) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_869(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_869(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_870) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_870(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_870(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_871) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_871(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_871(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_872) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_872(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_872(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_873) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_873(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_873(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_874) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_874(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_874(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_875) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_875(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_875(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_876) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_876(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_876(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_877) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_877(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_877(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_878) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_878(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_878(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_879) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_879(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_879(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_880) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_880(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_880(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_881) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_881(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_881(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_882) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_882(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_882(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_883) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_883(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_883(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_884) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_884(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_884(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_885) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_885(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_885(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_886) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_886(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_886(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_887) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_887(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_887(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_888) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_888(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_888(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_889) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_889(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_889(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_890) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_890(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_890(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_891) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_891(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_891(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_892) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_892(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_892(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_893) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_893(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_893(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_894) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_894(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_894(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_895) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_895(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_895(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_896) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_896(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_896(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_897) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_897(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_897(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_898) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_898(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_898(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_899) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_899(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_899(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_900) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_900(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_900(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_901) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_901(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_901(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_902) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_902(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_902(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_903) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_903(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_903(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_904) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_904(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_904(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_905) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_905(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_905(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_906) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_906(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_906(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_907) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_907(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_907(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_908) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_908(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_908(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_909) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_909(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_909(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_910) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_910(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_910(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_911) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_911(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_911(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_912) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_912(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_912(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_913) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_913(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_913(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_914) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_914(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_914(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_915) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_915(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_915(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_916) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_916(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_916(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_917) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_917(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_917(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_918) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_918(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_918(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_919) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_919(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_919(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_920) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_920(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_920(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_921) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_921(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_921(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_922) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_922(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_922(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_923) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_923(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_923(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_924) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_924(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_924(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_925) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_925(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_925(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_926) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_926(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_926(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_927) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_927(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_927(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_928) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_928(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_928(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_929) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_929(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_929(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_930) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_930(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_930(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_931) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_931(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_931(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_932) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_932(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_932(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_933) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_933(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_933(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_934) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_934(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_934(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_935) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_935(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_935(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_936) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_936(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_936(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_937) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_937(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_937(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_938) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_938(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_938(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_939) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_939(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_939(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_940) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_940(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_940(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_941) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_941(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_941(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_942) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_942(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_942(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_943) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_943(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_943(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_944) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_944(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_944(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_945) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_945(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_945(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_946) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_946(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_946(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_947) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_947(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_947(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_948) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_948(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_948(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_949) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_949(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_949(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_950) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_950(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_950(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_951) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_951(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_951(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_952) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_952(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_952(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_953) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_953(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_953(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_954) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_954(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_954(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_955) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_955(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_955(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_956) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_956(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_956(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_957) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_957(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_957(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_958) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_958(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_958(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_959) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_959(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_959(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_960) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_960(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_960(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_961) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_961(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_961(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_962) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_962(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_962(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_963) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_963(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_963(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_964) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_964(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_964(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_965) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_965(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_965(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_966) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_966(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_966(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_967) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_967(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_967(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_968) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_968(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_968(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_969) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_969(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_969(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_970) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_970(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_970(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_971) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_971(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_971(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_972) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_972(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_972(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_973) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_973(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_973(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_974) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_974(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_974(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_975) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_975(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_975(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_976) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_976(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_976(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_977) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_977(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_977(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_978) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_978(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_978(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_979) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_979(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_979(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_980) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_980(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_980(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_981) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_981(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_981(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_982) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_982(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_982(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_983) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_983(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_983(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_984) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_984(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_984(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_985) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_985(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_985(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_986) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_986(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_986(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_987) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_987(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_987(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_988) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_988(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_988(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_989) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_989(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_989(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_990) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_990(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_990(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_991) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_991(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_991(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_992) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_992(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_992(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_993) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_993(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_993(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_994) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_994(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_994(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_995) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_995(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_995(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_996) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_996(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_996(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_997) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_997(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_997(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_998) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_998(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_998(FUNC)\n#endif\n\n#if defined(EIGEN_TEST_PART_999) || defined(EIGEN_TEST_PART_ALL)\n#define CALL_SUBTEST_999(FUNC) CALL_SUBTEST(FUNC)\n#else\n#define CALL_SUBTEST_999(FUNC)\n#endif\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/spqr_support.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Desire Nuentsa Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n\n#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS\n#include \"sparse.h\"\n#include <Eigen/SPQRSupport>\n\n\ntemplate<typename MatrixType,typename DenseMat>\nint generate_sparse_rectangular_problem(MatrixType& A, DenseMat& dA, int maxRows = 300, int maxCols = 300)\n{\n  eigen_assert(maxRows >= maxCols);\n  typedef typename MatrixType::Scalar Scalar;\n  int rows = internal::random<int>(1,maxRows);\n  int cols = internal::random<int>(1,rows);\n  double density = (std::max)(8./(rows*cols), 0.01);\n  \n  A.resize(rows,cols);\n  dA.resize(rows,cols);\n  initSparse<Scalar>(density, dA, A,ForceNonZeroDiag);\n  A.makeCompressed();\n  return rows;\n}\n\ntemplate<typename Scalar> void test_spqr_scalar()\n{\n  typedef SparseMatrix<Scalar,ColMajor> MatrixType; \n  MatrixType A;\n  Matrix<Scalar,Dynamic,Dynamic> dA;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n  DenseVector refX,x,b; \n  SPQR<MatrixType> solver; \n  generate_sparse_rectangular_problem(A,dA);\n  \n  Index m = A.rows();\n  b = DenseVector::Random(m);\n  solver.compute(A);\n  if (solver.info() != Success)\n  {\n    std::cerr << \"sparse QR factorization failed\\n\";\n    exit(0);\n    return;\n  }\n  x = solver.solve(b);\n  if (solver.info() != Success)\n  {\n    std::cerr << \"sparse QR factorization failed\\n\";\n    exit(0);\n    return;\n  }  \n  //Compare with a dense solver\n  refX = dA.colPivHouseholderQr().solve(b);\n  VERIFY(x.isApprox(refX,test_precision<Scalar>()));\n}\nEIGEN_DECLARE_TEST(spqr_support)\n{\n  CALL_SUBTEST_1(test_spqr_scalar<double>());\n  CALL_SUBTEST_2(test_spqr_scalar<std::complex<double> >());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/stable_norm.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename T> EIGEN_DONT_INLINE T copy(const T& x)\n{\n  return x;\n}\n\ntemplate<typename MatrixType> void stable_norm(const MatrixType& m)\n{\n  /* this test covers the following files:\n     StableNorm.h\n  */\n  using std::sqrt;\n  using std::abs;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  \n  bool complex_real_product_ok = true;\n\n  // Check the basic machine-dependent constants.\n  {\n    int ibeta, it, iemin, iemax;\n\n    ibeta = std::numeric_limits<RealScalar>::radix;         // base for floating-point numbers\n    it    = std::numeric_limits<RealScalar>::digits;        // number of base-beta digits in mantissa\n    iemin = std::numeric_limits<RealScalar>::min_exponent;  // minimum exponent\n    iemax = std::numeric_limits<RealScalar>::max_exponent;  // maximum exponent\n\n    VERIFY( (!(iemin > 1 - 2*it || 1+it>iemax || (it==2 && ibeta<5) || (it<=4 && ibeta <= 3 ) || it<2))\n           && \"the stable norm algorithm cannot be guaranteed on this computer\");\n    \n    Scalar inf = std::numeric_limits<RealScalar>::infinity();\n    if(NumTraits<Scalar>::IsComplex && (numext::isnan)(inf*RealScalar(1)) )\n    {\n      complex_real_product_ok = false;\n      static bool first = true;\n      if(first)\n        std::cerr << \"WARNING: compiler mess up complex*real product, \" << inf << \" * \" << 1.0 << \" = \" << inf*RealScalar(1) << std::endl;\n      first = false;\n    }\n  }\n\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  // get a non-zero random factor\n  Scalar factor = internal::random<Scalar>();\n  while(numext::abs2(factor)<RealScalar(1e-4))\n    factor = internal::random<Scalar>();\n  Scalar big = factor * ((std::numeric_limits<RealScalar>::max)() * RealScalar(1e-4));\n  \n  factor = internal::random<Scalar>();\n  while(numext::abs2(factor)<RealScalar(1e-4))\n    factor = internal::random<Scalar>();\n  Scalar small = factor * ((std::numeric_limits<RealScalar>::min)() * RealScalar(1e4));\n\n  Scalar one(1);\n\n  MatrixType  vzero = MatrixType::Zero(rows, cols),\n              vrand = MatrixType::Random(rows, cols),\n              vbig(rows, cols),\n              vsmall(rows,cols);\n\n  vbig.fill(big);\n  vsmall.fill(small);\n\n  VERIFY_IS_MUCH_SMALLER_THAN(vzero.norm(), static_cast<RealScalar>(1));\n  VERIFY_IS_APPROX(vrand.stableNorm(),      vrand.norm());\n  VERIFY_IS_APPROX(vrand.blueNorm(),        vrand.norm());\n  VERIFY_IS_APPROX(vrand.hypotNorm(),       vrand.norm());\n\n  // test with expressions as input\n  VERIFY_IS_APPROX((one*vrand).stableNorm(),      vrand.norm());\n  VERIFY_IS_APPROX((one*vrand).blueNorm(),        vrand.norm());\n  VERIFY_IS_APPROX((one*vrand).hypotNorm(),       vrand.norm());\n  VERIFY_IS_APPROX((one*vrand+one*vrand-one*vrand).stableNorm(),      vrand.norm());\n  VERIFY_IS_APPROX((one*vrand+one*vrand-one*vrand).blueNorm(),        vrand.norm());\n  VERIFY_IS_APPROX((one*vrand+one*vrand-one*vrand).hypotNorm(),       vrand.norm());\n\n  RealScalar size = static_cast<RealScalar>(m.size());\n\n  // test numext::isfinite\n  VERIFY(!(numext::isfinite)( std::numeric_limits<RealScalar>::infinity()));\n  VERIFY(!(numext::isfinite)(sqrt(-abs(big))));\n\n  // test overflow\n  VERIFY((numext::isfinite)(sqrt(size)*abs(big)));\n  VERIFY_IS_NOT_APPROX(sqrt(copy(vbig.squaredNorm())), abs(sqrt(size)*big)); // here the default norm must fail\n  VERIFY_IS_APPROX(vbig.stableNorm(), sqrt(size)*abs(big));\n  VERIFY_IS_APPROX(vbig.blueNorm(),   sqrt(size)*abs(big));\n  VERIFY_IS_APPROX(vbig.hypotNorm(),  sqrt(size)*abs(big));\n\n  // test underflow\n  VERIFY((numext::isfinite)(sqrt(size)*abs(small)));\n  VERIFY_IS_NOT_APPROX(sqrt(copy(vsmall.squaredNorm())),   abs(sqrt(size)*small)); // here the default norm must fail\n  VERIFY_IS_APPROX(vsmall.stableNorm(), sqrt(size)*abs(small));\n  VERIFY_IS_APPROX(vsmall.blueNorm(),   sqrt(size)*abs(small));\n  VERIFY_IS_APPROX(vsmall.hypotNorm(),  sqrt(size)*abs(small));\n\n  // Test compilation of cwise() version\n  VERIFY_IS_APPROX(vrand.colwise().stableNorm(),      vrand.colwise().norm());\n  VERIFY_IS_APPROX(vrand.colwise().blueNorm(),        vrand.colwise().norm());\n  VERIFY_IS_APPROX(vrand.colwise().hypotNorm(),       vrand.colwise().norm());\n  VERIFY_IS_APPROX(vrand.rowwise().stableNorm(),      vrand.rowwise().norm());\n  VERIFY_IS_APPROX(vrand.rowwise().blueNorm(),        vrand.rowwise().norm());\n  VERIFY_IS_APPROX(vrand.rowwise().hypotNorm(),       vrand.rowwise().norm());\n  \n  // test NaN, +inf, -inf \n  MatrixType v;\n  Index i = internal::random<Index>(0,rows-1);\n  Index j = internal::random<Index>(0,cols-1);\n\n  // NaN\n  {\n    v = vrand;\n    v(i,j) = std::numeric_limits<RealScalar>::quiet_NaN();\n    VERIFY(!(numext::isfinite)(v.squaredNorm()));   VERIFY((numext::isnan)(v.squaredNorm()));\n    VERIFY(!(numext::isfinite)(v.norm()));          VERIFY((numext::isnan)(v.norm()));\n    VERIFY(!(numext::isfinite)(v.stableNorm()));    VERIFY((numext::isnan)(v.stableNorm()));\n    VERIFY(!(numext::isfinite)(v.blueNorm()));      VERIFY((numext::isnan)(v.blueNorm()));\n    VERIFY(!(numext::isfinite)(v.hypotNorm()));     VERIFY((numext::isnan)(v.hypotNorm()));\n  }\n  \n  // +inf\n  {\n    v = vrand;\n    v(i,j) = std::numeric_limits<RealScalar>::infinity();\n    VERIFY(!(numext::isfinite)(v.squaredNorm()));   VERIFY(isPlusInf(v.squaredNorm()));\n    VERIFY(!(numext::isfinite)(v.norm()));          VERIFY(isPlusInf(v.norm()));\n    VERIFY(!(numext::isfinite)(v.stableNorm()));\n    if(complex_real_product_ok){\n      VERIFY(isPlusInf(v.stableNorm()));\n    }\n    VERIFY(!(numext::isfinite)(v.blueNorm()));      VERIFY(isPlusInf(v.blueNorm()));\n    VERIFY(!(numext::isfinite)(v.hypotNorm()));     VERIFY(isPlusInf(v.hypotNorm()));\n  }\n  \n  // -inf\n  {\n    v = vrand;\n    v(i,j) = -std::numeric_limits<RealScalar>::infinity();\n    VERIFY(!(numext::isfinite)(v.squaredNorm()));   VERIFY(isPlusInf(v.squaredNorm()));\n    VERIFY(!(numext::isfinite)(v.norm()));          VERIFY(isPlusInf(v.norm()));\n    VERIFY(!(numext::isfinite)(v.stableNorm()));\n    if(complex_real_product_ok) {\n      VERIFY(isPlusInf(v.stableNorm()));\n    }\n    VERIFY(!(numext::isfinite)(v.blueNorm()));      VERIFY(isPlusInf(v.blueNorm()));\n    VERIFY(!(numext::isfinite)(v.hypotNorm()));     VERIFY(isPlusInf(v.hypotNorm()));\n  }\n  \n  // mix\n  {\n    Index i2 = internal::random<Index>(0,rows-1);\n    Index j2 = internal::random<Index>(0,cols-1);\n    v = vrand;\n    v(i,j) = -std::numeric_limits<RealScalar>::infinity();\n    v(i2,j2) = std::numeric_limits<RealScalar>::quiet_NaN();\n    VERIFY(!(numext::isfinite)(v.squaredNorm()));   VERIFY((numext::isnan)(v.squaredNorm()));\n    VERIFY(!(numext::isfinite)(v.norm()));          VERIFY((numext::isnan)(v.norm()));\n    VERIFY(!(numext::isfinite)(v.stableNorm()));    VERIFY((numext::isnan)(v.stableNorm()));\n    VERIFY(!(numext::isfinite)(v.blueNorm()));      VERIFY((numext::isnan)(v.blueNorm()));\n    if (i2 != i || j2 != j) {\n      // hypot propagates inf over NaN.\n      VERIFY(!(numext::isfinite)(v.hypotNorm()));     VERIFY((numext::isinf)(v.hypotNorm()));\n    } else {\n      // inf is overwritten by NaN, expect norm to be NaN.\n      VERIFY(!(numext::isfinite)(v.hypotNorm()));     VERIFY((numext::isnan)(v.hypotNorm()));\n    }\n  }\n\n  // stableNormalize[d]\n  {\n    VERIFY_IS_APPROX(vrand.stableNormalized(), vrand.normalized());\n    MatrixType vcopy(vrand);\n    vcopy.stableNormalize();\n    VERIFY_IS_APPROX(vcopy, vrand.normalized());\n    VERIFY_IS_APPROX((vrand.stableNormalized()).norm(), RealScalar(1));\n    VERIFY_IS_APPROX(vcopy.norm(), RealScalar(1));\n    VERIFY_IS_APPROX((vbig.stableNormalized()).norm(), RealScalar(1));\n    VERIFY_IS_APPROX((vsmall.stableNormalized()).norm(), RealScalar(1));\n    RealScalar big_scaling = ((std::numeric_limits<RealScalar>::max)() * RealScalar(1e-4));\n    VERIFY_IS_APPROX(vbig/big_scaling, (vbig.stableNorm() * vbig.stableNormalized()).eval()/big_scaling);\n    VERIFY_IS_APPROX(vsmall, vsmall.stableNorm() * vsmall.stableNormalized());\n  }\n}\n\ntemplate<typename Scalar>\nvoid test_hypot()\n{\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  Scalar factor = internal::random<Scalar>();\n  while(numext::abs2(factor)<RealScalar(1e-4))\n    factor = internal::random<Scalar>();\n  Scalar big = factor * ((std::numeric_limits<RealScalar>::max)() * RealScalar(1e-4));\n  \n  factor = internal::random<Scalar>();\n  while(numext::abs2(factor)<RealScalar(1e-4))\n    factor = internal::random<Scalar>();\n  Scalar small = factor * ((std::numeric_limits<RealScalar>::min)() * RealScalar(1e4));\n\n  Scalar  one   (1),\n          zero  (0),\n          sqrt2 (std::sqrt(2)),\n          nan   (std::numeric_limits<RealScalar>::quiet_NaN());\n\n  Scalar a = internal::random<Scalar>(-1,1);\n  Scalar b = internal::random<Scalar>(-1,1);\n  VERIFY_IS_APPROX(numext::hypot(a,b),std::sqrt(numext::abs2(a)+numext::abs2(b)));\n  VERIFY_IS_EQUAL(numext::hypot(zero,zero), zero);\n  VERIFY_IS_APPROX(numext::hypot(one, one), sqrt2);\n  VERIFY_IS_APPROX(numext::hypot(big,big), sqrt2*numext::abs(big));\n  VERIFY_IS_APPROX(numext::hypot(small,small), sqrt2*numext::abs(small));\n  VERIFY_IS_APPROX(numext::hypot(small,big), numext::abs(big));\n  VERIFY((numext::isnan)(numext::hypot(nan,a)));\n  VERIFY((numext::isnan)(numext::hypot(a,nan)));\n}\n\nEIGEN_DECLARE_TEST(stable_norm)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_3( test_hypot<double>() );\n    CALL_SUBTEST_4( test_hypot<float>() );\n    CALL_SUBTEST_5( test_hypot<std::complex<double> >() );\n    CALL_SUBTEST_6( test_hypot<std::complex<float> >() );\n\n    CALL_SUBTEST_1( stable_norm(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( stable_norm(Vector4d()) );\n    CALL_SUBTEST_3( stable_norm(VectorXd(internal::random<int>(10,2000))) );\n    CALL_SUBTEST_3( stable_norm(MatrixXd(internal::random<int>(10,200), internal::random<int>(10,200))) );\n    CALL_SUBTEST_4( stable_norm(VectorXf(internal::random<int>(10,2000))) );\n    CALL_SUBTEST_5( stable_norm(VectorXcd(internal::random<int>(10,2000))) );\n    CALL_SUBTEST_6( stable_norm(VectorXcf(internal::random<int>(10,2000))) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/stddeque.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2010 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/StdDeque>\n#include <Eigen/Geometry>\n\ntemplate<typename MatrixType>\nvoid check_stddeque_matrix(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n  MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols);\n  std::deque<MatrixType,Eigen::aligned_allocator<MatrixType> > v(10, MatrixType::Zero(rows,cols)), w(20, y);\n  v.front() = x;\n  w.front() = w.back();\n  VERIFY_IS_APPROX(w.front(), w.back());\n  v = w;\n\n  typename std::deque<MatrixType,Eigen::aligned_allocator<MatrixType> >::iterator vi = v.begin();\n  typename std::deque<MatrixType,Eigen::aligned_allocator<MatrixType> >::iterator wi = w.begin();\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(*vi, *wi);\n    ++vi;\n    ++wi;\n  }\n\n  v.resize(21,MatrixType::Zero(rows,cols));  \n  v.back() = x;\n  VERIFY_IS_APPROX(v.back(), x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v.back(), y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v.back(), x);\n}\n\ntemplate<typename TransformType>\nvoid check_stddeque_transform(const TransformType&)\n{\n  typedef typename TransformType::MatrixType MatrixType;\n  TransformType x(MatrixType::Random()), y(MatrixType::Random()), ti=TransformType::Identity();\n  std::deque<TransformType,Eigen::aligned_allocator<TransformType> > v(10,ti), w(20, y);\n  v.front() = x;\n  w.front() = w.back();\n  VERIFY_IS_APPROX(w.front(), w.back());\n  v = w;\n\n  typename std::deque<TransformType,Eigen::aligned_allocator<TransformType> >::iterator vi = v.begin();\n  typename std::deque<TransformType,Eigen::aligned_allocator<TransformType> >::iterator wi = w.begin();\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(*vi, *wi);\n    ++vi;\n    ++wi;\n  }\n\n  v.resize(21,ti);\n  v.back() = x;\n  VERIFY_IS_APPROX(v.back(), x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v.back(), y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v.back(), x);\n}\n\ntemplate<typename QuaternionType>\nvoid check_stddeque_quaternion(const QuaternionType&)\n{\n  typedef typename QuaternionType::Coefficients Coefficients;\n  QuaternionType x(Coefficients::Random()), y(Coefficients::Random()), qi=QuaternionType::Identity();\n  std::deque<QuaternionType,Eigen::aligned_allocator<QuaternionType> > v(10,qi), w(20, y);\n  v.front() = x;\n  w.front() = w.back();\n  VERIFY_IS_APPROX(w.front(), w.back());\n  v = w;\n\n  typename std::deque<QuaternionType,Eigen::aligned_allocator<QuaternionType> >::iterator vi = v.begin();\n  typename std::deque<QuaternionType,Eigen::aligned_allocator<QuaternionType> >::iterator wi = w.begin();\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(*vi, *wi);\n    ++vi;\n    ++wi;\n  }\n\n  v.resize(21,qi);\n  v.back() = x;\n  VERIFY_IS_APPROX(v.back(), x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v.back(), y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v.back(), x);\n}\n\nEIGEN_DECLARE_TEST(stddeque)\n{\n  // some non vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stddeque_matrix(Vector2f()));\n  CALL_SUBTEST_1(check_stddeque_matrix(Matrix3f()));\n  CALL_SUBTEST_2(check_stddeque_matrix(Matrix3d()));\n\n  // some vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stddeque_matrix(Matrix2f()));\n  CALL_SUBTEST_1(check_stddeque_matrix(Vector4f()));\n  CALL_SUBTEST_1(check_stddeque_matrix(Matrix4f()));\n  CALL_SUBTEST_2(check_stddeque_matrix(Matrix4d()));\n\n  // some dynamic sizes\n  CALL_SUBTEST_3(check_stddeque_matrix(MatrixXd(1,1)));\n  CALL_SUBTEST_3(check_stddeque_matrix(VectorXd(20)));\n  CALL_SUBTEST_3(check_stddeque_matrix(RowVectorXf(20)));\n  CALL_SUBTEST_3(check_stddeque_matrix(MatrixXcf(10,10)));\n\n  // some Transform\n  CALL_SUBTEST_4(check_stddeque_transform(Affine2f()));\n  CALL_SUBTEST_4(check_stddeque_transform(Affine3f()));\n  CALL_SUBTEST_4(check_stddeque_transform(Affine3d()));\n\n  // some Quaternion\n  CALL_SUBTEST_5(check_stddeque_quaternion(Quaternionf()));\n  CALL_SUBTEST_5(check_stddeque_quaternion(Quaterniond()));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/stddeque_overload.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2010 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/StdDeque>\n#include <Eigen/Geometry>\n\nEIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Vector4f)\n\nEIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Matrix2f)\nEIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Matrix4f)\nEIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Matrix4d)\n\nEIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Affine3f)\nEIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Affine3d)\n\nEIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Quaternionf)\nEIGEN_DEFINE_STL_DEQUE_SPECIALIZATION(Quaterniond)\n\ntemplate<typename MatrixType>\nvoid check_stddeque_matrix(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n  MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols);\n  std::deque<MatrixType> v(10, MatrixType::Zero(rows,cols)), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n\n  // do a lot of push_back such that the deque gets internally resized\n  // (with memory reallocation)\n  MatrixType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(v[i]==w[(i-23)%w.size()]);\n  }\n}\n\ntemplate<typename TransformType>\nvoid check_stddeque_transform(const TransformType&)\n{\n  typedef typename TransformType::MatrixType MatrixType;\n  TransformType x(MatrixType::Random()), y(MatrixType::Random()), ti=TransformType::Identity();\n  std::deque<TransformType> v(10,ti), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21,ti);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n\n  // do a lot of push_back such that the deque gets internally resized\n  // (with memory reallocation)\n  TransformType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(v[i].matrix()==w[(i-23)%w.size()].matrix());\n  }\n}\n\ntemplate<typename QuaternionType>\nvoid check_stddeque_quaternion(const QuaternionType&)\n{\n  typedef typename QuaternionType::Coefficients Coefficients;\n  QuaternionType x(Coefficients::Random()), y(Coefficients::Random()), qi=QuaternionType::Identity();\n  std::deque<QuaternionType> v(10,qi), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21,qi);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n\n  // do a lot of push_back such that the deque gets internally resized\n  // (with memory reallocation)\n  QuaternionType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(v[i].coeffs()==w[(i-23)%w.size()].coeffs());\n  }\n}\n\nEIGEN_DECLARE_TEST(stddeque_overload)\n{\n  // some non vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stddeque_matrix(Vector2f()));\n  CALL_SUBTEST_1(check_stddeque_matrix(Matrix3f()));\n  CALL_SUBTEST_2(check_stddeque_matrix(Matrix3d()));\n\n  // some vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stddeque_matrix(Matrix2f()));\n  CALL_SUBTEST_1(check_stddeque_matrix(Vector4f()));\n  CALL_SUBTEST_1(check_stddeque_matrix(Matrix4f()));\n  CALL_SUBTEST_2(check_stddeque_matrix(Matrix4d()));\n\n  // some dynamic sizes\n  CALL_SUBTEST_3(check_stddeque_matrix(MatrixXd(1,1)));\n  CALL_SUBTEST_3(check_stddeque_matrix(VectorXd(20)));\n  CALL_SUBTEST_3(check_stddeque_matrix(RowVectorXf(20)));\n  CALL_SUBTEST_3(check_stddeque_matrix(MatrixXcf(10,10)));\n\n  // some Transform\n  CALL_SUBTEST_4(check_stddeque_transform(Affine2f())); // does not need the specialization (2+1)^2 = 9\n  CALL_SUBTEST_4(check_stddeque_transform(Affine3f()));\n  CALL_SUBTEST_4(check_stddeque_transform(Affine3d()));\n\n  // some Quaternion\n  CALL_SUBTEST_5(check_stddeque_quaternion(Quaternionf()));\n  CALL_SUBTEST_5(check_stddeque_quaternion(Quaterniond()));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/stdlist.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2010 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/StdList>\n#include <Eigen/Geometry>\n\ntemplate<typename MatrixType>\nvoid check_stdlist_matrix(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n  MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols);\n  std::list<MatrixType,Eigen::aligned_allocator<MatrixType> > v(10, MatrixType::Zero(rows,cols)), w(20, y);\n  v.front() = x;\n  w.front() = w.back();\n  VERIFY_IS_APPROX(w.front(), w.back());\n  v = w;\n\n  typename std::list<MatrixType,Eigen::aligned_allocator<MatrixType> >::iterator vi = v.begin();\n  typename std::list<MatrixType,Eigen::aligned_allocator<MatrixType> >::iterator wi = w.begin();\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(*vi, *wi);\n    ++vi;\n    ++wi;\n  }\n\n  v.resize(21, MatrixType::Zero(rows,cols));  \n  v.back() = x;\n  VERIFY_IS_APPROX(v.back(), x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v.back(), y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v.back(), x);\n}\n\ntemplate<typename TransformType>\nvoid check_stdlist_transform(const TransformType&)\n{\n  typedef typename TransformType::MatrixType MatrixType;\n  TransformType x(MatrixType::Random()), y(MatrixType::Random()), ti=TransformType::Identity();\n  std::list<TransformType,Eigen::aligned_allocator<TransformType> > v(10,ti), w(20, y);\n  v.front() = x;\n  w.front() = w.back();\n  VERIFY_IS_APPROX(w.front(), w.back());\n  v = w;\n\n  typename std::list<TransformType,Eigen::aligned_allocator<TransformType> >::iterator vi = v.begin();\n  typename std::list<TransformType,Eigen::aligned_allocator<TransformType> >::iterator wi = w.begin();\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(*vi, *wi);\n    ++vi;\n    ++wi;\n  }\n\n  v.resize(21, ti);\n  v.back() = x;\n  VERIFY_IS_APPROX(v.back(), x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v.back(), y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v.back(), x);\n}\n\ntemplate<typename QuaternionType>\nvoid check_stdlist_quaternion(const QuaternionType&)\n{\n  typedef typename QuaternionType::Coefficients Coefficients;\n  QuaternionType x(Coefficients::Random()), y(Coefficients::Random()), qi=QuaternionType::Identity();\n  std::list<QuaternionType,Eigen::aligned_allocator<QuaternionType> > v(10,qi), w(20, y);\n  v.front() = x;\n  w.front() = w.back();\n  VERIFY_IS_APPROX(w.front(), w.back());\n  v = w;\n\n  typename std::list<QuaternionType,Eigen::aligned_allocator<QuaternionType> >::iterator vi = v.begin();\n  typename std::list<QuaternionType,Eigen::aligned_allocator<QuaternionType> >::iterator wi = w.begin();\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(*vi, *wi);\n    ++vi;\n    ++wi;\n  }\n\n  v.resize(21,qi);\n  v.back() = x;\n  VERIFY_IS_APPROX(v.back(), x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v.back(), y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v.back(), x);\n}\n\nEIGEN_DECLARE_TEST(stdlist)\n{\n  // some non vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stdlist_matrix(Vector2f()));\n  CALL_SUBTEST_1(check_stdlist_matrix(Matrix3f()));\n  CALL_SUBTEST_2(check_stdlist_matrix(Matrix3d()));\n\n  // some vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stdlist_matrix(Matrix2f()));\n  CALL_SUBTEST_1(check_stdlist_matrix(Vector4f()));\n  CALL_SUBTEST_1(check_stdlist_matrix(Matrix4f()));\n  CALL_SUBTEST_2(check_stdlist_matrix(Matrix4d()));\n\n  // some dynamic sizes\n  CALL_SUBTEST_3(check_stdlist_matrix(MatrixXd(1,1)));\n  CALL_SUBTEST_3(check_stdlist_matrix(VectorXd(20)));\n  CALL_SUBTEST_3(check_stdlist_matrix(RowVectorXf(20)));\n  CALL_SUBTEST_3(check_stdlist_matrix(MatrixXcf(10,10)));\n\n  // some Transform\n  CALL_SUBTEST_4(check_stdlist_transform(Affine2f()));\n  CALL_SUBTEST_4(check_stdlist_transform(Affine3f()));\n  CALL_SUBTEST_4(check_stdlist_transform(Affine3d()));\n\n  // some Quaternion\n  CALL_SUBTEST_5(check_stdlist_quaternion(Quaternionf()));\n  CALL_SUBTEST_5(check_stdlist_quaternion(Quaterniond()));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/stdlist_overload.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2010 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/StdList>\n#include <Eigen/Geometry>\n\nEIGEN_DEFINE_STL_LIST_SPECIALIZATION(Vector4f)\n\nEIGEN_DEFINE_STL_LIST_SPECIALIZATION(Matrix2f)\nEIGEN_DEFINE_STL_LIST_SPECIALIZATION(Matrix4f)\nEIGEN_DEFINE_STL_LIST_SPECIALIZATION(Matrix4d)\n\nEIGEN_DEFINE_STL_LIST_SPECIALIZATION(Affine3f)\nEIGEN_DEFINE_STL_LIST_SPECIALIZATION(Affine3d)\n\nEIGEN_DEFINE_STL_LIST_SPECIALIZATION(Quaternionf)\nEIGEN_DEFINE_STL_LIST_SPECIALIZATION(Quaterniond)\n\ntemplate <class Container, class Position>\ntypename Container::iterator get(Container & c, Position position)\n{\n  typename Container::iterator it = c.begin();\n  std::advance(it, position);\n  return it;\n}\n\ntemplate <class Container, class Position, class Value>\nvoid set(Container & c, Position position, const Value & value)\n{\n  typename Container::iterator it = c.begin();\n  std::advance(it, position);\n  *it = value;\n}\n\ntemplate<typename MatrixType>\nvoid check_stdlist_matrix(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n  MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols);\n  std::list<MatrixType> v(10, MatrixType::Zero(rows,cols)), w(20, y);\n  typename std::list<MatrixType>::iterator itv = get(v, 5);\n  typename std::list<MatrixType>::iterator itw = get(w, 6);\n  *itv = x;\n  *itw = *itv;\n  VERIFY_IS_APPROX(*itw, *itv);\n  v = w;\n  itv = v.begin();\n  itw = w.begin();\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(*itw, *itv);\n    ++itv;\n    ++itw;\n  }\n\n  v.resize(21);\n  set(v, 20, x);\n  VERIFY_IS_APPROX(*get(v, 20), x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(*get(v, 21), y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(*get(v, 22), x);\n\n  // do a lot of push_back such that the list gets internally resized\n  // (with memory reallocation)\n  MatrixType* ref = &(*get(w, 0));\n  for(int i=0; i<30 || ((ref==&(*get(w, 0))) && i<300); ++i)\n    v.push_back(*get(w, i%w.size()));\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY((*get(v, i))==(*get(w, (i-23)%w.size())));\n  }\n}\n\ntemplate<typename TransformType>\nvoid check_stdlist_transform(const TransformType&)\n{\n  typedef typename TransformType::MatrixType MatrixType;\n  TransformType x(MatrixType::Random()), y(MatrixType::Random()), ti=TransformType::Identity();\n  std::list<TransformType> v(10,ti), w(20, y);\n  typename std::list<TransformType>::iterator itv = get(v, 5);\n  typename std::list<TransformType>::iterator itw = get(w, 6);\n  *itv = x;\n  *itw = *itv;\n  VERIFY_IS_APPROX(*itw, *itv);\n  v = w;\n  itv = v.begin();\n  itw = w.begin();\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(*itw, *itv);\n    ++itv;\n    ++itw;\n  }\n\n  v.resize(21, ti);\n  set(v, 20, x);\n  VERIFY_IS_APPROX(*get(v, 20), x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(*get(v, 21), y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(*get(v, 22), x);\n\n  // do a lot of push_back such that the list gets internally resized\n  // (with memory reallocation)\n  TransformType* ref = &(*get(w, 0));\n  for(int i=0; i<30 || ((ref==&(*get(w, 0))) && i<300); ++i)\n    v.push_back(*get(w, i%w.size()));\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(get(v, i)->matrix()==get(w, (i-23)%w.size())->matrix());\n  }\n}\n\ntemplate<typename QuaternionType>\nvoid check_stdlist_quaternion(const QuaternionType&)\n{\n  typedef typename QuaternionType::Coefficients Coefficients;\n  QuaternionType x(Coefficients::Random()), y(Coefficients::Random()), qi=QuaternionType::Identity();\n  std::list<QuaternionType> v(10,qi), w(20, y);\n  typename std::list<QuaternionType>::iterator itv = get(v, 5);\n  typename std::list<QuaternionType>::iterator itw = get(w, 6);\n  *itv = x;\n  *itw = *itv;\n  VERIFY_IS_APPROX(*itw, *itv);\n  v = w;\n  itv = v.begin();\n  itw = w.begin();\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(*itw, *itv);\n    ++itv;\n    ++itw;\n  }\n\n  v.resize(21,qi);\n  set(v, 20, x);\n  VERIFY_IS_APPROX(*get(v, 20), x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(*get(v, 21), y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(*get(v, 22), x);\n\n  // do a lot of push_back such that the list gets internally resized\n  // (with memory reallocation)\n  QuaternionType* ref = &(*get(w, 0));\n  for(int i=0; i<30 || ((ref==&(*get(w, 0))) && i<300); ++i)\n    v.push_back(*get(w, i%w.size()));\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(get(v, i)->coeffs()==get(w, (i-23)%w.size())->coeffs());\n  }\n}\n\nEIGEN_DECLARE_TEST(stdlist_overload)\n{\n  // some non vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stdlist_matrix(Vector2f()));\n  CALL_SUBTEST_1(check_stdlist_matrix(Matrix3f()));\n  CALL_SUBTEST_2(check_stdlist_matrix(Matrix3d()));\n\n  // some vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stdlist_matrix(Matrix2f()));\n  CALL_SUBTEST_1(check_stdlist_matrix(Vector4f()));\n  CALL_SUBTEST_1(check_stdlist_matrix(Matrix4f()));\n  CALL_SUBTEST_2(check_stdlist_matrix(Matrix4d()));\n\n  // some dynamic sizes\n  CALL_SUBTEST_3(check_stdlist_matrix(MatrixXd(1,1)));\n  CALL_SUBTEST_3(check_stdlist_matrix(VectorXd(20)));\n  CALL_SUBTEST_3(check_stdlist_matrix(RowVectorXf(20)));\n  CALL_SUBTEST_3(check_stdlist_matrix(MatrixXcf(10,10)));\n\n  // some Transform\n  CALL_SUBTEST_4(check_stdlist_transform(Affine2f())); // does not need the specialization (2+1)^2 = 9\n  CALL_SUBTEST_4(check_stdlist_transform(Affine3f()));\n  CALL_SUBTEST_4(check_stdlist_transform(Affine3d()));\n\n  // some Quaternion\n  CALL_SUBTEST_5(check_stdlist_quaternion(Quaternionf()));\n  CALL_SUBTEST_5(check_stdlist_quaternion(Quaterniond()));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/stdvector.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/StdVector>\n#include <Eigen/Geometry>\n\ntemplate<typename MatrixType>\nvoid check_stdvector_matrix(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n  MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols);\n  std::vector<MatrixType,Eigen::aligned_allocator<MatrixType> > v(10, MatrixType::Zero(rows,cols)), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n  VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(MatrixType));\n\n  // do a lot of push_back such that the vector gets internally resized\n  // (with memory reallocation)\n  MatrixType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(v[i]==w[(i-23)%w.size()]);\n  }\n}\n\ntemplate<typename TransformType>\nvoid check_stdvector_transform(const TransformType&)\n{\n  typedef typename TransformType::MatrixType MatrixType;\n  TransformType x(MatrixType::Random()), y(MatrixType::Random());\n  std::vector<TransformType,Eigen::aligned_allocator<TransformType> > v(10), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n  VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(TransformType));\n\n  // do a lot of push_back such that the vector gets internally resized\n  // (with memory reallocation)\n  TransformType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(v[i].matrix()==w[(i-23)%w.size()].matrix());\n  }\n}\n\ntemplate<typename QuaternionType>\nvoid check_stdvector_quaternion(const QuaternionType&)\n{\n  typedef typename QuaternionType::Coefficients Coefficients;\n  QuaternionType x(Coefficients::Random()), y(Coefficients::Random()), qi=QuaternionType::Identity();\n  std::vector<QuaternionType,Eigen::aligned_allocator<QuaternionType> > v(10,qi), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n  VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(QuaternionType));\n\n  // do a lot of push_back such that the vector gets internally resized\n  // (with memory reallocation)\n  QuaternionType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(v[i].coeffs()==w[(i-23)%w.size()].coeffs());\n  }\n}\n\n// the code below triggered an invalid warning with gcc >= 7\n// eigen/Eigen/src/Core/util/Memory.h:189:12: warning: argument 1 value '18446744073709551612' exceeds maximum object size 9223372036854775807\n// This has been reported to gcc there: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=87544\nvoid std_vector_gcc_warning()\n{\n  typedef Eigen::Vector3f T;\n  std::vector<T, Eigen::aligned_allocator<T> > v;\n  v.push_back(T());\n}\n\nEIGEN_DECLARE_TEST(stdvector)\n{\n  // some non vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stdvector_matrix(Vector2f()));\n  CALL_SUBTEST_1(check_stdvector_matrix(Matrix3f()));\n  CALL_SUBTEST_2(check_stdvector_matrix(Matrix3d()));\n\n  // some vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stdvector_matrix(Matrix2f()));\n  CALL_SUBTEST_1(check_stdvector_matrix(Vector4f()));\n  CALL_SUBTEST_1(check_stdvector_matrix(Matrix4f()));\n  CALL_SUBTEST_2(check_stdvector_matrix(Matrix4d()));\n\n  // some dynamic sizes\n  CALL_SUBTEST_3(check_stdvector_matrix(MatrixXd(1,1)));\n  CALL_SUBTEST_3(check_stdvector_matrix(VectorXd(20)));\n  CALL_SUBTEST_3(check_stdvector_matrix(RowVectorXf(20)));\n  CALL_SUBTEST_3(check_stdvector_matrix(MatrixXcf(10,10)));\n\n  // some Transform\n  CALL_SUBTEST_4(check_stdvector_transform(Projective2f()));\n  CALL_SUBTEST_4(check_stdvector_transform(Projective3f()));\n  CALL_SUBTEST_4(check_stdvector_transform(Projective3d()));\n  //CALL_SUBTEST(heck_stdvector_transform(Projective4d()));\n\n  // some Quaternion\n  CALL_SUBTEST_5(check_stdvector_quaternion(Quaternionf()));\n  CALL_SUBTEST_5(check_stdvector_quaternion(Quaterniond()));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/stdvector_overload.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2010 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/StdVector>\n#include <Eigen/Geometry>\n\nEIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Vector4f)\n\nEIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Matrix2f)\nEIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Matrix4f)\nEIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Matrix4d)\n\nEIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Affine3f)\nEIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Affine3d)\n\nEIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Quaternionf)\nEIGEN_DEFINE_STL_VECTOR_SPECIALIZATION(Quaterniond)\n\ntemplate<typename MatrixType>\nvoid check_stdvector_matrix(const MatrixType& m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n  MatrixType x = MatrixType::Random(rows,cols), y = MatrixType::Random(rows,cols);\n  std::vector<MatrixType> v(10, MatrixType::Zero(rows,cols)), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n  VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(MatrixType));\n\n  // do a lot of push_back such that the vector gets internally resized\n  // (with memory reallocation)\n  MatrixType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(v[i]==w[(i-23)%w.size()]);\n  }\n}\n\ntemplate<typename TransformType>\nvoid check_stdvector_transform(const TransformType&)\n{\n  typedef typename TransformType::MatrixType MatrixType;\n  TransformType x(MatrixType::Random()), y(MatrixType::Random());\n  std::vector<TransformType> v(10), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n  VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(TransformType));\n\n  // do a lot of push_back such that the vector gets internally resized\n  // (with memory reallocation)\n  TransformType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(v[i].matrix()==w[(i-23)%w.size()].matrix());\n  }\n}\n\ntemplate<typename QuaternionType>\nvoid check_stdvector_quaternion(const QuaternionType&)\n{\n  typedef typename QuaternionType::Coefficients Coefficients;\n  QuaternionType x(Coefficients::Random()), y(Coefficients::Random()), qi=QuaternionType::Identity();\n  std::vector<QuaternionType> v(10,qi), w(20, y);\n  v[5] = x;\n  w[6] = v[5];\n  VERIFY_IS_APPROX(w[6], v[5]);\n  v = w;\n  for(int i = 0; i < 20; i++)\n  {\n    VERIFY_IS_APPROX(w[i], v[i]);\n  }\n\n  v.resize(21);\n  v[20] = x;\n  VERIFY_IS_APPROX(v[20], x);\n  v.resize(22,y);\n  VERIFY_IS_APPROX(v[21], y);\n  v.push_back(x);\n  VERIFY_IS_APPROX(v[22], x);\n  VERIFY((internal::UIntPtr)&(v[22]) == (internal::UIntPtr)&(v[21]) + sizeof(QuaternionType));\n\n  // do a lot of push_back such that the vector gets internally resized\n  // (with memory reallocation)\n  QuaternionType* ref = &w[0];\n  for(int i=0; i<30 || ((ref==&w[0]) && i<300); ++i)\n    v.push_back(w[i%w.size()]);\n  for(unsigned int i=23; i<v.size(); ++i)\n  {\n    VERIFY(v[i].coeffs()==w[(i-23)%w.size()].coeffs());\n  }\n}\n\nEIGEN_DECLARE_TEST(stdvector_overload)\n{\n  // some non vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stdvector_matrix(Vector2f()));\n  CALL_SUBTEST_1(check_stdvector_matrix(Matrix3f()));\n  CALL_SUBTEST_2(check_stdvector_matrix(Matrix3d()));\n\n  // some vectorizable fixed sizes\n  CALL_SUBTEST_1(check_stdvector_matrix(Matrix2f()));\n  CALL_SUBTEST_1(check_stdvector_matrix(Vector4f()));\n  CALL_SUBTEST_1(check_stdvector_matrix(Matrix4f()));\n  CALL_SUBTEST_2(check_stdvector_matrix(Matrix4d()));\n\n  // some dynamic sizes\n  CALL_SUBTEST_3(check_stdvector_matrix(MatrixXd(1,1)));\n  CALL_SUBTEST_3(check_stdvector_matrix(VectorXd(20)));\n  CALL_SUBTEST_3(check_stdvector_matrix(RowVectorXf(20)));\n  CALL_SUBTEST_3(check_stdvector_matrix(MatrixXcf(10,10)));\n\n  // some Transform\n  CALL_SUBTEST_4(check_stdvector_transform(Affine2f())); // does not need the specialization (2+1)^2 = 9\n  CALL_SUBTEST_4(check_stdvector_transform(Affine3f()));\n  CALL_SUBTEST_4(check_stdvector_transform(Affine3d()));\n\n  // some Quaternion\n  CALL_SUBTEST_5(check_stdvector_quaternion(Quaternionf()));\n  CALL_SUBTEST_5(check_stdvector_quaternion(Quaterniond()));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/stl_iterators.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2018-2019 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <iterator>\n#include <numeric>\n#include \"main.h\"\n\ntemplate< class Iterator >\nstd::reverse_iterator<Iterator>\nmake_reverse_iterator( Iterator i )\n{\n  return std::reverse_iterator<Iterator>(i);\n}\n\n#if !EIGEN_HAS_CXX11\ntemplate<class ForwardIt>\nForwardIt is_sorted_until(ForwardIt firstIt, ForwardIt lastIt)\n{\n    if (firstIt != lastIt) {\n        ForwardIt next = firstIt;\n        while (++next != lastIt) {\n            if (*next < *firstIt)\n                return next;\n            firstIt = next;\n        }\n    }\n    return lastIt;\n}\ntemplate<class ForwardIt>\nbool is_sorted(ForwardIt firstIt, ForwardIt lastIt)\n{\n    return ::is_sorted_until(firstIt, lastIt) == lastIt;\n}\n#else\nusing std::is_sorted;\n#endif\n\ntemplate<typename XprType>\nbool is_pointer_based_stl_iterator(const internal::pointer_based_stl_iterator<XprType> &) { return true; }\n\ntemplate<typename XprType>\nbool is_generic_randaccess_stl_iterator(const internal::generic_randaccess_stl_iterator<XprType> &) { return true; }\n\ntemplate<typename Xpr>\nvoid check_begin_end_for_loop(Xpr xpr)\n{\n  const Xpr& cxpr(xpr);\n  Index i = 0;\n\n  i = 0;\n  for(typename Xpr::iterator it = xpr.begin(); it!=xpr.end(); ++it) { VERIFY_IS_EQUAL(*it,xpr[i++]); }\n\n  i = 0;\n  for(typename Xpr::const_iterator it = xpr.cbegin(); it!=xpr.cend(); ++it) { VERIFY_IS_EQUAL(*it,xpr[i++]); }\n\n  i = 0;\n  for(typename Xpr::const_iterator it = cxpr.begin(); it!=cxpr.end(); ++it) { VERIFY_IS_EQUAL(*it,xpr[i++]); }\n\n  i = 0;\n  for(typename Xpr::const_iterator it = xpr.begin(); it!=xpr.end(); ++it) { VERIFY_IS_EQUAL(*it,xpr[i++]); }\n\n  {\n    // simple API check\n    typename Xpr::const_iterator cit = xpr.begin();\n    cit = xpr.cbegin();\n\n    #if EIGEN_HAS_CXX11\n    auto tmp1 = xpr.begin();\n    VERIFY(tmp1==xpr.begin());\n    auto tmp2 = xpr.cbegin();\n    VERIFY(tmp2==xpr.cbegin());\n    #endif\n  }\n\n  VERIFY( xpr.end() -xpr.begin()  == xpr.size() );\n  VERIFY( xpr.cend()-xpr.begin()  == xpr.size() );\n  VERIFY( xpr.end() -xpr.cbegin() == xpr.size() );\n  VERIFY( xpr.cend()-xpr.cbegin() == xpr.size() );\n\n  if(xpr.size()>0) {\n    VERIFY(xpr.begin() != xpr.end());\n    VERIFY(xpr.begin() < xpr.end());\n    VERIFY(xpr.begin() <= xpr.end());\n    VERIFY(!(xpr.begin() == xpr.end()));\n    VERIFY(!(xpr.begin() > xpr.end()));\n    VERIFY(!(xpr.begin() >= xpr.end()));\n    \n    VERIFY(xpr.cbegin() != xpr.end());\n    VERIFY(xpr.cbegin() < xpr.end());\n    VERIFY(xpr.cbegin() <= xpr.end());\n    VERIFY(!(xpr.cbegin() == xpr.end()));\n    VERIFY(!(xpr.cbegin() > xpr.end()));\n    VERIFY(!(xpr.cbegin() >= xpr.end()));\n\n    VERIFY(xpr.begin() != xpr.cend());\n    VERIFY(xpr.begin() < xpr.cend());\n    VERIFY(xpr.begin() <= xpr.cend());\n    VERIFY(!(xpr.begin() == xpr.cend()));\n    VERIFY(!(xpr.begin() > xpr.cend()));\n    VERIFY(!(xpr.begin() >= xpr.cend()));\n  }\n}\n\ntemplate<typename Scalar, int Rows, int Cols>\nvoid test_stl_iterators(int rows=Rows, int cols=Cols)\n{\n  typedef Matrix<Scalar,Rows,1> VectorType;\n  #if EIGEN_HAS_CXX11\n  typedef Matrix<Scalar,1,Cols> RowVectorType;\n  #endif\n  typedef Matrix<Scalar,Rows,Cols,ColMajor> ColMatrixType;\n  typedef Matrix<Scalar,Rows,Cols,RowMajor> RowMatrixType;\n  VectorType v = VectorType::Random(rows);\n  const VectorType& cv(v);\n  ColMatrixType A = ColMatrixType::Random(rows,cols);\n  const ColMatrixType& cA(A);\n  RowMatrixType B = RowMatrixType::Random(rows,cols);\n  \n  Index i, j;\n\n  // Check we got a fast pointer-based iterator when expected\n  {\n    VERIFY( is_pointer_based_stl_iterator(v.begin()) );\n    VERIFY( is_pointer_based_stl_iterator(v.end()) );\n    VERIFY( is_pointer_based_stl_iterator(cv.begin()) );\n    VERIFY( is_pointer_based_stl_iterator(cv.end()) );\n\n    j = internal::random<Index>(0,A.cols()-1);\n    VERIFY( is_pointer_based_stl_iterator(A.col(j).begin()) );\n    VERIFY( is_pointer_based_stl_iterator(A.col(j).end()) );\n    VERIFY( is_pointer_based_stl_iterator(cA.col(j).begin()) );\n    VERIFY( is_pointer_based_stl_iterator(cA.col(j).end()) );\n\n    i = internal::random<Index>(0,A.rows()-1);\n    VERIFY( is_pointer_based_stl_iterator(A.row(i).begin()) );\n    VERIFY( is_pointer_based_stl_iterator(A.row(i).end()) );\n    VERIFY( is_pointer_based_stl_iterator(cA.row(i).begin()) );\n    VERIFY( is_pointer_based_stl_iterator(cA.row(i).end()) );\n\n    VERIFY( is_pointer_based_stl_iterator(A.reshaped().begin()) );\n    VERIFY( is_pointer_based_stl_iterator(A.reshaped().end()) );\n    VERIFY( is_pointer_based_stl_iterator(cA.reshaped().begin()) );\n    VERIFY( is_pointer_based_stl_iterator(cA.reshaped().end()) );\n\n    VERIFY( is_pointer_based_stl_iterator(B.template reshaped<AutoOrder>().begin()) );\n    VERIFY( is_pointer_based_stl_iterator(B.template reshaped<AutoOrder>().end()) );\n\n    VERIFY( is_generic_randaccess_stl_iterator(A.template reshaped<RowMajor>().begin()) );\n    VERIFY( is_generic_randaccess_stl_iterator(A.template reshaped<RowMajor>().end()) );\n  }\n\n  {\n    check_begin_end_for_loop(v);\n    check_begin_end_for_loop(A.col(internal::random<Index>(0,A.cols()-1)));\n    check_begin_end_for_loop(A.row(internal::random<Index>(0,A.rows()-1)));\n    check_begin_end_for_loop(v+v);\n  }\n\n#if EIGEN_HAS_CXX11\n  // check swappable\n  {\n    using std::swap;\n    // pointer-based\n    {\n      VectorType v_copy = v;\n      auto a = v.begin();\n      auto b = v.end()-1;\n      swap(a,b);\n      VERIFY_IS_EQUAL(v,v_copy);\n      VERIFY_IS_EQUAL(*b,*v.begin());\n      VERIFY_IS_EQUAL(*b,v(0));\n      VERIFY_IS_EQUAL(*a,v.end()[-1]);\n      VERIFY_IS_EQUAL(*a,v(last));\n    }\n\n    // generic\n    {\n      RowMatrixType B_copy = B;\n      auto Br = B.reshaped();\n      auto a = Br.begin();\n      auto b = Br.end()-1;\n      swap(a,b);\n      VERIFY_IS_EQUAL(B,B_copy);\n      VERIFY_IS_EQUAL(*b,*Br.begin());\n      VERIFY_IS_EQUAL(*b,Br(0));\n      VERIFY_IS_EQUAL(*a,Br.end()[-1]);\n      VERIFY_IS_EQUAL(*a,Br(last));\n    }\n  }\n\n  // check non-const iterator with for-range loops\n  {\n    i = 0;\n    for(auto x : v) { VERIFY_IS_EQUAL(x,v[i++]); }\n\n    j = internal::random<Index>(0,A.cols()-1);\n    i = 0;\n    for(auto x : A.col(j)) { VERIFY_IS_EQUAL(x,A(i++,j)); }\n\n    i = 0;\n    for(auto x : (v+A.col(j))) { VERIFY_IS_APPROX(x,v(i)+A(i,j)); ++i; }\n\n    j = 0;\n    i = internal::random<Index>(0,A.rows()-1);\n    for(auto x : A.row(i)) { VERIFY_IS_EQUAL(x,A(i,j++)); }\n\n    i = 0;\n    for(auto x : A.reshaped()) { VERIFY_IS_EQUAL(x,A(i++)); }\n  }\n\n  // same for const_iterator\n  {\n    i = 0;\n    for(auto x : cv) { VERIFY_IS_EQUAL(x,v[i++]); }\n\n    i = 0;\n    for(auto x : cA.reshaped()) { VERIFY_IS_EQUAL(x,A(i++)); }\n\n    j = 0;\n    i = internal::random<Index>(0,A.rows()-1);\n    for(auto x : cA.row(i)) { VERIFY_IS_EQUAL(x,A(i,j++)); }\n  }\n\n  // check reshaped() on row-major\n  {\n    i = 0;\n    Matrix<Scalar,Dynamic,Dynamic,ColMajor> Bc = B;\n    for(auto x : B.reshaped()) { VERIFY_IS_EQUAL(x,Bc(i++)); }\n  }\n\n  // check write access\n  {\n    VectorType w(v.size());\n    i = 0;\n    for(auto& x : w) { x = v(i++); }\n    VERIFY_IS_EQUAL(v,w);\n  }\n\n  // check for dangling pointers\n  {\n    // no dangling because pointer-based\n    {\n      j = internal::random<Index>(0,A.cols()-1);\n      auto it = A.col(j).begin();\n      for(i=0;i<rows;++i) {\n        VERIFY_IS_EQUAL(it[i],A(i,j));\n      }\n    }\n\n    // no dangling because pointer-based\n    {\n      i = internal::random<Index>(0,A.rows()-1);\n      auto it = A.row(i).begin();\n      for(j=0;j<cols;++j) { VERIFY_IS_EQUAL(it[j],A(i,j)); }\n    }\n\n    {\n      j = internal::random<Index>(0,A.cols()-1);\n      // this would produce a dangling pointer:\n      // auto it = (A+2*A).col(j).begin(); \n      // we need to name the temporary expression:\n      auto tmp = (A+2*A).col(j);\n      auto it = tmp.begin();\n      for(i=0;i<rows;++i) {\n        VERIFY_IS_APPROX(it[i],3*A(i,j));\n      }\n    }\n  }\n\n  {\n    // check basic for loop on vector-wise iterators\n    j=0;\n    for (auto it = A.colwise().cbegin(); it != A.colwise().cend(); ++it, ++j) {\n      VERIFY_IS_APPROX( it->coeff(0), A(0,j) );\n      VERIFY_IS_APPROX( (*it).coeff(0), A(0,j) );\n    }\n    j=0;\n    for (auto it = A.colwise().begin(); it != A.colwise().end(); ++it, ++j) {\n      (*it).coeffRef(0) = (*it).coeff(0); // compilation check\n      it->coeffRef(0) = it->coeff(0);     // compilation check\n      VERIFY_IS_APPROX( it->coeff(0), A(0,j) );\n      VERIFY_IS_APPROX( (*it).coeff(0), A(0,j) );\n    }\n\n    // check valuetype gives us a copy\n    j=0;\n    for (auto it = A.colwise().cbegin(); it != A.colwise().cend(); ++it, ++j) {\n      typename decltype(it)::value_type tmp = *it;\n      VERIFY_IS_NOT_EQUAL( tmp.data() , it->data() );\n      VERIFY_IS_APPROX( tmp, A.col(j) );\n    }\n  }\n\n#endif\n\n  if(rows>=3) {\n    VERIFY_IS_EQUAL((v.begin()+rows/2)[1], v(rows/2+1));\n\n    VERIFY_IS_EQUAL((A.rowwise().begin()+rows/2)[1], A.row(rows/2+1));\n  }\n\n  if(cols>=3) {\n    VERIFY_IS_EQUAL((A.colwise().begin()+cols/2)[1], A.col(cols/2+1));\n  }\n\n  // check std::sort\n  {\n    // first check that is_sorted returns false when required\n    if(rows>=2)\n    {\n      v(1) = v(0)-Scalar(1);\n      #if EIGEN_HAS_CXX11\n      VERIFY(!is_sorted(std::begin(v),std::end(v)));\n      #else\n      VERIFY(!is_sorted(v.cbegin(),v.cend()));\n      #endif\n    }\n\n    // on a vector\n    {\n      std::sort(v.begin(),v.end());\n      VERIFY(is_sorted(v.begin(),v.end()));\n      VERIFY(!::is_sorted(make_reverse_iterator(v.end()),make_reverse_iterator(v.begin())));\n    }\n\n    // on a column of a column-major matrix -> pointer-based iterator and default increment\n    {\n      j = internal::random<Index>(0,A.cols()-1);\n      // std::sort(begin(A.col(j)),end(A.col(j))); // does not compile because this returns const iterators\n      typename ColMatrixType::ColXpr Acol = A.col(j);\n      std::sort(Acol.begin(),Acol.end());\n      VERIFY(is_sorted(Acol.cbegin(),Acol.cend()));\n      A.setRandom();\n\n      std::sort(A.col(j).begin(),A.col(j).end());\n      VERIFY(is_sorted(A.col(j).cbegin(),A.col(j).cend()));\n      A.setRandom();\n    }\n\n    // on a row of a rowmajor matrix -> pointer-based iterator and runtime increment\n    {\n      i = internal::random<Index>(0,A.rows()-1);\n      typename ColMatrixType::RowXpr Arow = A.row(i);\n      VERIFY_IS_EQUAL( std::distance(Arow.begin(),Arow.end()), cols);\n      std::sort(Arow.begin(),Arow.end());\n      VERIFY(is_sorted(Arow.cbegin(),Arow.cend()));\n      A.setRandom();\n\n      std::sort(A.row(i).begin(),A.row(i).end());\n      VERIFY(is_sorted(A.row(i).cbegin(),A.row(i).cend()));\n      A.setRandom();\n    }\n\n    // with a generic iterator\n    {\n      Reshaped<RowMatrixType,RowMatrixType::SizeAtCompileTime,1> B1 = B.reshaped();\n      std::sort(B1.begin(),B1.end());\n      VERIFY(is_sorted(B1.cbegin(),B1.cend()));\n      B.setRandom();\n\n      // assertion because nested expressions are different\n      // std::sort(B.reshaped().begin(),B.reshaped().end());\n      // VERIFY(is_sorted(B.reshaped().cbegin(),B.reshaped().cend()));\n      // B.setRandom();\n    }\n  }\n\n  // check with partial_sum\n  {\n    j = internal::random<Index>(0,A.cols()-1);\n    typename ColMatrixType::ColXpr Acol = A.col(j);\n    std::partial_sum(Acol.begin(), Acol.end(), v.begin());\n    VERIFY_IS_APPROX(v(seq(1,last)), v(seq(0,last-1))+Acol(seq(1,last)));\n\n    // inplace\n    std::partial_sum(Acol.begin(), Acol.end(), Acol.begin());\n    VERIFY_IS_APPROX(v, Acol);\n  }\n\n  // stress random access as required by std::nth_element\n  if(rows>=3)\n  {\n    v.setRandom();\n    VectorType v1 = v;\n    std::sort(v1.begin(),v1.end());\n    std::nth_element(v.begin(), v.begin()+rows/2, v.end());\n    VERIFY_IS_APPROX(v1(rows/2), v(rows/2));\n\n    v.setRandom();\n    v1 = v;\n    std::sort(v1.begin()+rows/2,v1.end());\n    std::nth_element(v.begin()+rows/2, v.begin()+rows/4, v.end());\n    VERIFY_IS_APPROX(v1(rows/4), v(rows/4));\n  }\n\n#if EIGEN_HAS_CXX11\n  // check rows/cols iterators with range-for loops\n  {\n    j = 0;\n    for(auto c : A.colwise()) { VERIFY_IS_APPROX(c.sum(), A.col(j).sum()); ++j; }\n    j = 0;\n    for(auto c : B.colwise()) { VERIFY_IS_APPROX(c.sum(), B.col(j).sum()); ++j; }\n\n    j = 0;\n    for(auto c : B.colwise()) {\n      i = 0;\n      for(auto& x : c) {\n        VERIFY_IS_EQUAL(x, B(i,j));\n        x = A(i,j);\n        ++i;\n      }\n      ++j;\n    }\n    VERIFY_IS_APPROX(A,B);\n    B.setRandom();\n    \n    i = 0;\n    for(auto r : A.rowwise()) { VERIFY_IS_APPROX(r.sum(), A.row(i).sum()); ++i; }\n    i = 0;\n    for(auto r : B.rowwise()) { VERIFY_IS_APPROX(r.sum(), B.row(i).sum()); ++i; }\n  }\n\n\n  // check rows/cols iterators with STL algorithms\n  {\n    RowVectorType row = RowVectorType::Random(cols);\n    A.rowwise() = row;\n    VERIFY( std::all_of(A.rowwise().begin(),  A.rowwise().end(),  [&row](typename ColMatrixType::RowXpr x) { return internal::isApprox(x.squaredNorm(),row.squaredNorm()); }) );\n    VERIFY( std::all_of(A.rowwise().rbegin(), A.rowwise().rend(), [&row](typename ColMatrixType::RowXpr x) { return internal::isApprox(x.squaredNorm(),row.squaredNorm()); }) );\n\n    VectorType col = VectorType::Random(rows);\n    A.colwise() = col;\n    VERIFY( std::all_of(A.colwise().begin(),   A.colwise().end(),   [&col](typename ColMatrixType::ColXpr x) { return internal::isApprox(x.squaredNorm(),col.squaredNorm()); }) );\n    VERIFY( std::all_of(A.colwise().rbegin(),  A.colwise().rend(),  [&col](typename ColMatrixType::ColXpr x) { return internal::isApprox(x.squaredNorm(),col.squaredNorm()); }) );\n    VERIFY( std::all_of(A.colwise().cbegin(),  A.colwise().cend(),  [&col](typename ColMatrixType::ConstColXpr x) { return internal::isApprox(x.squaredNorm(),col.squaredNorm()); }) );\n    VERIFY( std::all_of(A.colwise().crbegin(), A.colwise().crend(), [&col](typename ColMatrixType::ConstColXpr x) { return internal::isApprox(x.squaredNorm(),col.squaredNorm()); }) );\n\n    i = internal::random<Index>(0,A.rows()-1);\n    A.setRandom();\n    A.row(i).setZero();\n    VERIFY_IS_EQUAL( std::find_if(A.rowwise().begin(),  A.rowwise().end(),  [](typename ColMatrixType::RowXpr x) { return x.squaredNorm() == Scalar(0); })-A.rowwise().begin(),  i );\n    VERIFY_IS_EQUAL( std::find_if(A.rowwise().rbegin(), A.rowwise().rend(), [](typename ColMatrixType::RowXpr x) { return x.squaredNorm() == Scalar(0); })-A.rowwise().rbegin(), (A.rows()-1) - i );\n\n    j = internal::random<Index>(0,A.cols()-1);\n    A.setRandom();\n    A.col(j).setZero();\n    VERIFY_IS_EQUAL( std::find_if(A.colwise().begin(),  A.colwise().end(),  [](typename ColMatrixType::ColXpr x) { return x.squaredNorm() == Scalar(0); })-A.colwise().begin(),  j );\n    VERIFY_IS_EQUAL( std::find_if(A.colwise().rbegin(), A.colwise().rend(), [](typename ColMatrixType::ColXpr x) { return x.squaredNorm() == Scalar(0); })-A.colwise().rbegin(), (A.cols()-1) - j );\n  }\n\n  {\n    using VecOp = VectorwiseOp<ArrayXXi, 0>;\n    STATIC_CHECK(( internal::is_same<VecOp::const_iterator, decltype(std::declval<const VecOp&>().cbegin())>::value ));\n    STATIC_CHECK(( internal::is_same<VecOp::const_iterator, decltype(std::declval<const VecOp&>().cend  ())>::value ));\n    #if EIGEN_COMP_CXXVER>=14\n      STATIC_CHECK(( internal::is_same<VecOp::const_iterator, decltype(std::cbegin(std::declval<const VecOp&>()))>::value ));\n      STATIC_CHECK(( internal::is_same<VecOp::const_iterator, decltype(std::cend  (std::declval<const VecOp&>()))>::value ));\n    #endif\n  }\n\n#endif\n}\n\n\n#if EIGEN_HAS_CXX11\n// When the compiler sees expression IsContainerTest<C>(0), if C is an\n// STL-style container class, the first overload of IsContainerTest\n// will be viable (since both C::iterator* and C::const_iterator* are\n// valid types and NULL can be implicitly converted to them).  It will\n// be picked over the second overload as 'int' is a perfect match for\n// the type of argument 0.  If C::iterator or C::const_iterator is not\n// a valid type, the first overload is not viable, and the second\n// overload will be picked.\ntemplate <class C,\n          class Iterator = decltype(::std::declval<const C&>().begin()),\n          class = decltype(::std::declval<const C&>().end()),\n          class = decltype(++::std::declval<Iterator&>()),\n          class = decltype(*::std::declval<Iterator>()),\n          class = typename C::const_iterator>\nbool IsContainerType(int /* dummy */) { return true; }\n\ntemplate <class C>\nbool IsContainerType(long /* dummy */) { return false; }\n\ntemplate <typename Scalar, int Rows, int Cols>\nvoid test_stl_container_detection(int rows=Rows, int cols=Cols)\n{\n  typedef Matrix<Scalar,Rows,1> VectorType;\n  typedef Matrix<Scalar,Rows,Cols,ColMajor> ColMatrixType;\n  typedef Matrix<Scalar,Rows,Cols,RowMajor> RowMatrixType;\n\n  ColMatrixType A = ColMatrixType::Random(rows, cols);\n  RowMatrixType B = RowMatrixType::Random(rows, cols);\n\n  Index i = 1;\n\n  using ColMatrixColType = decltype(A.col(i));\n  using ColMatrixRowType = decltype(A.row(i));\n  using RowMatrixColType = decltype(B.col(i));\n  using RowMatrixRowType = decltype(B.row(i));\n\n  // Vector and matrix col/row are valid Stl-style container.\n  VERIFY_IS_EQUAL(IsContainerType<VectorType>(0), true);\n  VERIFY_IS_EQUAL(IsContainerType<ColMatrixColType>(0), true);\n  VERIFY_IS_EQUAL(IsContainerType<ColMatrixRowType>(0), true);\n  VERIFY_IS_EQUAL(IsContainerType<RowMatrixColType>(0), true);\n  VERIFY_IS_EQUAL(IsContainerType<RowMatrixRowType>(0), true);\n\n  // But the matrix itself is not a valid Stl-style container.\n  VERIFY_IS_EQUAL(IsContainerType<ColMatrixType>(0), rows == 1 || cols == 1);\n  VERIFY_IS_EQUAL(IsContainerType<RowMatrixType>(0), rows == 1 || cols == 1);\n}\n#endif\n\nEIGEN_DECLARE_TEST(stl_iterators)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(( test_stl_iterators<double,2,3>() ));\n    CALL_SUBTEST_1(( test_stl_iterators<float,7,5>() ));\n    CALL_SUBTEST_1(( test_stl_iterators<int,Dynamic,Dynamic>(internal::random<int>(5,10), internal::random<int>(5,10)) ));\n    CALL_SUBTEST_1(( test_stl_iterators<int,Dynamic,Dynamic>(internal::random<int>(10,200), internal::random<int>(10,200)) ));\n  }\n  \n#if EIGEN_HAS_CXX11\n  CALL_SUBTEST_1(( test_stl_container_detection<float,1,1>() ));\n  CALL_SUBTEST_1(( test_stl_container_detection<float,5,5>() ));\n#endif  \n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/superlu_support.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS\n#include \"sparse_solver.h\"\n\n#include <Eigen/SuperLUSupport>\n\nEIGEN_DECLARE_TEST(superlu_support)\n{\n  SuperLU<SparseMatrix<double> > superlu_double_colmajor;\n  SuperLU<SparseMatrix<std::complex<double> > > superlu_cplxdouble_colmajor;\n  CALL_SUBTEST_1( check_sparse_square_solving(superlu_double_colmajor)      );\n  CALL_SUBTEST_2( check_sparse_square_solving(superlu_cplxdouble_colmajor)  );\n  CALL_SUBTEST_1( check_sparse_square_determinant(superlu_double_colmajor)      );\n  CALL_SUBTEST_2( check_sparse_square_determinant(superlu_cplxdouble_colmajor)  );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/svd_common.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef SVD_DEFAULT\n#error a macro SVD_DEFAULT(MatrixType) must be defined prior to including svd_common.h\n#endif\n\n#ifndef SVD_FOR_MIN_NORM\n#error a macro SVD_FOR_MIN_NORM(MatrixType) must be defined prior to including svd_common.h\n#endif\n\n#include \"svd_fill.h\"\n#include \"solverbase.h\"\n\n// Check that the matrix m is properly reconstructed and that the U and V factors are unitary\n// The SVD must have already been computed.\ntemplate<typename SvdType, typename MatrixType>\nvoid svd_check_full(const MatrixType& m, const SvdType& svd)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  enum {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime\n  };\n\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef Matrix<Scalar, RowsAtCompileTime, RowsAtCompileTime> MatrixUType;\n  typedef Matrix<Scalar, ColsAtCompileTime, ColsAtCompileTime> MatrixVType;\n\n  MatrixType sigma = MatrixType::Zero(rows,cols);\n  sigma.diagonal() = svd.singularValues().template cast<Scalar>();\n  MatrixUType u = svd.matrixU();\n  MatrixVType v = svd.matrixV();\n  RealScalar scaling = m.cwiseAbs().maxCoeff();\n  if(scaling<(std::numeric_limits<RealScalar>::min)())\n  {\n    VERIFY(sigma.cwiseAbs().maxCoeff() <= (std::numeric_limits<RealScalar>::min)());\n  }\n  else\n  {\n    VERIFY_IS_APPROX(m/scaling, u * (sigma/scaling) * v.adjoint());\n  }\n  VERIFY_IS_UNITARY(u);\n  VERIFY_IS_UNITARY(v);\n}\n\n// Compare partial SVD defined by computationOptions to a full SVD referenceSvd\ntemplate<typename SvdType, typename MatrixType>\nvoid svd_compare_to_full(const MatrixType& m,\n                         unsigned int computationOptions,\n                         const SvdType& referenceSvd)\n{\n  typedef typename MatrixType::RealScalar RealScalar;\n  Index rows = m.rows();\n  Index cols = m.cols();\n  Index diagSize = (std::min)(rows, cols);\n  RealScalar prec = test_precision<RealScalar>();\n\n  SvdType svd(m, computationOptions);\n\n  VERIFY_IS_APPROX(svd.singularValues(), referenceSvd.singularValues());\n  \n  if(computationOptions & (ComputeFullV|ComputeThinV))\n  {\n    VERIFY( (svd.matrixV().adjoint()*svd.matrixV()).isIdentity(prec) );\n    VERIFY_IS_APPROX( svd.matrixV().leftCols(diagSize) * svd.singularValues().asDiagonal() * svd.matrixV().leftCols(diagSize).adjoint(),\n                      referenceSvd.matrixV().leftCols(diagSize) * referenceSvd.singularValues().asDiagonal() * referenceSvd.matrixV().leftCols(diagSize).adjoint());\n  }\n  \n  if(computationOptions & (ComputeFullU|ComputeThinU))\n  {\n    VERIFY( (svd.matrixU().adjoint()*svd.matrixU()).isIdentity(prec) );\n    VERIFY_IS_APPROX( svd.matrixU().leftCols(diagSize) * svd.singularValues().cwiseAbs2().asDiagonal() * svd.matrixU().leftCols(diagSize).adjoint(),\n                      referenceSvd.matrixU().leftCols(diagSize) * referenceSvd.singularValues().cwiseAbs2().asDiagonal() * referenceSvd.matrixU().leftCols(diagSize).adjoint());\n  }\n  \n  // The following checks are not critical.\n  // For instance, with Dived&Conquer SVD, if only the factor 'V' is computedt then different matrix-matrix product implementation will be used\n  // and the resulting 'V' factor might be significantly different when the SVD decomposition is not unique, especially with single precision float.\n  ++g_test_level;\n  if(computationOptions & ComputeFullU)  VERIFY_IS_APPROX(svd.matrixU(), referenceSvd.matrixU());\n  if(computationOptions & ComputeThinU)  VERIFY_IS_APPROX(svd.matrixU(), referenceSvd.matrixU().leftCols(diagSize));\n  if(computationOptions & ComputeFullV)  VERIFY_IS_APPROX(svd.matrixV().cwiseAbs(), referenceSvd.matrixV().cwiseAbs());\n  if(computationOptions & ComputeThinV)  VERIFY_IS_APPROX(svd.matrixV(), referenceSvd.matrixV().leftCols(diagSize));\n  --g_test_level;\n}\n\n//\ntemplate<typename SvdType, typename MatrixType>\nvoid svd_least_square(const MatrixType& m, unsigned int computationOptions)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  enum {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime\n  };\n\n  typedef Matrix<Scalar, RowsAtCompileTime, Dynamic> RhsType;\n  typedef Matrix<Scalar, ColsAtCompileTime, Dynamic> SolutionType;\n\n  RhsType rhs = RhsType::Random(rows, internal::random<Index>(1, cols));\n  SvdType svd(m, computationOptions);\n\n       if(internal::is_same<RealScalar,double>::value) svd.setThreshold(1e-8);\n  else if(internal::is_same<RealScalar,float>::value)  svd.setThreshold(2e-4);\n\n  SolutionType x = svd.solve(rhs);\n   \n  RealScalar residual = (m*x-rhs).norm();\n  RealScalar rhs_norm = rhs.norm();\n  if(!test_isMuchSmallerThan(residual,rhs.norm()))\n  {\n    // ^^^ If the residual is very small, then we have an exact solution, so we are already good.\n    \n    // evaluate normal equation which works also for least-squares solutions\n    if(internal::is_same<RealScalar,double>::value || svd.rank()==m.diagonal().size())\n    {\n      using std::sqrt;\n      // This test is not stable with single precision.\n      // This is probably because squaring m signicantly affects the precision.      \n      if(internal::is_same<RealScalar,float>::value) ++g_test_level;\n      \n      VERIFY_IS_APPROX(m.adjoint()*(m*x),m.adjoint()*rhs);\n      \n      if(internal::is_same<RealScalar,float>::value) --g_test_level;\n    }\n    \n    // Check that there is no significantly better solution in the neighborhood of x\n    for(Index k=0;k<x.rows();++k)\n    {\n      using std::abs;\n      \n      SolutionType y(x);\n      y.row(k) = (RealScalar(1)+2*NumTraits<RealScalar>::epsilon())*x.row(k);\n      RealScalar residual_y = (m*y-rhs).norm();\n      VERIFY( test_isMuchSmallerThan(abs(residual_y-residual), rhs_norm) || residual < residual_y );\n      if(internal::is_same<RealScalar,float>::value) ++g_test_level;\n      VERIFY( test_isApprox(residual_y,residual) || residual < residual_y );\n      if(internal::is_same<RealScalar,float>::value) --g_test_level;\n      \n      y.row(k) = (RealScalar(1)-2*NumTraits<RealScalar>::epsilon())*x.row(k);\n      residual_y = (m*y-rhs).norm();\n      VERIFY( test_isMuchSmallerThan(abs(residual_y-residual), rhs_norm) || residual < residual_y );\n      if(internal::is_same<RealScalar,float>::value) ++g_test_level;\n      VERIFY( test_isApprox(residual_y,residual) || residual < residual_y );\n      if(internal::is_same<RealScalar,float>::value) --g_test_level;\n    }\n  }\n}\n\n// check minimal norm solutions, the inoput matrix m is only used to recover problem size\ntemplate<typename MatrixType>\nvoid svd_min_norm(const MatrixType& m, unsigned int computationOptions)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  Index cols = m.cols();\n\n  enum {\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime\n  };\n\n  typedef Matrix<Scalar, ColsAtCompileTime, Dynamic> SolutionType;\n\n  // generate a full-rank m x n problem with m<n\n  enum {\n    RankAtCompileTime2 = ColsAtCompileTime==Dynamic ? Dynamic : (ColsAtCompileTime)/2+1,\n    RowsAtCompileTime3 = ColsAtCompileTime==Dynamic ? Dynamic : ColsAtCompileTime+1\n  };\n  typedef Matrix<Scalar, RankAtCompileTime2, ColsAtCompileTime> MatrixType2;\n  typedef Matrix<Scalar, RankAtCompileTime2, 1> RhsType2;\n  typedef Matrix<Scalar, ColsAtCompileTime, RankAtCompileTime2> MatrixType2T;\n  Index rank = RankAtCompileTime2==Dynamic ? internal::random<Index>(1,cols) : Index(RankAtCompileTime2);\n  MatrixType2 m2(rank,cols);\n  int guard = 0;\n  do {\n    m2.setRandom();\n  } while(SVD_FOR_MIN_NORM(MatrixType2)(m2).setThreshold(test_precision<Scalar>()).rank()!=rank && (++guard)<10);\n  VERIFY(guard<10);\n\n  RhsType2 rhs2 = RhsType2::Random(rank);\n  // use QR to find a reference minimal norm solution\n  HouseholderQR<MatrixType2T> qr(m2.adjoint());\n  Matrix<Scalar,Dynamic,1> tmp = qr.matrixQR().topLeftCorner(rank,rank).template triangularView<Upper>().adjoint().solve(rhs2);\n  tmp.conservativeResize(cols);\n  tmp.tail(cols-rank).setZero();\n  SolutionType x21 = qr.householderQ() * tmp;\n  // now check with SVD\n  SVD_FOR_MIN_NORM(MatrixType2) svd2(m2, computationOptions);\n  SolutionType x22 = svd2.solve(rhs2);\n  VERIFY_IS_APPROX(m2*x21, rhs2);\n  VERIFY_IS_APPROX(m2*x22, rhs2);\n  VERIFY_IS_APPROX(x21, x22);\n\n  // Now check with a rank deficient matrix\n  typedef Matrix<Scalar, RowsAtCompileTime3, ColsAtCompileTime> MatrixType3;\n  typedef Matrix<Scalar, RowsAtCompileTime3, 1> RhsType3;\n  Index rows3 = RowsAtCompileTime3==Dynamic ? internal::random<Index>(rank+1,2*cols) : Index(RowsAtCompileTime3);\n  Matrix<Scalar,RowsAtCompileTime3,Dynamic> C = Matrix<Scalar,RowsAtCompileTime3,Dynamic>::Random(rows3,rank);\n  MatrixType3 m3 = C * m2;\n  RhsType3 rhs3 = C * rhs2;\n  SVD_FOR_MIN_NORM(MatrixType3) svd3(m3, computationOptions);\n  SolutionType x3 = svd3.solve(rhs3);\n  VERIFY_IS_APPROX(m3*x3, rhs3);\n  VERIFY_IS_APPROX(m3*x21, rhs3);\n  VERIFY_IS_APPROX(m2*x3, rhs2);\n  VERIFY_IS_APPROX(x21, x3);\n}\n\ntemplate<typename MatrixType, typename SolverType>\nvoid svd_test_solvers(const MatrixType& m, const SolverType& solver) {\n    Index rows, cols, cols2;\n\n    rows = m.rows();\n    cols = m.cols();\n\n    if(MatrixType::ColsAtCompileTime==Dynamic)\n    {\n      cols2 = internal::random<int>(2,EIGEN_TEST_MAX_SIZE);\n    }\n    else\n    {\n      cols2 = cols;\n    }\n    typedef Matrix<typename MatrixType::Scalar, MatrixType::ColsAtCompileTime, MatrixType::ColsAtCompileTime> CMatrixType;\n    check_solverbase<CMatrixType, MatrixType>(m, solver, rows, cols, cols2);\n}\n\n// Check full, compare_to_full, least_square, and min_norm for all possible compute-options\ntemplate<typename SvdType, typename MatrixType>\nvoid svd_test_all_computation_options(const MatrixType& m, bool full_only)\n{\n//   if (QRPreconditioner == NoQRPreconditioner && m.rows() != m.cols())\n//     return;\n  STATIC_CHECK(( internal::is_same<typename SvdType::StorageIndex,int>::value ));\n\n  SvdType fullSvd(m, ComputeFullU|ComputeFullV);\n  CALL_SUBTEST(( svd_check_full(m, fullSvd) ));\n  CALL_SUBTEST(( svd_least_square<SvdType>(m, ComputeFullU | ComputeFullV) ));\n  CALL_SUBTEST(( svd_min_norm(m, ComputeFullU | ComputeFullV) ));\n  \n  #if defined __INTEL_COMPILER\n  // remark #111: statement is unreachable\n  #pragma warning disable 111\n  #endif\n\n  svd_test_solvers(m, fullSvd);\n\n  if(full_only)\n    return;\n\n  CALL_SUBTEST(( svd_compare_to_full(m, ComputeFullU, fullSvd) ));\n  CALL_SUBTEST(( svd_compare_to_full(m, ComputeFullV, fullSvd) ));\n  CALL_SUBTEST(( svd_compare_to_full(m, 0, fullSvd) ));\n\n  if (MatrixType::ColsAtCompileTime == Dynamic) {\n    // thin U/V are only available with dynamic number of columns\n    CALL_SUBTEST(( svd_compare_to_full(m, ComputeFullU|ComputeThinV, fullSvd) ));\n    CALL_SUBTEST(( svd_compare_to_full(m,              ComputeThinV, fullSvd) ));\n    CALL_SUBTEST(( svd_compare_to_full(m, ComputeThinU|ComputeFullV, fullSvd) ));\n    CALL_SUBTEST(( svd_compare_to_full(m, ComputeThinU             , fullSvd) ));\n    CALL_SUBTEST(( svd_compare_to_full(m, ComputeThinU|ComputeThinV, fullSvd) ));\n    \n    CALL_SUBTEST(( svd_least_square<SvdType>(m, ComputeFullU | ComputeThinV) ));\n    CALL_SUBTEST(( svd_least_square<SvdType>(m, ComputeThinU | ComputeFullV) ));\n    CALL_SUBTEST(( svd_least_square<SvdType>(m, ComputeThinU | ComputeThinV) ));\n\n    CALL_SUBTEST(( svd_min_norm(m, ComputeFullU | ComputeThinV) ));\n    CALL_SUBTEST(( svd_min_norm(m, ComputeThinU | ComputeFullV) ));\n    CALL_SUBTEST(( svd_min_norm(m, ComputeThinU | ComputeThinV) ));\n\n    // test reconstruction\n    Index diagSize = (std::min)(m.rows(), m.cols());\n    SvdType svd(m, ComputeThinU | ComputeThinV);\n    VERIFY_IS_APPROX(m, svd.matrixU().leftCols(diagSize) * svd.singularValues().asDiagonal() * svd.matrixV().leftCols(diagSize).adjoint());\n  }\n}\n\n\n// work around stupid msvc error when constructing at compile time an expression that involves\n// a division by zero, even if the numeric type has floating point\ntemplate<typename Scalar>\nEIGEN_DONT_INLINE Scalar zero() { return Scalar(0); }\n\n// workaround aggressive optimization in ICC\ntemplate<typename T> EIGEN_DONT_INLINE  T sub(T a, T b) { return a - b; }\n\n// all this function does is verify we don't iterate infinitely on nan/inf values\ntemplate<typename SvdType, typename MatrixType>\nvoid svd_inf_nan()\n{\n  SvdType svd;\n  typedef typename MatrixType::Scalar Scalar;\n  Scalar some_inf = Scalar(1) / zero<Scalar>();\n  VERIFY(sub(some_inf, some_inf) != sub(some_inf, some_inf));\n  svd.compute(MatrixType::Constant(10,10,some_inf), ComputeFullU | ComputeFullV);\n\n  Scalar nan = std::numeric_limits<Scalar>::quiet_NaN();\n  VERIFY(nan != nan);\n  svd.compute(MatrixType::Constant(10,10,nan), ComputeFullU | ComputeFullV);\n\n  MatrixType m = MatrixType::Zero(10,10);\n  m(internal::random<int>(0,9), internal::random<int>(0,9)) = some_inf;\n  svd.compute(m, ComputeFullU | ComputeFullV);\n\n  m = MatrixType::Zero(10,10);\n  m(internal::random<int>(0,9), internal::random<int>(0,9)) = nan;\n  svd.compute(m, ComputeFullU | ComputeFullV);\n  \n  // regression test for bug 791\n  m.resize(3,3);\n  m << 0,    2*NumTraits<Scalar>::epsilon(),  0.5,\n       0,   -0.5,                             0,\n       nan,  0,                               0;\n  svd.compute(m, ComputeFullU | ComputeFullV);\n  \n  m.resize(4,4);\n  m <<  1, 0, 0, 0,\n        0, 3, 1, 2e-308,\n        1, 0, 1, nan,\n        0, nan, nan, 0;\n  svd.compute(m, ComputeFullU | ComputeFullV);\n}\n\n// Regression test for bug 286: JacobiSVD loops indefinitely with some\n// matrices containing denormal numbers.\ntemplate<typename>\nvoid svd_underoverflow()\n{\n#if defined __INTEL_COMPILER\n// shut up warning #239: floating point underflow\n#pragma warning push\n#pragma warning disable 239\n#endif\n  Matrix2d M;\n  M << -7.90884e-313, -4.94e-324,\n                 0, 5.60844e-313;\n  SVD_DEFAULT(Matrix2d) svd;\n  svd.compute(M,ComputeFullU|ComputeFullV);\n  CALL_SUBTEST( svd_check_full(M,svd) );\n  \n  // Check all 2x2 matrices made with the following coefficients:\n  VectorXd value_set(9);\n  value_set << 0, 1, -1, 5.60844e-313, -5.60844e-313, 4.94e-324, -4.94e-324, -4.94e-223, 4.94e-223;\n  Array4i id(0,0,0,0);\n  int k = 0;\n  do\n  {\n    M << value_set(id(0)), value_set(id(1)), value_set(id(2)), value_set(id(3));\n    svd.compute(M,ComputeFullU|ComputeFullV);\n    CALL_SUBTEST( svd_check_full(M,svd) );\n\n    id(k)++;\n    if(id(k)>=value_set.size())\n    {\n      while(k<3 && id(k)>=value_set.size()) id(++k)++;\n      id.head(k).setZero();\n      k=0;\n    }\n\n  } while((id<int(value_set.size())).all());\n  \n#if defined __INTEL_COMPILER\n#pragma warning pop\n#endif\n  \n  // Check for overflow:\n  Matrix3d M3;\n  M3 << 4.4331978442502944e+307, -5.8585363752028680e+307,  6.4527017443412964e+307,\n        3.7841695601406358e+307,  2.4331702789740617e+306, -3.5235707140272905e+307,\n       -8.7190887618028355e+307, -7.3453213709232193e+307, -2.4367363684472105e+307;\n\n  SVD_DEFAULT(Matrix3d) svd3;\n  svd3.compute(M3,ComputeFullU|ComputeFullV); // just check we don't loop indefinitely\n  CALL_SUBTEST( svd_check_full(M3,svd3) );\n}\n\n// void jacobisvd(const MatrixType& a = MatrixType(), bool pickrandom = true)\n\ntemplate<typename MatrixType>\nvoid svd_all_trivial_2x2( void (*cb)(const MatrixType&,bool) )\n{\n  MatrixType M;\n  VectorXd value_set(3);\n  value_set << 0, 1, -1;\n  Array4i id(0,0,0,0);\n  int k = 0;\n  do\n  {\n    M << value_set(id(0)), value_set(id(1)), value_set(id(2)), value_set(id(3));\n    \n    cb(M,false);\n    \n    id(k)++;\n    if(id(k)>=value_set.size())\n    {\n      while(k<3 && id(k)>=value_set.size()) id(++k)++;\n      id.head(k).setZero();\n      k=0;\n    }\n    \n  } while((id<int(value_set.size())).all());\n}\n\ntemplate<typename>\nvoid svd_preallocate()\n{\n  Vector3f v(3.f, 2.f, 1.f);\n  MatrixXf m = v.asDiagonal();\n\n  internal::set_is_malloc_allowed(false);\n  VERIFY_RAISES_ASSERT(VectorXf tmp(10);)\n  SVD_DEFAULT(MatrixXf) svd;\n  internal::set_is_malloc_allowed(true);\n  svd.compute(m);\n  VERIFY_IS_APPROX(svd.singularValues(), v);\n\n  SVD_DEFAULT(MatrixXf) svd2(3,3);\n  internal::set_is_malloc_allowed(false);\n  svd2.compute(m);\n  internal::set_is_malloc_allowed(true);\n  VERIFY_IS_APPROX(svd2.singularValues(), v);\n  VERIFY_RAISES_ASSERT(svd2.matrixU());\n  VERIFY_RAISES_ASSERT(svd2.matrixV());\n  svd2.compute(m, ComputeFullU | ComputeFullV);\n  VERIFY_IS_APPROX(svd2.matrixU(), Matrix3f::Identity());\n  VERIFY_IS_APPROX(svd2.matrixV(), Matrix3f::Identity());\n  internal::set_is_malloc_allowed(false);\n  svd2.compute(m);\n  internal::set_is_malloc_allowed(true);\n\n  SVD_DEFAULT(MatrixXf) svd3(3,3,ComputeFullU|ComputeFullV);\n  internal::set_is_malloc_allowed(false);\n  svd2.compute(m);\n  internal::set_is_malloc_allowed(true);\n  VERIFY_IS_APPROX(svd2.singularValues(), v);\n  VERIFY_IS_APPROX(svd2.matrixU(), Matrix3f::Identity());\n  VERIFY_IS_APPROX(svd2.matrixV(), Matrix3f::Identity());\n  internal::set_is_malloc_allowed(false);\n  svd2.compute(m, ComputeFullU|ComputeFullV);\n  internal::set_is_malloc_allowed(true);\n}\n\ntemplate<typename SvdType,typename MatrixType> \nvoid svd_verify_assert(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  enum {\n    RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n    ColsAtCompileTime = MatrixType::ColsAtCompileTime\n  };\n\n  typedef Matrix<Scalar, RowsAtCompileTime, 1> RhsType;\n  RhsType rhs(rows);\n  SvdType svd;\n  VERIFY_RAISES_ASSERT(svd.matrixU())\n  VERIFY_RAISES_ASSERT(svd.singularValues())\n  VERIFY_RAISES_ASSERT(svd.matrixV())\n  VERIFY_RAISES_ASSERT(svd.solve(rhs))\n  VERIFY_RAISES_ASSERT(svd.transpose().solve(rhs))\n  VERIFY_RAISES_ASSERT(svd.adjoint().solve(rhs))\n  MatrixType a = MatrixType::Zero(rows, cols);\n  a.setZero();\n  svd.compute(a, 0);\n  VERIFY_RAISES_ASSERT(svd.matrixU())\n  VERIFY_RAISES_ASSERT(svd.matrixV())\n  svd.singularValues();\n  VERIFY_RAISES_ASSERT(svd.solve(rhs))\n    \n  if (ColsAtCompileTime == Dynamic)\n  {\n    svd.compute(a, ComputeThinU);\n    svd.matrixU();\n    VERIFY_RAISES_ASSERT(svd.matrixV())\n    VERIFY_RAISES_ASSERT(svd.solve(rhs))\n    svd.compute(a, ComputeThinV);\n    svd.matrixV();\n    VERIFY_RAISES_ASSERT(svd.matrixU())\n    VERIFY_RAISES_ASSERT(svd.solve(rhs))\n  }\n  else\n  {\n    VERIFY_RAISES_ASSERT(svd.compute(a, ComputeThinU))\n    VERIFY_RAISES_ASSERT(svd.compute(a, ComputeThinV))\n  }\n}\n\n#undef SVD_DEFAULT\n#undef SVD_FOR_MIN_NORM\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/svd_fill.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014-2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\ntemplate<typename T>\nArray<T,4,1> four_denorms();\n\ntemplate<>\nArray4f four_denorms() { return Array4f(5.60844e-39f, -5.60844e-39f, 4.94e-44f, -4.94e-44f); }\ntemplate<>\nArray4d four_denorms() { return Array4d(5.60844e-313, -5.60844e-313, 4.94e-324, -4.94e-324); }\ntemplate<typename T>\nArray<T,4,1> four_denorms() { return four_denorms<double>().cast<T>(); }\n\ntemplate<typename MatrixType>\nvoid svd_fill_random(MatrixType &m, int Option = 0)\n{\n  using std::pow;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  Index diagSize = (std::min)(m.rows(), m.cols());\n  RealScalar s = std::numeric_limits<RealScalar>::max_exponent10/4;\n  s = internal::random<RealScalar>(1,s);\n  Matrix<RealScalar,Dynamic,1> d =  Matrix<RealScalar,Dynamic,1>::Random(diagSize);\n  for(Index k=0; k<diagSize; ++k)\n    d(k) = d(k)*pow(RealScalar(10),internal::random<RealScalar>(-s,s));\n\n  bool dup     = internal::random<int>(0,10) < 3;\n  bool unit_uv = internal::random<int>(0,10) < (dup?7:3); // if we duplicate some diagonal entries, then increase the chance to preserve them using unitary U and V factors\n  \n  // duplicate some singular values\n  if(dup)\n  {\n    Index n = internal::random<Index>(0,d.size()-1);\n    for(Index i=0; i<n; ++i)\n      d(internal::random<Index>(0,d.size()-1)) = d(internal::random<Index>(0,d.size()-1));\n  }\n  \n  Matrix<Scalar,Dynamic,Dynamic> U(m.rows(),diagSize);\n  Matrix<Scalar,Dynamic,Dynamic> VT(diagSize,m.cols());\n  if(unit_uv)\n  {\n    // in very rare cases let's try with a pure diagonal matrix\n    if(internal::random<int>(0,10) < 1)\n    {\n      U.setIdentity();\n      VT.setIdentity();\n    }\n    else\n    {\n      createRandomPIMatrixOfRank(diagSize,U.rows(), U.cols(), U);\n      createRandomPIMatrixOfRank(diagSize,VT.rows(), VT.cols(), VT);\n    }\n  }\n  else\n  {\n    U.setRandom();\n    VT.setRandom();\n  }\n  \n  Matrix<Scalar,Dynamic,1> samples(9);\n  samples << 0, four_denorms<RealScalar>(),\n            -RealScalar(1)/NumTraits<RealScalar>::highest(), RealScalar(1)/NumTraits<RealScalar>::highest(), (std::numeric_limits<RealScalar>::min)(), pow((std::numeric_limits<RealScalar>::min)(),0.8);\n  \n  if(Option==Symmetric)\n  {\n    m = U * d.asDiagonal() * U.transpose();\n    \n    // randomly nullify some rows/columns\n    {\n      Index count = internal::random<Index>(-diagSize,diagSize);\n      for(Index k=0; k<count; ++k)\n      {\n        Index i = internal::random<Index>(0,diagSize-1);\n        m.row(i).setZero();\n        m.col(i).setZero();\n      }\n      if(count<0)\n      // (partly) cancel some coeffs\n      if(!(dup && unit_uv))\n      {\n        \n        Index n = internal::random<Index>(0,m.size()-1);\n        for(Index k=0; k<n; ++k)\n        {\n          Index i = internal::random<Index>(0,m.rows()-1);\n          Index j = internal::random<Index>(0,m.cols()-1);\n          m(j,i) = m(i,j) = samples(internal::random<Index>(0,samples.size()-1));\n          if(NumTraits<Scalar>::IsComplex)\n            *(&numext::real_ref(m(j,i))+1) = *(&numext::real_ref(m(i,j))+1) = samples.real()(internal::random<Index>(0,samples.size()-1));\n        }\n      }\n    }\n  }\n  else\n  {\n    m = U * d.asDiagonal() * VT;\n    // (partly) cancel some coeffs\n    if(!(dup && unit_uv))\n    {\n      Index n = internal::random<Index>(0,m.size()-1);\n      for(Index k=0; k<n; ++k)\n      {\n        Index i = internal::random<Index>(0,m.rows()-1);\n        Index j = internal::random<Index>(0,m.cols()-1);\n        m(i,j) = samples(internal::random<Index>(0,samples.size()-1));\n        if(NumTraits<Scalar>::IsComplex)\n          *(&numext::real_ref(m(i,j))+1) = samples.real()(internal::random<Index>(0,samples.size()-1));\n      }\n    }\n  }\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/swap.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_STATIC_ASSERT\n#include \"main.h\"\n\ntemplate<typename T>\nstruct other_matrix_type\n{\n  typedef int type;\n};\n\ntemplate<typename _Scalar, int _Rows, int _Cols, int _Options, int _MaxRows, int _MaxCols>\nstruct other_matrix_type<Matrix<_Scalar, _Rows, _Cols, _Options, _MaxRows, _MaxCols> >\n{\n  typedef Matrix<_Scalar, _Rows, _Cols, _Options^RowMajor, _MaxRows, _MaxCols> type;\n};\n\ntemplate<typename MatrixType> void swap(const MatrixType& m)\n{\n  typedef typename other_matrix_type<MatrixType>::type OtherMatrixType;\n  typedef typename MatrixType::Scalar Scalar;\n\n  eigen_assert((!internal::is_same<MatrixType,OtherMatrixType>::value));\n  Index rows = m.rows();\n  Index cols = m.cols();\n  \n  // construct 3 matrix guaranteed to be distinct\n  MatrixType m1 = MatrixType::Random(rows,cols);\n  MatrixType m2 = MatrixType::Random(rows,cols) + Scalar(100) * MatrixType::Identity(rows,cols);\n  OtherMatrixType m3 = OtherMatrixType::Random(rows,cols) + Scalar(200) * OtherMatrixType::Identity(rows,cols);\n  \n  MatrixType m1_copy = m1;\n  MatrixType m2_copy = m2;\n  OtherMatrixType m3_copy = m3;\n  \n  // test swapping 2 matrices of same type\n  Scalar *d1=m1.data(), *d2=m2.data();\n  m1.swap(m2);\n  VERIFY_IS_APPROX(m1,m2_copy);\n  VERIFY_IS_APPROX(m2,m1_copy);\n  if(MatrixType::SizeAtCompileTime==Dynamic)\n  {\n    VERIFY(m1.data()==d2);\n    VERIFY(m2.data()==d1);\n  }\n  m1 = m1_copy;\n  m2 = m2_copy;\n  \n  // test swapping 2 matrices of different types\n  m1.swap(m3);\n  VERIFY_IS_APPROX(m1,m3_copy);\n  VERIFY_IS_APPROX(m3,m1_copy);\n  m1 = m1_copy;\n  m3 = m3_copy;\n  \n  // test swapping matrix with expression\n  m1.swap(m2.block(0,0,rows,cols));\n  VERIFY_IS_APPROX(m1,m2_copy);\n  VERIFY_IS_APPROX(m2,m1_copy);\n  m1 = m1_copy;\n  m2 = m2_copy;\n\n  // test swapping two expressions of different types\n  m1.transpose().swap(m3.transpose());\n  VERIFY_IS_APPROX(m1,m3_copy);\n  VERIFY_IS_APPROX(m3,m1_copy);\n  m1 = m1_copy;\n  m3 = m3_copy;\n  \n  if(m1.rows()>1)\n  {\n    // test assertion on mismatching size -- matrix case\n    VERIFY_RAISES_ASSERT(m1.swap(m1.row(0)));\n    // test assertion on mismatching size -- xpr case\n    VERIFY_RAISES_ASSERT(m1.row(0).swap(m1));\n  }\n}\n\nEIGEN_DECLARE_TEST(swap)\n{\n  int s = internal::random<int>(1,EIGEN_TEST_MAX_SIZE);\n  CALL_SUBTEST_1( swap(Matrix3f()) ); // fixed size, no vectorization \n  CALL_SUBTEST_2( swap(Matrix4d()) ); // fixed size, possible vectorization \n  CALL_SUBTEST_3( swap(MatrixXd(s,s)) ); // dyn size, no vectorization \n  CALL_SUBTEST_4( swap(MatrixXf(s,s)) ); // dyn size, possible vectorization \n  TEST_SET_BUT_UNUSED_VARIABLE(s)\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/symbolic_index.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2017 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifdef EIGEN_TEST_PART_2\n#define EIGEN_MAX_CPP_VER 03\n\n// see indexed_view.cpp\n#if defined(__GNUC__) && (__GNUC__ > 4 || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8))\n  #pragma GCC diagnostic ignored \"-Wdeprecated\"\n#endif\n\n#endif\n\n#include \"main.h\"\n\ntemplate<typename T1,typename T2>\nbool is_same_symb(const T1& a, const T2& b, Index size)\n{\n  return a.eval(last=size-1) == b.eval(last=size-1);\n}\n\ntemplate<typename T>\nvoid check_is_symbolic(const T&) {\n  STATIC_CHECK(( symbolic::is_symbolic<T>::value ))\n}\n\ntemplate<typename T>\nvoid check_isnot_symbolic(const T&) {\n  STATIC_CHECK(( !symbolic::is_symbolic<T>::value ))\n}\n\n#define VERIFY_EQ_INT(A,B) VERIFY_IS_APPROX(int(A),int(B))\n\nvoid check_symbolic_index()\n{\n  check_is_symbolic(last);\n  check_is_symbolic(lastp1);\n  check_is_symbolic(last+1);\n  check_is_symbolic(last-lastp1);\n  check_is_symbolic(2*last-lastp1/2);\n  check_isnot_symbolic(fix<3>());\n\n  Index size=100;\n\n  // First, let's check FixedInt arithmetic:\n  VERIFY( is_same_type( (fix<5>()-fix<3>())*fix<9>()/(-fix<3>()), fix<-(5-3)*9/3>() ) );\n  VERIFY( is_same_type( (fix<5>()-fix<3>())*fix<9>()/fix<2>(), fix<(5-3)*9/2>() ) );\n  VERIFY( is_same_type( fix<9>()/fix<2>(), fix<9/2>() ) );\n  VERIFY( is_same_type( fix<9>()%fix<2>(), fix<9%2>() ) );\n  VERIFY( is_same_type( fix<9>()&fix<2>(), fix<9&2>() ) );\n  VERIFY( is_same_type( fix<9>()|fix<2>(), fix<9|2>() ) );\n  VERIFY( is_same_type( fix<9>()/2, int(9/2) ) );\n\n  VERIFY( is_same_symb( lastp1-1, last, size) );\n  VERIFY( is_same_symb( lastp1-fix<1>, last, size) );\n\n  VERIFY_IS_EQUAL( ( (last*5-2)/3 ).eval(last=size-1), ((size-1)*5-2)/3 );\n  VERIFY_IS_EQUAL( ( (last*fix<5>-fix<2>)/fix<3> ).eval(last=size-1), ((size-1)*5-2)/3 );\n  VERIFY_IS_EQUAL( ( -last*lastp1  ).eval(last=size-1), -(size-1)*size );\n  VERIFY_IS_EQUAL( ( lastp1-3*last  ).eval(last=size-1), size- 3*(size-1) );\n  VERIFY_IS_EQUAL( ( (lastp1-3*last)/lastp1  ).eval(last=size-1), (size- 3*(size-1))/size );\n\n#if EIGEN_HAS_CXX14\n  {\n    struct x_tag {};  static const symbolic::SymbolExpr<x_tag> x;\n    struct y_tag {};  static const symbolic::SymbolExpr<y_tag> y;\n    struct z_tag {};  static const symbolic::SymbolExpr<z_tag> z;\n\n    VERIFY_IS_APPROX( int(((x+3)/y+z).eval(x=6,y=3,z=-13)), (6+3)/3+(-13) );\n  }\n#endif\n}\n\nEIGEN_DECLARE_TEST(symbolic_index)\n{\n  CALL_SUBTEST_1( check_symbolic_index() );\n  CALL_SUBTEST_2( check_symbolic_index() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/triangular.cpp",
    "content": "// This file is triangularView of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifdef EIGEN_TEST_PART_100\n#  define EIGEN_NO_DEPRECATED_WARNING\n#endif\n\n#include \"main.h\"\n\n\ntemplate<typename MatrixType> void triangular_deprecated(const MatrixType &m)\n{\n  Index rows = m.rows();\n  Index cols = m.cols();\n  MatrixType m1, m2, m3, m4;\n  m1.setRandom(rows,cols);\n  m2.setRandom(rows,cols);\n  m3 = m1; m4 = m2;\n  // deprecated method:\n  m1.template triangularView<Eigen::Upper>().swap(m2);\n  // use this method instead:\n  m3.template triangularView<Eigen::Upper>().swap(m4.template triangularView<Eigen::Upper>());\n  VERIFY_IS_APPROX(m1,m3);\n  VERIFY_IS_APPROX(m2,m4);\n  // deprecated method:\n  m1.template triangularView<Eigen::Lower>().swap(m4);\n  // use this method instead:\n  m3.template triangularView<Eigen::Lower>().swap(m2.template triangularView<Eigen::Lower>());\n  VERIFY_IS_APPROX(m1,m3);\n  VERIFY_IS_APPROX(m2,m4);\n}\n\n\ntemplate<typename MatrixType> void triangular_square(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> VectorType;\n\n  RealScalar largerEps = 10*test_precision<RealScalar>();\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols),\n             m4(rows, cols),\n             r1(rows, cols),\n             r2(rows, cols);\n  VectorType v2 = VectorType::Random(rows);\n\n  MatrixType m1up = m1.template triangularView<Upper>();\n  MatrixType m2up = m2.template triangularView<Upper>();\n\n  if (rows*cols>1)\n  {\n    VERIFY(m1up.isUpperTriangular());\n    VERIFY(m2up.transpose().isLowerTriangular());\n    VERIFY(!m2.isLowerTriangular());\n  }\n\n//   VERIFY_IS_APPROX(m1up.transpose() * m2, m1.upper().transpose().lower() * m2);\n\n  // test overloaded operator+=\n  r1.setZero();\n  r2.setZero();\n  r1.template triangularView<Upper>() +=  m1;\n  r2 += m1up;\n  VERIFY_IS_APPROX(r1,r2);\n\n  // test overloaded operator=\n  m1.setZero();\n  m1.template triangularView<Upper>() = m2.transpose() + m2;\n  m3 = m2.transpose() + m2;\n  VERIFY_IS_APPROX(m3.template triangularView<Lower>().transpose().toDenseMatrix(), m1);\n\n  // test overloaded operator=\n  m1.setZero();\n  m1.template triangularView<Lower>() = m2.transpose() + m2;\n  VERIFY_IS_APPROX(m3.template triangularView<Lower>().toDenseMatrix(), m1);\n\n  VERIFY_IS_APPROX(m3.template triangularView<Lower>().conjugate().toDenseMatrix(),\n                   m3.conjugate().template triangularView<Lower>().toDenseMatrix());\n\n  m1 = MatrixType::Random(rows, cols);\n  for (int i=0; i<rows; ++i)\n    while (numext::abs2(m1(i,i))<RealScalar(1e-1)) m1(i,i) = internal::random<Scalar>();\n\n  Transpose<MatrixType> trm4(m4);\n  // test back and forward substitution with a vector as the rhs\n  m3 = m1.template triangularView<Upper>();\n  VERIFY(v2.isApprox(m3.adjoint() * (m1.adjoint().template triangularView<Lower>().solve(v2)), largerEps));\n  m3 = m1.template triangularView<Lower>();\n  VERIFY(v2.isApprox(m3.transpose() * (m1.transpose().template triangularView<Upper>().solve(v2)), largerEps));\n  m3 = m1.template triangularView<Upper>();\n  VERIFY(v2.isApprox(m3 * (m1.template triangularView<Upper>().solve(v2)), largerEps));\n  m3 = m1.template triangularView<Lower>();\n  VERIFY(v2.isApprox(m3.conjugate() * (m1.conjugate().template triangularView<Lower>().solve(v2)), largerEps));\n\n  // test back and forward substitution with a matrix as the rhs\n  m3 = m1.template triangularView<Upper>();\n  VERIFY(m2.isApprox(m3.adjoint() * (m1.adjoint().template triangularView<Lower>().solve(m2)), largerEps));\n  m3 = m1.template triangularView<Lower>();\n  VERIFY(m2.isApprox(m3.transpose() * (m1.transpose().template triangularView<Upper>().solve(m2)), largerEps));\n  m3 = m1.template triangularView<Upper>();\n  VERIFY(m2.isApprox(m3 * (m1.template triangularView<Upper>().solve(m2)), largerEps));\n  m3 = m1.template triangularView<Lower>();\n  VERIFY(m2.isApprox(m3.conjugate() * (m1.conjugate().template triangularView<Lower>().solve(m2)), largerEps));\n\n  // check M * inv(L) using in place API\n  m4 = m3;\n  m1.transpose().template triangularView<Eigen::Upper>().solveInPlace(trm4);\n  VERIFY_IS_APPROX(m4 * m1.template triangularView<Eigen::Lower>(), m3);\n\n  // check M * inv(U) using in place API\n  m3 = m1.template triangularView<Upper>();\n  m4 = m3;\n  m3.transpose().template triangularView<Eigen::Lower>().solveInPlace(trm4);\n  VERIFY_IS_APPROX(m4 * m1.template triangularView<Eigen::Upper>(), m3);\n\n  // check solve with unit diagonal\n  m3 = m1.template triangularView<UnitUpper>();\n  VERIFY(m2.isApprox(m3 * (m1.template triangularView<UnitUpper>().solve(m2)), largerEps));\n\n//   VERIFY((  m1.template triangularView<Upper>()\n//           * m2.template triangularView<Upper>()).isUpperTriangular());\n\n  // test swap\n  m1.setOnes();\n  m2.setZero();\n  m2.template triangularView<Upper>().swap(m1.template triangularView<Eigen::Upper>());\n  m3.setZero();\n  m3.template triangularView<Upper>().setOnes();\n  VERIFY_IS_APPROX(m2,m3);\n  VERIFY_RAISES_STATIC_ASSERT(m1.template triangularView<Eigen::Lower>().swap(m2.template triangularView<Eigen::Upper>()));\n\n  m1.setRandom();\n  m3 = m1.template triangularView<Upper>();\n  Matrix<Scalar, MatrixType::ColsAtCompileTime, Dynamic> m5(cols, internal::random<int>(1,20));  m5.setRandom();\n  Matrix<Scalar, Dynamic, MatrixType::RowsAtCompileTime> m6(internal::random<int>(1,20), rows);  m6.setRandom();\n  VERIFY_IS_APPROX(m1.template triangularView<Upper>() * m5, m3*m5);\n  VERIFY_IS_APPROX(m6*m1.template triangularView<Upper>(), m6*m3);\n\n  m1up = m1.template triangularView<Upper>();\n  VERIFY_IS_APPROX(m1.template selfadjointView<Upper>().template triangularView<Upper>().toDenseMatrix(), m1up);\n  VERIFY_IS_APPROX(m1up.template selfadjointView<Upper>().template triangularView<Upper>().toDenseMatrix(), m1up);\n  VERIFY_IS_APPROX(m1.template selfadjointView<Upper>().template triangularView<Lower>().toDenseMatrix(), m1up.adjoint());\n  VERIFY_IS_APPROX(m1up.template selfadjointView<Upper>().template triangularView<Lower>().toDenseMatrix(), m1up.adjoint());\n\n  VERIFY_IS_APPROX(m1.template selfadjointView<Upper>().diagonal(), m1.diagonal());\n\n  m3.setRandom();\n  const MatrixType& m3c(m3);\n  VERIFY( is_same_type(m3c.template triangularView<Lower>(),m3.template triangularView<Lower>().template conjugateIf<false>()) );\n  VERIFY( is_same_type(m3c.template triangularView<Lower>().conjugate(),m3.template triangularView<Lower>().template conjugateIf<true>()) );\n  VERIFY_IS_APPROX(m3.template triangularView<Lower>().template conjugateIf<true>().toDenseMatrix(),\n                   m3.conjugate().template triangularView<Lower>().toDenseMatrix());\n  VERIFY_IS_APPROX(m3.template triangularView<Lower>().template conjugateIf<false>().toDenseMatrix(),\n                   m3.template triangularView<Lower>().toDenseMatrix());\n\n  VERIFY( is_same_type(m3c.template selfadjointView<Lower>(),m3.template selfadjointView<Lower>().template conjugateIf<false>()) );\n  VERIFY( is_same_type(m3c.template selfadjointView<Lower>().conjugate(),m3.template selfadjointView<Lower>().template conjugateIf<true>()) );\n  VERIFY_IS_APPROX(m3.template selfadjointView<Lower>().template conjugateIf<true>().toDenseMatrix(),\n                   m3.conjugate().template selfadjointView<Lower>().toDenseMatrix());\n  VERIFY_IS_APPROX(m3.template selfadjointView<Lower>().template conjugateIf<false>().toDenseMatrix(),\n                   m3.template selfadjointView<Lower>().toDenseMatrix());\n\n}\n\n\ntemplate<typename MatrixType> void triangular_rect(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  enum { Rows =  MatrixType::RowsAtCompileTime, Cols =  MatrixType::ColsAtCompileTime };\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n             m2 = MatrixType::Random(rows, cols),\n             m3(rows, cols),\n             m4(rows, cols),\n             r1(rows, cols),\n             r2(rows, cols);\n\n  MatrixType m1up = m1.template triangularView<Upper>();\n  MatrixType m2up = m2.template triangularView<Upper>();\n\n  if (rows>1 && cols>1)\n  {\n    VERIFY(m1up.isUpperTriangular());\n    VERIFY(m2up.transpose().isLowerTriangular());\n    VERIFY(!m2.isLowerTriangular());\n  }\n\n  // test overloaded operator+=\n  r1.setZero();\n  r2.setZero();\n  r1.template triangularView<Upper>() +=  m1;\n  r2 += m1up;\n  VERIFY_IS_APPROX(r1,r2);\n\n  // test overloaded operator=\n  m1.setZero();\n  m1.template triangularView<Upper>() = 3 * m2;\n  m3 = 3 * m2;\n  VERIFY_IS_APPROX(m3.template triangularView<Upper>().toDenseMatrix(), m1);\n\n\n  m1.setZero();\n  m1.template triangularView<Lower>() = 3 * m2;\n  VERIFY_IS_APPROX(m3.template triangularView<Lower>().toDenseMatrix(), m1);\n\n  m1.setZero();\n  m1.template triangularView<StrictlyUpper>() = 3 * m2;\n  VERIFY_IS_APPROX(m3.template triangularView<StrictlyUpper>().toDenseMatrix(), m1);\n\n\n  m1.setZero();\n  m1.template triangularView<StrictlyLower>() = 3 * m2;\n  VERIFY_IS_APPROX(m3.template triangularView<StrictlyLower>().toDenseMatrix(), m1);\n  m1.setRandom();\n  m2 = m1.template triangularView<Upper>();\n  VERIFY(m2.isUpperTriangular());\n  VERIFY(!m2.isLowerTriangular());\n  m2 = m1.template triangularView<StrictlyUpper>();\n  VERIFY(m2.isUpperTriangular());\n  VERIFY(m2.diagonal().isMuchSmallerThan(RealScalar(1)));\n  m2 = m1.template triangularView<UnitUpper>();\n  VERIFY(m2.isUpperTriangular());\n  m2.diagonal().array() -= Scalar(1);\n  VERIFY(m2.diagonal().isMuchSmallerThan(RealScalar(1)));\n  m2 = m1.template triangularView<Lower>();\n  VERIFY(m2.isLowerTriangular());\n  VERIFY(!m2.isUpperTriangular());\n  m2 = m1.template triangularView<StrictlyLower>();\n  VERIFY(m2.isLowerTriangular());\n  VERIFY(m2.diagonal().isMuchSmallerThan(RealScalar(1)));\n  m2 = m1.template triangularView<UnitLower>();\n  VERIFY(m2.isLowerTriangular());\n  m2.diagonal().array() -= Scalar(1);\n  VERIFY(m2.diagonal().isMuchSmallerThan(RealScalar(1)));\n  // test swap\n  m1.setOnes();\n  m2.setZero();\n  m2.template triangularView<Upper>().swap(m1.template triangularView<Eigen::Upper>());\n  m3.setZero();\n  m3.template triangularView<Upper>().setOnes();\n  VERIFY_IS_APPROX(m2,m3);\n}\n\nvoid bug_159()\n{\n  Matrix3d m = Matrix3d::Random().triangularView<Lower>();\n  EIGEN_UNUSED_VARIABLE(m)\n}\n\nEIGEN_DECLARE_TEST(triangular)\n{\n  int maxsize = (std::min)(EIGEN_TEST_MAX_SIZE,20);\n  for(int i = 0; i < g_repeat ; i++)\n  {\n    int r = internal::random<int>(2,maxsize); TEST_SET_BUT_UNUSED_VARIABLE(r)\n    int c = internal::random<int>(2,maxsize); TEST_SET_BUT_UNUSED_VARIABLE(c)\n\n    CALL_SUBTEST_1( triangular_square(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( triangular_square(Matrix<float, 2, 2>()) );\n    CALL_SUBTEST_3( triangular_square(Matrix3d()) );\n    CALL_SUBTEST_4( triangular_square(Matrix<std::complex<float>,8, 8>()) );\n    CALL_SUBTEST_5( triangular_square(MatrixXcd(r,r)) );\n    CALL_SUBTEST_6( triangular_square(Matrix<float,Dynamic,Dynamic,RowMajor>(r, r)) );\n\n    CALL_SUBTEST_7( triangular_rect(Matrix<float, 4, 5>()) );\n    CALL_SUBTEST_8( triangular_rect(Matrix<double, 6, 2>()) );\n    CALL_SUBTEST_9( triangular_rect(MatrixXcf(r, c)) );\n    CALL_SUBTEST_5( triangular_rect(MatrixXcd(r, c)) );\n    CALL_SUBTEST_6( triangular_rect(Matrix<float,Dynamic,Dynamic,RowMajor>(r, c)) );\n\n    CALL_SUBTEST_100( triangular_deprecated(Matrix<float, 5, 7>()) );\n    CALL_SUBTEST_100( triangular_deprecated(MatrixXd(r,c)) );\n  }\n  \n  CALL_SUBTEST_1( bug_159() );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/type_alias.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2019 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\nEIGEN_DECLARE_TEST(type_alias)\n{\n  using namespace internal;\n\n  // To warm up, some basic checks:\n  STATIC_CHECK((is_same<MatrixXd,Matrix<double,Dynamic,Dynamic> >::value));\n  STATIC_CHECK((is_same<Matrix2f,Matrix<float,2,2> >::value));\n  STATIC_CHECK((is_same<Array33i,Array<int,3,3> >::value));\n\n#if EIGEN_HAS_CXX11\n  \n  STATIC_CHECK((is_same<MatrixX<double>,    MatrixXd>::value));\n  STATIC_CHECK((is_same<MatrixX<int>,       MatrixXi>::value));\n  STATIC_CHECK((is_same<Matrix2<int>,       Matrix2i>::value));\n  STATIC_CHECK((is_same<Matrix2X<float>,    Matrix2Xf>::value));\n  STATIC_CHECK((is_same<MatrixX4<double>,   MatrixX4d>::value));\n  STATIC_CHECK((is_same<VectorX<int>,       VectorXi>::value));\n  STATIC_CHECK((is_same<Vector2<float>,     Vector2f>::value));\n  STATIC_CHECK((is_same<RowVectorX<int>,    RowVectorXi>::value));\n  STATIC_CHECK((is_same<RowVector2<float>,  RowVector2f>::value));\n\n  STATIC_CHECK((is_same<ArrayXX<float>,     ArrayXXf>::value));\n  STATIC_CHECK((is_same<Array33<int>,       Array33i>::value));\n  STATIC_CHECK((is_same<Array2X<float>,     Array2Xf>::value));\n  STATIC_CHECK((is_same<ArrayX4<double>,    ArrayX4d>::value));\n  STATIC_CHECK((is_same<ArrayX<double>,     ArrayXd>::value));\n  STATIC_CHECK((is_same<Array4<double>,     Array4d>::value));\n\n  STATIC_CHECK((is_same<Vector<float,3>,        Vector3f>::value));\n  STATIC_CHECK((is_same<Vector<int,Dynamic>,    VectorXi>::value));\n  STATIC_CHECK((is_same<RowVector<float,3>,     RowVector3f>::value));\n  STATIC_CHECK((is_same<RowVector<int,Dynamic>, RowVectorXi>::value));\n\n#else\n  std::cerr << \"WARNING: c++11 type aliases not tested.\\n\";\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/umeyama.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/Core>\n#include <Eigen/Geometry>\n\n#include <Eigen/LU> // required for MatrixBase::determinant\n#include <Eigen/SVD> // required for SVD\n\nusing namespace Eigen;\n\n//  Constructs a random matrix from the unitary group U(size).\ntemplate <typename T>\nEigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> randMatrixUnitary(int size)\n{\n  typedef T Scalar;\n  typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> MatrixType;\n\n  MatrixType Q;\n\n  int max_tries = 40;\n  bool is_unitary = false;\n\n  while (!is_unitary && max_tries > 0)\n  {\n    // initialize random matrix\n    Q = MatrixType::Random(size, size);\n\n    // orthogonalize columns using the Gram-Schmidt algorithm\n    for (int col = 0; col < size; ++col)\n    {\n      typename MatrixType::ColXpr colVec = Q.col(col);\n      for (int prevCol = 0; prevCol < col; ++prevCol)\n      {\n        typename MatrixType::ColXpr prevColVec = Q.col(prevCol);\n        colVec -= colVec.dot(prevColVec)*prevColVec;\n      }\n      Q.col(col) = colVec.normalized();\n    }\n\n    // this additional orthogonalization is not necessary in theory but should enhance\n    // the numerical orthogonality of the matrix\n    for (int row = 0; row < size; ++row)\n    {\n      typename MatrixType::RowXpr rowVec = Q.row(row);\n      for (int prevRow = 0; prevRow < row; ++prevRow)\n      {\n        typename MatrixType::RowXpr prevRowVec = Q.row(prevRow);\n        rowVec -= rowVec.dot(prevRowVec)*prevRowVec;\n      }\n      Q.row(row) = rowVec.normalized();\n    }\n\n    // final check\n    is_unitary = Q.isUnitary();\n    --max_tries;\n  }\n\n  if (max_tries == 0)\n    eigen_assert(false && \"randMatrixUnitary: Could not construct unitary matrix!\");\n\n  return Q;\n}\n\n//  Constructs a random matrix from the special unitary group SU(size).\ntemplate <typename T>\nEigen::Matrix<T, Eigen::Dynamic, Eigen::Dynamic> randMatrixSpecialUnitary(int size)\n{\n  typedef T Scalar;\n\n  typedef Eigen::Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> MatrixType;\n\n  // initialize unitary matrix\n  MatrixType Q = randMatrixUnitary<Scalar>(size);\n\n  // tweak the first column to make the determinant be 1\n  Q.col(0) *= numext::conj(Q.determinant());\n\n  return Q;\n}\n\ntemplate <typename MatrixType>\nvoid run_test(int dim, int num_elements)\n{\n  using std::abs;\n  typedef typename internal::traits<MatrixType>::Scalar Scalar;\n  typedef Matrix<Scalar, Eigen::Dynamic, Eigen::Dynamic> MatrixX;\n  typedef Matrix<Scalar, Eigen::Dynamic, 1> VectorX;\n\n  // MUST be positive because in any other case det(cR_t) may become negative for\n  // odd dimensions!\n  const Scalar c = abs(internal::random<Scalar>());\n\n  MatrixX R = randMatrixSpecialUnitary<Scalar>(dim);\n  VectorX t = Scalar(50)*VectorX::Random(dim,1);\n\n  MatrixX cR_t = MatrixX::Identity(dim+1,dim+1);\n  cR_t.block(0,0,dim,dim) = c*R;\n  cR_t.block(0,dim,dim,1) = t;\n\n  MatrixX src = MatrixX::Random(dim+1, num_elements);\n  src.row(dim) = Matrix<Scalar, 1, Dynamic>::Constant(num_elements, Scalar(1));\n\n  MatrixX dst = cR_t*src;\n\n  MatrixX cR_t_umeyama = umeyama(src.block(0,0,dim,num_elements), dst.block(0,0,dim,num_elements));\n\n  const Scalar error = ( cR_t_umeyama*src - dst ).norm() / dst.norm();\n  VERIFY(error < Scalar(40)*std::numeric_limits<Scalar>::epsilon());\n}\n\ntemplate<typename Scalar, int Dimension>\nvoid run_fixed_size_test(int num_elements)\n{\n  using std::abs;\n  typedef Matrix<Scalar, Dimension+1, Dynamic> MatrixX;\n  typedef Matrix<Scalar, Dimension+1, Dimension+1> HomMatrix;\n  typedef Matrix<Scalar, Dimension, Dimension> FixedMatrix;\n  typedef Matrix<Scalar, Dimension, 1> FixedVector;\n\n  const int dim = Dimension;\n\n  // MUST be positive because in any other case det(cR_t) may become negative for\n  // odd dimensions!\n  // Also if c is to small compared to t.norm(), problem is ill-posed (cf. Bug 744)\n  const Scalar c = internal::random<Scalar>(0.5, 2.0);\n\n  FixedMatrix R = randMatrixSpecialUnitary<Scalar>(dim);\n  FixedVector t = Scalar(32)*FixedVector::Random(dim,1);\n\n  HomMatrix cR_t = HomMatrix::Identity(dim+1,dim+1);\n  cR_t.block(0,0,dim,dim) = c*R;\n  cR_t.block(0,dim,dim,1) = t;\n\n  MatrixX src = MatrixX::Random(dim+1, num_elements);\n  src.row(dim) = Matrix<Scalar, 1, Dynamic>::Constant(num_elements, Scalar(1));\n\n  MatrixX dst = cR_t*src;\n\n  Block<MatrixX, Dimension, Dynamic> src_block(src,0,0,dim,num_elements);\n  Block<MatrixX, Dimension, Dynamic> dst_block(dst,0,0,dim,num_elements);\n\n  HomMatrix cR_t_umeyama = umeyama(src_block, dst_block);\n\n  const Scalar error = ( cR_t_umeyama*src - dst ).squaredNorm();\n\n  VERIFY(error < Scalar(16)*std::numeric_limits<Scalar>::epsilon());\n}\n\nEIGEN_DECLARE_TEST(umeyama)\n{\n  for (int i=0; i<g_repeat; ++i)\n  {\n    const int num_elements = internal::random<int>(40,500);\n\n    // works also for dimensions bigger than 3...\n    for (int dim=2; dim<8; ++dim)\n    {\n      CALL_SUBTEST_1(run_test<MatrixXd>(dim, num_elements));\n      CALL_SUBTEST_2(run_test<MatrixXf>(dim, num_elements));\n    }\n\n    CALL_SUBTEST_3((run_fixed_size_test<float, 2>(num_elements)));\n    CALL_SUBTEST_4((run_fixed_size_test<float, 3>(num_elements)));\n    CALL_SUBTEST_5((run_fixed_size_test<float, 4>(num_elements)));\n\n    CALL_SUBTEST_6((run_fixed_size_test<double, 2>(num_elements)));\n    CALL_SUBTEST_7((run_fixed_size_test<double, 3>(num_elements)));\n    CALL_SUBTEST_8((run_fixed_size_test<double, 4>(num_elements)));\n  }\n\n  // Those two calls don't compile and result in meaningful error messages!\n  // umeyama(MatrixXcf(),MatrixXcf());\n  // umeyama(MatrixXcd(),MatrixXcd());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/umfpack_support.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_NO_DEBUG_SMALL_PRODUCT_BLOCKS\n#include \"sparse_solver.h\"\n\n#include <Eigen/UmfPackSupport>\n\ntemplate<typename T1, typename T2> void test_umfpack_support_T()\n{\n  UmfPackLU<SparseMatrix<T1, ColMajor, T2> > umfpack_colmajor;\n  UmfPackLU<SparseMatrix<T1, RowMajor, T2> > umfpack_rowmajor;\n  \n  check_sparse_square_solving(umfpack_colmajor);\n  check_sparse_square_solving(umfpack_rowmajor);\n  \n  check_sparse_square_determinant(umfpack_colmajor);\n  check_sparse_square_determinant(umfpack_rowmajor);\n}\n\nEIGEN_DECLARE_TEST(umfpack_support)\n{\n  CALL_SUBTEST_1((test_umfpack_support_T<double, int>()));\n  CALL_SUBTEST_2((test_umfpack_support_T<std::complex<double>, int>()));\n  CALL_SUBTEST_3((test_umfpack_support_T<double, long >()));\n  CALL_SUBTEST_4((test_umfpack_support_T<std::complex<double>, long>()));\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/unalignedassert.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#if defined(EIGEN_TEST_PART_1)\n  // default\n#elif defined(EIGEN_TEST_PART_2)\n  #define EIGEN_MAX_STATIC_ALIGN_BYTES 16\n  #define EIGEN_MAX_ALIGN_BYTES 16\n#elif defined(EIGEN_TEST_PART_3)\n  #define EIGEN_MAX_STATIC_ALIGN_BYTES 32\n  #define EIGEN_MAX_ALIGN_BYTES 32\n#elif defined(EIGEN_TEST_PART_4)\n  #define EIGEN_MAX_STATIC_ALIGN_BYTES 64\n  #define EIGEN_MAX_ALIGN_BYTES 64\n#endif\n\n#include \"main.h\"\n\ntypedef Matrix<float,  6,1> Vector6f;\ntypedef Matrix<float,  8,1> Vector8f;\ntypedef Matrix<float, 12,1> Vector12f;\n\ntypedef Matrix<double, 5,1> Vector5d;\ntypedef Matrix<double, 6,1> Vector6d;\ntypedef Matrix<double, 7,1> Vector7d;\ntypedef Matrix<double, 8,1> Vector8d;\ntypedef Matrix<double, 9,1> Vector9d;\ntypedef Matrix<double,10,1> Vector10d;\ntypedef Matrix<double,12,1> Vector12d;\n\nstruct TestNew1\n{\n  MatrixXd m; // good: m will allocate its own array, taking care of alignment.\n  TestNew1() : m(20,20) {}\n};\n\nstruct TestNew2\n{\n  Matrix3d m; // good: m's size isn't a multiple of 16 bytes, so m doesn't have to be 16-byte aligned,\n              // 8-byte alignment is good enough here, which we'll get automatically\n};\n\nstruct TestNew3\n{\n  Vector2f m; // good: m's size isn't a multiple of 16 bytes, so m doesn't have to be 16-byte aligned\n};\n\nstruct TestNew4\n{\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n  Vector2d m;\n  float f; // make the struct have sizeof%16!=0 to make it a little more tricky when we allow an array of 2 such objects\n};\n\nstruct TestNew5\n{\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW\n  float f; // try the f at first -- the EIGEN_ALIGN_MAX attribute of m should make that still work\n  Matrix4f m;\n};\n\nstruct TestNew6\n{\n  Matrix<float,2,2,DontAlign> m; // good: no alignment requested\n  float f;\n};\n\ntemplate<bool Align> struct Depends\n{\n  EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF(Align)\n  Vector2d m;\n  float f;\n};\n\ntemplate<typename T>\nvoid check_unalignedassert_good()\n{\n  T *x, *y;\n  x = new T;\n  delete x;\n  y = new T[2];\n  delete[] y;\n}\n\n#if EIGEN_MAX_STATIC_ALIGN_BYTES>0\ntemplate<typename T>\nvoid construct_at_boundary(int boundary)\n{\n  char buf[sizeof(T)+256];\n  size_t _buf = reinterpret_cast<internal::UIntPtr>(buf);\n  _buf += (EIGEN_MAX_ALIGN_BYTES - (_buf % EIGEN_MAX_ALIGN_BYTES)); // make 16/32/...-byte aligned\n  _buf += boundary; // make exact boundary-aligned\n  T *x = ::new(reinterpret_cast<void*>(_buf)) T;\n  x[0].setZero(); // just in order to silence warnings\n  x->~T();\n}\n#endif\n\nvoid unalignedassert()\n{\n#if EIGEN_MAX_STATIC_ALIGN_BYTES>0\n  construct_at_boundary<Vector2f>(4);\n  construct_at_boundary<Vector3f>(4);\n  construct_at_boundary<Vector4f>(16);\n  construct_at_boundary<Vector6f>(4);\n  construct_at_boundary<Vector8f>(EIGEN_MAX_ALIGN_BYTES);\n  construct_at_boundary<Vector12f>(16);\n  construct_at_boundary<Matrix2f>(16);\n  construct_at_boundary<Matrix3f>(4);\n  construct_at_boundary<Matrix4f>(EIGEN_MAX_ALIGN_BYTES);\n\n  construct_at_boundary<Vector2d>(16);\n  construct_at_boundary<Vector3d>(4);\n  construct_at_boundary<Vector4d>(EIGEN_MAX_ALIGN_BYTES);\n  construct_at_boundary<Vector5d>(4);\n  construct_at_boundary<Vector6d>(16);\n  construct_at_boundary<Vector7d>(4);\n  construct_at_boundary<Vector8d>(EIGEN_MAX_ALIGN_BYTES);\n  construct_at_boundary<Vector9d>(4);\n  construct_at_boundary<Vector10d>(16);\n  construct_at_boundary<Vector12d>(EIGEN_MAX_ALIGN_BYTES);\n  construct_at_boundary<Matrix2d>(EIGEN_MAX_ALIGN_BYTES);\n  construct_at_boundary<Matrix3d>(4);\n  construct_at_boundary<Matrix4d>(EIGEN_MAX_ALIGN_BYTES);\n\n  construct_at_boundary<Vector2cf>(16);\n  construct_at_boundary<Vector3cf>(4);\n  construct_at_boundary<Vector2cd>(EIGEN_MAX_ALIGN_BYTES);\n  construct_at_boundary<Vector3cd>(16);\n#endif\n\n  check_unalignedassert_good<TestNew1>();\n  check_unalignedassert_good<TestNew2>();\n  check_unalignedassert_good<TestNew3>();\n\n  check_unalignedassert_good<TestNew4>();\n  check_unalignedassert_good<TestNew5>();\n  check_unalignedassert_good<TestNew6>();\n  check_unalignedassert_good<Depends<true> >();\n\n#if EIGEN_MAX_STATIC_ALIGN_BYTES>0\n  if(EIGEN_MAX_ALIGN_BYTES>=16)\n  {\n    VERIFY_RAISES_ASSERT(construct_at_boundary<Vector4f>(8));\n    VERIFY_RAISES_ASSERT(construct_at_boundary<Vector8f>(8));\n    VERIFY_RAISES_ASSERT(construct_at_boundary<Vector12f>(8));\n    VERIFY_RAISES_ASSERT(construct_at_boundary<Vector2d>(8));\n    VERIFY_RAISES_ASSERT(construct_at_boundary<Vector4d>(8));\n    VERIFY_RAISES_ASSERT(construct_at_boundary<Vector6d>(8));\n    VERIFY_RAISES_ASSERT(construct_at_boundary<Vector8d>(8));\n    VERIFY_RAISES_ASSERT(construct_at_boundary<Vector10d>(8));\n    VERIFY_RAISES_ASSERT(construct_at_boundary<Vector12d>(8));\n    // Complexes are disabled because the compiler might aggressively vectorize\n    // the initialization of complex coeffs to 0 before we can check for alignedness\n    //VERIFY_RAISES_ASSERT(construct_at_boundary<Vector2cf>(8));\n    VERIFY_RAISES_ASSERT(construct_at_boundary<Vector4i>(8));\n  }\n  for(int b=8; b<EIGEN_MAX_ALIGN_BYTES; b+=8)\n  {\n    if(b<32)  VERIFY_RAISES_ASSERT(construct_at_boundary<Vector8f>(b));\n    if(b<64)  VERIFY_RAISES_ASSERT(construct_at_boundary<Matrix4f>(b));\n    if(b<32)  VERIFY_RAISES_ASSERT(construct_at_boundary<Vector4d>(b));\n    if(b<32)  VERIFY_RAISES_ASSERT(construct_at_boundary<Matrix2d>(b));\n    if(b<128) VERIFY_RAISES_ASSERT(construct_at_boundary<Matrix4d>(b));\n    //if(b<32)  VERIFY_RAISES_ASSERT(construct_at_boundary<Vector2cd>(b));\n  }\n#endif\n}\n\nEIGEN_DECLARE_TEST(unalignedassert)\n{\n  CALL_SUBTEST(unalignedassert());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/unalignedcount.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\nstatic int nb_load;\nstatic int nb_loadu;\nstatic int nb_store;\nstatic int nb_storeu;\n\n#define EIGEN_DEBUG_ALIGNED_LOAD    { nb_load++;    }\n#define EIGEN_DEBUG_UNALIGNED_LOAD  { nb_loadu++;   }\n#define EIGEN_DEBUG_ALIGNED_STORE   { nb_store++;   }\n#define EIGEN_DEBUG_UNALIGNED_STORE { nb_storeu++;  }\n\n#define VERIFY_ALIGNED_UNALIGNED_COUNT(XPR,AL,UL,AS,US) {\\\n    nb_load = nb_loadu = nb_store = nb_storeu = 0; \\\n    XPR; \\\n    if(!(nb_load==AL && nb_loadu==UL && nb_store==AS && nb_storeu==US)) \\\n      std::cerr << \" >> \" << nb_load << \", \" << nb_loadu << \", \" << nb_store << \", \" << nb_storeu << \"\\n\"; \\\n    VERIFY( (#XPR) && nb_load==AL && nb_loadu==UL && nb_store==AS && nb_storeu==US ); \\\n  }\n\n\n#include \"main.h\"\n\nEIGEN_DECLARE_TEST(unalignedcount)\n{\n  #if defined(EIGEN_VECTORIZE_AVX512)\n  VectorXf a(48), b(48);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a += b, 6, 0, 3, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,48) += b.segment(0,48), 3, 3, 3, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,48) -= b.segment(0,48), 3, 3, 3, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,48) *= 3.5, 3, 0, 3, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,48) /= 3.5, 3, 0, 3, 0);\n  #elif defined(EIGEN_VECTORIZE_AVX)\n  VectorXf a(40), b(40);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a += b, 10, 0, 5, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) += b.segment(0,40), 5, 5, 5, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) -= b.segment(0,40), 5, 5, 5, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) *= 3.5, 5, 0, 5, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) /= 3.5, 5, 0, 5, 0);\n  #elif defined(EIGEN_VECTORIZE_SSE)\n  VectorXf a(40), b(40);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a += b, 20, 0, 10, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) += b.segment(0,40), 10, 10, 10, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) -= b.segment(0,40), 10, 10, 10, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) *= 3.5, 10, 0, 10, 0);\n  VERIFY_ALIGNED_UNALIGNED_COUNT(a.segment(0,40) /= 3.5, 10, 0, 10, 0);\n  #else\n  // The following line is to eliminate \"variable not used\" warnings\n  nb_load = nb_loadu = nb_store = nb_storeu = 0;\n  int a(0), b(0);\n  VERIFY(a==b);\n  #endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/upperbidiagonalization.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/SVD>\n\ntemplate<typename MatrixType> void upperbidiag(const MatrixType& m)\n{\n  const Index rows = m.rows();\n  const Index cols = m.cols();\n\n  typedef Matrix<typename MatrixType::RealScalar, MatrixType::RowsAtCompileTime,  MatrixType::ColsAtCompileTime> RealMatrixType;\n  typedef Matrix<typename MatrixType::Scalar, MatrixType::ColsAtCompileTime,  MatrixType::RowsAtCompileTime> TransposeMatrixType;\n\n  MatrixType a = MatrixType::Random(rows,cols);\n  internal::UpperBidiagonalization<MatrixType> ubd(a);\n  RealMatrixType b(rows, cols);\n  b.setZero();\n  b.block(0,0,cols,cols) = ubd.bidiagonal();\n  MatrixType c = ubd.householderU() * b * ubd.householderV().adjoint();\n  VERIFY_IS_APPROX(a,c);\n  TransposeMatrixType d = ubd.householderV() * b.adjoint() * ubd.householderU().adjoint();\n  VERIFY_IS_APPROX(a.adjoint(),d);\n}\n\nEIGEN_DECLARE_TEST(upperbidiagonalization)\n{\n  for(int i = 0; i < g_repeat; i++) {\n   CALL_SUBTEST_1( upperbidiag(MatrixXf(3,3)) );\n   CALL_SUBTEST_2( upperbidiag(MatrixXd(17,12)) );\n   CALL_SUBTEST_3( upperbidiag(MatrixXcf(20,20)) );\n   CALL_SUBTEST_4( upperbidiag(Matrix<std::complex<double>,Dynamic,Dynamic,RowMajor>(16,15)) );\n   CALL_SUBTEST_5( upperbidiag(Matrix<float,6,4>()) );\n   CALL_SUBTEST_6( upperbidiag(Matrix<float,5,5>()) );\n   CALL_SUBTEST_7( upperbidiag(Matrix<double,4,3>()) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/vectorization_logic.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifdef EIGEN_TEST_PART_1\n#define EIGEN_UNALIGNED_VECTORIZE 1\n#endif\n\n#ifdef EIGEN_TEST_PART_2\n#define EIGEN_UNALIGNED_VECTORIZE 0\n#endif\n\n#ifdef EIGEN_DEFAULT_TO_ROW_MAJOR\n#undef EIGEN_DEFAULT_TO_ROW_MAJOR\n#endif\n#define EIGEN_DEBUG_ASSIGN\n#include \"main.h\"\n#include <typeinfo>\n\n// Disable \"ignoring attributes on template argument\"\n// for packet_traits<Packet*>\n// => The only workaround would be to wrap _m128 and the likes\n//    within wrappers.\n#if EIGEN_GNUC_AT_LEAST(6,0)\n    #pragma GCC diagnostic ignored \"-Wignored-attributes\"\n#endif\n\nusing internal::demangle_flags;\nusing internal::demangle_traversal;\nusing internal::demangle_unrolling;\n\ntemplate<typename Dst, typename Src>\nbool test_assign(const Dst&, const Src&, int traversal, int unrolling)\n{\n  EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Dst,Src);\n  typedef internal::copy_using_evaluator_traits<internal::evaluator<Dst>,internal::evaluator<Src>, internal::assign_op<typename Dst::Scalar,typename Src::Scalar> > traits;\n  bool res = traits::Traversal==traversal;\n  if(unrolling==InnerUnrolling+CompleteUnrolling)\n    res = res && (int(traits::Unrolling)==InnerUnrolling || int(traits::Unrolling)==CompleteUnrolling);\n  else\n    res = res && int(traits::Unrolling)==unrolling;\n  if(!res)\n  {\n    std::cerr << \"Src: \" << demangle_flags(Src::Flags) << std::endl;\n    std::cerr << \"     \" << demangle_flags(internal::evaluator<Src>::Flags) << std::endl;\n    std::cerr << \"Dst: \" << demangle_flags(Dst::Flags) << std::endl;\n    std::cerr << \"     \" << demangle_flags(internal::evaluator<Dst>::Flags) << std::endl;\n    traits::debug();\n    std::cerr << \" Expected Traversal == \" << demangle_traversal(traversal)\n              << \" got \" << demangle_traversal(traits::Traversal) << \"\\n\";\n    std::cerr << \" Expected Unrolling == \" << demangle_unrolling(unrolling)\n              << \" got \" << demangle_unrolling(traits::Unrolling) << \"\\n\";\n  }\n  return res;\n}\n\ntemplate<typename Dst, typename Src>\nbool test_assign(int traversal, int unrolling)\n{\n  EIGEN_STATIC_ASSERT_SAME_MATRIX_SIZE(Dst,Src);\n  typedef internal::copy_using_evaluator_traits<internal::evaluator<Dst>,internal::evaluator<Src>, internal::assign_op<typename Dst::Scalar,typename Src::Scalar> > traits;\n  bool res = traits::Traversal==traversal && traits::Unrolling==unrolling;\n  if(!res)\n  {\n    std::cerr << \"Src: \" << demangle_flags(Src::Flags) << std::endl;\n    std::cerr << \"     \" << demangle_flags(internal::evaluator<Src>::Flags) << std::endl;\n    std::cerr << \"Dst: \" << demangle_flags(Dst::Flags) << std::endl;\n    std::cerr << \"     \" << demangle_flags(internal::evaluator<Dst>::Flags) << std::endl;\n    traits::debug();\n    std::cerr << \" Expected Traversal == \" << demangle_traversal(traversal)\n              << \" got \" << demangle_traversal(traits::Traversal) << \"\\n\";\n    std::cerr << \" Expected Unrolling == \" << demangle_unrolling(unrolling)\n              << \" got \" << demangle_unrolling(traits::Unrolling) << \"\\n\";\n  }\n  return res;\n}\n\ntemplate<typename Xpr>\nbool test_redux(const Xpr&, int traversal, int unrolling)\n{\n  typedef typename Xpr::Scalar Scalar;\n  typedef internal::redux_traits<internal::scalar_sum_op<Scalar,Scalar>,internal::redux_evaluator<Xpr> > traits;\n  \n  bool res = traits::Traversal==traversal && traits::Unrolling==unrolling;\n  if(!res)\n  {\n    std::cerr << demangle_flags(Xpr::Flags) << std::endl;\n    std::cerr << demangle_flags(internal::evaluator<Xpr>::Flags) << std::endl;\n    traits::debug();\n    \n    std::cerr << \" Expected Traversal == \" << demangle_traversal(traversal)\n              << \" got \" << demangle_traversal(traits::Traversal) << \"\\n\";\n    std::cerr << \" Expected Unrolling == \" << demangle_unrolling(unrolling)\n              << \" got \" << demangle_unrolling(traits::Unrolling) << \"\\n\";\n  }\n  return res;\n}\n\ntemplate<typename Scalar, bool Enable = internal::packet_traits<Scalar>::Vectorizable>\nstruct vectorization_logic\n{\n  typedef internal::packet_traits<Scalar> PacketTraits;\n  \n  typedef typename internal::packet_traits<Scalar>::type PacketType;\n  typedef typename internal::unpacket_traits<PacketType>::half HalfPacketType;\n  enum {\n    PacketSize = internal::unpacket_traits<PacketType>::size,\n    HalfPacketSize = internal::unpacket_traits<HalfPacketType>::size\n  };\n  static void run()\n  {\n    \n    typedef Matrix<Scalar,PacketSize,1> Vector1;\n    typedef Matrix<Scalar,Dynamic,1> VectorX;\n    typedef Matrix<Scalar,Dynamic,Dynamic> MatrixXX;\n    typedef Matrix<Scalar,PacketSize,PacketSize> Matrix11;\n    typedef Matrix<Scalar,(Matrix11::Flags&RowMajorBit)?8:2*PacketSize,(Matrix11::Flags&RowMajorBit)?2*PacketSize:8>   Matrix22;\n    typedef Matrix<Scalar,(Matrix11::Flags&RowMajorBit)?16:4*PacketSize,(Matrix11::Flags&RowMajorBit)?4*PacketSize:16> Matrix44;\n    typedef Matrix<Scalar,(Matrix11::Flags&RowMajorBit)?16:4*PacketSize,(Matrix11::Flags&RowMajorBit)?4*PacketSize:16,DontAlign|EIGEN_DEFAULT_MATRIX_STORAGE_ORDER_OPTION> Matrix44u;\n    typedef Matrix<Scalar,4*PacketSize,4*PacketSize,ColMajor> Matrix44c;\n    typedef Matrix<Scalar,4*PacketSize,4*PacketSize,RowMajor> Matrix44r;\n\n    typedef Matrix<Scalar,\n        (PacketSize==16 ? 8 : PacketSize==8 ? 4 : PacketSize==4 ? 2 : PacketSize==2 ? 1 : /*PacketSize==1 ?*/ 1),\n        (PacketSize==16 ? 2 : PacketSize==8 ? 2 : PacketSize==4 ? 2 : PacketSize==2 ? 2 : /*PacketSize==1 ?*/ 1)\n      > Matrix1;\n\n    typedef Matrix<Scalar,\n        (PacketSize==16 ? 8 : PacketSize==8 ? 4 : PacketSize==4 ? 2 : PacketSize==2 ? 1 : /*PacketSize==1 ?*/ 1),\n        (PacketSize==16 ? 2 : PacketSize==8 ? 2 : PacketSize==4 ? 2 : PacketSize==2 ? 2 : /*PacketSize==1 ?*/ 1),\n      DontAlign|((Matrix1::Flags&RowMajorBit)?RowMajor:ColMajor)> Matrix1u;\n\n    // this type is made such that it can only be vectorized when viewed as a linear 1D vector\n    typedef Matrix<Scalar,\n        (PacketSize==16 ?  4 : PacketSize==8 ? 4 : PacketSize==4 ? 6 : PacketSize==2 ? ((Matrix11::Flags&RowMajorBit)?2:3) : /*PacketSize==1 ?*/ 1),\n        (PacketSize==16 ? 12 : PacketSize==8 ? 6 : PacketSize==4 ? 2 : PacketSize==2 ? ((Matrix11::Flags&RowMajorBit)?3:2) : /*PacketSize==1 ?*/ 3)\n      > Matrix3;\n    \n    #if !EIGEN_GCC_AND_ARCH_DOESNT_WANT_STACK_ALIGNMENT\n    VERIFY(test_assign(Vector1(),Vector1(),\n      InnerVectorizedTraversal,CompleteUnrolling));\n    VERIFY(test_assign(Vector1(),Vector1()+Vector1(),\n      InnerVectorizedTraversal,CompleteUnrolling));\n    VERIFY(test_assign(Vector1(),Vector1().cwiseProduct(Vector1()),\n      InnerVectorizedTraversal,CompleteUnrolling));\n    VERIFY(test_assign(Vector1(),Vector1().template cast<Scalar>(),\n      InnerVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_assign(Matrix44(),Matrix44()+Matrix44(),\n      InnerVectorizedTraversal,InnerUnrolling));\n\n    VERIFY(test_assign(Matrix44u(),Matrix44()+Matrix44(),\n      EIGEN_UNALIGNED_VECTORIZE ? InnerVectorizedTraversal : LinearTraversal,\n      EIGEN_UNALIGNED_VECTORIZE ? InnerUnrolling : NoUnrolling));\n\n    VERIFY(test_assign(Matrix1(),Matrix1()+Matrix1(),\n      (Matrix1::InnerSizeAtCompileTime % PacketSize)==0 ? InnerVectorizedTraversal : LinearVectorizedTraversal,\n      CompleteUnrolling));\n\n    VERIFY(test_assign(Matrix1u(),Matrix1()+Matrix1(),\n      EIGEN_UNALIGNED_VECTORIZE ? ((Matrix1::InnerSizeAtCompileTime % PacketSize)==0 ? InnerVectorizedTraversal : LinearVectorizedTraversal)\n                                : LinearTraversal, CompleteUnrolling));\n\n    VERIFY(test_assign(Matrix44c().col(1),Matrix44c().col(2)+Matrix44c().col(3),\n      InnerVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_assign(Matrix44r().row(2),Matrix44r().row(1)+Matrix44r().row(1),\n      InnerVectorizedTraversal,CompleteUnrolling));\n\n    if(PacketSize>1)\n    {\n      typedef Matrix<Scalar,3,3,ColMajor> Matrix33c;\n      typedef Matrix<Scalar,3,1,ColMajor> Vector3;\n      VERIFY(test_assign(Matrix33c().row(2),Matrix33c().row(1)+Matrix33c().row(1),\n        LinearTraversal,CompleteUnrolling));\n      VERIFY(test_assign(Vector3(),Vector3()+Vector3(),\n        sizeof(Scalar)==16 ? InnerVectorizedTraversal : (EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : LinearTraversal), CompleteUnrolling));\n      VERIFY(test_assign(Matrix33c().col(0),Matrix33c().col(1)+Matrix33c().col(1),\n        EIGEN_UNALIGNED_VECTORIZE ? (sizeof(Scalar)==16 ? InnerVectorizedTraversal : LinearVectorizedTraversal)\n                                  : (sizeof(Scalar)==16 ? SliceVectorizedTraversal : LinearTraversal),\n        ((!EIGEN_UNALIGNED_VECTORIZE) && (sizeof(Scalar)==16)) ? NoUnrolling : CompleteUnrolling));\n\n      VERIFY(test_assign(Matrix3(),Matrix3().cwiseProduct(Matrix3()),\n        LinearVectorizedTraversal,CompleteUnrolling));\n\n      VERIFY(test_assign(Matrix<Scalar,17,17>(),Matrix<Scalar,17,17>()+Matrix<Scalar,17,17>(),\n        sizeof(Scalar)==16        ? InnerVectorizedTraversal  :\n        EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal :\n                                    LinearTraversal,\n        NoUnrolling));\n\n      VERIFY(test_assign(Matrix11(), Matrix11()+Matrix11(),InnerVectorizedTraversal,CompleteUnrolling));\n\n\n      VERIFY(test_assign(Matrix11(),Matrix<Scalar,21,21>().template block<PacketSize,PacketSize>(2,3)+Matrix<Scalar,21,21>().template block<PacketSize,PacketSize>(3,2),\n        (EIGEN_UNALIGNED_VECTORIZE) ? InnerVectorizedTraversal : DefaultTraversal, CompleteUnrolling|InnerUnrolling));\n\n      VERIFY(test_assign(Vector1(),Matrix11()*Vector1(),\n                         InnerVectorizedTraversal,CompleteUnrolling));\n\n      VERIFY(test_assign(Matrix11(),Matrix11().lazyProduct(Matrix11()),\n                         InnerVectorizedTraversal,InnerUnrolling+CompleteUnrolling));\n    }\n\n    VERIFY(test_redux(Vector1(),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_redux(Vector1().array()*Vector1().array(),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_redux((Vector1().array()*Vector1().array()).col(0),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_redux(Matrix<Scalar,PacketSize,3>(),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_redux(Matrix3(),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_redux(Matrix44(),\n      LinearVectorizedTraversal,NoUnrolling));\n\n    if(PacketSize>1) {\n      VERIFY(test_redux(Matrix44().template block<(Matrix1::Flags&RowMajorBit)?4:PacketSize,(Matrix1::Flags&RowMajorBit)?PacketSize:4>(1,2),\n        SliceVectorizedTraversal,CompleteUnrolling));\n\n      VERIFY(test_redux(Matrix44().template block<(Matrix1::Flags&RowMajorBit)?2:PacketSize,(Matrix1::Flags&RowMajorBit)?PacketSize:2>(1,2),\n        DefaultTraversal,CompleteUnrolling));\n    }\n\n    VERIFY(test_redux(Matrix44c().template block<2*PacketSize,1>(1,2),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_redux(Matrix44r().template block<1,2*PacketSize>(2,1),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY((test_assign<\n            Map<Matrix22, AlignedMax, OuterStride<3*PacketSize> >,\n            Matrix22\n            >(InnerVectorizedTraversal,CompleteUnrolling)));\n\n    VERIFY((test_assign<\n            Map<Matrix<Scalar,EIGEN_PLAIN_ENUM_MAX(2,PacketSize),EIGEN_PLAIN_ENUM_MAX(2,PacketSize)>, AlignedMax, InnerStride<3*PacketSize> >,\n            Matrix<Scalar,EIGEN_PLAIN_ENUM_MAX(2,PacketSize),EIGEN_PLAIN_ENUM_MAX(2,PacketSize)>\n            >(DefaultTraversal,PacketSize>=8?InnerUnrolling:CompleteUnrolling)));\n\n    VERIFY((test_assign(Matrix11(), Matrix<Scalar,PacketSize,EIGEN_PLAIN_ENUM_MIN(2,PacketSize)>()*Matrix<Scalar,EIGEN_PLAIN_ENUM_MIN(2,PacketSize),PacketSize>(),\n                        InnerVectorizedTraversal, CompleteUnrolling)));\n    #endif\n\n    VERIFY(test_assign(MatrixXX(10,10),MatrixXX(20,20).block(10,10,2,3),\n      SliceVectorizedTraversal,NoUnrolling));\n\n    VERIFY(test_redux(VectorX(10),\n      LinearVectorizedTraversal,NoUnrolling));\n  }\n};\n\ntemplate<typename Scalar> struct vectorization_logic<Scalar,false>\n{\n  static void run() {}\n};\n\ntemplate<typename Scalar, bool Enable = !internal::is_same<typename internal::unpacket_traits<typename internal::packet_traits<Scalar>::type>::half,\n                                                           typename internal::packet_traits<Scalar>::type>::value >\nstruct vectorization_logic_half\n{\n  typedef internal::packet_traits<Scalar> PacketTraits;\n  typedef typename internal::unpacket_traits<typename internal::packet_traits<Scalar>::type>::half PacketType;\n  enum {\n    PacketSize = internal::unpacket_traits<PacketType>::size\n  };\n  static void run()\n  {\n    \n    typedef Matrix<Scalar,PacketSize,1> Vector1;\n    typedef Matrix<Scalar,PacketSize,PacketSize> Matrix11;\n    typedef Matrix<Scalar,5*PacketSize,7,ColMajor> Matrix57;\n    typedef Matrix<Scalar,3*PacketSize,5,ColMajor> Matrix35;\n    typedef Matrix<Scalar,5*PacketSize,7,DontAlign|ColMajor> Matrix57u;\n\n    typedef Matrix<Scalar,\n        (PacketSize==16 ? 8 : PacketSize==8 ? 4 : PacketSize==4 ? 2 : PacketSize==2 ? 1 : /*PacketSize==1 ?*/ 1),\n        (PacketSize==16 ? 2 : PacketSize==8 ? 2 : PacketSize==4 ? 2 : PacketSize==2 ? 2 : /*PacketSize==1 ?*/ 1)\n      > Matrix1;\n\n    typedef Matrix<Scalar,\n        (PacketSize==16 ? 8 : PacketSize==8 ? 4 : PacketSize==4 ? 2 : PacketSize==2 ? 1 : /*PacketSize==1 ?*/ 1),\n        (PacketSize==16 ? 2 : PacketSize==8 ? 2 : PacketSize==4 ? 2 : PacketSize==2 ? 2 : /*PacketSize==1 ?*/ 1),\n      DontAlign|((Matrix1::Flags&RowMajorBit)?RowMajor:ColMajor)> Matrix1u;\n\n    // this type is made such that it can only be vectorized when viewed as a linear 1D vector\n    typedef Matrix<Scalar,\n        (PacketSize==16 ?  4 : PacketSize==8 ? 4 : PacketSize==4 ? 6 : PacketSize==2 ? ((Matrix11::Flags&RowMajorBit)?2:3) : /*PacketSize==1 ?*/ 1),\n        (PacketSize==16 ? 12 : PacketSize==8 ? 6 : PacketSize==4 ? 2 : PacketSize==2 ? ((Matrix11::Flags&RowMajorBit)?3:2) : /*PacketSize==1 ?*/ 3)\n      > Matrix3;\n    \n    #if !EIGEN_GCC_AND_ARCH_DOESNT_WANT_STACK_ALIGNMENT\n    VERIFY(test_assign(Vector1(),Vector1(),\n      InnerVectorizedTraversal,CompleteUnrolling));\n    VERIFY(test_assign(Vector1(),Vector1()+Vector1(),\n      InnerVectorizedTraversal,CompleteUnrolling));\n    VERIFY(test_assign(Vector1(),Vector1().template segment<PacketSize>(0).derived(),\n      EIGEN_UNALIGNED_VECTORIZE ? InnerVectorizedTraversal : LinearVectorizedTraversal,CompleteUnrolling));\n    VERIFY(test_assign(Vector1(),Scalar(2.1)*Vector1()-Vector1(),\n      InnerVectorizedTraversal,CompleteUnrolling));\n    VERIFY(test_assign(Vector1(),(Scalar(2.1)*Vector1().template segment<PacketSize>(0)-Vector1().template segment<PacketSize>(0)).derived(),\n      EIGEN_UNALIGNED_VECTORIZE ? InnerVectorizedTraversal : LinearVectorizedTraversal,CompleteUnrolling));\n    VERIFY(test_assign(Vector1(),Vector1().cwiseProduct(Vector1()),\n      InnerVectorizedTraversal,CompleteUnrolling));\n    VERIFY(test_assign(Vector1(),Vector1().template cast<Scalar>(),\n      InnerVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_assign(Matrix57(),Matrix57()+Matrix57(),\n      InnerVectorizedTraversal,InnerUnrolling));\n\n    VERIFY(test_assign(Matrix57u(),Matrix57()+Matrix57(),\n      EIGEN_UNALIGNED_VECTORIZE ? InnerVectorizedTraversal : LinearTraversal,\n      EIGEN_UNALIGNED_VECTORIZE ? InnerUnrolling : NoUnrolling));\n\n    VERIFY(test_assign(Matrix1u(),Matrix1()+Matrix1(),\n      EIGEN_UNALIGNED_VECTORIZE ? ((Matrix1::InnerSizeAtCompileTime % PacketSize)==0 ? InnerVectorizedTraversal : LinearVectorizedTraversal) : LinearTraversal,CompleteUnrolling));\n        \n    if(PacketSize>1)\n    {\n      typedef Matrix<Scalar,3,3,ColMajor> Matrix33c;\n      VERIFY(test_assign(Matrix33c().row(2),Matrix33c().row(1)+Matrix33c().row(1),\n        LinearTraversal,CompleteUnrolling));\n      VERIFY(test_assign(Matrix33c().col(0),Matrix33c().col(1)+Matrix33c().col(1),\n        EIGEN_UNALIGNED_VECTORIZE ? (sizeof(Scalar)==16 ? InnerVectorizedTraversal : LinearVectorizedTraversal)\n                                  : (sizeof(Scalar)==16 ? SliceVectorizedTraversal : LinearTraversal),\n        ((!EIGEN_UNALIGNED_VECTORIZE) && (sizeof(Scalar)==16)) ? NoUnrolling : CompleteUnrolling));\n              \n      VERIFY(test_assign(Matrix3(),Matrix3().cwiseQuotient(Matrix3()),\n        PacketTraits::HasDiv ? LinearVectorizedTraversal : LinearTraversal,CompleteUnrolling));\n        \n      VERIFY(test_assign(Matrix<Scalar,17,17>(),Matrix<Scalar,17,17>()+Matrix<Scalar,17,17>(),\n        sizeof(Scalar)==16 ? InnerVectorizedTraversal : (EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : LinearTraversal),\n        NoUnrolling));\n        \n      VERIFY(test_assign(Matrix11(),Matrix<Scalar,17,17>().template block<PacketSize,PacketSize>(2,3)+Matrix<Scalar,17,17>().template block<PacketSize,PacketSize>(8,4),\n        EIGEN_UNALIGNED_VECTORIZE ? InnerVectorizedTraversal : DefaultTraversal,InnerUnrolling+CompleteUnrolling));\n  \n\n      VERIFY(test_assign(Vector1(),Matrix11()*Vector1(),\n                         InnerVectorizedTraversal,CompleteUnrolling));\n\n      VERIFY(test_assign(Matrix11(),Matrix11().lazyProduct(Matrix11()),\n                         InnerVectorizedTraversal,InnerUnrolling+CompleteUnrolling));\n    }\n    \n    VERIFY(test_redux(Vector1(),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_redux(Matrix<Scalar,PacketSize,3>(),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_redux(Matrix3(),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_redux(Matrix35(),\n      LinearVectorizedTraversal,CompleteUnrolling));\n\n    VERIFY(test_redux(Matrix57().template block<PacketSize==1?2:PacketSize,3>(1,0),\n      SliceVectorizedTraversal,CompleteUnrolling));\n\n    if(PacketSize>1) {\n      VERIFY(test_redux(Matrix57().template block<PacketSize,2>(1,0),\n        DefaultTraversal,CompleteUnrolling));\n    }\n\n    VERIFY((test_assign<\n            Map<Matrix<Scalar,EIGEN_PLAIN_ENUM_MAX(2,PacketSize),EIGEN_PLAIN_ENUM_MAX(2,PacketSize)>, AlignedMax, InnerStride<3*PacketSize> >,\n            Matrix<Scalar,EIGEN_PLAIN_ENUM_MAX(2,PacketSize),EIGEN_PLAIN_ENUM_MAX(2,PacketSize)>\n            >(DefaultTraversal,PacketSize>4?InnerUnrolling:CompleteUnrolling)));\n\n    VERIFY((test_assign(Matrix57(), Matrix<Scalar,5*PacketSize,3>()*Matrix<Scalar,3,7>(),\n                        InnerVectorizedTraversal, InnerUnrolling+CompleteUnrolling)));\n    #endif\n  }\n};\n\ntemplate<typename Scalar> struct vectorization_logic_half<Scalar,false>\n{\n  static void run() {}\n};\n\nEIGEN_DECLARE_TEST(vectorization_logic)\n{\n\n#ifdef EIGEN_VECTORIZE\n\n  CALL_SUBTEST( vectorization_logic<int>::run() );\n  CALL_SUBTEST( vectorization_logic<float>::run() );\n  CALL_SUBTEST( vectorization_logic<double>::run() );\n  CALL_SUBTEST( vectorization_logic<std::complex<float> >::run() );\n  CALL_SUBTEST( vectorization_logic<std::complex<double> >::run() );\n  \n  CALL_SUBTEST( vectorization_logic_half<int>::run() );\n  CALL_SUBTEST( vectorization_logic_half<float>::run() );\n  CALL_SUBTEST( vectorization_logic_half<double>::run() );\n  CALL_SUBTEST( vectorization_logic_half<std::complex<float> >::run() );\n  CALL_SUBTEST( vectorization_logic_half<std::complex<double> >::run() );\n  \n  if(internal::packet_traits<float>::Vectorizable)\n  {\n    VERIFY(test_assign(Matrix<float,3,3>(),Matrix<float,3,3>()+Matrix<float,3,3>(),\n      EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : LinearTraversal,CompleteUnrolling));\n      \n    VERIFY(test_redux(Matrix<float,5,2>(),\n      EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : DefaultTraversal,CompleteUnrolling));\n  }\n  \n  if(internal::packet_traits<double>::Vectorizable)\n  {\n    VERIFY(test_assign(Matrix<double,3,3>(),Matrix<double,3,3>()+Matrix<double,3,3>(),\n      EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : LinearTraversal,CompleteUnrolling));\n    \n    VERIFY(test_redux(Matrix<double,7,3>(),\n      EIGEN_UNALIGNED_VECTORIZE ? LinearVectorizedTraversal : DefaultTraversal,CompleteUnrolling));\n  }\n#endif // EIGEN_VECTORIZE\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/vectorwiseop.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Benoit Jacob <jacob.benoit.1@gmail.com>\n// Copyright (C) 2015 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define TEST_ENABLE_TEMPORARY_TRACKING\n#define EIGEN_NO_STATIC_ASSERT\n\n#include \"main.h\"\n\ntemplate<typename ArrayType> void vectorwiseop_array(const ArrayType& m)\n{\n  typedef typename ArrayType::Scalar Scalar;\n  typedef Array<Scalar, ArrayType::RowsAtCompileTime, 1> ColVectorType;\n  typedef Array<Scalar, 1, ArrayType::ColsAtCompileTime> RowVectorType;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n  Index r = internal::random<Index>(0, rows-1),\n        c = internal::random<Index>(0, cols-1);\n\n  ArrayType m1 = ArrayType::Random(rows, cols),\n            m2(rows, cols),\n            m3(rows, cols);\n\n  ColVectorType colvec = ColVectorType::Random(rows);\n  RowVectorType rowvec = RowVectorType::Random(cols);\n\n  // test addition\n\n  m2 = m1;\n  m2.colwise() += colvec;\n  VERIFY_IS_APPROX(m2, m1.colwise() + colvec);\n  VERIFY_IS_APPROX(m2.col(c), m1.col(c) + colvec);\n\n  VERIFY_RAISES_ASSERT(m2.colwise() += colvec.transpose());\n  VERIFY_RAISES_ASSERT(m1.colwise() + colvec.transpose());\n\n  m2 = m1;\n  m2.rowwise() += rowvec;\n  VERIFY_IS_APPROX(m2, m1.rowwise() + rowvec);\n  VERIFY_IS_APPROX(m2.row(r), m1.row(r) + rowvec);\n\n  VERIFY_RAISES_ASSERT(m2.rowwise() += rowvec.transpose());\n  VERIFY_RAISES_ASSERT(m1.rowwise() + rowvec.transpose());\n\n  // test substraction\n\n  m2 = m1;\n  m2.colwise() -= colvec;\n  VERIFY_IS_APPROX(m2, m1.colwise() - colvec);\n  VERIFY_IS_APPROX(m2.col(c), m1.col(c) - colvec);\n\n  VERIFY_RAISES_ASSERT(m2.colwise() -= colvec.transpose());\n  VERIFY_RAISES_ASSERT(m1.colwise() - colvec.transpose());\n\n  m2 = m1;\n  m2.rowwise() -= rowvec;\n  VERIFY_IS_APPROX(m2, m1.rowwise() - rowvec);\n  VERIFY_IS_APPROX(m2.row(r), m1.row(r) - rowvec);\n\n  VERIFY_RAISES_ASSERT(m2.rowwise() -= rowvec.transpose());\n  VERIFY_RAISES_ASSERT(m1.rowwise() - rowvec.transpose());\n\n  // test multiplication\n\n  m2 = m1;\n  m2.colwise() *= colvec;\n  VERIFY_IS_APPROX(m2, m1.colwise() * colvec);\n  VERIFY_IS_APPROX(m2.col(c), m1.col(c) * colvec);\n\n  VERIFY_RAISES_ASSERT(m2.colwise() *= colvec.transpose());\n  VERIFY_RAISES_ASSERT(m1.colwise() * colvec.transpose());\n\n  m2 = m1;\n  m2.rowwise() *= rowvec;\n  VERIFY_IS_APPROX(m2, m1.rowwise() * rowvec);\n  VERIFY_IS_APPROX(m2.row(r), m1.row(r) * rowvec);\n\n  VERIFY_RAISES_ASSERT(m2.rowwise() *= rowvec.transpose());\n  VERIFY_RAISES_ASSERT(m1.rowwise() * rowvec.transpose());\n\n  // test quotient\n\n  m2 = m1;\n  m2.colwise() /= colvec;\n  VERIFY_IS_APPROX(m2, m1.colwise() / colvec);\n  VERIFY_IS_APPROX(m2.col(c), m1.col(c) / colvec);\n\n  VERIFY_RAISES_ASSERT(m2.colwise() /= colvec.transpose());\n  VERIFY_RAISES_ASSERT(m1.colwise() / colvec.transpose());\n\n  m2 = m1;\n  m2.rowwise() /= rowvec;\n  VERIFY_IS_APPROX(m2, m1.rowwise() / rowvec);\n  VERIFY_IS_APPROX(m2.row(r), m1.row(r) / rowvec);\n\n  VERIFY_RAISES_ASSERT(m2.rowwise() /= rowvec.transpose());\n  VERIFY_RAISES_ASSERT(m1.rowwise() / rowvec.transpose());\n\n  m2 = m1;\n  // yes, there might be an aliasing issue there but \".rowwise() /=\"\n  // is supposed to evaluate \" m2.colwise().sum()\" into a temporary to avoid\n  // evaluating the reduction multiple times\n  if(ArrayType::RowsAtCompileTime>2 || ArrayType::RowsAtCompileTime==Dynamic)\n  {\n    m2.rowwise() /= m2.colwise().sum();\n    VERIFY_IS_APPROX(m2, m1.rowwise() / m1.colwise().sum());\n  }\n\n  // all/any\n  Array<bool,Dynamic,Dynamic> mb(rows,cols);\n  mb = (m1.real()<=0.7).colwise().all();\n  VERIFY( (mb.col(c) == (m1.real().col(c)<=0.7).all()).all() );\n  mb = (m1.real()<=0.7).rowwise().all();\n  VERIFY( (mb.row(r) == (m1.real().row(r)<=0.7).all()).all() );\n\n  mb = (m1.real()>=0.7).colwise().any();\n  VERIFY( (mb.col(c) == (m1.real().col(c)>=0.7).any()).all() );\n  mb = (m1.real()>=0.7).rowwise().any();\n  VERIFY( (mb.row(r) == (m1.real().row(r)>=0.7).any()).all() );\n}\n\ntemplate<typename MatrixType> void vectorwiseop_matrix(const MatrixType& m)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef Matrix<Scalar, MatrixType::RowsAtCompileTime, 1> ColVectorType;\n  typedef Matrix<Scalar, 1, MatrixType::ColsAtCompileTime> RowVectorType;\n  typedef Matrix<RealScalar, MatrixType::RowsAtCompileTime, 1> RealColVectorType;\n  typedef Matrix<RealScalar, 1, MatrixType::ColsAtCompileTime> RealRowVectorType;\n  typedef Matrix<Scalar,Dynamic,Dynamic> MatrixX;\n\n  Index rows = m.rows();\n  Index cols = m.cols();\n  Index r = internal::random<Index>(0, rows-1),\n        c = internal::random<Index>(0, cols-1);\n\n  MatrixType m1 = MatrixType::Random(rows, cols),\n            m2(rows, cols),\n            m3(rows, cols);\n\n  ColVectorType colvec = ColVectorType::Random(rows);\n  RowVectorType rowvec = RowVectorType::Random(cols);\n  RealColVectorType rcres;\n  RealRowVectorType rrres;\n\n  // test broadcast assignment\n  m2 = m1;\n  m2.colwise() = colvec;\n  for(Index j=0; j<cols; ++j)\n    VERIFY_IS_APPROX(m2.col(j), colvec);\n  m2.rowwise() = rowvec;\n  for(Index i=0; i<rows; ++i)\n    VERIFY_IS_APPROX(m2.row(i), rowvec);\n  if(rows>1)\n    VERIFY_RAISES_ASSERT(m2.colwise() = colvec.transpose());\n  if(cols>1)\n    VERIFY_RAISES_ASSERT(m2.rowwise() = rowvec.transpose());\n\n  // test addition\n\n  m2 = m1;\n  m2.colwise() += colvec;\n  VERIFY_IS_APPROX(m2, m1.colwise() + colvec);\n  VERIFY_IS_APPROX(m2.col(c), m1.col(c) + colvec);\n\n  if(rows>1)\n  {\n    VERIFY_RAISES_ASSERT(m2.colwise() += colvec.transpose());\n    VERIFY_RAISES_ASSERT(m1.colwise() + colvec.transpose());\n  }\n\n  m2 = m1;\n  m2.rowwise() += rowvec;\n  VERIFY_IS_APPROX(m2, m1.rowwise() + rowvec);\n  VERIFY_IS_APPROX(m2.row(r), m1.row(r) + rowvec);\n\n  if(cols>1)\n  {\n    VERIFY_RAISES_ASSERT(m2.rowwise() += rowvec.transpose());\n    VERIFY_RAISES_ASSERT(m1.rowwise() + rowvec.transpose());\n  }\n\n  // test substraction\n\n  m2 = m1;\n  m2.colwise() -= colvec;\n  VERIFY_IS_APPROX(m2, m1.colwise() - colvec);\n  VERIFY_IS_APPROX(m2.col(c), m1.col(c) - colvec);\n\n  if(rows>1)\n  {\n    VERIFY_RAISES_ASSERT(m2.colwise() -= colvec.transpose());\n    VERIFY_RAISES_ASSERT(m1.colwise() - colvec.transpose());\n  }\n\n  m2 = m1;\n  m2.rowwise() -= rowvec;\n  VERIFY_IS_APPROX(m2, m1.rowwise() - rowvec);\n  VERIFY_IS_APPROX(m2.row(r), m1.row(r) - rowvec);\n\n  if(cols>1)\n  {\n    VERIFY_RAISES_ASSERT(m2.rowwise() -= rowvec.transpose());\n    VERIFY_RAISES_ASSERT(m1.rowwise() - rowvec.transpose());\n  }\n\n  // ------ partial reductions ------\n\n  #define TEST_PARTIAL_REDUX_BASIC(FUNC,ROW,COL,PREPROCESS) {                          \\\n    ROW = m1 PREPROCESS .colwise().FUNC ;                                              \\\n    for(Index k=0; k<cols; ++k) VERIFY_IS_APPROX(ROW(k), m1.col(k) PREPROCESS .FUNC ); \\\n    COL = m1 PREPROCESS .rowwise().FUNC ;                                              \\\n    for(Index k=0; k<rows; ++k) VERIFY_IS_APPROX(COL(k), m1.row(k) PREPROCESS .FUNC ); \\\n  }\n\n  TEST_PARTIAL_REDUX_BASIC(sum(),        rowvec,colvec,EIGEN_EMPTY);\n  TEST_PARTIAL_REDUX_BASIC(prod(),       rowvec,colvec,EIGEN_EMPTY);\n  TEST_PARTIAL_REDUX_BASIC(mean(),       rowvec,colvec,EIGEN_EMPTY);\n  TEST_PARTIAL_REDUX_BASIC(minCoeff(),   rrres, rcres, .real());\n  TEST_PARTIAL_REDUX_BASIC(maxCoeff(),   rrres, rcres, .real());\n  TEST_PARTIAL_REDUX_BASIC(norm(),       rrres, rcres, EIGEN_EMPTY);\n  TEST_PARTIAL_REDUX_BASIC(squaredNorm(),rrres, rcres, EIGEN_EMPTY);\n  TEST_PARTIAL_REDUX_BASIC(redux(internal::scalar_sum_op<Scalar,Scalar>()),rowvec,colvec,EIGEN_EMPTY);\n\n  VERIFY_IS_APPROX(m1.cwiseAbs().colwise().sum(), m1.colwise().template lpNorm<1>());\n  VERIFY_IS_APPROX(m1.cwiseAbs().rowwise().sum(), m1.rowwise().template lpNorm<1>());\n  VERIFY_IS_APPROX(m1.cwiseAbs().colwise().maxCoeff(), m1.colwise().template lpNorm<Infinity>());\n  VERIFY_IS_APPROX(m1.cwiseAbs().rowwise().maxCoeff(), m1.rowwise().template lpNorm<Infinity>());\n\n  // regression for bug 1158\n  VERIFY_IS_APPROX(m1.cwiseAbs().colwise().sum().x(), m1.col(0).cwiseAbs().sum());\n\n  // test normalized\n  m2 = m1.colwise().normalized();\n  VERIFY_IS_APPROX(m2.col(c), m1.col(c).normalized());\n  m2 = m1.rowwise().normalized();\n  VERIFY_IS_APPROX(m2.row(r), m1.row(r).normalized());\n\n  // test normalize\n  m2 = m1;\n  m2.colwise().normalize();\n  VERIFY_IS_APPROX(m2.col(c), m1.col(c).normalized());\n  m2 = m1;\n  m2.rowwise().normalize();\n  VERIFY_IS_APPROX(m2.row(r), m1.row(r).normalized());\n\n  // test with partial reduction of products\n  Matrix<Scalar,MatrixType::RowsAtCompileTime,MatrixType::RowsAtCompileTime> m1m1 = m1 * m1.transpose();\n  VERIFY_IS_APPROX( (m1 * m1.transpose()).colwise().sum(), m1m1.colwise().sum());\n  Matrix<Scalar,1,MatrixType::RowsAtCompileTime> tmp(rows);\n  VERIFY_EVALUATION_COUNT( tmp = (m1 * m1.transpose()).colwise().sum(), 1);\n\n  m2 = m1.rowwise() - (m1.colwise().sum()/RealScalar(m1.rows())).eval();\n  m1 = m1.rowwise() - (m1.colwise().sum()/RealScalar(m1.rows()));\n  VERIFY_IS_APPROX( m1, m2 );\n  VERIFY_EVALUATION_COUNT( m2 = (m1.rowwise() - m1.colwise().sum()/RealScalar(m1.rows())), (MatrixType::RowsAtCompileTime!=1 ? 1 : 0) );\n\n  // test empty expressions\n  VERIFY_IS_APPROX(m1.matrix().middleCols(0,0).rowwise().sum().eval(), MatrixX::Zero(rows,1));\n  VERIFY_IS_APPROX(m1.matrix().middleRows(0,0).colwise().sum().eval(), MatrixX::Zero(1,cols));\n  VERIFY_IS_APPROX(m1.matrix().middleCols(0,fix<0>).rowwise().sum().eval(), MatrixX::Zero(rows,1));\n  VERIFY_IS_APPROX(m1.matrix().middleRows(0,fix<0>).colwise().sum().eval(), MatrixX::Zero(1,cols));\n\n  VERIFY_IS_APPROX(m1.matrix().middleCols(0,0).rowwise().prod().eval(), MatrixX::Ones(rows,1));\n  VERIFY_IS_APPROX(m1.matrix().middleRows(0,0).colwise().prod().eval(), MatrixX::Ones(1,cols));\n  VERIFY_IS_APPROX(m1.matrix().middleCols(0,fix<0>).rowwise().prod().eval(), MatrixX::Ones(rows,1));\n  VERIFY_IS_APPROX(m1.matrix().middleRows(0,fix<0>).colwise().prod().eval(), MatrixX::Ones(1,cols));\n  \n  VERIFY_IS_APPROX(m1.matrix().middleCols(0,0).rowwise().squaredNorm().eval(), MatrixX::Zero(rows,1));\n\n  VERIFY_RAISES_ASSERT(m1.real().middleCols(0,0).rowwise().minCoeff().eval());\n  VERIFY_RAISES_ASSERT(m1.real().middleRows(0,0).colwise().maxCoeff().eval());\n  VERIFY_IS_EQUAL(m1.real().middleRows(0,0).rowwise().maxCoeff().eval().rows(),0);\n  VERIFY_IS_EQUAL(m1.real().middleCols(0,0).colwise().maxCoeff().eval().cols(),0);\n  VERIFY_IS_EQUAL(m1.real().middleRows(0,fix<0>).rowwise().maxCoeff().eval().rows(),0);\n  VERIFY_IS_EQUAL(m1.real().middleCols(0,fix<0>).colwise().maxCoeff().eval().cols(),0);\n}\n\nEIGEN_DECLARE_TEST(vectorwiseop)\n{\n  CALL_SUBTEST_1( vectorwiseop_array(Array22cd()) );\n  CALL_SUBTEST_2( vectorwiseop_array(Array<double, 3, 2>()) );\n  CALL_SUBTEST_3( vectorwiseop_array(ArrayXXf(3, 4)) );\n  CALL_SUBTEST_4( vectorwiseop_matrix(Matrix4cf()) );\n  CALL_SUBTEST_5( vectorwiseop_matrix(Matrix4f()) );\n  CALL_SUBTEST_5( vectorwiseop_matrix(Vector4f()) );\n  CALL_SUBTEST_5( vectorwiseop_matrix(Matrix<float,4,5>()) );\n  CALL_SUBTEST_6( vectorwiseop_matrix(MatrixXd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE), internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  CALL_SUBTEST_7( vectorwiseop_matrix(VectorXd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n  CALL_SUBTEST_7( vectorwiseop_matrix(RowVectorXd(internal::random<int>(1,EIGEN_TEST_MAX_SIZE))) );\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/visitor.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\ntemplate<typename MatrixType> void matrixVisitor(const MatrixType& p)\n{\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index rows = p.rows();\n  Index cols = p.cols();\n\n  // construct a random matrix where all coefficients are different\n  MatrixType m;\n  m = MatrixType::Random(rows, cols);\n  for(Index i = 0; i < m.size(); i++)\n    for(Index i2 = 0; i2 < i; i2++)\n      while(m(i) == m(i2)) // yes, ==\n        m(i) = internal::random<Scalar>();\n  \n  Scalar minc = Scalar(1000), maxc = Scalar(-1000);\n  Index minrow=0,mincol=0,maxrow=0,maxcol=0;\n  for(Index j = 0; j < cols; j++)\n  for(Index i = 0; i < rows; i++)\n  {\n    if(m(i,j) < minc)\n    {\n      minc = m(i,j);\n      minrow = i;\n      mincol = j;\n    }\n    if(m(i,j) > maxc)\n    {\n      maxc = m(i,j);\n      maxrow = i;\n      maxcol = j;\n    }\n  }\n  Index eigen_minrow, eigen_mincol, eigen_maxrow, eigen_maxcol;\n  Scalar eigen_minc, eigen_maxc;\n  eigen_minc = m.minCoeff(&eigen_minrow,&eigen_mincol);\n  eigen_maxc = m.maxCoeff(&eigen_maxrow,&eigen_maxcol);\n  VERIFY(minrow == eigen_minrow);\n  VERIFY(maxrow == eigen_maxrow);\n  VERIFY(mincol == eigen_mincol);\n  VERIFY(maxcol == eigen_maxcol);\n  VERIFY_IS_APPROX(minc, eigen_minc);\n  VERIFY_IS_APPROX(maxc, eigen_maxc);\n  VERIFY_IS_APPROX(minc, m.minCoeff());\n  VERIFY_IS_APPROX(maxc, m.maxCoeff());\n\n  eigen_maxc = (m.adjoint()*m).maxCoeff(&eigen_maxrow,&eigen_maxcol);\n  Index maxrow2=0,maxcol2=0;\n  eigen_maxc = (m.adjoint()*m).eval().maxCoeff(&maxrow2,&maxcol2);\n  VERIFY(maxrow2 == eigen_maxrow);\n  VERIFY(maxcol2 == eigen_maxcol);\n\n  if (!NumTraits<Scalar>::IsInteger && m.size() > 2) {\n    // Test NaN propagation by replacing an element with NaN.\n    bool stop = false;\n    for (Index j = 0; j < cols && !stop; ++j) {\n      for (Index i = 0; i < rows && !stop; ++i) {\n        if (!(j == mincol && i == minrow) &&\n            !(j == maxcol && i == maxrow)) {\n          m(i,j) = NumTraits<Scalar>::quiet_NaN();\n          stop = true;\n          break;\n        }\n      }\n    }\n\n    eigen_minc = m.template minCoeff<PropagateNumbers>(&eigen_minrow, &eigen_mincol);\n    eigen_maxc = m.template maxCoeff<PropagateNumbers>(&eigen_maxrow, &eigen_maxcol);\n    VERIFY(minrow == eigen_minrow);\n    VERIFY(maxrow == eigen_maxrow);\n    VERIFY(mincol == eigen_mincol);\n    VERIFY(maxcol == eigen_maxcol);\n    VERIFY_IS_APPROX(minc, eigen_minc);\n    VERIFY_IS_APPROX(maxc, eigen_maxc);\n    VERIFY_IS_APPROX(minc, m.template minCoeff<PropagateNumbers>());\n    VERIFY_IS_APPROX(maxc, m.template maxCoeff<PropagateNumbers>());\n\n    eigen_minc = m.template minCoeff<PropagateNaN>(&eigen_minrow, &eigen_mincol);\n    eigen_maxc = m.template maxCoeff<PropagateNaN>(&eigen_maxrow, &eigen_maxcol);\n    VERIFY(minrow != eigen_minrow || mincol != eigen_mincol);\n    VERIFY(maxrow != eigen_maxrow || maxcol != eigen_maxcol);\n    VERIFY((numext::isnan)(eigen_minc));\n    VERIFY((numext::isnan)(eigen_maxc));\n  }\n\n}\n\ntemplate<typename VectorType> void vectorVisitor(const VectorType& w)\n{\n  typedef typename VectorType::Scalar Scalar;\n\n  Index size = w.size();\n\n  // construct a random vector where all coefficients are different\n  VectorType v;\n  v = VectorType::Random(size);\n  for(Index i = 0; i < size; i++)\n    for(Index i2 = 0; i2 < i; i2++)\n      while(v(i) == v(i2)) // yes, ==\n        v(i) = internal::random<Scalar>();\n  \n  Scalar minc = v(0), maxc = v(0);\n  Index minidx=0, maxidx=0;\n  for(Index i = 0; i < size; i++)\n  {\n    if(v(i) < minc)\n    {\n      minc = v(i);\n      minidx = i;\n    }\n    if(v(i) > maxc)\n    {\n      maxc = v(i);\n      maxidx = i;\n    }\n  }\n  Index eigen_minidx, eigen_maxidx;\n  Scalar eigen_minc, eigen_maxc;\n  eigen_minc = v.minCoeff(&eigen_minidx);\n  eigen_maxc = v.maxCoeff(&eigen_maxidx);\n  VERIFY(minidx == eigen_minidx);\n  VERIFY(maxidx == eigen_maxidx);\n  VERIFY_IS_APPROX(minc, eigen_minc);\n  VERIFY_IS_APPROX(maxc, eigen_maxc);\n  VERIFY_IS_APPROX(minc, v.minCoeff());\n  VERIFY_IS_APPROX(maxc, v.maxCoeff());\n  \n  Index idx0 = internal::random<Index>(0,size-1);\n  Index idx1 = eigen_minidx;\n  Index idx2 = eigen_maxidx;\n  VectorType v1(v), v2(v);\n  v1(idx0) = v1(idx1);\n  v2(idx0) = v2(idx2);\n  v1.minCoeff(&eigen_minidx);\n  v2.maxCoeff(&eigen_maxidx);\n  VERIFY(eigen_minidx == (std::min)(idx0,idx1));\n  VERIFY(eigen_maxidx == (std::min)(idx0,idx2));\n\n  if (!NumTraits<Scalar>::IsInteger && size > 2) {\n    // Test NaN propagation by replacing an element with NaN.\n    for (Index i = 0; i < size; ++i) {\n      if (i != minidx && i != maxidx) {\n        v(i) = NumTraits<Scalar>::quiet_NaN();\n        break;\n      }\n    }\n    eigen_minc = v.template minCoeff<PropagateNumbers>(&eigen_minidx);\n    eigen_maxc = v.template maxCoeff<PropagateNumbers>(&eigen_maxidx);\n    VERIFY(minidx == eigen_minidx);\n    VERIFY(maxidx == eigen_maxidx);\n    VERIFY_IS_APPROX(minc, eigen_minc);\n    VERIFY_IS_APPROX(maxc, eigen_maxc);\n    VERIFY_IS_APPROX(minc, v.template minCoeff<PropagateNumbers>());\n    VERIFY_IS_APPROX(maxc, v.template maxCoeff<PropagateNumbers>());\n\n    eigen_minc = v.template minCoeff<PropagateNaN>(&eigen_minidx);\n    eigen_maxc = v.template maxCoeff<PropagateNaN>(&eigen_maxidx);\n    VERIFY(minidx != eigen_minidx);\n    VERIFY(maxidx != eigen_maxidx);\n    VERIFY((numext::isnan)(eigen_minc));\n    VERIFY((numext::isnan)(eigen_maxc));\n  }\n}\n\nEIGEN_DECLARE_TEST(visitor)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( matrixVisitor(Matrix<float, 1, 1>()) );\n    CALL_SUBTEST_2( matrixVisitor(Matrix2f()) );\n    CALL_SUBTEST_3( matrixVisitor(Matrix4d()) );\n    CALL_SUBTEST_4( matrixVisitor(MatrixXd(8, 12)) );\n    CALL_SUBTEST_5( matrixVisitor(Matrix<double,Dynamic,Dynamic,RowMajor>(20, 20)) );\n    CALL_SUBTEST_6( matrixVisitor(MatrixXi(8, 12)) );\n  }\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_7( vectorVisitor(Vector4f()) );\n    CALL_SUBTEST_7( vectorVisitor(Matrix<int,12,1>()) );\n    CALL_SUBTEST_8( vectorVisitor(VectorXd(10)) );\n    CALL_SUBTEST_9( vectorVisitor(RowVectorXd(10)) );\n    CALL_SUBTEST_10( vectorVisitor(VectorXf(33)) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/test/zerosized.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n\ntemplate<typename MatrixType> void zeroReduction(const MatrixType& m) {\n  // Reductions that must hold for zero sized objects\n  VERIFY(m.all());\n  VERIFY(!m.any());\n  VERIFY(m.prod()==1);\n  VERIFY(m.sum()==0);\n  VERIFY(m.norm()==0);\n  VERIFY(m.squaredNorm()==0);\n  VERIFY(m.count()==0);\n  VERIFY(m.allFinite());\n  VERIFY(!m.hasNaN());\n  VERIFY_RAISES_ASSERT( m.minCoeff() );\n  VERIFY_RAISES_ASSERT( m.maxCoeff() );\n  Index i,j;\n  VERIFY_RAISES_ASSERT( m.minCoeff(&i,&j) );\n  VERIFY_RAISES_ASSERT( m.maxCoeff(&i,&j) );\n  VERIFY_RAISES_ASSERT( m.reshaped().minCoeff(&i) );\n  VERIFY_RAISES_ASSERT( m.reshaped().maxCoeff(&i) );\n}\n\n\ntemplate<typename MatrixType> void zeroSizedMatrix()\n{\n  MatrixType t1;\n  typedef typename MatrixType::Scalar Scalar;\n\n  if (MatrixType::SizeAtCompileTime == Dynamic || MatrixType::SizeAtCompileTime == 0)\n  {\n    zeroReduction(t1);\n    if (MatrixType::RowsAtCompileTime == Dynamic)\n      VERIFY(t1.rows() == 0);\n    if (MatrixType::ColsAtCompileTime == Dynamic)\n      VERIFY(t1.cols() == 0);\n\n    if (MatrixType::RowsAtCompileTime == Dynamic && MatrixType::ColsAtCompileTime == Dynamic)\n    {\n\n      MatrixType t2(0, 0), t3(t1);\n      VERIFY(t2.rows() == 0);\n      VERIFY(t2.cols() == 0);\n\n      zeroReduction(t2);\n      VERIFY(t1==t2);\n    }\n  }\n\n  if(MatrixType::MaxColsAtCompileTime!=0 && MatrixType::MaxRowsAtCompileTime!=0)\n  {\n    Index rows = MatrixType::RowsAtCompileTime==Dynamic ? internal::random<Index>(1,10) : Index(MatrixType::RowsAtCompileTime);\n    Index cols = MatrixType::ColsAtCompileTime==Dynamic ? internal::random<Index>(1,10) : Index(MatrixType::ColsAtCompileTime);\n    MatrixType m(rows,cols);\n    zeroReduction(m.template block<0,MatrixType::ColsAtCompileTime>(0,0,0,cols));\n    zeroReduction(m.template block<MatrixType::RowsAtCompileTime,0>(0,0,rows,0));\n    zeroReduction(m.template block<0,1>(0,0));\n    zeroReduction(m.template block<1,0>(0,0));\n    Matrix<Scalar,Dynamic,Dynamic> prod = m.template block<MatrixType::RowsAtCompileTime,0>(0,0,rows,0) * m.template block<0,MatrixType::ColsAtCompileTime>(0,0,0,cols);\n    VERIFY(prod.rows()==rows && prod.cols()==cols);\n    VERIFY(prod.isZero());\n    prod = m.template block<1,0>(0,0) * m.template block<0,1>(0,0);\n    VERIFY(prod.size()==1);\n    VERIFY(prod.isZero());\n  }\n}\n\ntemplate<typename VectorType> void zeroSizedVector()\n{\n  VectorType t1;\n\n  if (VectorType::SizeAtCompileTime == Dynamic || VectorType::SizeAtCompileTime==0)\n  {\n    zeroReduction(t1);\n    VERIFY(t1.size() == 0);\n    VectorType t2(DenseIndex(0)); // DenseIndex disambiguates with 0-the-null-pointer (error with gcc 4.4 and MSVC8)\n    VERIFY(t2.size() == 0);\n    zeroReduction(t2);\n\n    VERIFY(t1==t2);\n  }\n}\n\nEIGEN_DECLARE_TEST(zerosized)\n{\n  zeroSizedMatrix<Matrix2d>();\n  zeroSizedMatrix<Matrix3i>();\n  zeroSizedMatrix<Matrix<float, 2, Dynamic> >();\n  zeroSizedMatrix<MatrixXf>();\n  zeroSizedMatrix<Matrix<float, 0, 0> >();\n  zeroSizedMatrix<Matrix<float, Dynamic, 0, 0, 0, 0> >();\n  zeroSizedMatrix<Matrix<float, 0, Dynamic, 0, 0, 0> >();\n  zeroSizedMatrix<Matrix<float, Dynamic, Dynamic, 0, 0, 0> >();\n  zeroSizedMatrix<Matrix<float, 0, 4> >();\n  zeroSizedMatrix<Matrix<float, 4, 0> >();\n\n  zeroSizedVector<Vector2d>();\n  zeroSizedVector<Vector3i>();\n  zeroSizedVector<VectorXf>();\n  zeroSizedVector<Matrix<float, 0, 1> >();\n  zeroSizedVector<Matrix<float, 1, 0> >();\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/CMakeLists.txt",
    "content": "add_subdirectory(Eigen)\nif(EIGEN_BUILD_DOC)\n  add_subdirectory(doc EXCLUDE_FROM_ALL)\nendif()\nif(BUILD_TESTING)\n  if(EIGEN_LEAVE_TEST_IN_ALL_TARGET)\n    add_subdirectory(test) # can't do EXCLUDE_FROM_ALL here, breaks CTest\n  else()\n    add_subdirectory(test EXCLUDE_FROM_ALL)\n  endif()\nendif()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/AdolcForward",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ADLOC_FORWARD\n#define EIGEN_ADLOC_FORWARD\n\n//--------------------------------------------------------------------------------\n//\n// This file provides support for adolc's adouble type in forward mode.\n// ADOL-C is a C++ automatic differentiation library,\n// see https://projects.coin-or.org/ADOL-C for more information.\n//\n// Note that the maximal number of directions is controlled by\n// the preprocessor token NUMBER_DIRECTIONS. The default is 2.\n//\n//--------------------------------------------------------------------------------\n\n#define ADOLC_TAPELESS\n#ifndef NUMBER_DIRECTIONS\n# define NUMBER_DIRECTIONS 2\n#endif\n#include <adolc/adtl.h>\n\n// adolc defines some very stupid macros:\n#if defined(malloc)\n# undef malloc\n#endif\n\n#if defined(calloc)\n# undef calloc\n#endif\n\n#if defined(realloc)\n# undef realloc\n#endif\n\n#include \"../../Eigen/Core\"\n\nnamespace Eigen {\n\n/**\n  * \\defgroup AdolcForward_Module Adolc forward module\n  * This module provides support for adolc's adouble type in forward mode.\n  * ADOL-C is a C++ automatic differentiation library,\n  * see https://projects.coin-or.org/ADOL-C for more information.\n  * It mainly consists in:\n  *  - a struct Eigen::NumTraits<adtl::adouble> specialization\n  *  - overloads of internal::* math function for adtl::adouble type.\n  *\n  * Note that the maximal number of directions is controlled by\n  * the preprocessor token NUMBER_DIRECTIONS. The default is 2.\n  *\n  * \\code\n  * #include <unsupported/Eigen/AdolcSupport>\n  * \\endcode\n  */\n  //@{\n\n} // namespace Eigen\n\n// Eigen's require a few additional functions which must be defined in the same namespace\n// than the custom scalar type own namespace\nnamespace adtl {\n\ninline const adouble& conj(const adouble& x)  { return x; }\ninline const adouble& real(const adouble& x)  { return x; }\ninline adouble imag(const adouble&)    { return 0.; }\ninline adouble abs(const adouble&  x)  { return fabs(x); }\ninline adouble abs2(const adouble& x)  { return x*x; }\n\ninline bool (isinf)(const adouble& x) { return (Eigen::numext::isinf)(x.getValue()); }\ninline bool (isnan)(const adouble& x) { return (Eigen::numext::isnan)(x.getValue()); }\n\n}\n\nnamespace Eigen {\n\ntemplate<> struct NumTraits<adtl::adouble>\n    : NumTraits<double>\n{\n  typedef adtl::adouble Real;\n  typedef adtl::adouble NonInteger;\n  typedef adtl::adouble Nested;\n  enum {\n    IsComplex = 0,\n    IsInteger = 0,\n    IsSigned = 1,\n    RequireInitialization = 1,\n    ReadCost = 1,\n    AddCost = 1,\n    MulCost = 1\n  };\n};\n\ntemplate<typename Functor> class AdolcForwardJacobian : public Functor\n{\n  typedef adtl::adouble ActiveScalar;\npublic:\n\n  AdolcForwardJacobian() : Functor() {}\n  AdolcForwardJacobian(const Functor& f) : Functor(f) {}\n\n  // forward constructors\n  template<typename T0>\n  AdolcForwardJacobian(const T0& a0) : Functor(a0) {}\n  template<typename T0, typename T1>\n  AdolcForwardJacobian(const T0& a0, const T1& a1) : Functor(a0, a1) {}\n  template<typename T0, typename T1, typename T2>\n  AdolcForwardJacobian(const T0& a0, const T1& a1, const T1& a2) : Functor(a0, a1, a2) {}\n\n  typedef typename Functor::InputType InputType;\n  typedef typename Functor::ValueType ValueType;\n  typedef typename Functor::JacobianType JacobianType;\n\n  typedef Matrix<ActiveScalar, InputType::SizeAtCompileTime, 1> ActiveInput;\n  typedef Matrix<ActiveScalar, ValueType::SizeAtCompileTime, 1> ActiveValue;\n\n  void operator() (const InputType& x, ValueType* v, JacobianType* _jac) const\n  {\n    eigen_assert(v!=0);\n    if (!_jac)\n    {\n      Functor::operator()(x, v);\n      return;\n    }\n\n    JacobianType& jac = *_jac;\n\n    ActiveInput ax = x.template cast<ActiveScalar>();\n    ActiveValue av(jac.rows());\n\n    for (int j=0; j<jac.cols(); j++)\n      for (int i=0; i<jac.cols(); i++)\n        ax[i].setADValue(j, i==j ? 1 : 0);\n\n    Functor::operator()(ax, &av);\n\n    for (int i=0; i<jac.rows(); i++)\n    {\n      (*v)[i] = av[i].getValue();\n      for (int j=0; j<jac.cols(); j++)\n        jac.coeffRef(i,j) = av[i].getADValue(j);\n    }\n  }\nprotected:\n\n};\n\n//@}\n\n}\n\n#endif // EIGEN_ADLOC_FORWARD\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/AlignedVector3",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ALIGNED_VECTOR3\n#define EIGEN_ALIGNED_VECTOR3\n\n#include \"../../Eigen/Geometry\"\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\nnamespace Eigen {\n\n/**\n  * \\defgroup AlignedVector3_Module Aligned vector3 module\n  *\n  * \\code\n  * #include <unsupported/Eigen/AlignedVector3>\n  * \\endcode\n  */\n  //@{\n\n\n/** \\class AlignedVector3\n  *\n  * \\brief A vectorization friendly 3D vector\n  *\n  * This class represents a 3D vector internally using a 4D vector\n  * such that vectorization can be seamlessly enabled. Of course,\n  * the same result can be achieved by directly using a 4D vector.\n  * This class makes this process simpler.\n  *\n  */\n// TODO specialize Cwise\ntemplate<typename _Scalar> class AlignedVector3;\n\nnamespace internal {\ntemplate<typename _Scalar> struct traits<AlignedVector3<_Scalar> >\n  : traits<Matrix<_Scalar,3,1,0,4,1> >\n{\n};\n}\n\ntemplate<typename _Scalar> class AlignedVector3\n  : public MatrixBase<AlignedVector3<_Scalar> >\n{\n    typedef Matrix<_Scalar,4,1> CoeffType;\n    CoeffType m_coeffs;\n  public:\n\n    typedef MatrixBase<AlignedVector3<_Scalar> > Base;\t\n    EIGEN_DENSE_PUBLIC_INTERFACE(AlignedVector3)\n    using Base::operator*;\n\n    inline Index rows() const { return 3; }\n    inline Index cols() const { return 1; }\n    \n    Scalar* data() { return m_coeffs.data(); }\n    const Scalar* data() const { return m_coeffs.data(); }\n    Index innerStride() const { return 1; }\n    Index outerStride() const { return 3; }\n\n    inline const Scalar& coeff(Index row, Index col) const\n    { return m_coeffs.coeff(row, col); }\n\n    inline Scalar& coeffRef(Index row, Index col)\n    { return m_coeffs.coeffRef(row, col); }\n\n    inline const Scalar& coeff(Index index) const\n    { return m_coeffs.coeff(index); }\n\n    inline Scalar& coeffRef(Index index)\n    { return m_coeffs.coeffRef(index);}\n\n\n    inline AlignedVector3()\n    {}\n\n    inline AlignedVector3(const Scalar& x, const Scalar& y, const Scalar& z)\n      : m_coeffs(x, y, z, Scalar(0))\n    {}\n\n    inline AlignedVector3(const AlignedVector3& other)\n      : Base(), m_coeffs(other.m_coeffs)\n    {}\n\n    template<typename XprType, int Size=XprType::SizeAtCompileTime>\n    struct generic_assign_selector {};\n\n    template<typename XprType> struct generic_assign_selector<XprType,4>\n    {\n      inline static void run(AlignedVector3& dest, const XprType& src)\n      {\n        dest.m_coeffs = src;\n      }\n    };\n\n    template<typename XprType> struct generic_assign_selector<XprType,3>\n    {\n      inline static void run(AlignedVector3& dest, const XprType& src)\n      {\n        dest.m_coeffs.template head<3>() = src;\n        dest.m_coeffs.w() = Scalar(0);\n      }\n    };\n\n    template<typename Derived>\n    inline AlignedVector3(const MatrixBase<Derived>& other)\n    {\n      generic_assign_selector<Derived>::run(*this,other.derived());\n    }\n\n    inline AlignedVector3& operator=(const AlignedVector3& other)\n    { m_coeffs = other.m_coeffs; return *this; }\n\n    template <typename Derived>\n    inline AlignedVector3& operator=(const MatrixBase<Derived>& other)\n    {\n      generic_assign_selector<Derived>::run(*this,other.derived());\n      return *this;\n    }\n\n    inline AlignedVector3 operator+(const AlignedVector3& other) const\n    { return AlignedVector3(m_coeffs + other.m_coeffs); }\n\n    inline AlignedVector3& operator+=(const AlignedVector3& other)\n    { m_coeffs += other.m_coeffs; return *this; }\n\n    inline AlignedVector3 operator-(const AlignedVector3& other) const\n    { return AlignedVector3(m_coeffs - other.m_coeffs); }\n\n    inline AlignedVector3 operator-() const\n    { return AlignedVector3(-m_coeffs); }\n\n    inline AlignedVector3 operator-=(const AlignedVector3& other)\n    { m_coeffs -= other.m_coeffs; return *this; }\n\n    inline AlignedVector3 operator*(const Scalar& s) const\n    { return AlignedVector3(m_coeffs * s); }\n\n    inline friend AlignedVector3 operator*(const Scalar& s,const AlignedVector3& vec)\n    { return AlignedVector3(s * vec.m_coeffs); }\n\n    inline AlignedVector3& operator*=(const Scalar& s)\n    { m_coeffs *= s; return *this; }\n\n    inline AlignedVector3 operator/(const Scalar& s) const\n    { return AlignedVector3(m_coeffs / s); }\n\n    inline AlignedVector3& operator/=(const Scalar& s)\n    { m_coeffs /= s; return *this; }\n\n    inline Scalar dot(const AlignedVector3& other) const\n    {\n      eigen_assert(m_coeffs.w()==Scalar(0));\n      eigen_assert(other.m_coeffs.w()==Scalar(0));\n      return m_coeffs.dot(other.m_coeffs);\n    }\n\n    inline void normalize()\n    {\n      m_coeffs /= norm();\n    }\n\n    inline AlignedVector3 normalized() const\n    {\n      return AlignedVector3(m_coeffs / norm());\n    }\n\n    inline Scalar sum() const\n    {\n      eigen_assert(m_coeffs.w()==Scalar(0));\n      return m_coeffs.sum();\n    }\n\n    inline Scalar squaredNorm() const\n    {\n      eigen_assert(m_coeffs.w()==Scalar(0));\n      return m_coeffs.squaredNorm();\n    }\n\n    inline Scalar norm() const\n    {\n      using std::sqrt;\n      return sqrt(squaredNorm());\n    }\n\n    inline AlignedVector3 cross(const AlignedVector3& other) const\n    {\n      return AlignedVector3(m_coeffs.cross3(other.m_coeffs));\n    }\n\n    template<typename Derived>\n    inline bool isApprox(const MatrixBase<Derived>& other, const RealScalar& eps=NumTraits<Scalar>::dummy_precision()) const\n    {\n      return m_coeffs.template head<3>().isApprox(other,eps);\n    }\n    \n    CoeffType& coeffs() { return m_coeffs; }\n    const CoeffType& coeffs() const { return m_coeffs; }\n};\n\nnamespace internal {\n\ntemplate<typename _Scalar>\nstruct eval<AlignedVector3<_Scalar>, Dense>\n{\n typedef const AlignedVector3<_Scalar>& type;\n};\n\ntemplate<typename Scalar>\nstruct evaluator<AlignedVector3<Scalar> >\n  : evaluator<Matrix<Scalar,4,1> >\n{\n  typedef AlignedVector3<Scalar> XprType;\n  typedef evaluator<Matrix<Scalar,4,1> > Base;\n  \n  evaluator(const XprType &m) : Base(m.coeffs()) {}  \n};\n\n}\n\n//@}\n\n}\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_ALIGNED_VECTOR3\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/ArpackSupport",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ARPACKSUPPORT_MODULE_H\n#define EIGEN_ARPACKSUPPORT_MODULE_H\n\n#include \"../../Eigen/Core\"\n\n/** \\defgroup ArpackSupport_Module Arpack support module\n  *\n  * This module provides a wrapper to Arpack, a library for sparse eigenvalue decomposition.\n  *\n  * \\code\n  * #include <Eigen/ArpackSupport>\n  * \\endcode\n  */\n\n#include \"../../Eigen/SparseCholesky\"\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n#include \"src/Eigenvalues/ArpackSelfAdjointEigenSolver.h\"\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_ARPACKSUPPORT_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/AutoDiff",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_AUTODIFF_MODULE\n#define EIGEN_AUTODIFF_MODULE\n\nnamespace Eigen {\n\n/**\n  * \\defgroup AutoDiff_Module Auto Diff module\n  *\n  * This module features forward automatic differentation via a simple\n  * templated scalar type wrapper AutoDiffScalar.\n  *\n  * Warning : this should NOT be confused with numerical differentiation, which\n  * is a different method and has its own module in Eigen : \\ref NumericalDiff_Module.\n  *\n  * \\code\n  * #include <unsupported/Eigen/AutoDiff>\n  * \\endcode\n  */\n//@{\n\n}\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n\n#include \"src/AutoDiff/AutoDiffScalar.h\"\n// #include \"src/AutoDiff/AutoDiffVector.h\"\n#include \"src/AutoDiff/AutoDiffJacobian.h\"\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n\n\nnamespace Eigen {\n//@}\n}\n\n#endif // EIGEN_AUTODIFF_MODULE\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/BVH",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Ilya Baran <ibaran@mit.edu>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BVH_MODULE_H\n#define EIGEN_BVH_MODULE_H\n\n#include \"../../Eigen/Core\"\n#include \"../../Eigen/Geometry\"\n#include \"../../Eigen/StdVector\"\n#include <algorithm>\n#include <queue>\n\nnamespace Eigen {\n\n/**\n  * \\defgroup BVH_Module BVH module\n  * \\brief This module provides generic bounding volume hierarchy algorithms\n  * and reference tree implementations.\n  *\n  *\n  * \\code\n  * #include <unsupported/Eigen/BVH>\n  * \\endcode\n  *\n  * A bounding volume hierarchy (BVH) can accelerate many geometric queries.  This module provides a generic implementation\n  * of the two basic algorithms over a BVH: intersection of a query object against all objects in the hierarchy and minimization\n  * of a function over the objects in the hierarchy.  It also provides intersection and minimization over a cartesian product of\n  * two BVH's.  A BVH accelerates intersection by using the fact that if a query object does not intersect a volume, then it cannot\n  * intersect any object contained in that volume.  Similarly, a BVH accelerates minimization because the minimum of a function\n  * over a volume is no greater than the minimum of a function over any object contained in it.\n  *\n  * Some sample queries that can be written in terms of intersection are:\n  *   - Determine all points where a ray intersects a triangle mesh\n  *   - Given a set of points, determine which are contained in a query sphere\n  *   - Given a set of spheres, determine which contain the query point\n  *   - Given a set of disks, determine if any is completely contained in a query rectangle (represent each 2D disk as a point \\f$(x,y,r)\\f$\n  *     in 3D and represent the rectangle as a pyramid based on the original rectangle and shrinking in the \\f$r\\f$ direction)\n  *   - Given a set of points, count how many pairs are \\f$d\\pm\\epsilon\\f$ apart (done by looking at the cartesian product of the set\n  *     of points with itself)\n  *\n  * Some sample queries that can be written in terms of function minimization over a set of objects are:\n  *   - Find the intersection between a ray and a triangle mesh closest to the ray origin (function is infinite off the ray)\n  *   - Given a polyline and a query point, determine the closest point on the polyline to the query\n  *   - Find the diameter of a point cloud (done by looking at the cartesian product and using negative distance as the function)\n  *   - Determine how far two meshes are from colliding (this is also a cartesian product query)\n  *\n  * This implementation decouples the basic algorithms both from the type of hierarchy (and the types of the bounding volumes) and\n  * from the particulars of the query.  To enable abstraction from the BVH, the BVH is required to implement a generic mechanism\n  * for traversal.  To abstract from the query, the query is responsible for keeping track of results.\n  *\n  * To be used in the algorithms, a hierarchy must implement the following traversal mechanism (see KdBVH for a sample implementation): \\code\n      typedef Volume  //the type of bounding volume\n      typedef Object  //the type of object in the hierarchy\n      typedef Index   //a reference to a node in the hierarchy--typically an int or a pointer\n      typedef VolumeIterator //an iterator type over node children--returns Index\n      typedef ObjectIterator //an iterator over object (leaf) children--returns const Object &\n      Index getRootIndex() const //returns the index of the hierarchy root\n      const Volume &getVolume(Index index) const //returns the bounding volume of the node at given index\n      void getChildren(Index index, VolumeIterator &outVBegin, VolumeIterator &outVEnd,\n                      ObjectIterator &outOBegin, ObjectIterator &outOEnd) const\n      //getChildren takes a node index and makes [outVBegin, outVEnd) range over its node children\n      //and [outOBegin, outOEnd) range over its object children\n    \\endcode\n  *\n  * To use the hierarchy, call BVIntersect or BVMinimize, passing it a BVH (or two, for cartesian product) and a minimizer or intersector.\n  * For an intersection query on a single BVH, the intersector encapsulates the query and must provide two functions:\n  * \\code\n      bool intersectVolume(const Volume &volume) //returns true if the query intersects the volume\n      bool intersectObject(const Object &object) //returns true if the intersection search should terminate immediately\n    \\endcode\n  * The guarantee that BVIntersect provides is that intersectObject will be called on every object whose bounding volume\n  * intersects the query (but possibly on other objects too) unless the search is terminated prematurely.  It is the\n  * responsibility of the intersectObject function to keep track of the results in whatever manner is appropriate.\n  * The cartesian product intersection and the BVMinimize queries are similar--see their individual documentation.\n  *\n  * The following is a simple but complete example for how to use the BVH to accelerate the search for a closest red-blue point pair:\n  * \\include BVH_Example.cpp\n  * Output: \\verbinclude BVH_Example.out\n  */\n}\n\n//@{\n\n#include \"src/BVH/BVAlgorithms.h\"\n#include \"src/BVH/KdBVH.h\"\n\n//@}\n\n#endif // EIGEN_BVH_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CMakeLists.txt",
    "content": "set(Eigen_HEADERS \n  AdolcForward\n  AlignedVector3\n  ArpackSupport\n  AutoDiff\n  BVH\n  EulerAngles\n  FFT\n  IterativeSolvers \n  KroneckerProduct\n  LevenbergMarquardt\n  MatrixFunctions \n  MoreVectorization\n  MPRealSupport\n  NonLinearOptimization\n  NumericalDiff\n  OpenGLSupport\n  Polynomials\n  Skyline \n  SparseExtra\n  SpecialFunctions\n  Splines\n  )\n\ninstall(FILES\n  ${Eigen_HEADERS}\n  DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen COMPONENT Devel\n  )\n\ninstall(DIRECTORY src DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen COMPONENT Devel FILES_MATCHING PATTERN \"*.h\")\n\nadd_subdirectory(CXX11)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/CMakeLists.txt",
    "content": "set(Eigen_CXX11_HEADERS Tensor TensorSymmetry ThreadPool)\n\ninstall(FILES\n  ${Eigen_CXX11_HEADERS}\n  DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen/CXX11 COMPONENT Devel\n  )\n\ninstall(DIRECTORY src DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen/CXX11 COMPONENT Devel FILES_MATCHING PATTERN \"*.h\")\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/Tensor",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n//#ifndef EIGEN_CXX11_TENSOR_MODULE\n//#define EIGEN_CXX11_TENSOR_MODULE\n\n#include \"../../../Eigen/Core\"\n\n#if EIGEN_HAS_CXX11\n\n#include \"../SpecialFunctions\"\n\n#include \"../../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n#include \"src/util/CXX11Meta.h\"\n#include \"src/util/MaxSizeVector.h\"\n\n/** \\defgroup CXX11_Tensor_Module Tensor Module\n  *\n  * This module provides a Tensor class for storing arbitrarily indexed\n  * objects.\n  *\n  * \\code\n  * #include <Eigen/CXX11/Tensor>\n  * \\endcode\n  *\n  * Much of the documentation can be found \\ref eigen_tensors \"here\".\n  */\n\n#include <atomic>\n#include <chrono>\n#include <cmath>\n#include <cstddef>\n#include <cstring>\n#include <random>\n#include <thread>\n\n#ifdef _WIN32\n#include <windows.h>\n#elif defined(__APPLE__)\n#include <mach/mach_time.h>\n#else\n#include <time.h>\n#endif\n\n#if defined(EIGEN_USE_THREADS) || defined(EIGEN_USE_SYCL)\n#include \"ThreadPool\"\n#endif\n\n#ifdef EIGEN_USE_GPU\n  #include <iostream>\n  #if defined(EIGEN_USE_HIP)\n    #include <hip/hip_runtime.h>\n  #else\n    #include <cuda_runtime.h>\n  #endif\n#endif\n\n#include \"src/Tensor/TensorMacros.h\"\n#include \"src/Tensor/TensorForwardDeclarations.h\"\n#include \"src/Tensor/TensorMeta.h\"\n#include \"src/Tensor/TensorFunctors.h\"\n#include \"src/Tensor/TensorCostModel.h\"\n#include \"src/Tensor/TensorDeviceDefault.h\"\n#include \"src/Tensor/TensorDeviceThreadPool.h\"\n#include \"src/Tensor/TensorDeviceGpu.h\"\n#ifndef gpu_assert\n#define gpu_assert(x)\n#endif\n#include \"src/Tensor/TensorDeviceSycl.h\"\n#include \"src/Tensor/TensorIndexList.h\"\n#include \"src/Tensor/TensorDimensionList.h\"\n#include \"src/Tensor/TensorDimensions.h\"\n#include \"src/Tensor/TensorInitializer.h\"\n#include \"src/Tensor/TensorTraits.h\"\n#include \"src/Tensor/TensorRandom.h\"\n#include \"src/Tensor/TensorUInt128.h\"\n#include \"src/Tensor/TensorIntDiv.h\"\n#include \"src/Tensor/TensorGlobalFunctions.h\"\n\n#include \"src/Tensor/TensorBase.h\"\n#include \"src/Tensor/TensorBlock.h\"\n\n#include \"src/Tensor/TensorEvaluator.h\"\n#include \"src/Tensor/TensorExpr.h\"\n#include \"src/Tensor/TensorReduction.h\"\n#include \"src/Tensor/TensorReductionGpu.h\"\n#include \"src/Tensor/TensorArgMax.h\"\n#include \"src/Tensor/TensorConcatenation.h\"\n#include \"src/Tensor/TensorContractionMapper.h\"\n#include \"src/Tensor/TensorContractionBlocking.h\"\n#include \"src/Tensor/TensorContraction.h\"\n#include \"src/Tensor/TensorContractionThreadPool.h\"\n#include \"src/Tensor/TensorContractionGpu.h\"\n#include \"src/Tensor/TensorConversion.h\"\n#include \"src/Tensor/TensorConvolution.h\"\n#include \"src/Tensor/TensorFFT.h\"\n#include \"src/Tensor/TensorPatch.h\"\n#include \"src/Tensor/TensorImagePatch.h\"\n#include \"src/Tensor/TensorVolumePatch.h\"\n#include \"src/Tensor/TensorBroadcasting.h\"\n#include \"src/Tensor/TensorChipping.h\"\n#include \"src/Tensor/TensorInflation.h\"\n#include \"src/Tensor/TensorLayoutSwap.h\"\n#include \"src/Tensor/TensorMorphing.h\"\n#include \"src/Tensor/TensorPadding.h\"\n#include \"src/Tensor/TensorReverse.h\"\n#include \"src/Tensor/TensorShuffling.h\"\n#include \"src/Tensor/TensorStriding.h\"\n#include \"src/Tensor/TensorCustomOp.h\"\n#include \"src/Tensor/TensorEvalTo.h\"\n#include \"src/Tensor/TensorForcedEval.h\"\n#include \"src/Tensor/TensorGenerator.h\"\n#include \"src/Tensor/TensorAssign.h\"\n#include \"src/Tensor/TensorScan.h\"\n#include \"src/Tensor/TensorTrace.h\"\n\n#ifdef EIGEN_USE_SYCL\n#include \"src/Tensor/TensorReductionSycl.h\"\n#include \"src/Tensor/TensorConvolutionSycl.h\"\n#include \"src/Tensor/TensorContractionSycl.h\"\n#include \"src/Tensor/TensorScanSycl.h\"\n#endif\n\n#include \"src/Tensor/TensorExecutor.h\"\n#include \"src/Tensor/TensorDevice.h\"\n\n#include \"src/Tensor/TensorStorage.h\"\n#include \"src/Tensor/Tensor.h\"\n#include \"src/Tensor/TensorFixedSize.h\"\n#include \"src/Tensor/TensorMap.h\"\n#include \"src/Tensor/TensorRef.h\"\n\n#include \"src/Tensor/TensorIO.h\"\n\n#include \"../../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif  // EIGEN_HAS_CXX11\n//#endif // EIGEN_CXX11_TENSOR_MODULE\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/TensorSymmetry",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSORSYMMETRY_MODULE\n#define EIGEN_CXX11_TENSORSYMMETRY_MODULE\n\n#include \"Tensor\"\n\n#include \"../../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n#include \"src/util/CXX11Meta.h\"\n\n/** \\defgroup CXX11_TensorSymmetry_Module Tensor Symmetry Module\n  *\n  * This module provides a classes that allow for the definition of\n  * symmetries w.r.t. tensor indices.\n  *\n  * Including this module will implicitly include the Tensor module.\n  *\n  * \\code\n  * #include <Eigen/TensorSymmetry>\n  * \\endcode\n  */\n\n#include \"src/TensorSymmetry/util/TemplateGroupTheory.h\"\n#include \"src/TensorSymmetry/Symmetry.h\"\n#include \"src/TensorSymmetry/StaticSymmetry.h\"\n#include \"src/TensorSymmetry/DynamicSymmetry.h\"\n\n#include \"../../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_CXX11_TENSORSYMMETRY_MODULE\n\n/*\n * kate: space-indent on; indent-width 2; mixedindent off; indent-mode cstyle;\n */\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/ThreadPool",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_THREADPOOL_MODULE\n#define EIGEN_CXX11_THREADPOOL_MODULE\n\n#include \"../../../Eigen/Core\"\n\n#include \"../../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n/** \\defgroup CXX11_ThreadPool_Module C++11 ThreadPool Module\n  *\n  * This module provides 2 threadpool implementations\n  *  - a simple reference implementation\n  *  - a faster non blocking implementation\n  *\n  * This module requires C++11.\n  *\n  * \\code\n  * #include <Eigen/CXX11/ThreadPool>\n  * \\endcode\n  */\n\n\n// The code depends on CXX11, so only include the module if the\n// compiler supports it.\n#if (EIGEN_COMP_CXXVER >= 11)\n#include <cstddef>\n#include <cstring>\n#include <time.h>\n\n#include <vector>\n#include <atomic>\n#include <condition_variable>\n#include <deque>\n#include <mutex>\n#include <thread>\n#include <functional>\n#include <memory>\n#include <utility>\n\n// There are non-parenthesized calls to \"max\" in the  <unordered_map> header,\n// which trigger a check in test/main.h causing compilation to fail.\n// We work around the check here by removing the check for max in\n// the case where we have to emulate thread_local.\n#ifdef max\n#undef max\n#endif\n#include <unordered_map>\n\n#include \"src/util/CXX11Meta.h\"\n#include \"src/util/MaxSizeVector.h\"\n\n#include \"src/ThreadPool/ThreadLocal.h\"\n#include \"src/ThreadPool/ThreadYield.h\"\n#include \"src/ThreadPool/ThreadCancel.h\"\n#include \"src/ThreadPool/EventCount.h\"\n#include \"src/ThreadPool/RunQueue.h\"\n#include \"src/ThreadPool/ThreadPoolInterface.h\"\n#include \"src/ThreadPool/ThreadEnvironment.h\"\n#include \"src/ThreadPool/Barrier.h\"\n#include \"src/ThreadPool/NonBlockingThreadPool.h\"\n\n#endif\n\n#include \"../../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_CXX11_THREADPOOL_MODULE\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/README.md",
    "content": "# Eigen Tensors {#eigen_tensors}\n\nTensors are multidimensional arrays of elements. Elements are typically scalars,\nbut more complex types such as strings are also supported.\n\n[TOC]\n\n## Tensor Classes\n\nYou can manipulate a tensor with one of the following classes.  They all are in\nthe namespace `::Eigen.`\n\n\n### Class Tensor<data_type, rank>\n\nThis is the class to use to create a tensor and allocate memory for it.  The\nclass is templatized with the tensor datatype, such as float or int, and the\ntensor rank.  The rank is the number of dimensions, for example rank 2 is a\nmatrix.\n\nTensors of this class are resizable.  For example, if you assign a tensor of a\ndifferent size to a Tensor, that tensor is resized to match its new value.\n\n#### Constructor `Tensor<data_type, rank>(size0, size1, ...)`\n\nConstructor for a Tensor.  The constructor must be passed `rank` integers\nindicating the sizes of the instance along each of the the `rank`\ndimensions.\n\n    // Create a tensor of rank 3 of sizes 2, 3, 4.  This tensor owns\n    // memory to hold 24 floating point values (24 = 2 x 3 x 4).\n    Tensor<float, 3> t_3d(2, 3, 4);\n\n    // Resize t_3d by assigning a tensor of different sizes, but same rank.\n    t_3d = Tensor<float, 3>(3, 4, 3);\n\n#### Constructor `Tensor<data_type, rank>(size_array)`\n\nConstructor where the sizes for the constructor are specified as an array of\nvalues instead of an explicitly list of parameters.  The array type to use is\n`Eigen::array<Eigen::Index>`.  The array can be constructed automatically\nfrom an initializer list.\n\n    // Create a tensor of strings of rank 2 with sizes 5, 7.\n    Tensor<string, 2> t_2d({5, 7});\n\n\n### Class `TensorFixedSize<data_type, Sizes<size0, size1, ...>>`\n\nClass to use for tensors of fixed size, where the size is known at compile\ntime.  Fixed sized tensors can provide very fast computations because all their\ndimensions are known by the compiler.  FixedSize tensors are not resizable.\n\nIf the total number of elements in a fixed size tensor is small enough the\ntensor data is held onto the stack and does not cause heap allocation and free.\n\n    // Create a 4 x 3 tensor of floats.\n    TensorFixedSize<float, Sizes<4, 3>> t_4x3;\n\n### Class `TensorMap<Tensor<data_type, rank>>`\n\nThis is the class to use to create a tensor on top of memory allocated and\nowned by another part of your code.  It allows to view any piece of allocated\nmemory as a Tensor.  Instances of this class do not own the memory where the\ndata are stored.\n\nA TensorMap is not resizable because it does not own the memory where its data\nare stored.\n\n#### Constructor `TensorMap<Tensor<data_type, rank>>(data, size0, size1, ...)`\n\nConstructor for a Tensor.  The constructor must be passed a pointer to the\nstorage for the data, and \"rank\" size attributes.  The storage has to be\nlarge enough to hold all the data.\n\n    // Map a tensor of ints on top of stack-allocated storage.\n    int storage[128];  // 2 x 4 x 2 x 8 = 128\n    TensorMap<Tensor<int, 4>> t_4d(storage, 2, 4, 2, 8);\n\n    // The same storage can be viewed as a different tensor.\n    // You can also pass the sizes as an array.\n    TensorMap<Tensor<int, 2>> t_2d(storage, 16, 8);\n\n    // You can also map fixed-size tensors.  Here we get a 1d view of\n    // the 2d fixed-size tensor.\n    TensorFixedSize<float, Sizes<4, 3>> t_4x3;\n    TensorMap<Tensor<float, 1>> t_12(t_4x3.data(), 12);\n\n\n#### Class `TensorRef`\n\nSee Assigning to a TensorRef below.\n\n## Accessing Tensor Elements\n\n#### `<data_type> tensor(index0, index1...)`\n\nReturn the element at position `(index0, index1...)` in tensor\n`tensor`.  You must pass as many parameters as the rank of `tensor`.\nThe expression can be used as an l-value to set the value of the element at the\nspecified position.  The value returned is of the datatype of the tensor.\n\n    // Set the value of the element at position (0, 1, 0);\n    Tensor<float, 3> t_3d(2, 3, 4);\n    t_3d(0, 1, 0) = 12.0f;\n\n    // Initialize all elements to random values.\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 3; ++j) {\n        for (int k = 0; k < 4; ++k) {\n          t_3d(i, j, k) = ...some random value...;\n        }\n      }\n    }\n\n    // Print elements of a tensor.\n    for (int i = 0; i < 2; ++i) {\n      LOG(INFO) << t_3d(i, 0, 0);\n    }\n\n\n## TensorLayout\n\nThe tensor library supports 2 layouts: `ColMajor` (the default) and\n`RowMajor`.  Only the default column major layout is currently fully\nsupported, and it is therefore not recommended to attempt to use the row major\nlayout at the moment.\n\nThe layout of a tensor is optionally specified as part of its type. If not\nspecified explicitly column major is assumed.\n\n    Tensor<float, 3, ColMajor> col_major;  // equivalent to Tensor<float, 3>\n    TensorMap<Tensor<float, 3, RowMajor> > row_major(data, ...);\n\nAll the arguments to an expression must use the same layout. Attempting to mix\ndifferent layouts will result in a compilation error.\n\nIt is possible to change the layout of a tensor or an expression using the\n`swap_layout()` method.  Note that this will also reverse the order of the\ndimensions.\n\n    Tensor<float, 2, ColMajor> col_major(2, 4);\n    Tensor<float, 2, RowMajor> row_major(2, 4);\n\n    Tensor<float, 2> col_major_result = col_major;  // ok, layouts match\n    Tensor<float, 2> col_major_result = row_major;  // will not compile\n\n    // Simple layout swap\n    col_major_result = row_major.swap_layout();\n    eigen_assert(col_major_result.dimension(0) == 4);\n    eigen_assert(col_major_result.dimension(1) == 2);\n\n    // Swap the layout and preserve the order of the dimensions\n    array<int, 2> shuffle(1, 0);\n    col_major_result = row_major.swap_layout().shuffle(shuffle);\n    eigen_assert(col_major_result.dimension(0) == 2);\n    eigen_assert(col_major_result.dimension(1) == 4);\n\n\n## Tensor Operations\n\nThe Eigen Tensor library provides a vast library of operations on Tensors:\nnumerical operations such as addition and multiplication, geometry operations\nsuch as slicing and shuffling, etc.  These operations are available as methods\nof the Tensor classes, and in some cases as operator overloads.  For example\nthe following code computes the elementwise addition of two tensors:\n\n    Tensor<float, 3> t1(2, 3, 4);\n    ...set some values in t1...\n    Tensor<float, 3> t2(2, 3, 4);\n    ...set some values in t2...\n    // Set t3 to the element wise sum of t1 and t2\n    Tensor<float, 3> t3 = t1 + t2;\n\nWhile the code above looks easy enough, it is important to understand that the\nexpression `t1 + t2` is not actually adding the values of the tensors.  The\nexpression instead constructs a \"tensor operator\" object of the class\nTensorCwiseBinaryOp<scalar_sum>, which has references to the tensors\n`t1` and `t2`.  This is a small C++ object that knows how to add\n`t1` and `t2`.  It is only when the value of the expression is assigned\nto the tensor `t3` that the addition is actually performed.  Technically,\nthis happens through the overloading of `operator=()` in the Tensor class.\n\nThis mechanism for computing tensor expressions allows for lazy evaluation and\noptimizations which are what make the tensor library very fast.\n\nOf course, the tensor operators do nest, and the expression `t1 + t2 * 0.3f`\nis actually represented with the (approximate) tree of operators:\n\n    TensorCwiseBinaryOp<scalar_sum>(t1, TensorCwiseUnaryOp<scalar_mul>(t2, 0.3f))\n\n\n### Tensor Operations and C++ \"auto\"\n\nBecause Tensor operations create tensor operators, the C++ `auto` keyword\ndoes not have its intuitive meaning.  Consider these 2 lines of code:\n\n    Tensor<float, 3> t3 = t1 + t2;\n    auto t4 = t1 + t2;\n\nIn the first line we allocate the tensor `t3` and it will contain the\nresult of the addition of `t1` and `t2`.  In the second line, `t4`\nis actually the tree of tensor operators that will compute the addition of\n`t1` and `t2`.  In fact, `t4` is *not* a tensor and you cannot get\nthe values of its elements:\n\n    Tensor<float, 3> t3 = t1 + t2;\n    cout << t3(0, 0, 0);  // OK prints the value of t1(0, 0, 0) + t2(0, 0, 0)\n\n    auto t4 = t1 + t2;\n    cout << t4(0, 0, 0);  // Compilation error!\n\nWhen you use `auto` you do not get a Tensor as a result but instead a\nnon-evaluated expression.  So only use `auto` to delay evaluation.\n\nUnfortunately, there is no single underlying concrete type for holding\nnon-evaluated expressions, hence you have to use auto in the case when you do\nwant to hold non-evaluated expressions.\n\nWhen you need the results of set of tensor computations you have to assign the\nresult to a Tensor that will be capable of holding onto them.  This can be\neither a normal Tensor, a fixed size Tensor, or a TensorMap on an existing\npiece of memory.  All the following will work:\n\n    auto t4 = t1 + t2;\n\n    Tensor<float, 3> result = t4;  // Could also be: result(t4);\n    cout << result(0, 0, 0);\n\n    TensorMap<float, 4> result(<a float* with enough space>, <size0>, ...) = t4;\n    cout << result(0, 0, 0);\n\n    TensorFixedSize<float, Sizes<size0, ...>> result = t4;\n    cout << result(0, 0, 0);\n\nUntil you need the results, you can keep the operation around, and even reuse\nit for additional operations.  As long as you keep the expression as an\noperation, no computation is performed.\n\n    // One way to compute exp((t1 + t2) * 0.2f);\n    auto t3 = t1 + t2;\n    auto t4 = t3 * 0.2f;\n    auto t5 = t4.exp();\n    Tensor<float, 3> result = t5;\n\n    // Another way, exactly as efficient as the previous one:\n    Tensor<float, 3> result = ((t1 + t2) * 0.2f).exp();\n\n### Controlling When Expression are Evaluated\n\nThere are several ways to control when expressions are evaluated:\n\n*   Assignment to a Tensor, TensorFixedSize, or TensorMap.\n*   Use of the eval() method.\n*   Assignment to a TensorRef.\n\n#### Assigning to a Tensor, TensorFixedSize, or TensorMap.\n\nThe most common way to evaluate an expression is to assign it to a Tensor.  In\nthe example below, the `auto` declarations make the intermediate values\n\"Operations\", not Tensors, and do not cause the expressions to be evaluated.\nThe assignment to the Tensor `result` causes the evaluation of all the\noperations.\n\n    auto t3 = t1 + t2;             // t3 is an Operation.\n    auto t4 = t3 * 0.2f;           // t4 is an Operation.\n    auto t5 = t4.exp();            // t5 is an Operation.\n    Tensor<float, 3> result = t5;  // The operations are evaluated.\n\nIf you know the ranks and sizes of the Operation value you can assign the\nOperation to a TensorFixedSize instead of a Tensor, which is a bit more\nefficient.\n\n    // We know that the result is a 4x4x2 tensor!\n    TensorFixedSize<float, Sizes<4, 4, 2>> result = t5;\n\nSimiarly, assigning an expression to a TensorMap causes its evaluation.  Like\ntensors of type TensorFixedSize, TensorMaps cannot be resized so they have to\nhave the rank and sizes of the expression that are assigned to them.\n\n#### Calling `eval()`.\n\nWhen you compute large composite expressions, you sometimes want to tell Eigen\nthat an intermediate value in the expression tree is worth evaluating ahead of\ntime.  This is done by inserting a call to the `eval()` method of the\nexpression Operation.\n\n    // The previous example could have been written:\n    Tensor<float, 3> result = ((t1 + t2) * 0.2f).exp();\n\n    // If you want to compute (t1 + t2) once ahead of time you can write:\n    Tensor<float, 3> result = ((t1 + t2).eval() * 0.2f).exp();\n\nSemantically, calling `eval()` is equivalent to materializing the value of\nthe expression in a temporary Tensor of the right size.  The code above in\neffect does:\n\n    // .eval() knows the size!\n    TensorFixedSize<float, Sizes<4, 4, 2>> tmp = t1 + t2;\n    Tensor<float, 3> result = (tmp * 0.2f).exp();\n\nNote that the return value of `eval()` is itself an Operation, so the\nfollowing code does not do what you may think:\n\n    // Here t3 is an evaluation Operation.  t3 has not been evaluated yet.\n    auto t3 = (t1 + t2).eval();\n\n    // You can use t3 in another expression.  Still no evaluation.\n    auto t4 = (t3 * 0.2f).exp();\n\n    // The value is evaluated when you assign the Operation to a Tensor, using\n    // an intermediate tensor to represent t3.x\n    Tensor<float, 3> result = t4;\n\nWhile in the examples above calling `eval()` does not make a difference in\nperformance, in other cases it can make a huge difference.  In the expression\nbelow the `broadcast()` expression causes the `X.maximum()` expression\nto be evaluated many times:\n\n    Tensor<...> X ...;\n    Tensor<...> Y = ((X - X.maximum(depth_dim).reshape(dims2d).broadcast(bcast))\n                     * beta).exp();\n\nInserting a call to `eval()` between the `maximum()` and\n`reshape()` calls guarantees that maximum() is only computed once and\ngreatly speeds-up execution:\n\n    Tensor<...> Y =\n      ((X - X.maximum(depth_dim).eval().reshape(dims2d).broadcast(bcast))\n        * beta).exp();\n\nIn the other example below, the tensor `Y` is both used in the expression\nand its assignment.  This is an aliasing problem and if the evaluation is not\ndone in the right order Y will be updated incrementally during the evaluation\nresulting in bogus results:\n\n     Tensor<...> Y ...;\n     Y = Y / (Y.sum(depth_dim).reshape(dims2d).broadcast(bcast));\n\nInserting a call to `eval()` between the `sum()` and `reshape()`\nexpressions ensures that the sum is computed before any updates to `Y` are\ndone.\n\n     Y = Y / (Y.sum(depth_dim).eval().reshape(dims2d).broadcast(bcast));\n\nNote that an eval around the full right hand side expression is not needed\nbecause the generated has to compute the i-th value of the right hand side\nbefore assigning it to the left hand side.\n\nHowever, if you were assigning the expression value to a shuffle of `Y`\nthen you would need to force an eval for correctness by adding an `eval()`\ncall for the right hand side:\n\n     Y.shuffle(...) =\n        (Y / (Y.sum(depth_dim).eval().reshape(dims2d).broadcast(bcast))).eval();\n\n\n#### Assigning to a `TensorRef`.\n\nIf you need to access only a few elements from the value of an expression you\ncan avoid materializing the value in a full tensor by using a TensorRef.\n\nA TensorRef is a small wrapper class for any Eigen Operation.  It provides\noverloads for the `()` operator that let you access individual values in\nthe expression.  TensorRef is convenient, because the Operation themselves do\nnot provide a way to access individual elements.\n\n    // Create a TensorRef for the expression.  The expression is not\n    // evaluated yet.\n    TensorRef<Tensor<float, 3> > ref = ((t1 + t2) * 0.2f).exp();\n\n    // Use \"ref\" to access individual elements.  The expression is evaluated\n    // on the fly.\n    float at_0 = ref(0, 0, 0);\n    cout << ref(0, 1, 0);\n\nOnly use TensorRef when you need a subset of the values of the expression.\nTensorRef only computes the values you access.  However note that if you are\ngoing to access all the values it will be much faster to materialize the\nresults in a Tensor first.\n\nIn some cases, if the full Tensor result would be very large, you may save\nmemory by accessing it as a TensorRef.  But not always.  So don't count on it.\n\n\n### Controlling How Expressions Are Evaluated\n\nThe tensor library provides several implementations of the various operations\nsuch as contractions and convolutions.  The implementations are optimized for\ndifferent environments: single threaded on CPU, multi threaded on CPU, or on a\nGPU using cuda.  Additional implementations may be added later.\n\nYou can choose which implementation to use with the `device()` call.  If\nyou do not choose an implementation explicitly the default implementation that\nuses a single thread on the CPU is used.\n\nThe default implementation has been optimized for recent Intel CPUs, taking\nadvantage of SSE, AVX, and FMA instructions.  Work is ongoing to tune the\nlibrary on ARM CPUs.  Note that you need to pass compiler-dependent flags\nto enable the use of SSE, AVX, and other instructions.\n\nFor example, the following code adds two tensors using the default\nsingle-threaded CPU implementation:\n\n    Tensor<float, 2> a(30, 40);\n    Tensor<float, 2> b(30, 40);\n    Tensor<float, 2> c = a + b;\n\nTo choose a different implementation you have to insert a `device()` call\nbefore the assignment of the result.  For technical C++ reasons this requires\nthat the Tensor for the result be declared on its own.  This means that you\nhave to know the size of the result.\n\n    Eigen::Tensor<float, 2> c(30, 40);\n    c.device(...) = a + b;\n\nThe call to `device()` must be the last call on the left of the operator=.\n\nYou must pass to the `device()` call an Eigen device object.  There are\npresently three devices you can use: DefaultDevice, ThreadPoolDevice and\nGpuDevice.\n\n\n#### Evaluating With the DefaultDevice\n\nThis is exactly the same as not inserting a `device()` call.\n\n    DefaultDevice my_device;\n    c.device(my_device) = a + b;\n\n#### Evaluating with a Thread Pool\n\n    // Create the Eigen ThreadPool\n    Eigen::ThreadPool pool(8 /* number of threads in pool */)\n\n    // Create the Eigen ThreadPoolDevice.\n    Eigen::ThreadPoolDevice my_device(&pool, 4 /* number of threads to use */);\n\n    // Now just use the device when evaluating expressions.\n    Eigen::Tensor<float, 2> c(30, 50);\n    c.device(my_device) = a.contract(b, dot_product_dims);\n\n\n#### Evaluating On GPU\n\nThis is presently a bit more complicated than just using a thread pool device.\nYou need to create a GPU device but you also need to explicitly allocate the\nmemory for tensors with cuda.\n\n\n## API Reference\n\n### Datatypes\n\nIn the documentation of the tensor methods and Operation we mention datatypes\nthat are tensor-type specific:\n\n#### `<Tensor-Type>::``Dimensions`\n\nActs like an array of ints.  Has an `int size` attribute, and can be\nindexed like an array to access individual values.  Used to represent the\ndimensions of a tensor.  See `dimensions()`.\n\n#### `<Tensor-Type>::``Index`\n\nActs like an `int`.  Used for indexing tensors along their dimensions.  See\n`operator()`, `dimension()`, and `size()`.\n\n#### `<Tensor-Type>::``Scalar`\n\nRepresents the datatype of individual tensor elements.  For example, for a\n`Tensor<float>`, `Scalar` is the type `float`.  See\n`setConstant()`.\n\n#### `<Operation>`\n\nWe use this pseudo type to indicate that a tensor Operation is returned by a\nmethod.  We indicate in the text the type and dimensions of the tensor that the\nOperation returns after evaluation.\n\nThe Operation will have to be evaluated, for example by assigning it to a\ntensor, before you can access the values of the resulting tensor.  You can also\naccess the values through a TensorRef.\n\n\n## Built-in Tensor Methods\n\nThese are usual C++ methods that act on tensors immediately.  They are not\nOperations which provide delayed evaluation of their results.  Unless specified\notherwise, all the methods listed below are available on all tensor classes:\nTensor, TensorFixedSize, and TensorMap.\n\n## Metadata\n\n### `int NumDimensions`\n\nConstant value indicating the number of dimensions of a Tensor.  This is also\nknown as the tensor \"rank\".\n\n      Eigen::Tensor<float, 2> a(3, 4);\n      cout << \"Dims \" << a.NumDimensions;\n      => Dims 2\n\n### `Dimensions dimensions()`\n\nReturns an array-like object representing the dimensions of the tensor.\nThe actual type of the `dimensions()` result is `<Tensor-Type>::``Dimensions`.\n\n    Eigen::Tensor<float, 2> a(3, 4);\n    const Eigen::Tensor<float, 2>::Dimensions& d = a.dimensions();\n    cout << \"Dim size: \" << d.size << \", dim 0: \" << d[0]\n         << \", dim 1: \" << d[1];\n    => Dim size: 2, dim 0: 3, dim 1: 4\n\nIf you use a C++11 compiler, you can use `auto` to simplify the code:\n\n    const auto& d = a.dimensions();\n    cout << \"Dim size: \" << d.size << \", dim 0: \" << d[0]\n         << \", dim 1: \" << d[1];\n    => Dim size: 2, dim 0: 3, dim 1: 4\n\n### `Index dimension(Index n)`\n\nReturns the n-th dimension of the tensor.  The actual type of the\n`dimension()` result is `<Tensor-Type>::``Index`, but you can\nalways use it like an int.\n\n      Eigen::Tensor<float, 2> a(3, 4);\n      int dim1 = a.dimension(1);\n      cout << \"Dim 1: \" << dim1;\n      => Dim 1: 4\n\n### `Index size()`\n\nReturns the total number of elements in the tensor.  This is the product of all\nthe tensor dimensions.  The actual type of the `size()` result is\n`<Tensor-Type>::``Index`, but you can always use it like an int.\n\n    Eigen::Tensor<float, 2> a(3, 4);\n    cout << \"Size: \" << a.size();\n    => Size: 12\n\n\n### Getting Dimensions From An Operation\n\nA few operations provide `dimensions()` directly,\ne.g. `TensorReslicingOp`.  Most operations defer calculating dimensions\nuntil the operation is being evaluated.  If you need access to the dimensions\nof a deferred operation, you can wrap it in a TensorRef (see Assigning to a\nTensorRef above), which provides `dimensions()` and `dimension()` as\nabove.\n\nTensorRef can also wrap the plain Tensor types, so this is a useful idiom in\ntemplated contexts where the underlying object could be either a raw Tensor\nor some deferred operation (e.g. a slice of a Tensor).  In this case, the\ntemplate code can wrap the object in a TensorRef and reason about its\ndimensionality while remaining agnostic to the underlying type.\n\n\n## Constructors\n\n### Tensor\n\nCreates a tensor of the specified size. The number of arguments must be equal\nto the rank of the tensor. The content of the tensor is not initialized.\n\n    Eigen::Tensor<float, 2> a(3, 4);\n    cout << \"NumRows: \" << a.dimension(0) << \" NumCols: \" << a.dimension(1) << endl;\n    => NumRows: 3 NumCols: 4\n\n### TensorFixedSize\n\nCreates a tensor of the specified size. The number of arguments in the Sizes<>\ntemplate parameter determines the rank of the tensor. The content of the tensor\nis not initialized.\n\n    Eigen::TensorFixedSize<float, Sizes<3, 4>> a;\n    cout << \"Rank: \" << a.rank() << endl;\n    => Rank: 2\n    cout << \"NumRows: \" << a.dimension(0) << \" NumCols: \" << a.dimension(1) << endl;\n    => NumRows: 3 NumCols: 4\n\n### TensorMap\n\nCreates a tensor mapping an existing array of data. The data must not be freed\nuntil the TensorMap is discarded, and the size of the data must be large enough\nto accommodate the coefficients of the tensor.\n\n    float data[] = {0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11};\n    Eigen::TensorMap<Tensor<float, 2>> a(data, 3, 4);\n    cout << \"NumRows: \" << a.dimension(0) << \" NumCols: \" << a.dimension(1) << endl;\n    => NumRows: 3 NumCols: 4\n    cout << \"a(1, 2): \" << a(1, 2) << endl;\n    => a(1, 2): 7\n\n\n## Contents Initialization\n\nWhen a new Tensor or a new TensorFixedSize are created, memory is allocated to\nhold all the tensor elements, but the memory is not initialized.  Similarly,\nwhen a new TensorMap is created on top of non-initialized memory the memory its\ncontents are not initialized.\n\nYou can use one of the methods below to initialize the tensor memory.  These\nhave an immediate effect on the tensor and return the tensor itself as a\nresult.  These are not tensor Operations which delay evaluation.\n\n### `<Tensor-Type> setConstant(const Scalar& val)`\n\nSets all elements of the tensor to the constant value `val`.  `Scalar`\nis the type of data stored in the tensor.  You can pass any value that is\nconvertible to that type.\n\nReturns the tensor itself in case you want to chain another call.\n\n    a.setConstant(12.3f);\n    cout << \"Constant: \" << endl << a << endl << endl;\n    =>\n    Constant:\n    12.3 12.3 12.3 12.3\n    12.3 12.3 12.3 12.3\n    12.3 12.3 12.3 12.3\n\nNote that `setConstant()` can be used on any tensor where the element type\nhas a copy constructor and an `operator=()`:\n\n    Eigen::Tensor<string, 2> a(2, 3);\n    a.setConstant(\"yolo\");\n    cout << \"String tensor: \" << endl << a << endl << endl;\n    =>\n    String tensor:\n    yolo yolo yolo\n    yolo yolo yolo\n\n\n### `<Tensor-Type> setZero()`\n\nFills the tensor with zeros.  Equivalent to `setConstant(Scalar(0))`.\nReturns the tensor itself in case you want to chain another call.\n\n    a.setZero();\n    cout << \"Zeros: \" << endl << a << endl << endl;\n    =>\n    Zeros:\n    0 0 0 0\n    0 0 0 0\n    0 0 0 0\n\n\n### `<Tensor-Type> setValues({..initializer_list})`\n\nFills the tensor with explicit values specified in a std::initializer_list.\nThe type of the initializer list depends on the type and rank of the tensor.\n\nIf the tensor has rank N, the initializer list must be nested N times.  The\nmost deeply nested lists must contains P scalars of the Tensor type where P is\nthe size of the last dimension of the Tensor.\n\nFor example, for a `TensorFixedSize<float, 2, 3>` the initializer list must\ncontains 2 lists of 3 floats each.\n\n`setValues()` returns the tensor itself in case you want to chain another\ncall.\n\n    Eigen::Tensor<float, 2> a(2, 3);\n    a.setValues({{0.0f, 1.0f, 2.0f}, {3.0f, 4.0f, 5.0f}});\n    cout << \"a\" << endl << a << endl << endl;\n    =>\n    a\n    0 1 2\n    3 4 5\n\nIf a list is too short, the corresponding elements of the tensor will not be\nchanged.  This is valid at each level of nesting.  For example the following\ncode only sets the values of the first row of the tensor.\n\n    Eigen::Tensor<int, 2> a(2, 3);\n    a.setConstant(1000);\n    a.setValues({{10, 20, 30}});\n    cout << \"a\" << endl << a << endl << endl;\n    =>\n    a\n    10   20   30\n    1000 1000 1000\n\n### `<Tensor-Type> setRandom()`\n\nFills the tensor with random values.  Returns the tensor itself in case you\nwant to chain another call.\n\n    a.setRandom();\n    cout << \"Random: \" << endl << a << endl << endl;\n    =>\n    Random:\n      0.680375    0.59688  -0.329554    0.10794\n     -0.211234   0.823295   0.536459 -0.0452059\n      0.566198  -0.604897  -0.444451   0.257742\n\nYou can customize `setRandom()` by providing your own random number\ngenerator as a template argument:\n\n    a.setRandom<MyRandomGenerator>();\n\nHere, `MyRandomGenerator` must be a struct with the following member\nfunctions, where Scalar and Index are the same as `<Tensor-Type>::``Scalar`\nand `<Tensor-Type>::``Index`.\n\nSee `struct UniformRandomGenerator` in TensorFunctors.h for an example.\n\n    // Custom number generator for use with setRandom().\n    struct MyRandomGenerator {\n      // Default and copy constructors. Both are needed\n      MyRandomGenerator() { }\n      MyRandomGenerator(const MyRandomGenerator& ) { }\n\n      // Return a random value to be used.  \"element_location\" is the\n      // location of the entry to set in the tensor, it can typically\n      // be ignored.\n      Scalar operator()(Eigen::DenseIndex element_location,\n                        Eigen::DenseIndex /*unused*/ = 0) const {\n        return <randomly generated value of type T>;\n      }\n\n      // Same as above but generates several numbers at a time.\n      typename internal::packet_traits<Scalar>::type packetOp(\n          Eigen::DenseIndex packet_location, Eigen::DenseIndex /*unused*/ = 0) const {\n        return <a packet of randomly generated values>;\n      }\n    };\n\nYou can also use one of the 2 random number generators that are part of the\ntensor library:\n*   UniformRandomGenerator\n*   NormalRandomGenerator\n\n\n## Data Access\n\nThe Tensor, TensorFixedSize, and TensorRef classes provide the following\naccessors to access the tensor coefficients:\n\n    const Scalar& operator()(const array<Index, NumIndices>& indices)\n    const Scalar& operator()(Index firstIndex, IndexTypes... otherIndices)\n    Scalar& operator()(const array<Index, NumIndices>& indices)\n    Scalar& operator()(Index firstIndex, IndexTypes... otherIndices)\n\nThe number of indices must be equal to the rank of the tensor. Moreover, these\naccessors are not available on tensor expressions. In order to access the\nvalues of a tensor expression, the expression must either be evaluated or\nwrapped in a TensorRef.\n\n\n### `Scalar* data()` and `const Scalar* data() const`\n\nReturns a pointer to the storage for the tensor.  The pointer is const if the\ntensor was const.  This allows direct access to the data.  The layout of the\ndata depends on the tensor layout: RowMajor or ColMajor.\n\nThis access is usually only needed for special cases, for example when mixing\nEigen Tensor code with other libraries.\n\nScalar is the type of data stored in the tensor.\n\n    Eigen::Tensor<float, 2> a(3, 4);\n    float* a_data = a.data();\n    a_data[0] = 123.45f;\n    cout << \"a(0, 0): \" << a(0, 0);\n    => a(0, 0): 123.45\n\n\n## Tensor Operations\n\nAll the methods documented below return non evaluated tensor `Operations`.\nThese can be chained: you can apply another Tensor Operation to the value\nreturned by the method.\n\nThe chain of Operation is evaluated lazily, typically when it is assigned to a\ntensor.  See \"Controlling when Expression are Evaluated\" for more details about\ntheir evaluation.\n\n### `<Operation> constant(const Scalar& val)`\n\nReturns a tensor of the same type and dimensions as the original tensor but\nwhere all elements have the value `val`.\n\nThis is useful, for example, when you want to add or subtract a constant from a\ntensor, or multiply every element of a tensor by a scalar.\n\n    Eigen::Tensor<float, 2> a(2, 3);\n    a.setConstant(1.0f);\n    Eigen::Tensor<float, 2> b = a + a.constant(2.0f);\n    Eigen::Tensor<float, 2> c = b * b.constant(0.2f);\n    cout << \"a\" << endl << a << endl << endl;\n    cout << \"b\" << endl << b << endl << endl;\n    cout << \"c\" << endl << c << endl << endl;\n    =>\n    a\n    1 1 1\n    1 1 1\n\n    b\n    3 3 3\n    3 3 3\n\n    c\n    0.6 0.6 0.6\n    0.6 0.6 0.6\n\n### `<Operation> random()`\n\nReturns a tensor of the same type and dimensions as the current tensor\nbut where all elements have random values.\n\nThis is for example useful to add random values to an existing tensor.\nThe generation of random values can be customized in the same manner\nas for `setRandom()`.\n\n    Eigen::Tensor<float, 2> a(2, 3);\n    a.setConstant(1.0f);\n    Eigen::Tensor<float, 2> b = a + a.random();\n    cout << \"a\" << endl << a << endl << endl;\n    cout << \"b\" << endl << b << endl << endl;\n    =>\n    a\n    1 1 1\n    1 1 1\n\n    b\n    1.68038   1.5662  1.82329\n    0.788766  1.59688 0.395103\n\n\n## Unary Element Wise Operations\n\nAll these operations take a single input tensor as argument and return a tensor\nof the same type and dimensions as the tensor to which they are applied.  The\nrequested operations are applied to each element independently.\n\n### `<Operation> operator-()`\n\nReturns a tensor of the same type and dimensions as the original tensor\ncontaining the opposite values of the original tensor.\n\n    Eigen::Tensor<float, 2> a(2, 3);\n    a.setConstant(1.0f);\n    Eigen::Tensor<float, 2> b = -a;\n    cout << \"a\" << endl << a << endl << endl;\n    cout << \"b\" << endl << b << endl << endl;\n    =>\n    a\n    1 1 1\n    1 1 1\n\n    b\n    -1 -1 -1\n    -1 -1 -1\n\n### `<Operation> sqrt()`\n\nReturns a tensor of the same type and dimensions as the original tensor\ncontaining the square roots of the original tensor.\n\n### `<Operation> rsqrt()`\n\nReturns a tensor of the same type and dimensions as the original tensor\ncontaining the inverse square roots of the original tensor.\n\n### `<Operation> square()`\n\nReturns a tensor of the same type and dimensions as the original tensor\ncontaining the squares of the original tensor values.\n\n### `<Operation> inverse()`\n\nReturns a tensor of the same type and dimensions as the original tensor\ncontaining the inverse of the original tensor values.\n\n### `<Operation> exp()`\n\nReturns a tensor of the same type and dimensions as the original tensor\ncontaining the exponential of the original tensor.\n\n### `<Operation> log()`\n\nReturns a tensor of the same type and dimensions as the original tensor\ncontaining the natural logarithms of the original tensor.\n\n### `<Operation> abs()`\n\nReturns a tensor of the same type and dimensions as the original tensor\ncontaining the absolute values of the original tensor.\n\n### `<Operation> pow(Scalar exponent)`\n\nReturns a tensor of the same type and dimensions as the original tensor\ncontaining the coefficients of the original tensor to the power of the\nexponent.\n\nThe type of the exponent, Scalar, is always the same as the type of the\ntensor coefficients.  For example, only integer exponents can be used in\nconjuntion with tensors of integer values.\n\nYou can use cast() to lift this restriction.  For example this computes\ncubic roots of an int Tensor:\n\n    Eigen::Tensor<int, 2> a(2, 3);\n    a.setValues({{0, 1, 8}, {27, 64, 125}});\n    Eigen::Tensor<double, 2> b = a.cast<double>().pow(1.0 / 3.0);\n    cout << \"a\" << endl << a << endl << endl;\n    cout << \"b\" << endl << b << endl << endl;\n    =>\n    a\n    0   1   8\n    27  64 125\n\n    b\n    0 1 2\n    3 4 5\n\n### `<Operation>  operator * (Scalar scale)`\n\nMultiplies all the coefficients of the input tensor by the provided scale.\n\n### `<Operation>  cwiseMax(Scalar threshold)`\nTODO\n\n### `<Operation>  cwiseMin(Scalar threshold)`\nTODO\n\n### `<Operation>  unaryExpr(const CustomUnaryOp& func)`\nTODO\n\n\n## Binary Element Wise Operations\n\nThese operations take two input tensors as arguments. The 2 input tensors should\nbe of the same type and dimensions. The result is a tensor of the same\ndimensions as the tensors to which they are applied, and unless otherwise\nspecified it is also of the same type. The requested operations are applied to\neach pair of elements independently.\n\n### `<Operation> operator+(const OtherDerived& other)`\n\nReturns a tensor of the same type and dimensions as the input tensors\ncontaining the coefficient wise sums of the inputs.\n\n### `<Operation> operator-(const OtherDerived& other)`\n\nReturns a tensor of the same type and dimensions as the input tensors\ncontaining the coefficient wise differences of the inputs.\n\n### `<Operation> operator*(const OtherDerived& other)`\n\nReturns a tensor of the same type and dimensions as the input tensors\ncontaining the coefficient wise products of the inputs.\n\n### `<Operation> operator/(const OtherDerived& other)`\n\nReturns a tensor of the same type and dimensions as the input tensors\ncontaining the coefficient wise quotients of the inputs.\n\nThis operator is not supported for integer types.\n\n### `<Operation> cwiseMax(const OtherDerived& other)`\n\nReturns a tensor of the same type and dimensions as the input tensors\ncontaining the coefficient wise maximums of the inputs.\n\n### `<Operation> cwiseMin(const OtherDerived& other)`\n\nReturns a tensor of the same type and dimensions as the input tensors\ncontaining the coefficient wise mimimums of the inputs.\n\n### `<Operation> Logical operators`\n\nThe following logical operators are supported as well:\n\n*   operator&&(const OtherDerived& other)\n*   operator||(const OtherDerived& other)\n*   operator<(const OtherDerived& other)\n*   operator<=(const OtherDerived& other)\n*   operator>(const OtherDerived& other)\n*   operator>=(const OtherDerived& other)\n*   operator==(const OtherDerived& other)\n*   operator!=(const OtherDerived& other)\n\nThey all return a tensor of boolean values.\n\n\n## Selection (select(const ThenDerived& thenTensor, const ElseDerived& elseTensor)\n\nSelection is a coefficient-wise ternary operator that is the tensor equivalent\nto the if-then-else operation.\n\n    Tensor<bool, 3> if = ...;\n    Tensor<float, 3> then = ...;\n    Tensor<float, 3> else = ...;\n    Tensor<float, 3> result = if.select(then, else);\n\nThe 3 arguments must be of the same dimensions, which will also be the dimension\nof the result.  The 'if' tensor must be of type boolean, the 'then' and the\n'else' tensor must be of the same type, which will also be the type of the\nresult.\n\nEach coefficient in the result is equal to the corresponding coefficient in the\n'then' tensor if the corresponding value in the 'if' tensor is true. If not, the\nresulting coefficient will come from the 'else' tensor.\n\n\n## Contraction\n\nTensor *contractions* are a generalization of the matrix product to the\nmultidimensional case.\n\n    // Create 2 matrices using tensors of rank 2\n    Eigen::Tensor<int, 2> a(2, 3);\n    a.setValues({{1, 2, 3}, {6, 5, 4}});\n    Eigen::Tensor<int, 2> b(3, 2);\n    b.setValues({{1, 2}, {4, 5}, {5, 6}});\n\n    // Compute the traditional matrix product\n    Eigen::array<Eigen::IndexPair<int>, 1> product_dims = { Eigen::IndexPair<int>(1, 0) };\n    Eigen::Tensor<int, 2> AB = a.contract(b, product_dims);\n\n    // Compute the product of the transpose of the matrices\n    Eigen::array<Eigen::IndexPair<int>, 1> transposed_product_dims = { Eigen::IndexPair<int>(0, 1) };\n    Eigen::Tensor<int, 2> AtBt = a.contract(b, transposed_product_dims);\n\n    // Contraction to scalar value using a double contraction.\n    // First coordinate of both tensors are contracted as well as both second coordinates, i.e., this computes the sum of the squares of the elements.\n    Eigen::array<Eigen::IndexPair<int>, 2> double_contraction_product_dims = { Eigen::IndexPair<int>(0, 0), Eigen::IndexPair<int>(1, 1) };\n    Eigen::Tensor<int, 0> AdoubleContractedA = a.contract(a, double_contraction_product_dims);\n\n    // Extracting the scalar value of the tensor contraction for further usage\n    int value = AdoubleContractedA(0);\n\n## Reduction Operations\n\nA *Reduction* operation returns a tensor with fewer dimensions than the\noriginal tensor.  The values in the returned tensor are computed by applying a\n*reduction operator* to slices of values from the original tensor.  You specify\nthe dimensions along which the slices are made.\n\nThe Eigen Tensor library provides a set of predefined reduction operators such\nas `maximum()` and `sum()` and lets you define additional operators by\nimplementing a few methods from a reductor template.\n\n### Reduction Dimensions\n\nAll reduction operations take a single parameter of type\n`<TensorType>::``Dimensions` which can always be specified as an array of\nints.  These are called the \"reduction dimensions.\"  The values are the indices\nof the dimensions of the input tensor over which the reduction is done.  The\nparameter can have at most as many element as the rank of the input tensor;\neach element must be less than the tensor rank, as it indicates one of the\ndimensions to reduce.\n\nEach dimension of the input tensor should occur at most once in the reduction\ndimensions as the implementation does not remove duplicates.\n\nThe order of the values in the reduction dimensions does not affect the\nresults, but the code may execute faster if you list the dimensions in\nincreasing order.\n\nExample: Reduction along one dimension.\n\n    // Create a tensor of 2 dimensions\n    Eigen::Tensor<int, 2> a(2, 3);\n    a.setValues({{1, 2, 3}, {6, 5, 4}});\n    // Reduce it along the second dimension (1)...\n    Eigen::array<int, 1> dims({1 /* dimension to reduce */});\n    // ...using the \"maximum\" operator.\n    // The result is a tensor with one dimension.  The size of\n    // that dimension is the same as the first (non-reduced) dimension of a.\n    Eigen::Tensor<int, 1> b = a.maximum(dims);\n    cout << \"a\" << endl << a << endl << endl;\n    cout << \"b\" << endl << b << endl << endl;\n    =>\n    a\n    1 2 3\n    6 5 4\n\n    b\n    3\n    6\n\nExample: Reduction along two dimensions.\n\n    Eigen::Tensor<float, 3, Eigen::ColMajor> a(2, 3, 4);\n    a.setValues({{{0.0f, 1.0f, 2.0f, 3.0f},\n                  {7.0f, 6.0f, 5.0f, 4.0f},\n                  {8.0f, 9.0f, 10.0f, 11.0f}},\n                 {{12.0f, 13.0f, 14.0f, 15.0f},\n                  {19.0f, 18.0f, 17.0f, 16.0f},\n                  {20.0f, 21.0f, 22.0f, 23.0f}}});\n    // The tensor a has 3 dimensions.  We reduce along the\n    // first 2, resulting in a tensor with a single dimension\n    // of size 4 (the last dimension of a.)\n    // Note that we pass the array of reduction dimensions\n    // directly to the maximum() call.\n    Eigen::Tensor<float, 1, Eigen::ColMajor> b =\n        a.maximum(Eigen::array<int, 2>({0, 1}));\n    cout << \"b\" << endl << b << endl << endl;\n    =>\n    b\n    20\n    21\n    22\n    23\n\n#### Reduction along all dimensions\n\nAs a special case, if you pass no parameter to a reduction operation the\noriginal tensor is reduced along *all* its dimensions.  The result is a\nscalar, represented as a zero-dimension tensor.\n\n    Eigen::Tensor<float, 3> a(2, 3, 4);\n    a.setValues({{{0.0f, 1.0f, 2.0f, 3.0f},\n                  {7.0f, 6.0f, 5.0f, 4.0f},\n                  {8.0f, 9.0f, 10.0f, 11.0f}},\n                 {{12.0f, 13.0f, 14.0f, 15.0f},\n                  {19.0f, 18.0f, 17.0f, 16.0f},\n                  {20.0f, 21.0f, 22.0f, 23.0f}}});\n    // Reduce along all dimensions using the sum() operator.\n    Eigen::Tensor<float, 0> b = a.sum();\n    cout << \"b\" << endl << b << endl << endl;\n    =>\n    b\n    276\n\n\n### `<Operation> sum(const Dimensions& new_dims)`\n### `<Operation> sum()`\n\nReduce a tensor using the sum() operator.  The resulting values\nare the sum of the reduced values.\n\n### `<Operation> mean(const Dimensions& new_dims)`\n### `<Operation> mean()`\n\nReduce a tensor using the mean() operator.  The resulting values\nare the mean of the reduced values.\n\n### `<Operation> maximum(const Dimensions& new_dims)`\n### `<Operation> maximum()`\n\nReduce a tensor using the maximum() operator.  The resulting values are the\nlargest of the reduced values.\n\n### `<Operation> minimum(const Dimensions& new_dims)`\n### `<Operation> minimum()`\n\nReduce a tensor using the minimum() operator.  The resulting values\nare the smallest of the reduced values.\n\n### `<Operation> prod(const Dimensions& new_dims)`\n### `<Operation> prod()`\n\nReduce a tensor using the prod() operator.  The resulting values\nare the product of the reduced values.\n\n### `<Operation> all(const Dimensions& new_dims)`\n### `<Operation> all()`\nReduce a tensor using the all() operator.  Casts tensor to bool and then checks\nwhether all elements are true.  Runs through all elements rather than\nshort-circuiting, so may be significantly inefficient.\n\n### `<Operation> any(const Dimensions& new_dims)`\n### `<Operation> any()`\nReduce a tensor using the any() operator.  Casts tensor to bool and then checks\nwhether any element is true.  Runs through all elements rather than\nshort-circuiting, so may be significantly inefficient.\n\n\n### `<Operation> reduce(const Dimensions& new_dims, const Reducer& reducer)`\n\nReduce a tensor using a user-defined reduction operator.  See `SumReducer`\nin TensorFunctors.h for information on how to implement a reduction operator.\n\n\n## Trace\n\nA *Trace* operation returns a tensor with fewer dimensions than the original\ntensor. It returns a tensor whose elements are the sum of the elements of the\noriginal tensor along the main diagonal for a list of specified dimensions, the\n\"trace dimensions\". Similar to the `Reduction Dimensions`, the trace dimensions\nare passed as an input parameter to the operation, are of type `<TensorType>::``Dimensions`\n, and have the same requirements when passed as an input parameter. In addition,\nthe trace dimensions must have the same size.\n\nExample: Trace along 2 dimensions.\n\n    // Create a tensor of 3 dimensions\n    Eigen::Tensor<int, 3> a(2, 2, 3);\n    a.setValues({{{1, 2, 3}, {4, 5, 6}}, {{7, 8, 9}, {10, 11, 12}}});\n    // Specify the dimensions along which the trace will be computed.\n    // In this example, the trace can only be computed along the dimensions\n    // with indices 0 and 1\n    Eigen::array<int, 2> dims({0, 1});\n    // The output tensor contains all but the trace dimensions.\n    Tensor<int, 1> a_trace = a.trace(dims);\n    cout << \"a_trace:\" << endl;\n    cout << a_trace << endl;\n    =>\n    a_trace:\n    11\n    13\n    15\n\n\n### `<Operation> trace(const Dimensions& new_dims)`\n### `<Operation> trace()`\n\nAs a special case, if no parameter is passed to the operation, trace is computed\nalong *all* dimensions of the input tensor.\n\nExample: Trace along all dimensions.\n\n    // Create a tensor of 3 dimensions, with all dimensions having the same size.\n    Eigen::Tensor<int, 3> a(3, 3, 3);\n    a.setValues({{{1, 2, 3}, {4, 5, 6}, {7, 8, 9}},\n                {{10, 11, 12}, {13, 14, 15}, {16, 17, 18}},\n                {{19, 20, 21}, {22, 23, 24}, {25, 26, 27}}});\n    // Result is a zero dimension tensor\n    Tensor<int, 0> a_trace = a.trace();\n    cout<<\"a_trace:\"<<endl;\n    cout<<a_trace<<endl;\n    =>\n    a_trace:\n    42\n\n\n## Scan Operations\n\nA *Scan* operation returns a tensor with the same dimensions as the original\ntensor. The operation performs an inclusive scan along the specified\naxis, which means it computes a running total along the axis for a given\nreduction operation.\nIf the reduction operation corresponds to summation, then this computes the\nprefix sum of the tensor along the given axis.\n\nExample:\ndd a comment to this line\n\n    // Create a tensor of 2 dimensions\n    Eigen::Tensor<int, 2> a(2, 3);\n    a.setValues({{1, 2, 3}, {4, 5, 6}});\n    // Scan it along the second dimension (1) using summation\n    Eigen::Tensor<int, 2> b = a.cumsum(1);\n    // The result is a tensor with the same size as the input\n    cout << \"a\" << endl << a << endl << endl;\n    cout << \"b\" << endl << b << endl << endl;\n    =>\n    a\n    1 2 3\n    4 5 6\n\n    b\n    1  3  6\n    4  9 15\n\n### `<Operation> cumsum(const Index& axis)`\n\nPerform a scan by summing consecutive entries.\n\n### `<Operation> cumprod(const Index& axis)`\n\nPerform a scan by multiplying consecutive entries.\n\n\n## Convolutions\n\n### `<Operation> convolve(const Kernel& kernel, const Dimensions& dims)`\n\nReturns a tensor that is the output of the convolution of the input tensor with the kernel,\nalong the specified dimensions of the input tensor. The dimension size for dimensions of the output tensor\nwhich were part of the convolution will be reduced by the formula:\noutput_dim_size = input_dim_size - kernel_dim_size + 1 (requires: input_dim_size >= kernel_dim_size).\nThe dimension sizes for dimensions that were not part of the convolution will remain the same.\nPerformance of the convolution can depend on the length of the stride(s) of the input tensor dimension(s) along which the\nconvolution is computed (the first dimension has the shortest stride for ColMajor, whereas RowMajor's shortest stride is\nfor the last dimension).\n\n    // Compute convolution along the second and third dimension.\n    Tensor<float, 4, DataLayout> input(3, 3, 7, 11);\n    Tensor<float, 2, DataLayout> kernel(2, 2);\n    Tensor<float, 4, DataLayout> output(3, 2, 6, 11);\n    input.setRandom();\n    kernel.setRandom();\n\n    Eigen::array<ptrdiff_t, 2> dims({1, 2});  // Specify second and third dimension for convolution.\n    output = input.convolve(kernel, dims);\n\n    for (int i = 0; i < 3; ++i) {\n      for (int j = 0; j < 2; ++j) {\n        for (int k = 0; k < 6; ++k) {\n          for (int l = 0; l < 11; ++l) {\n            const float result = output(i,j,k,l);\n            const float expected = input(i,j+0,k+0,l) * kernel(0,0) +\n                                   input(i,j+1,k+0,l) * kernel(1,0) +\n                                   input(i,j+0,k+1,l) * kernel(0,1) +\n                                   input(i,j+1,k+1,l) * kernel(1,1);\n            VERIFY_IS_APPROX(result, expected);\n          }\n        }\n      }\n    }\n\n\n## Geometrical Operations\n\nThese operations return a Tensor with different dimensions than the original\nTensor.  They can be used to access slices of tensors, see them with different\ndimensions, or pad tensors with additional data.\n\n### `<Operation> reshape(const Dimensions& new_dims)`\n\nReturns a view of the input tensor that has been reshaped to the specified\nnew dimensions.  The argument new_dims is an array of Index values.  The\nrank of the resulting tensor is equal to the number of elements in new_dims.\n\nThe product of all the sizes in the new dimension array must be equal to\nthe number of elements in the input tensor.\n\n    // Increase the rank of the input tensor by introducing a new dimension\n    // of size 1.\n    Tensor<float, 2> input(7, 11);\n    array<int, 3> three_dims{{7, 11, 1}};\n    Tensor<float, 3> result = input.reshape(three_dims);\n\n    // Decrease the rank of the input tensor by merging 2 dimensions;\n    array<int, 1> one_dim{{7 * 11}};\n    Tensor<float, 1> result = input.reshape(one_dim);\n\nThis operation does not move any data in the input tensor, so the resulting\ncontents of a reshaped Tensor depend on the data layout of the original Tensor.\n\nFor example this is what happens when you `reshape()` a 2D ColMajor tensor\nto one dimension:\n\n    Eigen::Tensor<float, 2, Eigen::ColMajor> a(2, 3);\n    a.setValues({{0.0f, 100.0f, 200.0f}, {300.0f, 400.0f, 500.0f}});\n    Eigen::array<Eigen::DenseIndex, 1> one_dim({3 * 2});\n    Eigen::Tensor<float, 1, Eigen::ColMajor> b = a.reshape(one_dim);\n    cout << \"b\" << endl << b << endl;\n    =>\n    b\n      0\n    300\n    100\n    400\n    200\n    500\n\nThis is what happens when the 2D Tensor is RowMajor:\n\n    Eigen::Tensor<float, 2, Eigen::RowMajor> a(2, 3);\n    a.setValues({{0.0f, 100.0f, 200.0f}, {300.0f, 400.0f, 500.0f}});\n    Eigen::array<Eigen::DenseIndex, 1> one_dim({3 * 2});\n    Eigen::Tensor<float, 1, Eigen::RowMajor> b = a.reshape(one_dim);\n    cout << \"b\" << endl << b << endl;\n    =>\n    b\n      0\n    100\n    200\n    300\n    400\n    500\n\nThe reshape operation is a lvalue. In other words, it can be used on the left\nside of the assignment operator.\n\nThe previous example can be rewritten as follow:\n\n    Eigen::Tensor<float, 2, Eigen::ColMajor> a(2, 3);\n    a.setValues({{0.0f, 100.0f, 200.0f}, {300.0f, 400.0f, 500.0f}});\n    Eigen::array<Eigen::DenseIndex, 2> two_dim({2, 3});\n    Eigen::Tensor<float, 1, Eigen::ColMajor> b(6);\n    b.reshape(two_dim) = a;\n    cout << \"b\" << endl << b << endl;\n    =>\n    b\n      0\n    300\n    100\n    400\n    200\n    500\n\nNote that \"b\" itself was not reshaped but that instead the assignment is done to\nthe reshape view of b.\n\n\n### `<Operation> shuffle(const Shuffle& shuffle)`\n\nReturns a copy of the input tensor whose dimensions have been\nreordered according to the specified permutation. The argument shuffle\nis an array of Index values. Its size is the rank of the input\ntensor. It must contain a permutation of 0, 1, ..., rank - 1. The i-th\ndimension of the output tensor equals to the size of the shuffle[i]-th\ndimension of the input tensor. For example:\n\n    // Shuffle all dimensions to the left by 1.\n    Tensor<float, 3> input(20, 30, 50);\n    // ... set some values in input.\n    Tensor<float, 3> output = input.shuffle({1, 2, 0})\n\n    eigen_assert(output.dimension(0) == 30);\n    eigen_assert(output.dimension(1) == 50);\n    eigen_assert(output.dimension(2) == 20);\n\nIndices into the output tensor are shuffled accordingly to formulate\nindices into the input tensor. For example, one can assert in the above\ncode snippet that:\n\n    eigen_assert(output(3, 7, 11) == input(11, 3, 7));\n\nIn general, one can assert that\n\n    eigen_assert(output(..., indices[shuffle[i]], ...) ==\n                 input(..., indices[i], ...))\n\nThe shuffle operation results in a lvalue, which means that it can be assigned\nto. In other words, it can be used on the left side of the assignment operator.\n\nLet's rewrite the previous example to take advantage of this feature:\n\n    // Shuffle all dimensions to the left by 1.\n    Tensor<float, 3> input(20, 30, 50);\n    // ... set some values in input.\n    Tensor<float, 3> output(30, 50, 20);\n    output.shuffle({2, 0, 1}) = input;\n\n\n### `<Operation> stride(const Strides& strides)`\n\nReturns a view of the input tensor that strides (skips stride-1\nelements) along each of the dimensions.  The argument strides is an\narray of Index values.  The dimensions of the resulting tensor are\nceil(input_dimensions[i] / strides[i]).\n\nFor example this is what happens when you `stride()` a 2D tensor:\n\n    Eigen::Tensor<int, 2> a(4, 3);\n    a.setValues({{0, 100, 200}, {300, 400, 500}, {600, 700, 800}, {900, 1000, 1100}});\n    Eigen::array<Eigen::DenseIndex, 2> strides({3, 2});\n    Eigen::Tensor<int, 2> b = a.stride(strides);\n    cout << \"b\" << endl << b << endl;\n    =>\n    b\n       0   200\n     900  1100\n\nIt is possible to assign a tensor to a stride:\n    Tensor<float, 3> input(20, 30, 50);\n    // ... set some values in input.\n    Tensor<float, 3> output(40, 90, 200);\n    output.stride({2, 3, 4}) = input;\n\n\n### `<Operation> slice(const StartIndices& offsets, const Sizes& extents)`\n\nReturns a sub-tensor of the given tensor. For each dimension i, the slice is\nmade of the coefficients stored between offset[i] and offset[i] + extents[i] in\nthe input tensor.\n\n    Eigen::Tensor<int, 2> a(4, 3);\n    a.setValues({{0, 100, 200}, {300, 400, 500},\n                 {600, 700, 800}, {900, 1000, 1100}});\n    Eigen::array<int, 2> offsets = {1, 0};\n    Eigen::array<int, 2> extents = {2, 2};\n    Eigen::Tensor<int, 1> slice = a.slice(offsets, extents);\n    cout << \"a\" << endl << a << endl;\n    =>\n    a\n       0   100   200\n     300   400   500\n     600   700   800\n     900  1000  1100\n    cout << \"slice\" << endl << slice << endl;\n    =>\n    slice\n     300   400\n     600   700\n\n\n### `<Operation> chip(const Index offset, const Index dim)`\n\nA chip is a special kind of slice. It is the subtensor at the given offset in\nthe dimension dim. The returned tensor has one fewer dimension than the input\ntensor: the dimension dim is removed.\n\nFor example, a matrix chip would be either a row or a column of the input\nmatrix.\n\n    Eigen::Tensor<int, 2> a(4, 3);\n    a.setValues({{0, 100, 200}, {300, 400, 500},\n                 {600, 700, 800}, {900, 1000, 1100}});\n    Eigen::Tensor<int, 1> row_3 = a.chip(2, 0);\n    Eigen::Tensor<int, 1> col_2 = a.chip(1, 1);\n    cout << \"a\" << endl << a << endl;\n    =>\n    a\n       0   100   200\n     300   400   500\n     600   700   800\n     900  1000  1100\n    cout << \"row_3\" << endl << row_3 << endl;\n    =>\n    row_3\n       600   700   800\n    cout << \"col_2\" << endl << col_2 << endl;\n    =>\n    col_2\n       100   400   700    1000\n\nIt is possible to assign values to a tensor chip since the chip operation is a\nlvalue. For example:\n\n    Eigen::Tensor<int, 1> a(3);\n    a.setValues({{100, 200, 300}});\n    Eigen::Tensor<int, 2> b(2, 3);\n    b.setZero();\n    b.chip(0, 0) = a;\n    cout << \"a\" << endl << a << endl;\n    =>\n    a\n     100\n     200\n     300\n    cout << \"b\" << endl << b << endl;\n    =>\n    b\n       100   200   300\n         0     0     0\n\n\n### `<Operation> reverse(const ReverseDimensions& reverse)`\n\nReturns a view of the input tensor that reverses the order of the coefficients\nalong a subset of the dimensions.  The argument reverse is an array of boolean\nvalues that indicates whether or not the order of the coefficients should be\nreversed along each of the dimensions.  This operation preserves the dimensions\nof the input tensor.\n\nFor example this is what happens when you `reverse()` the first dimension\nof a 2D tensor:\n\n    Eigen::Tensor<int, 2> a(4, 3);\n    a.setValues({{0, 100, 200}, {300, 400, 500},\n                {600, 700, 800}, {900, 1000, 1100}});\n    Eigen::array<bool, 2> reverse({true, false});\n    Eigen::Tensor<int, 2> b = a.reverse(reverse);\n    cout << \"a\" << endl << a << endl << \"b\" << endl << b << endl;\n    =>\n    a\n       0   100   200\n     300   400   500\n     600   700   800\n     900  1000  1100\n    b\n     900  1000  1100\n     600   700   800\n     300   400   500\n       0   100   200\n\n\n### `<Operation> broadcast(const Broadcast& broadcast)`\n\nReturns a view of the input tensor in which the input is replicated one to many\ntimes.\nThe broadcast argument specifies how many copies of the input tensor need to be\nmade in each of the dimensions.\n\n    Eigen::Tensor<int, 2> a(2, 3);\n    a.setValues({{0, 100, 200}, {300, 400, 500}});\n    Eigen::array<int, 2> bcast({3, 2});\n    Eigen::Tensor<int, 2> b = a.broadcast(bcast);\n    cout << \"a\" << endl << a << endl << \"b\" << endl << b << endl;\n    =>\n    a\n       0   100   200\n     300   400   500\n    b\n       0   100   200    0   100   200\n     300   400   500  300   400   500\n       0   100   200    0   100   200\n     300   400   500  300   400   500\n       0   100   200    0   100   200\n     300   400   500  300   400   500\n\n### `<Operation> concatenate(const OtherDerived& other, Axis axis)`\n\nTODO\n\n### `<Operation>  pad(const PaddingDimensions& padding)`\n\nReturns a view of the input tensor in which the input is padded with zeros.\n\n    Eigen::Tensor<int, 2> a(2, 3);\n    a.setValues({{0, 100, 200}, {300, 400, 500}});\n    Eigen::array<pair<int, int>, 2> paddings;\n    paddings[0] = make_pair(0, 1);\n    paddings[1] = make_pair(2, 3);\n    Eigen::Tensor<int, 2> b = a.pad(paddings);\n    cout << \"a\" << endl << a << endl << \"b\" << endl << b << endl;\n    =>\n    a\n       0   100   200\n     300   400   500\n    b\n       0     0     0    0\n       0     0     0    0\n       0   100   200    0\n     300   400   500    0\n       0     0     0    0\n       0     0     0    0\n       0     0     0    0\n\n\n### `<Operation>  extract_patches(const PatchDims& patch_dims)`\n\nReturns a tensor of coefficient patches extracted from the input tensor, where\neach patch is of dimension specified by 'patch_dims'. The returned tensor has\none greater dimension than the input tensor, which is used to index each patch.\nThe patch index in the output tensor depends on the data layout of the input\ntensor: the patch index is the last dimension ColMajor layout, and the first\ndimension in RowMajor layout.\n\nFor example, given the following input tensor:\n\n    Eigen::Tensor<float, 2, DataLayout> tensor(3,4);\n    tensor.setValues({{0.0f, 1.0f, 2.0f, 3.0f},\n                      {4.0f, 5.0f, 6.0f, 7.0f},\n                      {8.0f, 9.0f, 10.0f, 11.0f}});\n\n    cout << \"tensor: \" << endl << tensor << endl;\n    =>\n    tensor:\n     0   1   2   3\n     4   5   6   7\n     8   9  10  11\n\nSix 2x2 patches can be extracted and indexed using the following code:\n\n    Eigen::Tensor<float, 3, DataLayout> patch;\n    Eigen::array<ptrdiff_t, 2> patch_dims;\n    patch_dims[0] = 2;\n    patch_dims[1] = 2;\n    patch = tensor.extract_patches(patch_dims);\n    for (int k = 0; k < 6; ++k) {\n      cout << \"patch index: \" << k << endl;\n      for (int i = 0; i < 2; ++i) {\n    \tfor (int j = 0; j < 2; ++j) {\n    \t  if (DataLayout == ColMajor) {\n    \t\tcout << patch(i, j, k) << \" \";\n    \t  } else {\n    \t\tcout << patch(k, i, j) << \" \";\n    \t  }\n    \t}\n    \tcout << endl;\n      }\n    }\n\nThis code results in the following output when the data layout is ColMajor:\n\n    patch index: 0\n    0 1\n    4 5\n    patch index: 1\n    4 5\n    8 9\n    patch index: 2\n    1 2\n    5 6\n    patch index: 3\n    5 6\n    9 10\n    patch index: 4\n    2 3\n    6 7\n    patch index: 5\n    6 7\n    10 11\n\nThis code results in the following output when the data layout is RowMajor:\n(NOTE: the set of patches is the same as in ColMajor, but are indexed differently).\n\n    patch index: 0\n    0 1\n    4 5\n    patch index: 1\n    1 2\n    5 6\n    patch index: 2\n    2 3\n    6 7\n    patch index: 3\n    4 5\n    8 9\n    patch index: 4\n    5 6\n    9 10\n    patch index: 5\n    6 7\n    10 11\n\n### `<Operation>  extract_image_patches(const Index patch_rows, const Index patch_cols, const Index row_stride, const Index col_stride, const PaddingType padding_type)`\n\nReturns a tensor of coefficient image patches extracted from the input tensor,\nwhich is expected to have dimensions ordered as follows (depending on the data\nlayout of the input tensor, and the number of additional dimensions 'N'):\n\n*) ColMajor\n1st dimension: channels (of size d)\n2nd dimension: rows (of size r)\n3rd dimension: columns (of size c)\n4th-Nth dimension: time (for video) or batch (for bulk processing).\n\n*) RowMajor (reverse order of ColMajor)\n1st-Nth dimension: time (for video) or batch (for bulk processing).\nN+1'th dimension: columns (of size c)\nN+2'th dimension: rows (of size r)\nN+3'th dimension: channels (of size d)\n\nThe returned tensor has one greater dimension than the input tensor, which is\nused to index each patch. The patch index in the output tensor depends on the\ndata layout of the input tensor: the patch index is the 4'th dimension in\nColMajor layout, and the 4'th from the last dimension in RowMajor layout.\n\nFor example, given the following input tensor with the following dimension\nsizes:\n *) depth:   2\n *) rows:    3\n *) columns: 5\n *) batch:   7\n\n    Tensor<float, 4> tensor(2,3,5,7);\n    Tensor<float, 4, RowMajor> tensor_row_major = tensor.swap_layout();\n\n2x2 image patches can be extracted and indexed using the following code:\n\n*) 2D patch: ColMajor (patch indexed by second-to-last dimension)\n\n    Tensor<float, 5> twod_patch;\n    twod_patch = tensor.extract_image_patches<2, 2>();\n    // twod_patch.dimension(0) == 2\n    // twod_patch.dimension(1) == 2\n    // twod_patch.dimension(2) == 2\n    // twod_patch.dimension(3) == 3*5\n    // twod_patch.dimension(4) == 7\n\n*) 2D patch: RowMajor (patch indexed by the second dimension)\n\n    Tensor<float, 5, RowMajor> twod_patch_row_major;\n    twod_patch_row_major = tensor_row_major.extract_image_patches<2, 2>();\n    // twod_patch_row_major.dimension(0) == 7\n    // twod_patch_row_major.dimension(1) == 3*5\n    // twod_patch_row_major.dimension(2) == 2\n    // twod_patch_row_major.dimension(3) == 2\n    // twod_patch_row_major.dimension(4) == 2\n\n## Special Operations\n\n### `<Operation> cast<T>()`\n\nReturns a tensor of type T with the same dimensions as the original tensor.\nThe returned tensor contains the values of the original tensor converted to\ntype T.\n\n    Eigen::Tensor<float, 2> a(2, 3);\n    Eigen::Tensor<int, 2> b = a.cast<int>();\n\nThis can be useful for example if you need to do element-wise division of\nTensors of integers.  This is not currently supported by the Tensor library\nbut you can easily cast the tensors to floats to do the division:\n\n    Eigen::Tensor<int, 2> a(2, 3);\n    a.setValues({{0, 1, 2}, {3, 4, 5}});\n    Eigen::Tensor<int, 2> b =\n        (a.cast<float>() / a.constant(2).cast<float>()).cast<int>();\n    cout << \"a\" << endl << a << endl << endl;\n    cout << \"b\" << endl << b << endl << endl;\n    =>\n    a\n    0 1 2\n    3 4 5\n\n    b\n    0 0 1\n    1 2 2\n\n\n### `<Operation>     eval()`\n\nTODO\n\n\n## Representation of scalar values\n\nScalar values are often represented by tensors of size 1 and rank 0.For example\nTensor<T, N>::maximum() currently returns a Tensor<T, 0>. Similarly, the inner\nproduct of 2 1d tensors (through contractions) returns a 0d tensor.\n\n## Limitations\n\n*   The number of tensor dimensions is currently limited to 250 when using a\n    compiler that supports cxx11. It is limited to only 5 for older compilers.\n*   The IndexList class requires a cxx11 compliant compiler. You can use an\n    array of indices instead if you don't have access to a modern compiler.\n*   On GPUs only floating point values are properly tested and optimized for.\n*   Complex and integer values are known to be broken on GPUs. If you try to use\n    them you'll most likely end up triggering a static assertion failure such as\n    EIGEN_STATIC_ASSERT(packetSize > 1, YOU_MADE_A_PROGRAMMING_MISTAKE)\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/Tensor.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_H\n#define EIGEN_CXX11_TENSOR_TENSOR_H\n\nnamespace Eigen {\n\n/** \\class Tensor\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief The tensor class.\n  *\n  * The %Tensor class is the work-horse for all \\em dense tensors within Eigen.\n  *\n  * The %Tensor class encompasses only dynamic-size objects so far.\n  *\n  * The first two template parameters are required:\n  * \\tparam Scalar_  Numeric type, e.g. float, double, int or `std::complex<float>`.\n  *                 User defined scalar types are supported as well (see \\ref user_defined_scalars \"here\").\n  * \\tparam NumIndices_ Number of indices (i.e. rank of the tensor)\n  *\n  * The remaining template parameters are optional -- in most cases you don't have to worry about them.\n  * \\tparam Options_  A combination of either \\b #RowMajor or \\b #ColMajor, and of either\n  *                 \\b #AutoAlign or \\b #DontAlign.\n  *                 The former controls \\ref TopicStorageOrders \"storage order\", and defaults to column-major. The latter controls alignment, which is required\n  *                 for vectorization. It defaults to aligning tensors. Note that tensors currently do not support any operations that profit from vectorization.\n  *                 Support for such operations (i.e. adding two tensors etc.) is planned.\n  *\n  * You can access elements of tensors using normal subscripting:\n  *\n  * \\code\n  * Eigen::Tensor<double, 4> t(10, 10, 10, 10);\n  * t(0, 1, 2, 3) = 42.0;\n  * \\endcode\n  *\n  * This class can be extended with the help of the plugin mechanism described on the page\n  * \\ref TopicCustomizing_Plugins by defining the preprocessor symbol \\c EIGEN_TENSOR_PLUGIN.\n  *\n  * <i><b>Some notes:</b></i>\n  *\n  * <dl>\n  * <dt><b>Relation to other parts of Eigen:</b></dt>\n  * <dd>The midterm development goal for this class is to have a similar hierarchy as Eigen uses for matrices, so that\n  * taking blocks or using tensors in expressions is easily possible, including an interface with the vector/matrix code\n  * by providing .asMatrix() and .asVector() (or similar) methods for rank 2 and 1 tensors. However, currently, the %Tensor\n  * class does not provide any of these features and is only available as a stand-alone class that just allows for\n  * coefficient access. Also, when fixed-size tensors are implemented, the number of template arguments is likely to\n  * change dramatically.</dd>\n  * </dl>\n  *\n  * \\ref TopicStorageOrders\n  */\n\ntemplate<typename Scalar_, int NumIndices_, int Options_, typename IndexType_>\nclass Tensor : public TensorBase<Tensor<Scalar_, NumIndices_, Options_, IndexType_> >\n{\n  public:\n    typedef Tensor<Scalar_, NumIndices_, Options_, IndexType_> Self;\n    typedef TensorBase<Tensor<Scalar_, NumIndices_, Options_, IndexType_> > Base;\n    typedef typename Eigen::internal::nested<Self>::type Nested;\n    typedef typename internal::traits<Self>::StorageKind StorageKind;\n    typedef typename internal::traits<Self>::Index Index;\n    typedef Scalar_ Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef typename Base::CoeffReturnType CoeffReturnType;\n\n    enum {\n      IsAligned = bool(EIGEN_MAX_ALIGN_BYTES>0) & !(Options_&DontAlign),\n      Layout = Options_ & RowMajor ? RowMajor : ColMajor,\n      CoordAccess = true,\n      RawAccess = true\n    };\n\n    static const int Options = Options_;\n    static const int NumIndices = NumIndices_;\n    typedef DSizes<Index, NumIndices_> Dimensions;\n\n  protected:\n    TensorStorage<Scalar, Dimensions, Options> m_storage;\n\n#ifdef EIGEN_HAS_SFINAE\n    template<typename CustomIndices>\n    struct isOfNormalIndex{\n      static const bool is_array = internal::is_base_of<array<Index, NumIndices>, CustomIndices>::value;\n      static const bool is_int = NumTraits<CustomIndices>::IsInteger;\n      static const bool value = is_array | is_int;\n    };\n#endif\n\n  public:\n    // Metadata\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index                         rank()                   const { return NumIndices; }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index                         dimension(std::size_t n) const { return m_storage.dimensions()[n]; }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions&             dimensions()             const { return m_storage.dimensions(); }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index                         size()                   const { return m_storage.size(); }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar                        *data()                        { return m_storage.data(); }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar                  *data()                  const { return m_storage.data(); }\n\n    // This makes EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED\n    // work, because that uses base().coeffRef() - and we don't yet\n    // implement a similar class hierarchy\n    inline Self& base()             { return *this; }\n    inline const Self& base() const { return *this; }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(Index firstIndex, Index secondIndex, IndexTypes... otherIndices) const\n    {\n      // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return coeff(array<Index, NumIndices>{{firstIndex, secondIndex, otherIndices...}});\n    }\n#endif\n\n    // normal indices\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(const array<Index, NumIndices>& indices) const\n    {\n      eigen_internal_assert(checkIndexRange(indices));\n      return m_storage.data()[linearizedIndex(indices)];\n    }\n\n    // custom indices\n#ifdef EIGEN_HAS_SFINAE\n    template<typename CustomIndices,\n             EIGEN_SFINAE_ENABLE_IF( !(isOfNormalIndex<CustomIndices>::value) )\n    >\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(CustomIndices& indices) const\n    {\n        return coeff(internal::customIndices2Array<Index,NumIndices>(indices));\n    }\n#endif\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff() const\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return m_storage.data()[0];\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(Index index) const\n    {\n      eigen_internal_assert(index >= 0 && index < size());\n      return m_storage.data()[index];\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes>\n    inline Scalar& coeffRef(Index firstIndex, Index secondIndex, IndexTypes... otherIndices)\n    {\n      // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return coeffRef(array<Index, NumIndices>{{firstIndex, secondIndex, otherIndices...}});\n    }\n#endif\n\n    // normal indices\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(const array<Index, NumIndices>& indices)\n    {\n      eigen_internal_assert(checkIndexRange(indices));\n      return m_storage.data()[linearizedIndex(indices)];\n    }\n\n    // custom indices\n#ifdef EIGEN_HAS_SFINAE\n    template<typename CustomIndices,\n             EIGEN_SFINAE_ENABLE_IF( !(isOfNormalIndex<CustomIndices>::value) )\n             >\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(CustomIndices& indices)\n    {\n        return coeffRef(internal::customIndices2Array<Index,NumIndices>(indices));\n    }\n#endif\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef()\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return m_storage.data()[0];\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index index)\n    {\n      eigen_internal_assert(index >= 0 && index < size());\n      return m_storage.data()[index];\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes>\n    inline const Scalar& operator()(Index firstIndex, Index secondIndex, IndexTypes... otherIndices) const\n    {\n      // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return this->operator()(array<Index, NumIndices>{{firstIndex, secondIndex, otherIndices...}});\n    }\n#else\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1) const\n    {\n      return coeff(array<Index, 2>(i0, i1));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2) const\n    {\n      return coeff(array<Index, 3>(i0, i1, i2));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2, Index i3) const\n    {\n      return coeff(array<Index, 4>(i0, i1, i2, i3));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2, Index i3, Index i4) const\n    {\n      return coeff(array<Index, 5>(i0, i1, i2, i3, i4));\n    }\n#endif\n\n    // custom indices\n#ifdef EIGEN_HAS_SFINAE\n    template<typename CustomIndices,\n             EIGEN_SFINAE_ENABLE_IF( !(isOfNormalIndex<CustomIndices>::value) )\n    >\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator()(CustomIndices& indices) const\n    {\n        return coeff(internal::customIndices2Array<Index,NumIndices>(indices));\n    }\n#endif\n\n    // normal indices\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator()(const array<Index, NumIndices>& indices) const\n    {\n      return coeff(indices);\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator()(Index index) const\n    {\n      eigen_internal_assert(index >= 0 && index < size());\n      return coeff(index);\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator()() const\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return coeff();\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator[](Index index) const\n    {\n      // The bracket operator is only for vectors, use the parenthesis operator instead.\n      EIGEN_STATIC_ASSERT(NumIndices == 1, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return coeff(index);\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes>\n    inline Scalar& operator()(Index firstIndex, Index secondIndex, IndexTypes... otherIndices)\n    {\n      // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return operator()(array<Index, NumIndices>{{firstIndex, secondIndex, otherIndices...}});\n    }\n#else\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1)\n    {\n      return coeffRef(array<Index, 2>(i0, i1));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2)\n    {\n      return coeffRef(array<Index, 3>(i0, i1, i2));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3)\n    {\n      return coeffRef(array<Index, 4>(i0, i1, i2, i3));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3, Index i4)\n    {\n      return coeffRef(array<Index, 5>(i0, i1, i2, i3, i4));\n    }\n#endif\n\n    // normal indices\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator()(const array<Index, NumIndices>& indices)\n    {\n      return coeffRef(indices);\n    }\n\n    // custom indices\n#ifdef EIGEN_HAS_SFINAE\n    template<typename CustomIndices,\n             EIGEN_SFINAE_ENABLE_IF( !(isOfNormalIndex<CustomIndices>::value) )\n    >\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator()(CustomIndices& indices)\n    {\n      return coeffRef(internal::customIndices2Array<Index,NumIndices>(indices));\n    }\n#endif\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator()(Index index)\n    {\n      eigen_assert(index >= 0 && index < size());\n      return coeffRef(index);\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator()()\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return coeffRef();\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator[](Index index)\n    {\n      // The bracket operator is only for vectors, use the parenthesis operator instead\n      EIGEN_STATIC_ASSERT(NumIndices == 1, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return coeffRef(index);\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Tensor()\n      : m_storage()\n    {\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Tensor(const Self& other)\n      : m_storage(other.m_storage)\n    {\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Tensor(Index firstDimension, IndexTypes... otherDimensions)\n        : m_storage(firstDimension, otherDimensions...)\n    {\n      // The number of dimensions used to construct a tensor must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT(sizeof...(otherDimensions) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n#else\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE explicit Tensor(Index dim1)\n      : m_storage(dim1, array<Index, 1>(dim1))\n    {\n      EIGEN_STATIC_ASSERT(1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Tensor(Index dim1, Index dim2)\n      : m_storage(dim1*dim2, array<Index, 2>(dim1, dim2))\n    {\n      EIGEN_STATIC_ASSERT(2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Tensor(Index dim1, Index dim2, Index dim3)\n      : m_storage(dim1*dim2*dim3, array<Index, 3>(dim1, dim2, dim3))\n    {\n      EIGEN_STATIC_ASSERT(3 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Tensor(Index dim1, Index dim2, Index dim3, Index dim4)\n      : m_storage(dim1*dim2*dim3*dim4, array<Index, 4>(dim1, dim2, dim3, dim4))\n    {\n      EIGEN_STATIC_ASSERT(4 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Tensor(Index dim1, Index dim2, Index dim3, Index dim4, Index dim5)\n      : m_storage(dim1*dim2*dim3*dim4*dim5, array<Index, 5>(dim1, dim2, dim3, dim4, dim5))\n    {\n      EIGEN_STATIC_ASSERT(5 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n#endif\n\n    /** Normal Dimension */\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE explicit Tensor(const array<Index, NumIndices>& dimensions)\n        : m_storage(internal::array_prod(dimensions), dimensions)\n    {\n      EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED\n    }\n\n    template<typename OtherDerived>\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Tensor(const TensorBase<OtherDerived, ReadOnlyAccessors>& other)\n    {\n      typedef TensorAssignOp<Tensor, const OtherDerived> Assign;\n      Assign assign(*this, other.derived());\n      resize(TensorEvaluator<const Assign, DefaultDevice>(assign, DefaultDevice()).dimensions());\n      internal::TensorExecutor<const Assign, DefaultDevice>::run(assign, DefaultDevice());\n    }\n\n    template<typename OtherDerived>\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Tensor(const TensorBase<OtherDerived, WriteAccessors>& other)\n    {\n      typedef TensorAssignOp<Tensor, const OtherDerived> Assign;\n      Assign assign(*this, other.derived());\n      resize(TensorEvaluator<const Assign, DefaultDevice>(assign, DefaultDevice()).dimensions());\n      internal::TensorExecutor<const Assign, DefaultDevice>::run(assign, DefaultDevice());\n    }\n\n    #if EIGEN_HAS_RVALUE_REFERENCES\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Tensor(Self&& other)\n      : m_storage(std::move(other.m_storage))\n    {\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Tensor& operator=(Self&& other)\n    {\n      m_storage = std::move(other.m_storage);\n      return *this;\n    }\n    #endif\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Tensor& operator=(const Tensor& other)\n    {\n      typedef TensorAssignOp<Tensor, const Tensor> Assign;\n      Assign assign(*this, other);\n      resize(TensorEvaluator<const Assign, DefaultDevice>(assign, DefaultDevice()).dimensions());\n      internal::TensorExecutor<const Assign, DefaultDevice>::run(assign, DefaultDevice());\n      return *this;\n    }\n    template<typename OtherDerived>\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Tensor& operator=(const OtherDerived& other)\n    {\n      typedef TensorAssignOp<Tensor, const OtherDerived> Assign;\n      Assign assign(*this, other);\n      resize(TensorEvaluator<const Assign, DefaultDevice>(assign, DefaultDevice()).dimensions());\n      internal::TensorExecutor<const Assign, DefaultDevice>::run(assign, DefaultDevice());\n      return *this;\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes> EIGEN_DEVICE_FUNC\n    void resize(Index firstDimension, IndexTypes... otherDimensions)\n    {\n      // The number of dimensions used to resize a tensor must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT(sizeof...(otherDimensions) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      resize(array<Index, NumIndices>{{firstDimension, otherDimensions...}});\n    }\n#endif\n\n    /** Normal Dimension */\n    EIGEN_DEVICE_FUNC void resize(const array<Index, NumIndices>& dimensions)\n    {\n      int i;\n      Index size = Index(1);\n      for (i = 0; i < NumIndices; i++) {\n        internal::check_rows_cols_for_overflow<Dynamic>::run(size, dimensions[i]);\n        size *= dimensions[i];\n      }\n      #ifdef EIGEN_INITIALIZE_COEFFS\n        bool size_changed = size != this->size();\n        m_storage.resize(size, dimensions);\n        if(size_changed) EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED\n      #else\n        m_storage.resize(size, dimensions);\n      #endif\n    }\n\n    // Why this overload, DSizes is derived from array ??? //\n    EIGEN_DEVICE_FUNC void resize(const DSizes<Index, NumIndices>& dimensions) {\n      array<Index, NumIndices> dims;\n      for (int i = 0; i < NumIndices; ++i) {\n        dims[i] = dimensions[i];\n      }\n      resize(dims);\n    }\n\n    EIGEN_DEVICE_FUNC\n    void resize()\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      // Nothing to do: rank 0 tensors have fixed size\n    }\n\n#ifdef EIGEN_HAS_INDEX_LIST\n    template <typename FirstType, typename... OtherTypes>\n    EIGEN_DEVICE_FUNC\n    void resize(const Eigen::IndexList<FirstType, OtherTypes...>& dimensions) {\n      array<Index, NumIndices> dims;\n      for (int i = 0; i < NumIndices; ++i) {\n        dims[i] = static_cast<Index>(dimensions[i]);\n      }\n      resize(dims);\n    }\n#endif\n\n    /** Custom Dimension */\n#ifdef EIGEN_HAS_SFINAE\n    template<typename CustomDimension,\n             EIGEN_SFINAE_ENABLE_IF( !(isOfNormalIndex<CustomDimension>::value) )\n    >\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void resize(CustomDimension& dimensions)\n    {\n      resize(internal::customIndices2Array<Index,NumIndices>(dimensions));\n    }\n#endif\n\n#ifndef EIGEN_EMULATE_CXX11_META_H\n    template <typename std::ptrdiff_t... Indices>\n    EIGEN_DEVICE_FUNC\n    void resize(const Sizes<Indices...>& dimensions) {\n      array<Index, NumIndices> dims;\n      for (int i = 0; i < NumIndices; ++i) {\n        dims[i] = static_cast<Index>(dimensions[i]);\n      }\n      resize(dims);\n    }\n#else\n    template <std::size_t V1, std::size_t V2, std::size_t V3, std::size_t V4, std::size_t V5>\n    EIGEN_DEVICE_FUNC\n    void resize(const Sizes<V1, V2, V3, V4, V5>& dimensions) {\n      array<Index, NumIndices> dims;\n      for (int i = 0; i < NumIndices; ++i) {\n        dims[i] = static_cast<Index>(dimensions[i]);\n      }\n      resize(dims);\n    }\n#endif\n\n  protected:\n\n    bool checkIndexRange(const array<Index, NumIndices>& indices) const\n    {\n      using internal::array_apply_and_reduce;\n      using internal::array_zip_and_reduce;\n      using internal::greater_equal_zero_op;\n      using internal::logical_and_op;\n      using internal::lesser_op;\n\n      return\n        // check whether the indices are all >= 0\n        array_apply_and_reduce<logical_and_op, greater_equal_zero_op>(indices) &&\n        // check whether the indices fit in the dimensions\n        array_zip_and_reduce<logical_and_op, lesser_op>(indices, m_storage.dimensions());\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index linearizedIndex(const array<Index, NumIndices>& indices) const\n    {\n      if (Options&RowMajor) {\n        return m_storage.dimensions().IndexOfRowMajor(indices);\n      } else {\n        return m_storage.dimensions().IndexOfColMajor(indices);\n      }\n    }\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorArgMax.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Eugene Brevdo <ebrevdo@gmail.com>\n//                    Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_ARG_MAX_H\n#define EIGEN_CXX11_TENSOR_TENSOR_ARG_MAX_H\n\nnamespace Eigen {\nnamespace internal {\n\n/** \\class TensorIndexTuple\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor + Index Tuple class.\n  *\n  *\n  */\ntemplate<typename XprType>\nstruct traits<TensorIndexTupleOp<XprType> > : public traits<XprType>\n{\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef Tuple<Index, typename XprTraits::Scalar> Scalar;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n};\n\ntemplate<typename XprType>\nstruct eval<TensorIndexTupleOp<XprType>, Eigen::Dense>\n{\n  typedef const TensorIndexTupleOp<XprType>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename XprType>\nstruct nested<TensorIndexTupleOp<XprType>, 1,\n              typename eval<TensorIndexTupleOp<XprType> >::type>\n{\n  typedef TensorIndexTupleOp<XprType> type;\n};\n\n}  // end namespace internal\n\ntemplate<typename XprType>\nclass TensorIndexTupleOp : public TensorBase<TensorIndexTupleOp<XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorIndexTupleOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename Eigen::internal::nested<TensorIndexTupleOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorIndexTupleOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorIndexTupleOp>::Index Index;\n  typedef Tuple<Index, typename XprType::CoeffReturnType> CoeffReturnType;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorIndexTupleOp(const XprType& expr)\n      : m_xpr(expr) {}\n\n  EIGEN_DEVICE_FUNC\n  const typename internal::remove_all<typename XprType::Nested>::type&\n  expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n};\n\n// Eval as rvalue\ntemplate<typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorIndexTupleOp<ArgType>, Device>\n{\n  typedef TensorIndexTupleOp<ArgType> XprType;\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n\n  typedef typename TensorEvaluator<ArgType, Device>::Dimensions Dimensions;\n  static const int NumDims = internal::array_size<Dimensions>::value;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = /*TensorEvaluator<ArgType, Device>::IsAligned*/ false,\n    PacketAccess = /*TensorEvaluator<ArgType, Device>::PacketAccess*/ false,\n    BlockAccess = false,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device) { }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const {\n    return m_impl.dimensions();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType /*data*/) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    return CoeffReturnType(index, m_impl.coeff(index));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    return m_impl.costPerCoeff(vectorized) + TensorOpCost(0, 0, 1);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n\n protected:\n  TensorEvaluator<ArgType, Device> m_impl;\n};\n\nnamespace internal {\n\n/** \\class TensorTupleIndex\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Converts to Tensor<Tuple<Index, Scalar> > and reduces to Tensor<Index>.\n  *\n  */\ntemplate<typename ReduceOp, typename Dims, typename XprType>\nstruct traits<TensorTupleReducerOp<ReduceOp, Dims, XprType> > : public traits<XprType>\n{\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef Index Scalar;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions - array_size<Dims>::value;\n  static const int Layout = XprTraits::Layout;\n};\n\ntemplate<typename ReduceOp, typename Dims, typename XprType>\nstruct eval<TensorTupleReducerOp<ReduceOp, Dims, XprType>, Eigen::Dense>\n{\n  typedef const TensorTupleReducerOp<ReduceOp, Dims, XprType>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename ReduceOp, typename Dims, typename XprType>\nstruct nested<TensorTupleReducerOp<ReduceOp, Dims, XprType>, 1,\n              typename eval<TensorTupleReducerOp<ReduceOp, Dims, XprType> >::type>\n{\n  typedef TensorTupleReducerOp<ReduceOp, Dims, XprType> type;\n};\n\n}  // end namespace internal\n\ntemplate<typename ReduceOp, typename Dims, typename XprType>\nclass TensorTupleReducerOp : public TensorBase<TensorTupleReducerOp<ReduceOp, Dims, XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorTupleReducerOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename Eigen::internal::nested<TensorTupleReducerOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorTupleReducerOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorTupleReducerOp>::Index Index;\n  typedef Index CoeffReturnType;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorTupleReducerOp(const XprType& expr,\n                                                          const ReduceOp& reduce_op,\n                                                          const Index return_dim,\n                                                          const Dims& reduce_dims)\n      : m_xpr(expr), m_reduce_op(reduce_op), m_return_dim(return_dim), m_reduce_dims(reduce_dims) {}\n\n  EIGEN_DEVICE_FUNC\n  const typename internal::remove_all<typename XprType::Nested>::type&\n  expression() const { return m_xpr; }\n\n  EIGEN_DEVICE_FUNC\n  const ReduceOp& reduce_op() const { return m_reduce_op; }\n\n  EIGEN_DEVICE_FUNC\n  const Dims& reduce_dims() const { return m_reduce_dims; }\n\n  EIGEN_DEVICE_FUNC\n  Index return_dim() const { return m_return_dim; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const ReduceOp m_reduce_op;\n    const Index m_return_dim;\n    const Dims m_reduce_dims;\n};\n\n// Eval as rvalue\ntemplate<typename ReduceOp, typename Dims, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorTupleReducerOp<ReduceOp, Dims, ArgType>, Device>\n{\n  typedef TensorTupleReducerOp<ReduceOp, Dims, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename TensorIndexTupleOp<ArgType>::CoeffReturnType TupleType;\n  typedef typename TensorEvaluator<const TensorReductionOp<ReduceOp, Dims, const TensorIndexTupleOp<ArgType> >, Device>::Dimensions Dimensions;\n  typedef typename TensorEvaluator<const TensorIndexTupleOp<ArgType> , Device>::Dimensions InputDimensions;\n  static const int NumDims = internal::array_size<InputDimensions>::value;\n  typedef array<Index, NumDims> StrideDims;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n  typedef StorageMemory<TupleType, Device> TupleStorageMem;\n\n  enum {\n    IsAligned         = /*TensorEvaluator<ArgType, Device>::IsAligned*/ false,\n    PacketAccess      = /*TensorEvaluator<ArgType, Device>::PacketAccess*/ false,\n    BlockAccess       = false,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout            = TensorEvaluator<const TensorReductionOp<ReduceOp, Dims, const TensorIndexTupleOp<ArgType> >, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_orig_impl(op.expression(), device),\n        m_impl(op.expression().index_tuples().reduce(op.reduce_dims(), op.reduce_op()), device),\n        m_return_dim(op.return_dim())\n  {\n    gen_strides(m_orig_impl.dimensions(), m_strides);\n    if (Layout == static_cast<int>(ColMajor)) {\n      const Index total_size = internal::array_prod(m_orig_impl.dimensions());\n      m_stride_mod = (m_return_dim < NumDims - 1) ? m_strides[m_return_dim + 1] : total_size;\n    } else {\n      const Index total_size = internal::array_prod(m_orig_impl.dimensions());\n      m_stride_mod = (m_return_dim > 0) ? m_strides[m_return_dim - 1] : total_size;\n    }    \n    // If m_return_dim is not a valid index, returns 1 or this can crash on Windows.\n    m_stride_div = ((m_return_dim >= 0) &&\n                    (m_return_dim < static_cast<Index>(m_strides.size())))\n                   ? m_strides[m_return_dim] : 1;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const {\n    return m_impl.dimensions();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType /*data*/) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const {\n    const TupleType v = m_impl.coeff(index);\n    return (m_return_dim < 0) ? v.first : (v.first % m_stride_mod) / m_stride_div;\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n#ifdef EIGEN_USE_SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n    m_orig_impl.bind(cgh);\n  }\n#endif\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    const double compute_cost = 1.0 +\n        (m_return_dim < 0 ? 0.0 : (TensorOpCost::ModCost<Index>() + TensorOpCost::DivCost<Index>()));\n    return m_orig_impl.costPerCoeff(vectorized) +\n           m_impl.costPerCoeff(vectorized) + TensorOpCost(0, 0, compute_cost);\n  }\n\n private:\n  EIGEN_DEVICE_FUNC void gen_strides(const InputDimensions& dims, StrideDims& strides) {\n    if (m_return_dim < 0) {\n      return;  // Won't be using the strides.\n    }\n    eigen_assert(m_return_dim < NumDims &&\n                 \"Asking to convert index to a dimension outside of the rank\");\n\n    // Calculate m_stride_div and m_stride_mod, which are used to\n    // calculate the value of an index w.r.t. the m_return_dim.\n    if (Layout == static_cast<int>(ColMajor)) {\n      strides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        strides[i] = strides[i-1] * dims[i-1];\n      }\n    } else {\n      strides[NumDims-1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        strides[i] = strides[i+1] * dims[i+1];\n      }\n    }\n  }\n\n protected:\n  TensorEvaluator<const TensorIndexTupleOp<ArgType>, Device> m_orig_impl;\n  TensorEvaluator<const TensorReductionOp<ReduceOp, Dims, const TensorIndexTupleOp<ArgType> >, Device> m_impl;\n  const Index m_return_dim;\n  StrideDims m_strides;\n  Index m_stride_mod;\n  Index m_stride_div;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_ARG_MAX_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorAssign.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_ASSIGN_H\n#define EIGEN_CXX11_TENSOR_TENSOR_ASSIGN_H\n\nnamespace Eigen {\n\n/** \\class TensorAssign\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief The tensor assignment class.\n  *\n  * This class is represents the assignment of the values resulting from the evaluation of\n  * the rhs expression to the memory locations denoted by the lhs expression.\n  */\nnamespace internal {\ntemplate<typename LhsXprType, typename RhsXprType>\nstruct traits<TensorAssignOp<LhsXprType, RhsXprType> >\n{\n  typedef typename LhsXprType::Scalar Scalar;\n  typedef typename traits<LhsXprType>::StorageKind StorageKind;\n  typedef typename promote_index_type<typename traits<LhsXprType>::Index,\n                                      typename traits<RhsXprType>::Index>::type Index;\n  typedef typename LhsXprType::Nested LhsNested;\n  typedef typename RhsXprType::Nested RhsNested;\n  typedef typename remove_reference<LhsNested>::type _LhsNested;\n  typedef typename remove_reference<RhsNested>::type _RhsNested;\n  static const std::size_t NumDimensions = internal::traits<LhsXprType>::NumDimensions;\n  static const int Layout = internal::traits<LhsXprType>::Layout;\n  typedef typename traits<LhsXprType>::PointerType PointerType;\n\n  enum {\n    Flags = 0\n  };\n};\n\ntemplate<typename LhsXprType, typename RhsXprType>\nstruct eval<TensorAssignOp<LhsXprType, RhsXprType>, Eigen::Dense>\n{\n  typedef const TensorAssignOp<LhsXprType, RhsXprType>& type;\n};\n\ntemplate<typename LhsXprType, typename RhsXprType>\nstruct nested<TensorAssignOp<LhsXprType, RhsXprType>, 1, typename eval<TensorAssignOp<LhsXprType, RhsXprType> >::type>\n{\n  typedef TensorAssignOp<LhsXprType, RhsXprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename LhsXprType, typename RhsXprType>\nclass TensorAssignOp : public TensorBase<TensorAssignOp<LhsXprType, RhsXprType> >\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorAssignOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename LhsXprType::CoeffReturnType CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorAssignOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorAssignOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorAssignOp>::Index Index;\n\n  static const int NumDims = Eigen::internal::traits<TensorAssignOp>::NumDimensions;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorAssignOp(LhsXprType& lhs, const RhsXprType& rhs)\n      : m_lhs_xpr(lhs), m_rhs_xpr(rhs) {}\n\n    /** \\returns the nested expressions */\n    EIGEN_DEVICE_FUNC\n    typename internal::remove_all<typename LhsXprType::Nested>::type&\n    lhsExpression() const { return *((typename internal::remove_all<typename LhsXprType::Nested>::type*)&m_lhs_xpr); }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename RhsXprType::Nested>::type&\n    rhsExpression() const { return m_rhs_xpr; }\n\n  protected:\n    typename internal::remove_all<typename LhsXprType::Nested>::type& m_lhs_xpr;\n    const typename internal::remove_all<typename RhsXprType::Nested>::type& m_rhs_xpr;\n};\n\n\ntemplate<typename LeftArgType, typename RightArgType, typename Device>\nstruct TensorEvaluator<const TensorAssignOp<LeftArgType, RightArgType>, Device>\n{\n  typedef TensorAssignOp<LeftArgType, RightArgType> XprType;\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef typename TensorEvaluator<RightArgType, Device>::Dimensions Dimensions;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  static const int NumDims = XprType::NumDims;\n\n  enum {\n    IsAligned         = TensorEvaluator<LeftArgType, Device>::IsAligned &\n                        TensorEvaluator<RightArgType, Device>::IsAligned,\n    PacketAccess      = TensorEvaluator<LeftArgType, Device>::PacketAccess &\n                        TensorEvaluator<RightArgType, Device>::PacketAccess,\n    BlockAccess       = TensorEvaluator<LeftArgType, Device>::BlockAccess &\n                        TensorEvaluator<RightArgType, Device>::BlockAccess,\n    PreferBlockAccess = TensorEvaluator<LeftArgType, Device>::PreferBlockAccess |\n                        TensorEvaluator<RightArgType, Device>::PreferBlockAccess,\n    Layout            = TensorEvaluator<LeftArgType, Device>::Layout,\n    RawAccess         = TensorEvaluator<LeftArgType, Device>::RawAccess\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename TensorEvaluator<const RightArgType, Device>::TensorBlock\n      RightTensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device) :\n      m_leftImpl(op.lhsExpression(), device),\n      m_rightImpl(op.rhsExpression(), device)\n  {\n    EIGEN_STATIC_ASSERT(\n        (static_cast<int>(TensorEvaluator<LeftArgType, Device>::Layout) ==\n         static_cast<int>(TensorEvaluator<RightArgType, Device>::Layout)),\n        YOU_MADE_A_PROGRAMMING_MISTAKE);\n  }\n\n  EIGEN_DEVICE_FUNC const Dimensions& dimensions() const\n  {\n    // The dimensions of the lhs and the rhs tensors should be equal to prevent\n    // overflows and ensure the result is fully initialized.\n    // TODO: use left impl instead if right impl dimensions are known at compile time.\n    return m_rightImpl.dimensions();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    eigen_assert(dimensions_match(m_leftImpl.dimensions(), m_rightImpl.dimensions()));\n    m_leftImpl.evalSubExprsIfNeeded(NULL);\n    // If the lhs provides raw access to its storage area (i.e. if m_leftImpl.data() returns a non\n    // null value), attempt to evaluate the rhs expression in place. Returns true iff in place\n    // evaluation isn't supported and the caller still needs to manually assign the values generated\n    // by the rhs to the lhs.\n    return m_rightImpl.evalSubExprsIfNeeded(m_leftImpl.data());\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    m_leftImpl.evalSubExprsIfNeededAsync(nullptr, [this, done](bool) {\n      m_rightImpl.evalSubExprsIfNeededAsync(\n          m_leftImpl.data(), [done](bool need_assign) { done(need_assign); });\n    });\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_leftImpl.cleanup();\n    m_rightImpl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalScalar(Index i) {\n    m_leftImpl.coeffRef(i) = m_rightImpl.coeff(i);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalPacket(Index i) {\n\n    const int LhsStoreMode = TensorEvaluator<LeftArgType, Device>::IsAligned ? Aligned : Unaligned;\n    const int RhsLoadMode = TensorEvaluator<RightArgType, Device>::IsAligned ? Aligned : Unaligned;\n    m_leftImpl.template writePacket<LhsStoreMode>(i, m_rightImpl.template packet<RhsLoadMode>(i));\n  }\n  EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const\n  {\n    return m_leftImpl.coeff(index);\n  }\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC PacketReturnType packet(Index index) const\n  {\n    return m_leftImpl.template packet<LoadMode>(index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    // We assume that evalPacket or evalScalar is called to perform the\n    // assignment and account for the cost of the write here, but reduce left\n    // cost by one load because we are using m_leftImpl.coeffRef.\n    TensorOpCost left = m_leftImpl.costPerCoeff(vectorized);\n    return m_rightImpl.costPerCoeff(vectorized) +\n           TensorOpCost(\n               numext::maxi(0.0, left.bytes_loaded() - sizeof(CoeffReturnType)),\n               left.bytes_stored(), left.compute_cycles()) +\n           TensorOpCost(0, sizeof(CoeffReturnType), 0, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    return internal::TensorBlockResourceRequirements::merge(\n        m_leftImpl.getResourceRequirements(),\n        m_rightImpl.getResourceRequirements());\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalBlock(\n      TensorBlockDesc& desc, TensorBlockScratch& scratch) {\n    if (TensorEvaluator<LeftArgType, Device>::RawAccess &&\n        m_leftImpl.data() != NULL) {\n      // If destination has raw data access, we pass it as a potential\n      // destination for a block descriptor evaluation.\n      desc.template AddDestinationBuffer<Layout>(\n          /*dst_base=*/m_leftImpl.data() + desc.offset(),\n          /*dst_strides=*/internal::strides<Layout>(m_leftImpl.dimensions()));\n    }\n\n    RightTensorBlock block = m_rightImpl.block(desc, scratch, /*root_of_expr_ast=*/true);\n    // If block was evaluated into a destination, there is no need to do assignment.\n    if (block.kind() != internal::TensorBlockKind::kMaterializedInOutput) {\n      m_leftImpl.writeBlock(desc, block);\n    }\n    block.cleanup();\n  }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_leftImpl.bind(cgh);\n    m_rightImpl.bind(cgh);\n  }\n#endif\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return m_leftImpl.data(); }\n\n private:\n  TensorEvaluator<LeftArgType, Device> m_leftImpl;\n  TensorEvaluator<RightArgType, Device> m_rightImpl;\n};\n\n}\n\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_ASSIGN_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBase.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_BASE_H\n#define EIGEN_CXX11_TENSOR_TENSOR_BASE_H\n\n// clang-format off\n\nnamespace Eigen {\n\n/** \\class TensorBase\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief The tensor base class.\n  *\n  * This class is the common parent of the Tensor and TensorMap class, thus\n  * making it possible to use either class interchangeably in expressions.\n  */\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n// FIXME Doxygen does not like the inheritance with different template parameters\n// Since there is no doxygen documentation inside, we disable it for now\ntemplate<typename Derived>\nclass TensorBase<Derived, ReadOnlyAccessors>\n{\n  public:\n    typedef internal::traits<Derived> DerivedTraits;\n    typedef typename DerivedTraits::Scalar Scalar;\n    typedef typename DerivedTraits::Index Index;\n    typedef typename internal::remove_const<Scalar>::type CoeffReturnType;\n    static const int NumDimensions = DerivedTraits::NumDimensions;\n\n    // Generic nullary operation support.\n    template <typename CustomNullaryOp> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseNullaryOp<CustomNullaryOp, const Derived>\n    nullaryExpr(const CustomNullaryOp& func) const {\n      return TensorCwiseNullaryOp<CustomNullaryOp, const Derived>(derived(), func);\n    }\n\n    // Coefficient-wise nullary operators\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseNullaryOp<internal::scalar_constant_op<Scalar>, const Derived>\n    constant(const Scalar& value) const {\n      return nullaryExpr(internal::scalar_constant_op<Scalar>(value));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseNullaryOp<internal::UniformRandomGenerator<Scalar>, const Derived>\n    random() const {\n      return nullaryExpr(internal::UniformRandomGenerator<Scalar>());\n    }\n    template <typename RandomGenerator> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseNullaryOp<RandomGenerator, const Derived>\n    random(const RandomGenerator& gen = RandomGenerator()) const {\n      return nullaryExpr(gen);\n    }\n\n    // Tensor generation\n    template <typename Generator> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorGeneratorOp<Generator, const Derived>\n    generate(const Generator& generator) const {\n      return TensorGeneratorOp<Generator, const Derived>(derived(), generator);\n    }\n\n    // Generic unary operation support.\n    template <typename CustomUnaryOp> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<CustomUnaryOp, const Derived>\n    unaryExpr(const CustomUnaryOp& func) const {\n      return TensorCwiseUnaryOp<CustomUnaryOp, const Derived>(derived(), func);\n    }\n\n    // Coefficient-wise unary operators\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_opposite_op<Scalar>, const Derived>\n    operator-() const {\n      return unaryExpr(internal::scalar_opposite_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_sqrt_op<Scalar>, const Derived>\n    sqrt() const {\n      return unaryExpr(internal::scalar_sqrt_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_sign_op<Scalar>, const Derived>\n    sign() const {\n      return unaryExpr(internal::scalar_sign_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_rsqrt_op<Scalar>, const Derived>\n    rsqrt() const {\n      return unaryExpr(internal::scalar_rsqrt_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_square_op<Scalar>, const Derived>\n    square() const {\n      return unaryExpr(internal::scalar_square_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_cube_op<Scalar>, const Derived>\n    cube() const {\n      return unaryExpr(internal::scalar_cube_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_inverse_op<Scalar>, const Derived>\n    inverse() const {\n      return unaryExpr(internal::scalar_inverse_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_tanh_op<Scalar>, const Derived>\n    tanh() const {\n      return unaryExpr(internal::scalar_tanh_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_lgamma_op<Scalar>, const Derived>\n    lgamma() const {\n      return unaryExpr(internal::scalar_lgamma_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_digamma_op<Scalar>, const Derived>\n    digamma() const {\n      return unaryExpr(internal::scalar_digamma_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_i0_op<Scalar>, const Derived>\n    bessel_i0() const {\n      return unaryExpr(internal::scalar_bessel_i0_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_i0e_op<Scalar>, const Derived>\n    bessel_i0e() const {\n      return unaryExpr(internal::scalar_bessel_i0e_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_i1_op<Scalar>, const Derived>\n    bessel_i1() const {\n      return unaryExpr(internal::scalar_bessel_i1_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_i1e_op<Scalar>, const Derived>\n    bessel_i1e() const {\n      return unaryExpr(internal::scalar_bessel_i1e_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_j0_op<Scalar>, const Derived>\n    bessel_j0() const {\n      return unaryExpr(internal::scalar_bessel_j0_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_y0_op<Scalar>, const Derived>\n    bessel_y0() const {\n      return unaryExpr(internal::scalar_bessel_y0_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_j1_op<Scalar>, const Derived>\n    bessel_j1() const {\n      return unaryExpr(internal::scalar_bessel_j1_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_y1_op<Scalar>, const Derived>\n    bessel_y1() const {\n      return unaryExpr(internal::scalar_bessel_y1_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_k0_op<Scalar>, const Derived>\n    bessel_k0() const {\n      return unaryExpr(internal::scalar_bessel_k0_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_k0e_op<Scalar>, const Derived>\n    bessel_k0e() const {\n      return unaryExpr(internal::scalar_bessel_k0e_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_k1_op<Scalar>, const Derived>\n    bessel_k1() const {\n      return unaryExpr(internal::scalar_bessel_k1_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_bessel_k1e_op<Scalar>, const Derived>\n    bessel_k1e() const {\n      return unaryExpr(internal::scalar_bessel_k1e_op<Scalar>());\n    }\n\n    // igamma(a = this, x = other)\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_igamma_op<Scalar>, const Derived, const OtherDerived>\n    igamma(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_igamma_op<Scalar>());\n    }\n\n    // igamma_der_a(a = this, x = other)\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_igamma_der_a_op<Scalar>, const Derived, const OtherDerived>\n    igamma_der_a(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_igamma_der_a_op<Scalar>());\n    }\n\n    // gamma_sample_der_alpha(alpha = this, sample = other)\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_gamma_sample_der_alpha_op<Scalar>, const Derived, const OtherDerived>\n    gamma_sample_der_alpha(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_gamma_sample_der_alpha_op<Scalar>());\n    }\n\n    // igammac(a = this, x = other)\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_igammac_op<Scalar>, const Derived, const OtherDerived>\n    igammac(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_igammac_op<Scalar>());\n    }\n\n    // zeta(x = this, q = other)\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_zeta_op<Scalar>, const Derived, const OtherDerived>\n    zeta(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_zeta_op<Scalar>());\n    }\n\n    // polygamma(n = this, x = other)\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_polygamma_op<Scalar>, const Derived, const OtherDerived>\n    polygamma(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_polygamma_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_erf_op<Scalar>, const Derived>\n    erf() const {\n      return unaryExpr(internal::scalar_erf_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_erfc_op<Scalar>, const Derived>\n    erfc() const {\n      return unaryExpr(internal::scalar_erfc_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_ndtri_op<Scalar>, const Derived>\n    ndtri() const {\n      return unaryExpr(internal::scalar_ndtri_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_logistic_op<Scalar>, const Derived>\n    sigmoid() const {\n      return unaryExpr(internal::scalar_logistic_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_exp_op<Scalar>, const Derived>\n    exp() const {\n      return unaryExpr(internal::scalar_exp_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_expm1_op<Scalar>, const Derived>\n    expm1() const {\n      return unaryExpr(internal::scalar_expm1_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_log_op<Scalar>, const Derived>\n    log() const {\n      return unaryExpr(internal::scalar_log_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_log1p_op<Scalar>, const Derived>\n    log1p() const {\n      return unaryExpr(internal::scalar_log1p_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_log2_op<Scalar>, const Derived>\n    log2() const {\n      return unaryExpr(internal::scalar_log2_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_abs_op<Scalar>, const Derived>\n    abs() const {\n      return unaryExpr(internal::scalar_abs_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_clamp_op<Scalar>, const Derived>\n    clip(Scalar min, Scalar max) const {\n      return unaryExpr(internal::scalar_clamp_op<Scalar>(min, max));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const typename internal::conditional<NumTraits<CoeffReturnType>::IsComplex,\n                                                             TensorCwiseUnaryOp<internal::scalar_conjugate_op<Scalar>, const Derived>,\n                                                             Derived>::type\n    conjugate() const {\n      return choose(Cond<NumTraits<CoeffReturnType>::IsComplex>(), unaryExpr(internal::scalar_conjugate_op<Scalar>()), derived());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::bind2nd_op<internal::scalar_pow_op<Scalar,Scalar> >, const Derived>\n    pow(Scalar exponent) const {\n      return unaryExpr(internal::bind2nd_op<internal::scalar_pow_op<Scalar,Scalar> >(exponent));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_real_op<Scalar>, const Derived>\n    real() const {\n      return unaryExpr(internal::scalar_real_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_imag_op<Scalar>, const Derived>\n    imag() const {\n      return unaryExpr(internal::scalar_imag_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::bind2nd_op<internal::scalar_sum_op<Scalar,Scalar> >, const Derived>\n    operator+ (Scalar rhs) const {\n      return unaryExpr(internal::bind2nd_op<internal::scalar_sum_op<Scalar,Scalar> >(rhs));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE friend\n    const TensorCwiseUnaryOp<internal::bind1st_op<internal::scalar_sum_op<Scalar> >, const Derived>\n    operator+ (Scalar lhs, const Derived& rhs) {\n      return rhs.unaryExpr(internal::bind1st_op<internal::scalar_sum_op<Scalar> >(lhs));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::bind2nd_op<internal::scalar_difference_op<Scalar,Scalar> >, const Derived>\n    operator- (Scalar rhs) const {\n      EIGEN_STATIC_ASSERT((NumTraits<Scalar>::IsSigned || internal::is_same<Scalar, const std::complex<float> >::value), YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return unaryExpr(internal::bind2nd_op<internal::scalar_difference_op<Scalar,Scalar> >(rhs));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE friend\n    const TensorCwiseUnaryOp<internal::bind1st_op<internal::scalar_difference_op<Scalar> >, const Derived>\n    operator- (Scalar lhs, const Derived& rhs) {\n      return rhs.unaryExpr(internal::bind1st_op<internal::scalar_difference_op<Scalar> >(lhs));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::bind2nd_op<internal::scalar_product_op<Scalar,Scalar> >, const Derived>\n    operator* (Scalar rhs) const {\n      return unaryExpr(internal::bind2nd_op<internal::scalar_product_op<Scalar,Scalar> >(rhs));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE friend\n    const TensorCwiseUnaryOp<internal::bind1st_op<internal::scalar_product_op<Scalar> >, const Derived>\n    operator* (Scalar lhs, const Derived& rhs) {\n      return rhs.unaryExpr(internal::bind1st_op<internal::scalar_product_op<Scalar> >(lhs));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::bind2nd_op<internal::scalar_quotient_op<Scalar,Scalar> >, const Derived>\n    operator/ (Scalar rhs) const {\n      return unaryExpr(internal::bind2nd_op<internal::scalar_quotient_op<Scalar,Scalar> >(rhs));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE friend\n    const TensorCwiseUnaryOp<internal::bind1st_op<internal::scalar_quotient_op<Scalar> >, const Derived>\n    operator/ (Scalar lhs, const Derived& rhs) {\n      return rhs.unaryExpr(internal::bind1st_op<internal::scalar_quotient_op<Scalar> >(lhs));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_mod_op<Scalar>, const Derived>\n    operator% (Scalar rhs) const {\n      EIGEN_STATIC_ASSERT(NumTraits<Scalar>::IsInteger, YOU_MADE_A_PROGRAMMING_MISTAKE_TRY_MOD);\n      return unaryExpr(internal::scalar_mod_op<Scalar>(rhs));\n    }\n\n    template <int NanPropagation=PropagateFast>\n    EIGEN_DEVICE_FUNC\n        EIGEN_STRONG_INLINE const TensorCwiseBinaryOp<internal::scalar_max_op<Scalar,Scalar,NanPropagation>, const Derived, const TensorCwiseNullaryOp<internal::scalar_constant_op<Scalar>, const Derived> >\n    cwiseMax(Scalar threshold) const {\n      return cwiseMax<NanPropagation>(constant(threshold));\n    }\n\n    template <int NanPropagation=PropagateFast>\n    EIGEN_DEVICE_FUNC\n        EIGEN_STRONG_INLINE const TensorCwiseBinaryOp<internal::scalar_min_op<Scalar,Scalar,NanPropagation>, const Derived, const TensorCwiseNullaryOp<internal::scalar_constant_op<Scalar>, const Derived> >\n    cwiseMin(Scalar threshold) const {\n      return cwiseMin<NanPropagation>(constant(threshold));\n    }\n\n    template<typename NewType>\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const typename internal::conditional<internal::is_same<NewType, CoeffReturnType>::value,\n                                                             Derived,\n                                                             TensorConversionOp<NewType, const Derived> >::type\n    cast() const {\n      return choose(Cond<internal::is_same<NewType, CoeffReturnType>::value>(), derived(), TensorConversionOp<NewType, const Derived>(derived()));\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_round_op<Scalar>, const Derived>\n    round() const {\n      return unaryExpr(internal::scalar_round_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_rint_op<Scalar>, const Derived>\n    rint() const {\n      return unaryExpr(internal::scalar_rint_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_ceil_op<Scalar>, const Derived>\n    ceil() const {\n      return unaryExpr(internal::scalar_ceil_op<Scalar>());\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_floor_op<Scalar>, const Derived>\n    floor() const {\n      return unaryExpr(internal::scalar_floor_op<Scalar>());\n    }\n\n    // Generic binary operation support.\n    template <typename CustomBinaryOp, typename OtherDerived> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseBinaryOp<CustomBinaryOp, const Derived, const OtherDerived>\n    binaryExpr(const OtherDerived& other, const CustomBinaryOp& func) const {\n      return TensorCwiseBinaryOp<CustomBinaryOp, const Derived, const OtherDerived>(derived(), other, func);\n    }\n\n    // Coefficient-wise binary operators.\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_sum_op<Scalar>, const Derived, const OtherDerived>\n    operator+(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_sum_op<Scalar>());\n    }\n\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_difference_op<Scalar>, const Derived, const OtherDerived>\n    operator-(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_difference_op<Scalar>());\n    }\n\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_product_op<Scalar>, const Derived, const OtherDerived>\n    operator*(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_product_op<Scalar>());\n    }\n\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_quotient_op<Scalar>, const Derived, const OtherDerived>\n    operator/(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_quotient_op<Scalar>());\n    }\n\n  template<int NaNPropagation=PropagateFast, typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n      const TensorCwiseBinaryOp<internal::scalar_max_op<Scalar,Scalar, NaNPropagation>, const Derived, const OtherDerived>\n    cwiseMax(const OtherDerived& other) const {\n    return binaryExpr(other.derived(), internal::scalar_max_op<Scalar,Scalar, NaNPropagation>());\n    }\n\n  template<int NaNPropagation=PropagateFast, typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_min_op<Scalar,Scalar, NaNPropagation>, const Derived, const OtherDerived>\n    cwiseMin(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_min_op<Scalar,Scalar, NaNPropagation>());\n    }\n\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_boolean_and_op, const Derived, const OtherDerived>\n    operator&&(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_boolean_and_op());\n    }\n\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_boolean_or_op, const Derived, const OtherDerived>\n    operator||(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_boolean_or_op());\n    }\n\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_boolean_xor_op, const Derived, const OtherDerived>\n    operator^(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_boolean_xor_op());\n    }\n\n    // Comparisons and tests.\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_LT>, const Derived, const OtherDerived>\n    operator<(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_LT>());\n    }\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_LE>, const Derived, const OtherDerived>\n    operator<=(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_LE>());\n    }\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_GT>, const Derived, const OtherDerived>\n    operator>(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_GT>());\n    }\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_GE>, const Derived, const OtherDerived>\n    operator>=(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_GE>());\n    }\n\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_EQ>, const Derived, const OtherDerived>\n    operator==(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_EQ>());\n    }\n\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_NEQ>, const Derived, const OtherDerived>\n    operator!=(const OtherDerived& other) const {\n      return binaryExpr(other.derived(), internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_NEQ>());\n    }\n\n    // comparisons and tests for Scalars\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_LT>, const Derived, const TensorCwiseNullaryOp<internal::scalar_constant_op<Scalar>, const Derived> >\n    operator<(Scalar threshold) const {\n      return operator<(constant(threshold));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_LE>, const Derived, const TensorCwiseNullaryOp<internal::scalar_constant_op<Scalar>, const Derived> >\n    operator<=(Scalar threshold) const {\n      return operator<=(constant(threshold));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_GT>, const Derived, const TensorCwiseNullaryOp<internal::scalar_constant_op<Scalar>, const Derived> >\n    operator>(Scalar threshold) const {\n      return operator>(constant(threshold));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_GE>, const Derived, const TensorCwiseNullaryOp<internal::scalar_constant_op<Scalar>, const Derived> >\n    operator>=(Scalar threshold) const {\n      return operator>=(constant(threshold));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_EQ>, const Derived, const TensorCwiseNullaryOp<internal::scalar_constant_op<Scalar>, const Derived> >\n    operator==(Scalar threshold) const {\n      return operator==(constant(threshold));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseBinaryOp<internal::scalar_cmp_op<Scalar, Scalar, internal::cmp_NEQ>, const Derived, const TensorCwiseNullaryOp<internal::scalar_constant_op<Scalar>, const Derived> >\n    operator!=(Scalar threshold) const {\n      return operator!=(constant(threshold));\n    }\n\n    // Checks\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_isnan_op<Scalar>, const Derived>\n    (isnan)() const {\n      return unaryExpr(internal::scalar_isnan_op<Scalar>());\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_isinf_op<Scalar>, const Derived>\n    (isinf)() const {\n      return unaryExpr(internal::scalar_isinf_op<Scalar>());\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const TensorCwiseUnaryOp<internal::scalar_isfinite_op<Scalar>, const Derived>\n    (isfinite)() const {\n      return unaryExpr(internal::scalar_isfinite_op<Scalar>());\n    }\n\n    // Coefficient-wise ternary operators.\n    template<typename ThenDerived, typename ElseDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorSelectOp<const Derived, const ThenDerived, const ElseDerived>\n    select(const ThenDerived& thenTensor, const ElseDerived& elseTensor) const {\n      return TensorSelectOp<const Derived, const ThenDerived, const ElseDerived>(derived(), thenTensor.derived(), elseTensor.derived());\n    }\n\n    // Contractions.\n    typedef Eigen::IndexPair<Index> DimensionPair;\n\n    template<typename OtherDerived, typename Dimensions> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorContractionOp<const Dimensions, const Derived, const OtherDerived, const NoOpOutputKernel>\n    contract(const OtherDerived& other, const Dimensions& dims) const {\n      return TensorContractionOp<const Dimensions, const Derived, const OtherDerived, const NoOpOutputKernel>(derived(), other.derived(), dims);\n    }\n\n    template<typename OtherDerived, typename Dimensions, typename OutputKernel> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorContractionOp<const Dimensions, const Derived, const OtherDerived, const OutputKernel>\n    contract(const OtherDerived& other, const Dimensions& dims, const OutputKernel& output_kernel) const {\n      return TensorContractionOp<const Dimensions, const Derived, const OtherDerived, const OutputKernel>(derived(), other.derived(), dims, output_kernel);\n    }\n\n    // Convolutions.\n    template<typename KernelDerived, typename Dimensions> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorConvolutionOp<const Dimensions, const Derived, const KernelDerived>\n    convolve(const KernelDerived& kernel, const Dimensions& dims) const {\n      return TensorConvolutionOp<const Dimensions, const Derived, const KernelDerived>(derived(), kernel.derived(), dims);\n    }\n\n    // Fourier transforms\n    template <int FFTDataType, int FFTDirection, typename FFT> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorFFTOp<const FFT, const Derived, FFTDataType, FFTDirection>\n    fft(const FFT& dims) const {\n      return TensorFFTOp<const FFT, const Derived, FFTDataType, FFTDirection>(derived(), dims);\n    }\n\n    // Scan.\n    typedef TensorScanOp<internal::SumReducer<CoeffReturnType>, const Derived> TensorScanSumOp;\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorScanSumOp\n    cumsum(const Index& axis, bool exclusive = false) const {\n      return TensorScanSumOp(derived(), axis, exclusive);\n    }\n\n    typedef TensorScanOp<internal::ProdReducer<CoeffReturnType>, const Derived> TensorScanProdOp;\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorScanProdOp\n    cumprod(const Index& axis, bool exclusive = false) const {\n      return TensorScanProdOp(derived(), axis, exclusive);\n    }\n\n    template <typename Reducer>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorScanOp<Reducer, const Derived>\n    scan(const Index& axis, const Reducer& reducer, bool exclusive = false) const {\n      return TensorScanOp<Reducer, const Derived>(derived(), axis, exclusive, reducer);\n    }\n\n    // Reductions.\n    template <typename Dims> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReductionOp<internal::SumReducer<CoeffReturnType>, const Dims, const Derived>\n    sum(const Dims& dims) const {\n      return TensorReductionOp<internal::SumReducer<CoeffReturnType>, const Dims, const Derived>(derived(), dims, internal::SumReducer<CoeffReturnType>());\n    }\n\n    const TensorReductionOp<internal::SumReducer<CoeffReturnType>, const DimensionList<Index, NumDimensions>, const Derived>\n    sum() const {\n      DimensionList<Index, NumDimensions> in_dims;\n      return TensorReductionOp<internal::SumReducer<CoeffReturnType>, const DimensionList<Index, NumDimensions>, const Derived>(derived(), in_dims, internal::SumReducer<CoeffReturnType>());\n    }\n\n    template <typename Dims> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReductionOp<internal::MeanReducer<CoeffReturnType>, const Dims, const Derived>\n    mean(const Dims& dims) const {\n      return TensorReductionOp<internal::MeanReducer<CoeffReturnType>, const Dims, const Derived>(derived(), dims, internal::MeanReducer<CoeffReturnType>());\n    }\n\n    const TensorReductionOp<internal::MeanReducer<CoeffReturnType>, const DimensionList<Index, NumDimensions>, const Derived>\n    mean() const {\n      DimensionList<Index, NumDimensions> in_dims;\n      return TensorReductionOp<internal::MeanReducer<CoeffReturnType>, const DimensionList<Index, NumDimensions>, const Derived>(derived(), in_dims, internal::MeanReducer<CoeffReturnType>());\n    }\n\n    template <typename Dims> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReductionOp<internal::ProdReducer<CoeffReturnType>, const Dims, const Derived>\n    prod(const Dims& dims) const {\n      return TensorReductionOp<internal::ProdReducer<CoeffReturnType>, const Dims, const Derived>(derived(), dims, internal::ProdReducer<CoeffReturnType>());\n    }\n\n    const TensorReductionOp<internal::ProdReducer<CoeffReturnType>, const DimensionList<Index, NumDimensions>, const Derived>\n    prod() const {\n      DimensionList<Index, NumDimensions> in_dims;\n      return TensorReductionOp<internal::ProdReducer<CoeffReturnType>, const DimensionList<Index, NumDimensions>, const Derived>(derived(), in_dims, internal::ProdReducer<CoeffReturnType>());\n    }\n\n    template <typename Dims,int NanPropagation=PropagateFast> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReductionOp<internal::MaxReducer<CoeffReturnType,NanPropagation>, const Dims, const Derived>\n    maximum(const Dims& dims) const {\n      return TensorReductionOp<internal::MaxReducer<CoeffReturnType,NanPropagation>, const Dims, const Derived>(derived(), dims, internal::MaxReducer<CoeffReturnType,NanPropagation>());\n    }\n\n    template <int NanPropagation=PropagateFast>\n    const TensorReductionOp<internal::MaxReducer<CoeffReturnType,NanPropagation>, const DimensionList<Index, NumDimensions>, const Derived>\n    maximum() const {\n      DimensionList<Index, NumDimensions> in_dims;\n      return TensorReductionOp<internal::MaxReducer<CoeffReturnType,NanPropagation>, const DimensionList<Index, NumDimensions>, const Derived>(derived(), in_dims, internal::MaxReducer<CoeffReturnType,NanPropagation>());\n    }\n\n    template <typename Dims,int NanPropagation=PropagateFast> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReductionOp<internal::MinReducer<CoeffReturnType,NanPropagation>, const Dims, const Derived>\n    minimum(const Dims& dims) const {\n      return TensorReductionOp<internal::MinReducer<CoeffReturnType,NanPropagation>, const Dims, const Derived>(derived(), dims, internal::MinReducer<CoeffReturnType,NanPropagation>());\n    }\n\n    template <int NanPropagation=PropagateFast>\n    const TensorReductionOp<internal::MinReducer<CoeffReturnType,NanPropagation>, const DimensionList<Index, NumDimensions>, const Derived>\n    minimum() const {\n      DimensionList<Index, NumDimensions> in_dims;\n      return TensorReductionOp<internal::MinReducer<CoeffReturnType,NanPropagation>, const DimensionList<Index, NumDimensions>, const Derived>(derived(), in_dims, internal::MinReducer<CoeffReturnType,NanPropagation>());\n    }\n\n    template <typename Dims> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReductionOp<internal::AndReducer, const Dims, const typename internal::conditional<internal::is_same<bool, CoeffReturnType>::value, Derived, TensorConversionOp<bool, const Derived> >::type >\n    all(const Dims& dims) const {\n      return cast<bool>().reduce(dims, internal::AndReducer());\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReductionOp<internal::AndReducer, const DimensionList<Index, NumDimensions>, const typename internal::conditional<internal::is_same<bool, CoeffReturnType>::value, Derived, TensorConversionOp<bool, const Derived> >::type >\n    all() const {\n      DimensionList<Index, NumDimensions> in_dims;\n      return cast<bool>().reduce(in_dims, internal::AndReducer());\n    }\n\n    template <typename Dims> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReductionOp<internal::OrReducer, const Dims, const typename internal::conditional<internal::is_same<bool, CoeffReturnType>::value, Derived, TensorConversionOp<bool, const Derived> >::type >\n    any(const Dims& dims) const {\n      return cast<bool>().reduce(dims, internal::OrReducer());\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReductionOp<internal::OrReducer, const DimensionList<Index, NumDimensions>, const typename internal::conditional<internal::is_same<bool, CoeffReturnType>::value, Derived, TensorConversionOp<bool, const Derived> >::type >\n    any() const {\n      DimensionList<Index, NumDimensions> in_dims;\n      return cast<bool>().reduce(in_dims, internal::OrReducer());\n    }\n\n   EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorTupleReducerOp<\n      internal::ArgMaxTupleReducer<Tuple<Index, CoeffReturnType> >,\n      const array<Index, NumDimensions>, const Derived>\n    argmax() const {\n      array<Index, NumDimensions> in_dims;\n      for (Index d = 0; d < NumDimensions; ++d) in_dims[d] = d;\n      return TensorTupleReducerOp<\n        internal::ArgMaxTupleReducer<Tuple<Index, CoeffReturnType> >,\n        const array<Index, NumDimensions>,\n        const Derived>(derived(), internal::ArgMaxTupleReducer<Tuple<Index, CoeffReturnType> >(), -1, in_dims);\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorTupleReducerOp<\n      internal::ArgMinTupleReducer<Tuple<Index, CoeffReturnType> >,\n      const array<Index, NumDimensions>, const Derived>\n    argmin() const {\n      array<Index, NumDimensions> in_dims;\n      for (Index d = 0; d < NumDimensions; ++d) in_dims[d] = d;\n      return TensorTupleReducerOp<\n        internal::ArgMinTupleReducer<Tuple<Index, CoeffReturnType> >,\n        const array<Index, NumDimensions>,\n        const Derived>(derived(), internal::ArgMinTupleReducer<Tuple<Index, CoeffReturnType> >(), -1, in_dims);\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorTupleReducerOp<\n      internal::ArgMaxTupleReducer<Tuple<Index, CoeffReturnType> >,\n      const array<Index, 1>, const Derived>\n    argmax(const Index return_dim) const {\n      array<Index, 1> in_dims;\n      in_dims[0] = return_dim;\n      return TensorTupleReducerOp<\n        internal::ArgMaxTupleReducer<Tuple<Index, CoeffReturnType> >,\n        const array<Index, 1>,\n        const Derived>(derived(), internal::ArgMaxTupleReducer<Tuple<Index, CoeffReturnType> >(), return_dim, in_dims);\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorTupleReducerOp<\n      internal::ArgMinTupleReducer<Tuple<Index, CoeffReturnType> >,\n      const array<Index, 1>, const Derived>\n    argmin(const Index return_dim) const {\n      array<Index, 1> in_dims;\n      in_dims[0] = return_dim;\n      return TensorTupleReducerOp<\n        internal::ArgMinTupleReducer<Tuple<Index, CoeffReturnType> >,\n        const array<Index, 1>,\n        const Derived>(derived(), internal::ArgMinTupleReducer<Tuple<Index, CoeffReturnType> >(), return_dim, in_dims);\n    }\n\n    template <typename Reducer, typename Dims> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReductionOp<Reducer, const Dims, const Derived>\n    reduce(const Dims& dims, const Reducer& reducer) const {\n      return TensorReductionOp<Reducer, const Dims, const Derived>(derived(), dims, reducer);\n    }\n\n    template <typename Dims> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorTraceOp<const Dims, const Derived>\n    trace(const Dims& dims) const {\n      return TensorTraceOp<const Dims, const Derived>(derived(), dims);\n    }\n\n    const TensorTraceOp<const DimensionList<Index, NumDimensions>, const Derived>\n    trace() const {\n      DimensionList<Index, NumDimensions> in_dims;\n      return TensorTraceOp<const DimensionList<Index, NumDimensions>, const Derived>(derived(), in_dims);\n    }\n\n    template <typename Broadcast> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorBroadcastingOp<const Broadcast, const Derived>\n    broadcast(const Broadcast& bcast) const {\n      return TensorBroadcastingOp<const Broadcast, const Derived>(derived(), bcast);\n    }\n\n    template <typename Axis, typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorConcatenationOp<Axis, const Derived, const OtherDerived>\n    concatenate(const OtherDerived& other, Axis axis) const {\n      return TensorConcatenationOp<Axis, const Derived, const OtherDerived>(derived(), other.derived(), axis);\n    }\n\n    template <typename PatchDims> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorPatchOp<const PatchDims, const Derived>\n    extract_patches(const PatchDims& patch_dims) const {\n      return TensorPatchOp<const PatchDims, const Derived>(derived(), patch_dims);\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorImagePatchOp<Dynamic, Dynamic, const Derived>\n    extract_image_patches(const Index patch_rows = 1, const Index patch_cols = 1,\n                          const Index row_stride = 1, const Index col_stride = 1,\n                          const Index in_row_stride = 1, const Index in_col_stride = 1,\n                          const PaddingType padding_type = PADDING_SAME, const Scalar padding_value = Scalar(0)) const {\n      return TensorImagePatchOp<Dynamic, Dynamic, const Derived>(derived(), patch_rows, patch_cols, row_stride, col_stride,\n                                                                 in_row_stride, in_col_stride, 1, 1, padding_type, padding_value);\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorImagePatchOp<Dynamic, Dynamic, const Derived>\n    extract_image_patches(const Index patch_rows, const Index patch_cols,\n                          const Index row_stride, const Index col_stride,\n                          const Index in_row_stride, const Index in_col_stride,\n                          const Index row_inflate_stride, const Index col_inflate_stride,\n                          const Index padding_top, const Index padding_bottom,\n                          const Index padding_left,const Index padding_right,\n                          const Scalar padding_value) const {\n      return TensorImagePatchOp<Dynamic, Dynamic, const Derived>(derived(), patch_rows, patch_cols, row_stride, col_stride,\n                                                                 in_row_stride, in_col_stride, row_inflate_stride, col_inflate_stride,\n                                                                 padding_top, padding_bottom, padding_left, padding_right, padding_value);\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorVolumePatchOp<Dynamic, Dynamic, Dynamic, const Derived>\n    extract_volume_patches(const Index patch_planes, const Index patch_rows, const Index patch_cols,\n                           const Index plane_stride = 1, const Index row_stride = 1, const Index col_stride = 1,\n                           const PaddingType padding_type = PADDING_SAME, const Scalar padding_value = Scalar(0)) const {\n      return TensorVolumePatchOp<Dynamic, Dynamic, Dynamic, const Derived>(derived(), patch_planes, patch_rows, patch_cols, plane_stride, row_stride, col_stride, 1, 1, 1, 1, 1, 1, padding_type, padding_value);\n    }\n\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorVolumePatchOp<Dynamic, Dynamic, Dynamic, const Derived>\n    extract_volume_patches(const Index patch_planes, const Index patch_rows, const Index patch_cols,\n                           const Index plane_stride, const Index row_stride, const Index col_stride,\n                           const Index plane_inflate_stride, const Index row_inflate_stride, const Index col_inflate_stride,\n                           const Index padding_top_z, const Index padding_bottom_z,\n                           const Index padding_top, const Index padding_bottom,\n                           const Index padding_left, const Index padding_right, const Scalar padding_value = Scalar(0)) const {\n      return TensorVolumePatchOp<Dynamic, Dynamic, Dynamic, const Derived>(derived(), patch_planes, patch_rows, patch_cols, plane_stride, row_stride, col_stride, 1, 1, 1, plane_inflate_stride, row_inflate_stride, col_inflate_stride, padding_top_z, padding_bottom_z, padding_top, padding_bottom, padding_left, padding_right, padding_value);\n    }\n\n    // Morphing operators.\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorLayoutSwapOp<const Derived>\n    swap_layout() const {\n      return TensorLayoutSwapOp<const Derived>(derived());\n    }\n    template <typename NewDimensions> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReshapingOp<const NewDimensions, const Derived>\n    reshape(const NewDimensions& newDimensions) const {\n      return TensorReshapingOp<const NewDimensions, const Derived>(derived(), newDimensions);\n    }\n    template <typename StartIndices, typename Sizes> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorSlicingOp<const StartIndices, const Sizes, const Derived>\n    slice(const StartIndices& startIndices, const Sizes& sizes) const {\n      return TensorSlicingOp<const StartIndices, const Sizes, const Derived>(derived(), startIndices, sizes);\n    }\n    template <typename StartIndices, typename StopIndices, typename Strides> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorStridingSlicingOp<const StartIndices, const StopIndices, const Strides, const Derived>\n    stridedSlice(const StartIndices& startIndices, const StopIndices& stopIndices, const Strides& strides) const {\n      return TensorStridingSlicingOp<const StartIndices, const StopIndices, const Strides,\n                                const Derived>(derived(), startIndices, stopIndices, strides);\n    }\n    template <Index DimId> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorChippingOp<DimId, const Derived>\n    chip(const Index offset) const {\n      return TensorChippingOp<DimId, const Derived>(derived(), offset, DimId);\n    }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorChippingOp<Dynamic, const Derived>\n    chip(const Index offset, const Index dim) const {\n      return TensorChippingOp<Dynamic, const Derived>(derived(), offset, dim);\n    }\n    template <typename ReverseDimensions> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReverseOp<const ReverseDimensions, const Derived>\n    reverse(const ReverseDimensions& rev) const {\n      return TensorReverseOp<const ReverseDimensions, const Derived>(derived(), rev);\n    }\n    template <typename PaddingDimensions> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorPaddingOp<const PaddingDimensions, const Derived>\n    pad(const PaddingDimensions& padding) const {\n      return TensorPaddingOp<const PaddingDimensions, const Derived>(derived(), padding, internal::scalar_cast_op<int, Scalar>()(0));\n    }\n    template <typename PaddingDimensions> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorPaddingOp<const PaddingDimensions, const Derived>\n    pad(const PaddingDimensions& padding, const Scalar padding_value) const {\n      return TensorPaddingOp<const PaddingDimensions, const Derived>(derived(), padding, padding_value);\n    }\n    template <typename Shuffle> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorShufflingOp<const Shuffle, const Derived>\n    shuffle(const Shuffle& shfl) const {\n      return TensorShufflingOp<const Shuffle, const Derived>(derived(), shfl);\n    }\n    template <typename Strides> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorStridingOp<const Strides, const Derived>\n    stride(const Strides& strides) const {\n      return TensorStridingOp<const Strides, const Derived>(derived(), strides);\n    }\n    template <typename Strides> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorInflationOp<const Strides, const Derived>\n    inflate(const Strides& strides) const {\n      return TensorInflationOp<const Strides, const Derived>(derived(), strides);\n    }\n\n    // Returns a tensor containing index/value tuples\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorIndexTupleOp<const Derived>\n    index_tuples() const {\n      return TensorIndexTupleOp<const Derived>(derived());\n    }\n\n    // Support for custom unary and binary operations\n    template <typename CustomUnaryFunc>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCustomUnaryOp<const CustomUnaryFunc, const Derived> customOp(const CustomUnaryFunc& op) const {\n      return TensorCustomUnaryOp<const CustomUnaryFunc, const Derived>(derived(), op);\n    }\n    template <typename OtherDerived, typename CustomBinaryFunc>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorCustomBinaryOp<const CustomBinaryFunc, const Derived, const OtherDerived> customOp(const OtherDerived& other, const CustomBinaryFunc& op) const {\n      return TensorCustomBinaryOp<const CustomBinaryFunc, const Derived, const OtherDerived>(derived(), other, op);\n    }\n\n    // Force the evaluation of the expression.\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorForcedEvalOp<const Derived> eval() const {\n      return TensorForcedEvalOp<const Derived>(derived());\n    }\n\n  protected:\n    template <typename Scalar, int NumIndices, int Options, typename IndexType> friend class Tensor;\n    template <typename Scalar, typename Dimensions, int Option, typename IndexTypes> friend class TensorFixedSize;\n    // the Eigen:: prefix is required to workaround a compilation issue with nvcc 9.0\n    template <typename OtherDerived, int AccessLevel> friend class Eigen::TensorBase;\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Derived& derived() const { return *static_cast<const Derived*>(this); }\n};\n\ntemplate<typename Derived, int AccessLevel = internal::accessors_level<Derived>::value>\nclass TensorBase : public TensorBase<Derived, ReadOnlyAccessors> {\n public:\n    typedef TensorBase<Derived, ReadOnlyAccessors> Base;\n    typedef internal::traits<Derived> DerivedTraits;\n    typedef typename DerivedTraits::Scalar Scalar;\n    typedef typename DerivedTraits::Index Index;\n    typedef Scalar CoeffReturnType;\n    static const int NumDimensions = DerivedTraits::NumDimensions;\n\n    template <typename Scalar, int NumIndices, int Options, typename IndexType> friend class Tensor;\n    template <typename Scalar, typename Dimensions, int Option, typename IndexTypes> friend class TensorFixedSize;\n    // the Eigen:: prefix is required to workaround a compilation issue with nvcc 9.0\n    template <typename OtherDerived, int OtherAccessLevel> friend class Eigen::TensorBase;\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Derived& setZero() {\n      return setConstant(Scalar(0));\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Derived& setConstant(const Scalar& val) {\n      return derived() = this->constant(val);\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Derived& setRandom() {\n      return derived() = this->random();\n    }\n    template <typename RandomGenerator> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Derived& setRandom() {\n      return derived() = this->template random<RandomGenerator>();\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Derived& setValues(\n        const typename internal::Initializer<Derived, NumDimensions>::InitList& vals) {\n      TensorEvaluator<Derived, DefaultDevice> eval(derived(), DefaultDevice());\n      internal::initialize_tensor<Derived, NumDimensions>(eval, vals);\n      return derived();\n    }\n#endif  // EIGEN_HAS_VARIADIC_TEMPLATES\n\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    Derived& operator+=(const OtherDerived& other) {\n      return derived() = derived() + other.derived();\n    }\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    Derived& operator-=(const OtherDerived& other) {\n      return derived() = derived() - other.derived();\n    }\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    Derived& operator*=(const OtherDerived& other) {\n      return derived() = derived() * other.derived();\n    }\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    Derived& operator/=(const OtherDerived& other) {\n      return derived() = derived() / other.derived();\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorLayoutSwapOp<const Derived>\n    swap_layout() const {\n      return TensorLayoutSwapOp<const Derived>(derived());\n    }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorLayoutSwapOp<Derived>\n    swap_layout() {\n      return TensorLayoutSwapOp<Derived>(derived());\n    }\n\n    template <typename Axis, typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorConcatenationOp<const Axis, const Derived, const OtherDerived>\n    concatenate(const OtherDerived& other, const Axis& axis) const {\n      return TensorConcatenationOp<const Axis, const Derived, const OtherDerived>(derived(), other, axis);\n    }\n    template <typename Axis, typename OtherDerived> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorConcatenationOp<const Axis, Derived, OtherDerived>\n    concatenate(const OtherDerived& other, const Axis& axis) {\n      return TensorConcatenationOp<const Axis, Derived, OtherDerived>(derived(), other, axis);\n    }\n\n    template <typename NewDimensions> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReshapingOp<const NewDimensions, const Derived>\n    reshape(const NewDimensions& newDimensions) const {\n      return TensorReshapingOp<const NewDimensions, const Derived>(derived(), newDimensions);\n    }\n    template <typename NewDimensions> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorReshapingOp<const NewDimensions, Derived>\n    reshape(const NewDimensions& newDimensions) {\n      return TensorReshapingOp<const NewDimensions, Derived>(derived(), newDimensions);\n    }\n\n    template <typename StartIndices, typename Sizes> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorSlicingOp<const StartIndices, const Sizes, const Derived>\n    slice(const StartIndices& startIndices, const Sizes& sizes) const {\n      return TensorSlicingOp<const StartIndices, const Sizes, const Derived>(derived(), startIndices, sizes);\n    }\n    template <typename StartIndices, typename Sizes> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorSlicingOp<const StartIndices, const Sizes, Derived>\n    slice(const StartIndices& startIndices, const Sizes& sizes) {\n      return TensorSlicingOp<const StartIndices, const Sizes, Derived>(derived(), startIndices, sizes);\n    }\n\n    template <typename StartIndices, typename StopIndices, typename Strides> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorStridingSlicingOp<const StartIndices, const StopIndices, const Strides, const Derived>\n    stridedSlice(const StartIndices& startIndices, const StopIndices& stopIndices, const Strides& strides) const {\n      return TensorStridingSlicingOp<const StartIndices, const StopIndices, const Strides,\n                                const Derived>(derived(), startIndices, stopIndices, strides);\n    }\n    template <typename StartIndices, typename StopIndices, typename Strides> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorStridingSlicingOp<const StartIndices, const StopIndices, const Strides, Derived>\n    stridedSlice(const StartIndices& startIndices, const StopIndices& stopIndices, const Strides& strides) {\n      return TensorStridingSlicingOp<const StartIndices, const StopIndices, const Strides,\n                                Derived>(derived(), startIndices, stopIndices, strides);\n    }\n\n    template <DenseIndex DimId> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorChippingOp<DimId, const Derived>\n    chip(const Index offset) const {\n      return TensorChippingOp<DimId, const Derived>(derived(), offset, DimId);\n    }\n    template <Index DimId> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorChippingOp<DimId, Derived>\n    chip(const Index offset) {\n      return TensorChippingOp<DimId, Derived>(derived(), offset, DimId);\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorChippingOp<Dynamic, const Derived>\n    chip(const Index offset, const Index dim) const {\n      return TensorChippingOp<Dynamic, const Derived>(derived(), offset, dim);\n    }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorChippingOp<Dynamic, Derived>\n    chip(const Index offset, const Index dim) {\n      return TensorChippingOp<Dynamic, Derived>(derived(), offset, dim);\n    }\n\n    template <typename ReverseDimensions> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorReverseOp<const ReverseDimensions, const Derived>\n    reverse(const ReverseDimensions& rev) const {\n      return TensorReverseOp<const ReverseDimensions, const Derived>(derived(), rev);\n    }\n    template <typename ReverseDimensions> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorReverseOp<const ReverseDimensions, Derived>\n    reverse(const ReverseDimensions& rev) {\n      return TensorReverseOp<const ReverseDimensions, Derived>(derived(), rev);\n    }\n\n    template <typename Shuffle> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorShufflingOp<const Shuffle, const Derived>\n    shuffle(const Shuffle& shfl) const {\n      return TensorShufflingOp<const Shuffle, const Derived>(derived(), shfl);\n    }\n    template <typename Shuffle> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorShufflingOp<const Shuffle, Derived>\n    shuffle(const Shuffle& shfl) {\n      return TensorShufflingOp<const Shuffle, Derived>(derived(), shfl);\n    }\n\n    template <typename Strides> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const TensorStridingOp<const Strides, const Derived>\n    stride(const Strides& strides) const {\n      return TensorStridingOp<const Strides, const Derived>(derived(), strides);\n    }\n    template <typename Strides> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorStridingOp<const Strides, Derived>\n    stride(const Strides& strides) {\n      return TensorStridingOp<const Strides, Derived>(derived(), strides);\n    }\n\n    // Select the device on which to evaluate the expression.\n    template <typename DeviceType>\n    TensorDevice<Derived, DeviceType> device(const DeviceType& dev) {\n      return TensorDevice<Derived, DeviceType>(dev, derived());\n    }\n\n    // Select the async device on which to evaluate the expression.\n    template <typename DeviceType, typename DoneCallback>\n    TensorAsyncDevice<Derived, DeviceType, DoneCallback> device(const DeviceType& dev, DoneCallback done) {\n      return TensorAsyncDevice<Derived, DeviceType, DoneCallback>(dev, derived(), std::move(done));\n    }\n\n protected:\n    EIGEN_DEFAULT_EMPTY_CONSTRUCTOR_AND_DESTRUCTOR(TensorBase)\n    EIGEN_DEFAULT_COPY_CONSTRUCTOR(TensorBase)\n\n    template<typename OtherDerived> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Derived& operator=(const OtherDerived& other)\n    {\n      typedef TensorAssignOp<Derived, const OtherDerived> Assign;\n      Assign assign(derived(), other.derived());\n      internal::TensorExecutor<const Assign, DefaultDevice>::run(assign, DefaultDevice());\n      return derived();\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Derived& derived() { return *static_cast<Derived*>(this); }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Derived& derived() const { return *static_cast<const Derived*>(this); }\n};\n#endif // EIGEN_PARSED_BY_DOXYGEN\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_BASE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBlock.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_BLOCK_H\n#define EIGEN_CXX11_TENSOR_TENSOR_BLOCK_H\n\nnamespace Eigen {\nnamespace internal {\n\n// -------------------------------------------------------------------------- //\n// Forward declarations for templates defined below.\ntemplate <typename Scalar, typename IndexType, int NumDims, int Layout>\nclass TensorBlockIO;\n\n// -------------------------------------------------------------------------- //\n// Helper function to compute strides for densely stored buffer of given\n// dimensions.\n\n// TODO(ezhulenev): We compute strides 1000 times in different evaluators, use\n// this function instead everywhere.\ntemplate <int Layout, typename IndexType, int NumDims>\nEIGEN_ALWAYS_INLINE DSizes<IndexType, NumDims> strides(\n    const DSizes<IndexType, NumDims>& dimensions) {\n  DSizes<IndexType, NumDims> strides;\n  if (NumDims == 0) return strides;\n\n  // TODO(ezhulenev): Use templates to unroll this loop (similar to\n  // h_array_reduce in CXX11meta.h)? Benchmark it.\n  if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n    strides[0] = 1;\n    for (int i = 1; i < NumDims; ++i) {\n      strides[i] = strides[i - 1] * dimensions[i - 1];\n    }\n  } else {\n    strides[NumDims - 1] = 1;\n    for (int i = NumDims - 2; i >= 0; --i) {\n      strides[i] = strides[i + 1] * dimensions[i + 1];\n    }\n  }\n\n  return strides;\n}\n\ntemplate <int Layout, typename IndexType, size_t NumDims>\nEIGEN_ALWAYS_INLINE DSizes<IndexType, NumDims> strides(\n    const Eigen::array<IndexType, NumDims>& dimensions) {\n  return strides<Layout>(DSizes<IndexType, NumDims>(dimensions));\n}\n\ntemplate <int Layout, std::ptrdiff_t... Indices>\nEIGEN_STRONG_INLINE DSizes<std::ptrdiff_t, sizeof...(Indices)> strides(\n    const Sizes<Indices...>& sizes) {\n  return strides<Layout>(DSizes<std::ptrdiff_t, sizeof...(Indices)>(sizes));\n}\n\n// -------------------------------------------------------------------------- //\n\n// Tensor block shape type defines what are the shape preference for the blocks\n// extracted from the larger tensor.\n//\n// Example: blocks of 100 elements from the large 100x100 tensor:\n// - tensor: 100x100\n// - target_block_size: 100\n//\n// TensorBlockShapeType:\n//  - kUniformAllDims: 100 blocks of size 10x10\n//  - kSkewedInnerDims: 100 blocks of size 100x1 (or 1x100 depending on a column\n//                      or row major layout)\nenum class TensorBlockShapeType { kUniformAllDims, kSkewedInnerDims };\n\nstruct TensorBlockResourceRequirements {\n  TensorBlockShapeType shape_type;  // target block shape\n  size_t size;                      // target block size\n  TensorOpCost cost_per_coeff;      // cost of computing a single block element\n\n#ifdef EIGEN_HIPCC\n  // For HIPCC, we need to explicitly declare as a \"device fun\", the constructor\n  // which is implicitly invoked in the \"merge\" / \"any\" routines. else HIPCC\n  // errors out complaining about the lack of a matching constructor\n  EIGEN_DEVICE_FUNC\n  TensorBlockResourceRequirements(TensorBlockShapeType shape_type_, size_t size_,\n\t\t\t\t  TensorOpCost cost_)\n    : shape_type(shape_type_), size(size_), cost_per_coeff(cost_)\n  {}\n#endif\n\n  template <typename Scalar>\n  EIGEN_DEVICE_FUNC static TensorBlockResourceRequirements withShapeAndSize(\n      TensorBlockShapeType shape_type, size_t size_in_bytes,\n      TensorOpCost cost) {\n    const size_t size = numext::maxi(size_t(1), size_in_bytes / sizeof(Scalar));\n    return {shape_type, size, cost};\n  }\n\n  template <typename Scalar>\n  EIGEN_DEVICE_FUNC static TensorBlockResourceRequirements withShapeAndSize(\n      TensorBlockShapeType shape_type, size_t size_in_bytes) {\n    // This default cost per coefficient is valid for most materialized tensor\n    // block evaluation implementations, because they typically just read\n    // coefficients from the underlying tensor storage, and write to the tensor\n    // block buffer (scratch or destination memory, reads and writes have linear\n    // access pattern). We ignore the fixed cost of block evaluation, because in\n    // practice it should negligible.\n    //\n    // Lazy block evaluation adds the cost of calling a functor for each\n    // coefficient.\n    //\n    // All non-trivial block evaluation implementations must provide their own\n    // cost approximation (e.g. shuffling inner dimension has a much higher cost\n    // because it reads memory randomly, although the total number of moved\n    // bytes is the same).\n    return withShapeAndSize<Scalar>(shape_type, size_in_bytes,\n                                    {/*bytes_loaded=*/sizeof(Scalar),\n                                     /*bytes_stored=*/sizeof(Scalar),\n                                     /*compute_cycles=*/0});\n  }\n\n  template <typename Scalar>\n  EIGEN_DEVICE_FUNC static TensorBlockResourceRequirements skewed(\n      size_t size_in_bytes) {\n    return withShapeAndSize<Scalar>(TensorBlockShapeType::kSkewedInnerDims,\n                                    size_in_bytes);\n  }\n\n  template <typename Scalar>\n  EIGEN_DEVICE_FUNC static TensorBlockResourceRequirements uniform(\n      size_t size_in_bytes) {\n    return withShapeAndSize<Scalar>(TensorBlockShapeType::kUniformAllDims,\n                                    size_in_bytes);\n  }\n\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE TensorBlockResourceRequirements\n  merge(const TensorBlockResourceRequirements& lhs,\n        const TensorBlockResourceRequirements& rhs) {\n    return {merge(lhs.shape_type, rhs.shape_type),           // shape_type\n            merge(lhs.size, rhs.size),                       // size\n            merge(lhs.cost_per_coeff, rhs.cost_per_coeff)};  // cost_per_coeff\n  }\n\n  EIGEN_DEVICE_FUNC TensorBlockResourceRequirements& addCostPerCoeff(\n      TensorOpCost cost) {\n    cost_per_coeff += cost;\n    return *this;\n  }\n\n  // This is a resource requirement that should be returned from expressions\n  // that do not have any block evaluation preference (e.g. default tensor\n  // expression with raw buffer access).\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE TensorBlockResourceRequirements any() {\n    return {TensorBlockShapeType::kUniformAllDims, 1, {0, 0, 0}};\n  }\n\n private:\n  using Requirements = TensorBlockResourceRequirements;\n\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE size_t merge(size_t lhs_size, size_t rhs_size) {\n    return numext::maxi(lhs_size, rhs_size);\n  }\n\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE TensorBlockShapeType\n  merge(TensorBlockShapeType lhs, TensorBlockShapeType rhs) {\n    return (lhs == TensorBlockShapeType::kSkewedInnerDims ||\n            rhs == TensorBlockShapeType::kSkewedInnerDims)\n               ? TensorBlockShapeType::kSkewedInnerDims\n               : TensorBlockShapeType::kUniformAllDims;\n  }\n\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE TensorOpCost merge(TensorOpCost lhs_cost,\n                                                TensorOpCost rhs_cost) {\n    return lhs_cost + rhs_cost;\n  }\n};\n\n// -------------------------------------------------------------------------- //\n// TensorBlockDescriptor specifies a block offset within a tensor and the block\n// sizes along each of the tensor dimensions.\n\ntemplate <int NumDims, typename IndexType = Eigen::Index>\nclass TensorBlockDescriptor {\n public:\n  typedef DSizes<IndexType, NumDims> Dimensions;\n\n  // If we evaluate a Tensor assignment, and expression on the left, already has\n  // a memory buffer, then we might do performance optimization, and evaluate\n  // the root expression directly into the final output memory. Some time it's\n  // possible to reuse it for materializing subexpressions inside an expression\n  // tree, to to avoid dynamic memory allocation.\n  //\n  // The pointer type of the underlying storage is erased, because passing\n  // Scalar type through all the expression evaluation layers is way too many\n  // templates. In practice destination buffer type should always match the\n  // evaluated expression scalar type.\n  class DestinationBuffer {\n   public:\n    enum DestinationBufferKind : int {\n      // The above explicit specification of \"int\" as the enum basetype is\n      // needed to get around a HIPCC link error (\"the field type is not\n      // amp-compatible\")\n      // which is issued for class members with the enum type.\n      // TODO(rocm):\n      // remove the \"int\" basetype once HIPCC has been fixed to not error out\n      // in the above scenario.\n\n      // Destination buffer is not defined (`m_data` == nullptr).\n      kEmpty,\n\n      // Tensor block defined by an owning tensor block descriptor can fit\n      // contiguously into the destination buffer. In this case it's safe to\n      // materialize tensor block in the destination buffer, wrap it in a\n      // TensorMap, and use to build Eigen expression on top of it.\n      kContiguous,\n\n      // Destination buffer strides do not match strides of the contiguously\n      // stored block, and it's impossible to define a TensorMap over this\n      // buffer. However if we are evaluating a root of an expression tree, we\n      // still can materialize an output into this destination, because we can\n      // guarantee that no one will ever access it through block API.\n      //\n      // In theory it is possible to build valid TensorStriding<TensorMap>\n      // expression on top of this destination buffer, however it has\n      // inefficient coeff/packet access, and defeats the purpose of fast block\n      // evaluation API.\n      kStrided\n    };\n\n    template <typename Scalar>\n    Scalar* data() const {\n      eigen_assert(m_data_type_size == sizeof(Scalar));\n      return static_cast<Scalar*>(m_data);\n    }\n\n    const Dimensions& strides() const { return m_strides; }\n    const DestinationBufferKind& kind() const { return m_kind; }\n\n   private:\n    friend class TensorBlockDescriptor;\n\n    DestinationBuffer() : m_data(NULL), m_data_type_size(0), m_kind(kEmpty) {}\n\n    template <typename Scalar>\n    DestinationBuffer(Scalar* data, const Dimensions& strides,\n                      DestinationBufferKind kind)\n        : m_data(static_cast<void*>(data)),\n          m_data_type_size(sizeof(Scalar)),\n          m_strides(strides),\n          m_kind(kind) {}\n\n    template <int Layout, typename Scalar>\n    static DestinationBuffer make(const TensorBlockDescriptor& desc,\n                                  Scalar* data, const Dimensions& strides) {\n      return DestinationBuffer(data, strides, kind<Layout>(desc, strides));\n    }\n\n    template <int Layout>\n    static DestinationBufferKind kind(const TensorBlockDescriptor& desc,\n                                      const Dimensions& strides) {\n      const Dimensions& desc_dims = desc.dimensions();\n      const Dimensions& desc_strides = internal::strides<Layout>(desc_dims);\n      for (int i = 0; i < NumDims; ++i) {\n        if (desc_dims[i] == 1) continue;\n        if (desc_strides[i] != strides[i]) return kStrided;\n      }\n      return kContiguous;\n    }\n\n    // Storage pointer is type erased, to reduce template bloat, but we still\n    // keep the size of the underlying element type for error checking.\n    void* m_data;\n    size_t m_data_type_size;\n\n    // Destination buffer dimensions always match the dimensions of a tensor\n    // block descriptor it belongs to, however strides might be different.\n    Dimensions m_strides;\n\n    DestinationBufferKind m_kind;\n  };\n\n  TensorBlockDescriptor(const IndexType offset, const Dimensions& dimensions,\n                        const DestinationBuffer& destination)\n      : m_offset(offset),\n        m_dimensions(dimensions),\n        m_destination(destination) {}\n\n  TensorBlockDescriptor(const IndexType offset, const Dimensions& dimensions)\n      : m_offset(offset),\n        m_dimensions(dimensions),\n        m_destination(DestinationBuffer()) {}\n\n  IndexType offset() const { return m_offset; }\n  const Dimensions& dimensions() const { return m_dimensions; }\n  IndexType dimension(int index) const { return m_dimensions[index]; }\n  IndexType size() const { return array_prod<IndexType>(m_dimensions); }\n\n  const DestinationBuffer& destination() const { return m_destination; }\n\n  template <int Layout, typename Scalar>\n  void AddDestinationBuffer(Scalar* dst_base, const Dimensions& dst_strides) {\n    eigen_assert(dst_base != NULL);\n    m_destination =\n        DestinationBuffer::template make<Layout>(*this, dst_base, dst_strides);\n  }\n\n  template <int Layout, typename Scalar, typename DstStridesIndexType>\n  void AddDestinationBuffer(\n      Scalar* dst_base,\n      const DSizes<DstStridesIndexType, NumDims>& dst_strides) {\n    // DSizes constructor will do index type promotion if it's safe.\n    AddDestinationBuffer<Layout>(dst_base, Dimensions(dst_strides));\n  }\n\n  TensorBlockDescriptor& DropDestinationBuffer() {\n    m_destination.m_data = NULL;\n    m_destination.m_kind = DestinationBuffer::kEmpty;\n    return *this;\n  }\n\n  bool HasDestinationBuffer() const {\n    return m_destination.kind() != DestinationBuffer::kEmpty;\n  }\n\n  // Returns a copy of `*this` with updated offset.\n  TensorBlockDescriptor WithOffset(IndexType offset) const {\n    return TensorBlockDescriptor(offset, m_dimensions, m_destination);\n  }\n\n private:\n  // Offset and dimensions are immutable after construction. Block descriptor\n  // can only be mutated by adding or dropping destination.\n  const IndexType m_offset;\n  const Dimensions m_dimensions;\n  DestinationBuffer m_destination;\n};\n\n// -------------------------------------------------------------------------- //\n// TensorBlockMapper is responsible for iterating over the blocks of a tensor.\n\ntemplate <int NumDims, int Layout, typename IndexType = Eigen::Index>\nclass TensorBlockMapper {\n  typedef TensorBlockDescriptor<NumDims, IndexType> BlockDescriptor;\n\n public:\n  typedef DSizes<IndexType, NumDims> Dimensions;\n\n  TensorBlockMapper() = default;\n  TensorBlockMapper(const DSizes<IndexType, NumDims>& dimensions,\n                    const TensorBlockResourceRequirements& requirements)\n      : m_tensor_dimensions(dimensions), m_requirements(requirements) {\n    // Compute block dimensions and the total number of blocks.\n    InitializeBlockDimensions();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE IndexType blockCount() const {\n    return m_total_block_count;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE IndexType blockTotalSize() const {\n    return m_block_dimensions.TotalSize();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const DSizes<IndexType, NumDims>&\n  blockDimensions() const {\n    return m_block_dimensions;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE BlockDescriptor\n  blockDescriptor(IndexType block_index) const {\n    static const bool isColMajor = Layout == static_cast<int>(ColMajor);\n\n    IndexType offset = 0;\n    DSizes<IndexType, NumDims> dimensions;\n\n    if (NumDims == 0) return BlockDescriptor(offset, dimensions);\n\n    // Iterate outer -> inner dimensions.\n    for (int i = NumDims - 1; i >= 0; --i) {\n      const int dim = isColMajor ? i : NumDims - i - 1;\n\n      const IndexType idx = block_index / m_block_strides[dim];\n      block_index -= idx * m_block_strides[dim];\n\n      const IndexType coord = idx * m_block_dimensions[dim];\n      dimensions[dim] = numext::mini(m_tensor_dimensions[dim] - coord,\n                                     m_block_dimensions[dim]);\n      offset += coord * m_tensor_strides[dim];\n    }\n\n    return {offset, dimensions};\n  }\n\n private:\n  void InitializeBlockDimensions() {\n    // Requested block shape and size.\n    const TensorBlockShapeType shape_type = m_requirements.shape_type;\n    IndexType target_block_size =\n        numext::maxi<IndexType>(1, static_cast<IndexType>(m_requirements.size));\n\n    IndexType tensor_size = m_tensor_dimensions.TotalSize();\n\n    // Corner case: one of the dimensions is zero. Logic below is too complex\n    // to handle this case on a general basis, just use unit block size.\n    // Note: we must not yield blocks with zero dimensions (recipe for\n    // overflows/underflows, divisions by zero and NaNs later).\n    if (tensor_size == 0) {\n      for (int i = 0; i < NumDims; ++i) {\n        m_block_dimensions[i] = 1;\n      }\n      m_total_block_count = 0;\n      return;\n    }\n\n    // If tensor fits into a target block size, evaluate it as a single block.\n    if (tensor_size <= target_block_size) {\n      m_block_dimensions = m_tensor_dimensions;\n      m_total_block_count = 1;\n      // The only valid block index is `0`, and in this case we do not need\n      // to compute real strides for tensor or blocks (see blockDescriptor).\n      for (int i = 0; i < NumDims; ++i) {\n        m_tensor_strides[i] = 0;\n        m_block_strides[i] = 1;\n      }\n      return;\n    }\n\n    static const bool isColMajor = Layout == static_cast<int>(ColMajor);\n\n    // Block shape skewed towards inner dimension.\n    if (shape_type == TensorBlockShapeType::kSkewedInnerDims) {\n      IndexType coeff_to_allocate = target_block_size;\n\n      for (int i = 0; i < NumDims; ++i) {\n        const int dim = isColMajor ? i : NumDims - i - 1;\n        m_block_dimensions[dim] =\n            numext::mini(coeff_to_allocate, m_tensor_dimensions[dim]);\n        coeff_to_allocate = divup(\n            coeff_to_allocate,\n            numext::maxi(static_cast<IndexType>(1), m_block_dimensions[dim]));\n      }\n      eigen_assert(coeff_to_allocate == 1);\n\n    } else if (shape_type == TensorBlockShapeType::kUniformAllDims) {\n      // Tensor will not fit within 'target_block_size' budget: calculate tensor\n      // block dimension sizes based on \"square\" dimension size target.\n      const IndexType dim_size_target = convert_index<IndexType>(\n          std::pow(static_cast<float>(target_block_size),\n                   1.0f / static_cast<float>(m_block_dimensions.rank())));\n\n      for (int i = 0; i < NumDims; ++i) {\n        // TODO(andydavis) Adjust the inner most 'block_dim_size' to make it\n        // a multiple of the packet size. Note that reducing\n        // 'block_dim_size' in this manner can increase the number of\n        // blocks, and so will amplify any per-block overhead.\n        m_block_dimensions[i] =\n            numext::mini(dim_size_target, m_tensor_dimensions[i]);\n      }\n\n      // Add any un-allocated coefficients to inner dimension(s).\n      IndexType total_size = m_block_dimensions.TotalSize();\n      for (int i = 0; i < NumDims; ++i) {\n        const int dim = isColMajor ? i : NumDims - i - 1;\n\n        if (m_block_dimensions[dim] < m_tensor_dimensions[dim]) {\n          const IndexType total_size_other_dims =\n              total_size / m_block_dimensions[dim];\n          const IndexType alloc_avail =\n              divup<IndexType>(target_block_size, total_size_other_dims);\n          if (alloc_avail == m_block_dimensions[dim]) {\n            // Insufficient excess coefficients to allocate.\n            break;\n          }\n          m_block_dimensions[dim] =\n              numext::mini(m_tensor_dimensions[dim], alloc_avail);\n          total_size = total_size_other_dims * m_block_dimensions[dim];\n        }\n      }\n\n    } else {\n      eigen_assert(false);  // unknown block shape\n    }\n\n    eigen_assert(m_block_dimensions.TotalSize() >=\n                 numext::mini<IndexType>(target_block_size,\n                                         m_tensor_dimensions.TotalSize()));\n\n    // Calculate block counts by dimension and total block count.\n    DSizes<IndexType, NumDims> block_count;\n    for (int i = 0; i < NumDims; ++i) {\n      block_count[i] = divup(m_tensor_dimensions[i], m_block_dimensions[i]);\n    }\n    m_total_block_count = array_prod(block_count);\n\n    // Calculate block strides (used for enumerating blocks).\n    m_tensor_strides = strides<Layout>(m_tensor_dimensions);\n    m_block_strides = strides<Layout>(block_count);\n  }\n\n  DSizes<IndexType, NumDims> m_tensor_dimensions;\n  TensorBlockResourceRequirements m_requirements;\n\n  DSizes<IndexType, NumDims> m_block_dimensions;\n  IndexType m_total_block_count;\n\n  DSizes<IndexType, NumDims> m_tensor_strides;\n  DSizes<IndexType, NumDims> m_block_strides;\n};\n\n// -------------------------------------------------------------------------- //\n// TensorBlockScratchAllocator is responsible for allocating temporary buffers\n// for block evaluation (output or input block materialization). Given that\n// Eigen expression traversal order is deterministic, all temporary allocations\n// are happening in the same order, and usually have exactly the same size.\n// Scratch allocator keeps a trace of all dynamic allocations, and after the\n// first block evaluation is completed, we should be able to reuse all the\n// temporary buffers for the next block evaluation.\n\ntemplate <typename Device>\nclass TensorBlockScratchAllocator {\n public:\n  explicit TensorBlockScratchAllocator(const Device& device)\n      : m_device(device), m_allocation_index(0) {}\n\n  ~TensorBlockScratchAllocator() {\n    for (size_t i = 0; i < m_allocations.size(); ++i) {\n      m_device.deallocate(m_allocations[i].ptr);\n    }\n  }\n\n  void* allocate(size_t size) {\n    // TODO(ezhulenev): Remove when replaced with inlined vector.\n    if (m_allocations.capacity() == 0) m_allocations.reserve(8);\n\n    // Check if we already have an existing allocation att current index.\n    const int num_allocations = static_cast<int>(m_allocations.size());\n    const bool has_allocation = m_allocation_index < num_allocations;\n\n    // Allocation index can't be larger than the number of allocations.\n    eigen_assert(m_allocation_index <= num_allocations);\n\n    // If we have existing allocation, and its size is larger or equal to\n    // requested size, we do nothing.\n\n    // If current allocation can't fit requested size, we deallocate it, and\n    // replace with a larger allocation.\n    if (has_allocation && m_allocations[m_allocation_index].size < size) {\n      m_device.deallocate(m_allocations[m_allocation_index].ptr);\n      m_allocations[m_allocation_index].ptr = m_device.allocate(size);\n      m_allocations[m_allocation_index].size = size;\n    }\n\n    // Make a new allocation if we don't have and existing one.\n    if (!has_allocation) {\n      Allocation allocation;\n      allocation.ptr = m_device.allocate(size);\n      allocation.size = size;\n      m_allocations.push_back(allocation);\n    }\n\n    eigen_assert(m_allocations[m_allocation_index].ptr != NULL);\n    eigen_assert(m_allocations[m_allocation_index].size >= size);\n\n    return m_allocations[m_allocation_index++].ptr;\n  }\n\n  void reset() { m_allocation_index = 0; }\n\n private:\n  struct Allocation {\n    void* ptr;\n    size_t size;\n  };\n\n  const Device& m_device;\n  int m_allocation_index;\n  // TODO(ezhulenev): This should be an inlined vector.\n  std::vector<Allocation> m_allocations;\n};\n\n// -------------------------------------------------------------------------- //\n// TensorBlockKind represents all possible block kinds, that can be produced by\n// TensorEvaluator::evalBlock function.\nenum TensorBlockKind {\n  // Tensor block that is a lazy expression that must be assigned to a\n  // destination using TensorBlockAssign.\n  kExpr,\n\n  // Tensor block that is a view into a memory buffer owned by an underlying\n  // Tensor expression (e.g. it can be a view into a Tensor buffer).\n  kView,\n\n  // Tensor block that was materialized in a scratch memory buffer, allocated\n  // with TensorBlockScratchAllocator. This block must be copied to a\n  // destination, similar to a block of `kExpr` type.\n  kMaterializedInScratch,\n\n  // Tensor block that was materialized directly into the final output memory\n  // buffer. For example if the left side of an assignment is a Tensor, we can\n  // directly materialize the block in the destination memory.\n  //\n  // If strides in the output buffer do not match tensor block strides, the\n  // Tensor expression will be invalid, and should not be used by\n  // TensorBlockAssign or for constructing another block expression.\n  kMaterializedInOutput\n};\n\n// -------------------------------------------------------------------------- //\n// TensorBlockNotImplemented should be used to defined TensorBlock typedef in\n// TensorEvaluators that do not support block evaluation.\n\nclass TensorBlockNotImplemented {\n public:\n  typedef void XprType;\n};\n\n// -------------------------------------------------------------------------- //\n// XprScalar extracts Scalar type from the Eigen expressions (if expression type\n// is not void). It's required to be able to define lazy block expression for\n// argument types, that do not support block evaluation.\n\ntemplate <typename XprType>\nstruct XprScalar {\n  typedef typename XprType::Scalar type;\n};\ntemplate <>\nstruct XprScalar<void> {\n  typedef void type;\n};\n\n// -------------------------------------------------------------------------- //\n// TensorMaterializedBlock is a fully evaluated block of the original tensor,\n// and XprType is just a TensorMap over the data. This block type is typically\n// used to materialize blocks of tensor expressions, that can't be efficiently\n// represented as lazy Tensor expressions with fast coeff/packet operations,\n// e.g. we materialize all broadcasts into evaluated blocks.\n//\n// TensorMaterializedBlock does not own its memory buffer, it's either a memory\n// buffer that backs the original expression (e.g. block is just a view into a\n// Tensor), or a memory buffer allocated with scratch allocator, and in this\n// case the scratch allocator will deallocate it at the end of block based\n// expression execution.\n//\n// If the block was evaluated directly into the output buffer, and strides in\n// the output buffer do not match block strides, the TensorMap expression will\n// be invalid, and should never be used in block assignment or any other tensor\n// expression.\n\ntemplate <typename Scalar, int NumDims, int Layout,\n          typename IndexType = Eigen::Index>\nclass TensorMaterializedBlock {\n public:\n  typedef DSizes<IndexType, NumDims> Dimensions;\n  typedef TensorMap<const Tensor<Scalar, NumDims, Layout> > XprType;\n\n  TensorMaterializedBlock(TensorBlockKind kind, const Scalar* data,\n                          const Dimensions& dimensions, bool valid_expr = true)\n      : m_kind(kind),\n        m_data(data),\n        m_dimensions(dimensions),\n        m_expr(m_data, m_dimensions),\n        m_valid_expr(valid_expr) {\n    eigen_assert(m_kind == internal::TensorBlockKind::kView ||\n                 m_kind == internal::TensorBlockKind::kMaterializedInScratch ||\n                 m_kind == internal::TensorBlockKind::kMaterializedInOutput);\n  }\n\n  TensorBlockKind kind() const { return m_kind; }\n  // NOTE(ezhulenev): Returning XprType by value like in other block types\n  // causes asan failures. The theory is that XprType::Nested doesn't work\n  // properly for TensorMap.\n  const XprType& expr() const {\n    eigen_assert(m_valid_expr);\n    return m_expr;\n  }\n  const Scalar* data() const { return m_data; }\n  void cleanup() {}\n\n  typedef internal::TensorBlockDescriptor<NumDims, IndexType> TensorBlockDesc;\n\n  // TensorMaterializedBlock can be backed by different types of storage:\n  //\n  //   (1) Contiguous block of memory allocated with scratch allocator.\n  //   (2) Contiguous block of memory reused from tensor block descriptor\n  //       destination buffer.\n  //   (3) Strided block of memory reused from tensor block descriptor\n  //       destination buffer.\n  //\n  class Storage {\n   public:\n    Scalar* data() const { return m_data; }\n    const Dimensions& dimensions() const { return m_dimensions; }\n    const Dimensions& strides() const { return m_strides; }\n\n    TensorMaterializedBlock AsTensorMaterializedBlock() const {\n      return TensorMaterializedBlock(\n          m_materialized_in_output\n              ? internal::TensorBlockKind::kMaterializedInOutput\n              : internal::TensorBlockKind::kMaterializedInScratch,\n          m_data, m_dimensions, !m_strided_storage);\n    }\n\n   private:\n    friend class TensorMaterializedBlock;\n\n    Storage(Scalar* data, const Dimensions& dimensions,\n            const Dimensions& strides, bool materialized_in_output,\n            bool strided_storage)\n        : m_data(data),\n          m_dimensions(dimensions),\n          m_strides(strides),\n          m_materialized_in_output(materialized_in_output),\n          m_strided_storage(strided_storage) {}\n\n    Scalar* m_data;\n    Dimensions m_dimensions;\n    Dimensions m_strides;\n    bool m_materialized_in_output;\n    bool m_strided_storage;\n  };\n\n  // Creates a storage for materialized block either from the block descriptor\n  // destination buffer, or allocates a new buffer with scratch allocator.\n  template <typename TensorBlockScratch>\n  EIGEN_STRONG_INLINE static Storage prepareStorage(\n      TensorBlockDesc& desc, TensorBlockScratch& scratch,\n      bool allow_strided_storage = false) {\n    // Try to reuse destination as an output block buffer.\n    typedef typename TensorBlockDesc::DestinationBuffer DestinationBuffer;\n\n    if (desc.destination().kind() == DestinationBuffer::kContiguous) {\n      Scalar* buffer = desc.destination().template data<Scalar>();\n      desc.DropDestinationBuffer();\n      return Storage(buffer, desc.dimensions(),\n                     internal::strides<Layout>(desc.dimensions()),\n                     /*materialized_in_output=*/true,\n                     /*strided_storage=*/false);\n\n    } else if (desc.destination().kind() == DestinationBuffer::kStrided &&\n               allow_strided_storage) {\n      Scalar* buffer = desc.destination().template data<Scalar>();\n      desc.DropDestinationBuffer();\n      return Storage(buffer, desc.dimensions(), desc.destination().strides(),\n                     /*materialized_in_output=*/true, /*strided_storage=*/true);\n\n    } else {\n      void* mem = scratch.allocate(desc.size() * sizeof(Scalar));\n      return Storage(static_cast<Scalar*>(mem), desc.dimensions(),\n                     internal::strides<Layout>(desc.dimensions()),\n                     /*materialized_in_output=*/false,\n                     /*strided_storage=*/false);\n    }\n  }\n\n  // Creates a materialized block for the given descriptor from a memory buffer.\n  template <typename DataDimensions, typename TensorBlockScratch>\n  EIGEN_STRONG_INLINE static TensorMaterializedBlock materialize(\n      const Scalar* data, const DataDimensions& data_dims,\n      TensorBlockDesc& desc, TensorBlockScratch& scratch) {\n    eigen_assert(array_size<DataDimensions>::value == desc.dimensions().size());\n\n    // If a tensor block dimensions covers a contiguous block of the underlying\n    // memory, we can skip block buffer memory allocation, and construct a block\n    // from existing `data` memory buffer.\n    //\n    // Example: (RowMajor layout)\n    //   data_dims:          [11, 12, 13, 14]\n    //   desc.dimensions():  [1,   1,  3, 14]\n    //\n    // In this case we can construct a TensorBlock starting at\n    // `data + desc.offset()`, with a `desc.dimensions()` block sizes.\n    static const bool is_col_major = Layout == ColMajor;\n\n    // Find out how many inner dimensions have a matching size.\n    int num_matching_inner_dims = 0;\n    for (int i = 0; i < NumDims; ++i) {\n      int dim = is_col_major ? i : NumDims - i - 1;\n      if (data_dims[dim] != desc.dimensions()[dim]) break;\n      ++num_matching_inner_dims;\n    }\n\n    // All the outer dimensions must be of size `1`, except a single dimension\n    // before the matching inner dimension (`3` in the example above).\n    bool can_use_direct_access = true;\n    for (int i = num_matching_inner_dims + 1; i < NumDims; ++i) {\n      int dim = is_col_major ? i : NumDims - i - 1;\n      if (desc.dimension(dim) != 1) {\n        can_use_direct_access = false;\n        break;\n      }\n    }\n\n    if (can_use_direct_access) {\n      const Scalar* block_start = data + desc.offset();\n      return TensorMaterializedBlock(internal::TensorBlockKind::kView,\n                                     block_start, desc.dimensions());\n\n    } else {\n      // Reuse destination buffer or allocate new buffer with scratch allocator.\n      const Storage storage = prepareStorage(desc, scratch);\n\n      typedef internal::TensorBlockIO<Scalar, IndexType, NumDims, Layout>\n          TensorBlockIO;\n      typedef typename TensorBlockIO::Dst TensorBlockIODst;\n      typedef typename TensorBlockIO::Src TensorBlockIOSrc;\n\n      TensorBlockIOSrc src(internal::strides<Layout>(Dimensions(data_dims)),\n                           data, desc.offset());\n      TensorBlockIODst dst(storage.dimensions(), storage.strides(),\n                           storage.data());\n\n      TensorBlockIO::Copy(dst, src);\n      return storage.AsTensorMaterializedBlock();\n    }\n  }\n\n private:\n  TensorBlockKind m_kind;\n  const Scalar* m_data;\n  Dimensions m_dimensions;\n  XprType m_expr;\n  bool m_valid_expr;\n};\n\n// -------------------------------------------------------------------------- //\n// TensorCwiseUnaryBlock is a lazy tensor expression block that applies UnaryOp\n// functor to the blocks produced by the underlying Tensor expression.\n\ntemplate <typename UnaryOp, typename ArgTensorBlock>\nclass TensorCwiseUnaryBlock {\n  static const bool NoArgBlockAccess =\n      internal::is_void<typename ArgTensorBlock::XprType>::value;\n\n public:\n  typedef typename conditional<\n      NoArgBlockAccess, void,\n      TensorCwiseUnaryOp<UnaryOp, const typename ArgTensorBlock::XprType> >::\n      type XprType;\n\n  typedef typename XprScalar<XprType>::type Scalar;\n\n  TensorCwiseUnaryBlock(const ArgTensorBlock& arg_block, const UnaryOp& functor)\n      : m_arg_block(arg_block), m_functor(functor) {}\n\n  TensorBlockKind kind() const { return internal::TensorBlockKind::kExpr; }\n\n  XprType expr() const { return XprType(m_arg_block.expr(), m_functor); }\n  const Scalar* data() const { return NULL; }\n  void cleanup() { m_arg_block.cleanup(); }\n\n private:\n  ArgTensorBlock m_arg_block;\n  UnaryOp m_functor;\n};\n\n// -------------------------------------------------------------------------- //\n// TensorCwiseUnaryBlock is a lazy tensor expression block that applies BinaryOp\n// functor to the blocks produced by the underlying Tensor expression.\n\ntemplate <typename BinaryOp, typename LhsTensorBlock, typename RhsTensorBlock>\nclass TensorCwiseBinaryBlock {\n  static const bool NoArgBlockAccess =\n      internal::is_void<typename LhsTensorBlock::XprType>::value ||\n      internal::is_void<typename RhsTensorBlock::XprType>::value;\n\n public:\n  typedef typename conditional<\n      NoArgBlockAccess, void,\n      TensorCwiseBinaryOp<BinaryOp, const typename LhsTensorBlock::XprType,\n                          const typename RhsTensorBlock::XprType> >::type\n      XprType;\n\n  typedef typename XprScalar<XprType>::type Scalar;\n\n  TensorCwiseBinaryBlock(const LhsTensorBlock& left_block,\n                         const RhsTensorBlock& right_block,\n                         const BinaryOp& functor)\n      : m_left_block(left_block),\n        m_right_block(right_block),\n        m_functor(functor) {}\n\n  TensorBlockKind kind() const { return internal::TensorBlockKind::kExpr; }\n\n  XprType expr() const {\n    return XprType(m_left_block.expr(), m_right_block.expr(), m_functor);\n  }\n\n  const Scalar* data() const { return NULL; }\n\n  void cleanup() {\n    m_left_block.cleanup();\n    m_right_block.cleanup();\n  }\n\n private:\n  LhsTensorBlock m_left_block;\n  RhsTensorBlock m_right_block;\n  BinaryOp m_functor;\n};\n\n// -------------------------------------------------------------------------- //\n// TensorUnaryExprBlock is a lazy tensor expression block that can construct\n// an arbitrary tensor expression from a block of the underlying type (this is a\n// generalization of the TensorCwiseUnaryBlock for arbitrary expressions).\n\ntemplate <typename BlockFactory, typename ArgTensorBlock>\nclass TensorUnaryExprBlock {\n  typedef typename ArgTensorBlock::XprType ArgXprType;\n  static const bool NoArgBlockAccess = internal::is_void<ArgXprType>::value;\n\n public:\n  typedef typename conditional<\n      NoArgBlockAccess, void,\n      typename BlockFactory::template XprType<ArgXprType>::type>::type XprType;\n\n  typedef typename XprScalar<XprType>::type Scalar;\n\n  TensorUnaryExprBlock(const ArgTensorBlock& arg_block,\n                       const BlockFactory& factory)\n      : m_arg_block(arg_block), m_factory(factory) {}\n\n  TensorBlockKind kind() const { return internal::TensorBlockKind::kExpr; }\n  XprType expr() const { return m_factory.expr(m_arg_block.expr()); }\n  const Scalar* data() const { return NULL; }\n  void cleanup() { m_arg_block.cleanup(); }\n\n private:\n  ArgTensorBlock m_arg_block;\n  BlockFactory m_factory;\n};\n\n// -------------------------------------------------------------------------- //\n// TensorTernaryExprBlock is a lazy tensor expression block that can construct\n// an arbitrary tensor expression from three blocks of the underlying type.\n\ntemplate <typename BlockFactory, typename Arg1TensorBlock,\n          typename Arg2TensorBlock, typename Arg3TensorBlock>\nclass TensorTernaryExprBlock {\n  typedef typename Arg1TensorBlock::XprType Arg1XprType;\n  typedef typename Arg2TensorBlock::XprType Arg2XprType;\n  typedef typename Arg3TensorBlock::XprType Arg3XprType;\n\n  static const bool NoArgBlockAccess = internal::is_void<Arg1XprType>::value ||\n                                       internal::is_void<Arg2XprType>::value ||\n                                       internal::is_void<Arg3XprType>::value;\n\n public:\n  typedef typename conditional<\n      NoArgBlockAccess, void,\n      typename BlockFactory::template XprType<Arg1XprType, Arg2XprType,\n                                              Arg3XprType>::type>::type XprType;\n\n  typedef typename XprScalar<XprType>::type Scalar;\n\n  TensorTernaryExprBlock(const Arg1TensorBlock& arg1_block,\n                         const Arg2TensorBlock& arg2_block,\n                         const Arg3TensorBlock& arg3_block,\n                         const BlockFactory& factory)\n      : m_arg1_block(arg1_block),\n        m_arg2_block(arg2_block),\n        m_arg3_block(arg3_block),\n        m_factory(factory) {}\n\n  TensorBlockKind kind() const { return internal::TensorBlockKind::kExpr; }\n  XprType expr() const {\n    return m_factory.expr(m_arg1_block.expr(), m_arg2_block.expr(),\n                          m_arg3_block.expr());\n  }\n  const Scalar* data() const { return NULL; }\n  void cleanup() {\n    m_arg1_block.cleanup();\n    m_arg2_block.cleanup();\n    m_arg3_block.cleanup();\n  }\n\n private:\n  Arg1TensorBlock m_arg1_block;\n  Arg2TensorBlock m_arg2_block;\n  Arg3TensorBlock m_arg3_block;\n  BlockFactory m_factory;\n};\n\n// -------------------------------------------------------------------------- //\n// StridedLinearBufferCopy provides a method to copy data between two linear\n// buffers with different strides, with optimized paths for scatter/gather.\n\ntemplate <typename Scalar, typename IndexType>\nclass StridedLinearBufferCopy {\n  typedef typename packet_traits<Scalar>::type Packet;\n  enum {\n    Vectorizable = packet_traits<Scalar>::Vectorizable,\n    PacketSize = packet_traits<Scalar>::size\n  };\n\n public:\n  // Specifying linear copy kind statically gives ~30% speedup for small sizes.\n  enum class Kind {\n    Linear = 0,       // src_stride == 1 && dst_stride == 1\n    Scatter = 1,      // src_stride == 1 && dst_stride != 1\n    FillLinear = 2,   // src_stride == 0 && dst_stride == 1\n    FillScatter = 3,  // src_stride == 0 && dst_stride != 1\n    Gather = 4,       // dst_stride == 1\n    Random = 5        // everything else\n  };\n\n  struct Dst {\n    Dst(IndexType o, IndexType s, Scalar* d) : offset(o), stride(s), data(d) {}\n\n    IndexType offset;\n    IndexType stride;\n    Scalar* data;\n  };\n\n  struct Src {\n    Src(IndexType o, IndexType s, const Scalar* d)\n        : offset(o), stride(s), data(d) {}\n\n    IndexType offset;\n    IndexType stride;\n    const Scalar* data;\n  };\n\n  template <typename StridedLinearBufferCopy::Kind kind>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void Run(const Dst& dst,\n                                                        const Src& src,\n                                                        const size_t count) {\n    Run<kind>(count, dst.offset, dst.stride, dst.data, src.offset, src.stride,\n              src.data);\n  }\n\n private:\n  template <typename StridedLinearBufferCopy::Kind kind>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void Run(\n      const IndexType count, const IndexType dst_offset,\n      const IndexType dst_stride, Scalar* EIGEN_RESTRICT dst_data,\n      const IndexType src_offset, const IndexType src_stride,\n      const Scalar* EIGEN_RESTRICT src_data) {\n    const Scalar* src = &src_data[src_offset];\n    Scalar* dst = &dst_data[dst_offset];\n\n    if (!Vectorizable) {\n      for (Index i = 0; i < count; ++i) {\n        dst[i * dst_stride] = src[i * src_stride];\n      }\n      return;\n    }\n\n    const IndexType vectorized_size = count - PacketSize;\n    IndexType i = 0;\n\n    if (kind == StridedLinearBufferCopy::Kind::Linear) {\n      // ******************************************************************** //\n      // Linear copy from `src` to `dst`.\n      const IndexType unrolled_size = count - 4 * PacketSize;\n      eigen_assert(src_stride == 1 && dst_stride == 1);\n      for (; i <= unrolled_size; i += 4 * PacketSize) {\n        for (int j = 0; j < 4; ++j) {\n          Packet p = ploadu<Packet>(src + i + j * PacketSize);\n          pstoreu<Scalar, Packet>(dst + i + j * PacketSize, p);\n        }\n      }\n      for (; i <= vectorized_size; i += PacketSize) {\n        Packet p = ploadu<Packet>(src + i);\n        pstoreu<Scalar, Packet>(dst + i, p);\n      }\n      for (; i < count; ++i) {\n        dst[i] = src[i];\n      }\n      // ******************************************************************** //\n    } else if (kind == StridedLinearBufferCopy::Kind::Scatter) {\n      // Scatter from `src` to `dst`.\n      eigen_assert(src_stride == 1 && dst_stride != 1);\n      for (; i <= vectorized_size; i += PacketSize) {\n        Packet p = ploadu<Packet>(src + i);\n        pscatter<Scalar, Packet>(dst + i * dst_stride, p, dst_stride);\n      }\n      for (; i < count; ++i) {\n        dst[i * dst_stride] = src[i];\n      }\n      // ******************************************************************** //\n    } else if (kind == StridedLinearBufferCopy::Kind::FillLinear) {\n      // Fill `dst` with value at `*src`.\n      eigen_assert(src_stride == 0 && dst_stride == 1);\n      const IndexType unrolled_size = count - 4 * PacketSize;\n      Packet p = pload1<Packet>(src);\n      for (; i <= unrolled_size; i += 4 * PacketSize) {\n        for (int j = 0; j < 4; ++j) {\n          pstoreu<Scalar, Packet>(dst + i + j * PacketSize, p);\n        }\n      }\n      for (; i <= vectorized_size; i += PacketSize) {\n        pstoreu<Scalar, Packet>(dst + i, p);\n      }\n      for (; i < count; ++i) {\n        dst[i] = *src;\n      }\n      // ******************************************************************** //\n    } else if (kind == StridedLinearBufferCopy::Kind::FillScatter) {\n      // Scatter `*src` into `dst`.\n      eigen_assert(src_stride == 0 && dst_stride != 1);\n      Packet p = pload1<Packet>(src);\n      for (; i <= vectorized_size; i += PacketSize) {\n        pscatter<Scalar, Packet>(dst + i * dst_stride, p, dst_stride);\n      }\n      for (; i < count; ++i) {\n        dst[i * dst_stride] = *src;\n      }\n      // ******************************************************************** //\n    } else if (kind == StridedLinearBufferCopy::Kind::Gather) {\n      // Gather from `src` into `dst`.\n      eigen_assert(dst_stride == 1);\n      for (; i <= vectorized_size; i += PacketSize) {\n        Packet p = pgather<Scalar, Packet>(src + i * src_stride, src_stride);\n        pstoreu<Scalar, Packet>(dst + i, p);\n      }\n      for (; i < count; ++i) {\n        dst[i] = src[i * src_stride];\n      }\n      // ******************************************************************** //\n    } else if (kind == StridedLinearBufferCopy::Kind::Random) {\n      // Random.\n      for (; i < count; ++i) {\n        dst[i * dst_stride] = src[i * src_stride];\n      }\n    } else {\n      eigen_assert(false);\n    }\n  }\n};\n\n// -------------------------------------------------------------------------- //\n// TensorBlockIO copies data from `src` tensor block, to the `dst` tensor block.\n// It's possible to specify src->dst dimension mapping for the copy operation.\n// Dimensions of `dst` specify how many elements have to be copied, for the\n// `src` we need to know only stride to navigate through source memory buffer.\n\ntemplate <typename Scalar, typename IndexType, int NumDims, int Layout>\nclass TensorBlockIO {\n  static const bool IsColMajor = (Layout == ColMajor);\n\n  typedef StridedLinearBufferCopy<Scalar, IndexType> LinCopy;\n\n public:\n  typedef DSizes<IndexType, NumDims> Dimensions;\n  typedef DSizes<int, NumDims> DimensionsMap;\n\n  struct Dst {\n    Dst(const Dimensions& dst_dims, const Dimensions& dst_strides, Scalar* dst,\n        IndexType dst_offset = 0)\n        : dims(dst_dims), strides(dst_strides), data(dst), offset(dst_offset) {}\n\n    Dimensions dims;\n    Dimensions strides;\n    Scalar* data;\n    IndexType offset;\n  };\n\n  struct Src {\n    Src(const Dimensions& src_strides, const Scalar* src,\n        IndexType src_offset = 0)\n        : strides(src_strides), data(src), offset(src_offset) {}\n\n    Dimensions strides;\n    const Scalar* data;\n    IndexType offset;\n  };\n\n  // Copies data to `dst` from `src`, using provided dimensions mapping:\n  //\n  //   src_dimension_index = dst_to_src_dim_map[dst_dimension_index]\n  //\n  // Returns the number of copied elements.\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE IndexType Copy(\n      const Dst& dst, const Src& src, const DimensionsMap& dst_to_src_dim_map) {\n    // Copy single scalar value from `src` to `dst`.\n    if (NumDims == 0) {\n      *(dst.data + dst.offset) = *(src.data + src.offset);\n      return 1;\n    }\n\n    // Both `dst` and `src` must have contiguous innermost dimension. We also\n    // accept the special case with stride '0', because it's used as a trick to\n    // implement broadcasting.\n    {\n      int inner_dim = IsColMajor ? 0 : NumDims - 1;\n      EIGEN_UNUSED_VARIABLE(inner_dim);\n      eigen_assert(dst.strides[inner_dim] == 1 || dst.strides[inner_dim] == 0);\n      eigen_assert(src.strides[inner_dim] == 1 || src.strides[inner_dim] == 0);\n    }\n\n    // Give a shorter name to `dst_to_src_dim_map`.\n    const DimensionsMap& dim_map = dst_to_src_dim_map;\n\n    // Do not squeeze reordered inner dimensions.\n    int num_squeezable_dims = NumSqueezableInnerDims(dim_map);\n\n    // NOTE: We find the innermost dimension (contiguous in memory) in the dst\n    // block, and we write data linearly into that dimension, reading it from\n    // the src. If dimensions are reordered, we might end up reading data from\n    // the src with `stride != 1`.\n    //\n    // NOTE: Random-Read/Linear-Write can be up to ~2X faster than\n    // Linear-Read/Random-Write: https://stackoverflow.com/a/54935680\n\n    // Find the innermost dimension in the dst whose size is not 1. This is the\n    // effective inner dim.\n    int num_size_one_inner_dims = 0;\n    for (int i = 0; i < num_squeezable_dims; ++i) {\n      const int dst_dim = IsColMajor ? i : NumDims - i - 1;\n      if (dst.dims[dst_dim] != 1) break;\n      num_size_one_inner_dims++;\n    }\n\n    // If all dimensions are of size 1, just copy a scalar from `src` to `dst`.\n    if (num_size_one_inner_dims == NumDims) {\n      *(dst.data + dst.offset) = *(src.data + src.offset);\n      return 1;\n    }\n\n    // Outermost dimension in the dst with `stride == 1` (contiguous in memory).\n    const int dst_stride1_dim = IsColMajor\n                                    ? num_size_one_inner_dims\n                                    : NumDims - num_size_one_inner_dims - 1;\n\n    // Dimension in the src that corresponds to the dst innermost dimension.\n    const int src_dim_for_dst_stride1_dim =\n        NumDims == 0 ? 1 : dim_map[dst_stride1_dim];\n\n    // Size of the innermost dimension (length of contiguous blocks of memory).\n    IndexType dst_inner_dim_size = NumDims == 0 ? 1 : dst.dims[dst_stride1_dim];\n\n    // Squeeze multiple inner dims into one if they are contiguous in `dst` and\n    // `src` memory, so we can do less linear copy calls.\n    for (int i = num_size_one_inner_dims + 1; i < num_squeezable_dims; ++i) {\n      const int dst_dim = IsColMajor ? i : NumDims - i - 1;\n      const IndexType dst_stride = dst.strides[dst_dim];\n      const IndexType src_stride = src.strides[dim_map[dst_dim]];\n      if (dst_inner_dim_size == dst_stride && dst_stride == src_stride) {\n        dst_inner_dim_size *= dst.dims[dst_dim];\n        ++num_size_one_inner_dims;\n      } else {\n        break;\n      }\n    }\n\n    // Setup strides to read data from `src` and write to `dst`.\n    IndexType input_offset = src.offset;\n    IndexType output_offset = dst.offset;\n    IndexType input_stride =\n        NumDims == 0 ? 1 : src.strides[src_dim_for_dst_stride1_dim];\n    IndexType output_stride = NumDims == 0 ? 1 : dst.strides[dst_stride1_dim];\n\n    const int at_least_1_dim = NumDims <= 1 ? 1 : NumDims - 1;\n    array<BlockIteratorState, at_least_1_dim> it;\n\n    // Initialize block iterator state. Squeeze away any dimension of size 1.\n    int idx = 0;  // currently initialized iterator state index\n    for (int i = num_size_one_inner_dims; i < NumDims - 1; ++i) {\n      const int dst_dim = IsColMajor ? i + 1 : NumDims - i - 2;\n      if (dst.dims[dst_dim] == 1) continue;\n\n      it[idx].size = dst.dims[dst_dim];\n      it[idx].input_stride = src.strides[dim_map[dst_dim]];\n      it[idx].output_stride = dst.strides[dst_dim];\n\n      it[idx].input_span = it[idx].input_stride * (it[idx].size - 1);\n      it[idx].output_span = it[idx].output_stride * (it[idx].size - 1);\n\n      idx++;\n    }\n\n    // Iterate copying data from src to dst.\n    const IndexType block_total_size = NumDims == 0 ? 1 : dst.dims.TotalSize();\n\n#define COPY_INNER_DIM(KIND)                                           \\\n  IndexType num_copied = 0;                                            \\\n  for (num_copied = 0; num_copied < block_total_size;                  \\\n       num_copied += dst_inner_dim_size) {                             \\\n    LinCopy::template Run<KIND>(                                       \\\n        typename LinCopy::Dst(output_offset, output_stride, dst.data), \\\n        typename LinCopy::Src(input_offset, input_stride, src.data),   \\\n        dst_inner_dim_size);                                           \\\n                                                                       \\\n    for (int j = 0; j < idx; ++j) {                                    \\\n      if (++it[j].count < it[j].size) {                                \\\n        input_offset += it[j].input_stride;                            \\\n        output_offset += it[j].output_stride;                          \\\n        break;                                                         \\\n      }                                                                \\\n      it[j].count = 0;                                                 \\\n      input_offset -= it[j].input_span;                                \\\n      output_offset -= it[j].output_span;                              \\\n    }                                                                  \\\n  }                                                                    \\\n  return num_copied;\n\n    if (input_stride == 1 && output_stride == 1) {\n      COPY_INNER_DIM(LinCopy::Kind::Linear);\n    } else if (input_stride == 1 && output_stride != 1) {\n      COPY_INNER_DIM(LinCopy::Kind::Scatter);\n    } else if (input_stride == 0 && output_stride == 1) {\n      COPY_INNER_DIM(LinCopy::Kind::FillLinear);\n    } else if (input_stride == 0 && output_stride != 1) {\n      COPY_INNER_DIM(LinCopy::Kind::FillScatter);\n    } else if (output_stride == 1) {\n      COPY_INNER_DIM(LinCopy::Kind::Gather);\n    } else {\n      COPY_INNER_DIM(LinCopy::Kind::Random);\n    }\n\n#undef COPY_INNER_DIM\n  }\n\n  // Copy from `src` to `dst` with an identity src->dst dimension map. Returns\n  // the number of copied elements.\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE IndexType Copy(const Dst& dst,\n                                                              const Src& src) {\n    DimensionsMap dst_to_src_map;\n    for (int i = 0; i < NumDims; ++i) dst_to_src_map[i] = i;\n    return Copy(dst, src, dst_to_src_map);\n  }\n\n private:\n  struct BlockIteratorState {\n    BlockIteratorState()\n        : size(0),\n          count(0),\n          input_stride(0),\n          output_stride(0),\n          input_span(0),\n          output_span(0) {}\n\n    IndexType size;\n    IndexType count;\n    IndexType input_stride;\n    IndexType output_stride;\n    IndexType input_span;\n    IndexType output_span;\n  };\n\n  // Compute how many inner dimensions it's allowed to squeeze when doing IO\n  // between two tensor blocks. It's safe to squeeze inner dimensions, only\n  // if they are not reordered.\n  static int NumSqueezableInnerDims(const DimensionsMap& dim_map) {\n    int num_squeezable_dims = 0;\n    for (int i = 0; i < NumDims; ++i) {\n      const int dim = IsColMajor ? i : NumDims - i - 1;\n      if (dim_map[dim] != dim) break;\n      num_squeezable_dims++;\n    }\n    return num_squeezable_dims;\n  }\n};\n\n// -------------------------------------------------------------------------- //\n// TensorBlockAssignment assigns a block expression of type `TensorBlockExpr` to\n// a Tensor block defined by `desc`, backed by a memory buffer at `target`.\n//\n// Currently there is no way to write from a Tensor expression to a block of\n// memory, if dimensions are reordered. If you need to do that, you should\n// materialize a Tensor block expression into a memory buffer, and then use\n// TensorBlockIO to copy data between two memory buffers with a custom\n// `target->src` dimension map (see definition above).\n//\n// Also currently the innermost dimension of `target` must have a stride '1'\n// (contiguous in memory). This restriction could be lifted with a `pscatter`,\n// but in practice it's never needed, and there is a similar TensorBlockIO\n// workaround for that.\n//\n// TODO(ezhulenev): TensorBlockAssignment is a special case of TensorBlockIO\n// where `src` is a tensor expression. Explore if it is possible to rewrite IO\n// to use expressions instead of pointers, and after that TensorBlockAssignment\n// will become an alias to IO.\ntemplate <typename Scalar, int NumDims, typename TensorBlockExpr,\n          typename IndexType = Eigen::Index>\nclass TensorBlockAssignment {\n  // We will use coeff/packet path to evaluate block expressions.\n  typedef TensorEvaluator<const TensorBlockExpr, DefaultDevice>\n      TensorBlockEvaluator;\n\n  typedef DSizes<IndexType, NumDims> Dimensions;\n\n  enum {\n    Vectorizable = packet_traits<Scalar>::Vectorizable,\n    PacketSize = packet_traits<Scalar>::size\n  };\n\n  template <bool Vectorizable, typename Evaluator>\n  struct InnerDimAssign {\n    EIGEN_ALWAYS_INLINE static void Run(Scalar* target, IndexType count,\n                                        const Evaluator& eval,\n                                        IndexType eval_offset) {\n      for (IndexType i = 0; i < count; ++i) {\n        target[i] = eval.coeff(eval_offset + i);\n      }\n    }\n  };\n\n  template <typename Evaluator>\n  struct InnerDimAssign<true, Evaluator> {\n    EIGEN_ALWAYS_INLINE static void Run(Scalar* target, IndexType count,\n                                        const Evaluator& eval,\n                                        IndexType eval_offset) {\n      typedef typename packet_traits<Scalar>::type Packet;\n\n      const IndexType unrolled_size = count - 4 * PacketSize;\n      const IndexType vectorized_size = count - PacketSize;\n      IndexType i = 0;\n\n      for (; i <= unrolled_size; i += 4 * PacketSize) {\n        for (int j = 0; j < 4; ++j) {\n          const IndexType idx = eval_offset + i + j * PacketSize;\n          Packet p = eval.template packet<Unaligned>(idx);\n          pstoreu<Scalar>(target + i + j * PacketSize, p);\n        }\n      }\n\n      for (; i <= vectorized_size; i += PacketSize) {\n        Packet p = eval.template packet<Unaligned>(eval_offset + i);\n        pstoreu<Scalar>(target + i, p);\n      }\n\n      for (; i < count; ++i) {\n        target[i] = eval.coeff(eval_offset + i);\n      }\n    }\n  };\n\n public:\n  struct Target {\n    Target(const Dimensions& target_dims, const Dimensions& target_strides,\n           Scalar* target_data, IndexType target_offset = 0)\n        : dims(target_dims),\n          strides(target_strides),\n          data(target_data),\n          offset(target_offset) {}\n\n    Dimensions dims;\n    Dimensions strides;\n    Scalar* data;\n    IndexType offset;\n  };\n\n  static Target target(const Dimensions& target_dims,\n                       const Dimensions& target_strides, Scalar* target_data,\n                       IndexType target_offset = 0) {\n    return Target(target_dims, target_strides, target_data, target_offset);\n  }\n\n  template <typename TargetDimsIndexType, typename TargetStridesIndexType>\n  static Target target(\n      const DSizes<TargetDimsIndexType, NumDims>& target_dims,\n      const DSizes<TargetStridesIndexType, NumDims>& target_strides,\n      Scalar* target_data, IndexType target_offset = 0) {\n    // DSizes constructor will do index type promotion if it's safe.\n    return Target(Dimensions(target_dims), Dimensions(target_strides),\n                  target_data, target_offset);\n  }\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void Run(\n      const Target& target, const TensorBlockExpr& expr) {\n    // Prepare evaluator for block expression.\n    DefaultDevice default_device;\n    TensorBlockEvaluator eval(expr, default_device);\n\n    // Tensor block expression dimension should match destination dimensions.\n    eigen_assert(dimensions_match(target.dims, eval.dimensions()));\n\n    static const int Layout = TensorBlockEvaluator::Layout;\n    static const bool is_col_major = Layout == ColMajor;\n\n    // Initialize output inner dimension size based on a layout.\n    const IndexType output_size = NumDims == 0 ? 1 : target.dims.TotalSize();\n    const int inner_dim_idx = is_col_major ? 0 : NumDims - 1;\n    IndexType output_inner_dim_size = target.dims[inner_dim_idx];\n\n    // Target inner dimension stride must be '1'.\n    eigen_assert(target.strides[inner_dim_idx] == 1);\n\n    // Squeeze multiple inner dims into one if they are contiguous in `target`.\n    IndexType num_squeezed_dims = 0;\n    for (Index i = 1; i < NumDims; ++i) {\n      const Index dim = is_col_major ? i : NumDims - i - 1;\n      const IndexType target_stride = target.strides[dim];\n\n      if (output_inner_dim_size == target_stride) {\n        output_inner_dim_size *= target.dims[dim];\n        num_squeezed_dims++;\n      } else {\n        break;\n      }\n    }\n\n    // Initialize output block iterator state. Dimension in this array are\n    // always in inner_most -> outer_most order (col major layout).\n    array<BlockIteratorState, NumDims> it;\n\n    int idx = 0;  // currently initialized iterator state index\n    for (Index i = num_squeezed_dims; i < NumDims - 1; ++i) {\n      const Index dim = is_col_major ? i + 1 : NumDims - i - 2;\n\n      it[idx].count = 0;\n      it[idx].size = target.dims[dim];\n      it[idx].output_stride = target.strides[dim];\n      it[idx].output_span = it[idx].output_stride * (it[idx].size - 1);\n      idx++;\n    }\n\n    // We read block expression from the beginning, and start writing data to\n    // `target` at given offset.\n    IndexType input_offset = 0;\n    IndexType output_offset = target.offset;\n\n    // Iterate copying data from `eval` to `target`.\n    for (IndexType i = 0; i < output_size; i += output_inner_dim_size) {\n      // Assign to `target` at current offset.\n      InnerDimAssign<Vectorizable && TensorBlockEvaluator::PacketAccess,\n                     TensorBlockEvaluator>::Run(target.data + output_offset,\n                                                output_inner_dim_size, eval,\n                                                input_offset);\n\n      // Move input offset forward by the number of assigned coefficients.\n      input_offset += output_inner_dim_size;\n\n      // Update index.\n      for (int j = 0; j < idx; ++j) {\n        if (++it[j].count < it[j].size) {\n          output_offset += it[j].output_stride;\n          break;\n        }\n        it[j].count = 0;\n        output_offset -= it[j].output_span;\n      }\n    }\n  }\n\n private:\n  struct BlockIteratorState {\n    BlockIteratorState()\n        : count(0), size(0), output_stride(0), output_span(0) {}\n\n    IndexType count;\n    IndexType size;\n    IndexType output_stride;\n    IndexType output_span;\n  };\n};\n\n// -------------------------------------------------------------------------- //\n\n}  // namespace internal\n}  // namespace Eigen\n\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_BLOCK_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorBroadcasting.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_BROADCASTING_H\n#define EIGEN_CXX11_TENSOR_TENSOR_BROADCASTING_H\n\nnamespace Eigen {\n\n/** \\class TensorBroadcasting\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor broadcasting class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename Broadcast, typename XprType>\nstruct traits<TensorBroadcastingOp<Broadcast, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename Broadcast, typename XprType>\nstruct eval<TensorBroadcastingOp<Broadcast, XprType>, Eigen::Dense>\n{\n  typedef const TensorBroadcastingOp<Broadcast, XprType> EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename Broadcast, typename XprType>\nstruct nested<TensorBroadcastingOp<Broadcast, XprType>, 1, typename eval<TensorBroadcastingOp<Broadcast, XprType> >::type>\n{\n  typedef TensorBroadcastingOp<Broadcast, XprType> type;\n};\n\ntemplate <typename Dims>\nstruct is_input_scalar {\n  static const bool value = false;\n};\ntemplate <>\nstruct is_input_scalar<Sizes<> > {\n  static const bool value = true;\n};\n#ifndef EIGEN_EMULATE_CXX11_META_H\ntemplate <typename std::ptrdiff_t... Indices>\nstruct is_input_scalar<Sizes<Indices...> > {\n  static const bool value = (Sizes<Indices...>::total_size == 1);\n};\n#endif\n\n}  // end namespace internal\n\n\n\ntemplate<typename Broadcast, typename XprType>\nclass TensorBroadcastingOp : public TensorBase<TensorBroadcastingOp<Broadcast, XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorBroadcastingOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorBroadcastingOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorBroadcastingOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorBroadcastingOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBroadcastingOp(const XprType& expr, const Broadcast& broadcast)\n      : m_xpr(expr), m_broadcast(broadcast) {}\n\n    EIGEN_DEVICE_FUNC\n    const Broadcast& broadcast() const { return m_broadcast; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const Broadcast m_broadcast;\n};\n\n\n// Eval as rvalue\ntemplate<typename Broadcast, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorBroadcastingOp<Broadcast, ArgType>, Device>\n{\n  typedef TensorBroadcastingOp<Broadcast, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename TensorEvaluator<ArgType, Device>::Dimensions InputDimensions;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  protected: //  all the non-static fields must have the same access control, otherwise the TensorEvaluator wont be standard layout;\n  bool isCopy, nByOne, oneByN;\n  public:\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned         = TensorEvaluator<ArgType, Device>::IsAligned,\n    PacketAccess      = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess       = TensorEvaluator<ArgType, Device>::BlockAccess,\n    PreferBlockAccess = true,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    RawAccess         = false\n  };\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  // We do block based broadcasting using a trick with 2x tensor rank and 0\n  // strides. See block method implementation for details.\n  typedef DSizes<Index, 2 * NumDims> BroadcastDimensions;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename TensorEvaluator<const ArgType, Device>::TensorBlock\n      ArgTensorBlock;\n\n  typedef typename internal::TensorMaterializedBlock<ScalarNoConst, NumDims,\n                                                     Layout, Index>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op,\n                                                        const Device& device)\n      : isCopy(false), nByOne(false), oneByN(false),\n        m_device(device), m_broadcast(op.broadcast()), m_impl(op.expression(), device)\n  {\n\n    // The broadcasting op doesn't change the rank of the tensor. One can't broadcast a scalar\n    // and store the result in a scalar. Instead one should reshape the scalar into a a N-D\n    // tensor with N >= 1 of 1 element first and then broadcast.\n    EIGEN_STATIC_ASSERT((NumDims > 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    const InputDimensions& input_dims = m_impl.dimensions();\n    isCopy = true;\n    for (int i = 0; i < NumDims; ++i) {\n      eigen_assert(input_dims[i] > 0);\n      m_dimensions[i] = input_dims[i] * m_broadcast[i];\n      if (m_broadcast[i] != 1) {\n        isCopy = false;\n      }\n    }\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_inputStrides[0] = 1;\n      m_outputStrides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1];\n        m_outputStrides[i] = m_outputStrides[i-1] * m_dimensions[i-1];\n      }\n    } else {\n      m_inputStrides[NumDims-1] = 1;\n      m_outputStrides[NumDims-1] = 1;\n      for (int i = NumDims-2; i >= 0; --i) {\n        m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1];\n        m_outputStrides[i] = m_outputStrides[i+1] * m_dimensions[i+1];\n      }\n    }\n\n    if (input_dims[0] == 1) {\n      oneByN = true;\n      for (int i = 1; i < NumDims; ++i) {\n        if (m_broadcast[i] != 1) {\n          oneByN = false;\n          break;\n        }\n      }\n    } else if (input_dims[NumDims-1] == 1) {\n      nByOne = true;\n      for (int i = 0; i < NumDims-1; ++i) {\n        if (m_broadcast[i] != 1) {\n          nByOne = false;\n          break;\n        }\n      }\n    }\n\n    // Handle special format like NCHW, its input shape is '[1, N..., 1]' and\n    // broadcast shape is '[N, 1..., N]'\n    if (!oneByN && !nByOne) {\n      if (input_dims[0] == 1 && input_dims[NumDims-1] == 1 && NumDims > 2) {\n        nByOne = true;\n        oneByN = true;\n        for (int i = 1; i < NumDims-1; ++i) {\n          if (m_broadcast[i] != 1) {\n            nByOne = false;\n            oneByN = false;\n            break;\n          }\n        }\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    m_impl.evalSubExprsIfNeededAsync(nullptr, [done](bool) { done(true); });\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE CoeffReturnType coeff(Index index) const\n  {\n    if (internal::is_input_scalar<typename internal::remove_all<InputDimensions>::type>::value) {\n      return m_impl.coeff(0);\n    }\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      if (isCopy) {\n        return m_impl.coeff(index);\n      } else {\n        return coeffColMajor(index);\n      }\n    } else {\n      if (isCopy) {\n        return m_impl.coeff(index);\n      } else {\n        return coeffRowMajor(index);\n      }\n    }\n  }\n\n  // TODO: attempt to speed this up. The integer divisions and modulo are slow\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index indexColMajor(Index index) const {\n    Index inputIndex = 0;\n    EIGEN_UNROLL_LOOP\n    for (int i = NumDims - 1; i > 0; --i) {\n      const Index idx = index / m_outputStrides[i];\n      if (internal::index_statically_eq<Broadcast>(i, 1)) {\n        eigen_assert(idx < m_impl.dimensions()[i]);\n        inputIndex += idx * m_inputStrides[i];\n      } else {\n        if (internal::index_statically_eq<InputDimensions>(i, 1)) {\n          eigen_assert(idx % m_impl.dimensions()[i] == 0);\n        } else {\n          inputIndex += (idx % m_impl.dimensions()[i]) * m_inputStrides[i];\n        }\n      }\n      index -= idx * m_outputStrides[i];\n    }\n    if (internal::index_statically_eq<Broadcast>(0, 1)) {\n      eigen_assert(index < m_impl.dimensions()[0]);\n      inputIndex += index;\n    } else {\n      if (internal::index_statically_eq<InputDimensions>(0, 1)) {\n        eigen_assert(index % m_impl.dimensions()[0] == 0);\n      } else {\n        inputIndex += (index % m_impl.dimensions()[0]);\n      }\n    }\n    return inputIndex;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeffColMajor(Index index) const\n  {\n    return m_impl.coeff(indexColMajor(index));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index indexRowMajor(Index index) const {\n    Index inputIndex = 0;\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < NumDims - 1; ++i) {\n      const Index idx = index / m_outputStrides[i];\n      if (internal::index_statically_eq<Broadcast>(i, 1)) {\n        eigen_assert(idx < m_impl.dimensions()[i]);\n        inputIndex += idx * m_inputStrides[i];\n      } else {\n        if (internal::index_statically_eq<InputDimensions>(i, 1)) {\n          eigen_assert(idx % m_impl.dimensions()[i] == 0);\n        } else {\n          inputIndex += (idx % m_impl.dimensions()[i]) * m_inputStrides[i];\n        }\n      }\n      index -= idx * m_outputStrides[i];\n    }\n    if (internal::index_statically_eq<Broadcast>(NumDims - 1, 1)) {\n      eigen_assert(index < m_impl.dimensions()[NumDims - 1]);\n      inputIndex += index;\n    } else {\n      if (internal::index_statically_eq<InputDimensions>(NumDims - 1, 1)) {\n        eigen_assert(index % m_impl.dimensions()[NumDims - 1] == 0);\n      } else {\n        inputIndex += (index % m_impl.dimensions()[NumDims - 1]);\n      }\n    }\n    return inputIndex;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeffRowMajor(Index index) const\n  {\n    return m_impl.coeff(indexRowMajor(index));\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketReturnType packet(Index index) const\n  {\n    if (internal::is_input_scalar<typename internal::remove_all<InputDimensions>::type>::value) {\n      return internal::pset1<PacketReturnType>(m_impl.coeff(0));\n    }\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      if (isCopy) {\n        #ifdef EIGEN_GPU_COMPILE_PHASE\n        // See PR 437: on NVIDIA P100 and K20m we observed a x3-4 speed up by enforcing\n        // unaligned loads here. The reason is unclear though.\n        return m_impl.template packet<Unaligned>(index);\n        #else\n        return m_impl.template packet<LoadMode>(index);\n        #endif\n      } else if (oneByN && !nByOne) {\n        return packetNByOne<LoadMode>(index);\n      } else if (!oneByN && nByOne) {\n        return packetOneByN<LoadMode>(index);\n      } else if (oneByN && nByOne) {\n        return packetOneByNByOne<LoadMode>(index);\n      } else {\n        return packetColMajor<LoadMode>(index);\n      }\n    } else {\n      if (isCopy) {\n        #ifdef EIGEN_GPU_COMPILE_PHASE\n        // See above.\n        return m_impl.template packet<Unaligned>(index);\n        #else\n        return m_impl.template packet<LoadMode>(index);\n        #endif\n      } else if (oneByN && !nByOne) {\n        return packetOneByN<LoadMode>(index);\n      } else if (!oneByN && nByOne) {\n        return packetNByOne<LoadMode>(index);\n      } else if (oneByN && nByOne) {\n        return packetOneByNByOne<LoadMode>(index);\n      } else {\n        return packetRowMajor<LoadMode>(index);\n      }\n    }\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetOneByNByOne\n  (Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n    Index startDim, endDim;\n    Index inputIndex, outputOffset, batchedIndex;\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      startDim = NumDims - 1;\n      endDim = 1;\n    } else {\n      startDim = 0;\n      endDim = NumDims - 2;\n    }\n\n    batchedIndex = index % m_outputStrides[startDim];\n    inputIndex   = batchedIndex / m_outputStrides[endDim];\n    outputOffset = batchedIndex % m_outputStrides[endDim];\n\n    if (outputOffset + PacketSize <= m_outputStrides[endDim]) {\n      values[0] = m_impl.coeff(inputIndex);\n      return internal::pload1<PacketReturnType>(values);\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0, cur = 0; i < PacketSize; ++i, ++cur) {\n        if (outputOffset + cur < m_outputStrides[endDim]) {\n          values[i] = m_impl.coeff(inputIndex);\n        } else {\n          ++inputIndex;\n          inputIndex = (inputIndex == m_inputStrides[startDim] ? 0 : inputIndex);\n          values[i] = m_impl.coeff(inputIndex);\n          outputOffset = 0;\n          cur = 0;\n        }\n      }\n      return internal::pload<PacketReturnType>(values);\n    }\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetOneByN(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    Index dim, inputIndex;\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      dim = NumDims - 1;\n    } else {\n      dim = 0;\n    }\n\n    inputIndex = index % m_inputStrides[dim];\n    if (inputIndex + PacketSize <= m_inputStrides[dim]) {\n      return m_impl.template packet<Unaligned>(inputIndex);\n    } else {\n      EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < PacketSize; ++i) {\n        if (inputIndex > m_inputStrides[dim]-1) {\n          inputIndex = 0;\n        }\n        values[i] = m_impl.coeff(inputIndex++);\n      }\n      return internal::pload<PacketReturnType>(values);\n    }\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetNByOne(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n    Index dim, inputIndex, outputOffset;\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      dim = 1;\n    } else {\n      dim = NumDims - 2;\n    }\n\n    inputIndex   = index / m_outputStrides[dim];\n    outputOffset = index % m_outputStrides[dim];\n    if (outputOffset + PacketSize <= m_outputStrides[dim]) {\n      values[0] = m_impl.coeff(inputIndex);\n      return internal::pload1<PacketReturnType>(values);\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0, cur = 0; i < PacketSize; ++i, ++cur) {\n        if (outputOffset + cur < m_outputStrides[dim]) {\n          values[i] = m_impl.coeff(inputIndex);\n        } else {\n          values[i] = m_impl.coeff(++inputIndex);\n          outputOffset = 0;\n          cur = 0;\n        }\n      }\n      return internal::pload<PacketReturnType>(values);\n    }\n  }\n\n  // Ignore the LoadMode and always use unaligned loads since we can't guarantee\n  // the alignment at compile time.\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetColMajor(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    const Index originalIndex = index;\n\n    Index inputIndex = 0;\n    EIGEN_UNROLL_LOOP\n    for (int i = NumDims - 1; i > 0; --i) {\n      const Index idx = index / m_outputStrides[i];\n      if (internal::index_statically_eq<Broadcast>(i, 1)) {\n        eigen_assert(idx < m_impl.dimensions()[i]);\n        inputIndex += idx * m_inputStrides[i];\n      } else {\n        if (internal::index_statically_eq<InputDimensions>(i, 1)) {\n          eigen_assert(idx % m_impl.dimensions()[i] == 0);\n        } else {\n          inputIndex += (idx % m_impl.dimensions()[i]) * m_inputStrides[i];\n        }\n      }\n      index -= idx * m_outputStrides[i];\n    }\n    Index innermostLoc;\n    if (internal::index_statically_eq<Broadcast>(0, 1)) {\n      eigen_assert(index < m_impl.dimensions()[0]);\n      innermostLoc = index;\n    } else {\n      if (internal::index_statically_eq<InputDimensions>(0, 1)) {\n        eigen_assert(index % m_impl.dimensions()[0] == 0);\n        innermostLoc = 0;\n      } else {\n        innermostLoc = index % m_impl.dimensions()[0];\n      }\n    }\n    inputIndex += innermostLoc;\n\n    // Todo: this could be extended to the second dimension if we're not\n    // broadcasting alongside the first dimension, and so on.\n    if (innermostLoc + PacketSize <= m_impl.dimensions()[0]) {\n      return m_impl.template packet<Unaligned>(inputIndex);\n    } else {\n      EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n      values[0] = m_impl.coeff(inputIndex);\n      EIGEN_UNROLL_LOOP\n      for (int i = 1; i < PacketSize; ++i) {\n        if (innermostLoc + i < m_impl.dimensions()[0]) {\n          values[i] = m_impl.coeff(inputIndex+i);\n        } else {\n          values[i] = coeffColMajor(originalIndex+i);\n        }\n      }\n      PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n      return rslt;\n    }\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetRowMajor(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    const Index originalIndex = index;\n\n    Index inputIndex = 0;\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < NumDims - 1; ++i) {\n      const Index idx = index / m_outputStrides[i];\n      if (internal::index_statically_eq<Broadcast>(i, 1)) {\n        eigen_assert(idx < m_impl.dimensions()[i]);\n        inputIndex += idx * m_inputStrides[i];\n      } else {\n        if (internal::index_statically_eq<InputDimensions>(i, 1)) {\n          eigen_assert(idx % m_impl.dimensions()[i] == 0);\n        } else {\n          inputIndex += (idx % m_impl.dimensions()[i]) * m_inputStrides[i];\n        }\n      }\n      index -= idx * m_outputStrides[i];\n    }\n    Index innermostLoc;\n    if (internal::index_statically_eq<Broadcast>(NumDims-1, 1)) {\n      eigen_assert(index < m_impl.dimensions()[NumDims-1]);\n      innermostLoc = index;\n    } else {\n      if (internal::index_statically_eq<InputDimensions>(NumDims-1, 1)) {\n        eigen_assert(index % m_impl.dimensions()[NumDims-1] == 0);\n        innermostLoc = 0;\n      } else {\n        innermostLoc = index % m_impl.dimensions()[NumDims-1];\n      }\n    }\n    inputIndex += innermostLoc;\n\n    // Todo: this could be extended to the second dimension if we're not\n    // broadcasting alongside the first dimension, and so on.\n    if (innermostLoc + PacketSize <= m_impl.dimensions()[NumDims-1]) {\n      return m_impl.template packet<Unaligned>(inputIndex);\n    } else {\n      EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n      values[0] = m_impl.coeff(inputIndex);\n      EIGEN_UNROLL_LOOP\n      for (int i = 1; i < PacketSize; ++i) {\n        if (innermostLoc + i < m_impl.dimensions()[NumDims-1]) {\n          values[i] = m_impl.coeff(inputIndex+i);\n        } else {\n          values[i] = coeffRowMajor(originalIndex+i);\n        }\n      }\n      PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n      return rslt;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    double compute_cost = TensorOpCost::AddCost<Index>();\n    if (!isCopy && NumDims > 0) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i > 0; --i) {\n        compute_cost += TensorOpCost::DivCost<Index>();\n        if (internal::index_statically_eq<Broadcast>(i, 1)) {\n          compute_cost +=\n              TensorOpCost::MulCost<Index>() + TensorOpCost::AddCost<Index>();\n        } else {\n          if (!internal::index_statically_eq<InputDimensions>(i, 1)) {\n            compute_cost += TensorOpCost::MulCost<Index>() +\n                            TensorOpCost::ModCost<Index>() +\n                            TensorOpCost::AddCost<Index>();\n          }\n        }\n        compute_cost +=\n            TensorOpCost::MulCost<Index>() + TensorOpCost::AddCost<Index>();\n      }\n    }\n    return m_impl.costPerCoeff(vectorized) +\n           TensorOpCost(0, 0, compute_cost, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    // TODO(wuke): Targeting L1 size is 30% faster than targeting L{-1} on large\n    // tensors. But this might need further tuning.\n    const size_t target_size = m_device.firstLevelCacheSize();\n    return internal::TensorBlockResourceRequirements::merge(\n        m_impl.getResourceRequirements(),\n        internal::TensorBlockResourceRequirements::skewed<Scalar>(target_size));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    BlockBroadcastingParams params = blockBroadcastingParams(desc);\n\n    if (params.inner_dim_size == 0 || params.bcast_dim_size == 0) {\n      return emptyBlock();\n    }\n\n    // Prepare storage for the materialized broadcasting result.\n    const typename TensorBlock::Storage block_storage =\n        TensorBlock::prepareStorage(desc, scratch);\n    ScalarNoConst* materialized_output = block_storage.data();\n\n    // We potentially will need to materialize input blocks.\n    size_t materialized_input_size = 0;\n    ScalarNoConst* materialized_input = NULL;\n\n    // Initialize block broadcating iterator state for outer dimensions (outer\n    // with regard to bcast dimension). Dimension in this array are always in\n    // inner_most -> outer_most order (col major layout).\n    array<BlockBroadcastingIteratorState, NumDims> it;\n    int idx = 0;\n\n    for (int i = params.inner_dim_count + 1; i < NumDims; ++i) {\n      const Index dim = IsColMajor ? i : NumDims - 1 - i;\n      it[idx].size = params.output_dims[dim];\n      it[idx].count = 0;\n      it[idx].output_stride = m_outputStrides[dim];\n      it[idx].output_span = it[idx].output_stride * (it[idx].size - 1);\n      idx++;\n    }\n\n    // Write output into the beginning of `materialized_output`.\n    Index output_offset = 0;\n\n    // We will fill output block by broadcasting along the bcast dim, and\n    // iterating over outer dimension.\n    const Index output_size = NumDims == 0 ? 1 : params.output_dims.TotalSize();\n\n    for (Index num_output_coeffs = 0; num_output_coeffs < output_size;) {\n      ScalarNoConst* bcast_output = materialized_output + num_output_coeffs;\n      Index bcast_offset = desc.offset() + output_offset;\n\n      // Broadcast along the bcast dimension.\n      num_output_coeffs += BroadcastBlockAlongBcastDim(\n          params, bcast_offset, scratch, bcast_output, &materialized_input,\n          &materialized_input_size);\n\n      // Switch to the next outer dimension.\n      for (int j = 0; j < idx; ++j) {\n        if (++it[j].count < it[j].size) {\n          output_offset += it[j].output_stride;\n          break;\n        }\n        it[j].count = 0;\n        output_offset -= it[j].output_span;\n      }\n    }\n\n    return block_storage.AsTensorMaterializedBlock();\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n  const TensorEvaluator<ArgType, Device>& impl() const { return m_impl; }\n\n  Broadcast functor() const { return m_broadcast; }\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(\n      cl::sycl::handler& cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n private:\n  static const bool IsColMajor =\n      static_cast<int>(Layout) == static_cast<int>(ColMajor);\n\n  // We will build a general case block broadcasting on top of broadcasting\n  // primitive that will do broadcasting only for the inner dimension(s) along\n  // the first dimension smaller than the input size (it's called `bcast_dim`).\n  //\n  // Example:\n  //           dim:  0  1  2   (ColMajor)\n  //    input size: [9, 3, 6]\n  //    block size: [9, 2, 6]\n  //\n  // We will compute broadcasted block by iterating over the outer dimensions\n  // before `bcast_dim` (only dimension `2` in this example) and computing\n  // broadcasts along the `bcast_dim` (dimension `1` in this example).\n\n  // BlockBroadcastingParams holds precomputed parameters for broadcasting a\n  // single block along the broadcasting dimension. Sizes and strides along the\n  // `bcast_dim` might be invalid, they will be adjusted later in\n  // `BroadcastBlockAlongBcastDim`.\n  struct BlockBroadcastingParams {\n    Dimensions input_dims;      // input expression dimensions\n    Dimensions output_dims;     // output block sizes\n    Dimensions output_strides;  // output block strides\n\n    int inner_dim_count;   // count inner dimensions matching in size\n    int bcast_dim;         // broadcasting dimension index\n    Index bcast_dim_size;  // broadcasting dimension size\n    Index inner_dim_size;  // inner dimensions size\n\n    // Block sizes and strides for the input block where all dimensions before\n    // `bcast_dim` are equal to `1`.\n    Dimensions input_block_sizes;\n    Dimensions input_block_strides;\n\n    // Block sizes and strides for blocks with extra dimensions and strides `0`.\n    BroadcastDimensions bcast_block_sizes;\n    BroadcastDimensions bcast_block_strides;\n    BroadcastDimensions bcast_input_strides;\n  };\n\n  struct BlockBroadcastingIteratorState {\n    Index size;\n    Index count;\n    Index output_stride;\n    Index output_span;\n  };\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE BlockBroadcastingParams\n  blockBroadcastingParams(TensorBlockDesc& desc) const {\n    BlockBroadcastingParams params;\n\n    params.input_dims = Dimensions(m_impl.dimensions());\n\n    // Output block sizes and strides.\n    params.output_dims = desc.dimensions();\n    params.output_strides = internal::strides<Layout>(params.output_dims);\n\n    // Find the broadcasting dimension (first dimension with output size smaller\n    // that the input size).\n    params.bcast_dim = 0;\n    params.bcast_dim_size = 1;\n    params.inner_dim_size = 1;\n\n    // Count the number of inner dimensions that have the same size in the block\n    // and in the broadcast expression.\n    params.inner_dim_count = 0;\n\n    for (int i = 0; i < NumDims; ++i) {\n      const int dim = IsColMajor ? i : NumDims - i - 1;\n\n      if (params.output_dims[dim] == m_dimensions[dim]) {\n        params.inner_dim_size *= params.output_dims[dim];\n        ++params.inner_dim_count;\n        continue;\n      }\n\n      // First non-matching dimension is the broadcasting dimension.\n      eigen_assert(params.output_dims[dim] < m_dimensions[dim]);\n      params.bcast_dim = dim;\n      params.bcast_dim_size = params.output_dims[dim];\n      break;\n    }\n\n    // Calculate the input block size for looking into the input.\n    for (int i = 0; i < params.inner_dim_count; ++i) {\n      const int dim = IsColMajor ? i : NumDims - i - 1;\n      params.input_block_sizes[dim] = params.input_dims[dim];\n    }\n    for (int i = params.inner_dim_count; i < NumDims; ++i) {\n      const int dim = IsColMajor ? i : NumDims - i - 1;\n      params.input_block_sizes[dim] = 1;\n    }\n    params.input_block_strides =\n        internal::strides<Layout>(params.input_block_sizes);\n\n    // Broadcast with the 0-stride trick: Create 1 extra dim for each\n    // broadcast, set the input stride to 0.\n    //\n    // When ColMajor:\n    //\n    // - bcast_block_sizes:\n    //   [d_0, b_0, d_1, b_1, ...]\n    //\n    // - bcast_block_strides:\n    //   [output_block_strides[0], output_block_strides[0] * d_0,\n    //    output_block_strides[1], output_block_strides[1] * d_1,\n    //   ...]\n    //\n    // - bcast_input_strides:\n    //   [input_block_strides[0], 0,\n    //    input_block_strides[1], 0,\n    //   ...].\n    //\n    for (int i = 0; i < params.inner_dim_count; ++i) {\n      const int dim = IsColMajor ? i : NumDims - i - 1;\n\n      const int copy_dim = IsColMajor ? 2 * i : 2 * NumDims - 2 * i - 1;\n      const int broadcast_dim = IsColMajor ? copy_dim + 1 : copy_dim - 1;\n\n      params.bcast_block_sizes[copy_dim] = params.input_dims[dim];\n      params.bcast_block_sizes[broadcast_dim] = m_broadcast[dim];\n      params.bcast_block_strides[copy_dim] = params.output_strides[dim];\n      params.bcast_block_strides[broadcast_dim] =\n          params.output_strides[dim] * params.input_dims[dim];\n      params.bcast_input_strides[copy_dim] = params.input_block_strides[dim];\n      params.bcast_input_strides[broadcast_dim] = 0;\n    }\n\n    for (int i = 2 * params.inner_dim_count; i < 2 * NumDims; ++i) {\n      const int dim = IsColMajor ? i : 2 * NumDims - i - 1;\n      params.bcast_block_sizes[dim] = 1;\n      params.bcast_block_strides[dim] = 0;\n      params.bcast_input_strides[dim] = 0;\n    }\n\n    return params;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock emptyBlock() const {\n    DSizes<Index, NumDims> dimensions;\n    for (int i = 0; i < NumDims; ++i) dimensions[i] = 0;\n    return TensorBlock(internal::TensorBlockKind::kView, NULL, dimensions);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index BroadcastBlockAlongBcastDim(\n      BlockBroadcastingParams params, Index bcast_offset,\n      TensorBlockScratch& scratch, ScalarNoConst* materialized_output,\n      ScalarNoConst** materialized_input,\n      size_t* materialized_input_size) const {\n    if (params.bcast_dim_size == 1) {\n      // We just need one block read using the ready-set values above.\n      return BroadcastBlock(\n          params.input_block_sizes, params.input_block_strides,\n          params.bcast_block_sizes, params.bcast_block_strides,\n          params.bcast_input_strides, bcast_offset, 0, scratch,\n          materialized_output, materialized_input, materialized_input_size);\n\n    } else if (params.input_dims[params.bcast_dim] == 1) {\n      // Broadcast bcast dimension (< NumDims) by bcast_dim_size.\n      const int broadcast_bcast_dim =\n          IsColMajor ? 2 * params.inner_dim_count + 1\n                     : 2 * NumDims - 2 * params.inner_dim_count - 2;\n\n      params.bcast_block_sizes[broadcast_bcast_dim] = params.bcast_dim_size;\n      params.bcast_input_strides[broadcast_bcast_dim] = 0;\n      params.bcast_block_strides[broadcast_bcast_dim] =\n          params.output_strides[params.bcast_dim];\n\n      return BroadcastBlock(\n          params.input_block_sizes, params.input_block_strides,\n          params.bcast_block_sizes, params.bcast_block_strides,\n          params.bcast_input_strides, bcast_offset, 0, scratch,\n          materialized_output, materialized_input, materialized_input_size);\n\n    } else {\n      // Keep track of the total number of the coefficients written to the\n      // output block.\n      Index num_output_coeffs = 0;\n\n      // The general case. Let's denote the output block as\n      //\n      //   x[..., a:a+bcast_dim_size, :, ..., :]\n      //\n      // where a:a+bcast_dim_size is a slice on the bcast_dim dimension\n      // (< NumDims). We need to split the a:a+bcast_dim_size into possibly 3\n      // sub-blocks:\n      //\n      // (1) a:b, where b is the smallest multiple of\n      //     input_dims[bcast_dim_start] in [a, a+bcast_dim_size].\n      //\n      // (2) b:c, where c is the largest multiple of input_dims[bcast_dim_start]\n      //     in [a, a+bcast_dim_size].\n      //\n      // (3) c:a+bcast_dim_size .\n      //\n      // Or, when b and c do not exist, we just need to process the whole block\n      // together.\n\n      // Find a.\n      const Index bcast_dim_left_index =\n          bcast_offset / m_outputStrides[params.bcast_dim];\n\n      // Find b and c.\n      const Index input_bcast_dim_size = params.input_dims[params.bcast_dim];\n\n      // First multiple after a. This is b when <= bcast_dim_left_index +\n      // bcast_dim_size.\n      const Index first_multiple =\n          divup<Index>(bcast_dim_left_index, input_bcast_dim_size) *\n          input_bcast_dim_size;\n\n      if (first_multiple <= bcast_dim_left_index + params.bcast_dim_size) {\n        // b exists, so does c. Find it.\n        const Index last_multiple =\n            (bcast_dim_left_index + params.bcast_dim_size) /\n            input_bcast_dim_size * input_bcast_dim_size;\n        const int copy_bcast_dim =\n            IsColMajor ? 2 * params.inner_dim_count\n                       : 2 * NumDims - 2 * params.inner_dim_count - 1;\n        const int broadcast_bcast_dim =\n            IsColMajor ? 2 * params.inner_dim_count + 1\n                       : 2 * NumDims - 2 * params.inner_dim_count - 2;\n\n        if (first_multiple > bcast_dim_left_index) {\n          const Index head_size = first_multiple - bcast_dim_left_index;\n          params.input_block_sizes[params.bcast_dim] = head_size;\n          params.bcast_block_sizes[copy_bcast_dim] = head_size;\n          params.bcast_input_strides[copy_bcast_dim] =\n              params.input_block_strides[params.bcast_dim];\n          params.bcast_block_strides[copy_bcast_dim] =\n              params.output_strides[params.bcast_dim];\n          params.bcast_block_sizes[broadcast_bcast_dim] = 1;\n          params.bcast_input_strides[broadcast_bcast_dim] = 0;\n          params.bcast_block_strides[broadcast_bcast_dim] =\n              params.output_strides[params.bcast_dim] *\n              params.input_dims[params.bcast_dim];\n\n          num_output_coeffs += BroadcastBlock(\n              params.input_block_sizes, params.input_block_strides,\n              params.bcast_block_sizes, params.bcast_block_strides,\n              params.bcast_input_strides, bcast_offset, 0, scratch,\n              materialized_output, materialized_input, materialized_input_size);\n        }\n        if (first_multiple < last_multiple) {\n          params.input_block_sizes[params.bcast_dim] = input_bcast_dim_size;\n          params.bcast_block_sizes[copy_bcast_dim] = input_bcast_dim_size;\n          params.bcast_input_strides[copy_bcast_dim] =\n              params.input_block_strides[params.bcast_dim];\n          params.bcast_block_strides[copy_bcast_dim] =\n              params.output_strides[params.bcast_dim];\n          params.bcast_block_sizes[broadcast_bcast_dim] =\n              (last_multiple - first_multiple) / input_bcast_dim_size;\n          params.bcast_input_strides[broadcast_bcast_dim] = 0;\n          params.bcast_block_strides[broadcast_bcast_dim] =\n              params.output_strides[params.bcast_dim] *\n              params.input_dims[params.bcast_dim];\n          const Index offset = (first_multiple - bcast_dim_left_index) *\n                               m_outputStrides[params.bcast_dim];\n\n          num_output_coeffs += BroadcastBlock(\n              params.input_block_sizes, params.input_block_strides,\n              params.bcast_block_sizes, params.bcast_block_strides,\n              params.bcast_input_strides, bcast_offset, offset, scratch,\n              materialized_output, materialized_input, materialized_input_size);\n        }\n        if (last_multiple < bcast_dim_left_index + params.bcast_dim_size) {\n          const Index tail_size =\n              bcast_dim_left_index + params.bcast_dim_size - last_multiple;\n          params.input_block_sizes[params.bcast_dim] = tail_size;\n          params.bcast_block_sizes[copy_bcast_dim] = tail_size;\n          params.bcast_input_strides[copy_bcast_dim] =\n              params.input_block_strides[params.bcast_dim];\n          params.bcast_block_strides[copy_bcast_dim] =\n              params.output_strides[params.bcast_dim];\n          params.bcast_block_sizes[broadcast_bcast_dim] = 1;\n          params.bcast_input_strides[broadcast_bcast_dim] = 0;\n          params.bcast_block_strides[broadcast_bcast_dim] =\n              params.output_strides[params.bcast_dim] *\n              params.input_dims[params.bcast_dim];\n          const Index offset = (last_multiple - bcast_dim_left_index) *\n                               m_outputStrides[params.bcast_dim];\n\n          num_output_coeffs += BroadcastBlock(\n              params.input_block_sizes, params.input_block_strides,\n              params.bcast_block_sizes, params.bcast_block_strides,\n              params.bcast_input_strides, bcast_offset, offset, scratch,\n              materialized_output, materialized_input, materialized_input_size);\n        }\n      } else {\n        // b and c do not exist.\n        const int copy_bcast_dim =\n            IsColMajor ? 2 * params.inner_dim_count\n                       : 2 * NumDims - 2 * params.inner_dim_count - 1;\n        params.input_block_sizes[params.bcast_dim] = params.bcast_dim_size;\n        params.bcast_block_sizes[copy_bcast_dim] = params.bcast_dim_size;\n        params.bcast_input_strides[copy_bcast_dim] =\n            params.input_block_strides[params.bcast_dim];\n        params.bcast_block_strides[copy_bcast_dim] =\n            params.output_strides[params.bcast_dim];\n\n        num_output_coeffs += BroadcastBlock(\n            params.input_block_sizes, params.input_block_strides,\n            params.bcast_block_sizes, params.bcast_block_strides,\n            params.bcast_input_strides, bcast_offset, 0, scratch,\n            materialized_output, materialized_input, materialized_input_size);\n      }\n\n      return num_output_coeffs;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index BroadcastBlock(\n      const Dimensions& input_block_sizes,\n      const Dimensions& input_block_strides,\n      const BroadcastDimensions& bcast_block_sizes,\n      const BroadcastDimensions& bcast_block_strides,\n      const BroadcastDimensions& bcast_input_strides, Index bcast_offset,\n      Index offset, TensorBlockScratch& scratch,\n      ScalarNoConst* materialized_output, ScalarNoConst** materialized_input,\n      size_t* materialized_input_size) const {\n    // ---------------------------------------------------------------------- //\n    // Tensor block descriptor for reading block from the input.\n    const Index input_offset = bcast_offset + offset;\n    TensorBlockDesc input_desc(\n        IsColMajor ? indexColMajor(input_offset) : indexRowMajor(input_offset),\n        input_block_sizes);\n\n    ArgTensorBlock input_block = m_impl.block(input_desc, scratch);\n\n    // ---------------------------------------------------------------------- //\n    // Materialize input block into a temporary memory buffer only if it's not\n    // already available in the arg block.\n    const ScalarNoConst* input_buffer = NULL;\n\n    if (input_block.data() != NULL) {\n      // Input block already has raw data, there is no need to materialize it.\n      input_buffer = input_block.data();\n\n    } else {\n      // Otherwise we have to do block assignment into a temporary buffer.\n\n      // Maybe reuse previously allocated buffer, or allocate a new one with a\n      // scratch allocator.\n      const size_t input_total_size = input_block_sizes.TotalSize();\n      if (*materialized_input == NULL ||\n          *materialized_input_size < input_total_size) {\n        *materialized_input_size = input_total_size;\n        void* mem = scratch.allocate(*materialized_input_size * sizeof(Scalar));\n        *materialized_input = static_cast<ScalarNoConst*>(mem);\n      }\n\n      typedef internal::TensorBlockAssignment<\n          ScalarNoConst, NumDims, typename ArgTensorBlock::XprType, Index>\n          TensorBlockAssignment;\n\n      TensorBlockAssignment::Run(\n          TensorBlockAssignment::target(input_block_sizes, input_block_strides,\n                                        *materialized_input),\n          input_block.expr());\n\n      input_buffer = *materialized_input;\n    }\n\n    // ---------------------------------------------------------------------- //\n    // Copy data from materialized input block to the materialized output, using\n    // given broadcast strides (strides with zeroes).\n    typedef internal::TensorBlockIO<ScalarNoConst, Index, 2 * NumDims, Layout>\n        TensorBlockIO;\n\n    typename TensorBlockIO::Src src(bcast_input_strides, input_buffer);\n    typename TensorBlockIO::Dst dst(bcast_block_sizes, bcast_block_strides,\n                                      materialized_output + offset);\n\n    return TensorBlockIO::Copy(dst, src);\n  }\n\nprotected:\n  const Device EIGEN_DEVICE_REF m_device;\n  const typename internal::remove_reference<Broadcast>::type m_broadcast;\n  Dimensions m_dimensions;\n  array<Index, NumDims> m_outputStrides;\n  array<Index, NumDims> m_inputStrides;\n  TensorEvaluator<ArgType, Device> m_impl;\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_BROADCASTING_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorChipping.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CHIPPING_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CHIPPING_H\n\nnamespace Eigen {\n\n/** \\class TensorKChippingReshaping\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief A chip is a thin slice, corresponding to a column or a row in a 2-d tensor.\n  *\n  *\n  */\n\nnamespace internal {\ntemplate<DenseIndex DimId, typename XprType>\nstruct traits<TensorChippingOp<DimId, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions - 1;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<DenseIndex DimId, typename XprType>\nstruct eval<TensorChippingOp<DimId, XprType>, Eigen::Dense>\n{\n  typedef const TensorChippingOp<DimId, XprType> EIGEN_DEVICE_REF type;\n};\n\ntemplate<DenseIndex DimId, typename XprType>\nstruct nested<TensorChippingOp<DimId, XprType>, 1, typename eval<TensorChippingOp<DimId, XprType> >::type>\n{\n  typedef TensorChippingOp<DimId, XprType> type;\n};\n\ntemplate <DenseIndex DimId>\nstruct DimensionId\n{\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DimensionId(DenseIndex dim) {\n    EIGEN_UNUSED_VARIABLE(dim);\n    eigen_assert(dim == DimId);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex actualDim() const {\n    return DimId;\n  }\n};\ntemplate <>\nstruct DimensionId<Dynamic>\n{\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DimensionId(DenseIndex dim) : actual_dim(dim) {\n    eigen_assert(dim >= 0);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex actualDim() const {\n    return actual_dim;\n  }\n private:\n  const DenseIndex actual_dim;\n};\n\n\n}  // end namespace internal\n\n\n\ntemplate<DenseIndex DimId, typename XprType>\nclass TensorChippingOp : public TensorBase<TensorChippingOp<DimId, XprType> >\n{\n  public:\n    typedef TensorBase<TensorChippingOp<DimId, XprType> > Base;\n    typedef typename Eigen::internal::traits<TensorChippingOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef typename XprType::CoeffReturnType CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorChippingOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorChippingOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorChippingOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorChippingOp(const XprType& expr, const Index offset, const Index dim)\n        : m_xpr(expr), m_offset(offset), m_dim(dim) {\n    }\n\n    EIGEN_DEVICE_FUNC\n    const Index offset() const { return m_offset; }\n    EIGEN_DEVICE_FUNC\n    const Index dim() const { return m_dim.actualDim(); }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(TensorChippingOp)\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const Index m_offset;\n    const internal::DimensionId<DimId> m_dim;\n};\n\n\n// Eval as rvalue\ntemplate<DenseIndex DimId, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorChippingOp<DimId, ArgType>, Device>\n{\n  typedef TensorChippingOp<DimId, ArgType> XprType;\n  static const int NumInputDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  static const int NumDims = NumInputDims-1;\n  typedef typename XprType::Index Index;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    // Alignment can't be guaranteed at compile time since it depends on the\n    // slice offsets.\n    IsAligned         = false,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    PacketAccess      = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess       = TensorEvaluator<ArgType, Device>::BlockAccess,\n    // Chipping of outer-most dimension is a trivial operation, because we can\n    // read and write directly from the underlying tensor using single offset.\n    IsOuterChipping   = (static_cast<int>(Layout) == ColMajor && DimId == NumInputDims - 1) ||\n                        (static_cast<int>(Layout) == RowMajor && DimId == 0),\n    // Chipping inner-most dimension.\n    IsInnerChipping   = (static_cast<int>(Layout) == ColMajor && DimId == 0) ||\n                        (static_cast<int>(Layout) == RowMajor && DimId == NumInputDims - 1),\n    // Prefer block access if the underlying expression prefers it, otherwise\n    // only if chipping is not trivial.\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess ||\n                        !IsOuterChipping,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = false\n  };\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef internal::TensorBlockDescriptor<NumInputDims, Index>\n      ArgTensorBlockDesc;\n  typedef typename TensorEvaluator<const ArgType, Device>::TensorBlock\n      ArgTensorBlock;\n\n  typedef typename internal::TensorMaterializedBlock<ScalarNoConst, NumDims,\n                                                     Layout, Index>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device), m_dim(op.dim()), m_device(device)\n  {\n    EIGEN_STATIC_ASSERT((NumInputDims >= 1), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    eigen_assert(NumInputDims > m_dim.actualDim());\n\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n    eigen_assert(op.offset() < input_dims[m_dim.actualDim()]);\n\n    int j = 0;\n    for (int i = 0; i < NumInputDims; ++i) {\n      if (i != m_dim.actualDim()) {\n        m_dimensions[j] = input_dims[i];\n        ++j;\n      }\n    }\n\n    m_stride = 1;\n    m_inputStride = 1;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = 0; i < m_dim.actualDim(); ++i) {\n        m_stride *= input_dims[i];\n        m_inputStride *= input_dims[i];\n      }\n    } else {\n      for (int i = NumInputDims-1; i > m_dim.actualDim(); --i) {\n        m_stride *= input_dims[i];\n        m_inputStride *= input_dims[i];\n      }\n    }\n    m_inputStride *= input_dims[m_dim.actualDim()];\n    m_inputOffset = m_stride * op.offset();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    return m_impl.coeff(srcCoeff(index));\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    if (isInnerChipping()) {\n      // m_stride is equal to 1, so let's avoid the integer division.\n      eigen_assert(m_stride == 1);\n      Index inputIndex = index * m_inputStride + m_inputOffset;\n      EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < PacketSize; ++i) {\n        values[i] = m_impl.coeff(inputIndex);\n        inputIndex += m_inputStride;\n      }\n      PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n      return rslt;\n    } else if (isOuterChipping()) {\n      // m_stride is always greater than index, so let's avoid the integer division.\n      eigen_assert(m_stride > index);\n      return m_impl.template packet<LoadMode>(index + m_inputOffset);\n    } else {\n      const Index idx = index / m_stride;\n      const Index rem = index - idx * m_stride;\n      if (rem + PacketSize <= m_stride) {\n        Index inputIndex = idx * m_inputStride + m_inputOffset + rem;\n        return m_impl.template packet<LoadMode>(inputIndex);\n      } else {\n        // Cross the stride boundary. Fallback to slow path.\n        EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n       EIGEN_UNROLL_LOOP\n        for (int i = 0; i < PacketSize; ++i) {\n          values[i] = coeff(index);\n          ++index;\n        }\n        PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n        return rslt;\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    double cost = 0;\n    if ((static_cast<int>(Layout) == static_cast<int>(ColMajor) &&\n         m_dim.actualDim() == 0) ||\n        (static_cast<int>(Layout) == static_cast<int>(RowMajor) &&\n         m_dim.actualDim() == NumInputDims - 1)) {\n      cost += TensorOpCost::MulCost<Index>() + TensorOpCost::AddCost<Index>();\n    } else if ((static_cast<int>(Layout) == static_cast<int>(ColMajor) &&\n                m_dim.actualDim() == NumInputDims - 1) ||\n               (static_cast<int>(Layout) == static_cast<int>(RowMajor) &&\n                m_dim.actualDim() == 0)) {\n      cost += TensorOpCost::AddCost<Index>();\n    } else {\n      cost += 3 * TensorOpCost::MulCost<Index>() + TensorOpCost::DivCost<Index>() +\n              3 * TensorOpCost::AddCost<Index>();\n    }\n\n    return m_impl.costPerCoeff(vectorized) +\n           TensorOpCost(0, 0, cost, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    const size_t target_size = m_device.lastLevelCacheSize();\n    return internal::TensorBlockResourceRequirements::merge(\n        internal::TensorBlockResourceRequirements::skewed<Scalar>(target_size),\n        m_impl.getResourceRequirements());\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool root_of_expr_ast = false) const {\n    const Index chip_dim = m_dim.actualDim();\n\n    DSizes<Index, NumInputDims> input_block_dims;\n    for (int i = 0; i < NumInputDims; ++i) {\n      input_block_dims[i]\n            = i < chip_dim ? desc.dimension(i)\n            : i > chip_dim ? desc.dimension(i - 1)\n            : 1;\n    }\n\n    ArgTensorBlockDesc arg_desc(srcCoeff(desc.offset()), input_block_dims);\n\n    // Try to reuse destination buffer for materializing argument block.\n    if (desc.HasDestinationBuffer()) {\n      DSizes<Index, NumInputDims> arg_destination_strides;\n      for (int i = 0; i < NumInputDims; ++i) {\n      arg_destination_strides[i]\n            = i < chip_dim ? desc.destination().strides()[i]\n            : i > chip_dim ? desc.destination().strides()[i - 1]\n            : 0; // for dimensions of size `1` stride should never be used.\n      }\n\n      arg_desc.template AddDestinationBuffer<Layout>(\n          desc.destination().template data<ScalarNoConst>(),\n          arg_destination_strides);\n    }\n\n    ArgTensorBlock arg_block = m_impl.block(arg_desc, scratch, root_of_expr_ast);\n    if (!arg_desc.HasDestinationBuffer()) desc.DropDestinationBuffer();\n\n    if (arg_block.data() != NULL) {\n      // Forward argument block buffer if possible.\n      return TensorBlock(arg_block.kind(), arg_block.data(),\n                           desc.dimensions());\n\n    } else {\n      // Assign argument block expression to a buffer.\n\n      // Prepare storage for the materialized chipping result.\n      const typename TensorBlock::Storage block_storage =\n          TensorBlock::prepareStorage(desc, scratch);\n\n      typedef internal::TensorBlockAssignment<\n          ScalarNoConst, NumInputDims, typename ArgTensorBlock::XprType, Index>\n          TensorBlockAssignment;\n\n      TensorBlockAssignment::Run(\n          TensorBlockAssignment::target(\n              arg_desc.dimensions(),\n              internal::strides<Layout>(arg_desc.dimensions()),\n              block_storage.data()),\n          arg_block.expr());\n\n      return block_storage.AsTensorMaterializedBlock();\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Storage::Type data() const {\n    typename Storage::Type result = constCast(m_impl.data());\n    if (isOuterChipping() && result) {\n      return result + m_inputOffset;\n    } else {\n      return NULL;\n    }\n  }\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n\n protected:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index srcCoeff(Index index) const\n  {\n    Index inputIndex;\n    if (isInnerChipping()) {\n      // m_stride is equal to 1, so let's avoid the integer division.\n      eigen_assert(m_stride == 1);\n      inputIndex = index * m_inputStride + m_inputOffset;\n    } else if (isOuterChipping()) {\n      // m_stride is always greater than index, so let's avoid the integer\n      // division.\n      eigen_assert(m_stride > index);\n      inputIndex = index + m_inputOffset;\n    } else {\n      const Index idx = index / m_stride;\n      inputIndex = idx * m_inputStride + m_inputOffset;\n      index -= idx * m_stride;\n      inputIndex += index;\n    }\n    return inputIndex;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool isInnerChipping() const {\n    return IsInnerChipping ||\n           (static_cast<int>(Layout) == ColMajor && m_dim.actualDim() == 0) ||\n           (static_cast<int>(Layout) == RowMajor && m_dim.actualDim() == NumInputDims - 1);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool isOuterChipping() const {\n    return IsOuterChipping ||\n           (static_cast<int>(Layout) == ColMajor && m_dim.actualDim() == NumInputDims-1) ||\n           (static_cast<int>(Layout) == RowMajor && m_dim.actualDim() == 0);\n  }\n\n  Dimensions m_dimensions;\n  Index m_stride;\n  Index m_inputOffset;\n  Index m_inputStride;\n  TensorEvaluator<ArgType, Device> m_impl;\n  const internal::DimensionId<DimId> m_dim;\n  const Device EIGEN_DEVICE_REF m_device;\n};\n\n\n// Eval as lvalue\ntemplate<DenseIndex DimId, typename ArgType, typename Device>\nstruct TensorEvaluator<TensorChippingOp<DimId, ArgType>, Device>\n  : public TensorEvaluator<const TensorChippingOp<DimId, ArgType>, Device>\n{\n  typedef TensorEvaluator<const TensorChippingOp<DimId, ArgType>, Device> Base;\n  typedef TensorChippingOp<DimId, ArgType> XprType;\n  static const int NumInputDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  static const int NumDims = NumInputDims-1;\n  typedef typename XprType::Index Index;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n\n  enum {\n    IsAligned     = false,\n    PacketAccess  = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess   = TensorEvaluator<ArgType, Device>::RawAccess,\n    Layout        = TensorEvaluator<ArgType, Device>::Layout,\n    RawAccess     = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n    : Base(op, device)\n    { }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index)\n  {\n    return this->m_impl.coeffRef(this->srcCoeff(index));\n  }\n\n  template <int StoreMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void writePacket(Index index, const PacketReturnType& x)\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n\n    if (this->isInnerChipping()) {\n      // m_stride is equal to 1, so let's avoid the integer division.\n      eigen_assert(this->m_stride == 1);\n      EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n      internal::pstore<CoeffReturnType, PacketReturnType>(values, x);\n      Index inputIndex = index * this->m_inputStride + this->m_inputOffset;\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < PacketSize; ++i) {\n        this->m_impl.coeffRef(inputIndex) = values[i];\n        inputIndex += this->m_inputStride;\n      }\n    } else if (this->isOuterChipping()) {\n      // m_stride is always greater than index, so let's avoid the integer division.\n      eigen_assert(this->m_stride > index);\n      this->m_impl.template writePacket<StoreMode>(index + this->m_inputOffset, x);\n    } else {\n      const Index idx = index / this->m_stride;\n      const Index rem = index - idx * this->m_stride;\n      if (rem + PacketSize <= this->m_stride) {\n        const Index inputIndex = idx * this->m_inputStride + this->m_inputOffset + rem;\n        this->m_impl.template writePacket<StoreMode>(inputIndex, x);\n      } else {\n        // Cross stride boundary. Fallback to slow path.\n        EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n        internal::pstore<CoeffReturnType, PacketReturnType>(values, x);\n        EIGEN_UNROLL_LOOP\n        for (int i = 0; i < PacketSize; ++i) {\n          this->coeffRef(index) = values[i];\n          ++index;\n        }\n      }\n    }\n  }\n\n  template <typename TensorBlock>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void writeBlock(\n      const TensorBlockDesc& desc, const TensorBlock& block) {\n    assert(this->m_impl.data() != NULL);\n\n    const Index chip_dim = this->m_dim.actualDim();\n\n    DSizes<Index, NumInputDims> input_block_dims;\n    for (int i = 0; i < NumInputDims; ++i) {\n      input_block_dims[i] = i < chip_dim ? desc.dimension(i)\n                          : i > chip_dim ? desc.dimension(i - 1)\n                          : 1;\n    }\n\n    typedef TensorReshapingOp<const DSizes<Index, NumInputDims>,\n                              const typename TensorBlock::XprType>\n        TensorBlockExpr;\n\n    typedef internal::TensorBlockAssignment<Scalar, NumInputDims,\n                                            TensorBlockExpr, Index>\n        TensorBlockAssign;\n\n    TensorBlockAssign::Run(\n        TensorBlockAssign::target(\n            input_block_dims,\n            internal::strides<Layout>(this->m_impl.dimensions()),\n            this->m_impl.data(), this->srcCoeff(desc.offset())),\n        block.expr().reshape(input_block_dims));\n  }\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_CHIPPING_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConcatenation.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONCATENATION_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CONCATENATION_H\n\nnamespace Eigen {\n\n/** \\class TensorConcatenationOp\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor concatenation class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename Axis, typename LhsXprType, typename RhsXprType>\nstruct traits<TensorConcatenationOp<Axis, LhsXprType, RhsXprType> >\n{\n  // Type promotion to handle the case where the types of the lhs and the rhs are different.\n  typedef typename promote_storage_type<typename LhsXprType::Scalar,\n                                        typename RhsXprType::Scalar>::ret Scalar;\n  typedef typename promote_storage_type<typename traits<LhsXprType>::StorageKind,\n                                        typename traits<RhsXprType>::StorageKind>::ret StorageKind;\n  typedef typename promote_index_type<typename traits<LhsXprType>::Index,\n                                      typename traits<RhsXprType>::Index>::type Index;\n  typedef typename LhsXprType::Nested LhsNested;\n  typedef typename RhsXprType::Nested RhsNested;\n  typedef typename remove_reference<LhsNested>::type _LhsNested;\n  typedef typename remove_reference<RhsNested>::type _RhsNested;\n  static const int NumDimensions = traits<LhsXprType>::NumDimensions;\n  static const int Layout = traits<LhsXprType>::Layout;\n  enum { Flags = 0 };\n  typedef typename conditional<Pointer_type_promotion<typename LhsXprType::Scalar, Scalar>::val,\n                               typename traits<LhsXprType>::PointerType, typename traits<RhsXprType>::PointerType>::type PointerType;\n};\n\ntemplate<typename Axis, typename LhsXprType, typename RhsXprType>\nstruct eval<TensorConcatenationOp<Axis, LhsXprType, RhsXprType>, Eigen::Dense>\n{\n  typedef const TensorConcatenationOp<Axis, LhsXprType, RhsXprType>& type;\n};\n\ntemplate<typename Axis, typename LhsXprType, typename RhsXprType>\nstruct nested<TensorConcatenationOp<Axis, LhsXprType, RhsXprType>, 1, typename eval<TensorConcatenationOp<Axis, LhsXprType, RhsXprType> >::type>\n{\n  typedef TensorConcatenationOp<Axis, LhsXprType, RhsXprType> type;\n};\n\n}  // end namespace internal\n\n\ntemplate<typename Axis, typename LhsXprType, typename RhsXprType>\nclass TensorConcatenationOp : public TensorBase<TensorConcatenationOp<Axis, LhsXprType, RhsXprType>, WriteAccessors>\n{\n  public:\n    typedef TensorBase<TensorConcatenationOp<Axis, LhsXprType, RhsXprType>, WriteAccessors> Base;\n    typedef typename internal::traits<TensorConcatenationOp>::Scalar Scalar;\n    typedef typename internal::traits<TensorConcatenationOp>::StorageKind StorageKind;\n    typedef typename internal::traits<TensorConcatenationOp>::Index Index;\n    typedef typename internal::nested<TensorConcatenationOp>::type Nested;\n    typedef typename internal::promote_storage_type<typename LhsXprType::CoeffReturnType,\n                                                    typename RhsXprType::CoeffReturnType>::ret CoeffReturnType;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorConcatenationOp(const LhsXprType& lhs, const RhsXprType& rhs, Axis axis)\n        : m_lhs_xpr(lhs), m_rhs_xpr(rhs), m_axis(axis) {}\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename LhsXprType::Nested>::type&\n    lhsExpression() const { return m_lhs_xpr; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename RhsXprType::Nested>::type&\n    rhsExpression() const { return m_rhs_xpr; }\n\n    EIGEN_DEVICE_FUNC const Axis& axis() const { return m_axis; }\n\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(TensorConcatenationOp)\n  protected:\n    typename LhsXprType::Nested m_lhs_xpr;\n    typename RhsXprType::Nested m_rhs_xpr;\n    const Axis m_axis;\n};\n\n\n// Eval as rvalue\ntemplate<typename Axis, typename LeftArgType, typename RightArgType, typename Device>\nstruct TensorEvaluator<const TensorConcatenationOp<Axis, LeftArgType, RightArgType>, Device>\n{\n  typedef TensorConcatenationOp<Axis, LeftArgType, RightArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<LeftArgType, Device>::Dimensions>::value;\n  static const int RightNumDims = internal::array_size<typename TensorEvaluator<RightArgType, Device>::Dimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n  enum {\n    IsAligned         = false,\n    PacketAccess      = TensorEvaluator<LeftArgType, Device>::PacketAccess &&\n                        TensorEvaluator<RightArgType, Device>::PacketAccess,\n    BlockAccess       = false,\n    PreferBlockAccess = TensorEvaluator<LeftArgType, Device>::PreferBlockAccess ||\n                        TensorEvaluator<RightArgType, Device>::PreferBlockAccess,\n    Layout            = TensorEvaluator<LeftArgType, Device>::Layout,\n    RawAccess         = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n    : m_leftImpl(op.lhsExpression(), device), m_rightImpl(op.rhsExpression(), device), m_axis(op.axis())\n  {\n    EIGEN_STATIC_ASSERT((static_cast<int>(TensorEvaluator<LeftArgType, Device>::Layout) == static_cast<int>(TensorEvaluator<RightArgType, Device>::Layout) || NumDims == 1), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    EIGEN_STATIC_ASSERT((NumDims == RightNumDims), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    EIGEN_STATIC_ASSERT((NumDims > 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    eigen_assert(0 <= m_axis && m_axis < NumDims);\n    const Dimensions& lhs_dims = m_leftImpl.dimensions();\n    const Dimensions& rhs_dims = m_rightImpl.dimensions();\n    {\n      int i = 0;\n      for (; i < m_axis; ++i) {\n        eigen_assert(lhs_dims[i] > 0);\n        eigen_assert(lhs_dims[i] == rhs_dims[i]);\n        m_dimensions[i] = lhs_dims[i];\n      }\n      eigen_assert(lhs_dims[i] > 0);  // Now i == m_axis.\n      eigen_assert(rhs_dims[i] > 0);\n      m_dimensions[i] = lhs_dims[i] + rhs_dims[i];\n      for (++i; i < NumDims; ++i) {\n        eigen_assert(lhs_dims[i] > 0);\n        eigen_assert(lhs_dims[i] == rhs_dims[i]);\n        m_dimensions[i] = lhs_dims[i];\n      }\n    }\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_leftStrides[0] = 1;\n      m_rightStrides[0] = 1;\n      m_outputStrides[0] = 1;\n\n      for (int j = 1; j < NumDims; ++j) {\n        m_leftStrides[j] = m_leftStrides[j-1] * lhs_dims[j-1];\n        m_rightStrides[j] = m_rightStrides[j-1] * rhs_dims[j-1];\n        m_outputStrides[j] = m_outputStrides[j-1] * m_dimensions[j-1];\n      }\n    } else {\n      m_leftStrides[NumDims - 1] = 1;\n      m_rightStrides[NumDims - 1] = 1;\n      m_outputStrides[NumDims - 1] = 1;\n\n      for (int j = NumDims - 2; j >= 0; --j) {\n        m_leftStrides[j] = m_leftStrides[j+1] * lhs_dims[j+1];\n        m_rightStrides[j] = m_rightStrides[j+1] * rhs_dims[j+1];\n        m_outputStrides[j] = m_outputStrides[j+1] * m_dimensions[j+1];\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  // TODO(phli): Add short-circuit memcpy evaluation if underlying data are linear?\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType)\n  {\n    m_leftImpl.evalSubExprsIfNeeded(NULL);\n    m_rightImpl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup()\n  {\n    m_leftImpl.cleanup();\n    m_rightImpl.cleanup();\n  }\n\n  // TODO(phli): attempt to speed this up. The integer divisions and modulo are slow.\n  // See CL/76180724 comments for more ideas.\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    // Collect dimension-wise indices (subs).\n    array<Index, NumDims> subs;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = NumDims - 1; i > 0; --i) {\n        subs[i] = index / m_outputStrides[i];\n        index -= subs[i] * m_outputStrides[i];\n      }\n      subs[0] = index;\n    } else {\n      for (int i = 0; i < NumDims - 1; ++i) {\n        subs[i] = index / m_outputStrides[i];\n        index -= subs[i] * m_outputStrides[i];\n      }\n      subs[NumDims - 1] = index;\n    }\n\n    const Dimensions& left_dims = m_leftImpl.dimensions();\n    if (subs[m_axis] < left_dims[m_axis]) {\n      Index left_index;\n      if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n        left_index = subs[0];\n        EIGEN_UNROLL_LOOP\n        for (int i = 1; i < NumDims; ++i) {\n          left_index += (subs[i] % left_dims[i]) * m_leftStrides[i];\n        }\n      } else {\n        left_index = subs[NumDims - 1];\n        EIGEN_UNROLL_LOOP\n        for (int i = NumDims - 2; i >= 0; --i) {\n          left_index += (subs[i] % left_dims[i]) * m_leftStrides[i];\n        }\n      }\n      return m_leftImpl.coeff(left_index);\n    } else {\n      subs[m_axis] -= left_dims[m_axis];\n      const Dimensions& right_dims = m_rightImpl.dimensions();\n      Index right_index;\n      if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n        right_index = subs[0];\n        EIGEN_UNROLL_LOOP\n        for (int i = 1; i < NumDims; ++i) {\n          right_index += (subs[i] % right_dims[i]) * m_rightStrides[i];\n        }\n      } else {\n        right_index = subs[NumDims - 1];\n        EIGEN_UNROLL_LOOP\n        for (int i = NumDims - 2; i >= 0; --i) {\n          right_index += (subs[i] % right_dims[i]) * m_rightStrides[i];\n        }\n      }\n      return m_rightImpl.coeff(right_index);\n    }\n  }\n\n  // TODO(phli): Add a real vectorization.\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    const int packetSize = PacketType<CoeffReturnType, Device>::size;\n    EIGEN_STATIC_ASSERT((packetSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index + packetSize - 1 < dimensions().TotalSize());\n\n    EIGEN_ALIGN_MAX CoeffReturnType values[packetSize];\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < packetSize; ++i) {\n      values[i] = coeff(index+i);\n    }\n    PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n    return rslt;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    const double compute_cost = NumDims * (2 * TensorOpCost::AddCost<Index>() +\n                                           2 * TensorOpCost::MulCost<Index>() +\n                                           TensorOpCost::DivCost<Index>() +\n                                           TensorOpCost::ModCost<Index>());\n    const double lhs_size = m_leftImpl.dimensions().TotalSize();\n    const double rhs_size = m_rightImpl.dimensions().TotalSize();\n    return (lhs_size / (lhs_size + rhs_size)) *\n               m_leftImpl.costPerCoeff(vectorized) +\n           (rhs_size / (lhs_size + rhs_size)) *\n               m_rightImpl.costPerCoeff(vectorized) +\n           TensorOpCost(0, 0, compute_cost);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n  #ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_leftImpl.bind(cgh);\n    m_rightImpl.bind(cgh);\n  }\n  #endif\n\n  protected:\n    Dimensions m_dimensions;\n    array<Index, NumDims> m_outputStrides;\n    array<Index, NumDims> m_leftStrides;\n    array<Index, NumDims> m_rightStrides;\n    TensorEvaluator<LeftArgType, Device> m_leftImpl;\n    TensorEvaluator<RightArgType, Device> m_rightImpl;\n    const Axis m_axis;\n};\n\n// Eval as lvalue\ntemplate<typename Axis, typename LeftArgType, typename RightArgType, typename Device>\n  struct TensorEvaluator<TensorConcatenationOp<Axis, LeftArgType, RightArgType>, Device>\n  : public TensorEvaluator<const TensorConcatenationOp<Axis, LeftArgType, RightArgType>, Device>\n{\n  typedef TensorEvaluator<const TensorConcatenationOp<Axis, LeftArgType, RightArgType>, Device> Base;\n  typedef TensorConcatenationOp<Axis, LeftArgType, RightArgType> XprType;\n  typedef typename Base::Dimensions Dimensions;\n  enum {\n    IsAligned         = false,\n    PacketAccess      = TensorEvaluator<LeftArgType, Device>::PacketAccess &&\n                        TensorEvaluator<RightArgType, Device>::PacketAccess,\n    BlockAccess       = false,\n    PreferBlockAccess = TensorEvaluator<LeftArgType, Device>::PreferBlockAccess ||\n                        TensorEvaluator<RightArgType, Device>::PreferBlockAccess,\n    Layout            = TensorEvaluator<LeftArgType, Device>::Layout,\n    RawAccess         = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(XprType& op, const Device& device)\n    : Base(op, device)\n  {\n    EIGEN_STATIC_ASSERT((static_cast<int>(Layout) == static_cast<int>(ColMajor)), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  }\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index)\n  {\n    // Collect dimension-wise indices (subs).\n    array<Index, Base::NumDims> subs;\n    for (int i = Base::NumDims - 1; i > 0; --i) {\n      subs[i] = index / this->m_outputStrides[i];\n      index -= subs[i] * this->m_outputStrides[i];\n    }\n    subs[0] = index;\n\n    const Dimensions& left_dims = this->m_leftImpl.dimensions();\n    if (subs[this->m_axis] < left_dims[this->m_axis]) {\n      Index left_index = subs[0];\n      for (int i = 1; i < Base::NumDims; ++i) {\n        left_index += (subs[i] % left_dims[i]) * this->m_leftStrides[i];\n      }\n      return this->m_leftImpl.coeffRef(left_index);\n    } else {\n      subs[this->m_axis] -= left_dims[this->m_axis];\n      const Dimensions& right_dims = this->m_rightImpl.dimensions();\n      Index right_index = subs[0];\n      for (int i = 1; i < Base::NumDims; ++i) {\n        right_index += (subs[i] % right_dims[i]) * this->m_rightStrides[i];\n      }\n      return this->m_rightImpl.coeffRef(right_index);\n    }\n  }\n\n  template <int StoreMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void writePacket(Index index, const PacketReturnType& x)\n  {\n    const int packetSize = PacketType<CoeffReturnType, Device>::size;\n    EIGEN_STATIC_ASSERT((packetSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index + packetSize - 1 < this->dimensions().TotalSize());\n\n    EIGEN_ALIGN_MAX CoeffReturnType values[packetSize];\n    internal::pstore<CoeffReturnType, PacketReturnType>(values, x);\n    for (int i = 0; i < packetSize; ++i) {\n      coeffRef(index+i) = values[i];\n    }\n  }\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_CONCATENATION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContraction.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_H\n\nnamespace Eigen {\n\n/** \\class TensorContraction\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor contraction class.\n  *\n  *\n  */\nnamespace internal {\n\ntemplate<typename Dimensions, typename LhsXprType, typename RhsXprType, typename OutputKernelType>\nstruct traits<TensorContractionOp<Dimensions, LhsXprType, RhsXprType, OutputKernelType> >\n{\n  // Type promotion to handle the case where the types of the lhs and the rhs are different.\n  typedef typename gebp_traits<typename remove_const<typename LhsXprType::Scalar>::type,\n                               typename remove_const<typename RhsXprType::Scalar>::type>::ResScalar Scalar;\n\n  typedef typename promote_storage_type<typename traits<LhsXprType>::StorageKind,\n                                        typename traits<RhsXprType>::StorageKind>::ret StorageKind;\n  typedef typename promote_index_type<typename traits<LhsXprType>::Index,\n                                      typename traits<RhsXprType>::Index>::type Index;\n  typedef typename LhsXprType::Nested LhsNested;\n  typedef typename RhsXprType::Nested RhsNested;\n  typedef typename remove_reference<LhsNested>::type _LhsNested;\n  typedef typename remove_reference<RhsNested>::type _RhsNested;\n\n  // From NumDims below.\n  static const int NumDimensions = traits<LhsXprType>::NumDimensions + traits<RhsXprType>::NumDimensions - 2 * array_size<Dimensions>::value;\n  static const int Layout = traits<LhsXprType>::Layout;\n  typedef typename conditional<Pointer_type_promotion<typename LhsXprType::Scalar, Scalar>::val,\n                               typename traits<LhsXprType>::PointerType,\n                               typename traits<RhsXprType>::PointerType>::type\n      PointerType;\n\n  enum {\n    Flags = 0\n  };\n};\n\ntemplate<typename Dimensions, typename LhsXprType, typename RhsXprType, typename OutputKernelType>\nstruct eval<TensorContractionOp<Dimensions, LhsXprType, RhsXprType, OutputKernelType>, Eigen::Dense>\n{\n  typedef const TensorContractionOp<Dimensions, LhsXprType, RhsXprType, OutputKernelType>& type;\n};\n\ntemplate<typename Dimensions, typename LhsXprType, typename RhsXprType, typename OutputKernelType>\nstruct nested<TensorContractionOp<Dimensions, LhsXprType, RhsXprType, OutputKernelType>, 1, typename eval<TensorContractionOp<Dimensions, LhsXprType, RhsXprType, OutputKernelType> >::type>\n{\n  typedef TensorContractionOp<Dimensions, LhsXprType, RhsXprType, OutputKernelType> type;\n};\n\ntemplate<typename Indices_, typename LeftArgType_, typename RightArgType_, typename OutputKernelType_, typename Device_>\nstruct traits<TensorEvaluator<const TensorContractionOp<Indices_, LeftArgType_, RightArgType_, OutputKernelType_>, Device_> > {\n  typedef Indices_ Indices;\n  typedef LeftArgType_ LeftArgType;\n  typedef RightArgType_ RightArgType;\n  typedef OutputKernelType_ OutputKernelType;\n  typedef Device_ Device;\n\n  // From NumDims below.\n  static const int NumDimensions = traits<LeftArgType_>::NumDimensions + traits<RightArgType_>::NumDimensions - 2 * array_size<Indices_>::value;\n};\n\n// Helper class to allocate and deallocate temporary memory for packed buffers.\ntemplate <typename LhsScalar, typename RhsScalar>\nstruct TensorContractionBlockMemAllocator {\n  typedef void* BlockMemHandle;\n\n  template <typename Device>\n  EIGEN_DEVICE_FUNC static BlockMemHandle allocate(Device& d, const Index bm,\n                                                   const Index bk,\n                                                   const Index bn,\n                                                   LhsScalar** lhs_block,\n                                                   RhsScalar** rhs_block) {\n    eigen_assert(lhs_block);\n    eigen_assert(rhs_block);\n    BlockSizes sz = ComputeLhsRhsBlockSizes(bm, bk, bn);\n    char* block_mem = static_cast<char*>(d.allocate(sz.lhs_size + sz.rhs_size));\n    eigen_assert(block_mem);\n    *lhs_block = reinterpret_cast<LhsScalar*>(block_mem);\n    *rhs_block = reinterpret_cast<RhsScalar*>(block_mem + sz.lhs_size);\n    return block_mem;\n  }\n\n  template <typename Device>\n  EIGEN_DEVICE_FUNC static BlockMemHandle allocateSlices(\n      Device& d, const Index bm, const Index bk, const Index bn,\n      const Index num_lhs, const Index num_rhs, const Index num_slices,\n      std::vector<LhsScalar*>* lhs_blocks,\n      std::vector<RhsScalar*>* rhs_blocks) {\n    eigen_assert(num_slices > 0);\n    eigen_assert(num_lhs >= 0 && num_rhs >= 0);\n    eigen_assert(num_lhs == 0 || lhs_blocks);\n    eigen_assert(num_rhs == 0 || rhs_blocks);\n    BlockSizes sz = ComputeLhsRhsBlockSizes(bm, bk, bn);\n    void* block_mem = d.allocate(\n        (num_lhs * sz.lhs_size + num_rhs * sz.rhs_size) * num_slices);\n    eigen_assert(block_mem);\n    char* mem = static_cast<char*>(block_mem);\n\n    for (Index x = 0; x < num_slices; x++) {\n      if (num_lhs > 0) lhs_blocks[x].resize(num_lhs);\n      for (Index m = 0; m < num_lhs; m++) {\n        lhs_blocks[x][m] = reinterpret_cast<LhsScalar*>(mem);\n        mem += sz.lhs_size;\n      }\n      if (num_rhs > 0) rhs_blocks[x].resize(num_rhs);\n      for (Index n = 0; n < num_rhs; n++) {\n        rhs_blocks[x][n] = reinterpret_cast<RhsScalar*>(mem);\n        mem += sz.rhs_size;\n      }\n    }\n\n    return block_mem;\n  }\n\n  template <typename Device>\n  EIGEN_DEVICE_FUNC static void deallocate(Device& d, BlockMemHandle handle) {\n    d.deallocate(handle);\n  }\n\n private:\n  struct BlockSizes {\n    Index lhs_size;\n    Index rhs_size;\n  };\n  EIGEN_DEVICE_FUNC static BlockSizes ComputeLhsRhsBlockSizes(const Index bm,\n                                                              const Index bk,\n                                                              const Index bn) {\n    Index align = numext::maxi(EIGEN_MAX_ALIGN_BYTES, 1);\n    BlockSizes sz;\n    sz.lhs_size = divup<Index>(bm * bk * sizeof(LhsScalar), align) * align;\n    sz.rhs_size = divup<Index>(bn * bk * sizeof(RhsScalar), align) * align;\n    return sz;\n  }\n};\n\n// WARNING: In this code we assume that Lhs and Rhs tensor expressions are in\n// ColMajor storage order. This property is guaranteed by the\n// TensorContractionOp evaluator. TensorContractionKernel specifies how we pack\n// blocks of Lhs and Rhs tensor expressions, and how we invoke matrix\n// multiplication for these blocks. Default tensor contraction uses\n// gemm_pack_rhs, gemm_pack_lhs and gebp_kernel from Eigen Core (see\n// GeneralBlocPanelKernel.h for details).\n//\n// By specializing contraction kernels we can use other low level libraries to\n// perform matrix multiplication, and still rely on Eigen contraction evaluator.\n// This also includes full support in TensorContractionThreadPool, assuming that\n// underlying gemm do not use it's own threading.\n//\n// - ResScalar/LhsScalar/RhsScalar - scalar type for the result of\n//   multiplication, lhs tensor and rhs tensor respectively.\n//\n// - StorageIndex - index type for the tensor expressions. In practice almost\n//   always is Eigen::Index.\n//\n// - OutputMapper provides access to the memory of the output matrix. In\n//   practice it's always column major blas_data_mapper (it must be of ResScalar\n//   type).\n//\n// - LhsMapper/RhsMapper similarly to blas_data_mapper provide a two dimensional\n//   view into the Lhs/Rhs tensor expressions. In practice it's\n//   TensorContractionInputMapper, or some specialization of it based on the\n//   type of tensor expression (e.g. TensorImagePatchOp has optimized input\n//   mapper).\ntemplate <typename ResScalar, typename LhsScalar, typename RhsScalar,\n    typename StorageIndex, typename OutputMapper, typename LhsMapper,\n    typename RhsMapper>\nstruct TensorContractionKernel {\n  // True if `invoke()` supports `beta` in `C <- alpha * A * B + beta * C`\n  // (otherwise beta should be always equal to 1).\n  enum { HasBeta = false };\n\n  EIGEN_DEVICE_FUNC\n  TensorContractionKernel(StorageIndex m_, StorageIndex k_, StorageIndex n_,\n                          StorageIndex bm_, StorageIndex bk_, StorageIndex bn_)\n      : m(m_), k(k_), n(n_), bm(bm_), bk(bk_), bn(bn_) {}\n\n  // Pack blocks of Lhs and Rhs into contiguous blocks in memory.\n  typedef LhsScalar* LhsBlock;\n  typedef RhsScalar* RhsBlock;\n\n  // Packed Lhs/Rhs block memory allocator.\n  typedef TensorContractionBlockMemAllocator<LhsScalar, RhsScalar>\n      BlockMemAllocator;\n  typedef typename BlockMemAllocator::BlockMemHandle BlockMemHandle;\n\n  typedef typename internal::gebp_traits<LhsScalar, RhsScalar> Traits;\n\n  typedef internal::gemm_pack_lhs<\n      LhsScalar, StorageIndex, typename LhsMapper::SubMapper, Traits::mr,\n      Traits::LhsProgress, typename Traits::LhsPacket4Packing, ColMajor>\n      LhsPacker;\n\n  typedef internal::gemm_pack_rhs<RhsScalar, StorageIndex,\n                                  typename RhsMapper::SubMapper, Traits::nr,\n                                  ColMajor>\n      RhsPacker;\n\n  typedef internal::gebp_kernel<LhsScalar, RhsScalar, StorageIndex,\n                                OutputMapper, Traits::mr, Traits::nr,\n      /*ConjugateLhs*/ false, /*ConjugateRhs*/ false>\n      GebpKernel;\n\n  template <typename Device>\n  EIGEN_DEVICE_FUNC BlockMemHandle allocate(Device& d, LhsBlock* lhs_block,\n                                            RhsBlock* rhs_block) {\n    return BlockMemAllocator::allocate(d, bm, bk, bn, lhs_block, rhs_block);\n  }\n\n  template <typename Device>\n  EIGEN_DEVICE_FUNC BlockMemHandle allocateSlices(\n      Device& d, const StorageIndex num_lhs, const StorageIndex num_rhs,\n      const StorageIndex num_slices, std::vector<LhsBlock>* lhs_blocks,\n      std::vector<RhsBlock>* rhs_blocks) {\n    return BlockMemAllocator::allocateSlices(\n        d, bm, bk, bn, num_lhs, num_rhs, num_slices, lhs_blocks, rhs_blocks);\n  }\n\n  template <typename Device>\n  EIGEN_DEVICE_FUNC static void deallocate(Device& d, BlockMemHandle handle) {\n    BlockMemAllocator::deallocate(d, handle);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_DONT_INLINE void packLhs(\n      LhsBlock* lhsBlock, const typename LhsMapper::SubMapper& data_mapper,\n      const StorageIndex depth, const StorageIndex rows) {\n    LhsPacker()(*lhsBlock, data_mapper, depth, rows, /*stride*/ 0,\n        /*offset*/ 0);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_DONT_INLINE void packRhs(\n      RhsBlock* rhsBlock, const typename RhsMapper::SubMapper& data_mapper,\n      const StorageIndex depth, const StorageIndex cols) {\n    RhsPacker()(*rhsBlock, data_mapper, depth, cols);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_DONT_INLINE void invoke(\n      const OutputMapper& output_mapper, const LhsBlock& lhsBlock,\n      const RhsBlock& rhsBlock, const StorageIndex rows,\n      const StorageIndex depth, const StorageIndex cols,\n      const ResScalar alpha, const ResScalar beta) {\n    // Default GEBP kernel does not support beta.\n    eigen_assert(beta == ResScalar(1));\n    static const int kComputeStrideFromBlockDimensions = -1;\n    GebpKernel()(output_mapper, lhsBlock, rhsBlock, rows, depth, cols, alpha,\n        /*strideA*/ kComputeStrideFromBlockDimensions,\n        /*strideB*/ kComputeStrideFromBlockDimensions,\n        /*offsetA*/ 0, /*offsetB*/ 0);\n  }\n\n private:\n  // These are dimensions of the original Tensors, and selected block sizes. The\n  // actual block sizes passed to all function above might be smaller because of\n  // the partial blocks at the end.\n  const StorageIndex m;\n  const StorageIndex k;\n  const StorageIndex n;\n  const StorageIndex bm;\n  const StorageIndex bk;\n  const StorageIndex bn;\n};\n\n}  // end namespace internal\n\n// Tensor contraction params that should enable to get from output matrix\n// 2-dimensional coordinates to the output tensor dimensions.\nstruct TensorContractionParams {\n  // TensorContraction evaluator assumes that both tensors are in ColMajor\n  // layout, if tensors are in RowMajor evaluator swap lhs with rhs.\n  bool swapped_arguments;\n};\n\n// Output kernel allows to fuse operations into the tensor contraction.\n//\n// Examples:\n//   1. Elementwise Relu transformation following Conv2D.\n//   2. AddBias to the Conv2D output channels dimension.\n//\n// The NoOpOutputKernel implements an output kernel that does absolutely nothing.\nstruct NoOpOutputKernel {\n  /**\n   * Tensor contraction evaluator calls this kernel after finishing each block\n   * of output matrix. Output blocks belong to the 2-dimensional output tensor.\n   *\n   * TensorContractionParams contains contraction dimensions information\n   * required to map output 2-d space into the expected output tensor space\n   * (potentially higher dimensional).\n   *\n   * \\param[in] output_mapper Access to output tensor memory\n   * \\param[in] params   Tensor contraction parameters\n   * \\param[in] i        Index of a first row available through output_mapper\n   * \\param[in] j        Index of a first column available through output_mapper\n   * \\param[in] num_rows Number of available rows\n   * \\param[in] num_cols Number of available columns\n   */\n  template <typename Index, typename Scalar>\n  EIGEN_ALWAYS_INLINE void operator()(\n      const internal::blas_data_mapper<Scalar, Index, ColMajor>& output_mapper,\n      const TensorContractionParams& params, Index i,\n      Index j, Index num_rows, Index num_cols) const {\n    EIGEN_UNUSED_VARIABLE(output_mapper);\n    EIGEN_UNUSED_VARIABLE(params);\n    EIGEN_UNUSED_VARIABLE(i);\n    EIGEN_UNUSED_VARIABLE(j);\n    EIGEN_UNUSED_VARIABLE(num_rows);\n    EIGEN_UNUSED_VARIABLE(num_cols);\n  }\n};\n\ntemplate<typename Indices, typename LhsXprType, typename RhsXprType, typename OutputKernelType = const NoOpOutputKernel>\nclass TensorContractionOp : public TensorBase<TensorContractionOp<Indices, LhsXprType, RhsXprType, OutputKernelType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorContractionOp>::Scalar Scalar;\n  typedef typename internal::gebp_traits<typename LhsXprType::CoeffReturnType,\n                                         typename RhsXprType::CoeffReturnType>::ResScalar CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorContractionOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorContractionOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorContractionOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorContractionOp(\n      const LhsXprType& lhs, const RhsXprType& rhs, const Indices& dims,\n      const OutputKernelType& output_kernel = OutputKernelType())\n      : m_lhs_xpr(lhs), m_rhs_xpr(rhs), m_indices(dims),\n        m_output_kernel(output_kernel) {}\n\n  EIGEN_DEVICE_FUNC\n  const Indices& indices() const { return m_indices; }\n\n  /** \\returns the nested expressions */\n  EIGEN_DEVICE_FUNC\n  const typename internal::remove_all<typename LhsXprType::Nested>::type&\n  lhsExpression() const { return m_lhs_xpr; }\n\n  EIGEN_DEVICE_FUNC\n  const typename internal::remove_all<typename RhsXprType::Nested>::type&\n  rhsExpression() const { return m_rhs_xpr; }\n\n  EIGEN_DEVICE_FUNC\n  const OutputKernelType& outputKernel() const { return m_output_kernel; }\n\n  protected:\n    typename LhsXprType::Nested m_lhs_xpr;\n    typename RhsXprType::Nested m_rhs_xpr;\n    const Indices m_indices;\n    const OutputKernelType m_output_kernel;\n};\n\n\ntemplate<typename Derived>\nstruct TensorContractionEvaluatorBase : internal::no_assignment_operator\n{\n  typedef typename internal::traits<Derived>::Indices Indices;\n  typedef typename internal::traits<Derived>::LeftArgType LeftArgType;\n  typedef typename internal::traits<Derived>::RightArgType RightArgType;\n  typedef typename internal::traits<Derived>::OutputKernelType OutputKernelType;\n  typedef typename internal::traits<Derived>::Device Device;\n\n  typedef TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType> XprType;\n  typedef typename internal::remove_const<typename XprType::Scalar>::type Scalar;\n  typedef typename XprType::Index Index;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef StorageMemory<Scalar, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned         = true,\n    PacketAccess      = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess       = false,\n    PreferBlockAccess = false,\n    Layout            = TensorEvaluator<LeftArgType, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = true\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  // Most of the code is assuming that both input tensors are ColMajor. If the\n  // inputs are RowMajor, we will \"cheat\" by swapping the LHS and RHS:\n  // If we want to compute A * B = C, where A is LHS and B is RHS, the code\n  // will pretend B is LHS and A is RHS.\n  typedef typename internal::conditional<\n    static_cast<int>(Layout) == static_cast<int>(ColMajor), LeftArgType, RightArgType>::type EvalLeftArgType;\n  typedef typename internal::conditional<\n    static_cast<int>(Layout) == static_cast<int>(ColMajor), RightArgType, LeftArgType>::type EvalRightArgType;\n\n  typedef TensorEvaluator<EvalLeftArgType, Device> LeftEvaluatorType;\n  typedef TensorEvaluator<EvalRightArgType, Device> RightEvaluatorType;\n\n  static const int LDims =\n      internal::array_size<typename TensorEvaluator<EvalLeftArgType, Device>::Dimensions>::value;\n  static const int RDims =\n      internal::array_size<typename TensorEvaluator<EvalRightArgType, Device>::Dimensions>::value;\n  static const int ContractDims = internal::array_size<Indices>::value;\n  static const int NumDims = LDims + RDims - 2 * ContractDims;\n\n  typedef array<Index, ContractDims> contract_t;\n  typedef array<Index, LDims - ContractDims> left_nocontract_t;\n  typedef array<Index, RDims - ContractDims> right_nocontract_t;\n\n  typedef DSizes<Index, NumDims> Dimensions;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  TensorContractionEvaluatorBase(const XprType& op, const Device& device)\n      : m_leftImpl(choose(Cond<static_cast<int>(Layout) == static_cast<int>(ColMajor)>(),\n                          op.lhsExpression(), op.rhsExpression()), device),\n        m_rightImpl(choose(Cond<static_cast<int>(Layout) == static_cast<int>(ColMajor)>(),\n                           op.rhsExpression(), op.lhsExpression()), device),\n        m_device(device),\n        m_output_kernel(op.outputKernel()),\n        m_result(NULL) {\n    EIGEN_STATIC_ASSERT((static_cast<int>(TensorEvaluator<LeftArgType, Device>::Layout) ==\n         static_cast<int>(TensorEvaluator<RightArgType, Device>::Layout)),\n                        YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n\n    DSizes<Index, LDims> eval_left_dims;\n    DSizes<Index, RDims> eval_right_dims;\n    array<IndexPair<Index>, ContractDims> eval_op_indices;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      // For ColMajor, we keep using the existing dimensions\n      for (int i = 0; i < LDims; i++) {\n        eval_left_dims[i] = m_leftImpl.dimensions()[i];\n      }\n      for (int i = 0; i < RDims; i++) {\n        eval_right_dims[i] = m_rightImpl.dimensions()[i];\n      }\n      // We keep the pairs of contracting indices.\n      for (int i = 0; i < ContractDims; i++) {\n        eval_op_indices[i].first = op.indices()[i].first;\n        eval_op_indices[i].second = op.indices()[i].second;\n      }\n    } else {\n      // For RowMajor, we need to reverse the existing dimensions\n      for (int i = 0; i < LDims; i++) {\n        eval_left_dims[i] = m_leftImpl.dimensions()[LDims - i - 1];\n      }\n      for (int i = 0; i < RDims; i++) {\n        eval_right_dims[i] = m_rightImpl.dimensions()[RDims - i - 1];\n      }\n      // We need to flip all the pairs of contracting indices as well as\n      // reversing the dimensions.\n      for (int i = 0; i < ContractDims; i++) {\n        eval_op_indices[i].first = LDims - 1 - op.indices()[ContractDims - 1 - i].second;\n        eval_op_indices[i].second = RDims - 1 - op.indices()[ContractDims - 1 - i].first;\n      }\n    }\n\n    // Check for duplicate axes and make sure the first index in eval_op_indices\n    // is increasing. Using O(n^2) sorting is OK since ContractDims is small\n    for (int i = 0; i < ContractDims; i++) {\n      for (int j = i + 1; j < ContractDims; j++) {\n        eigen_assert(eval_op_indices[j].first != eval_op_indices[i].first &&\n                     eval_op_indices[j].second != eval_op_indices[i].second &&\n                     \"contraction axes should be unique\");\n        if (eval_op_indices[j].first < eval_op_indices[i].first) {\n          numext::swap(eval_op_indices[j], eval_op_indices[i]);\n        }\n      }\n    }\n\n    array<Index, LDims> lhs_strides;\n    lhs_strides[0] = 1;\n    for (int i = 0; i < LDims-1; ++i) {\n      lhs_strides[i+1] = lhs_strides[i] * eval_left_dims[i];\n    }\n\n    array<Index, RDims> rhs_strides;\n    rhs_strides[0] = 1;\n    for (int i = 0; i < RDims-1; ++i) {\n      rhs_strides[i+1] = rhs_strides[i] * eval_right_dims[i];\n    }\n\n    if (m_i_strides.size() > 0) m_i_strides[0] = 1;\n    if (m_j_strides.size() > 0) m_j_strides[0] = 1;\n    if (m_k_strides.size() > 0) m_k_strides[0] = 1;\n\n    m_i_size = 1;\n    m_j_size = 1;\n    m_k_size = 1;\n\n    // To compute the dimension, we simply concatenate the non-contracting\n    // dimensions of the left and then the right tensor. Additionally, we also\n    // compute the strides corresponding to the left non-contracting\n    // dimensions and right non-contracting dimensions.\n    m_lhs_inner_dim_contiguous = true;\n    int dim_idx = 0;\n    Index nocontract_idx = 0;\n\n    for (int i = 0; i < LDims; i++) {\n      // find if we are contracting on index i of left tensor\n      bool contracting = false;\n      for (int j = 0; j < ContractDims; j++) {\n        if (eval_op_indices[j].first == i) {\n          contracting = true;\n          break;\n        }\n      }\n      if (!contracting) {\n        // add dimension size to output dimensions\n        m_dimensions[dim_idx] = eval_left_dims[i];\n        m_left_nocontract_strides[nocontract_idx] = lhs_strides[i];\n        if (dim_idx != i) {\n          m_lhs_inner_dim_contiguous = false;\n        }\n        if (nocontract_idx+1 < internal::array_size<left_nocontract_t>::value) {\n          m_i_strides[nocontract_idx+1] =\n              m_i_strides[nocontract_idx] * eval_left_dims[i];\n        } else {\n          m_i_size = m_i_strides[nocontract_idx] * eval_left_dims[i];\n        }\n        dim_idx++;\n        nocontract_idx++;\n      }\n    }\n\n    nocontract_idx = 0;\n    for (int i = 0; i < RDims; i++) {\n      bool contracting = false;\n      // find if we are contracting on index i of right tensor\n      for (int j = 0; j < ContractDims; j++) {\n        if (eval_op_indices[j].second == i) {\n          contracting = true;\n          break;\n        }\n      }\n      if (!contracting) {\n        m_dimensions[dim_idx] = eval_right_dims[i];\n        if (nocontract_idx+1 < internal::array_size<right_nocontract_t>::value) {\n          m_j_strides[nocontract_idx+1] =\n              m_j_strides[nocontract_idx] * eval_right_dims[i];\n        } else {\n          m_j_size = m_j_strides[nocontract_idx] * eval_right_dims[i];\n        }\n        m_right_nocontract_strides[nocontract_idx] = rhs_strides[i];\n        dim_idx++;\n        nocontract_idx++;\n      }\n    }\n\n    // Now compute the strides corresponding to the contracting dimensions. We\n    // assumed above that non-contracting axes are represented in the same order\n    // in the matrix as they are in the tensor. This is not the case for\n    // contracting axes. As the contracting axes must be of the same size in\n    // each tensor, we'll only look at the first tensor here.\n    m_rhs_inner_dim_contiguous = true;\n    m_rhs_inner_dim_reordered = false;\n    for (int i = 0; i < ContractDims; i++) {\n      Index left = eval_op_indices[i].first;\n      Index right = eval_op_indices[i].second;\n\n      Index size = eval_left_dims[left];\n      eigen_assert(size == eval_right_dims[right] &&\n                   \"Contraction axes must be same size\");\n\n      if (i+1 < static_cast<int>(internal::array_size<contract_t>::value)) {\n        m_k_strides[i+1] = m_k_strides[i] * size;\n      } else {\n        m_k_size = m_k_strides[i] * size;\n      }\n      m_left_contracting_strides[i] = lhs_strides[left];\n      m_right_contracting_strides[i] = rhs_strides[right];\n\n      if (i > 0 && right < eval_op_indices[i-1].second) {\n        m_rhs_inner_dim_reordered = true;\n      }\n      if (right != i) {\n        m_rhs_inner_dim_contiguous = false;\n      }\n    }\n\n    // If the layout is RowMajor, we need to reverse the m_dimensions\n    if (static_cast<int>(Layout) == static_cast<int>(RowMajor)) {\n      for (int i = 0, j = NumDims - 1; i < j; i++, j--) {\n        numext::swap(m_dimensions[i], m_dimensions[j]);\n      }\n    }\n\n    // A set of parameters that will allow output kernel to get from output\n    // tensor dimensions (i, j) into the original tensor dimensions.\n    // TODO(ezhulenev): Add parameters required to infer output tensor index for\n    // more complex contractions than 2x2 on internal dimension.\n    m_tensor_contraction_params.swapped_arguments = static_cast<int>(Layout) == RowMajor;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    m_leftImpl.evalSubExprsIfNeeded(NULL);\n    m_rightImpl.evalSubExprsIfNeeded(NULL);\n    if (data) {\n      evalTo(data);\n      return false;\n    } else {\n      m_result = static_cast<EvaluatorPointerType>(m_device.allocate(dimensions().TotalSize() * sizeof(Scalar)));\n      evalTo(m_result);\n      return true;\n    }\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType dest, EvalSubExprsCallback done) {\n    m_leftImpl.evalSubExprsIfNeededAsync(nullptr, [this, done, dest](bool) {\n      m_rightImpl.evalSubExprsIfNeededAsync(nullptr, [this, done, dest](bool) {\n        if (dest) {\n          evalToAsync(dest, [done]() { done(false); });\n        } else {\n          m_result = static_cast<EvaluatorPointerType>(\n              m_device.allocate(dimensions().TotalSize() * sizeof(Scalar)));\n          evalToAsync(m_result, [done]() { done(true); });\n        }\n      });\n    });\n  }\n#endif  // EIGEN_USE_THREADS\n\n#define TENSOR_CONTRACTION_DISPATCH(METHOD, ALIGNMENT, ARGS) \\\n  if (this->m_lhs_inner_dim_contiguous) {                    \\\n    if (this->m_rhs_inner_dim_contiguous) {                  \\\n      if (this->m_rhs_inner_dim_reordered) {                 \\\n        METHOD<true, true, true, ALIGNMENT> ARGS;            \\\n      } else {                                               \\\n        METHOD<true, true, false, ALIGNMENT> ARGS;           \\\n      }                                                      \\\n    } else {                                                 \\\n      if (this->m_rhs_inner_dim_reordered) {                 \\\n        METHOD<true, false, true, ALIGNMENT> ARGS;           \\\n      } else {                                               \\\n        METHOD<true, false, false, ALIGNMENT> ARGS;          \\\n      }                                                      \\\n    }                                                        \\\n  } else {                                                   \\\n    if (this->m_rhs_inner_dim_contiguous) {                  \\\n      if (this->m_rhs_inner_dim_reordered) {                 \\\n        METHOD<false, true, true, ALIGNMENT> ARGS;           \\\n      } else {                                               \\\n        METHOD<false, true, false, ALIGNMENT> ARGS;          \\\n      }                                                      \\\n    } else {                                                 \\\n      if (this->m_rhs_inner_dim_reordered) {                 \\\n        METHOD<false, false, true, ALIGNMENT> ARGS;          \\\n      } else {                                               \\\n        METHOD<false, false, false, ALIGNMENT> ARGS;         \\\n      }                                                      \\\n    }                                                        \\\n  }\n\n#define TENSOR_CONTRACTION_ASYNC_DISPATCH(METHOD, DONE, ALIGNMENT, ARGS, FN) \\\n  if (this->m_lhs_inner_dim_contiguous) {                                    \\\n    if (this->m_rhs_inner_dim_contiguous) {                                  \\\n      if (this->m_rhs_inner_dim_reordered) {                                 \\\n        (new METHOD<DONE, true, true, true, ALIGNMENT> ARGS)->FN;            \\\n      } else {                                                               \\\n        (new METHOD<DONE, true, true, false, ALIGNMENT> ARGS)->FN;           \\\n      }                                                                      \\\n    } else {                                                                 \\\n      if (this->m_rhs_inner_dim_reordered) {                                 \\\n        (new METHOD<DONE, true, false, true, ALIGNMENT> ARGS)->FN;           \\\n      } else {                                                               \\\n        (new METHOD<DONE, true, false, false, ALIGNMENT> ARGS)->FN;          \\\n      }                                                                      \\\n    }                                                                        \\\n  } else {                                                                   \\\n    if (this->m_rhs_inner_dim_contiguous) {                                  \\\n      if (this->m_rhs_inner_dim_reordered) {                                 \\\n        (new METHOD<DONE, false, true, true, ALIGNMENT> ARGS)->FN;           \\\n      } else {                                                               \\\n        (new METHOD<DONE, false, true, false, ALIGNMENT> ARGS)->FN;          \\\n      }                                                                      \\\n    } else {                                                                 \\\n      if (this->m_rhs_inner_dim_reordered) {                                 \\\n        (new METHOD<DONE, false, false, true, ALIGNMENT> ARGS)->FN;          \\\n      } else {                                                               \\\n        (new METHOD<DONE, false, false, false, ALIGNMENT> ARGS)->FN;         \\\n      }                                                                      \\\n    }                                                                        \\\n  }\n\n  EIGEN_DEVICE_FUNC void evalTo(Scalar* buffer) const {\n   static_cast<const Derived*>(this)->template evalProduct<Unaligned>(buffer);\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalToCallback>\n  void evalToAsync(Scalar* buffer, EvalToCallback done) const {\n    static_cast<const Derived*>(this)\n        ->template evalProductAsync<EvalToCallback, Unaligned>(buffer,\n                                                               std::move(done));\n  }\n#endif  // EIGEN_USE_THREADS\n\n  template <bool lhs_inner_dim_contiguous, bool rhs_inner_dim_contiguous,\n            bool rhs_inner_dim_reordered, int Alignment>\n  void evalProductSequential(Scalar* buffer) const {\n    if (this->m_j_size == 1) {\n      this->template evalGemv<lhs_inner_dim_contiguous,\n                              rhs_inner_dim_contiguous, rhs_inner_dim_reordered,\n                              Alignment>(buffer);\n    } else {\n      this->template evalGemm<lhs_inner_dim_contiguous, rhs_inner_dim_contiguous,\n                              rhs_inner_dim_reordered, Alignment>(buffer);\n    }\n  }\n\n  template <bool lhs_inner_dim_contiguous, bool rhs_inner_dim_contiguous, bool rhs_inner_dim_reordered, int Alignment>\n  #if !defined(EIGEN_HIPCC)\n  EIGEN_DEVICE_FUNC\n  #endif\n  void evalGemv(Scalar* buffer) const {\n    const Index rows = m_i_size;\n    const Index cols = m_k_size;\n\n    typedef typename internal::remove_const<typename EvalLeftArgType::Scalar>::type LhsScalar;\n    typedef typename internal::remove_const<typename EvalRightArgType::Scalar>::type RhsScalar;\n    typedef TensorEvaluator<EvalLeftArgType, Device> LeftEvaluator;\n    typedef TensorEvaluator<EvalRightArgType, Device> RightEvaluator;\n    const Index lhs_packet_size = internal::unpacket_traits<typename LeftEvaluator::PacketReturnType>::size;\n    const Index rhs_packet_size = internal::unpacket_traits<typename RightEvaluator::PacketReturnType>::size;\n    const int lhs_alignment = LeftEvaluator::IsAligned ? Aligned : Unaligned;\n    const int rhs_alignment = RightEvaluator::IsAligned ? Aligned : Unaligned;\n    typedef internal::TensorContractionInputMapper<LhsScalar, Index, internal::Lhs,\n                                                   LeftEvaluator, left_nocontract_t,\n                                                   contract_t, lhs_packet_size,\n                                                   lhs_inner_dim_contiguous,\n                                                   false, lhs_alignment> LhsMapper;\n\n    typedef internal::TensorContractionInputMapper<RhsScalar, Index, internal::Rhs,\n                                                   RightEvaluator, right_nocontract_t,\n                                                   contract_t, rhs_packet_size,\n                                                   rhs_inner_dim_contiguous,\n                                                   rhs_inner_dim_reordered, rhs_alignment> RhsMapper;\n\n    LhsMapper lhs(m_leftImpl, m_left_nocontract_strides, m_i_strides,\n                  m_left_contracting_strides, m_k_strides);\n    RhsMapper rhs(m_rightImpl, m_right_nocontract_strides, m_j_strides,\n                  m_right_contracting_strides, m_k_strides);\n\n    const Scalar alpha(1);\n    const Index resIncr(1);\n\n    // zero out the result buffer (which must be of size at least rows * sizeof(Scalar)\n    m_device.memset(buffer, 0, rows * sizeof(Scalar));\n\n    internal::general_matrix_vector_product<Index,LhsScalar,LhsMapper,ColMajor,false,RhsScalar,RhsMapper,false>::run(\n        rows, cols, lhs, rhs,\n        buffer, resIncr, alpha);\n\n    typedef internal::blas_data_mapper<Scalar, Index, ColMajor> OutputMapper;\n    m_output_kernel(OutputMapper(buffer, rows), m_tensor_contraction_params,\n                    static_cast<Index>(0), static_cast<Index>(0), rows,\n                    static_cast<Index>(1));\n  }\n\n  template <bool lhs_inner_dim_contiguous, bool rhs_inner_dim_contiguous, bool rhs_inner_dim_reordered, int Alignment>\n  #if !defined(EIGEN_HIPCC)\n  EIGEN_DEVICE_FUNC\n  #endif\n  void evalGemm(Scalar* buffer) const {\n    // columns in left side, rows in right side\n    const Index k = this->m_k_size;\n    this->template evalGemmPartial<lhs_inner_dim_contiguous,\n                                   rhs_inner_dim_contiguous,\n                                   rhs_inner_dim_reordered,\n                                   Alignment, true>(buffer, 0, k, 1);\n  }\n\n  template <bool lhs_inner_dim_contiguous, bool rhs_inner_dim_contiguous,\n      bool rhs_inner_dim_reordered, int Alignment>\n  EIGEN_DEVICE_FUNC void evalGemmPartialWithoutOutputKernel(\n      Scalar* buffer, Index k_start, Index k_end, int num_threads) const {\n    evalGemmPartial<lhs_inner_dim_contiguous, rhs_inner_dim_contiguous,\n                    rhs_inner_dim_reordered, Alignment,\n        /*use_output_kernel*/ false>(buffer, k_start, k_end,\n                                     num_threads);\n  }\n\n  template <bool lhs_inner_dim_contiguous, bool rhs_inner_dim_contiguous, bool rhs_inner_dim_reordered, int Alignment, bool use_output_kernel>\n  EIGEN_DEVICE_FUNC void evalGemmPartial(Scalar* buffer, Index k_start, Index k_end, int num_threads) const {\n    eigen_assert(k_end >= k_start && k_start >= 0 && k_end <= this->m_k_size);\n    // columns in slice on left side, rows on right side\n    const Index k_slice = k_end - k_start;\n\n    // rows in left side\n    const Index m = this->m_i_size;\n\n    // columns in right side\n    const Index n = this->m_j_size;\n\n    // define data mappers for Lhs and Rhs\n    typedef typename internal::remove_const<typename EvalLeftArgType::Scalar>::type LhsScalar;\n    typedef typename internal::remove_const<typename EvalRightArgType::Scalar>::type RhsScalar;\n\n    typedef TensorEvaluator<EvalLeftArgType, Device> LeftEvaluator;\n    typedef TensorEvaluator<EvalRightArgType, Device> RightEvaluator;\n\n    const Index lhs_packet_size = internal::unpacket_traits<typename LeftEvaluator::PacketReturnType>::size;\n    const Index rhs_packet_size = internal::unpacket_traits<typename RightEvaluator::PacketReturnType>::size;\n\n    typedef internal::TensorContractionInputMapper<LhsScalar, Index, internal::Lhs,\n                                                   LeftEvaluator, left_nocontract_t,\n                                                   contract_t, lhs_packet_size,\n                                                   lhs_inner_dim_contiguous,\n                                                   false, Unaligned> LhsMapper;\n\n    typedef internal::TensorContractionInputMapper<RhsScalar, Index, internal::Rhs,\n                                                   RightEvaluator, right_nocontract_t,\n                                                   contract_t, rhs_packet_size,\n                                                   rhs_inner_dim_contiguous,\n                                                   rhs_inner_dim_reordered, Unaligned> RhsMapper;\n\n    typedef internal::blas_data_mapper<Scalar, Index, ColMajor> OutputMapper;\n\n    typedef internal::TensorContractionKernel<\n        Scalar, LhsScalar, RhsScalar, Index, OutputMapper, LhsMapper, RhsMapper>\n        TensorContractionKernel;\n\n    // initialize data mappers\n    LhsMapper lhs(this->m_leftImpl, this->m_left_nocontract_strides, this->m_i_strides,\n                  this->m_left_contracting_strides, this->m_k_strides);\n\n    RhsMapper rhs(this->m_rightImpl, this->m_right_nocontract_strides, this->m_j_strides,\n                  this->m_right_contracting_strides, this->m_k_strides);\n\n    OutputMapper output(buffer, m);\n\n    // Sizes of the blocks to load in cache. See the Goto paper for details.\n    internal::TensorContractionBlocking<Scalar, LhsScalar, RhsScalar,\n                                        Index, internal::ShardByCol>\n        blocking(k_slice, m, n, num_threads);\n    const Index kc = blocking.kc();\n    const Index mc = numext::mini(m, blocking.mc());\n    const Index nc = numext::mini(n, blocking.nc());\n\n    typedef typename TensorContractionKernel::LhsBlock LhsBlock;\n    typedef typename TensorContractionKernel::RhsBlock RhsBlock;\n\n    LhsBlock blockA;\n    RhsBlock blockB;\n\n    TensorContractionKernel kernel(m, k_slice, n, mc, kc, nc);\n\n    typedef typename TensorContractionKernel::BlockMemHandle BlockMemHandle;\n    const BlockMemHandle packed_mem =\n        kernel.allocate(this->m_device, &blockA, &blockB);\n\n    // If a contraction kernel does not support beta, explicitly initialize\n    // output buffer with zeroes.\n    if (!TensorContractionKernel::HasBeta) {\n      this->m_device.memset(buffer, 0, m * n * sizeof(Scalar));\n    }\n\n    for(Index i2=0; i2<m; i2+=mc)\n    {\n      const Index actual_mc = numext::mini(i2+mc,m)-i2;\n      for (Index k2 = k_start; k2 < k_end; k2 += kc) {\n        // make sure we don't overshoot right edge of left matrix, then pack vertical panel\n        const Index actual_kc = numext::mini(k2 + kc, k_end) - k2;\n        kernel.packLhs(&blockA, lhs.getSubMapper(i2, k2), actual_kc, actual_mc);\n\n        // If kernel supports beta, there is no need to initialize output\n        // buffer with zeroes.\n        const Scalar alpha = Scalar(1);\n        const Scalar beta = (TensorContractionKernel::HasBeta && k2 == k_start)\n                                ? Scalar(0)\n                                : Scalar(1);\n\n        // series of horizontal blocks\n        for (Index j2 = 0; j2 < n; j2 += nc) {\n          // make sure we don't overshoot right edge of right matrix, then pack block\n          const Index actual_nc = numext::mini(j2 + nc, n) - j2;\n          kernel.packRhs(&blockB, rhs.getSubMapper(k2, j2), actual_kc,\n                         actual_nc);\n\n          // call gebp (matrix kernel)\n          // The parameters here are copied from Eigen's GEMM implementation\n          const OutputMapper output_mapper = output.getSubMapper(i2, j2);\n          kernel.invoke(output_mapper, blockA, blockB, actual_mc, actual_kc,\n                        actual_nc, alpha, beta);\n\n          // We are done with this [i2, j2] output block.\n          if (use_output_kernel && k2 + kc >= k_end) {\n            m_output_kernel(output_mapper, m_tensor_contraction_params, i2, j2,\n                            actual_mc, actual_nc);\n          }\n        }\n      }\n    }\n\n    kernel.deallocate(this->m_device, packed_mem);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_leftImpl.cleanup();\n    m_rightImpl.cleanup();\n\n    if (m_result != NULL) {\n      m_device.deallocate(m_result);\n      m_result = NULL;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const {\n    return m_result[index];\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool) const {\n    return TensorOpCost(sizeof(CoeffReturnType), 0, 0);\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const {\n    return internal::ploadt<PacketReturnType, LoadMode>(m_result + index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EvaluatorPointerType data() const { return m_result; }\n\nprotected:\n  Dimensions m_dimensions;\n\n  contract_t m_k_strides;\n  contract_t m_left_contracting_strides;\n  contract_t m_right_contracting_strides;\n\n  bool m_lhs_inner_dim_contiguous;\n  bool m_rhs_inner_dim_contiguous;\n  bool m_rhs_inner_dim_reordered;\n\n  left_nocontract_t m_i_strides;\n  right_nocontract_t m_j_strides;\n  left_nocontract_t m_left_nocontract_strides;\n  right_nocontract_t m_right_nocontract_strides;\n\n  Index m_i_size;\n  Index m_j_size;\n  Index m_k_size;\n\n  TensorContractionParams m_tensor_contraction_params;\n\n  TensorEvaluator<EvalLeftArgType, Device> m_leftImpl;\n  TensorEvaluator<EvalRightArgType, Device> m_rightImpl;\n  const Device EIGEN_DEVICE_REF m_device;\n  OutputKernelType m_output_kernel;\n  EvaluatorPointerType m_result;\n};\n\n\n// evaluator for default device\ntemplate<typename Indices, typename LeftArgType, typename RightArgType, typename OutputKernelType, typename Device>\nstruct TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, Device> :\n    public TensorContractionEvaluatorBase<\n      TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, Device> > {\n  typedef TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, Device> Self;\n  typedef TensorContractionEvaluatorBase<Self> Base;\n\n  typedef TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType> XprType;\n  typedef typename internal::remove_const<typename XprType::Scalar>::type Scalar;\n  typedef typename XprType::Index Index;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n\n  enum {\n    Layout = TensorEvaluator<LeftArgType, Device>::Layout\n  };\n\n  // Most of the code is assuming that both input tensors are ColMajor. If the\n  // inputs are RowMajor, we will \"cheat\" by swapping the LHS and RHS:\n  // If we want to compute A * B = C, where A is LHS and B is RHS, the code\n  // will pretend B is LHS and A is RHS.\n  typedef typename internal::conditional<\n    static_cast<int>(Layout) == static_cast<int>(ColMajor), LeftArgType, RightArgType>::type EvalLeftArgType;\n  typedef typename internal::conditional<\n    static_cast<int>(Layout) == static_cast<int>(ColMajor), RightArgType, LeftArgType>::type EvalRightArgType;\n\n  static const int LDims =\n      internal::array_size<typename TensorEvaluator<EvalLeftArgType, Device>::Dimensions>::value;\n  static const int RDims =\n      internal::array_size<typename TensorEvaluator<EvalRightArgType, Device>::Dimensions>::value;\n  static const int ContractDims = internal::array_size<Indices>::value;\n\n  typedef array<Index, ContractDims> contract_t;\n  typedef array<Index, LDims - ContractDims> left_nocontract_t;\n  typedef array<Index, RDims - ContractDims> right_nocontract_t;\n\n  static const int NumDims = LDims + RDims - 2 * ContractDims;\n\n  // Could we use NumDimensions here?\n  typedef DSizes<Index, NumDims> Dimensions;\n\n  EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device) :\n      Base(op, device) { }\n\n  template <int Alignment>\n  void evalProduct(Scalar* buffer) const {\n    TENSOR_CONTRACTION_DISPATCH(this->template evalProductSequential, Alignment, (buffer));\n  }\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionBlocking.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_BLOCKING_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_BLOCKING_H\n\n\nnamespace Eigen {\nnamespace internal {\n\nenum {\n  ShardByRow = 0,\n  ShardByCol = 1\n};\n\n\n// Default Blocking Strategy\ntemplate<typename ResScalar, typename LhsScalar, typename RhsScalar, typename StorageIndex, int ShardingType = ShardByCol>\nclass TensorContractionBlocking {\n public:\n\n /*\n   adding EIGEN_DEVICE_FUNC unconditionally to 'TensorContractionBlocking' constructor in `TensorContractionBlocking.h`\n     requires adding EIGEN_DEVICE_FUNC to `computeProductBlockingSizes` in `GeneralBlockPanelKernel.h`\n     which in turn, requires adding EIGEN_DEVICE_FUNC to `evaluateProductBlockingSizesHeuristic` in `GeneralBlockPanelKernel.h`\n     which in turn, requires adding EIGEN_DEVICE_FUNC to `manage_caching_sizes` in `GeneralBlockPanelKernel.h`\n     (else HIPCC will error out)\n\n   However adding EIGEN_DEVICE_FUNC to `manage_caching_sizes` in `GeneralBlockPanelKernel.h`\n   results in NVCC erroring out with the following error\n\n   ../Eigen/src/Core/products/GeneralBlockPanelKernel.h(57): error #2901:\n      dynamic initialization is not supported for function-scope static variables within a __device__/__global__ function\n */\n\n  #if !defined(EIGEN_HIPCC)\n  EIGEN_DEVICE_FUNC\n  #endif\n TensorContractionBlocking(StorageIndex k, StorageIndex m, StorageIndex n, StorageIndex num_threads = 1) :\n      kc_(k), mc_(m), nc_(n)\n  {\n    if (ShardingType == ShardByCol) {\n      computeProductBlockingSizes<LhsScalar, RhsScalar, 1>(kc_, mc_, nc_, num_threads);\n    }\n    else {\n      computeProductBlockingSizes<LhsScalar, RhsScalar, 1>(kc_, nc_, mc_, num_threads);\n    }\n\n    const int rhs_packet_size = internal::packet_traits<RhsScalar>::size;\n    kc_ = (rhs_packet_size <= 8 || kc_ <= rhs_packet_size) ?\n      kc_ : (kc_ / rhs_packet_size) * rhs_packet_size;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE StorageIndex kc() const { return kc_; }\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE StorageIndex mc() const { return mc_; }\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE StorageIndex nc() const { return nc_; }\n\n private:\n  StorageIndex kc_;\n  StorageIndex mc_;\n  StorageIndex nc_;\n};\n\n} // end namespace internal\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_BLOCKING_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionCuda.h",
    "content": "\n#if defined(__clang__) || defined(__GNUC__)\n#warning \"Deprecated header file, please either include the main Eigen/CXX11/Tensor header or the respective TensorContractionGpu.h file\"\n#endif\n\n#include \"TensorContractionGpu.h\"\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionGpu.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014-2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n// Copyright (C) 2015 Navdeep Jaitly <ndjaitly@google.com>\n// Copyright (C) 2014 Eric Martin <eric@ericmart.in>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_GPU_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_GPU_H\n\n#if defined(EIGEN_USE_GPU) && defined(EIGEN_GPUCC)\n\nnamespace Eigen {\n\ntemplate<typename Scalar, typename Index, typename LhsMapper,\n         typename RhsMapper, typename OutputMapper, bool needs_edge_check>\n__device__ EIGEN_STRONG_INLINE void\nEigenContractionKernelInternal(const LhsMapper lhs, const RhsMapper rhs,\n                               const OutputMapper output, Scalar* lhs_shmem, Scalar* rhs_shmem,\n                       const Index m_size, const Index n_size, const Index k_size) {\n\n  const Index m_block_idx = blockIdx.x;\n  const Index n_block_idx = blockIdx.y;\n\n  const Index base_m = 64 * m_block_idx;\n  const Index base_n = 64 * n_block_idx;\n\n  // declare and initialize 64 registers for output 8x8 block\n\n  // prefetch registers\n  Scalar lhs_pf0;\n  Scalar lhs_pf1;\n  Scalar lhs_pf2;\n  Scalar lhs_pf3;\n  Scalar lhs_pf4;\n  Scalar lhs_pf5;\n  Scalar lhs_pf6;\n  Scalar lhs_pf7;\n\n  Scalar rhs_pf0;\n  Scalar rhs_pf1;\n  Scalar rhs_pf2;\n  Scalar rhs_pf3;\n  Scalar rhs_pf4;\n  Scalar rhs_pf5;\n  Scalar rhs_pf6;\n  Scalar rhs_pf7;\n\n  // shared memory is formatted\n  // (contract idx in block, nocontract idx in block, block idx)\n  // where block idx is column major. This transposition limits the number of\n  // bank conflicts when reading the LHS. The core idea is that since the contracting\n  // index is shared by both sides, then the contracting index should be in threadIdx.x.\n\n  // On the LHS, we pad each row inside of each block with an extra element. This makes\n  // each block 8 rows of 9 elements, which is 72 elements. This gives no bank conflicts\n  // on writes and very few 2-way conflicts on reads. There is an 8x8 grid of these blocks.\n\n  // On the RHS we just add 8 padding elements to the end of each block. This gives no bank\n  // conflicts on writes and also none on reads.\n\n  // storage indices\n  const Index lhs_store_idx_base = threadIdx.y * 72 + threadIdx.x * 9 + threadIdx.z;\n  const Index rhs_store_idx_base = threadIdx.y * 72 + threadIdx.z * 8 + threadIdx.x;\n\n  const Index lhs_store_idx_0 = lhs_store_idx_base + 576 * 0;\n  const Index lhs_store_idx_1 = lhs_store_idx_base + 576 * 1;\n  const Index lhs_store_idx_2 = lhs_store_idx_base + 576 * 2;\n  const Index lhs_store_idx_3 = lhs_store_idx_base + 576 * 3;\n  const Index lhs_store_idx_4 = lhs_store_idx_base + 576 * 4;\n  const Index lhs_store_idx_5 = lhs_store_idx_base + 576 * 5;\n  const Index lhs_store_idx_6 = lhs_store_idx_base + 576 * 6;\n  const Index lhs_store_idx_7 = lhs_store_idx_base + 576 * 7;\n\n  const Index rhs_store_idx_0 = rhs_store_idx_base + 576 * 0;\n  const Index rhs_store_idx_1 = rhs_store_idx_base + 576 * 1;\n  const Index rhs_store_idx_2 = rhs_store_idx_base + 576 * 2;\n  const Index rhs_store_idx_3 = rhs_store_idx_base + 576 * 3;\n  const Index rhs_store_idx_4 = rhs_store_idx_base + 576 * 4;\n  const Index rhs_store_idx_5 = rhs_store_idx_base + 576 * 5;\n  const Index rhs_store_idx_6 = rhs_store_idx_base + 576 * 6;\n  const Index rhs_store_idx_7 = rhs_store_idx_base + 576 * 7;\n\n  // in the loading code, the following variables are important:\n  // threadIdx.x: the vertical position in an 8x8 block\n  // threadIdx.y: the vertical index of the 8x8 block in the grid\n  // threadIdx.z: the horizontal position in an 8x8 block\n  // k: the horizontal index of the 8x8 block in the grid\n  //\n  // The k parameter is implicit (it was the loop counter for a loop that went\n  // from 0 to <8, but now that loop is unrolled in the below code.\n\n  const Index load_idx_vert = threadIdx.x + 8 * threadIdx.y;\n  const Index lhs_vert = base_m + load_idx_vert;\n\n#define prefetchIntoRegisters(base_k)                           \\\n  {                                                             \\\n    lhs_pf0 = conv(0);                                          \\\n    lhs_pf1 = conv(0);                                          \\\n    lhs_pf2 = conv(0);                                          \\\n    lhs_pf3 = conv(0);                                          \\\n    lhs_pf4 = conv(0);                                          \\\n    lhs_pf5 = conv(0);                                          \\\n    lhs_pf6 = conv(0);                                          \\\n    lhs_pf7 = conv(0);                                          \\\n                                                                \\\n    rhs_pf0 = conv(0);                                          \\\n    rhs_pf1 = conv(0);                                          \\\n    rhs_pf2 = conv(0);                                          \\\n    rhs_pf3 = conv(0);                                          \\\n    rhs_pf4 = conv(0);                                          \\\n    rhs_pf5 = conv(0);                                          \\\n    rhs_pf6 = conv(0);                                          \\\n    rhs_pf7 = conv(0);                                          \\\n                                                                \\\n    if (!needs_edge_check || lhs_vert < m_size) {               \\\n      const Index lhs_horiz_0 = base_k + threadIdx.z + 0 * 8;   \\\n      const Index lhs_horiz_1 = base_k + threadIdx.z + 1 * 8;   \\\n      const Index lhs_horiz_2 = base_k + threadIdx.z + 2 * 8;   \\\n      const Index lhs_horiz_3 = base_k + threadIdx.z + 3 * 8;   \\\n      const Index lhs_horiz_4 = base_k + threadIdx.z + 4 * 8;   \\\n      const Index lhs_horiz_5 = base_k + threadIdx.z + 5 * 8;   \\\n      const Index lhs_horiz_6 = base_k + threadIdx.z + 6 * 8;   \\\n      const Index lhs_horiz_7 = base_k + threadIdx.z + 7 * 8;   \\\n                                                                \\\n      if (!needs_edge_check || lhs_horiz_7 < k_size) {          \\\n        lhs_pf0 = lhs(lhs_vert, lhs_horiz_0);                   \\\n        lhs_pf1 = lhs(lhs_vert, lhs_horiz_1);                   \\\n        lhs_pf2 = lhs(lhs_vert, lhs_horiz_2);                   \\\n        lhs_pf3 = lhs(lhs_vert, lhs_horiz_3);                   \\\n        lhs_pf4 = lhs(lhs_vert, lhs_horiz_4);                   \\\n        lhs_pf5 = lhs(lhs_vert, lhs_horiz_5);                   \\\n        lhs_pf6 = lhs(lhs_vert, lhs_horiz_6);                   \\\n        lhs_pf7 = lhs(lhs_vert, lhs_horiz_7);                   \\\n      } else if (lhs_horiz_6 < k_size) {                        \\\n        lhs_pf0 = lhs(lhs_vert, lhs_horiz_0);                   \\\n        lhs_pf1 = lhs(lhs_vert, lhs_horiz_1);                   \\\n        lhs_pf2 = lhs(lhs_vert, lhs_horiz_2);                   \\\n        lhs_pf3 = lhs(lhs_vert, lhs_horiz_3);                   \\\n        lhs_pf4 = lhs(lhs_vert, lhs_horiz_4);                   \\\n        lhs_pf5 = lhs(lhs_vert, lhs_horiz_5);                   \\\n        lhs_pf6 = lhs(lhs_vert, lhs_horiz_6);                   \\\n      } else if (lhs_horiz_5 < k_size) {                        \\\n        lhs_pf0 = lhs(lhs_vert, lhs_horiz_0);                   \\\n        lhs_pf1 = lhs(lhs_vert, lhs_horiz_1);                   \\\n        lhs_pf2 = lhs(lhs_vert, lhs_horiz_2);                   \\\n        lhs_pf3 = lhs(lhs_vert, lhs_horiz_3);                   \\\n        lhs_pf4 = lhs(lhs_vert, lhs_horiz_4);                   \\\n        lhs_pf5 = lhs(lhs_vert, lhs_horiz_5);                   \\\n      } else if (lhs_horiz_4 < k_size) {                        \\\n        lhs_pf0 = lhs(lhs_vert, lhs_horiz_0);                   \\\n        lhs_pf1 = lhs(lhs_vert, lhs_horiz_1);                   \\\n        lhs_pf2 = lhs(lhs_vert, lhs_horiz_2);                   \\\n        lhs_pf3 = lhs(lhs_vert, lhs_horiz_3);                   \\\n        lhs_pf4 = lhs(lhs_vert, lhs_horiz_4);                   \\\n      } else if (lhs_horiz_3 < k_size) {                        \\\n        lhs_pf0 = lhs(lhs_vert, lhs_horiz_0);                   \\\n        lhs_pf1 = lhs(lhs_vert, lhs_horiz_1);                   \\\n        lhs_pf2 = lhs(lhs_vert, lhs_horiz_2);                   \\\n        lhs_pf3 = lhs(lhs_vert, lhs_horiz_3);                   \\\n      } else if (lhs_horiz_2 < k_size) {                        \\\n        lhs_pf0 = lhs(lhs_vert, lhs_horiz_0);                   \\\n        lhs_pf1 = lhs(lhs_vert, lhs_horiz_1);                   \\\n        lhs_pf2 = lhs(lhs_vert, lhs_horiz_2);                   \\\n      } else if (lhs_horiz_1 < k_size) {                        \\\n        lhs_pf0 = lhs(lhs_vert, lhs_horiz_0);                   \\\n        lhs_pf1 = lhs(lhs_vert, lhs_horiz_1);                   \\\n      } else if (lhs_horiz_0 < k_size) {                        \\\n        lhs_pf0 = lhs(lhs_vert, lhs_horiz_0);                   \\\n      }                                                         \\\n    }                                                           \\\n                                                                \\\n    const Index rhs_vert = base_k + load_idx_vert;              \\\n    if (!needs_edge_check || rhs_vert < k_size) {               \\\n      const Index rhs_horiz_0 = base_n + threadIdx.z + 0 * 8;   \\\n      const Index rhs_horiz_1 = base_n + threadIdx.z + 1 * 8;   \\\n      const Index rhs_horiz_2 = base_n + threadIdx.z + 2 * 8;   \\\n      const Index rhs_horiz_3 = base_n + threadIdx.z + 3 * 8;   \\\n      const Index rhs_horiz_4 = base_n + threadIdx.z + 4 * 8;   \\\n      const Index rhs_horiz_5 = base_n + threadIdx.z + 5 * 8;   \\\n      const Index rhs_horiz_6 = base_n + threadIdx.z + 6 * 8;   \\\n      const Index rhs_horiz_7 = base_n + threadIdx.z + 7 * 8;   \\\n                                                                \\\n      if (rhs_horiz_7 < n_size) {                               \\\n        rhs_pf0 = rhs(rhs_vert, rhs_horiz_0);                   \\\n        rhs_pf1 = rhs(rhs_vert, rhs_horiz_1);                   \\\n        rhs_pf2 = rhs(rhs_vert, rhs_horiz_2);                   \\\n        rhs_pf3 = rhs(rhs_vert, rhs_horiz_3);                   \\\n        rhs_pf4 = rhs(rhs_vert, rhs_horiz_4);                   \\\n        rhs_pf5 = rhs(rhs_vert, rhs_horiz_5);                   \\\n        rhs_pf6 = rhs(rhs_vert, rhs_horiz_6);                   \\\n        rhs_pf7 = rhs(rhs_vert, rhs_horiz_7);                   \\\n      } else if (rhs_horiz_6 < n_size) {                        \\\n        rhs_pf0 = rhs(rhs_vert, rhs_horiz_0);                   \\\n        rhs_pf1 = rhs(rhs_vert, rhs_horiz_1);                   \\\n        rhs_pf2 = rhs(rhs_vert, rhs_horiz_2);                   \\\n        rhs_pf3 = rhs(rhs_vert, rhs_horiz_3);                   \\\n        rhs_pf4 = rhs(rhs_vert, rhs_horiz_4);                   \\\n        rhs_pf5 = rhs(rhs_vert, rhs_horiz_5);                   \\\n        rhs_pf6 = rhs(rhs_vert, rhs_horiz_6);                   \\\n      } else if (rhs_horiz_5 < n_size) {                        \\\n        rhs_pf0 = rhs(rhs_vert, rhs_horiz_0);                   \\\n        rhs_pf1 = rhs(rhs_vert, rhs_horiz_1);                   \\\n        rhs_pf2 = rhs(rhs_vert, rhs_horiz_2);                   \\\n        rhs_pf3 = rhs(rhs_vert, rhs_horiz_3);                   \\\n        rhs_pf4 = rhs(rhs_vert, rhs_horiz_4);                   \\\n        rhs_pf5 = rhs(rhs_vert, rhs_horiz_5);                   \\\n      } else if (rhs_horiz_4 < n_size) {                        \\\n        rhs_pf0 = rhs(rhs_vert, rhs_horiz_0);                   \\\n        rhs_pf1 = rhs(rhs_vert, rhs_horiz_1);                   \\\n        rhs_pf2 = rhs(rhs_vert, rhs_horiz_2);                   \\\n        rhs_pf3 = rhs(rhs_vert, rhs_horiz_3);                   \\\n        rhs_pf4 = rhs(rhs_vert, rhs_horiz_4);                   \\\n      } else if (rhs_horiz_3 < n_size) {                        \\\n        rhs_pf0 = rhs(rhs_vert, rhs_horiz_0);                   \\\n        rhs_pf1 = rhs(rhs_vert, rhs_horiz_1);                   \\\n        rhs_pf2 = rhs(rhs_vert, rhs_horiz_2);                   \\\n        rhs_pf3 = rhs(rhs_vert, rhs_horiz_3);                   \\\n      } else if (rhs_horiz_2 < n_size) {                        \\\n        rhs_pf0 = rhs(rhs_vert, rhs_horiz_0);                   \\\n        rhs_pf1 = rhs(rhs_vert, rhs_horiz_1);                   \\\n        rhs_pf2 = rhs(rhs_vert, rhs_horiz_2);                   \\\n      } else if (rhs_horiz_1 < n_size) {                        \\\n        rhs_pf0 = rhs(rhs_vert, rhs_horiz_0);                   \\\n        rhs_pf1 = rhs(rhs_vert, rhs_horiz_1);                   \\\n      } else if (rhs_horiz_0 < n_size) {                        \\\n        rhs_pf0 = rhs(rhs_vert, rhs_horiz_0);                   \\\n      }                                                         \\\n    }                                                           \\\n  }                                                             \\\n\n#define writeRegToShmem(_)                      \\\n  lhs_shmem[lhs_store_idx_0] = lhs_pf0;         \\\n  rhs_shmem[rhs_store_idx_0] = rhs_pf0;         \\\n                                                \\\n  lhs_shmem[lhs_store_idx_1] = lhs_pf1;         \\\n  rhs_shmem[rhs_store_idx_1] = rhs_pf1;         \\\n                                                \\\n  lhs_shmem[lhs_store_idx_2] = lhs_pf2;         \\\n  rhs_shmem[rhs_store_idx_2] = rhs_pf2;         \\\n                                                \\\n  lhs_shmem[lhs_store_idx_3] = lhs_pf3;         \\\n  rhs_shmem[rhs_store_idx_3] = rhs_pf3;         \\\n                                                \\\n  lhs_shmem[lhs_store_idx_4] = lhs_pf4;         \\\n  rhs_shmem[rhs_store_idx_4] = rhs_pf4;         \\\n                                                \\\n  lhs_shmem[lhs_store_idx_5] = lhs_pf5;         \\\n  rhs_shmem[rhs_store_idx_5] = rhs_pf5;         \\\n                                                \\\n  lhs_shmem[lhs_store_idx_6] = lhs_pf6;         \\\n  rhs_shmem[rhs_store_idx_6] = rhs_pf6;         \\\n                                                \\\n  lhs_shmem[lhs_store_idx_7] = lhs_pf7;         \\\n  rhs_shmem[rhs_store_idx_7] = rhs_pf7;         \\\n\n  // declare and initialize result array\n#define res(i, j) _res_##i##j\n#define initResultRow(i)                        \\\n  Scalar res(i, 0) = conv(0);                   \\\n  Scalar res(i, 1) = conv(0);                   \\\n  Scalar res(i, 2) = conv(0);                   \\\n  Scalar res(i, 3) = conv(0);                   \\\n  Scalar res(i, 4) = conv(0);                   \\\n  Scalar res(i, 5) = conv(0);                   \\\n  Scalar res(i, 6) = conv(0);                   \\\n  Scalar res(i, 7) = conv(0);                   \\\n\n  internal::scalar_cast_op<int, Scalar> conv;\n  initResultRow(0);\n  initResultRow(1);\n  initResultRow(2);\n  initResultRow(3);\n  initResultRow(4);\n  initResultRow(5);\n  initResultRow(6);\n  initResultRow(7);\n#undef initResultRow\n\n  for (Index base_k = 0; base_k < k_size; base_k += 64) {\n    // wait for previous iteration to finish with shmem. Despite common sense,\n    // the code is a bit faster with this here then at bottom of loop\n    __syncthreads();\n\n    prefetchIntoRegisters(base_k);\n    writeRegToShmem();\n\n    #undef prefetchIntoRegisters\n    #undef writeRegToShmem\n\n    // wait for shared mem packing to be done before starting computation\n    __syncthreads();\n\n    // compute 8x8 matrix product by outer product. This involves packing one column\n    // of LHS and one row of RHS into registers (takes 16 registers).\n\n#define lcol(i) _lcol##i\n    Scalar lcol(0);\n    Scalar lcol(1);\n    Scalar lcol(2);\n    Scalar lcol(3);\n    Scalar lcol(4);\n    Scalar lcol(5);\n    Scalar lcol(6);\n    Scalar lcol(7);\n\n#define rrow(j) _rrow##j\n    Scalar rrow(0);\n    Scalar rrow(1);\n    Scalar rrow(2);\n    Scalar rrow(3);\n    Scalar rrow(4);\n    Scalar rrow(5);\n    Scalar rrow(6);\n    Scalar rrow(7);\n\n    // Now x corresponds to k, y to m, and z to n\n    const Scalar* lhs_block = &lhs_shmem[threadIdx.x + 9 * threadIdx.y];\n    const Scalar* rhs_block = &rhs_shmem[threadIdx.x + 8 * threadIdx.z];\n\n#define lhs_element(i, j) lhs_block[72 * ((i) + 8 * (j))]\n#define rhs_element(i, j) rhs_block[72 * ((i) + 8 * (j))]\n\n#define loadData(i, j)                          \\\n    lcol(0) = lhs_element(0, j);               \\\n    rrow(0) = rhs_element(i, 0);               \\\n    lcol(1) = lhs_element(1, j);               \\\n    rrow(1) = rhs_element(i, 1);               \\\n    lcol(2) = lhs_element(2, j);               \\\n    rrow(2) = rhs_element(i, 2);               \\\n    lcol(3) = lhs_element(3, j);               \\\n    rrow(3) = rhs_element(i, 3);               \\\n    lcol(4) = lhs_element(4, j);               \\\n    rrow(4) = rhs_element(i, 4);               \\\n    lcol(5) = lhs_element(5, j);               \\\n    rrow(5) = rhs_element(i, 5);               \\\n    lcol(6) = lhs_element(6, j);               \\\n    rrow(6) = rhs_element(i, 6);               \\\n    lcol(7) = lhs_element(7, j);               \\\n    rrow(7) = rhs_element(i, 7);               \\\n\n#define computeCol(j)                           \\\n    res(0, j) += lcol(0) * rrow(j);             \\\n    res(1, j) += lcol(1) * rrow(j);             \\\n    res(2, j) += lcol(2) * rrow(j);             \\\n    res(3, j) += lcol(3) * rrow(j);             \\\n    res(4, j) += lcol(4) * rrow(j);             \\\n    res(5, j) += lcol(5) * rrow(j);             \\\n    res(6, j) += lcol(6) * rrow(j);             \\\n    res(7, j) += lcol(7) * rrow(j);             \\\n\n#define computePass(i)                          \\\n    loadData(i, i);                             \\\n                                                \\\n    computeCol(0);                              \\\n    computeCol(1);                              \\\n    computeCol(2);                              \\\n    computeCol(3);                              \\\n    computeCol(4);                              \\\n    computeCol(5);                              \\\n    computeCol(6);                              \\\n    computeCol(7);                              \\\n\n    computePass(0);\n    computePass(1);\n    computePass(2);\n    computePass(3);\n    computePass(4);\n    computePass(5);\n    computePass(6);\n    computePass(7);\n\n#undef lcol\n#undef rrow\n#undef lhs_element\n#undef rhs_element\n#undef loadData\n#undef computeCol\n#undef computePass\n  } // end loop over k\n\n  // we've now iterated over all of the large (ie width 64) k blocks and\n  // accumulated results in registers. At this point thread (x, y, z) contains\n  // the sum across all big k blocks of the product of little k block of index (x, y)\n  // with block of index (y, z). To compute the final output, we need to reduce\n  // the 8 threads over y by summation.\n#if defined(EIGEN_HIPCC) || (defined(EIGEN_CUDA_SDK_VER) && EIGEN_CUDA_SDK_VER < 90000)\n#define shuffleInc(i, j, mask) res(i, j) += __shfl_xor(res(i, j), mask)\n#else\n#define shuffleInc(i, j, mask) res(i, j) += __shfl_xor_sync(0xFFFFFFFF, res(i, j), mask)\n#endif\n\n#define reduceRow(i, mask)                      \\\n  shuffleInc(i, 0, mask);                       \\\n  shuffleInc(i, 1, mask);                       \\\n  shuffleInc(i, 2, mask);                       \\\n  shuffleInc(i, 3, mask);                       \\\n  shuffleInc(i, 4, mask);                       \\\n  shuffleInc(i, 5, mask);                       \\\n  shuffleInc(i, 6, mask);                       \\\n  shuffleInc(i, 7, mask);                       \\\n\n#define reduceMatrix(mask)                      \\\n  reduceRow(0, mask);                           \\\n  reduceRow(1, mask);                           \\\n  reduceRow(2, mask);                           \\\n  reduceRow(3, mask);                           \\\n  reduceRow(4, mask);                           \\\n  reduceRow(5, mask);                           \\\n  reduceRow(6, mask);                           \\\n  reduceRow(7, mask);                           \\\n\n  // actually perform the reduction, now each thread of index (_, y, z)\n  // contains the correct values in its registers that belong in the output\n  // block\n  reduceMatrix(1);\n  reduceMatrix(2);\n  reduceMatrix(4);\n\n#undef shuffleInc\n#undef reduceRow\n#undef reduceMatrix\n\n  // now we need to copy the 64 values into main memory. We can't split work\n  // among threads because all variables are in registers. There's 2 ways\n  // to do this:\n  // (1) have 1 thread do 64 writes from registers into global memory\n  // (2) have 1 thread do 64 writes into shared memory, and then 8 threads\n  //     each do 8 writes into global memory. We can just overwrite the shared\n  //     memory from the problem we just solved.\n  // (2) is slightly faster than (1) due to less branching and more ILP\n\n  // TODO: won't yield much gain, but could just use currently unused shared mem\n  //       and then we won't have to sync\n  // wait for shared mem to be out of use\n  __syncthreads();\n\n#define writeResultShmem(i, j)                                          \\\n  lhs_shmem[i + 8 * threadIdx.y + 64 * threadIdx.z + 512 * j] = res(i, j); \\\n\n#define writeRow(i)                             \\\n  writeResultShmem(i, 0);                       \\\n  writeResultShmem(i, 1);                       \\\n  writeResultShmem(i, 2);                       \\\n  writeResultShmem(i, 3);                       \\\n  writeResultShmem(i, 4);                       \\\n  writeResultShmem(i, 5);                       \\\n  writeResultShmem(i, 6);                       \\\n  writeResultShmem(i, 7);                       \\\n\n  if (threadIdx.x == 0) {\n    writeRow(0);\n    writeRow(1);\n    writeRow(2);\n    writeRow(3);\n    writeRow(4);\n    writeRow(5);\n    writeRow(6);\n    writeRow(7);\n  }\n#undef writeResultShmem\n#undef writeRow\n\n  const int max_i_write = numext::mini((int)((m_size - base_m - threadIdx.y + 7) / 8), 8);\n  const int max_j_write = numext::mini((int)((n_size - base_n - threadIdx.z + 7) / 8), 8);\n\n  if (threadIdx.x < max_i_write) {\n    if (max_j_write == 8) {\n      // TODO: can i trade bank conflicts for coalesced writes?\n      Scalar val0 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 0];\n      Scalar val1 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 1];\n      Scalar val2 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 2];\n      Scalar val3 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 3];\n      Scalar val4 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 4];\n      Scalar val5 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 5];\n      Scalar val6 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 6];\n      Scalar val7 = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * 7];\n\n      output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 0) = val0;\n      output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 1) = val1;\n      output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 2) = val2;\n      output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 3) = val3;\n      output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 4) = val4;\n      output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 5) = val5;\n      output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 6) = val6;\n      output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * 7) = val7;\n    } else {\n#pragma unroll 7\n      for (int j = 0; j < max_j_write; j++) {\n        Scalar val = lhs_shmem[threadIdx.x + 8 * threadIdx.y + 64 * threadIdx.z + 512 * j];\n        output(base_m + threadIdx.y + 8 * threadIdx.x, base_n + threadIdx.z + 8 * j) = val;\n      }\n    }\n  }\n#undef res\n}\n\n\ntemplate<typename Scalar, typename Index, typename LhsMapper,\n         typename RhsMapper, typename OutputMapper>\n__global__ void\n#if defined(EIGEN_HIPCC)\n__launch_bounds__(512, 1)\n#else\n__launch_bounds__(512)\n#endif\nEigenContractionKernel(const LhsMapper lhs, const RhsMapper rhs,\n                       const OutputMapper output,\n                       const Index m_size, const Index n_size, const Index k_size) {\n  __shared__ Scalar lhs_shmem[72 * 64];\n  __shared__ Scalar rhs_shmem[72 * 64];\n\n  const Index m_block_idx = blockIdx.x;\n  const Index n_block_idx = blockIdx.y;\n\n  const Index base_m = 64 * m_block_idx;\n  const Index base_n = 64 * n_block_idx;\n\n  if (base_m + 63 < m_size && base_n + 63 < n_size) {\n    EigenContractionKernelInternal<Scalar, Index, LhsMapper, RhsMapper, OutputMapper, false>(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size);\n  } else {\n    EigenContractionKernelInternal<Scalar, Index, LhsMapper, RhsMapper, OutputMapper, true>(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size);\n  }\n}\n\n\ntemplate<typename Index, typename LhsMapper,\n         typename RhsMapper, typename OutputMapper, bool CHECK_LHS_BOUNDARY,\n         bool CHECK_RHS_BOUNDARY>\n__device__ __forceinline__ void\nEigenFloatContractionKernelInternal16x16(const LhsMapper lhs, const RhsMapper rhs,\n                       const OutputMapper output, float2 lhs_shmem2[][16],\n                       float2 rhs_shmem2[][8], const Index m_size,\n                       const Index n_size, const Index k_size,\n                       const Index base_m, const Index base_n) {\n\n  // prefetch registers\n  float4 lhs_pf0, rhs_pf0;\n\n  float4 results[4];\n  for (int i=0; i < 4; i++) {\n    results[i].x = results[i].y = results[i].z = results[i].w = 0;\n  }\n\n#define prefetch_lhs(reg, row, col)                            \\\n    if (!CHECK_LHS_BOUNDARY) {                                 \\\n      if (col < k_size) {                                      \\\n        reg =lhs.template loadPacket<float4,Unaligned>(row, col);     \\\n      }                                                        \\\n    } else {                                                   \\\n      if (col < k_size) {                                      \\\n        if (row + 3 < m_size) {                                \\\n          reg =lhs.template loadPacket<float4,Unaligned>(row, col);   \\\n        } else if (row + 2 < m_size) {                         \\\n          reg.x =lhs(row + 0, col);                            \\\n          reg.y =lhs(row + 1, col);                            \\\n          reg.z =lhs(row + 2, col);                            \\\n        } else if (row + 1 < m_size) {                         \\\n          reg.x =lhs(row + 0, col);                            \\\n          reg.y =lhs(row + 1, col);                            \\\n        } else if (row  < m_size) {                            \\\n          reg.x =lhs(row + 0, col);                            \\\n        }                                                      \\\n      }                                                        \\\n    }\t\t\t\t\t\t\t       \\\n\n  Index lhs_vert = base_m+threadIdx.x*4;\n\n  for (Index k = 0; k < k_size; k += 16) {\n\n    lhs_pf0 = internal::pset1<float4>(0);\n    rhs_pf0 = internal::pset1<float4>(0);\n\n    Index lhs_horiz = threadIdx.y+k;\n    prefetch_lhs(lhs_pf0, lhs_vert, lhs_horiz)\n\n    Index rhs_vert = k+(threadIdx.x%4)*4;\n    Index rhs_horiz0 = (threadIdx.x>>2)+threadIdx.y*4+base_n;\n\n    if (!CHECK_RHS_BOUNDARY) {\n      if ((rhs_vert + 3) < k_size) {\n        // just CHECK_RHS_BOUNDARY\n        rhs_pf0 = rhs.template loadPacket<float4,Unaligned>(rhs_vert, rhs_horiz0);\n      } else if (rhs_vert + 2 < k_size) {\n        // just CHECK_RHS_BOUNDARY\n        rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n        rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0);\n        rhs_pf0.z = rhs(rhs_vert + 2, rhs_horiz0);\n      } else if (rhs_vert + 1 < k_size) {\n        rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n        rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0);\n      } else if (rhs_vert  < k_size) {\n        rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n      }\n    } else {\n      if (rhs_horiz0 < n_size) {\n        if ((rhs_vert + 3) < k_size) {\n          rhs_pf0 = rhs.template loadPacket<float4,Unaligned>(rhs_vert, rhs_horiz0);\n        } else if ((rhs_vert + 2) < k_size) {\n          rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n          rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0);\n          rhs_pf0.z = rhs(rhs_vert + 2, rhs_horiz0);\n        } else if ((rhs_vert + 1) < k_size) {\n          rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n          rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0);\n        } else if (rhs_vert  < k_size) {\n          rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n        }\n      }\n    }\n    float x1, x2 ;\n    // the following can be a bitwise operation..... some day.\n    if((threadIdx.x%8) < 4) {\n      x1 = rhs_pf0.y;\n      x2 = rhs_pf0.w;\n    } else {\n      x1 = rhs_pf0.x;\n      x2 = rhs_pf0.z;\n    }\n    #if defined(EIGEN_HIPCC) || (defined(EIGEN_CUDA_SDK_VER) && EIGEN_CUDA_SDK_VER < 90000)\n    x1 = __shfl_xor(x1, 4);\n    x2 = __shfl_xor(x2, 4);\n    #else\n    x1 = __shfl_xor_sync(0xFFFFFFFF, x1, 4);\n    x2 = __shfl_xor_sync(0xFFFFFFFF, x2, 4);\n    #endif\n    if((threadIdx.x%8) < 4) {\n      rhs_pf0.y = x1;\n      rhs_pf0.w = x2;\n    } else {\n      rhs_pf0.x = x1;\n      rhs_pf0.z = x2;\n    }\n\n    // We have 64 features.\n    // Row 0 -> times (0, 4, 8, 12, 1, 5, 9, 13) for features 0, 1.\n    // Row 1 -> times (0, 4, 8, 12, 1, 5, 9, 13) for features 2, 3.\n    // ...\n    // Row 31 -> times (0, 4, 8, 12, 1, 5, 9, 13) for features 62, 63\n    // Row 32 -> times (2, 6, 10, 14, 3, 7, 11, 15) for features 0, 1\n    // ...\n    rhs_shmem2[(threadIdx.x>>3)+ threadIdx.y*2][threadIdx.x%8] = make_float2(rhs_pf0.x, rhs_pf0.y);\n    rhs_shmem2[(threadIdx.x>>3)+ threadIdx.y*2+32][threadIdx.x%8] = make_float2(rhs_pf0.z, rhs_pf0.w);\n\n    // Row 0 (time 0) -> features (0, 1), (4, 5), .. (28, 29), (32, 33), ..  (60, 61)\n    // Row 1 (time 1) -> features (0, 1), (4, 5), .. (28, 29), (32, 33), ..  (60, 61)\n    // ...\n    // Row 15 (time 15) -> features (0, 1), (4, 5), .. (28, 29), (32, 33), ..  (60, 61)\n    // Row 16 (time 0) -> features (2, 3), (6, 7), .. (30, 31), (34, 35), ..  (62, 63)\n    // ...\n\n    lhs_shmem2[threadIdx.y][threadIdx.x] = make_float2(lhs_pf0.x, lhs_pf0.y);\n    lhs_shmem2[threadIdx.y+16][threadIdx.x] = make_float2(lhs_pf0.z, lhs_pf0.w);\n\n\n#define add_vals(fl1, fl2, fr1, fr2)\\\n    results[0].x += fl1.x * fr1.x;\\\n    results[0].y += fl1.y * fr1.x;\\\n    results[0].z += fl2.x * fr1.x;\\\n    results[0].w += fl2.y * fr1.x;\\\n\\\n    results[1].x += fl1.x * fr1.y;\\\n    results[1].y += fl1.y * fr1.y;\\\n    results[1].z += fl2.x * fr1.y;\\\n    results[1].w += fl2.y * fr1.y;\\\n\\\n    results[2].x += fl1.x * fr2.x;\\\n    results[2].y += fl1.y * fr2.x;\\\n    results[2].z += fl2.x * fr2.x;\\\n    results[2].w += fl2.y * fr2.x;\\\n\\\n    results[3].x += fl1.x * fr2.y;\\\n    results[3].y += fl1.y * fr2.y;\\\n    results[3].z += fl2.x * fr2.y;\\\n    results[3].w += fl2.y * fr2.y;\\\n\n    __syncthreads();\n\n    // Do the multiplies.\n    #pragma unroll\n    for (int koff = 0; koff < 16; koff ++) {\n      // 32 x threads.\n      float2 fl1 = lhs_shmem2[koff][threadIdx.x];\n      float2 fl2 = lhs_shmem2[koff + 16][threadIdx.x];\n\n      int start_feature = threadIdx.y * 4;\n      float2 fr1 = rhs_shmem2[(start_feature>>1) + 32*((koff%4)/2)][koff/4 + (koff%2)*4];\n      float2 fr2 = rhs_shmem2[(start_feature>>1) + 1 + 32*((koff%4)/2)][koff/4 + (koff%2)*4];\n\n      add_vals(fl1, fl2, fr1, fr2)\n    }\n    __syncthreads();\n  }\n\n#undef prefetch_lhs\n#undef add_vals\n\n  Index horiz_base = threadIdx.y*4+base_n;\n  if (!CHECK_LHS_BOUNDARY && !CHECK_RHS_BOUNDARY) {\n    for (int i = 0; i < 4; i++) {\n      output(lhs_vert, horiz_base + i) = results[i].x;\n      output(lhs_vert + 1, horiz_base + i) = results[i].y;\n      output(lhs_vert + 2, horiz_base + i) = results[i].z;\n      output(lhs_vert + 3, horiz_base + i) = results[i].w;\n    }\n  } else if (!CHECK_RHS_BOUNDARY) {\n    // CHECK LHS\n    if (lhs_vert + 3 < m_size) {\n      for (int i = 0; i < 4; i++) {\n        output(lhs_vert, horiz_base + i) = results[i].x;\n        output(lhs_vert + 1, horiz_base + i) = results[i].y;\n        output(lhs_vert + 2, horiz_base + i) = results[i].z;\n        output(lhs_vert + 3, horiz_base + i) = results[i].w;\n      }\n    } else if (lhs_vert + 2 < m_size) {\n      for (int i = 0; i < 4; i++) {\n        output(lhs_vert, horiz_base + i) = results[i].x;\n        output(lhs_vert + 1, horiz_base + i) = results[i].y;\n        output(lhs_vert + 2, horiz_base + i) = results[i].z;\n      }\n    } else if (lhs_vert + 1 < m_size) {\n      for (int i = 0; i < 4; i++) {\n        output(lhs_vert, horiz_base + i) = results[i].x;\n        output(lhs_vert + 1, horiz_base + i) = results[i].y;\n      }\n    } else if (lhs_vert  < m_size) {\n      for (int i = 0; i < 4; i++) {\n        output(lhs_vert, horiz_base + i) = results[i].x;\n      }\n    }\n  } else if (!CHECK_LHS_BOUNDARY) {\n    // CHECK RHS\n    /*\n    int ncols_rem = fminf(n_size- horiz_base, 4);\n    for (int i = 0; i < ncols_rem; i++) {\n      output(lhs_vert, horiz_base + i) = results[i].x;\n      output(lhs_vert + 1, horiz_base + i) = results[i].y;\n      output(lhs_vert + 2, horiz_base + i) = results[i].z;\n      output(lhs_vert + 3, horiz_base + i) = results[i].w;\n    }*/\n    for (int i = 0; i < 4; i++) {\n      if (horiz_base+i < n_size) {\n        output(lhs_vert, horiz_base + i) = results[i].x;\n        output(lhs_vert + 1, horiz_base + i) = results[i].y;\n        output(lhs_vert + 2, horiz_base + i) = results[i].z;\n        output(lhs_vert + 3, horiz_base + i) = results[i].w;\n       }\n    }\n  } else {\n    // CHECK both boundaries.\n    for (int i = 0; i < 4; i++) {\n      if (horiz_base+i < n_size) {\n        if (lhs_vert < m_size)\n          output(lhs_vert, horiz_base + i) = results[i].x;\n        if (lhs_vert + 1 < m_size)\n          output(lhs_vert + 1, horiz_base + i) = results[i].y;\n        if (lhs_vert + 2 < m_size)\n          output(lhs_vert + 2, horiz_base + i) = results[i].z;\n        if (lhs_vert + 3 < m_size)\n          output(lhs_vert + 3, horiz_base + i) = results[i].w;\n      }\n    }\n  }\n}\n\n\ntemplate<typename Index, typename LhsMapper,\n         typename RhsMapper, typename OutputMapper, bool CHECK_LHS_BOUNDARY,\n         bool CHECK_RHS_BOUNDARY>\n__device__ __forceinline__ void\nEigenFloatContractionKernelInternal(const LhsMapper lhs, const RhsMapper rhs,\n                       const OutputMapper output, float2 lhs_shmem2[][32],\n                       float2 rhs_shmem2[][8], const Index m_size,\n                       const Index n_size, const Index k_size,\n                       const Index base_m, const Index base_n) {\n\n  // prefetch registers\n  float4 lhs_pf0, lhs_pf1, lhs_pf2, lhs_pf3;\n  float4 rhs_pf0, rhs_pf1;\n\n  float4 results[8];\n  for (int i=0; i < 8; i++) {\n    results[i].x = results[i].y = results[i].z = results[i].w = 0;\n  }\n\n  Index lhs_vert = base_m+threadIdx.x*4+(threadIdx.y%4)*32;\n  for (Index k = 0; k < k_size; k += 32) {\n    lhs_pf0 = internal::pset1<float4>(0);\n    lhs_pf1 = internal::pset1<float4>(0);\n    lhs_pf2 = internal::pset1<float4>(0);\n    lhs_pf3 = internal::pset1<float4>(0);\n\n    rhs_pf0 = internal::pset1<float4>(0);\n    rhs_pf1 = internal::pset1<float4>(0);\n\n     if (!CHECK_LHS_BOUNDARY) {\n      if ((threadIdx.y/4+k+24) < k_size) {\n        lhs_pf0 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k));\n        lhs_pf1 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+8));\n        lhs_pf2 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+16));\n        lhs_pf3 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+24));\n      } else if ((threadIdx.y/4+k+16) < k_size) {\n        lhs_pf0 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k));\n        lhs_pf1 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+8));\n        lhs_pf2 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+16));\n      } else if ((threadIdx.y/4+k+8) < k_size) {\n        lhs_pf0 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k));\n        lhs_pf1 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+8));\n      } else if ((threadIdx.y/4+k) < k_size) {\n        lhs_pf0 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k));\n      }\n    } else {\n      // just CHECK_LHS_BOUNDARY\n      if (lhs_vert + 3 < m_size) {\n        if ((threadIdx.y/4+k+24) < k_size) {\n          lhs_pf0 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k));\n          lhs_pf1 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+8));\n          lhs_pf2 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+16));\n          lhs_pf3 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+24));\n        } else if ((threadIdx.y/4+k+16) < k_size) {\n          lhs_pf0 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k));\n          lhs_pf1 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+8));\n          lhs_pf2 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+16));\n        } else if ((threadIdx.y/4+k+8) < k_size) {\n          lhs_pf0 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k));\n          lhs_pf1 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k+8));\n        } else if ((threadIdx.y/4+k) < k_size) {\n          lhs_pf0 =lhs.template loadPacket<float4,Unaligned>(lhs_vert, (threadIdx.y/4+k));\n        }\n      } else if (lhs_vert + 2 < m_size) {\n        if ((threadIdx.y/4+k+24) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k));\n          lhs_pf0.z =lhs(lhs_vert + 2, (threadIdx.y/4+k));\n          lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8));\n          lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8));\n          lhs_pf1.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+8));\n          lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16));\n          lhs_pf2.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+16));\n          lhs_pf2.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+16));\n          lhs_pf3.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+24));\n          lhs_pf3.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+24));\n          lhs_pf3.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+24));\n        } else if ((threadIdx.y/4+k+16) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k));\n          lhs_pf0.z =lhs(lhs_vert + 2, (threadIdx.y/4+k));\n          lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8));\n          lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8));\n          lhs_pf1.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+8));\n          lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16));\n          lhs_pf2.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+16));\n          lhs_pf2.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+16));\n        } else if ((threadIdx.y/4+k+8) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k));\n          lhs_pf0.z =lhs(lhs_vert + 2, (threadIdx.y/4+k));\n          lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8));\n          lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8));\n          lhs_pf1.z =lhs(lhs_vert + 2, (threadIdx.y/4+k+8));\n        } else if ((threadIdx.y/4+k) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k));\n          lhs_pf0.z =lhs(lhs_vert + 2, (threadIdx.y/4+k));\n        }\n      } else if (lhs_vert + 1 < m_size) {\n        if ((threadIdx.y/4+k+24) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k));\n          lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8));\n          lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8));\n          lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16));\n          lhs_pf2.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+16));\n          lhs_pf3.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+24));\n          lhs_pf3.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+24));\n        } else if ((threadIdx.y/4+k+16) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k));\n          lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8));\n          lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8));\n          lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16));\n          lhs_pf2.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+16));\n        } else if ((threadIdx.y/4+k+8) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k));\n          lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8));\n          lhs_pf1.y =lhs(lhs_vert + 1, (threadIdx.y/4+k+8));\n        } else if ((threadIdx.y/4+k) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf0.y =lhs(lhs_vert + 1, (threadIdx.y/4+k));\n        }\n      } else if (lhs_vert < m_size) {\n        if ((threadIdx.y/4+k+24) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8));\n          lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16));\n          lhs_pf3.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+24));\n        } else if ((threadIdx.y/4+k+16) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8));\n          lhs_pf2.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+16));\n        } else if ((threadIdx.y/4+k+8) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n          lhs_pf1.x =lhs(lhs_vert + 0, (threadIdx.y/4+k+8));\n        } else if ((threadIdx.y/4+k) < k_size) {\n          lhs_pf0.x =lhs(lhs_vert + 0, (threadIdx.y/4+k));\n        }\n      }\n    }\n    __syncthreads();\n    Index rhs_vert = k+threadIdx.x*4;\n    Index rhs_horiz0 = threadIdx.y*2+base_n;\n    Index rhs_horiz1 = threadIdx.y*2+1+base_n;\n    if (!CHECK_RHS_BOUNDARY) {\n      if ((rhs_vert + 3) < k_size) {\n        // just CHECK_RHS_BOUNDARY\n        rhs_pf0 = rhs.template loadPacket<float4,Unaligned>(rhs_vert, rhs_horiz0);\n        rhs_pf1 = rhs.template loadPacket<float4,Unaligned>(rhs_vert, rhs_horiz1);\n      } else if (rhs_vert + 2 < k_size) {\n        // just CHECK_RHS_BOUNDARY\n        rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n        rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0);\n        rhs_pf0.z = rhs(rhs_vert + 2, rhs_horiz0);\n        rhs_pf1.x = rhs(rhs_vert, rhs_horiz1);\n        rhs_pf1.y = rhs(rhs_vert + 1, rhs_horiz1);\n        rhs_pf1.z = rhs(rhs_vert + 2, rhs_horiz1);\n      } else if (rhs_vert + 1 < k_size) {\n        rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n        rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0);\n        rhs_pf1.x = rhs(rhs_vert, rhs_horiz1);\n        rhs_pf1.y = rhs(rhs_vert + 1, rhs_horiz1);\n      } else if (rhs_vert  < k_size) {\n        rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n        rhs_pf1.x = rhs(rhs_vert, rhs_horiz1);\n      }\n    } else {\n      if (rhs_horiz1 < n_size) {\n        if ((rhs_vert + 3) < k_size) {\n          // just CHECK_RHS_BOUNDARY\n          rhs_pf0 = rhs.template loadPacket<float4,Unaligned>(rhs_vert, rhs_horiz0);\n          rhs_pf1 = rhs.template loadPacket<float4,Unaligned>(rhs_vert, rhs_horiz1);\n        } else if (rhs_vert + 2 < k_size) {\n          // just CHECK_RHS_BOUNDARY\n          rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n          rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0);\n          rhs_pf0.z = rhs(rhs_vert + 2, rhs_horiz0);\n          rhs_pf1.x = rhs(rhs_vert, rhs_horiz1);\n          rhs_pf1.y = rhs(rhs_vert + 1, rhs_horiz1);\n          rhs_pf1.z = rhs(rhs_vert + 2, rhs_horiz1);\n        } else if (k+threadIdx.x*4 + 1 < k_size) {\n          rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n          rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0);\n          rhs_pf1.x = rhs(rhs_vert, rhs_horiz1);\n          rhs_pf1.y = rhs(rhs_vert + 1, rhs_horiz1);\n        } else if (k+threadIdx.x*4  < k_size) {\n          rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n          rhs_pf1.x = rhs(rhs_vert, rhs_horiz1);\n        }\n      } else if (rhs_horiz0 < n_size) {\n        if ((rhs_vert + 3) < k_size) {\n          // just CHECK_RHS_BOUNDARY\n          rhs_pf0 = rhs.template loadPacket<float4,Unaligned>(rhs_vert, rhs_horiz0);\n        } else if ((rhs_vert + 2) < k_size) {\n          // just CHECK_RHS_BOUNDARY\n          rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n          rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0);\n          rhs_pf0.z = rhs(rhs_vert + 2, rhs_horiz0);\n        } else if ((rhs_vert + 1) < k_size) {\n          rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n          rhs_pf0.y = rhs(rhs_vert + 1, rhs_horiz0);\n        } else if (rhs_vert  < k_size) {\n          rhs_pf0.x = rhs(rhs_vert, rhs_horiz0);\n        }\n      }\n    }\n    __syncthreads();\n    // Loaded. Do computation\n    // Row 0 -> times (0, 4, 8, .. 28) for features 0, 1.\n    // Row 1 -> times (0, 4, 8, .. 28) for features 2, 3.\n    // ..\n    // Row 31 -> times (0, 4, 8, .. 28) for features 62, 63\n    rhs_shmem2[threadIdx.y][threadIdx.x] = make_float2(rhs_pf0.x, rhs_pf1.x);\n    // Row 32 -> times (1, 5, 9, .. 29) for features 0, 1.\n    // Row 33 -> times (1, 5, 9, .. 29) for features 2, 3.\n    // ..\n    rhs_shmem2[threadIdx.y+32][threadIdx.x] = make_float2(rhs_pf0.y, rhs_pf1.y);\n    // Row 64 -> times (2, 6, 10, .. 30) for features 0, 1.\n    // Row 65 -> times (2, 6, 10, .. 30) for features 2, 3.\n    rhs_shmem2[threadIdx.y+64][threadIdx.x] = make_float2(rhs_pf0.z, rhs_pf1.z);\n    // Row 96 -> times (3, 7, 11, .. 31) for features 0, 1.\n    // Row 97 -> times (3, 7, 11, .. 31) for features 2, 3.\n    rhs_shmem2[threadIdx.y+96][threadIdx.x] = make_float2(rhs_pf0.w, rhs_pf1.w);\n\n    // LHS.\n    // Row 0 (time 0) -> features (0, 1), (4, 5), .. (28, 29), (32, 33), ..  (60, 61) .. (124, 125)\n    // Row 1 (time 1) -> features (0, 1), (4, 5), .. (28, 29), (32, 33), ..  (60, 61) .. (124, 125)\n    // ...\n    // Row 8 (time 0) -> features (2, 3), (6, 7), .. (30, 31), (34, 35), ..  (62, 63) .. (126, 127)\n    // Row 15 (time 7) -> features (2, 3), (6, 7), .. (30, 31), (34, 35), ..  (62, 63) .. (126, 127)\n\n\n#define add_vals(a_feat1, a_feat2, f1, f2, f3, f4)\\\n      results[0].x += a_feat1.x * f1.x;\\\n      results[1].x += a_feat1.x * f1.y;\\\n      results[2].x += a_feat1.x * f2.x;\\\n      results[3].x += a_feat1.x * f2.y;\\\n      results[4].x += a_feat1.x * f3.x;\\\n      results[5].x += a_feat1.x * f3.y;\\\n      results[6].x += a_feat1.x * f4.x;\\\n      results[7].x += a_feat1.x * f4.y;\\\n\\\n      results[0].y += a_feat1.y * f1.x;\\\n      results[1].y += a_feat1.y * f1.y;\\\n      results[2].y += a_feat1.y * f2.x;\\\n      results[3].y += a_feat1.y * f2.y;\\\n      results[4].y += a_feat1.y * f3.x;\\\n      results[5].y += a_feat1.y * f3.y;\\\n      results[6].y += a_feat1.y * f4.x;\\\n      results[7].y += a_feat1.y * f4.y;\\\n\\\n      results[0].z += a_feat2.x * f1.x;\\\n      results[1].z += a_feat2.x * f1.y;\\\n      results[2].z += a_feat2.x * f2.x;\\\n      results[3].z += a_feat2.x * f2.y;\\\n      results[4].z += a_feat2.x * f3.x;\\\n      results[5].z += a_feat2.x * f3.y;\\\n      results[6].z += a_feat2.x * f4.x;\\\n      results[7].z += a_feat2.x * f4.y;\\\n\\\n      results[0].w += a_feat2.y * f1.x;\\\n      results[1].w += a_feat2.y * f1.y;\\\n      results[2].w += a_feat2.y * f2.x;\\\n      results[3].w += a_feat2.y * f2.y;\\\n      results[4].w += a_feat2.y * f3.x;\\\n      results[5].w += a_feat2.y * f3.y;\\\n      results[6].w += a_feat2.y * f4.x;\\\n      results[7].w += a_feat2.y * f4.y;\\\n\n    lhs_shmem2[threadIdx.y/4][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf0.x, lhs_pf0.y);\n    lhs_shmem2[threadIdx.y/4+8][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf1.x, lhs_pf1.y);\n    lhs_shmem2[threadIdx.y/4+16][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf2.x, lhs_pf2.y);\n    lhs_shmem2[threadIdx.y/4+24][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf3.x, lhs_pf3.y);\n\n    lhs_shmem2[threadIdx.y/4 + 32][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf0.z, lhs_pf0.w);\n    lhs_shmem2[threadIdx.y/4 + 40][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf1.z, lhs_pf1.w);\n    lhs_shmem2[threadIdx.y/4 + 48][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf2.z, lhs_pf2.w);\n    lhs_shmem2[threadIdx.y/4 + 56][threadIdx.x+(threadIdx.y%4)*8] = make_float2(lhs_pf3.z, lhs_pf3.w);\n\n    __syncthreads();\n\n    // Do the multiplies.\n    #pragma unroll\n    for (int koff = 0; koff < 32; koff ++) {\n      float2 a3 = lhs_shmem2[koff][threadIdx.x + (threadIdx.y % 4) * 8];\n      float2 a4 = lhs_shmem2[koff + 32][threadIdx.x + (threadIdx.y % 4) * 8];\n\n      // first feature is at (threadIdx.y/4) * 8 last is at start + 8.\n      int start_feature = (threadIdx.y / 4) * 8;\n\n      float2 br1 = rhs_shmem2[start_feature/2 +     (koff % 4) * 32][koff/4];\n      float2 br2 = rhs_shmem2[start_feature/2 + 1 + (koff % 4) * 32][koff/4];\n      float2 br3 = rhs_shmem2[start_feature/2 + 2 + (koff % 4) * 32][koff/4];\n      float2 br4 = rhs_shmem2[start_feature/2 + 3 + (koff % 4) * 32][koff/4];\n\n      add_vals(a3, a4, br1, br2, br3, br4)\n    }\n    __syncthreads();\n  } // end loop over k\n\n  __syncthreads();\n  Index horiz_base = (threadIdx.y/4)*8+base_n;\n  if (!CHECK_LHS_BOUNDARY && !CHECK_RHS_BOUNDARY) {\n    for (int i = 0; i < 8; i++) {\n      output(lhs_vert, horiz_base + i) = results[i].x;\n      output(lhs_vert + 1, horiz_base + i) = results[i].y;\n      output(lhs_vert + 2, horiz_base + i) = results[i].z;\n      output(lhs_vert + 3, horiz_base + i) = results[i].w;\n    }\n  } else if (!CHECK_RHS_BOUNDARY) {\n    if (lhs_vert + 3 < m_size) {\n      for (int i = 0; i < 8; i++) {\n        output(lhs_vert, horiz_base + i) = results[i].x;\n        output(lhs_vert + 1, horiz_base + i) = results[i].y;\n        output(lhs_vert + 2, horiz_base + i) = results[i].z;\n        output(lhs_vert + 3, horiz_base + i) = results[i].w;\n      }\n    } else if (lhs_vert + 2 < m_size) {\n      for (int i = 0; i < 8; i++) {\n        output(lhs_vert, horiz_base + i) = results[i].x;\n        output(lhs_vert + 1, horiz_base + i) = results[i].y;\n        output(lhs_vert + 2, horiz_base + i) = results[i].z;\n      }\n    } else if (lhs_vert + 1 < m_size) {\n      for (int i = 0; i < 8; i++) {\n        output(lhs_vert, horiz_base + i) = results[i].x;\n        output(lhs_vert + 1, horiz_base + i) = results[i].y;\n      }\n    } else if (lhs_vert  < m_size) {\n      for (int i = 0; i < 8; i++) {\n        output(lhs_vert, horiz_base + i) = results[i].x;\n      }\n    }\n  } else if (!CHECK_LHS_BOUNDARY) {\n    // CHECK BOUNDARY_B\n    for (int i = 0; i < 8; i++) {\n      if (horiz_base + i < n_size) {\n        output(lhs_vert, horiz_base + i) = results[i].x;\n        output(lhs_vert + 1, horiz_base + i) = results[i].y;\n        output(lhs_vert + 2, horiz_base + i) = results[i].z;\n        output(lhs_vert + 3, horiz_base + i) = results[i].w;\n      }\n    }\n  } else {\n    // CHECK both boundaries.\n    for (int i = 0; i < 8; i++) {\n      if (horiz_base + i < n_size) {\n        if (lhs_vert < m_size)\n          output(lhs_vert, horiz_base + i) = results[i].x;\n        if (lhs_vert + 1 < m_size)\n          output(lhs_vert + 1, horiz_base + i) = results[i].y;\n        if (lhs_vert + 2 < m_size)\n          output(lhs_vert + 2, horiz_base + i) = results[i].z;\n        if (lhs_vert + 3 < m_size)\n          output(lhs_vert + 3, horiz_base + i) = results[i].w;\n      }\n    }\n  }\n}\n\n\ntemplate<typename Index, typename LhsMapper,\n         typename RhsMapper, typename OutputMapper>\n__global__ void\n#if defined(EIGEN_HIPCC)\n__launch_bounds__(256, 1)\n#else\n__launch_bounds__(256)\n#endif\nEigenFloatContractionKernel(const LhsMapper lhs, const RhsMapper rhs,\n                       const OutputMapper output,\n                       const Index m_size, const Index n_size, const Index k_size) {\n  __shared__ float2 lhs_shmem[64*32];\n  __shared__ float2 rhs_shmem[128*8];\n\n  typedef float2 LHS_MEM[64][32];\n  typedef float2 RHS_MEM[128][8];\n\n  const Index m_block_idx = blockIdx.x;\n  const Index n_block_idx = blockIdx.y;\n\n  const Index base_m = 128 * m_block_idx;\n  const Index base_n = 64 * n_block_idx;\n\n  bool check_rhs = (base_n + 63) >= n_size;\n  bool check_lhs128 = (base_m + 127) >= m_size;\n\n  if (!check_rhs) {\n    if (!check_lhs128) {\n      // >= 128 rows left\n      EigenFloatContractionKernelInternal<Index, LhsMapper, RhsMapper, OutputMapper, false, false>(\n                     lhs, rhs, output, *((LHS_MEM *) lhs_shmem), *((RHS_MEM *) rhs_shmem), m_size, n_size, k_size, base_m, base_n);\n    } else {\n      EigenFloatContractionKernelInternal<Index, LhsMapper, RhsMapper, OutputMapper, true, false>(\n                     lhs, rhs, output, *((LHS_MEM *) lhs_shmem), *((RHS_MEM *) rhs_shmem), m_size, n_size, k_size, base_m, base_n);\n    }\n  } else {\n    if (!check_lhs128) {\n      // >= 128 rows left\n      EigenFloatContractionKernelInternal<Index, LhsMapper, RhsMapper, OutputMapper, false, true>(\n                     lhs, rhs, output, *((LHS_MEM *) lhs_shmem), *((RHS_MEM *) rhs_shmem), m_size, n_size, k_size, base_m, base_n);\n    } else {\n      EigenFloatContractionKernelInternal<Index, LhsMapper, RhsMapper, OutputMapper, true, true>(\n                     lhs, rhs, output, *((LHS_MEM *) lhs_shmem), *((RHS_MEM *) rhs_shmem), m_size, n_size, k_size, base_m, base_n);\n    }\n  }\n}\n\ntemplate<typename Index, typename LhsMapper,\n         typename RhsMapper, typename OutputMapper>\n__global__ void\n#if defined(EIGEN_HIPCC)\n__launch_bounds__(256, 1)\n#else\n__launch_bounds__(256)\n#endif\nEigenFloatContractionKernel16x16(const LhsMapper lhs, const RhsMapper rhs,\n                       const OutputMapper output,\n                       const Index m_size, const Index n_size, const Index k_size) {\n  __shared__ float2 lhs_shmem[32][16];\n  __shared__ float2 rhs_shmem[64][8];\n\n  const Index m_block_idx = blockIdx.x;\n  const Index n_block_idx = blockIdx.y;\n\n  const Index base_m = 64 * m_block_idx;\n  const Index base_n = 64 * n_block_idx;\n\n  if (base_m + 63 < m_size) {\n    if (base_n + 63 < n_size) {\n      EigenFloatContractionKernelInternal16x16<Index, LhsMapper, RhsMapper, OutputMapper, false, false>(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size, base_m, base_n);\n    } else {\n      EigenFloatContractionKernelInternal16x16<Index, LhsMapper, RhsMapper, OutputMapper, false, true>(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size, base_m, base_n);\n    }\n  } else {\n    if (base_n + 63 < n_size) {\n      EigenFloatContractionKernelInternal16x16<Index, LhsMapper, RhsMapper, OutputMapper, true, false>(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size, base_m, base_n);\n    } else {\n      EigenFloatContractionKernelInternal16x16<Index, LhsMapper, RhsMapper, OutputMapper, true, true>(lhs, rhs, output, lhs_shmem, rhs_shmem, m_size, n_size, k_size, base_m, base_n);\n    }\n  }\n}\n\n\ntemplate<typename Indices, typename LeftArgType, typename RightArgType, typename OutputKernelType>\nstruct TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, GpuDevice> :\n    public TensorContractionEvaluatorBase<TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, GpuDevice> > {\n\n  typedef GpuDevice Device;\n\n  typedef TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, Device> Self;\n  typedef TensorContractionEvaluatorBase<Self> Base;\n\n  typedef TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType> XprType;\n  typedef typename internal::remove_const<typename XprType::Scalar>::type Scalar;\n  typedef typename XprType::Index Index;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, GpuDevice>::type PacketReturnType;\n\n  enum {\n    Layout = TensorEvaluator<LeftArgType, Device>::Layout,\n  };\n\n  // Most of the code is assuming that both input tensors are ColMajor. If the\n  // inputs are RowMajor, we will \"cheat\" by swapping the LHS and RHS:\n  // If we want to compute A * B = C, where A is LHS and B is RHS, the code\n  // will pretend B is LHS and A is RHS.\n  typedef typename internal::conditional<\n    static_cast<int>(Layout) == static_cast<int>(ColMajor), LeftArgType, RightArgType>::type EvalLeftArgType;\n  typedef typename internal::conditional<\n    static_cast<int>(Layout) == static_cast<int>(ColMajor), RightArgType, LeftArgType>::type EvalRightArgType;\n\n  static const int LDims =\n      internal::array_size<typename TensorEvaluator<EvalLeftArgType, Device>::Dimensions>::value;\n  static const int RDims =\n      internal::array_size<typename TensorEvaluator<EvalRightArgType, Device>::Dimensions>::value;\n  static const int ContractDims = internal::array_size<Indices>::value;\n\n  typedef array<Index, LDims> left_dim_mapper_t;\n  typedef array<Index, RDims> right_dim_mapper_t;\n\n  typedef array<Index, ContractDims> contract_t;\n  typedef array<Index, LDims - ContractDims> left_nocontract_t;\n  typedef array<Index, RDims - ContractDims> right_nocontract_t;\n\n  static const int NumDims = LDims + RDims - 2 * ContractDims;\n\n  typedef DSizes<Index, NumDims> Dimensions;\n\n  // typedefs needed in evalTo\n  typedef typename internal::remove_const<typename EvalLeftArgType::Scalar>::type LhsScalar;\n  typedef typename internal::remove_const<typename EvalRightArgType::Scalar>::type RhsScalar;\n\n  typedef TensorEvaluator<EvalLeftArgType, Device> LeftEvaluator;\n  typedef TensorEvaluator<EvalRightArgType, Device> RightEvaluator;\n\n  typedef typename LeftEvaluator::Dimensions LeftDimensions;\n  typedef typename RightEvaluator::Dimensions RightDimensions;\n\n  EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device) :\n      Base(op, device)\n  {\n    EIGEN_STATIC_ASSERT( (internal::is_same<OutputKernelType, const NoOpOutputKernel>::value),\n                          GPU_TENSOR_CONTRACTION_DOES_NOT_SUPPORT_OUTPUT_KERNELS);\n  }\n\n  // We need to redefine this method to make nvcc happy\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* data) {\n    this->m_leftImpl.evalSubExprsIfNeeded(NULL);\n    this->m_rightImpl.evalSubExprsIfNeeded(NULL);\n    if (data) {\n      evalTo(data);\n      return false;\n    } else {\n      this->m_result = static_cast<Scalar *>(this->m_device.allocate(this->dimensions().TotalSize() * sizeof(Scalar)));\n      evalTo(this->m_result);\n      return true;\n    }\n  }\n\n  void evalTo(Scalar* buffer) const {\n    if (this->m_lhs_inner_dim_contiguous) {\n      if (this->m_rhs_inner_dim_contiguous) {\n        if (this->m_rhs_inner_dim_reordered) {\n          evalTyped<true, true, true, Unaligned>(buffer);\n        }\n        else {\n          evalTyped<true, true, false, Unaligned>(buffer);\n        }\n      }\n      else {\n       if (this->m_rhs_inner_dim_reordered) {\n          evalTyped<true, false, true, Unaligned>(buffer);\n        }\n        else {\n          evalTyped<true, false, false, Unaligned>(buffer);\n        }\n      }\n    }\n    else {\n      if (this->m_rhs_inner_dim_contiguous) {\n        if (this->m_rhs_inner_dim_reordered) {\n          evalTyped<false, true, true, Unaligned>(buffer);\n        }\n        else {\n          evalTyped<false, true, false, Unaligned>(buffer);\n        }\n      }\n      else {\n       if (this->m_rhs_inner_dim_reordered) {\n          evalTyped<false, false, true, Unaligned>(buffer);\n        }\n        else {\n          evalTyped<false, false, false, Unaligned>(buffer);\n        }\n      }\n    }\n  }\n\n  template <typename LhsScalar, typename RhsScalar, typename Index, typename LhsMapper, typename RhsMapper, typename OutputMapper> struct LaunchKernels {\n    static void Run(const LhsMapper& lhs, const RhsMapper& rhs, const OutputMapper& output, Index m, Index n, Index k, const GpuDevice& device) {\n    const Index m_blocks = (m + 63) / 64;\n    const Index n_blocks = (n + 63) / 64;\n    const dim3 num_blocks(m_blocks, n_blocks, 1);\n    const dim3 block_size(8, 8, 8);\n    LAUNCH_GPU_KERNEL((EigenContractionKernel<Scalar, Index, LhsMapper, RhsMapper, OutputMapper>), num_blocks, block_size, 0, device, lhs, rhs, output, m, n, k);\n    }\n  };\n\n  template <typename Index, typename LhsMapper, typename RhsMapper, typename OutputMapper> struct LaunchKernels<float, float, Index, LhsMapper, RhsMapper, OutputMapper> {\n    static void Run(const LhsMapper& lhs, const RhsMapper& rhs, const OutputMapper& output, Index m, Index n, Index k, const GpuDevice& device) {\n      if (m < 768 || n < 768) {\n        const Index m_blocks = (m + 63) / 64;\n        const Index n_blocks = (n + 63) / 64;\n        const dim3 num_blocks(m_blocks, n_blocks, 1);\n        const dim3 block_size(16, 16, 1);\n        LAUNCH_GPU_KERNEL((EigenFloatContractionKernel16x16<Index, LhsMapper, RhsMapper, OutputMapper>), num_blocks, block_size, 0, device, lhs, rhs, output, m, n, k);\n      } else {\n        const Index m_blocks = (m + 127) / 128;\n        const Index n_blocks = (n + 63) / 64;\n        const dim3 num_blocks(m_blocks, n_blocks, 1);\n        const dim3 block_size(8, 32, 1);\n        LAUNCH_GPU_KERNEL((EigenFloatContractionKernel<Index, LhsMapper, RhsMapper, OutputMapper>), num_blocks, block_size, 0, device, lhs, rhs, output, m, n, k);\n      }\n    }\n  };\n\n  template <bool lhs_inner_dim_contiguous, bool rhs_inner_dim_contiguous, bool rhs_inner_dim_reordered, int Alignment>\n  void evalTyped(Scalar* buffer) const {\n    // columns in left side, rows in right side\n    const Index k = this->m_k_size;\n    EIGEN_UNUSED_VARIABLE(k)\n\n    // rows in left side\n    const Index m = this->m_i_size;\n\n    // columns in right side\n    const Index n = this->m_j_size;\n\n    // zero out the result buffer (which must be of size at least m * n * sizeof(Scalar)\n    this->m_device.memset(buffer, 0, m * n * sizeof(Scalar));\n\n    typedef internal::TensorContractionInputMapper<LhsScalar, Index, internal::Lhs,\n                                                   LeftEvaluator, left_nocontract_t,\n                                                   contract_t, 4,\n                                                   lhs_inner_dim_contiguous,\n                                                   false, Unaligned> LhsMapper;\n\n    typedef internal::TensorContractionInputMapper<RhsScalar, Index, internal::Rhs,\n                                                   RightEvaluator, right_nocontract_t,\n                                                   contract_t, 4,\n                                                   rhs_inner_dim_contiguous,\n                                                   rhs_inner_dim_reordered, Unaligned> RhsMapper;\n\n    typedef internal::blas_data_mapper<Scalar, Index, ColMajor> OutputMapper;\n\n\n    // initialize data mappers\n    LhsMapper lhs(this->m_leftImpl, this->m_left_nocontract_strides, this->m_i_strides,\n                  this->m_left_contracting_strides, this->m_k_strides);\n\n    RhsMapper rhs(this->m_rightImpl, this->m_right_nocontract_strides, this->m_j_strides,\n                  this->m_right_contracting_strides, this->m_k_strides);\n\n    OutputMapper output(buffer, m);\n\n#if defined(EIGEN_USE_HIP)\n    setGpuSharedMemConfig(hipSharedMemBankSizeEightByte);\n#else\n    setGpuSharedMemConfig(cudaSharedMemBankSizeEightByte);\n#endif\n\n    LaunchKernels<LhsScalar, RhsScalar, Index, LhsMapper, RhsMapper, OutputMapper>::Run(lhs, rhs, output,  m, n, k, this->m_device);\n  }\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_USE_GPU and EIGEN_GPUCC\n#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_GPU_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionMapper.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_MAPPER_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_MAPPER_H\n\nnamespace Eigen {\n\nnamespace internal {\n\nenum {\n  Rhs = 0,\n  Lhs = 1\n};\n\n/*\n * Implementation of the Eigen blas_data_mapper class for tensors.\n */\n/// The make pointer class is used by sycl in order to build the mapper class on the device. For other platform the default make pointer is used which\n/// is scalar * for CoeffLoader.\ntemplate <typename Tensor, bool HasRawAccess, template <class> class MakePointer_ = MakePointer>\nstruct CoeffLoader;\n\ntemplate <typename Scalar, typename Index, int side, typename Tensor,\n          typename nocontract_t, typename contract_t, int packet_size,\n          bool inner_dim_contiguous, bool inner_dim_reordered, int Alignment,\n          template <class> class MakePointer_ = MakePointer>\nclass BaseTensorContractionMapper;\n\ntemplate <typename Tensor, bool HasRawAccess, template <class> class MakePointer_>\nstruct CoeffLoader {\n  enum {\n    DirectOffsets = false\n  };\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE CoeffLoader(const Tensor& tensor) : m_tensor(tensor) { }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void offsetBuffer(typename Tensor::Index) {\n    eigen_assert(false && \"unsupported\");\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE const typename MakePointer_<const typename Tensor::Scalar>::Type\n  data() const {\n    eigen_assert(false && \"unsupported\");\n    return NULL;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE typename Tensor::Scalar coeff(typename Tensor::Index index) const { return m_tensor.coeff(index); }\n\n template<int LoadMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n typename Tensor::PacketReturnType packet(typename Tensor::Index index) const\n  {\n    return m_tensor.template packet<LoadMode>(index);\n  }\n\n  #ifdef EIGEN_USE_SYCL\n  // The placeholder accessors require to be bound to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_tensor.bind(cgh);\n  }\n  #endif\n\n private:\n  const Tensor m_tensor;\n};\n\ntemplate <typename Tensor, template <class> class MakePointer_>\nstruct CoeffLoader<Tensor, true, MakePointer_> {\n  enum {\n    DirectOffsets = true\n  };\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE CoeffLoader(const Tensor& tensor) : m_data(tensor.data()) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void offsetBuffer(typename Tensor::Index offset) {\n    m_data += offset;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE const typename MakePointer_<const typename Tensor::Scalar>::Type\n  data() const {\n    return m_data;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE typename Tensor::Scalar coeff(typename Tensor::Index index) const { return loadConstant(m_data+index); }\n\n template<int LoadMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n typename Tensor::PacketReturnType packet(typename Tensor::Index index) const\n  {\n    return internal::ploadt_ro<typename Tensor::PacketReturnType, LoadMode>(m_data + index);\n  }\n\n  #ifdef EIGEN_USE_SYCL\n  // The placeholder accessors require to be bound to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_data.bind(cgh);\n  }\n  #endif\n private:\n  typedef typename Tensor::Scalar Scalar;\n\n  typename MakePointer_<const Scalar>::Type m_data;\n};\n\ntemplate<typename Scalar, typename Index, int side,\n         typename Tensor,\n         typename nocontract_t, typename contract_t,\n         int packet_size, bool inner_dim_contiguous, int Alignment, template <class> class MakePointer_ = MakePointer>\nclass SimpleTensorContractionMapper {\n  public:\n  EIGEN_DEVICE_FUNC\n  SimpleTensorContractionMapper(const Tensor& tensor,\n                                const nocontract_t& nocontract_strides,\n                                const nocontract_t& ij_strides,\n                                const contract_t& contract_strides,\n                                const contract_t& k_strides) :\n      m_tensor(tensor),\n      m_nocontract_strides(nocontract_strides),\n      m_ij_strides(ij_strides),\n      m_contract_strides(contract_strides),\n      m_k_strides(k_strides) { }\n\n  enum {\n    DirectOffsets = CoeffLoader<Tensor, Tensor::RawAccess, MakePointer_>::DirectOffsets\n  };\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void offsetBuffer(typename Tensor::Index offset) {\n    m_tensor.offsetBuffer(offset);\n  }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE void prefetch(Index /*i*/) { }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE Scalar operator()(Index row) const {\n    // column major assumption\n    return operator()(row, 0);\n  }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE Scalar operator()(Index row, Index col) const {\n    return m_tensor.coeff(computeIndex(row, col));\n  }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE Index computeIndex(Index row, Index col) const {\n    const bool left = (side == Lhs);\n    EIGEN_UNUSED_VARIABLE(left); // annoying bug in g++8.1: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=85963\n    Index nocontract_val = left ? row : col;\n    Index linidx = 0;\n    EIGEN_UNROLL_LOOP\n    for (int i = static_cast<int>(array_size<nocontract_t>::value) - 1; i > 0; i--) {\n      const Index idx = nocontract_val / m_ij_strides[i];\n      linidx += idx * m_nocontract_strides[i];\n      nocontract_val -= idx * m_ij_strides[i];\n    }\n    if (array_size<typename Tensor::Dimensions>::value > array_size<contract_t>::value) {\n      if (side == Lhs && inner_dim_contiguous) {\n        eigen_assert(m_nocontract_strides[0] == 1);\n        linidx += nocontract_val;\n      } else {\n        linidx += nocontract_val * m_nocontract_strides[0];\n      }\n    }\n\n    Index contract_val = left ? col : row;\n    if(array_size<contract_t>::value > 0) {\n      EIGEN_UNROLL_LOOP\n      for (int i = static_cast<int>(array_size<contract_t>::value) - 1; i > 0; i--) {\n        const Index idx = contract_val / m_k_strides[i];\n        linidx += idx * m_contract_strides[i];\n        contract_val -= idx * m_k_strides[i];\n      }\n\n      if (side == Rhs && inner_dim_contiguous) {\n        eigen_assert(m_contract_strides[0] == 1);\n        linidx += contract_val;\n      } else {\n        linidx += contract_val * m_contract_strides[0];\n      }\n    }\n\n    return linidx;\n  }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE IndexPair<Index> computeIndexPair(Index row, Index col, const Index distance) const {\n    const bool left = (side == Lhs);\n    EIGEN_UNUSED_VARIABLE(left); // annoying bug in g++8.1: https://gcc.gnu.org/bugzilla/show_bug.cgi?id=85963\n    Index nocontract_val[2] = {left ? row : col, left ? row + distance : col};\n    Index linidx[2] = {0, 0};\n    if (array_size<typename Tensor::Dimensions>::value > array_size<contract_t>::value) {\n      EIGEN_UNROLL_LOOP\n      for (int i = static_cast<int>(array_size<nocontract_t>::value) - 1; i > 0; i--) {\n        const Index idx0 = nocontract_val[0] / m_ij_strides[i];\n        const Index idx1 = nocontract_val[1] / m_ij_strides[i];\n        linidx[0] += idx0 * m_nocontract_strides[i];\n        linidx[1] += idx1 * m_nocontract_strides[i];\n        nocontract_val[0] -= idx0 * m_ij_strides[i];\n        nocontract_val[1] -= idx1 * m_ij_strides[i];\n      }\n      if (side == Lhs && inner_dim_contiguous) {\n        eigen_assert(m_nocontract_strides[0] == 1);\n        linidx[0] += nocontract_val[0];\n        linidx[1] += nocontract_val[1];\n      } else {\n        linidx[0] += nocontract_val[0] * m_nocontract_strides[0];\n        linidx[1] += nocontract_val[1] * m_nocontract_strides[0];\n      }\n    }\n\n    Index contract_val[2] = {left ? col : row, left ? col : row + distance};\n    if (array_size<contract_t>::value> 0) {\n      EIGEN_UNROLL_LOOP\n      for (int i = static_cast<int>(array_size<contract_t>::value) - 1; i > 0; i--) {\n        const Index idx0 = contract_val[0] / m_k_strides[i];\n        const Index idx1 = contract_val[1] / m_k_strides[i];\n        linidx[0] += idx0 * m_contract_strides[i];\n        linidx[1] += idx1 * m_contract_strides[i];\n        contract_val[0] -= idx0 * m_k_strides[i];\n        contract_val[1] -= idx1 * m_k_strides[i];\n      }\n\n      if (side == Rhs && inner_dim_contiguous) {\n        eigen_assert(m_contract_strides[0] == 1);\n        linidx[0] += contract_val[0];\n        linidx[1] += contract_val[1];\n      } else {\n        linidx[0] += contract_val[0] * m_contract_strides[0];\n        linidx[1] += contract_val[1] * m_contract_strides[0];\n      }\n    }\n    return IndexPair<Index>(linidx[0], linidx[1]);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Index firstAligned(Index size) const {\n    // Only claim alignment when we can compute the actual stride (ie when we're\n    // dealing with the lhs with inner_dim_contiguous. This is because the\n    // matrix-vector product relies on the stride when dealing with aligned inputs.\n    return (Alignment == Aligned) && (side == Lhs) && inner_dim_contiguous ? 0 : size;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Index stride() const {\n    return ((side == Lhs) && inner_dim_contiguous && array_size<contract_t>::value > 0) ? m_contract_strides[0] : 1;\n  }\n\n  #ifdef EIGEN_USE_SYCL\n  // The placeholder accessors require to be bound to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_tensor.bind(cgh);\n  }\n  #endif\n\n  const CoeffLoader<Tensor, Tensor::RawAccess, MakePointer_>& tensor() const {\n    return m_tensor;\n  }\n\n  const nocontract_t& nocontract_strides() const {\n    return m_nocontract_strides;\n  }\n  const nocontract_t& ij_strides() const { return m_ij_strides; }\n  const contract_t& contract_strides() const { return m_contract_strides; }\n  const contract_t& k_strides() const { return m_k_strides; }\n\n protected:\n  CoeffLoader<Tensor, Tensor::RawAccess, MakePointer_> m_tensor;\n  const nocontract_t m_nocontract_strides;\n  const nocontract_t m_ij_strides;\n  const contract_t m_contract_strides;\n  const contract_t m_k_strides;\n};\n\ntemplate<typename Scalar, typename Index, int side,\n         typename Tensor,\n         typename nocontract_t, typename contract_t,\n         int packet_size, bool inner_dim_contiguous,\n         bool inner_dim_reordered, int Alignment, template <class> class MakePointer_>\nclass BaseTensorContractionMapper : public SimpleTensorContractionMapper<Scalar, Index, side, Tensor, nocontract_t, contract_t, packet_size, inner_dim_contiguous, Alignment, MakePointer_>\n{\n public:\n  typedef SimpleTensorContractionMapper<Scalar, Index, side, Tensor, nocontract_t, contract_t, packet_size, inner_dim_contiguous, Alignment, MakePointer_> ParentMapper;\n\n  EIGEN_DEVICE_FUNC\n  BaseTensorContractionMapper(const Tensor& tensor,\n                              const nocontract_t& nocontract_strides,\n                              const nocontract_t& ij_strides,\n                              const contract_t& contract_strides,\n                              const contract_t& k_strides) :\n  ParentMapper(tensor, nocontract_strides, ij_strides, contract_strides, k_strides) { }\n\n  template <typename PacketT,int AlignmentType>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  typename internal::enable_if<internal::unpacket_traits<PacketT>::size==packet_size,PacketT>::type\n  load(Index i, Index j) const\n  {\n    // whole method makes column major assumption\n\n    // don't need to add offsets for now (because operator handles that)\n    // current code assumes packet size must be a multiple of 2\n    EIGEN_STATIC_ASSERT(packet_size % 2 == 0, YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    if (Tensor::PacketAccess && inner_dim_contiguous && !inner_dim_reordered) {\n      const Index index = this->computeIndex(i, j);\n      eigen_assert(this->computeIndex(i+packet_size-1, j) == index + packet_size-1);\n      return this->m_tensor.template packet<AlignmentType>(index);\n    }\n\n    const IndexPair<Index> indexPair = this->computeIndexPair(i, j, packet_size - 1);\n    const Index first = indexPair.first;\n    const Index lastIdx = indexPair.second;\n\n    // We can always do optimized packet reads from left hand side right now, because\n    // the vertical matrix dimension on the left hand side is never contracting.\n    // On the right hand side we need to check if the contracting dimensions may have\n    // been shuffled first.\n    if (Tensor::PacketAccess &&\n        (side == Lhs || internal::array_size<contract_t>::value <= 1 || !inner_dim_reordered) &&\n        (lastIdx - first) == (packet_size - 1)) {\n\n      return this->m_tensor.template packet<AlignmentType>(first);\n    }\n\n    EIGEN_ALIGN_MAX Scalar data[packet_size];\n\n    data[0] = this->m_tensor.coeff(first);\n    EIGEN_UNROLL_LOOP\n    for (Index k = 1; k < packet_size - 1; k += 2) {\n      const IndexPair<Index> internal_pair = this->computeIndexPair(i + k, j, 1);\n      data[k] = this->m_tensor.coeff(internal_pair.first);\n      data[k + 1] = this->m_tensor.coeff(internal_pair.second);\n    }\n    data[packet_size - 1] = this->m_tensor.coeff(lastIdx);\n\n    return pload<PacketT>(data);\n  }\n\n  template <typename PacketT,int AlignmentType>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  typename internal::enable_if<internal::unpacket_traits<PacketT>::size!=packet_size,PacketT>::type\n  load(Index i, Index j) const\n  {\n    const Index requested_packet_size = internal::unpacket_traits<PacketT>::size;\n    EIGEN_ALIGN_MAX Scalar data[requested_packet_size];\n\n    const IndexPair<Index> indexPair = this->computeIndexPair(i, j, requested_packet_size - 1);\n    const Index first = indexPair.first;\n    const Index lastIdx = indexPair.second;\n\n    data[0] = this->m_tensor.coeff(first);\n    for (Index k = 1; k < requested_packet_size - 1; k += 2) {\n      const IndexPair<Index> internal_pair = this->computeIndexPair(i + k, j, 1);\n      data[k] = this->m_tensor.coeff(internal_pair.first);\n      data[k + 1] = this->m_tensor.coeff(internal_pair.second);\n    }\n    data[requested_packet_size - 1] = this->m_tensor.coeff(lastIdx);\n\n    return pload<PacketT>(data);\n  }\n\n  template <typename PacketT,int AlignmentType>\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE PacketT loadPacket(Index i, Index j) const {\n    return this->load<PacketT,AlignmentType>(i,j);\n  }\n};\n\n\ntemplate<typename Scalar, typename Index, int side,\n         typename Tensor,\n         typename nocontract_t, typename contract_t,\n         bool inner_dim_contiguous,\n         bool inner_dim_reordered, int Alignment, template <class> class MakePointer_>\nclass BaseTensorContractionMapper<Scalar, Index, side, Tensor, nocontract_t, contract_t, 1, inner_dim_contiguous, inner_dim_reordered, Alignment, MakePointer_>\n  : public SimpleTensorContractionMapper<Scalar, Index, side, Tensor, nocontract_t, contract_t, 1, inner_dim_contiguous, Alignment, MakePointer_>\n{\n public:\n  typedef SimpleTensorContractionMapper<Scalar, Index, side, Tensor, nocontract_t, contract_t, 1, inner_dim_contiguous, Alignment, MakePointer_> ParentMapper;\n\n  EIGEN_DEVICE_FUNC\n  BaseTensorContractionMapper(const Tensor& tensor,\n                              const nocontract_t& nocontract_strides,\n                              const nocontract_t& ij_strides,\n                              const contract_t& contract_strides,\n                              const contract_t& k_strides) :\n  ParentMapper(tensor, nocontract_strides, ij_strides, contract_strides, k_strides) { }\n\n  template <typename PacketT,int> EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE PacketT loadPacket(Index i, Index j) const {\n    EIGEN_ALIGN_MAX Scalar data[1];\n    data[0] = this->m_tensor.coeff(this->computeIndex(i, j));\n    return pload<PacketT>(data);\n  }\n  template <typename PacketT,int> EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE PacketT load(Index i, Index j) const {\n    EIGEN_ALIGN_MAX Scalar data[1];\n    data[0] = this->m_tensor.coeff(this->computeIndex(i, j));\n    return pload<PacketT>(data);\n  }\n};\n\n\ntemplate<typename Scalar, typename Index, int side,\n         typename Tensor,\n         typename nocontract_t, typename contract_t,\n         int packet_size,\n         bool inner_dim_contiguous, bool inner_dim_reordered, int Alignment, template <class> class MakePointer_=MakePointer>\nclass TensorContractionSubMapper {\n public:\n\n  typedef BaseTensorContractionMapper<Scalar, Index, side, Tensor, nocontract_t, contract_t, packet_size, inner_dim_contiguous, inner_dim_reordered, Alignment, MakePointer_> ParentMapper;\n  typedef TensorContractionSubMapper<Scalar, Index, side, Tensor, nocontract_t, contract_t, packet_size, inner_dim_contiguous, inner_dim_reordered, Alignment, MakePointer_> Self;\n  typedef Self LinearMapper;\n\n  enum {\n    // We can use direct offsets iff the parent mapper supports then and we can compute the strides.\n    // TODO: we should also enable direct offsets for the Rhs case.\n    UseDirectOffsets = ParentMapper::DirectOffsets && (side == Lhs) && inner_dim_contiguous && (array_size<contract_t>::value > 0)\n  };\n\n  EIGEN_DEVICE_FUNC TensorContractionSubMapper(const ParentMapper& base_mapper, Index vert_offset, Index horiz_offset)\n      : m_base_mapper(base_mapper), m_vert_offset(vert_offset), m_horiz_offset(horiz_offset) {\n    // Bake the offsets into the buffer used by the base mapper whenever possible. This avoids the need to recompute\n    // this offset every time we attempt to access a coefficient.\n    if (UseDirectOffsets) {\n      Index stride = m_base_mapper.stride();\n      m_base_mapper.offsetBuffer(vert_offset + horiz_offset * stride);\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Scalar operator()(Index i) const {\n    if (UseDirectOffsets) {\n      return m_base_mapper(i, 0);\n    }\n    return m_base_mapper(i + m_vert_offset, m_horiz_offset);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Scalar operator()(Index i, Index j) const {\n    if (UseDirectOffsets) {\n      return m_base_mapper(i, j);\n    }\n    return m_base_mapper(i + m_vert_offset, j + m_horiz_offset);\n  }\n\n  template <typename PacketT>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketT loadPacket(Index i) const {\n    if (UseDirectOffsets) {\n      return m_base_mapper.template loadPacket<PacketT,Alignment>(i, 0);\n    }\n    return m_base_mapper.template loadPacket<PacketT,Alignment>(i + m_vert_offset, m_horiz_offset);\n  }\n\n  template <typename PacketT>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketT loadPacket(Index i, Index j) const {\n    if (UseDirectOffsets) {\n      return m_base_mapper.template loadPacket<PacketT,Alignment>(i, j);\n    }\n    return m_base_mapper.template loadPacket<PacketT,Alignment>(i + m_vert_offset, j + m_horiz_offset);\n  }\n\n  template <typename PacketT, int AlignmentType>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketT loadPacket(Index i, Index j) const {\n    if (UseDirectOffsets) {\n      return m_base_mapper.template load<PacketT,AlignmentType>(i, j);\n    }\n    return m_base_mapper.template loadPacket<PacketT,AlignmentType>(i + m_vert_offset, j + m_horiz_offset);\n  }\n\n  template <typename PacketT>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void storePacket(Index i, const PacketT& p) const {\n    if (UseDirectOffsets) {\n      m_base_mapper.storePacket(i, 0, p);\n    }\n    m_base_mapper.storePacket(i + m_vert_offset, m_horiz_offset, p);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE LinearMapper getLinearMapper(Index i, Index j) const {\n    if (UseDirectOffsets) {\n      return LinearMapper(m_base_mapper, i, j);\n    }\n    return LinearMapper(m_base_mapper, i + m_vert_offset, j + m_horiz_offset);\n  }\n\n  template <typename PacketT, int AlignmentType>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketT load(Index i) const {\n    EIGEN_STATIC_ASSERT((internal::is_same<PacketT, PacketT>::value), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    const int ActualAlignment = (AlignmentType == Aligned) && (Alignment == Aligned) ? Aligned : Unaligned;\n    if (UseDirectOffsets) {\n     return m_base_mapper.template loadPacket<PacketT,ActualAlignment>(i, 0);\n    }\n    return m_base_mapper.template loadPacket<PacketT,ActualAlignment>(i + m_vert_offset, m_horiz_offset);\n  }\n\n  template <typename PacketT>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool aligned(Index) const {\n    return false;\n  }\n\n  #ifdef EIGEN_USE_SYCL\n  // The placeholder accessors require to be bound to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_base_mapper.bind(cgh);\n  }\n  #endif\n\n  const ParentMapper& base_mapper() const { return m_base_mapper; }\n  Index vert_offset() const { return m_vert_offset; }\n  Index horiz_offset() const { return m_horiz_offset; }\n\n private:\n  ParentMapper m_base_mapper;\n  const Index m_vert_offset;\n  const Index m_horiz_offset;\n};\n\n\ntemplate<typename Scalar_, typename Index, int side,\n         typename Tensor,\n         typename nocontract_t, typename contract_t,\n         int packet_size,\n         bool inner_dim_contiguous, bool inner_dim_reordered, int Alignment,  template <class> class MakePointer_=MakePointer>\nclass TensorContractionInputMapper\n  : public BaseTensorContractionMapper<Scalar_, Index, side, Tensor, nocontract_t, contract_t, packet_size, inner_dim_contiguous, inner_dim_reordered, Alignment, MakePointer_> {\n\n public:\n  typedef Scalar_ Scalar;\n  typedef BaseTensorContractionMapper<Scalar, Index, side, Tensor, nocontract_t, contract_t, packet_size, inner_dim_contiguous, inner_dim_reordered, Alignment, MakePointer_> Base;\n  typedef TensorContractionSubMapper<Scalar, Index, side, Tensor, nocontract_t, contract_t, packet_size, inner_dim_contiguous, inner_dim_reordered, Alignment, MakePointer_> SubMapper;\n  typedef SubMapper VectorMapper;\n\n  EIGEN_DEVICE_FUNC TensorContractionInputMapper(const Tensor& tensor,\n                               const nocontract_t& nocontract_strides,\n                               const nocontract_t& ij_strides,\n                               const contract_t& contract_strides,\n                               const contract_t& k_strides)\n      : Base(tensor, nocontract_strides, ij_strides, contract_strides, k_strides) { }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE SubMapper getSubMapper(Index i, Index j) const {\n    return SubMapper(*this, i, j);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE VectorMapper getVectorMapper(Index i, Index j) const {\n    return VectorMapper(*this, i, j);\n  }\n  \n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE const CoeffLoader<Tensor, Tensor::RawAccess, MakePointer_>& get_tensor() const {\n    return Base::m_tensor;\n  }\n};\n\n\ntemplate <typename T> struct TensorContractionInputMapperTrait;\n\ntemplate<typename Scalar_, typename Index_, int side_,\n         typename Tensor_,\n         typename nocontract_t_, typename contract_t_,\n         int packet_size_,\n         bool inner_dim_contiguous_, bool inner_dim_reordered_, int Alignment_,  template <class> class MakePointer_>\nstruct TensorContractionInputMapperTrait<TensorContractionInputMapper<Scalar_, Index_, side_, Tensor_, \n                                                    nocontract_t_, contract_t_, packet_size_, inner_dim_contiguous_, \n                                                    inner_dim_reordered_, Alignment_, MakePointer_> > {\n\n      typedef Tensor_ XprType;\n      static const bool  inner_dim_contiguous = inner_dim_contiguous_;\n      static const bool  inner_dim_reordered = inner_dim_reordered_;\n  };  \n\n\n}  // end namespace internal\n}  // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_MAPPER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionSycl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library for linear algebra.\n//\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla Public License v. 2.0. If a copy of the MPL was not\n// distributed with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/*****************************************************************\n * TensorContractionSycl.h\n *\n * \\brief:\n *  TensorContractionSycl.h, provides various tensor contraction kernel for SYCL backend\n *\n *****************************************************************/\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_SYCL_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_SYCL_H\n\nnamespace Eigen {\n\nnamespace TensorSycl {\nnamespace internal {\n\n#ifndef EIGEN_SYCL_DISABLE_GEMV\n/*!\n * \\brief TVPanelSize, a template class used for setting the panel size required for launching General TensorVector\n * contraction kernel on various hardware devices.\n *\n * \\tparam Scalar: determines the element type of the tensor/vector\n *\n * \\tparam StorageIndex  determines the Index type.\n *\n * \\tparam NCWindow: determines the number of non-contracting element to be process by each work-group\n *\n * \\tparam CFactor: determines the number of contracting element to be process by each thread\n *\n * \\tparam NCFactor: determines the number of non-contracting element to be process by each thread\n */\ntemplate <typename Scalar, typename StorageIndex, StorageIndex NCWindow, StorageIndex CFactor, StorageIndex NCFactor>\nstruct TVPanelSize {\n  // LocalThreadSizeC: determines total number of thread per workgroup for the contracting dimension\n  static EIGEN_CONSTEXPR StorageIndex LocalThreadSizeC = EIGEN_SYCL_LOCAL_THREAD_DIM0;\n  // LocalThreadSizeNC: determines total number of thread per workgroup for the non-contracting dimension\n  static EIGEN_CONSTEXPR StorageIndex LocalThreadSizeNC = EIGEN_SYCL_LOCAL_THREAD_DIM1;\n  // TileSizeDimNC: determines the tile size for the non-contracting dimension\n  static EIGEN_CONSTEXPR StorageIndex TileSizeDimNC = NCWindow / NCFactor;\n  // TileSizeDimC: determines the tile size for the contracting dimension\n  static EIGEN_CONSTEXPR StorageIndex TileSizeDimC = CFactor * LocalThreadSizeNC * LocalThreadSizeC;\n  // WorkLoadPerThreadNC : determines workload per thread for loading the non-contracting dimension\n  static EIGEN_CONSTEXPR StorageIndex WorkLoadPerThreadNC = TileSizeDimNC / LocalThreadSizeNC;\n  // WorkLoadPerThreadC: determines workload per thread for loading the non-contracting dimension\n  static EIGEN_CONSTEXPR StorageIndex WorkLoadPerThreadC = TileSizeDimC / LocalThreadSizeC;\n  // BC : determines if supporting bank conflict is required\n  static EIGEN_CONSTEXPR bool BC = false;\n};\n#endif\n\n/*!\n * \\brief TTPanelSize, a template class used for setting the panel size required for launching General Tensor Tensor\n contraction kernel on various hardware devices.\n *\n * \\tparam Scalar: determines the element type of the tensor\n *\n * \\tparam StorageIndex: determines the Index type.\n *\n * \\tparam REG_SIZE_M: determines workload per thread for loading the M dimension This can be varied based on the\n available register on a chosen device(can be controlled by EIGEN_SYCL_REG_M macro).\n *\n * \\tparam REG_SIZE_N: determines workload per thread for loading the N dimension This can be varied based on the\n available register on a chosen device(can be controlled by EIGEN_SYCL_REG_N macro).\n *\n * \\tparam TSDK: determines Tile size for dimension K. The packet size is assumed to be considered\n */\n\ntemplate <typename Scalar, typename StorageIndex, StorageIndex REG_SIZE_M, StorageIndex REG_SIZE_N, StorageIndex TSDK>\nstruct TTPanelSize {\n  // TileSizeDimK: determines Tile size for dimension K. The packet size is assumed to be considered\n  static EIGEN_CONSTEXPR StorageIndex TileSizeDimK = TSDK;\n  // WorkLoadPerThreadM : determines workload per thread for loading the M dimension This can be varied based on the\n  // available register on a chosen device(can be controlled by EIGEN_SYCL_REG_M macro//\n#ifndef EIGEN_SYCL_REG_M\n  static EIGEN_CONSTEXPR StorageIndex WorkLoadPerThreadM = REG_SIZE_M;\n#else\n  static EIGEN_CONSTEXPR StorageIndex WorkLoadPerThreadM = EIGEN_SYCL_REG_M;\n#endif\n// WorkLoadPerThreadN : determines workload per thread for loading the N dimension This can be varied based on the\n// available register on a chosen device(can be controlled by EIGEN_SYCL_REG_N macro\n#ifndef EIGEN_SYCL_REG_N\n  static EIGEN_CONSTEXPR StorageIndex WorkLoadPerThreadN = REG_SIZE_N;\n#else\n  static EIGEN_CONSTEXPR StorageIndex WorkLoadPerThreadN = EIGEN_SYCL_REG_N;\n#endif\n  // LocalThreadSizeM: determines total number of thread per workgroup for the m dimension\n  static EIGEN_CONSTEXPR StorageIndex LocalThreadSizeM = EIGEN_SYCL_LOCAL_THREAD_DIM0;\n  // LocalThreadSizeN: determines total number of thread per workgroup for the n dimension\n  static EIGEN_CONSTEXPR StorageIndex LocalThreadSizeN = EIGEN_SYCL_LOCAL_THREAD_DIM1;\n  // TileSizeDimM: determines the tile size for the m dimension\n  static EIGEN_CONSTEXPR StorageIndex TileSizeDimM = LocalThreadSizeM * WorkLoadPerThreadM;\n  // TileSizeDimN: determines the tile size for the n dimension\n  static EIGEN_CONSTEXPR StorageIndex TileSizeDimN = LocalThreadSizeN * WorkLoadPerThreadN;\n  // LoadPerThreadLhs: determines workload per thread for loading Lhs Tensor. This must be divisable by packetsize\n  static EIGEN_CONSTEXPR StorageIndex LoadPerThreadLhs =\n      ((TileSizeDimK * WorkLoadPerThreadM * WorkLoadPerThreadN) / (TileSizeDimN));\n  // LoadPerThreadRhs: determines workload per thread for loading Rhs Tensor. This must be divisable by packetsize\n  static EIGEN_CONSTEXPR StorageIndex LoadPerThreadRhs =\n      ((TileSizeDimK * WorkLoadPerThreadM * WorkLoadPerThreadN) / (TileSizeDimM));\n  // BC : determines if supporting bank conflict is required\n  static EIGEN_CONSTEXPR bool BC = true;\n  // DoubleBuffer: determines if double buffering technique should be used (This can be disabled by\n  // EIGEN_SYCL_DISABLE_DOUBLE_BUFFER macro when the device doesnot have sufficient  local memory)\n  static EIGEN_CONSTEXPR bool DoubleBuffer =\n#ifdef EIGEN_SYCL_DISABLE_DOUBLE_BUFFER\n      false;\n#else\n      true;\n#endif\n};\n\n/* !\n * \\brief contraction_type: an enum class representing the Tensor Contraction implementation algorithm. This is used to\n * specialize the contraction algorithm based on device support for dedicated local memory.\n */\nenum class contraction_type { local, no_local };\n/* !\n * \\brief data_source an enum class determining the location of the data in a memory hierarchy (global, local, private).\n */\nenum class data_source { global_mem, local_mem, private_mem };\n\n/*!\n * \\brief read, a template function used for loading the data from global\n memory. This function is used to guarantee coalesced and vectorized load whenever possible\n *\n * \\tparam PacketLoad: determines if the each element of this tensor block should be loaded in a packet mode\n *\n * \\param is_coalesced_layout: determines whether or not the Tensor data in a memory can be access coalesced and\n vectorized when possible. Coalesced memory access is a key factor in Kernel performance. When a tensor is 2d and the\n contracting dimension is 1, it is always possible to accessed tensor data coalesced and vectorized. This is the case\n when RHS(right hand side) Tensor is transposed or when LHS(left hand side) Tensor is not transposed.\n *\n * \\tparam PacketType:  determines the type of packet\n *\n * \\tparam TensorMapper: determines the input tensor mapper type\n *\n * \\tparam StorageIndex: determines the Index type\n\n * \\param tensorMapper: is the input tensor\n *\n * \\param NCIndex: is the non-contracting dim index\n *\n * \\param CIndex is the contracting dim index\n *\n * \\param ld: is the leading dimension of the flattened tensor\n */\ntemplate <bool PacketLoad, bool is_coalesced_layout, bool, typename PacketType, typename TensorMapper,\n          typename StorageIndex>\nstatic EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename ::Eigen::internal::enable_if<PacketLoad, PacketType>::type read(\n    const TensorMapper &tensorMapper, const StorageIndex &NCIndex, const StorageIndex &CIndex, const StorageIndex &ld) {\n  const StorageIndex row = (is_coalesced_layout) ? NCIndex : CIndex;\n  const StorageIndex col = (is_coalesced_layout) ? CIndex : NCIndex;\n  return tensorMapper.get_tensor().template packet<Unaligned>(row + (col * ld));\n}\n\n/*!\n * \\brief read, special overload of read function, when the read access is not vectorized\n *\n * \\tparam PacketLoad: determines if the each element of this tensor block should be loaded in a packet mode\n *\n * \\param is_coalesced_layout: determines whether or not the Tensor data in a memory can be access coalesced and\n  vectorized when possible. Coalesced memory access is a key factor in Kernel performance. When a tensor is 2d and the\n  contracting dimension is 1, it is always possible to accessed tensor data coalesced and vectorized. This is the case\n  when RHS(right hand side) Tensor is transposed or when LHS(left hand side) Tensor is not transposed.\n *\n * \\tparam PacketType: determines the type of packet\n *\n * \\tparam TensorMapper: determines the input tensor mapper type\n *\n * \\tparam StorageIndex: determines the Index type\n\n * \\param tensorMapper: is the input tensor\n *\n * \\param NCIndex: is the non-contracting dim index\n *\n * \\param CIndex: is the contracting dim index\n */\ntemplate <bool PacketLoad, bool, bool IsRhs, typename PacketType, typename TensorMapper, typename StorageIndex>\nstatic EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename ::Eigen::internal::enable_if<!PacketLoad, PacketType>::type read(\n    const TensorMapper &tensorMapper, const StorageIndex &NCIndex, const StorageIndex &CIndex, const StorageIndex &) {\n  const StorageIndex row = (IsRhs) ? CIndex : NCIndex;\n  const StorageIndex col = (IsRhs) ? NCIndex : CIndex;\n  return tensorMapper(row, col);\n}\n\n/*!\n * \\brief write, a template function used for storing the data to local memory. This function is used to guarantee\n * coalesced and vectorized store whenever possible.\n *\n * \\tparam StorageIndex: determines the Index type\n *\n * \\param ld is the leading dimension of the local memory. ld is a compile time value for the local memory\n *\n * \\tparam data_source: an enum value representing if the location of the data in a memory hierarchy.\n *\n * \\tparam PacketType:  determines the type of packet\n *\n * \\tparam DataScalar: determines the output data type\n *\n * \\param packet_data: the data to be written in the local memory\n *\n * \\param ptr: a pointer to the local memory\n *\n * \\param CIndex is the contracting dim index\n */\n\ntemplate <typename StorageIndex, StorageIndex ld, data_source dt, typename PacketType, typename DataScalar>\nstatic EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    typename ::Eigen::internal::enable_if<dt != data_source::global_mem, void>::type\n    write(PacketType &packet_data, DataScalar ptr) {\n  EIGEN_CONSTEXPR int PacketSize = Eigen::internal::unpacket_traits<PacketType>::size;\n  EIGEN_UNROLL_LOOP\n  for (int i = 0; i < PacketSize; i++) {\n    *ptr = PacketWrapper<PacketType, PacketSize>::scalarize(i, packet_data);\n    ptr += ld;\n  }\n}\n\n/*!\n * \\brief Overloading the write function for storing the data to global memory, when vectorization enabled This function\n * is used to guarantee coalesced and vectorized store whenever possible.\n *\n * \\tparam data_source: an enum value representing if the location of the data in a memory hierarchy.\n *\n * \\tparam PacketType:  determines the type of packet\n *\n * \\tparam DataScalar: determines the output data type\n *\n * \\param packet_data: the data to be written in the local memory\n *\n * \\param ptr: a pointer to the local memory\n */\n\ntemplate <data_source dt, typename PacketType, typename DataScalar>\nstatic EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename ::Eigen::internal::enable_if<\n    Eigen::internal::unpacket_traits<PacketType>::size != 1 && dt == data_source::global_mem, void>::type\nwrite(PacketType &packet_data, DataScalar *ptr) {\n  ::Eigen::internal::pstoreu<DataScalar, PacketType>(ptr, packet_data);\n}\n\n/*!\n * \\brief Overloading the write function for storing the data to global memory, when vectorization is disabled.\n *\n * \\tparam data_source: an enum value representing if the location of the data in a memory hierarchy.\n *\n * \\tparam PacketType:  determines the type of packet\n *\n * \\tparam DataScalar: determines the output data type\n *\n * \\param packet_data: the data to be written in the local memory\n *\n * \\param ptr: a pointer to the local memory\n */\ntemplate <data_source dt, typename PacketType, typename DataScalar>\nstatic EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename ::Eigen::internal::enable_if<\n    Eigen::internal::unpacket_traits<PacketType>::size == 1 && dt == data_source::global_mem, void>::type\nwrite(PacketType &packet_data, DataScalar *ptr) {\n  *ptr = packet_data;\n}\n\n/*!\n * \\brief check_boundary: is used to check the edge condition for non-internal blocks.\n *\n * \\tparam is_internal: determines if the block is internal\n */\ntemplate <bool is_internal>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool check_boundary(bool) {\n  return true;\n}\n\n/*!\n * \\brief check_boundary: specialization of the check_boundary for non-internal blocks.\n *\n * \\param cond: true when the data is in range. Otherwise false\n */\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool check_boundary<false>(bool cond) {\n  return cond;\n}\n\n/*!\n * \\brief BlockProperties is a template class that provides different characteristic of a block of each Tensor processed\n * by each workgroup.\n *\n * \\tparam is_transposed: iff true, determines whether or not the block of the Tensor is transposed\n *\n * \\tparam packet_load_: determines if the each element of this tensor block should be loaded in a packet mode\n *\n * \\tparam PacketType:  determines the type of packet\n *\n * \\tparam OutType: determines the type of each element for this block of tensor. If packet load is true, it will be\n * packetType; Otherwise it will be scalar Type\n *\n * \\param elements_per_access determines the size of each element based on OutType\n *\n * \\param is_coalesced_layout  determines whether or not the Tensor data in a memory can be access coalesced and\n * vectorized when possible. Coalesced memory access is a key factor in Kernel performance. When a tensor is 2d and the\n * contracting dimension is 1, it is always possible to accessed tensor data coalesced and vectorized. This is the case\n * when RHS(right hand side) Tensor is transposed or when LHS(left hand side) Tensor is not transposed.\n *\n * \\param nc_stride determines the stride of non-contracting dimension to access the next adjustment element within the\n * Tensor Block for each workgroup\n *\n * \\param c_stride  determines the stride of contracting dimension to access the next adjustment element within the\n * Tensor Block for each workgroup\n */\ntemplate <bool is_transposed, bool is_rhs_, bool packet_load_, typename PacketType>\nstruct BlockProperties {\n  static EIGEN_CONSTEXPR bool packet_load = packet_load_;\n  typedef typename Eigen::internal::unpacket_traits<PacketType>::type OutScalar;\n  static EIGEN_CONSTEXPR bool is_rhs = is_rhs_;\n  typedef typename Eigen::internal::conditional<packet_load, PacketType, OutScalar>::type OutType;\n  static EIGEN_CONSTEXPR int elements_per_access = Eigen::internal::unpacket_traits<OutType>::size;\n  static EIGEN_CONSTEXPR bool is_coalesced_layout = !(is_transposed ^ is_rhs);\n  static EIGEN_CONSTEXPR int nc_stride = (is_coalesced_layout ? elements_per_access : 1);\n  static EIGEN_CONSTEXPR int c_stride = (is_coalesced_layout ? 1 : elements_per_access);\n};\n\n/*!\n * \\brief ThreadProperties is a template class that provides each thread's properties within a workgroup.  Please see\n * the sycl-1.2.1 specification (https://www.khronos.org/registry/SYCL/specs/sycl-1.2.1.pdf) for the workgroup,\n * work-items\n *\n * \\tparam StorageIndex: determines the StorageIndex Type\n *\n * \\param linearLocalThreadId: determines the linearized location of a thread within a work-group\n *\n * \\param kGroupId: determines the logical group id in a k dimension of the flattened tensor. It will be > 1 when\n * tall/skinny algorithm is used\n *\n * \\param mGroupOffset: determines the logical start position of all thread within a workgroup for the m dimension of\n * the flattened tensor.\n *\n * \\param kGroupOffset determines the logical start position of all thread within a workgroup for the k dimension of the\n * flattened tensor. It will be > 1 when tall/skinny algorithm is used.\n *\n * \\param mLocalOffset: determines the logical start position of each thread within a workgroup for the m dimension of a\n * flattened tensor. The position determines the distance of each thread within the workgroup from each other\n * independent from their global position.\n *\n * \\param nLocalOffset: determines the logical start position of each thread within a workgroup for the n dimension of a\n * flattened tensor. The position determines the distance of each thread within the workgroup from each other\n * independent from their global position.\n *\n * \\param mGlobalOffset: determines the logical start position of each thread a thread for the m dimension on a\n * flattened tensor\n *\n * \\param nGlobalOffset: determines the logical start position of each thread a thread for the n dimension on a\n * flattened tensor\n *\n * \\param kSize : determine the number of the k elements of the flattened Tensor to be processed by each thread for the\n * given tensor block. This is !=K dimension of Flattened Tensor when Tall/Skinny matrix is used.\n *\n * \\param is_internal : this will determined if the thread within the work-group computes an internal block of tensor or\n * the edge blocks. When it is internal, there is no need to check the boundaries and all the if stantement can be\n * resolve by compiler.\n */\ntemplate <typename StorageIndex>\nstruct ThreadProperties {\n  const StorageIndex linearLocalThreadId;\n  const StorageIndex kGroupId;\n  const StorageIndex mGroupOffset;\n  const StorageIndex nGroupOffset;\n  const StorageIndex kGroupOffset;\n  const StorageIndex mLocalOffset;\n  const StorageIndex nLocalOffset;\n  const StorageIndex mGlobalOffset;\n  const StorageIndex nGlobalOffset;\n  StorageIndex kSize;\n  const bool is_internal;\n  // this is used to adjust the last block\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ThreadProperties(\n      const StorageIndex linearLocalThreadId_, const StorageIndex kGroupId_, const StorageIndex mGroupOffset_,\n      const StorageIndex nGroupOffset_, const StorageIndex kGroupOffset_, const StorageIndex mLocalOffset_,\n      const StorageIndex nLocalOffset_, const StorageIndex mGlobalOffset_, const StorageIndex nGlobalOffset_,\n      StorageIndex kSize_, const bool is_internal_)\n      : linearLocalThreadId(linearLocalThreadId_),\n        kGroupId(kGroupId_),\n        mGroupOffset(mGroupOffset_),\n        nGroupOffset(nGroupOffset_),\n        kGroupOffset(kGroupOffset_),\n        mLocalOffset(mLocalOffset_),\n        nLocalOffset(nLocalOffset_),\n        mGlobalOffset(mGlobalOffset_),\n        nGlobalOffset(nGlobalOffset_),\n        kSize(kSize_),\n        is_internal(is_internal_) {}\n};\n\n/*!\n * \\brief TensorContractionKernel is a template class that provides Tensor -Tensor contraction operation.\n *\n * \\tparam OutScalar: determines the output scalar type\n *\n * \\tparam LhsScalar: determines the left-hand-side scalar type\n *\n * \\tparam RhsScalar: determines the right-hand-side scalar type\n *\n * \\tparam OutAccessor: determines the sycl accessor type for out put (please see the sycl-1.2.1 specification\n (https://www.khronos.org/registry/SYCL/specs/sycl-1.2.1.pdf) for accessor definition)\n *\n * \\tparam LhsMapper determines the tensor contraction mapper type for left-hand-side matrix\n *\n * \\tparam RhsMapper determines the tensor contraction mapper type for right-hand-side matrix\n *\n * \\tparam StorageIndex: determines the StorageIndex Type\n *\n * \\tparam Properties: determines the Contraction Panel properties\n *\n * \\tparam TripleDim: determines the M, K, N dimensions for the flatten tensors in order to treat them as a matrix\n *\n * \\tparam Vectorizable: determines whether or not the vectorization is enabled for the Eigen expression.\n *\n * \\tparam input_mapper_properties : determine if the input tensors are matrix. If they are matrix, special memory\n access is used to guarantee that always the memory access are coalesced.\n *\n * \\tptaram IsFinal : determine if this is the final kernel. If so, the result will be written in a final output.\n Otherwise, the result of contraction will be written iin a temporary buffer. This is the case when Tall/Skinny\n contraction is used. So in this case, a final reduction step is required to compute final output.\n\n * \\tparam contraction_tp: it is an enum value representing whether the local memroy/no local memory implementation of\n the algorithm to be used\n *\n * \\param scratch: local memory containing tiles of LHS and RHS tensors for each work-group\n *\n * \\param lhs: determines the left-hand-side flattened tensor (tensor mapper)\n *\n * \\param rhs: determines the right-hand-side flattened tensor (tensor mapper)\n *\n * \\param out_res: determines the output tensor containing the contraction result\n *\n * \\param groupSizeM: a logical number determining the number of work-group for m dimension\n *\n * \\param groupSizeN: a logical number determining the number of work-group for n dimension\n *\n * \\param numTiles: determines total number of tiles on the k dimension\n *\n * \\param TripleDim: determines the M, K, N dimensions for the flatten tensors in order to treat them as a matrix\n */\ntemplate <typename OutScalar, typename LhsScalar, typename RhsScalar, typename OutAccessor, typename LhsMapper,\n          typename RhsMapper, typename StorageIndex, typename Properties, typename TripleDim, bool Vectorizable,\n          typename input_mapper_properties, bool IsFinal, contraction_type contraction_tp>\nclass TensorContractionKernel {\n public:\n  typedef typename Eigen::TensorSycl::internal::Vectorise<OutScalar, Eigen::SyclDevice, Vectorizable>::PacketReturnType\n      PacketReturnType;\n  static EIGEN_CONSTEXPR int PacketSize =\n      Eigen::TensorSycl::internal::Vectorise<OutScalar, Eigen::SyclDevice, Vectorizable>::PacketSize;\n  static EIGEN_CONSTEXPR bool is_lhs_transposed =\n      !::Eigen::internal::TensorContractionInputMapperTrait<LhsMapper>::inner_dim_contiguous;\n  static EIGEN_CONSTEXPR bool is_rhs_transposed =\n      !::Eigen::internal::TensorContractionInputMapperTrait<RhsMapper>::inner_dim_contiguous;\n\n  typedef BlockProperties<is_lhs_transposed, false, input_mapper_properties::is_lhs_matrix && Vectorizable,\n                          PacketReturnType>\n      LHSBlockProperties;\n\n  typedef BlockProperties<is_rhs_transposed, true, input_mapper_properties::is_rhs_matrix && Vectorizable,\n                          PacketReturnType>\n      RHSBlockProperties;\n\n  static EIGEN_CONSTEXPR StorageIndex NStride =\n      contraction_tp == contraction_type::local ? Properties::WorkLoadPerThreadN : RHSBlockProperties::nc_stride;\n\n  typedef cl::sycl::accessor<OutScalar, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local> Scratch;\n  typedef cl::sycl::multi_ptr<OutScalar, cl::sycl::access::address_space::local_space> local_ptr;\n  typedef OutScalar * /*cl::sycl::multi_ptr<OutScalar, cl::sycl::access::address_space::private_space>*/ private_ptr;\n  typedef\n      typename ::Eigen::internal::conditional<contraction_tp == contraction_type::local, local_ptr, private_ptr>::type\n          tile_ptr;\n  static EIGEN_CONSTEXPR StorageIndex LSDL = contraction_tp == contraction_type::local\n                                                 ? Properties::TileSizeDimM + Properties::BC\n                                                 : Properties::WorkLoadPerThreadM;\n  static EIGEN_CONSTEXPR StorageIndex LSDR = contraction_tp == contraction_type::local\n                                                 ? Properties::TileSizeDimN + Properties::BC\n                                                 : Properties::WorkLoadPerThreadN;\n  static EIGEN_CONSTEXPR StorageIndex LocalOffset = Properties::LocalThreadSizeM * Properties::LocalThreadSizeN;\n\n  /**\n   * \\brief MemHolder this is a place holder struct for creating memory hierarchy in SYCL. Inside SYCL kernel it is not\n   * allowed to have dynamic memory allocation. While the local memory is created outside of the kernel and passed to\n   * the kernel as an accessor, the private memory can only allowed to be allocated statically. Since we are abstracting\n   * the TiledMemory for both local and private memory, the MemHolder structs is used as a helper to abstract out\n   * different type of memory needed when local/no_local memory computation is called.\n   *\n   * \\tparam contraction_type: it is an enum value representing whether the local memroy/no local memory implementation\n   of the algorithm to be used\n   * \\tparam the private memory size\n   * \\param ptr the tile memory pointer type\n   */\n  template <contraction_type, StorageIndex>\n  struct MemHolder {\n    tile_ptr ptr;\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE MemHolder(local_ptr block_start_ptr) : ptr(block_start_ptr) {}\n  };\n  /**\n   * \\brief specialization of memHolder class when no local memory kernel is used.\n   */\n  template <StorageIndex MemSize>\n  struct MemHolder<contraction_type::no_local, MemSize> {\n    OutScalar ptr[MemSize] = {OutScalar{0}};\n  };\n  /**\n   * \\brief TiledMemory: contains required memory pointer for loading  each tile of the TensorContraction panel from\n   * global memory to local/private memory when local/no_local algorithm used.\n   *\n   * \\param lhs_scratch_extract : determines the LHS tile memory. It is either private or local memory based on the\n   * selected contraction_type.\n   *\n   * \\param rhs_scratch_extract : determines the RHS tile memory. It is either private or local memory based on the\n   * selected contraction_type.\n   *\n   * \\param lhs_extract_index: determins the position of each thread on a local memory for lhs input. When private\n   * memory is used this is set to zero as this is not applicable in case of private memory.\n   *\n   * \\param rhs_extract_index: determins the position of each thread on a local memory for rhs input. When private\n   * memory is used this is set to zero as this is not applicable in case of private memory.\n   *\n   * \\param lhs_scratch_compute : determines the  location to load for computation for lhs_local memory. This is the\n   * same as lhs_scratch_extract for private memory.\n   *\n   * \\param rhs_scratch_compute : determines the  location to load for computation for rhs_local memory. This is the\n   * same as rhs_scratch_extract for private memory.\n   */\n  struct TiledMemory {\n    MemHolder<contraction_tp, Properties::WorkLoadPerThreadM * Properties::TileSizeDimK> lhs_scratch_extract;\n    MemHolder<contraction_tp, Properties::WorkLoadPerThreadN * Properties::TileSizeDimK> rhs_scratch_extract;\n    tile_ptr lhs_scratch_ptr_compute;\n    tile_ptr rhs_scratch_ptr_compute;\n    const std::pair<StorageIndex, StorageIndex> lhs_extract_index;\n    const std::pair<StorageIndex, StorageIndex> rhs_extract_index;\n    template <contraction_type tp = contraction_tp>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TiledMemory(const ThreadProperties<StorageIndex> &, local_ptr,\n                typename ::Eigen::internal::enable_if<tp == contraction_type::no_local>::type * = 0)\n        : lhs_scratch_extract{},\n          rhs_scratch_extract{},\n          lhs_scratch_ptr_compute(lhs_scratch_extract.ptr),\n          rhs_scratch_ptr_compute(rhs_scratch_extract.ptr),\n          lhs_extract_index(std::pair<StorageIndex, StorageIndex>(StorageIndex{0}, StorageIndex{0})),\n          rhs_extract_index(std::pair<StorageIndex, StorageIndex>(StorageIndex{0}, StorageIndex{0})) {}\n\n    template <contraction_type tp = contraction_tp>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TiledMemory(const ThreadProperties<StorageIndex> &thread_properties, local_ptr block_start_ptr,\n                typename ::Eigen::internal::enable_if<tp == contraction_type::local>::type * = 0)\n        : lhs_scratch_extract{block_start_ptr},\n          rhs_scratch_extract{lhs_scratch_extract.ptr +\n                              ((Properties::DoubleBuffer + 1) * LSDL * Properties::TileSizeDimK)},\n          lhs_scratch_ptr_compute(lhs_scratch_extract.ptr + thread_properties.mLocalOffset),\n          rhs_scratch_ptr_compute(rhs_scratch_extract.ptr + thread_properties.nLocalOffset),\n          lhs_extract_index(\n              local_id_extract<LHSBlockProperties, Properties::TileSizeDimM>(thread_properties.linearLocalThreadId)),\n          rhs_extract_index(\n              local_id_extract<RHSBlockProperties, Properties::TileSizeDimN>(thread_properties.linearLocalThreadId)) {}\n  };\n\n  Scratch scratch;\n  const LhsMapper lhs;\n  const RhsMapper rhs;\n  OutAccessor out_res;\n  const StorageIndex groupSizeM;\n  const StorageIndex groupSizeN;\n  const StorageIndex numTiles;\n  const TripleDim triple_dim;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorContractionKernel(Scratch scratch_, const LhsMapper lhs_,\n                                                                const RhsMapper rhs_, OutAccessor out_res_,\n                                                                const StorageIndex groupSizeM_,\n                                                                const StorageIndex groupSizeN_,\n                                                                const StorageIndex numTiles_,\n                                                                const TripleDim triple_dim_)\n      : scratch(scratch_),\n        lhs(lhs_),\n        rhs(rhs_),\n        out_res(out_res_),\n        groupSizeM(groupSizeM_),\n        groupSizeN(groupSizeN_),\n        numTiles(numTiles_),\n        triple_dim(triple_dim_) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorContractionKernel(Scratch scratch_, const LhsMapper lhs_,\n                                                                const RhsMapper rhs_, OutAccessor out_res_,\n                                                                const StorageIndex groupSizeM_,\n                                                                const StorageIndex numTiles_,\n                                                                const TripleDim triple_dim_)\n      : TensorContractionKernel(scratch_, lhs_, rhs_, out_res_, groupSizeM_, 1, numTiles_, triple_dim_) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void operator()(cl::sycl::nd_item<1> itemID) {\n    const StorageIndex linearLocalThreadId = itemID.get_local_id(0);\n    const StorageIndex nLocalThreadId = linearLocalThreadId / Properties::LocalThreadSizeM;\n    const StorageIndex mLocalThreadId = linearLocalThreadId % Properties::LocalThreadSizeM;\n    const StorageIndex mGroupId = itemID.get_group(0) % groupSizeM;\n    const StorageIndex tmp = itemID.get_group(0) / groupSizeM;\n    const StorageIndex nGroupId = IsFinal ? tmp : tmp % groupSizeN;\n    const StorageIndex kGroupId = IsFinal ? 0 : tmp / groupSizeN;\n    const StorageIndex mGroupOffset = mGroupId * Properties::TileSizeDimM;\n    const StorageIndex nGroupOffset = nGroupId * Properties::TileSizeDimN;\n    const StorageIndex mLocalOffset = PacketSize * mLocalThreadId;\n    const StorageIndex nLocalOffset = NStride * nLocalThreadId;\n    const StorageIndex mGlobalOffset = mGroupOffset + mLocalOffset;\n    const StorageIndex nGlobalOffset = nGroupOffset + nLocalOffset;\n\n    const StorageIndex kSizePerWG = IsFinal ? triple_dim.K : numTiles * Properties::TileSizeDimK;\n    StorageIndex kGroupOffset = kGroupId * kSizePerWG;\n    const bool is_internal = triple_dim.M - mGroupOffset >= Properties::TileSizeDimM &&\n                             triple_dim.N - nGroupOffset >= Properties::TileSizeDimN &&\n                             triple_dim.K - kGroupOffset >= kSizePerWG;\n    // this is used to adjust the last block\n    StorageIndex kSize = IsFinal ? triple_dim.K : std::min(kSizePerWG, triple_dim.K - kGroupOffset);\n    // This is used to find out the lats K offset so that kGroupOffset -kSize can compute the coffset for loading to\n    // tile\n    kGroupOffset += kSize;\n\n    auto thread_properties =\n        ThreadProperties<StorageIndex>(linearLocalThreadId, kGroupId, mGroupOffset, nGroupOffset, kGroupOffset,\n                                       mLocalOffset, nLocalOffset, mGlobalOffset, nGlobalOffset, kSize, is_internal);\n\n    auto out_ptr = out_res.get_pointer() + (IsFinal ? 0 : thread_properties.kGroupId * triple_dim.M * triple_dim.N);\n\n    (thread_properties.is_internal) ? compute_panel<true>(itemID, thread_properties, out_ptr)\n                                    : compute_panel<false>(itemID, thread_properties, out_ptr);\n  }\n  // The compute block computes the contraction operation private block for each thread and store the resutl in the\n  // privateRes memory of Each computation the compute block function is independent of local and no local concepts as\n  // it only compute the block on each thread's private memory space\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void compute_block_per_tile(OutScalar *lhs_block_ptr, OutScalar *rhs_block_ptr,\n                                                                    PacketReturnType *privateRes) {\n    StorageIndex idx = 0;\n    EIGEN_CONSTEXPR StorageIndex lhs_stride =\n        contraction_tp == contraction_type::local ? (PacketSize * Properties::LocalThreadSizeM) : 1;\n    EIGEN_UNROLL_LOOP\n    for (StorageIndex wLPTN = 0; wLPTN < Properties::WorkLoadPerThreadN; wLPTN++) {\n      auto rhsPacket = PacketReturnType{*(rhs_block_ptr + wLPTN)};\n      StorageIndex lhs_index = 0;\n      EIGEN_UNROLL_LOOP\n      for (StorageIndex wLPTM = 0; wLPTM < Properties::WorkLoadPerThreadM / PacketSize; wLPTM++) {\n        PacketReturnType lhsPack{};\n        Eigen::TensorSycl::internal::PacketWrapper<PacketReturnType, PacketSize>::set_packet(lhsPack,\n                                                                                             lhs_block_ptr + lhs_index);\n        privateRes[idx] = ::Eigen::internal::pmadd(lhsPack, rhsPacket, privateRes[idx]);\n\n        lhs_index += lhs_stride;\n        idx++;\n      }\n    }\n  }\n  // The store function write the computed contraction operation in the private memory of each thread to the global\n  // memory. The store function is independent of local and no local concepts s that it can be abstract out in the base\n  // class.\n  template <bool is_internal_block, StorageIndex PrivateNStride, typename OutPtr>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void store(OutPtr *out_ptr, PacketReturnType *privateRes,\n                                                   StorageIndex mGlobalOffset, StorageIndex nGlobalOffset) {\n    auto chk_bound = [&](const StorageIndex &mIndex, const StorageIndex &nIndex) EIGEN_DEVICE_FUNC {\n      return (mIndex + PacketSize - 1 < triple_dim.M && nGlobalOffset + nIndex < triple_dim.N);\n    };\n    // when local memory is not used M and N are both accessed in a coalesced way. However, when local memory is\n    // available the k*N is transposed in the local to N*K therefore, each blocks operates on blockId*\n    // WorkLoadPerThreadN slice of N\n    EIGEN_CONSTEXPR StorageIndex GlobalNStride =\n        contraction_tp == contraction_type::local ? 1 : Properties::LocalThreadSizeN;\n    EIGEN_UNROLL_LOOP\n    for (StorageIndex wLPTN = 0; wLPTN < Properties::WorkLoadPerThreadN / PrivateNStride; wLPTN++) {\n      // output leading dimension\n      StorageIndex outputLD = 0;\n      // When local memory is used the PrivateNstride is always 1 because the coalesed access on N is loaded into Local\n      // memory and extracting from local to global is the same as no transposed version. However, when local memory is\n      // not used and RHS is transposed we packetize the load for RHS.\n      EIGEN_UNROLL_LOOP\n      for (StorageIndex nId = 0; nId < PrivateNStride; nId++) {\n        StorageIndex globalRow = mGlobalOffset;\n        EIGEN_UNROLL_LOOP\n        for (StorageIndex wLPTM = 0; wLPTM < Properties::WorkLoadPerThreadM / PacketSize; wLPTM++) {\n          PacketReturnType privetOut = privateRes[wLPTM];\n          if (check_boundary<is_internal_block>(chk_bound(globalRow, nId))) {\n            // Store the final results in C. The C matrix has always M as a first StorageIndex and N as a second\n            // StorageIndex Therefore it is always coalesced layout\n            write<data_source::global_mem>(privetOut, out_ptr + outputLD + globalRow);\n          } else {\n            EIGEN_UNROLL_LOOP\n            for (StorageIndex mId = 0; mId < PacketSize; mId++) {\n              StorageIndex mOffset = globalRow + mId;\n              if (mOffset < triple_dim.M && (nGlobalOffset + nId < triple_dim.N)) {\n                out_ptr[mOffset + outputLD] =\n                    Eigen::TensorSycl::internal::PacketWrapper<PacketReturnType, PacketSize>::scalarize(mId, privetOut);\n              }\n            }\n          }\n          globalRow += (PacketSize * Properties::LocalThreadSizeM);\n        }\n        outputLD += triple_dim.M;\n        privateRes += Properties::WorkLoadPerThreadM / PacketSize;\n      }\n      out_ptr += (GlobalNStride * outputLD);\n\n      nGlobalOffset += (PrivateNStride * GlobalNStride);\n    }\n  }\n  // when no local memory is used the following extract_block will be enabled\n  template <typename InputBlockProperties, bool is_internal_block, typename Input, typename PrivateReg,\n            contraction_type contract_tp = contraction_tp>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n      typename ::Eigen::internal::enable_if<contract_tp == contraction_type::no_local>::type\n      extract_block(const Input &inpt, PrivateReg private_ptr, const std::pair<StorageIndex, StorageIndex> &,\n                    const StorageIndex &ncOffset, const StorageIndex cOffset) {\n    EIGEN_CONSTEXPR StorageIndex LocalThreadSizeNC =\n        InputBlockProperties::is_rhs ? Properties::LocalThreadSizeN : Properties::LocalThreadSizeM;\n    EIGEN_CONSTEXPR StorageIndex WorkLoadPerThreadNC =\n        InputBlockProperties::is_rhs ? Properties::WorkLoadPerThreadN : Properties::WorkLoadPerThreadM;\n    const StorageIndex &NC = InputBlockProperties::is_rhs ? triple_dim.N : triple_dim.M;\n\n    auto chk_bound = [&](const StorageIndex &CIndex, const StorageIndex &NCIndex) EIGEN_DEVICE_FUNC {\n      return ((CIndex + InputBlockProperties::c_stride - 1 < triple_dim.K) &&\n              (NCIndex + InputBlockProperties::nc_stride - 1 < NC));\n    };\n    const StorageIndex ld = InputBlockProperties::is_coalesced_layout ? NC : triple_dim.K;\n    StorageIndex cIndex = cOffset;\n\n    EIGEN_UNROLL_LOOP\n    for (StorageIndex cId = 0; cId < Properties::TileSizeDimK / InputBlockProperties::c_stride; cId++) {\n      StorageIndex ncIndex = ncOffset;\n      EIGEN_UNROLL_LOOP\n      for (StorageIndex ncId = 0; ncId < WorkLoadPerThreadNC / InputBlockProperties::nc_stride; ncId++) {\n        if (check_boundary<is_internal_block>(chk_bound(cIndex, ncIndex))) {\n          auto val =\n              read<InputBlockProperties::packet_load, InputBlockProperties::is_coalesced_layout,\n                   InputBlockProperties::is_rhs, typename InputBlockProperties::OutType>(inpt, ncIndex, cIndex, ld);\n\n          write<StorageIndex, (InputBlockProperties::is_coalesced_layout ? 1 : WorkLoadPerThreadNC),\n                data_source::private_mem>(val, private_ptr);\n        } else {\n          EIGEN_UNROLL_LOOP\n          for (StorageIndex i = 0; i < InputBlockProperties::elements_per_access; i++) {\n            const StorageIndex ncInd = ncIndex + (InputBlockProperties::is_coalesced_layout ? i : 0);\n            const StorageIndex cInd = cIndex + (InputBlockProperties::is_coalesced_layout ? 0 : i);\n            OutScalar val =\n                (ncInd < NC && cInd < triple_dim.K)\n                    ? read<false, InputBlockProperties::is_coalesced_layout, InputBlockProperties::is_rhs, OutScalar>(\n                          inpt, ncInd, cInd, ld)\n                    : OutScalar(0);\n            write<StorageIndex, (InputBlockProperties::is_coalesced_layout ? 1 : WorkLoadPerThreadNC),\n                  data_source::private_mem>(\n                val, private_ptr + (InputBlockProperties::is_coalesced_layout ? i : 0) +\n                         ((InputBlockProperties::is_coalesced_layout ? 0 : i) * WorkLoadPerThreadNC));\n          }\n        }\n\n        // if it is lhs we have to load it packetised when the packet size is > 1, because the output is coalesced. So\n        // even if M is not accessed in a coalesced mode, we have to load packet_size number of m per thread.\n        ncIndex = (!InputBlockProperties::is_rhs && InputBlockProperties::nc_stride == 1 && PacketSize != 1)\n                      ? ncOffset + (ncId + 1) % PacketSize + ((ncId + 1) / PacketSize) * LocalThreadSizeNC\n                      : (ncIndex + InputBlockProperties::nc_stride * LocalThreadSizeNC);\n        private_ptr += InputBlockProperties::nc_stride;\n      }\n      // the previous for loop ( private_ptr += (ncId * nc_stride)) has already moved ptr with one WorkLoadPerThreadNC\n      private_ptr += (InputBlockProperties::c_stride - 1) * WorkLoadPerThreadNC;\n      cIndex += InputBlockProperties::c_stride;\n    }\n  }\n  template <typename InputBlockProperties, StorageIndex TileSizeDimNC>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::pair<StorageIndex, StorageIndex> local_id_extract(\n      const StorageIndex &linearLocalThreadId) {\n    const StorageIndex localThreadNC =\n        (InputBlockProperties::is_coalesced_layout)\n            ? linearLocalThreadId % (TileSizeDimNC / InputBlockProperties::nc_stride)\n            : linearLocalThreadId / (Properties::TileSizeDimK / InputBlockProperties::c_stride);\n    const StorageIndex localThreadC =\n        (InputBlockProperties::is_coalesced_layout)\n            ? linearLocalThreadId / (TileSizeDimNC / InputBlockProperties::nc_stride)\n            : linearLocalThreadId % (Properties::TileSizeDimK / InputBlockProperties::c_stride);\n    return std::pair<StorageIndex, StorageIndex>(localThreadNC, localThreadC);\n  }\n\n  template <bool db = Properties::DoubleBuffer, contraction_type ctp = contraction_tp>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n      typename ::Eigen::internal::enable_if<db && ctp == contraction_type::local>::type\n      sync_mem(const cl::sycl::nd_item<1> &, bool &db_offset) noexcept {\n    db_offset = !db_offset;\n  }\n\n  template <bool db = Properties::DoubleBuffer, contraction_type ctp = contraction_tp>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n      typename ::Eigen::internal::enable_if<!db && ctp == contraction_type::local>::type\n      sync_mem(const cl::sycl::nd_item<1> &itemID, bool &) noexcept {\n    itemID.barrier(cl::sycl::access::fence_space::local_space);\n  }\n\n  template <contraction_type ctp = contraction_tp>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n      typename ::Eigen::internal::enable_if<ctp == contraction_type::no_local>::type\n      sync_mem(const cl::sycl::nd_item<1> &, bool &) noexcept {\n    return;\n  }\n\n  template <bool need_sync, contraction_type ctp = contraction_tp>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n      typename ::Eigen::internal::enable_if<need_sync && ctp == contraction_type::no_local>::type\n      sync_thread(const cl::sycl::nd_item<1> &\n#ifdef EIGEN_SYCL_ARM_GPU_CACHE_OPTIMISATION\n                      itemID\n#endif\n                  ) noexcept {\n#ifdef EIGEN_SYCL_ARM_GPU_CACHE_OPTIMISATION\n    itemID.barrier(cl::sycl::access::fence_spacce::local_space);\n#else\n    return;\n#endif\n  }\n  template <bool need_sync, contraction_type ctp = contraction_tp>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n      typename ::Eigen::internal::enable_if<need_sync && ctp == contraction_type::local>::type\n      sync_thread(const cl::sycl::nd_item<1> &itemID) {\n    itemID.barrier(cl::sycl::access::fence_space::local_space);\n  }\n  template <bool need_sync>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename ::Eigen::internal::enable_if<!need_sync>::type sync_thread(\n      const cl::sycl::nd_item<1> &) {\n    return;\n  }\n\n  template <bool is_internal_block>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void compute_tile_per_panel(const cl::sycl::nd_item<1> &itemID,\n                                                                    ThreadProperties<StorageIndex> &thread_properties,\n                                                                    TiledMemory &tiled_input_block,\n                                                                    PacketReturnType *privateRes, bool &db_offset) {\n    // Tiling the Rhs block from global to local memory\n    extract_block<RHSBlockProperties, is_internal_block>(\n        rhs, tiled_input_block.rhs_scratch_extract.ptr + (db_offset * Properties::TileSizeDimK * LSDR),\n        tiled_input_block.rhs_extract_index,\n        contraction_tp == contraction_type::local ? thread_properties.nGroupOffset : thread_properties.nGlobalOffset,\n        thread_properties.kGroupOffset - thread_properties.kSize);\n\n    sync_thread<contraction_tp == contraction_type::no_local>(itemID);\n\n    // Tiling the Lhs block from global to local memory\n    extract_block<LHSBlockProperties, is_internal_block>(\n        lhs, tiled_input_block.lhs_scratch_extract.ptr + (db_offset * LSDL * Properties::TileSizeDimK),\n        tiled_input_block.lhs_extract_index,\n        contraction_tp == contraction_type::local ? thread_properties.mGroupOffset : thread_properties.mGlobalOffset,\n        thread_properties.kGroupOffset - thread_properties.kSize);\n\n    // itemID.barrier(cl::sycl::access::fence_space::local_space);\n    sync_thread<contraction_tp == contraction_type::local>(itemID);\n    // switch to compute mede\n    StorageIndex lhs_offset = (db_offset * LSDL * Properties::TileSizeDimK);\n    StorageIndex rhs_offset = (db_offset * Properties::TileSizeDimK * LSDR);\n    // Loop over the values of a single tile\n    for (StorageIndex k = 0; k < Properties::TileSizeDimK; k++) {\n      compute_block_per_tile(tiled_input_block.lhs_scratch_ptr_compute + lhs_offset,\n                             tiled_input_block.rhs_scratch_ptr_compute + rhs_offset, privateRes);\n      lhs_offset += LSDL;\n      rhs_offset += LSDR;\n    }\n    // computing the K index for the next tile\n    thread_properties.kSize -= Properties::TileSizeDimK;\n    sync_mem(itemID, db_offset);\n  }\n\n  // when local memory is available the following compute_panel will be enabled\n  template <bool is_internal_block, typename OutPtr>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void compute_panel(const cl::sycl::nd_item<1> &itemID,\n                                                           ThreadProperties<StorageIndex> &thread_properties,\n                                                           OutPtr out_ptr) {\n    auto tiled_input_block = TiledMemory{thread_properties, scratch.get_pointer()};\n    // Allocate register space\n    PacketReturnType privateRes[Properties::WorkLoadPerThreadM * Properties::WorkLoadPerThreadN / PacketSize] = {\n        PacketReturnType{0}};\n    bool db_offset = 0;\n\n    while (thread_properties.kSize >= Properties::TileSizeDimK) {\n      compute_tile_per_panel<is_internal_block>(itemID, thread_properties, tiled_input_block, privateRes, db_offset);\n    }\n    if (thread_properties.kSize > 0) {\n      compute_tile_per_panel<false>(itemID, thread_properties, tiled_input_block, privateRes, db_offset);\n    }\n\n    // Storing the final results in the output\n    store<is_internal_block,\n          contraction_tp == contraction_type::local ? static_cast<StorageIndex>(1) : RHSBlockProperties::nc_stride>(\n        out_ptr + thread_properties.nGlobalOffset * triple_dim.M, privateRes, thread_properties.mGlobalOffset,\n        thread_properties.nGlobalOffset);\n  }\n  // When local memory is available the following extract_block will be enabled\n  template <typename InputBlockProperties, bool is_internal_block, typename Input, typename Local,\n            contraction_type contract_tp = contraction_tp>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n      typename ::Eigen::internal::enable_if<contract_tp == contraction_type::local>::type\n      extract_block(const Input &inpt, Local local_ptr, const std::pair<StorageIndex, StorageIndex>& local_index,\n                    const StorageIndex &ncOffset, const StorageIndex cOffset) {\n    EIGEN_CONSTEXPR StorageIndex TileSizeDimNC =\n        InputBlockProperties::is_rhs ? Properties::TileSizeDimN : Properties::TileSizeDimM;\n    EIGEN_CONSTEXPR StorageIndex LoadPerThread =\n        InputBlockProperties::is_rhs ? Properties::LoadPerThreadRhs : Properties::LoadPerThreadLhs;\n    EIGEN_CONSTEXPR StorageIndex LSD = InputBlockProperties::is_rhs ? LSDR : LSDL;\n    static_assert(((LocalOffset % (TileSizeDimNC / InputBlockProperties::nc_stride) == 0) &&\n                   (LocalOffset % (Properties::TileSizeDimK / InputBlockProperties::c_stride) == 0)),\n                  \" LocalOffset must be divisable by stride\");\n    const StorageIndex &NC = InputBlockProperties::is_rhs ? triple_dim.N : triple_dim.M;\n    StorageIndex localThreadNC = local_index.first;\n    StorageIndex localThreadC = local_index.second;\n    auto chk_bound = [&](const StorageIndex &CIndex, const StorageIndex &NCIndex) EIGEN_DEVICE_FUNC {\n      return ((CIndex + InputBlockProperties::c_stride - 1 < triple_dim.K) &&\n              (NCIndex + InputBlockProperties::nc_stride - 1 < NC));\n    };\n    EIGEN_UNROLL_LOOP\n    for (StorageIndex lPT = 0; lPT < LoadPerThread / InputBlockProperties::elements_per_access; lPT++) {\n      const StorageIndex CIndex = cOffset + (InputBlockProperties::c_stride * localThreadC);\n      const StorageIndex NCIndex = ncOffset + (InputBlockProperties::nc_stride * localThreadNC);\n      const StorageIndex ld = InputBlockProperties::is_coalesced_layout ? NC : triple_dim.K;\n      if (check_boundary<is_internal_block>(chk_bound(CIndex, NCIndex))) {\n        auto val =\n            read<InputBlockProperties::packet_load, InputBlockProperties::is_coalesced_layout,\n                 InputBlockProperties::is_rhs, typename InputBlockProperties::OutType>(inpt, NCIndex, CIndex, ld);\n        write<StorageIndex, (InputBlockProperties::is_coalesced_layout ? 1 : LSD), data_source::local_mem>(\n            val, local_ptr + (InputBlockProperties::nc_stride * localThreadNC) +\n                     (InputBlockProperties::c_stride * localThreadC * LSD));\n      } else {\n        EIGEN_UNROLL_LOOP\n        for (StorageIndex i = 0; i < InputBlockProperties::elements_per_access; i++) {\n          const StorageIndex nCInd = NCIndex + (InputBlockProperties::is_coalesced_layout ? i : 0);\n          const StorageIndex cInd = CIndex + (InputBlockProperties::is_coalesced_layout ? 0 : i);\n          OutScalar val =\n              (nCInd < NC && cInd < triple_dim.K)\n                  ? read<false, InputBlockProperties::is_coalesced_layout, InputBlockProperties::is_rhs, OutScalar>(\n                        inpt, nCInd, cInd, ld)\n                  : OutScalar(0);\n\n          write<StorageIndex, (InputBlockProperties::is_coalesced_layout ? 1 : LSD), data_source::local_mem>(\n              val, local_ptr + (InputBlockProperties::nc_stride * localThreadNC) +\n                       (InputBlockProperties::is_coalesced_layout ? i : 0) +\n                       ((InputBlockProperties::c_stride * localThreadC +\n                         (InputBlockProperties::is_coalesced_layout ? 0 : i)) *\n                        LSD));\n        }\n      }\n      localThreadNC += (InputBlockProperties::is_coalesced_layout)\n                           ? LocalOffset % (TileSizeDimNC / InputBlockProperties::nc_stride)\n                           : LocalOffset / (Properties::TileSizeDimK / InputBlockProperties::c_stride);\n      localThreadC += (InputBlockProperties::is_coalesced_layout)\n                          ? LocalOffset / (TileSizeDimNC / InputBlockProperties::nc_stride)\n                          : LocalOffset % (Properties::TileSizeDimK / InputBlockProperties::c_stride);\n    }\n  }\n};\n\n#ifndef EIGEN_SYCL_DISABLE_GEMV\n\n/*!\n * \\brief GeneralVectorTensor is a template class that provides Tensor -vector contraction operation, which is a special\n * case of Tensor Tensor contraction.\n *\n * \\tparam OutScalar: determines the output scalar type\n *\n * \\tparam OutAccessor: determines the sycl accessor type for out put (please see the sycl-1.2.1 specification\n * (https://www.khronos.org/registry/SYCL/specs/sycl-1.2.1.pdf) for accessor definition)\n *\n * \\tparam VectorMapper: determines the tensor contraction mapper for the vector input (can be lhs or rhs)\n *\n * \\tparam TensorMapper: determines the tensor contraction mapper for the tensor input (can be lhs or rhs)\n *\n * \\tparam StorageIndex: determines the StorageIndex Type\n *\n * \\tparam Properties: determines the Contraction Panel properties\n *\n * \\tparam KFactor: determines the number of elements in K dimension in a Tile\n *\n * \\tparam Vectorizable: determines whether or not the vectorization is enabled for the Eigen expression.\n *\n * \\tparam is_lhs_vec: determines whether lhs is a vector or rhs is a vector\n *\n * \\tparam IsFinal: determine if this is the final kernel. If so, the result will be written in a final output.\n * Otherwise, the result of contraction will be written iin a temporary buffer.\n *\n * \\param scratch: determines the local memory containing the vector block for each work-group\n *\n * \\param vec: determines the vector input (tensor mapper)\n *\n * \\param mat: determines the tensor input (tensor mapper)\n *\n * \\param out_res: determines the output vector containing the contraction result\n *\n * \\param nonContractGroupSize: a logical number determining the number of work-group for non-contracting dimension\n *\n * \\param nonContractDim: determines the size of non contracting dimension for the flattened tensor\n *\n * \\param contractDim: determines the size of non contracting dimension for the flattened tensor\n *\n */\ntemplate <typename OutScalar, typename OutAccessor, typename VectorMapper, typename TensorMapper, typename StorageIndex,\n          typename Properties, StorageIndex KFactor, bool Vectorizable, bool is_lhs_vec, bool IsFinal>\nstruct GeneralVectorTensor {\n  typedef typename Eigen::TensorSycl::internal::Vectorise<OutScalar, Eigen::SyclDevice, Vectorizable>::PacketReturnType\n      PacketReturnType;\n  static EIGEN_CONSTEXPR int PacketSize =\n      Eigen::TensorSycl::internal::Vectorise<OutScalar, Eigen::SyclDevice, Vectorizable>::PacketSize;\n  typedef cl::sycl::accessor<OutScalar, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local> Scratch;\n\n  static EIGEN_CONSTEXPR StorageIndex OutScratchOffset =\n      KFactor * Properties::LocalThreadSizeC * Properties::LocalThreadSizeNC;\n\n  // Since the access layout for a vector can always be coalesced, when LHS is a vector, we pass false and false to make\n  // sure that the !^ is true When RHS is a vector, we pass true and true to make sure that the !^ is true.\n  typedef BlockProperties<is_lhs_vec ? false : true, is_lhs_vec ? false : true, Vectorizable, PacketReturnType>\n      VecBlockProperties;\n\n  Scratch scratch;\n  const VectorMapper vec;\n  const TensorMapper mat;\n  OutAccessor out_res;\n  const StorageIndex nonContractGroupSize;\n  const StorageIndex nonContractDim;\n  const StorageIndex contractDim;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE GeneralVectorTensor(Scratch scratch_, const VectorMapper vec_,\n                                                            const TensorMapper mat_, OutAccessor out_res_,\n                                                            const StorageIndex nonContractGroupSize_,\n                                                            const StorageIndex nonContractDim_,\n                                                            const StorageIndex contractDim_)\n      : scratch(scratch_),\n        vec(vec_),\n        mat(mat_),\n        out_res(out_res_),\n        nonContractGroupSize(nonContractGroupSize_),\n        nonContractDim(nonContractDim_),\n        contractDim(contractDim_) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void operator()(cl::sycl::nd_item<1> itemID) {\n    auto scratch_ptr = scratch.get_pointer();\n    const StorageIndex linearLocalThreadId = itemID.get_local_id(0);\n    StorageIndex nonContractId = is_lhs_vec ? linearLocalThreadId / Properties::LocalThreadSizeC\n                                            : linearLocalThreadId % Properties::LocalThreadSizeNC;\n    StorageIndex contractId = is_lhs_vec ? linearLocalThreadId % Properties::LocalThreadSizeC\n                                         : linearLocalThreadId / Properties::LocalThreadSizeNC;\n    const StorageIndex cGroupSize = itemID.get_group_range(0) / nonContractGroupSize;\n    const StorageIndex nonContractGroupId =\n        is_lhs_vec ? itemID.get_group(0) / cGroupSize : itemID.get_group(0) % nonContractGroupSize;\n    const StorageIndex contractGroupId =\n        is_lhs_vec ? itemID.get_group(0) % cGroupSize : itemID.get_group(0) / nonContractGroupSize;\n    auto out_ptr = out_res.get_pointer() + (IsFinal ? 0 : contractGroupId * nonContractDim);\n\n    const StorageIndex nonContractGroupOffset = nonContractGroupId * Properties::TileSizeDimNC;\n    const StorageIndex contractGroupOffset = contractGroupId * Properties::TileSizeDimC;\n    auto outScratchIndex = nonContractId + contractId * Properties::LocalThreadSizeNC;\n    const StorageIndex globalNonContractDimOffset = nonContractGroupOffset + nonContractId;\n    const StorageIndex globalContractDimOffset = contractGroupOffset + contractId;\n    auto local_output = scratch_ptr + OutScratchOffset;\n    const bool is_internal = nonContractDim - nonContractGroupOffset >= Properties::TileSizeDimNC &&\n                             contractDim - contractGroupOffset >= Properties::TileSizeDimC;\n    is_internal\n        ? compute_panel<true>(itemID, vec, mat, local_output, out_ptr,\n#ifdef EIGEN_SYCL_LOCAL_MEM_UNSET_OR_ON\n                              scratch_ptr, contractGroupOffset,\n#endif\n                              nonContractGroupOffset, linearLocalThreadId, contractDim, nonContractDim, contractId,\n                              nonContractId, globalContractDimOffset, globalNonContractDimOffset, outScratchIndex)\n        : compute_panel<false>(itemID, vec, mat, local_output, out_ptr,\n#ifdef EIGEN_SYCL_LOCAL_MEM_UNSET_OR_ON\n                               scratch_ptr, contractGroupOffset,\n#endif\n                               nonContractGroupOffset, linearLocalThreadId, contractDim, nonContractDim, contractId,\n                               nonContractId, globalContractDimOffset, globalNonContractDimOffset, outScratchIndex);\n  }\n  template <bool is_internal_block, typename OutPtr>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void compute_panel(\n      const cl::sycl::nd_item<1> &itemID, const VectorMapper &vec, const TensorMapper &mat, OutScalar *local_output,\n      OutPtr out_ptr,\n#ifdef EIGEN_SYCL_LOCAL_MEM_UNSET_OR_ON\n      OutScalar *scratch_ptr, const StorageIndex contractGroupOffset,\n#endif\n      const StorageIndex nonContractGroupOffset, const StorageIndex linearLocalThreadId, StorageIndex contractDim,\n      StorageIndex nonContractDim, StorageIndex contractId, StorageIndex nonContractId,\n      StorageIndex globalContractDimOffset, StorageIndex globalNonContractDimOffset, StorageIndex outScratchIndex) {\n    OutScalar outScalar[Properties::WorkLoadPerThreadNC] = {OutScalar(0)};\n    // Reading the vector\n#ifdef EIGEN_SYCL_LOCAL_MEM_UNSET_OR_ON\n    const StorageIndex vectorOffset = contractGroupOffset + linearLocalThreadId;\n    extract_block<VecBlockProperties, is_internal_block, KFactor,\n                  Properties::LocalThreadSizeNC * Properties::LocalThreadSizeC>(vec, scratch_ptr, linearLocalThreadId,\n                                                                                vectorOffset, contractDim);\n\n    itemID.barrier(cl::sycl::access::fence_space::local_space);\n    auto in_scratch_ptr = scratch_ptr + contractId;\n#endif\n\n    StorageIndex privateOffsetC = 0;\n    EIGEN_UNROLL_LOOP\n    for (StorageIndex i = 0; i < Properties::WorkLoadPerThreadC; i++) {\n      StorageIndex privateOffsetNC = 0;\n      bool contract_conds = ((globalContractDimOffset + privateOffsetC) < contractDim);\n#ifdef EIGEN_SYCL_LOCAL_MEM_UNSET_OR_ON\n      auto vecScalar = *in_scratch_ptr;\n#else\n      auto vecScalar = (check_boundary<is_internal_block>(contract_conds))\n                           ? vec(is_lhs_vec ? StorageIndex(0) : globalContractDimOffset + privateOffsetC,\n                                 is_lhs_vec ? globalContractDimOffset + privateOffsetC : StorageIndex(0))\n                           : OutScalar(0);\n#endif\n      EIGEN_UNROLL_LOOP\n      for (StorageIndex j = 0; j < Properties::WorkLoadPerThreadNC; j++) {\n        auto matScalar = (check_boundary<is_internal_block>(\n                             contract_conds && ((globalNonContractDimOffset + privateOffsetNC) < nonContractDim)))\n                             ? mat(is_lhs_vec ? globalContractDimOffset + privateOffsetC\n                                              : globalNonContractDimOffset + privateOffsetNC,\n                                   is_lhs_vec ? globalNonContractDimOffset + privateOffsetNC\n                                              : globalContractDimOffset + privateOffsetC)\n                             : OutScalar(0);\n\n        outScalar[j] = cl::sycl::mad(matScalar, vecScalar, outScalar[j]);\n        privateOffsetNC += Properties::LocalThreadSizeNC;\n      }\n      privateOffsetC += Properties::LocalThreadSizeC;\n#ifdef EIGEN_SYCL_LOCAL_MEM_UNSET_OR_ON\n      in_scratch_ptr += Properties::LocalThreadSizeC;\n#endif\n    }\n\n    auto out_scratch_ptr = local_output + outScratchIndex;\n    // Each block of 16*16 element in shared memory should reduce to 16*1\n    EIGEN_UNROLL_LOOP\n    for (StorageIndex j = 0; j < Properties::WorkLoadPerThreadNC; j++) {\n      *out_scratch_ptr = outScalar[j];\n\n      out_scratch_ptr += (Properties::LocalThreadSizeNC * Properties::LocalThreadSizeC);\n    }\n    if (is_lhs_vec) {\n      nonContractId = linearLocalThreadId % Properties::LocalThreadSizeNC;\n      contractId = linearLocalThreadId / Properties::LocalThreadSizeNC;\n      outScratchIndex = nonContractId + contractId * Properties::LocalThreadSizeNC;\n    }\n\n    out_scratch_ptr = local_output + outScratchIndex;\n    EIGEN_UNROLL_LOOP\n    for (StorageIndex j = 0; j < Properties::WorkLoadPerThreadNC; j++) {\n      EIGEN_UNROLL_LOOP\n      for (StorageIndex offset = Properties::LocalThreadSizeC >> 1; offset > 0; offset >>= 1) {\n        itemID.barrier(cl::sycl::access::fence_space::local_space);\n        if (contractId < offset) {\n          StorageIndex myNeigbourId = (Properties::LocalThreadSizeNC * offset);\n          *out_scratch_ptr += out_scratch_ptr[myNeigbourId];\n        }\n      }\n      // moving to next 16 by 16 block\n      out_scratch_ptr += (Properties::LocalThreadSizeNC * Properties::LocalThreadSizeC);\n    }\n\n    if (contractId == 0) {\n      out_scratch_ptr = local_output + nonContractId;\n      StorageIndex global_final_offset = nonContractGroupOffset + nonContractId;\n      out_ptr += global_final_offset;\n      EIGEN_UNROLL_LOOP\n      for (StorageIndex j = 0; j < Properties::WorkLoadPerThreadNC; j++) {\n        if (check_boundary<is_internal_block>(global_final_offset < nonContractDim)) {\n          auto res = *out_scratch_ptr;\n\n          *out_ptr = res;\n          out_ptr += Properties::LocalThreadSizeNC;\n        }\n        // moving to next 16 by 16 block to ge the next 16 reduced elements\n        out_scratch_ptr += (Properties::LocalThreadSizeNC * Properties::LocalThreadSizeC);\n        if (!(is_internal_block)) global_final_offset += Properties::LocalThreadSizeNC;\n      }\n    }\n  }\n\n  template <typename InputBlockProperties, bool is_internal_block, int CFactor, int GroupSize, typename Input,\n            typename Local>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void extract_block(const Input &inpt, Local *local_ptr,\n                                                                  const StorageIndex &linearLocalThreadId,\n                                                                  const StorageIndex &cOffset, const StorageIndex &C) {\n    local_ptr += InputBlockProperties::c_stride * linearLocalThreadId;\n    StorageIndex cIndex = cOffset;\n    for (StorageIndex cId = 0; cId < CFactor / InputBlockProperties::c_stride; cId++) {\n      if (check_boundary<is_internal_block>(cIndex + InputBlockProperties::c_stride - 1 < C)) {\n        auto val = read<InputBlockProperties::packet_load, InputBlockProperties::is_coalesced_layout,\n                        InputBlockProperties::is_rhs, typename InputBlockProperties::OutType>(inpt, StorageIndex(0),\n                                                                                              cIndex, StorageIndex(1));\n        write<StorageIndex, 1, data_source::local_mem>(val, local_ptr);\n      } else {\n        EIGEN_UNROLL_LOOP\n        for (StorageIndex i = 0; i < InputBlockProperties::elements_per_access; i++) {\n          OutScalar val =\n              (cIndex + i < C)\n                  ? read<false, InputBlockProperties::is_coalesced_layout, InputBlockProperties::is_rhs, OutScalar>(\n                        inpt, StorageIndex(0), cIndex + i, StorageIndex(1))\n                  : OutScalar(0);\n          write<StorageIndex, 1, data_source::local_mem>(val, local_ptr + i);\n        }\n      }\n      local_ptr += InputBlockProperties::c_stride * GroupSize;\n      cIndex += InputBlockProperties::c_stride * GroupSize;\n    }\n  }\n};\n#endif\n\n#ifndef EIGEN_SYCL_DISABLE_SCALAR\n\n/*!\n * \\brief GeneralScalarContraction is a template class that provides the scalar value of Tensor -Tensor contraction\n * operation, when all the dimensions are contracting dimensions. This Kernel reduces two tensors to an scalar\n *\n * \\tparam OutScalar: determines the output scalar type\n *\n * \\tparam LhsScalar: determines the left-hand-side scalar type\n *\n * \\tparam RhsScalar: determines the right-hand-side scalar type\n *\n * \\tparam OutAccessor: determines the sycl accessor type for out put (please see the sycl-1.2.1 specification\n * (https://www.khronos.org/registry/SYCL/specs/sycl-1.2.1.pdf) for accessor definition)\n *\n * \\tparam LhsMapper: determines the tensor contraction mapper type for left-hand-side matrix\n *\n * \\tparam RhsMapper: determines the tensor contraction mapper type for right-hand-side matrix\n *\n * \\tparam StorageIndex: determines the StorageIndex Type\n *\n * \\tparam Vectorizable: determines whether or not the vectorization is enabled for the Eigen expression.\n *\n * \\param scratch: local memory containing tiles of LHS and RHS tensors for each work-group\n *\n * \\param lhs: determines the left-hand-side flattened tensor (tensor mapper)\n *\n * \\param rhs: determines the right-hand-side flattened tensor (tensor mapper)\n *\n * \\param out_res: determines the output tensor containing the contraction result\n *\n * \\param rng: determins the total input data size\n */\ntemplate <typename OutScalar, typename LhsScalar, typename RhsScalar, typename OutAccessor, typename LhsMapper,\n          typename RhsMapper, typename StorageIndex, bool Vectorizable>\nstruct GeneralScalarContraction {\n  typedef cl::sycl::accessor<OutScalar, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local> Scratch;\n  Scratch scratch;\n  const LhsMapper lhs;\n  const RhsMapper rhs;\n  OutAccessor out_res;\n  const StorageIndex rng;\n\n  EIGEN_DEVICE_FUNC\n  GeneralScalarContraction(Scratch scratch_, const LhsMapper lhs_, const RhsMapper rhs_, OutAccessor out_res_,\n                           const StorageIndex rng_)\n      : scratch(scratch_), lhs(lhs_), rhs(rhs_), out_res(out_res_), rng(rng_) {}\n\n  EIGEN_DEVICE_FUNC void operator()(cl::sycl::nd_item<1> itemID) {\n    auto out_ptr = out_res.get_pointer();\n    auto scratch_ptr = scratch.get_pointer().get();\n\n    StorageIndex globalid = itemID.get_global_id(0);\n    StorageIndex localid = itemID.get_local_id(0);\n    OutScalar accumulator = OutScalar(0);\n    for (StorageIndex i = globalid; i < rng; i += itemID.get_global_range(0)) {\n      accumulator = cl::sycl::mad(lhs(0, i), rhs(i, 0), accumulator);\n    }\n    auto out_scratch_ptr = scratch_ptr + localid;\n    *out_scratch_ptr = accumulator;\n    for (StorageIndex offset = itemID.get_local_range(0) >> 1; offset > 0; offset >>= 1) {\n      itemID.barrier(cl::sycl::access::fence_space::local_space);\n      if (localid < offset) {\n        *out_scratch_ptr = (accumulator += out_scratch_ptr[offset]);\n      }\n    }\n    if (localid == 0) {\n      out_ptr[itemID.get_group(0)] = accumulator;\n    }\n  }\n};\n#endif\n\n}  // namespace internal\n}  // namespace TensorSycl\n\ntemplate <typename Indices, typename LeftArgType, typename RightArgType, typename OutputKernelType>\nstruct TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>,\n                       Eigen::SyclDevice>\n    : public TensorContractionEvaluatorBase<TensorEvaluator<\n          const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, Eigen::SyclDevice>> {\n  static_assert(std::is_same<OutputKernelType, const NoOpOutputKernel>::value,\n                \"SYCL tensor contraction does not support output kernels.\");\n\n  typedef Eigen::SyclDevice Device;\n\n  typedef TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, Device> Self;\n  typedef TensorContractionEvaluatorBase<Self> Base;\n  typedef TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType> XprType;\n  typedef typename internal::remove_const<typename XprType::Scalar>::type Scalar;\n  typedef typename XprType::Index StorageIndex;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef typename Base::Storage Storage;\n  typedef typename Base::EvaluatorPointerType EvaluatorPointerType;\n  struct TripleDim {\n    const StorageIndex M;\n    const StorageIndex N;\n    const StorageIndex K;\n    TripleDim(const StorageIndex M_, const StorageIndex N_, const StorageIndex K_) : M(M_), N(N_), K(K_) {}\n  };\n  enum {\n    Layout = TensorEvaluator<LeftArgType, Device>::Layout,\n    PacketAccess = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess = false,\n  };\n\n  static EIGEN_CONSTEXPR int LDims = Base::LDims;\n  static EIGEN_CONSTEXPR int RDims = Base::RDims;\n  static EIGEN_CONSTEXPR int ContractDims = Base::ContractDims;\n\n  typedef array<StorageIndex, LDims> left_dim_mapper_t;\n  typedef array<StorageIndex, RDims> right_dim_mapper_t;\n\n  typedef array<StorageIndex, ContractDims> contract_t;\n  typedef array<StorageIndex, LDims - ContractDims> left_nocontract_t;\n  typedef array<StorageIndex, RDims - ContractDims> right_nocontract_t;\n\n  static const int NumDims = LDims + RDims - 2 * ContractDims;\n\n  typedef DSizes<StorageIndex, NumDims> Dimensions;\n\n  typedef TensorEvaluator<typename Base::EvalLeftArgType, Device> LeftEvaluator;\n  typedef TensorEvaluator<typename Base::EvalRightArgType, Device> RightEvaluator;\n  typedef typename Eigen::internal::remove_const<typename LeftEvaluator::CoeffReturnType>::type LhsScalar;\n  typedef typename Eigen::internal::remove_const<typename RightEvaluator::CoeffReturnType>::type RhsScalar;\n\n  typedef typename LeftEvaluator::Dimensions LeftDimensions;\n  typedef typename RightEvaluator::Dimensions RightDimensions;\n\n  template <bool lhs_inner_dim_contiguous, bool rhs_inner_dim_contiguous, bool rhs_inner_dim_reordered>\n  struct input_mapper_propertis {\n    static EIGEN_CONSTEXPR bool is_lhs_matrix = (LDims == 2 && ContractDims == 1) || lhs_inner_dim_contiguous;\n    static EIGEN_CONSTEXPR bool is_rhs_matrix =\n        (RDims == 2 && ContractDims == 1) || (rhs_inner_dim_contiguous && !rhs_inner_dim_reordered);\n  };\n\n  EIGEN_DEVICE_FUNC TensorEvaluator(const XprType &op, const Device &device) : Base(op, device) {}\n\n  // We need to redefine this method to make nvcc happy\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(typename Base::EvaluatorPointerType data) {\n    this->m_leftImpl.evalSubExprsIfNeeded(NULL);\n    this->m_rightImpl.evalSubExprsIfNeeded(NULL);\n    if (!data) {\n      this->m_result = this->m_device.get(\n          static_cast<Scalar *>(this->m_device.allocate_temp(this->dimensions().TotalSize() * sizeof(Scalar))));\n      data = this->m_result;\n    }\n    evalToSycl(data);\n    return (this->m_result != NULL);\n  }\n  const Eigen::SyclDevice &device() const { return this->m_device; }\n  void evalToSycl(typename Base::EvaluatorPointerType buffer) const {\n    if (this->m_lhs_inner_dim_contiguous) {\n      if (this->m_rhs_inner_dim_contiguous) {\n        if (this->m_rhs_inner_dim_reordered) {\n          evalTyped<true, true, true, Unaligned>(buffer);\n        } else {\n          evalTyped<true, true, false, Unaligned>(buffer);\n        }\n      } else {\n        if (this->m_rhs_inner_dim_reordered) {\n          evalTyped<true, false, true, Unaligned>(buffer);\n        } else {\n          evalTyped<true, false, false, Unaligned>(buffer);\n        }\n      }\n    } else {\n      if (this->m_rhs_inner_dim_contiguous) {\n        if (this->m_rhs_inner_dim_reordered) {\n          evalTyped<false, true, true, Unaligned>(buffer);\n        } else {\n          evalTyped<false, true, false, Unaligned>(buffer);\n        }\n      } else {\n        if (this->m_rhs_inner_dim_reordered) {\n          evalTyped<false, false, true, Unaligned>(buffer);\n        } else {\n          evalTyped<false, false, false, Unaligned>(buffer);\n        }\n      }\n    }\n  }\n\n  template <bool lhs_inner_dim_contiguous, bool rhs_inner_dim_contiguous, bool rhs_inner_dim_reordered, int Alignment>\n  void evalTyped(typename Base::EvaluatorPointerType buffer) const {\n    const auto triple_dim = TripleDim{this->m_i_size, this->m_j_size, this->m_k_size};\n    typedef internal::TensorContractionInputMapper<\n        LhsScalar, StorageIndex, internal::Lhs, LeftEvaluator, left_nocontract_t, contract_t,\n        PacketType<CoeffReturnType, Device>::size, lhs_inner_dim_contiguous, false, Unaligned, MakeSYCLPointer>\n        LhsMapper;\n\n    typedef internal::TensorContractionInputMapper<RhsScalar, StorageIndex, internal::Rhs, RightEvaluator,\n                                                   right_nocontract_t, contract_t,\n                                                   PacketType<CoeffReturnType, Device>::size, rhs_inner_dim_contiguous,\n                                                   rhs_inner_dim_reordered, Unaligned, MakeSYCLPointer>\n        RhsMapper;\n\n    // initialize data mappers\n    LhsMapper lhs(this->m_leftImpl, this->m_left_nocontract_strides, this->m_i_strides,\n                  this->m_left_contracting_strides, this->m_k_strides);\n\n    RhsMapper rhs(this->m_rightImpl, this->m_right_nocontract_strides, this->m_j_strides,\n                  this->m_right_contracting_strides, this->m_k_strides);\n\n#ifndef EIGEN_SYCL_DISABLE_SCALAR\n    if (triple_dim.M == 1 && triple_dim.N == 1) {\n      launchSC(buffer, lhs, rhs, triple_dim.K);\n    } else\n#endif\n#ifndef EIGEN_SYCL_DISABLE_GEMV\n        if (triple_dim.M != 1 && triple_dim.N == 1) {\n      LaunchVT<false>(buffer, rhs, lhs, triple_dim.M, triple_dim.K);\n    } else if (triple_dim.M == 1 && triple_dim.N != 1) {\n      LaunchVT<true>(buffer, lhs, rhs, triple_dim.N, triple_dim.K);\n    } else  // This is equivalent of if (m!=1 && n!=1)\n#endif\n    {\n      typedef input_mapper_propertis<lhs_inner_dim_contiguous, rhs_inner_dim_contiguous, rhs_inner_dim_reordered>\n          inpt_mapper_properties;\n#ifndef EIGEN_SYCL_DISABLE_SKINNY\n      bool skinny = false;\n      auto platform_name = this->device().getPlatformName();\n      // This is based on empirical calculation for AMD r9-nano and Fiji\n      if (platform_name.find(\"AMD\") == 0) {\n        skinny = (triple_dim.M < triple_dim.K || triple_dim.N < triple_dim.K) &&\n                 ((triple_dim.M < 1024 && triple_dim.N < 1024) ||\n                  (uint64_t(triple_dim.M * triple_dim.N) < uint64_t(triple_dim.K)));\n      } else {\n        skinny = (((std::max(triple_dim.K, triple_dim.N) / std::min(triple_dim.K, triple_dim.N)) > 100) ||\n                  ((std::max(triple_dim.K, triple_dim.M) / std::min(triple_dim.K, triple_dim.M)) > 100) ||\n                  ((std::max(triple_dim.N, triple_dim.M) / std::min(triple_dim.N, triple_dim.M)) > 100));\n      }\n      if (skinny)\n        adjustTT<true, inpt_mapper_properties>(buffer, lhs, rhs, triple_dim);\n      else\n#endif  // EIGEN_SYCL_DISABLE_SKINNY\n        adjustTT<false, inpt_mapper_properties>(buffer, lhs, rhs, triple_dim);\n    }\n  }\n\n  template <bool skinny, typename input_mapper_properties, typename LhsMapper, typename RhsMapper>\n  void EIGEN_ALWAYS_INLINE adjustTT(EvaluatorPointerType buffer, const LhsMapper &lhs, const RhsMapper &rhs,\n                                    const TripleDim &triple_dim) const {\n#ifdef EIGEN_SYCL_LOCAL_MEM_UNSET_OR_ON\n    if (device().has_local_memory()) {\n      typedef TensorSycl::internal::TTPanelSize<CoeffReturnType, StorageIndex, 4, 4, 16> PanelParameters;\n      launchTT<TensorSycl::internal::contraction_type::local, skinny, input_mapper_properties, PanelParameters>(\n          buffer, lhs, rhs, triple_dim);\n    }\n#endif\n#ifdef EIGEN_SYCL_LOCAL_MEM_UNSET_OR_OFF\n    if (!(device().has_local_memory())) {\n      typedef TensorSycl::internal::TTPanelSize<CoeffReturnType, StorageIndex, 4, 4, 4> PanelParameters;\n      launchTT<TensorSycl::internal::contraction_type::no_local, skinny, input_mapper_properties, PanelParameters>(\n          buffer, lhs, rhs, triple_dim);\n    }\n#endif\n  }\n\n  template <TensorSycl::internal::contraction_type ct, bool skinny, typename input_mapper_properties,\n            typename Properties, typename LhsMapper, typename RhsMapper>\n  void launchTT(EvaluatorPointerType buffer, const LhsMapper &lhs, const RhsMapper &rhs,\n                const TripleDim &triple_dim) const {\n    const StorageIndex roundUpM = Eigen::TensorSycl::internal::roundUp(triple_dim.M, Properties::TileSizeDimM);\n    const StorageIndex roundUpN = Eigen::TensorSycl::internal::roundUp(triple_dim.N, Properties::TileSizeDimN);\n    const StorageIndex groupSizeM = roundUpM / Properties::TileSizeDimM;\n    const StorageIndex groupSizeN = roundUpN / Properties::TileSizeDimN;\n\n    const StorageIndex roundUpK = Eigen::TensorSycl::internal::roundUp(triple_dim.K, Properties::TileSizeDimK);\n    StorageIndex totalTilesK = roundUpK / Properties::TileSizeDimK;\n    StorageIndex groupSizeK =\n        skinny\n            ? std::max(std::min(totalTilesK,\n                                (StorageIndex)(device().getPowerOfTwo(device().getNumSyclMultiProcessors(), true) * 4) /\n                                    (groupSizeM * groupSizeN)),\n                       StorageIndex(1))\n            : StorageIndex(1);\n\n    const StorageIndex numTilesPerGroup = Eigen::TensorSycl::internal::roundUp(totalTilesK, groupSizeK) / groupSizeK;\n\n    const StorageIndex totalGroupSize = groupSizeM * groupSizeN * groupSizeK;\n\n    const StorageIndex localRange = Properties::LocalThreadSizeM * Properties::LocalThreadSizeN;\n    const StorageIndex globalRange = totalGroupSize * localRange;\n\n    const StorageIndex scratchSize = (ct == TensorSycl::internal::contraction_type::local)\n                                         ? ((Properties::DoubleBuffer + 1) *\n                                            (Properties::TileSizeDimM + Properties::BC) * (Properties::TileSizeDimK)) +\n                                               ((Properties::DoubleBuffer + 1) * (Properties::TileSizeDimK) *\n                                                (Properties::TileSizeDimN + Properties::BC))\n                                         : StorageIndex(1);\n\n    auto thread_range = cl::sycl::nd_range<1>(cl::sycl::range<1>(globalRange), cl::sycl::range<1>(localRange));\n    if (groupSizeK == 1) {\n      typedef TensorSycl::internal::TensorContractionKernel<CoeffReturnType, LhsScalar, RhsScalar, EvaluatorPointerType,\n                                                            LhsMapper, RhsMapper, StorageIndex, Properties, TripleDim,\n                                                            PacketAccess, input_mapper_properties, true, ct>\n          ContractKernelName;\n      device().template binary_kernel_launcher<CoeffReturnType, ContractKernelName>(\n          lhs, rhs, buffer, thread_range, scratchSize, groupSizeM, groupSizeN, numTilesPerGroup, triple_dim);\n    } else {\n      typedef TensorSycl::internal::TensorContractionKernel<CoeffReturnType, LhsScalar, RhsScalar, EvaluatorPointerType,\n                                                            LhsMapper, RhsMapper, StorageIndex, Properties, TripleDim,\n                                                            PacketAccess, input_mapper_properties, false, ct>\n          ContractKernelName;\n      CoeffReturnType *temp_pointer = static_cast<CoeffReturnType *>(\n          device().allocate_temp(triple_dim.M * triple_dim.N * groupSizeK * sizeof(CoeffReturnType)));\n      EvaluatorPointerType tmp_global_accessor = device().get(temp_pointer);\n\n      device().template binary_kernel_launcher<CoeffReturnType, ContractKernelName>(\n          lhs, rhs, tmp_global_accessor, thread_range, scratchSize, groupSizeM, groupSizeN, numTilesPerGroup,\n          triple_dim);\n\n      typedef Eigen::internal::SumReducer<CoeffReturnType> Op;\n      auto op = Op();\n      typedef TensorSycl::internal::SecondStepPartialReduction<CoeffReturnType, StorageIndex, EvaluatorPointerType,\n                                                               EvaluatorPointerType, Op>\n          ReductionKernel;\n\n      device().template unary_kernel_launcher<CoeffReturnType, ReductionKernel>(\n          tmp_global_accessor, buffer,\n          cl::sycl::nd_range<1>(cl::sycl::range<1>(StorageIndex(\n                                    Eigen::TensorSycl::internal::roundUp(triple_dim.M * triple_dim.N, localRange))),\n                                cl::sycl::range<1>(localRange)),\n          StorageIndex(1), op, StorageIndex(triple_dim.M * triple_dim.N), groupSizeK);\n\n      device().deallocate_temp(temp_pointer);\n    }\n  }\n\n#ifndef EIGEN_SYCL_DISABLE_GEMV\n  template <bool is_lhs_vec, typename VectorMapper, typename TensorMapper, typename StorageIndex>\n  void EIGEN_ALWAYS_INLINE LaunchVT(EvaluatorPointerType buffer, const VectorMapper &vec, const TensorMapper &mat,\n                                    StorageIndex NC, StorageIndex C) const {\n    const StorageIndex nonContractDim = NC;\n    EIGEN_CONSTEXPR StorageIndex NCFactor = 1;\n    EIGEN_CONSTEXPR StorageIndex CFactor = 1;\n    EIGEN_CONSTEXPR StorageIndex NCWindow = 16;\n    typedef Eigen::TensorSycl::internal::TVPanelSize<CoeffReturnType, StorageIndex, NCWindow, CFactor, NCFactor>\n        Properties;\n    const StorageIndex roundUpC = Eigen::TensorSycl::internal::roundUp(C, Properties::TileSizeDimC);\n    const StorageIndex cNumGroups = roundUpC / (Properties::LocalThreadSizeC * Properties::WorkLoadPerThreadC);\n    const StorageIndex roundUpNC = Eigen::TensorSycl::internal::roundUp(nonContractDim, Properties::TileSizeDimNC);\n    const StorageIndex nCNumGroups = roundUpNC / (Properties::LocalThreadSizeNC * Properties::WorkLoadPerThreadNC);\n    const StorageIndex globalRange =\n        (roundUpNC / (Properties::WorkLoadPerThreadNC)) * (roundUpC / (Properties::WorkLoadPerThreadC));\n    const StorageIndex localRange = Properties::LocalThreadSizeNC * Properties::LocalThreadSizeC;\n    const StorageIndex scratchSize =\n        (Properties::WorkLoadPerThreadNC + CFactor) * Properties::LocalThreadSizeC * Properties::LocalThreadSizeNC;\n    auto thread_range = cl::sycl::nd_range<1>(cl::sycl::range<1>(globalRange), cl::sycl::range<1>(localRange));\n    if (cNumGroups > 1) {\n      typedef Eigen::TensorSycl::internal::GeneralVectorTensor<CoeffReturnType, EvaluatorPointerType, VectorMapper,\n                                                               TensorMapper, StorageIndex, Properties, CFactor, false,\n                                                               is_lhs_vec, false>\n          ContractKernelName;\n      CoeffReturnType *temp_pointer =\n          static_cast<CoeffReturnType *>(device().allocate_temp(nonContractDim * cNumGroups * sizeof(CoeffReturnType)));\n      EvaluatorPointerType tmp_global_accessor = device().get(temp_pointer);\n\n      device().template binary_kernel_launcher<CoeffReturnType, ContractKernelName>(\n          vec, mat, tmp_global_accessor, thread_range, scratchSize, nCNumGroups, nonContractDim, C);\n\n      typedef Eigen::internal::SumReducer<CoeffReturnType> Op;\n      typedef TensorSycl::internal::SecondStepPartialReduction<CoeffReturnType, StorageIndex, EvaluatorPointerType,\n                                                               EvaluatorPointerType, Op>\n          ReductionKernel;\n\n      device().template unary_kernel_launcher<CoeffReturnType, ReductionKernel>(\n          tmp_global_accessor, buffer,\n          cl::sycl::nd_range<1>(cl::sycl::range<1>(Eigen::TensorSycl::internal::roundUp(nonContractDim, localRange)),\n                                cl::sycl::range<1>(localRange)),\n          StorageIndex(1), Op(), nonContractDim, cNumGroups);\n\n      device().deallocate_temp(temp_pointer);\n    } else {\n      typedef Eigen::TensorSycl::internal::GeneralVectorTensor<CoeffReturnType, EvaluatorPointerType, VectorMapper,\n                                                               TensorMapper, StorageIndex, Properties, CFactor, false,\n                                                               is_lhs_vec, true>\n          ContractKernelName;\n      device().template binary_kernel_launcher<CoeffReturnType, ContractKernelName>(\n          vec, mat, buffer, thread_range, scratchSize, nCNumGroups, nonContractDim, C);\n    }\n  }\n#endif\n\n#ifndef EIGEN_SYCL_DISABLE_SCALAR\n  template <typename LhsMapper, typename RhsMapper>\n  EIGEN_ALWAYS_INLINE void launchSC(EvaluatorPointerType buffer, const LhsMapper &lhs, const RhsMapper &rhs,\n                                    StorageIndex K) const {\n    EIGEN_STATIC_ASSERT(!((EIGEN_SYCL_LOCAL_THREAD_DIM0 * EIGEN_SYCL_LOCAL_THREAD_DIM1) &\n                          (EIGEN_SYCL_LOCAL_THREAD_DIM0 * EIGEN_SYCL_LOCAL_THREAD_DIM1 - 1)),\n                        \"The Local thread size must be a power of 2 for the reduction \"\n                        \"operation\");\n    EIGEN_CONSTEXPR StorageIndex local_range = EIGEN_SYCL_LOCAL_THREAD_DIM0 * EIGEN_SYCL_LOCAL_THREAD_DIM1;\n\n    // Here we force the code not to be more than 2-step reduction: Our empirical research shows that if each thread\n    // reduces at least 512 elementss individually, we get better performance.\n    const StorageIndex num_work_group = ((K + (512 * local_range - 1)) / (512 * local_range) > 1 ? local_range : 1);\n    const StorageIndex global_range = num_work_group * local_range;\n\n    typedef Eigen::TensorSycl::internal::GeneralScalarContraction<\n        CoeffReturnType, LhsScalar, RhsScalar, EvaluatorPointerType, LhsMapper, RhsMapper, StorageIndex, false>\n        ContractKernelName;\n    auto thread_range = cl::sycl::nd_range<1>(cl::sycl::range<1>(global_range), cl::sycl::range<1>(local_range));\n    if (num_work_group > 1) {\n      CoeffReturnType *temp_pointer =\n          static_cast<CoeffReturnType *>(device().allocate_temp(num_work_group * sizeof(CoeffReturnType)));\n      EvaluatorPointerType tmp_global_accessor = device().get(temp_pointer);\n      device().template binary_kernel_launcher<CoeffReturnType, ContractKernelName>(lhs, rhs, tmp_global_accessor,\n                                                                                    thread_range, local_range, K);\n      typedef Eigen::internal::SumReducer<CoeffReturnType> Op;\n      typedef TensorSycl::internal::SecondStepFullReducer<CoeffReturnType, Op, EvaluatorPointerType,\n                                                          EvaluatorPointerType, StorageIndex, local_range>\n          GenericRKernel;\n      device().template unary_kernel_launcher<CoeffReturnType, GenericRKernel>(\n          tmp_global_accessor, buffer,\n          cl::sycl::nd_range<1>(cl::sycl::range<1>(local_range), cl::sycl::range<1>(local_range)), local_range, Op());\n\n      device().deallocate_temp(temp_pointer);\n    } else {\n      device().template binary_kernel_launcher<CoeffReturnType, ContractKernelName>(lhs, rhs, buffer, thread_range,\n                                                                                    local_range, K);\n    }\n  }\n#endif\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    this->m_leftImpl.cleanup();\n    this->m_rightImpl.cleanup();\n\n    if (this->m_result) {\n      this->m_device.deallocate_temp(this->m_result);\n      this->m_result = NULL;\n    }\n  }\n  // The placeholder accessors must bound to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    this->m_leftImpl.bind(cgh);\n    this->m_rightImpl.bind(cgh);\n    this->m_result.bind(cgh);\n  }\n};\n}  // namespace Eigen\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_SYCL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorContractionThreadPool.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_THREAD_POOL_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_THREAD_POOL_H\n\n// evaluator for thread pool device\n#ifdef EIGEN_USE_THREADS\n\nnamespace Eigen {\n\ntemplate<typename Indices, typename LeftArgType, typename RightArgType, typename OutputKernelType>\nstruct TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, ThreadPoolDevice> :\n    public TensorContractionEvaluatorBase<TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, ThreadPoolDevice> > {\n\n  typedef ThreadPoolDevice Device;\n\n  typedef TensorEvaluator<const TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType>, Device> Self;\n  typedef TensorContractionEvaluatorBase<Self> Base;\n\n  typedef TensorContractionOp<Indices, LeftArgType, RightArgType, OutputKernelType> XprType;\n  typedef typename internal::remove_const<typename XprType::Scalar>::type Scalar;\n  typedef typename XprType::Index Index;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n\n  enum {\n    Layout = TensorEvaluator<LeftArgType, Device>::Layout,\n  };\n\n  // Most of the code is assuming that both input tensors are ColMajor. If the\n  // inputs are RowMajor, we will \"cheat\" by swapping the LHS and RHS:\n  // If we want to compute A * B = C, where A is LHS and B is RHS, the code\n  // will pretend B is LHS and A is RHS.\n  typedef typename internal::conditional<\n    static_cast<int>(Layout) == static_cast<int>(ColMajor), LeftArgType, RightArgType>::type EvalLeftArgType;\n  typedef typename internal::conditional<\n    static_cast<int>(Layout) == static_cast<int>(ColMajor), RightArgType, LeftArgType>::type EvalRightArgType;\n\n  static const int LDims =\n      internal::array_size<typename TensorEvaluator<EvalLeftArgType, Device>::Dimensions>::value;\n  static const int RDims =\n      internal::array_size<typename TensorEvaluator<EvalRightArgType, Device>::Dimensions>::value;\n  static const int ContractDims = internal::array_size<Indices>::value;\n\n  typedef array<Index, LDims> left_dim_mapper_t;\n  typedef array<Index, RDims> right_dim_mapper_t;\n\n  typedef array<Index, ContractDims> contract_t;\n  typedef array<Index, LDims - ContractDims> left_nocontract_t;\n  typedef array<Index, RDims - ContractDims> right_nocontract_t;\n\n  static const int NumDims = LDims + RDims - 2 * ContractDims;\n\n  typedef DSizes<Index, NumDims> Dimensions;\n\n  // typedefs needed in evalTo\n  typedef typename internal::remove_const<typename EvalLeftArgType::Scalar>::type LhsScalar;\n  typedef typename internal::remove_const<typename EvalRightArgType::Scalar>::type RhsScalar;\n  typedef typename internal::gebp_traits<LhsScalar, RhsScalar> Traits;\n\n  typedef TensorEvaluator<EvalLeftArgType, Device> LeftEvaluator;\n  typedef TensorEvaluator<EvalRightArgType, Device> RightEvaluator;\n\n  TensorEvaluator(const XprType& op, const Device& device) :\n      Base(op, device) {}\n\n  template <int Alignment>\n  void evalProduct(Scalar* buffer) const {\n    evalProductImpl<NoCallback, Alignment>(buffer, NoCallback());\n  }\n\n  template <typename EvalToCallback, int Alignment>\n  void evalProductAsync(Scalar* buffer, EvalToCallback done) const {\n    evalProductImpl<EvalToCallback, Alignment>(buffer, std::move(done));\n  }\n\n  template <typename DoneCallback, int Alignment>\n  void evalProductImpl(Scalar* buffer, DoneCallback done) const {\n    // This function computes a lot of heuristics in multiple steps, and it\n    // also has multiple exit points. To keep it sane, readable and all in one\n    // place, sync/async execution decision is made at runtime at the very end.\n    //\n    // (1) In sync mode we allocate Context on the stack, submit computations\n    //     to the device thread pool, and block on a barrier until it is\n    //     completed.\n    //\n    // (2) In async mode we allocate Context on the heap, and after all tasks\n    //     are finished, we call provided the done callback, and delete a\n    //     context from the heap.\n    //\n    // (*) EvalParallelContext & EvalShardedByInnerDimContext owns all the state\n    // and temporary buffers, requried for executing the tensor contraction.\n    // They are responsible for cleaning it up after contraction is done.\n    static const bool IsEvalInSyncMode =\n        std::is_same<DoneCallback, NoCallback>::value;\n\n    const Index m = this->m_i_size;\n    const Index n = this->m_j_size;\n    const Index k = this->m_k_size;\n    if (m == 0 || n == 0 || k == 0) return;\n\n    // Compute a set of algorithm parameters:\n    // - kernel block sizes (bm, bn, bk)\n    // - task grain sizes (number of kernels executed per task: gm, gn)\n    // - number of threads\n    // - sharding by row/column\n    // - parallel packing or first lhs then rhs\n    // and some derived parameters:\n    // - number of tasks (nm, nn, nk)\n    // - number of kernels (nm0, nn0)\n    // Unfortunately, all these parameters are tightly interdependent.\n    // So in some cases we first compute approximate values, then compute other\n    // values based on these approximations and then refine the approximations.\n\n    // There are lots of heuristics here. There is some reasoning behind them,\n    // but ultimately they are just tuned on contraction benchmarks for\n    // different input configurations, thread counts and instruction sets.\n    // So feel free to question any of them.\n\n    // Compute whether we want to shard by row or by column.\n    // This is a first approximation, it will be refined later. Since we don't\n    // know number of threads yet we use 2, because what's we are most\n    // interested in at this point is whether it makes sense to use\n    // parallelization at all or not.\n    bool shard_by_col = shardByCol(m, n, 2);\n\n    // First approximation of kernel blocking sizes.\n    // Again, we don't know number of threads yet, so we use 2.\n    Index bm, bn, bk;\n    if (shard_by_col) {\n      internal::TensorContractionBlocking<Scalar, LhsScalar, RhsScalar, Index,\n                                          internal::ShardByCol>\n          blocking(k, m, n, 2);\n      bm = blocking.mc();\n      bn = blocking.nc();\n      bk = blocking.kc();\n    } else {\n      internal::TensorContractionBlocking<Scalar, LhsScalar, RhsScalar, Index,\n                                          internal::ShardByRow>\n          blocking(k, m, n, 2);\n      bm = blocking.mc();\n      bn = blocking.nc();\n      bk = blocking.kc();\n    }\n\n    // Compute optimal number of threads.\n    // Note: we use bk instead of k here because we are interested in amount of\n    // _parallelizable_ computations, and computations are not parallelizable\n    // across k dimension.\n    const TensorOpCost cost =\n        contractionCost(m, n, bm, bn, bk, shard_by_col, false);\n    int num_threads = TensorCostModel<ThreadPoolDevice>::numThreads(\n        static_cast<double>(n) * m, cost, this->m_device.numThreads());\n    int num_threads_by_k = numThreadsInnerDim(m, n, k);\n    if (shardByInnerDim(m, n, k, num_threads, num_threads_by_k)) {\n      // We are in the scenario where it is more effective to shard by the\n      // inner dimension.\n      if (IsEvalInSyncMode) {\n        EvalShardedByInnerDimContext<DoneCallback> ctx(\n            this, num_threads_by_k, buffer, m, n, k, std::move(done));\n        ctx.template run<Alignment>();\n      } else {\n        auto* ctx = new EvalShardedByInnerDimContext<DoneCallback>(\n            this, num_threads_by_k, buffer, m, n, k, std::move(done));\n        ctx->template runAsync<Alignment>();\n      }\n\n      return;\n    }\n\n    // TODO(dvyukov): this is a stop-gap to prevent regressions while the cost\n    // model is not tuned. Remove this when the cost model is tuned.\n    if (n == 1) num_threads = 1;\n\n    if (num_threads == 1) {\n      TENSOR_CONTRACTION_DISPATCH(this->template evalProductSequential,\n                                  Unaligned, (buffer));\n      if (!IsEvalInSyncMode) done();\n      return;\n    }\n\n    // Now that we know number of threads, recalculate sharding and blocking.\n    shard_by_col = shardByCol(m, n, num_threads);\n    if (shard_by_col) {\n      internal::TensorContractionBlocking<Scalar, LhsScalar, RhsScalar, Index,\n                                          internal::ShardByCol>\n          blocking(k, m, n, num_threads);\n      bm = blocking.mc();\n      bn = blocking.nc();\n      bk = blocking.kc();\n    } else {\n      internal::TensorContractionBlocking<Scalar, LhsScalar, RhsScalar, Index,\n                                          internal::ShardByRow>\n          blocking(k, m, n, num_threads);\n      bm = blocking.mc();\n      bn = blocking.nc();\n      bk = blocking.kc();\n    }\n\n    // Number of kernels for each dimension.\n    Index nm0 = divup(m, bm);\n    Index nn0 = divup(n, bn);\n    Index nk = divup(k, bk);\n\n    // Calculate task grain size (number of kernels executed per task).\n    // This task size coarsening serves two purposes:\n    // 1. It reduces per-task overheads including synchronization overheads.\n    // 2. It allows to use caches better (reuse the same packed rhs in several\n    // consecutive kernels).\n    Index gm = 1;\n    Index gn = 1;\n    // If we are sharding by column, then we prefer to reduce rows first.\n    if (shard_by_col) {\n      gm = coarsenM(m, n, bm, bn, bk, gn, num_threads, shard_by_col);\n      gn = coarsenN(m, n, bm, bn, bk, gm, num_threads, shard_by_col);\n    } else {\n      gn = coarsenN(m, n, bm, bn, bk, gm, num_threads, shard_by_col);\n      gm = coarsenM(m, n, bm, bn, bk, gn, num_threads, shard_by_col);\n    }\n    // Number of tasks in each dimension.\n    Index nm = divup(nm0, gm);\n    Index nn = divup(nn0, gn);\n\n    // If there is enough concurrency in the sharding dimension, we choose not\n    // to paralellize by the other dimension, and execute all kernels in sync\n    // mode. This reduces parallelism from the nm x nn down to nn\n    // (shard_by_col==true) or nm (shard_by_col==false).\n    const Index sharding_dim_tasks = shard_by_col ? nn : nm;\n    const int num_worker_threads = this->m_device.numThreadsInPool();\n\n    // With small number of threads we want to make sure that we do not reduce\n    // parallelism too much. With large number of threads we trade maximum\n    // parallelism for better memory locality.\n    const float oversharding_factor =\n        num_worker_threads <= 4  ? 8.0 :\n        num_worker_threads <= 8  ? 4.0 :\n        num_worker_threads <= 16 ? 2.0 :\n        num_worker_threads <= 32 ? 1.0 :\n        num_worker_threads <= 64 ? 0.8 : /* num_worker_threads > 64 */ 0.6;\n\n    const bool parallelize_by_sharding_dim_only =\n        sharding_dim_tasks >= oversharding_factor * num_worker_threads;\n\n    // Last by not least, decide whether we want to issue both lhs and rhs\n    // packing in parallel; or issue lhs packing first, and then issue rhs\n    // packing when lhs packing completes (for !shard_by_col lhs and rhs are\n    // swapped). Parallel packing allows more parallelism (for both packing and\n    // kernels), while sequential packing provides better locality (once\n    // a thread finishes rhs packing it proceed to kernels with that rhs).\n    // First, we are interested in parallel packing if there are few tasks.\n    bool parallel_pack = num_threads >= nm * nn;\n    // Also do parallel packing if all data fits into L2$.\n    if (m * bk * Index(sizeof(LhsScalar)) + n * bk * Index(sizeof(RhsScalar)) <=\n        l2CacheSize() * num_threads)\n      parallel_pack = true;\n    // But don't do it if we will use each rhs only once. Locality seems to be\n    // more important in this case.\n    if ((shard_by_col ? nm : nn) == 1) parallel_pack = false;\n    // Also don't get in the way of parallelize_by_sharding_dim_only\n    // optimization.\n    if (parallelize_by_sharding_dim_only) parallel_pack = false;\n\n    // TODO(ezhulnev): With if contexpr we don't need SyncEvalParallelContext.\n    if (IsEvalInSyncMode) {\n#define CONTEXT_ARGS                                                        \\\n  (this, num_threads, buffer, m, n, k, bm, bn, bk, nm, nn, nk, gm, gn, nm0, \\\n   nn0, shard_by_col, parallel_pack, parallelize_by_sharding_dim_only,      \\\n   NoCallback())                                                            \\\n      .run()\n      TENSOR_CONTRACTION_DISPATCH(SyncEvalParallelContext, Alignment,\n                                  CONTEXT_ARGS);\n#undef CONTEXT_ARGS\n\n    } else {\n#define CONTEXT_ARGS                                                        \\\n  (this, num_threads, buffer, m, n, k, bm, bn, bk, nm, nn, nk, gm, gn, nm0, \\\n   nn0, shard_by_col, parallel_pack, parallelize_by_sharding_dim_only,      \\\n   std::move(done))\n      TENSOR_CONTRACTION_ASYNC_DISPATCH(EvalParallelContext, DoneCallback,\n                                        Alignment, CONTEXT_ARGS, run());\n#undef CONTEXT_ARGS\n    }\n  }\n\n  // ------------------------------------------------------------------------ //\n\n  // Dummy struct to represent an empty DoneCallback.\n\n  struct NoCallback {\n    void operator()() {\n      eigen_assert(false && \"NoCallback should never be called\");\n    }\n  };\n\n  // ------------------------------------------------------------------------ //\n\n  template <typename DoneCallback, typename Context>\n  class EvalParallelNotification;\n\n  // Synchronous evaluation notification that blocks caller thread in Wait().\n  template <typename Context>\n  class EvalParallelNotification<NoCallback, Context> {\n   public:\n    EvalParallelNotification(Context*, NoCallback) {}\n    void Notify() { done_.Notify(); }\n    void Wait() { done_.Wait(); }\n   private:\n    Eigen::Notification done_;\n  };\n\n  // Asynchronous evaluation notification that does not block in Wait().\n  template <typename DoneCallback, typename Context>\n  class EvalParallelNotification {\n   public:\n    EvalParallelNotification(Context* ctx, DoneCallback done)\n        : ctx_(ctx), done_(std::move(done)) {}\n\n    void Notify() {\n      // Make a copy of done callback, because it will be destructed when we\n      // will delete context in the next line (EvalParallelNotification is a\n      // data member of EvalParallelContext class).\n      DoneCallback done_copy = std::move(done_);\n\n      // Delete parallel evaluation context.\n      delete ctx_;\n\n      // Now safely call the done callback.\n      done_copy();\n    }\n\n    void Wait() {}\n\n   private:\n    Context* ctx_;\n    DoneCallback done_;\n  };\n\n  // Context orchestrates sync/async parallel contraction evaluation. When it is\n  // executed in asynchronous mode, it owns all the shared state that might be\n  // accessible by block packing and kernel tasks.\n\n  template <typename DoneCallback, bool lhs_inner_dim_contiguous,\n            bool rhs_inner_dim_contiguous, bool rhs_inner_dim_reordered,\n            int Alignment>\n  class EvalParallelContext {\n   public:\n    typedef internal::TensorContractionInputMapper<\n        LhsScalar, Index, internal::Lhs, LeftEvaluator, left_nocontract_t,\n        contract_t, internal::packet_traits<LhsScalar>::size,\n        lhs_inner_dim_contiguous, false, Unaligned>\n        LhsMapper;\n    typedef internal::TensorContractionInputMapper<\n        RhsScalar, Index, internal::Rhs, RightEvaluator, right_nocontract_t,\n        contract_t, internal::packet_traits<RhsScalar>::size,\n        rhs_inner_dim_contiguous, rhs_inner_dim_reordered, Unaligned>\n        RhsMapper;\n\n    typedef internal::blas_data_mapper<Scalar, Index, ColMajor> OutputMapper;\n\n    typedef internal::TensorContractionKernel<\n        Scalar, LhsScalar, RhsScalar, Index, OutputMapper, LhsMapper, RhsMapper>\n        TensorContractionKernel;\n\n    typedef typename TensorContractionKernel::LhsBlock LhsBlock;\n    typedef typename TensorContractionKernel::RhsBlock RhsBlock;\n    typedef typename TensorContractionKernel::BlockMemHandle BlockMemHandle;\n\n    EvalParallelContext(const Self* self, int num_threads, Scalar* buffer,\n                        Index tm, Index tn, Index tk, Index bm, Index bn,\n                        Index bk, Index nm, Index nn, Index nk, Index gm,\n                        Index gn, Index nm0, Index nn0, bool shard_by_col,\n                        bool parallel_pack,\n                        bool parallelize_by_sharding_dim_only,\n                        DoneCallback done)\n        : created_by_thread_id_(std::this_thread::get_id()),\n          done_(this, std::move(done)),\n          device_(self->m_device),\n          lhs_(self->m_leftImpl, self->m_left_nocontract_strides,\n               self->m_i_strides, self->m_left_contracting_strides,\n               self->m_k_strides),\n          rhs_(self->m_rightImpl, self->m_right_nocontract_strides,\n               self->m_j_strides, self->m_right_contracting_strides,\n               self->m_k_strides),\n          buffer_(buffer),\n          output_(buffer, tm),\n          output_kernel_(self->m_output_kernel),\n          tensor_contraction_params_(self->m_tensor_contraction_params),\n          num_threads_(num_threads),\n          shard_by_col_(shard_by_col),\n          parallel_pack_(parallel_pack),\n          parallelize_by_sharding_dim_only_(parallelize_by_sharding_dim_only),\n          m_(tm),\n          n_(tn),\n          k_(tk),\n          bm_(bm),\n          bn_(bn),\n          bk_(bk),\n          nm_(nm),\n          nn_(nn),\n          nk_(nk),\n          gm_(gm),\n          gn_(gn),\n          nm0_(nm0),\n          nn0_(nn0),\n          kernel_(m_, k_, n_, bm_, bk_, bn_),\n          num_thread_local_allocations_(0),\n          // We reserve 2X more capacity for a thread local values, than the\n          // number of threads in the pool to efficiently handle task stealing\n          // by threads that are not managed by the pool.\n          thread_local_capacity(2 * (parallelize_by_sharding_dim_only_\n                                         ? device_.numThreadsInPool()\n                                         : 0)),\n          // We will use only one of the Lhs/Rhs thread local storage depending\n          // on the shard_by_col value and we parallelize by sharding dim ONLY.\n          lhs_thread_local_blocks_(shard_by_col_ ? 0 : thread_local_capacity,\n                                   {*this}, {*this}),\n          rhs_thread_local_blocks_(shard_by_col_ ? thread_local_capacity : 0,\n                                   {*this}, {*this}) {\n      // These two options are mutually exclusive.\n      eigen_assert(!(parallel_pack && parallelize_by_sharding_dim_only));\n\n      for (Index x = 0; x < P; x++) {\n        // Normal number of notifications for k slice switch is\n        // nm_ + nn_ + nm_ * nn_. However, first P - 1 slices will receive only\n        // nm_ + nn_ notifications, because they will not receive notifications\n        // from preceding kernels.\n        state_switch_[x] =\n            x == 0\n                ? 1\n                : (parallel_pack_ ? nn_ + nm_ : (shard_by_col_ ? nn_ : nm_)) +\n                      (x == P - 1 ? nm_ * nn_ : 0);\n        state_packing_ready_[x] =\n            parallel_pack_ ? 0 : (shard_by_col_ ? nm_ : nn_);\n        state_kernel_[x] = new std::atomic<uint8_t>*[nm_];\n        for (Index m = 0; m < nm_; m++) {\n          state_kernel_[x][m] = new std::atomic<uint8_t>[nn_];\n          // Kernels generally receive 3 notifications (previous kernel + 2\n          // packing), but the first slice won't get notifications from previous\n          // kernels.\n          for (Index n = 0; n < nn_; n++)\n            state_kernel_[x][m][n].store(\n                (x == 0 ? 0 : 1) + (parallel_pack_ ? 2 : 1),\n                std::memory_order_relaxed);\n        }\n      }\n\n      // Allocate memory for packed rhs/lhs matrices.\n      packed_mem_ = kernel_.allocateSlices(            //\n          device_,                                     //\n          /*num_lhs=*/nm0_,                            //\n          /*num_rhs=*/nn0_,                            //\n          /*num_slices=*/std::min<Index>(nk_, P - 1),  //\n          packed_lhs_, packed_rhs_);\n\n      if (parallelize_by_sharding_dim_only_) {\n        const int num_worker_threads = device_.numThreadsInPool();\n\n        if (shard_by_col) {\n          can_use_thread_local_packed_ = new std::atomic<bool>[nn_];\n          for (int i = 0; i < nn_; ++i)\n            can_use_thread_local_packed_[i].store(true,\n                                                  std::memory_order_relaxed);\n\n          Index num_blocks = num_worker_threads * gn_;\n          thread_local_pre_alocated_mem_ = kernel_.allocateSlices(  //\n              device_,                                              //\n              /*num_lhs=*/0,                                        //\n              /*num_rhs=*/num_blocks,                               //\n              /*num_slices=*/1,                                     //\n              /*lhs_blocks=*/nullptr, &rhs_thread_local_pre_allocated_);\n\n        } else {\n          can_use_thread_local_packed_ = new std::atomic<bool>[nm_];\n          for (int i = 0; i < nm_; ++i)\n            can_use_thread_local_packed_[i].store(true,\n                                                  std::memory_order_relaxed);\n\n          Index num_blocks = num_worker_threads * gm_;\n          thread_local_pre_alocated_mem_ = kernel_.allocateSlices(  //\n              device_,                                              //\n              /*num_lhs=*/num_blocks,                               //\n              /*num_rhs=*/0,                                        //\n              /*num_slices=*/1, &lhs_thread_local_pre_allocated_,   //\n              /*rhs_blocks=*/nullptr);\n        }\n      }\n    }\n\n    ~EvalParallelContext() {\n      for (Index x = 0; x < P; x++) {\n        for (Index m = 0; m < nm_; m++) delete[] state_kernel_[x][m];\n        delete[] state_kernel_[x];\n      }\n      kernel_.deallocate(device_, packed_mem_);\n      if (parallelize_by_sharding_dim_only_) {\n        kernel_.deallocate(device_, thread_local_pre_alocated_mem_);\n        delete[] can_use_thread_local_packed_;\n      }\n    }\n\n    void run() {\n      // Kick off packing of the first slice.\n      signal_switch(0, 1);\n\n      // Wait for overall completion.\n      //\n      // If parallel evaluation is executed in async mode, this is a no-op, and\n      // Wait() will return immediately. In synchronous mode it will block the\n      // caller thread until it will receive notification from last task.\n      //\n      // In async mode, last task when completed will call done callback from\n      // the same thread, and will delete this context.\n      //\n      // TODO(dvyukov): This wait can lead to deadlock if contraction is\n      // evaluated in synchronous mode. If nthreads contractions are\n      // concurrently submitted from worker threads, this wait will block all\n      // worker threads and the system will deadlock.\n      done_.Wait();\n    }\n\n   private:\n    std::thread::id created_by_thread_id_;\n\n    // This notification is specialized on the type of DoneCallback and can be\n    // blocking or non-blocking.\n    EvalParallelNotification<DoneCallback, EvalParallelContext> done_;\n\n    const Device& device_;\n    LhsMapper lhs_;\n    RhsMapper rhs_;\n    Scalar* const buffer_;\n    OutputMapper output_;\n    OutputKernelType output_kernel_;\n    TensorContractionParams tensor_contraction_params_;\n    const int num_threads_;\n    const bool shard_by_col_;\n    const bool parallel_pack_;\n    const bool parallelize_by_sharding_dim_only_;\n    // Matrix sizes.\n    const Index m_;\n    const Index n_;\n    const Index k_;\n    // Block sizes.\n    const Index bm_;\n    const Index bn_;\n    const Index bk_;\n    // Number of tasks.\n    const Index nm_;\n    const Index nn_;\n    const Index nk_;\n    // Task grain sizes (number of kernels executed per task).\n    const Index gm_;\n    const Index gn_;\n    // Number of blocks (this is different from ni_/nn_ because of task size\n    // coarsening).\n    const Index nm0_;\n    const Index nn0_;\n    // Tensor contraction kernel.\n    TensorContractionKernel kernel_;\n\n    // Parallelization strategy.\n    //\n    // Blocks related to the same k block can run in parallel because they write\n    // to different output blocks. So we parallelize within k slices, this\n    // gives us parallelism level of m x n. Before we can start any kernels\n    // related to k-th slice, we need to issue m lhs packing tasks and n rhs\n    // packing tasks.\n    //\n    // However, there is a bottleneck when we are finishing kernels for k-th\n    // slice (at the very end there is only 1 runnable kernel). To mitigate this\n    // bottleneck we allow kernels from k-th and k+1-th slices to run in\n    // parallel. Note that (m, n, k) and (m, n, k+1) kernels write to the same\n    // output block, so they must not run in parallel.\n    //\n    // This gives us the following dependency graph.\n    // On each k slice we have m x n kernel tasks, m lhs paking tasks and n rhs\n    // packing tasks.\n    // Kernel (m, n, k) can start when:\n    //  - kernel (m, n, k-1) has finished\n    //  - lhs packing (m, k) has finished\n    //  - rhs packing (n, k) has finished\n    // Lhs/rhs packing can start when:\n    //  - all k-1 packing has finished (artificially imposed to limit amount of\n    //  parallel packing)\n    //\n    // On top of that we limit runnable tasks to two consecutive k slices.\n    // This is done to limit amount of memory we need for packed lhs/rhs\n    // (for each k slice we need m*bk + n*bk memory in packed_lhs_/packed_rhs_).\n    //\n    // state_switch_ tracks when we are ready to switch to the next k slice.\n    // state_kernel_[m][n] tracks when we are ready to kick off kernel (m, n).\n    // These variable are rolling over 3 consecutive k slices: first two we are\n    // actively executing + one to track completion of kernels in the second\n    // slice.\n    static const Index P = 3;\n\n    // Handle to the allocated temporary storage for Lhs/Rhs blocks.\n    BlockMemHandle packed_mem_;\n    std::vector<LhsBlock> packed_lhs_[P - 1];\n    std::vector<RhsBlock> packed_rhs_[P - 1];\n\n    // If we choose to parallelize only by the sharding dimension, each thread\n    // will have it's own \"thead local\" (not a c++ thread local storage) memory\n    // for packed_lhs or packed_rhs (shard_by_col = false of true). This memory\n    // can't be passed to a kernel that might execute on a different thread.\n    //\n    // In practice when we are ready to pack memory for the sharding dimension\n    // (rhs if shard_by_col==true) of the K-th slice, all kernels for K-1 slice\n    // already computed (99% of the time), and we can pack data into the thread\n    // local storage, and guarantee that all the kernels will be executed\n    // immediately in the same thread. This significantly increases L1 cache hit\n    // ratio and reduces pressure on the memory bus.\n    //\n    // It's still possible that kernel for the K-th slice will be ready before\n    // completion of the K-1 kernel, so we have to allocate \"global\" packed_lhs_\n    // and packed_rhs_ to allow kernels to be executed later on a thread\n    // different from the thread that was used for packing.\n\n    // Handle for pre-allocated thread local memory buffers.\n    BlockMemHandle thread_local_pre_alocated_mem_;\n\n    // Only one of these will be initialized depending on shard_by_col value\n    // (the size will be `num_worker_threads * num_grains_in_the_sharding_dim`).\n    std::vector<LhsBlock> lhs_thread_local_pre_allocated_;\n    std::vector<RhsBlock> rhs_thread_local_pre_allocated_;\n\n    // How many thread local blocks were already allocated.\n    std::atomic<int> num_thread_local_allocations_;\n    const int thread_local_capacity;\n\n    // We will use pre-allocated Lhs/Rhs blocks defined above, if the number of\n    // unique threads in a system is below or equal to the number of threads in\n    // a thread pool. We will fallback on dynamic memory allocation after that.\n\n    // ThreadLocalBlocks is a container for Lhs or Rhs thread local buffers. Its\n    // size is equal to the grain size in Lhs/Rhs sharding dimension.\n    template <typename BlockType>\n    class ThreadLocalBlocks {\n     public:\n      ThreadLocalBlocks() = default;\n\n      ThreadLocalBlocks(BlockType* base, size_t grain_size)\n          : is_pre_allocated_(true),\n            thread_local_pre_allocated_base_(base),\n            grain_size_(grain_size) {}\n\n      ThreadLocalBlocks(BlockMemHandle mem_handle,\n                        std::vector<BlockType> blocks)\n          : is_pre_allocated_(false),\n            mem_handle_(std::move(mem_handle)),\n            blocks_(std::move(blocks)) {}\n\n      BlockType& block(int grain_index) {\n        eigen_assert(grain_index >= 0);\n        eigen_assert(static_cast<size_t>(grain_index) < size());\n        return is_pre_allocated_ ? thread_local_pre_allocated_base_[grain_index]\n                                 : blocks_[grain_index];\n      }\n\n      void Release(EvalParallelContext& ctx) const {\n        if (!is_pre_allocated_) {\n          ctx.kernel_.deallocate(ctx.device_, mem_handle_);\n        }\n      }\n\n      size_t size() const {\n        return is_pre_allocated_ ? grain_size_ : blocks_.size();\n      }\n\n     private:\n      bool is_pre_allocated_;\n\n      // Reuse pre-allocated thread local buffers.\n      BlockType* thread_local_pre_allocated_base_ = nullptr;\n      size_t grain_size_ = 0;\n\n      // These will be initialized only if `is_pre_allocated == false`.\n      BlockMemHandle mem_handle_{};\n      std::vector<BlockType> blocks_;\n    };\n\n    // ThreadLocalBlocksInitialize callable does custom thread local blocks\n    // initialization, and will reuse pre-allocated buffers if possible, or will\n    // dynamically allocate new memory.\n    //\n    // Lhs/Rhs blocks might be of the same type, so we have to pass explicitly\n    // for what side do we plan to do block allocation.\n    template <typename BlockType, bool is_rhs>\n    class ThreadLocalBlocksInitialize {\n      static constexpr bool kIsLhs =\n          !is_rhs && std::is_same<BlockType, LhsBlock>::value;\n      static const bool kIsRhs =\n          is_rhs && std::is_same<BlockType, RhsBlock>::value;\n      static_assert(kIsLhs || kIsRhs, \"Unkown block type\");\n\n      using Blocks = ThreadLocalBlocks<BlockType>;\n\n     public:\n      ThreadLocalBlocksInitialize(EvalParallelContext& ctx)\n          : ctx_(ctx),\n            num_worker_threads_(ctx_.device_.numThreadsInPool()) {}\n\n      void operator()(Blocks& blocks) {\n        const int n = ctx_.num_thread_local_allocations_.fetch_add(\n            1, std::memory_order_relaxed);\n\n        if (n >= num_worker_threads_) {\n          ThreadLocalBlocksAllocator<is_rhs>::allocate(ctx_, blocks);\n        } else {\n          ThreadLocalBlocksAllocator<is_rhs>::reuse(ctx_, n, blocks);\n        }\n      }\n\n     private:\n      // NOTE(ezhulenev): Without 'if constexpr' we have to put calls to\n      // TensorContractionKernel::allocateSlices into template specializations.\n      // Also explicit specializations are not allowed at class scope in C++03,\n      // EvalCtx type parameter is just a workaround for that limitation.\n      template <bool pack_rhs, typename EvalCtx = EvalParallelContext>\n      struct ThreadLocalBlocksAllocator;\n\n      template <typename EvalCtx>\n      struct ThreadLocalBlocksAllocator</*pack_rhs=*/true, EvalCtx> {\n        static void allocate(EvalCtx& ctx, Blocks& blocks) {\n          std::vector<RhsBlock> rhs_blocks;\n          BlockMemHandle mem_handle = ctx.kernel_.allocateSlices(\n              ctx.device_,\n              /*num_lhs=*/0,\n              /*num_rhs=*/ctx.gn_,\n              /*num_slices=*/1,\n              /*lhs_blocks=*/nullptr, /*rhs_blocks=*/&rhs_blocks);\n\n          blocks = ThreadLocalBlocks<RhsBlock>(std::move(mem_handle),\n                                               std::move(rhs_blocks));\n        }\n\n        static void reuse(EvalCtx& ctx, int index, Blocks& blocks) {\n          RhsBlock* ptr = &ctx.rhs_thread_local_pre_allocated_[ctx.gn_ * index];\n          blocks = ThreadLocalBlocks<RhsBlock>(ptr, ctx.gn_);\n        }\n      };\n\n      template <typename EvalCtx>\n      struct ThreadLocalBlocksAllocator</*pack_rhs=*/false, EvalCtx> {\n        static void allocate(EvalCtx& ctx, Blocks& blocks) {\n          std::vector<LhsBlock> lhs_blocks;\n          BlockMemHandle mem_handle = ctx.kernel_.allocateSlices(\n              ctx.device_,\n              /*num_lhs=*/ctx.gm_,\n              /*num_rhs=*/0,\n              /*num_slices=*/1,\n              /*lhs_blocks=*/&lhs_blocks, /*rhs_blocks=*/nullptr);\n\n          blocks = ThreadLocalBlocks<LhsBlock>(std::move(mem_handle),\n                                               std::move(lhs_blocks));\n        }\n\n        static void reuse(EvalCtx& ctx, int index, Blocks& blocks) {\n          LhsBlock* ptr = &ctx.lhs_thread_local_pre_allocated_[ctx.gm_ * index];\n          blocks = ThreadLocalBlocks<LhsBlock>(ptr, ctx.gm_);\n        }\n      };\n\n      EvalParallelContext& ctx_;\n      const int num_worker_threads_;\n    };\n\n    template <typename BlockType>\n    class ThreadLocalBlocksRelease {\n     public:\n      using Blocks = ThreadLocalBlocks<BlockType>;\n      ThreadLocalBlocksRelease(EvalParallelContext& ctx) : ctx_(ctx) {}\n      void operator()(Blocks& blocks) { blocks.Release(ctx_); }\n\n     private:\n      EvalParallelContext& ctx_;\n    };\n\n    // ThreadLocalBlocks initialization callables.\n    using ThreadLocalLhsInit =\n        ThreadLocalBlocksInitialize<LhsBlock, /*is_rhs=*/false>;\n    using ThreadLocalRhsInit =\n        ThreadLocalBlocksInitialize<RhsBlock, /*is_rhs=*/true>;\n\n    // ThreadLocalBlocks release callables.\n    using ThreadLocalLhsRelease = ThreadLocalBlocksRelease<LhsBlock>;\n    using ThreadLocalRhsRelease = ThreadLocalBlocksRelease<RhsBlock>;\n\n    // Thread local containers for Lhs/Rhs block packs. In practice only one of\n    // them will be used, depending on the shard_by_col value.\n    Eigen::ThreadLocal<ThreadLocalBlocks<LhsBlock>, ThreadLocalLhsInit,\n                       ThreadLocalLhsRelease>\n        lhs_thread_local_blocks_;\n    Eigen::ThreadLocal<ThreadLocalBlocks<RhsBlock>, ThreadLocalRhsInit,\n                       ThreadLocalRhsRelease>\n        rhs_thread_local_blocks_;\n\n    // After a particular shard for Kth slice missed thread local execution\n    // opportunity (K-1 slice didn't complete kernels execution), we can no\n    // longer schedule K+1 and following slices in thread local mode, because\n    // there is no more guarantee that previous kernels were executed\n    // sequentially in the same thread (size is nn_ or nm_).\n    std::atomic<bool>* can_use_thread_local_packed_;\n\n    std::atomic<uint8_t>** state_kernel_[P];\n    // state_switch_ is frequently modified by worker threads, while other\n    // fields are read-only after constructor. Let's move it to a separate cache\n    // line to reduce cache-coherency traffic.\n    char pad_[128];\n    std::atomic<Index> state_packing_ready_[P];\n    std::atomic<Index> state_switch_[P];\n\n    LhsBlock& packed_lhs(Index m, Index k, Index m1, bool use_thread_local) {\n      if (use_thread_local) {\n        eigen_assert(!shard_by_col_);\n        ThreadLocalBlocks<LhsBlock>& blocks = lhs_thread_local_blocks_.local();\n\n        Index grain_index = m1 - m * gm_;\n        return blocks.block(internal::convert_index<int>(grain_index)); // FIXME better make ThreadLocalBlocks use Eigen::Index?\n      } else {\n        return packed_lhs_[k % (P - 1)][m1];\n      }\n    }\n\n    RhsBlock& packed_rhs(Index n, Index k, Index n1, bool use_thread_local) {\n      if (use_thread_local) {\n        eigen_assert(shard_by_col_);\n        ThreadLocalBlocks<RhsBlock>& blocks = rhs_thread_local_blocks_.local();\n\n        Index grain_index = n1 - n * gn_;\n        return blocks.block(internal::convert_index<int>(grain_index)); // FIXME better make ThreadLocalBlocks use Eigen::Index?\n      } else {\n        return packed_rhs_[k % (P - 1)][n1];\n      }\n    }\n\n    // In following two methods (pack_lhs and pack_rhs), if we know for sure\n    // that we'll be able to immediately call a kernel with packed data, and do\n    // not submit it to the thread pool, we can use thread local memory for\n    // packed data.\n    //\n    // We can only reliably check it if we are running all kernels in sync mode\n    // (parallelize only by sharding dim). If kernel for m==0 (n==0) is ready to\n    // run, it's guaranteed that all kernels with larger values of m (n) are\n    // also ready, because we execute them in the same order for all K slices.\n\n    void pack_lhs(Index m, Index k) {\n      bool use_thread_local = false;\n\n      if (parallelize_by_sharding_dim_only_ && !shard_by_col_ &&\n          can_use_thread_local_packed_[m].load(std::memory_order_relaxed)) {\n        if (state_kernel_[k % P][m][0].load(std::memory_order_relaxed) == 1) {\n          use_thread_local = true;\n        } else {\n          // If we can't guarantee that all kernels in `k` slice will be\n          // executed sequentially in current thread, it's no longer safe to use\n          // thread local memory in following slices along the k dimensions.\n          eigen_assert(k > 0);\n          can_use_thread_local_packed_[m].store(false,\n                                                std::memory_order_relaxed);\n        }\n      }\n\n      const Index mend = m * gm_ + gm(m);\n      for (Index m1 = m * gm_; m1 < mend; m1++)\n        kernel_.packLhs(&packed_lhs(m, k, m1, use_thread_local),\n                        lhs_.getSubMapper(m1 * bm_, k * bk_), bk(k), bm(m1));\n\n      if (!parallel_pack_ && shard_by_col_) {\n        assert(!use_thread_local);\n        signal_packing(k);\n      } else {\n        signal_switch(k + 1);\n        for (Index n = nn_ - 1; n >= 0; n--) {\n          bool sync = parallelize_by_sharding_dim_only_ || n == 0;\n          signal_kernel(m, n, k, sync, use_thread_local);\n        }\n      }\n    }\n\n    void pack_rhs(Index n, Index k) {\n      bool use_thread_local = false;\n\n      if (parallelize_by_sharding_dim_only_ && shard_by_col_ &&\n          can_use_thread_local_packed_[n].load(std::memory_order_relaxed)) {\n        if (state_kernel_[k % P][0][n].load(std::memory_order_relaxed) == 1) {\n          use_thread_local = true;\n        } else {\n          // If we can't guarantee that all kernels in `k` slice will be\n          // executed sequentially in current thread, it's no longer safe to use\n          // thread local memory in followig slices along the k dimensions.\n          eigen_assert(k > 0);\n          can_use_thread_local_packed_[n].store(false,\n                                                std::memory_order_relaxed);\n        }\n      }\n\n      const Index nend = n * gn_ + gn(n);\n      for (Index n1 = n * gn_; n1 < nend; n1++) {\n        if (!TensorContractionKernel::HasBeta && k == 0) {\n          // Zero the output memory in parallel, only if contraction kernel does\n          // not support `beta`. Otherwise we will pass beta 0.0 to the first\n          // call to the `TensorContractionKernel::invoke()`.\n          //\n          // On 10000x2x10000 mm zeroing can easily take half of time. Zero (bn\n          // x m) row. Safe to do here because all kernels that will write to\n          // this memory depend on completion of this task. Note: don't call\n          // device_.memset() here. device_.memset() blocks on thread pool\n          // worker thread, which can lead to underutilization and deadlocks.\n          memset(buffer_ + n1 * bn_ * m_, 0, bn(n1) * m_ * sizeof(Scalar));\n        }\n        kernel_.packRhs(&packed_rhs(n, k, n1, use_thread_local),\n                        rhs_.getSubMapper(k * bk_, n1 * bn_), bk(k), bn(n1));\n      }\n\n      if (parallel_pack_ || shard_by_col_) {\n        signal_switch(k + 1);\n        for (Index m = nm_ - 1; m >= 0; m--) {\n          bool sync = parallelize_by_sharding_dim_only_ || m == 0;\n          signal_kernel(m, n, k, sync, use_thread_local);\n        }\n      } else {\n        assert(!use_thread_local);\n        signal_packing(k);\n      }\n    }\n\n    void kernel(Index m, Index n, Index k, bool use_thread_local) {\n      // Note: order of iteration matters here. Iteration over m is innermost\n      // because we want to reuse the same packed rhs in consecutive tasks\n      // (rhs fits into L2$ while lhs only into L3$).\n      const Index nend = n * gn_ + gn(n);\n      const Index mend = m * gm_ + gm(m);\n\n      // NOTE: output = alpha * LHS * RHS + beta * output.\n      const Scalar alpha = Scalar(1);\n      const Scalar beta =\n          (TensorContractionKernel::HasBeta && k == 0) ? Scalar(0) : Scalar(1);\n\n      if (shard_by_col_) {\n        for (Index n1 = n * gn_; n1 < nend; n1++) {\n          for (Index m1 = m * gm_; m1 < mend; m1++) {\n            const auto output_mapper = output_.getSubMapper(m1 * bm_, n1 * bn_);\n            kernel_.invoke(\n                output_mapper,\n                packed_lhs(m, k, m1, !shard_by_col_ && use_thread_local),\n                packed_rhs(n, k, n1, shard_by_col_ && use_thread_local), bm(m1),\n                bk(k), bn(n1), alpha, beta);\n\n            // We are done with the last task for the [m1, n1] block.\n            if (k + 1 == nk_) {\n              output_kernel_(output_mapper, tensor_contraction_params_,\n                             m1 * bm_, n1 * bn_, bm(m1), bn(n1));\n            }\n          }\n        }\n      } else {\n        for (Index m1 = m * gm_; m1 < mend; m1++)\n          for (Index n1 = n * gn_; n1 < nend; n1++) {\n            const auto output_mapper = output_.getSubMapper(m1 * bm_, n1 * bn_);\n            kernel_.invoke(\n                output_mapper,\n                packed_lhs(m, k, m1, !shard_by_col_ && use_thread_local),\n                packed_rhs(n, k, n1, shard_by_col_ && use_thread_local), bm(m1),\n                bk(k), bn(n1), alpha, beta);\n\n            // We are done with the last task for the [m1, n1] block.\n            if (k + 1 == nk_) {\n              output_kernel_(output_mapper, tensor_contraction_params_,\n                             m1 * bm_, n1 * bn_, bm(m1), bn(n1));\n            }\n          }\n      }\n      signal_kernel(m, n, k + 1, /*sync=*/false, /*use_thread_local=*/false);\n      signal_switch(k + 2);\n    }\n\n    void signal_packing(Index k) {\n      eigen_assert(!parallel_pack_);\n      Index s = state_packing_ready_[k % P].fetch_sub(1);\n      eigen_assert(s > 0);\n      if (s != 1) return;\n      state_packing_ready_[k % P] = shard_by_col_ ? nm_ : nn_;\n      enqueue_packing(k, shard_by_col_);\n    }\n\n    void signal_kernel(Index m, Index n, Index k, bool sync,\n                       bool use_thread_local) {\n      std::atomic<uint8_t>* state = &state_kernel_[k % P][m][n];\n      Index s = state->load();\n      eigen_assert(s > 0);\n      if (s != 1 && state->fetch_sub(1) != 1) {\n        eigen_assert(!use_thread_local);\n        return;\n      }\n      state->store(parallel_pack_ ? 3 : 2, std::memory_order_relaxed);\n      if (sync) {\n        kernel(m, n, k, use_thread_local);\n      } else {\n        eigen_assert(!use_thread_local);\n        device_.enqueueNoNotification(\n            [=]() { kernel(m, n, k, use_thread_local); });\n      }\n    }\n\n    void signal_switch(Index k, Index v = 1) {\n      Index s = state_switch_[k % P].fetch_sub(v);\n      eigen_assert(s >= v);\n      if (s != v) return;\n\n      // Ready to switch to the next k slice.\n      // Reset counter for the next iteration.\n      state_switch_[k % P] =\n          (parallel_pack_ ? nm_ + nn_ : (shard_by_col_ ? nn_ : nm_)) +\n          nm_ * nn_;\n      if (k < nk_) {\n        // Issue lhs/rhs packing. Their completion will in turn kick off\n        // kernels.\n        if (parallel_pack_) {\n          enqueue_packing(k, !shard_by_col_);\n          enqueue_packing(k, shard_by_col_);\n        } else if (shard_by_col_) {\n          enqueue_packing(k, false);\n        } else {\n          enqueue_packing(k, true);\n        }\n\n        // Termination handling.\n        // Because kernel completion signals k + 2 switch, we need to finish nk\n        // + 2 slices without issuing any tasks on nk + 1 slice. So here we\n        // pretend that all nk + 1 packing tasks just finish instantly; so that\n        // nk + 2 switch only waits for completion of nk kernels.\n      } else if (k == nk_) {\n        signal_switch(k + 1,\n                      parallel_pack_ ? nm_ + nn_ : (shard_by_col_ ? nn_ : nm_));\n      } else {\n        done_.Notify();\n      }\n    }\n\n    // Enqueue all rhs/lhs packing for k-th slice.\n    void enqueue_packing(Index k, bool rhs) {\n      enqueue_packing_helper(0, rhs ? nn_ : nm_, k, rhs);\n    }\n\n    void enqueue_packing_helper(Index start, Index end, Index k, bool rhs) {\n      if (end - start == 1) {\n        if (rhs)\n          pack_rhs(start, k);\n        else\n          pack_lhs(start, k);\n      } else {\n        while (end - start > 1) {\n          Index mid = (start + end) / 2;\n          device_.enqueueNoNotification(\n              [=]() { enqueue_packing_helper(mid, end, k, rhs); });\n          end = mid;\n        }\n\n        // Decide if we want to run first packing task (start == 0) in\n        // async mode if we parallelize only by sharding dim:\n        // (1) pack_lhs and pack_rhs call signal_switch before completing\n        //     all calls to signal_kernel, which in sync mode might lead\n        //     to the execution of the first kernel of the k+1 slice, before\n        //     completing a call to the last kernel of the k slice.\n        // (2) all pack tasks for sharded dim must be executed in a thread\n        //     pool to get pre-allocated thead local buffers.\n        bool pack_async =\n          (start == 0) &&\n          (parallelize_by_sharding_dim_only_&& shard_by_col_ == rhs) &&\n          (k > 0 || std::this_thread::get_id() == created_by_thread_id_);\n\n        if (pack_async) {\n          device_.enqueueNoNotification(\n              [=]() { enqueue_packing_helper(start, end, k, rhs); });\n        } else {\n          enqueue_packing_helper(start, end, k, rhs);\n        }\n      }\n    }\n\n    // Block sizes with accounting for potentially incomplete last block.\n    Index bm(Index m) const { return m + 1 < nm0_ ? bm_ : m_ + bm_ - bm_ * nm0_; }\n    Index bn(Index n) const { return n + 1 < nn0_ ? bn_ : n_ + bn_ - bn_ * nn0_; }\n    Index bk(Index k) const { return k + 1 < nk_ ? bk_ : k_ + bk_ - bk_ * nk_; }\n    // Task grain sizes accounting for potentially incomplete last task.\n    Index gm(Index m) const { return m + 1 < nm_ ? gm_ : nm0_ + gm_ - gm_ * nm_; }\n    Index gn(Index n) const { return n + 1 < nn_ ? gn_ : nn0_ + gn_ - gn_ * nn_; }\n\n    EvalParallelContext(const EvalParallelContext&) = delete;\n    void operator=(const EvalParallelContext&) = delete;\n  };\n\n  template <bool lhs_inner_dim_contiguous, bool rhs_inner_dim_contiguous,\n            bool rhs_inner_dim_reordered, int Alignment>\n  using SyncEvalParallelContext =\n      EvalParallelContext<NoCallback, lhs_inner_dim_contiguous,\n                          rhs_inner_dim_contiguous, rhs_inner_dim_reordered,\n                          Alignment>;\n\n  // ------------------------------------------------------------------------ //\n\n  // EvalShardedByInnerDimContext orchestrates sync/async contraction\n  // evaluation, when we shard by inner dimension. When it is executed in\n  // asynchronous mode, it owns all the shared state that might be accessible by\n  // block processing tasks.\n\n  template <typename DoneCallback>\n  struct EvalShardedByInnerDimContext {\n    EvalShardedByInnerDimContext(const Self* self, int num_threads,\n                                 Scalar* result_buffer,\n                                 Index m_size, Index n_size, Index k_size,\n                                 DoneCallback done_callback)\n        : evaluator(self),\n          m_lhs_inner_dim_contiguous(evaluator->m_lhs_inner_dim_contiguous),\n          m_rhs_inner_dim_contiguous(evaluator->m_rhs_inner_dim_contiguous),\n          m_rhs_inner_dim_reordered(evaluator->m_rhs_inner_dim_reordered),\n          result(result_buffer),\n          m(m_size),\n          n(n_size),\n          k(k_size),\n          done(std::move(done_callback)),\n          buffer_size_bytes(m * n * sizeof(Scalar)),\n          block_size(blockSize(k, num_threads)),\n          num_blocks(divup<Index>(k, block_size)),\n          num_pending_blocks(internal::convert_index<int>(num_blocks)),\n          l0_ranges(divup<Index>(num_blocks, l0_size)),\n          l0_state(l0_ranges),\n          block_buffers(num_blocks) {\n      // Keep count of pending gemm tasks for each l0 range.\n      for (int i = 0; i < l0_ranges; ++i) {\n        const Index num_pending_tasks = actualRangeSize(l0_ranges, l0_size, i);\n        l0_state.emplace_back(internal::convert_index<int>(num_pending_tasks));\n      }\n\n      // Allocate temporary buffers for each block.\n      for (Index block_idx = 0; block_idx < num_blocks; ++block_idx) {\n        Scalar* buf = block_idx == 0\n                          ? result\n                          : static_cast<Scalar*>(evaluator->m_device.allocate(\n                                buffer_size_bytes));\n        block_buffers.emplace_back(buf);\n      }\n    }\n\n    ~EvalShardedByInnerDimContext() {\n      for (Index i = 1; i < num_blocks; ++i) {\n        evaluator->m_device.deallocate(block_buffers[i]);\n      }\n    }\n\n    template <int Alignment>\n    void run() {\n      Barrier barrier(internal::convert_index<int>(num_blocks));\n      eval<Alignment>(barrier, 0, num_blocks);\n      barrier.Wait();\n\n      // Aggregate partial sums from l0 ranges.\n      aggregateL0Blocks<Alignment>();\n\n      // Apply output kernel.\n      applyOutputKernel();\n    }\n\n    template <int Alignment>\n    void runAsync() {\n      evalAsync<Alignment>(0, num_blocks);\n    }\n\n   private:\n    // The underlying GEMM kernel assumes that k is a multiple of\n    // the packet size and subtle breakage occurs if this is violated.\n    static const Index packet_size = internal::packet_traits<RhsScalar>::size;\n\n    const Self* evaluator;  // TensorContraction evaluator\n\n    // These fields required fromTENSOR_CONTRACTION_DISPATCH macro.\n    bool m_lhs_inner_dim_contiguous;\n    bool m_rhs_inner_dim_contiguous;\n    bool m_rhs_inner_dim_reordered;\n\n    Scalar* result;\n\n    Index m;\n    Index n;\n    Index k;\n\n    DoneCallback done;\n\n    // ----------------------------------------------------------------------//\n    // Algorithm parameters.\n\n    // We will compute partial results into the buffers of this size.\n    Index buffer_size_bytes;\n\n    Index block_size;\n    Index num_blocks;\n\n    // Keep track of pending tasks when evaluate in async mode.\n    std::atomic<int> num_pending_blocks;\n\n    // We compute partial gemm results in parallel, and to get the final result\n    // we need to add them all together. For the large number of threads (>= 48)\n    // this adds a very expensive sequential step at the end.\n    //\n    // We split the [0, num_blocks) into small ranges, and when a task for the\n    // block finishes its partial gemm computation, it checks if it was the last\n    // gemm in the range, and if so, it will add all blocks of the range.\n    //\n    // After all tasks done, we need to add only these pre-aggregated blocks.\n\n    // For now we use just a single level of ranges to compute pre-aggregated\n    // partial sums, but in general we can use more layers to compute tree\n    // aggregation in parallel and reduce the size of the sequential step.\n    //\n    // TODO(ezhulenev): Add multilevel tree aggregation? Probably will make\n    // sense only if number of threads >= ~128?\n    static const Index l0_size = 4;\n    Index l0_ranges;\n\n    // Keep count of pending gemm tasks for each l0 range.\n    MaxSizeVector<std::atomic<int>> l0_state;  // [0, l0_ranges)\n\n    // Buffers allocated for each temporary block computation.\n    MaxSizeVector<Scalar*> block_buffers;  // [0, num_blocks)\n\n    template <int Alignment>\n    void processBlock(Index block_idx, Index begin, Index end) {\n      Scalar* buf = block_buffers[block_idx];\n\n      TENSOR_CONTRACTION_DISPATCH(\n          evaluator->template evalGemmPartialWithoutOutputKernel, Alignment,\n          (buf, begin, end,\n           /*num_threads=*/internal::convert_index<int>(num_blocks)));\n\n      // Check if it was the last task in l0 range.\n      const Index l0_index = block_idx / l0_size;\n      const int v = l0_state[l0_index].fetch_sub(1);\n      eigen_assert(v >= 1);\n\n      // If we processed the last block of the range, we can aggregate all\n      // partial results into the first block of the range.\n      if (v == 1) {\n        const Index rng_size = actualRangeSize(l0_ranges, l0_size, l0_index);\n        const Index dst_block_idx = l0_index * l0_size;\n\n        if (rng_size == l0_size) {\n          addAllToBuffer<Alignment>(\n              m * n,\n              /*src_buf0=*/block_buffers[dst_block_idx + 1],\n              /*src_buf1=*/block_buffers[dst_block_idx + 2],\n              /*src_buf2=*/block_buffers[dst_block_idx + 3],\n              /*dst_buf= */ block_buffers[dst_block_idx]);\n        } else {\n          // Aggregate blocks of potentially incomplete last range.\n          for (int i = 1; i < rng_size; ++i) {\n            addToBuffer<Alignment>(m * n,\n                                   /*src_buf=*/block_buffers[dst_block_idx + i],\n                                   /*dst_buf=*/block_buffers[dst_block_idx]);\n          }\n        }\n      }\n    }\n\n    // Aggregate partial sums from l0 ranges.\n    template <int Alignment>\n    void aggregateL0Blocks() const {\n      Index l0_index = 1;\n\n      for (; l0_index + 2 < l0_ranges; l0_index += 3) {\n        addAllToBuffer<Alignment>(\n            m * n,\n            /*src_buf0=*/block_buffers[(l0_index + 0) * l0_size],\n            /*src_buf1=*/block_buffers[(l0_index + 1) * l0_size],\n            /*src_buf2=*/block_buffers[(l0_index + 2) * l0_size],\n            /*dst_buf= */ block_buffers[0]);\n      }\n\n      for (; l0_index < l0_ranges; ++l0_index) {\n        addToBuffer<Alignment>(m * n, block_buffers[l0_index * l0_size],\n                               block_buffers[0]);\n      }\n    }\n\n    void applyOutputKernel() const {\n      typedef internal::blas_data_mapper<Scalar, Index, ColMajor> OutputMapper;\n      evaluator->m_output_kernel(\n          OutputMapper(result, m), evaluator->m_tensor_contraction_params,\n          static_cast<Eigen::Index>(0), static_cast<Eigen::Index>(0), m, n);\n    }\n\n    // Compute block size with accounting for potentially incomplete last block.\n    Index actualBlockSize(Index block_idx) const {\n      return block_idx + 1 < num_blocks\n                 ? block_size\n                 : k + block_size - block_size * num_blocks;\n    };\n\n    // Compute range size with accounting for potentially incomplete last range.\n    Index actualRangeSize(Index num_ranges, Index range_size,\n                          Index range_idx) const {\n      eigen_assert(range_idx < num_ranges);\n      return range_idx + 1 < num_ranges\n                 ? range_size\n                 : num_blocks + range_size - range_size * num_ranges;\n    };\n\n    template <int Alignment>\n    EIGEN_STRONG_INLINE static void addToBuffer(size_t n, const Scalar* src_buf,\n                                                Scalar* tgt_buf) {\n      const int output_packet_size =\n          internal::unpacket_traits<PacketReturnType>::size;\n      size_t i = 0;\n      const size_t num_packets = n / output_packet_size;\n      for (; i < output_packet_size * num_packets; i += output_packet_size) {\n        const PacketReturnType src_val =\n            internal::pload<PacketReturnType>(src_buf + i);\n        const PacketReturnType tgt_val =\n            internal::ploadt<PacketReturnType, Alignment>(tgt_buf + i);\n        const PacketReturnType sum = internal::padd(src_val, tgt_val);\n        internal::pstoret<Scalar, PacketReturnType, Alignment>(tgt_buf + i,\n                                                               sum);\n      }\n      for (; i < n; ++i) {\n        tgt_buf[i] += src_buf[i];\n      }\n    }\n\n    template <int Alignment>\n    EIGEN_STRONG_INLINE static void addAllToBuffer(size_t n,\n                                                   const Scalar* src_buf0,\n                                                   const Scalar* src_buf1,\n                                                   const Scalar* src_buf2,\n                                                   Scalar* dst_buf) {\n      using ::Eigen::internal::padd;\n      using ::Eigen::internal::pload;\n      using ::Eigen::internal::ploadt;\n      using ::Eigen::internal::pstoret;\n\n      const int output_packet_size =\n          internal::unpacket_traits<PacketReturnType>::size;\n\n      size_t i = 0;\n      const size_t num_packets = n / output_packet_size;\n      for (; i < output_packet_size * num_packets; i += output_packet_size) {\n        const auto src_val0 = pload<PacketReturnType>(src_buf0 + i);\n        const auto src_val1 = pload<PacketReturnType>(src_buf1 + i);\n        const auto src_val2 = pload<PacketReturnType>(src_buf2 + i);\n\n        const auto dst_val = ploadt<PacketReturnType, Alignment>(dst_buf + i);\n        const auto sum =\n            padd(padd(dst_val, src_val0), padd(src_val1, src_val2));\n\n        pstoret<Scalar, PacketReturnType, Alignment>(dst_buf + i, sum);\n      }\n      for (; i < n; ++i) {\n        dst_buf[i] += src_buf0[i] + src_buf1[i] + src_buf2[i];\n      }\n    }\n\n    template <int Alignment>\n    void eval(Barrier& barrier, Index start_block_idx, Index end_block_idx) {\n      while (end_block_idx - start_block_idx > 1) {\n        Index mid_block_idx = (start_block_idx + end_block_idx) / 2;\n        evaluator->m_device.enqueueNoNotification(\n            [this, &barrier, mid_block_idx, end_block_idx]() {\n              eval<Alignment>(barrier, mid_block_idx, end_block_idx);\n            });\n        end_block_idx = mid_block_idx;\n      }\n\n      Index block_idx = start_block_idx;\n      Index block_start = block_idx * block_size;\n      Index block_end = block_start + actualBlockSize(block_idx);\n\n      processBlock<Alignment>(block_idx, block_start, block_end);\n      barrier.Notify();\n    }\n\n    template <int Alignment>\n    void evalAsync(Index start_block_idx, Index end_block_idx) {\n      while (end_block_idx - start_block_idx > 1) {\n        Index mid_block_idx = (start_block_idx + end_block_idx) / 2;\n        evaluator->m_device.enqueueNoNotification(\n            [this, mid_block_idx, end_block_idx]() {\n              evalAsync<Alignment>(mid_block_idx, end_block_idx);\n            });\n        end_block_idx = mid_block_idx;\n      }\n\n      Index block_idx = start_block_idx;\n\n      Index block_start = block_idx * block_size;\n      Index block_end = block_start + actualBlockSize(block_idx);\n\n      processBlock<Alignment>(block_idx, block_start, block_end);\n\n      int v = num_pending_blocks.fetch_sub(1);\n      eigen_assert(v >= 1);\n\n      if (v == 1) {\n        // Aggregate partial sums from l0 ranges.\n        aggregateL0Blocks<Alignment>();\n\n        // Apply output kernel.\n        applyOutputKernel();\n\n        // NOTE: If we call `done` callback before deleting this (context),\n        // it might deallocate Self* pointer captured by context, and we'll\n        // fail in destructor trying to deallocate temporary buffers.\n\n        // Move done call back from context before it will be destructed.\n        DoneCallback done_copy = std::move(done);\n\n        // We are confident that we are the last one who touches context.\n        delete this;\n\n        // Now safely call the done callback.\n        done_copy();\n      }\n    }\n\n    // Cost model doesn't capture well the cost associated with constructing\n    // tensor contraction mappers and computing loop bounds in gemm_pack_lhs\n    // and gemm_pack_rhs, so we specify minimum desired block size.\n    static Index blockSize(Index k, int num_threads) {\n      const auto round_up = [=](Index index) -> Index {\n        const Index kmultiple = packet_size <= 8 ? 8 : packet_size;\n        return divup<Index>(index, kmultiple) * kmultiple;\n      };\n\n      const Index target_block_size = round_up(divup<Index>(k, num_threads));\n      const Index desired_min_block_size = 12 * packet_size;\n\n      return numext::mini<Index>(\n          k, numext::maxi<Index>(desired_min_block_size, target_block_size));\n    }\n\n    EvalShardedByInnerDimContext(const EvalShardedByInnerDimContext&) = delete;\n    void operator=(const EvalShardedByInnerDimContext&) = delete;\n  };\n\n  // ------------------------------------------------------------------------ //\n\n  // Below are the function used by evalProductImpl heuristics, trying to select\n  // optimcal parameters for parallelization algorithm.\n\n  // Decide whether we want to shard m x n contraction by columns or by rows.\n  static bool shardByCol(Index m, Index n, Index num_threads) {\n    // Note: we are comparing both n and m against Traits::nr, it is not\n    // a mistake. We are trying to figure out how both n and m will fit into\n    // the main sharding dimension.\n\n    // Sharding by column is the default\n    // ... unless there is enough data for vectorization over rows\n    if (m / num_threads >= Traits::nr &&\n        // and not enough data for vectorization over columns\n        (n / num_threads < Traits::nr ||\n         // ... or barely enough data for vectorization over columns,\n         // but it is not evenly dividable across threads\n         (n / num_threads < 4 * Traits::nr &&\n          (n % (num_threads * Traits::nr)) != 0 &&\n          // ... and it is evenly dividable across threads for rows\n          ((m % (num_threads * Traits::nr)) == 0 ||\n           // .. or it is not evenly dividable for both dimensions but\n           // there is much more data over rows so that corner effects are\n           // mitigated.\n           (m / n >= 6)))))\n      return false;\n    // Wait, or if matrices are just substantially prolonged over the other\n    // dimension.\n    if (n / num_threads < 16 * Traits::nr && m > n * 32) return false;\n    return true;\n  }\n\n  Index coarsenM(Index m, Index n, Index bm, Index bn, Index bk, Index gn,\n                 int num_threads, bool shard_by_col) const {\n    Index gm = 1;\n    Index gm1 = 1;\n    Index nm0 = divup(m, bm);\n    Index nm1 = nm0;\n    for (;;) {\n      // Find the next candidate for m grain size. It needs to result in\n      // different number of blocks. E.g. if we have 10 kernels, we want to try\n      // 5 and 10, but not 6, 7, 8 and 9.\n      while (gm1 <= nm0 && nm1 == divup(nm0, gm1)) gm1++;\n      if (gm1 > nm0) break;\n      // Check the candidate.\n      int res = checkGrain(m, n, bm, bn, bk, gm1, gn, gm, gn, num_threads,\n                           shard_by_col);\n      if (res < 0) break;\n      nm1 = divup(nm0, gm1);\n      if (res == 0) continue;\n      // Commit new grain size.\n      gm = gm1;\n    }\n    return gm;\n  }\n\n  Index coarsenN(Index m, Index n, Index bm, Index bn, Index bk, Index gm,\n                 int num_threads, bool shard_by_col) const {\n    Index gn = 1;\n    Index gn1 = 1;\n    Index nn0 = divup(n, bn);\n    Index nn1 = nn0;\n    for (;;) {\n      while (gn1 <= nn0 && nn1 == divup(nn0, gn1)) gn1++;\n      if (gn1 > nn0) break;\n      int res = checkGrain(m, n, bm, bn, bk, gm, gn1, gm, gn, num_threads,\n                           shard_by_col);\n      if (res < 0) break;\n      nn1 = divup(nn0, gn1);\n      if (res == 0) continue;\n      gn = gn1;\n    }\n    return gn;\n  }\n\n  // checkGrain checks whether grain (gm, gn) is suitable and is better than\n  // (oldgm, oldgn).\n  int checkGrain(Index m, Index n, Index bm, Index bn, Index bk, Index gm,\n                 Index gn, Index oldgm, Index oldgn, int num_threads,\n                 bool shard_by_col) const {\n    const TensorOpCost cost =\n        contractionCost(bm * gm, bn * gn, bm, bn, bk, shard_by_col, true);\n    double taskSize = TensorCostModel<ThreadPoolDevice>::taskSize(\n        static_cast<double>(bm) * gm * bn * gn, cost);\n    // If the task is too small, then we agree on it regardless of anything\n    // else. Otherwise synchronization overheads will dominate.\n    if (taskSize < 1) return 1;\n    // If it is too large, then we reject it and all larger tasks.\n    if (taskSize > 2) return -1;\n    // Now we are in presumably good task size range.\n    // The main deciding factor here is parallelism. Consider that we have 12\n    // kernels and 4 threads. Grains of 2, 3 and 4 all yield good task sizes.\n    // But 2/4 yield 6/3 tasks, which gives us parallelism of 0.75 (at most 3/4\n    // of cores will be busy). While grain size 3 gives us 4 tasks, which gives\n    // us parallelism of 1 (we can load all cores).\n    Index nm0 = divup(m, bm);\n    Index nn0 = divup(n, bn);\n    Index new_tasks = divup(nm0, gm) * divup(nn0, gn);\n    double new_parallelism = static_cast<double>(new_tasks) /\n                             (divup<int>(new_tasks, num_threads) * num_threads);\n    Index old_tasks = divup(nm0, oldgm) * divup(nn0, oldgn);\n    double old_parallelism = static_cast<double>(old_tasks) /\n                             (divup<int>(old_tasks, num_threads) * num_threads);\n    if (new_parallelism > old_parallelism || new_parallelism == 1) return 1;\n    return 0;\n  }\n\n  TensorOpCost contractionCost(Index m, Index n, Index bm, Index bn, Index bk,\n                               bool shard_by_col, bool prepacked) const {\n    const int packed_size = std::min<int>(PacketType<LhsScalar, Device>::size,\n                                          PacketType<RhsScalar, Device>::size);\n    const int output_packet_size = internal::unpacket_traits<PacketReturnType>::size;\n    const double kd = static_cast<double>(bk);\n    double compute_bandwidth = computeBandwidth(false, bm, bn, bk);\n    // Computations.\n    TensorOpCost cost = TensorOpCost(0, 0, kd * compute_bandwidth, true, packed_size);\n    // Output stores.\n    cost += TensorOpCost(0, sizeof(CoeffReturnType), 0, true, output_packet_size);\n    if (prepacked) {\n      // Packing and kernels are executed in different tasks. When we calculate\n      // task grain size we look only at kernel cost assuming that kernel\n      // is more expensive than packing.\n      return cost;\n    }\n    // Lhs/rhs loads + computations.\n    TensorOpCost lhsCost = this->m_leftImpl.costPerCoeff(true) * (kd / n);\n    TensorOpCost rhsCost = this->m_rightImpl.costPerCoeff(true) * (kd / m);\n    // Lhs packing memory cost does not contribute considerably to overall\n    // execution time because lhs is prefetched early and accessed sequentially.\n    if (shard_by_col)\n      lhsCost.dropMemoryCost();\n    else\n      rhsCost.dropMemoryCost();\n    return cost + lhsCost + rhsCost;\n  }\n\n  // Decide whether we want to shard m x k x n contraction over the inner\n  // (contraction) dimension (k).\n  static bool shardByInnerDim(Index m, Index n, Index k, int num_threads,\n                              int num_threads_by_k) {\n    std::ptrdiff_t bufsize = m * n * sizeof(Scalar);\n    bool shard_by_k = false;\n    if (n == 1 ||                // If mat*vec or...\n        num_threads_by_k < 2 ||  // running single threaded or...\n        num_threads_by_k <\n            num_threads ||  // sharding by k gives less parallelism or...\n        bufsize > l3CacheSize() / num_threads_by_k ||  // need more buffer space\n        // than L3 cache or...\n        k / num_threads_by_k < 2 * Traits::nr) {  // k per thread is tiny.\n      shard_by_k = false;\n    } else if (numext::maxi(m, n) / num_threads <\n                   Traits::nr ||  // both other dimensions are tiny or...\n               // k per thread is not small and...\n               (k / num_threads_by_k > 8 * Traits::nr &&\n                // one of the outer dimensions is tiny or sharding by k offers\n                // more parallelism.\n                (numext::mini(m, n) < 2 * Traits::nr ||\n                 num_threads_by_k > num_threads))) {\n      shard_by_k = true;\n    }\n    return shard_by_k;\n  }\n\n  TensorOpCost contractionCostPerInnerDim(Index m, Index n, Index k) const {\n    // Compute cost.\n    const int output_packet_size = internal::unpacket_traits<PacketReturnType>::size;\n    TensorOpCost cost(0, 0, (computeBandwidth(true, m, n, k) * m) * n, true, output_packet_size);\n    // Output stores.\n    cost += TensorOpCost(0, sizeof(CoeffReturnType), 0, true, output_packet_size);\n    TensorOpCost lhsCost = this->m_leftImpl.costPerCoeff(true) * m;\n    TensorOpCost rhsCost = this->m_rightImpl.costPerCoeff(true) * n;\n    // Since the inner gemm kernel is always sharded by column, the lhs\n    // load cost is negligible.\n    lhsCost.dropMemoryCost();\n    return cost + lhsCost + rhsCost;\n  }\n\n  int numThreadsInnerDim(Index m, Index n, Index k) const {\n    const int output_packet_size = internal::unpacket_traits<PacketReturnType>::size;\n    TensorOpCost cost = contractionCostPerInnerDim(m, n, k);\n    double total_parallel_cost =\n        TensorCostModel<ThreadPoolDevice>::totalCost(k, cost);\n    // Cost of reduction step accumulating the m*n per-thread buffers into the\n    // result.\n    double reduction_cost = TensorCostModel<ThreadPoolDevice>::totalCost(\n        m * n, TensorOpCost(2, 1, 1, true, output_packet_size));\n    int num_threads = 1;\n    double min_cost = total_parallel_cost;\n    double kPerThreadOverHead = 3000;\n    double kFixedOverHead = 100000;\n    for (int nt = 2; nt <= this->m_device.numThreads(); nt += 2) {\n      double sequential_cost =\n          kFixedOverHead + nt * (reduction_cost + kPerThreadOverHead);\n      double parallel_cost = total_parallel_cost / nt + sequential_cost;\n      if (parallel_cost < min_cost) {\n        num_threads = nt;\n        min_cost = parallel_cost;\n      }\n    }\n    return num_threads;\n  }\n\n  double computeBandwidth(bool shard_by_col, Index bm, Index bn,\n                          Index bk) const {\n    // Peak VFMA bandwidth is 0.5. However if we have not enough data for\n    // vectorization bandwidth drops. The 4.0 and 2.0 bandwidth is determined\n    // experimentally.\n    double computeBandwidth =\n        bk == 1 ? 4.0\n                : (shard_by_col ? bn : bm) < Traits::nr ||\n                          (shard_by_col ? bm : bn) < Traits::mr\n                      ? 2.0\n                      : 0.5;\n#ifndef EIGEN_VECTORIZE_FMA\n    // Bandwidth of all of VFMA/MULPS/ADDPS is 0.5 on latest Intel processors.\n    // However for MULPS/ADDPS we have dependent sequence of 2 such\n    // instructions,\n    // so overall bandwidth is 1.0.\n    if (computeBandwidth == 0.5) computeBandwidth = 1.0;\n#endif\n    return computeBandwidth;\n  }\n\n};\n\n} // end namespace Eigen\n\n#endif  // EIGEN_USE_THREADS\n#endif // EIGEN_CXX11_TENSOR_TENSOR_CONTRACTION_THREAD_POOL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConversion.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONVERSION_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CONVERSION_H\n\nnamespace Eigen {\n\n/** \\class TensorConversionOp\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor conversion class. This class makes it possible to vectorize\n  * type casting operations when the number of scalars per packet in the source\n  * and the destination type differ\n  */\nnamespace internal {\ntemplate<typename TargetType, typename XprType>\nstruct traits<TensorConversionOp<TargetType, XprType> >\n{\n  // Type promotion to handle the case where the types of the lhs and the rhs are different.\n  typedef TargetType Scalar;\n  typedef typename traits<XprType>::StorageKind StorageKind;\n  typedef typename traits<XprType>::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = traits<XprType>::NumDimensions;\n  static const int Layout = traits<XprType>::Layout;\n  enum { Flags = 0 };\n  typedef typename TypeConversion<Scalar, typename traits<XprType>::PointerType>::type PointerType;\n};\n\ntemplate<typename TargetType, typename XprType>\nstruct eval<TensorConversionOp<TargetType, XprType>, Eigen::Dense>\n{\n  typedef const TensorConversionOp<TargetType, XprType>& type;\n};\n\ntemplate<typename TargetType, typename XprType>\nstruct nested<TensorConversionOp<TargetType, XprType>, 1, typename eval<TensorConversionOp<TargetType, XprType> >::type>\n{\n  typedef TensorConversionOp<TargetType, XprType> type;\n};\n\n}  // end namespace internal\n\n\ntemplate <typename TensorEvaluator, typename SrcPacket, typename TgtPacket, int SrcCoeffRatio, int TgtCoeffRatio>\nstruct PacketConverter;\n\ntemplate <typename TensorEvaluator, typename SrcPacket, typename TgtPacket>\nstruct PacketConverter<TensorEvaluator, SrcPacket, TgtPacket, 1, 1> {\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  PacketConverter(const TensorEvaluator& impl)\n      : m_impl(impl) {}\n\n  template<int LoadMode, typename Index>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TgtPacket packet(Index index) const {\n    return internal::pcast<SrcPacket, TgtPacket>(m_impl.template packet<LoadMode>(index));\n  }\n\n private:\n  const TensorEvaluator& m_impl;\n};\n\n\ntemplate <typename TensorEvaluator, typename SrcPacket, typename TgtPacket>\nstruct PacketConverter<TensorEvaluator, SrcPacket, TgtPacket, 2, 1> {\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  PacketConverter(const TensorEvaluator& impl)\n      : m_impl(impl) {}\n\n  template<int LoadMode, typename Index>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TgtPacket packet(Index index) const {\n    const int SrcPacketSize = internal::unpacket_traits<SrcPacket>::size;\n\n    SrcPacket src1 = m_impl.template packet<LoadMode>(index);\n    SrcPacket src2 = m_impl.template packet<LoadMode>(index + SrcPacketSize);\n    TgtPacket result = internal::pcast<SrcPacket, TgtPacket>(src1, src2);\n    return result;\n  }\n\n private:\n  const TensorEvaluator& m_impl;\n};\n\ntemplate <typename TensorEvaluator, typename SrcPacket, typename TgtPacket>\nstruct PacketConverter<TensorEvaluator, SrcPacket, TgtPacket, 4, 1> {\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  PacketConverter(const TensorEvaluator& impl)\n      : m_impl(impl) {}\n\n  template<int LoadMode, typename Index>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TgtPacket packet(Index index) const {\n    const int SrcPacketSize = internal::unpacket_traits<SrcPacket>::size;\n\n    SrcPacket src1 = m_impl.template packet<LoadMode>(index);\n    SrcPacket src2 = m_impl.template packet<LoadMode>(index + SrcPacketSize);\n    SrcPacket src3 = m_impl.template packet<LoadMode>(index + 2 * SrcPacketSize);\n    SrcPacket src4 = m_impl.template packet<LoadMode>(index + 3 * SrcPacketSize);\n    TgtPacket result = internal::pcast<SrcPacket, TgtPacket>(src1, src2, src3, src4);\n    return result;\n  }\n\n private:\n  const TensorEvaluator& m_impl;\n};\n\ntemplate <typename TensorEvaluator, typename SrcPacket, typename TgtPacket>\nstruct PacketConverter<TensorEvaluator, SrcPacket, TgtPacket, 8, 1> {\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  PacketConverter(const TensorEvaluator& impl)\n      : m_impl(impl) {}\n\n  template<int LoadMode, typename Index>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TgtPacket packet(Index index) const {\n    const int SrcPacketSize = internal::unpacket_traits<SrcPacket>::size;\n\n    SrcPacket src1 = m_impl.template packet<LoadMode>(index);\n    SrcPacket src2 = m_impl.template packet<LoadMode>(index + 1 * SrcPacketSize);\n    SrcPacket src3 = m_impl.template packet<LoadMode>(index + 2 * SrcPacketSize);\n    SrcPacket src4 = m_impl.template packet<LoadMode>(index + 3 * SrcPacketSize);\n    SrcPacket src5 = m_impl.template packet<LoadMode>(index + 4 * SrcPacketSize);\n    SrcPacket src6 = m_impl.template packet<LoadMode>(index + 5 * SrcPacketSize);\n    SrcPacket src7 = m_impl.template packet<LoadMode>(index + 6 * SrcPacketSize);\n    SrcPacket src8 = m_impl.template packet<LoadMode>(index + 7 * SrcPacketSize);\n    TgtPacket result = internal::pcast<SrcPacket, TgtPacket>(src1, src2, src3, src4, src5, src6, src7, src8);\n    return result;\n  }\n\n private:\n  const TensorEvaluator& m_impl;\n};\n\ntemplate <typename TensorEvaluator, typename SrcPacket, typename TgtPacket, int TgtCoeffRatio>\nstruct PacketConverter<TensorEvaluator, SrcPacket, TgtPacket, 1, TgtCoeffRatio> {\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  PacketConverter(const TensorEvaluator& impl)\n      : m_impl(impl), m_maxIndex(impl.dimensions().TotalSize()) {}\n\n  template<int LoadMode, typename Index>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TgtPacket packet(Index index) const {\n    const int SrcPacketSize = internal::unpacket_traits<SrcPacket>::size;\n    // Only call m_impl.packet() when we have direct access to the underlying data. This\n    // ensures that we don't compute the subexpression twice. We may however load some\n    // coefficients twice, but in practice this doesn't negatively impact performance.\n    if (m_impl.data() && (index + SrcPacketSize < m_maxIndex)) {\n      // Force unaligned memory loads since we can't ensure alignment anymore\n      return internal::pcast<SrcPacket, TgtPacket>(m_impl.template packet<Unaligned>(index));\n    } else {\n      const int TgtPacketSize = internal::unpacket_traits<TgtPacket>::size;\n      typedef typename internal::unpacket_traits<SrcPacket>::type SrcType;\n      typedef typename internal::unpacket_traits<TgtPacket>::type TgtType;\n      internal::scalar_cast_op<SrcType, TgtType> converter;\n      EIGEN_ALIGN_MAX typename internal::unpacket_traits<TgtPacket>::type values[TgtPacketSize];\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < TgtPacketSize; ++i) {\n        values[i] = converter(m_impl.coeff(index+i));\n      }\n      TgtPacket rslt = internal::pload<TgtPacket>(values);\n      return rslt;\n    }\n  }\n\n private:\n  const TensorEvaluator& m_impl;\n  const typename TensorEvaluator::Index m_maxIndex;\n};\n\ntemplate<typename TargetType, typename XprType>\nclass TensorConversionOp : public TensorBase<TensorConversionOp<TargetType, XprType>, ReadOnlyAccessors>\n{\n  public:\n    typedef typename internal::traits<TensorConversionOp>::Scalar Scalar;\n    typedef typename internal::traits<TensorConversionOp>::StorageKind StorageKind;\n    typedef typename internal::traits<TensorConversionOp>::Index Index;\n    typedef typename internal::nested<TensorConversionOp>::type Nested;\n    typedef Scalar CoeffReturnType;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorConversionOp(const XprType& xpr)\n        : m_xpr(xpr) {}\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n};\n\ntemplate <bool SameType, typename Eval, typename EvalPointerType> struct ConversionSubExprEval {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool run(Eval& impl, EvalPointerType) {\n    impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n};\n\ntemplate <typename Eval, typename EvalPointerType> struct ConversionSubExprEval<true, Eval, EvalPointerType> {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool run(Eval& impl, EvalPointerType data) {\n    return impl.evalSubExprsIfNeeded(data);\n  }\n};\n\n#ifdef EIGEN_USE_THREADS\ntemplate <bool SameType, typename Eval, typename EvalPointerType,\n          typename EvalSubExprsCallback>\nstruct ConversionSubExprEvalAsync {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(\n      Eval& impl, EvalPointerType, EvalSubExprsCallback done) {\n    impl.evalSubExprsIfNeededAsync(nullptr, std::move(done));\n  }\n};\n\ntemplate <typename Eval, typename EvalPointerType,\n          typename EvalSubExprsCallback>\nstruct ConversionSubExprEvalAsync<true, Eval, EvalPointerType,\n                                  EvalSubExprsCallback> {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(\n      Eval& impl, EvalPointerType data, EvalSubExprsCallback done) {\n    impl.evalSubExprsIfNeededAsync(data, std::move(done));\n  }\n};\n#endif\n\nnamespace internal {\n\ntemplate <typename SrcType, typename TargetType, bool IsSameT>\nstruct CoeffConv {\n  template <typename ArgType, typename Device>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TargetType run(const TensorEvaluator<ArgType, Device>& impl, Index index) {\n    internal::scalar_cast_op<SrcType, TargetType> converter;\n    return converter(impl.coeff(index));\n  }\n};\n\ntemplate <typename SrcType, typename TargetType>\nstruct CoeffConv<SrcType, TargetType, true> {\n  template <typename ArgType, typename Device>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TargetType run(const TensorEvaluator<ArgType, Device>& impl, Index index) {\n    return impl.coeff(index);\n  }\n};\n\ntemplate <typename SrcPacket, typename TargetPacket, int LoadMode, bool ActuallyVectorize, bool IsSameT>\nstruct PacketConv {\n  typedef typename internal::unpacket_traits<SrcPacket>::type SrcType;\n  typedef typename internal::unpacket_traits<TargetPacket>::type TargetType;\n\n  static const int PacketSize = internal::unpacket_traits<TargetPacket>::size;\n\n  template <typename ArgType, typename Device>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TargetPacket run(const TensorEvaluator<ArgType, Device>& impl, Index index) {\n    internal::scalar_cast_op<SrcType, TargetType> converter;\n    EIGEN_ALIGN_MAX typename internal::remove_const<TargetType>::type values[PacketSize];\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < PacketSize; ++i) {\n      values[i] = converter(impl.coeff(index+i));\n    }\n    TargetPacket rslt = internal::pload<TargetPacket>(values);\n    return rslt;\n  }\n};\n\ntemplate <typename SrcPacket, typename TargetPacket, int LoadMode, bool IsSameT>\nstruct PacketConv<SrcPacket, TargetPacket, LoadMode, true, IsSameT> {\n  typedef typename internal::unpacket_traits<SrcPacket>::type SrcType;\n  typedef typename internal::unpacket_traits<TargetPacket>::type TargetType;\n\n  template <typename ArgType, typename Device>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TargetPacket run(const TensorEvaluator<ArgType, Device>& impl, Index index) {\n    const int SrcCoeffRatio = internal::type_casting_traits<SrcType, TargetType>::SrcCoeffRatio;\n    const int TgtCoeffRatio = internal::type_casting_traits<SrcType, TargetType>::TgtCoeffRatio;\n    PacketConverter<TensorEvaluator<ArgType, Device>, SrcPacket, TargetPacket,\n                    SrcCoeffRatio, TgtCoeffRatio> converter(impl);\n    return converter.template packet<LoadMode>(index);\n  }\n};\n\ntemplate <typename SrcPacket, typename TargetPacket, int LoadMode>\nstruct PacketConv<SrcPacket, TargetPacket, LoadMode, /*ActuallyVectorize=*/false, /*IsSameT=*/true> {\n  typedef typename internal::unpacket_traits<TargetPacket>::type TargetType;\n  static const int PacketSize = internal::unpacket_traits<TargetPacket>::size;\n\n  template <typename ArgType, typename Device>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TargetPacket run(const TensorEvaluator<ArgType, Device>& impl, Index index) {\n    EIGEN_ALIGN_MAX typename internal::remove_const<TargetType>::type values[PacketSize];\n    for (int i = 0; i < PacketSize; ++i) values[i] = impl.coeff(index+i);\n    return internal::pload<TargetPacket>(values);\n  }\n};\n\ntemplate <typename SrcPacket, typename TargetPacket, int LoadMode>\nstruct PacketConv<SrcPacket, TargetPacket, LoadMode, /*ActuallyVectorize=*/true, /*IsSameT=*/true> {\n  template <typename ArgType, typename Device>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TargetPacket run(const TensorEvaluator<ArgType, Device>& impl, Index index) {\n    return impl.template packet<LoadMode>(index);\n  }\n};\n\n}  // namespace internal\n\n// Eval as rvalue\ntemplate<typename TargetType, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorConversionOp<TargetType, ArgType>, Device>\n{\n  typedef TensorConversionOp<TargetType, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  typedef typename TensorEvaluator<ArgType, Device>::Dimensions Dimensions;\n  typedef TargetType Scalar;\n  typedef TargetType CoeffReturnType;\n  typedef typename internal::remove_all<typename internal::traits<ArgType>::Scalar>::type SrcType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef typename PacketType<SrcType, Device>::type PacketSourceType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  static const bool IsSameType = internal::is_same<TargetType, SrcType>::value;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned         = false,\n    PacketAccess      =\n    #ifndef EIGEN_USE_SYCL\n                        true,\n    #else\n                        TensorEvaluator<ArgType, Device>::PacketAccess &\n                        internal::type_casting_traits<SrcType, TargetType>::VectorizedCast,\n    #endif\n    BlockAccess       = TensorEvaluator<ArgType, Device>::BlockAccess,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    RawAccess         = false\n  };\n\n  static const int NumDims = internal::array_size<Dimensions>::value;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename TensorEvaluator<const ArgType, Device>::TensorBlock\n      ArgTensorBlock;\n\n  struct TensorConversionOpBlockFactory {\n    template <typename ArgXprType>\n    struct XprType {\n      typedef TensorConversionOp<TargetType, const ArgXprType> type;\n    };\n\n    template <typename ArgXprType>\n    typename XprType<ArgXprType>::type expr(const ArgXprType& expr) const {\n      return typename XprType<ArgXprType>::type(expr);\n    }\n  };\n\n  typedef internal::TensorUnaryExprBlock<TensorConversionOpBlockFactory,\n                                         ArgTensorBlock>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n    : m_impl(op.expression(), device)\n  {\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_impl.dimensions(); }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data)\n  {\n    return ConversionSubExprEval<IsSameType, TensorEvaluator<ArgType, Device>, EvaluatorPointerType>::run(m_impl, data);\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType data, EvalSubExprsCallback done) {\n    ConversionSubExprEvalAsync<IsSameType, TensorEvaluator<ArgType, Device>,\n                               EvaluatorPointerType,\n        EvalSubExprsCallback>::run(m_impl, data, std::move(done));\n  }\n#endif\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup()\n  {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    return internal::CoeffConv<SrcType, TargetType, IsSameType>::run(m_impl,index);\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType\n  packet(Index index) const {\n    // If we are not going to do the cast, we just need to check that base\n    // TensorEvaluator has packet access. Otherwise we also need to make sure,\n    // that we have an implementation of vectorized cast.\n    const bool Vectorizable =\n        IsSameType\n        ? TensorEvaluator<ArgType, Device>::PacketAccess\n        : TensorEvaluator<ArgType, Device>::PacketAccess &\n          internal::type_casting_traits<SrcType, TargetType>::VectorizedCast;\n\n    return internal::PacketConv<PacketSourceType, PacketReturnType, LoadMode,\n                                Vectorizable, IsSameType>::run(m_impl, index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    const double cast_cost = TensorOpCost::CastCost<SrcType, TargetType>();\n    if (vectorized) {\n      const double SrcCoeffRatio =\n          internal::type_casting_traits<SrcType, TargetType>::SrcCoeffRatio;\n      const double TgtCoeffRatio =\n          internal::type_casting_traits<SrcType, TargetType>::TgtCoeffRatio;\n      return m_impl.costPerCoeff(vectorized) * (SrcCoeffRatio / PacketSize) +\n          TensorOpCost(0, 0, TgtCoeffRatio * (cast_cost / PacketSize));\n    } else {\n      return m_impl.costPerCoeff(vectorized) + TensorOpCost(0, 0, cast_cost);\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    return m_impl.getResourceRequirements();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    return TensorBlock(m_impl.block(desc, scratch),\n                         TensorConversionOpBlockFactory());\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n  /// required by sycl in order to extract the sycl accessor\n  const TensorEvaluator<ArgType, Device>& impl() const { return m_impl; }\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n\n protected:\n  TensorEvaluator<ArgType, Device> m_impl;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_CONVERSION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConvolution.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_H\n\nnamespace Eigen {\n\n/** \\class TensorConvolution\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor convolution class.\n  *\n  *\n  */\nnamespace internal {\n\ntemplate <typename Index, typename InputDims, int NumKernelDims, int Layout>\nclass IndexMapper {\n public:\n  IndexMapper(const InputDims& input_dims, const array<Index, NumKernelDims>& kernel_dims,\n              const array<Index, NumKernelDims>& indices) {\n\n    array<Index, NumDims> dimensions = input_dims;\n    for (int i = 0; i < NumKernelDims; ++i) {\n      const Index index = indices[i];\n      const Index input_dim = input_dims[index];\n      const Index kernel_dim = kernel_dims[i];\n      const Index result_dim = input_dim - kernel_dim + 1;\n      dimensions[index] = result_dim;\n    }\n\n    array<Index, NumDims> inputStrides;\n    array<Index, NumDims> outputStrides;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      inputStrides[0] = 1;\n      outputStrides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        inputStrides[i] = inputStrides[i-1] * input_dims[i-1];\n        outputStrides[i] = outputStrides[i-1] * dimensions[i-1];\n      }\n    } else {\n      inputStrides[NumDims - 1] = 1;\n      outputStrides[NumDims - 1] = 1;\n      for (int i = static_cast<int>(NumDims) - 2; i >= 0; --i) {\n        inputStrides[i] = inputStrides[i + 1] * input_dims[i + 1];\n        outputStrides[i] = outputStrides[i + 1] * dimensions[i + 1];\n      }\n    }\n\n    array<Index, NumDims> gpuInputDimensions;\n    array<Index, NumDims> gpuOutputDimensions;\n    array<Index, NumDims> tmp = dimensions;\n    array<Index, NumDims> ordering;\n    const size_t offset = static_cast<int>(Layout) == static_cast<int>(ColMajor)\n                              ? 0\n                              : NumDims - NumKernelDims;\n    for (int i = 0; i < NumKernelDims; ++i) {\n      const Index index = i + offset;\n      ordering[index] = indices[i];\n      tmp[indices[i]] = -1;\n      gpuInputDimensions[index] = input_dims[indices[i]];\n      gpuOutputDimensions[index] = dimensions[indices[i]];\n    }\n\n    int written = static_cast<int>(Layout) == static_cast<int>(ColMajor)\n                      ? NumKernelDims\n                      : 0;\n    for (int i = 0; i < NumDims; ++i) {\n      if (tmp[i] >= 0) {\n        ordering[written] = i;\n        gpuInputDimensions[written] = input_dims[i];\n        gpuOutputDimensions[written] = dimensions[i];\n        ++written;\n      }\n    }\n\n    for (int i = 0; i < NumDims; ++i) {\n      m_inputStrides[i] = inputStrides[ordering[i]];\n      m_outputStrides[i] = outputStrides[ordering[i]];\n    }\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = 0; i < NumDims; ++i) {\n        if (i > NumKernelDims) {\n          m_gpuInputStrides[i] =\n              m_gpuInputStrides[i - 1] * gpuInputDimensions[i - 1];\n          m_gpuOutputStrides[i] =\n              m_gpuOutputStrides[i - 1] * gpuOutputDimensions[i - 1];\n        } else {\n          m_gpuInputStrides[i] = 1;\n          m_gpuOutputStrides[i] = 1;\n        }\n      }\n    } else {\n      for (int i = NumDims - 1; i >= 0; --i) {\n        if (static_cast<size_t>(i + 1) < offset) {\n          m_gpuInputStrides[i] =\n              m_gpuInputStrides[i + 1] * gpuInputDimensions[i + 1];\n          m_gpuOutputStrides[i] =\n              m_gpuOutputStrides[i + 1] * gpuOutputDimensions[i + 1];\n        } else {\n          m_gpuInputStrides[i] = 1;\n          m_gpuOutputStrides[i] = 1;\n        }\n      }\n    }\n  }\n\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapGpuInputPlaneToTensorInputOffset(Index p) const {\n    Index inputIndex = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int d = NumDims - 1; d > NumKernelDims; --d) {\n        const Index idx = p / m_gpuInputStrides[d];\n        inputIndex += idx * m_inputStrides[d];\n        p -= idx * m_gpuInputStrides[d];\n      }\n      inputIndex += p * m_inputStrides[NumKernelDims];\n    } else {\n      std::ptrdiff_t limit = 0;\n      if (NumKernelDims < NumDims) {\n        limit = NumDims - NumKernelDims - 1;\n      }\n      for (int d = 0; d < limit; ++d) {\n        const Index idx = p / m_gpuInputStrides[d];\n        inputIndex += idx * m_inputStrides[d];\n        p -= idx * m_gpuInputStrides[d];\n      }\n      inputIndex += p * m_inputStrides[limit];\n    }\n    return inputIndex;\n  }\n\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapGpuOutputPlaneToTensorOutputOffset(Index p) const {\n    Index outputIndex = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int d = NumDims - 1; d > NumKernelDims; --d) {\n        const Index idx = p / m_gpuOutputStrides[d];\n        outputIndex += idx * m_outputStrides[d];\n        p -= idx * m_gpuOutputStrides[d];\n      }\n      outputIndex += p * m_outputStrides[NumKernelDims];\n    } else {\n      std::ptrdiff_t limit = 0;\n      if (NumKernelDims < NumDims) {\n        limit = NumDims - NumKernelDims - 1;\n      }\n      for (int d = 0; d < limit; ++d) {\n        const Index idx = p / m_gpuOutputStrides[d];\n        outputIndex += idx * m_outputStrides[d];\n        p -= idx * m_gpuOutputStrides[d];\n      }\n      outputIndex += p * m_outputStrides[limit];\n    }\n    return outputIndex;\n  }\n\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapGpuInputKernelToTensorInputOffset(Index i) const {\n    const size_t offset = static_cast<int>(Layout) == static_cast<int>(ColMajor)\n                              ? 0\n                              : NumDims - NumKernelDims;\n    return i * m_inputStrides[offset];\n  }\n\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapGpuOutputKernelToTensorOutputOffset(Index i) const {\n    const size_t offset = static_cast<int>(Layout) == static_cast<int>(ColMajor)\n                              ? 0\n                              : NumDims - NumKernelDims;\n    return i * m_outputStrides[offset];\n  }\n\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapGpuInputKernelToTensorInputOffset(Index i, Index j) const {\n    const size_t offset = static_cast<int>(Layout) == static_cast<int>(ColMajor)\n                              ? 0\n                              : NumDims - NumKernelDims;\n    return i * m_inputStrides[offset] + j * m_inputStrides[offset + 1];\n  }\n\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapGpuOutputKernelToTensorOutputOffset(Index i, Index j) const {\n    const size_t offset = static_cast<int>(Layout) == static_cast<int>(ColMajor)\n                              ? 0\n                              : NumDims - NumKernelDims;\n    return i * m_outputStrides[offset] + j * m_outputStrides[offset + 1];\n  }\n\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapGpuInputKernelToTensorInputOffset(Index i, Index j, Index k) const {\n    const size_t offset = static_cast<int>(Layout) == static_cast<int>(ColMajor)\n                              ? 0\n                              : NumDims - NumKernelDims;\n    return i * m_inputStrides[offset] + j * m_inputStrides[offset + 1] +\n           k * m_inputStrides[offset + 2];\n  }\n\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Index mapGpuOutputKernelToTensorOutputOffset(Index i, Index j, Index k) const {\n    const size_t offset = static_cast<int>(Layout) == static_cast<int>(ColMajor)\n                              ? 0\n                              : NumDims - NumKernelDims;\n    return i * m_outputStrides[offset] + j * m_outputStrides[offset + 1] +\n           k * m_outputStrides[offset + 2];\n  }\n\n private:\n  static const int NumDims = internal::array_size<InputDims>::value;\n  array<Index, NumDims> m_inputStrides;\n  array<Index, NumDims> m_outputStrides;\n  array<Index, NumDims> m_gpuInputStrides;\n  array<Index, NumDims> m_gpuOutputStrides;\n};\n\n\n\ntemplate<typename Dimensions, typename InputXprType, typename KernelXprType>\nstruct traits<TensorConvolutionOp<Dimensions, InputXprType, KernelXprType> >\n{\n  // Type promotion to handle the case where the types of the lhs and the rhs are different.\n  typedef typename promote_storage_type<typename InputXprType::Scalar,\n                                        typename KernelXprType::Scalar>::ret Scalar;\n  typedef typename promote_storage_type<typename traits<InputXprType>::StorageKind,\n                                        typename traits<KernelXprType>::StorageKind>::ret StorageKind;\n  typedef typename promote_index_type<typename traits<InputXprType>::Index,\n                                      typename traits<KernelXprType>::Index>::type Index;\n  typedef typename InputXprType::Nested LhsNested;\n  typedef typename KernelXprType::Nested RhsNested;\n  typedef typename remove_reference<LhsNested>::type _LhsNested;\n  typedef typename remove_reference<RhsNested>::type _RhsNested;\n  static const int NumDimensions = traits<InputXprType>::NumDimensions;\n  static const int Layout = traits<InputXprType>::Layout;\n  typedef typename conditional<Pointer_type_promotion<typename InputXprType::Scalar, Scalar>::val,\n  typename traits<InputXprType>::PointerType, typename traits<KernelXprType>::PointerType>::type PointerType;\n\n  enum {\n    Flags = 0\n  };\n};\n\ntemplate<typename Dimensions, typename InputXprType, typename KernelXprType>\nstruct eval<TensorConvolutionOp<Dimensions, InputXprType, KernelXprType>, Eigen::Dense>\n{\n  typedef const TensorConvolutionOp<Dimensions, InputXprType, KernelXprType>& type;\n};\n\ntemplate<typename Dimensions, typename InputXprType, typename KernelXprType>\nstruct nested<TensorConvolutionOp<Dimensions, InputXprType, KernelXprType>, 1, typename eval<TensorConvolutionOp<Dimensions, InputXprType, KernelXprType> >::type>\n{\n  typedef TensorConvolutionOp<Dimensions, InputXprType, KernelXprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename Indices, typename InputXprType, typename KernelXprType>\nclass TensorConvolutionOp : public TensorBase<TensorConvolutionOp<Indices, InputXprType, KernelXprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorConvolutionOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename internal::promote_storage_type<typename InputXprType::CoeffReturnType,\n                                                  typename KernelXprType::CoeffReturnType>::ret CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorConvolutionOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorConvolutionOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorConvolutionOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorConvolutionOp(const InputXprType& input, const KernelXprType& kernel, const Indices& dims)\n      : m_input_xpr(input), m_kernel_xpr(kernel), m_indices(dims) {}\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const Indices& indices() const { return m_indices; }\n\n    /** \\returns the nested expressions */\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const typename internal::remove_all<typename InputXprType::Nested>::type&\n    inputExpression() const { return m_input_xpr; }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const typename internal::remove_all<typename KernelXprType::Nested>::type&\n    kernelExpression() const { return m_kernel_xpr; }\n\n  protected:\n    typename InputXprType::Nested m_input_xpr;\n    typename KernelXprType::Nested m_kernel_xpr;\n    const Indices m_indices;\n};\n\n\ntemplate<typename Indices, typename InputArgType, typename KernelArgType, typename Device>\nstruct TensorEvaluator<const TensorConvolutionOp<Indices, InputArgType, KernelArgType>, Device>\n{\n  typedef TensorConvolutionOp<Indices, InputArgType, KernelArgType> XprType;\n\n  static const int NumDims = internal::array_size<typename TensorEvaluator<InputArgType, Device>::Dimensions>::value;\n  static const int NumKernelDims = internal::array_size<Indices>::value;\n  typedef typename XprType::Index Index;\n  typedef DSizes<Index, NumDims> Dimensions;\n\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<Scalar, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = TensorEvaluator<InputArgType, Device>::IsAligned & TensorEvaluator<KernelArgType, Device>::IsAligned,\n    PacketAccess = TensorEvaluator<InputArgType, Device>::PacketAccess & TensorEvaluator<KernelArgType, Device>::PacketAccess,\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<InputArgType, Device>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_inputImpl(op.inputExpression(), device), m_kernelImpl(op.kernelExpression(), device), m_kernelArg(op.kernelExpression()), m_kernel(NULL), m_local_kernel(false), m_device(device)\n  {\n    EIGEN_STATIC_ASSERT((static_cast<int>(TensorEvaluator<InputArgType, Device>::Layout) == static_cast<int>(TensorEvaluator<KernelArgType, Device>::Layout)), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    const typename TensorEvaluator<InputArgType, Device>::Dimensions& input_dims = m_inputImpl.dimensions();\n    const typename TensorEvaluator<KernelArgType, Device>::Dimensions& kernel_dims = m_kernelImpl.dimensions();\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_inputStride[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_inputStride[i] = m_inputStride[i - 1] * input_dims[i - 1];\n      }\n    } else {\n      m_inputStride[NumDims - 1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_inputStride[i] = m_inputStride[i + 1] * input_dims[i + 1];\n      }\n    }\n\n    m_dimensions = m_inputImpl.dimensions();\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = 0; i < NumKernelDims; ++i) {\n        const Index index = op.indices()[i];\n        const Index input_dim = input_dims[index];\n        const Index kernel_dim = kernel_dims[i];\n        const Index result_dim = input_dim - kernel_dim + 1;\n        m_dimensions[index] = result_dim;\n        if (i > 0) {\n          m_kernelStride[i] = m_kernelStride[i - 1] * kernel_dims[i - 1];\n        } else {\n          m_kernelStride[0] = 1;\n        }\n        m_indexStride[i] = m_inputStride[index];\n      }\n\n      m_outputStride[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_outputStride[i] = m_outputStride[i - 1] * m_dimensions[i - 1];\n      }\n    } else {\n      for (int i = NumKernelDims - 1; i >= 0; --i) {\n        const Index index = op.indices()[i];\n        const Index input_dim = input_dims[index];\n        const Index kernel_dim = kernel_dims[i];\n        const Index result_dim = input_dim - kernel_dim + 1;\n        m_dimensions[index] = result_dim;\n        if (i < NumKernelDims - 1) {\n          m_kernelStride[i] = m_kernelStride[i + 1] * kernel_dims[i + 1];\n        } else {\n          m_kernelStride[NumKernelDims - 1] = 1;\n        }\n        m_indexStride[i] = m_inputStride[index];\n      }\n\n      m_outputStride[NumDims - 1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_outputStride[i] = m_outputStride[i + 1] * m_dimensions[i + 1];\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar*) {\n    m_inputImpl.evalSubExprsIfNeeded(NULL);\n    preloadKernel();\n    return true;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_inputImpl.cleanup();\n    if (m_local_kernel) {\n      m_device.deallocate((void*)m_kernel);\n      m_local_kernel = false;\n    }\n    m_kernel = NULL;\n  }\n\n  void evalTo(typename XprType::Scalar* buffer) {\n    evalSubExprsIfNeeded(NULL);\n    for (int i = 0; i < dimensions().TotalSize(); ++i) {\n      buffer[i] += coeff(i);\n    }\n    cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    CoeffReturnType result = CoeffReturnType(0);\n    convolve(firstInput(index), 0, NumKernelDims-1, result);\n    return result;\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC PacketReturnType packet(const Index index) const\n  {\n    Index indices[2] = {index, index+PacketSize-1};\n    Index startInputs[2] = {0, 0};\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx0 = indices[0] / m_outputStride[i];\n        const Index idx1 = indices[1] / m_outputStride[i];\n        startInputs[0] += idx0 * m_inputStride[i];\n        startInputs[1] += idx1 * m_inputStride[i];\n        indices[0] -= idx0 * m_outputStride[i];\n        indices[1] -= idx1 * m_outputStride[i];\n      }\n    } else {\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx0 = indices[0] / m_outputStride[i];\n        const Index idx1 = indices[1] / m_outputStride[i];\n        startInputs[0] += idx0 * m_inputStride[i];\n        startInputs[1] += idx1 * m_inputStride[i];\n        indices[0] -= idx0 * m_outputStride[i];\n        indices[1] -= idx1 * m_outputStride[i];\n      }\n    }\n    startInputs[0] += indices[0];\n    startInputs[1] += indices[1];\n\n    if (startInputs[1]-startInputs[0] == PacketSize-1) {\n      PacketReturnType result = internal::pset1<PacketReturnType>(0);\n      convolvePacket(startInputs[0], 0, NumKernelDims-1, result);\n      return result;\n    } else {\n      EIGEN_ALIGN_MAX Scalar data[PacketSize];\n      data[0] = Scalar(0);\n      convolve(startInputs[0], 0, NumKernelDims-1, data[0]);\n      for (int i = 1; i < PacketSize-1; ++i) {\n        data[i] = Scalar(0);\n        convolve(firstInput(index+i), 0, NumKernelDims-1, data[i]);\n      }\n      data[PacketSize-1] = Scalar(0);\n      convolve(startInputs[1], 0, NumKernelDims-1, data[PacketSize-1]);\n      return internal::pload<PacketReturnType>(data);\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    const double kernel_size = m_kernelImpl.dimensions().TotalSize();\n    // We ignore the use of fused multiply-add.\n    const double convolve_compute_cost =\n        TensorOpCost::AddCost<Scalar>() + TensorOpCost::MulCost<Scalar>();\n    const double firstIndex_compute_cost =\n        NumDims *\n        (2 * TensorOpCost::AddCost<Index>() + 2 * TensorOpCost::MulCost<Index>() +\n         TensorOpCost::DivCost<Index>());\n    return TensorOpCost(0, 0, firstIndex_compute_cost, vectorized, PacketSize) +\n           kernel_size * (m_inputImpl.costPerCoeff(vectorized) +\n                          m_kernelImpl.costPerCoeff(vectorized) +\n                          TensorOpCost(0, 0, convolve_compute_cost, vectorized,\n                                       PacketSize));\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n private:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index firstInput(Index index) const {\n    Index startInput = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx = index / m_outputStride[i];\n        startInput += idx * m_inputStride[i];\n        index -= idx * m_outputStride[i];\n      }\n    } else {\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx = index / m_outputStride[i];\n        startInput += idx * m_inputStride[i];\n        index -= idx * m_outputStride[i];\n      }\n    }\n    startInput += index;\n    return startInput;\n  }\n\n  EIGEN_DEVICE_FUNC void convolve(Index firstIndex, Index firstKernel, int DimIndex, CoeffReturnType& accum) const {\n    for (int j = 0; j < m_kernelImpl.dimensions()[DimIndex]; ++j) {\n      const Index input = firstIndex + j * m_indexStride[DimIndex];\n      const Index kernel = firstKernel + j * m_kernelStride[DimIndex];\n      if (DimIndex > 0) {\n        convolve(input, kernel, DimIndex-1, accum);\n      } else {\n        accum += m_inputImpl.coeff(input) * m_kernel[kernel];\n      }\n    }\n  }\n\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC void convolvePacket(Index firstIndex, Index firstKernel, int DimIndex, Packet& accum) const {\n    for (int j = 0; j < m_kernelImpl.dimensions()[DimIndex]; ++j) {\n      const Index input = firstIndex + j * m_indexStride[DimIndex];\n      const Index kernel = firstKernel + j * m_kernelStride[DimIndex];\n      if (DimIndex > 0) {\n        convolvePacket(input, kernel, DimIndex-1, accum);\n      } else {\n        accum = internal::pmadd<Packet>(m_inputImpl.template packet<Unaligned>(input), internal::pset1<Packet>(m_kernel[kernel]), accum);\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void preloadKernel() {\n    // Don't make a local copy of the kernel unless we have to (i.e. it's an\n    // expression that needs to be evaluated)\n    const Scalar* in_place = m_kernelImpl.data();\n    if (in_place) {\n      m_kernel = in_place;\n      m_local_kernel = false;\n    } else {\n      size_t kernel_sz = m_kernelImpl.dimensions().TotalSize() * sizeof(Scalar);\n      Scalar* local = (Scalar*)m_device.allocate_temp(kernel_sz);\n      typedef TensorEvalToOp<const KernelArgType> EvalTo;\n      EvalTo evalToTmp(local, m_kernelArg);\n      const bool Vectorize = internal::IsVectorizable<Device, KernelArgType>::value;\n      internal::TensorExecutor<const EvalTo, Device, Vectorize>::run(evalToTmp, m_device);\n\n      m_kernel = local;\n      m_local_kernel = true;\n    }\n  }\n\n  array<Index, NumDims> m_inputStride;\n  array<Index, NumDims> m_outputStride;\n\n  array<Index, NumKernelDims> m_indexStride;\n  array<Index, NumKernelDims> m_kernelStride;\n  TensorEvaluator<InputArgType, Device> m_inputImpl;\n  TensorEvaluator<KernelArgType, Device> m_kernelImpl;\n  Dimensions m_dimensions;\n\n  KernelArgType m_kernelArg;\n  const Scalar* m_kernel;\n  bool m_local_kernel;\n  const Device EIGEN_DEVICE_REF m_device;\n};\n\n\n\n\n// Use an optimized implementation of the evaluation code for GPUs whenever possible.\n#if defined(EIGEN_USE_GPU) && defined(EIGEN_GPUCC)\n\ntemplate <int StaticKernelSize>\nstruct GetKernelSize {\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int operator() (const int /*kernelSize*/) const {\n    return StaticKernelSize;\n  }\n};\ntemplate <>\nstruct GetKernelSize<Dynamic> {\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int operator() (const int kernelSize) const {\n    return kernelSize;\n  }\n};\n\ntemplate <typename InputEvaluator, typename Index, typename InputDims,\n          int StaticKernelSize>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void EigenConvolutionKernel1D(\n    InputEvaluator eval,\n    const internal::IndexMapper<Index, InputDims, 1, InputEvaluator::Layout>\n        indexMapper,\n    const float* __restrict kernel, const int numPlanes, const int numX,\n    const int maxX, const int kernelSize, float* buffer) {\n#if defined(EIGEN_HIPCC)\n  HIP_DYNAMIC_SHARED(float, s)\n#else\n  extern __shared__ float s[];\n#endif\n\n  const int first_x = blockIdx.x * maxX;\n  const int last_x = (first_x + maxX < numX ? first_x + maxX : numX) - 1;\n  const int num_x_input = last_x - first_x + GetKernelSize<StaticKernelSize>()(kernelSize);\n  const int num_x_output = last_x - first_x + 1;\n\n  const int first_plane = blockIdx.y * blockDim.y;\n  const int plane_stride = blockDim.y * gridDim.y;\n\n  for (int p = first_plane + threadIdx.y; p < numPlanes; p += plane_stride) {\n    // Load inputs to shared memory\n    const int plane_input_offset = indexMapper.mapGpuInputPlaneToTensorInputOffset(p);\n    const int plane_kernel_offset = threadIdx.y * num_x_input;\n    #pragma unroll\n    for (int i = threadIdx.x; i < num_x_input; i += blockDim.x) {\n      const int tensor_index = plane_input_offset + indexMapper.mapGpuInputKernelToTensorInputOffset(i+first_x);\n      s[i + plane_kernel_offset] = eval.coeff(tensor_index);\n    }\n\n    __syncthreads();\n\n    // Compute the convolution\n    const int plane_output_offset = indexMapper.mapGpuOutputPlaneToTensorOutputOffset(p);\n\n    #pragma unroll\n    for (int i = threadIdx.x; i < num_x_output; i += blockDim.x) {\n      const int kernel_offset = plane_kernel_offset + i;\n      float result = 0.0f;\n      #pragma unroll\n      for (int k = 0; k < GetKernelSize<StaticKernelSize>()(kernelSize); ++k) {\n        result += s[k + kernel_offset] * kernel[k];\n      }\n      const int tensor_index = plane_output_offset + indexMapper.mapGpuOutputKernelToTensorOutputOffset(i+first_x);\n      buffer[tensor_index] = result;\n    }\n    __syncthreads();\n  }\n};\n\ntemplate <typename InputEvaluator, typename Index, typename InputDims,\n          int StaticKernelSizeX, int StaticKernelSizeY>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void EigenConvolutionKernel2D(\n    InputEvaluator eval,\n    const internal::IndexMapper<Index, InputDims, 2, InputEvaluator::Layout>\n        indexMapper,\n    const float* __restrict kernel, const int numPlanes, const int numX,\n    const int maxX, const int numY, const int maxY, const int kernelSizeX,\n    const int kernelSizeY, float* buffer) {\n#if defined(EIGEN_HIPCC)\n  HIP_DYNAMIC_SHARED(float, s)\n#else\n  extern __shared__ float s[];\n#endif\n\n  const int first_x = blockIdx.x * maxX;\n  const int last_x = (first_x + maxX < numX ? first_x + maxX : numX) - 1;\n  const int num_x_input = last_x - first_x + GetKernelSize<StaticKernelSizeX>()(kernelSizeX);\n  const int num_x_output = last_x - first_x + 1;\n\n  const int first_y = blockIdx.y * maxY;\n  const int last_y = (first_y + maxY < numY ? first_y + maxY : numY) - 1;\n  const int num_y_input = last_y - first_y + GetKernelSize<StaticKernelSizeY>()(kernelSizeY);\n  const int num_y_output = last_y - first_y + 1;\n\n  const int first_plane = blockIdx.z * blockDim.z;\n  const int plane_stride = blockDim.z * gridDim.z;\n\n  for (int p = first_plane + threadIdx.z; p < numPlanes; p += plane_stride) {\n\n    const int plane_input_offset = indexMapper.mapGpuInputPlaneToTensorInputOffset(p);\n    const int plane_kernel_offset = threadIdx.z * num_y_input;\n\n    // Load inputs to shared memory\n    #pragma unroll\n    for (int j = threadIdx.y; j < num_y_input; j += blockDim.y) {\n      const int input_offset = num_x_input * (j + plane_kernel_offset);\n      #pragma unroll\n      for (int i = threadIdx.x; i < num_x_input; i += blockDim.x) {\n        const int tensor_index = plane_input_offset + indexMapper.mapGpuInputKernelToTensorInputOffset(i+first_x, j+first_y);\n        s[i + input_offset] = eval.coeff(tensor_index);\n      }\n    }\n\n    __syncthreads();\n\n    // Convolution\n    const int plane_output_offset = indexMapper.mapGpuOutputPlaneToTensorOutputOffset(p);\n\n    #pragma unroll\n    for (int j = threadIdx.y; j < num_y_output; j += blockDim.y) {\n      #pragma unroll\n      for (int i = threadIdx.x; i < num_x_output; i += blockDim.x) {\n        float result = 0.0f;\n        #pragma unroll\n        for (int l = 0; l < GetKernelSize<StaticKernelSizeY>()(kernelSizeY); ++l) {\n          const int kernel_offset = kernelSizeX * l;\n          const int input_offset = i + num_x_input * (j + l + plane_kernel_offset);\n          #pragma unroll\n          for (int k = 0; k < GetKernelSize<StaticKernelSizeX>()(kernelSizeX); ++k) {\n            result += s[k + input_offset] * kernel[k + kernel_offset];\n          }\n        }\n        const int tensor_index = plane_output_offset + indexMapper.mapGpuOutputKernelToTensorOutputOffset(i+first_x, j+first_y);\n        buffer[tensor_index] = result;\n      }\n    }\n\n    __syncthreads();\n  }\n};\n\ntemplate <typename InputEvaluator, typename Index, typename InputDims>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void EigenConvolutionKernel3D(\n    InputEvaluator eval,\n    const internal::IndexMapper<Index, InputDims, 3, InputEvaluator::Layout>\n        indexMapper,\n    const float* __restrict kernel, const size_t numPlanes, const size_t numX,\n    const size_t maxX, const size_t numY, const size_t maxY, const size_t numZ,\n    const size_t maxZ, const size_t kernelSizeX, const size_t kernelSizeY,\n    const size_t kernelSizeZ, float* buffer) {\n#if defined(EIGEN_HIPCC)\n  HIP_DYNAMIC_SHARED(float, s)\n#else\n  extern __shared__ float s[];\n#endif\n\n  // Load inputs to shared memory\n  const int first_x = blockIdx.x * maxX;\n  const int last_x = (first_x + maxX < numX ? first_x + maxX : numX) - 1;\n  const int num_x_input = last_x - first_x + kernelSizeX;\n\n  const int first_y = blockIdx.y * maxY;\n  const int last_y = (first_y + maxY < numY ? first_y + maxY : numY) - 1;\n  const int num_y_input = last_y - first_y + kernelSizeY;\n\n  const int first_z = blockIdx.z * maxZ;\n  const int last_z = (first_z + maxZ < numZ ? first_z + maxZ : numZ) - 1;\n  const int num_z_input = last_z - first_z + kernelSizeZ;\n\n  for (int p = 0; p < numPlanes; ++p) {\n\n    const int plane_input_offset = indexMapper.mapGpuInputPlaneToTensorInputOffset(p);\n    const int plane_kernel_offset = 0;\n\n    for (int k = threadIdx.z; k < num_z_input; k += blockDim.z) {\n      for (int j = threadIdx.y; j < num_y_input; j += blockDim.y) {\n        for (int i = threadIdx.x; i < num_x_input; i += blockDim.x) {\n          const int tensor_index = plane_input_offset + indexMapper.mapGpuInputKernelToTensorInputOffset(i+first_x, j+first_y, k+first_z);\n          s[i + num_x_input * (j + num_y_input * (k + plane_kernel_offset))] = eval.coeff(tensor_index);\n        }\n      }\n    }\n\n    __syncthreads();\n\n    // Convolution\n    const int num_z_output = last_z - first_z + 1;\n    const int num_y_output = last_y - first_y + 1;\n    const int num_x_output = last_x - first_x + 1;\n    const int plane_output_offset = indexMapper.mapGpuOutputPlaneToTensorOutputOffset(p);\n\n    for (int k = threadIdx.z; k < num_z_output; k += blockDim.z) {\n      for (int j = threadIdx.y; j < num_y_output; j += blockDim.y) {\n        for (int i = threadIdx.x; i < num_x_output; i += blockDim.x) {\n          float result = 0.0f;\n          for (int n = 0; n < kernelSizeZ; ++n) {\n            for (int m = 0; m < kernelSizeY; ++m) {\n              for (int l = 0; l < kernelSizeX; ++l) {\n                result += s[i + l + num_x_input * (j + m + num_y_input * (k + n + plane_kernel_offset))] * kernel[l + kernelSizeX * (m + kernelSizeY * n)];\n              }\n            }\n          }\n          const int tensor_index = plane_output_offset + indexMapper.mapGpuOutputKernelToTensorOutputOffset(i+first_x, j+first_y, k+first_z);\n          buffer[tensor_index] = result;\n        }\n      }\n    }\n    __syncthreads();\n  }\n};\n\n\n\ntemplate<typename Indices, typename InputArgType, typename KernelArgType>\nstruct TensorEvaluator<const TensorConvolutionOp<Indices, InputArgType, KernelArgType>, GpuDevice>\n{\n  typedef TensorConvolutionOp<Indices, InputArgType, KernelArgType> XprType;\n\n  static const int NumDims =  internal::array_size<typename TensorEvaluator<InputArgType, GpuDevice>::Dimensions>::value;\n  static const int NumKernelDims = internal::array_size<Indices>::value;\n  typedef typename XprType::Index Index;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename TensorEvaluator<KernelArgType, GpuDevice>::Dimensions KernelDimensions;\n\n  enum {\n    IsAligned = TensorEvaluator<InputArgType, GpuDevice>::IsAligned & TensorEvaluator<KernelArgType, GpuDevice>::IsAligned,\n    PacketAccess = false,\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<InputArgType, GpuDevice>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const GpuDevice& device)\n      : m_inputImpl(op.inputExpression(), device), m_kernelImpl(op.kernelExpression(), device), m_kernelArg(op.kernelExpression()), m_indices(op.indices()), m_buf(NULL), m_kernel(NULL), m_local_kernel(false), m_device(device)\n  {\n    EIGEN_STATIC_ASSERT((static_cast<int>(TensorEvaluator<InputArgType, GpuDevice>::Layout) == static_cast<int>(TensorEvaluator<KernelArgType, GpuDevice>::Layout)), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    const typename TensorEvaluator<InputArgType, GpuDevice>::Dimensions& input_dims = m_inputImpl.dimensions();\n    const typename TensorEvaluator<KernelArgType, GpuDevice>::Dimensions& kernel_dims = m_kernelImpl.dimensions();\n\n    m_dimensions = m_inputImpl.dimensions();\n    for (int i = 0; i < NumKernelDims; ++i) {\n      const Index index = op.indices()[i];\n      const Index input_dim = input_dims[index];\n      const Index kernel_dim = kernel_dims[i];\n      const Index result_dim = input_dim - kernel_dim + 1;\n      m_dimensions[index] = result_dim;\n    }\n  }\n\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, GpuDevice>::type PacketReturnType;\n  typedef typename InputArgType::Scalar Scalar;\n  static const int PacketSize = internal::unpacket_traits<PacketReturnType>::size;\n\n  EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(Scalar* data) {\n    preloadKernel();\n    m_inputImpl.evalSubExprsIfNeeded(NULL);\n    if (data) {\n      executeEval(data);\n      return false;\n    } else {\n      m_buf = (Scalar*)m_device.allocate(dimensions().TotalSize() * sizeof(Scalar));\n      executeEval(m_buf);\n      return true;\n    }\n  }\n\n  EIGEN_STRONG_INLINE void cleanup() {\n    m_inputImpl.cleanup();\n    if (m_buf) {\n      m_device.deallocate(m_buf);\n      m_buf = NULL;\n    }\n    if (m_local_kernel) {\n      m_device.deallocate((void*)m_kernel);\n      m_local_kernel = false;\n    }\n    m_kernel = NULL;\n  }\n\n  EIGEN_STRONG_INLINE void preloadKernel() {\n    // Don't make a local copy of the kernel unless we have to (i.e. it's an\n    // expression that needs to be evaluated)\n    const Scalar* in_place = m_kernelImpl.data();\n    if (in_place) {\n      m_kernel = in_place;\n      m_local_kernel = false;\n    } else {\n      size_t kernel_sz = m_kernelImpl.dimensions().TotalSize() * sizeof(Scalar);\n      Scalar* local = (Scalar*)m_device.allocate(kernel_sz);\n      typedef TensorEvalToOp<const KernelArgType> EvalTo;\n      EvalTo evalToTmp(local, m_kernelArg);\n      const bool PacketAccess = internal::IsVectorizable<GpuDevice, KernelArgType>::value;\n      internal::TensorExecutor<const EvalTo, GpuDevice, PacketAccess>::run(evalToTmp, m_device);\n\n      m_kernel = local;\n      m_local_kernel = true;\n    }\n  }\n\n  static unsigned int ceil(unsigned int num, unsigned int denom) {\n    const unsigned int rounded_toward_zero = num / denom;\n    if (num > rounded_toward_zero * denom) {\n      return rounded_toward_zero + 1;\n    }\n    return rounded_toward_zero;\n  }\n\n  void executeEval(Scalar* data) const {\n    typedef typename TensorEvaluator<InputArgType, GpuDevice>::Dimensions InputDims;\n\n    const int maxSharedMem = m_device.sharedMemPerBlock();\n    const int maxThreadsPerBlock = m_device.maxGpuThreadsPerBlock();\n    const int maxBlocksPerProcessor = m_device.maxGpuThreadsPerMultiProcessor() / maxThreadsPerBlock;\n    const int numMultiProcessors = m_device.getNumGpuMultiProcessors();\n    const int warpSize = 32;\n\n    switch (NumKernelDims) {\n      case 1: {\n        const int kernel_size = m_kernelImpl.dimensions().TotalSize();\n\n        const int numX = dimensions()[m_indices[0]];\n        const int numP = dimensions().TotalSize() / numX;\n        int maxX;\n        dim3 block_size;\n\n        const int single_stride_dim =\n            static_cast<int>(Layout) == static_cast<int>(ColMajor)\n                ? 0\n                : m_inputImpl.dimensions().rank() - 1;\n        if (m_indices[0] == single_stride_dim) {\n          // Maximum the reuse\n          const int inner_dim = ((maxSharedMem / (sizeof(Scalar)) - kernel_size + 1 + 31) / 32) * 32;\n          maxX = numext::mini<int>(inner_dim, numX);\n          const int maxP = numext::mini<int>(maxSharedMem / ((kernel_size - 1 + maxX) * sizeof(Scalar)), numP);\n          block_size.x = numext::mini(maxThreadsPerBlock, maxX);\n          block_size.y = numext::mini<int>(maxThreadsPerBlock / block_size.x, maxP);\n        }\n        else {\n          // Read as much as possible alongside the inner most dimension, that is the plane\n          const int inner_dim = maxSharedMem / ((warpSize + kernel_size) * sizeof(Scalar));\n          const int maxP = numext::mini<int>(inner_dim, numP);\n          maxX = numext::mini<int>(maxSharedMem / (inner_dim * sizeof(Scalar)) - kernel_size + 1, numX);\n\n          block_size.x = numext::mini(warpSize, maxX);\n          block_size.y = numext::mini<int>(maxThreadsPerBlock/block_size.x, maxP);\n        }\n\n        const int shared_mem = block_size.y * (maxX + kernel_size - 1) * sizeof(Scalar);\n        gpu_assert(shared_mem <= maxSharedMem);\n\n        const int num_x_blocks = ceil(numX, maxX);\n        const int blocksPerProcessor = numext::mini(maxBlocksPerProcessor, maxSharedMem / shared_mem);\n        const int num_y_blocks = ceil(numMultiProcessors * blocksPerProcessor, num_x_blocks);\n\n        dim3 num_blocks(num_x_blocks, numext::mini<int>(num_y_blocks, ceil(numP, block_size.y)));\n\n\n        //cout << \"launching 1D kernel with block_size.x: \" << block_size.x << \" block_size.y: \" << block_size.y << \" num_blocks.x: \" << num_blocks.x << \" num_blocks.y: \" << num_blocks.y << \" maxX: \" << maxX << \" shared_mem: \" << shared_mem << \" in stream \" << m_device.stream() << endl;\n\n        const array<Index, 1> indices(m_indices[0]);\n        const array<Index, 1> kernel_dims(m_kernelImpl.dimensions()[0]);\n        internal::IndexMapper<Index, InputDims, 1, Layout> indexMapper(\n            m_inputImpl.dimensions(), kernel_dims, indices);\n        switch(kernel_size) {\n          case 4: {\n            LAUNCH_GPU_KERNEL((EigenConvolutionKernel1D<TensorEvaluator<InputArgType, GpuDevice>, Index, InputDims, 4>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, 4, data);\n            break;\n          }\n          case 7: {\n            LAUNCH_GPU_KERNEL((EigenConvolutionKernel1D<TensorEvaluator<InputArgType, GpuDevice>, Index, InputDims, 7>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, 7, data);\n            break;\n          }\n          default: {\n            LAUNCH_GPU_KERNEL((EigenConvolutionKernel1D<TensorEvaluator<InputArgType, GpuDevice>, Index, InputDims, Dynamic>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, kernel_size, data);\n          }\n        }\n        break;\n      }\n\n      case 2: {\n        const int idxX =\n            static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 0 : 1;\n        const int idxY =\n            static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 1 : 0;\n        const int kernel_size_x = m_kernelImpl.dimensions()[idxX];\n        const int kernel_size_y = m_kernelImpl.dimensions()[idxY];\n\n        const int numX = dimensions()[m_indices[idxX]];\n        const int numY = dimensions()[m_indices[idxY]];\n        const int numP = dimensions().TotalSize() / (numX*numY);\n\n        const float scaling_factor = sqrtf(static_cast<float>(maxSharedMem) / (sizeof(Scalar) * kernel_size_y * kernel_size_x));\n\n        // Snap maxX to warp size\n        int inner_dim = ((static_cast<int>(scaling_factor * kernel_size_x) - kernel_size_x + 1 + 32) / 32) * 32;\n        const int maxX = numext::mini<int>(inner_dim, numX);\n        const int maxY = numext::mini<int>(maxSharedMem / (sizeof(Scalar) * (maxX + kernel_size_x - 1)) - kernel_size_y + 1, numY);\n        const int maxP = numext::mini<int>(maxSharedMem / ((kernel_size_x - 1 + maxX) * (kernel_size_y - 1 + maxY) * sizeof(Scalar)), numP);\n\n        dim3 block_size;\n        block_size.x = numext::mini(1024, maxX);\n        block_size.y = numext::mini<int>(1024/block_size.x, maxY);\n        block_size.z = numext::mini<int>(1024/(block_size.x*block_size.y), maxP);\n\n        const int shared_mem = block_size.z * (maxX + kernel_size_x - 1) * (maxY + kernel_size_y - 1) * sizeof(Scalar);\n        gpu_assert(shared_mem <= maxSharedMem);\n\n        const int num_x_blocks = ceil(numX, maxX);\n        const int num_y_blocks = ceil(numY, maxY);\n        const int blocksPerProcessor = numext::mini(maxBlocksPerProcessor, maxSharedMem / shared_mem);\n        const int num_z_blocks = ceil(numMultiProcessors * blocksPerProcessor, num_x_blocks * num_y_blocks);\n\n        dim3 num_blocks(num_x_blocks, num_y_blocks, numext::mini<int>(num_z_blocks, ceil(numP, block_size.z)));\n\n\n        //cout << \"launching 2D kernel with block_size.x: \" << block_size.x << \" block_size.y: \" << block_size.y  << \" block_size.z: \" << block_size.z << \" num_blocks.x: \" << num_blocks.x << \" num_blocks.y: \" << num_blocks.y << \" num_blocks.z: \" << num_blocks.z << \" maxX: \" << maxX << \" maxY: \" << maxY << \" maxP: \" << maxP << \" shared_mem: \" << shared_mem << \" in stream \" << m_device.stream() << endl;\n\n        const array<Index, 2> indices(m_indices[idxX], m_indices[idxY]);\n        const array<Index, 2> kernel_dims(m_kernelImpl.dimensions()[idxX],\n                                          m_kernelImpl.dimensions()[idxY]);\n        internal::IndexMapper<Index, InputDims, 2, Layout> indexMapper(\n            m_inputImpl.dimensions(), kernel_dims, indices);\n        switch (kernel_size_x) {\n          case 4: {\n            switch (kernel_size_y) {\n              case 7: {\n                LAUNCH_GPU_KERNEL((EigenConvolutionKernel2D<TensorEvaluator<InputArgType, GpuDevice>, Index, InputDims, 4, 7>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, 4, 7, data);\n                break;\n              }\n              default: {\n                LAUNCH_GPU_KERNEL((EigenConvolutionKernel2D<TensorEvaluator<InputArgType, GpuDevice>, Index, InputDims, 4, Dynamic>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, 4, kernel_size_y, data);\n                break;\n              }\n            }\n            break;\n          }\n          case 7: {\n            switch (kernel_size_y) {\n              case 4: {\n                LAUNCH_GPU_KERNEL((EigenConvolutionKernel2D<TensorEvaluator<InputArgType, GpuDevice>, Index, InputDims, 7, 4>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, 7, 4, data);\n                break;\n              }\n              default: {\n                LAUNCH_GPU_KERNEL((EigenConvolutionKernel2D<TensorEvaluator<InputArgType, GpuDevice>, Index, InputDims, 7, Dynamic>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, 7, kernel_size_y, data);\n                break;\n              }\n            }\n            break;\n          }\n          default: {\n            LAUNCH_GPU_KERNEL((EigenConvolutionKernel2D<TensorEvaluator<InputArgType, GpuDevice>, Index, InputDims, Dynamic, Dynamic>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, kernel_size_x, kernel_size_y, data);\n            break;\n          }\n        }\n        break;\n      }\n\n      case 3: {\n        const int idxX =\n            static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 0 : 2;\n        const int idxY =\n            static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 1 : 1;\n        const int idxZ =\n            static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 2 : 0;\n\n        const int kernel_size_x = m_kernelImpl.dimensions()[idxX];\n        const int kernel_size_y = m_kernelImpl.dimensions()[idxY];\n        const int kernel_size_z = m_kernelImpl.dimensions()[idxZ];\n\n        const int numX = dimensions()[m_indices[idxX]];\n        const int numY = dimensions()[m_indices[idxY]];\n        const int numZ = dimensions()[m_indices[idxZ]];\n        const int numP = dimensions().TotalSize() / (numX*numY*numZ);\n\n        const int maxX = numext::mini<int>(128, numext::mini<int>(maxSharedMem / (sizeof(Scalar) * kernel_size_y * kernel_size_z) - kernel_size_x + 1, numX));\n        const int maxY = numext::mini<int>(128, numext::mini<int>(maxSharedMem / (sizeof(Scalar) * (maxX + kernel_size_x - 1) * kernel_size_z) - kernel_size_y + 1, numY));\n        const int maxZ = numext::mini<int>(128, numext::mini<int>(maxSharedMem / (sizeof(Scalar) * (maxX + kernel_size_x - 1) * (maxY + kernel_size_y - 1)) - kernel_size_z + 1, numZ));\n\n        dim3 block_size;\n        block_size.x = numext::mini(32, maxX);\n        block_size.y = numext::mini(32, maxY);\n        block_size.z = numext::mini<int>(1024/(block_size.x*block_size.y), maxZ);\n        dim3 num_blocks(ceil(numX, maxX), ceil(numY, maxY), ceil(numZ, maxZ));\n\n        const int shared_mem = (maxX + kernel_size_x - 1) * (maxY + kernel_size_y - 1) * (maxZ + kernel_size_z - 1) * sizeof(Scalar);\n        gpu_assert(shared_mem <= maxSharedMem);\n\n        //cout << \"launching 3D kernel with block_size.x: \" << block_size.x << \" block_size.y: \" << block_size.y  << \" block_size.z: \" << block_size.z << \" num_blocks.x: \" << num_blocks.x << \" num_blocks.y: \" << num_blocks.y << \" num_blocks.z: \" << num_blocks.z  << \" shared_mem: \" << shared_mem << \" in stream \" << m_device.stream() << endl;\n        const array<Index, 3> indices(m_indices[idxX], m_indices[idxY],\n                                      m_indices[idxZ]);\n        const array<Index, 3> kernel_dims(m_kernelImpl.dimensions()[idxX],\n                                          m_kernelImpl.dimensions()[idxY],\n                                          m_kernelImpl.dimensions()[idxZ]);\n        internal::IndexMapper<Index, InputDims, 3, Layout> indexMapper(\n            m_inputImpl.dimensions(), kernel_dims, indices);\n\n        LAUNCH_GPU_KERNEL((EigenConvolutionKernel3D<TensorEvaluator<InputArgType, GpuDevice>, Index, InputDims>), num_blocks, block_size, shared_mem, m_device, m_inputImpl, indexMapper, m_kernel, numP, numX, maxX, numY, maxY, numZ, maxZ, kernel_size_x, kernel_size_y, kernel_size_z, data);\n        break;\n      }\n\n      default: {\n        EIGEN_STATIC_ASSERT((NumKernelDims >= 1 && NumKernelDims <= 3), THIS_METHOD_IS_ONLY_FOR_OBJECTS_OF_A_SPECIFIC_SIZE);\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    eigen_assert(m_buf);\n    eigen_assert(index < m_dimensions.TotalSize());\n    return m_buf[index];\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(const Index index) const\n  {\n    eigen_assert(m_buf);\n    eigen_assert(index < m_dimensions.TotalSize());\n    return internal::ploadt<PacketReturnType, LoadMode>(m_buf+index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    // TODO(rmlarsen): FIXME: For now, this is just a copy of the CPU cost\n    // model.\n    const double kernel_size = m_kernelImpl.dimensions().TotalSize();\n    // We ignore the use of fused multiply-add.\n    const double convolve_compute_cost =\n        TensorOpCost::AddCost<Scalar>() + TensorOpCost::MulCost<Scalar>();\n    const double firstIndex_compute_cost =\n        NumDims *\n        (2 * TensorOpCost::AddCost<Index>() + 2 * TensorOpCost::MulCost<Index>() +\n         TensorOpCost::DivCost<Index>());\n    return TensorOpCost(0, 0, firstIndex_compute_cost, vectorized, PacketSize) +\n           kernel_size * (m_inputImpl.costPerCoeff(vectorized) +\n                          m_kernelImpl.costPerCoeff(vectorized) +\n                          TensorOpCost(0, 0, convolve_compute_cost, vectorized,\n                                       PacketSize));\n  }\n\n private:\n  // No assignment (copies are needed by the kernels)\n  TensorEvaluator& operator = (const TensorEvaluator&);\n\n  TensorEvaluator<InputArgType, GpuDevice> m_inputImpl;\n  TensorEvaluator<KernelArgType, GpuDevice> m_kernelImpl;\n  KernelArgType m_kernelArg;\n  Indices m_indices;\n  Dimensions m_dimensions;\n  Scalar* m_buf;\n  const Scalar* m_kernel;\n  bool m_local_kernel;\n\n  const GpuDevice& m_device;\n};\n#endif\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorConvolutionSycl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_SYCL_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_SYCL_H\n\nnamespace Eigen {\n\n/** \\class TensorConvolution\n * \\ingroup CXX11_Tensor_Module\n *\n * \\brief Tensor convolution class.\n *\n *\n */\n\nenum class convolution_type { CONV1D, CONV2D, CONV3D };\ntemplate <typename Evaluator, typename CoeffReturnType, typename KernelType, typename Index, typename InputDims,\n          typename Kernel_accessor, typename Buffer_accessor, convolution_type Conv_Dim>\nstruct EigenConvolutionKernel;\ntemplate <typename Evaluator, typename CoeffReturnType, typename KernelType, typename Index, typename InputDims,\n          typename Kernel_accessor, typename Buffer_accessor>\nstruct EigenConvolutionKernel<Evaluator, CoeffReturnType, KernelType, Index, InputDims, Kernel_accessor,\n                              Buffer_accessor, convolution_type::CONV1D> {\n  typedef cl::sycl::accessor<CoeffReturnType, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local>\n      Local_accessor;\n  Local_accessor local_acc;\n  Evaluator device_evaluator;\n  Kernel_accessor kernel_filter;\n  Buffer_accessor buffer_acc;\n  internal::IndexMapper<Index, InputDims, 1, Evaluator::Layout> indexMapper;\n  const size_t kernelSize;\n  const cl::sycl::range<2> input_range;\n  EigenConvolutionKernel(Local_accessor local_acc_, Evaluator device_evaluator_, Kernel_accessor kernel_filter_,\n                         Buffer_accessor buffer_acc_,\n                         internal::IndexMapper<Index, InputDims, 1, Evaluator::Layout> indexMapper_,\n                         const size_t kernelSize_, const cl::sycl::range<2> input_range_)\n      : local_acc(local_acc_),\n        device_evaluator(device_evaluator_),\n        kernel_filter(kernel_filter_),\n        buffer_acc(buffer_acc_),\n        indexMapper(indexMapper_),\n        kernelSize(kernelSize_),\n        input_range(input_range_) {}\n\n  template <typename BooleanDim2>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool boundary_check(const BooleanDim2 boolean_check) {\n    return (boolean_check[0] && boolean_check[1]);\n  }\n  void operator()(cl::sycl::nd_item<2> itemID) {\n    auto buffer_ptr = buffer_acc.get_pointer();\n    auto kernel_ptr = kernel_filter.get_pointer();\n    // the required row to be calculated for the for each plane in shered memory\n    const size_t num_input = (itemID.get_local_range()[0] + kernelSize - 1);\n    const size_t plane_kernel_offset = itemID.get_local_id(1) * num_input;\n    const size_t input_offset = itemID.get_group(0) * itemID.get_local_range()[0];\n    const size_t plane_tensor_offset = indexMapper.mapGpuInputPlaneToTensorInputOffset(itemID.get_global_id(1));\n    /// fill the shared memory\n    for (size_t i = itemID.get_local_id(0); i < num_input; i += itemID.get_local_range()[0]) {\n      const size_t local_index = i + plane_kernel_offset;\n      const size_t tensor_index =\n          plane_tensor_offset + indexMapper.mapGpuInputKernelToTensorInputOffset(i + input_offset);\n\n      local_acc[local_index] =\n          (((i + input_offset) < (input_range[0] + kernelSize - 1)) && itemID.get_global_id(1) < input_range[1])\n              ? device_evaluator.coeff(tensor_index)\n              : CoeffReturnType(0);\n    }\n\n    itemID.barrier(cl::sycl::access::fence_space::local_space);\n\n    // calculate the convolution // output start x\n    const size_t first_output_start = itemID.get_group(0) * (itemID.get_local_range()[0]);\n    if (boundary_check(itemID.get_global_id() < input_range)) {\n      CoeffReturnType result = static_cast<CoeffReturnType>(0);\n      const size_t index = plane_kernel_offset + itemID.get_local_id(0);\n      for (size_t k = 0; k < kernelSize; ++k) {\n        result += (local_acc[k + index] * kernel_ptr[k]);\n      }\n      const size_t tensor_index =\n          indexMapper.mapGpuOutputPlaneToTensorOutputOffset(itemID.get_global_id(1)) +\n          indexMapper.mapGpuOutputKernelToTensorOutputOffset(itemID.get_local_id(0) + first_output_start);\n      buffer_ptr[tensor_index] = result;\n    }\n  }\n};\n\ntemplate <typename Evaluator, typename CoeffReturnType, typename KernelType, typename Index, typename InputDims,\n          typename Kernel_accessor, typename Buffer_accessor>\nstruct EigenConvolutionKernel<Evaluator, CoeffReturnType, KernelType, Index, InputDims, Kernel_accessor,\n                              Buffer_accessor, convolution_type::CONV2D> {\n  typedef cl::sycl::accessor<CoeffReturnType, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local>\n      Local_accessor;\n  Local_accessor local_acc;\n  Evaluator device_evaluator;\n  Kernel_accessor kernel_filter;\n  Buffer_accessor buffer_acc;\n  internal::IndexMapper<Index, InputDims, 2, Evaluator::Layout> indexMapper;\n  const cl::sycl::range<2> kernel_size;\n  const cl::sycl::range<3> input_range;\n  EigenConvolutionKernel(Local_accessor local_acc_, Evaluator device_evaluator_, Kernel_accessor kernel_filter_,\n                         Buffer_accessor buffer_acc_,\n                         internal::IndexMapper<Index, InputDims, 2, Evaluator::Layout> indexMapper_,\n                         const cl::sycl::range<2> kernel_size_, const cl::sycl::range<3> input_range_)\n      : local_acc(local_acc_),\n        device_evaluator(device_evaluator_),\n        kernel_filter(kernel_filter_),\n        buffer_acc(buffer_acc_),\n        indexMapper(indexMapper_),\n        kernel_size(kernel_size_),\n        input_range(input_range_) {}\n  template <typename BooleanDim3>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool boundary_check(const BooleanDim3 boolean_check) {\n    return (boolean_check[0] && boolean_check[1] && boolean_check[2]);\n  }\n\n  void operator()(cl::sycl::nd_item<3> itemID) {\n    auto buffer_ptr = buffer_acc.get_pointer();\n    auto kernel_ptr = kernel_filter.get_pointer();\n    // the required row to be calculated for the for each plane in shered memory\n    const auto num_input = cl::sycl::range<2>{\n        (cl::sycl::range<2>(itemID.get_local_range()[0], itemID.get_local_range()[1]) + kernel_size - 1)};\n\n    const size_t plane_input_offset = indexMapper.mapGpuInputPlaneToTensorInputOffset(itemID.get_global_id(2));\n    const size_t plane_kernel_offset = itemID.get_local_id(2) * num_input[1];\n\n    const auto input_offset = cl::sycl::range<2>{itemID.get_group(0) * itemID.get_local_range()[0],\n                                                 itemID.get_group(1) * itemID.get_local_range()[1]};\n      \n    // fill the local memory\n    bool in_range_dim2 = itemID.get_global_id(2) < input_range[2];\n    for (size_t j = itemID.get_local_id(1); j < num_input[1]; j += itemID.get_local_range()[1]) {\n      const size_t local_input_offset = num_input[0] * (j + plane_kernel_offset);\n      bool in_range_dim1 = ((j + input_offset[1]) < (input_range[1] + kernel_size[1] - 1)); \n      for (size_t i = itemID.get_local_id(0); i < num_input[0]; i += itemID.get_local_range()[0]) {\n        const size_t local_index = i + local_input_offset;\n        const size_t tensor_index = plane_input_offset + indexMapper.mapGpuInputKernelToTensorInputOffset(\n                                                             i + input_offset[0], j + input_offset[1]);\n        local_acc[local_index] = (((i + input_offset[0]) < (input_range[0] + kernel_size[0] - 1)) &&\n                                  in_range_dim1 && in_range_dim2)\n                                     ? device_evaluator.coeff(tensor_index)\n                                     : CoeffReturnType(0);\n      }\n    }\n\n    itemID.barrier(cl::sycl::access::fence_space::local_space);\n\n    // output offset start for each thread\n    const auto output_offset = cl::sycl::range<2>{itemID.get_group(0) * itemID.get_local_range()[0],\n                                                  itemID.get_group(1) * itemID.get_local_range()[1]};\n\n    if (boundary_check(itemID.get_global_id() < input_range)) {\n      CoeffReturnType result = static_cast<CoeffReturnType>(0);\n\n      for (size_t j = 0; j < kernel_size[1]; j++) {\n        size_t kernel_offset = kernel_size[0] * j;\n        const size_t index =\n            (num_input[0] * (plane_kernel_offset + j + itemID.get_local_id(1))) + itemID.get_local_id(0);\n        for (size_t i = 0; i < kernel_size[0]; i++) {\n          result += (local_acc[i + index] * kernel_ptr[i + kernel_offset]);\n        }\n      }\n      const size_t tensor_index =\n          indexMapper.mapGpuOutputPlaneToTensorOutputOffset(itemID.get_global_id(2)) +\n          indexMapper.mapGpuOutputKernelToTensorOutputOffset(itemID.get_local_id(0) + output_offset[0],\n                                                             itemID.get_local_id(1) + output_offset[1]);\n\n      buffer_ptr[tensor_index] = result;\n    }\n  }\n};\n\ntemplate <typename Evaluator, typename CoeffReturnType, typename KernelType, typename Index, typename InputDims,\n          typename Kernel_accessor, typename Buffer_accessor>\nstruct EigenConvolutionKernel<Evaluator, CoeffReturnType, KernelType, Index, InputDims, Kernel_accessor,\n                              Buffer_accessor, convolution_type::CONV3D> {\n  typedef cl::sycl::accessor<CoeffReturnType, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local>\n      Local_accessor;\n  Local_accessor local_acc;\n  Evaluator device_evaluator;\n  Kernel_accessor kernel_filter;\n  Buffer_accessor buffer_acc;\n  internal::IndexMapper<Index, InputDims, 3, Evaluator::Layout> indexMapper;\n  const cl::sycl::range<3> kernel_size;\n  const cl::sycl::range<3> input_range;\n  const size_t numP;\n\n  EigenConvolutionKernel(Local_accessor local_acc_, Evaluator device_evaluator_, Kernel_accessor kernel_filter_,\n                         Buffer_accessor buffer_acc_,\n                         internal::IndexMapper<Index, InputDims, 3, Evaluator::Layout> indexMapper_,\n                         const cl::sycl::range<3> kernel_size_, const cl::sycl::range<3> input_range_,\n                         const size_t numP_)\n      : local_acc(local_acc_),\n        device_evaluator(device_evaluator_),\n        kernel_filter(kernel_filter_),\n        buffer_acc(buffer_acc_),\n        indexMapper(indexMapper_),\n        kernel_size(kernel_size_),\n        input_range(input_range_),\n        numP(numP_) {}\n  template <typename BooleanDim3>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool boundary_check(const BooleanDim3 boolean_check) {\n    return (boolean_check[0] && boolean_check[1] && boolean_check[2]);\n  }\n  void operator()(cl::sycl::nd_item<3> itemID) {\n    auto buffer_ptr = buffer_acc.get_pointer();\n    auto kernel_ptr = kernel_filter.get_pointer();\n    const auto num_input = cl::sycl::range<3>{itemID.get_local_range() + kernel_size - 1};\n\n    const auto input_offset = cl::sycl::range<3>{itemID.get_group().get_id() * itemID.get_local_range()};\n\n    const auto output_offset =\n          cl::sycl::range<3>{itemID.get_group().get_id() * itemID.get_local_range() + itemID.get_local_id()};\n\n    for (size_t p = 0; p < numP; p++) {\n      /// fill the shared memory\n      const size_t plane_input_offset = indexMapper.mapGpuInputPlaneToTensorInputOffset(p);\n      for (size_t k = itemID.get_local_id(2); k < num_input[2]; k += itemID.get_local_range()[2]) {\n        size_t local_index_dim2 = num_input[0] * num_input[1] * k;\n        bool cond_k_dim = (k + input_offset[2] < (input_range[2] + kernel_size[2] - 1));\n        for (size_t j = itemID.get_local_id(1); j < num_input[1]; j += itemID.get_local_range()[1]) {\n          bool cond_j_dim = cond_k_dim && (j + input_offset[1] < (input_range[1] + kernel_size[1] - 1));\n          size_t local_index_dim1 = (num_input[0] * j)  + local_index_dim2;\n          for (size_t i = itemID.get_local_id(0); i < num_input[0]; i += itemID.get_local_range()[0]) {\n            bool conds = cond_j_dim && (i + input_offset[0] < (input_range[0] + kernel_size[0] - 1));\n            const size_t local_index = local_index_dim1 + i;\n            const size_t tensor_index =\n                plane_input_offset + indexMapper.mapGpuInputKernelToTensorInputOffset(\n                                         i + input_offset[0], j + input_offset[1], k + input_offset[2]);\n            local_acc[local_index] = conds ? device_evaluator.coeff(tensor_index) : CoeffReturnType(0);\n          }\n        }\n      }\n      itemID.barrier(cl::sycl::access::fence_space::local_space);\n\n      // calculate the convolution\n\n      if (boundary_check(itemID.get_global_id() < input_range)) {\n        CoeffReturnType result = static_cast<CoeffReturnType>(0);\n        for (size_t k = 0; k < kernel_size[2]; k++) {\n          for (size_t j = 0; j < kernel_size[1]; j++) {\n            for (size_t i = 0; i < kernel_size[0]; i++) {\n              const size_t kernel_index = i + kernel_size[0] * (j + kernel_size[1] * k);\n              const size_t local_index =\n                  ((i + itemID.get_local_id(0)) +\n                   num_input[0] * ((j + itemID.get_local_id(1)) + num_input[1] * (k + itemID.get_local_id(2))));\n\n              result += (local_acc[local_index] * kernel_ptr[kernel_index]);\n            }\n          }\n        }\n        const size_t tensor_index =\n            indexMapper.mapGpuOutputPlaneToTensorOutputOffset(p) +\n            indexMapper.mapGpuOutputKernelToTensorOutputOffset(output_offset[0], output_offset[1], output_offset[2]);\n        buffer_ptr[tensor_index] = result;\n      }\n\n      itemID.barrier(cl::sycl::access::fence_space::local_space);\n    }\n  }\n};\n\ntemplate <typename Indices, typename InputArgType, typename KernelArgType>\nstruct TensorEvaluator<const TensorConvolutionOp<Indices, InputArgType, KernelArgType>, Eigen::SyclDevice> {\n  typedef TensorConvolutionOp<Indices, InputArgType, KernelArgType> XprType;\n\n  static const int NumDims =\n      internal::array_size<typename TensorEvaluator<InputArgType, Eigen::SyclDevice>::Dimensions>::value;\n  static const int NumKernelDims = internal::array_size<Indices>::value;\n  typedef typename XprType::Index Index;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename TensorEvaluator<KernelArgType, Eigen::SyclDevice>::Dimensions KernelDimensions;\n  typedef const Eigen::SyclDevice Device;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Eigen::SyclDevice>::type PacketReturnType;\n  typedef typename InputArgType::Scalar Scalar;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<CoeffReturnType, Eigen::SyclDevice> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n  typedef StorageMemory<const CoeffReturnType, Eigen::SyclDevice> KernelStorage;\n\n  enum {\n    IsAligned = TensorEvaluator<InputArgType, Eigen::SyclDevice>::IsAligned &\n                TensorEvaluator<KernelArgType, Eigen::SyclDevice>::IsAligned,\n    PacketAccess = false,\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<InputArgType, Eigen::SyclDevice>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC TensorEvaluator(const XprType &op, const Eigen::SyclDevice &device)\n      : m_inputImpl(op.inputExpression(), device),\n        m_kernelArg(op.kernelExpression()),\n        m_kernelImpl(op.kernelExpression(), device),\n        m_indices(op.indices()),\n        m_buf(NULL),\n        m_kernel(NULL),\n        m_local_kernel(false),\n        m_device(device) {\n    EIGEN_STATIC_ASSERT((static_cast<int>(TensorEvaluator<InputArgType, Eigen::SyclDevice>::Layout) ==\n                         static_cast<int>(TensorEvaluator<KernelArgType, Eigen::SyclDevice>::Layout)),\n                        YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    const typename TensorEvaluator<InputArgType, Eigen::SyclDevice>::Dimensions &input_dims = m_inputImpl.dimensions();\n    const typename TensorEvaluator<KernelArgType, Eigen::SyclDevice>::Dimensions &kernel_dims =\n        m_kernelImpl.dimensions();\n\n    m_dimensions = m_inputImpl.dimensions();\n    for (int i = 0; i < NumKernelDims; ++i) {\n      const Index index = op.indices()[i];\n      const Index input_dim = input_dims[index];\n      const Index kernel_dim = kernel_dims[i];\n      const Index result_dim = input_dim - kernel_dim + 1;\n      m_dimensions[index] = result_dim;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC const Dimensions &dimensions() const { return m_dimensions; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    preloadKernel();\n    m_inputImpl.evalSubExprsIfNeeded(NULL);\n    if (data) {\n      executeEval(data);\n      return false;\n    } else {\n      m_buf = (EvaluatorPointerType)m_device.get(\n          (Scalar *)m_device.allocate_temp(dimensions().TotalSize() * sizeof(Scalar)));\n      executeEval(m_buf);\n      return true;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_inputImpl.cleanup();\n    if (m_buf) {\n      m_device.deallocate_temp(m_buf);\n      m_buf = NULL;\n    }\n    if (m_local_kernel) {\n      m_device.deallocate_temp(m_kernel);\n      m_local_kernel = false;\n    }\n    m_kernel = NULL;\n  }\n  /// used by sycl in order to build the sycl buffer\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Device &device() const { return m_device; }\n  /// used by sycl in order to build the sycl buffer\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EvaluatorPointerType data() const { return m_buf; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void preloadKernel() {\n    // Don't make a local copy of the kernel unless we have to (i.e. it's an\n    // expression that needs to be evaluated)\n    typename KernelStorage::Type in_place = m_kernelImpl.data();\n    if (in_place) {\n      m_kernel = in_place;\n      m_local_kernel = false;\n    } else {\n      ptrdiff_t kernel_sz = m_kernelImpl.dimensions().TotalSize() * sizeof(Scalar);\n      EvaluatorPointerType local = (EvaluatorPointerType)m_device.get((Scalar *)m_device.allocate_temp(kernel_sz));\n      typedef TensorEvalToOp<const KernelArgType> EvalTo;\n      EvalTo evalToTmp(m_device.get(local), m_kernelArg);\n      const bool PacketAccess = internal::IsVectorizable<Eigen::SyclDevice, KernelArgType>::value;\n      internal::TensorExecutor<const EvalTo, Eigen::SyclDevice, PacketAccess>::run(evalToTmp, m_device);\n      m_kernel = local;\n      m_local_kernel = true;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void executeEval(EvaluatorPointerType data) const {\n    typedef TensorEvaluator<InputArgType, Eigen::SyclDevice> InputEvaluator;\n    typedef typename InputEvaluator::Dimensions InputDims;\n    switch (NumKernelDims) {\n      case 1: {\n        const size_t numX = dimensions()[m_indices[0]];\n        const size_t numP = dimensions().TotalSize() / numX;\n        const auto input_dim = std::array<size_t, 2>{numX, numP};\n        auto global_range = cl::sycl::range<2>{};\n        auto local_range = cl::sycl::range<2>{};\n        const size_t kernel_size = m_kernelImpl.dimensions().TotalSize();\n\n        m_device.parallel_for_setup(input_dim, global_range, local_range);\n        const size_t local_memory_size = (local_range[0] + kernel_size - 1) * (local_range[1]);\n        gpu_assert(static_cast<unsigned long>(local_memory_size) <= m_device.sharedMemPerBlock());\n        const array<Index, 1> indices{{m_indices[0]}};\n        const array<Index, 1> kernel_dims{{m_kernelImpl.dimensions()[0]}};\n        internal::IndexMapper<Index, InputDims, 1, Layout> indexMapper(m_inputImpl.dimensions(), kernel_dims, indices);\n\n        typedef EigenConvolutionKernel<InputEvaluator, CoeffReturnType, Scalar, Index, InputDims,\n                                       typename KernelStorage::Type, EvaluatorPointerType, convolution_type::CONV1D>\n            ConvKernel;\n\n        m_device.template binary_kernel_launcher<CoeffReturnType, ConvKernel>(\n            m_inputImpl, m_kernel, data, cl::sycl::nd_range<2>(global_range, local_range), local_memory_size,\n            indexMapper, kernel_size, cl::sycl::range<2>(input_dim[0], input_dim[1]));\n        break;\n      }\n\n      case 2: {\n        auto kernel_index = std::array<size_t, 2>{static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 0 : 1,\n                                                  static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 1 : 0};\n        auto kernel_size = cl::sycl::range<2>{(size_t)m_kernelImpl.dimensions()[kernel_index[0]],\n                                              (size_t)m_kernelImpl.dimensions()[kernel_index[1]]};\n        const size_t numX = dimensions()[m_indices[kernel_index[0]]];\n        const size_t numY = dimensions()[m_indices[kernel_index[1]]];\n        const size_t numP = dimensions().TotalSize() / (numX * numY);\n        auto input_dim = std::array<size_t, 3>{numX, numY, numP};\n\n        auto global_range = cl::sycl::range<3>{};\n        auto local_range = cl::sycl::range<3>{};\n\n        m_device.parallel_for_setup(input_dim, global_range, local_range);\n\n        const size_t local_memory_size =\n            (local_range[0] + kernel_size[0] - 1) * (local_range[1] + kernel_size[1] - 1) * local_range[2];\n        gpu_assert(static_cast<unsigned long>(local_memory_size) <= m_device.sharedMemPerBlock());\n        const array<Index, 2> indices{{m_indices[kernel_index[0]], m_indices[kernel_index[1]]}};\n        const array<Index, 2> kernel_dims{\n            {m_kernelImpl.dimensions()[kernel_index[0]], m_kernelImpl.dimensions()[kernel_index[1]]}};\n        internal::IndexMapper<Index, InputDims, 2, Layout> indexMapper(m_inputImpl.dimensions(), kernel_dims, indices);\n        typedef EigenConvolutionKernel<InputEvaluator, CoeffReturnType, Scalar, Index, InputDims,\n                                       typename KernelStorage::Type, EvaluatorPointerType, convolution_type::CONV2D>\n            ConvKernel;\n        m_device.template binary_kernel_launcher<CoeffReturnType, ConvKernel>(\n            m_inputImpl, m_kernel, data, cl::sycl::nd_range<3>(global_range, local_range), local_memory_size,\n            indexMapper, kernel_size, cl::sycl::range<3>{input_dim[0], input_dim[1], input_dim[2]});\n        break;\n      }\n\n      case 3: {\n        auto kernel_index = std::array<size_t, 3>{static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 0 : 2,\n                                                  static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 1 : 1,\n                                                  static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 2 : 0};\n\n        auto kernel_size = cl::sycl::range<3>{(size_t)m_kernelImpl.dimensions()[kernel_index[0]],\n                                              (size_t)m_kernelImpl.dimensions()[kernel_index[1]],\n                                              (size_t)m_kernelImpl.dimensions()[kernel_index[2]]};\n\n        const size_t numX = dimensions()[m_indices[kernel_index[0]]];\n        const size_t numY = dimensions()[m_indices[kernel_index[1]]];\n        const size_t numZ = dimensions()[m_indices[kernel_index[2]]];\n        auto input_dim = std::array<size_t, 3>{numX, numY, numZ};\n        const size_t numP = dimensions().TotalSize() / (numX * numY * numZ);\n\n        const array<Index, 3> indices{\n            {m_indices[kernel_index[0]], m_indices[kernel_index[1]], m_indices[kernel_index[2]]}};\n        const array<Index, 3> kernel_dims{{m_kernelImpl.dimensions()[kernel_index[0]],\n                                           m_kernelImpl.dimensions()[kernel_index[1]],\n                                           m_kernelImpl.dimensions()[kernel_index[2]]}};\n\n        internal::IndexMapper<Index, InputDims, 3, Layout> indexMapper(m_inputImpl.dimensions(), kernel_dims, indices);\n\n        auto global_range = cl::sycl::range<3>{};\n        auto local_range = cl::sycl::range<3>{};\n\n        m_device.parallel_for_setup(input_dim, global_range, local_range);\n        auto local_memory_range = (local_range + kernel_size - 1);\n        const size_t local_memory_size = local_memory_range[0] * local_memory_range[1] * local_memory_range[2];\n\n        gpu_assert(static_cast<unsigned long>(local_memory_size) <= m_device.sharedMemPerBlock());\n        typedef EigenConvolutionKernel<InputEvaluator, CoeffReturnType, Scalar, Index, InputDims,\n                                       typename KernelStorage::Type, EvaluatorPointerType, convolution_type::CONV3D>\n            ConvKernel;\n        m_device.template binary_kernel_launcher<CoeffReturnType, ConvKernel>(\n            m_inputImpl, m_kernel, data, cl::sycl::nd_range<3>(global_range, local_range), local_memory_size,\n            indexMapper, kernel_size, cl::sycl::range<3>(input_dim[0], input_dim[1], input_dim[2]), numP);\n        break;\n      }\n\n      default: {\n        EIGEN_STATIC_ASSERT((NumKernelDims >= 1 && NumKernelDims <= 3),\n                            THIS_METHOD_IS_ONLY_FOR_OBJECTS_OF_A_SPECIFIC_SIZE);\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const {\n    eigen_assert(m_buf != NULL);\n    eigen_assert(index < m_dimensions.TotalSize());\n    return m_buf[index];\n  }\n\n  template <int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(const Index index) const {\n    eigen_assert(m_buf != NULL);\n    eigen_assert(index < m_dimensions.TotalSize());\n    return internal::ploadt<PacketReturnType, LoadMode>(m_buf + index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    // TODO(rmlarsen): FIXME: For now, this is just a copy of the CPU cost\n    // model.\n    const double kernel_size = m_kernelImpl.dimensions().TotalSize();\n    // We ignore the use of fused multiply-add.\n    const double convolve_compute_cost = TensorOpCost::AddCost<Scalar>() + TensorOpCost::MulCost<Scalar>();\n    const double firstIndex_compute_cost =\n        NumDims *\n        (2 * TensorOpCost::AddCost<Index>() + 2 * TensorOpCost::MulCost<Index>() + TensorOpCost::DivCost<Index>());\n    return TensorOpCost(0, 0, firstIndex_compute_cost, vectorized, PacketSize) +\n           kernel_size * (m_inputImpl.costPerCoeff(vectorized) + m_kernelImpl.costPerCoeff(vectorized) +\n                          TensorOpCost(0, 0, convolve_compute_cost, vectorized, PacketSize));\n  }\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_kernelImpl.bind(cgh);\n    m_inputImpl.bind(cgh);\n    m_buf.bind(cgh);\n    m_kernel.bind(cgh);\n  }\n\n private:\n  // No assignment (copies are needed by the kernels)\n  TensorEvaluator &operator=(const TensorEvaluator &);\n  TensorEvaluator<InputArgType, Eigen::SyclDevice> m_inputImpl;\n  KernelArgType m_kernelArg;\n  TensorEvaluator<KernelArgType, Eigen::SyclDevice> m_kernelImpl;\n  Indices m_indices;\n  Dimensions m_dimensions;\n  EvaluatorPointerType m_buf;\n  typename KernelStorage::Type m_kernel;\n  bool m_local_kernel;\n  const Eigen::SyclDevice EIGEN_DEVICE_REF m_device;\n};  // namespace Eigen\n\n}  // end namespace Eigen\n\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_CONVOLUTION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorCostModel.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Rasmus Munk Larsen <rmlarsen@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_COST_MODEL_H\n#define EIGEN_CXX11_TENSOR_TENSOR_COST_MODEL_H\n\nnamespace Eigen {\n\n/** \\class TensorEvaluator\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief A cost model used to limit the number of threads used for evaluating\n  * tensor expression.\n  *\n  */\n\n// Class storing the cost of evaluating a tensor expression in terms of the\n// estimated number of operand bytes loads, bytes stored, and compute cycles.\nclass TensorOpCost {\n public:\n  // TODO(rmlarsen): Fix the scalar op costs in Eigen proper. Even a simple\n  // model based on minimal reciprocal throughput numbers from Intel or\n  // Agner Fog's tables would be better than what is there now.\n  template <typename ArgType>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int MulCost() {\n    return internal::functor_traits<\n        internal::scalar_product_op<ArgType, ArgType> >::Cost;\n  }\n  template <typename ArgType>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int AddCost() {\n    return internal::functor_traits<internal::scalar_sum_op<ArgType> >::Cost;\n  }\n  template <typename ArgType>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int DivCost() {\n    return internal::functor_traits<\n        internal::scalar_quotient_op<ArgType, ArgType> >::Cost;\n  }\n  template <typename ArgType>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int ModCost() {\n    return internal::functor_traits<internal::scalar_mod_op<ArgType> >::Cost;\n  }\n  template <typename SrcType, typename TargetType>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int CastCost() {\n    return internal::functor_traits<\n        internal::scalar_cast_op<SrcType, TargetType> >::Cost;\n  }\n\n  EIGEN_DEVICE_FUNC\n  TensorOpCost() : bytes_loaded_(0), bytes_stored_(0), compute_cycles_(0) {}\n  EIGEN_DEVICE_FUNC\n  TensorOpCost(double bytes_loaded, double bytes_stored, double compute_cycles)\n      : bytes_loaded_(bytes_loaded),\n        bytes_stored_(bytes_stored),\n        compute_cycles_(compute_cycles) {}\n\n  EIGEN_DEVICE_FUNC\n  TensorOpCost(double bytes_loaded, double bytes_stored, double compute_cycles,\n               bool vectorized, double packet_size)\n      : bytes_loaded_(bytes_loaded),\n        bytes_stored_(bytes_stored),\n        compute_cycles_(vectorized ? compute_cycles / packet_size\n                                   : compute_cycles) {\n    eigen_assert(bytes_loaded >= 0 && (numext::isfinite)(bytes_loaded));\n    eigen_assert(bytes_stored >= 0 && (numext::isfinite)(bytes_stored));\n    eigen_assert(compute_cycles >= 0 && (numext::isfinite)(compute_cycles));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double bytes_loaded() const {\n    return bytes_loaded_;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double bytes_stored() const {\n    return bytes_stored_;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double compute_cycles() const {\n    return compute_cycles_;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double total_cost(\n      double load_cost, double store_cost, double compute_cost) const {\n    return load_cost * bytes_loaded_ + store_cost * bytes_stored_ +\n           compute_cost * compute_cycles_;\n  }\n\n  // Drop memory access component. Intended for cases when memory accesses are\n  // sequential or are completely masked by computations.\n  EIGEN_DEVICE_FUNC void dropMemoryCost() {\n    bytes_loaded_ = 0;\n    bytes_stored_ = 0;\n  }\n\n  // TODO(rmlarsen): Define min in terms of total cost, not elementwise.\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost cwiseMin(\n      const TensorOpCost& rhs) const {\n    double bytes_loaded = numext::mini(bytes_loaded_, rhs.bytes_loaded());\n    double bytes_stored = numext::mini(bytes_stored_, rhs.bytes_stored());\n    double compute_cycles = numext::mini(compute_cycles_, rhs.compute_cycles());\n    return TensorOpCost(bytes_loaded, bytes_stored, compute_cycles);\n  }\n\n  // TODO(rmlarsen): Define max in terms of total cost, not elementwise.\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost cwiseMax(\n      const TensorOpCost& rhs) const {\n    double bytes_loaded = numext::maxi(bytes_loaded_, rhs.bytes_loaded());\n    double bytes_stored = numext::maxi(bytes_stored_, rhs.bytes_stored());\n    double compute_cycles = numext::maxi(compute_cycles_, rhs.compute_cycles());\n    return TensorOpCost(bytes_loaded, bytes_stored, compute_cycles);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost& operator+=(\n      const TensorOpCost& rhs) {\n    bytes_loaded_ += rhs.bytes_loaded();\n    bytes_stored_ += rhs.bytes_stored();\n    compute_cycles_ += rhs.compute_cycles();\n    return *this;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost& operator*=(double rhs) {\n    bytes_loaded_ *= rhs;\n    bytes_stored_ *= rhs;\n    compute_cycles_ *= rhs;\n    return *this;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE friend TensorOpCost operator+(\n      TensorOpCost lhs, const TensorOpCost& rhs) {\n    lhs += rhs;\n    return lhs;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE friend TensorOpCost operator*(\n      TensorOpCost lhs, double rhs) {\n    lhs *= rhs;\n    return lhs;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE friend TensorOpCost operator*(\n      double lhs, TensorOpCost rhs) {\n    rhs *= lhs;\n    return rhs;\n  }\n\n  friend std::ostream& operator<<(std::ostream& os, const TensorOpCost& tc) {\n    return os << \"[bytes_loaded = \" << tc.bytes_loaded()\n              << \", bytes_stored = \" << tc.bytes_stored()\n              << \", compute_cycles = \" << tc.compute_cycles() << \"]\";\n  }\n\n private:\n  double bytes_loaded_;\n  double bytes_stored_;\n  double compute_cycles_;\n};\n\n// TODO(rmlarsen): Implement a policy that chooses an \"optimal\" number of theads\n// in [1:max_threads] instead of just switching multi-threading off for small\n// work units.\ntemplate <typename Device>\nclass TensorCostModel {\n public:\n  // Scaling from Eigen compute cost to device cycles.\n  static const int kDeviceCyclesPerComputeCycle = 1;\n\n // Costs in device cycles.\n  static const int kStartupCycles = 100000;\n  static const int kPerThreadCycles = 100000;\n  static const int kTaskSize = 40000;\n\n  // Returns the number of threads in [1:max_threads] to use for\n  // evaluating an expression with the given output size and cost per\n  // coefficient.\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int numThreads(\n      double output_size, const TensorOpCost& cost_per_coeff, int max_threads) {\n    double cost = totalCost(output_size, cost_per_coeff);\n    double threads = (cost - kStartupCycles) / kPerThreadCycles + 0.9;\n    // Make sure we don't invoke undefined behavior when we convert to an int.\n    threads = numext::mini<double>(threads, GenericNumTraits<int>::highest());\n    return numext::mini(max_threads,\n                        numext::maxi<int>(1, static_cast<int>(threads)));\n  }\n\n  // taskSize assesses parallel task size.\n  // Value of 1.0 means ideal parallel task size. Values < 1.0 mean that task\n  // granularity needs to be increased to mitigate parallelization overheads.\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double taskSize(\n      double output_size, const TensorOpCost& cost_per_coeff) {\n    return totalCost(output_size, cost_per_coeff) / kTaskSize;\n  }\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double totalCost(\n      double output_size, const TensorOpCost& cost_per_coeff) {\n    // Cost of memory fetches from L2 cache. 64 is typical cache line size.\n    // 11 is L2 cache latency on Haswell.\n    // We don't know whether data is in L1, L2 or L3. But we are most interested\n    // in single-threaded computational time around 100us-10ms (smaller time\n    // is too small for parallelization, larger time is not interesting\n    // either because we are probably using all available threads already).\n    // And for the target time range, L2 seems to be what matters. Data set\n    // fitting into L1 is too small to take noticeable time. Data set fitting\n    // only into L3 presumably will take more than 10ms to load and process.\n    const double kLoadCycles = 1.0 / 64 * 11;\n    const double kStoreCycles = 1.0 / 64 * 11;\n    // Scaling from Eigen compute cost to device cycles.\n    return output_size *\n        cost_per_coeff.total_cost(kLoadCycles, kStoreCycles,\n                                  kDeviceCyclesPerComputeCycle);\n  }\n};\n\n}  // namespace Eigen\n\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_COST_MODEL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorCustomOp.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_CUSTOM_OP_H\n#define EIGEN_CXX11_TENSOR_TENSOR_CUSTOM_OP_H\n\nnamespace Eigen {\n\n/** \\class TensorCustomUnaryOp\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor custom class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename CustomUnaryFunc, typename XprType>\nstruct traits<TensorCustomUnaryOp<CustomUnaryFunc, XprType> >\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::StorageKind StorageKind;\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = traits<XprType>::NumDimensions;\n  static const int Layout = traits<XprType>::Layout;\n  typedef typename traits<XprType>::PointerType PointerType;\n};\n\ntemplate<typename CustomUnaryFunc, typename XprType>\nstruct eval<TensorCustomUnaryOp<CustomUnaryFunc, XprType>, Eigen::Dense>\n{\n  typedef const TensorCustomUnaryOp<CustomUnaryFunc, XprType>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename CustomUnaryFunc, typename XprType>\nstruct nested<TensorCustomUnaryOp<CustomUnaryFunc, XprType> >\n{\n  typedef TensorCustomUnaryOp<CustomUnaryFunc, XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename CustomUnaryFunc, typename XprType>\nclass TensorCustomUnaryOp : public TensorBase<TensorCustomUnaryOp<CustomUnaryFunc, XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename internal::traits<TensorCustomUnaryOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename internal::nested<TensorCustomUnaryOp>::type Nested;\n  typedef typename internal::traits<TensorCustomUnaryOp>::StorageKind StorageKind;\n  typedef typename internal::traits<TensorCustomUnaryOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCustomUnaryOp(const XprType& expr, const CustomUnaryFunc& func)\n      : m_expr(expr), m_func(func) {}\n\n  EIGEN_DEVICE_FUNC\n  const CustomUnaryFunc& func() const { return m_func; }\n\n  EIGEN_DEVICE_FUNC\n  const typename internal::remove_all<typename XprType::Nested>::type&\n  expression() const { return m_expr; }\n\n  protected:\n    typename XprType::Nested m_expr;\n    const CustomUnaryFunc m_func;\n};\n\n\n// Eval as rvalue\ntemplate<typename CustomUnaryFunc, typename XprType, typename Device>\nstruct TensorEvaluator<const TensorCustomUnaryOp<CustomUnaryFunc, XprType>, Device>\n{\n  typedef TensorCustomUnaryOp<CustomUnaryFunc, XprType> ArgType;\n  typedef typename internal::traits<ArgType>::Index Index;\n  static const int NumDims = internal::traits<ArgType>::NumDimensions;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename internal::remove_const<typename ArgType::Scalar>::type Scalar;\n  typedef typename internal::remove_const<typename XprType::CoeffReturnType>::type CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef typename Eigen::internal::traits<XprType>::PointerType TensorPointerType;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<XprType, Device>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const ArgType& op, const Device& device)\n      : m_op(op), m_device(device), m_result(NULL)\n  {\n    m_dimensions = op.func().dimensions(op.expression());\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    if (data) {\n      evalTo(data);\n      return false;\n    } else {\n      m_result = static_cast<EvaluatorPointerType>(m_device.get( (CoeffReturnType*)\n          m_device.allocate_temp(dimensions().TotalSize() * sizeof(Scalar))));\n      evalTo(m_result);\n      return true;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    if (m_result) {\n      m_device.deallocate_temp(m_result);\n      m_result = NULL;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const {\n    return m_result[index];\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC PacketReturnType packet(Index index) const {\n    return internal::ploadt<PacketReturnType, LoadMode>(m_result + index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    // TODO(rmlarsen): Extend CustomOp API to return its cost estimate.\n    return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return m_result; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_result.bind(cgh);\n  }\n#endif\n\n protected:\n  EIGEN_DEVICE_FUNC void evalTo(EvaluatorPointerType data) {\n    TensorMap<Tensor<CoeffReturnType, NumDims, Layout, Index> > result(m_device.get(data), m_dimensions);\n    m_op.func().eval(m_op.expression(), result, m_device);\n  }\n\n  Dimensions m_dimensions;\n  const ArgType m_op;\n  const Device EIGEN_DEVICE_REF m_device;\n  EvaluatorPointerType m_result;\n};\n\n\n\n/** \\class TensorCustomBinaryOp\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor custom class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename CustomBinaryFunc, typename LhsXprType, typename RhsXprType>\nstruct traits<TensorCustomBinaryOp<CustomBinaryFunc, LhsXprType, RhsXprType> >\n{\n  typedef typename internal::promote_storage_type<typename LhsXprType::Scalar,\n                                                  typename RhsXprType::Scalar>::ret Scalar;\n  typedef typename internal::promote_storage_type<typename LhsXprType::CoeffReturnType,\n                                                  typename RhsXprType::CoeffReturnType>::ret CoeffReturnType;\n  typedef typename promote_storage_type<typename traits<LhsXprType>::StorageKind,\n                                        typename traits<RhsXprType>::StorageKind>::ret StorageKind;\n  typedef typename promote_index_type<typename traits<LhsXprType>::Index,\n                                      typename traits<RhsXprType>::Index>::type Index;\n  typedef typename LhsXprType::Nested LhsNested;\n  typedef typename RhsXprType::Nested RhsNested;\n  typedef typename remove_reference<LhsNested>::type _LhsNested;\n  typedef typename remove_reference<RhsNested>::type _RhsNested;\n  static const int NumDimensions = traits<LhsXprType>::NumDimensions;\n  static const int Layout = traits<LhsXprType>::Layout;\n  typedef typename conditional<Pointer_type_promotion<typename LhsXprType::Scalar, Scalar>::val,\n                                typename traits<LhsXprType>::PointerType, typename traits<RhsXprType>::PointerType>::type PointerType;\n};\n\ntemplate<typename CustomBinaryFunc, typename LhsXprType, typename RhsXprType>\nstruct eval<TensorCustomBinaryOp<CustomBinaryFunc, LhsXprType, RhsXprType>, Eigen::Dense>\n{\n  typedef const TensorCustomBinaryOp<CustomBinaryFunc, LhsXprType, RhsXprType>& type;\n};\n\ntemplate<typename CustomBinaryFunc, typename LhsXprType, typename RhsXprType>\nstruct nested<TensorCustomBinaryOp<CustomBinaryFunc, LhsXprType, RhsXprType> >\n{\n  typedef TensorCustomBinaryOp<CustomBinaryFunc, LhsXprType, RhsXprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename CustomBinaryFunc, typename LhsXprType, typename RhsXprType>\nclass TensorCustomBinaryOp : public TensorBase<TensorCustomBinaryOp<CustomBinaryFunc, LhsXprType, RhsXprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename internal::traits<TensorCustomBinaryOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename internal::traits<TensorCustomBinaryOp>::CoeffReturnType CoeffReturnType;\n  typedef typename internal::nested<TensorCustomBinaryOp>::type Nested;\n  typedef typename internal::traits<TensorCustomBinaryOp>::StorageKind StorageKind;\n  typedef typename internal::traits<TensorCustomBinaryOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCustomBinaryOp(const LhsXprType& lhs, const RhsXprType& rhs, const CustomBinaryFunc& func)\n\n      : m_lhs_xpr(lhs), m_rhs_xpr(rhs), m_func(func) {}\n\n  EIGEN_DEVICE_FUNC\n  const CustomBinaryFunc& func() const { return m_func; }\n\n  EIGEN_DEVICE_FUNC\n  const typename internal::remove_all<typename LhsXprType::Nested>::type&\n  lhsExpression() const { return m_lhs_xpr; }\n\n  EIGEN_DEVICE_FUNC\n  const typename internal::remove_all<typename RhsXprType::Nested>::type&\n  rhsExpression() const { return m_rhs_xpr; }\n\n  protected:\n    typename LhsXprType::Nested m_lhs_xpr;\n    typename RhsXprType::Nested m_rhs_xpr;\n    const CustomBinaryFunc m_func;\n};\n\n\n// Eval as rvalue\ntemplate<typename CustomBinaryFunc, typename LhsXprType, typename RhsXprType, typename Device>\nstruct TensorEvaluator<const TensorCustomBinaryOp<CustomBinaryFunc, LhsXprType, RhsXprType>, Device>\n{\n  typedef TensorCustomBinaryOp<CustomBinaryFunc, LhsXprType, RhsXprType> XprType;\n  typedef typename internal::traits<XprType>::Index Index;\n  static const int NumDims = internal::traits<XprType>::NumDimensions;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename internal::remove_const<typename XprType::CoeffReturnType>::type CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n\n  typedef typename Eigen::internal::traits<XprType>::PointerType TensorPointerType;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<LhsXprType, Device>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_op(op), m_device(device), m_result(NULL)\n  {\n    m_dimensions = op.func().dimensions(op.lhsExpression(), op.rhsExpression());\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    if (data) {\n      evalTo(data);\n      return false;\n    } else {\n      m_result = static_cast<EvaluatorPointerType>(m_device.get( (CoeffReturnType*)\n        m_device.allocate_temp(dimensions().TotalSize() * sizeof(CoeffReturnType))));\n      evalTo(m_result);\n      return true;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    if (m_result != NULL) {\n      m_device.deallocate_temp(m_result);\n      m_result = NULL;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const {\n    return m_result[index];\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC PacketReturnType packet(Index index) const {\n    return internal::ploadt<PacketReturnType, LoadMode>(m_result + index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    // TODO(rmlarsen): Extend CustomOp API to return its cost estimate.\n    return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return m_result; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_result.bind(cgh);\n  }\n#endif\n\n protected:\n  EIGEN_DEVICE_FUNC void evalTo(EvaluatorPointerType data) {\n    TensorMap<Tensor<CoeffReturnType, NumDims, Layout> > result(m_device.get(data), m_dimensions);\n    m_op.func().eval(m_op.lhsExpression(), m_op.rhsExpression(), result, m_device);\n  }\n\n  Dimensions m_dimensions;\n  const XprType m_op;\n  const Device EIGEN_DEVICE_REF m_device;\n  EvaluatorPointerType m_result;\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_CUSTOM_OP_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDevice.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_DEVICE_H\n#define EIGEN_CXX11_TENSOR_TENSOR_DEVICE_H\n\nnamespace Eigen {\n\n/** \\class TensorDevice\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Pseudo expression providing an operator = that will evaluate its argument\n  * on the specified computing 'device' (GPU, thread pool, ...)\n  *\n  * Example:\n  *    C.device(EIGEN_GPU) = A + B;\n  *\n  * Todo: operator *= and /=.\n  */\n\ntemplate <typename ExpressionType, typename DeviceType> class TensorDevice {\n  public:\n    TensorDevice(const DeviceType& device, ExpressionType& expression) : m_device(device), m_expression(expression) {}\n\n    EIGEN_DEFAULT_COPY_CONSTRUCTOR(TensorDevice)\n\n    template<typename OtherDerived>\n    EIGEN_STRONG_INLINE TensorDevice& operator=(const OtherDerived& other) {\n      typedef TensorAssignOp<ExpressionType, const OtherDerived> Assign;\n      Assign assign(m_expression, other);\n      internal::TensorExecutor<const Assign, DeviceType>::run(assign, m_device);\n      return *this;\n    }\n\n    template<typename OtherDerived>\n    EIGEN_STRONG_INLINE TensorDevice& operator+=(const OtherDerived& other) {\n      typedef typename OtherDerived::Scalar Scalar;\n      typedef TensorCwiseBinaryOp<internal::scalar_sum_op<Scalar>, const ExpressionType, const OtherDerived> Sum;\n      Sum sum(m_expression, other);\n      typedef TensorAssignOp<ExpressionType, const Sum> Assign;\n      Assign assign(m_expression, sum);\n      internal::TensorExecutor<const Assign, DeviceType>::run(assign, m_device);\n      return *this;\n    }\n\n    template<typename OtherDerived>\n    EIGEN_STRONG_INLINE TensorDevice& operator-=(const OtherDerived& other) {\n      typedef typename OtherDerived::Scalar Scalar;\n      typedef TensorCwiseBinaryOp<internal::scalar_difference_op<Scalar>, const ExpressionType, const OtherDerived> Difference;\n      Difference difference(m_expression, other);\n      typedef TensorAssignOp<ExpressionType, const Difference> Assign;\n      Assign assign(m_expression, difference);\n      internal::TensorExecutor<const Assign, DeviceType>::run(assign, m_device);\n      return *this;\n    }\n\n  protected:\n    const DeviceType& m_device;\n    ExpressionType& m_expression;\n};\n\n/** \\class TensorAsyncDevice\n * \\ingroup CXX11_Tensor_Module\n *\n * \\brief Pseudo expression providing an operator = that will evaluate its\n * argument asynchronously on the specified device. Currently only\n * ThreadPoolDevice implements proper asynchronous execution, while the default\n * and GPU devices just run the expression synchronously and call m_done() on\n * completion..\n *\n * Example:\n *    auto done = []() { ... expression evaluation done ... };\n *    C.device(thread_pool_device, std::move(done)) = A + B;\n */\n\ntemplate <typename ExpressionType, typename DeviceType, typename DoneCallback>\nclass TensorAsyncDevice {\n public:\n  TensorAsyncDevice(const DeviceType& device, ExpressionType& expression,\n                    DoneCallback done)\n      : m_device(device), m_expression(expression), m_done(std::move(done)) {}\n\n  template <typename OtherDerived>\n  EIGEN_STRONG_INLINE TensorAsyncDevice& operator=(const OtherDerived& other) {\n    typedef TensorAssignOp<ExpressionType, const OtherDerived> Assign;\n    typedef internal::TensorExecutor<const Assign, DeviceType> Executor;\n\n    Assign assign(m_expression, other);\n    Executor::run(assign, m_device);\n    m_done();\n\n    return *this;\n  }\n\n protected:\n  const DeviceType& m_device;\n  ExpressionType& m_expression;\n  DoneCallback m_done;\n};\n\n\n#ifdef EIGEN_USE_THREADS\ntemplate <typename ExpressionType, typename DoneCallback>\nclass TensorAsyncDevice<ExpressionType, ThreadPoolDevice, DoneCallback> {\n public:\n  TensorAsyncDevice(const ThreadPoolDevice& device, ExpressionType& expression,\n                    DoneCallback done)\n      : m_device(device), m_expression(expression), m_done(std::move(done)) {}\n\n  template <typename OtherDerived>\n  EIGEN_STRONG_INLINE TensorAsyncDevice& operator=(const OtherDerived& other) {\n    typedef TensorAssignOp<ExpressionType, const OtherDerived> Assign;\n    typedef internal::TensorAsyncExecutor<const Assign, ThreadPoolDevice, DoneCallback> Executor;\n\n    // WARNING: After assignment 'm_done' callback will be in undefined state.\n    Assign assign(m_expression, other);\n    Executor::runAsync(assign, m_device, std::move(m_done));\n\n    return *this;\n  }\n\n protected:\n  const ThreadPoolDevice& m_device;\n  ExpressionType& m_expression;\n  DoneCallback m_done;\n};\n#endif\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_DEVICE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceCuda.h",
    "content": "\n#if defined(__clang__) || defined(__GNUC__)\n#warning \"Deprecated header file, please either include the main Eigen/CXX11/Tensor header or the respective TensorDeviceGpu.h file\"\n#endif\n\n#include \"TensorDeviceGpu.h\"\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceDefault.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_DEVICE_DEFAULT_H\n#define EIGEN_CXX11_TENSOR_TENSOR_DEVICE_DEFAULT_H\n\n\nnamespace Eigen {\n\n// Default device for the machine (typically a single cpu core)\nstruct DefaultDevice {\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void* allocate(size_t num_bytes) const {\n    return internal::aligned_malloc(num_bytes);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void deallocate(void* buffer) const {\n    internal::aligned_free(buffer);\n  }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void* allocate_temp(size_t num_bytes) const {\n    return allocate(num_bytes);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void deallocate_temp(void* buffer) const {\n    deallocate(buffer);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memcpy(void* dst, const void* src, size_t n) const {\n    ::memcpy(dst, src, n);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memcpyHostToDevice(void* dst, const void* src, size_t n) const {\n    memcpy(dst, src, n);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memcpyDeviceToHost(void* dst, const void* src, size_t n) const {\n    memcpy(dst, src, n);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memset(void* buffer, int c, size_t n) const {\n    ::memset(buffer, c, n);\n  }\n  template<typename Type>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Type get(Type data) const { \n    return data;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE size_t numThreads() const {\n#if !defined(EIGEN_GPU_COMPILE_PHASE)\n    // Running on the host CPU\n    return 1;\n#elif defined(EIGEN_HIP_DEVICE_COMPILE)\n    // Running on a HIP device\n    return 64;\n#else\n    // Running on a CUDA device\n    return 32;\n#endif\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE size_t firstLevelCacheSize() const {\n#if !defined(EIGEN_GPU_COMPILE_PHASE) && !defined(SYCL_DEVICE_ONLY)\n    // Running on the host CPU\n    return l1CacheSize();\n#elif defined(EIGEN_HIP_DEVICE_COMPILE)\n    // Running on a HIP device\n    return 48*1024; // FIXME : update this number for HIP\n#else\n    // Running on a CUDA device, return the amount of shared memory available.\n    return 48*1024;\n#endif\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE size_t lastLevelCacheSize() const {\n#if !defined(EIGEN_GPU_COMPILE_PHASE) && !defined(SYCL_DEVICE_ONLY)\n    // Running single threaded on the host CPU\n    return l3CacheSize();\n#elif defined(EIGEN_HIP_DEVICE_COMPILE)\n    // Running on a HIP device\n    return firstLevelCacheSize(); // FIXME : update this number for HIP\n#else\n    // Running on a CUDA device\n    return firstLevelCacheSize();\n#endif\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int majorDeviceVersion() const {\n#if !defined(EIGEN_GPU_COMPILE_PHASE)\n    // Running single threaded on the host CPU\n    // Should return an enum that encodes the ISA supported by the CPU\n    return 1;\n#elif defined(EIGEN_HIP_DEVICE_COMPILE)\n    // Running on a HIP device\n    // return 1 as major for HIP\n    return 1;\n#else\n    // Running on a CUDA device\n    return EIGEN_CUDA_ARCH / 100;\n#endif\n  }\n};\n\n}  // namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_DEVICE_DEFAULT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceGpu.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#if defined(EIGEN_USE_GPU) && !defined(EIGEN_CXX11_TENSOR_TENSOR_DEVICE_GPU_H)\n#define EIGEN_CXX11_TENSOR_TENSOR_DEVICE_GPU_H\n\n// This header file container defines fo gpu* macros which will resolve to\n// their equivalent hip* or cuda* versions depending on the compiler in use\n// A separate header (included at the end of this file) will undefine all \n#include \"TensorGpuHipCudaDefines.h\"\n\nnamespace Eigen {\n\nstatic const int kGpuScratchSize = 1024;\n\n// This defines an interface that GPUDevice can take to use\n// HIP / CUDA streams underneath.\nclass StreamInterface {\n public:\n  virtual ~StreamInterface() {}\n\n  virtual const gpuStream_t& stream() const = 0;\n  virtual const gpuDeviceProp_t& deviceProperties() const = 0;\n\n  // Allocate memory on the actual device where the computation will run\n  virtual void* allocate(size_t num_bytes) const = 0;\n  virtual void deallocate(void* buffer) const = 0;\n\n  // Return a scratchpad buffer of size 1k\n  virtual void* scratchpad() const = 0;\n\n  // Return a semaphore. The semaphore is initially initialized to 0, and\n  // each kernel using it is responsible for resetting to 0 upon completion\n  // to maintain the invariant that the semaphore is always equal to 0 upon\n  // each kernel start.\n  virtual unsigned int* semaphore() const = 0;\n};\n\nstatic gpuDeviceProp_t* m_deviceProperties;\nstatic bool m_devicePropInitialized = false;\n\nstatic void initializeDeviceProp() {\n  if (!m_devicePropInitialized) {\n    // Attempts to ensure proper behavior in the case of multiple threads\n    // calling this function simultaneously. This would be trivial to\n    // implement if we could use std::mutex, but unfortunately mutex don't\n    // compile with nvcc, so we resort to atomics and thread fences instead.\n    // Note that if the caller uses a compiler that doesn't support c++11 we\n    // can't ensure that the initialization is thread safe.\n    static std::atomic<bool> first(true);\n    if (first.exchange(false)) {\n      // We're the first thread to reach this point.\n      int num_devices;\n      gpuError_t status = gpuGetDeviceCount(&num_devices);\n      if (status != gpuSuccess) {\n        std::cerr << \"Failed to get the number of GPU devices: \"\n                  << gpuGetErrorString(status)\n                  << std::endl;\n        gpu_assert(status == gpuSuccess);\n      }\n      m_deviceProperties = new gpuDeviceProp_t[num_devices];\n      for (int i = 0; i < num_devices; ++i) {\n        status = gpuGetDeviceProperties(&m_deviceProperties[i], i);\n        if (status != gpuSuccess) {\n          std::cerr << \"Failed to initialize GPU device #\"\n                    << i\n                    << \": \"\n                    << gpuGetErrorString(status)\n                    << std::endl;\n          gpu_assert(status == gpuSuccess);\n        }\n      }\n\n      std::atomic_thread_fence(std::memory_order_release);\n      m_devicePropInitialized = true;\n    } else {\n      // Wait for the other thread to inititialize the properties.\n      while (!m_devicePropInitialized) {\n        std::atomic_thread_fence(std::memory_order_acquire);\n        std::this_thread::sleep_for(std::chrono::milliseconds(1000));\n      }\n    }\n  }\n}\n\nstatic const gpuStream_t default_stream = gpuStreamDefault;\n\nclass GpuStreamDevice : public StreamInterface {\n public:\n  // Use the default stream on the current device\n  GpuStreamDevice() : stream_(&default_stream), scratch_(NULL), semaphore_(NULL) {\n    gpuGetDevice(&device_);\n    initializeDeviceProp();\n  }\n  // Use the default stream on the specified device\n  GpuStreamDevice(int device) : stream_(&default_stream), device_(device), scratch_(NULL), semaphore_(NULL) {\n    initializeDeviceProp();\n  }\n  // Use the specified stream. Note that it's the\n  // caller responsibility to ensure that the stream can run on\n  // the specified device. If no device is specified the code\n  // assumes that the stream is associated to the current gpu device.\n  GpuStreamDevice(const gpuStream_t* stream, int device = -1)\n      : stream_(stream), device_(device), scratch_(NULL), semaphore_(NULL) {\n    if (device < 0) {\n      gpuGetDevice(&device_);\n    } else {\n      int num_devices;\n      gpuError_t err = gpuGetDeviceCount(&num_devices);\n      EIGEN_UNUSED_VARIABLE(err)\n      gpu_assert(err == gpuSuccess);\n      gpu_assert(device < num_devices);\n      device_ = device;\n    }\n    initializeDeviceProp();\n  }\n\n  virtual ~GpuStreamDevice() {\n    if (scratch_) {\n      deallocate(scratch_);\n    }\n  }\n\n  const gpuStream_t& stream() const { return *stream_; }\n  const gpuDeviceProp_t& deviceProperties() const {\n    return m_deviceProperties[device_];\n  }\n  virtual void* allocate(size_t num_bytes) const {\n    gpuError_t err = gpuSetDevice(device_);\n    EIGEN_UNUSED_VARIABLE(err)\n    gpu_assert(err == gpuSuccess);\n    void* result;\n    err = gpuMalloc(&result, num_bytes);\n    gpu_assert(err == gpuSuccess);\n    gpu_assert(result != NULL);\n    return result;\n  }\n  virtual void deallocate(void* buffer) const {\n    gpuError_t err = gpuSetDevice(device_);\n    EIGEN_UNUSED_VARIABLE(err)\n    gpu_assert(err == gpuSuccess);\n    gpu_assert(buffer != NULL);\n    err = gpuFree(buffer);\n    gpu_assert(err == gpuSuccess);\n  }\n\n  virtual void* scratchpad() const {\n    if (scratch_ == NULL) {\n      scratch_ = allocate(kGpuScratchSize + sizeof(unsigned int));\n    }\n    return scratch_;\n  }\n\n  virtual unsigned int* semaphore() const {\n    if (semaphore_ == NULL) {\n      char* scratch = static_cast<char*>(scratchpad()) + kGpuScratchSize;\n      semaphore_ = reinterpret_cast<unsigned int*>(scratch);\n      gpuError_t err = gpuMemsetAsync(semaphore_, 0, sizeof(unsigned int), *stream_);\n      EIGEN_UNUSED_VARIABLE(err)\n      gpu_assert(err == gpuSuccess);\n    }\n    return semaphore_;\n  }\n\n private:\n  const gpuStream_t* stream_;\n  int device_;\n  mutable void* scratch_;\n  mutable unsigned int* semaphore_;\n};\n\nstruct GpuDevice {\n  // The StreamInterface is not owned: the caller is\n  // responsible for its initialization and eventual destruction.\n  explicit GpuDevice(const StreamInterface* stream) : stream_(stream), max_blocks_(INT_MAX) {\n    eigen_assert(stream);\n  }\n  explicit GpuDevice(const StreamInterface* stream, int num_blocks) : stream_(stream), max_blocks_(num_blocks) {\n    eigen_assert(stream);\n  }\n  // TODO(bsteiner): This is an internal API, we should not expose it.\n  EIGEN_STRONG_INLINE const gpuStream_t& stream() const {\n    return stream_->stream();\n  }\n\n  EIGEN_STRONG_INLINE void* allocate(size_t num_bytes) const {\n    return stream_->allocate(num_bytes);\n  }\n\n  EIGEN_STRONG_INLINE void deallocate(void* buffer) const {\n    stream_->deallocate(buffer);\n  }\n\n  EIGEN_STRONG_INLINE void* allocate_temp(size_t num_bytes) const {\n    return stream_->allocate(num_bytes);\n  }\n\n  EIGEN_STRONG_INLINE void deallocate_temp(void* buffer) const {\n    stream_->deallocate(buffer);\n  }\n\n  template<typename Type>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Type get(Type data) const { \n    return data;\n  }\n\n  EIGEN_STRONG_INLINE void* scratchpad() const {\n    return stream_->scratchpad();\n  }\n\n  EIGEN_STRONG_INLINE unsigned int* semaphore() const {\n    return stream_->semaphore();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memcpy(void* dst, const void* src, size_t n) const {\n#ifndef EIGEN_GPU_COMPILE_PHASE\n    gpuError_t err = gpuMemcpyAsync(dst, src, n, gpuMemcpyDeviceToDevice,\n                                      stream_->stream());\n    EIGEN_UNUSED_VARIABLE(err)\n    gpu_assert(err == gpuSuccess);\n#else\n    EIGEN_UNUSED_VARIABLE(dst);\n    EIGEN_UNUSED_VARIABLE(src);\n    EIGEN_UNUSED_VARIABLE(n);\n    eigen_assert(false && \"The default device should be used instead to generate kernel code\");\n#endif\n  }\n\n  EIGEN_STRONG_INLINE void memcpyHostToDevice(void* dst, const void* src, size_t n) const {\n    gpuError_t err =\n        gpuMemcpyAsync(dst, src, n, gpuMemcpyHostToDevice, stream_->stream());\n    EIGEN_UNUSED_VARIABLE(err)\n    gpu_assert(err == gpuSuccess);\n  }\n\n  EIGEN_STRONG_INLINE void memcpyDeviceToHost(void* dst, const void* src, size_t n) const {\n    gpuError_t err =\n        gpuMemcpyAsync(dst, src, n, gpuMemcpyDeviceToHost, stream_->stream());\n    EIGEN_UNUSED_VARIABLE(err)\n    gpu_assert(err == gpuSuccess);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void memset(void* buffer, int c, size_t n) const {\n#ifndef EIGEN_GPU_COMPILE_PHASE\n    gpuError_t err = gpuMemsetAsync(buffer, c, n, stream_->stream());\n    EIGEN_UNUSED_VARIABLE(err)\n    gpu_assert(err == gpuSuccess);\n#else\n  eigen_assert(false && \"The default device should be used instead to generate kernel code\");\n#endif\n  }\n\n  EIGEN_STRONG_INLINE size_t numThreads() const {\n    // FIXME\n    return 32;\n  }\n\n  EIGEN_STRONG_INLINE size_t firstLevelCacheSize() const {\n    // FIXME\n    return 48*1024;\n  }\n\n  EIGEN_STRONG_INLINE size_t lastLevelCacheSize() const {\n    // We won't try to take advantage of the l2 cache for the time being, and\n    // there is no l3 cache on hip/cuda devices.\n    return firstLevelCacheSize();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void synchronize() const {\n#ifndef EIGEN_GPU_COMPILE_PHASE\n    gpuError_t err = gpuStreamSynchronize(stream_->stream());\n    if (err != gpuSuccess) {\n      std::cerr << \"Error detected in GPU stream: \"\n                << gpuGetErrorString(err)\n                << std::endl;\n      gpu_assert(err == gpuSuccess);\n    }\n#else\n    gpu_assert(false && \"The default device should be used instead to generate kernel code\");\n#endif\n  }\n\n  EIGEN_STRONG_INLINE int getNumGpuMultiProcessors() const {\n    return stream_->deviceProperties().multiProcessorCount;\n  }\n  EIGEN_STRONG_INLINE int maxGpuThreadsPerBlock() const {\n    return stream_->deviceProperties().maxThreadsPerBlock;\n  }\n  EIGEN_STRONG_INLINE int maxGpuThreadsPerMultiProcessor() const {\n    return stream_->deviceProperties().maxThreadsPerMultiProcessor;\n  }\n  EIGEN_STRONG_INLINE int sharedMemPerBlock() const {\n    return stream_->deviceProperties().sharedMemPerBlock;\n  }\n  EIGEN_STRONG_INLINE int majorDeviceVersion() const {\n    return stream_->deviceProperties().major;\n  }\n  EIGEN_STRONG_INLINE int minorDeviceVersion() const {\n    return stream_->deviceProperties().minor;\n  }\n\n  EIGEN_STRONG_INLINE int maxBlocks() const {\n    return max_blocks_;\n  }\n\n  // This function checks if the GPU runtime recorded an error for the\n  // underlying stream device.\n  inline bool ok() const {\n#ifdef EIGEN_GPUCC\n    gpuError_t error = gpuStreamQuery(stream_->stream());\n    return (error == gpuSuccess) || (error == gpuErrorNotReady);\n#else\n    return false;\n#endif\n  }\n\n private:\n  const StreamInterface* stream_;\n  int max_blocks_;\n};\n\n#if defined(EIGEN_HIPCC)\n\n#define LAUNCH_GPU_KERNEL(kernel, gridsize, blocksize, sharedmem, device, ...)             \\\n  hipLaunchKernelGGL(kernel, dim3(gridsize), dim3(blocksize), (sharedmem), (device).stream(), __VA_ARGS__); \\\n  gpu_assert(hipGetLastError() == hipSuccess);\n\n#else\n \n#define LAUNCH_GPU_KERNEL(kernel, gridsize, blocksize, sharedmem, device, ...)             \\\n  (kernel) <<< (gridsize), (blocksize), (sharedmem), (device).stream() >>> (__VA_ARGS__);   \\\n  gpu_assert(cudaGetLastError() == cudaSuccess);\n\n#endif\n \n// FIXME: Should be device and kernel specific.\n#ifdef EIGEN_GPUCC\nstatic EIGEN_DEVICE_FUNC inline void setGpuSharedMemConfig(gpuSharedMemConfig config) {\n#ifndef EIGEN_GPU_COMPILE_PHASE\n  gpuError_t status = gpuDeviceSetSharedMemConfig(config);\n  EIGEN_UNUSED_VARIABLE(status)\n  gpu_assert(status == gpuSuccess);\n#else\n  EIGEN_UNUSED_VARIABLE(config)\n#endif\n}\n#endif\n\n}  // end namespace Eigen\n\n// undefine all the gpu* macros we defined at the beginning of the file\n#include \"TensorGpuHipCudaUndefines.h\"\n\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_DEVICE_GPU_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceSycl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#if defined(EIGEN_USE_SYCL) && !defined(EIGEN_CXX11_TENSOR_TENSOR_DEVICE_SYCL_H)\n#define EIGEN_CXX11_TENSOR_TENSOR_DEVICE_SYCL_H\n#include <unordered_set>\n\nnamespace Eigen {\n\nnamespace TensorSycl {\nnamespace internal {\n\n/// Cache all the device information needed\nstruct SyclDeviceInfo {\n  SyclDeviceInfo(cl::sycl::queue queue)\n      : local_mem_type(\n            queue.get_device()\n                .template get_info<cl::sycl::info::device::local_mem_type>()),\n        max_work_item_sizes(\n            queue.get_device()\n                .template get_info<\n                    cl::sycl::info::device::max_work_item_sizes>()),\n        max_mem_alloc_size(\n            queue.get_device()\n                .template get_info<\n                    cl::sycl::info::device::max_mem_alloc_size>()),\n        max_compute_units(queue.get_device()\n                              .template get_info<\n                                  cl::sycl::info::device::max_compute_units>()),\n        max_work_group_size(\n            queue.get_device()\n                .template get_info<\n                    cl::sycl::info::device::max_work_group_size>()),\n        local_mem_size(\n            queue.get_device()\n                .template get_info<cl::sycl::info::device::local_mem_size>()),\n        platform_name(queue.get_device()\n                          .get_platform()\n                          .template get_info<cl::sycl::info::platform::name>()),\n        device_name(queue.get_device()\n                        .template get_info<cl::sycl::info::device::name>()),\n        device_vendor(\n            queue.get_device()\n                .template get_info<cl::sycl::info::device::vendor>()) {}\n\n  cl::sycl::info::local_mem_type local_mem_type;\n  cl::sycl::id<3> max_work_item_sizes;\n  unsigned long max_mem_alloc_size;\n  unsigned long max_compute_units;\n  unsigned long max_work_group_size;\n  size_t local_mem_size;\n  std::string platform_name;\n  std::string device_name;\n  std::string device_vendor;\n};\n\n}  // end namespace internal\n}  // end namespace TensorSycl\n\ntypedef TensorSycl::internal::buffer_data_type_t buffer_scalar_t;\n// All devices (even AMD CPU with intel OpenCL runtime) that support OpenCL and\n// can consume SPIR or SPIRV can use the Eigen SYCL backend and consequently\n// TensorFlow via the Eigen SYCL Backend.\nEIGEN_STRONG_INLINE auto get_sycl_supported_devices()\n    -> decltype(cl::sycl::device::get_devices()) {\n#ifdef EIGEN_SYCL_USE_DEFAULT_SELECTOR\n  return {cl::sycl::device(cl::sycl::default_selector())};\n#else\n  std::vector<cl::sycl::device> supported_devices;\n  auto platform_list = cl::sycl::platform::get_platforms();\n  for (const auto &platform : platform_list) {\n    auto device_list = platform.get_devices();\n    auto platform_name =\n        platform.template get_info<cl::sycl::info::platform::name>();\n    std::transform(platform_name.begin(), platform_name.end(),\n                   platform_name.begin(), ::tolower);\n    for (const auto &device : device_list) {\n      auto vendor = device.template get_info<cl::sycl::info::device::vendor>();\n      std::transform(vendor.begin(), vendor.end(), vendor.begin(), ::tolower);\n      bool unsupported_condition =\n          (device.is_cpu() && platform_name.find(\"amd\") != std::string::npos &&\n           vendor.find(\"apu\") == std::string::npos) ||\n          (platform_name.find(\"experimental\") != std::string::npos) ||\n          device.is_host();\n      if (!unsupported_condition) {\n        supported_devices.push_back(device);\n      }\n    }\n  }\n  return supported_devices;\n#endif\n}\n\nclass QueueInterface {\n public:\n  /// Creating device by using cl::sycl::selector or cl::sycl::device.\n  template <typename DeviceOrSelector>\n  explicit QueueInterface(\n      const DeviceOrSelector &dev_or_sel, cl::sycl::async_handler handler,\n      unsigned num_threads = std::thread::hardware_concurrency())\n      : m_queue(dev_or_sel, handler),\n#ifdef EIGEN_SYCL_USE_PROGRAM_CLASS\n        m_prog(m_queue.get_context(), get_sycl_supported_devices()),\n#endif\n        m_thread_pool(num_threads),\n        m_device_info(m_queue) {\n#ifdef EIGEN_SYCL_USE_PROGRAM_CLASS\n    m_prog.build_with_kernel_type<DeviceOrSelector>();\n    auto f = [&](cl::sycl::handler &cgh) {\n      cgh.single_task<DeviceOrSelector>(m_prog.get_kernel<DeviceOrSelector>(),\n                                        [=]() {})\n    };\n    EIGEN_SYCL_TRY_CATCH(m_queue.submit(f));\n#endif\n  }\n\n  template <typename DeviceOrSelector>\n  explicit QueueInterface(\n      const DeviceOrSelector &dev_or_sel,\n      unsigned num_threads = std::thread::hardware_concurrency())\n      : QueueInterface(dev_or_sel,\n                       [this](cl::sycl::exception_list l) {\n                         this->exception_caught_ = this->sycl_async_handler(l);\n                       },\n                       num_threads) {}\n\n#ifdef EIGEN_SYCL_USE_PROGRAM_CLASS\n  EIGEN_STRONG_INLINE cl::sycl::program &program() const { return m_prog; }\n#endif\n\n  /// Attach an existing buffer to the pointer map, Eigen will not reuse it\n  EIGEN_STRONG_INLINE void *attach_buffer(\n      cl::sycl::buffer<buffer_scalar_t, 1> &buf) const {\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n    return static_cast<void *>(pMapper.add_pointer(buf));\n  }\n\n  /// Detach previously attached buffer\n  EIGEN_STRONG_INLINE void detach_buffer(void *p) const {\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n    TensorSycl::internal::SYCLfree<false>(p, pMapper);\n  }\n\n  /// Allocating device pointer. This pointer is actually an 8 bytes host\n  /// pointer used as key to access the sycl device buffer. The reason is that\n  /// we cannot use device buffer as a pointer as a m_data in Eigen leafNode\n  /// expressions. So we create a key pointer to be used in Eigen expression\n  /// construction. When we convert the Eigen construction into the sycl\n  /// construction we use this pointer as a key in our buffer_map and we make\n  /// sure that we dedicate only one buffer only for this pointer. The device\n  /// pointer would be deleted by calling deallocate function.\n  EIGEN_STRONG_INLINE void *allocate(size_t num_bytes) const {\n#if EIGEN_MAX_ALIGN_BYTES > 0\n    size_t align = num_bytes % EIGEN_MAX_ALIGN_BYTES;\n    if (align > 0) {\n      num_bytes += EIGEN_MAX_ALIGN_BYTES - align;\n    }\n#endif\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n    return TensorSycl::internal::SYCLmalloc(num_bytes, pMapper);\n  }\n\n  EIGEN_STRONG_INLINE void *allocate_temp(size_t num_bytes) const {\n#if EIGEN_MAX_ALIGN_BYTES > 0\n    size_t align = num_bytes % EIGEN_MAX_ALIGN_BYTES;\n    if (align > 0) {\n      num_bytes += EIGEN_MAX_ALIGN_BYTES - align;\n    }\n#endif\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n#ifndef EIGEN_SYCL_NO_REUSE_BUFFERS\n    if (scratch_buffers.empty()) {\n      return TensorSycl::internal::SYCLmalloc(num_bytes, pMapper);\n      ;\n    } else {\n      for (auto it = scratch_buffers.begin(); it != scratch_buffers.end();) {\n        auto buff = pMapper.get_buffer(*it);\n        if (buff.get_size() >= num_bytes) {\n          auto ptr = *it;\n          scratch_buffers.erase(it);\n          return ptr;\n        } else {\n          ++it;\n        }\n      }\n      return TensorSycl::internal::SYCLmalloc(num_bytes, pMapper);\n    }\n#else\n    return TensorSycl::internal::SYCLmalloc(num_bytes, pMapper);\n#endif\n  }\n  template <typename data_t>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorSycl::internal::RangeAccess<\n      cl::sycl::access::mode::read_write, data_t>\n  get(data_t *data) const {\n    return get_range_accessor<cl::sycl::access::mode::read_write, data_t>(data);\n  }\n  template <typename data_t>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE data_t *get(\n      TensorSycl::internal::RangeAccess<cl::sycl::access::mode::read_write,\n                                        data_t>\n          data) const {\n    return static_cast<data_t *>(data.get_virtual_pointer());\n  }\n\n  EIGEN_STRONG_INLINE void deallocate_temp(void *p) const {\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n#ifndef EIGEN_SYCL_NO_REUSE_BUFFERS\n    scratch_buffers.insert(p);\n#else\n    TensorSycl::internal::SYCLfree(p, pMapper);\n#endif\n  }\n  template <cl::sycl::access::mode AcMd, typename T>\n  EIGEN_STRONG_INLINE void deallocate_temp(\n      const TensorSycl::internal::RangeAccess<AcMd, T> &p) const {\n    deallocate_temp(p.get_virtual_pointer());\n  }\n\n  /// This is used to deallocate the device pointer. p is used as a key inside\n  /// the map to find the device buffer and delete it.\n  EIGEN_STRONG_INLINE void deallocate(void *p) const {\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n    TensorSycl::internal::SYCLfree(p, pMapper);\n  }\n\n  EIGEN_STRONG_INLINE void deallocate_all() const {\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n    TensorSycl::internal::SYCLfreeAll(pMapper);\n#ifndef EIGEN_SYCL_NO_REUSE_BUFFERS\n    scratch_buffers.clear();\n#endif\n  }\n\n  /// The memcpyHostToDevice is used to copy the data from host to device\n  /// The destination pointer could be deleted before the copy happend which is\n  /// why a callback function is needed. By default if none is provided, the\n  /// function is blocking.\n  EIGEN_STRONG_INLINE void memcpyHostToDevice(\n      void *dst, const void *src, size_t n,\n      std::function<void()> callback) const {\n    static const auto write_mode = cl::sycl::access::mode::discard_write;\n    static const auto global_access = cl::sycl::access::target::global_buffer;\n    typedef cl::sycl::accessor<buffer_scalar_t, 1, write_mode, global_access>\n        write_accessor;\n    if (n == 0) {\n      if (callback) callback();\n      return;\n    }\n    n /= sizeof(buffer_scalar_t);\n    auto f = [&](cl::sycl::handler &cgh) {\n      write_accessor dst_acc = get_range_accessor<write_mode>(cgh, dst, n);\n      buffer_scalar_t const *ptr = static_cast<buffer_scalar_t const *>(src);\n      auto non_deleter = [](buffer_scalar_t const *) {};\n      std::shared_ptr<const buffer_scalar_t> s_ptr(ptr, non_deleter);\n      cgh.copy(s_ptr, dst_acc);\n    };\n    cl::sycl::event e;\n    EIGEN_SYCL_TRY_CATCH(e = m_queue.submit(f));\n    synchronize_and_callback(e, callback);\n  }\n\n  /// The memcpyDeviceToHost is used to copy the data from device to host.\n  /// The source pointer could be deleted before the copy happend which is\n  /// why a callback function is needed. By default if none is provided, the\n  /// function is blocking.\n  EIGEN_STRONG_INLINE void memcpyDeviceToHost(\n      void *dst, const void *src, size_t n,\n      std::function<void()> callback) const {\n    static const auto read_mode = cl::sycl::access::mode::read;\n    static const auto global_access = cl::sycl::access::target::global_buffer;\n    typedef cl::sycl::accessor<buffer_scalar_t, 1, read_mode, global_access>\n        read_accessor;\n    if (n == 0) {\n      if (callback) callback();\n      return;\n    }\n    n /= sizeof(buffer_scalar_t);\n    auto f = [&](cl::sycl::handler &cgh) {\n      read_accessor src_acc = get_range_accessor<read_mode>(cgh, src, n);\n      buffer_scalar_t *ptr = static_cast<buffer_scalar_t *>(dst);\n      auto non_deleter = [](buffer_scalar_t *) {};\n      std::shared_ptr<buffer_scalar_t> s_ptr(ptr, non_deleter);\n      cgh.copy(src_acc, s_ptr);\n    };\n    cl::sycl::event e;\n    EIGEN_SYCL_TRY_CATCH(e = m_queue.submit(f));\n    synchronize_and_callback(e, callback);\n  }\n\n  /// The memcpy function.\n  /// No callback is required here as both arguments are on the device\n  /// and SYCL can handle the dependency.\n  EIGEN_STRONG_INLINE void memcpy(void *dst, const void *src, size_t n) const {\n    static const auto read_mode = cl::sycl::access::mode::read;\n    static const auto write_mode = cl::sycl::access::mode::discard_write;\n    if (n == 0) {\n      return;\n    }\n    n /= sizeof(buffer_scalar_t);\n    auto f = [&](cl::sycl::handler &cgh) {\n      auto src_acc = get_range_accessor<read_mode>(cgh, src, n);\n      auto dst_acc = get_range_accessor<write_mode>(cgh, dst, n);\n      cgh.copy(src_acc, dst_acc);\n    };\n    cl::sycl::event e;\n    EIGEN_SYCL_TRY_CATCH(e = m_queue.submit(f));\n    async_synchronize(e);\n  }\n\n  /// the memset function.\n  /// No callback is required here as both arguments are on the device\n  /// and SYCL can handle the dependency.\n  EIGEN_STRONG_INLINE void memset(void *data, int c, size_t n) const {\n    static const auto write_mode = cl::sycl::access::mode::discard_write;\n    if (n == 0) {\n      return;\n    }\n    n /= sizeof(buffer_scalar_t);\n    auto f = [&](cl::sycl::handler &cgh) {\n      auto dst_acc = get_range_accessor<write_mode>(cgh, data, n);\n      // The cast to uint8_t is here to match the behaviour of the standard\n      // memset. The cast to buffer_scalar_t is needed to match the type of the\n      // accessor (in case buffer_scalar_t is not uint8_t)\n      cgh.fill(dst_acc, static_cast<buffer_scalar_t>(static_cast<uint8_t>(c)));\n    };\n    cl::sycl::event e;\n    EIGEN_SYCL_TRY_CATCH(e = m_queue.submit(f));\n    async_synchronize(e);\n  }\n\n  /// Get a range accessor to the virtual pointer's device memory. This range\n  /// accessor will allow access to the memory from the pointer to the end of\n  /// the buffer.\n  ///\n  /// NOTE: Inside a kernel the range accessor will always be indexed from the\n  /// start of the buffer, so the offset in the accessor is only used by\n  /// methods like handler::copy and will not be available inside a kernel.\n  template <cl::sycl::access::mode AcMd, typename T>\n  EIGEN_STRONG_INLINE TensorSycl::internal::RangeAccess<AcMd, T>\n  get_range_accessor(const void *ptr) const {\n    static const auto global_access = cl::sycl::access::target::global_buffer;\n    static const auto is_place_holder = cl::sycl::access::placeholder::true_t;\n    typedef TensorSycl::internal::RangeAccess<AcMd, T> ret_type;\n    typedef const TensorSycl::internal::buffer_data_type_t *internal_ptr_t;\n\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n\n    auto original_buffer = pMapper.get_buffer(ptr);\n    const ptrdiff_t offset = pMapper.get_offset(ptr);\n    const ptrdiff_t typed_offset = offset / sizeof(T);\n    eigen_assert(typed_offset >= 0);\n    const auto typed_size = original_buffer.get_size() / sizeof(T);\n    auto buffer = original_buffer.template reinterpret<\n        typename Eigen::internal::remove_const<T>::type>(\n        cl::sycl::range<1>(typed_size));\n    const ptrdiff_t size = buffer.get_count() - typed_offset;\n    eigen_assert(size >= 0);\n    typedef cl::sycl::accessor<typename Eigen::internal::remove_const<T>::type,\n                               1, AcMd, global_access, is_place_holder>\n        placeholder_accessor_t;\n    const auto start_ptr = static_cast<internal_ptr_t>(ptr) - offset;\n    return ret_type(placeholder_accessor_t(buffer, cl::sycl::range<1>(size),\n                                           cl::sycl::id<1>(typed_offset)),\n                    static_cast<size_t>(typed_offset),\n                    reinterpret_cast<std::intptr_t>(start_ptr));\n  }\n\n  /// Get a range accessor to the virtual pointer's device memory with a\n  /// specified size.\n  template <cl::sycl::access::mode AcMd, typename Index>\n  EIGEN_STRONG_INLINE cl::sycl::accessor<\n      buffer_scalar_t, 1, AcMd, cl::sycl::access::target::global_buffer>\n  get_range_accessor(cl::sycl::handler &cgh, const void *ptr,\n                     const Index n_bytes) const {\n    static const auto global_access = cl::sycl::access::target::global_buffer;\n    eigen_assert(n_bytes >= 0);\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n    auto buffer = pMapper.get_buffer(ptr);\n    const ptrdiff_t offset = pMapper.get_offset(ptr);\n    eigen_assert(offset >= 0);\n    eigen_assert(offset + n_bytes <= buffer.get_size());\n    return buffer.template get_access<AcMd, global_access>(\n        cgh, cl::sycl::range<1>(n_bytes), cl::sycl::id<1>(offset));\n  }\n\n  /// Creation of sycl accessor for a buffer. This function first tries to find\n  /// the buffer in the buffer_map. If found it gets the accessor from it, if\n  /// not, the function then adds an entry by creating a sycl buffer for that\n  /// particular pointer.\n  template <cl::sycl::access::mode AcMd>\n  EIGEN_STRONG_INLINE cl::sycl::accessor<\n      buffer_scalar_t, 1, AcMd, cl::sycl::access::target::global_buffer>\n  get_sycl_accessor(cl::sycl::handler &cgh, const void *ptr) const {\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n    return pMapper.get_buffer(ptr)\n        .template get_access<AcMd, cl::sycl::access::target::global_buffer>(\n            cgh);\n  }\n\n  EIGEN_STRONG_INLINE cl::sycl::buffer<buffer_scalar_t, 1> get_sycl_buffer(\n      const void *ptr) const {\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n    return pMapper.get_buffer(ptr);\n  }\n\n  EIGEN_STRONG_INLINE ptrdiff_t get_offset(const void *ptr) const {\n    std::lock_guard<std::mutex> lock(pmapper_mutex_);\n    return pMapper.get_offset(ptr);\n  }\n\n  template <typename OutScalar, typename sycl_kernel, typename Lhs,\n            typename Rhs, typename OutPtr, typename Range, typename Index,\n            typename... T>\n  EIGEN_ALWAYS_INLINE void binary_kernel_launcher(const Lhs &lhs,\n                                                  const Rhs &rhs, OutPtr outptr,\n                                                  Range thread_range,\n                                                  Index scratchSize,\n                                                  T... var) const {\n    auto kernel_functor = [=](cl::sycl::handler &cgh) {\n      // binding the placeholder accessors to a commandgroup handler\n      lhs.bind(cgh);\n      rhs.bind(cgh);\n      outptr.bind(cgh);\n      typedef cl::sycl::accessor<OutScalar, 1,\n                                 cl::sycl::access::mode::read_write,\n                                 cl::sycl::access::target::local>\n          LocalAccessor;\n\n      LocalAccessor scratch(cl::sycl::range<1>(scratchSize), cgh);\n      cgh.parallel_for(\n#ifdef EIGEN_SYCL_USE_PROGRAM_CLASS\n          program().template get_kernel<sycl_kernel>(),\n#endif\n          thread_range, sycl_kernel(scratch, lhs, rhs, outptr, var...));\n    };\n    cl::sycl::event e;\n    EIGEN_SYCL_TRY_CATCH(e = m_queue.submit(kernel_functor));\n    async_synchronize(e);\n  }\n\n  template <typename OutScalar, typename sycl_kernel, typename InPtr,\n            typename OutPtr, typename Range, typename Index, typename... T>\n  EIGEN_ALWAYS_INLINE void unary_kernel_launcher(const InPtr &inptr,\n                                                 OutPtr &outptr,\n                                                 Range thread_range,\n                                                 Index scratchSize,\n                                                 T... var) const {\n    auto kernel_functor = [=](cl::sycl::handler &cgh) {\n      // binding the placeholder accessors to a commandgroup handler\n      inptr.bind(cgh);\n      outptr.bind(cgh);\n      typedef cl::sycl::accessor<OutScalar, 1,\n                                 cl::sycl::access::mode::read_write,\n                                 cl::sycl::access::target::local>\n          LocalAccessor;\n\n      LocalAccessor scratch(cl::sycl::range<1>(scratchSize), cgh);\n      cgh.parallel_for(\n#ifdef EIGEN_SYCL_USE_PROGRAM_CLASS\n          program().template get_kernel<sycl_kernel>(),\n#endif\n          thread_range, sycl_kernel(scratch, inptr, outptr, var...));\n    };\n    cl::sycl::event e;\n    EIGEN_SYCL_TRY_CATCH(e = m_queue.submit(kernel_functor));\n    async_synchronize(e);\n  }\n\n    template <typename OutScalar, typename sycl_kernel, typename InPtr,\n           typename Range, typename Index, typename... T>\n  EIGEN_ALWAYS_INLINE void nullary_kernel_launcher(const InPtr &inptr,\n                                                 Range thread_range,\n                                                 Index scratchSize,\n                                                 T... var) const {\n    auto kernel_functor = [=](cl::sycl::handler &cgh) {\n      // binding the placeholder accessors to a commandgroup handler\n      inptr.bind(cgh);\n      typedef cl::sycl::accessor<OutScalar, 1,\n                                 cl::sycl::access::mode::read_write,\n                                 cl::sycl::access::target::local>\n          LocalAccessor;\n\n      LocalAccessor scratch(cl::sycl::range<1>(scratchSize), cgh);\n      cgh.parallel_for(\n#ifdef EIGEN_SYCL_USE_PROGRAM_CLASS\n          program().template get_kernel<sycl_kernel>(),\n#endif\n          thread_range, sycl_kernel(scratch, inptr, var...));\n    };\n    cl::sycl::event e;\n    EIGEN_SYCL_TRY_CATCH(e = m_queue.submit(kernel_functor));\n    async_synchronize(e);\n  }\n\n\n  EIGEN_STRONG_INLINE void synchronize() const {\n#ifdef EIGEN_EXCEPTIONS\n    m_queue.wait_and_throw();\n#else\n    m_queue.wait();\n#endif\n  }\n\n\n  EIGEN_STRONG_INLINE void async_synchronize(cl::sycl::event e) const {\n    set_latest_event(e);\n#ifndef EIGEN_SYCL_ASYNC_EXECUTION\n    synchronize();\n#endif\n  }\n\n  template <typename Index>\n  EIGEN_STRONG_INLINE void parallel_for_setup(Index n, Index &tileSize,\n                                              Index &rng, Index &GRange) const {\n    tileSize = static_cast<Index>(getNearestPowerOfTwoWorkGroupSize());\n    tileSize = std::min(static_cast<Index>(EIGEN_SYCL_LOCAL_THREAD_DIM0 *\n                                           EIGEN_SYCL_LOCAL_THREAD_DIM1),\n                        static_cast<Index>(tileSize));\n    rng = n;\n    if (rng == 0) rng = static_cast<Index>(1);\n    GRange = rng;\n    if (tileSize > GRange)\n      tileSize = GRange;\n    else if (GRange > tileSize) {\n      Index xMode = static_cast<Index>(GRange % tileSize);\n      if (xMode != 0) GRange += static_cast<Index>(tileSize - xMode);\n    }\n  }\n\n  /// This is used to prepare the number of threads and also the number of\n  /// threads per block for sycl kernels\n  template <typename Index>\n  EIGEN_STRONG_INLINE void parallel_for_setup(\n      const std::array<Index, 2> &input_dim, cl::sycl::range<2> &global_range,\n      cl::sycl::range<2> &local_range) const {\n    std::array<Index, 2> input_range = input_dim;\n    Index max_workgroup_Size =\n        static_cast<Index>(getNearestPowerOfTwoWorkGroupSize());\n    max_workgroup_Size =\n        std::min(static_cast<Index>(EIGEN_SYCL_LOCAL_THREAD_DIM0 *\n                                    EIGEN_SYCL_LOCAL_THREAD_DIM1),\n                 static_cast<Index>(max_workgroup_Size));\n    Index pow_of_2 = static_cast<Index>(std::log2(max_workgroup_Size));\n    local_range[1] =\n        static_cast<Index>(std::pow(2, static_cast<Index>(pow_of_2 / 2)));\n    input_range[1] = input_dim[1];\n    if (input_range[1] == 0) input_range[1] = static_cast<Index>(1);\n    global_range[1] = input_range[1];\n    if (local_range[1] > global_range[1])\n      local_range[1] = global_range[1];\n    else if (global_range[1] > local_range[1]) {\n      Index xMode = static_cast<Index>(global_range[1] % local_range[1]);\n      if (xMode != 0)\n        global_range[1] += static_cast<Index>(local_range[1] - xMode);\n    }\n    local_range[0] = static_cast<Index>(max_workgroup_Size / local_range[1]);\n    input_range[0] = input_dim[0];\n    if (input_range[0] == 0) input_range[0] = static_cast<Index>(1);\n    global_range[0] = input_range[0];\n    if (local_range[0] > global_range[0])\n      local_range[0] = global_range[0];\n    else if (global_range[0] > local_range[0]) {\n      Index xMode = static_cast<Index>(global_range[0] % local_range[0]);\n      if (xMode != 0)\n        global_range[0] += static_cast<Index>(local_range[0] - xMode);\n    }\n  }\n\n  /// This is used to prepare the number of threads and also the number of\n  /// threads per block for sycl kernels\n  template <typename Index>\n  EIGEN_STRONG_INLINE void parallel_for_setup(\n      const std::array<Index, 3> &input_dim, cl::sycl::range<3> &global_range,\n      cl::sycl::range<3> &local_range) const {\n    std::array<Index, 3> input_range = input_dim;\n    Index max_workgroup_Size =\n        static_cast<Index>(getNearestPowerOfTwoWorkGroupSize());\n    max_workgroup_Size =\n        std::min(static_cast<Index>(EIGEN_SYCL_LOCAL_THREAD_DIM0 *\n                                    EIGEN_SYCL_LOCAL_THREAD_DIM1),\n                 static_cast<Index>(max_workgroup_Size));\n    Index pow_of_2 = static_cast<Index>(std::log2(max_workgroup_Size));\n    local_range[2] =\n        static_cast<Index>(std::pow(2, static_cast<Index>(pow_of_2 / 3)));\n    input_range[2] = input_dim[2];\n    if (input_range[2] == 0) input_range[1] = static_cast<Index>(1);\n    global_range[2] = input_range[2];\n    if (local_range[2] > global_range[2])\n      local_range[2] = global_range[2];\n    else if (global_range[2] > local_range[2]) {\n      Index xMode = static_cast<Index>(global_range[2] % local_range[2]);\n      if (xMode != 0)\n        global_range[2] += static_cast<Index>(local_range[2] - xMode);\n    }\n    pow_of_2 = static_cast<Index>(\n        std::log2(static_cast<Index>(max_workgroup_Size / local_range[2])));\n    local_range[1] =\n        static_cast<Index>(std::pow(2, static_cast<Index>(pow_of_2 / 2)));\n    input_range[1] = input_dim[1];\n    if (input_range[1] == 0) input_range[1] = static_cast<Index>(1);\n    global_range[1] = input_range[1];\n    if (local_range[1] > global_range[1])\n      local_range[1] = global_range[1];\n    else if (global_range[1] > local_range[1]) {\n      Index xMode = static_cast<Index>(global_range[1] % local_range[1]);\n      if (xMode != 0)\n        global_range[1] += static_cast<Index>(local_range[1] - xMode);\n    }\n    local_range[0] = static_cast<Index>(max_workgroup_Size /\n                                        (local_range[1] * local_range[2]));\n    input_range[0] = input_dim[0];\n    if (input_range[0] == 0) input_range[0] = static_cast<Index>(1);\n    global_range[0] = input_range[0];\n    if (local_range[0] > global_range[0])\n      local_range[0] = global_range[0];\n    else if (global_range[0] > local_range[0]) {\n      Index xMode = static_cast<Index>(global_range[0] % local_range[0]);\n      if (xMode != 0)\n        global_range[0] += static_cast<Index>(local_range[0] - xMode);\n    }\n  }\n\n  EIGEN_STRONG_INLINE bool has_local_memory() const {\n#if !defined(EIGEN_SYCL_LOCAL_MEM) && defined(EIGEN_SYCL_NO_LOCAL_MEM)\n    return false;\n#elif defined(EIGEN_SYCL_LOCAL_MEM) && !defined(EIGEN_SYCL_NO_LOCAL_MEM)\n    return true;\n#else\n    return m_device_info.local_mem_type ==\n           cl::sycl::info::local_mem_type::local;\n#endif\n  }\n\n  EIGEN_STRONG_INLINE unsigned long max_buffer_size() const {\n    return m_device_info.max_mem_alloc_size;\n  }\n\n  EIGEN_STRONG_INLINE unsigned long getNumSyclMultiProcessors() const {\n    return m_device_info.max_compute_units;\n  }\n\n  EIGEN_STRONG_INLINE unsigned long maxSyclThreadsPerBlock() const {\n    return m_device_info.max_work_group_size;\n  }\n\n  EIGEN_STRONG_INLINE cl::sycl::id<3> maxWorkItemSizes() const {\n    return m_device_info.max_work_item_sizes;\n  }\n\n  /// No need for sycl it should act the same as CPU version\n  EIGEN_STRONG_INLINE int majorDeviceVersion() const { return 1; }\n\n  EIGEN_STRONG_INLINE unsigned long maxSyclThreadsPerMultiProcessor() const {\n    // OpenCL doesnot have such concept\n    return 2;\n  }\n\n  EIGEN_STRONG_INLINE size_t sharedMemPerBlock() const {\n    return m_device_info.local_mem_size;\n  }\n\n  // This function returns the nearest power of 2 Work-group size which is <=\n  // maximum device workgroup size.\n  EIGEN_STRONG_INLINE size_t getNearestPowerOfTwoWorkGroupSize() const {\n    return getPowerOfTwo(m_device_info.max_work_group_size, false);\n  }\n\n  EIGEN_STRONG_INLINE std::string getPlatformName() const {\n    return m_device_info.platform_name;\n  }\n\n  EIGEN_STRONG_INLINE std::string getDeviceName() const {\n    return m_device_info.device_name;\n  }\n\n  EIGEN_STRONG_INLINE std::string getDeviceVendor() const {\n    return m_device_info.device_vendor;\n  }\n\n  // This function returns the nearest power of 2\n  // if roundup is true returns result>=wgsize\n  // else it return result <= wgsize\n  EIGEN_STRONG_INLINE size_t getPowerOfTwo(size_t wGSize, bool roundUp) const {\n    if (roundUp) --wGSize;\n    wGSize |= (wGSize >> 1);\n    wGSize |= (wGSize >> 2);\n    wGSize |= (wGSize >> 4);\n    wGSize |= (wGSize >> 8);\n    wGSize |= (wGSize >> 16);\n#if EIGEN_ARCH_x86_64 || EIGEN_ARCH_ARM64 || EIGEN_OS_WIN64\n    wGSize |= (wGSize >> 32);\n#endif\n    return ((!roundUp) ? (wGSize - (wGSize >> 1)) : ++wGSize);\n  }\n\n  EIGEN_STRONG_INLINE cl::sycl::queue &sycl_queue() const { return m_queue; }\n\n  // This function checks if the runtime recorded an error for the\n  // underlying stream device.\n  EIGEN_STRONG_INLINE bool ok() const {\n    if (!exception_caught_) {\n      synchronize();\n    }\n    return !exception_caught_;\n  }\n\n  EIGEN_STRONG_INLINE cl::sycl::event get_latest_event() const {\n#ifdef EIGEN_SYCL_STORE_LATEST_EVENT\n    std::lock_guard<std::mutex> lock(event_mutex_);\n    return latest_events_[std::this_thread::get_id()];\n#else\n    eigen_assert(false);\n    return cl::sycl::event();\n#endif\n  }\n\n  // destructor\n  ~QueueInterface() {\n    pMapper.clear();\n#ifndef EIGEN_SYCL_NO_REUSE_BUFFERS\n    scratch_buffers.clear();\n#endif\n  }\n\n protected:\n  EIGEN_STRONG_INLINE void set_latest_event(cl::sycl::event e) const {\n#ifdef EIGEN_SYCL_STORE_LATEST_EVENT\n    std::lock_guard<std::mutex> lock(event_mutex_);\n    latest_events_[std::this_thread::get_id()] = e;\n#else\n    EIGEN_UNUSED_VARIABLE(e);\n#endif\n  }\n\n  void synchronize_and_callback(cl::sycl::event e,\n                                const std::function<void()> &callback) const {\n    set_latest_event(e);\n    if (callback) {\n      auto callback_ = [=]() {\n#ifdef EIGEN_EXCEPTIONS\n        cl::sycl::event(e).wait_and_throw();\n#else\n        cl::sycl::event(e).wait();\n#endif\n        callback();\n      };\n      m_thread_pool.Schedule(std::move(callback_));\n    } else {\n#ifdef EIGEN_EXCEPTIONS\n      m_queue.wait_and_throw();\n#else\n      m_queue.wait();\n#endif\n    }\n  }\n\n  bool sycl_async_handler(cl::sycl::exception_list exceptions) const {\n    bool exception_caught = false;\n    for (const auto &e : exceptions) {\n      if (e) {\n        exception_caught = true;\n        EIGEN_THROW_X(e);\n      }\n    }\n    return exception_caught;\n  }\n\n  /// class members:\n  bool exception_caught_ = false;\n\n  mutable std::mutex pmapper_mutex_;\n\n#ifdef EIGEN_SYCL_STORE_LATEST_EVENT\n  mutable std::mutex event_mutex_;\n  mutable std::unordered_map<std::thread::id, cl::sycl::event> latest_events_;\n#endif\n\n  /// std::map is the container used to make sure that we create only one buffer\n  /// per pointer. The lifespan of the buffer now depends on the lifespan of\n  /// SyclDevice. If a non-read-only pointer is needed to be accessed on the\n  /// host we should manually deallocate it.\n  mutable TensorSycl::internal::PointerMapper pMapper;\n#ifndef EIGEN_SYCL_NO_REUSE_BUFFERS\n  mutable std::unordered_set<void *> scratch_buffers;\n#endif\n  /// sycl queue\n  mutable cl::sycl::queue m_queue;\n#ifdef EIGEN_SYCL_USE_PROGRAM_CLASS\n  mutable cl::sycl::program m_prog;\n#endif\n\n  /// The thread pool is used to wait on events and call callbacks\n  /// asynchronously\n  mutable Eigen::ThreadPool m_thread_pool;\n\n  const TensorSycl::internal::SyclDeviceInfo m_device_info;\n};\n\nstruct SyclDeviceBase {\n  /// QueueInterface is not owned. it is the caller's responsibility to destroy\n  /// it\n  const QueueInterface *m_queue_stream;\n  explicit SyclDeviceBase(const QueueInterface *queue_stream)\n      : m_queue_stream(queue_stream) {}\n  EIGEN_STRONG_INLINE const QueueInterface *queue_stream() const {\n    return m_queue_stream;\n  }\n};\n\n// Here is a sycl device struct which accept the sycl queue interface\n// as an input\nstruct SyclDevice : public SyclDeviceBase {\n  explicit SyclDevice(const QueueInterface *queue_stream)\n      : SyclDeviceBase(queue_stream) {}\n\n  // this is the accessor used to construct the evaluator\n  template <cl::sycl::access::mode AcMd, typename T>\n  EIGEN_STRONG_INLINE TensorSycl::internal::RangeAccess<AcMd, T>\n  get_range_accessor(const void *ptr) const {\n    return queue_stream()->template get_range_accessor<AcMd, T>(ptr);\n  }\n\n  // get sycl accessor\n  template <cl::sycl::access::mode AcMd>\n  EIGEN_STRONG_INLINE cl::sycl::accessor<\n      buffer_scalar_t, 1, AcMd, cl::sycl::access::target::global_buffer>\n  get_sycl_accessor(cl::sycl::handler &cgh, const void *ptr) const {\n    return queue_stream()->template get_sycl_accessor<AcMd>(cgh, ptr);\n  }\n\n  /// Accessing the created sycl device buffer for the device pointer\n  EIGEN_STRONG_INLINE cl::sycl::buffer<buffer_scalar_t, 1> get_sycl_buffer(\n      const void *ptr) const {\n    return queue_stream()->get_sycl_buffer(ptr);\n  }\n\n  /// This is used to prepare the number of threads and also the number of\n  /// threads per block for sycl kernels\n  template <typename Index>\n  EIGEN_STRONG_INLINE void parallel_for_setup(Index n, Index &tileSize,\n                                              Index &rng, Index &GRange) const {\n    queue_stream()->parallel_for_setup(n, tileSize, rng, GRange);\n  }\n\n  /// This is used to prepare the number of threads and also the number of\n  /// threads per block for sycl kernels\n  template <typename Index>\n  EIGEN_STRONG_INLINE void parallel_for_setup(\n      const std::array<Index, 2> &input_dim, cl::sycl::range<2> &global_range,\n      cl::sycl::range<2> &local_range) const {\n    queue_stream()->parallel_for_setup(input_dim, global_range, local_range);\n  }\n\n  /// This is used to prepare the number of threads and also the number of\n  /// threads per block for sycl kernels\n  template <typename Index>\n  EIGEN_STRONG_INLINE void parallel_for_setup(\n      const std::array<Index, 3> &input_dim, cl::sycl::range<3> &global_range,\n      cl::sycl::range<3> &local_range) const {\n    queue_stream()->parallel_for_setup(input_dim, global_range, local_range);\n  }\n\n  /// allocate device memory\n  EIGEN_STRONG_INLINE void *allocate(size_t num_bytes) const {\n    return queue_stream()->allocate(num_bytes);\n  }\n\n  EIGEN_STRONG_INLINE void *allocate_temp(size_t num_bytes) const {\n    return queue_stream()->allocate_temp(num_bytes);\n  }\n\n  /// deallocate device memory\n  EIGEN_STRONG_INLINE void deallocate(void *p) const {\n    queue_stream()->deallocate(p);\n  }\n\n  EIGEN_STRONG_INLINE void deallocate_temp(void *buffer) const {\n    queue_stream()->deallocate_temp(buffer);\n  }\n  template <cl::sycl::access::mode AcMd, typename T>\n  EIGEN_STRONG_INLINE void deallocate_temp(\n      const TensorSycl::internal::RangeAccess<AcMd, T> &buffer) const {\n    queue_stream()->deallocate_temp(buffer);\n  }\n  EIGEN_STRONG_INLINE void deallocate_all() const {\n    queue_stream()->deallocate_all();\n  }\n\n  template <typename data_t>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorSycl::internal::RangeAccess<\n      cl::sycl::access::mode::read_write, data_t>\n  get(data_t *data) const {\n    return queue_stream()->get(data);\n  }\n  template <typename data_t>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE data_t *get(\n      TensorSycl::internal::RangeAccess<cl::sycl::access::mode::read_write,\n                                        data_t>\n          data) const {\n    return queue_stream()->get(data);\n  }\n\n  /// attach existing buffer\n  EIGEN_STRONG_INLINE void *attach_buffer(\n      cl::sycl::buffer<buffer_scalar_t, 1> &buf) const {\n    return queue_stream()->attach_buffer(buf);\n  }\n  /// detach buffer\n  EIGEN_STRONG_INLINE void detach_buffer(void *p) const {\n    queue_stream()->detach_buffer(p);\n  }\n  EIGEN_STRONG_INLINE ptrdiff_t get_offset(const void *ptr) const {\n    return queue_stream()->get_offset(ptr);\n  }\n\n  // some runtime conditions that can be applied here\n  EIGEN_STRONG_INLINE bool isDeviceSuitable() const { return true; }\n\n  /// memcpyHostToDevice\n  template <typename Index>\n  EIGEN_STRONG_INLINE void memcpyHostToDevice(\n      Index *dst, const Index *src, size_t n,\n      std::function<void()> callback = {}) const {\n    queue_stream()->memcpyHostToDevice(dst, src, n, callback);\n  }\n  /// memcpyDeviceToHost\n  template <typename Index>\n  EIGEN_STRONG_INLINE void memcpyDeviceToHost(\n      void *dst, const Index *src, size_t n,\n      std::function<void()> callback = {}) const {\n    queue_stream()->memcpyDeviceToHost(dst, src, n, callback);\n  }\n  /// the memcpy function\n  template <typename Index>\n  EIGEN_STRONG_INLINE void memcpy(void *dst, const Index *src, size_t n) const {\n    queue_stream()->memcpy(dst, src, n);\n  }\n  /// the memset function\n  EIGEN_STRONG_INLINE void memset(void *data, int c, size_t n) const {\n    queue_stream()->memset(data, c, n);\n  }\n  /// returning the sycl queue\n  EIGEN_STRONG_INLINE cl::sycl::queue &sycl_queue() const {\n    return queue_stream()->sycl_queue();\n  }\n#ifdef EIGEN_SYCL_USE_PROGRAM_CLASS\n  EIGEN_STRONG_INLINE cl::sycl::program &program() const {\n    return queue_stream()->program();\n  }\n#endif\n\n  EIGEN_STRONG_INLINE size_t firstLevelCacheSize() const { return 48 * 1024; }\n\n  EIGEN_STRONG_INLINE size_t lastLevelCacheSize() const {\n    // We won't try to take advantage of the l2 cache for the time being, and\n    // there is no l3 cache on sycl devices.\n    return firstLevelCacheSize();\n  }\n  EIGEN_STRONG_INLINE unsigned long getNumSyclMultiProcessors() const {\n    return queue_stream()->getNumSyclMultiProcessors();\n  }\n  EIGEN_STRONG_INLINE unsigned long maxSyclThreadsPerBlock() const {\n    return queue_stream()->maxSyclThreadsPerBlock();\n  }\n  EIGEN_STRONG_INLINE cl::sycl::id<3> maxWorkItemSizes() const {\n    return queue_stream()->maxWorkItemSizes();\n  }\n  EIGEN_STRONG_INLINE unsigned long maxSyclThreadsPerMultiProcessor() const {\n    // OpenCL doesnot have such concept\n    return queue_stream()->maxSyclThreadsPerMultiProcessor();\n  }\n  EIGEN_STRONG_INLINE size_t sharedMemPerBlock() const {\n    return queue_stream()->sharedMemPerBlock();\n  }\n  EIGEN_STRONG_INLINE size_t getNearestPowerOfTwoWorkGroupSize() const {\n    return queue_stream()->getNearestPowerOfTwoWorkGroupSize();\n  }\n\n  EIGEN_STRONG_INLINE size_t getPowerOfTwo(size_t val, bool roundUp) const {\n    return queue_stream()->getPowerOfTwo(val, roundUp);\n  }\n  /// No need for sycl it should act the same as CPU version\n  EIGEN_STRONG_INLINE int majorDeviceVersion() const {\n    return queue_stream()->majorDeviceVersion();\n  }\n\n  EIGEN_STRONG_INLINE void synchronize() const {\n    queue_stream()->synchronize();\n  }\n  EIGEN_STRONG_INLINE void async_synchronize(\n      cl::sycl::event e = cl::sycl::event()) const {\n    queue_stream()->async_synchronize(e);\n  }\n  EIGEN_STRONG_INLINE cl::sycl::event get_latest_event() const {\n    return queue_stream()->get_latest_event();\n  }\n\n  // This function checks if the runtime recorded an error for the\n  // underlying stream device.\n  EIGEN_STRONG_INLINE bool ok() const { return queue_stream()->ok(); }\n\n  EIGEN_STRONG_INLINE bool has_local_memory() const {\n    return queue_stream()->has_local_memory();\n  }\n  EIGEN_STRONG_INLINE long max_buffer_size() const {\n    return queue_stream()->max_buffer_size();\n  }\n  EIGEN_STRONG_INLINE std::string getPlatformName() const {\n    return queue_stream()->getPlatformName();\n  }\n  EIGEN_STRONG_INLINE std::string getDeviceName() const {\n    return queue_stream()->getDeviceName();\n  }\n  EIGEN_STRONG_INLINE std::string getDeviceVendor() const {\n    return queue_stream()->getDeviceVendor();\n  }\n  template <typename OutScalar, typename KernelType, typename... T>\n  EIGEN_ALWAYS_INLINE void binary_kernel_launcher(T... var) const {\n    queue_stream()->template binary_kernel_launcher<OutScalar, KernelType>(\n        var...);\n  }\n  template <typename OutScalar, typename KernelType, typename... T>\n  EIGEN_ALWAYS_INLINE void unary_kernel_launcher(T... var) const {\n    queue_stream()->template unary_kernel_launcher<OutScalar, KernelType>(\n        var...);\n  }\n\n  template <typename OutScalar, typename KernelType, typename... T>\n  EIGEN_ALWAYS_INLINE void nullary_kernel_launcher(T... var) const {\n    queue_stream()->template nullary_kernel_launcher<OutScalar, KernelType>(\n        var...);\n  }\n};\n}  // end namespace Eigen\n\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_DEVICE_SYCL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDeviceThreadPool.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#if defined(EIGEN_USE_THREADS) && !defined(EIGEN_CXX11_TENSOR_TENSOR_DEVICE_THREAD_POOL_H)\n#define EIGEN_CXX11_TENSOR_TENSOR_DEVICE_THREAD_POOL_H\n\nnamespace Eigen {\n\n// Runs an arbitrary function and then calls Notify() on the passed in\n// Notification.\ntemplate <typename Function, typename... Args> struct FunctionWrapperWithNotification\n{\n  static void run(Notification* n, Function f, Args... args) {\n    f(args...);\n    if (n) {\n      n->Notify();\n    }\n  }\n};\n\ntemplate <typename Function, typename... Args> struct FunctionWrapperWithBarrier\n{\n  static void run(Barrier* b, Function f, Args... args) {\n    f(args...);\n    if (b) {\n      b->Notify();\n    }\n  }\n};\n\ntemplate <typename SyncType>\nstatic EIGEN_STRONG_INLINE void wait_until_ready(SyncType* n) {\n  if (n) {\n    n->Wait();\n  }\n}\n\n// An abstract interface to a device specific memory allocator.\nclass Allocator {\n public:\n  virtual ~Allocator() {}\n  virtual void* allocate(size_t num_bytes) const = 0;\n  virtual void deallocate(void* buffer) const = 0;\n};\n\n// Build a thread pool device on top the an existing pool of threads.\nstruct ThreadPoolDevice {\n  // The ownership of the thread pool remains with the caller.\n  ThreadPoolDevice(ThreadPoolInterface* pool, int num_cores, Allocator* allocator = nullptr)\n      : pool_(pool), num_threads_(num_cores), allocator_(allocator) { }\n\n  EIGEN_STRONG_INLINE void* allocate(size_t num_bytes) const {\n    return allocator_ ? allocator_->allocate(num_bytes)\n        : internal::aligned_malloc(num_bytes);\n  }\n\n  EIGEN_STRONG_INLINE void deallocate(void* buffer) const {\n    if (allocator_) {\n      allocator_->deallocate(buffer);\n    } else {\n      internal::aligned_free(buffer);\n    }\n  }\n\n    EIGEN_STRONG_INLINE void* allocate_temp(size_t num_bytes) const {\n    return allocate(num_bytes);\n  }\n\n  EIGEN_STRONG_INLINE void deallocate_temp(void* buffer) const {\n    deallocate(buffer);\n  }\n\n  template<typename Type>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Type get(Type data) const {\n    return data;\n  }\n\n  EIGEN_STRONG_INLINE void memcpy(void* dst, const void* src, size_t n) const {\n#ifdef __ANDROID__\n    ::memcpy(dst, src, n);\n#else\n    // TODO(rmlarsen): Align blocks on cache lines.\n    // We have observed that going beyond 4 threads usually just wastes\n    // CPU cycles due to the threads competing for memory bandwidth, so we\n    // statically schedule at most 4 block copies here.\n    const size_t kMinBlockSize = 32768;\n    const size_t num_threads = CostModel::numThreads(n, TensorOpCost(1.0, 1.0, 0), 4);\n    if (n <= kMinBlockSize || num_threads < 2) {\n      ::memcpy(dst, src, n);\n    } else {\n      const char* src_ptr = static_cast<const char*>(src);\n      char* dst_ptr = static_cast<char*>(dst);\n      const size_t blocksize = (n + (num_threads - 1)) / num_threads;\n      Barrier barrier(static_cast<int>(num_threads - 1));\n      // Launch the last 3 blocks on worker threads.\n      for (size_t i = 1; i < num_threads; ++i) {\n        enqueue_with_barrier(&barrier, [n, i, src_ptr, dst_ptr, blocksize] {\n          ::memcpy(dst_ptr + i * blocksize, src_ptr + i * blocksize,\n                   numext::mini(blocksize, n - (i * blocksize)));\n        });\n      }\n      // Launch the first block on the main thread.\n      ::memcpy(dst_ptr, src_ptr, blocksize);\n      barrier.Wait();\n    }\n#endif\n  }\n  EIGEN_STRONG_INLINE void memcpyHostToDevice(void* dst, const void* src, size_t n) const {\n    memcpy(dst, src, n);\n  }\n  EIGEN_STRONG_INLINE void memcpyDeviceToHost(void* dst, const void* src, size_t n) const {\n    memcpy(dst, src, n);\n  }\n\n  EIGEN_STRONG_INLINE void memset(void* buffer, int c, size_t n) const {\n    ::memset(buffer, c, n);\n  }\n\n  EIGEN_STRONG_INLINE int numThreads() const {\n    return num_threads_;\n  }\n\n  // Number of theads available in the underlying thread pool. This number can\n  // be different from the value returned by numThreads().\n  EIGEN_STRONG_INLINE int numThreadsInPool() const {\n    return pool_->NumThreads();\n  }\n\n  EIGEN_STRONG_INLINE size_t firstLevelCacheSize() const {\n    return l1CacheSize();\n  }\n\n  EIGEN_STRONG_INLINE size_t lastLevelCacheSize() const {\n    // The l3 cache size is shared between all the cores.\n    return l3CacheSize() / num_threads_;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE int majorDeviceVersion() const {\n    // Should return an enum that encodes the ISA supported by the CPU\n    return 1;\n  }\n\n  template <class Function, class... Args>\n  EIGEN_STRONG_INLINE Notification* enqueue(Function&& f,\n                                            Args&&... args) const {\n    Notification* n = new Notification();\n    pool_->Schedule(\n        std::bind(&FunctionWrapperWithNotification<Function, Args...>::run, n,\n                  std::move(f), args...));\n    return n;\n  }\n\n  template <class Function, class... Args>\n  EIGEN_STRONG_INLINE void enqueue_with_barrier(Barrier* b, Function&& f,\n                                                Args&&... args) const {\n    pool_->Schedule(\n        std::bind(&FunctionWrapperWithBarrier<Function, Args...>::run, b,\n                  std::move(f), args...));\n  }\n\n  template <class Function, class... Args>\n  EIGEN_STRONG_INLINE void enqueueNoNotification(Function&& f,\n                                                 Args&&... args) const {\n    if (sizeof...(args) > 0) {\n      pool_->Schedule(std::bind(std::move(f), args...));\n    } else {\n      pool_->Schedule(std::move(f));\n    }\n  }\n\n  // Returns a logical thread index between 0 and pool_->NumThreads() - 1 if\n  // called from one of the threads in pool_. Returns -1 otherwise.\n  EIGEN_STRONG_INLINE int currentThreadId() const {\n    return pool_->CurrentThreadId();\n  }\n\n  // WARNING: This function is synchronous and will block the calling thread.\n  //\n  // Synchronous parallelFor executes f with [0, n) arguments in parallel and\n  // waits for completion. F accepts a half-open interval [first, last). Block\n  // size is chosen based on the iteration cost and resulting parallel\n  // efficiency. If block_align is not nullptr, it is called to round up the\n  // block size.\n  void parallelFor(Index n, const TensorOpCost& cost,\n                   std::function<Index(Index)> block_align,\n                   std::function<void(Index, Index)> f) const {\n    if (EIGEN_PREDICT_FALSE(n <= 0)){\n      return;\n    // Compute small problems directly in the caller thread.\n    } else if (n == 1 || numThreads() == 1 ||\n               CostModel::numThreads(n, cost, static_cast<int>(numThreads())) == 1) {\n      f(0, n);\n      return;\n    }\n\n    // Compute block size and total count of blocks.\n    ParallelForBlock block = CalculateParallelForBlock(n, cost, block_align);\n\n    // Recursively divide size into halves until we reach block_size.\n    // Division code rounds mid to block_size, so we are guaranteed to get\n    // block_count leaves that do actual computations.\n    Barrier barrier(static_cast<unsigned int>(block.count));\n    std::function<void(Index, Index)> handleRange;\n    handleRange = [=, &handleRange, &barrier, &f](Index firstIdx,\n                                                  Index lastIdx) {\n      while (lastIdx - firstIdx > block.size) {\n        // Split into halves and schedule the second half on a different thread.\n        const Index midIdx = firstIdx + divup((lastIdx - firstIdx) / 2, block.size) * block.size;\n        pool_->Schedule([=, &handleRange]() { handleRange(midIdx, lastIdx); });\n        lastIdx = midIdx;\n      }\n      // Single block or less, execute directly.\n      f(firstIdx, lastIdx);\n      barrier.Notify();\n    };\n\n    if (block.count <= numThreads()) {\n      // Avoid a thread hop by running the root of the tree and one block on the\n      // main thread.\n      handleRange(0, n);\n    } else {\n      // Execute the root in the thread pool to avoid running work on more than\n      // numThreads() threads.\n      pool_->Schedule([=, &handleRange]() { handleRange(0, n); });\n    }\n\n    barrier.Wait();\n  }\n\n  // Convenience wrapper for parallelFor that does not align blocks.\n  void parallelFor(Index n, const TensorOpCost& cost,\n                   std::function<void(Index, Index)> f) const {\n    parallelFor(n, cost, nullptr, std::move(f));\n  }\n\n  // WARNING: This function is asynchronous and will not block the calling thread.\n  //\n  // Asynchronous parallelFor executes f with [0, n) arguments in parallel\n  // without waiting for completion. When the last block finished, it will call\n  // 'done' callback. F accepts a half-open interval [first, last). Block size\n  // is chosen based on the iteration cost and resulting parallel efficiency. If\n  // block_align is not nullptr, it is called to round up the block size.\n  void parallelForAsync(Index n, const TensorOpCost& cost,\n                        std::function<Index(Index)> block_align,\n                        std::function<void(Index, Index)> f,\n                        std::function<void()> done) const {\n    // Compute small problems directly in the caller thread.\n    if (n <= 1 || numThreads() == 1 ||\n        CostModel::numThreads(n, cost, static_cast<int>(numThreads())) == 1) {\n      f(0, n);\n      done();\n      return;\n    }\n\n    // Compute block size and total count of blocks.\n    ParallelForBlock block = CalculateParallelForBlock(n, cost, block_align);\n\n    ParallelForAsyncContext* const ctx =\n        new ParallelForAsyncContext(block.count, std::move(f), std::move(done));\n\n    // Recursively divide size into halves until we reach block_size.\n    // Division code rounds mid to block_size, so we are guaranteed to get\n    // block_count leaves that do actual computations.\n    ctx->handle_range = [this, ctx, block](Index firstIdx, Index lastIdx) {\n      while (lastIdx - firstIdx > block.size) {\n        // Split into halves and schedule the second half on a different thread.\n        const Index midIdx = firstIdx + divup((lastIdx - firstIdx) / 2, block.size) * block.size;\n        pool_->Schedule(\n            [ctx, midIdx, lastIdx]() { ctx->handle_range(midIdx, lastIdx); });\n        lastIdx = midIdx;\n      }\n\n      // Single block or less, execute directly.\n      ctx->f(firstIdx, lastIdx);\n\n      // Delete async context if it was the last block.\n      if (ctx->count.fetch_sub(1) == 1) delete ctx;\n    };\n\n    if (block.count <= numThreads()) {\n      // Avoid a thread hop by running the root of the tree and one block on the\n      // main thread.\n      ctx->handle_range(0, n);\n    } else {\n      // Execute the root in the thread pool to avoid running work on more than\n      // numThreads() threads.\n      pool_->Schedule([ctx, n]() { ctx->handle_range(0, n); });\n    }\n  }\n\n  // Convenience wrapper for parallelForAsync that does not align blocks.\n  void parallelForAsync(Index n, const TensorOpCost& cost,\n                        std::function<void(Index, Index)> f,\n                        std::function<void()> done) const {\n    parallelForAsync(n, cost, nullptr, std::move(f), std::move(done));\n  }\n\n  // Thread pool accessor.\n  ThreadPoolInterface* getPool() const { return pool_; }\n\n  // Allocator accessor.\n  Allocator* allocator() const { return allocator_; }\n\n private:\n  typedef TensorCostModel<ThreadPoolDevice> CostModel;\n\n  // For parallelForAsync we must keep passed in closures on the heap, and\n  // delete them only after `done` callback finished.\n  struct ParallelForAsyncContext {\n    ParallelForAsyncContext(Index block_count,\n                            std::function<void(Index, Index)> block_f,\n                            std::function<void()> done_callback)\n        : count(block_count),\n          f(std::move(block_f)),\n          done(std::move(done_callback)) {}\n    ~ParallelForAsyncContext() { done(); }\n\n    std::atomic<Index> count;\n    std::function<void(Index, Index)> f;\n    std::function<void()> done;\n\n    std::function<void(Index, Index)> handle_range;\n  };\n\n  struct ParallelForBlock {\n    Index size;   // block size\n    Index count;  // number of blocks\n  };\n\n  // Calculates block size based on (1) the iteration cost and (2) parallel\n  // efficiency. We want blocks to be not too small to mitigate parallelization\n  // overheads; not too large to mitigate tail effect and potential load\n  // imbalance and we also want number of blocks to be evenly dividable across\n  // threads.\n  ParallelForBlock CalculateParallelForBlock(\n      const Index n, const TensorOpCost& cost,\n      std::function<Index(Index)> block_align) const {\n    const double block_size_f = 1.0 / CostModel::taskSize(1, cost);\n    const Index max_oversharding_factor = 4;\n    Index block_size = numext::mini(\n        n, numext::maxi<Index>(\n               divup<Index>(n, max_oversharding_factor * numThreads()),\n               block_size_f));\n    const Index max_block_size = numext::mini(n, 2 * block_size);\n\n    if (block_align) {\n      Index new_block_size = block_align(block_size);\n      eigen_assert(new_block_size >= block_size);\n      block_size = numext::mini(n, new_block_size);\n    }\n\n    Index block_count = divup(n, block_size);\n\n    // Calculate parallel efficiency as fraction of total CPU time used for\n    // computations:\n    double max_efficiency =\n        static_cast<double>(block_count) /\n        (divup<int>(block_count, numThreads()) * numThreads());\n\n    // Now try to increase block size up to max_block_size as long as it\n    // doesn't decrease parallel efficiency.\n    for (Index prev_block_count = block_count;\n         max_efficiency < 1.0 && prev_block_count > 1;) {\n      // This is the next block size that divides size into a smaller number\n      // of blocks than the current block_size.\n      Index coarser_block_size = divup(n, prev_block_count - 1);\n      if (block_align) {\n        Index new_block_size = block_align(coarser_block_size);\n        eigen_assert(new_block_size >= coarser_block_size);\n        coarser_block_size = numext::mini(n, new_block_size);\n      }\n      if (coarser_block_size > max_block_size) {\n        break;  // Reached max block size. Stop.\n      }\n      // Recalculate parallel efficiency.\n      const Index coarser_block_count = divup(n, coarser_block_size);\n      eigen_assert(coarser_block_count < prev_block_count);\n      prev_block_count = coarser_block_count;\n      const double coarser_efficiency =\n          static_cast<double>(coarser_block_count) /\n          (divup<int>(coarser_block_count, numThreads()) * numThreads());\n      if (coarser_efficiency + 0.01 >= max_efficiency) {\n        // Taking it.\n        block_size = coarser_block_size;\n        block_count = coarser_block_count;\n        if (max_efficiency < coarser_efficiency) {\n          max_efficiency = coarser_efficiency;\n        }\n      }\n    }\n\n    return {block_size, block_count};\n  }\n\n  ThreadPoolInterface* pool_;\n  int num_threads_;\n  Allocator* allocator_;\n};\n\n\n}  // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_DEVICE_THREAD_POOL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDimensionList.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_DIMENSION_LIST_H\n#define EIGEN_CXX11_TENSOR_TENSOR_DIMENSION_LIST_H\n\nnamespace Eigen {\n\n/** \\internal\n  *\n  * \\class TensorDimensionList\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Special case of tensor index list used to list all the dimensions of a tensor of rank n.\n  *\n  * \\sa Tensor\n  */\n\ntemplate <typename Index, std::size_t Rank> struct DimensionList {\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  const Index operator[] (const Index i) const { return i; }\n};\n\nnamespace internal {\n\ntemplate<typename Index, std::size_t Rank> struct array_size<DimensionList<Index, Rank> > {\n  static const size_t value = Rank;\n};\ntemplate<typename Index, std::size_t Rank> struct array_size<const DimensionList<Index, Rank> > {\n  static const size_t value = Rank;\n};\n\ntemplate<DenseIndex n, typename Index, std::size_t Rank> const Index array_get(DimensionList<Index, Rank>&) {\n  return n;\n}\ntemplate<DenseIndex n, typename Index, std::size_t Rank> const Index array_get(const DimensionList<Index, Rank>&) {\n  return n;\n}\n\n\n#if EIGEN_HAS_CONSTEXPR\ntemplate <typename Index, std::size_t Rank>\nstruct index_known_statically_impl<DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex) {\n    return true;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct index_known_statically_impl<const DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex) {\n    return true;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct all_indices_known_statically_impl<DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run() {\n    return true;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct all_indices_known_statically_impl<const DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run() {\n    return true;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct indices_statically_known_to_increase_impl<DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run() {\n    return true;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct indices_statically_known_to_increase_impl<const DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run() {\n    return true;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_eq_impl<DimensionList<Index, Rank> > {\n  static constexpr bool run(const DenseIndex i, const DenseIndex value) {\n    return i == value;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_eq_impl<const DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) {\n    return i == value;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_ne_impl<DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) {\n    return i != value;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_ne_impl<const DimensionList<Index, Rank> > {\n  static constexpr bool run(const DenseIndex i, const DenseIndex value) {\n    return i != value;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_gt_impl<DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) {\n    return i > value;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_gt_impl<const DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) {\n    return i > value;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_lt_impl<DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) {\n    return i < value;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_lt_impl<const DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const DenseIndex i, const DenseIndex value) {\n    return i < value;\n  }\n};\n\n#else\ntemplate <typename Index, std::size_t Rank>\nstruct index_known_statically_impl<DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static EIGEN_ALWAYS_INLINE bool run(const DenseIndex) {\n    return true;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct index_known_statically_impl<const DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static EIGEN_ALWAYS_INLINE bool run(const DenseIndex) {\n    return true;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct all_indices_known_statically_impl<DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static EIGEN_ALWAYS_INLINE bool run() {\n    return true;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct all_indices_known_statically_impl<const DimensionList<Index, Rank> > {\n  EIGEN_DEVICE_FUNC static EIGEN_ALWAYS_INLINE bool run() {\n    return true;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct indices_statically_known_to_increase_impl<DimensionList<Index, Rank> > {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run() {\n    return true;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct indices_statically_known_to_increase_impl<const DimensionList<Index, Rank> > {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run() {\n    return true;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_eq_impl<DimensionList<Index, Rank> > {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) {\n    return false;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_eq_impl<const DimensionList<Index, Rank> > {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) {\n    return false;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_ne_impl<DimensionList<Index, Rank> > {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex){\n    return false;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_ne_impl<const DimensionList<Index, Rank> > {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) {\n    return false;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_gt_impl<DimensionList<Index, Rank> > {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) {\n    return false;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_gt_impl<const DimensionList<Index, Rank> > {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) {\n    return false;\n  }\n};\n\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_lt_impl<DimensionList<Index, Rank> > {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) {\n    return false;\n  }\n};\ntemplate <typename Index, std::size_t Rank>\nstruct index_statically_lt_impl<const DimensionList<Index, Rank> > {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const DenseIndex, const DenseIndex) {\n    return false;\n  }\n};\n#endif\n\n}  // end namespace internal\n}  // end namespace Eigen\n\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_DIMENSION_LIST_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorDimensions.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_DIMENSIONS_H\n#define EIGEN_CXX11_TENSOR_TENSOR_DIMENSIONS_H\n\n\nnamespace Eigen {\n\n/** \\internal\n  *\n  * \\class TensorDimensions\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Set of classes used to encode and store the dimensions of a Tensor.\n  *\n  * The Sizes class encodes as part of the type the number of dimensions and the\n  * sizes corresponding to each dimension. It uses no storage space since it is\n  * entirely known at compile time.\n  * The DSizes class is its dynamic sibling: the number of dimensions is known\n  * at compile time but the sizes are set during execution.\n  *\n  * \\sa Tensor\n  */\n\n// Boilerplate code\nnamespace internal {\n\ntemplate<std::ptrdiff_t n, typename Dimension> struct dget {\n  static const std::ptrdiff_t value = get<n, Dimension>::value;\n};\n\n\ntemplate<typename Index, std::ptrdiff_t NumIndices, std::ptrdiff_t n, bool RowMajor>\nstruct fixed_size_tensor_index_linearization_helper\n{\n  template <typename Dimensions> EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Index run(array<Index, NumIndices> const& indices,\n                          const Dimensions& dimensions)\n  {\n    return array_get<RowMajor ? n - 1 : (NumIndices - n)>(indices) +\n        dget<RowMajor ? n - 1 : (NumIndices - n), Dimensions>::value *\n        fixed_size_tensor_index_linearization_helper<Index, NumIndices, n - 1, RowMajor>::run(indices, dimensions);\n  }\n};\n\ntemplate<typename Index, std::ptrdiff_t NumIndices, bool RowMajor>\nstruct fixed_size_tensor_index_linearization_helper<Index, NumIndices, 0, RowMajor>\n{\n  template <typename Dimensions> EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Index run(array<Index, NumIndices> const&, const Dimensions&)\n  {\n    return 0;\n  }\n};\n\ntemplate<typename Index, std::ptrdiff_t n>\nstruct fixed_size_tensor_index_extraction_helper\n{\n  template <typename Dimensions> EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Index run(const Index index,\n                          const Dimensions& dimensions)\n  {\n    const Index mult = (index == n-1) ? 1 : 0;\n    return array_get<n-1>(dimensions) * mult +\n        fixed_size_tensor_index_extraction_helper<Index, n - 1>::run(index, dimensions);\n  }\n};\n\ntemplate<typename Index>\nstruct fixed_size_tensor_index_extraction_helper<Index, 0>\n{\n  template <typename Dimensions> EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Index run(const Index,\n                          const Dimensions&)\n  {\n    return 0;\n  }\n  };\n\n}  // end namespace internal\n\n\n// Fixed size\n#ifndef EIGEN_EMULATE_CXX11_META_H\ntemplate <typename std::ptrdiff_t... Indices>\nstruct Sizes {\n  typedef internal::numeric_list<std::ptrdiff_t, Indices...> Base;\n  const Base t = Base();\n  static const std::ptrdiff_t total_size = internal::arg_prod(Indices...);\n  static const ptrdiff_t count = Base::count;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t rank() const {\n    return Base::count;\n  }\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t TotalSize() {\n    return internal::arg_prod(Indices...);\n  }\n\n  EIGEN_DEVICE_FUNC Sizes() { }\n  template <typename DenseIndex>\n  explicit EIGEN_DEVICE_FUNC Sizes(const array<DenseIndex, Base::count>& /*indices*/) {\n    // todo: add assertion\n  }\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  template <typename... DenseIndex> EIGEN_DEVICE_FUNC Sizes(DenseIndex...) { }\n  explicit EIGEN_DEVICE_FUNC Sizes(std::initializer_list<std::ptrdiff_t> /*l*/) {\n    // todo: add assertion\n  }\n#endif\n\n  template <typename T> Sizes& operator = (const T& /*other*/) {\n    // add assertion failure if the size of other is different\n    return *this;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t operator[] (const std::ptrdiff_t index) const {\n    return internal::fixed_size_tensor_index_extraction_helper<std::ptrdiff_t, Base::count>::run(index, t);\n  }\n\n  template <typename DenseIndex> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  ptrdiff_t IndexOfColMajor(const array<DenseIndex, Base::count>& indices) const {\n    return internal::fixed_size_tensor_index_linearization_helper<DenseIndex, Base::count, Base::count, false>::run(indices, t);\n  }\n  template <typename DenseIndex> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  ptrdiff_t IndexOfRowMajor(const array<DenseIndex, Base::count>& indices) const {\n    return internal::fixed_size_tensor_index_linearization_helper<DenseIndex, Base::count, Base::count, true>::run(indices, t);\n  }\n};\n\nnamespace internal {\ntemplate <typename std::ptrdiff_t... Indices>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t array_prod(const Sizes<Indices...>&) {\n  return Sizes<Indices...>::total_size;\n}\n}\n\n#else\n\ntemplate <std::ptrdiff_t n>\nstruct non_zero_size {\n  typedef internal::type2val<std::ptrdiff_t, n> type;\n};\ntemplate <>\nstruct non_zero_size<0> {\n  typedef internal::null_type type;\n};\n\ntemplate <std::ptrdiff_t V1=0, std::ptrdiff_t V2=0, std::ptrdiff_t V3=0, std::ptrdiff_t V4=0, std::ptrdiff_t V5=0> struct Sizes {\n  typedef typename internal::make_type_list<typename non_zero_size<V1>::type, typename non_zero_size<V2>::type, typename non_zero_size<V3>::type, typename non_zero_size<V4>::type, typename non_zero_size<V5>::type >::type Base;\n  static const std::ptrdiff_t count = Base::count;\n  static const std::ptrdiff_t total_size = internal::arg_prod<Base>::value;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ptrdiff_t rank() const {\n    return count;\n  }\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ptrdiff_t TotalSize() {\n    return internal::arg_prod<Base>::value;\n  }\n\n  Sizes() { }\n  template <typename DenseIndex>\n  explicit Sizes(const array<DenseIndex, Base::count>& /*indices*/) {\n    // todo: add assertion\n  }\n  template <typename T> Sizes& operator = (const T& /*other*/) {\n    // add assertion failure if the size of other is different\n    return *this;\n  }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  template <typename... DenseIndex> Sizes(DenseIndex... /*indices*/) { }\n  explicit Sizes(std::initializer_list<std::ptrdiff_t>) {\n    // todo: add assertion\n  }\n#else\n  EIGEN_DEVICE_FUNC explicit Sizes(const DenseIndex) {\n  }\n  EIGEN_DEVICE_FUNC Sizes(const DenseIndex, const DenseIndex) {\n  }\n  EIGEN_DEVICE_FUNC Sizes(const DenseIndex, const DenseIndex, const DenseIndex) {\n  }\n  EIGEN_DEVICE_FUNC Sizes(const DenseIndex, const DenseIndex, const DenseIndex, const DenseIndex) {\n  }\n  EIGEN_DEVICE_FUNC Sizes(const DenseIndex, const DenseIndex, const DenseIndex, const DenseIndex, const DenseIndex) {\n  }\n#endif\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index operator[] (const Index index) const {\n    switch (index) {\n      case 0:\n        return internal::get<0, Base>::value;\n      case 1:\n        return internal::get<1, Base>::value;\n      case 2:\n        return internal::get<2, Base>::value;\n      case 3:\n        return internal::get<3, Base>::value;\n      case 4:\n        return internal::get<4, Base>::value;\n      default:\n        eigen_assert(false && \"index overflow\");\n        return static_cast<Index>(-1);\n    }\n  }\n\n  template <typename DenseIndex> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  ptrdiff_t IndexOfColMajor(const array<DenseIndex, Base::count>& indices) const {\n    return internal::fixed_size_tensor_index_linearization_helper<DenseIndex, Base::count, Base::count, false>::run(indices, *reinterpret_cast<const Base*>(this));\n  }\n  template <typename DenseIndex> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  ptrdiff_t IndexOfRowMajor(const array<DenseIndex, Base::count>& indices) const {\n    return internal::fixed_size_tensor_index_linearization_helper<DenseIndex, Base::count, Base::count, true>::run(indices, *reinterpret_cast<const Base*>(this));\n  }\n};\n\nnamespace internal {\ntemplate <std::ptrdiff_t V1, std::ptrdiff_t V2, std::ptrdiff_t V3, std::ptrdiff_t V4, std::ptrdiff_t V5>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t array_prod(const Sizes<V1, V2, V3, V4, V5>&) {\n  return Sizes<V1, V2, V3, V4, V5>::total_size;\n}\n}\n\n#endif\n\n// Boilerplate\nnamespace internal {\ntemplate<typename Index, std::ptrdiff_t NumIndices, std::ptrdiff_t n, bool RowMajor>\nstruct tensor_index_linearization_helper\n{\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  Index run(array<Index, NumIndices> const& indices, array<Index, NumIndices> const& dimensions)\n  {\n    return array_get<RowMajor ? n : (NumIndices - n - 1)>(indices) +\n      array_get<RowMajor ? n : (NumIndices - n - 1)>(dimensions) *\n        tensor_index_linearization_helper<Index, NumIndices, n - 1, RowMajor>::run(indices, dimensions);\n  }\n};\n\ntemplate<typename Index, std::ptrdiff_t NumIndices, bool RowMajor>\nstruct tensor_index_linearization_helper<Index, NumIndices, 0, RowMajor>\n{\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  Index run(array<Index, NumIndices> const& indices, array<Index, NumIndices> const&)\n  {\n    return array_get<RowMajor ? 0 : NumIndices - 1>(indices);\n  }\n};\n}  // end namespace internal\n\n\n\n// Dynamic size\ntemplate <typename DenseIndex, int NumDims>\nstruct DSizes : array<DenseIndex, NumDims> {\n  typedef array<DenseIndex, NumDims> Base;\n  static const int count = NumDims;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index rank() const {\n    return NumDims;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex TotalSize() const {\n    return (NumDims == 0) ? 1 : internal::array_prod(*static_cast<const Base*>(this));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DSizes() {\n    for (int i = 0 ; i < NumDims; ++i) {\n      (*this)[i] = 0;\n    }\n  }\n  EIGEN_DEVICE_FUNC explicit DSizes(const array<DenseIndex, NumDims>& a) : Base(a) { }\n\n  EIGEN_DEVICE_FUNC explicit DSizes(const DenseIndex i0) {\n    eigen_assert(NumDims == 1);\n    (*this)[0] = i0;\n  }\n\n  EIGEN_DEVICE_FUNC DSizes(const DimensionList<DenseIndex, NumDims>& a) {\n    for (int i = 0 ; i < NumDims; ++i) {\n      (*this)[i] = a[i];\n    }\n  }\n\n  // Enable DSizes index type promotion only if we are promoting to the\n  // larger type, e.g. allow to promote dimensions of type int to long.\n  template<typename OtherIndex>\n  EIGEN_DEVICE_FUNC\n  explicit DSizes(const array<OtherIndex, NumDims>& other,\n                  // Default template parameters require c++11.\n                  typename internal::enable_if<\n                     internal::is_same<\n                         DenseIndex,\n                         typename internal::promote_index_type<\n                             DenseIndex,\n                             OtherIndex\n                         >::type\n                     >::value, void*>::type = 0) {\n    for (int i = 0; i < NumDims; ++i) {\n      (*this)[i] = static_cast<DenseIndex>(other[i]);\n    }\n  }\n\n#ifdef EIGEN_HAS_INDEX_LIST\n  template <typename FirstType, typename... OtherTypes>\n  EIGEN_DEVICE_FUNC\n  explicit DSizes(const Eigen::IndexList<FirstType, OtherTypes...>& dimensions) {\n    for (int i = 0; i < dimensions.count; ++i) {\n      (*this)[i] = dimensions[i];\n    }\n  }\n#endif\n\n#ifndef EIGEN_EMULATE_CXX11_META_H\n  template <typename std::ptrdiff_t... Indices>\n  EIGEN_DEVICE_FUNC DSizes(const Sizes<Indices...>& a) {\n    for (int i = 0 ; i < NumDims; ++i) {\n      (*this)[i] = a[i];\n    }\n  }\n#else\n  template <std::ptrdiff_t V1, std::ptrdiff_t V2, std::ptrdiff_t V3, std::ptrdiff_t V4, std::ptrdiff_t V5>\n  EIGEN_DEVICE_FUNC DSizes(const Sizes<V1, V2, V3, V4, V5>& a) {\n    for (int i = 0 ; i < NumDims; ++i) {\n      (*this)[i] = a[i];\n    }\n  }\n#endif\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  template<typename... IndexTypes> EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE explicit DSizes(DenseIndex firstDimension, DenseIndex secondDimension, IndexTypes... otherDimensions) : Base({{firstDimension, secondDimension, otherDimensions...}}) {\n    EIGEN_STATIC_ASSERT(sizeof...(otherDimensions) + 2 == NumDims, YOU_MADE_A_PROGRAMMING_MISTAKE)\n  }\n#else\n  EIGEN_DEVICE_FUNC DSizes(const DenseIndex i0, const DenseIndex i1) {\n    eigen_assert(NumDims == 2);\n    (*this)[0] = i0;\n    (*this)[1] = i1;\n  }\n  EIGEN_DEVICE_FUNC DSizes(const DenseIndex i0, const DenseIndex i1, const DenseIndex i2) {\n    eigen_assert(NumDims == 3);\n    (*this)[0] = i0;\n    (*this)[1] = i1;\n    (*this)[2] = i2;\n  }\n  EIGEN_DEVICE_FUNC DSizes(const DenseIndex i0, const DenseIndex i1, const DenseIndex i2, const DenseIndex i3) {\n    eigen_assert(NumDims == 4);\n    (*this)[0] = i0;\n    (*this)[1] = i1;\n    (*this)[2] = i2;\n    (*this)[3] = i3;\n  }\n  EIGEN_DEVICE_FUNC DSizes(const DenseIndex i0, const DenseIndex i1, const DenseIndex i2, const DenseIndex i3, const DenseIndex i4) {\n    eigen_assert(NumDims == 5);\n    (*this)[0] = i0;\n    (*this)[1] = i1;\n    (*this)[2] = i2;\n    (*this)[3] = i3;\n    (*this)[4] = i4;\n  }\n#endif\n\n  EIGEN_DEVICE_FUNC DSizes& operator = (const array<DenseIndex, NumDims>& other) {\n    *static_cast<Base*>(this) = other;\n    return *this;\n  }\n\n  // A constexpr would be so much better here\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex IndexOfColMajor(const array<DenseIndex, NumDims>& indices) const {\n    return internal::tensor_index_linearization_helper<DenseIndex, NumDims, NumDims - 1, false>::run(indices, *static_cast<const Base*>(this));\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE DenseIndex IndexOfRowMajor(const array<DenseIndex, NumDims>& indices) const {\n    return internal::tensor_index_linearization_helper<DenseIndex, NumDims, NumDims - 1, true>::run(indices, *static_cast<const Base*>(this));\n  }\n};\n\ntemplate <typename IndexType, int NumDims>\nstd::ostream& operator<<(std::ostream& os,\n                         const DSizes<IndexType, NumDims>& dims) {\n  os << \"[\";\n  for (int i = 0; i < NumDims; ++i) {\n    if (i > 0) os << \", \";\n    os << dims[i];\n  }\n  os << \"]\";\n  return os;\n}\n\n// Boilerplate\nnamespace internal {\ntemplate<typename Index, std::ptrdiff_t NumIndices, std::ptrdiff_t n, bool RowMajor>\nstruct tensor_vsize_index_linearization_helper\n{\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  Index run(array<Index, NumIndices> const& indices, std::vector<DenseIndex> const& dimensions)\n  {\n    return array_get<RowMajor ? n : (NumIndices - n - 1)>(indices) +\n      array_get<RowMajor ? n : (NumIndices - n - 1)>(dimensions) *\n        tensor_vsize_index_linearization_helper<Index, NumIndices, n - 1, RowMajor>::run(indices, dimensions);\n  }\n};\n\ntemplate<typename Index, std::ptrdiff_t NumIndices, bool RowMajor>\nstruct tensor_vsize_index_linearization_helper<Index, NumIndices, 0, RowMajor>\n{\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  Index run(array<Index, NumIndices> const& indices, std::vector<DenseIndex> const&)\n  {\n    return array_get<RowMajor ? 0 : NumIndices - 1>(indices);\n  }\n};\n}  // end namespace internal\n\n\nnamespace internal {\n\ntemplate <typename DenseIndex, int NumDims> struct array_size<const DSizes<DenseIndex, NumDims> > {\n  static const ptrdiff_t value = NumDims;\n};\ntemplate <typename DenseIndex, int NumDims> struct array_size<DSizes<DenseIndex, NumDims> > {\n  static const ptrdiff_t value = NumDims;\n};\n#ifndef EIGEN_EMULATE_CXX11_META_H\ntemplate <typename std::ptrdiff_t... Indices> struct array_size<const Sizes<Indices...> > {\nstatic const std::ptrdiff_t value = Sizes<Indices...>::count;\n};\ntemplate <typename std::ptrdiff_t... Indices> struct array_size<Sizes<Indices...> > {\nstatic const std::ptrdiff_t value = Sizes<Indices...>::count;\n};\ntemplate <std::ptrdiff_t n, typename std::ptrdiff_t... Indices> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t array_get(const Sizes<Indices...>&) {\n  return get<n, internal::numeric_list<std::ptrdiff_t, Indices...> >::value;\n}\ntemplate <std::ptrdiff_t n> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t array_get(const Sizes<>&) {\n  eigen_assert(false && \"should never be called\");\n  return -1;\n}\n#else\ntemplate <std::ptrdiff_t V1, std::ptrdiff_t V2, std::ptrdiff_t V3, std::ptrdiff_t V4, std::ptrdiff_t V5> struct array_size<const Sizes<V1,V2,V3,V4,V5> > {\n  static const ptrdiff_t value = Sizes<V1,V2,V3,V4,V5>::count;\n};\ntemplate <std::ptrdiff_t V1, std::ptrdiff_t V2, std::ptrdiff_t V3, std::ptrdiff_t V4, std::ptrdiff_t V5> struct array_size<Sizes<V1,V2,V3,V4,V5> > {\n  static const ptrdiff_t value = Sizes<V1,V2,V3,V4,V5>::count;\n};\ntemplate <std::ptrdiff_t n, std::ptrdiff_t V1, std::ptrdiff_t V2, std::ptrdiff_t V3, std::ptrdiff_t V4, std::ptrdiff_t V5> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE std::ptrdiff_t array_get(const Sizes<V1,V2,V3,V4,V5>&) {\n  return get<n, typename Sizes<V1,V2,V3,V4,V5>::Base>::value;\n}\n\n#endif\n\n\ntemplate <typename Dims1, typename Dims2, ptrdiff_t n, ptrdiff_t m>\nstruct sizes_match_below_dim {\n  static EIGEN_DEVICE_FUNC  EIGEN_STRONG_INLINE bool run(Dims1&, Dims2&) {\n    return false;\n  }\n};\ntemplate <typename Dims1, typename Dims2, ptrdiff_t n>\nstruct sizes_match_below_dim<Dims1, Dims2, n, n> {\n  static EIGEN_DEVICE_FUNC  EIGEN_STRONG_INLINE bool run(Dims1& dims1, Dims2& dims2) {\n    return (array_get<n-1>(dims1) == array_get<n-1>(dims2)) &\n        sizes_match_below_dim<Dims1, Dims2, n-1, n-1>::run(dims1, dims2);\n  }\n};\ntemplate <typename Dims1, typename Dims2>\nstruct sizes_match_below_dim<Dims1, Dims2, 0, 0> {\n  static EIGEN_DEVICE_FUNC  EIGEN_STRONG_INLINE bool run(Dims1&, Dims2&) {\n    return true;\n  }\n};\n\n} // end namespace internal\n\n\ntemplate <typename Dims1, typename Dims2>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool dimensions_match(Dims1 dims1, Dims2 dims2) {\n  return internal::sizes_match_below_dim<Dims1, Dims2, internal::array_size<Dims1>::value, internal::array_size<Dims2>::value>::run(dims1, dims2);\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_DIMENSIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorEvalTo.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_EVAL_TO_H\n#define EIGEN_CXX11_TENSOR_TENSOR_EVAL_TO_H\n\nnamespace Eigen {\n\n/** \\class TensorForcedEval\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor reshaping class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename XprType, template <class> class MakePointer_>\nstruct traits<TensorEvalToOp<XprType, MakePointer_> >\n{\n  // Type promotion to handle the case where the types of the lhs and the rhs are different.\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename MakePointer_<Scalar>::Type PointerType;\n\n  enum {\n    Flags = 0\n  };\n  template <class T>\n  struct MakePointer {\n    // Intermediate typedef to workaround MSVC issue.\n    typedef MakePointer_<T> MakePointerT;\n    typedef typename MakePointerT::Type Type;\n\n\n  };\n};\n\ntemplate<typename XprType, template <class> class MakePointer_>\nstruct eval<TensorEvalToOp<XprType, MakePointer_>, Eigen::Dense>\n{\n  typedef const TensorEvalToOp<XprType, MakePointer_>& type;\n};\n\ntemplate<typename XprType, template <class> class MakePointer_>\nstruct nested<TensorEvalToOp<XprType, MakePointer_>, 1, typename eval<TensorEvalToOp<XprType, MakePointer_> >::type>\n{\n  typedef TensorEvalToOp<XprType, MakePointer_> type;\n};\n\n}  // end namespace internal\n\n\n\n\ntemplate<typename XprType, template <class> class MakePointer_>\nclass TensorEvalToOp : public TensorBase<TensorEvalToOp<XprType, MakePointer_>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorEvalToOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename internal::remove_const<typename XprType::CoeffReturnType>::type CoeffReturnType;\n  typedef typename MakePointer_<CoeffReturnType>::Type PointerType;\n  typedef typename Eigen::internal::nested<TensorEvalToOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorEvalToOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorEvalToOp>::Index Index;\n\n  static const int NumDims = Eigen::internal::traits<TensorEvalToOp>::NumDimensions;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvalToOp(PointerType buffer, const XprType& expr)\n      : m_xpr(expr), m_buffer(buffer) {}\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n    EIGEN_DEVICE_FUNC PointerType buffer() const { return m_buffer; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    PointerType m_buffer;\n};\n\n\n\ntemplate<typename ArgType, typename Device, template <class> class MakePointer_>\nstruct TensorEvaluator<const TensorEvalToOp<ArgType, MakePointer_>, Device>\n{\n  typedef TensorEvalToOp<ArgType, MakePointer_> XprType;\n  typedef typename ArgType::Scalar Scalar;\n  typedef typename TensorEvaluator<ArgType, Device>::Dimensions Dimensions;\n  typedef typename XprType::Index Index;\n  typedef typename internal::remove_const<typename XprType::CoeffReturnType>::type CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef typename Eigen::internal::traits<XprType>::PointerType TensorPointerType;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n  enum {\n    IsAligned         = TensorEvaluator<ArgType, Device>::IsAligned,\n    PacketAccess      = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess       = true,\n    PreferBlockAccess = false,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = true\n  };\n\n  static const int NumDims = internal::traits<ArgType>::NumDimensions;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename TensorEvaluator<const ArgType, Device>::TensorBlock\n      ArgTensorBlock;\n\n  typedef internal::TensorBlockAssignment<\n      CoeffReturnType, NumDims, typename ArgTensorBlock::XprType, Index>\n      TensorBlockAssignment;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device), m_buffer(device.get(op.buffer())), m_expression(op.expression()){}\n\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ~TensorEvaluator() {\n  }\n\n\n  EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_impl.dimensions(); }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType scalar) {\n    EIGEN_UNUSED_VARIABLE(scalar);\n    eigen_assert(scalar == NULL);\n    return m_impl.evalSubExprsIfNeeded(m_buffer);\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType scalar, EvalSubExprsCallback done) {\n    EIGEN_UNUSED_VARIABLE(scalar);\n    eigen_assert(scalar == NULL);\n    m_impl.evalSubExprsIfNeededAsync(m_buffer, std::move(done));\n  }\n#endif\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalScalar(Index i) {\n    m_buffer[i] = m_impl.coeff(i);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalPacket(Index i) {\n    internal::pstoret<CoeffReturnType, PacketReturnType, Aligned>(m_buffer + i, m_impl.template packet<TensorEvaluator<ArgType, Device>::IsAligned ? Aligned : Unaligned>(i));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    return m_impl.getResourceRequirements();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalBlock(\n      TensorBlockDesc& desc, TensorBlockScratch& scratch) {\n    // Add `m_buffer` as destination buffer to the block descriptor.\n    desc.template AddDestinationBuffer<Layout>(\n        /*dst_base=*/m_buffer + desc.offset(),\n        /*dst_strides=*/internal::strides<Layout>(m_impl.dimensions()));\n\n    ArgTensorBlock block =\n        m_impl.block(desc, scratch, /*root_of_expr_ast=*/true);\n\n    // If block was evaluated into a destination buffer, there is no need to do\n    // an assignment.\n    if (block.kind() != internal::TensorBlockKind::kMaterializedInOutput) {\n      TensorBlockAssignment::Run(\n          TensorBlockAssignment::target(\n              desc.dimensions(), internal::strides<Layout>(m_impl.dimensions()),\n              m_buffer, desc.offset()),\n          block.expr());\n    }\n    block.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    return m_buffer[index];\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    return internal::ploadt<PacketReturnType, LoadMode>(m_buffer + index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    // We assume that evalPacket or evalScalar is called to perform the\n    // assignment and account for the cost of the write here.\n    return m_impl.costPerCoeff(vectorized) +\n        TensorOpCost(0, sizeof(CoeffReturnType), 0, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return m_buffer; }\n  ArgType expression() const { return m_expression; }\n  #ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n    m_buffer.bind(cgh);\n  }\n  #endif\n\n\n private:\n  TensorEvaluator<ArgType, Device> m_impl;\n  EvaluatorPointerType m_buffer;\n  const ArgType m_expression;\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_EVAL_TO_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorEvaluator.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_EVALUATOR_H\n#define EIGEN_CXX11_TENSOR_TENSOR_EVALUATOR_H\n\nnamespace Eigen {\n\n/** \\class TensorEvaluator\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief The tensor evaluator classes.\n  *\n  * These classes are responsible for the evaluation of the tensor expression.\n  *\n  * TODO: add support for more types of expressions, in particular expressions\n  * leading to lvalues (slicing, reshaping, etc...)\n  */\n\n// Generic evaluator\ntemplate<typename Derived, typename Device>\nstruct TensorEvaluator\n{\n  typedef typename Derived::Index Index;\n  typedef typename Derived::Scalar Scalar;\n  typedef typename Derived::Scalar CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef typename Derived::Dimensions Dimensions;\n  typedef Derived XprType;\n  static const int PacketSize =  PacketType<CoeffReturnType, Device>::size;\n  typedef typename internal::traits<Derived>::template MakePointer<Scalar>::Type TensorPointerType;\n  typedef StorageMemory<Scalar, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  // NumDimensions is -1 for variable dim tensors\n  static const int NumCoords = internal::traits<Derived>::NumDimensions > 0 ?\n                               internal::traits<Derived>::NumDimensions : 0;\n\n  enum {\n    IsAligned          = Derived::IsAligned,\n    PacketAccess       = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess        = internal::is_arithmetic<typename internal::remove_const<Scalar>::type>::value,\n    PreferBlockAccess  = false,\n    Layout             = Derived::Layout,\n    CoordAccess        = NumCoords > 0,\n    RawAccess          = true\n  };\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumCoords, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename internal::TensorMaterializedBlock<ScalarNoConst, NumCoords,\n                                                     Layout, Index>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const Derived& m, const Device& device)\n      : m_data(device.get((const_cast<TensorPointerType>(m.data())))),\n        m_dims(m.dimensions()),\n        m_device(device)\n  { }\n\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dims; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType dest) {\n    if (!NumTraits<typename internal::remove_const<Scalar>::type>::RequireInitialization && dest) {\n      m_device.memcpy((void*)(m_device.get(dest)), m_device.get(m_data), m_dims.TotalSize() * sizeof(Scalar));\n      return false;\n    }\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType dest, EvalSubExprsCallback done) {\n    // TODO(ezhulenev): ThreadPoolDevice memcpy is blockign operation.\n    done(evalSubExprsIfNeeded(dest));\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const {\n    eigen_assert(m_data != NULL);\n    return m_data[index];\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index) {\n    eigen_assert(m_data != NULL);\n    return m_data[index];\n  }\n\n  template<int LoadMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  PacketReturnType packet(Index index) const\n  {\n    return internal::ploadt<PacketReturnType, LoadMode>(m_data + index);\n  }\n\n  // Return a packet starting at `index` where `umask` specifies which elements\n  // have to be loaded. Type/size of mask depends on PacketReturnType, e.g. for\n  // Packet16f, `umask` is of type uint16_t and if a bit is 1, corresponding\n  // float element will be loaded, otherwise 0 will be loaded.\n  // Function has been templatized to enable Sfinae.\n  template <typename PacketReturnTypeT> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  typename internal::enable_if<internal::unpacket_traits<PacketReturnTypeT>::masked_load_available, PacketReturnTypeT>::type\n  partialPacket(Index index, typename internal::unpacket_traits<PacketReturnTypeT>::mask_t umask) const\n  {\n    return internal::ploadu<PacketReturnTypeT>(m_data + index, umask);\n  }\n\n  template <int StoreMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void writePacket(Index index, const PacketReturnType& x)\n  {\n    return internal::pstoret<Scalar, PacketReturnType, StoreMode>(m_data + index, x);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(const array<DenseIndex, NumCoords>& coords) const {\n    eigen_assert(m_data != NULL);\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      return m_data[m_dims.IndexOfColMajor(coords)];\n    } else {\n      return m_data[m_dims.IndexOfRowMajor(coords)];\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType&\n  coeffRef(const array<DenseIndex, NumCoords>& coords) {\n    eigen_assert(m_data != NULL);\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      return m_data[m_dims.IndexOfColMajor(coords)];\n    } else {\n      return m_data[m_dims.IndexOfRowMajor(coords)];\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized,\n                        PacketType<CoeffReturnType, Device>::size);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    return internal::TensorBlockResourceRequirements::any();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    assert(m_data != NULL);\n    return TensorBlock::materialize(m_data, m_dims, desc, scratch);\n  }\n\n  template<typename TensorBlock>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void writeBlock(\n      const TensorBlockDesc& desc, const TensorBlock& block) {\n    assert(m_data != NULL);\n\n    typedef typename TensorBlock::XprType TensorBlockExpr;\n    typedef internal::TensorBlockAssignment<Scalar, NumCoords, TensorBlockExpr,\n                                            Index>\n        TensorBlockAssign;\n\n    TensorBlockAssign::Run(\n        TensorBlockAssign::target(desc.dimensions(),\n                                  internal::strides<Layout>(m_dims), m_data,\n                                  desc.offset()),\n        block.expr());\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return m_data; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_data.bind(cgh);\n  }\n#endif\n protected:\n  EvaluatorPointerType m_data;\n  Dimensions m_dims;\n  const Device EIGEN_DEVICE_REF m_device;\n};\n\nnamespace {\ntemplate <typename T> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nT loadConstant(const T* address) {\n  return *address;\n}\n// Use the texture cache on CUDA devices whenever possible\n#if defined(EIGEN_CUDA_ARCH) && EIGEN_CUDA_ARCH >= 350\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nfloat loadConstant(const float* address) {\n  return __ldg(address);\n}\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\ndouble loadConstant(const double* address) {\n  return __ldg(address);\n}\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nEigen::half loadConstant(const Eigen::half* address) {\n  return Eigen::half(half_impl::raw_uint16_to_half(__ldg(&address->x)));\n}\n#endif\n#ifdef EIGEN_USE_SYCL\n// overload of load constant should be implemented here based on range access\ntemplate <cl::sycl::access::mode AcMd, typename T>\nT &loadConstant(const Eigen::TensorSycl::internal::RangeAccess<AcMd, T> &address) {\n  return *address;\n}\n#endif\n}\n\n\n// Default evaluator for rvalues\ntemplate<typename Derived, typename Device>\nstruct TensorEvaluator<const Derived, Device>\n{\n  typedef typename Derived::Index Index;\n  typedef typename Derived::Scalar Scalar;\n  typedef typename Derived::Scalar CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef typename Derived::Dimensions Dimensions;\n  typedef const Derived XprType;\n  typedef typename internal::traits<Derived>::template MakePointer<const Scalar>::Type TensorPointerType;\n  typedef StorageMemory<const Scalar, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  // NumDimensions is -1 for variable dim tensors\n  static const int NumCoords = internal::traits<Derived>::NumDimensions > 0 ?\n                               internal::traits<Derived>::NumDimensions : 0;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n\n  enum {\n    IsAligned         = Derived::IsAligned,\n    PacketAccess      = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess       = internal::is_arithmetic<ScalarNoConst>::value,\n    PreferBlockAccess = false,\n    Layout            = Derived::Layout,\n    CoordAccess       = NumCoords > 0,\n    RawAccess         = true\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumCoords, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename internal::TensorMaterializedBlock<ScalarNoConst, NumCoords,\n                                                     Layout, Index>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const Derived& m, const Device& device)\n      : m_data(device.get(m.data())), m_dims(m.dimensions()), m_device(device)\n  { }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dims; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    if (!NumTraits<typename internal::remove_const<Scalar>::type>::RequireInitialization && data) {\n      m_device.memcpy((void*)(m_device.get(data)),m_device.get(m_data), m_dims.TotalSize() * sizeof(Scalar));\n      return false;\n    }\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType dest, EvalSubExprsCallback done) {\n    // TODO(ezhulenev): ThreadPoolDevice memcpy is a blockign operation.\n    done(evalSubExprsIfNeeded(dest));\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const {\n    eigen_assert(m_data != NULL);\n    return loadConstant(m_data+index);\n  }\n\n  template<int LoadMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  PacketReturnType packet(Index index) const\n  {\n    return internal::ploadt_ro<PacketReturnType, LoadMode>(m_data + index);\n  }\n\n  // Return a packet starting at `index` where `umask` specifies which elements\n  // have to be loaded. Type/size of mask depends on PacketReturnType, e.g. for\n  // Packet16f, `umask` is of type uint16_t and if a bit is 1, corresponding\n  // float element will be loaded, otherwise 0 will be loaded.\n  // Function has been templatized to enable Sfinae.\n  template <typename PacketReturnTypeT> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  typename internal::enable_if<internal::unpacket_traits<PacketReturnTypeT>::masked_load_available, PacketReturnTypeT>::type\n  partialPacket(Index index, typename internal::unpacket_traits<PacketReturnTypeT>::mask_t umask) const\n  {\n    return internal::ploadu<PacketReturnTypeT>(m_data + index, umask);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(const array<DenseIndex, NumCoords>& coords) const {\n    eigen_assert(m_data != NULL);\n    const Index index = (static_cast<int>(Layout) == static_cast<int>(ColMajor)) ? m_dims.IndexOfColMajor(coords)\n                        : m_dims.IndexOfRowMajor(coords);\n    return loadConstant(m_data+index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized,\n                        PacketType<CoeffReturnType, Device>::size);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    return internal::TensorBlockResourceRequirements::any();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    assert(m_data != NULL);\n    return TensorBlock::materialize(m_data, m_dims, desc, scratch);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return m_data; }\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_data.bind(cgh);\n  }\n#endif\n protected:\n  EvaluatorPointerType m_data;\n  Dimensions m_dims;\n  const Device EIGEN_DEVICE_REF m_device;\n};\n\n\n\n\n// -------------------- CwiseNullaryOp --------------------\n\ntemplate<typename NullaryOp, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorCwiseNullaryOp<NullaryOp, ArgType>, Device>\n{\n  typedef TensorCwiseNullaryOp<NullaryOp, ArgType> XprType;\n\n  EIGEN_DEVICE_FUNC\n  TensorEvaluator(const XprType& op, const Device& device)\n      : m_functor(op.functor()), m_argImpl(op.nestedExpression(), device), m_wrapper()\n  { }\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename internal::traits<XprType>::Scalar CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef typename TensorEvaluator<ArgType, Device>::Dimensions Dimensions;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = true,\n    PacketAccess = internal::functor_traits<NullaryOp>::PacketAccess\n    #ifdef EIGEN_USE_SYCL\n    &&  (PacketType<CoeffReturnType, Device>::size >1)\n    #endif\n    ,\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_argImpl.dimensions(); }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) { return true; }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    done(true);\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { }\n\n  EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const\n  {\n    return m_wrapper(m_functor, index);\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    return m_wrapper.template packetOp<PacketReturnType, Index>(m_functor, index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized,\n                        PacketType<CoeffReturnType, Device>::size);\n  }\n\n  EIGEN_DEVICE_FUNC  EvaluatorPointerType data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n   // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_argImpl.bind(cgh);\n  }\n#endif\n\n private:\n  const NullaryOp m_functor;\n  TensorEvaluator<ArgType, Device> m_argImpl;\n  const internal::nullary_wrapper<CoeffReturnType,NullaryOp> m_wrapper;\n};\n\n\n\n// -------------------- CwiseUnaryOp --------------------\n\ntemplate<typename UnaryOp, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorCwiseUnaryOp<UnaryOp, ArgType>, Device>\n{\n  typedef TensorCwiseUnaryOp<UnaryOp, ArgType> XprType;\n\n  enum {\n    IsAligned          = TensorEvaluator<ArgType, Device>::IsAligned,\n    PacketAccess       = TensorEvaluator<ArgType, Device>::PacketAccess &\n                         internal::functor_traits<UnaryOp>::PacketAccess,\n    BlockAccess        = TensorEvaluator<ArgType, Device>::BlockAccess,\n    PreferBlockAccess  = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout             = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess        = false,  // to be implemented\n    RawAccess          = false\n  };\n\n  EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device)\n    : m_device(device),\n      m_functor(op.functor()),\n      m_argImpl(op.nestedExpression(), device)\n  { }\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n  typedef typename internal::traits<XprType>::Scalar CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef typename TensorEvaluator<ArgType, Device>::Dimensions Dimensions;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n  static const int NumDims = internal::array_size<Dimensions>::value;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename TensorEvaluator<const ArgType, Device>::TensorBlock\n      ArgTensorBlock;\n\n  typedef internal::TensorCwiseUnaryBlock<UnaryOp, ArgTensorBlock>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_argImpl.dimensions(); }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    m_argImpl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    m_argImpl.evalSubExprsIfNeededAsync(nullptr, [done](bool) { done(true); });\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_argImpl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const\n  {\n    return m_functor(m_argImpl.coeff(index));\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    return m_functor.packetOp(m_argImpl.template packet<LoadMode>(index));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    const double functor_cost = internal::functor_traits<UnaryOp>::Cost;\n    return m_argImpl.costPerCoeff(vectorized) +\n        TensorOpCost(0, 0, functor_cost, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    static const double functor_cost = internal::functor_traits<UnaryOp>::Cost;\n    return m_argImpl.getResourceRequirements().addCostPerCoeff(\n        {0, 0, functor_cost / PacketSize});\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    return TensorBlock(m_argImpl.block(desc, scratch), m_functor);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const{\n    m_argImpl.bind(cgh);\n  }\n#endif\n\n\n private:\n  const Device EIGEN_DEVICE_REF m_device;\n  const UnaryOp m_functor;\n  TensorEvaluator<ArgType, Device> m_argImpl;\n};\n\n\n// -------------------- CwiseBinaryOp --------------------\n\ntemplate<typename BinaryOp, typename LeftArgType, typename RightArgType, typename Device>\nstruct TensorEvaluator<const TensorCwiseBinaryOp<BinaryOp, LeftArgType, RightArgType>, Device>\n{\n  typedef TensorCwiseBinaryOp<BinaryOp, LeftArgType, RightArgType> XprType;\n\n  enum {\n    IsAligned         = TensorEvaluator<LeftArgType, Device>::IsAligned &\n                        TensorEvaluator<RightArgType, Device>::IsAligned,\n    PacketAccess      = TensorEvaluator<LeftArgType, Device>::PacketAccess &\n                        TensorEvaluator<RightArgType, Device>::PacketAccess &\n                        internal::functor_traits<BinaryOp>::PacketAccess,\n    BlockAccess       = TensorEvaluator<LeftArgType, Device>::BlockAccess &\n                        TensorEvaluator<RightArgType, Device>::BlockAccess,\n    PreferBlockAccess = TensorEvaluator<LeftArgType, Device>::PreferBlockAccess |\n                        TensorEvaluator<RightArgType, Device>::PreferBlockAccess,\n    Layout            = TensorEvaluator<LeftArgType, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = false\n  };\n\n  EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device)\n    : m_device(device),\n      m_functor(op.functor()),\n      m_leftImpl(op.lhsExpression(), device),\n      m_rightImpl(op.rhsExpression(), device)\n  {\n    EIGEN_STATIC_ASSERT((static_cast<int>(TensorEvaluator<LeftArgType, Device>::Layout) == static_cast<int>(TensorEvaluator<RightArgType, Device>::Layout) || internal::traits<XprType>::NumDimensions <= 1), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    eigen_assert(dimensions_match(m_leftImpl.dimensions(), m_rightImpl.dimensions()));\n  }\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename internal::traits<XprType>::Scalar CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef typename TensorEvaluator<LeftArgType, Device>::Dimensions Dimensions;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  static const int NumDims = internal::array_size<\n      typename TensorEvaluator<LeftArgType, Device>::Dimensions>::value;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename TensorEvaluator<const LeftArgType, Device>::TensorBlock\n      LeftTensorBlock;\n  typedef typename TensorEvaluator<const RightArgType, Device>::TensorBlock\n      RightTensorBlock;\n\n  typedef internal::TensorCwiseBinaryBlock<BinaryOp, LeftTensorBlock,\n                                           RightTensorBlock>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC const Dimensions& dimensions() const\n  {\n    // TODO: use right impl instead if right impl dimensions are known at compile time.\n    return m_leftImpl.dimensions();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    m_leftImpl.evalSubExprsIfNeeded(NULL);\n    m_rightImpl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    // TODO(ezhulenev): Evaluate two expression in parallel?\n    m_leftImpl.evalSubExprsIfNeededAsync(nullptr, [this, done](bool) {\n      m_rightImpl.evalSubExprsIfNeededAsync(nullptr,\n                                            [done](bool) { done(true); });\n    });\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_leftImpl.cleanup();\n    m_rightImpl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const\n  {\n    return m_functor(m_leftImpl.coeff(index), m_rightImpl.coeff(index));\n  }\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    return m_functor.packetOp(m_leftImpl.template packet<LoadMode>(index), m_rightImpl.template packet<LoadMode>(index));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    const double functor_cost = internal::functor_traits<BinaryOp>::Cost;\n    return m_leftImpl.costPerCoeff(vectorized) +\n           m_rightImpl.costPerCoeff(vectorized) +\n           TensorOpCost(0, 0, functor_cost, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    static const double functor_cost = internal::functor_traits<BinaryOp>::Cost;\n    return internal::TensorBlockResourceRequirements::merge(\n               m_leftImpl.getResourceRequirements(),\n               m_rightImpl.getResourceRequirements())\n        .addCostPerCoeff({0, 0, functor_cost / PacketSize});\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    desc.DropDestinationBuffer();\n    return TensorBlock(m_leftImpl.block(desc, scratch),\n                         m_rightImpl.block(desc, scratch), m_functor);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n  #ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_leftImpl.bind(cgh);\n    m_rightImpl.bind(cgh);\n  }\n  #endif\n private:\n  const Device EIGEN_DEVICE_REF m_device;\n  const BinaryOp m_functor;\n  TensorEvaluator<LeftArgType, Device> m_leftImpl;\n  TensorEvaluator<RightArgType, Device> m_rightImpl;\n};\n\n// -------------------- CwiseTernaryOp --------------------\n\ntemplate<typename TernaryOp, typename Arg1Type, typename Arg2Type, typename Arg3Type, typename Device>\nstruct TensorEvaluator<const TensorCwiseTernaryOp<TernaryOp, Arg1Type, Arg2Type, Arg3Type>, Device>\n{\n  typedef TensorCwiseTernaryOp<TernaryOp, Arg1Type, Arg2Type, Arg3Type> XprType;\n\n  enum {\n    IsAligned = TensorEvaluator<Arg1Type, Device>::IsAligned & TensorEvaluator<Arg2Type, Device>::IsAligned & TensorEvaluator<Arg3Type, Device>::IsAligned,\n    PacketAccess      = TensorEvaluator<Arg1Type, Device>::PacketAccess &&\n                        TensorEvaluator<Arg2Type, Device>::PacketAccess &&\n                        TensorEvaluator<Arg3Type, Device>::PacketAccess &&\n                        internal::functor_traits<TernaryOp>::PacketAccess,\n    BlockAccess       = false,\n    PreferBlockAccess = TensorEvaluator<Arg1Type, Device>::PreferBlockAccess ||\n                        TensorEvaluator<Arg2Type, Device>::PreferBlockAccess ||\n                        TensorEvaluator<Arg3Type, Device>::PreferBlockAccess,\n    Layout            = TensorEvaluator<Arg1Type, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = false\n  };\n\n  EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device)\n    : m_functor(op.functor()),\n      m_arg1Impl(op.arg1Expression(), device),\n      m_arg2Impl(op.arg2Expression(), device),\n      m_arg3Impl(op.arg3Expression(), device)\n  {\n    EIGEN_STATIC_ASSERT((static_cast<int>(TensorEvaluator<Arg1Type, Device>::Layout) == static_cast<int>(TensorEvaluator<Arg3Type, Device>::Layout) || internal::traits<XprType>::NumDimensions <= 1), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    EIGEN_STATIC_ASSERT((internal::is_same<typename internal::traits<Arg1Type>::StorageKind,\n                         typename internal::traits<Arg2Type>::StorageKind>::value),\n                        STORAGE_KIND_MUST_MATCH)\n    EIGEN_STATIC_ASSERT((internal::is_same<typename internal::traits<Arg1Type>::StorageKind,\n                         typename internal::traits<Arg3Type>::StorageKind>::value),\n                        STORAGE_KIND_MUST_MATCH)\n    EIGEN_STATIC_ASSERT((internal::is_same<typename internal::traits<Arg1Type>::Index,\n                         typename internal::traits<Arg2Type>::Index>::value),\n                        STORAGE_INDEX_MUST_MATCH)\n    EIGEN_STATIC_ASSERT((internal::is_same<typename internal::traits<Arg1Type>::Index,\n                         typename internal::traits<Arg3Type>::Index>::value),\n                        STORAGE_INDEX_MUST_MATCH)\n\n    eigen_assert(dimensions_match(m_arg1Impl.dimensions(), m_arg2Impl.dimensions()) && dimensions_match(m_arg1Impl.dimensions(), m_arg3Impl.dimensions()));\n  }\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename internal::traits<XprType>::Scalar CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef typename TensorEvaluator<Arg1Type, Device>::Dimensions Dimensions;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC const Dimensions& dimensions() const\n  {\n    // TODO: use arg2 or arg3 dimensions if they are known at compile time.\n    return m_arg1Impl.dimensions();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    m_arg1Impl.evalSubExprsIfNeeded(NULL);\n    m_arg2Impl.evalSubExprsIfNeeded(NULL);\n    m_arg3Impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_arg1Impl.cleanup();\n    m_arg2Impl.cleanup();\n    m_arg3Impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const\n  {\n    return m_functor(m_arg1Impl.coeff(index), m_arg2Impl.coeff(index), m_arg3Impl.coeff(index));\n  }\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    return m_functor.packetOp(m_arg1Impl.template packet<LoadMode>(index),\n                              m_arg2Impl.template packet<LoadMode>(index),\n                              m_arg3Impl.template packet<LoadMode>(index));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    const double functor_cost = internal::functor_traits<TernaryOp>::Cost;\n    return m_arg1Impl.costPerCoeff(vectorized) +\n           m_arg2Impl.costPerCoeff(vectorized) +\n           m_arg3Impl.costPerCoeff(vectorized) +\n           TensorOpCost(0, 0, functor_cost, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n   // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_arg1Impl.bind(cgh);\n    m_arg2Impl.bind(cgh);\n    m_arg3Impl.bind(cgh);\n  }\n#endif\n\n private:\n  const TernaryOp m_functor;\n  TensorEvaluator<Arg1Type, Device> m_arg1Impl;\n  TensorEvaluator<Arg2Type, Device> m_arg2Impl;\n  TensorEvaluator<Arg3Type, Device> m_arg3Impl;\n};\n\n\n// -------------------- SelectOp --------------------\n\ntemplate<typename IfArgType, typename ThenArgType, typename ElseArgType, typename Device>\nstruct TensorEvaluator<const TensorSelectOp<IfArgType, ThenArgType, ElseArgType>, Device>\n{\n  typedef TensorSelectOp<IfArgType, ThenArgType, ElseArgType> XprType;\n  typedef typename XprType::Scalar Scalar;\n\n  enum {\n    IsAligned         = TensorEvaluator<ThenArgType, Device>::IsAligned &\n                        TensorEvaluator<ElseArgType, Device>::IsAligned,\n    PacketAccess      = TensorEvaluator<ThenArgType, Device>::PacketAccess &\n                        TensorEvaluator<ElseArgType, Device>::PacketAccess &\n                        PacketType<Scalar, Device>::HasBlend,\n    BlockAccess       = TensorEvaluator<IfArgType, Device>::BlockAccess &&\n                        TensorEvaluator<ThenArgType, Device>::BlockAccess &&\n                        TensorEvaluator<ElseArgType, Device>::BlockAccess,\n    PreferBlockAccess = TensorEvaluator<IfArgType, Device>::PreferBlockAccess ||\n                        TensorEvaluator<ThenArgType, Device>::PreferBlockAccess ||\n                        TensorEvaluator<ElseArgType, Device>::PreferBlockAccess,\n    Layout            = TensorEvaluator<IfArgType, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = false\n  };\n\n  EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device)\n    : m_condImpl(op.ifExpression(), device),\n      m_thenImpl(op.thenExpression(), device),\n      m_elseImpl(op.elseExpression(), device)\n  {\n    EIGEN_STATIC_ASSERT((static_cast<int>(TensorEvaluator<IfArgType, Device>::Layout) == static_cast<int>(TensorEvaluator<ThenArgType, Device>::Layout)), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    EIGEN_STATIC_ASSERT((static_cast<int>(TensorEvaluator<IfArgType, Device>::Layout) == static_cast<int>(TensorEvaluator<ElseArgType, Device>::Layout)), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    eigen_assert(dimensions_match(m_condImpl.dimensions(), m_thenImpl.dimensions()));\n    eigen_assert(dimensions_match(m_thenImpl.dimensions(), m_elseImpl.dimensions()));\n  }\n\n  typedef typename XprType::Index Index;\n  typedef typename internal::traits<XprType>::Scalar CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef typename TensorEvaluator<IfArgType, Device>::Dimensions Dimensions;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  static const int NumDims = internal::array_size<Dimensions>::value;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n    typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename TensorEvaluator<const IfArgType, Device>::TensorBlock\n      IfArgTensorBlock;\n  typedef typename TensorEvaluator<const ThenArgType, Device>::TensorBlock\n      ThenArgTensorBlock;\n  typedef typename TensorEvaluator<const ElseArgType, Device>::TensorBlock\n      ElseArgTensorBlock;\n\n  struct TensorSelectOpBlockFactory {\n    template <typename IfArgXprType, typename ThenArgXprType, typename ElseArgXprType>\n    struct XprType {\n      typedef TensorSelectOp<const IfArgXprType, const ThenArgXprType, const ElseArgXprType> type;\n    };\n\n    template <typename IfArgXprType, typename ThenArgXprType, typename ElseArgXprType>\n    typename XprType<IfArgXprType, ThenArgXprType, ElseArgXprType>::type expr(\n        const IfArgXprType& if_expr, const ThenArgXprType& then_expr, const ElseArgXprType& else_expr) const {\n      return typename XprType<IfArgXprType, ThenArgXprType, ElseArgXprType>::type(if_expr, then_expr, else_expr);\n    }\n  };\n\n  typedef internal::TensorTernaryExprBlock<TensorSelectOpBlockFactory,\n                                           IfArgTensorBlock, ThenArgTensorBlock,\n                                           ElseArgTensorBlock>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC const Dimensions& dimensions() const\n  {\n    // TODO: use then or else impl instead if they happen to be known at compile time.\n    return m_condImpl.dimensions();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    m_condImpl.evalSubExprsIfNeeded(NULL);\n    m_thenImpl.evalSubExprsIfNeeded(NULL);\n    m_elseImpl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    m_condImpl.evalSubExprsIfNeeded(nullptr, [this, done](bool) {\n      m_thenImpl.evalSubExprsIfNeeded(nullptr, [this, done](bool) {\n        m_elseImpl.evalSubExprsIfNeeded(nullptr, [done](bool) { done(true); });\n      });\n    });\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_condImpl.cleanup();\n    m_thenImpl.cleanup();\n    m_elseImpl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC CoeffReturnType coeff(Index index) const\n  {\n    return m_condImpl.coeff(index) ? m_thenImpl.coeff(index) : m_elseImpl.coeff(index);\n  }\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC PacketReturnType packet(Index index) const\n  {\n     internal::Selector<PacketSize> select;\n     EIGEN_UNROLL_LOOP\n     for (Index i = 0; i < PacketSize; ++i) {\n       select.select[i] = m_condImpl.coeff(index+i);\n     }\n     return internal::pblend(select,\n                             m_thenImpl.template packet<LoadMode>(index),\n                             m_elseImpl.template packet<LoadMode>(index));\n\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    return m_condImpl.costPerCoeff(vectorized) +\n           m_thenImpl.costPerCoeff(vectorized)\n        .cwiseMax(m_elseImpl.costPerCoeff(vectorized));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    auto then_req = m_thenImpl.getResourceRequirements();\n    auto else_req = m_elseImpl.getResourceRequirements();\n\n    auto merged_req =\n        internal::TensorBlockResourceRequirements::merge(then_req, else_req);\n    merged_req.cost_per_coeff =\n        then_req.cost_per_coeff.cwiseMax(else_req.cost_per_coeff);\n\n    return internal::TensorBlockResourceRequirements::merge(\n        m_condImpl.getResourceRequirements(), merged_req);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    // It's unsafe to pass destination buffer to underlying expressions, because\n    // output might be aliased with one of the inputs.\n    desc.DropDestinationBuffer();\n\n    return TensorBlock(\n        m_condImpl.block(desc, scratch), m_thenImpl.block(desc, scratch),\n        m_elseImpl.block(desc, scratch), TensorSelectOpBlockFactory());\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EvaluatorPointerType data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_condImpl.bind(cgh);\n    m_thenImpl.bind(cgh);\n    m_elseImpl.bind(cgh);\n  }\n#endif\n private:\n  TensorEvaluator<IfArgType, Device> m_condImpl;\n  TensorEvaluator<ThenArgType, Device> m_thenImpl;\n  TensorEvaluator<ElseArgType, Device> m_elseImpl;\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_EVALUATOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorExecutor.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_EXECUTOR_H\n#define EIGEN_CXX11_TENSOR_TENSOR_EXECUTOR_H\n\nnamespace Eigen {\n\n/**\n * \\class TensorExecutor\n * \\ingroup CXX11_Tensor_Module\n *\n * \\brief The tensor executor class.\n *\n * This class is responsible for launch the evaluation of the expression on\n * the specified computing device.\n *\n * @tparam Vectorizable can use packet math (SSE/AVX/etc... registers and\n *                      instructions)\n * @tparam Tiling       can use block based tensor evaluation\n *                      (see TensorBlock.h)\n */\nnamespace internal {\n\n/**\n * Evaluating TensorBroadcastingOp via coefficient of packet path is extremely\n * expensive. If expression has at least one broadcast op in it, and it supports\n * block based evaluation, we always prefer it, even for the small tensors. For\n * all other tileable ops, block evaluation overhead for small tensors (fits\n * into L1) is too large, and we fallback on vectorized evaluation.\n */\n\n// TODO(ezhulenev): Add specializations for all other types of Tensor ops.\n\ntemplate<typename Expression>\nstruct ExpressionHasTensorBroadcastingOp {\n  enum { value = false };\n};\n\ntemplate<typename LhsXprType, typename RhsXprType>\nstruct ExpressionHasTensorBroadcastingOp<\n    const TensorAssignOp<LhsXprType, RhsXprType> > {\n  enum { value = ExpressionHasTensorBroadcastingOp<RhsXprType>::value };\n};\n\ntemplate<typename UnaryOp, typename XprType>\nstruct ExpressionHasTensorBroadcastingOp<\n    const TensorCwiseUnaryOp<UnaryOp, XprType> > {\n  enum { value = ExpressionHasTensorBroadcastingOp<XprType>::value };\n};\n\ntemplate<typename BinaryOp, typename LhsXprType, typename RhsXprType>\nstruct ExpressionHasTensorBroadcastingOp<\n    const TensorCwiseBinaryOp<BinaryOp, LhsXprType, RhsXprType> > {\n  enum {\n    value = ExpressionHasTensorBroadcastingOp<LhsXprType>::value ||\n        ExpressionHasTensorBroadcastingOp<RhsXprType>::value\n  };\n};\n\ntemplate<typename Broadcast, typename XprType>\nstruct ExpressionHasTensorBroadcastingOp<\n    const TensorBroadcastingOp<Broadcast, XprType> > {\n  enum { value = true };\n};\n\n// -------------------------------------------------------------------------- //\n\n/**\n * Default strategy: the expression is evaluated sequentially with a single cpu\n * thread, without vectorization and block evaluation.\n */\ntemplate <typename Expression, typename Device, bool Vectorizable,\n          TiledEvaluation Tiling>\nclass TensorExecutor {\n public:\n  typedef typename Expression::Index StorageIndex;\n\n  // Including `unsupported/Eigen/CXX11/Tensor` in different translation units\n  // with/without `EIGEN_USE_THREADS` or `EIGEN_USE_GPU` is a potential ODR\n  // violation. If this template is instantiated with a non-default device, it\n  // means that this header file was included without defining\n  // `EIGEN_USE_THREADS`, `EIGEN_USE_GPU` or `EIGEN_USE_SYCL`.\n  static_assert(std::is_same<Device, DefaultDevice>::value,\n                \"Default executor instantiated with non-default device. \"\n                \"You must #define EIGEN_USE_THREADS, EIGEN_USE_GPU or \"\n                \"EIGEN_USE_SYCL before including Eigen headers.\");\n\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE void run(const Expression& expr,\n                                      const Device& device = Device()) {\n    TensorEvaluator<Expression, Device> evaluator(expr, device);\n    const bool needs_assign = evaluator.evalSubExprsIfNeeded(NULL);\n    if (needs_assign) {\n      const StorageIndex size = array_prod(evaluator.dimensions());\n      for (StorageIndex i = 0; i < size; ++i) {\n        evaluator.evalScalar(i);\n      }\n    }\n    evaluator.cleanup();\n  }\n};\n\n/**\n * Default async execution strategy is not implemented. Currently it's only\n * available for ThreadPoolDevice (see definition below).\n */\ntemplate <typename Expression, typename Device, typename DoneCallback,\n          bool Vectorizable, TiledEvaluation Tiling>\nclass TensorAsyncExecutor {};\n\n/**\n * Process all the data with a single cpu thread, using vectorized instructions.\n */\ntemplate <typename Expression>\nclass TensorExecutor<Expression, DefaultDevice, /*Vectorizable=*/true,\n                     /*Tiling=*/TiledEvaluation::Off> {\n public:\n  typedef typename Expression::Index StorageIndex;\n\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE void run(\n      const Expression& expr, const DefaultDevice& device = DefaultDevice()) {\n    TensorEvaluator<Expression, DefaultDevice> evaluator(expr, device);\n    const bool needs_assign = evaluator.evalSubExprsIfNeeded(NULL);\n    if (needs_assign) {\n      const StorageIndex size = array_prod(evaluator.dimensions());\n      const int PacketSize = unpacket_traits<typename TensorEvaluator<\n          Expression, DefaultDevice>::PacketReturnType>::size;\n\n      // Give compiler a strong possibility to unroll the loop. But don't insist\n      // on unrolling, because if the function is expensive compiler should not\n      // unroll the loop at the expense of inlining.\n      const StorageIndex UnrolledSize =\n          (size / (4 * PacketSize)) * 4 * PacketSize;\n      for (StorageIndex i = 0; i < UnrolledSize; i += 4 * PacketSize) {\n        for (StorageIndex j = 0; j < 4; j++) {\n          evaluator.evalPacket(i + j * PacketSize);\n        }\n      }\n      const StorageIndex VectorizedSize = (size / PacketSize) * PacketSize;\n      for (StorageIndex i = UnrolledSize; i < VectorizedSize; i += PacketSize) {\n        evaluator.evalPacket(i);\n      }\n      for (StorageIndex i = VectorizedSize; i < size; ++i) {\n        evaluator.evalScalar(i);\n      }\n    }\n    evaluator.cleanup();\n  }\n};\n\n/**\n * Process all the data with a single cpu thread, using blocks of data. By\n * sizing a block to fit L1 cache we get better cache performance.\n */\ntemplate <typename Expression, bool Vectorizable>\nclass TensorExecutor<Expression, DefaultDevice, Vectorizable,\n                     /*Tiling=*/TiledEvaluation::On> {\n public:\n  typedef typename traits<Expression>::Scalar Scalar;\n  typedef typename remove_const<Scalar>::type ScalarNoConst;\n\n  typedef TensorEvaluator<Expression, DefaultDevice> Evaluator;\n  typedef typename traits<Expression>::Index StorageIndex;\n\n  static const int NumDims = traits<Expression>::NumDimensions;\n\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE void run(const Expression& expr,\n                         const DefaultDevice& device = DefaultDevice()) {\n    typedef TensorBlockMapper<NumDims, Evaluator::Layout, StorageIndex>\n        TensorBlockMapper;\n\n    typedef internal::TensorBlockDescriptor<NumDims, StorageIndex>\n        TensorBlockDesc;\n    typedef internal::TensorBlockScratchAllocator<DefaultDevice>\n        TensorBlockScratch;\n\n    Evaluator evaluator(expr, device);\n\n    // TODO(ezhulenev): Do not use tiling for small tensors?\n    const bool needs_assign = evaluator.evalSubExprsIfNeeded(NULL);\n\n    if (needs_assign) {\n      // Query expression tree for desired block size/shape.\n      const TensorBlockResourceRequirements requirements =\n          evaluator.getResourceRequirements();\n\n      const TensorBlockMapper block_mapper(\n          typename TensorBlockDesc::Dimensions(evaluator.dimensions()),\n          requirements);\n\n      // Share scratch memory allocator between all blocks.\n      TensorBlockScratch scratch(device);\n\n      const StorageIndex total_block_count = block_mapper.blockCount();\n      for (StorageIndex i = 0; i < total_block_count; ++i) {\n        TensorBlockDesc desc = block_mapper.blockDescriptor(i);\n        evaluator.evalBlock(desc, scratch);\n        scratch.reset();\n      }\n    }\n    evaluator.cleanup();\n  }\n};\n\n/**\n * Multicore strategy: the index space is partitioned and each partition is\n * executed on a single core.\n *\n * (1) TensorExecutor will submit work to the ThreadPoolDevice managed thread\n *     pool, and will block the caller thread until all tasks are finished.\n *\n * (2) TensorAsyncExecutor is a non-blocking version, that will submit work to\n *     the ThreadPoolDevice managed thread pool, and will return immediately.\n *     It will call 'done' callback after all tasks are finished.\n */\n#ifdef EIGEN_USE_THREADS\n\ntemplate <typename TensorBlockMapper>\nstruct TensorExecutorTilingContext {\n  TensorExecutorTilingContext() = default;\n  TensorExecutorTilingContext(const TensorBlockMapper& b_mapper,\n                              const TensorOpCost& b_cost, size_t b_aligned_size)\n      : block_mapper(b_mapper),\n        cost(b_cost),\n        aligned_blocksize(b_aligned_size) {}\n\n  TensorBlockMapper block_mapper;  // navigate through blocks\n  TensorOpCost cost;               // cost of computing a single block\n  size_t aligned_blocksize;        // block size after memory alignment\n};\n\n// Computes a block evaluation parameters, and allocates temporary memory buffer\n// for blocks. See TensorExecutor/TensorAsyncExecutor (Tiling=On) below.\ntemplate <typename Evaluator, typename TensorBlockMapper, bool Vectorizable>\nTensorExecutorTilingContext<TensorBlockMapper> GetTensorExecutorTilingContext(\n    const Evaluator& evaluator) {\n  // Query expression tree for desired block size/shape.\n  TensorBlockResourceRequirements requirements =\n      evaluator.getResourceRequirements();\n\n  // Update target block size based on cost model.\n  double taskSize = TensorCostModel<ThreadPoolDevice>::taskSize(\n      1, requirements.cost_per_coeff);\n  requirements.size = static_cast<size_t>(1.0 / taskSize);\n\n  TensorBlockMapper block_mapper(\n      typename TensorBlockMapper::Dimensions(evaluator.dimensions()),\n      requirements);\n\n  size_t block_size = block_mapper.blockTotalSize();\n  const size_t align = numext::maxi(EIGEN_MAX_ALIGN_BYTES, 1);\n  const size_t aligned_blocksize =\n      align *\n      divup<size_t>(block_size * sizeof(typename Evaluator::Scalar), align);\n\n  return {block_mapper, requirements.cost_per_coeff * block_size,\n          aligned_blocksize};\n}\n\ntemplate <typename Evaluator, typename StorageIndex, bool Vectorizable>\nstruct EvalRange {\n  static void run(Evaluator* evaluator_in, const StorageIndex firstIdx,\n                  const StorageIndex lastIdx) {\n    Evaluator evaluator = *evaluator_in;\n    eigen_assert(lastIdx >= firstIdx);\n    for (StorageIndex i = firstIdx; i < lastIdx; ++i) {\n      evaluator.evalScalar(i);\n    }\n  }\n\n  static StorageIndex alignBlockSize(StorageIndex size) { return size; }\n};\n\ntemplate <typename Evaluator, typename StorageIndex>\nstruct EvalRange<Evaluator, StorageIndex, /*Vectorizable*/ true> {\n  static const int PacketSize =\n      unpacket_traits<typename Evaluator::PacketReturnType>::size;\n\n  static void run(Evaluator* evaluator_in, const StorageIndex firstIdx,\n                  const StorageIndex lastIdx) {\n    Evaluator evaluator = *evaluator_in;\n    eigen_assert(lastIdx >= firstIdx);\n    StorageIndex i = firstIdx;\n    if (lastIdx - firstIdx >= PacketSize) {\n      eigen_assert(firstIdx % PacketSize == 0);\n      StorageIndex last_chunk_offset = lastIdx - 4 * PacketSize;\n      // Give compiler a strong possibility to unroll the loop. But don't insist\n      // on unrolling, because if the function is expensive compiler should not\n      // unroll the loop at the expense of inlining.\n      for (; i <= last_chunk_offset; i += 4 * PacketSize) {\n        for (StorageIndex j = 0; j < 4; j++) {\n          evaluator.evalPacket(i + j * PacketSize);\n        }\n      }\n      last_chunk_offset = lastIdx - PacketSize;\n      for (; i <= last_chunk_offset; i += PacketSize) {\n        evaluator.evalPacket(i);\n      }\n    }\n    for (; i < lastIdx; ++i) {\n      evaluator.evalScalar(i);\n    }\n  }\n\n  static StorageIndex alignBlockSize(StorageIndex size) {\n    // Align block size to packet size and account for unrolling in run above.\n    if (size >= 16 * PacketSize) {\n      return (size + 4 * PacketSize - 1) & ~(4 * PacketSize - 1);\n    }\n    // Aligning to 4 * PacketSize would increase block size by more than 25%.\n    return (size + PacketSize - 1) & ~(PacketSize - 1);\n  }\n};\n\ntemplate <typename Expression, bool Vectorizable, TiledEvaluation Tiling>\nclass TensorExecutor<Expression, ThreadPoolDevice, Vectorizable, Tiling> {\n public:\n  typedef typename Expression::Index StorageIndex;\n\n  static EIGEN_STRONG_INLINE void run(const Expression& expr,\n                         const ThreadPoolDevice& device) {\n    typedef TensorEvaluator<Expression, ThreadPoolDevice> Evaluator;\n    typedef EvalRange<Evaluator, StorageIndex, Vectorizable> EvalRange;\n\n    Evaluator evaluator(expr, device);\n    const bool needs_assign = evaluator.evalSubExprsIfNeeded(nullptr);\n    if (needs_assign) {\n      const StorageIndex size = array_prod(evaluator.dimensions());\n      device.parallelFor(size, evaluator.costPerCoeff(Vectorizable),\n                         EvalRange::alignBlockSize,\n                         [&evaluator](StorageIndex firstIdx, StorageIndex lastIdx) {\n                           EvalRange::run(&evaluator, firstIdx, lastIdx);\n                         });\n    }\n    evaluator.cleanup();\n  }\n};\n\ntemplate <typename Expression, bool Vectorizable>\nclass TensorExecutor<Expression, ThreadPoolDevice, Vectorizable,\n                     /*Tiling=*/TiledEvaluation::On> {\n public:\n  typedef typename traits<Expression>::Index IndexType;\n  typedef typename traits<Expression>::Scalar Scalar;\n  typedef typename remove_const<Scalar>::type ScalarNoConst;\n\n  static const int NumDims = traits<Expression>::NumDimensions;\n\n  typedef TensorEvaluator<Expression, ThreadPoolDevice> Evaluator;\n  typedef TensorBlockMapper<NumDims, Evaluator::Layout, IndexType> BlockMapper;\n  typedef TensorExecutorTilingContext<BlockMapper> TilingContext;\n\n  typedef internal::TensorBlockDescriptor<NumDims, IndexType>\n      TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<ThreadPoolDevice>\n      TensorBlockScratch;\n\n  static EIGEN_STRONG_INLINE void run(const Expression& expr,\n                                      const ThreadPoolDevice& device) {\n    Evaluator evaluator(expr, device);\n\n    const bool needs_assign = evaluator.evalSubExprsIfNeeded(nullptr);\n    if (needs_assign) {\n      const TilingContext tiling =\n          internal::GetTensorExecutorTilingContext<Evaluator, BlockMapper,\n                                                   Vectorizable>(evaluator);\n\n      auto eval_block = [&device, &evaluator, &tiling](IndexType firstBlockIdx,\n                                                       IndexType lastBlockIdx) {\n        TensorBlockScratch scratch(device);\n\n        for (IndexType block_idx = firstBlockIdx; block_idx < lastBlockIdx;\n             ++block_idx) {\n          TensorBlockDesc desc = tiling.block_mapper.blockDescriptor(block_idx);\n          evaluator.evalBlock(desc, scratch);\n          scratch.reset();\n        }\n      };\n\n      // Evaluate small expressions directly as a single block.\n      if (tiling.block_mapper.blockCount() == 1) {\n        TensorBlockScratch scratch(device);\n        TensorBlockDesc desc(0, tiling.block_mapper.blockDimensions());\n        evaluator.evalBlock(desc, scratch);\n      } else {\n        device.parallelFor(tiling.block_mapper.blockCount(), tiling.cost,\n                           eval_block);\n      }\n    }\n    evaluator.cleanup();\n  }\n};\n\ntemplate <typename Expression, typename DoneCallback, bool Vectorizable,\n          TiledEvaluation Tiling>\nclass TensorAsyncExecutor<Expression, ThreadPoolDevice, DoneCallback,\n                          Vectorizable, Tiling> {\n public:\n  typedef typename Expression::Index StorageIndex;\n  typedef TensorEvaluator<Expression, ThreadPoolDevice> Evaluator;\n\n  static EIGEN_STRONG_INLINE void runAsync(const Expression& expr,\n                                           const ThreadPoolDevice& device,\n                                           DoneCallback done) {\n    TensorAsyncExecutorContext* const ctx =\n        new TensorAsyncExecutorContext(expr, device, std::move(done));\n\n    const auto on_eval_subexprs = [ctx, &device](bool need_assign) -> void {\n      if (!need_assign) {\n        delete ctx;\n        return;\n      }\n\n      typedef EvalRange<Evaluator, StorageIndex, Vectorizable> EvalRange;\n      const StorageIndex size = array_prod(ctx->evaluator.dimensions());\n      device.parallelForAsync(\n          size, ctx->evaluator.costPerCoeff(Vectorizable),\n          EvalRange::alignBlockSize,\n          [ctx](StorageIndex firstIdx, StorageIndex lastIdx) {\n            EvalRange::run(&ctx->evaluator, firstIdx, lastIdx);\n          },\n          [ctx]() { delete ctx; });\n    };\n\n    ctx->evaluator.evalSubExprsIfNeededAsync(nullptr, on_eval_subexprs);\n  }\n\n private:\n  struct TensorAsyncExecutorContext {\n    TensorAsyncExecutorContext(const Expression& expr,\n                               const ThreadPoolDevice& thread_pool,\n                               DoneCallback done)\n        : evaluator(expr, thread_pool), on_done(std::move(done)) {}\n\n    ~TensorAsyncExecutorContext() {\n      evaluator.cleanup();\n      on_done();\n    }\n\n    Evaluator evaluator;\n\n   private:\n    DoneCallback on_done;\n  };\n};\n\ntemplate <typename Expression, typename DoneCallback, bool Vectorizable>\nclass TensorAsyncExecutor<Expression, ThreadPoolDevice, DoneCallback,\n                          Vectorizable, /*Tileable*/ TiledEvaluation::On> {\n public:\n  typedef typename traits<Expression>::Index IndexType;\n  typedef typename traits<Expression>::Scalar Scalar;\n  typedef typename remove_const<Scalar>::type ScalarNoConst;\n\n  static const int NumDims = traits<Expression>::NumDimensions;\n\n  typedef TensorEvaluator<Expression, ThreadPoolDevice> Evaluator;\n  typedef TensorBlockMapper<NumDims, Evaluator::Layout, IndexType> BlockMapper;\n  typedef TensorExecutorTilingContext<BlockMapper> TilingContext;\n\n  typedef internal::TensorBlockDescriptor<NumDims, IndexType> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<ThreadPoolDevice>\n      TensorBlockScratch;\n\n  static EIGEN_STRONG_INLINE void runAsync(const Expression& expr,\n                                           const ThreadPoolDevice& device,\n                                           DoneCallback done) {\n\n    TensorAsyncExecutorContext* const ctx =\n        new TensorAsyncExecutorContext(expr, device, std::move(done));\n\n    const auto on_eval_subexprs = [ctx](bool need_assign) -> void {\n      if (!need_assign) {\n        delete ctx;\n        return;\n      }\n\n      ctx->tiling = internal::GetTensorExecutorTilingContext<\n          Evaluator, BlockMapper, Vectorizable>(ctx->evaluator);\n\n      auto eval_block = [ctx](IndexType firstBlockIdx, IndexType lastBlockIdx) {\n        TensorBlockScratch scratch(ctx->device);\n\n        for (IndexType block_idx = firstBlockIdx; block_idx < lastBlockIdx;\n             ++block_idx) {\n          TensorBlockDesc desc =\n              ctx->tiling.block_mapper.blockDescriptor(block_idx);\n          ctx->evaluator.evalBlock(desc, scratch);\n          scratch.reset();\n        }\n      };\n\n      // Evaluate small expressions directly as a single block.\n      if (ctx->tiling.block_mapper.blockCount() == 1) {\n        TensorBlockScratch scratch(ctx->device);\n        TensorBlockDesc desc(0, ctx->tiling.block_mapper.blockDimensions());\n        ctx->evaluator.evalBlock(desc, scratch);\n        delete ctx;\n      } else {\n        ctx->device.parallelForAsync(ctx->tiling.block_mapper.blockCount(),\n                                     ctx->tiling.cost, eval_block,\n                                     [ctx]() { delete ctx; });\n      }\n    };\n\n    ctx->evaluator.evalSubExprsIfNeededAsync(nullptr, on_eval_subexprs);\n  }\n\n private:\n  struct TensorAsyncExecutorContext {\n    TensorAsyncExecutorContext(const Expression& expr,\n                               const ThreadPoolDevice& thread_pool,\n                               DoneCallback done)\n        : device(thread_pool),\n          evaluator(expr, thread_pool),\n          on_done(std::move(done)) {}\n\n    ~TensorAsyncExecutorContext() {\n      evaluator.cleanup();\n      on_done();\n    }\n\n    const ThreadPoolDevice& device;\n    Evaluator evaluator;\n    TilingContext tiling;\n\n   private:\n    DoneCallback on_done;\n  };\n};\n\n#endif  // EIGEN_USE_THREADS\n\n// GPU: the evaluation of the expression is offloaded to a GPU.\n#if defined(EIGEN_USE_GPU)\n\ntemplate <typename Expression, bool Vectorizable, TiledEvaluation Tiling>\nclass TensorExecutor<Expression, GpuDevice, Vectorizable, Tiling> {\n public:\n  typedef typename Expression::Index StorageIndex;\n  static void run(const Expression& expr, const GpuDevice& device);\n};\n\n#if defined(EIGEN_GPUCC)\ntemplate <typename Evaluator, typename StorageIndex, bool Vectorizable>\nstruct EigenMetaKernelEval {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  void run(Evaluator& eval, StorageIndex firstIdx, StorageIndex lastIdx, StorageIndex step_size) {\n    for (StorageIndex i = firstIdx; i < lastIdx; i += step_size) {\n      eval.evalScalar(i);\n    }\n  }\n};\n\ntemplate <typename Evaluator, typename StorageIndex>\nstruct EigenMetaKernelEval<Evaluator, StorageIndex, true> {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  void run(Evaluator& eval, StorageIndex firstIdx, StorageIndex lastIdx, StorageIndex step_size) {\n    const StorageIndex PacketSize = unpacket_traits<typename Evaluator::PacketReturnType>::size;\n    const StorageIndex vectorized_size = (lastIdx / PacketSize) * PacketSize;\n    const StorageIndex vectorized_step_size = step_size * PacketSize;\n\n    // Use the vector path\n    for (StorageIndex i = firstIdx * PacketSize; i < vectorized_size;\n         i += vectorized_step_size) {\n      eval.evalPacket(i);\n    }\n    for (StorageIndex i = vectorized_size + firstIdx; i < lastIdx; i += step_size) {\n      eval.evalScalar(i);\n    }\n  }\n};\n\ntemplate <typename Evaluator, typename StorageIndex>\n__global__ void\n__launch_bounds__(1024)\nEigenMetaKernel(Evaluator eval, StorageIndex size) {\n\n  const StorageIndex first_index = blockIdx.x * blockDim.x + threadIdx.x;\n  const StorageIndex step_size = blockDim.x * gridDim.x;\n\n  const bool vectorizable = Evaluator::PacketAccess & Evaluator::IsAligned;\n  EigenMetaKernelEval<Evaluator, StorageIndex, vectorizable>::run(eval, first_index, size, step_size);\n}\n\n/*static*/\ntemplate <typename Expression, bool Vectorizable, TiledEvaluation Tiling>\nEIGEN_STRONG_INLINE void TensorExecutor<Expression, GpuDevice, Vectorizable, Tiling>::run(\n    const Expression& expr, const GpuDevice& device) {\n  TensorEvaluator<Expression, GpuDevice> evaluator(expr, device);\n  const bool needs_assign = evaluator.evalSubExprsIfNeeded(nullptr);\n  if (needs_assign) {\n\n    const int block_size = device.maxGpuThreadsPerBlock();\n    const int max_blocks = device.getNumGpuMultiProcessors() *\n                           device.maxGpuThreadsPerMultiProcessor() / block_size;\n    const StorageIndex size = array_prod(evaluator.dimensions());\n    // Create a least one block to ensure we won't crash when tensorflow calls with tensors of size 0.\n    const int num_blocks = numext::maxi<int>(numext::mini<int>(max_blocks, divup<int>(size, block_size)), 1);\n\n    LAUNCH_GPU_KERNEL(\n        (EigenMetaKernel<TensorEvaluator<Expression, GpuDevice>, StorageIndex>),\n        num_blocks, block_size, 0, device, evaluator, size);\n  }\n  evaluator.cleanup();\n}\n\n#endif  // EIGEN_GPUCC\n#endif  // EIGEN_USE_GPU\n\n// SYCL Executor policy\n#ifdef EIGEN_USE_SYCL\n\ntemplate <typename Evaluator>\nstruct ExecExprFunctorKernel {\n  typedef typename Evaluator::Index Index;\n  Evaluator evaluator;\n  const Index range;\n  template <typename Scratch>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE ExecExprFunctorKernel(\n      const Scratch, Evaluator evaluator_, const Index range_)\n      : evaluator(evaluator_), range(range_) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE void operator()(\n      cl::sycl::nd_item<1> itemID) {\n    compute(itemID);\n  }\n  template <bool is_vec = Evaluator::PacketAccess>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE typename std::enable_if<!is_vec>::type\n  compute(const cl::sycl::nd_item<1>& itemID) {\n    Index gId = static_cast<Index>(itemID.get_global_linear_id());\n    Index total_threads = itemID.get_global_range(0);\n\n    for (Index i = gId; i < range; i += total_threads) {\n      evaluator.evalScalar(i);\n    }\n  }\n  template <bool is_vec = Evaluator::PacketAccess>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE typename std::enable_if<is_vec>::type\n  compute(const cl::sycl::nd_item<1>& itemID) {\n    const Index vectorizedRange =\n        (range / Evaluator::PacketSize) * Evaluator::PacketSize;\n    Index gId = static_cast<Index>(itemID.get_global_linear_id());\n    const Index step = Evaluator::PacketSize * itemID.get_global_range(0);\n    const Index start = Evaluator::PacketSize * gId;\n    for (Index i = start; i < vectorizedRange; i += step) {\n      evaluator.evalPacket(i);\n    }\n    gId += vectorizedRange;\n    for (Index i = gId; i < range; i += itemID.get_global_range(0)) {\n      evaluator.evalScalar(i);\n    }\n  }\n};\n\ntemplate <typename Expression, bool Vectorizable, TiledEvaluation Tiling>\nclass TensorExecutor<Expression, Eigen::SyclDevice, Vectorizable, Tiling> {\n public:\n  typedef typename Expression::Index Index;\n  static EIGEN_STRONG_INLINE void run(const Expression& expr,\n                                      const Eigen::SyclDevice& dev) {\n    typedef Eigen::TensorEvaluator<Expression, Eigen::SyclDevice> Evaluator;\n    Evaluator evaluator(expr, dev);\n    const bool needs_assign = evaluator.evalSubExprsIfNeeded(NULL);\n    if (needs_assign) {\n      Index range, GRange, tileSize;\n      Index total_size = ::Eigen::internal::array_prod(evaluator.dimensions());\n      total_size = (total_size == 0) ? 1 : total_size;\n      const int PacketSize =\n          Eigen::PacketType<typename Evaluator::CoeffReturnType,\n                            Eigen::SyclDevice>::size;\n      Index vectorizable_threads = static_cast<Index>(total_size / PacketSize);\n      dev.parallel_for_setup(vectorizable_threads, tileSize, range, GRange);\n      range = total_size;\n\n      dev.template nullary_kernel_launcher<\n          typename Evaluator::CoeffReturnType,\n          ExecExprFunctorKernel<Evaluator> >(\n          evaluator,\n          cl::sycl::nd_range<1>(cl::sycl::range<1>(GRange),\n                                cl::sycl::range<1>(tileSize)),\n          Index(1), range);\n    }\n    evaluator.cleanup();\n  }\n};\n\n#endif\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_EXECUTOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorExpr.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_EXPR_H\n#define EIGEN_CXX11_TENSOR_TENSOR_EXPR_H\n\nnamespace Eigen {\n\n/** \\class TensorExpr\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor expression classes.\n  *\n  * The TensorCwiseNullaryOp class applies a nullary operators to an expression.\n  * This is typically used to generate constants.\n  *\n  * The TensorCwiseUnaryOp class represents an expression where a unary operator\n  * (e.g. cwiseSqrt) is applied to an expression.\n  *\n  * The TensorCwiseBinaryOp class represents an expression where a binary\n  * operator (e.g. addition) is applied to a lhs and a rhs expression.\n  *\n  */\nnamespace internal {\ntemplate<typename NullaryOp, typename XprType>\nstruct traits<TensorCwiseNullaryOp<NullaryOp, XprType> >\n    : traits<XprType>\n{\n  typedef traits<XprType> XprTraits;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::Nested XprTypeNested;\n  typedef typename remove_reference<XprTypeNested>::type _XprTypeNested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n  enum {\n    Flags = 0\n  };\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename NullaryOp, typename XprType>\nclass TensorCwiseNullaryOp : public TensorBase<TensorCwiseNullaryOp<NullaryOp, XprType>, ReadOnlyAccessors>\n{\n  public:\n    typedef typename Eigen::internal::traits<TensorCwiseNullaryOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef typename XprType::CoeffReturnType CoeffReturnType;\n    typedef TensorCwiseNullaryOp<NullaryOp, XprType> Nested;\n    typedef typename Eigen::internal::traits<TensorCwiseNullaryOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorCwiseNullaryOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCwiseNullaryOp(const XprType& xpr, const NullaryOp& func = NullaryOp())\n        : m_xpr(xpr), m_functor(func) {}\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    nestedExpression() const { return m_xpr; }\n\n    EIGEN_DEVICE_FUNC\n    const NullaryOp& functor() const { return m_functor; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const NullaryOp m_functor;\n};\n\n\n\nnamespace internal {\ntemplate<typename UnaryOp, typename XprType>\nstruct traits<TensorCwiseUnaryOp<UnaryOp, XprType> >\n    : traits<XprType>\n{\n  // TODO(phli): Add InputScalar, InputPacket.  Check references to\n  // current Scalar/Packet to see if the intent is Input or Output.\n  typedef typename result_of<UnaryOp(typename XprType::Scalar)>::type Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprType::Nested XprTypeNested;\n  typedef typename remove_reference<XprTypeNested>::type _XprTypeNested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename TypeConversion<Scalar, \n                                  typename XprTraits::PointerType\n                                  >::type \n                                  PointerType;\n};\n\ntemplate<typename UnaryOp, typename XprType>\nstruct eval<TensorCwiseUnaryOp<UnaryOp, XprType>, Eigen::Dense>\n{\n  typedef const TensorCwiseUnaryOp<UnaryOp, XprType>& type;\n};\n\ntemplate<typename UnaryOp, typename XprType>\nstruct nested<TensorCwiseUnaryOp<UnaryOp, XprType>, 1, typename eval<TensorCwiseUnaryOp<UnaryOp, XprType> >::type>\n{\n  typedef TensorCwiseUnaryOp<UnaryOp, XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename UnaryOp, typename XprType>\nclass TensorCwiseUnaryOp : public TensorBase<TensorCwiseUnaryOp<UnaryOp, XprType>, ReadOnlyAccessors>\n{\n  public:\n    // TODO(phli): Add InputScalar, InputPacket.  Check references to\n    // current Scalar/Packet to see if the intent is Input or Output.\n    typedef typename Eigen::internal::traits<TensorCwiseUnaryOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef Scalar CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorCwiseUnaryOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorCwiseUnaryOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorCwiseUnaryOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCwiseUnaryOp(const XprType& xpr, const UnaryOp& func = UnaryOp())\n      : m_xpr(xpr), m_functor(func) {}\n\n    EIGEN_DEVICE_FUNC\n    const UnaryOp& functor() const { return m_functor; }\n\n    /** \\returns the nested expression */\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    nestedExpression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const UnaryOp m_functor;\n};\n\n\nnamespace internal {\ntemplate<typename BinaryOp, typename LhsXprType, typename RhsXprType>\nstruct traits<TensorCwiseBinaryOp<BinaryOp, LhsXprType, RhsXprType> >\n{\n  // Type promotion to handle the case where the types of the lhs and the rhs\n  // are different.\n  // TODO(phli): Add Lhs/RhsScalar, Lhs/RhsPacket.  Check references to\n  // current Scalar/Packet to see if the intent is Inputs or Output.\n  typedef typename result_of<\n      BinaryOp(typename LhsXprType::Scalar,\n               typename RhsXprType::Scalar)>::type Scalar;\n  typedef traits<LhsXprType> XprTraits;\n  typedef typename promote_storage_type<\n      typename traits<LhsXprType>::StorageKind,\n      typename traits<RhsXprType>::StorageKind>::ret StorageKind;\n  typedef typename promote_index_type<\n      typename traits<LhsXprType>::Index,\n      typename traits<RhsXprType>::Index>::type Index;\n  typedef typename LhsXprType::Nested LhsNested;\n  typedef typename RhsXprType::Nested RhsNested;\n  typedef typename remove_reference<LhsNested>::type _LhsNested;\n  typedef typename remove_reference<RhsNested>::type _RhsNested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename TypeConversion<Scalar,\n                                  typename conditional<Pointer_type_promotion<typename LhsXprType::Scalar, Scalar>::val,\n                                                      typename traits<LhsXprType>::PointerType,\n                                                      typename traits<RhsXprType>::PointerType>::type\n                                  >::type \n                                  PointerType;\n  enum {\n    Flags = 0\n  };\n};\n\ntemplate<typename BinaryOp, typename LhsXprType, typename RhsXprType>\nstruct eval<TensorCwiseBinaryOp<BinaryOp, LhsXprType, RhsXprType>, Eigen::Dense>\n{\n  typedef const TensorCwiseBinaryOp<BinaryOp, LhsXprType, RhsXprType>& type;\n};\n\ntemplate<typename BinaryOp, typename LhsXprType, typename RhsXprType>\nstruct nested<TensorCwiseBinaryOp<BinaryOp, LhsXprType, RhsXprType>, 1, typename eval<TensorCwiseBinaryOp<BinaryOp, LhsXprType, RhsXprType> >::type>\n{\n  typedef TensorCwiseBinaryOp<BinaryOp, LhsXprType, RhsXprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename BinaryOp, typename LhsXprType, typename RhsXprType>\nclass TensorCwiseBinaryOp : public TensorBase<TensorCwiseBinaryOp<BinaryOp, LhsXprType, RhsXprType>, ReadOnlyAccessors>\n{\n  public:\n    // TODO(phli): Add Lhs/RhsScalar, Lhs/RhsPacket.  Check references to\n    // current Scalar/Packet to see if the intent is Inputs or Output.\n    typedef typename Eigen::internal::traits<TensorCwiseBinaryOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef Scalar CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorCwiseBinaryOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorCwiseBinaryOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorCwiseBinaryOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCwiseBinaryOp(const LhsXprType& lhs, const RhsXprType& rhs, const BinaryOp& func = BinaryOp())\n        : m_lhs_xpr(lhs), m_rhs_xpr(rhs), m_functor(func) {}\n\n    EIGEN_DEVICE_FUNC\n    const BinaryOp& functor() const { return m_functor; }\n\n    /** \\returns the nested expressions */\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename LhsXprType::Nested>::type&\n    lhsExpression() const { return m_lhs_xpr; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename RhsXprType::Nested>::type&\n    rhsExpression() const { return m_rhs_xpr; }\n\n  protected:\n    typename LhsXprType::Nested m_lhs_xpr;\n    typename RhsXprType::Nested m_rhs_xpr;\n    const BinaryOp m_functor;\n};\n\n\nnamespace internal {\ntemplate<typename TernaryOp, typename Arg1XprType, typename Arg2XprType, typename Arg3XprType>\nstruct traits<TensorCwiseTernaryOp<TernaryOp, Arg1XprType, Arg2XprType, Arg3XprType> >\n{\n  // Type promotion to handle the case where the types of the args are different.\n  typedef typename result_of<\n      TernaryOp(typename Arg1XprType::Scalar,\n                typename Arg2XprType::Scalar,\n                typename Arg3XprType::Scalar)>::type Scalar;\n  typedef traits<Arg1XprType> XprTraits;\n  typedef typename traits<Arg1XprType>::StorageKind StorageKind;\n  typedef typename traits<Arg1XprType>::Index Index;\n  typedef typename Arg1XprType::Nested Arg1Nested;\n  typedef typename Arg2XprType::Nested Arg2Nested;\n  typedef typename Arg3XprType::Nested Arg3Nested;\n  typedef typename remove_reference<Arg1Nested>::type _Arg1Nested;\n  typedef typename remove_reference<Arg2Nested>::type _Arg2Nested;\n  typedef typename remove_reference<Arg3Nested>::type _Arg3Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename TypeConversion<Scalar,\n                                  typename conditional<Pointer_type_promotion<typename Arg2XprType::Scalar, Scalar>::val,\n                                                      typename traits<Arg2XprType>::PointerType,\n                                                      typename traits<Arg3XprType>::PointerType>::type\n                                  >::type \n                                  PointerType;\n  enum {\n    Flags = 0\n  };\n};\n\ntemplate<typename TernaryOp, typename Arg1XprType, typename Arg2XprType, typename Arg3XprType>\nstruct eval<TensorCwiseTernaryOp<TernaryOp, Arg1XprType, Arg2XprType, Arg3XprType>, Eigen::Dense>\n{\n  typedef const TensorCwiseTernaryOp<TernaryOp, Arg1XprType, Arg2XprType, Arg3XprType>& type;\n};\n\ntemplate<typename TernaryOp, typename Arg1XprType, typename Arg2XprType, typename Arg3XprType>\nstruct nested<TensorCwiseTernaryOp<TernaryOp, Arg1XprType, Arg2XprType, Arg3XprType>, 1, typename eval<TensorCwiseTernaryOp<TernaryOp, Arg1XprType, Arg2XprType, Arg3XprType> >::type>\n{\n  typedef TensorCwiseTernaryOp<TernaryOp, Arg1XprType, Arg2XprType, Arg3XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename TernaryOp, typename Arg1XprType, typename Arg2XprType, typename Arg3XprType>\nclass TensorCwiseTernaryOp : public TensorBase<TensorCwiseTernaryOp<TernaryOp, Arg1XprType, Arg2XprType, Arg3XprType>, ReadOnlyAccessors>\n{\n  public:\n    typedef typename Eigen::internal::traits<TensorCwiseTernaryOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef Scalar CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorCwiseTernaryOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorCwiseTernaryOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorCwiseTernaryOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorCwiseTernaryOp(const Arg1XprType& arg1, const Arg2XprType& arg2, const Arg3XprType& arg3, const TernaryOp& func = TernaryOp())\n        : m_arg1_xpr(arg1), m_arg2_xpr(arg2), m_arg3_xpr(arg3), m_functor(func) {}\n\n    EIGEN_DEVICE_FUNC\n    const TernaryOp& functor() const { return m_functor; }\n\n    /** \\returns the nested expressions */\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename Arg1XprType::Nested>::type&\n    arg1Expression() const { return m_arg1_xpr; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename Arg2XprType::Nested>::type&\n    arg2Expression() const { return m_arg2_xpr; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename Arg3XprType::Nested>::type&\n    arg3Expression() const { return m_arg3_xpr; }\n\n  protected:\n    typename Arg1XprType::Nested m_arg1_xpr;\n    typename Arg2XprType::Nested m_arg2_xpr;\n    typename Arg3XprType::Nested m_arg3_xpr;\n    const TernaryOp m_functor;\n};\n\n\nnamespace internal {\ntemplate<typename IfXprType, typename ThenXprType, typename ElseXprType>\nstruct traits<TensorSelectOp<IfXprType, ThenXprType, ElseXprType> >\n    : traits<ThenXprType>\n{\n  typedef typename traits<ThenXprType>::Scalar Scalar;\n  typedef traits<ThenXprType> XprTraits;\n  typedef typename promote_storage_type<typename traits<ThenXprType>::StorageKind,\n                                        typename traits<ElseXprType>::StorageKind>::ret StorageKind;\n  typedef typename promote_index_type<typename traits<ElseXprType>::Index,\n                                      typename traits<ThenXprType>::Index>::type Index;\n  typedef typename IfXprType::Nested IfNested;\n  typedef typename ThenXprType::Nested ThenNested;\n  typedef typename ElseXprType::Nested ElseNested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename conditional<Pointer_type_promotion<typename ThenXprType::Scalar, Scalar>::val,\n                               typename traits<ThenXprType>::PointerType,\n                               typename traits<ElseXprType>::PointerType>::type PointerType;\n};\n\ntemplate<typename IfXprType, typename ThenXprType, typename ElseXprType>\nstruct eval<TensorSelectOp<IfXprType, ThenXprType, ElseXprType>, Eigen::Dense>\n{\n  typedef const TensorSelectOp<IfXprType, ThenXprType, ElseXprType>& type;\n};\n\ntemplate<typename IfXprType, typename ThenXprType, typename ElseXprType>\nstruct nested<TensorSelectOp<IfXprType, ThenXprType, ElseXprType>, 1, typename eval<TensorSelectOp<IfXprType, ThenXprType, ElseXprType> >::type>\n{\n  typedef TensorSelectOp<IfXprType, ThenXprType, ElseXprType> type;\n};\n\n}  // end namespace internal\n\n\ntemplate<typename IfXprType, typename ThenXprType, typename ElseXprType>\nclass TensorSelectOp : public TensorBase<TensorSelectOp<IfXprType, ThenXprType, ElseXprType>, ReadOnlyAccessors>\n{\n  public:\n    typedef typename Eigen::internal::traits<TensorSelectOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef typename internal::promote_storage_type<typename ThenXprType::CoeffReturnType,\n                                                    typename ElseXprType::CoeffReturnType>::ret CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorSelectOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorSelectOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorSelectOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC\n    TensorSelectOp(const IfXprType& a_condition,\n                   const ThenXprType& a_then,\n                   const ElseXprType& a_else)\n      : m_condition(a_condition), m_then(a_then), m_else(a_else)\n    { }\n\n    EIGEN_DEVICE_FUNC\n    const IfXprType& ifExpression() const { return m_condition; }\n\n    EIGEN_DEVICE_FUNC\n    const ThenXprType& thenExpression() const { return m_then; }\n\n    EIGEN_DEVICE_FUNC\n    const ElseXprType& elseExpression() const { return m_else; }\n\n  protected:\n    typename IfXprType::Nested m_condition;\n    typename ThenXprType::Nested m_then;\n    typename ElseXprType::Nested m_else;\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_EXPR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFFT.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Jianwei Cui <thucjw@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_FFT_H\n#define EIGEN_CXX11_TENSOR_TENSOR_FFT_H\n\nnamespace Eigen {\n\n/** \\class TensorFFT\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor FFT class.\n  *\n  * TODO:\n  * Vectorize the Cooley Tukey and the Bluestein algorithm\n  * Add support for multithreaded evaluation\n  * Improve the performance on GPU\n  */\n\ntemplate <bool NeedUprade> struct MakeComplex {\n  template <typename T>\n  EIGEN_DEVICE_FUNC\n  T operator() (const T& val) const { return val; }\n};\n\ntemplate <> struct MakeComplex<true> {\n  template <typename T>\n  EIGEN_DEVICE_FUNC\n  std::complex<T> operator() (const T& val) const { return std::complex<T>(val, 0); }\n};\n\ntemplate <> struct MakeComplex<false> {\n  template <typename T>\n  EIGEN_DEVICE_FUNC\n  std::complex<T> operator() (const std::complex<T>& val) const { return val; }\n};\n\ntemplate <int ResultType> struct PartOf {\n  template <typename T> T operator() (const T& val) const { return val; }\n};\n\ntemplate <> struct PartOf<RealPart> {\n  template <typename T> T operator() (const std::complex<T>& val) const { return val.real(); }\n};\n\ntemplate <> struct PartOf<ImagPart> {\n  template <typename T> T operator() (const std::complex<T>& val) const { return val.imag(); }\n};\n\nnamespace internal {\ntemplate <typename FFT, typename XprType, int FFTResultType, int FFTDir>\nstruct traits<TensorFFTOp<FFT, XprType, FFTResultType, FFTDir> > : public traits<XprType> {\n  typedef traits<XprType> XprTraits;\n  typedef typename NumTraits<typename XprTraits::Scalar>::Real RealScalar;\n  typedef typename std::complex<RealScalar> ComplexScalar;\n  typedef typename XprTraits::Scalar InputScalar;\n  typedef typename conditional<FFTResultType == RealPart || FFTResultType == ImagPart, RealScalar, ComplexScalar>::type OutputScalar;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename traits<XprType>::PointerType PointerType;\n};\n\ntemplate <typename FFT, typename XprType, int FFTResultType, int FFTDirection>\nstruct eval<TensorFFTOp<FFT, XprType, FFTResultType, FFTDirection>, Eigen::Dense> {\n  typedef const TensorFFTOp<FFT, XprType, FFTResultType, FFTDirection>& type;\n};\n\ntemplate <typename FFT, typename XprType, int FFTResultType, int FFTDirection>\nstruct nested<TensorFFTOp<FFT, XprType, FFTResultType, FFTDirection>, 1, typename eval<TensorFFTOp<FFT, XprType, FFTResultType, FFTDirection> >::type> {\n  typedef TensorFFTOp<FFT, XprType, FFTResultType, FFTDirection> type;\n};\n\n}  // end namespace internal\n\ntemplate <typename FFT, typename XprType, int FFTResultType, int FFTDir>\nclass TensorFFTOp : public TensorBase<TensorFFTOp<FFT, XprType, FFTResultType, FFTDir>, ReadOnlyAccessors> {\n public:\n  typedef typename Eigen::internal::traits<TensorFFTOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename std::complex<RealScalar> ComplexScalar;\n  typedef typename internal::conditional<FFTResultType == RealPart || FFTResultType == ImagPart, RealScalar, ComplexScalar>::type OutputScalar;\n  typedef OutputScalar CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorFFTOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorFFTOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorFFTOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorFFTOp(const XprType& expr, const FFT& fft)\n      : m_xpr(expr), m_fft(fft) {}\n\n  EIGEN_DEVICE_FUNC\n  const FFT& fft() const { return m_fft; }\n\n  EIGEN_DEVICE_FUNC\n  const typename internal::remove_all<typename XprType::Nested>::type& expression() const {\n    return m_xpr;\n  }\n\n protected:\n  typename XprType::Nested m_xpr;\n  const FFT m_fft;\n};\n\n// Eval as rvalue\ntemplate <typename FFT, typename ArgType, typename Device, int FFTResultType, int FFTDir>\nstruct TensorEvaluator<const TensorFFTOp<FFT, ArgType, FFTResultType, FFTDir>, Device> {\n  typedef TensorFFTOp<FFT, ArgType, FFTResultType, FFTDir> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename std::complex<RealScalar> ComplexScalar;\n  typedef typename TensorEvaluator<ArgType, Device>::Dimensions InputDimensions;\n  typedef internal::traits<XprType> XprTraits;\n  typedef typename XprTraits::Scalar InputScalar;\n  typedef typename internal::conditional<FFTResultType == RealPart || FFTResultType == ImagPart, RealScalar, ComplexScalar>::type OutputScalar;\n  typedef OutputScalar CoeffReturnType;\n  typedef typename PacketType<OutputScalar, Device>::type PacketReturnType;\n  static const int PacketSize = internal::unpacket_traits<PacketReturnType>::size;\n    typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = true,\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) : m_fft(op.fft()), m_impl(op.expression(), device), m_data(NULL), m_device(device) {\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n    for (int i = 0; i < NumDims; ++i) {\n      eigen_assert(input_dims[i] > 0);\n      m_dimensions[i] = input_dims[i];\n    }\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_strides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_strides[i] = m_strides[i - 1] * m_dimensions[i - 1];\n      }\n    } else {\n      m_strides[NumDims - 1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_strides[i] = m_strides[i + 1] * m_dimensions[i + 1];\n      }\n    }\n    m_size = m_dimensions.TotalSize();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const {\n    return m_dimensions;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    if (data) {\n      evalToBuf(data);\n      return false;\n    } else {\n      m_data = (EvaluatorPointerType)m_device.get((CoeffReturnType*)(m_device.allocate_temp(sizeof(CoeffReturnType) * m_size)));\n      evalToBuf(m_data);\n      return true;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    if (m_data) {\n      m_device.deallocate(m_data);\n      m_data = NULL;\n    }\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE CoeffReturnType coeff(Index index) const {\n    return m_data[index];\n  }\n\n  template <int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE PacketReturnType\n  packet(Index index) const {\n    return internal::ploadt<PacketReturnType, LoadMode>(m_data + index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return m_data; }\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_data.bind(cgh);\n  }\n#endif\n\n private:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalToBuf(EvaluatorPointerType data) {\n    const bool write_to_out = internal::is_same<OutputScalar, ComplexScalar>::value;\n    ComplexScalar* buf = write_to_out ? (ComplexScalar*)data : (ComplexScalar*)m_device.allocate(sizeof(ComplexScalar) * m_size);\n\n    for (Index i = 0; i < m_size; ++i) {\n      buf[i] = MakeComplex<internal::is_same<InputScalar, RealScalar>::value>()(m_impl.coeff(i));\n    }\n\n    for (size_t i = 0; i < m_fft.size(); ++i) {\n      Index dim = m_fft[i];\n      eigen_assert(dim >= 0 && dim < NumDims);\n      Index line_len = m_dimensions[dim];\n      eigen_assert(line_len >= 1);\n      ComplexScalar* line_buf = (ComplexScalar*)m_device.allocate(sizeof(ComplexScalar) * line_len);\n      const bool is_power_of_two = isPowerOfTwo(line_len);\n      const Index good_composite = is_power_of_two ? 0 : findGoodComposite(line_len);\n      const Index log_len = is_power_of_two ? getLog2(line_len) : getLog2(good_composite);\n\n      ComplexScalar* a = is_power_of_two ? NULL : (ComplexScalar*)m_device.allocate(sizeof(ComplexScalar) * good_composite);\n      ComplexScalar* b = is_power_of_two ? NULL : (ComplexScalar*)m_device.allocate(sizeof(ComplexScalar) * good_composite);\n      ComplexScalar* pos_j_base_powered = is_power_of_two ? NULL : (ComplexScalar*)m_device.allocate(sizeof(ComplexScalar) * (line_len + 1));\n      if (!is_power_of_two) {\n        // Compute twiddle factors\n        //   t_n = exp(sqrt(-1) * pi * n^2 / line_len)\n        // for n = 0, 1,..., line_len-1.\n        // For n > 2 we use the recurrence t_n = t_{n-1}^2 / t_{n-2} * t_1^2\n\n        // The recurrence is correct in exact arithmetic, but causes\n        // numerical issues for large transforms, especially in\n        // single-precision floating point.\n        //\n        // pos_j_base_powered[0] = ComplexScalar(1, 0);\n        // if (line_len > 1) {\n        //   const ComplexScalar pos_j_base = ComplexScalar(\n        //       numext::cos(M_PI / line_len), numext::sin(M_PI / line_len));\n        //   pos_j_base_powered[1] = pos_j_base;\n        //   if (line_len > 2) {\n        //     const ComplexScalar pos_j_base_sq = pos_j_base * pos_j_base;\n        //     for (int i = 2; i < line_len + 1; ++i) {\n        //       pos_j_base_powered[i] = pos_j_base_powered[i - 1] *\n        //           pos_j_base_powered[i - 1] /\n        //           pos_j_base_powered[i - 2] *\n        //           pos_j_base_sq;\n        //     }\n        //   }\n        // }\n        // TODO(rmlarsen): Find a way to use Eigen's vectorized sin\n        // and cosine functions here.\n        for (int j = 0; j < line_len + 1; ++j) {\n          double arg = ((EIGEN_PI * j) * j) / line_len;\n          std::complex<double> tmp(numext::cos(arg), numext::sin(arg));\n          pos_j_base_powered[j] = static_cast<ComplexScalar>(tmp);\n        }\n      }\n\n      for (Index partial_index = 0; partial_index < m_size / line_len; ++partial_index) {\n        const Index base_offset = getBaseOffsetFromIndex(partial_index, dim);\n\n        // get data into line_buf\n        const Index stride = m_strides[dim];\n        if (stride == 1) {\n          m_device.memcpy(line_buf, &buf[base_offset], line_len*sizeof(ComplexScalar));\n        } else {\n          Index offset = base_offset;\n          for (int j = 0; j < line_len; ++j, offset += stride) {\n            line_buf[j] = buf[offset];\n          }\n        }\n\n        // process the line\n        if (is_power_of_two) {\n          processDataLineCooleyTukey(line_buf, line_len, log_len);\n        }\n        else {\n          processDataLineBluestein(line_buf, line_len, good_composite, log_len, a, b, pos_j_base_powered);\n        }\n\n        // write back\n        if (FFTDir == FFT_FORWARD && stride == 1) {\n          m_device.memcpy(&buf[base_offset], line_buf, line_len*sizeof(ComplexScalar));\n        } else {\n          Index offset = base_offset;\n          const ComplexScalar div_factor =  ComplexScalar(1.0 / line_len, 0);\n          for (int j = 0; j < line_len; ++j, offset += stride) {\n             buf[offset] = (FFTDir == FFT_FORWARD) ? line_buf[j] : line_buf[j] * div_factor;\n          }\n        }\n      }\n      m_device.deallocate(line_buf);\n      if (!is_power_of_two) {\n        m_device.deallocate(a);\n        m_device.deallocate(b);\n        m_device.deallocate(pos_j_base_powered);\n      }\n    }\n\n    if(!write_to_out) {\n      for (Index i = 0; i < m_size; ++i) {\n        data[i] = PartOf<FFTResultType>()(buf[i]);\n      }\n      m_device.deallocate(buf);\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static bool isPowerOfTwo(Index x) {\n    eigen_assert(x > 0);\n    return !(x & (x - 1));\n  }\n\n  // The composite number for padding, used in Bluestein's FFT algorithm\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static Index findGoodComposite(Index n) {\n    Index i = 2;\n    while (i < 2 * n - 1) i *= 2;\n    return i;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static Index getLog2(Index m) {\n    Index log2m = 0;\n    while (m >>= 1) log2m++;\n    return log2m;\n  }\n\n  // Call Cooley Tukey algorithm directly, data length must be power of 2\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void processDataLineCooleyTukey(ComplexScalar* line_buf, Index line_len, Index log_len) {\n    eigen_assert(isPowerOfTwo(line_len));\n    scramble_FFT(line_buf, line_len);\n    compute_1D_Butterfly<FFTDir>(line_buf, line_len, log_len);\n  }\n\n  // Call Bluestein's FFT algorithm, m is a good composite number greater than (2 * n - 1), used as the padding length\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void processDataLineBluestein(ComplexScalar* line_buf, Index line_len, Index good_composite, Index log_len, ComplexScalar* a, ComplexScalar* b, const ComplexScalar* pos_j_base_powered) {\n    Index n = line_len;\n    Index m = good_composite;\n    ComplexScalar* data = line_buf;\n\n    for (Index i = 0; i < n; ++i) {\n      if(FFTDir == FFT_FORWARD) {\n        a[i] = data[i] * numext::conj(pos_j_base_powered[i]);\n      }\n      else {\n        a[i] = data[i] * pos_j_base_powered[i];\n      }\n    }\n    for (Index i = n; i < m; ++i) {\n      a[i] = ComplexScalar(0, 0);\n    }\n\n    for (Index i = 0; i < n; ++i) {\n      if(FFTDir == FFT_FORWARD) {\n        b[i] = pos_j_base_powered[i];\n      }\n      else {\n        b[i] = numext::conj(pos_j_base_powered[i]);\n      }\n    }\n    for (Index i = n; i < m - n; ++i) {\n      b[i] = ComplexScalar(0, 0);\n    }\n    for (Index i = m - n; i < m; ++i) {\n      if(FFTDir == FFT_FORWARD) {\n        b[i] = pos_j_base_powered[m-i];\n      }\n      else {\n        b[i] = numext::conj(pos_j_base_powered[m-i]);\n      }\n    }\n\n    scramble_FFT(a, m);\n    compute_1D_Butterfly<FFT_FORWARD>(a, m, log_len);\n\n    scramble_FFT(b, m);\n    compute_1D_Butterfly<FFT_FORWARD>(b, m, log_len);\n\n    for (Index i = 0; i < m; ++i) {\n      a[i] *= b[i];\n    }\n\n    scramble_FFT(a, m);\n    compute_1D_Butterfly<FFT_REVERSE>(a, m, log_len);\n\n    //Do the scaling after ifft\n    for (Index i = 0; i < m; ++i) {\n      a[i] /= m;\n    }\n\n    for (Index i = 0; i < n; ++i) {\n      if(FFTDir == FFT_FORWARD) {\n        data[i] = a[i] * numext::conj(pos_j_base_powered[i]);\n      }\n      else {\n        data[i] = a[i] * pos_j_base_powered[i];\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE static void scramble_FFT(ComplexScalar* data, Index n) {\n    eigen_assert(isPowerOfTwo(n));\n    Index j = 1;\n    for (Index i = 1; i < n; ++i){\n      if (j > i) {\n        std::swap(data[j-1], data[i-1]);\n      }\n      Index m = n >> 1;\n      while (m >= 2 && j > m) {\n        j -= m;\n        m >>= 1;\n      }\n      j += m;\n    }\n  }\n\n  template <int Dir>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void butterfly_2(ComplexScalar* data) {\n    ComplexScalar tmp = data[1];\n    data[1] = data[0] - data[1];\n    data[0] += tmp;\n  }\n\n  template <int Dir>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void butterfly_4(ComplexScalar* data) {\n    ComplexScalar tmp[4];\n    tmp[0] = data[0] + data[1];\n    tmp[1] = data[0] - data[1];\n    tmp[2] = data[2] + data[3];\n    if (Dir == FFT_FORWARD) {\n      tmp[3] = ComplexScalar(0.0, -1.0) * (data[2] - data[3]);\n    } else {\n      tmp[3] = ComplexScalar(0.0, 1.0) * (data[2] - data[3]);\n    }\n    data[0] = tmp[0] + tmp[2];\n    data[1] = tmp[1] + tmp[3];\n    data[2] = tmp[0] - tmp[2];\n    data[3] = tmp[1] - tmp[3];\n  }\n\n  template <int Dir>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void butterfly_8(ComplexScalar* data) {\n    ComplexScalar tmp_1[8];\n    ComplexScalar tmp_2[8];\n\n    tmp_1[0] = data[0] + data[1];\n    tmp_1[1] = data[0] - data[1];\n    tmp_1[2] = data[2] + data[3];\n    if (Dir == FFT_FORWARD) {\n      tmp_1[3] = (data[2] - data[3]) * ComplexScalar(0, -1);\n    } else {\n      tmp_1[3] = (data[2] - data[3]) * ComplexScalar(0, 1);\n    }\n    tmp_1[4] = data[4] + data[5];\n    tmp_1[5] = data[4] - data[5];\n    tmp_1[6] = data[6] + data[7];\n    if (Dir == FFT_FORWARD) {\n      tmp_1[7] = (data[6] - data[7]) * ComplexScalar(0, -1);\n    } else {\n      tmp_1[7] = (data[6] - data[7]) * ComplexScalar(0, 1);\n    }\n    tmp_2[0] = tmp_1[0] + tmp_1[2];\n    tmp_2[1] = tmp_1[1] + tmp_1[3];\n    tmp_2[2] = tmp_1[0] - tmp_1[2];\n    tmp_2[3] = tmp_1[1] - tmp_1[3];\n    tmp_2[4] = tmp_1[4] + tmp_1[6];\n// SQRT2DIV2 = sqrt(2)/2\n#define SQRT2DIV2 0.7071067811865476\n    if (Dir == FFT_FORWARD) {\n      tmp_2[5] = (tmp_1[5] + tmp_1[7]) * ComplexScalar(SQRT2DIV2, -SQRT2DIV2);\n      tmp_2[6] = (tmp_1[4] - tmp_1[6]) * ComplexScalar(0, -1);\n      tmp_2[7] = (tmp_1[5] - tmp_1[7]) * ComplexScalar(-SQRT2DIV2, -SQRT2DIV2);\n    } else {\n      tmp_2[5] = (tmp_1[5] + tmp_1[7]) * ComplexScalar(SQRT2DIV2, SQRT2DIV2);\n      tmp_2[6] = (tmp_1[4] - tmp_1[6]) * ComplexScalar(0, 1);\n      tmp_2[7] = (tmp_1[5] - tmp_1[7]) * ComplexScalar(-SQRT2DIV2, SQRT2DIV2);\n    }\n    data[0] = tmp_2[0] + tmp_2[4];\n    data[1] = tmp_2[1] + tmp_2[5];\n    data[2] = tmp_2[2] + tmp_2[6];\n    data[3] = tmp_2[3] + tmp_2[7];\n    data[4] = tmp_2[0] - tmp_2[4];\n    data[5] = tmp_2[1] - tmp_2[5];\n    data[6] = tmp_2[2] - tmp_2[6];\n    data[7] = tmp_2[3] - tmp_2[7];\n  }\n\n  template <int Dir>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void butterfly_1D_merge(\n      ComplexScalar* data, Index n, Index n_power_of_2) {\n    // Original code:\n    // RealScalar wtemp = std::sin(M_PI/n);\n    // RealScalar wpi =  -std::sin(2 * M_PI/n);\n    const RealScalar wtemp = m_sin_PI_div_n_LUT[n_power_of_2];\n    const RealScalar wpi = (Dir == FFT_FORWARD)\n                               ? m_minus_sin_2_PI_div_n_LUT[n_power_of_2]\n                               : -m_minus_sin_2_PI_div_n_LUT[n_power_of_2];\n\n    const ComplexScalar wp(wtemp, wpi);\n    const ComplexScalar wp_one = wp + ComplexScalar(1, 0);\n    const ComplexScalar wp_one_2 = wp_one * wp_one;\n    const ComplexScalar wp_one_3 = wp_one_2 * wp_one;\n    const ComplexScalar wp_one_4 = wp_one_3 * wp_one;\n    const Index n2 = n / 2;\n    ComplexScalar w(1.0, 0.0);\n    for (Index i = 0; i < n2; i += 4) {\n       ComplexScalar temp0(data[i + n2] * w);\n       ComplexScalar temp1(data[i + 1 + n2] * w * wp_one);\n       ComplexScalar temp2(data[i + 2 + n2] * w * wp_one_2);\n       ComplexScalar temp3(data[i + 3 + n2] * w * wp_one_3);\n       w = w * wp_one_4;\n\n       data[i + n2] = data[i] - temp0;\n       data[i] += temp0;\n\n       data[i + 1 + n2] = data[i + 1] - temp1;\n       data[i + 1] += temp1;\n\n       data[i + 2 + n2] = data[i + 2] - temp2;\n       data[i + 2] += temp2;\n\n       data[i + 3 + n2] = data[i + 3] - temp3;\n       data[i + 3] += temp3;\n    }\n  }\n\n template <int Dir>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void compute_1D_Butterfly(\n      ComplexScalar* data, Index n, Index n_power_of_2) {\n    eigen_assert(isPowerOfTwo(n));\n    if (n > 8) {\n      compute_1D_Butterfly<Dir>(data, n / 2, n_power_of_2 - 1);\n      compute_1D_Butterfly<Dir>(data + n / 2, n / 2, n_power_of_2 - 1);\n      butterfly_1D_merge<Dir>(data, n, n_power_of_2);\n    } else if (n == 8) {\n      butterfly_8<Dir>(data);\n    } else if (n == 4) {\n      butterfly_4<Dir>(data);\n    } else if (n == 2) {\n      butterfly_2<Dir>(data);\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index getBaseOffsetFromIndex(Index index, Index omitted_dim) const {\n    Index result = 0;\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = NumDims - 1; i > omitted_dim; --i) {\n        const Index partial_m_stride = m_strides[i] / m_dimensions[omitted_dim];\n        const Index idx = index / partial_m_stride;\n        index -= idx * partial_m_stride;\n        result += idx * m_strides[i];\n      }\n      result += index;\n    }\n    else {\n      for (Index i = 0; i < omitted_dim; ++i) {\n        const Index partial_m_stride = m_strides[i] / m_dimensions[omitted_dim];\n        const Index idx = index / partial_m_stride;\n        index -= idx * partial_m_stride;\n        result += idx * m_strides[i];\n      }\n      result += index;\n    }\n    // Value of index_coords[omitted_dim] is not determined to this step\n    return result;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index getIndexFromOffset(Index base, Index omitted_dim, Index offset) const {\n    Index result = base + offset * m_strides[omitted_dim] ;\n    return result;\n  }\n\n protected:\n  Index m_size;\n  const FFT EIGEN_DEVICE_REF m_fft;\n  Dimensions m_dimensions;\n  array<Index, NumDims> m_strides;\n  TensorEvaluator<ArgType, Device> m_impl;\n  EvaluatorPointerType m_data;\n  const Device EIGEN_DEVICE_REF m_device;\n\n  // This will support a maximum FFT size of 2^32 for each dimension\n  // m_sin_PI_div_n_LUT[i] = (-2) * std::sin(M_PI / std::pow(2,i)) ^ 2;\n  const RealScalar m_sin_PI_div_n_LUT[32] = {\n    RealScalar(0.0),\n    RealScalar(-2),\n    RealScalar(-0.999999999999999),\n    RealScalar(-0.292893218813453),\n    RealScalar(-0.0761204674887130),\n    RealScalar(-0.0192147195967696),\n    RealScalar(-0.00481527332780311),\n    RealScalar(-0.00120454379482761),\n    RealScalar(-3.01181303795779e-04),\n    RealScalar(-7.52981608554592e-05),\n    RealScalar(-1.88247173988574e-05),\n    RealScalar(-4.70619042382852e-06),\n    RealScalar(-1.17654829809007e-06),\n    RealScalar(-2.94137117780840e-07),\n    RealScalar(-7.35342821488550e-08),\n    RealScalar(-1.83835707061916e-08),\n    RealScalar(-4.59589268710903e-09),\n    RealScalar(-1.14897317243732e-09),\n    RealScalar(-2.87243293150586e-10),\n    RealScalar( -7.18108232902250e-11),\n    RealScalar(-1.79527058227174e-11),\n    RealScalar(-4.48817645568941e-12),\n    RealScalar(-1.12204411392298e-12),\n    RealScalar(-2.80511028480785e-13),\n    RealScalar(-7.01277571201985e-14),\n    RealScalar(-1.75319392800498e-14),\n    RealScalar(-4.38298482001247e-15),\n    RealScalar(-1.09574620500312e-15),\n    RealScalar(-2.73936551250781e-16),\n    RealScalar(-6.84841378126949e-17),\n    RealScalar(-1.71210344531737e-17),\n    RealScalar(-4.28025861329343e-18)\n  };\n\n  // m_minus_sin_2_PI_div_n_LUT[i] = -std::sin(2 * M_PI / std::pow(2,i));\n  const RealScalar m_minus_sin_2_PI_div_n_LUT[32] = {\n    RealScalar(0.0),\n    RealScalar(0.0),\n    RealScalar(-1.00000000000000e+00),\n    RealScalar(-7.07106781186547e-01),\n    RealScalar(-3.82683432365090e-01),\n    RealScalar(-1.95090322016128e-01),\n    RealScalar(-9.80171403295606e-02),\n    RealScalar(-4.90676743274180e-02),\n    RealScalar(-2.45412285229123e-02),\n    RealScalar(-1.22715382857199e-02),\n    RealScalar(-6.13588464915448e-03),\n    RealScalar(-3.06795676296598e-03),\n    RealScalar(-1.53398018628477e-03),\n    RealScalar(-7.66990318742704e-04),\n    RealScalar(-3.83495187571396e-04),\n    RealScalar(-1.91747597310703e-04),\n    RealScalar(-9.58737990959773e-05),\n    RealScalar(-4.79368996030669e-05),\n    RealScalar(-2.39684498084182e-05),\n    RealScalar(-1.19842249050697e-05),\n    RealScalar(-5.99211245264243e-06),\n    RealScalar(-2.99605622633466e-06),\n    RealScalar(-1.49802811316901e-06),\n    RealScalar(-7.49014056584716e-07),\n    RealScalar(-3.74507028292384e-07),\n    RealScalar(-1.87253514146195e-07),\n    RealScalar(-9.36267570730981e-08),\n    RealScalar(-4.68133785365491e-08),\n    RealScalar(-2.34066892682746e-08),\n    RealScalar(-1.17033446341373e-08),\n    RealScalar(-5.85167231706864e-09),\n    RealScalar(-2.92583615853432e-09)\n  };\n};\n\n}  // end namespace Eigen\n\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_FFT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFixedSize.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_FIXED_SIZE_H\n#define EIGEN_CXX11_TENSOR_TENSOR_FIXED_SIZE_H\n\nnamespace Eigen {\n\n/** \\class TensorFixedSize\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief The fixed sized version of the tensor class.\n  *\n  * The fixed sized equivalent of\n  * Eigen::Tensor<float, 3> t(3, 5, 7);\n  * is\n  * Eigen::TensorFixedSize<float, Sizes<3,5,7>> t;\n  */\n\ntemplate<typename Scalar_, typename Dimensions_, int Options_, typename IndexType>\nclass TensorFixedSize : public TensorBase<TensorFixedSize<Scalar_, Dimensions_, Options_, IndexType> >\n{\n  public:\n    typedef TensorFixedSize<Scalar_, Dimensions_, Options_, IndexType> Self;\n    typedef TensorBase<TensorFixedSize<Scalar_, Dimensions_, Options_, IndexType> > Base;\n    typedef typename Eigen::internal::nested<Self>::type Nested;\n    typedef typename internal::traits<Self>::StorageKind StorageKind;\n    typedef typename internal::traits<Self>::Index Index;\n    typedef Scalar_ Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef typename Base::CoeffReturnType CoeffReturnType;\n\n    static const int Options = Options_;\n\n    enum {\n      IsAligned = bool(EIGEN_MAX_ALIGN_BYTES>0),\n      PacketAccess = (internal::packet_traits<Scalar>::size > 1),\n      BlockAccess = false,\n      PreferBlockAccess = false,\n      Layout = Options_ & RowMajor ? RowMajor : ColMajor,\n      CoordAccess = true,\n      RawAccess = true\n    };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  typedef Dimensions_ Dimensions;\n  static const std::size_t NumIndices = Dimensions::count;\n\n  protected:\n  TensorStorage<Scalar, Dimensions, Options> m_storage;\n\n  public:\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index                    rank()                   const { return NumIndices; }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index                    dimension(std::size_t n) const { return m_storage.dimensions()[n]; }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions&        dimensions()             const { return m_storage.dimensions(); }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index                    size()                   const { return m_storage.size(); }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar                   *data()                        { return m_storage.data(); }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar             *data()                  const { return m_storage.data(); }\n\n    // This makes EIGEN_INITIALIZE_COEFFS_IF_THAT_OPTION_IS_ENABLED\n    // work, because that uses base().coeffRef() - and we don't yet\n    // implement a similar class hierarchy\n    inline Self& base()             { return *this; }\n    inline const Self& base() const { return *this; }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& coeff(Index firstIndex, IndexTypes... otherIndices) const\n    {\n      // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return coeff(array<Index, NumIndices>{{firstIndex, otherIndices...}});\n    }\n#endif\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& coeff(const array<Index, NumIndices>& indices) const\n    {\n      eigen_internal_assert(checkIndexRange(indices));\n      return m_storage.data()[linearizedIndex(indices)];\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& coeff(Index index) const\n    {\n      eigen_internal_assert(index >= 0 && index < size());\n      return m_storage.data()[index];\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& coeff() const\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return m_storage.data()[0];\n    }\n\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index firstIndex, IndexTypes... otherIndices)\n    {\n      // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return coeffRef(array<Index, NumIndices>{{firstIndex, otherIndices...}});\n    }\n#endif\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& coeffRef(const array<Index, NumIndices>& indices)\n    {\n      eigen_internal_assert(checkIndexRange(indices));\n      return m_storage.data()[linearizedIndex(indices)];\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& coeffRef(Index index)\n    {\n      eigen_internal_assert(index >= 0 && index < size());\n      return m_storage.data()[index];\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& coeffRef()\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return m_storage.data()[0];\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar& operator()(Index firstIndex, IndexTypes... otherIndices) const\n    {\n      // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return this->operator()(array<Index, NumIndices>{{firstIndex, otherIndices...}});\n    }\n#else\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1) const\n    {\n      if (Options&RowMajor) {\n        const Index index = i1 + i0 * m_storage.dimensions()[1];\n        return m_storage.data()[index];\n      } else {\n        const Index index = i0 + i1 * m_storage.dimensions()[0];\n        return m_storage.data()[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2) const\n    {\n      if (Options&RowMajor) {\n         const Index index = i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0);\n         return m_storage.data()[index];\n      } else {\n         const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * i2);\n        return m_storage.data()[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2, Index i3) const\n    {\n      if (Options&RowMajor) {\n        const Index index = i3 + m_storage.dimensions()[3] * (i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0));\n        return m_storage.data()[index];\n      } else {\n        const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * (i2 + m_storage.dimensions()[2] * i3));\n        return m_storage.data()[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()(Index i0, Index i1, Index i2, Index i3, Index i4) const\n    {\n      if (Options&RowMajor) {\n        const Index index = i4 + m_storage.dimensions()[4] * (i3 + m_storage.dimensions()[3] * (i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0)));\n        return m_storage.data()[index];\n      } else {\n        const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * (i2 + m_storage.dimensions()[2] * (i3 + m_storage.dimensions()[3] * i4)));\n        return m_storage.data()[index];\n      }\n    }\n#endif\n\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()(const array<Index, NumIndices>& indices) const\n    {\n      eigen_assert(checkIndexRange(indices));\n      return coeff(indices);\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()(Index index) const\n    {\n      eigen_internal_assert(index >= 0 && index < size());\n      return coeff(index);\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator()() const\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return coeff();\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar& operator[](Index index) const\n    {\n      // The bracket operator is only for vectors, use the parenthesis operator instead.\n      EIGEN_STATIC_ASSERT(NumIndices == 1, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return coeff(index);\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& operator()(Index firstIndex, IndexTypes... otherIndices)\n    {\n      // The number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 1 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return operator()(array<Index, NumIndices>{{firstIndex, otherIndices...}});\n    }\n#else\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1)\n    {\n       if (Options&RowMajor) {\n         const Index index = i1 + i0 * m_storage.dimensions()[1];\n        return m_storage.data()[index];\n      } else {\n        const Index index = i0 + i1 * m_storage.dimensions()[0];\n        return m_storage.data()[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2)\n    {\n       if (Options&RowMajor) {\n         const Index index = i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0);\n        return m_storage.data()[index];\n      } else {\n         const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * i2);\n        return m_storage.data()[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3)\n    {\n      if (Options&RowMajor) {\n        const Index index = i3 + m_storage.dimensions()[3] * (i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0));\n        return m_storage.data()[index];\n      } else {\n        const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * (i2 + m_storage.dimensions()[2] * i3));\n        return m_storage.data()[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3, Index i4)\n    {\n      if (Options&RowMajor) {\n        const Index index = i4 + m_storage.dimensions()[4] * (i3 + m_storage.dimensions()[3] * (i2 + m_storage.dimensions()[2] * (i1 + m_storage.dimensions()[1] * i0)));\n        return m_storage.data()[index];\n      } else {\n        const Index index = i0 + m_storage.dimensions()[0] * (i1 + m_storage.dimensions()[1] * (i2 + m_storage.dimensions()[2] * (i3 + m_storage.dimensions()[3] * i4)));\n        return m_storage.data()[index];\n      }\n    }\n#endif\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(const array<Index, NumIndices>& indices)\n    {\n      eigen_assert(checkIndexRange(indices));\n      return coeffRef(indices);\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(Index index)\n    {\n      eigen_assert(index >= 0 && index < size());\n      return coeffRef(index);\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()()\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return coeffRef();\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator[](Index index)\n    {\n      // The bracket operator is only for vectors, use the parenthesis operator instead\n      EIGEN_STATIC_ASSERT(NumIndices == 1, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return coeffRef(index);\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorFixedSize()\n      : m_storage()\n    {\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorFixedSize(const Self& other)\n      : m_storage(other.m_storage)\n    {\n    }\n\n#if EIGEN_HAS_RVALUE_REFERENCES\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorFixedSize(Self&& other)\n      : m_storage(other.m_storage)\n    {\n    }\n#endif\n\n    template<typename OtherDerived>\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorFixedSize(const TensorBase<OtherDerived, ReadOnlyAccessors>& other)\n    {\n      typedef TensorAssignOp<TensorFixedSize, const OtherDerived> Assign;\n      Assign assign(*this, other.derived());\n      internal::TensorExecutor<const Assign, DefaultDevice>::run(assign, DefaultDevice());\n    }\n    template<typename OtherDerived>\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorFixedSize(const TensorBase<OtherDerived, WriteAccessors>& other)\n    {\n      typedef TensorAssignOp<TensorFixedSize, const OtherDerived> Assign;\n      Assign assign(*this, other.derived());\n      internal::TensorExecutor<const Assign, DefaultDevice>::run(assign, DefaultDevice());\n    }\n\n    // FIXME: check that the dimensions of other match the dimensions of *this.\n    // Unfortunately this isn't possible yet when the rhs is an expression.\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(TensorFixedSize)\n\n\n  protected:\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE bool checkIndexRange(const array<Index, NumIndices>& /*indices*/) const\n    {\n      using internal::array_apply_and_reduce;\n      using internal::array_zip_and_reduce;\n      using internal::greater_equal_zero_op;\n      using internal::logical_and_op;\n      using internal::lesser_op;\n\n      return true;\n        // check whether the indices are all >= 0\n          /*       array_apply_and_reduce<logical_and_op, greater_equal_zero_op>(indices) &&\n        // check whether the indices fit in the dimensions\n        array_zip_and_reduce<logical_and_op, lesser_op>(indices, m_storage.dimensions());*/\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Index linearizedIndex(const array<Index, NumIndices>& indices) const\n    {\n      if (Options&RowMajor) {\n        return m_storage.dimensions().IndexOfRowMajor(indices);\n      } else {\n        return m_storage.dimensions().IndexOfColMajor(indices);\n      }\n    }\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_FIXED_SIZE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorForcedEval.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_FORCED_EVAL_H\n#define EIGEN_CXX11_TENSOR_TENSOR_FORCED_EVAL_H\n\nnamespace Eigen {\n\n/** \\class TensorForcedEval\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor reshaping class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename XprType>\nstruct traits<TensorForcedEvalOp<XprType> >\n{\n  // Type promotion to handle the case where the types of the lhs and the rhs are different.\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename traits<XprType>::StorageKind StorageKind;\n  typedef typename traits<XprType>::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n\n  enum {\n    Flags = 0\n  };\n};\n\ntemplate<typename XprType>\nstruct eval<TensorForcedEvalOp<XprType>, Eigen::Dense>\n{\n  typedef const TensorForcedEvalOp<XprType>& type;\n};\n\ntemplate<typename XprType>\nstruct nested<TensorForcedEvalOp<XprType>, 1, typename eval<TensorForcedEvalOp<XprType> >::type>\n{\n  typedef TensorForcedEvalOp<XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename XprType>\nclass TensorForcedEvalOp : public TensorBase<TensorForcedEvalOp<XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorForcedEvalOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename internal::remove_const<typename XprType::CoeffReturnType>::type CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorForcedEvalOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorForcedEvalOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorForcedEvalOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorForcedEvalOp(const XprType& expr)\n      : m_xpr(expr) {}\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n};\n\nnamespace internal {\ntemplate <typename Device, typename CoeffReturnType>\nstruct non_integral_type_placement_new{\n  template <typename StorageType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void operator()(Index numValues, StorageType m_buffer) {\n   // Initialize non-trivially constructible types.\n    if (!internal::is_arithmetic<CoeffReturnType>::value) {\n      for (Index i = 0; i < numValues; ++i) new (m_buffer + i) CoeffReturnType();\n    }\n}\n};\n\n// SYCL does not support non-integral types \n// having new (m_buffer + i) CoeffReturnType() causes the following compiler error for SYCL Devices \n// no matching function for call to 'operator new'\ntemplate <typename CoeffReturnType>\nstruct non_integral_type_placement_new<Eigen::SyclDevice, CoeffReturnType> {\n  template <typename StorageType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void operator()(Index, StorageType) {\n}\n};\n} // end namespace internal\n\ntemplate<typename ArgType_, typename Device>\nstruct TensorEvaluator<const TensorForcedEvalOp<ArgType_>, Device>\n{\n  typedef const typename internal::remove_all<ArgType_>::type ArgType;\n  typedef TensorForcedEvalOp<ArgType> XprType;\n  typedef typename ArgType::Scalar Scalar;\n  typedef typename TensorEvaluator<ArgType, Device>::Dimensions Dimensions;\n  typedef typename XprType::Index Index;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef typename Eigen::internal::traits<XprType>::PointerType TensorPointerType;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned         = true,\n    PacketAccess      = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess       = internal::is_arithmetic<CoeffReturnType>::value,\n    PreferBlockAccess = false,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    RawAccess         = true\n  };\n\n  static const int NumDims = internal::traits<ArgType>::NumDimensions;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename internal::TensorMaterializedBlock<CoeffReturnType, NumDims,\n                                                     Layout, Index>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device), m_op(op.expression()),\n      m_device(device), m_buffer(NULL)\n  { }\n\n  EIGEN_DEVICE_FUNC const Dimensions& dimensions() const { return m_impl.dimensions(); }\n\n  #if !defined(EIGEN_HIPCC)\n  EIGEN_DEVICE_FUNC\n  #endif\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    const Index numValues =  internal::array_prod(m_impl.dimensions());\n    m_buffer = m_device.get((CoeffReturnType*)m_device.allocate_temp(numValues * sizeof(CoeffReturnType)));\n\n   internal::non_integral_type_placement_new<Device, CoeffReturnType>()(numValues, m_buffer);\n\n    typedef TensorEvalToOp< const typename internal::remove_const<ArgType>::type > EvalTo;\n    EvalTo evalToTmp(m_device.get(m_buffer), m_op);\n\n    internal::TensorExecutor<\n        const EvalTo, typename internal::remove_const<Device>::type,\n        /*Vectorizable=*/internal::IsVectorizable<Device, const ArgType>::value,\n        /*Tiling=*/internal::IsTileable<Device, const ArgType>::value>::\n        run(evalToTmp, m_device);\n\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    const Index numValues = internal::array_prod(m_impl.dimensions());\n    m_buffer = m_device.get((CoeffReturnType*)m_device.allocate_temp(\n        numValues * sizeof(CoeffReturnType)));\n    typedef TensorEvalToOp<const typename internal::remove_const<ArgType>::type>\n        EvalTo;\n    EvalTo evalToTmp(m_device.get(m_buffer), m_op);\n\n    auto on_done = std::bind([](EvalSubExprsCallback done_) { done_(true); },\n                             std::move(done));\n    internal::TensorAsyncExecutor<\n        const EvalTo, typename internal::remove_const<Device>::type,\n        decltype(on_done),\n        /*Vectorizable=*/internal::IsVectorizable<Device, const ArgType>::value,\n        /*Tiling=*/internal::IsTileable<Device, const ArgType>::value>::\n        runAsync(evalToTmp, m_device, std::move(on_done));\n  }\n#endif\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_device.deallocate_temp(m_buffer);\n    m_buffer = NULL;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    return m_buffer[index];\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    return internal::ploadt<PacketReturnType, LoadMode>(m_buffer + index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    return internal::TensorBlockResourceRequirements::any();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    assert(m_buffer != NULL);\n    return TensorBlock::materialize(m_buffer, m_impl.dimensions(), desc, scratch);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  EvaluatorPointerType data() const { return m_buffer; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_buffer.bind(cgh);\n    m_impl.bind(cgh);\n  }\n#endif\n private:\n  TensorEvaluator<ArgType, Device> m_impl;\n  const ArgType m_op;\n  const Device EIGEN_DEVICE_REF m_device;\n  EvaluatorPointerType m_buffer;\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_FORCED_EVAL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorForwardDeclarations.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_FORWARD_DECLARATIONS_H\n#define EIGEN_CXX11_TENSOR_TENSOR_FORWARD_DECLARATIONS_H\n\nnamespace Eigen {\n\n// MakePointer class is used as a container of the address space of the pointer\n// on the host and on the device. From the host side it generates the T* pointer\n// and when EIGEN_USE_SYCL is used it construct a buffer with a map_allocator to\n// T* m_data on the host. It is always called on the device.\n// Specialisation of MakePointer class for creating the sycl buffer with\n// map_allocator.\ntemplate<typename T> struct MakePointer {\n  typedef T* Type;\n  typedef const T* ConstType;\n};\n\ntemplate <typename T>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T* constCast(const T* data) {\n  return const_cast<T*>(data);\n}\n\n// The StorageMemory class is a container of the device specific pointer\n// used for refering to a Pointer on TensorEvaluator class. While the TensorExpression\n// is a device-agnostic type and need MakePointer class for type conversion,\n// the TensorEvaluator class can be specialized for a device, hence it is possible\n// to construct different types of temproray storage memory in TensorEvaluator\n// for different devices by specializing the following StorageMemory class.\ntemplate<typename T, typename device> struct StorageMemory: MakePointer <T> {};\n\nnamespace internal{\ntemplate<typename A, typename B> struct Pointer_type_promotion {\n  static const bool val=false;\n};\ntemplate<typename A> struct Pointer_type_promotion<A, A> {\n  static const bool val = true;\n};\ntemplate<typename A, typename B> struct TypeConversion {\n  typedef A* type;\n};\n}\n\n\ntemplate<typename PlainObjectType, int Options_ = Unaligned, template <class> class MakePointer_ = MakePointer> class TensorMap;\ntemplate<typename Scalar_, int NumIndices_, int Options_ = 0, typename IndexType = DenseIndex> class Tensor;\ntemplate<typename Scalar_, typename Dimensions, int Options_ = 0, typename IndexType = DenseIndex> class TensorFixedSize;\ntemplate<typename PlainObjectType> class TensorRef;\ntemplate<typename Derived, int AccessLevel> class TensorBase;\n\ntemplate<typename NullaryOp, typename PlainObjectType> class TensorCwiseNullaryOp;\ntemplate<typename UnaryOp, typename XprType> class TensorCwiseUnaryOp;\ntemplate<typename BinaryOp, typename LeftXprType, typename RightXprType> class TensorCwiseBinaryOp;\ntemplate<typename TernaryOp, typename Arg1XprType, typename Arg2XprType, typename Arg3XprType> class TensorCwiseTernaryOp;\ntemplate<typename IfXprType, typename ThenXprType, typename ElseXprType> class TensorSelectOp;\ntemplate<typename Op, typename Dims, typename XprType, template <class> class MakePointer_ = MakePointer > class TensorReductionOp;\ntemplate<typename XprType> class TensorIndexTupleOp;\ntemplate<typename ReduceOp, typename Dims, typename XprType> class TensorTupleReducerOp;\ntemplate<typename Axis, typename LeftXprType, typename RightXprType> class TensorConcatenationOp;\ntemplate<typename Dimensions, typename LeftXprType, typename RightXprType, typename OutputKernelType> class TensorContractionOp;\ntemplate<typename TargetType, typename XprType> class TensorConversionOp;\ntemplate<typename Dimensions, typename InputXprType, typename KernelXprType> class TensorConvolutionOp;\ntemplate<typename FFT, typename XprType, int FFTDataType, int FFTDirection> class TensorFFTOp;\ntemplate<typename PatchDim, typename XprType> class TensorPatchOp;\ntemplate<DenseIndex Rows, DenseIndex Cols, typename XprType> class TensorImagePatchOp;\ntemplate<DenseIndex Planes, DenseIndex Rows, DenseIndex Cols, typename XprType> class TensorVolumePatchOp;\ntemplate<typename Broadcast, typename XprType> class TensorBroadcastingOp;\ntemplate<DenseIndex DimId, typename XprType> class TensorChippingOp;\ntemplate<typename NewDimensions, typename XprType> class TensorReshapingOp;\ntemplate<typename XprType> class TensorLayoutSwapOp;\ntemplate<typename StartIndices, typename Sizes, typename XprType> class TensorSlicingOp;\ntemplate<typename ReverseDimensions, typename XprType> class TensorReverseOp;\ntemplate<typename PaddingDimensions, typename XprType> class TensorPaddingOp;\ntemplate<typename Shuffle, typename XprType> class TensorShufflingOp;\ntemplate<typename Strides, typename XprType> class TensorStridingOp;\ntemplate<typename StartIndices, typename StopIndices, typename Strides, typename XprType> class TensorStridingSlicingOp;\ntemplate<typename Strides, typename XprType> class TensorInflationOp;\ntemplate<typename Generator, typename XprType> class TensorGeneratorOp;\ntemplate<typename LeftXprType, typename RightXprType> class TensorAssignOp;\ntemplate<typename Op, typename XprType> class TensorScanOp;\ntemplate<typename Dims, typename XprType> class TensorTraceOp;\n\ntemplate<typename CustomUnaryFunc, typename XprType> class TensorCustomUnaryOp;\ntemplate<typename CustomBinaryFunc, typename LhsXprType, typename RhsXprType> class TensorCustomBinaryOp;\n\ntemplate<typename XprType, template <class> class MakePointer_ = MakePointer> class TensorEvalToOp;\ntemplate<typename XprType> class TensorForcedEvalOp;\n\ntemplate<typename ExpressionType, typename DeviceType> class TensorDevice;\ntemplate<typename ExpressionType, typename DeviceType, typename DoneCallback> class TensorAsyncDevice;\ntemplate<typename Derived, typename Device> struct TensorEvaluator;\n\nstruct NoOpOutputKernel;\n\nstruct DefaultDevice;\nstruct ThreadPoolDevice;\nstruct GpuDevice;\nstruct SyclDevice;\n\n#ifdef EIGEN_USE_SYCL\n\ntemplate <typename T> struct MakeSYCLPointer {\n  typedef Eigen::TensorSycl::internal::RangeAccess<cl::sycl::access::mode::read_write, T> Type;\n};\n\ntemplate <typename T>\nEIGEN_STRONG_INLINE const Eigen::TensorSycl::internal::RangeAccess<cl::sycl::access::mode::read_write, T>&\nconstCast(const Eigen::TensorSycl::internal::RangeAccess<cl::sycl::access::mode::read_write, T>& data) {\n  return data;\n}\n\ntemplate <typename T>\nstruct StorageMemory<T, SyclDevice> : MakeSYCLPointer<T> {};\ntemplate <typename T>\nstruct StorageMemory<T, const SyclDevice> : StorageMemory<T, SyclDevice> {};\n\nnamespace TensorSycl {\nnamespace internal{\ntemplate <typename Evaluator, typename Op> class GenericNondeterministicReducer;\n}\n}\n#endif\n\n\nenum FFTResultType {\n  RealPart = 0,\n  ImagPart = 1,\n  BothParts = 2\n};\n\nenum FFTDirection {\n    FFT_FORWARD = 0,\n    FFT_REVERSE = 1\n};\n\n\nnamespace internal {\n\ntemplate <typename Device, typename Expression>\nstruct IsVectorizable {\n  static const bool value = TensorEvaluator<Expression, Device>::PacketAccess;\n};\n\ntemplate <typename Expression>\nstruct IsVectorizable<GpuDevice, Expression> {\n  static const bool value = TensorEvaluator<Expression, GpuDevice>::PacketAccess &&\n                            TensorEvaluator<Expression, GpuDevice>::IsAligned;\n};\n\n// Tiled evaluation strategy.\nenum TiledEvaluation {\n  Off = 0,    // tiled evaluation is not supported\n  On = 1,     // still work in progress (see TensorBlock.h)\n};\n\ntemplate <typename Device, typename Expression>\nstruct IsTileable {\n  // Check that block evaluation is supported and it's a preferred option (at\n  // least one sub-expression has much faster block evaluation, e.g.\n  // broadcasting).\n  static const bool BlockAccess =\n      TensorEvaluator<Expression, Device>::BlockAccess &&\n      TensorEvaluator<Expression, Device>::PreferBlockAccess;\n\n  static const TiledEvaluation value =\n      BlockAccess ? TiledEvaluation::On : TiledEvaluation::Off;\n};\n\ntemplate <typename Expression, typename Device,\n          bool Vectorizable      = IsVectorizable<Device, Expression>::value,\n          TiledEvaluation Tiling = IsTileable<Device, Expression>::value>\nclass TensorExecutor;\n\ntemplate <typename Expression, typename Device, typename DoneCallback,\n          bool Vectorizable = IsVectorizable<Device, Expression>::value,\n          TiledEvaluation Tiling = IsTileable<Device, Expression>::value>\nclass TensorAsyncExecutor;\n\n\n}  // end namespace internal\n\n}  // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_FORWARD_DECLARATIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorFunctors.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_FUNCTORS_H\n#define EIGEN_CXX11_TENSOR_TENSOR_FUNCTORS_H\n\nnamespace Eigen {\nnamespace internal {\n\n\n/** \\internal\n * \\brief Template functor to compute the modulo between an array and a scalar.\n */\ntemplate <typename Scalar>\nstruct scalar_mod_op {\n  EIGEN_DEVICE_FUNC scalar_mod_op(const Scalar& divisor) : m_divisor(divisor) {}\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar operator() (const Scalar& a) const { return a % m_divisor; }\n  const Scalar m_divisor;\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_mod_op<Scalar> >\n{ enum { Cost = scalar_div_cost<Scalar,false>::value, PacketAccess = false }; };\n\n\n/** \\internal\n * \\brief Template functor to compute the modulo between 2 arrays.\n */\ntemplate <typename Scalar>\nstruct scalar_mod2_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_mod2_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar operator() (const Scalar& a, const Scalar& b) const { return a % b; }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_mod2_op<Scalar> >\n{ enum { Cost = scalar_div_cost<Scalar,false>::value, PacketAccess = false }; };\n\ntemplate <typename Scalar>\nstruct scalar_fmod_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_fmod_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar\n  operator()(const Scalar& a, const Scalar& b) const {\n    return numext::fmod(a, b);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_fmod_op<Scalar> > {\n  enum { Cost = 13,  // Reciprocal throughput of FPREM on Haswell.\n         PacketAccess = false };\n};\n\ntemplate<typename Reducer, typename Device>\nstruct reducer_traits {\n  enum {\n    Cost = 1,\n    PacketAccess = false,\n    IsStateful = false,\n    IsExactlyAssociative = true\n  };\n};\n\n// Standard reduction functors\ntemplate <typename T> struct SumReducer\n{\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) const {\n    internal::scalar_sum_op<T> sum_op;\n    *accum = sum_op(*accum, t);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reducePacket(const Packet& p, Packet* accum) const {\n    (*accum) = padd<Packet>(*accum, p);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const {\n    internal::scalar_cast_op<int, T> conv;\n    return conv(0);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet initializePacket() const {\n    return pset1<Packet>(initialize());\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T accum) const {\n    return accum;\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet finalizePacket(const Packet& vaccum) const {\n    return vaccum;\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalizeBoth(const T saccum, const Packet& vaccum) const {\n    internal::scalar_sum_op<T> sum_op;\n    return sum_op(saccum, predux(vaccum));\n  }\n};\n\ntemplate <typename T, typename Device>\nstruct reducer_traits<SumReducer<T>, Device> {\n  enum {\n    Cost = NumTraits<T>::AddCost,\n    PacketAccess = PacketType<T, Device>::HasAdd,\n    IsStateful = false,\n    IsExactlyAssociative = NumTraits<T>::IsInteger\n  };\n};\n\ntemplate <typename T> struct MeanReducer\n{\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  MeanReducer() : scalarCount_(0), packetCount_(0) { }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) {\n    internal::scalar_sum_op<T> sum_op;\n    *accum = sum_op(*accum, t);\n    scalarCount_++;\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reducePacket(const Packet& p, Packet* accum) {\n    (*accum) = padd<Packet>(*accum, p);\n    packetCount_++;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const {\n    internal::scalar_cast_op<int, T> conv;\n    return conv(0);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet initializePacket() const {\n    return pset1<Packet>(initialize());\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T accum) const {\n    internal::scalar_quotient_op<T> quotient_op;\n    return quotient_op(accum, T(scalarCount_));\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet finalizePacket(const Packet& vaccum) const {\n    return pdiv(vaccum, pset1<Packet>(T(packetCount_)));\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalizeBoth(const T saccum, const Packet& vaccum) const {\n    internal::scalar_sum_op<T> sum_op;\n    internal::scalar_quotient_op<T> quotient_op;\n    return quotient_op(\n        sum_op(saccum, predux(vaccum)),\n        T(scalarCount_ + packetCount_ * unpacket_traits<Packet>::size));\n  }\n\n  protected:\n    DenseIndex scalarCount_;\n    DenseIndex packetCount_;\n};\n\ntemplate <typename T, typename Device>\nstruct reducer_traits<MeanReducer<T>, Device> {\n  enum {\n    Cost = NumTraits<T>::AddCost,\n    PacketAccess = PacketType<T, Device>::HasAdd &&\n                   PacketType<T, Device>::HasDiv && !NumTraits<T>::IsInteger,\n    IsStateful = true,\n    IsExactlyAssociative = NumTraits<T>::IsInteger\n  };\n};\n\n\ntemplate <typename T, bool IsMax = true, bool IsInteger = true>\nstruct MinMaxBottomValue {\n  EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE T bottom_value() {\n    return Eigen::NumTraits<T>::lowest();\n  }\n};\ntemplate <typename T>\nstruct MinMaxBottomValue<T, true, false> {\n  EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE T bottom_value() {\n    return -Eigen::NumTraits<T>::infinity();\n  }\n};\ntemplate <typename T>\nstruct MinMaxBottomValue<T, false, true> {\n  EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE T bottom_value() {\n    return Eigen::NumTraits<T>::highest();\n  }\n};\ntemplate <typename T>\nstruct MinMaxBottomValue<T, false, false> {\n  EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE T bottom_value() {\n    return Eigen::NumTraits<T>::infinity();\n  }\n};\n\n\ntemplate <typename T, int NaNPropagation=PropagateFast> struct MaxReducer\n{\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) const {\n    scalar_max_op<T, T, NaNPropagation> op;\n    *accum = op(t, *accum);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reducePacket(const Packet& p, Packet* accum) const {\n    scalar_max_op<T, T, NaNPropagation> op;\n    (*accum) = op.packetOp(*accum, p);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const {\n    return MinMaxBottomValue<T, /*IsMax=*/true, Eigen::NumTraits<T>::IsInteger>::bottom_value();\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet initializePacket() const {\n    return pset1<Packet>(initialize());\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T accum) const {\n    return accum;\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet finalizePacket(const Packet& vaccum) const {\n    return vaccum;\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalizeBoth(const T saccum, const Packet& vaccum) const {\n    scalar_max_op<T, T, NaNPropagation> op;\n    return op(saccum, op.predux(vaccum));\n  }\n};\n\ntemplate <typename T, typename Device, int NaNPropagation>\n    struct reducer_traits<MaxReducer<T, NaNPropagation>, Device> {\n  enum {\n    Cost = NumTraits<T>::AddCost,\n    PacketAccess = PacketType<T, Device>::HasMax,\n    IsStateful = false,\n    IsExactlyAssociative = (NaNPropagation!=PropagateFast)\n  };\n};\n\ntemplate <typename T, int NaNPropagation=PropagateFast> struct MinReducer\n{\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) const {\n    scalar_min_op<T, T, NaNPropagation> op;\n    *accum = op(t, *accum);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reducePacket(const Packet& p, Packet* accum) const {\n    scalar_min_op<T, T, NaNPropagation> op;\n    (*accum) = op.packetOp(*accum, p);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const {\n    return MinMaxBottomValue<T, /*IsMax=*/false, Eigen::NumTraits<T>::IsInteger>::bottom_value();\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet initializePacket() const {\n    return pset1<Packet>(initialize());\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T accum) const {\n    return accum;\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet finalizePacket(const Packet& vaccum) const {\n    return vaccum;\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalizeBoth(const T saccum, const Packet& vaccum) const {\n    scalar_min_op<T, T, NaNPropagation> op;\n    return op(saccum, op.predux(vaccum));\n  }\n};\n\ntemplate <typename T, typename Device, int NaNPropagation>\n    struct reducer_traits<MinReducer<T, NaNPropagation>, Device> {\n  enum {\n    Cost = NumTraits<T>::AddCost,\n    PacketAccess = PacketType<T, Device>::HasMin,\n    IsStateful = false,\n    IsExactlyAssociative = (NaNPropagation!=PropagateFast)\n  };\n};\n\ntemplate <typename T> struct ProdReducer\n{\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) const {\n    internal::scalar_product_op<T> prod_op;\n    (*accum) = prod_op(*accum, t);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reducePacket(const Packet& p, Packet* accum) const {\n    (*accum) = pmul<Packet>(*accum, p);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const {\n    internal::scalar_cast_op<int, T> conv;\n    return conv(1);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet initializePacket() const {\n    return pset1<Packet>(initialize());\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T accum) const {\n    return accum;\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet finalizePacket(const Packet& vaccum) const {\n    return vaccum;\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalizeBoth(const T saccum, const Packet& vaccum) const {\n    internal::scalar_product_op<T> prod_op;\n    return prod_op(saccum, predux_mul(vaccum));\n  }\n};\n\ntemplate <typename T, typename Device>\nstruct reducer_traits<ProdReducer<T>, Device> {\n  enum {\n    Cost = NumTraits<T>::MulCost,\n    PacketAccess = PacketType<T, Device>::HasMul,\n    IsStateful = false,\n    IsExactlyAssociative = true\n  };\n};\n\n\nstruct AndReducer\n{\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(bool t, bool* accum) const {\n    *accum = *accum && t;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool initialize() const {\n    return true;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool finalize(bool accum) const {\n    return accum;\n  }\n};\n\ntemplate <typename Device>\nstruct reducer_traits<AndReducer, Device> {\n  enum {\n    Cost = 1,\n    PacketAccess = false,\n    IsStateful = false,\n    IsExactlyAssociative = true\n  };\n};\n\n\nstruct OrReducer {\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(bool t, bool* accum) const {\n    *accum = *accum || t;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool initialize() const {\n    return false;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool finalize(bool accum) const {\n    return accum;\n  }\n};\n\ntemplate <typename Device>\nstruct reducer_traits<OrReducer, Device> {\n  enum {\n    Cost = 1,\n    PacketAccess = false,\n    IsStateful = false,\n    IsExactlyAssociative = true\n  };\n};\n\n\n// Argmin/Argmax reducers\ntemplate <typename T> struct ArgMaxTupleReducer\n{\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T t, T* accum) const {\n    if (t.second > accum->second) { *accum = t; }\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const {\n    return T(0, NumTraits<typename T::second_type>::lowest());\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T& accum) const {\n    return accum;\n  }\n};\n\ntemplate <typename T, typename Device>\nstruct reducer_traits<ArgMaxTupleReducer<T>, Device> {\n  enum {\n    Cost = NumTraits<T>::AddCost,\n    PacketAccess = false,\n    IsStateful = false,\n    IsExactlyAssociative = true\n  };\n};\n\n\ntemplate <typename T> struct ArgMinTupleReducer\n{\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const T& t, T* accum) const {\n    if (t.second < accum->second) { *accum = t; }\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T initialize() const {\n    return T(0, NumTraits<typename T::second_type>::highest());\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T finalize(const T& accum) const {\n    return accum;\n  }\n};\n\ntemplate <typename T, typename Device>\nstruct reducer_traits<ArgMinTupleReducer<T>, Device> {\n  enum {\n    Cost = NumTraits<T>::AddCost,\n    PacketAccess = false,\n    IsStateful = false,\n    IsExactlyAssociative = true\n  };\n};\n\n\ntemplate <typename T, typename Index, size_t NumDims>\nclass GaussianGenerator {\n public:\n  static const bool PacketAccess = false;\n\n  EIGEN_DEVICE_FUNC GaussianGenerator(const array<T, NumDims>& means,\n                                      const array<T, NumDims>& std_devs)\n      : m_means(means)\n  {\n    EIGEN_UNROLL_LOOP\n    for (size_t i = 0; i < NumDims; ++i) {\n      m_two_sigmas[i] = std_devs[i] * std_devs[i] * 2;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC T operator()(const array<Index, NumDims>& coordinates) const {\n    T tmp = T(0);\n    EIGEN_UNROLL_LOOP\n    for (size_t i = 0; i < NumDims; ++i) {\n      T offset = coordinates[i] - m_means[i];\n      tmp += offset * offset / m_two_sigmas[i];\n    }\n    return numext::exp(-tmp);\n  }\n\n private:\n  array<T, NumDims> m_means;\n  array<T, NumDims> m_two_sigmas;\n};\n\ntemplate <typename T, typename Index, size_t NumDims>\nstruct functor_traits<GaussianGenerator<T, Index, NumDims> > {\n  enum {\n    Cost = NumDims * (2 * NumTraits<T>::AddCost + NumTraits<T>::MulCost +\n                      functor_traits<scalar_quotient_op<T, T> >::Cost) +\n           functor_traits<scalar_exp_op<T> >::Cost,\n    PacketAccess = GaussianGenerator<T, Index, NumDims>::PacketAccess\n  };\n};\n\ntemplate <typename Scalar>\nstruct scalar_clamp_op {\n  EIGEN_DEVICE_FUNC inline scalar_clamp_op(const Scalar& _min, const Scalar& _max) : m_min(_min), m_max(_max) {}\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar\n  operator()(const Scalar& x) const {\n    return numext::mini(numext::maxi(x, m_min), m_max);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet\n  packetOp(const Packet& x) const {\n    return internal::pmin(internal::pmax(x, pset1<Packet>(m_min)), pset1<Packet>(m_max));\n  }\n  const Scalar m_min;\n  const Scalar m_max;\n};\ntemplate<typename Scalar>\nstruct functor_traits<scalar_clamp_op<Scalar> >\n{ enum { Cost = 2 * NumTraits<Scalar>::AddCost, PacketAccess = (packet_traits<Scalar>::HasMin && packet_traits<Scalar>::HasMax)}; };\n\n} // end namespace internal\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_FUNCTORS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGenerator.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_GENERATOR_H\n#define EIGEN_CXX11_TENSOR_TENSOR_GENERATOR_H\n\nnamespace Eigen {\n\n/** \\class TensorGeneratorOp\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor generator class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename Generator, typename XprType>\nstruct traits<TensorGeneratorOp<Generator, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename Generator, typename XprType>\nstruct eval<TensorGeneratorOp<Generator, XprType>, Eigen::Dense>\n{\n  typedef const TensorGeneratorOp<Generator, XprType>& type;\n};\n\ntemplate<typename Generator, typename XprType>\nstruct nested<TensorGeneratorOp<Generator, XprType>, 1, typename eval<TensorGeneratorOp<Generator, XprType> >::type>\n{\n  typedef TensorGeneratorOp<Generator, XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename Generator, typename XprType>\nclass TensorGeneratorOp : public TensorBase<TensorGeneratorOp<Generator, XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorGeneratorOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorGeneratorOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorGeneratorOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorGeneratorOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorGeneratorOp(const XprType& expr, const Generator& generator)\n      : m_xpr(expr), m_generator(generator) {}\n\n    EIGEN_DEVICE_FUNC\n    const Generator& generator() const { return m_generator; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const Generator m_generator;\n};\n\n\n// Eval as rvalue\ntemplate<typename Generator, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorGeneratorOp<Generator, ArgType>, Device>\n{\n  typedef TensorGeneratorOp<Generator, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  typedef typename TensorEvaluator<ArgType, Device>::Dimensions Dimensions;\n  static const int NumDims = internal::array_size<Dimensions>::value;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n  enum {\n    IsAligned         = false,\n    PacketAccess      = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess       = true,\n    PreferBlockAccess = true,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = false\n  };\n\n  typedef internal::TensorIntDivisor<Index> IndexDivisor;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename internal::TensorMaterializedBlock<CoeffReturnType, NumDims,\n                                                     Layout, Index>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      :  m_device(device), m_generator(op.generator())\n  {\n    TensorEvaluator<ArgType, Device> argImpl(op.expression(), device);\n    m_dimensions = argImpl.dimensions();\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_strides[0] = 1;\n      EIGEN_UNROLL_LOOP\n      for (int i = 1; i < NumDims; ++i) {\n        m_strides[i] = m_strides[i - 1] * m_dimensions[i - 1];\n        if (m_strides[i] != 0) m_fast_strides[i] = IndexDivisor(m_strides[i]);\n      }\n    } else {\n      m_strides[NumDims - 1] = 1;\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_strides[i] = m_strides[i + 1] * m_dimensions[i + 1];\n        if (m_strides[i] != 0) m_fast_strides[i] = IndexDivisor(m_strides[i]);\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType /*data*/) {\n    return true;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    array<Index, NumDims> coords;\n    extract_coordinates(index, coords);\n    return m_generator(coords);\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    const int packetSize = PacketType<CoeffReturnType, Device>::size;\n    EIGEN_STATIC_ASSERT((packetSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+packetSize-1 < dimensions().TotalSize());\n\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[packetSize];\n    for (int i = 0; i < packetSize; ++i) {\n      values[i] = coeff(index+i);\n    }\n    PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n    return rslt;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    const size_t target_size = m_device.firstLevelCacheSize();\n    // TODO(ezhulenev): Generator should have a cost.\n    return internal::TensorBlockResourceRequirements::skewed<Scalar>(\n        target_size);\n  }\n\n  struct BlockIteratorState {\n    Index stride;\n    Index span;\n    Index size;\n    Index count;\n  };\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    static const bool is_col_major =\n        static_cast<int>(Layout) == static_cast<int>(ColMajor);\n\n    // Compute spatial coordinates for the first block element.\n    array<Index, NumDims> coords;\n    extract_coordinates(desc.offset(), coords);\n    array<Index, NumDims> initial_coords = coords;\n\n    // Offset in the output block buffer.\n    Index offset = 0;\n\n    // Initialize output block iterator state. Dimension in this array are\n    // always in inner_most -> outer_most order (col major layout).\n    array<BlockIteratorState, NumDims> it;\n    for (int i = 0; i < NumDims; ++i) {\n      const int dim = is_col_major ? i : NumDims - 1 - i;\n      it[i].size = desc.dimension(dim);\n      it[i].stride = i == 0 ? 1 : (it[i - 1].size * it[i - 1].stride);\n      it[i].span = it[i].stride * (it[i].size - 1);\n      it[i].count = 0;\n    }\n    eigen_assert(it[0].stride == 1);\n\n    // Prepare storage for the materialized generator result.\n    const typename TensorBlock::Storage block_storage =\n        TensorBlock::prepareStorage(desc, scratch);\n\n    CoeffReturnType* block_buffer = block_storage.data();\n\n    static const int packet_size = PacketType<CoeffReturnType, Device>::size;\n\n    static const int inner_dim = is_col_major ? 0 : NumDims - 1;\n    const Index inner_dim_size = it[0].size;\n    const Index inner_dim_vectorized = inner_dim_size - packet_size;\n\n    while (it[NumDims - 1].count < it[NumDims - 1].size) {\n      Index i = 0;\n      // Generate data for the vectorized part of the inner-most dimension.\n      for (; i <= inner_dim_vectorized; i += packet_size) {\n        for (Index j = 0; j < packet_size; ++j) {\n          array<Index, NumDims> j_coords = coords;  // Break loop dependence.\n          j_coords[inner_dim] += j;\n          *(block_buffer + offset + i + j) = m_generator(j_coords);\n        }\n        coords[inner_dim] += packet_size;\n      }\n      // Finalize non-vectorized part of the inner-most dimension.\n      for (; i < inner_dim_size; ++i) {\n        *(block_buffer + offset + i) = m_generator(coords);\n        coords[inner_dim]++;\n      }\n      coords[inner_dim] = initial_coords[inner_dim];\n\n      // For the 1d tensor we need to generate only one inner-most dimension.\n      if (NumDims == 1) break;\n\n      // Update offset.\n      for (i = 1; i < NumDims; ++i) {\n        if (++it[i].count < it[i].size) {\n          offset += it[i].stride;\n          coords[is_col_major ? i : NumDims - 1 - i]++;\n          break;\n        }\n        if (i != NumDims - 1) it[i].count = 0;\n        coords[is_col_major ? i : NumDims - 1 - i] =\n            initial_coords[is_col_major ? i : NumDims - 1 - i];\n        offset -= it[i].span;\n      }\n    }\n\n    return block_storage.AsTensorMaterializedBlock();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool) const {\n    // TODO(rmlarsen): This is just a placeholder. Define interface to make\n    // generators return their cost.\n    return TensorOpCost(0, 0, TensorOpCost::AddCost<Scalar>() +\n                                  TensorOpCost::MulCost<Scalar>());\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType  data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler&) const {}\n#endif\n\n protected:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void extract_coordinates(Index index, array<Index, NumDims>& coords) const {\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx = index / m_fast_strides[i];\n        index -= idx * m_strides[i];\n        coords[i] = idx;\n      }\n      coords[0] = index;\n    } else {\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx = index / m_fast_strides[i];\n        index -= idx * m_strides[i];\n        coords[i] = idx;\n      }\n      coords[NumDims-1] = index;\n    }\n  }\n\n  const Device EIGEN_DEVICE_REF m_device;\n  Dimensions m_dimensions;\n  array<Index, NumDims> m_strides;\n  array<IndexDivisor, NumDims> m_fast_strides;\n  Generator m_generator;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_GENERATOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGlobalFunctions.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Eugene Brevdo <ebrevdo@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_GLOBAL_FUNCTIONS_H\n#define EIGEN_CXX11_TENSOR_TENSOR_GLOBAL_FUNCTIONS_H\n\nnamespace Eigen {\n\n/** \\cpp11 \\returns an expression of the coefficient-wise betainc(\\a x, \\a a, \\a b) to the given tensors.\n *\n * This function computes the regularized incomplete beta function (integral).\n *\n */\ntemplate <typename ADerived, typename BDerived, typename XDerived>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const\n    TensorCwiseTernaryOp<internal::scalar_betainc_op<typename XDerived::Scalar>,\n                         const ADerived, const BDerived, const XDerived>\n    betainc(const ADerived& a, const BDerived& b, const XDerived& x) {\n  return TensorCwiseTernaryOp<\n      internal::scalar_betainc_op<typename XDerived::Scalar>, const ADerived,\n      const BDerived, const XDerived>(\n      a, b, x, internal::scalar_betainc_op<typename XDerived::Scalar>());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_GLOBAL_FUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGpuHipCudaDefines.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n// Copyright (C) 2018 Deven Desai <deven.desai.amd@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#if defined(EIGEN_USE_GPU) && !defined(EIGEN_CXX11_TENSOR_GPU_HIP_CUDA_DEFINES_H)\n#define EIGEN_CXX11_TENSOR_GPU_HIP_CUDA_DEFINES_H\n\n// Note that we are using EIGEN_USE_HIP here instead of EIGEN_HIPCC...this is by design\n// There is code in the Tensorflow codebase that will define EIGEN_USE_GPU,  but\n// for some reason gets sent to the gcc/host compiler instead of the gpu/nvcc/hipcc compiler\n// When compiling such files, gcc will end up trying to pick up the CUDA headers by \n// default (see the code within \"unsupported/Eigen/CXX11/Tensor\" that is guarded by EIGEN_USE_GPU)\n// This will obviously not work when trying to compile tensorflow on a system with no CUDA\n// To work around this issue for HIP systems (and leave the default behaviour intact), the\n// HIP tensorflow build defines EIGEN_USE_HIP when compiling all source files, and \n// \"unsupported/Eigen/CXX11/Tensor\" has been updated to use HIP header when EIGEN_USE_HIP is\n// defined. In continuation of that requirement, the guard here needs to be EIGEN_USE_HIP as well\n\n#if defined(EIGEN_USE_HIP)\n\n#define gpuStream_t hipStream_t\n#define gpuDeviceProp_t hipDeviceProp_t\n#define gpuError_t hipError_t\n#define gpuSuccess hipSuccess\n#define gpuErrorNotReady hipErrorNotReady\n#define gpuGetDeviceCount hipGetDeviceCount\n#define gpuGetLastError hipGetLastError\n#define gpuPeekAtLastError hipPeekAtLastError\n#define gpuGetErrorName hipGetErrorName\n#define gpuGetErrorString hipGetErrorString\n#define gpuGetDeviceProperties hipGetDeviceProperties\n#define gpuStreamDefault hipStreamDefault\n#define gpuGetDevice hipGetDevice\n#define gpuSetDevice hipSetDevice\n#define gpuMalloc hipMalloc\n#define gpuFree hipFree\n#define gpuMemsetAsync hipMemsetAsync\n#define gpuMemcpyAsync hipMemcpyAsync\n#define gpuMemcpyDeviceToDevice hipMemcpyDeviceToDevice\n#define gpuMemcpyDeviceToHost hipMemcpyDeviceToHost\n#define gpuMemcpyHostToDevice hipMemcpyHostToDevice\n#define gpuStreamQuery hipStreamQuery\n#define gpuSharedMemConfig hipSharedMemConfig\n#define gpuDeviceSetSharedMemConfig hipDeviceSetSharedMemConfig\n#define gpuStreamSynchronize hipStreamSynchronize\n#define gpuDeviceSynchronize hipDeviceSynchronize\n#define gpuMemcpy hipMemcpy\n\n#else\n\n#define gpuStream_t cudaStream_t\n#define gpuDeviceProp_t cudaDeviceProp\n#define gpuError_t cudaError_t\n#define gpuSuccess cudaSuccess\n#define gpuErrorNotReady cudaErrorNotReady\n#define gpuGetDeviceCount cudaGetDeviceCount\n#define gpuGetLastError cudaGetLastError\n#define gpuPeekAtLastError cudaPeekAtLastError\n#define gpuGetErrorName cudaGetErrorName\n#define gpuGetErrorString cudaGetErrorString\n#define gpuGetDeviceProperties cudaGetDeviceProperties\n#define gpuStreamDefault cudaStreamDefault\n#define gpuGetDevice cudaGetDevice\n#define gpuSetDevice cudaSetDevice\n#define gpuMalloc cudaMalloc\n#define gpuFree cudaFree\n#define gpuMemsetAsync cudaMemsetAsync\n#define gpuMemcpyAsync cudaMemcpyAsync\n#define gpuMemcpyDeviceToDevice cudaMemcpyDeviceToDevice\n#define gpuMemcpyDeviceToHost cudaMemcpyDeviceToHost\n#define gpuMemcpyHostToDevice cudaMemcpyHostToDevice\n#define gpuStreamQuery cudaStreamQuery\n#define gpuSharedMemConfig cudaSharedMemConfig\n#define gpuDeviceSetSharedMemConfig cudaDeviceSetSharedMemConfig\n#define gpuStreamSynchronize cudaStreamSynchronize\n#define gpuDeviceSynchronize cudaDeviceSynchronize\n#define gpuMemcpy cudaMemcpy\n\n#endif\n\n// gpu_assert can be overridden\n#ifndef gpu_assert\n\n#if defined(EIGEN_HIP_DEVICE_COMPILE)\n// HIPCC do not support the use of assert on the GPU side.\n#define gpu_assert(COND)\n#else\n#define gpu_assert(COND) assert(COND)\n#endif\n\n#endif // gpu_assert\n\n#endif  // EIGEN_CXX11_TENSOR_GPU_HIP_CUDA_DEFINES_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorGpuHipCudaUndefines.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n// Copyright (C) 2018 Deven Desai <deven.desai.amd@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#if defined(EIGEN_CXX11_TENSOR_GPU_HIP_CUDA_DEFINES_H)\n\n#undef gpuStream_t\n#undef gpuDeviceProp_t \n#undef gpuError_t\n#undef gpuSuccess\n#undef gpuErrorNotReady\n#undef gpuGetDeviceCount\n#undef gpuGetErrorString\n#undef gpuGetDeviceProperties\n#undef gpuStreamDefault\n#undef gpuGetDevice\n#undef gpuSetDevice\n#undef gpuMalloc\n#undef gpuFree\n#undef gpuMemsetAsync\n#undef gpuMemcpyAsync\n#undef gpuMemcpyDeviceToDevice\n#undef gpuMemcpyDeviceToHost\n#undef gpuMemcpyHostToDevice\n#undef gpuStreamQuery\n#undef gpuSharedMemConfig\n#undef gpuDeviceSetSharedMemConfig\n#undef gpuStreamSynchronize\n#undef gpuDeviceSynchronize\n#undef gpuMemcpy\n\n#undef EIGEN_CXX11_TENSOR_GPU_HIP_CUDA_DEFINES_H\n\n#endif // EIGEN_CXX11_TENSOR_GPU_HIP_CUDA_DEFINES_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIO.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_IO_H\n#define EIGEN_CXX11_TENSOR_TENSOR_IO_H\n\nnamespace Eigen {\n\nnamespace internal {\n\n// Print the tensor as a 2d matrix\ntemplate <typename Tensor, int Rank>\nstruct TensorPrinter {\n  static void run (std::ostream& os, const Tensor& tensor) {\n    typedef typename internal::remove_const<typename Tensor::Scalar>::type Scalar;\n    typedef typename Tensor::Index Index;\n    const Index total_size = internal::array_prod(tensor.dimensions());\n    if (total_size > 0) {\n      const Index first_dim = Eigen::internal::array_get<0>(tensor.dimensions());\n      static const int layout = Tensor::Layout;\n      Map<const Array<Scalar, Dynamic, Dynamic, layout> > matrix(const_cast<Scalar*>(tensor.data()), first_dim, total_size/first_dim);\n      os << matrix;\n    }\n  }\n};\n\n\n// Print the tensor as a vector\ntemplate <typename Tensor>\nstruct TensorPrinter<Tensor, 1> {\n  static void run (std::ostream& os, const Tensor& tensor) {\n    typedef typename internal::remove_const<typename Tensor::Scalar>::type Scalar;\n    typedef typename Tensor::Index Index;\n    const Index total_size = internal::array_prod(tensor.dimensions());\n    if (total_size > 0) {\n      Map<const Array<Scalar, Dynamic, 1> > array(const_cast<Scalar*>(tensor.data()), total_size);\n      os << array;\n    }\n  }\n};\n\n\n// Print the tensor as a scalar\ntemplate <typename Tensor>\nstruct TensorPrinter<Tensor, 0> {\n  static void run (std::ostream& os, const Tensor& tensor) {\n    os << tensor.coeff(0);\n  }\n};\n}\n\ntemplate <typename T>\nstd::ostream& operator << (std::ostream& os, const TensorBase<T, ReadOnlyAccessors>& expr) {\n  typedef TensorEvaluator<const TensorForcedEvalOp<const T>, DefaultDevice> Evaluator;\n  typedef typename Evaluator::Dimensions Dimensions;\n\n  // Evaluate the expression if needed\n  TensorForcedEvalOp<const T> eval = expr.eval();\n  Evaluator tensor(eval, DefaultDevice());\n  tensor.evalSubExprsIfNeeded(NULL);\n\n  // Print the result\n  static const int rank = internal::array_size<Dimensions>::value;\n  internal::TensorPrinter<Evaluator, rank>::run(os, tensor);\n\n  // Cleanup.\n  tensor.cleanup();\n  return os;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_IO_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorImagePatch.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_IMAGE_PATCH_H\n#define EIGEN_CXX11_TENSOR_TENSOR_IMAGE_PATCH_H\n\nnamespace Eigen {\n\n/** \\class TensorImagePatch\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Patch extraction specialized for image processing.\n  * This assumes that the input has a least 3 dimensions ordered as follow:\n  *  1st dimension: channels (of size d)\n  *  2nd dimension: rows (of size r)\n  *  3rd dimension: columns (of size c)\n  *  There can be additional dimensions such as time (for video) or batch (for\n  * bulk processing after the first 3.\n  * Calling the image patch code with patch_rows and patch_cols is equivalent\n  * to calling the regular patch extraction code with parameters d, patch_rows,\n  * patch_cols, and 1 for all the additional dimensions.\n  */\nnamespace internal {\n\ntemplate<DenseIndex Rows, DenseIndex Cols, typename XprType>\nstruct traits<TensorImagePatchOp<Rows, Cols, XprType> > : public traits<XprType>\n{\n  typedef typename internal::remove_const<typename XprType::Scalar>::type Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions + 1;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<DenseIndex Rows, DenseIndex Cols, typename XprType>\nstruct eval<TensorImagePatchOp<Rows, Cols, XprType>, Eigen::Dense>\n{\n  typedef const TensorImagePatchOp<Rows, Cols, XprType>& type;\n};\n\ntemplate<DenseIndex Rows, DenseIndex Cols, typename XprType>\nstruct nested<TensorImagePatchOp<Rows, Cols, XprType>, 1, typename eval<TensorImagePatchOp<Rows, Cols, XprType> >::type>\n{\n  typedef TensorImagePatchOp<Rows, Cols, XprType> type;\n};\n\ntemplate <typename Self, bool Vectorizable>\nstruct ImagePatchCopyOp {\n  typedef typename Self::Index Index;\n  typedef typename Self::Scalar Scalar;\n  typedef typename Self::Impl Impl;\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void Run(\n      const Self& self, const Index num_coeff_to_copy, const Index dst_index,\n      Scalar* dst_data, const Index src_index) {\n    const Impl& impl = self.impl();\n    for (Index i = 0; i < num_coeff_to_copy; ++i) {\n      dst_data[dst_index + i] = impl.coeff(src_index + i);\n    }\n  }\n};\n\ntemplate <typename Self>\nstruct ImagePatchCopyOp<Self, true> {\n  typedef typename Self::Index Index;\n  typedef typename Self::Scalar Scalar;\n  typedef typename Self::Impl Impl;\n  typedef typename packet_traits<Scalar>::type Packet;\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void Run(\n      const Self& self, const Index num_coeff_to_copy, const Index dst_index,\n      Scalar* dst_data, const Index src_index) {\n    const Impl& impl = self.impl();\n    const Index packet_size = internal::unpacket_traits<Packet>::size;\n    const Index vectorized_size =\n        (num_coeff_to_copy / packet_size) * packet_size;\n    for (Index i = 0; i < vectorized_size; i += packet_size) {\n      Packet p = impl.template packet<Unaligned>(src_index + i);\n      internal::pstoret<Scalar, Packet, Unaligned>(dst_data + dst_index + i, p);\n    }\n    for (Index i = vectorized_size; i < num_coeff_to_copy; ++i) {\n      dst_data[dst_index + i] = impl.coeff(src_index + i);\n    }\n  }\n};\n\ntemplate <typename Self>\nstruct ImagePatchPaddingOp {\n  typedef typename Self::Index Index;\n  typedef typename Self::Scalar Scalar;\n  typedef typename packet_traits<Scalar>::type Packet;\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void Run(\n      const Index num_coeff_to_pad, const Scalar padding_value,\n      const Index dst_index, Scalar* dst_data) {\n    const Index packet_size = internal::unpacket_traits<Packet>::size;\n    const Packet padded_packet = internal::pset1<Packet>(padding_value);\n    const Index vectorized_size =\n        (num_coeff_to_pad / packet_size) * packet_size;\n    for (Index i = 0; i < vectorized_size; i += packet_size) {\n      internal::pstoret<Scalar, Packet, Unaligned>(dst_data + dst_index + i,\n                                                   padded_packet);\n    }\n    for (Index i = vectorized_size; i < num_coeff_to_pad; ++i) {\n      dst_data[dst_index + i] = padding_value;\n    }\n  }\n};\n\n}  // end namespace internal\n\ntemplate<DenseIndex Rows, DenseIndex Cols, typename XprType>\nclass TensorImagePatchOp : public TensorBase<TensorImagePatchOp<Rows, Cols, XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorImagePatchOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorImagePatchOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorImagePatchOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorImagePatchOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorImagePatchOp(const XprType& expr, DenseIndex patch_rows, DenseIndex patch_cols,\n                                                           DenseIndex row_strides, DenseIndex col_strides,\n                                                           DenseIndex in_row_strides, DenseIndex in_col_strides,\n                                                           DenseIndex row_inflate_strides, DenseIndex col_inflate_strides,\n                                                           PaddingType padding_type, Scalar padding_value)\n                                                           : m_xpr(expr), m_patch_rows(patch_rows), m_patch_cols(patch_cols),\n                                                           m_row_strides(row_strides), m_col_strides(col_strides),\n                                                           m_in_row_strides(in_row_strides), m_in_col_strides(in_col_strides),\n                                                           m_row_inflate_strides(row_inflate_strides), m_col_inflate_strides(col_inflate_strides),\n                                                           m_padding_explicit(false), m_padding_top(0), m_padding_bottom(0), m_padding_left(0), m_padding_right(0),\n                                                           m_padding_type(padding_type), m_padding_value(padding_value) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorImagePatchOp(const XprType& expr, DenseIndex patch_rows, DenseIndex patch_cols,\n                                                           DenseIndex row_strides, DenseIndex col_strides,\n                                                           DenseIndex in_row_strides, DenseIndex in_col_strides,\n                                                           DenseIndex row_inflate_strides, DenseIndex col_inflate_strides,\n                                                           DenseIndex padding_top, DenseIndex padding_bottom,\n                                                           DenseIndex padding_left, DenseIndex padding_right,\n                                                           Scalar padding_value)\n                                                           : m_xpr(expr), m_patch_rows(patch_rows), m_patch_cols(patch_cols),\n                                                           m_row_strides(row_strides), m_col_strides(col_strides),\n                                                           m_in_row_strides(in_row_strides), m_in_col_strides(in_col_strides),\n                                                           m_row_inflate_strides(row_inflate_strides), m_col_inflate_strides(col_inflate_strides),\n                                                           m_padding_explicit(true), m_padding_top(padding_top), m_padding_bottom(padding_bottom),\n                                                           m_padding_left(padding_left), m_padding_right(padding_right),\n                                                           m_padding_type(PADDING_VALID), m_padding_value(padding_value) {}\n\n\n    EIGEN_DEVICE_FUNC\n    DenseIndex patch_rows() const { return m_patch_rows; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex patch_cols() const { return m_patch_cols; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex row_strides() const { return m_row_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex col_strides() const { return m_col_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex in_row_strides() const { return m_in_row_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex in_col_strides() const { return m_in_col_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex row_inflate_strides() const { return m_row_inflate_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex col_inflate_strides() const { return m_col_inflate_strides; }\n    EIGEN_DEVICE_FUNC\n    bool padding_explicit() const { return m_padding_explicit; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex padding_top() const { return m_padding_top; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex padding_bottom() const { return m_padding_bottom; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex padding_left() const { return m_padding_left; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex padding_right() const { return m_padding_right; }\n    EIGEN_DEVICE_FUNC\n    PaddingType padding_type() const { return m_padding_type; }\n    EIGEN_DEVICE_FUNC\n    Scalar padding_value() const { return m_padding_value; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const DenseIndex m_patch_rows;\n    const DenseIndex m_patch_cols;\n    const DenseIndex m_row_strides;\n    const DenseIndex m_col_strides;\n    const DenseIndex m_in_row_strides;\n    const DenseIndex m_in_col_strides;\n    const DenseIndex m_row_inflate_strides;\n    const DenseIndex m_col_inflate_strides;\n    const bool m_padding_explicit;\n    const DenseIndex m_padding_top;\n    const DenseIndex m_padding_bottom;\n    const DenseIndex m_padding_left;\n    const DenseIndex m_padding_right;\n    const PaddingType m_padding_type;\n    const Scalar m_padding_value;\n};\n\n// Eval as rvalue\ntemplate<DenseIndex Rows, DenseIndex Cols, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorImagePatchOp<Rows, Cols, ArgType>, Device>\n{\n  typedef TensorImagePatchOp<Rows, Cols, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumInputDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  static const int NumDims = NumInputDims + 1;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename internal::remove_const<typename XprType::Scalar>::type Scalar;\n  typedef TensorEvaluator<const TensorImagePatchOp<Rows, Cols, ArgType>,\n                          Device> Self;\n  typedef TensorEvaluator<ArgType, Device> Impl;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned         = false,\n    PacketAccess      = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess       = false,\n    PreferBlockAccess = true,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess       = false,\n    RawAccess         = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator( const XprType& op, const Device& device)\n      : m_device(device), m_impl(op.expression(), device)\n  {\n    EIGEN_STATIC_ASSERT((NumDims >= 4), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    m_paddingValue = op.padding_value();\n\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n\n    // Caches a few variables.\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_inputDepth = input_dims[0];\n      m_inputRows = input_dims[1];\n      m_inputCols = input_dims[2];\n    } else {\n      m_inputDepth = input_dims[NumInputDims-1];\n      m_inputRows = input_dims[NumInputDims-2];\n      m_inputCols = input_dims[NumInputDims-3];\n    }\n\n    m_row_strides = op.row_strides();\n    m_col_strides = op.col_strides();\n\n    // Input strides and effective input/patch size\n    m_in_row_strides = op.in_row_strides();\n    m_in_col_strides = op.in_col_strides();\n    m_row_inflate_strides = op.row_inflate_strides();\n    m_col_inflate_strides = op.col_inflate_strides();\n    // The \"effective\" input rows and input cols are the input rows and cols\n    // after inflating them with zeros.\n    // For examples, a 2x3 matrix with row_inflate_strides and\n    // col_inflate_strides of 2 comes from:\n    //   A B C\n    //   D E F\n    //\n    // to a matrix is 3 x 5:\n    //\n    //   A . B . C\n    //   . . . . .\n    //   D . E . F\n\n    m_input_rows_eff = (m_inputRows - 1) * m_row_inflate_strides + 1;\n    m_input_cols_eff = (m_inputCols - 1) * m_col_inflate_strides + 1;\n    m_patch_rows_eff = op.patch_rows() + (op.patch_rows() - 1) * (m_in_row_strides - 1);\n    m_patch_cols_eff = op.patch_cols() + (op.patch_cols() - 1) * (m_in_col_strides - 1);\n\n    if (op.padding_explicit()) {\n      m_outputRows = numext::ceil((m_input_rows_eff + op.padding_top() + op.padding_bottom() - m_patch_rows_eff + 1.f) / static_cast<float>(m_row_strides));\n      m_outputCols = numext::ceil((m_input_cols_eff + op.padding_left() + op.padding_right() - m_patch_cols_eff + 1.f) / static_cast<float>(m_col_strides));\n      m_rowPaddingTop = op.padding_top();\n      m_colPaddingLeft = op.padding_left();\n    } else {\n      // Computing padding from the type\n      switch (op.padding_type()) {\n        case PADDING_VALID:\n          m_outputRows = numext::ceil((m_input_rows_eff - m_patch_rows_eff + 1.f) / static_cast<float>(m_row_strides));\n          m_outputCols = numext::ceil((m_input_cols_eff - m_patch_cols_eff + 1.f) / static_cast<float>(m_col_strides));\n          // Calculate the padding\n          m_rowPaddingTop = numext::maxi<Index>(0, ((m_outputRows - 1) * m_row_strides + m_patch_rows_eff - m_input_rows_eff) / 2);\n          m_colPaddingLeft = numext::maxi<Index>(0, ((m_outputCols - 1) * m_col_strides + m_patch_cols_eff - m_input_cols_eff) / 2);\n          break;\n        case PADDING_SAME:\n          m_outputRows = numext::ceil(m_input_rows_eff / static_cast<float>(m_row_strides));\n          m_outputCols = numext::ceil(m_input_cols_eff / static_cast<float>(m_col_strides));\n          // Calculate the padding\n          m_rowPaddingTop = ((m_outputRows - 1) * m_row_strides + m_patch_rows_eff - m_input_rows_eff) / 2;\n          m_colPaddingLeft = ((m_outputCols - 1) * m_col_strides + m_patch_cols_eff - m_input_cols_eff) / 2;\n          // The padding size calculation for PADDING_SAME has been updated to\n          // be consistent with how TensorFlow extracts its paddings.\n          m_rowPaddingTop = numext::maxi<Index>(0, m_rowPaddingTop);\n          m_colPaddingLeft = numext::maxi<Index>(0, m_colPaddingLeft);\n          break;\n        default:\n          eigen_assert(false && \"unexpected padding\");\n          m_outputCols=0; // silence the uninitialised warning;\n          m_outputRows=0; //// silence the uninitialised warning;\n      }\n    }\n    eigen_assert(m_outputRows > 0);\n    eigen_assert(m_outputCols > 0);\n\n    // Dimensions for result of extraction.\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      // ColMajor\n      // 0: depth\n      // 1: patch_rows\n      // 2: patch_cols\n      // 3: number of patches\n      // 4 and beyond: anything else (such as batch).\n      m_dimensions[0] = input_dims[0];\n      m_dimensions[1] = op.patch_rows();\n      m_dimensions[2] = op.patch_cols();\n      m_dimensions[3] = m_outputRows * m_outputCols;\n      for (int i = 4; i < NumDims; ++i) {\n        m_dimensions[i] = input_dims[i-1];\n      }\n    } else {\n      // RowMajor\n      // NumDims-1: depth\n      // NumDims-2: patch_rows\n      // NumDims-3: patch_cols\n      // NumDims-4: number of patches\n      // NumDims-5 and beyond: anything else (such as batch).\n      m_dimensions[NumDims-1] = input_dims[NumInputDims-1];\n      m_dimensions[NumDims-2] = op.patch_rows();\n      m_dimensions[NumDims-3] = op.patch_cols();\n      m_dimensions[NumDims-4] = m_outputRows * m_outputCols;\n      for (int i = NumDims-5; i >= 0; --i) {\n        m_dimensions[i] = input_dims[i];\n      }\n    }\n\n    // Strides for moving the patch in various dimensions.\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_colStride = m_dimensions[1];\n      m_patchStride = m_colStride * m_dimensions[2] * m_dimensions[0];\n      m_otherStride = m_patchStride * m_dimensions[3];\n    } else {\n      m_colStride = m_dimensions[NumDims-2];\n      m_patchStride = m_colStride * m_dimensions[NumDims-3] * m_dimensions[NumDims-1];\n      m_otherStride = m_patchStride * m_dimensions[NumDims-4];\n    }\n\n    // Strides for navigating through the input tensor.\n    m_rowInputStride = m_inputDepth;\n    m_colInputStride = m_inputDepth * m_inputRows;\n    m_patchInputStride = m_inputDepth * m_inputRows * m_inputCols;\n\n    // Fast representations of different variables.\n    m_fastOtherStride = internal::TensorIntDivisor<Index>(m_otherStride);\n    m_fastPatchStride = internal::TensorIntDivisor<Index>(m_patchStride);\n    m_fastColStride = internal::TensorIntDivisor<Index>(m_colStride);\n    m_fastInflateRowStride = internal::TensorIntDivisor<Index>(m_row_inflate_strides);\n    m_fastInflateColStride = internal::TensorIntDivisor<Index>(m_col_inflate_strides);\n    m_fastInputColsEff = internal::TensorIntDivisor<Index>(m_input_cols_eff);\n\n    // Number of patches in the width dimension.\n    m_fastOutputRows = internal::TensorIntDivisor<Index>(m_outputRows);\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_fastOutputDepth = internal::TensorIntDivisor<Index>(m_dimensions[0]);\n    } else {\n      m_fastOutputDepth = internal::TensorIntDivisor<Index>(m_dimensions[NumDims-1]);\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType /*data*/) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    m_impl.evalSubExprsIfNeededAsync(nullptr, [done](bool) { done(true); });\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    // Patch index corresponding to the passed in index.\n    const Index patchIndex = index / m_fastPatchStride;\n    // Find the offset of the element wrt the location of the first element.\n    const Index patchOffset = (index - patchIndex * m_patchStride) / m_fastOutputDepth;\n\n    // Other ways to index this element.\n    const Index otherIndex = (NumDims == 4) ? 0 : index / m_fastOtherStride;\n    const Index patch2DIndex = (NumDims == 4) ? patchIndex : (index - otherIndex * m_otherStride) / m_fastPatchStride;\n\n    // Calculate col index in the input original tensor.\n    const Index colIndex = patch2DIndex / m_fastOutputRows;\n    const Index colOffset = patchOffset / m_fastColStride;\n    const Index inputCol = colIndex * m_col_strides + colOffset * m_in_col_strides - m_colPaddingLeft;\n    const Index origInputCol = (m_col_inflate_strides == 1) ? inputCol : ((inputCol >= 0) ? (inputCol / m_fastInflateColStride) : 0);\n    if (inputCol < 0 || inputCol >= m_input_cols_eff ||\n        ((m_col_inflate_strides != 1) && (inputCol != origInputCol * m_col_inflate_strides))) {\n      return Scalar(m_paddingValue);\n    }\n\n    // Calculate row index in the original input tensor.\n    const Index rowIndex = patch2DIndex - colIndex * m_outputRows;\n    const Index rowOffset = patchOffset - colOffset * m_colStride;\n    const Index inputRow = rowIndex * m_row_strides + rowOffset * m_in_row_strides - m_rowPaddingTop;\n    const Index origInputRow = (m_row_inflate_strides == 1) ? inputRow : ((inputRow >= 0) ? (inputRow / m_fastInflateRowStride) : 0);\n    if (inputRow < 0 || inputRow >= m_input_rows_eff ||\n        ((m_row_inflate_strides != 1) && (inputRow != origInputRow * m_row_inflate_strides))) {\n      return Scalar(m_paddingValue);\n    }\n\n    const int depth_index = static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 0 : NumDims - 1;\n    const Index depth = index - (index / m_fastOutputDepth) * m_dimensions[depth_index];\n\n    const Index inputIndex = depth + origInputRow * m_rowInputStride + origInputCol * m_colInputStride + otherIndex * m_patchInputStride;\n    return m_impl.coeff(inputIndex);\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    if (m_in_row_strides != 1 || m_in_col_strides != 1 || m_row_inflate_strides != 1 || m_col_inflate_strides != 1) {\n      return packetWithPossibleZero(index);\n    }\n\n    const Index indices[2] = {index, index + PacketSize - 1};\n    const Index patchIndex = indices[0] / m_fastPatchStride;\n    if (patchIndex != indices[1] / m_fastPatchStride) {\n      return packetWithPossibleZero(index);\n    }\n    const Index otherIndex = (NumDims == 4) ? 0 : indices[0] / m_fastOtherStride;\n    eigen_assert(otherIndex == indices[1] / m_fastOtherStride);\n\n    // Find the offset of the element wrt the location of the first element.\n    const Index patchOffsets[2] = {(indices[0] - patchIndex * m_patchStride) / m_fastOutputDepth,\n                                   (indices[1] - patchIndex * m_patchStride) / m_fastOutputDepth};\n\n    const Index patch2DIndex = (NumDims == 4) ? patchIndex : (indices[0] - otherIndex * m_otherStride) / m_fastPatchStride;\n    eigen_assert(patch2DIndex == (indices[1] - otherIndex * m_otherStride) / m_fastPatchStride);\n\n    const Index colIndex = patch2DIndex / m_fastOutputRows;\n    const Index colOffsets[2] = {patchOffsets[0] / m_fastColStride, patchOffsets[1] / m_fastColStride};\n\n    // Calculate col indices in the original input tensor.\n    const Index inputCols[2] = {colIndex * m_col_strides + colOffsets[0] -\n      m_colPaddingLeft, colIndex * m_col_strides + colOffsets[1] - m_colPaddingLeft};\n    if (inputCols[1] < 0 || inputCols[0] >= m_inputCols) {\n      return internal::pset1<PacketReturnType>(Scalar(m_paddingValue));\n    }\n\n    if (inputCols[0] == inputCols[1]) {\n      const Index rowIndex = patch2DIndex - colIndex * m_outputRows;\n      const Index rowOffsets[2] = {patchOffsets[0] - colOffsets[0]*m_colStride, patchOffsets[1] - colOffsets[1]*m_colStride};\n      eigen_assert(rowOffsets[0] <= rowOffsets[1]);\n      // Calculate col indices in the original input tensor.\n      const Index inputRows[2] = {rowIndex * m_row_strides + rowOffsets[0] -\n        m_rowPaddingTop, rowIndex * m_row_strides + rowOffsets[1] - m_rowPaddingTop};\n\n      if (inputRows[1] < 0 || inputRows[0] >= m_inputRows) {\n        return internal::pset1<PacketReturnType>(Scalar(m_paddingValue));\n      }\n\n      if (inputRows[0] >= 0 && inputRows[1] < m_inputRows) {\n        // no padding\n        const int depth_index = static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 0 : NumDims - 1;\n        const Index depth = index - (index / m_fastOutputDepth) * m_dimensions[depth_index];\n        const Index inputIndex = depth + inputRows[0] * m_rowInputStride + inputCols[0] * m_colInputStride + otherIndex * m_patchInputStride;\n        return m_impl.template packet<Unaligned>(inputIndex);\n      }\n    }\n\n    return packetWithPossibleZero(index);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const TensorEvaluator<ArgType, Device>& impl() const { return m_impl; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n\n  Index rowPaddingTop() const { return m_rowPaddingTop; }\n  Index colPaddingLeft() const { return m_colPaddingLeft; }\n  Index outputRows() const { return m_outputRows; }\n  Index outputCols() const { return m_outputCols; }\n  Index userRowStride() const { return m_row_strides; }\n  Index userColStride() const { return m_col_strides; }\n  Index userInRowStride() const { return m_in_row_strides; }\n  Index userInColStride() const { return m_in_col_strides; }\n  Index rowInflateStride() const { return m_row_inflate_strides; }\n  Index colInflateStride() const { return m_col_inflate_strides; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    // We conservatively estimate the cost for the code path where the computed\n    // index is inside the original image and\n    // TensorEvaluator<ArgType, Device>::CoordAccess is false.\n    const double compute_cost = 3 * TensorOpCost::DivCost<Index>() +\n                                6 * TensorOpCost::MulCost<Index>() +\n                                8 * TensorOpCost::MulCost<Index>();\n    return m_impl.costPerCoeff(vectorized) +\n           TensorOpCost(0, 0, compute_cost, vectorized, PacketSize);\n  }\n\n protected:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetWithPossibleZero(Index index) const\n  {\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < PacketSize; ++i) {\n      values[i] = coeff(index+i);\n    }\n    PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n    return rslt;\n  }\n\n  Dimensions m_dimensions;\n\n  Index m_otherStride;\n  Index m_patchStride;\n  Index m_colStride;\n  Index m_row_strides;\n  Index m_col_strides;\n\n  Index m_in_row_strides;\n  Index m_in_col_strides;\n  Index m_row_inflate_strides;\n  Index m_col_inflate_strides;\n\n  Index m_input_rows_eff;\n  Index m_input_cols_eff;\n  Index m_patch_rows_eff;\n  Index m_patch_cols_eff;\n\n  internal::TensorIntDivisor<Index> m_fastOtherStride;\n  internal::TensorIntDivisor<Index> m_fastPatchStride;\n  internal::TensorIntDivisor<Index> m_fastColStride;\n  internal::TensorIntDivisor<Index> m_fastInflateRowStride;\n  internal::TensorIntDivisor<Index> m_fastInflateColStride;\n  internal::TensorIntDivisor<Index> m_fastInputColsEff;\n\n  Index m_rowInputStride;\n  Index m_colInputStride;\n  Index m_patchInputStride;\n\n  Index m_inputDepth;\n  Index m_inputRows;\n  Index m_inputCols;\n\n  Index m_outputRows;\n  Index m_outputCols;\n\n  Index m_rowPaddingTop;\n  Index m_colPaddingLeft;\n\n  internal::TensorIntDivisor<Index> m_fastOutputRows;\n  internal::TensorIntDivisor<Index> m_fastOutputDepth;\n\n  Scalar m_paddingValue;\n\n  const Device EIGEN_DEVICE_REF m_device;\n  TensorEvaluator<ArgType, Device> m_impl;\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_IMAGE_PATCH_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIndexList.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_INDEX_LIST_H\n#define EIGEN_CXX11_TENSOR_TENSOR_INDEX_LIST_H\n\n\n#if EIGEN_HAS_CONSTEXPR && EIGEN_HAS_VARIADIC_TEMPLATES\n\n#define EIGEN_HAS_INDEX_LIST\n\nnamespace Eigen {\n\n/** \\internal\n  *\n  * \\class TensorIndexList\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Set of classes used to encode a set of Tensor dimensions/indices.\n  *\n  * The indices in the list can be known at compile time or at runtime. A mix\n  * of static and dynamic indices can also be provided if needed. The tensor\n  * code will attempt to take advantage of the indices that are known at\n  * compile time to optimize the code it generates.\n  *\n  * This functionality requires a c++11 compliant compiler. If your compiler\n  * is older you need to use arrays of indices instead.\n  *\n  * Several examples are provided in the cxx11_tensor_index_list.cpp file.\n  *\n  * \\sa Tensor\n  */\n\ntemplate <Index n>\nstruct type2index {\n  static const Index value = n;\n  EIGEN_DEVICE_FUNC constexpr operator Index() const { return n; }\n  EIGEN_DEVICE_FUNC void set(Index val) {\n    eigen_assert(val == n);\n  }\n};\n\n// This can be used with IndexPairList to get compile-time constant pairs,\n// such as IndexPairList<type2indexpair<1,2>, type2indexpair<3,4>>().\ntemplate <Index f, Index s>\nstruct type2indexpair {\n  static const Index first = f;\n  static const Index second = s;\n\n  constexpr EIGEN_DEVICE_FUNC operator IndexPair<Index>() const {\n    return IndexPair<Index>(f, s);\n  }\n\n  EIGEN_DEVICE_FUNC void set(const IndexPair<Index>& val) {\n    eigen_assert(val.first == f);\n    eigen_assert(val.second == s);\n  }\n};\n\n\ntemplate<Index n> struct NumTraits<type2index<n> >\n{\n  typedef Index Real;\n  enum {\n    IsComplex = 0,\n    RequireInitialization = false,\n    ReadCost = 1,\n    AddCost = 1,\n    MulCost = 1\n  };\n\n  EIGEN_DEVICE_FUNC static EIGEN_CONSTEXPR EIGEN_STRONG_INLINE Real epsilon() { return 0; }\n  EIGEN_DEVICE_FUNC static EIGEN_CONSTEXPR EIGEN_STRONG_INLINE Real dummy_precision() { return 0; }\n  EIGEN_DEVICE_FUNC static EIGEN_CONSTEXPR EIGEN_STRONG_INLINE Real highest() { return n; }\n  EIGEN_DEVICE_FUNC static EIGEN_CONSTEXPR EIGEN_STRONG_INLINE Real lowest() { return n; }\n};\n\nnamespace internal {\ntemplate <typename T>\nEIGEN_DEVICE_FUNC void update_value(T& val, Index new_val) {\n  val = internal::convert_index<T>(new_val);\n}\ntemplate <Index n>\nEIGEN_DEVICE_FUNC void update_value(type2index<n>& val, Index new_val) {\n  val.set(new_val);\n}\n\ntemplate <typename T>\nEIGEN_DEVICE_FUNC void update_value(T& val, IndexPair<Index> new_val) {\n  val = new_val;\n}\ntemplate <Index f, Index s>\nEIGEN_DEVICE_FUNC void update_value(type2indexpair<f, s>& val, IndexPair<Index> new_val) {\n  val.set(new_val);\n}\n\n\ntemplate <typename T>\nstruct is_compile_time_constant {\n  static constexpr bool value = false;\n};\n\ntemplate <Index idx>\nstruct is_compile_time_constant<type2index<idx> > {\n  static constexpr bool value = true;\n};\ntemplate <Index idx>\nstruct is_compile_time_constant<const type2index<idx> > {\n  static constexpr bool value = true;\n};\ntemplate <Index idx>\nstruct is_compile_time_constant<type2index<idx>& > {\n  static constexpr bool value = true;\n};\ntemplate <Index idx>\nstruct is_compile_time_constant<const type2index<idx>& > {\n  static constexpr bool value = true;\n};\n\ntemplate <Index f, Index s>\nstruct is_compile_time_constant<type2indexpair<f, s> > {\n  static constexpr bool value = true;\n};\ntemplate <Index f, Index s>\nstruct is_compile_time_constant<const type2indexpair<f, s> > {\n  static constexpr bool value = true;\n};\ntemplate <Index f, Index s>\nstruct is_compile_time_constant<type2indexpair<f, s>& > {\n  static constexpr bool value = true;\n};\ntemplate <Index f, Index s>\nstruct is_compile_time_constant<const type2indexpair<f, s>& > {\n  static constexpr bool value = true;\n};\n\n\ntemplate<typename... T>\nstruct IndexTuple;\n\ntemplate<typename T, typename... O>\nstruct IndexTuple<T, O...> {\n  EIGEN_DEVICE_FUNC constexpr IndexTuple() : head(), others() { }\n  EIGEN_DEVICE_FUNC constexpr IndexTuple(const T& v, const O... o) : head(v), others(o...) { }\n\n  constexpr static int count = 1 + sizeof...(O);\n  T head;\n  IndexTuple<O...> others;\n  typedef T Head;\n  typedef IndexTuple<O...> Other;\n};\n\ntemplate<typename T>\n  struct IndexTuple<T> {\n  EIGEN_DEVICE_FUNC constexpr IndexTuple() : head() { }\n  EIGEN_DEVICE_FUNC constexpr IndexTuple(const T& v) : head(v) { }\n\n  constexpr static int count = 1;\n  T head;\n  typedef T Head;\n};\n\n\ntemplate<int N, typename... T>\nstruct IndexTupleExtractor;\n\ntemplate<int N, typename T, typename... O>\nstruct IndexTupleExtractor<N, T, O...> {\n\n  typedef typename IndexTupleExtractor<N-1, O...>::ValType ValType;\n\n  EIGEN_DEVICE_FUNC static constexpr ValType& get_val(IndexTuple<T, O...>& val) {\n    return IndexTupleExtractor<N-1, O...>::get_val(val.others);\n  }\n\n  EIGEN_DEVICE_FUNC static constexpr const ValType& get_val(const IndexTuple<T, O...>& val) {\n    return IndexTupleExtractor<N-1, O...>::get_val(val.others);\n  }\n  template <typename V>\n  EIGEN_DEVICE_FUNC static void set_val(IndexTuple<T, O...>& val, V& new_val) {\n    IndexTupleExtractor<N-1, O...>::set_val(val.others, new_val);\n  }\n\n};\n\ntemplate<typename T, typename... O>\n  struct IndexTupleExtractor<0, T, O...> {\n\n  typedef T ValType;\n\n  EIGEN_DEVICE_FUNC static constexpr ValType& get_val(IndexTuple<T, O...>& val) {\n    return val.head;\n  }\n  EIGEN_DEVICE_FUNC static constexpr const ValType& get_val(const IndexTuple<T, O...>& val) {\n    return val.head;\n  }\n  template <typename V>\n  EIGEN_DEVICE_FUNC static void set_val(IndexTuple<T, O...>& val, V& new_val) {\n    val.head = new_val;\n  }\n};\n\n\n\ntemplate <int N, typename T, typename... O>\nEIGEN_DEVICE_FUNC constexpr typename IndexTupleExtractor<N, T, O...>::ValType& array_get(IndexTuple<T, O...>& tuple) {\n  return IndexTupleExtractor<N, T, O...>::get_val(tuple);\n}\ntemplate <int N, typename T, typename... O>\nEIGEN_DEVICE_FUNC constexpr const typename IndexTupleExtractor<N, T, O...>::ValType& array_get(const IndexTuple<T, O...>& tuple) {\n  return IndexTupleExtractor<N, T, O...>::get_val(tuple);\n}\ntemplate <typename T, typename... O>\n  struct array_size<IndexTuple<T, O...> > {\n  static const size_t value = IndexTuple<T, O...>::count;\n};\ntemplate <typename T, typename... O>\n  struct array_size<const IndexTuple<T, O...> > {\n  static const size_t value = IndexTuple<T, O...>::count;\n};\n\n\n\n\ntemplate <Index Idx, typename ValueT>\nstruct tuple_coeff {\n  template <typename... T>\n  EIGEN_DEVICE_FUNC static constexpr ValueT get(const Index i, const IndexTuple<T...>& t) {\n    //    return array_get<Idx>(t) * (i == Idx) + tuple_coeff<Idx-1>::get(i, t) * (i != Idx);\n    return (i == Idx ? array_get<Idx>(t) : tuple_coeff<Idx-1, ValueT>::get(i, t));\n  }\n  template <typename... T>\n  EIGEN_DEVICE_FUNC static void set(const Index i, IndexTuple<T...>& t, const ValueT& value) {\n    if (i == Idx) {\n      update_value(array_get<Idx>(t), value);\n    } else {\n      tuple_coeff<Idx-1, ValueT>::set(i, t, value);\n    }\n  }\n\n  template <typename... T>\n  EIGEN_DEVICE_FUNC static constexpr bool value_known_statically(const Index i, const IndexTuple<T...>& t) {\n    return ((i == Idx) & is_compile_time_constant<typename IndexTupleExtractor<Idx, T...>::ValType>::value) ||\n        tuple_coeff<Idx-1, ValueT>::value_known_statically(i, t);\n  }\n\n  template <typename... T>\n  EIGEN_DEVICE_FUNC static constexpr bool values_up_to_known_statically(const IndexTuple<T...>& t) {\n    return is_compile_time_constant<typename IndexTupleExtractor<Idx, T...>::ValType>::value &&\n        tuple_coeff<Idx-1, ValueT>::values_up_to_known_statically(t);\n  }\n\n  template <typename... T>\n  EIGEN_DEVICE_FUNC static constexpr bool values_up_to_statically_known_to_increase(const IndexTuple<T...>& t) {\n    return is_compile_time_constant<typename IndexTupleExtractor<Idx, T...>::ValType>::value &&\n           is_compile_time_constant<typename IndexTupleExtractor<Idx, T...>::ValType>::value &&\n           array_get<Idx>(t) > array_get<Idx-1>(t) &&\n           tuple_coeff<Idx-1, ValueT>::values_up_to_statically_known_to_increase(t);\n  }\n};\n\ntemplate <typename ValueT>\nstruct tuple_coeff<0, ValueT> {\n  template <typename... T>\n  EIGEN_DEVICE_FUNC static constexpr ValueT get(const Index /*i*/, const IndexTuple<T...>& t) {\n    //  eigen_assert (i == 0);  // gcc fails to compile assertions in constexpr\n    return array_get<0>(t)/* * (i == 0)*/;\n  }\n  template <typename... T>\n  EIGEN_DEVICE_FUNC static void set(const Index i, IndexTuple<T...>& t, const ValueT value) {\n    eigen_assert (i == 0);\n    update_value(array_get<0>(t), value);\n  }\n  template <typename... T>\n  EIGEN_DEVICE_FUNC static constexpr bool value_known_statically(const Index i, const IndexTuple<T...>&) {\n    return is_compile_time_constant<typename IndexTupleExtractor<0, T...>::ValType>::value && (i == 0);\n  }\n\n  template <typename... T>\n  EIGEN_DEVICE_FUNC static constexpr bool values_up_to_known_statically(const IndexTuple<T...>&) {\n    return is_compile_time_constant<typename IndexTupleExtractor<0, T...>::ValType>::value;\n  }\n\n  template <typename... T>\n  EIGEN_DEVICE_FUNC static constexpr bool values_up_to_statically_known_to_increase(const IndexTuple<T...>&) {\n    return true;\n  }\n};\n}  // namespace internal\n\n\n\ntemplate<typename FirstType, typename... OtherTypes>\nstruct IndexList : internal::IndexTuple<FirstType, OtherTypes...> {\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC constexpr Index operator[] (const Index i) const {\n    return internal::tuple_coeff<internal::array_size<internal::IndexTuple<FirstType, OtherTypes...> >::value-1, Index>::get(i, *this);\n  }\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC constexpr Index get(const Index i) const {\n    return internal::tuple_coeff<internal::array_size<internal::IndexTuple<FirstType, OtherTypes...> >::value-1, Index>::get(i, *this);\n  }\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC void set(const Index i, const Index value) {\n    return internal::tuple_coeff<internal::array_size<internal::IndexTuple<FirstType, OtherTypes...> >::value-1, Index>::set(i, *this, value);\n  }\n\n  EIGEN_DEVICE_FUNC constexpr IndexList(const internal::IndexTuple<FirstType, OtherTypes...>& other) : internal::IndexTuple<FirstType, OtherTypes...>(other) { }\n  EIGEN_DEVICE_FUNC constexpr IndexList(FirstType& first, OtherTypes... other) : internal::IndexTuple<FirstType, OtherTypes...>(first, other...) { }\n  EIGEN_DEVICE_FUNC constexpr IndexList() : internal::IndexTuple<FirstType, OtherTypes...>() { }\n\n  EIGEN_DEVICE_FUNC constexpr bool value_known_statically(const Index i) const {\n    return internal::tuple_coeff<internal::array_size<internal::IndexTuple<FirstType, OtherTypes...> >::value-1, Index>::value_known_statically(i, *this);\n  }\n  EIGEN_DEVICE_FUNC constexpr bool all_values_known_statically() const {\n    return internal::tuple_coeff<internal::array_size<internal::IndexTuple<FirstType, OtherTypes...> >::value-1, Index>::values_up_to_known_statically(*this);\n  }\n\n  EIGEN_DEVICE_FUNC constexpr bool values_statically_known_to_increase() const {\n    return internal::tuple_coeff<internal::array_size<internal::IndexTuple<FirstType, OtherTypes...> >::value-1, Index>::values_up_to_statically_known_to_increase(*this);\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstd::ostream& operator<<(std::ostream& os,\n                         const IndexList<FirstType, OtherTypes...>& dims) {\n  os << \"[\";\n  for (size_t i = 0; i < 1 + sizeof...(OtherTypes); ++i) {\n    if (i > 0) os << \", \";\n    os << dims[i];\n  }\n  os << \"]\";\n  return os;\n}\n\ntemplate<typename FirstType, typename... OtherTypes>\nconstexpr IndexList<FirstType, OtherTypes...> make_index_list(FirstType val1, OtherTypes... other_vals) {\n  return IndexList<FirstType, OtherTypes...>(val1, other_vals...);\n}\n\n\ntemplate<typename FirstType, typename... OtherTypes>\nstruct IndexPairList : internal::IndexTuple<FirstType, OtherTypes...> {\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC constexpr IndexPair<Index> operator[] (const Index i) const {\n    return internal::tuple_coeff<internal::array_size<internal::IndexTuple<FirstType, OtherTypes...> >::value-1, IndexPair<Index>>::get(i, *this);\n  }\n  EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC void set(const Index i, const IndexPair<Index> value) {\n    return internal::tuple_coeff<internal::array_size<internal::IndexTuple<FirstType, OtherTypes...>>::value-1, IndexPair<Index> >::set(i, *this, value);\n  }\n\n  EIGEN_DEVICE_FUNC  constexpr IndexPairList(const internal::IndexTuple<FirstType, OtherTypes...>& other) : internal::IndexTuple<FirstType, OtherTypes...>(other) { }\n  EIGEN_DEVICE_FUNC  constexpr IndexPairList() : internal::IndexTuple<FirstType, OtherTypes...>() { }\n\n  EIGEN_DEVICE_FUNC constexpr bool value_known_statically(const Index i) const {\n    return internal::tuple_coeff<internal::array_size<internal::IndexTuple<FirstType, OtherTypes...> >::value-1, Index>::value_known_statically(i, *this);\n  }\n};\n\nnamespace internal {\n\ntemplate<typename FirstType, typename... OtherTypes>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index array_prod(const IndexList<FirstType, OtherTypes...>& sizes) {\n  Index result = 1;\n  EIGEN_UNROLL_LOOP\n  for (size_t i = 0; i < array_size<IndexList<FirstType, OtherTypes...> >::value; ++i) {\n    result *= sizes[i];\n  }\n  return result;\n}\n\ntemplate<typename FirstType, typename... OtherTypes> struct array_size<IndexList<FirstType, OtherTypes...> > {\n  static const size_t value = array_size<IndexTuple<FirstType, OtherTypes...> >::value;\n};\ntemplate<typename FirstType, typename... OtherTypes> struct array_size<const IndexList<FirstType, OtherTypes...> > {\n  static const size_t value = array_size<IndexTuple<FirstType, OtherTypes...> >::value;\n};\n\ntemplate<typename FirstType, typename... OtherTypes> struct array_size<IndexPairList<FirstType, OtherTypes...> > {\n  static const size_t value = std::tuple_size<std::tuple<FirstType, OtherTypes...> >::value;\n};\ntemplate<typename FirstType, typename... OtherTypes> struct array_size<const IndexPairList<FirstType, OtherTypes...> > {\n  static const size_t value = std::tuple_size<std::tuple<FirstType, OtherTypes...> >::value;\n};\n\ntemplate<Index N, typename FirstType, typename... OtherTypes> EIGEN_DEVICE_FUNC constexpr Index array_get(IndexList<FirstType, OtherTypes...>& a) {\n  return IndexTupleExtractor<N, FirstType, OtherTypes...>::get_val(a);\n}\ntemplate<Index N, typename FirstType, typename... OtherTypes> EIGEN_DEVICE_FUNC constexpr Index array_get(const IndexList<FirstType, OtherTypes...>& a) {\n  return IndexTupleExtractor<N, FirstType, OtherTypes...>::get_val(a);\n}\n\ntemplate <typename T>\nstruct index_known_statically_impl {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index) {\n    return false;\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_known_statically_impl<IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i) {\n    return IndexList<FirstType, OtherTypes...>().value_known_statically(i);\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_known_statically_impl<const IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i) {\n    return IndexList<FirstType, OtherTypes...>().value_known_statically(i);\n  }\n};\n\n\ntemplate <typename T>\nstruct all_indices_known_statically_impl {\n  static constexpr bool run() {\n    return false;\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct all_indices_known_statically_impl<IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run() {\n    return IndexList<FirstType, OtherTypes...>().all_values_known_statically();\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct all_indices_known_statically_impl<const IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run() {\n    return IndexList<FirstType, OtherTypes...>().all_values_known_statically();\n  }\n};\n\n\ntemplate <typename T>\nstruct indices_statically_known_to_increase_impl {\n  EIGEN_DEVICE_FUNC static constexpr bool run() {\n    return false;\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\n  struct indices_statically_known_to_increase_impl<IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run() {\n    return Eigen::IndexList<FirstType, OtherTypes...>().values_statically_known_to_increase();\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\n  struct indices_statically_known_to_increase_impl<const IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run() {\n    return Eigen::IndexList<FirstType, OtherTypes...>().values_statically_known_to_increase();\n  }\n};\n\n\ntemplate <typename Tx>\nstruct index_statically_eq_impl {\n  EIGEN_DEVICE_FUNC static constexpr bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_statically_eq_impl<IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexList<FirstType, OtherTypes...>().get(i) == value);\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_statically_eq_impl<const IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexList<FirstType, OtherTypes...>().get(i) == value);\n  }\n};\n\n\ntemplate <typename T>\nstruct index_statically_ne_impl {\n  EIGEN_DEVICE_FUNC static constexpr bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_statically_ne_impl<IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexList<FirstType, OtherTypes...>().get(i) != value);\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_statically_ne_impl<const IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexList<FirstType, OtherTypes...>().get(i) != value);\n  }\n};\n\n\ntemplate <typename T>\nstruct index_statically_gt_impl {\n  EIGEN_DEVICE_FUNC static constexpr bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_statically_gt_impl<IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexList<FirstType, OtherTypes...>().get(i) > value);\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_statically_gt_impl<const IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexList<FirstType, OtherTypes...>().get(i) > value);\n  }\n};\n\n\n\ntemplate <typename T>\nstruct index_statically_lt_impl {\n  EIGEN_DEVICE_FUNC static constexpr bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_statically_lt_impl<IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexList<FirstType, OtherTypes...>().get(i) < value);\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_statically_lt_impl<const IndexList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexList<FirstType, OtherTypes...>().get(i) < value);\n  }\n};\n\n\n\ntemplate <typename Tx>\nstruct index_pair_first_statically_eq_impl {\n  EIGEN_DEVICE_FUNC static constexpr bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_pair_first_statically_eq_impl<IndexPairList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexPairList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexPairList<FirstType, OtherTypes...>().operator[](i).first == value);\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_pair_first_statically_eq_impl<const IndexPairList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexPairList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexPairList<FirstType, OtherTypes...>().operator[](i).first == value);\n  }\n};\n\n\n\ntemplate <typename Tx>\nstruct index_pair_second_statically_eq_impl {\n  EIGEN_DEVICE_FUNC static constexpr bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_pair_second_statically_eq_impl<IndexPairList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexPairList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexPairList<FirstType, OtherTypes...>().operator[](i).second == value);\n  }\n};\n\ntemplate <typename FirstType, typename... OtherTypes>\nstruct index_pair_second_statically_eq_impl<const IndexPairList<FirstType, OtherTypes...> > {\n  EIGEN_DEVICE_FUNC static constexpr bool run(const Index i, const Index value) {\n    return IndexPairList<FirstType, OtherTypes...>().value_known_statically(i) &\n        (IndexPairList<FirstType, OtherTypes...>().operator[](i).second == value);\n  }\n};\n\n\n}  // end namespace internal\n}  // end namespace Eigen\n\n#else\n\nnamespace Eigen {\nnamespace internal {\n\ntemplate <typename T>\nstruct index_known_statically_impl {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(const Index) {\n    return false;\n  }\n};\n\ntemplate <typename T>\nstruct all_indices_known_statically_impl {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run() {\n    return false;\n  }\n};\n\ntemplate <typename T>\nstruct indices_statically_known_to_increase_impl {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run() {\n    return false;\n  }\n};\n\ntemplate <typename T>\nstruct index_statically_eq_impl {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename T>\nstruct index_statically_ne_impl {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename T>\nstruct index_statically_gt_impl {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename T>\nstruct index_statically_lt_impl {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename Tx>\nstruct index_pair_first_statically_eq_impl {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(Index, Index) {\n    return false;\n  }\n};\n\ntemplate <typename Tx>\nstruct index_pair_second_statically_eq_impl {\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool run(Index, Index) {\n    return false;\n  }\n};\n\n\n\n}  // end namespace internal\n}  // end namespace Eigen\n\n#endif\n\n\nnamespace Eigen {\nnamespace internal {\ntemplate <typename T>\nstatic EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_known_statically(Index i) {\n  return index_known_statically_impl<T>::run(i);\n}\n\ntemplate <typename T>\nstatic EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool all_indices_known_statically() {\n  return all_indices_known_statically_impl<T>::run();\n}\n\ntemplate <typename T>\nstatic EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool indices_statically_known_to_increase() {\n  return indices_statically_known_to_increase_impl<T>::run();\n}\n\ntemplate <typename T>\nstatic EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_statically_eq(Index i, Index value) {\n  return index_statically_eq_impl<T>::run(i, value);\n}\n\ntemplate <typename T>\nstatic EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_statically_ne(Index i, Index value) {\n  return index_statically_ne_impl<T>::run(i, value);\n}\n\ntemplate <typename T>\nstatic EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_statically_gt(Index i, Index value) {\n  return index_statically_gt_impl<T>::run(i, value);\n}\n\ntemplate <typename T>\nstatic EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_statically_lt(Index i, Index value) {\n  return index_statically_lt_impl<T>::run(i, value);\n}\n\ntemplate <typename T>\nstatic EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_pair_first_statically_eq(Index i, Index value) {\n  return index_pair_first_statically_eq_impl<T>::run(i, value);\n}\n\ntemplate <typename T>\nstatic EIGEN_DEVICE_FUNC EIGEN_CONSTEXPR bool index_pair_second_statically_eq(Index i, Index value) {\n  return index_pair_second_statically_eq_impl<T>::run(i, value);\n}\n\n}  // end namespace internal\n}  // end namespace Eigen\n\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_INDEX_LIST_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorInflation.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Ke Yang <yangke@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_INFLATION_H\n#define EIGEN_CXX11_TENSOR_TENSOR_INFLATION_H\n\nnamespace Eigen {\n\n/** \\class TensorInflation\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor inflation class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename Strides, typename XprType>\nstruct traits<TensorInflationOp<Strides, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename Strides, typename XprType>\nstruct eval<TensorInflationOp<Strides, XprType>, Eigen::Dense>\n{\n  typedef const TensorInflationOp<Strides, XprType>& type;\n};\n\ntemplate<typename Strides, typename XprType>\nstruct nested<TensorInflationOp<Strides, XprType>, 1, typename eval<TensorInflationOp<Strides, XprType> >::type>\n{\n  typedef TensorInflationOp<Strides, XprType> type;\n};\n\n}  // end namespace internal\n\ntemplate<typename Strides, typename XprType>\nclass TensorInflationOp : public TensorBase<TensorInflationOp<Strides, XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorInflationOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorInflationOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorInflationOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorInflationOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorInflationOp(const XprType& expr, const Strides& strides)\n      : m_xpr(expr), m_strides(strides) {}\n\n    EIGEN_DEVICE_FUNC\n    const Strides& strides() const { return m_strides; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const Strides m_strides;\n};\n\n// Eval as rvalue\ntemplate<typename Strides, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorInflationOp<Strides, ArgType>, Device>\n{\n  typedef TensorInflationOp<Strides, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = /*TensorEvaluator<ArgType, Device>::IsAligned*/ false,\n    PacketAccess = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device), m_strides(op.strides())\n  {\n    m_dimensions = m_impl.dimensions();\n    // Expand each dimension to the inflated dimension.\n    for (int i = 0; i < NumDims; ++i) {\n      m_dimensions[i] = (m_dimensions[i] - 1) * op.strides()[i] + 1;\n    }\n\n    // Remember the strides for fast division.\n    for (int i = 0; i < NumDims; ++i) {\n      m_fastStrides[i] = internal::TensorIntDivisor<Index>(m_strides[i]);\n    }\n\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_outputStrides[0] = 1;\n      m_inputStrides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_outputStrides[i] = m_outputStrides[i-1] * m_dimensions[i-1];\n        m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1];\n      }\n    } else {  // RowMajor\n      m_outputStrides[NumDims-1] = 1;\n      m_inputStrides[NumDims-1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_outputStrides[i] = m_outputStrides[i+1] * m_dimensions[i+1];\n        m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1];\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType /*data*/) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  // Computes the input index given the output index. Returns true if the output\n  // index doesn't fall into a hole.\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool getInputIndex(Index index, Index* inputIndex) const\n  {\n    eigen_assert(index < dimensions().TotalSize());\n    *inputIndex = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx = index / m_outputStrides[i];\n        if (idx != idx / m_fastStrides[i] * m_strides[i]) {\n          return false;\n        }\n        *inputIndex += idx / m_strides[i] * m_inputStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      if (index != index / m_fastStrides[0] * m_strides[0]) {\n        return false;\n      }\n      *inputIndex += index / m_strides[0];\n      return true;\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx = index / m_outputStrides[i];\n        if (idx != idx / m_fastStrides[i] * m_strides[i]) {\n          return false;\n        }\n        *inputIndex += idx / m_strides[i] * m_inputStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      if (index != index / m_fastStrides[NumDims-1] * m_strides[NumDims-1]) {\n        return false;\n      }\n      *inputIndex += index / m_strides[NumDims - 1];\n    }\n    return true;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    Index inputIndex = 0;\n    if (getInputIndex(index, &inputIndex)) {\n     return m_impl.coeff(inputIndex);\n    } else {\n     return Scalar(0);\n    }\n  }\n\n  // TODO(yangke): optimize this function so that we can detect and produce\n  // all-zero packets\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < PacketSize; ++i) {\n      values[i] = coeff(index+i);\n    }\n    PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n    return rslt;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    const double compute_cost = NumDims * (3 * TensorOpCost::DivCost<Index>() +\n                                           3 * TensorOpCost::MulCost<Index>() +\n                                           2 * TensorOpCost::AddCost<Index>());\n    const double input_size = m_impl.dimensions().TotalSize();\n    const double output_size = m_dimensions.TotalSize();\n    if (output_size == 0)\n      return TensorOpCost();\n    return m_impl.costPerCoeff(vectorized) +\n           TensorOpCost(sizeof(CoeffReturnType) * input_size / output_size, 0,\n                        compute_cost, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n\n protected:\n  Dimensions m_dimensions;\n  array<Index, NumDims> m_outputStrides;\n  array<Index, NumDims> m_inputStrides;\n  TensorEvaluator<ArgType, Device> m_impl;\n  const Strides m_strides;\n  array<internal::TensorIntDivisor<Index>, NumDims> m_fastStrides;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_INFLATION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorInitializer.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_INITIALIZER_H\n#define EIGEN_CXX11_TENSOR_TENSOR_INITIALIZER_H\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n\n#include <initializer_list>\n\nnamespace Eigen {\n\n/** \\class TensorInitializer\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Helper template to initialize Tensors from std::initializer_lists.\n  */\nnamespace internal {\n\ntemplate <typename Derived, int N>\nstruct Initializer {\n  typedef std::initializer_list<\n    typename Initializer<Derived, N - 1>::InitList> InitList;\n\n  static void run(TensorEvaluator<Derived, DefaultDevice>& tensor,\n                  Eigen::array<typename traits<Derived>::Index, traits<Derived>::NumDimensions>* indices,\n                  const InitList& vals) {\n    int i = 0;\n    for (const auto& v : vals) {\n      (*indices)[traits<Derived>::NumDimensions - N] = i++;\n      Initializer<Derived, N - 1>::run(tensor, indices, v);\n    }\n  }\n};\n\ntemplate <typename Derived>\nstruct Initializer<Derived, 1> {\n  typedef std::initializer_list<typename traits<Derived>::Scalar> InitList;\n\n  static void run(TensorEvaluator<Derived, DefaultDevice>& tensor,\n                  Eigen::array<typename traits<Derived>::Index, traits<Derived>::NumDimensions>* indices,\n                  const InitList& vals) {\n    int i = 0;\n    // There is likely a faster way to do that than iterating.\n    for (const auto& v : vals) {\n      (*indices)[traits<Derived>::NumDimensions - 1] = i++;\n      tensor.coeffRef(*indices) = v;\n    }\n  }\n};\n\ntemplate <typename Derived>\nstruct Initializer<Derived, 0> {\n  typedef typename traits<Derived>::Scalar InitList;\n\n  static void run(TensorEvaluator<Derived, DefaultDevice>& tensor,\n                  Eigen::array<typename traits<Derived>::Index, traits<Derived>::NumDimensions>*,\n                  const InitList& v) {\n    tensor.coeffRef(0) = v;\n  }\n};\n\n\ntemplate <typename Derived, int N>\nvoid initialize_tensor(TensorEvaluator<Derived, DefaultDevice>& tensor,\n                       const typename Initializer<Derived, traits<Derived>::NumDimensions>::InitList& vals) {\n  Eigen::array<typename traits<Derived>::Index, traits<Derived>::NumDimensions> indices;\n  Initializer<Derived, traits<Derived>::NumDimensions>::run(tensor, &indices, vals);\n}\n\n}  // namespace internal\n}  // namespace Eigen\n\n#endif  // EIGEN_HAS_VARIADIC_TEMPLATES\n\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_INITIALIZER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorIntDiv.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_INTDIV_H\n#define EIGEN_CXX11_TENSOR_TENSOR_INTDIV_H\n\n\nnamespace Eigen {\n\n/** \\internal\n  *\n  * \\class TensorIntDiv\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Fast integer division by a constant.\n  *\n  * See the paper from Granlund and Montgomery for explanation.\n  *   (at https://doi.org/10.1145/773473.178249)\n  *\n  * \\sa Tensor\n  */\n\nnamespace internal {\n\nnamespace {\n\n  // Note: result is undefined if val == 0\n  template <typename T>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  typename internal::enable_if<sizeof(T)==4,int>::type count_leading_zeros(const T val)\n  {\n#ifdef EIGEN_GPU_COMPILE_PHASE\n    return __clz(val);\n#elif defined(SYCL_DEVICE_ONLY)\n    return cl::sycl::clz(val);\n#elif EIGEN_COMP_MSVC\n    unsigned long index;\n    _BitScanReverse(&index, val);\n    return 31 - index;\n#else\n    EIGEN_STATIC_ASSERT(sizeof(unsigned long long) == 8, YOU_MADE_A_PROGRAMMING_MISTAKE);\n    return __builtin_clz(static_cast<uint32_t>(val));\n#endif\n  }\n\n  template <typename T>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  typename internal::enable_if<sizeof(T)==8,int>::type count_leading_zeros(const T val)\n  {\n#ifdef EIGEN_GPU_COMPILE_PHASE\n    return __clzll(val);\n#elif defined(SYCL_DEVICE_ONLY)\n    return static_cast<int>(cl::sycl::clz(val));\n#elif EIGEN_COMP_MSVC && EIGEN_ARCH_x86_64\n    unsigned long index;\n    _BitScanReverse64(&index, val);\n    return 63 - index;\n#elif EIGEN_COMP_MSVC\n    // MSVC's _BitScanReverse64 is not available for 32bits builds.\n    unsigned int lo = (unsigned int)(val&0xffffffff);\n    unsigned int hi = (unsigned int)((val>>32)&0xffffffff);\n    int n;\n    if(hi==0)\n      n = 32 + count_leading_zeros<unsigned int>(lo);\n    else\n      n = count_leading_zeros<unsigned int>(hi);\n    return n;\n#else\n    EIGEN_STATIC_ASSERT(sizeof(unsigned long long) == 8, YOU_MADE_A_PROGRAMMING_MISTAKE);\n    return __builtin_clzll(static_cast<uint64_t>(val));\n#endif\n  }\n\n  template <typename T>\n  struct UnsignedTraits {\n    typedef typename conditional<sizeof(T) == 8, uint64_t, uint32_t>::type type;\n  };\n\n  template <typename T>\n  struct DividerTraits {\n    typedef typename UnsignedTraits<T>::type type;\n    static const int N = sizeof(T) * 8;\n  };\n\n  template <typename T>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE uint32_t muluh(const uint32_t a, const T b) {\n#if defined(EIGEN_GPU_COMPILE_PHASE)\n    return __umulhi(a, b);\n#elif defined(SYCL_DEVICE_ONLY)\n    return cl::sycl::mul_hi(a, static_cast<uint32_t>(b));\n#else\n    return (static_cast<uint64_t>(a) * b) >> 32;\n#endif\n  }\n\n  template <typename T>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE uint64_t muluh(const uint64_t a, const T b) {\n#if defined(EIGEN_GPU_COMPILE_PHASE)\n    return __umul64hi(a, b);\n#elif defined(SYCL_DEVICE_ONLY)\n    return cl::sycl::mul_hi(a, static_cast<uint64_t>(b));\n#elif EIGEN_HAS_BUILTIN_INT128\n    __uint128_t v = static_cast<__uint128_t>(a) * static_cast<__uint128_t>(b);\n    return static_cast<uint64_t>(v >> 64);\n#else\n    return (TensorUInt128<static_val<0>, uint64_t>(a) * TensorUInt128<static_val<0>, uint64_t>(b)).upper();\n#endif\n  }\n\n  template <int N, typename T>\n  struct DividerHelper {\n    static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE uint32_t computeMultiplier(const int log_div, const T divider) {\n      EIGEN_STATIC_ASSERT(N == 32, YOU_MADE_A_PROGRAMMING_MISTAKE);\n      return static_cast<uint32_t>((static_cast<uint64_t>(1) << (N+log_div)) / divider - (static_cast<uint64_t>(1) << N) + 1);\n    }\n  };\n\n  template <typename T>\n  struct DividerHelper<64, T> {\n    static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE uint64_t computeMultiplier(const int log_div, const T divider) {\n#if EIGEN_HAS_BUILTIN_INT128 && !defined(EIGEN_GPU_COMPILE_PHASE) && !defined(SYCL_DEVICE_ONLY)\n      return static_cast<uint64_t>((static_cast<__uint128_t>(1) << (64+log_div)) / static_cast<__uint128_t>(divider) - (static_cast<__uint128_t>(1) << 64) + 1);\n#else\n      const uint64_t shift = 1ULL << log_div;\n      TensorUInt128<uint64_t, uint64_t> result = TensorUInt128<uint64_t, static_val<0> >(shift, 0) / TensorUInt128<static_val<0>, uint64_t>(divider)\n                                               - TensorUInt128<static_val<1>, static_val<0> >(1, 0)\n                                               + TensorUInt128<static_val<0>, static_val<1> >(1);\n      return static_cast<uint64_t>(result);\n#endif\n    }\n  };\n}\n\n\ntemplate <typename T, bool div_gt_one = false>\nstruct TensorIntDivisor {\n public:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorIntDivisor() {\n    multiplier = 0;\n    shift1 = 0;\n    shift2 = 0;\n  }\n\n  // Must have 0 < divider < 2^31. This is relaxed to\n  // 0 < divider < 2^63 when using 64-bit indices on platforms that support\n  // the __uint128_t type.\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorIntDivisor(const T divider) {\n    const int N = DividerTraits<T>::N;\n    eigen_assert(static_cast<typename UnsignedTraits<T>::type>(divider) < NumTraits<UnsignedType>::highest()/2);\n    eigen_assert(divider > 0);\n\n    // fast ln2\n    const int leading_zeros = count_leading_zeros(static_cast<UnsignedType>(divider));\n    int log_div = N - leading_zeros;\n    // if divider is a power of two then log_div is 1 more than it should be.\n    if ((static_cast<typename UnsignedTraits<T>::type>(1) << (log_div-1)) == static_cast<typename UnsignedTraits<T>::type>(divider))\n      log_div--;\n\n    multiplier = DividerHelper<N, T>::computeMultiplier(log_div, divider);\n    shift1 = log_div > 1 ? 1 : log_div;\n    shift2 = log_div > 1 ? log_div-1 : 0;\n  }\n\n  // Must have 0 <= numerator. On platforms that don't support the __uint128_t\n  // type numerator should also be less than 2^32-1.\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T divide(const T numerator) const {\n    eigen_assert(static_cast<typename UnsignedTraits<T>::type>(numerator) < NumTraits<UnsignedType>::highest()/2);\n    //eigen_assert(numerator >= 0); // this is implicitly asserted by the line above\n\n    UnsignedType t1 = muluh(multiplier, numerator);\n    UnsignedType t = (static_cast<UnsignedType>(numerator) - t1) >> shift1;\n    return (t1 + t) >> shift2;\n  }\n\n private:\n  typedef typename DividerTraits<T>::type UnsignedType;\n  UnsignedType multiplier;\n  int32_t shift1;\n  int32_t shift2;\n};\n\n\n// Optimized version for signed 32 bit integers.\n// Derived from Hacker's Delight.\n// Only works for divisors strictly greater than one\ntemplate <>\nclass TensorIntDivisor<int32_t, true> {\n public:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorIntDivisor() {\n    magic = 0;\n    shift = 0;\n  }\n  // Must have 2 <= divider\n  EIGEN_DEVICE_FUNC TensorIntDivisor(int32_t divider)  {\n    eigen_assert(divider >= 2);\n    calcMagic(divider);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE int divide(const int32_t n) const {\n#ifdef EIGEN_GPU_COMPILE_PHASE\n    return (__umulhi(magic, n) >> shift);\n#elif defined(SYCL_DEVICE_ONLY)\n    return (cl::sycl::mul_hi(magic, static_cast<uint32_t>(n)) >> shift);\n#else\n    uint64_t v = static_cast<uint64_t>(magic) * static_cast<uint64_t>(n);\n    return (static_cast<uint32_t>(v >> 32) >> shift);\n#endif\n  }\n\nprivate:\n  // Compute the magic numbers. See Hacker's Delight section 10 for an in\n  // depth explanation.\n  EIGEN_DEVICE_FUNC void calcMagic(int32_t d) {\n   const unsigned two31 = 0x80000000;     // 2**31.\n   unsigned ad = d;\n   unsigned t = two31 + (ad >> 31);\n   unsigned anc = t - 1 - t%ad;     // Absolute value of nc.\n   int p = 31;                      // Init. p.\n   unsigned q1 = two31/anc;         // Init. q1 = 2**p/|nc|.\n   unsigned r1 = two31 - q1*anc;    // Init. r1 = rem(2**p, |nc|).\n   unsigned q2 = two31/ad;          // Init. q2 = 2**p/|d|.\n   unsigned r2 = two31 - q2*ad;     // Init. r2 = rem(2**p, |d|).\n   unsigned delta = 0;\n   do {\n      p = p + 1;\n      q1 = 2*q1;           // Update q1 = 2**p/|nc|.\n      r1 = 2*r1;           // Update r1 = rem(2**p, |nc|).\n      if (r1 >= anc) {     // (Must be an unsigned\n         q1 = q1 + 1;      // comparison here).\n         r1 = r1 - anc;}\n      q2 = 2*q2;           // Update q2 = 2**p/|d|.\n      r2 = 2*r2;           // Update r2 = rem(2**p, |d|).\n      if (r2 >= ad) {      // (Must be an unsigned\n         q2 = q2 + 1;      // comparison here).\n         r2 = r2 - ad;}\n      delta = ad - r2;\n   } while (q1 < delta || (q1 == delta && r1 == 0));\n\n   magic = (unsigned)(q2 + 1);\n   shift = p - 32;\n  }\n\n  uint32_t magic;\n  int32_t shift;\n};\n\n\ntemplate <typename T, bool div_gt_one>\nstatic EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T operator / (const T& numerator, const TensorIntDivisor<T, div_gt_one>& divisor) {\n  return divisor.divide(numerator);\n}\n\n\n} // end namespace internal\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_INTDIV_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorLayoutSwap.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_LAYOUT_SWAP_H\n#define EIGEN_CXX11_TENSOR_TENSOR_LAYOUT_SWAP_H\n\nnamespace Eigen {\n\n/** \\class TensorLayoutSwap\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Swap the layout from col-major to row-major, or row-major\n  * to col-major, and invert the order of the dimensions.\n  *\n  * Beware: the dimensions are reversed by this operation. If you want to\n  * preserve the ordering of the dimensions, you need to combine this\n  * operation with a shuffle.\n  *\n  * \\example:\n  * Tensor<float, 2, ColMajor> input(2, 4);\n  * Tensor<float, 2, RowMajor> output = input.swap_layout();\n  * eigen_assert(output.dimension(0) == 4);\n  * eigen_assert(output.dimension(1) == 2);\n  *\n  * array<int, 2> shuffle(1, 0);\n  * output = input.swap_layout().shuffle(shuffle);\n  * eigen_assert(output.dimension(0) == 2);\n  * eigen_assert(output.dimension(1) == 4);\n  *\n  */\nnamespace internal {\ntemplate<typename XprType>\nstruct traits<TensorLayoutSwapOp<XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = traits<XprType>::NumDimensions;\n  static const int Layout = (traits<XprType>::Layout == ColMajor) ? RowMajor : ColMajor;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename XprType>\nstruct eval<TensorLayoutSwapOp<XprType>, Eigen::Dense>\n{\n  typedef const TensorLayoutSwapOp<XprType>& type;\n};\n\ntemplate<typename XprType>\nstruct nested<TensorLayoutSwapOp<XprType>, 1, typename eval<TensorLayoutSwapOp<XprType> >::type>\n{\n  typedef TensorLayoutSwapOp<XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename XprType>\nclass TensorLayoutSwapOp : public TensorBase<TensorLayoutSwapOp<XprType>, WriteAccessors>\n{\n  public:\n    typedef TensorBase<TensorLayoutSwapOp<XprType>, WriteAccessors> Base;\n    typedef typename Eigen::internal::traits<TensorLayoutSwapOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef typename internal::remove_const<typename XprType::CoeffReturnType>::type CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorLayoutSwapOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorLayoutSwapOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorLayoutSwapOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorLayoutSwapOp(const XprType& expr)\n        : m_xpr(expr) {}\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(TensorLayoutSwapOp)\n  protected:\n    typename XprType::Nested m_xpr;\n};\n\n\n// Eval as rvalue\ntemplate<typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorLayoutSwapOp<ArgType>, Device>\n{\n  typedef TensorLayoutSwapOp<ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n\n  enum {\n    IsAligned = TensorEvaluator<ArgType, Device>::IsAligned,\n    PacketAccess = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess = false,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout = (static_cast<int>(TensorEvaluator<ArgType, Device>::Layout) == static_cast<int>(ColMajor)) ? RowMajor : ColMajor,\n    CoordAccess = false,  // to be implemented\n    RawAccess = TensorEvaluator<ArgType, Device>::RawAccess\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device)\n  {\n    for(int i = 0; i < NumDims; ++i) {\n      m_dimensions[i] = m_impl.dimensions()[NumDims-1-i];\n    }\n  }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    return m_impl.evalSubExprsIfNeeded(data);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    return m_impl.coeff(index);\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    return m_impl.template packet<LoadMode>(index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    return m_impl.costPerCoeff(vectorized);\n  }\n\n  EIGEN_DEVICE_FUNC typename Storage::Type data() const {\n    return constCast(m_impl.data());\n  }\n\n  const TensorEvaluator<ArgType, Device>& impl() const { return m_impl; }\n\n protected:\n  TensorEvaluator<ArgType, Device> m_impl;\n  Dimensions m_dimensions;\n};\n\n\n// Eval as lvalue\ntemplate<typename ArgType, typename Device>\n  struct TensorEvaluator<TensorLayoutSwapOp<ArgType>, Device>\n  : public TensorEvaluator<const TensorLayoutSwapOp<ArgType>, Device>\n{\n  typedef TensorEvaluator<const TensorLayoutSwapOp<ArgType>, Device> Base;\n  typedef TensorLayoutSwapOp<ArgType> XprType;\n\n  enum {\n    IsAligned = TensorEvaluator<ArgType, Device>::IsAligned,\n    PacketAccess = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess = false,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout = (static_cast<int>(TensorEvaluator<ArgType, Device>::Layout) == static_cast<int>(ColMajor)) ? RowMajor : ColMajor,\n    CoordAccess = false  // to be implemented\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n    : Base(op, device)\n  { }\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index)\n  {\n    return this->m_impl.coeffRef(index);\n  }\n  template <int StoreMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void writePacket(Index index, const PacketReturnType& x)\n  {\n    this->m_impl.template writePacket<StoreMode>(index, x);\n  }\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_LAYOUT_SWAP_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMacros.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_META_MACROS_H\n#define EIGEN_CXX11_TENSOR_TENSOR_META_MACROS_H\n\n\n/** use this macro in sfinae selection in templated functions\n *\n *   template<typename T,\n *            typename std::enable_if< isBanana<T>::value , int >::type = 0\n *   >\n *   void foo(){}\n *\n *   becomes =>\n *\n *   template<typename TopoType,\n *           SFINAE_ENABLE_IF( isBanana<T>::value )\n *   >\n *   void foo(){}\n */\n\n// SFINAE requires variadic templates\n#if !defined(EIGEN_GPUCC)\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  // SFINAE doesn't work for gcc <= 4.7\n  #ifdef EIGEN_COMP_GNUC\n    #if EIGEN_GNUC_AT_LEAST(4,8)\n      #define EIGEN_HAS_SFINAE\n    #endif\n  #else\n    #define EIGEN_HAS_SFINAE\n  #endif\n#endif\n#endif\n\n#define EIGEN_SFINAE_ENABLE_IF( __condition__ ) \\\n    typename internal::enable_if< ( __condition__ ) , int >::type = 0\n\n// Define a macro to use a reference on the host but a value on the device\n#if defined(SYCL_DEVICE_ONLY)\n  #define EIGEN_DEVICE_REF\n#else\n  #define EIGEN_DEVICE_REF &\n#endif\n\n// Define a macro for catching SYCL exceptions if exceptions are enabled\n#define EIGEN_SYCL_TRY_CATCH(X) \\\n  do { \\\n    EIGEN_TRY {X;} \\\n    EIGEN_CATCH(const cl::sycl::exception& e) { \\\n      EIGEN_THROW_X(std::runtime_error(\"SYCL exception at \" + \\\n                                       std::string(__FILE__) + \":\" + \\\n                                       std::to_string(__LINE__) + \"\\n\" + \\\n                                       e.what())); \\\n    } \\\n  } while (false)\n\n// Define a macro if local memory flags are unset or one of them is set\n// Setting both flags is the same as unsetting them\n#if (!defined(EIGEN_SYCL_LOCAL_MEM) && !defined(EIGEN_SYCL_NO_LOCAL_MEM)) || \\\n     (defined(EIGEN_SYCL_LOCAL_MEM) &&  defined(EIGEN_SYCL_NO_LOCAL_MEM))\n  #define EIGEN_SYCL_LOCAL_MEM_UNSET_OR_ON 1\n  #define EIGEN_SYCL_LOCAL_MEM_UNSET_OR_OFF 1\n#elif defined(EIGEN_SYCL_LOCAL_MEM) && !defined(EIGEN_SYCL_NO_LOCAL_MEM)\n  #define EIGEN_SYCL_LOCAL_MEM_UNSET_OR_ON 1\n#elif !defined(EIGEN_SYCL_LOCAL_MEM) && defined(EIGEN_SYCL_NO_LOCAL_MEM)\n  #define EIGEN_SYCL_LOCAL_MEM_UNSET_OR_OFF 1\n#endif\n\n#if EIGEN_COMP_CLANG // workaround clang bug (see http://forum.kde.org/viewtopic.php?f=74&t=102653)\n  #define EIGEN_TENSOR_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Derived) \\\n    using Base::operator =; \\\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const Derived& other) { Base::operator=(other); return *this; } \\\n    template <typename OtherDerived> \\\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Derived& operator=(const OtherDerived& other) { Base::operator=(other); return *this; }\n#else\n  #define EIGEN_TENSOR_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Derived) \\\n    EIGEN_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Derived)\n#endif\n\n/** \\internal\n * \\brief Macro to manually inherit assignment operators.\n * This is necessary, because the implicitly defined assignment operator gets deleted when a custom operator= is defined.\n * This also inherits template<OtherDerived> operator=(const OtherDerived&) assignments.\n * With C++11 or later this also default-implements the copy-constructor\n */\n#define EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(Derived)  \\\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_EQUAL_OPERATOR(Derived) \\\n    EIGEN_DEFAULT_COPY_CONSTRUCTOR(Derived)\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMap.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_MAP_H\n#define EIGEN_CXX11_TENSOR_TENSOR_MAP_H\n\nnamespace Eigen {\n\n// FIXME use proper doxygen documentation (e.g. \\tparam MakePointer_)\n\n/** \\class TensorMap\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief A tensor expression mapping an existing array of data.\n  *\n  */\n/// `template <class> class MakePointer_` is added to convert the host pointer to the device pointer.\n/// It is added due to the fact that for our device compiler `T*` is not allowed.\n/// If we wanted to use the same Evaluator functions we have to convert that type to our pointer `T`.\n/// This is done through our `MakePointer_` class. By default the Type in the `MakePointer_<T>` is `T*` .\n/// Therefore, by adding the default value, we managed to convert the type and it does not break any\n/// existing code as its default value is `T*`.\ntemplate<typename PlainObjectType, int Options_, template <class> class MakePointer_> class TensorMap : public TensorBase<TensorMap<PlainObjectType, Options_, MakePointer_> >\n{\n  public:\n    typedef TensorMap<PlainObjectType, Options_, MakePointer_> Self;\n    typedef TensorBase<TensorMap<PlainObjectType, Options_, MakePointer_> > Base;\n  #ifdef EIGEN_USE_SYCL\n    typedef  typename Eigen::internal::remove_reference<typename Eigen::internal::nested<Self>::type>::type Nested;\n  #else\n     typedef typename Eigen::internal::nested<Self>::type Nested;\n  #endif\n   typedef typename internal::traits<PlainObjectType>::StorageKind StorageKind;\n    typedef typename internal::traits<PlainObjectType>::Index Index;\n    typedef typename internal::traits<PlainObjectType>::Scalar Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef typename PlainObjectType::Base::CoeffReturnType CoeffReturnType;\n\n    typedef typename MakePointer_<Scalar>::Type PointerType;\n    typedef typename MakePointer_<Scalar>::ConstType PointerConstType;\n\n    // WARN: PointerType still can be a pointer to const (const Scalar*), for\n    // example in TensorMap<Tensor<const Scalar, ...>> expression. This type of\n    // expression should be illegal, but adding this restriction is not possible\n    // in practice (see https://bitbucket.org/eigen/eigen/pull-requests/488).\n    typedef typename internal::conditional<\n        bool(internal::is_lvalue<PlainObjectType>::value),\n        PointerType,      // use simple pointer in lvalue expressions\n        PointerConstType  // use const pointer in rvalue expressions\n        >::type StoragePointerType;\n\n    // If TensorMap was constructed over rvalue expression (e.g. const Tensor),\n    // we should return a reference to const from operator() (and others), even\n    // if TensorMap itself is not const.\n    typedef typename internal::conditional<\n        bool(internal::is_lvalue<PlainObjectType>::value),\n        Scalar&,\n        const Scalar&\n        >::type StorageRefType;\n\n    static const int Options = Options_;\n\n    static const Index NumIndices = PlainObjectType::NumIndices;\n    typedef typename PlainObjectType::Dimensions Dimensions;\n\n    enum {\n      IsAligned = ((int(Options_)&Aligned)==Aligned),\n      Layout = PlainObjectType::Layout,\n      CoordAccess = true,\n      RawAccess = true\n    };\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorMap(StoragePointerType dataPtr) : m_data(dataPtr), m_dimensions() {\n      // The number of dimensions used to construct a tensor must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT((0 == NumIndices || NumIndices == Dynamic), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorMap(StoragePointerType dataPtr, Index firstDimension, IndexTypes... otherDimensions) : m_data(dataPtr), m_dimensions(firstDimension, otherDimensions...) {\n      // The number of dimensions used to construct a tensor must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT((sizeof...(otherDimensions) + 1 == NumIndices || NumIndices == Dynamic), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n#else\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorMap(StoragePointerType dataPtr, Index firstDimension) : m_data(dataPtr), m_dimensions(firstDimension) {\n      // The number of dimensions used to construct a tensor must be equal to the rank of the tensor.\n      EIGEN_STATIC_ASSERT((1 == NumIndices || NumIndices == Dynamic), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorMap(StoragePointerType dataPtr, Index dim1, Index dim2) : m_data(dataPtr), m_dimensions(dim1, dim2) {\n      EIGEN_STATIC_ASSERT(2 == NumIndices || NumIndices == Dynamic, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorMap(StoragePointerType dataPtr, Index dim1, Index dim2, Index dim3) : m_data(dataPtr), m_dimensions(dim1, dim2, dim3) {\n      EIGEN_STATIC_ASSERT(3 == NumIndices || NumIndices == Dynamic, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorMap(StoragePointerType dataPtr, Index dim1, Index dim2, Index dim3, Index dim4) : m_data(dataPtr), m_dimensions(dim1, dim2, dim3, dim4) {\n      EIGEN_STATIC_ASSERT(4 == NumIndices || NumIndices == Dynamic, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE TensorMap(StoragePointerType dataPtr, Index dim1, Index dim2, Index dim3, Index dim4, Index dim5) : m_data(dataPtr), m_dimensions(dim1, dim2, dim3, dim4, dim5) {\n      EIGEN_STATIC_ASSERT(5 == NumIndices || NumIndices == Dynamic, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    }\n#endif\n\n   EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorMap(StoragePointerType dataPtr, const array<Index, NumIndices>& dimensions)\n      : m_data(dataPtr), m_dimensions(dimensions)\n    { }\n\n    template <typename Dimensions>\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorMap(StoragePointerType dataPtr, const Dimensions& dimensions)\n      : m_data(dataPtr), m_dimensions(dimensions)\n    { }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorMap(PlainObjectType& tensor)\n      : m_data(tensor.data()), m_dimensions(tensor.dimensions())\n    { }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Index rank() const { return m_dimensions.rank(); }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Index dimension(Index n) const { return m_dimensions[n]; }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Index size() const { return m_dimensions.TotalSize(); }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StoragePointerType data() { return m_data; }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StoragePointerType data() const { return m_data; }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(const array<Index, NumIndices>& indices) const\n    {\n      //      eigen_assert(checkIndexRange(indices));\n      if (PlainObjectType::Options&RowMajor) {\n        const Index index = m_dimensions.IndexOfRowMajor(indices);\n        return m_data[index];\n      } else {\n        const Index index = m_dimensions.IndexOfColMajor(indices);\n        return m_data[index];\n      }\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()() const\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return m_data[0];\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index index) const\n    {\n      eigen_internal_assert(index >= 0 && index < size());\n      return m_data[index];\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index firstIndex, Index secondIndex, IndexTypes... otherIndices) const\n    {\n      EIGEN_STATIC_ASSERT(sizeof...(otherIndices) + 2 == NumIndices, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      eigen_assert(internal::all((Eigen::NumTraits<Index>::highest() >= otherIndices)...));\n      if (PlainObjectType::Options&RowMajor) {\n        const Index index = m_dimensions.IndexOfRowMajor(array<Index, NumIndices>{{firstIndex, secondIndex, otherIndices...}});\n        return m_data[index];\n      } else {\n        const Index index = m_dimensions.IndexOfColMajor(array<Index, NumIndices>{{firstIndex, secondIndex, otherIndices...}});\n        return m_data[index];\n      }\n    }\n#else\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index i0, Index i1) const\n    {\n      if (PlainObjectType::Options&RowMajor) {\n        const Index index = i1 + i0 * m_dimensions[1];\n        return m_data[index];\n      } else {\n        const Index index = i0 + i1 * m_dimensions[0];\n        return m_data[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index i0, Index i1, Index i2) const\n    {\n      if (PlainObjectType::Options&RowMajor) {\n         const Index index = i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0);\n         return m_data[index];\n      } else {\n         const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * i2);\n        return m_data[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index i0, Index i1, Index i2, Index i3) const\n    {\n      if (PlainObjectType::Options&RowMajor) {\n        const Index index = i3 + m_dimensions[3] * (i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0));\n        return m_data[index];\n      } else {\n        const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * (i2 + m_dimensions[2] * i3));\n        return m_data[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index i0, Index i1, Index i2, Index i3, Index i4) const\n    {\n      if (PlainObjectType::Options&RowMajor) {\n        const Index index = i4 + m_dimensions[4] * (i3 + m_dimensions[3] * (i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0)));\n        return m_data[index];\n      } else {\n        const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * (i2 + m_dimensions[2] * (i3 + m_dimensions[3] * i4)));\n        return m_data[index];\n      }\n    }\n#endif\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(const array<Index, NumIndices>& indices)\n    {\n      //      eigen_assert(checkIndexRange(indices));\n      if (PlainObjectType::Options&RowMajor) {\n        const Index index = m_dimensions.IndexOfRowMajor(indices);\n        return m_data[index];\n      } else {\n        const Index index = m_dimensions.IndexOfColMajor(indices);\n        return m_data[index];\n      }\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()()\n    {\n      EIGEN_STATIC_ASSERT(NumIndices == 0, YOU_MADE_A_PROGRAMMING_MISTAKE)\n      return m_data[0];\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index index)\n    {\n      eigen_internal_assert(index >= 0 && index < size());\n      return m_data[index];\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index firstIndex, Index secondIndex, IndexTypes... otherIndices)\n    {\n      static_assert(sizeof...(otherIndices) + 2 == NumIndices || NumIndices == Dynamic, \"Number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\");\n       eigen_assert(internal::all((Eigen::NumTraits<Index>::highest() >= otherIndices)...));\n      const std::size_t NumDims = sizeof...(otherIndices) + 2;\n      if (PlainObjectType::Options&RowMajor) {\n        const Index index = m_dimensions.IndexOfRowMajor(array<Index, NumDims>{{firstIndex, secondIndex, otherIndices...}});\n        return m_data[index];\n      } else {\n        const Index index = m_dimensions.IndexOfColMajor(array<Index, NumDims>{{firstIndex, secondIndex, otherIndices...}});\n        return m_data[index];\n      }\n    }\n#else\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index i0, Index i1)\n    {\n       if (PlainObjectType::Options&RowMajor) {\n         const Index index = i1 + i0 * m_dimensions[1];\n        return m_data[index];\n      } else {\n        const Index index = i0 + i1 * m_dimensions[0];\n        return m_data[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index i0, Index i1, Index i2)\n    {\n       if (PlainObjectType::Options&RowMajor) {\n         const Index index = i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0);\n        return m_data[index];\n      } else {\n         const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * i2);\n        return m_data[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index i0, Index i1, Index i2, Index i3)\n    {\n      if (PlainObjectType::Options&RowMajor) {\n        const Index index = i3 + m_dimensions[3] * (i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0));\n        return m_data[index];\n      } else {\n        const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * (i2 + m_dimensions[2] * i3));\n        return m_data[index];\n      }\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE StorageRefType operator()(Index i0, Index i1, Index i2, Index i3, Index i4)\n    {\n      if (PlainObjectType::Options&RowMajor) {\n        const Index index = i4 + m_dimensions[4] * (i3 + m_dimensions[3] * (i2 + m_dimensions[2] * (i1 + m_dimensions[1] * i0)));\n        return m_data[index];\n      } else {\n        const Index index = i0 + m_dimensions[0] * (i1 + m_dimensions[1] * (i2 + m_dimensions[2] * (i3 + m_dimensions[3] * i4)));\n        return m_data[index];\n      }\n    }\n#endif\n\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(TensorMap)\n\n  private:\n    StoragePointerType m_data;\n    Dimensions m_dimensions;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_MAP_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMeta.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_META_H\n#define EIGEN_CXX11_TENSOR_TENSOR_META_H\n\nnamespace Eigen {\n\ntemplate<bool cond> struct Cond {};\n\ntemplate<typename T1, typename T2> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nconst T1& choose(Cond<true>, const T1& first, const T2&) {\n  return first;\n}\n\ntemplate<typename T1, typename T2> EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nconst T2& choose(Cond<false>, const T1&, const T2& second) {\n  return second;\n}\n\n\ntemplate <typename T, typename X, typename Y>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nT divup(const X x, const Y y) {\n  return static_cast<T>((x + y - 1) / y);\n}\n\ntemplate <typename T>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nT divup(const T x, const T y) {\n  return static_cast<T>((x + y - 1) / y);\n}\n\ntemplate <size_t n> struct max_n_1 {\n  static const size_t size = n;\n};\ntemplate <> struct max_n_1<0> {\n  static const size_t size = 1;\n};\n\n\n// Default packet types\ntemplate <typename Scalar, typename Device>\nstruct PacketType : internal::packet_traits<Scalar> {\n  typedef typename internal::packet_traits<Scalar>::type type;\n};\n\n// For CUDA packet types when using a GpuDevice\n#if defined(EIGEN_USE_GPU) && defined(EIGEN_HAS_GPU_FP16)\n\ntypedef ulonglong2 Packet4h2;\ntemplate<>\nstruct PacketType<half, GpuDevice> {\n  typedef Packet4h2 type;\n  static const int size = 8;\n  enum {\n    HasAdd    = 1,\n    HasSub    = 1,\n    HasMul    = 1,\n    HasNegate = 1,\n    HasAbs    = 1,\n    HasArg    = 0,\n    HasAbs2   = 0,\n    HasMin    = 1,\n    HasMax    = 1,\n    HasConj   = 0,\n    HasSetLinear = 0,\n    HasBlend  = 0,\n\n    HasDiv    = 1,\n    HasSqrt   = 1,\n    HasRsqrt  = 1,\n    HasExp    = 1,\n    HasExpm1  = 0,\n    HasLog    = 1,\n    HasLog1p  = 0,\n    HasLog10  = 0,\n    HasPow    = 1,\n  };\n};\n#endif\n\n#if defined(EIGEN_USE_SYCL)\n\nnamespace TensorSycl {\nnamespace internal {\n\ntemplate <typename Index, Index A, Index B> struct PlusOp {\n  static constexpr Index Value = A + B;\n};\n\ntemplate <typename Index, Index A, Index B> struct DivOp {\n  static constexpr Index Value = A / B;\n};\n\ntemplate <typename Index, Index start, Index end, Index step,\n          template <class Indx, Indx...> class StepOp>\nstruct static_for {\n  template <typename UnaryOperator>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void loop(UnaryOperator op) {\n    op(start);\n    static_for<Index, StepOp<Index, start, step>::Value, end, step,\n               StepOp>::loop(op);\n  }\n};\ntemplate <typename Index, Index end, Index step,\n          template <class Indx, Indx...> class StepOp>\nstruct static_for<Index, end, end, step, StepOp> {\n  template <typename UnaryOperator>\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void loop(UnaryOperator) {}\n};\n\ntemplate <typename OutScalar, typename Device, bool Vectorizable>\nstruct Vectorise {\n  static const int PacketSize = 1;\n  typedef OutScalar PacketReturnType;\n};\n\ntemplate <typename OutScalar, typename Device>\nstruct Vectorise<OutScalar, Device, true> {\n  static const int PacketSize = Eigen::PacketType<OutScalar, Device>::size;\n  typedef typename Eigen::PacketType<OutScalar, Device>::type PacketReturnType;\n};\n\nstatic EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE Index roundUp(Index x, Index y) {\n  return ((((x) + (y)-1) / (y)) * (y));\n}\n\n} // namespace internal\n} // namespace TensorSycl\n\ntemplate <>\n  struct PacketType<half, SyclDevice> {\n  typedef half type;\n  static const int size = 1;\n  enum {\n    HasAdd    = 0,\n    HasSub    = 0,\n    HasMul    = 0,\n    HasNegate = 0,\n    HasAbs    = 0,\n    HasArg    = 0,\n    HasAbs2   = 0,\n    HasMin    = 0,\n    HasMax    = 0,\n    HasConj   = 0,\n    HasSetLinear = 0,\n    HasBlend  = 0\n  };\n};\ntemplate <typename Scalar>\nstruct PacketType<Scalar, SyclDevice> : internal::default_packet_traits {\n  typedef Scalar type;\n  typedef Scalar half;\n  enum {\n    Vectorizable = 0,\n    size = 1,\n    AlignedOnScalar = 0,\n    HasHalfPacket = 0\n  };\n  enum {\n    HasAdd    = 0,\n    HasSub    = 0,\n    HasMul    = 0,\n    HasNegate = 0,\n    HasAbs    = 0,\n    HasAbs2   = 0,\n    HasMin    = 0,\n    HasMax    = 0,\n    HasConj   = 0,\n    HasSetLinear = 0\n  };\n\n};\n\ntemplate <typename Scalar>\nstruct PacketType<Scalar, const SyclDevice> : PacketType<Scalar, SyclDevice>{};\n\n#ifndef EIGEN_DONT_VECTORIZE_SYCL\n#define PACKET_TYPE(CVQual, Type, val, lengths, DEV)\\\ntemplate<> struct PacketType<CVQual Type, DEV> : internal::sycl_packet_traits<val, lengths> \\\n{\\\n  typedef typename internal::packet_traits<Type>::type type;\\\n  typedef typename internal::packet_traits<Type>::half half;\\\n};\n\n\nPACKET_TYPE(const, float, 1, 4, SyclDevice)\nPACKET_TYPE(, float, 1, 4, SyclDevice)\nPACKET_TYPE(const, float, 1, 4, const SyclDevice)\nPACKET_TYPE(, float, 1, 4, const SyclDevice)\n\nPACKET_TYPE(const, double, 0, 2, SyclDevice)\nPACKET_TYPE(, double, 0, 2, SyclDevice)\nPACKET_TYPE(const, double, 0, 2, const SyclDevice)\nPACKET_TYPE(, double, 0, 2, const SyclDevice)\n#undef PACKET_TYPE\n\ntemplate<> struct PacketType<half, const SyclDevice>: PacketType<half, SyclDevice>{};\ntemplate<> struct PacketType<const half, const SyclDevice>: PacketType<half, SyclDevice>{};\n#endif\n#endif\n\n// Tuple mimics std::pair but works on e.g. nvcc.\ntemplate <typename U, typename V> struct Tuple {\n public:\n  U first;\n  V second;\n\n  typedef U first_type;\n  typedef V second_type;\n\n  EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  Tuple() : first(), second() {}\n\n  EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  Tuple(const U& f, const V& s) : first(f), second(s) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void swap(Tuple& rhs) {\n    using numext::swap;\n    swap(first, rhs.first);\n    swap(second, rhs.second);\n  }\n};\n\ntemplate <typename U, typename V>\nEIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nbool operator==(const Tuple<U, V>& x, const Tuple<U, V>& y) {\n  return (x.first == y.first && x.second == y.second);\n}\n\ntemplate <typename U, typename V>\nEIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nbool operator!=(const Tuple<U, V>& x, const Tuple<U, V>& y) {\n  return !(x == y);\n}\n\n\n// Can't use std::pairs on cuda devices\ntemplate <typename Idx> struct IndexPair {\n  EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE IndexPair() : first(0), second(0) {}\n  EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE IndexPair(Idx f, Idx s) : first(f), second(s) {}\n\n  EIGEN_DEVICE_FUNC void set(IndexPair<Idx> val) {\n    first = val.first;\n    second = val.second;\n  }\n\n  Idx first;\n  Idx second;\n};\n\n\n#ifdef EIGEN_HAS_SFINAE\nnamespace internal {\n\n  template<typename IndexType, typename Index, Index... Is>\n  EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  array<Index, sizeof...(Is)> customIndices2Array(IndexType& idx, numeric_list<Index, Is...>) {\n    return { idx[Is]... };\n  }\n  template<typename IndexType, typename Index>\n  EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  array<Index, 0> customIndices2Array(IndexType&, numeric_list<Index>) {\n    return array<Index, 0>();\n  }\n\n  /** Make an array (for index/dimensions) out of a custom index */\n  template<typename Index, std::size_t NumIndices, typename IndexType>\n  EIGEN_CONSTEXPR EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  array<Index, NumIndices> customIndices2Array(IndexType& idx) {\n    return customIndices2Array(idx, typename gen_numeric_list<Index, NumIndices>::type{});\n  }\n\n\n  template <typename B, typename D>\n  struct is_base_of\n  {\n\n    typedef char (&yes)[1];\n    typedef char (&no)[2];\n\n    template <typename BB, typename DD>\n    struct Host\n    {\n      operator BB*() const;\n      operator DD*();\n    };\n\n    template<typename T>\n    static yes check(D*, T);\n    static no check(B*, int);\n\n    static const bool value = sizeof(check(Host<B,D>(), int())) == sizeof(yes);\n  };\n\n}\n#endif\n\n\n\n}  // namespace Eigen\n\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_META_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorMorphing.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_MORPHING_H\n#define EIGEN_CXX11_TENSOR_TENSOR_MORPHING_H\n\nnamespace Eigen {\n\n/** \\class TensorReshaping\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor reshaping class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename NewDimensions, typename XprType>\nstruct traits<TensorReshapingOp<NewDimensions, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = array_size<NewDimensions>::value;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename NewDimensions, typename XprType>\nstruct eval<TensorReshapingOp<NewDimensions, XprType>, Eigen::Dense>\n{\n  typedef const TensorReshapingOp<NewDimensions, XprType>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename NewDimensions, typename XprType>\nstruct nested<TensorReshapingOp<NewDimensions, XprType>, 1, typename eval<TensorReshapingOp<NewDimensions, XprType> >::type>\n{\n  typedef TensorReshapingOp<NewDimensions, XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename NewDimensions, typename XprType>\nclass TensorReshapingOp : public TensorBase<TensorReshapingOp<NewDimensions, XprType>, WriteAccessors>\n{\n  public:\n  typedef TensorBase<TensorReshapingOp<NewDimensions, XprType>, WriteAccessors> Base;\n  typedef typename Eigen::internal::traits<TensorReshapingOp>::Scalar Scalar;\n  typedef typename internal::remove_const<typename XprType::CoeffReturnType>::type CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorReshapingOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorReshapingOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorReshapingOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorReshapingOp(const XprType& expr, const NewDimensions& dims)\n      : m_xpr(expr), m_dims(dims) {}\n\n    EIGEN_DEVICE_FUNC\n    const NewDimensions& dimensions() const { return m_dims; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(TensorReshapingOp)\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const NewDimensions m_dims;\n};\n\n\n// Eval as rvalue\ntemplate<typename NewDimensions, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorReshapingOp<NewDimensions, ArgType>, Device>\n{\n  typedef TensorReshapingOp<NewDimensions, ArgType> XprType;\n  typedef NewDimensions Dimensions;\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n  typedef StorageMemory<typename internal::remove_const<CoeffReturnType>::type, Device> ConstCastStorage;\n\n  static const int NumOutputDims = internal::array_size<Dimensions>::value;\n  static const int NumInputDims  = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n\n  enum ReshapingKind {\n    // We do not use layout information to determine reshaping kind.\n    // Depending on the layout `N` can be inner or outer dimension.\n    OneByN = 0,  // expr.reshape(1, N)\n    NByOne = 1,  // expr.reshape(N, 1)\n    Runtime = 2  // Reshape dimensions are dynamic (specified at runtime).\n  };\n\n  // clang-format off\n  static const ReshapingKind kind =\n#if defined(EIGEN_HAS_INDEX_LIST)\n        (NumOutputDims == 2 && internal::index_statically_eq<NewDimensions>(/*index=*/0, /*value=*/1)) ? OneByN\n      : (NumOutputDims == 2 && internal::index_statically_eq<NewDimensions>(/*index=*/1, /*value=*/1)) ? NByOne\n      : Runtime;\n#else\n        Runtime;\n#endif\n  // clang-format on\n\n  enum {\n    IsAligned         = TensorEvaluator<ArgType, Device>::IsAligned,\n    PacketAccess      = TensorEvaluator<ArgType, Device>::PacketAccess,\n    // For trivial reshapes with raw access to underlying data we will provide\n    // zero overhead block access.\n    // TODO(ezhulenev): Consider adding block access without raw access?\n    BlockAccess       = TensorEvaluator<ArgType, Device>::RawAccess &&\n                        NumInputDims > 0 && NumOutputDims > 0,\n    PreferBlockAccess = false,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = TensorEvaluator<ArgType, Device>::RawAccess\n  };\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumOutputDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef\n      typename internal::TensorMaterializedBlock<ScalarNoConst, NumOutputDims,\n                                                 Layout, Index>\n          TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device), m_dimensions(op.dimensions())\n  {\n    // The total size of the reshaped tensor must be equal to the total size\n    // of the input tensor.\n    eigen_assert(internal::array_prod(m_impl.dimensions()) == internal::array_prod(op.dimensions()));\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType data, EvalSubExprsCallback done) {\n    m_impl.evalSubExprsIfNeededAsync(data, std::move(done));\n  }\n#endif\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    return m_impl.evalSubExprsIfNeeded(data);\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    return m_impl.coeff(index);\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    return m_impl.template packet<LoadMode>(index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    return m_impl.costPerCoeff(vectorized);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    return internal::TensorBlockResourceRequirements::any();\n  }\n\n  // required in block(OutputTensorBlock* output_block) const\n  // For C++03 compatibility this must be defined outside the method\n  struct BlockIteratorState {\n    Index stride;\n    Index span;\n    Index size;\n    Index count;\n  };\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    eigen_assert(m_impl.data() != NULL);\n    eigen_assert((kind == Runtime) ||\n                 (kind == OneByN && desc.dimensions()[0] == 1) ||\n                 (kind == NByOne && desc.dimensions()[1] == 1));\n\n    if (kind == OneByN || kind == NByOne) {\n      // We can guarantee at compile time that block is just a contiguous slice\n      // of the underlying expression memory buffer.\n      return TensorBlock(internal::TensorBlockKind::kView,\n                           m_impl.data() + desc.offset(), desc.dimensions());\n    } else {\n      // This will do additional runtime checks, and in the end it might be also\n      // a view, or it might be a block materialized in the temporary buffer.\n      return TensorBlock::materialize(m_impl.data(), m_dimensions, desc,\n                                        scratch);\n    }\n  }\n\n  EIGEN_DEVICE_FUNC typename Storage::Type data() const {\n    return constCast(m_impl.data());\n  }\n\n  EIGEN_DEVICE_FUNC const TensorEvaluator<ArgType, Device>& impl() const { return m_impl; }\n\n  #ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n  #endif\n protected:\n  TensorEvaluator<ArgType, Device> m_impl;\n  NewDimensions m_dimensions;\n};\n\n\n// Eval as lvalue\ntemplate<typename NewDimensions, typename ArgType, typename Device>\n  struct TensorEvaluator<TensorReshapingOp<NewDimensions, ArgType>, Device>\n  : public TensorEvaluator<const TensorReshapingOp<NewDimensions, ArgType>, Device>\n\n{\n  typedef TensorEvaluator<const TensorReshapingOp<NewDimensions, ArgType>, Device> Base;\n  typedef TensorReshapingOp<NewDimensions, ArgType> XprType;\n  typedef NewDimensions Dimensions;\n\n  enum {\n    IsAligned         = TensorEvaluator<ArgType, Device>::IsAligned,\n    PacketAccess      = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess       = TensorEvaluator<ArgType, Device>::RawAccess,\n    PreferBlockAccess = false,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = TensorEvaluator<ArgType, Device>::RawAccess\n  };\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n    : Base(op, device)\n  { }\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<TensorEvaluator::NumOutputDims, Index>\n      TensorBlockDesc;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index)\n  {\n    return this->m_impl.coeffRef(index);\n  }\n\n  template <int StoreMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void writePacket(Index index, const PacketReturnType& x)\n  {\n    this->m_impl.template writePacket<StoreMode>(index, x);\n  }\n\n  template <typename TensorBlock>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void writeBlock(\n      const TensorBlockDesc& desc, const TensorBlock& block) {\n    assert(this->m_impl.data() != NULL);\n\n    typedef typename TensorBlock::XprType TensorBlockExpr;\n    typedef internal::TensorBlockAssignment<\n        Scalar, TensorEvaluator::NumOutputDims, TensorBlockExpr, Index>\n        TensorBlockAssign;\n\n    TensorBlockAssign::Run(\n        TensorBlockAssign::target(desc.dimensions(),\n                                  internal::strides<Layout>(this->dimensions()),\n                                  this->m_impl.data(), desc.offset()),\n        block.expr());\n  }\n};\n\n\n/** \\class TensorSlicing\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor slicing class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename StartIndices, typename Sizes, typename XprType>\nstruct traits<TensorSlicingOp<StartIndices, Sizes, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = array_size<StartIndices>::value;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename StartIndices, typename Sizes, typename XprType>\nstruct eval<TensorSlicingOp<StartIndices, Sizes, XprType>, Eigen::Dense>\n{\n  typedef const TensorSlicingOp<StartIndices, Sizes, XprType>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename StartIndices, typename Sizes, typename XprType>\nstruct nested<TensorSlicingOp<StartIndices, Sizes, XprType>, 1, typename eval<TensorSlicingOp<StartIndices, Sizes, XprType> >::type>\n{\n  typedef TensorSlicingOp<StartIndices, Sizes, XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename StartIndices, typename Sizes, typename XprType>\nclass TensorSlicingOp : public TensorBase<TensorSlicingOp<StartIndices, Sizes, XprType> >\n{\n  public:\n  typedef TensorBase<TensorSlicingOp<StartIndices, Sizes, XprType> > Base;\n  typedef typename Eigen::internal::traits<TensorSlicingOp>::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorSlicingOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorSlicingOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorSlicingOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorSlicingOp(const XprType& expr, const StartIndices& indices, const Sizes& sizes)\n      : m_xpr(expr), m_indices(indices), m_sizes(sizes) {}\n\n    EIGEN_DEVICE_FUNC\n    const StartIndices& startIndices() const { return m_indices; }\n    EIGEN_DEVICE_FUNC\n    const Sizes& sizes() const { return m_sizes; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(TensorSlicingOp)\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const StartIndices m_indices;\n    const Sizes m_sizes;\n};\n\n\n// Fixme: figure out the exact threshold\nnamespace {\ntemplate <typename Index, typename Device, bool BlockAccess> struct MemcpyTriggerForSlicing {\n  EIGEN_DEVICE_FUNC MemcpyTriggerForSlicing(const Device& device) : threshold_(2 * device.numThreads()) { }\n  EIGEN_DEVICE_FUNC bool operator ()(Index total, Index contiguous) const {\n    const bool prefer_block_evaluation = BlockAccess && total > 32*1024;\n    return !prefer_block_evaluation && contiguous > threshold_;\n  }\n\n private:\n  Index threshold_;\n};\n\n// It is very expensive to start the memcpy kernel on GPU: we therefore only\n// use it for large copies.\n#ifdef EIGEN_USE_GPU\ntemplate <typename Index, bool BlockAccess> struct MemcpyTriggerForSlicing<Index, GpuDevice, BlockAccess>  {\n  EIGEN_DEVICE_FUNC MemcpyTriggerForSlicing(const GpuDevice&) { }\n  EIGEN_DEVICE_FUNC bool operator ()(Index, Index contiguous) const { return contiguous > 4*1024*1024; }\n};\n#endif\n\n// It is very expensive to start the memcpy kernel on GPU: we therefore only\n// use it for large copies.\n#ifdef EIGEN_USE_SYCL\ntemplate <typename Index, bool BlockAccess> struct MemcpyTriggerForSlicing<Index, Eigen::SyclDevice, BlockAccess>  {\n  EIGEN_DEVICE_FUNC MemcpyTriggerForSlicing(const SyclDevice&) { }\n  EIGEN_DEVICE_FUNC bool operator ()(Index, Index contiguous) const { return contiguous > 4*1024*1024; }\n};\n#endif\n\n}\n\n// Eval as rvalue\ntemplate<typename StartIndices, typename Sizes, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorSlicingOp<StartIndices, Sizes, ArgType>, Device>\n{\n  typedef TensorSlicingOp<StartIndices, Sizes, ArgType> XprType;\n  static const int NumDims = internal::array_size<Sizes>::value;\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef Sizes Dimensions;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef StorageMemory<typename internal::remove_const<CoeffReturnType>::type, Device> ConstCastStorage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    // Alignment can't be guaranteed at compile time since it depends on the\n    // slice offsets and sizes.\n    IsAligned         = false,\n    PacketAccess      = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess       = TensorEvaluator<ArgType, Device>::BlockAccess &&\n                        // FIXME: Temporary workaround for bug in slicing of bool tensors.\n                        !internal::is_same<typename internal::remove_const<Scalar>::type, bool>::value,\n    PreferBlockAccess = true,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess       = false,\n    RawAccess         = false\n  };\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  // Tensor slicing does not change the block type.\n  typedef typename TensorEvaluator<const ArgType, Device>::TensorBlock\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device), m_device(device), m_dimensions(op.sizes()), m_offsets(op.startIndices())\n  {\n    for (Index i = 0; i < internal::array_size<Dimensions>::value; ++i) {\n      eigen_assert(m_impl.dimensions()[i] >= op.sizes()[i] + op.startIndices()[i]);\n    }\n\n    m_is_identity = true;\n    bool degenerate = false;\n    for (int i = 0; i < internal::array_size<Dimensions>::value; ++i) {\n      eigen_assert(m_impl.dimensions()[i] >=\n                   op.sizes()[i] + op.startIndices()[i]);\n      if (m_impl.dimensions()[i] != op.sizes()[i] ||\n          op.startIndices()[i] != 0) {\n        m_is_identity = false;\n      }\n      if (op.sizes()[i] == 0) { // we have an empty size\n        degenerate = true;\n      }\n    }\n\n    // No strides for scalars.\n    if (NumDims == 0) return;\n\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n    const Sizes& output_dims = op.sizes();\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_inputStrides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1];\n      }\n\n     // Don't initialize m_fastOutputStrides[0] since it won't ever be accessed.\n      m_outputStrides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_outputStrides[i] = m_outputStrides[i-1] * output_dims[i-1];\n        // NOTE: if tensor is degenerate, we send 1 to prevent TensorIntDivisor constructor crash\n        m_fastOutputStrides[i] = internal::TensorIntDivisor<Index>(degenerate ? 1 : m_outputStrides[i]);      }\n    } else {\n      m_inputStrides[NumDims-1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1];\n      }\n\n     // Don't initialize m_fastOutputStrides[NumDims-1] since it won't ever be accessed.\n      m_outputStrides[NumDims-1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_outputStrides[i] = m_outputStrides[i+1] * output_dims[i+1];\n        // NOTE: if tensor is degenerate, we send 1 to prevent TensorIntDivisor constructor crash\n        m_fastOutputStrides[i] = internal::TensorIntDivisor<Index>(degenerate ? 1 : m_outputStrides[i]);      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    if (!NumTraits<typename internal::remove_const<Scalar>::type>::RequireInitialization\n        && data && m_impl.data()) {\n      Index contiguous_values = 1;\n      if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n        for (int i = 0; i < NumDims; ++i) {\n          contiguous_values *= dimensions()[i];\n          if (dimensions()[i] != m_impl.dimensions()[i]) {\n            break;\n          }\n        }\n      } else {\n        for (int i = NumDims-1; i >= 0; --i) {\n          contiguous_values *= dimensions()[i];\n          if (dimensions()[i] != m_impl.dimensions()[i]) {\n            break;\n          }\n        }\n      }\n      // Use memcpy if it's going to be faster than using the regular evaluation.\n      const MemcpyTriggerForSlicing<Index, Device, BlockAccess> trigger(m_device);\n      if (trigger(internal::array_prod(dimensions()), contiguous_values)) {\n        EvaluatorPointerType src = (EvaluatorPointerType)m_impl.data();\n        for (Index i = 0; i < internal::array_prod(dimensions()); i += contiguous_values) {\n          Index offset = srcCoeff(i);\n          m_device.memcpy((void*)(m_device.get(data + i)), m_device.get(src+offset), contiguous_values * sizeof(Scalar));\n        }\n        return false;\n      }\n    }\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType /*data*/, EvalSubExprsCallback done) {\n    m_impl.evalSubExprsIfNeededAsync(nullptr, [done](bool) { done(true); });\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    if (m_is_identity) {\n      return m_impl.coeff(index);\n    } else {\n      return m_impl.coeff(srcCoeff(index));\n    }\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    const int packetSize = PacketType<CoeffReturnType, Device>::size;\n    EIGEN_STATIC_ASSERT((packetSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+packetSize-1 < internal::array_prod(dimensions()));\n\n    if (m_is_identity) {\n      return m_impl.template packet<LoadMode>(index);\n    }\n\n    Index inputIndices[] = {0, 0};\n    Index indices[] = {index, index + packetSize - 1};\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx0 = indices[0] / m_fastOutputStrides[i];\n        const Index idx1 = indices[1] / m_fastOutputStrides[i];\n        inputIndices[0] += (idx0 + m_offsets[i]) * m_inputStrides[i];\n        inputIndices[1] += (idx1 + m_offsets[i]) * m_inputStrides[i];\n        indices[0] -= idx0 * m_outputStrides[i];\n        indices[1] -= idx1 * m_outputStrides[i];\n      }\n      inputIndices[0] += (indices[0] + m_offsets[0]);\n      inputIndices[1] += (indices[1] + m_offsets[0]);\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx0 = indices[0] / m_fastOutputStrides[i];\n        const Index idx1 = indices[1] / m_fastOutputStrides[i];\n        inputIndices[0] += (idx0 + m_offsets[i]) * m_inputStrides[i];\n        inputIndices[1] += (idx1 + m_offsets[i]) * m_inputStrides[i];\n        indices[0] -= idx0 * m_outputStrides[i];\n        indices[1] -= idx1 * m_outputStrides[i];\n      }\n      inputIndices[0] += (indices[0] + m_offsets[NumDims-1]);\n      inputIndices[1] += (indices[1] + m_offsets[NumDims-1]);\n    }\n    if (inputIndices[1] - inputIndices[0] == packetSize - 1) {\n      PacketReturnType rslt = m_impl.template packet<Unaligned>(inputIndices[0]);\n      return rslt;\n    }\n    else {\n      EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[packetSize];\n      values[0] = m_impl.coeff(inputIndices[0]);\n      values[packetSize-1] = m_impl.coeff(inputIndices[1]);\n      EIGEN_UNROLL_LOOP\n      for (int i = 1; i < packetSize-1; ++i) {\n        values[i] = coeff(index+i);\n      }\n      PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n      return rslt;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    return m_impl.costPerCoeff(vectorized) + TensorOpCost(0, 0, m_is_identity ? 1 : NumDims);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    const size_t target_size = m_device.lastLevelCacheSize();\n    return internal::TensorBlockResourceRequirements::merge(\n        internal::TensorBlockResourceRequirements::skewed<Scalar>(target_size),\n        m_impl.getResourceRequirements());\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    TensorBlockDesc arg_desc = desc.WithOffset(srcCoeff(desc.offset()));\n    TensorBlock block = m_impl.block(arg_desc, scratch);\n    if (!arg_desc.HasDestinationBuffer()) desc.DropDestinationBuffer();\n    return block;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Storage::Type data() const {\n    typename Storage::Type result = constCast(m_impl.data());\n    if (result) {\n      Index offset = 0;\n      if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n        for (int i = 0; i < NumDims; ++i) {\n          if (m_dimensions[i] != m_impl.dimensions()[i]) {\n            offset += m_offsets[i] * m_inputStrides[i];\n            for (int j = i+1; j < NumDims; ++j) {\n              if (m_dimensions[j] > 1) {\n                return NULL;\n              }\n              offset += m_offsets[j] * m_inputStrides[j];\n            }\n            break;\n          }\n        }\n      } else {\n        for (int i = NumDims - 1; i >= 0; --i) {\n          if (m_dimensions[i] != m_impl.dimensions()[i]) {\n            offset += m_offsets[i] * m_inputStrides[i];\n            for (int j = i-1; j >= 0; --j) {\n              if (m_dimensions[j] > 1) {\n                return NULL;\n              }\n              offset += m_offsets[j] * m_inputStrides[j];\n            }\n            break;\n          }\n        }\n      }\n      return result + offset;\n    }\n    return NULL;\n  }\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n\n protected:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index srcCoeff(Index index) const\n  {\n    Index inputIndex = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx = index / m_fastOutputStrides[i];\n        inputIndex += (idx + m_offsets[i]) * m_inputStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      inputIndex += (index + m_offsets[0]);\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx = index / m_fastOutputStrides[i];\n        inputIndex += (idx + m_offsets[i]) * m_inputStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      inputIndex += (index + m_offsets[NumDims-1]);\n    }\n    return inputIndex;\n  }\n\n  array<Index, NumDims> m_outputStrides;\n  array<internal::TensorIntDivisor<Index>, NumDims> m_fastOutputStrides;\n  array<Index, NumDims> m_inputStrides;\n  TensorEvaluator<ArgType, Device> m_impl;\n  const Device EIGEN_DEVICE_REF m_device;\n  Dimensions m_dimensions;\n  bool m_is_identity;\n  const StartIndices m_offsets;\n};\n\n\n// Eval as lvalue\ntemplate<typename StartIndices, typename Sizes, typename ArgType, typename Device>\nstruct TensorEvaluator<TensorSlicingOp<StartIndices, Sizes, ArgType>, Device>\n  : public TensorEvaluator<const TensorSlicingOp<StartIndices, Sizes, ArgType>, Device>\n{\n  typedef TensorEvaluator<const TensorSlicingOp<StartIndices, Sizes, ArgType>, Device> Base;\n  typedef TensorSlicingOp<StartIndices, Sizes, ArgType> XprType;\n  static const int NumDims = internal::array_size<Sizes>::value;\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef Sizes Dimensions;\n\n  enum {\n    IsAligned         = false,\n    PacketAccess      = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess       = TensorEvaluator<ArgType, Device>::BlockAccess,\n    PreferBlockAccess = true,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess       = false,\n    RawAccess         = (NumDims == 1) & TensorEvaluator<ArgType, Device>::RawAccess\n  };\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n    : Base(op, device)\n    { }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index)\n  {\n    if (this->m_is_identity) {\n      return this->m_impl.coeffRef(index);\n    } else {\n      return this->m_impl.coeffRef(this->srcCoeff(index));\n    }\n  }\n\n  template <int StoreMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void writePacket(Index index, const PacketReturnType& x)\n  {\n    if (this->m_is_identity) {\n      this->m_impl.template writePacket<StoreMode>(index, x);\n      return;\n    }\n\n    const int packetSize = PacketType<CoeffReturnType, Device>::size;\n    Index inputIndices[] = {0, 0};\n    Index indices[] = {index, index + packetSize - 1};\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx0 = indices[0] / this->m_fastOutputStrides[i];\n        const Index idx1 = indices[1] / this->m_fastOutputStrides[i];\n        inputIndices[0] += (idx0 + this->m_offsets[i]) * this->m_inputStrides[i];\n        inputIndices[1] += (idx1 + this->m_offsets[i]) * this->m_inputStrides[i];\n        indices[0] -= idx0 * this->m_outputStrides[i];\n        indices[1] -= idx1 * this->m_outputStrides[i];\n      }\n      inputIndices[0] += (indices[0] + this->m_offsets[0]);\n      inputIndices[1] += (indices[1] + this->m_offsets[0]);\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx0 = indices[0] / this->m_fastOutputStrides[i];\n        const Index idx1 = indices[1] / this->m_fastOutputStrides[i];\n        inputIndices[0] += (idx0 + this->m_offsets[i]) * this->m_inputStrides[i];\n        inputIndices[1] += (idx1 + this->m_offsets[i]) * this->m_inputStrides[i];\n        indices[0] -= idx0 * this->m_outputStrides[i];\n        indices[1] -= idx1 * this->m_outputStrides[i];\n      }\n      inputIndices[0] += (indices[0] + this->m_offsets[NumDims-1]);\n      inputIndices[1] += (indices[1] + this->m_offsets[NumDims-1]);\n    }\n    if (inputIndices[1] - inputIndices[0] == packetSize - 1) {\n      this->m_impl.template writePacket<StoreMode>(inputIndices[0], x);\n    }\n    else {\n      EIGEN_ALIGN_MAX CoeffReturnType values[packetSize];\n      internal::pstore<CoeffReturnType, PacketReturnType>(values, x);\n      this->m_impl.coeffRef(inputIndices[0]) = values[0];\n      this->m_impl.coeffRef(inputIndices[1]) = values[packetSize-1];\n      EIGEN_UNROLL_LOOP\n      for (int i = 1; i < packetSize-1; ++i) {\n        this->coeffRef(index+i) = values[i];\n      }\n    }\n  }\n\n  template<typename TensorBlock>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void writeBlock(\n      const TensorBlockDesc& desc, const TensorBlock& block) {\n    TensorBlockDesc arg_desc = desc.WithOffset(this->srcCoeff(desc.offset()));\n    this->m_impl.writeBlock(arg_desc, block);\n  }\n};\n\nnamespace internal {\ntemplate<typename StartIndices, typename StopIndices, typename Strides, typename XprType>\nstruct traits<TensorStridingSlicingOp<StartIndices, StopIndices, Strides, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = array_size<StartIndices>::value;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename StartIndices, typename StopIndices, typename Strides, typename XprType>\nstruct eval<TensorStridingSlicingOp<StartIndices, StopIndices, Strides, XprType>, Eigen::Dense>\n{\n  typedef const TensorStridingSlicingOp<StartIndices, StopIndices, Strides, XprType>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename StartIndices, typename StopIndices, typename Strides, typename XprType>\nstruct nested<TensorStridingSlicingOp<StartIndices, StopIndices, Strides, XprType>, 1, typename eval<TensorStridingSlicingOp<StartIndices, StopIndices, Strides, XprType> >::type>\n{\n  typedef TensorStridingSlicingOp<StartIndices, StopIndices, Strides, XprType> type;\n};\n\n}  // end namespace internal\n\n\ntemplate<typename StartIndices, typename StopIndices, typename Strides, typename XprType>\nclass TensorStridingSlicingOp : public TensorBase<TensorStridingSlicingOp<StartIndices, StopIndices, Strides, XprType> >\n{\n  public:\n  typedef TensorBase<TensorStridingSlicingOp<StartIndices, StopIndices, Strides, XprType> > Base;\n  typedef typename internal::traits<TensorStridingSlicingOp>::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename internal::nested<TensorStridingSlicingOp>::type Nested;\n  typedef typename internal::traits<TensorStridingSlicingOp>::StorageKind StorageKind;\n  typedef typename internal::traits<TensorStridingSlicingOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorStridingSlicingOp(\n    const XprType& expr, const StartIndices& startIndices,\n    const StopIndices& stopIndices, const Strides& strides)\n      : m_xpr(expr), m_startIndices(startIndices), m_stopIndices(stopIndices),\n        m_strides(strides) {}\n\n    EIGEN_DEVICE_FUNC\n    const StartIndices& startIndices() const { return m_startIndices; }\n    EIGEN_DEVICE_FUNC\n    const StartIndices& stopIndices() const { return m_stopIndices; }\n    EIGEN_DEVICE_FUNC\n    const StartIndices& strides() const { return m_strides; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(TensorStridingSlicingOp)\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const StartIndices m_startIndices;\n    const StopIndices m_stopIndices;\n    const Strides m_strides;\n};\n\n// Eval as rvalue\ntemplate<typename StartIndices, typename StopIndices, typename Strides, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorStridingSlicingOp<StartIndices, StopIndices, Strides, ArgType>, Device>\n{\n  typedef TensorStridingSlicingOp<StartIndices, StopIndices, Strides, ArgType> XprType;\n  static const int NumDims = internal::array_size<Strides>::value;\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n  typedef Strides Dimensions;\n\n  enum {\n    // Alignment can't be guaranteed at compile time since it depends on the\n    // slice offsets and sizes.\n    IsAligned = false,\n    PacketAccess = false,\n    BlockAccess = false,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device),\n        m_device(device),\n        m_strides(op.strides())\n  {\n    // Handle degenerate intervals by gracefully clamping and allowing m_dimensions to be zero\n    DSizes<Index, NumDims> startIndicesClamped, stopIndicesClamped;\n    for (ptrdiff_t i = 0; i < internal::array_size<Dimensions>::value; ++i) {\n      eigen_assert(m_strides[i] != 0 && \"0 stride is invalid\");\n      if (m_strides[i] > 0) {\n        startIndicesClamped[i] =\n            clamp(op.startIndices()[i], 0, m_impl.dimensions()[i]);\n        stopIndicesClamped[i] =\n            clamp(op.stopIndices()[i], 0, m_impl.dimensions()[i]);\n      } else {\n        /* implies m_strides[i] < 0 by assert */\n        startIndicesClamped[i] =\n            clamp(op.startIndices()[i], -1, m_impl.dimensions()[i] - 1);\n        stopIndicesClamped[i] =\n            clamp(op.stopIndices()[i], -1, m_impl.dimensions()[i] - 1);\n      }\n      m_startIndices[i] = startIndicesClamped[i];\n    }\n\n    typedef typename TensorEvaluator<ArgType, Device>::Dimensions InputDimensions;\n    const InputDimensions& input_dims = m_impl.dimensions();\n\n    // check for degenerate intervals and compute output tensor shape\n    bool degenerate = false;\n    m_is_identity = true;\n    for (int i = 0; i < NumDims; i++) {\n      Index interval = stopIndicesClamped[i] - startIndicesClamped[i];\n      if (interval == 0 || ((interval < 0) != (m_strides[i] < 0))) {\n        m_dimensions[i] = 0;\n        degenerate = true;\n      } else {\n        m_dimensions[i] =\n            (interval / m_strides[i]) + (interval % m_strides[i] != 0 ? 1 : 0);\n        eigen_assert(m_dimensions[i] >= 0);\n      }\n      if (m_strides[i] != 1 || interval != m_impl.dimensions()[i]) {\n        m_is_identity = false;\n      }\n    }\n\n    Strides output_dims = m_dimensions;\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_inputStrides[0] = m_strides[0];\n      m_offsets[0] = startIndicesClamped[0];\n      Index previousDimProduct = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        previousDimProduct *= input_dims[i-1];\n        m_inputStrides[i] = previousDimProduct * m_strides[i];\n        m_offsets[i] = startIndicesClamped[i] * previousDimProduct;\n      }\n\n      // Don't initialize m_fastOutputStrides[0] since it won't ever be accessed.\n      m_outputStrides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_outputStrides[i] = m_outputStrides[i-1] * output_dims[i-1];\n        // NOTE: if tensor is degenerate, we send 1 to prevent TensorIntDivisor constructor crash\n        m_fastOutputStrides[i] = internal::TensorIntDivisor<Index>(degenerate ? 1 : m_outputStrides[i]);\n      }\n    } else {\n      m_inputStrides[NumDims-1] = m_strides[NumDims-1];\n      m_offsets[NumDims-1] = startIndicesClamped[NumDims-1];\n      Index previousDimProduct = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        previousDimProduct *= input_dims[i+1];\n        m_inputStrides[i] = previousDimProduct * m_strides[i];\n        m_offsets[i] = startIndicesClamped[i] * previousDimProduct;\n      }\n\n      m_outputStrides[NumDims-1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_outputStrides[i] = m_outputStrides[i+1] * output_dims[i+1];\n        // NOTE: if tensor is degenerate, we send 1 to prevent TensorIntDivisor constructor crash\n        m_fastOutputStrides[i] = internal::TensorIntDivisor<Index>(degenerate ? 1 : m_outputStrides[i]);\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    if (m_is_identity) {\n      return m_impl.coeff(index);\n    } else {\n      return m_impl.coeff(srcCoeff(index));\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    return m_impl.costPerCoeff(vectorized) + TensorOpCost(0, 0, m_is_identity ? 1 : NumDims);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Storage::Type data() const {\n    return NULL;\n  }\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n protected:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index srcCoeff(Index index) const\n  {\n    Index inputIndex = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i >= 0; --i) {\n        const Index idx = index / m_fastOutputStrides[i];\n        inputIndex += idx * m_inputStrides[i] + m_offsets[i];\n        index -= idx * m_outputStrides[i];\n      }\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims; ++i) {\n        const Index idx = index / m_fastOutputStrides[i];\n        inputIndex += idx * m_inputStrides[i] + m_offsets[i];\n        index -= idx * m_outputStrides[i];\n      }\n    }\n    return inputIndex;\n  }\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index clamp(Index value, Index min, Index max) {\n#ifndef SYCL_DEVICE_ONLY\n    return numext::maxi(min, numext::mini(max,value));\n#else\n    return cl::sycl::clamp(value, min, max);\n#endif\n  }\n\n  array<Index, NumDims> m_outputStrides;\n  array<internal::TensorIntDivisor<Index>, NumDims> m_fastOutputStrides;\n  array<Index, NumDims> m_inputStrides;\n  bool m_is_identity;\n  TensorEvaluator<ArgType, Device> m_impl;\n  const Device EIGEN_DEVICE_REF m_device;\n  DSizes<Index, NumDims> m_startIndices; // clamped startIndices\n  DSizes<Index, NumDims> m_dimensions;\n  DSizes<Index, NumDims> m_offsets; // offset in a flattened shape\n  const Strides m_strides;\n};\n\n// Eval as lvalue\ntemplate<typename StartIndices, typename StopIndices, typename Strides, typename ArgType, typename Device>\nstruct TensorEvaluator<TensorStridingSlicingOp<StartIndices, StopIndices, Strides, ArgType>, Device>\n  : public TensorEvaluator<const TensorStridingSlicingOp<StartIndices, StopIndices, Strides, ArgType>, Device>\n{\n  typedef TensorEvaluator<const TensorStridingSlicingOp<StartIndices, StopIndices, Strides, ArgType>, Device> Base;\n  typedef TensorStridingSlicingOp<StartIndices, StopIndices, Strides, ArgType> XprType;\n  static const int NumDims = internal::array_size<Strides>::value;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = false,\n    BlockAccess = false,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = TensorEvaluator<ArgType, Device>::CoordAccess,\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n    : Base(op, device)\n    { }\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef Strides Dimensions;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index)\n  {\n    if (this->m_is_identity) {\n      return this->m_impl.coeffRef(index);\n    } else {\n      return this->m_impl.coeffRef(this->srcCoeff(index));\n    }\n  }\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_MORPHING_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorPadding.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_PADDING_H\n#define EIGEN_CXX11_TENSOR_TENSOR_PADDING_H\n\nnamespace Eigen {\n\n/** \\class TensorPadding\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor padding class.\n  * At the moment only padding with a constant value is supported.\n  *\n  */\nnamespace internal {\ntemplate<typename PaddingDimensions, typename XprType>\nstruct traits<TensorPaddingOp<PaddingDimensions, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename PaddingDimensions, typename XprType>\nstruct eval<TensorPaddingOp<PaddingDimensions, XprType>, Eigen::Dense>\n{\n  typedef const TensorPaddingOp<PaddingDimensions, XprType>& type;\n};\n\ntemplate<typename PaddingDimensions, typename XprType>\nstruct nested<TensorPaddingOp<PaddingDimensions, XprType>, 1, typename eval<TensorPaddingOp<PaddingDimensions, XprType> >::type>\n{\n  typedef TensorPaddingOp<PaddingDimensions, XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename PaddingDimensions, typename XprType>\nclass TensorPaddingOp : public TensorBase<TensorPaddingOp<PaddingDimensions, XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorPaddingOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorPaddingOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorPaddingOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorPaddingOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorPaddingOp(const XprType& expr, const PaddingDimensions& padding_dims, const Scalar padding_value)\n      : m_xpr(expr), m_padding_dims(padding_dims), m_padding_value(padding_value) {}\n\n    EIGEN_DEVICE_FUNC\n    const PaddingDimensions& padding() const { return m_padding_dims; }\n    EIGEN_DEVICE_FUNC\n    Scalar padding_value() const { return m_padding_value; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const PaddingDimensions m_padding_dims;\n    const Scalar m_padding_value;\n};\n\n\n// Eval as rvalue\ntemplate<typename PaddingDimensions, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorPaddingOp<PaddingDimensions, ArgType>, Device>\n{\n  typedef TensorPaddingOp<PaddingDimensions, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<PaddingDimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned         = true,\n    PacketAccess      = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess       = TensorEvaluator<ArgType, Device>::RawAccess,\n    PreferBlockAccess = true,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess       = true,\n    RawAccess         = false\n  };\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename internal::TensorMaterializedBlock<ScalarNoConst, NumDims,\n                                                     Layout, Index>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device), m_padding(op.padding()), m_paddingValue(op.padding_value()), m_device(device)\n  {\n    // The padding op doesn't change the rank of the tensor. Directly padding a scalar would lead\n    // to a vector, which doesn't make sense. Instead one should reshape the scalar into a vector\n    // of 1 element first and then pad.\n    EIGEN_STATIC_ASSERT((NumDims > 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    // Compute dimensions\n    m_dimensions = m_impl.dimensions();\n    for (int i = 0; i < NumDims; ++i) {\n      m_dimensions[i] += m_padding[i].first + m_padding[i].second;\n    }\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_inputStrides[0] = 1;\n      m_outputStrides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1];\n        m_outputStrides[i] = m_outputStrides[i-1] * m_dimensions[i-1];\n      }\n      m_outputStrides[NumDims] = m_outputStrides[NumDims-1] * m_dimensions[NumDims-1];\n    } else {\n      m_inputStrides[NumDims - 1] = 1;\n      m_outputStrides[NumDims] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1];\n        m_outputStrides[i+1] = m_outputStrides[i+2] * m_dimensions[i+1];\n      }\n      m_outputStrides[0] = m_outputStrides[1] * m_dimensions[0];\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    m_impl.evalSubExprsIfNeededAsync(nullptr, [done](bool) { done(true); });\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    eigen_assert(index < dimensions().TotalSize());\n    Index inputIndex = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx = index / m_outputStrides[i];\n        if (isPaddingAtIndexForDim(idx, i)) {\n          return m_paddingValue;\n        }\n        inputIndex += (idx - m_padding[i].first) * m_inputStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      if (isPaddingAtIndexForDim(index, 0)) {\n        return m_paddingValue;\n      }\n      inputIndex += (index - m_padding[0].first);\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx = index / m_outputStrides[i+1];\n        if (isPaddingAtIndexForDim(idx, i)) {\n          return m_paddingValue;\n        }\n        inputIndex += (idx - m_padding[i].first) * m_inputStrides[i];\n        index -= idx * m_outputStrides[i+1];\n      }\n      if (isPaddingAtIndexForDim(index, NumDims-1)) {\n        return m_paddingValue;\n      }\n      inputIndex += (index - m_padding[NumDims-1].first);\n    }\n    return m_impl.coeff(inputIndex);\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      return packetColMajor(index);\n    }\n    return packetRowMajor(index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    TensorOpCost cost = m_impl.costPerCoeff(vectorized);\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims; ++i)\n        updateCostPerDimension(cost, i, i == 0);\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i >= 0; --i)\n        updateCostPerDimension(cost, i, i == NumDims - 1);\n    }\n    return cost;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    const size_t target_size = m_device.lastLevelCacheSize();\n    return internal::TensorBlockResourceRequirements::merge(\n        internal::TensorBlockResourceRequirements::skewed<Scalar>(target_size),\n        m_impl.getResourceRequirements());\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    // If one of the dimensions is zero, return empty block view.\n    if (desc.size() == 0) {\n      return TensorBlock(internal::TensorBlockKind::kView, NULL,\n                           desc.dimensions());\n    }\n\n    static const bool IsColMajor = Layout == static_cast<int>(ColMajor);\n    const int inner_dim_idx = IsColMajor ? 0 : NumDims - 1;\n\n    Index offset = desc.offset();\n\n    // Compute offsets in the output tensor corresponding to the desc.offset().\n    DSizes<Index, NumDims> output_offsets;\n    for (int i = NumDims - 1; i > 0; --i) {\n      const int dim = IsColMajor ? i : NumDims - i - 1;\n      const int stride_dim = IsColMajor ? dim : dim + 1;\n      output_offsets[dim] = offset / m_outputStrides[stride_dim];\n      offset -= output_offsets[dim] * m_outputStrides[stride_dim];\n    }\n    output_offsets[inner_dim_idx] = offset;\n\n    // Offsets in the input corresponding to output offsets.\n    DSizes<Index, NumDims> input_offsets = output_offsets;\n    for (int i = 0; i < NumDims; ++i) {\n      const int dim = IsColMajor ? i : NumDims - i - 1;\n      input_offsets[dim] = input_offsets[dim] - m_padding[dim].first;\n    }\n\n    // Compute offset in the input buffer (at this point it might be illegal and\n    // point outside of the input buffer, because we don't check for negative\n    // offsets, it will be autocorrected in the block iteration loop below).\n    Index input_offset = 0;\n    for (int i = 0; i < NumDims; ++i) {\n      const int dim = IsColMajor ? i : NumDims - i - 1;\n      input_offset += input_offsets[dim] * m_inputStrides[dim];\n    }\n\n    // Destination buffer and scratch buffer both indexed from 0 and have the\n    // same dimensions as the requested block (for destination buffer this\n    // property is guaranteed by `desc.destination()`).\n    Index output_offset = 0;\n    const DSizes<Index, NumDims> output_strides =\n        internal::strides<Layout>(desc.dimensions());\n\n    // NOTE(ezhulenev): We initialize bock iteration state for `NumDims - 1`\n    // dimensions, skipping innermost dimension. In theory it should be possible\n    // to squeeze matching innermost dimensions, however in practice that did\n    // not show any improvements in benchmarks. Also in practice first outer\n    // dimension usually has padding, and will prevent squeezing.\n\n    // Initialize output block iterator state. Dimension in this array are\n    // always in inner_most -> outer_most order (col major layout).\n    array<BlockIteratorState, NumDims - 1> it;\n    for (int i = 0; i < NumDims - 1; ++i) {\n      const int dim = IsColMajor ? i + 1 : NumDims - i - 2;\n      it[i].count = 0;\n      it[i].size = desc.dimension(dim);\n\n      it[i].input_stride = m_inputStrides[dim];\n      it[i].input_span = it[i].input_stride * (it[i].size - 1);\n\n      it[i].output_stride = output_strides[dim];\n      it[i].output_span = it[i].output_stride * (it[i].size - 1);\n    }\n\n    const Index input_inner_dim_size =\n        static_cast<Index>(m_impl.dimensions()[inner_dim_idx]);\n\n    // Total output size.\n    const Index output_size = desc.size();\n\n    // We will fill inner dimension of this size in the output. It might be\n    // larger than the inner dimension in the input, so we might have to pad\n    // before/after we copy values from the input inner dimension.\n    const Index output_inner_dim_size = desc.dimension(inner_dim_idx);\n\n    // How many values to fill with padding BEFORE reading from the input inner\n    // dimension.\n    const Index output_inner_pad_before_size =\n        input_offsets[inner_dim_idx] < 0\n            ? numext::mini(numext::abs(input_offsets[inner_dim_idx]),\n                           output_inner_dim_size)\n            : 0;\n\n    // How many values we can actually copy from the input inner dimension.\n    const Index output_inner_copy_size = numext::mini(\n        // Want to copy from input.\n        (output_inner_dim_size - output_inner_pad_before_size),\n        // Can copy from input.\n        numext::maxi(input_inner_dim_size - (input_offsets[inner_dim_idx] +\n                                             output_inner_pad_before_size),\n                     Index(0)));\n\n    eigen_assert(output_inner_copy_size >= 0);\n\n    // How many values to fill with padding AFTER reading from the input inner\n    // dimension.\n    const Index output_inner_pad_after_size =\n        (output_inner_dim_size - output_inner_copy_size -\n         output_inner_pad_before_size);\n\n    // Sanity check, sum of all sizes must be equal to the output size.\n    eigen_assert(output_inner_dim_size ==\n                 (output_inner_pad_before_size + output_inner_copy_size +\n                  output_inner_pad_after_size));\n\n    // Keep track of current coordinates and padding in the output.\n    DSizes<Index, NumDims> output_coord = output_offsets;\n    DSizes<Index, NumDims> output_padded;\n    for (int i = 0; i < NumDims; ++i) {\n      const int dim = IsColMajor ? i : NumDims - i - 1;\n      output_padded[dim] = isPaddingAtIndexForDim(output_coord[dim], dim);\n    }\n\n    typedef internal::StridedLinearBufferCopy<ScalarNoConst, Index> LinCopy;\n\n    // Prepare storage for the materialized padding result.\n    const typename TensorBlock::Storage block_storage =\n        TensorBlock::prepareStorage(desc, scratch);\n\n    // TODO(ezhulenev): Squeeze multiple non-padded inner dimensions into a\n    // single logical inner dimension.\n\n    // When possible we squeeze writes for the innermost (only if non-padded)\n    // dimension with the first padded dimension. This allows to reduce the\n    // number of calls to LinCopy and better utilize vector instructions.\n    const bool squeeze_writes =\n        NumDims > 1 &&\n        // inner dimension is not padded\n        (input_inner_dim_size == m_dimensions[inner_dim_idx]) &&\n        // and equal to the block inner dimension\n        (input_inner_dim_size == output_inner_dim_size);\n\n    const int squeeze_dim = IsColMajor ? inner_dim_idx + 1 : inner_dim_idx - 1;\n\n    // Maximum coordinate on a squeeze dimension that we can write to.\n    const Index squeeze_max_coord =\n        squeeze_writes ? numext::mini(\n                             // max non-padded element in the input\n                             static_cast<Index>(m_dimensions[squeeze_dim] -\n                                                m_padding[squeeze_dim].second),\n                             // max element in the output buffer\n                             static_cast<Index>(output_offsets[squeeze_dim] +\n                                                desc.dimension(squeeze_dim)))\n                       : static_cast<Index>(0);\n\n    // Iterate copying data from `m_impl.data()` to the output buffer.\n    for (Index size = 0; size < output_size;) {\n      // Detect if we are in the padded region (exclude innermost dimension).\n      bool is_padded = false;\n      for (int j = 1; j < NumDims; ++j) {\n        const int dim = IsColMajor ? j : NumDims - j - 1;\n        is_padded = output_padded[dim];\n        if (is_padded) break;\n      }\n\n      if (is_padded) {\n        // Fill single innermost dimension with padding value.\n        size += output_inner_dim_size;\n\n        LinCopy::template Run<LinCopy::Kind::FillLinear>(\n            typename LinCopy::Dst(output_offset, 1, block_storage.data()),\n            typename LinCopy::Src(0, 0, &m_paddingValue),\n            output_inner_dim_size);\n\n\n      } else if (squeeze_writes) {\n        // Squeeze multiple reads from innermost dimensions.\n        const Index squeeze_num = squeeze_max_coord - output_coord[squeeze_dim];\n        size += output_inner_dim_size * squeeze_num;\n\n        // Copy `squeeze_num` inner dimensions from input to output.\n        LinCopy::template Run<LinCopy::Kind::Linear>(\n            typename LinCopy::Dst(output_offset, 1, block_storage.data()),\n            typename LinCopy::Src(input_offset, 1, m_impl.data()),\n            output_inner_dim_size * squeeze_num);\n\n        // Update iteration state for only `squeeze_num - 1` processed inner\n        // dimensions, because we have another iteration state update at the end\n        // of the loop that will update iteration state for the last inner\n        // processed dimension.\n        it[0].count += (squeeze_num - 1);\n        input_offset += it[0].input_stride * (squeeze_num - 1);\n        output_offset += it[0].output_stride * (squeeze_num - 1);\n        output_coord[squeeze_dim] += (squeeze_num - 1);\n\n      } else {\n        // Single read from innermost dimension.\n        size += output_inner_dim_size;\n\n        {  // Fill with padding before copying from input inner dimension.\n          const Index out = output_offset;\n\n          LinCopy::template Run<LinCopy::Kind::FillLinear>(\n              typename LinCopy::Dst(out, 1, block_storage.data()),\n              typename LinCopy::Src(0, 0, &m_paddingValue),\n              output_inner_pad_before_size);\n        }\n\n        {  // Copy data from input inner dimension.\n          const Index out = output_offset + output_inner_pad_before_size;\n          const Index in = input_offset + output_inner_pad_before_size;\n\n          eigen_assert(output_inner_copy_size == 0 || m_impl.data() != NULL);\n\n          LinCopy::template Run<LinCopy::Kind::Linear>(\n              typename LinCopy::Dst(out, 1, block_storage.data()),\n              typename LinCopy::Src(in, 1, m_impl.data()),\n              output_inner_copy_size);\n        }\n\n        {  // Fill with padding after copying from input inner dimension.\n          const Index out = output_offset + output_inner_pad_before_size +\n                            output_inner_copy_size;\n\n          LinCopy::template Run<LinCopy::Kind::FillLinear>(\n              typename LinCopy::Dst(out, 1, block_storage.data()),\n              typename LinCopy::Src(0, 0, &m_paddingValue),\n              output_inner_pad_after_size);\n        }\n      }\n\n      for (int j = 0; j < NumDims - 1; ++j) {\n        const int dim = IsColMajor ? j + 1 : NumDims - j - 2;\n\n        if (++it[j].count < it[j].size) {\n          input_offset += it[j].input_stride;\n          output_offset += it[j].output_stride;\n          output_coord[dim] += 1;\n          output_padded[dim] = isPaddingAtIndexForDim(output_coord[dim], dim);\n          break;\n        }\n        it[j].count = 0;\n        input_offset -= it[j].input_span;\n        output_offset -= it[j].output_span;\n        output_coord[dim] -= it[j].size - 1;\n        output_padded[dim] = isPaddingAtIndexForDim(output_coord[dim], dim);\n      }\n    }\n\n    return block_storage.AsTensorMaterializedBlock();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EvaluatorPointerType data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n\n private:\n  struct BlockIteratorState {\n    BlockIteratorState()\n        : count(0),\n          size(0),\n          input_stride(0),\n          input_span(0),\n          output_stride(0),\n          output_span(0) {}\n\n    Index count;\n    Index size;\n    Index input_stride;\n    Index input_span;\n    Index output_stride;\n    Index output_span;\n  };\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool isPaddingAtIndexForDim(\n      Index index, int dim_index) const {\n#if defined(EIGEN_HAS_INDEX_LIST)\n    return (!internal::index_pair_first_statically_eq<PaddingDimensions>(dim_index, 0) &&\n            index < m_padding[dim_index].first) ||\n        (!internal::index_pair_second_statically_eq<PaddingDimensions>(dim_index, 0) &&\n         index >= m_dimensions[dim_index] - m_padding[dim_index].second);\n#else\n    return (index < m_padding[dim_index].first) ||\n           (index >= m_dimensions[dim_index] - m_padding[dim_index].second);\n#endif\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool isLeftPaddingCompileTimeZero(\n      int dim_index) const {\n#if defined(EIGEN_HAS_INDEX_LIST)\n    return internal::index_pair_first_statically_eq<PaddingDimensions>(dim_index, 0);\n#else\n    EIGEN_UNUSED_VARIABLE(dim_index);\n    return false;\n#endif\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE bool isRightPaddingCompileTimeZero(\n      int dim_index) const {\n#if defined(EIGEN_HAS_INDEX_LIST)\n    return internal::index_pair_second_statically_eq<PaddingDimensions>(dim_index, 0);\n#else\n    EIGEN_UNUSED_VARIABLE(dim_index);\n    return false;\n#endif\n  }\n\n\n  void updateCostPerDimension(TensorOpCost& cost, int i, bool first) const {\n    const double in = static_cast<double>(m_impl.dimensions()[i]);\n    const double out = in + m_padding[i].first + m_padding[i].second;\n    if (out == 0)\n      return;\n    const double reduction = in / out;\n    cost *= reduction;\n    if (first) {\n      cost += TensorOpCost(0, 0, 2 * TensorOpCost::AddCost<Index>() +\n                    reduction * (1 * TensorOpCost::AddCost<Index>()));\n    } else {\n      cost += TensorOpCost(0, 0, 2 * TensorOpCost::AddCost<Index>() +\n                                 2 * TensorOpCost::MulCost<Index>() +\n                    reduction * (2 * TensorOpCost::MulCost<Index>() +\n                                 1 * TensorOpCost::DivCost<Index>()));\n    }\n  }\n\n protected:\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetColMajor(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    const Index initialIndex = index;\n    Index inputIndex = 0;\n    EIGEN_UNROLL_LOOP\n    for (int i = NumDims - 1; i > 0; --i) {\n      const Index firstIdx = index;\n      const Index lastIdx = index + PacketSize - 1;\n      const Index lastPaddedLeft = m_padding[i].first * m_outputStrides[i];\n      const Index firstPaddedRight = (m_dimensions[i] - m_padding[i].second) * m_outputStrides[i];\n      const Index lastPaddedRight = m_outputStrides[i+1];\n\n      if (!isLeftPaddingCompileTimeZero(i) && lastIdx < lastPaddedLeft) {\n        // all the coefficient are in the padding zone.\n        return internal::pset1<PacketReturnType>(m_paddingValue);\n      }\n      else if (!isRightPaddingCompileTimeZero(i) && firstIdx >= firstPaddedRight && lastIdx < lastPaddedRight) {\n        // all the coefficient are in the padding zone.\n        return internal::pset1<PacketReturnType>(m_paddingValue);\n      }\n      else if ((isLeftPaddingCompileTimeZero(i) && isRightPaddingCompileTimeZero(i)) || (firstIdx >= lastPaddedLeft && lastIdx < firstPaddedRight)) {\n        // all the coefficient are between the 2 padding zones.\n        const Index idx = index / m_outputStrides[i];\n        inputIndex += (idx - m_padding[i].first) * m_inputStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      else {\n        // Every other case\n        return packetWithPossibleZero(initialIndex);\n      }\n    }\n\n    const Index lastIdx = index + PacketSize - 1;\n    const Index firstIdx = index;\n    const Index lastPaddedLeft = m_padding[0].first;\n    const Index firstPaddedRight = (m_dimensions[0] - m_padding[0].second);\n    const Index lastPaddedRight = m_outputStrides[1];\n\n    if (!isLeftPaddingCompileTimeZero(0) && lastIdx < lastPaddedLeft) {\n      // all the coefficient are in the padding zone.\n      return internal::pset1<PacketReturnType>(m_paddingValue);\n    }\n    else if (!isRightPaddingCompileTimeZero(0) && firstIdx >= firstPaddedRight && lastIdx < lastPaddedRight) {\n      // all the coefficient are in the padding zone.\n      return internal::pset1<PacketReturnType>(m_paddingValue);\n    }\n    else if ((isLeftPaddingCompileTimeZero(0) && isRightPaddingCompileTimeZero(0)) || (firstIdx >= lastPaddedLeft && lastIdx < firstPaddedRight)) {\n      // all the coefficient are between the 2 padding zones.\n      inputIndex += (index - m_padding[0].first);\n      return m_impl.template packet<Unaligned>(inputIndex);\n    }\n    // Every other case\n    return packetWithPossibleZero(initialIndex);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetRowMajor(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    const Index initialIndex = index;\n    Index inputIndex = 0;\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < NumDims - 1; ++i) {\n      const Index firstIdx = index;\n      const Index lastIdx = index + PacketSize - 1;\n      const Index lastPaddedLeft = m_padding[i].first * m_outputStrides[i+1];\n      const Index firstPaddedRight = (m_dimensions[i] - m_padding[i].second) * m_outputStrides[i+1];\n      const Index lastPaddedRight = m_outputStrides[i];\n\n      if (!isLeftPaddingCompileTimeZero(i) && lastIdx < lastPaddedLeft) {\n        // all the coefficient are in the padding zone.\n        return internal::pset1<PacketReturnType>(m_paddingValue);\n      }\n      else if (!isRightPaddingCompileTimeZero(i) && firstIdx >= firstPaddedRight && lastIdx < lastPaddedRight) {\n        // all the coefficient are in the padding zone.\n        return internal::pset1<PacketReturnType>(m_paddingValue);\n      }\n      else if ((isLeftPaddingCompileTimeZero(i) && isRightPaddingCompileTimeZero(i)) || (firstIdx >= lastPaddedLeft && lastIdx < firstPaddedRight)) {\n        // all the coefficient are between the 2 padding zones.\n        const Index idx = index / m_outputStrides[i+1];\n        inputIndex += (idx - m_padding[i].first) * m_inputStrides[i];\n        index -= idx * m_outputStrides[i+1];\n      }\n      else {\n        // Every other case\n        return packetWithPossibleZero(initialIndex);\n      }\n    }\n\n    const Index lastIdx = index + PacketSize - 1;\n    const Index firstIdx = index;\n    const Index lastPaddedLeft = m_padding[NumDims-1].first;\n    const Index firstPaddedRight = (m_dimensions[NumDims-1] - m_padding[NumDims-1].second);\n    const Index lastPaddedRight = m_outputStrides[NumDims-1];\n\n    if (!isLeftPaddingCompileTimeZero(NumDims-1) && lastIdx < lastPaddedLeft) {\n      // all the coefficient are in the padding zone.\n      return internal::pset1<PacketReturnType>(m_paddingValue);\n    }\n    else if (!isRightPaddingCompileTimeZero(NumDims-1) && firstIdx >= firstPaddedRight && lastIdx < lastPaddedRight) {\n      // all the coefficient are in the padding zone.\n      return internal::pset1<PacketReturnType>(m_paddingValue);\n    }\n    else if ((isLeftPaddingCompileTimeZero(NumDims-1) && isRightPaddingCompileTimeZero(NumDims-1)) || (firstIdx >= lastPaddedLeft && lastIdx < firstPaddedRight)) {\n      // all the coefficient are between the 2 padding zones.\n      inputIndex += (index - m_padding[NumDims-1].first);\n      return m_impl.template packet<Unaligned>(inputIndex);\n    }\n    // Every other case\n    return packetWithPossibleZero(initialIndex);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetWithPossibleZero(Index index) const\n  {\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < PacketSize; ++i) {\n      values[i] = coeff(index+i);\n    }\n    PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n    return rslt;\n  }\n\n  Dimensions m_dimensions;\n  array<Index, NumDims+1> m_outputStrides;\n  array<Index, NumDims> m_inputStrides;\n  TensorEvaluator<ArgType, Device> m_impl;\n  PaddingDimensions m_padding;\n\n  Scalar m_paddingValue;\n\n  const Device EIGEN_DEVICE_REF m_device;\n};\n\n\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_PADDING_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorPatch.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_PATCH_H\n#define EIGEN_CXX11_TENSOR_TENSOR_PATCH_H\n\nnamespace Eigen {\n\n/** \\class TensorPatch\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor patch class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename PatchDim, typename XprType>\nstruct traits<TensorPatchOp<PatchDim, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions + 1;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename PatchDim, typename XprType>\nstruct eval<TensorPatchOp<PatchDim, XprType>, Eigen::Dense>\n{\n  typedef const TensorPatchOp<PatchDim, XprType>& type;\n};\n\ntemplate<typename PatchDim, typename XprType>\nstruct nested<TensorPatchOp<PatchDim, XprType>, 1, typename eval<TensorPatchOp<PatchDim, XprType> >::type>\n{\n  typedef TensorPatchOp<PatchDim, XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename PatchDim, typename XprType>\nclass TensorPatchOp : public TensorBase<TensorPatchOp<PatchDim, XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorPatchOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorPatchOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorPatchOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorPatchOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorPatchOp(const XprType& expr, const PatchDim& patch_dims)\n      : m_xpr(expr), m_patch_dims(patch_dims) {}\n\n    EIGEN_DEVICE_FUNC\n    const PatchDim& patch_dims() const { return m_patch_dims; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const PatchDim m_patch_dims;\n};\n\n\n// Eval as rvalue\ntemplate<typename PatchDim, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorPatchOp<PatchDim, ArgType>, Device>\n{\n  typedef TensorPatchOp<PatchDim, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value + 1;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n\n  enum {\n    IsAligned = false,\n    PacketAccess = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess = false,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,\n    RawAccess = false\n };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device)\n  {\n    Index num_patches = 1;\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n    const PatchDim& patch_dims = op.patch_dims();\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = 0; i < NumDims-1; ++i) {\n        m_dimensions[i] = patch_dims[i];\n        num_patches *= (input_dims[i] - patch_dims[i] + 1);\n      }\n      m_dimensions[NumDims-1] = num_patches;\n\n      m_inputStrides[0] = 1;\n      m_patchStrides[0] = 1;\n      for (int i = 1; i < NumDims-1; ++i) {\n        m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1];\n        m_patchStrides[i] = m_patchStrides[i-1] * (input_dims[i-1] - patch_dims[i-1] + 1);\n      }\n      m_outputStrides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_outputStrides[i] = m_outputStrides[i-1] * m_dimensions[i-1];\n      }\n    } else {\n      for (int i = 0; i < NumDims-1; ++i) {\n        m_dimensions[i+1] = patch_dims[i];\n        num_patches *= (input_dims[i] - patch_dims[i] + 1);\n      }\n      m_dimensions[0] = num_patches;\n\n      m_inputStrides[NumDims-2] = 1;\n      m_patchStrides[NumDims-2] = 1;\n      for (int i = NumDims-3; i >= 0; --i) {\n        m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1];\n        m_patchStrides[i] = m_patchStrides[i+1] * (input_dims[i+1] - patch_dims[i+1] + 1);\n      }\n      m_outputStrides[NumDims-1] = 1;\n      for (int i = NumDims-2; i >= 0; --i) {\n        m_outputStrides[i] = m_outputStrides[i+1] * m_dimensions[i+1];\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType /*data*/) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    Index output_stride_index = (static_cast<int>(Layout) == static_cast<int>(ColMajor)) ? NumDims - 1 : 0;\n    // Find the location of the first element of the patch.\n    Index patchIndex = index / m_outputStrides[output_stride_index];\n    // Find the offset of the element wrt the location of the first element.\n    Index patchOffset = index - patchIndex * m_outputStrides[output_stride_index];\n    Index inputIndex = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 2; i > 0; --i) {\n        const Index patchIdx = patchIndex / m_patchStrides[i];\n        patchIndex -= patchIdx * m_patchStrides[i];\n        const Index offsetIdx = patchOffset / m_outputStrides[i];\n        patchOffset -= offsetIdx * m_outputStrides[i];\n        inputIndex += (patchIdx + offsetIdx) * m_inputStrides[i];\n      }\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 2; ++i) {\n        const Index patchIdx = patchIndex / m_patchStrides[i];\n        patchIndex -= patchIdx * m_patchStrides[i];\n        const Index offsetIdx = patchOffset / m_outputStrides[i+1];\n        patchOffset -= offsetIdx * m_outputStrides[i+1];\n        inputIndex += (patchIdx + offsetIdx) * m_inputStrides[i];\n      }\n    }\n    inputIndex += (patchIndex + patchOffset);\n    return m_impl.coeff(inputIndex);\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    Index output_stride_index = (static_cast<int>(Layout) == static_cast<int>(ColMajor)) ? NumDims - 1 : 0;\n    Index indices[2] = {index, index + PacketSize - 1};\n    Index patchIndices[2] = {indices[0] / m_outputStrides[output_stride_index],\n                             indices[1] / m_outputStrides[output_stride_index]};\n    Index patchOffsets[2] = {indices[0] - patchIndices[0] * m_outputStrides[output_stride_index],\n                             indices[1] - patchIndices[1] * m_outputStrides[output_stride_index]};\n\n    Index inputIndices[2] = {0, 0};\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 2; i > 0; --i) {\n        const Index patchIdx[2] = {patchIndices[0] / m_patchStrides[i],\n                                   patchIndices[1] / m_patchStrides[i]};\n        patchIndices[0] -= patchIdx[0] * m_patchStrides[i];\n        patchIndices[1] -= patchIdx[1] * m_patchStrides[i];\n\n        const Index offsetIdx[2] = {patchOffsets[0] / m_outputStrides[i],\n                                    patchOffsets[1] / m_outputStrides[i]};\n        patchOffsets[0] -= offsetIdx[0] * m_outputStrides[i];\n        patchOffsets[1] -= offsetIdx[1] * m_outputStrides[i];\n\n        inputIndices[0] += (patchIdx[0] + offsetIdx[0]) * m_inputStrides[i];\n        inputIndices[1] += (patchIdx[1] + offsetIdx[1]) * m_inputStrides[i];\n      }\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 2; ++i) {\n        const Index patchIdx[2] = {patchIndices[0] / m_patchStrides[i],\n                                   patchIndices[1] / m_patchStrides[i]};\n        patchIndices[0] -= patchIdx[0] * m_patchStrides[i];\n        patchIndices[1] -= patchIdx[1] * m_patchStrides[i];\n\n        const Index offsetIdx[2] = {patchOffsets[0] / m_outputStrides[i+1],\n                                    patchOffsets[1] / m_outputStrides[i+1]};\n        patchOffsets[0] -= offsetIdx[0] * m_outputStrides[i+1];\n        patchOffsets[1] -= offsetIdx[1] * m_outputStrides[i+1];\n\n        inputIndices[0] += (patchIdx[0] + offsetIdx[0]) * m_inputStrides[i];\n        inputIndices[1] += (patchIdx[1] + offsetIdx[1]) * m_inputStrides[i];\n      }\n    }\n    inputIndices[0] += (patchIndices[0] + patchOffsets[0]);\n    inputIndices[1] += (patchIndices[1] + patchOffsets[1]);\n\n    if (inputIndices[1] - inputIndices[0] == PacketSize - 1) {\n      PacketReturnType rslt = m_impl.template packet<Unaligned>(inputIndices[0]);\n      return rslt;\n    }\n    else {\n      EIGEN_ALIGN_MAX CoeffReturnType values[PacketSize];\n      values[0] = m_impl.coeff(inputIndices[0]);\n      values[PacketSize-1] = m_impl.coeff(inputIndices[1]);\n      EIGEN_UNROLL_LOOP\n      for (int i = 1; i < PacketSize-1; ++i) {\n        values[i] = coeff(index+i);\n      }\n      PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n      return rslt;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    const double compute_cost = NumDims * (TensorOpCost::DivCost<Index>() +\n                                           TensorOpCost::MulCost<Index>() +\n                                           2 * TensorOpCost::AddCost<Index>());\n    return m_impl.costPerCoeff(vectorized) +\n           TensorOpCost(0, 0, compute_cost, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh); \n  }\n#endif\n\n protected:\n  Dimensions m_dimensions;\n  array<Index, NumDims> m_outputStrides;\n  array<Index, NumDims-1> m_inputStrides;\n  array<Index, NumDims-1> m_patchStrides;\n\n  TensorEvaluator<ArgType, Device> m_impl;\n\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_PATCH_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorRandom.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n// Copyright (C) 2018 Mehdi Goli <eigen@codeplay.com> Codeplay Software Ltd.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_RANDOM_H\n#define EIGEN_CXX11_TENSOR_TENSOR_RANDOM_H\n\nnamespace Eigen {\nnamespace internal {\n\nnamespace {\n\nEIGEN_DEVICE_FUNC uint64_t get_random_seed() {\n#if defined(EIGEN_GPU_COMPILE_PHASE)\n  // We don't support 3d kernels since we currently only use 1 and\n  // 2d kernels.\n  gpu_assert(threadIdx.z == 0);\n  return clock64() +\n      blockIdx.x * blockDim.x + threadIdx.x +\n      gridDim.x * blockDim.x * (blockIdx.y * blockDim.y + threadIdx.y);\n\n#elif defined _WIN32\n  // Use the current time as a baseline.\n  SYSTEMTIME st;\n  GetSystemTime(&st);\n  int time = st.wSecond + 1000 * st.wMilliseconds;\n  // Mix in a random number to make sure that we get different seeds if\n  // we try to generate seeds faster than the clock resolution.\n  // We need 2 random values since the generator only generate 16 bits at\n  // a time (https://msdn.microsoft.com/en-us/library/398ax69y.aspx)\n  int rnd1 = ::rand();\n  int rnd2 = ::rand();\n  uint64_t rnd = (rnd1 | rnd2 << 16) ^ time;\n  return rnd;\n\n#elif defined __APPLE__\n  // Same approach as for win32, except that the random number generator\n  // is better (// https://developer.apple.com/legacy/library/documentation/Darwin/Reference/ManPages/man3/random.3.html#//apple_ref/doc/man/3/random).\n  uint64_t rnd = ::random() ^ mach_absolute_time();\n  return rnd;\n\n#elif defined __native_client__\n  // Same approach as for win32, except using clock_gettime\n  timespec ts;\n  clock_gettime(CLOCK_REALTIME, &ts);\n  int rnd1 = ::rand();\n  int rnd2 = ::rand();\n  uint64_t rnd = (rnd1 | rnd2 << 16) ^ ts.tv_nsec;\n  return rnd;\n\n#else\n  // Augment the current time with pseudo random number generation\n  // to ensure that we get different seeds if we try to generate seeds\n  // faster than the clock resolution.\n  timespec ts;\n  clock_gettime(CLOCK_REALTIME, &ts);\n  uint64_t rnd = ::random() ^ ts.tv_nsec;\n  return rnd;\n#endif\n}\n\nstatic EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE unsigned PCG_XSH_RS_generator(uint64_t* state, uint64_t stream) {\n  // TODO: Unify with the implementation in the non blocking thread pool.\n  uint64_t current = *state;\n  // Update the internal state\n  *state = current * 6364136223846793005ULL + (stream << 1 | 1);\n  // Generate the random output (using the PCG-XSH-RS scheme)\n  return static_cast<unsigned>((current ^ (current >> 22)) >> (22 + (current >> 61)));\n}\n\nstatic EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE uint64_t PCG_XSH_RS_state(uint64_t seed) {\n  seed = seed ? seed : get_random_seed();\n  return seed * 6364136223846793005ULL + 0xda3e39cb94b95bdbULL;\n}\n\n}  // namespace\n\n\ntemplate <typename T> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nT RandomToTypeUniform(uint64_t* state, uint64_t stream) {\n  unsigned rnd = PCG_XSH_RS_generator(state, stream);\n  return static_cast<T>(rnd);\n}\n\n\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nEigen::half RandomToTypeUniform<Eigen::half>(uint64_t* state, uint64_t stream) {\n  // Generate 10 random bits for the mantissa, merge with exponent.\n  unsigned rnd = PCG_XSH_RS_generator(state, stream);\n  const uint16_t half_bits = static_cast<uint16_t>(rnd & 0x3ffu) | (static_cast<uint16_t>(15) << 10);\n  Eigen::half result = Eigen::numext::bit_cast<Eigen::half>(half_bits);\n  // Return the final result\n  return result - Eigen::half(1.0f);\n}\n\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nEigen::bfloat16 RandomToTypeUniform<Eigen::bfloat16>(uint64_t* state, uint64_t stream) {\n\n  // Generate 7 random bits for the mantissa, merge with exponent.\n  unsigned rnd = PCG_XSH_RS_generator(state, stream);\n  const uint16_t half_bits = static_cast<uint16_t>(rnd & 0x7fu) | (static_cast<uint16_t>(127) << 7);\n  Eigen::bfloat16 result = Eigen::numext::bit_cast<Eigen::bfloat16>(half_bits);\n  // Return the final result\n  return result - Eigen::bfloat16(1.0f);\n}\n\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat RandomToTypeUniform<float>(uint64_t* state, uint64_t stream) {\n  typedef union {\n    uint32_t raw;\n    float fp;\n  } internal;\n  internal result;\n  // Generate 23 random bits for the mantissa mantissa\n  const unsigned rnd = PCG_XSH_RS_generator(state, stream);\n  result.raw = rnd & 0x7fffffu;\n  // Set the exponent\n  result.raw |= (static_cast<uint32_t>(127) << 23);\n  // Return the final result\n  return result.fp - 1.0f;\n}\n\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble RandomToTypeUniform<double>(uint64_t* state, uint64_t stream) {\n  typedef union {\n    uint64_t raw;\n    double dp;\n  } internal;\n  internal result;\n  result.raw = 0;\n  // Generate 52 random bits for the mantissa\n  // First generate the upper 20 bits\n  unsigned rnd1 = PCG_XSH_RS_generator(state, stream) & 0xfffffu;\n  // The generate the lower 32 bits\n  unsigned rnd2 = PCG_XSH_RS_generator(state, stream);\n  result.raw = (static_cast<uint64_t>(rnd1) << 32) | rnd2;\n  // Set the exponent\n  result.raw |= (static_cast<uint64_t>(1023) << 52);\n  // Return the final result\n  return result.dp - 1.0;\n}\n\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nstd::complex<float> RandomToTypeUniform<std::complex<float> >(uint64_t* state, uint64_t stream) {\n  return std::complex<float>(RandomToTypeUniform<float>(state, stream),\n                             RandomToTypeUniform<float>(state, stream));\n}\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nstd::complex<double> RandomToTypeUniform<std::complex<double> >(uint64_t* state, uint64_t stream) {\n  return std::complex<double>(RandomToTypeUniform<double>(state, stream),\n                              RandomToTypeUniform<double>(state, stream));\n}\n\ntemplate <typename T> class UniformRandomGenerator {\n public:\n  static const bool PacketAccess = true;\n\n  // Uses the given \"seed\" if non-zero, otherwise uses a random seed.\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE UniformRandomGenerator(\n      uint64_t seed = 0) {\n    m_state = PCG_XSH_RS_state(seed);\n    #ifdef EIGEN_USE_SYCL\n    // In SYCL it is not possible to build PCG_XSH_RS_state in one step.\n    // Therefor, we need two step to initializate the m_state.\n    // IN SYCL, the constructor of the functor is s called on the CPU\n    // and we get the clock seed here from the CPU. However, This seed is\n    //the same for all the thread. As unlike CUDA, the thread.ID, BlockID, etc is not a global function.\n    // and only  available on the Operator() function (which is called on the GPU).\n    // Thus for CUDA (((CLOCK  + global_thread_id)* 6364136223846793005ULL) + 0xda3e39cb94b95bdbULL) is passed to each thread\n    // but for SYCL ((CLOCK * 6364136223846793005ULL) + 0xda3e39cb94b95bdbULL) is passed to each thread and each thread adds\n    // the  (global_thread_id* 6364136223846793005ULL) for itself only once, in order to complete the construction\n    // similar to CUDA Therefore, the thread Id injection is not available at this stage.\n    //However when the operator() is called the thread ID will be avilable. So inside the opeator,\n    // we add the thrreadID, BlockId,... (which is equivalent of i)\n    //to the seed and construct the unique m_state per thead similar to cuda.\n    m_exec_once =false;\n   #endif\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE UniformRandomGenerator(\n      const UniformRandomGenerator& other) {\n    m_state = other.m_state;\n    #ifdef EIGEN_USE_SYCL\n     m_exec_once =other.m_exec_once;\n    #endif\n  }\n\n  template<typename Index> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  T operator()(Index i) const {\n    #ifdef EIGEN_USE_SYCL\n      if(!m_exec_once) {\n      // This is the second stage of adding thread Id to the CPU clock seed and build unique seed per thread\n      // The (i * 6364136223846793005ULL) is the remaining part of the PCG_XSH_RS_state on the GPU side\n       m_state += (i * 6364136223846793005ULL);\n       m_exec_once =true;\n      }\n    #endif\n    T result = RandomToTypeUniform<T>(&m_state, i);\n    return result;\n  }\n\n  template<typename Packet, typename Index> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  Packet packetOp(Index i) const {\n    const int packetSize = internal::unpacket_traits<Packet>::size;\n    EIGEN_ALIGN_MAX T values[packetSize];\n      #ifdef EIGEN_USE_SYCL\n      if(!m_exec_once) {\n      // This is the second stage of adding thread Id to the CPU clock seed and build unique seed per thread\n       m_state += (i * 6364136223846793005ULL);\n       m_exec_once =true;\n      }\n    #endif\n    EIGEN_UNROLL_LOOP\n    for (int j = 0; j < packetSize; ++j) {\n      values[j] = RandomToTypeUniform<T>(&m_state, i);\n    }\n    return internal::pload<Packet>(values);\n  }\n\n private:\n  mutable uint64_t m_state;\n  #ifdef EIGEN_USE_SYCL\n  mutable bool m_exec_once;\n  #endif\n};\n\ntemplate <typename Scalar>\nstruct functor_traits<UniformRandomGenerator<Scalar> > {\n  enum {\n    // Rough estimate for floating point, multiplied by ceil(sizeof(T) / sizeof(float)).\n    Cost = 12 * NumTraits<Scalar>::AddCost *\n           ((sizeof(Scalar) + sizeof(float) - 1) / sizeof(float)),\n    PacketAccess = UniformRandomGenerator<Scalar>::PacketAccess\n  };\n};\n\n\n\ntemplate <typename T> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nT RandomToTypeNormal(uint64_t* state, uint64_t stream) {\n  // Use the ratio of uniform method to generate numbers following a normal\n  // distribution. See for example Numerical Recipes chapter 7.3.9 for the\n  // details.\n  T u, v, q;\n  do {\n    u = RandomToTypeUniform<T>(state, stream);\n    v = T(1.7156) * (RandomToTypeUniform<T>(state, stream) - T(0.5));\n    const T x = u - T(0.449871);\n    const T y = numext::abs(v) + T(0.386595);\n    q = x*x + y * (T(0.196)*y - T(0.25472)*x);\n  } while (q > T(0.27597) &&\n           (q > T(0.27846) || v*v > T(-4) * numext::log(u) * u*u));\n\n  return v/u;\n}\n\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nstd::complex<float> RandomToTypeNormal<std::complex<float> >(uint64_t* state, uint64_t stream) {\n  return std::complex<float>(RandomToTypeNormal<float>(state, stream),\n                             RandomToTypeNormal<float>(state, stream));\n}\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nstd::complex<double> RandomToTypeNormal<std::complex<double> >(uint64_t* state, uint64_t stream) {\n  return std::complex<double>(RandomToTypeNormal<double>(state, stream),\n                              RandomToTypeNormal<double>(state, stream));\n}\n\n\ntemplate <typename T> class NormalRandomGenerator {\n public:\n  static const bool PacketAccess = true;\n\n  // Uses the given \"seed\" if non-zero, otherwise uses a random seed.\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE NormalRandomGenerator(uint64_t seed = 0) {\n    m_state = PCG_XSH_RS_state(seed);\n    #ifdef EIGEN_USE_SYCL\n    // In SYCL it is not possible to build PCG_XSH_RS_state in one step.\n    // Therefor, we need two steps to initializate the m_state.\n    // IN SYCL, the constructor of the functor is s called on the CPU\n    // and we get the clock seed here from the CPU. However, This seed is\n    //the same for all the thread. As unlike CUDA, the thread.ID, BlockID, etc is not a global function.\n    // and only  available on the Operator() function (which is called on the GPU).\n    // Therefore, the thread Id injection is not available at this stage. However when the operator()\n    //is called the thread ID will be avilable. So inside the opeator,\n    // we add the thrreadID, BlockId,... (which is equivalent of i)\n    //to the seed and construct the unique m_state per thead similar to cuda.\n    m_exec_once =false;\n   #endif\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE NormalRandomGenerator(\n      const NormalRandomGenerator& other) {\n    m_state = other.m_state;\n#ifdef EIGEN_USE_SYCL\n    m_exec_once=other.m_exec_once;\n#endif\n  }\n\n template<typename Index> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  T operator()(Index i) const {\n    #ifdef EIGEN_USE_SYCL\n    if(!m_exec_once) {\n      // This is the second stage of adding thread Id to the CPU clock seed and build unique seed per thread\n      m_state += (i * 6364136223846793005ULL);\n      m_exec_once =true;\n    }\n    #endif\n    T result = RandomToTypeNormal<T>(&m_state, i);\n    return result;\n  }\n\n  template<typename Packet, typename Index> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  Packet packetOp(Index i) const {\n    const int packetSize = internal::unpacket_traits<Packet>::size;\n    EIGEN_ALIGN_MAX T values[packetSize];\n    #ifdef EIGEN_USE_SYCL\n    if(!m_exec_once) {\n      // This is the second stage of adding thread Id to the CPU clock seed and build unique seed per thread\n      m_state += (i * 6364136223846793005ULL);\n      m_exec_once =true;\n    }\n    #endif\n    EIGEN_UNROLL_LOOP\n    for (int j = 0; j < packetSize; ++j) {\n      values[j] = RandomToTypeNormal<T>(&m_state, i);\n    }\n    return internal::pload<Packet>(values);\n  }\n\n private:\n  mutable uint64_t m_state;\n   #ifdef EIGEN_USE_SYCL\n  mutable bool m_exec_once;\n  #endif\n};\n\n\ntemplate <typename Scalar>\nstruct functor_traits<NormalRandomGenerator<Scalar> > {\n  enum {\n    // On average, we need to generate about 3 random numbers\n    // 15 mul, 8 add, 1.5 logs\n    Cost = 3 * functor_traits<UniformRandomGenerator<Scalar> >::Cost +\n           15 * NumTraits<Scalar>::AddCost + 8 * NumTraits<Scalar>::AddCost +\n           3 * functor_traits<scalar_log_op<Scalar> >::Cost / 2,\n    PacketAccess = NormalRandomGenerator<Scalar>::PacketAccess\n  };\n};\n\n\n} // end namespace internal\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_RANDOM_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReduction.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n// Copyright (C) 2016 Mehdi Goli, Codeplay Software Ltd <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_H\n#define EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_H\n\n// clang is incompatible with the CUDA syntax wrt making a kernel a class friend,\n// so we'll use a macro to make clang happy.\n#ifndef KERNEL_FRIEND\n#if defined(__clang__) && (defined(__CUDA__) || defined(__HIP__))\n#define KERNEL_FRIEND friend __global__ EIGEN_HIP_LAUNCH_BOUNDS_1024\n#else\n#define KERNEL_FRIEND friend\n#endif\n#endif\n\n\nnamespace Eigen {\n\n\n/** \\class TensorReduction\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor reduction class.\n  *\n  */\n\nnamespace internal {\n  template<typename Op, typename Dims, typename XprType,template <class> class MakePointer_ >\n  struct traits<TensorReductionOp<Op, Dims, XprType, MakePointer_> >\n : traits<XprType>\n{\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::Scalar Scalar;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  static const int NumDimensions = XprTraits::NumDimensions - array_size<Dims>::value;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n\n  template <class T> struct MakePointer {\n    // Intermediate typedef to workaround MSVC issue.\n    typedef MakePointer_<T> MakePointerT;\n    typedef typename MakePointerT::Type Type;\n  };\n};\n\ntemplate<typename Op, typename Dims, typename XprType, template <class> class MakePointer_>\nstruct eval<TensorReductionOp<Op, Dims, XprType, MakePointer_>, Eigen::Dense>\n{\n  typedef const TensorReductionOp<Op, Dims, XprType, MakePointer_>& type;\n};\n\ntemplate<typename Op, typename Dims, typename XprType, template <class> class MakePointer_>\nstruct nested<TensorReductionOp<Op, Dims, XprType, MakePointer_>, 1, typename eval<TensorReductionOp<Op, Dims, XprType, MakePointer_> >::type>\n{\n  typedef TensorReductionOp<Op, Dims, XprType, MakePointer_> type;\n};\n\n\ntemplate <typename OutputDims> struct DimInitializer {\n  template <typename InputDims, typename ReducedDims> EIGEN_DEVICE_FUNC\n  static void run(const InputDims& input_dims,\n                  const array<bool, internal::array_size<InputDims>::value>& reduced,\n                  OutputDims* output_dims, ReducedDims* reduced_dims) {\n    const int NumInputDims = internal::array_size<InputDims>::value;\n    int outputIndex = 0;\n    int reduceIndex = 0;\n    for (int i = 0; i < NumInputDims; ++i) {\n      if (reduced[i]) {\n        (*reduced_dims)[reduceIndex] = input_dims[i];\n        ++reduceIndex;\n      } else {\n        (*output_dims)[outputIndex] = input_dims[i];\n        ++outputIndex;\n      }\n    }\n  }\n};\n\ntemplate <> struct DimInitializer<Sizes<> > {\n  template <typename InputDims, typename Index, size_t Rank> EIGEN_DEVICE_FUNC\n  static void run(const InputDims& input_dims, const array<bool, Rank>&,\n                  Sizes<>*, array<Index, Rank>* reduced_dims) {\n    const int NumInputDims = internal::array_size<InputDims>::value;\n    for (int i = 0; i < NumInputDims; ++i) {\n      (*reduced_dims)[i] = input_dims[i];\n    }\n  }\n};\n\n\ntemplate <typename ReducedDims, int NumTensorDims, int Layout>\nstruct are_inner_most_dims {\n  static const bool value = false;\n};\ntemplate <typename ReducedDims, int NumTensorDims, int Layout>\nstruct preserve_inner_most_dims {\n  static const bool value = false;\n};\n\n#if EIGEN_HAS_CONSTEXPR && EIGEN_HAS_VARIADIC_TEMPLATES\ntemplate <typename ReducedDims, int NumTensorDims>\nstruct are_inner_most_dims<ReducedDims, NumTensorDims, ColMajor>{\n  static const bool tmp1 = indices_statically_known_to_increase<ReducedDims>();\n  static const bool tmp2 = index_statically_eq<ReducedDims>(0, 0);\n  static const bool tmp3 = index_statically_eq<ReducedDims>(array_size<ReducedDims>::value-1, array_size<ReducedDims>::value-1);\n  static const bool value = tmp1 & tmp2 & tmp3;\n};\ntemplate <typename ReducedDims, int NumTensorDims>\nstruct are_inner_most_dims<ReducedDims, NumTensorDims, RowMajor>{\n  static const bool tmp1 = indices_statically_known_to_increase<ReducedDims>();\n  static const bool tmp2 = index_statically_eq<ReducedDims>(0, NumTensorDims - array_size<ReducedDims>::value);\n  static const bool tmp3 = index_statically_eq<ReducedDims>(array_size<ReducedDims>::value - 1, NumTensorDims - 1);\n  static const bool value = tmp1 & tmp2 & tmp3;\n\n};\ntemplate <typename ReducedDims, int NumTensorDims>\nstruct preserve_inner_most_dims<ReducedDims, NumTensorDims, ColMajor>{\n  static const bool tmp1 = indices_statically_known_to_increase<ReducedDims>();\n  static const bool tmp2 = index_statically_gt<ReducedDims>(0, 0);\n  static const bool value = tmp1 & tmp2;\n\n};\ntemplate <typename ReducedDims, int NumTensorDims>\nstruct preserve_inner_most_dims<ReducedDims, NumTensorDims, RowMajor>{\n  static const bool tmp1 = indices_statically_known_to_increase<ReducedDims>();\n  static const bool tmp2 = index_statically_lt<ReducedDims>(array_size<ReducedDims>::value - 1, NumTensorDims - 1);\n  static const bool value = tmp1 & tmp2;\n};\n#endif\n\n\ntemplate <int DimIndex, typename Self, typename Op>\nstruct GenericDimReducer {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self& self, typename Self::Index firstIndex, Op& reducer, typename Self::CoeffReturnType* accum) {\n    EIGEN_STATIC_ASSERT((DimIndex > 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    for (int j = 0; j < self.m_reducedDims[DimIndex]; ++j) {\n      const typename Self::Index input = firstIndex + j * self.m_reducedStrides[DimIndex];\n      GenericDimReducer<DimIndex-1, Self, Op>::reduce(self, input, reducer, accum);\n    }\n  }\n};\ntemplate <typename Self, typename Op>\nstruct GenericDimReducer<0, Self, Op> {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self& self, typename Self::Index firstIndex, Op& reducer, typename Self::CoeffReturnType* accum) {\n    for (int j = 0; j < self.m_reducedDims[0]; ++j) {\n      const typename Self::Index input = firstIndex + j * self.m_reducedStrides[0];\n      reducer.reduce(self.m_impl.coeff(input), accum);\n    }\n  }\n};\ntemplate <typename Self, typename Op>\nstruct GenericDimReducer<-1, Self, Op> {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self& self, typename Self::Index index, Op& reducer, typename Self::CoeffReturnType* accum) {\n    reducer.reduce(self.m_impl.coeff(index), accum);\n  }\n};\n\ntemplate <typename Self, typename Op, bool Vectorizable = (Self::InputPacketAccess && Self::ReducerTraits::PacketAccess),\n          bool UseTreeReduction = (!Self::ReducerTraits::IsStateful &&\n                                   !Self::ReducerTraits::IsExactlyAssociative)>\nstruct InnerMostDimReducer {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Self::CoeffReturnType reduce(const Self& self, typename Self::Index firstIndex, typename Self::Index numValuesToReduce, Op& reducer) {\n    typename Self::CoeffReturnType accum = reducer.initialize();\n    for (typename Self::Index j = 0; j < numValuesToReduce; ++j) {\n      reducer.reduce(self.m_impl.coeff(firstIndex + j), &accum);\n    }\n    return reducer.finalize(accum);\n  }\n};\n\ntemplate <typename Self, typename Op>\nstruct InnerMostDimReducer<Self, Op, true, false> {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Self::CoeffReturnType reduce(const Self& self, typename Self::Index firstIndex, typename Self::Index numValuesToReduce, Op& reducer) {\n    const typename Self::Index packetSize = internal::unpacket_traits<typename Self::PacketReturnType>::size;\n    const typename Self::Index VectorizedSize = (numValuesToReduce / packetSize) * packetSize;\n    typename Self::PacketReturnType paccum = reducer.template initializePacket<typename Self::PacketReturnType>();\n    for (typename Self::Index j = 0; j < VectorizedSize; j += packetSize) {\n      reducer.reducePacket(self.m_impl.template packet<Unaligned>(firstIndex + j), &paccum);\n    }\n    typename Self::CoeffReturnType accum = reducer.initialize();\n    for (typename Self::Index j = VectorizedSize; j < numValuesToReduce; ++j) {\n      reducer.reduce(self.m_impl.coeff(firstIndex + j), &accum);\n    }\n    return reducer.finalizeBoth(accum, paccum);\n  }\n};\n\n#if !defined(EIGEN_HIPCC) \nstatic const int kLeafSize = 1024;\n\ntemplate <typename Self, typename Op>\nstruct InnerMostDimReducer<Self, Op, false, true> {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Self::CoeffReturnType\n  reduce(const Self& self, typename Self::Index firstIndex,\n         typename Self::Index numValuesToReduce, Op& reducer) {\n    typename Self::CoeffReturnType accum = reducer.initialize();\n    if (numValuesToReduce > kLeafSize) {\n      const typename Self::Index half = numValuesToReduce / 2;\n      reducer.reduce(reduce(self, firstIndex, half, reducer), &accum);\n      reducer.reduce(\n          reduce(self, firstIndex + half, numValuesToReduce - half, reducer),\n          &accum);\n    } else {\n      for (typename Self::Index j = 0; j < numValuesToReduce; ++j) {\n        reducer.reduce(self.m_impl.coeff(firstIndex + j), &accum);\n      }\n    }\n    return reducer.finalize(accum);\n  }\n};\n\ntemplate <typename Self, typename Op>\nstruct InnerMostDimReducer<Self, Op, true, true> {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Self::CoeffReturnType\n  reduce(const Self& self, typename Self::Index firstIndex,\n         typename Self::Index numValuesToReduce, Op& reducer) {\n    const typename Self::Index packetSize =\n        internal::unpacket_traits<typename Self::PacketReturnType>::size;\n    typename Self::CoeffReturnType accum = reducer.initialize();\n    if (numValuesToReduce > packetSize * kLeafSize) {\n      // Make sure the split point is aligned on a packet boundary.\n      const typename Self::Index split =\n          packetSize *\n          divup(firstIndex + divup(numValuesToReduce, typename Self::Index(2)),\n                packetSize);\n      const typename Self::Index num_left =\n          numext::mini(split - firstIndex, numValuesToReduce);\n      reducer.reduce(reduce(self, firstIndex, num_left, reducer), &accum);\n      if (num_left < numValuesToReduce) {\n        reducer.reduce(\n            reduce(self, split, numValuesToReduce - num_left, reducer), &accum);\n      }\n      return reducer.finalize(accum);\n    } else {\n      const typename Self::Index UnrollSize =\n          (numValuesToReduce / (2*packetSize)) * 2*packetSize;\n      const typename Self::Index VectorizedSize =\n          (numValuesToReduce / packetSize) * packetSize;\n      typename Self::PacketReturnType paccum =\n          reducer.template initializePacket<typename Self::PacketReturnType>();\n      typename Self::PacketReturnType paccum2 =\n          reducer.template initializePacket<typename Self::PacketReturnType>();\n      for (typename Self::Index j = 0; j < UnrollSize; j += packetSize * 2) {\n        reducer.reducePacket(\n            self.m_impl.template packet<Unaligned>(firstIndex + j), &paccum);\n        reducer.reducePacket(\n            self.m_impl.template packet<Unaligned>(firstIndex + j + packetSize),\n            &paccum2);\n      }\n      for (typename Self::Index j = UnrollSize; j < VectorizedSize; j+= packetSize) {\n        reducer.reducePacket(self.m_impl.template packet<Unaligned>(\n                                 firstIndex + j), &paccum);\n      }\n      reducer.reducePacket(paccum2, &paccum);\n      for (typename Self::Index j = VectorizedSize; j < numValuesToReduce;\n           ++j) {\n        reducer.reduce(self.m_impl.coeff(firstIndex + j), &accum);\n      }\n      return reducer.finalizeBoth(accum, paccum);\n    }\n  }\n};\n#endif\n \ntemplate <int DimIndex, typename Self, typename Op, bool vectorizable = (Self::InputPacketAccess && Self::ReducerTraits::PacketAccess)>\nstruct InnerMostDimPreserver {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self&, typename Self::Index, Op&, typename Self::PacketReturnType*) {\n    eigen_assert(false && \"should never be called\");\n  }\n};\n\ntemplate <int DimIndex, typename Self, typename Op>\nstruct InnerMostDimPreserver<DimIndex, Self, Op, true> {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self& self, typename Self::Index firstIndex, Op& reducer, typename Self::PacketReturnType* accum) {\n    EIGEN_STATIC_ASSERT((DimIndex > 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    for (typename Self::Index j = 0; j < self.m_reducedDims[DimIndex]; ++j) {\n      const typename Self::Index input = firstIndex + j * self.m_reducedStrides[DimIndex];\n      InnerMostDimPreserver<DimIndex-1, Self, Op>::reduce(self, input, reducer, accum);\n    }\n  }\n};\n\ntemplate <typename Self, typename Op>\nstruct InnerMostDimPreserver<0, Self, Op, true> {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self& self, typename Self::Index firstIndex, Op& reducer, typename Self::PacketReturnType* accum) {\n    for (typename Self::Index j = 0; j < self.m_reducedDims[0]; ++j) {\n      const typename Self::Index input = firstIndex + j * self.m_reducedStrides[0];\n      reducer.reducePacket(self.m_impl.template packet<Unaligned>(input), accum);\n    }\n  }\n};\ntemplate <typename Self, typename Op>\nstruct InnerMostDimPreserver<-1, Self, Op, true> {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const Self&, typename Self::Index, Op&, typename Self::PacketReturnType*) {\n    eigen_assert(false && \"should never be called\");\n  }\n};\n\n// Default full reducer\ntemplate <typename Self, typename Op, typename Device, bool Vectorizable = (Self::InputPacketAccess && Self::ReducerTraits::PacketAccess)>\nstruct FullReducer {\n  static const bool HasOptimizedImplementation = false;\n\n  static EIGEN_DEVICE_FUNC void run(const Self& self, Op& reducer, const Device&, typename Self::EvaluatorPointerType output) {\n    const typename Self::Index num_coeffs = array_prod(self.m_impl.dimensions());\n    *output = InnerMostDimReducer<Self, Op, Vectorizable>::reduce(self, 0, num_coeffs, reducer);\n  }\n};\n\n\n#ifdef EIGEN_USE_THREADS\n// Multithreaded full reducers\ntemplate <typename Self, typename Op,\n          bool Vectorizable = (Self::InputPacketAccess && Self::ReducerTraits::PacketAccess)>\nstruct FullReducerShard {\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void run(const Self& self, typename Self::Index firstIndex,\n                  typename Self::Index numValuesToReduce, Op& reducer,\n                  typename Self::CoeffReturnType* output) {\n    *output = InnerMostDimReducer<Self, Op, Vectorizable>::reduce(\n        self, firstIndex, numValuesToReduce, reducer);\n  }\n};\n\n// Multithreaded full reducer\ntemplate <typename Self, typename Op, bool Vectorizable>\nstruct FullReducer<Self, Op, ThreadPoolDevice, Vectorizable> {\n  static const bool HasOptimizedImplementation = !Self::ReducerTraits::IsStateful;\n  static const Index PacketSize =\n      unpacket_traits<typename Self::PacketReturnType>::size;\n\n  // launch one reducer per thread and accumulate the result.\n  static void run(const Self& self, Op& reducer, const ThreadPoolDevice& device,\n                  typename Self::CoeffReturnType* output) {\n    typedef typename Self::Index Index;\n    const Index num_coeffs = array_prod(self.m_impl.dimensions());\n    if (num_coeffs == 0) {\n      *output = reducer.finalize(reducer.initialize());\n      return;\n    }\n    const TensorOpCost cost =\n        self.m_impl.costPerCoeff(Vectorizable) +\n        TensorOpCost(0, 0, internal::functor_traits<Op>::Cost, Vectorizable,\n                     PacketSize);\n    const int num_threads = TensorCostModel<ThreadPoolDevice>::numThreads(\n        num_coeffs, cost, device.numThreads());\n    if (num_threads == 1) {\n      *output =\n          InnerMostDimReducer<Self, Op, Vectorizable>::reduce(self, 0, num_coeffs, reducer);\n      return;\n    }\n    const Index blocksize =\n        std::floor<Index>(static_cast<float>(num_coeffs) / num_threads);\n    const Index numblocks = blocksize > 0 ? num_coeffs / blocksize : 0;\n    eigen_assert(num_coeffs >= numblocks * blocksize);\n\n    Barrier barrier(internal::convert_index<unsigned int>(numblocks));\n    MaxSizeVector<typename Self::CoeffReturnType> shards(numblocks, reducer.initialize());\n    for (Index i = 0; i < numblocks; ++i) {\n      device.enqueue_with_barrier(&barrier, &FullReducerShard<Self, Op, Vectorizable>::run,\n                                  self, i * blocksize, blocksize, reducer,\n                                  &shards[i]);\n    }\n    typename Self::CoeffReturnType finalShard;\n    if (numblocks * blocksize < num_coeffs) {\n      finalShard = InnerMostDimReducer<Self, Op, Vectorizable>::reduce(\n          self, numblocks * blocksize, num_coeffs - numblocks * blocksize,\n          reducer);\n    } else {\n      finalShard = reducer.initialize();\n    }\n    barrier.Wait();\n\n    for (Index i = 0; i < numblocks; ++i) {\n      reducer.reduce(shards[i], &finalShard);\n    }\n    *output = reducer.finalize(finalShard);\n  }\n};\n\n#endif\n\n\n// Default inner reducer\ntemplate <typename Self, typename Op, typename Device>\nstruct InnerReducer {\n  static const bool HasOptimizedImplementation = false;\n\n  EIGEN_DEVICE_FUNC static bool run(const Self&, Op&, const Device&, typename Self::CoeffReturnType*, typename Self::Index, typename Self::Index) {\n    eigen_assert(false && \"Not implemented\");\n    return true;\n  }\n};\n\n// Default outer reducer\ntemplate <typename Self, typename Op, typename Device>\nstruct OuterReducer {\n  static const bool HasOptimizedImplementation = false;\n\n  EIGEN_DEVICE_FUNC static bool run(const Self&, Op&, const Device&, typename Self::CoeffReturnType*, typename Self::Index, typename Self::Index) {\n    eigen_assert(false && \"Not implemented\");\n    return true;\n  }\n};\n\n#ifdef EIGEN_USE_SYCL\n// Default Generic reducer\ntemplate <typename Self, typename Op, typename Device>\nstruct GenericReducer {\n  static const bool HasOptimizedImplementation = false;\n\n  EIGEN_DEVICE_FUNC static bool run(const Self&, Op&, const Device&, typename Self::CoeffReturnType*, typename Self::Index, typename Self::Index) {\n    eigen_assert(false && \"Not implemented\");\n    return true;\n  }\n};\n#endif\n\n#if defined(EIGEN_USE_GPU) && (defined(EIGEN_GPUCC))\ntemplate <int B, int N, typename S, typename R, typename I_>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void FullReductionKernel(R, const S, I_, typename S::CoeffReturnType*, unsigned int*);\n\n\n#if defined(EIGEN_HAS_GPU_FP16)\ntemplate <typename S, typename R, typename I_>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void ReductionInitFullReduxKernelHalfFloat(R, const S, I_, internal::packet_traits<half>::type*);\ntemplate <int B, int N, typename S, typename R, typename I_>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void FullReductionKernelHalfFloat(R, const S, I_, half*, internal::packet_traits<half>::type*);\ntemplate <int NPT, typename S, typename R, typename I_>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void InnerReductionKernelHalfFloat(R, const S, I_, I_, half*);\n\n#endif\n\ntemplate <int NPT, typename S, typename R, typename I_>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void InnerReductionKernel(R, const S, I_, I_, typename S::CoeffReturnType*);\n\ntemplate <int NPT, typename S, typename R, typename I_>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void OuterReductionKernel(R, const S, I_, I_, typename S::CoeffReturnType*);\n#endif\n\n/**\n * For SYCL, the return type of the reduction is deduced from the initialize method of the given Op.\n * This allows the reduction to have a different type for the accumulator than the input data type.\n * If this is the case, the functor needs to have two reduce method: one for reducing an element of the input\n * with the accumulator and the other for reducing two accumulators.\n * Such a reducer can be useful for instance when the accumulator is a boolean or a bitset that checks for\n * some properties of the input.\n */\ntemplate <typename Op, typename CoeffReturnType>\nstruct ReductionReturnType {\n#if defined(EIGEN_USE_SYCL)\n  typedef typename remove_const<decltype(std::declval<Op>().initialize())>::type type;\n#else\n  typedef typename remove_const<CoeffReturnType>::type type;\n#endif\n};\n\n}  // end namespace internal\n\n\ntemplate <typename Op, typename Dims, typename XprType,  template <class> class MakePointer_>\nclass TensorReductionOp : public TensorBase<TensorReductionOp<Op, Dims, XprType, MakePointer_>, ReadOnlyAccessors> {\n  public:\n    typedef typename Eigen::internal::traits<TensorReductionOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef typename internal::remove_const<typename XprType::CoeffReturnType>::type CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorReductionOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorReductionOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorReductionOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorReductionOp(const XprType& expr, const Dims& dims) : m_expr(expr), m_dims(dims)\n    { }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    TensorReductionOp(const XprType& expr, const Dims& dims, const Op& reducer) : m_expr(expr), m_dims(dims), m_reducer(reducer)\n    { }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const XprType& expression() const { return m_expr; }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const Dims& dims() const { return m_dims; }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const Op& reducer() const { return m_reducer; }\n\n  protected:\n    typename XprType::Nested m_expr;\n    const Dims m_dims;\n    const Op m_reducer;\n};\n\ntemplate<typename ArgType, typename Device>\nstruct TensorReductionEvaluatorBase;\n\n// Eval as rvalue\ntemplate<typename Op, typename Dims, typename ArgType, template <class> class MakePointer_, typename Device>\nstruct TensorReductionEvaluatorBase<const TensorReductionOp<Op, Dims, ArgType, MakePointer_>, Device>\n{\n  typedef internal::reducer_traits<Op, Device> ReducerTraits;\n  typedef Dims ReducedDims;\n  typedef TensorReductionOp<Op, Dims, ArgType, MakePointer_> XprType;\n  typedef typename XprType::Index Index;\n  typedef ArgType ChildType;\n  typedef typename TensorEvaluator<ArgType, Device>::Dimensions InputDimensions;\n  static const int NumInputDims = internal::array_size<InputDimensions>::value;\n  static const int NumReducedDims = internal::array_size<Dims>::value;\n  static const int NumOutputDims = NumInputDims - NumReducedDims;\n  typedef typename internal::conditional<NumOutputDims==0, Sizes<>, DSizes<Index, NumOutputDims> >::type Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef TensorReductionEvaluatorBase<const TensorReductionOp<Op, Dims, ArgType, MakePointer_>, Device> Self;\n  static const bool InputPacketAccess = TensorEvaluator<ArgType, Device>::PacketAccess;\n  typedef typename internal::ReductionReturnType<Op, typename XprType::CoeffReturnType>::type CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const Index PacketSize = PacketType<CoeffReturnType, Device>::size;\n\n  typedef typename Eigen::internal::traits<XprType>::PointerType TensorPointerType;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n    // Subset of strides of the input tensor for the non-reduced dimensions.\n  // Indexed by output dimensions.\n  static const int NumPreservedStrides = max_n_1<NumOutputDims>::size;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = Self::InputPacketAccess && ReducerTraits::PacketAccess,\n    BlockAccess = false,\n    PreferBlockAccess = true,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  static const bool ReducingInnerMostDims = internal::are_inner_most_dims<Dims, NumInputDims, Layout>::value;\n  static const bool PreservingInnerMostDims = internal::preserve_inner_most_dims<Dims, NumInputDims, Layout>::value;\n  static const bool RunningFullReduction = (NumOutputDims==0);\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorReductionEvaluatorBase(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device), m_reducer(op.reducer()), m_result(NULL), m_device(device)\n  {\n    EIGEN_STATIC_ASSERT((NumInputDims >= NumReducedDims), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    EIGEN_STATIC_ASSERT((!ReducingInnerMostDims | !PreservingInnerMostDims | (NumReducedDims == NumInputDims)),\n                        YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    // Build the bitmap indicating if an input dimension is reduced or not.\n    for (int i = 0; i < NumInputDims; ++i) {\n      m_reduced[i] = false;\n    }\n    for (int i = 0; i < NumReducedDims; ++i) {\n      eigen_assert(op.dims()[i] >= 0);\n      eigen_assert(op.dims()[i] < NumInputDims);\n      m_reduced[op.dims()[i]] = true;\n    }\n\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n    internal::DimInitializer<Dimensions>::run(input_dims, m_reduced, &m_dimensions, &m_reducedDims);\n\n    // Precompute output strides.\n    if (NumOutputDims > 0) {\n      if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n        m_outputStrides[0] = 1;\n        for (int i = 1; i < NumOutputDims; ++i) {\n          m_outputStrides[i] = m_outputStrides[i - 1] * m_dimensions[i - 1];\n          m_fastOutputStrides[i] = internal::TensorIntDivisor<Index>(m_outputStrides[i]);\n        }\n      } else {\n        m_outputStrides[NumOutputDims - 1] = 1;\n        for (int i = NumOutputDims - 2; i >= 0; --i) {\n          m_outputStrides[i] = m_outputStrides[i + 1] * m_dimensions[i + 1];\n          m_fastOutputStrides[i] = internal::TensorIntDivisor<Index>(m_outputStrides[i]);\n        }\n      }\n    }\n\n    // Precompute input strides.\n    if (NumInputDims > 0) {\n      array<Index, NumInputDims> input_strides;\n      if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n        input_strides[0] = 1;\n        for (int i = 1; i < NumInputDims; ++i) {\n          input_strides[i] = input_strides[i-1] * input_dims[i-1];\n        }\n      } else {\n        input_strides.back() = 1;\n        for (int i = NumInputDims - 2; i >= 0; --i) {\n          input_strides[i] = input_strides[i + 1] * input_dims[i + 1];\n        }\n      }\n\n      int outputIndex = 0;\n      int reduceIndex = 0;\n      for (int i = 0; i < NumInputDims; ++i) {\n        if (m_reduced[i]) {\n          m_reducedStrides[reduceIndex] = input_strides[i];\n          ++reduceIndex;\n        } else {\n          m_preservedStrides[outputIndex] = input_strides[i];\n          m_output_to_input_dim_map[outputIndex] = i;\n          ++outputIndex;\n        }\n      }\n    }\n\n    // Special case for full reductions\n    if (NumOutputDims == 0) {\n      m_preservedStrides[0] = internal::array_prod(input_dims);\n    }\n\n    m_numValuesToReduce =\n        NumOutputDims == 0\n            ? internal::array_prod(input_dims)\n            : (static_cast<int>(Layout) == static_cast<int>(ColMajor))\n                  ? m_preservedStrides[0]\n                  : m_preservedStrides[NumOutputDims - 1];\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_STRONG_INLINE\n#if !defined(EIGEN_HIPCC)\n  // Marking this as EIGEN_DEVICE_FUNC for HIPCC requires also doing the same\n  // for all the functions being called within here, which then leads to\n  // proliferation of EIGEN_DEVICE_FUNC markings, one of which will eventually\n  // result in an NVCC error\n  EIGEN_DEVICE_FUNC\n#endif\n  bool evalSubExprsIfNeededCommon(EvaluatorPointerType data) {\n    // Use the FullReducer if possible.\n    if ((RunningFullReduction && RunningOnSycl) ||(RunningFullReduction &&\n        internal::FullReducer<Self, Op, Device>::HasOptimizedImplementation &&\n        ((RunningOnGPU && (m_device.majorDeviceVersion() >= 3)) ||\n         !RunningOnGPU))) {\n      bool need_assign = false;\n      if (!data) {\n        m_result = static_cast<EvaluatorPointerType>(m_device.get((CoeffReturnType*)m_device.allocate_temp(sizeof(CoeffReturnType))));\n        data = m_result;\n        need_assign = true;\n      }\n      Op reducer(m_reducer);\n      internal::FullReducer<Self, Op, Device>::run(*this, reducer, m_device, data);\n      return need_assign;\n    }\n\n    // Attempt to use an optimized reduction.\n    else if ((RunningOnGPU && (m_device.majorDeviceVersion() >= 3)) || (RunningOnSycl)) {\n      bool reducing_inner_dims = true;\n      for (int i = 0; i < NumReducedDims; ++i) {\n        if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n          reducing_inner_dims &= m_reduced[i];\n        } else {\n          reducing_inner_dims &= m_reduced[NumInputDims - 1 - i];\n        }\n      }\n      if (internal::InnerReducer<Self, Op, Device>::HasOptimizedImplementation &&\n          (reducing_inner_dims || ReducingInnerMostDims)) {\n        const Index num_values_to_reduce = internal::array_prod(m_reducedDims);\n        const Index num_coeffs_to_preserve = internal::array_prod(m_dimensions);\n        if (!data) {\n          if ((num_coeffs_to_preserve < 1024 && num_values_to_reduce > num_coeffs_to_preserve && num_values_to_reduce > 128) || (RunningOnSycl)) {\n            data = static_cast<EvaluatorPointerType>(m_device.get((CoeffReturnType*)m_device.allocate_temp(sizeof(CoeffReturnType) * num_coeffs_to_preserve)));\n            m_result = data;\n          }\n          else {\n            return true;\n          }\n        }\n        Op reducer(m_reducer);\n        // For SYCL this if always return false\n        if (internal::InnerReducer<Self, Op, Device>::run(*this, reducer, m_device, data, num_values_to_reduce, num_coeffs_to_preserve)) {\n          if (m_result) {\n            m_device.deallocate_temp(m_result);\n            m_result = NULL;\n          }\n          return true;\n        } else {\n          return (m_result != NULL);\n        }\n      }\n\n      bool preserving_inner_dims = true;\n      for (int i = 0; i < NumReducedDims; ++i) {\n        if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n          preserving_inner_dims &= m_reduced[NumInputDims - 1 - i];\n        } else {\n          preserving_inner_dims &= m_reduced[i];\n        }\n      }\n      if (internal::OuterReducer<Self, Op, Device>::HasOptimizedImplementation &&\n          preserving_inner_dims) {\n        const Index num_values_to_reduce = internal::array_prod(m_reducedDims);\n        const Index num_coeffs_to_preserve = internal::array_prod(m_dimensions);\n        if (!data) {\n          if ((num_coeffs_to_preserve < 1024 && num_values_to_reduce > num_coeffs_to_preserve && num_values_to_reduce > 32) || (RunningOnSycl)) {\n            data = static_cast<EvaluatorPointerType>(m_device.get((CoeffReturnType*)m_device.allocate_temp(sizeof(CoeffReturnType) * num_coeffs_to_preserve)));\n            m_result = data;\n          }\n          else {\n            return true;\n          }\n        }\n        Op reducer(m_reducer);\n        // For SYCL this if always return false\n        if (internal::OuterReducer<Self, Op, Device>::run(*this, reducer, m_device, data, num_values_to_reduce, num_coeffs_to_preserve)) {\n          if (m_result) {\n            m_device.deallocate_temp(m_result);\n            m_result = NULL;\n          }\n          return true;\n        } else {\n          return (m_result != NULL);\n        }\n      }\n      #if defined(EIGEN_USE_SYCL)\n      // If there is no Optimised version for SYCL, the reduction expression \n      // must break into two subexpression and use the SYCL generic Reducer on the device.\n      if(RunningOnSycl) {\n         const Index num_values_to_reduce = internal::array_prod(m_reducedDims);\n         const Index num_coeffs_to_preserve = internal::array_prod(m_dimensions);\n         if (!data) {\n           data = static_cast<EvaluatorPointerType>(m_device.get((CoeffReturnType*)m_device.allocate_temp(sizeof(CoeffReturnType) * num_coeffs_to_preserve)));\n           m_result = data;\n         }\n         Op reducer(m_reducer);\n         internal::GenericReducer<Self, Op, Device>::run(*this, reducer, m_device, data, num_values_to_reduce, num_coeffs_to_preserve);\n         return (m_result != NULL);\n       }\n      #endif\n    }\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_STRONG_INLINE\n#if !defined(EIGEN_HIPCC)\n      EIGEN_DEVICE_FUNC\n#endif\n      void\n      evalSubExprsIfNeededAsync(EvaluatorPointerType data,\n                                EvalSubExprsCallback done) {\n    m_impl.evalSubExprsIfNeededAsync(NULL, [this, data, done](bool) {\n      done(evalSubExprsIfNeededCommon(data));\n    });\n  }\n#endif\n\n  EIGEN_STRONG_INLINE\n#if !defined(EIGEN_HIPCC)\n  // Marking this as EIGEN_DEVICE_FUNC for HIPCC requires also doing the same\n  // for all the functions being called within here, which then leads to\n  // proliferation of EIGEN_DEVICE_FUNC markings, one of which will eventually\n  // result in an NVCC error\n  EIGEN_DEVICE_FUNC\n#endif\n  bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return evalSubExprsIfNeededCommon(data);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n    if (m_result) {\n      m_device.deallocate_temp(m_result);\n      m_result = NULL;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    if (( RunningFullReduction || RunningOnGPU) && m_result ) {\n      return *(m_result + index);\n    }\n    Op reducer(m_reducer);\n    if (ReducingInnerMostDims || RunningFullReduction) {\n      const Index num_values_to_reduce =\n        (static_cast<int>(Layout) == static_cast<int>(ColMajor)) ? m_preservedStrides[0] : m_preservedStrides[NumPreservedStrides - 1];\n      return internal::InnerMostDimReducer<Self, Op>::reduce(*this, firstInput(index),\n                                                             num_values_to_reduce, reducer);\n    } else {\n      typename Self::CoeffReturnType accum = reducer.initialize();\n      internal::GenericDimReducer<NumReducedDims-1, Self, Op>::reduce(*this, firstInput(index), reducer, &accum);\n      return reducer.finalize(accum);\n    }\n  }\n\n  // TODO(bsteiner): provide a more efficient implementation.\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index + PacketSize - 1 < Index(internal::array_prod(dimensions())));\n\n    if (RunningOnGPU && m_result) {\n      return internal::pload<PacketReturnType>(m_result + index);\n    }\n\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n    if (ReducingInnerMostDims) {\n      const Index num_values_to_reduce =\n        (static_cast<int>(Layout) == static_cast<int>(ColMajor)) ? m_preservedStrides[0] : m_preservedStrides[NumPreservedStrides - 1];\n      const Index firstIndex = firstInput(index);\n      for (Index i = 0; i < PacketSize; ++i) {\n        Op reducer(m_reducer);\n        values[i] = internal::InnerMostDimReducer<Self, Op>::reduce(*this, firstIndex + i * num_values_to_reduce,\n                                                                    num_values_to_reduce, reducer);\n      }\n    } else if (PreservingInnerMostDims) {\n      const Index firstIndex = firstInput(index);\n      const int innermost_dim = (static_cast<int>(Layout) == static_cast<int>(ColMajor)) ? 0 : NumOutputDims - 1;\n      // TBD: extend this the the n innermost dimensions that we preserve.\n      if (((firstIndex % m_dimensions[innermost_dim]) + PacketSize - 1) < m_dimensions[innermost_dim]) {\n        Op reducer(m_reducer);\n        typename Self::PacketReturnType accum = reducer.template initializePacket<typename Self::PacketReturnType>();\n        internal::InnerMostDimPreserver<NumReducedDims-1, Self, Op>::reduce(*this, firstIndex, reducer, &accum);\n        return reducer.finalizePacket(accum);\n      } else {\n        for (int i = 0; i < PacketSize; ++i) {\n          values[i] = coeff(index + i);\n        }\n      }\n    } else {\n      for (int i = 0; i < PacketSize; ++i) {\n        values[i] = coeff(index + i);\n      }\n    }\n    PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n    return rslt;\n  }\n\n  // Must be called after evalSubExprsIfNeeded().\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    if (RunningFullReduction && m_result) {\n      return TensorOpCost(sizeof(CoeffReturnType), 0, 0, vectorized, PacketSize);\n    } else {\n      const Index num_values_to_reduce = internal::array_prod(m_reducedDims);\n      const double compute_cost = num_values_to_reduce * internal::functor_traits<Op>::Cost;\n      return m_impl.costPerCoeff(vectorized) * num_values_to_reduce +\n          TensorOpCost(0, 0, compute_cost, vectorized, PacketSize);\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return m_result; }\n  EIGEN_DEVICE_FUNC const TensorEvaluator<ArgType, Device>& impl() const { return m_impl; }\n  EIGEN_DEVICE_FUNC const Device& device() const { return m_device; }\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n    m_result.bind(cgh);\n  }\n#endif\n\n  private:\n  template <int, typename, typename> friend struct internal::GenericDimReducer;\n  template <typename, typename, bool, bool> friend struct internal::InnerMostDimReducer;\n  template <int, typename, typename, bool> friend struct internal::InnerMostDimPreserver;\n  template <typename S, typename O, typename D, bool V> friend struct internal::FullReducer;\n#ifdef EIGEN_USE_THREADS\n  template <typename S, typename O, bool V> friend struct internal::FullReducerShard;\n#endif\n#if defined(EIGEN_USE_GPU) && (defined(EIGEN_GPUCC))\n  template <int B, int N, typename S, typename R, typename I_> KERNEL_FRIEND void internal::FullReductionKernel(R, const S, I_, typename S::CoeffReturnType*, unsigned int*);\n#if defined(EIGEN_HAS_GPU_FP16)\n  template <typename S, typename R, typename I_> KERNEL_FRIEND void internal::ReductionInitFullReduxKernelHalfFloat(R, const S, I_, internal::packet_traits<Eigen::half>::type*);\n  template <int B, int N, typename S, typename R, typename I_> KERNEL_FRIEND void internal::FullReductionKernelHalfFloat(R, const S, I_, half*, internal::packet_traits<Eigen::half>::type*);\n  template <int NPT, typename S, typename R, typename I_> KERNEL_FRIEND void internal::InnerReductionKernelHalfFloat(R, const S, I_, I_, half*);\n#endif\n  template <int NPT, typename S, typename R, typename I_> KERNEL_FRIEND void internal::InnerReductionKernel(R, const S, I_, I_, typename S::CoeffReturnType*);\n\n  template <int NPT, typename S, typename R, typename I_> KERNEL_FRIEND void internal::OuterReductionKernel(R, const S, I_, I_, typename S::CoeffReturnType*);\n#endif\n\n#if defined(EIGEN_USE_SYCL)\n template < typename Evaluator_, typename Op__> friend class TensorSycl::internal::GenericNondeterministicReducer;\n // SYCL need the Generic reducer for the case the recution algorithm is neither inner, outer, and full reducer\n template <typename, typename, typename> friend struct internal::GenericReducer;\n#endif\n\n\n  template <typename S, typename O, typename D> friend struct internal::InnerReducer;\n\n  struct BlockIteratorState {\n    Index input_dim;\n    Index output_size;\n    Index output_count;\n  };\n\n  // Returns the Index in the input tensor of the first value that needs to be\n  // used to compute the reduction at output index \"index\".\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index firstInput(Index index) const {\n    if (ReducingInnerMostDims) {\n      if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n        return index * m_preservedStrides[0];\n      } else {\n        return index * m_preservedStrides[NumPreservedStrides - 1];\n      }\n    }\n    // TBD: optimize the case where we preserve the innermost dimensions.\n    Index startInput = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = NumOutputDims - 1; i > 0; --i) {\n        // This is index_i in the output tensor.\n        const Index idx = index / m_outputStrides[i];\n        startInput += idx * m_preservedStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      if (PreservingInnerMostDims) {\n        eigen_assert(m_preservedStrides[0] == 1);\n        startInput += index;\n      } else {\n        startInput += index * m_preservedStrides[0];\n      }\n    } else {\n      for (int i = 0; i < NumOutputDims - 1; ++i) {\n        // This is index_i in the output tensor.\n        const Index idx = index / m_outputStrides[i];\n        startInput += idx * m_preservedStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      if (PreservingInnerMostDims) {\n        eigen_assert(m_preservedStrides[NumPreservedStrides - 1] == 1);\n        startInput += index;\n      } else {\n        startInput += index * m_preservedStrides[NumPreservedStrides - 1];\n      }\n    }\n    return startInput;\n  }\n\n  // Bitmap indicating if an input dimension is reduced or not.\n  array<bool, NumInputDims> m_reduced;\n  // Dimensions of the output of the operation.\n  Dimensions m_dimensions;\n  // Precomputed strides for the output tensor.\n  array<Index, NumOutputDims> m_outputStrides;\n  array<internal::TensorIntDivisor<Index>, NumOutputDims> m_fastOutputStrides;\n  array<Index, NumPreservedStrides> m_preservedStrides;\n  // Map from output to input dimension index.\n  array<Index, NumOutputDims> m_output_to_input_dim_map;\n  // How many values go into each reduction\n  Index m_numValuesToReduce;\n\n  // Subset of strides of the input tensor for the reduced dimensions.\n  // Indexed by reduced dimensions.\n  array<Index, NumReducedDims> m_reducedStrides;\n  // Size of the input dimensions that are reduced.\n  // Indexed by reduced dimensions.\n  array<Index, NumReducedDims> m_reducedDims;\n\n  // Evaluator for the input expression.\n  TensorEvaluator<ArgType, Device> m_impl;\n\n  // Operation to apply for computing the reduction.\n  Op m_reducer;\n\n  // For full reductions\n#if defined(EIGEN_USE_GPU) && (defined(EIGEN_GPUCC))\n  static const bool RunningOnGPU = internal::is_same<Device, Eigen::GpuDevice>::value;\n  static const bool RunningOnSycl = false;\n#elif defined(EIGEN_USE_SYCL)\nstatic const bool RunningOnSycl = internal::is_same<typename internal::remove_all<Device>::type, Eigen::SyclDevice>::value;\nstatic const bool RunningOnGPU = false;\n#else\n  static const bool RunningOnGPU = false;\n  static const bool RunningOnSycl = false;\n#endif\n  EvaluatorPointerType m_result;\n\n  const Device EIGEN_DEVICE_REF m_device;\n};\n\ntemplate<typename Op, typename Dims, typename ArgType, template <class> class MakePointer_, typename Device>\nstruct TensorEvaluator<const TensorReductionOp<Op, Dims, ArgType, MakePointer_>, Device>\n: public TensorReductionEvaluatorBase<const TensorReductionOp<Op, Dims, ArgType, MakePointer_>, Device> {\n  typedef TensorReductionEvaluatorBase<const TensorReductionOp<Op, Dims, ArgType, MakePointer_>, Device> Base;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const typename Base::XprType& op, const Device& device) : Base(op, device){}\n};\n\n\ntemplate<typename Op, typename Dims, typename ArgType, template <class> class MakePointer_>\nstruct TensorEvaluator<const TensorReductionOp<Op, Dims, ArgType, MakePointer_>, Eigen::SyclDevice>\n: public TensorReductionEvaluatorBase<const TensorReductionOp<Op, Dims, ArgType, MakePointer_>, Eigen::SyclDevice> {\n\n  typedef TensorReductionEvaluatorBase<const TensorReductionOp<Op, Dims, ArgType, MakePointer_>, Eigen::SyclDevice> Base;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const typename Base::XprType& op, const Eigen::SyclDevice& device) : Base(op, device){}\n  // The coeff function in the base the recursive method which is not an standard layout and cannot be used in the SYCL kernel\n  //Therefore the coeff function should be overridden by for SYCL kernel\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Base::CoeffReturnType coeff(typename Base::Index index) const {\n    return *(this->data() + index);\n  }\n  // The packet function in the base the recursive method which is not an standard layout and cannot be used in the SYCL kernel\n  //Therefore the packet function should be overridden by for SYCL kernel\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename Base::PacketReturnType packet(typename Base::Index index) const {\n    return internal::pload<typename Base::PacketReturnType>(this->data() + index);\n  }\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReductionCuda.h",
    "content": "\n#if defined(__clang__) || defined(__GNUC__)\n#warning \"Deprecated header file, please either include the main Eigen/CXX11/Tensor header or the respective TensorReductionGpu.h file\"\n#endif\n\n#include \"TensorReductionGpu.h\"\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReductionGpu.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_GPU_H\n#define EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_GPU_H\n\nnamespace Eigen {\nnamespace internal {\n\n\n#if defined(EIGEN_USE_GPU) && defined(EIGEN_GPUCC)\n// Full reducers for GPU, don't vectorize for now\n\n// Reducer function that enables multiple gpu thread to safely accumulate at the same\n// output address. It basically reads the current value of the output variable, and\n// attempts to update it with the new value. If in the meantime another gpu thread\n// updated the content of the output address it will try again.\ntemplate <typename T, typename R>\n__device__ EIGEN_ALWAYS_INLINE void atomicReduce(T* output, T accum, R& reducer) {\n#if (defined(EIGEN_HIP_DEVICE_COMPILE) && defined(__HIP_ARCH_HAS_WARP_SHUFFLE__)) || (EIGEN_CUDA_ARCH >= 300)\n  if (sizeof(T) == 4)\n  {\n    unsigned int oldval = *reinterpret_cast<unsigned int*>(output);\n    unsigned int newval = oldval;\n    reducer.reduce(accum, reinterpret_cast<T*>(&newval));\n    if (newval == oldval) {\n      return;\n    }\n    unsigned int readback;\n    while ((readback = atomicCAS((unsigned int*)output, oldval, newval)) != oldval) {\n      oldval = readback;\n      newval = oldval;\n      reducer.reduce(accum, reinterpret_cast<T*>(&newval));\n      if (newval == oldval) {\n        return;\n      }\n    }\n  }\n  else if (sizeof(T) == 8) {\n    unsigned long long oldval = *reinterpret_cast<unsigned long long*>(output);\n    unsigned long long newval = oldval;\n    reducer.reduce(accum, reinterpret_cast<T*>(&newval));\n    if (newval == oldval) {\n      return;\n    }\n    unsigned long long readback;\n    while ((readback = atomicCAS((unsigned long long*)output, oldval, newval)) != oldval) {\n      oldval = readback;\n      newval = oldval;\n      reducer.reduce(accum, reinterpret_cast<T*>(&newval));\n      if (newval == oldval) {\n        return;\n      }\n    }\n  }\n  else {\n    gpu_assert(0 && \"Wordsize not supported\");\n  }\n#else // EIGEN_CUDA_ARCH >= 300\n  gpu_assert(0 && \"Shouldn't be called on unsupported device\");\n#endif // EIGEN_CUDA_ARCH >= 300\n}\n\n// We extend atomicExch to support extra data types\ntemplate <typename Type>\n__device__ inline Type atomicExchCustom(Type* address, Type val) {\n  return atomicExch(address, val);\n}\n\ntemplate <>\n__device__ inline double atomicExchCustom(double* address, double val) {\n  unsigned long long int* address_as_ull = reinterpret_cast<unsigned long long int*>(address);\n  return __longlong_as_double(atomicExch(address_as_ull, __double_as_longlong(val)));\n}\n\n#ifdef EIGEN_HAS_GPU_FP16\ntemplate <typename R>\n__device__ inline void atomicReduce(half2* output, half2 accum, R& reducer) {\n  unsigned int oldval = *reinterpret_cast<unsigned int*>(output);\n  unsigned int newval = oldval;\n  reducer.reducePacket(accum, reinterpret_cast<half2*>(&newval));\n  if (newval == oldval) {\n    return;\n  }\n  unsigned int readback;\n  while ((readback = atomicCAS((unsigned int*)output, oldval, newval)) != oldval) {\n    oldval = readback;\n    newval = oldval;\n    reducer.reducePacket(accum, reinterpret_cast<half2*>(&newval));\n    if (newval == oldval) {\n      return;\n    }\n  }\n}\n// reduction should be associative since reduction is not atomic in wide vector but atomic in half2 operations\ntemplate <typename R>\n__device__ inline void atomicReduce(Packet4h2* output, Packet4h2 accum, R& reducer) {\n  half2* houtput=reinterpret_cast<half2*>(output);\n  half2* haccum=reinterpret_cast<half2*>(&accum);\n  for(int i=0;i<4;++i){\n    atomicReduce(houtput+i,*(haccum+i),reducer);\n  }\n}\n#endif  // EIGEN_HAS_GPU_FP16\n\ntemplate <>\n__device__ inline void atomicReduce(float* output, float accum, SumReducer<float>&) {\n#if (defined(EIGEN_HIP_DEVICE_COMPILE) && defined(__HIP_ARCH_HAS_WARP_SHUFFLE__)) || (EIGEN_CUDA_ARCH >= 300)\n  atomicAdd(output, accum);\n#else // EIGEN_CUDA_ARCH >= 300\n  gpu_assert(0 && \"Shouldn't be called on unsupported device\");\n#endif // EIGEN_CUDA_ARCH >= 300\n}\n\n\ntemplate <typename CoeffType, typename Index>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void ReductionInitKernel(const CoeffType val, Index num_preserved_coeffs, CoeffType* output) {\n  const Index thread_id = blockIdx.x * blockDim.x + threadIdx.x;\n  const Index num_threads = blockDim.x * gridDim.x;\n  for (Index i = thread_id; i < num_preserved_coeffs; i += num_threads) {\n    output[i] = val;\n  }\n}\n\n\ntemplate <int BlockSize, int NumPerThread, typename Self,\n          typename Reducer, typename Index>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void FullReductionKernel(Reducer reducer, const Self input, Index num_coeffs,\n                                    typename Self::CoeffReturnType* output, unsigned int* semaphore) {\n#if (defined(EIGEN_HIP_DEVICE_COMPILE) && defined(__HIP_ARCH_HAS_WARP_SHUFFLE__)) || (EIGEN_CUDA_ARCH >= 300)\n  // Initialize the output value\n  const Index first_index = blockIdx.x * BlockSize * NumPerThread + threadIdx.x;\n  if (gridDim.x == 1) {\n    if (first_index == 0) {\n      *output = reducer.initialize();\n    }\n  }\n  else {\n    if (threadIdx.x == 0) {\n      unsigned int block = atomicCAS(semaphore, 0u, 1u);\n      if (block == 0) {\n        // We're the first block to run, initialize the output value\n        atomicExchCustom(output, reducer.initialize());\n        __threadfence();\n        atomicExch(semaphore, 2u);\n      }\n      else {\n        // Wait for the first block to initialize the output value.\n        // Use atomicCAS here to ensure that the reads aren't cached\n        unsigned int val;\n        do {\n          val = atomicCAS(semaphore, 2u, 2u);\n        }\n        while (val < 2u);\n      }\n    }\n  }\n\n  __syncthreads();\n\n  eigen_assert(gridDim.x == 1 || *semaphore >= 2u);\n\n  typename Self::CoeffReturnType accum = reducer.initialize();\n  Index max_iter = numext::mini<Index>(num_coeffs - first_index, NumPerThread*BlockSize);\n  for (Index i = 0; i < max_iter; i+=BlockSize) {\n    const Index index = first_index + i;\n    eigen_assert(index < num_coeffs);\n    typename Self::CoeffReturnType val = input.m_impl.coeff(index);\n    reducer.reduce(val, &accum);\n  }\n\n#pragma unroll\n  for (int offset = warpSize/2; offset > 0; offset /= 2) {\n  #if defined(EIGEN_HIPCC)\n    // use std::is_floating_point to determine the type of reduced_val \n    // This is needed because when Type == double, hipcc will give a \"call to __shfl_down is ambguous\" error \n    // and list the float and int versions of __shfl_down as the candidate functions. \n    if (std::is_floating_point<typename Self::CoeffReturnType>::value) {\n      reducer.reduce(__shfl_down(static_cast<float>(accum), offset, warpSize), &accum);\n    } else {\n      reducer.reduce(__shfl_down(static_cast<int>(accum), offset, warpSize), &accum);\n    }\n  #elif defined(EIGEN_CUDA_SDK_VER) && EIGEN_CUDA_SDK_VER < 90000\n    reducer.reduce(__shfl_down(accum, offset, warpSize), &accum);\n  #else\n    reducer.reduce(__shfl_down_sync(0xFFFFFFFF, accum, offset, warpSize), &accum);\n  #endif\n  }\n\n  if ((threadIdx.x & (warpSize - 1)) == 0) {\n    atomicReduce(output, accum, reducer);\n  }\n\n  if (gridDim.x > 1 && threadIdx.x == 0) {\n    // Let the last block reset the semaphore\n    atomicInc(semaphore, gridDim.x + 1);\n#if defined(EIGEN_HIPCC)\n    __threadfence_system();\n#endif\n  }\n#else // EIGEN_CUDA_ARCH >= 300\n  gpu_assert(0 && \"Shouldn't be called on unsupported device\");\n#endif // EIGEN_CUDA_ARCH >= 300\n}\n\n\n#ifdef EIGEN_HAS_GPU_FP16\ntemplate <typename Self,\n          typename Reducer, typename Index>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void ReductionInitFullReduxKernelHalfFloat(Reducer reducer, const Self input, Index num_coeffs,\n                                                      packet_traits<Eigen::half>::type* scratch) {\n  eigen_assert(blockDim.x == 1);\n  eigen_assert(gridDim.x == 1);\n  typedef packet_traits<Eigen::half>::type packet_type;\n  Index packet_remainder =\n      num_coeffs % Index(unpacket_traits<packet_type>::size);\n  if (packet_remainder != 0) {\n    half2* h2scratch = reinterpret_cast<half2*>(scratch);\n    for (Index i = num_coeffs - packet_remainder; i + 2 <= num_coeffs; i += 2) {\n      *h2scratch =\n          __halves2half2(input.m_impl.coeff(i), input.m_impl.coeff(i + 1));\n      h2scratch++;\n    }\n    if ((num_coeffs & 1) != 0) {\n      half lastCoeff = input.m_impl.coeff(num_coeffs - 1);\n      *h2scratch = __halves2half2(lastCoeff, reducer.initialize());\n    }\n  } else {\n    *scratch = reducer.template initializePacket<packet_type>();\n  }\n}\n\ntemplate <typename Self,\n          typename Reducer, typename Index>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void ReductionInitKernelHalfFloat(Reducer reducer, const Self input, Index num_coeffs, half* output) {\n  const Index thread_id = blockIdx.x * blockDim.x + threadIdx.x;\n  const Index num_threads = blockDim.x * gridDim.x;\n  typedef typename packet_traits<Eigen::half>::type PacketType;\n\n  const Index num_packets =\n      num_coeffs / Index(unpacket_traits<PacketType>::size);\n  PacketType* p_output = reinterpret_cast<PacketType*>(output);\n  for (Index i = thread_id; i < num_packets; i += num_threads) {\n    p_output[i] = reducer.template initializePacket<PacketType>();\n  }\n  Index packet_remainder =\n      num_coeffs % Index(unpacket_traits<PacketType>::size);\n  if (thread_id < packet_remainder) {\n    output[num_coeffs - packet_remainder + thread_id] = reducer.initialize();\n  }\n}\n\ntemplate <int BlockSize, int NumPerThread, typename Self,\n          typename Reducer, typename Index>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void FullReductionKernelHalfFloat(Reducer reducer, const Self input, Index num_coeffs,\n                                    half* output, packet_traits<Eigen::half>::type* scratch) {\n  typedef typename packet_traits<Eigen::half>::type PacketType;\n  const int packet_width = unpacket_traits<PacketType>::size;\n  eigen_assert(NumPerThread % packet_width == 0);\n  const Index first_index =\n      blockIdx.x * BlockSize * NumPerThread + packet_width * threadIdx.x;\n\n  // Initialize the output value if it wasn't initialized by the ReductionInitKernel\n\n  if (gridDim.x == 1) {\n    if (first_index == 0) {\n      int rem = num_coeffs % packet_width;\n      if (rem != 0) {\n        half2* p_scratch = reinterpret_cast<half2*>(scratch);\n        *scratch = reducer.template initializePacket<PacketType>();\n        for (int i = 0; i < rem / 2; i++) {\n          *p_scratch = __halves2half2(\n              input.m_impl.coeff(num_coeffs - packet_width + 2 * i),\n              input.m_impl.coeff(num_coeffs - packet_width + 2 * i + 1));\n          p_scratch++;\n        }\n        if ((num_coeffs & 1) != 0) {\n          half last = input.m_impl.coeff(num_coeffs - 1);\n          *p_scratch = __halves2half2(last, reducer.initialize());\n        }\n      } else {\n        *scratch = reducer.template initializePacket<PacketType>();\n      }\n    }\n    __syncthreads();\n  }\n\n  PacketType accum = reducer.template initializePacket<PacketType>();\n  const Index max_iter =\n      numext::mini<Index>((num_coeffs - first_index) / packet_width,\n                          NumPerThread * BlockSize / packet_width);\n  for (Index i = 0; i < max_iter; i += BlockSize) {\n    const Index index = first_index + packet_width * i;\n    eigen_assert(index + packet_width < num_coeffs);\n    PacketType val = input.m_impl.template packet<Unaligned>(index);\n    reducer.reducePacket(val, &accum);\n  }\n\n#pragma unroll\n  for (int offset = warpSize/2; offset > 0; offset /= 2) {\n  #if defined(EIGEN_HIPCC)\n    PacketType r1;\n    half2* hr = reinterpret_cast<half2*>(&r1);\n    half2* hacc = reinterpret_cast<half2*>(&accum);\n    for (int i = 0; i < packet_width / 2; i++) {\n      // FIXME : remove this workaround once we have native half/half2 support for __shfl_down\n      union { int i; half2 h; } wka_in, wka_out;\n      wka_in.h = hacc[i];\n      wka_out.i = __shfl_down(wka_in.i, offset, warpSize);\n      hr[i] = wka_out.h;\n    }\n    reducer.reducePacket(r1, &accum);\n  #elif defined(EIGEN_CUDA_SDK_VER) && EIGEN_CUDA_SDK_VER < 90000\n    PacketType r1;\n    half2* hr = reinterpret_cast<half2*>(&r1);\n    half2* hacc = reinterpret_cast<half2*>(&accum);\n    for (int i = 0; i < packet_width / 2; i++) {\n      hr[i] = __shfl_down(hacc[i], offset, warpSize);\n    }\n    reducer.reducePacket(r1, &accum);\n  #else\n    PacketType r1;\n    half2* hr = reinterpret_cast<half2*>(&r1);\n    half2* hacc = reinterpret_cast<half2*>(&accum);\n    for (int i = 0; i < packet_width / 2; i++) {\n      hr[i] = __shfl_down_sync(0xFFFFFFFF, hacc[i], (unsigned)offset, warpSize);\n    }\n    reducer.reducePacket(r1, &accum);\n\n  #endif\n  }\n\n  if ((threadIdx.x & (warpSize - 1)) == 0) {\n    atomicReduce(scratch, accum, reducer);\n  }\n\n  __syncthreads();\n  half2* rv1 = reinterpret_cast<half2*>(scratch);\n  if (packet_width > 2) {\n    reducer.reducePacket(rv1[2], rv1);\n    reducer.reducePacket(rv1[3], rv1 + 1);\n    reducer.reducePacket(rv1[1], rv1);\n  }\n  if (gridDim.x == 1) {\n    if (first_index == 0) {\n      half tmp = __low2half(*rv1);\n      reducer.reduce(__high2half(*rv1), &tmp);\n      *output = tmp;\n    }\n  }\n}\n\ntemplate <typename Op>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void ReductionCleanupKernelHalfFloat(Op reducer, half* output, packet_traits<Eigen::half>::type* scratch) {\n  eigen_assert(threadIdx.x == 1);\n  half2* pscratch = reinterpret_cast<half2*>(scratch);\n  half tmp = __float2half(0.f);\n  typedef packet_traits<Eigen::half>::type packet_type;\n  for (int i = 0; i < unpacket_traits<packet_type>::size; i += 2) {\n    reducer.reduce(__low2half(*pscratch), &tmp);\n    reducer.reduce(__high2half(*pscratch), &tmp);\n    pscratch++;\n  }\n  *output = tmp;\n}\n\n#endif // EIGEN_HAS_GPU_FP16\n\ntemplate <typename Self, typename Op, typename OutputType, bool PacketAccess, typename Enabled = void>\nstruct FullReductionLauncher {\n  static void run(const Self&, Op&, const GpuDevice&, OutputType*, typename Self::Index) {\n    gpu_assert(false && \"Should only be called on doubles, floats and half floats\");\n  }\n};\n\n// Specialization for float and double\ntemplate <typename Self, typename Op, typename OutputType, bool PacketAccess>\nstruct FullReductionLauncher<\n    Self, Op, OutputType, PacketAccess,\n    typename internal::enable_if<\n      internal::is_same<float, OutputType>::value ||\n      internal::is_same<double, OutputType>::value,\n    void>::type> {\n  static void run(const Self& self, Op& reducer, const GpuDevice& device, OutputType* output, typename Self::Index num_coeffs) {\n\n    typedef typename Self::Index Index;\n    const int block_size = 256;\n    const int num_per_thread = 128;\n    const int num_blocks = divup<int>(num_coeffs, block_size * num_per_thread);\n\n    unsigned int* semaphore = NULL;\n    if (num_blocks > 1) {\n      semaphore = device.semaphore();\n    }\n\n    LAUNCH_GPU_KERNEL((FullReductionKernel<block_size, num_per_thread, Self, Op, Index>),\n                       num_blocks, block_size, 0, device, reducer, self, num_coeffs, output, semaphore);\n  }\n};\n\n#ifdef EIGEN_HAS_GPU_FP16\ntemplate <typename Self, typename Op>\nstruct FullReductionLauncher<Self, Op, Eigen::half, false> {\n  static void run(const Self&, Op&, const GpuDevice&, half*, typename Self::Index) {\n    gpu_assert(false && \"Should not be called since there is no packet accessor\");\n  }\n};\n\ntemplate <typename Self, typename Op>\nstruct FullReductionLauncher<Self, Op, Eigen::half, true> {\n  static void run(const Self& self, Op& reducer, const GpuDevice& device, half* output, typename Self::Index num_coeffs) {\n    typedef typename Self::Index Index;\n    typedef typename packet_traits<Eigen::half>::type PacketType;\n\n    const int block_size = 256;\n    const int num_per_thread = 128;\n    const int num_blocks = divup<int>(num_coeffs, block_size * num_per_thread);\n    PacketType* scratch = static_cast<PacketType*>(device.scratchpad());\n    // half2* scratch = static_cast<half2*>(device.scratchpad());\n\n    if (num_blocks > 1) {\n      // We initialize the output and the scrathpad outside the reduction kernel when we can't be sure that there\n      // won't be a race conditions between multiple thread blocks.\n      LAUNCH_GPU_KERNEL((ReductionInitFullReduxKernelHalfFloat<Self, Op, Index>),\n                         1, 1, 0, device, reducer, self, num_coeffs, scratch);\n    }\n\n    LAUNCH_GPU_KERNEL((FullReductionKernelHalfFloat<block_size, num_per_thread, Self, Op, Index>),\n                       num_blocks, block_size, 0, device, reducer, self, num_coeffs, output, scratch);\n\n    if (num_blocks > 1) {\n      LAUNCH_GPU_KERNEL((ReductionCleanupKernelHalfFloat<Op>),\n                         1, 1, 0, device, reducer, output, scratch);\n    }\n  }\n};\n#endif // EIGEN_HAS_GPU_FP16\n\n\ntemplate <typename Self, typename Op, bool Vectorizable>\nstruct FullReducer<Self, Op, GpuDevice, Vectorizable> {\n  // Unfortunately nvidia doesn't support well exotic types such as complex,\n  // so reduce the scope of the optimized version of the code to the simple cases\n  // of doubles, floats and half floats\n#ifdef EIGEN_HAS_GPU_FP16\n  static const bool HasOptimizedImplementation = !Self::ReducerTraits::IsStateful &&\n      (internal::is_same<typename Self::CoeffReturnType, float>::value ||\n       internal::is_same<typename Self::CoeffReturnType, double>::value ||\n       (internal::is_same<typename Self::CoeffReturnType, Eigen::half>::value && reducer_traits<Op, GpuDevice>::PacketAccess));\n#else // EIGEN_HAS_GPU_FP16\n  static const bool HasOptimizedImplementation = !Self::ReducerTraits::IsStateful &&\n                                                (internal::is_same<typename Self::CoeffReturnType, float>::value ||\n                                                 internal::is_same<typename Self::CoeffReturnType, double>::value);\n#endif // EIGEN_HAS_GPU_FP16\n\n  template <typename OutputType>\n  static void run(const Self& self, Op& reducer, const GpuDevice& device, OutputType* output) {\n    gpu_assert(HasOptimizedImplementation && \"Should only be called on doubles, floats or half floats\");\n    const Index num_coeffs = array_prod(self.m_impl.dimensions());\n    // Don't crash when we're called with an input tensor of size 0.\n    if (num_coeffs == 0) {\n      return;\n    }\n\n    FullReductionLauncher<Self, Op, OutputType, reducer_traits<Op, GpuDevice>::PacketAccess>::run(self, reducer, device, output, num_coeffs);\n  }\n};\n\n\ntemplate <int NumPerThread, typename Self,\n          typename Reducer, typename Index>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void InnerReductionKernel(Reducer reducer, const Self input, Index num_coeffs_to_reduce, Index num_preserved_coeffs,\n                                         typename Self::CoeffReturnType* output) {\n#if (defined(EIGEN_HIP_DEVICE_COMPILE) && defined(__HIP_ARCH_HAS_WARP_SHUFFLE__)) || (EIGEN_CUDA_ARCH >= 300)\n  typedef typename Self::CoeffReturnType Type;\n  eigen_assert(blockDim.y == 1);\n  eigen_assert(blockDim.z == 1);\n  eigen_assert(gridDim.y == 1);\n  eigen_assert(gridDim.z == 1);\n\n  const int unroll_times = 16;\n  eigen_assert(NumPerThread % unroll_times == 0);\n\n  const Index input_col_blocks = divup<Index>(num_coeffs_to_reduce, blockDim.x * NumPerThread);\n  const Index num_input_blocks = input_col_blocks * num_preserved_coeffs;\n\n  const Index num_threads = blockDim.x * gridDim.x;\n  const Index thread_id = blockIdx.x * blockDim.x + threadIdx.x;\n\n  // Initialize the output values if they weren't initialized by the ReductionInitKernel\n  if (gridDim.x == 1) {\n    for (Index i = thread_id; i < num_preserved_coeffs; i += num_threads) {\n      output[i] = reducer.initialize();\n    }\n    __syncthreads();\n  }\n\n  for (Index i = blockIdx.x; i < num_input_blocks; i += gridDim.x) {\n    const Index row = i / input_col_blocks;\n\n    if (row < num_preserved_coeffs) {\n      const Index col_block = i % input_col_blocks;\n      const Index col_begin = col_block * blockDim.x * NumPerThread + threadIdx.x;\n\n      Type reduced_val = reducer.initialize();\n\n      for (Index j = 0; j < NumPerThread; j += unroll_times) {\n        const Index last_col = col_begin + blockDim.x * (j + unroll_times - 1);\n        if (last_col >= num_coeffs_to_reduce) {\n          for (Index col = col_begin + blockDim.x * j; col < num_coeffs_to_reduce; col += blockDim.x) {\n            const Type val = input.m_impl.coeff(row * num_coeffs_to_reduce + col);\n            reducer.reduce(val, &reduced_val);\n          }\n          break;\n        } else {\n          // Faster version of the loop with no branches after unrolling.\n#pragma unroll\n          for (int k = 0; k < unroll_times; ++k) {\n            const Index col = col_begin + blockDim.x * (j + k);\n            reducer.reduce(input.m_impl.coeff(row * num_coeffs_to_reduce + col), &reduced_val);\n          }\n        }\n      }\n\n#pragma unroll\n      for (int offset = warpSize/2; offset > 0; offset /= 2) {\n      #if defined(EIGEN_HIPCC)\n        // use std::is_floating_point to determine the type of reduced_val \n       // This is needed because when Type == double, hipcc will give a \"call to __shfl_down is ambguous\" error \n       // and list the float and int versions of __shfl_down as the candidate functions. \n        if (std::is_floating_point<Type>::value) {\n          reducer.reduce(__shfl_down(static_cast<float>(reduced_val), offset), &reduced_val);\n        } else {\n          reducer.reduce(__shfl_down(static_cast<int>(reduced_val), offset), &reduced_val);\n        }\n      #elif defined(EIGEN_CUDA_SDK_VER) && EIGEN_CUDA_SDK_VER < 90000\n        reducer.reduce(__shfl_down(reduced_val, offset), &reduced_val);\n      #else\n        reducer.reduce(__shfl_down_sync(0xFFFFFFFF, reduced_val, offset), &reduced_val);\n      #endif\n      }\n\n      if ((threadIdx.x & (warpSize - 1)) == 0) {\n        atomicReduce(&(output[row]), reduced_val, reducer);\n      }\n    }\n  }\n#else // EIGEN_CUDA_ARCH >= 300\n  gpu_assert(0 && \"Shouldn't be called on unsupported device\");\n#endif // EIGEN_CUDA_ARCH >= 300\n}\n\n#ifdef EIGEN_HAS_GPU_FP16\n\ntemplate <int NumPerThread, typename Self,\n          typename Reducer, typename Index>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void InnerReductionKernelHalfFloat(Reducer reducer, const Self input, Index num_coeffs_to_reduce, Index num_preserved_coeffs,\n                                              half* output) {\n  eigen_assert(blockDim.y == 1);\n  eigen_assert(blockDim.z == 1);\n  eigen_assert(gridDim.y == 1);\n  eigen_assert(gridDim.z == 1);\n\n  typedef typename packet_traits<Eigen::half>::type PacketType;\n  const int packet_width = unpacket_traits<PacketType>::size;\n  const int unroll_times = 16 / packet_width;\n  eigen_assert(NumPerThread % unroll_times == 0);\n  eigen_assert(unroll_times % 2 == 0);\n\n  const Index input_col_blocks = divup<Index>(num_coeffs_to_reduce, blockDim.x * NumPerThread * 2);\n  const Index num_input_blocks = divup<Index>(input_col_blocks * num_preserved_coeffs, 2);\n\n  const Index num_threads = blockDim.x * gridDim.x;\n  const Index thread_id = blockIdx.x * blockDim.x + threadIdx.x;\n\n  // Initialize the output values if they weren't initialized by the ReductionInitKernel\n  if (gridDim.x == 1) {\n    Index i = packet_width * thread_id;\n    for (; i + packet_width <= num_preserved_coeffs;\n         i += packet_width * num_threads) {\n      PacketType* poutput = reinterpret_cast<PacketType*>(output + i);\n      *poutput = reducer.template initializePacket<PacketType>();\n    }\n    if (i < num_preserved_coeffs) {\n      output[i] = reducer.initialize();\n    }\n    __syncthreads();\n  }\n\n  for (Index i = blockIdx.x; i < num_input_blocks; i += gridDim.x) {\n    const Index row = 2 * (i / input_col_blocks);  // everybody takes 2 rows\n\n    if (row + 1 < num_preserved_coeffs) {\n      const Index col_block = i % input_col_blocks;\n      const Index col_begin =\n          packet_width * (col_block * blockDim.x * NumPerThread + threadIdx.x);\n\n      PacketType reduced_val1 = reducer.template initializePacket<PacketType>();\n      PacketType reduced_val2 = reducer.template initializePacket<PacketType>();\n\n      for (Index j = 0; j < NumPerThread; j += unroll_times) {\n        const Index last_col =\n            col_begin + blockDim.x * (j + unroll_times - 1) * packet_width;\n        if (last_col >= num_coeffs_to_reduce) {\n          Index col = col_begin + blockDim.x * j;\n          for (; col + packet_width <= num_coeffs_to_reduce;\n               col += blockDim.x) {\n            const PacketType val1 = input.m_impl.template packet<Unaligned>(\n                row * num_coeffs_to_reduce + col);\n            reducer.reducePacket(val1, &reduced_val1);\n            const PacketType val2 = input.m_impl.template packet<Unaligned>(\n                (row + 1) * num_coeffs_to_reduce + col);\n            reducer.reducePacket(val2, &reduced_val2);\n          }\n          if (col < num_coeffs_to_reduce) {\n            PacketType r1 = reducer.template initializePacket<PacketType>();\n            PacketType r2 = reducer.template initializePacket<PacketType>();\n            half2* hr1 = reinterpret_cast<half2*>(&r1);\n            half2* hr2 = reinterpret_cast<half2*>(&r2);\n            while (col + 1 < num_coeffs_to_reduce) {\n              *hr1 = __halves2half2(\n                  input.m_impl.coeff(row * num_coeffs_to_reduce + col),\n                  input.m_impl.coeff(row * num_coeffs_to_reduce + col + 1));\n              *hr2 = __halves2half2(\n                  input.m_impl.coeff((row + 1) * num_coeffs_to_reduce + col),\n                  input.m_impl.coeff((row + 1) * num_coeffs_to_reduce + col +\n                                     1));\n              hr1++;\n              hr2++;\n              col += 2;\n            }\n            if (col < num_coeffs_to_reduce) {\n              // Peel;\n              const half last1 =\n                  input.m_impl.coeff(row * num_coeffs_to_reduce + col);\n              *hr1 = __halves2half2(last1, reducer.initialize());\n              const half last2 =\n                  input.m_impl.coeff((row + 1) * num_coeffs_to_reduce + col);\n              *hr2 = __halves2half2(last2, reducer.initialize());\n            }\n            reducer.reducePacket(r1, &reduced_val1);\n            reducer.reducePacket(r2, &reduced_val2);\n          }\n          break;\n        } else {\n          // Faster version of the loop with no branches after unrolling.\n#pragma unroll\n          for (int k = 0; k < unroll_times; ++k) {\n            const Index col = col_begin + blockDim.x * (j + k) * packet_width;\n            reducer.reducePacket(input.m_impl.template packet<Unaligned>(\n                                     row * num_coeffs_to_reduce + col),\n                                 &reduced_val1);\n            reducer.reducePacket(input.m_impl.template packet<Unaligned>(\n                                     (row + 1) * num_coeffs_to_reduce + col),\n                                 &reduced_val2);\n          }\n        }\n      }\n\n#pragma unroll\n      for (int offset = warpSize/2; offset > 0; offset /= 2) {\n      #if defined(EIGEN_HIPCC)\n        PacketType r1;\n        PacketType r2;\n        half2* hr1 = reinterpret_cast<half2*>(&r1);\n        half2* hr2 = reinterpret_cast<half2*>(&r2);\n        half2* rv1 = reinterpret_cast<half2*>(&reduced_val1);\n        half2* rv2 = reinterpret_cast<half2*>(&reduced_val2);\n        for (int i = 0; i < packet_width / 2; i++) {\n\t  // FIXME : remove this workaround once we have native half/half2 support for __shfl_down\n\t  union { int i; half2 h; } wka_in1, wka_out1;\n\t  wka_in1.h = rv1[i];\n\t  wka_out1.i = __shfl_down(wka_in1.i, offset, warpSize);\n\t  hr1[i] = wka_out1.h;\n\n\t  union { int i; half2 h; } wka_in2, wka_out2;\n\t  wka_in2.h = rv2[i];\n\t  wka_out2.i = __shfl_down(wka_in2.i, offset, warpSize);\n\t  hr2[i] = wka_out2.h;\n        }\n        reducer.reducePacket(r1, &reduced_val1);\n        reducer.reducePacket(r2, &reduced_val2);\n      #elif defined(EIGEN_CUDA_SDK_VER) && EIGEN_CUDA_SDK_VER < 90000\n        PacketType r1;\n        PacketType r2;\n        half2* hr1 = reinterpret_cast<half2*>(&r1);\n        half2* hr2 = reinterpret_cast<half2*>(&r2);\n        half2* rv1 = reinterpret_cast<half2*>(&reduced_val1);\n        half2* rv2 = reinterpret_cast<half2*>(&reduced_val2);\n        for (int i = 0; i < packet_width / 2; i++) {\n          hr1[i] = __shfl_down(rv1[i], offset, warpSize);\n          hr2[i] = __shfl_down(rv2[i], offset, warpSize);\n        }\n        reducer.reducePacket(r1, &reduced_val1);\n        reducer.reducePacket(r2, &reduced_val2);\n      #else\n        PacketType r1;\n        PacketType r2;\n        half2* hr1 = reinterpret_cast<half2*>(&r1);\n        half2* hr2 = reinterpret_cast<half2*>(&r2);\n        half2* rr1 = reinterpret_cast<half2*>(&reduced_val1);\n        half2* rr2 = reinterpret_cast<half2*>(&reduced_val2);\n        for (int i = 0; i < packet_width / 2; i++) {\n          hr1[i] =\n              __shfl_down_sync(0xFFFFFFFF, rr1[i], (unsigned)offset, warpSize);\n          hr2[i] =\n              __shfl_down_sync(0xFFFFFFFF, rr2[i], (unsigned)offset, warpSize);\n        }\n        reducer.reducePacket(r1, &reduced_val1);\n        reducer.reducePacket(r2, &reduced_val2);\n\n      #endif\n      }\n      half2* rv1 = reinterpret_cast<half2*>(&reduced_val1);\n      half2* rv2 = reinterpret_cast<half2*>(&reduced_val2);\n      half2 val;\n      if (packet_width > 2) {\n        reducer.reducePacket(rv1[2], rv1);\n        reducer.reducePacket(rv1[3], rv1 + 1);\n        reducer.reducePacket(rv1[1], rv1);\n        reducer.reducePacket(rv2[2], rv2);\n        reducer.reducePacket(rv2[3], rv2 + 1);\n        reducer.reducePacket(rv2[1], rv2);\n      }\n      half val1 = __low2half(*rv1);\n      reducer.reduce(__high2half(*rv1), &val1);\n      half val2 = __low2half(*rv2);\n      reducer.reduce(__high2half(*rv2), &val2);\n      val = __halves2half2(val1, val2);\n      if ((threadIdx.x & (warpSize - 1)) == 0) {\n        half* loc = output + row;\n        atomicReduce((half2*)loc, val, reducer);\n      }\n    }\n  }\n}\n\n#endif // EIGEN_HAS_GPU_FP16\n\ntemplate <typename Self, typename Op, typename OutputType, bool PacketAccess, typename Enabled = void>\nstruct InnerReductionLauncher {\n  static EIGEN_DEVICE_FUNC bool run(const Self&, Op&, const GpuDevice&, OutputType*, typename Self::Index, typename Self::Index) {\n    gpu_assert(false && \"Should only be called to reduce doubles, floats and half floats on a gpu device\");\n    return true;\n  }\n};\n\n// Specialization for float and double\ntemplate <typename Self, typename Op, typename OutputType, bool PacketAccess>\nstruct InnerReductionLauncher<\n  Self, Op, OutputType, PacketAccess,\n  typename internal::enable_if<\n    internal::is_same<float, OutputType>::value ||\n    internal::is_same<double, OutputType>::value,\n  void>::type> {\n  static bool run(const Self& self, Op& reducer, const GpuDevice& device, OutputType* output, typename Self::Index num_coeffs_to_reduce, typename Self::Index num_preserved_vals) {\n    typedef typename Self::Index Index;\n\n    const Index num_coeffs = num_coeffs_to_reduce * num_preserved_vals;\n    const int block_size = 256;\n    const int num_per_thread = 128;\n    const int dyn_blocks = divup<int>(num_coeffs, block_size * num_per_thread);\n    const int max_blocks = device.getNumGpuMultiProcessors() *\n                           device.maxGpuThreadsPerMultiProcessor() / block_size;\n    const int num_blocks = numext::mini<int>(max_blocks, dyn_blocks);\n\n    if (num_blocks > 1) {\n      // We initialize the outputs outside the reduction kernel when we can't be sure that there\n      // won't be a race conditions between multiple thread blocks.\n      const int dyn_blocks = divup<int>(num_preserved_vals, 1024);\n      const int max_blocks = device.getNumGpuMultiProcessors() *\n                           device.maxGpuThreadsPerMultiProcessor() / 1024;\n      const int num_blocks = numext::mini<int>(max_blocks, dyn_blocks);\n      LAUNCH_GPU_KERNEL((ReductionInitKernel<OutputType, Index>),\n                         num_blocks, 1024, 0, device, reducer.initialize(),\n                         num_preserved_vals, output);\n    }\n\n    LAUNCH_GPU_KERNEL((InnerReductionKernel<num_per_thread, Self, Op, Index>),\n                       num_blocks, block_size, 0, device, reducer, self, num_coeffs_to_reduce, num_preserved_vals, output);\n\n    return false;\n  }\n};\n\n#ifdef EIGEN_HAS_GPU_FP16\ntemplate <typename Self, typename Op>\nstruct InnerReductionLauncher<Self, Op, Eigen::half, false> {\n  static bool run(const Self&, Op&, const GpuDevice&, half*, typename Self::Index, typename Self::Index) {\n    gpu_assert(false && \"Should not be called since there is no packet accessor\");\n    return true;\n  }\n};\n\ntemplate <typename Self, typename Op>\nstruct InnerReductionLauncher<Self, Op, Eigen::half, true> {\n  static bool run(const Self& self, Op& reducer, const GpuDevice& device, half* output, typename Self::Index num_coeffs_to_reduce, typename Self::Index num_preserved_vals) {\n    typedef typename Self::Index Index;\n\n    if (num_preserved_vals % 2 != 0) {\n      // Not supported yet, revert to the slower code path\n      return true;\n    }\n\n    const Index num_coeffs = num_coeffs_to_reduce * num_preserved_vals;\n    const int block_size = /*256*/128;\n    const int num_per_thread = /*128*/64;\n    const int dyn_blocks = divup<int>(num_coeffs, block_size * num_per_thread);\n    const int max_blocks = device.getNumGpuMultiProcessors() *\n                           device.maxGpuThreadsPerMultiProcessor() / block_size;\n    const int num_blocks = numext::mini<int>(max_blocks, dyn_blocks);\n\n    if (num_blocks > 1) {\n      // We initialize the outputs outside the reduction kernel when we can't be sure that there\n      // won't be a race conditions between multiple thread blocks.\n      LAUNCH_GPU_KERNEL((ReductionInitKernelHalfFloat<Self, Op, Index>),\n                         1, 1, 0, device, reducer, self, num_preserved_vals, output);\n    }\n\n    LAUNCH_GPU_KERNEL((InnerReductionKernelHalfFloat<num_per_thread, Self, Op, Index>),\n                       num_blocks, block_size, 0, device, reducer, self, num_coeffs_to_reduce, num_preserved_vals, output);\n\n    return false;\n  }\n};\n#endif // EIGEN_HAS_GPU_FP16\n\n\ntemplate <typename Self, typename Op>\nstruct InnerReducer<Self, Op, GpuDevice> {\n  // Unfortunately nvidia doesn't support well exotic types such as complex,\n  // so reduce the scope of the optimized version of the code to the simple case\n  // of floats and half floats.\n#ifdef EIGEN_HAS_GPU_FP16\n  static const bool HasOptimizedImplementation = !Self::ReducerTraits::IsStateful &&\n      (internal::is_same<typename Self::CoeffReturnType, float>::value ||\n       internal::is_same<typename Self::CoeffReturnType, double>::value ||\n       (internal::is_same<typename Self::CoeffReturnType, Eigen::half>::value && reducer_traits<Op, GpuDevice>::PacketAccess));\n#else // EIGEN_HAS_GPU_FP16\n  static const bool HasOptimizedImplementation = !Self::ReducerTraits::IsStateful &&\n                                                 (internal::is_same<typename Self::CoeffReturnType, float>::value ||\n                                                  internal::is_same<typename Self::CoeffReturnType, double>::value);\n#endif // EIGEN_HAS_GPU_FP16\n\n  template <typename OutputType>\n  static bool run(const Self& self, Op& reducer, const GpuDevice& device, OutputType* output, typename Self::Index num_coeffs_to_reduce, typename Self::Index num_preserved_vals) {\n    gpu_assert(HasOptimizedImplementation && \"Should only be called on doubles, floats or half floats\");\n    const Index num_coeffs = array_prod(self.m_impl.dimensions());\n    // Don't crash when we're called with an input tensor of size 0.\n    if (num_coeffs == 0) {\n      return true;\n    }\n    // It's faster to use the usual code.\n    if (num_coeffs_to_reduce <= 128) {\n      return true;\n    }\n\n    return InnerReductionLauncher<Self, Op, OutputType, reducer_traits<Op, GpuDevice>::PacketAccess>::run(self, reducer, device, output, num_coeffs_to_reduce, num_preserved_vals);\n  }\n};\n\ntemplate <int NumPerThread, typename Self,\n          typename Reducer, typename Index>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void OuterReductionKernel(Reducer reducer, const Self input, Index num_coeffs_to_reduce, Index num_preserved_coeffs,\n                                     typename Self::CoeffReturnType* output) {\n  const Index num_threads = blockDim.x * gridDim.x;\n  const Index thread_id = blockIdx.x * blockDim.x + threadIdx.x;\n  // Initialize the output values if they weren't initialized by the ReductionInitKernel\n  if (gridDim.x == 1) {\n    for (Index i = thread_id; i < num_preserved_coeffs; i += num_threads) {\n      output[i] = reducer.initialize();\n    }\n    __syncthreads();\n  }\n\n  // Do the reduction.\n  const Index max_iter = num_preserved_coeffs * divup<Index>(num_coeffs_to_reduce, NumPerThread);\n  for (Index i = thread_id; i < max_iter; i += num_threads) {\n    const Index input_col = i % num_preserved_coeffs;\n    const Index input_row = (i / num_preserved_coeffs) * NumPerThread;\n    typename Self::CoeffReturnType reduced_val = reducer.initialize();\n    const Index max_row = numext::mini(input_row + NumPerThread, num_coeffs_to_reduce);\n    for (Index j = input_row; j < max_row; j++) {\n      typename Self::CoeffReturnType val = input.m_impl.coeff(j * num_preserved_coeffs + input_col);\n      reducer.reduce(val, &reduced_val);\n    }\n    atomicReduce(&(output[input_col]), reduced_val, reducer);\n  }\n}\n\n\ntemplate <typename Self, typename Op>\nstruct OuterReducer<Self, Op, GpuDevice> {\n  // Unfortunately nvidia doesn't support well exotic types such as complex,\n  // so reduce the scope of the optimized version of the code to the simple case\n  // of floats.\n  static const bool HasOptimizedImplementation = !Self::ReducerTraits::IsStateful &&\n                                                 (internal::is_same<typename Self::CoeffReturnType, float>::value ||\n                                                  internal::is_same<typename Self::CoeffReturnType, double>::value);\n  template <typename Device, typename OutputType>\n  static\n    #if !defined(EIGEN_HIPCC)\n    // FIXME :  leaving this EIGEN_DEVICE_FUNC in, results in the following runtime error\n    //          (in the cxx11_tensor_reduction_gpu test)\n    //\n    // terminate called after throwing an instance of 'std::runtime_error'\n    //   what():  No device code available for function: _ZN5Eigen8internal20OuterReductionKernelIL...\n    //\n    // don't know why this happens (and why is it a runtime error instead of a compile time error)\n    //\n    // this will be fixed by HIP PR#457\n    EIGEN_DEVICE_FUNC\n    #endif\n    bool run(const Self&, Op&, const Device&, OutputType*, typename Self::Index, typename Self::Index) {\n    gpu_assert(false && \"Should only be called to reduce doubles or floats on a gpu device\");\n    return true;\n  }\n\n  static bool run(const Self& self, Op& reducer, const GpuDevice& device, float* output, typename Self::Index num_coeffs_to_reduce, typename Self::Index num_preserved_vals) {\n    typedef typename Self::Index Index;\n\n    // It's faster to use the usual code.\n    if (num_coeffs_to_reduce <= 32) {\n      return true;\n    }\n\n    const Index num_coeffs = num_coeffs_to_reduce * num_preserved_vals;\n    const int block_size = 256;\n    const int num_per_thread = 16;\n    const int dyn_blocks = divup<int>(num_coeffs, block_size * num_per_thread);\n    const int max_blocks = device.getNumGpuMultiProcessors() *\n                           device.maxGpuThreadsPerMultiProcessor() / block_size;\n    const int num_blocks = numext::mini<int>(max_blocks, dyn_blocks);\n\n    if (num_blocks > 1) {\n      // We initialize the outputs in the reduction kernel itself when we don't have to worry\n      // about race conditions between multiple thread blocks.\n      const int dyn_blocks = divup<int>(num_preserved_vals, 1024);\n      const int max_blocks = device.getNumGpuMultiProcessors() *\n                             device.maxGpuThreadsPerMultiProcessor() / 1024;\n      const int num_blocks = numext::mini<int>(max_blocks, dyn_blocks);\n      LAUNCH_GPU_KERNEL((ReductionInitKernel<float, Index>),\n                         num_blocks, 1024, 0, device, reducer.initialize(),\n                         num_preserved_vals, output);\n    }\n\n    LAUNCH_GPU_KERNEL((OuterReductionKernel<num_per_thread, Self, Op, Index>),\n                       num_blocks, block_size, 0, device, reducer, self, num_coeffs_to_reduce, num_preserved_vals, output);\n\n    return false;\n  }\n};\n\n#endif // defined(EIGEN_USE_GPU) && defined(EIGEN_GPUCC)\n\n\n} // end namespace internal\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_REDUCTION_GPU_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReductionSycl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/*****************************************************************\n * TensorReductionSycl.h\n *\n * \\brief:\n *  This is the specialization of the reduction operation. Two phase reduction approach \n * is used since the GPU does not have Global Synchronization for global memory among \n * different work-group/thread block. To solve the problem, we need to create two kernels \n * to reduce the data, where the first kernel reduce the data locally and each local \n * workgroup/thread-block save the input data into global memory. In the second phase (global reduction)\n * one work-group uses one work-group/thread-block to reduces the intermediate data into one single element. \n * Here is an NVIDIA presentation explaining the optimized two phase reduction algorithm on GPU:\n * https://developer.download.nvidia.com/assets/cuda/files/reduction.pdf\n *\n *****************************************************************/\n\n#ifndef UNSUPPORTED_EIGEN_CXX11_SRC_TENSOR_TENSOR_REDUCTION_SYCL_HPP\n#define UNSUPPORTED_EIGEN_CXX11_SRC_TENSOR_TENSOR_REDUCTION_SYCL_HPP\nnamespace Eigen {\nnamespace TensorSycl {\nnamespace internal {\n\ntemplate <typename Op, typename CoeffReturnType, typename Index, bool Vectorizable>\nstruct OpDefiner {\n  typedef typename Vectorise<CoeffReturnType, Eigen::SyclDevice, Vectorizable>::PacketReturnType PacketReturnType;\n  typedef Op type;\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE type get_op(Op &op) { return op; }\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType finalise_op(const PacketReturnType &accumulator,\n                                                                            const Index &) {\n    return accumulator;\n  }\n};\n\ntemplate <typename CoeffReturnType, typename Index>\nstruct OpDefiner<Eigen::internal::MeanReducer<CoeffReturnType>, CoeffReturnType, Index, false> {\n  typedef Eigen::internal::SumReducer<CoeffReturnType> type;\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE type get_op(Eigen::internal::MeanReducer<CoeffReturnType> &) {\n    return type();\n  }\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType finalise_op(const CoeffReturnType &accumulator,\n                                                                           const Index &scale) {\n    ::Eigen::internal::scalar_quotient_op<CoeffReturnType> quotient_op;\n    return quotient_op(accumulator, CoeffReturnType(scale));\n  }\n};\n\ntemplate <typename CoeffReturnType, typename Index>\nstruct OpDefiner<Eigen::internal::MeanReducer<CoeffReturnType>, CoeffReturnType, Index, true> {\n  typedef typename Vectorise<CoeffReturnType, Eigen::SyclDevice, true>::PacketReturnType PacketReturnType;\n  typedef Eigen::internal::SumReducer<CoeffReturnType> type;\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE type get_op(Eigen::internal::MeanReducer<CoeffReturnType> &) {\n    return type();\n  }\n\n  static EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType finalise_op(const PacketReturnType &accumulator,\n                                                                            const Index &scale) {\n    return ::Eigen::internal::pdiv(accumulator, ::Eigen::internal::pset1<PacketReturnType>(CoeffReturnType(scale)));\n  }\n};\n\ntemplate <typename CoeffReturnType, typename OpType, typename InputAccessor, typename OutputAccessor, typename Index,\n          Index local_range>\nstruct SecondStepFullReducer {\n  typedef cl::sycl::accessor<CoeffReturnType, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local>\n      LocalAccessor;\n  typedef OpDefiner<OpType, CoeffReturnType, Index, true> OpDef;\n  typedef typename OpDef::type Op;\n  LocalAccessor scratch;\n  InputAccessor aI;\n  OutputAccessor outAcc;\n  Op op;\n  SecondStepFullReducer(LocalAccessor scratch_, InputAccessor aI_, OutputAccessor outAcc_, OpType op_)\n      : scratch(scratch_), aI(aI_), outAcc(outAcc_), op(OpDef::get_op(op_)) {}\n\n  void operator()(cl::sycl::nd_item<1> itemID) {\n    // Our empirical research shows that the best performance will be achieved\n    // when there is only one element per thread to reduce in the second step.\n    // in this step the second step reduction time is almost negligible.\n    // Hence, in the second step of reduction the input size is fixed to the\n    // local size, thus, there is only one element read per thread. The\n    // algorithm must be changed if the number of reduce per thread in the\n    // second step is greater than 1. Otherwise, the result will be wrong.\n    const Index localid = itemID.get_local_id(0);\n    auto aInPtr = aI.get_pointer() + localid;\n    auto aOutPtr = outAcc.get_pointer();\n    CoeffReturnType *scratchptr = scratch.get_pointer();\n    CoeffReturnType accumulator = *aInPtr;\n\n    scratchptr[localid] = op.finalize(accumulator);\n    for (Index offset = itemID.get_local_range(0) / 2; offset > 0; offset /= 2) {\n      itemID.barrier(cl::sycl::access::fence_space::local_space);\n      if (localid < offset) {\n        op.reduce(scratchptr[localid + offset], &accumulator);\n        scratchptr[localid] = op.finalize(accumulator);\n      }\n    }\n    if (localid == 0) *aOutPtr = op.finalize(accumulator);\n  }\n};\n\n// Full reduction first phase. In this version the vectorization is true and the reduction accept \n// any generic reducerOp  e.g( max, min, sum, mean, iamax, iamin, etc ). \ntemplate <typename Evaluator, typename OpType, typename Evaluator::Index local_range>\nclass FullReductionKernelFunctor {\n public:\n  typedef typename Evaluator::CoeffReturnType CoeffReturnType;\n  typedef typename Evaluator::Index Index;\n  typedef OpDefiner<OpType, typename Evaluator::CoeffReturnType, Index,\n                    (Evaluator::ReducerTraits::PacketAccess & Evaluator::InputPacketAccess)>\n      OpDef;\n\n  typedef typename OpDef::type Op;\n  typedef typename Evaluator::EvaluatorPointerType EvaluatorPointerType;\n  typedef typename Evaluator::PacketReturnType PacketReturnType;\n  typedef\n      typename ::Eigen::internal::conditional<(Evaluator::ReducerTraits::PacketAccess & Evaluator::InputPacketAccess),\n                                              PacketReturnType, CoeffReturnType>::type OutType;\n  typedef cl::sycl::accessor<OutType, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local>\n      LocalAccessor;\n  LocalAccessor scratch;\n  Evaluator evaluator;\n  EvaluatorPointerType final_output;\n  Index rng;\n  Op op;\n\n  FullReductionKernelFunctor(LocalAccessor scratch_, Evaluator evaluator_, EvaluatorPointerType final_output_,\n                             Index rng_, OpType op_)\n      : scratch(scratch_), evaluator(evaluator_), final_output(final_output_), rng(rng_), op(OpDef::get_op(op_)) {}\n\n  void operator()(cl::sycl::nd_item<1> itemID) { compute_reduction(itemID); }\n\n  template <bool Vect = (Evaluator::ReducerTraits::PacketAccess & Evaluator::InputPacketAccess)>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename ::Eigen::internal::enable_if<Vect>::type compute_reduction(\n      const cl::sycl::nd_item<1> &itemID) {\n    auto output_ptr = final_output.get_pointer();\n    Index VectorizedRange = (rng / Evaluator::PacketSize) * Evaluator::PacketSize;\n    Index globalid = itemID.get_global_id(0);\n    Index localid = itemID.get_local_id(0);\n    Index step = Evaluator::PacketSize * itemID.get_global_range(0);\n    Index start = Evaluator::PacketSize * globalid;\n    // vectorizable parts\n    PacketReturnType packetAccumulator = op.template initializePacket<PacketReturnType>();\n    for (Index i = start; i < VectorizedRange; i += step) {\n      op.template reducePacket<PacketReturnType>(evaluator.impl().template packet<Unaligned>(i), &packetAccumulator);\n    }\n    globalid += VectorizedRange;\n    // non vectorizable parts\n    for (Index i = globalid; i < rng; i += itemID.get_global_range(0)) {\n      op.template reducePacket<PacketReturnType>(\n          ::Eigen::TensorSycl::internal::PacketWrapper<PacketReturnType, Evaluator::PacketSize>::convert_to_packet_type(\n              evaluator.impl().coeff(i), op.initialize()),\n          &packetAccumulator);\n    }\n    scratch[localid] = packetAccumulator =\n        OpDef::finalise_op(op.template finalizePacket<PacketReturnType>(packetAccumulator), rng);\n    // reduction parts // Local size is always power of 2\n    EIGEN_UNROLL_LOOP\n    for (Index offset = local_range / 2; offset > 0; offset /= 2) {\n      itemID.barrier(cl::sycl::access::fence_space::local_space);\n      if (localid < offset) {\n        op.template reducePacket<PacketReturnType>(scratch[localid + offset], &packetAccumulator);\n        scratch[localid] = op.template finalizePacket<PacketReturnType>(packetAccumulator);\n      }\n    }\n    if (localid == 0) {\n      output_ptr[itemID.get_group(0)] =\n          op.finalizeBoth(op.initialize(), op.template finalizePacket<PacketReturnType>(packetAccumulator));\n    }\n  }\n\n  template <bool Vect = (Evaluator::ReducerTraits::PacketAccess & Evaluator::InputPacketAccess)>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE typename ::Eigen::internal::enable_if<!Vect>::type compute_reduction(\n      const cl::sycl::nd_item<1> &itemID) {\n    auto output_ptr = final_output.get_pointer();\n    Index globalid = itemID.get_global_id(0);\n    Index localid = itemID.get_local_id(0);\n    // vectorizable parts\n    CoeffReturnType accumulator = op.initialize();\n    // non vectorizable parts\n    for (Index i = globalid; i < rng; i += itemID.get_global_range(0)) {\n      op.reduce(evaluator.impl().coeff(i), &accumulator);\n    }\n    scratch[localid] = accumulator = OpDef::finalise_op(op.finalize(accumulator), rng);\n\n    // reduction parts. the local size is always power of 2\n    EIGEN_UNROLL_LOOP\n    for (Index offset = local_range / 2; offset > 0; offset /= 2) {\n      itemID.barrier(cl::sycl::access::fence_space::local_space);\n      if (localid < offset) {\n        op.reduce(scratch[localid + offset], &accumulator);\n        scratch[localid] = op.finalize(accumulator);\n      }\n    }\n    if (localid == 0) {\n      output_ptr[itemID.get_group(0)] = op.finalize(accumulator);\n    }\n  }\n};\n\ntemplate <typename Evaluator, typename OpType>\nclass GenericNondeterministicReducer {\n public:\n  typedef typename Evaluator::CoeffReturnType CoeffReturnType;\n  typedef typename Evaluator::EvaluatorPointerType EvaluatorPointerType;\n  typedef typename Evaluator::Index Index;\n  typedef OpDefiner<OpType, CoeffReturnType, Index, false> OpDef;\n  typedef typename OpDef::type Op;\n  template <typename Scratch>\n  GenericNondeterministicReducer(Scratch, Evaluator evaluator_, EvaluatorPointerType output_accessor_, OpType functor_,\n                       Index range_, Index num_values_to_reduce_)\n      : evaluator(evaluator_),\n        output_accessor(output_accessor_),\n        functor(OpDef::get_op(functor_)),\n        range(range_),\n        num_values_to_reduce(num_values_to_reduce_) {}\n\n  void operator()(cl::sycl::nd_item<1> itemID) {\n    auto output_accessor_ptr = output_accessor.get_pointer();\n    /// const cast added as a naive solution to solve the qualifier drop error\n    Index globalid = static_cast<Index>(itemID.get_global_linear_id());\n    if (globalid < range) {\n      CoeffReturnType accum = functor.initialize();\n      Eigen::internal::GenericDimReducer<Evaluator::NumReducedDims - 1, Evaluator, Op>::reduce(\n          evaluator, evaluator.firstInput(globalid), functor, &accum);\n      output_accessor_ptr[globalid] = OpDef::finalise_op(functor.finalize(accum), num_values_to_reduce);\n    }\n  }\n\n private:\n  Evaluator evaluator;\n  EvaluatorPointerType output_accessor;\n  Op functor;\n  Index range;\n  Index num_values_to_reduce;\n};\n\nenum class reduction_dim { inner_most, outer_most };\n// default is preserver\ntemplate <typename Evaluator, typename OpType, typename PannelParameters, reduction_dim rt>\nstruct PartialReductionKernel {\n  typedef typename Evaluator::CoeffReturnType CoeffReturnType;\n  typedef typename Evaluator::EvaluatorPointerType EvaluatorPointerType;\n  typedef typename Evaluator::Index Index;\n  typedef OpDefiner<OpType, CoeffReturnType, Index, false> OpDef;\n  typedef typename OpDef::type Op;\n  typedef cl::sycl::accessor<CoeffReturnType, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local>\n      ScratchAcc;\n  ScratchAcc scratch;\n  Evaluator evaluator;\n  EvaluatorPointerType output_accessor;\n  Op op;\n  const Index preserve_elements_num_groups;\n  const Index reduce_elements_num_groups;\n  const Index num_coeffs_to_preserve;\n  const Index num_coeffs_to_reduce;\n\n  PartialReductionKernel(ScratchAcc scratch_, Evaluator evaluator_, EvaluatorPointerType output_accessor_, OpType op_,\n                         const Index preserve_elements_num_groups_, const Index reduce_elements_num_groups_,\n                         const Index num_coeffs_to_preserve_, const Index num_coeffs_to_reduce_)\n      : scratch(scratch_),\n        evaluator(evaluator_),\n        output_accessor(output_accessor_),\n        op(OpDef::get_op(op_)),\n        preserve_elements_num_groups(preserve_elements_num_groups_),\n        reduce_elements_num_groups(reduce_elements_num_groups_),\n        num_coeffs_to_preserve(num_coeffs_to_preserve_),\n        num_coeffs_to_reduce(num_coeffs_to_reduce_) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void element_wise_reduce(Index globalRId, Index globalPId,\n                                                                 CoeffReturnType &accumulator) {\n    if (globalPId >= num_coeffs_to_preserve) {\n      return;\n    }\n    Index global_offset = rt == reduction_dim::outer_most ? globalPId + (globalRId * num_coeffs_to_preserve)\n                                                          : globalRId + (globalPId * num_coeffs_to_reduce);\n    Index localOffset = globalRId;\n\n    const Index per_thread_local_stride = PannelParameters::LocalThreadSizeR * reduce_elements_num_groups;\n    const Index per_thread_global_stride =\n        rt == reduction_dim::outer_most ? num_coeffs_to_preserve * per_thread_local_stride : per_thread_local_stride;\n    for (Index i = globalRId; i < num_coeffs_to_reduce; i += per_thread_local_stride) {\n      op.reduce(evaluator.impl().coeff(global_offset), &accumulator);\n      localOffset += per_thread_local_stride;\n      global_offset += per_thread_global_stride;\n    }\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void operator()(cl::sycl::nd_item<1> itemID) {\n    const Index linearLocalThreadId = itemID.get_local_id(0);\n    Index pLocalThreadId = rt == reduction_dim::outer_most ? linearLocalThreadId % PannelParameters::LocalThreadSizeP\n                                                           : linearLocalThreadId / PannelParameters::LocalThreadSizeR;\n    Index rLocalThreadId = rt == reduction_dim::outer_most ? linearLocalThreadId / PannelParameters::LocalThreadSizeP\n                                                           : linearLocalThreadId % PannelParameters::LocalThreadSizeR;\n    const Index pGroupId = rt == reduction_dim::outer_most ? itemID.get_group(0) % preserve_elements_num_groups\n                                                           : itemID.get_group(0) / reduce_elements_num_groups;\n    const Index rGroupId = rt == reduction_dim::outer_most ? itemID.get_group(0) / preserve_elements_num_groups\n                                                           : itemID.get_group(0) % reduce_elements_num_groups;\n\n    Index globalPId = pGroupId * PannelParameters::LocalThreadSizeP + pLocalThreadId;\n    const Index globalRId = rGroupId * PannelParameters::LocalThreadSizeR + rLocalThreadId;\n    auto scratchPtr = scratch.get_pointer().get();\n    auto outPtr =\n        output_accessor.get_pointer() + (reduce_elements_num_groups > 1 ? rGroupId * num_coeffs_to_preserve : 0);\n    CoeffReturnType accumulator = op.initialize();\n\n    element_wise_reduce(globalRId, globalPId, accumulator);\n\n    accumulator = OpDef::finalise_op(op.finalize(accumulator), num_coeffs_to_reduce);\n    scratchPtr[pLocalThreadId + rLocalThreadId * (PannelParameters::LocalThreadSizeP + PannelParameters::BC)] =\n        accumulator;\n    if (rt == reduction_dim::inner_most) {\n      pLocalThreadId = linearLocalThreadId % PannelParameters::LocalThreadSizeP;\n      rLocalThreadId = linearLocalThreadId / PannelParameters::LocalThreadSizeP;\n      globalPId = pGroupId * PannelParameters::LocalThreadSizeP + pLocalThreadId;\n    }\n\n    /* Apply the reduction operation between the current local\n     * id and the one on the other half of the vector. */\n    auto out_scratch_ptr =\n        scratchPtr + (pLocalThreadId + (rLocalThreadId * (PannelParameters::LocalThreadSizeP + PannelParameters::BC)));\n    itemID.barrier(cl::sycl::access::fence_space::local_space);\n    if (rt == reduction_dim::inner_most) {\n      accumulator = *out_scratch_ptr;\n    }\n    // The Local LocalThreadSizeR is always power of 2\n    EIGEN_UNROLL_LOOP\n    for (Index offset = PannelParameters::LocalThreadSizeR >> 1; offset > 0; offset >>= 1) {\n      if (rLocalThreadId < offset) {\n        op.reduce(out_scratch_ptr[(PannelParameters::LocalThreadSizeP + PannelParameters::BC) * offset], &accumulator);\n        // The result has already been divided for mean reducer in the\n        // previous reduction so no need to divide furthermore\n        *out_scratch_ptr = op.finalize(accumulator);\n      }\n      /* All threads collectively read from global memory into local.\n       * The barrier ensures all threads' IO is resolved before\n       * execution continues (strictly speaking, all threads within\n       * a single work-group - there is no co-ordination between\n       * work-groups, only work-items). */\n      itemID.barrier(cl::sycl::access::fence_space::local_space);\n    }\n\n    if (rLocalThreadId == 0 && (globalPId < num_coeffs_to_preserve)) {\n      outPtr[globalPId] = op.finalize(accumulator);\n    }\n  }\n};\n\ntemplate <typename OutScalar, typename Index, typename InputAccessor, typename OutputAccessor, typename OpType>\nstruct SecondStepPartialReduction {\n  typedef OpDefiner<OpType, OutScalar, Index, false> OpDef;\n  typedef typename OpDef::type Op;\n  typedef cl::sycl::accessor<OutScalar, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local>\n      ScratchAccessor;\n  InputAccessor input_accessor;\n  OutputAccessor output_accessor;\n  Op op;\n  const Index num_coeffs_to_preserve;\n  const Index num_coeffs_to_reduce;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE SecondStepPartialReduction(ScratchAccessor, InputAccessor input_accessor_,\n                                                                   OutputAccessor output_accessor_, OpType op_,\n                                                                   const Index num_coeffs_to_preserve_,\n                                                                   const Index num_coeffs_to_reduce_)\n      : input_accessor(input_accessor_),\n        output_accessor(output_accessor_),\n        op(OpDef::get_op(op_)),\n        num_coeffs_to_preserve(num_coeffs_to_preserve_),\n        num_coeffs_to_reduce(num_coeffs_to_reduce_) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void operator()(cl::sycl::nd_item<1> itemID) {\n    const Index globalId = itemID.get_global_id(0);\n\n    if (globalId >= num_coeffs_to_preserve) return;\n\n    auto in_ptr = input_accessor.get_pointer() + globalId;\n\n    OutScalar accumulator = op.initialize();\n// num_coeffs_to_reduce is not bigger that 256\n    for (Index i = 0; i < num_coeffs_to_reduce; i++) {\n      op.reduce(*in_ptr, &accumulator);\n      in_ptr += num_coeffs_to_preserve;\n    }\n    output_accessor.get_pointer()[globalId] = op.finalize(accumulator);\n  }\n};  // namespace internal\n\ntemplate <typename Index, Index LTP, Index LTR, bool BC_>\nstruct ReductionPannel {\n  static EIGEN_CONSTEXPR Index LocalThreadSizeP = LTP;\n  static EIGEN_CONSTEXPR Index LocalThreadSizeR = LTR;\n  static EIGEN_CONSTEXPR bool BC = BC_;\n};\n\ntemplate <typename Self, typename Op, TensorSycl::internal::reduction_dim rt>\nstruct PartialReducerLauncher {\n  typedef typename Self::EvaluatorPointerType EvaluatorPointerType;\n  typedef typename Self::CoeffReturnType CoeffReturnType;\n  typedef typename Self::Storage Storage;\n  typedef typename Self::Index Index;\n  typedef ReductionPannel<typename Self::Index, EIGEN_SYCL_LOCAL_THREAD_DIM0, EIGEN_SYCL_LOCAL_THREAD_DIM1, true>\n      PannelParameters;\n\n  typedef PartialReductionKernel<Self, Op, PannelParameters, rt> SyclReducerKerneType;\n\n  static bool run(const Self &self, const Op &reducer, const Eigen::SyclDevice &dev, EvaluatorPointerType output,\n                  Index num_coeffs_to_reduce, Index num_coeffs_to_preserve) {\n    Index roundUpP = roundUp(num_coeffs_to_preserve, PannelParameters::LocalThreadSizeP);\n\n    // getPowerOfTwo makes sure local range is power of 2 and <=\n    // maxSyclThreadPerBlock this will help us to avoid extra check on the\n    // kernel\n    static_assert(!((PannelParameters::LocalThreadSizeP * PannelParameters::LocalThreadSizeR) &\n                    (PannelParameters::LocalThreadSizeP * PannelParameters::LocalThreadSizeR - 1)),\n                  \"The Local thread size must be a power of 2 for the reduction \"\n                  \"operation\");\n\n    EIGEN_CONSTEXPR Index localRange = PannelParameters::LocalThreadSizeP * PannelParameters::LocalThreadSizeR;\n    // In this step, we force the code not to be more than 2-step reduction:\n    // Our empirical research shows that if each thread reduces at least 64\n    // elemnts individually, we get better performance. However, this can change\n    // on different platforms. In this step we force the code not to be\n    // morthan step reduction: Our empirical research shows that for inner_most\n    // dim reducer, it is better to have 8 group in a reduce dimension for sizes\n    // > 1024 to achieve the best performance.\n    const Index reductionPerThread = 64;\n    Index cu = dev.getPowerOfTwo(dev.getNumSyclMultiProcessors(), true);\n    const Index pNumGroups = roundUpP / PannelParameters::LocalThreadSizeP;\n    Index rGroups = (cu + pNumGroups - 1) / pNumGroups;\n    const Index rNumGroups = num_coeffs_to_reduce > reductionPerThread * localRange ? std::min(rGroups, localRange) : 1;\n    const Index globalRange = pNumGroups * rNumGroups * localRange;\n\n    EIGEN_CONSTEXPR Index scratchSize =\n        PannelParameters::LocalThreadSizeR * (PannelParameters::LocalThreadSizeP + PannelParameters::BC);\n    auto thread_range = cl::sycl::nd_range<1>(cl::sycl::range<1>(globalRange), cl::sycl::range<1>(localRange));\n    if (rNumGroups > 1) {\n      CoeffReturnType *temp_pointer = static_cast<CoeffReturnType *>(\n          dev.allocate_temp(num_coeffs_to_preserve * rNumGroups * sizeof(CoeffReturnType)));\n      EvaluatorPointerType temp_accessor = dev.get(temp_pointer);\n      dev.template unary_kernel_launcher<CoeffReturnType, SyclReducerKerneType>(\n          self, temp_accessor, thread_range, scratchSize, reducer, pNumGroups, rNumGroups, num_coeffs_to_preserve,\n          num_coeffs_to_reduce);\n\n      typedef SecondStepPartialReduction<CoeffReturnType, Index, EvaluatorPointerType, EvaluatorPointerType, Op>\n          SecondStepPartialReductionKernel;\n\n      dev.template unary_kernel_launcher<CoeffReturnType, SecondStepPartialReductionKernel>(\n          temp_accessor, output,\n          cl::sycl::nd_range<1>(cl::sycl::range<1>(pNumGroups * localRange), cl::sycl::range<1>(localRange)), Index(1),\n          reducer, num_coeffs_to_preserve, rNumGroups);\n\n      self.device().deallocate_temp(temp_pointer);\n    } else {\n      dev.template unary_kernel_launcher<CoeffReturnType, SyclReducerKerneType>(\n          self, output, thread_range, scratchSize, reducer, pNumGroups, rNumGroups, num_coeffs_to_preserve,\n          num_coeffs_to_reduce);\n    }\n    return false;\n  }\n};\n}  // namespace internal\n}  // namespace TensorSycl\n\nnamespace internal {\n\ntemplate <typename Self, typename Op, bool Vectorizable>\nstruct FullReducer<Self, Op, Eigen::SyclDevice, Vectorizable> {\n  typedef typename Self::CoeffReturnType CoeffReturnType;\n  typedef typename Self::EvaluatorPointerType EvaluatorPointerType;\n  static EIGEN_CONSTEXPR bool HasOptimizedImplementation = true;\n  static EIGEN_CONSTEXPR int PacketSize = Self::PacketAccess ? Self::PacketSize : 1;\n  static void run(const Self &self, Op &reducer, const Eigen::SyclDevice &dev, EvaluatorPointerType data) {\n    typedef typename conditional<Self::PacketAccess, typename Self::PacketReturnType, CoeffReturnType>::type OutType;\n    static_assert(!((EIGEN_SYCL_LOCAL_THREAD_DIM0 * EIGEN_SYCL_LOCAL_THREAD_DIM1) &\n                    (EIGEN_SYCL_LOCAL_THREAD_DIM0 * EIGEN_SYCL_LOCAL_THREAD_DIM1 - 1)),\n                  \"The Local thread size must be a power of 2 for the reduction \"\n                  \"operation\");\n    EIGEN_CONSTEXPR Index local_range = EIGEN_SYCL_LOCAL_THREAD_DIM0 * EIGEN_SYCL_LOCAL_THREAD_DIM1;\n\n    typename Self::Index inputSize = self.impl().dimensions().TotalSize();\n    // In this step we force the code not to be more than 2-step reduction:\n    // Our empirical research shows that if each thread reduces at least 512\n    // elemnts individually, we get better performance.\n    const Index reductionPerThread = 2048;\n    // const Index num_work_group =\n    Index reductionGroup = dev.getPowerOfTwo(\n        (inputSize + (reductionPerThread * local_range - 1)) / (reductionPerThread * local_range), true);\n    const Index num_work_group = std::min(reductionGroup, local_range);\n    // 1\n    // ? local_range\n    // : 1);\n    const Index global_range = num_work_group * local_range;\n\n    auto thread_range = cl::sycl::nd_range<1>(cl::sycl::range<1>(global_range), cl::sycl::range<1>(local_range));\n    typedef TensorSycl::internal::FullReductionKernelFunctor<Self, Op, local_range> reduction_kernel_t;\n    if (num_work_group > 1) {\n      CoeffReturnType *temp_pointer =\n          static_cast<CoeffReturnType *>(dev.allocate_temp(num_work_group * sizeof(CoeffReturnType)));\n      typename Self::EvaluatorPointerType tmp_global_accessor = dev.get(temp_pointer);\n      dev.template unary_kernel_launcher<OutType, reduction_kernel_t>(self, tmp_global_accessor, thread_range,\n                                                                      local_range, inputSize, reducer);\n\n      typedef TensorSycl::internal::SecondStepFullReducer<CoeffReturnType, Op, EvaluatorPointerType,\n                                                          EvaluatorPointerType, Index, local_range>\n          GenericRKernel;\n      dev.template unary_kernel_launcher<CoeffReturnType, GenericRKernel>(\n          tmp_global_accessor, data,\n          cl::sycl::nd_range<1>(cl::sycl::range<1>(num_work_group), cl::sycl::range<1>(num_work_group)), num_work_group,\n          reducer);\n\n      dev.deallocate_temp(temp_pointer);\n    } else {\n      dev.template unary_kernel_launcher<OutType, reduction_kernel_t>(self, data, thread_range, local_range, inputSize,\n                                                                      reducer);\n    }\n  }\n};\n// vectorizable inner_most most dim preserver\n// col reduction\ntemplate <typename Self, typename Op>\nstruct OuterReducer<Self, Op, Eigen::SyclDevice> {\n  static EIGEN_CONSTEXPR bool HasOptimizedImplementation = true;\n\n  static bool run(const Self &self, const Op &reducer, const Eigen::SyclDevice &dev,\n                  typename Self::EvaluatorPointerType output, typename Self::Index num_coeffs_to_reduce,\n                  typename Self::Index num_coeffs_to_preserve) {\n    return ::Eigen::TensorSycl::internal::PartialReducerLauncher<\n        Self, Op, ::Eigen::TensorSycl::internal::reduction_dim::outer_most>::run(self, reducer, dev, output,\n                                                                                 num_coeffs_to_reduce,\n                                                                                 num_coeffs_to_preserve);\n  }\n};\n// row reduction\ntemplate <typename Self, typename Op>\nstruct InnerReducer<Self, Op, Eigen::SyclDevice> {\n  static EIGEN_CONSTEXPR bool HasOptimizedImplementation = true;\n\n  static bool run(const Self &self, const Op &reducer, const Eigen::SyclDevice &dev,\n                  typename Self::EvaluatorPointerType output, typename Self::Index num_coeffs_to_reduce,\n                  typename Self::Index num_coeffs_to_preserve) {\n    return ::Eigen::TensorSycl::internal::PartialReducerLauncher<\n        Self, Op, ::Eigen::TensorSycl::internal::reduction_dim::inner_most>::run(self, reducer, dev, output,\n                                                                                 num_coeffs_to_reduce,\n                                                                                 num_coeffs_to_preserve);\n  }\n};\n\n// ArmgMax uses this kernel for partial reduction//\n// TODO(@mehdi.goli) come up with a better kernel\n// generic partial reduction\ntemplate <typename Self, typename Op>\nstruct GenericReducer<Self, Op, Eigen::SyclDevice> {\n  static EIGEN_CONSTEXPR bool HasOptimizedImplementation = false;\n  static bool run(const Self &self, const Op &reducer, const Eigen::SyclDevice &dev,\n                  typename Self::EvaluatorPointerType output, typename Self::Index num_values_to_reduce,\n                  typename Self::Index num_coeffs_to_preserve) {\n    typename Self::Index range, GRange, tileSize;\n    dev.parallel_for_setup(num_coeffs_to_preserve, tileSize, range, GRange);\n\n    dev.template unary_kernel_launcher<typename Self::CoeffReturnType,\n                                       TensorSycl::internal::GenericNondeterministicReducer<Self, Op>>(\n        self, output, cl::sycl::nd_range<1>(cl::sycl::range<1>(GRange), cl::sycl::range<1>(tileSize)), Index(1),\n        reducer, range, (num_values_to_reduce != 0) ? num_values_to_reduce : static_cast<Index>(1));\n    return false;\n  }\n};\n\n}  // namespace internal\n}  // namespace Eigen\n\n#endif  // UNSUPPORTED_EIGEN_CXX11_SRC_TENSOR_TENSOR_REDUCTION_SYCL_HPP\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorRef.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_REF_H\n#define EIGEN_CXX11_TENSOR_TENSOR_REF_H\n\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate <typename Dimensions, typename Scalar>\nclass TensorLazyBaseEvaluator {\n public:\n  TensorLazyBaseEvaluator() : m_refcount(0) { }\n  virtual ~TensorLazyBaseEvaluator() { }\n\n  EIGEN_DEVICE_FUNC virtual const Dimensions& dimensions() const = 0;\n  EIGEN_DEVICE_FUNC virtual const Scalar* data() const = 0;\n\n  EIGEN_DEVICE_FUNC virtual const Scalar coeff(DenseIndex index) const = 0;\n  EIGEN_DEVICE_FUNC virtual Scalar& coeffRef(DenseIndex index) = 0;\n\n  void incrRefCount() { ++m_refcount; }\n  void decrRefCount() { --m_refcount; }\n  int refCount() const { return m_refcount; }\n\n private:\n  // No copy, no assignment;\n  TensorLazyBaseEvaluator(const TensorLazyBaseEvaluator& other);\n  TensorLazyBaseEvaluator& operator = (const TensorLazyBaseEvaluator& other);\n\n  int m_refcount;\n};\n\n\ntemplate <typename Dimensions, typename Expr, typename Device>\nclass TensorLazyEvaluatorReadOnly : public TensorLazyBaseEvaluator<Dimensions, typename TensorEvaluator<Expr, Device>::Scalar> {\n public:\n  //  typedef typename TensorEvaluator<Expr, Device>::Dimensions Dimensions;\n  typedef typename TensorEvaluator<Expr, Device>::Scalar Scalar;\n  typedef StorageMemory<Scalar, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n  typedef  TensorEvaluator<Expr, Device> EvalType;\n\n  TensorLazyEvaluatorReadOnly(const Expr& expr, const Device& device) : m_impl(expr, device), m_dummy(Scalar(0)) {\n    m_dims = m_impl.dimensions();\n    m_impl.evalSubExprsIfNeeded(NULL);\n  }\n  virtual ~TensorLazyEvaluatorReadOnly() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC virtual const Dimensions& dimensions() const {\n    return m_dims;\n  }\n  EIGEN_DEVICE_FUNC virtual const Scalar* data() const {\n    return m_impl.data();\n  }\n\n  EIGEN_DEVICE_FUNC virtual const Scalar coeff(DenseIndex index) const {\n    return m_impl.coeff(index);\n  }\n  EIGEN_DEVICE_FUNC virtual Scalar& coeffRef(DenseIndex /*index*/) {\n    eigen_assert(false && \"can't reference the coefficient of a rvalue\");\n    return m_dummy;\n  };\n\n protected:\n  TensorEvaluator<Expr, Device> m_impl;\n  Dimensions m_dims;\n  Scalar m_dummy;\n};\n\ntemplate <typename Dimensions, typename Expr, typename Device>\nclass TensorLazyEvaluatorWritable : public TensorLazyEvaluatorReadOnly<Dimensions, Expr, Device> {\n public:\n  typedef TensorLazyEvaluatorReadOnly<Dimensions, Expr, Device> Base;\n  typedef typename Base::Scalar Scalar;\n  typedef StorageMemory<Scalar, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  TensorLazyEvaluatorWritable(const Expr& expr, const Device& device) : Base(expr, device) {\n  }\n  virtual ~TensorLazyEvaluatorWritable() {\n  }\n\n  EIGEN_DEVICE_FUNC virtual Scalar& coeffRef(DenseIndex index) {\n    return this->m_impl.coeffRef(index);\n  }\n};\n\ntemplate <typename Dimensions, typename Expr, typename Device>\nclass TensorLazyEvaluator : public internal::conditional<bool(internal::is_lvalue<Expr>::value),\n                            TensorLazyEvaluatorWritable<Dimensions, Expr, Device>,\n                            TensorLazyEvaluatorReadOnly<Dimensions, const Expr, Device> >::type {\n public:\n  typedef typename internal::conditional<bool(internal::is_lvalue<Expr>::value),\n                                         TensorLazyEvaluatorWritable<Dimensions, Expr, Device>,\n                                         TensorLazyEvaluatorReadOnly<Dimensions, const Expr, Device> >::type Base;\n  typedef typename Base::Scalar Scalar;\n\n  TensorLazyEvaluator(const Expr& expr, const Device& device) : Base(expr, device) {\n  }\n  virtual ~TensorLazyEvaluator() {\n  }\n};\n\n}  // namespace internal\n\n\n/** \\class TensorRef\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief A reference to a tensor expression\n  * The expression will be evaluated lazily (as much as possible).\n  *\n  */\ntemplate<typename PlainObjectType> class TensorRef : public TensorBase<TensorRef<PlainObjectType> >\n{\n  public:\n    typedef TensorRef<PlainObjectType> Self;\n    typedef typename PlainObjectType::Base Base;\n    typedef typename Eigen::internal::nested<Self>::type Nested;\n    typedef typename internal::traits<PlainObjectType>::StorageKind StorageKind;\n    typedef typename internal::traits<PlainObjectType>::Index Index;\n    typedef typename internal::traits<PlainObjectType>::Scalar Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef typename Base::CoeffReturnType CoeffReturnType;\n    typedef Scalar* PointerType;\n    typedef PointerType PointerArgType;\n\n    static const Index NumIndices = PlainObjectType::NumIndices;\n    typedef typename PlainObjectType::Dimensions Dimensions;\n\n    enum {\n      IsAligned = false,\n      PacketAccess = false,\n      BlockAccess = false,\n      PreferBlockAccess = false,\n      Layout = PlainObjectType::Layout,\n      CoordAccess = false,  // to be implemented\n      RawAccess = false\n    };\n\n    //===- Tensor block evaluation strategy (see TensorBlock.h) -----------===//\n    typedef internal::TensorBlockNotImplemented TensorBlock;\n    //===------------------------------------------------------------------===//\n\n    EIGEN_STRONG_INLINE TensorRef() : m_evaluator(NULL) {\n    }\n\n    template <typename Expression>\n    EIGEN_STRONG_INLINE TensorRef(const Expression& expr) : m_evaluator(new internal::TensorLazyEvaluator<Dimensions, Expression, DefaultDevice>(expr, DefaultDevice())) {\n      m_evaluator->incrRefCount();\n    }\n\n    template <typename Expression>\n    EIGEN_STRONG_INLINE TensorRef& operator = (const Expression& expr) {\n      unrefEvaluator();\n      m_evaluator = new internal::TensorLazyEvaluator<Dimensions, Expression, DefaultDevice>(expr, DefaultDevice());\n      m_evaluator->incrRefCount();\n      return *this;\n    }\n\n    ~TensorRef() {\n      unrefEvaluator();\n    }\n\n    TensorRef(const TensorRef& other) : m_evaluator(other.m_evaluator) {\n      eigen_assert(m_evaluator->refCount() > 0);\n      m_evaluator->incrRefCount();\n    }\n\n    TensorRef& operator = (const TensorRef& other) {\n      if (this != &other) {\n        unrefEvaluator();\n        m_evaluator = other.m_evaluator;\n        eigen_assert(m_evaluator->refCount() > 0);\n        m_evaluator->incrRefCount();\n      }\n      return *this;\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Index rank() const { return m_evaluator->dimensions().size(); }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Index dimension(Index n) const { return m_evaluator->dimensions()[n]; }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_evaluator->dimensions(); }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Index size() const { return m_evaluator->dimensions().TotalSize(); }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar* data() const { return m_evaluator->data(); }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar operator()(Index index) const\n    {\n      return m_evaluator->coeff(index);\n    }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template<typename... IndexTypes> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar operator()(Index firstIndex, IndexTypes... otherIndices) const\n    {\n      const std::size_t num_indices = (sizeof...(otherIndices) + 1);\n      const array<Index, num_indices> indices{{firstIndex, otherIndices...}};\n      return coeff(indices);\n    }\n    template<typename... IndexTypes> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& coeffRef(Index firstIndex, IndexTypes... otherIndices)\n    {\n      const std::size_t num_indices = (sizeof...(otherIndices) + 1);\n      const array<Index, num_indices> indices{{firstIndex, otherIndices...}};\n      return coeffRef(indices);\n    }\n#else\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar operator()(Index i0, Index i1) const\n    {\n      array<Index, 2> indices;\n      indices[0] = i0;\n      indices[1] = i1;\n      return coeff(indices);\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar operator()(Index i0, Index i1, Index i2) const\n    {\n      array<Index, 3> indices;\n      indices[0] = i0;\n      indices[1] = i1;\n      indices[2] = i2;\n      return coeff(indices);\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar operator()(Index i0, Index i1, Index i2, Index i3) const\n    {\n      array<Index, 4> indices;\n      indices[0] = i0;\n      indices[1] = i1;\n      indices[2] = i2;\n      indices[3] = i3;\n      return coeff(indices);\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar operator()(Index i0, Index i1, Index i2, Index i3, Index i4) const\n    {\n      array<Index, 5> indices;\n      indices[0] = i0;\n      indices[1] = i1;\n      indices[2] = i2;\n      indices[3] = i3;\n      indices[4] = i4;\n      return coeff(indices);\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& coeffRef(Index i0, Index i1)\n    {\n      array<Index, 2> indices;\n      indices[0] = i0;\n      indices[1] = i1;\n      return coeffRef(indices);\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& coeffRef(Index i0, Index i1, Index i2)\n    {\n      array<Index, 3> indices;\n      indices[0] = i0;\n      indices[1] = i1;\n      indices[2] = i2;\n      return coeffRef(indices);\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& operator()(Index i0, Index i1, Index i2, Index i3)\n    {\n      array<Index, 4> indices;\n      indices[0] = i0;\n      indices[1] = i1;\n      indices[2] = i2;\n      indices[3] = i3;\n      return coeffRef(indices);\n    }\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& coeffRef(Index i0, Index i1, Index i2, Index i3, Index i4)\n    {\n      array<Index, 5> indices;\n      indices[0] = i0;\n      indices[1] = i1;\n      indices[2] = i2;\n      indices[3] = i3;\n      indices[4] = i4;\n      return coeffRef(indices);\n    }\n#endif\n\n    template <std::size_t NumIndices> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar coeff(const array<Index, NumIndices>& indices) const\n    {\n      const Dimensions& dims = this->dimensions();\n      Index index = 0;\n      if (PlainObjectType::Options & RowMajor) {\n        index += indices[0];\n        for (size_t i = 1; i < NumIndices; ++i) {\n          index = index * dims[i] + indices[i];\n        }\n      } else {\n        index += indices[NumIndices-1];\n        for (int i = NumIndices-2; i >= 0; --i) {\n          index = index * dims[i] + indices[i];\n        }\n      }\n      return m_evaluator->coeff(index);\n    }\n    template <std::size_t NumIndices> EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& coeffRef(const array<Index, NumIndices>& indices)\n    {\n      const Dimensions& dims = this->dimensions();\n      Index index = 0;\n      if (PlainObjectType::Options & RowMajor) {\n        index += indices[0];\n        for (size_t i = 1; i < NumIndices; ++i) {\n          index = index * dims[i] + indices[i];\n        }\n      } else {\n        index += indices[NumIndices-1];\n        for (int i = NumIndices-2; i >= 0; --i) {\n          index = index * dims[i] + indices[i];\n        }\n      }\n      return m_evaluator->coeffRef(index);\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE const Scalar coeff(Index index) const\n    {\n      return m_evaluator->coeff(index);\n    }\n\n    EIGEN_DEVICE_FUNC\n    EIGEN_STRONG_INLINE Scalar& coeffRef(Index index)\n    {\n      return m_evaluator->coeffRef(index);\n    }\n\n  private:\n    EIGEN_STRONG_INLINE void unrefEvaluator() {\n      if (m_evaluator) {\n        m_evaluator->decrRefCount();\n        if (m_evaluator->refCount() == 0) {\n          delete m_evaluator;\n        }\n      }\n    }\n\n  internal::TensorLazyBaseEvaluator<Dimensions, Scalar>* m_evaluator;\n};\n\n\n// evaluator for rvalues\ntemplate<typename Derived, typename Device>\nstruct TensorEvaluator<const TensorRef<Derived>, Device>\n{\n  typedef typename Derived::Index Index;\n  typedef typename Derived::Scalar Scalar;\n  typedef typename Derived::Scalar CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef typename Derived::Dimensions Dimensions;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = false,\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorRef<Derived>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const TensorRef<Derived>& m, const Device&)\n      : m_ref(m)\n  { }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_ref.dimensions(); }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    return true;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() { }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const {\n    return m_ref.coeff(index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index index) {\n    return m_ref.coeffRef(index);\n  }\n\n  EIGEN_DEVICE_FUNC const Scalar* data() const { return m_ref.data(); }\n\n protected:\n  TensorRef<Derived> m_ref;\n};\n\n\n// evaluator for lvalues\ntemplate<typename Derived, typename Device>\nstruct TensorEvaluator<TensorRef<Derived>, Device> : public TensorEvaluator<const TensorRef<Derived>, Device>\n{\n  typedef typename Derived::Index Index;\n  typedef typename Derived::Scalar Scalar;\n  typedef typename Derived::Scalar CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef typename Derived::Dimensions Dimensions;\n\n  typedef TensorEvaluator<const TensorRef<Derived>, Device> Base;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = false,\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(TensorRef<Derived>& m, const Device& d) : Base(m, d)\n  { }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index index) {\n    return this->m_ref.coeffRef(index);\n  }\n};\n\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_REF_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorReverse.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Navdeep Jaitly <ndjaitly@google.com>\n//                    Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_REVERSE_H\n#define EIGEN_CXX11_TENSOR_TENSOR_REVERSE_H\nnamespace Eigen {\n\n/** \\class TensorReverse\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor reverse elements class.\n  *\n  */\nnamespace internal {\ntemplate<typename ReverseDimensions, typename XprType>\nstruct traits<TensorReverseOp<ReverseDimensions,\n                              XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename ReverseDimensions, typename XprType>\nstruct eval<TensorReverseOp<ReverseDimensions, XprType>, Eigen::Dense>\n{\n  typedef const TensorReverseOp<ReverseDimensions, XprType>& type;\n};\n\ntemplate<typename ReverseDimensions, typename XprType>\nstruct nested<TensorReverseOp<ReverseDimensions, XprType>, 1,\n            typename eval<TensorReverseOp<ReverseDimensions, XprType> >::type>\n{\n  typedef TensorReverseOp<ReverseDimensions, XprType> type;\n};\n\n}  // end namespace internal\n\ntemplate<typename ReverseDimensions, typename XprType>\nclass TensorReverseOp : public TensorBase<TensorReverseOp<ReverseDimensions,\n                                          XprType>, WriteAccessors>\n{\n  public:\n    typedef TensorBase<TensorReverseOp<ReverseDimensions, XprType>, WriteAccessors>Base;\n    typedef typename Eigen::internal::traits<TensorReverseOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef typename XprType::CoeffReturnType CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorReverseOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorReverseOp>::StorageKind\n                                                                      StorageKind;\n    typedef typename Eigen::internal::traits<TensorReverseOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorReverseOp(\n      const XprType& expr, const ReverseDimensions& reverse_dims)\n      : m_xpr(expr), m_reverse_dims(reverse_dims) { }\n\n    EIGEN_DEVICE_FUNC\n    const ReverseDimensions& reverse() const { return m_reverse_dims; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(TensorReverseOp)\n\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const ReverseDimensions m_reverse_dims;\n};\n\n// Eval as rvalue\ntemplate<typename ReverseDimensions, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorReverseOp<ReverseDimensions, ArgType>, Device>\n{\n  typedef TensorReverseOp<ReverseDimensions, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<ReverseDimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned         = false,\n    PacketAccess      = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess       = NumDims > 0,\n    PreferBlockAccess = true,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = false\n  };\n\n  typedef internal::TensorIntDivisor<Index> IndexDivisor;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename TensorEvaluator<const ArgType, Device>::TensorBlock\n      ArgTensorBlock;\n\n  typedef typename internal::TensorMaterializedBlock<CoeffReturnType, NumDims,\n                                                     Layout, Index>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op,\n                                                        const Device& device)\n      : m_impl(op.expression(), device),\n        m_reverse(op.reverse()),\n        m_device(device)\n  {\n    // Reversing a scalar isn't supported yet. It would be a no-op anyway.\n    EIGEN_STATIC_ASSERT((NumDims > 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    // Compute strides\n    m_dimensions = m_impl.dimensions();\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_strides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_strides[i] = m_strides[i-1] * m_dimensions[i-1];\n        if (m_strides[i] > 0) m_fastStrides[i] = IndexDivisor(m_strides[i]);\n      }\n    } else {\n      m_strides[NumDims-1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_strides[i] = m_strides[i+1] * m_dimensions[i+1];\n        if (m_strides[i] > 0) m_fastStrides[i] = IndexDivisor(m_strides[i]);\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    m_impl.evalSubExprsIfNeededAsync(nullptr, [done](bool) { done(true); });\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index reverseIndex(\n      Index index) const {\n    eigen_assert(index < dimensions().TotalSize());\n    Index inputIndex = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i > 0; --i) {\n        Index idx = index / m_fastStrides[i];\n        index -= idx * m_strides[i];\n        if (m_reverse[i]) {\n          idx = m_dimensions[i] - idx - 1;\n        }\n        inputIndex += idx * m_strides[i] ;\n      }\n      if (m_reverse[0]) {\n        inputIndex += (m_dimensions[0] - index - 1);\n      } else {\n        inputIndex += index;\n      }\n    } else {\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 1; ++i) {\n        Index idx = index / m_fastStrides[i];\n        index -= idx * m_strides[i];\n        if (m_reverse[i]) {\n          idx = m_dimensions[i] - idx - 1;\n        }\n        inputIndex += idx * m_strides[i] ;\n      }\n      if (m_reverse[NumDims-1]) {\n        inputIndex += (m_dimensions[NumDims-1] - index - 1);\n      } else {\n        inputIndex += index;\n      }\n    }\n    return inputIndex;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(\n      Index index) const  {\n    return m_impl.coeff(reverseIndex(index));\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  PacketReturnType packet(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    // TODO(ndjaitly): write a better packing routine that uses\n    // local structure.\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type\n                                                            values[PacketSize];\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < PacketSize; ++i) {\n      values[i] = coeff(index+i);\n    }\n    PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n    return rslt;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    const size_t target_size = m_device.lastLevelCacheSize();\n    // Block evaluation reads underlying memory in reverse order, and default\n    // cost model does not properly catch this in bytes stored/loaded.\n    return internal::TensorBlockResourceRequirements::skewed<Scalar>(\n               target_size)\n        .addCostPerCoeff({0, 0, 24});\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool /*root_of_expr_ast*/ = false) const {\n    // TODO(ezhulenev): If underlying tensor expression supports and prefers\n    // block evaluation we must use it. Currently we use coeff and packet\n    // access into the underlying tensor expression.\n    // static const bool useBlockAccessForArgType =\n    //     TensorEvaluator<ArgType, Device>::BlockAccess &&\n    //     TensorEvaluator<ArgType, Device>::PreferBlockAccess;\n\n    static const bool isColMajor =\n        static_cast<int>(Layout) == static_cast<int>(ColMajor);\n\n    static const Index inner_dim_idx = isColMajor ? 0 : NumDims - 1;\n    const bool inner_dim_reversed = m_reverse[inner_dim_idx];\n\n    // Offset in the output block.\n    Index block_offset = 0;\n\n    // Offset in the input Tensor.\n    Index input_offset = reverseIndex(desc.offset());\n\n    // Initialize output block iterator state. Dimension in this array are\n    // always in inner_most -> outer_most order (col major layout).\n    array<BlockIteratorState, NumDims> it;\n    for (int i = 0; i < NumDims; ++i) {\n      const int dim = isColMajor ? i : NumDims - 1 - i;\n      it[i].size = desc.dimension(dim);\n      it[i].count = 0;\n      it[i].reverse = m_reverse[dim];\n\n      it[i].block_stride =\n          i == 0 ? 1 : (it[i - 1].size * it[i - 1].block_stride);\n      it[i].block_span = it[i].block_stride * (it[i].size - 1);\n\n      it[i].input_stride = m_strides[dim];\n      it[i].input_span = it[i].input_stride * (it[i].size - 1);\n\n      if (it[i].reverse) {\n        it[i].input_stride = -1 * it[i].input_stride;\n        it[i].input_span = -1 * it[i].input_span;\n      }\n    }\n\n    // If multiple inner dimensions have the same reverse flag, check if we can\n    // merge them into a single virtual inner dimension.\n    int effective_inner_dim = 0;\n    for (int i = 1; i < NumDims; ++i) {\n      if (it[i].reverse != it[effective_inner_dim].reverse) break;\n      if (it[i].block_stride != it[effective_inner_dim].size) break;\n      if (it[i].block_stride != numext::abs(it[i].input_stride)) break;\n\n      it[i].size = it[effective_inner_dim].size * it[i].size;\n\n      it[i].block_stride = 1;\n      it[i].input_stride = (inner_dim_reversed ? -1 : 1);\n\n      it[i].block_span = it[i].block_stride * (it[i].size - 1);\n      it[i].input_span = it[i].input_stride * (it[i].size - 1);\n\n      effective_inner_dim = i;\n    }\n\n    eigen_assert(it[effective_inner_dim].block_stride == 1);\n    eigen_assert(it[effective_inner_dim].input_stride ==\n                 (inner_dim_reversed ? -1 : 1));\n\n    const Index inner_dim_size = it[effective_inner_dim].size;\n\n    // Prepare storage for the materialized reverse result.\n    const typename TensorBlock::Storage block_storage =\n        TensorBlock::prepareStorage(desc, scratch);\n    CoeffReturnType* block_buffer = block_storage.data();\n\n    while (it[NumDims - 1].count < it[NumDims - 1].size) {\n      // Copy inner-most dimension data from reversed location in input.\n      Index dst = block_offset;\n      Index src = input_offset;\n\n      // NOTE(ezhulenev): Adding vectorized path with internal::preverse showed\n      // worse results in benchmarks than a simple coefficient loop.\n      if (inner_dim_reversed) {\n        for (Index i = 0; i < inner_dim_size; ++i) {\n          block_buffer[dst] = m_impl.coeff(src);\n          ++dst;\n          --src;\n        }\n      } else {\n        for (Index i = 0; i < inner_dim_size; ++i) {\n          block_buffer[dst] = m_impl.coeff(src);\n          ++dst;\n          ++src;\n        }\n      }\n\n      // For the 1d tensor we need to generate only one inner-most dimension.\n      if ((NumDims - effective_inner_dim) == 1) break;\n\n      // Update offset.\n      for (Index i = effective_inner_dim + 1; i < NumDims; ++i) {\n        if (++it[i].count < it[i].size) {\n          block_offset += it[i].block_stride;\n          input_offset += it[i].input_stride;\n          break;\n        }\n        if (i != NumDims - 1) it[i].count = 0;\n        block_offset -= it[i].block_span;\n        input_offset -= it[i].input_span;\n      }\n    }\n\n    return block_storage.AsTensorMaterializedBlock();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    double compute_cost = NumDims * (2 * TensorOpCost::AddCost<Index>() +\n                                     2 * TensorOpCost::MulCost<Index>() +\n                                     TensorOpCost::DivCost<Index>());\n    for (int i = 0; i < NumDims; ++i) {\n      if (m_reverse[i]) {\n        compute_cost += 2 * TensorOpCost::AddCost<Index>();\n      }\n    }\n    return m_impl.costPerCoeff(vectorized) +\n           TensorOpCost(0, 0, compute_cost, false /* vectorized */, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC typename Storage::Type data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n\n protected:\n  Dimensions m_dimensions;\n  array<Index, NumDims> m_strides;\n  array<IndexDivisor, NumDims> m_fastStrides;\n  TensorEvaluator<ArgType, Device> m_impl;\n  ReverseDimensions m_reverse;\n  const Device EIGEN_DEVICE_REF m_device;\n\n private:\n  struct BlockIteratorState {\n    BlockIteratorState()\n        : size(0),\n          count(0),\n          reverse(false),\n          block_stride(0),\n          block_span(0),\n          input_stride(0),\n          input_span(0) {}\n\n    Index size;\n    Index count;\n    bool reverse;\n    Index block_stride;\n    Index block_span;\n    Index input_stride;\n    Index input_span;\n  };\n};\n\n// Eval as lvalue\n\ntemplate <typename ReverseDimensions, typename ArgType, typename Device>\nstruct TensorEvaluator<TensorReverseOp<ReverseDimensions, ArgType>, Device>\n    : public TensorEvaluator<const TensorReverseOp<ReverseDimensions, ArgType>,\n                             Device> {\n  typedef TensorEvaluator<const TensorReverseOp<ReverseDimensions, ArgType>,\n                          Device> Base;\n  typedef TensorReverseOp<ReverseDimensions, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<ReverseDimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op,\n                                                        const Device& device)\n      : Base(op, device) {}\n\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  const Dimensions& dimensions() const { return this->m_dimensions; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index index) {\n    return this->m_impl.coeffRef(this->reverseIndex(index));\n  }\n\n  template <int StoreMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void writePacket(Index index, const PacketReturnType& x) {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    // This code is pilfered from TensorMorphing.h\n    EIGEN_ALIGN_MAX CoeffReturnType values[PacketSize];\n    internal::pstore<CoeffReturnType, PacketReturnType>(values, x);\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < PacketSize; ++i) {\n      this->coeffRef(index+i) = values[i];\n    }\n  }\n};\n\n\n}  // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_REVERSE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorScan.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Igor Babuschkin <igor@babuschk.in>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_SCAN_H\n#define EIGEN_CXX11_TENSOR_TENSOR_SCAN_H\n\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate <typename Op, typename XprType>\nstruct traits<TensorScanOp<Op, XprType> >\n    : public traits<XprType> {\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename Op, typename XprType>\nstruct eval<TensorScanOp<Op, XprType>, Eigen::Dense>\n{\n  typedef const TensorScanOp<Op, XprType>& type;\n};\n\ntemplate<typename Op, typename XprType>\nstruct nested<TensorScanOp<Op, XprType>, 1,\n            typename eval<TensorScanOp<Op, XprType> >::type>\n{\n  typedef TensorScanOp<Op, XprType> type;\n};\n} // end namespace internal\n\n/** \\class TensorScan\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor scan class.\n  */\ntemplate <typename Op, typename XprType>\nclass TensorScanOp\n    : public TensorBase<TensorScanOp<Op, XprType>, ReadOnlyAccessors> {\npublic:\n  typedef typename Eigen::internal::traits<TensorScanOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorScanOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorScanOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorScanOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorScanOp(\n      const XprType& expr, const Index& axis, bool exclusive = false, const Op& op = Op())\n      : m_expr(expr), m_axis(axis), m_accumulator(op), m_exclusive(exclusive) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  const Index axis() const { return m_axis; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  const XprType& expression() const { return m_expr; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  const Op accumulator() const { return m_accumulator; }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  bool exclusive() const { return m_exclusive; }\n\nprotected:\n  typename XprType::Nested m_expr;\n  const Index m_axis;\n  const Op m_accumulator;\n  const bool m_exclusive;\n};\n\n\nnamespace internal {\n\ntemplate <typename Self>\nEIGEN_STRONG_INLINE void ReduceScalar(Self& self, Index offset,\n                                      typename Self::CoeffReturnType* data) {\n  // Compute the scan along the axis, starting at the given offset\n  typename Self::CoeffReturnType accum = self.accumulator().initialize();\n  if (self.stride() == 1) {\n    if (self.exclusive()) {\n      for (Index curr = offset; curr < offset + self.size(); ++curr) {\n        data[curr] = self.accumulator().finalize(accum);\n        self.accumulator().reduce(self.inner().coeff(curr), &accum);\n      }\n    } else {\n      for (Index curr = offset; curr < offset + self.size(); ++curr) {\n        self.accumulator().reduce(self.inner().coeff(curr), &accum);\n        data[curr] = self.accumulator().finalize(accum);\n      }\n    }\n  } else {\n    if (self.exclusive()) {\n      for (Index idx3 = 0; idx3 < self.size(); idx3++) {\n        Index curr = offset + idx3 * self.stride();\n        data[curr] = self.accumulator().finalize(accum);\n        self.accumulator().reduce(self.inner().coeff(curr), &accum);\n      }\n    } else {\n      for (Index idx3 = 0; idx3 < self.size(); idx3++) {\n        Index curr = offset + idx3 * self.stride();\n        self.accumulator().reduce(self.inner().coeff(curr), &accum);\n        data[curr] = self.accumulator().finalize(accum);\n      }\n    }\n  }\n}\n\ntemplate <typename Self>\nEIGEN_STRONG_INLINE void ReducePacket(Self& self, Index offset,\n                                      typename Self::CoeffReturnType* data) {\n  using Scalar = typename Self::CoeffReturnType;\n  using Packet = typename Self::PacketReturnType;\n  // Compute the scan along the axis, starting at the calculated offset\n  Packet accum = self.accumulator().template initializePacket<Packet>();\n  if (self.stride() == 1) {\n    if (self.exclusive()) {\n      for (Index curr = offset; curr < offset + self.size(); ++curr) {\n        internal::pstoreu<Scalar, Packet>(data + curr, self.accumulator().finalizePacket(accum));\n        self.accumulator().reducePacket(self.inner().template packet<Unaligned>(curr), &accum);\n      }\n    } else {\n      for (Index curr = offset; curr < offset + self.size(); ++curr) {\n        self.accumulator().reducePacket(self.inner().template packet<Unaligned>(curr), &accum);\n        internal::pstoreu<Scalar, Packet>(data + curr, self.accumulator().finalizePacket(accum));\n      }\n    }\n  } else {\n    if (self.exclusive()) {\n      for (Index idx3 = 0; idx3 < self.size(); idx3++) {\n        const Index curr = offset + idx3 * self.stride();\n        internal::pstoreu<Scalar, Packet>(data + curr, self.accumulator().finalizePacket(accum));\n        self.accumulator().reducePacket(self.inner().template packet<Unaligned>(curr), &accum);\n      }\n    } else {\n      for (Index idx3 = 0; idx3 < self.size(); idx3++) {\n        const Index curr = offset + idx3 * self.stride();\n        self.accumulator().reducePacket(self.inner().template packet<Unaligned>(curr), &accum);\n        internal::pstoreu<Scalar, Packet>(data + curr, self.accumulator().finalizePacket(accum));\n      }\n    }\n  }\n}\n\ntemplate <typename Self, bool Vectorize, bool Parallel>\nstruct ReduceBlock {\n  EIGEN_STRONG_INLINE void operator()(Self& self, Index idx1,\n                                      typename Self::CoeffReturnType* data) {\n    for (Index idx2 = 0; idx2 < self.stride(); idx2++) {\n      // Calculate the starting offset for the scan\n      Index offset = idx1 + idx2;\n      ReduceScalar(self, offset, data);\n    }\n  }\n};\n\n// Specialization for vectorized reduction.\ntemplate <typename Self>\nstruct ReduceBlock<Self, /*Vectorize=*/true, /*Parallel=*/false> {\n  EIGEN_STRONG_INLINE void operator()(Self& self, Index idx1,\n                                      typename Self::CoeffReturnType* data) {\n    using Packet = typename Self::PacketReturnType;\n    const int PacketSize = internal::unpacket_traits<Packet>::size;\n    Index idx2 = 0;\n    for (; idx2 + PacketSize <= self.stride(); idx2 += PacketSize) {\n      // Calculate the starting offset for the packet scan\n      Index offset = idx1 + idx2;\n      ReducePacket(self, offset, data);\n    }\n    for (; idx2 < self.stride(); idx2++) {\n      // Calculate the starting offset for the scan\n      Index offset = idx1 + idx2;\n      ReduceScalar(self, offset, data);\n    }\n  }\n};\n\n// Single-threaded CPU implementation of scan\ntemplate <typename Self, typename Reducer, typename Device,\n          bool Vectorize =\n              (TensorEvaluator<typename Self::ChildTypeNoConst, Device>::PacketAccess &&\n               internal::reducer_traits<Reducer, Device>::PacketAccess)>\nstruct ScanLauncher {\n  void operator()(Self& self, typename Self::CoeffReturnType* data) {\n    Index total_size = internal::array_prod(self.dimensions());\n\n    // We fix the index along the scan axis to 0 and perform a\n    // scan per remaining entry. The iteration is split into two nested\n    // loops to avoid an integer division by keeping track of each idx1 and\n    // idx2.\n    for (Index idx1 = 0; idx1 < total_size; idx1 += self.stride() * self.size()) {\n      ReduceBlock<Self, Vectorize, /*Parallel=*/false> block_reducer;\n      block_reducer(self, idx1, data);\n    }\n  }\n};\n\n#ifdef EIGEN_USE_THREADS\n\n// Adjust block_size to avoid false sharing of cachelines among\n// threads. Currently set to twice the cache line size on Intel and ARM\n// processors.\nEIGEN_STRONG_INLINE Index AdjustBlockSize(Index item_size, Index block_size) {\n  EIGEN_CONSTEXPR Index kBlockAlignment = 128;\n  const Index items_per_cacheline =\n      numext::maxi<Index>(1, kBlockAlignment / item_size);\n  return items_per_cacheline * divup(block_size, items_per_cacheline);\n}\n\ntemplate <typename Self>\nstruct ReduceBlock<Self, /*Vectorize=*/true, /*Parallel=*/true> {\n  EIGEN_STRONG_INLINE void operator()(Self& self, Index idx1,\n                                      typename Self::CoeffReturnType* data) {\n    using Scalar = typename Self::CoeffReturnType;\n    using Packet = typename Self::PacketReturnType;\n    const int PacketSize = internal::unpacket_traits<Packet>::size;\n    Index num_scalars = self.stride();\n    Index num_packets = 0;\n    if (self.stride() >= PacketSize) {\n      num_packets = self.stride() / PacketSize;\n      self.device().parallelFor(\n          num_packets,\n        TensorOpCost(PacketSize * self.size(), PacketSize * self.size(),\n                     16 * PacketSize * self.size(), true, PacketSize),\n        // Make the shard size large enough that two neighboring threads\n        // won't write to the same cacheline of `data`.\n        [=](Index blk_size) {\n          return AdjustBlockSize(PacketSize * sizeof(Scalar), blk_size);\n        },\n        [&](Index first, Index last) {\n          for (Index packet = first; packet < last; ++packet) {\n            const Index idx2 = packet * PacketSize;\n            ReducePacket(self, idx1 + idx2, data);\n          }\n        });\n      num_scalars -= num_packets * PacketSize;\n    }\n    self.device().parallelFor(\n        num_scalars, TensorOpCost(self.size(), self.size(), 16 * self.size()),\n        // Make the shard size large enough that two neighboring threads\n        // won't write to the same cacheline of `data`.\n        [=](Index blk_size) {\n          return AdjustBlockSize(sizeof(Scalar), blk_size);\n        },\n        [&](Index first, Index last) {\n          for (Index scalar = first; scalar < last; ++scalar) {\n            const Index idx2 = num_packets * PacketSize + scalar;\n            ReduceScalar(self, idx1 + idx2, data);\n          }\n        });\n  }\n};\n\ntemplate <typename Self>\nstruct ReduceBlock<Self, /*Vectorize=*/false, /*Parallel=*/true> {\n  EIGEN_STRONG_INLINE void operator()(Self& self, Index idx1,\n                                      typename Self::CoeffReturnType* data) {\n    using Scalar = typename Self::CoeffReturnType;\n    self.device().parallelFor(\n        self.stride(), TensorOpCost(self.size(), self.size(), 16 * self.size()),\n        // Make the shard size large enough that two neighboring threads\n        // won't write to the same cacheline of `data`.\n        [=](Index blk_size) {\n          return AdjustBlockSize(sizeof(Scalar), blk_size);\n        },\n        [&](Index first, Index last) {\n          for (Index idx2 = first; idx2 < last; ++idx2) {\n            ReduceScalar(self, idx1 + idx2, data);\n          }\n        });\n  }\n};\n\n// Specialization for multi-threaded execution.\ntemplate <typename Self, typename Reducer, bool Vectorize>\nstruct ScanLauncher<Self, Reducer, ThreadPoolDevice, Vectorize> {\n  void operator()(Self& self, typename Self::CoeffReturnType* data) {\n    using Scalar = typename Self::CoeffReturnType;\n    using Packet = typename Self::PacketReturnType;\n    const int PacketSize = internal::unpacket_traits<Packet>::size;\n    const Index total_size = internal::array_prod(self.dimensions());\n    const Index inner_block_size = self.stride() * self.size();\n    bool parallelize_by_outer_blocks = (total_size >= (self.stride() * inner_block_size));\n\n    if ((parallelize_by_outer_blocks && total_size <= 4096) ||\n        (!parallelize_by_outer_blocks && self.stride() < PacketSize)) {\n      ScanLauncher<Self, Reducer, DefaultDevice, Vectorize> launcher;\n      launcher(self, data);\n      return;\n    }\n\n    if (parallelize_by_outer_blocks) {\n      // Parallelize over outer blocks.\n      const Index num_outer_blocks = total_size / inner_block_size;\n      self.device().parallelFor(\n          num_outer_blocks,\n          TensorOpCost(inner_block_size, inner_block_size,\n                       16 * PacketSize * inner_block_size, Vectorize,\n                       PacketSize),\n          [=](Index blk_size) {\n            return AdjustBlockSize(inner_block_size * sizeof(Scalar), blk_size);\n          },\n          [&](Index first, Index last) {\n            for (Index idx1 = first; idx1 < last; ++idx1) {\n              ReduceBlock<Self, Vectorize, /*Parallelize=*/false> block_reducer;\n              block_reducer(self, idx1 * inner_block_size, data);\n            }\n          });\n    } else {\n      // Parallelize over inner packets/scalars dimensions when the reduction\n      // axis is not an inner dimension.\n      ReduceBlock<Self, Vectorize, /*Parallelize=*/true> block_reducer;\n      for (Index idx1 = 0; idx1 < total_size;\n           idx1 += self.stride() * self.size()) {\n        block_reducer(self, idx1, data);\n      }\n    }\n  }\n};\n#endif  // EIGEN_USE_THREADS\n\n#if defined(EIGEN_USE_GPU) && (defined(EIGEN_GPUCC))\n\n// GPU implementation of scan\n// TODO(ibab) This placeholder implementation performs multiple scans in\n// parallel, but it would be better to use a parallel scan algorithm and\n// optimize memory access.\ntemplate <typename Self, typename Reducer>\n__global__ EIGEN_HIP_LAUNCH_BOUNDS_1024 void ScanKernel(Self self, Index total_size, typename Self::CoeffReturnType* data) {\n  // Compute offset as in the CPU version\n  Index val = threadIdx.x + blockIdx.x * blockDim.x;\n  Index offset = (val / self.stride()) * self.stride() * self.size() + val % self.stride();\n\n  if (offset + (self.size() - 1) * self.stride() < total_size) {\n    // Compute the scan along the axis, starting at the calculated offset\n    typename Self::CoeffReturnType accum = self.accumulator().initialize();\n    for (Index idx = 0; idx < self.size(); idx++) {\n      Index curr = offset + idx * self.stride();\n      if (self.exclusive()) {\n        data[curr] = self.accumulator().finalize(accum);\n        self.accumulator().reduce(self.inner().coeff(curr), &accum);\n      } else {\n        self.accumulator().reduce(self.inner().coeff(curr), &accum);\n        data[curr] = self.accumulator().finalize(accum);\n      }\n    }\n  }\n  __syncthreads();\n\n}\n\ntemplate <typename Self, typename Reducer>\nstruct ScanLauncher<Self, Reducer, GpuDevice, false> {\n  void operator()(const Self& self, typename Self::CoeffReturnType* data) {\n     Index total_size = internal::array_prod(self.dimensions());\n     Index num_blocks = (total_size / self.size() + 63) / 64;\n     Index block_size = 64;\n\n     LAUNCH_GPU_KERNEL((ScanKernel<Self, Reducer>), num_blocks, block_size, 0, self.device(), self, total_size, data);\n  }\n};\n#endif  // EIGEN_USE_GPU && (EIGEN_GPUCC)\n\n}  // namespace internal\n\n// Eval as rvalue\ntemplate <typename Op, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorScanOp<Op, ArgType>, Device> {\n\n  typedef TensorScanOp<Op, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  typedef const ArgType ChildTypeNoConst;\n  typedef const ArgType ChildType;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename internal::remove_const<typename XprType::Scalar>::type Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  typedef TensorEvaluator<const TensorScanOp<Op, ArgType>, Device> Self;\n  typedef StorageMemory<Scalar, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess = false,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,\n    RawAccess = true\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op,\n                                                        const Device& device)\n      : m_impl(op.expression(), device),\n        m_device(device),\n        m_exclusive(op.exclusive()),\n        m_accumulator(op.accumulator()),\n        m_size(m_impl.dimensions()[op.axis()]),\n        m_stride(1), m_consume_dim(op.axis()),\n        m_output(NULL) {\n\n    // Accumulating a scalar isn't supported.\n    EIGEN_STATIC_ASSERT((NumDims > 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    eigen_assert(op.axis() >= 0 && op.axis() < NumDims);\n\n    // Compute stride of scan axis\n    const Dimensions& dims = m_impl.dimensions();\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = 0; i < op.axis(); ++i) {\n        m_stride = m_stride * dims[i];\n      }\n    } else {\n      // dims can only be indexed through unsigned integers,\n      // so let's use an unsigned type to let the compiler knows.\n      // This prevents stupid warnings: \"\"'*((void*)(& evaluator)+64)[18446744073709551615]' may be used uninitialized in this function\"\n      unsigned int axis = internal::convert_index<unsigned int>(op.axis());\n      for (unsigned int i = NumDims - 1; i > axis; --i) {\n        m_stride = m_stride * dims[i];\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const {\n    return m_impl.dimensions();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Index& stride() const {\n    return m_stride;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Index& consume_dim() const {\n    return m_consume_dim;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Index& size() const {\n    return m_size;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Op& accumulator() const {\n    return m_accumulator;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool exclusive() const {\n    return m_exclusive;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const TensorEvaluator<ArgType, Device>& inner() const {\n    return m_impl;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Device& device() const {\n    return m_device;\n  }\n\n  EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType data) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    internal::ScanLauncher<Self, Op, Device> launcher;\n    if (data) {\n      launcher(*this, data);\n      return false;\n    }\n\n    const Index total_size = internal::array_prod(dimensions());\n    m_output = static_cast<EvaluatorPointerType>(m_device.get((Scalar*) m_device.allocate_temp(total_size * sizeof(Scalar))));\n    launcher(*this, m_output);\n    return true;\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC PacketReturnType packet(Index index) const {\n    return internal::ploadt<PacketReturnType, LoadMode>(m_output + index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE EvaluatorPointerType data() const\n  {\n    return m_output;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    return m_output[index];\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool) const {\n    return TensorOpCost(sizeof(CoeffReturnType), 0, 0);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    if (m_output) {\n      m_device.deallocate_temp(m_output);\n      m_output = NULL;\n    }\n    m_impl.cleanup();\n  }\n\n#ifdef EIGEN_USE_SYCL\n // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n    m_output.bind(cgh);\n  }\n#endif\nprotected:\n  TensorEvaluator<ArgType, Device> m_impl;\n  const Device EIGEN_DEVICE_REF m_device;\n  const bool m_exclusive;\n  Op m_accumulator;\n  const Index m_size;\n  Index m_stride;\n  Index m_consume_dim;\n  EvaluatorPointerType m_output;\n};\n\n}  // end namespace Eigen\n\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_SCAN_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorScanSycl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n/*****************************************************************\n * TensorScanSycl.h\n *\n * \\brief:\n *  Tensor Scan Sycl implement the extend  version of\n * \"Efficient parallel scan algorithms for GPUs.\" .for Tensor operations.\n * The algorithm requires up to 3 stage (consequently 3 kernels) depending on\n * the size of the tensor. In the first kernel (ScanKernelFunctor), each\n * threads within the work-group individually reduces the allocated elements per\n * thread in order to reduces the total number of blocks. In the next step all\n * thread within the work-group will reduce the associated blocks into the\n * temporary buffers. In the next kernel(ScanBlockKernelFunctor), the temporary\n * buffer is given as an input and all the threads within a work-group scan and\n * reduces the boundaries between the blocks (generated from the previous\n * kernel). and write the data on the temporary buffer. If the second kernel is\n * required, the third and final kerenl (ScanAdjustmentKernelFunctor) will\n * adjust the final result into the output buffer.\n * The original algorithm for the parallel prefix sum can be found here:\n *\n * Sengupta, Shubhabrata, Mark Harris, and Michael Garland. \"Efficient parallel\n * scan algorithms for GPUs.\" NVIDIA, Santa Clara, CA, Tech. Rep. NVR-2008-003\n *1, no. 1 (2008): 1-17.\n *****************************************************************/\n\n#ifndef UNSUPPORTED_EIGEN_CXX11_SRC_TENSOR_TENSOR_SYCL_SYCL_HPP\n#define UNSUPPORTED_EIGEN_CXX11_SRC_TENSOR_TENSOR_SYCL_SYCL_HPP\n\nnamespace Eigen {\nnamespace TensorSycl {\nnamespace internal {\n\n#ifndef EIGEN_SYCL_MAX_GLOBAL_RANGE\n#define EIGEN_SYCL_MAX_GLOBAL_RANGE (EIGEN_SYCL_LOCAL_THREAD_DIM0 * EIGEN_SYCL_LOCAL_THREAD_DIM1 * 4)\n#endif\n\ntemplate <typename index_t>\nstruct ScanParameters {\n  // must be power of 2\n  static EIGEN_CONSTEXPR index_t ScanPerThread = 8;\n  const index_t total_size;\n  const index_t non_scan_size;\n  const index_t scan_size;\n  const index_t non_scan_stride;\n  const index_t scan_stride;\n  const index_t panel_threads;\n  const index_t group_threads;\n  const index_t block_threads;\n  const index_t elements_per_group;\n  const index_t elements_per_block;\n  const index_t loop_range;\n\n  ScanParameters(index_t total_size_, index_t non_scan_size_, index_t scan_size_, index_t non_scan_stride_,\n                 index_t scan_stride_, index_t panel_threads_, index_t group_threads_, index_t block_threads_,\n                 index_t elements_per_group_, index_t elements_per_block_, index_t loop_range_)\n      : total_size(total_size_),\n        non_scan_size(non_scan_size_),\n        scan_size(scan_size_),\n        non_scan_stride(non_scan_stride_),\n        scan_stride(scan_stride_),\n        panel_threads(panel_threads_),\n        group_threads(group_threads_),\n        block_threads(block_threads_),\n        elements_per_group(elements_per_group_),\n        elements_per_block(elements_per_block_),\n        loop_range(loop_range_) {}\n};\n\nenum class scan_step { first, second };\ntemplate <typename Evaluator, typename CoeffReturnType, typename OutAccessor, typename Op, typename Index,\n          scan_step stp>\nstruct ScanKernelFunctor {\n  typedef cl::sycl::accessor<CoeffReturnType, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local>\n      LocalAccessor;\n  static EIGEN_CONSTEXPR int PacketSize = ScanParameters<Index>::ScanPerThread / 2;\n\n  LocalAccessor scratch;\n  Evaluator dev_eval;\n  OutAccessor out_accessor;\n  OutAccessor temp_accessor;\n  const ScanParameters<Index> scanParameters;\n  Op accumulator;\n  const bool inclusive;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ScanKernelFunctor(LocalAccessor scratch_, const Evaluator dev_eval_,\n                                                          OutAccessor out_accessor_, OutAccessor temp_accessor_,\n                                                          const ScanParameters<Index> scanParameters_, Op accumulator_,\n                                                          const bool inclusive_)\n      : scratch(scratch_),\n        dev_eval(dev_eval_),\n        out_accessor(out_accessor_),\n        temp_accessor(temp_accessor_),\n        scanParameters(scanParameters_),\n        accumulator(accumulator_),\n        inclusive(inclusive_) {}\n\n  template <scan_step sst = stp, typename Input>\n  typename ::Eigen::internal::enable_if<sst == scan_step::first, CoeffReturnType>::type EIGEN_DEVICE_FUNC\n      EIGEN_STRONG_INLINE\n      read(const Input &inpt, Index global_id) {\n    return inpt.coeff(global_id);\n  }\n\n  template <scan_step sst = stp, typename Input>\n  typename ::Eigen::internal::enable_if<sst != scan_step::first, CoeffReturnType>::type EIGEN_DEVICE_FUNC\n      EIGEN_STRONG_INLINE\n      read(const Input &inpt, Index global_id) {\n    return inpt[global_id];\n  }\n\n  template <scan_step sst = stp, typename InclusiveOp>\n  typename ::Eigen::internal::enable_if<sst == scan_step::first>::type EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  first_step_inclusive_Operation(InclusiveOp inclusive_op) {\n    inclusive_op();\n  }\n\n  template <scan_step sst = stp, typename InclusiveOp>\n  typename ::Eigen::internal::enable_if<sst != scan_step::first>::type EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  first_step_inclusive_Operation(InclusiveOp) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void operator()(cl::sycl::nd_item<1> itemID) {\n    auto out_ptr = out_accessor.get_pointer();\n    auto tmp_ptr = temp_accessor.get_pointer();\n    auto scratch_ptr = scratch.get_pointer().get();\n\n    for (Index loop_offset = 0; loop_offset < scanParameters.loop_range; loop_offset++) {\n      Index data_offset = (itemID.get_global_id(0) + (itemID.get_global_range(0) * loop_offset));\n      Index tmp = data_offset % scanParameters.panel_threads;\n      const Index panel_id = data_offset / scanParameters.panel_threads;\n      const Index group_id = tmp / scanParameters.group_threads;\n      tmp = tmp % scanParameters.group_threads;\n      const Index block_id = tmp / scanParameters.block_threads;\n      const Index local_id = tmp % scanParameters.block_threads;\n      // we put one element per packet in scratch_mem\n      const Index scratch_stride = scanParameters.elements_per_block / PacketSize;\n      const Index scratch_offset = (itemID.get_local_id(0) / scanParameters.block_threads) * scratch_stride;\n      CoeffReturnType private_scan[ScanParameters<Index>::ScanPerThread];\n      CoeffReturnType inclusive_scan;\n      // the actual panel size is scan_size * non_scan_size.\n      // elements_per_panel is roundup to power of 2 for binary tree\n      const Index panel_offset = panel_id * scanParameters.scan_size * scanParameters.non_scan_size;\n      const Index group_offset = group_id * scanParameters.non_scan_stride;\n      // This will be effective when the size is bigger than elements_per_block\n      const Index block_offset = block_id * scanParameters.elements_per_block * scanParameters.scan_stride;\n      const Index thread_offset = (ScanParameters<Index>::ScanPerThread * local_id * scanParameters.scan_stride);\n      const Index global_offset = panel_offset + group_offset + block_offset + thread_offset;\n      Index next_elements = 0;\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < ScanParameters<Index>::ScanPerThread; i++) {\n        Index global_id = global_offset + next_elements;\n        private_scan[i] = ((((block_id * scanParameters.elements_per_block) +\n                             (ScanParameters<Index>::ScanPerThread * local_id) + i) < scanParameters.scan_size) &&\n                           (global_id < scanParameters.total_size))\n                              ? read(dev_eval, global_id)\n                              : accumulator.initialize();\n        next_elements += scanParameters.scan_stride;\n      }\n      first_step_inclusive_Operation([&]() EIGEN_DEVICE_FUNC {\n        if (inclusive) {\n          inclusive_scan = private_scan[ScanParameters<Index>::ScanPerThread - 1];\n        }\n      });\n      // This for loop must be 2\n      EIGEN_UNROLL_LOOP\n      for (int packetIndex = 0; packetIndex < ScanParameters<Index>::ScanPerThread; packetIndex += PacketSize) {\n        Index private_offset = 1;\n        // build sum in place up the tree\n        EIGEN_UNROLL_LOOP\n        for (Index d = PacketSize >> 1; d > 0; d >>= 1) {\n          EIGEN_UNROLL_LOOP\n          for (Index l = 0; l < d; l++) {\n            Index ai = private_offset * (2 * l + 1) - 1 + packetIndex;\n            Index bi = private_offset * (2 * l + 2) - 1 + packetIndex;\n            CoeffReturnType accum = accumulator.initialize();\n            accumulator.reduce(private_scan[ai], &accum);\n            accumulator.reduce(private_scan[bi], &accum);\n            private_scan[bi] = accumulator.finalize(accum);\n          }\n          private_offset *= 2;\n        }\n        scratch_ptr[2 * local_id + (packetIndex / PacketSize) + scratch_offset] =\n            private_scan[PacketSize - 1 + packetIndex];\n        private_scan[PacketSize - 1 + packetIndex] = accumulator.initialize();\n        // traverse down tree & build scan\n        EIGEN_UNROLL_LOOP\n        for (Index d = 1; d < PacketSize; d *= 2) {\n          private_offset >>= 1;\n          EIGEN_UNROLL_LOOP\n          for (Index l = 0; l < d; l++) {\n            Index ai = private_offset * (2 * l + 1) - 1 + packetIndex;\n            Index bi = private_offset * (2 * l + 2) - 1 + packetIndex;\n            CoeffReturnType accum = accumulator.initialize();\n            accumulator.reduce(private_scan[ai], &accum);\n            accumulator.reduce(private_scan[bi], &accum);\n            private_scan[ai] = private_scan[bi];\n            private_scan[bi] = accumulator.finalize(accum);\n          }\n        }\n      }\n\n      Index offset = 1;\n      // build sum in place up the tree\n      for (Index d = scratch_stride >> 1; d > 0; d >>= 1) {\n        // Synchronise\n        itemID.barrier(cl::sycl::access::fence_space::local_space);\n        if (local_id < d) {\n          Index ai = offset * (2 * local_id + 1) - 1 + scratch_offset;\n          Index bi = offset * (2 * local_id + 2) - 1 + scratch_offset;\n          CoeffReturnType accum = accumulator.initialize();\n          accumulator.reduce(scratch_ptr[ai], &accum);\n          accumulator.reduce(scratch_ptr[bi], &accum);\n          scratch_ptr[bi] = accumulator.finalize(accum);\n        }\n        offset *= 2;\n      }\n      // Synchronise\n      itemID.barrier(cl::sycl::access::fence_space::local_space);\n      // next step optimisation\n      if (local_id == 0) {\n        if (((scanParameters.elements_per_group / scanParameters.elements_per_block) > 1)) {\n          const Index temp_id = panel_id * (scanParameters.elements_per_group / scanParameters.elements_per_block) *\n                                    scanParameters.non_scan_size +\n                                group_id * (scanParameters.elements_per_group / scanParameters.elements_per_block) +\n                                block_id;\n          tmp_ptr[temp_id] = scratch_ptr[scratch_stride - 1 + scratch_offset];\n        }\n        // clear the last element\n        scratch_ptr[scratch_stride - 1 + scratch_offset] = accumulator.initialize();\n      }\n      // traverse down tree & build scan\n      for (Index d = 1; d < scratch_stride; d *= 2) {\n        offset >>= 1;\n        // Synchronise\n        itemID.barrier(cl::sycl::access::fence_space::local_space);\n        if (local_id < d) {\n          Index ai = offset * (2 * local_id + 1) - 1 + scratch_offset;\n          Index bi = offset * (2 * local_id + 2) - 1 + scratch_offset;\n          CoeffReturnType accum = accumulator.initialize();\n          accumulator.reduce(scratch_ptr[ai], &accum);\n          accumulator.reduce(scratch_ptr[bi], &accum);\n          scratch_ptr[ai] = scratch_ptr[bi];\n          scratch_ptr[bi] = accumulator.finalize(accum);\n        }\n      }\n      // Synchronise\n      itemID.barrier(cl::sycl::access::fence_space::local_space);\n      // This for loop must be 2\n      EIGEN_UNROLL_LOOP\n      for (int packetIndex = 0; packetIndex < ScanParameters<Index>::ScanPerThread; packetIndex += PacketSize) {\n        EIGEN_UNROLL_LOOP\n        for (Index i = 0; i < PacketSize; i++) {\n          CoeffReturnType accum = private_scan[packetIndex + i];\n          accumulator.reduce(scratch_ptr[2 * local_id + (packetIndex / PacketSize) + scratch_offset], &accum);\n          private_scan[packetIndex + i] = accumulator.finalize(accum);\n        }\n      }\n      first_step_inclusive_Operation([&]() EIGEN_DEVICE_FUNC {\n        if (inclusive) {\n          accumulator.reduce(private_scan[ScanParameters<Index>::ScanPerThread - 1], &inclusive_scan);\n          private_scan[0] = accumulator.finalize(inclusive_scan);\n        }\n      });\n      next_elements = 0;\n      // right the first set of private param\n      EIGEN_UNROLL_LOOP\n      for (Index i = 0; i < ScanParameters<Index>::ScanPerThread; i++) {\n        Index global_id = global_offset + next_elements;\n        if ((((block_id * scanParameters.elements_per_block) + (ScanParameters<Index>::ScanPerThread * local_id) + i) <\n             scanParameters.scan_size) &&\n            (global_id < scanParameters.total_size)) {\n          Index private_id = (i * !inclusive) + (((i + 1) % ScanParameters<Index>::ScanPerThread) * (inclusive));\n          out_ptr[global_id] = private_scan[private_id];\n        }\n        next_elements += scanParameters.scan_stride;\n      }\n    }  // end for loop\n  }\n};\n\ntemplate <typename CoeffReturnType, typename InAccessor, typename OutAccessor, typename Op, typename Index>\nstruct ScanAdjustmentKernelFunctor {\n  typedef cl::sycl::accessor<CoeffReturnType, 1, cl::sycl::access::mode::read_write, cl::sycl::access::target::local>\n      LocalAccessor;\n  static EIGEN_CONSTEXPR int PacketSize = ScanParameters<Index>::ScanPerThread / 2;\n  InAccessor in_accessor;\n  OutAccessor out_accessor;\n  const ScanParameters<Index> scanParameters;\n  Op accumulator;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE ScanAdjustmentKernelFunctor(LocalAccessor, InAccessor in_accessor_,\n                                                                    OutAccessor out_accessor_,\n                                                                    const ScanParameters<Index> scanParameters_,\n                                                                    Op accumulator_)\n      : in_accessor(in_accessor_),\n        out_accessor(out_accessor_),\n        scanParameters(scanParameters_),\n        accumulator(accumulator_) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void operator()(cl::sycl::nd_item<1> itemID) {\n    auto in_ptr = in_accessor.get_pointer();\n    auto out_ptr = out_accessor.get_pointer();\n\n    for (Index loop_offset = 0; loop_offset < scanParameters.loop_range; loop_offset++) {\n      Index data_offset = (itemID.get_global_id(0) + (itemID.get_global_range(0) * loop_offset));\n      Index tmp = data_offset % scanParameters.panel_threads;\n      const Index panel_id = data_offset / scanParameters.panel_threads;\n      const Index group_id = tmp / scanParameters.group_threads;\n      tmp = tmp % scanParameters.group_threads;\n      const Index block_id = tmp / scanParameters.block_threads;\n      const Index local_id = tmp % scanParameters.block_threads;\n\n      // the actual panel size is scan_size * non_scan_size.\n      // elements_per_panel is roundup to power of 2 for binary tree\n      const Index panel_offset = panel_id * scanParameters.scan_size * scanParameters.non_scan_size;\n      const Index group_offset = group_id * scanParameters.non_scan_stride;\n      // This will be effective when the size is bigger than elements_per_block\n      const Index block_offset = block_id * scanParameters.elements_per_block * scanParameters.scan_stride;\n      const Index thread_offset = ScanParameters<Index>::ScanPerThread * local_id * scanParameters.scan_stride;\n\n      const Index global_offset = panel_offset + group_offset + block_offset + thread_offset;\n      const Index block_size = scanParameters.elements_per_group / scanParameters.elements_per_block;\n      const Index in_id = (panel_id * block_size * scanParameters.non_scan_size) + (group_id * block_size) + block_id;\n      CoeffReturnType adjust_val = in_ptr[in_id];\n\n      Index next_elements = 0;\n      EIGEN_UNROLL_LOOP\n      for (Index i = 0; i < ScanParameters<Index>::ScanPerThread; i++) {\n        Index global_id = global_offset + next_elements;\n        if ((((block_id * scanParameters.elements_per_block) + (ScanParameters<Index>::ScanPerThread * local_id) + i) <\n             scanParameters.scan_size) &&\n            (global_id < scanParameters.total_size)) {\n          CoeffReturnType accum = adjust_val;\n          accumulator.reduce(out_ptr[global_id], &accum);\n          out_ptr[global_id] = accumulator.finalize(accum);\n        }\n        next_elements += scanParameters.scan_stride;\n      }\n    }\n  }\n};\n\ntemplate <typename Index>\nstruct ScanInfo {\n  const Index &total_size;\n  const Index &scan_size;\n  const Index &panel_size;\n  const Index &non_scan_size;\n  const Index &scan_stride;\n  const Index &non_scan_stride;\n\n  Index max_elements_per_block;\n  Index block_size;\n  Index panel_threads;\n  Index group_threads;\n  Index block_threads;\n  Index elements_per_group;\n  Index elements_per_block;\n  Index loop_range;\n  Index global_range;\n  Index local_range;\n  const Eigen::SyclDevice &dev;\n  EIGEN_STRONG_INLINE ScanInfo(const Index &total_size_, const Index &scan_size_, const Index &panel_size_,\n                               const Index &non_scan_size_, const Index &scan_stride_, const Index &non_scan_stride_,\n                               const Eigen::SyclDevice &dev_)\n      : total_size(total_size_),\n        scan_size(scan_size_),\n        panel_size(panel_size_),\n        non_scan_size(non_scan_size_),\n        scan_stride(scan_stride_),\n        non_scan_stride(non_scan_stride_),\n        dev(dev_) {\n    // must be power of 2\n    local_range = std::min(Index(dev.getNearestPowerOfTwoWorkGroupSize()),\n                           Index(EIGEN_SYCL_LOCAL_THREAD_DIM0 * EIGEN_SYCL_LOCAL_THREAD_DIM1));\n\n    max_elements_per_block = local_range * ScanParameters<Index>::ScanPerThread;\n\n    elements_per_group =\n        dev.getPowerOfTwo(Index(roundUp(Index(scan_size), ScanParameters<Index>::ScanPerThread)), true);\n    const Index elements_per_panel = elements_per_group * non_scan_size;\n    elements_per_block = std::min(Index(elements_per_group), Index(max_elements_per_block));\n    panel_threads = elements_per_panel / ScanParameters<Index>::ScanPerThread;\n    group_threads = elements_per_group / ScanParameters<Index>::ScanPerThread;\n    block_threads = elements_per_block / ScanParameters<Index>::ScanPerThread;\n    block_size = elements_per_group / elements_per_block;\n#ifdef EIGEN_SYCL_MAX_GLOBAL_RANGE\n    const Index max_threads = std::min(Index(panel_threads * panel_size), Index(EIGEN_SYCL_MAX_GLOBAL_RANGE));\n#else\n    const Index max_threads = panel_threads * panel_size;\n#endif\n    global_range = roundUp(max_threads, local_range);\n    loop_range = Index(\n        std::ceil(double(elements_per_panel * panel_size) / (global_range * ScanParameters<Index>::ScanPerThread)));\n  }\n  inline ScanParameters<Index> get_scan_parameter() {\n    return ScanParameters<Index>(total_size, non_scan_size, scan_size, non_scan_stride, scan_stride, panel_threads,\n                                 group_threads, block_threads, elements_per_group, elements_per_block, loop_range);\n  }\n  inline cl::sycl::nd_range<1> get_thread_range() {\n    return cl::sycl::nd_range<1>(cl::sycl::range<1>(global_range), cl::sycl::range<1>(local_range));\n  }\n};\n\ntemplate <typename EvaluatorPointerType, typename CoeffReturnType, typename Reducer, typename Index>\nstruct SYCLAdjustBlockOffset {\n  EIGEN_STRONG_INLINE static void adjust_scan_block_offset(EvaluatorPointerType in_ptr, EvaluatorPointerType out_ptr,\n                                                           Reducer &accumulator, const Index total_size,\n                                                           const Index scan_size, const Index panel_size,\n                                                           const Index non_scan_size, const Index scan_stride,\n                                                           const Index non_scan_stride, const Eigen::SyclDevice &dev) {\n    auto scan_info =\n        ScanInfo<Index>(total_size, scan_size, panel_size, non_scan_size, scan_stride, non_scan_stride, dev);\n\n    typedef ScanAdjustmentKernelFunctor<CoeffReturnType, EvaluatorPointerType, EvaluatorPointerType, Reducer, Index>\n        AdjustFuctor;\n    dev.template unary_kernel_launcher<CoeffReturnType, AdjustFuctor>(in_ptr, out_ptr, scan_info.get_thread_range(),\n                                                                      scan_info.max_elements_per_block,\n                                                                      scan_info.get_scan_parameter(), accumulator);\n  }\n};\n\ntemplate <typename CoeffReturnType, scan_step stp>\nstruct ScanLauncher_impl {\n  template <typename Input, typename EvaluatorPointerType, typename Reducer, typename Index>\n  EIGEN_STRONG_INLINE static void scan_block(Input in_ptr, EvaluatorPointerType out_ptr, Reducer &accumulator,\n                                             const Index total_size, const Index scan_size, const Index panel_size,\n                                             const Index non_scan_size, const Index scan_stride,\n                                             const Index non_scan_stride, const bool inclusive,\n                                             const Eigen::SyclDevice &dev) {\n    auto scan_info =\n        ScanInfo<Index>(total_size, scan_size, panel_size, non_scan_size, scan_stride, non_scan_stride, dev);\n    const Index temp_pointer_size = scan_info.block_size * non_scan_size * panel_size;\n    const Index scratch_size = scan_info.max_elements_per_block / (ScanParameters<Index>::ScanPerThread / 2);\n    CoeffReturnType *temp_pointer =\n        static_cast<CoeffReturnType *>(dev.allocate_temp(temp_pointer_size * sizeof(CoeffReturnType)));\n    EvaluatorPointerType tmp_global_accessor = dev.get(temp_pointer);\n\n    typedef ScanKernelFunctor<Input, CoeffReturnType, EvaluatorPointerType, Reducer, Index, stp> ScanFunctor;\n    dev.template binary_kernel_launcher<CoeffReturnType, ScanFunctor>(\n        in_ptr, out_ptr, tmp_global_accessor, scan_info.get_thread_range(), scratch_size,\n        scan_info.get_scan_parameter(), accumulator, inclusive);\n\n    if (scan_info.block_size > 1) {\n      ScanLauncher_impl<CoeffReturnType, scan_step::second>::scan_block(\n          tmp_global_accessor, tmp_global_accessor, accumulator, temp_pointer_size, scan_info.block_size, panel_size,\n          non_scan_size, Index(1), scan_info.block_size, false, dev);\n\n      SYCLAdjustBlockOffset<EvaluatorPointerType, CoeffReturnType, Reducer, Index>::adjust_scan_block_offset(\n          tmp_global_accessor, out_ptr, accumulator, total_size, scan_size, panel_size, non_scan_size, scan_stride,\n          non_scan_stride, dev);\n    }\n    dev.deallocate_temp(temp_pointer);\n  }\n};\n\n}  // namespace internal\n}  // namespace TensorSycl\nnamespace internal {\ntemplate <typename Self, typename Reducer, bool vectorize>\nstruct ScanLauncher<Self, Reducer, Eigen::SyclDevice, vectorize> {\n  typedef typename Self::Index Index;\n  typedef typename Self::CoeffReturnType CoeffReturnType;\n  typedef typename Self::Storage Storage;\n  typedef typename Self::EvaluatorPointerType EvaluatorPointerType;\n  void operator()(Self &self, EvaluatorPointerType data) {\n    const Index total_size = internal::array_prod(self.dimensions());\n    const Index scan_size = self.size();\n    const Index scan_stride = self.stride();\n    // this is the scan op (can be sum or ...)\n    auto accumulator = self.accumulator();\n    auto inclusive = !self.exclusive();\n    auto consume_dim = self.consume_dim();\n    auto dev = self.device();\n\n    auto dims = self.inner().dimensions();\n\n    Index non_scan_size = 1;\n    Index panel_size = 1;\n    if (static_cast<int>(Self::Layout) == static_cast<int>(ColMajor)) {\n      for (int i = 0; i < consume_dim; i++) {\n        non_scan_size *= dims[i];\n      }\n      for (int i = consume_dim + 1; i < Self::NumDims; i++) {\n        panel_size *= dims[i];\n      }\n    } else {\n      for (int i = Self::NumDims - 1; i > consume_dim; i--) {\n        non_scan_size *= dims[i];\n      }\n      for (int i = consume_dim - 1; i >= 0; i--) {\n        panel_size *= dims[i];\n      }\n    }\n    const Index non_scan_stride = (scan_stride > 1) ? 1 : scan_size;\n    auto eval_impl = self.inner();\n    TensorSycl::internal::ScanLauncher_impl<CoeffReturnType, TensorSycl::internal::scan_step::first>::scan_block(\n        eval_impl, data, accumulator, total_size, scan_size, panel_size, non_scan_size, scan_stride, non_scan_stride,\n        inclusive, dev);\n  }\n};\n} // namespace internal\n}  // namespace Eigen\n\n#endif  // UNSUPPORTED_EIGEN_CXX11_SRC_TENSOR_TENSOR_SYCL_SYCL_HPP\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorShuffling.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_SHUFFLING_H\n#define EIGEN_CXX11_TENSOR_TENSOR_SHUFFLING_H\n\nnamespace Eigen {\n\n/** \\class TensorShuffling\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor shuffling class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename Shuffle, typename XprType>\nstruct traits<TensorShufflingOp<Shuffle, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename Shuffle, typename XprType>\nstruct eval<TensorShufflingOp<Shuffle, XprType>, Eigen::Dense>\n{\n  typedef const TensorShufflingOp<Shuffle, XprType>& type;\n};\n\ntemplate<typename Shuffle, typename XprType>\nstruct nested<TensorShufflingOp<Shuffle, XprType>, 1, typename eval<TensorShufflingOp<Shuffle, XprType> >::type>\n{\n  typedef TensorShufflingOp<Shuffle, XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename Shuffle, typename XprType>\nclass TensorShufflingOp : public TensorBase<TensorShufflingOp<Shuffle, XprType> >\n{\n  public:\n    typedef TensorBase<TensorShufflingOp<Shuffle, XprType> > Base;\n    typedef typename Eigen::internal::traits<TensorShufflingOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef typename XprType::CoeffReturnType CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorShufflingOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorShufflingOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorShufflingOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorShufflingOp(const XprType& expr, const Shuffle& shfl)\n      : m_xpr(expr), m_shuffle(shfl) {}\n\n    EIGEN_DEVICE_FUNC\n    const Shuffle& shufflePermutation() const { return m_shuffle; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(TensorShufflingOp)\n\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const Shuffle m_shuffle;\n};\n\n\n// Eval as rvalue\ntemplate<typename Shuffle, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorShufflingOp<Shuffle, ArgType>, Device>\n{\n  typedef TensorEvaluator<const TensorShufflingOp<Shuffle, ArgType>, Device> Self;\n  typedef TensorShufflingOp<Shuffle, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned         = false,\n    PacketAccess      = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess       = TensorEvaluator<ArgType, Device>::RawAccess,\n    PreferBlockAccess = true,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess       = false,  // to be implemented\n    RawAccess         = false\n  };\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n\n  typedef typename internal::TensorMaterializedBlock<ScalarNoConst, NumDims,\n                                                     Layout, Index>\n      TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op,\n                                                        const Device& device)\n      : m_device(device),\n        m_impl(op.expression(), device)\n  {\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n    const Shuffle& shuffle = op.shufflePermutation();\n    m_is_identity = true;\n    for (int i = 0; i < NumDims; ++i) {\n      m_shuffle[i] = static_cast<int>(shuffle[i]);\n      m_dimensions[i] = input_dims[shuffle[i]];\n      m_inverseShuffle[shuffle[i]] = i;\n      if (m_is_identity && shuffle[i] != i) {\n        m_is_identity = false;\n      }\n    }\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_unshuffledInputStrides[0] = 1;\n      m_outputStrides[0] = 1;\n\n      for (int i = 1; i < NumDims; ++i) {\n        m_unshuffledInputStrides[i] =\n            m_unshuffledInputStrides[i - 1] * input_dims[i - 1];\n        m_outputStrides[i] = m_outputStrides[i - 1] * m_dimensions[i - 1];\n        m_fastOutputStrides[i] = internal::TensorIntDivisor<Index>(m_outputStrides[i]);\n      }\n    } else {\n      m_unshuffledInputStrides[NumDims - 1] = 1;\n      m_outputStrides[NumDims - 1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_unshuffledInputStrides[i] =\n            m_unshuffledInputStrides[i + 1] * input_dims[i + 1];\n        m_outputStrides[i] = m_outputStrides[i + 1] * m_dimensions[i + 1];\n        m_fastOutputStrides[i] = internal::TensorIntDivisor<Index>(m_outputStrides[i]);\n      }\n    }\n\n    for (int i = 0; i < NumDims; ++i) {\n      m_inputStrides[i] = m_unshuffledInputStrides[shuffle[i]];\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType /*data*/) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n#ifdef EIGEN_USE_THREADS\n  template <typename EvalSubExprsCallback>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void evalSubExprsIfNeededAsync(\n      EvaluatorPointerType, EvalSubExprsCallback done) {\n    m_impl.evalSubExprsIfNeededAsync(nullptr, [done](bool) { done(true); });\n  }\n#endif  // EIGEN_USE_THREADS\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    if (m_is_identity) {\n      return m_impl.coeff(index);\n    } else {\n      return m_impl.coeff(srcCoeff(index));\n    }\n  }\n\n  template <int LoadMode, typename Self, bool ImplPacketAccess>\n  struct PacketLoader {\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    static PacketReturnType Run(const Self& self, Index index) {\n      EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < PacketSize; ++i) {\n        values[i] = self.coeff(index + i);\n      }\n      PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n      return rslt;\n    }\n  };\n\n  template<int LoadMode, typename Self>\n  struct PacketLoader<LoadMode, Self, true> {\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    static PacketReturnType Run(const Self& self, Index index) {\n      if (self.m_is_identity) {\n        return self.m_impl.template packet<LoadMode>(index);\n      } else {\n        EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n        EIGEN_UNROLL_LOOP\n        for (int i = 0; i < PacketSize; ++i) {\n          values[i] = self.coeff(index + i);\n        }\n        PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n        return rslt;\n      }\n    }\n  };\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n        eigen_assert(index + PacketSize - 1 < dimensions().TotalSize());\n    return PacketLoader<LoadMode, Self, TensorEvaluator<ArgType, Device>::PacketAccess>::Run(*this, index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  internal::TensorBlockResourceRequirements getResourceRequirements() const {\n    static const int inner_dim =\n        Layout == static_cast<int>(ColMajor) ? 0 : NumDims - 1;\n\n    const size_t target_size = m_device.firstLevelCacheSize();\n    const bool inner_dim_shuffled = m_shuffle[inner_dim] != inner_dim;\n\n    // Shuffled inner dimensions leads to a random memory access, which is not\n    // captured by default cost model bytes loaded/stored. We add this cost\n    // explicitly. The number of cycles picked based on the benchmarks.\n    // TODO(ezhulenev): This number was picked based on a very questionable\n    // benchmarks, add benchmarks that are representative of real workloads.\n    using BlockRequirements = internal::TensorBlockResourceRequirements;\n    if (inner_dim_shuffled) {\n      return BlockRequirements::uniform<Scalar>(target_size)\n          .addCostPerCoeff({0, 0, NumDims * 28});\n    } else {\n      return BlockRequirements::skewed<Scalar>(target_size);\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorBlock\n  block(TensorBlockDesc& desc, TensorBlockScratch& scratch,\n          bool root_of_expr_ast = false) const {\n    assert(m_impl.data() != NULL);\n\n    typedef internal::TensorBlockIO<ScalarNoConst, Index, NumDims, Layout>\n        TensorBlockIO;\n    typedef typename TensorBlockIO::Dst TensorBlockIODst;\n    typedef typename TensorBlockIO::Src TensorBlockIOSrc;\n\n    const typename TensorBlock::Storage block_storage =\n        TensorBlock::prepareStorage(\n            desc, scratch, /*allow_strided_storage=*/root_of_expr_ast);\n\n    typename TensorBlockIO::Dimensions input_strides(m_unshuffledInputStrides);\n    TensorBlockIOSrc src(input_strides, m_impl.data(), srcCoeff(desc.offset()));\n\n    TensorBlockIODst dst(block_storage.dimensions(), block_storage.strides(),\n                         block_storage.data());\n\n    typename TensorBlockIO::DimensionsMap dst_to_src_dim_map(m_shuffle);\n    TensorBlockIO::Copy(dst, src, dst_to_src_dim_map);\n\n    return block_storage.AsTensorMaterializedBlock();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    const double compute_cost = m_is_identity ? TensorOpCost::AddCost<Index>() :\n                                NumDims * (2 * TensorOpCost::AddCost<Index>() +\n                                           2 * TensorOpCost::MulCost<Index>() +\n                                           TensorOpCost::DivCost<Index>());\n    return m_impl.costPerCoeff(vectorized) +\n           TensorOpCost(0, 0, compute_cost, m_is_identity /* vectorized */, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC typename Storage::Type data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n   // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n protected:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index GetBlockOutputIndex(\n      Index input_index,\n      const DSizes<Index, NumDims>& input_block_strides,\n      const DSizes<Index, NumDims>& output_block_strides,\n      const DSizes<internal::TensorIntDivisor<Index>, NumDims>& fast_input_block_strides) const {\n    Index output_index = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx = input_index / fast_input_block_strides[i];\n        output_index += idx * output_block_strides[m_inverseShuffle[i]];\n        input_index -= idx * input_block_strides[i];\n      }\n      return output_index + input_index *\n          output_block_strides[m_inverseShuffle[0]];\n    } else {\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx = input_index / fast_input_block_strides[i];\n        output_index += idx * output_block_strides[m_inverseShuffle[i]];\n        input_index -= idx * input_block_strides[i];\n      }\n      return output_index + input_index *\n          output_block_strides[m_inverseShuffle[NumDims - 1]];\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index srcCoeff(Index index) const {\n    Index inputIndex = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx = index / m_fastOutputStrides[i];\n        inputIndex += idx * m_inputStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      return inputIndex + index * m_inputStrides[0];\n    } else {\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx = index / m_fastOutputStrides[i];\n        inputIndex += idx * m_inputStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      return inputIndex + index * m_inputStrides[NumDims - 1];\n    }\n  }\n\n  Dimensions m_dimensions;\n  bool m_is_identity;\n  array<int, NumDims> m_shuffle;\n  array<Index, NumDims> m_inverseShuffle;  // TODO(ezhulenev): Make it int type.\n  array<Index, NumDims> m_outputStrides;\n  array<internal::TensorIntDivisor<Index>, NumDims> m_fastOutputStrides;\n  array<Index, NumDims> m_inputStrides;\n  array<Index, NumDims> m_unshuffledInputStrides;\n\n  const Device EIGEN_DEVICE_REF m_device;\n  TensorEvaluator<ArgType, Device> m_impl;\n};\n\n\n// Eval as lvalue\ntemplate<typename Shuffle, typename ArgType, typename Device>\nstruct TensorEvaluator<TensorShufflingOp<Shuffle, ArgType>, Device>\n    : public TensorEvaluator<const TensorShufflingOp<Shuffle, ArgType>, Device>\n{\n  typedef TensorEvaluator<const TensorShufflingOp<Shuffle, ArgType>, Device> Base;\n\n  typedef TensorShufflingOp<Shuffle, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n\n  enum {\n    IsAligned         = false,\n    PacketAccess      = (PacketType<CoeffReturnType, Device>::size > 1),\n    BlockAccess       = TensorEvaluator<ArgType, Device>::RawAccess,\n    PreferBlockAccess = true,\n    Layout            = TensorEvaluator<ArgType, Device>::Layout,\n    RawAccess         = false\n  };\n\n  typedef typename internal::remove_const<Scalar>::type ScalarNoConst;\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockDescriptor<NumDims, Index> TensorBlockDesc;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : Base(op, device)\n  { }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType& coeffRef(Index index)\n  {\n    return this->m_impl.coeffRef(this->srcCoeff(index));\n  }\n\n  template <int StoreMode> EIGEN_STRONG_INLINE\n  void writePacket(Index index, const PacketReturnType& x)\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n    internal::pstore<CoeffReturnType, PacketReturnType>(values, x);\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < PacketSize; ++i) {\n      this->coeffRef(index+i) = values[i];\n    }\n  }\n\n  template <typename TensorBlock>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void writeBlock(\n      const TensorBlockDesc& desc, const TensorBlock& block) {\n    eigen_assert(this->m_impl.data() != NULL);\n\n    typedef internal::TensorBlockIO<ScalarNoConst, Index, NumDims, Layout>\n        TensorBlockIO;\n    typedef typename TensorBlockIO::Dst TensorBlockIODst;\n    typedef typename TensorBlockIO::Src TensorBlockIOSrc;\n\n    const Scalar* block_buffer = block.data();\n\n    // TODO(ezhulenev): TensorBlockIO should be able to read from any Eigen\n    // expression with coefficient and packet access as `src`.\n    void* mem = NULL;\n    if (block_buffer == NULL) {\n      mem = this->m_device.allocate(desc.size() * sizeof(Scalar));\n      ScalarNoConst* buf = static_cast<ScalarNoConst*>(mem);\n\n      typedef internal::TensorBlockAssignment<\n          ScalarNoConst, NumDims, typename TensorBlock::XprType, Index>\n          TensorBlockAssignment;\n\n      TensorBlockAssignment::Run(\n          TensorBlockAssignment::target(\n              desc.dimensions(), internal::strides<Layout>(desc.dimensions()),\n              buf),\n          block.expr());\n\n      block_buffer = buf;\n    }\n\n    // Read from block.\n    TensorBlockIOSrc src(internal::strides<Layout>(desc.dimensions()),\n                         block_buffer);\n\n    // Write to the output buffer.\n    typename TensorBlockIO::Dimensions output_strides(\n        this->m_unshuffledInputStrides);\n    typename TensorBlockIO::Dimensions output_dimensions;\n    for (int i = 0; i < NumDims; ++i) {\n      output_dimensions[this->m_shuffle[i]] = desc.dimension(i);\n    }\n    TensorBlockIODst dst(output_dimensions, output_strides, this->m_impl.data(),\n                         this->srcCoeff(desc.offset()));\n\n    // Reorder dimensions according to the shuffle.\n    typename TensorBlockIO::DimensionsMap dst_to_src_dim_map;\n    for (int i = 0; i < NumDims; ++i) {\n      dst_to_src_dim_map[i] = static_cast<int>(this->m_inverseShuffle[i]);\n    }\n    TensorBlockIO::Copy(dst, src, dst_to_src_dim_map);\n\n    // Deallocate temporary buffer used for the block materialization.\n    if (mem != NULL) this->m_device.deallocate(mem);\n  }\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_SHUFFLING_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorStorage.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n// Copyright (C) 2014-2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSORSTORAGE_H\n#define EIGEN_CXX11_TENSOR_TENSORSTORAGE_H\n\n#ifdef EIGEN_TENSOR_STORAGE_CTOR_PLUGIN\n  #define EIGEN_INTERNAL_TENSOR_STORAGE_CTOR_PLUGIN EIGEN_TENSOR_STORAGE_CTOR_PLUGIN;\n#else\n  #define EIGEN_INTERNAL_TENSOR_STORAGE_CTOR_PLUGIN\n#endif\n\nnamespace Eigen {\n\n/** \\internal\n  *\n  * \\class TensorStorage\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Stores the data of a tensor\n  *\n  * This class stores the data of fixed-size, dynamic-size or mixed tensors\n  * in a way as compact as possible.\n  *\n  * \\sa Tensor\n  */\ntemplate<typename T, typename Dimensions, int Options> class TensorStorage;\n\n\n// Pure fixed-size storage\ntemplate<typename T, typename FixedDimensions, int Options_>\nclass TensorStorage\n{\n private:\n  static const std::size_t Size = FixedDimensions::total_size;\n\n  // Allocate an array of size at least one to prevent compiler warnings.\n  static const std::size_t MinSize = max_n_1<Size>::size;\n  EIGEN_ALIGN_MAX T m_data[MinSize];\n\n public:\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE TensorStorage() {\n  }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE T *data() { return m_data; }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE const T *data() const { return m_data; }\n\n  static EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE const FixedDimensions& dimensions()\n  {\n    static const FixedDimensions* singleton_dimensions = new FixedDimensions();\n    return *singleton_dimensions;\n  }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE DenseIndex size() const { return Size; }\n};\n\n// pure dynamic\ntemplate<typename T, typename IndexType, int NumIndices_, int Options_>\nclass TensorStorage<T, DSizes<IndexType, NumIndices_>, Options_>\n{\n  public:\n    typedef IndexType Index;\n    typedef DSizes<IndexType, NumIndices_> Dimensions;\n    typedef TensorStorage<T, DSizes<IndexType, NumIndices_>, Options_> Self;\n\n    EIGEN_DEVICE_FUNC TensorStorage() : m_data(0), m_dimensions() {\n      if (NumIndices_ == 0) {\n\tm_data = internal::conditional_aligned_new_auto<T,(Options_&DontAlign)==0>(1);\n      }\n    }\n    EIGEN_DEVICE_FUNC TensorStorage(internal::constructor_without_unaligned_array_assert)\n      : m_data(0), m_dimensions(internal::template repeat<NumIndices_, Index>(0)) {}\n    EIGEN_DEVICE_FUNC TensorStorage(Index size, const array<Index, NumIndices_>& dimensions)\n        : m_data(internal::conditional_aligned_new_auto<T,(Options_&DontAlign)==0>(size)), m_dimensions(dimensions)\n      { EIGEN_INTERNAL_TENSOR_STORAGE_CTOR_PLUGIN }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    template <typename... DenseIndex>\n    EIGEN_DEVICE_FUNC TensorStorage(DenseIndex... indices) : m_dimensions(indices...) {\n      m_data = internal::conditional_aligned_new_auto<T,(Options_&DontAlign)==0>(internal::array_prod(m_dimensions));\n    }\n#endif\n\n    EIGEN_DEVICE_FUNC TensorStorage(const Self& other)\n      : m_data(internal::conditional_aligned_new_auto<T,(Options_&DontAlign)==0>(internal::array_prod(other.m_dimensions)))\n      , m_dimensions(other.m_dimensions)\n    {\n      internal::smart_copy(other.m_data, other.m_data+internal::array_prod(other.m_dimensions), m_data);\n    }\n    EIGEN_DEVICE_FUNC Self& operator=(const Self& other)\n    {\n      if (this != &other) {\n        Self tmp(other);\n        this->swap(tmp);\n      }\n      return *this;\n    }\n\n#if EIGEN_HAS_RVALUE_REFERENCES\n    EIGEN_DEVICE_FUNC TensorStorage(Self&& other) : TensorStorage()\n    {\n      *this = std::move(other);\n    }\n    \n    EIGEN_DEVICE_FUNC Self& operator=(Self&& other)\n    {\n      numext::swap(m_data, other.m_data);\n      numext::swap(m_dimensions, other.m_dimensions);\n      return *this;\n    }\n#endif\n\n    EIGEN_DEVICE_FUNC  ~TensorStorage() { internal::conditional_aligned_delete_auto<T,(Options_&DontAlign)==0>(m_data, internal::array_prod(m_dimensions)); }\n    EIGEN_DEVICE_FUNC  void swap(Self& other)\n    { numext::swap(m_data,other.m_data); numext::swap(m_dimensions,other.m_dimensions); }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const {return m_dimensions;}\n\n    EIGEN_DEVICE_FUNC void resize(Index size, const array<Index, NumIndices_>& nbDimensions)\n    {\n      const Index currentSz = internal::array_prod(m_dimensions);\n      if(size != currentSz)\n      {\n        internal::conditional_aligned_delete_auto<T,(Options_&DontAlign)==0>(m_data, currentSz);\n        if (size)\n          m_data = internal::conditional_aligned_new_auto<T,(Options_&DontAlign)==0>(size);\n        else if (NumIndices_ == 0) {\n\t  m_data = internal::conditional_aligned_new_auto<T,(Options_&DontAlign)==0>(1);\n\t}\n\telse \n          m_data = 0;\n        EIGEN_INTERNAL_DENSE_STORAGE_CTOR_PLUGIN({})\n      }\n      m_dimensions = nbDimensions;\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T *data() { return m_data; }\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const T *data() const { return m_data; }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index size() const { return m_dimensions.TotalSize(); }\n\n private:\n  T *m_data;\n  Dimensions m_dimensions;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSORSTORAGE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorStriding.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_STRIDING_H\n#define EIGEN_CXX11_TENSOR_TENSOR_STRIDING_H\n\nnamespace Eigen {\n\n/** \\class TensorStriding\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor striding class.\n  *\n  *\n  */\nnamespace internal {\ntemplate<typename Strides, typename XprType>\nstruct traits<TensorStridingOp<Strides, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n};\n\ntemplate<typename Strides, typename XprType>\nstruct eval<TensorStridingOp<Strides, XprType>, Eigen::Dense>\n{\n  typedef const TensorStridingOp<Strides, XprType>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename Strides, typename XprType>\nstruct nested<TensorStridingOp<Strides, XprType>, 1, typename eval<TensorStridingOp<Strides, XprType> >::type>\n{\n  typedef TensorStridingOp<Strides, XprType> type;\n};\n\n}  // end namespace internal\n\n\n\ntemplate<typename Strides, typename XprType>\nclass TensorStridingOp : public TensorBase<TensorStridingOp<Strides, XprType> >\n{\n  public:\n    typedef TensorBase<TensorStridingOp<Strides, XprType> > Base;\n    typedef typename Eigen::internal::traits<TensorStridingOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef typename XprType::CoeffReturnType CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorStridingOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorStridingOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorStridingOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorStridingOp(const XprType& expr, const Strides& dims)\n      : m_xpr(expr), m_dims(dims) {}\n\n    EIGEN_DEVICE_FUNC\n    const Strides& strides() const { return m_dims; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n    EIGEN_TENSOR_INHERIT_ASSIGNMENT_OPERATORS(TensorStridingOp)\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const Strides m_dims;\n};\n\n\n// Eval as rvalue\ntemplate<typename Strides, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorStridingOp<Strides, ArgType>, Device>\n{\n  typedef TensorStridingOp<Strides, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = /*TensorEvaluator<ArgType, Device>::IsAligned*/false,\n    PacketAccess = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess = false,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : m_impl(op.expression(), device)\n  {\n    m_dimensions = m_impl.dimensions();\n    for (int i = 0; i < NumDims; ++i) {\n      m_dimensions[i] =Eigen::numext::ceil(static_cast<float>(m_dimensions[i]) / op.strides()[i]);\n    }\n\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_outputStrides[0] = 1;\n      m_inputStrides[0] = 1;\n      for (int i = 1; i < NumDims; ++i) {\n        m_outputStrides[i] = m_outputStrides[i-1] * m_dimensions[i-1];\n        m_inputStrides[i] = m_inputStrides[i-1] * input_dims[i-1];\n        m_inputStrides[i-1] *= op.strides()[i-1];\n      }\n      m_inputStrides[NumDims-1] *= op.strides()[NumDims-1];\n    } else {  // RowMajor\n      m_outputStrides[NumDims-1] = 1;\n      m_inputStrides[NumDims-1] = 1;\n      for (int i = NumDims - 2; i >= 0; --i) {\n        m_outputStrides[i] = m_outputStrides[i+1] * m_dimensions[i+1];\n        m_inputStrides[i] = m_inputStrides[i+1] * input_dims[i+1];\n        m_inputStrides[i+1] *= op.strides()[i+1];\n      }\n      m_inputStrides[0] *= op.strides()[0];\n    }\n  }\n\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType/*data*/) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    return m_impl.coeff(srcCoeff(index));\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    Index inputIndices[] = {0, 0};\n    Index indices[] = {index, index + PacketSize - 1};\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx0 = indices[0] / m_outputStrides[i];\n        const Index idx1 = indices[1] / m_outputStrides[i];\n        inputIndices[0] += idx0 * m_inputStrides[i];\n        inputIndices[1] += idx1 * m_inputStrides[i];\n        indices[0] -= idx0 * m_outputStrides[i];\n        indices[1] -= idx1 * m_outputStrides[i];\n      }\n      inputIndices[0] += indices[0] * m_inputStrides[0];\n      inputIndices[1] += indices[1] * m_inputStrides[0];\n    } else {  // RowMajor\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx0 = indices[0] / m_outputStrides[i];\n        const Index idx1 = indices[1] / m_outputStrides[i];\n        inputIndices[0] += idx0 * m_inputStrides[i];\n        inputIndices[1] += idx1 * m_inputStrides[i];\n        indices[0] -= idx0 * m_outputStrides[i];\n        indices[1] -= idx1 * m_outputStrides[i];\n      }\n      inputIndices[0] += indices[0] * m_inputStrides[NumDims-1];\n      inputIndices[1] += indices[1] * m_inputStrides[NumDims-1];\n    }\n    if (inputIndices[1] - inputIndices[0] == PacketSize - 1) {\n      PacketReturnType rslt = m_impl.template packet<Unaligned>(inputIndices[0]);\n      return rslt;\n    }\n    else {\n      EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n      values[0] = m_impl.coeff(inputIndices[0]);\n      values[PacketSize-1] = m_impl.coeff(inputIndices[1]);\n      EIGEN_UNROLL_LOOP\n      for (int i = 1; i < PacketSize-1; ++i) {\n        values[i] = coeff(index+i);\n      }\n      PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n      return rslt;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost costPerCoeff(bool vectorized) const {\n    double compute_cost = (NumDims - 1) * (TensorOpCost::AddCost<Index>() +\n                                           TensorOpCost::MulCost<Index>() +\n                                           TensorOpCost::DivCost<Index>()) +\n        TensorOpCost::MulCost<Index>();\n    if (vectorized) {\n      compute_cost *= 2;  // packet() computes two indices\n    }\n    const int innerDim = (static_cast<int>(Layout) == static_cast<int>(ColMajor)) ? 0 : (NumDims - 1);\n    return m_impl.costPerCoeff(vectorized && m_inputStrides[innerDim] == 1) +\n        // Computation is not vectorized per se, but it is done once per packet.\n        TensorOpCost(0, 0, compute_cost, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC typename Storage::Type data() const { return NULL; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n protected:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index srcCoeff(Index index) const\n  {\n    Index inputIndex = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx = index / m_outputStrides[i];\n        inputIndex += idx * m_inputStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      inputIndex += index * m_inputStrides[0];\n    } else {  // RowMajor\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx = index / m_outputStrides[i];\n        inputIndex += idx * m_inputStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      inputIndex += index * m_inputStrides[NumDims-1];\n    }\n    return inputIndex;\n  }\n\n  Dimensions m_dimensions;\n  array<Index, NumDims> m_outputStrides;\n  array<Index, NumDims> m_inputStrides;\n  TensorEvaluator<ArgType, Device> m_impl;\n};\n\n// Eval as lvalue\ntemplate<typename Strides, typename ArgType, typename Device>\nstruct TensorEvaluator<TensorStridingOp<Strides, ArgType>, Device>\n    : public TensorEvaluator<const TensorStridingOp<Strides, ArgType>, Device>\n{\n  typedef TensorStridingOp<Strides, ArgType> XprType;\n  typedef TensorEvaluator<const XprType, Device> Base;\n  //  typedef typename XprType::Index Index;\n  static const int NumDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  //  typedef DSizes<Index, NumDims> Dimensions;\n\n  enum {\n    IsAligned = /*TensorEvaluator<ArgType, Device>::IsAligned*/false,\n    PacketAccess = TensorEvaluator<ArgType, Device>::PacketAccess,\n    PreferBlockAccess = false,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,  // to be implemented\n    RawAccess = false\n  };\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n      : Base(op, device) { }\n\n  typedef typename XprType::Index Index;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Scalar& coeffRef(Index index)\n  {\n    return this->m_impl.coeffRef(this->srcCoeff(index));\n  }\n\n  template <int StoreMode> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void writePacket(Index index, const PacketReturnType& x)\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < this->dimensions().TotalSize());\n\n    Index inputIndices[] = {0, 0};\n    Index indices[] = {index, index + PacketSize - 1};\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      EIGEN_UNROLL_LOOP\n      for (int i = NumDims - 1; i > 0; --i) {\n        const Index idx0 = indices[0] / this->m_outputStrides[i];\n        const Index idx1 = indices[1] / this->m_outputStrides[i];\n        inputIndices[0] += idx0 * this->m_inputStrides[i];\n        inputIndices[1] += idx1 * this->m_inputStrides[i];\n        indices[0] -= idx0 * this->m_outputStrides[i];\n        indices[1] -= idx1 * this->m_outputStrides[i];\n      }\n      inputIndices[0] += indices[0] * this->m_inputStrides[0];\n      inputIndices[1] += indices[1] * this->m_inputStrides[0];\n    } else {  // RowMajor\n      EIGEN_UNROLL_LOOP\n      for (int i = 0; i < NumDims - 1; ++i) {\n        const Index idx0 = indices[0] / this->m_outputStrides[i];\n        const Index idx1 = indices[1] / this->m_outputStrides[i];\n        inputIndices[0] += idx0 * this->m_inputStrides[i];\n        inputIndices[1] += idx1 * this->m_inputStrides[i];\n        indices[0] -= idx0 * this->m_outputStrides[i];\n        indices[1] -= idx1 * this->m_outputStrides[i];\n      }\n      inputIndices[0] += indices[0] * this->m_inputStrides[NumDims-1];\n      inputIndices[1] += indices[1] * this->m_inputStrides[NumDims-1];\n    }\n    if (inputIndices[1] - inputIndices[0] == PacketSize - 1) {\n      this->m_impl.template writePacket<Unaligned>(inputIndices[0], x);\n    }\n    else {\n      EIGEN_ALIGN_MAX Scalar values[PacketSize];\n      internal::pstore<Scalar, PacketReturnType>(values, x);\n      this->m_impl.coeffRef(inputIndices[0]) = values[0];\n      this->m_impl.coeffRef(inputIndices[1]) = values[PacketSize-1];\n      EIGEN_UNROLL_LOOP\n      for (int i = 1; i < PacketSize-1; ++i) {\n        this->coeffRef(index+i) = values[i];\n      }\n    }\n  }\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_STRIDING_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorTrace.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2017 Gagan Goel <gagan.nith@gmail.com>\n// Copyright (C) 2017 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_TRACE_H\n#define EIGEN_CXX11_TENSOR_TENSOR_TRACE_H\n\nnamespace Eigen {\n\n/** \\class TensorTrace\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Tensor Trace class.\n  *\n  *\n  */\n\nnamespace internal {\ntemplate<typename Dims, typename XprType>\nstruct traits<TensorTraceOp<Dims, XprType> > : public traits<XprType>\n{\n  typedef typename XprType::Scalar Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions - array_size<Dims>::value;\n  static const int Layout = XprTraits::Layout;\n};\n\ntemplate<typename Dims, typename XprType>\nstruct eval<TensorTraceOp<Dims, XprType>, Eigen::Dense>\n{\n  typedef const TensorTraceOp<Dims, XprType>& type;\n};\n\ntemplate<typename Dims, typename XprType>\nstruct nested<TensorTraceOp<Dims, XprType>, 1, typename eval<TensorTraceOp<Dims, XprType> >::type>\n{\n  typedef TensorTraceOp<Dims, XprType> type;\n};\n\n} // end namespace internal\n\n\ntemplate<typename Dims, typename XprType>\nclass TensorTraceOp : public TensorBase<TensorTraceOp<Dims, XprType> >\n{\n  public:\n    typedef typename Eigen::internal::traits<TensorTraceOp>::Scalar Scalar;\n    typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n    typedef typename XprType::CoeffReturnType CoeffReturnType;\n    typedef typename Eigen::internal::nested<TensorTraceOp>::type Nested;\n    typedef typename Eigen::internal::traits<TensorTraceOp>::StorageKind StorageKind;\n    typedef typename Eigen::internal::traits<TensorTraceOp>::Index Index;\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorTraceOp(const XprType& expr, const Dims& dims)\n      : m_xpr(expr), m_dims(dims) {\n    }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const Dims& dims() const { return m_dims; }\n\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n    const typename internal::remove_all<typename XprType::Nested>::type& expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const Dims m_dims;\n};\n\n\n// Eval as rvalue\ntemplate<typename Dims, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorTraceOp<Dims, ArgType>, Device>\n{\n  typedef TensorTraceOp<Dims, ArgType> XprType;\n  static const int NumInputDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  static const int NumReducedDims = internal::array_size<Dims>::value;\n  static const int NumOutputDims = NumInputDims - NumReducedDims;\n  typedef typename XprType::Index Index;\n  typedef DSizes<Index, NumOutputDims> Dimensions;\n  typedef typename XprType::Scalar Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = internal::unpacket_traits<PacketReturnType>::size;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess = false,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device)\n    : m_impl(op.expression(), device), m_traceDim(1), m_device(device)\n  {\n\n    EIGEN_STATIC_ASSERT((NumOutputDims >= 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    EIGEN_STATIC_ASSERT((NumReducedDims >= 2) || ((NumReducedDims == 0) && (NumInputDims == 0)), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    for (int i = 0; i < NumInputDims; ++i) {\n      m_reduced[i] = false;\n    }\n\n    const Dims& op_dims = op.dims();\n    for (int i = 0; i < NumReducedDims; ++i) {\n      eigen_assert(op_dims[i] >= 0);\n      eigen_assert(op_dims[i] < NumInputDims);\n      m_reduced[op_dims[i]] = true;\n    }\n\n    // All the dimensions should be distinct to compute the trace\n    int num_distinct_reduce_dims = 0;\n    for (int i = 0; i < NumInputDims; ++i) {\n      if (m_reduced[i]) {\n        ++num_distinct_reduce_dims;\n      }\n    }\n\n    eigen_assert(num_distinct_reduce_dims == NumReducedDims);\n\n    // Compute the dimensions of the result.\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n\n    int output_index = 0;\n    int reduced_index = 0;\n    for (int i = 0; i < NumInputDims; ++i) {\n      if (m_reduced[i]) {\n        m_reducedDims[reduced_index] = input_dims[i];\n        if (reduced_index > 0) {\n          // All the trace dimensions must have the same size\n          eigen_assert(m_reducedDims[0] == m_reducedDims[reduced_index]);\n        }\n        ++reduced_index;\n      }\n      else {\n        m_dimensions[output_index] = input_dims[i];\n        ++output_index;\n      }\n    }\n\n    if (NumReducedDims != 0) {\n      m_traceDim = m_reducedDims[0];\n    }\n\n    // Compute the output strides\n    if (NumOutputDims > 0) {\n      if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n        m_outputStrides[0] = 1;\n        for (int i = 1; i < NumOutputDims; ++i) {\n          m_outputStrides[i] = m_outputStrides[i - 1] * m_dimensions[i - 1];\n        }\n      }\n      else {\n        m_outputStrides.back() = 1;\n        for (int i = NumOutputDims - 2; i >= 0; --i) {\n          m_outputStrides[i] = m_outputStrides[i + 1] * m_dimensions[i + 1];\n        }\n      }\n    }\n\n    // Compute the input strides\n    if (NumInputDims > 0) {\n      array<Index, NumInputDims> input_strides;\n      if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n        input_strides[0] = 1;\n        for (int i = 1; i < NumInputDims; ++i) {\n          input_strides[i] = input_strides[i - 1] * input_dims[i - 1];\n        }\n      }\n      else {\n        input_strides.back() = 1;\n        for (int i = NumInputDims - 2; i >= 0; --i) {\n          input_strides[i] = input_strides[i + 1] * input_dims[i + 1];\n        }\n      }\n\n      output_index = 0;\n      reduced_index = 0;\n      for (int i = 0; i < NumInputDims; ++i) {\n        if(m_reduced[i]) {\n          m_reducedStrides[reduced_index] = input_strides[i];\n          ++reduced_index;\n        }\n        else {\n          m_preservedStrides[output_index] = input_strides[i];\n          ++output_index;\n        }\n      }\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const {\n    return m_dimensions;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType /*data*/) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    // Initialize the result\n    CoeffReturnType result = internal::cast<int, CoeffReturnType>(0);\n    Index index_stride = 0;\n    for (int i = 0; i < NumReducedDims; ++i) {\n      index_stride += m_reducedStrides[i];\n    }\n\n    // If trace is requested along all dimensions, starting index would be 0\n    Index cur_index = 0;\n    if (NumOutputDims != 0)\n      cur_index = firstInput(index);\n    for (Index i = 0; i < m_traceDim; ++i) {\n        result += m_impl.coeff(cur_index);\n        cur_index += index_stride;\n    }\n\n    return result;\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const {\n\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    eigen_assert(index + PacketSize - 1 < dimensions().TotalSize());\n\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n    for (int i = 0; i < PacketSize; ++i) {\n        values[i] = coeff(index + i);\n    }\n    PacketReturnType result = internal::ploadt<PacketReturnType, LoadMode>(values);\n    return result;\n  }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n\n protected:\n  // Given the output index, finds the first index in the input tensor used to compute the trace\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Index firstInput(Index index) const {\n    Index startInput = 0;\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      for (int i = NumOutputDims - 1; i > 0; --i) {\n        const Index idx = index / m_outputStrides[i];\n        startInput += idx * m_preservedStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      startInput += index * m_preservedStrides[0];\n    }\n    else {\n      for (int i = 0; i < NumOutputDims - 1; ++i) {\n        const Index idx = index / m_outputStrides[i];\n        startInput += idx * m_preservedStrides[i];\n        index -= idx * m_outputStrides[i];\n      }\n      startInput += index * m_preservedStrides[NumOutputDims - 1];\n    }\n    return startInput;\n  }\n\n  Dimensions m_dimensions;\n  TensorEvaluator<ArgType, Device> m_impl;\n  // Initialize the size of the trace dimension\n  Index m_traceDim;\n  const Device EIGEN_DEVICE_REF m_device;\n  array<bool, NumInputDims> m_reduced;\n  array<Index, NumReducedDims> m_reducedDims;\n  array<Index, NumOutputDims> m_outputStrides;\n  array<Index, NumReducedDims> m_reducedStrides;\n  array<Index, NumOutputDims> m_preservedStrides;\n};\n\n\n} // End namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_TRACE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorTraits.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_TRAITS_H\n#define EIGEN_CXX11_TENSOR_TENSOR_TRAITS_H\n\nnamespace Eigen {\nnamespace internal {\n\n\ntemplate<typename Scalar, int Options>\nclass compute_tensor_flags\n{\n  enum {\n    is_dynamic_size_storage = 1,\n\n    is_aligned =\n    (\n        ((Options&DontAlign)==0) && (\n#if EIGEN_MAX_STATIC_ALIGN_BYTES>0\n            (!is_dynamic_size_storage)\n#else\n            0\n#endif\n            |\n#if EIGEN_MAX_ALIGN_BYTES>0\n            is_dynamic_size_storage\n#else\n            0\n#endif\n      )\n     ),\n    packet_access_bit = packet_traits<Scalar>::Vectorizable && is_aligned ? PacketAccessBit : 0\n  };\n\n  public:\n    enum { ret = packet_access_bit };\n};\n\n\ntemplate<typename Scalar_, int NumIndices_, int Options_, typename IndexType_>\nstruct traits<Tensor<Scalar_, NumIndices_, Options_, IndexType_> >\n{\n  typedef Scalar_ Scalar;\n  typedef Dense StorageKind;\n  typedef IndexType_ Index;\n  static const int NumDimensions = NumIndices_;\n  static const int Layout = Options_ & RowMajor ? RowMajor : ColMajor;\n  enum {\n    Options = Options_,\n    Flags = compute_tensor_flags<Scalar_, Options_>::ret | (is_const<Scalar_>::value ? 0 : LvalueBit)\n  };\n  template <typename T> struct MakePointer {\n    typedef T* Type;\n  };\n  typedef typename MakePointer<Scalar>::Type PointerType;\n};\n\n\ntemplate<typename Scalar_, typename Dimensions, int Options_, typename IndexType_>\nstruct traits<TensorFixedSize<Scalar_, Dimensions, Options_, IndexType_> >\n{\n  typedef Scalar_ Scalar;\n  typedef Dense StorageKind;\n  typedef IndexType_ Index;\n  static const int NumDimensions = array_size<Dimensions>::value;\n  static const int Layout = Options_ & RowMajor ? RowMajor : ColMajor;\n  enum {\n    Options = Options_,\n    Flags = compute_tensor_flags<Scalar_, Options_>::ret | (is_const<Scalar_>::value ? 0: LvalueBit)\n  };\n  template <typename T> struct MakePointer {\n    typedef T* Type;\n  };\n  typedef typename MakePointer<Scalar>::Type PointerType;\n};\n\n\ntemplate<typename PlainObjectType, int Options_, template <class> class MakePointer_>\nstruct traits<TensorMap<PlainObjectType, Options_, MakePointer_> >\n  : public traits<PlainObjectType>\n{\n  typedef traits<PlainObjectType> BaseTraits;\n  typedef typename BaseTraits::Scalar Scalar;\n  typedef typename BaseTraits::StorageKind StorageKind;\n  typedef typename BaseTraits::Index Index;\n  static const int NumDimensions = BaseTraits::NumDimensions;\n  static const int Layout = BaseTraits::Layout;\n  enum {\n    Options = Options_,\n    Flags = BaseTraits::Flags\n  };\n  template <class T> struct MakePointer {\n    // Intermediate typedef to workaround MSVC issue.\n    typedef MakePointer_<T> MakePointerT;\n    typedef typename MakePointerT::Type Type;\n  };\n  typedef typename MakePointer<Scalar>::Type PointerType;\n};\n\ntemplate<typename PlainObjectType>\nstruct traits<TensorRef<PlainObjectType> >\n  : public traits<PlainObjectType>\n{\n  typedef traits<PlainObjectType> BaseTraits;\n  typedef typename BaseTraits::Scalar Scalar;\n  typedef typename BaseTraits::StorageKind StorageKind;\n  typedef typename BaseTraits::Index Index;\n  static const int NumDimensions = BaseTraits::NumDimensions;\n  static const int Layout = BaseTraits::Layout;\n  enum {\n    Options = BaseTraits::Options,\n    Flags = BaseTraits::Flags\n  };\n  typedef typename BaseTraits::PointerType PointerType;\n};\n\n\ntemplate<typename _Scalar, int NumIndices_, int Options, typename IndexType_>\nstruct eval<Tensor<_Scalar, NumIndices_, Options, IndexType_>, Eigen::Dense>\n{\n  typedef const Tensor<_Scalar, NumIndices_, Options, IndexType_>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename _Scalar, int NumIndices_, int Options, typename IndexType_>\nstruct eval<const Tensor<_Scalar, NumIndices_, Options, IndexType_>, Eigen::Dense>\n{\n  typedef const Tensor<_Scalar, NumIndices_, Options, IndexType_>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename Scalar_, typename Dimensions, int Options, typename IndexType_>\nstruct eval<TensorFixedSize<Scalar_, Dimensions, Options, IndexType_>, Eigen::Dense>\n{\n  typedef const TensorFixedSize<Scalar_, Dimensions, Options, IndexType_>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename Scalar_, typename Dimensions, int Options, typename IndexType_>\nstruct eval<const TensorFixedSize<Scalar_, Dimensions, Options, IndexType_>, Eigen::Dense>\n{\n  typedef const TensorFixedSize<Scalar_, Dimensions, Options, IndexType_>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename PlainObjectType, int Options, template <class> class MakePointer>\nstruct eval<TensorMap<PlainObjectType, Options, MakePointer>, Eigen::Dense>\n{\n  typedef const TensorMap<PlainObjectType, Options, MakePointer>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename PlainObjectType, int Options, template <class> class MakePointer>\nstruct eval<const TensorMap<PlainObjectType, Options, MakePointer>, Eigen::Dense>\n{\n  typedef const TensorMap<PlainObjectType, Options, MakePointer>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename PlainObjectType>\nstruct eval<TensorRef<PlainObjectType>, Eigen::Dense>\n{\n  typedef const TensorRef<PlainObjectType>EIGEN_DEVICE_REF type;\n};\n\ntemplate<typename PlainObjectType>\nstruct eval<const TensorRef<PlainObjectType>, Eigen::Dense>\n{\n  typedef const TensorRef<PlainObjectType>EIGEN_DEVICE_REF type;\n};\n\n// TODO nested<> does not exist anymore in Eigen/Core, and it thus has to be removed in favor of ref_selector.\ntemplate<typename T, int n=1, typename PlainObject = void> struct nested\n{\n  typedef typename ref_selector<T>::type type;\n};\n\ntemplate <typename Scalar_, int NumIndices_, int Options_, typename IndexType_>\nstruct nested<Tensor<Scalar_, NumIndices_, Options_, IndexType_> >\n{\n  typedef const Tensor<Scalar_, NumIndices_, Options_, IndexType_>EIGEN_DEVICE_REF type;\n};\n\ntemplate <typename Scalar_, int NumIndices_, int Options_, typename IndexType_>\nstruct nested<const Tensor<Scalar_, NumIndices_, Options_, IndexType_> >\n{\n  typedef const Tensor<Scalar_, NumIndices_, Options_, IndexType_>EIGEN_DEVICE_REF type;\n};\n\ntemplate <typename Scalar_, typename Dimensions, int Options, typename IndexType_>\nstruct nested<TensorFixedSize<Scalar_, Dimensions, Options, IndexType_> >\n{\n  typedef const TensorFixedSize<Scalar_, Dimensions, Options, IndexType_>EIGEN_DEVICE_REF type;\n};\n\ntemplate <typename Scalar_, typename Dimensions, int Options, typename IndexType_>\nstruct nested<const TensorFixedSize<Scalar_, Dimensions, Options, IndexType_> >\n{\n  typedef const TensorFixedSize<Scalar_, Dimensions, Options, IndexType_>EIGEN_DEVICE_REF type;\n};\n\n\ntemplate <typename PlainObjectType>\nstruct nested<TensorRef<PlainObjectType> >\n{\n  typedef const TensorRef<PlainObjectType>EIGEN_DEVICE_REF type;\n};\n\ntemplate <typename PlainObjectType>\nstruct nested<const TensorRef<PlainObjectType> >\n{\n  typedef const TensorRef<PlainObjectType>EIGEN_DEVICE_REF type;\n};\n\n}  // end namespace internal\n\n// Convolutional layers take in an input tensor of shape (D, R, C, B), or (D, C,\n// R, B), and convolve it with a set of filters, which can also be presented as\n// a tensor (D, K, K, M), where M is the number of filters, K is the filter\n// size, and each 3-dimensional tensor of size (D, K, K) is a filter. For\n// simplicity we assume that we always use square filters (which is usually the\n// case in images), hence the two Ks in the tensor dimension.  It also takes in\n// a few additional parameters:\n// Stride (S): The convolution stride is the offset between locations where we\n//             apply the filters.  A larger stride means that the output will be\n//             spatially smaller.\n// Padding (P): The padding we apply to the input tensor along the R and C\n//              dimensions.  This is usually used to make sure that the spatial\n//              dimensions of the output matches our intention.\n//\n// Two types of padding are often used:\n//   SAME: The pad value is computed so that the output will have size\n//         R/S and C/S.\n//   VALID: no padding is carried out.\n// When we do padding, the padded values at the padded locations are usually\n// zero.\n//\n// The output dimensions for convolution, when given all the parameters above,\n// are as follows:\n// When Padding = SAME: the output size is (B, R', C', M), where\n//   R' = ceil(float(R) / float(S))\n//   C' = ceil(float(C) / float(S))\n// where ceil is the ceiling function.  The input tensor is padded with 0 as\n// needed.  The number of padded rows and columns are computed as:\n//   Pr = ((R' - 1) * S + K - R) / 2\n//   Pc = ((C' - 1) * S + K - C) / 2\n// when the stride is 1, we have the simplified case R'=R, C'=C, Pr=Pc=(K-1)/2.\n// This is where SAME comes from - the output has the same size as the input has.\n// When Padding = VALID: the output size is computed as\n//   R' = ceil(float(R - K + 1) / float(S))\n//   C' = ceil(float(C - K + 1) / float(S))\n// and the number of padded rows and columns are computed in the same way as in\n// the SAME case.\n// When the stride is 1, we have the simplified case R'=R-K+1, C'=C-K+1, Pr=0,\n// Pc=0.\ntypedef enum {\n  PADDING_VALID = 1,\n  PADDING_SAME = 2\n} PaddingType;\n\n}  // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_TRAITS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorUInt128.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_UINT128_H\n#define EIGEN_CXX11_TENSOR_TENSOR_UINT128_H\n\nnamespace Eigen {\nnamespace internal {\n\n\ntemplate <uint64_t n>\nstruct static_val {\n  static const uint64_t value = n;\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE operator uint64_t() const { return n; }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE static_val() { }\n\n  template <typename T>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE static_val(const T& v) {\n    EIGEN_UNUSED_VARIABLE(v);\n    eigen_assert(v == n);\n  }\n};\n\n\ntemplate <typename HIGH = uint64_t, typename LOW = uint64_t>\nstruct TensorUInt128\n{\n  HIGH high;\n  LOW low;\n\n  template<typename OTHER_HIGH, typename OTHER_LOW>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  TensorUInt128(const TensorUInt128<OTHER_HIGH, OTHER_LOW>& other) : high(other.high), low(other.low) {\n    EIGEN_STATIC_ASSERT(sizeof(OTHER_HIGH) <= sizeof(HIGH), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    EIGEN_STATIC_ASSERT(sizeof(OTHER_LOW) <= sizeof(LOW), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  }\n\n  template<typename OTHER_HIGH, typename OTHER_LOW>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  TensorUInt128& operator = (const TensorUInt128<OTHER_HIGH, OTHER_LOW>& other) {\n    EIGEN_STATIC_ASSERT(sizeof(OTHER_HIGH) <= sizeof(HIGH), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    EIGEN_STATIC_ASSERT(sizeof(OTHER_LOW) <= sizeof(LOW), YOU_MADE_A_PROGRAMMING_MISTAKE);\n    high = other.high;\n    low = other.low;\n    return *this;\n  }\n\n  template<typename T>\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  explicit TensorUInt128(const T& x) : high(0), low(x) {\n    eigen_assert((static_cast<typename conditional<sizeof(T) == 8, uint64_t, uint32_t>::type>(x) <= NumTraits<uint64_t>::highest()));\n    eigen_assert(x >= 0);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  TensorUInt128(HIGH y, LOW x) : high(y), low(x) { }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE operator LOW() const {\n    return low;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE LOW lower() const {\n    return low;\n  }\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE HIGH upper() const {\n    return high;\n  }\n};\n\n\ntemplate <typename HL, typename LL, typename HR, typename LR>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nbool operator == (const TensorUInt128<HL, LL>& lhs, const TensorUInt128<HR, LR>& rhs)\n{\n  return (lhs.high == rhs.high) & (lhs.low == rhs.low);\n}\n\ntemplate <typename HL, typename LL, typename HR, typename LR>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nbool operator != (const TensorUInt128<HL, LL>& lhs, const TensorUInt128<HR, LR>& rhs)\n{\n  return (lhs.high != rhs.high) | (lhs.low != rhs.low);\n}\n\ntemplate <typename HL, typename LL, typename HR, typename LR>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nbool operator >= (const TensorUInt128<HL, LL>& lhs, const TensorUInt128<HR, LR>& rhs)\n{\n  if (lhs.high != rhs.high) {\n    return lhs.high > rhs.high;\n  }\n  return lhs.low >= rhs.low;\n}\n\ntemplate <typename HL, typename LL, typename HR, typename LR>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nbool operator < (const TensorUInt128<HL, LL>& lhs, const TensorUInt128<HR, LR>& rhs)\n{\n  if (lhs.high != rhs.high) {\n    return lhs.high < rhs.high;\n  }\n  return lhs.low < rhs.low;\n}\n\ntemplate <typename HL, typename LL, typename HR, typename LR>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nTensorUInt128<uint64_t, uint64_t> operator + (const TensorUInt128<HL, LL>& lhs, const TensorUInt128<HR, LR>& rhs)\n{\n  TensorUInt128<uint64_t, uint64_t> result(lhs.high + rhs.high, lhs.low + rhs.low);\n  if (result.low < rhs.low) {\n    result.high += 1;\n  }\n  return result;\n}\n\ntemplate <typename HL, typename LL, typename HR, typename LR>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nTensorUInt128<uint64_t, uint64_t> operator - (const TensorUInt128<HL, LL>& lhs, const TensorUInt128<HR, LR>& rhs)\n{\n  TensorUInt128<uint64_t, uint64_t> result(lhs.high - rhs.high, lhs.low - rhs.low);\n  if (result.low > lhs.low) {\n    result.high -= 1;\n  }\n  return result;\n}\n\n\ntemplate <typename HL, typename LL, typename HR, typename LR>\nstatic EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nTensorUInt128<uint64_t, uint64_t> operator * (const TensorUInt128<HL, LL>& lhs, const TensorUInt128<HR, LR>& rhs)\n{\n  // Split each 128-bit integer into 4 32-bit integers, and then do the\n  // multiplications by hand as follow:\n  //   lhs      a  b  c  d\n  //   rhs      e  f  g  h\n  //           -----------\n  //           ah bh ch dh\n  //           bg cg dg\n  //           cf df\n  //           de\n  // The result is stored in 2 64bit integers, high and low.\n\n  const uint64_t LOW = 0x00000000FFFFFFFFLL;\n  const uint64_t HIGH = 0xFFFFFFFF00000000LL;\n\n  uint64_t d = lhs.low & LOW;\n  uint64_t c = (lhs.low & HIGH) >> 32LL;\n  uint64_t b = lhs.high & LOW;\n  uint64_t a = (lhs.high & HIGH) >> 32LL;\n\n  uint64_t h = rhs.low & LOW;\n  uint64_t g = (rhs.low & HIGH) >> 32LL;\n  uint64_t f = rhs.high & LOW;\n  uint64_t e = (rhs.high & HIGH) >> 32LL;\n\n  // Compute the low 32 bits of low\n  uint64_t acc = d * h;\n  uint64_t low = acc & LOW;\n  //  Compute the high 32 bits of low. Add a carry every time we wrap around\n  acc >>= 32LL;\n  uint64_t carry = 0;\n  uint64_t acc2 = acc + c * h;\n  if (acc2 < acc) {\n    carry++;\n  }\n  acc = acc2 + d * g;\n  if (acc < acc2) {\n    carry++;\n  }\n  low |= (acc << 32LL);\n\n  // Carry forward the high bits of acc to initiate the computation of the\n  // low 32 bits of high\n  acc2 = (acc >> 32LL) | (carry << 32LL);\n  carry = 0;\n\n  acc = acc2 + b * h;\n  if (acc < acc2) {\n    carry++;\n  }\n  acc2 = acc + c * g;\n  if (acc2 < acc) {\n    carry++;\n  }\n  acc = acc2 + d * f;\n  if (acc < acc2) {\n    carry++;\n  }\n  uint64_t high = acc & LOW;\n\n  // Start to compute the high 32 bits of high.\n  acc2 = (acc >> 32LL) | (carry << 32LL);\n\n  acc = acc2 + a * h;\n  acc2 = acc + b * g;\n  acc = acc2 + c * f;\n  acc2 = acc + d * e;\n  high |= (acc2 << 32LL);\n\n  return TensorUInt128<uint64_t, uint64_t>(high, low);\n}\n\ntemplate <typename HL, typename LL, typename HR, typename LR>\nstatic EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nTensorUInt128<uint64_t, uint64_t> operator / (const TensorUInt128<HL, LL>& lhs, const TensorUInt128<HR, LR>& rhs)\n{\n  if (rhs == TensorUInt128<static_val<0>, static_val<1> >(1)) {\n    return TensorUInt128<uint64_t, uint64_t>(lhs.high, lhs.low);\n  } else if (lhs < rhs) {\n    return TensorUInt128<uint64_t, uint64_t>(0);\n  } else {\n    // calculate the biggest power of 2 times rhs that's less than or equal to lhs\n    TensorUInt128<uint64_t, uint64_t> power2(1);\n    TensorUInt128<uint64_t, uint64_t> d(rhs);\n    TensorUInt128<uint64_t, uint64_t> tmp(lhs - d);\n    while (lhs >= d) {\n      tmp = tmp - d;\n      d = d + d;\n      power2 = power2 + power2;\n    }\n\n    tmp = TensorUInt128<uint64_t, uint64_t>(lhs.high, lhs.low);\n    TensorUInt128<uint64_t, uint64_t> result(0);\n    while (power2 != TensorUInt128<static_val<0>, static_val<0> >(0)) {\n      if (tmp >= d) {\n        tmp = tmp - d;\n        result = result + power2;\n      }\n      // Shift right\n      power2 = TensorUInt128<uint64_t, uint64_t>(power2.high >> 1, (power2.low >> 1) | (power2.high << 63));\n      d = TensorUInt128<uint64_t, uint64_t>(d.high >> 1, (d.low >> 1) | (d.high << 63));\n    }\n\n    return result;\n  }\n}\n\n\n}  // namespace internal\n}  // namespace Eigen\n\n\n#endif  // EIGEN_CXX11_TENSOR_TENSOR_UINT128_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/Tensor/TensorVolumePatch.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n\n#ifndef EIGEN_CXX11_TENSOR_TENSOR_VOLUME_PATCH_H\n#define EIGEN_CXX11_TENSOR_TENSOR_VOLUME_PATCH_H\n\nnamespace Eigen {\n\n/** \\class TensorVolumePatch\n  * \\ingroup CXX11_Tensor_Module\n  *\n  * \\brief Patch extraction specialized for processing of volumetric data.\n  * This assumes that the input has a least 4 dimensions ordered as follows:\n  *  - channels\n  *  - planes\n  *  - rows\n  *  - columns\n  *  - (optional) additional dimensions such as time or batch size.\n  * Calling the volume patch code with patch_planes, patch_rows, and patch_cols\n  * is equivalent to calling the regular patch extraction code with parameters\n  * d, patch_planes, patch_rows, patch_cols, and 1 for all the additional\n  * dimensions.\n  */\nnamespace internal {\n\ntemplate<DenseIndex Planes, DenseIndex Rows, DenseIndex Cols, typename XprType>\nstruct traits<TensorVolumePatchOp<Planes, Rows, Cols, XprType> > : public traits<XprType>\n{\n  typedef typename internal::remove_const<typename XprType::Scalar>::type Scalar;\n  typedef traits<XprType> XprTraits;\n  typedef typename XprTraits::StorageKind StorageKind;\n  typedef typename XprTraits::Index Index;\n  typedef typename XprType::Nested Nested;\n  typedef typename remove_reference<Nested>::type _Nested;\n  static const int NumDimensions = XprTraits::NumDimensions + 1;\n  static const int Layout = XprTraits::Layout;\n  typedef typename XprTraits::PointerType PointerType;\n\n};\n\ntemplate<DenseIndex Planes, DenseIndex Rows, DenseIndex Cols, typename XprType>\nstruct eval<TensorVolumePatchOp<Planes, Rows, Cols, XprType>, Eigen::Dense>\n{\n  typedef const TensorVolumePatchOp<Planes, Rows, Cols, XprType>& type;\n};\n\ntemplate<DenseIndex Planes, DenseIndex Rows, DenseIndex Cols, typename XprType>\nstruct nested<TensorVolumePatchOp<Planes, Rows, Cols, XprType>, 1, typename eval<TensorVolumePatchOp<Planes, Rows, Cols, XprType> >::type>\n{\n  typedef TensorVolumePatchOp<Planes, Rows, Cols, XprType> type;\n};\n\n}  // end namespace internal\n\ntemplate<DenseIndex Planes, DenseIndex Rows, DenseIndex Cols, typename XprType>\nclass TensorVolumePatchOp : public TensorBase<TensorVolumePatchOp<Planes, Rows, Cols, XprType>, ReadOnlyAccessors>\n{\n  public:\n  typedef typename Eigen::internal::traits<TensorVolumePatchOp>::Scalar Scalar;\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename Eigen::internal::nested<TensorVolumePatchOp>::type Nested;\n  typedef typename Eigen::internal::traits<TensorVolumePatchOp>::StorageKind StorageKind;\n  typedef typename Eigen::internal::traits<TensorVolumePatchOp>::Index Index;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorVolumePatchOp(const XprType& expr, DenseIndex patch_planes, DenseIndex patch_rows, DenseIndex patch_cols,\n                                                            DenseIndex plane_strides, DenseIndex row_strides, DenseIndex col_strides,\n                                                            DenseIndex in_plane_strides, DenseIndex in_row_strides, DenseIndex in_col_strides,\n                                                            DenseIndex plane_inflate_strides, DenseIndex row_inflate_strides, DenseIndex col_inflate_strides,\n                                                            PaddingType padding_type, Scalar padding_value)\n                                                            : m_xpr(expr), m_patch_planes(patch_planes), m_patch_rows(patch_rows), m_patch_cols(patch_cols),\n                                                            m_plane_strides(plane_strides), m_row_strides(row_strides), m_col_strides(col_strides),\n                                                            m_in_plane_strides(in_plane_strides), m_in_row_strides(in_row_strides), m_in_col_strides(in_col_strides),\n                                                            m_plane_inflate_strides(plane_inflate_strides), m_row_inflate_strides(row_inflate_strides), m_col_inflate_strides(col_inflate_strides),\n                                                            m_padding_explicit(false), m_padding_top_z(0), m_padding_bottom_z(0), m_padding_top(0), m_padding_bottom(0), m_padding_left(0), m_padding_right(0),\n                                                            m_padding_type(padding_type), m_padding_value(padding_value) {}\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorVolumePatchOp(const XprType& expr, DenseIndex patch_planes, DenseIndex patch_rows, DenseIndex patch_cols,\n                                                           DenseIndex plane_strides, DenseIndex row_strides, DenseIndex col_strides,\n                                                           DenseIndex in_plane_strides, DenseIndex in_row_strides, DenseIndex in_col_strides,\n                                                           DenseIndex plane_inflate_strides, DenseIndex row_inflate_strides, DenseIndex col_inflate_strides,\n                                                           DenseIndex padding_top_z, DenseIndex padding_bottom_z,\n                                                           DenseIndex padding_top, DenseIndex padding_bottom,\n                                                           DenseIndex padding_left, DenseIndex padding_right,\n                                                           Scalar padding_value)\n                                                           : m_xpr(expr), m_patch_planes(patch_planes), m_patch_rows(patch_rows), m_patch_cols(patch_cols),\n                                                           m_plane_strides(plane_strides), m_row_strides(row_strides), m_col_strides(col_strides),\n                                                           m_in_plane_strides(in_plane_strides), m_in_row_strides(in_row_strides), m_in_col_strides(in_col_strides),\n                                                           m_plane_inflate_strides(plane_inflate_strides), m_row_inflate_strides(row_inflate_strides), m_col_inflate_strides(col_inflate_strides),\n                                                           m_padding_explicit(true), m_padding_top_z(padding_top_z), m_padding_bottom_z(padding_bottom_z), m_padding_top(padding_top), m_padding_bottom(padding_bottom),\n                                                           m_padding_left(padding_left), m_padding_right(padding_right),\n                                                           m_padding_type(PADDING_VALID), m_padding_value(padding_value) {}\n\n    EIGEN_DEVICE_FUNC\n    DenseIndex patch_planes() const { return m_patch_planes; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex patch_rows() const { return m_patch_rows; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex patch_cols() const { return m_patch_cols; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex plane_strides() const { return m_plane_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex row_strides() const { return m_row_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex col_strides() const { return m_col_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex in_plane_strides() const { return m_in_plane_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex in_row_strides() const { return m_in_row_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex in_col_strides() const { return m_in_col_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex plane_inflate_strides() const { return m_plane_inflate_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex row_inflate_strides() const { return m_row_inflate_strides; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex col_inflate_strides() const { return m_col_inflate_strides; }\n    EIGEN_DEVICE_FUNC\n    bool padding_explicit() const { return m_padding_explicit; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex padding_top_z() const { return m_padding_top_z; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex padding_bottom_z() const { return m_padding_bottom_z; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex padding_top() const { return m_padding_top; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex padding_bottom() const { return m_padding_bottom; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex padding_left() const { return m_padding_left; }\n    EIGEN_DEVICE_FUNC\n    DenseIndex padding_right() const { return m_padding_right; }\n    EIGEN_DEVICE_FUNC\n    PaddingType padding_type() const { return m_padding_type; }\n    EIGEN_DEVICE_FUNC\n    Scalar padding_value() const { return m_padding_value; }\n\n    EIGEN_DEVICE_FUNC\n    const typename internal::remove_all<typename XprType::Nested>::type&\n    expression() const { return m_xpr; }\n\n  protected:\n    typename XprType::Nested m_xpr;\n    const DenseIndex m_patch_planes;\n    const DenseIndex m_patch_rows;\n    const DenseIndex m_patch_cols;\n    const DenseIndex m_plane_strides;\n    const DenseIndex m_row_strides;\n    const DenseIndex m_col_strides;\n    const DenseIndex m_in_plane_strides;\n    const DenseIndex m_in_row_strides;\n    const DenseIndex m_in_col_strides;\n    const DenseIndex m_plane_inflate_strides;\n    const DenseIndex m_row_inflate_strides;\n    const DenseIndex m_col_inflate_strides;\n    const bool m_padding_explicit;\n    const DenseIndex m_padding_top_z;\n    const DenseIndex m_padding_bottom_z;\n    const DenseIndex m_padding_top;\n    const DenseIndex m_padding_bottom;\n    const DenseIndex m_padding_left;\n    const DenseIndex m_padding_right;\n    const PaddingType m_padding_type;\n    const Scalar m_padding_value;\n};\n\n\n// Eval as rvalue\ntemplate<DenseIndex Planes, DenseIndex Rows, DenseIndex Cols, typename ArgType, typename Device>\nstruct TensorEvaluator<const TensorVolumePatchOp<Planes, Rows, Cols, ArgType>, Device>\n{\n  typedef TensorVolumePatchOp<Planes, Rows, Cols, ArgType> XprType;\n  typedef typename XprType::Index Index;\n  static const int NumInputDims = internal::array_size<typename TensorEvaluator<ArgType, Device>::Dimensions>::value;\n  static const int NumDims = NumInputDims + 1;\n  typedef DSizes<Index, NumDims> Dimensions;\n  typedef typename internal::remove_const<typename XprType::Scalar>::type Scalar;\n  typedef typename XprType::CoeffReturnType CoeffReturnType;\n  typedef typename PacketType<CoeffReturnType, Device>::type PacketReturnType;\n  static const int PacketSize = PacketType<CoeffReturnType, Device>::size;\n  typedef StorageMemory<CoeffReturnType, Device> Storage;\n  typedef typename Storage::Type EvaluatorPointerType;\n\n  enum {\n    IsAligned = false,\n    PacketAccess = TensorEvaluator<ArgType, Device>::PacketAccess,\n    BlockAccess = false,\n    PreferBlockAccess = TensorEvaluator<ArgType, Device>::PreferBlockAccess,\n    Layout = TensorEvaluator<ArgType, Device>::Layout,\n    CoordAccess = false,\n    RawAccess = false\n  };\n\n  //===- Tensor block evaluation strategy (see TensorBlock.h) -------------===//\n  typedef internal::TensorBlockNotImplemented TensorBlock;\n  //===--------------------------------------------------------------------===//\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorEvaluator(const XprType& op, const Device& device) :\n m_impl(op.expression(), device)\n  {\n    EIGEN_STATIC_ASSERT((NumDims >= 5), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n    m_paddingValue = op.padding_value();\n\n    const typename TensorEvaluator<ArgType, Device>::Dimensions& input_dims = m_impl.dimensions();\n\n    // Cache a few variables.\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_inputDepth = input_dims[0];\n      m_inputPlanes = input_dims[1];\n      m_inputRows = input_dims[2];\n      m_inputCols = input_dims[3];\n    } else {\n      m_inputDepth = input_dims[NumInputDims-1];\n      m_inputPlanes = input_dims[NumInputDims-2];\n      m_inputRows = input_dims[NumInputDims-3];\n      m_inputCols = input_dims[NumInputDims-4];\n    }\n\n    m_plane_strides = op.plane_strides();\n    m_row_strides = op.row_strides();\n    m_col_strides = op.col_strides();\n\n    // Input strides and effective input/patch size\n    m_in_plane_strides = op.in_plane_strides();\n    m_in_row_strides = op.in_row_strides();\n    m_in_col_strides = op.in_col_strides();\n    m_plane_inflate_strides = op.plane_inflate_strides();\n    m_row_inflate_strides = op.row_inflate_strides();\n    m_col_inflate_strides = op.col_inflate_strides();\n\n    // The \"effective\" spatial size after inflating data with zeros.\n    m_input_planes_eff = (m_inputPlanes - 1) * m_plane_inflate_strides + 1;\n    m_input_rows_eff = (m_inputRows - 1) * m_row_inflate_strides + 1;\n    m_input_cols_eff = (m_inputCols - 1) * m_col_inflate_strides + 1;\n    m_patch_planes_eff = op.patch_planes() + (op.patch_planes() - 1) * (m_in_plane_strides - 1);\n    m_patch_rows_eff = op.patch_rows() + (op.patch_rows() - 1) * (m_in_row_strides - 1);\n    m_patch_cols_eff = op.patch_cols() + (op.patch_cols() - 1) * (m_in_col_strides - 1);\n\n    if (op.padding_explicit()) {\n      m_outputPlanes = numext::ceil((m_input_planes_eff + op.padding_top_z() + op.padding_bottom_z() - m_patch_planes_eff + 1.f) / static_cast<float>(m_plane_strides));\n      m_outputRows = numext::ceil((m_input_rows_eff + op.padding_top() + op.padding_bottom() - m_patch_rows_eff + 1.f) / static_cast<float>(m_row_strides));\n      m_outputCols = numext::ceil((m_input_cols_eff + op.padding_left() + op.padding_right() - m_patch_cols_eff + 1.f) / static_cast<float>(m_col_strides));\n      m_planePaddingTop = op.padding_top_z();\n      m_rowPaddingTop = op.padding_top();\n      m_colPaddingLeft = op.padding_left();\n    } else {\n      // Computing padding from the type\n      switch (op.padding_type()) {\n        case PADDING_VALID:\n          m_outputPlanes = numext::ceil((m_input_planes_eff - m_patch_planes_eff + 1.f) / static_cast<float>(m_plane_strides));\n          m_outputRows = numext::ceil((m_input_rows_eff - m_patch_rows_eff + 1.f) / static_cast<float>(m_row_strides));\n          m_outputCols = numext::ceil((m_input_cols_eff - m_patch_cols_eff + 1.f) / static_cast<float>(m_col_strides));\n          m_planePaddingTop = 0;\n          m_rowPaddingTop = 0;\n          m_colPaddingLeft = 0;\n          break;\n        case PADDING_SAME: {\n          m_outputPlanes = numext::ceil(m_input_planes_eff / static_cast<float>(m_plane_strides));\n          m_outputRows = numext::ceil(m_input_rows_eff / static_cast<float>(m_row_strides));\n          m_outputCols = numext::ceil(m_input_cols_eff / static_cast<float>(m_col_strides));\n          const Index dz = (m_outputPlanes - 1) * m_plane_strides + m_patch_planes_eff - m_input_planes_eff;\n          const Index dy = (m_outputRows - 1) * m_row_strides + m_patch_rows_eff - m_input_rows_eff;\n          const Index dx = (m_outputCols - 1) * m_col_strides + m_patch_cols_eff - m_input_cols_eff;\n          m_planePaddingTop = dz / 2;\n          m_rowPaddingTop = dy / 2;\n          m_colPaddingLeft = dx / 2;\n          break;\n        }\n        default:\n          eigen_assert(false && \"unexpected padding\");\n      }\n    }\n    eigen_assert(m_outputRows > 0);\n    eigen_assert(m_outputCols > 0);\n    eigen_assert(m_outputPlanes > 0);\n\n    // Dimensions for result of extraction.\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      // ColMajor\n      // 0: depth\n      // 1: patch_planes\n      // 2: patch_rows\n      // 3: patch_cols\n      // 4: number of patches\n      // 5 and beyond: anything else (such as batch).\n      m_dimensions[0] = input_dims[0];\n      m_dimensions[1] = op.patch_planes();\n      m_dimensions[2] = op.patch_rows();\n      m_dimensions[3] = op.patch_cols();\n      m_dimensions[4] = m_outputPlanes * m_outputRows * m_outputCols;\n      for (int i = 5; i < NumDims; ++i) {\n        m_dimensions[i] = input_dims[i-1];\n      }\n    } else {\n      // RowMajor\n      // NumDims-1: depth\n      // NumDims-2: patch_planes\n      // NumDims-3: patch_rows\n      // NumDims-4: patch_cols\n      // NumDims-5: number of patches\n      // NumDims-6 and beyond: anything else (such as batch).\n      m_dimensions[NumDims-1] = input_dims[NumInputDims-1];\n      m_dimensions[NumDims-2] = op.patch_planes();\n      m_dimensions[NumDims-3] = op.patch_rows();\n      m_dimensions[NumDims-4] = op.patch_cols();\n      m_dimensions[NumDims-5] = m_outputPlanes * m_outputRows * m_outputCols;\n      for (int i = NumDims-6; i >= 0; --i) {\n        m_dimensions[i] = input_dims[i];\n      }\n    }\n\n    // Strides for the output tensor.\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_rowStride = m_dimensions[1];\n      m_colStride = m_dimensions[2] * m_rowStride;\n      m_patchStride = m_colStride * m_dimensions[3] * m_dimensions[0];\n      m_otherStride = m_patchStride * m_dimensions[4];\n    } else {\n      m_rowStride = m_dimensions[NumDims-2];\n      m_colStride = m_dimensions[NumDims-3] * m_rowStride;\n      m_patchStride = m_colStride * m_dimensions[NumDims-4] * m_dimensions[NumDims-1];\n      m_otherStride = m_patchStride * m_dimensions[NumDims-5];\n    }\n\n    // Strides for navigating through the input tensor.\n    m_planeInputStride = m_inputDepth;\n    m_rowInputStride = m_inputDepth * m_inputPlanes;\n    m_colInputStride = m_inputDepth * m_inputRows * m_inputPlanes;\n    m_otherInputStride = m_inputDepth * m_inputRows * m_inputCols * m_inputPlanes;\n\n    m_outputPlanesRows = m_outputPlanes * m_outputRows;\n\n    // Fast representations of different variables.\n    m_fastOtherStride = internal::TensorIntDivisor<Index>(m_otherStride);\n\n    m_fastPatchStride = internal::TensorIntDivisor<Index>(m_patchStride);\n    m_fastColStride = internal::TensorIntDivisor<Index>(m_colStride);\n    m_fastRowStride = internal::TensorIntDivisor<Index>(m_rowStride);\n    m_fastInputRowStride = internal::TensorIntDivisor<Index>(m_row_inflate_strides);\n    m_fastInputColStride = internal::TensorIntDivisor<Index>(m_col_inflate_strides);\n    m_fastInputPlaneStride = internal::TensorIntDivisor<Index>(m_plane_inflate_strides);\n    m_fastInputColsEff = internal::TensorIntDivisor<Index>(m_input_cols_eff);\n    m_fastOutputPlanes = internal::TensorIntDivisor<Index>(m_outputPlanes);\n    m_fastOutputPlanesRows = internal::TensorIntDivisor<Index>(m_outputPlanesRows);\n\n    if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n      m_fastOutputDepth = internal::TensorIntDivisor<Index>(m_dimensions[0]);\n    } else {\n      m_fastOutputDepth = internal::TensorIntDivisor<Index>(m_dimensions[NumDims-1]);\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Dimensions& dimensions() const { return m_dimensions; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE bool evalSubExprsIfNeeded(EvaluatorPointerType /*data*/) {\n    m_impl.evalSubExprsIfNeeded(NULL);\n    return true;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void cleanup() {\n    m_impl.cleanup();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE CoeffReturnType coeff(Index index) const\n  {\n    // Patch index corresponding to the passed in index.\n    const Index patchIndex = index / m_fastPatchStride;\n\n    // Spatial offset within the patch. This has to be translated into 3D\n    // coordinates within the patch.\n    const Index patchOffset = (index - patchIndex * m_patchStride) / m_fastOutputDepth;\n\n    // Batch, etc.\n    const Index otherIndex = (NumDims == 5) ? 0 : index / m_fastOtherStride;\n    const Index patch3DIndex = (NumDims == 5) ? patchIndex : (index - otherIndex * m_otherStride) / m_fastPatchStride;\n\n    // Calculate column index in the input original tensor.\n    const Index colIndex = patch3DIndex / m_fastOutputPlanesRows;\n    const Index colOffset = patchOffset / m_fastColStride;\n    const Index inputCol = colIndex * m_col_strides + colOffset * m_in_col_strides - m_colPaddingLeft;\n    const Index origInputCol = (m_col_inflate_strides == 1) ? inputCol : ((inputCol >= 0) ? (inputCol / m_fastInputColStride) : 0);\n    if (inputCol < 0 || inputCol >= m_input_cols_eff ||\n        ((m_col_inflate_strides != 1) && (inputCol != origInputCol * m_col_inflate_strides))) {\n      return Scalar(m_paddingValue);\n    }\n\n    // Calculate row index in the original input tensor.\n    const Index rowIndex = (patch3DIndex - colIndex * m_outputPlanesRows) / m_fastOutputPlanes;\n    const Index rowOffset = (patchOffset - colOffset * m_colStride) / m_fastRowStride;\n    const Index inputRow = rowIndex * m_row_strides + rowOffset * m_in_row_strides - m_rowPaddingTop;\n    const Index origInputRow = (m_row_inflate_strides == 1) ? inputRow : ((inputRow >= 0) ? (inputRow / m_fastInputRowStride) : 0);\n    if (inputRow < 0 || inputRow >= m_input_rows_eff ||\n        ((m_row_inflate_strides != 1) && (inputRow != origInputRow * m_row_inflate_strides))) {\n      return Scalar(m_paddingValue);\n    }\n\n    // Calculate plane index in the original input tensor.\n    const Index planeIndex = (patch3DIndex - m_outputPlanes * (colIndex * m_outputRows + rowIndex));\n    const Index planeOffset = patchOffset - colOffset * m_colStride - rowOffset * m_rowStride;\n    const Index inputPlane = planeIndex * m_plane_strides + planeOffset * m_in_plane_strides - m_planePaddingTop;\n    const Index origInputPlane = (m_plane_inflate_strides == 1) ? inputPlane : ((inputPlane >= 0) ? (inputPlane / m_fastInputPlaneStride) : 0);\n    if (inputPlane < 0 || inputPlane >= m_input_planes_eff ||\n        ((m_plane_inflate_strides != 1) && (inputPlane != origInputPlane * m_plane_inflate_strides))) {\n      return Scalar(m_paddingValue);\n    }\n\n    const int depth_index = static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 0 : NumDims - 1;\n    const Index depth = index - (index / m_fastOutputDepth) * m_dimensions[depth_index];\n\n    const Index inputIndex = depth +\n        origInputRow * m_rowInputStride +\n        origInputCol * m_colInputStride +\n        origInputPlane * m_planeInputStride +\n        otherIndex * m_otherInputStride;\n\n    return m_impl.coeff(inputIndex);\n  }\n\n  template<int LoadMode>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packet(Index index) const\n  {\n    EIGEN_STATIC_ASSERT((PacketSize > 1), YOU_MADE_A_PROGRAMMING_MISTAKE)\n    eigen_assert(index+PacketSize-1 < dimensions().TotalSize());\n\n    if (m_in_row_strides != 1 || m_in_col_strides != 1 || m_row_inflate_strides != 1 || m_col_inflate_strides != 1 ||\n        m_in_plane_strides != 1 || m_plane_inflate_strides != 1) {\n      return packetWithPossibleZero(index);\n    }\n\n    const Index indices[2] = {index, index + PacketSize - 1};\n    const Index patchIndex = indices[0] / m_fastPatchStride;\n    if (patchIndex != indices[1] / m_fastPatchStride) {\n      return packetWithPossibleZero(index);\n    }\n    const Index otherIndex = (NumDims == 5) ? 0 : indices[0] / m_fastOtherStride;\n    eigen_assert(otherIndex == indices[1] / m_fastOtherStride);\n\n    // Find the offset of the element wrt the location of the first element.\n    const Index patchOffsets[2] = {(indices[0] - patchIndex * m_patchStride) / m_fastOutputDepth,\n                                   (indices[1] - patchIndex * m_patchStride) / m_fastOutputDepth};\n\n    const Index patch3DIndex = (NumDims == 5) ? patchIndex : (indices[0] - otherIndex * m_otherStride) / m_fastPatchStride;\n    eigen_assert(patch3DIndex == (indices[1] - otherIndex * m_otherStride) / m_fastPatchStride);\n\n    const Index colIndex = patch3DIndex / m_fastOutputPlanesRows;\n    const Index colOffsets[2] = {\n      patchOffsets[0] / m_fastColStride,\n      patchOffsets[1] / m_fastColStride};\n\n    // Calculate col indices in the original input tensor.\n    const Index inputCols[2] = {\n      colIndex * m_col_strides + colOffsets[0] - m_colPaddingLeft,\n      colIndex * m_col_strides + colOffsets[1] - m_colPaddingLeft};\n    if (inputCols[1] < 0 || inputCols[0] >= m_inputCols) {\n      return internal::pset1<PacketReturnType>(Scalar(m_paddingValue));\n    }\n\n    if (inputCols[0] != inputCols[1]) {\n      return packetWithPossibleZero(index);\n    }\n\n    const Index rowIndex = (patch3DIndex - colIndex * m_outputPlanesRows) / m_fastOutputPlanes;\n    const Index rowOffsets[2] = {\n      (patchOffsets[0] - colOffsets[0] * m_colStride) / m_fastRowStride,\n      (patchOffsets[1] - colOffsets[1] * m_colStride) / m_fastRowStride};\n    eigen_assert(rowOffsets[0] <= rowOffsets[1]);\n    // Calculate col indices in the original input tensor.\n    const Index inputRows[2] = {\n      rowIndex * m_row_strides + rowOffsets[0] - m_rowPaddingTop,\n      rowIndex * m_row_strides + rowOffsets[1] - m_rowPaddingTop};\n\n    if (inputRows[1] < 0 || inputRows[0] >= m_inputRows) {\n      return internal::pset1<PacketReturnType>(Scalar(m_paddingValue));\n    }\n\n    if (inputRows[0] != inputRows[1]) {\n      return packetWithPossibleZero(index);\n    }\n\n    const Index planeIndex = (patch3DIndex - m_outputPlanes * (colIndex * m_outputRows + rowIndex));\n    const Index planeOffsets[2] = {\n      patchOffsets[0] - colOffsets[0] * m_colStride - rowOffsets[0] * m_rowStride,\n      patchOffsets[1] - colOffsets[1] * m_colStride - rowOffsets[1] * m_rowStride};\n    eigen_assert(planeOffsets[0] <= planeOffsets[1]);\n    const Index inputPlanes[2] = {\n      planeIndex * m_plane_strides + planeOffsets[0] - m_planePaddingTop,\n      planeIndex * m_plane_strides + planeOffsets[1] - m_planePaddingTop};\n\n    if (inputPlanes[1] < 0 || inputPlanes[0] >= m_inputPlanes) {\n      return internal::pset1<PacketReturnType>(Scalar(m_paddingValue));\n    }\n\n    if (inputPlanes[0] >= 0 && inputPlanes[1] < m_inputPlanes) {\n      // no padding\n      const int depth_index = static_cast<int>(Layout) == static_cast<int>(ColMajor) ? 0 : NumDims - 1;\n      const Index depth = index - (index / m_fastOutputDepth) * m_dimensions[depth_index];\n      const Index inputIndex = depth +\n          inputRows[0] * m_rowInputStride +\n          inputCols[0] * m_colInputStride +\n          m_planeInputStride * inputPlanes[0] +\n          otherIndex * m_otherInputStride;\n      return m_impl.template packet<Unaligned>(inputIndex);\n    }\n\n    return packetWithPossibleZero(index);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE TensorOpCost\n  costPerCoeff(bool vectorized) const {\n    const double compute_cost =\n        10 * TensorOpCost::DivCost<Index>() + 21 * TensorOpCost::MulCost<Index>() +\n        8 * TensorOpCost::AddCost<Index>();\n    return TensorOpCost(0, 0, compute_cost, vectorized, PacketSize);\n  }\n\n  EIGEN_DEVICE_FUNC EvaluatorPointerType data() const { return NULL; }\n\n  const TensorEvaluator<ArgType, Device>& impl() const { return m_impl; }\n\n\n  Index planePaddingTop() const { return m_planePaddingTop; }\n  Index rowPaddingTop() const { return m_rowPaddingTop; }\n  Index colPaddingLeft() const { return m_colPaddingLeft; }\n  Index outputPlanes() const { return m_outputPlanes; }\n  Index outputRows() const { return m_outputRows; }\n  Index outputCols() const { return m_outputCols; }\n  Index userPlaneStride() const { return m_plane_strides; }\n  Index userRowStride() const { return m_row_strides; }\n  Index userColStride() const { return m_col_strides; }\n  Index userInPlaneStride() const { return m_in_plane_strides; }\n  Index userInRowStride() const { return m_in_row_strides; }\n  Index userInColStride() const { return m_in_col_strides; }\n  Index planeInflateStride() const { return m_plane_inflate_strides; }\n  Index rowInflateStride() const { return m_row_inflate_strides; }\n  Index colInflateStride() const { return m_col_inflate_strides; }\n\n#ifdef EIGEN_USE_SYCL\n  // binding placeholder accessors to a command group handler for SYCL\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void bind(cl::sycl::handler &cgh) const {\n    m_impl.bind(cgh);\n  }\n#endif\n protected:\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE PacketReturnType packetWithPossibleZero(Index index) const\n  {\n    EIGEN_ALIGN_MAX typename internal::remove_const<CoeffReturnType>::type values[PacketSize];\n    EIGEN_UNROLL_LOOP\n    for (int i = 0; i < PacketSize; ++i) {\n      values[i] = coeff(index+i);\n    }\n    PacketReturnType rslt = internal::pload<PacketReturnType>(values);\n    return rslt;\n  }\n\n  Dimensions m_dimensions;\n\n  // Parameters passed to the constructor.\n  Index m_plane_strides;\n  Index m_row_strides;\n  Index m_col_strides;\n\n  Index m_outputPlanes;\n  Index m_outputRows;\n  Index m_outputCols;\n\n  Index m_planePaddingTop;\n  Index m_rowPaddingTop;\n  Index m_colPaddingLeft;\n\n  Index m_in_plane_strides;\n  Index m_in_row_strides;\n  Index m_in_col_strides;\n\n  Index m_plane_inflate_strides;\n  Index m_row_inflate_strides;\n  Index m_col_inflate_strides;\n\n  // Cached input size.\n  Index m_inputDepth;\n  Index m_inputPlanes;\n  Index m_inputRows;\n  Index m_inputCols;\n\n  // Other cached variables.\n  Index m_outputPlanesRows;\n\n  // Effective input/patch post-inflation size.\n  Index m_input_planes_eff;\n  Index m_input_rows_eff;\n  Index m_input_cols_eff;\n  Index m_patch_planes_eff;\n  Index m_patch_rows_eff;\n  Index m_patch_cols_eff;\n\n  // Strides for the output tensor.\n  Index m_otherStride;\n  Index m_patchStride;\n  Index m_rowStride;\n  Index m_colStride;\n\n  // Strides for the input tensor.\n  Index m_planeInputStride;\n  Index m_rowInputStride;\n  Index m_colInputStride;\n  Index m_otherInputStride;\n\n  internal::TensorIntDivisor<Index> m_fastOtherStride;\n  internal::TensorIntDivisor<Index> m_fastPatchStride;\n  internal::TensorIntDivisor<Index> m_fastColStride;\n  internal::TensorIntDivisor<Index> m_fastRowStride;\n  internal::TensorIntDivisor<Index> m_fastInputPlaneStride;\n  internal::TensorIntDivisor<Index> m_fastInputRowStride;\n  internal::TensorIntDivisor<Index> m_fastInputColStride;\n  internal::TensorIntDivisor<Index> m_fastInputColsEff;\n  internal::TensorIntDivisor<Index> m_fastOutputPlanesRows;\n  internal::TensorIntDivisor<Index> m_fastOutputPlanes;\n  internal::TensorIntDivisor<Index> m_fastOutputDepth;\n\n  Scalar m_paddingValue;\n\n  TensorEvaluator<ArgType, Device> m_impl;\n\n\n};\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSOR_TENSOR_VOLUME_PATCH_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/TensorSymmetry/DynamicSymmetry.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSORSYMMETRY_DYNAMICSYMMETRY_H\n#define EIGEN_CXX11_TENSORSYMMETRY_DYNAMICSYMMETRY_H\n\nnamespace Eigen {\n\nclass DynamicSGroup\n{\n  public:\n    inline explicit DynamicSGroup() : m_numIndices(1), m_elements(), m_generators(), m_globalFlags(0) { m_elements.push_back(ge(Generator(0, 0, 0))); }\n    inline DynamicSGroup(const DynamicSGroup& o) : m_numIndices(o.m_numIndices), m_elements(o.m_elements), m_generators(o.m_generators), m_globalFlags(o.m_globalFlags) { }\n    inline DynamicSGroup(DynamicSGroup&& o) : m_numIndices(o.m_numIndices), m_elements(), m_generators(o.m_generators), m_globalFlags(o.m_globalFlags) { std::swap(m_elements, o.m_elements); }\n    inline DynamicSGroup& operator=(const DynamicSGroup& o) { m_numIndices = o.m_numIndices; m_elements = o.m_elements; m_generators = o.m_generators; m_globalFlags = o.m_globalFlags; return *this; }\n    inline DynamicSGroup& operator=(DynamicSGroup&& o) { m_numIndices = o.m_numIndices; std::swap(m_elements, o.m_elements); m_generators = o.m_generators; m_globalFlags = o.m_globalFlags; return *this; }\n\n    void add(int one, int two, int flags = 0);\n\n    template<typename Gen_>\n    inline void add(Gen_) { add(Gen_::One, Gen_::Two, Gen_::Flags); }\n    inline void addSymmetry(int one, int two) { add(one, two, 0); }\n    inline void addAntiSymmetry(int one, int two) { add(one, two, NegationFlag); }\n    inline void addHermiticity(int one, int two) { add(one, two, ConjugationFlag); }\n    inline void addAntiHermiticity(int one, int two) { add(one, two, NegationFlag | ConjugationFlag); }\n\n    template<typename Op, typename RV, typename Index, std::size_t N, typename... Args>\n    inline RV apply(const std::array<Index, N>& idx, RV initial, Args&&... args) const\n    {\n      eigen_assert(N >= m_numIndices && \"Can only apply symmetry group to objects that have at least the required amount of indices.\");\n      for (std::size_t i = 0; i < size(); i++)\n        initial = Op::run(h_permute(i, idx, typename internal::gen_numeric_list<int, N>::type()), m_elements[i].flags, initial, std::forward<Args>(args)...);\n      return initial;\n    }\n\n    template<typename Op, typename RV, typename Index, typename... Args>\n    inline RV apply(const std::vector<Index>& idx, RV initial, Args&&... args) const\n    {\n      eigen_assert(idx.size() >= m_numIndices && \"Can only apply symmetry group to objects that have at least the required amount of indices.\");\n      for (std::size_t i = 0; i < size(); i++)\n        initial = Op::run(h_permute(i, idx), m_elements[i].flags, initial, std::forward<Args>(args)...);\n      return initial;\n    }\n\n    inline int globalFlags() const { return m_globalFlags; }\n    inline std::size_t size() const { return m_elements.size(); }\n\n    template<typename Tensor_, typename... IndexTypes>\n    inline internal::tensor_symmetry_value_setter<Tensor_, DynamicSGroup> operator()(Tensor_& tensor, typename Tensor_::Index firstIndex, IndexTypes... otherIndices) const\n    {\n      static_assert(sizeof...(otherIndices) + 1 == Tensor_::NumIndices, \"Number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\");\n      return operator()(tensor, std::array<typename Tensor_::Index, Tensor_::NumIndices>{{firstIndex, otherIndices...}});\n    }\n\n    template<typename Tensor_>\n    inline internal::tensor_symmetry_value_setter<Tensor_, DynamicSGroup> operator()(Tensor_& tensor, std::array<typename Tensor_::Index, Tensor_::NumIndices> const& indices) const\n    {\n      return internal::tensor_symmetry_value_setter<Tensor_, DynamicSGroup>(tensor, *this, indices);\n    }\n  private:\n    struct GroupElement {\n      std::vector<int> representation;\n      int flags;\n      bool isId() const\n      {\n        for (std::size_t i = 0; i < representation.size(); i++)\n          if (i != (size_t)representation[i])\n            return false;\n        return true;\n      }\n    };\n    struct Generator {\n      int one;\n      int two;\n      int flags;\n      constexpr inline Generator(int one_, int two_, int flags_) : one(one_), two(two_), flags(flags_) {}\n    };\n\n    std::size_t m_numIndices;\n    std::vector<GroupElement> m_elements;\n    std::vector<Generator> m_generators;\n    int m_globalFlags;\n\n    template<typename Index, std::size_t N, int... n>\n    inline std::array<Index, N> h_permute(std::size_t which, const std::array<Index, N>& idx, internal::numeric_list<int, n...>) const\n    {\n      return std::array<Index, N>{{ idx[n >= m_numIndices ? n : m_elements[which].representation[n]]... }};\n    }\n\n    template<typename Index>\n    inline std::vector<Index> h_permute(std::size_t which, std::vector<Index> idx) const\n    {\n      std::vector<Index> result;\n      result.reserve(idx.size());\n      for (auto k : m_elements[which].representation)\n        result.push_back(idx[k]);\n      for (std::size_t i = m_numIndices; i < idx.size(); i++)\n        result.push_back(idx[i]);\n      return result;\n    }\n\n    inline GroupElement ge(Generator const& g) const\n    {\n      GroupElement result;\n      result.representation.reserve(m_numIndices);\n      result.flags = g.flags;\n      for (std::size_t k = 0; k < m_numIndices; k++) {\n        if (k == (std::size_t)g.one)\n          result.representation.push_back(g.two);\n        else if (k == (std::size_t)g.two)\n          result.representation.push_back(g.one);\n        else\n          result.representation.push_back(int(k));\n      }\n      return result;\n    }\n\n    GroupElement mul(GroupElement, GroupElement) const;\n    inline GroupElement mul(Generator g1, GroupElement g2) const\n    {\n      return mul(ge(g1), g2);\n    }\n\n    inline GroupElement mul(GroupElement g1, Generator g2) const\n    {\n      return mul(g1, ge(g2));\n    }\n\n    inline GroupElement mul(Generator g1, Generator g2) const\n    {\n      return mul(ge(g1), ge(g2));\n    }\n\n    inline int findElement(GroupElement e) const\n    {\n      for (auto ee : m_elements) {\n        if (ee.representation == e.representation)\n          return ee.flags ^ e.flags;\n      }\n      return -1;\n    }\n\n    void updateGlobalFlags(int flagDiffOfSameGenerator);\n};\n\n// dynamic symmetry group that auto-adds the template parameters in the constructor\ntemplate<typename... Gen>\nclass DynamicSGroupFromTemplateArgs : public DynamicSGroup\n{\n  public:\n    inline DynamicSGroupFromTemplateArgs() : DynamicSGroup()\n    {\n      add_all(internal::type_list<Gen...>());\n    }\n    inline DynamicSGroupFromTemplateArgs(DynamicSGroupFromTemplateArgs const& other) : DynamicSGroup(other) { }\n    inline DynamicSGroupFromTemplateArgs(DynamicSGroupFromTemplateArgs&& other) : DynamicSGroup(other) { }\n    inline DynamicSGroupFromTemplateArgs<Gen...>& operator=(const DynamicSGroupFromTemplateArgs<Gen...>& o) { DynamicSGroup::operator=(o); return *this; }\n    inline DynamicSGroupFromTemplateArgs<Gen...>& operator=(DynamicSGroupFromTemplateArgs<Gen...>&& o) { DynamicSGroup::operator=(o); return *this; }\n  \n  private:\n    template<typename Gen1, typename... GenNext>\n    inline void add_all(internal::type_list<Gen1, GenNext...>)\n    {\n      add(Gen1());\n      add_all(internal::type_list<GenNext...>());\n    }\n\n    inline void add_all(internal::type_list<>)\n    {\n    }\n};\n\ninline DynamicSGroup::GroupElement DynamicSGroup::mul(GroupElement g1, GroupElement g2) const\n{\n  eigen_internal_assert(g1.representation.size() == m_numIndices);\n  eigen_internal_assert(g2.representation.size() == m_numIndices);\n\n  GroupElement result;\n  result.representation.reserve(m_numIndices);\n  for (std::size_t i = 0; i < m_numIndices; i++) {\n    int v = g2.representation[g1.representation[i]];\n    eigen_assert(v >= 0);\n    result.representation.push_back(v);\n  }\n  result.flags = g1.flags ^ g2.flags;\n  return result;\n}\n\ninline void DynamicSGroup::add(int one, int two, int flags)\n{\n  eigen_assert(one >= 0);\n  eigen_assert(two >= 0);\n  eigen_assert(one != two);\n\n  if ((std::size_t)one >= m_numIndices || (std::size_t)two >= m_numIndices) {\n    std::size_t newNumIndices = (one > two) ? one : two + 1;\n    for (auto& gelem : m_elements) {\n      gelem.representation.reserve(newNumIndices);\n      for (std::size_t i = m_numIndices; i < newNumIndices; i++)\n        gelem.representation.push_back(i);\n    }\n    m_numIndices = newNumIndices;\n  }\n\n  Generator g{one, two, flags};\n  GroupElement e = ge(g);\n\n  /* special case for first generator */\n  if (m_elements.size() == 1) {\n    while (!e.isId()) {\n      m_elements.push_back(e);\n      e = mul(e, g);\n    }\n\n    if (e.flags > 0)\n      updateGlobalFlags(e.flags);\n\n    // only add in case we didn't have identity\n    if (m_elements.size() > 1)\n      m_generators.push_back(g);\n    return;\n  }\n\n  int p = findElement(e);\n  if (p >= 0) {\n    updateGlobalFlags(p);\n    return;\n  }\n\n  std::size_t coset_order = m_elements.size();\n  m_elements.push_back(e);\n  for (std::size_t i = 1; i < coset_order; i++)\n    m_elements.push_back(mul(m_elements[i], e));\n  m_generators.push_back(g);\n\n  std::size_t coset_rep = coset_order;\n  do {\n    for (auto g : m_generators) {\n      e = mul(m_elements[coset_rep], g);\n      p = findElement(e);\n      if (p < 0) {\n        // element not yet in group\n        m_elements.push_back(e);\n        for (std::size_t i = 1; i < coset_order; i++)\n          m_elements.push_back(mul(m_elements[i], e));\n      } else if (p > 0) {\n        updateGlobalFlags(p);\n      }\n    }\n    coset_rep += coset_order;\n  } while (coset_rep < m_elements.size());\n}\n\ninline void DynamicSGroup::updateGlobalFlags(int flagDiffOfSameGenerator)\n{\n    switch (flagDiffOfSameGenerator) {\n      case 0:\n      default:\n        // nothing happened\n        break;\n      case NegationFlag:\n        // every element is it's own negative => whole tensor is zero\n        m_globalFlags |= GlobalZeroFlag;\n        break;\n      case ConjugationFlag:\n        // every element is it's own conjugate => whole tensor is real\n        m_globalFlags |= GlobalRealFlag;\n        break;\n      case (NegationFlag | ConjugationFlag):\n        // every element is it's own negative conjugate => whole tensor is imaginary\n        m_globalFlags |= GlobalImagFlag;\n        break;\n      /* NOTE:\n       *   since GlobalZeroFlag == GlobalRealFlag | GlobalImagFlag, if one generator\n       *   causes the tensor to be real and the next one to be imaginary, this will\n       *   trivially give the correct result\n       */\n    }\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSORSYMMETRY_DYNAMICSYMMETRY_H\n\n/*\n * kate: space-indent on; indent-width 2; mixedindent off; indent-mode cstyle;\n */\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/TensorSymmetry/StaticSymmetry.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSORSYMMETRY_STATICSYMMETRY_H\n#define EIGEN_CXX11_TENSORSYMMETRY_STATICSYMMETRY_H\n\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate<typename list> struct tensor_static_symgroup_permutate;\n\ntemplate<int... nn>\nstruct tensor_static_symgroup_permutate<numeric_list<int, nn...>>\n{\n  constexpr static std::size_t N = sizeof...(nn);\n\n  template<typename T>\n  constexpr static inline std::array<T, N> run(const std::array<T, N>& indices)\n  {\n    return {{indices[nn]...}};\n  }\n};\n\ntemplate<typename indices_, int flags_>\nstruct tensor_static_symgroup_element\n{\n  typedef indices_ indices;\n  constexpr static int flags = flags_;\n};\n\ntemplate<typename Gen, int N>\nstruct tensor_static_symgroup_element_ctor\n{\n  typedef tensor_static_symgroup_element<\n    typename gen_numeric_list_swapped_pair<int, N, Gen::One, Gen::Two>::type,\n    Gen::Flags\n  > type;\n};\n\ntemplate<int N>\nstruct tensor_static_symgroup_identity_ctor\n{\n  typedef tensor_static_symgroup_element<\n    typename gen_numeric_list<int, N>::type,\n    0\n  > type;\n};\n\ntemplate<typename iib>\nstruct tensor_static_symgroup_multiply_helper\n{\n  template<int... iia>\n  constexpr static inline numeric_list<int, get<iia, iib>::value...> helper(numeric_list<int, iia...>) {\n    return numeric_list<int, get<iia, iib>::value...>();\n  }\n};\n\ntemplate<typename A, typename B>\nstruct tensor_static_symgroup_multiply\n{\n  private:\n    typedef typename A::indices iia;\n    typedef typename B::indices iib;\n    constexpr static int ffa = A::flags;\n    constexpr static int ffb = B::flags;\n  \n  public:\n    static_assert(iia::count == iib::count, \"Cannot multiply symmetry elements with different number of indices.\");\n\n    typedef tensor_static_symgroup_element<\n      decltype(tensor_static_symgroup_multiply_helper<iib>::helper(iia())),\n      ffa ^ ffb\n    > type;\n};\n\ntemplate<typename A, typename B>\nstruct tensor_static_symgroup_equality\n{\n    typedef typename A::indices iia;\n    typedef typename B::indices iib;\n    constexpr static int ffa = A::flags;\n    constexpr static int ffb = B::flags;\n    static_assert(iia::count == iib::count, \"Cannot compare symmetry elements with different number of indices.\");\n\n    constexpr static bool value = is_same<iia, iib>::value;\n\n  private:\n    /* this should be zero if they are identical, or else the tensor\n     * will be forced to be pure real, pure imaginary or even pure zero\n     */\n    constexpr static int flags_cmp_ = ffa ^ ffb;\n\n    /* either they are not equal, then we don't care whether the flags\n     * match, or they are equal, and then we have to check\n     */\n    constexpr static bool is_zero      = value && flags_cmp_ == NegationFlag;\n    constexpr static bool is_real      = value && flags_cmp_ == ConjugationFlag;\n    constexpr static bool is_imag      = value && flags_cmp_ == (NegationFlag | ConjugationFlag);\n\n  public:\n    constexpr static int global_flags = \n      (is_real ? GlobalRealFlag : 0) |\n      (is_imag ? GlobalImagFlag : 0) |\n      (is_zero ? GlobalZeroFlag : 0);\n};\n\ntemplate<std::size_t NumIndices, typename... Gen>\nstruct tensor_static_symgroup\n{\n  typedef StaticSGroup<Gen...> type;\n  constexpr static std::size_t size = type::static_size;\n};\n\ntemplate<typename Index, std::size_t N, int... ii, int... jj>\nconstexpr static inline std::array<Index, N> tensor_static_symgroup_index_permute(std::array<Index, N> idx, internal::numeric_list<int, ii...>, internal::numeric_list<int, jj...>)\n{\n  return {{ idx[ii]..., idx[jj]... }};\n}\n\ntemplate<typename Index, int... ii>\nstatic inline std::vector<Index> tensor_static_symgroup_index_permute(std::vector<Index> idx, internal::numeric_list<int, ii...>)\n{\n  std::vector<Index> result{{ idx[ii]... }};\n  std::size_t target_size = idx.size();\n  for (std::size_t i = result.size(); i < target_size; i++)\n    result.push_back(idx[i]);\n  return result;\n}\n\ntemplate<typename T> struct tensor_static_symgroup_do_apply;\n\ntemplate<typename first, typename... next>\nstruct tensor_static_symgroup_do_apply<internal::type_list<first, next...>>\n{\n  template<typename Op, typename RV, std::size_t SGNumIndices, typename Index, std::size_t NumIndices, typename... Args>\n  static inline RV run(const std::array<Index, NumIndices>& idx, RV initial, Args&&... args)\n  {\n    static_assert(NumIndices >= SGNumIndices, \"Can only apply symmetry group to objects that have at least the required amount of indices.\");\n    typedef typename internal::gen_numeric_list<int, NumIndices - SGNumIndices, SGNumIndices>::type remaining_indices;\n    initial = Op::run(tensor_static_symgroup_index_permute(idx, typename first::indices(), remaining_indices()), first::flags, initial, std::forward<Args>(args)...);\n    return tensor_static_symgroup_do_apply<internal::type_list<next...>>::template run<Op, RV, SGNumIndices>(idx, initial, args...);\n  }\n\n  template<typename Op, typename RV, std::size_t SGNumIndices, typename Index, typename... Args>\n  static inline RV run(const std::vector<Index>& idx, RV initial, Args&&... args)\n  {\n    eigen_assert(idx.size() >= SGNumIndices && \"Can only apply symmetry group to objects that have at least the required amount of indices.\");\n    initial = Op::run(tensor_static_symgroup_index_permute(idx, typename first::indices()), first::flags, initial, std::forward<Args>(args)...);\n    return tensor_static_symgroup_do_apply<internal::type_list<next...>>::template run<Op, RV, SGNumIndices>(idx, initial, args...);\n  }\n};\n\ntemplate<EIGEN_TPL_PP_SPEC_HACK_DEF(typename, empty)>\nstruct tensor_static_symgroup_do_apply<internal::type_list<EIGEN_TPL_PP_SPEC_HACK_USE(empty)>>\n{\n  template<typename Op, typename RV, std::size_t SGNumIndices, typename Index, std::size_t NumIndices, typename... Args>\n  static inline RV run(const std::array<Index, NumIndices>&, RV initial, Args&&...)\n  {\n    // do nothing\n    return initial;\n  }\n\n  template<typename Op, typename RV, std::size_t SGNumIndices, typename Index, typename... Args>\n  static inline RV run(const std::vector<Index>&, RV initial, Args&&...)\n  {\n    // do nothing\n    return initial;\n  }\n};\n\n} // end namespace internal\n\ntemplate<typename... Gen>\nclass StaticSGroup\n{\n    constexpr static std::size_t NumIndices = internal::tensor_symmetry_num_indices<Gen...>::value;\n    typedef internal::group_theory::enumerate_group_elements<\n      internal::tensor_static_symgroup_multiply,\n      internal::tensor_static_symgroup_equality,\n      typename internal::tensor_static_symgroup_identity_ctor<NumIndices>::type,\n      internal::type_list<typename internal::tensor_static_symgroup_element_ctor<Gen, NumIndices>::type...>\n    > group_elements;\n    typedef typename group_elements::type ge;\n  public:\n    constexpr inline StaticSGroup() {}\n    constexpr inline StaticSGroup(const StaticSGroup<Gen...>&) {}\n    constexpr inline StaticSGroup(StaticSGroup<Gen...>&&) {}\n\n    template<typename Op, typename RV, typename Index, std::size_t N, typename... Args>\n    static inline RV apply(const std::array<Index, N>& idx, RV initial, Args&&... args)\n    {\n      return internal::tensor_static_symgroup_do_apply<ge>::template run<Op, RV, NumIndices>(idx, initial, args...);\n    }\n\n    template<typename Op, typename RV, typename Index, typename... Args>\n    static inline RV apply(const std::vector<Index>& idx, RV initial, Args&&... args)\n    {\n      eigen_assert(idx.size() == NumIndices);\n      return internal::tensor_static_symgroup_do_apply<ge>::template run<Op, RV, NumIndices>(idx, initial, args...);\n    }\n\n    constexpr static std::size_t static_size = ge::count;\n\n    constexpr static inline std::size_t size() {\n      return ge::count;\n    }\n    constexpr static inline int globalFlags() { return group_elements::global_flags; }\n\n    template<typename Tensor_, typename... IndexTypes>\n    inline internal::tensor_symmetry_value_setter<Tensor_, StaticSGroup<Gen...>> operator()(Tensor_& tensor, typename Tensor_::Index firstIndex, IndexTypes... otherIndices) const\n    {\n      static_assert(sizeof...(otherIndices) + 1 == Tensor_::NumIndices, \"Number of indices used to access a tensor coefficient must be equal to the rank of the tensor.\");\n      return operator()(tensor, std::array<typename Tensor_::Index, Tensor_::NumIndices>{{firstIndex, otherIndices...}});\n    }\n\n    template<typename Tensor_>\n    inline internal::tensor_symmetry_value_setter<Tensor_, StaticSGroup<Gen...>> operator()(Tensor_& tensor, std::array<typename Tensor_::Index, Tensor_::NumIndices> const& indices) const\n    {\n      return internal::tensor_symmetry_value_setter<Tensor_, StaticSGroup<Gen...>>(tensor, *this, indices);\n    }\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSORSYMMETRY_STATICSYMMETRY_H\n\n/*\n * kate: space-indent on; indent-width 2; mixedindent off; indent-mode cstyle;\n */\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/TensorSymmetry/Symmetry.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSORSYMMETRY_SYMMETRY_H\n#define EIGEN_CXX11_TENSORSYMMETRY_SYMMETRY_H\n\nnamespace Eigen {\n\nenum {\n  NegationFlag           = 0x01,\n  ConjugationFlag        = 0x02\n};\n\nenum {\n  GlobalRealFlag         = 0x01,\n  GlobalImagFlag         = 0x02,\n  GlobalZeroFlag         = 0x03\n};\n\nnamespace internal {\n\ntemplate<std::size_t NumIndices, typename... Sym>                   struct tensor_symmetry_pre_analysis;\ntemplate<std::size_t NumIndices, typename... Sym>                   struct tensor_static_symgroup;\ntemplate<bool instantiate, std::size_t NumIndices, typename... Sym> struct tensor_static_symgroup_if;\ntemplate<typename Tensor_> struct tensor_symmetry_calculate_flags;\ntemplate<typename Tensor_> struct tensor_symmetry_assign_value;\ntemplate<typename... Sym> struct tensor_symmetry_num_indices;\n\n} // end namespace internal\n\ntemplate<int One_, int Two_>\nstruct Symmetry\n{\n  static_assert(One_ != Two_, \"Symmetries must cover distinct indices.\");\n  constexpr static int One = One_;\n  constexpr static int Two = Two_;\n  constexpr static int Flags = 0;\n};\n\ntemplate<int One_, int Two_>\nstruct AntiSymmetry\n{\n  static_assert(One_ != Two_, \"Symmetries must cover distinct indices.\");\n  constexpr static int One = One_;\n  constexpr static int Two = Two_;\n  constexpr static int Flags = NegationFlag;\n};\n\ntemplate<int One_, int Two_>\nstruct Hermiticity\n{\n  static_assert(One_ != Two_, \"Symmetries must cover distinct indices.\");\n  constexpr static int One = One_;\n  constexpr static int Two = Two_;\n  constexpr static int Flags = ConjugationFlag;\n};\n\ntemplate<int One_, int Two_>\nstruct AntiHermiticity\n{\n  static_assert(One_ != Two_, \"Symmetries must cover distinct indices.\");\n  constexpr static int One = One_;\n  constexpr static int Two = Two_;\n  constexpr static int Flags = ConjugationFlag | NegationFlag;\n};\n\n/** \\class DynamicSGroup\n  * \\ingroup TensorSymmetry_Module\n  *\n  * \\brief Dynamic symmetry group\n  *\n  * The %DynamicSGroup class represents a symmetry group that need not be known at\n  * compile time. It is useful if one wants to support arbitrary run-time defineable\n  * symmetries for tensors, but it is also instantiated if a symmetry group is defined\n  * at compile time that would be either too large for the compiler to reasonably\n  * generate (using templates to calculate this at compile time is very inefficient)\n  * or that the compiler could generate the group but that it wouldn't make sense to\n  * unroll the loop for setting coefficients anymore.\n  */\nclass DynamicSGroup;\n\n/** \\internal\n  *\n  * \\class DynamicSGroupFromTemplateArgs\n  * \\ingroup TensorSymmetry_Module\n  *\n  * \\brief Dynamic symmetry group, initialized from template arguments\n  *\n  * This class is a child class of DynamicSGroup. It uses the template arguments\n  * specified to initialize itself.\n  */\ntemplate<typename... Gen>\nclass DynamicSGroupFromTemplateArgs;\n\n/** \\class StaticSGroup\n  * \\ingroup TensorSymmetry_Module\n  *\n  * \\brief Static symmetry group\n  *\n  * This class represents a symmetry group that is known and resolved completely\n  * at compile time. Ideally, no run-time penalty is incurred compared to the\n  * manual unrolling of the symmetry.\n  *\n  * <b><i>CAUTION:</i></b>\n  *\n  * Do not use this class directly for large symmetry groups. The compiler\n  * may run into a limit, or segfault or in the very least will take a very,\n  * very, very long time to compile the code. Use the SGroup class instead\n  * if you want a static group. That class contains logic that will\n  * automatically select the DynamicSGroup class instead if the symmetry\n  * group becomes too large. (In that case, unrolling may not even be\n  * beneficial.)\n  */\ntemplate<typename... Gen>\nclass StaticSGroup;\n\n/** \\class SGroup\n  * \\ingroup TensorSymmetry_Module\n  *\n  * \\brief Symmetry group, initialized from template arguments\n  *\n  * This class represents a symmetry group whose generators are already\n  * known at compile time. It may or may not be resolved at compile time,\n  * depending on the estimated size of the group.\n  *\n  * \\sa StaticSGroup\n  * \\sa DynamicSGroup\n  */\ntemplate<typename... Gen>\nclass SGroup : public internal::tensor_symmetry_pre_analysis<internal::tensor_symmetry_num_indices<Gen...>::value, Gen...>::root_type\n{\n  public:\n    constexpr static std::size_t NumIndices = internal::tensor_symmetry_num_indices<Gen...>::value;\n    typedef typename internal::tensor_symmetry_pre_analysis<NumIndices, Gen...>::root_type Base;\n\n    // make standard constructors + assignment operators public\n    inline SGroup() : Base() { }\n    inline SGroup(const SGroup<Gen...>& other) : Base(other) { }\n    inline SGroup(SGroup<Gen...>&& other) : Base(other) { }\n    inline SGroup<Gen...>& operator=(const SGroup<Gen...>& other) { Base::operator=(other); return *this; }\n    inline SGroup<Gen...>& operator=(SGroup<Gen...>&& other) { Base::operator=(other); return *this; }\n\n    // all else is defined in the base class\n};\n\nnamespace internal {\n\ntemplate<typename... Sym> struct tensor_symmetry_num_indices\n{\n  constexpr static std::size_t value = 1;\n};\n\ntemplate<int One_, int Two_, typename... Sym> struct tensor_symmetry_num_indices<Symmetry<One_, Two_>, Sym...>\n{\nprivate:\n  constexpr static std::size_t One = static_cast<std::size_t>(One_);\n  constexpr static std::size_t Two = static_cast<std::size_t>(Two_);\n  constexpr static std::size_t Three = tensor_symmetry_num_indices<Sym...>::value;\n\n  // don't use std::max, since it's not constexpr until C++14...\n  constexpr static std::size_t maxOneTwoPlusOne = ((One > Two) ? One : Two) + 1;\npublic:\n  constexpr static std::size_t value = (maxOneTwoPlusOne > Three) ? maxOneTwoPlusOne : Three;\n};\n\ntemplate<int One_, int Two_, typename... Sym> struct tensor_symmetry_num_indices<AntiSymmetry<One_, Two_>, Sym...>\n  : public tensor_symmetry_num_indices<Symmetry<One_, Two_>, Sym...> {};\ntemplate<int One_, int Two_, typename... Sym> struct tensor_symmetry_num_indices<Hermiticity<One_, Two_>, Sym...>\n  : public tensor_symmetry_num_indices<Symmetry<One_, Two_>, Sym...> {};\ntemplate<int One_, int Two_, typename... Sym> struct tensor_symmetry_num_indices<AntiHermiticity<One_, Two_>, Sym...>\n  : public tensor_symmetry_num_indices<Symmetry<One_, Two_>, Sym...> {};\n\n/** \\internal\n  *\n  * \\class tensor_symmetry_pre_analysis\n  * \\ingroup TensorSymmetry_Module\n  *\n  * \\brief Pre-select whether to use a static or dynamic symmetry group\n  *\n  * When a symmetry group could in principle be determined at compile time,\n  * this template implements the logic whether to actually do that or whether\n  * to rather defer that to runtime.\n  *\n  * The logic is as follows:\n  * <dl>\n  * <dt><b>No generators (trivial symmetry):</b></dt>\n  * <dd>Use a trivial static group. Ideally, this has no performance impact\n  *     compared to not using symmetry at all. In practice, this might not\n  *     be the case.</dd>\n  * <dt><b>More than 4 generators:</b></dt>\n  * <dd>Calculate the group at run time, it is likely far too large for the\n  *     compiler to be able to properly generate it in a realistic time.</dd>\n  * <dt><b>Up to and including 4 generators:</b></dt>\n  * <dd>Actually enumerate all group elements, but then check how many there\n  *     are. If there are more than 16, it is unlikely that unrolling the\n  *     loop (as is done in the static compile-time case) is sensible, so\n  *     use a dynamic group instead. If there are at most 16 elements, actually\n  *     use that static group. Note that the largest group with 4 generators\n  *     still compiles with reasonable resources.</dd>\n  * </dl>\n  *\n  * Note: Example compile time performance with g++-4.6 on an Intenl Core i5-3470\n  *       with 16 GiB RAM (all generators non-redundant and the subgroups don't\n  *       factorize):\n  *\n  *          # Generators          -O0 -ggdb               -O2\n  *          -------------------------------------------------------------------\n  *          1                 0.5 s  /   250 MiB     0.45s /   230 MiB\n  *          2                 0.5 s  /   260 MiB     0.5 s /   250 MiB\n  *          3                 0.65s  /   310 MiB     0.62s /   310 MiB\n  *          4                 2.2 s  /   860 MiB     1.7 s /   770 MiB\n  *          5               130   s  / 13000 MiB   120   s / 11000 MiB\n  *\n  * It is clear that everything is still very efficient up to 4 generators, then\n  * the memory and CPU requirements become unreasonable. Thus we only instantiate\n  * the template group theory logic if the number of generators supplied is 4 or\n  * lower, otherwise this will be forced to be done during runtime, where the\n  * algorithm is reasonably fast.\n  */\ntemplate<std::size_t NumIndices>\nstruct tensor_symmetry_pre_analysis<NumIndices>\n{\n  typedef StaticSGroup<> root_type;\n};\n\ntemplate<std::size_t NumIndices, typename Gen_, typename... Gens_>\nstruct tensor_symmetry_pre_analysis<NumIndices, Gen_, Gens_...>\n{\n  constexpr static std::size_t max_static_generators = 4;\n  constexpr static std::size_t max_static_elements = 16;\n  typedef tensor_static_symgroup_if<(sizeof...(Gens_) + 1 <= max_static_generators), NumIndices, Gen_, Gens_...> helper;\n  constexpr static std::size_t possible_size = helper::size;\n\n  typedef typename conditional<\n    possible_size == 0 || possible_size >= max_static_elements,\n    DynamicSGroupFromTemplateArgs<Gen_, Gens_...>,\n    typename helper::type\n  >::type root_type;\n};\n\ntemplate<bool instantiate, std::size_t NumIndices, typename... Gens>\nstruct tensor_static_symgroup_if\n{\n  constexpr static std::size_t size = 0;\n  typedef void type;\n};\n\ntemplate<std::size_t NumIndices, typename... Gens>\nstruct tensor_static_symgroup_if<true, NumIndices, Gens...> : tensor_static_symgroup<NumIndices, Gens...> {};\n\ntemplate<typename Tensor_>\nstruct tensor_symmetry_assign_value\n{\n  typedef typename Tensor_::Index Index;\n  typedef typename Tensor_::Scalar Scalar;\n  constexpr static std::size_t NumIndices = Tensor_::NumIndices;\n\n  static inline int run(const std::array<Index, NumIndices>& transformed_indices, int transformation_flags, int dummy, Tensor_& tensor, const Scalar& value_)\n  {\n    Scalar value(value_);\n    if (transformation_flags & ConjugationFlag)\n      value = numext::conj(value);\n    if (transformation_flags & NegationFlag)\n      value = -value;\n    tensor.coeffRef(transformed_indices) = value;\n    return dummy;\n  }\n};\n\ntemplate<typename Tensor_>\nstruct tensor_symmetry_calculate_flags\n{\n  typedef typename Tensor_::Index Index;\n  constexpr static std::size_t NumIndices = Tensor_::NumIndices;\n\n  static inline int run(const std::array<Index, NumIndices>& transformed_indices, int transform_flags, int current_flags, const std::array<Index, NumIndices>& orig_indices)\n  {\n    if (transformed_indices == orig_indices) {\n      if (transform_flags & (ConjugationFlag | NegationFlag))\n        return current_flags | GlobalImagFlag; // anti-hermitian diagonal\n      else if (transform_flags & ConjugationFlag)\n        return current_flags | GlobalRealFlag; // hermitian diagonal\n      else if (transform_flags & NegationFlag)\n        return current_flags | GlobalZeroFlag; // anti-symmetric diagonal\n    }\n    return current_flags;\n  }\n};\n\ntemplate<typename Tensor_, typename Symmetry_, int Flags = 0>\nclass tensor_symmetry_value_setter\n{\n  public:\n    typedef typename Tensor_::Index Index;\n    typedef typename Tensor_::Scalar Scalar;\n    constexpr static std::size_t NumIndices = Tensor_::NumIndices;\n\n    inline tensor_symmetry_value_setter(Tensor_& tensor, Symmetry_ const& symmetry, std::array<Index, NumIndices> const& indices)\n      : m_tensor(tensor), m_symmetry(symmetry), m_indices(indices) { }\n\n    inline tensor_symmetry_value_setter<Tensor_, Symmetry_, Flags>& operator=(Scalar const& value)\n    {\n      doAssign(value);\n      return *this;\n    }\n  private:\n    Tensor_& m_tensor;\n    Symmetry_ m_symmetry;\n    std::array<Index, NumIndices> m_indices;\n\n    inline void doAssign(Scalar const& value)\n    {\n      #ifdef EIGEN_TENSOR_SYMMETRY_CHECK_VALUES\n        int value_flags = m_symmetry.template apply<internal::tensor_symmetry_calculate_flags<Tensor_>, int>(m_indices, m_symmetry.globalFlags(), m_indices);\n        if (value_flags & GlobalRealFlag)\n          eigen_assert(numext::imag(value) == 0);\n        if (value_flags & GlobalImagFlag)\n          eigen_assert(numext::real(value) == 0);\n      #endif\n      m_symmetry.template apply<internal::tensor_symmetry_assign_value<Tensor_>, int>(m_indices, 0, m_tensor, value);\n    }\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSORSYMMETRY_SYMMETRY_H\n\n/*\n * kate: space-indent on; indent-width 2; mixedindent off; indent-mode cstyle;\n */\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/TensorSymmetry/util/TemplateGroupTheory.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_TENSORSYMMETRY_TEMPLATEGROUPTHEORY_H\n#define EIGEN_CXX11_TENSORSYMMETRY_TEMPLATEGROUPTHEORY_H\n\nnamespace Eigen {\n\nnamespace internal {\n\nnamespace group_theory {\n\n/** \\internal\n  * \\file CXX11/src/TensorSymmetry/util/TemplateGroupTheory.h\n  * This file contains C++ templates that implement group theory algorithms.\n  *\n  * The algorithms allow for a compile-time analysis of finite groups.\n  *\n  * Currently only Dimino's algorithm is implemented, which returns a list\n  * of all elements in a group given a set of (possibly redundant) generators.\n  * (One could also do that with the so-called orbital algorithm, but that\n  * is much more expensive and usually has no advantages.)\n  */\n\n/**********************************************************************\n *                \"Ok kid, here is where it gets complicated.\"\n *                         - Amelia Pond in the \"Doctor Who\" episode\n *                           \"The Big Bang\"\n *\n * Dimino's algorithm\n * ==================\n *\n * The following is Dimino's algorithm in sequential form:\n *\n * Input: identity element, list of generators, equality check,\n *        multiplication operation\n * Output: list of group elements\n *\n * 1. add identity element\n * 2. remove identities from list of generators\n * 3. add all powers of first generator that aren't the\n *    identity element\n * 4. go through all remaining generators:\n *        a. if generator is already in the list of elements\n *                -> do nothing\n *        b. otherwise\n *                i.   remember current # of elements\n *                     (i.e. the size of the current subgroup)\n *                ii.  add all current elements (which includes\n *                     the identity) each multiplied from right\n *                     with the current generator to the group\n *                iii. add all remaining cosets that are generated\n *                     by products of the new generator with itself\n *                     and all other generators seen so far\n *\n * In functional form, this is implemented as a long set of recursive\n * templates that have a complicated relationship.\n *\n * The main interface for Dimino's algorithm is the template\n * enumerate_group_elements. All lists are implemented as variadic\n * type_list<typename...> and numeric_list<typename = int, int...>\n * templates.\n *\n * 'Calling' templates is usually done via typedefs.\n *\n * This algorithm is an extended version of the basic version. The\n * extension consists in the fact that each group element has a set\n * of flags associated with it. Multiplication of two group elements\n * with each other results in a group element whose flags are the\n * XOR of the flags of the previous elements. Each time the algorithm\n * notices that a group element it just calculated is already in the\n * list of current elements, the flags of both will be compared and\n * added to the so-called 'global flags' of the group.\n *\n * The rationale behind this extension is that this allows not only\n * for the description of symmetries between tensor indices, but\n * also allows for the description of hermiticity, antisymmetry and\n * antihermiticity. Negation and conjugation each are specific bit\n * in the flags value and if two different ways to reach a group\n * element lead to two different flags, this poses a constraint on\n * the allowed values of the resulting tensor. For example, if a\n * group element is reach both with and without the conjugation\n * flags, it is clear that the resulting tensor has to be real.\n *\n * Note that this flag mechanism is quite generic and may have other\n * uses beyond tensor properties.\n *\n * IMPORTANT: \n *     This algorithm assumes the group to be finite. If you try to\n *     run it with a group that's infinite, the algorithm will only\n *     terminate once you hit a compiler limit (max template depth).\n *     Also note that trying to use this implementation to create a\n *     very large group will probably either make you hit the same\n *     limit, cause the compiler to segfault or at the very least\n *     take a *really* long time (hours, days, weeks - sic!) to\n *     compile. It is not recommended to plug in more than 4\n *     generators, unless they are independent of each other.\n */\n\n/** \\internal\n  *\n  * \\class strip_identities\n  * \\ingroup CXX11_TensorSymmetry_Module\n  *\n  * \\brief Cleanse a list of group elements of the identity element\n  *\n  * This template is used to make a first pass through all initial\n  * generators of Dimino's algorithm and remove the identity\n  * elements.\n  *\n  * \\sa enumerate_group_elements\n  */\ntemplate<template<typename, typename> class Equality, typename id, typename L> struct strip_identities;\n\ntemplate<\n  template<typename, typename> class Equality,\n  typename id,\n  typename t,\n  typename... ts\n>\nstruct strip_identities<Equality, id, type_list<t, ts...>>\n{\n  typedef typename conditional<\n    Equality<id, t>::value,\n    typename strip_identities<Equality, id, type_list<ts...>>::type,\n    typename concat<type_list<t>, typename strip_identities<Equality, id, type_list<ts...>>::type>::type\n  >::type type;\n  constexpr static int global_flags = Equality<id, t>::global_flags | strip_identities<Equality, id, type_list<ts...>>::global_flags;\n};\n\ntemplate<\n  template<typename, typename> class Equality,\n  typename id\n  EIGEN_TPL_PP_SPEC_HACK_DEFC(typename, ts)\n>\nstruct strip_identities<Equality, id, type_list<EIGEN_TPL_PP_SPEC_HACK_USE(ts)>>\n{\n  typedef type_list<> type;\n  constexpr static int global_flags = 0;\n};\n\n/** \\internal\n  *\n  * \\class dimino_first_step_elements_helper \n  * \\ingroup CXX11_TensorSymmetry_Module\n  *\n  * \\brief Recursive template that adds powers of the first generator to the list of group elements\n  *\n  * This template calls itself recursively to add powers of the first\n  * generator to the list of group elements. It stops if it reaches\n  * the identity element again.\n  *\n  * \\sa enumerate_group_elements, dimino_first_step_elements\n  */\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename g,\n  typename current_element,\n  typename elements,\n  bool dont_add_current_element   // = false\n>\nstruct dimino_first_step_elements_helper\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n  : // recursive inheritance is too difficult for Doxygen\n  public dimino_first_step_elements_helper<\n    Multiply,\n    Equality,\n    id,\n    g,\n    typename Multiply<current_element, g>::type,\n    typename concat<elements, type_list<current_element>>::type,\n    Equality<typename Multiply<current_element, g>::type, id>::value\n  > {};\n\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename g,\n  typename current_element,\n  typename elements\n>\nstruct dimino_first_step_elements_helper<Multiply, Equality, id, g, current_element, elements, true>\n#endif // EIGEN_PARSED_BY_DOXYGEN\n{\n  typedef elements type;\n  constexpr static int global_flags = Equality<current_element, id>::global_flags;\n};\n\n/** \\internal\n  *\n  * \\class dimino_first_step_elements\n  * \\ingroup CXX11_TensorSymmetry_Module\n  *\n  * \\brief Add all powers of the first generator to the list of group elements\n  *\n  * This template takes the first non-identity generator and generates the initial\n  * list of elements which consists of all powers of that generator. For a group\n  * with just one generated, it would be enumerated after this.\n  *\n  * \\sa enumerate_group_elements\n  */\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename generators\n>\nstruct dimino_first_step_elements\n{\n  typedef typename get<0, generators>::type first_generator;\n  typedef typename skip<1, generators>::type next_generators;\n  typedef type_list<first_generator> generators_done;\n\n  typedef dimino_first_step_elements_helper<\n    Multiply,\n    Equality,\n    id,\n    first_generator,\n    first_generator,\n    type_list<id>,\n    false\n  > helper;\n  typedef typename helper::type type;\n  constexpr static int global_flags = helper::global_flags;\n};\n\n/** \\internal\n  *\n  * \\class dimino_get_coset_elements\n  * \\ingroup CXX11_TensorSymmetry_Module\n  *\n  * \\brief Generate all elements of a specific coset\n  *\n  * This template generates all the elements of a specific coset by\n  * multiplying all elements in the given subgroup with the new\n  * coset representative. Note that the first element of the\n  * subgroup is always the identity element, so the first element of\n  * the result of this template is going to be the coset\n  * representative itself.\n  *\n  * Note that this template accepts an additional boolean parameter\n  * that specifies whether to actually generate the coset (true) or\n  * just return an empty list (false).\n  *\n  * \\sa enumerate_group_elements, dimino_add_cosets_for_rep\n  */\ntemplate<\n  template<typename, typename> class Multiply,\n  typename sub_group_elements,\n  typename new_coset_rep,\n  bool generate_coset      // = true\n>\nstruct dimino_get_coset_elements\n{\n  typedef typename apply_op_from_right<Multiply, new_coset_rep, sub_group_elements>::type type;\n};\n\ntemplate<\n  template<typename, typename> class Multiply,\n  typename sub_group_elements,\n  typename new_coset_rep\n>\nstruct dimino_get_coset_elements<Multiply, sub_group_elements, new_coset_rep, false>\n{\n  typedef type_list<> type;\n};\n\n/** \\internal\n  *\n  * \\class dimino_add_cosets_for_rep\n  * \\ingroup CXX11_TensorSymmetry_Module\n  *\n  * \\brief Recursive template for adding coset spaces\n  *\n  * This template multiplies the coset representative with a generator\n  * from the list of previous generators. If the new element is not in\n  * the group already, it adds the corresponding coset. Finally it\n  * proceeds to call itself with the next generator from the list.\n  *\n  * \\sa enumerate_group_elements, dimino_add_all_coset_spaces\n  */\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename sub_group_elements,\n  typename elements,\n  typename generators,\n  typename rep_element,\n  int sub_group_size\n>\nstruct dimino_add_cosets_for_rep;\n\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename sub_group_elements,\n  typename elements,\n  typename g,\n  typename... gs,\n  typename rep_element,\n  int sub_group_size\n>\nstruct dimino_add_cosets_for_rep<Multiply, Equality, id, sub_group_elements, elements, type_list<g, gs...>, rep_element, sub_group_size>\n{\n  typedef typename Multiply<rep_element, g>::type new_coset_rep;\n  typedef contained_in_list_gf<Equality, new_coset_rep, elements> _cil;\n  constexpr static bool add_coset = !_cil::value;\n\n  typedef typename dimino_get_coset_elements<\n    Multiply,\n    sub_group_elements,\n    new_coset_rep,\n    add_coset\n  >::type coset_elements;\n\n  typedef dimino_add_cosets_for_rep<\n    Multiply,\n    Equality,\n    id,\n    sub_group_elements,\n    typename concat<elements, coset_elements>::type,\n    type_list<gs...>,\n    rep_element,\n    sub_group_size\n  > _helper;\n\n  typedef typename _helper::type type;\n  constexpr static int global_flags = _cil::global_flags | _helper::global_flags;\n\n  /* Note that we don't have to update global flags here, since\n   * we will only add these elements if they are not part of\n   * the group already. But that only happens if the coset rep\n   * is not already in the group, so the check for the coset rep\n   * will catch this.\n   */\n};\n\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename sub_group_elements,\n  typename elements\n  EIGEN_TPL_PP_SPEC_HACK_DEFC(typename, empty),\n  typename rep_element,\n  int sub_group_size\n>\nstruct dimino_add_cosets_for_rep<Multiply, Equality, id, sub_group_elements, elements, type_list<EIGEN_TPL_PP_SPEC_HACK_USE(empty)>, rep_element, sub_group_size>\n{\n  typedef elements type;\n  constexpr static int global_flags = 0;\n};\n\n/** \\internal\n  *\n  * \\class dimino_add_all_coset_spaces\n  * \\ingroup CXX11_TensorSymmetry_Module\n  *\n  * \\brief Recursive template for adding all coset spaces for a new generator\n  *\n  * This template tries to go through the list of generators (with\n  * the help of the dimino_add_cosets_for_rep template) as long as\n  * it still finds elements that are not part of the group and add\n  * the corresponding cosets.\n  *\n  * \\sa enumerate_group_elements, dimino_add_cosets_for_rep\n  */\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename sub_group_elements,\n  typename elements,\n  typename generators,\n  int sub_group_size,\n  int rep_pos,\n  bool stop_condition        // = false\n>\nstruct dimino_add_all_coset_spaces\n{\n  typedef typename get<rep_pos, elements>::type rep_element;\n  typedef dimino_add_cosets_for_rep<\n    Multiply,\n    Equality,\n    id,\n    sub_group_elements,\n    elements,\n    generators,\n    rep_element,\n    sub_group_elements::count\n  > _ac4r;\n  typedef typename _ac4r::type new_elements;\n  \n  constexpr static int new_rep_pos = rep_pos + sub_group_elements::count;\n  constexpr static bool new_stop_condition = new_rep_pos >= new_elements::count;\n\n  typedef dimino_add_all_coset_spaces<\n    Multiply,\n    Equality,\n    id,\n    sub_group_elements,\n    new_elements,\n    generators,\n    sub_group_size,\n    new_rep_pos,\n    new_stop_condition\n  > _helper;\n\n  typedef typename _helper::type type;\n  constexpr static int global_flags = _helper::global_flags | _ac4r::global_flags;\n};\n\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename sub_group_elements,\n  typename elements,\n  typename generators,\n  int sub_group_size,\n  int rep_pos\n>\nstruct dimino_add_all_coset_spaces<Multiply, Equality, id, sub_group_elements, elements, generators, sub_group_size, rep_pos, true>\n{\n  typedef elements type;\n  constexpr static int global_flags = 0;\n};\n\n/** \\internal\n  *\n  * \\class dimino_add_generator\n  * \\ingroup CXX11_TensorSymmetry_Module\n  *\n  * \\brief Enlarge the group by adding a new generator.\n  *\n  * It accepts a boolean parameter that determines if the generator is redundant,\n  * i.e. was already seen in the group. In that case, it reduces to a no-op.\n  *\n  * \\sa enumerate_group_elements, dimino_add_all_coset_spaces\n  */\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename elements,\n  typename generators_done,\n  typename current_generator,\n  bool redundant          // = false\n>\nstruct dimino_add_generator\n{\n  /* this template is only called if the generator is not redundant\n   * => all elements of the group multiplied with the new generator\n   *    are going to be new elements of the most trivial coset space\n   */\n  typedef typename apply_op_from_right<Multiply, current_generator, elements>::type multiplied_elements;\n  typedef typename concat<elements, multiplied_elements>::type new_elements;\n\n  constexpr static int rep_pos = elements::count;\n\n  typedef dimino_add_all_coset_spaces<\n    Multiply,\n    Equality,\n    id,\n    elements, // elements of previous subgroup\n    new_elements,\n    typename concat<generators_done, type_list<current_generator>>::type,\n    elements::count, // size of previous subgroup\n    rep_pos,\n    false // don't stop (because rep_pos >= new_elements::count is always false at this point)\n  > _helper;\n  typedef typename _helper::type type;\n  constexpr static int global_flags = _helper::global_flags;\n};\n\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename elements,\n  typename generators_done,\n  typename current_generator\n>\nstruct dimino_add_generator<Multiply, Equality, id, elements, generators_done, current_generator, true>\n{\n  // redundant case\n  typedef elements type;\n  constexpr static int global_flags = 0;\n};\n\n/** \\internal\n  *\n  * \\class dimino_add_remaining_generators\n  * \\ingroup CXX11_TensorSymmetry_Module\n  *\n  * \\brief Recursive template that adds all remaining generators to a group\n  *\n  * Loop through the list of generators that remain and successively\n  * add them to the group.\n  *\n  * \\sa enumerate_group_elements, dimino_add_generator\n  */\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename generators_done,\n  typename remaining_generators,\n  typename elements\n>\nstruct dimino_add_remaining_generators\n{\n  typedef typename get<0, remaining_generators>::type first_generator;\n  typedef typename skip<1, remaining_generators>::type next_generators;\n\n  typedef contained_in_list_gf<Equality, first_generator, elements> _cil;\n\n  typedef dimino_add_generator<\n    Multiply,\n    Equality,\n    id,\n    elements,\n    generators_done,\n    first_generator,\n    _cil::value\n  > _helper;\n\n  typedef typename _helper::type new_elements;\n\n  typedef dimino_add_remaining_generators<\n    Multiply,\n    Equality,\n    id,\n    typename concat<generators_done, type_list<first_generator>>::type,\n    next_generators,\n    new_elements\n  > _next_iter;\n\n  typedef typename _next_iter::type type;\n  constexpr static int global_flags =\n    _cil::global_flags |\n    _helper::global_flags |\n    _next_iter::global_flags;\n};\n\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename generators_done,\n  typename elements\n>\nstruct dimino_add_remaining_generators<Multiply, Equality, id, generators_done, type_list<>, elements>\n{\n  typedef elements type;\n  constexpr static int global_flags = 0;\n};\n\n/** \\internal\n  *\n  * \\class enumerate_group_elements_noid\n  * \\ingroup CXX11_TensorSymmetry_Module\n  *\n  * \\brief Helper template that implements group element enumeration\n  *\n  * This is a helper template that implements the actual enumeration\n  * of group elements. This has been split so that the list of\n  * generators can be cleansed of the identity element before\n  * performing the actual operation.\n  *\n  * \\sa enumerate_group_elements\n  */\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename generators,\n  int initial_global_flags = 0\n>\nstruct enumerate_group_elements_noid\n{\n  typedef dimino_first_step_elements<Multiply, Equality, id, generators> first_step;\n  typedef typename first_step::type first_step_elements;\n\n  typedef dimino_add_remaining_generators<\n    Multiply,\n    Equality,\n    id,\n    typename first_step::generators_done,\n    typename first_step::next_generators, // remaining_generators\n    typename first_step::type // first_step elements\n  > _helper;\n\n  typedef typename _helper::type type;\n  constexpr static int global_flags =\n    initial_global_flags |\n    first_step::global_flags |\n    _helper::global_flags;\n};\n\n// in case when no generators are specified\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  int initial_global_flags\n>\nstruct enumerate_group_elements_noid<Multiply, Equality, id, type_list<>, initial_global_flags>\n{\n  typedef type_list<id> type;\n  constexpr static int global_flags = initial_global_flags;\n};\n\n/** \\internal\n  *\n  * \\class enumerate_group_elements\n  * \\ingroup CXX11_TensorSymmetry_Module\n  *\n  * \\brief Enumerate all elements in a finite group\n  *\n  * This template enumerates all elements in a finite group. It accepts\n  * the following template parameters:\n  *\n  * \\tparam Multiply      The multiplication operation that multiplies two group elements\n  *                       with each other.\n  * \\tparam Equality      The equality check operation that checks if two group elements\n  *                       are equal to another.\n  * \\tparam id            The identity element\n  * \\tparam _generators   A list of (possibly redundant) generators of the group\n  */\ntemplate<\n  template<typename, typename> class Multiply,\n  template<typename, typename> class Equality,\n  typename id,\n  typename _generators\n>\nstruct enumerate_group_elements\n  : public enumerate_group_elements_noid<\n      Multiply,\n      Equality,\n      id,\n      typename strip_identities<Equality, id, _generators>::type,\n      strip_identities<Equality, id, _generators>::global_flags\n    >\n{\n};\n\n} // end namespace group_theory\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11_TENSORSYMMETRY_TEMPLATEGROUPTHEORY_H\n\n/*\n * kate: space-indent on; indent-width 2; mixedindent off; indent-mode cstyle;\n */\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/ThreadPool/Barrier.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2018 Rasmus Munk Larsen <rmlarsen@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// Barrier is an object that allows one or more threads to wait until\n// Notify has been called a specified number of times.\n\n#ifndef EIGEN_CXX11_THREADPOOL_BARRIER_H\n#define EIGEN_CXX11_THREADPOOL_BARRIER_H\n\nnamespace Eigen {\n\nclass Barrier {\n public:\n  Barrier(unsigned int count) : state_(count << 1), notified_(false) {\n    eigen_plain_assert(((count << 1) >> 1) == count);\n  }\n  ~Barrier() { eigen_plain_assert((state_ >> 1) == 0); }\n\n  void Notify() {\n    unsigned int v = state_.fetch_sub(2, std::memory_order_acq_rel) - 2;\n    if (v != 1) {\n      // Clear the lowest bit (waiter flag) and check that the original state\n      // value was not zero. If it was zero, it means that notify was called\n      // more times than the original count.\n      eigen_plain_assert(((v + 2) & ~1) != 0);\n      return;  // either count has not dropped to 0, or waiter is not waiting\n    }\n    std::unique_lock<std::mutex> l(mu_);\n    eigen_plain_assert(!notified_);\n    notified_ = true;\n    cv_.notify_all();\n  }\n\n  void Wait() {\n    unsigned int v = state_.fetch_or(1, std::memory_order_acq_rel);\n    if ((v >> 1) == 0) return;\n    std::unique_lock<std::mutex> l(mu_);\n    while (!notified_) {\n      cv_.wait(l);\n    }\n  }\n\n private:\n  std::mutex mu_;\n  std::condition_variable cv_;\n  std::atomic<unsigned int> state_;  // low bit is waiter flag\n  bool notified_;\n};\n\n// Notification is an object that allows a user to to wait for another\n// thread to signal a notification that an event has occurred.\n//\n// Multiple threads can wait on the same Notification object,\n// but only one caller must call Notify() on the object.\nstruct Notification : Barrier {\n  Notification() : Barrier(1){};\n};\n\n}  // namespace Eigen\n\n#endif  // EIGEN_CXX11_THREADPOOL_BARRIER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/ThreadPool/EventCount.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Dmitry Vyukov <dvyukov@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_THREADPOOL_EVENTCOUNT_H_\n#define EIGEN_CXX11_THREADPOOL_EVENTCOUNT_H_\n\nnamespace Eigen {\n\n// EventCount allows to wait for arbitrary predicates in non-blocking\n// algorithms. Think of condition variable, but wait predicate does not need to\n// be protected by a mutex. Usage:\n// Waiting thread does:\n//\n//   if (predicate)\n//     return act();\n//   EventCount::Waiter& w = waiters[my_index];\n//   ec.Prewait(&w);\n//   if (predicate) {\n//     ec.CancelWait(&w);\n//     return act();\n//   }\n//   ec.CommitWait(&w);\n//\n// Notifying thread does:\n//\n//   predicate = true;\n//   ec.Notify(true);\n//\n// Notify is cheap if there are no waiting threads. Prewait/CommitWait are not\n// cheap, but they are executed only if the preceding predicate check has\n// failed.\n//\n// Algorithm outline:\n// There are two main variables: predicate (managed by user) and state_.\n// Operation closely resembles Dekker mutual algorithm:\n// https://en.wikipedia.org/wiki/Dekker%27s_algorithm\n// Waiting thread sets state_ then checks predicate, Notifying thread sets\n// predicate then checks state_. Due to seq_cst fences in between these\n// operations it is guaranteed than either waiter will see predicate change\n// and won't block, or notifying thread will see state_ change and will unblock\n// the waiter, or both. But it can't happen that both threads don't see each\n// other changes, which would lead to deadlock.\nclass EventCount {\n public:\n  class Waiter;\n\n  EventCount(MaxSizeVector<Waiter>& waiters)\n      : state_(kStackMask), waiters_(waiters) {\n    eigen_plain_assert(waiters.size() < (1 << kWaiterBits) - 1);\n  }\n\n  ~EventCount() {\n    // Ensure there are no waiters.\n    eigen_plain_assert(state_.load() == kStackMask);\n  }\n\n  // Prewait prepares for waiting.\n  // After calling Prewait, the thread must re-check the wait predicate\n  // and then call either CancelWait or CommitWait.\n  void Prewait() {\n    uint64_t state = state_.load(std::memory_order_relaxed);\n    for (;;) {\n      CheckState(state);\n      uint64_t newstate = state + kWaiterInc;\n      CheckState(newstate);\n      if (state_.compare_exchange_weak(state, newstate,\n                                       std::memory_order_seq_cst))\n        return;\n    }\n  }\n\n  // CommitWait commits waiting after Prewait.\n  void CommitWait(Waiter* w) {\n    eigen_plain_assert((w->epoch & ~kEpochMask) == 0);\n    w->state = Waiter::kNotSignaled;\n    const uint64_t me = (w - &waiters_[0]) | w->epoch;\n    uint64_t state = state_.load(std::memory_order_seq_cst);\n    for (;;) {\n      CheckState(state, true);\n      uint64_t newstate;\n      if ((state & kSignalMask) != 0) {\n        // Consume the signal and return immidiately.\n        newstate = state - kWaiterInc - kSignalInc;\n      } else {\n        // Remove this thread from pre-wait counter and add to the waiter stack.\n        newstate = ((state & kWaiterMask) - kWaiterInc) | me;\n        w->next.store(state & (kStackMask | kEpochMask),\n                      std::memory_order_relaxed);\n      }\n      CheckState(newstate);\n      if (state_.compare_exchange_weak(state, newstate,\n                                       std::memory_order_acq_rel)) {\n        if ((state & kSignalMask) == 0) {\n          w->epoch += kEpochInc;\n          Park(w);\n        }\n        return;\n      }\n    }\n  }\n\n  // CancelWait cancels effects of the previous Prewait call.\n  void CancelWait() {\n    uint64_t state = state_.load(std::memory_order_relaxed);\n    for (;;) {\n      CheckState(state, true);\n      uint64_t newstate = state - kWaiterInc;\n      // We don't know if the thread was also notified or not,\n      // so we should not consume a signal unconditionaly.\n      // Only if number of waiters is equal to number of signals,\n      // we know that the thread was notified and we must take away the signal.\n      if (((state & kWaiterMask) >> kWaiterShift) ==\n          ((state & kSignalMask) >> kSignalShift))\n        newstate -= kSignalInc;\n      CheckState(newstate);\n      if (state_.compare_exchange_weak(state, newstate,\n                                       std::memory_order_acq_rel))\n        return;\n    }\n  }\n\n  // Notify wakes one or all waiting threads.\n  // Must be called after changing the associated wait predicate.\n  void Notify(bool notifyAll) {\n    std::atomic_thread_fence(std::memory_order_seq_cst);\n    uint64_t state = state_.load(std::memory_order_acquire);\n    for (;;) {\n      CheckState(state);\n      const uint64_t waiters = (state & kWaiterMask) >> kWaiterShift;\n      const uint64_t signals = (state & kSignalMask) >> kSignalShift;\n      // Easy case: no waiters.\n      if ((state & kStackMask) == kStackMask && waiters == signals) return;\n      uint64_t newstate;\n      if (notifyAll) {\n        // Empty wait stack and set signal to number of pre-wait threads.\n        newstate =\n            (state & kWaiterMask) | (waiters << kSignalShift) | kStackMask;\n      } else if (signals < waiters) {\n        // There is a thread in pre-wait state, unblock it.\n        newstate = state + kSignalInc;\n      } else {\n        // Pop a waiter from list and unpark it.\n        Waiter* w = &waiters_[state & kStackMask];\n        uint64_t next = w->next.load(std::memory_order_relaxed);\n        newstate = (state & (kWaiterMask | kSignalMask)) | next;\n      }\n      CheckState(newstate);\n      if (state_.compare_exchange_weak(state, newstate,\n                                       std::memory_order_acq_rel)) {\n        if (!notifyAll && (signals < waiters))\n          return;  // unblocked pre-wait thread\n        if ((state & kStackMask) == kStackMask) return;\n        Waiter* w = &waiters_[state & kStackMask];\n        if (!notifyAll) w->next.store(kStackMask, std::memory_order_relaxed);\n        Unpark(w);\n        return;\n      }\n    }\n  }\n\n  class Waiter {\n    friend class EventCount;\n    // Align to 128 byte boundary to prevent false sharing with other Waiter\n    // objects in the same vector.\n    EIGEN_ALIGN_TO_BOUNDARY(128) std::atomic<uint64_t> next;\n    std::mutex mu;\n    std::condition_variable cv;\n    uint64_t epoch = 0;\n    unsigned state = kNotSignaled;\n    enum {\n      kNotSignaled,\n      kWaiting,\n      kSignaled,\n    };\n  };\n\n private:\n  // State_ layout:\n  // - low kWaiterBits is a stack of waiters committed wait\n  //   (indexes in waiters_ array are used as stack elements,\n  //   kStackMask means empty stack).\n  // - next kWaiterBits is count of waiters in prewait state.\n  // - next kWaiterBits is count of pending signals.\n  // - remaining bits are ABA counter for the stack.\n  //   (stored in Waiter node and incremented on push).\n  static const uint64_t kWaiterBits = 14;\n  static const uint64_t kStackMask = (1ull << kWaiterBits) - 1;\n  static const uint64_t kWaiterShift = kWaiterBits;\n  static const uint64_t kWaiterMask = ((1ull << kWaiterBits) - 1)\n                                      << kWaiterShift;\n  static const uint64_t kWaiterInc = 1ull << kWaiterShift;\n  static const uint64_t kSignalShift = 2 * kWaiterBits;\n  static const uint64_t kSignalMask = ((1ull << kWaiterBits) - 1)\n                                      << kSignalShift;\n  static const uint64_t kSignalInc = 1ull << kSignalShift;\n  static const uint64_t kEpochShift = 3 * kWaiterBits;\n  static const uint64_t kEpochBits = 64 - kEpochShift;\n  static const uint64_t kEpochMask = ((1ull << kEpochBits) - 1) << kEpochShift;\n  static const uint64_t kEpochInc = 1ull << kEpochShift;\n  std::atomic<uint64_t> state_;\n  MaxSizeVector<Waiter>& waiters_;\n\n  static void CheckState(uint64_t state, bool waiter = false) {\n    static_assert(kEpochBits >= 20, \"not enough bits to prevent ABA problem\");\n    const uint64_t waiters = (state & kWaiterMask) >> kWaiterShift;\n    const uint64_t signals = (state & kSignalMask) >> kSignalShift;\n    eigen_plain_assert(waiters >= signals);\n    eigen_plain_assert(waiters < (1 << kWaiterBits) - 1);\n    eigen_plain_assert(!waiter || waiters > 0);\n    (void)waiters;\n    (void)signals;\n  }\n\n  void Park(Waiter* w) {\n    std::unique_lock<std::mutex> lock(w->mu);\n    while (w->state != Waiter::kSignaled) {\n      w->state = Waiter::kWaiting;\n      w->cv.wait(lock);\n    }\n  }\n\n  void Unpark(Waiter* w) {\n    for (Waiter* next; w; w = next) {\n      uint64_t wnext = w->next.load(std::memory_order_relaxed) & kStackMask;\n      next = wnext == kStackMask ? nullptr : &waiters_[wnext];\n      unsigned state;\n      {\n        std::unique_lock<std::mutex> lock(w->mu);\n        state = w->state;\n        w->state = Waiter::kSignaled;\n      }\n      // Avoid notifying if it wasn't waiting.\n      if (state == Waiter::kWaiting) w->cv.notify_one();\n    }\n  }\n\n  EventCount(const EventCount&) = delete;\n  void operator=(const EventCount&) = delete;\n};\n\n}  // namespace Eigen\n\n#endif  // EIGEN_CXX11_THREADPOOL_EVENTCOUNT_H_\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/ThreadPool/NonBlockingThreadPool.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Dmitry Vyukov <dvyukov@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_THREADPOOL_NONBLOCKING_THREAD_POOL_H\n#define EIGEN_CXX11_THREADPOOL_NONBLOCKING_THREAD_POOL_H\n\nnamespace Eigen {\n\ntemplate <typename Environment>\nclass ThreadPoolTempl : public Eigen::ThreadPoolInterface {\n public:\n  typedef typename Environment::Task Task;\n  typedef RunQueue<Task, 1024> Queue;\n\n  ThreadPoolTempl(int num_threads, Environment env = Environment())\n      : ThreadPoolTempl(num_threads, true, env) {}\n\n  ThreadPoolTempl(int num_threads, bool allow_spinning,\n                  Environment env = Environment())\n      : env_(env),\n        num_threads_(num_threads),\n        allow_spinning_(allow_spinning),\n        thread_data_(num_threads),\n        all_coprimes_(num_threads),\n        waiters_(num_threads),\n        global_steal_partition_(EncodePartition(0, num_threads_)),\n        blocked_(0),\n        spinning_(0),\n        done_(false),\n        cancelled_(false),\n        ec_(waiters_) {\n    waiters_.resize(num_threads_);\n    // Calculate coprimes of all numbers [1, num_threads].\n    // Coprimes are used for random walks over all threads in Steal\n    // and NonEmptyQueueIndex. Iteration is based on the fact that if we take\n    // a random starting thread index t and calculate num_threads - 1 subsequent\n    // indices as (t + coprime) % num_threads, we will cover all threads without\n    // repetitions (effectively getting a presudo-random permutation of thread\n    // indices).\n    eigen_plain_assert(num_threads_ < kMaxThreads);\n    for (int i = 1; i <= num_threads_; ++i) {\n      all_coprimes_.emplace_back(i);\n      ComputeCoprimes(i, &all_coprimes_.back());\n    }\n#ifndef EIGEN_THREAD_LOCAL\n    init_barrier_.reset(new Barrier(num_threads_));\n#endif\n    thread_data_.resize(num_threads_);\n    for (int i = 0; i < num_threads_; i++) {\n      SetStealPartition(i, EncodePartition(0, num_threads_));\n      thread_data_[i].thread.reset(\n          env_.CreateThread([this, i]() { WorkerLoop(i); }));\n    }\n#ifndef EIGEN_THREAD_LOCAL\n    // Wait for workers to initialize per_thread_map_. Otherwise we might race\n    // with them in Schedule or CurrentThreadId.\n    init_barrier_->Wait();\n#endif\n  }\n\n  ~ThreadPoolTempl() {\n    done_ = true;\n\n    // Now if all threads block without work, they will start exiting.\n    // But note that threads can continue to work arbitrary long,\n    // block, submit new work, unblock and otherwise live full life.\n    if (!cancelled_) {\n      ec_.Notify(true);\n    } else {\n      // Since we were cancelled, there might be entries in the queues.\n      // Empty them to prevent their destructor from asserting.\n      for (size_t i = 0; i < thread_data_.size(); i++) {\n        thread_data_[i].queue.Flush();\n      }\n    }\n    // Join threads explicitly (by destroying) to avoid destruction order within\n    // this class.\n    for (size_t i = 0; i < thread_data_.size(); ++i)\n      thread_data_[i].thread.reset();\n  }\n\n  void SetStealPartitions(const std::vector<std::pair<unsigned, unsigned>>& partitions) {\n    eigen_plain_assert(partitions.size() == static_cast<std::size_t>(num_threads_));\n\n    // Pass this information to each thread queue.\n    for (int i = 0; i < num_threads_; i++) {\n      const auto& pair = partitions[i];\n      unsigned start = pair.first, end = pair.second;\n      AssertBounds(start, end);\n      unsigned val = EncodePartition(start, end);\n      SetStealPartition(i, val);\n    }\n  }\n\n  void Schedule(std::function<void()> fn) EIGEN_OVERRIDE {\n    ScheduleWithHint(std::move(fn), 0, num_threads_);\n  }\n\n  void ScheduleWithHint(std::function<void()> fn, int start,\n                        int limit) override {\n    Task t = env_.CreateTask(std::move(fn));\n    PerThread* pt = GetPerThread();\n    if (pt->pool == this) {\n      // Worker thread of this pool, push onto the thread's queue.\n      Queue& q = thread_data_[pt->thread_id].queue;\n      t = q.PushFront(std::move(t));\n    } else {\n      // A free-standing thread (or worker of another pool), push onto a random\n      // queue.\n      eigen_plain_assert(start < limit);\n      eigen_plain_assert(limit <= num_threads_);\n      int num_queues = limit - start;\n      int rnd = Rand(&pt->rand) % num_queues;\n      eigen_plain_assert(start + rnd < limit);\n      Queue& q = thread_data_[start + rnd].queue;\n      t = q.PushBack(std::move(t));\n    }\n    // Note: below we touch this after making w available to worker threads.\n    // Strictly speaking, this can lead to a racy-use-after-free. Consider that\n    // Schedule is called from a thread that is neither main thread nor a worker\n    // thread of this pool. Then, execution of w directly or indirectly\n    // completes overall computations, which in turn leads to destruction of\n    // this. We expect that such scenario is prevented by program, that is,\n    // this is kept alive while any threads can potentially be in Schedule.\n    if (!t.f) {\n      ec_.Notify(false);\n    } else {\n      env_.ExecuteTask(t);  // Push failed, execute directly.\n    }\n  }\n\n  void Cancel() EIGEN_OVERRIDE {\n    cancelled_ = true;\n    done_ = true;\n\n    // Let each thread know it's been cancelled.\n#ifdef EIGEN_THREAD_ENV_SUPPORTS_CANCELLATION\n    for (size_t i = 0; i < thread_data_.size(); i++) {\n      thread_data_[i].thread->OnCancel();\n    }\n#endif\n\n    // Wake up the threads without work to let them exit on their own.\n    ec_.Notify(true);\n  }\n\n  int NumThreads() const EIGEN_FINAL { return num_threads_; }\n\n  int CurrentThreadId() const EIGEN_FINAL {\n    const PerThread* pt = const_cast<ThreadPoolTempl*>(this)->GetPerThread();\n    if (pt->pool == this) {\n      return pt->thread_id;\n    } else {\n      return -1;\n    }\n  }\n\n private:\n  // Create a single atomic<int> that encodes start and limit information for\n  // each thread.\n  // We expect num_threads_ < 65536, so we can store them in a single\n  // std::atomic<unsigned>.\n  // Exposed publicly as static functions so that external callers can reuse\n  // this encode/decode logic for maintaining their own thread-safe copies of\n  // scheduling and steal domain(s).\n  static const int kMaxPartitionBits = 16;\n  static const int kMaxThreads = 1 << kMaxPartitionBits;\n\n  inline unsigned EncodePartition(unsigned start, unsigned limit) {\n    return (start << kMaxPartitionBits) | limit;\n  }\n\n  inline void DecodePartition(unsigned val, unsigned* start, unsigned* limit) {\n    *limit = val & (kMaxThreads - 1);\n    val >>= kMaxPartitionBits;\n    *start = val;\n  }\n\n  void AssertBounds(int start, int end) {\n    eigen_plain_assert(start >= 0);\n    eigen_plain_assert(start < end);  // non-zero sized partition\n    eigen_plain_assert(end <= num_threads_);\n  }\n\n  inline void SetStealPartition(size_t i, unsigned val) {\n    thread_data_[i].steal_partition.store(val, std::memory_order_relaxed);\n  }\n\n  inline unsigned GetStealPartition(int i) {\n    return thread_data_[i].steal_partition.load(std::memory_order_relaxed);\n  }\n\n  void ComputeCoprimes(int N, MaxSizeVector<unsigned>* coprimes) {\n    for (int i = 1; i <= N; i++) {\n      unsigned a = i;\n      unsigned b = N;\n      // If GCD(a, b) == 1, then a and b are coprimes.\n      while (b != 0) {\n        unsigned tmp = a;\n        a = b;\n        b = tmp % b;\n      }\n      if (a == 1) {\n        coprimes->push_back(i);\n      }\n    }\n  }\n\n  typedef typename Environment::EnvThread Thread;\n\n  struct PerThread {\n    constexpr PerThread() : pool(NULL), rand(0), thread_id(-1) {}\n    ThreadPoolTempl* pool;  // Parent pool, or null for normal threads.\n    uint64_t rand;          // Random generator state.\n    int thread_id;          // Worker thread index in pool.\n#ifndef EIGEN_THREAD_LOCAL\n    // Prevent false sharing.\n    char pad_[128];\n#endif\n  };\n\n  struct ThreadData {\n    constexpr ThreadData() : thread(), steal_partition(0), queue() {}\n    std::unique_ptr<Thread> thread;\n    std::atomic<unsigned> steal_partition;\n    Queue queue;\n  };\n\n  Environment env_;\n  const int num_threads_;\n  const bool allow_spinning_;\n  MaxSizeVector<ThreadData> thread_data_;\n  MaxSizeVector<MaxSizeVector<unsigned>> all_coprimes_;\n  MaxSizeVector<EventCount::Waiter> waiters_;\n  unsigned global_steal_partition_;\n  std::atomic<unsigned> blocked_;\n  std::atomic<bool> spinning_;\n  std::atomic<bool> done_;\n  std::atomic<bool> cancelled_;\n  EventCount ec_;\n#ifndef EIGEN_THREAD_LOCAL\n  std::unique_ptr<Barrier> init_barrier_;\n  std::mutex per_thread_map_mutex_;  // Protects per_thread_map_.\n  std::unordered_map<uint64_t, std::unique_ptr<PerThread>> per_thread_map_;\n#endif\n\n  // Main worker thread loop.\n  void WorkerLoop(int thread_id) {\n#ifndef EIGEN_THREAD_LOCAL\n    std::unique_ptr<PerThread> new_pt(new PerThread());\n    per_thread_map_mutex_.lock();\n    bool insertOK = per_thread_map_.emplace(GlobalThreadIdHash(), std::move(new_pt)).second;\n    eigen_plain_assert(insertOK);\n    EIGEN_UNUSED_VARIABLE(insertOK);\n    per_thread_map_mutex_.unlock();\n    init_barrier_->Notify();\n    init_barrier_->Wait();\n#endif\n    PerThread* pt = GetPerThread();\n    pt->pool = this;\n    pt->rand = GlobalThreadIdHash();\n    pt->thread_id = thread_id;\n    Queue& q = thread_data_[thread_id].queue;\n    EventCount::Waiter* waiter = &waiters_[thread_id];\n    // TODO(dvyukov,rmlarsen): The time spent in NonEmptyQueueIndex() is\n    // proportional to num_threads_ and we assume that new work is scheduled at\n    // a constant rate, so we set spin_count to 5000 / num_threads_. The\n    // constant was picked based on a fair dice roll, tune it.\n    const int spin_count =\n        allow_spinning_ && num_threads_ > 0 ? 5000 / num_threads_ : 0;\n    if (num_threads_ == 1) {\n      // For num_threads_ == 1 there is no point in going through the expensive\n      // steal loop. Moreover, since NonEmptyQueueIndex() calls PopBack() on the\n      // victim queues it might reverse the order in which ops are executed\n      // compared to the order in which they are scheduled, which tends to be\n      // counter-productive for the types of I/O workloads the single thread\n      // pools tend to be used for.\n      while (!cancelled_) {\n        Task t = q.PopFront();\n        for (int i = 0; i < spin_count && !t.f; i++) {\n          if (!cancelled_.load(std::memory_order_relaxed)) {\n            t = q.PopFront();\n          }\n        }\n        if (!t.f) {\n          if (!WaitForWork(waiter, &t)) {\n            return;\n          }\n        }\n        if (t.f) {\n          env_.ExecuteTask(t);\n        }\n      }\n    } else {\n      while (!cancelled_) {\n        Task t = q.PopFront();\n        if (!t.f) {\n          t = LocalSteal();\n          if (!t.f) {\n            t = GlobalSteal();\n            if (!t.f) {\n              // Leave one thread spinning. This reduces latency.\n              if (allow_spinning_ && !spinning_ && !spinning_.exchange(true)) {\n                for (int i = 0; i < spin_count && !t.f; i++) {\n                  if (!cancelled_.load(std::memory_order_relaxed)) {\n                    t = GlobalSteal();\n                  } else {\n                    return;\n                  }\n                }\n                spinning_ = false;\n              }\n              if (!t.f) {\n                if (!WaitForWork(waiter, &t)) {\n                  return;\n                }\n              }\n            }\n          }\n        }\n        if (t.f) {\n          env_.ExecuteTask(t);\n        }\n      }\n    }\n  }\n\n  // Steal tries to steal work from other worker threads in the range [start,\n  // limit) in best-effort manner.\n  Task Steal(unsigned start, unsigned limit) {\n    PerThread* pt = GetPerThread();\n    const size_t size = limit - start;\n    unsigned r = Rand(&pt->rand);\n    // Reduce r into [0, size) range, this utilizes trick from\n    // https://lemire.me/blog/2016/06/27/a-fast-alternative-to-the-modulo-reduction/\n    eigen_plain_assert(all_coprimes_[size - 1].size() < (1<<30));\n    unsigned victim = ((uint64_t)r * (uint64_t)size) >> 32;\n    unsigned index = ((uint64_t) all_coprimes_[size - 1].size() * (uint64_t)r) >> 32;\n    unsigned inc = all_coprimes_[size - 1][index];\n\n    for (unsigned i = 0; i < size; i++) {\n      eigen_plain_assert(start + victim < limit);\n      Task t = thread_data_[start + victim].queue.PopBack();\n      if (t.f) {\n        return t;\n      }\n      victim += inc;\n      if (victim >= size) {\n        victim -= size;\n      }\n    }\n    return Task();\n  }\n\n  // Steals work within threads belonging to the partition.\n  Task LocalSteal() {\n    PerThread* pt = GetPerThread();\n    unsigned partition = GetStealPartition(pt->thread_id);\n    // If thread steal partition is the same as global partition, there is no\n    // need to go through the steal loop twice.\n    if (global_steal_partition_ == partition) return Task();\n    unsigned start, limit;\n    DecodePartition(partition, &start, &limit);\n    AssertBounds(start, limit);\n\n    return Steal(start, limit);\n  }\n\n  // Steals work from any other thread in the pool.\n  Task GlobalSteal() {\n    return Steal(0, num_threads_);\n  }\n\n\n  // WaitForWork blocks until new work is available (returns true), or if it is\n  // time to exit (returns false). Can optionally return a task to execute in t\n  // (in such case t.f != nullptr on return).\n  bool WaitForWork(EventCount::Waiter* waiter, Task* t) {\n    eigen_plain_assert(!t->f);\n    // We already did best-effort emptiness check in Steal, so prepare for\n    // blocking.\n    ec_.Prewait();\n    // Now do a reliable emptiness check.\n    int victim = NonEmptyQueueIndex();\n    if (victim != -1) {\n      ec_.CancelWait();\n      if (cancelled_) {\n        return false;\n      } else {\n        *t = thread_data_[victim].queue.PopBack();\n        return true;\n      }\n    }\n    // Number of blocked threads is used as termination condition.\n    // If we are shutting down and all worker threads blocked without work,\n    // that's we are done.\n    blocked_++;\n    // TODO is blocked_ required to be unsigned?\n    if (done_ && blocked_ == static_cast<unsigned>(num_threads_)) {\n      ec_.CancelWait();\n      // Almost done, but need to re-check queues.\n      // Consider that all queues are empty and all worker threads are preempted\n      // right after incrementing blocked_ above. Now a free-standing thread\n      // submits work and calls destructor (which sets done_). If we don't\n      // re-check queues, we will exit leaving the work unexecuted.\n      if (NonEmptyQueueIndex() != -1) {\n        // Note: we must not pop from queues before we decrement blocked_,\n        // otherwise the following scenario is possible. Consider that instead\n        // of checking for emptiness we popped the only element from queues.\n        // Now other worker threads can start exiting, which is bad if the\n        // work item submits other work. So we just check emptiness here,\n        // which ensures that all worker threads exit at the same time.\n        blocked_--;\n        return true;\n      }\n      // Reached stable termination state.\n      ec_.Notify(true);\n      return false;\n    }\n    ec_.CommitWait(waiter);\n    blocked_--;\n    return true;\n  }\n\n  int NonEmptyQueueIndex() {\n    PerThread* pt = GetPerThread();\n    // We intentionally design NonEmptyQueueIndex to steal work from\n    // anywhere in the queue so threads don't block in WaitForWork() forever\n    // when all threads in their partition go to sleep. Steal is still local.\n    const size_t size = thread_data_.size();\n    unsigned r = Rand(&pt->rand);\n    unsigned inc = all_coprimes_[size - 1][r % all_coprimes_[size - 1].size()];\n    unsigned victim = r % size;\n    for (unsigned i = 0; i < size; i++) {\n      if (!thread_data_[victim].queue.Empty()) {\n        return victim;\n      }\n      victim += inc;\n      if (victim >= size) {\n        victim -= size;\n      }\n    }\n    return -1;\n  }\n\n  static EIGEN_STRONG_INLINE uint64_t GlobalThreadIdHash() {\n    return std::hash<std::thread::id>()(std::this_thread::get_id());\n  }\n\n  EIGEN_STRONG_INLINE PerThread* GetPerThread() {\n#ifndef EIGEN_THREAD_LOCAL\n    static PerThread dummy;\n    auto it = per_thread_map_.find(GlobalThreadIdHash());\n    if (it == per_thread_map_.end()) {\n      return &dummy;\n    } else {\n      return it->second.get();\n    }\n#else\n    EIGEN_THREAD_LOCAL PerThread per_thread_;\n    PerThread* pt = &per_thread_;\n    return pt;\n#endif\n  }\n\n  static EIGEN_STRONG_INLINE unsigned Rand(uint64_t* state) {\n    uint64_t current = *state;\n    // Update the internal state\n    *state = current * 6364136223846793005ULL + 0xda3e39cb94b95bdbULL;\n    // Generate the random output (using the PCG-XSH-RS scheme)\n    return static_cast<unsigned>((current ^ (current >> 22)) >>\n                                 (22 + (current >> 61)));\n  }\n};\n\ntypedef ThreadPoolTempl<StlThreadEnvironment> ThreadPool;\n\n}  // namespace Eigen\n\n#endif  // EIGEN_CXX11_THREADPOOL_NONBLOCKING_THREAD_POOL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/ThreadPool/RunQueue.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Dmitry Vyukov <dvyukov@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_THREADPOOL_RUNQUEUE_H_\n#define EIGEN_CXX11_THREADPOOL_RUNQUEUE_H_\n\nnamespace Eigen {\n\n// RunQueue is a fixed-size, partially non-blocking deque or Work items.\n// Operations on front of the queue must be done by a single thread (owner),\n// operations on back of the queue can be done by multiple threads concurrently.\n//\n// Algorithm outline:\n// All remote threads operating on the queue back are serialized by a mutex.\n// This ensures that at most two threads access state: owner and one remote\n// thread (Size aside). The algorithm ensures that the occupied region of the\n// underlying array is logically continuous (can wraparound, but no stray\n// occupied elements). Owner operates on one end of this region, remote thread\n// operates on the other end. Synchronization between these threads\n// (potential consumption of the last element and take up of the last empty\n// element) happens by means of state variable in each element. States are:\n// empty, busy (in process of insertion of removal) and ready. Threads claim\n// elements (empty->busy and ready->busy transitions) by means of a CAS\n// operation. The finishing transition (busy->empty and busy->ready) are done\n// with plain store as the element is exclusively owned by the current thread.\n//\n// Note: we could permit only pointers as elements, then we would not need\n// separate state variable as null/non-null pointer value would serve as state,\n// but that would require malloc/free per operation for large, complex values\n// (and this is designed to store std::function<()>).\ntemplate <typename Work, unsigned kSize>\nclass RunQueue {\n public:\n  RunQueue() : front_(0), back_(0) {\n    // require power-of-two for fast masking\n    eigen_plain_assert((kSize & (kSize - 1)) == 0);\n    eigen_plain_assert(kSize > 2);            // why would you do this?\n    eigen_plain_assert(kSize <= (64 << 10));  // leave enough space for counter\n    for (unsigned i = 0; i < kSize; i++)\n      array_[i].state.store(kEmpty, std::memory_order_relaxed);\n  }\n\n  ~RunQueue() { eigen_plain_assert(Size() == 0); }\n\n  // PushFront inserts w at the beginning of the queue.\n  // If queue is full returns w, otherwise returns default-constructed Work.\n  Work PushFront(Work w) {\n    unsigned front = front_.load(std::memory_order_relaxed);\n    Elem* e = &array_[front & kMask];\n    uint8_t s = e->state.load(std::memory_order_relaxed);\n    if (s != kEmpty ||\n        !e->state.compare_exchange_strong(s, kBusy, std::memory_order_acquire))\n      return w;\n    front_.store(front + 1 + (kSize << 1), std::memory_order_relaxed);\n    e->w = std::move(w);\n    e->state.store(kReady, std::memory_order_release);\n    return Work();\n  }\n\n  // PopFront removes and returns the first element in the queue.\n  // If the queue was empty returns default-constructed Work.\n  Work PopFront() {\n    unsigned front = front_.load(std::memory_order_relaxed);\n    Elem* e = &array_[(front - 1) & kMask];\n    uint8_t s = e->state.load(std::memory_order_relaxed);\n    if (s != kReady ||\n        !e->state.compare_exchange_strong(s, kBusy, std::memory_order_acquire))\n      return Work();\n    Work w = std::move(e->w);\n    e->state.store(kEmpty, std::memory_order_release);\n    front = ((front - 1) & kMask2) | (front & ~kMask2);\n    front_.store(front, std::memory_order_relaxed);\n    return w;\n  }\n\n  // PushBack adds w at the end of the queue.\n  // If queue is full returns w, otherwise returns default-constructed Work.\n  Work PushBack(Work w) {\n    std::unique_lock<std::mutex> lock(mutex_);\n    unsigned back = back_.load(std::memory_order_relaxed);\n    Elem* e = &array_[(back - 1) & kMask];\n    uint8_t s = e->state.load(std::memory_order_relaxed);\n    if (s != kEmpty ||\n        !e->state.compare_exchange_strong(s, kBusy, std::memory_order_acquire))\n      return w;\n    back = ((back - 1) & kMask2) | (back & ~kMask2);\n    back_.store(back, std::memory_order_relaxed);\n    e->w = std::move(w);\n    e->state.store(kReady, std::memory_order_release);\n    return Work();\n  }\n\n  // PopBack removes and returns the last elements in the queue.\n  Work PopBack() {\n    if (Empty()) return Work();\n    std::unique_lock<std::mutex> lock(mutex_);\n    unsigned back = back_.load(std::memory_order_relaxed);\n    Elem* e = &array_[back & kMask];\n    uint8_t s = e->state.load(std::memory_order_relaxed);\n    if (s != kReady ||\n        !e->state.compare_exchange_strong(s, kBusy, std::memory_order_acquire))\n      return Work();\n    Work w = std::move(e->w);\n    e->state.store(kEmpty, std::memory_order_release);\n    back_.store(back + 1 + (kSize << 1), std::memory_order_relaxed);\n    return w;\n  }\n\n  // PopBackHalf removes and returns half last elements in the queue.\n  // Returns number of elements removed.\n  unsigned PopBackHalf(std::vector<Work>* result) {\n    if (Empty()) return 0;\n    std::unique_lock<std::mutex> lock(mutex_);\n    unsigned back = back_.load(std::memory_order_relaxed);\n    unsigned size = Size();\n    unsigned mid = back;\n    if (size > 1) mid = back + (size - 1) / 2;\n    unsigned n = 0;\n    unsigned start = 0;\n    for (; static_cast<int>(mid - back) >= 0; mid--) {\n      Elem* e = &array_[mid & kMask];\n      uint8_t s = e->state.load(std::memory_order_relaxed);\n      if (n == 0) {\n        if (s != kReady || !e->state.compare_exchange_strong(\n                               s, kBusy, std::memory_order_acquire))\n          continue;\n        start = mid;\n      } else {\n        // Note: no need to store temporal kBusy, we exclusively own these\n        // elements.\n        eigen_plain_assert(s == kReady);\n      }\n      result->push_back(std::move(e->w));\n      e->state.store(kEmpty, std::memory_order_release);\n      n++;\n    }\n    if (n != 0)\n      back_.store(start + 1 + (kSize << 1), std::memory_order_relaxed);\n    return n;\n  }\n\n  // Size returns current queue size.\n  // Can be called by any thread at any time.\n  unsigned Size() const { return SizeOrNotEmpty<true>(); }\n\n  // Empty tests whether container is empty.\n  // Can be called by any thread at any time.\n  bool Empty() const { return SizeOrNotEmpty<false>() == 0; }\n\n  // Delete all the elements from the queue.\n  void Flush() {\n    while (!Empty()) {\n      PopFront();\n    }\n  }\n\n private:\n  static const unsigned kMask = kSize - 1;\n  static const unsigned kMask2 = (kSize << 1) - 1;\n  struct Elem {\n    std::atomic<uint8_t> state;\n    Work w;\n  };\n  enum {\n    kEmpty,\n    kBusy,\n    kReady,\n  };\n  std::mutex mutex_;\n  // Low log(kSize) + 1 bits in front_ and back_ contain rolling index of\n  // front/back, respectively. The remaining bits contain modification counters\n  // that are incremented on Push operations. This allows us to (1) distinguish\n  // between empty and full conditions (if we would use log(kSize) bits for\n  // position, these conditions would be indistinguishable); (2) obtain\n  // consistent snapshot of front_/back_ for Size operation using the\n  // modification counters.\n  std::atomic<unsigned> front_;\n  std::atomic<unsigned> back_;\n  Elem array_[kSize];\n\n  // SizeOrNotEmpty returns current queue size; if NeedSizeEstimate is false,\n  // only whether the size is 0 is guaranteed to be correct.\n  // Can be called by any thread at any time.\n  template<bool NeedSizeEstimate>\n  unsigned SizeOrNotEmpty() const {\n    // Emptiness plays critical role in thread pool blocking. So we go to great\n    // effort to not produce false positives (claim non-empty queue as empty).\n    unsigned front = front_.load(std::memory_order_acquire);\n    for (;;) {\n      // Capture a consistent snapshot of front/tail.\n      unsigned back = back_.load(std::memory_order_acquire);\n      unsigned front1 = front_.load(std::memory_order_relaxed);\n      if (front != front1) {\n        front = front1;\n        std::atomic_thread_fence(std::memory_order_acquire);\n        continue;\n      }\n      if (NeedSizeEstimate) {\n        return CalculateSize(front, back);\n      } else {\n        // This value will be 0 if the queue is empty, and undefined otherwise.\n        unsigned maybe_zero = ((front ^ back) & kMask2);\n        // Queue size estimate must agree with maybe zero check on the queue\n        // empty/non-empty state.\n        eigen_assert((CalculateSize(front, back) == 0) == (maybe_zero == 0));\n        return maybe_zero;\n      }\n    }\n  }\n\n  EIGEN_ALWAYS_INLINE\n  unsigned CalculateSize(unsigned front, unsigned back) const {\n    int size = (front & kMask2) - (back & kMask2);\n    // Fix overflow.\n    if (size < 0) size += 2 * kSize;\n    // Order of modification in push/pop is crafted to make the queue look\n    // larger than it is during concurrent modifications. E.g. push can\n    // increment size before the corresponding pop has decremented it.\n    // So the computed size can be up to kSize + 1, fix it.\n    if (size > static_cast<int>(kSize)) size = kSize;\n    return static_cast<unsigned>(size);\n  }\n\n  RunQueue(const RunQueue&) = delete;\n  void operator=(const RunQueue&) = delete;\n};\n\n}  // namespace Eigen\n\n#endif  // EIGEN_CXX11_THREADPOOL_RUNQUEUE_H_\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/ThreadPool/ThreadCancel.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_THREADPOOL_THREAD_CANCEL_H\n#define EIGEN_CXX11_THREADPOOL_THREAD_CANCEL_H\n\n// Try to come up with a portable way to cancel a thread\n#if EIGEN_OS_GNULINUX\n  #define EIGEN_THREAD_CANCEL(t)                  \\\n    pthread_cancel(t.native_handle());\n  #define EIGEN_SUPPORTS_THREAD_CANCELLATION 1\n#else\n#define EIGEN_THREAD_CANCEL(t)\n#endif\n\n\n#endif  // EIGEN_CXX11_THREADPOOL_THREAD_CANCEL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/ThreadPool/ThreadEnvironment.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_THREADPOOL_THREAD_ENVIRONMENT_H\n#define EIGEN_CXX11_THREADPOOL_THREAD_ENVIRONMENT_H\n\nnamespace Eigen {\n\nstruct StlThreadEnvironment {\n  struct Task {\n    std::function<void()> f;\n  };\n\n  // EnvThread constructor must start the thread,\n  // destructor must join the thread.\n  class EnvThread {\n   public:\n    EnvThread(std::function<void()> f) : thr_(std::move(f)) {}\n    ~EnvThread() { thr_.join(); }\n    // This function is called when the threadpool is cancelled.\n    void OnCancel() { }\n\n   private:\n    std::thread thr_;\n  };\n\n  EnvThread* CreateThread(std::function<void()> f) { return new EnvThread(std::move(f)); }\n  Task CreateTask(std::function<void()> f) { return Task{std::move(f)}; }\n  void ExecuteTask(const Task& t) { t.f(); }\n};\n\n}  // namespace Eigen\n\n#endif  // EIGEN_CXX11_THREADPOOL_THREAD_ENVIRONMENT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/ThreadPool/ThreadLocal.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_THREADPOOL_THREAD_LOCAL_H\n#define EIGEN_CXX11_THREADPOOL_THREAD_LOCAL_H\n\n#ifdef EIGEN_AVOID_THREAD_LOCAL\n\n#ifdef EIGEN_THREAD_LOCAL\n#undef EIGEN_THREAD_LOCAL\n#endif\n\n#else\n\n#if EIGEN_MAX_CPP_VER >= 11 &&                         \\\n    ((EIGEN_COMP_GNUC && EIGEN_GNUC_AT_LEAST(4, 8)) || \\\n     __has_feature(cxx_thread_local)                || \\\n     (EIGEN_COMP_MSVC >= 1900) )\n#define EIGEN_THREAD_LOCAL static thread_local\n#endif\n\n// Disable TLS for Apple and Android builds with older toolchains.\n#if defined(__APPLE__)\n// Included for TARGET_OS_IPHONE, __IPHONE_OS_VERSION_MIN_REQUIRED,\n// __IPHONE_8_0.\n#include <Availability.h>\n#include <TargetConditionals.h>\n#endif\n// Checks whether C++11's `thread_local` storage duration specifier is\n// supported.\n#if defined(__apple_build_version__) &&     \\\n    ((__apple_build_version__ < 8000042) || \\\n     (TARGET_OS_IPHONE && __IPHONE_OS_VERSION_MIN_REQUIRED < __IPHONE_9_0))\n// Notes: Xcode's clang did not support `thread_local` until version\n// 8, and even then not for all iOS < 9.0.\n#undef EIGEN_THREAD_LOCAL\n\n#elif defined(__ANDROID__) && EIGEN_COMP_CLANG\n// There are platforms for which TLS should not be used even though the compiler\n// makes it seem like it's supported (Android NDK < r12b for example).\n// This is primarily because of linker problems and toolchain misconfiguration:\n// TLS isn't supported until NDK r12b per\n// https://developer.android.com/ndk/downloads/revision_history.html\n// Since NDK r16, `__NDK_MAJOR__` and `__NDK_MINOR__` are defined in\n// <android/ndk-version.h>. For NDK < r16, users should define these macros,\n// e.g. `-D__NDK_MAJOR__=11 -D__NKD_MINOR__=0` for NDK r11.\n#if __has_include(<android/ndk-version.h>)\n#include <android/ndk-version.h>\n#endif  // __has_include(<android/ndk-version.h>)\n#if defined(__ANDROID__) && defined(__clang__) && defined(__NDK_MAJOR__) && \\\n    defined(__NDK_MINOR__) &&                                               \\\n    ((__NDK_MAJOR__ < 12) || ((__NDK_MAJOR__ == 12) && (__NDK_MINOR__ < 1)))\n#undef EIGEN_THREAD_LOCAL\n#endif\n#endif  // defined(__ANDROID__) && defined(__clang__)\n\n#endif  // EIGEN_AVOID_THREAD_LOCAL\n\nnamespace Eigen {\n\nnamespace internal {\ntemplate <typename T>\nstruct ThreadLocalNoOpInitialize {\n  void operator()(T&) const {}\n};\n\ntemplate <typename T>\nstruct ThreadLocalNoOpRelease {\n  void operator()(T&) const {}\n};\n\n}  // namespace internal\n\n// Thread local container for elements of type T, that does not use thread local\n// storage. As long as the number of unique threads accessing this storage\n// is smaller than `capacity_`, it is lock-free and wait-free. Otherwise it will\n// use a mutex for synchronization.\n//\n// Type `T` has to be default constructible, and by default each thread will get\n// a default constructed value. It is possible to specify custom `initialize`\n// callable, that will be called lazily from each thread accessing this object,\n// and will be passed a default initialized object of type `T`. Also it's\n// possible to pass a custom `release` callable, that will be invoked before\n// calling ~T().\n//\n// Example:\n//\n//   struct Counter {\n//     int value = 0;\n//   }\n//\n//   Eigen::ThreadLocal<Counter> counter(10);\n//\n//   // Each thread will have access to it's own counter object.\n//   Counter& cnt = counter.local();\n//   cnt++;\n//\n// WARNING: Eigen::ThreadLocal uses the OS-specific value returned by\n// std::this_thread::get_id() to identify threads. This value is not guaranteed\n// to be unique except for the life of the thread. A newly created thread may\n// get an OS-specific ID equal to that of an already destroyed thread.\n//\n// Somewhat similar to TBB thread local storage, with similar restrictions:\n// https://www.threadingbuildingblocks.org/docs/help/reference/thread_local_storage/enumerable_thread_specific_cls.html\n//\ntemplate <typename T,\n          typename Initialize = internal::ThreadLocalNoOpInitialize<T>,\n          typename Release = internal::ThreadLocalNoOpRelease<T>>\nclass ThreadLocal {\n  // We preallocate default constructed elements in MaxSizedVector.\n  static_assert(std::is_default_constructible<T>::value,\n                \"ThreadLocal data type must be default constructible\");\n\n public:\n  explicit ThreadLocal(int capacity)\n      : ThreadLocal(capacity, internal::ThreadLocalNoOpInitialize<T>(),\n                    internal::ThreadLocalNoOpRelease<T>()) {}\n\n  ThreadLocal(int capacity, Initialize initialize)\n      : ThreadLocal(capacity, std::move(initialize),\n                    internal::ThreadLocalNoOpRelease<T>()) {}\n\n  ThreadLocal(int capacity, Initialize initialize, Release release)\n      : initialize_(std::move(initialize)),\n        release_(std::move(release)),\n        capacity_(capacity),\n        data_(capacity_),\n        ptr_(capacity_),\n        filled_records_(0) {\n    eigen_assert(capacity_ >= 0);\n    data_.resize(capacity_);\n    for (int i = 0; i < capacity_; ++i) {\n      ptr_.emplace_back(nullptr);\n    }\n  }\n\n  T& local() {\n    std::thread::id this_thread = std::this_thread::get_id();\n    if (capacity_ == 0) return SpilledLocal(this_thread);\n\n    std::size_t h = std::hash<std::thread::id>()(this_thread);\n    const int start_idx = h % capacity_;\n\n    // NOTE: From the definition of `std::this_thread::get_id()` it is\n    // guaranteed that we never can have concurrent insertions with the same key\n    // to our hash-map like data structure. If we didn't find an element during\n    // the initial traversal, it's guaranteed that no one else could have\n    // inserted it while we are in this function. This allows to massively\n    // simplify out lock-free insert-only hash map.\n\n    // Check if we already have an element for `this_thread`.\n    int idx = start_idx;\n    while (ptr_[idx].load() != nullptr) {\n      ThreadIdAndValue& record = *(ptr_[idx].load());\n      if (record.thread_id == this_thread) return record.value;\n\n      idx += 1;\n      if (idx >= capacity_) idx -= capacity_;\n      if (idx == start_idx) break;\n    }\n\n    // If we are here, it means that we found an insertion point in lookup\n    // table at `idx`, or we did a full traversal and table is full.\n\n    // If lock-free storage is full, fallback on mutex.\n    if (filled_records_.load() >= capacity_) return SpilledLocal(this_thread);\n\n    // We double check that we still have space to insert an element into a lock\n    // free storage. If old value in `filled_records_` is larger than the\n    // records capacity, it means that some other thread added an element while\n    // we were traversing lookup table.\n    int insertion_index =\n        filled_records_.fetch_add(1, std::memory_order_relaxed);\n    if (insertion_index >= capacity_) return SpilledLocal(this_thread);\n\n    // At this point it's guaranteed that we can access to\n    // data_[insertion_index_] without a data race.\n    data_[insertion_index].thread_id = this_thread;\n    initialize_(data_[insertion_index].value);\n\n    // That's the pointer we'll put into the lookup table.\n    ThreadIdAndValue* inserted = &data_[insertion_index];\n\n    // We'll use nullptr pointer to ThreadIdAndValue in a compare-and-swap loop.\n    ThreadIdAndValue* empty = nullptr;\n\n    // Now we have to find an insertion point into the lookup table. We start\n    // from the `idx` that was identified as an insertion point above, it's\n    // guaranteed that we will have an empty record somewhere in a lookup table\n    // (because we created a record in the `data_`).\n    const int insertion_idx = idx;\n\n    do {\n      // Always start search from the original insertion candidate.\n      idx = insertion_idx;\n      while (ptr_[idx].load() != nullptr) {\n        idx += 1;\n        if (idx >= capacity_) idx -= capacity_;\n        // If we did a full loop, it means that we don't have any free entries\n        // in the lookup table, and this means that something is terribly wrong.\n        eigen_assert(idx != insertion_idx);\n      }\n      // Atomic CAS of the pointer guarantees that any other thread, that will\n      // follow this pointer will see all the mutations in the `data_`.\n    } while (!ptr_[idx].compare_exchange_weak(empty, inserted));\n\n    return inserted->value;\n  }\n\n  // WARN: It's not thread safe to call it concurrently with `local()`.\n  void ForEach(std::function<void(std::thread::id, T&)> f) {\n    // Reading directly from `data_` is unsafe, because only CAS to the\n    // record in `ptr_` makes all changes visible to other threads.\n    for (auto& ptr : ptr_) {\n      ThreadIdAndValue* record = ptr.load();\n      if (record == nullptr) continue;\n      f(record->thread_id, record->value);\n    }\n\n    // We did not spill into the map based storage.\n    if (filled_records_.load(std::memory_order_relaxed) < capacity_) return;\n\n    // Adds a happens before edge from the last call to SpilledLocal().\n    std::unique_lock<std::mutex> lock(mu_);\n    for (auto& kv : per_thread_map_) {\n      f(kv.first, kv.second);\n    }\n  }\n\n  // WARN: It's not thread safe to call it concurrently with `local()`.\n  ~ThreadLocal() {\n    // Reading directly from `data_` is unsafe, because only CAS to the record\n    // in `ptr_` makes all changes visible to other threads.\n    for (auto& ptr : ptr_) {\n      ThreadIdAndValue* record = ptr.load();\n      if (record == nullptr) continue;\n      release_(record->value);\n    }\n\n    // We did not spill into the map based storage.\n    if (filled_records_.load(std::memory_order_relaxed) < capacity_) return;\n\n    // Adds a happens before edge from the last call to SpilledLocal().\n    std::unique_lock<std::mutex> lock(mu_);\n    for (auto& kv : per_thread_map_) {\n      release_(kv.second);\n    }\n  }\n\n private:\n  struct ThreadIdAndValue {\n    std::thread::id thread_id;\n    T value;\n  };\n\n  // Use unordered map guarded by a mutex when lock free storage is full.\n  T& SpilledLocal(std::thread::id this_thread) {\n    std::unique_lock<std::mutex> lock(mu_);\n\n    auto it = per_thread_map_.find(this_thread);\n    if (it == per_thread_map_.end()) {\n      auto result = per_thread_map_.emplace(this_thread, T());\n      eigen_assert(result.second);\n      initialize_((*result.first).second);\n      return (*result.first).second;\n    } else {\n      return it->second;\n    }\n  }\n\n  Initialize initialize_;\n  Release release_;\n  const int capacity_;\n\n  // Storage that backs lock-free lookup table `ptr_`. Records stored in this\n  // storage contiguously starting from index 0.\n  MaxSizeVector<ThreadIdAndValue> data_;\n\n  // Atomic pointers to the data stored in `data_`. Used as a lookup table for\n  // linear probing hash map (https://en.wikipedia.org/wiki/Linear_probing).\n  MaxSizeVector<std::atomic<ThreadIdAndValue*>> ptr_;\n\n  // Number of records stored in the `data_`.\n  std::atomic<int> filled_records_;\n\n  // We fallback on per thread map if lock-free storage is full. In practice\n  // this should never happen, if `capacity_` is a reasonable estimate of the\n  // number of threads running in a system.\n  std::mutex mu_;  // Protects per_thread_map_.\n  std::unordered_map<std::thread::id, T> per_thread_map_;\n};\n\n}  // namespace Eigen\n\n#endif  // EIGEN_CXX11_THREADPOOL_THREAD_LOCAL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/ThreadPool/ThreadPoolInterface.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_THREADPOOL_THREAD_POOL_INTERFACE_H\n#define EIGEN_CXX11_THREADPOOL_THREAD_POOL_INTERFACE_H\n\nnamespace Eigen {\n\n// This defines an interface that ThreadPoolDevice can take to use\n// custom thread pools underneath.\nclass ThreadPoolInterface {\n public:\n  // Submits a closure to be run by a thread in the pool.\n  virtual void Schedule(std::function<void()> fn) = 0;\n\n  // Submits a closure to be run by threads in the range [start, end) in the\n  // pool.\n  virtual void ScheduleWithHint(std::function<void()> fn, int /*start*/,\n                                int /*end*/) {\n    // Just defer to Schedule in case sub-classes aren't interested in\n    // overriding this functionality.\n    Schedule(fn);\n  }\n\n  // If implemented, stop processing the closures that have been enqueued.\n  // Currently running closures may still be processed.\n  // If not implemented, does nothing.\n  virtual void Cancel() {}\n\n  // Returns the number of threads in the pool.\n  virtual int NumThreads() const = 0;\n\n  // Returns a logical thread index between 0 and NumThreads() - 1 if called\n  // from one of the threads in the pool. Returns -1 otherwise.\n  virtual int CurrentThreadId() const = 0;\n\n  virtual ~ThreadPoolInterface() {}\n};\n\n}  // namespace Eigen\n\n#endif  // EIGEN_CXX11_THREADPOOL_THREAD_POOL_INTERFACE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/ThreadPool/ThreadYield.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11_THREADPOOL_THREAD_YIELD_H\n#define EIGEN_CXX11_THREADPOOL_THREAD_YIELD_H\n\n// Try to come up with a portable way to yield\n#if EIGEN_COMP_GNUC && EIGEN_GNUC_AT_MOST(4, 7)\n#define EIGEN_THREAD_YIELD() sched_yield()\n#else\n#define EIGEN_THREAD_YIELD() std::this_thread::yield()\n#endif\n\n#endif  // EIGEN_CXX11_THREADPOOL_THREAD_YIELD_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/util/CXX11Meta.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11META_H\n#define EIGEN_CXX11META_H\n\n#include <vector>\n#include \"EmulateArray.h\"\n\n#include \"CXX11Workarounds.h\"\n\nnamespace Eigen {\n\nnamespace internal {\n\n/** \\internal\n  * \\file CXX11/util/CXX11Meta.h\n  * This file contains generic metaprogramming classes which are not specifically related to Eigen.\n  * This file expands upon Core/util/Meta.h and adds support for C++11 specific features.\n  */\n\ntemplate<typename... tt>\nstruct type_list { constexpr static int count = sizeof...(tt); };\n\ntemplate<typename t, typename... tt>\nstruct type_list<t, tt...> { constexpr static int count = sizeof...(tt) + 1; typedef t first_type; };\n\ntemplate<typename T, T... nn>\nstruct numeric_list { constexpr static std::size_t count = sizeof...(nn); };\n\ntemplate<typename T, T n, T... nn>\nstruct numeric_list<T, n, nn...> { static const std::size_t count = sizeof...(nn) + 1; const static T first_value = n; };\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n/* numeric list constructors\n *\n * equivalencies:\n *     constructor                                              result\n *     typename gen_numeric_list<int, 5>::type                  numeric_list<int, 0,1,2,3,4>\n *     typename gen_numeric_list_reversed<int, 5>::type         numeric_list<int, 4,3,2,1,0>\n *     typename gen_numeric_list_swapped_pair<int, 5,1,2>::type numeric_list<int, 0,2,1,3,4>\n *     typename gen_numeric_list_repeated<int, 0, 5>::type      numeric_list<int, 0,0,0,0,0>\n */\n\ntemplate<typename T, std::size_t n, T start = 0, T... ii> struct gen_numeric_list                     : gen_numeric_list<T, n-1, start, start + n-1, ii...> {};\ntemplate<typename T, T start, T... ii>                    struct gen_numeric_list<T, 0, start, ii...> { typedef numeric_list<T, ii...> type; };\n\ntemplate<typename T, std::size_t n, T start = 0, T... ii> struct gen_numeric_list_reversed                     : gen_numeric_list_reversed<T, n-1, start, ii..., start + n-1> {};\ntemplate<typename T, T start, T... ii>                    struct gen_numeric_list_reversed<T, 0, start, ii...> { typedef numeric_list<T, ii...> type; };\n\ntemplate<typename T, std::size_t n, T a, T b, T start = 0, T... ii> struct gen_numeric_list_swapped_pair                           : gen_numeric_list_swapped_pair<T, n-1, a, b, start, (start + n-1) == a ? b : ((start + n-1) == b ? a : (start + n-1)), ii...> {};\ntemplate<typename T, T a, T b, T start, T... ii>                    struct gen_numeric_list_swapped_pair<T, 0, a, b, start, ii...> { typedef numeric_list<T, ii...> type; };\n\ntemplate<typename T, std::size_t n, T V, T... nn> struct gen_numeric_list_repeated                 : gen_numeric_list_repeated<T, n-1, V, V, nn...> {};\ntemplate<typename T, T V, T... nn>                struct gen_numeric_list_repeated<T, 0, V, nn...> { typedef numeric_list<T, nn...> type; };\n\n/* list manipulation: concatenate */\n\ntemplate<class a, class b> struct concat;\n\ntemplate<typename... as, typename... bs> struct concat<type_list<as...>,       type_list<bs...>>        { typedef type_list<as..., bs...> type; };\ntemplate<typename T, T... as, T... bs>   struct concat<numeric_list<T, as...>, numeric_list<T, bs...> > { typedef numeric_list<T, as..., bs...> type; };\n\ntemplate<typename... p> struct mconcat;\ntemplate<typename a>                             struct mconcat<a>           { typedef a type; };\ntemplate<typename a, typename b>                 struct mconcat<a, b>        : concat<a, b> {};\ntemplate<typename a, typename b, typename... cs> struct mconcat<a, b, cs...> : concat<a, typename mconcat<b, cs...>::type> {};\n\n/* list manipulation: extract slices */\n\ntemplate<int n, typename x> struct take;\ntemplate<int n, typename a, typename... as> struct take<n, type_list<a, as...>> : concat<type_list<a>, typename take<n-1, type_list<as...>>::type> {};\ntemplate<int n>                             struct take<n, type_list<>>         { typedef type_list<> type; };\ntemplate<typename a, typename... as>        struct take<0, type_list<a, as...>> { typedef type_list<> type; };\ntemplate<>                                  struct take<0, type_list<>>         { typedef type_list<> type; };\n\ntemplate<typename T, int n, T a, T... as> struct take<n, numeric_list<T, a, as...>> : concat<numeric_list<T, a>, typename take<n-1, numeric_list<T, as...>>::type> {};\ntemplate<typename T, int n>               struct take<n, numeric_list<T>>           { typedef numeric_list<T> type; };\ntemplate<typename T, T a, T... as>        struct take<0, numeric_list<T, a, as...>> { typedef numeric_list<T> type; };\ntemplate<typename T>                      struct take<0, numeric_list<T>>           { typedef numeric_list<T> type; };\n\ntemplate<typename T, int n, T... ii>      struct h_skip_helper_numeric;\ntemplate<typename T, int n, T i, T... ii> struct h_skip_helper_numeric<T, n, i, ii...> : h_skip_helper_numeric<T, n-1, ii...> {};\ntemplate<typename T, T i, T... ii>        struct h_skip_helper_numeric<T, 0, i, ii...> { typedef numeric_list<T, i, ii...> type; };\ntemplate<typename T, int n>               struct h_skip_helper_numeric<T, n>           { typedef numeric_list<T> type; };\ntemplate<typename T>                      struct h_skip_helper_numeric<T, 0>           { typedef numeric_list<T> type; };\n\ntemplate<int n, typename... tt>             struct h_skip_helper_type;\ntemplate<int n, typename t, typename... tt> struct h_skip_helper_type<n, t, tt...> : h_skip_helper_type<n-1, tt...> {};\ntemplate<typename t, typename... tt>        struct h_skip_helper_type<0, t, tt...> { typedef type_list<t, tt...> type; };\ntemplate<int n>                             struct h_skip_helper_type<n>           { typedef type_list<> type; };\ntemplate<>                                  struct h_skip_helper_type<0>           { typedef type_list<> type; };\n#endif //not EIGEN_PARSED_BY_DOXYGEN\n\ntemplate<int n>\nstruct h_skip {\n  template<typename T, T... ii>\n  constexpr static EIGEN_STRONG_INLINE typename h_skip_helper_numeric<T, n, ii...>::type helper(numeric_list<T, ii...>) { return typename h_skip_helper_numeric<T, n, ii...>::type(); }\n  template<typename... tt>\n  constexpr static EIGEN_STRONG_INLINE typename h_skip_helper_type<n, tt...>::type helper(type_list<tt...>) { return typename h_skip_helper_type<n, tt...>::type(); }\n};\n\ntemplate<int n, typename a> struct skip { typedef decltype(h_skip<n>::helper(a())) type; };\n\ntemplate<int start, int count, typename a> struct slice : take<count, typename skip<start, a>::type> {};\n\n/* list manipulation: retrieve single element from list */\n\ntemplate<int n, typename x> struct get;\n\ntemplate<int n, typename a, typename... as>               struct get<n, type_list<a, as...>>   : get<n-1, type_list<as...>> {};\ntemplate<typename a, typename... as>                      struct get<0, type_list<a, as...>>   { typedef a type; };\n\ntemplate<typename T, int n, T a, T... as>                        struct get<n, numeric_list<T, a, as...>>   : get<n-1, numeric_list<T, as...>> {};\ntemplate<typename T, T a, T... as>                               struct get<0, numeric_list<T, a, as...>>   { constexpr static T value = a; };\n\ntemplate<std::size_t n, typename T, T a, T... as> constexpr T       array_get(const numeric_list<T, a, as...>&) {\n   return get<(int)n, numeric_list<T, a, as...>>::value;\n}\n\n/* always get type, regardless of dummy; good for parameter pack expansion */\n\ntemplate<typename T, T dummy, typename t> struct id_numeric  { typedef t type; };\ntemplate<typename dummy, typename t>      struct id_type     { typedef t type; };\n\n/* equality checking, flagged version */\n\ntemplate<typename a, typename b> struct is_same_gf : is_same<a, b> { constexpr static int global_flags = 0; };\n\n/* apply_op to list */\n\ntemplate<\n  bool from_left, // false\n  template<typename, typename> class op,\n  typename additional_param,\n  typename... values\n>\nstruct h_apply_op_helper                                        { typedef type_list<typename op<values, additional_param>::type...> type; };\ntemplate<\n  template<typename, typename> class op,\n  typename additional_param,\n  typename... values\n>\nstruct h_apply_op_helper<true, op, additional_param, values...> { typedef type_list<typename op<additional_param, values>::type...> type; };\n\ntemplate<\n  bool from_left,\n  template<typename, typename> class op,\n  typename additional_param\n>\nstruct h_apply_op\n{\n  template<typename... values>\n  constexpr static typename h_apply_op_helper<from_left, op, additional_param, values...>::type helper(type_list<values...>)\n  { return typename h_apply_op_helper<from_left, op, additional_param, values...>::type(); }\n};\n\ntemplate<\n  template<typename, typename> class op,\n  typename additional_param,\n  typename a\n>\nstruct apply_op_from_left { typedef decltype(h_apply_op<true, op, additional_param>::helper(a())) type; };\n\ntemplate<\n  template<typename, typename> class op,\n  typename additional_param,\n  typename a\n>\nstruct apply_op_from_right { typedef decltype(h_apply_op<false, op, additional_param>::helper(a())) type; };\n\n/* see if an element is in a list */\n\ntemplate<\n  template<typename, typename> class test,\n  typename check_against,\n  typename h_list,\n  bool last_check_positive = false\n>\nstruct contained_in_list;\n\ntemplate<\n  template<typename, typename> class test,\n  typename check_against,\n  typename h_list\n>\nstruct contained_in_list<test, check_against, h_list, true>\n{\n  constexpr static bool value = true;\n};\n\ntemplate<\n  template<typename, typename> class test,\n  typename check_against,\n  typename a,\n  typename... as\n>\nstruct contained_in_list<test, check_against, type_list<a, as...>, false> : contained_in_list<test, check_against, type_list<as...>, test<check_against, a>::value> {};\n\ntemplate<\n  template<typename, typename> class test,\n  typename check_against\n  EIGEN_TPL_PP_SPEC_HACK_DEFC(typename, empty)\n>\nstruct contained_in_list<test, check_against, type_list<EIGEN_TPL_PP_SPEC_HACK_USE(empty)>, false> { constexpr static bool value = false; };\n\n/* see if an element is in a list and check for global flags */\n\ntemplate<\n  template<typename, typename> class test,\n  typename check_against,\n  typename h_list,\n  int default_flags = 0,\n  bool last_check_positive = false,\n  int last_check_flags = default_flags\n>\nstruct contained_in_list_gf;\n\ntemplate<\n  template<typename, typename> class test,\n  typename check_against,\n  typename h_list,\n  int default_flags,\n  int last_check_flags\n>\nstruct contained_in_list_gf<test, check_against, h_list, default_flags, true, last_check_flags>\n{\n  constexpr static bool value = true;\n  constexpr static int global_flags = last_check_flags;\n};\n\ntemplate<\n  template<typename, typename> class test,\n  typename check_against,\n  typename a,\n  typename... as,\n  int default_flags,\n  int last_check_flags\n>\nstruct contained_in_list_gf<test, check_against, type_list<a, as...>, default_flags, false, last_check_flags> : contained_in_list_gf<test, check_against, type_list<as...>, default_flags, test<check_against, a>::value, test<check_against, a>::global_flags> {};\n\ntemplate<\n  template<typename, typename> class test,\n  typename check_against\n  EIGEN_TPL_PP_SPEC_HACK_DEFC(typename, empty),\n  int default_flags,\n  int last_check_flags\n>\nstruct contained_in_list_gf<test, check_against, type_list<EIGEN_TPL_PP_SPEC_HACK_USE(empty)>, default_flags, false, last_check_flags> { constexpr static bool value = false; constexpr static int global_flags = default_flags; };\n\n/* generic reductions */\n\ntemplate<\n  typename Reducer,\n  typename... Ts\n> struct reduce;\n\ntemplate<\n  typename Reducer\n> struct reduce<Reducer>\n{\n  EIGEN_DEVICE_FUNC constexpr static EIGEN_STRONG_INLINE int run() { return Reducer::Identity; }\n};\n\ntemplate<\n  typename Reducer,\n  typename A\n> struct reduce<Reducer, A>\n{\n  EIGEN_DEVICE_FUNC constexpr static EIGEN_STRONG_INLINE A run(A a) { return a; }\n};\n\ntemplate<\n  typename Reducer,\n  typename A,\n  typename... Ts\n> struct reduce<Reducer, A, Ts...>\n{\n  EIGEN_DEVICE_FUNC constexpr static EIGEN_STRONG_INLINE auto run(A a, Ts... ts) -> decltype(Reducer::run(a, reduce<Reducer, Ts...>::run(ts...))) {\n    return Reducer::run(a, reduce<Reducer, Ts...>::run(ts...));\n  }\n};\n\n/* generic binary operations */\n\nstruct sum_op           {\n  template<typename A, typename B> EIGEN_DEVICE_FUNC constexpr static EIGEN_STRONG_INLINE auto run(A a, B b) -> decltype(a + b)   { return a + b;   }\n  static constexpr int Identity = 0;\n};\nstruct product_op       {\n  template<typename A, typename B> EIGEN_DEVICE_FUNC constexpr static EIGEN_STRONG_INLINE auto run(A a, B b) -> decltype(a * b)   { return a * b;   }\n  static constexpr int Identity = 1;\n};\n\nstruct logical_and_op   { template<typename A, typename B> constexpr static EIGEN_STRONG_INLINE auto run(A a, B b) -> decltype(a && b)  { return a && b;  } };\nstruct logical_or_op    { template<typename A, typename B> constexpr static EIGEN_STRONG_INLINE auto run(A a, B b) -> decltype(a || b)  { return a || b;  } };\n\nstruct equal_op         { template<typename A, typename B> constexpr static EIGEN_STRONG_INLINE auto run(A a, B b) -> decltype(a == b)  { return a == b;  } };\nstruct not_equal_op     { template<typename A, typename B> constexpr static EIGEN_STRONG_INLINE auto run(A a, B b) -> decltype(a != b)  { return a != b;  } };\nstruct lesser_op        { template<typename A, typename B> constexpr static EIGEN_STRONG_INLINE auto run(A a, B b) -> decltype(a < b)   { return a < b;   } };\nstruct lesser_equal_op  { template<typename A, typename B> constexpr static EIGEN_STRONG_INLINE auto run(A a, B b) -> decltype(a <= b)  { return a <= b;  } };\nstruct greater_op       { template<typename A, typename B> constexpr static EIGEN_STRONG_INLINE auto run(A a, B b) -> decltype(a > b)   { return a > b;   } };\nstruct greater_equal_op { template<typename A, typename B> constexpr static EIGEN_STRONG_INLINE auto run(A a, B b) -> decltype(a >= b)  { return a >= b;  } };\n\n/* generic unary operations */\n\nstruct not_op                { template<typename A> constexpr static EIGEN_STRONG_INLINE auto run(A a) -> decltype(!a)      { return !a;      } };\nstruct negation_op           { template<typename A> constexpr static EIGEN_STRONG_INLINE auto run(A a) -> decltype(-a)      { return -a;      } };\nstruct greater_equal_zero_op { template<typename A> constexpr static EIGEN_STRONG_INLINE auto run(A a) -> decltype(a >= 0)  { return a >= 0;  } };\n\n\n/* reductions for lists */\n\n// using auto -> return value spec makes ICC 13.0 and 13.1 crash here, so we have to hack it\n// together in front... (13.0 doesn't work with array_prod/array_reduce/... anyway, but 13.1\n// does...\ntemplate<typename... Ts>\nEIGEN_DEVICE_FUNC constexpr EIGEN_STRONG_INLINE decltype(reduce<product_op, Ts...>::run((*((Ts*)0))...)) arg_prod(Ts... ts)\n{\n  return reduce<product_op, Ts...>::run(ts...);\n}\n\ntemplate<typename... Ts>\nconstexpr EIGEN_STRONG_INLINE decltype(reduce<sum_op, Ts...>::run((*((Ts*)0))...)) arg_sum(Ts... ts)\n{\n  return reduce<sum_op, Ts...>::run(ts...);\n}\n\n/* reverse arrays */\n\ntemplate<typename Array, int... n>\nconstexpr EIGEN_STRONG_INLINE Array h_array_reverse(Array arr, numeric_list<int, n...>)\n{\n  return {{array_get<sizeof...(n) - n - 1>(arr)...}};\n}\n\ntemplate<typename T, std::size_t N>\nconstexpr EIGEN_STRONG_INLINE array<T, N> array_reverse(array<T, N> arr)\n{\n  return h_array_reverse(arr, typename gen_numeric_list<int, N>::type());\n}\n\n\n/* generic array reductions */\n\n// can't reuse standard reduce() interface above because Intel's Compiler\n// *really* doesn't like it, so we just reimplement the stuff\n// (start from N - 1 and work down to 0 because specialization for\n// n == N - 1 also doesn't work in Intel's compiler, so it goes into\n// an infinite loop)\ntemplate<typename Reducer, typename T, std::size_t N, std::size_t n = N - 1>\nstruct h_array_reduce {\n  EIGEN_DEVICE_FUNC constexpr static EIGEN_STRONG_INLINE auto run(array<T, N> arr, T identity) -> decltype(Reducer::run(h_array_reduce<Reducer, T, N, n - 1>::run(arr, identity), array_get<n>(arr)))\n  {\n    return Reducer::run(h_array_reduce<Reducer, T, N, n - 1>::run(arr, identity), array_get<n>(arr));\n  }\n};\n\ntemplate<typename Reducer, typename T, std::size_t N>\nstruct h_array_reduce<Reducer, T, N, 0>\n{\n  EIGEN_DEVICE_FUNC constexpr static EIGEN_STRONG_INLINE T run(const array<T, N>& arr, T)\n  {\n    return array_get<0>(arr);\n  }\n};\n\ntemplate<typename Reducer, typename T>\nstruct h_array_reduce<Reducer, T, 0>\n{\n  EIGEN_DEVICE_FUNC constexpr static EIGEN_STRONG_INLINE T run(const array<T, 0>&, T identity)\n  {\n    return identity;\n  }\n};\n\ntemplate<typename Reducer, typename T, std::size_t N>\nEIGEN_DEVICE_FUNC constexpr EIGEN_STRONG_INLINE auto array_reduce(const array<T, N>& arr, T identity) -> decltype(h_array_reduce<Reducer, T, N>::run(arr, identity))\n{\n  return h_array_reduce<Reducer, T, N>::run(arr, identity);\n}\n\n/* standard array reductions */\n\ntemplate<typename T, std::size_t N>\nEIGEN_DEVICE_FUNC constexpr EIGEN_STRONG_INLINE auto array_sum(const array<T, N>& arr) -> decltype(array_reduce<sum_op, T, N>(arr, static_cast<T>(0)))\n{\n  return array_reduce<sum_op, T, N>(arr, static_cast<T>(0));\n}\n\ntemplate<typename T, std::size_t N>\nEIGEN_DEVICE_FUNC constexpr EIGEN_STRONG_INLINE auto array_prod(const array<T, N>& arr) -> decltype(array_reduce<product_op, T, N>(arr, static_cast<T>(1)))\n{\n  return array_reduce<product_op, T, N>(arr, static_cast<T>(1));\n}\n\ntemplate<typename t>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE t array_prod(const std::vector<t>& a) {\n  eigen_assert(a.size() > 0);\n  t prod = 1;\n  for (size_t i = 0; i < a.size(); ++i) { prod *= a[i]; }\n  return prod;\n}\n\n/* zip an array */\n\ntemplate<typename Op, typename A, typename B, std::size_t N, int... n>\nconstexpr EIGEN_STRONG_INLINE array<decltype(Op::run(A(), B())),N> h_array_zip(array<A, N> a, array<B, N> b, numeric_list<int, n...>)\n{\n  return array<decltype(Op::run(A(), B())),N>{{ Op::run(array_get<n>(a), array_get<n>(b))... }};\n}\n\ntemplate<typename Op, typename A, typename B, std::size_t N>\nconstexpr EIGEN_STRONG_INLINE array<decltype(Op::run(A(), B())),N> array_zip(array<A, N> a, array<B, N> b)\n{\n  return h_array_zip<Op>(a, b, typename gen_numeric_list<int, N>::type());\n}\n\n/* zip an array and reduce the result */\n\ntemplate<typename Reducer, typename Op, typename A, typename B, std::size_t N, int... n>\nconstexpr EIGEN_STRONG_INLINE auto h_array_zip_and_reduce(array<A, N> a, array<B, N> b, numeric_list<int, n...>) -> decltype(reduce<Reducer, typename id_numeric<int,n,decltype(Op::run(A(), B()))>::type...>::run(Op::run(array_get<n>(a), array_get<n>(b))...))\n{\n  return reduce<Reducer, typename id_numeric<int,n,decltype(Op::run(A(), B()))>::type...>::run(Op::run(array_get<n>(a), array_get<n>(b))...);\n}\n\ntemplate<typename Reducer, typename Op, typename A, typename B, std::size_t N>\nconstexpr EIGEN_STRONG_INLINE auto array_zip_and_reduce(array<A, N> a, array<B, N> b) -> decltype(h_array_zip_and_reduce<Reducer, Op, A, B, N>(a, b, typename gen_numeric_list<int, N>::type()))\n{\n  return h_array_zip_and_reduce<Reducer, Op, A, B, N>(a, b, typename gen_numeric_list<int, N>::type());\n}\n\n/* apply stuff to an array */\n\ntemplate<typename Op, typename A, std::size_t N, int... n>\nconstexpr EIGEN_STRONG_INLINE array<decltype(Op::run(A())),N> h_array_apply(array<A, N> a, numeric_list<int, n...>)\n{\n  return array<decltype(Op::run(A())),N>{{ Op::run(array_get<n>(a))... }};\n}\n\ntemplate<typename Op, typename A, std::size_t N>\nconstexpr EIGEN_STRONG_INLINE array<decltype(Op::run(A())),N> array_apply(array<A, N> a)\n{\n  return h_array_apply<Op>(a, typename gen_numeric_list<int, N>::type());\n}\n\n/* apply stuff to an array and reduce */\n\ntemplate<typename Reducer, typename Op, typename A, std::size_t N, int... n>\nconstexpr EIGEN_STRONG_INLINE auto h_array_apply_and_reduce(array<A, N> arr, numeric_list<int, n...>) -> decltype(reduce<Reducer, typename id_numeric<int,n,decltype(Op::run(A()))>::type...>::run(Op::run(array_get<n>(arr))...))\n{\n  return reduce<Reducer, typename id_numeric<int,n,decltype(Op::run(A()))>::type...>::run(Op::run(array_get<n>(arr))...);\n}\n\ntemplate<typename Reducer, typename Op, typename A, std::size_t N>\nconstexpr EIGEN_STRONG_INLINE auto array_apply_and_reduce(array<A, N> a) -> decltype(h_array_apply_and_reduce<Reducer, Op, A, N>(a, typename gen_numeric_list<int, N>::type()))\n{\n  return h_array_apply_and_reduce<Reducer, Op, A, N>(a, typename gen_numeric_list<int, N>::type());\n}\n\n/* repeat a value n times (and make an array out of it\n * usage:\n *   array<int, 16> = repeat<16>(42);\n */\n\ntemplate<int n>\nstruct h_repeat\n{\n  template<typename t, int... ii>\n  constexpr static EIGEN_STRONG_INLINE array<t, n> run(t v, numeric_list<int, ii...>)\n  {\n    return {{ typename id_numeric<int, ii, t>::type(v)... }};\n  }\n};\n\ntemplate<int n, typename t>\nconstexpr array<t, n> repeat(t v) { return h_repeat<n>::run(v, typename gen_numeric_list<int, n>::type()); }\n\n/* instantiate a class by a C-style array */\ntemplate<class InstType, typename ArrType, std::size_t N, bool Reverse, typename... Ps>\nstruct h_instantiate_by_c_array;\n\ntemplate<class InstType, typename ArrType, std::size_t N, typename... Ps>\nstruct h_instantiate_by_c_array<InstType, ArrType, N, false, Ps...>\n{\n  static InstType run(ArrType* arr, Ps... args)\n  {\n    return h_instantiate_by_c_array<InstType, ArrType, N - 1, false, Ps..., ArrType>::run(arr + 1, args..., arr[0]);\n  }\n};\n\ntemplate<class InstType, typename ArrType, std::size_t N, typename... Ps>\nstruct h_instantiate_by_c_array<InstType, ArrType, N, true, Ps...>\n{\n  static InstType run(ArrType* arr, Ps... args)\n  {\n    return h_instantiate_by_c_array<InstType, ArrType, N - 1, false, ArrType, Ps...>::run(arr + 1, arr[0], args...);\n  }\n};\n\ntemplate<class InstType, typename ArrType, typename... Ps>\nstruct h_instantiate_by_c_array<InstType, ArrType, 0, false, Ps...>\n{\n  static InstType run(ArrType* arr, Ps... args)\n  {\n    (void)arr;\n    return InstType(args...);\n  }\n};\n\ntemplate<class InstType, typename ArrType, typename... Ps>\nstruct h_instantiate_by_c_array<InstType, ArrType, 0, true, Ps...>\n{\n  static InstType run(ArrType* arr, Ps... args)\n  {\n    (void)arr;\n    return InstType(args...);\n  }\n};\n\ntemplate<class InstType, typename ArrType, std::size_t N, bool Reverse = false>\nInstType instantiate_by_c_array(ArrType* arr)\n{\n  return h_instantiate_by_c_array<InstType, ArrType, N, Reverse>::run(arr);\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11META_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/util/CXX11Workarounds.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_CXX11WORKAROUNDS_H\n#define EIGEN_CXX11WORKAROUNDS_H\n\n/* COMPATIBILITY CHECKS\n * (so users of compilers that are too old get some realistic error messages)\n */\n#if defined(__INTEL_COMPILER) && (__INTEL_COMPILER < 1310)\n#error Intel Compiler only supports required C++ features since version 13.1.\n// note that most stuff in principle works with 13.0 but when combining\n// some features, at some point 13.0 will just fail with an internal assertion\n#elif defined(__GNUC__) && !defined(__clang__) && !defined(__INTEL_COMPILER) && (__GNUC__ < 4 || (__GNUC__ == 4 && __GNUC_MINOR__ < 6))\n// G++ < 4.6 by default will continue processing the source files - even if we use #error to make\n// it error out. For this reason, we use the pragma to make sure G++ aborts at the first error\n// it sees. Unfortunately, that is still not our #error directive, but at least the output is\n// short enough the user has a chance to see that the compiler version is not sufficient for\n// the funky template mojo we use.\n#pragma GCC diagnostic error \"-Wfatal-errors\"\n#error GNU C++ Compiler (g++) only supports required C++ features since version 4.6.\n#endif\n\n/* Check that the compiler at least claims to support C++11. It might not be sufficient\n * because the compiler may not implement it correctly, but at least we'll know.\n * On the other hand, visual studio still doesn't claim to support C++11 although it's\n * compliant enugh for our purpose.\n */\n#if (EIGEN_COMP_CXXVER < 11)\n#if defined(__GNUC__) && !defined(__clang__) && !defined(__INTEL_COMPILER)\n#pragma GCC diagnostic error \"-Wfatal-errors\"\n#endif\n#error This library needs at least a C++11 compliant compiler. If you use g++/clang, please enable the -std=c++11 compiler flag. (-std=c++0x on older versions.)\n#endif\n\nnamespace Eigen {\n\nnamespace internal {\n\n/* std::get is only constexpr in C++14, not yet in C++11\n */\n\n\ntemplate<std::size_t I_, class T> constexpr inline T&       array_get(std::vector<T>&       a) { return a[I_]; }\ntemplate<std::size_t I_, class T> constexpr inline T&&      array_get(std::vector<T>&&      a) { return a[I_]; }\ntemplate<std::size_t I_, class T> constexpr inline T const& array_get(std::vector<T> const& a) { return a[I_]; }\n\n/* Suppose you have a template of the form\n * template<typename T> struct X;\n * And you want to specialize it in such a way:\n *    template<typename S1, typename... SN> struct X<Foo<S1, SN...>> { ::: };\n *    template<>                            struct X<Foo<>>          { ::: };\n * This will work in Intel's compiler 13.0, but only to some extent in g++ 4.6, since\n * g++ can only match templates called with parameter packs if the number of template\n * arguments is not a fixed size (so inside the first specialization, referencing\n * X<Foo<Sn...>> will fail in g++). On the other hand, g++ will accept the following:\n *    template<typename S...> struct X<Foo<S...>> { ::: }:\n * as an additional (!) specialization, which will then only match the empty case.\n * But Intel's compiler 13.0 won't accept that, it will only accept the empty syntax,\n * so we have to create a workaround for this.\n */\n#if defined(__GNUC__) && !defined(__INTEL_COMPILER)\n#define EIGEN_TPL_PP_SPEC_HACK_DEF(mt, n)    mt... n\n#define EIGEN_TPL_PP_SPEC_HACK_DEFC(mt, n)   , EIGEN_TPL_PP_SPEC_HACK_DEF(mt, n)\n#define EIGEN_TPL_PP_SPEC_HACK_USE(n)        n...\n#define EIGEN_TPL_PP_SPEC_HACK_USEC(n)       , n...\n#else\n#define EIGEN_TPL_PP_SPEC_HACK_DEF(mt, n)\n#define EIGEN_TPL_PP_SPEC_HACK_DEFC(mt, n)\n#define EIGEN_TPL_PP_SPEC_HACK_USE(n)\n#define EIGEN_TPL_PP_SPEC_HACK_USEC(n)\n#endif\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_CXX11WORKAROUNDS_H\n\n/*\n * kate: space-indent on; indent-width 2; mixedindent off; indent-mode cstyle;\n */\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/util/EmulateArray.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_EMULATE_ARRAY_H\n#define EIGEN_EMULATE_ARRAY_H\n\n\n\n// The array class is only available starting with cxx11. Emulate our own here\n// if needed. Beware, msvc still doesn't advertise itself as a c++11 compiler!\n// Moreover, CUDA doesn't support the STL containers, so we use our own instead.\n#if (__cplusplus <= 199711L && EIGEN_COMP_MSVC < 1900) || defined(EIGEN_GPUCC) || defined(EIGEN_AVOID_STL_ARRAY)\n\nnamespace Eigen {\ntemplate <typename T, size_t n> class array {\n public:\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE T& operator[] (size_t index) { eigen_internal_assert(index < size()); return values[index]; }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE const T& operator[] (size_t index) const { eigen_internal_assert(index < size()); return values[index]; }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE T& at(size_t index) { eigen_assert(index < size()); return values[index]; }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE const T& at(size_t index) const { eigen_assert(index < size()); return values[index]; }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE T& front() { return values[0]; }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE const T& front() const { return values[0]; }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE T& back() { return values[n-1]; }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE const T& back() const { return values[n-1]; }\n\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  static std::size_t size() { return n; }\n\n  T values[n];\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array() { }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array(const T& v) {\n    EIGEN_STATIC_ASSERT(n==1, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    values[0] = v;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array(const T& v1, const T& v2) {\n    EIGEN_STATIC_ASSERT(n==2, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    values[0] = v1;\n    values[1] = v2;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array(const T& v1, const T& v2, const T& v3) {\n    EIGEN_STATIC_ASSERT(n==3, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    values[0] = v1;\n    values[1] = v2;\n    values[2] = v3;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array(const T& v1, const T& v2, const T& v3,\n                            const T& v4) {\n    EIGEN_STATIC_ASSERT(n==4, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    values[0] = v1;\n    values[1] = v2;\n    values[2] = v3;\n    values[3] = v4;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array(const T& v1, const T& v2, const T& v3, const T& v4,\n                            const T& v5) {\n    EIGEN_STATIC_ASSERT(n==5, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    values[0] = v1;\n    values[1] = v2;\n    values[2] = v3;\n    values[3] = v4;\n    values[4] = v5;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array(const T& v1, const T& v2, const T& v3, const T& v4,\n                            const T& v5, const T& v6) {\n    EIGEN_STATIC_ASSERT(n==6, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    values[0] = v1;\n    values[1] = v2;\n    values[2] = v3;\n    values[3] = v4;\n    values[4] = v5;\n    values[5] = v6;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array(const T& v1, const T& v2, const T& v3, const T& v4,\n                            const T& v5, const T& v6, const T& v7) {\n    EIGEN_STATIC_ASSERT(n==7, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    values[0] = v1;\n    values[1] = v2;\n    values[2] = v3;\n    values[3] = v4;\n    values[4] = v5;\n    values[5] = v6;\n    values[6] = v7;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array(\n      const T& v1, const T& v2, const T& v3, const T& v4,\n      const T& v5, const T& v6, const T& v7, const T& v8) {\n    EIGEN_STATIC_ASSERT(n==8, YOU_MADE_A_PROGRAMMING_MISTAKE)\n    values[0] = v1;\n    values[1] = v2;\n    values[2] = v3;\n    values[3] = v4;\n    values[4] = v5;\n    values[5] = v6;\n    values[6] = v7;\n    values[7] = v8;\n  }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array(std::initializer_list<T> l) {\n    eigen_assert(l.size() == n);\n    internal::smart_copy(l.begin(), l.end(), values);\n  }\n#endif\n};\n\n\n// Specialize array for zero size\ntemplate <typename T> class array<T, 0> {\n public:\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE T& operator[] (size_t) {\n    eigen_assert(false && \"Can't index a zero size array\");\n    return dummy;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE const T& operator[] (size_t) const {\n    eigen_assert(false && \"Can't index a zero size array\");\n    return dummy;\n  }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE T& front() {\n    eigen_assert(false && \"Can't index a zero size array\");\n    return dummy;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE const T& front() const {\n    eigen_assert(false && \"Can't index a zero size array\");\n    return dummy;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE T& back() {\n    eigen_assert(false && \"Can't index a zero size array\");\n    return dummy;\n  }\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE const T& back() const {\n    eigen_assert(false && \"Can't index a zero size array\");\n    return dummy;\n  }\n\n  static EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE std::size_t size() { return 0; }\n\n  EIGEN_DEVICE_FUNC\n  EIGEN_STRONG_INLINE array() : dummy() { }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  EIGEN_DEVICE_FUNC array(std::initializer_list<T> l) : dummy() {\n    EIGEN_UNUSED_VARIABLE(l);\n    eigen_assert(l.size() == 0);\n  }\n#endif\n\n private:\n  T dummy;\n};\n\n// Comparison operator\n// Todo: implement !=, <, <=, >,  and >=\ntemplate<class T, std::size_t N>\nEIGEN_DEVICE_FUNC bool operator==(const array<T,N>& lhs, const array<T,N>& rhs) {\n  for (std::size_t i = 0; i < N; ++i) {\n    if (lhs[i] != rhs[i]) {\n      return false;\n    }\n  }\n  return true;\n}\n\n\nnamespace internal {\ntemplate<std::size_t I_, class T, std::size_t N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T& array_get(array<T,N>& a) {\n  return a[I_];\n}\ntemplate<std::size_t I_, class T, std::size_t N>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const T& array_get(const array<T,N>& a) {\n  return a[I_];\n}\n\ntemplate<class T, std::size_t N> struct array_size<array<T,N> > {\n  enum { value = N };\n};\ntemplate<class T, std::size_t N> struct array_size<array<T,N>& > {\n  enum { value = N };\n};\ntemplate<class T, std::size_t N> struct array_size<const array<T,N> > {\n  enum { value = N };\n};\ntemplate<class T, std::size_t N> struct array_size<const array<T,N>& > {\n  enum { value = N };\n};\n\n}  // end namespace internal\n}  // end namespace Eigen\n\n#else\n\n// The compiler supports c++11, and we're not targeting cuda: use std::array as Eigen::array\n#include <array>\nnamespace Eigen {\n\ntemplate <typename T, std::size_t N> using array = std::array<T, N>;\n\nnamespace internal {\n/* std::get is only constexpr in C++14, not yet in C++11\n *     - libstdc++ from version 4.7 onwards has it nevertheless,\n *                                          so use that\n *     - libstdc++ older versions: use _M_instance directly\n *     - libc++ all versions so far: use __elems_ directly\n *     - all other libs: use std::get to be portable, but\n *                       this may not be constexpr\n */\n#if defined(__GLIBCXX__) && __GLIBCXX__ < 20120322\n#define STD_GET_ARR_HACK             a._M_instance[I_]\n#elif defined(_LIBCPP_VERSION)\n#define STD_GET_ARR_HACK             a.__elems_[I_]\n#else\n#define STD_GET_ARR_HACK             std::template get<I_, T, N>(a)\n#endif\n\ntemplate<std::size_t I_, class T, std::size_t N> constexpr inline T&       array_get(std::array<T,N>&       a) { return (T&)       STD_GET_ARR_HACK; }\ntemplate<std::size_t I_, class T, std::size_t N> constexpr inline T&&      array_get(std::array<T,N>&&      a) { return (T&&)      STD_GET_ARR_HACK; }\ntemplate<std::size_t I_, class T, std::size_t N> constexpr inline T const& array_get(std::array<T,N> const& a) { return (T const&) STD_GET_ARR_HACK; }\n\n#undef STD_GET_ARR_HACK\n\n}  // end namespace internal\n}  // end namespace Eigen\n\n#endif\n\n#endif  // EIGEN_EMULATE_ARRAY_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/CXX11/src/util/MaxSizeVector.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_FIXEDSIZEVECTOR_H\n#define EIGEN_FIXEDSIZEVECTOR_H\n\nnamespace Eigen {\n\n/** \\class MaxSizeVector\n  * \\ingroup Core\n  *\n  * \\brief The MaxSizeVector class.\n  *\n  * The %MaxSizeVector provides a subset of std::vector functionality.\n  *\n  * The goal is to provide basic std::vector operations when using\n  * std::vector is not an option (e.g. on GPU or when compiling using\n  * FMA/AVX, as this can cause either compilation failures or illegal\n  * instruction failures).\n  *\n  * Beware: The constructors are not API compatible with these of\n  * std::vector.\n  */\ntemplate <typename T>\nclass MaxSizeVector {\n  static const size_t alignment = EIGEN_PLAIN_ENUM_MAX(EIGEN_ALIGNOF(T), sizeof(void*));\n public:\n  // Construct a new MaxSizeVector, reserve n elements.\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  explicit MaxSizeVector(size_t n)\n      : reserve_(n), size_(0),\n        data_(static_cast<T*>(internal::handmade_aligned_malloc(n * sizeof(T), alignment))) {\n  }\n\n  // Construct a new MaxSizeVector, reserve and resize to n.\n  // Copy the init value to all elements.\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  MaxSizeVector(size_t n, const T& init)\n      : reserve_(n), size_(n),\n        data_(static_cast<T*>(internal::handmade_aligned_malloc(n * sizeof(T), alignment))) {\n    size_t i = 0;\n    EIGEN_TRY\n    {\n      for(; i < size_; ++i) { new (&data_[i]) T(init); }\n    }\n    EIGEN_CATCH(...)\n    {\n      // Construction failed, destruct in reverse order:\n      for(; (i+1) > 0; --i) { data_[i-1].~T(); }\n      internal::handmade_aligned_free(data_);\n      EIGEN_THROW;\n    }\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  ~MaxSizeVector() {\n    for (size_t i = size_; i > 0; --i) {\n      data_[i-1].~T();\n    }\n    internal::handmade_aligned_free(data_);\n  }\n\n  void resize(size_t n) {\n    eigen_assert(n <= reserve_);\n    for (; size_ < n; ++size_) {\n      new (&data_[size_]) T;\n    }\n    for (; size_ > n; --size_) {\n      data_[size_-1].~T();\n    }\n    eigen_assert(size_ == n);\n  }\n\n  // Append new elements (up to reserved size).\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void push_back(const T& t) {\n    eigen_assert(size_ < reserve_);\n    new (&data_[size_++]) T(t);\n  }\n\n  // For C++03 compatibility this only takes one argument\n  template<class X>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void emplace_back(const X& x) {\n    eigen_assert(size_ < reserve_);\n    new (&data_[size_++]) T(x);\n  }\n\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  const T& operator[] (size_t i) const {\n    eigen_assert(i < size_);\n    return data_[i];\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  T& operator[] (size_t i) {\n    eigen_assert(i < size_);\n    return data_[i];\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  T& back() {\n    eigen_assert(size_ > 0);\n    return data_[size_ - 1];\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  const T& back() const {\n    eigen_assert(size_ > 0);\n    return data_[size_ - 1];\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  void pop_back() {\n    eigen_assert(size_ > 0);\n    data_[--size_].~T();\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  size_t size() const { return size_; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  bool empty() const { return size_ == 0; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  T* data() { return data_; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  const T* data() const { return data_; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  T* begin() { return data_; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  T* end() { return data_ + size_; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  const T* begin() const { return data_; }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\n  const T* end() const { return data_ + size_; }\n\n private:\n  size_t reserve_;\n  size_t size_;\n  T* data_;\n};\n\n}  // namespace Eigen\n\n#endif  // EIGEN_FIXEDSIZEVECTOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/EulerAngles",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Tal Hadad <tal_hd@hotmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_EULERANGLES_MODULE_H\n#define EIGEN_EULERANGLES_MODULE_H\n\n\n#include \"../../Eigen/Core\"\n#include \"../../Eigen/Geometry\"\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\nnamespace Eigen {\n\n/**\n  * \\defgroup EulerAngles_Module EulerAngles module\n  * \\brief This module provides generic euler angles rotation.\n  *\n  * Euler angles are a way to represent 3D rotation.\n  *\n  * In order to use this module in your code, include this header:\n  * \\code\n  * #include <unsupported/Eigen/EulerAngles>\n  * \\endcode\n  *\n  * See \\ref EulerAngles for more information.\n  *\n  */\n\n}\n\n#include \"src/EulerAngles/EulerSystem.h\"\n#include \"src/EulerAngles/EulerAngles.h\"\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_EULERANGLES_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/FFT",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra. \n//\n// Copyright (C) 2009 Mark Borgerding mark a borgerding net\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_FFT_H\n#define EIGEN_FFT_H\n\n#include <complex>\n#include <vector>\n#include <map>\n#include \"../../Eigen/Core\"\n\n\n/**\n  * \\defgroup FFT_Module Fast Fourier Transform module\n  *\n  * \\code\n  * #include <unsupported/Eigen/FFT>\n  * \\endcode\n  *\n  * This module provides Fast Fourier transformation, with a configurable backend\n  * implementation.\n  *\n  * The default implementation is based on kissfft. It is a small, free, and\n  * reasonably efficient default.\n  *\n  * There are currently two implementation backend:\n  *\n  * - fftw (http://www.fftw.org) : faster, GPL -- incompatible with Eigen in LGPL form, bigger code size.\n  * - MKL (http://en.wikipedia.org/wiki/Math_Kernel_Library) : fastest, commercial -- may be incompatible with Eigen in GPL form.\n  *\n  * \\section FFTDesign Design\n  *\n  * The following design decisions were made concerning scaling and\n  * half-spectrum for real FFT.\n  *\n  * The intent is to facilitate generic programming and ease migrating code\n  * from  Matlab/octave.\n  * We think the default behavior of Eigen/FFT should favor correctness and\n  * generality over speed. Of course, the caller should be able to \"opt-out\" from this\n  * behavior and get the speed increase if they want it.\n  *\n  * 1) %Scaling:\n  * Other libraries (FFTW,IMKL,KISSFFT)  do not perform scaling, so there\n  * is a constant gain incurred after the forward&inverse transforms , so \n  * IFFT(FFT(x)) = Kx;  this is done to avoid a vector-by-value multiply.  \n  * The downside is that algorithms that worked correctly in Matlab/octave \n  * don't behave the same way once implemented in C++.\n  *\n  * How Eigen/FFT differs: invertible scaling is performed so IFFT( FFT(x) ) = x. \n  *\n  * 2) Real FFT half-spectrum\n  * Other libraries use only half the frequency spectrum (plus one extra \n  * sample for the Nyquist bin) for a real FFT, the other half is the \n  * conjugate-symmetric of the first half.  This saves them a copy and some \n  * memory.  The downside is the caller needs to have special logic for the \n  * number of bins in complex vs real.\n  *\n  * How Eigen/FFT differs: The full spectrum is returned from the forward \n  * transform.  This facilitates generic template programming by obviating \n  * separate specializations for real vs complex.  On the inverse\n  * transform, only half the spectrum is actually used if the output type is real.\n  */\n \n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n#ifdef EIGEN_FFTW_DEFAULT\n// FFTW: faster, GPL -- incompatible with Eigen in LGPL form, bigger code size\n#  include <fftw3.h>\n#  include \"src/FFT/ei_fftw_impl.h\"\n   namespace Eigen {\n     //template <typename T> typedef struct internal::fftw_impl  default_fft_impl; this does not work\n     template <typename T> struct default_fft_impl : public internal::fftw_impl<T> {};\n   }\n#elif defined EIGEN_MKL_DEFAULT\n// TODO \n// intel Math Kernel Library: fastest, commercial -- may be incompatible with Eigen in GPL form\n#  include \"src/FFT/ei_imklfft_impl.h\"\n   namespace Eigen {\n     template <typename T> struct default_fft_impl : public internal::imklfft_impl {};\n   }\n#else\n// internal::kissfft_impl:  small, free, reasonably efficient default, derived from kissfft\n//\n# include \"src/FFT/ei_kissfft_impl.h\"\n  namespace Eigen {\n     template <typename T> \n       struct default_fft_impl : public internal::kissfft_impl<T> {};\n  }\n#endif\n\nnamespace Eigen {\n\n \n// \ntemplate<typename T_SrcMat,typename T_FftIfc> struct fft_fwd_proxy;\ntemplate<typename T_SrcMat,typename T_FftIfc> struct fft_inv_proxy;\n\nnamespace internal {\ntemplate<typename T_SrcMat,typename T_FftIfc>\nstruct traits< fft_fwd_proxy<T_SrcMat,T_FftIfc> >\n{\n  typedef typename T_SrcMat::PlainObject ReturnType;\n};\ntemplate<typename T_SrcMat,typename T_FftIfc>\nstruct traits< fft_inv_proxy<T_SrcMat,T_FftIfc> >\n{\n  typedef typename T_SrcMat::PlainObject ReturnType;\n};\n}\n\ntemplate<typename T_SrcMat,typename T_FftIfc> \nstruct fft_fwd_proxy\n : public ReturnByValue<fft_fwd_proxy<T_SrcMat,T_FftIfc> >\n{\n  typedef DenseIndex Index;\n\n  fft_fwd_proxy(const T_SrcMat& src,T_FftIfc & fft, Index nfft) : m_src(src),m_ifc(fft), m_nfft(nfft) {}\n\n  template<typename T_DestMat> void evalTo(T_DestMat& dst) const;\n\n  Index rows() const { return m_src.rows(); }\n  Index cols() const { return m_src.cols(); }\nprotected:\n  const T_SrcMat & m_src;\n  T_FftIfc & m_ifc;\n  Index m_nfft;\n};\n\ntemplate<typename T_SrcMat,typename T_FftIfc> \nstruct fft_inv_proxy\n : public ReturnByValue<fft_inv_proxy<T_SrcMat,T_FftIfc> >\n{\n  typedef DenseIndex Index;\n\n  fft_inv_proxy(const T_SrcMat& src,T_FftIfc & fft, Index nfft) : m_src(src),m_ifc(fft), m_nfft(nfft) {}\n\n  template<typename T_DestMat> void evalTo(T_DestMat& dst) const;\n\n  Index rows() const { return m_src.rows(); }\n  Index cols() const { return m_src.cols(); }\nprotected:\n  const T_SrcMat & m_src;\n  T_FftIfc & m_ifc;\n  Index m_nfft;\n};\n\n\ntemplate <typename T_Scalar,\n         typename T_Impl=default_fft_impl<T_Scalar> >\nclass FFT\n{\n  public:\n    typedef T_Impl impl_type;\n    typedef DenseIndex Index;\n    typedef typename impl_type::Scalar Scalar;\n    typedef typename impl_type::Complex Complex;\n\n    enum Flag {\n      Default=0, // goof proof\n      Unscaled=1,\n      HalfSpectrum=2,\n      // SomeOtherSpeedOptimization=4\n      Speedy=32767\n    };\n\n    FFT( const impl_type & impl=impl_type() , Flag flags=Default ) :m_impl(impl),m_flag(flags) { }\n\n    inline\n    bool HasFlag(Flag f) const { return (m_flag & (int)f) == f;}\n\n    inline\n    void SetFlag(Flag f) { m_flag |= (int)f;}\n\n    inline\n    void ClearFlag(Flag f) { m_flag &= (~(int)f);}\n\n    inline\n    void fwd( Complex * dst, const Scalar * src, Index nfft)\n    {\n        m_impl.fwd(dst,src,static_cast<int>(nfft));\n        if ( HasFlag(HalfSpectrum) == false)\n          ReflectSpectrum(dst,nfft);\n    }\n\n    inline\n    void fwd( Complex * dst, const Complex * src, Index nfft)\n    {\n        m_impl.fwd(dst,src,static_cast<int>(nfft));\n    }\n\n    /*\n    inline \n    void fwd2(Complex * dst, const Complex * src, int n0,int n1)\n    {\n      m_impl.fwd2(dst,src,n0,n1);\n    }\n    */\n\n    template <typename _Input>\n    inline\n    void fwd( std::vector<Complex> & dst, const std::vector<_Input> & src) \n    {\n      if ( NumTraits<_Input>::IsComplex == 0 && HasFlag(HalfSpectrum) )\n        dst.resize( (src.size()>>1)+1); // half the bins + Nyquist bin\n      else\n        dst.resize(src.size());\n      fwd(&dst[0],&src[0],src.size());\n    }\n\n    template<typename InputDerived, typename ComplexDerived>\n    inline\n    void fwd( MatrixBase<ComplexDerived> & dst, const MatrixBase<InputDerived> & src, Index nfft=-1)\n    {\n      typedef typename ComplexDerived::Scalar dst_type;\n      typedef typename InputDerived::Scalar src_type;\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(InputDerived)\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(ComplexDerived)\n      EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(ComplexDerived,InputDerived) // size at compile-time\n      EIGEN_STATIC_ASSERT((internal::is_same<dst_type, Complex>::value),\n            YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n      EIGEN_STATIC_ASSERT(int(InputDerived::Flags)&int(ComplexDerived::Flags)&DirectAccessBit,\n            THIS_METHOD_IS_ONLY_FOR_EXPRESSIONS_WITH_DIRECT_MEMORY_ACCESS_SUCH_AS_MAP_OR_PLAIN_MATRICES)\n\n      if (nfft<1)\n        nfft = src.size();\n\n      if ( NumTraits< src_type >::IsComplex == 0 && HasFlag(HalfSpectrum) )\n        dst.derived().resize( (nfft>>1)+1);\n      else\n        dst.derived().resize(nfft);\n\n      if ( src.innerStride() != 1 || src.size() < nfft ) {\n        Matrix<src_type,1,Dynamic> tmp;\n        if (src.size()<nfft) {\n          tmp.setZero(nfft);\n          tmp.block(0,0,src.size(),1 ) = src;\n        }else{\n          tmp = src;\n        }\n        fwd( &dst[0],&tmp[0],nfft );\n      }else{\n        fwd( &dst[0],&src[0],nfft );\n      }\n    }\n \n    template<typename InputDerived>\n    inline\n    fft_fwd_proxy< MatrixBase<InputDerived>, FFT<T_Scalar,T_Impl> >\n    fwd( const MatrixBase<InputDerived> & src, Index nfft=-1)\n    {\n      return fft_fwd_proxy< MatrixBase<InputDerived> ,FFT<T_Scalar,T_Impl> >( src, *this,nfft );\n    }\n\n    template<typename InputDerived>\n    inline\n    fft_inv_proxy< MatrixBase<InputDerived>, FFT<T_Scalar,T_Impl> >\n    inv( const MatrixBase<InputDerived> & src, Index nfft=-1)\n    {\n      return  fft_inv_proxy< MatrixBase<InputDerived> ,FFT<T_Scalar,T_Impl> >( src, *this,nfft );\n    }\n\n    inline\n    void inv( Complex * dst, const Complex * src, Index nfft)\n    {\n      m_impl.inv( dst,src,static_cast<int>(nfft) );\n      if ( HasFlag( Unscaled ) == false)\n        scale(dst,Scalar(1./nfft),nfft); // scale the time series\n    }\n\n    inline\n    void inv( Scalar * dst, const Complex * src, Index nfft)\n    {\n      m_impl.inv( dst,src,static_cast<int>(nfft) );\n      if ( HasFlag( Unscaled ) == false)\n        scale(dst,Scalar(1./nfft),nfft); // scale the time series\n    }\n\n    template<typename OutputDerived, typename ComplexDerived>\n    inline\n    void inv( MatrixBase<OutputDerived> & dst, const MatrixBase<ComplexDerived> & src, Index nfft=-1)\n    {\n      typedef typename ComplexDerived::Scalar src_type;\n      typedef typename ComplexDerived::RealScalar real_type;\n      typedef typename OutputDerived::Scalar dst_type;\n      const bool realfft= (NumTraits<dst_type>::IsComplex == 0);\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(OutputDerived)\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(ComplexDerived)\n      EIGEN_STATIC_ASSERT_SAME_VECTOR_SIZE(ComplexDerived,OutputDerived) // size at compile-time\n      EIGEN_STATIC_ASSERT((internal::is_same<src_type, Complex>::value),\n            YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n      EIGEN_STATIC_ASSERT(int(OutputDerived::Flags)&int(ComplexDerived::Flags)&DirectAccessBit,\n            THIS_METHOD_IS_ONLY_FOR_EXPRESSIONS_WITH_DIRECT_MEMORY_ACCESS_SUCH_AS_MAP_OR_PLAIN_MATRICES)\n\n      if (nfft<1) { //automatic FFT size determination\n        if ( realfft && HasFlag(HalfSpectrum) ) \n          nfft = 2*(src.size()-1); //assume even fft size\n        else\n          nfft = src.size();\n      }\n      dst.derived().resize( nfft );\n\n      // check for nfft that does not fit the input data size\n      Index resize_input= ( realfft && HasFlag(HalfSpectrum) )\n        ? ( (nfft/2+1) - src.size() )\n        : ( nfft - src.size() );\n\n      if ( src.innerStride() != 1 || resize_input ) {\n        // if the vector is strided, then we need to copy it to a packed temporary\n        Matrix<src_type,1,Dynamic> tmp;\n        if ( resize_input ) {\n          size_t ncopy = (std::min)(src.size(),src.size() + resize_input);\n          tmp.setZero(src.size() + resize_input);\n          if ( realfft && HasFlag(HalfSpectrum) ) {\n            // pad at the Nyquist bin\n            tmp.head(ncopy) = src.head(ncopy);\n            tmp(ncopy-1) = real(tmp(ncopy-1)); // enforce real-only Nyquist bin\n          }else{\n            size_t nhead,ntail;\n            nhead = 1+ncopy/2-1; // range  [0:pi)\n            ntail = ncopy/2-1;   // range (-pi:0)\n            tmp.head(nhead) = src.head(nhead);\n            tmp.tail(ntail) = src.tail(ntail);\n            if (resize_input<0) { //shrinking -- create the Nyquist bin as the average of the two bins that fold into it\n              tmp(nhead) = ( src(nfft/2) + src( src.size() - nfft/2 ) )*real_type(.5);\n            }else{ // expanding -- split the old Nyquist bin into two halves\n              tmp(nhead) = src(nhead) * real_type(.5);\n              tmp(tmp.size()-nhead) = tmp(nhead);\n            }\n          }\n        }else{\n          tmp = src;\n        }\n        inv( &dst[0],&tmp[0], nfft);\n      }else{\n        inv( &dst[0],&src[0], nfft);\n      }\n    }\n\n    template <typename _Output>\n    inline\n    void inv( std::vector<_Output> & dst, const std::vector<Complex> & src,Index nfft=-1)\n    {\n      if (nfft<1)\n        nfft = ( NumTraits<_Output>::IsComplex == 0 && HasFlag(HalfSpectrum) ) ? 2*(src.size()-1) : src.size();\n      dst.resize( nfft );\n      inv( &dst[0],&src[0],nfft);\n    }\n\n\n    /*\n    // TODO: multi-dimensional FFTs\n    inline \n    void inv2(Complex * dst, const Complex * src, int n0,int n1)\n    {\n      m_impl.inv2(dst,src,n0,n1);\n      if ( HasFlag( Unscaled ) == false)\n          scale(dst,1./(n0*n1),n0*n1);\n    }\n  */\n\n    inline\n    impl_type & impl() {return m_impl;}\n  private:\n\n    template <typename T_Data>\n    inline\n    void scale(T_Data * x,Scalar s,Index nx)\n    {\n#if 1\n      for (int k=0;k<nx;++k)\n        *x++ *= s;\n#else\n      if ( ((ptrdiff_t)x) & 15 )\n        Matrix<T_Data, Dynamic, 1>::Map(x,nx) *= s;\n      else\n        Matrix<T_Data, Dynamic, 1>::MapAligned(x,nx) *= s;\n         //Matrix<T_Data, Dynamic, Dynamic>::Map(x,nx) * s;\n#endif  \n    }\n\n    inline\n    void ReflectSpectrum(Complex * freq, Index nfft)\n    {\n      // create the implicit right-half spectrum (conjugate-mirror of the left-half)\n      Index nhbins=(nfft>>1)+1;\n      for (Index k=nhbins;k < nfft; ++k )\n        freq[k] = conj(freq[nfft-k]);\n    }\n\n    impl_type m_impl;\n    int m_flag;\n};\n\ntemplate<typename T_SrcMat,typename T_FftIfc> \ntemplate<typename T_DestMat> inline \nvoid fft_fwd_proxy<T_SrcMat,T_FftIfc>::evalTo(T_DestMat& dst) const\n{\n    m_ifc.fwd( dst, m_src, m_nfft);\n}\n\ntemplate<typename T_SrcMat,typename T_FftIfc> \ntemplate<typename T_DestMat> inline \nvoid fft_inv_proxy<T_SrcMat,T_FftIfc>::evalTo(T_DestMat& dst) const\n{\n    m_ifc.inv( dst, m_src, m_nfft);\n}\n\n}\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/IterativeSolvers",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ITERATIVE_SOLVERS_MODULE_H\n#define EIGEN_ITERATIVE_SOLVERS_MODULE_H\n\n#include \"../../Eigen/Sparse\"\n#include \"../../Eigen/Jacobi\"\n#include \"../../Eigen/Householder\"\n\n/**\n  * \\defgroup IterativeLinearSolvers_Module Iterative solvers module\n  * This module aims to provide various iterative linear and non linear solver algorithms.\n  * It currently provides:\n  *  - a constrained conjugate gradient\n  *  - a Householder GMRES implementation\n  *  - an IDR(s) implementation\n  *  - a DGMRES implementation\n  *  - a MINRES implementation\n  * \\code\n  * #include <unsupported/Eigen/IterativeSolvers>\n  * \\endcode\n  */\n//@{\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n#ifndef EIGEN_MPL2_ONLY\n#include \"src/IterativeSolvers/IterationController.h\"\n#include \"src/IterativeSolvers/ConstrainedConjGrad.h\"\n#endif\n\n#include \"src/IterativeSolvers/IncompleteLU.h\"\n#include \"src/IterativeSolvers/GMRES.h\"\n#include \"src/IterativeSolvers/DGMRES.h\"\n//#include \"src/IterativeSolvers/SSORPreconditioner.h\"\n#include \"src/IterativeSolvers/MINRES.h\"\n#include \"src/IterativeSolvers/IDRS.h\"\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n//@}\n\n#endif // EIGEN_ITERATIVE_SOLVERS_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/KroneckerProduct",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_KRONECKER_PRODUCT_MODULE_H\n#define EIGEN_KRONECKER_PRODUCT_MODULE_H\n\n#include \"../../Eigen/Core\"\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n#include \"../../Eigen/src/SparseCore/SparseUtil.h\"\n\nnamespace Eigen {\n\n/**\n  * \\defgroup KroneckerProduct_Module KroneckerProduct module\n  *\n  * This module contains an experimental Kronecker product implementation.\n  *\n  * \\code\n  * #include <Eigen/KroneckerProduct>\n  * \\endcode\n  */\n\n} // namespace Eigen\n\n#include \"src/KroneckerProduct/KroneckerTensorProduct.h\"\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_KRONECKER_PRODUCT_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/LevenbergMarquardt",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_LEVENBERGMARQUARDT_MODULE\n#define EIGEN_LEVENBERGMARQUARDT_MODULE\n\n// #include <vector>\n\n#include \"../../Eigen/Core\"\n#include \"../../Eigen/Jacobi\"\n#include \"../../Eigen/QR\"\n#include \"NumericalDiff\"\n\n#include \"../../Eigen/SparseQR\"\n\n/**\n  * \\defgroup LevenbergMarquardt_Module Levenberg-Marquardt module\n  *\n  * \\code\n  * #include </Eigen/LevenbergMarquardt>\n  * \\endcode\n  *\n  * \n  */\n\n#include \"../../Eigen/SparseCore\"\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n\n#include \"src/LevenbergMarquardt/LMqrsolv.h\"\n#include \"src/LevenbergMarquardt/LMcovar.h\"\n#include \"src/LevenbergMarquardt/LMpar.h\"\n\n#endif\n\n#include \"src/LevenbergMarquardt/LevenbergMarquardt.h\"\n#include \"src/LevenbergMarquardt/LMonestep.h\"\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_LEVENBERGMARQUARDT_MODULE\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/MPRealSupport",
    "content": "// This file is part of a joint effort between Eigen, a lightweight C++ template library\n// for linear algebra, and MPFR C++, a C++ interface to MPFR library (http://www.holoborodko.com/pavel/)\n//\n// Copyright (C) 2010-2012 Pavel Holoborodko <pavel@holoborodko.com>\n// Copyright (C) 2010 Konstantin Holoborodko <konstantin@holoborodko.com>\n// Copyright (C) 2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MPREALSUPPORT_MODULE_H\n#define EIGEN_MPREALSUPPORT_MODULE_H\n\n#include \"../../Eigen/Core\"\n#include <mpreal.h>\n\nnamespace Eigen {\n  \n/**\n  * \\defgroup MPRealSupport_Module MPFRC++ Support module\n  * \\code\n  * #include <Eigen/MPRealSupport>\n  * \\endcode\n  *\n  * This module provides support for multi precision floating point numbers\n  * via the <a href=\"http://www.holoborodko.com/pavel/mpfr\">MPFR C++</a>\n  * library which itself is built upon <a href=\"http://www.mpfr.org/\">MPFR</a>/<a href=\"http://gmplib.org/\">GMP</a>.\n  *\n  * \\warning MPFR C++ is licensed under the GPL.\n  *\n  * You can find a copy of MPFR C++ that is known to be compatible in the unsupported/test/mpreal folder.\n  *\n  * Here is an example:\n  *\n\\code\n#include <iostream>\n#include <Eigen/MPRealSupport>\n#include <Eigen/LU>\nusing namespace mpfr;\nusing namespace Eigen;\nint main()\n{\n  // set precision to 256 bits (double has only 53 bits)\n  mpreal::set_default_prec(256);\n  // Declare matrix and vector types with multi-precision scalar type\n  typedef Matrix<mpreal,Dynamic,Dynamic>  MatrixXmp;\n  typedef Matrix<mpreal,Dynamic,1>        VectorXmp;\n\n  MatrixXmp A = MatrixXmp::Random(100,100);\n  VectorXmp b = VectorXmp::Random(100);\n\n  // Solve Ax=b using LU\n  VectorXmp x = A.lu().solve(b);\n  std::cout << \"relative error: \" << (A*x - b).norm() / b.norm() << std::endl;\n  return 0;\n}\n\\endcode\n  *\n  */\n\t\n  template<> struct NumTraits<mpfr::mpreal>\n    : GenericNumTraits<mpfr::mpreal>\n  {\n    enum {\n      IsInteger = 0,\n      IsSigned = 1,\n      IsComplex = 0,\n      RequireInitialization = 1,\n      ReadCost = HugeCost,\n      AddCost  = HugeCost,\n      MulCost  = HugeCost\n    };\n\n    typedef mpfr::mpreal Real;\n    typedef mpfr::mpreal NonInteger;\n    \n    static inline Real highest  (long Precision = mpfr::mpreal::get_default_prec()) { return  mpfr::maxval(Precision); }\n    static inline Real lowest   (long Precision = mpfr::mpreal::get_default_prec()) { return -mpfr::maxval(Precision); }\n\n    // Constants\n    static inline Real Pi      (long Precision = mpfr::mpreal::get_default_prec())  { return mpfr::const_pi(Precision);        }\n    static inline Real Euler   (long Precision = mpfr::mpreal::get_default_prec())  { return mpfr::const_euler(Precision);     }\n    static inline Real Log2    (long Precision = mpfr::mpreal::get_default_prec())  { return mpfr::const_log2(Precision);      }\n    static inline Real Catalan (long Precision = mpfr::mpreal::get_default_prec())  { return mpfr::const_catalan(Precision);   }\n\n    static inline Real epsilon (long Precision = mpfr::mpreal::get_default_prec())  { return mpfr::machine_epsilon(Precision); }\n    static inline Real epsilon (const Real& x)                                      { return mpfr::machine_epsilon(x); }\n\n#ifdef MPREAL_HAVE_DYNAMIC_STD_NUMERIC_LIMITS\n    static inline int digits10 (long Precision = mpfr::mpreal::get_default_prec())  { return std::numeric_limits<Real>::digits10(Precision); }\n    static inline int digits10 (const Real& x)                                      { return std::numeric_limits<Real>::digits10(x); }\n    \n    static inline int digits ()               { return std::numeric_limits<Real>::digits(); }\n    static inline int digits (const Real& x)  { return std::numeric_limits<Real>::digits(x); }\n#endif\n\n    static inline Real dummy_precision()\n    {\n      mpfr_prec_t weak_prec = ((mpfr::mpreal::get_default_prec()-1) * 90) / 100;\n      return mpfr::machine_epsilon(weak_prec);\n    }\n  };\n\n  namespace internal {\n\n  template<> inline mpfr::mpreal random<mpfr::mpreal>()\n  {\n    return mpfr::random();\n  }\n\n  template<> inline mpfr::mpreal random<mpfr::mpreal>(const mpfr::mpreal& a, const mpfr::mpreal& b)\n  {\n    return a + (b-a) * random<mpfr::mpreal>();\n  }\n\n  inline bool isMuchSmallerThan(const mpfr::mpreal& a, const mpfr::mpreal& b, const mpfr::mpreal& eps)\n  {\n    return mpfr::abs(a) <= mpfr::abs(b) * eps;\n  }\n\n  inline bool isApprox(const mpfr::mpreal& a, const mpfr::mpreal& b, const mpfr::mpreal& eps)\n  {\n    return mpfr::isEqualFuzzy(a,b,eps);\n  }\n\n  inline bool isApproxOrLessThan(const mpfr::mpreal& a, const mpfr::mpreal& b, const mpfr::mpreal& eps)\n  {\n    return a <= b || mpfr::isEqualFuzzy(a,b,eps);\n  }\n\n  template<> inline long double cast<mpfr::mpreal,long double>(const mpfr::mpreal& x)\n  { return x.toLDouble(); }\n\n  template<> inline double cast<mpfr::mpreal,double>(const mpfr::mpreal& x)\n  { return x.toDouble(); }\n\n  template<> inline long cast<mpfr::mpreal,long>(const mpfr::mpreal& x)\n  { return x.toLong(); }\n\n  template<> inline int cast<mpfr::mpreal,int>(const mpfr::mpreal& x)\n  { return int(x.toLong()); }\n\n  // Specialize GEBP kernel and traits for mpreal (no need for peeling, nor complicated stuff)\n  // This also permits to directly call mpfr's routines and avoid many temporaries produced by mpreal\n    template<>\n    class gebp_traits<mpfr::mpreal, mpfr::mpreal, false, false>\n    {\n    public:\n      typedef mpfr::mpreal ResScalar;\n      enum {\n        Vectorizable = false,\n        LhsPacketSize = 1,\n        RhsPacketSize = 1,\n        ResPacketSize = 1,\n        NumberOfRegisters = 1,\n        nr = 1,\n        mr = 1,\n        LhsProgress = 1,\n        RhsProgress = 1\n      };\n      typedef ResScalar LhsPacket;\n      typedef ResScalar RhsPacket;\n      typedef ResScalar ResPacket;\n      typedef LhsPacket LhsPacket4Packing;\n      \n    };\n\n\n\n    template<typename Index, typename DataMapper, bool ConjugateLhs, bool ConjugateRhs>\n    struct gebp_kernel<mpfr::mpreal,mpfr::mpreal,Index,DataMapper,1,1,ConjugateLhs,ConjugateRhs>\n    {\n      typedef mpfr::mpreal mpreal;\n\n      EIGEN_DONT_INLINE\n      void operator()(const DataMapper& res, const mpreal* blockA, const mpreal* blockB, \n                      Index rows, Index depth, Index cols, const mpreal& alpha,\n                      Index strideA=-1, Index strideB=-1, Index offsetA=0, Index offsetB=0)\n      {\n        if(rows==0 || cols==0 || depth==0)\n          return;\n\n        mpreal  acc1(0,mpfr_get_prec(blockA[0].mpfr_srcptr())),\n                tmp (0,mpfr_get_prec(blockA[0].mpfr_srcptr()));\n\n        if(strideA==-1) strideA = depth;\n        if(strideB==-1) strideB = depth;\n\n        for(Index i=0; i<rows; ++i)\n        {\n          for(Index j=0; j<cols; ++j)\n          {\n            const mpreal *A = blockA + i*strideA + offsetA;\n            const mpreal *B = blockB + j*strideB + offsetB;\n            \n            acc1 = 0;\n            for(Index k=0; k<depth; k++)\n            {\n              mpfr_mul(tmp.mpfr_ptr(), A[k].mpfr_srcptr(), B[k].mpfr_srcptr(), mpreal::get_default_rnd());\n              mpfr_add(acc1.mpfr_ptr(), acc1.mpfr_ptr(), tmp.mpfr_ptr(),  mpreal::get_default_rnd());\n            }\n            \n            mpfr_mul(acc1.mpfr_ptr(), acc1.mpfr_srcptr(), alpha.mpfr_srcptr(), mpreal::get_default_rnd());\n            mpfr_add(res(i,j).mpfr_ptr(), res(i,j).mpfr_srcptr(), acc1.mpfr_srcptr(),  mpreal::get_default_rnd());\n          }\n        }\n      }\n    };\n  } // end namespace internal\n}\n\n#endif // EIGEN_MPREALSUPPORT_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/MatrixFunctions",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Jitse Niesen <jitse@maths.leeds.ac.uk>\n// Copyright (C) 2012 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MATRIX_FUNCTIONS\n#define EIGEN_MATRIX_FUNCTIONS\n\n#include <cfloat>\n#include <list>\n\n#include \"../../Eigen/Core\"\n#include \"../../Eigen/LU\"\n#include \"../../Eigen/Eigenvalues\"\n\n/**\n  * \\defgroup MatrixFunctions_Module Matrix functions module\n  * \\brief This module aims to provide various methods for the computation of\n  * matrix functions. \n  *\n  * To use this module, add \n  * \\code\n  * #include <unsupported/Eigen/MatrixFunctions>\n  * \\endcode\n  * at the start of your source file.\n  *\n  * This module defines the following MatrixBase methods.\n  *  - \\ref matrixbase_cos \"MatrixBase::cos()\", for computing the matrix cosine\n  *  - \\ref matrixbase_cosh \"MatrixBase::cosh()\", for computing the matrix hyperbolic cosine\n  *  - \\ref matrixbase_exp \"MatrixBase::exp()\", for computing the matrix exponential\n  *  - \\ref matrixbase_log \"MatrixBase::log()\", for computing the matrix logarithm\n  *  - \\ref matrixbase_pow \"MatrixBase::pow()\", for computing the matrix power\n  *  - \\ref matrixbase_matrixfunction \"MatrixBase::matrixFunction()\", for computing general matrix functions\n  *  - \\ref matrixbase_sin \"MatrixBase::sin()\", for computing the matrix sine\n  *  - \\ref matrixbase_sinh \"MatrixBase::sinh()\", for computing the matrix hyperbolic sine\n  *  - \\ref matrixbase_sqrt \"MatrixBase::sqrt()\", for computing the matrix square root\n  *\n  * These methods are the main entry points to this module. \n  *\n  * %Matrix functions are defined as follows.  Suppose that \\f$ f \\f$\n  * is an entire function (that is, a function on the complex plane\n  * that is everywhere complex differentiable).  Then its Taylor\n  * series\n  * \\f[ f(0) + f'(0) x + \\frac{f''(0)}{2} x^2 + \\frac{f'''(0)}{3!} x^3 + \\cdots \\f]\n  * converges to \\f$ f(x) \\f$. In this case, we can define the matrix\n  * function by the same series:\n  * \\f[ f(M) = f(0) + f'(0) M + \\frac{f''(0)}{2} M^2 + \\frac{f'''(0)}{3!} M^3 + \\cdots \\f]\n  *\n  */\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n#include \"src/MatrixFunctions/MatrixExponential.h\"\n#include \"src/MatrixFunctions/MatrixFunction.h\"\n#include \"src/MatrixFunctions/MatrixSquareRoot.h\"\n#include \"src/MatrixFunctions/MatrixLogarithm.h\"\n#include \"src/MatrixFunctions/MatrixPower.h\"\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n\n/** \n\\page matrixbaseextra_page\n\\ingroup MatrixFunctions_Module\n\n\\section matrixbaseextra MatrixBase methods defined in the MatrixFunctions module\n\nThe remainder of the page documents the following MatrixBase methods\nwhich are defined in the MatrixFunctions module.\n\n\n\n\\subsection matrixbase_cos MatrixBase::cos()\n\nCompute the matrix cosine.\n\n\\code\nconst MatrixFunctionReturnValue<Derived> MatrixBase<Derived>::cos() const\n\\endcode\n\n\\param[in]  M  a square matrix.\n\\returns  expression representing \\f$ \\cos(M) \\f$.\n\nThis function computes the matrix cosine. Use ArrayBase::cos() for computing the entry-wise cosine.\n\nThe implementation calls \\ref matrixbase_matrixfunction \"matrixFunction()\" with StdStemFunctions::cos().\n\n\\sa \\ref matrixbase_sin \"sin()\" for an example.\n\n\n\n\\subsection matrixbase_cosh MatrixBase::cosh()\n\nCompute the matrix hyberbolic cosine.\n\n\\code\nconst MatrixFunctionReturnValue<Derived> MatrixBase<Derived>::cosh() const\n\\endcode\n\n\\param[in]  M  a square matrix.\n\\returns  expression representing \\f$ \\cosh(M) \\f$\n\nThis function calls \\ref matrixbase_matrixfunction \"matrixFunction()\" with StdStemFunctions::cosh().\n\n\\sa \\ref matrixbase_sinh \"sinh()\" for an example.\n\n\n\n\\subsection matrixbase_exp MatrixBase::exp()\n\nCompute the matrix exponential.\n\n\\code\nconst MatrixExponentialReturnValue<Derived> MatrixBase<Derived>::exp() const\n\\endcode\n\n\\param[in]  M  matrix whose exponential is to be computed.\n\\returns    expression representing the matrix exponential of \\p M.\n\nThe matrix exponential of \\f$ M \\f$ is defined by\n\\f[ \\exp(M) = \\sum_{k=0}^\\infty \\frac{M^k}{k!}. \\f]\nThe matrix exponential can be used to solve linear ordinary\ndifferential equations: the solution of \\f$ y' = My \\f$ with the\ninitial condition \\f$ y(0) = y_0 \\f$ is given by\n\\f$ y(t) = \\exp(M) y_0 \\f$.\n\nThe matrix exponential is different from applying the exp function to all the entries in the matrix.\nUse ArrayBase::exp() if you want to do the latter.\n\nThe cost of the computation is approximately \\f$ 20 n^3 \\f$ for\nmatrices of size \\f$ n \\f$. The number 20 depends weakly on the\nnorm of the matrix.\n\nThe matrix exponential is computed using the scaling-and-squaring\nmethod combined with Pad&eacute; approximation. The matrix is first\nrescaled, then the exponential of the reduced matrix is computed\napproximant, and then the rescaling is undone by repeated\nsquaring. The degree of the Pad&eacute; approximant is chosen such\nthat the approximation error is less than the round-off\nerror. However, errors may accumulate during the squaring phase.\n\nDetails of the algorithm can be found in: Nicholas J. Higham, \"The\nscaling and squaring method for the matrix exponential revisited,\"\n<em>SIAM J. %Matrix Anal. Applic.</em>, <b>26</b>:1179&ndash;1193,\n2005.\n\nExample: The following program checks that\n\\f[ \\exp \\left[ \\begin{array}{ccc}\n      0 & \\frac14\\pi & 0 \\\\\n      -\\frac14\\pi & 0 & 0 \\\\\n      0 & 0 & 0\n    \\end{array} \\right] = \\left[ \\begin{array}{ccc}\n      \\frac12\\sqrt2 & -\\frac12\\sqrt2 & 0 \\\\\n      \\frac12\\sqrt2 & \\frac12\\sqrt2 & 0 \\\\\n      0 & 0 & 1\n    \\end{array} \\right]. \\f]\nThis corresponds to a rotation of \\f$ \\frac14\\pi \\f$ radians around\nthe z-axis.\n\n\\include MatrixExponential.cpp\nOutput: \\verbinclude MatrixExponential.out\n\n\\note \\p M has to be a matrix of \\c float, \\c double, `long double`\n\\c complex<float>, \\c complex<double>, or `complex<long double>` .\n\n\n\\subsection matrixbase_log MatrixBase::log()\n\nCompute the matrix logarithm.\n\n\\code\nconst MatrixLogarithmReturnValue<Derived> MatrixBase<Derived>::log() const\n\\endcode\n\n\\param[in]  M  invertible matrix whose logarithm is to be computed.\n\\returns    expression representing the matrix logarithm root of \\p M.\n\nThe matrix logarithm of \\f$ M \\f$ is a matrix \\f$ X \\f$ such that \n\\f$ \\exp(X) = M \\f$ where exp denotes the matrix exponential. As for\nthe scalar logarithm, the equation \\f$ \\exp(X) = M \\f$ may have\nmultiple solutions; this function returns a matrix whose eigenvalues\nhave imaginary part in the interval \\f$ (-\\pi,\\pi] \\f$.\n\nThe matrix logarithm is different from applying the log function to all the entries in the matrix.\nUse ArrayBase::log() if you want to do the latter.\n\nIn the real case, the matrix \\f$ M \\f$ should be invertible and\nit should have no eigenvalues which are real and negative (pairs of\ncomplex conjugate eigenvalues are allowed). In the complex case, it\nonly needs to be invertible.\n\nThis function computes the matrix logarithm using the Schur-Parlett\nalgorithm as implemented by MatrixBase::matrixFunction(). The\nlogarithm of an atomic block is computed by MatrixLogarithmAtomic,\nwhich uses direct computation for 1-by-1 and 2-by-2 blocks and an\ninverse scaling-and-squaring algorithm for bigger blocks, with the\nsquare roots computed by MatrixBase::sqrt().\n\nDetails of the algorithm can be found in Section 11.6.2 of:\nNicholas J. Higham,\n<em>Functions of Matrices: Theory and Computation</em>,\nSIAM 2008. ISBN 978-0-898716-46-7.\n\nExample: The following program checks that\n\\f[ \\log \\left[ \\begin{array}{ccc} \n      \\frac12\\sqrt2 & -\\frac12\\sqrt2 & 0 \\\\\n      \\frac12\\sqrt2 & \\frac12\\sqrt2 & 0 \\\\\n      0 & 0 & 1\n    \\end{array} \\right] = \\left[ \\begin{array}{ccc}\n      0 & \\frac14\\pi & 0 \\\\ \n      -\\frac14\\pi & 0 & 0 \\\\\n      0 & 0 & 0 \n    \\end{array} \\right]. \\f]\nThis corresponds to a rotation of \\f$ \\frac14\\pi \\f$ radians around\nthe z-axis. This is the inverse of the example used in the\ndocumentation of \\ref matrixbase_exp \"exp()\".\n\n\\include MatrixLogarithm.cpp\nOutput: \\verbinclude MatrixLogarithm.out\n\n\\note \\p M has to be a matrix of \\c float, \\c double, `long\ndouble`, \\c complex<float>, \\c complex<double>, or `complex<long double>`.\n\n\\sa MatrixBase::exp(), MatrixBase::matrixFunction(), \n    class MatrixLogarithmAtomic, MatrixBase::sqrt().\n\n\n\\subsection matrixbase_pow MatrixBase::pow()\n\nCompute the matrix raised to arbitrary real power.\n\n\\code\nconst MatrixPowerReturnValue<Derived> MatrixBase<Derived>::pow(RealScalar p) const\n\\endcode\n\n\\param[in]  M  base of the matrix power, should be a square matrix.\n\\param[in]  p  exponent of the matrix power.\n\nThe matrix power \\f$ M^p \\f$ is defined as \\f$ \\exp(p \\log(M)) \\f$,\nwhere exp denotes the matrix exponential, and log denotes the matrix\nlogarithm. This is different from raising all the entries in the matrix\nto the p-th power. Use ArrayBase::pow() if you want to do the latter.\n\nIf \\p p is complex, the scalar type of \\p M should be the type of \\p\np . \\f$ M^p \\f$ simply evaluates into \\f$ \\exp(p \\log(M)) \\f$.\nTherefore, the matrix \\f$ M \\f$ should meet the conditions to be an\nargument of matrix logarithm.\n\nIf \\p p is real, it is casted into the real scalar type of \\p M. Then\nthis function computes the matrix power using the Schur-Pad&eacute;\nalgorithm as implemented by class MatrixPower. The exponent is split\ninto integral part and fractional part, where the fractional part is\nin the interval \\f$ (-1, 1) \\f$. The main diagonal and the first\nsuper-diagonal is directly computed.\n\nIf \\p M is singular with a semisimple zero eigenvalue and \\p p is\npositive, the Schur factor \\f$ T \\f$ is reordered with Givens\nrotations, i.e.\n\n\\f[ T = \\left[ \\begin{array}{cc}\n      T_1 & T_2 \\\\\n      0   & 0\n    \\end{array} \\right] \\f]\n\nwhere \\f$ T_1 \\f$ is invertible. Then \\f$ T^p \\f$ is given by\n\n\\f[ T^p = \\left[ \\begin{array}{cc}\n      T_1^p & T_1^{-1} T_1^p T_2 \\\\\n      0     & 0\n    \\end{array}. \\right] \\f]\n\n\\warning Fractional power of a matrix with a non-semisimple zero\neigenvalue is not well-defined. We introduce an assertion failure\nagainst inaccurate result, e.g. \\code\n#include <unsupported/Eigen/MatrixFunctions>\n#include <iostream>\n\nint main()\n{\n  Eigen::Matrix4d A;\n  A << 0, 0, 2, 3,\n       0, 0, 4, 5,\n       0, 0, 6, 7,\n       0, 0, 8, 9;\n  std::cout << A.pow(0.37) << std::endl;\n  \n  // The 1 makes eigenvalue 0 non-semisimple.\n  A.coeffRef(0, 1) = 1;\n\n  // This fails if EIGEN_NO_DEBUG is undefined.\n  std::cout << A.pow(0.37) << std::endl;\n\n  return 0;\n}\n\\endcode\n\nDetails of the algorithm can be found in: Nicholas J. Higham and\nLijing Lin, \"A Schur-Pad&eacute; algorithm for fractional powers of a\nmatrix,\" <em>SIAM J. %Matrix Anal. Applic.</em>,\n<b>32(3)</b>:1056&ndash;1078, 2011.\n\nExample: The following program checks that\n\\f[ \\left[ \\begin{array}{ccc}\n      \\cos1 & -\\sin1 & 0 \\\\\n      \\sin1 & \\cos1 & 0 \\\\\n      0 & 0 & 1\n    \\end{array} \\right]^{\\frac14\\pi} = \\left[ \\begin{array}{ccc}\n      \\frac12\\sqrt2 & -\\frac12\\sqrt2 & 0 \\\\\n      \\frac12\\sqrt2 & \\frac12\\sqrt2 & 0 \\\\\n      0 & 0 & 1\n    \\end{array} \\right]. \\f]\nThis corresponds to \\f$ \\frac14\\pi \\f$ rotations of 1 radian around\nthe z-axis.\n\n\\include MatrixPower.cpp\nOutput: \\verbinclude MatrixPower.out\n\nMatrixBase::pow() is user-friendly. However, there are some\ncircumstances under which you should use class MatrixPower directly.\nMatrixPower can save the result of Schur decomposition, so it's\nbetter for computing various powers for the same matrix.\n\nExample:\n\\include MatrixPower_optimal.cpp\nOutput: \\verbinclude MatrixPower_optimal.out\n\n\\note \\p M has to be a matrix of \\c float, \\c double, `long\ndouble`, \\c complex<float>, \\c complex<double>, or\n\\c complex<long double> .\n\n\\sa MatrixBase::exp(), MatrixBase::log(), class MatrixPower.\n\n\n\\subsection matrixbase_matrixfunction MatrixBase::matrixFunction()\n\nCompute a matrix function.\n\n\\code\nconst MatrixFunctionReturnValue<Derived> MatrixBase<Derived>::matrixFunction(typename internal::stem_function<typename internal::traits<Derived>::Scalar>::type f) const\n\\endcode\n\n\\param[in]  M  argument of matrix function, should be a square matrix.\n\\param[in]  f  an entire function; \\c f(x,n) should compute the n-th\nderivative of f at x.\n\\returns  expression representing \\p f applied to \\p M.\n\nSuppose that \\p M is a matrix whose entries have type \\c Scalar. \nThen, the second argument, \\p f, should be a function with prototype\n\\code \nComplexScalar f(ComplexScalar, int) \n\\endcode\nwhere \\c ComplexScalar = \\c std::complex<Scalar> if \\c Scalar is\nreal (e.g., \\c float or \\c double) and \\c ComplexScalar =\n\\c Scalar if \\c Scalar is complex. The return value of \\c f(x,n)\nshould be \\f$ f^{(n)}(x) \\f$, the n-th derivative of f at x.\n\nThis routine uses the algorithm described in:\nPhilip Davies and Nicholas J. Higham, \n\"A Schur-Parlett algorithm for computing matrix functions\", \n<em>SIAM J. %Matrix Anal. Applic.</em>, <b>25</b>:464&ndash;485, 2003.\n\nThe actual work is done by the MatrixFunction class.\n\nExample: The following program checks that\n\\f[ \\exp \\left[ \\begin{array}{ccc} \n      0 & \\frac14\\pi & 0 \\\\ \n      -\\frac14\\pi & 0 & 0 \\\\\n      0 & 0 & 0 \n    \\end{array} \\right] = \\left[ \\begin{array}{ccc}\n      \\frac12\\sqrt2 & -\\frac12\\sqrt2 & 0 \\\\\n      \\frac12\\sqrt2 & \\frac12\\sqrt2 & 0 \\\\\n      0 & 0 & 1\n    \\end{array} \\right]. \\f]\nThis corresponds to a rotation of \\f$ \\frac14\\pi \\f$ radians around\nthe z-axis. This is the same example as used in the documentation\nof \\ref matrixbase_exp \"exp()\".\n\n\\include MatrixFunction.cpp\nOutput: \\verbinclude MatrixFunction.out\n\nNote that the function \\c expfn is defined for complex numbers \n\\c x, even though the matrix \\c A is over the reals. Instead of\n\\c expfn, we could also have used StdStemFunctions::exp:\n\\code\nA.matrixFunction(StdStemFunctions<std::complex<double> >::exp, &B);\n\\endcode\n\n\n\n\\subsection matrixbase_sin MatrixBase::sin()\n\nCompute the matrix sine.\n\n\\code\nconst MatrixFunctionReturnValue<Derived> MatrixBase<Derived>::sin() const\n\\endcode\n\n\\param[in]  M  a square matrix.\n\\returns  expression representing \\f$ \\sin(M) \\f$.\n\nThis function computes the matrix sine. Use ArrayBase::sin() for computing the entry-wise sine.\n\nThe implementation calls \\ref matrixbase_matrixfunction \"matrixFunction()\" with StdStemFunctions::sin().\n\nExample: \\include MatrixSine.cpp\nOutput: \\verbinclude MatrixSine.out\n\n\n\n\\subsection matrixbase_sinh MatrixBase::sinh()\n\nCompute the matrix hyperbolic sine.\n\n\\code\nMatrixFunctionReturnValue<Derived> MatrixBase<Derived>::sinh() const\n\\endcode\n\n\\param[in]  M  a square matrix.\n\\returns  expression representing \\f$ \\sinh(M) \\f$\n\nThis function calls \\ref matrixbase_matrixfunction \"matrixFunction()\" with StdStemFunctions::sinh().\n\nExample: \\include MatrixSinh.cpp\nOutput: \\verbinclude MatrixSinh.out\n\n\n\\subsection matrixbase_sqrt MatrixBase::sqrt()\n\nCompute the matrix square root.\n\n\\code\nconst MatrixSquareRootReturnValue<Derived> MatrixBase<Derived>::sqrt() const\n\\endcode\n\n\\param[in]  M  invertible matrix whose square root is to be computed.\n\\returns    expression representing the matrix square root of \\p M.\n\nThe matrix square root of \\f$ M \\f$ is the matrix \\f$ M^{1/2} \\f$\nwhose square is the original matrix; so if \\f$ S = M^{1/2} \\f$ then\n\\f$ S^2 = M \\f$. This is different from taking the square root of all\nthe entries in the matrix; use ArrayBase::sqrt() if you want to do the\nlatter.\n\nIn the <b>real case</b>, the matrix \\f$ M \\f$ should be invertible and\nit should have no eigenvalues which are real and negative (pairs of\ncomplex conjugate eigenvalues are allowed). In that case, the matrix\nhas a square root which is also real, and this is the square root\ncomputed by this function. \n\nThe matrix square root is computed by first reducing the matrix to\nquasi-triangular form with the real Schur decomposition. The square\nroot of the quasi-triangular matrix can then be computed directly. The\ncost is approximately \\f$ 25 n^3 \\f$ real flops for the real Schur\ndecomposition and \\f$ 3\\frac13 n^3 \\f$ real flops for the remainder\n(though the computation time in practice is likely more than this\nindicates).\n\nDetails of the algorithm can be found in: Nicholas J. Highan,\n\"Computing real square roots of a real matrix\", <em>Linear Algebra\nAppl.</em>, 88/89:405&ndash;430, 1987.\n\nIf the matrix is <b>positive-definite symmetric</b>, then the square\nroot is also positive-definite symmetric. In this case, it is best to\nuse SelfAdjointEigenSolver::operatorSqrt() to compute it.\n\nIn the <b>complex case</b>, the matrix \\f$ M \\f$ should be invertible;\nthis is a restriction of the algorithm. The square root computed by\nthis algorithm is the one whose eigenvalues have an argument in the\ninterval \\f$ (-\\frac12\\pi, \\frac12\\pi] \\f$. This is the usual branch\ncut.\n\nThe computation is the same as in the real case, except that the\ncomplex Schur decomposition is used to reduce the matrix to a\ntriangular matrix. The theoretical cost is the same. Details are in:\n&Aring;ke Bj&ouml;rck and Sven Hammarling, \"A Schur method for the\nsquare root of a matrix\", <em>Linear Algebra Appl.</em>,\n52/53:127&ndash;140, 1983.\n\nExample: The following program checks that the square root of\n\\f[ \\left[ \\begin{array}{cc} \n              \\cos(\\frac13\\pi) & -\\sin(\\frac13\\pi) \\\\\n              \\sin(\\frac13\\pi) & \\cos(\\frac13\\pi)\n    \\end{array} \\right], \\f]\ncorresponding to a rotation over 60 degrees, is a rotation over 30 degrees:\n\\f[ \\left[ \\begin{array}{cc} \n              \\cos(\\frac16\\pi) & -\\sin(\\frac16\\pi) \\\\\n              \\sin(\\frac16\\pi) & \\cos(\\frac16\\pi)\n    \\end{array} \\right]. \\f]\n\n\\include MatrixSquareRoot.cpp\nOutput: \\verbinclude MatrixSquareRoot.out\n\n\\sa class RealSchur, class ComplexSchur, class MatrixSquareRoot,\n    SelfAdjointEigenSolver::operatorSqrt().\n\n*/\n\n#endif // EIGEN_MATRIX_FUNCTIONS\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/MoreVectorization",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MOREVECTORIZATION_MODULE_H\n#define EIGEN_MOREVECTORIZATION_MODULE_H\n\n#include \"../../Eigen/Core\"\n\nnamespace Eigen {\n\n/**\n  * \\defgroup MoreVectorization More vectorization module\n  */\n\n}\n\n#include \"src/MoreVectorization/MathFunctions.h\"\n\n#endif // EIGEN_MOREVECTORIZATION_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/NonLinearOptimization",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_NONLINEAROPTIMIZATION_MODULE\n#define EIGEN_NONLINEAROPTIMIZATION_MODULE\n\n#include <vector>\n\n#include \"../../Eigen/Core\"\n#include \"../../Eigen/Jacobi\"\n#include \"../../Eigen/QR\"\n#include \"NumericalDiff\"\n\n/**\n  * \\defgroup NonLinearOptimization_Module Non linear optimization module\n  *\n  * \\code\n  * #include <unsupported/Eigen/NonLinearOptimization>\n  * \\endcode\n  *\n  * This module provides implementation of two important algorithms in non linear\n  * optimization. In both cases, we consider a system of non linear functions. Of\n  * course, this should work, and even work very well if those functions are\n  * actually linear. But if this is so, you should probably better use other\n  * methods more fitted to this special case.\n  *\n  * One algorithm allows to find a least-squares solution of such a system\n  * (Levenberg-Marquardt algorithm) and the second one is used to find \n  * a zero for the system (Powell hybrid \"dogleg\" method).\n  *\n  * This code is a port of minpack (http://en.wikipedia.org/wiki/MINPACK).\n  * Minpack is a very famous, old, robust and well renowned package, written in\n  * fortran. Those implementations have been carefully tuned, tested, and used\n  * for several decades.\n  *\n  * The original fortran code was automatically translated using f2c (http://en.wikipedia.org/wiki/F2c) in C,\n  * then c++, and then cleaned by several different authors.\n  * The last one of those cleanings being our starting point : \n  * http://devernay.free.fr/hacks/cminpack.html\n  * \n  * Finally, we ported this code to Eigen, creating classes and API\n  * coherent with Eigen. When possible, we switched to Eigen\n  * implementation, such as most linear algebra (vectors, matrices, stable norms).\n  *\n  * Doing so, we were very careful to check the tests we setup at the very\n  * beginning, which ensure that the same results are found.\n  *\n  * \\section Tests Tests\n  * \n  * The tests are placed in the file unsupported/test/NonLinear.cpp.\n  * \n  * There are two kinds of tests : those that come from examples bundled with cminpack.\n  * They guaranty we get the same results as the original algorithms (value for 'x',\n  * for the number of evaluations of the function, and for the number of evaluations\n  * of the Jacobian if ever).\n  * \n  * Other tests were added by myself at the very beginning of the \n  * process and check the results for Levenberg-Marquardt using the reference data \n  * on http://www.itl.nist.gov/div898/strd/nls/nls_main.shtml. Since then i've \n  * carefully checked that the same results were obtained when modifying the\n  * code. Please note that we do not always get the exact same decimals as they do,\n  * but this is ok : they use 128bits float, and we do the tests using the C type 'double',\n  * which is 64 bits on most platforms (x86 and amd64, at least).\n  * I've performed those tests on several other implementations of Levenberg-Marquardt, and\n  * (c)minpack performs VERY well compared to those, both in accuracy and speed.\n  * \n  * The documentation for running the tests is on the wiki\n  * http://eigen.tuxfamily.org/index.php?title=Tests\n  * \n  * \\section API API: overview of methods\n  * \n  * Both algorithms needs a functor computing the Jacobian. It can be computed by\n  * hand, using auto-differentiation (see \\ref AutoDiff_Module), or using numerical\n  * differences (see \\ref NumericalDiff_Module). For instance:\n  *\\code\n  * MyFunc func;\n  * NumericalDiff<MyFunc> func_with_num_diff(func);\n  * LevenbergMarquardt<NumericalDiff<MyFunc> > lm(func_with_num_diff);\n  * \\endcode\n  * For HybridNonLinearSolver, the method solveNumericalDiff() does the above wrapping for\n  * you.\n  * \n  * The methods LevenbergMarquardt.lmder1()/lmdif1()/lmstr1() and \n  * HybridNonLinearSolver.hybrj1()/hybrd1() are specific methods from the original \n  * minpack package that you probably should NOT use until you are porting a code that\n  * was previously using minpack. They just define a 'simple' API with default values \n  * for some parameters.\n  * \n  * All algorithms are provided using two APIs :\n  *     - one where the user inits the algorithm, and uses '*OneStep()' as much as he wants : \n  * this way the caller have control over the steps\n  *     - one where the user just calls a method (optimize() or solve()) which will \n  * handle the loop: init + loop until a stop condition is met. Those are provided for\n  *  convenience.\n  * \n  * As an example, the method LevenbergMarquardt::minimize() is \n  * implemented as follow: \n  * \\code\n  * Status LevenbergMarquardt<FunctorType,Scalar>::minimize(FVectorType  &x, const int mode)\n  * {\n  *     Status status = minimizeInit(x, mode);\n  *     do {\n  *         status = minimizeOneStep(x, mode);\n  *     } while (status==Running);\n  *     return status;\n  * }\n  * \\endcode\n  * \n  * \\section examples Examples\n  * \n  * The easiest way to understand how to use this module is by looking at the many examples in the file\n  * unsupported/test/NonLinearOptimization.cpp.\n  */\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n\n#include \"src/NonLinearOptimization/qrsolv.h\"\n#include \"src/NonLinearOptimization/r1updt.h\"\n#include \"src/NonLinearOptimization/r1mpyq.h\"\n#include \"src/NonLinearOptimization/rwupdt.h\"\n#include \"src/NonLinearOptimization/fdjac1.h\"\n#include \"src/NonLinearOptimization/lmpar.h\"\n#include \"src/NonLinearOptimization/dogleg.h\"\n#include \"src/NonLinearOptimization/covar.h\"\n\n#include \"src/NonLinearOptimization/chkder.h\"\n\n#endif\n\n#include \"src/NonLinearOptimization/HybridNonLinearSolver.h\"\n#include \"src/NonLinearOptimization/LevenbergMarquardt.h\"\n\n\n#endif // EIGEN_NONLINEAROPTIMIZATION_MODULE\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/NumericalDiff",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_NUMERICALDIFF_MODULE\n#define EIGEN_NUMERICALDIFF_MODULE\n\n#include \"../../Eigen/Core\"\n\nnamespace Eigen {\n\n/**\n  * \\defgroup NumericalDiff_Module Numerical differentiation module\n  *\n  * \\code\n  * #include <unsupported/Eigen/NumericalDiff>\n  * \\endcode\n  *\n  * See http://en.wikipedia.org/wiki/Numerical_differentiation\n  *\n  * Warning : this should NOT be confused with automatic differentiation, which\n  * is a different method and has its own module in Eigen : \\ref\n  * AutoDiff_Module.\n  *\n  * Currently only \"Forward\" and \"Central\" schemes are implemented. Those\n  * are basic methods, and there exist some more elaborated way of\n  * computing such approximates. They are implemented using both\n  * proprietary and free software, and usually requires linking to an\n  * external library. It is very easy for you to write a functor\n  * using such software, and the purpose is quite orthogonal to what we\n  * want to achieve with Eigen.\n  *\n  * This is why we will not provide wrappers for every great numerical\n  * differentiation software that exist, but should rather stick with those\n  * basic ones, that still are useful for testing.\n  *\n  * Also, the \\ref NonLinearOptimization_Module needs this in order to\n  * provide full features compatibility with the original (c)minpack\n  * package.\n  *\n  */\n}\n\n//@{\n\n#include \"src/NumericalDiff/NumericalDiff.h\"\n\n//@}\n\n\n#endif // EIGEN_NUMERICALDIFF_MODULE\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/OpenGLSupport",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_OPENGL_MODULE\n#define EIGEN_OPENGL_MODULE\n\n#include \"../../Eigen/Geometry\"\n\n#if defined(__APPLE_CC__)\n  #include <OpenGL/gl.h>\n#else\n  #include <GL/gl.h>\n#endif\n\nnamespace Eigen {\n\n/**\n  * \\defgroup OpenGLSUpport_Module OpenGL Support module\n  *\n  * This module provides wrapper functions for a couple of OpenGL functions\n  * which simplify the way to pass Eigen's object to openGL.\n  * Here is an example:\n  * \n  * \\code\n  * // You need to add path_to_eigen/unsupported to your include path.\n  * #include <Eigen/OpenGLSupport>\n  * // ...\n  * Vector3f x, y;\n  * Matrix3f rot;\n  * \n  * glVertex(y + x * rot);\n  * \n  * Quaternion q;\n  * glRotate(q);\n  * \n  * // ...\n  * \\endcode\n  *\n  */\n//@{\n\n#define EIGEN_GL_FUNC_DECLARATION(FUNC)                                                                             \\\nnamespace internal {                                                                                                \\\n  template< typename XprType,                                                                                       \\\n            typename Scalar = typename XprType::Scalar,                                                             \\\n            int Rows = XprType::RowsAtCompileTime,                                                                  \\\n            int Cols = XprType::ColsAtCompileTime,                                                                  \\\n            bool IsGLCompatible = bool(internal::evaluator<XprType>::Flags&LinearAccessBit)                         \\\n                              && bool(XprType::Flags&DirectAccessBit)                                               \\\n                              && (XprType::IsVectorAtCompileTime || (XprType::Flags&RowMajorBit)==0)>               \\\n  struct EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl);                                                                      \\\n                                                                                                                    \\\n  template<typename XprType, typename Scalar, int Rows, int Cols>                                                   \\\n  struct EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl)<XprType,Scalar,Rows,Cols,false> {                                     \\\n    inline static void run(const XprType& p) {                                                                      \\\n      EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl)<typename plain_matrix_type_column_major<XprType>::type>::run(p); }       \\\n  };                                                                                                                \\\n}                                                                                                                   \\\n                                                                                                                    \\\ntemplate<typename Derived> inline void FUNC(const Eigen::DenseBase<Derived>& p) {                                   \\\n  EIGEN_CAT(EIGEN_CAT(internal::gl_,FUNC),_impl)<Derived>::run(p.derived());                                        \\\n}\n\n\n#define EIGEN_GL_FUNC_SPECIALIZATION_MAT(FUNC,SCALAR,ROWS,COLS,SUFFIX)                                              \\\nnamespace internal {                                                                                                \\\n  template< typename XprType> struct EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl)<XprType, SCALAR, ROWS, COLS, true> {      \\\n    inline static void run(const XprType& p) { FUNC##SUFFIX(p.data()); }                                            \\\n  };                                                                                                                \\\n}\n\n  \n#define EIGEN_GL_FUNC_SPECIALIZATION_VEC(FUNC,SCALAR,SIZE,SUFFIX)                                                   \\\nnamespace internal {                                                                                                \\\n  template< typename XprType> struct EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl)<XprType, SCALAR, SIZE, 1, true> {         \\\n    inline static void run(const XprType& p) { FUNC##SUFFIX(p.data()); }                                            \\\n  };                                                                                                                \\\n  template< typename XprType> struct EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl)<XprType, SCALAR, 1, SIZE, true> {         \\\n    inline static void run(const XprType& p) { FUNC##SUFFIX(p.data()); }                                            \\\n  };                                                                                                                \\\n}\n\n  \nEIGEN_GL_FUNC_DECLARATION       (glVertex)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,int,    2,2iv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,short,  2,2sv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,float,  2,2fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,double, 2,2dv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,int,    3,3iv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,short,  3,3sv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,float,  3,3fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,double, 3,3dv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,int,    4,4iv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,short,  4,4sv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,float,  4,4fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glVertex,double, 4,4dv)\n\nEIGEN_GL_FUNC_DECLARATION       (glTexCoord)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,int,    2,2iv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,short,  2,2sv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,float,  2,2fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,double, 2,2dv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,int,    3,3iv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,short,  3,3sv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,float,  3,3fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,double, 3,3dv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,int,    4,4iv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,short,  4,4sv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,float,  4,4fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTexCoord,double, 4,4dv)\n\nEIGEN_GL_FUNC_DECLARATION       (glColor)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,int,    2,2iv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,short,  2,2sv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,float,  2,2fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,double, 2,2dv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,int,    3,3iv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,short,  3,3sv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,float,  3,3fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,double, 3,3dv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,int,    4,4iv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,short,  4,4sv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,float,  4,4fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glColor,double, 4,4dv)\n\nEIGEN_GL_FUNC_DECLARATION       (glNormal)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glNormal,int,    3,3iv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glNormal,short,  3,3sv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glNormal,float,  3,3fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glNormal,double, 3,3dv)\n\ninline void glScale2fv(const float*  v) { glScalef(v[0], v[1], 1.f);  }\ninline void glScale2dv(const double* v) { glScaled(v[0], v[1], 1.0);  }\ninline void glScale3fv(const float*  v) { glScalef(v[0], v[1], v[2]); }\ninline void glScale3dv(const double* v) { glScaled(v[0], v[1], v[2]); }\n\nEIGEN_GL_FUNC_DECLARATION       (glScale)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glScale,float,  2,2fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glScale,double, 2,2dv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glScale,float,  3,3fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glScale,double, 3,3dv)\n\ntemplate<typename Scalar> void glScale(const UniformScaling<Scalar>& s)  { glScale(Matrix<Scalar,3,1>::Constant(s.factor())); }\n\ninline void glTranslate2fv(const float*  v) { glTranslatef(v[0], v[1], 0.f);  }\ninline void glTranslate2dv(const double* v) { glTranslated(v[0], v[1], 0.0);  }\ninline void glTranslate3fv(const float*  v) { glTranslatef(v[0], v[1], v[2]); }\ninline void glTranslate3dv(const double* v) { glTranslated(v[0], v[1], v[2]); }\n\nEIGEN_GL_FUNC_DECLARATION       (glTranslate)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTranslate,float,  2,2fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTranslate,double, 2,2dv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTranslate,float,  3,3fv)\nEIGEN_GL_FUNC_SPECIALIZATION_VEC(glTranslate,double, 3,3dv)\n\ntemplate<typename Scalar> void glTranslate(const Translation<Scalar,2>& t)  { glTranslate(t.vector()); }\ntemplate<typename Scalar> void glTranslate(const Translation<Scalar,3>& t)  { glTranslate(t.vector()); }\n\nEIGEN_GL_FUNC_DECLARATION       (glMultMatrix)\nEIGEN_GL_FUNC_SPECIALIZATION_MAT(glMultMatrix,float,  4,4,f)\nEIGEN_GL_FUNC_SPECIALIZATION_MAT(glMultMatrix,double, 4,4,d)\n\ntemplate<typename Scalar> void glMultMatrix(const Transform<Scalar,3,Affine>& t)        { glMultMatrix(t.matrix()); }\ntemplate<typename Scalar> void glMultMatrix(const Transform<Scalar,3,Projective>& t)    { glMultMatrix(t.matrix()); }\ntemplate<typename Scalar> void glMultMatrix(const Transform<Scalar,3,AffineCompact>& t) { glMultMatrix(Transform<Scalar,3,Affine>(t).matrix()); }\n\nEIGEN_GL_FUNC_DECLARATION       (glLoadMatrix)\nEIGEN_GL_FUNC_SPECIALIZATION_MAT(glLoadMatrix,float,  4,4,f)\nEIGEN_GL_FUNC_SPECIALIZATION_MAT(glLoadMatrix,double, 4,4,d)\n\ntemplate<typename Scalar> void glLoadMatrix(const Transform<Scalar,3,Affine>& t)        { glLoadMatrix(t.matrix()); }\ntemplate<typename Scalar> void glLoadMatrix(const Transform<Scalar,3,Projective>& t)    { glLoadMatrix(t.matrix()); }\ntemplate<typename Scalar> void glLoadMatrix(const Transform<Scalar,3,AffineCompact>& t) { glLoadMatrix(Transform<Scalar,3,Affine>(t).matrix()); }\n\ninline void glRotate(const Rotation2D<float>& rot)\n{\n  glRotatef(rot.angle()*180.f/float(EIGEN_PI), 0.f, 0.f, 1.f);\n}\ninline void glRotate(const Rotation2D<double>& rot)\n{\n  glRotated(rot.angle()*180.0/double(EIGEN_PI), 0.0, 0.0, 1.0);\n}\n\ntemplate<typename Derived> void glRotate(const RotationBase<Derived,3>& rot)\n{  \n  Transform<typename Derived::Scalar,3,Projective> tr(rot);\n  glMultMatrix(tr.matrix());\n}\n\n#define EIGEN_GL_MAKE_CONST_const const\n#define EIGEN_GL_MAKE_CONST__ \n#define EIGEN_GL_EVAL(X) X\n\n#define EIGEN_GL_FUNC1_DECLARATION(FUNC,ARG1,CONST)                                                                             \\\nnamespace internal {                                                                                                            \\\n  template< typename XprType,                                                                                                   \\\n            typename Scalar = typename XprType::Scalar,                                                                         \\\n            int Rows = XprType::RowsAtCompileTime,                                                                              \\\n            int Cols = XprType::ColsAtCompileTime,                                                                              \\\n            bool IsGLCompatible = bool(internal::evaluator<XprType>::Flags&LinearAccessBit)                                     \\\n                              && bool(XprType::Flags&DirectAccessBit)                                                           \\\n                              && (XprType::IsVectorAtCompileTime || (XprType::Flags&RowMajorBit)==0)>                           \\\n  struct EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl);                                                                                  \\\n                                                                                                                                \\\n  template<typename XprType, typename Scalar, int Rows, int Cols>                                                               \\\n  struct EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl)<XprType,Scalar,Rows,Cols,false> {                                                 \\\n    inline static void run(ARG1 a,EIGEN_GL_EVAL(EIGEN_GL_MAKE_CONST_##CONST) XprType& p) {                                      \\\n      EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl)<typename plain_matrix_type_column_major<XprType>::type>::run(a,p); }                 \\\n  };                                                                                                                            \\\n}                                                                                                                               \\\n                                                                                                                                \\\ntemplate<typename Derived> inline void FUNC(ARG1 a,EIGEN_GL_EVAL(EIGEN_GL_MAKE_CONST_##CONST) Eigen::DenseBase<Derived>& p) {   \\\n  EIGEN_CAT(EIGEN_CAT(internal::gl_,FUNC),_impl)<Derived>::run(a,p.derived());                                                  \\\n}\n\n\n#define EIGEN_GL_FUNC1_SPECIALIZATION_MAT(FUNC,ARG1,CONST,SCALAR,ROWS,COLS,SUFFIX)                                              \\\nnamespace internal {                                                                                                            \\\n  template< typename XprType> struct EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl)<XprType, SCALAR, ROWS, COLS, true> {                  \\\n    inline static void run(ARG1 a, EIGEN_GL_EVAL(EIGEN_GL_MAKE_CONST_##CONST) XprType& p) { FUNC##SUFFIX(a,p.data()); }         \\\n  }; \\\n}\n\n  \n#define EIGEN_GL_FUNC1_SPECIALIZATION_VEC(FUNC,ARG1,CONST,SCALAR,SIZE,SUFFIX)                                                   \\\nnamespace internal {                                                                                                            \\\n  template< typename XprType> struct EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl)<XprType, SCALAR, SIZE, 1, true> {                     \\\n    inline static void run(ARG1 a, EIGEN_GL_EVAL(EIGEN_GL_MAKE_CONST_##CONST) XprType& p) { FUNC##SUFFIX(a,p.data()); }         \\\n  };                                                                                                                            \\\n  template< typename XprType> struct EIGEN_CAT(EIGEN_CAT(gl_,FUNC),_impl)<XprType, SCALAR, 1, SIZE, true> {                     \\\n    inline static void run(ARG1 a, EIGEN_GL_EVAL(EIGEN_GL_MAKE_CONST_##CONST) XprType& p) { FUNC##SUFFIX(a,p.data()); }         \\\n  };                                                                                                                            \\\n}\n\nEIGEN_GL_FUNC1_DECLARATION       (glGet,GLenum,_)\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glGet,GLenum,_,float,  4,4,Floatv)\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glGet,GLenum,_,double, 4,4,Doublev)\n\n// glUniform API\n\n#ifdef GL_VERSION_2_0\n\ninline void glUniform2fv_ei  (GLint loc, const float* v)         { glUniform2fv(loc,1,v); }\ninline void glUniform2iv_ei  (GLint loc, const int* v)           { glUniform2iv(loc,1,v); }\n\ninline void glUniform3fv_ei  (GLint loc, const float* v)         { glUniform3fv(loc,1,v); }\ninline void glUniform3iv_ei  (GLint loc, const int* v)           { glUniform3iv(loc,1,v); }\n\ninline void glUniform4fv_ei  (GLint loc, const float* v)         { glUniform4fv(loc,1,v); }\ninline void glUniform4iv_ei  (GLint loc, const int* v)           { glUniform4iv(loc,1,v); }\n\ninline void glUniformMatrix2fv_ei  (GLint loc, const float* v)         { glUniformMatrix2fv(loc,1,false,v); }\ninline void glUniformMatrix3fv_ei  (GLint loc, const float* v)         { glUniformMatrix3fv(loc,1,false,v); }\ninline void glUniformMatrix4fv_ei  (GLint loc, const float* v)         { glUniformMatrix4fv(loc,1,false,v); }\n\n\nEIGEN_GL_FUNC1_DECLARATION       (glUniform,GLint,const)\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,float,        2,2fv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,int,          2,2iv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,float,        3,3fv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,int,          3,3iv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,float,        4,4fv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,int,          4,4iv_ei)\n\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glUniform,GLint,const,float,        2,2,Matrix2fv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glUniform,GLint,const,float,        3,3,Matrix3fv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glUniform,GLint,const,float,        4,4,Matrix4fv_ei)\n\n#endif\n\n#ifdef GL_VERSION_2_1\n\ninline void glUniformMatrix2x3fv_ei(GLint loc, const float* v)         { glUniformMatrix2x3fv(loc,1,false,v); }\ninline void glUniformMatrix3x2fv_ei(GLint loc, const float* v)         { glUniformMatrix3x2fv(loc,1,false,v); }\ninline void glUniformMatrix2x4fv_ei(GLint loc, const float* v)         { glUniformMatrix2x4fv(loc,1,false,v); }\ninline void glUniformMatrix4x2fv_ei(GLint loc, const float* v)         { glUniformMatrix4x2fv(loc,1,false,v); }\ninline void glUniformMatrix3x4fv_ei(GLint loc, const float* v)         { glUniformMatrix3x4fv(loc,1,false,v); }\ninline void glUniformMatrix4x3fv_ei(GLint loc, const float* v)         { glUniformMatrix4x3fv(loc,1,false,v); }\n\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glUniform,GLint,const,float,        2,3,Matrix2x3fv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glUniform,GLint,const,float,        3,2,Matrix3x2fv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glUniform,GLint,const,float,        2,4,Matrix2x4fv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glUniform,GLint,const,float,        4,2,Matrix4x2fv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glUniform,GLint,const,float,        3,4,Matrix3x4fv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_MAT(glUniform,GLint,const,float,        4,3,Matrix4x3fv_ei)\n\n#endif\n\n#ifdef GL_VERSION_3_0\n\ninline void glUniform2uiv_ei (GLint loc, const unsigned int* v)  { glUniform2uiv(loc,1,v); }\ninline void glUniform3uiv_ei (GLint loc, const unsigned int* v)  { glUniform3uiv(loc,1,v); }\ninline void glUniform4uiv_ei (GLint loc, const unsigned int* v)  { glUniform4uiv(loc,1,v); }\n\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,unsigned int, 2,2uiv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,unsigned int, 3,3uiv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,unsigned int, 4,4uiv_ei)\n\n#endif\n\n#ifdef GL_ARB_gpu_shader_fp64\ninline void glUniform2dv_ei  (GLint loc, const double* v)        { glUniform2dv(loc,1,v); }\ninline void glUniform3dv_ei  (GLint loc, const double* v)        { glUniform3dv(loc,1,v); }\ninline void glUniform4dv_ei  (GLint loc, const double* v)        { glUniform4dv(loc,1,v); }\n\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,double,       2,2dv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,double,       3,3dv_ei)\nEIGEN_GL_FUNC1_SPECIALIZATION_VEC(glUniform,GLint,const,double,       4,4dv_ei)\n#endif\n\n\n//@}\n\n}\n\n#endif // EIGEN_OPENGL_MODULE\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/Polynomials",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_POLYNOMIALS_MODULE_H\n#define EIGEN_POLYNOMIALS_MODULE_H\n\n#include \"../../Eigen/Core\"\n\n#include \"../../Eigen/Eigenvalues\"\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n// Note that EIGEN_HIDE_HEAVY_CODE has to be defined per module\n#if (defined EIGEN_EXTERN_INSTANTIATIONS) && (EIGEN_EXTERN_INSTANTIATIONS>=2)\n  #ifndef EIGEN_HIDE_HEAVY_CODE\n  #define EIGEN_HIDE_HEAVY_CODE\n  #endif\n#elif defined EIGEN_HIDE_HEAVY_CODE\n  #undef EIGEN_HIDE_HEAVY_CODE\n#endif\n\n/**\n  * \\defgroup Polynomials_Module Polynomials module\n  * \\brief This module provides a QR based polynomial solver.\n\t*\n  * To use this module, add\n  * \\code\n  * #include <unsupported/Eigen/Polynomials>\n  * \\endcode\n\t* at the start of your source file.\n  */\n\n#include \"src/Polynomials/PolynomialUtils.h\"\n#include \"src/Polynomials/Companion.h\"\n#include \"src/Polynomials/PolynomialSolver.h\"\n\n/**\n\t\\page polynomials Polynomials defines functions for dealing with polynomials\n\tand a QR based polynomial solver.\n\t\\ingroup Polynomials_Module\n\n\tThe remainder of the page documents first the functions for evaluating, computing\n\tpolynomials, computing estimates about polynomials and next the QR based polynomial\n\tsolver.\n\n\t\\section polynomialUtils convenient functions to deal with polynomials\n\t\\subsection roots_to_monicPolynomial\n\tThe function\n\t\\code\n\tvoid roots_to_monicPolynomial( const RootVector& rv, Polynomial& poly )\n\t\\endcode\n\tcomputes the coefficients \\f$ a_i \\f$ of\n\n\t\\f$ p(x) = a_0 + a_{1}x + ... + a_{n-1}x^{n-1} + x^n \\f$\n\n\twhere \\f$ p \\f$ is known through its roots i.e. \\f$ p(x) = (x-r_1)(x-r_2)...(x-r_n) \\f$.\n\n\t\\subsection poly_eval\n\tThe function\n\t\\code\n\tT poly_eval( const Polynomials& poly, const T& x )\n\t\\endcode\n\tevaluates a polynomial at a given point using stabilized H&ouml;rner method.\n\n\tThe following code: first computes the coefficients in the monomial basis of the monic polynomial that has the provided roots;\n\tthen, it evaluates the computed polynomial, using a stabilized H&ouml;rner method.\n\n\t\\include PolynomialUtils1.cpp\n  Output: \\verbinclude PolynomialUtils1.out\n\n\t\\subsection Cauchy bounds\n\tThe function\n\t\\code\n\tReal cauchy_max_bound( const Polynomial& poly )\n\t\\endcode\n\tprovides a maximum bound (the Cauchy one: \\f$C(p)\\f$) for the absolute value of a root of the given polynomial i.e.\n\t\\f$ \\forall r_i \\f$ root of \\f$ p(x) = \\sum_{k=0}^d a_k x^k \\f$,\n\t\\f$ |r_i| \\le C(p) = \\sum_{k=0}^{d} \\left | \\frac{a_k}{a_d} \\right | \\f$\n\tThe leading coefficient \\f$ p \\f$: should be non zero \\f$a_d \\neq 0\\f$.\n\n\n\tThe function\n\t\\code\n\tReal cauchy_min_bound( const Polynomial& poly )\n\t\\endcode\n\tprovides a minimum bound (the Cauchy one: \\f$c(p)\\f$) for the absolute value of a non zero root of the given polynomial i.e.\n\t\\f$ \\forall r_i \\neq 0 \\f$ root of \\f$ p(x) = \\sum_{k=0}^d a_k x^k \\f$,\n\t\\f$ |r_i| \\ge c(p) = \\left( \\sum_{k=0}^{d} \\left | \\frac{a_k}{a_0} \\right | \\right)^{-1} \\f$\n\n\n\n\n\t\\section QR polynomial solver class\n\tComputes the complex roots of a polynomial by computing the eigenvalues of the associated companion matrix with the QR algorithm.\n\t\n\tThe roots of \\f$ p(x) = a_0 + a_1 x + a_2 x^2 + a_{3} x^3 + x^4 \\f$ are the eigenvalues of\n\t\\f$\n\t\\left [\n\t\\begin{array}{cccc}\n\t0 & 0 &  0 & a_0 \\\\\n\t1 & 0 &  0 & a_1 \\\\\n\t0 & 1 &  0 & a_2 \\\\\n\t0 & 0 &  1 & a_3\n\t\\end{array} \\right ]\n\t\\f$\n\n\tHowever, the QR algorithm is not guaranteed to converge when there are several eigenvalues with same modulus.\n\n\tTherefore the current polynomial solver is guaranteed to provide a correct result only when the complex roots \\f$r_1,r_2,...,r_d\\f$ have distinct moduli i.e.\n\t\n\t\\f$ \\forall i,j \\in [1;d],~ \\| r_i \\| \\neq \\| r_j \\| \\f$.\n\n\tWith 32bit (float) floating types this problem shows up frequently.\n  However, almost always, correct accuracy is reached even in these cases for 64bit\n  (double) floating types and small polynomial degree (<20).\n\n\t\\include PolynomialSolver1.cpp\n\t\n\tIn the above example:\n\t\n\t-# a simple use of the polynomial solver is shown;\n\t-# the accuracy problem with the QR algorithm is presented: a polynomial with almost conjugate roots is provided to the solver.\n\tThose roots have almost same module therefore the QR algorithm failed to converge: the accuracy\n\tof the last root is bad;\n\t-# a simple way to circumvent the problem is shown: use doubles instead of floats.\n\n  Output: \\verbinclude PolynomialSolver1.out\n*/\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_POLYNOMIALS_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/Skyline",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SKYLINE_MODULE_H\n#define EIGEN_SKYLINE_MODULE_H\n\n\n#include \"../../Eigen/Core\"\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n#include <map>\n#include <cstdlib>\n#include <cstring>\n#include <algorithm>\n\n/**\n *  \\defgroup Skyline_Module Skyline module\n *\n *\n *\n *\n */\n\n#include \"src/Skyline/SkylineUtil.h\"\n#include \"src/Skyline/SkylineMatrixBase.h\"\n#include \"src/Skyline/SkylineStorage.h\"\n#include \"src/Skyline/SkylineMatrix.h\"\n#include \"src/Skyline/SkylineInplaceLU.h\"\n#include \"src/Skyline/SkylineProduct.h\"\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_SKYLINE_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/SparseExtra",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_EXTRA_MODULE_H\n#define EIGEN_SPARSE_EXTRA_MODULE_H\n\n#include \"../../Eigen/Sparse\"\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n#include <vector>\n#include <map>\n#include <cstdlib>\n#include <cstring>\n#include <algorithm>\n#include <fstream>\n#include <sstream>\n\n#ifdef EIGEN_GOOGLEHASH_SUPPORT\n  #include <google/dense_hash_map>\n#endif\n\n/**\n  * \\defgroup SparseExtra_Module SparseExtra module\n  *\n  * This module contains some experimental features extending the sparse module.\n  *\n  * \\code\n  * #include <Eigen/SparseExtra>\n  * \\endcode\n  */\n\n\n#include \"src/SparseExtra/DynamicSparseMatrix.h\"\n#include \"src/SparseExtra/BlockOfDynamicSparseMatrix.h\"\n#include \"src/SparseExtra/RandomSetter.h\"\n\n#include \"src/SparseExtra/MarketIO.h\"\n\n#if !defined(_WIN32)\n#include <dirent.h>\n#include \"src/SparseExtra/MatrixMarketIterator.h\"\n#endif\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_SPARSE_EXTRA_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/SpecialFunctions",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPECIALFUNCTIONS_MODULE\n#define EIGEN_SPECIALFUNCTIONS_MODULE\n\n#include <math.h>\n\n#include \"../../Eigen/Core\"\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\nnamespace Eigen {\n\n/**\n  * \\defgroup SpecialFunctions_Module Special math functions module\n  *\n  * This module features additional coefficient-wise math functions available\n  * within the numext:: namespace for the scalar version, and as method and/or free\n  * functions of Array. Those include:\n  *\n  * - erf\n  * - erfc\n  * - lgamma\n  * - igamma\n  * - igamma_der_a\n  * - gamma_sample_der_alpha\n  * - igammac\n  * - digamma\n  * - ndtri\n  * - polygamma\n  * - zeta\n  * - betainc\n  *\n  * Bessel Functions\n  * - bessel_i0\n  * - bessel_i0e\n  * - bessel_i1\n  * - bessel_i1e\n  * - bessel_j0\n  * - bessel_j1\n  * - bessel_k0\n  * - bessel_k0e\n  * - bessel_k1\n  * - bessel_k1e\n  * - bessel_y0\n  * - bessel_y1\n  *\n  * \\code\n  * #include <unsupported/Eigen/SpecialFunctions>\n  * \\endcode\n  */\n//@{\n\n}\n\n#include \"src/SpecialFunctions/BesselFunctionsImpl.h\"\n#include \"src/SpecialFunctions/BesselFunctionsBFloat16.h\"\n#include \"src/SpecialFunctions/BesselFunctionsHalf.h\"\n#include \"src/SpecialFunctions/BesselFunctionsPacketMath.h\"\n#include \"src/SpecialFunctions/BesselFunctionsFunctors.h\"\n#include \"src/SpecialFunctions/BesselFunctionsArrayAPI.h\"\n#include \"src/SpecialFunctions/SpecialFunctionsImpl.h\"\n#if defined(EIGEN_HIPCC)\n#include \"src/SpecialFunctions/HipVectorCompatibility.h\"\n#endif\n#include \"src/SpecialFunctions/SpecialFunctionsBFloat16.h\"\n#include \"src/SpecialFunctions/SpecialFunctionsHalf.h\"\n#include \"src/SpecialFunctions/SpecialFunctionsPacketMath.h\"\n#include \"src/SpecialFunctions/SpecialFunctionsFunctors.h\"\n#include \"src/SpecialFunctions/SpecialFunctionsArrayAPI.h\"\n\n#if defined EIGEN_VECTORIZE_AVX512\n  #include \"src/SpecialFunctions/arch/AVX/BesselFunctions.h\"\n  #include \"src/SpecialFunctions/arch/AVX/SpecialFunctions.h\"\n  #include \"src/SpecialFunctions/arch/AVX512/BesselFunctions.h\"\n  #include \"src/SpecialFunctions/arch/AVX512/SpecialFunctions.h\"\n#elif defined EIGEN_VECTORIZE_AVX\n  #include \"src/SpecialFunctions/arch/AVX/BesselFunctions.h\"\n  #include \"src/SpecialFunctions/arch/AVX/SpecialFunctions.h\"\n#elif defined EIGEN_VECTORIZE_NEON\n  #include \"src/SpecialFunctions/arch/NEON/BesselFunctions.h\"\n  #include \"src/SpecialFunctions/arch/NEON/SpecialFunctions.h\"\n#endif\n\n#if defined EIGEN_VECTORIZE_GPU\n  #include \"src/SpecialFunctions/arch/GPU/SpecialFunctions.h\"\n#endif\n\nnamespace Eigen {\n//@}\n}\n\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_SPECIALFUNCTIONS_MODULE\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/Splines",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 20010-2011 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPLINES_MODULE_H\n#define EIGEN_SPLINES_MODULE_H\n\nnamespace Eigen \n{\n/**\n  * \\defgroup Splines_Module Spline and spline fitting module\n  *\n  * This module provides a simple multi-dimensional spline class while\n  * offering most basic functionality to fit a spline to point sets.\n  *\n  * \\code\n  * #include <unsupported/Eigen/Splines>\n  * \\endcode\n  */\n}\n\n#include \"../../Eigen/src/Core/util/DisableStupidWarnings.h\"\n\n#include \"src/Splines/SplineFwd.h\"\n#include \"src/Splines/Spline.h\"\n#include \"src/Splines/SplineFitting.h\"\n\n#include \"../../Eigen/src/Core/util/ReenableStupidWarnings.h\"\n\n#endif // EIGEN_SPLINES_MODULE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/AutoDiff/AutoDiffJacobian.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_AUTODIFF_JACOBIAN_H\n#define EIGEN_AUTODIFF_JACOBIAN_H\n\nnamespace Eigen\n{\n\ntemplate<typename Functor> class AutoDiffJacobian : public Functor\n{\npublic:\n  AutoDiffJacobian() : Functor() {}\n  AutoDiffJacobian(const Functor& f) : Functor(f) {}\n\n  // forward constructors\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  template<typename... T>\n  AutoDiffJacobian(const T& ...Values) : Functor(Values...) {}\n#else\n  template<typename T0>\n  AutoDiffJacobian(const T0& a0) : Functor(a0) {}\n  template<typename T0, typename T1>\n  AutoDiffJacobian(const T0& a0, const T1& a1) : Functor(a0, a1) {}\n  template<typename T0, typename T1, typename T2>\n  AutoDiffJacobian(const T0& a0, const T1& a1, const T2& a2) : Functor(a0, a1, a2) {}\n#endif\n\n  typedef typename Functor::InputType InputType;\n  typedef typename Functor::ValueType ValueType;\n  typedef typename ValueType::Scalar Scalar;\n\n  enum {\n    InputsAtCompileTime = InputType::RowsAtCompileTime,\n    ValuesAtCompileTime = ValueType::RowsAtCompileTime\n  };\n\n  typedef Matrix<Scalar, ValuesAtCompileTime, InputsAtCompileTime> JacobianType;\n  typedef typename JacobianType::Index Index;\n\n  typedef Matrix<Scalar, InputsAtCompileTime, 1> DerivativeType;\n  typedef AutoDiffScalar<DerivativeType> ActiveScalar;\n\n  typedef Matrix<ActiveScalar, InputsAtCompileTime, 1> ActiveInput;\n  typedef Matrix<ActiveScalar, ValuesAtCompileTime, 1> ActiveValue;\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  // Some compilers don't accept variadic parameters after a default parameter,\n  // i.e., we can't just write _jac=0 but we need to overload operator():\n  EIGEN_STRONG_INLINE\n  void operator() (const InputType& x, ValueType* v) const\n  {\n      this->operator()(x, v, 0);\n  }\n  template<typename... ParamsType>\n  void operator() (const InputType& x, ValueType* v, JacobianType* _jac,\n                   const ParamsType&... Params) const\n#else\n  void operator() (const InputType& x, ValueType* v, JacobianType* _jac=0) const\n#endif\n  {\n    eigen_assert(v!=0);\n\n    if (!_jac)\n    {\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n      Functor::operator()(x, v, Params...);\n#else\n      Functor::operator()(x, v);\n#endif\n      return;\n    }\n\n    JacobianType& jac = *_jac;\n\n    ActiveInput ax = x.template cast<ActiveScalar>();\n    ActiveValue av(jac.rows());\n\n    if(InputsAtCompileTime==Dynamic)\n      for (Index j=0; j<jac.rows(); j++)\n        av[j].derivatives().resize(x.rows());\n\n    for (Index i=0; i<jac.cols(); i++)\n      ax[i].derivatives() = DerivativeType::Unit(x.rows(),i);\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n    Functor::operator()(ax, &av, Params...);\n#else\n    Functor::operator()(ax, &av);\n#endif\n\n    for (Index i=0; i<jac.rows(); i++)\n    {\n      (*v)[i] = av[i].value();\n      jac.row(i) = av[i].derivatives();\n    }\n  }\n};\n\n}\n\n#endif // EIGEN_AUTODIFF_JACOBIAN_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/AutoDiff/AutoDiffScalar.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_AUTODIFF_SCALAR_H\n#define EIGEN_AUTODIFF_SCALAR_H\n\nnamespace Eigen {\n\nnamespace internal {\n\ntemplate<typename A, typename B>\nstruct make_coherent_impl {\n  static void run(A&, B&) {}\n};\n\n// resize a to match b is a.size()==0, and conversely.\ntemplate<typename A, typename B>\nvoid make_coherent(const A& a, const B&b)\n{\n  make_coherent_impl<A,B>::run(a.const_cast_derived(), b.const_cast_derived());\n}\n\ntemplate<typename _DerType, bool Enable> struct auto_diff_special_op;\n\n} // end namespace internal\n\ntemplate<typename _DerType> class AutoDiffScalar;\n\ntemplate<typename NewDerType>\ninline AutoDiffScalar<NewDerType> MakeAutoDiffScalar(const typename NewDerType::Scalar& value, const NewDerType &der) {\n  return AutoDiffScalar<NewDerType>(value,der);\n}\n\n/** \\class AutoDiffScalar\n  * \\brief A scalar type replacement with automatic differentation capability\n  *\n  * \\param _DerType the vector type used to store/represent the derivatives. The base scalar type\n  *                 as well as the number of derivatives to compute are determined from this type.\n  *                 Typical choices include, e.g., \\c Vector4f for 4 derivatives, or \\c VectorXf\n  *                 if the number of derivatives is not known at compile time, and/or, the number\n  *                 of derivatives is large.\n  *                 Note that _DerType can also be a reference (e.g., \\c VectorXf&) to wrap a\n  *                 existing vector into an AutoDiffScalar.\n  *                 Finally, _DerType can also be any Eigen compatible expression.\n  *\n  * This class represents a scalar value while tracking its respective derivatives using Eigen's expression\n  * template mechanism.\n  *\n  * It supports the following list of global math function:\n  *  - std::abs, std::sqrt, std::pow, std::exp, std::log, std::sin, std::cos,\n  *  - internal::abs, internal::sqrt, numext::pow, internal::exp, internal::log, internal::sin, internal::cos,\n  *  - internal::conj, internal::real, internal::imag, numext::abs2.\n  *\n  * AutoDiffScalar can be used as the scalar type of an Eigen::Matrix object. However,\n  * in that case, the expression template mechanism only occurs at the top Matrix level,\n  * while derivatives are computed right away.\n  *\n  */\n\ntemplate<typename _DerType>\nclass AutoDiffScalar\n  : public internal::auto_diff_special_op\n            <_DerType, !internal::is_same<typename internal::traits<typename internal::remove_all<_DerType>::type>::Scalar,\n                                          typename NumTraits<typename internal::traits<typename internal::remove_all<_DerType>::type>::Scalar>::Real>::value>\n{\n  public:\n    typedef internal::auto_diff_special_op\n            <_DerType, !internal::is_same<typename internal::traits<typename internal::remove_all<_DerType>::type>::Scalar,\n                       typename NumTraits<typename internal::traits<typename internal::remove_all<_DerType>::type>::Scalar>::Real>::value> Base;\n    typedef typename internal::remove_all<_DerType>::type DerType;\n    typedef typename internal::traits<DerType>::Scalar Scalar;\n    typedef typename NumTraits<Scalar>::Real Real;\n\n    using Base::operator+;\n    using Base::operator*;\n\n    /** Default constructor without any initialization. */\n    AutoDiffScalar() {}\n\n    /** Constructs an active scalar from its \\a value,\n        and initializes the \\a nbDer derivatives such that it corresponds to the \\a derNumber -th variable */\n    AutoDiffScalar(const Scalar& value, int nbDer, int derNumber)\n      : m_value(value), m_derivatives(DerType::Zero(nbDer))\n    {\n      m_derivatives.coeffRef(derNumber) = Scalar(1);\n    }\n\n    /** Conversion from a scalar constant to an active scalar.\n      * The derivatives are set to zero. */\n    /*explicit*/ AutoDiffScalar(const Real& value)\n      : m_value(value)\n    {\n      if(m_derivatives.size()>0)\n        m_derivatives.setZero();\n    }\n\n    /** Constructs an active scalar from its \\a value and derivatives \\a der */\n    AutoDiffScalar(const Scalar& value, const DerType& der)\n      : m_value(value), m_derivatives(der)\n    {}\n\n    template<typename OtherDerType>\n    AutoDiffScalar(const AutoDiffScalar<OtherDerType>& other\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n    , typename internal::enable_if<\n            internal::is_same<Scalar, typename internal::traits<typename internal::remove_all<OtherDerType>::type>::Scalar>::value\n        &&  internal::is_convertible<OtherDerType,DerType>::value , void*>::type = 0\n#endif\n    )\n      : m_value(other.value()), m_derivatives(other.derivatives())\n    {}\n\n    friend  std::ostream & operator << (std::ostream & s, const AutoDiffScalar& a)\n    {\n      return s << a.value();\n    }\n\n    AutoDiffScalar(const AutoDiffScalar& other)\n      : m_value(other.value()), m_derivatives(other.derivatives())\n    {}\n\n    template<typename OtherDerType>\n    inline AutoDiffScalar& operator=(const AutoDiffScalar<OtherDerType>& other)\n    {\n      m_value = other.value();\n      m_derivatives = other.derivatives();\n      return *this;\n    }\n\n    inline AutoDiffScalar& operator=(const AutoDiffScalar& other)\n    {\n      m_value = other.value();\n      m_derivatives = other.derivatives();\n      return *this;\n    }\n\n    inline AutoDiffScalar& operator=(const Scalar& other)\n    {\n      m_value = other;\n      if(m_derivatives.size()>0)\n        m_derivatives.setZero();\n      return *this;\n    }\n\n//     inline operator const Scalar& () const { return m_value; }\n//     inline operator Scalar& () { return m_value; }\n\n    inline const Scalar& value() const { return m_value; }\n    inline Scalar& value() { return m_value; }\n\n    inline const DerType& derivatives() const { return m_derivatives; }\n    inline DerType& derivatives() { return m_derivatives; }\n\n    inline bool operator< (const Scalar& other) const  { return m_value <  other; }\n    inline bool operator<=(const Scalar& other) const  { return m_value <= other; }\n    inline bool operator> (const Scalar& other) const  { return m_value >  other; }\n    inline bool operator>=(const Scalar& other) const  { return m_value >= other; }\n    inline bool operator==(const Scalar& other) const  { return m_value == other; }\n    inline bool operator!=(const Scalar& other) const  { return m_value != other; }\n\n    friend inline bool operator< (const Scalar& a, const AutoDiffScalar& b) { return a <  b.value(); }\n    friend inline bool operator<=(const Scalar& a, const AutoDiffScalar& b) { return a <= b.value(); }\n    friend inline bool operator> (const Scalar& a, const AutoDiffScalar& b) { return a >  b.value(); }\n    friend inline bool operator>=(const Scalar& a, const AutoDiffScalar& b) { return a >= b.value(); }\n    friend inline bool operator==(const Scalar& a, const AutoDiffScalar& b) { return a == b.value(); }\n    friend inline bool operator!=(const Scalar& a, const AutoDiffScalar& b) { return a != b.value(); }\n\n    template<typename OtherDerType> inline bool operator< (const AutoDiffScalar<OtherDerType>& b) const  { return m_value <  b.value(); }\n    template<typename OtherDerType> inline bool operator<=(const AutoDiffScalar<OtherDerType>& b) const  { return m_value <= b.value(); }\n    template<typename OtherDerType> inline bool operator> (const AutoDiffScalar<OtherDerType>& b) const  { return m_value >  b.value(); }\n    template<typename OtherDerType> inline bool operator>=(const AutoDiffScalar<OtherDerType>& b) const  { return m_value >= b.value(); }\n    template<typename OtherDerType> inline bool operator==(const AutoDiffScalar<OtherDerType>& b) const  { return m_value == b.value(); }\n    template<typename OtherDerType> inline bool operator!=(const AutoDiffScalar<OtherDerType>& b) const  { return m_value != b.value(); }\n\n    inline const AutoDiffScalar<DerType&> operator+(const Scalar& other) const\n    {\n      return AutoDiffScalar<DerType&>(m_value + other, m_derivatives);\n    }\n\n    friend inline const AutoDiffScalar<DerType&> operator+(const Scalar& a, const AutoDiffScalar& b)\n    {\n      return AutoDiffScalar<DerType&>(a + b.value(), b.derivatives());\n    }\n\n//     inline const AutoDiffScalar<DerType&> operator+(const Real& other) const\n//     {\n//       return AutoDiffScalar<DerType&>(m_value + other, m_derivatives);\n//     }\n\n//     friend inline const AutoDiffScalar<DerType&> operator+(const Real& a, const AutoDiffScalar& b)\n//     {\n//       return AutoDiffScalar<DerType&>(a + b.value(), b.derivatives());\n//     }\n\n    inline AutoDiffScalar& operator+=(const Scalar& other)\n    {\n      value() += other;\n      return *this;\n    }\n\n    template<typename OtherDerType>\n    inline const AutoDiffScalar<CwiseBinaryOp<internal::scalar_sum_op<Scalar>,const DerType,const typename internal::remove_all<OtherDerType>::type> >\n    operator+(const AutoDiffScalar<OtherDerType>& other) const\n    {\n      internal::make_coherent(m_derivatives, other.derivatives());\n      return AutoDiffScalar<CwiseBinaryOp<internal::scalar_sum_op<Scalar>,const DerType,const typename internal::remove_all<OtherDerType>::type> >(\n        m_value + other.value(),\n        m_derivatives + other.derivatives());\n    }\n\n    template<typename OtherDerType>\n    inline AutoDiffScalar&\n    operator+=(const AutoDiffScalar<OtherDerType>& other)\n    {\n      (*this) = (*this) + other;\n      return *this;\n    }\n\n    inline const AutoDiffScalar<DerType&> operator-(const Scalar& b) const\n    {\n      return AutoDiffScalar<DerType&>(m_value - b, m_derivatives);\n    }\n\n    friend inline const AutoDiffScalar<CwiseUnaryOp<internal::scalar_opposite_op<Scalar>, const DerType> >\n    operator-(const Scalar& a, const AutoDiffScalar& b)\n    {\n      return AutoDiffScalar<CwiseUnaryOp<internal::scalar_opposite_op<Scalar>, const DerType> >\n            (a - b.value(), -b.derivatives());\n    }\n\n    inline AutoDiffScalar& operator-=(const Scalar& other)\n    {\n      value() -= other;\n      return *this;\n    }\n\n    template<typename OtherDerType>\n    inline const AutoDiffScalar<CwiseBinaryOp<internal::scalar_difference_op<Scalar>, const DerType,const typename internal::remove_all<OtherDerType>::type> >\n    operator-(const AutoDiffScalar<OtherDerType>& other) const\n    {\n      internal::make_coherent(m_derivatives, other.derivatives());\n      return AutoDiffScalar<CwiseBinaryOp<internal::scalar_difference_op<Scalar>, const DerType,const typename internal::remove_all<OtherDerType>::type> >(\n        m_value - other.value(),\n        m_derivatives - other.derivatives());\n    }\n\n    template<typename OtherDerType>\n    inline AutoDiffScalar&\n    operator-=(const AutoDiffScalar<OtherDerType>& other)\n    {\n      *this = *this - other;\n      return *this;\n    }\n\n    inline const AutoDiffScalar<CwiseUnaryOp<internal::scalar_opposite_op<Scalar>, const DerType> >\n    operator-() const\n    {\n      return AutoDiffScalar<CwiseUnaryOp<internal::scalar_opposite_op<Scalar>, const DerType> >(\n        -m_value,\n        -m_derivatives);\n    }\n\n    inline const AutoDiffScalar<EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(DerType,Scalar,product) >\n    operator*(const Scalar& other) const\n    {\n      return MakeAutoDiffScalar(m_value * other, m_derivatives * other);\n    }\n\n    friend inline const AutoDiffScalar<EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(DerType,Scalar,product) >\n    operator*(const Scalar& other, const AutoDiffScalar& a)\n    {\n      return MakeAutoDiffScalar(a.value() * other, a.derivatives() * other);\n    }\n\n//     inline const AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >\n//     operator*(const Real& other) const\n//     {\n//       return AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >(\n//         m_value * other,\n//         (m_derivatives * other));\n//     }\n//\n//     friend inline const AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >\n//     operator*(const Real& other, const AutoDiffScalar& a)\n//     {\n//       return AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >(\n//         a.value() * other,\n//         a.derivatives() * other);\n//     }\n\n    inline const AutoDiffScalar<EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(DerType,Scalar,product) >\n    operator/(const Scalar& other) const\n    {\n      return MakeAutoDiffScalar(m_value / other, (m_derivatives * (Scalar(1)/other)));\n    }\n\n    friend inline const AutoDiffScalar<EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(DerType,Scalar,product) >\n    operator/(const Scalar& other, const AutoDiffScalar& a)\n    {\n      return MakeAutoDiffScalar(other / a.value(), a.derivatives() * (Scalar(-other) / (a.value()*a.value())));\n    }\n\n//     inline const AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >\n//     operator/(const Real& other) const\n//     {\n//       return AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >(\n//         m_value / other,\n//         (m_derivatives * (Real(1)/other)));\n//     }\n//\n//     friend inline const AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >\n//     operator/(const Real& other, const AutoDiffScalar& a)\n//     {\n//       return AutoDiffScalar<typename CwiseUnaryOp<internal::scalar_multiple_op<Real>, DerType>::Type >(\n//         other / a.value(),\n//         a.derivatives() * (-Real(1)/other));\n//     }\n\n    template<typename OtherDerType>\n    inline const AutoDiffScalar<EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(\n        CwiseBinaryOp<internal::scalar_difference_op<Scalar> EIGEN_COMMA\n          const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(DerType,Scalar,product) EIGEN_COMMA\n          const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(typename internal::remove_all<OtherDerType>::type,Scalar,product) >,Scalar,product) >\n    operator/(const AutoDiffScalar<OtherDerType>& other) const\n    {\n      internal::make_coherent(m_derivatives, other.derivatives());\n      return MakeAutoDiffScalar(\n        m_value / other.value(),\n          ((m_derivatives * other.value()) - (other.derivatives() * m_value))\n        * (Scalar(1)/(other.value()*other.value())));\n    }\n\n    template<typename OtherDerType>\n    inline const AutoDiffScalar<CwiseBinaryOp<internal::scalar_sum_op<Scalar>,\n        const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(DerType,Scalar,product),\n        const EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(typename internal::remove_all<OtherDerType>::type,Scalar,product) > >\n    operator*(const AutoDiffScalar<OtherDerType>& other) const\n    {\n      internal::make_coherent(m_derivatives, other.derivatives());\n      return MakeAutoDiffScalar(\n        m_value * other.value(),\n        (m_derivatives * other.value()) + (other.derivatives() * m_value));\n    }\n\n    inline AutoDiffScalar& operator*=(const Scalar& other)\n    {\n      *this = *this * other;\n      return *this;\n    }\n\n    template<typename OtherDerType>\n    inline AutoDiffScalar& operator*=(const AutoDiffScalar<OtherDerType>& other)\n    {\n      *this = *this * other;\n      return *this;\n    }\n\n    inline AutoDiffScalar& operator/=(const Scalar& other)\n    {\n      *this = *this / other;\n      return *this;\n    }\n\n    template<typename OtherDerType>\n    inline AutoDiffScalar& operator/=(const AutoDiffScalar<OtherDerType>& other)\n    {\n      *this = *this / other;\n      return *this;\n    }\n\n  protected:\n    Scalar m_value;\n    DerType m_derivatives;\n\n};\n\nnamespace internal {\n\ntemplate<typename _DerType>\nstruct auto_diff_special_op<_DerType, true>\n//   : auto_diff_scalar_op<_DerType, typename NumTraits<Scalar>::Real,\n//                            is_same<Scalar,typename NumTraits<Scalar>::Real>::value>\n{\n  typedef typename remove_all<_DerType>::type DerType;\n  typedef typename traits<DerType>::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real Real;\n\n//   typedef auto_diff_scalar_op<_DerType, typename NumTraits<Scalar>::Real,\n//                            is_same<Scalar,typename NumTraits<Scalar>::Real>::value> Base;\n\n//   using Base::operator+;\n//   using Base::operator+=;\n//   using Base::operator-;\n//   using Base::operator-=;\n//   using Base::operator*;\n//   using Base::operator*=;\n\n  const AutoDiffScalar<_DerType>& derived() const { return *static_cast<const AutoDiffScalar<_DerType>*>(this); }\n  AutoDiffScalar<_DerType>& derived() { return *static_cast<AutoDiffScalar<_DerType>*>(this); }\n\n\n  inline const AutoDiffScalar<DerType&> operator+(const Real& other) const\n  {\n    return AutoDiffScalar<DerType&>(derived().value() + other, derived().derivatives());\n  }\n\n  friend inline const AutoDiffScalar<DerType&> operator+(const Real& a, const AutoDiffScalar<_DerType>& b)\n  {\n    return AutoDiffScalar<DerType&>(a + b.value(), b.derivatives());\n  }\n\n  inline AutoDiffScalar<_DerType>& operator+=(const Real& other)\n  {\n    derived().value() += other;\n    return derived();\n  }\n\n\n  inline const AutoDiffScalar<typename CwiseUnaryOp<bind2nd_op<scalar_product_op<Scalar,Real> >, DerType>::Type >\n  operator*(const Real& other) const\n  {\n    return AutoDiffScalar<typename CwiseUnaryOp<bind2nd_op<scalar_product_op<Scalar,Real> >, DerType>::Type >(\n      derived().value() * other,\n      derived().derivatives() * other);\n  }\n\n  friend inline const AutoDiffScalar<typename CwiseUnaryOp<bind1st_op<scalar_product_op<Real,Scalar> >, DerType>::Type >\n  operator*(const Real& other, const AutoDiffScalar<_DerType>& a)\n  {\n    return AutoDiffScalar<typename CwiseUnaryOp<bind1st_op<scalar_product_op<Real,Scalar> >, DerType>::Type >(\n      a.value() * other,\n      a.derivatives() * other);\n  }\n\n  inline AutoDiffScalar<_DerType>& operator*=(const Scalar& other)\n  {\n    *this = *this * other;\n    return derived();\n  }\n};\n\ntemplate<typename _DerType>\nstruct auto_diff_special_op<_DerType, false>\n{\n  void operator*() const;\n  void operator-() const;\n  void operator+() const;\n};\n\ntemplate<typename BinOp, typename A, typename B, typename RefType>\nvoid make_coherent_expression(CwiseBinaryOp<BinOp,A,B> xpr, const RefType &ref)\n{\n  make_coherent(xpr.const_cast_derived().lhs(), ref);\n  make_coherent(xpr.const_cast_derived().rhs(), ref);\n}\n\ntemplate<typename UnaryOp, typename A, typename RefType>\nvoid make_coherent_expression(const CwiseUnaryOp<UnaryOp,A> &xpr, const RefType &ref)\n{\n  make_coherent(xpr.nestedExpression().const_cast_derived(), ref);\n}\n\n// needed for compilation only\ntemplate<typename UnaryOp, typename A, typename RefType>\nvoid make_coherent_expression(const CwiseNullaryOp<UnaryOp,A> &, const RefType &)\n{}\n\ntemplate<typename A_Scalar, int A_Rows, int A_Cols, int A_Options, int A_MaxRows, int A_MaxCols, typename B>\nstruct make_coherent_impl<Matrix<A_Scalar, A_Rows, A_Cols, A_Options, A_MaxRows, A_MaxCols>, B> {\n  typedef Matrix<A_Scalar, A_Rows, A_Cols, A_Options, A_MaxRows, A_MaxCols> A;\n  static void run(A& a, B& b) {\n    if((A_Rows==Dynamic || A_Cols==Dynamic) && (a.size()==0))\n    {\n      a.resize(b.size());\n      a.setZero();\n    }\n    else if (B::SizeAtCompileTime==Dynamic && a.size()!=0 && b.size()==0)\n    {\n      make_coherent_expression(b,a);\n    }\n  }\n};\n\ntemplate<typename A, typename B_Scalar, int B_Rows, int B_Cols, int B_Options, int B_MaxRows, int B_MaxCols>\nstruct make_coherent_impl<A, Matrix<B_Scalar, B_Rows, B_Cols, B_Options, B_MaxRows, B_MaxCols> > {\n  typedef Matrix<B_Scalar, B_Rows, B_Cols, B_Options, B_MaxRows, B_MaxCols> B;\n  static void run(A& a, B& b) {\n    if((B_Rows==Dynamic || B_Cols==Dynamic) && (b.size()==0))\n    {\n      b.resize(a.size());\n      b.setZero();\n    }\n    else if (A::SizeAtCompileTime==Dynamic && b.size()!=0 && a.size()==0)\n    {\n      make_coherent_expression(a,b);\n    }\n  }\n};\n\ntemplate<typename A_Scalar, int A_Rows, int A_Cols, int A_Options, int A_MaxRows, int A_MaxCols,\n         typename B_Scalar, int B_Rows, int B_Cols, int B_Options, int B_MaxRows, int B_MaxCols>\nstruct make_coherent_impl<Matrix<A_Scalar, A_Rows, A_Cols, A_Options, A_MaxRows, A_MaxCols>,\n                          Matrix<B_Scalar, B_Rows, B_Cols, B_Options, B_MaxRows, B_MaxCols> > {\n  typedef Matrix<A_Scalar, A_Rows, A_Cols, A_Options, A_MaxRows, A_MaxCols> A;\n  typedef Matrix<B_Scalar, B_Rows, B_Cols, B_Options, B_MaxRows, B_MaxCols> B;\n  static void run(A& a, B& b) {\n    if((A_Rows==Dynamic || A_Cols==Dynamic) && (a.size()==0))\n    {\n      a.resize(b.size());\n      a.setZero();\n    }\n    else if((B_Rows==Dynamic || B_Cols==Dynamic) && (b.size()==0))\n    {\n      b.resize(a.size());\n      b.setZero();\n    }\n  }\n};\n\n} // end namespace internal\n\ntemplate<typename DerType, typename BinOp>\nstruct ScalarBinaryOpTraits<AutoDiffScalar<DerType>,typename DerType::Scalar,BinOp>\n{\n  typedef AutoDiffScalar<DerType> ReturnType;\n};\n\ntemplate<typename DerType, typename BinOp>\nstruct ScalarBinaryOpTraits<typename DerType::Scalar,AutoDiffScalar<DerType>, BinOp>\n{\n  typedef AutoDiffScalar<DerType> ReturnType;\n};\n\n\n// The following is an attempt to let Eigen's known about expression template, but that's more tricky!\n\n// template<typename DerType, typename BinOp>\n// struct ScalarBinaryOpTraits<AutoDiffScalar<DerType>,AutoDiffScalar<DerType>, BinOp>\n// {\n//   enum { Defined = 1 };\n//   typedef AutoDiffScalar<typename DerType::PlainObject> ReturnType;\n// };\n//\n// template<typename DerType1,typename DerType2, typename BinOp>\n// struct ScalarBinaryOpTraits<AutoDiffScalar<DerType1>,AutoDiffScalar<DerType2>, BinOp>\n// {\n//   enum { Defined = 1 };//internal::is_same<typename DerType1::Scalar,typename DerType2::Scalar>::value };\n//   typedef AutoDiffScalar<typename DerType1::PlainObject> ReturnType;\n// };\n\n#define EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(FUNC,CODE) \\\n  template<typename DerType> \\\n  inline const Eigen::AutoDiffScalar< \\\n  EIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(typename Eigen::internal::remove_all<DerType>::type, typename Eigen::internal::traits<typename Eigen::internal::remove_all<DerType>::type>::Scalar, product) > \\\n  FUNC(const Eigen::AutoDiffScalar<DerType>& x) { \\\n    using namespace Eigen; \\\n    typedef typename Eigen::internal::traits<typename Eigen::internal::remove_all<DerType>::type>::Scalar Scalar; \\\n    EIGEN_UNUSED_VARIABLE(sizeof(Scalar)); \\\n    CODE; \\\n  }\n\ntemplate<typename DerType>\nstruct CleanedUpDerType {\n  typedef AutoDiffScalar<typename Eigen::internal::remove_all<DerType>::type::PlainObject> type;\n};\n\ntemplate<typename DerType>\ninline const AutoDiffScalar<DerType>& conj(const AutoDiffScalar<DerType>& x)  { return x; }\ntemplate<typename DerType>\ninline const AutoDiffScalar<DerType>& real(const AutoDiffScalar<DerType>& x)  { return x; }\ntemplate<typename DerType>\ninline typename DerType::Scalar imag(const AutoDiffScalar<DerType>&)    { return 0.; }\ntemplate<typename DerType, typename T>\ninline typename CleanedUpDerType<DerType>::type (min)(const AutoDiffScalar<DerType>& x, const T& y) {\n  typedef typename CleanedUpDerType<DerType>::type ADS;\n  return (x <= y ? ADS(x) : ADS(y));\n}\ntemplate<typename DerType, typename T>\ninline typename CleanedUpDerType<DerType>::type (max)(const AutoDiffScalar<DerType>& x, const T& y) {\n  typedef typename CleanedUpDerType<DerType>::type ADS;\n  return (x >= y ? ADS(x) : ADS(y));\n}\ntemplate<typename DerType, typename T>\ninline typename CleanedUpDerType<DerType>::type (min)(const T& x, const AutoDiffScalar<DerType>& y) {\n  typedef typename CleanedUpDerType<DerType>::type ADS;\n  return (x < y ? ADS(x) : ADS(y));\n}\ntemplate<typename DerType, typename T>\ninline typename CleanedUpDerType<DerType>::type (max)(const T& x, const AutoDiffScalar<DerType>& y) {\n  typedef typename CleanedUpDerType<DerType>::type ADS;\n  return (x > y ? ADS(x) : ADS(y));\n}\ntemplate<typename DerType>\ninline typename CleanedUpDerType<DerType>::type (min)(const AutoDiffScalar<DerType>& x, const AutoDiffScalar<DerType>& y) {\n  return (x.value() < y.value() ? x : y);\n}\ntemplate<typename DerType>\ninline typename CleanedUpDerType<DerType>::type (max)(const AutoDiffScalar<DerType>& x, const AutoDiffScalar<DerType>& y) {\n  return (x.value() >= y.value() ? x : y);\n}\n\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(abs,\n  using std::abs;\n  return Eigen::MakeAutoDiffScalar(abs(x.value()), x.derivatives() * (x.value()<0 ? -1 : 1) );)\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(abs2,\n  using numext::abs2;\n  return Eigen::MakeAutoDiffScalar(abs2(x.value()), x.derivatives() * (Scalar(2)*x.value()));)\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(sqrt,\n  using std::sqrt;\n  Scalar sqrtx = sqrt(x.value());\n  return Eigen::MakeAutoDiffScalar(sqrtx,x.derivatives() * (Scalar(0.5) / sqrtx));)\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(cos,\n  using std::cos;\n  using std::sin;\n  return Eigen::MakeAutoDiffScalar(cos(x.value()), x.derivatives() * (-sin(x.value())));)\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(sin,\n  using std::sin;\n  using std::cos;\n  return Eigen::MakeAutoDiffScalar(sin(x.value()),x.derivatives() * cos(x.value()));)\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(exp,\n  using std::exp;\n  Scalar expx = exp(x.value());\n  return Eigen::MakeAutoDiffScalar(expx,x.derivatives() * expx);)\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(log,\n  using std::log;\n  return Eigen::MakeAutoDiffScalar(log(x.value()),x.derivatives() * (Scalar(1)/x.value()));)\n\ntemplate<typename DerType>\ninline const Eigen::AutoDiffScalar<\nEIGEN_EXPR_BINARYOP_SCALAR_RETURN_TYPE(typename internal::remove_all<DerType>::type,typename internal::traits<typename internal::remove_all<DerType>::type>::Scalar,product) >\npow(const Eigen::AutoDiffScalar<DerType> &x, const typename internal::traits<typename internal::remove_all<DerType>::type>::Scalar &y)\n{\n  using namespace Eigen;\n  using std::pow;\n  return Eigen::MakeAutoDiffScalar(pow(x.value(),y), x.derivatives() * (y * pow(x.value(),y-1)));\n}\n\n\ntemplate<typename DerTypeA,typename DerTypeB>\ninline const AutoDiffScalar<Matrix<typename internal::traits<typename internal::remove_all<DerTypeA>::type>::Scalar,Dynamic,1> >\natan2(const AutoDiffScalar<DerTypeA>& a, const AutoDiffScalar<DerTypeB>& b)\n{\n  using std::atan2;\n  typedef typename internal::traits<typename internal::remove_all<DerTypeA>::type>::Scalar Scalar;\n  typedef AutoDiffScalar<Matrix<Scalar,Dynamic,1> > PlainADS;\n  PlainADS ret;\n  ret.value() = atan2(a.value(), b.value());\n  \n  Scalar squared_hypot = a.value() * a.value() + b.value() * b.value();\n  \n  // if (squared_hypot==0) the derivation is undefined and the following results in a NaN:\n  ret.derivatives() = (a.derivatives() * b.value() - a.value() * b.derivatives()) / squared_hypot;\n\n  return ret;\n}\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(tan,\n  using std::tan;\n  using std::cos;\n  return Eigen::MakeAutoDiffScalar(tan(x.value()),x.derivatives() * (Scalar(1)/numext::abs2(cos(x.value()))));)\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(asin,\n  using std::sqrt;\n  using std::asin;\n  return Eigen::MakeAutoDiffScalar(asin(x.value()),x.derivatives() * (Scalar(1)/sqrt(1-numext::abs2(x.value()))));)\n  \nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(acos,\n  using std::sqrt;\n  using std::acos;\n  return Eigen::MakeAutoDiffScalar(acos(x.value()),x.derivatives() * (Scalar(-1)/sqrt(1-numext::abs2(x.value()))));)\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(tanh,\n  using std::cosh;\n  using std::tanh;\n  return Eigen::MakeAutoDiffScalar(tanh(x.value()),x.derivatives() * (Scalar(1)/numext::abs2(cosh(x.value()))));)\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(sinh,\n  using std::sinh;\n  using std::cosh;\n  return Eigen::MakeAutoDiffScalar(sinh(x.value()),x.derivatives() * cosh(x.value()));)\n\nEIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY(cosh,\n  using std::sinh;\n  using std::cosh;\n  return Eigen::MakeAutoDiffScalar(cosh(x.value()),x.derivatives() * sinh(x.value()));)\n\n#undef EIGEN_AUTODIFF_DECLARE_GLOBAL_UNARY\n\ntemplate<typename DerType> struct NumTraits<AutoDiffScalar<DerType> >\n  : NumTraits< typename NumTraits<typename internal::remove_all<DerType>::type::Scalar>::Real >\n{\n  typedef typename internal::remove_all<DerType>::type DerTypeCleaned;\n  typedef AutoDiffScalar<Matrix<typename NumTraits<typename DerTypeCleaned::Scalar>::Real,DerTypeCleaned::RowsAtCompileTime,DerTypeCleaned::ColsAtCompileTime,\n                                0, DerTypeCleaned::MaxRowsAtCompileTime, DerTypeCleaned::MaxColsAtCompileTime> > Real;\n  typedef AutoDiffScalar<DerType> NonInteger;\n  typedef AutoDiffScalar<DerType> Nested;\n  typedef typename NumTraits<typename DerTypeCleaned::Scalar>::Literal Literal;\n  enum{\n    RequireInitialization = 1\n  };\n};\n\n}\n\nnamespace std {\n\ntemplate <typename T>\nclass numeric_limits<Eigen::AutoDiffScalar<T> >\n  : public numeric_limits<typename T::Scalar> {};\n\ntemplate <typename T>\nclass numeric_limits<Eigen::AutoDiffScalar<T&> >\n  : public numeric_limits<typename T::Scalar> {};\n\n}  // namespace std\n\n#endif // EIGEN_AUTODIFF_SCALAR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/AutoDiff/AutoDiffVector.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_AUTODIFF_VECTOR_H\n#define EIGEN_AUTODIFF_VECTOR_H\n\nnamespace Eigen {\n\n/* \\class AutoDiffScalar\n  * \\brief A scalar type replacement with automatic differentation capability\n  *\n  * \\param DerType the vector type used to store/represent the derivatives (e.g. Vector3f)\n  *\n  * This class represents a scalar value while tracking its respective derivatives.\n  *\n  * It supports the following list of global math function:\n  *  - std::abs, std::sqrt, std::pow, std::exp, std::log, std::sin, std::cos,\n  *  - internal::abs, internal::sqrt, numext::pow, internal::exp, internal::log, internal::sin, internal::cos,\n  *  - internal::conj, internal::real, internal::imag, numext::abs2.\n  *\n  * AutoDiffScalar can be used as the scalar type of an Eigen::Matrix object. However,\n  * in that case, the expression template mechanism only occurs at the top Matrix level,\n  * while derivatives are computed right away.\n  *\n  */\ntemplate<typename ValueType, typename JacobianType>\nclass AutoDiffVector\n{\n  public:\n    //typedef typename internal::traits<ValueType>::Scalar Scalar;\n    typedef typename internal::traits<ValueType>::Scalar BaseScalar;\n    typedef AutoDiffScalar<Matrix<BaseScalar,JacobianType::RowsAtCompileTime,1> > ActiveScalar;\n    typedef ActiveScalar Scalar;\n    typedef AutoDiffScalar<typename JacobianType::ColXpr> CoeffType;\n    typedef typename JacobianType::Index Index;\n\n    inline AutoDiffVector() {}\n\n    inline AutoDiffVector(const ValueType& values)\n      : m_values(values)\n    {\n      m_jacobian.setZero();\n    }\n\n\n    CoeffType operator[] (Index i) { return CoeffType(m_values[i], m_jacobian.col(i)); }\n    const CoeffType operator[] (Index i) const { return CoeffType(m_values[i], m_jacobian.col(i)); }\n\n    CoeffType operator() (Index i) { return CoeffType(m_values[i], m_jacobian.col(i)); }\n    const CoeffType operator() (Index i) const { return CoeffType(m_values[i], m_jacobian.col(i)); }\n\n    CoeffType coeffRef(Index i) { return CoeffType(m_values[i], m_jacobian.col(i)); }\n    const CoeffType coeffRef(Index i) const { return CoeffType(m_values[i], m_jacobian.col(i)); }\n\n    Index size() const { return m_values.size(); }\n\n    // FIXME here we could return an expression of the sum\n    Scalar sum() const { /*std::cerr << \"sum \\n\\n\";*/ /*std::cerr << m_jacobian.rowwise().sum() << \"\\n\\n\";*/ return Scalar(m_values.sum(), m_jacobian.rowwise().sum()); }\n\n\n    inline AutoDiffVector(const ValueType& values, const JacobianType& jac)\n      : m_values(values), m_jacobian(jac)\n    {}\n\n    template<typename OtherValueType, typename OtherJacobianType>\n    inline AutoDiffVector(const AutoDiffVector<OtherValueType, OtherJacobianType>& other)\n      : m_values(other.values()), m_jacobian(other.jacobian())\n    {}\n\n    inline AutoDiffVector(const AutoDiffVector& other)\n      : m_values(other.values()), m_jacobian(other.jacobian())\n    {}\n\n    template<typename OtherValueType, typename OtherJacobianType>\n    inline AutoDiffVector& operator=(const AutoDiffVector<OtherValueType, OtherJacobianType>& other)\n    {\n      m_values = other.values();\n      m_jacobian = other.jacobian();\n      return *this;\n    }\n\n    inline AutoDiffVector& operator=(const AutoDiffVector& other)\n    {\n      m_values = other.values();\n      m_jacobian = other.jacobian();\n      return *this;\n    }\n\n    inline const ValueType& values() const { return m_values; }\n    inline ValueType& values() { return m_values; }\n\n    inline const JacobianType& jacobian() const { return m_jacobian; }\n    inline JacobianType& jacobian() { return m_jacobian; }\n\n    template<typename OtherValueType,typename OtherJacobianType>\n    inline const AutoDiffVector<\n      typename MakeCwiseBinaryOp<internal::scalar_sum_op<BaseScalar>,ValueType,OtherValueType>::Type,\n      typename MakeCwiseBinaryOp<internal::scalar_sum_op<BaseScalar>,JacobianType,OtherJacobianType>::Type >\n    operator+(const AutoDiffVector<OtherValueType,OtherJacobianType>& other) const\n    {\n      return AutoDiffVector<\n      typename MakeCwiseBinaryOp<internal::scalar_sum_op<BaseScalar>,ValueType,OtherValueType>::Type,\n      typename MakeCwiseBinaryOp<internal::scalar_sum_op<BaseScalar>,JacobianType,OtherJacobianType>::Type >(\n        m_values + other.values(),\n        m_jacobian + other.jacobian());\n    }\n\n    template<typename OtherValueType, typename OtherJacobianType>\n    inline AutoDiffVector&\n    operator+=(const AutoDiffVector<OtherValueType,OtherJacobianType>& other)\n    {\n      m_values += other.values();\n      m_jacobian += other.jacobian();\n      return *this;\n    }\n\n    template<typename OtherValueType,typename OtherJacobianType>\n    inline const AutoDiffVector<\n      typename MakeCwiseBinaryOp<internal::scalar_difference_op<Scalar>,ValueType,OtherValueType>::Type,\n      typename MakeCwiseBinaryOp<internal::scalar_difference_op<Scalar>,JacobianType,OtherJacobianType>::Type >\n    operator-(const AutoDiffVector<OtherValueType,OtherJacobianType>& other) const\n    {\n      return AutoDiffVector<\n        typename MakeCwiseBinaryOp<internal::scalar_difference_op<Scalar>,ValueType,OtherValueType>::Type,\n        typename MakeCwiseBinaryOp<internal::scalar_difference_op<Scalar>,JacobianType,OtherJacobianType>::Type >(\n          m_values - other.values(),\n          m_jacobian - other.jacobian());\n    }\n\n    template<typename OtherValueType, typename OtherJacobianType>\n    inline AutoDiffVector&\n    operator-=(const AutoDiffVector<OtherValueType,OtherJacobianType>& other)\n    {\n      m_values -= other.values();\n      m_jacobian -= other.jacobian();\n      return *this;\n    }\n\n    inline const AutoDiffVector<\n      typename MakeCwiseUnaryOp<internal::scalar_opposite_op<Scalar>, ValueType>::Type,\n      typename MakeCwiseUnaryOp<internal::scalar_opposite_op<Scalar>, JacobianType>::Type >\n    operator-() const\n    {\n      return AutoDiffVector<\n        typename MakeCwiseUnaryOp<internal::scalar_opposite_op<Scalar>, ValueType>::Type,\n        typename MakeCwiseUnaryOp<internal::scalar_opposite_op<Scalar>, JacobianType>::Type >(\n          -m_values,\n          -m_jacobian);\n    }\n\n    inline const AutoDiffVector<\n      typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, ValueType>::Type,\n      typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, JacobianType>::Type>\n    operator*(const BaseScalar& other) const\n    {\n      return AutoDiffVector<\n        typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, ValueType>::Type,\n        typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, JacobianType>::Type >(\n          m_values * other,\n          m_jacobian * other);\n    }\n\n    friend inline const AutoDiffVector<\n      typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, ValueType>::Type,\n      typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, JacobianType>::Type >\n    operator*(const Scalar& other, const AutoDiffVector& v)\n    {\n      return AutoDiffVector<\n        typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, ValueType>::Type,\n        typename MakeCwiseUnaryOp<internal::scalar_multiple_op<Scalar>, JacobianType>::Type >(\n          v.values() * other,\n          v.jacobian() * other);\n    }\n\n//     template<typename OtherValueType,typename OtherJacobianType>\n//     inline const AutoDiffVector<\n//       CwiseBinaryOp<internal::scalar_multiple_op<Scalar>, ValueType, OtherValueType>\n//       CwiseBinaryOp<internal::scalar_sum_op<Scalar>,\n//         CwiseUnaryOp<internal::scalar_multiple_op<Scalar>, JacobianType>,\n//         CwiseUnaryOp<internal::scalar_multiple_op<Scalar>, OtherJacobianType> > >\n//     operator*(const AutoDiffVector<OtherValueType,OtherJacobianType>& other) const\n//     {\n//       return AutoDiffVector<\n//         CwiseBinaryOp<internal::scalar_multiple_op<Scalar>, ValueType, OtherValueType>\n//         CwiseBinaryOp<internal::scalar_sum_op<Scalar>,\n//           CwiseUnaryOp<internal::scalar_multiple_op<Scalar>, JacobianType>,\n//           CwiseUnaryOp<internal::scalar_multiple_op<Scalar>, OtherJacobianType> > >(\n//             m_values.cwise() * other.values(),\n//             (m_jacobian * other.values()) + (m_values * other.jacobian()));\n//     }\n\n    inline AutoDiffVector& operator*=(const Scalar& other)\n    {\n      m_values *= other;\n      m_jacobian *= other;\n      return *this;\n    }\n\n    template<typename OtherValueType,typename OtherJacobianType>\n    inline AutoDiffVector& operator*=(const AutoDiffVector<OtherValueType,OtherJacobianType>& other)\n    {\n      *this = *this * other;\n      return *this;\n    }\n\n  protected:\n    ValueType m_values;\n    JacobianType m_jacobian;\n\n};\n\n}\n\n#endif // EIGEN_AUTODIFF_VECTOR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/BVH/BVAlgorithms.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Ilya Baran <ibaran@mit.edu>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BVALGORITHMS_H\n#define EIGEN_BVALGORITHMS_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename BVH, typename Intersector>\nbool intersect_helper(const BVH &tree, Intersector &intersector, typename BVH::Index root)\n{\n  typedef typename BVH::Index Index;\n  typedef typename BVH::VolumeIterator VolIter;\n  typedef typename BVH::ObjectIterator ObjIter;\n\n  VolIter vBegin = VolIter(), vEnd = VolIter();\n  ObjIter oBegin = ObjIter(), oEnd = ObjIter();\n\n  std::vector<Index> todo(1, root);\n\n  while(!todo.empty()) {\n    tree.getChildren(todo.back(), vBegin, vEnd, oBegin, oEnd);\n    todo.pop_back();\n\n    for(; vBegin != vEnd; ++vBegin) //go through child volumes\n      if(intersector.intersectVolume(tree.getVolume(*vBegin)))\n        todo.push_back(*vBegin);\n\n    for(; oBegin != oEnd; ++oBegin) //go through child objects\n      if(intersector.intersectObject(*oBegin))\n        return true; //intersector said to stop query\n  }\n  return false;\n}\n#endif //not EIGEN_PARSED_BY_DOXYGEN\n\ntemplate<typename Volume1, typename Object1, typename Object2, typename Intersector>\nstruct intersector_helper1\n{\n  intersector_helper1(const Object2 &inStored, Intersector &in) : stored(inStored), intersector(in) {}\n  bool intersectVolume(const Volume1 &vol) { return intersector.intersectVolumeObject(vol, stored); }\n  bool intersectObject(const Object1 &obj) { return intersector.intersectObjectObject(obj, stored); }\n  Object2 stored;\n  Intersector &intersector;\nprivate:\n  intersector_helper1& operator=(const intersector_helper1&);\n};\n\ntemplate<typename Volume2, typename Object2, typename Object1, typename Intersector>\nstruct intersector_helper2\n{\n  intersector_helper2(const Object1 &inStored, Intersector &in) : stored(inStored), intersector(in) {}\n  bool intersectVolume(const Volume2 &vol) { return intersector.intersectObjectVolume(stored, vol); }\n  bool intersectObject(const Object2 &obj) { return intersector.intersectObjectObject(stored, obj); }\n  Object1 stored;\n  Intersector &intersector;\nprivate:\n  intersector_helper2& operator=(const intersector_helper2&);\n};\n\n} // end namespace internal\n\n/**  Given a BVH, runs the query encapsulated by \\a intersector.\n  *  The Intersector type must provide the following members: \\code\n     bool intersectVolume(const BVH::Volume &volume) //returns true if volume intersects the query\n     bool intersectObject(const BVH::Object &object) //returns true if the search should terminate immediately\n  \\endcode\n  */\ntemplate<typename BVH, typename Intersector>\nvoid BVIntersect(const BVH &tree, Intersector &intersector)\n{\n  internal::intersect_helper(tree, intersector, tree.getRootIndex());\n}\n\n/**  Given two BVH's, runs the query on their Cartesian product encapsulated by \\a intersector.\n  *  The Intersector type must provide the following members: \\code\n     bool intersectVolumeVolume(const BVH1::Volume &v1, const BVH2::Volume &v2) //returns true if product of volumes intersects the query\n     bool intersectVolumeObject(const BVH1::Volume &v1, const BVH2::Object &o2) //returns true if the volume-object product intersects the query\n     bool intersectObjectVolume(const BVH1::Object &o1, const BVH2::Volume &v2) //returns true if the volume-object product intersects the query\n     bool intersectObjectObject(const BVH1::Object &o1, const BVH2::Object &o2) //returns true if the search should terminate immediately\n  \\endcode\n  */\ntemplate<typename BVH1, typename BVH2, typename Intersector>\nvoid BVIntersect(const BVH1 &tree1, const BVH2 &tree2, Intersector &intersector) //TODO: tandem descent when it makes sense\n{\n  typedef typename BVH1::Index Index1;\n  typedef typename BVH2::Index Index2;\n  typedef internal::intersector_helper1<typename BVH1::Volume, typename BVH1::Object, typename BVH2::Object, Intersector> Helper1;\n  typedef internal::intersector_helper2<typename BVH2::Volume, typename BVH2::Object, typename BVH1::Object, Intersector> Helper2;\n  typedef typename BVH1::VolumeIterator VolIter1;\n  typedef typename BVH1::ObjectIterator ObjIter1;\n  typedef typename BVH2::VolumeIterator VolIter2;\n  typedef typename BVH2::ObjectIterator ObjIter2;\n\n  VolIter1 vBegin1 = VolIter1(), vEnd1 = VolIter1();\n  ObjIter1 oBegin1 = ObjIter1(), oEnd1 = ObjIter1();\n  VolIter2 vBegin2 = VolIter2(), vEnd2 = VolIter2(), vCur2 = VolIter2();\n  ObjIter2 oBegin2 = ObjIter2(), oEnd2 = ObjIter2(), oCur2 = ObjIter2();\n\n  std::vector<std::pair<Index1, Index2> > todo(1, std::make_pair(tree1.getRootIndex(), tree2.getRootIndex()));\n\n  while(!todo.empty()) {\n    tree1.getChildren(todo.back().first, vBegin1, vEnd1, oBegin1, oEnd1);\n    tree2.getChildren(todo.back().second, vBegin2, vEnd2, oBegin2, oEnd2);\n    todo.pop_back();\n\n    for(; vBegin1 != vEnd1; ++vBegin1) { //go through child volumes of first tree\n      const typename BVH1::Volume &vol1 = tree1.getVolume(*vBegin1);\n      for(vCur2 = vBegin2; vCur2 != vEnd2; ++vCur2) { //go through child volumes of second tree\n        if(intersector.intersectVolumeVolume(vol1, tree2.getVolume(*vCur2)))\n          todo.push_back(std::make_pair(*vBegin1, *vCur2));\n      }\n\n      for(oCur2 = oBegin2; oCur2 != oEnd2; ++oCur2) {//go through child objects of second tree\n        Helper1 helper(*oCur2, intersector);\n        if(internal::intersect_helper(tree1, helper, *vBegin1))\n          return; //intersector said to stop query\n      }\n    }\n\n    for(; oBegin1 != oEnd1; ++oBegin1) { //go through child objects of first tree\n      for(vCur2 = vBegin2; vCur2 != vEnd2; ++vCur2) { //go through child volumes of second tree\n        Helper2 helper(*oBegin1, intersector);\n        if(internal::intersect_helper(tree2, helper, *vCur2))\n          return; //intersector said to stop query\n      }\n\n      for(oCur2 = oBegin2; oCur2 != oEnd2; ++oCur2) {//go through child objects of second tree\n        if(intersector.intersectObjectObject(*oBegin1, *oCur2))\n          return; //intersector said to stop query\n      }\n    }\n  }\n}\n\nnamespace internal {\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\ntemplate<typename BVH, typename Minimizer>\ntypename Minimizer::Scalar minimize_helper(const BVH &tree, Minimizer &minimizer, typename BVH::Index root, typename Minimizer::Scalar minimum)\n{\n  typedef typename Minimizer::Scalar Scalar;\n  typedef typename BVH::Index Index;\n  typedef std::pair<Scalar, Index> QueueElement; //first element is priority\n  typedef typename BVH::VolumeIterator VolIter;\n  typedef typename BVH::ObjectIterator ObjIter;\n\n  VolIter vBegin = VolIter(), vEnd = VolIter();\n  ObjIter oBegin = ObjIter(), oEnd = ObjIter();\n  std::priority_queue<QueueElement, std::vector<QueueElement>, std::greater<QueueElement> > todo; //smallest is at the top\n\n  todo.push(std::make_pair(Scalar(), root));\n\n  while(!todo.empty()) {\n    tree.getChildren(todo.top().second, vBegin, vEnd, oBegin, oEnd);\n    todo.pop();\n\n    for(; oBegin != oEnd; ++oBegin) //go through child objects\n      minimum = (std::min)(minimum, minimizer.minimumOnObject(*oBegin));\n\n    for(; vBegin != vEnd; ++vBegin) { //go through child volumes\n      Scalar val = minimizer.minimumOnVolume(tree.getVolume(*vBegin));\n      if(val < minimum)\n        todo.push(std::make_pair(val, *vBegin));\n    }\n  }\n\n  return minimum;\n}\n#endif //not EIGEN_PARSED_BY_DOXYGEN\n\n\ntemplate<typename Volume1, typename Object1, typename Object2, typename Minimizer>\nstruct minimizer_helper1\n{\n  typedef typename Minimizer::Scalar Scalar;\n  minimizer_helper1(const Object2 &inStored, Minimizer &m) : stored(inStored), minimizer(m) {}\n  Scalar minimumOnVolume(const Volume1 &vol) { return minimizer.minimumOnVolumeObject(vol, stored); }\n  Scalar minimumOnObject(const Object1 &obj) { return minimizer.minimumOnObjectObject(obj, stored); }\n  Object2 stored;\n  Minimizer &minimizer;\nprivate:\n  minimizer_helper1& operator=(const minimizer_helper1&);\n};\n\ntemplate<typename Volume2, typename Object2, typename Object1, typename Minimizer>\nstruct minimizer_helper2\n{\n  typedef typename Minimizer::Scalar Scalar;\n  minimizer_helper2(const Object1 &inStored, Minimizer &m) : stored(inStored), minimizer(m) {}\n  Scalar minimumOnVolume(const Volume2 &vol) { return minimizer.minimumOnObjectVolume(stored, vol); }\n  Scalar minimumOnObject(const Object2 &obj) { return minimizer.minimumOnObjectObject(stored, obj); }\n  Object1 stored;\n  Minimizer &minimizer;\nprivate:\n  minimizer_helper2& operator=(const minimizer_helper2&);\n};\n\n} // end namespace internal\n\n/**  Given a BVH, runs the query encapsulated by \\a minimizer.\n  *  \\returns the minimum value.\n  *  The Minimizer type must provide the following members: \\code\n     typedef Scalar //the numeric type of what is being minimized--not necessarily the Scalar type of the BVH (if it has one)\n     Scalar minimumOnVolume(const BVH::Volume &volume)\n     Scalar minimumOnObject(const BVH::Object &object)\n  \\endcode\n  */\ntemplate<typename BVH, typename Minimizer>\ntypename Minimizer::Scalar BVMinimize(const BVH &tree, Minimizer &minimizer)\n{\n  return internal::minimize_helper(tree, minimizer, tree.getRootIndex(), (std::numeric_limits<typename Minimizer::Scalar>::max)());\n}\n\n/**  Given two BVH's, runs the query on their cartesian product encapsulated by \\a minimizer.\n  *  \\returns the minimum value.\n  *  The Minimizer type must provide the following members: \\code\n     typedef Scalar //the numeric type of what is being minimized--not necessarily the Scalar type of the BVH (if it has one)\n     Scalar minimumOnVolumeVolume(const BVH1::Volume &v1, const BVH2::Volume &v2)\n     Scalar minimumOnVolumeObject(const BVH1::Volume &v1, const BVH2::Object &o2)\n     Scalar minimumOnObjectVolume(const BVH1::Object &o1, const BVH2::Volume &v2)\n     Scalar minimumOnObjectObject(const BVH1::Object &o1, const BVH2::Object &o2)\n  \\endcode\n  */\ntemplate<typename BVH1, typename BVH2, typename Minimizer>\ntypename Minimizer::Scalar BVMinimize(const BVH1 &tree1, const BVH2 &tree2, Minimizer &minimizer)\n{\n  typedef typename Minimizer::Scalar Scalar;\n  typedef typename BVH1::Index Index1;\n  typedef typename BVH2::Index Index2;\n  typedef internal::minimizer_helper1<typename BVH1::Volume, typename BVH1::Object, typename BVH2::Object, Minimizer> Helper1;\n  typedef internal::minimizer_helper2<typename BVH2::Volume, typename BVH2::Object, typename BVH1::Object, Minimizer> Helper2;\n  typedef std::pair<Scalar, std::pair<Index1, Index2> > QueueElement; //first element is priority\n  typedef typename BVH1::VolumeIterator VolIter1;\n  typedef typename BVH1::ObjectIterator ObjIter1;\n  typedef typename BVH2::VolumeIterator VolIter2;\n  typedef typename BVH2::ObjectIterator ObjIter2;\n\n  VolIter1 vBegin1 = VolIter1(), vEnd1 = VolIter1();\n  ObjIter1 oBegin1 = ObjIter1(), oEnd1 = ObjIter1();\n  VolIter2 vBegin2 = VolIter2(), vEnd2 = VolIter2(), vCur2 = VolIter2();\n  ObjIter2 oBegin2 = ObjIter2(), oEnd2 = ObjIter2(), oCur2 = ObjIter2();\n  std::priority_queue<QueueElement, std::vector<QueueElement>, std::greater<QueueElement> > todo; //smallest is at the top\n\n  Scalar minimum = (std::numeric_limits<Scalar>::max)();\n  todo.push(std::make_pair(Scalar(), std::make_pair(tree1.getRootIndex(), tree2.getRootIndex())));\n\n  while(!todo.empty()) {\n    tree1.getChildren(todo.top().second.first, vBegin1, vEnd1, oBegin1, oEnd1);\n    tree2.getChildren(todo.top().second.second, vBegin2, vEnd2, oBegin2, oEnd2);\n    todo.pop();\n\n    for(; oBegin1 != oEnd1; ++oBegin1) { //go through child objects of first tree\n      for(oCur2 = oBegin2; oCur2 != oEnd2; ++oCur2) {//go through child objects of second tree\n        minimum = (std::min)(minimum, minimizer.minimumOnObjectObject(*oBegin1, *oCur2));\n      }\n\n      for(vCur2 = vBegin2; vCur2 != vEnd2; ++vCur2) { //go through child volumes of second tree\n        Helper2 helper(*oBegin1, minimizer);\n        minimum = (std::min)(minimum, internal::minimize_helper(tree2, helper, *vCur2, minimum));\n      }\n    }\n\n    for(; vBegin1 != vEnd1; ++vBegin1) { //go through child volumes of first tree\n      const typename BVH1::Volume &vol1 = tree1.getVolume(*vBegin1);\n\n      for(oCur2 = oBegin2; oCur2 != oEnd2; ++oCur2) {//go through child objects of second tree\n        Helper1 helper(*oCur2, minimizer);\n        minimum = (std::min)(minimum, internal::minimize_helper(tree1, helper, *vBegin1, minimum));\n      }\n\n      for(vCur2 = vBegin2; vCur2 != vEnd2; ++vCur2) { //go through child volumes of second tree\n        Scalar val = minimizer.minimumOnVolumeVolume(vol1, tree2.getVolume(*vCur2));\n        if(val < minimum)\n          todo.push(std::make_pair(val, std::make_pair(*vBegin1, *vCur2)));\n      }\n    }\n  }\n  return minimum;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_BVALGORITHMS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/BVH/KdBVH.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Ilya Baran <ibaran@mit.edu>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef KDBVH_H_INCLUDED\n#define KDBVH_H_INCLUDED\n\nnamespace Eigen { \n\nnamespace internal {\n\n//internal pair class for the BVH--used instead of std::pair because of alignment\ntemplate<typename Scalar, int Dim>\nstruct vector_int_pair\n{\nEIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(Scalar, Dim)\n  typedef Matrix<Scalar, Dim, 1> VectorType;\n\n  vector_int_pair(const VectorType &v, int i) : first(v), second(i) {}\n\n  VectorType first;\n  int second;\n};\n\n//these templates help the tree initializer get the bounding boxes either from a provided\n//iterator range or using bounding_box in a unified way\ntemplate<typename ObjectList, typename VolumeList, typename BoxIter>\nstruct get_boxes_helper {\n  void operator()(const ObjectList &objects, BoxIter boxBegin, BoxIter boxEnd, VolumeList &outBoxes)\n  {\n    outBoxes.insert(outBoxes.end(), boxBegin, boxEnd);\n    eigen_assert(outBoxes.size() == objects.size());\n    EIGEN_ONLY_USED_FOR_DEBUG(objects);\n  }\n};\n\ntemplate<typename ObjectList, typename VolumeList>\nstruct get_boxes_helper<ObjectList, VolumeList, int> {\n  void operator()(const ObjectList &objects, int, int, VolumeList &outBoxes)\n  {\n    outBoxes.reserve(objects.size());\n    for(int i = 0; i < (int)objects.size(); ++i)\n      outBoxes.push_back(bounding_box(objects[i]));\n  }\n};\n\n} // end namespace internal\n\n\n/** \\class KdBVH\n *  \\brief A simple bounding volume hierarchy based on AlignedBox\n *\n *  \\param _Scalar The underlying scalar type of the bounding boxes\n *  \\param _Dim The dimension of the space in which the hierarchy lives\n *  \\param _Object The object type that lives in the hierarchy.  It must have value semantics.  Either bounding_box(_Object) must\n *                 be defined and return an AlignedBox<_Scalar, _Dim> or bounding boxes must be provided to the tree initializer.\n *\n *  This class provides a simple (as opposed to optimized) implementation of a bounding volume hierarchy analogous to a Kd-tree.\n *  Given a sequence of objects, it computes their bounding boxes, constructs a Kd-tree of their centers\n *  and builds a BVH with the structure of that Kd-tree.  When the elements of the tree are too expensive to be copied around,\n *  it is useful for _Object to be a pointer.\n */\ntemplate<typename _Scalar, int _Dim, typename _Object> class KdBVH\n{\npublic:\n  enum { Dim = _Dim };\n  typedef _Object Object;\n  typedef std::vector<Object, aligned_allocator<Object> > ObjectList;\n  typedef _Scalar Scalar;\n  typedef AlignedBox<Scalar, Dim> Volume;\n  typedef std::vector<Volume, aligned_allocator<Volume> > VolumeList;\n  typedef int Index;\n  typedef const int *VolumeIterator; //the iterators are just pointers into the tree's vectors\n  typedef const Object *ObjectIterator;\n\n  KdBVH() {}\n\n  /** Given an iterator range over \\a Object references, constructs the BVH.  Requires that bounding_box(Object) return a Volume. */\n  template<typename Iter> KdBVH(Iter begin, Iter end) { init(begin, end, 0, 0); } //int is recognized by init as not being an iterator type\n\n  /** Given an iterator range over \\a Object references and an iterator range over their bounding boxes, constructs the BVH */\n  template<typename OIter, typename BIter> KdBVH(OIter begin, OIter end, BIter boxBegin, BIter boxEnd) { init(begin, end, boxBegin, boxEnd); }\n\n  /** Given an iterator range over \\a Object references, constructs the BVH, overwriting whatever is in there currently.\n    * Requires that bounding_box(Object) return a Volume. */\n  template<typename Iter> void init(Iter begin, Iter end) { init(begin, end, 0, 0); }\n\n  /** Given an iterator range over \\a Object references and an iterator range over their bounding boxes,\n    * constructs the BVH, overwriting whatever is in there currently. */\n  template<typename OIter, typename BIter> void init(OIter begin, OIter end, BIter boxBegin, BIter boxEnd)\n  {\n    objects.clear();\n    boxes.clear();\n    children.clear();\n\n    objects.insert(objects.end(), begin, end);\n    int n = static_cast<int>(objects.size());\n\n    if(n < 2)\n      return; //if we have at most one object, we don't need any internal nodes\n\n    VolumeList objBoxes;\n    VIPairList objCenters;\n\n    //compute the bounding boxes depending on BIter type\n    internal::get_boxes_helper<ObjectList, VolumeList, BIter>()(objects, boxBegin, boxEnd, objBoxes);\n\n    objCenters.reserve(n);\n    boxes.reserve(n - 1);\n    children.reserve(2 * n - 2);\n\n    for(int i = 0; i < n; ++i)\n      objCenters.push_back(VIPair(objBoxes[i].center(), i));\n\n    build(objCenters, 0, n, objBoxes, 0); //the recursive part of the algorithm\n\n    ObjectList tmp(n);\n    tmp.swap(objects);\n    for(int i = 0; i < n; ++i)\n      objects[i] = tmp[objCenters[i].second];\n  }\n\n  /** \\returns the index of the root of the hierarchy */\n  inline Index getRootIndex() const { return (int)boxes.size() - 1; }\n\n  /** Given an \\a index of a node, on exit, \\a outVBegin and \\a outVEnd range over the indices of the volume children of the node\n    * and \\a outOBegin and \\a outOEnd range over the object children of the node */\n  EIGEN_STRONG_INLINE void getChildren(Index index, VolumeIterator &outVBegin, VolumeIterator &outVEnd,\n                                       ObjectIterator &outOBegin, ObjectIterator &outOEnd) const\n  { //inlining this function should open lots of optimization opportunities to the compiler\n    if(index < 0) {\n      outVBegin = outVEnd;\n      if(!objects.empty())\n        outOBegin = &(objects[0]);\n      outOEnd = outOBegin + objects.size(); //output all objects--necessary when the tree has only one object\n      return;\n    }\n\n    int numBoxes = static_cast<int>(boxes.size());\n\n    int idx = index * 2;\n    if(children[idx + 1] < numBoxes) { //second index is always bigger\n      outVBegin = &(children[idx]);\n      outVEnd = outVBegin + 2;\n      outOBegin = outOEnd;\n    }\n    else if(children[idx] >= numBoxes) { //if both children are objects\n      outVBegin = outVEnd;\n      outOBegin = &(objects[children[idx] - numBoxes]);\n      outOEnd = outOBegin + 2;\n    } else { //if the first child is a volume and the second is an object\n      outVBegin = &(children[idx]);\n      outVEnd = outVBegin + 1;\n      outOBegin = &(objects[children[idx + 1] - numBoxes]);\n      outOEnd = outOBegin + 1;\n    }\n  }\n\n  /** \\returns the bounding box of the node at \\a index */\n  inline const Volume &getVolume(Index index) const\n  {\n    return boxes[index];\n  }\n\nprivate:\n  typedef internal::vector_int_pair<Scalar, Dim> VIPair;\n  typedef std::vector<VIPair, aligned_allocator<VIPair> > VIPairList;\n  typedef Matrix<Scalar, Dim, 1> VectorType;\n  struct VectorComparator //compares vectors, or more specifically, VIPairs along a particular dimension\n  {\n    VectorComparator(int inDim) : dim(inDim) {}\n    inline bool operator()(const VIPair &v1, const VIPair &v2) const { return v1.first[dim] < v2.first[dim]; }\n    int dim;\n  };\n\n  //Build the part of the tree between objects[from] and objects[to] (not including objects[to]).\n  //This routine partitions the objCenters in [from, to) along the dimension dim, recursively constructs\n  //the two halves, and adds their parent node.  TODO: a cache-friendlier layout\n  void build(VIPairList &objCenters, int from, int to, const VolumeList &objBoxes, int dim)\n  {\n    eigen_assert(to - from > 1);\n    if(to - from == 2) {\n      boxes.push_back(objBoxes[objCenters[from].second].merged(objBoxes[objCenters[from + 1].second]));\n      children.push_back(from + (int)objects.size() - 1); //there are objects.size() - 1 tree nodes\n      children.push_back(from + (int)objects.size());\n    }\n    else if(to - from == 3) {\n      int mid = from + 2;\n      std::nth_element(objCenters.begin() + from, objCenters.begin() + mid,\n                        objCenters.begin() + to, VectorComparator(dim)); //partition\n      build(objCenters, from, mid, objBoxes, (dim + 1) % Dim);\n      int idx1 = (int)boxes.size() - 1;\n      boxes.push_back(boxes[idx1].merged(objBoxes[objCenters[mid].second]));\n      children.push_back(idx1);\n      children.push_back(mid + (int)objects.size() - 1);\n    }\n    else {\n      int mid = from + (to - from) / 2;\n      nth_element(objCenters.begin() + from, objCenters.begin() + mid,\n                  objCenters.begin() + to, VectorComparator(dim)); //partition\n      build(objCenters, from, mid, objBoxes, (dim + 1) % Dim);\n      int idx1 = (int)boxes.size() - 1;\n      build(objCenters, mid, to, objBoxes, (dim + 1) % Dim);\n      int idx2 = (int)boxes.size() - 1;\n      boxes.push_back(boxes[idx1].merged(boxes[idx2]));\n      children.push_back(idx1);\n      children.push_back(idx2);\n    }\n  }\n\n  std::vector<int> children; //children of x are children[2x] and children[2x+1], indices bigger than boxes.size() index into objects.\n  VolumeList boxes;\n  ObjectList objects;\n};\n\n} // end namespace Eigen\n\n#endif //KDBVH_H_INCLUDED\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/Eigenvalues/ArpackSelfAdjointEigenSolver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 David Harmon <dharmon@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ARPACKGENERALIZEDSELFADJOINTEIGENSOLVER_H\n#define EIGEN_ARPACKGENERALIZEDSELFADJOINTEIGENSOLVER_H\n\n#include \"../../../../Eigen/Dense\"\n\nnamespace Eigen { \n\nnamespace internal {\n  template<typename Scalar, typename RealScalar> struct arpack_wrapper;\n  template<typename MatrixSolver, typename MatrixType, typename Scalar, bool BisSPD> struct OP;\n}\n\n\n\ntemplate<typename MatrixType, typename MatrixSolver=SimplicialLLT<MatrixType>, bool BisSPD=false>\nclass ArpackGeneralizedSelfAdjointEigenSolver\n{\npublic:\n  //typedef typename MatrixSolver::MatrixType MatrixType;\n\n  /** \\brief Scalar type for matrices of type \\p MatrixType. */\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::Index Index;\n\n  /** \\brief Real scalar type for \\p MatrixType.\n   *\n   * This is just \\c Scalar if #Scalar is real (e.g., \\c float or\n   * \\c Scalar), and the type of the real part of \\c Scalar if #Scalar is\n   * complex.\n   */\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  /** \\brief Type for vector of eigenvalues as returned by eigenvalues().\n   *\n   * This is a column vector with entries of type #RealScalar.\n   * The length of the vector is the size of \\p nbrEigenvalues.\n   */\n  typedef typename internal::plain_col_type<MatrixType, RealScalar>::type RealVectorType;\n\n  /** \\brief Default constructor.\n   *\n   * The default constructor is for cases in which the user intends to\n   * perform decompositions via compute().\n   *\n   */\n  ArpackGeneralizedSelfAdjointEigenSolver()\n   : m_eivec(),\n     m_eivalues(),\n     m_isInitialized(false),\n     m_eigenvectorsOk(false),\n     m_nbrConverged(0),\n     m_nbrIterations(0)\n  { }\n\n  /** \\brief Constructor; computes generalized eigenvalues of given matrix with respect to another matrix.\n   *\n   * \\param[in] A Self-adjoint matrix whose eigenvalues / eigenvectors will\n   *    computed. By default, the upper triangular part is used, but can be changed\n   *    through the template parameter.\n   * \\param[in] B Self-adjoint matrix for the generalized eigenvalue problem.\n   * \\param[in] nbrEigenvalues The number of eigenvalues / eigenvectors to compute.\n   *    Must be less than the size of the input matrix, or an error is returned.\n   * \\param[in] eigs_sigma String containing either \"LM\", \"SM\", \"LA\", or \"SA\", with\n   *    respective meanings to find the largest magnitude , smallest magnitude,\n   *    largest algebraic, or smallest algebraic eigenvalues. Alternatively, this\n   *    value can contain floating point value in string form, in which case the\n   *    eigenvalues closest to this value will be found.\n   * \\param[in]  options Can be #ComputeEigenvectors (default) or #EigenvaluesOnly.\n   * \\param[in] tol What tolerance to find the eigenvalues to. Default is 0, which\n   *    means machine precision.\n   *\n   * This constructor calls compute(const MatrixType&, const MatrixType&, Index, string, int, RealScalar)\n   * to compute the eigenvalues of the matrix \\p A with respect to \\p B. The eigenvectors are computed if\n   * \\p options equals #ComputeEigenvectors.\n   *\n   */\n  ArpackGeneralizedSelfAdjointEigenSolver(const MatrixType& A, const MatrixType& B,\n                                          Index nbrEigenvalues, std::string eigs_sigma=\"LM\",\n                               int options=ComputeEigenvectors, RealScalar tol=0.0)\n    : m_eivec(),\n      m_eivalues(),\n      m_isInitialized(false),\n      m_eigenvectorsOk(false),\n      m_nbrConverged(0),\n      m_nbrIterations(0)\n  {\n    compute(A, B, nbrEigenvalues, eigs_sigma, options, tol);\n  }\n\n  /** \\brief Constructor; computes eigenvalues of given matrix.\n   *\n   * \\param[in] A Self-adjoint matrix whose eigenvalues / eigenvectors will\n   *    computed. By default, the upper triangular part is used, but can be changed\n   *    through the template parameter.\n   * \\param[in] nbrEigenvalues The number of eigenvalues / eigenvectors to compute.\n   *    Must be less than the size of the input matrix, or an error is returned.\n   * \\param[in] eigs_sigma String containing either \"LM\", \"SM\", \"LA\", or \"SA\", with\n   *    respective meanings to find the largest magnitude , smallest magnitude,\n   *    largest algebraic, or smallest algebraic eigenvalues. Alternatively, this\n   *    value can contain floating point value in string form, in which case the\n   *    eigenvalues closest to this value will be found.\n   * \\param[in]  options Can be #ComputeEigenvectors (default) or #EigenvaluesOnly.\n   * \\param[in] tol What tolerance to find the eigenvalues to. Default is 0, which\n   *    means machine precision.\n   *\n   * This constructor calls compute(const MatrixType&, Index, string, int, RealScalar)\n   * to compute the eigenvalues of the matrix \\p A. The eigenvectors are computed if\n   * \\p options equals #ComputeEigenvectors.\n   *\n   */\n\n  ArpackGeneralizedSelfAdjointEigenSolver(const MatrixType& A,\n                                          Index nbrEigenvalues, std::string eigs_sigma=\"LM\",\n                               int options=ComputeEigenvectors, RealScalar tol=0.0)\n    : m_eivec(),\n      m_eivalues(),\n      m_isInitialized(false),\n      m_eigenvectorsOk(false),\n      m_nbrConverged(0),\n      m_nbrIterations(0)\n  {\n    compute(A, nbrEigenvalues, eigs_sigma, options, tol);\n  }\n\n\n  /** \\brief Computes generalized eigenvalues / eigenvectors of given matrix using the external ARPACK library.\n   *\n   * \\param[in]  A  Selfadjoint matrix whose eigendecomposition is to be computed.\n   * \\param[in]  B  Selfadjoint matrix for generalized eigenvalues.\n   * \\param[in] nbrEigenvalues The number of eigenvalues / eigenvectors to compute.\n   *    Must be less than the size of the input matrix, or an error is returned.\n   * \\param[in] eigs_sigma String containing either \"LM\", \"SM\", \"LA\", or \"SA\", with\n   *    respective meanings to find the largest magnitude , smallest magnitude,\n   *    largest algebraic, or smallest algebraic eigenvalues. Alternatively, this\n   *    value can contain floating point value in string form, in which case the\n   *    eigenvalues closest to this value will be found.\n   * \\param[in]  options Can be #ComputeEigenvectors (default) or #EigenvaluesOnly.\n   * \\param[in] tol What tolerance to find the eigenvalues to. Default is 0, which\n   *    means machine precision.\n   *\n   * \\returns    Reference to \\c *this\n   *\n   * This function computes the generalized eigenvalues of \\p A with respect to \\p B using ARPACK.  The eigenvalues()\n   * function can be used to retrieve them.  If \\p options equals #ComputeEigenvectors,\n   * then the eigenvectors are also computed and can be retrieved by\n   * calling eigenvectors().\n   *\n   */\n  ArpackGeneralizedSelfAdjointEigenSolver& compute(const MatrixType& A, const MatrixType& B,\n                                                   Index nbrEigenvalues, std::string eigs_sigma=\"LM\",\n                                        int options=ComputeEigenvectors, RealScalar tol=0.0);\n  \n  /** \\brief Computes eigenvalues / eigenvectors of given matrix using the external ARPACK library.\n   *\n   * \\param[in]  A  Selfadjoint matrix whose eigendecomposition is to be computed.\n   * \\param[in] nbrEigenvalues The number of eigenvalues / eigenvectors to compute.\n   *    Must be less than the size of the input matrix, or an error is returned.\n   * \\param[in] eigs_sigma String containing either \"LM\", \"SM\", \"LA\", or \"SA\", with\n   *    respective meanings to find the largest magnitude , smallest magnitude,\n   *    largest algebraic, or smallest algebraic eigenvalues. Alternatively, this\n   *    value can contain floating point value in string form, in which case the\n   *    eigenvalues closest to this value will be found.\n   * \\param[in]  options Can be #ComputeEigenvectors (default) or #EigenvaluesOnly.\n   * \\param[in] tol What tolerance to find the eigenvalues to. Default is 0, which\n   *    means machine precision.\n   *\n   * \\returns    Reference to \\c *this\n   *\n   * This function computes the eigenvalues of \\p A using ARPACK.  The eigenvalues()\n   * function can be used to retrieve them.  If \\p options equals #ComputeEigenvectors,\n   * then the eigenvectors are also computed and can be retrieved by\n   * calling eigenvectors().\n   *\n   */\n  ArpackGeneralizedSelfAdjointEigenSolver& compute(const MatrixType& A,\n                                                   Index nbrEigenvalues, std::string eigs_sigma=\"LM\",\n                                        int options=ComputeEigenvectors, RealScalar tol=0.0);\n\n\n  /** \\brief Returns the eigenvectors of given matrix.\n   *\n   * \\returns  A const reference to the matrix whose columns are the eigenvectors.\n   *\n   * \\pre The eigenvectors have been computed before.\n   *\n   * Column \\f$ k \\f$ of the returned matrix is an eigenvector corresponding\n   * to eigenvalue number \\f$ k \\f$ as returned by eigenvalues().  The\n   * eigenvectors are normalized to have (Euclidean) norm equal to one. If\n   * this object was used to solve the eigenproblem for the selfadjoint\n   * matrix \\f$ A \\f$, then the matrix returned by this function is the\n   * matrix \\f$ V \\f$ in the eigendecomposition \\f$ A V = D V \\f$.\n   * For the generalized eigenproblem, the matrix returned is the solution \\f$ A V = D B V \\f$\n   *\n   * Example: \\include SelfAdjointEigenSolver_eigenvectors.cpp\n   * Output: \\verbinclude SelfAdjointEigenSolver_eigenvectors.out\n   *\n   * \\sa eigenvalues()\n   */\n  const Matrix<Scalar, Dynamic, Dynamic>& eigenvectors() const\n  {\n    eigen_assert(m_isInitialized && \"ArpackGeneralizedSelfAdjointEigenSolver is not initialized.\");\n    eigen_assert(m_eigenvectorsOk && \"The eigenvectors have not been computed together with the eigenvalues.\");\n    return m_eivec;\n  }\n\n  /** \\brief Returns the eigenvalues of given matrix.\n   *\n   * \\returns A const reference to the column vector containing the eigenvalues.\n   *\n   * \\pre The eigenvalues have been computed before.\n   *\n   * The eigenvalues are repeated according to their algebraic multiplicity,\n   * so there are as many eigenvalues as rows in the matrix. The eigenvalues\n   * are sorted in increasing order.\n   *\n   * Example: \\include SelfAdjointEigenSolver_eigenvalues.cpp\n   * Output: \\verbinclude SelfAdjointEigenSolver_eigenvalues.out\n   *\n   * \\sa eigenvectors(), MatrixBase::eigenvalues()\n   */\n  const Matrix<Scalar, Dynamic, 1>& eigenvalues() const\n  {\n    eigen_assert(m_isInitialized && \"ArpackGeneralizedSelfAdjointEigenSolver is not initialized.\");\n    return m_eivalues;\n  }\n\n  /** \\brief Computes the positive-definite square root of the matrix.\n   *\n   * \\returns the positive-definite square root of the matrix\n   *\n   * \\pre The eigenvalues and eigenvectors of a positive-definite matrix\n   * have been computed before.\n   *\n   * The square root of a positive-definite matrix \\f$ A \\f$ is the\n   * positive-definite matrix whose square equals \\f$ A \\f$. This function\n   * uses the eigendecomposition \\f$ A = V D V^{-1} \\f$ to compute the\n   * square root as \\f$ A^{1/2} = V D^{1/2} V^{-1} \\f$.\n   *\n   * Example: \\include SelfAdjointEigenSolver_operatorSqrt.cpp\n   * Output: \\verbinclude SelfAdjointEigenSolver_operatorSqrt.out\n   *\n   * \\sa operatorInverseSqrt(),\n   *     \\ref MatrixFunctions_Module \"MatrixFunctions Module\"\n   */\n  Matrix<Scalar, Dynamic, Dynamic> operatorSqrt() const\n  {\n    eigen_assert(m_isInitialized && \"SelfAdjointEigenSolver is not initialized.\");\n    eigen_assert(m_eigenvectorsOk && \"The eigenvectors have not been computed together with the eigenvalues.\");\n    return m_eivec * m_eivalues.cwiseSqrt().asDiagonal() * m_eivec.adjoint();\n  }\n\n  /** \\brief Computes the inverse square root of the matrix.\n   *\n   * \\returns the inverse positive-definite square root of the matrix\n   *\n   * \\pre The eigenvalues and eigenvectors of a positive-definite matrix\n   * have been computed before.\n   *\n   * This function uses the eigendecomposition \\f$ A = V D V^{-1} \\f$ to\n   * compute the inverse square root as \\f$ V D^{-1/2} V^{-1} \\f$. This is\n   * cheaper than first computing the square root with operatorSqrt() and\n   * then its inverse with MatrixBase::inverse().\n   *\n   * Example: \\include SelfAdjointEigenSolver_operatorInverseSqrt.cpp\n   * Output: \\verbinclude SelfAdjointEigenSolver_operatorInverseSqrt.out\n   *\n   * \\sa operatorSqrt(), MatrixBase::inverse(),\n   *     \\ref MatrixFunctions_Module \"MatrixFunctions Module\"\n   */\n  Matrix<Scalar, Dynamic, Dynamic> operatorInverseSqrt() const\n  {\n    eigen_assert(m_isInitialized && \"SelfAdjointEigenSolver is not initialized.\");\n    eigen_assert(m_eigenvectorsOk && \"The eigenvectors have not been computed together with the eigenvalues.\");\n    return m_eivec * m_eivalues.cwiseInverse().cwiseSqrt().asDiagonal() * m_eivec.adjoint();\n  }\n\n  /** \\brief Reports whether previous computation was successful.\n   *\n   * \\returns \\c Success if computation was successful, \\c NoConvergence otherwise.\n   */\n  ComputationInfo info() const\n  {\n    eigen_assert(m_isInitialized && \"ArpackGeneralizedSelfAdjointEigenSolver is not initialized.\");\n    return m_info;\n  }\n\n  size_t getNbrConvergedEigenValues() const\n  { return m_nbrConverged; }\n\n  size_t getNbrIterations() const\n  { return m_nbrIterations; }\n\nprotected:\n  Matrix<Scalar, Dynamic, Dynamic> m_eivec;\n  Matrix<Scalar, Dynamic, 1> m_eivalues;\n  ComputationInfo m_info;\n  bool m_isInitialized;\n  bool m_eigenvectorsOk;\n\n  size_t m_nbrConverged;\n  size_t m_nbrIterations;\n};\n\n\n\n\n\ntemplate<typename MatrixType, typename MatrixSolver, bool BisSPD>\nArpackGeneralizedSelfAdjointEigenSolver<MatrixType, MatrixSolver, BisSPD>&\n    ArpackGeneralizedSelfAdjointEigenSolver<MatrixType, MatrixSolver, BisSPD>\n::compute(const MatrixType& A, Index nbrEigenvalues,\n          std::string eigs_sigma, int options, RealScalar tol)\n{\n    MatrixType B(0,0);\n    compute(A, B, nbrEigenvalues, eigs_sigma, options, tol);\n    \n    return *this;\n}\n\n\ntemplate<typename MatrixType, typename MatrixSolver, bool BisSPD>\nArpackGeneralizedSelfAdjointEigenSolver<MatrixType, MatrixSolver, BisSPD>&\n    ArpackGeneralizedSelfAdjointEigenSolver<MatrixType, MatrixSolver, BisSPD>\n::compute(const MatrixType& A, const MatrixType& B, Index nbrEigenvalues,\n          std::string eigs_sigma, int options, RealScalar tol)\n{\n  eigen_assert(A.cols() == A.rows());\n  eigen_assert(B.cols() == B.rows());\n  eigen_assert(B.rows() == 0 || A.cols() == B.rows());\n  eigen_assert((options &~ (EigVecMask | GenEigMask)) == 0\n            && (options & EigVecMask) != EigVecMask\n            && \"invalid option parameter\");\n\n  bool isBempty = (B.rows() == 0) || (B.cols() == 0);\n\n  // For clarity, all parameters match their ARPACK name\n  //\n  // Always 0 on the first call\n  //\n  int ido = 0;\n\n  int n = (int)A.cols();\n\n  // User options: \"LA\", \"SA\", \"SM\", \"LM\", \"BE\"\n  //\n  char whch[3] = \"LM\";\n    \n  // Specifies the shift if iparam[6] = { 3, 4, 5 }, not used if iparam[6] = { 1, 2 }\n  //\n  RealScalar sigma = 0.0;\n\n  if (eigs_sigma.length() >= 2 && isalpha(eigs_sigma[0]) && isalpha(eigs_sigma[1]))\n  {\n      eigs_sigma[0] = toupper(eigs_sigma[0]);\n      eigs_sigma[1] = toupper(eigs_sigma[1]);\n\n      // In the following special case we're going to invert the problem, since solving\n      // for larger magnitude is much much faster\n      // i.e., if 'SM' is specified, we're going to really use 'LM', the default\n      //\n      if (eigs_sigma.substr(0,2) != \"SM\")\n      {\n          whch[0] = eigs_sigma[0];\n          whch[1] = eigs_sigma[1];\n      }\n  }\n  else\n  {\n      eigen_assert(false && \"Specifying clustered eigenvalues is not yet supported!\");\n\n      // If it's not scalar values, then the user may be explicitly\n      // specifying the sigma value to cluster the evs around\n      //\n      sigma = atof(eigs_sigma.c_str());\n\n      // If atof fails, it returns 0.0, which is a fine default\n      //\n  }\n\n  // \"I\" means normal eigenvalue problem, \"G\" means generalized\n  //\n  char bmat[2] = \"I\";\n  if (eigs_sigma.substr(0,2) == \"SM\" || !(isalpha(eigs_sigma[0]) && isalpha(eigs_sigma[1])) || (!isBempty && !BisSPD))\n      bmat[0] = 'G';\n\n  // Now we determine the mode to use\n  //\n  int mode = (bmat[0] == 'G') + 1;\n  if (eigs_sigma.substr(0,2) == \"SM\" || !(isalpha(eigs_sigma[0]) && isalpha(eigs_sigma[1])))\n  {\n      // We're going to use shift-and-invert mode, and basically find\n      // the largest eigenvalues of the inverse operator\n      //\n      mode = 3;\n  }\n\n  // The user-specified number of eigenvalues/vectors to compute\n  //\n  int nev = (int)nbrEigenvalues;\n\n  // Allocate space for ARPACK to store the residual\n  //\n  Scalar *resid = new Scalar[n];\n\n  // Number of Lanczos vectors, must satisfy nev < ncv <= n\n  // Note that this indicates that nev != n, and we cannot compute\n  // all eigenvalues of a mtrix\n  //\n  int ncv = std::min(std::max(2*nev, 20), n);\n\n  // The working n x ncv matrix, also store the final eigenvectors (if computed)\n  //\n  Scalar *v = new Scalar[n*ncv];\n  int ldv = n;\n\n  // Working space\n  //\n  Scalar *workd = new Scalar[3*n];\n  int lworkl = ncv*ncv+8*ncv; // Must be at least this length\n  Scalar *workl = new Scalar[lworkl];\n\n  int *iparam= new int[11];\n  iparam[0] = 1; // 1 means we let ARPACK perform the shifts, 0 means we'd have to do it\n  iparam[2] = std::max(300, (int)std::ceil(2*n/std::max(ncv,1)));\n  iparam[6] = mode; // The mode, 1 is standard ev problem, 2 for generalized ev, 3 for shift-and-invert\n\n  // Used during reverse communicate to notify where arrays start\n  //\n  int *ipntr = new int[11]; \n\n  // Error codes are returned in here, initial value of 0 indicates a random initial\n  // residual vector is used, any other values means resid contains the initial residual\n  // vector, possibly from a previous run\n  //\n  int info = 0;\n\n  Scalar scale = 1.0;\n  //if (!isBempty)\n  //{\n  //Scalar scale = B.norm() / std::sqrt(n);\n  //scale = std::pow(2, std::floor(std::log(scale+1)));\n  ////M /= scale;\n  //for (size_t i=0; i<(size_t)B.outerSize(); i++)\n  //    for (typename MatrixType::InnerIterator it(B, i); it; ++it)\n  //        it.valueRef() /= scale;\n  //}\n\n  MatrixSolver OP;\n  if (mode == 1 || mode == 2)\n  {\n      if (!isBempty)\n          OP.compute(B);\n  }\n  else if (mode == 3)\n  {\n      if (sigma == 0.0)\n      {\n          OP.compute(A);\n      }\n      else\n      {\n          // Note: We will never enter here because sigma must be 0.0\n          //\n          if (isBempty)\n          {\n            MatrixType AminusSigmaB(A);\n            for (Index i=0; i<A.rows(); ++i)\n                AminusSigmaB.coeffRef(i,i) -= sigma;\n            \n            OP.compute(AminusSigmaB);\n          }\n          else\n          {\n              MatrixType AminusSigmaB = A - sigma * B;\n              OP.compute(AminusSigmaB);\n          }\n      }\n  }\n \n  if (!(mode == 1 && isBempty) && !(mode == 2 && isBempty) && OP.info() != Success)\n      std::cout << \"Error factoring matrix\" << std::endl;\n\n  do\n  {\n    internal::arpack_wrapper<Scalar, RealScalar>::saupd(&ido, bmat, &n, whch, &nev, &tol, resid, \n                                                        &ncv, v, &ldv, iparam, ipntr, workd, workl,\n                                                        &lworkl, &info);\n\n    if (ido == -1 || ido == 1)\n    {\n      Scalar *in  = workd + ipntr[0] - 1;\n      Scalar *out = workd + ipntr[1] - 1;\n\n      if (ido == 1 && mode != 2)\n      {\n          Scalar *out2 = workd + ipntr[2] - 1;\n          if (isBempty || mode == 1)\n            Matrix<Scalar, Dynamic, 1>::Map(out2, n) = Matrix<Scalar, Dynamic, 1>::Map(in, n);\n          else\n            Matrix<Scalar, Dynamic, 1>::Map(out2, n) = B * Matrix<Scalar, Dynamic, 1>::Map(in, n);\n          \n          in = workd + ipntr[2] - 1;\n      }\n\n      if (mode == 1)\n      {\n        if (isBempty)\n        {\n          // OP = A\n          //\n          Matrix<Scalar, Dynamic, 1>::Map(out, n) = A * Matrix<Scalar, Dynamic, 1>::Map(in, n);\n        }\n        else\n        {\n          // OP = L^{-1}AL^{-T}\n          //\n          internal::OP<MatrixSolver, MatrixType, Scalar, BisSPD>::applyOP(OP, A, n, in, out);\n        }\n      }\n      else if (mode == 2)\n      {\n        if (ido == 1)\n          Matrix<Scalar, Dynamic, 1>::Map(in, n)  = A * Matrix<Scalar, Dynamic, 1>::Map(in, n);\n        \n        // OP = B^{-1} A\n        //\n        Matrix<Scalar, Dynamic, 1>::Map(out, n) = OP.solve(Matrix<Scalar, Dynamic, 1>::Map(in, n));\n      }\n      else if (mode == 3)\n      {\n        // OP = (A-\\sigmaB)B (\\sigma could be 0, and B could be I)\n        // The B * in is already computed and stored at in if ido == 1\n        //\n        if (ido == 1 || isBempty)\n          Matrix<Scalar, Dynamic, 1>::Map(out, n) = OP.solve(Matrix<Scalar, Dynamic, 1>::Map(in, n));\n        else\n          Matrix<Scalar, Dynamic, 1>::Map(out, n) = OP.solve(B * Matrix<Scalar, Dynamic, 1>::Map(in, n));\n      }\n    }\n    else if (ido == 2)\n    {\n      Scalar *in  = workd + ipntr[0] - 1;\n      Scalar *out = workd + ipntr[1] - 1;\n\n      if (isBempty || mode == 1)\n        Matrix<Scalar, Dynamic, 1>::Map(out, n) = Matrix<Scalar, Dynamic, 1>::Map(in, n);\n      else\n        Matrix<Scalar, Dynamic, 1>::Map(out, n) = B * Matrix<Scalar, Dynamic, 1>::Map(in, n);\n    }\n  } while (ido != 99);\n\n  if (info == 1)\n    m_info = NoConvergence;\n  else if (info == 3)\n    m_info = NumericalIssue;\n  else if (info < 0)\n    m_info = InvalidInput;\n  else if (info != 0)\n    eigen_assert(false && \"Unknown ARPACK return value!\");\n  else\n  {\n    // Do we compute eigenvectors or not?\n    //\n    int rvec = (options & ComputeEigenvectors) == ComputeEigenvectors;\n\n    // \"A\" means \"All\", use \"S\" to choose specific eigenvalues (not yet supported in ARPACK))\n    //\n    char howmny[2] = \"A\"; \n\n    // if howmny == \"S\", specifies the eigenvalues to compute (not implemented in ARPACK)\n    //\n    int *select = new int[ncv];\n\n    // Final eigenvalues\n    //\n    m_eivalues.resize(nev, 1);\n\n    internal::arpack_wrapper<Scalar, RealScalar>::seupd(&rvec, howmny, select, m_eivalues.data(), v, &ldv,\n                                                        &sigma, bmat, &n, whch, &nev, &tol, resid, &ncv,\n                                                        v, &ldv, iparam, ipntr, workd, workl, &lworkl, &info);\n\n    if (info == -14)\n      m_info = NoConvergence;\n    else if (info != 0)\n      m_info = InvalidInput;\n    else\n    {\n      if (rvec)\n      {\n        m_eivec.resize(A.rows(), nev);\n        for (int i=0; i<nev; i++)\n          for (int j=0; j<n; j++)\n            m_eivec(j,i) = v[i*n+j] / scale;\n      \n        if (mode == 1 && !isBempty && BisSPD)\n          internal::OP<MatrixSolver, MatrixType, Scalar, BisSPD>::project(OP, n, nev, m_eivec.data());\n\n        m_eigenvectorsOk = true;\n      }\n\n      m_nbrIterations = iparam[2];\n      m_nbrConverged  = iparam[4];\n\n      m_info = Success;\n    }\n\n    delete[] select;\n  }\n\n  delete[] v;\n  delete[] iparam;\n  delete[] ipntr;\n  delete[] workd;\n  delete[] workl;\n  delete[] resid;\n\n  m_isInitialized = true;\n\n  return *this;\n}\n\n\n// Single precision\n//\nextern \"C\" void ssaupd_(int *ido, char *bmat, int *n, char *which,\n    int *nev, float *tol, float *resid, int *ncv,\n    float *v, int *ldv, int *iparam, int *ipntr,\n    float *workd, float *workl, int *lworkl,\n    int *info);\n\nextern \"C\" void sseupd_(int *rvec, char *All, int *select, float *d,\n    float *z, int *ldz, float *sigma, \n    char *bmat, int *n, char *which, int *nev,\n    float *tol, float *resid, int *ncv, float *v,\n    int *ldv, int *iparam, int *ipntr, float *workd,\n    float *workl, int *lworkl, int *ierr);\n\n// Double precision\n//\nextern \"C\" void dsaupd_(int *ido, char *bmat, int *n, char *which,\n    int *nev, double *tol, double *resid, int *ncv,\n    double *v, int *ldv, int *iparam, int *ipntr,\n    double *workd, double *workl, int *lworkl,\n    int *info);\n\nextern \"C\" void dseupd_(int *rvec, char *All, int *select, double *d,\n    double *z, int *ldz, double *sigma, \n    char *bmat, int *n, char *which, int *nev,\n    double *tol, double *resid, int *ncv, double *v,\n    int *ldv, int *iparam, int *ipntr, double *workd,\n    double *workl, int *lworkl, int *ierr);\n\n\nnamespace internal {\n\ntemplate<typename Scalar, typename RealScalar> struct arpack_wrapper\n{\n  static inline void saupd(int *ido, char *bmat, int *n, char *which,\n      int *nev, RealScalar *tol, Scalar *resid, int *ncv,\n      Scalar *v, int *ldv, int *iparam, int *ipntr,\n      Scalar *workd, Scalar *workl, int *lworkl, int *info)\n  { \n    EIGEN_STATIC_ASSERT(!NumTraits<Scalar>::IsComplex, NUMERIC_TYPE_MUST_BE_REAL)\n  }\n\n  static inline void seupd(int *rvec, char *All, int *select, Scalar *d,\n      Scalar *z, int *ldz, RealScalar *sigma,\n      char *bmat, int *n, char *which, int *nev,\n      RealScalar *tol, Scalar *resid, int *ncv, Scalar *v,\n      int *ldv, int *iparam, int *ipntr, Scalar *workd,\n      Scalar *workl, int *lworkl, int *ierr)\n  {\n    EIGEN_STATIC_ASSERT(!NumTraits<Scalar>::IsComplex, NUMERIC_TYPE_MUST_BE_REAL)\n  }\n};\n\ntemplate <> struct arpack_wrapper<float, float>\n{\n  static inline void saupd(int *ido, char *bmat, int *n, char *which,\n      int *nev, float *tol, float *resid, int *ncv,\n      float *v, int *ldv, int *iparam, int *ipntr,\n      float *workd, float *workl, int *lworkl, int *info)\n  {\n    ssaupd_(ido, bmat, n, which, nev, tol, resid, ncv, v, ldv, iparam, ipntr, workd, workl, lworkl, info);\n  }\n\n  static inline void seupd(int *rvec, char *All, int *select, float *d,\n      float *z, int *ldz, float *sigma,\n      char *bmat, int *n, char *which, int *nev,\n      float *tol, float *resid, int *ncv, float *v,\n      int *ldv, int *iparam, int *ipntr, float *workd,\n      float *workl, int *lworkl, int *ierr)\n  {\n    sseupd_(rvec, All, select, d, z, ldz, sigma, bmat, n, which, nev, tol, resid, ncv, v, ldv, iparam, ipntr,\n        workd, workl, lworkl, ierr);\n  }\n};\n\ntemplate <> struct arpack_wrapper<double, double>\n{\n  static inline void saupd(int *ido, char *bmat, int *n, char *which,\n      int *nev, double *tol, double *resid, int *ncv,\n      double *v, int *ldv, int *iparam, int *ipntr,\n      double *workd, double *workl, int *lworkl, int *info)\n  {\n    dsaupd_(ido, bmat, n, which, nev, tol, resid, ncv, v, ldv, iparam, ipntr, workd, workl, lworkl, info);\n  }\n\n  static inline void seupd(int *rvec, char *All, int *select, double *d,\n      double *z, int *ldz, double *sigma,\n      char *bmat, int *n, char *which, int *nev,\n      double *tol, double *resid, int *ncv, double *v,\n      int *ldv, int *iparam, int *ipntr, double *workd,\n      double *workl, int *lworkl, int *ierr)\n  {\n    dseupd_(rvec, All, select, d, v, ldv, sigma, bmat, n, which, nev, tol, resid, ncv, v, ldv, iparam, ipntr,\n        workd, workl, lworkl, ierr);\n  }\n};\n\n\ntemplate<typename MatrixSolver, typename MatrixType, typename Scalar, bool BisSPD>\nstruct OP\n{\n    static inline void applyOP(MatrixSolver &OP, const MatrixType &A, int n, Scalar *in, Scalar *out);\n    static inline void project(MatrixSolver &OP, int n, int k, Scalar *vecs);\n};\n\ntemplate<typename MatrixSolver, typename MatrixType, typename Scalar>\nstruct OP<MatrixSolver, MatrixType, Scalar, true>\n{\n  static inline void applyOP(MatrixSolver &OP, const MatrixType &A, int n, Scalar *in, Scalar *out)\n{\n    // OP = L^{-1} A L^{-T}  (B = LL^T)\n    //\n    // First solve L^T out = in\n    //\n    Matrix<Scalar, Dynamic, 1>::Map(out, n) = OP.matrixU().solve(Matrix<Scalar, Dynamic, 1>::Map(in, n));\n    Matrix<Scalar, Dynamic, 1>::Map(out, n) = OP.permutationPinv() * Matrix<Scalar, Dynamic, 1>::Map(out, n);\n\n    // Then compute out = A out\n    //\n    Matrix<Scalar, Dynamic, 1>::Map(out, n) = A * Matrix<Scalar, Dynamic, 1>::Map(out, n);\n\n    // Then solve L out = out\n    //\n    Matrix<Scalar, Dynamic, 1>::Map(out, n) = OP.permutationP() * Matrix<Scalar, Dynamic, 1>::Map(out, n);\n    Matrix<Scalar, Dynamic, 1>::Map(out, n) = OP.matrixL().solve(Matrix<Scalar, Dynamic, 1>::Map(out, n));\n}\n\n  static inline void project(MatrixSolver &OP, int n, int k, Scalar *vecs)\n{\n    // Solve L^T out = in\n    //\n    Matrix<Scalar, Dynamic, Dynamic>::Map(vecs, n, k) = OP.matrixU().solve(Matrix<Scalar, Dynamic, Dynamic>::Map(vecs, n, k));\n    Matrix<Scalar, Dynamic, Dynamic>::Map(vecs, n, k) = OP.permutationPinv() * Matrix<Scalar, Dynamic, Dynamic>::Map(vecs, n, k);\n}\n\n};\n\ntemplate<typename MatrixSolver, typename MatrixType, typename Scalar>\nstruct OP<MatrixSolver, MatrixType, Scalar, false>\n{\n  static inline void applyOP(MatrixSolver &OP, const MatrixType &A, int n, Scalar *in, Scalar *out)\n{\n    eigen_assert(false && \"Should never be in here...\");\n}\n\n  static inline void project(MatrixSolver &OP, int n, int k, Scalar *vecs)\n{\n    eigen_assert(false && \"Should never be in here...\");\n}\n\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_ARPACKSELFADJOINTEIGENSOLVER_H\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/EulerAngles/CMakeLists.txt",
    "content": "file(GLOB Eigen_EulerAngles_SRCS \"*.h\")\n\ninstall(FILES\n  ${Eigen_EulerAngles_SRCS}\n  DESTINATION ${INCLUDE_INSTALL_DIR}/unsupported/Eigen/src/EulerAngles COMPONENT Devel\n  )\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/EulerAngles/EulerAngles.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Tal Hadad <tal_hd@hotmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_EULERANGLESCLASS_H// TODO: Fix previous \"EIGEN_EULERANGLES_H\" definition?\n#define EIGEN_EULERANGLESCLASS_H\n\nnamespace Eigen\n{\n  /** \\class EulerAngles\n    *\n    * \\ingroup EulerAngles_Module\n    *\n    * \\brief Represents a rotation in a 3 dimensional space as three Euler angles.\n    *\n    * Euler rotation is a set of three rotation of three angles over three fixed axes, defined by the EulerSystem given as a template parameter.\n    * \n    * Here is how intrinsic Euler angles works:\n    *  - first, rotate the axes system over the alpha axis in angle alpha\n    *  - then, rotate the axes system over the beta axis(which was rotated in the first stage) in angle beta\n    *  - then, rotate the axes system over the gamma axis(which was rotated in the two stages above) in angle gamma\n    *\n    * \\note This class support only intrinsic Euler angles for simplicity,\n    *  see EulerSystem how to easily overcome this for extrinsic systems.\n    *\n    * ### Rotation representation and conversions ###\n    *\n    * It has been proved(see Wikipedia link below) that every rotation can be represented\n    *  by Euler angles, but there is no single representation (e.g. unlike rotation matrices).\n    * Therefore, you can convert from Eigen rotation and to them\n    *  (including rotation matrices, which is not called \"rotations\" by Eigen design).\n    *\n    * Euler angles usually used for:\n    *  - convenient human representation of rotation, especially in interactive GUI.\n    *  - gimbal systems and robotics\n    *  - efficient encoding(i.e. 3 floats only) of rotation for network protocols.\n    *\n    * However, Euler angles are slow comparing to quaternion or matrices,\n    *  because their unnatural math definition, although it's simple for human.\n    * To overcome this, this class provide easy movement from the math friendly representation\n    *  to the human friendly representation, and vise-versa.\n    *\n    * All the user need to do is a safe simple C++ type conversion,\n    *  and this class take care for the math.\n    * Additionally, some axes related computation is done in compile time.\n    *\n    * #### Euler angles ranges in conversions ####\n    * Rotations representation as EulerAngles are not single (unlike matrices),\n    *  and even have infinite EulerAngles representations.<BR>\n    * For example, add or subtract 2*PI from either angle of EulerAngles\n    *  and you'll get the same rotation.\n    * This is the general reason for infinite representation,\n    *  but it's not the only general reason for not having a single representation.\n    *\n    * When converting rotation to EulerAngles, this class convert it to specific ranges\n    * When converting some rotation to EulerAngles, the rules for ranges are as follow:\n    * - If the rotation we converting from is an EulerAngles\n    *  (even when it represented as RotationBase explicitly), angles ranges are __undefined__.\n    * - otherwise, alpha and gamma angles will be in the range [-PI, PI].<BR>\n    *   As for Beta angle:\n    *    - If the system is Tait-Bryan, the beta angle will be in the range [-PI/2, PI/2].\n    *    - otherwise:\n    *      - If the beta axis is positive, the beta angle will be in the range [0, PI]\n    *      - If the beta axis is negative, the beta angle will be in the range [-PI, 0]\n    *\n    * \\sa EulerAngles(const MatrixBase<Derived>&)\n    * \\sa EulerAngles(const RotationBase<Derived, 3>&)\n    *\n    * ### Convenient user typedefs ###\n    *\n    * Convenient typedefs for EulerAngles exist for float and double scalar,\n    *  in a form of EulerAngles{A}{B}{C}{scalar},\n    *  e.g. \\ref EulerAnglesXYZd, \\ref EulerAnglesZYZf.\n    *\n    * Only for positive axes{+x,+y,+z} Euler systems are have convenient typedef.\n    * If you need negative axes{-x,-y,-z}, it is recommended to create you own typedef with\n    *  a word that represent what you need.\n    *\n    * ### Example ###\n    *\n    * \\include EulerAngles.cpp\n    * Output: \\verbinclude EulerAngles.out\n    *\n    * ### Additional reading ###\n    *\n    * If you're want to get more idea about how Euler system work in Eigen see EulerSystem.\n    *\n    * More information about Euler angles: https://en.wikipedia.org/wiki/Euler_angles\n    *\n    * \\tparam _Scalar the scalar type, i.e. the type of the angles.\n    *\n    * \\tparam _System the EulerSystem to use, which represents the axes of rotation.\n    */\n  template <typename _Scalar, class _System>\n  class EulerAngles : public RotationBase<EulerAngles<_Scalar, _System>, 3>\n  {\n    public:\n      typedef RotationBase<EulerAngles<_Scalar, _System>, 3> Base;\n      \n      /** the scalar type of the angles */\n      typedef _Scalar Scalar;\n      typedef typename NumTraits<Scalar>::Real RealScalar;\n      \n      /** the EulerSystem to use, which represents the axes of rotation. */\n      typedef _System System;\n    \n      typedef Matrix<Scalar,3,3> Matrix3; /*!< the equivalent rotation matrix type */\n      typedef Matrix<Scalar,3,1> Vector3; /*!< the equivalent 3 dimension vector type */\n      typedef Quaternion<Scalar> QuaternionType; /*!< the equivalent quaternion type */\n      typedef AngleAxis<Scalar> AngleAxisType; /*!< the equivalent angle-axis type */\n      \n      /** \\returns the axis vector of the first (alpha) rotation */\n      static Vector3 AlphaAxisVector() {\n        const Vector3& u = Vector3::Unit(System::AlphaAxisAbs - 1);\n        return System::IsAlphaOpposite ? -u : u;\n      }\n      \n      /** \\returns the axis vector of the second (beta) rotation */\n      static Vector3 BetaAxisVector() {\n        const Vector3& u = Vector3::Unit(System::BetaAxisAbs - 1);\n        return System::IsBetaOpposite ? -u : u;\n      }\n      \n      /** \\returns the axis vector of the third (gamma) rotation */\n      static Vector3 GammaAxisVector() {\n        const Vector3& u = Vector3::Unit(System::GammaAxisAbs - 1);\n        return System::IsGammaOpposite ? -u : u;\n      }\n\n    private:\n      Vector3 m_angles;\n\n    public:\n      /** Default constructor without initialization. */\n      EulerAngles() {}\n      /** Constructs and initialize an EulerAngles (\\p alpha, \\p beta, \\p gamma). */\n      EulerAngles(const Scalar& alpha, const Scalar& beta, const Scalar& gamma) :\n        m_angles(alpha, beta, gamma) {}\n      \n      // TODO: Test this constructor\n      /** Constructs and initialize an EulerAngles from the array data {alpha, beta, gamma} */\n      explicit EulerAngles(const Scalar* data) : m_angles(data) {}\n      \n      /** Constructs and initializes an EulerAngles from either:\n        *  - a 3x3 rotation matrix expression(i.e. pure orthogonal matrix with determinant of +1),\n        *  - a 3D vector expression representing Euler angles.\n        *\n        * \\note If \\p other is a 3x3 rotation matrix, the angles range rules will be as follow:<BR>\n        *  Alpha and gamma angles will be in the range [-PI, PI].<BR>\n        *  As for Beta angle:\n        *   - If the system is Tait-Bryan, the beta angle will be in the range [-PI/2, PI/2].\n        *   - otherwise:\n        *     - If the beta axis is positive, the beta angle will be in the range [0, PI]\n        *     - If the beta axis is negative, the beta angle will be in the range [-PI, 0]\n       */\n      template<typename Derived>\n      explicit EulerAngles(const MatrixBase<Derived>& other) { *this = other; }\n      \n      /** Constructs and initialize Euler angles from a rotation \\p rot.\n        *\n        * \\note If \\p rot is an EulerAngles (even when it represented as RotationBase explicitly),\n        *  angles ranges are __undefined__.\n        *  Otherwise, alpha and gamma angles will be in the range [-PI, PI].<BR>\n        *  As for Beta angle:\n        *   - If the system is Tait-Bryan, the beta angle will be in the range [-PI/2, PI/2].\n        *   - otherwise:\n        *     - If the beta axis is positive, the beta angle will be in the range [0, PI]\n        *     - If the beta axis is negative, the beta angle will be in the range [-PI, 0]\n      */\n      template<typename Derived>\n      EulerAngles(const RotationBase<Derived, 3>& rot) { System::CalcEulerAngles(*this, rot.toRotationMatrix()); }\n      \n      /*EulerAngles(const QuaternionType& q)\n      {\n        // TODO: Implement it in a faster way for quaternions\n        // According to http://www.euclideanspace.com/maths/geometry/rotations/conversions/quaternionToEuler/\n        //  we can compute only the needed matrix cells and then convert to euler angles. (see ZYX example below)\n        // Currently we compute all matrix cells from quaternion.\n\n        // Special case only for ZYX\n        //Scalar y2 = q.y() * q.y();\n        //m_angles[0] = std::atan2(2*(q.w()*q.z() + q.x()*q.y()), (1 - 2*(y2 + q.z()*q.z())));\n        //m_angles[1] = std::asin( 2*(q.w()*q.y() - q.z()*q.x()));\n        //m_angles[2] = std::atan2(2*(q.w()*q.x() + q.y()*q.z()), (1 - 2*(q.x()*q.x() + y2)));\n      }*/\n\n      /** \\returns The angle values stored in a vector (alpha, beta, gamma). */\n      const Vector3& angles() const { return m_angles; }\n      /** \\returns A read-write reference to the angle values stored in a vector (alpha, beta, gamma). */\n      Vector3& angles() { return m_angles; }\n\n      /** \\returns The value of the first angle. */\n      Scalar alpha() const { return m_angles[0]; }\n      /** \\returns A read-write reference to the angle of the first angle. */\n      Scalar& alpha() { return m_angles[0]; }\n\n      /** \\returns The value of the second angle. */\n      Scalar beta() const { return m_angles[1]; }\n      /** \\returns A read-write reference to the angle of the second angle. */\n      Scalar& beta() { return m_angles[1]; }\n\n      /** \\returns The value of the third angle. */\n      Scalar gamma() const { return m_angles[2]; }\n      /** \\returns A read-write reference to the angle of the third angle. */\n      Scalar& gamma() { return m_angles[2]; }\n\n      /** \\returns The Euler angles rotation inverse (which is as same as the negative),\n        *  (-alpha, -beta, -gamma).\n      */\n      EulerAngles inverse() const\n      {\n        EulerAngles res;\n        res.m_angles = -m_angles;\n        return res;\n      }\n\n      /** \\returns The Euler angles rotation negative (which is as same as the inverse),\n        *  (-alpha, -beta, -gamma).\n      */\n      EulerAngles operator -() const\n      {\n        return inverse();\n      }\n      \n      /** Set \\c *this from either:\n        *  - a 3x3 rotation matrix expression(i.e. pure orthogonal matrix with determinant of +1),\n        *  - a 3D vector expression representing Euler angles.\n        *\n        * See EulerAngles(const MatrixBase<Derived, 3>&) for more information about\n        *  angles ranges output.\n      */\n      template<class Derived>\n      EulerAngles& operator=(const MatrixBase<Derived>& other)\n      {\n        EIGEN_STATIC_ASSERT((internal::is_same<Scalar, typename Derived::Scalar>::value),\n         YOU_MIXED_DIFFERENT_NUMERIC_TYPES__YOU_NEED_TO_USE_THE_CAST_METHOD_OF_MATRIXBASE_TO_CAST_NUMERIC_TYPES_EXPLICITLY)\n        \n        internal::eulerangles_assign_impl<System, Derived>::run(*this, other.derived());\n        return *this;\n      }\n\n      // TODO: Assign and construct from another EulerAngles (with different system)\n      \n      /** Set \\c *this from a rotation.\n        *\n        * See EulerAngles(const RotationBase<Derived, 3>&) for more information about\n        *  angles ranges output.\n      */\n      template<typename Derived>\n      EulerAngles& operator=(const RotationBase<Derived, 3>& rot) {\n        System::CalcEulerAngles(*this, rot.toRotationMatrix());\n        return *this;\n      }\n      \n      /** \\returns \\c true if \\c *this is approximately equal to \\a other, within the precision\n        * determined by \\a prec.\n        *\n        * \\sa MatrixBase::isApprox() */\n      bool isApprox(const EulerAngles& other,\n        const RealScalar& prec = NumTraits<Scalar>::dummy_precision()) const\n      { return angles().isApprox(other.angles(), prec); }\n\n      /** \\returns an equivalent 3x3 rotation matrix. */\n      Matrix3 toRotationMatrix() const\n      {\n        // TODO: Calc it faster\n        return static_cast<QuaternionType>(*this).toRotationMatrix();\n      }\n\n      /** Convert the Euler angles to quaternion. */\n      operator QuaternionType() const\n      {\n        return\n          AngleAxisType(alpha(), AlphaAxisVector()) *\n          AngleAxisType(beta(), BetaAxisVector())   *\n          AngleAxisType(gamma(), GammaAxisVector());\n      }\n      \n      friend std::ostream& operator<<(std::ostream& s, const EulerAngles<Scalar, System>& eulerAngles)\n      {\n        s << eulerAngles.angles().transpose();\n        return s;\n      }\n      \n      /** \\returns \\c *this with scalar type casted to \\a NewScalarType */\n      template <typename NewScalarType>\n      EulerAngles<NewScalarType, System> cast() const\n      {\n        EulerAngles<NewScalarType, System> e;\n        e.angles() = angles().template cast<NewScalarType>();\n        return e;\n      }\n  };\n\n#define EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(AXES, SCALAR_TYPE, SCALAR_POSTFIX) \\\n  /** \\ingroup EulerAngles_Module */ \\\n  typedef EulerAngles<SCALAR_TYPE, EulerSystem##AXES> EulerAngles##AXES##SCALAR_POSTFIX;\n\n#define EIGEN_EULER_ANGLES_TYPEDEFS(SCALAR_TYPE, SCALAR_POSTFIX) \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(XYZ, SCALAR_TYPE, SCALAR_POSTFIX) \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(XYX, SCALAR_TYPE, SCALAR_POSTFIX) \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(XZY, SCALAR_TYPE, SCALAR_POSTFIX) \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(XZX, SCALAR_TYPE, SCALAR_POSTFIX) \\\n \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(YZX, SCALAR_TYPE, SCALAR_POSTFIX) \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(YZY, SCALAR_TYPE, SCALAR_POSTFIX) \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(YXZ, SCALAR_TYPE, SCALAR_POSTFIX) \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(YXY, SCALAR_TYPE, SCALAR_POSTFIX) \\\n \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(ZXY, SCALAR_TYPE, SCALAR_POSTFIX) \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(ZXZ, SCALAR_TYPE, SCALAR_POSTFIX) \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(ZYX, SCALAR_TYPE, SCALAR_POSTFIX) \\\n  EIGEN_EULER_ANGLES_SINGLE_TYPEDEF(ZYZ, SCALAR_TYPE, SCALAR_POSTFIX)\n\nEIGEN_EULER_ANGLES_TYPEDEFS(float, f)\nEIGEN_EULER_ANGLES_TYPEDEFS(double, d)\n\n  namespace internal\n  {\n    template<typename _Scalar, class _System>\n    struct traits<EulerAngles<_Scalar, _System> >\n    {\n      typedef _Scalar Scalar;\n    };\n    \n    // set from a rotation matrix\n    template<class System, class Other>\n    struct eulerangles_assign_impl<System,Other,3,3>\n    {\n      typedef typename Other::Scalar Scalar;\n      static void run(EulerAngles<Scalar, System>& e, const Other& m)\n      {\n        System::CalcEulerAngles(e, m);\n      }\n    };\n    \n    // set from a vector of Euler angles\n    template<class System, class Other>\n    struct eulerangles_assign_impl<System,Other,3,1>\n    {\n      typedef typename Other::Scalar Scalar;\n      static void run(EulerAngles<Scalar, System>& e, const Other& vec)\n      {\n        e.angles() = vec;\n      }\n    };\n  }\n}\n\n#endif // EIGEN_EULERANGLESCLASS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/EulerAngles/EulerSystem.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Tal Hadad <tal_hd@hotmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_EULERSYSTEM_H\n#define EIGEN_EULERSYSTEM_H\n\nnamespace Eigen\n{\n  // Forward declarations\n  template <typename _Scalar, class _System>\n  class EulerAngles;\n  \n  namespace internal\n  {\n    // TODO: Add this trait to the Eigen internal API?\n    template <int Num, bool IsPositive = (Num > 0)>\n    struct Abs\n    {\n      enum { value = Num };\n    };\n  \n    template <int Num>\n    struct Abs<Num, false>\n    {\n      enum { value = -Num };\n    };\n\n    template <int Axis>\n    struct IsValidAxis\n    {\n      enum { value = Axis != 0 && Abs<Axis>::value <= 3 };\n    };\n    \n    template<typename System,\n            typename Other,\n            int OtherRows=Other::RowsAtCompileTime,\n            int OtherCols=Other::ColsAtCompileTime>\n    struct eulerangles_assign_impl;\n  }\n  \n  #define EIGEN_EULER_ANGLES_CLASS_STATIC_ASSERT(COND,MSG) typedef char static_assertion_##MSG[(COND)?1:-1]\n  \n  /** \\brief Representation of a fixed signed rotation axis for EulerSystem.\n    *\n    * \\ingroup EulerAngles_Module\n    *\n    * Values here represent:\n    *  - The axis of the rotation: X, Y or Z.\n    *  - The sign (i.e. direction of the rotation along the axis): positive(+) or negative(-)\n    *\n    * Therefore, this could express all the axes {+X,+Y,+Z,-X,-Y,-Z}\n    *\n    * For positive axis, use +EULER_{axis}, and for negative axis use -EULER_{axis}.\n    */\n  enum EulerAxis\n  {\n    EULER_X = 1, /*!< the X axis */\n    EULER_Y = 2, /*!< the Y axis */\n    EULER_Z = 3  /*!< the Z axis */\n  };\n  \n  /** \\class EulerSystem\n    *\n    * \\ingroup EulerAngles_Module\n    *\n    * \\brief Represents a fixed Euler rotation system.\n    *\n    * This meta-class goal is to represent the Euler system in compilation time, for EulerAngles.\n    *\n    * You can use this class to get two things:\n    *  - Build an Euler system, and then pass it as a template parameter to EulerAngles.\n    *  - Query some compile time data about an Euler system. (e.g. Whether it's Tait-Bryan)\n    *\n    * Euler rotation is a set of three rotation on fixed axes. (see \\ref EulerAngles)\n    * This meta-class store constantly those signed axes. (see \\ref EulerAxis)\n    *\n    * ### Types of Euler systems ###\n    *\n    * All and only valid 3 dimension Euler rotation over standard\n    *  signed axes{+X,+Y,+Z,-X,-Y,-Z} are supported:\n    *  - all axes X, Y, Z in each valid order (see below what order is valid)\n    *  - rotation over the axis is supported both over the positive and negative directions.\n    *  - both Tait-Bryan and proper/classic Euler angles (i.e. the opposite).\n    *\n    * Since EulerSystem support both positive and negative directions,\n    *  you may call this rotation distinction in other names:\n    *  - _right handed_ or _left handed_\n    *  - _counterclockwise_ or _clockwise_\n    *\n    * Notice all axed combination are valid, and would trigger a static assertion.\n    * Same unsigned axes can't be neighbors, e.g. {X,X,Y} is invalid.\n    * This yield two and only two classes:\n    *  - _Tait-Bryan_ - all unsigned axes are distinct, e.g. {X,Y,Z}\n    *  - _proper/classic Euler angles_ - The first and the third unsigned axes is equal,\n    *     and the second is different, e.g. {X,Y,X}\n    *\n    * ### Intrinsic vs extrinsic Euler systems ###\n    *\n    * Only intrinsic Euler systems are supported for simplicity.\n    *  If you want to use extrinsic Euler systems,\n    *   just use the equal intrinsic opposite order for axes and angles.\n    *  I.e axes (A,B,C) becomes (C,B,A), and angles (a,b,c) becomes (c,b,a).\n    *\n    * ### Convenient user typedefs ###\n    *\n    * Convenient typedefs for EulerSystem exist (only for positive axes Euler systems),\n    *  in a form of EulerSystem{A}{B}{C}, e.g. \\ref EulerSystemXYZ.\n    *\n    * ### Additional reading ###\n    *\n    * More information about Euler angles: https://en.wikipedia.org/wiki/Euler_angles\n    *\n    * \\tparam _AlphaAxis the first fixed EulerAxis\n    *\n    * \\tparam _BetaAxis the second fixed EulerAxis\n    *\n    * \\tparam _GammaAxis the third fixed EulerAxis\n    */\n  template <int _AlphaAxis, int _BetaAxis, int _GammaAxis>\n  class EulerSystem\n  {\n    public:\n    // It's defined this way and not as enum, because I think\n    //  that enum is not guerantee to support negative numbers\n    \n    /** The first rotation axis */\n    static const int AlphaAxis = _AlphaAxis;\n    \n    /** The second rotation axis */\n    static const int BetaAxis = _BetaAxis;\n    \n    /** The third rotation axis */\n    static const int GammaAxis = _GammaAxis;\n\n    enum\n    {\n      AlphaAxisAbs = internal::Abs<AlphaAxis>::value, /*!< the first rotation axis unsigned */\n      BetaAxisAbs = internal::Abs<BetaAxis>::value, /*!< the second rotation axis unsigned */\n      GammaAxisAbs = internal::Abs<GammaAxis>::value, /*!< the third rotation axis unsigned */\n      \n      IsAlphaOpposite = (AlphaAxis < 0) ? 1 : 0, /*!< whether alpha axis is negative */\n      IsBetaOpposite = (BetaAxis < 0) ? 1 : 0, /*!< whether beta axis is negative */\n      IsGammaOpposite = (GammaAxis < 0) ? 1 : 0, /*!< whether gamma axis is negative */\n\n      // Parity is even if alpha axis X is followed by beta axis Y, or Y is followed\n      // by Z, or Z is followed by X; otherwise it is odd.\n      IsOdd = ((AlphaAxisAbs)%3 == (BetaAxisAbs - 1)%3) ? 0 : 1, /*!< whether the Euler system is odd */\n      IsEven = IsOdd ? 0 : 1, /*!< whether the Euler system is even */\n\n      IsTaitBryan = ((unsigned)AlphaAxisAbs != (unsigned)GammaAxisAbs) ? 1 : 0 /*!< whether the Euler system is Tait-Bryan */\n    };\n    \n    private:\n    \n    EIGEN_EULER_ANGLES_CLASS_STATIC_ASSERT(internal::IsValidAxis<AlphaAxis>::value,\n      ALPHA_AXIS_IS_INVALID);\n      \n    EIGEN_EULER_ANGLES_CLASS_STATIC_ASSERT(internal::IsValidAxis<BetaAxis>::value,\n      BETA_AXIS_IS_INVALID);\n      \n    EIGEN_EULER_ANGLES_CLASS_STATIC_ASSERT(internal::IsValidAxis<GammaAxis>::value,\n      GAMMA_AXIS_IS_INVALID);\n      \n    EIGEN_EULER_ANGLES_CLASS_STATIC_ASSERT((unsigned)AlphaAxisAbs != (unsigned)BetaAxisAbs,\n      ALPHA_AXIS_CANT_BE_EQUAL_TO_BETA_AXIS);\n      \n    EIGEN_EULER_ANGLES_CLASS_STATIC_ASSERT((unsigned)BetaAxisAbs != (unsigned)GammaAxisAbs,\n      BETA_AXIS_CANT_BE_EQUAL_TO_GAMMA_AXIS);\n\n    static const int\n      // I, J, K are the pivot indexes permutation for the rotation matrix, that match this Euler system. \n      // They are used in this class converters.\n      // They are always different from each other, and their possible values are: 0, 1, or 2.\n      I_ = AlphaAxisAbs - 1,\n      J_ = (AlphaAxisAbs - 1 + 1 + IsOdd)%3,\n      K_ = (AlphaAxisAbs - 1 + 2 - IsOdd)%3\n    ;\n    \n    // TODO: Get @mat parameter in form that avoids double evaluation.\n    template <typename Derived>\n    static void CalcEulerAngles_imp(Matrix<typename MatrixBase<Derived>::Scalar, 3, 1>& res, const MatrixBase<Derived>& mat, internal::true_type /*isTaitBryan*/)\n    {\n      using std::atan2;\n      using std::sqrt;\n      \n      typedef typename Derived::Scalar Scalar;\n\n      const Scalar plusMinus = IsEven? 1 : -1;\n      const Scalar minusPlus = IsOdd?  1 : -1;\n\n      const Scalar Rsum = sqrt((mat(I_,I_) * mat(I_,I_) + mat(I_,J_) * mat(I_,J_) + mat(J_,K_) * mat(J_,K_) + mat(K_,K_) * mat(K_,K_))/2);\n      res[1] = atan2(plusMinus * mat(I_,K_), Rsum);\n\n      // There is a singularity when cos(beta) == 0\n      if(Rsum > 4 * NumTraits<Scalar>::epsilon()) {// cos(beta) != 0\n        res[0] = atan2(minusPlus * mat(J_, K_), mat(K_, K_));\n        res[2] = atan2(minusPlus * mat(I_, J_), mat(I_, I_));\n      }\n      else if(plusMinus * mat(I_, K_) > 0) {// cos(beta) == 0 and sin(beta) == 1\n        Scalar spos = mat(J_, I_) + plusMinus * mat(K_, J_); // 2*sin(alpha + plusMinus * gamma\n        Scalar cpos = mat(J_, J_) + minusPlus * mat(K_, I_); // 2*cos(alpha + plusMinus * gamma)\n        Scalar alphaPlusMinusGamma = atan2(spos, cpos);\n        res[0] = alphaPlusMinusGamma;\n        res[2] = 0;\n      }\n      else {// cos(beta) == 0 and sin(beta) == -1\n        Scalar sneg = plusMinus * (mat(K_, J_) + minusPlus * mat(J_, I_)); // 2*sin(alpha + minusPlus*gamma)\n        Scalar cneg = mat(J_, J_) + plusMinus * mat(K_, I_);               // 2*cos(alpha + minusPlus*gamma)\n        Scalar alphaMinusPlusBeta = atan2(sneg, cneg);\n        res[0] = alphaMinusPlusBeta;\n        res[2] = 0;\n      }\n    }\n\n    template <typename Derived>\n    static void CalcEulerAngles_imp(Matrix<typename MatrixBase<Derived>::Scalar,3,1>& res,\n                                    const MatrixBase<Derived>& mat, internal::false_type /*isTaitBryan*/)\n    {\n      using std::atan2;\n      using std::sqrt;\n\n      typedef typename Derived::Scalar Scalar;\n\n      const Scalar plusMinus = IsEven? 1 : -1;\n      const Scalar minusPlus = IsOdd?  1 : -1;\n\n      const Scalar Rsum = sqrt((mat(I_, J_) * mat(I_, J_) + mat(I_, K_) * mat(I_, K_) + mat(J_, I_) * mat(J_, I_) + mat(K_, I_) * mat(K_, I_)) / 2);\n\n      res[1] = atan2(Rsum, mat(I_, I_));\n\n      // There is a singularity when sin(beta) == 0\n      if(Rsum > 4 * NumTraits<Scalar>::epsilon()) {// sin(beta) != 0\n        res[0] = atan2(mat(J_, I_), minusPlus * mat(K_, I_));\n        res[2] = atan2(mat(I_, J_), plusMinus * mat(I_, K_));\n      }\n      else if(mat(I_, I_) > 0) {// sin(beta) == 0 and cos(beta) == 1\n        Scalar spos = plusMinus * mat(K_, J_) + minusPlus * mat(J_, K_); // 2*sin(alpha + gamma)\n        Scalar cpos = mat(J_, J_) + mat(K_, K_);                         // 2*cos(alpha + gamma)\n        res[0] = atan2(spos, cpos);\n        res[2] = 0;\n      }\n      else {// sin(beta) == 0 and cos(beta) == -1\n        Scalar sneg = plusMinus * mat(K_, J_) + plusMinus * mat(J_, K_); // 2*sin(alpha - gamma)\n        Scalar cneg = mat(J_, J_) - mat(K_, K_);                         // 2*cos(alpha - gamma)\n        res[0] = atan2(sneg, cneg);\n        res[2] = 0;\n      }\n    }\n    \n    template<typename Scalar>\n    static void CalcEulerAngles(\n      EulerAngles<Scalar, EulerSystem>& res,\n      const typename EulerAngles<Scalar, EulerSystem>::Matrix3& mat)\n    {\n      CalcEulerAngles_imp(\n        res.angles(), mat,\n        typename internal::conditional<IsTaitBryan, internal::true_type, internal::false_type>::type());\n\n      if (IsAlphaOpposite)\n        res.alpha() = -res.alpha();\n        \n      if (IsBetaOpposite)\n        res.beta() = -res.beta();\n        \n      if (IsGammaOpposite)\n        res.gamma() = -res.gamma();\n    }\n    \n    template <typename _Scalar, class _System>\n    friend class Eigen::EulerAngles;\n    \n    template<typename System,\n            typename Other,\n            int OtherRows,\n            int OtherCols>\n    friend struct internal::eulerangles_assign_impl;\n  };\n\n#define EIGEN_EULER_SYSTEM_TYPEDEF(A, B, C) \\\n  /** \\ingroup EulerAngles_Module */ \\\n  typedef EulerSystem<EULER_##A, EULER_##B, EULER_##C> EulerSystem##A##B##C;\n  \n  EIGEN_EULER_SYSTEM_TYPEDEF(X,Y,Z)\n  EIGEN_EULER_SYSTEM_TYPEDEF(X,Y,X)\n  EIGEN_EULER_SYSTEM_TYPEDEF(X,Z,Y)\n  EIGEN_EULER_SYSTEM_TYPEDEF(X,Z,X)\n  \n  EIGEN_EULER_SYSTEM_TYPEDEF(Y,Z,X)\n  EIGEN_EULER_SYSTEM_TYPEDEF(Y,Z,Y)\n  EIGEN_EULER_SYSTEM_TYPEDEF(Y,X,Z)\n  EIGEN_EULER_SYSTEM_TYPEDEF(Y,X,Y)\n  \n  EIGEN_EULER_SYSTEM_TYPEDEF(Z,X,Y)\n  EIGEN_EULER_SYSTEM_TYPEDEF(Z,X,Z)\n  EIGEN_EULER_SYSTEM_TYPEDEF(Z,Y,X)\n  EIGEN_EULER_SYSTEM_TYPEDEF(Z,Y,Z)\n}\n\n#endif // EIGEN_EULERSYSTEM_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/FFT/ei_fftw_impl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra. \n//\n// Copyright (C) 2009 Mark Borgerding mark a borgerding net\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\nnamespace Eigen { \n\nnamespace internal {\n\n  // FFTW uses non-const arguments\n  // so we must use ugly const_cast calls for all the args it uses\n  //\n  // This should be safe as long as \n  // 1. we use FFTW_ESTIMATE for all our planning\n  //       see the FFTW docs section 4.3.2 \"Planner Flags\"\n  // 2. fftw_complex is compatible with std::complex\n  //    This assumes std::complex<T> layout is array of size 2 with real,imag\n  template <typename T> \n  inline \n  T * fftw_cast(const T* p)\n  { \n      return const_cast<T*>( p); \n  }\n\n  inline \n  fftw_complex * fftw_cast( const std::complex<double> * p)\n  {\n      return const_cast<fftw_complex*>( reinterpret_cast<const fftw_complex*>(p) ); \n  }\n\n  inline \n  fftwf_complex * fftw_cast( const std::complex<float> * p)\n  { \n      return const_cast<fftwf_complex*>( reinterpret_cast<const fftwf_complex*>(p) ); \n  }\n\n  inline \n  fftwl_complex * fftw_cast( const std::complex<long double> * p)\n  { \n      return const_cast<fftwl_complex*>( reinterpret_cast<const fftwl_complex*>(p) ); \n  }\n\n  template <typename T> \n  struct fftw_plan {};\n\n  template <> \n  struct fftw_plan<float>\n  {\n      typedef float scalar_type;\n      typedef fftwf_complex complex_type;\n      fftwf_plan m_plan;\n      fftw_plan() :m_plan(NULL) {}\n      ~fftw_plan() {if (m_plan) fftwf_destroy_plan(m_plan);}\n\n      inline\n      void fwd(complex_type * dst,complex_type * src,int nfft) {\n          if (m_plan==NULL) m_plan = fftwf_plan_dft_1d(nfft,src,dst, FFTW_FORWARD, FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwf_execute_dft( m_plan, src,dst);\n      }\n      inline\n      void inv(complex_type * dst,complex_type * src,int nfft) {\n          if (m_plan==NULL) m_plan = fftwf_plan_dft_1d(nfft,src,dst, FFTW_BACKWARD , FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwf_execute_dft( m_plan, src,dst);\n      }\n      inline\n      void fwd(complex_type * dst,scalar_type * src,int nfft) {\n          if (m_plan==NULL) m_plan = fftwf_plan_dft_r2c_1d(nfft,src,dst,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwf_execute_dft_r2c( m_plan,src,dst);\n      }\n      inline\n      void inv(scalar_type * dst,complex_type * src,int nfft) {\n          if (m_plan==NULL)\n              m_plan = fftwf_plan_dft_c2r_1d(nfft,src,dst,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwf_execute_dft_c2r( m_plan, src,dst);\n      }\n\n      inline \n      void fwd2( complex_type * dst,complex_type * src,int n0,int n1) {\n          if (m_plan==NULL) m_plan = fftwf_plan_dft_2d(n0,n1,src,dst,FFTW_FORWARD,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwf_execute_dft( m_plan, src,dst);\n      }\n      inline \n      void inv2( complex_type * dst,complex_type * src,int n0,int n1) {\n          if (m_plan==NULL) m_plan = fftwf_plan_dft_2d(n0,n1,src,dst,FFTW_BACKWARD,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwf_execute_dft( m_plan, src,dst);\n      }\n\n  };\n  template <> \n  struct fftw_plan<double>\n  {\n      typedef double scalar_type;\n      typedef fftw_complex complex_type;\n      ::fftw_plan m_plan;\n      fftw_plan() :m_plan(NULL) {}\n      ~fftw_plan() {if (m_plan) fftw_destroy_plan(m_plan);}\n\n      inline\n      void fwd(complex_type * dst,complex_type * src,int nfft) {\n          if (m_plan==NULL) m_plan = fftw_plan_dft_1d(nfft,src,dst, FFTW_FORWARD, FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftw_execute_dft( m_plan, src,dst);\n      }\n      inline\n      void inv(complex_type * dst,complex_type * src,int nfft) {\n          if (m_plan==NULL) m_plan = fftw_plan_dft_1d(nfft,src,dst, FFTW_BACKWARD , FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftw_execute_dft( m_plan, src,dst);\n      }\n      inline\n      void fwd(complex_type * dst,scalar_type * src,int nfft) {\n          if (m_plan==NULL) m_plan = fftw_plan_dft_r2c_1d(nfft,src,dst,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftw_execute_dft_r2c( m_plan,src,dst);\n      }\n      inline\n      void inv(scalar_type * dst,complex_type * src,int nfft) {\n          if (m_plan==NULL)\n              m_plan = fftw_plan_dft_c2r_1d(nfft,src,dst,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftw_execute_dft_c2r( m_plan, src,dst);\n      }\n      inline \n      void fwd2( complex_type * dst,complex_type * src,int n0,int n1) {\n          if (m_plan==NULL) m_plan = fftw_plan_dft_2d(n0,n1,src,dst,FFTW_FORWARD,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftw_execute_dft( m_plan, src,dst);\n      }\n      inline \n      void inv2( complex_type * dst,complex_type * src,int n0,int n1) {\n          if (m_plan==NULL) m_plan = fftw_plan_dft_2d(n0,n1,src,dst,FFTW_BACKWARD,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftw_execute_dft( m_plan, src,dst);\n      }\n  };\n  template <> \n  struct fftw_plan<long double>\n  {\n      typedef long double scalar_type;\n      typedef fftwl_complex complex_type;\n      fftwl_plan m_plan;\n      fftw_plan() :m_plan(NULL) {}\n      ~fftw_plan() {if (m_plan) fftwl_destroy_plan(m_plan);}\n\n      inline\n      void fwd(complex_type * dst,complex_type * src,int nfft) {\n          if (m_plan==NULL) m_plan = fftwl_plan_dft_1d(nfft,src,dst, FFTW_FORWARD, FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwl_execute_dft( m_plan, src,dst);\n      }\n      inline\n      void inv(complex_type * dst,complex_type * src,int nfft) {\n          if (m_plan==NULL) m_plan = fftwl_plan_dft_1d(nfft,src,dst, FFTW_BACKWARD , FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwl_execute_dft( m_plan, src,dst);\n      }\n      inline\n      void fwd(complex_type * dst,scalar_type * src,int nfft) {\n          if (m_plan==NULL) m_plan = fftwl_plan_dft_r2c_1d(nfft,src,dst,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwl_execute_dft_r2c( m_plan,src,dst);\n      }\n      inline\n      void inv(scalar_type * dst,complex_type * src,int nfft) {\n          if (m_plan==NULL)\n              m_plan = fftwl_plan_dft_c2r_1d(nfft,src,dst,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwl_execute_dft_c2r( m_plan, src,dst);\n      }\n      inline \n      void fwd2( complex_type * dst,complex_type * src,int n0,int n1) {\n          if (m_plan==NULL) m_plan = fftwl_plan_dft_2d(n0,n1,src,dst,FFTW_FORWARD,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwl_execute_dft( m_plan, src,dst);\n      }\n      inline \n      void inv2( complex_type * dst,complex_type * src,int n0,int n1) {\n          if (m_plan==NULL) m_plan = fftwl_plan_dft_2d(n0,n1,src,dst,FFTW_BACKWARD,FFTW_ESTIMATE|FFTW_PRESERVE_INPUT);\n          fftwl_execute_dft( m_plan, src,dst);\n      }\n  };\n\n  template <typename _Scalar>\n  struct fftw_impl\n  {\n      typedef _Scalar Scalar;\n      typedef std::complex<Scalar> Complex;\n\n      inline\n      void clear() \n      {\n        m_plans.clear();\n      }\n\n      // complex-to-complex forward FFT\n      inline\n      void fwd( Complex * dst,const Complex *src,int nfft)\n      {\n        get_plan(nfft,false,dst,src).fwd(fftw_cast(dst), fftw_cast(src),nfft );\n      }\n\n      // real-to-complex forward FFT\n      inline\n      void fwd( Complex * dst,const Scalar * src,int nfft) \n      {\n          get_plan(nfft,false,dst,src).fwd(fftw_cast(dst), fftw_cast(src) ,nfft);\n      }\n\n      // 2-d complex-to-complex\n      inline\n      void fwd2(Complex * dst, const Complex * src, int n0,int n1)\n      {\n          get_plan(n0,n1,false,dst,src).fwd2(fftw_cast(dst), fftw_cast(src) ,n0,n1);\n      }\n\n      // inverse complex-to-complex\n      inline\n      void inv(Complex * dst,const Complex  *src,int nfft)\n      {\n        get_plan(nfft,true,dst,src).inv(fftw_cast(dst), fftw_cast(src),nfft );\n      }\n\n      // half-complex to scalar\n      inline\n      void inv( Scalar * dst,const Complex * src,int nfft) \n      {\n        get_plan(nfft,true,dst,src).inv(fftw_cast(dst), fftw_cast(src),nfft );\n      }\n\n      // 2-d complex-to-complex\n      inline\n      void inv2(Complex * dst, const Complex * src, int n0,int n1)\n      {\n        get_plan(n0,n1,true,dst,src).inv2(fftw_cast(dst), fftw_cast(src) ,n0,n1);\n      }\n\n\n  protected:\n      typedef fftw_plan<Scalar> PlanData;\n\n      typedef Eigen::numext::int64_t int64_t;\n\n      typedef std::map<int64_t,PlanData> PlanMap;\n\n      PlanMap m_plans;\n\n      inline\n      PlanData & get_plan(int nfft,bool inverse,void * dst,const void * src)\n      {\n          bool inplace = (dst==src);\n          bool aligned = ( (reinterpret_cast<size_t>(src)&15) | (reinterpret_cast<size_t>(dst)&15) ) == 0;\n          int64_t key = ( (nfft<<3 ) | (inverse<<2) | (inplace<<1) | aligned ) << 1;\n          return m_plans[key];\n      }\n\n      inline\n      PlanData & get_plan(int n0,int n1,bool inverse,void * dst,const void * src)\n      {\n          bool inplace = (dst==src);\n          bool aligned = ( (reinterpret_cast<size_t>(src)&15) | (reinterpret_cast<size_t>(dst)&15) ) == 0;\n          int64_t key = ( ( (((int64_t)n0) << 30)|(n1<<3 ) | (inverse<<2) | (inplace<<1) | aligned ) << 1 ) + 1;\n          return m_plans[key];\n      }\n  };\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/FFT/ei_kissfft_impl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Mark Borgerding mark a borgerding net\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\nnamespace Eigen { \n\nnamespace internal {\n\n  // This FFT implementation was derived from kissfft http:sourceforge.net/projects/kissfft\n  // Copyright 2003-2009 Mark Borgerding\n\ntemplate <typename _Scalar>\nstruct kiss_cpx_fft\n{\n  typedef _Scalar Scalar;\n  typedef std::complex<Scalar> Complex;\n  std::vector<Complex> m_twiddles;\n  std::vector<int> m_stageRadix;\n  std::vector<int> m_stageRemainder;\n  std::vector<Complex> m_scratchBuf;\n  bool m_inverse;\n\n  inline void make_twiddles(int nfft, bool inverse)\n  {\n    using numext::sin;\n    using numext::cos;\n    m_inverse = inverse;\n    m_twiddles.resize(nfft);\n    double phinc =  0.25 * double(EIGEN_PI) / nfft;\n    Scalar flip = inverse ? Scalar(1) : Scalar(-1);\n    m_twiddles[0] = Complex(Scalar(1), Scalar(0));\n    if ((nfft&1)==0)\n      m_twiddles[nfft/2] = Complex(Scalar(-1), Scalar(0));\n    int i=1;\n    for (;i*8<nfft;++i)\n    {\n      Scalar c = Scalar(cos(i*8*phinc));\n      Scalar s = Scalar(sin(i*8*phinc));\n      m_twiddles[i] = Complex(c, s*flip);\n      m_twiddles[nfft-i] = Complex(c, -s*flip);\n    }\n    for (;i*4<nfft;++i)\n    {\n      Scalar c = Scalar(cos((2*nfft-8*i)*phinc));\n      Scalar s = Scalar(sin((2*nfft-8*i)*phinc));\n      m_twiddles[i] = Complex(s, c*flip);\n      m_twiddles[nfft-i] = Complex(s, -c*flip);\n    }\n    for (;i*8<3*nfft;++i)\n    {\n      Scalar c = Scalar(cos((8*i-2*nfft)*phinc));\n      Scalar s = Scalar(sin((8*i-2*nfft)*phinc));\n      m_twiddles[i] = Complex(-s, c*flip);\n      m_twiddles[nfft-i] = Complex(-s, -c*flip);\n    }\n    for (;i*2<nfft;++i)\n    {\n      Scalar c = Scalar(cos((4*nfft-8*i)*phinc));\n      Scalar s = Scalar(sin((4*nfft-8*i)*phinc));\n      m_twiddles[i] = Complex(-c, s*flip);\n      m_twiddles[nfft-i] = Complex(-c, -s*flip);\n    }\n  }\n\n  void factorize(int nfft)\n  {\n    //start factoring out 4's, then 2's, then 3,5,7,9,...\n    int n= nfft;\n    int p=4;\n    do {\n      while (n % p) {\n        switch (p) {\n          case 4: p = 2; break;\n          case 2: p = 3; break;\n          default: p += 2; break;\n        }\n        if (p*p>n)\n          p=n;// impossible to have a factor > sqrt(n)\n      }\n      n /= p;\n      m_stageRadix.push_back(p);\n      m_stageRemainder.push_back(n);\n      if ( p > 5 )\n        m_scratchBuf.resize(p); // scratchbuf will be needed in bfly_generic\n    }while(n>1);\n  }\n\n  template <typename _Src>\n    inline\n    void work( int stage,Complex * xout, const _Src * xin, size_t fstride,size_t in_stride)\n    {\n      int p = m_stageRadix[stage];\n      int m = m_stageRemainder[stage];\n      Complex * Fout_beg = xout;\n      Complex * Fout_end = xout + p*m;\n\n      if (m>1) {\n        do{\n          // recursive call:\n          // DFT of size m*p performed by doing\n          // p instances of smaller DFTs of size m, \n          // each one takes a decimated version of the input\n          work(stage+1, xout , xin, fstride*p,in_stride);\n          xin += fstride*in_stride;\n        }while( (xout += m) != Fout_end );\n      }else{\n        do{\n          *xout = *xin;\n          xin += fstride*in_stride;\n        }while(++xout != Fout_end );\n      }\n      xout=Fout_beg;\n\n      // recombine the p smaller DFTs \n      switch (p) {\n        case 2: bfly2(xout,fstride,m); break;\n        case 3: bfly3(xout,fstride,m); break;\n        case 4: bfly4(xout,fstride,m); break;\n        case 5: bfly5(xout,fstride,m); break;\n        default: bfly_generic(xout,fstride,m,p); break;\n      }\n    }\n\n  inline\n    void bfly2( Complex * Fout, const size_t fstride, int m)\n    {\n      for (int k=0;k<m;++k) {\n        Complex t = Fout[m+k] * m_twiddles[k*fstride];\n        Fout[m+k] = Fout[k] - t;\n        Fout[k] += t;\n      }\n    }\n\n  inline\n    void bfly4( Complex * Fout, const size_t fstride, const size_t m)\n    {\n      Complex scratch[6];\n      int negative_if_inverse = m_inverse * -2 +1;\n      for (size_t k=0;k<m;++k) {\n        scratch[0] = Fout[k+m] * m_twiddles[k*fstride];\n        scratch[1] = Fout[k+2*m] * m_twiddles[k*fstride*2];\n        scratch[2] = Fout[k+3*m] * m_twiddles[k*fstride*3];\n        scratch[5] = Fout[k] - scratch[1];\n\n        Fout[k] += scratch[1];\n        scratch[3] = scratch[0] + scratch[2];\n        scratch[4] = scratch[0] - scratch[2];\n        scratch[4] = Complex( scratch[4].imag()*negative_if_inverse , -scratch[4].real()* negative_if_inverse );\n\n        Fout[k+2*m]  = Fout[k] - scratch[3];\n        Fout[k] += scratch[3];\n        Fout[k+m] = scratch[5] + scratch[4];\n        Fout[k+3*m] = scratch[5] - scratch[4];\n      }\n    }\n\n  inline\n    void bfly3( Complex * Fout, const size_t fstride, const size_t m)\n    {\n      size_t k=m;\n      const size_t m2 = 2*m;\n      Complex *tw1,*tw2;\n      Complex scratch[5];\n      Complex epi3;\n      epi3 = m_twiddles[fstride*m];\n\n      tw1=tw2=&m_twiddles[0];\n\n      do{\n        scratch[1]=Fout[m] * *tw1;\n        scratch[2]=Fout[m2] * *tw2;\n\n        scratch[3]=scratch[1]+scratch[2];\n        scratch[0]=scratch[1]-scratch[2];\n        tw1 += fstride;\n        tw2 += fstride*2;\n        Fout[m] = Complex( Fout->real() - Scalar(.5)*scratch[3].real() , Fout->imag() - Scalar(.5)*scratch[3].imag() );\n        scratch[0] *= epi3.imag();\n        *Fout += scratch[3];\n        Fout[m2] = Complex(  Fout[m].real() + scratch[0].imag() , Fout[m].imag() - scratch[0].real() );\n        Fout[m] += Complex( -scratch[0].imag(),scratch[0].real() );\n        ++Fout;\n      }while(--k);\n    }\n\n  inline\n    void bfly5( Complex * Fout, const size_t fstride, const size_t m)\n    {\n      Complex *Fout0,*Fout1,*Fout2,*Fout3,*Fout4;\n      size_t u;\n      Complex scratch[13];\n      Complex * twiddles = &m_twiddles[0];\n      Complex *tw;\n      Complex ya,yb;\n      ya = twiddles[fstride*m];\n      yb = twiddles[fstride*2*m];\n\n      Fout0=Fout;\n      Fout1=Fout0+m;\n      Fout2=Fout0+2*m;\n      Fout3=Fout0+3*m;\n      Fout4=Fout0+4*m;\n\n      tw=twiddles;\n      for ( u=0; u<m; ++u ) {\n        scratch[0] = *Fout0;\n\n        scratch[1]  = *Fout1 * tw[u*fstride];\n        scratch[2]  = *Fout2 * tw[2*u*fstride];\n        scratch[3]  = *Fout3 * tw[3*u*fstride];\n        scratch[4]  = *Fout4 * tw[4*u*fstride];\n\n        scratch[7] = scratch[1] + scratch[4];\n        scratch[10] = scratch[1] - scratch[4];\n        scratch[8] = scratch[2] + scratch[3];\n        scratch[9] = scratch[2] - scratch[3];\n\n        *Fout0 +=  scratch[7];\n        *Fout0 +=  scratch[8];\n\n        scratch[5] = scratch[0] + Complex(\n            (scratch[7].real()*ya.real() ) + (scratch[8].real() *yb.real() ),\n            (scratch[7].imag()*ya.real()) + (scratch[8].imag()*yb.real())\n            );\n\n        scratch[6] = Complex(\n            (scratch[10].imag()*ya.imag()) + (scratch[9].imag()*yb.imag()),\n            -(scratch[10].real()*ya.imag()) - (scratch[9].real()*yb.imag())\n            );\n\n        *Fout1 = scratch[5] - scratch[6];\n        *Fout4 = scratch[5] + scratch[6];\n\n        scratch[11] = scratch[0] +\n          Complex(\n              (scratch[7].real()*yb.real()) + (scratch[8].real()*ya.real()),\n              (scratch[7].imag()*yb.real()) + (scratch[8].imag()*ya.real())\n              );\n\n        scratch[12] = Complex(\n            -(scratch[10].imag()*yb.imag()) + (scratch[9].imag()*ya.imag()),\n            (scratch[10].real()*yb.imag()) - (scratch[9].real()*ya.imag())\n            );\n\n        *Fout2=scratch[11]+scratch[12];\n        *Fout3=scratch[11]-scratch[12];\n\n        ++Fout0;++Fout1;++Fout2;++Fout3;++Fout4;\n      }\n    }\n\n  /* perform the butterfly for one stage of a mixed radix FFT */\n  inline\n    void bfly_generic(\n        Complex * Fout,\n        const size_t fstride,\n        int m,\n        int p\n        )\n    {\n      int u,k,q1,q;\n      Complex * twiddles = &m_twiddles[0];\n      Complex t;\n      int Norig = static_cast<int>(m_twiddles.size());\n      Complex * scratchbuf = &m_scratchBuf[0];\n\n      for ( u=0; u<m; ++u ) {\n        k=u;\n        for ( q1=0 ; q1<p ; ++q1 ) {\n          scratchbuf[q1] = Fout[ k  ];\n          k += m;\n        }\n\n        k=u;\n        for ( q1=0 ; q1<p ; ++q1 ) {\n          int twidx=0;\n          Fout[ k ] = scratchbuf[0];\n          for (q=1;q<p;++q ) {\n            twidx += static_cast<int>(fstride) * k;\n            if (twidx>=Norig) twidx-=Norig;\n            t=scratchbuf[q] * twiddles[twidx];\n            Fout[ k ] += t;\n          }\n          k += m;\n        }\n      }\n    }\n};\n\ntemplate <typename _Scalar>\nstruct kissfft_impl\n{\n  typedef _Scalar Scalar;\n  typedef std::complex<Scalar> Complex;\n\n  void clear() \n  {\n    m_plans.clear();\n    m_realTwiddles.clear();\n  }\n\n  inline\n    void fwd( Complex * dst,const Complex *src,int nfft)\n    {\n      get_plan(nfft,false).work(0, dst, src, 1,1);\n    }\n\n  inline\n    void fwd2( Complex * dst,const Complex *src,int n0,int n1)\n    {\n        EIGEN_UNUSED_VARIABLE(dst);\n        EIGEN_UNUSED_VARIABLE(src);\n        EIGEN_UNUSED_VARIABLE(n0);\n        EIGEN_UNUSED_VARIABLE(n1);\n    }\n\n  inline\n    void inv2( Complex * dst,const Complex *src,int n0,int n1)\n    {\n        EIGEN_UNUSED_VARIABLE(dst);\n        EIGEN_UNUSED_VARIABLE(src);\n        EIGEN_UNUSED_VARIABLE(n0);\n        EIGEN_UNUSED_VARIABLE(n1);\n    }\n\n  // real-to-complex forward FFT\n  // perform two FFTs of src even and src odd\n  // then twiddle to recombine them into the half-spectrum format\n  // then fill in the conjugate symmetric half\n  inline\n    void fwd( Complex * dst,const Scalar * src,int nfft) \n    {\n      if ( nfft&3  ) {\n        // use generic mode for odd\n        m_tmpBuf1.resize(nfft);\n        get_plan(nfft,false).work(0, &m_tmpBuf1[0], src, 1,1);\n        std::copy(m_tmpBuf1.begin(),m_tmpBuf1.begin()+(nfft>>1)+1,dst );\n      }else{\n        int ncfft = nfft>>1;\n        int ncfft2 = nfft>>2;\n        Complex * rtw = real_twiddles(ncfft2);\n\n        // use optimized mode for even real\n        fwd( dst, reinterpret_cast<const Complex*> (src), ncfft);\n        Complex dc(dst[0].real() +  dst[0].imag());\n        Complex nyquist(dst[0].real() -  dst[0].imag());\n        int k;\n        for ( k=1;k <= ncfft2 ; ++k ) {\n          Complex fpk = dst[k];\n          Complex fpnk = conj(dst[ncfft-k]);\n          Complex f1k = fpk + fpnk;\n          Complex f2k = fpk - fpnk;\n          Complex tw= f2k * rtw[k-1];\n          dst[k] =  (f1k + tw) * Scalar(.5);\n          dst[ncfft-k] =  conj(f1k -tw)*Scalar(.5);\n        }\n        dst[0] = dc;\n        dst[ncfft] = nyquist;\n      }\n    }\n\n  // inverse complex-to-complex\n  inline\n    void inv(Complex * dst,const Complex  *src,int nfft)\n    {\n      get_plan(nfft,true).work(0, dst, src, 1,1);\n    }\n\n  // half-complex to scalar\n  inline\n    void inv( Scalar * dst,const Complex * src,int nfft) \n    {\n      if (nfft&3) {\n        m_tmpBuf1.resize(nfft);\n        m_tmpBuf2.resize(nfft);\n        std::copy(src,src+(nfft>>1)+1,m_tmpBuf1.begin() );\n        for (int k=1;k<(nfft>>1)+1;++k)\n          m_tmpBuf1[nfft-k] = conj(m_tmpBuf1[k]);\n        inv(&m_tmpBuf2[0],&m_tmpBuf1[0],nfft);\n        for (int k=0;k<nfft;++k)\n          dst[k] = m_tmpBuf2[k].real();\n      }else{\n        // optimized version for multiple of 4\n        int ncfft = nfft>>1;\n        int ncfft2 = nfft>>2;\n        Complex * rtw = real_twiddles(ncfft2);\n        m_tmpBuf1.resize(ncfft);\n        m_tmpBuf1[0] = Complex( src[0].real() + src[ncfft].real(), src[0].real() - src[ncfft].real() );\n        for (int k = 1; k <= ncfft / 2; ++k) {\n          Complex fk = src[k];\n          Complex fnkc = conj(src[ncfft-k]);\n          Complex fek = fk + fnkc;\n          Complex tmp = fk - fnkc;\n          Complex fok = tmp * conj(rtw[k-1]);\n          m_tmpBuf1[k] = fek + fok;\n          m_tmpBuf1[ncfft-k] = conj(fek - fok);\n        }\n        get_plan(ncfft,true).work(0, reinterpret_cast<Complex*>(dst), &m_tmpBuf1[0], 1,1);\n      }\n    }\n\n  protected:\n  typedef kiss_cpx_fft<Scalar> PlanData;\n  typedef std::map<int,PlanData> PlanMap;\n\n  PlanMap m_plans;\n  std::map<int, std::vector<Complex> > m_realTwiddles;\n  std::vector<Complex> m_tmpBuf1;\n  std::vector<Complex> m_tmpBuf2;\n\n  inline\n    int PlanKey(int nfft, bool isinverse) const { return (nfft<<1) | int(isinverse); }\n\n  inline\n    PlanData & get_plan(int nfft, bool inverse)\n    {\n      // TODO look for PlanKey(nfft, ! inverse) and conjugate the twiddles\n      PlanData & pd = m_plans[ PlanKey(nfft,inverse) ];\n      if ( pd.m_twiddles.size() == 0 ) {\n        pd.make_twiddles(nfft,inverse);\n        pd.factorize(nfft);\n      }\n      return pd;\n    }\n\n  inline\n    Complex * real_twiddles(int ncfft2)\n    {\n      using std::acos;\n      std::vector<Complex> & twidref = m_realTwiddles[ncfft2];// creates new if not there\n      if ( (int)twidref.size() != ncfft2 ) {\n        twidref.resize(ncfft2);\n        int ncfft= ncfft2<<1;\n        Scalar pi =  acos( Scalar(-1) );\n        for (int k=1;k<=ncfft2;++k) \n          twidref[k-1] = exp( Complex(0,-pi * (Scalar(k) / ncfft + Scalar(.5)) ) );\n      }\n      return &twidref[0];\n    }\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/IterativeSolvers/ConstrainedConjGrad.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n\n/* NOTE The functions of this file have been adapted from the GMM++ library */\n\n//========================================================================\n//\n// Copyright (C) 2002-2007 Yves Renard\n//\n// This file is a part of GETFEM++\n//\n// Getfem++ is free software; you can redistribute it and/or modify\n// it under the terms of the GNU Lesser General Public License as\n// published by the Free Software Foundation; version 2.1 of the License.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU Lesser General Public License for more details.\n// You should have received a copy of the GNU Lesser General Public\n// License along with this program; if not, write to the Free Software\n// Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301,\n// USA.\n//\n//========================================================================\n\n#include \"../../../../Eigen/src/Core/util/NonMPL2.h\"\n\n#ifndef EIGEN_CONSTRAINEDCG_H\n#define EIGEN_CONSTRAINEDCG_H\n\n#include \"../../../../Eigen/Core\"\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * Compute the pseudo inverse of the non-square matrix C such that\n  * \\f$ CINV = (C * C^T)^{-1} * C \\f$ based on a conjugate gradient method.\n  *\n  * This function is internally used by constrained_cg.\n  */\ntemplate <typename CMatrix, typename CINVMatrix>\nvoid pseudo_inverse(const CMatrix &C, CINVMatrix &CINV)\n{\n  // optimisable : copie de la ligne, precalcul de C * trans(C).\n  typedef typename CMatrix::Scalar Scalar;\n  typedef typename CMatrix::Index Index;\n  // FIXME use sparse vectors ?\n  typedef Matrix<Scalar,Dynamic,1> TmpVec;\n\n  Index rows = C.rows(), cols = C.cols();\n\n  TmpVec d(rows), e(rows), l(cols), p(rows), q(rows), r(rows);\n  Scalar rho, rho_1, alpha;\n  d.setZero();\n\n  typedef Triplet<double> T;\n  std::vector<T> tripletList;\n    \n  for (Index i = 0; i < rows; ++i)\n  {\n    d[i] = 1.0;\n    rho = 1.0;\n    e.setZero();\n    r = d;\n    p = d;\n\n    while (rho >= 1e-38)\n    { /* conjugate gradient to compute e             */\n      /* which is the i-th row of inv(C * trans(C))  */\n      l = C.transpose() * p;\n      q = C * l;\n      alpha = rho / p.dot(q);\n      e +=  alpha * p;\n      r += -alpha * q;\n      rho_1 = rho;\n      rho = r.dot(r);\n      p = (rho/rho_1) * p + r;\n    }\n\n    l = C.transpose() * e; // l is the i-th row of CINV\n    // FIXME add a generic \"prune/filter\" expression for both dense and sparse object to sparse\n    for (Index j=0; j<l.size(); ++j)\n      if (l[j]<1e-15)\n\ttripletList.push_back(T(i,j,l(j)));\n\n\t\n    d[i] = 0.0;\n  }\n  CINV.setFromTriplets(tripletList.begin(), tripletList.end());\n}\n\n\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * Constrained conjugate gradient\n  *\n  * Computes the minimum of \\f$ 1/2((Ax).x) - bx \\f$ under the constraint \\f$ Cx \\le f \\f$\n  */\ntemplate<typename TMatrix, typename CMatrix,\n         typename VectorX, typename VectorB, typename VectorF>\nvoid constrained_cg(const TMatrix& A, const CMatrix& C, VectorX& x,\n                       const VectorB& b, const VectorF& f, IterationController &iter)\n{\n  using std::sqrt;\n  typedef typename TMatrix::Scalar Scalar;\n  typedef typename TMatrix::Index Index;\n  typedef Matrix<Scalar,Dynamic,1>  TmpVec;\n\n  Scalar rho = 1.0, rho_1, lambda, gamma;\n  Index xSize = x.size();\n  TmpVec  p(xSize), q(xSize), q2(xSize),\n          r(xSize), old_z(xSize), z(xSize),\n          memox(xSize);\n  std::vector<bool> satured(C.rows());\n  p.setZero();\n  iter.setRhsNorm(sqrt(b.dot(b))); // gael vect_sp(PS, b, b)\n  if (iter.rhsNorm() == 0.0) iter.setRhsNorm(1.0);\n\n  SparseMatrix<Scalar,RowMajor> CINV(C.rows(), C.cols());\n  pseudo_inverse(C, CINV);\n\n  while(true)\n  {\n    // computation of residual\n    old_z = z;\n    memox = x;\n    r = b;\n    r += A * -x;\n    z = r;\n    bool transition = false;\n    for (Index i = 0; i < C.rows(); ++i)\n    {\n      Scalar al = C.row(i).dot(x) - f.coeff(i);\n      if (al >= -1.0E-15)\n      {\n        if (!satured[i])\n        {\n          satured[i] = true;\n          transition = true;\n        }\n        Scalar bb = CINV.row(i).dot(z);\n        if (bb > 0.0)\n          // FIXME: we should allow that: z += -bb * C.row(i);\n          for (typename CMatrix::InnerIterator it(C,i); it; ++it)\n            z.coeffRef(it.index()) -= bb*it.value();\n      }\n      else\n        satured[i] = false;\n    }\n\n    // descent direction\n    rho_1 = rho;\n    rho = r.dot(z);\n\n    if (iter.finished(rho)) break;\n    if (transition || iter.first()) gamma = 0.0;\n    else gamma = (std::max)(0.0, (rho - old_z.dot(z)) / rho_1);\n    p = z + gamma*p;\n\n    ++iter;\n    // one dimensionnal optimization\n    q = A * p;\n    lambda = rho / q.dot(p);\n    for (Index i = 0; i < C.rows(); ++i)\n    {\n      if (!satured[i])\n      {\n        Scalar bb = C.row(i).dot(p) - f[i];\n        if (bb > 0.0)\n          lambda = (std::min)(lambda, (f.coeff(i)-C.row(i).dot(x)) / bb);\n      }\n    }\n    x += lambda * p;\n    memox -= x;\n  }\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_CONSTRAINEDCG_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/IterativeSolvers/DGMRES.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Désiré Nuentsa-Wakam <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_DGMRES_H\n#define EIGEN_DGMRES_H\n\n#include \"../../../../Eigen/Eigenvalues\"\n\nnamespace Eigen { \n  \ntemplate< typename _MatrixType,\n          typename _Preconditioner = DiagonalPreconditioner<typename _MatrixType::Scalar> >\nclass DGMRES;\n\nnamespace internal {\n\ntemplate< typename _MatrixType, typename _Preconditioner>\nstruct traits<DGMRES<_MatrixType,_Preconditioner> >\n{\n  typedef _MatrixType MatrixType;\n  typedef _Preconditioner Preconditioner;\n};\n\n/** \\brief Computes a permutation vector to have a sorted sequence\n  * \\param vec The vector to reorder.\n  * \\param perm gives the sorted sequence on output. Must be initialized with 0..n-1\n  * \\param ncut Put  the ncut smallest elements at the end of the vector\n  * WARNING This is an expensive sort, so should be used only \n  * for small size vectors\n  * TODO Use modified QuickSplit or std::nth_element to get the smallest values \n  */\ntemplate <typename VectorType, typename IndexType>\nvoid sortWithPermutation (VectorType& vec, IndexType& perm, typename IndexType::Scalar& ncut)\n{\n  eigen_assert(vec.size() == perm.size());\n  bool flag; \n  for (Index k  = 0; k < ncut; k++)\n  {\n    flag = false;\n    for (Index j = 0; j < vec.size()-1; j++)\n    {\n      if ( vec(perm(j)) < vec(perm(j+1)) )\n      {\n        std::swap(perm(j),perm(j+1)); \n        flag = true;\n      }\n      if (!flag) break; // The vector is in sorted order\n    }\n  }\n}\n\n}\n/**\n * \\ingroup IterativeLinearSolvers_Module\n * \\brief A Restarted GMRES with deflation.\n * This class implements a modification of the GMRES solver for\n * sparse linear systems. The basis is built with modified \n * Gram-Schmidt. At each restart, a few approximated eigenvectors\n * corresponding to the smallest eigenvalues are used to build a\n * preconditioner for the next cycle. This preconditioner \n * for deflation can be combined with any other preconditioner, \n * the IncompleteLUT for instance. The preconditioner is applied \n * at right of the matrix and the combination is multiplicative.\n * \n * \\tparam _MatrixType the type of the sparse matrix A, can be a dense or a sparse matrix.\n * \\tparam _Preconditioner the type of the preconditioner. Default is DiagonalPreconditioner\n * Typical usage :\n * \\code\n * SparseMatrix<double> A;\n * VectorXd x, b; \n * //Fill A and b ...\n * DGMRES<SparseMatrix<double> > solver;\n * solver.set_restart(30); // Set restarting value\n * solver.setEigenv(1); // Set the number of eigenvalues to deflate\n * solver.compute(A);\n * x = solver.solve(b);\n * \\endcode\n * \n * DGMRES can also be used in a matrix-free context, see the following \\link MatrixfreeSolverExample example \\endlink.\n *\n * References :\n * [1] D. NUENTSA WAKAM and F. PACULL, Memory Efficient Hybrid\n *  Algebraic Solvers for Linear Systems Arising from Compressible\n *  Flows, Computers and Fluids, In Press,\n *  https://doi.org/10.1016/j.compfluid.2012.03.023   \n * [2] K. Burrage and J. Erhel, On the performance of various \n * adaptive preconditioned GMRES strategies, 5(1998), 101-121.\n * [3] J. Erhel, K. Burrage and B. Pohl, Restarted GMRES \n *  preconditioned by deflation,J. Computational and Applied\n *  Mathematics, 69(1996), 303-318. \n\n * \n */\ntemplate< typename _MatrixType, typename _Preconditioner>\nclass DGMRES : public IterativeSolverBase<DGMRES<_MatrixType,_Preconditioner> >\n{\n    typedef IterativeSolverBase<DGMRES> Base;\n    using Base::matrix;\n    using Base::m_error;\n    using Base::m_iterations;\n    using Base::m_info;\n    using Base::m_isInitialized;\n    using Base::m_tolerance; \n  public:\n    using Base::_solve_impl;\n    using Base::_solve_with_guess_impl;\n    typedef _MatrixType MatrixType;\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::StorageIndex StorageIndex;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef _Preconditioner Preconditioner;\n    typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix; \n    typedef Matrix<RealScalar,Dynamic,Dynamic> DenseRealMatrix; \n    typedef Matrix<Scalar,Dynamic,1> DenseVector;\n    typedef Matrix<RealScalar,Dynamic,1> DenseRealVector; \n    typedef Matrix<std::complex<RealScalar>, Dynamic, 1> ComplexVector;\n \n    \n  /** Default constructor. */\n  DGMRES() : Base(),m_restart(30),m_neig(0),m_r(0),m_maxNeig(5),m_isDeflAllocated(false),m_isDeflInitialized(false) {}\n\n  /** Initialize the solver with matrix \\a A for further \\c Ax=b solving.\n    * \n    * This constructor is a shortcut for the default constructor followed\n    * by a call to compute().\n    * \n    * \\warning this class stores a reference to the matrix A as well as some\n    * precomputed values that depend on it. Therefore, if \\a A is changed\n    * this class becomes invalid. Call compute() to update it with the new\n    * matrix A, or modify a copy of A.\n    */\n  template<typename MatrixDerived>\n  explicit DGMRES(const EigenBase<MatrixDerived>& A) : Base(A.derived()), m_restart(30),m_neig(0),m_r(0),m_maxNeig(5),m_isDeflAllocated(false),m_isDeflInitialized(false) {}\n\n  ~DGMRES() {}\n  \n  /** \\internal */\n  template<typename Rhs,typename Dest>\n  void _solve_vector_with_guess_impl(const Rhs& b, Dest& x) const\n  {\n    EIGEN_STATIC_ASSERT(Rhs::ColsAtCompileTime==1 || Dest::ColsAtCompileTime==1, YOU_TRIED_CALLING_A_VECTOR_METHOD_ON_A_MATRIX);\n    \n    m_iterations = Base::maxIterations();\n    m_error = Base::m_tolerance;\n    \n    dgmres(matrix(), b, x, Base::m_preconditioner);\n  }\n\n  /** \n   * Get the restart value\n    */\n  Index restart() { return m_restart; }\n  \n  /** \n   * Set the restart value (default is 30)  \n   */\n  void set_restart(const Index restart) { m_restart=restart; }\n  \n  /** \n   * Set the number of eigenvalues to deflate at each restart \n   */\n  void setEigenv(const Index neig) \n  {\n    m_neig = neig;\n    if (neig+1 > m_maxNeig) m_maxNeig = neig+1; // To allow for complex conjugates\n  }\n  \n  /** \n   * Get the size of the deflation subspace size\n   */ \n  Index deflSize() {return m_r; }\n  \n  /**\n   * Set the maximum size of the deflation subspace\n   */\n  void setMaxEigenv(const Index maxNeig) { m_maxNeig = maxNeig; }\n  \n  protected:\n    // DGMRES algorithm \n    template<typename Rhs, typename Dest>\n    void dgmres(const MatrixType& mat,const Rhs& rhs, Dest& x, const Preconditioner& precond) const;\n    // Perform one cycle of GMRES\n    template<typename Dest>\n    Index dgmresCycle(const MatrixType& mat, const Preconditioner& precond, Dest& x, DenseVector& r0, RealScalar& beta, const RealScalar& normRhs, Index& nbIts) const; \n    // Compute data to use for deflation \n    Index dgmresComputeDeflationData(const MatrixType& mat, const Preconditioner& precond, const Index& it, StorageIndex& neig) const;\n    // Apply deflation to a vector\n    template<typename RhsType, typename DestType>\n    Index dgmresApplyDeflation(const RhsType& In, DestType& Out) const; \n    ComplexVector schurValues(const ComplexSchur<DenseMatrix>& schurofH) const;\n    ComplexVector schurValues(const RealSchur<DenseMatrix>& schurofH) const;\n    // Init data for deflation\n    void dgmresInitDeflation(Index& rows) const; \n    mutable DenseMatrix m_V; // Krylov basis vectors\n    mutable DenseMatrix m_H; // Hessenberg matrix \n    mutable DenseMatrix m_Hes; // Initial hessenberg matrix without Givens rotations applied\n    mutable Index m_restart; // Maximum size of the Krylov subspace\n    mutable DenseMatrix m_U; // Vectors that form the basis of the invariant subspace \n    mutable DenseMatrix m_MU; // matrix operator applied to m_U (for next cycles)\n    mutable DenseMatrix m_T; /* T=U^T*M^{-1}*A*U */\n    mutable PartialPivLU<DenseMatrix> m_luT; // LU factorization of m_T\n    mutable StorageIndex m_neig; //Number of eigenvalues to extract at each restart\n    mutable Index m_r; // Current number of deflated eigenvalues, size of m_U\n    mutable Index m_maxNeig; // Maximum number of eigenvalues to deflate\n    mutable RealScalar m_lambdaN; //Modulus of the largest eigenvalue of A\n    mutable bool m_isDeflAllocated;\n    mutable bool m_isDeflInitialized;\n    \n    //Adaptive strategy \n    mutable RealScalar m_smv; // Smaller multiple of the remaining number of steps allowed\n    mutable bool m_force; // Force the use of deflation at each restart\n    \n}; \n/** \n * \\brief Perform several cycles of restarted GMRES with modified Gram Schmidt, \n * \n * A right preconditioner is used combined with deflation.\n * \n */\ntemplate< typename _MatrixType, typename _Preconditioner>\ntemplate<typename Rhs, typename Dest>\nvoid DGMRES<_MatrixType, _Preconditioner>::dgmres(const MatrixType& mat,const Rhs& rhs, Dest& x,\n              const Preconditioner& precond) const\n{\n  const RealScalar considerAsZero = (std::numeric_limits<RealScalar>::min)();\n\n  RealScalar normRhs = rhs.norm();\n  if(normRhs <= considerAsZero) \n  {\n    x.setZero();\n    m_error = 0;\n    return;\n  }\n\n  //Initialization\n  m_isDeflInitialized = false;\n  Index n = mat.rows(); \n  DenseVector r0(n); \n  Index nbIts = 0; \n  m_H.resize(m_restart+1, m_restart);\n  m_Hes.resize(m_restart, m_restart);\n  m_V.resize(n,m_restart+1);\n  //Initial residual vector and initial norm\n  if(x.squaredNorm()==0) \n    x = precond.solve(rhs);\n  r0 = rhs - mat * x; \n  RealScalar beta = r0.norm(); \n  \n  m_error = beta/normRhs; \n  if(m_error < m_tolerance)\n    m_info = Success; \n  else\n    m_info = NoConvergence;\n  \n  // Iterative process\n  while (nbIts < m_iterations && m_info == NoConvergence)\n  {\n    dgmresCycle(mat, precond, x, r0, beta, normRhs, nbIts); \n    \n    // Compute the new residual vector for the restart \n    if (nbIts < m_iterations && m_info == NoConvergence) {\n      r0 = rhs - mat * x;\n      beta = r0.norm();\n    }\n  }\n} \n\n/**\n * \\brief Perform one restart cycle of DGMRES\n * \\param mat The coefficient matrix\n * \\param precond The preconditioner\n * \\param x the new approximated solution\n * \\param r0 The initial residual vector\n * \\param beta The norm of the residual computed so far\n * \\param normRhs The norm of the right hand side vector\n * \\param nbIts The number of iterations\n */\ntemplate< typename _MatrixType, typename _Preconditioner>\ntemplate<typename Dest>\nIndex DGMRES<_MatrixType, _Preconditioner>::dgmresCycle(const MatrixType& mat, const Preconditioner& precond, Dest& x, DenseVector& r0, RealScalar& beta, const RealScalar& normRhs, Index& nbIts) const\n{\n  //Initialization \n  DenseVector g(m_restart+1); // Right hand side of the least square problem\n  g.setZero();  \n  g(0) = Scalar(beta); \n  m_V.col(0) = r0/beta; \n  m_info = NoConvergence; \n  std::vector<JacobiRotation<Scalar> >gr(m_restart); // Givens rotations\n  Index it = 0; // Number of inner iterations \n  Index n = mat.rows();\n  DenseVector tv1(n), tv2(n);  //Temporary vectors\n  while (m_info == NoConvergence && it < m_restart && nbIts < m_iterations)\n  {    \n    // Apply preconditioner(s) at right\n    if (m_isDeflInitialized )\n    {\n      dgmresApplyDeflation(m_V.col(it), tv1); // Deflation\n      tv2 = precond.solve(tv1); \n    }\n    else\n    {\n      tv2 = precond.solve(m_V.col(it)); // User's selected preconditioner\n    }\n    tv1 = mat * tv2; \n   \n    // Orthogonalize it with the previous basis in the basis using modified Gram-Schmidt\n    Scalar coef; \n    for (Index i = 0; i <= it; ++i)\n    { \n      coef = tv1.dot(m_V.col(i));\n      tv1 = tv1 - coef * m_V.col(i); \n      m_H(i,it) = coef; \n      m_Hes(i,it) = coef; \n    }\n    // Normalize the vector \n    coef = tv1.norm(); \n    m_V.col(it+1) = tv1/coef;\n    m_H(it+1, it) = coef;\n//     m_Hes(it+1,it) = coef; \n    \n    // FIXME Check for happy breakdown \n    \n    // Update Hessenberg matrix with Givens rotations\n    for (Index i = 1; i <= it; ++i) \n    {\n      m_H.col(it).applyOnTheLeft(i-1,i,gr[i-1].adjoint());\n    }\n    // Compute the new plane rotation \n    gr[it].makeGivens(m_H(it, it), m_H(it+1,it)); \n    // Apply the new rotation\n    m_H.col(it).applyOnTheLeft(it,it+1,gr[it].adjoint());\n    g.applyOnTheLeft(it,it+1, gr[it].adjoint()); \n    \n    beta = std::abs(g(it+1));\n    m_error = beta/normRhs; \n    // std::cerr << nbIts << \" Relative Residual Norm \" << m_error << std::endl;\n    it++; nbIts++; \n    \n    if (m_error < m_tolerance)\n    {\n      // The method has converged\n      m_info = Success;\n      break;\n    }\n  }\n  \n  // Compute the new coefficients by solving the least square problem\n//   it++;\n  //FIXME  Check first if the matrix is singular ... zero diagonal\n  DenseVector nrs(m_restart); \n  nrs = m_H.topLeftCorner(it,it).template triangularView<Upper>().solve(g.head(it)); \n  \n  // Form the new solution\n  if (m_isDeflInitialized)\n  {\n    tv1 = m_V.leftCols(it) * nrs; \n    dgmresApplyDeflation(tv1, tv2); \n    x = x + precond.solve(tv2);\n  }\n  else\n    x = x + precond.solve(m_V.leftCols(it) * nrs); \n  \n  // Go for a new cycle and compute data for deflation\n  if(nbIts < m_iterations && m_info == NoConvergence && m_neig > 0 && (m_r+m_neig) < m_maxNeig)\n    dgmresComputeDeflationData(mat, precond, it, m_neig); \n  return 0; \n  \n}\n\n\ntemplate< typename _MatrixType, typename _Preconditioner>\nvoid DGMRES<_MatrixType, _Preconditioner>::dgmresInitDeflation(Index& rows) const\n{\n  m_U.resize(rows, m_maxNeig);\n  m_MU.resize(rows, m_maxNeig); \n  m_T.resize(m_maxNeig, m_maxNeig);\n  m_lambdaN = 0.0; \n  m_isDeflAllocated = true; \n}\n\ntemplate< typename _MatrixType, typename _Preconditioner>\ninline typename DGMRES<_MatrixType, _Preconditioner>::ComplexVector DGMRES<_MatrixType, _Preconditioner>::schurValues(const ComplexSchur<DenseMatrix>& schurofH) const\n{\n  return schurofH.matrixT().diagonal();\n}\n\ntemplate< typename _MatrixType, typename _Preconditioner>\ninline typename DGMRES<_MatrixType, _Preconditioner>::ComplexVector DGMRES<_MatrixType, _Preconditioner>::schurValues(const RealSchur<DenseMatrix>& schurofH) const\n{\n  const DenseMatrix& T = schurofH.matrixT();\n  Index it = T.rows();\n  ComplexVector eig(it);\n  Index j = 0;\n  while (j < it-1)\n  {\n    if (T(j+1,j) ==Scalar(0))\n    {\n      eig(j) = std::complex<RealScalar>(T(j,j),RealScalar(0)); \n      j++; \n    }\n    else\n    {\n      eig(j) = std::complex<RealScalar>(T(j,j),T(j+1,j)); \n      eig(j+1) = std::complex<RealScalar>(T(j,j+1),T(j+1,j+1));\n      j++;\n    }\n  }\n  if (j < it-1) eig(j) = std::complex<RealScalar>(T(j,j),RealScalar(0));\n  return eig;\n}\n\ntemplate< typename _MatrixType, typename _Preconditioner>\nIndex DGMRES<_MatrixType, _Preconditioner>::dgmresComputeDeflationData(const MatrixType& mat, const Preconditioner& precond, const Index& it, StorageIndex& neig) const\n{\n  // First, find the Schur form of the Hessenberg matrix H\n  typename internal::conditional<NumTraits<Scalar>::IsComplex, ComplexSchur<DenseMatrix>, RealSchur<DenseMatrix> >::type schurofH; \n  bool computeU = true;\n  DenseMatrix matrixQ(it,it); \n  matrixQ.setIdentity();\n  schurofH.computeFromHessenberg(m_Hes.topLeftCorner(it,it), matrixQ, computeU); \n  \n  ComplexVector eig(it);\n  Matrix<StorageIndex,Dynamic,1>perm(it);\n  eig = this->schurValues(schurofH);\n  \n  // Reorder the absolute values of Schur values\n  DenseRealVector modulEig(it); \n  for (Index j=0; j<it; ++j) modulEig(j) = std::abs(eig(j)); \n  perm.setLinSpaced(it,0,internal::convert_index<StorageIndex>(it-1));\n  internal::sortWithPermutation(modulEig, perm, neig);\n  \n  if (!m_lambdaN)\n  {\n    m_lambdaN = (std::max)(modulEig.maxCoeff(), m_lambdaN);\n  }\n  //Count the real number of extracted eigenvalues (with complex conjugates)\n  Index nbrEig = 0; \n  while (nbrEig < neig)\n  {\n    if(eig(perm(it-nbrEig-1)).imag() == RealScalar(0)) nbrEig++; \n    else nbrEig += 2; \n  }\n  // Extract the  Schur vectors corresponding to the smallest Ritz values\n  DenseMatrix Sr(it, nbrEig); \n  Sr.setZero();\n  for (Index j = 0; j < nbrEig; j++)\n  {\n    Sr.col(j) = schurofH.matrixU().col(perm(it-j-1));\n  }\n  \n  // Form the Schur vectors of the initial matrix using the Krylov basis\n  DenseMatrix X; \n  X = m_V.leftCols(it) * Sr;\n  if (m_r)\n  {\n   // Orthogonalize X against m_U using modified Gram-Schmidt\n   for (Index j = 0; j < nbrEig; j++)\n     for (Index k =0; k < m_r; k++)\n      X.col(j) = X.col(j) - (m_U.col(k).dot(X.col(j)))*m_U.col(k); \n  }\n  \n  // Compute m_MX = A * M^-1 * X\n  Index m = m_V.rows();\n  if (!m_isDeflAllocated) \n    dgmresInitDeflation(m); \n  DenseMatrix MX(m, nbrEig);\n  DenseVector tv1(m);\n  for (Index j = 0; j < nbrEig; j++)\n  {\n    tv1 = mat * X.col(j);\n    MX.col(j) = precond.solve(tv1);\n  }\n  \n  //Update m_T = [U'MU U'MX; X'MU X'MX]\n  m_T.block(m_r, m_r, nbrEig, nbrEig) = X.transpose() * MX; \n  if(m_r)\n  {\n    m_T.block(0, m_r, m_r, nbrEig) = m_U.leftCols(m_r).transpose() * MX; \n    m_T.block(m_r, 0, nbrEig, m_r) = X.transpose() * m_MU.leftCols(m_r);\n  }\n  \n  // Save X into m_U and m_MX in m_MU\n  for (Index j = 0; j < nbrEig; j++) m_U.col(m_r+j) = X.col(j);\n  for (Index j = 0; j < nbrEig; j++) m_MU.col(m_r+j) = MX.col(j);\n  // Increase the size of the invariant subspace\n  m_r += nbrEig; \n  \n  // Factorize m_T into m_luT\n  m_luT.compute(m_T.topLeftCorner(m_r, m_r));\n  \n  //FIXME CHeck if the factorization was correctly done (nonsingular matrix)\n  m_isDeflInitialized = true;\n  return 0; \n}\ntemplate<typename _MatrixType, typename _Preconditioner>\ntemplate<typename RhsType, typename DestType>\nIndex DGMRES<_MatrixType, _Preconditioner>::dgmresApplyDeflation(const RhsType &x, DestType &y) const\n{\n  DenseVector x1 = m_U.leftCols(m_r).transpose() * x; \n  y = x + m_U.leftCols(m_r) * ( m_lambdaN * m_luT.solve(x1) - x1);\n  return 0; \n}\n\n} // end namespace Eigen\n#endif \n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/IterativeSolvers/GMRES.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2012, 2014 Kolja Brix <brix@igpm.rwth-aaachen.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_GMRES_H\n#define EIGEN_GMRES_H\n\nnamespace Eigen {\n\nnamespace internal {\n\n/**\n* Generalized Minimal Residual Algorithm based on the\n* Arnoldi algorithm implemented with Householder reflections.\n*\n* Parameters:\n*  \\param mat       matrix of linear system of equations\n*  \\param rhs       right hand side vector of linear system of equations\n*  \\param x         on input: initial guess, on output: solution\n*  \\param precond   preconditioner used\n*  \\param iters     on input: maximum number of iterations to perform\n*                   on output: number of iterations performed\n*  \\param restart   number of iterations for a restart\n*  \\param tol_error on input: relative residual tolerance\n*                   on output: residuum achieved\n*\n* \\sa IterativeMethods::bicgstab()\n*\n*\n* For references, please see:\n*\n* Saad, Y. and Schultz, M. H.\n* GMRES: A Generalized Minimal Residual Algorithm for Solving Nonsymmetric Linear Systems.\n* SIAM J.Sci.Stat.Comp. 7, 1986, pp. 856 - 869.\n*\n* Saad, Y.\n* Iterative Methods for Sparse Linear Systems.\n* Society for Industrial and Applied Mathematics, Philadelphia, 2003.\n*\n* Walker, H. F.\n* Implementations of the GMRES method.\n* Comput.Phys.Comm. 53, 1989, pp. 311 - 320.\n*\n* Walker, H. F.\n* Implementation of the GMRES Method using Householder Transformations.\n* SIAM J.Sci.Stat.Comp. 9, 1988, pp. 152 - 163.\n*\n*/\ntemplate<typename MatrixType, typename Rhs, typename Dest, typename Preconditioner>\nbool gmres(const MatrixType & mat, const Rhs & rhs, Dest & x, const Preconditioner & precond,\n    Index &iters, const Index &restart, typename Dest::RealScalar & tol_error) {\n\n  using std::sqrt;\n  using std::abs;\n\n  typedef typename Dest::RealScalar RealScalar;\n  typedef typename Dest::Scalar Scalar;\n  typedef Matrix < Scalar, Dynamic, 1 > VectorType;\n  typedef Matrix < Scalar, Dynamic, Dynamic, ColMajor> FMatrixType;\n\n  const RealScalar considerAsZero = (std::numeric_limits<RealScalar>::min)();\n\n  if(rhs.norm() <= considerAsZero) \n  {\n    x.setZero();\n    tol_error = 0;\n    return true;\n  }\n\n  RealScalar tol = tol_error;\n  const Index maxIters = iters;\n  iters = 0;\n\n  const Index m = mat.rows();\n\n  // residual and preconditioned residual\n  VectorType p0 = rhs - mat*x;\n  VectorType r0 = precond.solve(p0);\n\n  const RealScalar r0Norm = r0.norm();\n\n  // is initial guess already good enough?\n  if(r0Norm == 0)\n  {\n    tol_error = 0;\n    return true;\n  }\n\n  // storage for Hessenberg matrix and Householder data\n  FMatrixType H   = FMatrixType::Zero(m, restart + 1);\n  VectorType w    = VectorType::Zero(restart + 1);\n  VectorType tau  = VectorType::Zero(restart + 1);\n\n  // storage for Jacobi rotations\n  std::vector < JacobiRotation < Scalar > > G(restart);\n  \n  // storage for temporaries\n  VectorType t(m), v(m), workspace(m), x_new(m);\n\n  // generate first Householder vector\n  Ref<VectorType> H0_tail = H.col(0).tail(m - 1);\n  RealScalar beta;\n  r0.makeHouseholder(H0_tail, tau.coeffRef(0), beta);\n  w(0) = Scalar(beta);\n  \n  for (Index k = 1; k <= restart; ++k)\n  {\n    ++iters;\n\n    v = VectorType::Unit(m, k - 1);\n\n    // apply Householder reflections H_{1} ... H_{k-1} to v\n    // TODO: use a HouseholderSequence\n    for (Index i = k - 1; i >= 0; --i) {\n      v.tail(m - i).applyHouseholderOnTheLeft(H.col(i).tail(m - i - 1), tau.coeffRef(i), workspace.data());\n    }\n\n    // apply matrix M to v:  v = mat * v;\n    t.noalias() = mat * v;\n    v = precond.solve(t);\n\n    // apply Householder reflections H_{k-1} ... H_{1} to v\n    // TODO: use a HouseholderSequence\n    for (Index i = 0; i < k; ++i) {\n      v.tail(m - i).applyHouseholderOnTheLeft(H.col(i).tail(m - i - 1), tau.coeffRef(i), workspace.data());\n    }\n\n    if (v.tail(m - k).norm() != 0.0)\n    {\n      if (k <= restart)\n      {\n        // generate new Householder vector\n        Ref<VectorType> Hk_tail = H.col(k).tail(m - k - 1);\n        v.tail(m - k).makeHouseholder(Hk_tail, tau.coeffRef(k), beta);\n\n        // apply Householder reflection H_{k} to v\n        v.tail(m - k).applyHouseholderOnTheLeft(Hk_tail, tau.coeffRef(k), workspace.data());\n      }\n    }\n\n    if (k > 1)\n    {\n      for (Index i = 0; i < k - 1; ++i)\n      {\n        // apply old Givens rotations to v\n        v.applyOnTheLeft(i, i + 1, G[i].adjoint());\n      }\n    }\n\n    if (k<m && v(k) != (Scalar) 0)\n    {\n      // determine next Givens rotation\n      G[k - 1].makeGivens(v(k - 1), v(k));\n\n      // apply Givens rotation to v and w\n      v.applyOnTheLeft(k - 1, k, G[k - 1].adjoint());\n      w.applyOnTheLeft(k - 1, k, G[k - 1].adjoint());\n    }\n\n    // insert coefficients into upper matrix triangle\n    H.col(k-1).head(k) = v.head(k);\n\n    tol_error = abs(w(k)) / r0Norm;\n    bool stop = (k==m || tol_error < tol || iters == maxIters);\n\n    if (stop || k == restart)\n    {\n      // solve upper triangular system\n      Ref<VectorType> y = w.head(k);\n      H.topLeftCorner(k, k).template triangularView <Upper>().solveInPlace(y);\n\n      // use Horner-like scheme to calculate solution vector\n      x_new.setZero();\n      for (Index i = k - 1; i >= 0; --i)\n      {\n        x_new(i) += y(i);\n        // apply Householder reflection H_{i} to x_new\n        x_new.tail(m - i).applyHouseholderOnTheLeft(H.col(i).tail(m - i - 1), tau.coeffRef(i), workspace.data());\n      }\n\n      x += x_new;\n\n      if(stop)\n      {\n        return true;\n      }\n      else\n      {\n        k=0;\n\n        // reset data for restart\n        p0.noalias() = rhs - mat*x;\n        r0 = precond.solve(p0);\n\n        // clear Hessenberg matrix and Householder data\n        H.setZero();\n        w.setZero();\n        tau.setZero();\n\n        // generate first Householder vector\n        r0.makeHouseholder(H0_tail, tau.coeffRef(0), beta);\n        w(0) = Scalar(beta);\n      }\n    }\n  }\n\n  return false;\n\n}\n\n}\n\ntemplate< typename _MatrixType,\n          typename _Preconditioner = DiagonalPreconditioner<typename _MatrixType::Scalar> >\nclass GMRES;\n\nnamespace internal {\n\ntemplate< typename _MatrixType, typename _Preconditioner>\nstruct traits<GMRES<_MatrixType,_Preconditioner> >\n{\n  typedef _MatrixType MatrixType;\n  typedef _Preconditioner Preconditioner;\n};\n\n}\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\brief A GMRES solver for sparse square problems\n  *\n  * This class allows to solve for A.x = b sparse linear problems using a generalized minimal\n  * residual method. The vectors x and b can be either dense or sparse.\n  *\n  * \\tparam _MatrixType the type of the sparse matrix A, can be a dense or a sparse matrix.\n  * \\tparam _Preconditioner the type of the preconditioner. Default is DiagonalPreconditioner\n  *\n  * The maximal number of iterations and tolerance value can be controlled via the setMaxIterations()\n  * and setTolerance() methods. The defaults are the size of the problem for the maximal number of iterations\n  * and NumTraits<Scalar>::epsilon() for the tolerance.\n  *\n  * This class can be used as the direct solver classes. Here is a typical usage example:\n  * \\code\n  * int n = 10000;\n  * VectorXd x(n), b(n);\n  * SparseMatrix<double> A(n,n);\n  * // fill A and b\n  * GMRES<SparseMatrix<double> > solver(A);\n  * x = solver.solve(b);\n  * std::cout << \"#iterations:     \" << solver.iterations() << std::endl;\n  * std::cout << \"estimated error: \" << solver.error()      << std::endl;\n  * // update b, and solve again\n  * x = solver.solve(b);\n  * \\endcode\n  *\n  * By default the iterations start with x=0 as an initial guess of the solution.\n  * One can control the start using the solveWithGuess() method.\n  * \n  * GMRES can also be used in a matrix-free context, see the following \\link MatrixfreeSolverExample example \\endlink.\n  *\n  * \\sa class SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner\n  */\ntemplate< typename _MatrixType, typename _Preconditioner>\nclass GMRES : public IterativeSolverBase<GMRES<_MatrixType,_Preconditioner> >\n{\n  typedef IterativeSolverBase<GMRES> Base;\n  using Base::matrix;\n  using Base::m_error;\n  using Base::m_iterations;\n  using Base::m_info;\n  using Base::m_isInitialized;\n\nprivate:\n  Index m_restart;\n\npublic:\n  using Base::_solve_impl;\n  typedef _MatrixType MatrixType;\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  typedef _Preconditioner Preconditioner;\n\npublic:\n\n  /** Default constructor. */\n  GMRES() : Base(), m_restart(30) {}\n\n  /** Initialize the solver with matrix \\a A for further \\c Ax=b solving.\n    *\n    * This constructor is a shortcut for the default constructor followed\n    * by a call to compute().\n    *\n    * \\warning this class stores a reference to the matrix A as well as some\n    * precomputed values that depend on it. Therefore, if \\a A is changed\n    * this class becomes invalid. Call compute() to update it with the new\n    * matrix A, or modify a copy of A.\n    */\n  template<typename MatrixDerived>\n  explicit GMRES(const EigenBase<MatrixDerived>& A) : Base(A.derived()), m_restart(30) {}\n\n  ~GMRES() {}\n\n  /** Get the number of iterations after that a restart is performed.\n    */\n  Index get_restart() { return m_restart; }\n\n  /** Set the number of iterations after that a restart is performed.\n    *  \\param restart   number of iterations for a restarti, default is 30.\n    */\n  void set_restart(const Index restart) { m_restart=restart; }\n\n  /** \\internal */\n  template<typename Rhs,typename Dest>\n  void _solve_vector_with_guess_impl(const Rhs& b, Dest& x) const\n  {\n    m_iterations = Base::maxIterations();\n    m_error = Base::m_tolerance;\n    bool ret = internal::gmres(matrix(), b, x, Base::m_preconditioner, m_iterations, m_restart, m_error);\n    m_info = (!ret) ? NumericalIssue\n          : m_error <= Base::m_tolerance ? Success\n          : NoConvergence;\n  }\n\nprotected:\n\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_GMRES_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/IterativeSolvers/IDRS.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2020 Chris Schoutrop <c.e.m.schoutrop@tue.nl>\n// Copyright (C) 2020 Jens Wehner <j.wehner@esciencecenter.nl>\n// Copyright (C) 2020 Jan van Dijk <j.v.dijk@tue.nl>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#ifndef EIGEN_IDRS_H\n#define EIGEN_IDRS_H\n\nnamespace Eigen\n{\n\n\tnamespace internal\n\t{\n\t\t/**     \\internal Low-level Induced Dimension Reduction algoritm\n\t\t        \\param A The matrix A\n\t\t        \\param b The right hand side vector b\n\t\t        \\param x On input and initial solution, on output the computed solution.\n\t\t        \\param precond A preconditioner being able to efficiently solve for an\n\t\t                  approximation of Ax=b (regardless of b)\n\t\t        \\param iter On input the max number of iteration, on output the number of performed iterations.\n\t\t        \\param relres On input the tolerance error, on output an estimation of the relative error.\n\t\t        \\param S On input Number of the dimension of the shadow space.\n\t\t\t\t\\param smoothing switches residual smoothing on.\n\t\t\t\t\\param angle small omega lead to faster convergence at the expense of numerical stability\n\t\t\t\t\\param replacement switches on a residual replacement strategy to increase accuracy of residual at the expense of more Mat*vec products\n\t\t        \\return false in the case of numerical issue, for example a break down of IDRS.\n\t\t*/\n\t\ttemplate<typename Vector, typename RealScalar>\n\t\ttypename Vector::Scalar omega(const Vector& t, const Vector& s, RealScalar angle)\n\t\t{\n\t\t\tusing numext::abs;\n\t\t\ttypedef typename Vector::Scalar Scalar;\n\t\t\tconst RealScalar ns = s.norm();\n\t\t\tconst RealScalar nt = t.norm();\n\t\t\tconst Scalar ts = t.dot(s);\n\t\t\tconst RealScalar rho = abs(ts / (nt * ns));\n\n\t\t\tif (rho < angle) {\n\t\t\t\tif (ts == Scalar(0)) {\n\t\t\t\t\treturn Scalar(0);\n\t\t\t\t}\n\t\t\t\t// Original relation for om is given by\n\t\t\t\t// om = om * angle / rho;\n\t\t\t\t// To alleviate potential (near) division by zero this can be rewritten as\n\t\t\t\t// om = angle * (ns / nt) * (ts / abs(ts)) = angle * (ns / nt) * sgn(ts)\n  \t\t\t\treturn angle * (ns / nt) * (ts / abs(ts));\n\t\t\t}\n\t\t\treturn ts / (nt * nt);\n\t\t}\n\n\t\ttemplate <typename MatrixType, typename Rhs, typename Dest, typename Preconditioner>\n\t\tbool idrs(const MatrixType& A, const Rhs& b, Dest& x, const Preconditioner& precond,\n\t\t\tIndex& iter,\n\t\t\ttypename Dest::RealScalar& relres, Index S, bool smoothing, typename Dest::RealScalar angle, bool replacement)\n\t\t{\n\t\t\ttypedef typename Dest::RealScalar RealScalar;\n\t\t\ttypedef typename Dest::Scalar Scalar;\n\t\t\ttypedef Matrix<Scalar, Dynamic, 1> VectorType;\n\t\t\ttypedef Matrix<Scalar, Dynamic, Dynamic, ColMajor> DenseMatrixType;\n\t\t\tconst Index N = b.size();\n\t\t\tS = S < x.rows() ? S : x.rows();\n\t\t\tconst RealScalar tol = relres;\n\t\t\tconst Index maxit = iter;\n\n\t\t\tIndex replacements = 0;\n\t\t\tbool trueres = false;\n\n\t\t\tFullPivLU<DenseMatrixType> lu_solver;\n\n\t\t\tDenseMatrixType P;\n\t\t\t{\n\t\t\t\tHouseholderQR<DenseMatrixType> qr(DenseMatrixType::Random(N, S));\n\t\t\t    P = (qr.householderQ() * DenseMatrixType::Identity(N, S));\n\t\t\t}\n\n\t\t\tconst RealScalar normb = b.norm();\n\n\t\t\tif (internal::isApprox(normb, RealScalar(0)))\n\t\t\t{\n\t\t\t\t//Solution is the zero vector\n\t\t\t\tx.setZero();\n\t\t\t\titer = 0;\n\t\t\t\trelres = 0;\n\t\t\t\treturn true;\n\t\t\t}\n\t\t\t // from http://homepage.tudelft.nl/1w5b5/IDRS/manual.pdf\n\t\t\t // A peak in the residual is considered dangerously high if‖ri‖/‖b‖> C(tol/epsilon).\n\t\t\t // With epsilon the\n             // relative machine precision. The factor tol/epsilon corresponds to the size of a\n             // finite precision number that is so large that the absolute round-off error in\n             // this number, when propagated through the process, makes it impossible to\n             // achieve the required accuracy.The factor C accounts for the accumulation of\n             // round-off errors. This parameter has beenset to 10−3.\n\t\t\t // mp is epsilon/C\n\t\t\t // 10^3 * eps is very conservative, so normally no residual replacements will take place. \n\t\t\t // It only happens if things go very wrong. Too many restarts may ruin the convergence.\n\t\t\tconst RealScalar mp = RealScalar(1e3) * NumTraits<Scalar>::epsilon();\n\n\n\n\t\t\t//Compute initial residual\n\t\t\tconst RealScalar tolb = tol * normb; //Relative tolerance\n\t\t\tVectorType r = b - A * x;\n\n\t\t\tVectorType x_s, r_s;\n\n\t\t\tif (smoothing)\n\t\t\t{\n\t\t\t\tx_s = x;\n\t\t\t\tr_s = r;\n\t\t\t}\n\n\t\t\tRealScalar normr = r.norm();\n\n\t\t\tif (normr <= tolb)\n\t\t\t{\n\t\t\t\t//Initial guess is a good enough solution\n\t\t\t\titer = 0;\n\t\t\t\trelres = normr / normb;\n\t\t\t\treturn true;\n\t\t\t}\n\n\t\t\tDenseMatrixType G = DenseMatrixType::Zero(N, S);\n\t\t\tDenseMatrixType U = DenseMatrixType::Zero(N, S);\n\t\t\tDenseMatrixType M = DenseMatrixType::Identity(S, S);\n\t\t\tVectorType t(N), v(N);\n\t\t\tScalar om = 1.;\n\n\t\t\t//Main iteration loop, guild G-spaces:\n\t\t\titer = 0;\n\n\t\t\twhile (normr > tolb && iter < maxit)\n\t\t\t{\n\t\t\t\t//New right hand size for small system:\n\t\t\t\tVectorType f = (r.adjoint() * P).adjoint();\n\n\t\t\t\tfor (Index k = 0; k < S; ++k)\n\t\t\t\t{\n\t\t\t\t\t//Solve small system and make v orthogonal to P:\n\t\t\t\t\t//c = M(k:s,k:s)\\f(k:s);\n\t\t\t\t\tlu_solver.compute(M.block(k , k , S -k, S - k ));\n\t\t\t\t\tVectorType c = lu_solver.solve(f.segment(k , S - k ));\n\t\t\t\t\t//v = r - G(:,k:s)*c;\n\t\t\t\t\tv = r - G.rightCols(S - k ) * c;\n\t\t\t\t\t//Preconditioning\n\t\t\t\t\tv = precond.solve(v);\n\n\t\t\t\t\t//Compute new U(:,k) and G(:,k), G(:,k) is in space G_j\n\t\t\t\t\tU.col(k) = U.rightCols(S - k ) * c + om * v;\n\t\t\t\t\tG.col(k) = A * U.col(k );\n\n\t\t\t\t\t//Bi-Orthogonalise the new basis vectors:\n\t\t\t\t\tfor (Index i = 0; i < k-1 ; ++i)\n\t\t\t\t\t{\n\t\t\t\t\t\t//alpha =  ( P(:,i)'*G(:,k) )/M(i,i);\n\t\t\t\t\t\tScalar alpha = P.col(i ).dot(G.col(k )) / M(i, i );\n\t\t\t\t\t\tG.col(k ) = G.col(k ) - alpha * G.col(i );\n\t\t\t\t\t\tU.col(k ) = U.col(k ) - alpha * U.col(i );\n\t\t\t\t\t}\n\n\t\t\t\t\t//New column of M = P'*G  (first k-1 entries are zero)\n\t\t\t\t\t//M(k:s,k) = (G(:,k)'*P(:,k:s))';\n\t\t\t\t\tM.block(k , k , S - k , 1) = (G.col(k ).adjoint() * P.rightCols(S - k )).adjoint();\n\n\t\t\t\t\tif (internal::isApprox(M(k,k), Scalar(0)))\n\t\t\t\t\t{\n\t\t\t\t\t\treturn false;\n\t\t\t\t\t}\n\n\t\t\t\t\t//Make r orthogonal to q_i, i = 0..k-1\n\t\t\t\t\tScalar beta = f(k ) / M(k , k );\n\t\t\t\t\tr = r - beta * G.col(k );\n\t\t\t\t\tx = x + beta * U.col(k );\n\t\t\t\t\tnormr = r.norm();\n\n\t\t\t\t\tif (replacement && normr > tolb / mp)\n\t\t\t\t\t{\n\t\t\t\t\t\ttrueres = true;\n\t\t\t\t\t}\n\n\t\t\t\t\t//Smoothing:\n\t\t\t\t\tif (smoothing)\n\t\t\t\t\t{\n\t\t\t\t\t\tt = r_s - r;\n\t\t\t\t\t\t//gamma is a Scalar, but the conversion is not allowed\n\t\t\t\t\t\tScalar gamma = t.dot(r_s) / t.norm();\n\t\t\t\t\t\tr_s = r_s - gamma * t;\n\t\t\t\t\t\tx_s = x_s - gamma * (x_s - x);\n\t\t\t\t\t\tnormr = r_s.norm();\n\t\t\t\t\t}\n\n\t\t\t\t\tif (normr < tolb || iter == maxit)\n\t\t\t\t\t{\n\t\t\t\t\t\tbreak;\n\t\t\t\t\t}\n\n\t\t\t\t\t//New f = P'*r (first k  components are zero)\n\t\t\t\t\tif (k < S-1)\n\t\t\t\t\t{\n\t\t\t\t\t\tf.segment(k + 1, S - (k + 1) ) = f.segment(k + 1 , S - (k + 1)) - beta * M.block(k + 1 , k , S - (k + 1), 1);\n\t\t\t\t\t}\n\t\t\t\t}//end for\n\n\t\t\t\tif (normr < tolb || iter == maxit)\n\t\t\t\t{\n\t\t\t\t\tbreak;\n\t\t\t\t}\n\n\t\t\t\t//Now we have sufficient vectors in G_j to compute residual in G_j+1\n\t\t\t\t//Note: r is already perpendicular to P so v = r\n\t\t\t\t//Preconditioning\n\t\t\t\tv = r;\n\t\t\t\tv = precond.solve(v);\n\n\t\t\t\t//Matrix-vector multiplication:\n\t\t\t\tt = A * v;\n\n\t\t\t\t//Computation of a new omega\n\t\t\t\tom = internal::omega(t, r, angle);\n\n\t\t\t\tif (om == RealScalar(0.0))\n\t\t\t\t{\n\t\t\t\t\treturn false;\n\t\t\t\t}\n\n\t\t\t\tr = r - om * t;\n\t\t\t\tx = x + om * v;\n\t\t\t\tnormr = r.norm();\n\n\t\t\t\tif (replacement && normr > tolb / mp)\n\t\t\t\t{\n\t\t\t\t\ttrueres = true;\n\t\t\t\t}\n\n\t\t\t\t//Residual replacement?\n\t\t\t\tif (trueres && normr < normb)\n\t\t\t\t{\n\t\t\t\t\tr = b - A * x;\n\t\t\t\t\ttrueres = false;\n\t\t\t\t\treplacements++;\n\t\t\t\t}\n\n\t\t\t\t//Smoothing:\n\t\t\t\tif (smoothing)\n\t\t\t\t{\n\t\t\t\t\tt = r_s - r;\n\t\t\t\t\tScalar gamma = t.dot(r_s) /t.norm();\n\t\t\t\t\tr_s = r_s - gamma * t;\n\t\t\t\t\tx_s = x_s - gamma * (x_s - x);\n\t\t\t\t\tnormr = r_s.norm();\n\t\t\t\t}\n\n\t\t\t\titer++;\n\n\t\t\t}//end while\n\n\t\t\tif (smoothing)\n\t\t\t{\n\t\t\t\tx = x_s;\n\t\t\t}\n\t\t\trelres=normr/normb;\n\t\t\treturn true;\n\t\t}\n\n\t}  // namespace internal\n\n\ttemplate <typename _MatrixType, typename _Preconditioner = DiagonalPreconditioner<typename _MatrixType::Scalar> >\n\tclass IDRS;\n\n\tnamespace internal\n\t{\n\n\t\ttemplate <typename _MatrixType, typename _Preconditioner>\n\t\tstruct traits<Eigen::IDRS<_MatrixType, _Preconditioner> >\n\t\t{\n\t\t\ttypedef _MatrixType MatrixType;\n\t\t\ttypedef _Preconditioner Preconditioner;\n\t\t};\n\n\t}  // namespace internal\n\n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\brief The Induced Dimension Reduction method (IDR(s)) is a short-recurrences Krylov method for sparse square problems.\n  *\n  * This class allows to solve for A.x = b sparse linear problems. The vectors x and b can be either dense or sparse.\n  * he Induced Dimension Reduction method, IDR(), is a robust and efficient short-recurrence Krylov subspace method for\n  * solving large nonsymmetric systems of linear equations.\n  *\n  * For indefinite systems IDR(S) outperforms both BiCGStab and BiCGStab(L). Additionally, IDR(S) can handle matrices\n  * with complex eigenvalues more efficiently than BiCGStab.\n  *\n  * Many problems that do not converge for BiCGSTAB converge for IDR(s) (for larger values of s). And if both methods \n  * converge the convergence for IDR(s) is typically much faster for difficult systems (for example indefinite problems). \n  *\n  * IDR(s) is a limited memory finite termination method. In exact arithmetic it converges in at most N+N/s iterations,\n  * with N the system size.  It uses a fixed number of 4+3s vector. In comparison, BiCGSTAB terminates in 2N iterations \n  * and uses 7 vectors. GMRES terminates in at most N iterations, and uses I+3 vectors, with I the number of iterations. \n  * Restarting GMRES limits the memory consumption, but destroys the finite termination property.\n  *\n  * \\tparam _MatrixType the type of the sparse matrix A, can be a dense or a sparse matrix.\n  * \\tparam _Preconditioner the type of the preconditioner. Default is DiagonalPreconditioner\n  *\n  * \\implsparsesolverconcept\n  *\n  * The maximal number of iterations and tolerance value can be controlled via the setMaxIterations()\n  * and setTolerance() methods. The defaults are the size of the problem for the maximal number of iterations\n  * and NumTraits<Scalar>::epsilon() for the tolerance.\n  *\n  * The tolerance corresponds to the relative residual error: |Ax-b|/|b|\n  *\n  * \\b Performance: when using sparse matrices, best performance is achied for a row-major sparse matrix format.\n  * Moreover, in this case multi-threading can be exploited if the user code is compiled with OpenMP enabled.\n  * See \\ref TopicMultiThreading for details.\n  *\n  * By default the iterations start with x=0 as an initial guess of the solution.\n  * One can control the start using the solveWithGuess() method.\n  *\n  * IDR(s) can also be used in a matrix-free context, see the following \\link MatrixfreeSolverExample example \\endlink.\n  *\n  * \\sa class SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner\n  */\n\ttemplate <typename _MatrixType, typename _Preconditioner>\n\tclass IDRS : public IterativeSolverBase<IDRS<_MatrixType, _Preconditioner> >\n\t{\n\n\t\tpublic:\n\t\t\ttypedef _MatrixType MatrixType;\n\t\t\ttypedef typename MatrixType::Scalar Scalar;\n\t\t\ttypedef typename MatrixType::RealScalar RealScalar;\n\t\t\ttypedef _Preconditioner Preconditioner;\n\n\t\tprivate:\n\t\t\ttypedef IterativeSolverBase<IDRS> Base;\n\t\t\tusing Base::m_error;\n\t\t\tusing Base::m_info;\n\t\t\tusing Base::m_isInitialized;\n\t\t\tusing Base::m_iterations;\n\t\t\tusing Base::matrix;\n\t\t\tIndex m_S;\n\t\t\tbool m_smoothing;\n\t\t\tRealScalar m_angle;\n\t\t\tbool m_residual;\n\n\t\tpublic:\n\t\t\t/** Default constructor. */\n\t\t\tIDRS(): m_S(4), m_smoothing(false), m_angle(RealScalar(0.7)), m_residual(false) {}\n\n\t\t\t/**     Initialize the solver with matrix \\a A for further \\c Ax=b solving.\n\n\t\t\t        This constructor is a shortcut for the default constructor followed\n\t\t\t        by a call to compute().\n\n\t\t\t        \\warning this class stores a reference to the matrix A as well as some\n\t\t\t        precomputed values that depend on it. Therefore, if \\a A is changed\n\t\t\t        this class becomes invalid. Call compute() to update it with the new\n\t\t\t        matrix A, or modify a copy of A.\n\t\t\t*/\n\t\t\ttemplate <typename MatrixDerived>\n\t\t\texplicit IDRS(const EigenBase<MatrixDerived>& A) : Base(A.derived()), m_S(4), m_smoothing(false),\n\t\t\t\t\t\t\t\t\t\t\t\t\t\t\t   m_angle(RealScalar(0.7)), m_residual(false) {}\n\n\n\t\t\t/** \\internal */\n\t\t\t/**     Loops over the number of columns of b and does the following:\n\t\t\t                1. sets the tolerence and maxIterations\n\t\t\t                2. Calls the function that has the core solver routine\n\t\t\t*/\n\t\t\ttemplate <typename Rhs, typename Dest>\n\t\t\tvoid _solve_vector_with_guess_impl(const Rhs& b, Dest& x) const\n\t\t\t{\n\t\t\t\tm_iterations = Base::maxIterations();\n\t\t\t\tm_error = Base::m_tolerance;\n\n\t\t\t\tbool ret = internal::idrs(matrix(), b, x, Base::m_preconditioner, m_iterations, m_error, m_S,m_smoothing,m_angle,m_residual);\n\n\t\t\t\tm_info = (!ret) ? NumericalIssue : m_error <= Base::m_tolerance ? Success : NoConvergence;\n\t\t\t}\n\n\t\t\t/** Sets the parameter S, indicating the dimension of the shadow space. Default is 4*/\n\t\t\tvoid setS(Index S)\n\t\t\t{\n\t\t\t\tif (S < 1)\n\t\t\t\t{\n\t\t\t\t\tS = 4;\n\t\t\t\t}\n\n\t\t\t\tm_S = S;\n\t\t\t}\n\n\t\t\t/** Switches off and on smoothing.\n\t\t\tResidual smoothing results in monotonically decreasing residual norms at\n\t\t\tthe expense of two extra vectors of storage and a few extra vector\n\t\t\toperations. Although monotonic decrease of the residual norms is a\n\t\t\tdesirable property, the rate of convergence of the unsmoothed process and\n\t\t\tthe smoothed process is basically the same. Default is off */\n\t\t\tvoid setSmoothing(bool smoothing)\n\t\t\t{\n\t\t\t\tm_smoothing=smoothing;\n\t\t\t}\n\n\t\t\t/** The angle must be a real scalar. In IDR(s), a value for the\n\t\t\titeration parameter omega must be chosen in every s+1th step. The most\n\t\t\tnatural choice is to select a value to minimize the norm of the next residual.\n\t\t\tThis corresponds to the parameter omega = 0. In practice, this may lead to\n\t\t\tvalues of omega that are so small that the other iteration parameters\n\t\t\tcannot be computed with sufficient accuracy. In such cases it is better to\n\t\t\tincrease the value of omega sufficiently such that a compromise is reached\n\t\t\tbetween accurate computations and reduction of the residual norm. The\n\t\t\tparameter angle =0.7 (”maintaining the convergence strategy”)\n\t\t\tresults in such a compromise. */\n\t\t\tvoid setAngle(RealScalar angle)\n\t\t\t{\n\t\t\t\tm_angle=angle;\n\t\t\t}\n\n\t\t\t/** The parameter replace is a logical that determines whether a\n\t\t\tresidual replacement strategy is employed to increase the accuracy of the\n\t\t\tsolution. */\n\t\t\tvoid setResidualUpdate(bool update)\n\t\t\t{\n\t\t\t\tm_residual=update;\n\t\t\t}\n\n\t};\n\n}  // namespace Eigen\n\n#endif /* EIGEN_IDRS_H */\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/IterativeSolvers/IncompleteLU.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_INCOMPLETE_LU_H\n#define EIGEN_INCOMPLETE_LU_H\n\nnamespace Eigen { \n\ntemplate <typename _Scalar>\nclass IncompleteLU : public SparseSolverBase<IncompleteLU<_Scalar> >\n{\n  protected:\n    typedef SparseSolverBase<IncompleteLU<_Scalar> > Base;\n    using Base::m_isInitialized;\n    \n    typedef _Scalar Scalar;\n    typedef Matrix<Scalar,Dynamic,1> Vector;\n    typedef typename Vector::Index Index;\n    typedef SparseMatrix<Scalar,RowMajor> FactorType;\n\n  public:\n    typedef Matrix<Scalar,Dynamic,Dynamic> MatrixType;\n\n    IncompleteLU() {}\n\n    template<typename MatrixType>\n    IncompleteLU(const MatrixType& mat)\n    {\n      compute(mat);\n    }\n\n    Index rows() const { return m_lu.rows(); }\n    Index cols() const { return m_lu.cols(); }\n\n    template<typename MatrixType>\n    IncompleteLU& compute(const MatrixType& mat)\n    {\n      m_lu = mat;\n      int size = mat.cols();\n      Vector diag(size);\n      for(int i=0; i<size; ++i)\n      {\n        typename FactorType::InnerIterator k_it(m_lu,i);\n        for(; k_it && k_it.index()<i; ++k_it)\n        {\n          int k = k_it.index();\n          k_it.valueRef() /= diag(k);\n\n          typename FactorType::InnerIterator j_it(k_it);\n          typename FactorType::InnerIterator kj_it(m_lu, k);\n          while(kj_it && kj_it.index()<=k) ++kj_it;\n          for(++j_it; j_it; )\n          {\n            if(kj_it.index()==j_it.index())\n            {\n              j_it.valueRef() -= k_it.value() * kj_it.value();\n              ++j_it;\n              ++kj_it;\n            }\n            else if(kj_it.index()<j_it.index()) ++kj_it;\n            else                                ++j_it;\n          }\n        }\n        if(k_it && k_it.index()==i) diag(i) = k_it.value();\n        else                        diag(i) = 1;\n      }\n      m_isInitialized = true;\n      return *this;\n    }\n\n    template<typename Rhs, typename Dest>\n    void _solve_impl(const Rhs& b, Dest& x) const\n    {\n      x = m_lu.template triangularView<UnitLower>().solve(b);\n      x = m_lu.template triangularView<Upper>().solve(x);\n    }\n\n  protected:\n    FactorType m_lu;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_INCOMPLETE_LU_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/IterativeSolvers/IterationController.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n\n/* NOTE The class IterationController has been adapted from the iteration\n *      class of the GMM++ and ITL libraries.\n */\n\n//=======================================================================\n// Copyright (C) 1997-2001\n// Authors: Andrew Lumsdaine <lums@osl.iu.edu> \n//          Lie-Quan Lee     <llee@osl.iu.edu>\n//\n// This file is part of the Iterative Template Library\n//\n// You should have received a copy of the License Agreement for the\n// Iterative Template Library along with the software;  see the\n// file LICENSE.  \n//\n// Permission to modify the code and to distribute modified code is\n// granted, provided the text of this NOTICE is retained, a notice that\n// the code was modified is included with the above COPYRIGHT NOTICE and\n// with the COPYRIGHT NOTICE in the LICENSE file, and that the LICENSE\n// file is distributed with the modified code.\n//\n// LICENSOR MAKES NO REPRESENTATIONS OR WARRANTIES, EXPRESS OR IMPLIED.\n// By way of example, but not limitation, Licensor MAKES NO\n// REPRESENTATIONS OR WARRANTIES OF MERCHANTABILITY OR FITNESS FOR ANY\n// PARTICULAR PURPOSE OR THAT THE USE OF THE LICENSED SOFTWARE COMPONENTS\n// OR DOCUMENTATION WILL NOT INFRINGE ANY PATENTS, COPYRIGHTS, TRADEMARKS\n// OR OTHER RIGHTS.\n//=======================================================================\n\n//========================================================================\n//\n// Copyright (C) 2002-2007 Yves Renard\n//\n// This file is a part of GETFEM++\n//\n// Getfem++ is free software; you can redistribute it and/or modify\n// it under the terms of the GNU Lesser General Public License as\n// published by the Free Software Foundation; version 2.1 of the License.\n//\n// This program is distributed in the hope that it will be useful,\n// but WITHOUT ANY WARRANTY; without even the implied warranty of\n// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n// GNU Lesser General Public License for more details.\n// You should have received a copy of the GNU Lesser General Public\n// License along with this program; if not, write to the Free Software\n// Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301,\n// USA.\n//\n//========================================================================\n\n#include \"../../../../Eigen/src/Core/util/NonMPL2.h\"\n\n#ifndef EIGEN_ITERATION_CONTROLLER_H\n#define EIGEN_ITERATION_CONTROLLER_H\n\nnamespace Eigen { \n\n/** \\ingroup IterativeLinearSolvers_Module\n  * \\class IterationController\n  *\n  * \\brief Controls the iterations of the iterative solvers\n  *\n  * This class has been adapted from the iteration class of GMM++ and ITL libraries.\n  *\n  */\nclass IterationController\n{\n  protected :\n    double m_rhsn;        ///< Right hand side norm\n    size_t m_maxiter;     ///< Max. number of iterations\n    int m_noise;          ///< if noise > 0 iterations are printed\n    double m_resmax;      ///< maximum residual\n    double m_resminreach, m_resadd;\n    size_t m_nit;         ///< iteration number\n    double m_res;         ///< last computed residual\n    bool m_written;\n    void (*m_callback)(const IterationController&);\n  public :\n\n    void init()\n    {\n      m_nit = 0; m_res = 0.0; m_written = false;\n      m_resminreach = 1E50; m_resadd = 0.0;\n      m_callback = 0;\n    }\n\n    IterationController(double r = 1.0E-8, int noi = 0, size_t mit = size_t(-1))\n      : m_rhsn(1.0), m_maxiter(mit), m_noise(noi), m_resmax(r) { init(); }\n\n    void operator ++(int) { m_nit++; m_written = false; m_resadd += m_res; }\n    void operator ++() { (*this)++; }\n\n    bool first() { return m_nit == 0; }\n\n    /* get/set the \"noisyness\" (verbosity) of the solvers */\n    int noiseLevel() const { return m_noise; }\n    void setNoiseLevel(int n) { m_noise = n; }\n    void reduceNoiseLevel() { if (m_noise > 0) m_noise--; }\n\n    double maxResidual() const { return m_resmax; }\n    void setMaxResidual(double r) { m_resmax = r; }\n\n    double residual() const { return m_res; }\n\n    /* change the user-definable callback, called after each iteration */\n    void setCallback(void (*t)(const IterationController&))\n    {\n      m_callback = t;\n    }\n\n    size_t iteration() const { return m_nit; }\n    void setIteration(size_t i) { m_nit = i; }\n\n    size_t maxIterarions() const { return m_maxiter; }\n    void setMaxIterations(size_t i) { m_maxiter = i; }\n\n    double rhsNorm() const { return m_rhsn; }\n    void setRhsNorm(double r) { m_rhsn = r; }\n\n    bool converged() const { return m_res <= m_rhsn * m_resmax; }\n    bool converged(double nr)\n    {\n      using std::abs;\n      m_res = abs(nr); \n      m_resminreach = (std::min)(m_resminreach, m_res);\n      return converged();\n    }\n    template<typename VectorType> bool converged(const VectorType &v)\n    { return converged(v.squaredNorm()); }\n\n    bool finished(double nr)\n    {\n      if (m_callback) m_callback(*this);\n      if (m_noise > 0 && !m_written)\n      {\n        converged(nr);\n        m_written = true;\n      }\n      return (m_nit >= m_maxiter || converged(nr));\n    }\n    template <typename VectorType>\n    bool finished(const MatrixBase<VectorType> &v)\n    { return finished(double(v.squaredNorm())); }\n\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_ITERATION_CONTROLLER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/IterativeSolvers/MINRES.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Giacomo Po <gpo@ucla.edu>\n// Copyright (C) 2011-2014 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2018 David Hyde <dabh@stanford.edu>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#ifndef EIGEN_MINRES_H_\n#define EIGEN_MINRES_H_\n\n\nnamespace Eigen {\n    \n    namespace internal {\n        \n        /** \\internal Low-level MINRES algorithm\n         * \\param mat The matrix A\n         * \\param rhs The right hand side vector b\n         * \\param x On input and initial solution, on output the computed solution.\n         * \\param precond A right preconditioner being able to efficiently solve for an\n         *                approximation of Ax=b (regardless of b)\n         * \\param iters On input the max number of iteration, on output the number of performed iterations.\n         * \\param tol_error On input the tolerance error, on output an estimation of the relative error.\n         */\n        template<typename MatrixType, typename Rhs, typename Dest, typename Preconditioner>\n        EIGEN_DONT_INLINE\n        void minres(const MatrixType& mat, const Rhs& rhs, Dest& x,\n                    const Preconditioner& precond, Index& iters,\n                    typename Dest::RealScalar& tol_error)\n        {\n            using std::sqrt;\n            typedef typename Dest::RealScalar RealScalar;\n            typedef typename Dest::Scalar Scalar;\n            typedef Matrix<Scalar,Dynamic,1> VectorType;\n\n            // Check for zero rhs\n            const RealScalar rhsNorm2(rhs.squaredNorm());\n            if(rhsNorm2 == 0)\n            {\n                x.setZero();\n                iters = 0;\n                tol_error = 0;\n                return;\n            }\n            \n            // initialize\n            const Index maxIters(iters);  // initialize maxIters to iters\n            const Index N(mat.cols());    // the size of the matrix\n            const RealScalar threshold2(tol_error*tol_error*rhsNorm2); // convergence threshold (compared to residualNorm2)\n            \n            // Initialize preconditioned Lanczos\n            VectorType v_old(N); // will be initialized inside loop\n            VectorType v( VectorType::Zero(N) ); //initialize v\n            VectorType v_new(rhs-mat*x); //initialize v_new\n            RealScalar residualNorm2(v_new.squaredNorm());\n            VectorType w(N); // will be initialized inside loop\n            VectorType w_new(precond.solve(v_new)); // initialize w_new\n//            RealScalar beta; // will be initialized inside loop\n            RealScalar beta_new2(v_new.dot(w_new));\n            eigen_assert(beta_new2 >= 0.0 && \"PRECONDITIONER IS NOT POSITIVE DEFINITE\");\n            RealScalar beta_new(sqrt(beta_new2));\n            const RealScalar beta_one(beta_new);\n            // Initialize other variables\n            RealScalar c(1.0); // the cosine of the Givens rotation\n            RealScalar c_old(1.0);\n            RealScalar s(0.0); // the sine of the Givens rotation\n            RealScalar s_old(0.0); // the sine of the Givens rotation\n            VectorType p_oold(N); // will be initialized in loop\n            VectorType p_old(VectorType::Zero(N)); // initialize p_old=0\n            VectorType p(p_old); // initialize p=0\n            RealScalar eta(1.0);\n                        \n            iters = 0; // reset iters\n            while ( iters < maxIters )\n            {\n                // Preconditioned Lanczos\n                /* Note that there are 4 variants on the Lanczos algorithm. These are\n                 * described in Paige, C. C. (1972). Computational variants of\n                 * the Lanczos method for the eigenproblem. IMA Journal of Applied\n                 * Mathematics, 10(3), 373-381. The current implementation corresponds \n                 * to the case A(2,7) in the paper. It also corresponds to \n                 * algorithm 6.14 in Y. Saad, Iterative Methods for Sparse Linear\n                 * Systems, 2003 p.173. For the preconditioned version see \n                 * A. Greenbaum, Iterative Methods for Solving Linear Systems, SIAM (1987).\n                 */\n                const RealScalar beta(beta_new);\n                v_old = v; // update: at first time step, this makes v_old = 0 so value of beta doesn't matter\n                v_new /= beta_new; // overwrite v_new for next iteration\n                w_new /= beta_new; // overwrite w_new for next iteration\n                v = v_new; // update\n                w = w_new; // update\n                v_new.noalias() = mat*w - beta*v_old; // compute v_new\n                const RealScalar alpha = v_new.dot(w);\n                v_new -= alpha*v; // overwrite v_new\n                w_new = precond.solve(v_new); // overwrite w_new\n                beta_new2 = v_new.dot(w_new); // compute beta_new\n                eigen_assert(beta_new2 >= 0.0 && \"PRECONDITIONER IS NOT POSITIVE DEFINITE\");\n                beta_new = sqrt(beta_new2); // compute beta_new\n                \n                // Givens rotation\n                const RealScalar r2 =s*alpha+c*c_old*beta; // s, s_old, c and c_old are still from previous iteration\n                const RealScalar r3 =s_old*beta; // s, s_old, c and c_old are still from previous iteration\n                const RealScalar r1_hat=c*alpha-c_old*s*beta;\n                const RealScalar r1 =sqrt( std::pow(r1_hat,2) + std::pow(beta_new,2) );\n                c_old = c; // store for next iteration\n                s_old = s; // store for next iteration\n                c=r1_hat/r1; // new cosine\n                s=beta_new/r1; // new sine\n                \n                // Update solution\n                p_oold = p_old;\n                p_old = p;\n                p.noalias()=(w-r2*p_old-r3*p_oold) /r1; // IS NOALIAS REQUIRED?\n                x += beta_one*c*eta*p;\n                \n                /* Update the squared residual. Note that this is the estimated residual.\n                The real residual |Ax-b|^2 may be slightly larger */\n                residualNorm2 *= s*s;\n                \n                if ( residualNorm2 < threshold2)\n                {\n                    break;\n                }\n                \n                eta=-s*eta; // update eta\n                iters++; // increment iteration number (for output purposes)\n            }\n            \n            /* Compute error. Note that this is the estimated error. The real \n             error |Ax-b|/|b| may be slightly larger */\n            tol_error = std::sqrt(residualNorm2 / rhsNorm2);\n        }\n        \n    }\n    \n    template< typename _MatrixType, int _UpLo=Lower,\n    typename _Preconditioner = IdentityPreconditioner>\n    class MINRES;\n    \n    namespace internal {\n        \n        template< typename _MatrixType, int _UpLo, typename _Preconditioner>\n        struct traits<MINRES<_MatrixType,_UpLo,_Preconditioner> >\n        {\n            typedef _MatrixType MatrixType;\n            typedef _Preconditioner Preconditioner;\n        };\n        \n    }\n    \n    /** \\ingroup IterativeLinearSolvers_Module\n     * \\brief A minimal residual solver for sparse symmetric problems\n     *\n     * This class allows to solve for A.x = b sparse linear problems using the MINRES algorithm\n     * of Paige and Saunders (1975). The sparse matrix A must be symmetric (possibly indefinite).\n     * The vectors x and b can be either dense or sparse.\n     *\n     * \\tparam _MatrixType the type of the sparse matrix A, can be a dense or a sparse matrix.\n     * \\tparam _UpLo the triangular part that will be used for the computations. It can be Lower,\n     *               Upper, or Lower|Upper in which the full matrix entries will be considered. Default is Lower.\n     * \\tparam _Preconditioner the type of the preconditioner. Default is DiagonalPreconditioner\n     *\n     * The maximal number of iterations and tolerance value can be controlled via the setMaxIterations()\n     * and setTolerance() methods. The defaults are the size of the problem for the maximal number of iterations\n     * and NumTraits<Scalar>::epsilon() for the tolerance.\n     *\n     * This class can be used as the direct solver classes. Here is a typical usage example:\n     * \\code\n     * int n = 10000;\n     * VectorXd x(n), b(n);\n     * SparseMatrix<double> A(n,n);\n     * // fill A and b\n     * MINRES<SparseMatrix<double> > mr;\n     * mr.compute(A);\n     * x = mr.solve(b);\n     * std::cout << \"#iterations:     \" << mr.iterations() << std::endl;\n     * std::cout << \"estimated error: \" << mr.error()      << std::endl;\n     * // update b, and solve again\n     * x = mr.solve(b);\n     * \\endcode\n     *\n     * By default the iterations start with x=0 as an initial guess of the solution.\n     * One can control the start using the solveWithGuess() method.\n     *\n     * MINRES can also be used in a matrix-free context, see the following \\link MatrixfreeSolverExample example \\endlink.\n     *\n     * \\sa class ConjugateGradient, BiCGSTAB, SimplicialCholesky, DiagonalPreconditioner, IdentityPreconditioner\n     */\n    template< typename _MatrixType, int _UpLo, typename _Preconditioner>\n    class MINRES : public IterativeSolverBase<MINRES<_MatrixType,_UpLo,_Preconditioner> >\n    {\n        \n        typedef IterativeSolverBase<MINRES> Base;\n        using Base::matrix;\n        using Base::m_error;\n        using Base::m_iterations;\n        using Base::m_info;\n        using Base::m_isInitialized;\n    public:\n        using Base::_solve_impl;\n        typedef _MatrixType MatrixType;\n        typedef typename MatrixType::Scalar Scalar;\n        typedef typename MatrixType::RealScalar RealScalar;\n        typedef _Preconditioner Preconditioner;\n        \n        enum {UpLo = _UpLo};\n        \n    public:\n        \n        /** Default constructor. */\n        MINRES() : Base() {}\n        \n        /** Initialize the solver with matrix \\a A for further \\c Ax=b solving.\n         *\n         * This constructor is a shortcut for the default constructor followed\n         * by a call to compute().\n         *\n         * \\warning this class stores a reference to the matrix A as well as some\n         * precomputed values that depend on it. Therefore, if \\a A is changed\n         * this class becomes invalid. Call compute() to update it with the new\n         * matrix A, or modify a copy of A.\n         */\n        template<typename MatrixDerived>\n        explicit MINRES(const EigenBase<MatrixDerived>& A) : Base(A.derived()) {}\n        \n        /** Destructor. */\n        ~MINRES(){}\n\n        /** \\internal */\n        template<typename Rhs,typename Dest>\n        void _solve_vector_with_guess_impl(const Rhs& b, Dest& x) const\n        {\n            typedef typename Base::MatrixWrapper MatrixWrapper;\n            typedef typename Base::ActualMatrixType ActualMatrixType;\n            enum {\n              TransposeInput  =   (!MatrixWrapper::MatrixFree)\n                              &&  (UpLo==(Lower|Upper))\n                              &&  (!MatrixType::IsRowMajor)\n                              &&  (!NumTraits<Scalar>::IsComplex)\n            };\n            typedef typename internal::conditional<TransposeInput,Transpose<const ActualMatrixType>, ActualMatrixType const&>::type RowMajorWrapper;\n            EIGEN_STATIC_ASSERT(EIGEN_IMPLIES(MatrixWrapper::MatrixFree,UpLo==(Lower|Upper)),MATRIX_FREE_CONJUGATE_GRADIENT_IS_COMPATIBLE_WITH_UPPER_UNION_LOWER_MODE_ONLY);\n            typedef typename internal::conditional<UpLo==(Lower|Upper),\n                                                  RowMajorWrapper,\n                                                  typename MatrixWrapper::template ConstSelfAdjointViewReturnType<UpLo>::Type\n                                            >::type SelfAdjointWrapper;\n\n            m_iterations = Base::maxIterations();\n            m_error = Base::m_tolerance;\n            RowMajorWrapper row_mat(matrix());\n            internal::minres(SelfAdjointWrapper(row_mat), b, x,\n                             Base::m_preconditioner, m_iterations, m_error);\n            m_info = m_error <= Base::m_tolerance ? Success : NoConvergence;\n        }\n        \n    protected:\n        \n    };\n\n} // end namespace Eigen\n\n#endif // EIGEN_MINRES_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/IterativeSolvers/Scaling.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Desire NUENTSA WAKAM <desire.nuentsa_wakam@inria.fr\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_ITERSCALING_H\n#define EIGEN_ITERSCALING_H\n\nnamespace Eigen {\n\n/**\n  * \\ingroup IterativeSolvers_Module\n  * \\brief iterative scaling algorithm to equilibrate rows and column norms in matrices\n  * \n  * This class can be used as a preprocessing tool to accelerate the convergence of iterative methods \n  * \n  * This feature is  useful to limit the pivoting amount during LU/ILU factorization\n  * The  scaling strategy as presented here preserves the symmetry of the problem\n  * NOTE It is assumed that the matrix does not have empty row or column, \n  * \n  * Example with key steps \n  * \\code\n  * VectorXd x(n), b(n);\n  * SparseMatrix<double> A;\n  * // fill A and b;\n  * IterScaling<SparseMatrix<double> > scal; \n  * // Compute the left and right scaling vectors. The matrix is equilibrated at output\n  * scal.computeRef(A); \n  * // Scale the right hand side\n  * b = scal.LeftScaling().cwiseProduct(b); \n  * // Now, solve the equilibrated linear system with any available solver\n  * \n  * // Scale back the computed solution\n  * x = scal.RightScaling().cwiseProduct(x); \n  * \\endcode\n  * \n  * \\tparam _MatrixType the type of the matrix. It should be a real square sparsematrix\n  * \n  * References : D. Ruiz and B. Ucar, A Symmetry Preserving Algorithm for Matrix Scaling, INRIA Research report RR-7552\n  * \n  * \\sa \\ref IncompleteLUT \n  */\ntemplate<typename _MatrixType>\nclass IterScaling\n{\n  public:\n    typedef _MatrixType MatrixType; \n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::Index Index;\n    \n  public:\n    IterScaling() { init(); }\n    \n    IterScaling(const MatrixType& matrix)\n    {\n      init();\n      compute(matrix);\n    }\n    \n    ~IterScaling() { }\n    \n    /** \n     * Compute the left and right diagonal matrices to scale the input matrix @p mat\n     * \n     * FIXME This algorithm will be modified such that the diagonal elements are permuted on the diagonal. \n     * \n     * \\sa LeftScaling() RightScaling()\n     */\n    void compute (const MatrixType& mat)\n    {\n      using std::abs;\n      int m = mat.rows(); \n      int n = mat.cols();\n      eigen_assert((m>0 && m == n) && \"Please give a non - empty matrix\");\n      m_left.resize(m); \n      m_right.resize(n);\n      m_left.setOnes();\n      m_right.setOnes();\n      m_matrix = mat;\n      VectorXd Dr, Dc, DrRes, DcRes; // Temporary Left and right scaling vectors\n      Dr.resize(m); Dc.resize(n);\n      DrRes.resize(m); DcRes.resize(n);\n      double EpsRow = 1.0, EpsCol = 1.0;\n      int its = 0; \n      do\n      { // Iterate until the infinite norm of each row and column is approximately 1\n        // Get the maximum value in each row and column\n        Dr.setZero(); Dc.setZero();\n        for (int k=0; k<m_matrix.outerSize(); ++k)\n        {\n          for (typename MatrixType::InnerIterator it(m_matrix, k); it; ++it)\n          {\n            if ( Dr(it.row()) < abs(it.value()) )\n              Dr(it.row()) = abs(it.value());\n            \n            if ( Dc(it.col()) < abs(it.value()) )\n              Dc(it.col()) = abs(it.value());\n          }\n        }\n        for (int i = 0; i < m; ++i) \n        {\n          Dr(i) = std::sqrt(Dr(i));\n        }\n        for (int i = 0; i < n; ++i) \n        {\n          Dc(i) = std::sqrt(Dc(i));\n        }\n        // Save the scaling factors \n        for (int i = 0; i < m; ++i) \n        {\n          m_left(i) /= Dr(i);\n        }\n        for (int i = 0; i < n; ++i) \n        {\n          m_right(i) /= Dc(i);\n        }\n        // Scale the rows and the columns of the matrix\n        DrRes.setZero(); DcRes.setZero(); \n        for (int k=0; k<m_matrix.outerSize(); ++k)\n        {\n          for (typename MatrixType::InnerIterator it(m_matrix, k); it; ++it)\n          {\n            it.valueRef() = it.value()/( Dr(it.row()) * Dc(it.col()) );\n            // Accumulate the norms of the row and column vectors   \n            if ( DrRes(it.row()) < abs(it.value()) )\n              DrRes(it.row()) = abs(it.value());\n            \n            if ( DcRes(it.col()) < abs(it.value()) )\n              DcRes(it.col()) = abs(it.value());\n          }\n        }  \n        DrRes.array() = (1-DrRes.array()).abs();\n        EpsRow = DrRes.maxCoeff();\n        DcRes.array() = (1-DcRes.array()).abs();\n        EpsCol = DcRes.maxCoeff();\n        its++;\n      }while ( (EpsRow >m_tol || EpsCol > m_tol) && (its < m_maxits) );\n      m_isInitialized = true;\n    }\n    /** Compute the left and right vectors to scale the vectors\n     * the input matrix is scaled with the computed vectors at output\n     * \n     * \\sa compute()\n     */\n    void computeRef (MatrixType& mat)\n    {\n      compute (mat);\n      mat = m_matrix;\n    }\n    /** Get the vector to scale the rows of the matrix \n     */\n    VectorXd& LeftScaling()\n    {\n      return m_left;\n    }\n    \n    /** Get the vector to scale the columns of the matrix \n     */\n    VectorXd& RightScaling()\n    {\n      return m_right;\n    }\n    \n    /** Set the tolerance for the convergence of the iterative scaling algorithm\n     */\n    void setTolerance(double tol)\n    {\n      m_tol = tol; \n    }\n      \n  protected:\n    \n    void init()\n    {\n      m_tol = 1e-10;\n      m_maxits = 5;\n      m_isInitialized = false;\n    }\n    \n    MatrixType m_matrix;\n    mutable ComputationInfo m_info; \n    bool m_isInitialized; \n    VectorXd m_left; // Left scaling vector\n    VectorXd m_right; // m_right scaling vector\n    double m_tol; \n    int m_maxits; // Maximum number of iterations allowed\n};\n}\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/KroneckerProduct/KroneckerTensorProduct.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Kolja Brix <brix@igpm.rwth-aachen.de>\n// Copyright (C) 2011 Andreas Platen <andiplaten@gmx.de>\n// Copyright (C) 2012 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef KRONECKER_TENSOR_PRODUCT_H\n#define KRONECKER_TENSOR_PRODUCT_H\n\nnamespace Eigen {\n\n/*!\n * \\ingroup KroneckerProduct_Module\n *\n * \\brief The base class of dense and sparse Kronecker product.\n *\n * \\tparam Derived is the derived type.\n */\ntemplate<typename Derived>\nclass KroneckerProductBase : public ReturnByValue<Derived>\n{\n  private:\n    typedef typename internal::traits<Derived> Traits;\n    typedef typename Traits::Scalar Scalar;\n\n  protected:\n    typedef typename Traits::Lhs Lhs;\n    typedef typename Traits::Rhs Rhs;\n\n  public:\n    /*! \\brief Constructor. */\n    KroneckerProductBase(const Lhs& A, const Rhs& B)\n      : m_A(A), m_B(B)\n    {}\n\n    inline Index rows() const { return m_A.rows() * m_B.rows(); }\n    inline Index cols() const { return m_A.cols() * m_B.cols(); }\n\n    /*!\n     * This overrides ReturnByValue::coeff because this function is\n     * efficient enough.\n     */\n    Scalar coeff(Index row, Index col) const\n    {\n      return m_A.coeff(row / m_B.rows(), col / m_B.cols()) *\n             m_B.coeff(row % m_B.rows(), col % m_B.cols());\n    }\n\n    /*!\n     * This overrides ReturnByValue::coeff because this function is\n     * efficient enough.\n     */\n    Scalar coeff(Index i) const\n    {\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(Derived);\n      return m_A.coeff(i / m_A.size()) * m_B.coeff(i % m_A.size());\n    }\n\n  protected:\n    typename Lhs::Nested m_A;\n    typename Rhs::Nested m_B;\n};\n\n/*!\n * \\ingroup KroneckerProduct_Module\n *\n * \\brief Kronecker tensor product helper class for dense matrices\n *\n * This class is the return value of kroneckerProduct(MatrixBase,\n * MatrixBase). Use the function rather than construct this class\n * directly to avoid specifying template prarameters.\n *\n * \\tparam Lhs  Type of the left-hand side, a matrix expression.\n * \\tparam Rhs  Type of the rignt-hand side, a matrix expression.\n */\ntemplate<typename Lhs, typename Rhs>\nclass KroneckerProduct : public KroneckerProductBase<KroneckerProduct<Lhs,Rhs> >\n{\n  private:\n    typedef KroneckerProductBase<KroneckerProduct> Base;\n    using Base::m_A;\n    using Base::m_B;\n\n  public:\n    /*! \\brief Constructor. */\n    KroneckerProduct(const Lhs& A, const Rhs& B)\n      : Base(A, B)\n    {}\n\n    /*! \\brief Evaluate the Kronecker tensor product. */\n    template<typename Dest> void evalTo(Dest& dst) const;\n};\n\n/*!\n * \\ingroup KroneckerProduct_Module\n *\n * \\brief Kronecker tensor product helper class for sparse matrices\n *\n * If at least one of the operands is a sparse matrix expression,\n * then this class is returned and evaluates into a sparse matrix.\n *\n * This class is the return value of kroneckerProduct(EigenBase,\n * EigenBase). Use the function rather than construct this class\n * directly to avoid specifying template prarameters.\n *\n * \\tparam Lhs  Type of the left-hand side, a matrix expression.\n * \\tparam Rhs  Type of the rignt-hand side, a matrix expression.\n */\ntemplate<typename Lhs, typename Rhs>\nclass KroneckerProductSparse : public KroneckerProductBase<KroneckerProductSparse<Lhs,Rhs> >\n{\n  private:\n    typedef KroneckerProductBase<KroneckerProductSparse> Base;\n    using Base::m_A;\n    using Base::m_B;\n\n  public:\n    /*! \\brief Constructor. */\n    KroneckerProductSparse(const Lhs& A, const Rhs& B)\n      : Base(A, B)\n    {}\n\n    /*! \\brief Evaluate the Kronecker tensor product. */\n    template<typename Dest> void evalTo(Dest& dst) const;\n};\n\ntemplate<typename Lhs, typename Rhs>\ntemplate<typename Dest>\nvoid KroneckerProduct<Lhs,Rhs>::evalTo(Dest& dst) const\n{\n  const int BlockRows = Rhs::RowsAtCompileTime,\n            BlockCols = Rhs::ColsAtCompileTime;\n  const Index Br = m_B.rows(),\n              Bc = m_B.cols();\n  for (Index i=0; i < m_A.rows(); ++i)\n    for (Index j=0; j < m_A.cols(); ++j)\n      Block<Dest,BlockRows,BlockCols>(dst,i*Br,j*Bc,Br,Bc) = m_A.coeff(i,j) * m_B;\n}\n\ntemplate<typename Lhs, typename Rhs>\ntemplate<typename Dest>\nvoid KroneckerProductSparse<Lhs,Rhs>::evalTo(Dest& dst) const\n{\n  Index Br = m_B.rows(), Bc = m_B.cols();\n  dst.resize(this->rows(), this->cols());\n  dst.resizeNonZeros(0);\n  \n  // 1 - evaluate the operands if needed:\n  typedef typename internal::nested_eval<Lhs,Dynamic>::type Lhs1;\n  typedef typename internal::remove_all<Lhs1>::type Lhs1Cleaned;\n  const Lhs1 lhs1(m_A);\n  typedef typename internal::nested_eval<Rhs,Dynamic>::type Rhs1;\n  typedef typename internal::remove_all<Rhs1>::type Rhs1Cleaned;\n  const Rhs1 rhs1(m_B);\n    \n  // 2 - construct respective iterators\n  typedef Eigen::InnerIterator<Lhs1Cleaned> LhsInnerIterator;\n  typedef Eigen::InnerIterator<Rhs1Cleaned> RhsInnerIterator;\n  \n  // compute number of non-zeros per innervectors of dst\n  {\n    // TODO VectorXi is not necessarily big enough!\n    VectorXi nnzA = VectorXi::Zero(Dest::IsRowMajor ? m_A.rows() : m_A.cols());\n    for (Index kA=0; kA < m_A.outerSize(); ++kA)\n      for (LhsInnerIterator itA(lhs1,kA); itA; ++itA)\n        nnzA(Dest::IsRowMajor ? itA.row() : itA.col())++;\n      \n    VectorXi nnzB = VectorXi::Zero(Dest::IsRowMajor ? m_B.rows() : m_B.cols());\n    for (Index kB=0; kB < m_B.outerSize(); ++kB)\n      for (RhsInnerIterator itB(rhs1,kB); itB; ++itB)\n        nnzB(Dest::IsRowMajor ? itB.row() : itB.col())++;\n    \n    Matrix<int,Dynamic,Dynamic,ColMajor> nnzAB = nnzB * nnzA.transpose();\n    dst.reserve(VectorXi::Map(nnzAB.data(), nnzAB.size()));\n  }\n\n  for (Index kA=0; kA < m_A.outerSize(); ++kA)\n  {\n    for (Index kB=0; kB < m_B.outerSize(); ++kB)\n    {\n      for (LhsInnerIterator itA(lhs1,kA); itA; ++itA)\n      {\n        for (RhsInnerIterator itB(rhs1,kB); itB; ++itB)\n        {\n          Index i = itA.row() * Br + itB.row(),\n                j = itA.col() * Bc + itB.col();\n          dst.insert(i,j) = itA.value() * itB.value();\n        }\n      }\n    }\n  }\n}\n\nnamespace internal {\n\ntemplate<typename _Lhs, typename _Rhs>\nstruct traits<KroneckerProduct<_Lhs,_Rhs> >\n{\n  typedef typename remove_all<_Lhs>::type Lhs;\n  typedef typename remove_all<_Rhs>::type Rhs;\n  typedef typename ScalarBinaryOpTraits<typename Lhs::Scalar, typename Rhs::Scalar>::ReturnType Scalar;\n  typedef typename promote_index_type<typename Lhs::StorageIndex, typename Rhs::StorageIndex>::type StorageIndex;\n\n  enum {\n    Rows = size_at_compile_time<traits<Lhs>::RowsAtCompileTime, traits<Rhs>::RowsAtCompileTime>::ret,\n    Cols = size_at_compile_time<traits<Lhs>::ColsAtCompileTime, traits<Rhs>::ColsAtCompileTime>::ret,\n    MaxRows = size_at_compile_time<traits<Lhs>::MaxRowsAtCompileTime, traits<Rhs>::MaxRowsAtCompileTime>::ret,\n    MaxCols = size_at_compile_time<traits<Lhs>::MaxColsAtCompileTime, traits<Rhs>::MaxColsAtCompileTime>::ret\n  };\n\n  typedef Matrix<Scalar,Rows,Cols> ReturnType;\n};\n\ntemplate<typename _Lhs, typename _Rhs>\nstruct traits<KroneckerProductSparse<_Lhs,_Rhs> >\n{\n  typedef MatrixXpr XprKind;\n  typedef typename remove_all<_Lhs>::type Lhs;\n  typedef typename remove_all<_Rhs>::type Rhs;\n  typedef typename ScalarBinaryOpTraits<typename Lhs::Scalar, typename Rhs::Scalar>::ReturnType Scalar;\n  typedef typename cwise_promote_storage_type<typename traits<Lhs>::StorageKind, typename traits<Rhs>::StorageKind, scalar_product_op<typename Lhs::Scalar, typename Rhs::Scalar> >::ret StorageKind;\n  typedef typename promote_index_type<typename Lhs::StorageIndex, typename Rhs::StorageIndex>::type StorageIndex;\n\n  enum {\n    LhsFlags = Lhs::Flags,\n    RhsFlags = Rhs::Flags,\n\n    RowsAtCompileTime = size_at_compile_time<traits<Lhs>::RowsAtCompileTime, traits<Rhs>::RowsAtCompileTime>::ret,\n    ColsAtCompileTime = size_at_compile_time<traits<Lhs>::ColsAtCompileTime, traits<Rhs>::ColsAtCompileTime>::ret,\n    MaxRowsAtCompileTime = size_at_compile_time<traits<Lhs>::MaxRowsAtCompileTime, traits<Rhs>::MaxRowsAtCompileTime>::ret,\n    MaxColsAtCompileTime = size_at_compile_time<traits<Lhs>::MaxColsAtCompileTime, traits<Rhs>::MaxColsAtCompileTime>::ret,\n\n    EvalToRowMajor = (int(LhsFlags) & int(RhsFlags) & RowMajorBit),\n    RemovedBits = ~(EvalToRowMajor ? 0 : RowMajorBit),\n\n    Flags = ((int(LhsFlags) | int(RhsFlags)) & HereditaryBits & RemovedBits)\n          | EvalBeforeNestingBit,\n    CoeffReadCost = HugeCost\n  };\n\n  typedef SparseMatrix<Scalar, 0, StorageIndex> ReturnType;\n};\n\n} // end namespace internal\n\n/*!\n * \\ingroup KroneckerProduct_Module\n *\n * Computes Kronecker tensor product of two dense matrices\n *\n * \\warning If you want to replace a matrix by its Kronecker product\n *          with some matrix, do \\b NOT do this:\n * \\code\n * A = kroneckerProduct(A,B); // bug!!! caused by aliasing effect\n * \\endcode\n * instead, use eval() to work around this:\n * \\code\n * A = kroneckerProduct(A,B).eval();\n * \\endcode\n *\n * \\param a  Dense matrix a\n * \\param b  Dense matrix b\n * \\return   Kronecker tensor product of a and b\n */\ntemplate<typename A, typename B>\nKroneckerProduct<A,B> kroneckerProduct(const MatrixBase<A>& a, const MatrixBase<B>& b)\n{\n  return KroneckerProduct<A, B>(a.derived(), b.derived());\n}\n\n/*!\n * \\ingroup KroneckerProduct_Module\n *\n * Computes Kronecker tensor product of two matrices, at least one of\n * which is sparse\n *\n * \\warning If you want to replace a matrix by its Kronecker product\n *          with some matrix, do \\b NOT do this:\n * \\code\n * A = kroneckerProduct(A,B); // bug!!! caused by aliasing effect\n * \\endcode\n * instead, use eval() to work around this:\n * \\code\n * A = kroneckerProduct(A,B).eval();\n * \\endcode\n *\n * \\param a  Dense/sparse matrix a\n * \\param b  Dense/sparse matrix b\n * \\return   Kronecker tensor product of a and b, stored in a sparse\n *           matrix\n */\ntemplate<typename A, typename B>\nKroneckerProductSparse<A,B> kroneckerProduct(const EigenBase<A>& a, const EigenBase<B>& b)\n{\n  return KroneckerProductSparse<A,B>(a.derived(), b.derived());\n}\n\n} // end namespace Eigen\n\n#endif // KRONECKER_TENSOR_PRODUCT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/LevenbergMarquardt/CopyrightMINPACK.txt",
    "content": "Minpack Copyright Notice (1999) University of Chicago.  All rights reserved\n\nRedistribution and use in source and binary forms, with or\nwithout modification, are permitted provided that the\nfollowing conditions are met:\n\n1. Redistributions of source code must retain the above\ncopyright notice, this list of conditions and the following\ndisclaimer.\n\n2. Redistributions in binary form must reproduce the above\ncopyright notice, this list of conditions and the following\ndisclaimer in the documentation and/or other materials\nprovided with the distribution.\n\n3. The end-user documentation included with the\nredistribution, if any, must include the following\nacknowledgment:\n\n   \"This product includes software developed by the\n   University of Chicago, as Operator of Argonne National\n   Laboratory.\n\nAlternately, this acknowledgment may appear in the software\nitself, if and wherever such third-party acknowledgments\nnormally appear.\n\n4. WARRANTY DISCLAIMER. THE SOFTWARE IS SUPPLIED \"AS IS\"\nWITHOUT WARRANTY OF ANY KIND. THE COPYRIGHT HOLDER, THE\nUNITED STATES, THE UNITED STATES DEPARTMENT OF ENERGY, AND\nTHEIR EMPLOYEES: (1) DISCLAIM ANY WARRANTIES, EXPRESS OR\nIMPLIED, INCLUDING BUT NOT LIMITED TO ANY IMPLIED WARRANTIES\nOF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE, TITLE\nOR NON-INFRINGEMENT, (2) DO NOT ASSUME ANY LEGAL LIABILITY\nOR RESPONSIBILITY FOR THE ACCURACY, COMPLETENESS, OR\nUSEFULNESS OF THE SOFTWARE, (3) DO NOT REPRESENT THAT USE OF\nTHE SOFTWARE WOULD NOT INFRINGE PRIVATELY OWNED RIGHTS, (4)\nDO NOT WARRANT THAT THE SOFTWARE WILL FUNCTION\nUNINTERRUPTED, THAT IT IS ERROR-FREE OR THAT ANY ERRORS WILL\nBE CORRECTED.\n\n5. LIMITATION OF LIABILITY. IN NO EVENT WILL THE COPYRIGHT\nHOLDER, THE UNITED STATES, THE UNITED STATES DEPARTMENT OF\nENERGY, OR THEIR EMPLOYEES: BE LIABLE FOR ANY INDIRECT,\nINCIDENTAL, CONSEQUENTIAL, SPECIAL OR PUNITIVE DAMAGES OF\nANY KIND OR NATURE, INCLUDING BUT NOT LIMITED TO LOSS OF\nPROFITS OR LOSS OF DATA, FOR ANY REASON WHATSOEVER, WHETHER\nSUCH LIABILITY IS ASSERTED ON THE BASIS OF CONTRACT, TORT\n(INCLUDING NEGLIGENCE OR STRICT LIABILITY), OR OTHERWISE,\nEVEN IF ANY OF SAID PARTIES HAS BEEN WARNED OF THE\nPOSSIBILITY OF SUCH LOSS OR DAMAGES.\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/LevenbergMarquardt/LMcovar.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This code initially comes from MINPACK whose original authors are:\n// Copyright Jorge More - Argonne National Laboratory\n// Copyright Burt Garbow - Argonne National Laboratory\n// Copyright Ken Hillstrom - Argonne National Laboratory\n//\n// This Source Code Form is subject to the terms of the Minpack license\n// (a BSD-like license) described in the campaigned CopyrightMINPACK.txt file.\n\n#ifndef EIGEN_LMCOVAR_H\n#define EIGEN_LMCOVAR_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate <typename Scalar>\nvoid covar(\n        Matrix< Scalar, Dynamic, Dynamic > &r,\n        const VectorXi& ipvt,\n        Scalar tol = std::sqrt(NumTraits<Scalar>::epsilon()) )\n{\n    using std::abs;\n    /* Local variables */\n    Index i, j, k, l, ii, jj;\n    bool sing;\n    Scalar temp;\n\n    /* Function Body */\n    const Index n = r.cols();\n    const Scalar tolr = tol * abs(r(0,0));\n    Matrix< Scalar, Dynamic, 1 > wa(n);\n    eigen_assert(ipvt.size()==n);\n\n    /* form the inverse of r in the full upper triangle of r. */\n    l = -1;\n    for (k = 0; k < n; ++k)\n        if (abs(r(k,k)) > tolr) {\n            r(k,k) = 1. / r(k,k);\n            for (j = 0; j <= k-1; ++j) {\n                temp = r(k,k) * r(j,k);\n                r(j,k) = 0.;\n                r.col(k).head(j+1) -= r.col(j).head(j+1) * temp;\n            }\n            l = k;\n        }\n\n    /* form the full upper triangle of the inverse of (r transpose)*r */\n    /* in the full upper triangle of r. */\n    for (k = 0; k <= l; ++k) {\n        for (j = 0; j <= k-1; ++j)\n            r.col(j).head(j+1) += r.col(k).head(j+1) * r(j,k);\n        r.col(k).head(k+1) *= r(k,k);\n    }\n\n    /* form the full lower triangle of the covariance matrix */\n    /* in the strict lower triangle of r and in wa. */\n    for (j = 0; j < n; ++j) {\n        jj = ipvt[j];\n        sing = j > l;\n        for (i = 0; i <= j; ++i) {\n            if (sing)\n                r(i,j) = 0.;\n            ii = ipvt[i];\n            if (ii > jj)\n                r(ii,jj) = r(i,j);\n            if (ii < jj)\n                r(jj,ii) = r(i,j);\n        }\n        wa[jj] = r(j,j);\n    }\n\n    /* symmetrize the covariance matrix in r. */\n    r.topLeftCorner(n,n).template triangularView<StrictlyUpper>() = r.topLeftCorner(n,n).transpose();\n    r.diagonal() = wa;\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_LMCOVAR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/LevenbergMarquardt/LMonestep.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n//\n// This code initially comes from MINPACK whose original authors are:\n// Copyright Jorge More - Argonne National Laboratory\n// Copyright Burt Garbow - Argonne National Laboratory\n// Copyright Ken Hillstrom - Argonne National Laboratory\n//\n// This Source Code Form is subject to the terms of the Minpack license\n// (a BSD-like license) described in the campaigned CopyrightMINPACK.txt file.\n\n#ifndef EIGEN_LMONESTEP_H\n#define EIGEN_LMONESTEP_H\n\nnamespace Eigen {\n\ntemplate<typename FunctorType>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType>::minimizeOneStep(FVectorType  &x)\n{\n  using std::abs;\n  using std::sqrt;\n  RealScalar temp, temp1,temp2; \n  RealScalar ratio; \n  RealScalar pnorm, xnorm, fnorm1, actred, dirder, prered;\n  eigen_assert(x.size()==n); // check the caller is not cheating us\n\n  temp = 0.0; xnorm = 0.0;\n  /* calculate the jacobian matrix. */\n  Index df_ret = m_functor.df(x, m_fjac);\n  if (df_ret<0)\n      return LevenbergMarquardtSpace::UserAsked;\n  if (df_ret>0)\n      // numerical diff, we evaluated the function df_ret times\n      m_nfev += df_ret;\n  else m_njev++;\n\n  /* compute the qr factorization of the jacobian. */\n  for (int j = 0; j < x.size(); ++j)\n    m_wa2(j) = m_fjac.col(j).blueNorm();\n  QRSolver qrfac(m_fjac);\n  if(qrfac.info() != Success) {\n    m_info = NumericalIssue;\n    return LevenbergMarquardtSpace::ImproperInputParameters;\n  }\n  // Make a copy of the first factor with the associated permutation\n  m_rfactor = qrfac.matrixR();\n  m_permutation = (qrfac.colsPermutation());\n\n  /* on the first iteration and if external scaling is not used, scale according */\n  /* to the norms of the columns of the initial jacobian. */\n  if (m_iter == 1) {\n      if (!m_useExternalScaling)\n          for (Index j = 0; j < n; ++j)\n              m_diag[j] = (m_wa2[j]==0.)? 1. : m_wa2[j];\n\n      /* on the first iteration, calculate the norm of the scaled x */\n      /* and initialize the step bound m_delta. */\n      xnorm = m_diag.cwiseProduct(x).stableNorm();\n      m_delta = m_factor * xnorm;\n      if (m_delta == 0.)\n          m_delta = m_factor;\n  }\n\n  /* form (q transpose)*m_fvec and store the first n components in */\n  /* m_qtf. */\n  m_wa4 = m_fvec;\n  m_wa4 = qrfac.matrixQ().adjoint() * m_fvec; \n  m_qtf = m_wa4.head(n);\n\n  /* compute the norm of the scaled gradient. */\n  m_gnorm = 0.;\n  if (m_fnorm != 0.)\n      for (Index j = 0; j < n; ++j)\n          if (m_wa2[m_permutation.indices()[j]] != 0.)\n              m_gnorm = (std::max)(m_gnorm, abs( m_rfactor.col(j).head(j+1).dot(m_qtf.head(j+1)/m_fnorm) / m_wa2[m_permutation.indices()[j]]));\n\n  /* test for convergence of the gradient norm. */\n  if (m_gnorm <= m_gtol) {\n    m_info = Success;\n    return LevenbergMarquardtSpace::CosinusTooSmall;\n  }\n\n  /* rescale if necessary. */\n  if (!m_useExternalScaling)\n      m_diag = m_diag.cwiseMax(m_wa2);\n\n  do {\n    /* determine the levenberg-marquardt parameter. */\n    internal::lmpar2(qrfac, m_diag, m_qtf, m_delta, m_par, m_wa1);\n\n    /* store the direction p and x + p. calculate the norm of p. */\n    m_wa1 = -m_wa1;\n    m_wa2 = x + m_wa1;\n    pnorm = m_diag.cwiseProduct(m_wa1).stableNorm();\n\n    /* on the first iteration, adjust the initial step bound. */\n    if (m_iter == 1)\n        m_delta = (std::min)(m_delta,pnorm);\n\n    /* evaluate the function at x + p and calculate its norm. */\n    if ( m_functor(m_wa2, m_wa4) < 0)\n        return LevenbergMarquardtSpace::UserAsked;\n    ++m_nfev;\n    fnorm1 = m_wa4.stableNorm();\n\n    /* compute the scaled actual reduction. */\n    actred = -1.;\n    if (Scalar(.1) * fnorm1 < m_fnorm)\n        actred = 1. - numext::abs2(fnorm1 / m_fnorm);\n\n    /* compute the scaled predicted reduction and */\n    /* the scaled directional derivative. */\n    m_wa3 = m_rfactor.template triangularView<Upper>() * (m_permutation.inverse() *m_wa1);\n    temp1 = numext::abs2(m_wa3.stableNorm() / m_fnorm);\n    temp2 = numext::abs2(sqrt(m_par) * pnorm / m_fnorm);\n    prered = temp1 + temp2 / Scalar(.5);\n    dirder = -(temp1 + temp2);\n\n    /* compute the ratio of the actual to the predicted */\n    /* reduction. */\n    ratio = 0.;\n    if (prered != 0.)\n        ratio = actred / prered;\n\n    /* update the step bound. */\n    if (ratio <= Scalar(.25)) {\n        if (actred >= 0.)\n            temp = RealScalar(.5);\n        if (actred < 0.)\n            temp = RealScalar(.5) * dirder / (dirder + RealScalar(.5) * actred);\n        if (RealScalar(.1) * fnorm1 >= m_fnorm || temp < RealScalar(.1))\n            temp = Scalar(.1);\n        /* Computing MIN */\n        m_delta = temp * (std::min)(m_delta, pnorm / RealScalar(.1));\n        m_par /= temp;\n    } else if (!(m_par != 0. && ratio < RealScalar(.75))) {\n        m_delta = pnorm / RealScalar(.5);\n        m_par = RealScalar(.5) * m_par;\n    }\n\n    /* test for successful iteration. */\n    if (ratio >= RealScalar(1e-4)) {\n        /* successful iteration. update x, m_fvec, and their norms. */\n        x = m_wa2;\n        m_wa2 = m_diag.cwiseProduct(x);\n        m_fvec = m_wa4;\n        xnorm = m_wa2.stableNorm();\n        m_fnorm = fnorm1;\n        ++m_iter;\n    }\n\n    /* tests for convergence. */\n    if (abs(actred) <= m_ftol && prered <= m_ftol && Scalar(.5) * ratio <= 1. && m_delta <= m_xtol * xnorm)\n    {\n       m_info = Success;\n      return LevenbergMarquardtSpace::RelativeErrorAndReductionTooSmall;\n    }\n    if (abs(actred) <= m_ftol && prered <= m_ftol && Scalar(.5) * ratio <= 1.) \n    {\n      m_info = Success;\n      return LevenbergMarquardtSpace::RelativeReductionTooSmall;\n    }\n    if (m_delta <= m_xtol * xnorm)\n    {\n      m_info = Success;\n      return LevenbergMarquardtSpace::RelativeErrorTooSmall;\n    }\n\n    /* tests for termination and stringent tolerances. */\n    if (m_nfev >= m_maxfev) \n    {\n      m_info = NoConvergence;\n      return LevenbergMarquardtSpace::TooManyFunctionEvaluation;\n    }\n    if (abs(actred) <= NumTraits<Scalar>::epsilon() && prered <= NumTraits<Scalar>::epsilon() && Scalar(.5) * ratio <= 1.)\n    {\n      m_info = Success;\n      return LevenbergMarquardtSpace::FtolTooSmall;\n    }\n    if (m_delta <= NumTraits<Scalar>::epsilon() * xnorm) \n    {\n      m_info = Success;\n      return LevenbergMarquardtSpace::XtolTooSmall;\n    }\n    if (m_gnorm <= NumTraits<Scalar>::epsilon())\n    {\n      m_info = Success;\n      return LevenbergMarquardtSpace::GtolTooSmall;\n    }\n\n  } while (ratio < Scalar(1e-4));\n\n  return LevenbergMarquardtSpace::Running;\n}\n\n  \n} // end namespace Eigen\n\n#endif // EIGEN_LMONESTEP_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/LevenbergMarquardt/LMpar.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This code initially comes from MINPACK whose original authors are:\n// Copyright Jorge More - Argonne National Laboratory\n// Copyright Burt Garbow - Argonne National Laboratory\n// Copyright Ken Hillstrom - Argonne National Laboratory\n//\n// This Source Code Form is subject to the terms of the Minpack license\n// (a BSD-like license) described in the campaigned CopyrightMINPACK.txt file.\n\n#ifndef EIGEN_LMPAR_H\n#define EIGEN_LMPAR_H\n\nnamespace Eigen {\n\nnamespace internal {\n  \n  template <typename QRSolver, typename VectorType>\n    void lmpar2(\n    const QRSolver &qr,\n    const VectorType  &diag,\n    const VectorType  &qtb,\n    typename VectorType::Scalar m_delta,\n    typename VectorType::Scalar &par,\n    VectorType  &x)\n\n  {\n    using std::sqrt;\n    using std::abs;\n    typedef typename QRSolver::MatrixType MatrixType;\n    typedef typename QRSolver::Scalar Scalar;\n//    typedef typename QRSolver::StorageIndex StorageIndex;\n\n    /* Local variables */\n    Index j;\n    Scalar fp;\n    Scalar parc, parl;\n    Index iter;\n    Scalar temp, paru;\n    Scalar gnorm;\n    Scalar dxnorm;\n    \n    // Make a copy of the triangular factor. \n    // This copy is modified during call the qrsolv\n    MatrixType s;\n    s = qr.matrixR();\n\n    /* Function Body */\n    const Scalar dwarf = (std::numeric_limits<Scalar>::min)();\n    const Index n = qr.matrixR().cols();\n    eigen_assert(n==diag.size());\n    eigen_assert(n==qtb.size());\n\n    VectorType  wa1, wa2;\n\n    /* compute and store in x the gauss-newton direction. if the */\n    /* jacobian is rank-deficient, obtain a least squares solution. */\n\n    //    const Index rank = qr.nonzeroPivots(); // exactly double(0.)\n    const Index rank = qr.rank(); // use a threshold\n    wa1 = qtb;\n    wa1.tail(n-rank).setZero();\n    //FIXME There is no solve in place for sparse triangularView\n    wa1.head(rank) = s.topLeftCorner(rank,rank).template triangularView<Upper>().solve(qtb.head(rank));\n\n    x = qr.colsPermutation()*wa1;\n\n    /* initialize the iteration counter. */\n    /* evaluate the function at the origin, and test */\n    /* for acceptance of the gauss-newton direction. */\n    iter = 0;\n    wa2 = diag.cwiseProduct(x);\n    dxnorm = wa2.blueNorm();\n    fp = dxnorm - m_delta;\n    if (fp <= Scalar(0.1) * m_delta) {\n      par = 0;\n      return;\n    }\n\n    /* if the jacobian is not rank deficient, the newton */\n    /* step provides a lower bound, parl, for the zero of */\n    /* the function. otherwise set this bound to zero. */\n    parl = 0.;\n    if (rank==n) {\n      wa1 = qr.colsPermutation().inverse() *  diag.cwiseProduct(wa2)/dxnorm;\n      s.topLeftCorner(n,n).transpose().template triangularView<Lower>().solveInPlace(wa1);\n      temp = wa1.blueNorm();\n      parl = fp / m_delta / temp / temp;\n    }\n\n    /* calculate an upper bound, paru, for the zero of the function. */\n    for (j = 0; j < n; ++j)\n      wa1[j] = s.col(j).head(j+1).dot(qtb.head(j+1)) / diag[qr.colsPermutation().indices()(j)];\n\n    gnorm = wa1.stableNorm();\n    paru = gnorm / m_delta;\n    if (paru == 0.)\n      paru = dwarf / (std::min)(m_delta,Scalar(0.1));\n\n    /* if the input par lies outside of the interval (parl,paru), */\n    /* set par to the closer endpoint. */\n    par = (std::max)(par,parl);\n    par = (std::min)(par,paru);\n    if (par == 0.)\n      par = gnorm / dxnorm;\n\n    /* beginning of an iteration. */\n    while (true) {\n      ++iter;\n\n      /* evaluate the function at the current value of par. */\n      if (par == 0.)\n        par = (std::max)(dwarf,Scalar(.001) * paru); /* Computing MAX */\n      wa1 = sqrt(par)* diag;\n\n      VectorType sdiag(n);\n      lmqrsolv(s, qr.colsPermutation(), wa1, qtb, x, sdiag);\n\n      wa2 = diag.cwiseProduct(x);\n      dxnorm = wa2.blueNorm();\n      temp = fp;\n      fp = dxnorm - m_delta;\n\n      /* if the function is small enough, accept the current value */\n      /* of par. also test for the exceptional cases where parl */\n      /* is zero or the number of iterations has reached 10. */\n      if (abs(fp) <= Scalar(0.1) * m_delta || (parl == 0. && fp <= temp && temp < 0.) || iter == 10)\n        break;\n\n      /* compute the newton correction. */\n      wa1 = qr.colsPermutation().inverse() * diag.cwiseProduct(wa2/dxnorm);\n      // we could almost use this here, but the diagonal is outside qr, in sdiag[]\n      for (j = 0; j < n; ++j) {\n        wa1[j] /= sdiag[j];\n        temp = wa1[j];\n        for (Index i = j+1; i < n; ++i)\n          wa1[i] -= s.coeff(i,j) * temp;\n      }\n      temp = wa1.blueNorm();\n      parc = fp / m_delta / temp / temp;\n\n      /* depending on the sign of the function, update parl or paru. */\n      if (fp > 0.)\n        parl = (std::max)(parl,par);\n      if (fp < 0.)\n        paru = (std::min)(paru,par);\n\n      /* compute an improved estimate for par. */\n      par = (std::max)(parl,par+parc);\n    }\n    if (iter == 0)\n      par = 0.;\n    return;\n  }\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_LMPAR_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/LevenbergMarquardt/LMqrsolv.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n// Copyright (C) 2012 Desire Nuentsa <desire.nuentsa_wakam@inria.fr>\n//\n// This code initially comes from MINPACK whose original authors are:\n// Copyright Jorge More - Argonne National Laboratory\n// Copyright Burt Garbow - Argonne National Laboratory\n// Copyright Ken Hillstrom - Argonne National Laboratory\n//\n// This Source Code Form is subject to the terms of the Minpack license\n// (a BSD-like license) described in the campaigned CopyrightMINPACK.txt file.\n\n#ifndef EIGEN_LMQRSOLV_H\n#define EIGEN_LMQRSOLV_H\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate <typename Scalar,int Rows, int Cols, typename PermIndex>\nvoid lmqrsolv(\n  Matrix<Scalar,Rows,Cols> &s,\n  const PermutationMatrix<Dynamic,Dynamic,PermIndex> &iPerm,\n  const Matrix<Scalar,Dynamic,1> &diag,\n  const Matrix<Scalar,Dynamic,1> &qtb,\n  Matrix<Scalar,Dynamic,1> &x,\n  Matrix<Scalar,Dynamic,1> &sdiag)\n{\n    /* Local variables */\n    Index i, j, k;\n    Scalar temp;\n    Index n = s.cols();\n    Matrix<Scalar,Dynamic,1>  wa(n);\n    JacobiRotation<Scalar> givens;\n\n    /* Function Body */\n    // the following will only change the lower triangular part of s, including\n    // the diagonal, though the diagonal is restored afterward\n\n    /*     copy r and (q transpose)*b to preserve input and initialize s. */\n    /*     in particular, save the diagonal elements of r in x. */\n    x = s.diagonal();\n    wa = qtb;\n    \n   \n    s.topLeftCorner(n,n).template triangularView<StrictlyLower>() = s.topLeftCorner(n,n).transpose();\n    /*     eliminate the diagonal matrix d using a givens rotation. */\n    for (j = 0; j < n; ++j) {\n\n        /*        prepare the row of d to be eliminated, locating the */\n        /*        diagonal element using p from the qr factorization. */\n        const PermIndex l = iPerm.indices()(j);\n        if (diag[l] == 0.)\n            break;\n        sdiag.tail(n-j).setZero();\n        sdiag[j] = diag[l];\n\n        /*        the transformations to eliminate the row of d */\n        /*        modify only a single element of (q transpose)*b */\n        /*        beyond the first n, which is initially zero. */\n        Scalar qtbpj = 0.;\n        for (k = j; k < n; ++k) {\n            /*           determine a givens rotation which eliminates the */\n            /*           appropriate element in the current row of d. */\n            givens.makeGivens(-s(k,k), sdiag[k]);\n\n            /*           compute the modified diagonal element of r and */\n            /*           the modified element of ((q transpose)*b,0). */\n            s(k,k) = givens.c() * s(k,k) + givens.s() * sdiag[k];\n            temp = givens.c() * wa[k] + givens.s() * qtbpj;\n            qtbpj = -givens.s() * wa[k] + givens.c() * qtbpj;\n            wa[k] = temp;\n\n            /*           accumulate the transformation in the row of s. */\n            for (i = k+1; i<n; ++i) {\n                temp = givens.c() * s(i,k) + givens.s() * sdiag[i];\n                sdiag[i] = -givens.s() * s(i,k) + givens.c() * sdiag[i];\n                s(i,k) = temp;\n            }\n        }\n    }\n  \n    /*     solve the triangular system for z. if the system is */\n    /*     singular, then obtain a least squares solution. */\n    Index nsing;\n    for(nsing=0; nsing<n && sdiag[nsing]!=0; nsing++) {}\n\n    wa.tail(n-nsing).setZero();\n    s.topLeftCorner(nsing, nsing).transpose().template triangularView<Upper>().solveInPlace(wa.head(nsing));\n  \n    // restore\n    sdiag = s.diagonal();\n    s.diagonal() = x;\n\n    /* permute the components of z back to components of x. */\n    x = iPerm * wa; \n}\n\ntemplate <typename Scalar, int _Options, typename Index>\nvoid lmqrsolv(\n  SparseMatrix<Scalar,_Options,Index> &s,\n  const PermutationMatrix<Dynamic,Dynamic> &iPerm,\n  const Matrix<Scalar,Dynamic,1> &diag,\n  const Matrix<Scalar,Dynamic,1> &qtb,\n  Matrix<Scalar,Dynamic,1> &x,\n  Matrix<Scalar,Dynamic,1> &sdiag)\n{\n  /* Local variables */\n  typedef SparseMatrix<Scalar,RowMajor,Index> FactorType;\n    Index i, j, k, l;\n    Scalar temp;\n    Index n = s.cols();\n    Matrix<Scalar,Dynamic,1>  wa(n);\n    JacobiRotation<Scalar> givens;\n\n    /* Function Body */\n    // the following will only change the lower triangular part of s, including\n    // the diagonal, though the diagonal is restored afterward\n\n    /*     copy r and (q transpose)*b to preserve input and initialize R. */\n    wa = qtb;\n    FactorType R(s);\n    // Eliminate the diagonal matrix d using a givens rotation\n    for (j = 0; j < n; ++j)\n    {\n      // Prepare the row of d to be eliminated, locating the \n      // diagonal element using p from the qr factorization\n      l = iPerm.indices()(j);\n      if (diag(l) == Scalar(0)) \n        break; \n      sdiag.tail(n-j).setZero();\n      sdiag[j] = diag[l];\n      // the transformations to eliminate the row of d\n      // modify only a single element of (q transpose)*b\n      // beyond the first n, which is initially zero. \n      \n      Scalar qtbpj = 0; \n      // Browse the nonzero elements of row j of the upper triangular s\n      for (k = j; k < n; ++k)\n      {\n        typename FactorType::InnerIterator itk(R,k);\n        for (; itk; ++itk){\n          if (itk.index() < k) continue;\n          else break;\n        }\n        //At this point, we have the diagonal element R(k,k)\n        // Determine a givens rotation which eliminates \n        // the appropriate element in the current row of d\n        givens.makeGivens(-itk.value(), sdiag(k));\n        \n        // Compute the modified diagonal element of r and \n        // the modified element of ((q transpose)*b,0).\n        itk.valueRef() = givens.c() * itk.value() + givens.s() * sdiag(k);\n        temp = givens.c() * wa(k) + givens.s() * qtbpj; \n        qtbpj = -givens.s() * wa(k) + givens.c() * qtbpj;\n        wa(k) = temp;\n        \n        // Accumulate the transformation in the remaining k row/column of R\n        for (++itk; itk; ++itk)\n        {\n          i = itk.index();\n          temp = givens.c() *  itk.value() + givens.s() * sdiag(i);\n          sdiag(i) = -givens.s() * itk.value() + givens.c() * sdiag(i);\n          itk.valueRef() = temp;\n        }\n      }\n    }\n    \n    // Solve the triangular system for z. If the system is \n    // singular, then obtain a least squares solution\n    Index nsing;\n    for(nsing = 0; nsing<n && sdiag(nsing) !=0; nsing++) {}\n    \n    wa.tail(n-nsing).setZero();\n//     x = wa; \n    wa.head(nsing) = R.topLeftCorner(nsing,nsing).template triangularView<Upper>().solve/*InPlace*/(wa.head(nsing));\n    \n    sdiag = R.diagonal();\n    // Permute the components of z back to components of x\n    x = iPerm * wa; \n}\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_LMQRSOLV_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/LevenbergMarquardt/LevenbergMarquardt.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n// Copyright (C) 2012 Desire Nuentsa <desire.nuentsa_wakam@inria.fr>\n//\n// The algorithm of this class initially comes from MINPACK whose original authors are:\n// Copyright Jorge More - Argonne National Laboratory\n// Copyright Burt Garbow - Argonne National Laboratory\n// Copyright Ken Hillstrom - Argonne National Laboratory\n//\n// This Source Code Form is subject to the terms of the Minpack license\n// (a BSD-like license) described in the campaigned CopyrightMINPACK.txt file.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_LEVENBERGMARQUARDT_H\n#define EIGEN_LEVENBERGMARQUARDT_H\n\n\nnamespace Eigen {\nnamespace LevenbergMarquardtSpace {\n    enum Status {\n        NotStarted = -2,\n        Running = -1,\n        ImproperInputParameters = 0,\n        RelativeReductionTooSmall = 1,\n        RelativeErrorTooSmall = 2,\n        RelativeErrorAndReductionTooSmall = 3,\n        CosinusTooSmall = 4,\n        TooManyFunctionEvaluation = 5,\n        FtolTooSmall = 6,\n        XtolTooSmall = 7,\n        GtolTooSmall = 8,\n        UserAsked = 9\n    };\n}\n\ntemplate <typename _Scalar, int NX=Dynamic, int NY=Dynamic>\nstruct DenseFunctor\n{\n  typedef _Scalar Scalar;\n  enum {\n    InputsAtCompileTime = NX,\n    ValuesAtCompileTime = NY\n  };\n  typedef Matrix<Scalar,InputsAtCompileTime,1> InputType;\n  typedef Matrix<Scalar,ValuesAtCompileTime,1> ValueType;\n  typedef Matrix<Scalar,ValuesAtCompileTime,InputsAtCompileTime> JacobianType;\n  typedef ColPivHouseholderQR<JacobianType> QRSolver;\n  const int m_inputs, m_values;\n\n  DenseFunctor() : m_inputs(InputsAtCompileTime), m_values(ValuesAtCompileTime) {}\n  DenseFunctor(int inputs, int values) : m_inputs(inputs), m_values(values) {}\n\n  int inputs() const { return m_inputs; }\n  int values() const { return m_values; }\n\n  //int operator()(const InputType &x, ValueType& fvec) { }\n  // should be defined in derived classes\n  \n  //int df(const InputType &x, JacobianType& fjac) { }\n  // should be defined in derived classes\n};\n\ntemplate <typename _Scalar, typename _Index>\nstruct SparseFunctor\n{\n  typedef _Scalar Scalar;\n  typedef _Index Index;\n  typedef Matrix<Scalar,Dynamic,1> InputType;\n  typedef Matrix<Scalar,Dynamic,1> ValueType;\n  typedef SparseMatrix<Scalar, ColMajor, Index> JacobianType;\n  typedef SparseQR<JacobianType, COLAMDOrdering<int> > QRSolver;\n  enum {\n    InputsAtCompileTime = Dynamic,\n    ValuesAtCompileTime = Dynamic\n  };\n  \n  SparseFunctor(int inputs, int values) : m_inputs(inputs), m_values(values) {}\n\n  int inputs() const { return m_inputs; }\n  int values() const { return m_values; }\n  \n  const int m_inputs, m_values;\n  //int operator()(const InputType &x, ValueType& fvec) { }\n  // to be defined in the functor\n  \n  //int df(const InputType &x, JacobianType& fjac) { }\n  // to be defined in the functor if no automatic differentiation\n  \n};\nnamespace internal {\ntemplate <typename QRSolver, typename VectorType>\nvoid lmpar2(const QRSolver &qr, const VectorType  &diag, const VectorType  &qtb,\n\t    typename VectorType::Scalar m_delta, typename VectorType::Scalar &par,\n\t    VectorType  &x);\n    }\n/**\n  * \\ingroup NonLinearOptimization_Module\n  * \\brief Performs non linear optimization over a non-linear function,\n  * using a variant of the Levenberg Marquardt algorithm.\n  *\n  * Check wikipedia for more information.\n  * http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm\n  */\ntemplate<typename _FunctorType>\nclass LevenbergMarquardt : internal::no_assignment_operator\n{\n  public:\n    typedef _FunctorType FunctorType;\n    typedef typename FunctorType::QRSolver QRSolver;\n    typedef typename FunctorType::JacobianType JacobianType;\n    typedef typename JacobianType::Scalar Scalar;\n    typedef typename JacobianType::RealScalar RealScalar; \n    typedef typename QRSolver::StorageIndex PermIndex;\n    typedef Matrix<Scalar,Dynamic,1> FVectorType;\n    typedef PermutationMatrix<Dynamic,Dynamic,int> PermutationType;\n  public:\n    LevenbergMarquardt(FunctorType& functor) \n    : m_functor(functor),m_nfev(0),m_njev(0),m_fnorm(0.0),m_gnorm(0),\n      m_isInitialized(false),m_info(InvalidInput)\n    {\n      resetParameters();\n      m_useExternalScaling=false; \n    }\n    \n    LevenbergMarquardtSpace::Status minimize(FVectorType &x);\n    LevenbergMarquardtSpace::Status minimizeInit(FVectorType &x);\n    LevenbergMarquardtSpace::Status minimizeOneStep(FVectorType &x);\n    LevenbergMarquardtSpace::Status lmder1(\n      FVectorType  &x, \n      const Scalar tol = std::sqrt(NumTraits<Scalar>::epsilon())\n    );\n    static LevenbergMarquardtSpace::Status lmdif1(\n            FunctorType &functor,\n            FVectorType  &x,\n            Index *nfev,\n            const Scalar tol = std::sqrt(NumTraits<Scalar>::epsilon())\n            );\n    \n    /** Sets the default parameters */\n    void resetParameters() \n    {\n      using std::sqrt;        \n\n      m_factor = 100.; \n      m_maxfev = 400; \n      m_ftol = sqrt(NumTraits<RealScalar>::epsilon());\n      m_xtol = sqrt(NumTraits<RealScalar>::epsilon());\n      m_gtol = 0. ; \n      m_epsfcn = 0. ;\n    }\n    \n    /** Sets the tolerance for the norm of the solution vector*/\n    void setXtol(RealScalar xtol) { m_xtol = xtol; }\n    \n    /** Sets the tolerance for the norm of the vector function*/\n    void setFtol(RealScalar ftol) { m_ftol = ftol; }\n    \n    /** Sets the tolerance for the norm of the gradient of the error vector*/\n    void setGtol(RealScalar gtol) { m_gtol = gtol; }\n    \n    /** Sets the step bound for the diagonal shift */\n    void setFactor(RealScalar factor) { m_factor = factor; }    \n    \n    /** Sets the error precision  */\n    void setEpsilon (RealScalar epsfcn) { m_epsfcn = epsfcn; }\n    \n    /** Sets the maximum number of function evaluation */\n    void setMaxfev(Index maxfev) {m_maxfev = maxfev; }\n    \n    /** Use an external Scaling. If set to true, pass a nonzero diagonal to diag() */\n    void setExternalScaling(bool value) {m_useExternalScaling  = value; }\n    \n    /** \\returns the tolerance for the norm of the solution vector */\n    RealScalar xtol() const {return m_xtol; }\n    \n    /** \\returns the tolerance for the norm of the vector function */\n    RealScalar ftol() const {return m_ftol; }\n    \n    /** \\returns the tolerance for the norm of the gradient of the error vector */\n    RealScalar gtol() const {return m_gtol; }\n    \n    /** \\returns the step bound for the diagonal shift */\n    RealScalar factor() const {return m_factor; }\n    \n    /** \\returns the error precision */\n    RealScalar epsilon() const {return m_epsfcn; }\n    \n    /** \\returns the maximum number of function evaluation */\n    Index maxfev() const {return m_maxfev; }\n    \n    /** \\returns a reference to the diagonal of the jacobian */\n    FVectorType& diag() {return m_diag; }\n    \n    /** \\returns the number of iterations performed */\n    Index iterations() { return m_iter; }\n    \n    /** \\returns the number of functions evaluation */\n    Index nfev() { return m_nfev; }\n    \n    /** \\returns the number of jacobian evaluation */\n    Index njev() { return m_njev; }\n    \n    /** \\returns the norm of current vector function */\n    RealScalar fnorm() {return m_fnorm; }\n    \n    /** \\returns the norm of the gradient of the error */\n    RealScalar gnorm() {return m_gnorm; }\n    \n    /** \\returns the LevenbergMarquardt parameter */\n    RealScalar lm_param(void) { return m_par; }\n    \n    /** \\returns a reference to the  current vector function \n     */\n    FVectorType& fvec() {return m_fvec; }\n    \n    /** \\returns a reference to the matrix where the current Jacobian matrix is stored\n     */\n    JacobianType& jacobian() {return m_fjac; }\n    \n    /** \\returns a reference to the triangular matrix R from the QR of the jacobian matrix.\n     * \\sa jacobian()\n     */\n    JacobianType& matrixR() {return m_rfactor; }\n    \n    /** the permutation used in the QR factorization\n     */\n    PermutationType permutation() {return m_permutation; }\n    \n    /** \n     * \\brief Reports whether the minimization was successful\n     * \\returns \\c Success if the minimization was successful,\n     *         \\c NumericalIssue if a numerical problem arises during the \n     *          minimization process, for example during the QR factorization\n     *         \\c NoConvergence if the minimization did not converge after \n     *          the maximum number of function evaluation allowed\n     *          \\c InvalidInput if the input matrix is invalid\n     */\n    ComputationInfo info() const\n    {\n      \n      return m_info;\n    }\n  private:\n    JacobianType m_fjac; \n    JacobianType m_rfactor; // The triangular matrix R from the QR of the jacobian matrix m_fjac\n    FunctorType &m_functor;\n    FVectorType m_fvec, m_qtf, m_diag; \n    Index n;\n    Index m; \n    Index m_nfev;\n    Index m_njev; \n    RealScalar m_fnorm; // Norm of the current vector function\n    RealScalar m_gnorm; //Norm of the gradient of the error \n    RealScalar m_factor; //\n    Index m_maxfev; // Maximum number of function evaluation\n    RealScalar m_ftol; //Tolerance in the norm of the vector function\n    RealScalar m_xtol; // \n    RealScalar m_gtol; //tolerance of the norm of the error gradient\n    RealScalar m_epsfcn; //\n    Index m_iter; // Number of iterations performed\n    RealScalar m_delta;\n    bool m_useExternalScaling;\n    PermutationType m_permutation;\n    FVectorType m_wa1, m_wa2, m_wa3, m_wa4; //Temporary vectors\n    RealScalar m_par;\n    bool m_isInitialized; // Check whether the minimization step has been called\n    ComputationInfo m_info; \n};\n\ntemplate<typename FunctorType>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType>::minimize(FVectorType  &x)\n{\n    LevenbergMarquardtSpace::Status status = minimizeInit(x);\n    if (status==LevenbergMarquardtSpace::ImproperInputParameters) {\n      m_isInitialized = true;\n      return status;\n    }\n    do {\n//       std::cout << \" uv \" << x.transpose() << \"\\n\";\n        status = minimizeOneStep(x);\n    } while (status==LevenbergMarquardtSpace::Running);\n     m_isInitialized = true;\n     return status;\n}\n\ntemplate<typename FunctorType>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType>::minimizeInit(FVectorType  &x)\n{\n    n = x.size();\n    m = m_functor.values();\n\n    m_wa1.resize(n); m_wa2.resize(n); m_wa3.resize(n);\n    m_wa4.resize(m);\n    m_fvec.resize(m);\n    //FIXME Sparse Case : Allocate space for the jacobian\n    m_fjac.resize(m, n);\n//     m_fjac.reserve(VectorXi::Constant(n,5)); // FIXME Find a better alternative\n    if (!m_useExternalScaling)\n        m_diag.resize(n);\n    eigen_assert( (!m_useExternalScaling || m_diag.size()==n) && \"When m_useExternalScaling is set, the caller must provide a valid 'm_diag'\");\n    m_qtf.resize(n);\n\n    /* Function Body */\n    m_nfev = 0;\n    m_njev = 0;\n\n    /*     check the input parameters for errors. */\n    if (n <= 0 || m < n || m_ftol < 0. || m_xtol < 0. || m_gtol < 0. || m_maxfev <= 0 || m_factor <= 0.){\n      m_info = InvalidInput;\n      return LevenbergMarquardtSpace::ImproperInputParameters;\n    }\n\n    if (m_useExternalScaling)\n        for (Index j = 0; j < n; ++j)\n            if (m_diag[j] <= 0.) \n            {\n              m_info = InvalidInput;\n              return LevenbergMarquardtSpace::ImproperInputParameters;\n            }\n\n    /*     evaluate the function at the starting point */\n    /*     and calculate its norm. */\n    m_nfev = 1;\n    if ( m_functor(x, m_fvec) < 0)\n        return LevenbergMarquardtSpace::UserAsked;\n    m_fnorm = m_fvec.stableNorm();\n\n    /*     initialize levenberg-marquardt parameter and iteration counter. */\n    m_par = 0.;\n    m_iter = 1;\n\n    return LevenbergMarquardtSpace::NotStarted;\n}\n\ntemplate<typename FunctorType>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType>::lmder1(\n        FVectorType  &x,\n        const Scalar tol\n        )\n{\n    n = x.size();\n    m = m_functor.values();\n\n    /* check the input parameters for errors. */\n    if (n <= 0 || m < n || tol < 0.)\n        return LevenbergMarquardtSpace::ImproperInputParameters;\n\n    resetParameters();\n    m_ftol = tol;\n    m_xtol = tol;\n    m_maxfev = 100*(n+1);\n\n    return minimize(x);\n}\n\n\ntemplate<typename FunctorType>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType>::lmdif1(\n        FunctorType &functor,\n        FVectorType  &x,\n        Index *nfev,\n        const Scalar tol\n        )\n{\n    Index n = x.size();\n    Index m = functor.values();\n\n    /* check the input parameters for errors. */\n    if (n <= 0 || m < n || tol < 0.)\n        return LevenbergMarquardtSpace::ImproperInputParameters;\n\n    NumericalDiff<FunctorType> numDiff(functor);\n    // embedded LevenbergMarquardt\n    LevenbergMarquardt<NumericalDiff<FunctorType> > lm(numDiff);\n    lm.setFtol(tol);\n    lm.setXtol(tol);\n    lm.setMaxfev(200*(n+1));\n\n    LevenbergMarquardtSpace::Status info = LevenbergMarquardtSpace::Status(lm.minimize(x));\n    if (nfev)\n        * nfev = lm.nfev();\n    return info;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_LEVENBERGMARQUARDT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/MatrixFunctions/MatrixExponential.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009, 2010, 2013 Jitse Niesen <jitse@maths.leeds.ac.uk>\n// Copyright (C) 2011, 2013 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MATRIX_EXPONENTIAL\n#define EIGEN_MATRIX_EXPONENTIAL\n\n#include \"StemFunction.h\"\n\nnamespace Eigen {\nnamespace internal {\n\n/** \\brief Scaling operator.\n *\n * This struct is used by CwiseUnaryOp to scale a matrix by \\f$ 2^{-s} \\f$.\n */\ntemplate <typename RealScalar>\nstruct MatrixExponentialScalingOp\n{\n  /** \\brief Constructor.\n   *\n   * \\param[in] squarings  The integer \\f$ s \\f$ in this document.\n   */\n  MatrixExponentialScalingOp(int squarings) : m_squarings(squarings) { }\n\n\n  /** \\brief Scale a matrix coefficient.\n   *\n   * \\param[in,out] x  The scalar to be scaled, becoming \\f$ 2^{-s} x \\f$.\n   */\n  inline const RealScalar operator() (const RealScalar& x) const\n  {\n    using std::ldexp;\n    return ldexp(x, -m_squarings);\n  }\n\n  typedef std::complex<RealScalar> ComplexScalar;\n\n  /** \\brief Scale a matrix coefficient.\n   *\n   * \\param[in,out] x  The scalar to be scaled, becoming \\f$ 2^{-s} x \\f$.\n   */\n  inline const ComplexScalar operator() (const ComplexScalar& x) const\n  {\n    using std::ldexp;\n    return ComplexScalar(ldexp(x.real(), -m_squarings), ldexp(x.imag(), -m_squarings));\n  }\n\n  private:\n    int m_squarings;\n};\n\n/** \\brief Compute the (3,3)-Pad&eacute; approximant to the exponential.\n *\n *  After exit, \\f$ (V+U)(V-U)^{-1} \\f$ is the Pad&eacute;\n *  approximant of \\f$ \\exp(A) \\f$ around \\f$ A = 0 \\f$.\n */\ntemplate <typename MatA, typename MatU, typename MatV>\nvoid matrix_exp_pade3(const MatA& A, MatU& U, MatV& V)\n{\n  typedef typename MatA::PlainObject MatrixType;\n  typedef typename NumTraits<typename traits<MatA>::Scalar>::Real RealScalar;\n  const RealScalar b[] = {120.L, 60.L, 12.L, 1.L};\n  const MatrixType A2 = A * A;\n  const MatrixType tmp = b[3] * A2 + b[1] * MatrixType::Identity(A.rows(), A.cols());\n  U.noalias() = A * tmp;\n  V = b[2] * A2 + b[0] * MatrixType::Identity(A.rows(), A.cols());\n}\n\n/** \\brief Compute the (5,5)-Pad&eacute; approximant to the exponential.\n *\n *  After exit, \\f$ (V+U)(V-U)^{-1} \\f$ is the Pad&eacute;\n *  approximant of \\f$ \\exp(A) \\f$ around \\f$ A = 0 \\f$.\n */\ntemplate <typename MatA, typename MatU, typename MatV>\nvoid matrix_exp_pade5(const MatA& A, MatU& U, MatV& V)\n{\n  typedef typename MatA::PlainObject MatrixType;\n  typedef typename NumTraits<typename traits<MatrixType>::Scalar>::Real RealScalar;\n  const RealScalar b[] = {30240.L, 15120.L, 3360.L, 420.L, 30.L, 1.L};\n  const MatrixType A2 = A * A;\n  const MatrixType A4 = A2 * A2;\n  const MatrixType tmp = b[5] * A4 + b[3] * A2 + b[1] * MatrixType::Identity(A.rows(), A.cols());\n  U.noalias() = A * tmp;\n  V = b[4] * A4 + b[2] * A2 + b[0] * MatrixType::Identity(A.rows(), A.cols());\n}\n\n/** \\brief Compute the (7,7)-Pad&eacute; approximant to the exponential.\n *\n *  After exit, \\f$ (V+U)(V-U)^{-1} \\f$ is the Pad&eacute;\n *  approximant of \\f$ \\exp(A) \\f$ around \\f$ A = 0 \\f$.\n */\ntemplate <typename MatA, typename MatU, typename MatV>\nvoid matrix_exp_pade7(const MatA& A, MatU& U, MatV& V)\n{\n  typedef typename MatA::PlainObject MatrixType;\n  typedef typename NumTraits<typename traits<MatrixType>::Scalar>::Real RealScalar;\n  const RealScalar b[] = {17297280.L, 8648640.L, 1995840.L, 277200.L, 25200.L, 1512.L, 56.L, 1.L};\n  const MatrixType A2 = A * A;\n  const MatrixType A4 = A2 * A2;\n  const MatrixType A6 = A4 * A2;\n  const MatrixType tmp = b[7] * A6 + b[5] * A4 + b[3] * A2 \n    + b[1] * MatrixType::Identity(A.rows(), A.cols());\n  U.noalias() = A * tmp;\n  V = b[6] * A6 + b[4] * A4 + b[2] * A2 + b[0] * MatrixType::Identity(A.rows(), A.cols());\n\n}\n\n/** \\brief Compute the (9,9)-Pad&eacute; approximant to the exponential.\n *\n *  After exit, \\f$ (V+U)(V-U)^{-1} \\f$ is the Pad&eacute;\n *  approximant of \\f$ \\exp(A) \\f$ around \\f$ A = 0 \\f$.\n */\ntemplate <typename MatA, typename MatU, typename MatV>\nvoid matrix_exp_pade9(const MatA& A, MatU& U, MatV& V)\n{\n  typedef typename MatA::PlainObject MatrixType;\n  typedef typename NumTraits<typename traits<MatrixType>::Scalar>::Real RealScalar;\n  const RealScalar b[] = {17643225600.L, 8821612800.L, 2075673600.L, 302702400.L, 30270240.L,\n                          2162160.L, 110880.L, 3960.L, 90.L, 1.L};\n  const MatrixType A2 = A * A;\n  const MatrixType A4 = A2 * A2;\n  const MatrixType A6 = A4 * A2;\n  const MatrixType A8 = A6 * A2;\n  const MatrixType tmp = b[9] * A8 + b[7] * A6 + b[5] * A4 + b[3] * A2 \n    + b[1] * MatrixType::Identity(A.rows(), A.cols());\n  U.noalias() = A * tmp;\n  V = b[8] * A8 + b[6] * A6 + b[4] * A4 + b[2] * A2 + b[0] * MatrixType::Identity(A.rows(), A.cols());\n}\n\n/** \\brief Compute the (13,13)-Pad&eacute; approximant to the exponential.\n *\n *  After exit, \\f$ (V+U)(V-U)^{-1} \\f$ is the Pad&eacute;\n *  approximant of \\f$ \\exp(A) \\f$ around \\f$ A = 0 \\f$.\n */\ntemplate <typename MatA, typename MatU, typename MatV>\nvoid matrix_exp_pade13(const MatA& A, MatU& U, MatV& V)\n{\n  typedef typename MatA::PlainObject MatrixType;\n  typedef typename NumTraits<typename traits<MatrixType>::Scalar>::Real RealScalar;\n  const RealScalar b[] = {64764752532480000.L, 32382376266240000.L, 7771770303897600.L,\n                          1187353796428800.L, 129060195264000.L, 10559470521600.L, 670442572800.L,\n                          33522128640.L, 1323241920.L, 40840800.L, 960960.L, 16380.L, 182.L, 1.L};\n  const MatrixType A2 = A * A;\n  const MatrixType A4 = A2 * A2;\n  const MatrixType A6 = A4 * A2;\n  V = b[13] * A6 + b[11] * A4 + b[9] * A2; // used for temporary storage\n  MatrixType tmp = A6 * V;\n  tmp += b[7] * A6 + b[5] * A4 + b[3] * A2 + b[1] * MatrixType::Identity(A.rows(), A.cols());\n  U.noalias() = A * tmp;\n  tmp = b[12] * A6 + b[10] * A4 + b[8] * A2;\n  V.noalias() = A6 * tmp;\n  V += b[6] * A6 + b[4] * A4 + b[2] * A2 + b[0] * MatrixType::Identity(A.rows(), A.cols());\n}\n\n/** \\brief Compute the (17,17)-Pad&eacute; approximant to the exponential.\n *\n *  After exit, \\f$ (V+U)(V-U)^{-1} \\f$ is the Pad&eacute;\n *  approximant of \\f$ \\exp(A) \\f$ around \\f$ A = 0 \\f$.\n *\n *  This function activates only if your long double is double-double or quadruple.\n */\n#if LDBL_MANT_DIG > 64\ntemplate <typename MatA, typename MatU, typename MatV>\nvoid matrix_exp_pade17(const MatA& A, MatU& U, MatV& V)\n{\n  typedef typename MatA::PlainObject MatrixType;\n  typedef typename NumTraits<typename traits<MatrixType>::Scalar>::Real RealScalar;\n  const RealScalar b[] = {830034394580628357120000.L, 415017197290314178560000.L,\n                          100610229646136770560000.L, 15720348382208870400000.L,\n                          1774878043152614400000.L, 153822763739893248000.L, 10608466464820224000.L,\n                          595373117923584000.L, 27563570274240000.L, 1060137318240000.L,\n                          33924394183680.L, 899510451840.L, 19554575040.L, 341863200.L, 4651200.L,\n                          46512.L, 306.L, 1.L};\n  const MatrixType A2 = A * A;\n  const MatrixType A4 = A2 * A2;\n  const MatrixType A6 = A4 * A2;\n  const MatrixType A8 = A4 * A4;\n  V = b[17] * A8 + b[15] * A6 + b[13] * A4 + b[11] * A2; // used for temporary storage\n  MatrixType tmp = A8 * V;\n  tmp += b[9] * A8 + b[7] * A6 + b[5] * A4 + b[3] * A2 \n    + b[1] * MatrixType::Identity(A.rows(), A.cols());\n  U.noalias() = A * tmp;\n  tmp = b[16] * A8 + b[14] * A6 + b[12] * A4 + b[10] * A2;\n  V.noalias() = tmp * A8;\n  V += b[8] * A8 + b[6] * A6 + b[4] * A4 + b[2] * A2 \n    + b[0] * MatrixType::Identity(A.rows(), A.cols());\n}\n#endif\n\ntemplate <typename MatrixType, typename RealScalar = typename NumTraits<typename traits<MatrixType>::Scalar>::Real>\nstruct matrix_exp_computeUV\n{\n  /** \\brief Compute Pad&eacute; approximant to the exponential.\n    *\n    * Computes \\c U, \\c V and \\c squarings such that \\f$ (V+U)(V-U)^{-1} \\f$ is a Pad&eacute;\n    * approximant of \\f$ \\exp(2^{-\\mbox{squarings}}M) \\f$ around \\f$ M = 0 \\f$, where \\f$ M \\f$\n    * denotes the matrix \\c arg. The degree of the Pad&eacute; approximant and the value of squarings\n    * are chosen such that the approximation error is no more than the round-off error.\n    */\n  static void run(const MatrixType& arg, MatrixType& U, MatrixType& V, int& squarings);\n};\n\ntemplate <typename MatrixType>\nstruct matrix_exp_computeUV<MatrixType, float>\n{\n  template <typename ArgType>\n  static void run(const ArgType& arg, MatrixType& U, MatrixType& V, int& squarings)\n  {\n    using std::frexp;\n    using std::pow;\n    const float l1norm = arg.cwiseAbs().colwise().sum().maxCoeff();\n    squarings = 0;\n    if (l1norm < 4.258730016922831e-001f) {\n      matrix_exp_pade3(arg, U, V);\n    } else if (l1norm < 1.880152677804762e+000f) {\n      matrix_exp_pade5(arg, U, V);\n    } else {\n      const float maxnorm = 3.925724783138660f;\n      frexp(l1norm / maxnorm, &squarings);\n      if (squarings < 0) squarings = 0;\n      MatrixType A = arg.unaryExpr(MatrixExponentialScalingOp<float>(squarings));\n      matrix_exp_pade7(A, U, V);\n    }\n  }\n};\n\ntemplate <typename MatrixType>\nstruct matrix_exp_computeUV<MatrixType, double>\n{\n  typedef typename NumTraits<typename traits<MatrixType>::Scalar>::Real RealScalar;\n  template <typename ArgType>\n  static void run(const ArgType& arg, MatrixType& U, MatrixType& V, int& squarings)\n  {\n    using std::frexp;\n    using std::pow;\n    const RealScalar l1norm = arg.cwiseAbs().colwise().sum().maxCoeff();\n    squarings = 0;\n    if (l1norm < 1.495585217958292e-002) {\n      matrix_exp_pade3(arg, U, V);\n    } else if (l1norm < 2.539398330063230e-001) {\n      matrix_exp_pade5(arg, U, V);\n    } else if (l1norm < 9.504178996162932e-001) {\n      matrix_exp_pade7(arg, U, V);\n    } else if (l1norm < 2.097847961257068e+000) {\n      matrix_exp_pade9(arg, U, V);\n    } else {\n      const RealScalar maxnorm = 5.371920351148152;\n      frexp(l1norm / maxnorm, &squarings);\n      if (squarings < 0) squarings = 0;\n      MatrixType A = arg.unaryExpr(MatrixExponentialScalingOp<RealScalar>(squarings));\n      matrix_exp_pade13(A, U, V);\n    }\n  }\n};\n  \ntemplate <typename MatrixType>\nstruct matrix_exp_computeUV<MatrixType, long double>\n{\n  template <typename ArgType>\n  static void run(const ArgType& arg, MatrixType& U, MatrixType& V, int& squarings)\n  {\n#if   LDBL_MANT_DIG == 53   // double precision\n    matrix_exp_computeUV<MatrixType, double>::run(arg, U, V, squarings);\n  \n#else\n  \n    using std::frexp;\n    using std::pow;\n    const long double l1norm = arg.cwiseAbs().colwise().sum().maxCoeff();\n    squarings = 0;\n  \n#if LDBL_MANT_DIG <= 64   // extended precision\n  \n    if (l1norm < 4.1968497232266989671e-003L) {\n      matrix_exp_pade3(arg, U, V);\n    } else if (l1norm < 1.1848116734693823091e-001L) {\n      matrix_exp_pade5(arg, U, V);\n    } else if (l1norm < 5.5170388480686700274e-001L) {\n      matrix_exp_pade7(arg, U, V);\n    } else if (l1norm < 1.3759868875587845383e+000L) {\n      matrix_exp_pade9(arg, U, V);\n    } else {\n      const long double maxnorm = 4.0246098906697353063L;\n      frexp(l1norm / maxnorm, &squarings);\n      if (squarings < 0) squarings = 0;\n      MatrixType A = arg.unaryExpr(MatrixExponentialScalingOp<long double>(squarings));\n      matrix_exp_pade13(A, U, V);\n    }\n  \n#elif LDBL_MANT_DIG <= 106  // double-double\n  \n    if (l1norm < 3.2787892205607026992947488108213e-005L) {\n      matrix_exp_pade3(arg, U, V);\n    } else if (l1norm < 6.4467025060072760084130906076332e-003L) {\n      matrix_exp_pade5(arg, U, V);\n    } else if (l1norm < 6.8988028496595374751374122881143e-002L) {\n      matrix_exp_pade7(arg, U, V);\n    } else if (l1norm < 2.7339737518502231741495857201670e-001L) {\n      matrix_exp_pade9(arg, U, V);\n    } else if (l1norm < 1.3203382096514474905666448850278e+000L) {\n      matrix_exp_pade13(arg, U, V);\n    } else {\n      const long double maxnorm = 3.2579440895405400856599663723517L;\n      frexp(l1norm / maxnorm, &squarings);\n      if (squarings < 0) squarings = 0;\n      MatrixType A = arg.unaryExpr(MatrixExponentialScalingOp<long double>(squarings));\n      matrix_exp_pade17(A, U, V);\n    }\n  \n#elif LDBL_MANT_DIG <= 113  // quadruple precision\n  \n    if (l1norm < 1.639394610288918690547467954466970e-005L) {\n      matrix_exp_pade3(arg, U, V);\n    } else if (l1norm < 4.253237712165275566025884344433009e-003L) {\n      matrix_exp_pade5(arg, U, V);\n    } else if (l1norm < 5.125804063165764409885122032933142e-002L) {\n      matrix_exp_pade7(arg, U, V);\n    } else if (l1norm < 2.170000765161155195453205651889853e-001L) {\n      matrix_exp_pade9(arg, U, V);\n    } else if (l1norm < 1.125358383453143065081397882891878e+000L) {\n      matrix_exp_pade13(arg, U, V);\n    } else {\n      const long double maxnorm = 2.884233277829519311757165057717815L;\n      frexp(l1norm / maxnorm, &squarings);\n      if (squarings < 0) squarings = 0;\n      MatrixType A = arg.unaryExpr(MatrixExponentialScalingOp<long double>(squarings));\n      matrix_exp_pade17(A, U, V);\n    }\n  \n#else\n  \n    // this case should be handled in compute()\n    eigen_assert(false && \"Bug in MatrixExponential\"); \n  \n#endif\n#endif  // LDBL_MANT_DIG\n  }\n};\n\ntemplate<typename T> struct is_exp_known_type : false_type {};\ntemplate<> struct is_exp_known_type<float> : true_type {};\ntemplate<> struct is_exp_known_type<double> : true_type {};\n#if LDBL_MANT_DIG <= 113\ntemplate<> struct is_exp_known_type<long double> : true_type {};\n#endif\n\ntemplate <typename ArgType, typename ResultType>\nvoid matrix_exp_compute(const ArgType& arg, ResultType &result, true_type) // natively supported scalar type\n{\n  typedef typename ArgType::PlainObject MatrixType;\n  MatrixType U, V;\n  int squarings;\n  matrix_exp_computeUV<MatrixType>::run(arg, U, V, squarings); // Pade approximant is (U+V) / (-U+V)\n  MatrixType numer = U + V;\n  MatrixType denom = -U + V;\n  result = denom.partialPivLu().solve(numer);\n  for (int i=0; i<squarings; i++)\n    result *= result;   // undo scaling by repeated squaring\n}\n\n\n/* Computes the matrix exponential\n *\n * \\param arg    argument of matrix exponential (should be plain object)\n * \\param result variable in which result will be stored\n */\ntemplate <typename ArgType, typename ResultType>\nvoid matrix_exp_compute(const ArgType& arg, ResultType &result, false_type) // default\n{\n  typedef typename ArgType::PlainObject MatrixType;\n  typedef typename traits<MatrixType>::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef typename std::complex<RealScalar> ComplexScalar;\n  result = arg.matrixFunction(internal::stem_function_exp<ComplexScalar>);\n}\n\n} // end namespace Eigen::internal\n\n/** \\ingroup MatrixFunctions_Module\n  *\n  * \\brief Proxy for the matrix exponential of some matrix (expression).\n  *\n  * \\tparam Derived  Type of the argument to the matrix exponential.\n  *\n  * This class holds the argument to the matrix exponential until it is assigned or evaluated for\n  * some other reason (so the argument should not be changed in the meantime). It is the return type\n  * of MatrixBase::exp() and most of the time this is the only way it is used.\n  */\ntemplate<typename Derived> struct MatrixExponentialReturnValue\n: public ReturnByValue<MatrixExponentialReturnValue<Derived> >\n{\n  public:\n    /** \\brief Constructor.\n      *\n      * \\param src %Matrix (expression) forming the argument of the matrix exponential.\n      */\n    MatrixExponentialReturnValue(const Derived& src) : m_src(src) { }\n\n    /** \\brief Compute the matrix exponential.\n      *\n      * \\param result the matrix exponential of \\p src in the constructor.\n      */\n    template <typename ResultType>\n    inline void evalTo(ResultType& result) const\n    {\n      const typename internal::nested_eval<Derived, 10>::type tmp(m_src);\n      internal::matrix_exp_compute(tmp, result, internal::is_exp_known_type<typename Derived::RealScalar>());\n    }\n\n    Index rows() const { return m_src.rows(); }\n    Index cols() const { return m_src.cols(); }\n\n  protected:\n    const typename internal::ref_selector<Derived>::type m_src;\n};\n\nnamespace internal {\ntemplate<typename Derived>\nstruct traits<MatrixExponentialReturnValue<Derived> >\n{\n  typedef typename Derived::PlainObject ReturnType;\n};\n}\n\ntemplate <typename Derived>\nconst MatrixExponentialReturnValue<Derived> MatrixBase<Derived>::exp() const\n{\n  eigen_assert(rows() == cols());\n  return MatrixExponentialReturnValue<Derived>(derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_MATRIX_EXPONENTIAL\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/MatrixFunctions/MatrixFunction.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2011, 2013 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MATRIX_FUNCTION_H\n#define EIGEN_MATRIX_FUNCTION_H\n\n#include \"StemFunction.h\"\n\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\brief Maximum distance allowed between eigenvalues to be considered \"close\". */\nstatic const float matrix_function_separation = 0.1f;\n\n/** \\ingroup MatrixFunctions_Module\n  * \\class MatrixFunctionAtomic\n  * \\brief Helper class for computing matrix functions of atomic matrices.\n  *\n  * Here, an atomic matrix is a triangular matrix whose diagonal entries are close to each other.\n  */\ntemplate <typename MatrixType>\nclass MatrixFunctionAtomic \n{\n  public:\n\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename stem_function<Scalar>::type StemFunction;\n\n    /** \\brief Constructor\n      * \\param[in]  f  matrix function to compute.\n      */\n    MatrixFunctionAtomic(StemFunction f) : m_f(f) { }\n\n    /** \\brief Compute matrix function of atomic matrix\n      * \\param[in]  A  argument of matrix function, should be upper triangular and atomic\n      * \\returns  f(A), the matrix function evaluated at the given matrix\n      */\n    MatrixType compute(const MatrixType& A);\n\n  private:\n    StemFunction* m_f;\n};\n\ntemplate <typename MatrixType>\ntypename NumTraits<typename MatrixType::Scalar>::Real matrix_function_compute_mu(const MatrixType& A)\n{\n  typedef typename plain_col_type<MatrixType>::type VectorType;\n  Index rows = A.rows();\n  const MatrixType N = MatrixType::Identity(rows, rows) - A;\n  VectorType e = VectorType::Ones(rows);\n  N.template triangularView<Upper>().solveInPlace(e);\n  return e.cwiseAbs().maxCoeff();\n}\n\ntemplate <typename MatrixType>\nMatrixType MatrixFunctionAtomic<MatrixType>::compute(const MatrixType& A)\n{\n  // TODO: Use that A is upper triangular\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  Index rows = A.rows();\n  Scalar avgEival = A.trace() / Scalar(RealScalar(rows));\n  MatrixType Ashifted = A - avgEival * MatrixType::Identity(rows, rows);\n  RealScalar mu = matrix_function_compute_mu(Ashifted);\n  MatrixType F = m_f(avgEival, 0) * MatrixType::Identity(rows, rows);\n  MatrixType P = Ashifted;\n  MatrixType Fincr;\n  for (Index s = 1; double(s) < 1.1 * double(rows) + 10.0; s++) { // upper limit is fairly arbitrary\n    Fincr = m_f(avgEival, static_cast<int>(s)) * P;\n    F += Fincr;\n    P = Scalar(RealScalar(1)/RealScalar(s + 1)) * P * Ashifted;\n\n    // test whether Taylor series converged\n    const RealScalar F_norm = F.cwiseAbs().rowwise().sum().maxCoeff();\n    const RealScalar Fincr_norm = Fincr.cwiseAbs().rowwise().sum().maxCoeff();\n    if (Fincr_norm < NumTraits<Scalar>::epsilon() * F_norm) {\n      RealScalar delta = 0;\n      RealScalar rfactorial = 1;\n      for (Index r = 0; r < rows; r++) {\n        RealScalar mx = 0;\n        for (Index i = 0; i < rows; i++)\n          mx = (std::max)(mx, std::abs(m_f(Ashifted(i, i) + avgEival, static_cast<int>(s+r))));\n        if (r != 0)\n          rfactorial *= RealScalar(r);\n        delta = (std::max)(delta, mx / rfactorial);\n      }\n      const RealScalar P_norm = P.cwiseAbs().rowwise().sum().maxCoeff();\n      if (mu * delta * P_norm < NumTraits<Scalar>::epsilon() * F_norm) // series converged\n        break;\n    }\n  }\n  return F;\n}\n\n/** \\brief Find cluster in \\p clusters containing some value \n  * \\param[in] key Value to find\n  * \\returns Iterator to cluster containing \\p key, or \\c clusters.end() if no cluster in \\p m_clusters\n  * contains \\p key.\n  */\ntemplate <typename Index, typename ListOfClusters>\ntypename ListOfClusters::iterator matrix_function_find_cluster(Index key, ListOfClusters& clusters)\n{\n  typename std::list<Index>::iterator j;\n  for (typename ListOfClusters::iterator i = clusters.begin(); i != clusters.end(); ++i) {\n    j = std::find(i->begin(), i->end(), key);\n    if (j != i->end())\n      return i;\n  }\n  return clusters.end();\n}\n\n/** \\brief Partition eigenvalues in clusters of ei'vals close to each other\n  * \n  * \\param[in]  eivals    Eigenvalues\n  * \\param[out] clusters  Resulting partition of eigenvalues\n  *\n  * The partition satisfies the following two properties:\n  * # Any eigenvalue in a certain cluster is at most matrix_function_separation() away from another eigenvalue\n  *   in the same cluster.\n  * # The distance between two eigenvalues in different clusters is more than matrix_function_separation().  \n  * The implementation follows Algorithm 4.1 in the paper of Davies and Higham.\n  */\ntemplate <typename EivalsType, typename Cluster>\nvoid matrix_function_partition_eigenvalues(const EivalsType& eivals, std::list<Cluster>& clusters)\n{\n  typedef typename EivalsType::RealScalar RealScalar;\n  for (Index i=0; i<eivals.rows(); ++i) {\n    // Find cluster containing i-th ei'val, adding a new cluster if necessary\n    typename std::list<Cluster>::iterator qi = matrix_function_find_cluster(i, clusters);\n    if (qi == clusters.end()) {\n      Cluster l;\n      l.push_back(i);\n      clusters.push_back(l);\n      qi = clusters.end();\n      --qi;\n    }\n\n    // Look for other element to add to the set\n    for (Index j=i+1; j<eivals.rows(); ++j) {\n      if (abs(eivals(j) - eivals(i)) <= RealScalar(matrix_function_separation)\n          && std::find(qi->begin(), qi->end(), j) == qi->end()) {\n        typename std::list<Cluster>::iterator qj = matrix_function_find_cluster(j, clusters);\n        if (qj == clusters.end()) {\n          qi->push_back(j);\n        } else {\n          qi->insert(qi->end(), qj->begin(), qj->end());\n          clusters.erase(qj);\n        }\n      }\n    }\n  }\n}\n\n/** \\brief Compute size of each cluster given a partitioning */\ntemplate <typename ListOfClusters, typename Index>\nvoid matrix_function_compute_cluster_size(const ListOfClusters& clusters, Matrix<Index, Dynamic, 1>& clusterSize)\n{\n  const Index numClusters = static_cast<Index>(clusters.size());\n  clusterSize.setZero(numClusters);\n  Index clusterIndex = 0;\n  for (typename ListOfClusters::const_iterator cluster = clusters.begin(); cluster != clusters.end(); ++cluster) {\n    clusterSize[clusterIndex] = cluster->size();\n    ++clusterIndex;\n  }\n}\n\n/** \\brief Compute start of each block using clusterSize */\ntemplate <typename VectorType>\nvoid matrix_function_compute_block_start(const VectorType& clusterSize, VectorType& blockStart)\n{\n  blockStart.resize(clusterSize.rows());\n  blockStart(0) = 0;\n  for (Index i = 1; i < clusterSize.rows(); i++) {\n    blockStart(i) = blockStart(i-1) + clusterSize(i-1);\n  }\n}\n\n/** \\brief Compute mapping of eigenvalue indices to cluster indices */\ntemplate <typename EivalsType, typename ListOfClusters, typename VectorType>\nvoid matrix_function_compute_map(const EivalsType& eivals, const ListOfClusters& clusters, VectorType& eivalToCluster)\n{\n  eivalToCluster.resize(eivals.rows());\n  Index clusterIndex = 0;\n  for (typename ListOfClusters::const_iterator cluster = clusters.begin(); cluster != clusters.end(); ++cluster) {\n    for (Index i = 0; i < eivals.rows(); ++i) {\n      if (std::find(cluster->begin(), cluster->end(), i) != cluster->end()) {\n        eivalToCluster[i] = clusterIndex;\n      }\n    }\n    ++clusterIndex;\n  }\n}\n\n/** \\brief Compute permutation which groups ei'vals in same cluster together */\ntemplate <typename DynVectorType, typename VectorType>\nvoid matrix_function_compute_permutation(const DynVectorType& blockStart, const DynVectorType& eivalToCluster, VectorType& permutation)\n{\n  DynVectorType indexNextEntry = blockStart;\n  permutation.resize(eivalToCluster.rows());\n  for (Index i = 0; i < eivalToCluster.rows(); i++) {\n    Index cluster = eivalToCluster[i];\n    permutation[i] = indexNextEntry[cluster];\n    ++indexNextEntry[cluster];\n  }\n}  \n\n/** \\brief Permute Schur decomposition in U and T according to permutation */\ntemplate <typename VectorType, typename MatrixType>\nvoid matrix_function_permute_schur(VectorType& permutation, MatrixType& U, MatrixType& T)\n{\n  for (Index i = 0; i < permutation.rows() - 1; i++) {\n    Index j;\n    for (j = i; j < permutation.rows(); j++) {\n      if (permutation(j) == i) break;\n    }\n    eigen_assert(permutation(j) == i);\n    for (Index k = j-1; k >= i; k--) {\n      JacobiRotation<typename MatrixType::Scalar> rotation;\n      rotation.makeGivens(T(k, k+1), T(k+1, k+1) - T(k, k));\n      T.applyOnTheLeft(k, k+1, rotation.adjoint());\n      T.applyOnTheRight(k, k+1, rotation);\n      U.applyOnTheRight(k, k+1, rotation);\n      std::swap(permutation.coeffRef(k), permutation.coeffRef(k+1));\n    }\n  }\n}\n\n/** \\brief Compute block diagonal part of matrix function.\n  *\n  * This routine computes the matrix function applied to the block diagonal part of \\p T (which should be\n  * upper triangular), with the blocking given by \\p blockStart and \\p clusterSize. The matrix function of\n  * each diagonal block is computed by \\p atomic. The off-diagonal parts of \\p fT are set to zero.\n  */\ntemplate <typename MatrixType, typename AtomicType, typename VectorType>\nvoid matrix_function_compute_block_atomic(const MatrixType& T, AtomicType& atomic, const VectorType& blockStart, const VectorType& clusterSize, MatrixType& fT)\n{ \n  fT.setZero(T.rows(), T.cols());\n  for (Index i = 0; i < clusterSize.rows(); ++i) {\n    fT.block(blockStart(i), blockStart(i), clusterSize(i), clusterSize(i))\n      = atomic.compute(T.block(blockStart(i), blockStart(i), clusterSize(i), clusterSize(i)));\n  }\n}\n\n/** \\brief Solve a triangular Sylvester equation AX + XB = C \n  *\n  * \\param[in]  A  the matrix A; should be square and upper triangular\n  * \\param[in]  B  the matrix B; should be square and upper triangular\n  * \\param[in]  C  the matrix C; should have correct size.\n  *\n  * \\returns the solution X.\n  *\n  * If A is m-by-m and B is n-by-n, then both C and X are m-by-n.  The (i,j)-th component of the Sylvester\n  * equation is\n  * \\f[ \n  *     \\sum_{k=i}^m A_{ik} X_{kj} + \\sum_{k=1}^j X_{ik} B_{kj} = C_{ij}. \n  * \\f]\n  * This can be re-arranged to yield:\n  * \\f[ \n  *     X_{ij} = \\frac{1}{A_{ii} + B_{jj}} \\Bigl( C_{ij}\n  *     - \\sum_{k=i+1}^m A_{ik} X_{kj} - \\sum_{k=1}^{j-1} X_{ik} B_{kj} \\Bigr).\n  * \\f]\n  * It is assumed that A and B are such that the numerator is never zero (otherwise the Sylvester equation\n  * does not have a unique solution). In that case, these equations can be evaluated in the order \n  * \\f$ i=m,\\ldots,1 \\f$ and \\f$ j=1,\\ldots,n \\f$.\n  */\ntemplate <typename MatrixType>\nMatrixType matrix_function_solve_triangular_sylvester(const MatrixType& A, const MatrixType& B, const MatrixType& C)\n{\n  eigen_assert(A.rows() == A.cols());\n  eigen_assert(A.isUpperTriangular());\n  eigen_assert(B.rows() == B.cols());\n  eigen_assert(B.isUpperTriangular());\n  eigen_assert(C.rows() == A.rows());\n  eigen_assert(C.cols() == B.rows());\n\n  typedef typename MatrixType::Scalar Scalar;\n\n  Index m = A.rows();\n  Index n = B.rows();\n  MatrixType X(m, n);\n\n  for (Index i = m - 1; i >= 0; --i) {\n    for (Index j = 0; j < n; ++j) {\n\n      // Compute AX = \\sum_{k=i+1}^m A_{ik} X_{kj}\n      Scalar AX;\n      if (i == m - 1) {\n\tAX = 0; \n      } else {\n\tMatrix<Scalar,1,1> AXmatrix = A.row(i).tail(m-1-i) * X.col(j).tail(m-1-i);\n\tAX = AXmatrix(0,0);\n      }\n\n      // Compute XB = \\sum_{k=1}^{j-1} X_{ik} B_{kj}\n      Scalar XB;\n      if (j == 0) {\n\tXB = 0; \n      } else {\n\tMatrix<Scalar,1,1> XBmatrix = X.row(i).head(j) * B.col(j).head(j);\n\tXB = XBmatrix(0,0);\n      }\n\n      X(i,j) = (C(i,j) - AX - XB) / (A(i,i) + B(j,j));\n    }\n  }\n  return X;\n}\n\n/** \\brief Compute part of matrix function above block diagonal.\n  *\n  * This routine completes the computation of \\p fT, denoting a matrix function applied to the triangular\n  * matrix \\p T. It assumes that the block diagonal part of \\p fT has already been computed. The part below\n  * the diagonal is zero, because \\p T is upper triangular.\n  */\ntemplate <typename MatrixType, typename VectorType>\nvoid matrix_function_compute_above_diagonal(const MatrixType& T, const VectorType& blockStart, const VectorType& clusterSize, MatrixType& fT)\n{ \n  typedef internal::traits<MatrixType> Traits;\n  typedef typename MatrixType::Scalar Scalar;\n  static const int Options = MatrixType::Options;\n  typedef Matrix<Scalar, Dynamic, Dynamic, Options, Traits::RowsAtCompileTime, Traits::ColsAtCompileTime> DynMatrixType;\n\n  for (Index k = 1; k < clusterSize.rows(); k++) {\n    for (Index i = 0; i < clusterSize.rows() - k; i++) {\n      // compute (i, i+k) block\n      DynMatrixType A = T.block(blockStart(i), blockStart(i), clusterSize(i), clusterSize(i));\n      DynMatrixType B = -T.block(blockStart(i+k), blockStart(i+k), clusterSize(i+k), clusterSize(i+k));\n      DynMatrixType C = fT.block(blockStart(i), blockStart(i), clusterSize(i), clusterSize(i))\n        * T.block(blockStart(i), blockStart(i+k), clusterSize(i), clusterSize(i+k));\n      C -= T.block(blockStart(i), blockStart(i+k), clusterSize(i), clusterSize(i+k))\n        * fT.block(blockStart(i+k), blockStart(i+k), clusterSize(i+k), clusterSize(i+k));\n      for (Index m = i + 1; m < i + k; m++) {\n        C += fT.block(blockStart(i), blockStart(m), clusterSize(i), clusterSize(m))\n          * T.block(blockStart(m), blockStart(i+k), clusterSize(m), clusterSize(i+k));\n        C -= T.block(blockStart(i), blockStart(m), clusterSize(i), clusterSize(m))\n          * fT.block(blockStart(m), blockStart(i+k), clusterSize(m), clusterSize(i+k));\n      }\n      fT.block(blockStart(i), blockStart(i+k), clusterSize(i), clusterSize(i+k))\n        = matrix_function_solve_triangular_sylvester(A, B, C);\n    }\n  }\n}\n\n/** \\ingroup MatrixFunctions_Module\n  * \\brief Class for computing matrix functions.\n  * \\tparam  MatrixType  type of the argument of the matrix function,\n  *                      expected to be an instantiation of the Matrix class template.\n  * \\tparam  AtomicType  type for computing matrix function of atomic blocks.\n  * \\tparam  IsComplex   used internally to select correct specialization.\n  *\n  * This class implements the Schur-Parlett algorithm for computing matrix functions. The spectrum of the\n  * matrix is divided in clustered of eigenvalues that lies close together. This class delegates the\n  * computation of the matrix function on every block corresponding to these clusters to an object of type\n  * \\p AtomicType and uses these results to compute the matrix function of the whole matrix. The class\n  * \\p AtomicType should have a \\p compute() member function for computing the matrix function of a block.\n  *\n  * \\sa class MatrixFunctionAtomic, class MatrixLogarithmAtomic\n  */\ntemplate <typename MatrixType, int IsComplex = NumTraits<typename internal::traits<MatrixType>::Scalar>::IsComplex>\nstruct matrix_function_compute\n{  \n    /** \\brief Compute the matrix function.\n      *\n      * \\param[in]  A       argument of matrix function, should be a square matrix.\n      * \\param[in]  atomic  class for computing matrix function of atomic blocks.\n      * \\param[out] result  the function \\p f applied to \\p A, as\n      * specified in the constructor.\n      *\n      * See MatrixBase::matrixFunction() for details on how this computation\n      * is implemented.\n      */\n    template <typename AtomicType, typename ResultType> \n    static void run(const MatrixType& A, AtomicType& atomic, ResultType &result);    \n};\n\n/** \\internal \\ingroup MatrixFunctions_Module \n  * \\brief Partial specialization of MatrixFunction for real matrices\n  *\n  * This converts the real matrix to a complex matrix, compute the matrix function of that matrix, and then\n  * converts the result back to a real matrix.\n  */\ntemplate <typename MatrixType>\nstruct matrix_function_compute<MatrixType, 0>\n{  \n  template <typename MatA, typename AtomicType, typename ResultType>\n  static void run(const MatA& A, AtomicType& atomic, ResultType &result)\n  {\n    typedef internal::traits<MatrixType> Traits;\n    typedef typename Traits::Scalar Scalar;\n    static const int Rows = Traits::RowsAtCompileTime, Cols = Traits::ColsAtCompileTime;\n    static const int MaxRows = Traits::MaxRowsAtCompileTime, MaxCols = Traits::MaxColsAtCompileTime;\n\n    typedef std::complex<Scalar> ComplexScalar;\n    typedef Matrix<ComplexScalar, Rows, Cols, 0, MaxRows, MaxCols> ComplexMatrix;\n\n    ComplexMatrix CA = A.template cast<ComplexScalar>();\n    ComplexMatrix Cresult;\n    matrix_function_compute<ComplexMatrix>::run(CA, atomic, Cresult);\n    result = Cresult.real();\n  }\n};\n\n/** \\internal \\ingroup MatrixFunctions_Module \n  * \\brief Partial specialization of MatrixFunction for complex matrices\n  */\ntemplate <typename MatrixType>\nstruct matrix_function_compute<MatrixType, 1>\n{\n  template <typename MatA, typename AtomicType, typename ResultType>\n  static void run(const MatA& A, AtomicType& atomic, ResultType &result)\n  {\n    typedef internal::traits<MatrixType> Traits;\n    \n    // compute Schur decomposition of A\n    const ComplexSchur<MatrixType> schurOfA(A);\n    eigen_assert(schurOfA.info()==Success);\n    MatrixType T = schurOfA.matrixT();\n    MatrixType U = schurOfA.matrixU();\n\n    // partition eigenvalues into clusters of ei'vals \"close\" to each other\n    std::list<std::list<Index> > clusters; \n    matrix_function_partition_eigenvalues(T.diagonal(), clusters);\n\n    // compute size of each cluster\n    Matrix<Index, Dynamic, 1> clusterSize;\n    matrix_function_compute_cluster_size(clusters, clusterSize);\n\n    // blockStart[i] is row index at which block corresponding to i-th cluster starts \n    Matrix<Index, Dynamic, 1> blockStart; \n    matrix_function_compute_block_start(clusterSize, blockStart);\n\n    // compute map so that eivalToCluster[i] = j means that i-th ei'val is in j-th cluster \n    Matrix<Index, Dynamic, 1> eivalToCluster;\n    matrix_function_compute_map(T.diagonal(), clusters, eivalToCluster);\n\n    // compute permutation which groups ei'vals in same cluster together \n    Matrix<Index, Traits::RowsAtCompileTime, 1> permutation;\n    matrix_function_compute_permutation(blockStart, eivalToCluster, permutation);\n\n    // permute Schur decomposition\n    matrix_function_permute_schur(permutation, U, T);\n\n    // compute result\n    MatrixType fT; // matrix function applied to T\n    matrix_function_compute_block_atomic(T, atomic, blockStart, clusterSize, fT);\n    matrix_function_compute_above_diagonal(T, blockStart, clusterSize, fT);\n    result = U * (fT.template triangularView<Upper>() * U.adjoint());\n  }\n};\n\n} // end of namespace internal\n\n/** \\ingroup MatrixFunctions_Module\n  *\n  * \\brief Proxy for the matrix function of some matrix (expression).\n  *\n  * \\tparam Derived  Type of the argument to the matrix function.\n  *\n  * This class holds the argument to the matrix function until it is assigned or evaluated for some other\n  * reason (so the argument should not be changed in the meantime). It is the return type of\n  * matrixBase::matrixFunction() and related functions and most of the time this is the only way it is used.\n  */\ntemplate<typename Derived> class MatrixFunctionReturnValue\n: public ReturnByValue<MatrixFunctionReturnValue<Derived> >\n{\n  public:\n    typedef typename Derived::Scalar Scalar;\n    typedef typename internal::stem_function<Scalar>::type StemFunction;\n\n  protected:\n    typedef typename internal::ref_selector<Derived>::type DerivedNested;\n\n  public:\n\n    /** \\brief Constructor.\n      *\n      * \\param[in] A  %Matrix (expression) forming the argument of the matrix function.\n      * \\param[in] f  Stem function for matrix function under consideration.\n      */\n    MatrixFunctionReturnValue(const Derived& A, StemFunction f) : m_A(A), m_f(f) { }\n\n    /** \\brief Compute the matrix function.\n      *\n      * \\param[out] result \\p f applied to \\p A, where \\p f and \\p A are as in the constructor.\n      */\n    template <typename ResultType>\n    inline void evalTo(ResultType& result) const\n    {\n      typedef typename internal::nested_eval<Derived, 10>::type NestedEvalType;\n      typedef typename internal::remove_all<NestedEvalType>::type NestedEvalTypeClean;\n      typedef internal::traits<NestedEvalTypeClean> Traits;\n      typedef std::complex<typename NumTraits<Scalar>::Real> ComplexScalar;\n      typedef Matrix<ComplexScalar, Dynamic, Dynamic, 0, Traits::RowsAtCompileTime, Traits::ColsAtCompileTime> DynMatrixType;\n\n      typedef internal::MatrixFunctionAtomic<DynMatrixType> AtomicType;\n      AtomicType atomic(m_f);\n\n      internal::matrix_function_compute<typename NestedEvalTypeClean::PlainObject>::run(m_A, atomic, result);\n    }\n\n    Index rows() const { return m_A.rows(); }\n    Index cols() const { return m_A.cols(); }\n\n  private:\n    const DerivedNested m_A;\n    StemFunction *m_f;\n};\n\nnamespace internal {\ntemplate<typename Derived>\nstruct traits<MatrixFunctionReturnValue<Derived> >\n{\n  typedef typename Derived::PlainObject ReturnType;\n};\n}\n\n\n/********** MatrixBase methods **********/\n\n\ntemplate <typename Derived>\nconst MatrixFunctionReturnValue<Derived> MatrixBase<Derived>::matrixFunction(typename internal::stem_function<typename internal::traits<Derived>::Scalar>::type f) const\n{\n  eigen_assert(rows() == cols());\n  return MatrixFunctionReturnValue<Derived>(derived(), f);\n}\n\ntemplate <typename Derived>\nconst MatrixFunctionReturnValue<Derived> MatrixBase<Derived>::sin() const\n{\n  eigen_assert(rows() == cols());\n  typedef typename internal::stem_function<Scalar>::ComplexScalar ComplexScalar;\n  return MatrixFunctionReturnValue<Derived>(derived(), internal::stem_function_sin<ComplexScalar>);\n}\n\ntemplate <typename Derived>\nconst MatrixFunctionReturnValue<Derived> MatrixBase<Derived>::cos() const\n{\n  eigen_assert(rows() == cols());\n  typedef typename internal::stem_function<Scalar>::ComplexScalar ComplexScalar;\n  return MatrixFunctionReturnValue<Derived>(derived(), internal::stem_function_cos<ComplexScalar>);\n}\n\ntemplate <typename Derived>\nconst MatrixFunctionReturnValue<Derived> MatrixBase<Derived>::sinh() const\n{\n  eigen_assert(rows() == cols());\n  typedef typename internal::stem_function<Scalar>::ComplexScalar ComplexScalar;\n  return MatrixFunctionReturnValue<Derived>(derived(), internal::stem_function_sinh<ComplexScalar>);\n}\n\ntemplate <typename Derived>\nconst MatrixFunctionReturnValue<Derived> MatrixBase<Derived>::cosh() const\n{\n  eigen_assert(rows() == cols());\n  typedef typename internal::stem_function<Scalar>::ComplexScalar ComplexScalar;\n  return MatrixFunctionReturnValue<Derived>(derived(), internal::stem_function_cosh<ComplexScalar>);\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_MATRIX_FUNCTION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/MatrixFunctions/MatrixLogarithm.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011, 2013 Jitse Niesen <jitse@maths.leeds.ac.uk>\n// Copyright (C) 2011 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MATRIX_LOGARITHM\n#define EIGEN_MATRIX_LOGARITHM\n\nnamespace Eigen { \n\nnamespace internal { \n\ntemplate <typename Scalar>\nstruct matrix_log_min_pade_degree \n{\n  static const int value = 3;\n};\n\ntemplate <typename Scalar>\nstruct matrix_log_max_pade_degree \n{\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  static const int value = std::numeric_limits<RealScalar>::digits<= 24?  5:  // single precision\n                           std::numeric_limits<RealScalar>::digits<= 53?  7:  // double precision\n                           std::numeric_limits<RealScalar>::digits<= 64?  8:  // extended precision\n                           std::numeric_limits<RealScalar>::digits<=106? 10:  // double-double\n                                                                         11;  // quadruple precision\n};\n\n/** \\brief Compute logarithm of 2x2 triangular matrix. */\ntemplate <typename MatrixType>\nvoid matrix_log_compute_2x2(const MatrixType& A, MatrixType& result)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  using std::abs;\n  using std::ceil;\n  using std::imag;\n  using std::log;\n\n  Scalar logA00 = log(A(0,0));\n  Scalar logA11 = log(A(1,1));\n\n  result(0,0) = logA00;\n  result(1,0) = Scalar(0);\n  result(1,1) = logA11;\n\n  Scalar y = A(1,1) - A(0,0);\n  if (y==Scalar(0))\n  {\n    result(0,1) = A(0,1) / A(0,0);\n  }\n  else if ((abs(A(0,0)) < RealScalar(0.5)*abs(A(1,1))) || (abs(A(0,0)) > 2*abs(A(1,1))))\n  {\n    result(0,1) = A(0,1) * (logA11 - logA00) / y;\n  }\n  else\n  {\n    // computation in previous branch is inaccurate if A(1,1) \\approx A(0,0)\n    RealScalar unwindingNumber = ceil((imag(logA11 - logA00) - RealScalar(EIGEN_PI)) / RealScalar(2*EIGEN_PI));\n    result(0,1) = A(0,1) * (numext::log1p(y/A(0,0)) + Scalar(0,RealScalar(2*EIGEN_PI)*unwindingNumber)) / y;\n  }\n}\n\n/* \\brief Get suitable degree for Pade approximation. (specialized for RealScalar = float) */\ninline int matrix_log_get_pade_degree(float normTminusI)\n{\n  const float maxNormForPade[] = { 2.5111573934555054e-1 /* degree = 3 */ , 4.0535837411880493e-1,\n            5.3149729967117310e-1 };\n  const int minPadeDegree = matrix_log_min_pade_degree<float>::value;\n  const int maxPadeDegree = matrix_log_max_pade_degree<float>::value;\n  int degree = minPadeDegree;\n  for (; degree <= maxPadeDegree; ++degree) \n    if (normTminusI <= maxNormForPade[degree - minPadeDegree])\n      break;\n  return degree;\n}\n\n/* \\brief Get suitable degree for Pade approximation. (specialized for RealScalar = double) */\ninline int matrix_log_get_pade_degree(double normTminusI)\n{\n  const double maxNormForPade[] = { 1.6206284795015624e-2 /* degree = 3 */ , 5.3873532631381171e-2,\n            1.1352802267628681e-1, 1.8662860613541288e-1, 2.642960831111435e-1 };\n  const int minPadeDegree = matrix_log_min_pade_degree<double>::value;\n  const int maxPadeDegree = matrix_log_max_pade_degree<double>::value;\n  int degree = minPadeDegree;\n  for (; degree <= maxPadeDegree; ++degree)\n    if (normTminusI <= maxNormForPade[degree - minPadeDegree])\n      break;\n  return degree;\n}\n\n/* \\brief Get suitable degree for Pade approximation. (specialized for RealScalar = long double) */\ninline int matrix_log_get_pade_degree(long double normTminusI)\n{\n#if   LDBL_MANT_DIG == 53         // double precision\n  const long double maxNormForPade[] = { 1.6206284795015624e-2L /* degree = 3 */ , 5.3873532631381171e-2L,\n            1.1352802267628681e-1L, 1.8662860613541288e-1L, 2.642960831111435e-1L };\n#elif LDBL_MANT_DIG <= 64         // extended precision\n  const long double maxNormForPade[] = { 5.48256690357782863103e-3L /* degree = 3 */, 2.34559162387971167321e-2L,\n            5.84603923897347449857e-2L, 1.08486423756725170223e-1L, 1.68385767881294446649e-1L,\n            2.32777776523703892094e-1L };\n#elif LDBL_MANT_DIG <= 106        // double-double\n  const long double maxNormForPade[] = { 8.58970550342939562202529664318890e-5L /* degree = 3 */,\n            9.34074328446359654039446552677759e-4L, 4.26117194647672175773064114582860e-3L,\n            1.21546224740281848743149666560464e-2L, 2.61100544998339436713088248557444e-2L,\n            4.66170074627052749243018566390567e-2L, 7.32585144444135027565872014932387e-2L,\n            1.05026503471351080481093652651105e-1L };\n#else                             // quadruple precision\n  const long double maxNormForPade[] = { 4.7419931187193005048501568167858103e-5L /* degree = 3 */,\n            5.8853168473544560470387769480192666e-4L, 2.9216120366601315391789493628113520e-3L,\n            8.8415758124319434347116734705174308e-3L, 1.9850836029449446668518049562565291e-2L,\n            3.6688019729653446926585242192447447e-2L, 5.9290962294020186998954055264528393e-2L,\n            8.6998436081634343903250580992127677e-2L, 1.1880960220216759245467951592883642e-1L };\n#endif\n  const int minPadeDegree = matrix_log_min_pade_degree<long double>::value;\n  const int maxPadeDegree = matrix_log_max_pade_degree<long double>::value;\n  int degree = minPadeDegree;\n  for (; degree <= maxPadeDegree; ++degree)\n    if (normTminusI <= maxNormForPade[degree - minPadeDegree])\n      break;\n  return degree;\n}\n\n/* \\brief Compute Pade approximation to matrix logarithm */\ntemplate <typename MatrixType>\nvoid matrix_log_compute_pade(MatrixType& result, const MatrixType& T, int degree)\n{\n  typedef typename NumTraits<typename MatrixType::Scalar>::Real RealScalar;\n  const int minPadeDegree = 3;\n  const int maxPadeDegree = 11;\n  assert(degree >= minPadeDegree && degree <= maxPadeDegree);\n  // FIXME this creates float-conversion-warnings if these are enabled.\n  // Either manually convert each value, or disable the warning locally\n  const RealScalar nodes[][maxPadeDegree] = { \n    { 0.1127016653792583114820734600217600L, 0.5000000000000000000000000000000000L,  // degree 3\n      0.8872983346207416885179265399782400L }, \n    { 0.0694318442029737123880267555535953L, 0.3300094782075718675986671204483777L,  // degree 4\n      0.6699905217924281324013328795516223L, 0.9305681557970262876119732444464048L },\n    { 0.0469100770306680036011865608503035L, 0.2307653449471584544818427896498956L,  // degree 5\n      0.5000000000000000000000000000000000L, 0.7692346550528415455181572103501044L,\n      0.9530899229693319963988134391496965L },\n    { 0.0337652428984239860938492227530027L, 0.1693953067668677431693002024900473L,  // degree 6\n      0.3806904069584015456847491391596440L, 0.6193095930415984543152508608403560L,\n      0.8306046932331322568306997975099527L, 0.9662347571015760139061507772469973L },\n    { 0.0254460438286207377369051579760744L, 0.1292344072003027800680676133596058L,  // degree 7\n      0.2970774243113014165466967939615193L, 0.5000000000000000000000000000000000L,\n      0.7029225756886985834533032060384807L, 0.8707655927996972199319323866403942L,\n      0.9745539561713792622630948420239256L },\n    { 0.0198550717512318841582195657152635L, 0.1016667612931866302042230317620848L,  // degree 8\n      0.2372337950418355070911304754053768L, 0.4082826787521750975302619288199080L,\n      0.5917173212478249024697380711800920L, 0.7627662049581644929088695245946232L,\n      0.8983332387068133697957769682379152L, 0.9801449282487681158417804342847365L },\n    { 0.0159198802461869550822118985481636L, 0.0819844463366821028502851059651326L,  // degree 9\n      0.1933142836497048013456489803292629L, 0.3378732882980955354807309926783317L,\n      0.5000000000000000000000000000000000L, 0.6621267117019044645192690073216683L,\n      0.8066857163502951986543510196707371L, 0.9180155536633178971497148940348674L,\n      0.9840801197538130449177881014518364L },\n    { 0.0130467357414141399610179939577740L, 0.0674683166555077446339516557882535L,  // degree 10\n      0.1602952158504877968828363174425632L, 0.2833023029353764046003670284171079L,\n      0.4255628305091843945575869994351400L, 0.5744371694908156054424130005648600L,\n      0.7166976970646235953996329715828921L, 0.8397047841495122031171636825574368L,\n      0.9325316833444922553660483442117465L, 0.9869532642585858600389820060422260L },\n    { 0.0108856709269715035980309994385713L, 0.0564687001159523504624211153480364L,  // degree 11\n      0.1349239972129753379532918739844233L, 0.2404519353965940920371371652706952L,\n      0.3652284220238275138342340072995692L, 0.5000000000000000000000000000000000L,\n      0.6347715779761724861657659927004308L, 0.7595480646034059079628628347293048L,\n      0.8650760027870246620467081260155767L, 0.9435312998840476495375788846519636L,\n      0.9891143290730284964019690005614287L } };\n\n  const RealScalar weights[][maxPadeDegree] = { \n    { 0.2777777777777777777777777777777778L, 0.4444444444444444444444444444444444L,  // degree 3\n      0.2777777777777777777777777777777778L },\n    { 0.1739274225687269286865319746109997L, 0.3260725774312730713134680253890003L,  // degree 4\n      0.3260725774312730713134680253890003L, 0.1739274225687269286865319746109997L },\n    { 0.1184634425280945437571320203599587L, 0.2393143352496832340206457574178191L,  // degree 5\n      0.2844444444444444444444444444444444L, 0.2393143352496832340206457574178191L,\n      0.1184634425280945437571320203599587L },\n    { 0.0856622461895851725201480710863665L, 0.1803807865240693037849167569188581L,  // degree 6\n      0.2339569672863455236949351719947755L, 0.2339569672863455236949351719947755L,\n      0.1803807865240693037849167569188581L, 0.0856622461895851725201480710863665L },\n    { 0.0647424830844348466353057163395410L, 0.1398526957446383339507338857118898L,  // degree 7\n      0.1909150252525594724751848877444876L, 0.2089795918367346938775510204081633L,\n      0.1909150252525594724751848877444876L, 0.1398526957446383339507338857118898L,\n      0.0647424830844348466353057163395410L },\n    { 0.0506142681451881295762656771549811L, 0.1111905172266872352721779972131204L,  // degree 8\n      0.1568533229389436436689811009933007L, 0.1813418916891809914825752246385978L,\n      0.1813418916891809914825752246385978L, 0.1568533229389436436689811009933007L,\n      0.1111905172266872352721779972131204L, 0.0506142681451881295762656771549811L },\n    { 0.0406371941807872059859460790552618L, 0.0903240803474287020292360156214564L,  // degree 9\n      0.1303053482014677311593714347093164L, 0.1561735385200014200343152032922218L,\n      0.1651196775006298815822625346434870L, 0.1561735385200014200343152032922218L,\n      0.1303053482014677311593714347093164L, 0.0903240803474287020292360156214564L,\n      0.0406371941807872059859460790552618L },\n    { 0.0333356721543440687967844049466659L, 0.0747256745752902965728881698288487L,  // degree 10\n      0.1095431812579910219977674671140816L, 0.1346333596549981775456134607847347L,\n      0.1477621123573764350869464973256692L, 0.1477621123573764350869464973256692L,\n      0.1346333596549981775456134607847347L, 0.1095431812579910219977674671140816L,\n      0.0747256745752902965728881698288487L, 0.0333356721543440687967844049466659L },\n    { 0.0278342835580868332413768602212743L, 0.0627901847324523123173471496119701L,  // degree 11\n      0.0931451054638671257130488207158280L, 0.1165968822959952399592618524215876L,\n      0.1314022722551233310903444349452546L, 0.1364625433889503153572417641681711L,\n      0.1314022722551233310903444349452546L, 0.1165968822959952399592618524215876L,\n      0.0931451054638671257130488207158280L, 0.0627901847324523123173471496119701L,\n      0.0278342835580868332413768602212743L } };\n\n  MatrixType TminusI = T - MatrixType::Identity(T.rows(), T.rows());\n  result.setZero(T.rows(), T.rows());\n  for (int k = 0; k < degree; ++k) {\n    RealScalar weight = weights[degree-minPadeDegree][k];\n    RealScalar node = nodes[degree-minPadeDegree][k];\n    result += weight * (MatrixType::Identity(T.rows(), T.rows()) + node * TminusI)\n                       .template triangularView<Upper>().solve(TminusI);\n  }\n} \n\n/** \\brief Compute logarithm of triangular matrices with size > 2. \n  * \\details This uses a inverse scale-and-square algorithm. */\ntemplate <typename MatrixType>\nvoid matrix_log_compute_big(const MatrixType& A, MatrixType& result)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  using std::pow;\n\n  int numberOfSquareRoots = 0;\n  int numberOfExtraSquareRoots = 0;\n  int degree;\n  MatrixType T = A, sqrtT;\n\n  const int maxPadeDegree = matrix_log_max_pade_degree<Scalar>::value;\n  const RealScalar maxNormForPade = RealScalar(\n                                    maxPadeDegree<= 5? 5.3149729967117310e-1L:                    // single precision\n                                    maxPadeDegree<= 7? 2.6429608311114350e-1L:                    // double precision\n                                    maxPadeDegree<= 8? 2.32777776523703892094e-1L:                // extended precision\n                                    maxPadeDegree<=10? 1.05026503471351080481093652651105e-1L:    // double-double\n                                                       1.1880960220216759245467951592883642e-1L); // quadruple precision\n\n  while (true) {\n    RealScalar normTminusI = (T - MatrixType::Identity(T.rows(), T.rows())).cwiseAbs().colwise().sum().maxCoeff();\n    if (normTminusI < maxNormForPade) {\n      degree = matrix_log_get_pade_degree(normTminusI);\n      int degree2 = matrix_log_get_pade_degree(normTminusI / RealScalar(2));\n      if ((degree - degree2 <= 1) || (numberOfExtraSquareRoots == 1)) \n        break;\n      ++numberOfExtraSquareRoots;\n    }\n    matrix_sqrt_triangular(T, sqrtT);\n    T = sqrtT.template triangularView<Upper>();\n    ++numberOfSquareRoots;\n  }\n\n  matrix_log_compute_pade(result, T, degree);\n  result *= pow(RealScalar(2), RealScalar(numberOfSquareRoots)); // TODO replace by bitshift if possible\n}\n\n/** \\ingroup MatrixFunctions_Module\n  * \\class MatrixLogarithmAtomic\n  * \\brief Helper class for computing matrix logarithm of atomic matrices.\n  *\n  * Here, an atomic matrix is a triangular matrix whose diagonal entries are close to each other.\n  *\n  * \\sa class MatrixFunctionAtomic, MatrixBase::log()\n  */\ntemplate <typename MatrixType>\nclass MatrixLogarithmAtomic\n{\npublic:\n  /** \\brief Compute matrix logarithm of atomic matrix\n    * \\param[in]  A  argument of matrix logarithm, should be upper triangular and atomic\n    * \\returns  The logarithm of \\p A.\n    */\n  MatrixType compute(const MatrixType& A);\n};\n\ntemplate <typename MatrixType>\nMatrixType MatrixLogarithmAtomic<MatrixType>::compute(const MatrixType& A)\n{\n  using std::log;\n  MatrixType result(A.rows(), A.rows());\n  if (A.rows() == 1)\n    result(0,0) = log(A(0,0));\n  else if (A.rows() == 2)\n    matrix_log_compute_2x2(A, result);\n  else\n    matrix_log_compute_big(A, result);\n  return result;\n}\n\n} // end of namespace internal\n\n/** \\ingroup MatrixFunctions_Module\n  *\n  * \\brief Proxy for the matrix logarithm of some matrix (expression).\n  *\n  * \\tparam Derived  Type of the argument to the matrix function.\n  *\n  * This class holds the argument to the matrix function until it is\n  * assigned or evaluated for some other reason (so the argument\n  * should not be changed in the meantime). It is the return type of\n  * MatrixBase::log() and most of the time this is the only way it\n  * is used.\n  */\ntemplate<typename Derived> class MatrixLogarithmReturnValue\n: public ReturnByValue<MatrixLogarithmReturnValue<Derived> >\n{\npublic:\n  typedef typename Derived::Scalar Scalar;\n  typedef typename Derived::Index Index;\n\nprotected:\n  typedef typename internal::ref_selector<Derived>::type DerivedNested;\n\npublic:\n\n  /** \\brief Constructor.\n    *\n    * \\param[in]  A  %Matrix (expression) forming the argument of the matrix logarithm.\n    */\n  explicit MatrixLogarithmReturnValue(const Derived& A) : m_A(A) { }\n  \n  /** \\brief Compute the matrix logarithm.\n    *\n    * \\param[out]  result  Logarithm of \\c A, where \\c A is as specified in the constructor.\n    */\n  template <typename ResultType>\n  inline void evalTo(ResultType& result) const\n  {\n    typedef typename internal::nested_eval<Derived, 10>::type DerivedEvalType;\n    typedef typename internal::remove_all<DerivedEvalType>::type DerivedEvalTypeClean;\n    typedef internal::traits<DerivedEvalTypeClean> Traits;\n    typedef std::complex<typename NumTraits<Scalar>::Real> ComplexScalar;\n    typedef Matrix<ComplexScalar, Dynamic, Dynamic, 0, Traits::RowsAtCompileTime, Traits::ColsAtCompileTime> DynMatrixType;\n    typedef internal::MatrixLogarithmAtomic<DynMatrixType> AtomicType;\n    AtomicType atomic;\n    \n    internal::matrix_function_compute<typename DerivedEvalTypeClean::PlainObject>::run(m_A, atomic, result);\n  }\n\n  Index rows() const { return m_A.rows(); }\n  Index cols() const { return m_A.cols(); }\n  \nprivate:\n  const DerivedNested m_A;\n};\n\nnamespace internal {\n  template<typename Derived>\n  struct traits<MatrixLogarithmReturnValue<Derived> >\n  {\n    typedef typename Derived::PlainObject ReturnType;\n  };\n}\n\n\n/********** MatrixBase method **********/\n\n\ntemplate <typename Derived>\nconst MatrixLogarithmReturnValue<Derived> MatrixBase<Derived>::log() const\n{\n  eigen_assert(rows() == cols());\n  return MatrixLogarithmReturnValue<Derived>(derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_MATRIX_LOGARITHM\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/MatrixFunctions/MatrixPower.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012, 2013 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MATRIX_POWER\n#define EIGEN_MATRIX_POWER\n\nnamespace Eigen {\n\ntemplate<typename MatrixType> class MatrixPower;\n\n/**\n * \\ingroup MatrixFunctions_Module\n *\n * \\brief Proxy for the matrix power of some matrix.\n *\n * \\tparam MatrixType  type of the base, a matrix.\n *\n * This class holds the arguments to the matrix power until it is\n * assigned or evaluated for some other reason (so the argument\n * should not be changed in the meantime). It is the return type of\n * MatrixPower::operator() and related functions and most of the\n * time this is the only way it is used.\n */\n/* TODO This class is only used by MatrixPower, so it should be nested\n * into MatrixPower, like MatrixPower::ReturnValue. However, my\n * compiler complained about unused template parameter in the\n * following declaration in namespace internal.\n *\n * template<typename MatrixType>\n * struct traits<MatrixPower<MatrixType>::ReturnValue>;\n */\ntemplate<typename MatrixType>\nclass MatrixPowerParenthesesReturnValue : public ReturnByValue< MatrixPowerParenthesesReturnValue<MatrixType> >\n{\n  public:\n    typedef typename MatrixType::RealScalar RealScalar;\n\n    /**\n     * \\brief Constructor.\n     *\n     * \\param[in] pow  %MatrixPower storing the base.\n     * \\param[in] p    scalar, the exponent of the matrix power.\n     */\n    MatrixPowerParenthesesReturnValue(MatrixPower<MatrixType>& pow, RealScalar p) : m_pow(pow), m_p(p)\n    { }\n\n    /**\n     * \\brief Compute the matrix power.\n     *\n     * \\param[out] result\n     */\n    template<typename ResultType>\n    inline void evalTo(ResultType& result) const\n    { m_pow.compute(result, m_p); }\n\n    Index rows() const { return m_pow.rows(); }\n    Index cols() const { return m_pow.cols(); }\n\n  private:\n    MatrixPower<MatrixType>& m_pow;\n    const RealScalar m_p;\n};\n\n/**\n * \\ingroup MatrixFunctions_Module\n *\n * \\brief Class for computing matrix powers.\n *\n * \\tparam MatrixType  type of the base, expected to be an instantiation\n * of the Matrix class template.\n *\n * This class is capable of computing triangular real/complex matrices\n * raised to a power in the interval \\f$ (-1, 1) \\f$.\n *\n * \\note Currently this class is only used by MatrixPower. One may\n * insist that this be nested into MatrixPower. This class is here to\n * facilitate future development of triangular matrix functions.\n */\ntemplate<typename MatrixType>\nclass MatrixPowerAtomic : internal::noncopyable\n{\n  private:\n    enum {\n      RowsAtCompileTime = MatrixType::RowsAtCompileTime,\n      MaxRowsAtCompileTime = MatrixType::MaxRowsAtCompileTime\n    };\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    typedef std::complex<RealScalar> ComplexScalar;\n    typedef Block<MatrixType,Dynamic,Dynamic> ResultType;\n\n    const MatrixType& m_A;\n    RealScalar m_p;\n\n    void computePade(int degree, const MatrixType& IminusT, ResultType& res) const;\n    void compute2x2(ResultType& res, RealScalar p) const;\n    void computeBig(ResultType& res) const;\n    static int getPadeDegree(float normIminusT);\n    static int getPadeDegree(double normIminusT);\n    static int getPadeDegree(long double normIminusT);\n    static ComplexScalar computeSuperDiag(const ComplexScalar&, const ComplexScalar&, RealScalar p);\n    static RealScalar computeSuperDiag(RealScalar, RealScalar, RealScalar p);\n\n  public:\n    /**\n     * \\brief Constructor.\n     *\n     * \\param[in] T  the base of the matrix power.\n     * \\param[in] p  the exponent of the matrix power, should be in\n     * \\f$ (-1, 1) \\f$.\n     *\n     * The class stores a reference to T, so it should not be changed\n     * (or destroyed) before evaluation. Only the upper triangular\n     * part of T is read.\n     */\n    MatrixPowerAtomic(const MatrixType& T, RealScalar p);\n    \n    /**\n     * \\brief Compute the matrix power.\n     *\n     * \\param[out] res  \\f$ A^p \\f$ where A and p are specified in the\n     * constructor.\n     */\n    void compute(ResultType& res) const;\n};\n\ntemplate<typename MatrixType>\nMatrixPowerAtomic<MatrixType>::MatrixPowerAtomic(const MatrixType& T, RealScalar p) :\n  m_A(T), m_p(p)\n{\n  eigen_assert(T.rows() == T.cols());\n  eigen_assert(p > -1 && p < 1);\n}\n\ntemplate<typename MatrixType>\nvoid MatrixPowerAtomic<MatrixType>::compute(ResultType& res) const\n{\n  using std::pow;\n  switch (m_A.rows()) {\n    case 0:\n      break;\n    case 1:\n      res(0,0) = pow(m_A(0,0), m_p);\n      break;\n    case 2:\n      compute2x2(res, m_p);\n      break;\n    default:\n      computeBig(res);\n  }\n}\n\ntemplate<typename MatrixType>\nvoid MatrixPowerAtomic<MatrixType>::computePade(int degree, const MatrixType& IminusT, ResultType& res) const\n{\n  int i = 2*degree;\n  res = (m_p-RealScalar(degree)) / RealScalar(2*i-2) * IminusT;\n\n  for (--i; i; --i) {\n    res = (MatrixType::Identity(IminusT.rows(), IminusT.cols()) + res).template triangularView<Upper>()\n\t.solve((i==1 ? -m_p : i&1 ? (-m_p-RealScalar(i/2))/RealScalar(2*i) : (m_p-RealScalar(i/2))/RealScalar(2*i-2)) * IminusT).eval();\n  }\n  res += MatrixType::Identity(IminusT.rows(), IminusT.cols());\n}\n\n// This function assumes that res has the correct size (see bug 614)\ntemplate<typename MatrixType>\nvoid MatrixPowerAtomic<MatrixType>::compute2x2(ResultType& res, RealScalar p) const\n{\n  using std::abs;\n  using std::pow;\n  res.coeffRef(0,0) = pow(m_A.coeff(0,0), p);\n\n  for (Index i=1; i < m_A.cols(); ++i) {\n    res.coeffRef(i,i) = pow(m_A.coeff(i,i), p);\n    if (m_A.coeff(i-1,i-1) == m_A.coeff(i,i))\n      res.coeffRef(i-1,i) = p * pow(m_A.coeff(i,i), p-1);\n    else if (2*abs(m_A.coeff(i-1,i-1)) < abs(m_A.coeff(i,i)) || 2*abs(m_A.coeff(i,i)) < abs(m_A.coeff(i-1,i-1)))\n      res.coeffRef(i-1,i) = (res.coeff(i,i)-res.coeff(i-1,i-1)) / (m_A.coeff(i,i)-m_A.coeff(i-1,i-1));\n    else\n      res.coeffRef(i-1,i) = computeSuperDiag(m_A.coeff(i,i), m_A.coeff(i-1,i-1), p);\n    res.coeffRef(i-1,i) *= m_A.coeff(i-1,i);\n  }\n}\n\ntemplate<typename MatrixType>\nvoid MatrixPowerAtomic<MatrixType>::computeBig(ResultType& res) const\n{\n  using std::ldexp;\n  const int digits = std::numeric_limits<RealScalar>::digits;\n  const RealScalar maxNormForPade = RealScalar(\n                                    digits <=  24? 4.3386528e-1L                            // single precision\n                                  : digits <=  53? 2.789358995219730e-1L                    // double precision\n                                  : digits <=  64? 2.4471944416607995472e-1L                // extended precision\n                                  : digits <= 106? 1.1016843812851143391275867258512e-1L    // double-double\n                                  :                9.134603732914548552537150753385375e-2L); // quadruple precision\n  MatrixType IminusT, sqrtT, T = m_A.template triangularView<Upper>();\n  RealScalar normIminusT;\n  int degree, degree2, numberOfSquareRoots = 0;\n  bool hasExtraSquareRoot = false;\n\n  for (Index i=0; i < m_A.cols(); ++i)\n    eigen_assert(m_A(i,i) != RealScalar(0));\n\n  while (true) {\n    IminusT = MatrixType::Identity(m_A.rows(), m_A.cols()) - T;\n    normIminusT = IminusT.cwiseAbs().colwise().sum().maxCoeff();\n    if (normIminusT < maxNormForPade) {\n      degree = getPadeDegree(normIminusT);\n      degree2 = getPadeDegree(normIminusT/2);\n      if (degree - degree2 <= 1 || hasExtraSquareRoot)\n\tbreak;\n      hasExtraSquareRoot = true;\n    }\n    matrix_sqrt_triangular(T, sqrtT);\n    T = sqrtT.template triangularView<Upper>();\n    ++numberOfSquareRoots;\n  }\n  computePade(degree, IminusT, res);\n\n  for (; numberOfSquareRoots; --numberOfSquareRoots) {\n    compute2x2(res, ldexp(m_p, -numberOfSquareRoots));\n    res = res.template triangularView<Upper>() * res;\n  }\n  compute2x2(res, m_p);\n}\n  \ntemplate<typename MatrixType>\ninline int MatrixPowerAtomic<MatrixType>::getPadeDegree(float normIminusT)\n{\n  const float maxNormForPade[] = { 2.8064004e-1f /* degree = 3 */ , 4.3386528e-1f };\n  int degree = 3;\n  for (; degree <= 4; ++degree)\n    if (normIminusT <= maxNormForPade[degree - 3])\n      break;\n  return degree;\n}\n\ntemplate<typename MatrixType>\ninline int MatrixPowerAtomic<MatrixType>::getPadeDegree(double normIminusT)\n{\n  const double maxNormForPade[] = { 1.884160592658218e-2 /* degree = 3 */ , 6.038881904059573e-2, 1.239917516308172e-1,\n      1.999045567181744e-1, 2.789358995219730e-1 };\n  int degree = 3;\n  for (; degree <= 7; ++degree)\n    if (normIminusT <= maxNormForPade[degree - 3])\n      break;\n  return degree;\n}\n\ntemplate<typename MatrixType>\ninline int MatrixPowerAtomic<MatrixType>::getPadeDegree(long double normIminusT)\n{\n#if   LDBL_MANT_DIG == 53\n  const int maxPadeDegree = 7;\n  const double maxNormForPade[] = { 1.884160592658218e-2L /* degree = 3 */ , 6.038881904059573e-2L, 1.239917516308172e-1L,\n      1.999045567181744e-1L, 2.789358995219730e-1L };\n#elif LDBL_MANT_DIG <= 64\n  const int maxPadeDegree = 8;\n  const long double maxNormForPade[] = { 6.3854693117491799460e-3L /* degree = 3 */ , 2.6394893435456973676e-2L,\n      6.4216043030404063729e-2L, 1.1701165502926694307e-1L, 1.7904284231268670284e-1L, 2.4471944416607995472e-1L };\n#elif LDBL_MANT_DIG <= 106\n  const int maxPadeDegree = 10;\n  const double maxNormForPade[] = { 1.0007161601787493236741409687186e-4L /* degree = 3 */ ,\n      1.0007161601787493236741409687186e-3L, 4.7069769360887572939882574746264e-3L, 1.3220386624169159689406653101695e-2L,\n      2.8063482381631737920612944054906e-2L, 4.9625993951953473052385361085058e-2L, 7.7367040706027886224557538328171e-2L,\n      1.1016843812851143391275867258512e-1L };\n#else\n  const int maxPadeDegree = 10;\n  const double maxNormForPade[] = { 5.524506147036624377378713555116378e-5L /* degree = 3 */ ,\n      6.640600568157479679823602193345995e-4L, 3.227716520106894279249709728084626e-3L,\n      9.619593944683432960546978734646284e-3L, 2.134595382433742403911124458161147e-2L,\n      3.908166513900489428442993794761185e-2L, 6.266780814639442865832535460550138e-2L,\n      9.134603732914548552537150753385375e-2L };\n#endif\n  int degree = 3;\n  for (; degree <= maxPadeDegree; ++degree)\n    if (normIminusT <= maxNormForPade[degree - 3])\n      break;\n  return degree;\n}\n\ntemplate<typename MatrixType>\ninline typename MatrixPowerAtomic<MatrixType>::ComplexScalar\nMatrixPowerAtomic<MatrixType>::computeSuperDiag(const ComplexScalar& curr, const ComplexScalar& prev, RealScalar p)\n{\n  using std::ceil;\n  using std::exp;\n  using std::log;\n  using std::sinh;\n\n  ComplexScalar logCurr = log(curr);\n  ComplexScalar logPrev = log(prev);\n  RealScalar unwindingNumber = ceil((numext::imag(logCurr - logPrev) - RealScalar(EIGEN_PI)) / RealScalar(2*EIGEN_PI));\n  ComplexScalar w = numext::log1p((curr-prev)/prev)/RealScalar(2) + ComplexScalar(0, RealScalar(EIGEN_PI)*unwindingNumber);\n  return RealScalar(2) * exp(RealScalar(0.5) * p * (logCurr + logPrev)) * sinh(p * w) / (curr - prev);\n}\n\ntemplate<typename MatrixType>\ninline typename MatrixPowerAtomic<MatrixType>::RealScalar\nMatrixPowerAtomic<MatrixType>::computeSuperDiag(RealScalar curr, RealScalar prev, RealScalar p)\n{\n  using std::exp;\n  using std::log;\n  using std::sinh;\n\n  RealScalar w = numext::log1p((curr-prev)/prev)/RealScalar(2);\n  return 2 * exp(p * (log(curr) + log(prev)) / 2) * sinh(p * w) / (curr - prev);\n}\n\n/**\n * \\ingroup MatrixFunctions_Module\n *\n * \\brief Class for computing matrix powers.\n *\n * \\tparam MatrixType  type of the base, expected to be an instantiation\n * of the Matrix class template.\n *\n * This class is capable of computing real/complex matrices raised to\n * an arbitrary real power. Meanwhile, it saves the result of Schur\n * decomposition if an non-integral power has even been calculated.\n * Therefore, if you want to compute multiple (>= 2) matrix powers\n * for the same matrix, using the class directly is more efficient than\n * calling MatrixBase::pow().\n *\n * Example:\n * \\include MatrixPower_optimal.cpp\n * Output: \\verbinclude MatrixPower_optimal.out\n */\ntemplate<typename MatrixType>\nclass MatrixPower : internal::noncopyable\n{\n  private:\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n\n  public:\n    /**\n     * \\brief Constructor.\n     *\n     * \\param[in] A  the base of the matrix power.\n     *\n     * The class stores a reference to A, so it should not be changed\n     * (or destroyed) before evaluation.\n     */\n    explicit MatrixPower(const MatrixType& A) :\n      m_A(A),\n      m_conditionNumber(0),\n      m_rank(A.cols()),\n      m_nulls(0)\n    { eigen_assert(A.rows() == A.cols()); }\n\n    /**\n     * \\brief Returns the matrix power.\n     *\n     * \\param[in] p  exponent, a real scalar.\n     * \\return The expression \\f$ A^p \\f$, where A is specified in the\n     * constructor.\n     */\n    const MatrixPowerParenthesesReturnValue<MatrixType> operator()(RealScalar p)\n    { return MatrixPowerParenthesesReturnValue<MatrixType>(*this, p); }\n\n    /**\n     * \\brief Compute the matrix power.\n     *\n     * \\param[in]  p    exponent, a real scalar.\n     * \\param[out] res  \\f$ A^p \\f$ where A is specified in the\n     * constructor.\n     */\n    template<typename ResultType>\n    void compute(ResultType& res, RealScalar p);\n    \n    Index rows() const { return m_A.rows(); }\n    Index cols() const { return m_A.cols(); }\n\n  private:\n    typedef std::complex<RealScalar> ComplexScalar;\n    typedef Matrix<ComplexScalar, Dynamic, Dynamic, 0,\n              MatrixType::RowsAtCompileTime, MatrixType::ColsAtCompileTime> ComplexMatrix;\n\n    /** \\brief Reference to the base of matrix power. */\n    typename MatrixType::Nested m_A;\n\n    /** \\brief Temporary storage. */\n    MatrixType m_tmp;\n\n    /** \\brief Store the result of Schur decomposition. */\n    ComplexMatrix m_T, m_U;\n    \n    /** \\brief Store fractional power of m_T. */\n    ComplexMatrix m_fT;\n\n    /**\n     * \\brief Condition number of m_A.\n     *\n     * It is initialized as 0 to avoid performing unnecessary Schur\n     * decomposition, which is the bottleneck.\n     */\n    RealScalar m_conditionNumber;\n\n    /** \\brief Rank of m_A. */\n    Index m_rank;\n    \n    /** \\brief Rank deficiency of m_A. */\n    Index m_nulls;\n\n    /**\n     * \\brief Split p into integral part and fractional part.\n     *\n     * \\param[in]  p        The exponent.\n     * \\param[out] p        The fractional part ranging in \\f$ (-1, 1) \\f$.\n     * \\param[out] intpart  The integral part.\n     *\n     * Only if the fractional part is nonzero, it calls initialize().\n     */\n    void split(RealScalar& p, RealScalar& intpart);\n\n    /** \\brief Perform Schur decomposition for fractional power. */\n    void initialize();\n\n    template<typename ResultType>\n    void computeIntPower(ResultType& res, RealScalar p);\n\n    template<typename ResultType>\n    void computeFracPower(ResultType& res, RealScalar p);\n\n    template<int Rows, int Cols, int Options, int MaxRows, int MaxCols>\n    static void revertSchur(\n        Matrix<ComplexScalar, Rows, Cols, Options, MaxRows, MaxCols>& res,\n        const ComplexMatrix& T,\n        const ComplexMatrix& U);\n\n    template<int Rows, int Cols, int Options, int MaxRows, int MaxCols>\n    static void revertSchur(\n        Matrix<RealScalar, Rows, Cols, Options, MaxRows, MaxCols>& res,\n        const ComplexMatrix& T,\n        const ComplexMatrix& U);\n};\n\ntemplate<typename MatrixType>\ntemplate<typename ResultType>\nvoid MatrixPower<MatrixType>::compute(ResultType& res, RealScalar p)\n{\n  using std::pow;\n  switch (cols()) {\n    case 0:\n      break;\n    case 1:\n      res(0,0) = pow(m_A.coeff(0,0), p);\n      break;\n    default:\n      RealScalar intpart;\n      split(p, intpart);\n\n      res = MatrixType::Identity(rows(), cols());\n      computeIntPower(res, intpart);\n      if (p) computeFracPower(res, p);\n  }\n}\n\ntemplate<typename MatrixType>\nvoid MatrixPower<MatrixType>::split(RealScalar& p, RealScalar& intpart)\n{\n  using std::floor;\n  using std::pow;\n\n  intpart = floor(p);\n  p -= intpart;\n\n  // Perform Schur decomposition if it is not yet performed and the power is\n  // not an integer.\n  if (!m_conditionNumber && p)\n    initialize();\n\n  // Choose the more stable of intpart = floor(p) and intpart = ceil(p).\n  if (p > RealScalar(0.5) && p > (1-p) * pow(m_conditionNumber, p)) {\n    --p;\n    ++intpart;\n  }\n}\n\ntemplate<typename MatrixType>\nvoid MatrixPower<MatrixType>::initialize()\n{\n  const ComplexSchur<MatrixType> schurOfA(m_A);\n  JacobiRotation<ComplexScalar> rot;\n  ComplexScalar eigenvalue;\n\n  m_fT.resizeLike(m_A);\n  m_T = schurOfA.matrixT();\n  m_U = schurOfA.matrixU();\n  m_conditionNumber = m_T.diagonal().array().abs().maxCoeff() / m_T.diagonal().array().abs().minCoeff();\n\n  // Move zero eigenvalues to the bottom right corner.\n  for (Index i = cols()-1; i>=0; --i) {\n    if (m_rank <= 2)\n      return;\n    if (m_T.coeff(i,i) == RealScalar(0)) {\n      for (Index j=i+1; j < m_rank; ++j) {\n        eigenvalue = m_T.coeff(j,j);\n        rot.makeGivens(m_T.coeff(j-1,j), eigenvalue);\n        m_T.applyOnTheRight(j-1, j, rot);\n        m_T.applyOnTheLeft(j-1, j, rot.adjoint());\n        m_T.coeffRef(j-1,j-1) = eigenvalue;\n        m_T.coeffRef(j,j) = RealScalar(0);\n        m_U.applyOnTheRight(j-1, j, rot);\n      }\n      --m_rank;\n    }\n  }\n\n  m_nulls = rows() - m_rank;\n  if (m_nulls) {\n    eigen_assert(m_T.bottomRightCorner(m_nulls, m_nulls).isZero()\n        && \"Base of matrix power should be invertible or with a semisimple zero eigenvalue.\");\n    m_fT.bottomRows(m_nulls).fill(RealScalar(0));\n  }\n}\n\ntemplate<typename MatrixType>\ntemplate<typename ResultType>\nvoid MatrixPower<MatrixType>::computeIntPower(ResultType& res, RealScalar p)\n{\n  using std::abs;\n  using std::fmod;\n  RealScalar pp = abs(p);\n\n  if (p<0) \n    m_tmp = m_A.inverse();\n  else     \n    m_tmp = m_A;\n\n  while (true) {\n    if (fmod(pp, 2) >= 1)\n      res = m_tmp * res;\n    pp /= 2;\n    if (pp < 1)\n      break;\n    m_tmp *= m_tmp;\n  }\n}\n\ntemplate<typename MatrixType>\ntemplate<typename ResultType>\nvoid MatrixPower<MatrixType>::computeFracPower(ResultType& res, RealScalar p)\n{\n  Block<ComplexMatrix,Dynamic,Dynamic> blockTp(m_fT, 0, 0, m_rank, m_rank);\n  eigen_assert(m_conditionNumber);\n  eigen_assert(m_rank + m_nulls == rows());\n\n  MatrixPowerAtomic<ComplexMatrix>(m_T.topLeftCorner(m_rank, m_rank), p).compute(blockTp);\n  if (m_nulls) {\n    m_fT.topRightCorner(m_rank, m_nulls) = m_T.topLeftCorner(m_rank, m_rank).template triangularView<Upper>()\n        .solve(blockTp * m_T.topRightCorner(m_rank, m_nulls));\n  }\n  revertSchur(m_tmp, m_fT, m_U);\n  res = m_tmp * res;\n}\n\ntemplate<typename MatrixType>\ntemplate<int Rows, int Cols, int Options, int MaxRows, int MaxCols>\ninline void MatrixPower<MatrixType>::revertSchur(\n    Matrix<ComplexScalar, Rows, Cols, Options, MaxRows, MaxCols>& res,\n    const ComplexMatrix& T,\n    const ComplexMatrix& U)\n{ res.noalias() = U * (T.template triangularView<Upper>() * U.adjoint()); }\n\ntemplate<typename MatrixType>\ntemplate<int Rows, int Cols, int Options, int MaxRows, int MaxCols>\ninline void MatrixPower<MatrixType>::revertSchur(\n    Matrix<RealScalar, Rows, Cols, Options, MaxRows, MaxCols>& res,\n    const ComplexMatrix& T,\n    const ComplexMatrix& U)\n{ res.noalias() = (U * (T.template triangularView<Upper>() * U.adjoint())).real(); }\n\n/**\n * \\ingroup MatrixFunctions_Module\n *\n * \\brief Proxy for the matrix power of some matrix (expression).\n *\n * \\tparam Derived  type of the base, a matrix (expression).\n *\n * This class holds the arguments to the matrix power until it is\n * assigned or evaluated for some other reason (so the argument\n * should not be changed in the meantime). It is the return type of\n * MatrixBase::pow() and related functions and most of the\n * time this is the only way it is used.\n */\ntemplate<typename Derived>\nclass MatrixPowerReturnValue : public ReturnByValue< MatrixPowerReturnValue<Derived> >\n{\n  public:\n    typedef typename Derived::PlainObject PlainObject;\n    typedef typename Derived::RealScalar RealScalar;\n\n    /**\n     * \\brief Constructor.\n     *\n     * \\param[in] A  %Matrix (expression), the base of the matrix power.\n     * \\param[in] p  real scalar, the exponent of the matrix power.\n     */\n    MatrixPowerReturnValue(const Derived& A, RealScalar p) : m_A(A), m_p(p)\n    { }\n\n    /**\n     * \\brief Compute the matrix power.\n     *\n     * \\param[out] result  \\f$ A^p \\f$ where \\p A and \\p p are as in the\n     * constructor.\n     */\n    template<typename ResultType>\n    inline void evalTo(ResultType& result) const\n    { MatrixPower<PlainObject>(m_A.eval()).compute(result, m_p); }\n\n    Index rows() const { return m_A.rows(); }\n    Index cols() const { return m_A.cols(); }\n\n  private:\n    const Derived& m_A;\n    const RealScalar m_p;\n};\n\n/**\n * \\ingroup MatrixFunctions_Module\n *\n * \\brief Proxy for the matrix power of some matrix (expression).\n *\n * \\tparam Derived  type of the base, a matrix (expression).\n *\n * This class holds the arguments to the matrix power until it is\n * assigned or evaluated for some other reason (so the argument\n * should not be changed in the meantime). It is the return type of\n * MatrixBase::pow() and related functions and most of the\n * time this is the only way it is used.\n */\ntemplate<typename Derived>\nclass MatrixComplexPowerReturnValue : public ReturnByValue< MatrixComplexPowerReturnValue<Derived> >\n{\n  public:\n    typedef typename Derived::PlainObject PlainObject;\n    typedef typename std::complex<typename Derived::RealScalar> ComplexScalar;\n\n    /**\n     * \\brief Constructor.\n     *\n     * \\param[in] A  %Matrix (expression), the base of the matrix power.\n     * \\param[in] p  complex scalar, the exponent of the matrix power.\n     */\n    MatrixComplexPowerReturnValue(const Derived& A, const ComplexScalar& p) : m_A(A), m_p(p)\n    { }\n\n    /**\n     * \\brief Compute the matrix power.\n     *\n     * Because \\p p is complex, \\f$ A^p \\f$ is simply evaluated as \\f$\n     * \\exp(p \\log(A)) \\f$.\n     *\n     * \\param[out] result  \\f$ A^p \\f$ where \\p A and \\p p are as in the\n     * constructor.\n     */\n    template<typename ResultType>\n    inline void evalTo(ResultType& result) const\n    { result = (m_p * m_A.log()).exp(); }\n\n    Index rows() const { return m_A.rows(); }\n    Index cols() const { return m_A.cols(); }\n\n  private:\n    const Derived& m_A;\n    const ComplexScalar m_p;\n};\n\nnamespace internal {\n\ntemplate<typename MatrixPowerType>\nstruct traits< MatrixPowerParenthesesReturnValue<MatrixPowerType> >\n{ typedef typename MatrixPowerType::PlainObject ReturnType; };\n\ntemplate<typename Derived>\nstruct traits< MatrixPowerReturnValue<Derived> >\n{ typedef typename Derived::PlainObject ReturnType; };\n\ntemplate<typename Derived>\nstruct traits< MatrixComplexPowerReturnValue<Derived> >\n{ typedef typename Derived::PlainObject ReturnType; };\n\n}\n\ntemplate<typename Derived>\nconst MatrixPowerReturnValue<Derived> MatrixBase<Derived>::pow(const RealScalar& p) const\n{ return MatrixPowerReturnValue<Derived>(derived(), p); }\n\ntemplate<typename Derived>\nconst MatrixComplexPowerReturnValue<Derived> MatrixBase<Derived>::pow(const std::complex<RealScalar>& p) const\n{ return MatrixComplexPowerReturnValue<Derived>(derived(), p); }\n\n} // namespace Eigen\n\n#endif // EIGEN_MATRIX_POWER\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/MatrixFunctions/MatrixSquareRoot.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011, 2013 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MATRIX_SQUARE_ROOT\n#define EIGEN_MATRIX_SQUARE_ROOT\n\nnamespace Eigen { \n\nnamespace internal {\n\n// pre:  T.block(i,i,2,2) has complex conjugate eigenvalues\n// post: sqrtT.block(i,i,2,2) is square root of T.block(i,i,2,2)\ntemplate <typename MatrixType, typename ResultType>\nvoid matrix_sqrt_quasi_triangular_2x2_diagonal_block(const MatrixType& T, Index i, ResultType& sqrtT)\n{\n  // TODO: This case (2-by-2 blocks with complex conjugate eigenvalues) is probably hidden somewhere\n  //       in EigenSolver. If we expose it, we could call it directly from here.\n  typedef typename traits<MatrixType>::Scalar Scalar;\n  Matrix<Scalar,2,2> block = T.template block<2,2>(i,i);\n  EigenSolver<Matrix<Scalar,2,2> > es(block);\n  sqrtT.template block<2,2>(i,i)\n    = (es.eigenvectors() * es.eigenvalues().cwiseSqrt().asDiagonal() * es.eigenvectors().inverse()).real();\n}\n\n// pre:  block structure of T is such that (i,j) is a 1x1 block,\n//       all blocks of sqrtT to left of and below (i,j) are correct\n// post: sqrtT(i,j) has the correct value\ntemplate <typename MatrixType, typename ResultType>\nvoid matrix_sqrt_quasi_triangular_1x1_off_diagonal_block(const MatrixType& T, Index i, Index j, ResultType& sqrtT)\n{\n  typedef typename traits<MatrixType>::Scalar Scalar;\n  Scalar tmp = (sqrtT.row(i).segment(i+1,j-i-1) * sqrtT.col(j).segment(i+1,j-i-1)).value();\n  sqrtT.coeffRef(i,j) = (T.coeff(i,j) - tmp) / (sqrtT.coeff(i,i) + sqrtT.coeff(j,j));\n}\n\n// similar to compute1x1offDiagonalBlock()\ntemplate <typename MatrixType, typename ResultType>\nvoid matrix_sqrt_quasi_triangular_1x2_off_diagonal_block(const MatrixType& T, Index i, Index j, ResultType& sqrtT)\n{\n  typedef typename traits<MatrixType>::Scalar Scalar;\n  Matrix<Scalar,1,2> rhs = T.template block<1,2>(i,j);\n  if (j-i > 1)\n    rhs -= sqrtT.block(i, i+1, 1, j-i-1) * sqrtT.block(i+1, j, j-i-1, 2);\n  Matrix<Scalar,2,2> A = sqrtT.coeff(i,i) * Matrix<Scalar,2,2>::Identity();\n  A += sqrtT.template block<2,2>(j,j).transpose();\n  sqrtT.template block<1,2>(i,j).transpose() = A.fullPivLu().solve(rhs.transpose());\n}\n\n// similar to compute1x1offDiagonalBlock()\ntemplate <typename MatrixType, typename ResultType>\nvoid matrix_sqrt_quasi_triangular_2x1_off_diagonal_block(const MatrixType& T, Index i, Index j, ResultType& sqrtT)\n{\n  typedef typename traits<MatrixType>::Scalar Scalar;\n  Matrix<Scalar,2,1> rhs = T.template block<2,1>(i,j);\n  if (j-i > 2)\n    rhs -= sqrtT.block(i, i+2, 2, j-i-2) * sqrtT.block(i+2, j, j-i-2, 1);\n  Matrix<Scalar,2,2> A = sqrtT.coeff(j,j) * Matrix<Scalar,2,2>::Identity();\n  A += sqrtT.template block<2,2>(i,i);\n  sqrtT.template block<2,1>(i,j) = A.fullPivLu().solve(rhs);\n}\n\n// solves the equation A X + X B = C where all matrices are 2-by-2\ntemplate <typename MatrixType>\nvoid matrix_sqrt_quasi_triangular_solve_auxiliary_equation(MatrixType& X, const MatrixType& A, const MatrixType& B, const MatrixType& C)\n{\n  typedef typename traits<MatrixType>::Scalar Scalar;\n  Matrix<Scalar,4,4> coeffMatrix = Matrix<Scalar,4,4>::Zero();\n  coeffMatrix.coeffRef(0,0) = A.coeff(0,0) + B.coeff(0,0);\n  coeffMatrix.coeffRef(1,1) = A.coeff(0,0) + B.coeff(1,1);\n  coeffMatrix.coeffRef(2,2) = A.coeff(1,1) + B.coeff(0,0);\n  coeffMatrix.coeffRef(3,3) = A.coeff(1,1) + B.coeff(1,1);\n  coeffMatrix.coeffRef(0,1) = B.coeff(1,0);\n  coeffMatrix.coeffRef(0,2) = A.coeff(0,1);\n  coeffMatrix.coeffRef(1,0) = B.coeff(0,1);\n  coeffMatrix.coeffRef(1,3) = A.coeff(0,1);\n  coeffMatrix.coeffRef(2,0) = A.coeff(1,0);\n  coeffMatrix.coeffRef(2,3) = B.coeff(1,0);\n  coeffMatrix.coeffRef(3,1) = A.coeff(1,0);\n  coeffMatrix.coeffRef(3,2) = B.coeff(0,1);\n\n  Matrix<Scalar,4,1> rhs;\n  rhs.coeffRef(0) = C.coeff(0,0);\n  rhs.coeffRef(1) = C.coeff(0,1);\n  rhs.coeffRef(2) = C.coeff(1,0);\n  rhs.coeffRef(3) = C.coeff(1,1);\n\n  Matrix<Scalar,4,1> result;\n  result = coeffMatrix.fullPivLu().solve(rhs);\n\n  X.coeffRef(0,0) = result.coeff(0);\n  X.coeffRef(0,1) = result.coeff(1);\n  X.coeffRef(1,0) = result.coeff(2);\n  X.coeffRef(1,1) = result.coeff(3);\n}\n\n// similar to compute1x1offDiagonalBlock()\ntemplate <typename MatrixType, typename ResultType>\nvoid matrix_sqrt_quasi_triangular_2x2_off_diagonal_block(const MatrixType& T, Index i, Index j, ResultType& sqrtT)\n{\n  typedef typename traits<MatrixType>::Scalar Scalar;\n  Matrix<Scalar,2,2> A = sqrtT.template block<2,2>(i,i);\n  Matrix<Scalar,2,2> B = sqrtT.template block<2,2>(j,j);\n  Matrix<Scalar,2,2> C = T.template block<2,2>(i,j);\n  if (j-i > 2)\n    C -= sqrtT.block(i, i+2, 2, j-i-2) * sqrtT.block(i+2, j, j-i-2, 2);\n  Matrix<Scalar,2,2> X;\n  matrix_sqrt_quasi_triangular_solve_auxiliary_equation(X, A, B, C);\n  sqrtT.template block<2,2>(i,j) = X;\n}\n\n// pre:  T is quasi-upper-triangular and sqrtT is a zero matrix of the same size\n// post: the diagonal blocks of sqrtT are the square roots of the diagonal blocks of T\ntemplate <typename MatrixType, typename ResultType>\nvoid matrix_sqrt_quasi_triangular_diagonal(const MatrixType& T, ResultType& sqrtT)\n{\n  using std::sqrt;\n  const Index size = T.rows();\n  for (Index i = 0; i < size; i++) {\n    if (i == size - 1 || T.coeff(i+1, i) == 0) {\n      eigen_assert(T(i,i) >= 0);\n      sqrtT.coeffRef(i,i) = sqrt(T.coeff(i,i));\n    }\n    else {\n      matrix_sqrt_quasi_triangular_2x2_diagonal_block(T, i, sqrtT);\n      ++i;\n    }\n  }\n}\n\n// pre:  T is quasi-upper-triangular and diagonal blocks of sqrtT are square root of diagonal blocks of T.\n// post: sqrtT is the square root of T.\ntemplate <typename MatrixType, typename ResultType>\nvoid matrix_sqrt_quasi_triangular_off_diagonal(const MatrixType& T, ResultType& sqrtT)\n{\n  const Index size = T.rows();\n  for (Index j = 1; j < size; j++) {\n      if (T.coeff(j, j-1) != 0)  // if T(j-1:j, j-1:j) is a 2-by-2 block\n\tcontinue;\n    for (Index i = j-1; i >= 0; i--) {\n      if (i > 0 && T.coeff(i, i-1) != 0)  // if T(i-1:i, i-1:i) is a 2-by-2 block\n\tcontinue;\n      bool iBlockIs2x2 = (i < size - 1) && (T.coeff(i+1, i) != 0);\n      bool jBlockIs2x2 = (j < size - 1) && (T.coeff(j+1, j) != 0);\n      if (iBlockIs2x2 && jBlockIs2x2) \n        matrix_sqrt_quasi_triangular_2x2_off_diagonal_block(T, i, j, sqrtT);\n      else if (iBlockIs2x2 && !jBlockIs2x2) \n        matrix_sqrt_quasi_triangular_2x1_off_diagonal_block(T, i, j, sqrtT);\n      else if (!iBlockIs2x2 && jBlockIs2x2) \n        matrix_sqrt_quasi_triangular_1x2_off_diagonal_block(T, i, j, sqrtT);\n      else if (!iBlockIs2x2 && !jBlockIs2x2) \n        matrix_sqrt_quasi_triangular_1x1_off_diagonal_block(T, i, j, sqrtT);\n    }\n  }\n}\n\n} // end of namespace internal\n\n/** \\ingroup MatrixFunctions_Module\n  * \\brief Compute matrix square root of quasi-triangular matrix.\n  *\n  * \\tparam  MatrixType  type of \\p arg, the argument of matrix square root,\n  *                      expected to be an instantiation of the Matrix class template.\n  * \\tparam  ResultType  type of \\p result, where result is to be stored.\n  * \\param[in]  arg      argument of matrix square root.\n  * \\param[out] result   matrix square root of upper Hessenberg part of \\p arg.\n  *\n  * This function computes the square root of the upper quasi-triangular matrix stored in the upper\n  * Hessenberg part of \\p arg.  Only the upper Hessenberg part of \\p result is updated, the rest is\n  * not touched.  See MatrixBase::sqrt() for details on how this computation is implemented.\n  *\n  * \\sa MatrixSquareRoot, MatrixSquareRootQuasiTriangular\n  */\ntemplate <typename MatrixType, typename ResultType> \nvoid matrix_sqrt_quasi_triangular(const MatrixType &arg, ResultType &result)\n{\n  eigen_assert(arg.rows() == arg.cols());\n  result.resize(arg.rows(), arg.cols());\n  internal::matrix_sqrt_quasi_triangular_diagonal(arg, result);\n  internal::matrix_sqrt_quasi_triangular_off_diagonal(arg, result);\n}\n\n\n/** \\ingroup MatrixFunctions_Module\n  * \\brief Compute matrix square root of triangular matrix.\n  *\n  * \\tparam  MatrixType  type of \\p arg, the argument of matrix square root,\n  *                      expected to be an instantiation of the Matrix class template.\n  * \\tparam  ResultType  type of \\p result, where result is to be stored.\n  * \\param[in]  arg      argument of matrix square root.\n  * \\param[out] result   matrix square root of upper triangular part of \\p arg.\n  *\n  * Only the upper triangular part (including the diagonal) of \\p result is updated, the rest is not\n  * touched.  See MatrixBase::sqrt() for details on how this computation is implemented.\n  *\n  * \\sa MatrixSquareRoot, MatrixSquareRootQuasiTriangular\n  */\ntemplate <typename MatrixType, typename ResultType> \nvoid matrix_sqrt_triangular(const MatrixType &arg, ResultType &result)\n{\n  using std::sqrt;\n  typedef typename MatrixType::Scalar Scalar;\n\n  eigen_assert(arg.rows() == arg.cols());\n\n  // Compute square root of arg and store it in upper triangular part of result\n  // This uses that the square root of triangular matrices can be computed directly.\n  result.resize(arg.rows(), arg.cols());\n  for (Index i = 0; i < arg.rows(); i++) {\n    result.coeffRef(i,i) = sqrt(arg.coeff(i,i));\n  }\n  for (Index j = 1; j < arg.cols(); j++) {\n    for (Index i = j-1; i >= 0; i--) {\n      // if i = j-1, then segment has length 0 so tmp = 0\n      Scalar tmp = (result.row(i).segment(i+1,j-i-1) * result.col(j).segment(i+1,j-i-1)).value();\n      // denominator may be zero if original matrix is singular\n      result.coeffRef(i,j) = (arg.coeff(i,j) - tmp) / (result.coeff(i,i) + result.coeff(j,j));\n    }\n  }\n}\n\n\nnamespace internal {\n\n/** \\ingroup MatrixFunctions_Module\n  * \\brief Helper struct for computing matrix square roots of general matrices.\n  * \\tparam  MatrixType  type of the argument of the matrix square root,\n  *                      expected to be an instantiation of the Matrix class template.\n  *\n  * \\sa MatrixSquareRootTriangular, MatrixSquareRootQuasiTriangular, MatrixBase::sqrt()\n  */\ntemplate <typename MatrixType, int IsComplex = NumTraits<typename internal::traits<MatrixType>::Scalar>::IsComplex>\nstruct matrix_sqrt_compute\n{\n  /** \\brief Compute the matrix square root\n    *\n    * \\param[in]  arg     matrix whose square root is to be computed.\n    * \\param[out] result  square root of \\p arg.\n    *\n    * See MatrixBase::sqrt() for details on how this computation is implemented.\n    */\n  template <typename ResultType> static void run(const MatrixType &arg, ResultType &result);    \n};\n\n\n// ********** Partial specialization for real matrices **********\n\ntemplate <typename MatrixType>\nstruct matrix_sqrt_compute<MatrixType, 0>\n{\n  typedef typename MatrixType::PlainObject PlainType;\n  template <typename ResultType>\n  static void run(const MatrixType &arg, ResultType &result)\n  {\n    eigen_assert(arg.rows() == arg.cols());\n\n    // Compute Schur decomposition of arg\n    const RealSchur<PlainType> schurOfA(arg);\n    const PlainType& T = schurOfA.matrixT();\n    const PlainType& U = schurOfA.matrixU();\n    \n    // Compute square root of T\n    PlainType sqrtT = PlainType::Zero(arg.rows(), arg.cols());\n    matrix_sqrt_quasi_triangular(T, sqrtT);\n    \n    // Compute square root of arg\n    result = U * sqrtT * U.adjoint();\n  }\n};\n\n\n// ********** Partial specialization for complex matrices **********\n\ntemplate <typename MatrixType>\nstruct matrix_sqrt_compute<MatrixType, 1>\n{\n  typedef typename MatrixType::PlainObject PlainType;\n  template <typename ResultType>\n  static void run(const MatrixType &arg, ResultType &result)\n  {\n    eigen_assert(arg.rows() == arg.cols());\n\n    // Compute Schur decomposition of arg\n    const ComplexSchur<PlainType> schurOfA(arg);\n    const PlainType& T = schurOfA.matrixT();\n    const PlainType& U = schurOfA.matrixU();\n    \n    // Compute square root of T\n    PlainType sqrtT;\n    matrix_sqrt_triangular(T, sqrtT);\n    \n    // Compute square root of arg\n    result = U * (sqrtT.template triangularView<Upper>() * U.adjoint());\n  }\n};\n\n} // end namespace internal\n\n/** \\ingroup MatrixFunctions_Module\n  *\n  * \\brief Proxy for the matrix square root of some matrix (expression).\n  *\n  * \\tparam Derived  Type of the argument to the matrix square root.\n  *\n  * This class holds the argument to the matrix square root until it\n  * is assigned or evaluated for some other reason (so the argument\n  * should not be changed in the meantime). It is the return type of\n  * MatrixBase::sqrt() and most of the time this is the only way it is\n  * used.\n  */\ntemplate<typename Derived> class MatrixSquareRootReturnValue\n: public ReturnByValue<MatrixSquareRootReturnValue<Derived> >\n{\n  protected:\n    typedef typename internal::ref_selector<Derived>::type DerivedNested;\n\n  public:\n    /** \\brief Constructor.\n      *\n      * \\param[in]  src  %Matrix (expression) forming the argument of the\n      * matrix square root.\n      */\n    explicit MatrixSquareRootReturnValue(const Derived& src) : m_src(src) { }\n\n    /** \\brief Compute the matrix square root.\n      *\n      * \\param[out]  result  the matrix square root of \\p src in the\n      * constructor.\n      */\n    template <typename ResultType>\n    inline void evalTo(ResultType& result) const\n    {\n      typedef typename internal::nested_eval<Derived, 10>::type DerivedEvalType;\n      typedef typename internal::remove_all<DerivedEvalType>::type DerivedEvalTypeClean;\n      DerivedEvalType tmp(m_src);\n      internal::matrix_sqrt_compute<DerivedEvalTypeClean>::run(tmp, result);\n    }\n\n    Index rows() const { return m_src.rows(); }\n    Index cols() const { return m_src.cols(); }\n\n  protected:\n    const DerivedNested m_src;\n};\n\nnamespace internal {\ntemplate<typename Derived>\nstruct traits<MatrixSquareRootReturnValue<Derived> >\n{\n  typedef typename Derived::PlainObject ReturnType;\n};\n}\n\ntemplate <typename Derived>\nconst MatrixSquareRootReturnValue<Derived> MatrixBase<Derived>::sqrt() const\n{\n  eigen_assert(rows() == cols());\n  return MatrixSquareRootReturnValue<Derived>(derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_MATRIX_FUNCTION\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/MatrixFunctions/StemFunction.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010, 2013 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_STEM_FUNCTION\n#define EIGEN_STEM_FUNCTION\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\brief The exponential function (and its derivatives). */\ntemplate <typename Scalar>\nScalar stem_function_exp(Scalar x, int)\n{\n  using std::exp;\n  return exp(x);\n}\n\n/** \\brief Cosine (and its derivatives). */\ntemplate <typename Scalar>\nScalar stem_function_cos(Scalar x, int n)\n{\n  using std::cos;\n  using std::sin;\n  Scalar res;\n\n  switch (n % 4) {\n  case 0: \n    res = std::cos(x);\n    break;\n  case 1:\n    res = -std::sin(x);\n    break;\n  case 2:\n    res = -std::cos(x);\n    break;\n  case 3:\n    res = std::sin(x);\n    break;\n  }\n  return res;\n}\n\n/** \\brief Sine (and its derivatives). */\ntemplate <typename Scalar>\nScalar stem_function_sin(Scalar x, int n)\n{\n  using std::cos;\n  using std::sin;\n  Scalar res;\n\n  switch (n % 4) {\n  case 0:\n    res = std::sin(x);\n    break;\n  case 1:\n    res = std::cos(x);\n    break;\n  case 2:\n    res = -std::sin(x);\n    break;\n  case 3:\n    res = -std::cos(x);\n    break;\n  }\n  return res;\n}\n\n/** \\brief Hyperbolic cosine (and its derivatives). */\ntemplate <typename Scalar>\nScalar stem_function_cosh(Scalar x, int n)\n{\n  using std::cosh;\n  using std::sinh;\n  Scalar res;\n  \n  switch (n % 2) {\n  case 0:\n    res = std::cosh(x);\n    break;\n  case 1:\n    res = std::sinh(x);\n    break;\n  }\n  return res;\n}\n\t\n/** \\brief Hyperbolic sine (and its derivatives). */\ntemplate <typename Scalar>\nScalar stem_function_sinh(Scalar x, int n)\n{\n  using std::cosh;\n  using std::sinh;\n  Scalar res;\n  \n  switch (n % 2) {\n  case 0:\n    res = std::sinh(x);\n    break;\n  case 1:\n    res = std::cosh(x);\n    break;\n  }\n  return res;\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_STEM_FUNCTION\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/MoreVectorization/MathFunctions.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Rohit Garg <rpg.314@gmail.com>\n// Copyright (C) 2009 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_MOREVECTORIZATION_MATHFUNCTIONS_H\n#define EIGEN_MOREVECTORIZATION_MATHFUNCTIONS_H\n\nnamespace Eigen { \n\nnamespace internal {\n\n/** \\internal \\returns the arcsin of \\a a (coeff-wise) */\ntemplate<typename Packet> inline static Packet pasin(Packet a) { return std::asin(a); }\n\n#ifdef EIGEN_VECTORIZE_SSE\n\ntemplate<> EIGEN_DONT_INLINE Packet4f pasin(Packet4f x)\n{\n  _EIGEN_DECLARE_CONST_Packet4f(half, 0.5);\n  _EIGEN_DECLARE_CONST_Packet4f(minus_half, -0.5);\n  _EIGEN_DECLARE_CONST_Packet4f(3half, 1.5);\n\n  _EIGEN_DECLARE_CONST_Packet4f_FROM_INT(sign_mask, 0x80000000);\n\n  _EIGEN_DECLARE_CONST_Packet4f(pi, 3.141592654);\n  _EIGEN_DECLARE_CONST_Packet4f(pi_over_2, 3.141592654*0.5);\n\n  _EIGEN_DECLARE_CONST_Packet4f(asin1, 4.2163199048E-2);\n  _EIGEN_DECLARE_CONST_Packet4f(asin2, 2.4181311049E-2);\n  _EIGEN_DECLARE_CONST_Packet4f(asin3, 4.5470025998E-2);\n  _EIGEN_DECLARE_CONST_Packet4f(asin4, 7.4953002686E-2);\n  _EIGEN_DECLARE_CONST_Packet4f(asin5, 1.6666752422E-1);\n\n  Packet4f a = pabs(x);//got the absolute value\n\n  Packet4f sign_bit= _mm_and_ps(x, p4f_sign_mask);//extracted the sign bit\n\n  Packet4f z1,z2;//will need them during computation    \n\n\n//will compute the two branches for asin\n//so first compare with half\n\n  Packet4f branch_mask= _mm_cmpgt_ps(a, p4f_half);//this is to select which branch to take\n//both will be taken, and finally results will be merged\n//the branch for values >0.5\n\n    {\n//the core series expansion \n    z1=pmadd(p4f_minus_half,a,p4f_half);\n    Packet4f x1=psqrt(z1);\n    Packet4f s1=pmadd(p4f_asin1, z1, p4f_asin2);\n    Packet4f s2=pmadd(s1, z1, p4f_asin3);\n    Packet4f s3=pmadd(s2,z1, p4f_asin4);\n    Packet4f s4=pmadd(s3,z1, p4f_asin5);\n    Packet4f temp=pmul(s4,z1);//not really a madd but a mul by z so that the next term can be a madd\n    z1=pmadd(temp,x1,x1);\n    z1=padd(z1,z1);\n    z1=psub(p4f_pi_over_2,z1);\n    }\n\n    {\n//the core series expansion \n    Packet4f x2=a;\n    z2=pmul(x2,x2);\n    Packet4f s1=pmadd(p4f_asin1, z2, p4f_asin2);\n    Packet4f s2=pmadd(s1, z2, p4f_asin3);\n    Packet4f s3=pmadd(s2,z2, p4f_asin4);\n    Packet4f s4=pmadd(s3,z2, p4f_asin5);\n    Packet4f temp=pmul(s4,z2);//not really a madd but a mul by z so that the next term can be a madd\n    z2=pmadd(temp,x2,x2);\n    }\n\n/* select the correct result from the two branch evaluations */\n  z1  = _mm_and_ps(branch_mask, z1);\n  z2  = _mm_andnot_ps(branch_mask, z2);\n  Packet4f z  = _mm_or_ps(z1,z2);\n\n/* update the sign */\n  return _mm_xor_ps(z, sign_bit);\n}\n\n#endif // EIGEN_VECTORIZE_SSE\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_MOREVECTORIZATION_MATHFUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/NonLinearOptimization/HybridNonLinearSolver.h",
    "content": "// -*- coding: utf-8\n// vim: set fileencoding=utf-8\n\n// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_HYBRIDNONLINEARSOLVER_H\n#define EIGEN_HYBRIDNONLINEARSOLVER_H\n\nnamespace Eigen { \n\nnamespace HybridNonLinearSolverSpace { \n    enum Status {\n        Running = -1,\n        ImproperInputParameters = 0,\n        RelativeErrorTooSmall = 1,\n        TooManyFunctionEvaluation = 2,\n        TolTooSmall = 3,\n        NotMakingProgressJacobian = 4,\n        NotMakingProgressIterations = 5,\n        UserAsked = 6\n    };\n}\n\n/**\n  * \\ingroup NonLinearOptimization_Module\n  * \\brief Finds a zero of a system of n\n  * nonlinear functions in n variables by a modification of the Powell\n  * hybrid method (\"dogleg\").\n  *\n  * The user must provide a subroutine which calculates the\n  * functions. The Jacobian is either provided by the user, or approximated\n  * using a forward-difference method.\n  *\n  */\ntemplate<typename FunctorType, typename Scalar=double>\nclass HybridNonLinearSolver\n{\npublic:\n    typedef DenseIndex Index;\n\n    HybridNonLinearSolver(FunctorType &_functor)\n        : functor(_functor) { nfev=njev=iter = 0;  fnorm= 0.; useExternalScaling=false;}\n\n    struct Parameters {\n        Parameters()\n            : factor(Scalar(100.))\n            , maxfev(1000)\n            , xtol(numext::sqrt(NumTraits<Scalar>::epsilon()))\n            , nb_of_subdiagonals(-1)\n            , nb_of_superdiagonals(-1)\n            , epsfcn(Scalar(0.)) {}\n        Scalar factor;\n        Index maxfev;   // maximum number of function evaluation\n        Scalar xtol;\n        Index nb_of_subdiagonals;\n        Index nb_of_superdiagonals;\n        Scalar epsfcn;\n    };\n    typedef Matrix< Scalar, Dynamic, 1 > FVectorType;\n    typedef Matrix< Scalar, Dynamic, Dynamic > JacobianType;\n    /* TODO: if eigen provides a triangular storage, use it here */\n    typedef Matrix< Scalar, Dynamic, Dynamic > UpperTriangularType;\n\n    HybridNonLinearSolverSpace::Status hybrj1(\n            FVectorType  &x,\n            const Scalar tol = numext::sqrt(NumTraits<Scalar>::epsilon())\n            );\n\n    HybridNonLinearSolverSpace::Status solveInit(FVectorType  &x);\n    HybridNonLinearSolverSpace::Status solveOneStep(FVectorType  &x);\n    HybridNonLinearSolverSpace::Status solve(FVectorType  &x);\n\n    HybridNonLinearSolverSpace::Status hybrd1(\n            FVectorType  &x,\n            const Scalar tol = numext::sqrt(NumTraits<Scalar>::epsilon())\n            );\n\n    HybridNonLinearSolverSpace::Status solveNumericalDiffInit(FVectorType  &x);\n    HybridNonLinearSolverSpace::Status solveNumericalDiffOneStep(FVectorType  &x);\n    HybridNonLinearSolverSpace::Status solveNumericalDiff(FVectorType  &x);\n\n    void resetParameters(void) { parameters = Parameters(); }\n    Parameters parameters;\n    FVectorType  fvec, qtf, diag;\n    JacobianType fjac;\n    UpperTriangularType R;\n    Index nfev;\n    Index njev;\n    Index iter;\n    Scalar fnorm;\n    bool useExternalScaling; \nprivate:\n    FunctorType &functor;\n    Index n;\n    Scalar sum;\n    bool sing;\n    Scalar temp;\n    Scalar delta;\n    bool jeval;\n    Index ncsuc;\n    Scalar ratio;\n    Scalar pnorm, xnorm, fnorm1;\n    Index nslow1, nslow2;\n    Index ncfail;\n    Scalar actred, prered;\n    FVectorType wa1, wa2, wa3, wa4;\n\n    HybridNonLinearSolver& operator=(const HybridNonLinearSolver&);\n};\n\n\n\ntemplate<typename FunctorType, typename Scalar>\nHybridNonLinearSolverSpace::Status\nHybridNonLinearSolver<FunctorType,Scalar>::hybrj1(\n        FVectorType  &x,\n        const Scalar tol\n        )\n{\n    n = x.size();\n\n    /* check the input parameters for errors. */\n    if (n <= 0 || tol < 0.)\n        return HybridNonLinearSolverSpace::ImproperInputParameters;\n\n    resetParameters();\n    parameters.maxfev = 100*(n+1);\n    parameters.xtol = tol;\n    diag.setConstant(n, 1.);\n    useExternalScaling = true;\n    return solve(x);\n}\n\ntemplate<typename FunctorType, typename Scalar>\nHybridNonLinearSolverSpace::Status\nHybridNonLinearSolver<FunctorType,Scalar>::solveInit(FVectorType  &x)\n{\n    n = x.size();\n\n    wa1.resize(n); wa2.resize(n); wa3.resize(n); wa4.resize(n);\n    fvec.resize(n);\n    qtf.resize(n);\n    fjac.resize(n, n);\n    if (!useExternalScaling)\n        diag.resize(n);\n    eigen_assert( (!useExternalScaling || diag.size()==n) && \"When useExternalScaling is set, the caller must provide a valid 'diag'\");\n\n    /* Function Body */\n    nfev = 0;\n    njev = 0;\n\n    /*     check the input parameters for errors. */\n    if (n <= 0 || parameters.xtol < 0. || parameters.maxfev <= 0 || parameters.factor <= 0. )\n        return HybridNonLinearSolverSpace::ImproperInputParameters;\n    if (useExternalScaling)\n        for (Index j = 0; j < n; ++j)\n            if (diag[j] <= 0.)\n                return HybridNonLinearSolverSpace::ImproperInputParameters;\n\n    /*     evaluate the function at the starting point */\n    /*     and calculate its norm. */\n    nfev = 1;\n    if ( functor(x, fvec) < 0)\n        return HybridNonLinearSolverSpace::UserAsked;\n    fnorm = fvec.stableNorm();\n\n    /*     initialize iteration counter and monitors. */\n    iter = 1;\n    ncsuc = 0;\n    ncfail = 0;\n    nslow1 = 0;\n    nslow2 = 0;\n\n    return HybridNonLinearSolverSpace::Running;\n}\n\ntemplate<typename FunctorType, typename Scalar>\nHybridNonLinearSolverSpace::Status\nHybridNonLinearSolver<FunctorType,Scalar>::solveOneStep(FVectorType  &x)\n{\n    using std::abs;\n    \n    eigen_assert(x.size()==n); // check the caller is not cheating us\n\n    Index j;\n    std::vector<JacobiRotation<Scalar> > v_givens(n), w_givens(n);\n\n    jeval = true;\n\n    /* calculate the jacobian matrix. */\n    if ( functor.df(x, fjac) < 0)\n        return HybridNonLinearSolverSpace::UserAsked;\n    ++njev;\n\n    wa2 = fjac.colwise().blueNorm();\n\n    /* on the first iteration and if external scaling is not used, scale according */\n    /* to the norms of the columns of the initial jacobian. */\n    if (iter == 1) {\n        if (!useExternalScaling)\n            for (j = 0; j < n; ++j)\n                diag[j] = (wa2[j]==0.) ? 1. : wa2[j];\n\n        /* on the first iteration, calculate the norm of the scaled x */\n        /* and initialize the step bound delta. */\n        xnorm = diag.cwiseProduct(x).stableNorm();\n        delta = parameters.factor * xnorm;\n        if (delta == 0.)\n            delta = parameters.factor;\n    }\n\n    /* compute the qr factorization of the jacobian. */\n    HouseholderQR<JacobianType> qrfac(fjac); // no pivoting:\n\n    /* copy the triangular factor of the qr factorization into r. */\n    R = qrfac.matrixQR();\n\n    /* accumulate the orthogonal factor in fjac. */\n    fjac = qrfac.householderQ();\n\n    /* form (q transpose)*fvec and store in qtf. */\n    qtf = fjac.transpose() * fvec;\n\n    /* rescale if necessary. */\n    if (!useExternalScaling)\n        diag = diag.cwiseMax(wa2);\n\n    while (true) {\n        /* determine the direction p. */\n        internal::dogleg<Scalar>(R, diag, qtf, delta, wa1);\n\n        /* store the direction p and x + p. calculate the norm of p. */\n        wa1 = -wa1;\n        wa2 = x + wa1;\n        pnorm = diag.cwiseProduct(wa1).stableNorm();\n\n        /* on the first iteration, adjust the initial step bound. */\n        if (iter == 1)\n            delta = (std::min)(delta,pnorm);\n\n        /* evaluate the function at x + p and calculate its norm. */\n        if ( functor(wa2, wa4) < 0)\n            return HybridNonLinearSolverSpace::UserAsked;\n        ++nfev;\n        fnorm1 = wa4.stableNorm();\n\n        /* compute the scaled actual reduction. */\n        actred = -1.;\n        if (fnorm1 < fnorm) /* Computing 2nd power */\n            actred = 1. - numext::abs2(fnorm1 / fnorm);\n\n        /* compute the scaled predicted reduction. */\n        wa3 = R.template triangularView<Upper>()*wa1 + qtf;\n        temp = wa3.stableNorm();\n        prered = 0.;\n        if (temp < fnorm) /* Computing 2nd power */\n            prered = 1. - numext::abs2(temp / fnorm);\n\n        /* compute the ratio of the actual to the predicted reduction. */\n        ratio = 0.;\n        if (prered > 0.)\n            ratio = actred / prered;\n\n        /* update the step bound. */\n        if (ratio < Scalar(.1)) {\n            ncsuc = 0;\n            ++ncfail;\n            delta = Scalar(.5) * delta;\n        } else {\n            ncfail = 0;\n            ++ncsuc;\n            if (ratio >= Scalar(.5) || ncsuc > 1)\n                delta = (std::max)(delta, pnorm / Scalar(.5));\n            if (abs(ratio - 1.) <= Scalar(.1)) {\n                delta = pnorm / Scalar(.5);\n            }\n        }\n\n        /* test for successful iteration. */\n        if (ratio >= Scalar(1e-4)) {\n            /* successful iteration. update x, fvec, and their norms. */\n            x = wa2;\n            wa2 = diag.cwiseProduct(x);\n            fvec = wa4;\n            xnorm = wa2.stableNorm();\n            fnorm = fnorm1;\n            ++iter;\n        }\n\n        /* determine the progress of the iteration. */\n        ++nslow1;\n        if (actred >= Scalar(.001))\n            nslow1 = 0;\n        if (jeval)\n            ++nslow2;\n        if (actred >= Scalar(.1))\n            nslow2 = 0;\n\n        /* test for convergence. */\n        if (delta <= parameters.xtol * xnorm || fnorm == 0.)\n            return HybridNonLinearSolverSpace::RelativeErrorTooSmall;\n\n        /* tests for termination and stringent tolerances. */\n        if (nfev >= parameters.maxfev)\n            return HybridNonLinearSolverSpace::TooManyFunctionEvaluation;\n        if (Scalar(.1) * (std::max)(Scalar(.1) * delta, pnorm) <= NumTraits<Scalar>::epsilon() * xnorm)\n            return HybridNonLinearSolverSpace::TolTooSmall;\n        if (nslow2 == 5)\n            return HybridNonLinearSolverSpace::NotMakingProgressJacobian;\n        if (nslow1 == 10)\n            return HybridNonLinearSolverSpace::NotMakingProgressIterations;\n\n        /* criterion for recalculating jacobian. */\n        if (ncfail == 2)\n            break; // leave inner loop and go for the next outer loop iteration\n\n        /* calculate the rank one modification to the jacobian */\n        /* and update qtf if necessary. */\n        wa1 = diag.cwiseProduct( diag.cwiseProduct(wa1)/pnorm );\n        wa2 = fjac.transpose() * wa4;\n        if (ratio >= Scalar(1e-4))\n            qtf = wa2;\n        wa2 = (wa2-wa3)/pnorm;\n\n        /* compute the qr factorization of the updated jacobian. */\n        internal::r1updt<Scalar>(R, wa1, v_givens, w_givens, wa2, wa3, &sing);\n        internal::r1mpyq<Scalar>(n, n, fjac.data(), v_givens, w_givens);\n        internal::r1mpyq<Scalar>(1, n, qtf.data(), v_givens, w_givens);\n\n        jeval = false;\n    }\n    return HybridNonLinearSolverSpace::Running;\n}\n\ntemplate<typename FunctorType, typename Scalar>\nHybridNonLinearSolverSpace::Status\nHybridNonLinearSolver<FunctorType,Scalar>::solve(FVectorType  &x)\n{\n    HybridNonLinearSolverSpace::Status status = solveInit(x);\n    if (status==HybridNonLinearSolverSpace::ImproperInputParameters)\n        return status;\n    while (status==HybridNonLinearSolverSpace::Running)\n        status = solveOneStep(x);\n    return status;\n}\n\n\n\ntemplate<typename FunctorType, typename Scalar>\nHybridNonLinearSolverSpace::Status\nHybridNonLinearSolver<FunctorType,Scalar>::hybrd1(\n        FVectorType  &x,\n        const Scalar tol\n        )\n{\n    n = x.size();\n\n    /* check the input parameters for errors. */\n    if (n <= 0 || tol < 0.)\n        return HybridNonLinearSolverSpace::ImproperInputParameters;\n\n    resetParameters();\n    parameters.maxfev = 200*(n+1);\n    parameters.xtol = tol;\n\n    diag.setConstant(n, 1.);\n    useExternalScaling = true;\n    return solveNumericalDiff(x);\n}\n\ntemplate<typename FunctorType, typename Scalar>\nHybridNonLinearSolverSpace::Status\nHybridNonLinearSolver<FunctorType,Scalar>::solveNumericalDiffInit(FVectorType  &x)\n{\n    n = x.size();\n\n    if (parameters.nb_of_subdiagonals<0) parameters.nb_of_subdiagonals= n-1;\n    if (parameters.nb_of_superdiagonals<0) parameters.nb_of_superdiagonals= n-1;\n\n    wa1.resize(n); wa2.resize(n); wa3.resize(n); wa4.resize(n);\n    qtf.resize(n);\n    fjac.resize(n, n);\n    fvec.resize(n);\n    if (!useExternalScaling)\n        diag.resize(n);\n    eigen_assert( (!useExternalScaling || diag.size()==n) && \"When useExternalScaling is set, the caller must provide a valid 'diag'\");\n\n    /* Function Body */\n    nfev = 0;\n    njev = 0;\n\n    /*     check the input parameters for errors. */\n    if (n <= 0 || parameters.xtol < 0. || parameters.maxfev <= 0 || parameters.nb_of_subdiagonals< 0 || parameters.nb_of_superdiagonals< 0 || parameters.factor <= 0. )\n        return HybridNonLinearSolverSpace::ImproperInputParameters;\n    if (useExternalScaling)\n        for (Index j = 0; j < n; ++j)\n            if (diag[j] <= 0.)\n                return HybridNonLinearSolverSpace::ImproperInputParameters;\n\n    /*     evaluate the function at the starting point */\n    /*     and calculate its norm. */\n    nfev = 1;\n    if ( functor(x, fvec) < 0)\n        return HybridNonLinearSolverSpace::UserAsked;\n    fnorm = fvec.stableNorm();\n\n    /*     initialize iteration counter and monitors. */\n    iter = 1;\n    ncsuc = 0;\n    ncfail = 0;\n    nslow1 = 0;\n    nslow2 = 0;\n\n    return HybridNonLinearSolverSpace::Running;\n}\n\ntemplate<typename FunctorType, typename Scalar>\nHybridNonLinearSolverSpace::Status\nHybridNonLinearSolver<FunctorType,Scalar>::solveNumericalDiffOneStep(FVectorType  &x)\n{\n    using std::sqrt;\n    using std::abs;\n    \n    assert(x.size()==n); // check the caller is not cheating us\n\n    Index j;\n    std::vector<JacobiRotation<Scalar> > v_givens(n), w_givens(n);\n\n    jeval = true;\n    if (parameters.nb_of_subdiagonals<0) parameters.nb_of_subdiagonals= n-1;\n    if (parameters.nb_of_superdiagonals<0) parameters.nb_of_superdiagonals= n-1;\n\n    /* calculate the jacobian matrix. */\n    if (internal::fdjac1(functor, x, fvec, fjac, parameters.nb_of_subdiagonals, parameters.nb_of_superdiagonals, parameters.epsfcn) <0)\n        return HybridNonLinearSolverSpace::UserAsked;\n    nfev += (std::min)(parameters.nb_of_subdiagonals+parameters.nb_of_superdiagonals+ 1, n);\n\n    wa2 = fjac.colwise().blueNorm();\n\n    /* on the first iteration and if external scaling is not used, scale according */\n    /* to the norms of the columns of the initial jacobian. */\n    if (iter == 1) {\n        if (!useExternalScaling)\n            for (j = 0; j < n; ++j)\n                diag[j] = (wa2[j]==0.) ? 1. : wa2[j];\n\n        /* on the first iteration, calculate the norm of the scaled x */\n        /* and initialize the step bound delta. */\n        xnorm = diag.cwiseProduct(x).stableNorm();\n        delta = parameters.factor * xnorm;\n        if (delta == 0.)\n            delta = parameters.factor;\n    }\n\n    /* compute the qr factorization of the jacobian. */\n    HouseholderQR<JacobianType> qrfac(fjac); // no pivoting:\n\n    /* copy the triangular factor of the qr factorization into r. */\n    R = qrfac.matrixQR();\n\n    /* accumulate the orthogonal factor in fjac. */\n    fjac = qrfac.householderQ();\n\n    /* form (q transpose)*fvec and store in qtf. */\n    qtf = fjac.transpose() * fvec;\n\n    /* rescale if necessary. */\n    if (!useExternalScaling)\n        diag = diag.cwiseMax(wa2);\n\n    while (true) {\n        /* determine the direction p. */\n        internal::dogleg<Scalar>(R, diag, qtf, delta, wa1);\n\n        /* store the direction p and x + p. calculate the norm of p. */\n        wa1 = -wa1;\n        wa2 = x + wa1;\n        pnorm = diag.cwiseProduct(wa1).stableNorm();\n\n        /* on the first iteration, adjust the initial step bound. */\n        if (iter == 1)\n            delta = (std::min)(delta,pnorm);\n\n        /* evaluate the function at x + p and calculate its norm. */\n        if ( functor(wa2, wa4) < 0)\n            return HybridNonLinearSolverSpace::UserAsked;\n        ++nfev;\n        fnorm1 = wa4.stableNorm();\n\n        /* compute the scaled actual reduction. */\n        actred = -1.;\n        if (fnorm1 < fnorm) /* Computing 2nd power */\n            actred = 1. - numext::abs2(fnorm1 / fnorm);\n\n        /* compute the scaled predicted reduction. */\n        wa3 = R.template triangularView<Upper>()*wa1 + qtf;\n        temp = wa3.stableNorm();\n        prered = 0.;\n        if (temp < fnorm) /* Computing 2nd power */\n            prered = 1. - numext::abs2(temp / fnorm);\n\n        /* compute the ratio of the actual to the predicted reduction. */\n        ratio = 0.;\n        if (prered > 0.)\n            ratio = actred / prered;\n\n        /* update the step bound. */\n        if (ratio < Scalar(.1)) {\n            ncsuc = 0;\n            ++ncfail;\n            delta = Scalar(.5) * delta;\n        } else {\n            ncfail = 0;\n            ++ncsuc;\n            if (ratio >= Scalar(.5) || ncsuc > 1)\n                delta = (std::max)(delta, pnorm / Scalar(.5));\n            if (abs(ratio - 1.) <= Scalar(.1)) {\n                delta = pnorm / Scalar(.5);\n            }\n        }\n\n        /* test for successful iteration. */\n        if (ratio >= Scalar(1e-4)) {\n            /* successful iteration. update x, fvec, and their norms. */\n            x = wa2;\n            wa2 = diag.cwiseProduct(x);\n            fvec = wa4;\n            xnorm = wa2.stableNorm();\n            fnorm = fnorm1;\n            ++iter;\n        }\n\n        /* determine the progress of the iteration. */\n        ++nslow1;\n        if (actred >= Scalar(.001))\n            nslow1 = 0;\n        if (jeval)\n            ++nslow2;\n        if (actred >= Scalar(.1))\n            nslow2 = 0;\n\n        /* test for convergence. */\n        if (delta <= parameters.xtol * xnorm || fnorm == 0.)\n            return HybridNonLinearSolverSpace::RelativeErrorTooSmall;\n\n        /* tests for termination and stringent tolerances. */\n        if (nfev >= parameters.maxfev)\n            return HybridNonLinearSolverSpace::TooManyFunctionEvaluation;\n        if (Scalar(.1) * (std::max)(Scalar(.1) * delta, pnorm) <= NumTraits<Scalar>::epsilon() * xnorm)\n            return HybridNonLinearSolverSpace::TolTooSmall;\n        if (nslow2 == 5)\n            return HybridNonLinearSolverSpace::NotMakingProgressJacobian;\n        if (nslow1 == 10)\n            return HybridNonLinearSolverSpace::NotMakingProgressIterations;\n\n        /* criterion for recalculating jacobian. */\n        if (ncfail == 2)\n            break; // leave inner loop and go for the next outer loop iteration\n\n        /* calculate the rank one modification to the jacobian */\n        /* and update qtf if necessary. */\n        wa1 = diag.cwiseProduct( diag.cwiseProduct(wa1)/pnorm );\n        wa2 = fjac.transpose() * wa4;\n        if (ratio >= Scalar(1e-4))\n            qtf = wa2;\n        wa2 = (wa2-wa3)/pnorm;\n\n        /* compute the qr factorization of the updated jacobian. */\n        internal::r1updt<Scalar>(R, wa1, v_givens, w_givens, wa2, wa3, &sing);\n        internal::r1mpyq<Scalar>(n, n, fjac.data(), v_givens, w_givens);\n        internal::r1mpyq<Scalar>(1, n, qtf.data(), v_givens, w_givens);\n\n        jeval = false;\n    }\n    return HybridNonLinearSolverSpace::Running;\n}\n\ntemplate<typename FunctorType, typename Scalar>\nHybridNonLinearSolverSpace::Status\nHybridNonLinearSolver<FunctorType,Scalar>::solveNumericalDiff(FVectorType  &x)\n{\n    HybridNonLinearSolverSpace::Status status = solveNumericalDiffInit(x);\n    if (status==HybridNonLinearSolverSpace::ImproperInputParameters)\n        return status;\n    while (status==HybridNonLinearSolverSpace::Running)\n        status = solveNumericalDiffOneStep(x);\n    return status;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_HYBRIDNONLINEARSOLVER_H\n\n//vim: ai ts=4 sts=4 et sw=4\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/NonLinearOptimization/LevenbergMarquardt.h",
    "content": "// -*- coding: utf-8\n// vim: set fileencoding=utf-8\n\n// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_LEVENBERGMARQUARDT__H\n#define EIGEN_LEVENBERGMARQUARDT__H\n\nnamespace Eigen { \n\nnamespace LevenbergMarquardtSpace {\n    enum Status {\n        NotStarted = -2,\n        Running = -1,\n        ImproperInputParameters = 0,\n        RelativeReductionTooSmall = 1,\n        RelativeErrorTooSmall = 2,\n        RelativeErrorAndReductionTooSmall = 3,\n        CosinusTooSmall = 4,\n        TooManyFunctionEvaluation = 5,\n        FtolTooSmall = 6,\n        XtolTooSmall = 7,\n        GtolTooSmall = 8,\n        UserAsked = 9\n    };\n}\n\n\n\n/**\n  * \\ingroup NonLinearOptimization_Module\n  * \\brief Performs non linear optimization over a non-linear function,\n  * using a variant of the Levenberg Marquardt algorithm.\n  *\n  * Check wikipedia for more information.\n  * http://en.wikipedia.org/wiki/Levenberg%E2%80%93Marquardt_algorithm\n  */\ntemplate<typename FunctorType, typename Scalar=double>\nclass LevenbergMarquardt\n{\n    static Scalar sqrt_epsilon()\n    {\n      using std::sqrt;\n      return sqrt(NumTraits<Scalar>::epsilon());\n    }\n    \npublic:\n    LevenbergMarquardt(FunctorType &_functor)\n        : functor(_functor) { nfev = njev = iter = 0;  fnorm = gnorm = 0.; useExternalScaling=false; }\n\n    typedef DenseIndex Index;\n    \n    struct Parameters {\n        Parameters()\n            : factor(Scalar(100.))\n            , maxfev(400)\n            , ftol(sqrt_epsilon())\n            , xtol(sqrt_epsilon())\n            , gtol(Scalar(0.))\n            , epsfcn(Scalar(0.)) {}\n        Scalar factor;\n        Index maxfev;   // maximum number of function evaluation\n        Scalar ftol;\n        Scalar xtol;\n        Scalar gtol;\n        Scalar epsfcn;\n    };\n\n    typedef Matrix< Scalar, Dynamic, 1 > FVectorType;\n    typedef Matrix< Scalar, Dynamic, Dynamic > JacobianType;\n\n    LevenbergMarquardtSpace::Status lmder1(\n            FVectorType &x,\n            const Scalar tol = sqrt_epsilon()\n            );\n\n    LevenbergMarquardtSpace::Status minimize(FVectorType &x);\n    LevenbergMarquardtSpace::Status minimizeInit(FVectorType &x);\n    LevenbergMarquardtSpace::Status minimizeOneStep(FVectorType &x);\n\n    static LevenbergMarquardtSpace::Status lmdif1(\n            FunctorType &functor,\n            FVectorType &x,\n            Index *nfev,\n            const Scalar tol = sqrt_epsilon()\n            );\n\n    LevenbergMarquardtSpace::Status lmstr1(\n            FVectorType  &x,\n            const Scalar tol = sqrt_epsilon()\n            );\n\n    LevenbergMarquardtSpace::Status minimizeOptimumStorage(FVectorType  &x);\n    LevenbergMarquardtSpace::Status minimizeOptimumStorageInit(FVectorType  &x);\n    LevenbergMarquardtSpace::Status minimizeOptimumStorageOneStep(FVectorType  &x);\n\n    void resetParameters(void) { parameters = Parameters(); }\n\n    Parameters parameters;\n    FVectorType  fvec, qtf, diag;\n    JacobianType fjac;\n    PermutationMatrix<Dynamic,Dynamic> permutation;\n    Index nfev;\n    Index njev;\n    Index iter;\n    Scalar fnorm, gnorm;\n    bool useExternalScaling; \n\n    Scalar lm_param(void) { return par; }\nprivate:\n    \n    FunctorType &functor;\n    Index n;\n    Index m;\n    FVectorType wa1, wa2, wa3, wa4;\n\n    Scalar par, sum;\n    Scalar temp, temp1, temp2;\n    Scalar delta;\n    Scalar ratio;\n    Scalar pnorm, xnorm, fnorm1, actred, dirder, prered;\n\n    LevenbergMarquardt& operator=(const LevenbergMarquardt&);\n};\n\ntemplate<typename FunctorType, typename Scalar>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType,Scalar>::lmder1(\n        FVectorType  &x,\n        const Scalar tol\n        )\n{\n    n = x.size();\n    m = functor.values();\n\n    /* check the input parameters for errors. */\n    if (n <= 0 || m < n || tol < 0.)\n        return LevenbergMarquardtSpace::ImproperInputParameters;\n\n    resetParameters();\n    parameters.ftol = tol;\n    parameters.xtol = tol;\n    parameters.maxfev = 100*(n+1);\n\n    return minimize(x);\n}\n\n\ntemplate<typename FunctorType, typename Scalar>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType,Scalar>::minimize(FVectorType  &x)\n{\n    LevenbergMarquardtSpace::Status status = minimizeInit(x);\n    if (status==LevenbergMarquardtSpace::ImproperInputParameters)\n        return status;\n    do {\n        status = minimizeOneStep(x);\n    } while (status==LevenbergMarquardtSpace::Running);\n    return status;\n}\n\ntemplate<typename FunctorType, typename Scalar>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType,Scalar>::minimizeInit(FVectorType  &x)\n{\n    n = x.size();\n    m = functor.values();\n\n    wa1.resize(n); wa2.resize(n); wa3.resize(n);\n    wa4.resize(m);\n    fvec.resize(m);\n    fjac.resize(m, n);\n    if (!useExternalScaling)\n        diag.resize(n);\n    eigen_assert( (!useExternalScaling || diag.size()==n) && \"When useExternalScaling is set, the caller must provide a valid 'diag'\");\n    qtf.resize(n);\n\n    /* Function Body */\n    nfev = 0;\n    njev = 0;\n\n    /*     check the input parameters for errors. */\n    if (n <= 0 || m < n || parameters.ftol < 0. || parameters.xtol < 0. || parameters.gtol < 0. || parameters.maxfev <= 0 || parameters.factor <= 0.)\n        return LevenbergMarquardtSpace::ImproperInputParameters;\n\n    if (useExternalScaling)\n        for (Index j = 0; j < n; ++j)\n            if (diag[j] <= 0.)\n                return LevenbergMarquardtSpace::ImproperInputParameters;\n\n    /*     evaluate the function at the starting point */\n    /*     and calculate its norm. */\n    nfev = 1;\n    if ( functor(x, fvec) < 0)\n        return LevenbergMarquardtSpace::UserAsked;\n    fnorm = fvec.stableNorm();\n\n    /*     initialize levenberg-marquardt parameter and iteration counter. */\n    par = 0.;\n    iter = 1;\n\n    return LevenbergMarquardtSpace::NotStarted;\n}\n\ntemplate<typename FunctorType, typename Scalar>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType,Scalar>::minimizeOneStep(FVectorType  &x)\n{\n    using std::abs;\n    using std::sqrt;\n\n    eigen_assert(x.size()==n); // check the caller is not cheating us\n\n    /* calculate the jacobian matrix. */\n    Index df_ret = functor.df(x, fjac);\n    if (df_ret<0)\n        return LevenbergMarquardtSpace::UserAsked;\n    if (df_ret>0)\n        // numerical diff, we evaluated the function df_ret times\n        nfev += df_ret;\n    else njev++;\n\n    /* compute the qr factorization of the jacobian. */\n    wa2 = fjac.colwise().blueNorm();\n    ColPivHouseholderQR<JacobianType> qrfac(fjac);\n    fjac = qrfac.matrixQR();\n    permutation = qrfac.colsPermutation();\n\n    /* on the first iteration and if external scaling is not used, scale according */\n    /* to the norms of the columns of the initial jacobian. */\n    if (iter == 1) {\n        if (!useExternalScaling)\n            for (Index j = 0; j < n; ++j)\n                diag[j] = (wa2[j]==0.)? 1. : wa2[j];\n\n        /* on the first iteration, calculate the norm of the scaled x */\n        /* and initialize the step bound delta. */\n        xnorm = diag.cwiseProduct(x).stableNorm();\n        delta = parameters.factor * xnorm;\n        if (delta == 0.)\n            delta = parameters.factor;\n    }\n\n    /* form (q transpose)*fvec and store the first n components in */\n    /* qtf. */\n    wa4 = fvec;\n    wa4.applyOnTheLeft(qrfac.householderQ().adjoint());\n    qtf = wa4.head(n);\n\n    /* compute the norm of the scaled gradient. */\n    gnorm = 0.;\n    if (fnorm != 0.)\n        for (Index j = 0; j < n; ++j)\n            if (wa2[permutation.indices()[j]] != 0.)\n                gnorm = (std::max)(gnorm, abs( fjac.col(j).head(j+1).dot(qtf.head(j+1)/fnorm) / wa2[permutation.indices()[j]]));\n\n    /* test for convergence of the gradient norm. */\n    if (gnorm <= parameters.gtol)\n        return LevenbergMarquardtSpace::CosinusTooSmall;\n\n    /* rescale if necessary. */\n    if (!useExternalScaling)\n        diag = diag.cwiseMax(wa2);\n\n    do {\n\n        /* determine the levenberg-marquardt parameter. */\n        internal::lmpar2<Scalar>(qrfac, diag, qtf, delta, par, wa1);\n\n        /* store the direction p and x + p. calculate the norm of p. */\n        wa1 = -wa1;\n        wa2 = x + wa1;\n        pnorm = diag.cwiseProduct(wa1).stableNorm();\n\n        /* on the first iteration, adjust the initial step bound. */\n        if (iter == 1)\n            delta = (std::min)(delta,pnorm);\n\n        /* evaluate the function at x + p and calculate its norm. */\n        if ( functor(wa2, wa4) < 0)\n            return LevenbergMarquardtSpace::UserAsked;\n        ++nfev;\n        fnorm1 = wa4.stableNorm();\n\n        /* compute the scaled actual reduction. */\n        actred = -1.;\n        if (Scalar(.1) * fnorm1 < fnorm)\n            actred = 1. - numext::abs2(fnorm1 / fnorm);\n\n        /* compute the scaled predicted reduction and */\n        /* the scaled directional derivative. */\n        wa3 = fjac.template triangularView<Upper>() * (qrfac.colsPermutation().inverse() *wa1);\n        temp1 = numext::abs2(wa3.stableNorm() / fnorm);\n        temp2 = numext::abs2(sqrt(par) * pnorm / fnorm);\n        prered = temp1 + temp2 / Scalar(.5);\n        dirder = -(temp1 + temp2);\n\n        /* compute the ratio of the actual to the predicted */\n        /* reduction. */\n        ratio = 0.;\n        if (prered != 0.)\n            ratio = actred / prered;\n\n        /* update the step bound. */\n        if (ratio <= Scalar(.25)) {\n            if (actred >= 0.)\n                temp = Scalar(.5);\n            if (actred < 0.)\n                temp = Scalar(.5) * dirder / (dirder + Scalar(.5) * actred);\n            if (Scalar(.1) * fnorm1 >= fnorm || temp < Scalar(.1))\n                temp = Scalar(.1);\n            /* Computing MIN */\n            delta = temp * (std::min)(delta, pnorm / Scalar(.1));\n            par /= temp;\n        } else if (!(par != 0. && ratio < Scalar(.75))) {\n            delta = pnorm / Scalar(.5);\n            par = Scalar(.5) * par;\n        }\n\n        /* test for successful iteration. */\n        if (ratio >= Scalar(1e-4)) {\n            /* successful iteration. update x, fvec, and their norms. */\n            x = wa2;\n            wa2 = diag.cwiseProduct(x);\n            fvec = wa4;\n            xnorm = wa2.stableNorm();\n            fnorm = fnorm1;\n            ++iter;\n        }\n\n        /* tests for convergence. */\n        if (abs(actred) <= parameters.ftol && prered <= parameters.ftol && Scalar(.5) * ratio <= 1. && delta <= parameters.xtol * xnorm)\n            return LevenbergMarquardtSpace::RelativeErrorAndReductionTooSmall;\n        if (abs(actred) <= parameters.ftol && prered <= parameters.ftol && Scalar(.5) * ratio <= 1.)\n            return LevenbergMarquardtSpace::RelativeReductionTooSmall;\n        if (delta <= parameters.xtol * xnorm)\n            return LevenbergMarquardtSpace::RelativeErrorTooSmall;\n\n        /* tests for termination and stringent tolerances. */\n        if (nfev >= parameters.maxfev)\n            return LevenbergMarquardtSpace::TooManyFunctionEvaluation;\n        if (abs(actred) <= NumTraits<Scalar>::epsilon() && prered <= NumTraits<Scalar>::epsilon() && Scalar(.5) * ratio <= 1.)\n            return LevenbergMarquardtSpace::FtolTooSmall;\n        if (delta <= NumTraits<Scalar>::epsilon() * xnorm)\n            return LevenbergMarquardtSpace::XtolTooSmall;\n        if (gnorm <= NumTraits<Scalar>::epsilon())\n            return LevenbergMarquardtSpace::GtolTooSmall;\n\n    } while (ratio < Scalar(1e-4));\n\n    return LevenbergMarquardtSpace::Running;\n}\n\ntemplate<typename FunctorType, typename Scalar>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType,Scalar>::lmstr1(\n        FVectorType  &x,\n        const Scalar tol\n        )\n{\n    n = x.size();\n    m = functor.values();\n\n    /* check the input parameters for errors. */\n    if (n <= 0 || m < n || tol < 0.)\n        return LevenbergMarquardtSpace::ImproperInputParameters;\n\n    resetParameters();\n    parameters.ftol = tol;\n    parameters.xtol = tol;\n    parameters.maxfev = 100*(n+1);\n\n    return minimizeOptimumStorage(x);\n}\n\ntemplate<typename FunctorType, typename Scalar>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType,Scalar>::minimizeOptimumStorageInit(FVectorType  &x)\n{\n    n = x.size();\n    m = functor.values();\n\n    wa1.resize(n); wa2.resize(n); wa3.resize(n);\n    wa4.resize(m);\n    fvec.resize(m);\n    // Only R is stored in fjac. Q is only used to compute 'qtf', which is\n    // Q.transpose()*rhs. qtf will be updated using givens rotation,\n    // instead of storing them in Q.\n    // The purpose it to only use a nxn matrix, instead of mxn here, so\n    // that we can handle cases where m>>n :\n    fjac.resize(n, n);\n    if (!useExternalScaling)\n        diag.resize(n);\n    eigen_assert( (!useExternalScaling || diag.size()==n) && \"When useExternalScaling is set, the caller must provide a valid 'diag'\");\n    qtf.resize(n);\n\n    /* Function Body */\n    nfev = 0;\n    njev = 0;\n\n    /*     check the input parameters for errors. */\n    if (n <= 0 || m < n || parameters.ftol < 0. || parameters.xtol < 0. || parameters.gtol < 0. || parameters.maxfev <= 0 || parameters.factor <= 0.)\n        return LevenbergMarquardtSpace::ImproperInputParameters;\n\n    if (useExternalScaling)\n        for (Index j = 0; j < n; ++j)\n            if (diag[j] <= 0.)\n                return LevenbergMarquardtSpace::ImproperInputParameters;\n\n    /*     evaluate the function at the starting point */\n    /*     and calculate its norm. */\n    nfev = 1;\n    if ( functor(x, fvec) < 0)\n        return LevenbergMarquardtSpace::UserAsked;\n    fnorm = fvec.stableNorm();\n\n    /*     initialize levenberg-marquardt parameter and iteration counter. */\n    par = 0.;\n    iter = 1;\n\n    return LevenbergMarquardtSpace::NotStarted;\n}\n\n\ntemplate<typename FunctorType, typename Scalar>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType,Scalar>::minimizeOptimumStorageOneStep(FVectorType  &x)\n{\n    using std::abs;\n    using std::sqrt;\n    \n    eigen_assert(x.size()==n); // check the caller is not cheating us\n\n    Index i, j;\n    bool sing;\n\n    /* compute the qr factorization of the jacobian matrix */\n    /* calculated one row at a time, while simultaneously */\n    /* forming (q transpose)*fvec and storing the first */\n    /* n components in qtf. */\n    qtf.fill(0.);\n    fjac.fill(0.);\n    Index rownb = 2;\n    for (i = 0; i < m; ++i) {\n        if (functor.df(x, wa3, rownb) < 0) return LevenbergMarquardtSpace::UserAsked;\n        internal::rwupdt<Scalar>(fjac, wa3, qtf, fvec[i]);\n        ++rownb;\n    }\n    ++njev;\n\n    /* if the jacobian is rank deficient, call qrfac to */\n    /* reorder its columns and update the components of qtf. */\n    sing = false;\n    for (j = 0; j < n; ++j) {\n        if (fjac(j,j) == 0.)\n            sing = true;\n        wa2[j] = fjac.col(j).head(j).stableNorm();\n    }\n    permutation.setIdentity(n);\n    if (sing) {\n        wa2 = fjac.colwise().blueNorm();\n        // TODO We have no unit test covering this code path, do not modify\n        // until it is carefully tested\n        ColPivHouseholderQR<JacobianType> qrfac(fjac);\n        fjac = qrfac.matrixQR();\n        wa1 = fjac.diagonal();\n        fjac.diagonal() = qrfac.hCoeffs();\n        permutation = qrfac.colsPermutation();\n        // TODO : avoid this:\n        for(Index ii=0; ii< fjac.cols(); ii++) fjac.col(ii).segment(ii+1, fjac.rows()-ii-1) *= fjac(ii,ii); // rescale vectors\n\n        for (j = 0; j < n; ++j) {\n            if (fjac(j,j) != 0.) {\n                sum = 0.;\n                for (i = j; i < n; ++i)\n                    sum += fjac(i,j) * qtf[i];\n                temp = -sum / fjac(j,j);\n                for (i = j; i < n; ++i)\n                    qtf[i] += fjac(i,j) * temp;\n            }\n            fjac(j,j) = wa1[j];\n        }\n    }\n\n    /* on the first iteration and if external scaling is not used, scale according */\n    /* to the norms of the columns of the initial jacobian. */\n    if (iter == 1) {\n        if (!useExternalScaling)\n            for (j = 0; j < n; ++j)\n                diag[j] = (wa2[j]==0.)? 1. : wa2[j];\n\n        /* on the first iteration, calculate the norm of the scaled x */\n        /* and initialize the step bound delta. */\n        xnorm = diag.cwiseProduct(x).stableNorm();\n        delta = parameters.factor * xnorm;\n        if (delta == 0.)\n            delta = parameters.factor;\n    }\n\n    /* compute the norm of the scaled gradient. */\n    gnorm = 0.;\n    if (fnorm != 0.)\n        for (j = 0; j < n; ++j)\n            if (wa2[permutation.indices()[j]] != 0.)\n                gnorm = (std::max)(gnorm, abs( fjac.col(j).head(j+1).dot(qtf.head(j+1)/fnorm) / wa2[permutation.indices()[j]]));\n\n    /* test for convergence of the gradient norm. */\n    if (gnorm <= parameters.gtol)\n        return LevenbergMarquardtSpace::CosinusTooSmall;\n\n    /* rescale if necessary. */\n    if (!useExternalScaling)\n        diag = diag.cwiseMax(wa2);\n\n    do {\n\n        /* determine the levenberg-marquardt parameter. */\n        internal::lmpar<Scalar>(fjac, permutation.indices(), diag, qtf, delta, par, wa1);\n\n        /* store the direction p and x + p. calculate the norm of p. */\n        wa1 = -wa1;\n        wa2 = x + wa1;\n        pnorm = diag.cwiseProduct(wa1).stableNorm();\n\n        /* on the first iteration, adjust the initial step bound. */\n        if (iter == 1)\n            delta = (std::min)(delta,pnorm);\n\n        /* evaluate the function at x + p and calculate its norm. */\n        if ( functor(wa2, wa4) < 0)\n            return LevenbergMarquardtSpace::UserAsked;\n        ++nfev;\n        fnorm1 = wa4.stableNorm();\n\n        /* compute the scaled actual reduction. */\n        actred = -1.;\n        if (Scalar(.1) * fnorm1 < fnorm)\n            actred = 1. - numext::abs2(fnorm1 / fnorm);\n\n        /* compute the scaled predicted reduction and */\n        /* the scaled directional derivative. */\n        wa3 = fjac.topLeftCorner(n,n).template triangularView<Upper>() * (permutation.inverse() * wa1);\n        temp1 = numext::abs2(wa3.stableNorm() / fnorm);\n        temp2 = numext::abs2(sqrt(par) * pnorm / fnorm);\n        prered = temp1 + temp2 / Scalar(.5);\n        dirder = -(temp1 + temp2);\n\n        /* compute the ratio of the actual to the predicted */\n        /* reduction. */\n        ratio = 0.;\n        if (prered != 0.)\n            ratio = actred / prered;\n\n        /* update the step bound. */\n        if (ratio <= Scalar(.25)) {\n            if (actred >= 0.)\n                temp = Scalar(.5);\n            if (actred < 0.)\n                temp = Scalar(.5) * dirder / (dirder + Scalar(.5) * actred);\n            if (Scalar(.1) * fnorm1 >= fnorm || temp < Scalar(.1))\n                temp = Scalar(.1);\n            /* Computing MIN */\n            delta = temp * (std::min)(delta, pnorm / Scalar(.1));\n            par /= temp;\n        } else if (!(par != 0. && ratio < Scalar(.75))) {\n            delta = pnorm / Scalar(.5);\n            par = Scalar(.5) * par;\n        }\n\n        /* test for successful iteration. */\n        if (ratio >= Scalar(1e-4)) {\n            /* successful iteration. update x, fvec, and their norms. */\n            x = wa2;\n            wa2 = diag.cwiseProduct(x);\n            fvec = wa4;\n            xnorm = wa2.stableNorm();\n            fnorm = fnorm1;\n            ++iter;\n        }\n\n        /* tests for convergence. */\n        if (abs(actred) <= parameters.ftol && prered <= parameters.ftol && Scalar(.5) * ratio <= 1. && delta <= parameters.xtol * xnorm)\n            return LevenbergMarquardtSpace::RelativeErrorAndReductionTooSmall;\n        if (abs(actred) <= parameters.ftol && prered <= parameters.ftol && Scalar(.5) * ratio <= 1.)\n            return LevenbergMarquardtSpace::RelativeReductionTooSmall;\n        if (delta <= parameters.xtol * xnorm)\n            return LevenbergMarquardtSpace::RelativeErrorTooSmall;\n\n        /* tests for termination and stringent tolerances. */\n        if (nfev >= parameters.maxfev)\n            return LevenbergMarquardtSpace::TooManyFunctionEvaluation;\n        if (abs(actred) <= NumTraits<Scalar>::epsilon() && prered <= NumTraits<Scalar>::epsilon() && Scalar(.5) * ratio <= 1.)\n            return LevenbergMarquardtSpace::FtolTooSmall;\n        if (delta <= NumTraits<Scalar>::epsilon() * xnorm)\n            return LevenbergMarquardtSpace::XtolTooSmall;\n        if (gnorm <= NumTraits<Scalar>::epsilon())\n            return LevenbergMarquardtSpace::GtolTooSmall;\n\n    } while (ratio < Scalar(1e-4));\n\n    return LevenbergMarquardtSpace::Running;\n}\n\ntemplate<typename FunctorType, typename Scalar>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType,Scalar>::minimizeOptimumStorage(FVectorType  &x)\n{\n    LevenbergMarquardtSpace::Status status = minimizeOptimumStorageInit(x);\n    if (status==LevenbergMarquardtSpace::ImproperInputParameters)\n        return status;\n    do {\n        status = minimizeOptimumStorageOneStep(x);\n    } while (status==LevenbergMarquardtSpace::Running);\n    return status;\n}\n\ntemplate<typename FunctorType, typename Scalar>\nLevenbergMarquardtSpace::Status\nLevenbergMarquardt<FunctorType,Scalar>::lmdif1(\n        FunctorType &functor,\n        FVectorType  &x,\n        Index *nfev,\n        const Scalar tol\n        )\n{\n    Index n = x.size();\n    Index m = functor.values();\n\n    /* check the input parameters for errors. */\n    if (n <= 0 || m < n || tol < 0.)\n        return LevenbergMarquardtSpace::ImproperInputParameters;\n\n    NumericalDiff<FunctorType> numDiff(functor);\n    // embedded LevenbergMarquardt\n    LevenbergMarquardt<NumericalDiff<FunctorType>, Scalar > lm(numDiff);\n    lm.parameters.ftol = tol;\n    lm.parameters.xtol = tol;\n    lm.parameters.maxfev = 200*(n+1);\n\n    LevenbergMarquardtSpace::Status info = LevenbergMarquardtSpace::Status(lm.minimize(x));\n    if (nfev)\n        * nfev = lm.nfev;\n    return info;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_LEVENBERGMARQUARDT__H\n\n//vim: ai ts=4 sts=4 et sw=4\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/NonLinearOptimization/chkder.h",
    "content": "#define chkder_log10e 0.43429448190325182765\n#define chkder_factor 100.\n\nnamespace Eigen { \n\nnamespace internal {\n\ntemplate<typename Scalar>\nvoid chkder(\n        const Matrix< Scalar, Dynamic, 1 >  &x,\n        const Matrix< Scalar, Dynamic, 1 >  &fvec,\n        const Matrix< Scalar, Dynamic, Dynamic > &fjac,\n        Matrix< Scalar, Dynamic, 1 >  &xp,\n        const Matrix< Scalar, Dynamic, 1 >  &fvecp,\n        int mode,\n        Matrix< Scalar, Dynamic, 1 >  &err\n        )\n{\n    using std::sqrt;\n    using std::abs;\n    using std::log;\n    \n    typedef DenseIndex Index;\n\n    const Scalar eps = sqrt(NumTraits<Scalar>::epsilon());\n    const Scalar epsf = chkder_factor * NumTraits<Scalar>::epsilon();\n    const Scalar epslog = chkder_log10e * log(eps);\n    Scalar temp;\n\n    const Index m = fvec.size(), n = x.size();\n\n    if (mode != 2) {\n        /* mode = 1. */\n        xp.resize(n);\n        for (Index j = 0; j < n; ++j) {\n            temp = eps * abs(x[j]);\n            if (temp == 0.)\n                temp = eps;\n            xp[j] = x[j] + temp;\n        }\n    }\n    else {\n        /* mode = 2. */\n        err.setZero(m); \n        for (Index j = 0; j < n; ++j) {\n            temp = abs(x[j]);\n            if (temp == 0.)\n                temp = 1.;\n            err += temp * fjac.col(j);\n        }\n        for (Index i = 0; i < m; ++i) {\n            temp = 1.;\n            if (fvec[i] != 0. && fvecp[i] != 0. && abs(fvecp[i] - fvec[i]) >= epsf * abs(fvec[i]))\n                temp = eps * abs((fvecp[i] - fvec[i]) / eps - err[i]) / (abs(fvec[i]) + abs(fvecp[i]));\n            err[i] = 1.;\n            if (temp > NumTraits<Scalar>::epsilon() && temp < eps)\n                err[i] = (chkder_log10e * log(temp) - epslog) / epslog;\n            if (temp >= eps)\n                err[i] = 0.;\n        }\n    }\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/NonLinearOptimization/covar.h",
    "content": "namespace Eigen { \n\nnamespace internal {\n\ntemplate <typename Scalar>\nvoid covar(\n        Matrix< Scalar, Dynamic, Dynamic > &r,\n        const VectorXi &ipvt,\n        Scalar tol = std::sqrt(NumTraits<Scalar>::epsilon()) )\n{\n    using std::abs;\n    typedef DenseIndex Index;\n\n    /* Local variables */\n    Index i, j, k, l, ii, jj;\n    bool sing;\n    Scalar temp;\n\n    /* Function Body */\n    const Index n = r.cols();\n    const Scalar tolr = tol * abs(r(0,0));\n    Matrix< Scalar, Dynamic, 1 > wa(n);\n    eigen_assert(ipvt.size()==n);\n\n    /* form the inverse of r in the full upper triangle of r. */\n    l = -1;\n    for (k = 0; k < n; ++k)\n        if (abs(r(k,k)) > tolr) {\n            r(k,k) = 1. / r(k,k);\n            for (j = 0; j <= k-1; ++j) {\n                temp = r(k,k) * r(j,k);\n                r(j,k) = 0.;\n                r.col(k).head(j+1) -= r.col(j).head(j+1) * temp;\n            }\n            l = k;\n        }\n\n    /* form the full upper triangle of the inverse of (r transpose)*r */\n    /* in the full upper triangle of r. */\n    for (k = 0; k <= l; ++k) {\n        for (j = 0; j <= k-1; ++j)\n            r.col(j).head(j+1) += r.col(k).head(j+1) * r(j,k);\n        r.col(k).head(k+1) *= r(k,k);\n    }\n\n    /* form the full lower triangle of the covariance matrix */\n    /* in the strict lower triangle of r and in wa. */\n    for (j = 0; j < n; ++j) {\n        jj = ipvt[j];\n        sing = j > l;\n        for (i = 0; i <= j; ++i) {\n            if (sing)\n                r(i,j) = 0.;\n            ii = ipvt[i];\n            if (ii > jj)\n                r(ii,jj) = r(i,j);\n            if (ii < jj)\n                r(jj,ii) = r(i,j);\n        }\n        wa[jj] = r(j,j);\n    }\n\n    /* symmetrize the covariance matrix in r. */\n    r.topLeftCorner(n,n).template triangularView<StrictlyUpper>() = r.topLeftCorner(n,n).transpose();\n    r.diagonal() = wa;\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/NonLinearOptimization/dogleg.h",
    "content": "namespace Eigen { \n\nnamespace internal {\n\ntemplate <typename Scalar>\nvoid dogleg(\n        const Matrix< Scalar, Dynamic, Dynamic >  &qrfac,\n        const Matrix< Scalar, Dynamic, 1 >  &diag,\n        const Matrix< Scalar, Dynamic, 1 >  &qtb,\n        Scalar delta,\n        Matrix< Scalar, Dynamic, 1 >  &x)\n{\n    using std::abs;\n    using std::sqrt;\n    \n    typedef DenseIndex Index;\n\n    /* Local variables */\n    Index i, j;\n    Scalar sum, temp, alpha, bnorm;\n    Scalar gnorm, qnorm;\n    Scalar sgnorm;\n\n    /* Function Body */\n    const Scalar epsmch = NumTraits<Scalar>::epsilon();\n    const Index n = qrfac.cols();\n    eigen_assert(n==qtb.size());\n    eigen_assert(n==x.size());\n    eigen_assert(n==diag.size());\n    Matrix< Scalar, Dynamic, 1 >  wa1(n), wa2(n);\n\n    /* first, calculate the gauss-newton direction. */\n    for (j = n-1; j >=0; --j) {\n        temp = qrfac(j,j);\n        if (temp == 0.) {\n            temp = epsmch * qrfac.col(j).head(j+1).maxCoeff();\n            if (temp == 0.)\n                temp = epsmch;\n        }\n        if (j==n-1)\n            x[j] = qtb[j] / temp;\n        else\n            x[j] = (qtb[j] - qrfac.row(j).tail(n-j-1).dot(x.tail(n-j-1))) / temp;\n    }\n\n    /* test whether the gauss-newton direction is acceptable. */\n    qnorm = diag.cwiseProduct(x).stableNorm();\n    if (qnorm <= delta)\n        return;\n\n    // TODO : this path is not tested by Eigen unit tests\n\n    /* the gauss-newton direction is not acceptable. */\n    /* next, calculate the scaled gradient direction. */\n\n    wa1.fill(0.);\n    for (j = 0; j < n; ++j) {\n        wa1.tail(n-j) += qrfac.row(j).tail(n-j) * qtb[j];\n        wa1[j] /= diag[j];\n    }\n\n    /* calculate the norm of the scaled gradient and test for */\n    /* the special case in which the scaled gradient is zero. */\n    gnorm = wa1.stableNorm();\n    sgnorm = 0.;\n    alpha = delta / qnorm;\n    if (gnorm == 0.)\n        goto algo_end;\n\n    /* calculate the point along the scaled gradient */\n    /* at which the quadratic is minimized. */\n    wa1.array() /= (diag*gnorm).array();\n    // TODO : once unit tests cover this part,:\n    // wa2 = qrfac.template triangularView<Upper>() * wa1;\n    for (j = 0; j < n; ++j) {\n        sum = 0.;\n        for (i = j; i < n; ++i) {\n            sum += qrfac(j,i) * wa1[i];\n        }\n        wa2[j] = sum;\n    }\n    temp = wa2.stableNorm();\n    sgnorm = gnorm / temp / temp;\n\n    /* test whether the scaled gradient direction is acceptable. */\n    alpha = 0.;\n    if (sgnorm >= delta)\n        goto algo_end;\n\n    /* the scaled gradient direction is not acceptable. */\n    /* finally, calculate the point along the dogleg */\n    /* at which the quadratic is minimized. */\n    bnorm = qtb.stableNorm();\n    temp = bnorm / gnorm * (bnorm / qnorm) * (sgnorm / delta);\n    temp = temp - delta / qnorm * numext::abs2(sgnorm / delta) + sqrt(numext::abs2(temp - delta / qnorm) + (1.-numext::abs2(delta / qnorm)) * (1.-numext::abs2(sgnorm / delta)));\n    alpha = delta / qnorm * (1. - numext::abs2(sgnorm / delta)) / temp;\nalgo_end:\n\n    /* form appropriate convex combination of the gauss-newton */\n    /* direction and the scaled gradient direction. */\n    temp = (1.-alpha) * (std::min)(sgnorm,delta);\n    x = temp * wa1 + alpha * x;\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/NonLinearOptimization/fdjac1.h",
    "content": "namespace Eigen { \n\nnamespace internal {\n\ntemplate<typename FunctorType, typename Scalar>\nDenseIndex fdjac1(\n        const FunctorType &Functor,\n        Matrix< Scalar, Dynamic, 1 >  &x,\n        Matrix< Scalar, Dynamic, 1 >  &fvec,\n        Matrix< Scalar, Dynamic, Dynamic > &fjac,\n        DenseIndex ml, DenseIndex mu,\n        Scalar epsfcn)\n{\n    using std::sqrt;\n    using std::abs;\n    \n    typedef DenseIndex Index;\n\n    /* Local variables */\n    Scalar h;\n    Index j, k;\n    Scalar eps, temp;\n    Index msum;\n    int iflag;\n    Index start, length;\n\n    /* Function Body */\n    const Scalar epsmch = NumTraits<Scalar>::epsilon();\n    const Index n = x.size();\n    eigen_assert(fvec.size()==n);\n    Matrix< Scalar, Dynamic, 1 >  wa1(n);\n    Matrix< Scalar, Dynamic, 1 >  wa2(n);\n\n    eps = sqrt((std::max)(epsfcn,epsmch));\n    msum = ml + mu + 1;\n    if (msum >= n) {\n        /* computation of dense approximate jacobian. */\n        for (j = 0; j < n; ++j) {\n            temp = x[j];\n            h = eps * abs(temp);\n            if (h == 0.)\n                h = eps;\n            x[j] = temp + h;\n            iflag = Functor(x, wa1);\n            if (iflag < 0)\n                return iflag;\n            x[j] = temp;\n            fjac.col(j) = (wa1-fvec)/h;\n        }\n\n    }else {\n        /* computation of banded approximate jacobian. */\n        for (k = 0; k < msum; ++k) {\n            for (j = k; (msum<0) ? (j>n): (j<n); j += msum) {\n                wa2[j] = x[j];\n                h = eps * abs(wa2[j]);\n                if (h == 0.) h = eps;\n                x[j] = wa2[j] + h;\n            }\n            iflag = Functor(x, wa1);\n            if (iflag < 0)\n                return iflag;\n            for (j = k; (msum<0) ? (j>n): (j<n); j += msum) {\n                x[j] = wa2[j];\n                h = eps * abs(wa2[j]);\n                if (h == 0.) h = eps;\n                fjac.col(j).setZero();\n                start = std::max<Index>(0,j-mu);\n                length = (std::min)(n-1, j+ml) - start + 1;\n                fjac.col(j).segment(start, length) = ( wa1.segment(start, length)-fvec.segment(start, length))/h;\n            }\n        }\n    }\n    return 0;\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/NonLinearOptimization/lmpar.h",
    "content": "namespace Eigen { \n\nnamespace internal {\n\ntemplate <typename Scalar>\nvoid lmpar(\n        Matrix< Scalar, Dynamic, Dynamic > &r,\n        const VectorXi &ipvt,\n        const Matrix< Scalar, Dynamic, 1 >  &diag,\n        const Matrix< Scalar, Dynamic, 1 >  &qtb,\n        Scalar delta,\n        Scalar &par,\n        Matrix< Scalar, Dynamic, 1 >  &x)\n{\n    using std::abs;\n    using std::sqrt;\n    typedef DenseIndex Index;\n\n    /* Local variables */\n    Index i, j, l;\n    Scalar fp;\n    Scalar parc, parl;\n    Index iter;\n    Scalar temp, paru;\n    Scalar gnorm;\n    Scalar dxnorm;\n\n\n    /* Function Body */\n    const Scalar dwarf = (std::numeric_limits<Scalar>::min)();\n    const Index n = r.cols();\n    eigen_assert(n==diag.size());\n    eigen_assert(n==qtb.size());\n    eigen_assert(n==x.size());\n\n    Matrix< Scalar, Dynamic, 1 >  wa1, wa2;\n\n    /* compute and store in x the gauss-newton direction. if the */\n    /* jacobian is rank-deficient, obtain a least squares solution. */\n    Index nsing = n-1;\n    wa1 = qtb;\n    for (j = 0; j < n; ++j) {\n        if (r(j,j) == 0. && nsing == n-1)\n            nsing = j - 1;\n        if (nsing < n-1)\n            wa1[j] = 0.;\n    }\n    for (j = nsing; j>=0; --j) {\n        wa1[j] /= r(j,j);\n        temp = wa1[j];\n        for (i = 0; i < j ; ++i)\n            wa1[i] -= r(i,j) * temp;\n    }\n\n    for (j = 0; j < n; ++j)\n        x[ipvt[j]] = wa1[j];\n\n    /* initialize the iteration counter. */\n    /* evaluate the function at the origin, and test */\n    /* for acceptance of the gauss-newton direction. */\n    iter = 0;\n    wa2 = diag.cwiseProduct(x);\n    dxnorm = wa2.blueNorm();\n    fp = dxnorm - delta;\n    if (fp <= Scalar(0.1) * delta) {\n        par = 0;\n        return;\n    }\n\n    /* if the jacobian is not rank deficient, the newton */\n    /* step provides a lower bound, parl, for the zero of */\n    /* the function. otherwise set this bound to zero. */\n    parl = 0.;\n    if (nsing >= n-1) {\n        for (j = 0; j < n; ++j) {\n            l = ipvt[j];\n            wa1[j] = diag[l] * (wa2[l] / dxnorm);\n        }\n        // it's actually a triangularView.solveInplace(), though in a weird\n        // way:\n        for (j = 0; j < n; ++j) {\n            Scalar sum = 0.;\n            for (i = 0; i < j; ++i)\n                sum += r(i,j) * wa1[i];\n            wa1[j] = (wa1[j] - sum) / r(j,j);\n        }\n        temp = wa1.blueNorm();\n        parl = fp / delta / temp / temp;\n    }\n\n    /* calculate an upper bound, paru, for the zero of the function. */\n    for (j = 0; j < n; ++j)\n        wa1[j] = r.col(j).head(j+1).dot(qtb.head(j+1)) / diag[ipvt[j]];\n\n    gnorm = wa1.stableNorm();\n    paru = gnorm / delta;\n    if (paru == 0.)\n        paru = dwarf / (std::min)(delta,Scalar(0.1));\n\n    /* if the input par lies outside of the interval (parl,paru), */\n    /* set par to the closer endpoint. */\n    par = (std::max)(par,parl);\n    par = (std::min)(par,paru);\n    if (par == 0.)\n        par = gnorm / dxnorm;\n\n    /* beginning of an iteration. */\n    while (true) {\n        ++iter;\n\n        /* evaluate the function at the current value of par. */\n        if (par == 0.)\n            par = (std::max)(dwarf,Scalar(.001) * paru); /* Computing MAX */\n        wa1 = sqrt(par)* diag;\n\n        Matrix< Scalar, Dynamic, 1 > sdiag(n);\n        qrsolv<Scalar>(r, ipvt, wa1, qtb, x, sdiag);\n\n        wa2 = diag.cwiseProduct(x);\n        dxnorm = wa2.blueNorm();\n        temp = fp;\n        fp = dxnorm - delta;\n\n        /* if the function is small enough, accept the current value */\n        /* of par. also test for the exceptional cases where parl */\n        /* is zero or the number of iterations has reached 10. */\n        if (abs(fp) <= Scalar(0.1) * delta || (parl == 0. && fp <= temp && temp < 0.) || iter == 10)\n            break;\n\n        /* compute the newton correction. */\n        for (j = 0; j < n; ++j) {\n            l = ipvt[j];\n            wa1[j] = diag[l] * (wa2[l] / dxnorm);\n        }\n        for (j = 0; j < n; ++j) {\n            wa1[j] /= sdiag[j];\n            temp = wa1[j];\n            for (i = j+1; i < n; ++i)\n                wa1[i] -= r(i,j) * temp;\n        }\n        temp = wa1.blueNorm();\n        parc = fp / delta / temp / temp;\n\n        /* depending on the sign of the function, update parl or paru. */\n        if (fp > 0.)\n            parl = (std::max)(parl,par);\n        if (fp < 0.)\n            paru = (std::min)(paru,par);\n\n        /* compute an improved estimate for par. */\n        /* Computing MAX */\n        par = (std::max)(parl,par+parc);\n\n        /* end of an iteration. */\n    }\n\n    /* termination. */\n    if (iter == 0)\n        par = 0.;\n    return;\n}\n\ntemplate <typename Scalar>\nvoid lmpar2(\n        const ColPivHouseholderQR<Matrix< Scalar, Dynamic, Dynamic> > &qr,\n        const Matrix< Scalar, Dynamic, 1 >  &diag,\n        const Matrix< Scalar, Dynamic, 1 >  &qtb,\n        Scalar delta,\n        Scalar &par,\n        Matrix< Scalar, Dynamic, 1 >  &x)\n\n{\n    using std::sqrt;\n    using std::abs;\n    typedef DenseIndex Index;\n\n    /* Local variables */\n    Index j;\n    Scalar fp;\n    Scalar parc, parl;\n    Index iter;\n    Scalar temp, paru;\n    Scalar gnorm;\n    Scalar dxnorm;\n\n\n    /* Function Body */\n    const Scalar dwarf = (std::numeric_limits<Scalar>::min)();\n    const Index n = qr.matrixQR().cols();\n    eigen_assert(n==diag.size());\n    eigen_assert(n==qtb.size());\n\n    Matrix< Scalar, Dynamic, 1 >  wa1, wa2;\n\n    /* compute and store in x the gauss-newton direction. if the */\n    /* jacobian is rank-deficient, obtain a least squares solution. */\n\n//    const Index rank = qr.nonzeroPivots(); // exactly double(0.)\n    const Index rank = qr.rank(); // use a threshold\n    wa1 = qtb;\n    wa1.tail(n-rank).setZero();\n    qr.matrixQR().topLeftCorner(rank, rank).template triangularView<Upper>().solveInPlace(wa1.head(rank));\n\n    x = qr.colsPermutation()*wa1;\n\n    /* initialize the iteration counter. */\n    /* evaluate the function at the origin, and test */\n    /* for acceptance of the gauss-newton direction. */\n    iter = 0;\n    wa2 = diag.cwiseProduct(x);\n    dxnorm = wa2.blueNorm();\n    fp = dxnorm - delta;\n    if (fp <= Scalar(0.1) * delta) {\n        par = 0;\n        return;\n    }\n\n    /* if the jacobian is not rank deficient, the newton */\n    /* step provides a lower bound, parl, for the zero of */\n    /* the function. otherwise set this bound to zero. */\n    parl = 0.;\n    if (rank==n) {\n        wa1 = qr.colsPermutation().inverse() *  diag.cwiseProduct(wa2)/dxnorm;\n        qr.matrixQR().topLeftCorner(n, n).transpose().template triangularView<Lower>().solveInPlace(wa1);\n        temp = wa1.blueNorm();\n        parl = fp / delta / temp / temp;\n    }\n\n    /* calculate an upper bound, paru, for the zero of the function. */\n    for (j = 0; j < n; ++j)\n        wa1[j] = qr.matrixQR().col(j).head(j+1).dot(qtb.head(j+1)) / diag[qr.colsPermutation().indices()(j)];\n\n    gnorm = wa1.stableNorm();\n    paru = gnorm / delta;\n    if (paru == 0.)\n        paru = dwarf / (std::min)(delta,Scalar(0.1));\n\n    /* if the input par lies outside of the interval (parl,paru), */\n    /* set par to the closer endpoint. */\n    par = (std::max)(par,parl);\n    par = (std::min)(par,paru);\n    if (par == 0.)\n        par = gnorm / dxnorm;\n\n    /* beginning of an iteration. */\n    Matrix< Scalar, Dynamic, Dynamic > s = qr.matrixQR();\n    while (true) {\n        ++iter;\n\n        /* evaluate the function at the current value of par. */\n        if (par == 0.)\n            par = (std::max)(dwarf,Scalar(.001) * paru); /* Computing MAX */\n        wa1 = sqrt(par)* diag;\n\n        Matrix< Scalar, Dynamic, 1 > sdiag(n);\n        qrsolv<Scalar>(s, qr.colsPermutation().indices(), wa1, qtb, x, sdiag);\n\n        wa2 = diag.cwiseProduct(x);\n        dxnorm = wa2.blueNorm();\n        temp = fp;\n        fp = dxnorm - delta;\n\n        /* if the function is small enough, accept the current value */\n        /* of par. also test for the exceptional cases where parl */\n        /* is zero or the number of iterations has reached 10. */\n        if (abs(fp) <= Scalar(0.1) * delta || (parl == 0. && fp <= temp && temp < 0.) || iter == 10)\n            break;\n\n        /* compute the newton correction. */\n        wa1 = qr.colsPermutation().inverse() * diag.cwiseProduct(wa2/dxnorm);\n        // we could almost use this here, but the diagonal is outside qr, in sdiag[]\n        // qr.matrixQR().topLeftCorner(n, n).transpose().template triangularView<Lower>().solveInPlace(wa1);\n        for (j = 0; j < n; ++j) {\n            wa1[j] /= sdiag[j];\n            temp = wa1[j];\n            for (Index i = j+1; i < n; ++i)\n                wa1[i] -= s(i,j) * temp;\n        }\n        temp = wa1.blueNorm();\n        parc = fp / delta / temp / temp;\n\n        /* depending on the sign of the function, update parl or paru. */\n        if (fp > 0.)\n            parl = (std::max)(parl,par);\n        if (fp < 0.)\n            paru = (std::min)(paru,par);\n\n        /* compute an improved estimate for par. */\n        par = (std::max)(parl,par+parc);\n    }\n    if (iter == 0)\n        par = 0.;\n    return;\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/NonLinearOptimization/qrsolv.h",
    "content": "namespace Eigen { \n\nnamespace internal {\n\n// TODO : once qrsolv2 is removed, use ColPivHouseholderQR or PermutationMatrix instead of ipvt\ntemplate <typename Scalar>\nvoid qrsolv(\n        Matrix< Scalar, Dynamic, Dynamic > &s,\n        // TODO : use a PermutationMatrix once lmpar is no more:\n        const VectorXi &ipvt,\n        const Matrix< Scalar, Dynamic, 1 >  &diag,\n        const Matrix< Scalar, Dynamic, 1 >  &qtb,\n        Matrix< Scalar, Dynamic, 1 >  &x,\n        Matrix< Scalar, Dynamic, 1 >  &sdiag)\n\n{\n    typedef DenseIndex Index;\n\n    /* Local variables */\n    Index i, j, k, l;\n    Scalar temp;\n    Index n = s.cols();\n    Matrix< Scalar, Dynamic, 1 >  wa(n);\n    JacobiRotation<Scalar> givens;\n\n    /* Function Body */\n    // the following will only change the lower triangular part of s, including\n    // the diagonal, though the diagonal is restored afterward\n\n    /*     copy r and (q transpose)*b to preserve input and initialize s. */\n    /*     in particular, save the diagonal elements of r in x. */\n    x = s.diagonal();\n    wa = qtb;\n\n    s.topLeftCorner(n,n).template triangularView<StrictlyLower>() = s.topLeftCorner(n,n).transpose();\n\n    /*     eliminate the diagonal matrix d using a givens rotation. */\n    for (j = 0; j < n; ++j) {\n\n        /*        prepare the row of d to be eliminated, locating the */\n        /*        diagonal element using p from the qr factorization. */\n        l = ipvt[j];\n        if (diag[l] == 0.)\n            break;\n        sdiag.tail(n-j).setZero();\n        sdiag[j] = diag[l];\n\n        /*        the transformations to eliminate the row of d */\n        /*        modify only a single element of (q transpose)*b */\n        /*        beyond the first n, which is initially zero. */\n        Scalar qtbpj = 0.;\n        for (k = j; k < n; ++k) {\n            /*           determine a givens rotation which eliminates the */\n            /*           appropriate element in the current row of d. */\n            givens.makeGivens(-s(k,k), sdiag[k]);\n\n            /*           compute the modified diagonal element of r and */\n            /*           the modified element of ((q transpose)*b,0). */\n            s(k,k) = givens.c() * s(k,k) + givens.s() * sdiag[k];\n            temp = givens.c() * wa[k] + givens.s() * qtbpj;\n            qtbpj = -givens.s() * wa[k] + givens.c() * qtbpj;\n            wa[k] = temp;\n\n            /*           accumulate the transformation in the row of s. */\n            for (i = k+1; i<n; ++i) {\n                temp = givens.c() * s(i,k) + givens.s() * sdiag[i];\n                sdiag[i] = -givens.s() * s(i,k) + givens.c() * sdiag[i];\n                s(i,k) = temp;\n            }\n        }\n    }\n\n    /*     solve the triangular system for z. if the system is */\n    /*     singular, then obtain a least squares solution. */\n    Index nsing;\n    for(nsing=0; nsing<n && sdiag[nsing]!=0; nsing++) {}\n\n    wa.tail(n-nsing).setZero();\n    s.topLeftCorner(nsing, nsing).transpose().template triangularView<Upper>().solveInPlace(wa.head(nsing));\n\n    // restore\n    sdiag = s.diagonal();\n    s.diagonal() = x;\n\n    /*     permute the components of z back to components of x. */\n    for (j = 0; j < n; ++j) x[ipvt[j]] = wa[j];\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/NonLinearOptimization/r1mpyq.h",
    "content": "namespace Eigen { \n\nnamespace internal {\n\n// TODO : move this to GivensQR once there's such a thing in Eigen\n\ntemplate <typename Scalar>\nvoid r1mpyq(DenseIndex m, DenseIndex n, Scalar *a, const std::vector<JacobiRotation<Scalar> > &v_givens, const std::vector<JacobiRotation<Scalar> > &w_givens)\n{\n    typedef DenseIndex Index;\n\n    /*     apply the first set of givens rotations to a. */\n    for (Index j = n-2; j>=0; --j)\n        for (Index i = 0; i<m; ++i) {\n            Scalar temp = v_givens[j].c() * a[i+m*j] - v_givens[j].s() * a[i+m*(n-1)];\n            a[i+m*(n-1)] = v_givens[j].s() * a[i+m*j] + v_givens[j].c() * a[i+m*(n-1)];\n            a[i+m*j] = temp;\n        }\n    /*     apply the second set of givens rotations to a. */\n    for (Index j = 0; j<n-1; ++j)\n        for (Index i = 0; i<m; ++i) {\n            Scalar temp = w_givens[j].c() * a[i+m*j] + w_givens[j].s() * a[i+m*(n-1)];\n            a[i+m*(n-1)] = -w_givens[j].s() * a[i+m*j] + w_givens[j].c() * a[i+m*(n-1)];\n            a[i+m*j] = temp;\n        }\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/NonLinearOptimization/r1updt.h",
    "content": "namespace Eigen { \n\nnamespace internal {\n\ntemplate <typename Scalar>\nvoid r1updt(\n        Matrix< Scalar, Dynamic, Dynamic > &s,\n        const Matrix< Scalar, Dynamic, 1> &u,\n        std::vector<JacobiRotation<Scalar> > &v_givens,\n        std::vector<JacobiRotation<Scalar> > &w_givens,\n        Matrix< Scalar, Dynamic, 1> &v,\n        Matrix< Scalar, Dynamic, 1> &w,\n        bool *sing)\n{\n    typedef DenseIndex Index;\n    const JacobiRotation<Scalar> IdentityRotation = JacobiRotation<Scalar>(1,0);\n\n    /* Local variables */\n    const Index m = s.rows();\n    const Index n = s.cols();\n    Index i, j=1;\n    Scalar temp;\n    JacobiRotation<Scalar> givens;\n\n    // r1updt had a broader usecase, but we don't use it here. And, more\n    // importantly, we can not test it.\n    eigen_assert(m==n);\n    eigen_assert(u.size()==m);\n    eigen_assert(v.size()==n);\n    eigen_assert(w.size()==n);\n\n    /* move the nontrivial part of the last column of s into w. */\n    w[n-1] = s(n-1,n-1);\n\n    /* rotate the vector v into a multiple of the n-th unit vector */\n    /* in such a way that a spike is introduced into w. */\n    for (j=n-2; j>=0; --j) {\n        w[j] = 0.;\n        if (v[j] != 0.) {\n            /* determine a givens rotation which eliminates the */\n            /* j-th element of v. */\n            givens.makeGivens(-v[n-1], v[j]);\n\n            /* apply the transformation to v and store the information */\n            /* necessary to recover the givens rotation. */\n            v[n-1] = givens.s() * v[j] + givens.c() * v[n-1];\n            v_givens[j] = givens;\n\n            /* apply the transformation to s and extend the spike in w. */\n            for (i = j; i < m; ++i) {\n                temp = givens.c() * s(j,i) - givens.s() * w[i];\n                w[i] = givens.s() * s(j,i) + givens.c() * w[i];\n                s(j,i) = temp;\n            }\n        } else\n            v_givens[j] = IdentityRotation;\n    }\n\n    /* add the spike from the rank 1 update to w. */\n    w += v[n-1] * u;\n\n    /* eliminate the spike. */\n    *sing = false;\n    for (j = 0; j < n-1; ++j) {\n        if (w[j] != 0.) {\n            /* determine a givens rotation which eliminates the */\n            /* j-th element of the spike. */\n            givens.makeGivens(-s(j,j), w[j]);\n\n            /* apply the transformation to s and reduce the spike in w. */\n            for (i = j; i < m; ++i) {\n                temp = givens.c() * s(j,i) + givens.s() * w[i];\n                w[i] = -givens.s() * s(j,i) + givens.c() * w[i];\n                s(j,i) = temp;\n            }\n\n            /* store the information necessary to recover the */\n            /* givens rotation. */\n            w_givens[j] = givens;\n        } else\n            v_givens[j] = IdentityRotation;\n\n        /* test for zero diagonal elements in the output s. */\n        if (s(j,j) == 0.) {\n            *sing = true;\n        }\n    }\n    /* move w back into the last column of the output s. */\n    s(n-1,n-1) = w[n-1];\n\n    if (s(j,j) == 0.) {\n        *sing = true;\n    }\n    return;\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/NonLinearOptimization/rwupdt.h",
    "content": "namespace Eigen { \n\nnamespace internal {\n\ntemplate <typename Scalar>\nvoid rwupdt(\n        Matrix< Scalar, Dynamic, Dynamic >  &r,\n        const Matrix< Scalar, Dynamic, 1>  &w,\n        Matrix< Scalar, Dynamic, 1>  &b,\n        Scalar alpha)\n{\n    typedef DenseIndex Index;\n\n    const Index n = r.cols();\n    eigen_assert(r.rows()>=n);\n    std::vector<JacobiRotation<Scalar> > givens(n);\n\n    /* Local variables */\n    Scalar temp, rowj;\n\n    /* Function Body */\n    for (Index j = 0; j < n; ++j) {\n        rowj = w[j];\n\n        /* apply the previous transformations to */\n        /* r(i,j), i=0,1,...,j-1, and to w(j). */\n        for (Index i = 0; i < j; ++i) {\n            temp = givens[i].c() * r(i,j) + givens[i].s() * rowj;\n            rowj = -givens[i].s() * r(i,j) + givens[i].c() * rowj;\n            r(i,j) = temp;\n        }\n\n        /* determine a givens rotation which eliminates w(j). */\n        givens[j].makeGivens(-r(j,j), rowj);\n\n        if (rowj == 0.)\n            continue; // givens[j] is identity\n\n        /* apply the current transformation to r(j,j), b(j), and alpha. */\n        r(j,j) = givens[j].c() * r(j,j) + givens[j].s() * rowj;\n        temp = givens[j].c() * b[j] + givens[j].s() * alpha;\n        alpha = -givens[j].s() * b[j] + givens[j].c() * alpha;\n        b[j] = temp;\n    }\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/NumericalDiff/NumericalDiff.h",
    "content": "// -*- coding: utf-8\n// vim: set fileencoding=utf-8\n\n// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_NUMERICAL_DIFF_H\n#define EIGEN_NUMERICAL_DIFF_H\n\nnamespace Eigen { \n\nenum NumericalDiffMode {\n    Forward,\n    Central\n};\n\n\n/**\n  * This class allows you to add a method df() to your functor, which will \n  * use numerical differentiation to compute an approximate of the\n  * derivative for the functor. Of course, if you have an analytical form\n  * for the derivative, you should rather implement df() by yourself.\n  *\n  * More information on\n  * http://en.wikipedia.org/wiki/Numerical_differentiation\n  *\n  * Currently only \"Forward\" and \"Central\" scheme are implemented.\n  */\ntemplate<typename _Functor, NumericalDiffMode mode=Forward>\nclass NumericalDiff : public _Functor\n{\npublic:\n    typedef _Functor Functor;\n    typedef typename Functor::Scalar Scalar;\n    typedef typename Functor::InputType InputType;\n    typedef typename Functor::ValueType ValueType;\n    typedef typename Functor::JacobianType JacobianType;\n\n    NumericalDiff(Scalar _epsfcn=0.) : Functor(), epsfcn(_epsfcn) {}\n    NumericalDiff(const Functor& f, Scalar _epsfcn=0.) : Functor(f), epsfcn(_epsfcn) {}\n\n    // forward constructors\n    template<typename T0>\n        NumericalDiff(const T0& a0) : Functor(a0), epsfcn(0) {}\n    template<typename T0, typename T1>\n        NumericalDiff(const T0& a0, const T1& a1) : Functor(a0, a1), epsfcn(0) {}\n    template<typename T0, typename T1, typename T2>\n        NumericalDiff(const T0& a0, const T1& a1, const T2& a2) : Functor(a0, a1, a2), epsfcn(0) {}\n\n    enum {\n        InputsAtCompileTime = Functor::InputsAtCompileTime,\n        ValuesAtCompileTime = Functor::ValuesAtCompileTime\n    };\n\n    /**\n      * return the number of evaluation of functor\n     */\n    int df(const InputType& _x, JacobianType &jac) const\n    {\n        using std::sqrt;\n        using std::abs;\n        /* Local variables */\n        Scalar h;\n        int nfev=0;\n        const typename InputType::Index n = _x.size();\n        const Scalar eps = sqrt(((std::max)(epsfcn,NumTraits<Scalar>::epsilon() )));\n        ValueType val1, val2;\n        InputType x = _x;\n        // TODO : we should do this only if the size is not already known\n        val1.resize(Functor::values());\n        val2.resize(Functor::values());\n\n        // initialization\n        switch(mode) {\n            case Forward:\n                // compute f(x)\n                Functor::operator()(x, val1); nfev++;\n                break;\n            case Central:\n                // do nothing\n                break;\n            default:\n                eigen_assert(false);\n        };\n\n        // Function Body\n        for (int j = 0; j < n; ++j) {\n            h = eps * abs(x[j]);\n            if (h == 0.) {\n                h = eps;\n            }\n            switch(mode) {\n                case Forward:\n                    x[j] += h;\n                    Functor::operator()(x, val2);\n                    nfev++;\n                    x[j] = _x[j];\n                    jac.col(j) = (val2-val1)/h;\n                    break;\n                case Central:\n                    x[j] += h;\n                    Functor::operator()(x, val2); nfev++;\n                    x[j] -= 2*h;\n                    Functor::operator()(x, val1); nfev++;\n                    x[j] = _x[j];\n                    jac.col(j) = (val2-val1)/(2*h);\n                    break;\n                default:\n                    eigen_assert(false);\n            };\n        }\n        return nfev;\n    }\nprivate:\n    Scalar epsfcn;\n\n    NumericalDiff& operator=(const NumericalDiff&);\n};\n\n} // end namespace Eigen\n\n//vim: ai ts=4 sts=4 et sw=4\n#endif // EIGEN_NUMERICAL_DIFF_H\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/Polynomials/Companion.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Manuel Yguel <manuel.yguel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_COMPANION_H\n#define EIGEN_COMPANION_H\n\n// This file requires the user to include\n// * Eigen/Core\n// * Eigen/src/PolynomialSolver.h\n\nnamespace Eigen { \n\nnamespace internal {\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n\ntemplate <typename T>\nT radix(){ return 2; }\n\ntemplate <typename T>\nT radix2(){ return radix<T>()*radix<T>(); }\n\ntemplate<int Size>\nstruct decrement_if_fixed_size\n{\n  enum {\n    ret = (Size == Dynamic) ? Dynamic : Size-1 };\n};\n\n#endif\n\ntemplate< typename _Scalar, int _Deg >\nclass companion\n{\n  public:\n    EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_Deg==Dynamic ? Dynamic : _Deg)\n\n    enum {\n      Deg = _Deg,\n      Deg_1=decrement_if_fixed_size<Deg>::ret\n    };\n\n    typedef _Scalar                                Scalar;\n    typedef typename NumTraits<Scalar>::Real       RealScalar;\n    typedef Matrix<Scalar, Deg, 1>                 RightColumn;\n    //typedef DiagonalMatrix< Scalar, Deg_1, Deg_1 > BottomLeftDiagonal;\n    typedef Matrix<Scalar, Deg_1, 1>               BottomLeftDiagonal;\n\n    typedef Matrix<Scalar, Deg, Deg>               DenseCompanionMatrixType;\n    typedef Matrix< Scalar, _Deg, Deg_1 >          LeftBlock;\n    typedef Matrix< Scalar, Deg_1, Deg_1 >         BottomLeftBlock;\n    typedef Matrix< Scalar, 1, Deg_1 >             LeftBlockFirstRow;\n\n    typedef DenseIndex Index;\n\n  public:\n    EIGEN_STRONG_INLINE const _Scalar operator()(Index row, Index col ) const\n    {\n      if( m_bl_diag.rows() > col )\n      {\n        if( 0 < row ){ return m_bl_diag[col]; }\n        else{ return 0; }\n      }\n      else{ return m_monic[row]; }\n    }\n\n  public:\n    template<typename VectorType>\n    void setPolynomial( const VectorType& poly )\n    {\n      const Index deg = poly.size()-1;\n      m_monic = -poly.head(deg)/poly[deg];\n      m_bl_diag.setOnes(deg-1);\n    }\n\n    template<typename VectorType>\n    companion( const VectorType& poly ){\n      setPolynomial( poly ); }\n\n  public:\n    DenseCompanionMatrixType denseMatrix() const\n    {\n      const Index deg   = m_monic.size();\n      const Index deg_1 = deg-1;\n      DenseCompanionMatrixType companMat(deg,deg);\n      companMat <<\n        ( LeftBlock(deg,deg_1)\n          << LeftBlockFirstRow::Zero(1,deg_1),\n          BottomLeftBlock::Identity(deg-1,deg-1)*m_bl_diag.asDiagonal() ).finished()\n        , m_monic;\n      return companMat;\n    }\n\n\n\n  protected:\n    /** Helper function for the balancing algorithm.\n     * \\returns true if the row and the column, having colNorm and rowNorm\n     * as norms, are balanced, false otherwise.\n     * colB and rowB are respectively the multipliers for\n     * the column and the row in order to balance them.\n     * */\n    bool balanced( RealScalar colNorm, RealScalar rowNorm,\n        bool& isBalanced, RealScalar& colB, RealScalar& rowB );\n\n    /** Helper function for the balancing algorithm.\n     * \\returns true if the row and the column, having colNorm and rowNorm\n     * as norms, are balanced, false otherwise.\n     * colB and rowB are respectively the multipliers for\n     * the column and the row in order to balance them.\n     * */\n    bool balancedR( RealScalar colNorm, RealScalar rowNorm,\n        bool& isBalanced, RealScalar& colB, RealScalar& rowB );\n\n  public:\n    /**\n     * Balancing algorithm from B. N. PARLETT and C. REINSCH (1969)\n     * \"Balancing a matrix for calculation of eigenvalues and eigenvectors\"\n     * adapted to the case of companion matrices.\n     * A matrix with non zero row and non zero column is balanced\n     * for a certain norm if the i-th row and the i-th column\n     * have same norm for all i.\n     */\n    void balance();\n\n  protected:\n      RightColumn                m_monic;\n      BottomLeftDiagonal         m_bl_diag;\n};\n\n\n\ntemplate< typename _Scalar, int _Deg >\ninline\nbool companion<_Scalar,_Deg>::balanced( RealScalar colNorm, RealScalar rowNorm,\n    bool& isBalanced, RealScalar& colB, RealScalar& rowB )\n{\n  if( RealScalar(0) == colNorm || RealScalar(0) == rowNorm ){ return true; }\n  else\n  {\n    //To find the balancing coefficients, if the radix is 2,\n    //one finds \\f$ \\sigma \\f$ such that\n    // \\f$ 2^{2\\sigma-1} < rowNorm / colNorm \\le 2^{2\\sigma+1} \\f$\n    // then the balancing coefficient for the row is \\f$ 1/2^{\\sigma} \\f$\n    // and the balancing coefficient for the column is \\f$ 2^{\\sigma} \\f$\n    rowB = rowNorm / radix<RealScalar>();\n    colB = RealScalar(1);\n    const RealScalar s = colNorm + rowNorm;\n\n    while (colNorm < rowB)\n    {\n      colB *= radix<RealScalar>();\n      colNorm *= radix2<RealScalar>();\n    }\n\n    rowB = rowNorm * radix<RealScalar>();\n\n    while (colNorm >= rowB)\n    {\n      colB /= radix<RealScalar>();\n      colNorm /= radix2<RealScalar>();\n    }\n\n    //This line is used to avoid insubstantial balancing\n    if ((rowNorm + colNorm) < RealScalar(0.95) * s * colB)\n    {\n      isBalanced = false;\n      rowB = RealScalar(1) / colB;\n      return false;\n    }\n    else{\n      return true; }\n  }\n}\n\ntemplate< typename _Scalar, int _Deg >\ninline\nbool companion<_Scalar,_Deg>::balancedR( RealScalar colNorm, RealScalar rowNorm,\n    bool& isBalanced, RealScalar& colB, RealScalar& rowB )\n{\n  if( RealScalar(0) == colNorm || RealScalar(0) == rowNorm ){ return true; }\n  else\n  {\n    /**\n     * Set the norm of the column and the row to the geometric mean\n     * of the row and column norm\n     */\n    const RealScalar q = colNorm/rowNorm;\n    if( !isApprox( q, _Scalar(1) ) )\n    {\n      rowB = sqrt( colNorm/rowNorm );\n      colB = RealScalar(1)/rowB;\n\n      isBalanced = false;\n      return false;\n    }\n    else{\n      return true; }\n  }\n}\n\n\ntemplate< typename _Scalar, int _Deg >\nvoid companion<_Scalar,_Deg>::balance()\n{\n  using std::abs;\n  EIGEN_STATIC_ASSERT( Deg == Dynamic || 1 < Deg, YOU_MADE_A_PROGRAMMING_MISTAKE );\n  const Index deg   = m_monic.size();\n  const Index deg_1 = deg-1;\n\n  bool hasConverged=false;\n  while( !hasConverged )\n  {\n    hasConverged = true;\n    RealScalar colNorm,rowNorm;\n    RealScalar colB,rowB;\n\n    //First row, first column excluding the diagonal\n    //==============================================\n    colNorm = abs(m_bl_diag[0]);\n    rowNorm = abs(m_monic[0]);\n\n    //Compute balancing of the row and the column\n    if( !balanced( colNorm, rowNorm, hasConverged, colB, rowB ) )\n    {\n      m_bl_diag[0] *= colB;\n      m_monic[0] *= rowB;\n    }\n\n    //Middle rows and columns excluding the diagonal\n    //==============================================\n    for( Index i=1; i<deg_1; ++i )\n    {\n      // column norm, excluding the diagonal\n      colNorm = abs(m_bl_diag[i]);\n\n      // row norm, excluding the diagonal\n      rowNorm = abs(m_bl_diag[i-1]) + abs(m_monic[i]);\n\n      //Compute balancing of the row and the column\n      if( !balanced( colNorm, rowNorm, hasConverged, colB, rowB ) )\n      {\n        m_bl_diag[i]   *= colB;\n        m_bl_diag[i-1] *= rowB;\n        m_monic[i]     *= rowB;\n      }\n    }\n\n    //Last row, last column excluding the diagonal\n    //============================================\n    const Index ebl = m_bl_diag.size()-1;\n    VectorBlock<RightColumn,Deg_1> headMonic( m_monic, 0, deg_1 );\n    colNorm = headMonic.array().abs().sum();\n    rowNorm = abs( m_bl_diag[ebl] );\n\n    //Compute balancing of the row and the column\n    if( !balanced( colNorm, rowNorm, hasConverged, colB, rowB ) )\n    {\n      headMonic      *= colB;\n      m_bl_diag[ebl] *= rowB;\n    }\n  }\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_COMPANION_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/Polynomials/PolynomialSolver.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Manuel Yguel <manuel.yguel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_POLYNOMIAL_SOLVER_H\n#define EIGEN_POLYNOMIAL_SOLVER_H\n\nnamespace Eigen { \n\n/** \\ingroup Polynomials_Module\n *  \\class PolynomialSolverBase.\n *\n * \\brief Defined to be inherited by polynomial solvers: it provides\n * convenient methods such as\n *  - real roots,\n *  - greatest, smallest complex roots,\n *  - real roots with greatest, smallest absolute real value,\n *  - greatest, smallest real roots.\n *\n * It stores the set of roots as a vector of complexes.\n *\n */\ntemplate< typename _Scalar, int _Deg >\nclass PolynomialSolverBase\n{\n  public:\n    EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_Deg==Dynamic ? Dynamic : _Deg)\n\n    typedef _Scalar                             Scalar;\n    typedef typename NumTraits<Scalar>::Real    RealScalar;\n    typedef std::complex<RealScalar>            RootType;\n    typedef Matrix<RootType,_Deg,1>             RootsType;\n\n    typedef DenseIndex Index;\n\n  protected:\n    template< typename OtherPolynomial >\n    inline void setPolynomial( const OtherPolynomial& poly ){\n      m_roots.resize(poly.size()-1); }\n\n  public:\n    template< typename OtherPolynomial >\n    inline PolynomialSolverBase( const OtherPolynomial& poly ){\n      setPolynomial( poly() ); }\n\n    inline PolynomialSolverBase(){}\n\n  public:\n    /** \\returns the complex roots of the polynomial */\n    inline const RootsType& roots() const { return m_roots; }\n\n  public:\n    /** Clear and fills the back insertion sequence with the real roots of the polynomial\n     * i.e. the real part of the complex roots that have an imaginary part which\n     * absolute value is smaller than absImaginaryThreshold.\n     * absImaginaryThreshold takes the dummy_precision associated\n     * with the _Scalar template parameter of the PolynomialSolver class as the default value.\n     *\n     * \\param[out] bi_seq : the back insertion sequence (stl concept)\n     * \\param[in]  absImaginaryThreshold : the maximum bound of the imaginary part of a complex\n     *  number that is considered as real.\n     * */\n    template<typename Stl_back_insertion_sequence>\n    inline void realRoots( Stl_back_insertion_sequence& bi_seq,\n        const RealScalar& absImaginaryThreshold = NumTraits<Scalar>::dummy_precision() ) const\n    {\n      using std::abs;\n      bi_seq.clear();\n      for(Index i=0; i<m_roots.size(); ++i )\n      {\n        if( abs( m_roots[i].imag() ) < absImaginaryThreshold ){\n          bi_seq.push_back( m_roots[i].real() ); }\n      }\n    }\n\n  protected:\n    template<typename squaredNormBinaryPredicate>\n    inline const RootType& selectComplexRoot_withRespectToNorm( squaredNormBinaryPredicate& pred ) const\n    {\n      Index res=0;\n      RealScalar norm2 = numext::abs2( m_roots[0] );\n      for( Index i=1; i<m_roots.size(); ++i )\n      {\n        const RealScalar currNorm2 = numext::abs2( m_roots[i] );\n        if( pred( currNorm2, norm2 ) ){\n          res=i; norm2=currNorm2; }\n      }\n      return m_roots[res];\n    }\n\n  public:\n    /**\n     * \\returns the complex root with greatest norm.\n     */\n    inline const RootType& greatestRoot() const\n    {\n      std::greater<RealScalar> greater;\n      return selectComplexRoot_withRespectToNorm( greater );\n    }\n\n    /**\n     * \\returns the complex root with smallest norm.\n     */\n    inline const RootType& smallestRoot() const\n    {\n      std::less<RealScalar> less;\n      return selectComplexRoot_withRespectToNorm( less );\n    }\n\n  protected:\n    template<typename squaredRealPartBinaryPredicate>\n    inline const RealScalar& selectRealRoot_withRespectToAbsRealPart(\n        squaredRealPartBinaryPredicate& pred,\n        bool& hasArealRoot,\n        const RealScalar& absImaginaryThreshold = NumTraits<Scalar>::dummy_precision() ) const\n    {\n      using std::abs;\n      hasArealRoot = false;\n      Index res=0;\n      RealScalar abs2(0);\n\n      for( Index i=0; i<m_roots.size(); ++i )\n      {\n        if( abs( m_roots[i].imag() ) <= absImaginaryThreshold )\n        {\n          if( !hasArealRoot )\n          {\n            hasArealRoot = true;\n            res = i;\n            abs2 = m_roots[i].real() * m_roots[i].real();\n          }\n          else\n          {\n            const RealScalar currAbs2 = m_roots[i].real() * m_roots[i].real();\n            if( pred( currAbs2, abs2 ) )\n            {\n              abs2 = currAbs2;\n              res = i;\n            }\n          }\n        }\n        else if(!hasArealRoot)\n        {\n          if( abs( m_roots[i].imag() ) < abs( m_roots[res].imag() ) ){\n            res = i;}\n        }\n      }\n      return numext::real_ref(m_roots[res]);\n    }\n\n\n    template<typename RealPartBinaryPredicate>\n    inline const RealScalar& selectRealRoot_withRespectToRealPart(\n        RealPartBinaryPredicate& pred,\n        bool& hasArealRoot,\n        const RealScalar& absImaginaryThreshold = NumTraits<Scalar>::dummy_precision() ) const\n    {\n      using std::abs;\n      hasArealRoot = false;\n      Index res=0;\n      RealScalar val(0);\n\n      for( Index i=0; i<m_roots.size(); ++i )\n      {\n        if( abs( m_roots[i].imag() ) <= absImaginaryThreshold )\n        {\n          if( !hasArealRoot )\n          {\n            hasArealRoot = true;\n            res = i;\n            val = m_roots[i].real();\n          }\n          else\n          {\n            const RealScalar curr = m_roots[i].real();\n            if( pred( curr, val ) )\n            {\n              val = curr;\n              res = i;\n            }\n          }\n        }\n        else\n        {\n          if( abs( m_roots[i].imag() ) < abs( m_roots[res].imag() ) ){\n            res = i; }\n        }\n      }\n      return numext::real_ref(m_roots[res]);\n    }\n\n  public:\n    /**\n     * \\returns a real root with greatest absolute magnitude.\n     * A real root is defined as the real part of a complex root with absolute imaginary\n     * part smallest than absImaginaryThreshold.\n     * absImaginaryThreshold takes the dummy_precision associated\n     * with the _Scalar template parameter of the PolynomialSolver class as the default value.\n     * If no real root is found the boolean hasArealRoot is set to false and the real part of\n     * the root with smallest absolute imaginary part is returned instead.\n     *\n     * \\param[out] hasArealRoot : boolean true if a real root is found according to the\n     *  absImaginaryThreshold criterion, false otherwise.\n     * \\param[in] absImaginaryThreshold : threshold on the absolute imaginary part to decide\n     *  whether or not a root is real.\n     */\n    inline const RealScalar& absGreatestRealRoot(\n        bool& hasArealRoot,\n        const RealScalar& absImaginaryThreshold = NumTraits<Scalar>::dummy_precision() ) const\n    {\n      std::greater<RealScalar> greater;\n      return selectRealRoot_withRespectToAbsRealPart( greater, hasArealRoot, absImaginaryThreshold );\n    }\n\n\n    /**\n     * \\returns a real root with smallest absolute magnitude.\n     * A real root is defined as the real part of a complex root with absolute imaginary\n     * part smallest than absImaginaryThreshold.\n     * absImaginaryThreshold takes the dummy_precision associated\n     * with the _Scalar template parameter of the PolynomialSolver class as the default value.\n     * If no real root is found the boolean hasArealRoot is set to false and the real part of\n     * the root with smallest absolute imaginary part is returned instead.\n     *\n     * \\param[out] hasArealRoot : boolean true if a real root is found according to the\n     *  absImaginaryThreshold criterion, false otherwise.\n     * \\param[in] absImaginaryThreshold : threshold on the absolute imaginary part to decide\n     *  whether or not a root is real.\n     */\n    inline const RealScalar& absSmallestRealRoot(\n        bool& hasArealRoot,\n        const RealScalar& absImaginaryThreshold = NumTraits<Scalar>::dummy_precision() ) const\n    {\n      std::less<RealScalar> less;\n      return selectRealRoot_withRespectToAbsRealPart( less, hasArealRoot, absImaginaryThreshold );\n    }\n\n\n    /**\n     * \\returns the real root with greatest value.\n     * A real root is defined as the real part of a complex root with absolute imaginary\n     * part smallest than absImaginaryThreshold.\n     * absImaginaryThreshold takes the dummy_precision associated\n     * with the _Scalar template parameter of the PolynomialSolver class as the default value.\n     * If no real root is found the boolean hasArealRoot is set to false and the real part of\n     * the root with smallest absolute imaginary part is returned instead.\n     *\n     * \\param[out] hasArealRoot : boolean true if a real root is found according to the\n     *  absImaginaryThreshold criterion, false otherwise.\n     * \\param[in] absImaginaryThreshold : threshold on the absolute imaginary part to decide\n     *  whether or not a root is real.\n     */\n    inline const RealScalar& greatestRealRoot(\n        bool& hasArealRoot,\n        const RealScalar& absImaginaryThreshold = NumTraits<Scalar>::dummy_precision() ) const\n    {\n      std::greater<RealScalar> greater;\n      return selectRealRoot_withRespectToRealPart( greater, hasArealRoot, absImaginaryThreshold );\n    }\n\n\n    /**\n     * \\returns the real root with smallest value.\n     * A real root is defined as the real part of a complex root with absolute imaginary\n     * part smallest than absImaginaryThreshold.\n     * absImaginaryThreshold takes the dummy_precision associated\n     * with the _Scalar template parameter of the PolynomialSolver class as the default value.\n     * If no real root is found the boolean hasArealRoot is set to false and the real part of\n     * the root with smallest absolute imaginary part is returned instead.\n     *\n     * \\param[out] hasArealRoot : boolean true if a real root is found according to the\n     *  absImaginaryThreshold criterion, false otherwise.\n     * \\param[in] absImaginaryThreshold : threshold on the absolute imaginary part to decide\n     *  whether or not a root is real.\n     */\n    inline const RealScalar& smallestRealRoot(\n        bool& hasArealRoot,\n        const RealScalar& absImaginaryThreshold = NumTraits<Scalar>::dummy_precision() ) const\n    {\n      std::less<RealScalar> less;\n      return selectRealRoot_withRespectToRealPart( less, hasArealRoot, absImaginaryThreshold );\n    }\n\n  protected:\n    RootsType               m_roots;\n};\n\n#define EIGEN_POLYNOMIAL_SOLVER_BASE_INHERITED_TYPES( BASE )  \\\n  typedef typename BASE::Scalar                 Scalar;       \\\n  typedef typename BASE::RealScalar             RealScalar;   \\\n  typedef typename BASE::RootType               RootType;     \\\n  typedef typename BASE::RootsType              RootsType;\n\n\n\n/** \\ingroup Polynomials_Module\n  *\n  * \\class PolynomialSolver\n  *\n  * \\brief A polynomial solver\n  *\n  * Computes the complex roots of a real polynomial.\n  *\n  * \\param _Scalar the scalar type, i.e., the type of the polynomial coefficients\n  * \\param _Deg the degree of the polynomial, can be a compile time value or Dynamic.\n  *             Notice that the number of polynomial coefficients is _Deg+1.\n  *\n  * This class implements a polynomial solver and provides convenient methods such as\n  * - real roots,\n  * - greatest, smallest complex roots,\n  * - real roots with greatest, smallest absolute real value.\n  * - greatest, smallest real roots.\n  *\n  * WARNING: this polynomial solver is experimental, part of the unsupported Eigen modules.\n  *\n  *\n  * Currently a QR algorithm is used to compute the eigenvalues of the companion matrix of\n  * the polynomial to compute its roots.\n  * This supposes that the complex moduli of the roots are all distinct: e.g. there should\n  * be no multiple roots or conjugate roots for instance.\n  * With 32bit (float) floating types this problem shows up frequently.\n  * However, almost always, correct accuracy is reached even in these cases for 64bit\n  * (double) floating types and small polynomial degree (<20).\n  */\ntemplate<typename _Scalar, int _Deg>\nclass PolynomialSolver : public PolynomialSolverBase<_Scalar,_Deg>\n{\n  public:\n    EIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(_Scalar,_Deg==Dynamic ? Dynamic : _Deg)\n\n    typedef PolynomialSolverBase<_Scalar,_Deg>    PS_Base;\n    EIGEN_POLYNOMIAL_SOLVER_BASE_INHERITED_TYPES( PS_Base )\n\n    typedef Matrix<Scalar,_Deg,_Deg>                 CompanionMatrixType;\n    typedef typename internal::conditional<NumTraits<Scalar>::IsComplex,\n                                          ComplexEigenSolver<CompanionMatrixType>,\n                                          EigenSolver<CompanionMatrixType> >::type EigenSolverType;\n    typedef typename internal::conditional<NumTraits<Scalar>::IsComplex, Scalar, std::complex<Scalar> >::type ComplexScalar;\n\n  public:\n    /** Computes the complex roots of a new polynomial. */\n    template< typename OtherPolynomial >\n    void compute( const OtherPolynomial& poly )\n    {\n      eigen_assert( Scalar(0) != poly[poly.size()-1] );\n      eigen_assert( poly.size() > 1 );\n      if(poly.size() >  2 )\n      {\n        internal::companion<Scalar,_Deg> companion( poly );\n        companion.balance();\n        m_eigenSolver.compute( companion.denseMatrix() );\n        m_roots = m_eigenSolver.eigenvalues();\n        // cleanup noise in imaginary part of real roots:\n        // if the imaginary part is rather small compared to the real part\n        // and that cancelling the imaginary part yield a smaller evaluation,\n        // then it's safe to keep the real part only.\n        RealScalar coarse_prec = RealScalar(std::pow(4,poly.size()+1))*NumTraits<RealScalar>::epsilon();\n        for(Index i = 0; i<m_roots.size(); ++i)\n        {\n          if( internal::isMuchSmallerThan(numext::abs(numext::imag(m_roots[i])),\n                                          numext::abs(numext::real(m_roots[i])),\n                                          coarse_prec) )\n          {\n            ComplexScalar as_real_root = ComplexScalar(numext::real(m_roots[i]));\n            if(    numext::abs(poly_eval(poly, as_real_root))\n                <= numext::abs(poly_eval(poly, m_roots[i])))\n            {\n              m_roots[i] = as_real_root;\n            }\n          }\n        }\n      }\n      else if(poly.size () == 2)\n      {\n        m_roots.resize(1);\n        m_roots[0] = -poly[0]/poly[1];\n      }\n    }\n\n  public:\n    template< typename OtherPolynomial >\n    inline PolynomialSolver( const OtherPolynomial& poly ){\n      compute( poly ); }\n\n    inline PolynomialSolver(){}\n\n  protected:\n    using                   PS_Base::m_roots;\n    EigenSolverType         m_eigenSolver;\n};\n\n\ntemplate< typename _Scalar >\nclass PolynomialSolver<_Scalar,1> : public PolynomialSolverBase<_Scalar,1>\n{\n  public:\n    typedef PolynomialSolverBase<_Scalar,1>    PS_Base;\n    EIGEN_POLYNOMIAL_SOLVER_BASE_INHERITED_TYPES( PS_Base )\n\n  public:\n    /** Computes the complex roots of a new polynomial. */\n    template< typename OtherPolynomial >\n    void compute( const OtherPolynomial& poly )\n    {\n      eigen_assert( poly.size() == 2 );\n      eigen_assert( Scalar(0) != poly[1] );\n      m_roots[0] = -poly[0]/poly[1];\n    }\n\n  public:\n    template< typename OtherPolynomial >\n    inline PolynomialSolver( const OtherPolynomial& poly ){\n      compute( poly ); }\n\n    inline PolynomialSolver(){}\n\n  protected:\n    using                   PS_Base::m_roots;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_POLYNOMIAL_SOLVER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/Polynomials/PolynomialUtils.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Manuel Yguel <manuel.yguel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_POLYNOMIAL_UTILS_H\n#define EIGEN_POLYNOMIAL_UTILS_H\n\nnamespace Eigen { \n\n/** \\ingroup Polynomials_Module\n * \\returns the evaluation of the polynomial at x using Horner algorithm.\n *\n * \\param[in] poly : the vector of coefficients of the polynomial ordered\n *  by degrees i.e. poly[i] is the coefficient of degree i of the polynomial\n *  e.g. \\f$ 1 + 3x^2 \\f$ is stored as a vector \\f$ [ 1, 0, 3 ] \\f$.\n * \\param[in] x : the value to evaluate the polynomial at.\n *\n * \\note for stability:\n *   \\f$ |x| \\le 1 \\f$\n */\ntemplate <typename Polynomials, typename T>\ninline\nT poly_eval_horner( const Polynomials& poly, const T& x )\n{\n  T val=poly[poly.size()-1];\n  for(DenseIndex i=poly.size()-2; i>=0; --i ){\n    val = val*x + poly[i]; }\n  return val;\n}\n\n/** \\ingroup Polynomials_Module\n * \\returns the evaluation of the polynomial at x using stabilized Horner algorithm.\n *\n * \\param[in] poly : the vector of coefficients of the polynomial ordered\n *  by degrees i.e. poly[i] is the coefficient of degree i of the polynomial\n *  e.g. \\f$ 1 + 3x^2 \\f$ is stored as a vector \\f$ [ 1, 0, 3 ] \\f$.\n * \\param[in] x : the value to evaluate the polynomial at.\n */\ntemplate <typename Polynomials, typename T>\ninline\nT poly_eval( const Polynomials& poly, const T& x )\n{\n  typedef typename NumTraits<T>::Real Real;\n\n  if( numext::abs2( x ) <= Real(1) ){\n    return poly_eval_horner( poly, x ); }\n  else\n  {\n    T val=poly[0];\n    T inv_x = T(1)/x;\n    for( DenseIndex i=1; i<poly.size(); ++i ){\n      val = val*inv_x + poly[i]; }\n\n    return numext::pow(x,(T)(poly.size()-1)) * val;\n  }\n}\n\n/** \\ingroup Polynomials_Module\n * \\returns a maximum bound for the absolute value of any root of the polynomial.\n *\n * \\param[in] poly : the vector of coefficients of the polynomial ordered\n *  by degrees i.e. poly[i] is the coefficient of degree i of the polynomial\n *  e.g. \\f$ 1 + 3x^2 \\f$ is stored as a vector \\f$ [ 1, 0, 3 ] \\f$.\n *\n *  \\pre\n *   the leading coefficient of the input polynomial poly must be non zero\n */\ntemplate <typename Polynomial>\ninline\ntypename NumTraits<typename Polynomial::Scalar>::Real cauchy_max_bound( const Polynomial& poly )\n{\n  using std::abs;\n  typedef typename Polynomial::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real Real;\n\n  eigen_assert( Scalar(0) != poly[poly.size()-1] );\n  const Scalar inv_leading_coeff = Scalar(1)/poly[poly.size()-1];\n  Real cb(0);\n\n  for( DenseIndex i=0; i<poly.size()-1; ++i ){\n    cb += abs(poly[i]*inv_leading_coeff); }\n  return cb + Real(1);\n}\n\n/** \\ingroup Polynomials_Module\n * \\returns a minimum bound for the absolute value of any non zero root of the polynomial.\n * \\param[in] poly : the vector of coefficients of the polynomial ordered\n *  by degrees i.e. poly[i] is the coefficient of degree i of the polynomial\n *  e.g. \\f$ 1 + 3x^2 \\f$ is stored as a vector \\f$ [ 1, 0, 3 ] \\f$.\n */\ntemplate <typename Polynomial>\ninline\ntypename NumTraits<typename Polynomial::Scalar>::Real cauchy_min_bound( const Polynomial& poly )\n{\n  using std::abs;\n  typedef typename Polynomial::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real Real;\n\n  DenseIndex i=0;\n  while( i<poly.size()-1 && Scalar(0) == poly(i) ){ ++i; }\n  if( poly.size()-1 == i ){\n    return Real(1); }\n\n  const Scalar inv_min_coeff = Scalar(1)/poly[i];\n  Real cb(1);\n  for( DenseIndex j=i+1; j<poly.size(); ++j ){\n    cb += abs(poly[j]*inv_min_coeff); }\n  return Real(1)/cb;\n}\n\n/** \\ingroup Polynomials_Module\n * Given the roots of a polynomial compute the coefficients in the\n * monomial basis of the monic polynomial with same roots and minimal degree.\n * If RootVector is a vector of complexes, Polynomial should also be a vector\n * of complexes.\n * \\param[in] rv : a vector containing the roots of a polynomial.\n * \\param[out] poly : the vector of coefficients of the polynomial ordered\n *  by degrees i.e. poly[i] is the coefficient of degree i of the polynomial\n *  e.g. \\f$ 3 + x^2 \\f$ is stored as a vector \\f$ [ 3, 0, 1 ] \\f$.\n */\ntemplate <typename RootVector, typename Polynomial>\nvoid roots_to_monicPolynomial( const RootVector& rv, Polynomial& poly )\n{\n\n  typedef typename Polynomial::Scalar Scalar;\n\n  poly.setZero( rv.size()+1 );\n  poly[0] = -rv[0]; poly[1] = Scalar(1);\n  for( DenseIndex i=1; i< rv.size(); ++i )\n  {\n    for( DenseIndex j=i+1; j>0; --j ){ poly[j] = poly[j-1] - rv[i]*poly[j]; }\n    poly[0] = -rv[i]*poly[0];\n  }\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_POLYNOMIAL_UTILS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/Skyline/SkylineInplaceLU.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Guillaume Saupin <guillaume.saupin@cea.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SKYLINEINPLACELU_H\n#define EIGEN_SKYLINEINPLACELU_H\n\nnamespace Eigen { \n\n/** \\ingroup Skyline_Module\n *\n * \\class SkylineInplaceLU\n *\n * \\brief Inplace LU decomposition of a skyline matrix and associated features\n *\n * \\param MatrixType the type of the matrix of which we are computing the LU factorization\n *\n */\ntemplate<typename MatrixType>\nclass SkylineInplaceLU {\nprotected:\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::Index Index;\n    \n    typedef typename NumTraits<typename MatrixType::Scalar>::Real RealScalar;\n\npublic:\n\n    /** Creates a LU object and compute the respective factorization of \\a matrix using\n     * flags \\a flags. */\n    SkylineInplaceLU(MatrixType& matrix, int flags = 0)\n    : /*m_matrix(matrix.rows(), matrix.cols()),*/ m_flags(flags), m_status(0), m_lu(matrix) {\n        m_precision = RealScalar(0.1) * Eigen::dummy_precision<RealScalar > ();\n        m_lu.IsRowMajor ? computeRowMajor() : compute();\n    }\n\n    /** Sets the relative threshold value used to prune zero coefficients during the decomposition.\n     *\n     * Setting a value greater than zero speeds up computation, and yields to an incomplete\n     * factorization with fewer non zero coefficients. Such approximate factors are especially\n     * useful to initialize an iterative solver.\n     *\n     * Note that the exact meaning of this parameter might depends on the actual\n     * backend. Moreover, not all backends support this feature.\n     *\n     * \\sa precision() */\n    void setPrecision(RealScalar v) {\n        m_precision = v;\n    }\n\n    /** \\returns the current precision.\n     *\n     * \\sa setPrecision() */\n    RealScalar precision() const {\n        return m_precision;\n    }\n\n    /** Sets the flags. Possible values are:\n     *  - CompleteFactorization\n     *  - IncompleteFactorization\n     *  - MemoryEfficient\n     *  - one of the ordering methods\n     *  - etc...\n     *\n     * \\sa flags() */\n    void setFlags(int f) {\n        m_flags = f;\n    }\n\n    /** \\returns the current flags */\n    int flags() const {\n        return m_flags;\n    }\n\n    void setOrderingMethod(int m) {\n        m_flags = m;\n    }\n\n    int orderingMethod() const {\n        return m_flags;\n    }\n\n    /** Computes/re-computes the LU factorization */\n    void compute();\n    void computeRowMajor();\n\n    /** \\returns the lower triangular matrix L */\n    //inline const MatrixType& matrixL() const { return m_matrixL; }\n\n    /** \\returns the upper triangular matrix U */\n    //inline const MatrixType& matrixU() const { return m_matrixU; }\n\n    template<typename BDerived, typename XDerived>\n    bool solve(const MatrixBase<BDerived> &b, MatrixBase<XDerived>* x,\n            const int transposed = 0) const;\n\n    /** \\returns true if the factorization succeeded */\n    inline bool succeeded(void) const {\n        return m_succeeded;\n    }\n\nprotected:\n    RealScalar m_precision;\n    int m_flags;\n    mutable int m_status;\n    bool m_succeeded;\n    MatrixType& m_lu;\n};\n\n/** Computes / recomputes the in place LU decomposition of the SkylineInplaceLU.\n * using the default algorithm.\n */\ntemplate<typename MatrixType>\n//template<typename _Scalar>\nvoid SkylineInplaceLU<MatrixType>::compute() {\n    const size_t rows = m_lu.rows();\n    const size_t cols = m_lu.cols();\n\n    eigen_assert(rows == cols && \"We do not (yet) support rectangular LU.\");\n    eigen_assert(!m_lu.IsRowMajor && \"LU decomposition does not work with rowMajor Storage\");\n\n    for (Index row = 0; row < rows; row++) {\n        const double pivot = m_lu.coeffDiag(row);\n\n        //Lower matrix Columns update\n        const Index& col = row;\n        for (typename MatrixType::InnerLowerIterator lIt(m_lu, col); lIt; ++lIt) {\n            lIt.valueRef() /= pivot;\n        }\n\n        //Upper matrix update -> contiguous memory access\n        typename MatrixType::InnerLowerIterator lIt(m_lu, col);\n        for (Index rrow = row + 1; rrow < m_lu.rows(); rrow++) {\n            typename MatrixType::InnerUpperIterator uItPivot(m_lu, row);\n            typename MatrixType::InnerUpperIterator uIt(m_lu, rrow);\n            const double coef = lIt.value();\n\n            uItPivot += (rrow - row - 1);\n\n            //update upper part  -> contiguous memory access\n            for (++uItPivot; uIt && uItPivot;) {\n                uIt.valueRef() -= uItPivot.value() * coef;\n\n                ++uIt;\n                ++uItPivot;\n            }\n            ++lIt;\n        }\n\n        //Upper matrix update -> non contiguous memory access\n        typename MatrixType::InnerLowerIterator lIt3(m_lu, col);\n        for (Index rrow = row + 1; rrow < m_lu.rows(); rrow++) {\n            typename MatrixType::InnerUpperIterator uItPivot(m_lu, row);\n            const double coef = lIt3.value();\n\n            //update lower part ->  non contiguous memory access\n            for (Index i = 0; i < rrow - row - 1; i++) {\n                m_lu.coeffRefLower(rrow, row + i + 1) -= uItPivot.value() * coef;\n                ++uItPivot;\n            }\n            ++lIt3;\n        }\n        //update diag -> contiguous\n        typename MatrixType::InnerLowerIterator lIt2(m_lu, col);\n        for (Index rrow = row + 1; rrow < m_lu.rows(); rrow++) {\n\n            typename MatrixType::InnerUpperIterator uItPivot(m_lu, row);\n            typename MatrixType::InnerUpperIterator uIt(m_lu, rrow);\n            const double coef = lIt2.value();\n\n            uItPivot += (rrow - row - 1);\n            m_lu.coeffRefDiag(rrow) -= uItPivot.value() * coef;\n            ++lIt2;\n        }\n    }\n}\n\ntemplate<typename MatrixType>\nvoid SkylineInplaceLU<MatrixType>::computeRowMajor() {\n    const size_t rows = m_lu.rows();\n    const size_t cols = m_lu.cols();\n\n    eigen_assert(rows == cols && \"We do not (yet) support rectangular LU.\");\n    eigen_assert(m_lu.IsRowMajor && \"You're trying to apply rowMajor decomposition on a ColMajor matrix !\");\n\n    for (Index row = 0; row < rows; row++) {\n        typename MatrixType::InnerLowerIterator llIt(m_lu, row);\n\n\n        for (Index col = llIt.col(); col < row; col++) {\n            if (m_lu.coeffExistLower(row, col)) {\n                const double diag = m_lu.coeffDiag(col);\n\n                typename MatrixType::InnerLowerIterator lIt(m_lu, row);\n                typename MatrixType::InnerUpperIterator uIt(m_lu, col);\n\n\n                const Index offset = lIt.col() - uIt.row();\n\n\n                Index stop = offset > 0 ? col - lIt.col() : col - uIt.row();\n\n                //#define VECTORIZE\n#ifdef VECTORIZE\n                Map<VectorXd > rowVal(lIt.valuePtr() + (offset > 0 ? 0 : -offset), stop);\n                Map<VectorXd > colVal(uIt.valuePtr() + (offset > 0 ? offset : 0), stop);\n\n\n                Scalar newCoeff = m_lu.coeffLower(row, col) - rowVal.dot(colVal);\n#else\n                if (offset > 0) //Skip zero value of lIt\n                    uIt += offset;\n                else //Skip zero values of uIt\n                    lIt += -offset;\n                Scalar newCoeff = m_lu.coeffLower(row, col);\n\n                for (Index k = 0; k < stop; ++k) {\n                    const Scalar tmp = newCoeff;\n                    newCoeff = tmp - lIt.value() * uIt.value();\n                    ++lIt;\n                    ++uIt;\n                }\n#endif\n\n                m_lu.coeffRefLower(row, col) = newCoeff / diag;\n            }\n        }\n\n        //Upper matrix update\n        const Index col = row;\n        typename MatrixType::InnerUpperIterator uuIt(m_lu, col);\n        for (Index rrow = uuIt.row(); rrow < col; rrow++) {\n\n            typename MatrixType::InnerLowerIterator lIt(m_lu, rrow);\n            typename MatrixType::InnerUpperIterator uIt(m_lu, col);\n            const Index offset = lIt.col() - uIt.row();\n\n            Index stop = offset > 0 ? rrow - lIt.col() : rrow - uIt.row();\n\n#ifdef VECTORIZE\n            Map<VectorXd > rowVal(lIt.valuePtr() + (offset > 0 ? 0 : -offset), stop);\n            Map<VectorXd > colVal(uIt.valuePtr() + (offset > 0 ? offset : 0), stop);\n\n            Scalar newCoeff = m_lu.coeffUpper(rrow, col) - rowVal.dot(colVal);\n#else\n            if (offset > 0) //Skip zero value of lIt\n                uIt += offset;\n            else //Skip zero values of uIt\n                lIt += -offset;\n            Scalar newCoeff = m_lu.coeffUpper(rrow, col);\n            for (Index k = 0; k < stop; ++k) {\n                const Scalar tmp = newCoeff;\n                newCoeff = tmp - lIt.value() * uIt.value();\n\n                ++lIt;\n                ++uIt;\n            }\n#endif\n            m_lu.coeffRefUpper(rrow, col) = newCoeff;\n        }\n\n\n        //Diag matrix update\n        typename MatrixType::InnerLowerIterator lIt(m_lu, row);\n        typename MatrixType::InnerUpperIterator uIt(m_lu, row);\n\n        const Index offset = lIt.col() - uIt.row();\n\n\n        Index stop = offset > 0 ? lIt.size() : uIt.size();\n#ifdef VECTORIZE\n        Map<VectorXd > rowVal(lIt.valuePtr() + (offset > 0 ? 0 : -offset), stop);\n        Map<VectorXd > colVal(uIt.valuePtr() + (offset > 0 ? offset : 0), stop);\n        Scalar newCoeff = m_lu.coeffDiag(row) - rowVal.dot(colVal);\n#else\n        if (offset > 0) //Skip zero value of lIt\n            uIt += offset;\n        else //Skip zero values of uIt\n            lIt += -offset;\n        Scalar newCoeff = m_lu.coeffDiag(row);\n        for (Index k = 0; k < stop; ++k) {\n            const Scalar tmp = newCoeff;\n            newCoeff = tmp - lIt.value() * uIt.value();\n            ++lIt;\n            ++uIt;\n        }\n#endif\n        m_lu.coeffRefDiag(row) = newCoeff;\n    }\n}\n\n/** Computes *x = U^-1 L^-1 b\n *\n * If \\a transpose is set to SvTranspose or SvAdjoint, the solution\n * of the transposed/adjoint system is computed instead.\n *\n * Not all backends implement the solution of the transposed or\n * adjoint system.\n */\ntemplate<typename MatrixType>\ntemplate<typename BDerived, typename XDerived>\nbool SkylineInplaceLU<MatrixType>::solve(const MatrixBase<BDerived> &b, MatrixBase<XDerived>* x, const int transposed) const {\n    const size_t rows = m_lu.rows();\n    const size_t cols = m_lu.cols();\n\n\n    for (Index row = 0; row < rows; row++) {\n        x->coeffRef(row) = b.coeff(row);\n        Scalar newVal = x->coeff(row);\n        typename MatrixType::InnerLowerIterator lIt(m_lu, row);\n\n        Index col = lIt.col();\n        while (lIt.col() < row) {\n\n            newVal -= x->coeff(col++) * lIt.value();\n            ++lIt;\n        }\n\n        x->coeffRef(row) = newVal;\n    }\n\n\n    for (Index col = rows - 1; col > 0; col--) {\n        x->coeffRef(col) = x->coeff(col) / m_lu.coeffDiag(col);\n\n        const Scalar x_col = x->coeff(col);\n\n        typename MatrixType::InnerUpperIterator uIt(m_lu, col);\n        uIt += uIt.size()-1;\n\n\n        while (uIt) {\n            x->coeffRef(uIt.row()) -= x_col * uIt.value();\n            //TODO : introduce --operator\n            uIt += -1;\n        }\n\n\n    }\n    x->coeffRef(0) = x->coeff(0) / m_lu.coeffDiag(0);\n\n    return true;\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SKYLINEINPLACELU_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/Skyline/SkylineMatrix.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Guillaume Saupin <guillaume.saupin@cea.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SKYLINEMATRIX_H\n#define EIGEN_SKYLINEMATRIX_H\n\n#include \"SkylineStorage.h\"\n#include \"SkylineMatrixBase.h\"\n\nnamespace Eigen { \n\n/** \\ingroup Skyline_Module\n *\n * \\class SkylineMatrix\n *\n * \\brief The main skyline matrix class\n *\n * This class implements a skyline matrix using the very uncommon storage\n * scheme.\n *\n * \\param _Scalar the scalar type, i.e. the type of the coefficients\n * \\param _Options Union of bit flags controlling the storage scheme. Currently the only possibility\n *                 is RowMajor. The default is 0 which means column-major.\n *\n *\n */\nnamespace internal {\ntemplate<typename _Scalar, int _Options>\nstruct traits<SkylineMatrix<_Scalar, _Options> > {\n    typedef _Scalar Scalar;\n    typedef Sparse StorageKind;\n\n    enum {\n        RowsAtCompileTime = Dynamic,\n        ColsAtCompileTime = Dynamic,\n        MaxRowsAtCompileTime = Dynamic,\n        MaxColsAtCompileTime = Dynamic,\n        Flags = SkylineBit | _Options,\n        CoeffReadCost = NumTraits<Scalar>::ReadCost,\n    };\n};\n}\n\ntemplate<typename _Scalar, int _Options>\nclass SkylineMatrix\n: public SkylineMatrixBase<SkylineMatrix<_Scalar, _Options> > {\npublic:\n    EIGEN_SKYLINE_GENERIC_PUBLIC_INTERFACE(SkylineMatrix)\n    EIGEN_SKYLINE_INHERIT_ASSIGNMENT_OPERATOR(SkylineMatrix, +=)\n    EIGEN_SKYLINE_INHERIT_ASSIGNMENT_OPERATOR(SkylineMatrix, -=)\n\n    using Base::IsRowMajor;\n\nprotected:\n\n    typedef SkylineMatrix<Scalar, (Flags&~RowMajorBit) | (IsRowMajor ? RowMajorBit : 0) > TransposedSkylineMatrix;\n\n    Index m_outerSize;\n    Index m_innerSize;\n\npublic:\n    Index* m_colStartIndex;\n    Index* m_rowStartIndex;\n    SkylineStorage<Scalar> m_data;\n\npublic:\n\n    inline Index rows() const {\n        return IsRowMajor ? m_outerSize : m_innerSize;\n    }\n\n    inline Index cols() const {\n        return IsRowMajor ? m_innerSize : m_outerSize;\n    }\n\n    inline Index innerSize() const {\n        return m_innerSize;\n    }\n\n    inline Index outerSize() const {\n        return m_outerSize;\n    }\n\n    inline Index upperNonZeros() const {\n        return m_data.upperSize();\n    }\n\n    inline Index lowerNonZeros() const {\n        return m_data.lowerSize();\n    }\n\n    inline Index upperNonZeros(Index j) const {\n        return m_colStartIndex[j + 1] - m_colStartIndex[j];\n    }\n\n    inline Index lowerNonZeros(Index j) const {\n        return m_rowStartIndex[j + 1] - m_rowStartIndex[j];\n    }\n\n    inline const Scalar* _diagPtr() const {\n        return &m_data.diag(0);\n    }\n\n    inline Scalar* _diagPtr() {\n        return &m_data.diag(0);\n    }\n\n    inline const Scalar* _upperPtr() const {\n        return &m_data.upper(0);\n    }\n\n    inline Scalar* _upperPtr() {\n        return &m_data.upper(0);\n    }\n\n    inline const Scalar* _lowerPtr() const {\n        return &m_data.lower(0);\n    }\n\n    inline Scalar* _lowerPtr() {\n        return &m_data.lower(0);\n    }\n\n    inline const Index* _upperProfilePtr() const {\n        return &m_data.upperProfile(0);\n    }\n\n    inline Index* _upperProfilePtr() {\n        return &m_data.upperProfile(0);\n    }\n\n    inline const Index* _lowerProfilePtr() const {\n        return &m_data.lowerProfile(0);\n    }\n\n    inline Index* _lowerProfilePtr() {\n        return &m_data.lowerProfile(0);\n    }\n\n    inline Scalar coeff(Index row, Index col) const {\n        const Index outer = IsRowMajor ? row : col;\n        const Index inner = IsRowMajor ? col : row;\n\n        eigen_assert(outer < outerSize());\n        eigen_assert(inner < innerSize());\n\n        if (outer == inner)\n            return this->m_data.diag(outer);\n\n        if (IsRowMajor) {\n            if (inner > outer) //upper matrix\n            {\n                const Index minOuterIndex = inner - m_data.upperProfile(inner);\n                if (outer >= minOuterIndex)\n                    return this->m_data.upper(m_colStartIndex[inner] + outer - (inner - m_data.upperProfile(inner)));\n                else\n                    return Scalar(0);\n            }\n            if (inner < outer) //lower matrix\n            {\n                const Index minInnerIndex = outer - m_data.lowerProfile(outer);\n                if (inner >= minInnerIndex)\n                    return this->m_data.lower(m_rowStartIndex[outer] + inner - (outer - m_data.lowerProfile(outer)));\n                else\n                    return Scalar(0);\n            }\n            return m_data.upper(m_colStartIndex[inner] + outer - inner);\n        } else {\n            if (outer > inner) //upper matrix\n            {\n                const Index maxOuterIndex = inner + m_data.upperProfile(inner);\n                if (outer <= maxOuterIndex)\n                    return this->m_data.upper(m_colStartIndex[inner] + (outer - inner));\n                else\n                    return Scalar(0);\n            }\n            if (outer < inner) //lower matrix\n            {\n                const Index maxInnerIndex = outer + m_data.lowerProfile(outer);\n\n                if (inner <= maxInnerIndex)\n                    return this->m_data.lower(m_rowStartIndex[outer] + (inner - outer));\n                else\n                    return Scalar(0);\n            }\n        }\n    }\n\n    inline Scalar& coeffRef(Index row, Index col) {\n        const Index outer = IsRowMajor ? row : col;\n        const Index inner = IsRowMajor ? col : row;\n\n        eigen_assert(outer < outerSize());\n        eigen_assert(inner < innerSize());\n\n        if (outer == inner)\n            return this->m_data.diag(outer);\n\n        if (IsRowMajor) {\n            if (col > row) //upper matrix\n            {\n                const Index minOuterIndex = inner - m_data.upperProfile(inner);\n                eigen_assert(outer >= minOuterIndex && \"You tried to access a coeff that does not exist in the storage\");\n                return this->m_data.upper(m_colStartIndex[inner] + outer - (inner - m_data.upperProfile(inner)));\n            }\n            if (col < row) //lower matrix\n            {\n                const Index minInnerIndex = outer - m_data.lowerProfile(outer);\n                eigen_assert(inner >= minInnerIndex && \"You tried to access a coeff that does not exist in the storage\");\n                return this->m_data.lower(m_rowStartIndex[outer] + inner - (outer - m_data.lowerProfile(outer)));\n            }\n        } else {\n            if (outer > inner) //upper matrix\n            {\n                const Index maxOuterIndex = inner + m_data.upperProfile(inner);\n                eigen_assert(outer <= maxOuterIndex && \"You tried to access a coeff that does not exist in the storage\");\n                return this->m_data.upper(m_colStartIndex[inner] + (outer - inner));\n            }\n            if (outer < inner) //lower matrix\n            {\n                const Index maxInnerIndex = outer + m_data.lowerProfile(outer);\n                eigen_assert(inner <= maxInnerIndex && \"You tried to access a coeff that does not exist in the storage\");\n                return this->m_data.lower(m_rowStartIndex[outer] + (inner - outer));\n            }\n        }\n    }\n\n    inline Scalar coeffDiag(Index idx) const {\n        eigen_assert(idx < outerSize());\n        eigen_assert(idx < innerSize());\n        return this->m_data.diag(idx);\n    }\n\n    inline Scalar coeffLower(Index row, Index col) const {\n        const Index outer = IsRowMajor ? row : col;\n        const Index inner = IsRowMajor ? col : row;\n\n        eigen_assert(outer < outerSize());\n        eigen_assert(inner < innerSize());\n        eigen_assert(inner != outer);\n\n        if (IsRowMajor) {\n            const Index minInnerIndex = outer - m_data.lowerProfile(outer);\n            if (inner >= minInnerIndex)\n                return this->m_data.lower(m_rowStartIndex[outer] + inner - (outer - m_data.lowerProfile(outer)));\n            else\n                return Scalar(0);\n\n        } else {\n            const Index maxInnerIndex = outer + m_data.lowerProfile(outer);\n            if (inner <= maxInnerIndex)\n                return this->m_data.lower(m_rowStartIndex[outer] + (inner - outer));\n            else\n                return Scalar(0);\n        }\n    }\n\n    inline Scalar coeffUpper(Index row, Index col) const {\n        const Index outer = IsRowMajor ? row : col;\n        const Index inner = IsRowMajor ? col : row;\n\n        eigen_assert(outer < outerSize());\n        eigen_assert(inner < innerSize());\n        eigen_assert(inner != outer);\n\n        if (IsRowMajor) {\n            const Index minOuterIndex = inner - m_data.upperProfile(inner);\n            if (outer >= minOuterIndex)\n                return this->m_data.upper(m_colStartIndex[inner] + outer - (inner - m_data.upperProfile(inner)));\n            else\n                return Scalar(0);\n        } else {\n            const Index maxOuterIndex = inner + m_data.upperProfile(inner);\n            if (outer <= maxOuterIndex)\n                return this->m_data.upper(m_colStartIndex[inner] + (outer - inner));\n            else\n                return Scalar(0);\n        }\n    }\n\n    inline Scalar& coeffRefDiag(Index idx) {\n        eigen_assert(idx < outerSize());\n        eigen_assert(idx < innerSize());\n        return this->m_data.diag(idx);\n    }\n\n    inline Scalar& coeffRefLower(Index row, Index col) {\n        const Index outer = IsRowMajor ? row : col;\n        const Index inner = IsRowMajor ? col : row;\n\n        eigen_assert(outer < outerSize());\n        eigen_assert(inner < innerSize());\n        eigen_assert(inner != outer);\n\n        if (IsRowMajor) {\n            const Index minInnerIndex = outer - m_data.lowerProfile(outer);\n            eigen_assert(inner >= minInnerIndex && \"You tried to access a coeff that does not exist in the storage\");\n            return this->m_data.lower(m_rowStartIndex[outer] + inner - (outer - m_data.lowerProfile(outer)));\n        } else {\n            const Index maxInnerIndex = outer + m_data.lowerProfile(outer);\n            eigen_assert(inner <= maxInnerIndex && \"You tried to access a coeff that does not exist in the storage\");\n            return this->m_data.lower(m_rowStartIndex[outer] + (inner - outer));\n        }\n    }\n\n    inline bool coeffExistLower(Index row, Index col) {\n        const Index outer = IsRowMajor ? row : col;\n        const Index inner = IsRowMajor ? col : row;\n\n        eigen_assert(outer < outerSize());\n        eigen_assert(inner < innerSize());\n        eigen_assert(inner != outer);\n\n        if (IsRowMajor) {\n            const Index minInnerIndex = outer - m_data.lowerProfile(outer);\n            return inner >= minInnerIndex;\n        } else {\n            const Index maxInnerIndex = outer + m_data.lowerProfile(outer);\n            return inner <= maxInnerIndex;\n        }\n    }\n\n    inline Scalar& coeffRefUpper(Index row, Index col) {\n        const Index outer = IsRowMajor ? row : col;\n        const Index inner = IsRowMajor ? col : row;\n\n        eigen_assert(outer < outerSize());\n        eigen_assert(inner < innerSize());\n        eigen_assert(inner != outer);\n\n        if (IsRowMajor) {\n            const Index minOuterIndex = inner - m_data.upperProfile(inner);\n            eigen_assert(outer >= minOuterIndex && \"You tried to access a coeff that does not exist in the storage\");\n            return this->m_data.upper(m_colStartIndex[inner] + outer - (inner - m_data.upperProfile(inner)));\n        } else {\n            const Index maxOuterIndex = inner + m_data.upperProfile(inner);\n            eigen_assert(outer <= maxOuterIndex && \"You tried to access a coeff that does not exist in the storage\");\n            return this->m_data.upper(m_colStartIndex[inner] + (outer - inner));\n        }\n    }\n\n    inline bool coeffExistUpper(Index row, Index col) {\n        const Index outer = IsRowMajor ? row : col;\n        const Index inner = IsRowMajor ? col : row;\n\n        eigen_assert(outer < outerSize());\n        eigen_assert(inner < innerSize());\n        eigen_assert(inner != outer);\n\n        if (IsRowMajor) {\n            const Index minOuterIndex = inner - m_data.upperProfile(inner);\n            return outer >= minOuterIndex;\n        } else {\n            const Index maxOuterIndex = inner + m_data.upperProfile(inner);\n            return outer <= maxOuterIndex;\n        }\n    }\n\n\nprotected:\n\npublic:\n    class InnerUpperIterator;\n    class InnerLowerIterator;\n\n    class OuterUpperIterator;\n    class OuterLowerIterator;\n\n    /** Removes all non zeros */\n    inline void setZero() {\n        m_data.clear();\n        memset(m_colStartIndex, 0, (m_outerSize + 1) * sizeof (Index));\n        memset(m_rowStartIndex, 0, (m_outerSize + 1) * sizeof (Index));\n    }\n\n    /** \\returns the number of non zero coefficients */\n    inline Index nonZeros() const {\n        return m_data.diagSize() + m_data.upperSize() + m_data.lowerSize();\n    }\n\n    /** Preallocates \\a reserveSize non zeros */\n    inline void reserve(Index reserveSize, Index reserveUpperSize, Index reserveLowerSize) {\n        m_data.reserve(reserveSize, reserveUpperSize, reserveLowerSize);\n    }\n\n    /** \\returns a reference to a novel non zero coefficient with coordinates \\a row x \\a col.\n\n     *\n     * \\warning This function can be extremely slow if the non zero coefficients\n     * are not inserted in a coherent order.\n     *\n     * After an insertion session, you should call the finalize() function.\n     */\n    EIGEN_DONT_INLINE Scalar & insert(Index row, Index col) {\n        const Index outer = IsRowMajor ? row : col;\n        const Index inner = IsRowMajor ? col : row;\n\n        eigen_assert(outer < outerSize());\n        eigen_assert(inner < innerSize());\n\n        if (outer == inner)\n            return m_data.diag(col);\n\n        if (IsRowMajor) {\n            if (outer < inner) //upper matrix\n            {\n                Index minOuterIndex = 0;\n                minOuterIndex = inner - m_data.upperProfile(inner);\n\n                if (outer < minOuterIndex) //The value does not yet exist\n                {\n                    const Index previousProfile = m_data.upperProfile(inner);\n\n                    m_data.upperProfile(inner) = inner - outer;\n\n\n                    const Index bandIncrement = m_data.upperProfile(inner) - previousProfile;\n                    //shift data stored after this new one\n                    const Index stop = m_colStartIndex[cols()];\n                    const Index start = m_colStartIndex[inner];\n\n\n                    for (Index innerIdx = stop; innerIdx >= start; innerIdx--) {\n                        m_data.upper(innerIdx + bandIncrement) = m_data.upper(innerIdx);\n                    }\n\n                    for (Index innerIdx = cols(); innerIdx > inner; innerIdx--) {\n                        m_colStartIndex[innerIdx] += bandIncrement;\n                    }\n\n                    //zeros new data\n                    memset(this->_upperPtr() + start, 0, (bandIncrement - 1) * sizeof (Scalar));\n\n                    return m_data.upper(m_colStartIndex[inner]);\n                } else {\n                    return m_data.upper(m_colStartIndex[inner] + outer - (inner - m_data.upperProfile(inner)));\n                }\n            }\n\n            if (outer > inner) //lower matrix\n            {\n                const Index minInnerIndex = outer - m_data.lowerProfile(outer);\n                if (inner < minInnerIndex) //The value does not yet exist\n                {\n                    const Index previousProfile = m_data.lowerProfile(outer);\n                    m_data.lowerProfile(outer) = outer - inner;\n\n                    const Index bandIncrement = m_data.lowerProfile(outer) - previousProfile;\n                    //shift data stored after this new one\n                    const Index stop = m_rowStartIndex[rows()];\n                    const Index start = m_rowStartIndex[outer];\n\n\n                    for (Index innerIdx = stop; innerIdx >= start; innerIdx--) {\n                        m_data.lower(innerIdx + bandIncrement) = m_data.lower(innerIdx);\n                    }\n\n                    for (Index innerIdx = rows(); innerIdx > outer; innerIdx--) {\n                        m_rowStartIndex[innerIdx] += bandIncrement;\n                    }\n\n                    //zeros new data\n                    memset(this->_lowerPtr() + start, 0, (bandIncrement - 1) * sizeof (Scalar));\n                    return m_data.lower(m_rowStartIndex[outer]);\n                } else {\n                    return m_data.lower(m_rowStartIndex[outer] + inner - (outer - m_data.lowerProfile(outer)));\n                }\n            }\n        } else {\n            if (outer > inner) //upper matrix\n            {\n                const Index maxOuterIndex = inner + m_data.upperProfile(inner);\n                if (outer > maxOuterIndex) //The value does not yet exist\n                {\n                    const Index previousProfile = m_data.upperProfile(inner);\n                    m_data.upperProfile(inner) = outer - inner;\n\n                    const Index bandIncrement = m_data.upperProfile(inner) - previousProfile;\n                    //shift data stored after this new one\n                    const Index stop = m_rowStartIndex[rows()];\n                    const Index start = m_rowStartIndex[inner + 1];\n\n                    for (Index innerIdx = stop; innerIdx >= start; innerIdx--) {\n                        m_data.upper(innerIdx + bandIncrement) = m_data.upper(innerIdx);\n                    }\n\n                    for (Index innerIdx = inner + 1; innerIdx < outerSize() + 1; innerIdx++) {\n                        m_rowStartIndex[innerIdx] += bandIncrement;\n                    }\n                    memset(this->_upperPtr() + m_rowStartIndex[inner] + previousProfile + 1, 0, (bandIncrement - 1) * sizeof (Scalar));\n                    return m_data.upper(m_rowStartIndex[inner] + m_data.upperProfile(inner));\n                } else {\n                    return m_data.upper(m_rowStartIndex[inner] + (outer - inner));\n                }\n            }\n\n            if (outer < inner) //lower matrix\n            {\n                const Index maxInnerIndex = outer + m_data.lowerProfile(outer);\n                if (inner > maxInnerIndex) //The value does not yet exist\n                {\n                    const Index previousProfile = m_data.lowerProfile(outer);\n                    m_data.lowerProfile(outer) = inner - outer;\n\n                    const Index bandIncrement = m_data.lowerProfile(outer) - previousProfile;\n                    //shift data stored after this new one\n                    const Index stop = m_colStartIndex[cols()];\n                    const Index start = m_colStartIndex[outer + 1];\n\n                    for (Index innerIdx = stop; innerIdx >= start; innerIdx--) {\n                        m_data.lower(innerIdx + bandIncrement) = m_data.lower(innerIdx);\n                    }\n\n                    for (Index innerIdx = outer + 1; innerIdx < outerSize() + 1; innerIdx++) {\n                        m_colStartIndex[innerIdx] += bandIncrement;\n                    }\n                    memset(this->_lowerPtr() + m_colStartIndex[outer] + previousProfile + 1, 0, (bandIncrement - 1) * sizeof (Scalar));\n                    return m_data.lower(m_colStartIndex[outer] + m_data.lowerProfile(outer));\n                } else {\n                    return m_data.lower(m_colStartIndex[outer] + (inner - outer));\n                }\n            }\n        }\n    }\n\n    /** Must be called after inserting a set of non zero entries.\n     */\n    inline void finalize() {\n        if (IsRowMajor) {\n            if (rows() > cols())\n                m_data.resize(cols(), cols(), rows(), m_colStartIndex[cols()] + 1, m_rowStartIndex[rows()] + 1);\n            else\n                m_data.resize(rows(), cols(), rows(), m_colStartIndex[cols()] + 1, m_rowStartIndex[rows()] + 1);\n\n            //            eigen_assert(rows() == cols() && \"memory reorganisatrion only works with suare matrix\");\n            //\n            //            Scalar* newArray = new Scalar[m_colStartIndex[cols()] + 1 + m_rowStartIndex[rows()] + 1];\n            //            Index dataIdx = 0;\n            //            for (Index row = 0; row < rows(); row++) {\n            //\n            //                const Index nbLowerElts = m_rowStartIndex[row + 1] - m_rowStartIndex[row];\n            //                //                std::cout << \"nbLowerElts\" << nbLowerElts << std::endl;\n            //                memcpy(newArray + dataIdx, m_data.m_lower + m_rowStartIndex[row], nbLowerElts * sizeof (Scalar));\n            //                m_rowStartIndex[row] = dataIdx;\n            //                dataIdx += nbLowerElts;\n            //\n            //                const Index nbUpperElts = m_colStartIndex[row + 1] - m_colStartIndex[row];\n            //                memcpy(newArray + dataIdx, m_data.m_upper + m_colStartIndex[row], nbUpperElts * sizeof (Scalar));\n            //                m_colStartIndex[row] = dataIdx;\n            //                dataIdx += nbUpperElts;\n            //\n            //\n            //            }\n            //            //todo : don't access m_data profile directly : add an accessor from SkylineMatrix\n            //            m_rowStartIndex[rows()] = m_rowStartIndex[rows()-1] + m_data.lowerProfile(rows()-1);\n            //            m_colStartIndex[cols()] = m_colStartIndex[cols()-1] + m_data.upperProfile(cols()-1);\n            //\n            //            delete[] m_data.m_lower;\n            //            delete[] m_data.m_upper;\n            //\n            //            m_data.m_lower = newArray;\n            //            m_data.m_upper = newArray;\n        } else {\n            if (rows() > cols())\n                m_data.resize(cols(), rows(), cols(), m_rowStartIndex[cols()] + 1, m_colStartIndex[cols()] + 1);\n            else\n                m_data.resize(rows(), rows(), cols(), m_rowStartIndex[rows()] + 1, m_colStartIndex[rows()] + 1);\n        }\n    }\n\n    inline void squeeze() {\n        finalize();\n        m_data.squeeze();\n    }\n\n    void prune(Scalar reference, RealScalar epsilon = dummy_precision<RealScalar > ()) {\n        //TODO\n    }\n\n    /** Resizes the matrix to a \\a rows x \\a cols matrix and initializes it to zero\n     * \\sa resizeNonZeros(Index), reserve(), setZero()\n     */\n    void resize(size_t rows, size_t cols) {\n        const Index diagSize = rows > cols ? cols : rows;\n        m_innerSize = IsRowMajor ? cols : rows;\n\n        eigen_assert(rows == cols && \"Skyline matrix must be square matrix\");\n\n        if (diagSize % 2) { // diagSize is odd\n            const Index k = (diagSize - 1) / 2;\n\n            m_data.resize(diagSize, IsRowMajor ? cols : rows, IsRowMajor ? rows : cols,\n                    2 * k * k + k + 1,\n                    2 * k * k + k + 1);\n\n        } else // diagSize is even\n        {\n            const Index k = diagSize / 2;\n            m_data.resize(diagSize, IsRowMajor ? cols : rows, IsRowMajor ? rows : cols,\n                    2 * k * k - k + 1,\n                    2 * k * k - k + 1);\n        }\n\n        if (m_colStartIndex && m_rowStartIndex) {\n            delete[] m_colStartIndex;\n            delete[] m_rowStartIndex;\n        }\n        m_colStartIndex = new Index [cols + 1];\n        m_rowStartIndex = new Index [rows + 1];\n        m_outerSize = diagSize;\n\n        m_data.reset();\n        m_data.clear();\n\n        m_outerSize = diagSize;\n        memset(m_colStartIndex, 0, (cols + 1) * sizeof (Index));\n        memset(m_rowStartIndex, 0, (rows + 1) * sizeof (Index));\n    }\n\n    void resizeNonZeros(Index size) {\n        m_data.resize(size);\n    }\n\n    inline SkylineMatrix()\n    : m_outerSize(-1), m_innerSize(0), m_colStartIndex(0), m_rowStartIndex(0) {\n        resize(0, 0);\n    }\n\n    inline SkylineMatrix(size_t rows, size_t cols)\n    : m_outerSize(0), m_innerSize(0), m_colStartIndex(0), m_rowStartIndex(0) {\n        resize(rows, cols);\n    }\n\n    template<typename OtherDerived>\n    inline SkylineMatrix(const SkylineMatrixBase<OtherDerived>& other)\n    : m_outerSize(0), m_innerSize(0), m_colStartIndex(0), m_rowStartIndex(0) {\n        *this = other.derived();\n    }\n\n    inline SkylineMatrix(const SkylineMatrix & other)\n    : Base(), m_outerSize(0), m_innerSize(0), m_colStartIndex(0), m_rowStartIndex(0) {\n        *this = other.derived();\n    }\n\n    inline void swap(SkylineMatrix & other) {\n        //EIGEN_DBG_SKYLINE(std::cout << \"SkylineMatrix:: swap\\n\");\n        std::swap(m_colStartIndex, other.m_colStartIndex);\n        std::swap(m_rowStartIndex, other.m_rowStartIndex);\n        std::swap(m_innerSize, other.m_innerSize);\n        std::swap(m_outerSize, other.m_outerSize);\n        m_data.swap(other.m_data);\n    }\n\n    inline SkylineMatrix & operator=(const SkylineMatrix & other) {\n        std::cout << \"SkylineMatrix& operator=(const SkylineMatrix& other)\\n\";\n        if (other.isRValue()) {\n            swap(other.const_cast_derived());\n        } else {\n            resize(other.rows(), other.cols());\n            memcpy(m_colStartIndex, other.m_colStartIndex, (m_outerSize + 1) * sizeof (Index));\n            memcpy(m_rowStartIndex, other.m_rowStartIndex, (m_outerSize + 1) * sizeof (Index));\n            m_data = other.m_data;\n        }\n        return *this;\n    }\n\n    template<typename OtherDerived>\n            inline SkylineMatrix & operator=(const SkylineMatrixBase<OtherDerived>& other) {\n        const bool needToTranspose = (Flags & RowMajorBit) != (OtherDerived::Flags & RowMajorBit);\n        if (needToTranspose) {\n            //         TODO\n            //            return *this;\n        } else {\n            // there is no special optimization\n            return SkylineMatrixBase<SkylineMatrix>::operator=(other.derived());\n        }\n    }\n\n    friend std::ostream & operator <<(std::ostream & s, const SkylineMatrix & m) {\n\n        EIGEN_DBG_SKYLINE(\n        std::cout << \"upper elements : \" << std::endl;\n        for (Index i = 0; i < m.m_data.upperSize(); i++)\n            std::cout << m.m_data.upper(i) << \"\\t\";\n        std::cout << std::endl;\n        std::cout << \"upper profile : \" << std::endl;\n        for (Index i = 0; i < m.m_data.upperProfileSize(); i++)\n            std::cout << m.m_data.upperProfile(i) << \"\\t\";\n        std::cout << std::endl;\n        std::cout << \"lower startIdx : \" << std::endl;\n        for (Index i = 0; i < m.m_data.upperProfileSize(); i++)\n            std::cout << (IsRowMajor ? m.m_colStartIndex[i] : m.m_rowStartIndex[i]) << \"\\t\";\n        std::cout << std::endl;\n\n\n        std::cout << \"lower elements : \" << std::endl;\n        for (Index i = 0; i < m.m_data.lowerSize(); i++)\n            std::cout << m.m_data.lower(i) << \"\\t\";\n        std::cout << std::endl;\n        std::cout << \"lower profile : \" << std::endl;\n        for (Index i = 0; i < m.m_data.lowerProfileSize(); i++)\n            std::cout << m.m_data.lowerProfile(i) << \"\\t\";\n        std::cout << std::endl;\n        std::cout << \"lower startIdx : \" << std::endl;\n        for (Index i = 0; i < m.m_data.lowerProfileSize(); i++)\n            std::cout << (IsRowMajor ? m.m_rowStartIndex[i] : m.m_colStartIndex[i]) << \"\\t\";\n        std::cout << std::endl;\n        );\n        for (Index rowIdx = 0; rowIdx < m.rows(); rowIdx++) {\n            for (Index colIdx = 0; colIdx < m.cols(); colIdx++) {\n                s << m.coeff(rowIdx, colIdx) << \"\\t\";\n            }\n            s << std::endl;\n        }\n        return s;\n    }\n\n    /** Destructor */\n    inline ~SkylineMatrix() {\n        delete[] m_colStartIndex;\n        delete[] m_rowStartIndex;\n    }\n\n    /** Overloaded for performance */\n    Scalar sum() const;\n};\n\ntemplate<typename Scalar, int _Options>\nclass SkylineMatrix<Scalar, _Options>::InnerUpperIterator {\npublic:\n\n    InnerUpperIterator(const SkylineMatrix& mat, Index outer)\n    : m_matrix(mat), m_outer(outer),\n    m_id(_Options == RowMajor ? mat.m_colStartIndex[outer] : mat.m_rowStartIndex[outer] + 1),\n    m_start(m_id),\n    m_end(_Options == RowMajor ? mat.m_colStartIndex[outer + 1] : mat.m_rowStartIndex[outer + 1] + 1) {\n    }\n\n    inline InnerUpperIterator & operator++() {\n        m_id++;\n        return *this;\n    }\n\n    inline InnerUpperIterator & operator+=(Index shift) {\n        m_id += shift;\n        return *this;\n    }\n\n    inline Scalar value() const {\n        return m_matrix.m_data.upper(m_id);\n    }\n\n    inline Scalar* valuePtr() {\n        return const_cast<Scalar*> (&(m_matrix.m_data.upper(m_id)));\n    }\n\n    inline Scalar& valueRef() {\n        return const_cast<Scalar&> (m_matrix.m_data.upper(m_id));\n    }\n\n    inline Index index() const {\n        return IsRowMajor ? m_outer - m_matrix.m_data.upperProfile(m_outer) + (m_id - m_start) :\n                m_outer + (m_id - m_start) + 1;\n    }\n\n    inline Index row() const {\n        return IsRowMajor ? index() : m_outer;\n    }\n\n    inline Index col() const {\n        return IsRowMajor ? m_outer : index();\n    }\n\n    inline size_t size() const {\n        return m_matrix.m_data.upperProfile(m_outer);\n    }\n\n    inline operator bool() const {\n        return (m_id < m_end) && (m_id >= m_start);\n    }\n\nprotected:\n    const SkylineMatrix& m_matrix;\n    const Index m_outer;\n    Index m_id;\n    const Index m_start;\n    const Index m_end;\n};\n\ntemplate<typename Scalar, int _Options>\nclass SkylineMatrix<Scalar, _Options>::InnerLowerIterator {\npublic:\n\n    InnerLowerIterator(const SkylineMatrix& mat, Index outer)\n    : m_matrix(mat),\n    m_outer(outer),\n    m_id(_Options == RowMajor ? mat.m_rowStartIndex[outer] : mat.m_colStartIndex[outer] + 1),\n    m_start(m_id),\n    m_end(_Options == RowMajor ? mat.m_rowStartIndex[outer + 1] : mat.m_colStartIndex[outer + 1] + 1) {\n    }\n\n    inline InnerLowerIterator & operator++() {\n        m_id++;\n        return *this;\n    }\n\n    inline InnerLowerIterator & operator+=(Index shift) {\n        m_id += shift;\n        return *this;\n    }\n\n    inline Scalar value() const {\n        return m_matrix.m_data.lower(m_id);\n    }\n\n    inline Scalar* valuePtr() {\n        return const_cast<Scalar*> (&(m_matrix.m_data.lower(m_id)));\n    }\n\n    inline Scalar& valueRef() {\n        return const_cast<Scalar&> (m_matrix.m_data.lower(m_id));\n    }\n\n    inline Index index() const {\n        return IsRowMajor ? m_outer - m_matrix.m_data.lowerProfile(m_outer) + (m_id - m_start) :\n                m_outer + (m_id - m_start) + 1;\n        ;\n    }\n\n    inline Index row() const {\n        return IsRowMajor ? m_outer : index();\n    }\n\n    inline Index col() const {\n        return IsRowMajor ? index() : m_outer;\n    }\n\n    inline size_t size() const {\n        return m_matrix.m_data.lowerProfile(m_outer);\n    }\n\n    inline operator bool() const {\n        return (m_id < m_end) && (m_id >= m_start);\n    }\n\nprotected:\n    const SkylineMatrix& m_matrix;\n    const Index m_outer;\n    Index m_id;\n    const Index m_start;\n    const Index m_end;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_SKYLINEMATRIX_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/Skyline/SkylineMatrixBase.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Guillaume Saupin <guillaume.saupin@cea.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SKYLINEMATRIXBASE_H\n#define EIGEN_SKYLINEMATRIXBASE_H\n\n#include \"SkylineUtil.h\"\n\nnamespace Eigen { \n\n/** \\ingroup Skyline_Module\n *\n * \\class SkylineMatrixBase\n *\n * \\brief Base class of any skyline matrices or skyline expressions\n *\n * \\param Derived\n *\n */\ntemplate<typename Derived> class SkylineMatrixBase : public EigenBase<Derived> {\npublic:\n\n    typedef typename internal::traits<Derived>::Scalar Scalar;\n    typedef typename internal::traits<Derived>::StorageKind StorageKind;\n    typedef typename internal::index<StorageKind>::type Index;\n\n    enum {\n        RowsAtCompileTime = internal::traits<Derived>::RowsAtCompileTime,\n        /**< The number of rows at compile-time. This is just a copy of the value provided\n         * by the \\a Derived type. If a value is not known at compile-time,\n         * it is set to the \\a Dynamic constant.\n         * \\sa MatrixBase::rows(), MatrixBase::cols(), ColsAtCompileTime, SizeAtCompileTime */\n\n        ColsAtCompileTime = internal::traits<Derived>::ColsAtCompileTime,\n        /**< The number of columns at compile-time. This is just a copy of the value provided\n         * by the \\a Derived type. If a value is not known at compile-time,\n         * it is set to the \\a Dynamic constant.\n         * \\sa MatrixBase::rows(), MatrixBase::cols(), RowsAtCompileTime, SizeAtCompileTime */\n\n\n        SizeAtCompileTime = (internal::size_at_compile_time<internal::traits<Derived>::RowsAtCompileTime,\n        internal::traits<Derived>::ColsAtCompileTime>::ret),\n        /**< This is equal to the number of coefficients, i.e. the number of\n         * rows times the number of columns, or to \\a Dynamic if this is not\n         * known at compile-time. \\sa RowsAtCompileTime, ColsAtCompileTime */\n\n        MaxRowsAtCompileTime = RowsAtCompileTime,\n        MaxColsAtCompileTime = ColsAtCompileTime,\n\n        MaxSizeAtCompileTime = (internal::size_at_compile_time<MaxRowsAtCompileTime,\n        MaxColsAtCompileTime>::ret),\n\n        IsVectorAtCompileTime = RowsAtCompileTime == 1 || ColsAtCompileTime == 1,\n        /**< This is set to true if either the number of rows or the number of\n         * columns is known at compile-time to be equal to 1. Indeed, in that case,\n         * we are dealing with a column-vector (if there is only one column) or with\n         * a row-vector (if there is only one row). */\n\n        Flags = internal::traits<Derived>::Flags,\n        /**< This stores expression \\ref flags flags which may or may not be inherited by new expressions\n         * constructed from this one. See the \\ref flags \"list of flags\".\n         */\n\n        CoeffReadCost = internal::traits<Derived>::CoeffReadCost,\n        /**< This is a rough measure of how expensive it is to read one coefficient from\n         * this expression.\n         */\n\n        IsRowMajor = Flags & RowMajorBit ? 1 : 0\n    };\n\n#ifndef EIGEN_PARSED_BY_DOXYGEN\n    /** This is the \"real scalar\" type; if the \\a Scalar type is already real numbers\n     * (e.g. int, float or double) then \\a RealScalar is just the same as \\a Scalar. If\n     * \\a Scalar is \\a std::complex<T> then RealScalar is \\a T.\n     *\n     * \\sa class NumTraits\n     */\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n\n    /** type of the equivalent square matrix */\n    typedef Matrix<Scalar, EIGEN_SIZE_MAX(RowsAtCompileTime, ColsAtCompileTime),\n                           EIGEN_SIZE_MAX(RowsAtCompileTime, ColsAtCompileTime) > SquareMatrixType;\n\n    inline const Derived& derived() const {\n        return *static_cast<const Derived*> (this);\n    }\n\n    inline Derived& derived() {\n        return *static_cast<Derived*> (this);\n    }\n\n    inline Derived& const_cast_derived() const {\n        return *static_cast<Derived*> (const_cast<SkylineMatrixBase*> (this));\n    }\n#endif // not EIGEN_PARSED_BY_DOXYGEN\n\n    /** \\returns the number of rows. \\sa cols(), RowsAtCompileTime */\n    inline Index rows() const {\n        return derived().rows();\n    }\n\n    /** \\returns the number of columns. \\sa rows(), ColsAtCompileTime*/\n    inline Index cols() const {\n        return derived().cols();\n    }\n\n    /** \\returns the number of coefficients, which is \\a rows()*cols().\n     * \\sa rows(), cols(), SizeAtCompileTime. */\n    inline Index size() const {\n        return rows() * cols();\n    }\n\n    /** \\returns the number of nonzero coefficients which is in practice the number\n     * of stored coefficients. */\n    inline Index nonZeros() const {\n        return derived().nonZeros();\n    }\n\n    /** \\returns the size of the storage major dimension,\n     * i.e., the number of columns for a columns major matrix, and the number of rows otherwise */\n    Index outerSize() const {\n        return (int(Flags) & RowMajorBit) ? this->rows() : this->cols();\n    }\n\n    /** \\returns the size of the inner dimension according to the storage order,\n     * i.e., the number of rows for a columns major matrix, and the number of cols otherwise */\n    Index innerSize() const {\n        return (int(Flags) & RowMajorBit) ? this->cols() : this->rows();\n    }\n\n    bool isRValue() const {\n        return m_isRValue;\n    }\n\n    Derived& markAsRValue() {\n        m_isRValue = true;\n        return derived();\n    }\n\n    SkylineMatrixBase() : m_isRValue(false) {\n        /* TODO check flags */\n    }\n\n    inline Derived & operator=(const Derived& other) {\n        this->operator=<Derived > (other);\n        return derived();\n    }\n\n    template<typename OtherDerived>\n    inline void assignGeneric(const OtherDerived& other) {\n        derived().resize(other.rows(), other.cols());\n        for (Index row = 0; row < rows(); row++)\n            for (Index col = 0; col < cols(); col++) {\n                if (other.coeff(row, col) != Scalar(0))\n                    derived().insert(row, col) = other.coeff(row, col);\n            }\n        derived().finalize();\n    }\n\n    template<typename OtherDerived>\n            inline Derived & operator=(const SkylineMatrixBase<OtherDerived>& other) {\n        //TODO\n    }\n\n    template<typename Lhs, typename Rhs>\n            inline Derived & operator=(const SkylineProduct<Lhs, Rhs, SkylineTimeSkylineProduct>& product);\n\n    friend std::ostream & operator <<(std::ostream & s, const SkylineMatrixBase& m) {\n        s << m.derived();\n        return s;\n    }\n\n    template<typename OtherDerived>\n    const typename SkylineProductReturnType<Derived, OtherDerived>::Type\n    operator*(const MatrixBase<OtherDerived> &other) const;\n\n    /** \\internal use operator= */\n    template<typename DenseDerived>\n    void evalTo(MatrixBase<DenseDerived>& dst) const {\n        dst.setZero();\n        for (Index i = 0; i < rows(); i++)\n            for (Index j = 0; j < rows(); j++)\n                dst(i, j) = derived().coeff(i, j);\n    }\n\n    Matrix<Scalar, RowsAtCompileTime, ColsAtCompileTime> toDense() const {\n        return derived();\n    }\n\n    /** \\returns the matrix or vector obtained by evaluating this expression.\n     *\n     * Notice that in the case of a plain matrix or vector (not an expression) this function just returns\n     * a const reference, in order to avoid a useless copy.\n     */\n    EIGEN_STRONG_INLINE const typename internal::eval<Derived, IsSkyline>::type eval() const {\n        return typename internal::eval<Derived>::type(derived());\n    }\n\nprotected:\n    bool m_isRValue;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_SKYLINEMATRIXBASE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/Skyline/SkylineProduct.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Guillaume Saupin <guillaume.saupin@cea.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SKYLINEPRODUCT_H\n#define EIGEN_SKYLINEPRODUCT_H\n\nnamespace Eigen { \n\ntemplate<typename Lhs, typename Rhs, int ProductMode>\nstruct SkylineProductReturnType {\n    typedef const typename internal::nested_eval<Lhs, Rhs::RowsAtCompileTime>::type LhsNested;\n    typedef const typename internal::nested_eval<Rhs, Lhs::RowsAtCompileTime>::type RhsNested;\n\n    typedef SkylineProduct<LhsNested, RhsNested, ProductMode> Type;\n};\n\ntemplate<typename LhsNested, typename RhsNested, int ProductMode>\nstruct internal::traits<SkylineProduct<LhsNested, RhsNested, ProductMode> > {\n    // clean the nested types:\n    typedef typename internal::remove_all<LhsNested>::type _LhsNested;\n    typedef typename internal::remove_all<RhsNested>::type _RhsNested;\n    typedef typename _LhsNested::Scalar Scalar;\n\n    enum {\n        LhsCoeffReadCost = _LhsNested::CoeffReadCost,\n        RhsCoeffReadCost = _RhsNested::CoeffReadCost,\n        LhsFlags = _LhsNested::Flags,\n        RhsFlags = _RhsNested::Flags,\n\n        RowsAtCompileTime = _LhsNested::RowsAtCompileTime,\n        ColsAtCompileTime = _RhsNested::ColsAtCompileTime,\n        InnerSize = EIGEN_SIZE_MIN_PREFER_FIXED(_LhsNested::ColsAtCompileTime, _RhsNested::RowsAtCompileTime),\n\n        MaxRowsAtCompileTime = _LhsNested::MaxRowsAtCompileTime,\n        MaxColsAtCompileTime = _RhsNested::MaxColsAtCompileTime,\n\n        EvalToRowMajor = (RhsFlags & LhsFlags & RowMajorBit),\n        ResultIsSkyline = ProductMode == SkylineTimeSkylineProduct,\n\n        RemovedBits = ~((EvalToRowMajor ? 0 : RowMajorBit) | (ResultIsSkyline ? 0 : SkylineBit)),\n\n        Flags = (int(LhsFlags | RhsFlags) & HereditaryBits & RemovedBits)\n        | EvalBeforeAssigningBit\n        | EvalBeforeNestingBit,\n\n        CoeffReadCost = HugeCost\n    };\n\n    typedef typename internal::conditional<ResultIsSkyline,\n            SkylineMatrixBase<SkylineProduct<LhsNested, RhsNested, ProductMode> >,\n            MatrixBase<SkylineProduct<LhsNested, RhsNested, ProductMode> > >::type Base;\n};\n\nnamespace internal {\ntemplate<typename LhsNested, typename RhsNested, int ProductMode>\nclass SkylineProduct : no_assignment_operator,\npublic traits<SkylineProduct<LhsNested, RhsNested, ProductMode> >::Base {\npublic:\n\n    EIGEN_GENERIC_PUBLIC_INTERFACE(SkylineProduct)\n\nprivate:\n\n    typedef typename traits<SkylineProduct>::_LhsNested _LhsNested;\n    typedef typename traits<SkylineProduct>::_RhsNested _RhsNested;\n\npublic:\n\n    template<typename Lhs, typename Rhs>\n    EIGEN_STRONG_INLINE SkylineProduct(const Lhs& lhs, const Rhs& rhs)\n    : m_lhs(lhs), m_rhs(rhs) {\n        eigen_assert(lhs.cols() == rhs.rows());\n\n        enum {\n            ProductIsValid = _LhsNested::ColsAtCompileTime == Dynamic\n            || _RhsNested::RowsAtCompileTime == Dynamic\n            || int(_LhsNested::ColsAtCompileTime) == int(_RhsNested::RowsAtCompileTime),\n            AreVectors = _LhsNested::IsVectorAtCompileTime && _RhsNested::IsVectorAtCompileTime,\n            SameSizes = EIGEN_PREDICATE_SAME_MATRIX_SIZE(_LhsNested, _RhsNested)\n        };\n        // note to the lost user:\n        //    * for a dot product use: v1.dot(v2)\n        //    * for a coeff-wise product use: v1.cwise()*v2\n        EIGEN_STATIC_ASSERT(ProductIsValid || !(AreVectors && SameSizes),\n                INVALID_VECTOR_VECTOR_PRODUCT__IF_YOU_WANTED_A_DOT_OR_COEFF_WISE_PRODUCT_YOU_MUST_USE_THE_EXPLICIT_FUNCTIONS)\n                EIGEN_STATIC_ASSERT(ProductIsValid || !(SameSizes && !AreVectors),\n                INVALID_MATRIX_PRODUCT__IF_YOU_WANTED_A_COEFF_WISE_PRODUCT_YOU_MUST_USE_THE_EXPLICIT_FUNCTION)\n                EIGEN_STATIC_ASSERT(ProductIsValid || SameSizes, INVALID_MATRIX_PRODUCT)\n    }\n\n    EIGEN_STRONG_INLINE Index rows() const {\n        return m_lhs.rows();\n    }\n\n    EIGEN_STRONG_INLINE Index cols() const {\n        return m_rhs.cols();\n    }\n\n    EIGEN_STRONG_INLINE const _LhsNested& lhs() const {\n        return m_lhs;\n    }\n\n    EIGEN_STRONG_INLINE const _RhsNested& rhs() const {\n        return m_rhs;\n    }\n\nprotected:\n    LhsNested m_lhs;\n    RhsNested m_rhs;\n};\n\n// dense = skyline * dense\n// Note that here we force no inlining and separate the setZero() because GCC messes up otherwise\n\ntemplate<typename Lhs, typename Rhs, typename Dest>\nEIGEN_DONT_INLINE void skyline_row_major_time_dense_product(const Lhs& lhs, const Rhs& rhs, Dest& dst) {\n    typedef typename remove_all<Lhs>::type _Lhs;\n    typedef typename remove_all<Rhs>::type _Rhs;\n    typedef typename traits<Lhs>::Scalar Scalar;\n\n    enum {\n        LhsIsRowMajor = (_Lhs::Flags & RowMajorBit) == RowMajorBit,\n        LhsIsSelfAdjoint = (_Lhs::Flags & SelfAdjointBit) == SelfAdjointBit,\n        ProcessFirstHalf = LhsIsSelfAdjoint\n        && (((_Lhs::Flags & (UpperTriangularBit | LowerTriangularBit)) == 0)\n        || ((_Lhs::Flags & UpperTriangularBit) && !LhsIsRowMajor)\n        || ((_Lhs::Flags & LowerTriangularBit) && LhsIsRowMajor)),\n        ProcessSecondHalf = LhsIsSelfAdjoint && (!ProcessFirstHalf)\n    };\n\n    //Use matrix diagonal part <- Improvement : use inner iterator on dense matrix.\n    for (Index col = 0; col < rhs.cols(); col++) {\n        for (Index row = 0; row < lhs.rows(); row++) {\n            dst(row, col) = lhs.coeffDiag(row) * rhs(row, col);\n        }\n    }\n    //Use matrix lower triangular part\n    for (Index row = 0; row < lhs.rows(); row++) {\n        typename _Lhs::InnerLowerIterator lIt(lhs, row);\n        const Index stop = lIt.col() + lIt.size();\n        for (Index col = 0; col < rhs.cols(); col++) {\n\n            Index k = lIt.col();\n            Scalar tmp = 0;\n            while (k < stop) {\n                tmp +=\n                        lIt.value() *\n                        rhs(k++, col);\n                ++lIt;\n            }\n            dst(row, col) += tmp;\n            lIt += -lIt.size();\n        }\n\n    }\n\n    //Use matrix upper triangular part\n    for (Index lhscol = 0; lhscol < lhs.cols(); lhscol++) {\n        typename _Lhs::InnerUpperIterator uIt(lhs, lhscol);\n        const Index stop = uIt.size() + uIt.row();\n        for (Index rhscol = 0; rhscol < rhs.cols(); rhscol++) {\n\n\n            const Scalar rhsCoeff = rhs.coeff(lhscol, rhscol);\n            Index k = uIt.row();\n            while (k < stop) {\n                dst(k++, rhscol) +=\n                        uIt.value() *\n                        rhsCoeff;\n                ++uIt;\n            }\n            uIt += -uIt.size();\n        }\n    }\n\n}\n\ntemplate<typename Lhs, typename Rhs, typename Dest>\nEIGEN_DONT_INLINE void skyline_col_major_time_dense_product(const Lhs& lhs, const Rhs& rhs, Dest& dst) {\n    typedef typename remove_all<Lhs>::type _Lhs;\n    typedef typename remove_all<Rhs>::type _Rhs;\n    typedef typename traits<Lhs>::Scalar Scalar;\n\n    enum {\n        LhsIsRowMajor = (_Lhs::Flags & RowMajorBit) == RowMajorBit,\n        LhsIsSelfAdjoint = (_Lhs::Flags & SelfAdjointBit) == SelfAdjointBit,\n        ProcessFirstHalf = LhsIsSelfAdjoint\n        && (((_Lhs::Flags & (UpperTriangularBit | LowerTriangularBit)) == 0)\n        || ((_Lhs::Flags & UpperTriangularBit) && !LhsIsRowMajor)\n        || ((_Lhs::Flags & LowerTriangularBit) && LhsIsRowMajor)),\n        ProcessSecondHalf = LhsIsSelfAdjoint && (!ProcessFirstHalf)\n    };\n\n    //Use matrix diagonal part <- Improvement : use inner iterator on dense matrix.\n    for (Index col = 0; col < rhs.cols(); col++) {\n        for (Index row = 0; row < lhs.rows(); row++) {\n            dst(row, col) = lhs.coeffDiag(row) * rhs(row, col);\n        }\n    }\n\n    //Use matrix upper triangular part\n    for (Index row = 0; row < lhs.rows(); row++) {\n        typename _Lhs::InnerUpperIterator uIt(lhs, row);\n        const Index stop = uIt.col() + uIt.size();\n        for (Index col = 0; col < rhs.cols(); col++) {\n\n            Index k = uIt.col();\n            Scalar tmp = 0;\n            while (k < stop) {\n                tmp +=\n                        uIt.value() *\n                        rhs(k++, col);\n                ++uIt;\n            }\n\n\n            dst(row, col) += tmp;\n            uIt += -uIt.size();\n        }\n    }\n\n    //Use matrix lower triangular part\n    for (Index lhscol = 0; lhscol < lhs.cols(); lhscol++) {\n        typename _Lhs::InnerLowerIterator lIt(lhs, lhscol);\n        const Index stop = lIt.size() + lIt.row();\n        for (Index rhscol = 0; rhscol < rhs.cols(); rhscol++) {\n\n            const Scalar rhsCoeff = rhs.coeff(lhscol, rhscol);\n            Index k = lIt.row();\n            while (k < stop) {\n                dst(k++, rhscol) +=\n                        lIt.value() *\n                        rhsCoeff;\n                ++lIt;\n            }\n            lIt += -lIt.size();\n        }\n    }\n\n}\n\ntemplate<typename Lhs, typename Rhs, typename ResultType,\n        int LhsStorageOrder = traits<Lhs>::Flags&RowMajorBit>\n        struct skyline_product_selector;\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct skyline_product_selector<Lhs, Rhs, ResultType, RowMajor> {\n    typedef typename traits<typename remove_all<Lhs>::type>::Scalar Scalar;\n\n    static void run(const Lhs& lhs, const Rhs& rhs, ResultType & res) {\n        skyline_row_major_time_dense_product<Lhs, Rhs, ResultType > (lhs, rhs, res);\n    }\n};\n\ntemplate<typename Lhs, typename Rhs, typename ResultType>\nstruct skyline_product_selector<Lhs, Rhs, ResultType, ColMajor> {\n    typedef typename traits<typename remove_all<Lhs>::type>::Scalar Scalar;\n\n    static void run(const Lhs& lhs, const Rhs& rhs, ResultType & res) {\n        skyline_col_major_time_dense_product<Lhs, Rhs, ResultType > (lhs, rhs, res);\n    }\n};\n\n} // end namespace internal\n\n// template<typename Derived>\n// template<typename Lhs, typename Rhs >\n// Derived & MatrixBase<Derived>::lazyAssign(const SkylineProduct<Lhs, Rhs, SkylineTimeDenseProduct>& product) {\n//     typedef typename internal::remove_all<Lhs>::type _Lhs;\n//     internal::skyline_product_selector<typename internal::remove_all<Lhs>::type,\n//             typename internal::remove_all<Rhs>::type,\n//             Derived>::run(product.lhs(), product.rhs(), derived());\n// \n//     return derived();\n// }\n\n// skyline * dense\n\ntemplate<typename Derived>\ntemplate<typename OtherDerived >\nEIGEN_STRONG_INLINE const typename SkylineProductReturnType<Derived, OtherDerived>::Type\nSkylineMatrixBase<Derived>::operator*(const MatrixBase<OtherDerived> &other) const {\n\n    return typename SkylineProductReturnType<Derived, OtherDerived>::Type(derived(), other.derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SKYLINEPRODUCT_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/Skyline/SkylineStorage.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Guillaume Saupin <guillaume.saupin@cea.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SKYLINE_STORAGE_H\n#define EIGEN_SKYLINE_STORAGE_H\n\nnamespace Eigen { \n\n/** Stores a skyline set of values in three structures :\n * The diagonal elements\n * The upper elements\n * The lower elements\n *\n */\ntemplate<typename Scalar>\nclass SkylineStorage {\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef SparseIndex Index;\npublic:\n\n    SkylineStorage()\n    : m_diag(0),\n    m_lower(0),\n    m_upper(0),\n    m_lowerProfile(0),\n    m_upperProfile(0),\n    m_diagSize(0),\n    m_upperSize(0),\n    m_lowerSize(0),\n    m_upperProfileSize(0),\n    m_lowerProfileSize(0),\n    m_allocatedSize(0) {\n    }\n\n    SkylineStorage(const SkylineStorage& other)\n    : m_diag(0),\n    m_lower(0),\n    m_upper(0),\n    m_lowerProfile(0),\n    m_upperProfile(0),\n    m_diagSize(0),\n    m_upperSize(0),\n    m_lowerSize(0),\n    m_upperProfileSize(0),\n    m_lowerProfileSize(0),\n    m_allocatedSize(0) {\n        *this = other;\n    }\n\n    SkylineStorage & operator=(const SkylineStorage& other) {\n        resize(other.diagSize(), other.m_upperProfileSize, other.m_lowerProfileSize, other.upperSize(), other.lowerSize());\n        memcpy(m_diag, other.m_diag, m_diagSize * sizeof (Scalar));\n        memcpy(m_upper, other.m_upper, other.upperSize() * sizeof (Scalar));\n        memcpy(m_lower, other.m_lower, other.lowerSize() * sizeof (Scalar));\n        memcpy(m_upperProfile, other.m_upperProfile, m_upperProfileSize * sizeof (Index));\n        memcpy(m_lowerProfile, other.m_lowerProfile, m_lowerProfileSize * sizeof (Index));\n        return *this;\n    }\n\n    void swap(SkylineStorage& other) {\n        std::swap(m_diag, other.m_diag);\n        std::swap(m_upper, other.m_upper);\n        std::swap(m_lower, other.m_lower);\n        std::swap(m_upperProfile, other.m_upperProfile);\n        std::swap(m_lowerProfile, other.m_lowerProfile);\n        std::swap(m_diagSize, other.m_diagSize);\n        std::swap(m_upperSize, other.m_upperSize);\n        std::swap(m_lowerSize, other.m_lowerSize);\n        std::swap(m_allocatedSize, other.m_allocatedSize);\n    }\n\n    ~SkylineStorage() {\n        delete[] m_diag;\n        delete[] m_upper;\n        if (m_upper != m_lower)\n            delete[] m_lower;\n        delete[] m_upperProfile;\n        delete[] m_lowerProfile;\n    }\n\n    void reserve(Index size, Index upperProfileSize, Index lowerProfileSize, Index upperSize, Index lowerSize) {\n        Index newAllocatedSize = size + upperSize + lowerSize;\n        if (newAllocatedSize > m_allocatedSize)\n            reallocate(size, upperProfileSize, lowerProfileSize, upperSize, lowerSize);\n    }\n\n    void squeeze() {\n        if (m_allocatedSize > m_diagSize + m_upperSize + m_lowerSize)\n            reallocate(m_diagSize, m_upperProfileSize, m_lowerProfileSize, m_upperSize, m_lowerSize);\n    }\n\n    void resize(Index diagSize, Index upperProfileSize, Index lowerProfileSize, Index upperSize, Index lowerSize, float reserveSizeFactor = 0) {\n        if (m_allocatedSize < diagSize + upperSize + lowerSize)\n            reallocate(diagSize, upperProfileSize, lowerProfileSize, upperSize + Index(reserveSizeFactor * upperSize), lowerSize + Index(reserveSizeFactor * lowerSize));\n        m_diagSize = diagSize;\n        m_upperSize = upperSize;\n        m_lowerSize = lowerSize;\n        m_upperProfileSize = upperProfileSize;\n        m_lowerProfileSize = lowerProfileSize;\n    }\n\n    inline Index diagSize() const {\n        return m_diagSize;\n    }\n\n    inline Index upperSize() const {\n        return m_upperSize;\n    }\n\n    inline Index lowerSize() const {\n        return m_lowerSize;\n    }\n\n    inline Index upperProfileSize() const {\n        return m_upperProfileSize;\n    }\n\n    inline Index lowerProfileSize() const {\n        return m_lowerProfileSize;\n    }\n\n    inline Index allocatedSize() const {\n        return m_allocatedSize;\n    }\n\n    inline void clear() {\n        m_diagSize = 0;\n    }\n\n    inline Scalar& diag(Index i) {\n        return m_diag[i];\n    }\n\n    inline const Scalar& diag(Index i) const {\n        return m_diag[i];\n    }\n\n    inline Scalar& upper(Index i) {\n        return m_upper[i];\n    }\n\n    inline const Scalar& upper(Index i) const {\n        return m_upper[i];\n    }\n\n    inline Scalar& lower(Index i) {\n        return m_lower[i];\n    }\n\n    inline const Scalar& lower(Index i) const {\n        return m_lower[i];\n    }\n\n    inline Index& upperProfile(Index i) {\n        return m_upperProfile[i];\n    }\n\n    inline const Index& upperProfile(Index i) const {\n        return m_upperProfile[i];\n    }\n\n    inline Index& lowerProfile(Index i) {\n        return m_lowerProfile[i];\n    }\n\n    inline const Index& lowerProfile(Index i) const {\n        return m_lowerProfile[i];\n    }\n\n    static SkylineStorage Map(Index* upperProfile, Index* lowerProfile, Scalar* diag, Scalar* upper, Scalar* lower, Index size, Index upperSize, Index lowerSize) {\n        SkylineStorage res;\n        res.m_upperProfile = upperProfile;\n        res.m_lowerProfile = lowerProfile;\n        res.m_diag = diag;\n        res.m_upper = upper;\n        res.m_lower = lower;\n        res.m_allocatedSize = res.m_diagSize = size;\n        res.m_upperSize = upperSize;\n        res.m_lowerSize = lowerSize;\n        return res;\n    }\n\n    inline void reset() {\n        memset(m_diag, 0, m_diagSize * sizeof (Scalar));\n        memset(m_upper, 0, m_upperSize * sizeof (Scalar));\n        memset(m_lower, 0, m_lowerSize * sizeof (Scalar));\n        memset(m_upperProfile, 0, m_diagSize * sizeof (Index));\n        memset(m_lowerProfile, 0, m_diagSize * sizeof (Index));\n    }\n\n    void prune(Scalar reference, RealScalar epsilon = dummy_precision<RealScalar>()) {\n        //TODO\n    }\n\nprotected:\n\n    inline void reallocate(Index diagSize, Index upperProfileSize, Index lowerProfileSize, Index upperSize, Index lowerSize) {\n\n        Scalar* diag = new Scalar[diagSize];\n        Scalar* upper = new Scalar[upperSize];\n        Scalar* lower = new Scalar[lowerSize];\n        Index* upperProfile = new Index[upperProfileSize];\n        Index* lowerProfile = new Index[lowerProfileSize];\n\n        Index copyDiagSize = (std::min)(diagSize, m_diagSize);\n        Index copyUpperSize = (std::min)(upperSize, m_upperSize);\n        Index copyLowerSize = (std::min)(lowerSize, m_lowerSize);\n        Index copyUpperProfileSize = (std::min)(upperProfileSize, m_upperProfileSize);\n        Index copyLowerProfileSize = (std::min)(lowerProfileSize, m_lowerProfileSize);\n\n        // copy\n        memcpy(diag, m_diag, copyDiagSize * sizeof (Scalar));\n        memcpy(upper, m_upper, copyUpperSize * sizeof (Scalar));\n        memcpy(lower, m_lower, copyLowerSize * sizeof (Scalar));\n        memcpy(upperProfile, m_upperProfile, copyUpperProfileSize * sizeof (Index));\n        memcpy(lowerProfile, m_lowerProfile, copyLowerProfileSize * sizeof (Index));\n\n\n\n        // delete old stuff\n        delete[] m_diag;\n        delete[] m_upper;\n        delete[] m_lower;\n        delete[] m_upperProfile;\n        delete[] m_lowerProfile;\n        m_diag = diag;\n        m_upper = upper;\n        m_lower = lower;\n        m_upperProfile = upperProfile;\n        m_lowerProfile = lowerProfile;\n        m_allocatedSize = diagSize + upperSize + lowerSize;\n        m_upperSize = upperSize;\n        m_lowerSize = lowerSize;\n    }\n\npublic:\n    Scalar* m_diag;\n    Scalar* m_upper;\n    Scalar* m_lower;\n    Index* m_upperProfile;\n    Index* m_lowerProfile;\n    Index m_diagSize;\n    Index m_upperSize;\n    Index m_lowerSize;\n    Index m_upperProfileSize;\n    Index m_lowerProfileSize;\n    Index m_allocatedSize;\n\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_SKYLINE_STORAGE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/Skyline/SkylineUtil.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Guillaume Saupin <guillaume.saupin@cea.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SKYLINEUTIL_H\n#define EIGEN_SKYLINEUTIL_H\n\nnamespace Eigen { \n\n#ifdef NDEBUG\n#define EIGEN_DBG_SKYLINE(X)\n#else\n#define EIGEN_DBG_SKYLINE(X) X\n#endif\n\nconst unsigned int SkylineBit = 0x1200;\ntemplate<typename Lhs, typename Rhs, int ProductMode> class SkylineProduct;\nenum AdditionalProductEvaluationMode {SkylineTimeDenseProduct, SkylineTimeSkylineProduct, DenseTimeSkylineProduct};\nenum {IsSkyline = SkylineBit};\n\n\n#define EIGEN_SKYLINE_INHERIT_ASSIGNMENT_OPERATOR(Derived, Op) \\\ntemplate<typename OtherDerived> \\\nEIGEN_STRONG_INLINE Derived& operator Op(const Eigen::SkylineMatrixBase<OtherDerived>& other) \\\n{ \\\n  return Base::operator Op(other.derived()); \\\n} \\\nEIGEN_STRONG_INLINE Derived& operator Op(const Derived& other) \\\n{ \\\n  return Base::operator Op(other); \\\n}\n\n#define EIGEN_SKYLINE_INHERIT_SCALAR_ASSIGNMENT_OPERATOR(Derived, Op) \\\ntemplate<typename Other> \\\nEIGEN_STRONG_INLINE Derived& operator Op(const Other& scalar) \\\n{ \\\n  return Base::operator Op(scalar); \\\n}\n\n#define EIGEN_SKYLINE_INHERIT_ASSIGNMENT_OPERATORS(Derived) \\\n  EIGEN_SKYLINE_INHERIT_ASSIGNMENT_OPERATOR(Derived, =) \\\n  EIGEN_SKYLINE_INHERIT_ASSIGNMENT_OPERATOR(Derived, +=) \\\n  EIGEN_SKYLINE_INHERIT_ASSIGNMENT_OPERATOR(Derived, -=) \\\n  EIGEN_SKYLINE_INHERIT_SCALAR_ASSIGNMENT_OPERATOR(Derived, *=) \\\n  EIGEN_SKYLINE_INHERIT_SCALAR_ASSIGNMENT_OPERATOR(Derived, /=)\n\n#define _EIGEN_SKYLINE_GENERIC_PUBLIC_INTERFACE(Derived, BaseClass) \\\n  typedef BaseClass Base; \\\n  typedef typename Eigen::internal::traits<Derived>::Scalar Scalar; \\\n  typedef typename Eigen::NumTraits<Scalar>::Real RealScalar; \\\n  typedef typename Eigen::internal::traits<Derived>::StorageKind StorageKind; \\\n  typedef typename Eigen::internal::index<StorageKind>::type Index; \\\n  enum {  Flags = Eigen::internal::traits<Derived>::Flags, };\n\n#define EIGEN_SKYLINE_GENERIC_PUBLIC_INTERFACE(Derived) \\\n  _EIGEN_SKYLINE_GENERIC_PUBLIC_INTERFACE(Derived, Eigen::SkylineMatrixBase<Derived>)\n\ntemplate<typename Derived> class SkylineMatrixBase;\ntemplate<typename _Scalar, int _Flags = 0> class SkylineMatrix;\ntemplate<typename _Scalar, int _Flags = 0> class DynamicSkylineMatrix;\ntemplate<typename _Scalar, int _Flags = 0> class SkylineVector;\ntemplate<typename _Scalar, int _Flags = 0> class MappedSkylineMatrix;\n\nnamespace internal {\n\ntemplate<typename Lhs, typename Rhs> struct skyline_product_mode;\ntemplate<typename Lhs, typename Rhs, int ProductMode = skyline_product_mode<Lhs,Rhs>::value> struct SkylineProductReturnType;\n\ntemplate<typename T> class eval<T,IsSkyline>\n{\n    typedef typename traits<T>::Scalar _Scalar;\n    enum {\n          _Flags = traits<T>::Flags\n    };\n\n  public:\n    typedef SkylineMatrix<_Scalar, _Flags> type;\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SKYLINEUTIL_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SparseExtra/BlockOfDynamicSparseMatrix.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_BLOCKFORDYNAMICMATRIX_H\n#define EIGEN_SPARSE_BLOCKFORDYNAMICMATRIX_H\n\nnamespace Eigen { \n\n#if 0\n\n// NOTE Have to be reimplemented as a specialization of BlockImpl< DynamicSparseMatrix<_Scalar, _Options, _Index>, ... >\n// See SparseBlock.h for an example\n\n\n/***************************************************************************\n* specialisation for DynamicSparseMatrix\n***************************************************************************/\n\ntemplate<typename _Scalar, int _Options, typename _Index, int Size>\nclass SparseInnerVectorSet<DynamicSparseMatrix<_Scalar, _Options, _Index>, Size>\n  : public SparseMatrixBase<SparseInnerVectorSet<DynamicSparseMatrix<_Scalar, _Options, _Index>, Size> >\n{\n    typedef DynamicSparseMatrix<_Scalar, _Options, _Index> MatrixType;\n  public:\n\n    enum { IsRowMajor = internal::traits<SparseInnerVectorSet>::IsRowMajor };\n\n    EIGEN_SPARSE_PUBLIC_INTERFACE(SparseInnerVectorSet)\n    class InnerIterator: public MatrixType::InnerIterator\n    {\n      public:\n        inline InnerIterator(const SparseInnerVectorSet& xpr, Index outer)\n          : MatrixType::InnerIterator(xpr.m_matrix, xpr.m_outerStart + outer), m_outer(outer)\n        {}\n        inline Index row() const { return IsRowMajor ? m_outer : this->index(); }\n        inline Index col() const { return IsRowMajor ? this->index() : m_outer; }\n      protected:\n        Index m_outer;\n    };\n\n    inline SparseInnerVectorSet(const MatrixType& matrix, Index outerStart, Index outerSize)\n      : m_matrix(matrix), m_outerStart(outerStart), m_outerSize(outerSize)\n    {\n      eigen_assert( (outerStart>=0) && ((outerStart+outerSize)<=matrix.outerSize()) );\n    }\n\n    inline SparseInnerVectorSet(const MatrixType& matrix, Index outer)\n      : m_matrix(matrix), m_outerStart(outer), m_outerSize(Size)\n    {\n      eigen_assert(Size!=Dynamic);\n      eigen_assert( (outer>=0) && (outer<matrix.outerSize()) );\n    }\n\n    template<typename OtherDerived>\n    inline SparseInnerVectorSet& operator=(const SparseMatrixBase<OtherDerived>& other)\n    {\n      if (IsRowMajor != ((OtherDerived::Flags&RowMajorBit)==RowMajorBit))\n      {\n        // need to transpose => perform a block evaluation followed by a big swap\n        DynamicSparseMatrix<Scalar,IsRowMajor?RowMajorBit:0> aux(other);\n        *this = aux.markAsRValue();\n      }\n      else\n      {\n        // evaluate/copy vector per vector\n        for (Index j=0; j<m_outerSize.value(); ++j)\n        {\n          SparseVector<Scalar,IsRowMajor ? RowMajorBit : 0> aux(other.innerVector(j));\n          m_matrix.const_cast_derived()._data()[m_outerStart+j].swap(aux._data());\n        }\n      }\n      return *this;\n    }\n\n    inline SparseInnerVectorSet& operator=(const SparseInnerVectorSet& other)\n    {\n      return operator=<SparseInnerVectorSet>(other);\n    }\n\n    Index nonZeros() const\n    {\n      Index count = 0;\n      for (Index j=0; j<m_outerSize.value(); ++j)\n        count += m_matrix._data()[m_outerStart+j].size();\n      return count;\n    }\n\n    const Scalar& lastCoeff() const\n    {\n      EIGEN_STATIC_ASSERT_VECTOR_ONLY(SparseInnerVectorSet);\n      eigen_assert(m_matrix.data()[m_outerStart].size()>0);\n      return m_matrix.data()[m_outerStart].vale(m_matrix.data()[m_outerStart].size()-1);\n    }\n\n//     template<typename Sparse>\n//     inline SparseInnerVectorSet& operator=(const SparseMatrixBase<OtherDerived>& other)\n//     {\n//       return *this;\n//     }\n\n    EIGEN_STRONG_INLINE Index rows() const { return IsRowMajor ? m_outerSize.value() : m_matrix.rows(); }\n    EIGEN_STRONG_INLINE Index cols() const { return IsRowMajor ? m_matrix.cols() : m_outerSize.value(); }\n\n  protected:\n\n    const typename MatrixType::Nested m_matrix;\n    Index m_outerStart;\n    const internal::variable_if_dynamic<Index, Size> m_outerSize;\n\n};\n\n#endif\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_BLOCKFORDYNAMICMATRIX_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SparseExtra/BlockSparseMatrix.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Desire Nuentsa <desire.nuentsa_wakam@inria.fr>\n// Copyright (C) 2013 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSEBLOCKMATRIX_H\n#define EIGEN_SPARSEBLOCKMATRIX_H\n\nnamespace Eigen { \n/** \\ingroup SparseCore_Module\n  *\n  * \\class BlockSparseMatrix\n  *\n  * \\brief A versatile sparse matrix representation where each element is a block\n  *\n  * This class provides routines to manipulate block sparse matrices stored in a\n  * BSR-like representation. There are two main types :\n  *\n  * 1. All blocks have the same number of rows and columns, called block size\n  * in the following. In this case, if this block size is known at compile time,\n  * it can be given as a template parameter like\n  * \\code\n  * BlockSparseMatrix<Scalar, 3, ColMajor> bmat(b_rows, b_cols);\n  * \\endcode\n  * Here, bmat is a b_rows x b_cols block sparse matrix\n  * where each coefficient is a 3x3 dense matrix.\n  * If the block size is fixed but will be given at runtime,\n  * \\code\n  * BlockSparseMatrix<Scalar, Dynamic, ColMajor> bmat(b_rows, b_cols);\n  * bmat.setBlockSize(block_size);\n  * \\endcode\n  *\n  * 2. The second case is for variable-block sparse matrices.\n  * Here each block has its own dimensions. The only restriction is that all the blocks\n  * in a row (resp. a column) should have the same number of rows (resp. of columns).\n  * It is thus required in this case to describe the layout of the matrix by calling\n  * setBlockLayout(rowBlocks, colBlocks).\n  *\n  * In any of the previous case, the matrix can be filled by calling setFromTriplets().\n  * A regular sparse matrix can be converted to a block sparse matrix and vice versa.\n  * It is obviously required to describe the block layout beforehand by calling either\n  * setBlockSize() for fixed-size blocks or setBlockLayout for variable-size blocks.\n  *\n  * \\tparam _Scalar The Scalar type\n  * \\tparam _BlockAtCompileTime The block layout option. It takes the following values\n  * Dynamic : block size known at runtime\n  * a numeric number : fixed-size block known at compile time\n  */\ntemplate<typename _Scalar, int _BlockAtCompileTime=Dynamic, int _Options=ColMajor, typename _StorageIndex=int> class BlockSparseMatrix;\n\ntemplate<typename BlockSparseMatrixT> class BlockSparseMatrixView;\n\nnamespace internal {\ntemplate<typename _Scalar, int _BlockAtCompileTime, int _Options, typename _Index>\nstruct traits<BlockSparseMatrix<_Scalar,_BlockAtCompileTime,_Options, _Index> >\n{\n  typedef _Scalar Scalar;\n  typedef _Index Index;\n  typedef Sparse StorageKind; // FIXME Where is it used ??\n  typedef MatrixXpr XprKind;\n  enum {\n    RowsAtCompileTime = Dynamic,\n    ColsAtCompileTime = Dynamic,\n    MaxRowsAtCompileTime = Dynamic,\n    MaxColsAtCompileTime = Dynamic,\n    BlockSize = _BlockAtCompileTime,\n    Flags = _Options | NestByRefBit | LvalueBit,\n    CoeffReadCost = NumTraits<Scalar>::ReadCost,\n    SupportedAccessPatterns = InnerRandomAccessPattern\n  };\n};\ntemplate<typename BlockSparseMatrixT>\nstruct traits<BlockSparseMatrixView<BlockSparseMatrixT> >\n{\n  typedef Ref<Matrix<typename BlockSparseMatrixT::Scalar, BlockSparseMatrixT::BlockSize, BlockSparseMatrixT::BlockSize> > Scalar;\n  typedef Ref<Matrix<typename BlockSparseMatrixT::RealScalar, BlockSparseMatrixT::BlockSize, BlockSparseMatrixT::BlockSize> > RealScalar;\n\n};\n\n// Function object to sort a triplet list\ntemplate<typename Iterator, bool IsColMajor>\nstruct TripletComp\n{\n  typedef typename Iterator::value_type Triplet;\n  bool operator()(const Triplet& a, const Triplet& b)\n  { if(IsColMajor)\n      return ((a.col() == b.col() && a.row() < b.row()) || (a.col() < b.col()));\n    else\n      return ((a.row() == b.row() && a.col() < b.col()) || (a.row() < b.row()));\n  }\n};\n} // end namespace internal\n\n\n/* Proxy to view the block sparse matrix as a regular sparse matrix */\ntemplate<typename BlockSparseMatrixT>\nclass BlockSparseMatrixView : public SparseMatrixBase<BlockSparseMatrixT>\n{\n  public:\n    typedef Ref<typename BlockSparseMatrixT::BlockScalar> Scalar;\n    typedef Ref<typename BlockSparseMatrixT::BlockRealScalar> RealScalar;\n    typedef typename BlockSparseMatrixT::Index Index;\n    typedef  BlockSparseMatrixT Nested;\n    enum {\n      Flags = BlockSparseMatrixT::Options,\n      Options = BlockSparseMatrixT::Options,\n      RowsAtCompileTime = BlockSparseMatrixT::RowsAtCompileTime,\n      ColsAtCompileTime = BlockSparseMatrixT::ColsAtCompileTime,\n      MaxColsAtCompileTime = BlockSparseMatrixT::MaxColsAtCompileTime,\n      MaxRowsAtCompileTime = BlockSparseMatrixT::MaxRowsAtCompileTime\n    };\n  public:\n    BlockSparseMatrixView(const BlockSparseMatrixT& spblockmat)\n     : m_spblockmat(spblockmat)\n    {}\n\n    Index outerSize() const\n    {\n      return (Flags&RowMajorBit) == 1 ? this->rows() : this->cols();\n    }\n    Index cols() const\n    {\n      return m_spblockmat.blockCols();\n    }\n    Index rows() const\n    {\n      return m_spblockmat.blockRows();\n    }\n    Scalar coeff(Index row, Index col)\n    {\n      return m_spblockmat.coeff(row, col);\n    }\n    Scalar coeffRef(Index row, Index col)\n    {\n      return m_spblockmat.coeffRef(row, col);\n    }\n    // Wrapper to iterate over all blocks\n    class InnerIterator : public BlockSparseMatrixT::BlockInnerIterator\n    {\n      public:\n      InnerIterator(const BlockSparseMatrixView& mat, Index outer)\n          : BlockSparseMatrixT::BlockInnerIterator(mat.m_spblockmat, outer)\n      {}\n\n    };\n\n  protected:\n    const BlockSparseMatrixT& m_spblockmat;\n};\n\n// Proxy to view a regular vector as a block vector\ntemplate<typename BlockSparseMatrixT, typename VectorType>\nclass BlockVectorView\n{\n  public:\n    enum {\n      BlockSize = BlockSparseMatrixT::BlockSize,\n      ColsAtCompileTime = VectorType::ColsAtCompileTime,\n      RowsAtCompileTime = VectorType::RowsAtCompileTime,\n      Flags = VectorType::Flags\n    };\n    typedef Ref<const Matrix<typename BlockSparseMatrixT::Scalar, (RowsAtCompileTime==1)? 1 : BlockSize, (ColsAtCompileTime==1)? 1 : BlockSize> >Scalar;\n    typedef typename BlockSparseMatrixT::Index Index;\n  public:\n    BlockVectorView(const BlockSparseMatrixT& spblockmat, const VectorType& vec)\n    : m_spblockmat(spblockmat),m_vec(vec)\n    { }\n    inline Index cols() const\n    {\n      return m_vec.cols();\n    }\n    inline Index size() const\n    {\n      return m_spblockmat.blockRows();\n    }\n    inline Scalar coeff(Index bi) const\n    {\n      Index startRow = m_spblockmat.blockRowsIndex(bi);\n      Index rowSize = m_spblockmat.blockRowsIndex(bi+1) - startRow;\n      return m_vec.middleRows(startRow, rowSize);\n    }\n    inline Scalar coeff(Index bi, Index j) const\n    {\n      Index startRow = m_spblockmat.blockRowsIndex(bi);\n      Index rowSize = m_spblockmat.blockRowsIndex(bi+1) - startRow;\n      return m_vec.block(startRow, j, rowSize, 1);\n    }\n  protected:\n    const BlockSparseMatrixT& m_spblockmat;\n    const VectorType& m_vec;\n};\n\ntemplate<typename VectorType, typename Index> class BlockVectorReturn;\n\n\n// Proxy to view a regular vector as a block vector\ntemplate<typename BlockSparseMatrixT, typename VectorType>\nclass BlockVectorReturn\n{\n  public:\n    enum {\n      ColsAtCompileTime = VectorType::ColsAtCompileTime,\n      RowsAtCompileTime = VectorType::RowsAtCompileTime,\n      Flags = VectorType::Flags\n    };\n    typedef Ref<Matrix<typename VectorType::Scalar, RowsAtCompileTime, ColsAtCompileTime> > Scalar;\n    typedef typename BlockSparseMatrixT::Index Index;\n  public:\n    BlockVectorReturn(const BlockSparseMatrixT& spblockmat, VectorType& vec)\n    : m_spblockmat(spblockmat),m_vec(vec)\n    { }\n    inline Index size() const\n    {\n      return m_spblockmat.blockRows();\n    }\n    inline Scalar coeffRef(Index bi)\n    {\n      Index startRow = m_spblockmat.blockRowsIndex(bi);\n      Index rowSize = m_spblockmat.blockRowsIndex(bi+1) - startRow;\n      return m_vec.middleRows(startRow, rowSize);\n    }\n    inline Scalar coeffRef(Index bi, Index j)\n    {\n      Index startRow = m_spblockmat.blockRowsIndex(bi);\n      Index rowSize = m_spblockmat.blockRowsIndex(bi+1) - startRow;\n      return m_vec.block(startRow, j, rowSize, 1);\n    }\n\n  protected:\n    const BlockSparseMatrixT& m_spblockmat;\n    VectorType& m_vec;\n};\n\n// Block version of the sparse dense product\ntemplate<typename Lhs, typename Rhs>\nclass BlockSparseTimeDenseProduct;\n\nnamespace internal {\n\ntemplate<typename BlockSparseMatrixT, typename VecType>\nstruct traits<BlockSparseTimeDenseProduct<BlockSparseMatrixT, VecType> >\n{\n  typedef Dense StorageKind;\n  typedef MatrixXpr XprKind;\n  typedef typename BlockSparseMatrixT::Scalar Scalar;\n  typedef typename BlockSparseMatrixT::Index Index;\n  enum {\n    RowsAtCompileTime = Dynamic,\n    ColsAtCompileTime = Dynamic,\n    MaxRowsAtCompileTime = Dynamic,\n    MaxColsAtCompileTime = Dynamic,\n    Flags = 0,\n    CoeffReadCost = internal::traits<BlockSparseMatrixT>::CoeffReadCost\n  };\n};\n} // end namespace internal\n\ntemplate<typename Lhs, typename Rhs>\nclass BlockSparseTimeDenseProduct\n  : public ProductBase<BlockSparseTimeDenseProduct<Lhs,Rhs>, Lhs, Rhs>\n{\n  public:\n    EIGEN_PRODUCT_PUBLIC_INTERFACE(BlockSparseTimeDenseProduct)\n\n    BlockSparseTimeDenseProduct(const Lhs& lhs, const Rhs& rhs) : Base(lhs,rhs)\n    {}\n\n    template<typename Dest> void scaleAndAddTo(Dest& dest, const typename Rhs::Scalar& alpha) const\n    {\n      BlockVectorReturn<Lhs,Dest> tmpDest(m_lhs, dest);\n      internal::sparse_time_dense_product( BlockSparseMatrixView<Lhs>(m_lhs),  BlockVectorView<Lhs, Rhs>(m_lhs, m_rhs), tmpDest, alpha);\n    }\n\n  private:\n    BlockSparseTimeDenseProduct& operator=(const BlockSparseTimeDenseProduct&);\n};\n\ntemplate<typename _Scalar, int _BlockAtCompileTime, int _Options, typename _StorageIndex>\nclass BlockSparseMatrix : public SparseMatrixBase<BlockSparseMatrix<_Scalar,_BlockAtCompileTime, _Options,_StorageIndex> >\n{\n  public:\n    typedef _Scalar Scalar;\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n    typedef _StorageIndex StorageIndex;\n    typedef typename internal::ref_selector<BlockSparseMatrix<_Scalar, _BlockAtCompileTime, _Options, _StorageIndex> >::type Nested;\n\n    enum {\n      Options = _Options,\n      Flags = Options,\n      BlockSize=_BlockAtCompileTime,\n      RowsAtCompileTime = Dynamic,\n      ColsAtCompileTime = Dynamic,\n      MaxRowsAtCompileTime = Dynamic,\n      MaxColsAtCompileTime = Dynamic,\n      IsVectorAtCompileTime = 0,\n      IsColMajor = Flags&RowMajorBit ? 0 : 1\n    };\n    typedef Matrix<Scalar, _BlockAtCompileTime, _BlockAtCompileTime,IsColMajor ? ColMajor : RowMajor> BlockScalar;\n    typedef Matrix<RealScalar, _BlockAtCompileTime, _BlockAtCompileTime,IsColMajor ? ColMajor : RowMajor> BlockRealScalar;\n    typedef typename internal::conditional<_BlockAtCompileTime==Dynamic, Scalar, BlockScalar>::type BlockScalarReturnType;\n    typedef BlockSparseMatrix<Scalar, BlockSize, IsColMajor ? ColMajor : RowMajor, StorageIndex> PlainObject;\n  public:\n    // Default constructor\n    BlockSparseMatrix()\n    : m_innerBSize(0),m_outerBSize(0),m_innerOffset(0),m_outerOffset(0),\n      m_nonzerosblocks(0),m_values(0),m_blockPtr(0),m_indices(0),\n      m_outerIndex(0),m_blockSize(BlockSize)\n    { }\n\n\n    /**\n     * \\brief Construct and resize\n     *\n     */\n    BlockSparseMatrix(Index brow, Index bcol)\n      : m_innerBSize(IsColMajor ? brow : bcol),\n        m_outerBSize(IsColMajor ? bcol : brow),\n        m_innerOffset(0),m_outerOffset(0),m_nonzerosblocks(0),\n        m_values(0),m_blockPtr(0),m_indices(0),\n        m_outerIndex(0),m_blockSize(BlockSize)\n    { }\n\n    /**\n     * \\brief Copy-constructor\n     */\n    BlockSparseMatrix(const BlockSparseMatrix& other)\n      : m_innerBSize(other.m_innerBSize),m_outerBSize(other.m_outerBSize),\n        m_nonzerosblocks(other.m_nonzerosblocks),m_nonzeros(other.m_nonzeros),\n        m_blockPtr(0),m_blockSize(other.m_blockSize)\n    {\n      // should we allow copying between variable-size blocks and fixed-size blocks ??\n      eigen_assert(m_blockSize == BlockSize && \" CAN NOT COPY BETWEEN FIXED-SIZE AND VARIABLE-SIZE BLOCKS\");\n\n      std::copy(other.m_innerOffset, other.m_innerOffset+m_innerBSize+1, m_innerOffset);\n      std::copy(other.m_outerOffset, other.m_outerOffset+m_outerBSize+1, m_outerOffset);\n      std::copy(other.m_values, other.m_values+m_nonzeros, m_values);\n\n      if(m_blockSize != Dynamic)\n        std::copy(other.m_blockPtr, other.m_blockPtr+m_nonzerosblocks, m_blockPtr);\n\n      std::copy(other.m_indices, other.m_indices+m_nonzerosblocks, m_indices);\n      std::copy(other.m_outerIndex, other.m_outerIndex+m_outerBSize, m_outerIndex);\n    }\n\n    friend void swap(BlockSparseMatrix& first, BlockSparseMatrix& second)\n    {\n      std::swap(first.m_innerBSize, second.m_innerBSize);\n      std::swap(first.m_outerBSize, second.m_outerBSize);\n      std::swap(first.m_innerOffset, second.m_innerOffset);\n      std::swap(first.m_outerOffset, second.m_outerOffset);\n      std::swap(first.m_nonzerosblocks, second.m_nonzerosblocks);\n      std::swap(first.m_nonzeros, second.m_nonzeros);\n      std::swap(first.m_values, second.m_values);\n      std::swap(first.m_blockPtr, second.m_blockPtr);\n      std::swap(first.m_indices, second.m_indices);\n      std::swap(first.m_outerIndex, second.m_outerIndex);\n      std::swap(first.m_BlockSize, second.m_blockSize);\n    }\n\n    BlockSparseMatrix& operator=(BlockSparseMatrix other)\n    {\n      //Copy-and-swap paradigm ... avoid leaked data if thrown\n      swap(*this, other);\n      return *this;\n    }\n\n    // Destructor\n    ~BlockSparseMatrix()\n    {\n      delete[] m_outerIndex;\n      delete[] m_innerOffset;\n      delete[] m_outerOffset;\n      delete[] m_indices;\n      delete[] m_blockPtr;\n      delete[] m_values;\n    }\n\n\n    /**\n      * \\brief Constructor from a sparse matrix\n      *\n      */\n    template<typename MatrixType>\n    inline BlockSparseMatrix(const MatrixType& spmat) : m_blockSize(BlockSize)\n    {\n      EIGEN_STATIC_ASSERT((m_blockSize != Dynamic), THIS_METHOD_IS_ONLY_FOR_FIXED_SIZE);\n\n      *this = spmat;\n    }\n\n    /**\n      * \\brief Assignment from a sparse matrix with the same storage order\n      *\n      * Convert from a sparse matrix to block sparse matrix.\n      * \\warning Before calling this function, tt is necessary to call\n      * either setBlockLayout() (matrices with variable-size blocks)\n      * or setBlockSize() (for fixed-size blocks).\n      */\n    template<typename MatrixType>\n    inline BlockSparseMatrix& operator=(const MatrixType& spmat)\n    {\n      eigen_assert((m_innerBSize != 0 && m_outerBSize != 0)\n                   && \"Trying to assign to a zero-size matrix, call resize() first\");\n      eigen_assert(((MatrixType::Options&RowMajorBit) != IsColMajor) && \"Wrong storage order\");\n      typedef SparseMatrix<bool,MatrixType::Options,typename MatrixType::Index> MatrixPatternType;\n      MatrixPatternType  blockPattern(blockRows(), blockCols());\n      m_nonzeros = 0;\n\n      // First, compute the number of nonzero blocks and their locations\n      for(StorageIndex bj = 0; bj < m_outerBSize; ++bj)\n      {\n        // Browse each outer block and compute the structure\n        std::vector<bool> nzblocksFlag(m_innerBSize,false);  // Record the existing blocks\n        blockPattern.startVec(bj);\n        for(StorageIndex j = blockOuterIndex(bj); j < blockOuterIndex(bj+1); ++j)\n        {\n          typename MatrixType::InnerIterator it_spmat(spmat, j);\n          for(; it_spmat; ++it_spmat)\n          {\n            StorageIndex bi = innerToBlock(it_spmat.index()); // Index of the current nonzero block\n            if(!nzblocksFlag[bi])\n            {\n              // Save the index of this nonzero block\n              nzblocksFlag[bi] = true;\n              blockPattern.insertBackByOuterInnerUnordered(bj, bi) = true;\n              // Compute the total number of nonzeros (including explicit zeros in blocks)\n              m_nonzeros += blockOuterSize(bj) * blockInnerSize(bi);\n            }\n          }\n        } // end current outer block\n      }\n      blockPattern.finalize();\n\n      // Allocate the internal arrays\n      setBlockStructure(blockPattern);\n\n      for(StorageIndex nz = 0; nz < m_nonzeros; ++nz) m_values[nz] = Scalar(0);\n      for(StorageIndex bj = 0; bj < m_outerBSize; ++bj)\n      {\n        // Now copy the values\n        for(StorageIndex j = blockOuterIndex(bj); j < blockOuterIndex(bj+1); ++j)\n        {\n          // Browse the outer block column by column (for column-major matrices)\n          typename MatrixType::InnerIterator it_spmat(spmat, j);\n          for(; it_spmat; ++it_spmat)\n          {\n            StorageIndex idx = 0; // Position of this block in the column block\n            StorageIndex bi = innerToBlock(it_spmat.index()); // Index of the current nonzero block\n            // Go to the inner block where this element belongs to\n            while(bi > m_indices[m_outerIndex[bj]+idx]) ++idx; // Not expensive for ordered blocks\n            StorageIndex idxVal;// Get the right position in the array of values for this element\n            if(m_blockSize == Dynamic)\n            {\n              // Offset from all blocks before ...\n              idxVal =  m_blockPtr[m_outerIndex[bj]+idx];\n              // ... and offset inside the block\n              idxVal += (j - blockOuterIndex(bj)) * blockOuterSize(bj) + it_spmat.index() - m_innerOffset[bi];\n            }\n            else\n            {\n              // All blocks before\n              idxVal = (m_outerIndex[bj] + idx) * m_blockSize * m_blockSize;\n              // inside the block\n              idxVal += (j - blockOuterIndex(bj)) * m_blockSize + (it_spmat.index()%m_blockSize);\n            }\n            // Insert the value\n            m_values[idxVal] = it_spmat.value();\n          } // end of this column\n        } // end of this block\n      } // end of this outer block\n\n      return *this;\n    }\n\n    /**\n      * \\brief Set the nonzero block pattern of the matrix\n      *\n      * Given a sparse matrix describing the nonzero block pattern,\n      * this function prepares the internal pointers for values.\n      * After calling this function, any *nonzero* block (bi, bj) can be set\n      * with a simple call to coeffRef(bi,bj).\n      *\n      *\n      * \\warning Before calling this function, tt is necessary to call\n      * either setBlockLayout() (matrices with variable-size blocks)\n      * or setBlockSize() (for fixed-size blocks).\n      *\n      * \\param blockPattern Sparse matrix of boolean elements describing the block structure\n      *\n      * \\sa setBlockLayout() \\sa setBlockSize()\n      */\n    template<typename MatrixType>\n    void setBlockStructure(const MatrixType& blockPattern)\n    {\n      resize(blockPattern.rows(), blockPattern.cols());\n      reserve(blockPattern.nonZeros());\n\n      // Browse the block pattern and set up the various pointers\n      m_outerIndex[0] = 0;\n      if(m_blockSize == Dynamic) m_blockPtr[0] = 0;\n      for(StorageIndex nz = 0; nz < m_nonzeros; ++nz) m_values[nz] = Scalar(0);\n      for(StorageIndex bj = 0; bj < m_outerBSize; ++bj)\n      {\n        //Browse each outer block\n\n        //First, copy and save the indices of nonzero blocks\n        //FIXME : find a way to avoid this ...\n        std::vector<int> nzBlockIdx;\n        typename MatrixType::InnerIterator it(blockPattern, bj);\n        for(; it; ++it)\n        {\n          nzBlockIdx.push_back(it.index());\n        }\n        std::sort(nzBlockIdx.begin(), nzBlockIdx.end());\n\n        // Now, fill block indices and (eventually) pointers to blocks\n        for(StorageIndex idx = 0; idx < nzBlockIdx.size(); ++idx)\n        {\n          StorageIndex offset = m_outerIndex[bj]+idx; // offset in m_indices\n          m_indices[offset] = nzBlockIdx[idx];\n          if(m_blockSize == Dynamic)\n            m_blockPtr[offset] = m_blockPtr[offset-1] + blockInnerSize(nzBlockIdx[idx]) * blockOuterSize(bj);\n          // There is no blockPtr for fixed-size blocks... not needed !???\n        }\n        // Save the pointer to the next outer block\n        m_outerIndex[bj+1] = m_outerIndex[bj] + nzBlockIdx.size();\n      }\n    }\n\n    /**\n      * \\brief Set the number of rows and columns blocks\n      */\n    inline void resize(Index brow, Index bcol)\n    {\n      m_innerBSize = IsColMajor ? brow : bcol;\n      m_outerBSize = IsColMajor ? bcol : brow;\n    }\n\n    /**\n      * \\brief set the block size at runtime for fixed-size block layout\n      *\n      * Call this only for fixed-size blocks\n      */\n    inline void setBlockSize(Index blockSize)\n    {\n      m_blockSize = blockSize;\n    }\n\n    /**\n      * \\brief Set the row and column block layouts,\n      *\n      * This function set the size of each row and column block.\n      * So this function should be used only for blocks with variable size.\n      * \\param rowBlocks : Number of rows per row block\n      * \\param colBlocks : Number of columns per column block\n      * \\sa resize(), setBlockSize()\n      */\n    inline void setBlockLayout(const VectorXi& rowBlocks, const VectorXi& colBlocks)\n    {\n      const VectorXi& innerBlocks = IsColMajor ? rowBlocks : colBlocks;\n      const VectorXi& outerBlocks = IsColMajor ? colBlocks : rowBlocks;\n      eigen_assert(m_innerBSize == innerBlocks.size() && \"CHECK THE NUMBER OF ROW OR COLUMN BLOCKS\");\n      eigen_assert(m_outerBSize == outerBlocks.size() && \"CHECK THE NUMBER OF ROW OR COLUMN BLOCKS\");\n      m_outerBSize = outerBlocks.size();\n      //  starting index of blocks... cumulative sums\n      m_innerOffset = new StorageIndex[m_innerBSize+1];\n      m_outerOffset = new StorageIndex[m_outerBSize+1];\n      m_innerOffset[0] = 0;\n      m_outerOffset[0] = 0;\n      std::partial_sum(&innerBlocks[0], &innerBlocks[m_innerBSize-1]+1, &m_innerOffset[1]);\n      std::partial_sum(&outerBlocks[0], &outerBlocks[m_outerBSize-1]+1, &m_outerOffset[1]);\n\n      // Compute the total number of nonzeros\n      m_nonzeros = 0;\n      for(StorageIndex bj = 0; bj < m_outerBSize; ++bj)\n        for(StorageIndex bi = 0; bi < m_innerBSize; ++bi)\n          m_nonzeros += outerBlocks[bj] * innerBlocks[bi];\n\n    }\n\n    /**\n      * \\brief Allocate the internal array of pointers to blocks and their inner indices\n      *\n      * \\note For fixed-size blocks, call setBlockSize() to set the block.\n      * And For variable-size blocks, call setBlockLayout() before using this function\n      *\n      * \\param nonzerosblocks Number of nonzero blocks. The total number of nonzeros is\n      * is computed in setBlockLayout() for variable-size blocks\n      * \\sa setBlockSize()\n      */\n    inline void reserve(const Index nonzerosblocks)\n    {\n      eigen_assert((m_innerBSize != 0 && m_outerBSize != 0) &&\n          \"TRYING TO RESERVE ZERO-SIZE MATRICES, CALL resize() first\");\n\n      //FIXME Should free if already allocated\n      m_outerIndex = new StorageIndex[m_outerBSize+1];\n\n      m_nonzerosblocks = nonzerosblocks;\n      if(m_blockSize != Dynamic)\n      {\n        m_nonzeros = nonzerosblocks * (m_blockSize * m_blockSize);\n        m_blockPtr = 0;\n      }\n      else\n      {\n        // m_nonzeros  is already computed in setBlockLayout()\n        m_blockPtr = new StorageIndex[m_nonzerosblocks+1];\n      }\n      m_indices = new StorageIndex[m_nonzerosblocks+1];\n      m_values = new Scalar[m_nonzeros];\n    }\n\n\n    /**\n      * \\brief Fill values in a matrix  from a triplet list.\n      *\n      * Each triplet item has a block stored in an Eigen dense matrix.\n      * The InputIterator class should provide the functions row(), col() and value()\n      *\n      * \\note For fixed-size blocks, call setBlockSize() before this function.\n      *\n      * FIXME Do not accept duplicates\n      */\n    template<typename InputIterator>\n    void setFromTriplets(const InputIterator& begin, const InputIterator& end)\n    {\n      eigen_assert((m_innerBSize!=0 && m_outerBSize !=0) && \"ZERO BLOCKS, PLEASE CALL resize() before\");\n\n      /* First, sort the triplet list\n        * FIXME This can be unnecessarily expensive since only the inner indices have to be sorted\n        * The best approach is like in SparseMatrix::setFromTriplets()\n        */\n      internal::TripletComp<InputIterator, IsColMajor> tripletcomp;\n      std::sort(begin, end, tripletcomp);\n\n      /* Count the number of rows and column blocks,\n       * and the number of nonzero blocks per outer dimension\n       */\n      VectorXi rowBlocks(m_innerBSize); // Size of each block row\n      VectorXi colBlocks(m_outerBSize); // Size of each block column\n      rowBlocks.setZero(); colBlocks.setZero();\n      VectorXi nzblock_outer(m_outerBSize); // Number of nz blocks per outer vector\n      VectorXi nz_outer(m_outerBSize); // Number of nz per outer vector...for variable-size blocks\n      nzblock_outer.setZero();\n      nz_outer.setZero();\n      for(InputIterator it(begin); it !=end; ++it)\n      {\n        eigen_assert(it->row() >= 0 && it->row() < this->blockRows() && it->col() >= 0 && it->col() < this->blockCols());\n        eigen_assert((it->value().rows() == it->value().cols() && (it->value().rows() == m_blockSize))\n                     || (m_blockSize == Dynamic));\n\n        if(m_blockSize == Dynamic)\n        {\n          eigen_assert((rowBlocks[it->row()] == 0 || rowBlocks[it->row()] == it->value().rows()) &&\n              \"NON CORRESPONDING SIZES FOR ROW BLOCKS\");\n          eigen_assert((colBlocks[it->col()] == 0 || colBlocks[it->col()] == it->value().cols()) &&\n              \"NON CORRESPONDING SIZES FOR COLUMN BLOCKS\");\n          rowBlocks[it->row()] =it->value().rows();\n          colBlocks[it->col()] = it->value().cols();\n        }\n        nz_outer(IsColMajor ? it->col() : it->row()) += it->value().rows() * it->value().cols();\n        nzblock_outer(IsColMajor ? it->col() : it->row())++;\n      }\n      // Allocate member arrays\n      if(m_blockSize == Dynamic) setBlockLayout(rowBlocks, colBlocks);\n      StorageIndex nzblocks = nzblock_outer.sum();\n      reserve(nzblocks);\n\n       // Temporary markers\n      VectorXi block_id(m_outerBSize); // To be used as a block marker during insertion\n\n      // Setup outer index pointers and markers\n      m_outerIndex[0] = 0;\n      if (m_blockSize == Dynamic)  m_blockPtr[0] =  0;\n      for(StorageIndex bj = 0; bj < m_outerBSize; ++bj)\n      {\n        m_outerIndex[bj+1] = m_outerIndex[bj] + nzblock_outer(bj);\n        block_id(bj) = m_outerIndex[bj];\n        if(m_blockSize==Dynamic)\n        {\n          m_blockPtr[m_outerIndex[bj+1]] = m_blockPtr[m_outerIndex[bj]] + nz_outer(bj);\n        }\n      }\n\n      // Fill the matrix\n      for(InputIterator it(begin); it!=end; ++it)\n      {\n        StorageIndex outer = IsColMajor ? it->col() : it->row();\n        StorageIndex inner = IsColMajor ? it->row() : it->col();\n        m_indices[block_id(outer)] = inner;\n        StorageIndex block_size = it->value().rows()*it->value().cols();\n        StorageIndex nz_marker = blockPtr(block_id[outer]);\n        memcpy(&(m_values[nz_marker]), it->value().data(), block_size * sizeof(Scalar));\n        if(m_blockSize == Dynamic)\n        {\n          m_blockPtr[block_id(outer)+1] = m_blockPtr[block_id(outer)] + block_size;\n        }\n        block_id(outer)++;\n      }\n\n      // An alternative when the outer indices are sorted...no need to use an array of markers\n//      for(Index bcol = 0; bcol < m_outerBSize; ++bcol)\n//      {\n//      Index id = 0, id_nz = 0, id_nzblock = 0;\n//      for(InputIterator it(begin); it!=end; ++it)\n//      {\n//        while (id<bcol) // one pass should do the job unless there are empty columns\n//        {\n//          id++;\n//          m_outerIndex[id+1]=m_outerIndex[id];\n//        }\n//        m_outerIndex[id+1] += 1;\n//        m_indices[id_nzblock]=brow;\n//        Index block_size = it->value().rows()*it->value().cols();\n//        m_blockPtr[id_nzblock+1] = m_blockPtr[id_nzblock] + block_size;\n//        id_nzblock++;\n//        memcpy(&(m_values[id_nz]),it->value().data(), block_size*sizeof(Scalar));\n//        id_nz += block_size;\n//      }\n//      while(id < m_outerBSize-1) // Empty columns at the end\n//      {\n//        id++;\n//        m_outerIndex[id+1]=m_outerIndex[id];\n//      }\n//      }\n    }\n\n\n    /**\n      * \\returns the number of rows\n      */\n    inline Index rows() const\n    {\n//      return blockRows();\n      return (IsColMajor ? innerSize() : outerSize());\n    }\n\n    /**\n      * \\returns the number of cols\n      */\n    inline Index cols() const\n    {\n//      return blockCols();\n      return (IsColMajor ? outerSize() : innerSize());\n    }\n\n    inline Index innerSize() const\n    {\n      if(m_blockSize == Dynamic) return m_innerOffset[m_innerBSize];\n      else return  (m_innerBSize * m_blockSize) ;\n    }\n\n    inline Index outerSize() const\n    {\n      if(m_blockSize == Dynamic) return m_outerOffset[m_outerBSize];\n      else return  (m_outerBSize * m_blockSize) ;\n    }\n    /** \\returns the number of rows grouped by blocks */\n    inline Index blockRows() const\n    {\n      return (IsColMajor ? m_innerBSize : m_outerBSize);\n    }\n    /** \\returns the number of columns grouped by blocks */\n    inline Index blockCols() const\n    {\n      return (IsColMajor ? m_outerBSize : m_innerBSize);\n    }\n\n    inline Index outerBlocks() const { return m_outerBSize; }\n    inline Index innerBlocks() const { return m_innerBSize; }\n\n    /** \\returns the block index where outer belongs to */\n    inline Index outerToBlock(Index outer) const\n    {\n      eigen_assert(outer < outerSize() && \"OUTER INDEX OUT OF BOUNDS\");\n\n      if(m_blockSize != Dynamic)\n        return (outer / m_blockSize); // Integer division\n\n      StorageIndex b_outer = 0;\n      while(m_outerOffset[b_outer] <= outer) ++b_outer;\n      return b_outer - 1;\n    }\n    /** \\returns  the block index where inner belongs to */\n    inline Index innerToBlock(Index inner) const\n    {\n      eigen_assert(inner < innerSize() && \"OUTER INDEX OUT OF BOUNDS\");\n\n      if(m_blockSize != Dynamic)\n        return (inner / m_blockSize); // Integer division\n\n      StorageIndex b_inner = 0;\n      while(m_innerOffset[b_inner] <= inner) ++b_inner;\n      return b_inner - 1;\n    }\n\n    /**\n      *\\returns a reference to the (i,j) block as an Eigen Dense Matrix\n      */\n    Ref<BlockScalar> coeffRef(Index brow, Index bcol)\n    {\n      eigen_assert(brow < blockRows() && \"BLOCK ROW INDEX OUT OF BOUNDS\");\n      eigen_assert(bcol < blockCols() && \"BLOCK nzblocksFlagCOLUMN OUT OF BOUNDS\");\n\n      StorageIndex rsize = IsColMajor ? blockInnerSize(brow): blockOuterSize(bcol);\n      StorageIndex csize = IsColMajor ? blockOuterSize(bcol) : blockInnerSize(brow);\n      StorageIndex inner = IsColMajor ? brow : bcol;\n      StorageIndex outer = IsColMajor ? bcol : brow;\n      StorageIndex offset = m_outerIndex[outer];\n      while(offset < m_outerIndex[outer+1] && m_indices[offset] != inner)\n        offset++;\n      if(m_indices[offset] == inner)\n      {\n        return Map<BlockScalar>(&(m_values[blockPtr(offset)]), rsize, csize);\n      }\n      else\n      {\n        //FIXME the block does not exist, Insert it !!!!!!!!!\n        eigen_assert(\"DYNAMIC INSERTION IS NOT YET SUPPORTED\");\n      }\n    }\n\n    /**\n      * \\returns the value of the (i,j) block as an Eigen Dense Matrix\n      */\n    Map<const BlockScalar> coeff(Index brow, Index bcol) const\n    {\n      eigen_assert(brow < blockRows() && \"BLOCK ROW INDEX OUT OF BOUNDS\");\n      eigen_assert(bcol < blockCols() && \"BLOCK COLUMN OUT OF BOUNDS\");\n\n      StorageIndex rsize = IsColMajor ? blockInnerSize(brow): blockOuterSize(bcol);\n      StorageIndex csize = IsColMajor ? blockOuterSize(bcol) : blockInnerSize(brow);\n      StorageIndex inner = IsColMajor ? brow : bcol;\n      StorageIndex outer = IsColMajor ? bcol : brow;\n      StorageIndex offset = m_outerIndex[outer];\n      while(offset < m_outerIndex[outer+1] && m_indices[offset] != inner) offset++;\n      if(m_indices[offset] == inner)\n      {\n        return Map<const BlockScalar> (&(m_values[blockPtr(offset)]), rsize, csize);\n      }\n      else\n//        return BlockScalar::Zero(rsize, csize);\n        eigen_assert(\"NOT YET SUPPORTED\");\n    }\n\n    // Block Matrix times vector product\n    template<typename VecType>\n    BlockSparseTimeDenseProduct<BlockSparseMatrix, VecType> operator*(const VecType& lhs) const\n    {\n      return BlockSparseTimeDenseProduct<BlockSparseMatrix, VecType>(*this, lhs);\n    }\n\n    /** \\returns the number of nonzero blocks */\n    inline Index nonZerosBlocks() const { return m_nonzerosblocks; }\n    /** \\returns the total number of nonzero elements, including eventual explicit zeros in blocks */\n    inline Index nonZeros() const { return m_nonzeros; }\n\n    inline BlockScalarReturnType *valuePtr() {return static_cast<BlockScalarReturnType *>(m_values);}\n//    inline Scalar *valuePtr(){ return m_values; }\n    inline StorageIndex *innerIndexPtr() {return m_indices; }\n    inline const StorageIndex *innerIndexPtr() const {return m_indices; }\n    inline StorageIndex *outerIndexPtr() {return m_outerIndex; }\n    inline const StorageIndex* outerIndexPtr() const {return m_outerIndex; }\n\n    /** \\brief for compatibility purposes with the SparseMatrix class */\n    inline bool isCompressed() const {return true;}\n    /**\n      * \\returns the starting index of the bi row block\n      */\n    inline Index blockRowsIndex(Index bi) const\n    {\n      return IsColMajor ? blockInnerIndex(bi) : blockOuterIndex(bi);\n    }\n\n    /**\n      * \\returns the starting index of the bj col block\n      */\n    inline Index blockColsIndex(Index bj) const\n    {\n      return IsColMajor ? blockOuterIndex(bj) : blockInnerIndex(bj);\n    }\n\n    inline Index blockOuterIndex(Index bj) const\n    {\n      return (m_blockSize == Dynamic) ? m_outerOffset[bj] : (bj * m_blockSize);\n    }\n    inline Index blockInnerIndex(Index bi) const\n    {\n      return (m_blockSize == Dynamic) ? m_innerOffset[bi] : (bi * m_blockSize);\n    }\n\n    // Not needed ???\n    inline Index blockInnerSize(Index bi) const\n    {\n      return (m_blockSize == Dynamic) ? (m_innerOffset[bi+1] - m_innerOffset[bi]) : m_blockSize;\n    }\n    inline Index blockOuterSize(Index bj) const\n    {\n      return (m_blockSize == Dynamic) ? (m_outerOffset[bj+1]- m_outerOffset[bj]) : m_blockSize;\n    }\n\n    /**\n      * \\brief Browse the matrix by outer index\n      */\n    class InnerIterator; // Browse column by column\n\n    /**\n      * \\brief Browse the matrix by block outer index\n      */\n    class BlockInnerIterator; // Browse block by block\n\n    friend std::ostream & operator << (std::ostream & s, const BlockSparseMatrix& m)\n    {\n      for (StorageIndex j = 0; j < m.outerBlocks(); ++j)\n      {\n        BlockInnerIterator itb(m, j);\n        for(; itb; ++itb)\n        {\n          s << \"(\"<<itb.row() << \", \" << itb.col() << \")\\n\";\n          s << itb.value() <<\"\\n\";\n        }\n      }\n      s << std::endl;\n      return s;\n    }\n\n    /**\n      * \\returns the starting position of the block \\p id in the array of values\n      */\n    Index blockPtr(Index id) const\n    {\n      if(m_blockSize == Dynamic) return m_blockPtr[id];\n      else return id * m_blockSize * m_blockSize;\n      //return blockDynIdx(id, typename internal::conditional<(BlockSize==Dynamic), internal::true_type, internal::false_type>::type());\n    }\n\n\n  protected:\n//    inline Index blockDynIdx(Index id, internal::true_type) const\n//    {\n//      return m_blockPtr[id];\n//    }\n//    inline Index blockDynIdx(Index id, internal::false_type) const\n//    {\n//      return id * BlockSize * BlockSize;\n//    }\n\n    // To be implemented\n    // Insert a block at a particular location... need to make a room for that\n    Map<BlockScalar> insert(Index brow, Index bcol);\n\n    Index m_innerBSize; // Number of block rows\n    Index m_outerBSize; // Number of block columns\n    StorageIndex *m_innerOffset; // Starting index of each inner block (size m_innerBSize+1)\n    StorageIndex *m_outerOffset; // Starting index of each outer block (size m_outerBSize+1)\n    Index m_nonzerosblocks; // Total nonzeros blocks (lower than  m_innerBSize x m_outerBSize)\n    Index m_nonzeros; // Total nonzeros elements\n    Scalar *m_values; //Values stored block column after block column (size m_nonzeros)\n    StorageIndex *m_blockPtr; // Pointer to the beginning of each block in m_values, size m_nonzeroblocks ... null for fixed-size blocks\n    StorageIndex *m_indices; //Inner block indices, size m_nonzerosblocks ... OK\n    StorageIndex *m_outerIndex; // Starting pointer of each block column in m_indices (size m_outerBSize)... OK\n    Index m_blockSize; // Size of a block for fixed-size blocks, otherwise -1\n};\n\ntemplate<typename _Scalar, int _BlockAtCompileTime, int _Options, typename _StorageIndex>\nclass BlockSparseMatrix<_Scalar, _BlockAtCompileTime, _Options, _StorageIndex>::BlockInnerIterator\n{\n  public:\n\n    enum{\n      Flags = _Options\n    };\n\n    BlockInnerIterator(const BlockSparseMatrix& mat, const Index outer)\n    : m_mat(mat),m_outer(outer),\n      m_id(mat.m_outerIndex[outer]),\n      m_end(mat.m_outerIndex[outer+1])\n    {\n    }\n\n    inline BlockInnerIterator& operator++() {m_id++; return *this; }\n\n    inline const Map<const BlockScalar> value() const\n    {\n      return Map<const BlockScalar>(&(m_mat.m_values[m_mat.blockPtr(m_id)]),\n          rows(),cols());\n    }\n    inline Map<BlockScalar> valueRef()\n    {\n      return Map<BlockScalar>(&(m_mat.m_values[m_mat.blockPtr(m_id)]),\n          rows(),cols());\n    }\n    // Block inner index\n    inline Index index() const {return m_mat.m_indices[m_id]; }\n    inline Index outer() const { return m_outer; }\n    // block row index\n    inline Index row() const  {return index(); }\n    // block column index\n    inline Index col() const {return outer(); }\n    // FIXME Number of rows in the current block\n    inline Index rows() const { return (m_mat.m_blockSize==Dynamic) ? (m_mat.m_innerOffset[index()+1] - m_mat.m_innerOffset[index()]) : m_mat.m_blockSize; }\n    // Number of columns in the current block ...\n    inline Index cols() const { return (m_mat.m_blockSize==Dynamic) ? (m_mat.m_outerOffset[m_outer+1]-m_mat.m_outerOffset[m_outer]) : m_mat.m_blockSize;}\n    inline operator bool() const { return (m_id < m_end); }\n\n  protected:\n    const BlockSparseMatrix<_Scalar, _BlockAtCompileTime, _Options, StorageIndex>& m_mat;\n    const Index m_outer;\n    Index m_id;\n    Index m_end;\n};\n\ntemplate<typename _Scalar, int _BlockAtCompileTime, int _Options, typename _StorageIndex>\nclass BlockSparseMatrix<_Scalar, _BlockAtCompileTime, _Options, _StorageIndex>::InnerIterator\n{\n  public:\n    InnerIterator(const BlockSparseMatrix& mat, Index outer)\n    : m_mat(mat),m_outerB(mat.outerToBlock(outer)),m_outer(outer),\n      itb(mat, mat.outerToBlock(outer)),\n      m_offset(outer - mat.blockOuterIndex(m_outerB))\n     {\n        if (itb)\n        {\n          m_id = m_mat.blockInnerIndex(itb.index());\n          m_start = m_id;\n          m_end = m_mat.blockInnerIndex(itb.index()+1);\n        }\n     }\n    inline InnerIterator& operator++()\n    {\n      m_id++;\n      if (m_id >= m_end)\n      {\n        ++itb;\n        if (itb)\n        {\n          m_id = m_mat.blockInnerIndex(itb.index());\n          m_start = m_id;\n          m_end = m_mat.blockInnerIndex(itb.index()+1);\n        }\n      }\n      return *this;\n    }\n    inline const Scalar& value() const\n    {\n      return itb.value().coeff(m_id - m_start, m_offset);\n    }\n    inline Scalar& valueRef()\n    {\n      return itb.valueRef().coeff(m_id - m_start, m_offset);\n    }\n    inline Index index() const { return m_id; }\n    inline Index outer() const {return m_outer; }\n    inline Index col() const {return outer(); }\n    inline Index row() const { return index();}\n    inline operator bool() const\n    {\n      return itb;\n    }\n  protected:\n    const BlockSparseMatrix& m_mat;\n    const Index m_outer;\n    const Index m_outerB;\n    BlockInnerIterator itb; // Iterator through the blocks\n    const Index m_offset; // Position of this column in the block\n    Index m_start; // starting inner index of this block\n    Index m_id; // current inner index in the block\n    Index m_end; // starting inner index of the next block\n\n};\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSEBLOCKMATRIX_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SparseExtra/DynamicSparseMatrix.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_DYNAMIC_SPARSEMATRIX_H\n#define EIGEN_DYNAMIC_SPARSEMATRIX_H\n\nnamespace Eigen { \n\n/** \\deprecated use a SparseMatrix in an uncompressed mode\n  *\n  * \\class DynamicSparseMatrix\n  *\n  * \\brief A sparse matrix class designed for matrix assembly purpose\n  *\n  * \\param _Scalar the scalar type, i.e. the type of the coefficients\n  *\n  * Unlike SparseMatrix, this class provides a much higher degree of flexibility. In particular, it allows\n  * random read/write accesses in log(rho*outer_size) where \\c rho is the probability that a coefficient is\n  * nonzero and outer_size is the number of columns if the matrix is column-major and the number of rows\n  * otherwise.\n  *\n  * Internally, the data are stored as a std::vector of compressed vector. The performances of random writes might\n  * decrease as the number of nonzeros per inner-vector increase. In practice, we observed very good performance\n  * till about 100 nonzeros/vector, and the performance remains relatively good till 500 nonzeros/vectors.\n  *\n  * \\see SparseMatrix\n  */\n\nnamespace internal {\ntemplate<typename _Scalar, int _Options, typename _StorageIndex>\nstruct traits<DynamicSparseMatrix<_Scalar, _Options, _StorageIndex> >\n{\n  typedef _Scalar Scalar;\n  typedef _StorageIndex StorageIndex;\n  typedef Sparse StorageKind;\n  typedef MatrixXpr XprKind;\n  enum {\n    RowsAtCompileTime = Dynamic,\n    ColsAtCompileTime = Dynamic,\n    MaxRowsAtCompileTime = Dynamic,\n    MaxColsAtCompileTime = Dynamic,\n    Flags = _Options | NestByRefBit | LvalueBit,\n    CoeffReadCost = NumTraits<Scalar>::ReadCost,\n    SupportedAccessPatterns = OuterRandomAccessPattern\n  };\n};\n}\n\ntemplate<typename _Scalar, int _Options, typename _StorageIndex>\n class  DynamicSparseMatrix\n  : public SparseMatrixBase<DynamicSparseMatrix<_Scalar, _Options, _StorageIndex> >\n{\n    typedef SparseMatrixBase<DynamicSparseMatrix> Base;\n    using Base::convert_index;\n  public:\n    EIGEN_SPARSE_PUBLIC_INTERFACE(DynamicSparseMatrix)\n    // FIXME: why are these operator already alvailable ???\n    // EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(DynamicSparseMatrix, +=)\n    // EIGEN_SPARSE_INHERIT_ASSIGNMENT_OPERATOR(DynamicSparseMatrix, -=)\n    typedef MappedSparseMatrix<Scalar,Flags> Map;\n    using Base::IsRowMajor;\n    using Base::operator=;\n    enum {\n      Options = _Options\n    };\n\n  protected:\n\n    typedef DynamicSparseMatrix<Scalar,(Flags&~RowMajorBit)|(IsRowMajor?RowMajorBit:0), StorageIndex> TransposedSparseMatrix;\n\n    Index m_innerSize;\n    std::vector<internal::CompressedStorage<Scalar,StorageIndex> > m_data;\n\n  public:\n\n    inline Index rows() const { return IsRowMajor ? outerSize() : m_innerSize; }\n    inline Index cols() const { return IsRowMajor ? m_innerSize : outerSize(); }\n    inline Index innerSize() const { return m_innerSize; }\n    inline Index outerSize() const { return convert_index(m_data.size()); }\n    inline Index innerNonZeros(Index j) const { return m_data[j].size(); }\n\n    std::vector<internal::CompressedStorage<Scalar,StorageIndex> >& _data() { return m_data; }\n    const std::vector<internal::CompressedStorage<Scalar,StorageIndex> >& _data() const { return m_data; }\n\n    /** \\returns the coefficient value at given position \\a row, \\a col\n      * This operation involes a log(rho*outer_size) binary search.\n      */\n    inline Scalar coeff(Index row, Index col) const\n    {\n      const Index outer = IsRowMajor ? row : col;\n      const Index inner = IsRowMajor ? col : row;\n      return m_data[outer].at(inner);\n    }\n\n    /** \\returns a reference to the coefficient value at given position \\a row, \\a col\n      * This operation involes a log(rho*outer_size) binary search. If the coefficient does not\n      * exist yet, then a sorted insertion into a sequential buffer is performed.\n      */\n    inline Scalar& coeffRef(Index row, Index col)\n    {\n      const Index outer = IsRowMajor ? row : col;\n      const Index inner = IsRowMajor ? col : row;\n      return m_data[outer].atWithInsertion(inner);\n    }\n\n    class InnerIterator;\n    class ReverseInnerIterator;\n\n    void setZero()\n    {\n      for (Index j=0; j<outerSize(); ++j)\n        m_data[j].clear();\n    }\n\n    /** \\returns the number of non zero coefficients */\n    Index nonZeros() const\n    {\n      Index res = 0;\n      for (Index j=0; j<outerSize(); ++j)\n        res += m_data[j].size();\n      return res;\n    }\n\n\n\n    void reserve(Index reserveSize = 1000)\n    {\n      if (outerSize()>0)\n      {\n        Index reserveSizePerVector = (std::max)(reserveSize/outerSize(),Index(4));\n        for (Index j=0; j<outerSize(); ++j)\n        {\n          m_data[j].reserve(reserveSizePerVector);\n        }\n      }\n    }\n\n    /** Does nothing: provided for compatibility with SparseMatrix */\n    inline void startVec(Index /*outer*/) {}\n\n    /** \\returns a reference to the non zero coefficient at position \\a row, \\a col assuming that:\n      * - the nonzero does not already exist\n      * - the new coefficient is the last one of the given inner vector.\n      *\n      * \\sa insert, insertBackByOuterInner */\n    inline Scalar& insertBack(Index row, Index col)\n    {\n      return insertBackByOuterInner(IsRowMajor?row:col, IsRowMajor?col:row);\n    }\n\n    /** \\sa insertBack */\n    inline Scalar& insertBackByOuterInner(Index outer, Index inner)\n    {\n      eigen_assert(outer<Index(m_data.size()) && inner<m_innerSize && \"out of range\");\n      eigen_assert(((m_data[outer].size()==0) || (m_data[outer].index(m_data[outer].size()-1)<inner))\n                && \"wrong sorted insertion\");\n      m_data[outer].append(0, inner);\n      return m_data[outer].value(m_data[outer].size()-1);\n    }\n\n    inline Scalar& insert(Index row, Index col)\n    {\n      const Index outer = IsRowMajor ? row : col;\n      const Index inner = IsRowMajor ? col : row;\n\n      Index startId = 0;\n      Index id = static_cast<Index>(m_data[outer].size()) - 1;\n      m_data[outer].resize(id+2,1);\n\n      while ( (id >= startId) && (m_data[outer].index(id) > inner) )\n      {\n        m_data[outer].index(id+1) = m_data[outer].index(id);\n        m_data[outer].value(id+1) = m_data[outer].value(id);\n        --id;\n      }\n      m_data[outer].index(id+1) = inner;\n      m_data[outer].value(id+1) = 0;\n      return m_data[outer].value(id+1);\n    }\n\n    /** Does nothing: provided for compatibility with SparseMatrix */\n    inline void finalize() {}\n\n    /** Suppress all nonzeros which are smaller than \\a reference under the tolerance \\a epsilon */\n    void prune(Scalar reference, RealScalar epsilon = NumTraits<RealScalar>::dummy_precision())\n    {\n      for (Index j=0; j<outerSize(); ++j)\n        m_data[j].prune(reference,epsilon);\n    }\n\n    /** Resize the matrix without preserving the data (the matrix is set to zero)\n      */\n    void resize(Index rows, Index cols)\n    {\n      const Index outerSize = IsRowMajor ? rows : cols;\n      m_innerSize = convert_index(IsRowMajor ? cols : rows);\n      setZero();\n      if (Index(m_data.size()) != outerSize)\n      {\n        m_data.resize(outerSize);\n      }\n    }\n\n    void resizeAndKeepData(Index rows, Index cols)\n    {\n      const Index outerSize = IsRowMajor ? rows : cols;\n      const Index innerSize = IsRowMajor ? cols : rows;\n      if (m_innerSize>innerSize)\n      {\n        // remove all coefficients with innerCoord>=innerSize\n        // TODO\n        //std::cerr << \"not implemented yet\\n\";\n        exit(2);\n      }\n      if (m_data.size() != outerSize)\n      {\n        m_data.resize(outerSize);\n      }\n    }\n\n    /** The class DynamicSparseMatrix is deprecated */\n    EIGEN_DEPRECATED inline DynamicSparseMatrix()\n      : m_innerSize(0), m_data(0)\n    {\n      #ifdef EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n        EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n      #endif\n      eigen_assert(innerSize()==0 && outerSize()==0);\n    }\n\n    /** The class DynamicSparseMatrix is deprecated */\n    EIGEN_DEPRECATED inline DynamicSparseMatrix(Index rows, Index cols)\n      : m_innerSize(0)\n    {\n      #ifdef EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n        EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n      #endif\n      resize(rows, cols);\n    }\n\n    /** The class DynamicSparseMatrix is deprecated */\n    template<typename OtherDerived>\n    EIGEN_DEPRECATED explicit inline DynamicSparseMatrix(const SparseMatrixBase<OtherDerived>& other)\n      : m_innerSize(0)\n    {\n      #ifdef EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n        EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n      #endif\n      Base::operator=(other.derived());\n    }\n\n    inline DynamicSparseMatrix(const DynamicSparseMatrix& other)\n      : Base(), m_innerSize(0)\n    {\n      #ifdef EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n        EIGEN_SPARSE_CREATE_TEMPORARY_PLUGIN\n      #endif\n      *this = other.derived();\n    }\n\n    inline void swap(DynamicSparseMatrix& other)\n    {\n      //EIGEN_DBG_SPARSE(std::cout << \"SparseMatrix:: swap\\n\");\n      std::swap(m_innerSize, other.m_innerSize);\n      //std::swap(m_outerSize, other.m_outerSize);\n      m_data.swap(other.m_data);\n    }\n\n    inline DynamicSparseMatrix& operator=(const DynamicSparseMatrix& other)\n    {\n      if (other.isRValue())\n      {\n        swap(other.const_cast_derived());\n      }\n      else\n      {\n        resize(other.rows(), other.cols());\n        m_data = other.m_data;\n      }\n      return *this;\n    }\n\n    /** Destructor */\n    inline ~DynamicSparseMatrix() {}\n\n  public:\n\n    /** \\deprecated\n      * Set the matrix to zero and reserve the memory for \\a reserveSize nonzero coefficients. */\n    EIGEN_DEPRECATED void startFill(Index reserveSize = 1000)\n    {\n      setZero();\n      reserve(reserveSize);\n    }\n\n    /** \\deprecated use insert()\n      * inserts a nonzero coefficient at given coordinates \\a row, \\a col and returns its reference assuming that:\n      *  1 - the coefficient does not exist yet\n      *  2 - this the coefficient with greater inner coordinate for the given outer coordinate.\n      * In other words, assuming \\c *this is column-major, then there must not exists any nonzero coefficient of coordinates\n      * \\c i \\c x \\a col such that \\c i >= \\a row. Otherwise the matrix is invalid.\n      *\n      * \\see fillrand(), coeffRef()\n      */\n    EIGEN_DEPRECATED Scalar& fill(Index row, Index col)\n    {\n      const Index outer = IsRowMajor ? row : col;\n      const Index inner = IsRowMajor ? col : row;\n      return insertBack(outer,inner);\n    }\n\n    /** \\deprecated use insert()\n      * Like fill() but with random inner coordinates.\n      * Compared to the generic coeffRef(), the unique limitation is that we assume\n      * the coefficient does not exist yet.\n      */\n    EIGEN_DEPRECATED Scalar& fillrand(Index row, Index col)\n    {\n      return insert(row,col);\n    }\n\n    /** \\deprecated use finalize()\n      * Does nothing. Provided for compatibility with SparseMatrix. */\n    EIGEN_DEPRECATED void endFill() {}\n    \n#   ifdef EIGEN_DYNAMICSPARSEMATRIX_PLUGIN\n#     include EIGEN_DYNAMICSPARSEMATRIX_PLUGIN\n#   endif\n };\n\ntemplate<typename Scalar, int _Options, typename _StorageIndex>\nclass DynamicSparseMatrix<Scalar,_Options,_StorageIndex>::InnerIterator : public SparseVector<Scalar,_Options,_StorageIndex>::InnerIterator\n{\n    typedef typename SparseVector<Scalar,_Options,_StorageIndex>::InnerIterator Base;\n  public:\n    InnerIterator(const DynamicSparseMatrix& mat, Index outer)\n      : Base(mat.m_data[outer]), m_outer(outer)\n    {}\n\n    inline Index row() const { return IsRowMajor ? m_outer : Base::index(); }\n    inline Index col() const { return IsRowMajor ? Base::index() : m_outer; }\n    inline Index outer() const { return m_outer; }\n\n  protected:\n    const Index m_outer;\n};\n\ntemplate<typename Scalar, int _Options, typename _StorageIndex>\nclass DynamicSparseMatrix<Scalar,_Options,_StorageIndex>::ReverseInnerIterator : public SparseVector<Scalar,_Options,_StorageIndex>::ReverseInnerIterator\n{\n    typedef typename SparseVector<Scalar,_Options,_StorageIndex>::ReverseInnerIterator Base;\n  public:\n    ReverseInnerIterator(const DynamicSparseMatrix& mat, Index outer)\n      : Base(mat.m_data[outer]), m_outer(outer)\n    {}\n\n    inline Index row() const { return IsRowMajor ? m_outer : Base::index(); }\n    inline Index col() const { return IsRowMajor ? Base::index() : m_outer; }\n    inline Index outer() const { return m_outer; }\n\n  protected:\n    const Index m_outer;\n};\n\nnamespace internal {\n\ntemplate<typename _Scalar, int _Options, typename _StorageIndex>\nstruct evaluator<DynamicSparseMatrix<_Scalar,_Options,_StorageIndex> >\n  : evaluator_base<DynamicSparseMatrix<_Scalar,_Options,_StorageIndex> >\n{\n  typedef _Scalar Scalar;\n  typedef DynamicSparseMatrix<_Scalar,_Options,_StorageIndex> SparseMatrixType;\n  typedef typename SparseMatrixType::InnerIterator InnerIterator;\n  typedef typename SparseMatrixType::ReverseInnerIterator ReverseInnerIterator;\n  \n  enum {\n    CoeffReadCost = NumTraits<_Scalar>::ReadCost,\n    Flags = SparseMatrixType::Flags\n  };\n  \n  evaluator() : m_matrix(0) {}\n  evaluator(const SparseMatrixType &mat) : m_matrix(&mat) {}\n  \n  operator SparseMatrixType&() { return m_matrix->const_cast_derived(); }\n  operator const SparseMatrixType&() const { return *m_matrix; }\n  \n  Scalar coeff(Index row, Index col) const { return m_matrix->coeff(row,col); }\n  \n  Index nonZerosEstimate() const { return m_matrix->nonZeros(); }\n\n  const SparseMatrixType *m_matrix;\n};\n\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_DYNAMIC_SPARSEMATRIX_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SparseExtra/MarketIO.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2012 Desire NUENTSA WAKAM <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPARSE_MARKET_IO_H\n#define EIGEN_SPARSE_MARKET_IO_H\n\n#include <iostream>\n#include <vector>\n\nnamespace Eigen { \n\nnamespace internal \n{\n  template <typename Scalar, typename StorageIndex>\n  inline void GetMarketLine (const char* line, StorageIndex& i, StorageIndex& j, Scalar& value)\n  {\n    std::stringstream sline(line);\n    sline >> i >> j >> value;\n  }\n\n  template<> inline void GetMarketLine (const char* line, int& i, int& j, float& value)\n  { std::sscanf(line, \"%d %d %g\", &i, &j, &value); }\n\n  template<> inline void GetMarketLine (const char* line, int& i, int& j, double& value)\n  { std::sscanf(line, \"%d %d %lg\", &i, &j, &value); }\n\n  template<> inline void GetMarketLine (const char* line, int& i, int& j, std::complex<float>& value)\n  { std::sscanf(line, \"%d %d %g %g\", &i, &j, &numext::real_ref(value), &numext::imag_ref(value)); }\n\n  template<> inline void GetMarketLine (const char* line, int& i, int& j, std::complex<double>& value)\n  { std::sscanf(line, \"%d %d %lg %lg\", &i, &j, &numext::real_ref(value), &numext::imag_ref(value)); }\n\n  template <typename Scalar, typename StorageIndex>\n  inline void GetMarketLine (const char* line, StorageIndex& i, StorageIndex& j, std::complex<Scalar>& value)\n  {\n    std::stringstream sline(line);\n    Scalar valR, valI;\n    sline >> i >> j >> valR >> valI;\n    value = std::complex<Scalar>(valR,valI);\n  }\n\n  template <typename RealScalar>\n  inline void  GetVectorElt (const std::string& line, RealScalar& val)\n  {\n    std::istringstream newline(line);\n    newline >> val;  \n  }\n\n  template <typename RealScalar>\n  inline void GetVectorElt (const std::string& line, std::complex<RealScalar>& val)\n  {\n    RealScalar valR, valI; \n    std::istringstream newline(line);\n    newline >> valR >> valI; \n    val = std::complex<RealScalar>(valR, valI);\n  }\n  \n  template<typename Scalar>\n  inline void putMarketHeader(std::string& header,int sym)\n  {\n    header= \"%%MatrixMarket matrix coordinate \";\n    if(internal::is_same<Scalar, std::complex<float> >::value || internal::is_same<Scalar, std::complex<double> >::value)\n    {\n      header += \" complex\"; \n      if(sym == Symmetric) header += \" symmetric\";\n      else if (sym == SelfAdjoint) header += \" Hermitian\";\n      else header += \" general\";\n    }\n    else\n    {\n      header += \" real\"; \n      if(sym == Symmetric) header += \" symmetric\";\n      else header += \" general\";\n    }\n  }\n\n  template<typename Scalar, typename StorageIndex>\n  inline void PutMatrixElt(Scalar value, StorageIndex row, StorageIndex col, std::ofstream& out)\n  {\n    out << row << \" \"<< col << \" \" << value << \"\\n\";\n  }\n  template<typename Scalar, typename StorageIndex>\n  inline void PutMatrixElt(std::complex<Scalar> value, StorageIndex row, StorageIndex col, std::ofstream& out)\n  {\n    out << row << \" \" << col << \" \" << value.real() << \" \" << value.imag() << \"\\n\";\n  }\n\n\n  template<typename Scalar>\n  inline void putVectorElt(Scalar value, std::ofstream& out)\n  {\n    out << value << \"\\n\"; \n  }\n  template<typename Scalar>\n  inline void putVectorElt(std::complex<Scalar> value, std::ofstream& out)\n  {\n    out << value.real() << \" \" << value.imag()<< \"\\n\"; \n  }\n\n} // end namespace internal\n\ninline bool getMarketHeader(const std::string& filename, int& sym, bool& iscomplex, bool& isvector)\n{\n  sym = 0; \n  iscomplex = false;\n  isvector = false;\n  std::ifstream in(filename.c_str(),std::ios::in);\n  if(!in)\n    return false;\n  \n  std::string line; \n  // The matrix header is always the first line in the file \n  std::getline(in, line); eigen_assert(in.good());\n  \n  std::stringstream fmtline(line); \n  std::string substr[5];\n  fmtline>> substr[0] >> substr[1] >> substr[2] >> substr[3] >> substr[4];\n  if(substr[2].compare(\"array\") == 0) isvector = true;\n  if(substr[3].compare(\"complex\") == 0) iscomplex = true;\n  if(substr[4].compare(\"symmetric\") == 0) sym = Symmetric;\n  else if (substr[4].compare(\"Hermitian\") == 0) sym = SelfAdjoint;\n  \n  return true;\n}\n  \ntemplate<typename SparseMatrixType>\nbool loadMarket(SparseMatrixType& mat, const std::string& filename)\n{\n  typedef typename SparseMatrixType::Scalar Scalar;\n  typedef typename SparseMatrixType::StorageIndex StorageIndex;\n  std::ifstream input(filename.c_str(),std::ios::in);\n  if(!input)\n    return false;\n\n  char rdbuffer[4096];\n  input.rdbuf()->pubsetbuf(rdbuffer, 4096);\n  \n  const int maxBuffersize = 2048;\n  char buffer[maxBuffersize];\n  \n  bool readsizes = false;\n\n  typedef Triplet<Scalar,StorageIndex> T;\n  std::vector<T> elements;\n  \n  Index M(-1), N(-1), NNZ(-1);\n  Index count = 0;\n  while(input.getline(buffer, maxBuffersize))\n  {\n    // skip comments   \n    //NOTE An appropriate test should be done on the header to get the  symmetry\n    if(buffer[0]=='%')\n      continue;\n\n    if(!readsizes)\n    {\n      std::stringstream line(buffer);\n      line >> M >> N >> NNZ;\n      if(M > 0 && N > 0)\n      {\n        readsizes = true;\n        mat.resize(M,N);\n        mat.reserve(NNZ);\n      }\n    }\n    else\n    { \n      StorageIndex i(-1), j(-1);\n      Scalar value; \n      internal::GetMarketLine(buffer, i, j, value);\n\n      i--;\n      j--;\n      if(i>=0 && j>=0 && i<M && j<N)\n      {\n        ++count;\n        elements.push_back(T(i,j,value));\n      }\n      else\n        std::cerr << \"Invalid read: \" << i << \",\" << j << \"\\n\";        \n    }\n  }\n\n  mat.setFromTriplets(elements.begin(), elements.end());\n  if(count!=NNZ)\n    std::cerr << count << \"!=\" << NNZ << \"\\n\";\n  \n  input.close();\n  return true;\n}\n\ntemplate<typename VectorType>\nbool loadMarketVector(VectorType& vec, const std::string& filename)\n{\n   typedef typename VectorType::Scalar Scalar;\n  std::ifstream in(filename.c_str(), std::ios::in);\n  if(!in)\n    return false;\n  \n  std::string line; \n  int n(0), col(0); \n  do \n  { // Skip comments\n    std::getline(in, line); eigen_assert(in.good());\n  } while (line[0] == '%');\n  std::istringstream newline(line);\n  newline  >> n >> col; \n  eigen_assert(n>0 && col>0);\n  vec.resize(n);\n  int i = 0; \n  Scalar value; \n  while ( std::getline(in, line) && (i < n) ){\n    internal::GetVectorElt(line, value); \n    vec(i++) = value; \n  }\n  in.close();\n  if (i!=n){\n    std::cerr<< \"Unable to read all elements from file \" << filename << \"\\n\";\n    return false;\n  }\n  return true;\n}\n\ntemplate<typename SparseMatrixType>\nbool saveMarket(const SparseMatrixType& mat, const std::string& filename, int sym = 0)\n{\n  typedef typename SparseMatrixType::Scalar Scalar;\n  typedef typename SparseMatrixType::RealScalar RealScalar;\n  std::ofstream out(filename.c_str(),std::ios::out);\n  if(!out)\n    return false;\n  \n  out.flags(std::ios_base::scientific);\n  out.precision(std::numeric_limits<RealScalar>::digits10 + 2);\n  std::string header; \n  internal::putMarketHeader<Scalar>(header, sym); \n  out << header << std::endl; \n  out << mat.rows() << \" \" << mat.cols() << \" \" << mat.nonZeros() << \"\\n\";\n  int count = 0;\n  for(int j=0; j<mat.outerSize(); ++j)\n    for(typename SparseMatrixType::InnerIterator it(mat,j); it; ++it)\n    {\n      ++ count;\n      internal::PutMatrixElt(it.value(), it.row()+1, it.col()+1, out);\n    }\n  out.close();\n  return true;\n}\n\ntemplate<typename VectorType>\nbool saveMarketVector (const VectorType& vec, const std::string& filename)\n{\n typedef typename VectorType::Scalar Scalar;\n typedef typename VectorType::RealScalar RealScalar;\n std::ofstream out(filename.c_str(),std::ios::out);\n  if(!out)\n    return false;\n  \n  out.flags(std::ios_base::scientific);\n  out.precision(std::numeric_limits<RealScalar>::digits10 + 2);\n  if(internal::is_same<Scalar, std::complex<float> >::value || internal::is_same<Scalar, std::complex<double> >::value)\n      out << \"%%MatrixMarket matrix array complex general\\n\"; \n  else\n    out << \"%%MatrixMarket matrix array real general\\n\"; \n  out << vec.size() << \" \"<< 1 << \"\\n\";\n  for (int i=0; i < vec.size(); i++){\n    internal::putVectorElt(vec(i), out); \n  }\n  out.close();\n  return true; \n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPARSE_MARKET_IO_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SparseExtra/MatrixMarketIterator.h",
    "content": "\n// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Desire NUENTSA WAKAM <desire.nuentsa_wakam@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BROWSE_MATRICES_H\n#define EIGEN_BROWSE_MATRICES_H\n\nnamespace Eigen {\n\nenum {\n  SPD = 0x100,\n  NonSymmetric = 0x0\n}; \n\n/** \n * @brief Iterator to browse matrices from a specified folder\n * \n * This is used to load all the matrices from a folder. \n * The matrices should be in Matrix Market format\n * It is assumed that the matrices are named as matname.mtx\n * and matname_SPD.mtx if the matrix is Symmetric and positive definite (or Hermitian)\n * The right hand side vectors are loaded as well, if they exist.\n * They should be named as matname_b.mtx. \n * Note that the right hand side for a SPD matrix is named as matname_SPD_b.mtx\n * \n * Sometimes a reference solution is available. In this case, it should be named as matname_x.mtx\n * \n * Sample code\n * \\code\n * \n * \\endcode\n * \n * \\tparam Scalar The scalar type \n */\ntemplate <typename Scalar>\nclass MatrixMarketIterator \n{\n    typedef typename NumTraits<Scalar>::Real RealScalar;\n  public:\n    typedef Matrix<Scalar,Dynamic,1> VectorType; \n    typedef SparseMatrix<Scalar,ColMajor> MatrixType; \n  \n  public:\n    MatrixMarketIterator(const std::string &folder)\n      : m_sym(0), m_isvalid(false), m_matIsLoaded(false), m_hasRhs(false), m_hasrefX(false), m_folder(folder)\n    {\n      m_folder_id = opendir(folder.c_str());\n      if(m_folder_id)\n        Getnextvalidmatrix();\n    }\n    \n    ~MatrixMarketIterator()\n    {\n      if (m_folder_id) closedir(m_folder_id); \n    }\n    \n    inline MatrixMarketIterator& operator++()\n    {\n      m_matIsLoaded = false;\n      m_hasrefX = false;\n      m_hasRhs = false;\n      Getnextvalidmatrix();\n      return *this;\n    }\n    inline operator bool() const { return m_isvalid;}\n    \n    /** Return the sparse matrix corresponding to the current file */\n    inline MatrixType& matrix() \n    { \n      // Read the matrix\n      if (m_matIsLoaded) return m_mat;\n      \n      std::string matrix_file = m_folder + \"/\" + m_matname + \".mtx\";\n      if ( !loadMarket(m_mat, matrix_file)) \n      {\n        std::cerr << \"Warning loadMarket failed when loading \\\"\" << matrix_file << \"\\\"\" << std::endl;\n        m_matIsLoaded = false;\n        return m_mat;\n      }\n      m_matIsLoaded = true; \n\n      if (m_sym != NonSymmetric) \n      {\n        // Check whether we need to restore a full matrix:\n        RealScalar diag_norm  = m_mat.diagonal().norm();\n        RealScalar lower_norm = m_mat.template triangularView<Lower>().norm();\n        RealScalar upper_norm = m_mat.template triangularView<Upper>().norm();\n        if(lower_norm>diag_norm && upper_norm==diag_norm)\n        {\n          // only the lower part is stored\n          MatrixType tmp(m_mat);\n          m_mat = tmp.template selfadjointView<Lower>();\n        }\n        else if(upper_norm>diag_norm && lower_norm==diag_norm)\n        {\n          // only the upper part is stored\n          MatrixType tmp(m_mat);\n          m_mat = tmp.template selfadjointView<Upper>();\n        }\n      }\n      return m_mat; \n    }\n    \n    /** Return the right hand side corresponding to the current matrix. \n     * If the rhs file is not provided, a random rhs is generated\n     */\n    inline VectorType& rhs() \n    { \n       // Get the right hand side\n      if (m_hasRhs) return m_rhs;\n      \n      std::string rhs_file;\n      rhs_file = m_folder + \"/\" + m_matname + \"_b.mtx\"; // The pattern is matname_b.mtx\n      m_hasRhs = Fileexists(rhs_file);\n      if (m_hasRhs)\n      {\n        m_rhs.resize(m_mat.cols());\n        m_hasRhs = loadMarketVector(m_rhs, rhs_file);\n      }\n      if (!m_hasRhs)\n      {\n        // Generate a random right hand side\n        if (!m_matIsLoaded) this->matrix(); \n        m_refX.resize(m_mat.cols());\n        m_refX.setRandom();\n        m_rhs = m_mat * m_refX;\n        m_hasrefX = true;\n        m_hasRhs = true;\n      }\n      return m_rhs; \n    }\n    \n    /** Return a reference solution\n     * If it is not provided and if the right hand side is not available\n     * then refX is randomly generated such that A*refX = b \n     * where A and b are the matrix and the rhs. \n     * Note that when a rhs is provided, refX is not available \n     */\n    inline VectorType& refX() \n    { \n      // Check if a reference solution is provided\n      if (m_hasrefX) return m_refX;\n      \n      std::string lhs_file;\n      lhs_file = m_folder + \"/\" + m_matname + \"_x.mtx\"; \n      m_hasrefX = Fileexists(lhs_file);\n      if (m_hasrefX)\n      {\n        m_refX.resize(m_mat.cols());\n        m_hasrefX = loadMarketVector(m_refX, lhs_file);\n      }\n      else\n        m_refX.resize(0);\n      return m_refX; \n    }\n    \n    inline std::string& matname() { return m_matname; }\n    \n    inline int sym() { return m_sym; }\n    \n    bool hasRhs() {return m_hasRhs; }\n    bool hasrefX() {return m_hasrefX; }\n    bool isFolderValid() { return bool(m_folder_id); }\n    \n  protected:\n    \n    inline bool Fileexists(std::string file)\n    {\n      std::ifstream file_id(file.c_str());\n      if (!file_id.good() ) \n      {\n        return false;\n      }\n      else \n      {\n        file_id.close();\n        return true;\n      }\n    }\n    \n    void Getnextvalidmatrix( )\n    {\n      m_isvalid = false;\n      // Here, we return with the next valid matrix in the folder\n      while ( (m_curs_id = readdir(m_folder_id)) != NULL) {\n        m_isvalid = false;\n        std::string curfile;\n        curfile = m_folder + \"/\" + m_curs_id->d_name;\n        // Discard if it is a folder\n        if (m_curs_id->d_type == DT_DIR) continue; //FIXME This may not be available on non BSD systems\n//         struct stat st_buf; \n//         stat (curfile.c_str(), &st_buf);\n//         if (S_ISDIR(st_buf.st_mode)) continue;\n        \n        // Determine from the header if it is a matrix or a right hand side \n        bool isvector,iscomplex=false;\n        if(!getMarketHeader(curfile,m_sym,iscomplex,isvector)) continue;\n        if(isvector) continue;\n        if (!iscomplex)\n        {\n          if(internal::is_same<Scalar, std::complex<float> >::value || internal::is_same<Scalar, std::complex<double> >::value)\n            continue; \n        }\n        if (iscomplex)\n        {\n          if(internal::is_same<Scalar, float>::value || internal::is_same<Scalar, double>::value)\n            continue; \n        }\n        \n        \n        // Get the matrix name\n        std::string filename = m_curs_id->d_name;\n        m_matname = filename.substr(0, filename.length()-4); \n        \n        // Find if the matrix is SPD \n        size_t found = m_matname.find(\"SPD\");\n        if( (found!=std::string::npos) && (m_sym != NonSymmetric) )\n          m_sym = SPD;\n       \n        m_isvalid = true;\n        break; \n      }\n    }\n    int m_sym; // Symmetry of the matrix\n    MatrixType m_mat; // Current matrix  \n    VectorType m_rhs;  // Current vector\n    VectorType m_refX; // The reference solution, if exists\n    std::string m_matname; // Matrix Name\n    bool m_isvalid; \n    bool m_matIsLoaded; // Determine if the matrix has already been loaded from the file\n    bool m_hasRhs; // The right hand side exists\n    bool m_hasrefX; // A reference solution is provided\n    std::string m_folder;\n    DIR * m_folder_id;\n    struct dirent *m_curs_id; \n    \n};\n\n} // end namespace Eigen\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SparseExtra/RandomSetter.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_RANDOMSETTER_H\n#define EIGEN_RANDOMSETTER_H\n\nnamespace Eigen { \n\n/** Represents a std::map\n  *\n  * \\see RandomSetter\n  */\ntemplate<typename Scalar> struct StdMapTraits\n{\n  typedef int KeyType;\n  typedef std::map<KeyType,Scalar> Type;\n  enum {\n    IsSorted = 1\n  };\n\n  static void setInvalidKey(Type&, const KeyType&) {}\n};\n\n#ifdef EIGEN_UNORDERED_MAP_SUPPORT\n/** Represents a std::unordered_map\n  *\n  * To use it you need to both define EIGEN_UNORDERED_MAP_SUPPORT and include the unordered_map header file\n  * yourself making sure that unordered_map is defined in the std namespace.\n  *\n  * For instance, with current version of gcc you can either enable C++0x standard (-std=c++0x) or do:\n  * \\code\n  * #include <tr1/unordered_map>\n  * #define EIGEN_UNORDERED_MAP_SUPPORT\n  * namespace std {\n  *   using std::tr1::unordered_map;\n  * }\n  * \\endcode\n  *\n  * \\see RandomSetter\n  */\ntemplate<typename Scalar> struct StdUnorderedMapTraits\n{\n  typedef int KeyType;\n  typedef std::unordered_map<KeyType,Scalar> Type;\n  enum {\n    IsSorted = 0\n  };\n\n  static void setInvalidKey(Type&, const KeyType&) {}\n};\n#endif // EIGEN_UNORDERED_MAP_SUPPORT\n\n#ifdef _DENSE_HASH_MAP_H_\n/** Represents a google::dense_hash_map\n  *\n  * \\see RandomSetter\n  */\ntemplate<typename Scalar> struct GoogleDenseHashMapTraits\n{\n  typedef int KeyType;\n  typedef google::dense_hash_map<KeyType,Scalar> Type;\n  enum {\n    IsSorted = 0\n  };\n\n  static void setInvalidKey(Type& map, const KeyType& k)\n  { map.set_empty_key(k); }\n};\n#endif\n\n#ifdef _SPARSE_HASH_MAP_H_\n/** Represents a google::sparse_hash_map\n  *\n  * \\see RandomSetter\n  */\ntemplate<typename Scalar> struct GoogleSparseHashMapTraits\n{\n  typedef int KeyType;\n  typedef google::sparse_hash_map<KeyType,Scalar> Type;\n  enum {\n    IsSorted = 0\n  };\n\n  static void setInvalidKey(Type&, const KeyType&) {}\n};\n#endif\n\n/** \\class RandomSetter\n  *\n  * \\brief The RandomSetter is a wrapper object allowing to set/update a sparse matrix with random access\n  *\n  * \\tparam SparseMatrixType the type of the sparse matrix we are updating\n  * \\tparam MapTraits a traits class representing the map implementation used for the temporary sparse storage.\n  *                  Its default value depends on the system.\n  * \\tparam OuterPacketBits defines the number of rows (or columns) manage by a single map object\n  *                        as a power of two exponent.\n  *\n  * This class temporarily represents a sparse matrix object using a generic map implementation allowing for\n  * efficient random access. The conversion from the compressed representation to a hash_map object is performed\n  * in the RandomSetter constructor, while the sparse matrix is updated back at destruction time. This strategy\n  * suggest the use of nested blocks as in this example:\n  *\n  * \\code\n  * SparseMatrix<double> m(rows,cols);\n  * {\n  *   RandomSetter<SparseMatrix<double> > w(m);\n  *   // don't use m but w instead with read/write random access to the coefficients:\n  *   for(;;)\n  *     w(rand(),rand()) = rand;\n  * }\n  * // when w is deleted, the data are copied back to m\n  * // and m is ready to use.\n  * \\endcode\n  *\n  * Since hash_map objects are not fully sorted, representing a full matrix as a single hash_map would\n  * involve a big and costly sort to update the compressed matrix back. To overcome this issue, a RandomSetter\n  * use multiple hash_map, each representing 2^OuterPacketBits columns or rows according to the storage order.\n  * To reach optimal performance, this value should be adjusted according to the average number of nonzeros\n  * per rows/columns.\n  *\n  * The possible values for the template parameter MapTraits are:\n  *  - \\b StdMapTraits: corresponds to std::map. (does not perform very well)\n  *  - \\b GnuHashMapTraits: corresponds to __gnu_cxx::hash_map (available only with GCC)\n  *  - \\b GoogleDenseHashMapTraits: corresponds to google::dense_hash_map (best efficiency, reasonable memory consumption)\n  *  - \\b GoogleSparseHashMapTraits: corresponds to google::sparse_hash_map (best memory consumption, relatively good performance)\n  *\n  * The default map implementation depends on the availability, and the preferred order is:\n  * GoogleSparseHashMapTraits, GnuHashMapTraits, and finally StdMapTraits.\n  *\n  * For performance and memory consumption reasons it is highly recommended to use one of\n  * the Google's hash_map implementation. To enable the support for them, you have two options:\n  *  - \\#include <google/dense_hash_map> yourself \\b before Eigen/Sparse header\n  *  - define EIGEN_GOOGLEHASH_SUPPORT\n  * In the later case the inclusion of <google/dense_hash_map> is made for you.\n  *\n  * \\see http://code.google.com/p/google-sparsehash/\n  */\ntemplate<typename SparseMatrixType,\n         template <typename T> class MapTraits =\n#if defined _DENSE_HASH_MAP_H_\n          GoogleDenseHashMapTraits\n#elif defined _HASH_MAP\n          GnuHashMapTraits\n#else\n          StdMapTraits\n#endif\n         ,int OuterPacketBits = 6>\nclass RandomSetter\n{\n    typedef typename SparseMatrixType::Scalar Scalar;\n    typedef typename SparseMatrixType::StorageIndex StorageIndex;\n\n    struct ScalarWrapper\n    {\n      ScalarWrapper() : value(0) {}\n      Scalar value;\n    };\n    typedef typename MapTraits<ScalarWrapper>::KeyType KeyType;\n    typedef typename MapTraits<ScalarWrapper>::Type HashMapType;\n    static const int OuterPacketMask = (1 << OuterPacketBits) - 1;\n    enum {\n      SwapStorage = 1 - MapTraits<ScalarWrapper>::IsSorted,\n      TargetRowMajor = (SparseMatrixType::Flags & RowMajorBit) ? 1 : 0,\n      SetterRowMajor = SwapStorage ? 1-TargetRowMajor : TargetRowMajor\n    };\n\n  public:\n\n    /** Constructs a random setter object from the sparse matrix \\a target\n      *\n      * Note that the initial value of \\a target are imported. If you want to re-set\n      * a sparse matrix from scratch, then you must set it to zero first using the\n      * setZero() function.\n      */\n    inline RandomSetter(SparseMatrixType& target)\n      : mp_target(&target)\n    {\n      const Index outerSize = SwapStorage ? target.innerSize() : target.outerSize();\n      const Index innerSize = SwapStorage ? target.outerSize() : target.innerSize();\n      m_outerPackets = outerSize >> OuterPacketBits;\n      if (outerSize&OuterPacketMask)\n        m_outerPackets += 1;\n      m_hashmaps = new HashMapType[m_outerPackets];\n      // compute number of bits needed to store inner indices\n      Index aux = innerSize - 1;\n      m_keyBitsOffset = 0;\n      while (aux)\n      {\n        ++m_keyBitsOffset;\n        aux = aux >> 1;\n      }\n      KeyType ik = (1<<(OuterPacketBits+m_keyBitsOffset));\n      for (Index k=0; k<m_outerPackets; ++k)\n        MapTraits<ScalarWrapper>::setInvalidKey(m_hashmaps[k],ik);\n\n      // insert current coeffs\n      for (Index j=0; j<mp_target->outerSize(); ++j)\n        for (typename SparseMatrixType::InnerIterator it(*mp_target,j); it; ++it)\n          (*this)(TargetRowMajor?j:it.index(), TargetRowMajor?it.index():j) = it.value();\n    }\n\n    /** Destructor updating back the sparse matrix target */\n    ~RandomSetter()\n    {\n      KeyType keyBitsMask = (1<<m_keyBitsOffset)-1;\n      if (!SwapStorage) // also means the map is sorted\n      {\n        mp_target->setZero();\n        mp_target->makeCompressed();\n        mp_target->reserve(nonZeros());\n        Index prevOuter = -1;\n        for (Index k=0; k<m_outerPackets; ++k)\n        {\n          const Index outerOffset = (1<<OuterPacketBits) * k;\n          typename HashMapType::iterator end = m_hashmaps[k].end();\n          for (typename HashMapType::iterator it = m_hashmaps[k].begin(); it!=end; ++it)\n          {\n            const Index outer = (it->first >> m_keyBitsOffset) + outerOffset;\n            const Index inner = it->first & keyBitsMask;\n            if (prevOuter!=outer)\n            {\n              for (Index j=prevOuter+1;j<=outer;++j)\n                mp_target->startVec(j);\n              prevOuter = outer;\n            }\n            mp_target->insertBackByOuterInner(outer, inner) = it->second.value;\n          }\n        }\n        mp_target->finalize();\n      }\n      else\n      {\n        VectorXi positions(mp_target->outerSize());\n        positions.setZero();\n        // pass 1\n        for (Index k=0; k<m_outerPackets; ++k)\n        {\n          typename HashMapType::iterator end = m_hashmaps[k].end();\n          for (typename HashMapType::iterator it = m_hashmaps[k].begin(); it!=end; ++it)\n          {\n            const Index outer = it->first & keyBitsMask;\n            ++positions[outer];\n          }\n        }\n        // prefix sum\n        StorageIndex count = 0;\n        for (Index j=0; j<mp_target->outerSize(); ++j)\n        {\n          StorageIndex tmp = positions[j];\n          mp_target->outerIndexPtr()[j] = count;\n          positions[j] = count;\n          count += tmp;\n        }\n        mp_target->makeCompressed();\n        mp_target->outerIndexPtr()[mp_target->outerSize()] = count;\n        mp_target->resizeNonZeros(count);\n        // pass 2\n        for (Index k=0; k<m_outerPackets; ++k)\n        {\n          const Index outerOffset = (1<<OuterPacketBits) * k;\n          typename HashMapType::iterator end = m_hashmaps[k].end();\n          for (typename HashMapType::iterator it = m_hashmaps[k].begin(); it!=end; ++it)\n          {\n            const Index inner = (it->first >> m_keyBitsOffset) + outerOffset;\n            const Index outer = it->first & keyBitsMask;\n            // sorted insertion\n            // Note that we have to deal with at most 2^OuterPacketBits unsorted coefficients,\n            // moreover those 2^OuterPacketBits coeffs are likely to be sparse, an so only a\n            // small fraction of them have to be sorted, whence the following simple procedure:\n            Index posStart = mp_target->outerIndexPtr()[outer];\n            Index i = (positions[outer]++) - 1;\n            while ( (i >= posStart) && (mp_target->innerIndexPtr()[i] > inner) )\n            {\n              mp_target->valuePtr()[i+1] = mp_target->valuePtr()[i];\n              mp_target->innerIndexPtr()[i+1] = mp_target->innerIndexPtr()[i];\n              --i;\n            }\n            mp_target->innerIndexPtr()[i+1] = internal::convert_index<StorageIndex>(inner);\n            mp_target->valuePtr()[i+1] = it->second.value;\n          }\n        }\n      }\n      delete[] m_hashmaps;\n    }\n\n    /** \\returns a reference to the coefficient at given coordinates \\a row, \\a col */\n    Scalar& operator() (Index row, Index col)\n    {\n      const Index outer = SetterRowMajor ? row : col;\n      const Index inner = SetterRowMajor ? col : row;\n      const Index outerMajor = outer >> OuterPacketBits; // index of the packet/map\n      const Index outerMinor = outer & OuterPacketMask;  // index of the inner vector in the packet\n      const KeyType key = internal::convert_index<KeyType>((outerMinor<<m_keyBitsOffset) | inner);\n      return m_hashmaps[outerMajor][key].value;\n    }\n\n    /** \\returns the number of non zero coefficients\n      *\n      * \\note According to the underlying map/hash_map implementation,\n      * this function might be quite expensive.\n      */\n    Index nonZeros() const\n    {\n      Index nz = 0;\n      for (Index k=0; k<m_outerPackets; ++k)\n        nz += static_cast<Index>(m_hashmaps[k].size());\n      return nz;\n    }\n\n\n  protected:\n\n    HashMapType* m_hashmaps;\n    SparseMatrixType* mp_target;\n    Index m_outerPackets;\n    unsigned char m_keyBitsOffset;\n};\n\n} // end namespace Eigen\n\n#endif // EIGEN_RANDOMSETTER_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SpecialFunctions/BesselFunctionsArrayAPI.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#ifndef EIGEN_BESSELFUNCTIONS_ARRAYAPI_H\n#define EIGEN_BESSELFUNCTIONS_ARRAYAPI_H\n\nnamespace Eigen {\n\n/** \\returns an expression of the coefficient-wise i0(\\a x) to the given\n * arrays.\n  *\n  * It returns the modified Bessel function of the first kind of order zero.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of i0(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_i0()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_i0_op<typename Derived::Scalar>, const Derived>\nbessel_i0(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_i0_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise i0e(\\a x) to the given\n * arrays.\n  *\n  * It returns the exponentially scaled modified Bessel\n  * function of the first kind of order zero.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of i0e(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_i0e()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_i0e_op<typename Derived::Scalar>, const Derived>\nbessel_i0e(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_i0e_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise i1(\\a x) to the given\n * arrays.\n  *\n  * It returns the modified Bessel function of the first kind of order one.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of i1(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_i1()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_i1_op<typename Derived::Scalar>, const Derived>\nbessel_i1(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_i1_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise i1e(\\a x) to the given\n * arrays.\n  *\n  * It returns the exponentially scaled modified Bessel\n  * function of the first kind of order one.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of i1e(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_i1e()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_i1e_op<typename Derived::Scalar>, const Derived>\nbessel_i1e(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_i1e_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise k0(\\a x) to the given\n * arrays.\n  *\n  * It returns the modified Bessel function of the second kind of order zero.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of k0(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_k0()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_k0_op<typename Derived::Scalar>, const Derived>\nbessel_k0(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_k0_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise k0e(\\a x) to the given\n * arrays.\n  *\n  * It returns the exponentially scaled modified Bessel\n  * function of the second kind of order zero.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of k0e(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_k0e()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_k0e_op<typename Derived::Scalar>, const Derived>\nbessel_k0e(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_k0e_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise k1(\\a x) to the given\n * arrays.\n  *\n  * It returns the modified Bessel function of the second kind of order one.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of k1(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_k1()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_k1_op<typename Derived::Scalar>, const Derived>\nbessel_k1(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_k1_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise k1e(\\a x) to the given\n * arrays.\n  *\n  * It returns the exponentially scaled modified Bessel\n  * function of the second kind of order one.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of k1e(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_k1e()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_k1e_op<typename Derived::Scalar>, const Derived>\nbessel_k1e(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_k1e_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise j0(\\a x) to the given\n * arrays.\n  *\n  * It returns the Bessel function of the first kind of order zero.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of j0(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_j0()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_j0_op<typename Derived::Scalar>, const Derived>\nbessel_j0(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_j0_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise y0(\\a x) to the given\n * arrays.\n  *\n  * It returns the Bessel function of the second kind of order zero.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of y0(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_y0()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_y0_op<typename Derived::Scalar>, const Derived>\nbessel_y0(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_y0_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise j1(\\a x) to the given\n * arrays.\n  *\n  * It returns the modified Bessel function of the first kind of order one.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of j1(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_j1()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_j1_op<typename Derived::Scalar>, const Derived>\nbessel_j1(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_j1_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n/** \\returns an expression of the coefficient-wise y1(\\a x) to the given\n * arrays.\n  *\n  * It returns the Bessel function of the second kind of order one.\n  *\n  * \\param x is the argument\n  *\n  * \\note This function supports only float and double scalar types. To support\n  * other scalar types, the user has to provide implementations of y1(T) for\n  * any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::bessel_y1()\n  */\ntemplate <typename Derived>\nEIGEN_STRONG_INLINE const Eigen::CwiseUnaryOp<\n    Eigen::internal::scalar_bessel_y1_op<typename Derived::Scalar>, const Derived>\nbessel_y1(const Eigen::ArrayBase<Derived>& x) {\n  return Eigen::CwiseUnaryOp<\n      Eigen::internal::scalar_bessel_y1_op<typename Derived::Scalar>,\n      const Derived>(x.derived());\n}\n\n} // end namespace Eigen\n\n#endif // EIGEN_BESSELFUNCTIONS_ARRAYAPI_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SpecialFunctions/BesselFunctionsBFloat16.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BESSELFUNCTIONS_BFLOAT16_H\n#define EIGEN_BESSELFUNCTIONS_BFLOAT16_H\n\nnamespace Eigen {\nnamespace numext {\n\n#if EIGEN_HAS_C99_MATH\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_i0(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_i0(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_i0e(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_i0e(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_i1(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_i1(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_i1e(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_i1e(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_j0(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_j0(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_j1(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_j1(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_y0(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_y0(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_y1(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_y1(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_k0(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_k0(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_k0e(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_k0e(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_k1(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_k1(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 bessel_k1e(const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::bessel_k1e(static_cast<float>(x)));\n}\n#endif\n\n}  // end namespace numext\n}  // end namespace Eigen\n\n#endif  // EIGEN_BESSELFUNCTIONS_BFLOAT16_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SpecialFunctions/BesselFunctionsFunctors.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Eugene Brevdo <ebrevdo@gmail.com>\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BESSELFUNCTIONS_FUNCTORS_H\n#define EIGEN_BESSELFUNCTIONS_FUNCTORS_H\n\nnamespace Eigen {\n\nnamespace internal {\n\n/** \\internal\n * \\brief Template functor to compute the modified Bessel function of the first\n * kind of order zero.\n * \\sa class CwiseUnaryOp, Cwise::bessel_i0()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_i0_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_i0_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_i0;\n    return bessel_i0(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_i0(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_i0_op<Scalar> > {\n  enum {\n    // On average, a Chebyshev polynomial of order N=20 is computed.\n    // The cost is N multiplications and 2N additions. We also add\n    // the cost of an additional exp over i0e.\n    Cost = 28 * NumTraits<Scalar>::MulCost + 48 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the exponentially scaled modified Bessel\n * function of the first kind of order zero\n * \\sa class CwiseUnaryOp, Cwise::bessel_i0e()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_i0e_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_i0e_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_i0e;\n    return bessel_i0e(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_i0e(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_i0e_op<Scalar> > {\n  enum {\n    // On average, a Chebyshev polynomial of order N=20 is computed.\n    // The cost is N multiplications and 2N additions.\n    Cost = 20 * NumTraits<Scalar>::MulCost + 40 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the modified Bessel function of the first\n * kind of order one\n * \\sa class CwiseUnaryOp, Cwise::bessel_i1()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_i1_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_i1_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_i1;\n    return bessel_i1(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_i1(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_i1_op<Scalar> > {\n  enum {\n    // On average, a Chebyshev polynomial of order N=20 is computed.\n    // The cost is N multiplications and 2N additions. We also add\n    // the cost of an additional exp over i1e.\n    Cost = 28 * NumTraits<Scalar>::MulCost + 48 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the exponentially scaled modified Bessel\n * function of the first kind of order zero\n * \\sa class CwiseUnaryOp, Cwise::bessel_i1e()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_i1e_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_i1e_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_i1e;\n    return bessel_i1e(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_i1e(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_i1e_op<Scalar> > {\n  enum {\n    // On average, a Chebyshev polynomial of order N=20 is computed.\n    // The cost is N multiplications and 2N additions.\n    Cost = 20 * NumTraits<Scalar>::MulCost + 40 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the Bessel function of the second kind of\n * order zero\n * \\sa class CwiseUnaryOp, Cwise::bessel_j0()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_j0_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_j0_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_j0;\n    return bessel_j0(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_j0(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_j0_op<Scalar> > {\n  enum {\n    // 6 polynomial of order ~N=8 is computed.\n    // The cost is N multiplications and N additions each, along with a\n    // sine, cosine and rsqrt cost.\n    Cost = 63 * NumTraits<Scalar>::MulCost + 48 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the Bessel function of the second kind of\n * order zero\n * \\sa class CwiseUnaryOp, Cwise::bessel_y0()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_y0_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_y0_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_y0;\n    return bessel_y0(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_y0(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_y0_op<Scalar> > {\n  enum {\n    // 6 polynomial of order ~N=8 is computed.\n    // The cost is N multiplications and N additions each, along with a\n    // sine, cosine, rsqrt and j0 cost.\n    Cost = 126 * NumTraits<Scalar>::MulCost + 96 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the Bessel function of the first kind of\n * order one\n * \\sa class CwiseUnaryOp, Cwise::bessel_j1()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_j1_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_j1_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_j1;\n    return bessel_j1(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_j1(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_j1_op<Scalar> > {\n  enum {\n    // 6 polynomial of order ~N=8 is computed.\n    // The cost is N multiplications and N additions each, along with a\n    // sine, cosine and rsqrt cost.\n    Cost = 63 * NumTraits<Scalar>::MulCost + 48 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the Bessel function of the second kind of\n * order one\n * \\sa class CwiseUnaryOp, Cwise::bessel_j1e()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_y1_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_y1_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_y1;\n    return bessel_y1(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_y1(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_y1_op<Scalar> > {\n  enum {\n    // 6 polynomial of order ~N=8 is computed.\n    // The cost is N multiplications and N additions each, along with a\n    // sine, cosine, rsqrt and j1 cost.\n    Cost = 126 * NumTraits<Scalar>::MulCost + 96 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the modified Bessel function of the second\n * kind of order zero\n * \\sa class CwiseUnaryOp, Cwise::bessel_k0()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_k0_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_k0_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_k0;\n    return bessel_k0(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_k0(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_k0_op<Scalar> > {\n  enum {\n    // On average, a Chebyshev polynomial of order N=10 is computed.\n    // The cost is N multiplications and 2N additions. In addition we compute\n    // i0, a log, exp and prsqrt and sin and cos.\n    Cost = 68 * NumTraits<Scalar>::MulCost + 88 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the exponentially scaled modified Bessel\n * function of the second kind of order zero\n * \\sa class CwiseUnaryOp, Cwise::bessel_k0e()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_k0e_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_k0e_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_k0e;\n    return bessel_k0e(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_k0e(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_k0e_op<Scalar> > {\n  enum {\n    // On average, a Chebyshev polynomial of order N=10 is computed.\n    // The cost is N multiplications and 2N additions. In addition we compute\n    // i0, a log, exp and prsqrt and sin and cos.\n    Cost = 68 * NumTraits<Scalar>::MulCost + 88 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the modified Bessel function of the\n * second kind of order one\n * \\sa class CwiseUnaryOp, Cwise::bessel_k1()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_k1_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_k1_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_k1;\n    return bessel_k1(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_k1(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_k1_op<Scalar> > {\n  enum {\n    // On average, a Chebyshev polynomial of order N=10 is computed.\n    // The cost is N multiplications and 2N additions. In addition we compute\n    // i1, a log, exp and prsqrt and sin and cos.\n    Cost = 68 * NumTraits<Scalar>::MulCost + 88 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the exponentially scaled modified Bessel\n * function of the second kind of order one\n * \\sa class CwiseUnaryOp, Cwise::bessel_k1e()\n */\ntemplate <typename Scalar>\nstruct scalar_bessel_k1e_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_bessel_k1e_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& x) const {\n    using numext::bessel_k1e;\n    return bessel_k1e(x);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return internal::pbessel_k1e(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_bessel_k1e_op<Scalar> > {\n  enum {\n    // On average, a Chebyshev polynomial of order N=10 is computed.\n    // The cost is N multiplications and 2N additions. In addition we compute\n    // i1, a log, exp and prsqrt and sin and cos.\n    Cost = 68 * NumTraits<Scalar>::MulCost + 88 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBessel\n  };\n};\n\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_BESSELFUNCTIONS_FUNCTORS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SpecialFunctions/BesselFunctionsHalf.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BESSELFUNCTIONS_HALF_H\n#define EIGEN_BESSELFUNCTIONS_HALF_H\n\nnamespace Eigen {\nnamespace numext {\n\n#if EIGEN_HAS_C99_MATH\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_i0(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_i0(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_i0e(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_i0e(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_i1(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_i1(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_i1e(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_i1e(static_cast<float>(x)));\n}\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_j0(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_j0(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_j1(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_j1(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_y0(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_y0(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_y1(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_y1(static_cast<float>(x)));\n}\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_k0(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_k0(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_k0e(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_k0e(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_k1(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_k1(static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half bessel_k1e(const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::bessel_k1e(static_cast<float>(x)));\n}\n#endif\n\n}  // end namespace numext\n}  // end namespace Eigen\n\n#endif  // EIGEN_BESSELFUNCTIONS_HALF_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SpecialFunctions/BesselFunctionsImpl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Eugene Brevdo <ebrevdo@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BESSEL_FUNCTIONS_H\n#define EIGEN_BESSEL_FUNCTIONS_H\n\nnamespace Eigen {\nnamespace internal {\n\n//  Parts of this code are based on the Cephes Math Library.\n//\n//  Cephes Math Library Release 2.8:  June, 2000\n//  Copyright 1984, 1987, 1992, 2000 by Stephen L. Moshier\n//\n//  Permission has been kindly provided by the original author\n//  to incorporate the Cephes software into the Eigen codebase:\n//\n//    From: Stephen Moshier\n//    To: Eugene Brevdo\n//    Subject: Re: Permission to wrap several cephes functions in Eigen\n//\n//    Hello Eugene,\n//\n//    Thank you for writing.\n//\n//    If your licensing is similar to BSD, the formal way that has been\n//    handled is simply to add a statement to the effect that you are incorporating\n//    the Cephes software by permission of the author.\n//\n//    Good luck with your project,\n//    Steve\n\n\n/****************************************************************************\n * Implementation of Bessel function, based on Cephes                       *\n ****************************************************************************/\n\ntemplate <typename Scalar>\nstruct bessel_i0e_retval {\n  typedef Scalar type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_i0e {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T&) {\n    EIGEN_STATIC_ASSERT((internal::is_same<T, T>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return ScalarType(0);\n  }\n};\n\ntemplate <typename T>\nstruct generic_i0e<T, float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  i0ef.c\n     *\n     *  Modified Bessel function of order zero,\n     *  exponentially scaled\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float x, y, i0ef();\n     *\n     * y = i0ef( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns exponentially scaled modified Bessel function\n     * of order zero of the argument.\n     *\n     * The function is defined as i0e(x) = exp(-|x|) j0( ix ).\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0,30        100000      3.7e-7      7.0e-8\n     * See i0f().\n     *\n     */\n\n    const float A[] = {-1.30002500998624804212E-8f, 6.04699502254191894932E-8f,\n                       -2.67079385394061173391E-7f, 1.11738753912010371815E-6f,\n                       -4.41673835845875056359E-6f, 1.64484480707288970893E-5f,\n                       -5.75419501008210370398E-5f, 1.88502885095841655729E-4f,\n                       -5.76375574538582365885E-4f, 1.63947561694133579842E-3f,\n                       -4.32430999505057594430E-3f, 1.05464603945949983183E-2f,\n                       -2.37374148058994688156E-2f, 4.93052842396707084878E-2f,\n                       -9.49010970480476444210E-2f, 1.71620901522208775349E-1f,\n                       -3.04682672343198398683E-1f, 6.76795274409476084995E-1f};\n\n    const float B[] = {3.39623202570838634515E-9f, 2.26666899049817806459E-8f,\n                       2.04891858946906374183E-7f, 2.89137052083475648297E-6f,\n                       6.88975834691682398426E-5f, 3.36911647825569408990E-3f,\n                       8.04490411014108831608E-1f};\n    T y = pabs(x);\n    T y_le_eight = internal::pchebevl<T, 18>::run(\n        pmadd(pset1<T>(0.5f), y, pset1<T>(-2.0f)), A);\n    T y_gt_eight = pmul(\n        internal::pchebevl<T, 7>::run(\n            psub(pdiv(pset1<T>(32.0f), y), pset1<T>(2.0f)), B),\n        prsqrt(y));\n    // TODO: Perhaps instead check whether all packet elements are in\n    // [-8, 8] and evaluate a branch based off of that. It's possible\n    // in practice most elements are in this region.\n    return pselect(pcmp_le(y, pset1<T>(8.0f)), y_le_eight, y_gt_eight);\n  }\n};\n\ntemplate <typename T>\nstruct generic_i0e<T, double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  i0e.c\n     *\n     *  Modified Bessel function of order zero,\n     *  exponentially scaled\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, i0e();\n     *\n     * y = i0e( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns exponentially scaled modified Bessel function\n     * of order zero of the argument.\n     *\n     * The function is defined as i0e(x) = exp(-|x|) j0( ix ).\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0,30        30000       5.4e-16     1.2e-16\n     * See i0().\n     *\n     */\n\n    const double A[] = {-4.41534164647933937950E-18, 3.33079451882223809783E-17,\n                        -2.43127984654795469359E-16, 1.71539128555513303061E-15,\n                        -1.16853328779934516808E-14, 7.67618549860493561688E-14,\n                        -4.85644678311192946090E-13, 2.95505266312963983461E-12,\n                        -1.72682629144155570723E-11, 9.67580903537323691224E-11,\n                        -5.18979560163526290666E-10, 2.65982372468238665035E-9,\n                        -1.30002500998624804212E-8,  6.04699502254191894932E-8,\n                        -2.67079385394061173391E-7,  1.11738753912010371815E-6,\n                        -4.41673835845875056359E-6,  1.64484480707288970893E-5,\n                        -5.75419501008210370398E-5,  1.88502885095841655729E-4,\n                        -5.76375574538582365885E-4,  1.63947561694133579842E-3,\n                        -4.32430999505057594430E-3,  1.05464603945949983183E-2,\n                        -2.37374148058994688156E-2,  4.93052842396707084878E-2,\n                        -9.49010970480476444210E-2,  1.71620901522208775349E-1,\n                        -3.04682672343198398683E-1,  6.76795274409476084995E-1};\n    const double B[] = {\n        -7.23318048787475395456E-18, -4.83050448594418207126E-18,\n        4.46562142029675999901E-17,  3.46122286769746109310E-17,\n        -2.82762398051658348494E-16, -3.42548561967721913462E-16,\n        1.77256013305652638360E-15,  3.81168066935262242075E-15,\n        -9.55484669882830764870E-15, -4.15056934728722208663E-14,\n        1.54008621752140982691E-14,  3.85277838274214270114E-13,\n        7.18012445138366623367E-13,  -1.79417853150680611778E-12,\n        -1.32158118404477131188E-11, -3.14991652796324136454E-11,\n        1.18891471078464383424E-11,  4.94060238822496958910E-10,\n        3.39623202570838634515E-9,   2.26666899049817806459E-8,\n        2.04891858946906374183E-7,   2.89137052083475648297E-6,\n        6.88975834691682398426E-5,   3.36911647825569408990E-3,\n        8.04490411014108831608E-1};\n    T y = pabs(x);\n    T y_le_eight = internal::pchebevl<T, 30>::run(\n        pmadd(pset1<T>(0.5), y, pset1<T>(-2.0)), A);\n    T y_gt_eight = pmul(\n        internal::pchebevl<T, 25>::run(\n            psub(pdiv(pset1<T>(32.0), y), pset1<T>(2.0)), B),\n        prsqrt(y));\n    // TODO: Perhaps instead check whether all packet elements are in\n    // [-8, 8] and evaluate a branch based off of that. It's possible\n    // in practice most elements are in this region.\n    return pselect(pcmp_le(y, pset1<T>(8.0)), y_le_eight, y_gt_eight);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_i0e_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_i0e<T>::run(x);\n  }\n};\n\ntemplate <typename Scalar>\nstruct bessel_i0_retval {\n  typedef Scalar type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_i0 {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    return pmul(\n        pexp(pabs(x)),\n        generic_i0e<T, ScalarType>::run(x));\n  }\n};\n\ntemplate <typename T>\nstruct bessel_i0_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_i0<T>::run(x);\n  }\n};\n\ntemplate <typename Scalar>\nstruct bessel_i1e_retval {\n  typedef Scalar type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type >\nstruct generic_i1e {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T&) {\n    EIGEN_STATIC_ASSERT((internal::is_same<T, T>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return ScalarType(0);\n  }\n};\n\ntemplate <typename T>\nstruct generic_i1e<T, float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /* i1ef.c\n     *\n     *  Modified Bessel function of order one,\n     *  exponentially scaled\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float x, y, i1ef();\n     *\n     * y = i1ef( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns exponentially scaled modified Bessel function\n     * of order one of the argument.\n     *\n     * The function is defined as i1(x) = -i exp(-|x|) j1( ix ).\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 30       30000       1.5e-6      1.5e-7\n     * See i1().\n     *\n     */\n    const float A[] = {9.38153738649577178388E-9f, -4.44505912879632808065E-8f,\n                       2.00329475355213526229E-7f, -8.56872026469545474066E-7f,\n                       3.47025130813767847674E-6f, -1.32731636560394358279E-5f,\n                       4.78156510755005422638E-5f, -1.61760815825896745588E-4f,\n                       5.12285956168575772895E-4f, -1.51357245063125314899E-3f,\n                       4.15642294431288815669E-3f, -1.05640848946261981558E-2f,\n                       2.47264490306265168283E-2f, -5.29459812080949914269E-2f,\n                       1.02643658689847095384E-1f, -1.76416518357834055153E-1f,\n                       2.52587186443633654823E-1f};\n\n    const float B[] = {-3.83538038596423702205E-9f, -2.63146884688951950684E-8f,\n                       -2.51223623787020892529E-7f, -3.88256480887769039346E-6f,\n                       -1.10588938762623716291E-4f, -9.76109749136146840777E-3f,\n                       7.78576235018280120474E-1f};\n\n\n    T y = pabs(x);\n    T y_le_eight = pmul(y, internal::pchebevl<T, 17>::run(\n        pmadd(pset1<T>(0.5f), y, pset1<T>(-2.0f)), A));\n    T y_gt_eight = pmul(\n        internal::pchebevl<T, 7>::run(\n            psub(pdiv(pset1<T>(32.0f), y),\n                 pset1<T>(2.0f)), B),\n        prsqrt(y));\n    // TODO: Perhaps instead check whether all packet elements are in\n    // [-8, 8] and evaluate a branch based off of that. It's possible\n    // in practice most elements are in this region.\n    y = pselect(pcmp_le(y, pset1<T>(8.0f)), y_le_eight, y_gt_eight);\n    return pselect(pcmp_lt(x, pset1<T>(0.0f)), pnegate(y), y);\n  }\n};\n\ntemplate <typename T>\nstruct generic_i1e<T, double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  i1e.c\n     *\n     *  Modified Bessel function of order one,\n     *  exponentially scaled\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, i1e();\n     *\n     * y = i1e( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns exponentially scaled modified Bessel function\n     * of order one of the argument.\n     *\n     * The function is defined as i1(x) = -i exp(-|x|) j1( ix ).\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 30       30000       2.0e-15     2.0e-16\n     * See i1().\n     *\n     */\n    const double A[] = {2.77791411276104639959E-18, -2.11142121435816608115E-17,\n                        1.55363195773620046921E-16, -1.10559694773538630805E-15,\n                        7.60068429473540693410E-15, -5.04218550472791168711E-14,\n                        3.22379336594557470981E-13, -1.98397439776494371520E-12,\n                        1.17361862988909016308E-11, -6.66348972350202774223E-11,\n                        3.62559028155211703701E-10, -1.88724975172282928790E-9,\n                        9.38153738649577178388E-9,  -4.44505912879632808065E-8,\n                        2.00329475355213526229E-7,  -8.56872026469545474066E-7,\n                        3.47025130813767847674E-6,  -1.32731636560394358279E-5,\n                        4.78156510755005422638E-5,  -1.61760815825896745588E-4,\n                        5.12285956168575772895E-4,  -1.51357245063125314899E-3,\n                        4.15642294431288815669E-3,  -1.05640848946261981558E-2,\n                        2.47264490306265168283E-2,  -5.29459812080949914269E-2,\n                        1.02643658689847095384E-1,  -1.76416518357834055153E-1,\n                        2.52587186443633654823E-1};\n    const double B[] = {\n        7.51729631084210481353E-18,  4.41434832307170791151E-18,\n        -4.65030536848935832153E-17, -3.20952592199342395980E-17,\n        2.96262899764595013876E-16,  3.30820231092092828324E-16,\n        -1.88035477551078244854E-15, -3.81440307243700780478E-15,\n        1.04202769841288027642E-14,  4.27244001671195135429E-14,\n        -2.10154184277266431302E-14, -4.08355111109219731823E-13,\n        -7.19855177624590851209E-13, 2.03562854414708950722E-12,\n        1.41258074366137813316E-11,  3.25260358301548823856E-11,\n        -1.89749581235054123450E-11, -5.58974346219658380687E-10,\n        -3.83538038596423702205E-9,  -2.63146884688951950684E-8,\n        -2.51223623787020892529E-7,  -3.88256480887769039346E-6,\n        -1.10588938762623716291E-4,  -9.76109749136146840777E-3,\n        7.78576235018280120474E-1};\n    T y = pabs(x);\n    T y_le_eight = pmul(y, internal::pchebevl<T, 29>::run(\n        pmadd(pset1<T>(0.5), y, pset1<T>(-2.0)), A));\n    T y_gt_eight = pmul(\n        internal::pchebevl<T, 25>::run(\n            psub(pdiv(pset1<T>(32.0), y),\n                 pset1<T>(2.0)), B),\n        prsqrt(y));\n    // TODO: Perhaps instead check whether all packet elements are in\n    // [-8, 8] and evaluate a branch based off of that. It's possible\n    // in practice most elements are in this region.\n    y = pselect(pcmp_le(y, pset1<T>(8.0)), y_le_eight, y_gt_eight);\n    return pselect(pcmp_lt(x, pset1<T>(0.0)), pnegate(y), y);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_i1e_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_i1e<T>::run(x);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_i1_retval {\n  typedef T type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_i1 {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    return pmul(\n        pexp(pabs(x)),\n        generic_i1e<T, ScalarType>::run(x));\n  }\n};\n\ntemplate <typename T>\nstruct bessel_i1_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_i1<T>::run(x);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_k0e_retval {\n  typedef T type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_k0e {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T&) {\n    EIGEN_STATIC_ASSERT((internal::is_same<T, T>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return ScalarType(0);\n  }\n};\n\ntemplate <typename T>\nstruct generic_k0e<T, float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  k0ef.c\n     *\tModified Bessel function, third kind, order zero,\n     *\texponentially scaled\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float x, y, k0ef();\n     *\n     * y = k0ef( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns exponentially scaled modified Bessel function\n     * of the third kind of order zero of the argument.\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 30       30000       8.1e-7      7.8e-8\n     * See k0().\n     *\n     */\n\n    const float A[] = {1.90451637722020886025E-9f, 2.53479107902614945675E-7f,\n                       2.28621210311945178607E-5f, 1.26461541144692592338E-3f,\n                       3.59799365153615016266E-2f, 3.44289899924628486886E-1f,\n                       -5.35327393233902768720E-1f};\n\n    const float B[] = {-1.69753450938905987466E-9f, 8.57403401741422608519E-9f,\n                       -4.66048989768794782956E-8f, 2.76681363944501510342E-7f,\n                       -1.83175552271911948767E-6f, 1.39498137188764993662E-5f,\n                       -1.28495495816278026384E-4f, 1.56988388573005337491E-3f,\n                       -3.14481013119645005427E-2f, 2.44030308206595545468E0f};\n    const T MAXNUM = pset1<T>(NumTraits<float>::infinity());\n    const T two = pset1<T>(2.0);\n    T x_le_two = internal::pchebevl<T, 7>::run(\n        pmadd(x, x, pset1<T>(-2.0)), A);\n    x_le_two = pmadd(\n        generic_i0<T, float>::run(x), pnegate(\n            plog(pmul(pset1<T>(0.5), x))), x_le_two);\n    x_le_two = pmul(pexp(x), x_le_two);\n    T x_gt_two = pmul(\n            internal::pchebevl<T, 10>::run(\n                psub(pdiv(pset1<T>(8.0), x), two), B),\n            prsqrt(x));\n    return pselect(\n        pcmp_le(x, pset1<T>(0.0)),\n        MAXNUM,\n        pselect(pcmp_le(x, two), x_le_two, x_gt_two));\n  }\n};\n\ntemplate <typename T>\nstruct generic_k0e<T, double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  k0e.c\n     *\tModified Bessel function, third kind, order zero,\n     *\texponentially scaled\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, k0e();\n     *\n     * y = k0e( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns exponentially scaled modified Bessel function\n     * of the third kind of order zero of the argument.\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 30       30000       1.4e-15     1.4e-16\n     * See k0().\n     *\n     */\n\n    const double A[] = {\n      1.37446543561352307156E-16,\n      4.25981614279661018399E-14,\n      1.03496952576338420167E-11,\n      1.90451637722020886025E-9,\n      2.53479107902614945675E-7,\n      2.28621210311945178607E-5,\n      1.26461541144692592338E-3,\n      3.59799365153615016266E-2,\n      3.44289899924628486886E-1,\n      -5.35327393233902768720E-1};\n    const double B[] = {\n       5.30043377268626276149E-18, -1.64758043015242134646E-17,\n       5.21039150503902756861E-17, -1.67823109680541210385E-16,\n       5.51205597852431940784E-16, -1.84859337734377901440E-15,\n       6.34007647740507060557E-15, -2.22751332699166985548E-14,\n       8.03289077536357521100E-14, -2.98009692317273043925E-13,\n       1.14034058820847496303E-12, -4.51459788337394416547E-12,\n       1.85594911495471785253E-11, -7.95748924447710747776E-11,\n       3.57739728140030116597E-10, -1.69753450938905987466E-9,\n       8.57403401741422608519E-9, -4.66048989768794782956E-8,\n       2.76681363944501510342E-7, -1.83175552271911948767E-6,\n       1.39498137188764993662E-5, -1.28495495816278026384E-4,\n       1.56988388573005337491E-3, -3.14481013119645005427E-2,\n       2.44030308206595545468E0\n    };\n    const T MAXNUM = pset1<T>(NumTraits<double>::infinity());\n    const T two = pset1<T>(2.0);\n    T x_le_two = internal::pchebevl<T, 10>::run(\n        pmadd(x, x, pset1<T>(-2.0)), A);\n    x_le_two = pmadd(\n        generic_i0<T, double>::run(x), pmul(\n            pset1<T>(-1.0), plog(pmul(pset1<T>(0.5), x))), x_le_two);\n    x_le_two = pmul(pexp(x), x_le_two);\n    x_le_two = pselect(pcmp_le(x, pset1<T>(0.0)), MAXNUM, x_le_two);\n    T x_gt_two = pmul(\n            internal::pchebevl<T, 25>::run(\n                psub(pdiv(pset1<T>(8.0), x), two), B),\n            prsqrt(x));\n    return pselect(pcmp_le(x, two), x_le_two, x_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_k0e_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_k0e<T>::run(x);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_k0_retval {\n  typedef T type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_k0 {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T&) {\n    EIGEN_STATIC_ASSERT((internal::is_same<T, T>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return ScalarType(0);\n  }\n};\n\ntemplate <typename T>\nstruct generic_k0<T, float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  k0f.c\n     *\tModified Bessel function, third kind, order zero\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float x, y, k0f();\n     *\n     * y = k0f( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns modified Bessel function of the third kind\n     * of order zero of the argument.\n     *\n     * The range is partitioned into the two intervals [0,8] and\n     * (8, infinity).  Chebyshev polynomial expansions are employed\n     * in each interval.\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     * Tested at 2000 random points between 0 and 8.  Peak absolute\n     * error (relative when K0 > 1) was 1.46e-14; rms, 4.26e-15.\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 30       30000       7.8e-7      8.5e-8\n     *\n     * ERROR MESSAGES:\n     *\n     *   message         condition      value returned\n     *  K0 domain          x <= 0          MAXNUM\n     *\n     */\n\n    const float A[] = {1.90451637722020886025E-9f, 2.53479107902614945675E-7f,\n                       2.28621210311945178607E-5f, 1.26461541144692592338E-3f,\n                       3.59799365153615016266E-2f, 3.44289899924628486886E-1f,\n                       -5.35327393233902768720E-1f};\n\n    const float B[] = {-1.69753450938905987466E-9f, 8.57403401741422608519E-9f,\n                       -4.66048989768794782956E-8f, 2.76681363944501510342E-7f,\n                       -1.83175552271911948767E-6f, 1.39498137188764993662E-5f,\n                       -1.28495495816278026384E-4f, 1.56988388573005337491E-3f,\n                       -3.14481013119645005427E-2f, 2.44030308206595545468E0f};\n    const T MAXNUM = pset1<T>(NumTraits<float>::infinity());\n    const T two = pset1<T>(2.0);\n    T x_le_two = internal::pchebevl<T, 7>::run(\n        pmadd(x, x, pset1<T>(-2.0)), A);\n    x_le_two = pmadd(\n        generic_i0<T, float>::run(x), pnegate(\n            plog(pmul(pset1<T>(0.5), x))), x_le_two);\n    x_le_two = pselect(pcmp_le(x, pset1<T>(0.0)), MAXNUM, x_le_two);\n    T x_gt_two = pmul(\n        pmul(\n            pexp(pnegate(x)),\n            internal::pchebevl<T, 10>::run(\n                psub(pdiv(pset1<T>(8.0), x), two), B)),\n        prsqrt(x));\n    return pselect(pcmp_le(x, two), x_le_two, x_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct generic_k0<T, double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*\n     *\n     *\tModified Bessel function, third kind, order zero,\n     *\texponentially scaled\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, k0();\n     *\n     * y = k0( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns exponentially scaled modified Bessel function\n     * of the third kind of order zero of the argument.\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 30       30000       1.4e-15     1.4e-16\n     * See k0().\n     *\n     */\n    const double A[] = {\n      1.37446543561352307156E-16,\n      4.25981614279661018399E-14,\n      1.03496952576338420167E-11,\n      1.90451637722020886025E-9,\n      2.53479107902614945675E-7,\n      2.28621210311945178607E-5,\n      1.26461541144692592338E-3,\n      3.59799365153615016266E-2,\n      3.44289899924628486886E-1,\n      -5.35327393233902768720E-1};\n    const double B[] = {\n       5.30043377268626276149E-18, -1.64758043015242134646E-17,\n       5.21039150503902756861E-17, -1.67823109680541210385E-16,\n       5.51205597852431940784E-16, -1.84859337734377901440E-15,\n       6.34007647740507060557E-15, -2.22751332699166985548E-14,\n       8.03289077536357521100E-14, -2.98009692317273043925E-13,\n       1.14034058820847496303E-12, -4.51459788337394416547E-12,\n       1.85594911495471785253E-11, -7.95748924447710747776E-11,\n       3.57739728140030116597E-10, -1.69753450938905987466E-9,\n       8.57403401741422608519E-9, -4.66048989768794782956E-8,\n       2.76681363944501510342E-7, -1.83175552271911948767E-6,\n       1.39498137188764993662E-5, -1.28495495816278026384E-4,\n       1.56988388573005337491E-3, -3.14481013119645005427E-2,\n       2.44030308206595545468E0\n    };\n    const T MAXNUM = pset1<T>(NumTraits<double>::infinity());\n    const T two = pset1<T>(2.0);\n    T x_le_two = internal::pchebevl<T, 10>::run(\n        pmadd(x, x, pset1<T>(-2.0)), A);\n    x_le_two = pmadd(\n        generic_i0<T, double>::run(x), pnegate(\n            plog(pmul(pset1<T>(0.5), x))), x_le_two);\n    x_le_two = pselect(pcmp_le(x, pset1<T>(0.0)), MAXNUM, x_le_two);\n    T x_gt_two = pmul(\n        pmul(\n            pexp(-x),\n            internal::pchebevl<T, 25>::run(\n                psub(pdiv(pset1<T>(8.0), x), two), B)),\n        prsqrt(x));\n    return pselect(pcmp_le(x, two), x_le_two, x_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_k0_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_k0<T>::run(x);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_k1e_retval {\n  typedef T type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_k1e {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T&) {\n    EIGEN_STATIC_ASSERT((internal::is_same<T, T>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return ScalarType(0);\n  }\n};\n\ntemplate <typename T>\nstruct generic_k1e<T, float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /* k1ef.c\n     *\n     *\tModified Bessel function, third kind, order one,\n     *\texponentially scaled\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float x, y, k1ef();\n     *\n     * y = k1ef( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns exponentially scaled modified Bessel function\n     * of the third kind of order one of the argument:\n     *\n     *      k1e(x) = exp(x) * k1(x).\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 30       30000       4.9e-7      6.7e-8\n     * See k1().\n     *\n     */\n\n    const float A[] = {-2.21338763073472585583E-8f, -2.43340614156596823496E-6f,\n                        -1.73028895751305206302E-4f, -6.97572385963986435018E-3f,\n                        -1.22611180822657148235E-1f, -3.53155960776544875667E-1f,\n                        1.52530022733894777053E0f};\n    const float B[] = {2.01504975519703286596E-9f, -1.03457624656780970260E-8f,\n                       5.74108412545004946722E-8f, -3.50196060308781257119E-7f,\n                       2.40648494783721712015E-6f, -1.93619797416608296024E-5f,\n                       1.95215518471351631108E-4f, -2.85781685962277938680E-3f,\n                       1.03923736576817238437E-1f, 2.72062619048444266945E0f};\n    const T MAXNUM = pset1<T>(NumTraits<float>::infinity());\n    const T two = pset1<T>(2.0);\n    T x_le_two = pdiv(internal::pchebevl<T, 7>::run(\n        pmadd(x, x, pset1<T>(-2.0)), A), x);\n    x_le_two = pmadd(\n        generic_i1<T, float>::run(x), plog(pmul(pset1<T>(0.5), x)), x_le_two);\n    x_le_two = pmul(x_le_two, pexp(x));\n    x_le_two = pselect(pcmp_le(x, pset1<T>(0.0)), MAXNUM, x_le_two);\n    T x_gt_two = pmul(\n        internal::pchebevl<T, 10>::run(\n            psub(pdiv(pset1<T>(8.0), x), two), B),\n        prsqrt(x));\n    return pselect(pcmp_le(x, two), x_le_two, x_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct generic_k1e<T, double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  k1e.c\n     *\n     *\tModified Bessel function, third kind, order one,\n     *\texponentially scaled\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, k1e();\n     *\n     * y = k1e( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns exponentially scaled modified Bessel function\n     * of the third kind of order one of the argument:\n     *\n     *      k1e(x) = exp(x) * k1(x).\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 30       30000       7.8e-16     1.2e-16\n     * See k1().\n     *\n     */\n    const double A[] = {-7.02386347938628759343E-18, -2.42744985051936593393E-15,\n                        -6.66690169419932900609E-13, -1.41148839263352776110E-10,\n                        -2.21338763073472585583E-8, -2.43340614156596823496E-6,\n                        -1.73028895751305206302E-4, -6.97572385963986435018E-3,\n                        -1.22611180822657148235E-1, -3.53155960776544875667E-1,\n                        1.52530022733894777053E0};\n    const double B[] = {-5.75674448366501715755E-18, 1.79405087314755922667E-17,\n                        -5.68946255844285935196E-17, 1.83809354436663880070E-16,\n                        -6.05704724837331885336E-16, 2.03870316562433424052E-15,\n                        -7.01983709041831346144E-15, 2.47715442448130437068E-14,\n                        -8.97670518232499435011E-14, 3.34841966607842919884E-13,\n                        -1.28917396095102890680E-12, 5.13963967348173025100E-12,\n                        -2.12996783842756842877E-11, 9.21831518760500529508E-11,\n                        -4.19035475934189648750E-10, 2.01504975519703286596E-9,\n                        -1.03457624656780970260E-8, 5.74108412545004946722E-8,\n                        -3.50196060308781257119E-7, 2.40648494783721712015E-6,\n                        -1.93619797416608296024E-5, 1.95215518471351631108E-4,\n                        -2.85781685962277938680E-3, 1.03923736576817238437E-1,\n                        2.72062619048444266945E0};\n    const T MAXNUM = pset1<T>(NumTraits<double>::infinity());\n    const T two = pset1<T>(2.0);\n    T x_le_two = pdiv(internal::pchebevl<T, 11>::run(\n        pmadd(x, x, pset1<T>(-2.0)), A), x);\n    x_le_two = pmadd(\n        generic_i1<T, double>::run(x), plog(pmul(pset1<T>(0.5), x)), x_le_two);\n    x_le_two = pmul(x_le_two, pexp(x));\n    x_le_two = pselect(pcmp_le(x, pset1<T>(0.0)), MAXNUM, x_le_two);\n    T x_gt_two = pmul(\n        internal::pchebevl<T, 25>::run(\n            psub(pdiv(pset1<T>(8.0), x), two), B),\n        prsqrt(x));\n    return pselect(pcmp_le(x, two), x_le_two, x_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_k1e_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_k1e<T>::run(x);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_k1_retval {\n  typedef T type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_k1 {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T&) {\n    EIGEN_STATIC_ASSERT((internal::is_same<T, T>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return ScalarType(0);\n  }\n};\n\ntemplate <typename T>\nstruct generic_k1<T, float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /* k1f.c\n     *\tModified Bessel function, third kind, order one\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float x, y, k1f();\n     *\n     * y = k1f( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Computes the modified Bessel function of the third kind\n     * of order one of the argument.\n     *\n     * The range is partitioned into the two intervals [0,2] and\n     * (2, infinity).  Chebyshev polynomial expansions are employed\n     * in each interval.\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 30       30000       4.6e-7      7.6e-8\n     *\n     * ERROR MESSAGES:\n     *\n     *   message         condition      value returned\n     * k1 domain          x <= 0          MAXNUM\n     *\n     */\n\n    const float A[] = {-2.21338763073472585583E-8f, -2.43340614156596823496E-6f,\n                        -1.73028895751305206302E-4f, -6.97572385963986435018E-3f,\n                        -1.22611180822657148235E-1f, -3.53155960776544875667E-1f,\n                        1.52530022733894777053E0f};\n    const float B[] = {2.01504975519703286596E-9f, -1.03457624656780970260E-8f,\n                       5.74108412545004946722E-8f, -3.50196060308781257119E-7f,\n                       2.40648494783721712015E-6f, -1.93619797416608296024E-5f,\n                       1.95215518471351631108E-4f, -2.85781685962277938680E-3f,\n                       1.03923736576817238437E-1f, 2.72062619048444266945E0f};\n    const T MAXNUM = pset1<T>(NumTraits<float>::infinity());\n    const T two = pset1<T>(2.0);\n    T x_le_two = pdiv(internal::pchebevl<T, 7>::run(\n        pmadd(x, x, pset1<T>(-2.0)), A), x);\n    x_le_two = pmadd(\n        generic_i1<T, float>::run(x), plog(pmul(pset1<T>(0.5), x)), x_le_two);\n    x_le_two = pselect(pcmp_le(x, pset1<T>(0.0)), MAXNUM, x_le_two);\n    T x_gt_two = pmul(\n        pexp(pnegate(x)),\n        pmul(\n            internal::pchebevl<T, 10>::run(\n                psub(pdiv(pset1<T>(8.0), x), two), B),\n            prsqrt(x)));\n    return pselect(pcmp_le(x, two), x_le_two, x_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct generic_k1<T, double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  k1.c\n     *\tModified Bessel function, third kind, order one\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float x, y, k1f();\n     *\n     * y = k1f( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Computes the modified Bessel function of the third kind\n     * of order one of the argument.\n     *\n     * The range is partitioned into the two intervals [0,2] and\n     * (2, infinity).  Chebyshev polynomial expansions are employed\n     * in each interval.\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 30       30000       4.6e-7      7.6e-8\n     *\n     * ERROR MESSAGES:\n     *\n     *   message         condition      value returned\n     * k1 domain          x <= 0          MAXNUM\n     *\n     */\n    const double A[] = {-7.02386347938628759343E-18, -2.42744985051936593393E-15,\n                        -6.66690169419932900609E-13, -1.41148839263352776110E-10,\n                        -2.21338763073472585583E-8, -2.43340614156596823496E-6,\n                        -1.73028895751305206302E-4, -6.97572385963986435018E-3,\n                        -1.22611180822657148235E-1, -3.53155960776544875667E-1,\n                        1.52530022733894777053E0};\n    const double B[] = {-5.75674448366501715755E-18, 1.79405087314755922667E-17,\n                        -5.68946255844285935196E-17, 1.83809354436663880070E-16,\n                        -6.05704724837331885336E-16, 2.03870316562433424052E-15,\n                        -7.01983709041831346144E-15, 2.47715442448130437068E-14,\n                        -8.97670518232499435011E-14, 3.34841966607842919884E-13,\n                        -1.28917396095102890680E-12, 5.13963967348173025100E-12,\n                        -2.12996783842756842877E-11, 9.21831518760500529508E-11,\n                        -4.19035475934189648750E-10, 2.01504975519703286596E-9,\n                        -1.03457624656780970260E-8, 5.74108412545004946722E-8,\n                        -3.50196060308781257119E-7, 2.40648494783721712015E-6,\n                        -1.93619797416608296024E-5, 1.95215518471351631108E-4,\n                        -2.85781685962277938680E-3, 1.03923736576817238437E-1,\n                        2.72062619048444266945E0};\n    const T MAXNUM = pset1<T>(NumTraits<double>::infinity());\n    const T two = pset1<T>(2.0);\n    T x_le_two = pdiv(internal::pchebevl<T, 11>::run(\n        pmadd(x, x, pset1<T>(-2.0)), A), x);\n    x_le_two = pmadd(\n        generic_i1<T, double>::run(x), plog(pmul(pset1<T>(0.5), x)), x_le_two);\n    x_le_two = pselect(pcmp_le(x, pset1<T>(0.0)), MAXNUM, x_le_two);\n    T x_gt_two = pmul(\n        pexp(-x),\n        pmul(\n            internal::pchebevl<T, 25>::run(\n                psub(pdiv(pset1<T>(8.0), x), two), B),\n            prsqrt(x)));\n    return pselect(pcmp_le(x, two), x_le_two, x_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_k1_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_k1<T>::run(x);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_j0_retval {\n  typedef T type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_j0 {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T&) {\n    EIGEN_STATIC_ASSERT((internal::is_same<T, T>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return ScalarType(0);\n  }\n};\n\ntemplate <typename T>\nstruct generic_j0<T, float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /* j0f.c\n     *\tBessel function of order zero\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float x, y, j0f();\n     *\n     * y = j0f( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns Bessel function of order zero of the argument.\n     *\n     * The domain is divided into the intervals [0, 2] and\n     * (2, infinity). In the first interval the following polynomial\n     * approximation is used:\n     *\n     *\n     *        2         2         2\n     * (w - r  ) (w - r  ) (w - r  ) P(w)\n     *       1         2         3\n     *\n     *            2\n     * where w = x  and the three r's are zeros of the function.\n     *\n     * In the second interval, the modulus and phase are approximated\n     * by polynomials of the form Modulus(x) = sqrt(1/x) Q(1/x)\n     * and Phase(x) = x + 1/x R(1/x^2) - pi/4.  The function is\n     *\n     *   j0(x) = Modulus(x) cos( Phase(x) ).\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Absolute error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0, 2        100000      1.3e-7      3.6e-8\n     *    IEEE      2, 32       100000      1.9e-7      5.4e-8\n     *\n     */\n\n    const float JP[] = {-6.068350350393235E-008f, 6.388945720783375E-006f,\n                        -3.969646342510940E-004f, 1.332913422519003E-002f,\n                        -1.729150680240724E-001f};\n    const float MO[] = {-6.838999669318810E-002f, 1.864949361379502E-001f,\n                        -2.145007480346739E-001f, 1.197549369473540E-001f,\n                        -3.560281861530129E-003f, -4.969382655296620E-002f,\n                        -3.355424622293709E-006f, 7.978845717621440E-001f};\n    const float PH[] = {3.242077816988247E+001f, -3.630592630518434E+001f,\n                        1.756221482109099E+001f, -4.974978466280903E+000f,\n                        1.001973420681837E+000f, -1.939906941791308E-001f,\n                        6.490598792654666E-002f, -1.249992184872738E-001f};\n    const T DR1 =  pset1<T>(5.78318596294678452118f);\n    const T NEG_PIO4F = pset1<T>(-0.7853981633974483096f); /* -pi / 4 */\n    T y = pabs(x);\n    T z = pmul(y, y);\n    T y_le_two = pselect(\n        pcmp_lt(y, pset1<T>(1.0e-3f)),\n        pmadd(z, pset1<T>(-0.25f), pset1<T>(1.0f)),\n        pmul(psub(z, DR1), internal::ppolevl<T, 4>::run(z, JP)));\n    T q = pdiv(pset1<T>(1.0f), y);\n    T w = prsqrt(y);\n    T p = pmul(w, internal::ppolevl<T, 7>::run(q, MO));\n    w = pmul(q, q);\n    T yn = pmadd(q, internal::ppolevl<T, 7>::run(w, PH), NEG_PIO4F);\n    T y_gt_two = pmul(p, pcos(padd(yn, y)));\n    return pselect(pcmp_le(y, pset1<T>(2.0)), y_le_two, y_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct generic_j0<T, double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  j0.c\n     *\tBessel function of order zero\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, j0();\n     *\n     * y = j0( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns Bessel function of order zero of the argument.\n     *\n     * The domain is divided into the intervals [0, 5] and\n     * (5, infinity). In the first interval the following rational\n     * approximation is used:\n     *\n     *\n     *        2         2\n     * (w - r  ) (w - r  ) P (w) / Q (w)\n     *       1         2    3       8\n     *\n     *            2\n     * where w = x  and the two r's are zeros of the function.\n     *\n     * In the second interval, the Hankel asymptotic expansion\n     * is employed with two rational functions of degree 6/6\n     * and 7/7.\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Absolute error:\n     * arithmetic   domain     # trials      peak         rms\n     *    DEC       0, 30       10000       4.4e-17     6.3e-18\n     *    IEEE      0, 30       60000       4.2e-16     1.1e-16\n     *\n     */\n    const double PP[] = {7.96936729297347051624E-4, 8.28352392107440799803E-2,\n                        1.23953371646414299388E0, 5.44725003058768775090E0,\n                        8.74716500199817011941E0, 5.30324038235394892183E0,\n                        9.99999999999999997821E-1};\n    const double PQ[] = {9.24408810558863637013E-4, 8.56288474354474431428E-2,\n                         1.25352743901058953537E0, 5.47097740330417105182E0,\n                         8.76190883237069594232E0, 5.30605288235394617618E0,\n                         1.00000000000000000218E0};\n    const double QP[] = {-1.13663838898469149931E-2, -1.28252718670509318512E0,\n                         -1.95539544257735972385E1, -9.32060152123768231369E1,\n                         -1.77681167980488050595E2, -1.47077505154951170175E2,\n                         -5.14105326766599330220E1, -6.05014350600728481186E0};\n    const double QQ[] = {1.00000000000000000000E0, 6.43178256118178023184E1,\n                         8.56430025976980587198E2, 3.88240183605401609683E3,\n                         7.24046774195652478189E3, 5.93072701187316984827E3,\n                         2.06209331660327847417E3, 2.42005740240291393179E2};\n    const double RP[] = {-4.79443220978201773821E9, 1.95617491946556577543E12,\n                         -2.49248344360967716204E14, 9.70862251047306323952E15};\n    const double RQ[] = {1.00000000000000000000E0, 4.99563147152651017219E2,\n                         1.73785401676374683123E5, 4.84409658339962045305E7,\n                         1.11855537045356834862E10, 2.11277520115489217587E12,\n                         3.10518229857422583814E14, 3.18121955943204943306E16,\n                         1.71086294081043136091E18};\n    const T DR1 = pset1<T>(5.78318596294678452118E0);\n    const T DR2 = pset1<T>(3.04712623436620863991E1);\n    const T SQ2OPI = pset1<T>(7.9788456080286535587989E-1); /* sqrt(2 / pi) */\n    const T NEG_PIO4 = pset1<T>(-0.7853981633974483096); /* pi / 4 */\n\n    T y = pabs(x);\n    T z = pmul(y, y);\n    T y_le_five = pselect(\n        pcmp_lt(y, pset1<T>(1.0e-5)),\n        pmadd(z, pset1<T>(-0.25), pset1<T>(1.0)),\n        pmul(pmul(psub(z, DR1), psub(z, DR2)),\n             pdiv(internal::ppolevl<T, 3>::run(z, RP),\n                  internal::ppolevl<T, 8>::run(z, RQ))));\n    T s = pdiv(pset1<T>(25.0), z);\n    T p = pdiv(\n        internal::ppolevl<T, 6>::run(s, PP),\n        internal::ppolevl<T, 6>::run(s, PQ));\n    T q = pdiv(\n        internal::ppolevl<T, 7>::run(s, QP),\n        internal::ppolevl<T, 7>::run(s, QQ));\n    T yn = padd(y, NEG_PIO4);\n    T w = pdiv(pset1<T>(-5.0), y);\n    p = pmadd(p, pcos(yn), pmul(w, pmul(q, psin(yn))));\n    T y_gt_five = pmul(p, pmul(SQ2OPI, prsqrt(y)));\n    return pselect(pcmp_le(y, pset1<T>(5.0)), y_le_five, y_gt_five);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_j0_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_j0<T>::run(x);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_y0_retval {\n  typedef T type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_y0 {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T&) {\n    EIGEN_STATIC_ASSERT((internal::is_same<T, T>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return ScalarType(0);\n  }\n};\n\ntemplate <typename T>\nstruct generic_y0<T, float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /* j0f.c\n     * \tBessel function of the second kind, order zero\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float x, y, y0f();\n     *\n     * y = y0f( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns Bessel function of the second kind, of order\n     * zero, of the argument.\n     *\n     * The domain is divided into the intervals [0, 2] and\n     * (2, infinity). In the first interval a rational approximation\n     * R(x) is employed to compute\n     *\n     *                  2         2         2\n     * y0(x)  =  (w - r  ) (w - r  ) (w - r  ) R(x)  +  2/pi ln(x) j0(x).\n     *                 1         2         3\n     *\n     * Thus a call to j0() is required.  The three zeros are removed\n     * from R(x) to improve its numerical stability.\n     *\n     * In the second interval, the modulus and phase are approximated\n     * by polynomials of the form Modulus(x) = sqrt(1/x) Q(1/x)\n     * and Phase(x) = x + 1/x S(1/x^2) - pi/4.  Then the function is\n     *\n     *   y0(x) = Modulus(x) sin( Phase(x) ).\n     *\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *  Absolute error, when y0(x) < 1; else relative error:\n     *\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0,  2       100000      2.4e-7      3.4e-8\n     *    IEEE      2, 32       100000      1.8e-7      5.3e-8\n     *\n     */\n\n    const float YP[] = {9.454583683980369E-008f, -9.413212653797057E-006f,\n                        5.344486707214273E-004f, -1.584289289821316E-002f,\n                        1.707584643733568E-001f};\n    const float MO[] = {-6.838999669318810E-002f, 1.864949361379502E-001f,\n                        -2.145007480346739E-001f, 1.197549369473540E-001f,\n                        -3.560281861530129E-003f, -4.969382655296620E-002f,\n                        -3.355424622293709E-006f, 7.978845717621440E-001f};\n    const float PH[] = {3.242077816988247E+001f, -3.630592630518434E+001f,\n                        1.756221482109099E+001f, -4.974978466280903E+000f,\n                        1.001973420681837E+000f, -1.939906941791308E-001f,\n                        6.490598792654666E-002f, -1.249992184872738E-001f};\n    const T YZ1 = pset1<T>(0.43221455686510834878f);\n    const T TWOOPI =  pset1<T>(0.636619772367581343075535f); /* 2 / pi */\n    const T NEG_PIO4F = pset1<T>(-0.7853981633974483096f); /* -pi / 4 */\n    const T NEG_MAXNUM = pset1<T>(-NumTraits<float>::infinity());\n    T z = pmul(x, x);\n    T x_le_two = pmul(TWOOPI, pmul(plog(x), generic_j0<T, float>::run(x)));\n    x_le_two = pmadd(\n        psub(z, YZ1), internal::ppolevl<T, 4>::run(z, YP), x_le_two);\n    x_le_two = pselect(pcmp_le(x, pset1<T>(0.0)), NEG_MAXNUM, x_le_two);\n    T q = pdiv(pset1<T>(1.0), x);\n    T w = prsqrt(x);\n    T p = pmul(w, internal::ppolevl<T, 7>::run(q, MO));\n    T u = pmul(q, q);\n    T xn = pmadd(q, internal::ppolevl<T, 7>::run(u, PH), NEG_PIO4F);\n    T x_gt_two = pmul(p, psin(padd(xn, x)));\n    return pselect(pcmp_le(x, pset1<T>(2.0)), x_le_two, x_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct generic_y0<T, double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  j0.c\n     *\tBessel function of the second kind, order zero\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, y0();\n     *\n     * y = y0( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns Bessel function of the second kind, of order\n     * zero, of the argument.\n     *\n     * The domain is divided into the intervals [0, 5] and\n     * (5, infinity). In the first interval a rational approximation\n     * R(x) is employed to compute\n     *   y0(x)  = R(x)  +   2 * log(x) * j0(x) / PI.\n     * Thus a call to j0() is required.\n     *\n     * In the second interval, the Hankel asymptotic expansion\n     * is employed with two rational functions of degree 6/6\n     * and 7/7.\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *  Absolute error, when y0(x) < 1; else relative error:\n     *\n     * arithmetic   domain     # trials      peak         rms\n     *    DEC       0, 30        9400       7.0e-17     7.9e-18\n     *    IEEE      0, 30       30000       1.3e-15     1.6e-16\n     *\n     */\n    const double PP[] = {7.96936729297347051624E-4, 8.28352392107440799803E-2,\n                        1.23953371646414299388E0, 5.44725003058768775090E0,\n                        8.74716500199817011941E0, 5.30324038235394892183E0,\n                        9.99999999999999997821E-1};\n    const double PQ[] = {9.24408810558863637013E-4, 8.56288474354474431428E-2,\n                         1.25352743901058953537E0, 5.47097740330417105182E0,\n                         8.76190883237069594232E0, 5.30605288235394617618E0,\n                         1.00000000000000000218E0};\n    const double QP[] = {-1.13663838898469149931E-2, -1.28252718670509318512E0,\n                         -1.95539544257735972385E1, -9.32060152123768231369E1,\n                         -1.77681167980488050595E2, -1.47077505154951170175E2,\n                         -5.14105326766599330220E1, -6.05014350600728481186E0};\n    const double QQ[] = {1.00000000000000000000E0, 6.43178256118178023184E1,\n                         8.56430025976980587198E2, 3.88240183605401609683E3,\n                         7.24046774195652478189E3, 5.93072701187316984827E3,\n                         2.06209331660327847417E3, 2.42005740240291393179E2};\n    const double YP[] = {1.55924367855235737965E4, -1.46639295903971606143E7,\n                         5.43526477051876500413E9, -9.82136065717911466409E11,\n                         8.75906394395366999549E13, -3.46628303384729719441E15,\n                         4.42733268572569800351E16, -1.84950800436986690637E16};\n    const double YQ[] = {1.00000000000000000000E0,  1.04128353664259848412E3,\n                         6.26107330137134956842E5, 2.68919633393814121987E8,\n                         8.64002487103935000337E10, 2.02979612750105546709E13,\n                         3.17157752842975028269E15, 2.50596256172653059228E17};\n    const T SQ2OPI = pset1<T>(7.9788456080286535587989E-1); /* sqrt(2 / pi) */\n    const T TWOOPI =  pset1<T>(0.636619772367581343075535); /* 2 / pi */\n    const T NEG_PIO4 = pset1<T>(-0.7853981633974483096); /* -pi / 4 */\n    const T NEG_MAXNUM = pset1<T>(-NumTraits<double>::infinity());\n\n    T z = pmul(x, x);\n    T x_le_five = pdiv(internal::ppolevl<T, 7>::run(z, YP),\n                       internal::ppolevl<T, 7>::run(z, YQ));\n    x_le_five = pmadd(\n        pmul(TWOOPI, plog(x)), generic_j0<T, double>::run(x), x_le_five);\n    x_le_five = pselect(pcmp_le(x, pset1<T>(0.0)), NEG_MAXNUM, x_le_five);\n    T s = pdiv(pset1<T>(25.0), z);\n    T p = pdiv(\n        internal::ppolevl<T, 6>::run(s, PP),\n        internal::ppolevl<T, 6>::run(s, PQ));\n    T q = pdiv(\n        internal::ppolevl<T, 7>::run(s, QP),\n        internal::ppolevl<T, 7>::run(s, QQ));\n    T xn = padd(x, NEG_PIO4);\n    T w = pdiv(pset1<T>(5.0), x);\n    p = pmadd(p, psin(xn), pmul(w, pmul(q, pcos(xn))));\n    T x_gt_five = pmul(p, pmul(SQ2OPI, prsqrt(x)));\n    return pselect(pcmp_le(x, pset1<T>(5.0)), x_le_five, x_gt_five);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_y0_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_y0<T>::run(x);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_j1_retval {\n  typedef T type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_j1 {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T&) {\n    EIGEN_STATIC_ASSERT((internal::is_same<T, T>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return ScalarType(0);\n  }\n};\n\ntemplate <typename T>\nstruct generic_j1<T, float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /* j1f.c\n     *\tBessel function of order one\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float x, y, j1f();\n     *\n     * y = j1f( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns Bessel function of order one of the argument.\n     *\n     * The domain is divided into the intervals [0, 2] and\n     * (2, infinity). In the first interval a polynomial approximation\n     *        2\n     * (w - r  ) x P(w)\n     *       1\n     *                     2\n     * is used, where w = x  and r is the first zero of the function.\n     *\n     * In the second interval, the modulus and phase are approximated\n     * by polynomials of the form Modulus(x) = sqrt(1/x) Q(1/x)\n     * and Phase(x) = x + 1/x R(1/x^2) - 3pi/4.  The function is\n     *\n     *   j0(x) = Modulus(x) cos( Phase(x) ).\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Absolute error:\n     * arithmetic   domain      # trials      peak       rms\n     *    IEEE      0,  2       100000       1.2e-7     2.5e-8\n     *    IEEE      2, 32       100000       2.0e-7     5.3e-8\n     *\n     *\n     */\n\n    const float JP[] = {-4.878788132172128E-009f, 6.009061827883699E-007f,\n                        -4.541343896997497E-005f, 1.937383947804541E-003f,\n                        -3.405537384615824E-002f};\n    const float MO1[] = {6.913942741265801E-002f, -2.284801500053359E-001f,\n                        3.138238455499697E-001f, -2.102302420403875E-001f,\n                        5.435364690523026E-003f, 1.493389585089498E-001f,\n                        4.976029650847191E-006f, 7.978845453073848E-001f};\n    const float PH1[] = {-4.497014141919556E+001f, 5.073465654089319E+001f,\n                        -2.485774108720340E+001f, 7.222973196770240E+000f,\n                        -1.544842782180211E+000f, 3.503787691653334E-001f,\n                        -1.637986776941202E-001f, 3.749989509080821E-001f};\n    const T Z1 = pset1<T>(1.46819706421238932572E1f);\n    const T NEG_THPIO4F = pset1<T>(-2.35619449019234492885f);    /* -3*pi/4 */\n\n    T y = pabs(x);\n    T z = pmul(y, y);\n    T y_le_two = pmul(\n        psub(z, Z1),\n        pmul(x, internal::ppolevl<T, 4>::run(z, JP)));\n    T q = pdiv(pset1<T>(1.0f), y);\n    T w = prsqrt(y);\n    T p = pmul(w, internal::ppolevl<T, 7>::run(q, MO1));\n    w = pmul(q, q);\n    T yn = pmadd(q, internal::ppolevl<T, 7>::run(w, PH1), NEG_THPIO4F);\n    T y_gt_two = pmul(p, pcos(padd(yn, y)));\n    // j1 is an odd function. This implementation differs from cephes to\n    // take this fact in to account. Cephes returns -j1(x) for y > 2 range.\n    y_gt_two = pselect(\n        pcmp_lt(x, pset1<T>(0.0f)), pnegate(y_gt_two), y_gt_two);\n    return pselect(pcmp_le(y, pset1<T>(2.0f)), y_le_two, y_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct generic_j1<T, double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  j1.c\n     *\tBessel function of order one\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, j1();\n     *\n     * y = j1( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns Bessel function of order one of the argument.\n     *\n     * The domain is divided into the intervals [0, 8] and\n     * (8, infinity). In the first interval a 24 term Chebyshev\n     * expansion is used. In the second, the asymptotic\n     * trigonometric representation is employed using two\n     * rational functions of degree 5/5.\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Absolute error:\n     * arithmetic   domain      # trials      peak         rms\n     *    DEC       0, 30       10000       4.0e-17     1.1e-17\n     *    IEEE      0, 30       30000       2.6e-16     1.1e-16\n     *\n     */\n    const double PP[] = {7.62125616208173112003E-4, 7.31397056940917570436E-2,\n                         1.12719608129684925192E0, 5.11207951146807644818E0,\n                         8.42404590141772420927E0, 5.21451598682361504063E0,\n                         1.00000000000000000254E0};\n    const double PQ[] = {5.71323128072548699714E-4, 6.88455908754495404082E-2,\n                         1.10514232634061696926E0, 5.07386386128601488557E0,\n                         8.39985554327604159757E0, 5.20982848682361821619E0,\n                         9.99999999999999997461E-1};\n    const double QP[] = {5.10862594750176621635E-2, 4.98213872951233449420E0,\n                         7.58238284132545283818E1, 3.66779609360150777800E2,\n                         7.10856304998926107277E2, 5.97489612400613639965E2,\n                         2.11688757100572135698E2, 2.52070205858023719784E1};\n    const double QQ[] = {1.00000000000000000000E0, 7.42373277035675149943E1,\n                         1.05644886038262816351E3, 4.98641058337653607651E3,\n                         9.56231892404756170795E3, 7.99704160447350683650E3,\n                         2.82619278517639096600E3, 3.36093607810698293419E2};\n    const double RP[] = {-8.99971225705559398224E8, 4.52228297998194034323E11,\n                         -7.27494245221818276015E13, 3.68295732863852883286E15};\n    const double RQ[] = {1.00000000000000000000E0, 6.20836478118054335476E2,\n                         2.56987256757748830383E5, 8.35146791431949253037E7,\n                         2.21511595479792499675E10, 4.74914122079991414898E12,\n                         7.84369607876235854894E14, 8.95222336184627338078E16,\n                         5.32278620332680085395E18};\n    const T Z1 = pset1<T>(1.46819706421238932572E1);\n    const T Z2 = pset1<T>(4.92184563216946036703E1);\n    const T NEG_THPIO4 = pset1<T>(-2.35619449019234492885);    /* -3*pi/4 */\n    const T SQ2OPI = pset1<T>(7.9788456080286535587989E-1); /* sqrt(2 / pi) */\n    T y = pabs(x);\n    T z = pmul(y, y);\n    T y_le_five = pdiv(internal::ppolevl<T, 3>::run(z, RP),\n                       internal::ppolevl<T, 8>::run(z, RQ));\n    y_le_five = pmul(pmul(pmul(y_le_five, x), psub(z, Z1)), psub(z, Z2));\n    T s = pdiv(pset1<T>(25.0), z);\n    T p = pdiv(\n        internal::ppolevl<T, 6>::run(s, PP),\n        internal::ppolevl<T, 6>::run(s, PQ));\n    T q = pdiv(\n        internal::ppolevl<T, 7>::run(s, QP),\n        internal::ppolevl<T, 7>::run(s, QQ));\n    T yn = padd(y, NEG_THPIO4);\n    T w = pdiv(pset1<T>(-5.0), y);\n    p = pmadd(p, pcos(yn), pmul(w, pmul(q, psin(yn))));\n    T y_gt_five = pmul(p, pmul(SQ2OPI, prsqrt(y)));\n    // j1 is an odd function. This implementation differs from cephes to\n    // take this fact in to account. Cephes returns -j1(x) for y > 5 range.\n    y_gt_five = pselect(\n        pcmp_lt(x, pset1<T>(0.0)), pnegate(y_gt_five), y_gt_five);\n    return pselect(pcmp_le(y, pset1<T>(5.0)), y_le_five, y_gt_five);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_j1_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_j1<T>::run(x);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_y1_retval {\n  typedef T type;\n};\n\ntemplate <typename T, typename ScalarType = typename unpacket_traits<T>::type>\nstruct generic_y1 {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T&) {\n    EIGEN_STATIC_ASSERT((internal::is_same<T, T>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return ScalarType(0);\n  }\n};\n\ntemplate <typename T>\nstruct generic_y1<T, float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /* j1f.c\n     *\tBessel function of second kind of order one\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, y1();\n     *\n     * y = y1( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns Bessel function of the second kind of order one\n     * of the argument.\n     *\n     * The domain is divided into the intervals [0, 2] and\n     * (2, infinity). In the first interval a rational approximation\n     * R(x) is employed to compute\n     *\n     *                  2\n     * y0(x)  =  (w - r  ) x R(x^2)  +  2/pi (ln(x) j1(x) - 1/x) .\n     *                 1\n     *\n     * Thus a call to j1() is required.\n     *\n     * In the second interval, the modulus and phase are approximated\n     * by polynomials of the form Modulus(x) = sqrt(1/x) Q(1/x)\n     * and Phase(x) = x + 1/x S(1/x^2) - 3pi/4.  Then the function is\n     *\n     *   y0(x) = Modulus(x) sin( Phase(x) ).\n     *\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Absolute error:\n     * arithmetic   domain      # trials      peak         rms\n     *    IEEE      0,  2       100000       2.2e-7     4.6e-8\n     *    IEEE      2, 32       100000       1.9e-7     5.3e-8\n     *\n     * (error criterion relative when |y1| > 1).\n     *\n     */\n\n    const float YP[] = {8.061978323326852E-009f, -9.496460629917016E-007f,\n                        6.719543806674249E-005f, -2.641785726447862E-003f,\n                        4.202369946500099E-002f};\n    const float MO1[] = {6.913942741265801E-002f, -2.284801500053359E-001f,\n                        3.138238455499697E-001f, -2.102302420403875E-001f,\n                        5.435364690523026E-003f, 1.493389585089498E-001f,\n                        4.976029650847191E-006f, 7.978845453073848E-001f};\n    const float PH1[] = {-4.497014141919556E+001f, 5.073465654089319E+001f,\n                        -2.485774108720340E+001f, 7.222973196770240E+000f,\n                        -1.544842782180211E+000f, 3.503787691653334E-001f,\n                        -1.637986776941202E-001f, 3.749989509080821E-001f};\n    const T YO1 = pset1<T>(4.66539330185668857532f);\n    const T NEG_THPIO4F = pset1<T>(-2.35619449019234492885f);    /* -3*pi/4 */\n    const T TWOOPI = pset1<T>(0.636619772367581343075535f); /* 2/pi */\n    const T NEG_MAXNUM = pset1<T>(-NumTraits<float>::infinity());\n\n    T z = pmul(x, x);\n    T x_le_two = pmul(psub(z, YO1), internal::ppolevl<T, 4>::run(z, YP));\n    x_le_two = pmadd(\n       x_le_two, x,\n       pmul(TWOOPI, pmadd(\n           generic_j1<T, float>::run(x), plog(x),\n           pdiv(pset1<T>(-1.0f), x))));\n    x_le_two = pselect(pcmp_lt(x, pset1<T>(0.0f)), NEG_MAXNUM, x_le_two);\n\n    T q = pdiv(pset1<T>(1.0), x);\n    T w = prsqrt(x);\n    T p = pmul(w, internal::ppolevl<T, 7>::run(q, MO1));\n    w = pmul(q, q);\n    T xn = pmadd(q, internal::ppolevl<T, 7>::run(w, PH1), NEG_THPIO4F);\n    T x_gt_two = pmul(p, psin(padd(xn, x)));\n    return pselect(pcmp_le(x, pset1<T>(2.0)), x_le_two, x_gt_two);\n  }\n};\n\ntemplate <typename T>\nstruct generic_y1<T, double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    /*  j1.c\n     *\tBessel function of second kind of order one\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, y1();\n     *\n     * y = y1( x );\n     *\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns Bessel function of the second kind of order one\n     * of the argument.\n     *\n     * The domain is divided into the intervals [0, 8] and\n     * (8, infinity). In the first interval a 25 term Chebyshev\n     * expansion is used, and a call to j1() is required.\n     * In the second, the asymptotic trigonometric representation\n     * is employed using two rational functions of degree 5/5.\n     *\n     *\n     *\n     * ACCURACY:\n     *\n     *                      Absolute error:\n     * arithmetic   domain      # trials      peak         rms\n     *    DEC       0, 30       10000       8.6e-17     1.3e-17\n     *    IEEE      0, 30       30000       1.0e-15     1.3e-16\n     *\n     * (error criterion relative when |y1| > 1).\n     *\n     */\n    const double PP[] = {7.62125616208173112003E-4, 7.31397056940917570436E-2,\n                         1.12719608129684925192E0, 5.11207951146807644818E0,\n                         8.42404590141772420927E0, 5.21451598682361504063E0,\n                         1.00000000000000000254E0};\n    const double PQ[] = {5.71323128072548699714E-4, 6.88455908754495404082E-2,\n                         1.10514232634061696926E0, 5.07386386128601488557E0,\n                         8.39985554327604159757E0, 5.20982848682361821619E0,\n                         9.99999999999999997461E-1};\n    const double QP[] = {5.10862594750176621635E-2, 4.98213872951233449420E0,\n                         7.58238284132545283818E1, 3.66779609360150777800E2,\n                         7.10856304998926107277E2, 5.97489612400613639965E2,\n                         2.11688757100572135698E2, 2.52070205858023719784E1};\n    const double QQ[] = {1.00000000000000000000E0, 7.42373277035675149943E1,\n                         1.05644886038262816351E3, 4.98641058337653607651E3,\n                         9.56231892404756170795E3, 7.99704160447350683650E3,\n                         2.82619278517639096600E3, 3.36093607810698293419E2};\n    const double YP[] = {1.26320474790178026440E9, -6.47355876379160291031E11,\n                         1.14509511541823727583E14, -8.12770255501325109621E15,\n                         2.02439475713594898196E17, -7.78877196265950026825E17};\n    const double YQ[] = {1.00000000000000000000E0, 5.94301592346128195359E2,\n                         2.35564092943068577943E5, 7.34811944459721705660E7,\n                         1.87601316108706159478E10, 3.88231277496238566008E12,\n                         6.20557727146953693363E14, 6.87141087355300489866E16,\n                         3.97270608116560655612E18};\n    const T SQ2OPI = pset1<T>(.79788456080286535588);\n    const T NEG_THPIO4 = pset1<T>(-2.35619449019234492885);    /* -3*pi/4 */\n    const T TWOOPI = pset1<T>(0.636619772367581343075535); /* 2/pi */\n    const T NEG_MAXNUM = pset1<T>(-NumTraits<double>::infinity());\n\n    T z = pmul(x, x);\n    T x_le_five = pdiv(internal::ppolevl<T, 5>::run(z, YP),\n                   internal::ppolevl<T, 8>::run(z, YQ));\n    x_le_five = pmadd(\n        x_le_five, x, pmul(\n            TWOOPI, pmadd(generic_j1<T, double>::run(x), plog(x),\n                          pdiv(pset1<T>(-1.0), x))));\n\n    x_le_five = pselect(pcmp_le(x, pset1<T>(0.0)), NEG_MAXNUM, x_le_five);\n    T s = pdiv(pset1<T>(25.0), z);\n    T p = pdiv(\n        internal::ppolevl<T, 6>::run(s, PP),\n        internal::ppolevl<T, 6>::run(s, PQ));\n    T q = pdiv(\n        internal::ppolevl<T, 7>::run(s, QP),\n        internal::ppolevl<T, 7>::run(s, QQ));\n    T xn = padd(x, NEG_THPIO4);\n    T w = pdiv(pset1<T>(5.0), x);\n    p = pmadd(p, psin(xn), pmul(w, pmul(q, pcos(xn))));\n    T x_gt_five = pmul(p, pmul(SQ2OPI, prsqrt(x)));\n    return pselect(pcmp_le(x, pset1<T>(5.0)), x_le_five, x_gt_five);\n  }\n};\n\ntemplate <typename T>\nstruct bessel_y1_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T x) {\n    return generic_y1<T>::run(x);\n  }\n};\n\n}  // end namespace internal\n\nnamespace numext {\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_i0, Scalar)\n    bessel_i0(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_i0, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_i0e, Scalar)\n    bessel_i0e(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_i0e, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_i1, Scalar)\n    bessel_i1(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_i1, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_i1e, Scalar)\n    bessel_i1e(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_i1e, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_k0, Scalar)\n    bessel_k0(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_k0, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_k0e, Scalar)\n    bessel_k0e(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_k0e, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_k1, Scalar)\n    bessel_k1(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_k1, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_k1e, Scalar)\n    bessel_k1e(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_k1e, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_j0, Scalar)\n    bessel_j0(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_j0, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_y0, Scalar)\n    bessel_y0(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_y0, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_j1, Scalar)\n    bessel_j1(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_j1, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(bessel_y1, Scalar)\n    bessel_y1(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(bessel_y1, Scalar)::run(x);\n}\n\n}  // end namespace numext\n\n}  // end namespace Eigen\n\n#endif  // EIGEN_BESSEL_FUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SpecialFunctions/BesselFunctionsPacketMath.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_BESSELFUNCTIONS_PACKETMATH_H\n#define EIGEN_BESSELFUNCTIONS_PACKETMATH_H\n\nnamespace Eigen {\n\nnamespace internal {\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order zero i0(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_i0(const Packet& x) {\n  return numext::bessel_i0(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order zero i0e(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_i0e(const Packet& x) {\n  return numext::bessel_i0e(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order one i1(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_i1(const Packet& x) {\n  return numext::bessel_i1(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order one i1e(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_i1e(const Packet& x) {\n  return numext::bessel_i1e(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order zero j0(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_j0(const Packet& x) {\n  return numext::bessel_j0(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order zero j1(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_j1(const Packet& x) {\n  return numext::bessel_j1(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order one y0(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_y0(const Packet& x) {\n  return numext::bessel_y0(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order one y1(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_y1(const Packet& x) {\n  return numext::bessel_y1(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order zero k0(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_k0(const Packet& x) {\n  return numext::bessel_k0(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order zero k0e(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_k0e(const Packet& x) {\n  return numext::bessel_k0e(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order one k1e(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_k1(const Packet& x) {\n  return numext::bessel_k1(x);\n}\n\n/** \\internal \\returns the exponentially scaled modified Bessel function of\n * order one k1e(\\a a) (coeff-wise) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pbessel_k1e(const Packet& x) {\n  return numext::bessel_k1e(x);\n}\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_BESSELFUNCTIONS_PACKETMATH_H\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SpecialFunctions/HipVectorCompatibility.h",
    "content": "#ifndef HIP_VECTOR_COMPATIBILITY_H\n#define HIP_VECTOR_COMPATIBILITY_H\n\nnamespace hip_impl {\n  template <typename, typename, unsigned int> struct Scalar_accessor;\n}   // end namespace hip_impl\n\nnamespace Eigen {\nnamespace internal {\n\n#define HIP_SCALAR_ACCESSOR_BUILDER(NAME) \\\ntemplate <typename T, typename U, unsigned int n> \\\nstruct NAME <hip_impl::Scalar_accessor<T, U, n>> : NAME <T> {};\n\n#define HIP_SCALAR_ACCESSOR_BUILDER_RETVAL(NAME) \\\ntemplate <typename T, typename U, unsigned int n> \\\nstruct NAME##_impl <hip_impl::Scalar_accessor<T, U, n>> : NAME##_impl <T> {}; \\\ntemplate <typename T, typename U, unsigned int n> \\\nstruct NAME##_retval <hip_impl::Scalar_accessor<T, U, n>> : NAME##_retval <T> {};\n\n#define HIP_SCALAR_ACCESSOR_BUILDER_IGAMMA(NAME) \\\ntemplate <typename T, typename U, unsigned int n, IgammaComputationMode mode> \\\nstruct NAME <hip_impl::Scalar_accessor<T, U, n>, mode> : NAME <T, mode> {};\n\n#if EIGEN_HAS_C99_MATH\nHIP_SCALAR_ACCESSOR_BUILDER(betainc_helper)\nHIP_SCALAR_ACCESSOR_BUILDER(incbeta_cfe)\n\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(erf)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(erfc)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(igammac)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(lgamma)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(ndtri)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(polygamma)\n\nHIP_SCALAR_ACCESSOR_BUILDER_IGAMMA(igamma_generic_impl)\n#endif\n\nHIP_SCALAR_ACCESSOR_BUILDER(digamma_impl_maybe_poly)\nHIP_SCALAR_ACCESSOR_BUILDER(zeta_impl_series)\n\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_i0)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_i0e)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_i1)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_i1e)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_j0)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_j1)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_k0)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_k0e)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_k1)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_k1e)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_y0)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(bessel_y1)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(betainc)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(digamma)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(gamma_sample_der_alpha)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(igamma_der_a)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(igamma)\nHIP_SCALAR_ACCESSOR_BUILDER_RETVAL(zeta)\n\nHIP_SCALAR_ACCESSOR_BUILDER_IGAMMA(igamma_series_impl)\nHIP_SCALAR_ACCESSOR_BUILDER_IGAMMA(igammac_cf_impl)\n\n}  // end namespace internal\n}  // end namespace Eigen\n\n#endif  // HIP_VECTOR_COMPATIBILITY_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsArrayAPI.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#ifndef EIGEN_SPECIALFUNCTIONS_ARRAYAPI_H\n#define EIGEN_SPECIALFUNCTIONS_ARRAYAPI_H\n\nnamespace Eigen {\n\n/** \\cpp11 \\returns an expression of the coefficient-wise igamma(\\a a, \\a x) to the given arrays.\n  *\n  * This function computes the coefficient-wise incomplete gamma function.\n  *\n  * \\note This function supports only float and double scalar types in c++11 mode. To support other scalar types,\n  * or float/double in non c++11 mode, the user has to provide implementations of igammac(T,T) for any scalar\n  * type T to be supported.\n  *\n  * \\sa Eigen::igammac(), Eigen::lgamma()\n  */\ntemplate<typename Derived,typename ExponentDerived>\nEIGEN_STRONG_INLINE const Eigen::CwiseBinaryOp<Eigen::internal::scalar_igamma_op<typename Derived::Scalar>, const Derived, const ExponentDerived>\nigamma(const Eigen::ArrayBase<Derived>& a, const Eigen::ArrayBase<ExponentDerived>& x)\n{\n  return Eigen::CwiseBinaryOp<Eigen::internal::scalar_igamma_op<typename Derived::Scalar>, const Derived, const ExponentDerived>(\n    a.derived(),\n    x.derived()\n  );\n}\n\n/** \\cpp11 \\returns an expression of the coefficient-wise igamma_der_a(\\a a, \\a x) to the given arrays.\n  *\n  * This function computes the coefficient-wise derivative of the incomplete\n  * gamma function with respect to the parameter a.\n  *\n  * \\note This function supports only float and double scalar types in c++11\n  * mode. To support other scalar types,\n  * or float/double in non c++11 mode, the user has to provide implementations\n  * of igamma_der_a(T,T) for any scalar\n  * type T to be supported.\n  *\n  * \\sa Eigen::igamma(), Eigen::lgamma()\n  */\ntemplate <typename Derived, typename ExponentDerived>\nEIGEN_STRONG_INLINE const Eigen::CwiseBinaryOp<Eigen::internal::scalar_igamma_der_a_op<typename Derived::Scalar>, const Derived, const ExponentDerived>\nigamma_der_a(const Eigen::ArrayBase<Derived>& a, const Eigen::ArrayBase<ExponentDerived>& x) {\n  return Eigen::CwiseBinaryOp<Eigen::internal::scalar_igamma_der_a_op<typename Derived::Scalar>, const Derived, const ExponentDerived>(\n    a.derived(),\n    x.derived());\n}\n\n/** \\cpp11 \\returns an expression of the coefficient-wise gamma_sample_der_alpha(\\a alpha, \\a sample) to the given arrays.\n  *\n  * This function computes the coefficient-wise derivative of the sample\n  * of a Gamma(alpha, 1) random variable with respect to the parameter alpha.\n  *\n  * \\note This function supports only float and double scalar types in c++11\n  * mode. To support other scalar types,\n  * or float/double in non c++11 mode, the user has to provide implementations\n  * of gamma_sample_der_alpha(T,T) for any scalar\n  * type T to be supported.\n  *\n  * \\sa Eigen::igamma(), Eigen::lgamma()\n  */\ntemplate <typename AlphaDerived, typename SampleDerived>\nEIGEN_STRONG_INLINE const Eigen::CwiseBinaryOp<Eigen::internal::scalar_gamma_sample_der_alpha_op<typename AlphaDerived::Scalar>, const AlphaDerived, const SampleDerived>\ngamma_sample_der_alpha(const Eigen::ArrayBase<AlphaDerived>& alpha, const Eigen::ArrayBase<SampleDerived>& sample) {\n  return Eigen::CwiseBinaryOp<Eigen::internal::scalar_gamma_sample_der_alpha_op<typename AlphaDerived::Scalar>, const AlphaDerived, const SampleDerived>(\n      alpha.derived(),\n      sample.derived());\n}\n\n/** \\cpp11 \\returns an expression of the coefficient-wise igammac(\\a a, \\a x) to the given arrays.\n  *\n  * This function computes the coefficient-wise complementary incomplete gamma function.\n  *\n  * \\note This function supports only float and double scalar types in c++11 mode. To support other scalar types,\n  * or float/double in non c++11 mode, the user has to provide implementations of igammac(T,T) for any scalar\n  * type T to be supported.\n  *\n  * \\sa Eigen::igamma(), Eigen::lgamma()\n  */\ntemplate<typename Derived,typename ExponentDerived>\nEIGEN_STRONG_INLINE const Eigen::CwiseBinaryOp<Eigen::internal::scalar_igammac_op<typename Derived::Scalar>, const Derived, const ExponentDerived>\nigammac(const Eigen::ArrayBase<Derived>& a, const Eigen::ArrayBase<ExponentDerived>& x)\n{\n  return Eigen::CwiseBinaryOp<Eigen::internal::scalar_igammac_op<typename Derived::Scalar>, const Derived, const ExponentDerived>(\n    a.derived(),\n    x.derived()\n  );\n}\n\n/** \\cpp11 \\returns an expression of the coefficient-wise polygamma(\\a n, \\a x) to the given arrays.\n  *\n  * It returns the \\a n -th derivative of the digamma(psi) evaluated at \\c x.\n  *\n  * \\note This function supports only float and double scalar types in c++11 mode. To support other scalar types,\n  * or float/double in non c++11 mode, the user has to provide implementations of polygamma(T,T) for any scalar\n  * type T to be supported.\n  *\n  * \\sa Eigen::digamma()\n  */\n// * \\warning Be careful with the order of the parameters: x.polygamma(n) is equivalent to polygamma(n,x)\n// * \\sa ArrayBase::polygamma()\ntemplate<typename DerivedN,typename DerivedX>\nEIGEN_STRONG_INLINE const Eigen::CwiseBinaryOp<Eigen::internal::scalar_polygamma_op<typename DerivedX::Scalar>, const DerivedN, const DerivedX>\npolygamma(const Eigen::ArrayBase<DerivedN>& n, const Eigen::ArrayBase<DerivedX>& x)\n{\n  return Eigen::CwiseBinaryOp<Eigen::internal::scalar_polygamma_op<typename DerivedX::Scalar>, const DerivedN, const DerivedX>(\n    n.derived(),\n    x.derived()\n  );\n}\n\n/** \\cpp11 \\returns an expression of the coefficient-wise betainc(\\a x, \\a a, \\a b) to the given arrays.\n  *\n  * This function computes the regularized incomplete beta function (integral).\n  *\n  * \\note This function supports only float and double scalar types in c++11 mode. To support other scalar types,\n  * or float/double in non c++11 mode, the user has to provide implementations of betainc(T,T,T) for any scalar\n  * type T to be supported.\n  *\n  * \\sa Eigen::betainc(), Eigen::lgamma()\n  */\ntemplate<typename ArgADerived, typename ArgBDerived, typename ArgXDerived>\nEIGEN_STRONG_INLINE const Eigen::CwiseTernaryOp<Eigen::internal::scalar_betainc_op<typename ArgXDerived::Scalar>, const ArgADerived, const ArgBDerived, const ArgXDerived>\nbetainc(const Eigen::ArrayBase<ArgADerived>& a, const Eigen::ArrayBase<ArgBDerived>& b, const Eigen::ArrayBase<ArgXDerived>& x)\n{\n  return Eigen::CwiseTernaryOp<Eigen::internal::scalar_betainc_op<typename ArgXDerived::Scalar>, const ArgADerived, const ArgBDerived, const ArgXDerived>(\n    a.derived(),\n    b.derived(),\n    x.derived()\n  );\n}\n\n\n/** \\returns an expression of the coefficient-wise zeta(\\a x, \\a q) to the given arrays.\n  *\n  * It returns the Riemann zeta function of two arguments \\a x and \\a q:\n  *\n  * \\param x is the exponent, it must be > 1\n  * \\param q is the shift, it must be > 0\n  *\n  * \\note This function supports only float and double scalar types. To support other scalar types, the user has\n  * to provide implementations of zeta(T,T) for any scalar type T to be supported.\n  *\n  * \\sa ArrayBase::zeta()\n  */\ntemplate<typename DerivedX,typename DerivedQ>\nEIGEN_STRONG_INLINE const Eigen::CwiseBinaryOp<Eigen::internal::scalar_zeta_op<typename DerivedX::Scalar>, const DerivedX, const DerivedQ>\nzeta(const Eigen::ArrayBase<DerivedX>& x, const Eigen::ArrayBase<DerivedQ>& q)\n{\n  return Eigen::CwiseBinaryOp<Eigen::internal::scalar_zeta_op<typename DerivedX::Scalar>, const DerivedX, const DerivedQ>(\n    x.derived(),\n    q.derived()\n  );\n}\n\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPECIALFUNCTIONS_ARRAYAPI_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsBFloat16.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPECIALFUNCTIONS_BFLOAT16_H\n#define EIGEN_SPECIALFUNCTIONS_BFLOAT16_H\n\nnamespace Eigen {\nnamespace numext {\n\n#if EIGEN_HAS_C99_MATH\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 lgamma(const Eigen::bfloat16& a) {\n  return Eigen::bfloat16(Eigen::numext::lgamma(static_cast<float>(a)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 digamma(const Eigen::bfloat16& a) {\n  return Eigen::bfloat16(Eigen::numext::digamma(static_cast<float>(a)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 zeta(const Eigen::bfloat16& x, const Eigen::bfloat16& q) {\n  return Eigen::bfloat16(Eigen::numext::zeta(static_cast<float>(x), static_cast<float>(q)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 polygamma(const Eigen::bfloat16& n, const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::polygamma(static_cast<float>(n), static_cast<float>(x)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 erf(const Eigen::bfloat16& a) {\n  return Eigen::bfloat16(Eigen::numext::erf(static_cast<float>(a)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 erfc(const Eigen::bfloat16& a) {\n  return Eigen::bfloat16(Eigen::numext::erfc(static_cast<float>(a)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 ndtri(const Eigen::bfloat16& a) {\n  return Eigen::bfloat16(Eigen::numext::ndtri(static_cast<float>(a)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 igamma(const Eigen::bfloat16& a, const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::igamma(static_cast<float>(a), static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 igamma_der_a(const Eigen::bfloat16& a, const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::igamma_der_a(static_cast<float>(a), static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 gamma_sample_der_alpha(const Eigen::bfloat16& alpha, const Eigen::bfloat16& sample) {\n  return Eigen::bfloat16(Eigen::numext::gamma_sample_der_alpha(static_cast<float>(alpha), static_cast<float>(sample)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 igammac(const Eigen::bfloat16& a, const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::igammac(static_cast<float>(a), static_cast<float>(x)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::bfloat16 betainc(const Eigen::bfloat16& a, const Eigen::bfloat16& b, const Eigen::bfloat16& x) {\n  return Eigen::bfloat16(Eigen::numext::betainc(static_cast<float>(a), static_cast<float>(b), static_cast<float>(x)));\n}\n#endif\n\n}  // end namespace numext\n}  // end namespace Eigen\n\n#endif  // EIGEN_SPECIALFUNCTIONS_BFLOAT16_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsFunctors.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Eugene Brevdo <ebrevdo@gmail.com>\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPECIALFUNCTIONS_FUNCTORS_H\n#define EIGEN_SPECIALFUNCTIONS_FUNCTORS_H\n\nnamespace Eigen {\n\nnamespace internal {\n\n\n/** \\internal\n  * \\brief Template functor to compute the incomplete gamma function igamma(a, x)\n  *\n  * \\sa class CwiseBinaryOp, Cwise::igamma\n  */\ntemplate<typename Scalar> struct scalar_igamma_op : binary_op_base<Scalar,Scalar>\n{\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_igamma_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a, const Scalar& x) const {\n    using numext::igamma; return igamma(a, x);\n  }\n  template<typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& x) const {\n    return internal::pigamma(a, x);\n  }\n};\ntemplate<typename Scalar>\nstruct functor_traits<scalar_igamma_op<Scalar> > {\n  enum {\n    // Guesstimate\n    Cost = 20 * NumTraits<Scalar>::MulCost + 10 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasIGamma\n  };\n};\n\n/** \\internal\n  * \\brief Template functor to compute the derivative of the incomplete gamma\n  * function igamma_der_a(a, x)\n  *\n  * \\sa class CwiseBinaryOp, Cwise::igamma_der_a\n  */\ntemplate <typename Scalar>\nstruct scalar_igamma_der_a_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_igamma_der_a_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& a, const Scalar& x) const {\n    using numext::igamma_der_a;\n    return igamma_der_a(a, x);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& x) const {\n    return internal::pigamma_der_a(a, x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_igamma_der_a_op<Scalar> > {\n  enum {\n    // 2x the cost of igamma\n    Cost = 40 * NumTraits<Scalar>::MulCost + 20 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasIGammaDerA\n  };\n};\n\n/** \\internal\n  * \\brief Template functor to compute the derivative of the sample\n  * of a Gamma(alpha, 1) random variable with respect to the parameter alpha\n  * gamma_sample_der_alpha(alpha, sample)\n  *\n  * \\sa class CwiseBinaryOp, Cwise::gamma_sample_der_alpha\n  */\ntemplate <typename Scalar>\nstruct scalar_gamma_sample_der_alpha_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_gamma_sample_der_alpha_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator()(const Scalar& alpha, const Scalar& sample) const {\n    using numext::gamma_sample_der_alpha;\n    return gamma_sample_der_alpha(alpha, sample);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& alpha, const Packet& sample) const {\n    return internal::pgamma_sample_der_alpha(alpha, sample);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_gamma_sample_der_alpha_op<Scalar> > {\n  enum {\n    // 2x the cost of igamma, minus the lgamma cost (the lgamma cancels out)\n    Cost = 30 * NumTraits<Scalar>::MulCost + 15 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasGammaSampleDerAlpha\n  };\n};\n\n/** \\internal\n  * \\brief Template functor to compute the complementary incomplete gamma function igammac(a, x)\n  *\n  * \\sa class CwiseBinaryOp, Cwise::igammac\n  */\ntemplate<typename Scalar> struct scalar_igammac_op : binary_op_base<Scalar,Scalar>\n{\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_igammac_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a, const Scalar& x) const {\n    using numext::igammac; return igammac(a, x);\n  }\n  template<typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& a, const Packet& x) const\n  {\n    return internal::pigammac(a, x);\n  }\n};\ntemplate<typename Scalar>\nstruct functor_traits<scalar_igammac_op<Scalar> > {\n  enum {\n    // Guesstimate\n    Cost = 20 * NumTraits<Scalar>::MulCost + 10 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasIGammac\n  };\n};\n\n\n/** \\internal\n  * \\brief Template functor to compute the incomplete beta integral betainc(a, b, x)\n  *\n  */\ntemplate<typename Scalar> struct scalar_betainc_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_betainc_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& x, const Scalar& a, const Scalar& b) const {\n    using numext::betainc; return betainc(x, a, b);\n  }\n  template<typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Packet packetOp(const Packet& x, const Packet& a, const Packet& b) const\n  {\n    return internal::pbetainc(x, a, b);\n  }\n};\ntemplate<typename Scalar>\nstruct functor_traits<scalar_betainc_op<Scalar> > {\n  enum {\n    // Guesstimate\n    Cost = 400 * NumTraits<Scalar>::MulCost + 400 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasBetaInc\n  };\n};\n\n\n/** \\internal\n * \\brief Template functor to compute the natural log of the absolute\n * value of Gamma of a scalar\n * \\sa class CwiseUnaryOp, Cwise::lgamma()\n */\ntemplate<typename Scalar> struct scalar_lgamma_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_lgamma_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a) const {\n    using numext::lgamma; return lgamma(a);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& a) const { return internal::plgamma(a); }\n};\ntemplate<typename Scalar>\nstruct functor_traits<scalar_lgamma_op<Scalar> >\n{\n  enum {\n    // Guesstimate\n    Cost = 10 * NumTraits<Scalar>::MulCost + 5 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasLGamma\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute psi, the derivative of lgamma of a scalar.\n * \\sa class CwiseUnaryOp, Cwise::digamma()\n */\ntemplate<typename Scalar> struct scalar_digamma_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_digamma_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a) const {\n    using numext::digamma; return digamma(a);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& a) const { return internal::pdigamma(a); }\n};\ntemplate<typename Scalar>\nstruct functor_traits<scalar_digamma_op<Scalar> >\n{\n  enum {\n    // Guesstimate\n    Cost = 10 * NumTraits<Scalar>::MulCost + 5 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasDiGamma\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the Riemann Zeta function of two arguments.\n * \\sa class CwiseUnaryOp, Cwise::zeta()\n */\ntemplate<typename Scalar> struct scalar_zeta_op {\n    EIGEN_EMPTY_STRUCT_CTOR(scalar_zeta_op)\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& x, const Scalar& q) const {\n        using numext::zeta; return zeta(x, q);\n    }\n    typedef typename packet_traits<Scalar>::type Packet;\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x, const Packet& q) const { return internal::pzeta(x, q); }\n};\ntemplate<typename Scalar>\nstruct functor_traits<scalar_zeta_op<Scalar> >\n{\n    enum {\n        // Guesstimate\n        Cost = 10 * NumTraits<Scalar>::MulCost + 5 * NumTraits<Scalar>::AddCost,\n        PacketAccess = packet_traits<Scalar>::HasZeta\n    };\n};\n\n/** \\internal\n * \\brief Template functor to compute the polygamma function.\n * \\sa class CwiseUnaryOp, Cwise::polygamma()\n */\ntemplate<typename Scalar> struct scalar_polygamma_op {\n    EIGEN_EMPTY_STRUCT_CTOR(scalar_polygamma_op)\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& n, const Scalar& x) const {\n        using numext::polygamma; return polygamma(n, x);\n    }\n    typedef typename packet_traits<Scalar>::type Packet;\n    EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& n, const Packet& x) const { return internal::ppolygamma(n, x); }\n};\ntemplate<typename Scalar>\nstruct functor_traits<scalar_polygamma_op<Scalar> >\n{\n    enum {\n        // Guesstimate\n        Cost = 10 * NumTraits<Scalar>::MulCost + 5 * NumTraits<Scalar>::AddCost,\n        PacketAccess = packet_traits<Scalar>::HasPolygamma\n    };\n};\n\n/** \\internal\n * \\brief Template functor to compute the error function of a scalar\n * \\sa class CwiseUnaryOp, ArrayBase::erf()\n */\ntemplate<typename Scalar> struct scalar_erf_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_erf_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar\n  operator()(const Scalar& a) const {\n    return numext::erf(a);\n  }\n  template <typename Packet>\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& x) const {\n    return perf(x);\n  }\n};\ntemplate <typename Scalar>\nstruct functor_traits<scalar_erf_op<Scalar> > {\n  enum {\n    PacketAccess = packet_traits<Scalar>::HasErf,\n    Cost =\n        (PacketAccess\n#ifdef EIGEN_VECTORIZE_FMA\n             // TODO(rmlarsen): Move the FMA cost model to a central location.\n             // Haswell can issue 2 add/mul/madd per cycle.\n             // 10 pmadd, 2 pmul, 1 div, 2 other\n             ? (2 * NumTraits<Scalar>::AddCost +\n                7 * NumTraits<Scalar>::MulCost +\n                scalar_div_cost<Scalar, packet_traits<Scalar>::HasDiv>::value)\n#else\n             ? (12 * NumTraits<Scalar>::AddCost +\n                12 * NumTraits<Scalar>::MulCost +\n                scalar_div_cost<Scalar, packet_traits<Scalar>::HasDiv>::value)\n#endif\n             // Assume for simplicity that this is as expensive as an exp().\n             : (functor_traits<scalar_exp_op<Scalar> >::Cost))\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the Complementary Error Function\n * of a scalar\n * \\sa class CwiseUnaryOp, Cwise::erfc()\n */\ntemplate<typename Scalar> struct scalar_erfc_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_erfc_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a) const {\n    using numext::erfc; return erfc(a);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& a) const { return internal::perfc(a); }\n};\ntemplate<typename Scalar>\nstruct functor_traits<scalar_erfc_op<Scalar> >\n{\n  enum {\n    // Guesstimate\n    Cost = 10 * NumTraits<Scalar>::MulCost + 5 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasErfc\n  };\n};\n\n/** \\internal\n * \\brief Template functor to compute the Inverse of the normal distribution\n * function of a scalar\n * \\sa class CwiseUnaryOp, Cwise::ndtri()\n */\ntemplate<typename Scalar> struct scalar_ndtri_op {\n  EIGEN_EMPTY_STRUCT_CTOR(scalar_ndtri_op)\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE const Scalar operator() (const Scalar& a) const {\n    using numext::ndtri; return ndtri(a);\n  }\n  typedef typename packet_traits<Scalar>::type Packet;\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet packetOp(const Packet& a) const { return internal::pndtri(a); }\n};\ntemplate<typename Scalar>\nstruct functor_traits<scalar_ndtri_op<Scalar> >\n{\n  enum {\n    // On average, We are evaluating rational functions with degree N=9 in the\n    // numerator and denominator. This results in 2*N additions and 2*N\n    // multiplications.\n    Cost = 18 * NumTraits<Scalar>::MulCost + 18 * NumTraits<Scalar>::AddCost,\n    PacketAccess = packet_traits<Scalar>::HasNdtri\n  };\n};\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPECIALFUNCTIONS_FUNCTORS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsHalf.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPECIALFUNCTIONS_HALF_H\n#define EIGEN_SPECIALFUNCTIONS_HALF_H\n\nnamespace Eigen {\nnamespace numext {\n\n#if EIGEN_HAS_C99_MATH\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half lgamma(const Eigen::half& a) {\n  return Eigen::half(Eigen::numext::lgamma(static_cast<float>(a)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half digamma(const Eigen::half& a) {\n  return Eigen::half(Eigen::numext::digamma(static_cast<float>(a)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half zeta(const Eigen::half& x, const Eigen::half& q) {\n  return Eigen::half(Eigen::numext::zeta(static_cast<float>(x), static_cast<float>(q)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half polygamma(const Eigen::half& n, const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::polygamma(static_cast<float>(n), static_cast<float>(x)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half erf(const Eigen::half& a) {\n  return Eigen::half(Eigen::numext::erf(static_cast<float>(a)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half erfc(const Eigen::half& a) {\n  return Eigen::half(Eigen::numext::erfc(static_cast<float>(a)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half ndtri(const Eigen::half& a) {\n  return Eigen::half(Eigen::numext::ndtri(static_cast<float>(a)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half igamma(const Eigen::half& a, const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::igamma(static_cast<float>(a), static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half igamma_der_a(const Eigen::half& a, const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::igamma_der_a(static_cast<float>(a), static_cast<float>(x)));\n}\ntemplate <>\nEIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half gamma_sample_der_alpha(const Eigen::half& alpha, const Eigen::half& sample) {\n  return Eigen::half(Eigen::numext::gamma_sample_der_alpha(static_cast<float>(alpha), static_cast<float>(sample)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half igammac(const Eigen::half& a, const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::igammac(static_cast<float>(a), static_cast<float>(x)));\n}\ntemplate<> EIGEN_STRONG_INLINE EIGEN_DEVICE_FUNC Eigen::half betainc(const Eigen::half& a, const Eigen::half& b, const Eigen::half& x) {\n  return Eigen::half(Eigen::numext::betainc(static_cast<float>(a), static_cast<float>(b), static_cast<float>(x)));\n}\n#endif\n\n}  // end namespace numext\n}  // end namespace Eigen\n\n#endif  // EIGEN_SPECIALFUNCTIONS_HALF_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsImpl.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Eugene Brevdo <ebrevdo@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPECIAL_FUNCTIONS_H\n#define EIGEN_SPECIAL_FUNCTIONS_H\n\nnamespace Eigen {\nnamespace internal {\n\n//  Parts of this code are based on the Cephes Math Library.\n//\n//  Cephes Math Library Release 2.8:  June, 2000\n//  Copyright 1984, 1987, 1992, 2000 by Stephen L. Moshier\n//\n//  Permission has been kindly provided by the original author\n//  to incorporate the Cephes software into the Eigen codebase:\n//\n//    From: Stephen Moshier\n//    To: Eugene Brevdo\n//    Subject: Re: Permission to wrap several cephes functions in Eigen\n//\n//    Hello Eugene,\n//\n//    Thank you for writing.\n//\n//    If your licensing is similar to BSD, the formal way that has been\n//    handled is simply to add a statement to the effect that you are incorporating\n//    the Cephes software by permission of the author.\n//\n//    Good luck with your project,\n//    Steve\n\n\n/****************************************************************************\n * Implementation of lgamma, requires C++11/C99                             *\n ****************************************************************************/\n\ntemplate <typename Scalar>\nstruct lgamma_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar run(const Scalar) {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar, Scalar>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return Scalar(0);\n  }\n};\n\ntemplate <typename Scalar>\nstruct lgamma_retval {\n  typedef Scalar type;\n};\n\n#if EIGEN_HAS_C99_MATH\n// Since glibc 2.19\n#if defined(__GLIBC__) && ((__GLIBC__>=2 && __GLIBC_MINOR__ >= 19) || __GLIBC__>2) \\\n && (defined(_DEFAULT_SOURCE) || defined(_BSD_SOURCE) || defined(_SVID_SOURCE))\n#define EIGEN_HAS_LGAMMA_R\n#endif\n\n// Glibc versions before 2.19\n#if defined(__GLIBC__) && ((__GLIBC__==2 && __GLIBC_MINOR__ < 19) || __GLIBC__<2) \\\n && (defined(_BSD_SOURCE) || defined(_SVID_SOURCE))\n#define EIGEN_HAS_LGAMMA_R\n#endif\n\ntemplate <>\nstruct lgamma_impl<float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE float run(float x) {\n#if !defined(EIGEN_GPU_COMPILE_PHASE) && defined (EIGEN_HAS_LGAMMA_R) && !defined(__APPLE__)\n    int dummy;\n    return ::lgammaf_r(x, &dummy);\n#elif defined(SYCL_DEVICE_ONLY)\n    return cl::sycl::lgamma(x);\n#else\n    return ::lgammaf(x);\n#endif\n  }\n};\n\ntemplate <>\nstruct lgamma_impl<double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE double run(double x) {\n#if !defined(EIGEN_GPU_COMPILE_PHASE) && defined(EIGEN_HAS_LGAMMA_R) && !defined(__APPLE__)\n    int dummy;\n    return ::lgamma_r(x, &dummy);\n#elif defined(SYCL_DEVICE_ONLY)\n    return cl::sycl::lgamma(x);\n#else\n    return ::lgamma(x);\n#endif\n  }\n};\n\n#undef EIGEN_HAS_LGAMMA_R\n#endif\n\n/****************************************************************************\n * Implementation of digamma (psi), based on Cephes                         *\n ****************************************************************************/\n\ntemplate <typename Scalar>\nstruct digamma_retval {\n  typedef Scalar type;\n};\n\n/*\n *\n * Polynomial evaluation helper for the Psi (digamma) function.\n *\n * digamma_impl_maybe_poly::run(s) evaluates the asymptotic Psi expansion for\n * input Scalar s, assuming s is above 10.0.\n *\n * If s is above a certain threshold for the given Scalar type, zero\n * is returned.  Otherwise the polynomial is evaluated with enough\n * coefficients for results matching Scalar machine precision.\n *\n *\n */\ntemplate <typename Scalar>\nstruct digamma_impl_maybe_poly {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar run(const Scalar) {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar, Scalar>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return Scalar(0);\n  }\n};\n\n\ntemplate <>\nstruct digamma_impl_maybe_poly<float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE float run(const float s) {\n    const float A[] = {\n      -4.16666666666666666667E-3f,\n      3.96825396825396825397E-3f,\n      -8.33333333333333333333E-3f,\n      8.33333333333333333333E-2f\n    };\n\n    float z;\n    if (s < 1.0e8f) {\n      z = 1.0f / (s * s);\n      return z * internal::ppolevl<float, 3>::run(z, A);\n    } else return 0.0f;\n  }\n};\n\ntemplate <>\nstruct digamma_impl_maybe_poly<double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE double run(const double s) {\n    const double A[] = {\n      8.33333333333333333333E-2,\n      -2.10927960927960927961E-2,\n      7.57575757575757575758E-3,\n      -4.16666666666666666667E-3,\n      3.96825396825396825397E-3,\n      -8.33333333333333333333E-3,\n      8.33333333333333333333E-2\n    };\n\n    double z;\n    if (s < 1.0e17) {\n      z = 1.0 / (s * s);\n      return z * internal::ppolevl<double, 6>::run(z, A);\n    }\n    else return 0.0;\n  }\n};\n\ntemplate <typename Scalar>\nstruct digamma_impl {\n  EIGEN_DEVICE_FUNC\n  static Scalar run(Scalar x) {\n    /*\n     *\n     *     Psi (digamma) function (modified for Eigen)\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double x, y, psi();\n     *\n     * y = psi( x );\n     *\n     *\n     * DESCRIPTION:\n     *\n     *              d      -\n     *   psi(x)  =  -- ln | (x)\n     *              dx\n     *\n     * is the logarithmic derivative of the gamma function.\n     * For integer x,\n     *                   n-1\n     *                    -\n     * psi(n) = -EUL  +   >  1/k.\n     *                    -\n     *                   k=1\n     *\n     * If x is negative, it is transformed to a positive argument by the\n     * reflection formula  psi(1-x) = psi(x) + pi cot(pi x).\n     * For general positive x, the argument is made greater than 10\n     * using the recurrence  psi(x+1) = psi(x) + 1/x.\n     * Then the following asymptotic expansion is applied:\n     *\n     *                           inf.   B\n     *                            -      2k\n     * psi(x) = log(x) - 1/2x -   >   -------\n     *                            -        2k\n     *                           k=1   2k x\n     *\n     * where the B2k are Bernoulli numbers.\n     *\n     * ACCURACY (float):\n     *    Relative error (except absolute when |psi| < 1):\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0,30        30000       1.3e-15     1.4e-16\n     *    IEEE      -30,0       40000       1.5e-15     2.2e-16\n     *\n     * ACCURACY (double):\n     *    Absolute error,  relative when |psi| > 1 :\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      -33,0        30000      8.2e-7      1.2e-7\n     *    IEEE      0,33        100000      7.3e-7      7.7e-8\n     *\n     * ERROR MESSAGES:\n     *     message         condition      value returned\n     * psi singularity    x integer <=0      INFINITY\n     */\n\n    Scalar p, q, nz, s, w, y;\n    bool negative = false;\n\n    const Scalar nan = NumTraits<Scalar>::quiet_NaN();\n    const Scalar m_pi = Scalar(EIGEN_PI);\n\n    const Scalar zero = Scalar(0);\n    const Scalar one = Scalar(1);\n    const Scalar half = Scalar(0.5);\n    nz = zero;\n\n    if (x <= zero) {\n      negative = true;\n      q = x;\n      p = numext::floor(q);\n      if (p == q) {\n        return nan;\n      }\n      /* Remove the zeros of tan(m_pi x)\n       * by subtracting the nearest integer from x\n       */\n      nz = q - p;\n      if (nz != half) {\n        if (nz > half) {\n          p += one;\n          nz = q - p;\n        }\n        nz = m_pi / numext::tan(m_pi * nz);\n      }\n      else {\n        nz = zero;\n      }\n      x = one - x;\n    }\n\n    /* use the recurrence psi(x+1) = psi(x) + 1/x. */\n    s = x;\n    w = zero;\n    while (s < Scalar(10)) {\n      w += one / s;\n      s += one;\n    }\n\n    y = digamma_impl_maybe_poly<Scalar>::run(s);\n\n    y = numext::log(s) - (half / s) - y - w;\n\n    return (negative) ? y - nz : y;\n  }\n};\n\n/****************************************************************************\n * Implementation of erf, requires C++11/C99                                *\n ****************************************************************************/\n\n/** \\internal \\returns the error function of \\a a (coeff-wise)\n    Doesn't do anything fancy, just a 13/8-degree rational interpolant which\n    is accurate up to a couple of ulp in the range [-4, 4], outside of which\n    fl(erf(x)) = +/-1.\n\n    This implementation works on both scalars and Ts.\n*/\ntemplate <typename T>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T generic_fast_erf_float(const T& a_x) {\n  // Clamp the inputs to the range [-4, 4] since anything outside\n  // this range is +/-1.0f in single-precision.\n  const T plus_4 = pset1<T>(4.f);\n  const T minus_4 = pset1<T>(-4.f);\n  const T x = pmax(pmin(a_x, plus_4), minus_4);\n  // The monomial coefficients of the numerator polynomial (odd).\n  const T alpha_1 = pset1<T>(-1.60960333262415e-02f);\n  const T alpha_3 = pset1<T>(-2.95459980854025e-03f);\n  const T alpha_5 = pset1<T>(-7.34990630326855e-04f);\n  const T alpha_7 = pset1<T>(-5.69250639462346e-05f);\n  const T alpha_9 = pset1<T>(-2.10102402082508e-06f);\n  const T alpha_11 = pset1<T>(2.77068142495902e-08f);\n  const T alpha_13 = pset1<T>(-2.72614225801306e-10f);\n\n  // The monomial coefficients of the denominator polynomial (even).\n  const T beta_0 = pset1<T>(-1.42647390514189e-02f);\n  const T beta_2 = pset1<T>(-7.37332916720468e-03f);\n  const T beta_4 = pset1<T>(-1.68282697438203e-03f);\n  const T beta_6 = pset1<T>(-2.13374055278905e-04f);\n  const T beta_8 = pset1<T>(-1.45660718464996e-05f);\n\n  // Since the polynomials are odd/even, we need x^2.\n  const T x2 = pmul(x, x);\n\n  // Evaluate the numerator polynomial p.\n  T p = pmadd(x2, alpha_13, alpha_11);\n  p = pmadd(x2, p, alpha_9);\n  p = pmadd(x2, p, alpha_7);\n  p = pmadd(x2, p, alpha_5);\n  p = pmadd(x2, p, alpha_3);\n  p = pmadd(x2, p, alpha_1);\n  p = pmul(x, p);\n\n  // Evaluate the denominator polynomial p.\n  T q = pmadd(x2, beta_8, beta_6);\n  q = pmadd(x2, q, beta_4);\n  q = pmadd(x2, q, beta_2);\n  q = pmadd(x2, q, beta_0);\n\n  // Divide the numerator by the denominator.\n  return pdiv(p, q);\n}\n\ntemplate <typename T>\nstruct erf_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE T run(const T& x) {\n    return generic_fast_erf_float(x);\n  }\n};\n\ntemplate <typename Scalar>\nstruct erf_retval {\n  typedef Scalar type;\n};\n\n#if EIGEN_HAS_C99_MATH\ntemplate <>\nstruct erf_impl<float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE float run(float x) {\n#if defined(SYCL_DEVICE_ONLY)\n    return cl::sycl::erf(x);\n#else\n    return generic_fast_erf_float(x);\n#endif\n  }\n};\n\ntemplate <>\nstruct erf_impl<double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE double run(double x) {\n#if defined(SYCL_DEVICE_ONLY)\n    return cl::sycl::erf(x);\n#else\n    return ::erf(x);\n#endif\n  }\n};\n#endif  // EIGEN_HAS_C99_MATH\n\n/***************************************************************************\n* Implementation of erfc, requires C++11/C99                               *\n****************************************************************************/\n\ntemplate <typename Scalar>\nstruct erfc_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar run(const Scalar) {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar, Scalar>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return Scalar(0);\n  }\n};\n\ntemplate <typename Scalar>\nstruct erfc_retval {\n  typedef Scalar type;\n};\n\n#if EIGEN_HAS_C99_MATH\ntemplate <>\nstruct erfc_impl<float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE float run(const float x) {\n#if defined(SYCL_DEVICE_ONLY)\n    return cl::sycl::erfc(x);\n#else\n    return ::erfcf(x);\n#endif\n  }\n};\n\ntemplate <>\nstruct erfc_impl<double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE double run(const double x) {\n#if defined(SYCL_DEVICE_ONLY)\n    return cl::sycl::erfc(x);\n#else\n    return ::erfc(x);\n#endif\n  }\n};\n#endif  // EIGEN_HAS_C99_MATH\n\n\n/***************************************************************************\n* Implementation of ndtri.                                                 *\n****************************************************************************/\n\n/* Inverse of Normal distribution function (modified for Eigen).\n *\n *\n * SYNOPSIS:\n *\n * double x, y, ndtri();\n *\n * x = ndtri( y );\n *\n *\n *\n * DESCRIPTION:\n *\n * Returns the argument, x, for which the area under the\n * Gaussian probability density function (integrated from\n * minus infinity to x) is equal to y.\n *\n *\n * For small arguments 0 < y < exp(-2), the program computes\n * z = sqrt( -2.0 * log(y) );  then the approximation is\n * x = z - log(z)/z  - (1/z) P(1/z) / Q(1/z).\n * There are two rational functions P/Q, one for 0 < y < exp(-32)\n * and the other for y up to exp(-2).  For larger arguments,\n * w = y - 0.5, and  x/sqrt(2pi) = w + w**3 R(w**2)/S(w**2)).\n *\n *\n * ACCURACY:\n *\n *                      Relative error:\n * arithmetic   domain        # trials      peak         rms\n *    DEC      0.125, 1         5500       9.5e-17     2.1e-17\n *    DEC      6e-39, 0.135     3500       5.7e-17     1.3e-17\n *    IEEE     0.125, 1        20000       7.2e-16     1.3e-16\n *    IEEE     3e-308, 0.135   50000       4.6e-16     9.8e-17\n *\n *\n * ERROR MESSAGES:\n *\n *   message         condition    value returned\n * ndtri domain       x <= 0        -MAXNUM\n * ndtri domain       x >= 1         MAXNUM\n *\n */\n /*\n   Cephes Math Library Release 2.2: June, 1992\n   Copyright 1985, 1987, 1992 by Stephen L. Moshier\n   Direct inquiries to 30 Frost Street, Cambridge, MA 02140\n */\n\n\n// TODO: Add a cheaper approximation for float.\n\n\ntemplate<typename T>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T flipsign(\n    const T& should_flipsign, const T& x) {\n  typedef typename unpacket_traits<T>::type Scalar;\n  const T sign_mask = pset1<T>(Scalar(-0.0));\n  T sign_bit = pand<T>(should_flipsign, sign_mask);\n  return pxor<T>(sign_bit, x);\n}\n\ntemplate<>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double flipsign<double>(\n    const double& should_flipsign, const double& x) {\n  return should_flipsign == 0 ? x : -x;\n}\n\ntemplate<>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float flipsign<float>(\n    const float& should_flipsign, const float& x) {\n  return should_flipsign == 0 ? x : -x;\n}\n\n// We split this computation in to two so that in the scalar path\n// only one branch is evaluated (due to our template specialization of pselect\n// being an if statement.)\n\ntemplate <typename T, typename ScalarType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T generic_ndtri_gt_exp_neg_two(const T& b) {\n  const ScalarType p0[] = {\n    ScalarType(-5.99633501014107895267e1),\n    ScalarType(9.80010754185999661536e1),\n    ScalarType(-5.66762857469070293439e1),\n    ScalarType(1.39312609387279679503e1),\n    ScalarType(-1.23916583867381258016e0)\n  };\n  const ScalarType q0[] = {\n    ScalarType(1.0),\n    ScalarType(1.95448858338141759834e0),\n    ScalarType(4.67627912898881538453e0),\n    ScalarType(8.63602421390890590575e1),\n    ScalarType(-2.25462687854119370527e2),\n    ScalarType(2.00260212380060660359e2),\n    ScalarType(-8.20372256168333339912e1),\n    ScalarType(1.59056225126211695515e1),\n    ScalarType(-1.18331621121330003142e0)\n  };\n  const T sqrt2pi = pset1<T>(ScalarType(2.50662827463100050242e0));\n  const T half = pset1<T>(ScalarType(0.5));\n  T c, c2, ndtri_gt_exp_neg_two;\n\n  c = psub(b, half);\n  c2 = pmul(c, c);\n  ndtri_gt_exp_neg_two = pmadd(c, pmul(\n      c2, pdiv(\n          internal::ppolevl<T, 4>::run(c2, p0),\n          internal::ppolevl<T, 8>::run(c2, q0))), c);\n  return pmul(ndtri_gt_exp_neg_two, sqrt2pi);\n}\n\ntemplate <typename T, typename ScalarType>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE T generic_ndtri_lt_exp_neg_two(\n    const T& b, const T& should_flipsign) {\n  /* Approximation for interval z = sqrt(-2 log a ) between 2 and 8\n   * i.e., a between exp(-2) = .135 and exp(-32) = 1.27e-14.\n   */\n  const ScalarType p1[] = {\n    ScalarType(4.05544892305962419923e0),\n    ScalarType(3.15251094599893866154e1),\n    ScalarType(5.71628192246421288162e1),\n    ScalarType(4.40805073893200834700e1),\n    ScalarType(1.46849561928858024014e1),\n    ScalarType(2.18663306850790267539e0),\n    ScalarType(-1.40256079171354495875e-1),\n    ScalarType(-3.50424626827848203418e-2),\n    ScalarType(-8.57456785154685413611e-4)\n  };\n  const ScalarType q1[] = {\n    ScalarType(1.0),\n    ScalarType(1.57799883256466749731e1),\n    ScalarType(4.53907635128879210584e1),\n    ScalarType(4.13172038254672030440e1),\n    ScalarType(1.50425385692907503408e1),\n    ScalarType(2.50464946208309415979e0),\n    ScalarType(-1.42182922854787788574e-1),\n    ScalarType(-3.80806407691578277194e-2),\n    ScalarType(-9.33259480895457427372e-4)\n  };\n  /* Approximation for interval z = sqrt(-2 log a ) between 8 and 64\n   * i.e., a between exp(-32) = 1.27e-14 and exp(-2048) = 3.67e-890.\n   */\n  const ScalarType p2[] = {\n    ScalarType(3.23774891776946035970e0),\n    ScalarType(6.91522889068984211695e0),\n    ScalarType(3.93881025292474443415e0),\n    ScalarType(1.33303460815807542389e0),\n    ScalarType(2.01485389549179081538e-1),\n    ScalarType(1.23716634817820021358e-2),\n    ScalarType(3.01581553508235416007e-4),\n    ScalarType(2.65806974686737550832e-6),\n    ScalarType(6.23974539184983293730e-9)\n  };\n  const ScalarType q2[] = {\n    ScalarType(1.0),\n    ScalarType(6.02427039364742014255e0),\n    ScalarType(3.67983563856160859403e0),\n    ScalarType(1.37702099489081330271e0),\n    ScalarType(2.16236993594496635890e-1),\n    ScalarType(1.34204006088543189037e-2),\n    ScalarType(3.28014464682127739104e-4),\n    ScalarType(2.89247864745380683936e-6),\n    ScalarType(6.79019408009981274425e-9)\n  };\n  const T eight = pset1<T>(ScalarType(8.0));\n  const T one = pset1<T>(ScalarType(1));\n  const T neg_two = pset1<T>(ScalarType(-2));\n  T x, x0, x1, z;\n\n  x = psqrt(pmul(neg_two, plog(b)));\n  x0 = psub(x, pdiv(plog(x), x));\n  z = pdiv(one, x);\n  x1 = pmul(\n      z, pselect(\n          pcmp_lt(x, eight),\n          pdiv(internal::ppolevl<T, 8>::run(z, p1),\n               internal::ppolevl<T, 8>::run(z, q1)),\n          pdiv(internal::ppolevl<T, 8>::run(z, p2),\n               internal::ppolevl<T, 8>::run(z, q2))));\n  return flipsign(should_flipsign, psub(x0, x1));\n}\n\ntemplate <typename T, typename ScalarType>\nEIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\nT generic_ndtri(const T& a) {\n  const T maxnum = pset1<T>(NumTraits<ScalarType>::infinity());\n  const T neg_maxnum = pset1<T>(-NumTraits<ScalarType>::infinity());\n\n  const T zero = pset1<T>(ScalarType(0));\n  const T one = pset1<T>(ScalarType(1));\n  // exp(-2)\n  const T exp_neg_two = pset1<T>(ScalarType(0.13533528323661269189));\n  T b, ndtri, should_flipsign;\n\n  should_flipsign = pcmp_le(a, psub(one, exp_neg_two));\n  b = pselect(should_flipsign, a, psub(one, a));\n\n  ndtri = pselect(\n      pcmp_lt(exp_neg_two, b),\n      generic_ndtri_gt_exp_neg_two<T, ScalarType>(b),\n      generic_ndtri_lt_exp_neg_two<T, ScalarType>(b, should_flipsign));\n\n  return pselect(\n      pcmp_le(a, zero), neg_maxnum,\n      pselect(pcmp_le(one, a), maxnum, ndtri));\n}\n\ntemplate <typename Scalar>\nstruct ndtri_retval {\n  typedef Scalar type;\n};\n\n#if !EIGEN_HAS_C99_MATH\n\ntemplate <typename Scalar>\nstruct ndtri_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar run(const Scalar) {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar, Scalar>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return Scalar(0);\n  }\n};\n\n# else\n\ntemplate <typename Scalar>\nstruct ndtri_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar run(const Scalar x) {\n    return generic_ndtri<Scalar, Scalar>(x);\n  }\n};\n\n#endif  // EIGEN_HAS_C99_MATH\n\n\n/**************************************************************************************************************\n * Implementation of igammac (complemented incomplete gamma integral), based on Cephes but requires C++11/C99 *\n **************************************************************************************************************/\n\ntemplate <typename Scalar>\nstruct igammac_retval {\n  typedef Scalar type;\n};\n\n// NOTE: cephes_helper is also used to implement zeta\ntemplate <typename Scalar>\nstruct cephes_helper {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar machep() { assert(false && \"machep not supported for this type\"); return 0.0; }\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar big() { assert(false && \"big not supported for this type\"); return 0.0; }\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar biginv() { assert(false && \"biginv not supported for this type\"); return 0.0; }\n};\n\ntemplate <>\nstruct cephes_helper<float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE float machep() {\n    return NumTraits<float>::epsilon() / 2;  // 1.0 - machep == 1.0\n  }\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE float big() {\n    // use epsneg (1.0 - epsneg == 1.0)\n    return 1.0f / (NumTraits<float>::epsilon() / 2);\n  }\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE float biginv() {\n    // epsneg\n    return machep();\n  }\n};\n\ntemplate <>\nstruct cephes_helper<double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE double machep() {\n    return NumTraits<double>::epsilon() / 2;  // 1.0 - machep == 1.0\n  }\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE double big() {\n    return 1.0 / NumTraits<double>::epsilon();\n  }\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE double biginv() {\n    // inverse of eps\n    return NumTraits<double>::epsilon();\n  }\n};\n\nenum IgammaComputationMode { VALUE, DERIVATIVE, SAMPLE_DERIVATIVE };\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC\nstatic EIGEN_STRONG_INLINE Scalar main_igamma_term(Scalar a, Scalar x) {\n    /* Compute  x**a * exp(-x) / gamma(a)  */\n    Scalar logax = a * numext::log(x) - x - lgamma_impl<Scalar>::run(a);\n    if (logax < -numext::log(NumTraits<Scalar>::highest()) ||\n        // Assuming x and a aren't Nan.\n        (numext::isnan)(logax)) {\n      return Scalar(0);\n    }\n    return numext::exp(logax);\n}\n\ntemplate <typename Scalar, IgammaComputationMode mode>\nEIGEN_DEVICE_FUNC\nint igamma_num_iterations() {\n  /* Returns the maximum number of internal iterations for igamma computation.\n   */\n  if (mode == VALUE) {\n    return 2000;\n  }\n\n  if (internal::is_same<Scalar, float>::value) {\n    return 200;\n  } else if (internal::is_same<Scalar, double>::value) {\n    return 500;\n  } else {\n    return 2000;\n  }\n}\n\ntemplate <typename Scalar, IgammaComputationMode mode>\nstruct igammac_cf_impl {\n  /* Computes igamc(a, x) or derivative (depending on the mode)\n   * using the continued fraction expansion of the complementary\n   * incomplete Gamma function.\n   *\n   * Preconditions:\n   *   a > 0\n   *   x >= 1\n   *   x >= a\n   */\n  EIGEN_DEVICE_FUNC\n  static Scalar run(Scalar a, Scalar x) {\n    const Scalar zero = 0;\n    const Scalar one = 1;\n    const Scalar two = 2;\n    const Scalar machep = cephes_helper<Scalar>::machep();\n    const Scalar big = cephes_helper<Scalar>::big();\n    const Scalar biginv = cephes_helper<Scalar>::biginv();\n\n    if ((numext::isinf)(x)) {\n      return zero;\n    }\n\n    Scalar ax = main_igamma_term<Scalar>(a, x);\n    // This is independent of mode. If this value is zero,\n    // then the function value is zero. If the function value is zero,\n    // then we are in a neighborhood where the function value evalutes to zero,\n    // so the derivative is zero.\n    if (ax == zero) {\n      return zero;\n    }\n\n    // continued fraction\n    Scalar y = one - a;\n    Scalar z = x + y + one;\n    Scalar c = zero;\n    Scalar pkm2 = one;\n    Scalar qkm2 = x;\n    Scalar pkm1 = x + one;\n    Scalar qkm1 = z * x;\n    Scalar ans = pkm1 / qkm1;\n\n    Scalar dpkm2_da = zero;\n    Scalar dqkm2_da = zero;\n    Scalar dpkm1_da = zero;\n    Scalar dqkm1_da = -x;\n    Scalar dans_da = (dpkm1_da - ans * dqkm1_da) / qkm1;\n\n    for (int i = 0; i < igamma_num_iterations<Scalar, mode>(); i++) {\n      c += one;\n      y += one;\n      z += two;\n\n      Scalar yc = y * c;\n      Scalar pk = pkm1 * z - pkm2 * yc;\n      Scalar qk = qkm1 * z - qkm2 * yc;\n\n      Scalar dpk_da = dpkm1_da * z - pkm1 - dpkm2_da * yc + pkm2 * c;\n      Scalar dqk_da = dqkm1_da * z - qkm1 - dqkm2_da * yc + qkm2 * c;\n\n      if (qk != zero) {\n        Scalar ans_prev = ans;\n        ans = pk / qk;\n\n        Scalar dans_da_prev = dans_da;\n        dans_da = (dpk_da - ans * dqk_da) / qk;\n\n        if (mode == VALUE) {\n          if (numext::abs(ans_prev - ans) <= machep * numext::abs(ans)) {\n            break;\n          }\n        } else {\n          if (numext::abs(dans_da - dans_da_prev) <= machep) {\n            break;\n          }\n        }\n      }\n\n      pkm2 = pkm1;\n      pkm1 = pk;\n      qkm2 = qkm1;\n      qkm1 = qk;\n\n      dpkm2_da = dpkm1_da;\n      dpkm1_da = dpk_da;\n      dqkm2_da = dqkm1_da;\n      dqkm1_da = dqk_da;\n\n      if (numext::abs(pk) > big) {\n        pkm2 *= biginv;\n        pkm1 *= biginv;\n        qkm2 *= biginv;\n        qkm1 *= biginv;\n\n        dpkm2_da *= biginv;\n        dpkm1_da *= biginv;\n        dqkm2_da *= biginv;\n        dqkm1_da *= biginv;\n      }\n    }\n\n    /* Compute  x**a * exp(-x) / gamma(a)  */\n    Scalar dlogax_da = numext::log(x) - digamma_impl<Scalar>::run(a);\n    Scalar dax_da = ax * dlogax_da;\n\n    switch (mode) {\n      case VALUE:\n        return ans * ax;\n      case DERIVATIVE:\n        return ans * dax_da + dans_da * ax;\n      case SAMPLE_DERIVATIVE:\n      default: // this is needed to suppress clang warning\n        return -(dans_da + ans * dlogax_da) * x;\n    }\n  }\n};\n\ntemplate <typename Scalar, IgammaComputationMode mode>\nstruct igamma_series_impl {\n  /* Computes igam(a, x) or its derivative (depending on the mode)\n   * using the series expansion of the incomplete Gamma function.\n   *\n   * Preconditions:\n   *   x > 0\n   *   a > 0\n   *   !(x > 1 && x > a)\n   */\n  EIGEN_DEVICE_FUNC\n  static Scalar run(Scalar a, Scalar x) {\n    const Scalar zero = 0;\n    const Scalar one = 1;\n    const Scalar machep = cephes_helper<Scalar>::machep();\n\n    Scalar ax = main_igamma_term<Scalar>(a, x);\n\n    // This is independent of mode. If this value is zero,\n    // then the function value is zero. If the function value is zero,\n    // then we are in a neighborhood where the function value evalutes to zero,\n    // so the derivative is zero.\n    if (ax == zero) {\n      return zero;\n    }\n\n    ax /= a;\n\n    /* power series */\n    Scalar r = a;\n    Scalar c = one;\n    Scalar ans = one;\n\n    Scalar dc_da = zero;\n    Scalar dans_da = zero;\n\n    for (int i = 0; i < igamma_num_iterations<Scalar, mode>(); i++) {\n      r += one;\n      Scalar term = x / r;\n      Scalar dterm_da = -x / (r * r);\n      dc_da = term * dc_da + dterm_da * c;\n      dans_da += dc_da;\n      c *= term;\n      ans += c;\n\n      if (mode == VALUE) {\n        if (c <= machep * ans) {\n          break;\n        }\n      } else {\n        if (numext::abs(dc_da) <= machep * numext::abs(dans_da)) {\n          break;\n        }\n      }\n    }\n\n    Scalar dlogax_da = numext::log(x) - digamma_impl<Scalar>::run(a + one);\n    Scalar dax_da = ax * dlogax_da;\n\n    switch (mode) {\n      case VALUE:\n        return ans * ax;\n      case DERIVATIVE:\n        return ans * dax_da + dans_da * ax;\n      case SAMPLE_DERIVATIVE:\n      default: // this is needed to suppress clang warning\n        return -(dans_da + ans * dlogax_da) * x / a;\n    }\n  }\n};\n\n#if !EIGEN_HAS_C99_MATH\n\ntemplate <typename Scalar>\nstruct igammac_impl {\n  EIGEN_DEVICE_FUNC\n  static Scalar run(Scalar a, Scalar x) {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar, Scalar>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return Scalar(0);\n  }\n};\n\n#else\n\ntemplate <typename Scalar>\nstruct igammac_impl {\n  EIGEN_DEVICE_FUNC\n  static Scalar run(Scalar a, Scalar x) {\n    /*  igamc()\n     *\n     *\tIncomplete gamma integral (modified for Eigen)\n     *\n     *\n     *\n     * SYNOPSIS:\n     *\n     * double a, x, y, igamc();\n     *\n     * y = igamc( a, x );\n     *\n     * DESCRIPTION:\n     *\n     * The function is defined by\n     *\n     *\n     *  igamc(a,x)   =   1 - igam(a,x)\n     *\n     *                            inf.\n     *                              -\n     *                     1       | |  -t  a-1\n     *               =   -----     |   e   t   dt.\n     *                    -      | |\n     *                   | (a)    -\n     *                             x\n     *\n     *\n     * In this implementation both arguments must be positive.\n     * The integral is evaluated by either a power series or\n     * continued fraction expansion, depending on the relative\n     * values of a and x.\n     *\n     * ACCURACY (float):\n     *\n     *                      Relative error:\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0,30        30000       7.8e-6      5.9e-7\n     *\n     *\n     * ACCURACY (double):\n     *\n     * Tested at random a, x.\n     *                a         x                      Relative error:\n     * arithmetic   domain   domain     # trials      peak         rms\n     *    IEEE     0.5,100   0,100      200000       1.9e-14     1.7e-15\n     *    IEEE     0.01,0.5  0,100      200000       1.4e-13     1.6e-15\n     *\n     */\n    /*\n      Cephes Math Library Release 2.2: June, 1992\n      Copyright 1985, 1987, 1992 by Stephen L. Moshier\n      Direct inquiries to 30 Frost Street, Cambridge, MA 02140\n    */\n    const Scalar zero = 0;\n    const Scalar one = 1;\n    const Scalar nan = NumTraits<Scalar>::quiet_NaN();\n\n    if ((x < zero) || (a <= zero)) {\n      // domain error\n      return nan;\n    }\n\n    if ((numext::isnan)(a) || (numext::isnan)(x)) {  // propagate nans\n      return nan;\n    }\n\n    if ((x < one) || (x < a)) {\n      return (one - igamma_series_impl<Scalar, VALUE>::run(a, x));\n    }\n\n    return igammac_cf_impl<Scalar, VALUE>::run(a, x);\n  }\n};\n\n#endif  // EIGEN_HAS_C99_MATH\n\n/************************************************************************************************\n * Implementation of igamma (incomplete gamma integral), based on Cephes but requires C++11/C99 *\n ************************************************************************************************/\n\n#if !EIGEN_HAS_C99_MATH\n\ntemplate <typename Scalar, IgammaComputationMode mode>\nstruct igamma_generic_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar run(Scalar a, Scalar x) {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar, Scalar>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return Scalar(0);\n  }\n};\n\n#else\n\ntemplate <typename Scalar, IgammaComputationMode mode>\nstruct igamma_generic_impl {\n  EIGEN_DEVICE_FUNC\n  static Scalar run(Scalar a, Scalar x) {\n    /* Depending on the mode, returns\n     * - VALUE: incomplete Gamma function igamma(a, x)\n     * - DERIVATIVE: derivative of incomplete Gamma function d/da igamma(a, x)\n     * - SAMPLE_DERIVATIVE: implicit derivative of a Gamma random variable\n     * x ~ Gamma(x | a, 1), dx/da = -1 / Gamma(x | a, 1) * d igamma(a, x) / dx\n     *\n     * Derivatives are implemented by forward-mode differentiation.\n     */\n    const Scalar zero = 0;\n    const Scalar one = 1;\n    const Scalar nan = NumTraits<Scalar>::quiet_NaN();\n\n    if (x == zero) return zero;\n\n    if ((x < zero) || (a <= zero)) {  // domain error\n      return nan;\n    }\n\n    if ((numext::isnan)(a) || (numext::isnan)(x)) {  // propagate nans\n      return nan;\n    }\n\n    if ((x > one) && (x > a)) {\n      Scalar ret = igammac_cf_impl<Scalar, mode>::run(a, x);\n      if (mode == VALUE) {\n        return one - ret;\n      } else {\n        return -ret;\n      }\n    }\n\n    return igamma_series_impl<Scalar, mode>::run(a, x);\n  }\n};\n\n#endif  // EIGEN_HAS_C99_MATH\n\ntemplate <typename Scalar>\nstruct igamma_retval {\n  typedef Scalar type;\n};\n\ntemplate <typename Scalar>\nstruct igamma_impl : igamma_generic_impl<Scalar, VALUE> {\n  /* igam()\n   * Incomplete gamma integral.\n   *\n   * The CDF of Gamma(a, 1) random variable at the point x.\n   *\n   * Accuracy estimation. For each a in [10^-2, 10^-1...10^3] we sample\n   * 50 Gamma random variables x ~ Gamma(x | a, 1), a total of 300 points.\n   * The ground truth is computed by mpmath. Mean absolute error:\n   * float: 1.26713e-05\n   * double: 2.33606e-12\n   *\n   * Cephes documentation below.\n   *\n   * SYNOPSIS:\n   *\n   * double a, x, y, igam();\n   *\n   * y = igam( a, x );\n   *\n   * DESCRIPTION:\n   *\n   * The function is defined by\n   *\n   *                           x\n   *                            -\n   *                   1       | |  -t  a-1\n   *  igam(a,x)  =   -----     |   e   t   dt.\n   *                  -      | |\n   *                 | (a)    -\n   *                           0\n   *\n   *\n   * In this implementation both arguments must be positive.\n   * The integral is evaluated by either a power series or\n   * continued fraction expansion, depending on the relative\n   * values of a and x.\n   *\n   * ACCURACY (double):\n   *\n   *                      Relative error:\n   * arithmetic   domain     # trials      peak         rms\n   *    IEEE      0,30       200000       3.6e-14     2.9e-15\n   *    IEEE      0,100      300000       9.9e-14     1.5e-14\n   *\n   *\n   * ACCURACY (float):\n   *\n   *                      Relative error:\n   * arithmetic   domain     # trials      peak         rms\n   *    IEEE      0,30        20000       7.8e-6      5.9e-7\n   *\n   */\n  /*\n    Cephes Math Library Release 2.2: June, 1992\n    Copyright 1985, 1987, 1992 by Stephen L. Moshier\n    Direct inquiries to 30 Frost Street, Cambridge, MA 02140\n  */\n\n  /* left tail of incomplete gamma function:\n   *\n   *          inf.      k\n   *   a  -x   -       x\n   *  x  e     >   ----------\n   *           -     -\n   *          k=0   | (a+k+1)\n   *\n   */\n};\n\ntemplate <typename Scalar>\nstruct igamma_der_a_retval : igamma_retval<Scalar> {};\n\ntemplate <typename Scalar>\nstruct igamma_der_a_impl : igamma_generic_impl<Scalar, DERIVATIVE> {\n  /* Derivative of the incomplete Gamma function with respect to a.\n   *\n   * Computes d/da igamma(a, x) by forward differentiation of the igamma code.\n   *\n   * Accuracy estimation. For each a in [10^-2, 10^-1...10^3] we sample\n   * 50 Gamma random variables x ~ Gamma(x | a, 1), a total of 300 points.\n   * The ground truth is computed by mpmath. Mean absolute error:\n   * float: 6.17992e-07\n   * double: 4.60453e-12\n   *\n   * Reference:\n   * R. Moore. \"Algorithm AS 187: Derivatives of the incomplete gamma\n   * integral\". Journal of the Royal Statistical Society. 1982\n   */\n};\n\ntemplate <typename Scalar>\nstruct gamma_sample_der_alpha_retval : igamma_retval<Scalar> {};\n\ntemplate <typename Scalar>\nstruct gamma_sample_der_alpha_impl\n    : igamma_generic_impl<Scalar, SAMPLE_DERIVATIVE> {\n  /* Derivative of a Gamma random variable sample with respect to alpha.\n   *\n   * Consider a sample of a Gamma random variable with the concentration\n   * parameter alpha: sample ~ Gamma(alpha, 1). The reparameterization\n   * derivative that we want to compute is dsample / dalpha =\n   * d igammainv(alpha, u) / dalpha, where u = igamma(alpha, sample).\n   * However, this formula is numerically unstable and expensive, so instead\n   * we use implicit differentiation:\n   *\n   * igamma(alpha, sample) = u, where u ~ Uniform(0, 1).\n   * Apply d / dalpha to both sides:\n   * d igamma(alpha, sample) / dalpha\n   *     + d igamma(alpha, sample) / dsample * dsample/dalpha  = 0\n   * d igamma(alpha, sample) / dalpha\n   *     + Gamma(sample | alpha, 1) dsample / dalpha = 0\n   * dsample/dalpha = - (d igamma(alpha, sample) / dalpha)\n   *                   / Gamma(sample | alpha, 1)\n   *\n   * Here Gamma(sample | alpha, 1) is the PDF of the Gamma distribution\n   * (note that the derivative of the CDF w.r.t. sample is the PDF).\n   * See the reference below for more details.\n   *\n   * The derivative of igamma(alpha, sample) is computed by forward\n   * differentiation of the igamma code. Division by the Gamma PDF is performed\n   * in the same code, increasing the accuracy and speed due to cancellation\n   * of some terms.\n   *\n   * Accuracy estimation. For each alpha in [10^-2, 10^-1...10^3] we sample\n   * 50 Gamma random variables sample ~ Gamma(sample | alpha, 1), a total of 300\n   * points. The ground truth is computed by mpmath. Mean absolute error:\n   * float: 2.1686e-06\n   * double: 1.4774e-12\n   *\n   * Reference:\n   * M. Figurnov, S. Mohamed, A. Mnih \"Implicit Reparameterization Gradients\".\n   * 2018\n   */\n};\n\n/*****************************************************************************\n * Implementation of Riemann zeta function of two arguments, based on Cephes *\n *****************************************************************************/\n\ntemplate <typename Scalar>\nstruct zeta_retval {\n    typedef Scalar type;\n};\n\ntemplate <typename Scalar>\nstruct zeta_impl_series {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar run(const Scalar) {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar, Scalar>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return Scalar(0);\n  }\n};\n\ntemplate <>\nstruct zeta_impl_series<float> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE bool run(float& a, float& b, float& s, const float x, const float machep) {\n    int i = 0;\n    while(i < 9)\n    {\n        i += 1;\n        a += 1.0f;\n        b = numext::pow( a, -x );\n        s += b;\n        if( numext::abs(b/s) < machep )\n            return true;\n    }\n\n    //Return whether we are done\n    return false;\n  }\n};\n\ntemplate <>\nstruct zeta_impl_series<double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE bool run(double& a, double& b, double& s, const double x, const double machep) {\n    int i = 0;\n    while( (i < 9) || (a <= 9.0) )\n    {\n        i += 1;\n        a += 1.0;\n        b = numext::pow( a, -x );\n        s += b;\n        if( numext::abs(b/s) < machep )\n            return true;\n    }\n\n    //Return whether we are done\n    return false;\n  }\n};\n\ntemplate <typename Scalar>\nstruct zeta_impl {\n    EIGEN_DEVICE_FUNC\n    static Scalar run(Scalar x, Scalar q) {\n        /*\t\t\t\t\t\t\tzeta.c\n         *\n         *\tRiemann zeta function of two arguments\n         *\n         *\n         *\n         * SYNOPSIS:\n         *\n         * double x, q, y, zeta();\n         *\n         * y = zeta( x, q );\n         *\n         *\n         *\n         * DESCRIPTION:\n         *\n         *\n         *\n         *                 inf.\n         *                  -        -x\n         *   zeta(x,q)  =   >   (k+q)\n         *                  -\n         *                 k=0\n         *\n         * where x > 1 and q is not a negative integer or zero.\n         * The Euler-Maclaurin summation formula is used to obtain\n         * the expansion\n         *\n         *                n\n         *                -       -x\n         * zeta(x,q)  =   >  (k+q)\n         *                -\n         *               k=1\n         *\n         *           1-x                 inf.  B   x(x+1)...(x+2j)\n         *      (n+q)           1         -     2j\n         *  +  ---------  -  -------  +   >    --------------------\n         *        x-1              x      -                   x+2j+1\n         *                   2(n+q)      j=1       (2j)! (n+q)\n         *\n         * where the B2j are Bernoulli numbers.  Note that (see zetac.c)\n         * zeta(x,1) = zetac(x) + 1.\n         *\n         *\n         *\n         * ACCURACY:\n         *\n         * Relative error for single precision:\n         * arithmetic   domain     # trials      peak         rms\n         *    IEEE      0,25        10000       6.9e-7      1.0e-7\n         *\n         * Large arguments may produce underflow in powf(), in which\n         * case the results are inaccurate.\n         *\n         * REFERENCE:\n         *\n         * Gradshteyn, I. S., and I. M. Ryzhik, Tables of Integrals,\n         * Series, and Products, p. 1073; Academic Press, 1980.\n         *\n         */\n\n        int i;\n        Scalar p, r, a, b, k, s, t, w;\n\n        const Scalar A[] = {\n            Scalar(12.0),\n            Scalar(-720.0),\n            Scalar(30240.0),\n            Scalar(-1209600.0),\n            Scalar(47900160.0),\n            Scalar(-1.8924375803183791606e9), /*1.307674368e12/691*/\n            Scalar(7.47242496e10),\n            Scalar(-2.950130727918164224e12), /*1.067062284288e16/3617*/\n            Scalar(1.1646782814350067249e14), /*5.109094217170944e18/43867*/\n            Scalar(-4.5979787224074726105e15), /*8.028576626982912e20/174611*/\n            Scalar(1.8152105401943546773e17), /*1.5511210043330985984e23/854513*/\n            Scalar(-7.1661652561756670113e18) /*1.6938241367317436694528e27/236364091*/\n            };\n\n        const Scalar maxnum = NumTraits<Scalar>::infinity();\n        const Scalar zero = 0.0, half = 0.5, one = 1.0;\n        const Scalar machep = cephes_helper<Scalar>::machep();\n        const Scalar nan = NumTraits<Scalar>::quiet_NaN();\n\n        if( x == one )\n            return maxnum;\n\n        if( x < one )\n        {\n            return nan;\n        }\n\n        if( q <= zero )\n        {\n            if(q == numext::floor(q))\n            {\n                if (x == numext::floor(x) && long(x) % 2 == 0) {\n                    return maxnum;\n                }\n                else {\n                    return nan;\n                }\n            }\n            p = x;\n            r = numext::floor(p);\n            if (p != r)\n                return nan;\n        }\n\n        /* Permit negative q but continue sum until n+q > +9 .\n         * This case should be handled by a reflection formula.\n         * If q<0 and x is an integer, there is a relation to\n         * the polygamma function.\n         */\n        s = numext::pow( q, -x );\n        a = q;\n        b = zero;\n        // Run the summation in a helper function that is specific to the floating precision\n        if (zeta_impl_series<Scalar>::run(a, b, s, x, machep)) {\n            return s;\n        }\n\n        w = a;\n        s += b*w/(x-one);\n        s -= half * b;\n        a = one;\n        k = zero;\n        for( i=0; i<12; i++ )\n        {\n            a *= x + k;\n            b /= w;\n            t = a*b/A[i];\n            s = s + t;\n            t = numext::abs(t/s);\n            if( t < machep ) {\n              break;\n            }\n            k += one;\n            a *= x + k;\n            b /= w;\n            k += one;\n        }\n        return s;\n  }\n};\n\n/****************************************************************************\n * Implementation of polygamma function, requires C++11/C99                 *\n ****************************************************************************/\n\ntemplate <typename Scalar>\nstruct polygamma_retval {\n    typedef Scalar type;\n};\n\n#if !EIGEN_HAS_C99_MATH\n\ntemplate <typename Scalar>\nstruct polygamma_impl {\n    EIGEN_DEVICE_FUNC\n    static EIGEN_STRONG_INLINE Scalar run(Scalar n, Scalar x) {\n        EIGEN_STATIC_ASSERT((internal::is_same<Scalar, Scalar>::value == false),\n                            THIS_TYPE_IS_NOT_SUPPORTED);\n        return Scalar(0);\n    }\n};\n\n#else\n\ntemplate <typename Scalar>\nstruct polygamma_impl {\n    EIGEN_DEVICE_FUNC\n    static Scalar run(Scalar n, Scalar x) {\n        Scalar zero = 0.0, one = 1.0;\n        Scalar nplus = n + one;\n        const Scalar nan = NumTraits<Scalar>::quiet_NaN();\n\n        // Check that n is a non-negative integer\n        if (numext::floor(n) != n || n < zero) {\n            return nan;\n        }\n        // Just return the digamma function for n = 0\n        else if (n == zero) {\n            return digamma_impl<Scalar>::run(x);\n        }\n        // Use the same implementation as scipy\n        else {\n            Scalar factorial = numext::exp(lgamma_impl<Scalar>::run(nplus));\n            return numext::pow(-one, nplus) * factorial * zeta_impl<Scalar>::run(nplus, x);\n        }\n  }\n};\n\n#endif  // EIGEN_HAS_C99_MATH\n\n/************************************************************************************************\n * Implementation of betainc (incomplete beta integral), based on Cephes but requires C++11/C99 *\n ************************************************************************************************/\n\ntemplate <typename Scalar>\nstruct betainc_retval {\n  typedef Scalar type;\n};\n\n#if !EIGEN_HAS_C99_MATH\n\ntemplate <typename Scalar>\nstruct betainc_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar run(Scalar a, Scalar b, Scalar x) {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar, Scalar>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return Scalar(0);\n  }\n};\n\n#else\n\ntemplate <typename Scalar>\nstruct betainc_impl {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar run(Scalar, Scalar, Scalar) {\n    /*\tbetaincf.c\n     *\n     *\tIncomplete beta integral\n     *\n     *\n     * SYNOPSIS:\n     *\n     * float a, b, x, y, betaincf();\n     *\n     * y = betaincf( a, b, x );\n     *\n     *\n     * DESCRIPTION:\n     *\n     * Returns incomplete beta integral of the arguments, evaluated\n     * from zero to x.  The function is defined as\n     *\n     *                  x\n     *     -            -\n     *    | (a+b)      | |  a-1     b-1\n     *  -----------    |   t   (1-t)   dt.\n     *   -     -     | |\n     *  | (a) | (b)   -\n     *                 0\n     *\n     * The domain of definition is 0 <= x <= 1.  In this\n     * implementation a and b are restricted to positive values.\n     * The integral from x to 1 may be obtained by the symmetry\n     * relation\n     *\n     *    1 - betainc( a, b, x )  =  betainc( b, a, 1-x ).\n     *\n     * The integral is evaluated by a continued fraction expansion.\n     * If a < 1, the function calls itself recursively after a\n     * transformation to increase a to a+1.\n     *\n     * ACCURACY (float):\n     *\n     * Tested at random points (a,b,x) with a and b in the indicated\n     * interval and x between 0 and 1.\n     *\n     * arithmetic   domain     # trials      peak         rms\n     * Relative error:\n     *    IEEE       0,30       10000       3.7e-5      5.1e-6\n     *    IEEE       0,100      10000       1.7e-4      2.5e-5\n     * The useful domain for relative error is limited by underflow\n     * of the single precision exponential function.\n     * Absolute error:\n     *    IEEE       0,30      100000       2.2e-5      9.6e-7\n     *    IEEE       0,100      10000       6.5e-5      3.7e-6\n     *\n     * Larger errors may occur for extreme ratios of a and b.\n     *\n     * ACCURACY (double):\n     * arithmetic   domain     # trials      peak         rms\n     *    IEEE      0,5         10000       6.9e-15     4.5e-16\n     *    IEEE      0,85       250000       2.2e-13     1.7e-14\n     *    IEEE      0,1000      30000       5.3e-12     6.3e-13\n     *    IEEE      0,10000    250000       9.3e-11     7.1e-12\n     *    IEEE      0,100000    10000       8.7e-10     4.8e-11\n     * Outputs smaller than the IEEE gradual underflow threshold\n     * were excluded from these statistics.\n     *\n     * ERROR MESSAGES:\n     *   message         condition      value returned\n     * incbet domain      x<0, x>1          nan\n     * incbet underflow                     nan\n     */\n\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar, Scalar>::value == false),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    return Scalar(0);\n  }\n};\n\n/* Continued fraction expansion #1 for incomplete beta integral (small_branch = True)\n * Continued fraction expansion #2 for incomplete beta integral (small_branch = False)\n */\ntemplate <typename Scalar>\nstruct incbeta_cfe {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE Scalar run(Scalar a, Scalar b, Scalar x, bool small_branch) {\n    EIGEN_STATIC_ASSERT((internal::is_same<Scalar, float>::value ||\n                         internal::is_same<Scalar, double>::value),\n                        THIS_TYPE_IS_NOT_SUPPORTED);\n    const Scalar big = cephes_helper<Scalar>::big();\n    const Scalar machep = cephes_helper<Scalar>::machep();\n    const Scalar biginv = cephes_helper<Scalar>::biginv();\n\n    const Scalar zero = 0;\n    const Scalar one = 1;\n    const Scalar two = 2;\n\n    Scalar xk, pk, pkm1, pkm2, qk, qkm1, qkm2;\n    Scalar k1, k2, k3, k4, k5, k6, k7, k8, k26update;\n    Scalar ans;\n    int n;\n\n    const int num_iters = (internal::is_same<Scalar, float>::value) ? 100 : 300;\n    const Scalar thresh =\n        (internal::is_same<Scalar, float>::value) ? machep : Scalar(3) * machep;\n    Scalar r = (internal::is_same<Scalar, float>::value) ? zero : one;\n\n    if (small_branch) {\n      k1 = a;\n      k2 = a + b;\n      k3 = a;\n      k4 = a + one;\n      k5 = one;\n      k6 = b - one;\n      k7 = k4;\n      k8 = a + two;\n      k26update = one;\n    } else {\n      k1 = a;\n      k2 = b - one;\n      k3 = a;\n      k4 = a + one;\n      k5 = one;\n      k6 = a + b;\n      k7 = a + one;\n      k8 = a + two;\n      k26update = -one;\n      x = x / (one - x);\n    }\n\n    pkm2 = zero;\n    qkm2 = one;\n    pkm1 = one;\n    qkm1 = one;\n    ans = one;\n    n = 0;\n\n    do {\n      xk = -(x * k1 * k2) / (k3 * k4);\n      pk = pkm1 + pkm2 * xk;\n      qk = qkm1 + qkm2 * xk;\n      pkm2 = pkm1;\n      pkm1 = pk;\n      qkm2 = qkm1;\n      qkm1 = qk;\n\n      xk = (x * k5 * k6) / (k7 * k8);\n      pk = pkm1 + pkm2 * xk;\n      qk = qkm1 + qkm2 * xk;\n      pkm2 = pkm1;\n      pkm1 = pk;\n      qkm2 = qkm1;\n      qkm1 = qk;\n\n      if (qk != zero) {\n        r = pk / qk;\n        if (numext::abs(ans - r) < numext::abs(r) * thresh) {\n          return r;\n        }\n        ans = r;\n      }\n\n      k1 += one;\n      k2 += k26update;\n      k3 += two;\n      k4 += two;\n      k5 += one;\n      k6 -= k26update;\n      k7 += two;\n      k8 += two;\n\n      if ((numext::abs(qk) + numext::abs(pk)) > big) {\n        pkm2 *= biginv;\n        pkm1 *= biginv;\n        qkm2 *= biginv;\n        qkm1 *= biginv;\n      }\n      if ((numext::abs(qk) < biginv) || (numext::abs(pk) < biginv)) {\n        pkm2 *= big;\n        pkm1 *= big;\n        qkm2 *= big;\n        qkm1 *= big;\n      }\n    } while (++n < num_iters);\n\n    return ans;\n  }\n};\n\n/* Helper functions depending on the Scalar type */\ntemplate <typename Scalar>\nstruct betainc_helper {};\n\ntemplate <>\nstruct betainc_helper<float> {\n  /* Core implementation, assumes a large (> 1.0) */\n  EIGEN_DEVICE_FUNC static EIGEN_STRONG_INLINE float incbsa(float aa, float bb,\n                                                            float xx) {\n    float ans, a, b, t, x, onemx;\n    bool reversed_a_b = false;\n\n    onemx = 1.0f - xx;\n\n    /* see if x is greater than the mean */\n    if (xx > (aa / (aa + bb))) {\n      reversed_a_b = true;\n      a = bb;\n      b = aa;\n      t = xx;\n      x = onemx;\n    } else {\n      a = aa;\n      b = bb;\n      t = onemx;\n      x = xx;\n    }\n\n    /* Choose expansion for optimal convergence */\n    if (b > 10.0f) {\n      if (numext::abs(b * x / a) < 0.3f) {\n        t = betainc_helper<float>::incbps(a, b, x);\n        if (reversed_a_b) t = 1.0f - t;\n        return t;\n      }\n    }\n\n    ans = x * (a + b - 2.0f) / (a - 1.0f);\n    if (ans < 1.0f) {\n      ans = incbeta_cfe<float>::run(a, b, x, true /* small_branch */);\n      t = b * numext::log(t);\n    } else {\n      ans = incbeta_cfe<float>::run(a, b, x, false /* small_branch */);\n      t = (b - 1.0f) * numext::log(t);\n    }\n\n    t += a * numext::log(x) + lgamma_impl<float>::run(a + b) -\n         lgamma_impl<float>::run(a) - lgamma_impl<float>::run(b);\n    t += numext::log(ans / a);\n    t = numext::exp(t);\n\n    if (reversed_a_b) t = 1.0f - t;\n    return t;\n  }\n\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE float incbps(float a, float b, float x) {\n    float t, u, y, s;\n    const float machep = cephes_helper<float>::machep();\n\n    y = a * numext::log(x) + (b - 1.0f) * numext::log1p(-x) - numext::log(a);\n    y -= lgamma_impl<float>::run(a) + lgamma_impl<float>::run(b);\n    y += lgamma_impl<float>::run(a + b);\n\n    t = x / (1.0f - x);\n    s = 0.0f;\n    u = 1.0f;\n    do {\n      b -= 1.0f;\n      if (b == 0.0f) {\n        break;\n      }\n      a += 1.0f;\n      u *= t * b / a;\n      s += u;\n    } while (numext::abs(u) > machep);\n\n    return numext::exp(y) * (1.0f + s);\n  }\n};\n\ntemplate <>\nstruct betainc_impl<float> {\n  EIGEN_DEVICE_FUNC\n  static float run(float a, float b, float x) {\n    const float nan = NumTraits<float>::quiet_NaN();\n    float ans, t;\n\n    if (a <= 0.0f) return nan;\n    if (b <= 0.0f) return nan;\n    if ((x <= 0.0f) || (x >= 1.0f)) {\n      if (x == 0.0f) return 0.0f;\n      if (x == 1.0f) return 1.0f;\n      // mtherr(\"betaincf\", DOMAIN);\n      return nan;\n    }\n\n    /* transformation for small aa */\n    if (a <= 1.0f) {\n      ans = betainc_helper<float>::incbsa(a + 1.0f, b, x);\n      t = a * numext::log(x) + b * numext::log1p(-x) +\n          lgamma_impl<float>::run(a + b) - lgamma_impl<float>::run(a + 1.0f) -\n          lgamma_impl<float>::run(b);\n      return (ans + numext::exp(t));\n    } else {\n      return betainc_helper<float>::incbsa(a, b, x);\n    }\n  }\n};\n\ntemplate <>\nstruct betainc_helper<double> {\n  EIGEN_DEVICE_FUNC\n  static EIGEN_STRONG_INLINE double incbps(double a, double b, double x) {\n    const double machep = cephes_helper<double>::machep();\n\n    double s, t, u, v, n, t1, z, ai;\n\n    ai = 1.0 / a;\n    u = (1.0 - b) * x;\n    v = u / (a + 1.0);\n    t1 = v;\n    t = u;\n    n = 2.0;\n    s = 0.0;\n    z = machep * ai;\n    while (numext::abs(v) > z) {\n      u = (n - b) * x / n;\n      t *= u;\n      v = t / (a + n);\n      s += v;\n      n += 1.0;\n    }\n    s += t1;\n    s += ai;\n\n    u = a * numext::log(x);\n    // TODO: gamma() is not directly implemented in Eigen.\n    /*\n    if ((a + b) < maxgam && numext::abs(u) < maxlog) {\n      t = gamma(a + b) / (gamma(a) * gamma(b));\n      s = s * t * pow(x, a);\n    }\n    */\n    t = lgamma_impl<double>::run(a + b) - lgamma_impl<double>::run(a) -\n        lgamma_impl<double>::run(b) + u + numext::log(s);\n    return s = numext::exp(t);\n  }\n};\n\ntemplate <>\nstruct betainc_impl<double> {\n  EIGEN_DEVICE_FUNC\n  static double run(double aa, double bb, double xx) {\n    const double nan = NumTraits<double>::quiet_NaN();\n    const double machep = cephes_helper<double>::machep();\n    // const double maxgam = 171.624376956302725;\n\n    double a, b, t, x, xc, w, y;\n    bool reversed_a_b = false;\n\n    if (aa <= 0.0 || bb <= 0.0) {\n      return nan;  // goto domerr;\n    }\n\n    if ((xx <= 0.0) || (xx >= 1.0)) {\n      if (xx == 0.0) return (0.0);\n      if (xx == 1.0) return (1.0);\n      // mtherr(\"incbet\", DOMAIN);\n      return nan;\n    }\n\n    if ((bb * xx) <= 1.0 && xx <= 0.95) {\n      return betainc_helper<double>::incbps(aa, bb, xx);\n    }\n\n    w = 1.0 - xx;\n\n    /* Reverse a and b if x is greater than the mean. */\n    if (xx > (aa / (aa + bb))) {\n      reversed_a_b = true;\n      a = bb;\n      b = aa;\n      xc = xx;\n      x = w;\n    } else {\n      a = aa;\n      b = bb;\n      xc = w;\n      x = xx;\n    }\n\n    if (reversed_a_b && (b * x) <= 1.0 && x <= 0.95) {\n      t = betainc_helper<double>::incbps(a, b, x);\n      if (t <= machep) {\n        t = 1.0 - machep;\n      } else {\n        t = 1.0 - t;\n      }\n      return t;\n    }\n\n    /* Choose expansion for better convergence. */\n    y = x * (a + b - 2.0) - (a - 1.0);\n    if (y < 0.0) {\n      w = incbeta_cfe<double>::run(a, b, x, true /* small_branch */);\n    } else {\n      w = incbeta_cfe<double>::run(a, b, x, false /* small_branch */) / xc;\n    }\n\n    /* Multiply w by the factor\n         a      b   _             _     _\n        x  (1-x)   | (a+b) / ( a | (a) | (b) ) .   */\n\n    y = a * numext::log(x);\n    t = b * numext::log(xc);\n    // TODO: gamma is not directly implemented in Eigen.\n    /*\n    if ((a + b) < maxgam && numext::abs(y) < maxlog && numext::abs(t) < maxlog)\n    {\n      t = pow(xc, b);\n      t *= pow(x, a);\n      t /= a;\n      t *= w;\n      t *= gamma(a + b) / (gamma(a) * gamma(b));\n    } else {\n    */\n    /* Resort to logarithms.  */\n    y += t + lgamma_impl<double>::run(a + b) - lgamma_impl<double>::run(a) -\n         lgamma_impl<double>::run(b);\n    y += numext::log(w / a);\n    t = numext::exp(y);\n\n    /* } */\n    // done:\n\n    if (reversed_a_b) {\n      if (t <= machep) {\n        t = 1.0 - machep;\n      } else {\n        t = 1.0 - t;\n      }\n    }\n    return t;\n  }\n};\n\n#endif  // EIGEN_HAS_C99_MATH\n\n}  // end namespace internal\n\nnamespace numext {\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(lgamma, Scalar)\n    lgamma(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(lgamma, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(digamma, Scalar)\n    digamma(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(digamma, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(zeta, Scalar)\nzeta(const Scalar& x, const Scalar& q) {\n    return EIGEN_MATHFUNC_IMPL(zeta, Scalar)::run(x, q);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(polygamma, Scalar)\npolygamma(const Scalar& n, const Scalar& x) {\n    return EIGEN_MATHFUNC_IMPL(polygamma, Scalar)::run(n, x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(erf, Scalar)\n    erf(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(erf, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(erfc, Scalar)\n    erfc(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(erfc, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(ndtri, Scalar)\n    ndtri(const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(ndtri, Scalar)::run(x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(igamma, Scalar)\n    igamma(const Scalar& a, const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(igamma, Scalar)::run(a, x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(igamma_der_a, Scalar)\n    igamma_der_a(const Scalar& a, const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(igamma_der_a, Scalar)::run(a, x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(gamma_sample_der_alpha, Scalar)\n    gamma_sample_der_alpha(const Scalar& a, const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(gamma_sample_der_alpha, Scalar)::run(a, x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(igammac, Scalar)\n    igammac(const Scalar& a, const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(igammac, Scalar)::run(a, x);\n}\n\ntemplate <typename Scalar>\nEIGEN_DEVICE_FUNC inline EIGEN_MATHFUNC_RETVAL(betainc, Scalar)\n    betainc(const Scalar& a, const Scalar& b, const Scalar& x) {\n  return EIGEN_MATHFUNC_IMPL(betainc, Scalar)::run(a, b, x);\n}\n\n}  // end namespace numext\n}  // end namespace Eigen\n\n#endif  // EIGEN_SPECIAL_FUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SpecialFunctions/SpecialFunctionsPacketMath.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPECIALFUNCTIONS_PACKETMATH_H\n#define EIGEN_SPECIALFUNCTIONS_PACKETMATH_H\n\nnamespace Eigen {\n\nnamespace internal {\n\n/** \\internal \\returns the ln(|gamma(\\a a)|) (coeff-wise) */\ntemplate<typename Packet> EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket plgamma(const Packet& a) { using numext::lgamma; return lgamma(a); }\n\n/** \\internal \\returns the derivative of lgamma, psi(\\a a) (coeff-wise) */\ntemplate<typename Packet> EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pdigamma(const Packet& a) { using numext::digamma; return digamma(a); }\n\n/** \\internal \\returns the zeta function of two arguments (coeff-wise) */\ntemplate<typename Packet> EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pzeta(const Packet& x, const Packet& q) { using numext::zeta; return zeta(x, q); }\n\n/** \\internal \\returns the polygamma function (coeff-wise) */\ntemplate<typename Packet> EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket ppolygamma(const Packet& n, const Packet& x) { using numext::polygamma; return polygamma(n, x); }\n\n/** \\internal \\returns the erf(\\a a) (coeff-wise) */\ntemplate<typename Packet> EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket perf(const Packet& a) { using numext::erf; return erf(a); }\n\n/** \\internal \\returns the erfc(\\a a) (coeff-wise) */\ntemplate<typename Packet> EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket perfc(const Packet& a) { using numext::erfc; return erfc(a); }\n\n/** \\internal \\returns the ndtri(\\a a) (coeff-wise) */\ntemplate<typename Packet> EIGEN_DECLARE_FUNCTION_ALLOWING_MULTIPLE_DEFINITIONS\nPacket pndtri(const Packet& a) {\n  typedef typename unpacket_traits<Packet>::type ScalarType;\n  using internal::generic_ndtri; return generic_ndtri<Packet, ScalarType>(a);\n}\n\n/** \\internal \\returns the incomplete gamma function igamma(\\a a, \\a x) */\ntemplate<typename Packet> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nPacket pigamma(const Packet& a, const Packet& x) { using numext::igamma; return igamma(a, x); }\n\n/** \\internal \\returns the derivative of the incomplete gamma function\n * igamma_der_a(\\a a, \\a x) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet pigamma_der_a(const Packet& a, const Packet& x) {\n  using numext::igamma_der_a; return igamma_der_a(a, x);\n}\n\n/** \\internal \\returns compute the derivative of the sample\n  * of Gamma(alpha, 1) random variable with respect to the parameter a\n  * gamma_sample_der_alpha(\\a alpha, \\a sample) */\ntemplate <typename Packet>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE Packet pgamma_sample_der_alpha(const Packet& alpha, const Packet& sample) {\n  using numext::gamma_sample_der_alpha; return gamma_sample_der_alpha(alpha, sample);\n}\n\n/** \\internal \\returns the complementary incomplete gamma function igammac(\\a a, \\a x) */\ntemplate<typename Packet> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nPacket pigammac(const Packet& a, const Packet& x) { using numext::igammac; return igammac(a, x); }\n\n/** \\internal \\returns the complementary incomplete gamma function betainc(\\a a, \\a b, \\a x) */\ntemplate<typename Packet> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nPacket pbetainc(const Packet& a, const Packet& b,const Packet& x) { using numext::betainc; return betainc(a, b, x); }\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_SPECIALFUNCTIONS_PACKETMATH_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SpecialFunctions/arch/AVX/BesselFunctions.h",
    "content": "#ifndef EIGEN_AVX_BESSELFUNCTIONS_H\n#define EIGEN_AVX_BESSELFUNCTIONS_H\n\nnamespace Eigen {\nnamespace internal {\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_i0)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_i0)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_i0e)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_i0e)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_i1)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_i1)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_i1e)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_i1e)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_j0)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_j0)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_j1)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_j1)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_k0)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_k0)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_k0e)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_k0e)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_k1)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_k1)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_k1e)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_k1e)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_y0)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_y0)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pbessel_y1)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pbessel_y1)\n\n}  // namespace internal\n}  // namespace Eigen\n\n#endif  // EIGEN_AVX_BESSELFUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SpecialFunctions/arch/AVX/SpecialFunctions.h",
    "content": "#ifndef EIGEN_AVX_SPECIALFUNCTIONS_H\n#define EIGEN_AVX_SPECIALFUNCTIONS_H\n\nnamespace Eigen {\nnamespace internal {\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, perf)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, perf)\n\nF16_PACKET_FUNCTION(Packet8f, Packet8h, pndtri)\nBF16_PACKET_FUNCTION(Packet8f, Packet8bf, pndtri)\n\n}  // namespace internal\n}  // namespace Eigen\n\n#endif  // EIGEN_AVX_SPECIAL_FUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SpecialFunctions/arch/AVX512/BesselFunctions.h",
    "content": "#ifndef EIGEN_AVX512_BESSELFUNCTIONS_H\n#define EIGEN_AVX512_BESSELFUNCTIONS_H\n\nnamespace Eigen {\nnamespace internal {\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_i0)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_i0)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_i0e)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_i0e)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_i1)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_i1)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_i1e)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_i1e)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_j0)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_j0)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_j1)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_j1)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_k0)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_k0)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_k0e)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_k0e)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_k1)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_k1)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_k1e)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_k1e)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_y0)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_y0)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pbessel_y1)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pbessel_y1)\n\n}  // namespace internal\n}  // namespace Eigen\n\n#endif  // EIGEN_AVX512_BESSELFUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SpecialFunctions/arch/AVX512/SpecialFunctions.h",
    "content": "#ifndef EIGEN_AVX512_SPECIALFUNCTIONS_H\n#define EIGEN_AVX512_SPECIALFUNCTIONS_H\n\nnamespace Eigen {\nnamespace internal {\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, perf)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, perf)\n\nF16_PACKET_FUNCTION(Packet16f, Packet16h, pndtri)\nBF16_PACKET_FUNCTION(Packet16f, Packet16bf, pndtri)\n\n}  // namespace internal\n}  // namespace Eigen\n\n#endif  // EIGEN_AVX512_SPECIAL_FUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SpecialFunctions/arch/GPU/SpecialFunctions.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_GPU_SPECIALFUNCTIONS_H\n#define EIGEN_GPU_SPECIALFUNCTIONS_H\n\nnamespace Eigen {\n\nnamespace internal {\n\n// Make sure this is only available when targeting a GPU: we don't want to\n// introduce conflicts between these packet_traits definitions and the ones\n// we'll use on the host side (SSE, AVX, ...)\n#if defined(EIGEN_GPUCC) && defined(EIGEN_USE_GPU)\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat4 plgamma<float4>(const float4& a)\n{\n  return make_float4(lgammaf(a.x), lgammaf(a.y), lgammaf(a.z), lgammaf(a.w));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble2 plgamma<double2>(const double2& a)\n{\n  using numext::lgamma;\n  return make_double2(lgamma(a.x), lgamma(a.y));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat4 pdigamma<float4>(const float4& a)\n{\n  using numext::digamma;\n  return make_float4(digamma(a.x), digamma(a.y), digamma(a.z), digamma(a.w));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble2 pdigamma<double2>(const double2& a)\n{\n  using numext::digamma;\n  return make_double2(digamma(a.x), digamma(a.y));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat4 pzeta<float4>(const float4& x, const float4& q)\n{\n    using numext::zeta;\n    return make_float4(zeta(x.x, q.x), zeta(x.y, q.y), zeta(x.z, q.z), zeta(x.w, q.w));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble2 pzeta<double2>(const double2& x, const double2& q)\n{\n    using numext::zeta;\n    return make_double2(zeta(x.x, q.x), zeta(x.y, q.y));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat4 ppolygamma<float4>(const float4& n, const float4& x)\n{\n    using numext::polygamma;\n    return make_float4(polygamma(n.x, x.x), polygamma(n.y, x.y), polygamma(n.z, x.z), polygamma(n.w, x.w));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble2 ppolygamma<double2>(const double2& n, const double2& x)\n{\n    using numext::polygamma;\n    return make_double2(polygamma(n.x, x.x), polygamma(n.y, x.y));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat4 perf<float4>(const float4& a)\n{\n  return make_float4(erff(a.x), erff(a.y), erff(a.z), erff(a.w));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble2 perf<double2>(const double2& a)\n{\n  using numext::erf;\n  return make_double2(erf(a.x), erf(a.y));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat4 perfc<float4>(const float4& a)\n{\n  using numext::erfc;\n  return make_float4(erfc(a.x), erfc(a.y), erfc(a.z), erfc(a.w));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble2 perfc<double2>(const double2& a)\n{\n  using numext::erfc;\n  return make_double2(erfc(a.x), erfc(a.y));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat4 pndtri<float4>(const float4& a)\n{\n  using numext::ndtri;\n  return make_float4(ndtri(a.x), ndtri(a.y), ndtri(a.z), ndtri(a.w));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble2 pndtri<double2>(const double2& a)\n{\n  using numext::ndtri;\n  return make_double2(ndtri(a.x), ndtri(a.y));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat4 pigamma<float4>(const float4& a, const float4& x)\n{\n  using numext::igamma;\n  return make_float4(\n      igamma(a.x, x.x),\n      igamma(a.y, x.y),\n      igamma(a.z, x.z),\n      igamma(a.w, x.w));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble2 pigamma<double2>(const double2& a, const double2& x)\n{\n  using numext::igamma;\n  return make_double2(igamma(a.x, x.x), igamma(a.y, x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pigamma_der_a<float4>(\n    const float4& a, const float4& x) {\n  using numext::igamma_der_a;\n  return make_float4(igamma_der_a(a.x, x.x), igamma_der_a(a.y, x.y),\n                     igamma_der_a(a.z, x.z), igamma_der_a(a.w, x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npigamma_der_a<double2>(const double2& a, const double2& x) {\n  using numext::igamma_der_a;\n  return make_double2(igamma_der_a(a.x, x.x), igamma_der_a(a.y, x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pgamma_sample_der_alpha<float4>(\n    const float4& alpha, const float4& sample) {\n  using numext::gamma_sample_der_alpha;\n  return make_float4(\n      gamma_sample_der_alpha(alpha.x, sample.x),\n      gamma_sample_der_alpha(alpha.y, sample.y),\n      gamma_sample_der_alpha(alpha.z, sample.z),\n      gamma_sample_der_alpha(alpha.w, sample.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npgamma_sample_der_alpha<double2>(const double2& alpha, const double2& sample) {\n  using numext::gamma_sample_der_alpha;\n  return make_double2(\n      gamma_sample_der_alpha(alpha.x, sample.x),\n      gamma_sample_der_alpha(alpha.y, sample.y));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat4 pigammac<float4>(const float4& a, const float4& x)\n{\n  using numext::igammac;\n  return make_float4(\n      igammac(a.x, x.x),\n      igammac(a.y, x.y),\n      igammac(a.z, x.z),\n      igammac(a.w, x.w));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble2 pigammac<double2>(const double2& a, const double2& x)\n{\n  using numext::igammac;\n  return make_double2(igammac(a.x, x.x), igammac(a.y, x.y));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\nfloat4 pbetainc<float4>(const float4& a, const float4& b, const float4& x)\n{\n  using numext::betainc;\n  return make_float4(\n      betainc(a.x, b.x, x.x),\n      betainc(a.y, b.y, x.y),\n      betainc(a.z, b.z, x.z),\n      betainc(a.w, b.w, x.w));\n}\n\ntemplate<> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE\ndouble2 pbetainc<double2>(const double2& a, const double2& b, const double2& x)\n{\n  using numext::betainc;\n  return make_double2(betainc(a.x, b.x, x.x), betainc(a.y, b.y, x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_i0e<float4>(const float4& x) {\n  using numext::bessel_i0e;\n  return make_float4(bessel_i0e(x.x), bessel_i0e(x.y), bessel_i0e(x.z), bessel_i0e(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_i0e<double2>(const double2& x) {\n  using numext::bessel_i0e;\n  return make_double2(bessel_i0e(x.x), bessel_i0e(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_i0<float4>(const float4& x) {\n  using numext::bessel_i0;\n  return make_float4(bessel_i0(x.x), bessel_i0(x.y), bessel_i0(x.z), bessel_i0(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_i0<double2>(const double2& x) {\n  using numext::bessel_i0;\n  return make_double2(bessel_i0(x.x), bessel_i0(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_i1e<float4>(const float4& x) {\n  using numext::bessel_i1e;\n  return make_float4(bessel_i1e(x.x), bessel_i1e(x.y), bessel_i1e(x.z), bessel_i1e(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_i1e<double2>(const double2& x) {\n  using numext::bessel_i1e;\n  return make_double2(bessel_i1e(x.x), bessel_i1e(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_i1<float4>(const float4& x) {\n  using numext::bessel_i1;\n  return make_float4(bessel_i1(x.x), bessel_i1(x.y), bessel_i1(x.z), bessel_i1(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_i1<double2>(const double2& x) {\n  using numext::bessel_i1;\n  return make_double2(bessel_i1(x.x), bessel_i1(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_k0e<float4>(const float4& x) {\n  using numext::bessel_k0e;\n  return make_float4(bessel_k0e(x.x), bessel_k0e(x.y), bessel_k0e(x.z), bessel_k0e(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_k0e<double2>(const double2& x) {\n  using numext::bessel_k0e;\n  return make_double2(bessel_k0e(x.x), bessel_k0e(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_k0<float4>(const float4& x) {\n  using numext::bessel_k0;\n  return make_float4(bessel_k0(x.x), bessel_k0(x.y), bessel_k0(x.z), bessel_k0(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_k0<double2>(const double2& x) {\n  using numext::bessel_k0;\n  return make_double2(bessel_k0(x.x), bessel_k0(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_k1e<float4>(const float4& x) {\n  using numext::bessel_k1e;\n  return make_float4(bessel_k1e(x.x), bessel_k1e(x.y), bessel_k1e(x.z), bessel_k1e(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_k1e<double2>(const double2& x) {\n  using numext::bessel_k1e;\n  return make_double2(bessel_k1e(x.x), bessel_k1e(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_k1<float4>(const float4& x) {\n  using numext::bessel_k1;\n  return make_float4(bessel_k1(x.x), bessel_k1(x.y), bessel_k1(x.z), bessel_k1(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_k1<double2>(const double2& x) {\n  using numext::bessel_k1;\n  return make_double2(bessel_k1(x.x), bessel_k1(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_j0<float4>(const float4& x) {\n  using numext::bessel_j0;\n  return make_float4(bessel_j0(x.x), bessel_j0(x.y), bessel_j0(x.z), bessel_j0(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_j0<double2>(const double2& x) {\n  using numext::bessel_j0;\n  return make_double2(bessel_j0(x.x), bessel_j0(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_j1<float4>(const float4& x) {\n  using numext::bessel_j1;\n  return make_float4(bessel_j1(x.x), bessel_j1(x.y), bessel_j1(x.z), bessel_j1(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_j1<double2>(const double2& x) {\n  using numext::bessel_j1;\n  return make_double2(bessel_j1(x.x), bessel_j1(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_y0<float4>(const float4& x) {\n  using numext::bessel_y0;\n  return make_float4(bessel_y0(x.x), bessel_y0(x.y), bessel_y0(x.z), bessel_y0(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_y0<double2>(const double2& x) {\n  using numext::bessel_y0;\n  return make_double2(bessel_y0(x.x), bessel_y0(x.y));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE float4 pbessel_y1<float4>(const float4& x) {\n  using numext::bessel_y1;\n  return make_float4(bessel_y1(x.x), bessel_y1(x.y), bessel_y1(x.z), bessel_y1(x.w));\n}\n\ntemplate <>\nEIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE double2\npbessel_y1<double2>(const double2& x) {\n  using numext::bessel_y1;\n  return make_double2(bessel_y1(x.x), bessel_y1(x.y));\n}\n\n#endif\n\n} // end namespace internal\n\n} // end namespace Eigen\n\n#endif // EIGEN_GPU_SPECIALFUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SpecialFunctions/arch/NEON/BesselFunctions.h",
    "content": "#ifndef EIGEN_NEON_BESSELFUNCTIONS_H\n#define EIGEN_NEON_BESSELFUNCTIONS_H\n\nnamespace Eigen {\nnamespace internal {\n\n#if EIGEN_HAS_ARM64_FP16_VECTOR_ARITHMETIC\n\n#define NEON_HALF_TO_FLOAT_FUNCTIONS(METHOD)                            \\\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE                       \\\nPacket8hf METHOD<Packet8hf>(const Packet8hf& x) {                       \\\n  const Packet4f lo = METHOD<Packet4f>(vcvt_f32_f16(vget_low_f16(x)));  \\\n  const Packet4f hi = METHOD<Packet4f>(vcvt_f32_f16(vget_high_f16(x))); \\\n  return vcombine_f16(vcvt_f16_f32(lo), vcvt_f16_f32(hi));              \\\n}                                                                       \\\n                                                                        \\\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE                       \\\nPacket4hf METHOD<Packet4hf>(const Packet4hf& x) {                       \\\n  return vcvt_f16_f32(METHOD<Packet4f>(vcvt_f32_f16(x)));               \\\n}\n\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_i0)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_i0e)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_i1)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_i1e)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_j0)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_j1)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_k0)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_k0e)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_k1)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_k1e)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_y0)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pbessel_y1)\n\n#undef NEON_HALF_TO_FLOAT_FUNCTIONS\n#endif\n\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_i0)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_i0e)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_i1)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_i1e)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_j0)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_j1)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_k0)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_k0e)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_k1)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_k1e)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_y0)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pbessel_y1)\n\n}  // namespace internal\n}  // namespace Eigen\n\n#endif  // EIGEN_NEON_BESSELFUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/SpecialFunctions/arch/NEON/SpecialFunctions.h",
    "content": "#ifndef EIGEN_NEON_SPECIALFUNCTIONS_H\n#define EIGEN_NEON_SPECIALFUNCTIONS_H\n\nnamespace Eigen {\nnamespace internal {\n\n#if EIGEN_HAS_ARM64_FP16_VECTOR_ARITHMETIC\n\n#define NEON_HALF_TO_FLOAT_FUNCTIONS(METHOD)                            \\\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE                       \\\nPacket8hf METHOD<Packet8hf>(const Packet8hf& x) {                       \\\n  const Packet4f lo = METHOD<Packet4f>(vcvt_f32_f16(vget_low_f16(x)));  \\\n  const Packet4f hi = METHOD<Packet4f>(vcvt_f32_f16(vget_high_f16(x))); \\\n  return vcombine_f16(vcvt_f16_f32(lo), vcvt_f16_f32(hi));              \\\n}                                                                       \\\n                                                                        \\\ntemplate <> EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE                       \\\nPacket4hf METHOD<Packet4hf>(const Packet4hf& x) {                       \\\n  return vcvt_f16_f32(METHOD<Packet4f>(vcvt_f32_f16(x)));               \\\n}\n\nNEON_HALF_TO_FLOAT_FUNCTIONS(perf)\nNEON_HALF_TO_FLOAT_FUNCTIONS(pndtri)\n\n#undef NEON_HALF_TO_FLOAT_FUNCTIONS\n#endif\n\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, perf)\nBF16_PACKET_FUNCTION(Packet4f, Packet4bf, pndtri)\n\n}  // namespace internal\n}  // namespace Eigen\n\n#endif  // EIGEN_NEON_SPECIALFUNCTIONS_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/Splines/Spline.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 20010-2011 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPLINE_H\n#define EIGEN_SPLINE_H\n\n#include \"SplineFwd.h\"\n\nnamespace Eigen\n{\n    /**\n     * \\ingroup Splines_Module\n     * \\class Spline\n     * \\brief A class representing multi-dimensional spline curves.\n     *\n     * The class represents B-splines with non-uniform knot vectors. Each control\n     * point of the B-spline is associated with a basis function\n     * \\f{align*}\n     *   C(u) & = \\sum_{i=0}^{n}N_{i,p}(u)P_i\n     * \\f}\n     *\n     * \\tparam _Scalar The underlying data type (typically float or double)\n     * \\tparam _Dim The curve dimension (e.g. 2 or 3)\n     * \\tparam _Degree Per default set to Dynamic; could be set to the actual desired\n     *                degree for optimization purposes (would result in stack allocation\n     *                of several temporary variables).\n     **/\n  template <typename _Scalar, int _Dim, int _Degree>\n  class Spline\n  {\n  public:\n    typedef _Scalar Scalar; /*!< The spline curve's scalar type. */\n    enum { Dimension = _Dim /*!< The spline curve's dimension. */ };\n    enum { Degree = _Degree /*!< The spline curve's degree. */ };\n\n    /** \\brief The point type the spline is representing. */\n    typedef typename SplineTraits<Spline>::PointType PointType;\n    \n    /** \\brief The data type used to store knot vectors. */\n    typedef typename SplineTraits<Spline>::KnotVectorType KnotVectorType;\n\n    /** \\brief The data type used to store parameter vectors. */\n    typedef typename SplineTraits<Spline>::ParameterVectorType ParameterVectorType;\n    \n    /** \\brief The data type used to store non-zero basis functions. */\n    typedef typename SplineTraits<Spline>::BasisVectorType BasisVectorType;\n\n    /** \\brief The data type used to store the values of the basis function derivatives. */\n    typedef typename SplineTraits<Spline>::BasisDerivativeType BasisDerivativeType;\n    \n    /** \\brief The data type representing the spline's control points. */\n    typedef typename SplineTraits<Spline>::ControlPointVectorType ControlPointVectorType;\n    \n    /**\n    * \\brief Creates a (constant) zero spline.\n    * For Splines with dynamic degree, the resulting degree will be 0.\n    **/\n    Spline() \n    : m_knots(1, (Degree==Dynamic ? 2 : 2*Degree+2))\n    , m_ctrls(ControlPointVectorType::Zero(Dimension,(Degree==Dynamic ? 1 : Degree+1))) \n    {\n      // in theory this code can go to the initializer list but it will get pretty\n      // much unreadable ...\n      enum { MinDegree = (Degree==Dynamic ? 0 : Degree) };\n      m_knots.template segment<MinDegree+1>(0) = Array<Scalar,1,MinDegree+1>::Zero();\n      m_knots.template segment<MinDegree+1>(MinDegree+1) = Array<Scalar,1,MinDegree+1>::Ones();\n    }\n\n    /**\n    * \\brief Creates a spline from a knot vector and control points.\n    * \\param knots The spline's knot vector.\n    * \\param ctrls The spline's control point vector.\n    **/\n    template <typename OtherVectorType, typename OtherArrayType>\n    Spline(const OtherVectorType& knots, const OtherArrayType& ctrls) : m_knots(knots), m_ctrls(ctrls) {}\n\n    /**\n    * \\brief Copy constructor for splines.\n    * \\param spline The input spline.\n    **/\n    template <int OtherDegree>\n    Spline(const Spline<Scalar, Dimension, OtherDegree>& spline) : \n    m_knots(spline.knots()), m_ctrls(spline.ctrls()) {}\n\n    /**\n     * \\brief Returns the knots of the underlying spline.\n     **/\n    const KnotVectorType& knots() const { return m_knots; }\n    \n    /**\n     * \\brief Returns the ctrls of the underlying spline.\n     **/    \n    const ControlPointVectorType& ctrls() const { return m_ctrls; }\n\n    /**\n     * \\brief Returns the spline value at a given site \\f$u\\f$.\n     *\n     * The function returns\n     * \\f{align*}\n     *   C(u) & = \\sum_{i=0}^{n}N_{i,p}P_i\n     * \\f}\n     *\n     * \\param u Parameter \\f$u \\in [0;1]\\f$ at which the spline is evaluated.\n     * \\return The spline value at the given location \\f$u\\f$.\n     **/\n    PointType operator()(Scalar u) const;\n\n    /**\n     * \\brief Evaluation of spline derivatives of up-to given order.\n     *\n     * The function returns\n     * \\f{align*}\n     *   \\frac{d^i}{du^i}C(u) & = \\sum_{i=0}^{n} \\frac{d^i}{du^i} N_{i,p}(u)P_i\n     * \\f}\n     * for i ranging between 0 and order.\n     *\n     * \\param u Parameter \\f$u \\in [0;1]\\f$ at which the spline derivative is evaluated.\n     * \\param order The order up to which the derivatives are computed.\n     **/\n    typename SplineTraits<Spline>::DerivativeType\n      derivatives(Scalar u, DenseIndex order) const;\n\n    /**\n     * \\copydoc Spline::derivatives\n     * Using the template version of this function is more efficieent since\n     * temporary objects are allocated on the stack whenever this is possible.\n     **/    \n    template <int DerivativeOrder>\n    typename SplineTraits<Spline,DerivativeOrder>::DerivativeType\n      derivatives(Scalar u, DenseIndex order = DerivativeOrder) const;\n\n    /**\n     * \\brief Computes the non-zero basis functions at the given site.\n     *\n     * Splines have local support and a point from their image is defined\n     * by exactly \\f$p+1\\f$ control points \\f$P_i\\f$ where \\f$p\\f$ is the\n     * spline degree.\n     *\n     * This function computes the \\f$p+1\\f$ non-zero basis function values\n     * for a given parameter value \\f$u\\f$. It returns\n     * \\f{align*}{\n     *   N_{i,p}(u), \\hdots, N_{i+p+1,p}(u)\n     * \\f}\n     *\n     * \\param u Parameter \\f$u \\in [0;1]\\f$ at which the non-zero basis functions \n     *          are computed.\n     **/\n    typename SplineTraits<Spline>::BasisVectorType\n      basisFunctions(Scalar u) const;\n\n    /**\n     * \\brief Computes the non-zero spline basis function derivatives up to given order.\n     *\n     * The function computes\n     * \\f{align*}{\n     *   \\frac{d^i}{du^i} N_{i,p}(u), \\hdots, \\frac{d^i}{du^i} N_{i+p+1,p}(u)\n     * \\f}\n     * with i ranging from 0 up to the specified order.\n     *\n     * \\param u Parameter \\f$u \\in [0;1]\\f$ at which the non-zero basis function\n     *          derivatives are computed.\n     * \\param order The order up to which the basis function derivatives are computes.\n     **/\n    typename SplineTraits<Spline>::BasisDerivativeType\n      basisFunctionDerivatives(Scalar u, DenseIndex order) const;\n\n    /**\n     * \\copydoc Spline::basisFunctionDerivatives\n     * Using the template version of this function is more efficieent since\n     * temporary objects are allocated on the stack whenever this is possible.\n     **/    \n    template <int DerivativeOrder>\n    typename SplineTraits<Spline,DerivativeOrder>::BasisDerivativeType\n      basisFunctionDerivatives(Scalar u, DenseIndex order = DerivativeOrder) const;\n\n    /**\n     * \\brief Returns the spline degree.\n     **/ \n    DenseIndex degree() const;\n\n    /** \n     * \\brief Returns the span within the knot vector in which u is falling.\n     * \\param u The site for which the span is determined.\n     **/\n    DenseIndex span(Scalar u) const;\n\n    /**\n     * \\brief Computes the span within the provided knot vector in which u is falling.\n     **/\n    static DenseIndex Span(typename SplineTraits<Spline>::Scalar u, DenseIndex degree, const typename SplineTraits<Spline>::KnotVectorType& knots);\n    \n    /**\n     * \\brief Returns the spline's non-zero basis functions.\n     *\n     * The function computes and returns\n     * \\f{align*}{\n     *   N_{i,p}(u), \\hdots, N_{i+p+1,p}(u)\n     * \\f}\n     *\n     * \\param u The site at which the basis functions are computed.\n     * \\param degree The degree of the underlying spline.\n     * \\param knots The underlying spline's knot vector.\n     **/\n    static BasisVectorType BasisFunctions(Scalar u, DenseIndex degree, const KnotVectorType& knots);\n\n    /**\n     * \\copydoc Spline::basisFunctionDerivatives\n     * \\param degree The degree of the underlying spline\n     * \\param knots The underlying spline's knot vector.\n     **/    \n    static BasisDerivativeType BasisFunctionDerivatives(\n      const Scalar u, const DenseIndex order, const DenseIndex degree, const KnotVectorType& knots);\n\n  private:\n    KnotVectorType m_knots; /*!< Knot vector. */\n    ControlPointVectorType  m_ctrls; /*!< Control points. */\n\n    template <typename DerivativeType>\n    static void BasisFunctionDerivativesImpl(\n      const typename Spline<_Scalar, _Dim, _Degree>::Scalar u,\n      const DenseIndex order,\n      const DenseIndex p, \n      const typename Spline<_Scalar, _Dim, _Degree>::KnotVectorType& U,\n      DerivativeType& N_);\n  };\n\n  template <typename _Scalar, int _Dim, int _Degree>\n  DenseIndex Spline<_Scalar, _Dim, _Degree>::Span(\n    typename SplineTraits< Spline<_Scalar, _Dim, _Degree> >::Scalar u,\n    DenseIndex degree,\n    const typename SplineTraits< Spline<_Scalar, _Dim, _Degree> >::KnotVectorType& knots)\n  {\n    // Piegl & Tiller, \"The NURBS Book\", A2.1 (p. 68)\n    if (u <= knots(0)) return degree;\n    const Scalar* pos = std::upper_bound(knots.data()+degree-1, knots.data()+knots.size()-degree-1, u);\n    return static_cast<DenseIndex>( std::distance(knots.data(), pos) - 1 );\n  }\n\n  template <typename _Scalar, int _Dim, int _Degree>\n  typename Spline<_Scalar, _Dim, _Degree>::BasisVectorType\n    Spline<_Scalar, _Dim, _Degree>::BasisFunctions(\n    typename Spline<_Scalar, _Dim, _Degree>::Scalar u,\n    DenseIndex degree,\n    const typename Spline<_Scalar, _Dim, _Degree>::KnotVectorType& knots)\n  {\n    const DenseIndex p = degree;\n    const DenseIndex i = Spline::Span(u, degree, knots);\n\n    const KnotVectorType& U = knots;\n\n    BasisVectorType left(p+1); left(0) = Scalar(0);\n    BasisVectorType right(p+1); right(0) = Scalar(0);\n\n    VectorBlock<BasisVectorType,Degree>(left,1,p) = u - VectorBlock<const KnotVectorType,Degree>(U,i+1-p,p).reverse();\n    VectorBlock<BasisVectorType,Degree>(right,1,p) = VectorBlock<const KnotVectorType,Degree>(U,i+1,p) - u;\n\n    BasisVectorType N(1,p+1);\n    N(0) = Scalar(1);\n    for (DenseIndex j=1; j<=p; ++j)\n    {\n      Scalar saved = Scalar(0);\n      for (DenseIndex r=0; r<j; r++)\n      {\n        const Scalar tmp = N(r)/(right(r+1)+left(j-r));\n        N[r] = saved + right(r+1)*tmp;\n        saved = left(j-r)*tmp;\n      }\n      N(j) = saved;\n    }\n    return N;\n  }\n\n  template <typename _Scalar, int _Dim, int _Degree>\n  DenseIndex Spline<_Scalar, _Dim, _Degree>::degree() const\n  {\n    if (_Degree == Dynamic)\n      return m_knots.size() - m_ctrls.cols() - 1;\n    else\n      return _Degree;\n  }\n\n  template <typename _Scalar, int _Dim, int _Degree>\n  DenseIndex Spline<_Scalar, _Dim, _Degree>::span(Scalar u) const\n  {\n    return Spline::Span(u, degree(), knots());\n  }\n\n  template <typename _Scalar, int _Dim, int _Degree>\n  typename Spline<_Scalar, _Dim, _Degree>::PointType Spline<_Scalar, _Dim, _Degree>::operator()(Scalar u) const\n  {\n    enum { Order = SplineTraits<Spline>::OrderAtCompileTime };\n\n    const DenseIndex span = this->span(u);\n    const DenseIndex p = degree();\n    const BasisVectorType basis_funcs = basisFunctions(u);\n\n    const Replicate<BasisVectorType,Dimension,1> ctrl_weights(basis_funcs);\n    const Block<const ControlPointVectorType,Dimension,Order> ctrl_pts(ctrls(),0,span-p,Dimension,p+1);\n    return (ctrl_weights * ctrl_pts).rowwise().sum();\n  }\n\n  /* --------------------------------------------------------------------------------------------- */\n\n  template <typename SplineType, typename DerivativeType>\n  void derivativesImpl(const SplineType& spline, typename SplineType::Scalar u, DenseIndex order, DerivativeType& der)\n  {    \n    enum { Dimension = SplineTraits<SplineType>::Dimension };\n    enum { Order = SplineTraits<SplineType>::OrderAtCompileTime };\n    enum { DerivativeOrder = DerivativeType::ColsAtCompileTime };\n\n    typedef typename SplineTraits<SplineType>::ControlPointVectorType ControlPointVectorType;\n    typedef typename SplineTraits<SplineType,DerivativeOrder>::BasisDerivativeType BasisDerivativeType;\n    typedef typename BasisDerivativeType::ConstRowXpr BasisDerivativeRowXpr;    \n\n    const DenseIndex p = spline.degree();\n    const DenseIndex span = spline.span(u);\n\n    const DenseIndex n = (std::min)(p, order);\n\n    der.resize(Dimension,n+1);\n\n    // Retrieve the basis function derivatives up to the desired order...    \n    const BasisDerivativeType basis_func_ders = spline.template basisFunctionDerivatives<DerivativeOrder>(u, n+1);\n\n    // ... and perform the linear combinations of the control points.\n    for (DenseIndex der_order=0; der_order<n+1; ++der_order)\n    {\n      const Replicate<BasisDerivativeRowXpr,Dimension,1> ctrl_weights( basis_func_ders.row(der_order) );\n      const Block<const ControlPointVectorType,Dimension,Order> ctrl_pts(spline.ctrls(),0,span-p,Dimension,p+1);\n      der.col(der_order) = (ctrl_weights * ctrl_pts).rowwise().sum();\n    }\n  }\n\n  template <typename _Scalar, int _Dim, int _Degree>\n  typename SplineTraits< Spline<_Scalar, _Dim, _Degree> >::DerivativeType\n    Spline<_Scalar, _Dim, _Degree>::derivatives(Scalar u, DenseIndex order) const\n  {\n    typename SplineTraits< Spline >::DerivativeType res;\n    derivativesImpl(*this, u, order, res);\n    return res;\n  }\n\n  template <typename _Scalar, int _Dim, int _Degree>\n  template <int DerivativeOrder>\n  typename SplineTraits< Spline<_Scalar, _Dim, _Degree>, DerivativeOrder >::DerivativeType\n    Spline<_Scalar, _Dim, _Degree>::derivatives(Scalar u, DenseIndex order) const\n  {\n    typename SplineTraits< Spline, DerivativeOrder >::DerivativeType res;\n    derivativesImpl(*this, u, order, res);\n    return res;\n  }\n\n  template <typename _Scalar, int _Dim, int _Degree>\n  typename SplineTraits< Spline<_Scalar, _Dim, _Degree> >::BasisVectorType\n    Spline<_Scalar, _Dim, _Degree>::basisFunctions(Scalar u) const\n  {\n    return Spline::BasisFunctions(u, degree(), knots());\n  }\n\n  /* --------------------------------------------------------------------------------------------- */\n  \n  \n  template <typename _Scalar, int _Dim, int _Degree>\n  template <typename DerivativeType>\n  void Spline<_Scalar, _Dim, _Degree>::BasisFunctionDerivativesImpl(\n    const typename Spline<_Scalar, _Dim, _Degree>::Scalar u,\n    const DenseIndex order,\n    const DenseIndex p, \n    const typename Spline<_Scalar, _Dim, _Degree>::KnotVectorType& U,\n    DerivativeType& N_)\n  {\n    typedef Spline<_Scalar, _Dim, _Degree> SplineType;\n    enum { Order = SplineTraits<SplineType>::OrderAtCompileTime };\n\n    const DenseIndex span = SplineType::Span(u, p, U);\n\n    const DenseIndex n = (std::min)(p, order);\n\n    N_.resize(n+1, p+1);\n\n    BasisVectorType left = BasisVectorType::Zero(p+1);\n    BasisVectorType right = BasisVectorType::Zero(p+1);\n\n    Matrix<Scalar,Order,Order> ndu(p+1,p+1);\n\n    Scalar saved, temp; // FIXME These were double instead of Scalar. Was there a reason for that?\n\n    ndu(0,0) = 1.0;\n\n    DenseIndex j;\n    for (j=1; j<=p; ++j)\n    {\n      left[j] = u-U[span+1-j];\n      right[j] = U[span+j]-u;\n      saved = 0.0;\n\n      for (DenseIndex r=0; r<j; ++r)\n      {\n        /* Lower triangle */\n        ndu(j,r) = right[r+1]+left[j-r];\n        temp = ndu(r,j-1)/ndu(j,r);\n        /* Upper triangle */\n        ndu(r,j) = static_cast<Scalar>(saved+right[r+1] * temp);\n        saved = left[j-r] * temp;\n      }\n\n      ndu(j,j) = static_cast<Scalar>(saved);\n    }\n\n    for (j = p; j>=0; --j) \n      N_(0,j) = ndu(j,p);\n\n    // Compute the derivatives\n    DerivativeType a(n+1,p+1);\n    DenseIndex r=0;\n    for (; r<=p; ++r)\n    {\n      DenseIndex s1,s2;\n      s1 = 0; s2 = 1; // alternate rows in array a\n      a(0,0) = 1.0;\n\n      // Compute the k-th derivative\n      for (DenseIndex k=1; k<=static_cast<DenseIndex>(n); ++k)\n      {\n        Scalar d = 0.0;\n        DenseIndex rk,pk,j1,j2;\n        rk = r-k; pk = p-k;\n\n        if (r>=k)\n        {\n          a(s2,0) = a(s1,0)/ndu(pk+1,rk);\n          d = a(s2,0)*ndu(rk,pk);\n        }\n\n        if (rk>=-1) j1 = 1;\n        else        j1 = -rk;\n\n        if (r-1 <= pk) j2 = k-1;\n        else           j2 = p-r;\n\n        for (j=j1; j<=j2; ++j)\n        {\n          a(s2,j) = (a(s1,j)-a(s1,j-1))/ndu(pk+1,rk+j);\n          d += a(s2,j)*ndu(rk+j,pk);\n        }\n\n        if (r<=pk)\n        {\n          a(s2,k) = -a(s1,k-1)/ndu(pk+1,r);\n          d += a(s2,k)*ndu(r,pk);\n        }\n\n        N_(k,r) = static_cast<Scalar>(d);\n        j = s1; s1 = s2; s2 = j; // Switch rows\n      }\n    }\n\n    /* Multiply through by the correct factors */\n    /* (Eq. [2.9])                             */\n    r = p;\n    for (DenseIndex k=1; k<=static_cast<DenseIndex>(n); ++k)\n    {\n      for (j=p; j>=0; --j) N_(k,j) *= r;\n      r *= p-k;\n    }\n  }\n\n  template <typename _Scalar, int _Dim, int _Degree>\n  typename SplineTraits< Spline<_Scalar, _Dim, _Degree> >::BasisDerivativeType\n    Spline<_Scalar, _Dim, _Degree>::basisFunctionDerivatives(Scalar u, DenseIndex order) const\n  {\n    typename SplineTraits<Spline<_Scalar, _Dim, _Degree> >::BasisDerivativeType der;\n    BasisFunctionDerivativesImpl(u, order, degree(), knots(), der);\n    return der;\n  }\n\n  template <typename _Scalar, int _Dim, int _Degree>\n  template <int DerivativeOrder>\n  typename SplineTraits< Spline<_Scalar, _Dim, _Degree>, DerivativeOrder >::BasisDerivativeType\n    Spline<_Scalar, _Dim, _Degree>::basisFunctionDerivatives(Scalar u, DenseIndex order) const\n  {\n    typename SplineTraits< Spline<_Scalar, _Dim, _Degree>, DerivativeOrder >::BasisDerivativeType der;\n    BasisFunctionDerivativesImpl(u, order, degree(), knots(), der);\n    return der;\n  }\n\n  template <typename _Scalar, int _Dim, int _Degree>\n  typename SplineTraits<Spline<_Scalar, _Dim, _Degree> >::BasisDerivativeType\n  Spline<_Scalar, _Dim, _Degree>::BasisFunctionDerivatives(\n    const typename Spline<_Scalar, _Dim, _Degree>::Scalar u,\n    const DenseIndex order,\n    const DenseIndex degree,\n    const typename Spline<_Scalar, _Dim, _Degree>::KnotVectorType& knots)\n  {\n    typename SplineTraits<Spline>::BasisDerivativeType der;\n    BasisFunctionDerivativesImpl(u, order, degree, knots, der);\n    return der;\n  }\n}\n\n#endif // EIGEN_SPLINE_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/Splines/SplineFitting.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 20010-2011 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPLINE_FITTING_H\n#define EIGEN_SPLINE_FITTING_H\n\n#include <algorithm>\n#include <functional>\n#include <numeric>\n#include <vector>\n\n#include \"SplineFwd.h\"\n\n#include \"../../../../Eigen/LU\"\n#include \"../../../../Eigen/QR\"\n\nnamespace Eigen\n{\n  /**\n   * \\brief Computes knot averages.\n   * \\ingroup Splines_Module\n   *\n   * The knots are computed as\n   * \\f{align*}\n   *  u_0 & = \\hdots = u_p = 0 \\\\\n   *  u_{m-p} & = \\hdots = u_{m} = 1 \\\\\n   *  u_{j+p} & = \\frac{1}{p}\\sum_{i=j}^{j+p-1}\\bar{u}_i \\quad\\quad j=1,\\hdots,n-p\n   * \\f}\n   * where \\f$p\\f$ is the degree and \\f$m+1\\f$ the number knots\n   * of the desired interpolating spline.\n   *\n   * \\param[in] parameters The input parameters. During interpolation one for each data point.\n   * \\param[in] degree The spline degree which is used during the interpolation.\n   * \\param[out] knots The output knot vector.\n   *\n   * \\sa Les Piegl and Wayne Tiller, The NURBS book (2nd ed.), 1997, 9.2.1 Global Curve Interpolation to Point Data\n   **/\n  template <typename KnotVectorType>\n  void KnotAveraging(const KnotVectorType& parameters, DenseIndex degree, KnotVectorType& knots)\n  {\n    knots.resize(parameters.size()+degree+1);      \n\n    for (DenseIndex j=1; j<parameters.size()-degree; ++j)\n      knots(j+degree) = parameters.segment(j,degree).mean();\n\n    knots.segment(0,degree+1) = KnotVectorType::Zero(degree+1);\n    knots.segment(knots.size()-degree-1,degree+1) = KnotVectorType::Ones(degree+1);\n  }\n\n  /**\n   * \\brief Computes knot averages when derivative constraints are present.\n   * Note that this is a technical interpretation of the referenced article\n   * since the algorithm contained therein is incorrect as written.\n   * \\ingroup Splines_Module\n   *\n   * \\param[in] parameters The parameters at which the interpolation B-Spline\n   *            will intersect the given interpolation points. The parameters\n   *            are assumed to be a non-decreasing sequence.\n   * \\param[in] degree The degree of the interpolating B-Spline. This must be\n   *            greater than zero.\n   * \\param[in] derivativeIndices The indices corresponding to parameters at\n   *            which there are derivative constraints. The indices are assumed\n   *            to be a non-decreasing sequence.\n   * \\param[out] knots The calculated knot vector. These will be returned as a\n   *             non-decreasing sequence\n   *\n   * \\sa Les A. Piegl, Khairan Rajab, Volha Smarodzinana. 2008.\n   * Curve interpolation with directional constraints for engineering design. \n   * Engineering with Computers\n   **/\n  template <typename KnotVectorType, typename ParameterVectorType, typename IndexArray>\n  void KnotAveragingWithDerivatives(const ParameterVectorType& parameters,\n                                    const unsigned int degree,\n                                    const IndexArray& derivativeIndices,\n                                    KnotVectorType& knots)\n  {\n    typedef typename ParameterVectorType::Scalar Scalar;\n\n    DenseIndex numParameters = parameters.size();\n    DenseIndex numDerivatives = derivativeIndices.size();\n\n    if (numDerivatives < 1)\n    {\n      KnotAveraging(parameters, degree, knots);\n      return;\n    }\n\n    DenseIndex startIndex;\n    DenseIndex endIndex;\n  \n    DenseIndex numInternalDerivatives = numDerivatives;\n    \n    if (derivativeIndices[0] == 0)\n    {\n      startIndex = 0;\n      --numInternalDerivatives;\n    }\n    else\n    {\n      startIndex = 1;\n    }\n    if (derivativeIndices[numDerivatives - 1] == numParameters - 1)\n    {\n      endIndex = numParameters - degree;\n      --numInternalDerivatives;\n    }\n    else\n    {\n      endIndex = numParameters - degree - 1;\n    }\n\n    // There are (endIndex - startIndex + 1) knots obtained from the averaging\n    // and 2 for the first and last parameters.\n    DenseIndex numAverageKnots = endIndex - startIndex + 3;\n    KnotVectorType averageKnots(numAverageKnots);\n    averageKnots[0] = parameters[0];\n\n    int newKnotIndex = 0;\n    for (DenseIndex i = startIndex; i <= endIndex; ++i)\n      averageKnots[++newKnotIndex] = parameters.segment(i, degree).mean();\n    averageKnots[++newKnotIndex] = parameters[numParameters - 1];\n\n    newKnotIndex = -1;\n  \n    ParameterVectorType temporaryParameters(numParameters + 1);\n    KnotVectorType derivativeKnots(numInternalDerivatives);\n    for (DenseIndex i = 0; i < numAverageKnots - 1; ++i)\n    {\n      temporaryParameters[0] = averageKnots[i];\n      ParameterVectorType parameterIndices(numParameters);\n      int temporaryParameterIndex = 1;\n      for (DenseIndex j = 0; j < numParameters; ++j)\n      {\n        Scalar parameter = parameters[j];\n        if (parameter >= averageKnots[i] && parameter < averageKnots[i + 1])\n        {\n          parameterIndices[temporaryParameterIndex] = j;\n          temporaryParameters[temporaryParameterIndex++] = parameter;\n        }\n      }\n      temporaryParameters[temporaryParameterIndex] = averageKnots[i + 1];\n\n      for (int j = 0; j <= temporaryParameterIndex - 2; ++j)\n      {\n        for (DenseIndex k = 0; k < derivativeIndices.size(); ++k)\n        {\n          if (parameterIndices[j + 1] == derivativeIndices[k]\n              && parameterIndices[j + 1] != 0\n              && parameterIndices[j + 1] != numParameters - 1)\n          {\n            derivativeKnots[++newKnotIndex] = temporaryParameters.segment(j, 3).mean();\n            break;\n          }\n        }\n      }\n    }\n    \n    KnotVectorType temporaryKnots(averageKnots.size() + derivativeKnots.size());\n\n    std::merge(averageKnots.data(), averageKnots.data() + averageKnots.size(),\n               derivativeKnots.data(), derivativeKnots.data() + derivativeKnots.size(),\n               temporaryKnots.data());\n\n    // Number of knots (one for each point and derivative) plus spline order.\n    DenseIndex numKnots = numParameters + numDerivatives + degree + 1;\n    knots.resize(numKnots);\n\n    knots.head(degree).fill(temporaryKnots[0]);\n    knots.tail(degree).fill(temporaryKnots.template tail<1>()[0]);\n    knots.segment(degree, temporaryKnots.size()) = temporaryKnots;\n  }\n\n  /**\n   * \\brief Computes chord length parameters which are required for spline interpolation.\n   * \\ingroup Splines_Module\n   *\n   * \\param[in] pts The data points to which a spline should be fit.\n   * \\param[out] chord_lengths The resulting chord length vector.\n   *\n   * \\sa Les Piegl and Wayne Tiller, The NURBS book (2nd ed.), 1997, 9.2.1 Global Curve Interpolation to Point Data\n   **/   \n  template <typename PointArrayType, typename KnotVectorType>\n  void ChordLengths(const PointArrayType& pts, KnotVectorType& chord_lengths)\n  {\n    typedef typename KnotVectorType::Scalar Scalar;\n\n    const DenseIndex n = pts.cols();\n\n    // 1. compute the column-wise norms\n    chord_lengths.resize(pts.cols());\n    chord_lengths[0] = 0;\n    chord_lengths.rightCols(n-1) = (pts.array().leftCols(n-1) - pts.array().rightCols(n-1)).matrix().colwise().norm();\n\n    // 2. compute the partial sums\n    std::partial_sum(chord_lengths.data(), chord_lengths.data()+n, chord_lengths.data());\n\n    // 3. normalize the data\n    chord_lengths /= chord_lengths(n-1);\n    chord_lengths(n-1) = Scalar(1);\n  }\n\n  /**\n   * \\brief Spline fitting methods.\n   * \\ingroup Splines_Module\n   **/     \n  template <typename SplineType>\n  struct SplineFitting\n  {\n    typedef typename SplineType::KnotVectorType KnotVectorType;\n    typedef typename SplineType::ParameterVectorType ParameterVectorType;\n\n    /**\n     * \\brief Fits an interpolating Spline to the given data points.\n     *\n     * \\param pts The points for which an interpolating spline will be computed.\n     * \\param degree The degree of the interpolating spline.\n     *\n     * \\returns A spline interpolating the initially provided points.\n     **/\n    template <typename PointArrayType>\n    static SplineType Interpolate(const PointArrayType& pts, DenseIndex degree);\n\n    /**\n     * \\brief Fits an interpolating Spline to the given data points.\n     *\n     * \\param pts The points for which an interpolating spline will be computed.\n     * \\param degree The degree of the interpolating spline.\n     * \\param knot_parameters The knot parameters for the interpolation.\n     *\n     * \\returns A spline interpolating the initially provided points.\n     **/\n    template <typename PointArrayType>\n    static SplineType Interpolate(const PointArrayType& pts, DenseIndex degree, const KnotVectorType& knot_parameters);\n\n    /**\n     * \\brief Fits an interpolating spline to the given data points and\n     * derivatives.\n     * \n     * \\param points The points for which an interpolating spline will be computed.\n     * \\param derivatives The desired derivatives of the interpolating spline at interpolation\n     *                    points.\n     * \\param derivativeIndices An array indicating which point each derivative belongs to. This\n     *                          must be the same size as @a derivatives.\n     * \\param degree The degree of the interpolating spline.\n     *\n     * \\returns A spline interpolating @a points with @a derivatives at those points.\n     *\n     * \\sa Les A. Piegl, Khairan Rajab, Volha Smarodzinana. 2008.\n     * Curve interpolation with directional constraints for engineering design. \n     * Engineering with Computers\n     **/\n    template <typename PointArrayType, typename IndexArray>\n    static SplineType InterpolateWithDerivatives(const PointArrayType& points,\n                                                 const PointArrayType& derivatives,\n                                                 const IndexArray& derivativeIndices,\n                                                 const unsigned int degree);\n\n    /**\n     * \\brief Fits an interpolating spline to the given data points and derivatives.\n     * \n     * \\param points The points for which an interpolating spline will be computed.\n     * \\param derivatives The desired derivatives of the interpolating spline at interpolation points.\n     * \\param derivativeIndices An array indicating which point each derivative belongs to. This\n     *                          must be the same size as @a derivatives.\n     * \\param degree The degree of the interpolating spline.\n     * \\param parameters The parameters corresponding to the interpolation points.\n     *\n     * \\returns A spline interpolating @a points with @a derivatives at those points.\n     *\n     * \\sa Les A. Piegl, Khairan Rajab, Volha Smarodzinana. 2008.\n     * Curve interpolation with directional constraints for engineering design. \n     * Engineering with Computers\n     */\n    template <typename PointArrayType, typename IndexArray>\n    static SplineType InterpolateWithDerivatives(const PointArrayType& points,\n                                                 const PointArrayType& derivatives,\n                                                 const IndexArray& derivativeIndices,\n                                                 const unsigned int degree,\n                                                 const ParameterVectorType& parameters);\n  };\n\n  template <typename SplineType>\n  template <typename PointArrayType>\n  SplineType SplineFitting<SplineType>::Interpolate(const PointArrayType& pts, DenseIndex degree, const KnotVectorType& knot_parameters)\n  {\n    typedef typename SplineType::KnotVectorType::Scalar Scalar;      \n    typedef typename SplineType::ControlPointVectorType ControlPointVectorType;      \n\n    typedef Matrix<Scalar,Dynamic,Dynamic> MatrixType;\n\n    KnotVectorType knots;\n    KnotAveraging(knot_parameters, degree, knots);\n\n    DenseIndex n = pts.cols();\n    MatrixType A = MatrixType::Zero(n,n);\n    for (DenseIndex i=1; i<n-1; ++i)\n    {\n      const DenseIndex span = SplineType::Span(knot_parameters[i], degree, knots);\n\n      // The segment call should somehow be told the spline order at compile time.\n      A.row(i).segment(span-degree, degree+1) = SplineType::BasisFunctions(knot_parameters[i], degree, knots);\n    }\n    A(0,0) = 1.0;\n    A(n-1,n-1) = 1.0;\n\n    HouseholderQR<MatrixType> qr(A);\n\n    // Here, we are creating a temporary due to an Eigen issue.\n    ControlPointVectorType ctrls = qr.solve(MatrixType(pts.transpose())).transpose();\n\n    return SplineType(knots, ctrls);\n  }\n\n  template <typename SplineType>\n  template <typename PointArrayType>\n  SplineType SplineFitting<SplineType>::Interpolate(const PointArrayType& pts, DenseIndex degree)\n  {\n    KnotVectorType chord_lengths; // knot parameters\n    ChordLengths(pts, chord_lengths);\n    return Interpolate(pts, degree, chord_lengths);\n  }\n  \n  template <typename SplineType>\n  template <typename PointArrayType, typename IndexArray>\n  SplineType \n  SplineFitting<SplineType>::InterpolateWithDerivatives(const PointArrayType& points,\n                                                        const PointArrayType& derivatives,\n                                                        const IndexArray& derivativeIndices,\n                                                        const unsigned int degree,\n                                                        const ParameterVectorType& parameters)\n  {\n    typedef typename SplineType::KnotVectorType::Scalar Scalar;      \n    typedef typename SplineType::ControlPointVectorType ControlPointVectorType;\n\n    typedef Matrix<Scalar, Dynamic, Dynamic> MatrixType;\n\n    const DenseIndex n = points.cols() + derivatives.cols();\n    \n    KnotVectorType knots;\n\n    KnotAveragingWithDerivatives(parameters, degree, derivativeIndices, knots);\n    \n    // fill matrix\n    MatrixType A = MatrixType::Zero(n, n);\n\n    // Use these dimensions for quicker populating, then transpose for solving.\n    MatrixType b(points.rows(), n);\n\n    DenseIndex startRow;\n    DenseIndex derivativeStart;\n\n    // End derivatives.\n    if (derivativeIndices[0] == 0)\n    {\n      A.template block<1, 2>(1, 0) << -1, 1;\n      \n      Scalar y = (knots(degree + 1) - knots(0)) / degree;\n      b.col(1) = y*derivatives.col(0);\n      \n      startRow = 2;\n      derivativeStart = 1;\n    }\n    else\n    {\n      startRow = 1;\n      derivativeStart = 0;\n    }\n    if (derivativeIndices[derivatives.cols() - 1] == points.cols() - 1)\n    {\n      A.template block<1, 2>(n - 2, n - 2) << -1, 1;\n\n      Scalar y = (knots(knots.size() - 1) - knots(knots.size() - (degree + 2))) / degree;\n      b.col(b.cols() - 2) = y*derivatives.col(derivatives.cols() - 1);\n    }\n    \n    DenseIndex row = startRow;\n    DenseIndex derivativeIndex = derivativeStart;\n    for (DenseIndex i = 1; i < parameters.size() - 1; ++i)\n    {\n      const DenseIndex span = SplineType::Span(parameters[i], degree, knots);\n\n      if (derivativeIndex < derivativeIndices.size() && derivativeIndices[derivativeIndex] == i)\n      {\n        A.block(row, span - degree, 2, degree + 1)\n          = SplineType::BasisFunctionDerivatives(parameters[i], 1, degree, knots);\n\n        b.col(row++) = points.col(i);\n        b.col(row++) = derivatives.col(derivativeIndex++);\n      }\n      else\n      {\n        A.row(row).segment(span - degree, degree + 1)\n          = SplineType::BasisFunctions(parameters[i], degree, knots);\n        b.col(row++) = points.col(i);\n      }\n    }\n    b.col(0) = points.col(0);\n    b.col(b.cols() - 1) = points.col(points.cols() - 1);\n    A(0,0) = 1;\n    A(n - 1, n - 1) = 1;\n    \n    // Solve\n    FullPivLU<MatrixType> lu(A);\n    ControlPointVectorType controlPoints = lu.solve(MatrixType(b.transpose())).transpose();\n\n    SplineType spline(knots, controlPoints);\n    \n    return spline;\n  }\n  \n  template <typename SplineType>\n  template <typename PointArrayType, typename IndexArray>\n  SplineType\n  SplineFitting<SplineType>::InterpolateWithDerivatives(const PointArrayType& points,\n                                                        const PointArrayType& derivatives,\n                                                        const IndexArray& derivativeIndices,\n                                                        const unsigned int degree)\n  {\n    ParameterVectorType parameters;\n    ChordLengths(points, parameters);\n    return InterpolateWithDerivatives(points, derivatives, derivativeIndices, degree, parameters);\n  }\n}\n\n#endif // EIGEN_SPLINE_FITTING_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/Eigen/src/Splines/SplineFwd.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 20010-2011 Hauke Heibel <hauke.heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#ifndef EIGEN_SPLINES_FWD_H\n#define EIGEN_SPLINES_FWD_H\n\n#include \"../../../../Eigen/Core\"\n\nnamespace Eigen\n{\n    template <typename Scalar, int Dim, int Degree = Dynamic> class Spline;\n\n    template < typename SplineType, int DerivativeOrder = Dynamic > struct SplineTraits {};\n\n    /**\n     * \\ingroup Splines_Module\n     * \\brief Compile-time attributes of the Spline class for Dynamic degree.\n     **/\n    template <typename _Scalar, int _Dim, int _Degree>\n    struct SplineTraits< Spline<_Scalar, _Dim, _Degree>, Dynamic >\n    {\n      typedef _Scalar Scalar; /*!< The spline curve's scalar type. */\n      enum { Dimension = _Dim /*!< The spline curve's dimension. */ };\n      enum { Degree = _Degree /*!< The spline curve's degree. */ };\n\n      enum { OrderAtCompileTime = _Degree==Dynamic ? Dynamic : _Degree+1 /*!< The spline curve's order at compile-time. */ };\n      enum { NumOfDerivativesAtCompileTime = OrderAtCompileTime /*!< The number of derivatives defined for the current spline. */ };\n      \n      enum { DerivativeMemoryLayout = Dimension==1 ? RowMajor : ColMajor /*!< The derivative type's memory layout. */ };\n\n      /** \\brief The data type used to store non-zero basis functions. */\n      typedef Array<Scalar,1,OrderAtCompileTime> BasisVectorType;\n\n      /** \\brief The data type used to store the values of the basis function derivatives. */\n      typedef Array<Scalar,Dynamic,Dynamic,RowMajor,NumOfDerivativesAtCompileTime,OrderAtCompileTime> BasisDerivativeType;\n      \n      /** \\brief The data type used to store the spline's derivative values. */\n      typedef Array<Scalar,Dimension,Dynamic,DerivativeMemoryLayout,Dimension,NumOfDerivativesAtCompileTime> DerivativeType;\n\n      /** \\brief The point type the spline is representing. */\n      typedef Array<Scalar,Dimension,1> PointType;\n      \n      /** \\brief The data type used to store knot vectors. */\n      typedef Array<Scalar,1,Dynamic> KnotVectorType;\n\n      /** \\brief The data type used to store parameter vectors. */\n      typedef Array<Scalar,1,Dynamic> ParameterVectorType;\n      \n      /** \\brief The data type representing the spline's control points. */\n      typedef Array<Scalar,Dimension,Dynamic> ControlPointVectorType;\n    };\n\n    /**\n     * \\ingroup Splines_Module\n     * \\brief Compile-time attributes of the Spline class for fixed degree.\n     *\n     * The traits class inherits all attributes from the SplineTraits of Dynamic degree.\n     **/\n    template < typename _Scalar, int _Dim, int _Degree, int _DerivativeOrder >\n    struct SplineTraits< Spline<_Scalar, _Dim, _Degree>, _DerivativeOrder > : public SplineTraits< Spline<_Scalar, _Dim, _Degree> >\n    {\n      enum { OrderAtCompileTime = _Degree==Dynamic ? Dynamic : _Degree+1 /*!< The spline curve's order at compile-time. */ };\n      enum { NumOfDerivativesAtCompileTime = _DerivativeOrder==Dynamic ? Dynamic : _DerivativeOrder+1 /*!< The number of derivatives defined for the current spline. */ };\n      \n      enum { DerivativeMemoryLayout = _Dim==1 ? RowMajor : ColMajor /*!< The derivative type's memory layout. */ };\n\n      /** \\brief The data type used to store the values of the basis function derivatives. */\n      typedef Array<_Scalar,Dynamic,Dynamic,RowMajor,NumOfDerivativesAtCompileTime,OrderAtCompileTime> BasisDerivativeType;\n      \n      /** \\brief The data type used to store the spline's derivative values. */      \n      typedef Array<_Scalar,_Dim,Dynamic,DerivativeMemoryLayout,_Dim,NumOfDerivativesAtCompileTime> DerivativeType;\n    };\n\n    /** \\brief 2D float B-spline with dynamic degree. */\n    typedef Spline<float,2> Spline2f;\n    \n    /** \\brief 3D float B-spline with dynamic degree. */\n    typedef Spline<float,3> Spline3f;\n\n    /** \\brief 2D double B-spline with dynamic degree. */\n    typedef Spline<double,2> Spline2d;\n    \n    /** \\brief 3D double B-spline with dynamic degree. */\n    typedef Spline<double,3> Spline3d;\n}\n\n#endif // EIGEN_SPLINES_FWD_H\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/README.txt",
    "content": "This directory contains contributions from various users.\nThey are provided \"as is\", without any support. Nevertheless,\nmost of them are subject to be included in Eigen in the future.\n\nIn order to use an unsupported module you have to do either:\n\n - add the path_to_eigen/unsupported directory to your include path and do:\n   #include <Eigen/ModuleHeader>\n\n - or directly do:\n   #include <unsupported/Eigen/ModuleHeader>\n\n\nIf you are interested in contributing to one of them, or have other stuff\nyou would like to share, feel free to contact us:\nhttp://eigen.tuxfamily.org/index.php?title=Main_Page#Mailing_list\n\nAny kind of contributions are much appreciated, even very preliminary ones.\nHowever, it:\n - must rely on Eigen,\n - must be highly related to math,\n - should have some general purpose in the sense that it could\n   potentially become an official Eigen module (or be merged into another one).\n\nIn doubt feel free to contact us. For instance, if your addons is very too specific\nbut it shows an interesting way of using Eigen, then it could be a nice demo.\n\n\nThis directory is organized as follow:\n\nunsupported/Eigen/ModuleHeader1\nunsupported/Eigen/ModuleHeader2\nunsupported/Eigen/...\nunsupported/Eigen/src/Module1/SourceFile1.h\nunsupported/Eigen/src/Module1/SourceFile2.h\nunsupported/Eigen/src/Module1/...\nunsupported/Eigen/src/Module2/SourceFile1.h\nunsupported/Eigen/src/Module2/SourceFile2.h\nunsupported/Eigen/src/Module2/...\nunsupported/Eigen/src/...\nunsupported/doc/snippets/.cpp   <- code snippets for the doc\nunsupported/doc/examples/.cpp   <- examples for the doc\nunsupported/doc/TutorialModule1.dox\nunsupported/doc/TutorialModule2.dox\nunsupported/doc/...\nunsupported/test/.cpp           <- unit test files\n\nThe documentation is generated at the same time than the main Eigen documentation.\nThe .html files are generated in: build_dir/doc/html/unsupported/\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/bench/bench_svd.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Gauthier Brun <brun.gauthier@gmail.com>\n// Copyright (C) 2013 Nicolas Carre <nicolas.carre@ensimag.fr>\n// Copyright (C) 2013 Jean Ceccato <jean.ceccato@ensimag.fr>\n// Copyright (C) 2013 Pierre Zoppitelli <pierre.zoppitelli@ensimag.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/\n\n// Bench to compare the efficiency of SVD algorithms\n\n#include <iostream>\n#include <bench/BenchTimer.h>\n#include <unsupported/Eigen/SVD>\n\n\nusing namespace Eigen;\nusing namespace std;\n\n// number of computations of each algorithm before the print of the time\n#ifndef REPEAT\n#define REPEAT 10\n#endif\n\n// number of tests of the same type\n#ifndef NUMBER_SAMPLE\n#define NUMBER_SAMPLE 2\n#endif\n\ntemplate<typename MatrixType>\nvoid bench_svd(const MatrixType& a = MatrixType())\n{\n  MatrixType m = MatrixType::Random(a.rows(), a.cols());\n  BenchTimer timerJacobi;\n  BenchTimer timerBDC;\n  timerJacobi.reset();\n  timerBDC.reset();\n\n  cout << \" Only compute Singular Values\" <<endl;\n  for (int k=1; k<=NUMBER_SAMPLE; ++k)\n  {\n    timerBDC.start();\n    for (int i=0; i<REPEAT; ++i) \n    {\n      BDCSVD<MatrixType> bdc_matrix(m);\n    }\n    timerBDC.stop();\n    \n    timerJacobi.start();\n    for (int i=0; i<REPEAT; ++i) \n    {\n      JacobiSVD<MatrixType> jacobi_matrix(m);\n    }\n    timerJacobi.stop();\n\n\n    cout << \"Sample \" << k << \" : \" << REPEAT << \" computations :  Jacobi : \" << fixed << timerJacobi.value() << \"s \";\n    cout << \" || \" << \" BDC : \" << timerBDC.value() << \"s \" <<endl <<endl;\n      \n    if (timerBDC.value() >= timerJacobi.value())  \n      cout << \"KO : BDC is \" <<  timerJacobi.value() / timerBDC.value() << \"  times faster than Jacobi\" <<endl;\n    else \n      cout << \"OK : BDC is \" << timerJacobi.value() / timerBDC.value() << \"  times faster than Jacobi\"  <<endl;\n      \n  }\n  cout << \"       =================\" <<endl;\n  std::cout<< std::endl;\n  timerJacobi.reset();\n  timerBDC.reset();\n  cout << \" Computes rotation matrix\" <<endl;\n  for (int k=1; k<=NUMBER_SAMPLE; ++k)\n  {\n    timerBDC.start();\n    for (int i=0; i<REPEAT; ++i) \n    {\n      BDCSVD<MatrixType> bdc_matrix(m, ComputeFullU|ComputeFullV);\n    }\n    timerBDC.stop();\n    \n    timerJacobi.start();\n    for (int i=0; i<REPEAT; ++i) \n    {\n      JacobiSVD<MatrixType> jacobi_matrix(m, ComputeFullU|ComputeFullV);\n    }\n    timerJacobi.stop();\n\n\n    cout << \"Sample \" << k << \" : \" << REPEAT << \" computations :  Jacobi : \" << fixed << timerJacobi.value() << \"s \";\n    cout << \" || \" << \" BDC : \" << timerBDC.value() << \"s \" <<endl <<endl;\n      \n    if (timerBDC.value() >= timerJacobi.value())  \n      cout << \"KO : BDC is \" <<  timerJacobi.value() / timerBDC.value() << \"  times faster than Jacobi\" <<endl;\n    else \n      cout << \"OK : BDC is \" << timerJacobi.value() / timerBDC.value() << \"  times faster than Jacobi\"  <<endl;\n      \n  }\n  std::cout<< std::endl;\n}\n\n\n\nint main(int argc, char* argv[])\n{\n  std::cout<< std::endl;\n\n  std::cout<<\"On a (Dynamic, Dynamic) (6, 6) Matrix\" <<std::endl;\n  bench_svd<Matrix<double,Dynamic,Dynamic> >(Matrix<double,Dynamic,Dynamic>(6, 6));\n  \n  std::cout<<\"On a (Dynamic, Dynamic) (32, 32) Matrix\" <<std::endl;\n  bench_svd<Matrix<double,Dynamic,Dynamic> >(Matrix<double,Dynamic,Dynamic>(32, 32));\n\n  //std::cout<<\"On a (Dynamic, Dynamic) (128, 128) Matrix\" <<std::endl;\n  //bench_svd<Matrix<double,Dynamic,Dynamic> >(Matrix<double,Dynamic,Dynamic>(128, 128));\n\n  std::cout<<\"On a (Dynamic, Dynamic) (160, 160) Matrix\" <<std::endl;\n  bench_svd<Matrix<double,Dynamic,Dynamic> >(Matrix<double,Dynamic,Dynamic>(160, 160));\n  \n  std::cout<< \"--------------------------------------------------------------------\"<< std::endl;\n           \n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/CMakeLists.txt",
    "content": "set_directory_properties(PROPERTIES EXCLUDE_FROM_ALL TRUE)\n\nadd_subdirectory(examples)\nadd_subdirectory(snippets)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/Overview.dox",
    "content": "/// \\brief Namespace containing all symbols from the %Eigen library.\nnamespace Eigen {\n\n/** \\mainpage %Eigen's unsupported modules\n\nThis is the API documentation for %Eigen's unsupported modules.\n\nThese modules are contributions from various users. They are provided \"as is\", without any support.\n\nClick on the \\e Modules tab at the top of this page to get a list of all unsupported modules.\n\nDon't miss the <a href=\"../index.html\">official Eigen documentation</a>.\n\n \\subpage SYCL_EIGEN \"SYCL backend for Eigen\"\n\n*/\n\n/*\n\n\\defgroup Unsupported_modules Unsupported modules\n\nThe unsupported modules are contributions from various users. They are\nprovided \"as is\", without any support. Nevertheless, some of them are\nsubject to be included in %Eigen in the future.\n\n*/\n\n/// \\internal \\brief Namespace containing low-level routines from the %Eigen library.\nnamespace internal {}\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/SYCL.dox",
    "content": "/** \\page SYCL_EIGEN Eigen SYCL Backend\n\nUseful information for Eigen SYCL Backend:\n\n- <a href=\"https://developer.codeplay.com/computecppce/latest/getting-started-with-eigen\">Getting Started with Eigen</a> \n\n- <a href=\"https://developer.codeplay.com/computecppce/latest/options-for-building-eigen-sycl\">Options for Building Eigen SYCL</a>  \n\n*/\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/eigendoxy_layout.xml.in",
    "content": "<?xml version=\"1.0\"?>\n<doxygenlayout version=\"1.0\">\n  <!-- Navigation index tabs for HTML output -->\n  <navindex>\n    <tab type=\"user\" url=\"index.html\" title=\"Overview\" />\n    <tab type=\"modules\" visible=\"yes\" title=\"Unsupported Modules\" intro=\"\"/>\n<!--     <tab type=\"mainpage\" visible=\"yes\" title=\"\"/> -->\n    <tab type=\"classlist\" visible=\"yes\" title=\"\" intro=\"\"/>\n<!--     <tab type=\"classmembers\" visible=\"yes\" title=\"\" intro=\"\"/> -->\n  </navindex>\n\n  <!-- Layout definition for a class page -->\n  <class>\n    <briefdescription visible=\"no\"/>\n    <includes visible=\"$SHOW_INCLUDE_FILES\"/>\n    <detaileddescription title=\"\"/>\n    <inheritancegraph visible=\"$CLASS_GRAPH\"/>\n    <collaborationgraph visible=\"$COLLABORATION_GRAPH\"/>\n    <allmemberslink visible=\"yes\"/>\n    <memberdecl>\n      <nestedclasses visible=\"yes\" title=\"\"/>\n      <publictypes title=\"\"/>\n      <publicslots title=\"\"/>\n      <signals title=\"\"/>\n      <publicmethods title=\"\"/>\n      <publicstaticmethods title=\"\"/>\n      <publicattributes title=\"\"/>\n      <publicstaticattributes title=\"\"/>\n      <protectedtypes title=\"\"/>\n      <protectedslots title=\"\"/>\n      <protectedmethods title=\"\"/>\n      <protectedstaticmethods title=\"\"/>\n      <protectedattributes title=\"\"/>\n      <protectedstaticattributes title=\"\"/>\n      <packagetypes title=\"\"/>\n      <packagemethods title=\"\"/>\n      <packagestaticmethods title=\"\"/>\n      <packageattributes title=\"\"/>\n      <packagestaticattributes title=\"\"/>\n      <properties title=\"\"/>\n      <events title=\"\"/>\n      <privatetypes title=\"\"/>\n      <privateslots title=\"\"/>\n      <privatemethods title=\"\"/>\n      <privatestaticmethods title=\"\"/>\n      <privateattributes title=\"\"/>\n      <privatestaticattributes title=\"\"/>\n      <friends title=\"\"/>\n      <related title=\"\" subtitle=\"\"/>\n      <membergroups visible=\"yes\"/>\n    </memberdecl>\n    \n    <memberdef>\n      <inlineclasses title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <constructors title=\"\"/>\n      <functions title=\"\"/>\n      <related title=\"\"/>\n      <variables title=\"\"/>\n      <properties title=\"\"/>\n      <events title=\"\"/>\n    </memberdef>\n    <usedfiles visible=\"$SHOW_USED_FILES\"/>\n    <authorsection visible=\"yes\"/>\n  </class>\n\n  <!-- Layout definition for a namespace page -->\n  <namespace>\n    <briefdescription visible=\"yes\"/>\n    <memberdecl>\n      <nestednamespaces visible=\"yes\" title=\"\"/>\n      <classes visible=\"yes\" title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n      <membergroups visible=\"yes\"/>\n    </memberdecl>\n    <detaileddescription title=\"\"/>\n    <memberdef>\n      <inlineclasses title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n    </memberdef>\n    <authorsection visible=\"yes\"/>\n  </namespace>\n\n  <!-- Layout definition for a file page -->\n  <file>\n    <briefdescription visible=\"yes\"/>\n    <includes visible=\"$SHOW_INCLUDE_FILES\"/>\n    <includegraph visible=\"$INCLUDE_GRAPH\"/>\n    <includedbygraph visible=\"$INCLUDED_BY_GRAPH\"/>\n    <sourcelink visible=\"yes\"/>\n    <memberdecl>\n      <classes visible=\"yes\" title=\"\"/>\n      <namespaces visible=\"yes\" title=\"\"/>\n      <defines title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n      <membergroups visible=\"yes\"/>\n    </memberdecl>\n    <detaileddescription title=\"\"/>\n    <memberdef>\n      <inlineclasses title=\"\"/>\n      <defines title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n    </memberdef>\n    <authorsection/>\n  </file>\n\n  <!-- Layout definition for a group page -->\n  <group>\n    <briefdescription visible=\"no\"/>\n    <detaileddescription title=\"\"/>\n    <groupgraph visible=\"$GROUP_GRAPHS\"/>\n    <memberdecl>\n      <nestedgroups visible=\"yes\" title=\"\"/>\n      <dirs visible=\"yes\" title=\"\"/>\n      <files visible=\"yes\" title=\"\"/>\n      <namespaces visible=\"yes\" title=\"\"/>\n      <classes visible=\"yes\" title=\"\"/>\n      <defines title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <enumvalues title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n      <signals title=\"\"/>\n      <publicslots title=\"\"/>\n      <protectedslots title=\"\"/>\n      <privateslots title=\"\"/>\n      <events title=\"\"/>\n      <properties title=\"\"/>\n      <friends title=\"\"/>\n      <membergroups visible=\"yes\"/>\n    </memberdecl>\n    \n    <memberdef>\n      <pagedocs/>\n      <inlineclasses title=\"\"/>\n      <defines title=\"\"/>\n      <typedefs title=\"\"/>\n      <enums title=\"\"/>\n      <enumvalues title=\"\"/>\n      <functions title=\"\"/>\n      <variables title=\"\"/>\n      <signals title=\"\"/>\n      <publicslots title=\"\"/>\n      <protectedslots title=\"\"/>\n      <privateslots title=\"\"/>\n      <events title=\"\"/>\n      <properties title=\"\"/>\n      <friends title=\"\"/>\n    </memberdef>\n    <authorsection visible=\"yes\"/>\n  </group>\n\n  <!-- Layout definition for a directory page -->\n  <directory>\n    <briefdescription visible=\"yes\"/>\n    <directorygraph visible=\"yes\"/>\n    <memberdecl>\n      <dirs visible=\"yes\"/>\n      <files visible=\"yes\"/>\n    </memberdecl>\n    <detaileddescription title=\"\"/>\n  </directory>\n</doxygenlayout>\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/examples/BVH_Example.cpp",
    "content": "#include <Eigen/StdVector>\n#include <unsupported/Eigen/BVH>\n#include <iostream>\n\nusing namespace Eigen;\ntypedef AlignedBox<double, 2> Box2d;\n\nnamespace Eigen {\n  Box2d bounding_box(const Vector2d &v) { return Box2d(v, v); } //compute the bounding box of a single point\n}\n\nstruct PointPointMinimizer //how to compute squared distances between points and rectangles\n{\n  PointPointMinimizer() : calls(0) {}\n  typedef double Scalar;\n\n  double minimumOnVolumeVolume(const Box2d &r1, const Box2d &r2) { ++calls; return r1.squaredExteriorDistance(r2); }\n  double minimumOnVolumeObject(const Box2d &r, const Vector2d &v) { ++calls; return r.squaredExteriorDistance(v); }\n  double minimumOnObjectVolume(const Vector2d &v, const Box2d &r) { ++calls; return r.squaredExteriorDistance(v); }\n  double minimumOnObjectObject(const Vector2d &v1, const Vector2d &v2) { ++calls; return (v1 - v2).squaredNorm(); }\n\n  int calls;\n};\n\nint main()\n{\n  typedef std::vector<Vector2d, aligned_allocator<Vector2d> > StdVectorOfVector2d;\n  StdVectorOfVector2d redPoints, bluePoints;\n  for(int i = 0; i < 100; ++i) { //initialize random set of red points and blue points\n    redPoints.push_back(Vector2d::Random());\n    bluePoints.push_back(Vector2d::Random());\n  }\n\n  PointPointMinimizer minimizer;\n  double minDistSq = std::numeric_limits<double>::max();\n\n  //brute force to find closest red-blue pair\n  for(int i = 0; i < (int)redPoints.size(); ++i)\n    for(int j = 0; j < (int)bluePoints.size(); ++j)\n      minDistSq = std::min(minDistSq, minimizer.minimumOnObjectObject(redPoints[i], bluePoints[j]));\n  std::cout << \"Brute force distance = \" << sqrt(minDistSq) << \", calls = \" << minimizer.calls << std::endl;\n\n  //using BVH to find closest red-blue pair\n  minimizer.calls = 0;\n  KdBVH<double, 2, Vector2d> redTree(redPoints.begin(), redPoints.end()), blueTree(bluePoints.begin(), bluePoints.end()); //construct the trees\n  minDistSq = BVMinimize(redTree, blueTree, minimizer); //actual BVH minimization call\n  std::cout << \"BVH distance         = \" << sqrt(minDistSq) << \", calls = \" << minimizer.calls << std::endl;\n\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/examples/CMakeLists.txt",
    "content": "file(GLOB examples_SRCS \"*.cpp\")\n\nadd_custom_target(unsupported_examples)\n\ninclude_directories(../../../unsupported ../../../unsupported/test)\n\nforeach(example_src ${examples_SRCS})\n  get_filename_component(example ${example_src} NAME_WE)\n  add_executable(example_${example} ${example_src})\n  if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO)\n    target_link_libraries(example_${example} ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO})\n  endif()\n  add_custom_command(\n    TARGET example_${example}\n    POST_BUILD\n    COMMAND example_${example}\n    ARGS >${CMAKE_CURRENT_BINARY_DIR}/${example}.out\n  )\n  add_dependencies(unsupported_examples example_${example})\nendforeach(example_src)\n\nif(EIGEN_TEST_SYCL)\n  add_subdirectory(SYCL)\nendif(EIGEN_TEST_SYCL)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/examples/EulerAngles.cpp",
    "content": "#include <unsupported/Eigen/EulerAngles>\n#include <iostream>\n\nusing namespace Eigen;\n\nint main()\n{\n  // A common Euler system by many armies around the world,\n  //  where the first one is the azimuth(the angle from the north -\n  //   the same angle that is show in compass)\n  //  and the second one is elevation(the angle from the horizon)\n  //  and the third one is roll(the angle between the horizontal body\n  //   direction and the plane ground surface)\n  // Keep remembering we're using radian angles here!\n  typedef EulerSystem<-EULER_Z, EULER_Y, EULER_X> MyArmySystem;\n  typedef EulerAngles<double, MyArmySystem> MyArmyAngles;\n  \n  MyArmyAngles vehicleAngles(\n    3.14/*PI*/ / 2, /* heading to east, notice that this angle is counter-clockwise */\n    -0.3, /* going down from a mountain */\n    0.1); /* slightly rolled to the right */\n  \n  // Some Euler angles representation that our plane use.\n  EulerAnglesZYZd planeAngles(0.78474, 0.5271, -0.513794);\n  \n  MyArmyAngles planeAnglesInMyArmyAngles(planeAngles);\n  \n  std::cout << \"vehicle angles(MyArmy):     \" << vehicleAngles << std::endl;\n  std::cout << \"plane angles(ZYZ):        \" << planeAngles << std::endl;\n  std::cout << \"plane angles(MyArmy):     \" << planeAnglesInMyArmyAngles << std::endl;\n  \n  // Now lets rotate the plane a little bit\n  std::cout << \"==========================================================\\n\";\n  std::cout << \"rotating plane now!\\n\";\n  std::cout << \"==========================================================\\n\";\n  \n  Quaterniond planeRotated = AngleAxisd(-0.342, Vector3d::UnitY()) * planeAngles;\n  \n  planeAngles = planeRotated;\n  planeAnglesInMyArmyAngles = planeRotated;\n  \n  std::cout << \"new plane angles(ZYZ):     \" << planeAngles << std::endl;\n  std::cout << \"new plane angles(MyArmy): \" << planeAnglesInMyArmyAngles << std::endl;\n  \n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/examples/FFT.cpp",
    "content": "//  To use the simple FFT implementation\n//  g++ -o demofft -I.. -Wall -O3 FFT.cpp \n\n//  To use the FFTW implementation\n//  g++ -o demofft -I.. -DUSE_FFTW -Wall -O3 FFT.cpp -lfftw3 -lfftw3f -lfftw3l\n\n#ifdef USE_FFTW\n#include <fftw3.h>\n#endif\n\n#include <vector>\n#include <complex>\n#include <algorithm>\n#include <iterator>\n#include <iostream>\n#include <Eigen/Core>\n#include <unsupported/Eigen/FFT>\n\nusing namespace std;\nusing namespace Eigen;\n\ntemplate <typename T>\nT mag2(T a)\n{\n    return a*a;\n}\ntemplate <typename T>\nT mag2(std::complex<T> a)\n{\n    return norm(a);\n}\n\ntemplate <typename T>\nT mag2(const std::vector<T> & vec)\n{\n    T out=0;\n    for (size_t k=0;k<vec.size();++k)\n        out += mag2(vec[k]);\n    return out;\n}\n\ntemplate <typename T>\nT mag2(const std::vector<std::complex<T> > & vec)\n{\n    T out=0;\n    for (size_t k=0;k<vec.size();++k)\n        out += mag2(vec[k]);\n    return out;\n}\n\ntemplate <typename T>\nvector<T> operator-(const vector<T> & a,const vector<T> & b )\n{\n    vector<T> c(a);\n    for (size_t k=0;k<b.size();++k) \n        c[k] -= b[k];\n    return c;\n}\n\ntemplate <typename T>\nvoid RandomFill(std::vector<T> & vec)\n{\n    for (size_t k=0;k<vec.size();++k)\n        vec[k] = T( rand() )/T(RAND_MAX) - T(.5);\n}\n\ntemplate <typename T>\nvoid RandomFill(std::vector<std::complex<T> > & vec)\n{\n    for (size_t k=0;k<vec.size();++k)\n        vec[k] = std::complex<T> ( T( rand() )/T(RAND_MAX) - T(.5), T( rand() )/T(RAND_MAX) - T(.5));\n}\n\ntemplate <typename T_time,typename T_freq>\nvoid fwd_inv(size_t nfft)\n{\n    typedef typename NumTraits<T_freq>::Real Scalar;\n    vector<T_time> timebuf(nfft);\n    RandomFill(timebuf);\n\n    vector<T_freq> freqbuf;\n    static FFT<Scalar> fft;\n    fft.fwd(freqbuf,timebuf);\n\n    vector<T_time> timebuf2;\n    fft.inv(timebuf2,freqbuf);\n\n    T_time rmse = mag2(timebuf - timebuf2) / mag2(timebuf);\n    cout << \"roundtrip rmse: \" << rmse << endl;\n}\n\ntemplate <typename T_scalar>\nvoid two_demos(int nfft)\n{\n    cout << \"     scalar \";\n    fwd_inv<T_scalar,std::complex<T_scalar> >(nfft);\n    cout << \"    complex \";\n    fwd_inv<std::complex<T_scalar>,std::complex<T_scalar> >(nfft);\n}\n\nvoid demo_all_types(int nfft)\n{\n    cout << \"nfft=\" << nfft << endl;\n    cout << \"   float\" << endl;\n    two_demos<float>(nfft);\n    cout << \"   double\" << endl;\n    two_demos<double>(nfft);\n    cout << \"   long double\" << endl;\n    two_demos<long double>(nfft);\n}\n\nint main()\n{\n    demo_all_types( 2*3*4*5*7 );\n    demo_all_types( 2*9*16*25 );\n    demo_all_types( 1024 );\n    return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/examples/MatrixExponential.cpp",
    "content": "#include <unsupported/Eigen/MatrixFunctions>\n#include <iostream>\n\nusing namespace Eigen;\n\nint main()\n{\n  const double pi = std::acos(-1.0);\n\n  MatrixXd A(3,3);\n  A << 0,    -pi/4, 0,\n       pi/4, 0,     0,\n       0,    0,     0;\n  std::cout << \"The matrix A is:\\n\" << A << \"\\n\\n\";\n  std::cout << \"The matrix exponential of A is:\\n\" << A.exp() << \"\\n\\n\";\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/examples/MatrixFunction.cpp",
    "content": "#include <unsupported/Eigen/MatrixFunctions>\n#include <iostream>\n\nusing namespace Eigen;\n\nstd::complex<double> expfn(std::complex<double> x, int)\n{\n  return std::exp(x);\n}\n\nint main()\n{\n  const double pi = std::acos(-1.0);\n\n  MatrixXd A(3,3);\n  A << 0,    -pi/4, 0,\n       pi/4, 0,     0,\n       0,    0,     0;\n\n  std::cout << \"The matrix A is:\\n\" << A << \"\\n\\n\";\n  std::cout << \"The matrix exponential of A is:\\n\" \n            << A.matrixFunction(expfn) << \"\\n\\n\";\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/examples/MatrixLogarithm.cpp",
    "content": "#include <unsupported/Eigen/MatrixFunctions>\n#include <iostream>\n\nusing namespace Eigen;\n\nint main()\n{\n  using std::sqrt;\n  MatrixXd A(3,3);\n  A << 0.5*sqrt(2), -0.5*sqrt(2), 0,\n       0.5*sqrt(2),  0.5*sqrt(2), 0,\n       0,            0,           1;\n  std::cout << \"The matrix A is:\\n\" << A << \"\\n\\n\";\n  std::cout << \"The matrix logarithm of A is:\\n\" << A.log() << \"\\n\";\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/examples/MatrixPower.cpp",
    "content": "#include <unsupported/Eigen/MatrixFunctions>\n#include <iostream>\n\nusing namespace Eigen;\n\nint main()\n{\n  const double pi = std::acos(-1.0);\n  Matrix3d A;\n  A << cos(1), -sin(1), 0,\n       sin(1),  cos(1), 0,\n\t   0 ,      0 , 1;\n  std::cout << \"The matrix A is:\\n\" << A << \"\\n\\n\"\n\t       \"The matrix power A^(pi/4) is:\\n\" << A.pow(pi/4) << std::endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/examples/MatrixPower_optimal.cpp",
    "content": "#include <unsupported/Eigen/MatrixFunctions>\n#include <iostream>\n\nusing namespace Eigen;\n\nint main()\n{\n  Matrix4cd A = Matrix4cd::Random();\n  MatrixPower<Matrix4cd> Apow(A);\n\n  std::cout << \"The matrix A is:\\n\" << A << \"\\n\\n\"\n\t       \"A^3.1 is:\\n\" << Apow(3.1) << \"\\n\\n\"\n\t       \"A^3.3 is:\\n\" << Apow(3.3) << \"\\n\\n\"\n\t       \"A^3.7 is:\\n\" << Apow(3.7) << \"\\n\\n\"\n\t       \"A^3.9 is:\\n\" << Apow(3.9) << std::endl;\n  return 0;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/examples/MatrixSine.cpp",
    "content": "#include <unsupported/Eigen/MatrixFunctions>\n#include <iostream>\n\nusing namespace Eigen;\n\nint main()\n{\n  MatrixXd A = MatrixXd::Random(3,3);\n  std::cout << \"A = \\n\" << A << \"\\n\\n\";\n\n  MatrixXd sinA = A.sin();\n  std::cout << \"sin(A) = \\n\" << sinA << \"\\n\\n\";\n\n  MatrixXd cosA = A.cos();\n  std::cout << \"cos(A) = \\n\" << cosA << \"\\n\\n\";\n  \n  // The matrix functions satisfy sin^2(A) + cos^2(A) = I, \n  // like the scalar functions.\n  std::cout << \"sin^2(A) + cos^2(A) = \\n\" << sinA*sinA + cosA*cosA << \"\\n\\n\";\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/examples/MatrixSinh.cpp",
    "content": "#include <unsupported/Eigen/MatrixFunctions>\n#include <iostream>\n\nusing namespace Eigen;\n\nint main()\n{\n  MatrixXf A = MatrixXf::Random(3,3);\n  std::cout << \"A = \\n\" << A << \"\\n\\n\";\n\n  MatrixXf sinhA = A.sinh();\n  std::cout << \"sinh(A) = \\n\" << sinhA << \"\\n\\n\";\n\n  MatrixXf coshA = A.cosh();\n  std::cout << \"cosh(A) = \\n\" << coshA << \"\\n\\n\";\n  \n  // The matrix functions satisfy cosh^2(A) - sinh^2(A) = I, \n  // like the scalar functions.\n  std::cout << \"cosh^2(A) - sinh^2(A) = \\n\" << coshA*coshA - sinhA*sinhA << \"\\n\\n\";\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/examples/MatrixSquareRoot.cpp",
    "content": "#include <unsupported/Eigen/MatrixFunctions>\n#include <iostream>\n\nusing namespace Eigen;\n\nint main()\n{\n  const double pi = std::acos(-1.0);\n\n  MatrixXd A(2,2);\n  A << cos(pi/3), -sin(pi/3), \n       sin(pi/3),  cos(pi/3);\n  std::cout << \"The matrix A is:\\n\" << A << \"\\n\\n\";\n  std::cout << \"The matrix square root of A is:\\n\" << A.sqrt() << \"\\n\\n\";\n  std::cout << \"The square of the last matrix is:\\n\" << A.sqrt() * A.sqrt() << \"\\n\";\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/examples/PolynomialSolver1.cpp",
    "content": "#include <unsupported/Eigen/Polynomials>\n#include <vector>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  typedef Matrix<double,5,1> Vector5d;\n\n  Vector5d roots = Vector5d::Random();\n  cout << \"Roots: \" << roots.transpose() << endl;\n  Eigen::Matrix<double,6,1> polynomial;\n  roots_to_monicPolynomial( roots, polynomial );\n\n  PolynomialSolver<double,5> psolve( polynomial );\n  cout << \"Complex roots: \" << psolve.roots().transpose() << endl;\n\n  std::vector<double> realRoots;\n  psolve.realRoots( realRoots );\n  Map<Vector5d> mapRR( &realRoots[0] );\n  cout << \"Real roots: \" << mapRR.transpose() << endl;\n\n  cout << endl;\n  cout << \"Illustration of the convergence problem with the QR algorithm: \" << endl;\n  cout << \"---------------------------------------------------------------\" << endl;\n  Eigen::Matrix<float,7,1> hardCase_polynomial;\n  hardCase_polynomial <<\n  -0.957, 0.9219, 0.3516, 0.9453, -0.4023, -0.5508, -0.03125;\n  cout << \"Hard case polynomial defined by floats: \" << hardCase_polynomial.transpose() << endl;\n  PolynomialSolver<float,6> psolvef( hardCase_polynomial );\n  cout << \"Complex roots: \" << psolvef.roots().transpose() << endl;\n  Eigen::Matrix<float,6,1> evals;\n  for( int i=0; i<6; ++i ){ evals[i] = std::abs( poly_eval( hardCase_polynomial, psolvef.roots()[i] ) ); }\n  cout << \"Norms of the evaluations of the polynomial at the roots: \" << evals.transpose() << endl << endl;\n\n  cout << \"Using double's almost always solves the problem for small degrees: \" << endl;\n  cout << \"-------------------------------------------------------------------\" << endl;\n  PolynomialSolver<double,6> psolve6d( hardCase_polynomial.cast<double>() );\n  cout << \"Complex roots: \" << psolve6d.roots().transpose() << endl;\n  for( int i=0; i<6; ++i )\n  {\n    std::complex<float> castedRoot( psolve6d.roots()[i].real(), psolve6d.roots()[i].imag() );\n    evals[i] = std::abs( poly_eval( hardCase_polynomial, castedRoot ) );\n  }\n  cout << \"Norms of the evaluations of the polynomial at the roots: \" << evals.transpose() << endl << endl;\n\n  cout.precision(10);\n  cout << \"The last root in float then in double: \" << psolvef.roots()[5] << \"\\t\" << psolve6d.roots()[5] << endl;\n  std::complex<float> castedRoot( psolve6d.roots()[5].real(), psolve6d.roots()[5].imag() );\n  cout << \"Norm of the difference: \" << std::abs( psolvef.roots()[5] - castedRoot ) << endl;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/examples/PolynomialUtils1.cpp",
    "content": "#include <unsupported/Eigen/Polynomials>\n#include <iostream>\n\nusing namespace Eigen;\nusing namespace std;\n\nint main()\n{\n  Vector4d roots = Vector4d::Random();\n  cout << \"Roots: \" << roots.transpose() << endl;\n  Eigen::Matrix<double,5,1> polynomial;\n  roots_to_monicPolynomial( roots, polynomial );\n  cout << \"Polynomial: \";\n  for( int i=0; i<4; ++i ){ cout << polynomial[i] << \".x^\" << i << \"+ \"; }\n  cout << polynomial[4] << \".x^4\" << endl;\n  Vector4d evaluation;\n  for( int i=0; i<4; ++i ){\n    evaluation[i] = poly_eval( polynomial, roots[i] ); }\n  cout << \"Evaluation of the polynomial at the roots: \" << evaluation.transpose();\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/examples/SYCL/CMakeLists.txt",
    "content": "FILE(GLOB examples_SRCS \"*.cpp\")\n\nset(EIGEN_SYCL ON)\nlist(APPEND CMAKE_EXE_LINKER_FLAGS -pthread)\nif(EIGEN_SYCL_TRISYCL)\n  set(CMAKE_CXX_STANDARD 14)\n  set(STD_CXX_FLAG \"-std=c++1z\")\nelse(EIGEN_SYCL_TRISYCL)\n  if(MSVC)\n    # Set the host and device compilers C++ standard to C++14. On Windows setting this to C++11\n    # can cause issues with the ComputeCpp device compiler parsing Visual Studio Headers.\n    set(CMAKE_CXX_STANDARD 14)\n    list(APPEND COMPUTECPP_USER_FLAGS -DWIN32)\n  else()\n    set(CMAKE_CXX_STANDARD 11)\n    list(APPEND COMPUTECPP_USER_FLAGS -Wall)\n  endif()\n  # The following flags are not supported by Clang and can cause warnings\n  # if used with -Werror so they are removed here.\n  if(COMPUTECPP_USE_COMPILER_DRIVER)\n    set(CMAKE_CXX_COMPILER ${ComputeCpp_DEVICE_COMPILER_EXECUTABLE})\n    string(REPLACE \"-Wlogical-op\" \"\" CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS})\n    string(REPLACE \"-Wno-psabi\" \"\" CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS})\n    string(REPLACE \"-ansi\" \"\" CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS})\n  endif()\n  list(APPEND COMPUTECPP_USER_FLAGS\n      -DEIGEN_NO_ASSERTION_CHECKING=1\n      -no-serial-memop\n      -Xclang\n      -cl-mad-enable)\nendif(EIGEN_SYCL_TRISYCL)\n\nFOREACH(example_src ${examples_SRCS})\n  GET_FILENAME_COMPONENT(example ${example_src} NAME_WE)\n  ei_add_test_internal(${example} example_${example})\n  ADD_DEPENDENCIES(unsupported_examples example_${example})\nENDFOREACH(example_src)\nset(EIGEN_SYCL OFF)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/examples/SYCL/CwiseMul.cpp",
    "content": "#include <iostream>\n#define EIGEN_USE_SYCL\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\nint main()\n{\n  using DataType = float;\n  using IndexType = int64_t;\n  constexpr auto DataLayout = Eigen::RowMajor;\n\n  auto devices = Eigen::get_sycl_supported_devices();\n  const auto device_selector = *devices.begin();\n  Eigen::QueueInterface queueInterface(device_selector);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  \n  // create the tensors to be used in the operation\n  IndexType sizeDim1 = 3;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 3;\n  array<IndexType, 3> tensorRange = {{sizeDim1, sizeDim2, sizeDim3}};\n\n  // initialize the tensors with the data we want manipulate to\n  Tensor<DataType, 3,DataLayout, IndexType> in1(tensorRange);\n  Tensor<DataType, 3,DataLayout, IndexType> in2(tensorRange);\n  Tensor<DataType, 3,DataLayout, IndexType> out(tensorRange);\n\n  // set up some random data in the tensors to be multiplied\n  in1 = in1.random();\n  in2 = in2.random();\n\n  // allocate memory for the tensors\n  DataType * gpu_in1_data  = static_cast<DataType*>(sycl_device.allocate(in1.size()*sizeof(DataType)));\n  DataType * gpu_in2_data  = static_cast<DataType*>(sycl_device.allocate(in2.size()*sizeof(DataType)));\n  DataType * gpu_out_data =  static_cast<DataType*>(sycl_device.allocate(out.size()*sizeof(DataType)));\n\n  // \n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu_in1(gpu_in1_data, tensorRange);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu_in2(gpu_in2_data, tensorRange);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu_out(gpu_out_data, tensorRange);\n\n  // copy the memory to the device and do the c=a*b calculation\n  sycl_device.memcpyHostToDevice(gpu_in1_data, in1.data(),(in1.size())*sizeof(DataType));\n  sycl_device.memcpyHostToDevice(gpu_in2_data, in2.data(),(in2.size())*sizeof(DataType));\n  gpu_out.device(sycl_device) = gpu_in1 * gpu_in2;\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data,(out.size())*sizeof(DataType));\n  sycl_device.synchronize();\n\n  // print out the results\n   for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        std::cout << \"device_out\" << \"(\" << i << \", \" << j << \", \" << k << \") : \" << out(i,j,k) \n                  << \" vs host_out\" << \"(\" << i << \", \" << j << \", \" << k << \") : \" << in1(i,j,k) * in2(i,j,k) << \"\\n\";\n      }\n    }\n  }\n  printf(\"c=a*b Done\\n\");\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/doc/snippets/CMakeLists.txt",
    "content": "file(GLOB snippets_SRCS \"*.cpp\")\n\nadd_custom_target(unsupported_snippets)\n\nforeach(snippet_src ${snippets_SRCS})\n  get_filename_component(snippet ${snippet_src} NAME_WE)\n  set(compile_snippet_target compile_${snippet})\n  set(compile_snippet_src ${compile_snippet_target}.cpp)\n  file(READ ${snippet_src} snippet_source_code)\n  configure_file(${PROJECT_SOURCE_DIR}/doc/snippets/compile_snippet.cpp.in\n                 ${CMAKE_CURRENT_BINARY_DIR}/${compile_snippet_src})\n  add_executable(${compile_snippet_target}\n                 ${CMAKE_CURRENT_BINARY_DIR}/${compile_snippet_src})\n  if(EIGEN_STANDARD_LIBRARIES_TO_LINK_TO)\n    target_link_libraries(${compile_snippet_target} ${EIGEN_STANDARD_LIBRARIES_TO_LINK_TO})\n  endif()\n  add_custom_command(\n    TARGET ${compile_snippet_target}\n    POST_BUILD\n    COMMAND ${compile_snippet_target}\n    ARGS >${CMAKE_CURRENT_BINARY_DIR}/${snippet}.out\n  )\n  add_dependencies(unsupported_snippets ${compile_snippet_target})\n  set_source_files_properties(${CMAKE_CURRENT_BINARY_DIR}/${compile_snippet_src}\n                              PROPERTIES OBJECT_DEPENDS ${snippet_src})\nendforeach(snippet_src)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/BVH.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Ilya Baran <ibaran@mit.edu>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/StdVector>\n#include <Eigen/Geometry>\n#include <unsupported/Eigen/BVH>\n\nnamespace Eigen {\n\ntemplate<typename Scalar, int Dim> AlignedBox<Scalar, Dim> bounding_box(const Matrix<Scalar, Dim, 1> &v) { return AlignedBox<Scalar, Dim>(v); }\n\n}\n\n\ntemplate<int Dim>\nstruct Ball\n{\nEIGEN_MAKE_ALIGNED_OPERATOR_NEW_IF_VECTORIZABLE_FIXED_SIZE(double, Dim)\n\n  typedef Matrix<double, Dim, 1> VectorType;\n\n  Ball() {}\n  Ball(const VectorType &c, double r) : center(c), radius(r) {}\n\n  VectorType center;\n  double radius;\n};\ntemplate<int Dim> AlignedBox<double, Dim> bounding_box(const Ball<Dim> &b)\n{ return AlignedBox<double, Dim>(b.center.array() - b.radius, b.center.array() + b.radius); }\n\ninline double SQR(double x) { return x * x; }\n\ntemplate<int Dim>\nstruct BallPointStuff //this class provides functions to be both an intersector and a minimizer, both for a ball and a point and for two trees\n{\n  typedef double Scalar;\n  typedef Matrix<double, Dim, 1> VectorType;\n  typedef Ball<Dim> BallType;\n  typedef AlignedBox<double, Dim> BoxType;\n\n  BallPointStuff() : calls(0), count(0) {}\n  BallPointStuff(const VectorType &inP) : p(inP), calls(0), count(0) {}\n\n\n  bool intersectVolume(const BoxType &r) { ++calls; return r.contains(p); }\n  bool intersectObject(const BallType &b) {\n    ++calls;\n    if((b.center - p).squaredNorm() < SQR(b.radius))\n      ++count;\n    return false; //continue\n  }\n\n  bool intersectVolumeVolume(const BoxType &r1, const BoxType &r2) { ++calls; return !(r1.intersection(r2)).isNull(); }\n  bool intersectVolumeObject(const BoxType &r, const BallType &b) { ++calls; return r.squaredExteriorDistance(b.center) < SQR(b.radius); }\n  bool intersectObjectVolume(const BallType &b, const BoxType &r) { ++calls; return r.squaredExteriorDistance(b.center) < SQR(b.radius); }\n  bool intersectObjectObject(const BallType &b1, const BallType &b2){\n    ++calls;\n    if((b1.center - b2.center).norm() < b1.radius + b2.radius)\n      ++count;\n    return false;\n  }\n  bool intersectVolumeObject(const BoxType &r, const VectorType &v) { ++calls; return r.contains(v); }\n  bool intersectObjectObject(const BallType &b, const VectorType &v){\n    ++calls;\n    if((b.center - v).squaredNorm() < SQR(b.radius))\n      ++count;\n    return false;\n  }\n\n  double minimumOnVolume(const BoxType &r) { ++calls; return r.squaredExteriorDistance(p); }\n  double minimumOnObject(const BallType &b) { ++calls; return (std::max)(0., (b.center - p).squaredNorm() - SQR(b.radius)); }\n  double minimumOnVolumeVolume(const BoxType &r1, const BoxType &r2) { ++calls; return r1.squaredExteriorDistance(r2); }\n  double minimumOnVolumeObject(const BoxType &r, const BallType &b) { ++calls; return SQR((std::max)(0., r.exteriorDistance(b.center) - b.radius)); }\n  double minimumOnObjectVolume(const BallType &b, const BoxType &r) { ++calls; return SQR((std::max)(0., r.exteriorDistance(b.center) - b.radius)); }\n  double minimumOnObjectObject(const BallType &b1, const BallType &b2){ ++calls; return SQR((std::max)(0., (b1.center - b2.center).norm() - b1.radius - b2.radius)); }\n  double minimumOnVolumeObject(const BoxType &r, const VectorType &v) { ++calls; return r.squaredExteriorDistance(v); }\n  double minimumOnObjectObject(const BallType &b, const VectorType &v){ ++calls; return SQR((std::max)(0., (b.center - v).norm() - b.radius)); }\n\n  VectorType p;\n  int calls;\n  int count;\n};\n\n\ntemplate<int Dim>\nstruct TreeTest\n{\n  typedef Matrix<double, Dim, 1> VectorType;\n  typedef std::vector<VectorType, aligned_allocator<VectorType> > VectorTypeList;\n  typedef Ball<Dim> BallType;\n  typedef std::vector<BallType, aligned_allocator<BallType> > BallTypeList;\n  typedef AlignedBox<double, Dim> BoxType;\n\n  void testIntersect1()\n  {\n    BallTypeList b;\n    for(int i = 0; i < 500; ++i) {\n        b.push_back(BallType(VectorType::Random(), 0.5 * internal::random(0., 1.)));\n    }\n    KdBVH<double, Dim, BallType> tree(b.begin(), b.end());\n\n    VectorType pt = VectorType::Random();\n    BallPointStuff<Dim> i1(pt), i2(pt);\n\n    for(int i = 0; i < (int)b.size(); ++i)\n      i1.intersectObject(b[i]);\n\n    BVIntersect(tree, i2);\n\n    VERIFY(i1.count == i2.count);\n  }\n\n  void testMinimize1()\n  {\n    BallTypeList b;\n    for(int i = 0; i < 500; ++i) {\n        b.push_back(BallType(VectorType::Random(), 0.01 * internal::random(0., 1.)));\n    }\n    KdBVH<double, Dim, BallType> tree(b.begin(), b.end());\n\n    VectorType pt = VectorType::Random();\n    BallPointStuff<Dim> i1(pt), i2(pt);\n\n    double m1 = (std::numeric_limits<double>::max)(), m2 = m1;\n\n    for(int i = 0; i < (int)b.size(); ++i)\n      m1 = (std::min)(m1, i1.minimumOnObject(b[i]));\n\n    m2 = BVMinimize(tree, i2);\n\n    VERIFY_IS_APPROX(m1, m2);\n  }\n\n  void testIntersect2()\n  {\n    BallTypeList b;\n    VectorTypeList v;\n\n    for(int i = 0; i < 50; ++i) {\n        b.push_back(BallType(VectorType::Random(), 0.5 * internal::random(0., 1.)));\n        for(int j = 0; j < 3; ++j)\n            v.push_back(VectorType::Random());\n    }\n\n    KdBVH<double, Dim, BallType> tree(b.begin(), b.end());\n    KdBVH<double, Dim, VectorType> vTree(v.begin(), v.end());\n\n    BallPointStuff<Dim> i1, i2;\n\n    for(int i = 0; i < (int)b.size(); ++i)\n        for(int j = 0; j < (int)v.size(); ++j)\n            i1.intersectObjectObject(b[i], v[j]);\n\n    BVIntersect(tree, vTree, i2);\n\n    VERIFY(i1.count == i2.count);\n  }\n\n  void testMinimize2()\n  {\n    BallTypeList b;\n    VectorTypeList v;\n\n    for(int i = 0; i < 50; ++i) {\n        b.push_back(BallType(VectorType::Random(), 1e-7 + 1e-6 * internal::random(0., 1.)));\n        for(int j = 0; j < 3; ++j)\n            v.push_back(VectorType::Random());\n    }\n\n    KdBVH<double, Dim, BallType> tree(b.begin(), b.end());\n    KdBVH<double, Dim, VectorType> vTree(v.begin(), v.end());\n\n    BallPointStuff<Dim> i1, i2;\n\n    double m1 = (std::numeric_limits<double>::max)(), m2 = m1;\n\n    for(int i = 0; i < (int)b.size(); ++i)\n        for(int j = 0; j < (int)v.size(); ++j)\n            m1 = (std::min)(m1, i1.minimumOnObjectObject(b[i], v[j]));\n\n    m2 = BVMinimize(tree, vTree, i2);\n\n    VERIFY_IS_APPROX(m1, m2);\n  }\n};\n\n\nEIGEN_DECLARE_TEST(BVH)\n{\n  for(int i = 0; i < g_repeat; i++) {\n#ifdef EIGEN_TEST_PART_1\n    TreeTest<2> test2;\n    CALL_SUBTEST(test2.testIntersect1());\n    CALL_SUBTEST(test2.testMinimize1());\n    CALL_SUBTEST(test2.testIntersect2());\n    CALL_SUBTEST(test2.testMinimize2());\n#endif\n\n#ifdef EIGEN_TEST_PART_2\n    TreeTest<3> test3;\n    CALL_SUBTEST(test3.testIntersect1());\n    CALL_SUBTEST(test3.testMinimize1());\n    CALL_SUBTEST(test3.testIntersect2());\n    CALL_SUBTEST(test3.testMinimize2());\n#endif\n\n#ifdef EIGEN_TEST_PART_3\n    TreeTest<4> test4;\n    CALL_SUBTEST(test4.testIntersect1());\n    CALL_SUBTEST(test4.testMinimize1());\n    CALL_SUBTEST(test4.testIntersect2());\n    CALL_SUBTEST(test4.testMinimize2());\n#endif\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/CMakeLists.txt",
    "content": "# The file split_test_helper.h was generated at first run,\n# it is now included in test/\nif(EXISTS ${CMAKE_CURRENT_BINARY_DIR}/split_test_helper.h)\n  file(REMOVE ${CMAKE_CURRENT_BINARY_DIR}/split_test_helper.h)\nendif()\n\nset_property(GLOBAL PROPERTY EIGEN_CURRENT_SUBPROJECT \"Unsupported\")\nadd_custom_target(BuildUnsupported)\n\ninclude_directories(../../test ../../unsupported ../../Eigen\n                    ${CMAKE_CURRENT_BINARY_DIR}/../../test)\n\nfind_package (Threads)\n\nfind_package(GoogleHash)\nif(GoogleHash_FOUND)\n  add_definitions(\"-DEIGEN_GOOGLEHASH_SUPPORT\")\n  include_directories(${GOOGLEHASH_INCLUDES})\n  ei_add_property(EIGEN_TESTED_BACKENDS  \"GoogleHash, \")\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS  \"GoogleHash, \")\nendif()\n\n\nfind_package(Adolc)\nif(Adolc_FOUND)\n  include_directories(${ADOLC_INCLUDES})\n  ei_add_property(EIGEN_TESTED_BACKENDS \"Adolc, \")\n  if(EIGEN_TEST_CXX11)\n    ei_add_test(forward_adolc \"\" ${ADOLC_LIBRARIES})\n  else()\n    message(STATUS \"Adolc found, but tests require C++11 mode\")\n  endif()\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS \"Adolc, \")\nendif()\n\n# this test seems to never have been successful on x87, so is considered to contain a FP-related bug.\n# see thread: \"non-linear optimization test summary\"\nei_add_test(NonLinearOptimization)\n\nei_add_test(NumericalDiff)\nei_add_test(autodiff_scalar)\nei_add_test(autodiff)\n\nei_add_test(BVH)\n\nei_add_test(matrix_exponential)\nei_add_test(matrix_function)\nei_add_test(matrix_power)\nei_add_test(matrix_square_root)\nei_add_test(alignedvector3)\n\nei_add_test(FFT)\n\nei_add_test(EulerAngles)\n\nfind_package(MPFR 2.3.0)\nfind_package(GMP)\nif(MPFR_FOUND AND EIGEN_COMPILER_SUPPORT_CPP11)\n  include_directories(${MPFR_INCLUDES} ./mpreal)\n  ei_add_property(EIGEN_TESTED_BACKENDS \"MPFR C++, \")\n  set(EIGEN_MPFR_TEST_LIBRARIES ${MPFR_LIBRARIES} ${GMP_LIBRARIES})\n ei_add_test(mpreal_support \"-std=c++11\" \"${EIGEN_MPFR_TEST_LIBRARIES}\" )\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS \"MPFR C++, \")\nendif()\n\nei_add_test(sparse_extra   \"\" \"\")\n\nfind_package(FFTW)\nif(FFTW_FOUND)\n  ei_add_property(EIGEN_TESTED_BACKENDS \"fftw, \")\n  include_directories( ${FFTW_INCLUDES} )\n  if(FFTWL_LIB)\n    ei_add_test(FFTW  \"-DEIGEN_FFTW_DEFAULT -DEIGEN_HAS_FFTWL\" \"${FFTW_LIBRARIES}\" )\n  else()\n    ei_add_test(FFTW  \"-DEIGEN_FFTW_DEFAULT\" \"${FFTW_LIBRARIES}\" )\n  endif()\nelse()\n  ei_add_property(EIGEN_MISSING_BACKENDS \"fftw, \")\nendif()\n\noption(EIGEN_TEST_OPENGL \"Enable OpenGL support in unit tests\" OFF)\nif(EIGEN_TEST_OPENGL)\n  find_package(OpenGL)\n  find_package(GLUT)\n  find_package(GLEW)\n  if(OPENGL_FOUND AND GLUT_FOUND AND GLEW_FOUND)\n    include_directories(${OPENGL_INCLUDE_DIR} ${GLUT_INCLUDE_DIR} ${GLEW_INCLUDE_DIRS})\n    ei_add_property(EIGEN_TESTED_BACKENDS \"OpenGL, \")\n    set(EIGEN_GL_LIB ${GLUT_LIBRARIES} ${GLEW_LIBRARIES} ${OPENGL_LIBRARIES})\n    ei_add_test(openglsupport  \"\" \"${EIGEN_GL_LIB}\" )\n  else()\n    ei_add_property(EIGEN_MISSING_BACKENDS \"OpenGL, \")\n  endif()\nelse()\n    ei_add_property(EIGEN_MISSING_BACKENDS \"OpenGL, \")\nendif()\n\nei_add_test(polynomialsolver)\nei_add_test(polynomialutils)\nei_add_test(splines)\nei_add_test(gmres)\nei_add_test(dgmres)\nei_add_test(minres)\nei_add_test(idrs)\nei_add_test(levenberg_marquardt)\nei_add_test(kronecker_product)\nei_add_test(bessel_functions)\nei_add_test(special_functions)\nei_add_test(special_packetmath \"-DEIGEN_FAST_MATH=1\")\n\nif(EIGEN_TEST_CXX11)\n  if(EIGEN_TEST_SYCL)\n    set(EIGEN_SYCL ON)\n    # Forward CMake options as preprocessor definitions\n    if(EIGEN_SYCL_USE_DEFAULT_SELECTOR)\n      add_definitions(-DEIGEN_SYCL_USE_DEFAULT_SELECTOR=${EIGEN_SYCL_USE_DEFAULT_SELECTOR})\n    endif()\n    if(EIGEN_SYCL_NO_LOCAL_MEM)\n      add_definitions(-DEIGEN_SYCL_NO_LOCAL_MEM=${EIGEN_SYCL_NO_LOCAL_MEM})\n    endif()\n    if(EIGEN_SYCL_LOCAL_MEM)\n      add_definitions(-DEIGEN_SYCL_LOCAL_MEM=${EIGEN_SYCL_LOCAL_MEM})\n    endif()\n    if(EIGEN_SYCL_MAX_GLOBAL_RANGE)\n      add_definitions(-DEIGEN_SYCL_MAX_GLOBAL_RANGE=${EIGEN_SYCL_MAX_GLOBAL_RANGE})\n    endif()\n    if(EIGEN_SYCL_LOCAL_THREAD_DIM0)\n      add_definitions(-DEIGEN_SYCL_LOCAL_THREAD_DIM0=${EIGEN_SYCL_LOCAL_THREAD_DIM0})\n    endif()\n    if(EIGEN_SYCL_LOCAL_THREAD_DIM1)\n      add_definitions(-DEIGEN_SYCL_LOCAL_THREAD_DIM1=${EIGEN_SYCL_LOCAL_THREAD_DIM1})\n    endif()\n    if(EIGEN_SYCL_REG_M)\n      add_definitions(-DEIGEN_SYCL_REG_M=${EIGEN_SYCL_REG_M})\n    endif()\n    if(EIGEN_SYCL_REG_N)\n      add_definitions(-DEIGEN_SYCL_REG_N=${EIGEN_SYCL_REG_N})\n    endif()\n    if(EIGEN_SYCL_USE_PROGRAM_CLASS)\n      add_definitions(-DEIGEN_SYCL_USE_PROGRAM_CLASS=${EIGEN_SYCL_USE_PROGRAM_CLASS})\n    endif()\n    if(EIGEN_SYCL_ASYNC_EXECUTION)\n      add_definitions(-DEIGEN_SYCL_ASYNC_EXECUTION=${EIGEN_SYCL_ASYNC_EXECUTION})\n    endif()\n    if(EIGEN_SYCL_DISABLE_SKINNY)\n      add_definitions(-DEIGEN_SYCL_DISABLE_SKINNY=${EIGEN_SYCL_DISABLE_SKINNY})\n    endif()\n    if(EIGEN_SYCL_DISABLE_DOUBLE_BUFFER)\n    add_definitions(-DEIGEN_SYCL_DISABLE_DOUBLE_BUFFER=${EIGEN_SYCL_DISABLE_DOUBLE_BUFFER})\n  endif()\n    if(EIGEN_SYCL_DISABLE_RANK1)\n      add_definitions(-DEIGEN_SYCL_DISABLE_RANK1=${EIGEN_SYCL_DISABLE_RANK1})\n    endif()\n    if(EIGEN_SYCL_DISABLE_SCALAR)\n      add_definitions(-DEIGEN_SYCL_DISABLE_SCALAR=${EIGEN_SYCL_DISABLE_SCALAR})\n    endif()\n    if(EIGEN_SYCL_DISABLE_GEMV)\n      add_definitions(-DEIGEN_SYCL_DISABLE_GEMV=${EIGEN_SYCL_DISABLE_GEMV})\n    endif()\n    if(EIGEN_SYCL_DISABLE_ARM_GPU_CACHE_OPTIMISATION)\n      add_definitions(-DEIGEN_SYCL_DISABLE_ARM_GPU_CACHE_OPTIMISATION=${EIGEN_SYCL_DISABLE_ARM_GPU_CACHE_OPTIMISATION})\n    endif()\n\n    if(EIGEN_SYCL_TRISYCL)\n      set(CMAKE_CXX_STANDARD 14)\n      set(STD_CXX_FLAG \"-std=c++1z\")\n    else()\n      if(MSVC)\n        # Set the host and device compilers C++ standard to C++14. On Windows setting this to C++11\n        # can cause issues with the ComputeCpp device compiler parsing Visual Studio Headers.\n        set(CMAKE_CXX_STANDARD 14)\n        list(APPEND COMPUTECPP_USER_FLAGS -DWIN32)\n      else()\n        set(CMAKE_CXX_STANDARD 11)\n        list(APPEND COMPUTECPP_USER_FLAGS -Wall)\n      endif()\n      # The following flags are not supported by Clang and can cause warnings\n      # if used with -Werror so they are removed here.\n      if(COMPUTECPP_USE_COMPILER_DRIVER)\n        set(CMAKE_CXX_COMPILER ${ComputeCpp_DEVICE_COMPILER_EXECUTABLE})\n        string(REPLACE \"-Wlogical-op\" \"\" CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS})\n        string(REPLACE \"-Wno-psabi\" \"\" CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS})\n        string(REPLACE \"-ansi\" \"\" CMAKE_CXX_FLAGS ${CMAKE_CXX_FLAGS})\n      endif()\n      list(APPEND COMPUTECPP_USER_FLAGS\n          -DEIGEN_NO_ASSERTION_CHECKING=1\n          -no-serial-memop\n          -Xclang\n          -cl-mad-enable)\n    endif()\n\n    ei_add_test(cxx11_tensor_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_image_op_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_math_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_forced_eval_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_broadcast_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_device_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_reduction_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_morphing_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_shuffling_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_padding_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_builtins_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_contract_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_concatenation_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_reverse_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_convolution_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_striding_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_chipping_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_layout_swap_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_inflation_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_random_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_generator_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_patch_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_image_patch_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_volume_patch_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_argmax_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_custom_op_sycl ${STD_CXX_FLAG})\n    ei_add_test(cxx11_tensor_scan_sycl ${STD_CXX_FLAG})\n    set(EIGEN_SYCL OFF)\n  endif()\n\n  ei_add_test(cxx11_eventcount \"-pthread\" \"${CMAKE_THREAD_LIBS_INIT}\")\n  ei_add_test(cxx11_runqueue \"-pthread\" \"${CMAKE_THREAD_LIBS_INIT}\")\n  ei_add_test(cxx11_non_blocking_thread_pool \"-pthread\" \"${CMAKE_THREAD_LIBS_INIT}\")\n\n  ei_add_test(cxx11_meta)\n  ei_add_test(cxx11_maxsizevector)\n  ei_add_test(cxx11_tensor_argmax)\n  ei_add_test(cxx11_tensor_assign)\n  ei_add_test(cxx11_tensor_block_access)\n  ei_add_test(cxx11_tensor_block_eval)\n  ei_add_test(cxx11_tensor_block_io)\n  ei_add_test(cxx11_tensor_broadcasting)\n  ei_add_test(cxx11_tensor_casts)\n  ei_add_test(cxx11_tensor_chipping)\n  ei_add_test(cxx11_tensor_comparisons)\n  ei_add_test(cxx11_tensor_concatenation)\n  ei_add_test(cxx11_tensor_const)\n  ei_add_test(cxx11_tensor_contraction)\n  ei_add_test(cxx11_tensor_convolution)\n  ei_add_test(cxx11_tensor_custom_index)\n  ei_add_test(cxx11_tensor_custom_op)\n  ei_add_test(cxx11_tensor_dimension)\n  ei_add_test(cxx11_tensor_empty)\n  ei_add_test(cxx11_tensor_executor \"-pthread\" \"${CMAKE_THREAD_LIBS_INIT}\")\n  ei_add_test(cxx11_tensor_expr)\n  ei_add_test(cxx11_tensor_fft)\n  ei_add_test(cxx11_tensor_fixed_size)\n  ei_add_test(cxx11_tensor_forced_eval)\n  ei_add_test(cxx11_tensor_generator)\n  ei_add_test(cxx11_tensor_ifft)\n  ei_add_test(cxx11_tensor_image_patch)\n  ei_add_test(cxx11_tensor_index_list)\n  ei_add_test(cxx11_tensor_inflation)\n  ei_add_test(cxx11_tensor_intdiv)\n  ei_add_test(cxx11_tensor_io)\n  ei_add_test(cxx11_tensor_layout_swap)\n  ei_add_test(cxx11_tensor_lvalue)\n  ei_add_test(cxx11_tensor_map)\n  ei_add_test(cxx11_tensor_math)\n  ei_add_test(cxx11_tensor_mixed_indices)\n  ei_add_test(cxx11_tensor_morphing)\n  ei_add_test(cxx11_tensor_move)\n  ei_add_test(cxx11_tensor_notification \"-pthread\" \"${CMAKE_THREAD_LIBS_INIT}\")\n  ei_add_test(cxx11_tensor_of_complex)\n  ei_add_test(cxx11_tensor_of_const_values)\n  ei_add_test(cxx11_tensor_of_strings)\n  ei_add_test(cxx11_tensor_padding)\n  ei_add_test(cxx11_tensor_patch)\n  ei_add_test(cxx11_tensor_random)\n  ei_add_test(cxx11_tensor_reduction)\n  ei_add_test(cxx11_tensor_ref)\n  ei_add_test(cxx11_tensor_roundings)\n  ei_add_test(cxx11_tensor_scan)\n  ei_add_test(cxx11_tensor_shuffling)\n  ei_add_test(cxx11_tensor_simple)\n  ei_add_test(cxx11_tensor_striding)\n  ei_add_test(cxx11_tensor_sugar)\n  ei_add_test(cxx11_tensor_thread_local \"-pthread\" \"${CMAKE_THREAD_LIBS_INIT}\")\n  ei_add_test(cxx11_tensor_thread_pool \"-pthread\" \"${CMAKE_THREAD_LIBS_INIT}\")\n  ei_add_test(cxx11_tensor_trace)\n  ei_add_test(cxx11_tensor_volume_patch)\n#  ei_add_test(cxx11_tensor_symmetry)\nif(\"${CMAKE_SIZEOF_VOID_P}\" EQUAL \"8\" AND NOT CMAKE_CXX_COMPILER_ID STREQUAL \"MSVC\")\n  # This test requires __uint128_t which is only available on 64bit systems\n  ei_add_test(cxx11_tensor_uint128)\nendif()\n\nendif()\n\n# These tests needs nvcc\nfind_package(CUDA 7.0)\nif(CUDA_FOUND AND EIGEN_TEST_CUDA)\n  # Make sure to compile without the -pedantic, -Wundef, -Wnon-virtual-dtor\n  # and -fno-check-new flags since they trigger thousands of compilation warnings\n  # in the CUDA runtime\n  # Also remove -ansi that is incompatible with std=c++11.\n  string(REPLACE \"-pedantic\" \"\" CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS}\")\n  string(REPLACE \"-Wundef\" \"\" CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS}\")\n  string(REPLACE \"-Wnon-virtual-dtor\" \"\" CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS}\")\n  string(REPLACE \"-fno-check-new\" \"\" CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS}\")\n  string(REPLACE \"-ansi\" \"\" CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS}\")\n\n  message(STATUS \"Flags used to compile cuda code: \" ${CMAKE_CXX_FLAGS})\n\n  if(\"${CMAKE_CXX_COMPILER_ID}\" STREQUAL \"Clang\")\n    set(CUDA_NVCC_FLAGS \"-ccbin ${CMAKE_C_COMPILER}\" CACHE STRING \"nvcc flags\" FORCE)\n  endif()\n  if(EIGEN_TEST_CUDA_CLANG)\n    set(CMAKE_CXX_FLAGS \"${CMAKE_CXX_FLAGS} -std=c++11\")\n    string(APPEND CMAKE_CXX_FLAGS \" --cuda-path=${CUDA_TOOLKIT_ROOT_DIR}\")\n    foreach(ARCH IN LISTS EIGEN_CUDA_COMPUTE_ARCH)\n        string(APPEND CMAKE_CXX_FLAGS \" --cuda-gpu-arch=sm_${ARCH}\")\n    endforeach()\n  endif()\n\n  set(EIGEN_CUDA_RELAXED_CONSTEXPR \"--expt-relaxed-constexpr\")\n  if (${CUDA_VERSION} STREQUAL \"7.0\")\n    set(EIGEN_CUDA_RELAXED_CONSTEXPR \"--relaxed-constexpr\")\n  endif()\n\n  set(NVCC_ARCH_FLAGS)\n  foreach(ARCH IN LISTS EIGEN_CUDA_COMPUTE_ARCH)\n    string(APPEND NVCC_ARCH_FLAGS \" -gencode arch=compute_${ARCH},code=sm_${ARCH}\")\n  endforeach()\n  set(CUDA_NVCC_FLAGS  \"${EIGEN_CUDA_RELAXED_CONSTEXPR} -Xcudafe \\\"--display_error_number\\\" ${NVCC_ARCH_FLAGS} ${CUDA_NVCC_FLAGS}\")\n  cuda_include_directories(\"${CMAKE_CURRENT_BINARY_DIR}\" \"${CUDA_TOOLKIT_ROOT_DIR}/include\")\n  set(EIGEN_ADD_TEST_FILENAME_EXTENSION \"cu\")\n\n  ei_add_test(cxx11_tensor_complex_gpu)\n  ei_add_test(cxx11_tensor_complex_cwise_ops_gpu)\n  ei_add_test(cxx11_tensor_reduction_gpu)\n  ei_add_test(cxx11_tensor_argmax_gpu)\n  ei_add_test(cxx11_tensor_cast_float16_gpu)\n  ei_add_test(cxx11_tensor_scan_gpu)\n\n  set(EIGEN_CUDA_OLDEST_COMPUTE_ARCH 9999)\n  foreach(ARCH IN LISTS EIGEN_CUDA_COMPUTE_ARCH)\n    if(${ARCH} LESS ${EIGEN_CUDA_OLDEST_COMPUTE_ARCH})\n      set(EIGEN_CUDA_OLDEST_COMPUTE_ARCH ${ARCH})\n    endif()\n  endforeach()\n\n  # Contractions require arch 3.0 or higher\n  if (${EIGEN_CUDA_OLDEST_COMPUTE_ARCH} GREATER 29)\n    ei_add_test(cxx11_tensor_device)\n    ei_add_test(cxx11_tensor_gpu)\n    ei_add_test(cxx11_tensor_contract_gpu)\n    ei_add_test(cxx11_tensor_of_float16_gpu)\n  endif()\n\n  # The random number generation code requires arch 3.5 or greater.\n  if (${EIGEN_CUDA_OLDEST_COMPUTE_ARCH} GREATER 34)\n    ei_add_test(cxx11_tensor_random_gpu)\n  endif()\n\n\n  unset(EIGEN_ADD_TEST_FILENAME_EXTENSION)\nendif()\n\n# Add HIP specific tests\nif (EIGEN_TEST_HIP)\n\n  set(HIP_PATH \"/opt/rocm/hip\" CACHE STRING \"Path to the HIP installation.\")\n\n  if (EXISTS ${HIP_PATH})\n\n    list(APPEND CMAKE_MODULE_PATH ${HIP_PATH}/cmake)\n\n    find_package(HIP REQUIRED)\n    if (HIP_FOUND)\n\n      execute_process(COMMAND ${HIP_PATH}/bin/hipconfig --platform OUTPUT_VARIABLE HIP_PLATFORM)\n\n      if ((${HIP_PLATFORM} STREQUAL \"hcc\") OR (${HIP_PLATFORM} STREQUAL \"amd\"))\n\n\tinclude_directories(${CMAKE_CURRENT_BINARY_DIR})\n\tinclude_directories(${HIP_PATH}/include)\n\n\tset(EIGEN_ADD_TEST_FILENAME_EXTENSION  \"cu\")\n\t#\n\t# complex datatype is not yet supported by HIP\n\t# so leaving out those tests for now\n\t#\n\t# ei_add_test(cxx11_tensor_complex_gpu)\n\t# ei_add_test(cxx11_tensor_complex_cwise_ops_gpu)\n\t#\n\tei_add_test(cxx11_tensor_reduction_gpu)\n\tei_add_test(cxx11_tensor_argmax_gpu)\n\tei_add_test(cxx11_tensor_cast_float16_gpu)\n\tei_add_test(cxx11_tensor_scan_gpu)\n\tei_add_test(cxx11_tensor_device)\n\n\tei_add_test(cxx11_tensor_gpu)\n\tei_add_test(cxx11_tensor_contract_gpu)\n\tei_add_test(cxx11_tensor_of_float16_gpu)\n\tei_add_test(cxx11_tensor_random_gpu)\n\n\tunset(EIGEN_ADD_TEST_FILENAME_EXTENSION)\n\n      elseif ((${HIP_PLATFORM} STREQUAL \"nvcc\") OR (${HIP_PLATFORM} STREQUAL \"nvidia\"))\n\tmessage(FATAL_ERROR \"HIP_PLATFORM = nvcc is not supported within Eigen\")\n      else ()\n\tmessage(FATAL_ERROR \"Unknown HIP_PLATFORM = ${HIP_PLATFORM}\")\n      endif()\n\n    endif()\n\n  else ()\n\n    message(FATAL_ERROR \"EIGEN_TEST_HIP is ON, but the specified HIP_PATH (${HIP_PATH}) does not exist\")\n\n  endif()\n\nendif()\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/EulerAngles.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Tal Hadad <tal_hd@hotmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <unsupported/Eigen/EulerAngles>\n\nusing namespace Eigen;\n\n// Unfortunately, we need to specialize it in order to work. (We could add it in main.h test framework)\ntemplate <typename Scalar, class System>\nbool verifyIsApprox(const Eigen::EulerAngles<Scalar, System>& a, const Eigen::EulerAngles<Scalar, System>& b)\n{\n  return verifyIsApprox(a.angles(), b.angles());\n}\n\n// Verify that x is in the approxed range [a, b]\n#define VERIFY_APPROXED_RANGE(a, x, b) \\\n  do { \\\n  VERIFY_IS_APPROX_OR_LESS_THAN(a, x); \\\n  VERIFY_IS_APPROX_OR_LESS_THAN(x, b); \\\n  } while(0)\n\nconst char X = EULER_X;\nconst char Y = EULER_Y;\nconst char Z = EULER_Z;\n\ntemplate<typename Scalar, class EulerSystem>\nvoid verify_euler(const EulerAngles<Scalar, EulerSystem>& e)\n{\n  typedef EulerAngles<Scalar, EulerSystem> EulerAnglesType;\n  typedef Matrix<Scalar,3,3> Matrix3;\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef Quaternion<Scalar> QuaternionType;\n  typedef AngleAxis<Scalar> AngleAxisType;\n  \n  const Scalar ONE = Scalar(1);\n  const Scalar HALF_PI = Scalar(EIGEN_PI / 2);\n  const Scalar PI = Scalar(EIGEN_PI);\n  \n  // It's very important calc the acceptable precision depending on the distance from the pole.\n  const Scalar longitudeRadius = std::abs(\n    EulerSystem::IsTaitBryan ?\n    std::cos(e.beta()) :\n    std::sin(e.beta())\n    );\n  Scalar precision = test_precision<Scalar>() / longitudeRadius;\n  \n  Scalar betaRangeStart, betaRangeEnd;\n  if (EulerSystem::IsTaitBryan)\n  {\n    betaRangeStart = -HALF_PI;\n    betaRangeEnd = HALF_PI;\n  }\n  else\n  {\n    if (!EulerSystem::IsBetaOpposite)\n    {\n      betaRangeStart = 0;\n      betaRangeEnd = PI;\n    }\n    else\n    {\n      betaRangeStart = -PI;\n      betaRangeEnd = 0;\n    }\n  }\n  \n  const Vector3 I_ = EulerAnglesType::AlphaAxisVector();\n  const Vector3 J_ = EulerAnglesType::BetaAxisVector();\n  const Vector3 K_ = EulerAnglesType::GammaAxisVector();\n  \n  // Is approx checks\n  VERIFY(e.isApprox(e));\n  VERIFY_IS_APPROX(e, e);\n  VERIFY_IS_NOT_APPROX(e, EulerAnglesType(e.alpha() + ONE, e.beta() + ONE, e.gamma() + ONE));\n\n  const Matrix3 m(e);\n  VERIFY_IS_APPROX(Scalar(m.determinant()), ONE);\n\n  EulerAnglesType ebis(m);\n  \n  // When no roll(acting like polar representation), we have the best precision.\n  // One of those cases is when the Euler angles are on the pole, and because it's singular case,\n  //  the computation returns no roll.\n  if (ebis.beta() == 0)\n    precision = test_precision<Scalar>();\n  \n  // Check that eabis in range\n  VERIFY_APPROXED_RANGE(-PI, ebis.alpha(), PI);\n  VERIFY_APPROXED_RANGE(betaRangeStart, ebis.beta(), betaRangeEnd);\n  VERIFY_APPROXED_RANGE(-PI, ebis.gamma(), PI);\n\n  const Matrix3 mbis(AngleAxisType(ebis.alpha(), I_) * AngleAxisType(ebis.beta(), J_) * AngleAxisType(ebis.gamma(), K_));\n  VERIFY_IS_APPROX(Scalar(mbis.determinant()), ONE);\n  VERIFY_IS_APPROX(mbis, ebis.toRotationMatrix());\n  /*std::cout << \"===================\\n\" <<\n    \"e: \" << e << std::endl <<\n    \"eabis: \" << eabis.transpose() << std::endl <<\n    \"m: \" << m << std::endl <<\n    \"mbis: \" << mbis << std::endl <<\n    \"X: \" << (m * Vector3::UnitX()).transpose() << std::endl <<\n    \"X: \" << (mbis * Vector3::UnitX()).transpose() << std::endl;*/\n  VERIFY(m.isApprox(mbis, precision));\n\n  // Test if ea and eabis are the same\n  // Need to check both singular and non-singular cases\n  // There are two singular cases.\n  // 1. When I==K and sin(ea(1)) == 0\n  // 2. When I!=K and cos(ea(1)) == 0\n\n  // TODO: Make this test work well, and use range saturation function.\n  /*// If I==K, and ea[1]==0, then there no unique solution.\n  // The remark apply in the case where I!=K, and |ea[1]| is close to +-pi/2.\n  if( (i!=k || ea[1]!=0) && (i==k || !internal::isApprox(abs(ea[1]),Scalar(EIGEN_PI/2),test_precision<Scalar>())) ) \n      VERIFY_IS_APPROX(ea, eabis);*/\n  \n  // Quaternions\n  const QuaternionType q(e);\n  ebis = q;\n  const QuaternionType qbis(ebis);\n  VERIFY(internal::isApprox<Scalar>(std::abs(q.dot(qbis)), ONE, precision));\n  //VERIFY_IS_APPROX(eabis, eabis2);// Verify that the euler angles are still the same\n  \n  // A suggestion for simple product test when will be supported.\n  /*EulerAnglesType e2(PI/2, PI/2, PI/2);\n  Matrix3 m2(e2);\n  VERIFY_IS_APPROX(e*e2, m*m2);*/\n}\n\ntemplate<signed char A, signed char B, signed char C, typename Scalar>\nvoid verify_euler_vec(const Matrix<Scalar,3,1>& ea)\n{\n  verify_euler(EulerAngles<Scalar, EulerSystem<A, B, C> >(ea[0], ea[1], ea[2]));\n}\n\ntemplate<signed char A, signed char B, signed char C, typename Scalar>\nvoid verify_euler_all_neg(const Matrix<Scalar,3,1>& ea)\n{\n  verify_euler_vec<+A,+B,+C>(ea);\n  verify_euler_vec<+A,+B,-C>(ea);\n  verify_euler_vec<+A,-B,+C>(ea);\n  verify_euler_vec<+A,-B,-C>(ea);\n  \n  verify_euler_vec<-A,+B,+C>(ea);\n  verify_euler_vec<-A,+B,-C>(ea);\n  verify_euler_vec<-A,-B,+C>(ea);\n  verify_euler_vec<-A,-B,-C>(ea);\n}\n\ntemplate<typename Scalar> void check_all_var(const Matrix<Scalar,3,1>& ea)\n{\n  verify_euler_all_neg<X,Y,Z>(ea);\n  verify_euler_all_neg<X,Y,X>(ea);\n  verify_euler_all_neg<X,Z,Y>(ea);\n  verify_euler_all_neg<X,Z,X>(ea);\n  \n  verify_euler_all_neg<Y,Z,X>(ea);\n  verify_euler_all_neg<Y,Z,Y>(ea);\n  verify_euler_all_neg<Y,X,Z>(ea);\n  verify_euler_all_neg<Y,X,Y>(ea);\n  \n  verify_euler_all_neg<Z,X,Y>(ea);\n  verify_euler_all_neg<Z,X,Z>(ea);\n  verify_euler_all_neg<Z,Y,X>(ea);\n  verify_euler_all_neg<Z,Y,Z>(ea);\n}\n\ntemplate<typename Scalar> void check_singular_cases(const Scalar& singularBeta)\n{\n  typedef Matrix<Scalar,3,1> Vector3;\n  const Scalar PI = Scalar(EIGEN_PI);\n  \n  for (Scalar epsilon = NumTraits<Scalar>::epsilon(); epsilon < 1; epsilon *= Scalar(1.2))\n  {\n    check_all_var(Vector3(PI/4, singularBeta, PI/3));\n    check_all_var(Vector3(PI/4, singularBeta - epsilon, PI/3));\n    check_all_var(Vector3(PI/4, singularBeta - Scalar(1.5)*epsilon, PI/3));\n    check_all_var(Vector3(PI/4, singularBeta - 2*epsilon, PI/3));\n    check_all_var(Vector3(PI*Scalar(0.8), singularBeta - epsilon, Scalar(0.9)*PI));\n    check_all_var(Vector3(PI*Scalar(-0.9), singularBeta + epsilon, PI*Scalar(0.3)));\n    check_all_var(Vector3(PI*Scalar(-0.6), singularBeta + Scalar(1.5)*epsilon, PI*Scalar(0.3)));\n    check_all_var(Vector3(PI*Scalar(-0.5), singularBeta + 2*epsilon, PI*Scalar(0.4)));\n    check_all_var(Vector3(PI*Scalar(0.9), singularBeta + epsilon, Scalar(0.8)*PI));\n  }\n  \n  // This one for sanity, it had a problem with near pole cases in float scalar.\n  check_all_var(Vector3(PI*Scalar(0.8), singularBeta - Scalar(1E-6), Scalar(0.9)*PI));\n}\n\ntemplate<typename Scalar> void eulerangles_manual()\n{\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef Matrix<Scalar,Dynamic,1> VectorX;\n  const Vector3 Zero = Vector3::Zero();\n  const Scalar PI = Scalar(EIGEN_PI);\n  \n  check_all_var(Zero);\n  \n  // singular cases\n  check_singular_cases(PI/2);\n  check_singular_cases(-PI/2);\n  \n  check_singular_cases(Scalar(0));\n  check_singular_cases(Scalar(-0));\n  \n  check_singular_cases(PI);\n  check_singular_cases(-PI);\n  \n  // non-singular cases\n  VectorX alpha = VectorX::LinSpaced(20, Scalar(-0.99) * PI, PI);\n  VectorX beta =  VectorX::LinSpaced(20, Scalar(-0.49) * PI, Scalar(0.49) * PI);\n  VectorX gamma = VectorX::LinSpaced(20, Scalar(-0.99) * PI, PI);\n  for (int i = 0; i < alpha.size(); ++i) {\n    for (int j = 0; j < beta.size(); ++j) {\n      for (int k = 0; k < gamma.size(); ++k) {\n        check_all_var(Vector3(alpha(i), beta(j), gamma(k)));\n      }\n    }\n  }\n}\n\ntemplate<typename Scalar> void eulerangles_rand()\n{\n  typedef Matrix<Scalar,3,3> Matrix3;\n  typedef Matrix<Scalar,3,1> Vector3;\n  typedef Array<Scalar,3,1> Array3;\n  typedef Quaternion<Scalar> Quaternionx;\n  typedef AngleAxis<Scalar> AngleAxisType;\n\n  Scalar a = internal::random<Scalar>(-Scalar(EIGEN_PI), Scalar(EIGEN_PI));\n  Quaternionx q1;\n  q1 = AngleAxisType(a, Vector3::Random().normalized());\n  Matrix3 m;\n  m = q1;\n  \n  Vector3 ea = m.eulerAngles(0,1,2);\n  check_all_var(ea);\n  ea = m.eulerAngles(0,1,0);\n  check_all_var(ea);\n  \n  // Check with purely random Quaternion:\n  q1.coeffs() = Quaternionx::Coefficients::Random().normalized();\n  m = q1;\n  ea = m.eulerAngles(0,1,2);\n  check_all_var(ea);\n  ea = m.eulerAngles(0,1,0);\n  check_all_var(ea);\n  \n  // Check with random angles in range [0:pi]x[-pi:pi]x[-pi:pi].\n  ea = (Array3::Random() + Array3(1,0,0))*Scalar(EIGEN_PI)*Array3(0.5,1,1);\n  check_all_var(ea);\n  \n  ea[2] = ea[0] = internal::random<Scalar>(0,Scalar(EIGEN_PI));\n  check_all_var(ea);\n  \n  ea[0] = ea[1] = internal::random<Scalar>(0,Scalar(EIGEN_PI));\n  check_all_var(ea);\n  \n  ea[1] = 0;\n  check_all_var(ea);\n  \n  ea.head(2).setZero();\n  check_all_var(ea);\n  \n  ea.setZero();\n  check_all_var(ea);\n}\n\nEIGEN_DECLARE_TEST(EulerAngles)\n{\n  // Simple cast test\n  EulerAnglesXYZd onesEd(1, 1, 1);\n  EulerAnglesXYZf onesEf = onesEd.cast<float>();\n  VERIFY_IS_APPROX(onesEd, onesEf.cast<double>());\n\n  // Simple Construction from Vector3 test\n  VERIFY_IS_APPROX(onesEd, EulerAnglesXYZd(Vector3d::Ones()));\n  \n  CALL_SUBTEST_1( eulerangles_manual<float>() );\n  CALL_SUBTEST_2( eulerangles_manual<double>() );\n  \n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_3( eulerangles_rand<float>() );\n    CALL_SUBTEST_4( eulerangles_rand<double>() );\n  }\n  \n  // TODO: Add tests for auto diff\n  // TODO: Add tests for complex numbers\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/FFT.cpp",
    "content": "#define test_FFTW test_FFT\n#include \"FFTW.cpp\"\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/FFTW.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Mark Borgerding mark a borgerding net\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <unsupported/Eigen/FFT>\n\ntemplate <typename T> \nstd::complex<T> RandomCpx() { return std::complex<T>( (T)(rand()/(T)RAND_MAX - .5), (T)(rand()/(T)RAND_MAX - .5) ); }\n\nusing namespace std;\nusing namespace Eigen;\n\n\ntemplate < typename T>\ncomplex<long double>  promote(complex<T> x) { return complex<long double>((long double)x.real(),(long double)x.imag()); }\n\ncomplex<long double>  promote(float x) { return complex<long double>((long double)x); }\ncomplex<long double>  promote(double x) { return complex<long double>((long double)x); }\ncomplex<long double>  promote(long double x) { return complex<long double>((long double)x); }\n    \n\n    template <typename VT1,typename VT2>\n    long double fft_rmse( const VT1 & fftbuf,const VT2 & timebuf)\n    {\n        long double totalpower=0;\n        long double difpower=0;\n        long double pi = acos((long double)-1 );\n        for (size_t k0=0;k0<(size_t)fftbuf.size();++k0) {\n            complex<long double> acc = 0;\n            long double phinc = (long double)(-2.)*k0* pi / timebuf.size();\n            for (size_t k1=0;k1<(size_t)timebuf.size();++k1) {\n                acc +=  promote( timebuf[k1] ) * exp( complex<long double>(0,k1*phinc) );\n            }\n            totalpower += numext::abs2(acc);\n            complex<long double> x = promote(fftbuf[k0]); \n            complex<long double> dif = acc - x;\n            difpower += numext::abs2(dif);\n            //cerr << k0 << \"\\t\" << acc << \"\\t\" <<  x << \"\\t\" << sqrt(numext::abs2(dif)) << endl;\n        }\n        cerr << \"rmse:\" << sqrt(difpower/totalpower) << endl;\n        return sqrt(difpower/totalpower);\n    }\n\n    template <typename VT1,typename VT2>\n    long double dif_rmse( const VT1 buf1,const VT2 buf2)\n    {\n        long double totalpower=0;\n        long double difpower=0;\n        size_t n = (min)( buf1.size(),buf2.size() );\n        for (size_t k=0;k<n;++k) {\n            totalpower += (long double)((numext::abs2( buf1[k] ) + numext::abs2(buf2[k]) )/2);\n            difpower += (long double)(numext::abs2(buf1[k] - buf2[k]));\n        }\n        return sqrt(difpower/totalpower);\n    }\n\nenum { StdVectorContainer, EigenVectorContainer };\n\ntemplate<int Container, typename Scalar> struct VectorType;\n\ntemplate<typename Scalar> struct VectorType<StdVectorContainer,Scalar>\n{\n  typedef vector<Scalar> type;\n};\n\ntemplate<typename Scalar> struct VectorType<EigenVectorContainer,Scalar>\n{\n  typedef Matrix<Scalar,Dynamic,1> type;\n};\n\ntemplate <int Container, typename T>\nvoid test_scalar_generic(int nfft)\n{\n    typedef typename FFT<T>::Complex Complex;\n    typedef typename FFT<T>::Scalar Scalar;\n    typedef typename VectorType<Container,Scalar>::type ScalarVector;\n    typedef typename VectorType<Container,Complex>::type ComplexVector;\n\n    FFT<T> fft;\n    ScalarVector tbuf(nfft);\n    ComplexVector freqBuf;\n    for (int k=0;k<nfft;++k)\n        tbuf[k]= (T)( rand()/(double)RAND_MAX - .5);\n\n    // make sure it DOESN'T give the right full spectrum answer\n    // if we've asked for half-spectrum\n    fft.SetFlag(fft.HalfSpectrum );\n    fft.fwd( freqBuf,tbuf);\n    VERIFY((size_t)freqBuf.size() == (size_t)( (nfft>>1)+1) );\n    VERIFY( T(fft_rmse(freqBuf,tbuf)) < test_precision<T>()  );// gross check\n\n    fft.ClearFlag(fft.HalfSpectrum );\n    fft.fwd( freqBuf,tbuf);\n    VERIFY( (size_t)freqBuf.size() == (size_t)nfft);\n    VERIFY( T(fft_rmse(freqBuf,tbuf)) < test_precision<T>()  );// gross check\n\n    if (nfft&1)\n        return; // odd FFTs get the wrong size inverse FFT\n\n    ScalarVector tbuf2;\n    fft.inv( tbuf2 , freqBuf);\n    VERIFY( T(dif_rmse(tbuf,tbuf2)) < test_precision<T>()  );// gross check\n\n\n    // verify that the Unscaled flag takes effect\n    ScalarVector tbuf3;\n    fft.SetFlag(fft.Unscaled);\n\n    fft.inv( tbuf3 , freqBuf);\n\n    for (int k=0;k<nfft;++k)\n        tbuf3[k] *= T(1./nfft);\n\n\n    //for (size_t i=0;i<(size_t) tbuf.size();++i)\n    //    cout << \"freqBuf=\" << freqBuf[i] << \" in2=\" << tbuf3[i] << \" -  in=\" << tbuf[i] << \" => \" << (tbuf3[i] - tbuf[i] ) <<  endl;\n\n    VERIFY( T(dif_rmse(tbuf,tbuf3)) < test_precision<T>()  );// gross check\n\n    // verify that ClearFlag works\n    fft.ClearFlag(fft.Unscaled);\n    fft.inv( tbuf2 , freqBuf);\n    VERIFY( T(dif_rmse(tbuf,tbuf2)) < test_precision<T>()  );// gross check\n}\n\ntemplate <typename T>\nvoid test_scalar(int nfft)\n{\n  test_scalar_generic<StdVectorContainer,T>(nfft);\n  //test_scalar_generic<EigenVectorContainer,T>(nfft);\n}\n\n\ntemplate <int Container, typename T>\nvoid test_complex_generic(int nfft)\n{\n    typedef typename FFT<T>::Complex Complex;\n    typedef typename VectorType<Container,Complex>::type ComplexVector;\n\n    FFT<T> fft;\n\n    ComplexVector inbuf(nfft);\n    ComplexVector outbuf;\n    ComplexVector buf3;\n    for (int k=0;k<nfft;++k)\n        inbuf[k]= Complex( (T)(rand()/(double)RAND_MAX - .5), (T)(rand()/(double)RAND_MAX - .5) );\n    fft.fwd( outbuf , inbuf);\n\n    VERIFY( T(fft_rmse(outbuf,inbuf)) < test_precision<T>()  );// gross check\n    fft.inv( buf3 , outbuf);\n\n    VERIFY( T(dif_rmse(inbuf,buf3)) < test_precision<T>()  );// gross check\n\n    // verify that the Unscaled flag takes effect\n    ComplexVector buf4;\n    fft.SetFlag(fft.Unscaled);\n    fft.inv( buf4 , outbuf);\n    for (int k=0;k<nfft;++k)\n        buf4[k] *= T(1./nfft);\n    VERIFY( T(dif_rmse(inbuf,buf4)) < test_precision<T>()  );// gross check\n\n    // verify that ClearFlag works\n    fft.ClearFlag(fft.Unscaled);\n    fft.inv( buf3 , outbuf);\n    VERIFY( T(dif_rmse(inbuf,buf3)) < test_precision<T>()  );// gross check\n}\n\ntemplate <typename T>\nvoid test_complex(int nfft)\n{\n  test_complex_generic<StdVectorContainer,T>(nfft);\n  test_complex_generic<EigenVectorContainer,T>(nfft);\n}\n/*\ntemplate <typename T,int nrows,int ncols>\nvoid test_complex2d()\n{\n    typedef typename Eigen::FFT<T>::Complex Complex;\n    FFT<T> fft;\n    Eigen::Matrix<Complex,nrows,ncols> src,src2,dst,dst2;\n\n    src = Eigen::Matrix<Complex,nrows,ncols>::Random();\n    //src =  Eigen::Matrix<Complex,nrows,ncols>::Identity();\n\n    for (int k=0;k<ncols;k++) {\n        Eigen::Matrix<Complex,nrows,1> tmpOut;\n        fft.fwd( tmpOut,src.col(k) );\n        dst2.col(k) = tmpOut;\n    }\n\n    for (int k=0;k<nrows;k++) {\n        Eigen::Matrix<Complex,1,ncols> tmpOut;\n        fft.fwd( tmpOut,  dst2.row(k) );\n        dst2.row(k) = tmpOut;\n    }\n\n    fft.fwd2(dst.data(),src.data(),ncols,nrows);\n    fft.inv2(src2.data(),dst.data(),ncols,nrows);\n    VERIFY( (src-src2).norm() < test_precision<T>() );\n    VERIFY( (dst-dst2).norm() < test_precision<T>() );\n}\n*/\n\n\nvoid test_return_by_value(int len)\n{\n    VectorXf in;\n    VectorXf in1;\n    in.setRandom( len );\n    VectorXcf out1,out2;\n    FFT<float> fft;\n\n    fft.SetFlag(fft.HalfSpectrum );\n\n    fft.fwd(out1,in);\n    out2 = fft.fwd(in);\n    VERIFY( (out1-out2).norm() < test_precision<float>() );\n    in1 = fft.inv(out1);\n    VERIFY( (in1-in).norm() < test_precision<float>() );\n}\n\nEIGEN_DECLARE_TEST(FFTW)\n{\n  CALL_SUBTEST( test_return_by_value(32) );\n  //CALL_SUBTEST( ( test_complex2d<float,4,8> () ) ); CALL_SUBTEST( ( test_complex2d<double,4,8> () ) );\n  //CALL_SUBTEST( ( test_complex2d<long double,4,8> () ) );\n  CALL_SUBTEST( test_complex<float>(32) ); CALL_SUBTEST( test_complex<double>(32) ); \n  CALL_SUBTEST( test_complex<float>(256) ); CALL_SUBTEST( test_complex<double>(256) ); \n  CALL_SUBTEST( test_complex<float>(3*8) ); CALL_SUBTEST( test_complex<double>(3*8) ); \n  CALL_SUBTEST( test_complex<float>(5*32) ); CALL_SUBTEST( test_complex<double>(5*32) ); \n  CALL_SUBTEST( test_complex<float>(2*3*4) ); CALL_SUBTEST( test_complex<double>(2*3*4) ); \n  CALL_SUBTEST( test_complex<float>(2*3*4*5) ); CALL_SUBTEST( test_complex<double>(2*3*4*5) ); \n  CALL_SUBTEST( test_complex<float>(2*3*4*5*7) ); CALL_SUBTEST( test_complex<double>(2*3*4*5*7) ); \n\n  CALL_SUBTEST( test_scalar<float>(32) ); CALL_SUBTEST( test_scalar<double>(32) ); \n  CALL_SUBTEST( test_scalar<float>(45) ); CALL_SUBTEST( test_scalar<double>(45) ); \n  CALL_SUBTEST( test_scalar<float>(50) ); CALL_SUBTEST( test_scalar<double>(50) ); \n  CALL_SUBTEST( test_scalar<float>(256) ); CALL_SUBTEST( test_scalar<double>(256) ); \n  CALL_SUBTEST( test_scalar<float>(2*3*4*5*7) ); CALL_SUBTEST( test_scalar<double>(2*3*4*5*7) ); \n  \n  #ifdef EIGEN_HAS_FFTWL\n  CALL_SUBTEST( test_complex<long double>(32) );\n  CALL_SUBTEST( test_complex<long double>(256) );\n  CALL_SUBTEST( test_complex<long double>(3*8) );\n  CALL_SUBTEST( test_complex<long double>(5*32) );\n  CALL_SUBTEST( test_complex<long double>(2*3*4) );\n  CALL_SUBTEST( test_complex<long double>(2*3*4*5) );\n  CALL_SUBTEST( test_complex<long double>(2*3*4*5*7) );\n  \n  CALL_SUBTEST( test_scalar<long double>(32) );\n  CALL_SUBTEST( test_scalar<long double>(45) );\n  CALL_SUBTEST( test_scalar<long double>(50) );\n  CALL_SUBTEST( test_scalar<long double>(256) );\n  CALL_SUBTEST( test_scalar<long double>(2*3*4*5*7) );\n  #endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/NonLinearOptimization.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n\n#include <stdio.h>\n\n#include \"main.h\"\n#include <unsupported/Eigen/NonLinearOptimization>\n\n// This disables some useless Warnings on MSVC.\n// It is intended to be done for this test only.\n#include <Eigen/src/Core/util/DisableStupidWarnings.h>\n\n// tolerance for chekcing number of iterations\n#define LM_EVAL_COUNT_TOL 4/3\n\n#define LM_CHECK_N_ITERS(SOLVER,NFEV,NJEV) { \\\n            ++g_test_level; \\\n            VERIFY_IS_EQUAL(SOLVER.nfev, NFEV); \\\n            VERIFY_IS_EQUAL(SOLVER.njev, NJEV); \\\n            --g_test_level; \\\n            VERIFY(SOLVER.nfev <= NFEV * LM_EVAL_COUNT_TOL); \\\n            VERIFY(SOLVER.njev <= NJEV * LM_EVAL_COUNT_TOL); \\\n        }\n\nint fcn_chkder(const VectorXd &x, VectorXd &fvec, MatrixXd &fjac, int iflag)\n{\n    /*      subroutine fcn for chkder example. */\n\n    int i;\n    assert(15 ==  fvec.size());\n    assert(3 ==  x.size());\n    double tmp1, tmp2, tmp3, tmp4;\n    static const double y[15]={1.4e-1, 1.8e-1, 2.2e-1, 2.5e-1, 2.9e-1, 3.2e-1, 3.5e-1,\n        3.9e-1, 3.7e-1, 5.8e-1, 7.3e-1, 9.6e-1, 1.34, 2.1, 4.39};\n\n\n    if (iflag == 0)\n        return 0;\n\n    if (iflag != 2)\n        for (i=0; i<15; i++) {\n            tmp1 = i+1;\n            tmp2 = 16-i-1;\n            tmp3 = tmp1;\n            if (i >= 8) tmp3 = tmp2;\n            fvec[i] = y[i] - (x[0] + tmp1/(x[1]*tmp2 + x[2]*tmp3));\n        }\n    else {\n        for (i = 0; i < 15; i++) {\n            tmp1 = i+1;\n            tmp2 = 16-i-1;\n\n            /* error introduced into next statement for illustration. */\n            /* corrected statement should read    tmp3 = tmp1 . */\n\n            tmp3 = tmp2;\n            if (i >= 8) tmp3 = tmp2;\n            tmp4 = (x[1]*tmp2 + x[2]*tmp3); tmp4=tmp4*tmp4;\n            fjac(i,0) = -1.;\n            fjac(i,1) = tmp1*tmp2/tmp4;\n            fjac(i,2) = tmp1*tmp3/tmp4;\n        }\n    }\n    return 0;\n}\n\n\nvoid testChkder()\n{\n  const int m=15, n=3;\n  VectorXd x(n), fvec(m), xp, fvecp(m), err;\n  MatrixXd fjac(m,n);\n  VectorXi ipvt;\n\n  /*      the following values should be suitable for */\n  /*      checking the jacobian matrix. */\n  x << 9.2e-1, 1.3e-1, 5.4e-1;\n\n  internal::chkder(x, fvec, fjac, xp, fvecp, 1, err);\n  fcn_chkder(x, fvec, fjac, 1);\n  fcn_chkder(x, fvec, fjac, 2);\n  fcn_chkder(xp, fvecp, fjac, 1);\n  internal::chkder(x, fvec, fjac, xp, fvecp, 2, err);\n\n  fvecp -= fvec;\n\n  // check those\n  VectorXd fvec_ref(m), fvecp_ref(m), err_ref(m);\n  fvec_ref <<\n      -1.181606, -1.429655, -1.606344,\n      -1.745269, -1.840654, -1.921586,\n      -1.984141, -2.022537, -2.468977,\n      -2.827562, -3.473582, -4.437612,\n      -6.047662, -9.267761, -18.91806;\n  fvecp_ref <<\n      -7.724666e-09, -3.432406e-09, -2.034843e-10,\n      2.313685e-09,  4.331078e-09,  5.984096e-09,\n      7.363281e-09,   8.53147e-09,  1.488591e-08,\n      2.33585e-08,  3.522012e-08,  5.301255e-08,\n      8.26666e-08,  1.419747e-07,   3.19899e-07;\n  err_ref <<\n      0.1141397,  0.09943516,  0.09674474,\n      0.09980447,  0.1073116, 0.1220445,\n      0.1526814, 1, 1,\n      1, 1, 1,\n      1, 1, 1;\n\n  VERIFY_IS_APPROX(fvec, fvec_ref);\n  VERIFY_IS_APPROX(fvecp, fvecp_ref);\n  VERIFY_IS_APPROX(err, err_ref);\n}\n\n// Generic functor\ntemplate<typename _Scalar, int NX=Dynamic, int NY=Dynamic>\nstruct Functor\n{\n  typedef _Scalar Scalar;\n  enum {\n    InputsAtCompileTime = NX,\n    ValuesAtCompileTime = NY\n  };\n  typedef Matrix<Scalar,InputsAtCompileTime,1> InputType;\n  typedef Matrix<Scalar,ValuesAtCompileTime,1> ValueType;\n  typedef Matrix<Scalar,ValuesAtCompileTime,InputsAtCompileTime> JacobianType;\n\n  const int m_inputs, m_values;\n\n  Functor() : m_inputs(InputsAtCompileTime), m_values(ValuesAtCompileTime) {}\n  Functor(int inputs, int values) : m_inputs(inputs), m_values(values) {}\n\n  int inputs() const { return m_inputs; }\n  int values() const { return m_values; }\n\n  // you should define that in the subclass :\n//  void operator() (const InputType& x, ValueType* v, JacobianType* _j=0) const;\n};\n\nstruct lmder_functor : Functor<double>\n{\n    lmder_functor(void): Functor<double>(3,15) {}\n    int operator()(const VectorXd &x, VectorXd &fvec) const\n    {\n        double tmp1, tmp2, tmp3;\n        static const double y[15] = {1.4e-1, 1.8e-1, 2.2e-1, 2.5e-1, 2.9e-1, 3.2e-1, 3.5e-1,\n            3.9e-1, 3.7e-1, 5.8e-1, 7.3e-1, 9.6e-1, 1.34, 2.1, 4.39};\n\n        for (int i = 0; i < values(); i++)\n        {\n            tmp1 = i+1;\n            tmp2 = 16 - i - 1;\n            tmp3 = (i>=8)? tmp2 : tmp1;\n            fvec[i] = y[i] - (x[0] + tmp1/(x[1]*tmp2 + x[2]*tmp3));\n        }\n        return 0;\n    }\n\n    int df(const VectorXd &x, MatrixXd &fjac) const\n    {\n        double tmp1, tmp2, tmp3, tmp4;\n        for (int i = 0; i < values(); i++)\n        {\n            tmp1 = i+1;\n            tmp2 = 16 - i - 1;\n            tmp3 = (i>=8)? tmp2 : tmp1;\n            tmp4 = (x[1]*tmp2 + x[2]*tmp3); tmp4 = tmp4*tmp4;\n            fjac(i,0) = -1;\n            fjac(i,1) = tmp1*tmp2/tmp4;\n            fjac(i,2) = tmp1*tmp3/tmp4;\n        }\n        return 0;\n    }\n};\n\nvoid testLmder1()\n{\n  int n=3, info;\n\n  VectorXd x;\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, 1.);\n\n  // do the computation\n  lmder_functor functor;\n  LevenbergMarquardt<lmder_functor> lm(functor);\n  info = lm.lmder1(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 6, 5);\n\n  // check norm\n  VERIFY_IS_APPROX(lm.fvec.blueNorm(), 0.09063596);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << 0.08241058, 1.133037, 2.343695;\n  VERIFY_IS_APPROX(x, x_ref);\n}\n\nvoid testLmder()\n{\n  const int m=15, n=3;\n  int info;\n  double fnorm, covfac;\n  VectorXd x;\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, 1.);\n\n  // do the computation\n  lmder_functor functor;\n  LevenbergMarquardt<lmder_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return values\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 6, 5);\n\n  // check norm\n  fnorm = lm.fvec.blueNorm();\n  VERIFY_IS_APPROX(fnorm, 0.09063596);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << 0.08241058, 1.133037, 2.343695;\n  VERIFY_IS_APPROX(x, x_ref);\n\n  // check covariance\n  covfac = fnorm*fnorm/(m-n);\n  internal::covar(lm.fjac, lm.permutation.indices()); // TODO : move this as a function of lm\n\n  MatrixXd cov_ref(n,n);\n  cov_ref <<\n      0.0001531202,   0.002869941,  -0.002656662,\n      0.002869941,    0.09480935,   -0.09098995,\n      -0.002656662,   -0.09098995,    0.08778727;\n\n//  std::cout << fjac*covfac << std::endl;\n\n  MatrixXd cov;\n  cov =  covfac*lm.fjac.topLeftCorner<n,n>();\n  VERIFY_IS_APPROX( cov, cov_ref);\n  // TODO: why isn't this allowed ? :\n  // VERIFY_IS_APPROX( covfac*fjac.topLeftCorner<n,n>() , cov_ref);\n}\n\nstruct hybrj_functor : Functor<double>\n{\n    hybrj_functor(void) : Functor<double>(9,9) {}\n\n    int operator()(const VectorXd &x, VectorXd &fvec)\n    {\n        double temp, temp1, temp2;\n        const VectorXd::Index n = x.size();\n        assert(fvec.size()==n);\n        for (VectorXd::Index k = 0; k < n; k++)\n        {\n            temp = (3. - 2.*x[k])*x[k];\n            temp1 = 0.;\n            if (k) temp1 = x[k-1];\n            temp2 = 0.;\n            if (k != n-1) temp2 = x[k+1];\n            fvec[k] = temp - temp1 - 2.*temp2 + 1.;\n        }\n        return 0;\n    }\n    int df(const VectorXd &x, MatrixXd &fjac)\n    {\n        const VectorXd::Index n = x.size();\n        assert(fjac.rows()==n);\n        assert(fjac.cols()==n);\n        for (VectorXd::Index k = 0; k < n; k++)\n        {\n            for (VectorXd::Index j = 0; j < n; j++)\n                fjac(k,j) = 0.;\n            fjac(k,k) = 3.- 4.*x[k];\n            if (k) fjac(k,k-1) = -1.;\n            if (k != n-1) fjac(k,k+1) = -2.;\n        }\n        return 0;\n    }\n};\n\n\nvoid testHybrj1()\n{\n  const int n=9;\n  int info;\n  VectorXd x(n);\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, -1.);\n\n  // do the computation\n  hybrj_functor functor;\n  HybridNonLinearSolver<hybrj_functor> solver(functor);\n  info = solver.hybrj1(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(solver, 11, 1);\n\n  // check norm\n  VERIFY_IS_APPROX(solver.fvec.blueNorm(), 1.192636e-08);\n\n\n// check x\n  VectorXd x_ref(n);\n  x_ref <<\n     -0.5706545,    -0.6816283,    -0.7017325,\n     -0.7042129,     -0.701369,    -0.6918656,\n     -0.665792,    -0.5960342,    -0.4164121;\n  VERIFY_IS_APPROX(x, x_ref);\n}\n\nvoid testHybrj()\n{\n  const int n=9;\n  int info;\n  VectorXd x(n);\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, -1.);\n\n\n  // do the computation\n  hybrj_functor functor;\n  HybridNonLinearSolver<hybrj_functor> solver(functor);\n  solver.diag.setConstant(n, 1.);\n  solver.useExternalScaling = true;\n  info = solver.solve(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(solver, 11, 1);\n\n  // check norm\n  VERIFY_IS_APPROX(solver.fvec.blueNorm(), 1.192636e-08);\n\n\n// check x\n  VectorXd x_ref(n);\n  x_ref <<\n     -0.5706545,    -0.6816283,    -0.7017325,\n     -0.7042129,     -0.701369,    -0.6918656,\n     -0.665792,    -0.5960342,    -0.4164121;\n  VERIFY_IS_APPROX(x, x_ref);\n\n}\n\nstruct hybrd_functor : Functor<double>\n{\n    hybrd_functor(void) : Functor<double>(9,9) {}\n    int operator()(const VectorXd &x, VectorXd &fvec) const\n    {\n        double temp, temp1, temp2;\n        const VectorXd::Index n = x.size();\n\n        assert(fvec.size()==n);\n        for (VectorXd::Index k=0; k < n; k++)\n        {\n            temp = (3. - 2.*x[k])*x[k];\n            temp1 = 0.;\n            if (k) temp1 = x[k-1];\n            temp2 = 0.;\n            if (k != n-1) temp2 = x[k+1];\n            fvec[k] = temp - temp1 - 2.*temp2 + 1.;\n        }\n        return 0;\n    }\n};\n\nvoid testHybrd1()\n{\n  int n=9, info;\n  VectorXd x(n);\n\n  /* the following starting values provide a rough solution. */\n  x.setConstant(n, -1.);\n\n  // do the computation\n  hybrd_functor functor;\n  HybridNonLinearSolver<hybrd_functor> solver(functor);\n  info = solver.hybrd1(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(solver.nfev, 20);\n\n  // check norm\n  VERIFY_IS_APPROX(solver.fvec.blueNorm(), 1.192636e-08);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << -0.5706545, -0.6816283, -0.7017325, -0.7042129, -0.701369, -0.6918656, -0.665792, -0.5960342, -0.4164121;\n  VERIFY_IS_APPROX(x, x_ref);\n}\n\nvoid testHybrd()\n{\n  const int n=9;\n  int info;\n  VectorXd x;\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, -1.);\n\n  // do the computation\n  hybrd_functor functor;\n  HybridNonLinearSolver<hybrd_functor> solver(functor);\n  solver.parameters.nb_of_subdiagonals = 1;\n  solver.parameters.nb_of_superdiagonals = 1;\n  solver.diag.setConstant(n, 1.);\n  solver.useExternalScaling = true;\n  info = solver.solveNumericalDiff(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(solver.nfev, 14);\n\n  // check norm\n  VERIFY_IS_APPROX(solver.fvec.blueNorm(), 1.192636e-08);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref <<\n      -0.5706545,    -0.6816283,    -0.7017325,\n      -0.7042129,     -0.701369,    -0.6918656,\n      -0.665792,    -0.5960342,    -0.4164121;\n  VERIFY_IS_APPROX(x, x_ref);\n}\n\nstruct lmstr_functor : Functor<double>\n{\n    lmstr_functor(void) : Functor<double>(3,15) {}\n    int operator()(const VectorXd &x, VectorXd &fvec)\n    {\n        /*  subroutine fcn for lmstr1 example. */\n        double tmp1, tmp2, tmp3;\n        static const double y[15]={1.4e-1, 1.8e-1, 2.2e-1, 2.5e-1, 2.9e-1, 3.2e-1, 3.5e-1,\n            3.9e-1, 3.7e-1, 5.8e-1, 7.3e-1, 9.6e-1, 1.34, 2.1, 4.39};\n\n        assert(15==fvec.size());\n        assert(3==x.size());\n\n        for (int i=0; i<15; i++)\n        {\n            tmp1 = i+1;\n            tmp2 = 16 - i - 1;\n            tmp3 = (i>=8)? tmp2 : tmp1;\n            fvec[i] = y[i] - (x[0] + tmp1/(x[1]*tmp2 + x[2]*tmp3));\n        }\n        return 0;\n    }\n    int df(const VectorXd &x, VectorXd &jac_row, VectorXd::Index rownb)\n    {\n        assert(x.size()==3);\n        assert(jac_row.size()==x.size());\n        double tmp1, tmp2, tmp3, tmp4;\n\n        VectorXd::Index i = rownb-2;\n        tmp1 = i+1;\n        tmp2 = 16 - i - 1;\n        tmp3 = (i>=8)? tmp2 : tmp1;\n        tmp4 = (x[1]*tmp2 + x[2]*tmp3); tmp4 = tmp4*tmp4;\n        jac_row[0] = -1;\n        jac_row[1] = tmp1*tmp2/tmp4;\n        jac_row[2] = tmp1*tmp3/tmp4;\n        return 0;\n    }\n};\n\nvoid testLmstr1()\n{\n  const int n=3;\n  int info;\n\n  VectorXd x(n);\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, 1.);\n\n  // do the computation\n  lmstr_functor functor;\n  LevenbergMarquardt<lmstr_functor> lm(functor);\n  info = lm.lmstr1(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 6, 5);\n\n  // check norm\n  VERIFY_IS_APPROX(lm.fvec.blueNorm(), 0.09063596);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << 0.08241058, 1.133037, 2.343695 ;\n  VERIFY_IS_APPROX(x, x_ref);\n}\n\nvoid testLmstr()\n{\n  const int n=3;\n  int info;\n  double fnorm;\n  VectorXd x(n);\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, 1.);\n\n  // do the computation\n  lmstr_functor functor;\n  LevenbergMarquardt<lmstr_functor> lm(functor);\n  info = lm.minimizeOptimumStorage(x);\n\n  // check return values\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 6, 5);\n\n  // check norm\n  fnorm = lm.fvec.blueNorm();\n  VERIFY_IS_APPROX(fnorm, 0.09063596);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << 0.08241058, 1.133037, 2.343695;\n  VERIFY_IS_APPROX(x, x_ref);\n\n}\n\nstruct lmdif_functor : Functor<double>\n{\n    lmdif_functor(void) : Functor<double>(3,15) {}\n    int operator()(const VectorXd &x, VectorXd &fvec) const\n    {\n        int i;\n        double tmp1,tmp2,tmp3;\n        static const double y[15]={1.4e-1,1.8e-1,2.2e-1,2.5e-1,2.9e-1,3.2e-1,3.5e-1,3.9e-1,\n            3.7e-1,5.8e-1,7.3e-1,9.6e-1,1.34e0,2.1e0,4.39e0};\n\n        assert(x.size()==3);\n        assert(fvec.size()==15);\n        for (i=0; i<15; i++)\n        {\n            tmp1 = i+1;\n            tmp2 = 15 - i;\n            tmp3 = tmp1;\n\n            if (i >= 8) tmp3 = tmp2;\n            fvec[i] = y[i] - (x[0] + tmp1/(x[1]*tmp2 + x[2]*tmp3));\n        }\n        return 0;\n    }\n};\n\nvoid testLmdif1()\n{\n  const int n=3;\n  int info;\n\n  VectorXd x(n), fvec(15);\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, 1.);\n\n  // do the computation\n  lmdif_functor functor;\n  DenseIndex nfev = -1; // initialize to avoid maybe-uninitialized warning\n  info = LevenbergMarquardt<lmdif_functor>::lmdif1(functor, x, &nfev);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(nfev, 26);\n\n  // check norm\n  functor(x, fvec);\n  VERIFY_IS_APPROX(fvec.blueNorm(), 0.09063596);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << 0.0824106, 1.1330366, 2.3436947;\n  VERIFY_IS_APPROX(x, x_ref);\n\n}\n\nvoid testLmdif()\n{\n  const int m=15, n=3;\n  int info;\n  double fnorm, covfac;\n  VectorXd x(n);\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, 1.);\n\n  // do the computation\n  lmdif_functor functor;\n  NumericalDiff<lmdif_functor> numDiff(functor);\n  LevenbergMarquardt<NumericalDiff<lmdif_functor> > lm(numDiff);\n  info = lm.minimize(x);\n\n  // check return values\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev, 26);\n\n  // check norm\n  fnorm = lm.fvec.blueNorm();\n  VERIFY_IS_APPROX(fnorm, 0.09063596);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << 0.08241058, 1.133037, 2.343695;\n  VERIFY_IS_APPROX(x, x_ref);\n\n  // check covariance\n  covfac = fnorm*fnorm/(m-n);\n  internal::covar(lm.fjac, lm.permutation.indices()); // TODO : move this as a function of lm\n\n  MatrixXd cov_ref(n,n);\n  cov_ref <<\n      0.0001531202,   0.002869942,  -0.002656662,\n      0.002869942,    0.09480937,   -0.09098997,\n      -0.002656662,   -0.09098997,    0.08778729;\n\n//  std::cout << fjac*covfac << std::endl;\n\n  MatrixXd cov;\n  cov =  covfac*lm.fjac.topLeftCorner<n,n>();\n  VERIFY_IS_APPROX( cov, cov_ref);\n  // TODO: why isn't this allowed ? :\n  // VERIFY_IS_APPROX( covfac*fjac.topLeftCorner<n,n>() , cov_ref);\n}\n\nstruct chwirut2_functor : Functor<double>\n{\n    chwirut2_functor(void) : Functor<double>(3,54) {}\n    static const double m_x[54];\n    static const double m_y[54];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        int i;\n\n        assert(b.size()==3);\n        assert(fvec.size()==54);\n        for(i=0; i<54; i++) {\n            double x = m_x[i];\n            fvec[i] = exp(-b[0]*x)/(b[1]+b[2]*x) - m_y[i];\n        }\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==3);\n        assert(fjac.rows()==54);\n        assert(fjac.cols()==3);\n        for(int i=0; i<54; i++) {\n            double x = m_x[i];\n            double factor = 1./(b[1]+b[2]*x);\n            double e = exp(-b[0]*x);\n            fjac(i,0) = -x*e*factor;\n            fjac(i,1) = -e*factor*factor;\n            fjac(i,2) = -x*e*factor*factor;\n        }\n        return 0;\n    }\n};\nconst double chwirut2_functor::m_x[54] = { 0.500E0, 1.000E0, 1.750E0, 3.750E0, 5.750E0, 0.875E0, 2.250E0, 3.250E0, 5.250E0, 0.750E0, 1.750E0, 2.750E0, 4.750E0, 0.625E0, 1.250E0, 2.250E0, 4.250E0, .500E0, 3.000E0, .750E0, 3.000E0, 1.500E0, 6.000E0, 3.000E0, 6.000E0, 1.500E0, 3.000E0, .500E0, 2.000E0, 4.000E0, .750E0, 2.000E0, 5.000E0, .750E0, 2.250E0, 3.750E0, 5.750E0, 3.000E0, .750E0, 2.500E0, 4.000E0, .750E0, 2.500E0, 4.000E0, .750E0, 2.500E0, 4.000E0, .500E0, 6.000E0, 3.000E0, .500E0, 2.750E0, .500E0, 1.750E0};\nconst double chwirut2_functor::m_y[54] = { 92.9000E0 ,57.1000E0 ,31.0500E0 ,11.5875E0 ,8.0250E0 ,63.6000E0 ,21.4000E0 ,14.2500E0 ,8.4750E0 ,63.8000E0 ,26.8000E0 ,16.4625E0 ,7.1250E0 ,67.3000E0 ,41.0000E0 ,21.1500E0 ,8.1750E0 ,81.5000E0 ,13.1200E0 ,59.9000E0 ,14.6200E0 ,32.9000E0 ,5.4400E0 ,12.5600E0 ,5.4400E0 ,32.0000E0 ,13.9500E0 ,75.8000E0 ,20.0000E0 ,10.4200E0 ,59.5000E0 ,21.6700E0 ,8.5500E0 ,62.0000E0 ,20.2000E0 ,7.7600E0 ,3.7500E0 ,11.8100E0 ,54.7000E0 ,23.7000E0 ,11.5500E0 ,61.3000E0 ,17.7000E0 ,8.7400E0 ,59.2000E0 ,16.3000E0 ,8.6200E0 ,81.0000E0 ,4.8700E0 ,14.6200E0 ,81.7000E0 ,17.1700E0 ,81.3000E0 ,28.9000E0  };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/chwirut2.shtml\nvoid testNistChwirut2(void)\n{\n  const int n=3;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 0.1, 0.01, 0.02;\n  // do the computation\n  chwirut2_functor functor;\n  LevenbergMarquardt<chwirut2_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 10, 8);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 5.1304802941E+02);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.6657666537E-01);\n  VERIFY_IS_APPROX(x[1], 5.1653291286E-03);\n  VERIFY_IS_APPROX(x[2], 1.2150007096E-02);\n\n  /*\n   * Second try\n   */\n  x<< 0.15, 0.008, 0.010;\n  // do the computation\n  lm.resetParameters();\n  lm.parameters.ftol = 1.E6*NumTraits<double>::epsilon();\n  lm.parameters.xtol = 1.E6*NumTraits<double>::epsilon();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 7, 6);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 5.1304802941E+02);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.6657666537E-01);\n  VERIFY_IS_APPROX(x[1], 5.1653291286E-03);\n  VERIFY_IS_APPROX(x[2], 1.2150007096E-02);\n}\n\n\nstruct misra1a_functor : Functor<double>\n{\n    misra1a_functor(void) : Functor<double>(2,14) {}\n    static const double m_x[14];\n    static const double m_y[14];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==2);\n        assert(fvec.size()==14);\n        for(int i=0; i<14; i++) {\n            fvec[i] = b[0]*(1.-exp(-b[1]*m_x[i])) - m_y[i] ;\n        }\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==2);\n        assert(fjac.rows()==14);\n        assert(fjac.cols()==2);\n        for(int i=0; i<14; i++) {\n            fjac(i,0) = (1.-exp(-b[1]*m_x[i]));\n            fjac(i,1) = (b[0]*m_x[i]*exp(-b[1]*m_x[i]));\n        }\n        return 0;\n    }\n};\nconst double misra1a_functor::m_x[14] = { 77.6E0, 114.9E0, 141.1E0, 190.8E0, 239.9E0, 289.0E0, 332.8E0, 378.4E0, 434.8E0, 477.3E0, 536.8E0, 593.1E0, 689.1E0, 760.0E0};\nconst double misra1a_functor::m_y[14] = { 10.07E0, 14.73E0, 17.94E0, 23.93E0, 29.61E0, 35.18E0, 40.02E0, 44.82E0, 50.76E0, 55.05E0, 61.01E0, 66.40E0, 75.47E0, 81.78E0};\n\n// http://www.itl.nist.gov/div898/strd/nls/data/misra1a.shtml\nvoid testNistMisra1a(void)\n{\n  const int n=2;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 500., 0.0001;\n  // do the computation\n  misra1a_functor functor;\n  LevenbergMarquardt<misra1a_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 19, 15);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 1.2455138894E-01);\n  // check x\n  VERIFY_IS_APPROX(x[0], 2.3894212918E+02);\n  VERIFY_IS_APPROX(x[1], 5.5015643181E-04);\n\n  /*\n   * Second try\n   */\n  x<< 250., 0.0005;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 5, 4);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 1.2455138894E-01);\n  // check x\n  VERIFY_IS_APPROX(x[0], 2.3894212918E+02);\n  VERIFY_IS_APPROX(x[1], 5.5015643181E-04);\n}\n\nstruct hahn1_functor : Functor<double>\n{\n    hahn1_functor(void) : Functor<double>(7,236) {}\n    static const double m_x[236];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        static const double m_y[236] = { .591E0 , 1.547E0 , 2.902E0 , 2.894E0 , 4.703E0 , 6.307E0 , 7.03E0  , 7.898E0 , 9.470E0 , 9.484E0 , 10.072E0 , 10.163E0 , 11.615E0 , 12.005E0 , 12.478E0 , 12.982E0 , 12.970E0 , 13.926E0 , 14.452E0 , 14.404E0 , 15.190E0 , 15.550E0 , 15.528E0 , 15.499E0 , 16.131E0 , 16.438E0 , 16.387E0 , 16.549E0 , 16.872E0 , 16.830E0 , 16.926E0 , 16.907E0 , 16.966E0 , 17.060E0 , 17.122E0 , 17.311E0 , 17.355E0 , 17.668E0 , 17.767E0 , 17.803E0 , 17.765E0 , 17.768E0 , 17.736E0 , 17.858E0 , 17.877E0 , 17.912E0 , 18.046E0 , 18.085E0 , 18.291E0 , 18.357E0 , 18.426E0 , 18.584E0 , 18.610E0 , 18.870E0 , 18.795E0 , 19.111E0 , .367E0 , .796E0 , 0.892E0 , 1.903E0 , 2.150E0 , 3.697E0 , 5.870E0 , 6.421E0 , 7.422E0 , 9.944E0 , 11.023E0 , 11.87E0  , 12.786E0 , 14.067E0 , 13.974E0 , 14.462E0 , 14.464E0 , 15.381E0 , 15.483E0 , 15.59E0  , 16.075E0 , 16.347E0 , 16.181E0 , 16.915E0 , 17.003E0 , 16.978E0 , 17.756E0 , 17.808E0 , 17.868E0 , 18.481E0 , 18.486E0 , 19.090E0 , 16.062E0 , 16.337E0 , 16.345E0 ,\n        16.388E0 , 17.159E0 , 17.116E0 , 17.164E0 , 17.123E0 , 17.979E0 , 17.974E0 , 18.007E0 , 17.993E0 , 18.523E0 , 18.669E0 , 18.617E0 , 19.371E0 , 19.330E0 , 0.080E0 , 0.248E0 , 1.089E0 , 1.418E0 , 2.278E0 , 3.624E0 , 4.574E0 , 5.556E0 , 7.267E0 , 7.695E0 , 9.136E0 , 9.959E0 , 9.957E0 , 11.600E0 , 13.138E0 , 13.564E0 , 13.871E0 , 13.994E0 , 14.947E0 , 15.473E0 , 15.379E0 , 15.455E0 , 15.908E0 , 16.114E0 , 17.071E0 , 17.135E0 , 17.282E0 , 17.368E0 , 17.483E0 , 17.764E0 , 18.185E0 , 18.271E0 , 18.236E0 , 18.237E0 , 18.523E0 , 18.627E0 , 18.665E0 , 19.086E0 , 0.214E0 , 0.943E0 , 1.429E0 , 2.241E0 , 2.951E0 , 3.782E0 , 4.757E0 , 5.602E0 , 7.169E0 , 8.920E0 , 10.055E0 , 12.035E0 , 12.861E0 , 13.436E0 , 14.167E0 , 14.755E0 , 15.168E0 , 15.651E0 , 15.746E0 , 16.216E0 , 16.445E0 , 16.965E0 , 17.121E0 , 17.206E0 , 17.250E0 , 17.339E0 , 17.793E0 , 18.123E0 , 18.49E0  , 18.566E0 , 18.645E0 , 18.706E0 , 18.924E0 , 19.1E0   , 0.375E0 , 0.471E0 , 1.504E0 , 2.204E0 , 2.813E0 , 4.765E0 , 9.835E0 , 10.040E0 , 11.946E0 , 12.596E0 , \n13.303E0 , 13.922E0 , 14.440E0 , 14.951E0 , 15.627E0 , 15.639E0 , 15.814E0 , 16.315E0 , 16.334E0 , 16.430E0 , 16.423E0 , 17.024E0 , 17.009E0 , 17.165E0 , 17.134E0 , 17.349E0 , 17.576E0 , 17.848E0 , 18.090E0 , 18.276E0 , 18.404E0 , 18.519E0 , 19.133E0 , 19.074E0 , 19.239E0 , 19.280E0 , 19.101E0 , 19.398E0 , 19.252E0 , 19.89E0  , 20.007E0 , 19.929E0 , 19.268E0 , 19.324E0 , 20.049E0 , 20.107E0 , 20.062E0 , 20.065E0 , 19.286E0 , 19.972E0 , 20.088E0 , 20.743E0 , 20.83E0  , 20.935E0 , 21.035E0 , 20.93E0  , 21.074E0 , 21.085E0 , 20.935E0 };\n\n        //        int called=0; printf(\"call hahn1_functor with  iflag=%d, called=%d\\n\", iflag, called); if (iflag==1) called++;\n\n        assert(b.size()==7);\n        assert(fvec.size()==236);\n        for(int i=0; i<236; i++) {\n            double x=m_x[i], xx=x*x, xxx=xx*x;\n            fvec[i] = (b[0]+b[1]*x+b[2]*xx+b[3]*xxx) / (1.+b[4]*x+b[5]*xx+b[6]*xxx) - m_y[i];\n        }\n        return 0;\n    }\n\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==7);\n        assert(fjac.rows()==236);\n        assert(fjac.cols()==7);\n        for(int i=0; i<236; i++) {\n            double x=m_x[i], xx=x*x, xxx=xx*x;\n            double fact = 1./(1.+b[4]*x+b[5]*xx+b[6]*xxx);\n            fjac(i,0) = 1.*fact;\n            fjac(i,1) = x*fact;\n            fjac(i,2) = xx*fact;\n            fjac(i,3) = xxx*fact;\n            fact = - (b[0]+b[1]*x+b[2]*xx+b[3]*xxx) * fact * fact;\n            fjac(i,4) = x*fact;\n            fjac(i,5) = xx*fact;\n            fjac(i,6) = xxx*fact;\n        }\n        return 0;\n    }\n};\nconst double hahn1_functor::m_x[236] = { 24.41E0 , 34.82E0 , 44.09E0 , 45.07E0 , 54.98E0 , 65.51E0 , 70.53E0 , 75.70E0 , 89.57E0 , 91.14E0 , 96.40E0 , 97.19E0 , 114.26E0 , 120.25E0 , 127.08E0 , 133.55E0 , 133.61E0 , 158.67E0 , 172.74E0 , 171.31E0 , 202.14E0 , 220.55E0 , 221.05E0 , 221.39E0 , 250.99E0 , 268.99E0 , 271.80E0 , 271.97E0 , 321.31E0 , 321.69E0 , 330.14E0 , 333.03E0 , 333.47E0 , 340.77E0 , 345.65E0 , 373.11E0 , 373.79E0 , 411.82E0 , 419.51E0 , 421.59E0 , 422.02E0 , 422.47E0 , 422.61E0 , 441.75E0 , 447.41E0 , 448.7E0  , 472.89E0 , 476.69E0 , 522.47E0 , 522.62E0 , 524.43E0 , 546.75E0 , 549.53E0 , 575.29E0 , 576.00E0 , 625.55E0 , 20.15E0 , 28.78E0 , 29.57E0 , 37.41E0 , 39.12E0 , 50.24E0 , 61.38E0 , 66.25E0 , 73.42E0 , 95.52E0 , 107.32E0 , 122.04E0 , 134.03E0 , 163.19E0 , 163.48E0 , 175.70E0 , 179.86E0 , 211.27E0 , 217.78E0 , 219.14E0 , 262.52E0 , 268.01E0 , 268.62E0 , 336.25E0 , 337.23E0 , 339.33E0 , 427.38E0 , 428.58E0 , 432.68E0 , 528.99E0 , 531.08E0 , 628.34E0 , 253.24E0 , 273.13E0 , 273.66E0 ,\n282.10E0 , 346.62E0 , 347.19E0 , 348.78E0 , 351.18E0 , 450.10E0 , 450.35E0 , 451.92E0 , 455.56E0 , 552.22E0 , 553.56E0 , 555.74E0 , 652.59E0 , 656.20E0 , 14.13E0 , 20.41E0 , 31.30E0 , 33.84E0 , 39.70E0 , 48.83E0 , 54.50E0 , 60.41E0 , 72.77E0 , 75.25E0 , 86.84E0 , 94.88E0 , 96.40E0 , 117.37E0 , 139.08E0 , 147.73E0 , 158.63E0 , 161.84E0 , 192.11E0 , 206.76E0 , 209.07E0 , 213.32E0 , 226.44E0 , 237.12E0 , 330.90E0 , 358.72E0 , 370.77E0 , 372.72E0 , 396.24E0 , 416.59E0 , 484.02E0 , 495.47E0 , 514.78E0 , 515.65E0 , 519.47E0 , 544.47E0 , 560.11E0 , 620.77E0 , 18.97E0 , 28.93E0 , 33.91E0 , 40.03E0 , 44.66E0 , 49.87E0 , 55.16E0 , 60.90E0 , 72.08E0 , 85.15E0 , 97.06E0 , 119.63E0 , 133.27E0 , 143.84E0 , 161.91E0 , 180.67E0 , 198.44E0 , 226.86E0 , 229.65E0 , 258.27E0 , 273.77E0 , 339.15E0 , 350.13E0 , 362.75E0 , 371.03E0 , 393.32E0 , 448.53E0 , 473.78E0 , 511.12E0 , 524.70E0 , 548.75E0 , 551.64E0 , 574.02E0 , 623.86E0 , 21.46E0 , 24.33E0 , 33.43E0 , 39.22E0 , 44.18E0 , 55.02E0 , 94.33E0 , 96.44E0 , 118.82E0 , 128.48E0 ,\n141.94E0 , 156.92E0 , 171.65E0 , 190.00E0 , 223.26E0 , 223.88E0 , 231.50E0 , 265.05E0 , 269.44E0 , 271.78E0 , 273.46E0 , 334.61E0 , 339.79E0 , 349.52E0 , 358.18E0 , 377.98E0 , 394.77E0 , 429.66E0 , 468.22E0 , 487.27E0 , 519.54E0 , 523.03E0 , 612.99E0 , 638.59E0 , 641.36E0 , 622.05E0 , 631.50E0 , 663.97E0 , 646.9E0  , 748.29E0 , 749.21E0 , 750.14E0 , 647.04E0 , 646.89E0 , 746.9E0  , 748.43E0 , 747.35E0 , 749.27E0 , 647.61E0 , 747.78E0 , 750.51E0 , 851.37E0 , 845.97E0 , 847.54E0 , 849.93E0 , 851.61E0 , 849.75E0 , 850.98E0 , 848.23E0};\n\n// http://www.itl.nist.gov/div898/strd/nls/data/hahn1.shtml\nvoid testNistHahn1(void)\n{\n  const int  n=7;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 10., -1., .05, -.00001, -.05, .001, -.000001;\n  // do the computation\n  hahn1_functor functor;\n  LevenbergMarquardt<hahn1_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 11, 10);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 1.5324382854E+00);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.0776351733E+00);\n  VERIFY_IS_APPROX(x[1],-1.2269296921E-01);\n  VERIFY_IS_APPROX(x[2], 4.0863750610E-03);\n  VERIFY_IS_APPROX(x[3],-1.426264e-06); // shoulde be : -1.4262662514E-06\n  VERIFY_IS_APPROX(x[4],-5.7609940901E-03);\n  VERIFY_IS_APPROX(x[5], 2.4053735503E-04);\n  VERIFY_IS_APPROX(x[6],-1.2314450199E-07);\n\n  /*\n   * Second try\n   */\n  x<< .1, -.1, .005, -.000001, -.005, .0001, -.0000001;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 11, 10);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 1.5324382854E+00);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.077640); // should be :  1.0776351733E+00\n  VERIFY_IS_APPROX(x[1], -0.1226933); // should be : -1.2269296921E-01\n  VERIFY_IS_APPROX(x[2], 0.004086383); // should be : 4.0863750610E-03\n  VERIFY_IS_APPROX(x[3], -1.426277e-06); // shoulde be : -1.4262662514E-06\n  VERIFY_IS_APPROX(x[4],-5.7609940901E-03);\n  VERIFY_IS_APPROX(x[5], 0.00024053772); // should be : 2.4053735503E-04\n  VERIFY_IS_APPROX(x[6], -1.231450e-07); // should be : -1.2314450199E-07\n\n}\n\nstruct misra1d_functor : Functor<double>\n{\n    misra1d_functor(void) : Functor<double>(2,14) {}\n    static const double x[14];\n    static const double y[14];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==2);\n        assert(fvec.size()==14);\n        for(int i=0; i<14; i++) {\n            fvec[i] = b[0]*b[1]*x[i]/(1.+b[1]*x[i]) - y[i];\n        }\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==2);\n        assert(fjac.rows()==14);\n        assert(fjac.cols()==2);\n        for(int i=0; i<14; i++) {\n            double den = 1.+b[1]*x[i];\n            fjac(i,0) = b[1]*x[i] / den;\n            fjac(i,1) = b[0]*x[i]*(den-b[1]*x[i])/den/den;\n        }\n        return 0;\n    }\n};\nconst double misra1d_functor::x[14] = { 77.6E0, 114.9E0, 141.1E0, 190.8E0, 239.9E0, 289.0E0, 332.8E0, 378.4E0, 434.8E0, 477.3E0, 536.8E0, 593.1E0, 689.1E0, 760.0E0};\nconst double misra1d_functor::y[14] = { 10.07E0, 14.73E0, 17.94E0, 23.93E0, 29.61E0, 35.18E0, 40.02E0, 44.82E0, 50.76E0, 55.05E0, 61.01E0, 66.40E0, 75.47E0, 81.78E0};\n\n// http://www.itl.nist.gov/div898/strd/nls/data/misra1d.shtml\nvoid testNistMisra1d(void)\n{\n  const int n=2;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 500., 0.0001;\n  // do the computation\n  misra1d_functor functor;\n  LevenbergMarquardt<misra1d_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 3);\n  LM_CHECK_N_ITERS(lm, 9, 7);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 5.6419295283E-02);\n  // check x\n  VERIFY_IS_APPROX(x[0], 4.3736970754E+02);\n  VERIFY_IS_APPROX(x[1], 3.0227324449E-04);\n\n  /*\n   * Second try\n   */\n  x<< 450., 0.0003;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 4, 3);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 5.6419295283E-02);\n  // check x\n  VERIFY_IS_APPROX(x[0], 4.3736970754E+02);\n  VERIFY_IS_APPROX(x[1], 3.0227324449E-04);\n}\n\n\nstruct lanczos1_functor : Functor<double>\n{\n    lanczos1_functor(void) : Functor<double>(6,24) {}\n    static const double x[24];\n    static const double y[24];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==6);\n        assert(fvec.size()==24);\n        for(int i=0; i<24; i++)\n            fvec[i] = b[0]*exp(-b[1]*x[i]) + b[2]*exp(-b[3]*x[i]) + b[4]*exp(-b[5]*x[i])  - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==6);\n        assert(fjac.rows()==24);\n        assert(fjac.cols()==6);\n        for(int i=0; i<24; i++) {\n            fjac(i,0) = exp(-b[1]*x[i]);\n            fjac(i,1) = -b[0]*x[i]*exp(-b[1]*x[i]);\n            fjac(i,2) = exp(-b[3]*x[i]);\n            fjac(i,3) = -b[2]*x[i]*exp(-b[3]*x[i]);\n            fjac(i,4) = exp(-b[5]*x[i]);\n            fjac(i,5) = -b[4]*x[i]*exp(-b[5]*x[i]);\n        }\n        return 0;\n    }\n};\nconst double lanczos1_functor::x[24] = { 0.000000000000E+00, 5.000000000000E-02, 1.000000000000E-01, 1.500000000000E-01, 2.000000000000E-01, 2.500000000000E-01, 3.000000000000E-01, 3.500000000000E-01, 4.000000000000E-01, 4.500000000000E-01, 5.000000000000E-01, 5.500000000000E-01, 6.000000000000E-01, 6.500000000000E-01, 7.000000000000E-01, 7.500000000000E-01, 8.000000000000E-01, 8.500000000000E-01, 9.000000000000E-01, 9.500000000000E-01, 1.000000000000E+00, 1.050000000000E+00, 1.100000000000E+00, 1.150000000000E+00 };\nconst double lanczos1_functor::y[24] = { 2.513400000000E+00 ,2.044333373291E+00 ,1.668404436564E+00 ,1.366418021208E+00 ,1.123232487372E+00 ,9.268897180037E-01 ,7.679338563728E-01 ,6.388775523106E-01 ,5.337835317402E-01 ,4.479363617347E-01 ,3.775847884350E-01 ,3.197393199326E-01 ,2.720130773746E-01 ,2.324965529032E-01 ,1.996589546065E-01 ,1.722704126914E-01 ,1.493405660168E-01 ,1.300700206922E-01 ,1.138119324644E-01 ,1.000415587559E-01 ,8.833209084540E-02 ,7.833544019350E-02 ,6.976693743449E-02 ,6.239312536719E-02 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/lanczos1.shtml\nvoid testNistLanczos1(void)\n{\n  const int n=6;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 1.2, 0.3, 5.6, 5.5, 6.5, 7.6;\n  // do the computation\n  lanczos1_functor functor;\n  LevenbergMarquardt<lanczos1_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 2);\n  LM_CHECK_N_ITERS(lm, 79, 72);\n  // check norm^2\n  std::cout.precision(30);\n  std::cout << lm.fvec.squaredNorm() << \"\\n\";\n  VERIFY(lm.fvec.squaredNorm() <= 1.4307867721E-25);\n  // check x\n  VERIFY_IS_APPROX(x[0], 9.5100000027E-02);\n  VERIFY_IS_APPROX(x[1], 1.0000000001E+00);\n  VERIFY_IS_APPROX(x[2], 8.6070000013E-01);\n  VERIFY_IS_APPROX(x[3], 3.0000000002E+00);\n  VERIFY_IS_APPROX(x[4], 1.5575999998E+00);\n  VERIFY_IS_APPROX(x[5], 5.0000000001E+00);\n\n  /*\n   * Second try\n   */\n  x<< 0.5, 0.7, 3.6, 4.2, 4., 6.3;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 2);\n  LM_CHECK_N_ITERS(lm, 9, 8);\n  // check norm^2\n  VERIFY(lm.fvec.squaredNorm() <= 1.4307867721E-25);\n  // check x\n  VERIFY_IS_APPROX(x[0], 9.5100000027E-02);\n  VERIFY_IS_APPROX(x[1], 1.0000000001E+00);\n  VERIFY_IS_APPROX(x[2], 8.6070000013E-01);\n  VERIFY_IS_APPROX(x[3], 3.0000000002E+00);\n  VERIFY_IS_APPROX(x[4], 1.5575999998E+00);\n  VERIFY_IS_APPROX(x[5], 5.0000000001E+00);\n\n}\n\nstruct rat42_functor : Functor<double>\n{\n    rat42_functor(void) : Functor<double>(3,9) {}\n    static const double x[9];\n    static const double y[9];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==3);\n        assert(fvec.size()==9);\n        for(int i=0; i<9; i++) {\n            fvec[i] = b[0] / (1.+exp(b[1]-b[2]*x[i])) - y[i];\n        }\n        return 0;\n    }\n\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==3);\n        assert(fjac.rows()==9);\n        assert(fjac.cols()==3);\n        for(int i=0; i<9; i++) {\n            double e = exp(b[1]-b[2]*x[i]);\n            fjac(i,0) = 1./(1.+e);\n            fjac(i,1) = -b[0]*e/(1.+e)/(1.+e);\n            fjac(i,2) = +b[0]*e*x[i]/(1.+e)/(1.+e);\n        }\n        return 0;\n    }\n};\nconst double rat42_functor::x[9] = { 9.000E0, 14.000E0, 21.000E0, 28.000E0, 42.000E0, 57.000E0, 63.000E0, 70.000E0, 79.000E0 };\nconst double rat42_functor::y[9] = { 8.930E0 ,10.800E0 ,18.590E0 ,22.330E0 ,39.350E0 ,56.110E0 ,61.730E0 ,64.620E0 ,67.080E0 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/ratkowsky2.shtml\nvoid testNistRat42(void)\n{\n  const int n=3;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 100., 1., 0.1;\n  // do the computation\n  rat42_functor functor;\n  LevenbergMarquardt<rat42_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 10, 8);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 8.0565229338E+00);\n  // check x\n  VERIFY_IS_APPROX(x[0], 7.2462237576E+01);\n  VERIFY_IS_APPROX(x[1], 2.6180768402E+00);\n  VERIFY_IS_APPROX(x[2], 6.7359200066E-02);\n\n  /*\n   * Second try\n   */\n  x<< 75., 2.5, 0.07;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 6, 5);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 8.0565229338E+00);\n  // check x\n  VERIFY_IS_APPROX(x[0], 7.2462237576E+01);\n  VERIFY_IS_APPROX(x[1], 2.6180768402E+00);\n  VERIFY_IS_APPROX(x[2], 6.7359200066E-02);\n}\n\nstruct MGH10_functor : Functor<double>\n{\n    MGH10_functor(void) : Functor<double>(3,16) {}\n    static const double x[16];\n    static const double y[16];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==3);\n        assert(fvec.size()==16);\n        for(int i=0; i<16; i++)\n            fvec[i] =  b[0] * exp(b[1]/(x[i]+b[2])) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==3);\n        assert(fjac.rows()==16);\n        assert(fjac.cols()==3);\n        for(int i=0; i<16; i++) {\n            double factor = 1./(x[i]+b[2]);\n            double e = exp(b[1]*factor);\n            fjac(i,0) = e;\n            fjac(i,1) = b[0]*factor*e;\n            fjac(i,2) = -b[1]*b[0]*factor*factor*e;\n        }\n        return 0;\n    }\n};\nconst double MGH10_functor::x[16] = { 5.000000E+01, 5.500000E+01, 6.000000E+01, 6.500000E+01, 7.000000E+01, 7.500000E+01, 8.000000E+01, 8.500000E+01, 9.000000E+01, 9.500000E+01, 1.000000E+02, 1.050000E+02, 1.100000E+02, 1.150000E+02, 1.200000E+02, 1.250000E+02 };\nconst double MGH10_functor::y[16] = { 3.478000E+04, 2.861000E+04, 2.365000E+04, 1.963000E+04, 1.637000E+04, 1.372000E+04, 1.154000E+04, 9.744000E+03, 8.261000E+03, 7.030000E+03, 6.005000E+03, 5.147000E+03, 4.427000E+03, 3.820000E+03, 3.307000E+03, 2.872000E+03 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/mgh10.shtml\nvoid testNistMGH10(void)\n{\n  const int n=3;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 2., 400000., 25000.;\n  // do the computation\n  MGH10_functor functor;\n  LevenbergMarquardt<MGH10_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 2); \n  LM_CHECK_N_ITERS(lm, 284, 249); \n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 8.7945855171E+01);\n  // check x\n  VERIFY_IS_APPROX(x[0], 5.6096364710E-03);\n  VERIFY_IS_APPROX(x[1], 6.1813463463E+03);\n  VERIFY_IS_APPROX(x[2], 3.4522363462E+02);\n\n  /*\n   * Second try\n   */\n  x<< 0.02, 4000., 250.;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 3);\n  LM_CHECK_N_ITERS(lm, 126, 116);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 8.7945855171E+01);\n  // check x\n  VERIFY_IS_APPROX(x[0], 5.6096364710E-03);\n  VERIFY_IS_APPROX(x[1], 6.1813463463E+03);\n  VERIFY_IS_APPROX(x[2], 3.4522363462E+02);\n}\n\n\nstruct BoxBOD_functor : Functor<double>\n{\n    BoxBOD_functor(void) : Functor<double>(2,6) {}\n    static const double x[6];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        static const double y[6] = { 109., 149., 149., 191., 213., 224. };\n        assert(b.size()==2);\n        assert(fvec.size()==6);\n        for(int i=0; i<6; i++)\n            fvec[i] =  b[0]*(1.-exp(-b[1]*x[i])) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==2);\n        assert(fjac.rows()==6);\n        assert(fjac.cols()==2);\n        for(int i=0; i<6; i++) {\n            double e = exp(-b[1]*x[i]);\n            fjac(i,0) = 1.-e;\n            fjac(i,1) = b[0]*x[i]*e;\n        }\n        return 0;\n    }\n};\nconst double BoxBOD_functor::x[6] = { 1., 2., 3., 5., 7., 10. };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/boxbod.shtml\nvoid testNistBoxBOD(void)\n{\n  const int n=2;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 1., 1.;\n  // do the computation\n  BoxBOD_functor functor;\n  LevenbergMarquardt<BoxBOD_functor> lm(functor);\n  lm.parameters.ftol = 1.E6*NumTraits<double>::epsilon();\n  lm.parameters.xtol = 1.E6*NumTraits<double>::epsilon();\n  lm.parameters.factor = 10.;\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 31, 25);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 1.1680088766E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 2.1380940889E+02);\n  VERIFY_IS_APPROX(x[1], 5.4723748542E-01);\n\n  /*\n   * Second try\n   */\n  x<< 100., 0.75;\n  // do the computation\n  lm.resetParameters();\n  lm.parameters.ftol = NumTraits<double>::epsilon();\n  lm.parameters.xtol = NumTraits<double>::epsilon();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 15, 14);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 1.1680088766E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 2.1380940889E+02);\n  VERIFY_IS_APPROX(x[1], 5.4723748542E-01);\n}\n\nstruct MGH17_functor : Functor<double>\n{\n    MGH17_functor(void) : Functor<double>(5,33) {}\n    static const double x[33];\n    static const double y[33];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==5);\n        assert(fvec.size()==33);\n        for(int i=0; i<33; i++)\n            fvec[i] =  b[0] + b[1]*exp(-b[3]*x[i]) +  b[2]*exp(-b[4]*x[i]) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==5);\n        assert(fjac.rows()==33);\n        assert(fjac.cols()==5);\n        for(int i=0; i<33; i++) {\n            fjac(i,0) = 1.;\n            fjac(i,1) = exp(-b[3]*x[i]);\n            fjac(i,2) = exp(-b[4]*x[i]);\n            fjac(i,3) = -x[i]*b[1]*exp(-b[3]*x[i]);\n            fjac(i,4) = -x[i]*b[2]*exp(-b[4]*x[i]);\n        }\n        return 0;\n    }\n};\nconst double MGH17_functor::x[33] = { 0.000000E+00, 1.000000E+01, 2.000000E+01, 3.000000E+01, 4.000000E+01, 5.000000E+01, 6.000000E+01, 7.000000E+01, 8.000000E+01, 9.000000E+01, 1.000000E+02, 1.100000E+02, 1.200000E+02, 1.300000E+02, 1.400000E+02, 1.500000E+02, 1.600000E+02, 1.700000E+02, 1.800000E+02, 1.900000E+02, 2.000000E+02, 2.100000E+02, 2.200000E+02, 2.300000E+02, 2.400000E+02, 2.500000E+02, 2.600000E+02, 2.700000E+02, 2.800000E+02, 2.900000E+02, 3.000000E+02, 3.100000E+02, 3.200000E+02 };\nconst double MGH17_functor::y[33] = { 8.440000E-01, 9.080000E-01, 9.320000E-01, 9.360000E-01, 9.250000E-01, 9.080000E-01, 8.810000E-01, 8.500000E-01, 8.180000E-01, 7.840000E-01, 7.510000E-01, 7.180000E-01, 6.850000E-01, 6.580000E-01, 6.280000E-01, 6.030000E-01, 5.800000E-01, 5.580000E-01, 5.380000E-01, 5.220000E-01, 5.060000E-01, 4.900000E-01, 4.780000E-01, 4.670000E-01, 4.570000E-01, 4.480000E-01, 4.380000E-01, 4.310000E-01, 4.240000E-01, 4.200000E-01, 4.140000E-01, 4.110000E-01, 4.060000E-01 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/mgh17.shtml\nvoid testNistMGH17(void)\n{\n  const int n=5;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 50., 150., -100., 1., 2.;\n  // do the computation\n  MGH17_functor functor;\n  LevenbergMarquardt<MGH17_functor> lm(functor);\n  lm.parameters.ftol = NumTraits<double>::epsilon();\n  lm.parameters.xtol = NumTraits<double>::epsilon();\n  lm.parameters.maxfev = 1000;\n  info = lm.minimize(x);\n\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 5.4648946975E-05);\n  // check x\n  VERIFY_IS_APPROX(x[0], 3.7541005211E-01);\n  VERIFY_IS_APPROX(x[1], 1.9358469127E+00);\n  VERIFY_IS_APPROX(x[2], -1.4646871366E+00);\n  VERIFY_IS_APPROX(x[3], 1.2867534640E-02);\n  VERIFY_IS_APPROX(x[4], 2.2122699662E-02);\n  \n  // check return value\n  VERIFY_IS_EQUAL(info, 2); \n  LM_CHECK_N_ITERS(lm, 602, 545);\n\n  /*\n   * Second try\n   */\n  x<< 0.5  ,1.5  ,-1   ,0.01 ,0.02;\n  // do the computation\n  lm.resetParameters();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 18, 15);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 5.4648946975E-05);\n  // check x\n  VERIFY_IS_APPROX(x[0], 3.7541005211E-01);\n  VERIFY_IS_APPROX(x[1], 1.9358469127E+00);\n  VERIFY_IS_APPROX(x[2], -1.4646871366E+00);\n  VERIFY_IS_APPROX(x[3], 1.2867534640E-02);\n  VERIFY_IS_APPROX(x[4], 2.2122699662E-02);\n}\n\nstruct MGH09_functor : Functor<double>\n{\n    MGH09_functor(void) : Functor<double>(4,11) {}\n    static const double _x[11];\n    static const double y[11];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==4);\n        assert(fvec.size()==11);\n        for(int i=0; i<11; i++) {\n            double x = _x[i], xx=x*x;\n            fvec[i] = b[0]*(xx+x*b[1])/(xx+x*b[2]+b[3]) - y[i];\n        }\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==4);\n        assert(fjac.rows()==11);\n        assert(fjac.cols()==4);\n        for(int i=0; i<11; i++) {\n            double x = _x[i], xx=x*x;\n            double factor = 1./(xx+x*b[2]+b[3]);\n            fjac(i,0) = (xx+x*b[1]) * factor;\n            fjac(i,1) = b[0]*x* factor;\n            fjac(i,2) = - b[0]*(xx+x*b[1]) * x * factor * factor;\n            fjac(i,3) = - b[0]*(xx+x*b[1]) * factor * factor;\n        }\n        return 0;\n    }\n};\nconst double MGH09_functor::_x[11] = { 4., 2., 1., 5.E-1 , 2.5E-01, 1.670000E-01, 1.250000E-01,  1.E-01, 8.330000E-02, 7.140000E-02, 6.250000E-02 };\nconst double MGH09_functor::y[11] = { 1.957000E-01, 1.947000E-01, 1.735000E-01, 1.600000E-01, 8.440000E-02, 6.270000E-02, 4.560000E-02, 3.420000E-02, 3.230000E-02, 2.350000E-02, 2.460000E-02 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/mgh09.shtml\nvoid testNistMGH09(void)\n{\n  const int n=4;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 25., 39, 41.5, 39.;\n  // do the computation\n  MGH09_functor functor;\n  LevenbergMarquardt<MGH09_functor> lm(functor);\n  lm.parameters.maxfev = 1000;\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 490, 376);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 3.0750560385E-04);\n  // check x\n  VERIFY_IS_APPROX(x[0], 0.1928077089); // should be 1.9280693458E-01\n  VERIFY_IS_APPROX(x[1], 0.19126423573); // should be 1.9128232873E-01\n  VERIFY_IS_APPROX(x[2], 0.12305309914); // should be 1.2305650693E-01\n  VERIFY_IS_APPROX(x[3], 0.13605395375); // should be 1.3606233068E-01\n\n  /*\n   * Second try\n   */\n  x<< 0.25, 0.39, 0.415, 0.39;\n  // do the computation\n  lm.resetParameters();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 18, 16);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 3.0750560385E-04);\n  // check x\n  VERIFY_IS_APPROX(x[0], 0.19280781); // should be 1.9280693458E-01\n  VERIFY_IS_APPROX(x[1], 0.19126265); // should be 1.9128232873E-01\n  VERIFY_IS_APPROX(x[2], 0.12305280); // should be 1.2305650693E-01\n  VERIFY_IS_APPROX(x[3], 0.13605322); // should be 1.3606233068E-01\n}\n\n\n\nstruct Bennett5_functor : Functor<double>\n{\n    Bennett5_functor(void) : Functor<double>(3,154) {}\n    static const double x[154];\n    static const double y[154];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==3);\n        assert(fvec.size()==154);\n        for(int i=0; i<154; i++)\n            fvec[i] = b[0]* pow(b[1]+x[i],-1./b[2]) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==3);\n        assert(fjac.rows()==154);\n        assert(fjac.cols()==3);\n        for(int i=0; i<154; i++) {\n            double e = pow(b[1]+x[i],-1./b[2]);\n            fjac(i,0) = e;\n            fjac(i,1) = - b[0]*e/b[2]/(b[1]+x[i]);\n            fjac(i,2) = b[0]*e*log(b[1]+x[i])/b[2]/b[2];\n        }\n        return 0;\n    }\n};\nconst double Bennett5_functor::x[154] = { 7.447168E0, 8.102586E0, 8.452547E0, 8.711278E0, 8.916774E0, 9.087155E0, 9.232590E0, 9.359535E0, 9.472166E0, 9.573384E0, 9.665293E0, 9.749461E0, 9.827092E0, 9.899128E0, 9.966321E0, 10.029280E0, 10.088510E0, 10.144430E0, 10.197380E0, 10.247670E0, 10.295560E0, 10.341250E0, 10.384950E0, 10.426820E0, 10.467000E0, 10.505640E0, 10.542830E0, 10.578690E0, 10.613310E0, 10.646780E0, 10.679150E0, 10.710520E0, 10.740920E0, 10.770440E0, 10.799100E0, 10.826970E0, 10.854080E0, 10.880470E0, 10.906190E0, 10.931260E0, 10.955720E0, 10.979590E0, 11.002910E0, 11.025700E0, 11.047980E0, 11.069770E0, 11.091100E0, 11.111980E0, 11.132440E0, 11.152480E0, 11.172130E0, 11.191410E0, 11.210310E0, 11.228870E0, 11.247090E0, 11.264980E0, 11.282560E0, 11.299840E0, 11.316820E0, 11.333520E0, 11.349940E0, 11.366100E0, 11.382000E0, 11.397660E0, 11.413070E0, 11.428240E0, 11.443200E0, 11.457930E0, 11.472440E0, 11.486750E0, 11.500860E0, 11.514770E0, 11.528490E0, 11.542020E0, 11.555380E0, 11.568550E0,\n11.581560E0, 11.594420E0, 11.607121E0, 11.619640E0, 11.632000E0, 11.644210E0, 11.656280E0, 11.668200E0, 11.679980E0, 11.691620E0, 11.703130E0, 11.714510E0, 11.725760E0, 11.736880E0, 11.747890E0, 11.758780E0, 11.769550E0, 11.780200E0, 11.790730E0, 11.801160E0, 11.811480E0, 11.821700E0, 11.831810E0, 11.841820E0, 11.851730E0, 11.861550E0, 11.871270E0, 11.880890E0, 11.890420E0, 11.899870E0, 11.909220E0, 11.918490E0, 11.927680E0, 11.936780E0, 11.945790E0, 11.954730E0, 11.963590E0, 11.972370E0, 11.981070E0, 11.989700E0, 11.998260E0, 12.006740E0, 12.015150E0, 12.023490E0, 12.031760E0, 12.039970E0, 12.048100E0, 12.056170E0, 12.064180E0, 12.072120E0, 12.080010E0, 12.087820E0, 12.095580E0, 12.103280E0, 12.110920E0, 12.118500E0, 12.126030E0, 12.133500E0, 12.140910E0, 12.148270E0, 12.155570E0, 12.162830E0, 12.170030E0, 12.177170E0, 12.184270E0, 12.191320E0, 12.198320E0, 12.205270E0, 12.212170E0, 12.219030E0, 12.225840E0, 12.232600E0, 12.239320E0, 12.245990E0, 12.252620E0, 12.259200E0, 12.265750E0, 12.272240E0 };\nconst double Bennett5_functor::y[154] = { -34.834702E0 ,-34.393200E0 ,-34.152901E0 ,-33.979099E0 ,-33.845901E0 ,-33.732899E0 ,-33.640301E0 ,-33.559200E0 ,-33.486801E0 ,-33.423100E0 ,-33.365101E0 ,-33.313000E0 ,-33.260899E0 ,-33.217400E0 ,-33.176899E0 ,-33.139198E0 ,-33.101601E0 ,-33.066799E0 ,-33.035000E0 ,-33.003101E0 ,-32.971298E0 ,-32.942299E0 ,-32.916302E0 ,-32.890202E0 ,-32.864101E0 ,-32.841000E0 ,-32.817799E0 ,-32.797501E0 ,-32.774300E0 ,-32.757000E0 ,-32.733799E0 ,-32.716400E0 ,-32.699100E0 ,-32.678799E0 ,-32.661400E0 ,-32.644001E0 ,-32.626701E0 ,-32.612202E0 ,-32.597698E0 ,-32.583199E0 ,-32.568699E0 ,-32.554298E0 ,-32.539799E0 ,-32.525299E0 ,-32.510799E0 ,-32.499199E0 ,-32.487598E0 ,-32.473202E0 ,-32.461601E0 ,-32.435501E0 ,-32.435501E0 ,-32.426800E0 ,-32.412300E0 ,-32.400799E0 ,-32.392101E0 ,-32.380501E0 ,-32.366001E0 ,-32.357300E0 ,-32.348598E0 ,-32.339901E0 ,-32.328400E0 ,-32.319698E0 ,-32.311001E0 ,-32.299400E0 ,-32.290699E0 ,-32.282001E0 ,-32.273300E0 ,-32.264599E0 ,-32.256001E0 ,-32.247299E0\n,-32.238602E0 ,-32.229900E0 ,-32.224098E0 ,-32.215401E0 ,-32.203800E0 ,-32.198002E0 ,-32.189400E0 ,-32.183601E0 ,-32.174900E0 ,-32.169102E0 ,-32.163300E0 ,-32.154598E0 ,-32.145901E0 ,-32.140099E0 ,-32.131401E0 ,-32.125599E0 ,-32.119801E0 ,-32.111198E0 ,-32.105400E0 ,-32.096699E0 ,-32.090900E0 ,-32.088001E0 ,-32.079300E0 ,-32.073502E0 ,-32.067699E0 ,-32.061901E0 ,-32.056099E0 ,-32.050301E0 ,-32.044498E0 ,-32.038799E0 ,-32.033001E0 ,-32.027199E0 ,-32.024300E0 ,-32.018501E0 ,-32.012699E0 ,-32.004002E0 ,-32.001099E0 ,-31.995300E0 ,-31.989500E0 ,-31.983700E0 ,-31.977900E0 ,-31.972099E0 ,-31.969299E0 ,-31.963501E0 ,-31.957701E0 ,-31.951900E0 ,-31.946100E0 ,-31.940300E0 ,-31.937401E0 ,-31.931601E0 ,-31.925800E0 ,-31.922899E0 ,-31.917101E0 ,-31.911301E0 ,-31.908400E0 ,-31.902599E0 ,-31.896900E0 ,-31.893999E0 ,-31.888201E0 ,-31.885300E0 ,-31.882401E0 ,-31.876600E0 ,-31.873699E0 ,-31.867901E0 ,-31.862101E0 ,-31.859200E0 ,-31.856300E0 ,-31.850500E0 ,-31.844700E0 ,-31.841801E0 ,-31.838900E0 ,-31.833099E0 ,-31.830200E0 ,\n-31.827299E0 ,-31.821600E0 ,-31.818701E0 ,-31.812901E0 ,-31.809999E0 ,-31.807100E0 ,-31.801300E0 ,-31.798401E0 ,-31.795500E0 ,-31.789700E0 ,-31.786800E0 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/bennett5.shtml\nvoid testNistBennett5(void)\n{\n  const int  n=3;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< -2000., 50., 0.8;\n  // do the computation\n  Bennett5_functor functor;\n  LevenbergMarquardt<Bennett5_functor> lm(functor);\n  lm.parameters.maxfev = 1000;\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 758, 744);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 5.2404744073E-04);\n  // check x\n  VERIFY_IS_APPROX(x[0], -2.5235058043E+03);\n  VERIFY_IS_APPROX(x[1], 4.6736564644E+01);\n  VERIFY_IS_APPROX(x[2], 9.3218483193E-01);\n  /*\n   * Second try\n   */\n  x<< -1500., 45., 0.85;\n  // do the computation\n  lm.resetParameters();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 203, 192);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 5.2404744073E-04);\n  // check x\n  VERIFY_IS_APPROX(x[0], -2523.3007865); // should be -2.5235058043E+03\n  VERIFY_IS_APPROX(x[1], 46.735705771); // should be 4.6736564644E+01);\n  VERIFY_IS_APPROX(x[2], 0.93219881891); // should be 9.3218483193E-01);\n}\n\nstruct thurber_functor : Functor<double>\n{\n    thurber_functor(void) : Functor<double>(7,37) {}\n    static const double _x[37];\n    static const double _y[37];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        //        int called=0; printf(\"call hahn1_functor with  iflag=%d, called=%d\\n\", iflag, called); if (iflag==1) called++;\n        assert(b.size()==7);\n        assert(fvec.size()==37);\n        for(int i=0; i<37; i++) {\n            double x=_x[i], xx=x*x, xxx=xx*x;\n            fvec[i] = (b[0]+b[1]*x+b[2]*xx+b[3]*xxx) / (1.+b[4]*x+b[5]*xx+b[6]*xxx) - _y[i];\n        }\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==7);\n        assert(fjac.rows()==37);\n        assert(fjac.cols()==7);\n        for(int i=0; i<37; i++) {\n            double x=_x[i], xx=x*x, xxx=xx*x;\n            double fact = 1./(1.+b[4]*x+b[5]*xx+b[6]*xxx);\n            fjac(i,0) = 1.*fact;\n            fjac(i,1) = x*fact;\n            fjac(i,2) = xx*fact;\n            fjac(i,3) = xxx*fact;\n            fact = - (b[0]+b[1]*x+b[2]*xx+b[3]*xxx) * fact * fact;\n            fjac(i,4) = x*fact;\n            fjac(i,5) = xx*fact;\n            fjac(i,6) = xxx*fact;\n        }\n        return 0;\n    }\n};\nconst double thurber_functor::_x[37] = { -3.067E0, -2.981E0, -2.921E0, -2.912E0, -2.840E0, -2.797E0, -2.702E0, -2.699E0, -2.633E0, -2.481E0, -2.363E0, -2.322E0, -1.501E0, -1.460E0, -1.274E0, -1.212E0, -1.100E0, -1.046E0, -0.915E0, -0.714E0, -0.566E0, -0.545E0, -0.400E0, -0.309E0, -0.109E0, -0.103E0, 0.010E0, 0.119E0, 0.377E0, 0.790E0, 0.963E0, 1.006E0, 1.115E0, 1.572E0, 1.841E0, 2.047E0, 2.200E0 };\nconst double thurber_functor::_y[37] = { 80.574E0, 84.248E0, 87.264E0, 87.195E0, 89.076E0, 89.608E0, 89.868E0, 90.101E0, 92.405E0, 95.854E0, 100.696E0, 101.060E0, 401.672E0, 390.724E0, 567.534E0, 635.316E0, 733.054E0, 759.087E0, 894.206E0, 990.785E0, 1090.109E0, 1080.914E0, 1122.643E0, 1178.351E0, 1260.531E0, 1273.514E0, 1288.339E0, 1327.543E0, 1353.863E0, 1414.509E0, 1425.208E0, 1421.384E0, 1442.962E0, 1464.350E0, 1468.705E0, 1447.894E0, 1457.628E0};\n\n// http://www.itl.nist.gov/div898/strd/nls/data/thurber.shtml\nvoid testNistThurber(void)\n{\n  const int n=7;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 1000 ,1000 ,400 ,40 ,0.7,0.3,0.0 ;\n  // do the computation\n  thurber_functor functor;\n  LevenbergMarquardt<thurber_functor> lm(functor);\n  lm.parameters.ftol = 1.E4*NumTraits<double>::epsilon();\n  lm.parameters.xtol = 1.E4*NumTraits<double>::epsilon();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 39,36);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 5.6427082397E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.2881396800E+03);\n  VERIFY_IS_APPROX(x[1], 1.4910792535E+03);\n  VERIFY_IS_APPROX(x[2], 5.8323836877E+02);\n  VERIFY_IS_APPROX(x[3], 7.5416644291E+01);\n  VERIFY_IS_APPROX(x[4], 9.6629502864E-01);\n  VERIFY_IS_APPROX(x[5], 3.9797285797E-01);\n  VERIFY_IS_APPROX(x[6], 4.9727297349E-02);\n\n  /*\n   * Second try\n   */\n  x<< 1300 ,1500 ,500  ,75   ,1    ,0.4  ,0.05  ;\n  // do the computation\n  lm.resetParameters();\n  lm.parameters.ftol = 1.E4*NumTraits<double>::epsilon();\n  lm.parameters.xtol = 1.E4*NumTraits<double>::epsilon();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 29, 28);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 5.6427082397E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.2881396800E+03);\n  VERIFY_IS_APPROX(x[1], 1.4910792535E+03);\n  VERIFY_IS_APPROX(x[2], 5.8323836877E+02);\n  VERIFY_IS_APPROX(x[3], 7.5416644291E+01);\n  VERIFY_IS_APPROX(x[4], 9.6629502864E-01);\n  VERIFY_IS_APPROX(x[5], 3.9797285797E-01);\n  VERIFY_IS_APPROX(x[6], 4.9727297349E-02);\n}\n\nstruct rat43_functor : Functor<double>\n{\n    rat43_functor(void) : Functor<double>(4,15) {}\n    static const double x[15];\n    static const double y[15];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==4);\n        assert(fvec.size()==15);\n        for(int i=0; i<15; i++)\n            fvec[i] = b[0] * pow(1.+exp(b[1]-b[2]*x[i]),-1./b[3]) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==4);\n        assert(fjac.rows()==15);\n        assert(fjac.cols()==4);\n        for(int i=0; i<15; i++) {\n            double e = exp(b[1]-b[2]*x[i]);\n            double power = -1./b[3];\n            fjac(i,0) = pow(1.+e, power);\n            fjac(i,1) = power*b[0]*e*pow(1.+e, power-1.);\n            fjac(i,2) = -power*b[0]*e*x[i]*pow(1.+e, power-1.);\n            fjac(i,3) = b[0]*power*power*log(1.+e)*pow(1.+e, power);\n        }\n        return 0;\n    }\n};\nconst double rat43_functor::x[15] = { 1., 2., 3., 4., 5., 6., 7., 8., 9., 10., 11., 12., 13., 14., 15. };\nconst double rat43_functor::y[15] = { 16.08, 33.83, 65.80, 97.20, 191.55, 326.20, 386.87, 520.53, 590.03, 651.92, 724.93, 699.56, 689.96, 637.56, 717.41 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/ratkowsky3.shtml\nvoid testNistRat43(void)\n{\n  const int n=4;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 100., 10., 1., 1.;\n  // do the computation\n  rat43_functor functor;\n  LevenbergMarquardt<rat43_functor> lm(functor);\n  lm.parameters.ftol = 1.E6*NumTraits<double>::epsilon();\n  lm.parameters.xtol = 1.E6*NumTraits<double>::epsilon();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 27, 20);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 8.7864049080E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 6.9964151270E+02);\n  VERIFY_IS_APPROX(x[1], 5.2771253025E+00);\n  VERIFY_IS_APPROX(x[2], 7.5962938329E-01);\n  VERIFY_IS_APPROX(x[3], 1.2792483859E+00);\n\n  /*\n   * Second try\n   */\n  x<< 700., 5., 0.75, 1.3;\n  // do the computation\n  lm.resetParameters();\n  lm.parameters.ftol = 1.E5*NumTraits<double>::epsilon();\n  lm.parameters.xtol = 1.E5*NumTraits<double>::epsilon();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 9, 8);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 8.7864049080E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 6.9964151270E+02);\n  VERIFY_IS_APPROX(x[1], 5.2771253025E+00);\n  VERIFY_IS_APPROX(x[2], 7.5962938329E-01);\n  VERIFY_IS_APPROX(x[3], 1.2792483859E+00);\n}\n\n\n\nstruct eckerle4_functor : Functor<double>\n{\n    eckerle4_functor(void) : Functor<double>(3,35) {}\n    static const double x[35];\n    static const double y[35];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==3);\n        assert(fvec.size()==35);\n        for(int i=0; i<35; i++)\n            fvec[i] = b[0]/b[1] * exp(-0.5*(x[i]-b[2])*(x[i]-b[2])/(b[1]*b[1])) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==3);\n        assert(fjac.rows()==35);\n        assert(fjac.cols()==3);\n        for(int i=0; i<35; i++) {\n            double b12 = b[1]*b[1];\n            double e = exp(-0.5*(x[i]-b[2])*(x[i]-b[2])/b12);\n            fjac(i,0) = e / b[1];\n            fjac(i,1) = ((x[i]-b[2])*(x[i]-b[2])/b12-1.) * b[0]*e/b12;\n            fjac(i,2) = (x[i]-b[2])*e*b[0]/b[1]/b12;\n        }\n        return 0;\n    }\n};\nconst double eckerle4_functor::x[35] = { 400.0, 405.0, 410.0, 415.0, 420.0, 425.0, 430.0, 435.0, 436.5, 438.0, 439.5, 441.0, 442.5, 444.0, 445.5, 447.0, 448.5, 450.0, 451.5, 453.0, 454.5, 456.0, 457.5, 459.0, 460.5, 462.0, 463.5, 465.0, 470.0, 475.0, 480.0, 485.0, 490.0, 495.0, 500.0};\nconst double eckerle4_functor::y[35] = { 0.0001575, 0.0001699, 0.0002350, 0.0003102, 0.0004917, 0.0008710, 0.0017418, 0.0046400, 0.0065895, 0.0097302, 0.0149002, 0.0237310, 0.0401683, 0.0712559, 0.1264458, 0.2073413, 0.2902366, 0.3445623, 0.3698049, 0.3668534, 0.3106727, 0.2078154, 0.1164354, 0.0616764, 0.0337200, 0.0194023, 0.0117831, 0.0074357, 0.0022732, 0.0008800, 0.0004579, 0.0002345, 0.0001586, 0.0001143, 0.0000710 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/eckerle4.shtml\nvoid testNistEckerle4(void)\n{\n  const int n=3;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 1., 10., 500.;\n  // do the computation\n  eckerle4_functor functor;\n  LevenbergMarquardt<eckerle4_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 18, 15);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 1.4635887487E-03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.5543827178);\n  VERIFY_IS_APPROX(x[1], 4.0888321754);\n  VERIFY_IS_APPROX(x[2], 4.5154121844E+02);\n\n  /*\n   * Second try\n   */\n  x<< 1.5, 5., 450.;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  LM_CHECK_N_ITERS(lm, 7, 6);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec.squaredNorm(), 1.4635887487E-03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.5543827178);\n  VERIFY_IS_APPROX(x[1], 4.0888321754);\n  VERIFY_IS_APPROX(x[2], 4.5154121844E+02);\n}\n\nEIGEN_DECLARE_TEST(NonLinearOptimization)\n{\n    // Tests using the examples provided by (c)minpack\n    CALL_SUBTEST/*_1*/(testChkder());\n    CALL_SUBTEST/*_1*/(testLmder1());\n    CALL_SUBTEST/*_1*/(testLmder());\n    CALL_SUBTEST/*_2*/(testHybrj1());\n    CALL_SUBTEST/*_2*/(testHybrj());\n    CALL_SUBTEST/*_2*/(testHybrd1());\n    CALL_SUBTEST/*_2*/(testHybrd());\n    CALL_SUBTEST/*_3*/(testLmstr1());\n    CALL_SUBTEST/*_3*/(testLmstr());\n    CALL_SUBTEST/*_3*/(testLmdif1());\n    CALL_SUBTEST/*_3*/(testLmdif());\n\n    // NIST tests, level of difficulty = \"Lower\"\n    CALL_SUBTEST/*_4*/(testNistMisra1a());\n    CALL_SUBTEST/*_4*/(testNistChwirut2());\n\n    // NIST tests, level of difficulty = \"Average\"\n    CALL_SUBTEST/*_5*/(testNistHahn1());\n    CALL_SUBTEST/*_6*/(testNistMisra1d());\n    CALL_SUBTEST/*_7*/(testNistMGH17());\n    CALL_SUBTEST/*_8*/(testNistLanczos1());\n\n//     // NIST tests, level of difficulty = \"Higher\"\n    CALL_SUBTEST/*_9*/(testNistRat42());\n//     CALL_SUBTEST/*_10*/(testNistMGH10());\n    CALL_SUBTEST/*_11*/(testNistBoxBOD());\n//     CALL_SUBTEST/*_12*/(testNistMGH09());\n    CALL_SUBTEST/*_13*/(testNistBennett5());\n    CALL_SUBTEST/*_14*/(testNistThurber());\n    CALL_SUBTEST/*_15*/(testNistRat43());\n    CALL_SUBTEST/*_16*/(testNistEckerle4());\n}\n\n/*\n * Can be useful for debugging...\n  printf(\"info, nfev : %d, %d\\n\", info, lm.nfev);\n  printf(\"info, nfev, njev : %d, %d, %d\\n\", info, solver.nfev, solver.njev);\n  printf(\"info, nfev : %d, %d\\n\", info, solver.nfev);\n  printf(\"x[0] : %.32g\\n\", x[0]);\n  printf(\"x[1] : %.32g\\n\", x[1]);\n  printf(\"x[2] : %.32g\\n\", x[2]);\n  printf(\"x[3] : %.32g\\n\", x[3]);\n  printf(\"fvec.blueNorm() : %.32g\\n\", solver.fvec.blueNorm());\n  printf(\"fvec.blueNorm() : %.32g\\n\", lm.fvec.blueNorm());\n\n  printf(\"info, nfev, njev : %d, %d, %d\\n\", info, lm.nfev, lm.njev);\n  printf(\"fvec.squaredNorm() : %.13g\\n\", lm.fvec.squaredNorm());\n  std::cout << x << std::endl;\n  std::cout.precision(9);\n  std::cout << x[0] << std::endl;\n  std::cout << x[1] << std::endl;\n  std::cout << x[2] << std::endl;\n  std::cout << x[3] << std::endl;\n*/\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/NumericalDiff.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n\n#include <stdio.h>\n\n#include \"main.h\"\n#include <unsupported/Eigen/NumericalDiff>\n    \n// Generic functor\ntemplate<typename _Scalar, int NX=Dynamic, int NY=Dynamic>\nstruct Functor\n{\n  typedef _Scalar Scalar;\n  enum {\n    InputsAtCompileTime = NX,\n    ValuesAtCompileTime = NY\n  };\n  typedef Matrix<Scalar,InputsAtCompileTime,1> InputType;\n  typedef Matrix<Scalar,ValuesAtCompileTime,1> ValueType;\n  typedef Matrix<Scalar,ValuesAtCompileTime,InputsAtCompileTime> JacobianType;\n  \n  int m_inputs, m_values;\n  \n  Functor() : m_inputs(InputsAtCompileTime), m_values(ValuesAtCompileTime) {}\n  Functor(int inputs_, int values_) : m_inputs(inputs_), m_values(values_) {}\n  \n  int inputs() const { return m_inputs; }\n  int values() const { return m_values; }\n\n};\n\nstruct my_functor : Functor<double>\n{\n    my_functor(void): Functor<double>(3,15) {}\n    int operator()(const VectorXd &x, VectorXd &fvec) const\n    {\n        double tmp1, tmp2, tmp3;\n        double y[15] = {1.4e-1, 1.8e-1, 2.2e-1, 2.5e-1, 2.9e-1, 3.2e-1, 3.5e-1,\n            3.9e-1, 3.7e-1, 5.8e-1, 7.3e-1, 9.6e-1, 1.34, 2.1, 4.39};\n\n        for (int i = 0; i < values(); i++)\n        {\n            tmp1 = i+1;\n            tmp2 = 16 - i - 1;\n            tmp3 = (i>=8)? tmp2 : tmp1;\n            fvec[i] = y[i] - (x[0] + tmp1/(x[1]*tmp2 + x[2]*tmp3));\n        }\n        return 0;\n    }\n\n    int actual_df(const VectorXd &x, MatrixXd &fjac) const\n    {\n        double tmp1, tmp2, tmp3, tmp4;\n        for (int i = 0; i < values(); i++)\n        {\n            tmp1 = i+1;\n            tmp2 = 16 - i - 1;\n            tmp3 = (i>=8)? tmp2 : tmp1;\n            tmp4 = (x[1]*tmp2 + x[2]*tmp3); tmp4 = tmp4*tmp4;\n            fjac(i,0) = -1;\n            fjac(i,1) = tmp1*tmp2/tmp4;\n            fjac(i,2) = tmp1*tmp3/tmp4;\n        }\n        return 0;\n    }\n};\n\nvoid test_forward()\n{\n    VectorXd x(3);\n    MatrixXd jac(15,3);\n    MatrixXd actual_jac(15,3);\n    my_functor functor;\n\n    x << 0.082, 1.13, 2.35;\n\n    // real one \n    functor.actual_df(x, actual_jac);\n//    std::cout << actual_jac << std::endl << std::endl;\n\n    // using NumericalDiff\n    NumericalDiff<my_functor> numDiff(functor);\n    numDiff.df(x, jac);\n//    std::cout << jac << std::endl;\n\n    VERIFY_IS_APPROX(jac, actual_jac);\n}\n\nvoid test_central()\n{\n    VectorXd x(3);\n    MatrixXd jac(15,3);\n    MatrixXd actual_jac(15,3);\n    my_functor functor;\n\n    x << 0.082, 1.13, 2.35;\n\n    // real one \n    functor.actual_df(x, actual_jac);\n\n    // using NumericalDiff\n    NumericalDiff<my_functor,Central> numDiff(functor);\n    numDiff.df(x, jac);\n\n    VERIFY_IS_APPROX(jac, actual_jac);\n}\n\nEIGEN_DECLARE_TEST(NumericalDiff)\n{\n    CALL_SUBTEST(test_forward());\n    CALL_SUBTEST(test_central());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/alignedvector3.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <unsupported/Eigen/AlignedVector3>\n\nnamespace Eigen {\n\ntemplate<typename T,typename Derived>\nT test_relative_error(const AlignedVector3<T> &a, const MatrixBase<Derived> &b)\n{\n  return test_relative_error(a.coeffs().template head<3>(), b);\n}\n\n}\n\ntemplate<typename Scalar>\nvoid alignedvector3()\n{\n  Scalar s1 = internal::random<Scalar>();\n  Scalar s2 = internal::random<Scalar>();\n  typedef Matrix<Scalar,3,1> RefType;\n  typedef Matrix<Scalar,3,3> Mat33;\n  typedef AlignedVector3<Scalar> FastType;\n  RefType  r1(RefType::Random()), r2(RefType::Random()), r3(RefType::Random()),\n           r4(RefType::Random()), r5(RefType::Random());\n  FastType f1(r1), f2(r2), f3(r3), f4(r4), f5(r5);\n  Mat33 m1(Mat33::Random());\n  \n  VERIFY_IS_APPROX(f1,r1);\n  VERIFY_IS_APPROX(f4,r4);\n\n  VERIFY_IS_APPROX(f4+f1,r4+r1);\n  VERIFY_IS_APPROX(f4-f1,r4-r1);\n  VERIFY_IS_APPROX(f4+f1-f2,r4+r1-r2);\n  VERIFY_IS_APPROX(f4+=f3,r4+=r3);\n  VERIFY_IS_APPROX(f4-=f5,r4-=r5);\n  VERIFY_IS_APPROX(f4-=f5+f1,r4-=r5+r1);\n  VERIFY_IS_APPROX(f5+f1-s1*f2,r5+r1-s1*r2);\n  VERIFY_IS_APPROX(f5+f1/s2-s1*f2,r5+r1/s2-s1*r2);\n  \n  VERIFY_IS_APPROX(m1*f4,m1*r4);\n  VERIFY_IS_APPROX(f4.transpose()*m1,r4.transpose()*m1);\n  \n  VERIFY_IS_APPROX(f2.dot(f3),r2.dot(r3));\n  VERIFY_IS_APPROX(f2.cross(f3),r2.cross(r3));\n  VERIFY_IS_APPROX(f2.norm(),r2.norm());\n\n  VERIFY_IS_APPROX(f2.normalized(),r2.normalized());\n\n  VERIFY_IS_APPROX((f2+f1).normalized(),(r2+r1).normalized());\n  \n  f2.normalize();\n  r2.normalize();\n  VERIFY_IS_APPROX(f2,r2);\n  \n  {\n    FastType f6 = RefType::Zero();\n    FastType f7 = FastType::Zero();\n    VERIFY_IS_APPROX(f6,f7);\n    f6 = r4+r1;\n    VERIFY_IS_APPROX(f6,r4+r1);\n    f6 -= Scalar(2)*r4;\n    VERIFY_IS_APPROX(f6,r1-r4);\n  }\n  \n  FastType f8, f9(0,0,0);\n  VERIFY_IS_APPROX(f9-f1,-f1);\n\n  std::stringstream ss1, ss2;\n  ss1 << f1;\n  ss2 << r1;\n  VERIFY(ss1.str()==ss2.str());\n}\n\nEIGEN_DECLARE_TEST(alignedvector3)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST( alignedvector3<float>() );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/autodiff.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <unsupported/Eigen/AutoDiff>\n\ntemplate<typename Scalar>\nEIGEN_DONT_INLINE Scalar foo(const Scalar& x, const Scalar& y)\n{\n  using namespace std;\n//   return x+std::sin(y);\n  EIGEN_ASM_COMMENT(\"mybegin\");\n  // pow(float, int) promotes to pow(double, double)\n  return x*2 - 1 + static_cast<Scalar>(pow(1+x,2)) + 2*sqrt(y*y+0) - 4 * sin(0+x) + 2 * cos(y+0) - exp(Scalar(-0.5)*x*x+0);\n  //return x+2*y*x;//x*2 -std::pow(x,2);//(2*y/x);// - y*2;\n  EIGEN_ASM_COMMENT(\"myend\");\n}\n\ntemplate<typename Vector>\nEIGEN_DONT_INLINE typename Vector::Scalar foo(const Vector& p)\n{\n  typedef typename Vector::Scalar Scalar;\n  return (p-Vector(Scalar(-1),Scalar(1.))).norm() + (p.array() * p.array()).sum() + p.dot(p);\n}\n\ntemplate<typename _Scalar, int NX=Dynamic, int NY=Dynamic>\nstruct TestFunc1\n{\n  typedef _Scalar Scalar;\n  enum {\n    InputsAtCompileTime = NX,\n    ValuesAtCompileTime = NY\n  };\n  typedef Matrix<Scalar,InputsAtCompileTime,1> InputType;\n  typedef Matrix<Scalar,ValuesAtCompileTime,1> ValueType;\n  typedef Matrix<Scalar,ValuesAtCompileTime,InputsAtCompileTime> JacobianType;\n\n  int m_inputs, m_values;\n\n  TestFunc1() : m_inputs(InputsAtCompileTime), m_values(ValuesAtCompileTime) {}\n  TestFunc1(int inputs_, int values_) : m_inputs(inputs_), m_values(values_) {}\n\n  int inputs() const { return m_inputs; }\n  int values() const { return m_values; }\n\n  template<typename T>\n  void operator() (const Matrix<T,InputsAtCompileTime,1>& x, Matrix<T,ValuesAtCompileTime,1>* _v) const\n  {\n    Matrix<T,ValuesAtCompileTime,1>& v = *_v;\n\n    v[0] = 2 * x[0] * x[0] + x[0] * x[1];\n    v[1] = 3 * x[1] * x[0] + 0.5 * x[1] * x[1];\n    if(inputs()>2)\n    {\n      v[0] += 0.5 * x[2];\n      v[1] += x[2];\n    }\n    if(values()>2)\n    {\n      v[2] = 3 * x[1] * x[0] * x[0];\n    }\n    if (inputs()>2 && values()>2)\n      v[2] *= x[2];\n  }\n\n  void operator() (const InputType& x, ValueType* v, JacobianType* _j) const\n  {\n    (*this)(x, v);\n\n    if(_j)\n    {\n      JacobianType& j = *_j;\n\n      j(0,0) = 4 * x[0] + x[1];\n      j(1,0) = 3 * x[1];\n\n      j(0,1) = x[0];\n      j(1,1) = 3 * x[0] + 2 * 0.5 * x[1];\n\n      if (inputs()>2)\n      {\n        j(0,2) = 0.5;\n        j(1,2) = 1;\n      }\n      if(values()>2)\n      {\n        j(2,0) = 3 * x[1] * 2 * x[0];\n        j(2,1) = 3 * x[0] * x[0];\n      }\n      if (inputs()>2 && values()>2)\n      {\n        j(2,0) *= x[2];\n        j(2,1) *= x[2];\n\n        j(2,2) = 3 * x[1] * x[0] * x[0];\n        j(2,2) = 3 * x[1] * x[0] * x[0];\n      }\n    }\n  }\n};\n\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n/* Test functor for the C++11 features. */\ntemplate <typename Scalar>\nstruct integratorFunctor\n{\n    typedef Matrix<Scalar, 2, 1> InputType;\n    typedef Matrix<Scalar, 2, 1> ValueType;\n\n    /*\n     * Implementation starts here.\n     */\n    integratorFunctor(const Scalar gain) : _gain(gain) {}\n    integratorFunctor(const integratorFunctor& f) : _gain(f._gain) {}\n    const Scalar _gain;\n\n    template <typename T1, typename T2>\n    void operator() (const T1 &input, T2 *output, const Scalar dt) const\n    {\n        T2 &o = *output;\n\n        /* Integrator to test the AD. */\n        o[0] = input[0] + input[1] * dt * _gain;\n        o[1] = input[1] * _gain;\n    }\n\n    /* Only needed for the test */\n    template <typename T1, typename T2, typename T3>\n    void operator() (const T1 &input, T2 *output, T3 *jacobian, const Scalar dt) const\n    {\n        T2 &o = *output;\n\n        /* Integrator to test the AD. */\n        o[0] = input[0] + input[1] * dt * _gain;\n        o[1] = input[1] * _gain;\n\n        if (jacobian)\n        {\n            T3 &j = *jacobian;\n\n            j(0, 0) = 1;\n            j(0, 1) = dt * _gain;\n            j(1, 0) = 0;\n            j(1, 1) = _gain;\n        }\n    }\n\n};\n\ntemplate<typename Func> void forward_jacobian_cpp11(const Func& f)\n{\n    typedef typename Func::ValueType::Scalar Scalar;\n    typedef typename Func::ValueType ValueType;\n    typedef typename Func::InputType InputType;\n    typedef typename AutoDiffJacobian<Func>::JacobianType JacobianType;\n\n    InputType x = InputType::Random(InputType::RowsAtCompileTime);\n    ValueType y, yref;\n    JacobianType j, jref;\n\n    const Scalar dt = internal::random<double>();\n\n    jref.setZero();\n    yref.setZero();\n    f(x, &yref, &jref, dt);\n\n    //std::cerr << \"y, yref, jref: \" << \"\\n\";\n    //std::cerr << y.transpose() << \"\\n\\n\";\n    //std::cerr << yref << \"\\n\\n\";\n    //std::cerr << jref << \"\\n\\n\";\n\n    AutoDiffJacobian<Func> autoj(f);\n    autoj(x, &y, &j, dt);\n\n    //std::cerr << \"y j (via autodiff): \" << \"\\n\";\n    //std::cerr << y.transpose() << \"\\n\\n\";\n    //std::cerr << j << \"\\n\\n\";\n\n    VERIFY_IS_APPROX(y, yref);\n    VERIFY_IS_APPROX(j, jref);\n}\n#endif\n\ntemplate<typename Func> void forward_jacobian(const Func& f)\n{\n    typename Func::InputType x = Func::InputType::Random(f.inputs());\n    typename Func::ValueType y(f.values()), yref(f.values());\n    typename Func::JacobianType j(f.values(),f.inputs()), jref(f.values(),f.inputs());\n\n    jref.setZero();\n    yref.setZero();\n    f(x,&yref,&jref);\n//     std::cerr << y.transpose() << \"\\n\\n\";;\n//     std::cerr << j << \"\\n\\n\";;\n\n    j.setZero();\n    y.setZero();\n    AutoDiffJacobian<Func> autoj(f);\n    autoj(x, &y, &j);\n//     std::cerr << y.transpose() << \"\\n\\n\";;\n//     std::cerr << j << \"\\n\\n\";;\n\n    VERIFY_IS_APPROX(y, yref);\n    VERIFY_IS_APPROX(j, jref);\n}\n\n// TODO also check actual derivatives!\ntemplate <int>\nvoid test_autodiff_scalar()\n{\n  Vector2f p = Vector2f::Random();\n  typedef AutoDiffScalar<Vector2f> AD;\n  AD ax(p.x(),Vector2f::UnitX());\n  AD ay(p.y(),Vector2f::UnitY());\n  AD res = foo<AD>(ax,ay);\n  VERIFY_IS_APPROX(res.value(), foo(p.x(),p.y()));\n}\n\n\n// TODO also check actual derivatives!\ntemplate <int>\nvoid test_autodiff_vector()\n{\n  Vector2f p = Vector2f::Random();\n  typedef AutoDiffScalar<Vector2f> AD;\n  typedef Matrix<AD,2,1> VectorAD;\n  VectorAD ap = p.cast<AD>();\n  ap.x().derivatives() = Vector2f::UnitX();\n  ap.y().derivatives() = Vector2f::UnitY();\n\n  AD res = foo<VectorAD>(ap);\n  VERIFY_IS_APPROX(res.value(), foo(p));\n}\n\ntemplate <int>\nvoid test_autodiff_jacobian()\n{\n  CALL_SUBTEST(( forward_jacobian(TestFunc1<double,2,2>()) ));\n  CALL_SUBTEST(( forward_jacobian(TestFunc1<double,2,3>()) ));\n  CALL_SUBTEST(( forward_jacobian(TestFunc1<double,3,2>()) ));\n  CALL_SUBTEST(( forward_jacobian(TestFunc1<double,3,3>()) ));\n  CALL_SUBTEST(( forward_jacobian(TestFunc1<double>(3,3)) ));\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  CALL_SUBTEST(( forward_jacobian_cpp11(integratorFunctor<double>(10)) ));\n#endif\n}\n\n\ntemplate <int>\nvoid test_autodiff_hessian()\n{\n  typedef AutoDiffScalar<VectorXd> AD;\n  typedef Matrix<AD,Eigen::Dynamic,1> VectorAD;\n  typedef AutoDiffScalar<VectorAD> ADD;\n  typedef Matrix<ADD,Eigen::Dynamic,1> VectorADD;\n  VectorADD x(2);\n  double s1 = internal::random<double>(), s2 = internal::random<double>(), s3 = internal::random<double>(), s4 = internal::random<double>();\n  x(0).value()=s1;\n  x(1).value()=s2;\n\n  //set unit vectors for the derivative directions (partial derivatives of the input vector)\n  x(0).derivatives().resize(2);\n  x(0).derivatives().setZero();\n  x(0).derivatives()(0)= 1;\n  x(1).derivatives().resize(2);\n  x(1).derivatives().setZero();\n  x(1).derivatives()(1)=1;\n\n  //repeat partial derivatives for the inner AutoDiffScalar\n  x(0).value().derivatives() = VectorXd::Unit(2,0);\n  x(1).value().derivatives() = VectorXd::Unit(2,1);\n\n  //set the hessian matrix to zero\n  for(int idx=0; idx<2; idx++) {\n      x(0).derivatives()(idx).derivatives()  = VectorXd::Zero(2);\n      x(1).derivatives()(idx).derivatives()  = VectorXd::Zero(2);\n  }\n\n  ADD y = sin(AD(s3)*x(0) + AD(s4)*x(1));\n\n  VERIFY_IS_APPROX(y.value().derivatives()(0), y.derivatives()(0).value());\n  VERIFY_IS_APPROX(y.value().derivatives()(1), y.derivatives()(1).value());\n  VERIFY_IS_APPROX(y.value().derivatives()(0), s3*std::cos(s1*s3+s2*s4));\n  VERIFY_IS_APPROX(y.value().derivatives()(1), s4*std::cos(s1*s3+s2*s4));\n  VERIFY_IS_APPROX(y.derivatives()(0).derivatives(), -std::sin(s1*s3+s2*s4)*Vector2d(s3*s3,s4*s3));\n  VERIFY_IS_APPROX(y.derivatives()(1).derivatives(),  -std::sin(s1*s3+s2*s4)*Vector2d(s3*s4,s4*s4));\n\n  ADD z = x(0)*x(1);\n  VERIFY_IS_APPROX(z.derivatives()(0).derivatives(), Vector2d(0,1));\n  VERIFY_IS_APPROX(z.derivatives()(1).derivatives(), Vector2d(1,0));\n}\n\ndouble bug_1222() {\n  typedef Eigen::AutoDiffScalar<Eigen::Vector3d> AD;\n  const double _cv1_3 = 1.0;\n  const AD chi_3 = 1.0;\n  // this line did not work, because operator+ returns ADS<DerType&>, which then cannot be converted to ADS<DerType>\n  const AD denom = chi_3 + _cv1_3;\n  return denom.value();\n}\n\n#ifdef EIGEN_TEST_PART_5\n\ndouble bug_1223() {\n  using std::min;\n  typedef Eigen::AutoDiffScalar<Eigen::Vector3d> AD;\n\n  const double _cv1_3 = 1.0;\n  const AD chi_3 = 1.0;\n  const AD denom = 1.0;\n\n  // failed because implementation of min attempts to construct ADS<DerType&> via constructor AutoDiffScalar(const Real& value)\n  // without initializing m_derivatives (which is a reference in this case)\n  #define EIGEN_TEST_SPACE\n  const AD t = min EIGEN_TEST_SPACE (denom / chi_3, 1.0);\n\n  const AD t2 = min EIGEN_TEST_SPACE (denom / (chi_3 * _cv1_3), 1.0);\n\n  return t.value() + t2.value();\n}\n\n// regression test for some compilation issues with specializations of ScalarBinaryOpTraits\nvoid bug_1260() {\n  Matrix4d A = Matrix4d::Ones();\n  Vector4d v = Vector4d::Ones();\n  A*v;\n}\n\n// check a compilation issue with numext::max\ndouble bug_1261() {\n  typedef AutoDiffScalar<Matrix2d> AD;\n  typedef Matrix<AD,2,1> VectorAD;\n\n  VectorAD v(0.,0.);\n  const AD maxVal = v.maxCoeff();\n  const AD minVal = v.minCoeff();\n  return maxVal.value() + minVal.value();\n}\n\ndouble bug_1264() {\n  typedef AutoDiffScalar<Vector2d> AD;\n  const AD s = 0.;\n  const Matrix<AD, 3, 1> v1(0.,0.,0.);\n  const Matrix<AD, 3, 1> v2 = (s + 3.0) * v1;\n  return v2(0).value();\n}\n\n// check with expressions on constants\ndouble bug_1281() {\n  int n = 2;\n  typedef AutoDiffScalar<VectorXd> AD;\n  const AD c = 1.;\n  AD x0(2,n,0);\n  AD y1 = (AD(c)+AD(c))*x0;\n  y1 = x0 * (AD(c)+AD(c));\n  AD y2 = (-AD(c))+x0;\n  y2 = x0+(-AD(c));\n  AD y3 = (AD(c)*(-AD(c))+AD(c))*x0;\n  y3 = x0 * (AD(c)*(-AD(c))+AD(c));\n  return (y1+y2+y3).value();\n}\n\n#endif\n\nEIGEN_DECLARE_TEST(autodiff)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( test_autodiff_scalar<1>() );\n    CALL_SUBTEST_2( test_autodiff_vector<1>() );\n    CALL_SUBTEST_3( test_autodiff_jacobian<1>() );\n    CALL_SUBTEST_4( test_autodiff_hessian<1>() );\n  }\n\n  CALL_SUBTEST_5( bug_1222() );\n  CALL_SUBTEST_5( bug_1223() );\n  CALL_SUBTEST_5( bug_1260() );\n  CALL_SUBTEST_5( bug_1261() );\n  CALL_SUBTEST_5( bug_1281() );\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/autodiff_scalar.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christoph Hertzberg <chtz@informatik.uni-bremen.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <unsupported/Eigen/AutoDiff>\n\n/*\n * In this file scalar derivations are tested for correctness.\n * TODO add more tests!\n */\n\ntemplate<typename Scalar> void check_atan2()\n{\n  typedef Matrix<Scalar, 1, 1> Deriv1;\n  typedef AutoDiffScalar<Deriv1> AD;\n  \n  AD x(internal::random<Scalar>(-3.0, 3.0), Deriv1::UnitX());\n  \n  using std::exp;\n  Scalar r = exp(internal::random<Scalar>(-10, 10));\n  \n  AD s = sin(x), c = cos(x);\n  AD res = atan2(r*s, r*c);\n  \n  VERIFY_IS_APPROX(res.value(), x.value());\n  VERIFY_IS_APPROX(res.derivatives(), x.derivatives());\n\n  res = atan2(r*s+0, r*c+0);\n  VERIFY_IS_APPROX(res.value(), x.value());\n  VERIFY_IS_APPROX(res.derivatives(), x.derivatives());\n}\n\ntemplate<typename Scalar> void check_hyperbolic_functions()\n{\n  using std::sinh;\n  using std::cosh;\n  using std::tanh;\n  typedef Matrix<Scalar, 1, 1> Deriv1;\n  typedef AutoDiffScalar<Deriv1> AD;\n  Deriv1 p = Deriv1::Random();\n  AD val(p.x(),Deriv1::UnitX());\n\n  Scalar cosh_px = std::cosh(p.x());\n  AD res1 = tanh(val);\n  VERIFY_IS_APPROX(res1.value(), std::tanh(p.x()));\n  VERIFY_IS_APPROX(res1.derivatives().x(), Scalar(1.0) / (cosh_px * cosh_px));\n\n  AD res2 = sinh(val);\n  VERIFY_IS_APPROX(res2.value(), std::sinh(p.x()));\n  VERIFY_IS_APPROX(res2.derivatives().x(), cosh_px);\n\n  AD res3 = cosh(val);\n  VERIFY_IS_APPROX(res3.value(), cosh_px);\n  VERIFY_IS_APPROX(res3.derivatives().x(), std::sinh(p.x()));\n\n  // Check constant values.\n  const Scalar sample_point = Scalar(1) / Scalar(3); \n  val = AD(sample_point,Deriv1::UnitX());\n  res1 = tanh(val);\n  VERIFY_IS_APPROX(res1.derivatives().x(), Scalar(0.896629559604914));\n\n  res2 = sinh(val);\n  VERIFY_IS_APPROX(res2.derivatives().x(), Scalar(1.056071867829939));\n\n  res3 = cosh(val);\n  VERIFY_IS_APPROX(res3.derivatives().x(), Scalar(0.339540557256150));\n}\n\ntemplate <typename Scalar>\nvoid check_limits_specialization()\n{\n  typedef Eigen::Matrix<Scalar, 1, 1> Deriv;\n  typedef Eigen::AutoDiffScalar<Deriv> AD;\n\n  typedef std::numeric_limits<AD> A;\n  typedef std::numeric_limits<Scalar> B;\n\n  // workaround \"unused typedef\" warning:\n  VERIFY(!bool(internal::is_same<B, A>::value));\n\n#if EIGEN_HAS_CXX11\n  VERIFY(bool(std::is_base_of<B, A>::value));\n#endif\n}\n\nEIGEN_DECLARE_TEST(autodiff_scalar)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1( check_atan2<float>() );\n    CALL_SUBTEST_2( check_atan2<double>() );\n    CALL_SUBTEST_3( check_hyperbolic_functions<float>() );\n    CALL_SUBTEST_4( check_hyperbolic_functions<double>() );\n    CALL_SUBTEST_5( check_limits_specialization<double>());\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/bessel_functions.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include \"../Eigen/SpecialFunctions\"\n\ntemplate<typename X, typename Y>\nvoid verify_component_wise(const X& x, const Y& y)\n{\n  for(Index i=0; i<x.size(); ++i)\n  {\n    if((numext::isfinite)(y(i))) {\n      VERIFY_IS_APPROX( x(i), y(i) );\n    }\n    else if((numext::isnan)(y(i)))\n      VERIFY((numext::isnan)(x(i)));\n    else\n      VERIFY_IS_EQUAL( x(i), y(i) );\n  }\n}\n\ntemplate<typename ArrayType> void array_bessel_functions() \n{\n  // Test Bessel function i0. Reference results obtained with SciPy.\n  {\n    ArrayType x(21);\n    ArrayType expected(21);\n    ArrayType res(21);\n\n    x << -20.0, -18.0, -16.0, -14.0, -12.0, -10.0, -8.0, -6.0, -4.0, -2.0, 0.0,\n        2.0, 4.0, 6.0, 8.0, 10.0, 12.0, 14.0, 16.0, 18.0, 20.0;\n\n    expected << 4.35582826e+07, 6.21841242e+06, 8.93446228e+05, 1.29418563e+05,\n       1.89489253e+04, 2.81571663e+03, 4.27564116e+02, 6.72344070e+01,\n       1.13019220e+01, 2.27958530e+00, 1.00000000e+00, 2.27958530e+00,\n       1.13019220e+01, 6.72344070e+01, 4.27564116e+02, 2.81571663e+03,\n       1.89489253e+04, 1.29418563e+05, 8.93446228e+05, 6.21841242e+06,\n       4.35582826e+07;\n\n    CALL_SUBTEST(res = bessel_i0(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function i0e. Reference results obtained with SciPy.\n  {\n    ArrayType x(21);\n    ArrayType expected(21);\n    ArrayType res(21);\n\n    x << -20.0, -18.0, -16.0, -14.0, -12.0, -10.0, -8.0, -6.0, -4.0, -2.0, 0.0,\n        2.0, 4.0, 6.0, 8.0, 10.0, 12.0, 14.0, 16.0, 18.0, 20.0;\n\n    expected << 0.0897803118848, 0.0947062952128, 0.100544127361,\n        0.107615251671, 0.116426221213, 0.127833337163, 0.143431781857,\n        0.16665743264, 0.207001921224, 0.308508322554, 1.0, 0.308508322554,\n        0.207001921224, 0.16665743264, 0.143431781857, 0.127833337163,\n        0.116426221213, 0.107615251671, 0.100544127361, 0.0947062952128,\n        0.0897803118848;\n\n    CALL_SUBTEST(res = bessel_i0e(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function i1. Reference results obtained with SciPy.\n  {\n    ArrayType x(21);\n    ArrayType expected(21);\n    ArrayType res(21);\n\n    x << -20.0, -18.0, -16.0, -14.0, -12.0, -10.0, -8.0, -6.0, -4.0, -2.0, 0.0,\n        2.0, 4.0, 6.0, 8.0, 10.0, 12.0, 14.0, 16.0, 18.0, 20.0;\n\n    expected << -4.24549734e+07, -6.04313324e+06, -8.65059436e+05, -1.24707259e+05,\n       -1.81413488e+04, -2.67098830e+03, -3.99873137e+02, -6.13419368e+01,\n       -9.75946515e+00, -1.59063685e+00,  0.00000000e+00,  1.59063685e+00,\n        9.75946515e+00,  6.13419368e+01,  3.99873137e+02,  2.67098830e+03,\n        1.81413488e+04,  1.24707259e+05,  8.65059436e+05,  6.04313324e+06,\n        4.24549734e+07;\n\n    CALL_SUBTEST(res = bessel_i1(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function i1e. Reference results obtained with SciPy.\n  {\n    ArrayType x(21);\n    ArrayType expected(21);\n    ArrayType res(21);\n\n    x << -20.0, -18.0, -16.0, -14.0, -12.0, -10.0, -8.0, -6.0, -4.0, -2.0, 0.0,\n        2.0, 4.0, 6.0, 8.0, 10.0, 12.0, 14.0, 16.0, 18.0, 20.0;\n\n    expected << -0.0875062221833, -0.092036796872, -0.0973496147565,\n        -0.103697667463, -0.11146429929, -0.121262681384, -0.134142493293,\n        -0.152051459309, -0.178750839502, -0.215269289249, 0.0, 0.215269289249,\n        0.178750839502, 0.152051459309, 0.134142493293, 0.121262681384,\n        0.11146429929, 0.103697667463, 0.0973496147565, 0.092036796872,\n        0.0875062221833;\n\n    CALL_SUBTEST(res = bessel_i1e(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function j0. Reference results obtained with SciPy.\n  {\n    ArrayType x(77);\n    ArrayType expected(77);\n    ArrayType res(77);\n\n    x << -38., -37., -36., -35., -34., -33., -32., -31., -30.,\n      -29., -28., -27., -26., -25., -24., -23., -22., -21., -20., -19.,\n      -18., -17., -16., -15., -14., -13., -12., -11., -10.,  -9.,  -8.,\n       -7.,  -6.,  -5.,  -4.,  -3.,  -2.,  -1.,   0.,   1.,   2.,   3.,\n        4.,   5.,   6.,   7.,   8.,   9.,  10.,  11.,  12.,  13.,  14.,\n       15.,  16.,  17.,  18.,  19.,  20.,  21.,  22.,  23.,  24.,  25.,\n       26.,  27.,  28.,  29.,  30.,  31.,  32.,  33.,  34.,  35.,  36.,\n       37.,  38.;\n\n    expected << 0.11433274,  0.01086237, -0.10556738,\n             -0.12684568, -0.03042119,  0.09727067,  0.13807901,  0.05120815,\n             -0.08636798, -0.14784876, -0.07315701,  0.07274192,  0.15599932,\n              0.09626678, -0.05623027, -0.16241278, -0.12065148,  0.03657907,\n              0.16702466,  0.14662944, -0.01335581, -0.16985425, -0.17489907,\n             -0.01422447,  0.17107348,  0.2069261 ,  0.04768931, -0.1711903 ,\n             -0.24593576, -0.09033361,  0.17165081,  0.30007927,  0.15064526,\n             -0.17759677, -0.39714981, -0.26005195,  0.22389078,  0.76519769,\n              1.        ,  0.76519769,  0.22389078, -0.26005195, -0.39714981,\n             -0.17759677,  0.15064526,  0.30007927,  0.17165081, -0.09033361,\n             -0.24593576, -0.1711903 ,  0.04768931,  0.2069261 ,  0.17107348,\n             -0.01422447, -0.17489907, -0.16985425, -0.01335581,  0.14662944,\n              0.16702466,  0.03657907, -0.12065148, -0.16241278, -0.05623027,\n              0.09626678,  0.15599932,  0.07274192, -0.07315701, -0.14784876,\n             -0.08636798,  0.05120815,  0.13807901,  0.09727067, -0.03042119,\n             -0.12684568, -0.10556738,  0.01086237,  0.11433274;\n\n    CALL_SUBTEST(res = bessel_j0(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function j1. Reference results obtained with SciPy.\n  {\n    ArrayType x(81);\n    ArrayType expected(81);\n    ArrayType res(81);\n\n    x << -40., -39., -38., -37., -36., -35., -34., -33., -32., -31., -30.,\n      -29., -28., -27., -26., -25., -24., -23., -22., -21., -20., -19.,\n      -18., -17., -16., -15., -14., -13., -12., -11., -10.,  -9.,  -8.,\n       -7.,  -6.,  -5.,  -4.,  -3.,  -2.,  -1.,   0.,   1.,   2.,   3.,\n        4.,   5.,   6.,   7.,   8.,   9.,  10.,  11.,  12.,  13.,  14.,\n       15.,  16.,  17.,  18.,  19.,  20.,  21.,  22.,  23.,  24.,  25.,\n       26.,  27.,  28.,  29.,  30.,  31.,  32.,  33.,  34.,  35.,  36.,\n       37.,  38.,  39.,  40.;\n\n    expected << -0.12603832, -0.0640561 ,  0.05916189,  0.13058004,  0.08232981,\n             -0.04399094, -0.13297118, -0.10061965,  0.02658903,  0.13302432,\n              0.11875106, -0.0069342 , -0.13055149, -0.13658472, -0.01504573,\n              0.12535025,  0.15403807,  0.03951932, -0.11717779, -0.17112027,\n             -0.06683312,  0.10570143,  0.18799489,  0.09766849, -0.09039718,\n             -0.20510404, -0.13337515,  0.07031805,  0.2234471 ,  0.1767853 ,\n             -0.04347275, -0.24531179, -0.23463635,  0.00468282,  0.27668386,\n              0.32757914,  0.06604333, -0.33905896, -0.57672481, -0.44005059,\n              0.        ,  0.44005059,  0.57672481,  0.33905896, -0.06604333,\n             -0.32757914, -0.27668386, -0.00468282,  0.23463635,  0.24531179,\n              0.04347275, -0.1767853 , -0.2234471 , -0.07031805,  0.13337515,\n              0.20510404,  0.09039718, -0.09766849, -0.18799489, -0.10570143,\n              0.06683312,  0.17112027,  0.11717779, -0.03951932, -0.15403807,\n             -0.12535025,  0.01504573,  0.13658472,  0.13055149,  0.0069342 ,\n             -0.11875106, -0.13302432, -0.02658903,  0.10061965,  0.13297118,\n              0.04399094, -0.08232981, -0.13058004, -0.05916189,  0.0640561 ,\n              0.12603832;\n\n    CALL_SUBTEST(res = bessel_j1(x);\n                 verify_component_wise(res, expected););\n  }\n  // Test Bessel function k0e. Reference results obtained with SciPy.\n  {\n    ArrayType x(42);\n    ArrayType expected(42);\n    ArrayType res(42);\n\n    x << 0.25, 0.5,  1.,  2.,  3.,  4.,  5.,  6.,  7.,  8.,  9., 10., 11., 12.,\n       13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25.,\n       26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36., 37., 38.,\n       39., 40.;\n\n    expected << 1.97933385, 1.52410939, 1.14446308, 0.84156822,\n             0.6977616 , 0.60929767, 0.54780756, 0.50186313, 0.4658451 ,\n             0.43662302, 0.41229555, 0.39163193, 0.3737955 , 0.35819488,\n             0.34439865, 0.33208364, 0.32100235, 0.31096159, 0.30180802,\n             0.29341821, 0.28569149, 0.27854488, 0.2719092 , 0.26572635,\n             0.25994703, 0.25452917, 0.2494366 , 0.24463801, 0.24010616,\n             0.23581722, 0.23175022, 0.22788667, 0.22421014, 0.22070602,\n             0.21736123, 0.21416406, 0.21110397, 0.20817141, 0.20535778,\n             0.20265524, 0.20005668, 0.19755558;\n\n    CALL_SUBTEST(res = bessel_k0e(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function k0. Reference results obtained with SciPy.\n  {\n    ArrayType x(42);\n    ArrayType expected(42);\n    ArrayType res(42);\n\n    x << 0.25, 0.5,  1.,  2.,  3.,  4.,  5.,  6.,  7.,  8.,  9., 10., 11., 12.,\n       13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25.,\n       26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36., 37., 38.,\n       39., 40.;\n\n    expected << 1.54150675, 0.92441907, 4.21024438e-01, 1.13893873e-01,\n             3.47395044e-02, 1.11596761e-02, 3.69109833e-03, 1.24399433e-03,\n             4.24795742e-04, 1.46470705e-04, 5.08813130e-05, 1.77800623e-05,\n             6.24302055e-06, 2.20082540e-06, 7.78454386e-07, 2.76137082e-07,\n             9.81953648e-08, 3.49941166e-08, 1.24946640e-08, 4.46875334e-09,\n             1.60067129e-09, 5.74123782e-10, 2.06176797e-10, 7.41235161e-11,\n             2.66754511e-11, 9.60881878e-12, 3.46416156e-12, 1.24987740e-12,\n             4.51286453e-13, 1.63053459e-13, 5.89495073e-14, 2.13247750e-14,\n             7.71838266e-15, 2.79505752e-15, 1.01266123e-15, 3.67057597e-16,\n             1.33103515e-16, 4.82858338e-17, 1.75232770e-17, 6.36161716e-18,\n             2.31029936e-18, 8.39286110e-19;\n\n    CALL_SUBTEST(res = bessel_k0(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function k0e. Reference results obtained with SciPy.\n  {\n    ArrayType x(42);\n    ArrayType expected(42);\n    ArrayType res(42);\n\n    x << 0.25, 0.5,  1.,  2.,  3.,  4.,  5.,  6.,  7.,  8.,  9., 10., 11., 12.,\n       13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25.,\n       26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36., 37., 38.,\n       39., 40.;\n\n    expected << 1.97933385, 1.52410939, 1.14446308, 0.84156822,\n             0.6977616 , 0.60929767, 0.54780756, 0.50186313,\n             0.4658451 , 0.43662302, 0.41229555, 0.39163193,\n             0.3737955 , 0.35819488, 0.34439865, 0.33208364,\n             0.32100235, 0.31096159, 0.30180802, 0.29341821,\n             0.28569149, 0.27854488, 0.2719092 , 0.26572635,\n             0.25994703, 0.25452917, 0.2494366 , 0.24463801,\n             0.24010616, 0.23581722, 0.23175022, 0.22788667,\n             0.22421014, 0.22070602, 0.21736123, 0.21416406,\n             0.21110397, 0.20817141, 0.20535778, 0.20265524,\n             0.20005668, 0.19755558;\n\n    CALL_SUBTEST(res = bessel_k0e(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function k1. Reference results obtained with SciPy.\n  {\n    ArrayType x(42);\n    ArrayType expected(42);\n    ArrayType res(42);\n\n    x << 0.25, 0.5,  1.,  2.,  3.,  4.,  5.,  6.,  7.,  8.,  9., 10., 11., 12.,\n       13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25.,\n       26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36., 37., 38.,\n       39., 40.;\n\n    expected << 3.74702597, 1.65644112, 6.01907230e-01, 1.39865882e-01,\n             4.01564311e-02, 1.24834989e-02, 4.04461345e-03, 1.34391972e-03,\n             4.54182487e-04, 1.55369212e-04, 5.36370164e-05, 1.86487735e-05,\n             6.52086067e-06, 2.29075746e-06, 8.07858841e-07, 2.85834365e-07,\n             1.01417294e-07, 3.60715712e-08, 1.28570417e-08, 4.59124963e-09,\n             1.64226697e-09, 5.88305797e-10, 2.11029922e-10, 7.57898116e-11,\n             2.72493059e-11, 9.80699893e-12, 3.53277807e-12, 1.27369078e-12,\n             4.59568940e-13, 1.65940011e-13, 5.99574032e-14, 2.16773200e-14,\n             7.84189960e-15, 2.83839927e-15, 1.02789171e-15, 3.72416929e-16,\n             1.34991783e-16, 4.89519373e-17, 1.77585196e-17, 6.44478588e-18,\n             2.33973340e-18, 8.49713195e-19;\n\n    CALL_SUBTEST(res = bessel_k1(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function k1e. Reference results obtained with SciPy.\n  {\n    ArrayType x(42);\n    ArrayType expected(42);\n    ArrayType res(42);\n\n    x << 0.25, 0.5,  1.,  2.,  3.,  4.,  5.,  6.,  7.,  8.,  9., 10., 11., 12.,\n       13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25.,\n       26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36., 37., 38.,\n       39., 40.;\n\n    expected << 4.81127659, 2.73100971, 1.63615349, 1.03347685,\n             0.80656348, 0.68157595, 0.60027386, 0.54217591,\n             0.49807158, 0.46314909, 0.43462525, 0.41076657,\n             0.39043094, 0.37283175, 0.35740757, 0.34374563,\n             0.33153489, 0.32053597, 0.31056123, 0.30146131,\n             0.29311559, 0.2854255 , 0.27830958, 0.27169987,\n             0.26553913, 0.25977879, 0.25437733, 0.249299  ,\n             0.24451285, 0.23999191, 0.2357126 , 0.23165413,\n             0.22779816, 0.22412841, 0.22063036, 0.21729103,\n             0.21409878, 0.21104314, 0.20811462, 0.20530466,\n             0.20260547, 0.20000997;\n\n    CALL_SUBTEST(res = bessel_k1e(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function y0. Reference results obtained with SciPy.\n  {\n    ArrayType x(42);\n    ArrayType expected(42);\n    ArrayType res(42);\n\n    x << 0.25, 0.5,  1.,  2.,  3.,  4.,  5.,  6.,  7.,  8.,  9., 10., 11., 12.,\n       13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25.,\n       26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36., 37., 38.,\n       39., 40.;\n\n    expected << -0.93157302, -0.44451873, 0.08825696,  0.51037567,  0.37685001,\n             -0.01694074, -0.30851763, -0.28819468, -0.02594974,  0.22352149,\n             0.2499367 ,  0.05567117, -0.16884732, -0.22523731, -0.07820786,\n             0.12719257,  0.2054643 , 0.095811  , -0.0926372 , -0.18755216,\n             -0.10951969,  0.0626406 , 0.17020176,  0.1198876 , -0.03598179,\n             -0.15283403, -0.12724943, 0.01204463,  0.13521498,  0.13183647,\n             0.00948116, -0.11729573, -0.13383266, -0.02874248,  0.09913483,\n             0.13340405,  0.04579799, -0.08085609, -0.13071488, -0.06066076,\n             0.06262353,  0.12593642;\n\n    CALL_SUBTEST(res = bessel_y0(x);\n                 verify_component_wise(res, expected););\n  }\n\n  // Test Bessel function y1. Reference results obtained with SciPy.\n  {\n    ArrayType x(42);\n    ArrayType expected(42);\n    ArrayType res(42);\n\n    x << 0.25, 0.5,  1.,  2.,  3.,  4.,  5.,  6.,  7.,  8.,  9., 10., 11., 12.,\n       13., 14., 15., 16., 17., 18., 19., 20., 21., 22., 23., 24., 25.,\n       26., 27., 28., 29., 30., 31., 32., 33., 34., 35., 36., 37., 38.,\n       39., 40.;\n\n    expected << -2.70410523, -1.47147239, -0.78121282, -0.10703243,\n             0.32467442,  0.39792571,  0.14786314, -0.17501034, -0.30266724,\n             -0.15806046,  0.10431458,  0.24901542, 0.16370554, -0.05709922,\n             -0.21008141, -0.16664484,  0.02107363, 0.17797517,  0.16720504,\n             0.00815513, -0.14956011, -0.16551161, -0.03253926,  0.12340586,\n             0.1616692 ,  0.05305978, -0.09882996, -0.15579655, -0.07025124,\n             0.07552213,  0.14803412,  0.08442557, -0.05337283, -0.13854483,\n             -0.09578012,  0.03238588,  0.12751273, 0.10445477, -0.01262946,\n             -0.11514066, -0.11056411, -0.00579351;\n\n    CALL_SUBTEST(res = bessel_y1(x);\n                 verify_component_wise(res, expected););\n  }\n}\n\nEIGEN_DECLARE_TEST(bessel_functions)\n{\n  CALL_SUBTEST_1(array_bessel_functions<ArrayXf>());\n  CALL_SUBTEST_2(array_bessel_functions<ArrayXd>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_eventcount.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Dmitry Vyukov <dvyukov@google.com>\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_USE_THREADS\n#include \"main.h\"\n#include <Eigen/CXX11/ThreadPool>\n\n// Visual studio doesn't implement a rand_r() function since its\n// implementation of rand() is already thread safe\nint rand_reentrant(unsigned int* s) {\n#ifdef EIGEN_COMP_MSVC_STRICT\n  EIGEN_UNUSED_VARIABLE(s);\n  return rand();\n#else\n  return rand_r(s);\n#endif\n}\n\nstatic void test_basic_eventcount()\n{\n  MaxSizeVector<EventCount::Waiter> waiters(1);\n  waiters.resize(1);\n  EventCount ec(waiters);\n  EventCount::Waiter& w = waiters[0];\n  ec.Notify(false);\n  ec.Prewait();\n  ec.Notify(true);\n  ec.CommitWait(&w);\n  ec.Prewait();\n  ec.CancelWait();\n}\n\n// Fake bounded counter-based queue.\nstruct TestQueue {\n  std::atomic<int> val_;\n  static const int kQueueSize = 10;\n\n  TestQueue() : val_() {}\n\n  ~TestQueue() { VERIFY_IS_EQUAL(val_.load(), 0); }\n\n  bool Push() {\n    int val = val_.load(std::memory_order_relaxed);\n    for (;;) {\n      VERIFY_GE(val, 0);\n      VERIFY_LE(val, kQueueSize);\n      if (val == kQueueSize) return false;\n      if (val_.compare_exchange_weak(val, val + 1, std::memory_order_relaxed))\n        return true;\n    }\n  }\n\n  bool Pop() {\n    int val = val_.load(std::memory_order_relaxed);\n    for (;;) {\n      VERIFY_GE(val, 0);\n      VERIFY_LE(val, kQueueSize);\n      if (val == 0) return false;\n      if (val_.compare_exchange_weak(val, val - 1, std::memory_order_relaxed))\n        return true;\n    }\n  }\n\n  bool Empty() { return val_.load(std::memory_order_relaxed) == 0; }\n};\n\nconst int TestQueue::kQueueSize;\n\n// A number of producers send messages to a set of consumers using a set of\n// fake queues. Ensure that it does not crash, consumers don't deadlock and\n// number of blocked and unblocked threads match.\nstatic void test_stress_eventcount()\n{\n  const int kThreads = std::thread::hardware_concurrency();\n  static const int kEvents = 1 << 16;\n  static const int kQueues = 10;\n\n  MaxSizeVector<EventCount::Waiter> waiters(kThreads);\n  waiters.resize(kThreads);\n  EventCount ec(waiters);\n  TestQueue queues[kQueues];\n\n  std::vector<std::unique_ptr<std::thread>> producers;\n  for (int i = 0; i < kThreads; i++) {\n    producers.emplace_back(new std::thread([&ec, &queues]() {\n      unsigned int rnd = static_cast<unsigned int>(std::hash<std::thread::id>()(std::this_thread::get_id()));\n      for (int j = 0; j < kEvents; j++) {\n        unsigned idx = rand_reentrant(&rnd) % kQueues;\n        if (queues[idx].Push()) {\n          ec.Notify(false);\n          continue;\n        }\n        EIGEN_THREAD_YIELD();\n        j--;\n      }\n    }));\n  }\n\n  std::vector<std::unique_ptr<std::thread>> consumers;\n  for (int i = 0; i < kThreads; i++) {\n    consumers.emplace_back(new std::thread([&ec, &queues, &waiters, i]() {\n      EventCount::Waiter& w = waiters[i];\n      unsigned int rnd = static_cast<unsigned int>(std::hash<std::thread::id>()(std::this_thread::get_id()));\n      for (int j = 0; j < kEvents; j++) {\n        unsigned idx = rand_reentrant(&rnd) % kQueues;\n        if (queues[idx].Pop()) continue;\n        j--;\n        ec.Prewait();\n        bool empty = true;\n        for (int q = 0; q < kQueues; q++) {\n          if (!queues[q].Empty()) {\n            empty = false;\n            break;\n          }\n        }\n        if (!empty) {\n          ec.CancelWait();\n          continue;\n        }\n        ec.CommitWait(&w);\n      }\n    }));\n  }\n\n  for (int i = 0; i < kThreads; i++) {\n    producers[i]->join();\n    consumers[i]->join();\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_eventcount)\n{\n  CALL_SUBTEST(test_basic_eventcount());\n  CALL_SUBTEST(test_stress_eventcount());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_maxsizevector.cpp",
    "content": "#include \"main.h\"\n\n#include <exception>  // std::exception\n\n#include <unsupported/Eigen/CXX11/Tensor>\n\nstruct Foo\n{\n  static Index object_count;\n  static Index object_limit;\n  EIGEN_ALIGN_TO_BOUNDARY(128) int dummy;\n\n  Foo(int x=0) : dummy(x)\n  {\n#ifdef EIGEN_EXCEPTIONS\n    // TODO: Is this the correct way to handle this?\n    if (Foo::object_count > Foo::object_limit) { std::cout << \"\\nThrow!\\n\"; throw Foo::Fail(); }\n#endif\n    std::cout << '+';\n    ++Foo::object_count;\n    eigen_assert((internal::UIntPtr(this) & (127)) == 0);\n  }\n  Foo(const Foo&)\n  {\n    std::cout << 'c';\n    ++Foo::object_count;\n    eigen_assert((internal::UIntPtr(this) & (127)) == 0);\n  }\n\n  ~Foo()\n  {\n    std::cout << '~';\n    --Foo::object_count;\n  }\n\n  class Fail : public std::exception {};\n};\n\nIndex Foo::object_count = 0;\nIndex Foo::object_limit = 0;\n\n\n\nEIGEN_DECLARE_TEST(cxx11_maxsizevector)\n{\n  typedef MaxSizeVector<Foo> VectorX;\n  Foo::object_count = 0;\n  for(int r = 0; r < g_repeat; r++) {\n    Index rows = internal::random<Index>(3,30);\n    Foo::object_limit = internal::random<Index>(0, rows - 2);\n    std::cout << \"object_limit = \" << Foo::object_limit << std::endl;\n    bool exception_raised = false;\n#ifdef EIGEN_EXCEPTIONS\n    try\n    {\n#endif\n      std::cout <<       \"\\nVectorX m(\" << rows << \");\\n\";\n      VectorX vect(rows);\n      for(int i=0; i<rows; ++i)\n          vect.push_back(Foo());\n#ifdef EIGEN_EXCEPTIONS\n      VERIFY(false);  // not reached if exceptions are enabled\n    }\n    catch (const Foo::Fail&) { exception_raised = true; }\n    VERIFY(exception_raised);\n#endif\n    VERIFY_IS_EQUAL(Index(0), Foo::object_count);\n\n    {\n      Foo::object_limit = rows+1;\n      VectorX vect2(rows, Foo());\n      VERIFY_IS_EQUAL(Foo::object_count, rows);\n    }\n    VERIFY_IS_EQUAL(Index(0), Foo::object_count);\n    std::cout << '\\n';\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_meta.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <array>\n#include <Eigen/CXX11/src/util/CXX11Meta.h>\n\nusing Eigen::internal::is_same;\nusing Eigen::internal::type_list;\nusing Eigen::internal::numeric_list;\nusing Eigen::internal::gen_numeric_list;\nusing Eigen::internal::gen_numeric_list_reversed;\nusing Eigen::internal::gen_numeric_list_swapped_pair;\nusing Eigen::internal::gen_numeric_list_repeated;\nusing Eigen::internal::concat;\nusing Eigen::internal::mconcat;\nusing Eigen::internal::take;\nusing Eigen::internal::skip;\nusing Eigen::internal::slice;\nusing Eigen::internal::get;\nusing Eigen::internal::id_numeric;\nusing Eigen::internal::id_type;\nusing Eigen::internal::is_same_gf;\nusing Eigen::internal::apply_op_from_left;\nusing Eigen::internal::apply_op_from_right;\nusing Eigen::internal::contained_in_list;\nusing Eigen::internal::contained_in_list_gf;\nusing Eigen::internal::arg_prod;\nusing Eigen::internal::arg_sum;\nusing Eigen::internal::sum_op;\nusing Eigen::internal::product_op;\nusing Eigen::internal::array_reverse;\nusing Eigen::internal::array_sum;\nusing Eigen::internal::array_prod;\nusing Eigen::internal::array_reduce;\nusing Eigen::internal::array_zip;\nusing Eigen::internal::array_zip_and_reduce;\nusing Eigen::internal::array_apply;\nusing Eigen::internal::array_apply_and_reduce;\nusing Eigen::internal::repeat;\nusing Eigen::internal::instantiate_by_c_array;\n\nstruct dummy_a {};\nstruct dummy_b {};\nstruct dummy_c {};\nstruct dummy_d {};\nstruct dummy_e {};\n\n// dummy operation for testing apply\ntemplate<typename A, typename B> struct dummy_op;\ntemplate<> struct dummy_op<dummy_a, dummy_b> { typedef dummy_c type; };\ntemplate<> struct dummy_op<dummy_b, dummy_a> { typedef dummy_d type; };\ntemplate<> struct dummy_op<dummy_b, dummy_c> { typedef dummy_a type; };\ntemplate<> struct dummy_op<dummy_c, dummy_b> { typedef dummy_d type; };\ntemplate<> struct dummy_op<dummy_c, dummy_a> { typedef dummy_b type; };\ntemplate<> struct dummy_op<dummy_a, dummy_c> { typedef dummy_d type; };\ntemplate<> struct dummy_op<dummy_a, dummy_a> { typedef dummy_e type; };\ntemplate<> struct dummy_op<dummy_b, dummy_b> { typedef dummy_e type; };\ntemplate<> struct dummy_op<dummy_c, dummy_c> { typedef dummy_e type; };\n\ntemplate<typename A, typename B> struct dummy_test { constexpr static bool value = false; constexpr static int global_flags = 0; };\ntemplate<> struct dummy_test<dummy_a, dummy_a>     { constexpr static bool value = true;  constexpr static int global_flags = 1; };\ntemplate<> struct dummy_test<dummy_b, dummy_b>     { constexpr static bool value = true;  constexpr static int global_flags = 2; };\ntemplate<> struct dummy_test<dummy_c, dummy_c>     { constexpr static bool value = true;  constexpr static int global_flags = 4; };\n\nstruct times2_op { template<typename A> static A run(A v) { return v * 2; } };\n\nstruct dummy_inst\n{\n  int c;\n\n  dummy_inst() : c(0) {}\n  explicit dummy_inst(int) : c(1) {}\n  dummy_inst(int, int) : c(2) {}\n  dummy_inst(int, int, int) : c(3) {}\n  dummy_inst(int, int, int, int) : c(4) {}\n  dummy_inst(int, int, int, int, int) : c(5) {}\n};\n\nstatic void test_gen_numeric_list()\n{\n  VERIFY((is_same<typename gen_numeric_list<int, 0>::type, numeric_list<int>>::value));\n  VERIFY((is_same<typename gen_numeric_list<int, 1>::type, numeric_list<int, 0>>::value));\n  VERIFY((is_same<typename gen_numeric_list<int, 2>::type, numeric_list<int, 0, 1>>::value));\n  VERIFY((is_same<typename gen_numeric_list<int, 5>::type, numeric_list<int, 0, 1, 2, 3, 4>>::value));\n  VERIFY((is_same<typename gen_numeric_list<int, 10>::type, numeric_list<int, 0, 1, 2, 3, 4, 5, 6, 7, 8, 9>>::value));\n\n  VERIFY((is_same<typename gen_numeric_list<int, 0, 42>::type, numeric_list<int>>::value));\n  VERIFY((is_same<typename gen_numeric_list<int, 1, 42>::type, numeric_list<int, 42>>::value));\n  VERIFY((is_same<typename gen_numeric_list<int, 2, 42>::type, numeric_list<int, 42, 43>>::value));\n  VERIFY((is_same<typename gen_numeric_list<int, 5, 42>::type, numeric_list<int, 42, 43, 44, 45, 46>>::value));\n  VERIFY((is_same<typename gen_numeric_list<int, 10, 42>::type, numeric_list<int, 42, 43, 44, 45, 46, 47, 48, 49, 50, 51>>::value));\n\n  VERIFY((is_same<typename gen_numeric_list_reversed<int, 0>::type, numeric_list<int>>::value));\n  VERIFY((is_same<typename gen_numeric_list_reversed<int, 1>::type, numeric_list<int, 0>>::value));\n  VERIFY((is_same<typename gen_numeric_list_reversed<int, 2>::type, numeric_list<int, 1, 0>>::value));\n  VERIFY((is_same<typename gen_numeric_list_reversed<int, 5>::type, numeric_list<int, 4, 3, 2, 1, 0>>::value));\n  VERIFY((is_same<typename gen_numeric_list_reversed<int, 10>::type, numeric_list<int, 9, 8, 7, 6, 5, 4, 3, 2, 1, 0>>::value));\n\n  VERIFY((is_same<typename gen_numeric_list_reversed<int, 0, 42>::type, numeric_list<int>>::value));\n  VERIFY((is_same<typename gen_numeric_list_reversed<int, 1, 42>::type, numeric_list<int, 42>>::value));\n  VERIFY((is_same<typename gen_numeric_list_reversed<int, 2, 42>::type, numeric_list<int, 43, 42>>::value));\n  VERIFY((is_same<typename gen_numeric_list_reversed<int, 5, 42>::type, numeric_list<int, 46, 45, 44, 43, 42>>::value));\n  VERIFY((is_same<typename gen_numeric_list_reversed<int, 10, 42>::type, numeric_list<int, 51, 50, 49, 48, 47, 46, 45, 44, 43, 42>>::value));\n\n  VERIFY((is_same<typename gen_numeric_list_swapped_pair<int, 0, 2, 3>::type, numeric_list<int>>::value));\n  VERIFY((is_same<typename gen_numeric_list_swapped_pair<int, 1, 2, 3>::type, numeric_list<int, 0>>::value));\n  VERIFY((is_same<typename gen_numeric_list_swapped_pair<int, 2, 2, 3>::type, numeric_list<int, 0, 1>>::value));\n  VERIFY((is_same<typename gen_numeric_list_swapped_pair<int, 5, 2, 3>::type, numeric_list<int, 0, 1, 3, 2, 4>>::value));\n  VERIFY((is_same<typename gen_numeric_list_swapped_pair<int, 10, 2, 3>::type, numeric_list<int, 0, 1, 3, 2, 4, 5, 6, 7, 8, 9>>::value));\n\n  VERIFY((is_same<typename gen_numeric_list_swapped_pair<int, 0, 44, 45, 42>::type, numeric_list<int>>::value));\n  VERIFY((is_same<typename gen_numeric_list_swapped_pair<int, 1, 44, 45, 42>::type, numeric_list<int, 42>>::value));\n  VERIFY((is_same<typename gen_numeric_list_swapped_pair<int, 2, 44, 45, 42>::type, numeric_list<int, 42, 43>>::value));\n  VERIFY((is_same<typename gen_numeric_list_swapped_pair<int, 5, 44, 45, 42>::type, numeric_list<int, 42, 43, 45, 44, 46>>::value));\n  VERIFY((is_same<typename gen_numeric_list_swapped_pair<int, 10, 44, 45, 42>::type, numeric_list<int, 42, 43, 45, 44, 46, 47, 48, 49, 50, 51>>::value));\n\n  VERIFY((is_same<typename gen_numeric_list_repeated<int, 0, 0>::type, numeric_list<int>>::value));\n  VERIFY((is_same<typename gen_numeric_list_repeated<int, 1, 0>::type, numeric_list<int, 0>>::value));\n  VERIFY((is_same<typename gen_numeric_list_repeated<int, 2, 0>::type, numeric_list<int, 0, 0>>::value));\n  VERIFY((is_same<typename gen_numeric_list_repeated<int, 5, 0>::type, numeric_list<int, 0, 0, 0, 0, 0>>::value));\n  VERIFY((is_same<typename gen_numeric_list_repeated<int, 10, 0>::type, numeric_list<int, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0>>::value));\n}\n\nstatic void test_concat()\n{\n  VERIFY((is_same<typename concat<type_list<dummy_a, dummy_a>, type_list<>>::type, type_list<dummy_a, dummy_a>>::value));\n  VERIFY((is_same<typename concat<type_list<>, type_list<dummy_a, dummy_a>>::type, type_list<dummy_a, dummy_a>>::value));\n  VERIFY((is_same<typename concat<type_list<dummy_a, dummy_a>, type_list<dummy_a, dummy_a>>::type, type_list<dummy_a, dummy_a, dummy_a, dummy_a>>::value));\n  VERIFY((is_same<typename concat<type_list<dummy_a, dummy_a>, type_list<dummy_b, dummy_c>>::type, type_list<dummy_a, dummy_a, dummy_b, dummy_c>>::value));\n  VERIFY((is_same<typename concat<type_list<dummy_a>, type_list<dummy_b, dummy_c>>::type, type_list<dummy_a, dummy_b, dummy_c>>::value));\n\n  VERIFY((is_same<typename concat<numeric_list<int, 0, 0>, numeric_list<int>>::type, numeric_list<int, 0, 0>>::value));\n  VERIFY((is_same<typename concat<numeric_list<int>, numeric_list<int, 0, 0>>::type, numeric_list<int, 0, 0>>::value));\n  VERIFY((is_same<typename concat<numeric_list<int, 0, 0>, numeric_list<int, 0, 0>>::type, numeric_list<int, 0, 0, 0, 0>>::value));\n  VERIFY((is_same<typename concat<numeric_list<int, 0, 0>, numeric_list<int, 1, 2>>::type, numeric_list<int, 0, 0, 1, 2>>::value));\n  VERIFY((is_same<typename concat<numeric_list<int, 0>, numeric_list<int, 1, 2>>::type, numeric_list<int, 0, 1, 2>>::value));\n\n  VERIFY((is_same<typename mconcat<type_list<dummy_a>>::type, type_list<dummy_a>>::value));\n  VERIFY((is_same<typename mconcat<type_list<dummy_a>, type_list<dummy_b>>::type, type_list<dummy_a, dummy_b>>::value));\n  VERIFY((is_same<typename mconcat<type_list<dummy_a>, type_list<dummy_b>, type_list<dummy_c>>::type, type_list<dummy_a, dummy_b, dummy_c>>::value));\n  VERIFY((is_same<typename mconcat<type_list<dummy_a>, type_list<dummy_b, dummy_c>>::type, type_list<dummy_a, dummy_b, dummy_c>>::value));\n  VERIFY((is_same<typename mconcat<type_list<dummy_a, dummy_b>, type_list<dummy_c>>::type, type_list<dummy_a, dummy_b, dummy_c>>::value));\n\n  VERIFY((is_same<typename mconcat<numeric_list<int, 0>>::type, numeric_list<int, 0>>::value));\n  VERIFY((is_same<typename mconcat<numeric_list<int, 0>, numeric_list<int, 1>>::type, numeric_list<int, 0, 1>>::value));\n  VERIFY((is_same<typename mconcat<numeric_list<int, 0>, numeric_list<int, 1>, numeric_list<int, 2>>::type, numeric_list<int, 0, 1, 2>>::value));\n  VERIFY((is_same<typename mconcat<numeric_list<int, 0>, numeric_list<int, 1, 2>>::type, numeric_list<int, 0, 1, 2>>::value));\n  VERIFY((is_same<typename mconcat<numeric_list<int, 0, 1>, numeric_list<int, 2>>::type, numeric_list<int, 0, 1, 2>>::value));\n}\n\nstatic void test_slice()\n{\n  typedef type_list<dummy_a, dummy_a, dummy_b, dummy_b, dummy_c, dummy_c> tl;\n  typedef numeric_list<int, 0, 1, 2, 3, 4, 5> il;\n\n  VERIFY((is_same<typename take<0, tl>::type, type_list<>>::value));\n  VERIFY((is_same<typename take<1, tl>::type, type_list<dummy_a>>::value));\n  VERIFY((is_same<typename take<2, tl>::type, type_list<dummy_a, dummy_a>>::value));\n  VERIFY((is_same<typename take<3, tl>::type, type_list<dummy_a, dummy_a, dummy_b>>::value));\n  VERIFY((is_same<typename take<4, tl>::type, type_list<dummy_a, dummy_a, dummy_b, dummy_b>>::value));\n  VERIFY((is_same<typename take<5, tl>::type, type_list<dummy_a, dummy_a, dummy_b, dummy_b, dummy_c>>::value));\n  VERIFY((is_same<typename take<6, tl>::type, type_list<dummy_a, dummy_a, dummy_b, dummy_b, dummy_c, dummy_c>>::value));\n\n  VERIFY((is_same<typename take<0, il>::type, numeric_list<int>>::value));\n  VERIFY((is_same<typename take<1, il>::type, numeric_list<int, 0>>::value));\n  VERIFY((is_same<typename take<2, il>::type, numeric_list<int, 0, 1>>::value));\n  VERIFY((is_same<typename take<3, il>::type, numeric_list<int, 0, 1, 2>>::value));\n  VERIFY((is_same<typename take<4, il>::type, numeric_list<int, 0, 1, 2, 3>>::value));\n  VERIFY((is_same<typename take<5, il>::type, numeric_list<int, 0, 1, 2, 3, 4>>::value));\n  VERIFY((is_same<typename take<6, il>::type, numeric_list<int, 0, 1, 2, 3, 4, 5>>::value));\n  \n  VERIFY((is_same<typename skip<0, tl>::type, type_list<dummy_a, dummy_a, dummy_b, dummy_b, dummy_c, dummy_c>>::value));\n  VERIFY((is_same<typename skip<1, tl>::type, type_list<dummy_a, dummy_b, dummy_b, dummy_c, dummy_c>>::value));\n  VERIFY((is_same<typename skip<2, tl>::type, type_list<dummy_b, dummy_b, dummy_c, dummy_c>>::value));\n  VERIFY((is_same<typename skip<3, tl>::type, type_list<dummy_b, dummy_c, dummy_c>>::value));\n  VERIFY((is_same<typename skip<4, tl>::type, type_list<dummy_c, dummy_c>>::value));\n  VERIFY((is_same<typename skip<5, tl>::type, type_list<dummy_c>>::value));\n  VERIFY((is_same<typename skip<6, tl>::type, type_list<>>::value));\n\n  VERIFY((is_same<typename skip<0, il>::type, numeric_list<int, 0, 1, 2, 3, 4, 5>>::value));\n  VERIFY((is_same<typename skip<1, il>::type, numeric_list<int, 1, 2, 3, 4, 5>>::value));\n  VERIFY((is_same<typename skip<2, il>::type, numeric_list<int, 2, 3, 4, 5>>::value));\n  VERIFY((is_same<typename skip<3, il>::type, numeric_list<int, 3, 4, 5>>::value));\n  VERIFY((is_same<typename skip<4, il>::type, numeric_list<int, 4, 5>>::value));\n  VERIFY((is_same<typename skip<5, il>::type, numeric_list<int, 5>>::value));\n  VERIFY((is_same<typename skip<6, il>::type, numeric_list<int>>::value));\n\n  VERIFY((is_same<typename slice<0, 3, tl>::type, typename take<3, tl>::type>::value));\n  VERIFY((is_same<typename slice<0, 3, il>::type, typename take<3, il>::type>::value));\n  VERIFY((is_same<typename slice<1, 3, tl>::type, type_list<dummy_a, dummy_b, dummy_b>>::value));\n  VERIFY((is_same<typename slice<1, 3, il>::type, numeric_list<int, 1, 2, 3>>::value));\n}\n\nstatic void test_get()\n{\n  typedef type_list<dummy_a, dummy_a, dummy_b, dummy_b, dummy_c, dummy_c> tl;\n  typedef numeric_list<int, 4, 8, 15, 16, 23, 42> il;\n\n  VERIFY((is_same<typename get<0, tl>::type, dummy_a>::value));\n  VERIFY((is_same<typename get<1, tl>::type, dummy_a>::value));\n  VERIFY((is_same<typename get<2, tl>::type, dummy_b>::value));\n  VERIFY((is_same<typename get<3, tl>::type, dummy_b>::value));\n  VERIFY((is_same<typename get<4, tl>::type, dummy_c>::value));\n  VERIFY((is_same<typename get<5, tl>::type, dummy_c>::value));\n\n  VERIFY_IS_EQUAL(((int)get<0, il>::value), 4);\n  VERIFY_IS_EQUAL(((int)get<1, il>::value), 8);\n  VERIFY_IS_EQUAL(((int)get<2, il>::value), 15);\n  VERIFY_IS_EQUAL(((int)get<3, il>::value), 16);\n  VERIFY_IS_EQUAL(((int)get<4, il>::value), 23);\n  VERIFY_IS_EQUAL(((int)get<5, il>::value), 42);\n}\n\nstatic void test_id_helper(dummy_a a, dummy_a b, dummy_a c)\n{\n  (void)a;\n  (void)b;\n  (void)c;\n}\n\ntemplate<int... ii>\nstatic void test_id_numeric()\n{\n  test_id_helper(typename id_numeric<int, ii, dummy_a>::type()...);\n}\n\ntemplate<typename... tt>\nstatic void test_id_type()\n{\n  test_id_helper(typename id_type<tt, dummy_a>::type()...);\n}\n\nstatic void test_id()\n{\n  // don't call VERIFY here, just assume it works if it compiles\n  // (otherwise it will complain that it can't find the function)\n  test_id_numeric<1, 4, 6>();\n  test_id_type<dummy_a, dummy_b, dummy_c>();\n}\n\nstatic void test_is_same_gf()\n{\n  VERIFY((!is_same_gf<dummy_a, dummy_b>::value));\n  VERIFY((!!is_same_gf<dummy_a, dummy_a>::value));\n  VERIFY_IS_EQUAL((!!is_same_gf<dummy_a, dummy_b>::global_flags), false);\n  VERIFY_IS_EQUAL((!!is_same_gf<dummy_a, dummy_a>::global_flags), false);\n}\n\nstatic void test_apply_op()\n{\n  typedef type_list<dummy_a, dummy_b, dummy_c> tl;\n  VERIFY((!!is_same<typename apply_op_from_left<dummy_op, dummy_a, tl>::type, type_list<dummy_e, dummy_c, dummy_d>>::value));\n  VERIFY((!!is_same<typename apply_op_from_right<dummy_op, dummy_a, tl>::type, type_list<dummy_e, dummy_d, dummy_b>>::value));\n}\n\nstatic void test_contained_in_list()\n{\n  typedef type_list<dummy_a, dummy_b, dummy_c> tl;\n\n  VERIFY((!!contained_in_list<is_same, dummy_a, tl>::value));\n  VERIFY((!!contained_in_list<is_same, dummy_b, tl>::value));\n  VERIFY((!!contained_in_list<is_same, dummy_c, tl>::value));\n  VERIFY((!contained_in_list<is_same, dummy_d, tl>::value));\n  VERIFY((!contained_in_list<is_same, dummy_e, tl>::value));\n\n  VERIFY((!!contained_in_list_gf<dummy_test, dummy_a, tl>::value));\n  VERIFY((!!contained_in_list_gf<dummy_test, dummy_b, tl>::value));\n  VERIFY((!!contained_in_list_gf<dummy_test, dummy_c, tl>::value));\n  VERIFY((!contained_in_list_gf<dummy_test, dummy_d, tl>::value));\n  VERIFY((!contained_in_list_gf<dummy_test, dummy_e, tl>::value));\n\n  VERIFY_IS_EQUAL(((int)contained_in_list_gf<dummy_test, dummy_a, tl>::global_flags), 1);\n  VERIFY_IS_EQUAL(((int)contained_in_list_gf<dummy_test, dummy_b, tl>::global_flags), 2);\n  VERIFY_IS_EQUAL(((int)contained_in_list_gf<dummy_test, dummy_c, tl>::global_flags), 4);\n  VERIFY_IS_EQUAL(((int)contained_in_list_gf<dummy_test, dummy_d, tl>::global_flags), 0);\n  VERIFY_IS_EQUAL(((int)contained_in_list_gf<dummy_test, dummy_e, tl>::global_flags), 0);\n}\n\nstatic void test_arg_reductions()\n{\n  VERIFY_IS_EQUAL(arg_sum(1,2,3,4), 10);\n  VERIFY_IS_EQUAL(arg_prod(1,2,3,4), 24);\n  VERIFY_IS_APPROX(arg_sum(0.5, 2, 5), 7.5);\n  VERIFY_IS_APPROX(arg_prod(0.5, 2, 5), 5.0);\n}\n\nstatic void test_array_reverse_and_reduce()\n{\n  array<int, 6> a{{4, 8, 15, 16, 23, 42}};\n  array<int, 6> b{{42, 23, 16, 15, 8, 4}};\n\n  // there is no operator<< for std::array, so VERIFY_IS_EQUAL will\n  // not compile\n  VERIFY((array_reverse(a) == b));\n  VERIFY((array_reverse(b) == a));\n  VERIFY_IS_EQUAL((array_sum(a)), 108);\n  VERIFY_IS_EQUAL((array_sum(b)), 108);\n  VERIFY_IS_EQUAL((array_prod(a)), 7418880);\n  VERIFY_IS_EQUAL((array_prod(b)), 7418880);\n}\n\nstatic void test_array_zip_and_apply()\n{\n  array<int, 6> a{{4, 8, 15, 16, 23, 42}};\n  array<int, 6> b{{0, 1, 2, 3, 4, 5}};\n  array<int, 6> c{{4, 9, 17, 19, 27, 47}};\n  array<int, 6> d{{0, 8, 30, 48, 92, 210}};\n  array<int, 6> e{{0, 2, 4, 6, 8, 10}};\n\n  VERIFY((array_zip<sum_op>(a, b) == c));\n  VERIFY((array_zip<product_op>(a, b) == d));\n  VERIFY((array_apply<times2_op>(b) == e));\n  VERIFY_IS_EQUAL((array_apply_and_reduce<sum_op, times2_op>(a)), 216);\n  VERIFY_IS_EQUAL((array_apply_and_reduce<sum_op, times2_op>(b)), 30);\n  VERIFY_IS_EQUAL((array_zip_and_reduce<product_op, sum_op>(a, b)), 14755932);\n  VERIFY_IS_EQUAL((array_zip_and_reduce<sum_op, product_op>(a, b)), 388);\n}\n\nstatic void test_array_misc()\n{\n  array<int, 3> a3{{1, 1, 1}};\n  array<int, 6> a6{{2, 2, 2, 2, 2, 2}};\n  VERIFY((repeat<3, int>(1) == a3));\n  VERIFY((repeat<6, int>(2) == a6));\n\n  int data[5] = { 0, 1, 2, 3, 4 };\n  VERIFY_IS_EQUAL((instantiate_by_c_array<dummy_inst, int, 0>(data).c), 0);\n  VERIFY_IS_EQUAL((instantiate_by_c_array<dummy_inst, int, 1>(data).c), 1);\n  VERIFY_IS_EQUAL((instantiate_by_c_array<dummy_inst, int, 2>(data).c), 2);\n  VERIFY_IS_EQUAL((instantiate_by_c_array<dummy_inst, int, 3>(data).c), 3);\n  VERIFY_IS_EQUAL((instantiate_by_c_array<dummy_inst, int, 4>(data).c), 4);\n  VERIFY_IS_EQUAL((instantiate_by_c_array<dummy_inst, int, 5>(data).c), 5);\n}\n\nEIGEN_DECLARE_TEST(cxx11_meta)\n{\n  CALL_SUBTEST(test_gen_numeric_list());\n  CALL_SUBTEST(test_concat());\n  CALL_SUBTEST(test_slice());\n  CALL_SUBTEST(test_get());\n  CALL_SUBTEST(test_id());\n  CALL_SUBTEST(test_is_same_gf());\n  CALL_SUBTEST(test_apply_op());\n  CALL_SUBTEST(test_contained_in_list());\n  CALL_SUBTEST(test_arg_reductions());\n  CALL_SUBTEST(test_array_reverse_and_reduce());\n  CALL_SUBTEST(test_array_zip_and_apply());\n  CALL_SUBTEST(test_array_misc());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_non_blocking_thread_pool.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Dmitry Vyukov <dvyukov@google.com>\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_USE_THREADS\n#include \"main.h\"\n#include \"Eigen/CXX11/ThreadPool\"\n#include \"Eigen/CXX11/Tensor\"\n\nstatic void test_create_destroy_empty_pool()\n{\n  // Just create and destroy the pool. This will wind up and tear down worker\n  // threads. Ensure there are no issues in that logic.\n  for (int i = 0; i < 16; ++i) {\n    ThreadPool tp(i);\n  }\n}\n\n\nstatic void test_parallelism(bool allow_spinning)\n{\n  // Test we never-ever fail to match available tasks with idle threads.\n  const int kThreads = 16;  // code below expects that this is a multiple of 4\n  ThreadPool tp(kThreads, allow_spinning);\n  VERIFY_IS_EQUAL(tp.NumThreads(), kThreads);\n  VERIFY_IS_EQUAL(tp.CurrentThreadId(), -1);\n  for (int iter = 0; iter < 100; ++iter) {\n    std::atomic<int> running(0);\n    std::atomic<int> done(0);\n    std::atomic<int> phase(0);\n    // Schedule kThreads tasks and ensure that they all are running.\n    for (int i = 0; i < kThreads; ++i) {\n      tp.Schedule([&]() {\n        const int thread_id = tp.CurrentThreadId();\n        VERIFY_GE(thread_id, 0);\n        VERIFY_LE(thread_id, kThreads - 1);\n        running++;\n        while (phase < 1) {\n        }\n        done++;\n      });\n    }\n    while (running != kThreads) {\n    }\n    running = 0;\n    phase = 1;\n    // Now, while the previous tasks exit, schedule another kThreads tasks and\n    // ensure that they are running.\n    for (int i = 0; i < kThreads; ++i) {\n      tp.Schedule([&, i]() {\n        running++;\n        while (phase < 2) {\n        }\n        // When all tasks are running, half of tasks exit, quarter of tasks\n        // continue running and quarter of tasks schedule another 2 tasks each.\n        // Concurrently main thread schedules another quarter of tasks.\n        // This gives us another kThreads tasks and we ensure that they all\n        // are running.\n        if (i < kThreads / 2) {\n        } else if (i < 3 * kThreads / 4) {\n          running++;\n          while (phase < 3) {\n          }\n          done++;\n        } else {\n          for (int j = 0; j < 2; ++j) {\n            tp.Schedule([&]() {\n              running++;\n              while (phase < 3) {\n              }\n              done++;\n            });\n          }\n        }\n        done++;\n      });\n    }\n    while (running != kThreads) {\n    }\n    running = 0;\n    phase = 2;\n    for (int i = 0; i < kThreads / 4; ++i) {\n      tp.Schedule([&]() {\n        running++;\n        while (phase < 3) {\n        }\n        done++;\n      });\n    }\n    while (running != kThreads) {\n    }\n    phase = 3;\n    while (done != 3 * kThreads) {\n    }\n  }\n}\n\n\nstatic void test_cancel()\n{\n  ThreadPool tp(2);\n\n  // Schedule a large number of closure that each sleeps for one second. This\n  // will keep the thread pool busy for much longer than the default test timeout.\n  for (int i = 0; i < 1000; ++i) {\n    tp.Schedule([]() {\n      std::this_thread::sleep_for(std::chrono::milliseconds(2000));\n    });\n  }\n\n  // Cancel the processing of all the closures that are still pending.\n  tp.Cancel();\n}\n\nstatic void test_pool_partitions() {\n  const int kThreads = 2;\n  ThreadPool tp(kThreads);\n\n  // Assign each thread to its own partition, so that stealing other work only\n  // occurs globally when a thread is idle.\n  std::vector<std::pair<unsigned, unsigned>> steal_partitions(kThreads);\n  for (int i = 0; i < kThreads; ++i) {\n    steal_partitions[i] = std::make_pair(i, i + 1);\n  }\n  tp.SetStealPartitions(steal_partitions);\n\n  std::atomic<int> running(0);\n  std::atomic<int> done(0);\n  std::atomic<int> phase(0);\n\n  // Schedule kThreads tasks and ensure that they all are running.\n  for (int i = 0; i < kThreads; ++i) {\n    tp.Schedule([&]() {\n      const int thread_id = tp.CurrentThreadId();\n      VERIFY_GE(thread_id, 0);\n      VERIFY_LE(thread_id, kThreads - 1);\n      ++running;\n      while (phase < 1) {\n      }\n      ++done;\n    });\n  }\n  while (running != kThreads) {\n  }\n  // Schedule each closure to only run on thread 'i' and verify that it does.\n  for (int i = 0; i < kThreads; ++i) {\n    tp.ScheduleWithHint(\n        [&, i]() {\n          ++running;\n          const int thread_id = tp.CurrentThreadId();\n          VERIFY_IS_EQUAL(thread_id, i);\n          while (phase < 2) {\n          }\n          ++done;\n        },\n        i, i + 1);\n  }\n  running = 0;\n  phase = 1;\n  while (running != kThreads) {\n  }\n  running = 0;\n  phase = 2;\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_non_blocking_thread_pool)\n{\n  CALL_SUBTEST(test_create_destroy_empty_pool());\n  CALL_SUBTEST(test_parallelism(true));\n  CALL_SUBTEST(test_parallelism(false));\n  CALL_SUBTEST(test_cancel());\n  CALL_SUBTEST(test_pool_partitions());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_runqueue.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Dmitry Vyukov <dvyukov@google.com>\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_USE_THREADS\n#include <cstdlib>\n#include \"main.h\"\n#include <Eigen/CXX11/ThreadPool>\n\n\n// Visual studio doesn't implement a rand_r() function since its\n// implementation of rand() is already thread safe\nint rand_reentrant(unsigned int* s) {\n#ifdef EIGEN_COMP_MSVC_STRICT\n  EIGEN_UNUSED_VARIABLE(s);\n  return rand();\n#else\n  return rand_r(s);\n#endif\n}\n\nvoid test_basic_runqueue()\n{\n  RunQueue<int, 4> q;\n  // Check empty state.\n  VERIFY(q.Empty());\n  VERIFY_IS_EQUAL(0u, q.Size());\n  VERIFY_IS_EQUAL(0, q.PopFront());\n  std::vector<int> stolen;\n  VERIFY_IS_EQUAL(0u, q.PopBackHalf(&stolen));\n  VERIFY_IS_EQUAL(0u, stolen.size());\n  // Push one front, pop one front.\n  VERIFY_IS_EQUAL(0, q.PushFront(1));\n  VERIFY_IS_EQUAL(1u, q.Size());\n  VERIFY_IS_EQUAL(1, q.PopFront());\n  VERIFY_IS_EQUAL(0u, q.Size());\n  // Push front to overflow.\n  VERIFY_IS_EQUAL(0, q.PushFront(2));\n  VERIFY_IS_EQUAL(1u, q.Size());\n  VERIFY_IS_EQUAL(0, q.PushFront(3));\n  VERIFY_IS_EQUAL(2u, q.Size());\n  VERIFY_IS_EQUAL(0, q.PushFront(4));\n  VERIFY_IS_EQUAL(3u, q.Size());\n  VERIFY_IS_EQUAL(0, q.PushFront(5));\n  VERIFY_IS_EQUAL(4u, q.Size());\n  VERIFY_IS_EQUAL(6, q.PushFront(6));\n  VERIFY_IS_EQUAL(4u, q.Size());\n  VERIFY_IS_EQUAL(5, q.PopFront());\n  VERIFY_IS_EQUAL(3u, q.Size());\n  VERIFY_IS_EQUAL(4, q.PopFront());\n  VERIFY_IS_EQUAL(2u, q.Size());\n  VERIFY_IS_EQUAL(3, q.PopFront());\n  VERIFY_IS_EQUAL(1u, q.Size());\n  VERIFY_IS_EQUAL(2, q.PopFront());\n  VERIFY_IS_EQUAL(0u, q.Size());\n  VERIFY_IS_EQUAL(0, q.PopFront());\n  // Push one back, pop one back.\n  VERIFY_IS_EQUAL(0, q.PushBack(7));\n  VERIFY_IS_EQUAL(1u, q.Size());\n  VERIFY_IS_EQUAL(1u, q.PopBackHalf(&stolen));\n  VERIFY_IS_EQUAL(1u, stolen.size());\n  VERIFY_IS_EQUAL(7, stolen[0]);\n  VERIFY_IS_EQUAL(0u, q.Size());\n  stolen.clear();\n  // Push back to overflow.\n  VERIFY_IS_EQUAL(0, q.PushBack(8));\n  VERIFY_IS_EQUAL(1u, q.Size());\n  VERIFY_IS_EQUAL(0, q.PushBack(9));\n  VERIFY_IS_EQUAL(2u, q.Size());\n  VERIFY_IS_EQUAL(0, q.PushBack(10));\n  VERIFY_IS_EQUAL(3u, q.Size());\n  VERIFY_IS_EQUAL(0, q.PushBack(11));\n  VERIFY_IS_EQUAL(4u, q.Size());\n  VERIFY_IS_EQUAL(12, q.PushBack(12));\n  VERIFY_IS_EQUAL(4u, q.Size());\n  // Pop back in halves.\n  VERIFY_IS_EQUAL(2u, q.PopBackHalf(&stolen));\n  VERIFY_IS_EQUAL(2u, stolen.size());\n  VERIFY_IS_EQUAL(10, stolen[0]);\n  VERIFY_IS_EQUAL(11, stolen[1]);\n  VERIFY_IS_EQUAL(2u, q.Size());\n  stolen.clear();\n  VERIFY_IS_EQUAL(1u, q.PopBackHalf(&stolen));\n  VERIFY_IS_EQUAL(1u, stolen.size());\n  VERIFY_IS_EQUAL(9, stolen[0]);\n  VERIFY_IS_EQUAL(1u, q.Size());\n  stolen.clear();\n  VERIFY_IS_EQUAL(1u, q.PopBackHalf(&stolen));\n  VERIFY_IS_EQUAL(1u, stolen.size());\n  VERIFY_IS_EQUAL(8, stolen[0]);\n  stolen.clear();\n  VERIFY_IS_EQUAL(0u, q.PopBackHalf(&stolen));\n  VERIFY_IS_EQUAL(0u, stolen.size());\n  // Empty again.\n  VERIFY(q.Empty());\n  VERIFY_IS_EQUAL(0u, q.Size());\n  VERIFY_IS_EQUAL(0, q.PushFront(1));\n  VERIFY_IS_EQUAL(0, q.PushFront(2));\n  VERIFY_IS_EQUAL(0, q.PushFront(3));\n  VERIFY_IS_EQUAL(1, q.PopBack());\n  VERIFY_IS_EQUAL(2, q.PopBack());\n  VERIFY_IS_EQUAL(3, q.PopBack());\n  VERIFY(q.Empty());\n  VERIFY_IS_EQUAL(0u, q.Size());\n}\n\n// Empty tests that the queue is not claimed to be empty when is is in fact not.\n// Emptiness property is crucial part of thread pool blocking scheme,\n// so we go to great effort to ensure this property. We create a queue with\n// 1 element and then push 1 element (either front or back at random) and pop\n// 1 element (either front or back at random). So queue always contains at least\n// 1 element, but otherwise changes chaotically. Another thread constantly tests\n// that the queue is not claimed to be empty.\nvoid test_empty_runqueue()\n{\n  RunQueue<int, 4> q;\n  q.PushFront(1);\n  std::atomic<bool> done(false);\n  std::thread mutator([&q, &done]() {\n    unsigned rnd = 0;\n    std::vector<int> stolen;\n    for (int i = 0; i < 1 << 18; i++) {\n      if (rand_reentrant(&rnd) % 2)\n        VERIFY_IS_EQUAL(0, q.PushFront(1));\n      else\n        VERIFY_IS_EQUAL(0, q.PushBack(1));\n      if (rand_reentrant(&rnd) % 2)\n        VERIFY_IS_EQUAL(1, q.PopFront());\n      else {\n        for (;;) {\n          if (q.PopBackHalf(&stolen) == 1) {\n            stolen.clear();\n            break;\n          }\n          VERIFY_IS_EQUAL(0u, stolen.size());\n        }\n      }\n    }\n    done = true;\n  });\n  while (!done) {\n    VERIFY(!q.Empty());\n    int size = q.Size();\n    VERIFY_GE(size, 1);\n    VERIFY_LE(size, 2);\n  }\n  VERIFY_IS_EQUAL(1, q.PopFront());\n  mutator.join();\n}\n\n// Stress is a chaotic random test.\n// One thread (owner) calls PushFront/PopFront, other threads call PushBack/\n// PopBack. Ensure that we don't crash, deadlock, and all sanity checks pass.\nvoid test_stress_runqueue()\n{\n  static const int kEvents = 1 << 18;\n  RunQueue<int, 8> q;\n  std::atomic<int> total(0);\n  std::vector<std::unique_ptr<std::thread>> threads;\n  threads.emplace_back(new std::thread([&q, &total]() {\n    int sum = 0;\n    int pushed = 1;\n    int popped = 1;\n    while (pushed < kEvents || popped < kEvents) {\n      if (pushed < kEvents) {\n        if (q.PushFront(pushed) == 0) {\n          sum += pushed;\n          pushed++;\n        }\n      }\n      if (popped < kEvents) {\n        int v = q.PopFront();\n        if (v != 0) {\n          sum -= v;\n          popped++;\n        }\n      }\n    }\n    total += sum;\n  }));\n  for (int i = 0; i < 2; i++) {\n    threads.emplace_back(new std::thread([&q, &total]() {\n      int sum = 0;\n      for (int j = 1; j < kEvents; j++) {\n        if (q.PushBack(j) == 0) {\n          sum += j;\n          continue;\n        }\n        EIGEN_THREAD_YIELD();\n        j--;\n      }\n      total += sum;\n    }));\n    threads.emplace_back(new std::thread([&q, &total]() {\n      int sum = 0;\n      std::vector<int> stolen;\n      for (int j = 1; j < kEvents;) {\n        if (q.PopBackHalf(&stolen) == 0) {\n          EIGEN_THREAD_YIELD();\n          continue;\n        }\n        while (stolen.size() && j < kEvents) {\n          int v = stolen.back();\n          stolen.pop_back();\n          VERIFY_IS_NOT_EQUAL(v, 0);\n          sum += v;\n          j++;\n        }\n      }\n      while (stolen.size()) {\n        int v = stolen.back();\n        stolen.pop_back();\n        VERIFY_IS_NOT_EQUAL(v, 0);\n        while ((v = q.PushBack(v)) != 0) EIGEN_THREAD_YIELD();\n      }\n      total -= sum;\n    }));\n  }\n  for (size_t i = 0; i < threads.size(); i++) threads[i]->join();\n  VERIFY(q.Empty());\n  VERIFY(total.load() == 0);\n}\n\nEIGEN_DECLARE_TEST(cxx11_runqueue)\n{\n  CALL_SUBTEST_1(test_basic_runqueue());\n  CALL_SUBTEST_2(test_empty_runqueue());\n  CALL_SUBTEST_3(test_stress_runqueue());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_argmax.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Eugene Brevdo <ebrevdo@google.com>\n//                    Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::array;\nusing Eigen::Tuple;\n\ntemplate <int DataLayout>\nstatic void test_simple_index_tuples()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  tensor = (tensor + tensor.constant(0.5)).log();\n\n  Tensor<Tuple<DenseIndex, float>, 4, DataLayout> index_tuples(2,3,5,7);\n  index_tuples = tensor.index_tuples();\n\n  for (DenseIndex n = 0; n < 2*3*5*7; ++n) {\n    const Tuple<DenseIndex, float>& v = index_tuples.coeff(n);\n    VERIFY_IS_EQUAL(v.first, n);\n    VERIFY_IS_EQUAL(v.second, tensor.coeff(n));\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_index_tuples_dim()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  tensor = (tensor + tensor.constant(0.5)).log();\n\n  Tensor<Tuple<DenseIndex, float>, 4, DataLayout> index_tuples(2,3,5,7);\n\n  index_tuples = tensor.index_tuples();\n\n  for (Eigen::DenseIndex n = 0; n < tensor.size(); ++n) {\n    const Tuple<DenseIndex, float>& v = index_tuples(n); //(i, j, k, l);\n    VERIFY_IS_EQUAL(v.first, n);\n    VERIFY_IS_EQUAL(v.second, tensor(n));\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_argmax_tuple_reducer()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  tensor = (tensor + tensor.constant(0.5)).log();\n\n  Tensor<Tuple<DenseIndex, float>, 4, DataLayout> index_tuples(2,3,5,7);\n  index_tuples = tensor.index_tuples();\n\n  Tensor<Tuple<DenseIndex, float>, 0, DataLayout> reduced;\n  DimensionList<DenseIndex, 4> dims;\n  reduced = index_tuples.reduce(\n      dims, internal::ArgMaxTupleReducer<Tuple<DenseIndex, float> >());\n\n  Tensor<float, 0, DataLayout> maxi = tensor.maximum();\n\n  VERIFY_IS_EQUAL(maxi(), reduced(0).second);\n\n  array<DenseIndex, 3> reduce_dims;\n  for (int d = 0; d < 3; ++d) reduce_dims[d] = d;\n  Tensor<Tuple<DenseIndex, float>, 1, DataLayout> reduced_by_dims(7);\n  reduced_by_dims = index_tuples.reduce(\n      reduce_dims, internal::ArgMaxTupleReducer<Tuple<DenseIndex, float> >());\n\n  Tensor<float, 1, DataLayout> max_by_dims = tensor.maximum(reduce_dims);\n\n  for (int l = 0; l < 7; ++l) {\n    VERIFY_IS_EQUAL(max_by_dims(l), reduced_by_dims(l).second);\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_argmin_tuple_reducer()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  tensor = (tensor + tensor.constant(0.5)).log();\n\n  Tensor<Tuple<DenseIndex, float>, 4, DataLayout> index_tuples(2,3,5,7);\n  index_tuples = tensor.index_tuples();\n\n  Tensor<Tuple<DenseIndex, float>, 0, DataLayout> reduced;\n  DimensionList<DenseIndex, 4> dims;\n  reduced = index_tuples.reduce(\n      dims, internal::ArgMinTupleReducer<Tuple<DenseIndex, float> >());\n\n  Tensor<float, 0, DataLayout> mini = tensor.minimum();\n\n  VERIFY_IS_EQUAL(mini(), reduced(0).second);\n\n  array<DenseIndex, 3> reduce_dims;\n  for (int d = 0; d < 3; ++d) reduce_dims[d] = d;\n  Tensor<Tuple<DenseIndex, float>, 1, DataLayout> reduced_by_dims(7);\n  reduced_by_dims = index_tuples.reduce(\n      reduce_dims, internal::ArgMinTupleReducer<Tuple<DenseIndex, float> >());\n\n  Tensor<float, 1, DataLayout> min_by_dims = tensor.minimum(reduce_dims);\n\n  for (int l = 0; l < 7; ++l) {\n    VERIFY_IS_EQUAL(min_by_dims(l), reduced_by_dims(l).second);\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_simple_argmax()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  tensor = (tensor + tensor.constant(0.5)).log();\n  tensor(0,0,0,0) = 10.0;\n\n  Tensor<DenseIndex, 0, DataLayout> tensor_argmax;\n\n  tensor_argmax = tensor.argmax();\n\n  VERIFY_IS_EQUAL(tensor_argmax(0), 0);\n\n  tensor(1,2,4,6) = 20.0;\n\n  tensor_argmax = tensor.argmax();\n\n  VERIFY_IS_EQUAL(tensor_argmax(0), 2*3*5*7 - 1);\n}\n\ntemplate <int DataLayout>\nstatic void test_simple_argmin()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  tensor = (tensor + tensor.constant(0.5)).log();\n  tensor(0,0,0,0) = -10.0;\n\n  Tensor<DenseIndex, 0, DataLayout> tensor_argmin;\n\n  tensor_argmin = tensor.argmin();\n\n  VERIFY_IS_EQUAL(tensor_argmin(0), 0);\n\n  tensor(1,2,4,6) = -20.0;\n\n  tensor_argmin = tensor.argmin();\n\n  VERIFY_IS_EQUAL(tensor_argmin(0), 2*3*5*7 - 1);\n}\n\ntemplate <int DataLayout>\nstatic void test_argmax_dim()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  std::vector<int> dims {2, 3, 5, 7};\n\n  for (int dim = 0; dim < 4; ++dim) {\n    tensor.setRandom();\n    tensor = (tensor + tensor.constant(0.5)).log();\n\n    Tensor<DenseIndex, 3, DataLayout> tensor_argmax;\n    array<DenseIndex, 4> ix;\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 3; ++j) {\n        for (int k = 0; k < 5; ++k) {\n          for (int l = 0; l < 7; ++l) {\n            ix[0] = i; ix[1] = j; ix[2] = k; ix[3] = l;\n            if (ix[dim] != 0) continue;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 0, k, l) = 10.0\n            tensor(ix) = 10.0;\n          }\n        }\n      }\n    }\n\n    tensor_argmax = tensor.argmax(dim);\n\n    VERIFY_IS_EQUAL(tensor_argmax.size(),\n                    ptrdiff_t(2*3*5*7 / tensor.dimension(dim)));\n    for (ptrdiff_t n = 0; n < tensor_argmax.size(); ++n) {\n      // Expect max to be in the first index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_argmax.data()[n], 0);\n    }\n\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 3; ++j) {\n        for (int k = 0; k < 5; ++k) {\n          for (int l = 0; l < 7; ++l) {\n            ix[0] = i; ix[1] = j; ix[2] = k; ix[3] = l;\n            if (ix[dim] != tensor.dimension(dim) - 1) continue;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 2, k, l) = 20.0\n            tensor(ix) = 20.0;\n          }\n        }\n      }\n    }\n\n    tensor_argmax = tensor.argmax(dim);\n\n    VERIFY_IS_EQUAL(tensor_argmax.size(),\n                    ptrdiff_t(2*3*5*7 / tensor.dimension(dim)));\n    for (ptrdiff_t n = 0; n < tensor_argmax.size(); ++n) {\n      // Expect max to be in the last index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_argmax.data()[n], tensor.dimension(dim) - 1);\n    }\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_argmin_dim()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  std::vector<int> dims {2, 3, 5, 7};\n\n  for (int dim = 0; dim < 4; ++dim) {\n    tensor.setRandom();\n    tensor = (tensor + tensor.constant(0.5)).log();\n\n    Tensor<DenseIndex, 3, DataLayout> tensor_argmin;\n    array<DenseIndex, 4> ix;\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 3; ++j) {\n        for (int k = 0; k < 5; ++k) {\n          for (int l = 0; l < 7; ++l) {\n            ix[0] = i; ix[1] = j; ix[2] = k; ix[3] = l;\n            if (ix[dim] != 0) continue;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 0, k, l) = -10.0\n            tensor(ix) = -10.0;\n          }\n        }\n      }\n    }\n\n    tensor_argmin = tensor.argmin(dim);\n\n    VERIFY_IS_EQUAL(tensor_argmin.size(),\n                    ptrdiff_t(2*3*5*7 / tensor.dimension(dim)));\n    for (ptrdiff_t n = 0; n < tensor_argmin.size(); ++n) {\n      // Expect min to be in the first index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_argmin.data()[n], 0);\n    }\n\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 3; ++j) {\n        for (int k = 0; k < 5; ++k) {\n          for (int l = 0; l < 7; ++l) {\n            ix[0] = i; ix[1] = j; ix[2] = k; ix[3] = l;\n            if (ix[dim] != tensor.dimension(dim) - 1) continue;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 2, k, l) = -20.0\n            tensor(ix) = -20.0;\n          }\n        }\n      }\n    }\n\n    tensor_argmin = tensor.argmin(dim);\n\n    VERIFY_IS_EQUAL(tensor_argmin.size(),\n                    ptrdiff_t(2*3*5*7 / tensor.dimension(dim)));\n    for (ptrdiff_t n = 0; n < tensor_argmin.size(); ++n) {\n      // Expect min to be in the last index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_argmin.data()[n], tensor.dimension(dim) - 1);\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_argmax)\n{\n  CALL_SUBTEST(test_simple_index_tuples<RowMajor>());\n  CALL_SUBTEST(test_simple_index_tuples<ColMajor>());\n  CALL_SUBTEST(test_index_tuples_dim<RowMajor>());\n  CALL_SUBTEST(test_index_tuples_dim<ColMajor>());\n  CALL_SUBTEST(test_argmax_tuple_reducer<RowMajor>());\n  CALL_SUBTEST(test_argmax_tuple_reducer<ColMajor>());\n  CALL_SUBTEST(test_argmin_tuple_reducer<RowMajor>());\n  CALL_SUBTEST(test_argmin_tuple_reducer<ColMajor>());\n  CALL_SUBTEST(test_simple_argmax<RowMajor>());\n  CALL_SUBTEST(test_simple_argmax<ColMajor>());\n  CALL_SUBTEST(test_simple_argmin<RowMajor>());\n  CALL_SUBTEST(test_simple_argmin<ColMajor>());\n  CALL_SUBTEST(test_argmax_dim<RowMajor>());\n  CALL_SUBTEST(test_argmax_dim<ColMajor>());\n  CALL_SUBTEST(test_argmin_dim<RowMajor>());\n  CALL_SUBTEST(test_argmin_dim<ColMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_argmax_gpu.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\n#include <unsupported/Eigen/CXX11/src/Tensor/TensorGpuHipCudaDefines.h>\n\nusing Eigen::Tensor;\n\ntemplate <int Layout>\nvoid test_gpu_simple_argmax()\n{\n  Tensor<double, 3, Layout> in(Eigen::array<DenseIndex, 3>(72,53,97));\n  Tensor<DenseIndex, 1, Layout> out_max(Eigen::array<DenseIndex, 1>(1));\n  Tensor<DenseIndex, 1, Layout> out_min(Eigen::array<DenseIndex, 1>(1));\n  in.setRandom();\n  in *= in.constant(100.0);\n  in(0, 0, 0) = -1000.0;\n  in(71, 52, 96) = 1000.0;\n\n  std::size_t in_bytes = in.size() * sizeof(double);\n  std::size_t out_bytes = out_max.size() * sizeof(DenseIndex);\n\n  double* d_in;\n  DenseIndex* d_out_max;\n  DenseIndex* d_out_min;\n  gpuMalloc((void**)(&d_in), in_bytes);\n  gpuMalloc((void**)(&d_out_max), out_bytes);\n  gpuMalloc((void**)(&d_out_min), out_bytes);\n\n  gpuMemcpy(d_in, in.data(), in_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<double, 3, Layout>, Aligned > gpu_in(d_in, Eigen::array<DenseIndex, 3>(72,53,97));\n  Eigen::TensorMap<Eigen::Tensor<DenseIndex, 1, Layout>, Aligned > gpu_out_max(d_out_max, Eigen::array<DenseIndex, 1>(1));\n  Eigen::TensorMap<Eigen::Tensor<DenseIndex, 1, Layout>, Aligned > gpu_out_min(d_out_min, Eigen::array<DenseIndex, 1>(1));\n\n  gpu_out_max.device(gpu_device) = gpu_in.argmax();\n  gpu_out_min.device(gpu_device) = gpu_in.argmin();\n\n  assert(gpuMemcpyAsync(out_max.data(), d_out_max, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuMemcpyAsync(out_min.data(), d_out_min, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  VERIFY_IS_EQUAL(out_max(Eigen::array<DenseIndex, 1>(0)), 72*53*97 - 1);\n  VERIFY_IS_EQUAL(out_min(Eigen::array<DenseIndex, 1>(0)), 0);\n\n  gpuFree(d_in);\n  gpuFree(d_out_max);\n  gpuFree(d_out_min);\n}\n\ntemplate <int DataLayout>\nvoid test_gpu_argmax_dim()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  std::vector<int> dims;\n  dims.push_back(2); dims.push_back(3); dims.push_back(5); dims.push_back(7);\n\n  for (int dim = 0; dim < 4; ++dim) {\n    tensor.setRandom();\n    tensor = (tensor + tensor.constant(0.5)).log();\n\n    array<DenseIndex, 3> out_shape;\n    for (int d = 0; d < 3; ++d) out_shape[d] = (d < dim) ? dims[d] : dims[d+1];\n\n    Tensor<DenseIndex, 3, DataLayout> tensor_arg(out_shape);\n\n    array<DenseIndex, 4> ix;\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 3; ++j) {\n        for (int k = 0; k < 5; ++k) {\n          for (int l = 0; l < 7; ++l) {\n            ix[0] = i; ix[1] = j; ix[2] = k; ix[3] = l;\n            if (ix[dim] != 0) continue;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 0, k, l) = 10.0\n            tensor(ix) = 10.0;\n          }\n        }\n      }\n    }\n\n    std::size_t in_bytes = tensor.size() * sizeof(float);\n    std::size_t out_bytes = tensor_arg.size() * sizeof(DenseIndex);\n\n    float* d_in;\n    DenseIndex* d_out;\n    gpuMalloc((void**)(&d_in), in_bytes);\n    gpuMalloc((void**)(&d_out), out_bytes);\n\n    gpuMemcpy(d_in, tensor.data(), in_bytes, gpuMemcpyHostToDevice);\n\n    Eigen::GpuStreamDevice stream;\n    Eigen::GpuDevice gpu_device(&stream);\n\n    Eigen::TensorMap<Eigen::Tensor<float, 4, DataLayout>, Aligned > gpu_in(d_in, Eigen::array<DenseIndex, 4>(2, 3, 5, 7));\n    Eigen::TensorMap<Eigen::Tensor<DenseIndex, 3, DataLayout>, Aligned > gpu_out(d_out, out_shape);\n\n    gpu_out.device(gpu_device) = gpu_in.argmax(dim);\n\n    assert(gpuMemcpyAsync(tensor_arg.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n    assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n    VERIFY_IS_EQUAL(tensor_arg.size(),\n                    size_t(2*3*5*7 / tensor.dimension(dim)));\n\n    for (DenseIndex n = 0; n < tensor_arg.size(); ++n) {\n      // Expect max to be in the first index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_arg.data()[n], 0);\n    }\n\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 3; ++j) {\n        for (int k = 0; k < 5; ++k) {\n          for (int l = 0; l < 7; ++l) {\n            ix[0] = i; ix[1] = j; ix[2] = k; ix[3] = l;\n            if (ix[dim] != tensor.dimension(dim) - 1) continue;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 2, k, l) = 20.0\n            tensor(ix) = 20.0;\n          }\n        }\n      }\n    }\n\n    gpuMemcpy(d_in, tensor.data(), in_bytes, gpuMemcpyHostToDevice);\n\n    gpu_out.device(gpu_device) = gpu_in.argmax(dim);\n\n    assert(gpuMemcpyAsync(tensor_arg.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n    assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n    for (DenseIndex n = 0; n < tensor_arg.size(); ++n) {\n      // Expect max to be in the last index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_arg.data()[n], tensor.dimension(dim) - 1);\n    }\n\n    gpuFree(d_in);\n    gpuFree(d_out);\n  }\n}\n\ntemplate <int DataLayout>\nvoid test_gpu_argmin_dim()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  std::vector<int> dims;\n  dims.push_back(2); dims.push_back(3); dims.push_back(5); dims.push_back(7);\n\n  for (int dim = 0; dim < 4; ++dim) {\n    tensor.setRandom();\n    tensor = (tensor + tensor.constant(0.5)).log();\n\n    array<DenseIndex, 3> out_shape;\n    for (int d = 0; d < 3; ++d) out_shape[d] = (d < dim) ? dims[d] : dims[d+1];\n\n    Tensor<DenseIndex, 3, DataLayout> tensor_arg(out_shape);\n\n    array<DenseIndex, 4> ix;\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 3; ++j) {\n        for (int k = 0; k < 5; ++k) {\n          for (int l = 0; l < 7; ++l) {\n            ix[0] = i; ix[1] = j; ix[2] = k; ix[3] = l;\n            if (ix[dim] != 0) continue;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 0, k, l) = 10.0\n            tensor(ix) = -10.0;\n          }\n        }\n      }\n    }\n\n    std::size_t in_bytes = tensor.size() * sizeof(float);\n    std::size_t out_bytes = tensor_arg.size() * sizeof(DenseIndex);\n\n    float* d_in;\n    DenseIndex* d_out;\n    gpuMalloc((void**)(&d_in), in_bytes);\n    gpuMalloc((void**)(&d_out), out_bytes);\n\n    gpuMemcpy(d_in, tensor.data(), in_bytes, gpuMemcpyHostToDevice);\n\n    Eigen::GpuStreamDevice stream;\n    Eigen::GpuDevice gpu_device(&stream);\n\n    Eigen::TensorMap<Eigen::Tensor<float, 4, DataLayout>, Aligned > gpu_in(d_in, Eigen::array<DenseIndex, 4>(2, 3, 5, 7));\n    Eigen::TensorMap<Eigen::Tensor<DenseIndex, 3, DataLayout>, Aligned > gpu_out(d_out, out_shape);\n\n    gpu_out.device(gpu_device) = gpu_in.argmin(dim);\n\n    assert(gpuMemcpyAsync(tensor_arg.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n    assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n    VERIFY_IS_EQUAL(tensor_arg.size(),\n                    2*3*5*7 / tensor.dimension(dim));\n\n    for (DenseIndex n = 0; n < tensor_arg.size(); ++n) {\n      // Expect min to be in the first index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_arg.data()[n], 0);\n    }\n\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 3; ++j) {\n        for (int k = 0; k < 5; ++k) {\n          for (int l = 0; l < 7; ++l) {\n            ix[0] = i; ix[1] = j; ix[2] = k; ix[3] = l;\n            if (ix[dim] != tensor.dimension(dim) - 1) continue;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 2, k, l) = 20.0\n            tensor(ix) = -20.0;\n          }\n        }\n      }\n    }\n\n    gpuMemcpy(d_in, tensor.data(), in_bytes, gpuMemcpyHostToDevice);\n\n    gpu_out.device(gpu_device) = gpu_in.argmin(dim);\n\n    assert(gpuMemcpyAsync(tensor_arg.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n    assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n    for (DenseIndex n = 0; n < tensor_arg.size(); ++n) {\n      // Expect max to be in the last index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_arg.data()[n], tensor.dimension(dim) - 1);\n    }\n\n    gpuFree(d_in);\n    gpuFree(d_out);\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_argmax_gpu)\n{\n  CALL_SUBTEST_1(test_gpu_simple_argmax<RowMajor>());\n  CALL_SUBTEST_1(test_gpu_simple_argmax<ColMajor>());\n  CALL_SUBTEST_2(test_gpu_argmax_dim<RowMajor>());\n  CALL_SUBTEST_2(test_gpu_argmax_dim<ColMajor>());\n  CALL_SUBTEST_3(test_gpu_argmin_dim<RowMajor>());\n  CALL_SUBTEST_3(test_gpu_argmin_dim<ColMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_argmax_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n#define EIGEN_HAS_CONSTEXPR 1\n\n#include \"main.h\"\n\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\ntemplate <typename DataType, int Layout, typename DenseIndex>\nstatic void test_sycl_simple_argmax(const Eigen::SyclDevice& sycl_device) {\n  Tensor<DataType, 3, Layout, DenseIndex> in(Eigen::array<DenseIndex, 3>{{2, 2, 2}});\n  Tensor<DenseIndex, 0, Layout, DenseIndex> out_max;\n  Tensor<DenseIndex, 0, Layout, DenseIndex> out_min;\n  in.setRandom();\n  in *= in.constant(100.0);\n  in(0, 0, 0) = -1000.0;\n  in(1, 1, 1) = 1000.0;\n\n  std::size_t in_bytes = in.size() * sizeof(DataType);\n  std::size_t out_bytes = out_max.size() * sizeof(DenseIndex);\n\n  DataType* d_in = static_cast<DataType*>(sycl_device.allocate(in_bytes));\n  DenseIndex* d_out_max = static_cast<DenseIndex*>(sycl_device.allocate(out_bytes));\n  DenseIndex* d_out_min = static_cast<DenseIndex*>(sycl_device.allocate(out_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, Layout, DenseIndex> > gpu_in(d_in,\n                                                                           Eigen::array<DenseIndex, 3>{{2, 2, 2}});\n  Eigen::TensorMap<Eigen::Tensor<DenseIndex, 0, Layout, DenseIndex> > gpu_out_max(d_out_max);\n  Eigen::TensorMap<Eigen::Tensor<DenseIndex, 0, Layout, DenseIndex> > gpu_out_min(d_out_min);\n  sycl_device.memcpyHostToDevice(d_in, in.data(), in_bytes);\n\n  gpu_out_max.device(sycl_device) = gpu_in.argmax();\n  gpu_out_min.device(sycl_device) = gpu_in.argmin();\n\n  sycl_device.memcpyDeviceToHost(out_max.data(), d_out_max, out_bytes);\n  sycl_device.memcpyDeviceToHost(out_min.data(), d_out_min, out_bytes);\n\n  VERIFY_IS_EQUAL(out_max(), 2 * 2 * 2 - 1);\n  VERIFY_IS_EQUAL(out_min(), 0);\n\n  sycl_device.deallocate(d_in);\n  sycl_device.deallocate(d_out_max);\n  sycl_device.deallocate(d_out_min);\n}\n\ntemplate <typename DataType, int DataLayout, typename DenseIndex>\nstatic void test_sycl_argmax_dim(const Eigen::SyclDevice& sycl_device) {\n  DenseIndex sizeDim0 = 9;\n  DenseIndex sizeDim1 = 3;\n  DenseIndex sizeDim2 = 5;\n  DenseIndex sizeDim3 = 7;\n  Tensor<DataType, 4, DataLayout, DenseIndex> tensor(sizeDim0, sizeDim1, sizeDim2, sizeDim3);\n\n  std::vector<DenseIndex> dims;\n  dims.push_back(sizeDim0);\n  dims.push_back(sizeDim1);\n  dims.push_back(sizeDim2);\n  dims.push_back(sizeDim3);\n  for (DenseIndex dim = 0; dim < 4; ++dim) {\n    array<DenseIndex, 3> out_shape;\n    for (DenseIndex d = 0; d < 3; ++d) out_shape[d] = (d < dim) ? dims[d] : dims[d + 1];\n\n    Tensor<DenseIndex, 3, DataLayout, DenseIndex> tensor_arg(out_shape);\n\n    array<DenseIndex, 4> ix;\n    for (DenseIndex i = 0; i < sizeDim0; ++i) {\n      for (DenseIndex j = 0; j < sizeDim1; ++j) {\n        for (DenseIndex k = 0; k < sizeDim2; ++k) {\n          for (DenseIndex l = 0; l < sizeDim3; ++l) {\n            ix[0] = i;\n            ix[1] = j;\n            ix[2] = k;\n            ix[3] = l;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 0, k, l)\n            // = 10.0\n            tensor(ix) = (ix[dim] != 0) ? -1.0 : 10.0;\n          }\n        }\n      }\n    }\n\n    std::size_t in_bytes = tensor.size() * sizeof(DataType);\n    std::size_t out_bytes = tensor_arg.size() * sizeof(DenseIndex);\n\n    DataType* d_in = static_cast<DataType*>(sycl_device.allocate(in_bytes));\n    DenseIndex* d_out = static_cast<DenseIndex*>(sycl_device.allocate(out_bytes));\n\n    Eigen::TensorMap<Eigen::Tensor<DataType, 4, DataLayout, DenseIndex> > gpu_in(\n        d_in, Eigen::array<DenseIndex, 4>{{sizeDim0, sizeDim1, sizeDim2, sizeDim3}});\n    Eigen::TensorMap<Eigen::Tensor<DenseIndex, 3, DataLayout, DenseIndex> > gpu_out(d_out, out_shape);\n\n    sycl_device.memcpyHostToDevice(d_in, tensor.data(), in_bytes);\n    gpu_out.device(sycl_device) = gpu_in.argmax(dim);\n    sycl_device.memcpyDeviceToHost(tensor_arg.data(), d_out, out_bytes);\n\n    VERIFY_IS_EQUAL(static_cast<size_t>(tensor_arg.size()),\n                    size_t(sizeDim0 * sizeDim1 * sizeDim2 * sizeDim3 / tensor.dimension(dim)));\n\n    for (DenseIndex n = 0; n < tensor_arg.size(); ++n) {\n      // Expect max to be in the first index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_arg.data()[n], 0);\n    }\n\n    sycl_device.synchronize();\n\n    for (DenseIndex i = 0; i < sizeDim0; ++i) {\n      for (DenseIndex j = 0; j < sizeDim1; ++j) {\n        for (DenseIndex k = 0; k < sizeDim2; ++k) {\n          for (DenseIndex l = 0; l < sizeDim3; ++l) {\n            ix[0] = i;\n            ix[1] = j;\n            ix[2] = k;\n            ix[3] = l;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 2, k, l) = 20.0\n            tensor(ix) = (ix[dim] != tensor.dimension(dim) - 1) ? -1.0 : 20.0;\n          }\n        }\n      }\n    }\n\n    sycl_device.memcpyHostToDevice(d_in, tensor.data(), in_bytes);\n    gpu_out.device(sycl_device) = gpu_in.argmax(dim);\n    sycl_device.memcpyDeviceToHost(tensor_arg.data(), d_out, out_bytes);\n\n    for (DenseIndex n = 0; n < tensor_arg.size(); ++n) {\n      // Expect max to be in the last index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_arg.data()[n], tensor.dimension(dim) - 1);\n    }\n    sycl_device.deallocate(d_in);\n    sycl_device.deallocate(d_out);\n  }\n}\n\ntemplate <typename DataType, int DataLayout, typename DenseIndex>\nstatic void test_sycl_argmin_dim(const Eigen::SyclDevice& sycl_device) {\n  DenseIndex sizeDim0 = 9;\n  DenseIndex sizeDim1 = 3;\n  DenseIndex sizeDim2 = 5;\n  DenseIndex sizeDim3 = 7;\n  Tensor<DataType, 4, DataLayout, DenseIndex> tensor(sizeDim0, sizeDim1, sizeDim2, sizeDim3);\n\n  std::vector<DenseIndex> dims;\n  dims.push_back(sizeDim0);\n  dims.push_back(sizeDim1);\n  dims.push_back(sizeDim2);\n  dims.push_back(sizeDim3);\n  for (DenseIndex dim = 0; dim < 4; ++dim) {\n    array<DenseIndex, 3> out_shape;\n    for (DenseIndex d = 0; d < 3; ++d) out_shape[d] = (d < dim) ? dims[d] : dims[d + 1];\n\n    Tensor<DenseIndex, 3, DataLayout, DenseIndex> tensor_arg(out_shape);\n\n    array<DenseIndex, 4> ix;\n    for (DenseIndex i = 0; i < sizeDim0; ++i) {\n      for (DenseIndex j = 0; j < sizeDim1; ++j) {\n        for (DenseIndex k = 0; k < sizeDim2; ++k) {\n          for (DenseIndex l = 0; l < sizeDim3; ++l) {\n            ix[0] = i;\n            ix[1] = j;\n            ix[2] = k;\n            ix[3] = l;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 0, k, l) = -10.0\n            tensor(ix) = (ix[dim] != 0) ? 1.0 : -10.0;\n          }\n        }\n      }\n    }\n\n    std::size_t in_bytes = tensor.size() * sizeof(DataType);\n    std::size_t out_bytes = tensor_arg.size() * sizeof(DenseIndex);\n\n    DataType* d_in = static_cast<DataType*>(sycl_device.allocate(in_bytes));\n    DenseIndex* d_out = static_cast<DenseIndex*>(sycl_device.allocate(out_bytes));\n\n    Eigen::TensorMap<Eigen::Tensor<DataType, 4, DataLayout, DenseIndex> > gpu_in(\n        d_in, Eigen::array<DenseIndex, 4>{{sizeDim0, sizeDim1, sizeDim2, sizeDim3}});\n    Eigen::TensorMap<Eigen::Tensor<DenseIndex, 3, DataLayout, DenseIndex> > gpu_out(d_out, out_shape);\n\n    sycl_device.memcpyHostToDevice(d_in, tensor.data(), in_bytes);\n    gpu_out.device(sycl_device) = gpu_in.argmin(dim);\n    sycl_device.memcpyDeviceToHost(tensor_arg.data(), d_out, out_bytes);\n\n    VERIFY_IS_EQUAL(static_cast<size_t>(tensor_arg.size()),\n                    size_t(sizeDim0 * sizeDim1 * sizeDim2 * sizeDim3 / tensor.dimension(dim)));\n\n    for (DenseIndex n = 0; n < tensor_arg.size(); ++n) {\n      // Expect max to be in the first index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_arg.data()[n], 0);\n    }\n\n    sycl_device.synchronize();\n\n    for (DenseIndex i = 0; i < sizeDim0; ++i) {\n      for (DenseIndex j = 0; j < sizeDim1; ++j) {\n        for (DenseIndex k = 0; k < sizeDim2; ++k) {\n          for (DenseIndex l = 0; l < sizeDim3; ++l) {\n            ix[0] = i;\n            ix[1] = j;\n            ix[2] = k;\n            ix[3] = l;\n            // suppose dim == 1, then for all i, k, l, set tensor(i, 2, k, l) = -20.0\n            tensor(ix) = (ix[dim] != tensor.dimension(dim) - 1) ? 1.0 : -20.0;\n          }\n        }\n      }\n    }\n\n    sycl_device.memcpyHostToDevice(d_in, tensor.data(), in_bytes);\n    gpu_out.device(sycl_device) = gpu_in.argmin(dim);\n    sycl_device.memcpyDeviceToHost(tensor_arg.data(), d_out, out_bytes);\n\n    for (DenseIndex n = 0; n < tensor_arg.size(); ++n) {\n      // Expect max to be in the last index of the reduced dimension\n      VERIFY_IS_EQUAL(tensor_arg.data()[n], tensor.dimension(dim) - 1);\n    }\n    sycl_device.deallocate(d_in);\n    sycl_device.deallocate(d_out);\n  }\n}\n\ntemplate <typename DataType, typename Device_Selector>\nvoid sycl_argmax_test_per_device(const Device_Selector& d) {\n  QueueInterface queueInterface(d);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_sycl_simple_argmax<DataType, RowMajor, int64_t>(sycl_device);\n  test_sycl_simple_argmax<DataType, ColMajor, int64_t>(sycl_device);\n  test_sycl_argmax_dim<DataType, ColMajor, int64_t>(sycl_device);\n  test_sycl_argmax_dim<DataType, RowMajor, int64_t>(sycl_device);\n  test_sycl_argmin_dim<DataType, ColMajor, int64_t>(sycl_device);\n  test_sycl_argmin_dim<DataType, RowMajor, int64_t>(sycl_device);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_argmax_sycl) {\n  for (const auto& device : Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_argmax_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_assign.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\nstatic void test_1d()\n{\n  Tensor<int, 1> vec1(6);\n  Tensor<int, 1, RowMajor> vec2(6);\n  vec1(0) = 4;  vec2(0) = 0;\n  vec1(1) = 8;  vec2(1) = 1;\n  vec1(2) = 15; vec2(2) = 2;\n  vec1(3) = 16; vec2(3) = 3;\n  vec1(4) = 23; vec2(4) = 4;\n  vec1(5) = 42; vec2(5) = 5;\n\n  int col_major[6];\n  int row_major[6];\n  memset(col_major, 0, 6*sizeof(int));\n  memset(row_major, 0, 6*sizeof(int));\n  TensorMap<Tensor<int, 1> > vec3(col_major, 6);\n  TensorMap<Tensor<int, 1, RowMajor> > vec4(row_major, 6);\n\n  vec3 = vec1;\n  vec4 = vec2;\n\n  VERIFY_IS_EQUAL(vec3(0), 4);\n  VERIFY_IS_EQUAL(vec3(1), 8);\n  VERIFY_IS_EQUAL(vec3(2), 15);\n  VERIFY_IS_EQUAL(vec3(3), 16);\n  VERIFY_IS_EQUAL(vec3(4), 23);\n  VERIFY_IS_EQUAL(vec3(5), 42);\n\n  VERIFY_IS_EQUAL(vec4(0), 0);\n  VERIFY_IS_EQUAL(vec4(1), 1);\n  VERIFY_IS_EQUAL(vec4(2), 2);\n  VERIFY_IS_EQUAL(vec4(3), 3);\n  VERIFY_IS_EQUAL(vec4(4), 4);\n  VERIFY_IS_EQUAL(vec4(5), 5);\n\n  vec1.setZero();\n  vec2.setZero();\n  vec1 = vec3;\n  vec2 = vec4;\n\n  VERIFY_IS_EQUAL(vec1(0), 4);\n  VERIFY_IS_EQUAL(vec1(1), 8);\n  VERIFY_IS_EQUAL(vec1(2), 15);\n  VERIFY_IS_EQUAL(vec1(3), 16);\n  VERIFY_IS_EQUAL(vec1(4), 23);\n  VERIFY_IS_EQUAL(vec1(5), 42);\n\n  VERIFY_IS_EQUAL(vec2(0), 0);\n  VERIFY_IS_EQUAL(vec2(1), 1);\n  VERIFY_IS_EQUAL(vec2(2), 2);\n  VERIFY_IS_EQUAL(vec2(3), 3);\n  VERIFY_IS_EQUAL(vec2(4), 4);\n  VERIFY_IS_EQUAL(vec2(5), 5);\n}\n\nstatic void test_2d()\n{\n  Tensor<int, 2> mat1(2,3);\n  Tensor<int, 2, RowMajor> mat2(2,3);\n\n  mat1(0,0) = 0;\n  mat1(0,1) = 1;\n  mat1(0,2) = 2;\n  mat1(1,0) = 3;\n  mat1(1,1) = 4;\n  mat1(1,2) = 5;\n\n  mat2(0,0) = 0;\n  mat2(0,1) = 1;\n  mat2(0,2) = 2;\n  mat2(1,0) = 3;\n  mat2(1,1) = 4;\n  mat2(1,2) = 5;\n\n  int col_major[6];\n  int row_major[6];\n  memset(col_major, 0, 6*sizeof(int));\n  memset(row_major, 0, 6*sizeof(int));\n  TensorMap<Tensor<int, 2> > mat3(row_major, 2, 3);\n  TensorMap<Tensor<int, 2, RowMajor> > mat4(col_major, 2, 3);\n\n  mat3 = mat1;\n  mat4 = mat2;\n\n  VERIFY_IS_EQUAL(mat3(0,0), 0);\n  VERIFY_IS_EQUAL(mat3(0,1), 1);\n  VERIFY_IS_EQUAL(mat3(0,2), 2);\n  VERIFY_IS_EQUAL(mat3(1,0), 3);\n  VERIFY_IS_EQUAL(mat3(1,1), 4);\n  VERIFY_IS_EQUAL(mat3(1,2), 5);\n\n  VERIFY_IS_EQUAL(mat4(0,0), 0);\n  VERIFY_IS_EQUAL(mat4(0,1), 1);\n  VERIFY_IS_EQUAL(mat4(0,2), 2);\n  VERIFY_IS_EQUAL(mat4(1,0), 3);\n  VERIFY_IS_EQUAL(mat4(1,1), 4);\n  VERIFY_IS_EQUAL(mat4(1,2), 5);\n\n  mat1.setZero();\n  mat2.setZero();\n  mat1 = mat3;\n  mat2 = mat4;\n\n  VERIFY_IS_EQUAL(mat1(0,0), 0);\n  VERIFY_IS_EQUAL(mat1(0,1), 1);\n  VERIFY_IS_EQUAL(mat1(0,2), 2);\n  VERIFY_IS_EQUAL(mat1(1,0), 3);\n  VERIFY_IS_EQUAL(mat1(1,1), 4);\n  VERIFY_IS_EQUAL(mat1(1,2), 5);\n\n  VERIFY_IS_EQUAL(mat2(0,0), 0);\n  VERIFY_IS_EQUAL(mat2(0,1), 1);\n  VERIFY_IS_EQUAL(mat2(0,2), 2);\n  VERIFY_IS_EQUAL(mat2(1,0), 3);\n  VERIFY_IS_EQUAL(mat2(1,1), 4);\n  VERIFY_IS_EQUAL(mat2(1,2), 5);\n}\n\nstatic void test_3d()\n{\n  Tensor<int, 3> mat1(2,3,7);\n  Tensor<int, 3, RowMajor> mat2(2,3,7);\n\n  int val = 0;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        mat1(i,j,k) = val;\n        mat2(i,j,k) = val;\n        val++;\n      }\n    }\n  }\n\n  int col_major[2*3*7];\n  int row_major[2*3*7];\n  memset(col_major, 0, 2*3*7*sizeof(int));\n  memset(row_major, 0, 2*3*7*sizeof(int));\n  TensorMap<Tensor<int, 3> > mat3(col_major, 2, 3, 7);\n  TensorMap<Tensor<int, 3, RowMajor> > mat4(row_major, 2, 3, 7);\n\n  mat3 = mat1;\n  mat4 = mat2;\n\n  val = 0;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(mat3(i,j,k), val);\n        VERIFY_IS_EQUAL(mat4(i,j,k), val);\n        val++;\n      }\n    }\n  }\n\n  mat1.setZero();\n  mat2.setZero();\n  mat1 = mat3;\n  mat2 = mat4;\n\n  val = 0;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(mat1(i,j,k), val);\n        VERIFY_IS_EQUAL(mat2(i,j,k), val);\n        val++;\n      }\n    }\n  }\n}\n\nstatic void test_same_type()\n{\n  Tensor<int, 1> orig_tensor(5);\n  Tensor<int, 1> dest_tensor(5);\n  orig_tensor.setRandom();\n  dest_tensor.setRandom();\n  int* orig_data = orig_tensor.data();\n  int* dest_data = dest_tensor.data();\n  dest_tensor = orig_tensor;\n  VERIFY_IS_EQUAL(orig_tensor.data(), orig_data);\n  VERIFY_IS_EQUAL(dest_tensor.data(), dest_data);\n  for (int i = 0; i < 5; ++i) {\n    VERIFY_IS_EQUAL(dest_tensor(i), orig_tensor(i));\n  }\n\n  TensorFixedSize<int, Sizes<5> > orig_array;\n  TensorFixedSize<int, Sizes<5> > dest_array;\n  orig_array.setRandom();\n  dest_array.setRandom();\n  orig_data = orig_array.data();\n  dest_data = dest_array.data();\n  dest_array = orig_array;\n  VERIFY_IS_EQUAL(orig_array.data(), orig_data);\n  VERIFY_IS_EQUAL(dest_array.data(), dest_data);\n  for (int i = 0; i < 5; ++i) {\n    VERIFY_IS_EQUAL(dest_array(i), orig_array(i));\n  }\n\n  int orig[5] = {1, 2, 3, 4, 5};\n  int dest[5] = {6, 7, 8, 9, 10};\n  TensorMap<Tensor<int, 1> > orig_map(orig, 5);\n  TensorMap<Tensor<int, 1> > dest_map(dest, 5);\n  orig_data = orig_map.data();\n  dest_data = dest_map.data();\n  dest_map = orig_map;\n  VERIFY_IS_EQUAL(orig_map.data(), orig_data);\n  VERIFY_IS_EQUAL(dest_map.data(), dest_data);\n  for (int i = 0; i < 5; ++i) {\n    VERIFY_IS_EQUAL(dest[i], i+1);\n  }\n}\n\nstatic void test_auto_resize()\n{\n  Tensor<int, 1> tensor1;\n  Tensor<int, 1> tensor2(3);\n  Tensor<int, 1> tensor3(5);\n  Tensor<int, 1> tensor4(7);\n\n  Tensor<int, 1> new_tensor(5);\n  new_tensor.setRandom();\n\n  tensor1 = tensor2 = tensor3 = tensor4 = new_tensor;\n\n  VERIFY_IS_EQUAL(tensor1.dimension(0), new_tensor.dimension(0));\n  VERIFY_IS_EQUAL(tensor2.dimension(0), new_tensor.dimension(0));\n  VERIFY_IS_EQUAL(tensor3.dimension(0), new_tensor.dimension(0));\n  VERIFY_IS_EQUAL(tensor4.dimension(0), new_tensor.dimension(0));\n  for (int i = 0; i < new_tensor.dimension(0); ++i) {\n    VERIFY_IS_EQUAL(tensor1(i), new_tensor(i));\n    VERIFY_IS_EQUAL(tensor2(i), new_tensor(i));\n    VERIFY_IS_EQUAL(tensor3(i), new_tensor(i));\n    VERIFY_IS_EQUAL(tensor4(i), new_tensor(i));\n  }\n}\n\n\nstatic void test_compound_assign()\n{\n  Tensor<int, 1> start_tensor(10);\n  Tensor<int, 1> offset_tensor(10);\n  start_tensor.setRandom();\n  offset_tensor.setRandom();\n\n  Tensor<int, 1> tensor = start_tensor;\n  tensor += offset_tensor;\n  for (int i = 0; i < 10; ++i) {\n    VERIFY_IS_EQUAL(tensor(i), start_tensor(i) + offset_tensor(i));\n  }\n\n  tensor = start_tensor;\n  tensor -= offset_tensor;\n  for (int i = 0; i < 10; ++i) {\n    VERIFY_IS_EQUAL(tensor(i), start_tensor(i) - offset_tensor(i));\n  }\n\n  tensor = start_tensor;\n  tensor *= offset_tensor;\n  for (int i = 0; i < 10; ++i) {\n    VERIFY_IS_EQUAL(tensor(i), start_tensor(i) * offset_tensor(i));\n  }\n\n  tensor = start_tensor;\n  tensor /= offset_tensor;\n  for (int i = 0; i < 10; ++i) {\n    VERIFY_IS_EQUAL(tensor(i), start_tensor(i) / offset_tensor(i));\n  }\n}\n\nstatic void test_std_initializers_tensor() {\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  Tensor<int, 1> a(3);\n  a.setValues({0, 1, 2});\n  VERIFY_IS_EQUAL(a(0), 0);\n  VERIFY_IS_EQUAL(a(1), 1);\n  VERIFY_IS_EQUAL(a(2), 2);\n\n  // It fills the top-left slice.\n  a.setValues({10, 20});\n  VERIFY_IS_EQUAL(a(0), 10);\n  VERIFY_IS_EQUAL(a(1), 20);\n  VERIFY_IS_EQUAL(a(2), 2);\n\n  // Chaining.\n  Tensor<int, 1> a2(3);\n  a2 = a.setValues({100, 200, 300});\n  VERIFY_IS_EQUAL(a(0), 100);\n  VERIFY_IS_EQUAL(a(1), 200);\n  VERIFY_IS_EQUAL(a(2), 300);\n  VERIFY_IS_EQUAL(a2(0), 100);\n  VERIFY_IS_EQUAL(a2(1), 200);\n  VERIFY_IS_EQUAL(a2(2), 300);\n\n  Tensor<int, 2> b(2, 3);\n  b.setValues({{0, 1, 2}, {3, 4, 5}});\n  VERIFY_IS_EQUAL(b(0, 0), 0);\n  VERIFY_IS_EQUAL(b(0, 1), 1);\n  VERIFY_IS_EQUAL(b(0, 2), 2);\n  VERIFY_IS_EQUAL(b(1, 0), 3);\n  VERIFY_IS_EQUAL(b(1, 1), 4);\n  VERIFY_IS_EQUAL(b(1, 2), 5);\n\n  // It fills the top-left slice.\n  b.setValues({{10, 20}, {30}});\n  VERIFY_IS_EQUAL(b(0, 0), 10);\n  VERIFY_IS_EQUAL(b(0, 1), 20);\n  VERIFY_IS_EQUAL(b(0, 2), 2);\n  VERIFY_IS_EQUAL(b(1, 0), 30);\n  VERIFY_IS_EQUAL(b(1, 1), 4);\n  VERIFY_IS_EQUAL(b(1, 2), 5);\n\n  Eigen::Tensor<int, 3> c(3, 2, 4);\n  c.setValues({{{0, 1, 2, 3}, {4, 5, 6, 7}},\n               {{10, 11, 12, 13}, {14, 15, 16, 17}},\n               {{20, 21, 22, 23}, {24, 25, 26, 27}}});\n  VERIFY_IS_EQUAL(c(0, 0, 0), 0);\n  VERIFY_IS_EQUAL(c(0, 0, 1), 1);\n  VERIFY_IS_EQUAL(c(0, 0, 2), 2);\n  VERIFY_IS_EQUAL(c(0, 0, 3), 3);\n  VERIFY_IS_EQUAL(c(0, 1, 0), 4);\n  VERIFY_IS_EQUAL(c(0, 1, 1), 5);\n  VERIFY_IS_EQUAL(c(0, 1, 2), 6);\n  VERIFY_IS_EQUAL(c(0, 1, 3), 7);\n  VERIFY_IS_EQUAL(c(1, 0, 0), 10);\n  VERIFY_IS_EQUAL(c(1, 0, 1), 11);\n  VERIFY_IS_EQUAL(c(1, 0, 2), 12);\n  VERIFY_IS_EQUAL(c(1, 0, 3), 13);\n  VERIFY_IS_EQUAL(c(1, 1, 0), 14);\n  VERIFY_IS_EQUAL(c(1, 1, 1), 15);\n  VERIFY_IS_EQUAL(c(1, 1, 2), 16);\n  VERIFY_IS_EQUAL(c(1, 1, 3), 17);\n  VERIFY_IS_EQUAL(c(2, 0, 0), 20);\n  VERIFY_IS_EQUAL(c(2, 0, 1), 21);\n  VERIFY_IS_EQUAL(c(2, 0, 2), 22);\n  VERIFY_IS_EQUAL(c(2, 0, 3), 23);\n  VERIFY_IS_EQUAL(c(2, 1, 0), 24);\n  VERIFY_IS_EQUAL(c(2, 1, 1), 25);\n  VERIFY_IS_EQUAL(c(2, 1, 2), 26);\n  VERIFY_IS_EQUAL(c(2, 1, 3), 27);\n#endif  // EIGEN_HAS_VARIADIC_TEMPLATES\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_assign)\n{\n  CALL_SUBTEST(test_1d());\n  CALL_SUBTEST(test_2d());\n  CALL_SUBTEST(test_3d());\n  CALL_SUBTEST(test_same_type());\n  CALL_SUBTEST(test_auto_resize());\n  CALL_SUBTEST(test_compound_assign());\n  CALL_SUBTEST(test_std_initializers_tensor());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_block_access.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2018 Andy Davis <andydavis@google.com>\n// Copyright (C) 2018 Eugene Zhulenev <ezhulenev@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <algorithm>\n#include <set>\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::Index;\nusing Eigen::RowMajor;\nusing Eigen::ColMajor;\nusing Eigen::internal::TensorBlockShapeType;\n\nstatic TensorOpCost zeroCost() { return {0, 0, 0}; }\n\ntemplate<typename T>\nstatic const T& choose(int layout, const T& col, const T& row) {\n  return layout == ColMajor ? col : row;\n}\n\nstatic TensorBlockShapeType RandomShape() {\n  return internal::random<bool>()\n         ? TensorBlockShapeType::kUniformAllDims\n         : TensorBlockShapeType::kSkewedInnerDims;\n}\n\ntemplate <int NumDims>\nstatic size_t RandomTargetSize(const DSizes<Index, NumDims>& dims) {\n  return internal::random<size_t>(1, dims.TotalSize());\n}\n\ntemplate <int NumDims>\nstatic DSizes<Index, NumDims> RandomDims() {\n  array<Index, NumDims> dims;\n  for (int i = 0; i < NumDims; ++i) {\n    dims[i] = internal::random<int>(1, 20);\n  }\n  return DSizes<Index, NumDims>(dims);\n}\n\ntemplate <typename T>\nstatic T* GenerateRandomData(const Index& size) {\n  T* data = new T[size];\n  for (int i = 0; i < size; ++i) {\n    data[i] = internal::random<T>();\n  }\n  return data;\n}\n\ntemplate <int NumDims>\nstatic void Debug(DSizes<Index, NumDims> dims) {\n  for (int i = 0; i < NumDims; ++i) {\n    std::cout << dims[i] << \"; \";\n  }\n  std::cout << std::endl;\n}\n\ntemplate <int Layout>\nstatic void test_block_mapper_sanity()\n{\n  typedef internal::TensorBlockMapper<2, Layout> TensorBlockMapper;\n\n  DSizes<Index, 2> tensor_dims(100, 100);\n\n  // Test uniform blocks.\n  TensorBlockMapper uniform_block_mapper(\n      tensor_dims, {TensorBlockShapeType::kUniformAllDims, 100, zeroCost()});\n\n  VERIFY_IS_EQUAL(uniform_block_mapper.blockCount(), 100);\n  VERIFY_IS_EQUAL(uniform_block_mapper.blockTotalSize(), 100);\n\n  // 10x10 blocks\n  auto uniform_b0 = uniform_block_mapper.blockDescriptor(0);\n  VERIFY_IS_EQUAL(uniform_b0.dimensions().at(0), 10);\n  VERIFY_IS_EQUAL(uniform_b0.dimensions().at(1), 10);\n\n  // Test skewed to inner dims blocks.\n  TensorBlockMapper skewed_block_mapper(\n      tensor_dims, {TensorBlockShapeType::kSkewedInnerDims, 100, zeroCost()});\n\n  VERIFY_IS_EQUAL(skewed_block_mapper.blockCount(), 100);\n  VERIFY_IS_EQUAL(skewed_block_mapper.blockTotalSize(), 100);\n\n  // 1x100 (100x1) rows/cols depending on a tensor layout.\n  auto skewed_b0 = skewed_block_mapper.blockDescriptor(0);\n  VERIFY_IS_EQUAL(skewed_b0.dimensions().at(0), choose(Layout, 100, 1));\n  VERIFY_IS_EQUAL(skewed_b0.dimensions().at(1), choose(Layout, 1, 100));\n}\n\n// Given a TensorBlock \"visit\" every element accessible though it, and a keep an\n// index in the visited set. Verify that every coeff accessed only once.\ntemplate<int NumDims, int Layout>\nstatic void UpdateCoeffSet(\n    const DSizes<Index, NumDims>& tensor_strides,\n    const internal::TensorBlockDescriptor<NumDims>& block,\n    Index first_coeff_index, int dim_index, std::set<Index>* visited_coeffs) {\n  const DSizes<Index, NumDims>& block_sizes = block.dimensions();\n\n  for (int i = 0; i < block_sizes[dim_index]; ++i) {\n    if (tensor_strides[dim_index] == 1) {\n      typedef std::pair<std::set<Index>::iterator, bool> ReturnType;\n      ReturnType inserted = visited_coeffs->insert(first_coeff_index + i);\n      VERIFY_IS_EQUAL(inserted.second, true);\n    } else {\n      int next_dim_index = dim_index + choose(Layout, -1, 1);\n      UpdateCoeffSet<NumDims, Layout>(tensor_strides, block, first_coeff_index,\n                                         next_dim_index, visited_coeffs);\n      first_coeff_index += tensor_strides[dim_index];\n    }\n  }\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_block_mapper_maps_every_element() {\n  typedef internal::TensorBlockMapper<NumDims, Layout> TensorBlockMapper;\n\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>();\n  DSizes<Index, NumDims> strides = internal::strides<Layout>(dims);\n\n  // Keep track of elements indices available via block access.\n  std::set<Index> coeff_set;\n\n  // Try different combinations of block types and sizes.\n  TensorBlockMapper block_mapper(\n      dims, {RandomShape(), RandomTargetSize(dims), zeroCost()});\n\n  for (int i = 0; i < block_mapper.blockCount(); ++i) {\n    auto block = block_mapper.blockDescriptor(i);\n    UpdateCoeffSet<NumDims, Layout>(strides, block, block.offset(),\n                                    choose(Layout, NumDims - 1, 0),\n                                    &coeff_set);\n  }\n\n  // Verify that every coefficient in the original Tensor is accessible through\n  // TensorBlock only once.\n  Index total_coeffs = dims.TotalSize();\n  VERIFY_IS_EQUAL(Index(coeff_set.size()), total_coeffs);\n  VERIFY_IS_EQUAL(*coeff_set.begin(), 0);\n  VERIFY_IS_EQUAL(*coeff_set.rbegin(), total_coeffs - 1);\n}\n\ntemplate <int Layout, int NumDims>\nstatic Index GetInputIndex(Index output_index,\n                         const array<Index, NumDims>& output_to_input_dim_map,\n                         const array<Index, NumDims>& input_strides,\n                         const array<Index, NumDims>& output_strides) {\n  int input_index = 0;\n  if (Layout == ColMajor) {\n    for (int i = NumDims - 1; i > 0; --i) {\n      const Index idx = output_index / output_strides[i];\n      input_index += idx * input_strides[output_to_input_dim_map[i]];\n      output_index -= idx * output_strides[i];\n    }\n    return input_index +\n           output_index * input_strides[output_to_input_dim_map[0]];\n  } else {\n    for (int i = 0; i < NumDims - 1; ++i) {\n      const Index idx = output_index / output_strides[i];\n      input_index += idx * input_strides[output_to_input_dim_map[i]];\n      output_index -= idx * output_strides[i];\n    }\n    return input_index +\n           output_index * input_strides[output_to_input_dim_map[NumDims - 1]];\n  }\n}\n\ntemplate <int Layout, int NumDims>\nstatic array<Index, NumDims> ComputeStrides(\n    const array<Index, NumDims>& sizes) {\n  array<Index, NumDims> strides;\n  if (Layout == ColMajor) {\n    strides[0] = 1;\n    for (int i = 1; i < NumDims; ++i) {\n      strides[i] = strides[i - 1] * sizes[i - 1];\n    }\n  } else {\n    strides[NumDims - 1] = 1;\n    for (int i = NumDims - 2; i >= 0; --i) {\n      strides[i] = strides[i + 1] * sizes[i + 1];\n    }\n  }\n  return strides;\n}\n\ntemplate<typename Scalar, typename StorageIndex, int Dim>\nclass EqualityChecker\n{\n    const Scalar* input_data;\n    const DSizes<StorageIndex, Dim> &input_dims, &input_strides, &output_dims, &output_strides;\n    void check_recursive(const Scalar* input, const Scalar* output, int depth=0) const\n    {\n        if(depth==Dim)\n        {\n            VERIFY_IS_EQUAL(*input, *output);\n            return;\n        }\n\n        for(int i=0; i<output_dims[depth]; ++i)\n        {\n            check_recursive(input + i % input_dims[depth] * input_strides[depth], output + i*output_strides[depth], depth+1);\n        }\n    }\npublic:\n    EqualityChecker(const Scalar* input_data_,\n            const DSizes<StorageIndex, Dim> &input_dims_, const DSizes<StorageIndex, Dim> &input_strides_,\n            const DSizes<StorageIndex, Dim> &output_dims_, const DSizes<StorageIndex, Dim> &output_strides_)\n        : input_data(input_data_)\n        , input_dims(input_dims_), input_strides(input_strides_)\n        , output_dims(output_dims_), output_strides(output_strides_)\n        {}\n\n    void operator()(const Scalar* output_data) const\n    {\n        check_recursive(input_data, output_data);\n    }\n};\n\ntemplate <int Layout>\nstatic void test_uniform_block_shape()\n{\n  typedef internal::TensorBlockDescriptor<5> TensorBlock;\n  typedef internal::TensorBlockMapper<5, Layout> TensorBlockMapper;\n\n  {\n    // Test shape 'UniformAllDims' with uniform 'max_coeff count'.\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 5 * 5 * 5 * 5 * 5;\n    TensorBlockMapper block_mapper(dims, {TensorBlockShapeType::kUniformAllDims,\n                                          max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    for (int i = 0; i < 5; ++i) {\n      VERIFY_IS_EQUAL(5, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  }\n\n  // Test shape 'UniformAllDims' with larger 'max_coeff count' which spills\n  // partially into first inner-most dimension.\n  if (Layout == ColMajor) {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 7 * 5 * 5 * 5 * 5;\n    TensorBlockMapper block_mapper(dims, {TensorBlockShapeType::kUniformAllDims,\n                                          max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(7, block.dimensions()[0]);\n    for (int i = 1; i < 5; ++i) {\n      VERIFY_IS_EQUAL(5, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  } else {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 5 * 5 * 5 * 5 * 6;\n    TensorBlockMapper block_mapper(dims, {TensorBlockShapeType::kUniformAllDims,\n                                          max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(6, block.dimensions()[4]);\n    for (int i = 3; i >= 0; --i) {\n      VERIFY_IS_EQUAL(5, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  }\n\n  // Test shape 'UniformAllDims' with larger 'max_coeff count' which spills\n  // fully into first inner-most dimension.\n  if (Layout == ColMajor) {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 11 * 5 * 5 * 5 * 5;\n    TensorBlockMapper block_mapper(dims, {TensorBlockShapeType::kUniformAllDims,\n                                          max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(11, block.dimensions()[0]);\n    for (int i = 1; i < 5; ++i) {\n      VERIFY_IS_EQUAL(5, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  } else {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 5 * 5 * 5 * 5 * 7;\n    TensorBlockMapper block_mapper(dims, {TensorBlockShapeType::kUniformAllDims,\n                                          max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(7, block.dimensions()[4]);\n    for (int i = 3; i >= 0; --i) {\n      VERIFY_IS_EQUAL(5, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  }\n\n  // Test shape 'UniformAllDims' with larger 'max_coeff count' which spills\n  // fully into first few inner-most dimensions.\n  if (Layout == ColMajor) {\n    DSizes<Index, 5> dims(7, 5, 6, 17, 7);\n    const Index max_coeff_count = 7 * 5 * 6 * 7 * 5;\n    TensorBlockMapper block_mapper(dims, {TensorBlockShapeType::kUniformAllDims,\n                                          max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(7, block.dimensions()[0]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[1]);\n    VERIFY_IS_EQUAL(6, block.dimensions()[2]);\n    VERIFY_IS_EQUAL(7, block.dimensions()[3]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[4]);\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  } else {\n    DSizes<Index, 5> dims(7, 5, 6, 9, 7);\n    const Index max_coeff_count = 5 * 5 * 5 * 6 * 7;\n    TensorBlockMapper block_mapper(dims, {TensorBlockShapeType::kUniformAllDims,\n                                          max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(7, block.dimensions()[4]);\n    VERIFY_IS_EQUAL(6, block.dimensions()[3]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[2]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[1]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[0]);\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  }\n\n  // Test shape 'UniformAllDims' with full allocation to all dims.\n  if (Layout == ColMajor) {\n    DSizes<Index, 5> dims(7, 5, 6, 17, 7);\n    const Index max_coeff_count = 7 * 5 * 6 * 17 * 7;\n    TensorBlockMapper block_mapper(dims, {TensorBlockShapeType::kUniformAllDims,\n                                          max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(7, block.dimensions()[0]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[1]);\n    VERIFY_IS_EQUAL(6, block.dimensions()[2]);\n    VERIFY_IS_EQUAL(17, block.dimensions()[3]);\n    VERIFY_IS_EQUAL(7, block.dimensions()[4]);\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  } else {\n    DSizes<Index, 5> dims(7, 5, 6, 9, 7);\n    const Index max_coeff_count = 7 * 5 * 6 * 9 * 7;\n    TensorBlockMapper block_mapper(dims, {TensorBlockShapeType::kUniformAllDims,\n                                          max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(7, block.dimensions()[4]);\n    VERIFY_IS_EQUAL(9, block.dimensions()[3]);\n    VERIFY_IS_EQUAL(6, block.dimensions()[2]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[1]);\n    VERIFY_IS_EQUAL(7, block.dimensions()[0]);\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  }\n}\n\ntemplate <int Layout>\nstatic void test_skewed_inner_dim_block_shape()\n{\n  typedef internal::TensorBlockDescriptor<5> TensorBlock;\n  typedef internal::TensorBlockMapper<5, Layout> TensorBlockMapper;\n\n  // Test shape 'SkewedInnerDims' with partial allocation to inner-most dim.\n  if (Layout == ColMajor) {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 10 * 1 * 1 * 1 * 1;\n    TensorBlockMapper block_mapper(\n        dims,\n        {TensorBlockShapeType::kSkewedInnerDims, max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(10, block.dimensions()[0]);\n    for (int i = 1; i < 5; ++i) {\n      VERIFY_IS_EQUAL(1, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  } else {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 1 * 1 * 1 * 1 * 6;\n    TensorBlockMapper block_mapper(\n        dims,\n        {TensorBlockShapeType::kSkewedInnerDims, max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(6, block.dimensions()[4]);\n    for (int i = 3; i >= 0; --i) {\n      VERIFY_IS_EQUAL(1, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  }\n\n  // Test shape 'SkewedInnerDims' with full allocation to inner-most dim.\n  if (Layout == ColMajor) {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 11 * 1 * 1 * 1 * 1;\n    TensorBlockMapper block_mapper(\n        dims,\n        {TensorBlockShapeType::kSkewedInnerDims, max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(11, block.dimensions()[0]);\n    for (int i = 1; i < 5; ++i) {\n      VERIFY_IS_EQUAL(1, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  } else {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 1 * 1 * 1 * 1 * 7;\n    TensorBlockMapper block_mapper(\n        dims,\n        {TensorBlockShapeType::kSkewedInnerDims, max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(7, block.dimensions()[4]);\n    for (int i = 3; i >= 0; --i) {\n      VERIFY_IS_EQUAL(1, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  }\n\n  // Test shape 'SkewedInnerDims' with full allocation to inner-most dim,\n  // and partial allocation to second inner-dim.\n  if (Layout == ColMajor) {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 11 * 3 * 1 * 1 * 1;\n    TensorBlockMapper block_mapper(\n        dims,\n        {TensorBlockShapeType::kSkewedInnerDims, max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(11, block.dimensions()[0]);\n    VERIFY_IS_EQUAL(3, block.dimensions()[1]);\n    for (int i = 2; i < 5; ++i) {\n      VERIFY_IS_EQUAL(1, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  } else {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 1 * 1 * 1 * 15 * 7;\n    TensorBlockMapper block_mapper(\n        dims,\n        {TensorBlockShapeType::kSkewedInnerDims, max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(7, block.dimensions()[4]);\n    VERIFY_IS_EQUAL(15, block.dimensions()[3]);\n    for (int i = 2; i >= 0; --i) {\n      VERIFY_IS_EQUAL(1, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  }\n\n  // Test shape 'SkewedInnerDims' with full allocation to inner-most dim,\n  // and partial allocation to third inner-dim.\n  if (Layout == ColMajor) {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 11 * 5 * 5 * 1 * 1;\n    TensorBlockMapper block_mapper(\n        dims,\n        {TensorBlockShapeType::kSkewedInnerDims, max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(11, block.dimensions()[0]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[1]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[2]);\n    for (int i = 3; i < 5; ++i) {\n      VERIFY_IS_EQUAL(1, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  } else {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 1 * 1 * 5 * 17 * 7;\n    TensorBlockMapper block_mapper(\n        dims,\n        {TensorBlockShapeType::kSkewedInnerDims, max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(7, block.dimensions()[4]);\n    VERIFY_IS_EQUAL(17, block.dimensions()[3]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[2]);\n    for (int i = 1; i >= 0; --i) {\n      VERIFY_IS_EQUAL(1, block.dimensions()[i]);\n    }\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  }\n\n  // Test shape 'SkewedInnerDims' with full allocation to all dims.\n  if (Layout == ColMajor) {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 11 * 5 * 6 * 17 * 7;\n    TensorBlockMapper block_mapper(\n        dims,\n        {TensorBlockShapeType::kSkewedInnerDims, max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(11, block.dimensions()[0]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[1]);\n    VERIFY_IS_EQUAL(6, block.dimensions()[2]);\n    VERIFY_IS_EQUAL(17, block.dimensions()[3]);\n    VERIFY_IS_EQUAL(7, block.dimensions()[4]);\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  } else {\n    DSizes<Index, 5> dims(11, 5, 6, 17, 7);\n    const Index max_coeff_count = 11 * 5 * 6 * 17 * 7;\n    TensorBlockMapper block_mapper(\n        dims,\n        {TensorBlockShapeType::kSkewedInnerDims, max_coeff_count, zeroCost()});\n    TensorBlock block = block_mapper.blockDescriptor(0);\n    VERIFY_IS_EQUAL(7, block.dimensions()[4]);\n    VERIFY_IS_EQUAL(17, block.dimensions()[3]);\n    VERIFY_IS_EQUAL(6, block.dimensions()[2]);\n    VERIFY_IS_EQUAL(5, block.dimensions()[1]);\n    VERIFY_IS_EQUAL(11, block.dimensions()[0]);\n    VERIFY(block.dimensions().TotalSize() <= max_coeff_count);\n  }\n}\n\ntemplate <int Layout>\nstatic void test_empty_dims(const internal::TensorBlockShapeType block_shape)\n{\n  // Test blocking of tensors with zero dimensions:\n  //  - we must not crash on asserts and divisions by zero\n  //  - we must not return block with zero dimensions\n  //    (recipe for overflows/underflows, divisions by zero and NaNs later)\n  //  - total block count must be zero\n  {\n    typedef internal::TensorBlockMapper<1, Layout> TensorBlockMapper;\n\n    DSizes<Index, 1> dims(0);\n    for (size_t max_coeff_count = 0; max_coeff_count < 2; ++max_coeff_count) {\n      TensorBlockMapper block_mapper(\n          dims, {block_shape, max_coeff_count, zeroCost()});\n      VERIFY_IS_EQUAL(block_mapper.blockCount(), 0);\n      VERIFY(block_mapper.blockTotalSize() >= 1);\n    }\n  }\n\n  {\n    typedef internal::TensorBlockMapper<2, Layout> TensorBlockMapper;\n\n    for (int dim1 = 0; dim1 < 3; ++dim1) {\n      for (int dim2 = 0; dim2 < 3; ++dim2) {\n        DSizes<Index, 2> dims(dim1, dim2);\n        for (size_t max_coeff_count = 0; max_coeff_count < 2; ++max_coeff_count) {\n          TensorBlockMapper block_mapper(\n              dims, {block_shape, max_coeff_count, zeroCost()});\n          if (dim1 * dim2 == 0) {\n            VERIFY_IS_EQUAL(block_mapper.blockCount(), 0);\n          }\n          VERIFY(block_mapper.blockTotalSize() >= 1);\n        }\n      }\n    }\n  }\n}\n\n#define TEST_LAYOUTS(NAME) \\\n  CALL_SUBTEST(NAME<ColMajor>()); \\\n  CALL_SUBTEST(NAME<RowMajor>())\n\n#define TEST_LAYOUTS_AND_DIMS(TYPE, NAME)    \\\n  CALL_SUBTEST((NAME<TYPE, 1, ColMajor>())); \\\n  CALL_SUBTEST((NAME<TYPE, 1, RowMajor>())); \\\n  CALL_SUBTEST((NAME<TYPE, 2, ColMajor>())); \\\n  CALL_SUBTEST((NAME<TYPE, 2, RowMajor>())); \\\n  CALL_SUBTEST((NAME<TYPE, 3, ColMajor>())); \\\n  CALL_SUBTEST((NAME<TYPE, 3, RowMajor>())); \\\n  CALL_SUBTEST((NAME<TYPE, 4, ColMajor>())); \\\n  CALL_SUBTEST((NAME<TYPE, 4, RowMajor>())); \\\n  CALL_SUBTEST((NAME<TYPE, 5, ColMajor>())); \\\n  CALL_SUBTEST((NAME<TYPE, 5, RowMajor>()))\n\n#define TEST_LAYOUTS_WITH_ARG(NAME, ARG) \\\n  CALL_SUBTEST(NAME<ColMajor>(ARG)); \\\n  CALL_SUBTEST(NAME<RowMajor>(ARG))\n\nEIGEN_DECLARE_TEST(cxx11_tensor_block_access) {\n  TEST_LAYOUTS(test_block_mapper_sanity);\n  TEST_LAYOUTS_AND_DIMS(float, test_block_mapper_maps_every_element);\n  TEST_LAYOUTS(test_uniform_block_shape);\n  TEST_LAYOUTS(test_skewed_inner_dim_block_shape);\n  TEST_LAYOUTS_WITH_ARG(test_empty_dims, TensorBlockShapeType::kUniformAllDims);\n  TEST_LAYOUTS_WITH_ARG(test_empty_dims, TensorBlockShapeType::kSkewedInnerDims);\n}\n\n#undef TEST_LAYOUTS\n#undef TEST_LAYOUTS_WITH_ARG\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_block_eval.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// clang-format off\n#include \"main.h\"\n#include <Eigen/CXX11/Tensor>\n// clang-format on\n\nusing Eigen::internal::TensorBlockDescriptor;\nusing Eigen::internal::TensorExecutor;\n\n// -------------------------------------------------------------------------- //\n// Utility functions to generate random tensors, blocks, and evaluate them.\n\ntemplate <int NumDims>\nstatic DSizes<Index, NumDims> RandomDims(Index min, Index max) {\n  DSizes<Index, NumDims> dims;\n  for (int i = 0; i < NumDims; ++i) {\n    dims[i] = internal::random<Index>(min, max);\n  }\n  return DSizes<Index, NumDims>(dims);\n}\n\n// Block offsets and extents allows to construct a TensorSlicingOp corresponding\n// to a TensorBlockDescriptor.\ntemplate <int NumDims>\nstruct TensorBlockParams {\n  DSizes<Index, NumDims> offsets;\n  DSizes<Index, NumDims> sizes;\n  TensorBlockDescriptor<NumDims, Index> desc;\n};\n\ntemplate <int Layout, int NumDims>\nstatic TensorBlockParams<NumDims> RandomBlock(DSizes<Index, NumDims> dims,\n                                              Index min, Index max) {\n  // Choose random offsets and sizes along all tensor dimensions.\n  DSizes<Index, NumDims> offsets(RandomDims<NumDims>(min, max));\n  DSizes<Index, NumDims> sizes(RandomDims<NumDims>(min, max));\n\n  // Make sure that offset + size do not overflow dims.\n  for (int i = 0; i < NumDims; ++i) {\n    offsets[i] = numext::mini(dims[i] - 1, offsets[i]);\n    sizes[i] = numext::mini(sizes[i], dims[i] - offsets[i]);\n  }\n\n  Index offset = 0;\n  DSizes<Index, NumDims> strides = Eigen::internal::strides<Layout>(dims);\n  for (int i = 0; i < NumDims; ++i) {\n    offset += strides[i] * offsets[i];\n  }\n\n  return {offsets, sizes, TensorBlockDescriptor<NumDims, Index>(offset, sizes)};\n}\n\n// Generate block with block sizes skewed towards inner dimensions. This type of\n// block is required for evaluating broadcast expressions.\ntemplate <int Layout, int NumDims>\nstatic TensorBlockParams<NumDims> SkewedInnerBlock(\n    DSizes<Index, NumDims> dims) {\n  using BlockMapper = internal::TensorBlockMapper<NumDims, Layout, Index>;\n  BlockMapper block_mapper(dims,\n                           {internal::TensorBlockShapeType::kSkewedInnerDims,\n                            internal::random<size_t>(1, dims.TotalSize()),\n                            {0, 0, 0}});\n\n  Index total_blocks = block_mapper.blockCount();\n  Index block_index = internal::random<Index>(0, total_blocks - 1);\n  auto block = block_mapper.blockDescriptor(block_index);\n  DSizes<Index, NumDims> sizes = block.dimensions();\n\n  auto strides = internal::strides<Layout>(dims);\n  DSizes<Index, NumDims> offsets;\n\n  // Compute offsets for the first block coefficient.\n  Index index = block.offset();\n  if (static_cast<int>(Layout) == static_cast<int>(ColMajor)) {\n    for (int i = NumDims - 1; i > 0; --i) {\n      const Index idx = index / strides[i];\n      index -= idx * strides[i];\n      offsets[i] = idx;\n    }\n    if (NumDims > 0) offsets[0] = index;\n  } else {\n    for (int i = 0; i < NumDims - 1; ++i) {\n      const Index idx = index / strides[i];\n      index -= idx * strides[i];\n      offsets[i] = idx;\n    }\n    if (NumDims > 0) offsets[NumDims - 1] = index;\n  }\n\n  return {offsets, sizes, block};\n}\n\ntemplate <int NumDims>\nstatic TensorBlockParams<NumDims> FixedSizeBlock(DSizes<Index, NumDims> dims) {\n  DSizes<Index, NumDims> offsets;\n  for (int i = 0; i < NumDims; ++i) offsets[i] = 0;\n\n  return {offsets, dims, TensorBlockDescriptor<NumDims, Index>(0, dims)};\n}\n\ninline Eigen::IndexList<Index, Eigen::type2index<1>> NByOne(Index n) {\n  Eigen::IndexList<Index, Eigen::type2index<1>> ret;\n  ret.set(0, n);\n  return ret;\n}\ninline Eigen::IndexList<Eigen::type2index<1>, Index> OneByM(Index m) {\n  Eigen::IndexList<Eigen::type2index<1>, Index> ret;\n  ret.set(1, m);\n  return ret;\n}\n\n// -------------------------------------------------------------------------- //\n// Verify that block expression evaluation produces the same result as a\n// TensorSliceOp (reading a tensor block is same to taking a tensor slice).\n\ntemplate <typename T, int NumDims, int Layout, typename Expression,\n          typename GenBlockParams>\nstatic void VerifyBlockEvaluator(Expression expr, GenBlockParams gen_block) {\n  using Device = DefaultDevice;\n  auto d = Device();\n\n  // Scratch memory allocator for block evaluation.\n  typedef internal::TensorBlockScratchAllocator<Device> TensorBlockScratch;\n  TensorBlockScratch scratch(d);\n\n  // TensorEvaluator is needed to produce tensor blocks of the expression.\n  auto eval = TensorEvaluator<const decltype(expr), Device>(expr, d);\n  eval.evalSubExprsIfNeeded(nullptr);\n\n  // Choose a random offsets, sizes and TensorBlockDescriptor.\n  TensorBlockParams<NumDims> block_params = gen_block();\n\n  // Evaluate TensorBlock expression into a tensor.\n  Tensor<T, NumDims, Layout> block(block_params.desc.dimensions());\n\n  // Dimensions for the potential destination buffer.\n  DSizes<Index, NumDims> dst_dims;\n  if (internal::random<bool>()) {\n    dst_dims = block_params.desc.dimensions();\n  } else {\n    for (int i = 0; i < NumDims; ++i) {\n      Index extent = internal::random<Index>(0, 5);\n      dst_dims[i] = block_params.desc.dimension(i) + extent;\n    }\n  }\n\n  // Maybe use this tensor as a block desc destination.\n  Tensor<T, NumDims, Layout> dst(dst_dims);\n  dst.setZero();\n  if (internal::random<bool>()) {\n    block_params.desc.template AddDestinationBuffer<Layout>(\n        dst.data(), internal::strides<Layout>(dst.dimensions()));\n  }\n\n  const bool root_of_expr = internal::random<bool>();\n  auto tensor_block = eval.block(block_params.desc, scratch, root_of_expr);\n\n  if (tensor_block.kind() == internal::TensorBlockKind::kMaterializedInOutput) {\n    // Copy data from destination buffer.\n    if (dimensions_match(dst.dimensions(), block.dimensions())) {\n      block = dst;\n    } else {\n      DSizes<Index, NumDims> offsets;\n      for (int i = 0; i < NumDims; ++i) offsets[i] = 0;\n      block = dst.slice(offsets, block.dimensions());\n    }\n\n  } else {\n    // Assign to block from expression.\n    auto b_expr = tensor_block.expr();\n\n    // We explicitly disable vectorization and tiling, to run a simple coefficient\n    // wise assignment loop, because it's very simple and should be correct.\n    using BlockAssign = TensorAssignOp<decltype(block), const decltype(b_expr)>;\n    using BlockExecutor = TensorExecutor<const BlockAssign, Device, false,\n                                         internal::TiledEvaluation::Off>;\n    BlockExecutor::run(BlockAssign(block, b_expr), d);\n  }\n\n  // Cleanup temporary buffers owned by a tensor block.\n  tensor_block.cleanup();\n\n  // Compute a Tensor slice corresponding to a Tensor block.\n  Tensor<T, NumDims, Layout> slice(block_params.desc.dimensions());\n  auto s_expr = expr.slice(block_params.offsets, block_params.sizes);\n\n  // Explicitly use coefficient assignment to evaluate slice expression.\n  using SliceAssign = TensorAssignOp<decltype(slice), const decltype(s_expr)>;\n  using SliceExecutor = TensorExecutor<const SliceAssign, Device, false,\n                                       internal::TiledEvaluation::Off>;\n  SliceExecutor::run(SliceAssign(slice, s_expr), d);\n\n  // Tensor block and tensor slice must be the same.\n  for (Index i = 0; i < block.dimensions().TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(block.coeff(i), slice.coeff(i));\n  }\n}\n\n// -------------------------------------------------------------------------- //\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_block() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  // Identity tensor expression transformation.\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input, [&dims]() { return RandomBlock<Layout>(dims, 1, 10); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_unary_expr_block() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.abs(), [&dims]() { return RandomBlock<Layout>(dims, 1, 10); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_binary_expr_block() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> lhs(dims), rhs(dims);\n  lhs.setRandom();\n  rhs.setRandom();\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      lhs * rhs, [&dims]() { return RandomBlock<Layout>(dims, 1, 10); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_binary_with_unary_expr_block() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> lhs(dims), rhs(dims);\n  lhs.setRandom();\n  rhs.setRandom();\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      (lhs.square() + rhs.square()).sqrt(),\n      [&dims]() { return RandomBlock<Layout>(dims, 1, 10); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_broadcast() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(1, 10);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  DSizes<Index, NumDims> bcast = RandomDims<NumDims>(1, 5);\n\n  DSizes<Index, NumDims> bcasted_dims;\n  for (int i = 0; i < NumDims; ++i) bcasted_dims[i] = dims[i] * bcast[i];\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.broadcast(bcast),\n      [&bcasted_dims]() { return SkewedInnerBlock<Layout>(bcasted_dims); });\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.broadcast(bcast),\n      [&bcasted_dims]() { return RandomBlock<Layout>(bcasted_dims, 5, 10); });\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.broadcast(bcast),\n      [&bcasted_dims]() { return FixedSizeBlock(bcasted_dims); });\n\n  // Check that desc.destination() memory is not shared between two broadcast\n  // materializations.\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.broadcast(bcast) * input.abs().broadcast(bcast),\n      [&bcasted_dims]() { return SkewedInnerBlock<Layout>(bcasted_dims); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_reshape() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(1, 10);\n\n  DSizes<Index, NumDims> shuffled = dims;\n  std::shuffle(&shuffled[0], &shuffled[NumDims - 1], std::mt19937(g_seed));\n\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.reshape(shuffled),\n      [&shuffled]() { return RandomBlock<Layout>(shuffled, 1, 10); });\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.reshape(shuffled),\n      [&shuffled]() { return SkewedInnerBlock<Layout>(shuffled); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_cast() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.template cast<int>().template cast<T>(),\n      [&dims]() { return RandomBlock<Layout>(dims, 1, 10); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_select() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> lhs(dims);\n  Tensor<T, NumDims, Layout> rhs(dims);\n  Tensor<bool, NumDims, Layout> cond(dims);\n  lhs.setRandom();\n  rhs.setRandom();\n  cond.setRandom();\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(cond.select(lhs, rhs), [&dims]() {\n    return RandomBlock<Layout>(dims, 1, 20);\n  });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_padding() {\n  const int inner_dim = Layout == static_cast<int>(ColMajor) ? 0 : NumDims - 1;\n\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  DSizes<Index, NumDims> pad_before = RandomDims<NumDims>(0, 4);\n  DSizes<Index, NumDims> pad_after = RandomDims<NumDims>(0, 4);\n  array<std::pair<Index, Index>, NumDims> paddings;\n  for (int i = 0; i < NumDims; ++i) {\n    paddings[i] = std::make_pair(pad_before[i], pad_after[i]);\n  }\n\n  // Test squeezing reads from inner dim.\n  if (internal::random<bool>()) {\n    pad_before[inner_dim] = 0;\n    pad_after[inner_dim] = 0;\n    paddings[inner_dim] = std::make_pair(0, 0);\n  }\n\n  DSizes<Index, NumDims> padded_dims;\n  for (int i = 0; i < NumDims; ++i) {\n    padded_dims[i] = dims[i] + pad_before[i] + pad_after[i];\n  }\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.pad(paddings),\n      [&padded_dims]() { return FixedSizeBlock(padded_dims); });\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.pad(paddings),\n      [&padded_dims]() { return RandomBlock<Layout>(padded_dims, 1, 10); });\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.pad(paddings),\n      [&padded_dims]() { return SkewedInnerBlock<Layout>(padded_dims); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_chipping() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  Index chip_dim = internal::random<int>(0, NumDims - 1);\n  Index chip_offset = internal::random<Index>(0, dims[chip_dim] - 2);\n\n  DSizes<Index, NumDims - 1> chipped_dims;\n  for (Index i = 0; i < chip_dim; ++i) {\n    chipped_dims[i] = dims[i];\n  }\n  for (Index i = chip_dim + 1; i < NumDims; ++i) {\n    chipped_dims[i - 1] = dims[i];\n  }\n\n  // Block buffer forwarding.\n  VerifyBlockEvaluator<T, NumDims - 1, Layout>(\n      input.chip(chip_offset, chip_dim),\n      [&chipped_dims]() { return FixedSizeBlock(chipped_dims); });\n\n  VerifyBlockEvaluator<T, NumDims - 1, Layout>(\n      input.chip(chip_offset, chip_dim),\n      [&chipped_dims]() { return RandomBlock<Layout>(chipped_dims, 1, 10); });\n\n  // Block expression assignment.\n  VerifyBlockEvaluator<T, NumDims - 1, Layout>(\n      input.abs().chip(chip_offset, chip_dim),\n      [&chipped_dims]() { return FixedSizeBlock(chipped_dims); });\n\n  VerifyBlockEvaluator<T, NumDims - 1, Layout>(\n      input.abs().chip(chip_offset, chip_dim),\n      [&chipped_dims]() { return RandomBlock<Layout>(chipped_dims, 1, 10); });\n}\n\n\ntemplate<typename T, int NumDims>\nstruct SimpleTensorGenerator {\n  T operator()(const array<Index, NumDims>& coords) const {\n    T result = static_cast<T>(0);\n    for (int i = 0; i < NumDims; ++i) {\n      result += static_cast<T>((i + 1) * coords[i]);\n    }\n    return result;\n  }\n};\n\n// Boolean specialization to avoid -Wint-in-bool-context warnings on GCC.\ntemplate<int NumDims>\nstruct SimpleTensorGenerator<bool, NumDims> {\n  bool operator()(const array<Index, NumDims>& coords) const {\n    bool result = false;\n    for (int i = 0; i < NumDims; ++i) {\n      result ^= coords[i];\n    }\n    return result;\n  }\n};\n\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_generator() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  auto generator = SimpleTensorGenerator<T, NumDims>();\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.generate(generator), [&dims]() { return FixedSizeBlock(dims); });\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.generate(generator),\n      [&dims]() { return RandomBlock<Layout>(dims, 1, 10); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_reverse() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  // Randomly reverse dimensions.\n  Eigen::DSizes<bool, NumDims> reverse;\n  for (int i = 0; i < NumDims; ++i) reverse[i] = internal::random<bool>();\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.reverse(reverse), [&dims]() { return FixedSizeBlock(dims); });\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(input.reverse(reverse), [&dims]() {\n    return RandomBlock<Layout>(dims, 1, 10);\n  });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_slice() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  // Pick a random slice of an input tensor.\n  DSizes<Index, NumDims> slice_start = RandomDims<NumDims>(5, 10);\n  DSizes<Index, NumDims> slice_size = RandomDims<NumDims>(5, 10);\n\n  // Make sure that slice start + size do not overflow tensor dims.\n  for (int i = 0; i < NumDims; ++i) {\n    slice_start[i] = numext::mini(dims[i] - 1, slice_start[i]);\n    slice_size[i] = numext::mini(slice_size[i], dims[i] - slice_start[i]);\n  }\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.slice(slice_start, slice_size),\n      [&slice_size]() { return FixedSizeBlock(slice_size); });\n\n  VerifyBlockEvaluator<T, NumDims, Layout>(\n      input.slice(slice_start, slice_size),\n      [&slice_size]() { return RandomBlock<Layout>(slice_size, 1, 10); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_eval_tensor_shuffle() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(5, 15);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  DSizes<Index, NumDims> shuffle;\n  for (int i = 0; i < NumDims; ++i) shuffle[i] = i;\n\n  do {\n    DSizes<Index, NumDims> shuffled_dims;\n    for (int i = 0; i < NumDims; ++i) shuffled_dims[i] = dims[shuffle[i]];\n\n    VerifyBlockEvaluator<T, NumDims, Layout>(\n        input.shuffle(shuffle),\n        [&shuffled_dims]() { return FixedSizeBlock(shuffled_dims); });\n\n    VerifyBlockEvaluator<T, NumDims, Layout>(\n        input.shuffle(shuffle), [&shuffled_dims]() {\n          return RandomBlock<Layout>(shuffled_dims, 1, 5);\n        });\n\n    break;\n\n  } while (std::next_permutation(&shuffle[0], &shuffle[0] + NumDims));\n}\n\ntemplate <typename T, int Layout>\nstatic void test_eval_tensor_reshape_with_bcast() {\n  Index dim = internal::random<Index>(1, 100);\n\n  Tensor<T, 2, Layout> lhs(1, dim);\n  Tensor<T, 2, Layout> rhs(dim, 1);\n  lhs.setRandom();\n  rhs.setRandom();\n\n  auto reshapeLhs = NByOne(dim);\n  auto reshapeRhs = OneByM(dim);\n\n  auto bcastLhs = OneByM(dim);\n  auto bcastRhs = NByOne(dim);\n\n  DSizes<Index, 2> dims(dim, dim);\n\n  VerifyBlockEvaluator<T, 2, Layout>(\n      lhs.reshape(reshapeLhs).broadcast(bcastLhs) *\n          rhs.reshape(reshapeRhs).broadcast(bcastRhs),\n      [dims]() { return SkewedInnerBlock<Layout, 2>(dims); });\n}\n\ntemplate <typename T, int Layout>\nstatic void test_eval_tensor_forced_eval() {\n  Index dim = internal::random<Index>(1, 100);\n\n  Tensor<T, 2, Layout> lhs(dim, 1);\n  Tensor<T, 2, Layout> rhs(1, dim);\n  lhs.setRandom();\n  rhs.setRandom();\n\n  auto bcastLhs = OneByM(dim);\n  auto bcastRhs = NByOne(dim);\n\n  DSizes<Index, 2> dims(dim, dim);\n\n  VerifyBlockEvaluator<T, 2, Layout>(\n      (lhs.broadcast(bcastLhs) * rhs.broadcast(bcastRhs)).eval().reshape(dims),\n      [dims]() { return SkewedInnerBlock<Layout, 2>(dims); });\n\n  VerifyBlockEvaluator<T, 2, Layout>(\n      (lhs.broadcast(bcastLhs) * rhs.broadcast(bcastRhs)).eval().reshape(dims),\n      [dims]() { return RandomBlock<Layout, 2>(dims, 1, 50); });\n}\n\ntemplate <typename T, int Layout>\nstatic void test_eval_tensor_chipping_of_bcast() {\n  if (Layout != static_cast<int>(RowMajor)) return;\n\n  Index dim0 = internal::random<Index>(1, 10);\n  Index dim1 = internal::random<Index>(1, 10);\n  Index dim2 = internal::random<Index>(1, 10);\n\n  Tensor<T, 3, Layout> input(1, dim1, dim2);\n  input.setRandom();\n\n  Eigen::array<Index, 3> bcast = {{dim0, 1, 1}};\n  DSizes<Index, 2> chipped_dims(dim0, dim2);\n\n  VerifyBlockEvaluator<T, 2, Layout>(\n      input.broadcast(bcast).chip(0, 1),\n      [chipped_dims]() { return FixedSizeBlock(chipped_dims); });\n\n  VerifyBlockEvaluator<T, 2, Layout>(\n      input.broadcast(bcast).chip(0, 1),\n      [chipped_dims]() { return SkewedInnerBlock<Layout, 2>(chipped_dims); });\n\n  VerifyBlockEvaluator<T, 2, Layout>(\n      input.broadcast(bcast).chip(0, 1),\n      [chipped_dims]() { return RandomBlock<Layout, 2>(chipped_dims, 1, 5); });\n}\n\n// -------------------------------------------------------------------------- //\n// Verify that assigning block to a Tensor expression produces the same result\n// as an assignment to TensorSliceOp (writing a block is is identical to\n// assigning one tensor to a slice of another tensor).\n\ntemplate <typename T, int NumDims, int Layout, int NumExprDims = NumDims,\n          typename Expression, typename GenBlockParams>\nstatic void VerifyBlockAssignment(Tensor<T, NumDims, Layout>& tensor,\n                                  Expression expr, GenBlockParams gen_block) {\n  using Device = DefaultDevice;\n  auto d = Device();\n\n  // We use tensor evaluator as a target for block and slice assignments.\n  auto eval = TensorEvaluator<decltype(expr), Device>(expr, d);\n\n  // Generate a random block, or choose a block that fits in full expression.\n  TensorBlockParams<NumExprDims> block_params = gen_block();\n\n  // Generate random data of the selected block size.\n  Tensor<T, NumExprDims, Layout> block(block_params.desc.dimensions());\n  block.setRandom();\n\n  // ************************************************************************ //\n  // (1) Assignment from a block.\n\n  // Construct a materialize block from a random generated block tensor.\n  internal::TensorMaterializedBlock<T, NumExprDims, Layout> blk(\n      internal::TensorBlockKind::kView, block.data(), block.dimensions());\n\n  // Reset all underlying tensor values to zero.\n  tensor.setZero();\n\n  // Use evaluator to write block into a tensor.\n  eval.writeBlock(block_params.desc, blk);\n\n  // Make a copy of the result after assignment.\n  Tensor<T, NumDims, Layout> block_assigned = tensor;\n\n  // ************************************************************************ //\n  // (2) Assignment to a slice\n\n  // Reset all underlying tensor values to zero.\n  tensor.setZero();\n\n  // Assign block to a slice of original expression\n  auto s_expr = expr.slice(block_params.offsets, block_params.sizes);\n\n  // Explicitly use coefficient assignment to evaluate slice expression.\n  using SliceAssign = TensorAssignOp<decltype(s_expr), const decltype(block)>;\n  using SliceExecutor = TensorExecutor<const SliceAssign, Device, false,\n                                       internal::TiledEvaluation::Off>;\n  SliceExecutor::run(SliceAssign(s_expr, block), d);\n\n  // Make a copy of the result after assignment.\n  Tensor<T, NumDims, Layout> slice_assigned = tensor;\n\n  for (Index i = 0; i < tensor.dimensions().TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(block_assigned.coeff(i), slice_assigned.coeff(i));\n  }\n}\n\n// -------------------------------------------------------------------------- //\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_assign_to_tensor() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> tensor(dims);\n\n  TensorMap<Tensor<T, NumDims, Layout>> map(tensor.data(), dims);\n\n  VerifyBlockAssignment<T, NumDims, Layout>(\n      tensor, map, [&dims]() { return RandomBlock<Layout>(dims, 10, 20); });\n  VerifyBlockAssignment<T, NumDims, Layout>(\n      tensor, map, [&dims]() { return FixedSizeBlock(dims); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_assign_to_tensor_reshape() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> tensor(dims);\n\n  TensorMap<Tensor<T, NumDims, Layout>> map(tensor.data(), dims);\n\n  DSizes<Index, NumDims> shuffled = dims;\n  std::shuffle(&shuffled[0], &shuffled[NumDims - 1], std::mt19937(g_seed));\n\n  VerifyBlockAssignment<T, NumDims, Layout>(\n      tensor, map.reshape(shuffled),\n      [&shuffled]() { return RandomBlock<Layout>(shuffled, 1, 10); });\n\n  VerifyBlockAssignment<T, NumDims, Layout>(\n      tensor, map.reshape(shuffled),\n      [&shuffled]() { return SkewedInnerBlock<Layout>(shuffled); });\n\n  VerifyBlockAssignment<T, NumDims, Layout>(\n      tensor, map.reshape(shuffled),\n      [&shuffled]() { return FixedSizeBlock(shuffled); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_assign_to_tensor_chipping() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> tensor(dims);\n\n  Index chip_dim = internal::random<int>(0, NumDims - 1);\n  Index chip_offset = internal::random<Index>(0, dims[chip_dim] - 2);\n\n  DSizes<Index, NumDims - 1> chipped_dims;\n  for (Index i = 0; i < chip_dim; ++i) {\n    chipped_dims[i] = dims[i];\n  }\n  for (Index i = chip_dim + 1; i < NumDims; ++i) {\n    chipped_dims[i - 1] = dims[i];\n  }\n\n  TensorMap<Tensor<T, NumDims, Layout>> map(tensor.data(), dims);\n\n  VerifyBlockAssignment<T, NumDims, Layout, NumDims - 1>(\n      tensor, map.chip(chip_offset, chip_dim),\n      [&chipped_dims]() { return RandomBlock<Layout>(chipped_dims, 1, 10); });\n\n  VerifyBlockAssignment<T, NumDims, Layout, NumDims - 1>(\n      tensor, map.chip(chip_offset, chip_dim),\n      [&chipped_dims]() { return SkewedInnerBlock<Layout>(chipped_dims); });\n\n  VerifyBlockAssignment<T, NumDims, Layout, NumDims - 1>(\n      tensor, map.chip(chip_offset, chip_dim),\n      [&chipped_dims]() { return FixedSizeBlock(chipped_dims); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_assign_to_tensor_slice() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(10, 20);\n  Tensor<T, NumDims, Layout> tensor(dims);\n\n  // Pick a random slice of tensor.\n  DSizes<Index, NumDims> slice_start = RandomDims<NumDims>(5, 10);\n  DSizes<Index, NumDims> slice_size = RandomDims<NumDims>(5, 10);\n\n  // Make sure that slice start + size do not overflow tensor dims.\n  for (int i = 0; i < NumDims; ++i) {\n    slice_start[i] = numext::mini(dims[i] - 1, slice_start[i]);\n    slice_size[i] = numext::mini(slice_size[i], dims[i] - slice_start[i]);\n  }\n\n  TensorMap<Tensor<T, NumDims, Layout>> map(tensor.data(), dims);\n\n  VerifyBlockAssignment<T, NumDims, Layout>(\n      tensor, map.slice(slice_start, slice_size),\n      [&slice_size]() { return RandomBlock<Layout>(slice_size, 1, 10); });\n\n  VerifyBlockAssignment<T, NumDims, Layout>(\n      tensor, map.slice(slice_start, slice_size),\n      [&slice_size]() { return SkewedInnerBlock<Layout>(slice_size); });\n\n  VerifyBlockAssignment<T, NumDims, Layout>(\n      tensor, map.slice(slice_start, slice_size),\n      [&slice_size]() { return FixedSizeBlock(slice_size); });\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_assign_to_tensor_shuffle() {\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(5, 15);\n  Tensor<T, NumDims, Layout> tensor(dims);\n\n  DSizes<Index, NumDims> shuffle;\n  for (int i = 0; i < NumDims; ++i) shuffle[i] = i;\n\n  TensorMap<Tensor<T, NumDims, Layout>> map(tensor.data(), dims);\n\n  do {\n    DSizes<Index, NumDims> shuffled_dims;\n    for (int i = 0; i < NumDims; ++i) shuffled_dims[i] = dims[shuffle[i]];\n\n    VerifyBlockAssignment<T, NumDims, Layout>(\n        tensor, map.shuffle(shuffle),\n        [&shuffled_dims]() { return FixedSizeBlock(shuffled_dims); });\n\n    VerifyBlockAssignment<T, NumDims, Layout>(\n        tensor, map.shuffle(shuffle), [&shuffled_dims]() {\n          return RandomBlock<Layout>(shuffled_dims, 1, 5);\n        });\n\n  } while (std::next_permutation(&shuffle[0], &shuffle[0] + NumDims));\n}\n\n// -------------------------------------------------------------------------- //\n\n#define CALL_SUBTEST_PART(PART) \\\n  CALL_SUBTEST_##PART\n\n#define CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(PART, NAME)           \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 1, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 2, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 3, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 4, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 5, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 1, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 2, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 4, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 4, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 5, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<int, 1, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<int, 2, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<int, 3, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<int, 4, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<int, 5, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<int, 1, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<int, 2, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<int, 4, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<int, 4, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<int, 5, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, 1, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, 2, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, 3, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, 4, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, 5, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, 1, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, 2, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, 4, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, 4, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, 5, ColMajor>()))\n\n#define CALL_SUBTESTS_DIMS_LAYOUTS(PART, NAME)     \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 1, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 2, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 3, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 4, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 5, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 1, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 2, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 4, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 4, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, 5, ColMajor>()))\n\n#define CALL_SUBTESTS_LAYOUTS_TYPES(PART, NAME)       \\\n  CALL_SUBTEST_PART(PART)((NAME<float, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, ColMajor>()));  \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, ColMajor>()))\n\nEIGEN_DECLARE_TEST(cxx11_tensor_block_eval) {\n  // clang-format off\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(1, test_eval_tensor_block);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(1, test_eval_tensor_binary_expr_block);\n  CALL_SUBTESTS_DIMS_LAYOUTS(1, test_eval_tensor_unary_expr_block);\n  CALL_SUBTESTS_DIMS_LAYOUTS(2, test_eval_tensor_binary_with_unary_expr_block);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(2, test_eval_tensor_broadcast);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(2, test_eval_tensor_reshape);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(3, test_eval_tensor_cast);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(3, test_eval_tensor_select);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(3, test_eval_tensor_padding);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(4, test_eval_tensor_chipping);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(4, test_eval_tensor_generator);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(4, test_eval_tensor_reverse);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(5, test_eval_tensor_slice);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(5, test_eval_tensor_shuffle);\n\n  CALL_SUBTESTS_LAYOUTS_TYPES(6, test_eval_tensor_reshape_with_bcast);\n  CALL_SUBTESTS_LAYOUTS_TYPES(6, test_eval_tensor_forced_eval);\n  CALL_SUBTESTS_LAYOUTS_TYPES(6, test_eval_tensor_chipping_of_bcast);\n\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(7, test_assign_to_tensor);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(7, test_assign_to_tensor_reshape);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(7, test_assign_to_tensor_chipping);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(8, test_assign_to_tensor_slice);\n  CALL_SUBTESTS_DIMS_LAYOUTS_TYPES(8, test_assign_to_tensor_shuffle);\n\n  // Force CMake to split this test.\n  // EIGEN_SUFFIXES;1;2;3;4;5;6;7;8\n\n  // clang-format on\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_block_io.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n// clang-format off\n#include \"main.h\"\n#include <Eigen/CXX11/Tensor>\n// clang-format on\n\n// -------------------------------------------------------------------------- //\n// A set of tests for TensorBlockIO: copying data between tensor blocks.\n\ntemplate <int NumDims>\nstatic DSizes<Index, NumDims> RandomDims(Index min, Index max) {\n  DSizes<Index, NumDims> dims;\n  for (int i = 0; i < NumDims; ++i) {\n    dims[i] = internal::random<Index>(min, max);\n  }\n  return DSizes<Index, NumDims>(dims);\n}\n\nstatic internal::TensorBlockShapeType RandomBlockShape() {\n  return internal::random<bool>()\n         ? internal::TensorBlockShapeType::kUniformAllDims\n         : internal::TensorBlockShapeType::kSkewedInnerDims;\n}\n\ntemplate <int NumDims>\nstatic size_t RandomTargetBlockSize(const DSizes<Index, NumDims>& dims) {\n  return internal::random<size_t>(1, dims.TotalSize());\n}\n\ntemplate <int Layout, int NumDims>\nstatic Index GetInputIndex(Index output_index,\n                           const array<Index, NumDims>& output_to_input_dim_map,\n                           const array<Index, NumDims>& input_strides,\n                           const array<Index, NumDims>& output_strides) {\n  int input_index = 0;\n  if (Layout == ColMajor) {\n    for (int i = NumDims - 1; i > 0; --i) {\n      const Index idx = output_index / output_strides[i];\n      input_index += idx * input_strides[output_to_input_dim_map[i]];\n      output_index -= idx * output_strides[i];\n    }\n    return input_index +\n           output_index * input_strides[output_to_input_dim_map[0]];\n  } else {\n    for (int i = 0; i < NumDims - 1; ++i) {\n      const Index idx = output_index / output_strides[i];\n      input_index += idx * input_strides[output_to_input_dim_map[i]];\n      output_index -= idx * output_strides[i];\n    }\n    return input_index +\n           output_index * input_strides[output_to_input_dim_map[NumDims - 1]];\n  }\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_block_io_copy_data_from_source_to_target() {\n  using TensorBlockIO = internal::TensorBlockIO<T, Index, NumDims, Layout>;\n  using IODst = typename TensorBlockIO::Dst;\n  using IOSrc = typename TensorBlockIO::Src;\n\n  // Generate a random input Tensor.\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(1, 30);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  // Write data to an output Tensor.\n  Tensor<T, NumDims, Layout> output(dims);\n\n  // Construct a tensor block mapper.\n  using TensorBlockMapper =\n      internal::TensorBlockMapper<NumDims, Layout, Index>;\n  TensorBlockMapper block_mapper(\n      dims, {RandomBlockShape(), RandomTargetBlockSize(dims), {0, 0, 0}});\n\n  // We will copy data from input to output through this buffer.\n  Tensor<T, NumDims, Layout> block(block_mapper.blockDimensions());\n\n  // Precompute strides for TensorBlockIO::Copy.\n  auto input_strides = internal::strides<Layout>(dims);\n  auto output_strides = internal::strides<Layout>(dims);\n\n  const T* input_data = input.data();\n  T* output_data = output.data();\n  T* block_data = block.data();\n\n  for (int i = 0; i < block_mapper.blockCount(); ++i) {\n    auto desc = block_mapper.blockDescriptor(i);\n\n    auto blk_dims = desc.dimensions();\n    auto blk_strides = internal::strides<Layout>(blk_dims);\n\n    {\n      // Read from input into a block buffer.\n      IODst dst(blk_dims, blk_strides, block_data, 0);\n      IOSrc src(input_strides, input_data, desc.offset());\n\n      TensorBlockIO::Copy(dst, src);\n    }\n\n    {\n      // Write from block buffer to output.\n      IODst dst(blk_dims, output_strides, output_data, desc.offset());\n      IOSrc src(blk_strides, block_data, 0);\n\n      TensorBlockIO::Copy(dst, src);\n    }\n  }\n\n  for (int i = 0; i < dims.TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(input_data[i], output_data[i]);\n  }\n}\n\ntemplate <typename T, int NumDims, int Layout>\nstatic void test_block_io_copy_using_reordered_dimensions() {\n  // Generate a random input Tensor.\n  DSizes<Index, NumDims> dims = RandomDims<NumDims>(1, 30);\n  Tensor<T, NumDims, Layout> input(dims);\n  input.setRandom();\n\n  // Create a random dimension re-ordering/shuffle.\n  std::vector<int> shuffle;\n\n  for (int i = 0; i < NumDims; ++i) shuffle.push_back(i);\n  std::shuffle(shuffle.begin(), shuffle.end(), std::mt19937(g_seed));\n\n  DSizes<Index, NumDims> output_tensor_dims;\n  DSizes<Index, NumDims> input_to_output_dim_map;\n  DSizes<Index, NumDims> output_to_input_dim_map;\n  for (Index i = 0; i < NumDims; ++i) {\n    output_tensor_dims[shuffle[i]] = dims[i];\n    input_to_output_dim_map[i] = shuffle[i];\n    output_to_input_dim_map[shuffle[i]] = i;\n  }\n\n  // Write data to an output Tensor.\n  Tensor<T, NumDims, Layout> output(output_tensor_dims);\n\n  // Construct a tensor block mapper.\n  // NOTE: Tensor block mapper works with shuffled dimensions.\n  using TensorBlockMapper =\n      internal::TensorBlockMapper<NumDims, Layout, Index>;\n  TensorBlockMapper block_mapper(output_tensor_dims,\n                                 {RandomBlockShape(),\n                                  RandomTargetBlockSize(output_tensor_dims),\n                                  {0, 0, 0}});\n\n  // We will copy data from input to output through this buffer.\n  Tensor<T, NumDims, Layout> block(block_mapper.blockDimensions());\n\n  // Precompute strides for TensorBlockIO::Copy.\n  auto input_strides = internal::strides<Layout>(dims);\n  auto output_strides = internal::strides<Layout>(output_tensor_dims);\n\n  const T* input_data = input.data();\n  T* output_data = output.data();\n  T* block_data = block.data();\n\n  for (Index i = 0; i < block_mapper.blockCount(); ++i) {\n    auto desc = block_mapper.blockDescriptor(i);\n\n    const Index first_coeff_index = GetInputIndex<Layout, NumDims>(\n        desc.offset(), output_to_input_dim_map, input_strides,\n        output_strides);\n\n    // NOTE: Block dimensions are in the same order as output dimensions.\n\n    using TensorBlockIO = internal::TensorBlockIO<T, Index, NumDims, Layout>;\n    using IODst = typename TensorBlockIO::Dst;\n    using IOSrc = typename TensorBlockIO::Src;\n\n    auto blk_dims = desc.dimensions();\n    auto blk_strides = internal::strides<Layout>(blk_dims);\n\n    {\n      // Read from input into a block buffer.\n      IODst dst(blk_dims, blk_strides, block_data, 0);\n      IOSrc src(input_strides, input_data, first_coeff_index);\n\n      // TODO(ezhulenev): Remove when fully switched to TensorBlock.\n      DSizes<int, NumDims> dim_map;\n      for (int j = 0; j < NumDims; ++j)\n        dim_map[j] = static_cast<int>(output_to_input_dim_map[j]);\n      TensorBlockIO::Copy(dst, src, /*dst_to_src_dim_map=*/dim_map);\n    }\n\n    {\n      // We need to convert block dimensions from output to input order.\n      auto dst_dims = blk_dims;\n      for (int out_dim = 0; out_dim < NumDims; ++out_dim) {\n        dst_dims[output_to_input_dim_map[out_dim]] = blk_dims[out_dim];\n      }\n\n      // Write from block buffer to output.\n      IODst dst(dst_dims, input_strides, output_data, first_coeff_index);\n      IOSrc src(blk_strides, block_data, 0);\n\n      // TODO(ezhulenev): Remove when fully switched to TensorBlock.\n      DSizes<int, NumDims> dim_map;\n      for (int j = 0; j < NumDims; ++j)\n        dim_map[j] = static_cast<int>(input_to_output_dim_map[j]);\n      TensorBlockIO::Copy(dst, src, /*dst_to_src_dim_map=*/dim_map);\n    }\n  }\n\n  for (Index i = 0; i < dims.TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(input_data[i], output_data[i]);\n  }\n}\n\n// This is the special case for reading data with reordering, when dimensions\n// before/after reordering are the same. Squeezing reads along inner dimensions\n// in this case is illegal, because we reorder innermost dimension.\ntemplate <int Layout>\nstatic void test_block_io_copy_using_reordered_dimensions_do_not_squeeze() {\n  DSizes<Index, 3> tensor_dims(7, 9, 7);\n  DSizes<Index, 3> block_dims = tensor_dims;\n\n  DSizes<int, 3> block_to_tensor_dim;\n  block_to_tensor_dim[0] = 2;\n  block_to_tensor_dim[1] = 1;\n  block_to_tensor_dim[2] = 0;\n\n  auto tensor_strides = internal::strides<Layout>(tensor_dims);\n  auto block_strides = internal::strides<Layout>(block_dims);\n\n  Tensor<float, 3, Layout> block(block_dims);\n  Tensor<float, 3, Layout> tensor(tensor_dims);\n  tensor.setRandom();\n\n  float* tensor_data = tensor.data();\n  float* block_data = block.data();\n\n  using TensorBlockIO = internal::TensorBlockIO<float, Index, 3, Layout>;\n  using IODst = typename TensorBlockIO::Dst;\n  using IOSrc = typename TensorBlockIO::Src;\n\n  // Read from a tensor into a block.\n  IODst dst(block_dims, block_strides, block_data, 0);\n  IOSrc src(tensor_strides, tensor_data, 0);\n\n  TensorBlockIO::Copy(dst, src, /*dst_to_src_dim_map=*/block_to_tensor_dim);\n\n  TensorMap<Tensor<float, 3, Layout> > block_tensor(block_data, block_dims);\n  TensorMap<Tensor<float, 3, Layout> > tensor_tensor(tensor_data, tensor_dims);\n\n  for (Index d0 = 0; d0 < tensor_dims[0]; ++d0) {\n    for (Index d1 = 0; d1 < tensor_dims[1]; ++d1) {\n      for (Index d2 = 0; d2 < tensor_dims[2]; ++d2) {\n        float block_value = block_tensor(d2, d1, d0);\n        float tensor_value = tensor_tensor(d0, d1, d2);\n        VERIFY_IS_EQUAL(block_value, tensor_value);\n      }\n    }\n  }\n}\n\n// This is the special case for reading data with reordering, when dimensions\n// before/after reordering are the same. Squeezing reads in this case is allowed\n// because we reorder outer dimensions.\ntemplate <int Layout>\nstatic void test_block_io_copy_using_reordered_dimensions_squeeze() {\n  DSizes<Index, 4> tensor_dims(7, 5, 9, 9);\n  DSizes<Index, 4> block_dims = tensor_dims;\n\n  DSizes<int, 4> block_to_tensor_dim;\n  block_to_tensor_dim[0] = 0;\n  block_to_tensor_dim[1] = 1;\n  block_to_tensor_dim[2] = 3;\n  block_to_tensor_dim[3] = 2;\n\n  auto tensor_strides = internal::strides<Layout>(tensor_dims);\n  auto block_strides = internal::strides<Layout>(block_dims);\n\n  Tensor<float, 4, Layout> block(block_dims);\n  Tensor<float, 4, Layout> tensor(tensor_dims);\n  tensor.setRandom();\n\n  float* tensor_data = tensor.data();\n  float* block_data = block.data();\n\n  using TensorBlockIO = internal::TensorBlockIO<float, Index, 4, Layout>;\n  using IODst = typename TensorBlockIO::Dst;\n  using IOSrc = typename TensorBlockIO::Src;\n\n  // Read from a tensor into a block.\n  IODst dst(block_dims, block_strides, block_data, 0);\n  IOSrc src(tensor_strides, tensor_data, 0);\n\n  TensorBlockIO::Copy(dst, src, /*dst_to_src_dim_map=*/block_to_tensor_dim);\n\n  TensorMap<Tensor<float, 4, Layout> > block_tensor(block_data, block_dims);\n  TensorMap<Tensor<float, 4, Layout> > tensor_tensor(tensor_data, tensor_dims);\n\n  for (Index d0 = 0; d0 < tensor_dims[0]; ++d0) {\n    for (Index d1 = 0; d1 < tensor_dims[1]; ++d1) {\n      for (Index d2 = 0; d2 < tensor_dims[2]; ++d2) {\n        for (Index d3 = 0; d3 < tensor_dims[3]; ++d3) {\n          float block_value = block_tensor(d0, d1, d3, d2);\n          float tensor_value = tensor_tensor(d0, d1, d2, d3);\n          VERIFY_IS_EQUAL(block_value, tensor_value);\n        }\n      }\n    }\n  }\n}\n\ntemplate <int Layout>\nstatic void test_block_io_zero_stride() {\n  DSizes<Index, 5> rnd_dims = RandomDims<5>(1, 30);\n\n  DSizes<Index, 5> input_tensor_dims = rnd_dims;\n  input_tensor_dims[0] = 1;\n  input_tensor_dims[2] = 1;\n  input_tensor_dims[4] = 1;\n\n  Tensor<float, 5, Layout> input(input_tensor_dims);\n  input.setRandom();\n\n  DSizes<Index, 5> output_tensor_dims = rnd_dims;\n\n  auto input_tensor_strides = internal::strides<Layout>(input_tensor_dims);\n  auto output_tensor_strides = internal::strides<Layout>(output_tensor_dims);\n\n  auto input_tensor_strides_with_zeros = input_tensor_strides;\n  input_tensor_strides_with_zeros[0] = 0;\n  input_tensor_strides_with_zeros[2] = 0;\n  input_tensor_strides_with_zeros[4] = 0;\n\n  Tensor<float, 5, Layout> output(output_tensor_dims);\n  output.setRandom();\n\n  using TensorBlockIO = internal::TensorBlockIO<float, Index, 5, Layout>;\n  using IODst = typename TensorBlockIO::Dst;\n  using IOSrc = typename TensorBlockIO::Src;\n\n  // Write data from input to output with broadcasting in dims [0, 2, 4].\n  IODst dst(output_tensor_dims, output_tensor_strides, output.data(), 0);\n  IOSrc src(input_tensor_strides_with_zeros, input.data(), 0);\n  TensorBlockIO::Copy(dst, src);\n\n  for (int i = 0; i < output_tensor_dims[0]; ++i) {\n    for (int j = 0; j < output_tensor_dims[1]; ++j) {\n      for (int k = 0; k < output_tensor_dims[2]; ++k) {\n        for (int l = 0; l < output_tensor_dims[3]; ++l) {\n          for (int m = 0; m < output_tensor_dims[4]; ++m) {\n            float input_value = input(0, j, 0, l, 0);\n            float output_value = output(i, j, k, l, m);\n            VERIFY_IS_EQUAL(input_value, output_value);\n          }\n        }\n      }\n    }\n  }\n}\n\ntemplate <int Layout>\nstatic void test_block_io_squeeze_ones() {\n  using TensorBlockIO = internal::TensorBlockIO<float, Index, 5, Layout>;\n  using IODst = typename TensorBlockIO::Dst;\n  using IOSrc = typename TensorBlockIO::Src;\n\n  // Total size > 1.\n  {\n    DSizes<Index, 5> block_sizes(1, 2, 1, 2, 1);\n    auto strides = internal::strides<Layout>(block_sizes);\n\n    // Create a random input tensor.\n    Tensor<float, 5> input(block_sizes);\n    input.setRandom();\n\n    Tensor<float, 5> output(block_sizes);\n\n    IODst dst(block_sizes, strides, output.data(), 0);\n    IOSrc src(strides, input.data());\n    TensorBlockIO::Copy(dst, src);\n\n    for (Index i = 0; i < block_sizes.TotalSize(); ++i) {\n      VERIFY_IS_EQUAL(output.data()[i], input.data()[i]);\n    }\n  }\n\n  // Total size == 1.\n  {\n    DSizes<Index, 5> block_sizes(1, 1, 1, 1, 1);\n    auto strides = internal::strides<Layout>(block_sizes);\n\n    // Create a random input tensor.\n    Tensor<float, 5> input(block_sizes);\n    input.setRandom();\n\n    Tensor<float, 5> output(block_sizes);\n\n    IODst dst(block_sizes, strides, output.data(), 0);\n    IOSrc src(strides, input.data());\n    TensorBlockIO::Copy(dst, src);\n\n    for (Index i = 0; i < block_sizes.TotalSize(); ++i) {\n      VERIFY_IS_EQUAL(output.data()[i], input.data()[i]);\n    }\n  }\n}\n\n#define CALL_SUBTESTS(NAME)                   \\\n  CALL_SUBTEST((NAME<float, 1, RowMajor>())); \\\n  CALL_SUBTEST((NAME<float, 2, RowMajor>())); \\\n  CALL_SUBTEST((NAME<float, 4, RowMajor>())); \\\n  CALL_SUBTEST((NAME<float, 5, RowMajor>())); \\\n  CALL_SUBTEST((NAME<float, 1, ColMajor>())); \\\n  CALL_SUBTEST((NAME<float, 2, ColMajor>())); \\\n  CALL_SUBTEST((NAME<float, 4, ColMajor>())); \\\n  CALL_SUBTEST((NAME<float, 5, ColMajor>())); \\\n  CALL_SUBTEST((NAME<bool, 1, RowMajor>())); \\\n  CALL_SUBTEST((NAME<bool, 2, RowMajor>())); \\\n  CALL_SUBTEST((NAME<bool, 4, RowMajor>())); \\\n  CALL_SUBTEST((NAME<bool, 5, RowMajor>())); \\\n  CALL_SUBTEST((NAME<bool, 1, ColMajor>())); \\\n  CALL_SUBTEST((NAME<bool, 2, ColMajor>())); \\\n  CALL_SUBTEST((NAME<bool, 4, ColMajor>())); \\\n  CALL_SUBTEST((NAME<bool, 5, ColMajor>()))\n\nEIGEN_DECLARE_TEST(cxx11_tensor_block_io) {\n  // clang-format off\n  CALL_SUBTESTS(test_block_io_copy_data_from_source_to_target);\n  CALL_SUBTESTS(test_block_io_copy_using_reordered_dimensions);\n\n  CALL_SUBTEST(test_block_io_copy_using_reordered_dimensions_do_not_squeeze<RowMajor>());\n  CALL_SUBTEST(test_block_io_copy_using_reordered_dimensions_do_not_squeeze<ColMajor>());\n\n  CALL_SUBTEST(test_block_io_copy_using_reordered_dimensions_squeeze<RowMajor>());\n  CALL_SUBTEST(test_block_io_copy_using_reordered_dimensions_squeeze<ColMajor>());\n\n  CALL_SUBTEST(test_block_io_zero_stride<RowMajor>());\n  CALL_SUBTEST(test_block_io_zero_stride<ColMajor>());\n\n  CALL_SUBTEST(test_block_io_squeeze_ones<RowMajor>());\n  CALL_SUBTEST(test_block_io_squeeze_ones<ColMajor>());\n  // clang-format on\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_broadcast_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_broadcast_sycl_fixed(const Eigen::SyclDevice &sycl_device){\n\n  // BROADCAST test:\n  IndexType inDim1=2;\n  IndexType inDim2=3;\n  IndexType inDim3=5;\n  IndexType inDim4=7;\n  IndexType bDim1=2;\n  IndexType bDim2=3;\n  IndexType bDim3=1;\n  IndexType bDim4=4;\n  array<IndexType, 4> in_range   = {{inDim1, inDim2, inDim3, inDim4}};\n  array<IndexType, 4> broadcasts = {{bDim1, bDim2, bDim3, bDim4}};\n  array<IndexType, 4> out_range;  // = in_range * broadcasts\n  for (size_t i = 0; i < out_range.size(); ++i)\n    out_range[i] = in_range[i] * broadcasts[i];\n\n  Tensor<DataType, 4, DataLayout, IndexType>  input(in_range);\n  Tensor<DataType, 4, DataLayout, IndexType> out(out_range);\n\n  for (size_t i = 0; i < in_range.size(); ++i)\n    VERIFY_IS_EQUAL(out.dimension(i), out_range[i]);\n\n\n  for (IndexType i = 0; i < input.size(); ++i)\n    input(i) = static_cast<DataType>(i);\n\n  DataType * gpu_in_data  = static_cast<DataType*>(sycl_device.allocate(input.dimensions().TotalSize()*sizeof(DataType)));\n  DataType * gpu_out_data  = static_cast<DataType*>(sycl_device.allocate(out.dimensions().TotalSize()*sizeof(DataType)));\n\n  TensorMap<TensorFixedSize<DataType, Sizes<2, 3, 5, 7>, DataLayout, IndexType>> gpu_in(gpu_in_data, in_range);\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType>> gpu_out(gpu_out_data, out_range);\n  sycl_device.memcpyHostToDevice(gpu_in_data, input.data(),(input.dimensions().TotalSize())*sizeof(DataType));\n  gpu_out.device(sycl_device) = gpu_in.broadcast(broadcasts);\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data,(out.dimensions().TotalSize())*sizeof(DataType));\n\n  for (IndexType i = 0; i < inDim1*bDim1; ++i) {\n    for (IndexType j = 0; j < inDim2*bDim2; ++j) {\n      for (IndexType k = 0; k < inDim3*bDim3; ++k) {\n        for (IndexType l = 0; l < inDim4*bDim4; ++l) {\n          VERIFY_IS_APPROX(input(i%2,j%3,k%5,l%7), out(i,j,k,l));\n        }\n      }\n    }\n  }\n  printf(\"Broadcast Test with fixed size Passed\\n\");\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_broadcast_sycl(const Eigen::SyclDevice &sycl_device){\n\n  // BROADCAST test:\n  IndexType inDim1=2;\n  IndexType inDim2=3;\n  IndexType inDim3=5;\n  IndexType inDim4=7;\n  IndexType bDim1=2;\n  IndexType bDim2=3;\n  IndexType bDim3=1;\n  IndexType bDim4=4;\n  array<IndexType, 4> in_range   = {{inDim1, inDim2, inDim3, inDim4}};\n  array<IndexType, 4> broadcasts = {{bDim1, bDim2, bDim3, bDim4}};\n  array<IndexType, 4> out_range;  // = in_range * broadcasts\n  for (size_t i = 0; i < out_range.size(); ++i)\n    out_range[i] = in_range[i] * broadcasts[i];\n\n  Tensor<DataType, 4, DataLayout, IndexType>  input(in_range);\n  Tensor<DataType, 4, DataLayout, IndexType> out(out_range);\n\n  for (size_t i = 0; i < in_range.size(); ++i)\n    VERIFY_IS_EQUAL(out.dimension(i), out_range[i]);\n\n\n  for (IndexType i = 0; i < input.size(); ++i)\n    input(i) = static_cast<DataType>(i);\n\n  DataType * gpu_in_data  = static_cast<DataType*>(sycl_device.allocate(input.dimensions().TotalSize()*sizeof(DataType)));\n  DataType * gpu_out_data  = static_cast<DataType*>(sycl_device.allocate(out.dimensions().TotalSize()*sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType>>  gpu_in(gpu_in_data, in_range);\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType>> gpu_out(gpu_out_data, out_range);\n  sycl_device.memcpyHostToDevice(gpu_in_data, input.data(),(input.dimensions().TotalSize())*sizeof(DataType));\n  gpu_out.device(sycl_device) = gpu_in.broadcast(broadcasts);\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data,(out.dimensions().TotalSize())*sizeof(DataType));\n\n  for (IndexType i = 0; i < inDim1*bDim1; ++i) {\n    for (IndexType j = 0; j < inDim2*bDim2; ++j) {\n      for (IndexType k = 0; k < inDim3*bDim3; ++k) {\n        for (IndexType l = 0; l < inDim4*bDim4; ++l) {\n          VERIFY_IS_APPROX(input(i%inDim1,j%inDim2,k%inDim3,l%inDim4), out(i,j,k,l));\n        }\n      }\n    }\n  }\n  printf(\"Broadcast Test Passed\\n\");\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate<typename DataType> void sycl_broadcast_test_per_device(const cl::sycl::device& d){\n  std::cout << \"Running on \" << d.template get_info<cl::sycl::info::device::name>() << std::endl;\n  QueueInterface queueInterface(d);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_broadcast_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_broadcast_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_broadcast_sycl_fixed<DataType, RowMajor, int64_t>(sycl_device);\n  test_broadcast_sycl_fixed<DataType, ColMajor, int64_t>(sycl_device);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_broadcast_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_broadcast_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_broadcasting.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate <int DataLayout>\nstatic void test_simple_broadcasting()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> broadcasts;\n  broadcasts[0] = 1;\n  broadcasts[1] = 1;\n  broadcasts[2] = 1;\n  broadcasts[3] = 1;\n\n  Tensor<float, 4, DataLayout> no_broadcast;\n  no_broadcast = tensor.broadcast(broadcasts);\n\n  VERIFY_IS_EQUAL(no_broadcast.dimension(0), 2);\n  VERIFY_IS_EQUAL(no_broadcast.dimension(1), 3);\n  VERIFY_IS_EQUAL(no_broadcast.dimension(2), 5);\n  VERIFY_IS_EQUAL(no_broadcast.dimension(3), 7);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), no_broadcast(i,j,k,l));\n        }\n      }\n    }\n  }\n\n  broadcasts[0] = 2;\n  broadcasts[1] = 3;\n  broadcasts[2] = 1;\n  broadcasts[3] = 4;\n  Tensor<float, 4, DataLayout> broadcast;\n  broadcast = tensor.broadcast(broadcasts);\n\n  VERIFY_IS_EQUAL(broadcast.dimension(0), 4);\n  VERIFY_IS_EQUAL(broadcast.dimension(1), 9);\n  VERIFY_IS_EQUAL(broadcast.dimension(2), 5);\n  VERIFY_IS_EQUAL(broadcast.dimension(3), 28);\n\n  for (int i = 0; i < 4; ++i) {\n    for (int j = 0; j < 9; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 28; ++l) {\n          VERIFY_IS_EQUAL(tensor(i%2,j%3,k%5,l%7), broadcast(i,j,k,l));\n        }\n      }\n    }\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_vectorized_broadcasting()\n{\n  Tensor<float, 3, DataLayout> tensor(8,3,5);\n  tensor.setRandom();\n  array<ptrdiff_t, 3> broadcasts;\n  broadcasts[0] = 2;\n  broadcasts[1] = 3;\n  broadcasts[2] = 4;\n\n  Tensor<float, 3, DataLayout> broadcast;\n  broadcast = tensor.broadcast(broadcasts);\n\n  VERIFY_IS_EQUAL(broadcast.dimension(0), 16);\n  VERIFY_IS_EQUAL(broadcast.dimension(1), 9);\n  VERIFY_IS_EQUAL(broadcast.dimension(2), 20);\n\n  for (int i = 0; i < 16; ++i) {\n    for (int j = 0; j < 9; ++j) {\n      for (int k = 0; k < 20; ++k) {\n        VERIFY_IS_EQUAL(tensor(i%8,j%3,k%5), broadcast(i,j,k));\n      }\n    }\n  }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  tensor.resize(11,3,5);\n#else\n  array<Index, 3> new_dims;\n  new_dims[0] = 11;\n  new_dims[1] = 3;\n  new_dims[2] = 5;\n  tensor.resize(new_dims);\n#endif\n\n  tensor.setRandom();\n  broadcast = tensor.broadcast(broadcasts);\n\n  VERIFY_IS_EQUAL(broadcast.dimension(0), 22);\n  VERIFY_IS_EQUAL(broadcast.dimension(1), 9);\n  VERIFY_IS_EQUAL(broadcast.dimension(2), 20);\n\n  for (int i = 0; i < 22; ++i) {\n    for (int j = 0; j < 9; ++j) {\n      for (int k = 0; k < 20; ++k) {\n        VERIFY_IS_EQUAL(tensor(i%11,j%3,k%5), broadcast(i,j,k));\n      }\n    }\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_static_broadcasting()\n{\n  Tensor<float, 3, DataLayout> tensor(8,3,5);\n  tensor.setRandom();\n\n#if defined(EIGEN_HAS_INDEX_LIST)\n  Eigen::IndexList<Eigen::type2index<2>, Eigen::type2index<3>, Eigen::type2index<4>> broadcasts;\n#else\n  Eigen::array<int, 3> broadcasts;\n  broadcasts[0] = 2;\n  broadcasts[1] = 3;\n  broadcasts[2] = 4;\n#endif\n\n  Tensor<float, 3, DataLayout> broadcast;\n  broadcast = tensor.broadcast(broadcasts);\n\n  VERIFY_IS_EQUAL(broadcast.dimension(0), 16);\n  VERIFY_IS_EQUAL(broadcast.dimension(1), 9);\n  VERIFY_IS_EQUAL(broadcast.dimension(2), 20);\n\n  for (int i = 0; i < 16; ++i) {\n    for (int j = 0; j < 9; ++j) {\n      for (int k = 0; k < 20; ++k) {\n        VERIFY_IS_EQUAL(tensor(i%8,j%3,k%5), broadcast(i,j,k));\n      }\n    }\n  }\n\n#if EIGEN_HAS_VARIADIC_TEMPLATES\n  tensor.resize(11,3,5);\n#else\n  array<Index, 3> new_dims;\n  new_dims[0] = 11;\n  new_dims[1] = 3;\n  new_dims[2] = 5;\n  tensor.resize(new_dims);\n#endif\n\n  tensor.setRandom();\n  broadcast = tensor.broadcast(broadcasts);\n\n  VERIFY_IS_EQUAL(broadcast.dimension(0), 22);\n  VERIFY_IS_EQUAL(broadcast.dimension(1), 9);\n  VERIFY_IS_EQUAL(broadcast.dimension(2), 20);\n\n  for (int i = 0; i < 22; ++i) {\n    for (int j = 0; j < 9; ++j) {\n      for (int k = 0; k < 20; ++k) {\n        VERIFY_IS_EQUAL(tensor(i%11,j%3,k%5), broadcast(i,j,k));\n      }\n    }\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_fixed_size_broadcasting()\n{\n  // Need to add a [] operator to the Size class for this to work\n#if 0\n  Tensor<float, 1, DataLayout> t1(10);\n  t1.setRandom();\n  TensorFixedSize<float, Sizes<1>, DataLayout> t2;\n  t2 = t2.constant(20.0f);\n\n  Tensor<float, 1, DataLayout> t3 = t1 + t2.broadcast(Eigen::array<int, 1>{{10}});\n  for (int i = 0; i < 10; ++i) {\n    VERIFY_IS_APPROX(t3(i), t1(i) + t2(0));\n  }\n\n  TensorMap<TensorFixedSize<float, Sizes<1>, DataLayout> > t4(t2.data(), {{1}});\n  Tensor<float, 1, DataLayout> t5 = t1 + t4.broadcast(Eigen::array<int, 1>{{10}});\n  for (int i = 0; i < 10; ++i) {\n    VERIFY_IS_APPROX(t5(i), t1(i) + t2(0));\n  }\n#endif\n}\n\ntemplate <int DataLayout>\nstatic void test_simple_broadcasting_one_by_n()\n{\n  Tensor<float, 4, DataLayout> tensor(1,13,5,7);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> broadcasts;\n  broadcasts[0] = 9;\n  broadcasts[1] = 1;\n  broadcasts[2] = 1;\n  broadcasts[3] = 1;\n  Tensor<float, 4, DataLayout> broadcast;\n  broadcast = tensor.broadcast(broadcasts);\n\n  VERIFY_IS_EQUAL(broadcast.dimension(0), 9);\n  VERIFY_IS_EQUAL(broadcast.dimension(1), 13);\n  VERIFY_IS_EQUAL(broadcast.dimension(2), 5);\n  VERIFY_IS_EQUAL(broadcast.dimension(3), 7);\n\n  for (int i = 0; i < 9; ++i) {\n    for (int j = 0; j < 13; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i%1,j%13,k%5,l%7), broadcast(i,j,k,l));\n        }\n      }\n    }\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_simple_broadcasting_n_by_one()\n{\n  Tensor<float, 4, DataLayout> tensor(7,3,5,1);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> broadcasts;\n  broadcasts[0] = 1;\n  broadcasts[1] = 1;\n  broadcasts[2] = 1;\n  broadcasts[3] = 19;\n  Tensor<float, 4, DataLayout> broadcast;\n  broadcast = tensor.broadcast(broadcasts);\n\n  VERIFY_IS_EQUAL(broadcast.dimension(0), 7);\n  VERIFY_IS_EQUAL(broadcast.dimension(1), 3);\n  VERIFY_IS_EQUAL(broadcast.dimension(2), 5);\n  VERIFY_IS_EQUAL(broadcast.dimension(3), 19);\n\n  for (int i = 0; i < 7; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 19; ++l) {\n          VERIFY_IS_EQUAL(tensor(i%7,j%3,k%5,l%1), broadcast(i,j,k,l));\n        }\n      }\n    }\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_simple_broadcasting_one_by_n_by_one_1d()\n{\n  Tensor<float, 3, DataLayout> tensor(1,7,1);\n  tensor.setRandom();\n  array<ptrdiff_t, 3> broadcasts;\n  broadcasts[0] = 5;\n  broadcasts[1] = 1;\n  broadcasts[2] = 13;\n  Tensor<float, 3, DataLayout> broadcasted;\n  broadcasted = tensor.broadcast(broadcasts);\n\n  VERIFY_IS_EQUAL(broadcasted.dimension(0), 5);\n  VERIFY_IS_EQUAL(broadcasted.dimension(1), 7);\n  VERIFY_IS_EQUAL(broadcasted.dimension(2), 13);\n\n  for (int i = 0; i < 5; ++i) {\n    for (int j = 0; j < 7; ++j) {\n      for (int k = 0; k < 13; ++k) {\n        VERIFY_IS_EQUAL(tensor(0,j%7,0), broadcasted(i,j,k));\n      }\n    }\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_simple_broadcasting_one_by_n_by_one_2d()\n{\n  Tensor<float, 4, DataLayout> tensor(1,7,13,1);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> broadcasts;\n  broadcasts[0] = 5;\n  broadcasts[1] = 1;\n  broadcasts[2] = 1;\n  broadcasts[3] = 19;\n  Tensor<float, 4, DataLayout> broadcast;\n  broadcast = tensor.broadcast(broadcasts);\n\n  VERIFY_IS_EQUAL(broadcast.dimension(0), 5);\n  VERIFY_IS_EQUAL(broadcast.dimension(1), 7);\n  VERIFY_IS_EQUAL(broadcast.dimension(2), 13);\n  VERIFY_IS_EQUAL(broadcast.dimension(3), 19);\n\n  for (int i = 0; i < 5; ++i) {\n    for (int j = 0; j < 7; ++j) {\n      for (int k = 0; k < 13; ++k) {\n        for (int l = 0; l < 19; ++l) {\n          VERIFY_IS_EQUAL(tensor(0,j%7,k%13,0), broadcast(i,j,k,l));\n        }\n      }\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_broadcasting)\n{\n  CALL_SUBTEST(test_simple_broadcasting<ColMajor>());\n  CALL_SUBTEST(test_simple_broadcasting<RowMajor>());\n  CALL_SUBTEST(test_vectorized_broadcasting<ColMajor>());\n  CALL_SUBTEST(test_vectorized_broadcasting<RowMajor>());\n  CALL_SUBTEST(test_static_broadcasting<ColMajor>());\n  CALL_SUBTEST(test_static_broadcasting<RowMajor>());\n  CALL_SUBTEST(test_fixed_size_broadcasting<ColMajor>());\n  CALL_SUBTEST(test_fixed_size_broadcasting<RowMajor>());\n  CALL_SUBTEST(test_simple_broadcasting_one_by_n<RowMajor>());\n  CALL_SUBTEST(test_simple_broadcasting_n_by_one<RowMajor>());\n  CALL_SUBTEST(test_simple_broadcasting_one_by_n<ColMajor>());\n  CALL_SUBTEST(test_simple_broadcasting_n_by_one<ColMajor>());\n  CALL_SUBTEST(test_simple_broadcasting_one_by_n_by_one_1d<ColMajor>());\n  CALL_SUBTEST(test_simple_broadcasting_one_by_n_by_one_2d<ColMajor>());\n  CALL_SUBTEST(test_simple_broadcasting_one_by_n_by_one_1d<RowMajor>());\n  CALL_SUBTEST(test_simple_broadcasting_one_by_n_by_one_2d<RowMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_builtins_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\n// Functions used to compare the TensorMap implementation on the device with\n// the equivalent on the host\nnamespace cl {\nnamespace sycl {\ntemplate <typename T> T abs(T x) { return cl::sycl::fabs(x); }\ntemplate <typename T> T square(T x) { return x * x; }\ntemplate <typename T> T cube(T x) { return x * x * x; }\ntemplate <typename T> T inverse(T x) { return T(1) / x; }\ntemplate <typename T> T cwiseMax(T x, T y) { return cl::sycl::max(x, y); }\ntemplate <typename T> T cwiseMin(T x, T y) { return cl::sycl::min(x, y); }\n}\n}\n\nstruct EqualAssignement {\n  template <typename Lhs, typename Rhs>\n  void operator()(Lhs& lhs, const Rhs& rhs) { lhs = rhs; }\n};\n\nstruct PlusEqualAssignement {\n  template <typename Lhs, typename Rhs>\n  void operator()(Lhs& lhs, const Rhs& rhs) { lhs += rhs; }\n};\n\ntemplate <typename DataType, int DataLayout,\n          typename Assignement, typename Operator>\nvoid test_unary_builtins_for_scalar(const Eigen::SyclDevice& sycl_device,\n                                    const array<int64_t, 3>& tensor_range) {\n  Operator op;\n  Assignement asgn;\n  {\n    /* Assignement(out, Operator(in)) */\n    Tensor<DataType, 3, DataLayout, int64_t> in(tensor_range);\n    Tensor<DataType, 3, DataLayout, int64_t> out(tensor_range);\n    in = in.random() + DataType(0.01);\n    out = out.random() + DataType(0.01);\n    Tensor<DataType, 3, DataLayout, int64_t> reference(out);\n    DataType *gpu_data = static_cast<DataType *>(\n        sycl_device.allocate(in.size() * sizeof(DataType)));\n    DataType *gpu_data_out = static_cast<DataType *>(\n        sycl_device.allocate(out.size() * sizeof(DataType)));\n    TensorMap<Tensor<DataType, 3, DataLayout, int64_t>> gpu(gpu_data, tensor_range);\n    TensorMap<Tensor<DataType, 3, DataLayout, int64_t>> gpu_out(gpu_data_out, tensor_range);\n    sycl_device.memcpyHostToDevice(gpu_data, in.data(),\n                                   (in.size()) * sizeof(DataType));\n    sycl_device.memcpyHostToDevice(gpu_data_out, out.data(),\n                                   (out.size()) * sizeof(DataType));\n    auto device_expr = gpu_out.device(sycl_device);\n    asgn(device_expr, op(gpu));\n    sycl_device.memcpyDeviceToHost(out.data(), gpu_data_out,\n                                   (out.size()) * sizeof(DataType));\n    for (int64_t i = 0; i < out.size(); ++i) {\n      DataType ver = reference(i);\n      asgn(ver, op(in(i)));\n      VERIFY_IS_APPROX(out(i), ver);\n    }\n    sycl_device.deallocate(gpu_data);\n    sycl_device.deallocate(gpu_data_out);\n  }\n  {\n    /* Assignement(out, Operator(out)) */\n    Tensor<DataType, 3, DataLayout, int64_t> out(tensor_range);\n    out = out.random() + DataType(0.01);\n    Tensor<DataType, 3, DataLayout, int64_t> reference(out);\n    DataType *gpu_data_out = static_cast<DataType *>(\n        sycl_device.allocate(out.size() * sizeof(DataType)));\n    TensorMap<Tensor<DataType, 3, DataLayout, int64_t>> gpu_out(gpu_data_out, tensor_range);\n    sycl_device.memcpyHostToDevice(gpu_data_out, out.data(),\n                                   (out.size()) * sizeof(DataType));\n    auto device_expr = gpu_out.device(sycl_device);\n    asgn(device_expr, op(gpu_out));\n    sycl_device.memcpyDeviceToHost(out.data(), gpu_data_out,\n                                   (out.size()) * sizeof(DataType));\n    for (int64_t i = 0; i < out.size(); ++i) {\n      DataType ver = reference(i);\n      asgn(ver, op(reference(i)));\n      VERIFY_IS_APPROX(out(i), ver);\n    }\n    sycl_device.deallocate(gpu_data_out);\n  }\n}\n\n#define DECLARE_UNARY_STRUCT(FUNC)                                 \\\n  struct op_##FUNC {                                               \\\n    template <typename T>                                          \\\n    auto operator()(const T& x) -> decltype(cl::sycl::FUNC(x)) {   \\\n      return cl::sycl::FUNC(x);                                    \\\n    }                                                              \\\n    template <typename T>                                          \\\n    auto operator()(const TensorMap<T>& x) -> decltype(x.FUNC()) { \\\n      return x.FUNC();                                             \\\n    }                                                              \\\n  };\n\nDECLARE_UNARY_STRUCT(abs)\nDECLARE_UNARY_STRUCT(sqrt)\nDECLARE_UNARY_STRUCT(rsqrt)\nDECLARE_UNARY_STRUCT(square)\nDECLARE_UNARY_STRUCT(cube)\nDECLARE_UNARY_STRUCT(inverse)\nDECLARE_UNARY_STRUCT(tanh)\nDECLARE_UNARY_STRUCT(exp)\nDECLARE_UNARY_STRUCT(expm1)\nDECLARE_UNARY_STRUCT(log)\nDECLARE_UNARY_STRUCT(ceil)\nDECLARE_UNARY_STRUCT(floor)\nDECLARE_UNARY_STRUCT(round)\nDECLARE_UNARY_STRUCT(log1p)\nDECLARE_UNARY_STRUCT(sign)\nDECLARE_UNARY_STRUCT(isnan)\nDECLARE_UNARY_STRUCT(isfinite)\nDECLARE_UNARY_STRUCT(isinf)\n\ntemplate <typename DataType, int DataLayout, typename Assignement>\nvoid test_unary_builtins_for_assignement(const Eigen::SyclDevice& sycl_device,\n                                         const array<int64_t, 3>& tensor_range) {\n#define RUN_UNARY_TEST(FUNC) \\\n  test_unary_builtins_for_scalar<DataType, DataLayout, Assignement, \\\n                                 op_##FUNC>(sycl_device, tensor_range)\n  RUN_UNARY_TEST(abs);\n  RUN_UNARY_TEST(sqrt);\n  RUN_UNARY_TEST(rsqrt);\n  RUN_UNARY_TEST(square);\n  RUN_UNARY_TEST(cube);\n  RUN_UNARY_TEST(inverse);\n  RUN_UNARY_TEST(tanh);\n  RUN_UNARY_TEST(exp);\n  RUN_UNARY_TEST(expm1);\n  RUN_UNARY_TEST(log);\n  RUN_UNARY_TEST(ceil);\n  RUN_UNARY_TEST(floor);\n  RUN_UNARY_TEST(round);\n  RUN_UNARY_TEST(log1p);\n  RUN_UNARY_TEST(sign);\n}\n\ntemplate <typename DataType, int DataLayout, typename Operator>\nvoid test_unary_builtins_return_bool(const Eigen::SyclDevice& sycl_device,\n                                     const array<int64_t, 3>& tensor_range) {\n  /* out = op(in) */\n  Operator op;\n  Tensor<DataType, 3, DataLayout, int64_t> in(tensor_range);\n  Tensor<bool, 3, DataLayout, int64_t> out(tensor_range);\n  in = in.random() + DataType(0.01);\n  DataType *gpu_data = static_cast<DataType *>(\n      sycl_device.allocate(in.size() * sizeof(DataType)));\n  bool *gpu_data_out =\n      static_cast<bool *>(sycl_device.allocate(out.size() * sizeof(bool)));\n  TensorMap<Tensor<DataType, 3, DataLayout, int64_t>> gpu(gpu_data, tensor_range);\n  TensorMap<Tensor<bool, 3, DataLayout, int64_t>> gpu_out(gpu_data_out, tensor_range);\n  sycl_device.memcpyHostToDevice(gpu_data, in.data(),\n                                 (in.size()) * sizeof(DataType));\n  gpu_out.device(sycl_device) = op(gpu);\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_data_out,\n                                 (out.size()) * sizeof(bool));\n  for (int64_t i = 0; i < out.size(); ++i) {\n    VERIFY_IS_EQUAL(out(i), op(in(i)));\n  }\n  sycl_device.deallocate(gpu_data);\n  sycl_device.deallocate(gpu_data_out);\n}\n\ntemplate <typename DataType, int DataLayout>\nvoid test_unary_builtins(const Eigen::SyclDevice& sycl_device,\n                         const array<int64_t, 3>& tensor_range) {\n  test_unary_builtins_for_assignement<DataType, DataLayout,\n                                      PlusEqualAssignement>(sycl_device, tensor_range);\n  test_unary_builtins_for_assignement<DataType, DataLayout,\n                                      EqualAssignement>(sycl_device, tensor_range);\n  test_unary_builtins_return_bool<DataType, DataLayout,\n                                  op_isnan>(sycl_device, tensor_range);\n  test_unary_builtins_return_bool<DataType, DataLayout,\n                                  op_isfinite>(sycl_device, tensor_range);\n  test_unary_builtins_return_bool<DataType, DataLayout,\n                                  op_isinf>(sycl_device, tensor_range);\n}\n\ntemplate <typename DataType>\nstatic void test_builtin_unary_sycl(const Eigen::SyclDevice &sycl_device) {\n  int64_t sizeDim1 = 10;\n  int64_t sizeDim2 = 10;\n  int64_t sizeDim3 = 10;\n  array<int64_t, 3> tensor_range = {{sizeDim1, sizeDim2, sizeDim3}};\n\n  test_unary_builtins<DataType, RowMajor>(sycl_device, tensor_range);\n  test_unary_builtins<DataType, ColMajor>(sycl_device, tensor_range);\n}\n\ntemplate <typename DataType, int DataLayout, typename Operator>\nvoid test_binary_builtins_func(const Eigen::SyclDevice& sycl_device,\n                               const array<int64_t, 3>& tensor_range) {\n  /* out = op(in_1, in_2) */\n  Operator op;\n  Tensor<DataType, 3, DataLayout, int64_t> in_1(tensor_range);\n  Tensor<DataType, 3, DataLayout, int64_t> in_2(tensor_range);\n  Tensor<DataType, 3, DataLayout, int64_t> out(tensor_range);\n  in_1 = in_1.random() + DataType(0.01);\n  in_2 = in_2.random() + DataType(0.01);\n  Tensor<DataType, 3, DataLayout, int64_t> reference(out);\n  DataType *gpu_data_1 = static_cast<DataType *>(\n      sycl_device.allocate(in_1.size() * sizeof(DataType)));\n  DataType *gpu_data_2 = static_cast<DataType *>(\n      sycl_device.allocate(in_2.size() * sizeof(DataType)));\n  DataType *gpu_data_out = static_cast<DataType *>(\n      sycl_device.allocate(out.size() * sizeof(DataType)));\n  TensorMap<Tensor<DataType, 3, DataLayout, int64_t>> gpu_1(gpu_data_1, tensor_range);\n  TensorMap<Tensor<DataType, 3, DataLayout, int64_t>> gpu_2(gpu_data_2, tensor_range);\n  TensorMap<Tensor<DataType, 3, DataLayout, int64_t>> gpu_out(gpu_data_out, tensor_range);\n  sycl_device.memcpyHostToDevice(gpu_data_1, in_1.data(),\n                                 (in_1.size()) * sizeof(DataType));\n  sycl_device.memcpyHostToDevice(gpu_data_2, in_2.data(),\n                                 (in_2.size()) * sizeof(DataType));\n  gpu_out.device(sycl_device) = op(gpu_1, gpu_2);\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_data_out,\n                                 (out.size()) * sizeof(DataType));\n  for (int64_t i = 0; i < out.size(); ++i) {\n    VERIFY_IS_APPROX(out(i), op(in_1(i), in_2(i)));\n  }\n  sycl_device.deallocate(gpu_data_1);\n  sycl_device.deallocate(gpu_data_2);\n  sycl_device.deallocate(gpu_data_out);\n}\n\ntemplate <typename DataType, int DataLayout, typename Operator>\nvoid test_binary_builtins_fixed_arg2(const Eigen::SyclDevice& sycl_device,\n                                     const array<int64_t, 3>& tensor_range) {\n  /* out = op(in_1, 2) */\n  Operator op;\n  const DataType arg2(2);\n  Tensor<DataType, 3, DataLayout, int64_t> in_1(tensor_range);\n  Tensor<DataType, 3, DataLayout, int64_t> out(tensor_range);\n  in_1 = in_1.random();\n  Tensor<DataType, 3, DataLayout, int64_t> reference(out);\n  DataType *gpu_data_1 = static_cast<DataType *>(\n      sycl_device.allocate(in_1.size() * sizeof(DataType)));\n  DataType *gpu_data_out = static_cast<DataType *>(\n      sycl_device.allocate(out.size() * sizeof(DataType)));\n  TensorMap<Tensor<DataType, 3, DataLayout, int64_t>> gpu_1(gpu_data_1, tensor_range);\n  TensorMap<Tensor<DataType, 3, DataLayout, int64_t>> gpu_out(gpu_data_out, tensor_range);\n  sycl_device.memcpyHostToDevice(gpu_data_1, in_1.data(),\n                                 (in_1.size()) * sizeof(DataType));\n  gpu_out.device(sycl_device) = op(gpu_1, arg2);\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_data_out,\n                                 (out.size()) * sizeof(DataType));\n  for (int64_t i = 0; i < out.size(); ++i) {\n    VERIFY_IS_APPROX(out(i), op(in_1(i), arg2));\n  }\n  sycl_device.deallocate(gpu_data_1);\n  sycl_device.deallocate(gpu_data_out);\n}\n\n#define DECLARE_BINARY_STRUCT(FUNC)                                                          \\\n  struct op_##FUNC {                                                                         \\\n    template <typename T1, typename T2>                                                      \\\n    auto operator()(const T1& x, const T2& y) -> decltype(cl::sycl::FUNC(x, y)) {            \\\n      return cl::sycl::FUNC(x, y);                                                           \\\n    }                                                                                        \\\n    template <typename T1, typename T2>                                                      \\\n    auto operator()(const TensorMap<T1>& x, const TensorMap<T2>& y) -> decltype(x.FUNC(y)) { \\\n      return x.FUNC(y);                                                                      \\\n    }                                                                                        \\\n  };\n\nDECLARE_BINARY_STRUCT(cwiseMax)\nDECLARE_BINARY_STRUCT(cwiseMin)\n\n#define DECLARE_BINARY_STRUCT_OP(NAME, OPERATOR)                          \\\n  struct op_##NAME {                                                      \\\n    template <typename T1, typename T2>                                   \\\n    auto operator()(const T1& x, const T2& y) -> decltype(x OPERATOR y) { \\\n      return x OPERATOR y;                                                \\\n    }                                                                     \\\n  };\n\nDECLARE_BINARY_STRUCT_OP(plus, +)\nDECLARE_BINARY_STRUCT_OP(minus, -)\nDECLARE_BINARY_STRUCT_OP(times, *)\nDECLARE_BINARY_STRUCT_OP(divide, /)\nDECLARE_BINARY_STRUCT_OP(modulo, %)\n\ntemplate <typename DataType, int DataLayout>\nvoid test_binary_builtins(const Eigen::SyclDevice& sycl_device,\n                          const array<int64_t, 3>& tensor_range) {\n  test_binary_builtins_func<DataType, DataLayout,\n                            op_cwiseMax>(sycl_device, tensor_range);\n  test_binary_builtins_func<DataType, DataLayout,\n                            op_cwiseMin>(sycl_device, tensor_range);\n  test_binary_builtins_func<DataType, DataLayout,\n                            op_plus>(sycl_device, tensor_range);\n  test_binary_builtins_func<DataType, DataLayout,\n                            op_minus>(sycl_device, tensor_range);\n  test_binary_builtins_func<DataType, DataLayout,\n                            op_times>(sycl_device, tensor_range);\n  test_binary_builtins_func<DataType, DataLayout,\n                            op_divide>(sycl_device, tensor_range);\n}\n\ntemplate <typename DataType>\nstatic void test_floating_builtin_binary_sycl(const Eigen::SyclDevice &sycl_device) {\n  int64_t sizeDim1 = 10;\n  int64_t sizeDim2 = 10;\n  int64_t sizeDim3 = 10;\n  array<int64_t, 3> tensor_range = {{sizeDim1, sizeDim2, sizeDim3}};\n  test_binary_builtins<DataType, RowMajor>(sycl_device, tensor_range);\n  test_binary_builtins<DataType, ColMajor>(sycl_device, tensor_range);\n}\n\ntemplate <typename DataType>\nstatic void test_integer_builtin_binary_sycl(const Eigen::SyclDevice &sycl_device) {\n  int64_t sizeDim1 = 10;\n  int64_t sizeDim2 = 10;\n  int64_t sizeDim3 = 10;\n  array<int64_t, 3> tensor_range = {{sizeDim1, sizeDim2, sizeDim3}};\n  test_binary_builtins_fixed_arg2<DataType, RowMajor,\n                                  op_modulo>(sycl_device, tensor_range);\n  test_binary_builtins_fixed_arg2<DataType, ColMajor,\n                                  op_modulo>(sycl_device, tensor_range);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_builtins_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    QueueInterface queueInterface(device);\n    Eigen::SyclDevice sycl_device(&queueInterface);\n    CALL_SUBTEST_1(test_builtin_unary_sycl<float>(sycl_device));\n    CALL_SUBTEST_2(test_floating_builtin_binary_sycl<float>(sycl_device));\n    CALL_SUBTEST_3(test_integer_builtin_binary_sycl<int>(sycl_device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_cast_float16_gpu.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\nvoid test_gpu_conversion() {\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n  int num_elem = 101;\n\n  Tensor<float, 1> floats(num_elem);\n  floats.setRandom();\n\n  float* d_float = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  Eigen::half* d_half = (Eigen::half*)gpu_device.allocate(num_elem * sizeof(Eigen::half));\n  float* d_conv = (float*)gpu_device.allocate(num_elem * sizeof(float));\n\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_float(\n      d_float, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_half(\n      d_half, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_conv(\n      d_conv, num_elem);\n\n  gpu_device.memcpyHostToDevice(d_float, floats.data(), num_elem*sizeof(float));\n\n  gpu_half.device(gpu_device) = gpu_float.cast<Eigen::half>();\n  gpu_conv.device(gpu_device) = gpu_half.cast<float>();\n\n  Tensor<float, 1> initial(num_elem);\n  Tensor<float, 1> final(num_elem);\n  gpu_device.memcpyDeviceToHost(initial.data(), d_float, num_elem*sizeof(float));\n  gpu_device.memcpyDeviceToHost(final.data(), d_conv, num_elem*sizeof(float));\n  gpu_device.synchronize();\n\n  for (int i = 0; i < num_elem; ++i) {\n    VERIFY_IS_APPROX(initial(i), final(i));\n  }\n\n  gpu_device.deallocate(d_float);\n  gpu_device.deallocate(d_half);\n  gpu_device.deallocate(d_conv);\n}\n\n\nvoid test_fallback_conversion() {\n  int num_elem = 101;\n  Tensor<float, 1> floats(num_elem);\n  floats.setRandom();\n\n  Eigen::Tensor<Eigen::half, 1> halfs = floats.cast<Eigen::half>();\n  Eigen::Tensor<float, 1> conv = halfs.cast<float>();\n\n  for (int i = 0; i < num_elem; ++i) {\n    VERIFY_IS_APPROX(floats(i), conv(i));\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_cast_float16_gpu)\n{\n  CALL_SUBTEST(test_gpu_conversion());\n  CALL_SUBTEST(test_fallback_conversion());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_casts.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include \"random_without_cast_overflow.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::array;\n\nstatic void test_simple_cast()\n{\n  Tensor<float, 2> ftensor(20,30);\n  ftensor = ftensor.random() * 100.f;\n  Tensor<char, 2> chartensor(20,30);\n  chartensor.setRandom();\n  Tensor<std::complex<float>, 2> cplextensor(20,30);\n  cplextensor.setRandom();\n\n  chartensor = ftensor.cast<char>();\n  cplextensor = ftensor.cast<std::complex<float> >();\n\n  for (int i = 0; i < 20; ++i) {\n    for (int j = 0; j < 30; ++j) {\n      VERIFY_IS_EQUAL(chartensor(i,j), static_cast<char>(ftensor(i,j)));\n      VERIFY_IS_EQUAL(cplextensor(i,j), static_cast<std::complex<float> >(ftensor(i,j)));\n    }\n  }\n}\n\n\nstatic void test_vectorized_cast()\n{\n  Tensor<int, 2> itensor(20,30);\n  itensor = itensor.random() / 1000;\n  Tensor<float, 2> ftensor(20,30);\n  ftensor.setRandom();\n  Tensor<double, 2> dtensor(20,30);\n  dtensor.setRandom();\n\n  ftensor = itensor.cast<float>();\n  dtensor = itensor.cast<double>();\n\n  for (int i = 0; i < 20; ++i) {\n    for (int j = 0; j < 30; ++j) {\n      VERIFY_IS_EQUAL(itensor(i,j), static_cast<int>(ftensor(i,j)));\n      VERIFY_IS_EQUAL(dtensor(i,j), static_cast<double>(ftensor(i,j)));\n    }\n  }\n}\n\n\nstatic void test_float_to_int_cast()\n{\n  Tensor<float, 2> ftensor(20,30);\n  ftensor = ftensor.random() * 1000.0f;\n  Tensor<double, 2> dtensor(20,30);\n  dtensor = dtensor.random() * 1000.0;\n\n  Tensor<int, 2> i1tensor = ftensor.cast<int>();\n  Tensor<int, 2> i2tensor = dtensor.cast<int>();\n\n  for (int i = 0; i < 20; ++i) {\n    for (int j = 0; j < 30; ++j) {\n      VERIFY_IS_EQUAL(i1tensor(i,j), static_cast<int>(ftensor(i,j)));\n      VERIFY_IS_EQUAL(i2tensor(i,j), static_cast<int>(dtensor(i,j)));\n    }\n  }\n}\n\n\nstatic void test_big_to_small_type_cast()\n{\n  Tensor<double, 2> dtensor(20, 30);\n  dtensor.setRandom();\n  Tensor<float, 2> ftensor(20, 30);\n  ftensor = dtensor.cast<float>();\n\n  for (int i = 0; i < 20; ++i) {\n    for (int j = 0; j < 30; ++j) {\n      VERIFY_IS_APPROX(dtensor(i,j), static_cast<double>(ftensor(i,j)));\n    }\n  }\n}\n\n\nstatic void test_small_to_big_type_cast()\n{\n  Tensor<float, 2> ftensor(20, 30);\n  ftensor.setRandom();\n  Tensor<double, 2> dtensor(20, 30);\n  dtensor = ftensor.cast<double>();\n\n  for (int i = 0; i < 20; ++i) {\n    for (int j = 0; j < 30; ++j) {\n      VERIFY_IS_APPROX(dtensor(i,j), static_cast<double>(ftensor(i,j)));\n    }\n  }\n}\n\ntemplate <typename FromType, typename ToType>\nstatic void test_type_cast() {\n  Tensor<FromType, 2> ftensor(100, 200);\n  // Generate random values for a valid cast.\n  for (int i = 0; i < 100; ++i) {\n    for (int j = 0; j < 200; ++j) {\n      ftensor(i, j) = internal::random_without_cast_overflow<FromType,ToType>::value();\n    }\n  }\n\n  Tensor<ToType, 2> ttensor(100, 200);\n  ttensor = ftensor.template cast<ToType>();\n\n  for (int i = 0; i < 100; ++i) {\n    for (int j = 0; j < 200; ++j) {\n      const ToType ref = internal::cast<FromType,ToType>(ftensor(i, j));\n      VERIFY_IS_APPROX(ttensor(i, j), ref);\n    }\n  }\n}\n\ntemplate<typename Scalar, typename EnableIf = void>\nstruct test_cast_runner {\n  static void run() {\n    test_type_cast<Scalar, bool>();\n    test_type_cast<Scalar, int8_t>();\n    test_type_cast<Scalar, int16_t>();\n    test_type_cast<Scalar, int32_t>();\n    test_type_cast<Scalar, int64_t>();\n    test_type_cast<Scalar, uint8_t>();\n    test_type_cast<Scalar, uint16_t>();\n    test_type_cast<Scalar, uint32_t>();\n    test_type_cast<Scalar, uint64_t>();\n    test_type_cast<Scalar, half>();\n    test_type_cast<Scalar, bfloat16>();\n    test_type_cast<Scalar, float>();\n    test_type_cast<Scalar, double>();\n    test_type_cast<Scalar, std::complex<float>>();\n    test_type_cast<Scalar, std::complex<double>>();\n  }\n};\n\n// Only certain types allow cast from std::complex<>.\ntemplate<typename Scalar>\nstruct test_cast_runner<Scalar, typename internal::enable_if<NumTraits<Scalar>::IsComplex>::type> {\n  static void run() {\n    test_type_cast<Scalar, half>();\n    test_type_cast<Scalar, bfloat16>();\n    test_type_cast<Scalar, std::complex<float>>();\n    test_type_cast<Scalar, std::complex<double>>();\n  }\n};\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_casts)\n{\n  CALL_SUBTEST(test_simple_cast());\n  CALL_SUBTEST(test_vectorized_cast());\n  CALL_SUBTEST(test_float_to_int_cast());\n  CALL_SUBTEST(test_big_to_small_type_cast());\n  CALL_SUBTEST(test_small_to_big_type_cast());\n\n  CALL_SUBTEST(test_cast_runner<bool>::run());\n  CALL_SUBTEST(test_cast_runner<int8_t>::run());\n  CALL_SUBTEST(test_cast_runner<int16_t>::run());\n  CALL_SUBTEST(test_cast_runner<int32_t>::run());\n  CALL_SUBTEST(test_cast_runner<int64_t>::run());\n  CALL_SUBTEST(test_cast_runner<uint8_t>::run());\n  CALL_SUBTEST(test_cast_runner<uint16_t>::run());\n  CALL_SUBTEST(test_cast_runner<uint32_t>::run());\n  CALL_SUBTEST(test_cast_runner<uint64_t>::run());\n  CALL_SUBTEST(test_cast_runner<half>::run());\n  CALL_SUBTEST(test_cast_runner<bfloat16>::run());\n  CALL_SUBTEST(test_cast_runner<float>::run());\n  CALL_SUBTEST(test_cast_runner<double>::run());\n  CALL_SUBTEST(test_cast_runner<std::complex<float>>::run());\n  CALL_SUBTEST(test_cast_runner<std::complex<double>>::run());\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_chipping.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate<int DataLayout>\nstatic void test_simple_chip()\n{\n  Tensor<float, 5, DataLayout> tensor(2,3,5,7,11);\n  tensor.setRandom();\n\n  Tensor<float, 4, DataLayout> chip1;\n  chip1 = tensor.template chip<0>(1);\n\n  VERIFY_IS_EQUAL(chip1.dimension(0), 3);\n  VERIFY_IS_EQUAL(chip1.dimension(1), 5);\n  VERIFY_IS_EQUAL(chip1.dimension(2), 7);\n  VERIFY_IS_EQUAL(chip1.dimension(3), 11);\n\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        for (int l = 0; l < 11; ++l) {\n          VERIFY_IS_EQUAL(chip1(i,j,k,l), tensor(1,i,j,k,l));\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> chip2 = tensor.template chip<1>(1);\n  VERIFY_IS_EQUAL(chip2.dimension(0), 2);\n  VERIFY_IS_EQUAL(chip2.dimension(1), 5);\n  VERIFY_IS_EQUAL(chip2.dimension(2), 7);\n  VERIFY_IS_EQUAL(chip2.dimension(3), 11);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        for (int l = 0; l < 11; ++l) {\n          VERIFY_IS_EQUAL(chip2(i,j,k,l), tensor(i,1,j,k,l));\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> chip3 = tensor.template chip<2>(2);\n  VERIFY_IS_EQUAL(chip3.dimension(0), 2);\n  VERIFY_IS_EQUAL(chip3.dimension(1), 3);\n  VERIFY_IS_EQUAL(chip3.dimension(2), 7);\n  VERIFY_IS_EQUAL(chip3.dimension(3), 11);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        for (int l = 0; l < 11; ++l) {\n          VERIFY_IS_EQUAL(chip3(i,j,k,l), tensor(i,j,2,k,l));\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> chip4(tensor.template chip<3>(5));\n  VERIFY_IS_EQUAL(chip4.dimension(0), 2);\n  VERIFY_IS_EQUAL(chip4.dimension(1), 3);\n  VERIFY_IS_EQUAL(chip4.dimension(2), 5);\n  VERIFY_IS_EQUAL(chip4.dimension(3), 11);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 11; ++l) {\n          VERIFY_IS_EQUAL(chip4(i,j,k,l), tensor(i,j,k,5,l));\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> chip5(tensor.template chip<4>(7));\n  VERIFY_IS_EQUAL(chip5.dimension(0), 2);\n  VERIFY_IS_EQUAL(chip5.dimension(1), 3);\n  VERIFY_IS_EQUAL(chip5.dimension(2), 5);\n  VERIFY_IS_EQUAL(chip5.dimension(3), 7);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(chip5(i,j,k,l), tensor(i,j,k,l,7));\n        }\n      }\n    }\n  }\n}\n\ntemplate<int DataLayout>\nstatic void test_dynamic_chip()\n{\n  Tensor<float, 5, DataLayout> tensor(2,3,5,7,11);\n  tensor.setRandom();\n\n  Tensor<float, 4, DataLayout> chip1;\n  chip1 = tensor.chip(1, 0);\n  VERIFY_IS_EQUAL(chip1.dimension(0), 3);\n  VERIFY_IS_EQUAL(chip1.dimension(1), 5);\n  VERIFY_IS_EQUAL(chip1.dimension(2), 7);\n  VERIFY_IS_EQUAL(chip1.dimension(3), 11);\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        for (int l = 0; l < 11; ++l) {\n          VERIFY_IS_EQUAL(chip1(i,j,k,l), tensor(1,i,j,k,l));\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> chip2 = tensor.chip(1, 1);\n  VERIFY_IS_EQUAL(chip2.dimension(0), 2);\n  VERIFY_IS_EQUAL(chip2.dimension(1), 5);\n  VERIFY_IS_EQUAL(chip2.dimension(2), 7);\n  VERIFY_IS_EQUAL(chip2.dimension(3), 11);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        for (int l = 0; l < 11; ++l) {\n          VERIFY_IS_EQUAL(chip2(i,j,k,l), tensor(i,1,j,k,l));\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> chip3 = tensor.chip(2, 2);\n  VERIFY_IS_EQUAL(chip3.dimension(0), 2);\n  VERIFY_IS_EQUAL(chip3.dimension(1), 3);\n  VERIFY_IS_EQUAL(chip3.dimension(2), 7);\n  VERIFY_IS_EQUAL(chip3.dimension(3), 11);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        for (int l = 0; l < 11; ++l) {\n          VERIFY_IS_EQUAL(chip3(i,j,k,l), tensor(i,j,2,k,l));\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> chip4(tensor.chip(5, 3));\n  VERIFY_IS_EQUAL(chip4.dimension(0), 2);\n  VERIFY_IS_EQUAL(chip4.dimension(1), 3);\n  VERIFY_IS_EQUAL(chip4.dimension(2), 5);\n  VERIFY_IS_EQUAL(chip4.dimension(3), 11);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 11; ++l) {\n          VERIFY_IS_EQUAL(chip4(i,j,k,l), tensor(i,j,k,5,l));\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> chip5(tensor.chip(7, 4));\n  VERIFY_IS_EQUAL(chip5.dimension(0), 2);\n  VERIFY_IS_EQUAL(chip5.dimension(1), 3);\n  VERIFY_IS_EQUAL(chip5.dimension(2), 5);\n  VERIFY_IS_EQUAL(chip5.dimension(3), 7);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(chip5(i,j,k,l), tensor(i,j,k,l,7));\n        }\n      }\n    }\n  }\n}\n\ntemplate<int DataLayout>\nstatic void test_chip_in_expr() {\n  Tensor<float, 5, DataLayout> input1(2,3,5,7,11);\n  input1.setRandom();\n  Tensor<float, 4, DataLayout> input2(3,5,7,11);\n  input2.setRandom();\n\n  Tensor<float, 4, DataLayout> result = input1.template chip<0>(0) + input2;\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        for (int l = 0; l < 11; ++l) {\n          float expected = input1(0,i,j,k,l) + input2(i,j,k,l);\n          VERIFY_IS_EQUAL(result(i,j,k,l), expected);\n        }\n      }\n    }\n  }\n\n  Tensor<float, 3, DataLayout> input3(3,7,11);\n  input3.setRandom();\n  Tensor<float, 3, DataLayout> result2 = input1.template chip<0>(0).template chip<1>(2) + input3;\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 7; ++j) {\n      for (int k = 0; k < 11; ++k) {\n        float expected = input1(0,i,2,j,k) + input3(i,j,k);\n        VERIFY_IS_EQUAL(result2(i,j,k), expected);\n      }\n    }\n  }\n}\n\ntemplate<int DataLayout>\nstatic void test_chip_as_lvalue()\n{\n  Tensor<float, 5, DataLayout> input1(2,3,5,7,11);\n  input1.setRandom();\n\n  Tensor<float, 4, DataLayout> input2(3,5,7,11);\n  input2.setRandom();\n  Tensor<float, 5, DataLayout> tensor = input1;\n  tensor.template chip<0>(1) = input2;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          for (int m = 0; m < 11; ++m) {\n            if (i != 1) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input2(j,k,l,m));\n            }\n          }\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> input3(2,5,7,11);\n  input3.setRandom();\n  tensor = input1;\n  tensor.template chip<1>(1) = input3;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          for (int m = 0; m < 11; ++m) {\n            if (j != 1) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input3(i,k,l,m));\n            }\n          }\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> input4(2,3,7,11);\n  input4.setRandom();\n  tensor = input1;\n  tensor.template chip<2>(3) = input4;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          for (int m = 0; m < 11; ++m) {\n            if (k != 3) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input4(i,j,l,m));\n            }\n          }\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> input5(2,3,5,11);\n  input5.setRandom();\n  tensor = input1;\n  tensor.template chip<3>(4) = input5;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          for (int m = 0; m < 11; ++m) {\n            if (l != 4) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input5(i,j,k,m));\n            }\n          }\n        }\n      }\n    }\n  }\n\n  Tensor<float, 4, DataLayout> input6(2,3,5,7);\n  input6.setRandom();\n  tensor = input1;\n  tensor.template chip<4>(5) = input6;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          for (int m = 0; m < 11; ++m) {\n            if (m != 5) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input6(i,j,k,l));\n            }\n          }\n        }\n      }\n    }\n  }\n\n  Tensor<float, 5, DataLayout> input7(2,3,5,7,11);\n  input7.setRandom();\n  tensor = input1;\n  tensor.chip(0, 0) = input7.chip(0, 0);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          for (int m = 0; m < 11; ++m) {\n            if (i != 0) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input7(i,j,k,l,m));\n            }\n          }\n        }\n      }\n    }\n  }\n}\n\nstatic void test_chip_raw_data_col_major()\n{\n  Tensor<float, 5, ColMajor> tensor(2,3,5,7,11);\n  tensor.setRandom();\n\n  typedef TensorEvaluator<decltype(tensor.chip<4>(3)), DefaultDevice> Evaluator4;\n  auto chip = Evaluator4(tensor.chip<4>(3), DefaultDevice());\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          int chip_index = i + 2 * (j + 3 * (k + 5 * l));\n          VERIFY_IS_EQUAL(chip.data()[chip_index], tensor(i,j,k,l,3));\n        }\n      }\n    }\n  }\n\n  typedef TensorEvaluator<decltype(tensor.chip<0>(0)), DefaultDevice> Evaluator0;\n  auto chip0 = Evaluator0(tensor.chip<0>(0), DefaultDevice());\n  VERIFY_IS_EQUAL(chip0.data(), static_cast<float*>(0));\n\n  typedef TensorEvaluator<decltype(tensor.chip<1>(0)), DefaultDevice> Evaluator1;\n  auto chip1 = Evaluator1(tensor.chip<1>(0), DefaultDevice());\n  VERIFY_IS_EQUAL(chip1.data(), static_cast<float*>(0));\n\n  typedef TensorEvaluator<decltype(tensor.chip<2>(0)), DefaultDevice> Evaluator2;\n  auto chip2 = Evaluator2(tensor.chip<2>(0), DefaultDevice());\n  VERIFY_IS_EQUAL(chip2.data(), static_cast<float*>(0));\n\n  typedef TensorEvaluator<decltype(tensor.chip<3>(0)), DefaultDevice> Evaluator3;\n  auto chip3 = Evaluator3(tensor.chip<3>(0), DefaultDevice());\n  VERIFY_IS_EQUAL(chip3.data(), static_cast<float*>(0));\n}\n\nstatic void test_chip_raw_data_row_major()\n{\n  Tensor<float, 5, RowMajor> tensor(11,7,5,3,2);\n  tensor.setRandom();\n\n  typedef TensorEvaluator<decltype(tensor.chip<0>(3)), DefaultDevice> Evaluator0;\n  auto chip = Evaluator0(tensor.chip<0>(3), DefaultDevice());\n  for (int i = 0; i < 7; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 3; ++k) {\n        for (int l = 0; l < 2; ++l) {\n          int chip_index = l + 2 * (k + 3 * (j + 5 * i));\n          VERIFY_IS_EQUAL(chip.data()[chip_index], tensor(3,i,j,k,l));\n        }\n      }\n    }\n  }\n\n  typedef TensorEvaluator<decltype(tensor.chip<1>(0)), DefaultDevice> Evaluator1;\n  auto chip1 = Evaluator1(tensor.chip<1>(0), DefaultDevice());\n  VERIFY_IS_EQUAL(chip1.data(), static_cast<float*>(0));\n\n  typedef TensorEvaluator<decltype(tensor.chip<2>(0)), DefaultDevice> Evaluator2;\n  auto chip2 = Evaluator2(tensor.chip<2>(0), DefaultDevice());\n  VERIFY_IS_EQUAL(chip2.data(), static_cast<float*>(0));\n\n  typedef TensorEvaluator<decltype(tensor.chip<3>(0)), DefaultDevice> Evaluator3;\n  auto chip3 = Evaluator3(tensor.chip<3>(0), DefaultDevice());\n  VERIFY_IS_EQUAL(chip3.data(), static_cast<float*>(0));\n\n  typedef TensorEvaluator<decltype(tensor.chip<4>(0)), DefaultDevice> Evaluator4;\n  auto chip4 = Evaluator4(tensor.chip<4>(0), DefaultDevice());\n  VERIFY_IS_EQUAL(chip4.data(), static_cast<float*>(0));\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_chipping)\n{\n  CALL_SUBTEST(test_simple_chip<ColMajor>());\n  CALL_SUBTEST(test_simple_chip<RowMajor>());\n  CALL_SUBTEST(test_dynamic_chip<ColMajor>());\n  CALL_SUBTEST(test_dynamic_chip<RowMajor>());\n  CALL_SUBTEST(test_chip_in_expr<ColMajor>());\n  CALL_SUBTEST(test_chip_in_expr<RowMajor>());\n  CALL_SUBTEST(test_chip_as_lvalue<ColMajor>());\n  CALL_SUBTEST(test_chip_as_lvalue<RowMajor>());\n  CALL_SUBTEST(test_chip_raw_data_col_major());\n  CALL_SUBTEST(test_chip_raw_data_row_major());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_chipping_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_static_chip_sycl(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  IndexType sizeDim5 = 11;\n\n  array<IndexType, 5> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4, sizeDim5}};\n  array<IndexType, 4> chip1TensorRange = {{sizeDim2, sizeDim3, sizeDim4, sizeDim5}};\n\n  Tensor<DataType, 5, DataLayout,IndexType> tensor(tensorRange);\n  Tensor<DataType, 4, DataLayout,IndexType> chip1(chip1TensorRange);\n\n  tensor.setRandom();\n\n  const size_t tensorBuffSize =tensor.size()*sizeof(DataType);\n  const size_t chip1TensorBuffSize =chip1.size()*sizeof(DataType);\n  DataType* gpu_data_tensor  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  DataType* gpu_data_chip1  = static_cast<DataType*>(sycl_device.allocate(chip1TensorBuffSize));\n\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_tensor(gpu_data_tensor, tensorRange);\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip1(gpu_data_chip1, chip1TensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_tensor, tensor.data(), tensorBuffSize);\n  gpu_chip1.device(sycl_device)=gpu_tensor.template chip<0l>(1l);\n  sycl_device.memcpyDeviceToHost(chip1.data(), gpu_data_chip1, chip1TensorBuffSize);\n\n  VERIFY_IS_EQUAL(chip1.dimension(0), sizeDim2);\n  VERIFY_IS_EQUAL(chip1.dimension(1), sizeDim3);\n  VERIFY_IS_EQUAL(chip1.dimension(2), sizeDim4);\n  VERIFY_IS_EQUAL(chip1.dimension(3), sizeDim5);\n\n  for (IndexType i = 0; i < sizeDim2; ++i) {\n    for (IndexType j = 0; j < sizeDim3; ++j) {\n      for (IndexType k = 0; k < sizeDim4; ++k) {\n        for (IndexType l = 0; l < sizeDim5; ++l) {\n          VERIFY_IS_EQUAL(chip1(i,j,k,l), tensor(1l,i,j,k,l));\n        }\n      }\n    }\n  }\n\n  array<IndexType, 4> chip2TensorRange = {{sizeDim1, sizeDim3, sizeDim4, sizeDim5}};\n  Tensor<DataType, 4, DataLayout,IndexType> chip2(chip2TensorRange);\n  const size_t chip2TensorBuffSize =chip2.size()*sizeof(DataType);\n  DataType* gpu_data_chip2  = static_cast<DataType*>(sycl_device.allocate(chip2TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip2(gpu_data_chip2, chip2TensorRange);\n\n  gpu_chip2.device(sycl_device)=gpu_tensor.template chip<1l>(1l);\n  sycl_device.memcpyDeviceToHost(chip2.data(), gpu_data_chip2, chip2TensorBuffSize);\n\n  VERIFY_IS_EQUAL(chip2.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(chip2.dimension(1), sizeDim3);\n  VERIFY_IS_EQUAL(chip2.dimension(2), sizeDim4);\n  VERIFY_IS_EQUAL(chip2.dimension(3), sizeDim5);\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim3; ++j) {\n      for (IndexType k = 0; k < sizeDim4; ++k) {\n        for (IndexType l = 0; l < sizeDim5; ++l) {\n          VERIFY_IS_EQUAL(chip2(i,j,k,l), tensor(i,1l,j,k,l));\n        }\n      }\n    }\n  }\n\n  array<IndexType, 4> chip3TensorRange = {{sizeDim1, sizeDim2, sizeDim4, sizeDim5}};\n  Tensor<DataType, 4, DataLayout,IndexType> chip3(chip3TensorRange);\n  const size_t chip3TensorBuffSize =chip3.size()*sizeof(DataType);\n  DataType* gpu_data_chip3  = static_cast<DataType*>(sycl_device.allocate(chip3TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip3(gpu_data_chip3, chip3TensorRange);\n\n  gpu_chip3.device(sycl_device)=gpu_tensor.template chip<2l>(2l);\n  sycl_device.memcpyDeviceToHost(chip3.data(), gpu_data_chip3, chip3TensorBuffSize);\n\n  VERIFY_IS_EQUAL(chip3.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(chip3.dimension(1), sizeDim2);\n  VERIFY_IS_EQUAL(chip3.dimension(2), sizeDim4);\n  VERIFY_IS_EQUAL(chip3.dimension(3), sizeDim5);\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim4; ++k) {\n        for (IndexType l = 0; l < sizeDim5; ++l) {\n          VERIFY_IS_EQUAL(chip3(i,j,k,l), tensor(i,j,2l,k,l));\n        }\n      }\n    }\n  }\n\n  array<IndexType, 4> chip4TensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim5}};\n  Tensor<DataType, 4, DataLayout,IndexType> chip4(chip4TensorRange);\n  const size_t chip4TensorBuffSize =chip4.size()*sizeof(DataType);\n  DataType* gpu_data_chip4  = static_cast<DataType*>(sycl_device.allocate(chip4TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip4(gpu_data_chip4, chip4TensorRange);\n\n  gpu_chip4.device(sycl_device)=gpu_tensor.template chip<3l>(5l);\n  sycl_device.memcpyDeviceToHost(chip4.data(), gpu_data_chip4, chip4TensorBuffSize);\n\n  VERIFY_IS_EQUAL(chip4.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(chip4.dimension(1), sizeDim2);\n  VERIFY_IS_EQUAL(chip4.dimension(2), sizeDim3);\n  VERIFY_IS_EQUAL(chip4.dimension(3), sizeDim5);\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        for (IndexType l = 0; l < sizeDim5; ++l) {\n          VERIFY_IS_EQUAL(chip4(i,j,k,l), tensor(i,j,k,5l,l));\n        }\n      }\n    }\n  }\n\n\n  array<IndexType, 4> chip5TensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  Tensor<DataType, 4, DataLayout,IndexType> chip5(chip5TensorRange);\n  const size_t chip5TensorBuffSize =chip5.size()*sizeof(DataType);\n  DataType* gpu_data_chip5  = static_cast<DataType*>(sycl_device.allocate(chip5TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip5(gpu_data_chip5, chip5TensorRange);\n\n  gpu_chip5.device(sycl_device)=gpu_tensor.template chip<4l>(7l);\n  sycl_device.memcpyDeviceToHost(chip5.data(), gpu_data_chip5, chip5TensorBuffSize);\n\n  VERIFY_IS_EQUAL(chip5.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(chip5.dimension(1), sizeDim2);\n  VERIFY_IS_EQUAL(chip5.dimension(2), sizeDim3);\n  VERIFY_IS_EQUAL(chip5.dimension(3), sizeDim4);\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        for (IndexType l = 0; l < sizeDim4; ++l) {\n          VERIFY_IS_EQUAL(chip5(i,j,k,l), tensor(i,j,k,l,7l));\n        }\n      }\n    }\n  }\n\n  sycl_device.deallocate(gpu_data_tensor);\n  sycl_device.deallocate(gpu_data_chip1);\n  sycl_device.deallocate(gpu_data_chip2);\n  sycl_device.deallocate(gpu_data_chip3);\n  sycl_device.deallocate(gpu_data_chip4);\n  sycl_device.deallocate(gpu_data_chip5);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_dynamic_chip_sycl(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  IndexType sizeDim5 = 11;\n\n  array<IndexType, 5> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4, sizeDim5}};\n  array<IndexType, 4> chip1TensorRange = {{sizeDim2, sizeDim3, sizeDim4, sizeDim5}};\n\n  Tensor<DataType, 5, DataLayout,IndexType> tensor(tensorRange);\n  Tensor<DataType, 4, DataLayout,IndexType> chip1(chip1TensorRange);\n\n  tensor.setRandom();\n\n  const size_t tensorBuffSize =tensor.size()*sizeof(DataType);\n  const size_t chip1TensorBuffSize =chip1.size()*sizeof(DataType);\n  DataType* gpu_data_tensor  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  DataType* gpu_data_chip1  = static_cast<DataType*>(sycl_device.allocate(chip1TensorBuffSize));\n\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_tensor(gpu_data_tensor, tensorRange);\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip1(gpu_data_chip1, chip1TensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_tensor, tensor.data(), tensorBuffSize);\n  gpu_chip1.device(sycl_device)=gpu_tensor.chip(1l,0l);\n  sycl_device.memcpyDeviceToHost(chip1.data(), gpu_data_chip1, chip1TensorBuffSize);\n\n  VERIFY_IS_EQUAL(chip1.dimension(0), sizeDim2);\n  VERIFY_IS_EQUAL(chip1.dimension(1), sizeDim3);\n  VERIFY_IS_EQUAL(chip1.dimension(2), sizeDim4);\n  VERIFY_IS_EQUAL(chip1.dimension(3), sizeDim5);\n\n  for (IndexType i = 0; i < sizeDim2; ++i) {\n    for (IndexType j = 0; j < sizeDim3; ++j) {\n      for (IndexType k = 0; k < sizeDim4; ++k) {\n        for (IndexType l = 0; l < sizeDim5; ++l) {\n          VERIFY_IS_EQUAL(chip1(i,j,k,l), tensor(1l,i,j,k,l));\n        }\n      }\n    }\n  }\n\n  array<IndexType, 4> chip2TensorRange = {{sizeDim1, sizeDim3, sizeDim4, sizeDim5}};\n  Tensor<DataType, 4, DataLayout,IndexType> chip2(chip2TensorRange);\n  const size_t chip2TensorBuffSize =chip2.size()*sizeof(DataType);\n  DataType* gpu_data_chip2  = static_cast<DataType*>(sycl_device.allocate(chip2TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip2(gpu_data_chip2, chip2TensorRange);\n\n  gpu_chip2.device(sycl_device)=gpu_tensor.chip(1l,1l);\n  sycl_device.memcpyDeviceToHost(chip2.data(), gpu_data_chip2, chip2TensorBuffSize);\n\n  VERIFY_IS_EQUAL(chip2.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(chip2.dimension(1), sizeDim3);\n  VERIFY_IS_EQUAL(chip2.dimension(2), sizeDim4);\n  VERIFY_IS_EQUAL(chip2.dimension(3), sizeDim5);\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim3; ++j) {\n      for (IndexType k = 0; k < sizeDim4; ++k) {\n        for (IndexType l = 0; l < sizeDim5; ++l) {\n          VERIFY_IS_EQUAL(chip2(i,j,k,l), tensor(i,1l,j,k,l));\n        }\n      }\n    }\n  }\n\n  array<IndexType, 4> chip3TensorRange = {{sizeDim1, sizeDim2, sizeDim4, sizeDim5}};\n  Tensor<DataType, 4, DataLayout,IndexType> chip3(chip3TensorRange);\n  const size_t chip3TensorBuffSize =chip3.size()*sizeof(DataType);\n  DataType* gpu_data_chip3  = static_cast<DataType*>(sycl_device.allocate(chip3TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip3(gpu_data_chip3, chip3TensorRange);\n\n  gpu_chip3.device(sycl_device)=gpu_tensor.chip(2l,2l);\n  sycl_device.memcpyDeviceToHost(chip3.data(), gpu_data_chip3, chip3TensorBuffSize);\n\n  VERIFY_IS_EQUAL(chip3.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(chip3.dimension(1), sizeDim2);\n  VERIFY_IS_EQUAL(chip3.dimension(2), sizeDim4);\n  VERIFY_IS_EQUAL(chip3.dimension(3), sizeDim5);\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim4; ++k) {\n        for (IndexType l = 0; l < sizeDim5; ++l) {\n          VERIFY_IS_EQUAL(chip3(i,j,k,l), tensor(i,j,2l,k,l));\n        }\n      }\n    }\n  }\n\n  array<IndexType, 4> chip4TensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim5}};\n  Tensor<DataType, 4, DataLayout,IndexType> chip4(chip4TensorRange);\n  const size_t chip4TensorBuffSize =chip4.size()*sizeof(DataType);\n  DataType* gpu_data_chip4  = static_cast<DataType*>(sycl_device.allocate(chip4TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip4(gpu_data_chip4, chip4TensorRange);\n\n  gpu_chip4.device(sycl_device)=gpu_tensor.chip(5l,3l);\n  sycl_device.memcpyDeviceToHost(chip4.data(), gpu_data_chip4, chip4TensorBuffSize);\n\n  VERIFY_IS_EQUAL(chip4.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(chip4.dimension(1), sizeDim2);\n  VERIFY_IS_EQUAL(chip4.dimension(2), sizeDim3);\n  VERIFY_IS_EQUAL(chip4.dimension(3), sizeDim5);\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        for (IndexType l = 0; l < sizeDim5; ++l) {\n          VERIFY_IS_EQUAL(chip4(i,j,k,l), tensor(i,j,k,5l,l));\n        }\n      }\n    }\n  }\n\n\n  array<IndexType, 4> chip5TensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  Tensor<DataType, 4, DataLayout,IndexType> chip5(chip5TensorRange);\n  const size_t chip5TensorBuffSize =chip5.size()*sizeof(DataType);\n  DataType* gpu_data_chip5  = static_cast<DataType*>(sycl_device.allocate(chip5TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip5(gpu_data_chip5, chip5TensorRange);\n\n  gpu_chip5.device(sycl_device)=gpu_tensor.chip(7l,4l);\n  sycl_device.memcpyDeviceToHost(chip5.data(), gpu_data_chip5, chip5TensorBuffSize);\n\n  VERIFY_IS_EQUAL(chip5.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(chip5.dimension(1), sizeDim2);\n  VERIFY_IS_EQUAL(chip5.dimension(2), sizeDim3);\n  VERIFY_IS_EQUAL(chip5.dimension(3), sizeDim4);\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        for (IndexType l = 0; l < sizeDim4; ++l) {\n          VERIFY_IS_EQUAL(chip5(i,j,k,l), tensor(i,j,k,l,7l));\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data_tensor);\n  sycl_device.deallocate(gpu_data_chip1);\n  sycl_device.deallocate(gpu_data_chip2);\n  sycl_device.deallocate(gpu_data_chip3);\n  sycl_device.deallocate(gpu_data_chip4);\n  sycl_device.deallocate(gpu_data_chip5);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_chip_in_expr(const Eigen::SyclDevice& sycl_device) {\n\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  IndexType sizeDim5 = 11;\n\n  array<IndexType, 5> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4, sizeDim5}};\n  array<IndexType, 4> chip1TensorRange = {{sizeDim2, sizeDim3, sizeDim4, sizeDim5}};\n\n  Tensor<DataType, 5, DataLayout,IndexType> tensor(tensorRange);\n\n  Tensor<DataType, 4, DataLayout,IndexType> chip1(chip1TensorRange);\n  Tensor<DataType, 4, DataLayout,IndexType> tensor1(chip1TensorRange);\n  tensor.setRandom();\n  tensor1.setRandom();\n\n  const size_t tensorBuffSize =tensor.size()*sizeof(DataType);\n  const size_t chip1TensorBuffSize =chip1.size()*sizeof(DataType);\n  DataType* gpu_data_tensor  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  DataType* gpu_data_chip1  = static_cast<DataType*>(sycl_device.allocate(chip1TensorBuffSize));\n  DataType* gpu_data_tensor1  = static_cast<DataType*>(sycl_device.allocate(chip1TensorBuffSize));\n\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_tensor(gpu_data_tensor, tensorRange);\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_chip1(gpu_data_chip1, chip1TensorRange);\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_tensor1(gpu_data_tensor1, chip1TensorRange);\n\n\n  sycl_device.memcpyHostToDevice(gpu_data_tensor, tensor.data(), tensorBuffSize);\n  sycl_device.memcpyHostToDevice(gpu_data_tensor1, tensor1.data(), chip1TensorBuffSize);\n  gpu_chip1.device(sycl_device)=gpu_tensor.template chip<0l>(0l) + gpu_tensor1;\n  sycl_device.memcpyDeviceToHost(chip1.data(), gpu_data_chip1, chip1TensorBuffSize);\n\n  for (int i = 0; i < sizeDim2; ++i) {\n    for (int j = 0; j < sizeDim3; ++j) {\n      for (int k = 0; k < sizeDim4; ++k) {\n        for (int l = 0; l < sizeDim5; ++l) {\n          float expected = tensor(0l,i,j,k,l) + tensor1(i,j,k,l);\n          VERIFY_IS_EQUAL(chip1(i,j,k,l), expected);\n        }\n      }\n    }\n  }\n\n  array<IndexType, 3> chip2TensorRange = {{sizeDim2, sizeDim4, sizeDim5}};\n  Tensor<DataType, 3, DataLayout,IndexType> tensor2(chip2TensorRange);\n  Tensor<DataType, 3, DataLayout,IndexType> chip2(chip2TensorRange);\n  tensor2.setRandom();\n  const size_t chip2TensorBuffSize =tensor2.size()*sizeof(DataType);\n  DataType* gpu_data_tensor2  = static_cast<DataType*>(sycl_device.allocate(chip2TensorBuffSize));\n  DataType* gpu_data_chip2  = static_cast<DataType*>(sycl_device.allocate(chip2TensorBuffSize));\n  TensorMap<Tensor<DataType, 3, DataLayout,IndexType>> gpu_tensor2(gpu_data_tensor2, chip2TensorRange);\n  TensorMap<Tensor<DataType, 3, DataLayout,IndexType>> gpu_chip2(gpu_data_chip2, chip2TensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_tensor2, tensor2.data(), chip2TensorBuffSize);\n  gpu_chip2.device(sycl_device)=gpu_tensor.template chip<0l>(0l).template chip<1l>(2l) + gpu_tensor2;\n  sycl_device.memcpyDeviceToHost(chip2.data(), gpu_data_chip2, chip2TensorBuffSize);\n\n  for (int i = 0; i < sizeDim2; ++i) {\n    for (int j = 0; j < sizeDim4; ++j) {\n      for (int k = 0; k < sizeDim5; ++k) {\n        float expected = tensor(0l,i,2l,j,k) + tensor2(i,j,k);\n        VERIFY_IS_EQUAL(chip2(i,j,k), expected);\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data_tensor);\n  sycl_device.deallocate(gpu_data_tensor1);\n  sycl_device.deallocate(gpu_data_chip1);\n  sycl_device.deallocate(gpu_data_tensor2);\n  sycl_device.deallocate(gpu_data_chip2);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_chip_as_lvalue_sycl(const Eigen::SyclDevice& sycl_device)\n{\n\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  IndexType sizeDim5 = 11;\n\n  array<IndexType, 5> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4, sizeDim5}};\n  array<IndexType, 4> input2TensorRange = {{sizeDim2, sizeDim3, sizeDim4, sizeDim5}};\n\n  Tensor<DataType, 5, DataLayout,IndexType> tensor(tensorRange);\n  Tensor<DataType, 5, DataLayout,IndexType> input1(tensorRange);\n  Tensor<DataType, 4, DataLayout,IndexType> input2(input2TensorRange);\n  input1.setRandom();\n  input2.setRandom();\n\n\n  const size_t tensorBuffSize =tensor.size()*sizeof(DataType);\n  const size_t input2TensorBuffSize =input2.size()*sizeof(DataType);\n  std::cout << tensorBuffSize << \" , \"<<  input2TensorBuffSize << std::endl;\n  DataType* gpu_data_tensor  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  DataType* gpu_data_input1  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  DataType* gpu_data_input2  = static_cast<DataType*>(sycl_device.allocate(input2TensorBuffSize));\n\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_tensor(gpu_data_tensor, tensorRange);\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_input1(gpu_data_input1, tensorRange);\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_input2(gpu_data_input2, input2TensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_input1, input1.data(), tensorBuffSize);\n  gpu_tensor.device(sycl_device)=gpu_input1;\n  sycl_device.memcpyHostToDevice(gpu_data_input2, input2.data(), input2TensorBuffSize);\n  gpu_tensor.template chip<0l>(1l).device(sycl_device)=gpu_input2;\n  sycl_device.memcpyDeviceToHost(tensor.data(), gpu_data_tensor, tensorBuffSize);\n\n  for (int i = 0; i < sizeDim1; ++i) {\n    for (int j = 0; j < sizeDim2; ++j) {\n      for (int k = 0; k < sizeDim3; ++k) {\n        for (int l = 0; l < sizeDim4; ++l) {\n          for (int m = 0; m < sizeDim5; ++m) {\n            if (i != 1) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input2(j,k,l,m));\n            }\n          }\n        }\n      }\n    }\n  }\n\n  gpu_tensor.device(sycl_device)=gpu_input1;\n  array<IndexType, 4> input3TensorRange = {{sizeDim1, sizeDim3, sizeDim4, sizeDim5}};\n  Tensor<DataType, 4, DataLayout,IndexType> input3(input3TensorRange);\n  input3.setRandom();\n\n  const size_t input3TensorBuffSize =input3.size()*sizeof(DataType);\n  DataType* gpu_data_input3  = static_cast<DataType*>(sycl_device.allocate(input3TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_input3(gpu_data_input3, input3TensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_input3, input3.data(), input3TensorBuffSize);\n  gpu_tensor.template chip<1l>(1l).device(sycl_device)=gpu_input3;\n  sycl_device.memcpyDeviceToHost(tensor.data(), gpu_data_tensor, tensorBuffSize);\n\n  for (int i = 0; i < sizeDim1; ++i) {\n    for (int j = 0; j < sizeDim2; ++j) {\n      for (int k = 0; k <sizeDim3; ++k) {\n        for (int l = 0; l < sizeDim4; ++l) {\n          for (int m = 0; m < sizeDim5; ++m) {\n            if (j != 1) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input3(i,k,l,m));\n            }\n          }\n        }\n      }\n    }\n  }\n\n  gpu_tensor.device(sycl_device)=gpu_input1;\n  array<IndexType, 4> input4TensorRange = {{sizeDim1, sizeDim2, sizeDim4, sizeDim5}};\n  Tensor<DataType, 4, DataLayout,IndexType> input4(input4TensorRange);\n  input4.setRandom();\n\n  const size_t input4TensorBuffSize =input4.size()*sizeof(DataType);\n  DataType* gpu_data_input4  = static_cast<DataType*>(sycl_device.allocate(input4TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_input4(gpu_data_input4, input4TensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_input4, input4.data(), input4TensorBuffSize);\n  gpu_tensor.template chip<2l>(3l).device(sycl_device)=gpu_input4;\n  sycl_device.memcpyDeviceToHost(tensor.data(), gpu_data_tensor, tensorBuffSize);\n\n  for (int i = 0; i < sizeDim1; ++i) {\n    for (int j = 0; j < sizeDim2; ++j) {\n      for (int k = 0; k <sizeDim3; ++k) {\n        for (int l = 0; l < sizeDim4; ++l) {\n          for (int m = 0; m < sizeDim5; ++m) {\n            if (k != 3) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input4(i,j,l,m));\n            }\n          }\n        }\n      }\n    }\n  }\n\n  gpu_tensor.device(sycl_device)=gpu_input1;\n  array<IndexType, 4> input5TensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim5}};\n  Tensor<DataType, 4, DataLayout,IndexType> input5(input5TensorRange);\n  input5.setRandom();\n\n  const size_t input5TensorBuffSize =input5.size()*sizeof(DataType);\n  DataType* gpu_data_input5  = static_cast<DataType*>(sycl_device.allocate(input5TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_input5(gpu_data_input5, input5TensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_input5, input5.data(), input5TensorBuffSize);\n  gpu_tensor.template chip<3l>(4l).device(sycl_device)=gpu_input5;\n  sycl_device.memcpyDeviceToHost(tensor.data(), gpu_data_tensor, tensorBuffSize);\n\n  for (int i = 0; i < sizeDim1; ++i) {\n    for (int j = 0; j < sizeDim2; ++j) {\n      for (int k = 0; k <sizeDim3; ++k) {\n        for (int l = 0; l < sizeDim4; ++l) {\n          for (int m = 0; m < sizeDim5; ++m) {\n            if (l != 4) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input5(i,j,k,m));\n            }\n          }\n        }\n      }\n    }\n  }\n  gpu_tensor.device(sycl_device)=gpu_input1;\n  array<IndexType, 4> input6TensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  Tensor<DataType, 4, DataLayout,IndexType> input6(input6TensorRange);\n  input6.setRandom();\n\n  const size_t input6TensorBuffSize =input6.size()*sizeof(DataType);\n  DataType* gpu_data_input6  = static_cast<DataType*>(sycl_device.allocate(input6TensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_input6(gpu_data_input6, input6TensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_input6, input6.data(), input6TensorBuffSize);\n  gpu_tensor.template chip<4l>(5l).device(sycl_device)=gpu_input6;\n  sycl_device.memcpyDeviceToHost(tensor.data(), gpu_data_tensor, tensorBuffSize);\n\n  for (int i = 0; i < sizeDim1; ++i) {\n    for (int j = 0; j < sizeDim2; ++j) {\n      for (int k = 0; k <sizeDim3; ++k) {\n        for (int l = 0; l < sizeDim4; ++l) {\n          for (int m = 0; m < sizeDim5; ++m) {\n            if (m != 5) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input6(i,j,k,l));\n            }\n          }\n        }\n      }\n    }\n  }\n\n\n  gpu_tensor.device(sycl_device)=gpu_input1;\n  Tensor<DataType, 5, DataLayout,IndexType> input7(tensorRange);\n  input7.setRandom();\n\n  DataType* gpu_data_input7  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_input7(gpu_data_input7, tensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_input7, input7.data(), tensorBuffSize);\n  gpu_tensor.chip(0l,0l).device(sycl_device)=gpu_input7.chip(0l,0l);\n  sycl_device.memcpyDeviceToHost(tensor.data(), gpu_data_tensor, tensorBuffSize);\n\n  for (int i = 0; i < sizeDim1; ++i) {\n    for (int j = 0; j < sizeDim2; ++j) {\n      for (int k = 0; k <sizeDim3; ++k) {\n        for (int l = 0; l < sizeDim4; ++l) {\n          for (int m = 0; m < sizeDim5; ++m) {\n            if (i != 0) {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input1(i,j,k,l,m));\n            } else {\n              VERIFY_IS_EQUAL(tensor(i,j,k,l,m), input7(i,j,k,l,m));\n            }\n          }\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data_tensor);\n  sycl_device.deallocate(gpu_data_input1);\n  sycl_device.deallocate(gpu_data_input2);\n  sycl_device.deallocate(gpu_data_input3);\n  sycl_device.deallocate(gpu_data_input4);\n  sycl_device.deallocate(gpu_data_input5);\n  sycl_device.deallocate(gpu_data_input6);\n  sycl_device.deallocate(gpu_data_input7);\n\n}\n\ntemplate<typename DataType, typename dev_Selector> void sycl_chipping_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n /* test_static_chip_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_static_chip_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_dynamic_chip_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_dynamic_chip_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_chip_in_expr<DataType, RowMajor, int64_t>(sycl_device);\n  test_chip_in_expr<DataType, ColMajor, int64_t>(sycl_device);*/\n  test_chip_as_lvalue_sycl<DataType, RowMajor, int64_t>(sycl_device);\n // test_chip_as_lvalue_sycl<DataType, ColMajor, int64_t>(sycl_device);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_chipping_sycl)\n{\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_chipping_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_comparisons.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\nstatic void test_orderings()\n{\n  Tensor<float, 3> mat1(2,3,7);\n  Tensor<float, 3> mat2(2,3,7);\n  Tensor<bool, 3> lt(2,3,7);\n  Tensor<bool, 3> le(2,3,7);\n  Tensor<bool, 3> gt(2,3,7);\n  Tensor<bool, 3> ge(2,3,7);\n\n  mat1.setRandom();\n  mat2.setRandom();\n\n  lt = mat1 < mat2;\n  le = mat1 <= mat2;\n  gt = mat1 > mat2;\n  ge = mat1 >= mat2;\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(lt(i,j,k), mat1(i,j,k) < mat2(i,j,k));\n        VERIFY_IS_EQUAL(le(i,j,k), mat1(i,j,k) <= mat2(i,j,k));\n        VERIFY_IS_EQUAL(gt(i,j,k), mat1(i,j,k) > mat2(i,j,k));\n        VERIFY_IS_EQUAL(ge(i,j,k), mat1(i,j,k) >= mat2(i,j,k));\n      }\n    }\n  }\n}\n\n\nstatic void test_equality()\n{\n  Tensor<float, 3> mat1(2,3,7);\n  Tensor<float, 3> mat2(2,3,7);\n\n  mat1.setRandom();\n  mat2.setRandom();\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        if (internal::random<bool>()) {\n          mat2(i,j,k) = mat1(i,j,k);\n        }\n      }\n    }\n  }\n\n  Tensor<bool, 3> eq(2,3,7);\n  Tensor<bool, 3> ne(2,3,7);\n  eq = (mat1 == mat2);\n  ne = (mat1 != mat2);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(eq(i,j,k), mat1(i,j,k) == mat2(i,j,k));\n        VERIFY_IS_EQUAL(ne(i,j,k), mat1(i,j,k) != mat2(i,j,k));\n      }\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_comparisons)\n{\n  CALL_SUBTEST(test_orderings());\n  CALL_SUBTEST(test_equality());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_complex_cwise_ops_gpu.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate<typename T>\nvoid test_cuda_complex_cwise_ops() {\n  const int kNumItems = 2;\n  std::size_t complex_bytes = kNumItems * sizeof(std::complex<T>);\n\n  std::complex<T>* d_in1;\n  std::complex<T>* d_in2;\n  std::complex<T>* d_out;\n  cudaMalloc((void**)(&d_in1), complex_bytes);\n  cudaMalloc((void**)(&d_in2), complex_bytes);\n  cudaMalloc((void**)(&d_out), complex_bytes);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<std::complex<T>, 1, 0, int>, Eigen::Aligned> gpu_in1(\n      d_in1, kNumItems);\n  Eigen::TensorMap<Eigen::Tensor<std::complex<T>, 1, 0, int>, Eigen::Aligned> gpu_in2(\n      d_in2, kNumItems);\n  Eigen::TensorMap<Eigen::Tensor<std::complex<T>, 1, 0, int>, Eigen::Aligned> gpu_out(\n      d_out, kNumItems);\n\n  const std::complex<T> a(3.14f, 2.7f);\n  const std::complex<T> b(-10.6f, 1.4f);\n\n  gpu_in1.device(gpu_device) = gpu_in1.constant(a);\n  gpu_in2.device(gpu_device) = gpu_in2.constant(b);\n\n  enum CwiseOp {\n    Add = 0,\n    Sub,\n    Mul,\n    Div,\n    Neg,\n    NbOps\n  };\n\n  Tensor<std::complex<T>, 1, 0, int> actual(kNumItems);\n  for (int op = Add; op < NbOps; op++) {\n    std::complex<T> expected;\n    switch (static_cast<CwiseOp>(op)) {\n      case Add:\n        gpu_out.device(gpu_device) = gpu_in1 + gpu_in2;\n        expected = a + b;\n        break;\n      case Sub:\n        gpu_out.device(gpu_device) = gpu_in1 - gpu_in2;\n        expected = a - b;\n        break;\n      case Mul:\n        gpu_out.device(gpu_device) = gpu_in1 * gpu_in2;\n        expected = a * b;\n        break;\n      case Div:\n        gpu_out.device(gpu_device) = gpu_in1 / gpu_in2;\n        expected = a / b;\n        break;\n      case Neg:\n        gpu_out.device(gpu_device) = -gpu_in1;\n        expected = -a;\n        break;\n      case NbOps:\n        break;\n    }\n    assert(cudaMemcpyAsync(actual.data(), d_out, complex_bytes, cudaMemcpyDeviceToHost,\n                           gpu_device.stream()) == cudaSuccess);\n    assert(cudaStreamSynchronize(gpu_device.stream()) == cudaSuccess);\n\n    for (int i = 0; i < kNumItems; ++i) {\n      VERIFY_IS_APPROX(actual(i), expected);\n    }\n  }\n\n  cudaFree(d_in1);\n  cudaFree(d_in2);\n  cudaFree(d_out);\n}\n\n\nEIGEN_DECLARE_TEST(test_cxx11_tensor_complex_cwise_ops)\n{\n  CALL_SUBTEST(test_cuda_complex_cwise_ops<float>());\n  CALL_SUBTEST(test_cuda_complex_cwise_ops<double>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_complex_gpu.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\nvoid test_cuda_nullary() {\n  Tensor<std::complex<float>, 1, 0, int> in1(2);\n  Tensor<std::complex<float>, 1, 0, int> in2(2);\n  in1.setRandom();\n  in2.setRandom();\n\n  std::size_t float_bytes = in1.size() * sizeof(float);\n  std::size_t complex_bytes = in1.size() * sizeof(std::complex<float>);\n\n  std::complex<float>* d_in1;\n  std::complex<float>* d_in2;\n  float* d_out2;\n  cudaMalloc((void**)(&d_in1), complex_bytes);\n  cudaMalloc((void**)(&d_in2), complex_bytes);\n  cudaMalloc((void**)(&d_out2), float_bytes);\n  cudaMemcpy(d_in1, in1.data(), complex_bytes, cudaMemcpyHostToDevice);\n  cudaMemcpy(d_in2, in2.data(), complex_bytes, cudaMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<std::complex<float>, 1, 0, int>, Eigen::Aligned> gpu_in1(\n      d_in1, 2);\n  Eigen::TensorMap<Eigen::Tensor<std::complex<float>, 1, 0, int>, Eigen::Aligned> gpu_in2(\n      d_in2, 2);\n  Eigen::TensorMap<Eigen::Tensor<float, 1, 0, int>, Eigen::Aligned> gpu_out2(\n      d_out2, 2);\n\n  gpu_in1.device(gpu_device) = gpu_in1.constant(std::complex<float>(3.14f, 2.7f));\n  gpu_out2.device(gpu_device) = gpu_in2.abs();\n\n  Tensor<std::complex<float>, 1, 0, int> new1(2);\n  Tensor<float, 1, 0, int> new2(2);\n\n  assert(cudaMemcpyAsync(new1.data(), d_in1, complex_bytes, cudaMemcpyDeviceToHost,\n                         gpu_device.stream()) == cudaSuccess);\n  assert(cudaMemcpyAsync(new2.data(), d_out2, float_bytes, cudaMemcpyDeviceToHost,\n                         gpu_device.stream()) == cudaSuccess);\n\n  assert(cudaStreamSynchronize(gpu_device.stream()) == cudaSuccess);\n\n  for (int i = 0; i < 2; ++i) {\n    VERIFY_IS_APPROX(new1(i), std::complex<float>(3.14f, 2.7f));\n    VERIFY_IS_APPROX(new2(i), std::abs(in2(i)));\n  }\n\n  cudaFree(d_in1);\n  cudaFree(d_in2);\n  cudaFree(d_out2);\n}\n\n\nstatic void test_cuda_sum_reductions() {\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  const int num_rows = internal::random<int>(1024, 5*1024);\n  const int num_cols = internal::random<int>(1024, 5*1024);\n\n  Tensor<std::complex<float>, 2> in(num_rows, num_cols);\n  in.setRandom();\n\n  Tensor<std::complex<float>, 0> full_redux;\n  full_redux = in.sum();\n\n  std::size_t in_bytes = in.size() * sizeof(std::complex<float>);\n  std::size_t out_bytes = full_redux.size() * sizeof(std::complex<float>);\n  std::complex<float>* gpu_in_ptr = static_cast<std::complex<float>*>(gpu_device.allocate(in_bytes));\n  std::complex<float>* gpu_out_ptr = static_cast<std::complex<float>*>(gpu_device.allocate(out_bytes));\n  gpu_device.memcpyHostToDevice(gpu_in_ptr, in.data(), in_bytes);\n\n  TensorMap<Tensor<std::complex<float>, 2> > in_gpu(gpu_in_ptr, num_rows, num_cols);\n  TensorMap<Tensor<std::complex<float>, 0> > out_gpu(gpu_out_ptr);\n\n  out_gpu.device(gpu_device) = in_gpu.sum();\n\n  Tensor<std::complex<float>, 0> full_redux_gpu;\n  gpu_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_ptr, out_bytes);\n  gpu_device.synchronize();\n\n  // Check that the CPU and GPU reductions return the same result.\n  VERIFY_IS_APPROX(full_redux(), full_redux_gpu());\n\n  gpu_device.deallocate(gpu_in_ptr);\n  gpu_device.deallocate(gpu_out_ptr);\n}\n\nstatic void test_cuda_mean_reductions() {\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  const int num_rows = internal::random<int>(1024, 5*1024);\n  const int num_cols = internal::random<int>(1024, 5*1024);\n\n  Tensor<std::complex<float>, 2> in(num_rows, num_cols);\n  in.setRandom();\n\n  Tensor<std::complex<float>, 0> full_redux;\n  full_redux = in.mean();\n\n  std::size_t in_bytes = in.size() * sizeof(std::complex<float>);\n  std::size_t out_bytes = full_redux.size() * sizeof(std::complex<float>);\n  std::complex<float>* gpu_in_ptr = static_cast<std::complex<float>*>(gpu_device.allocate(in_bytes));\n  std::complex<float>* gpu_out_ptr = static_cast<std::complex<float>*>(gpu_device.allocate(out_bytes));\n  gpu_device.memcpyHostToDevice(gpu_in_ptr, in.data(), in_bytes);\n\n  TensorMap<Tensor<std::complex<float>, 2> > in_gpu(gpu_in_ptr, num_rows, num_cols);\n  TensorMap<Tensor<std::complex<float>, 0> > out_gpu(gpu_out_ptr);\n\n  out_gpu.device(gpu_device) = in_gpu.mean();\n\n  Tensor<std::complex<float>, 0> full_redux_gpu;\n  gpu_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_ptr, out_bytes);\n  gpu_device.synchronize();\n\n  // Check that the CPU and GPU reductions return the same result.\n  VERIFY_IS_APPROX(full_redux(), full_redux_gpu());\n\n  gpu_device.deallocate(gpu_in_ptr);\n  gpu_device.deallocate(gpu_out_ptr);\n}\n\nstatic void test_cuda_product_reductions() {\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  const int num_rows = internal::random<int>(1024, 5*1024);\n  const int num_cols = internal::random<int>(1024, 5*1024);\n\n  Tensor<std::complex<float>, 2> in(num_rows, num_cols);\n  in.setRandom();\n\n  Tensor<std::complex<float>, 0> full_redux;\n  full_redux = in.prod();\n\n  std::size_t in_bytes = in.size() * sizeof(std::complex<float>);\n  std::size_t out_bytes = full_redux.size() * sizeof(std::complex<float>);\n  std::complex<float>* gpu_in_ptr = static_cast<std::complex<float>*>(gpu_device.allocate(in_bytes));\n  std::complex<float>* gpu_out_ptr = static_cast<std::complex<float>*>(gpu_device.allocate(out_bytes));\n  gpu_device.memcpyHostToDevice(gpu_in_ptr, in.data(), in_bytes);\n\n  TensorMap<Tensor<std::complex<float>, 2> > in_gpu(gpu_in_ptr, num_rows, num_cols);\n  TensorMap<Tensor<std::complex<float>, 0> > out_gpu(gpu_out_ptr);\n\n  out_gpu.device(gpu_device) = in_gpu.prod();\n\n  Tensor<std::complex<float>, 0> full_redux_gpu;\n  gpu_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_ptr, out_bytes);\n  gpu_device.synchronize();\n\n  // Check that the CPU and GPU reductions return the same result.\n  VERIFY_IS_APPROX(full_redux(), full_redux_gpu());\n\n  gpu_device.deallocate(gpu_in_ptr);\n  gpu_device.deallocate(gpu_out_ptr);\n}\n\n\nEIGEN_DECLARE_TEST(test_cxx11_tensor_complex)\n{\n  CALL_SUBTEST(test_cuda_nullary());\n  CALL_SUBTEST(test_cuda_sum_reductions());\n  CALL_SUBTEST(test_cuda_mean_reductions());\n  CALL_SUBTEST(test_cuda_product_reductions());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_concatenation.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate<int DataLayout>\nstatic void test_dimension_failures()\n{\n  Tensor<int, 3, DataLayout> left(2, 3, 1);\n  Tensor<int, 3, DataLayout> right(3, 3, 1);\n  left.setRandom();\n  right.setRandom();\n\n  // Okay; other dimensions are equal.\n  Tensor<int, 3, DataLayout> concatenation = left.concatenate(right, 0);\n\n  // Dimension mismatches.\n  VERIFY_RAISES_ASSERT(concatenation = left.concatenate(right, 1));\n  VERIFY_RAISES_ASSERT(concatenation = left.concatenate(right, 2));\n\n  // Axis > NumDims or < 0.\n  VERIFY_RAISES_ASSERT(concatenation = left.concatenate(right, 3));\n  VERIFY_RAISES_ASSERT(concatenation = left.concatenate(right, -1));\n}\n\ntemplate<int DataLayout>\nstatic void test_static_dimension_failure()\n{\n  Tensor<int, 2, DataLayout> left(2, 3);\n  Tensor<int, 3, DataLayout> right(2, 3, 1);\n\n#ifdef CXX11_TENSOR_CONCATENATION_STATIC_DIMENSION_FAILURE\n  // Technically compatible, but we static assert that the inputs have same\n  // NumDims.\n  Tensor<int, 3, DataLayout> concatenation = left.concatenate(right, 0);\n#endif\n\n  // This can be worked around in this case.\n  Tensor<int, 3, DataLayout> concatenation = left\n      .reshape(Tensor<int, 3>::Dimensions(2, 3, 1))\n      .concatenate(right, 0);\n  Tensor<int, 2, DataLayout> alternative = left\n   // Clang compiler break with {{{}}} with an ambiguous error on copy constructor\n  // the variadic DSize constructor added for #ifndef EIGEN_EMULATE_CXX11_META_H.\n  // Solution:\n  // either the code should change to \n  //  Tensor<int, 2>::Dimensions{{2, 3}}\n  // or Tensor<int, 2>::Dimensions{Tensor<int, 2>::Dimensions{{2, 3}}}\n      .concatenate(right.reshape(Tensor<int, 2>::Dimensions(2, 3)), 0);\n}\n\ntemplate<int DataLayout>\nstatic void test_simple_concatenation()\n{\n  Tensor<int, 3, DataLayout> left(2, 3, 1);\n  Tensor<int, 3, DataLayout> right(2, 3, 1);\n  left.setRandom();\n  right.setRandom();\n\n  Tensor<int, 3, DataLayout> concatenation = left.concatenate(right, 0);\n  VERIFY_IS_EQUAL(concatenation.dimension(0), 4);\n  VERIFY_IS_EQUAL(concatenation.dimension(1), 3);\n  VERIFY_IS_EQUAL(concatenation.dimension(2), 1);\n  for (int j = 0; j < 3; ++j) {\n    for (int i = 0; i < 2; ++i) {\n      VERIFY_IS_EQUAL(concatenation(i, j, 0), left(i, j, 0));\n    }\n    for (int i = 2; i < 4; ++i) {\n      VERIFY_IS_EQUAL(concatenation(i, j, 0), right(i - 2, j, 0));\n    }\n  }\n\n  concatenation = left.concatenate(right, 1);\n  VERIFY_IS_EQUAL(concatenation.dimension(0), 2);\n  VERIFY_IS_EQUAL(concatenation.dimension(1), 6);\n  VERIFY_IS_EQUAL(concatenation.dimension(2), 1);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_EQUAL(concatenation(i, j, 0), left(i, j, 0));\n    }\n    for (int j = 3; j < 6; ++j) {\n      VERIFY_IS_EQUAL(concatenation(i, j, 0), right(i, j - 3, 0));\n    }\n  }\n\n  concatenation = left.concatenate(right, 2);\n  VERIFY_IS_EQUAL(concatenation.dimension(0), 2);\n  VERIFY_IS_EQUAL(concatenation.dimension(1), 3);\n  VERIFY_IS_EQUAL(concatenation.dimension(2), 2);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_EQUAL(concatenation(i, j, 0), left(i, j, 0));\n      VERIFY_IS_EQUAL(concatenation(i, j, 1), right(i, j, 0));\n    }\n  }\n}\n\n\n// TODO(phli): Add test once we have a real vectorized implementation.\n// static void test_vectorized_concatenation() {}\n\nstatic void test_concatenation_as_lvalue()\n{\n  Tensor<int, 2> t1(2, 3);\n  Tensor<int, 2> t2(2, 3);\n  t1.setRandom();\n  t2.setRandom();\n\n  Tensor<int, 2> result(4, 3);\n  result.setRandom();\n  t1.concatenate(t2, 0) = result;\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_EQUAL(t1(i, j), result(i, j));\n      VERIFY_IS_EQUAL(t2(i, j), result(i+2, j));\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_concatenation)\n{\n   CALL_SUBTEST(test_dimension_failures<ColMajor>());\n   CALL_SUBTEST(test_dimension_failures<RowMajor>());\n   CALL_SUBTEST(test_static_dimension_failure<ColMajor>());\n   CALL_SUBTEST(test_static_dimension_failure<RowMajor>());\n   CALL_SUBTEST(test_simple_concatenation<ColMajor>());\n   CALL_SUBTEST(test_simple_concatenation<RowMajor>());\n   // CALL_SUBTEST(test_vectorized_concatenation());\n   CALL_SUBTEST(test_concatenation_as_lvalue());\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_concatenation_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate<typename DataType, int DataLayout, typename IndexType>\nstatic void test_simple_concatenation(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType leftDim1 = 2;\n  IndexType leftDim2 = 3;\n  IndexType leftDim3 = 1;\n  Eigen::array<IndexType, 3> leftRange = {{leftDim1, leftDim2, leftDim3}};\n  IndexType rightDim1 = 2;\n  IndexType rightDim2 = 3;\n  IndexType rightDim3 = 1;\n  Eigen::array<IndexType, 3> rightRange = {{rightDim1, rightDim2, rightDim3}};\n\n  //IndexType concatDim1 = 3;\n//\tIndexType concatDim2 = 3;\n//\tIndexType concatDim3 = 1;\n  //Eigen::array<IndexType, 3> concatRange = {{concatDim1, concatDim2, concatDim3}};\n\n  Tensor<DataType, 3, DataLayout, IndexType> left(leftRange);\n  Tensor<DataType, 3, DataLayout, IndexType> right(rightRange);\n  left.setRandom();\n  right.setRandom();\n\n  DataType * gpu_in1_data  = static_cast<DataType*>(sycl_device.allocate(left.dimensions().TotalSize()*sizeof(DataType)));\n  DataType * gpu_in2_data  = static_cast<DataType*>(sycl_device.allocate(right.dimensions().TotalSize()*sizeof(DataType)));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType>> gpu_in1(gpu_in1_data, leftRange);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType>> gpu_in2(gpu_in2_data, rightRange);\n  sycl_device.memcpyHostToDevice(gpu_in1_data, left.data(),(left.dimensions().TotalSize())*sizeof(DataType));\n  sycl_device.memcpyHostToDevice(gpu_in2_data, right.data(),(right.dimensions().TotalSize())*sizeof(DataType));\n  ///\n  Tensor<DataType, 3, DataLayout, IndexType> concatenation1(leftDim1+rightDim1, leftDim2, leftDim3);\n  DataType * gpu_out_data1 =  static_cast<DataType*>(sycl_device.allocate(concatenation1.dimensions().TotalSize()*sizeof(DataType)));\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType>> gpu_out1(gpu_out_data1, concatenation1.dimensions());\n\n  //concatenation = left.concatenate(right, 0);\n  gpu_out1.device(sycl_device) =gpu_in1.concatenate(gpu_in2, 0);\n  sycl_device.memcpyDeviceToHost(concatenation1.data(), gpu_out_data1,(concatenation1.dimensions().TotalSize())*sizeof(DataType));\n\n  VERIFY_IS_EQUAL(concatenation1.dimension(0), 4);\n  VERIFY_IS_EQUAL(concatenation1.dimension(1), 3);\n  VERIFY_IS_EQUAL(concatenation1.dimension(2), 1);\n  for (IndexType j = 0; j < 3; ++j) {\n    for (IndexType i = 0; i < 2; ++i) {\n      VERIFY_IS_EQUAL(concatenation1(i, j, 0), left(i, j, 0));\n    }\n    for (IndexType i = 2; i < 4; ++i) {\n      VERIFY_IS_EQUAL(concatenation1(i, j, 0), right(i - 2, j, 0));\n    }\n  }\n\n  sycl_device.deallocate(gpu_out_data1);\n  Tensor<DataType, 3, DataLayout, IndexType> concatenation2(leftDim1, leftDim2 +rightDim2, leftDim3);\n  DataType * gpu_out_data2 =  static_cast<DataType*>(sycl_device.allocate(concatenation2.dimensions().TotalSize()*sizeof(DataType)));\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType>> gpu_out2(gpu_out_data2, concatenation2.dimensions());\n  gpu_out2.device(sycl_device) =gpu_in1.concatenate(gpu_in2, 1);\n  sycl_device.memcpyDeviceToHost(concatenation2.data(), gpu_out_data2,(concatenation2.dimensions().TotalSize())*sizeof(DataType));\n\n  //concatenation = left.concatenate(right, 1);\n  VERIFY_IS_EQUAL(concatenation2.dimension(0), 2);\n  VERIFY_IS_EQUAL(concatenation2.dimension(1), 6);\n  VERIFY_IS_EQUAL(concatenation2.dimension(2), 1);\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      VERIFY_IS_EQUAL(concatenation2(i, j, 0), left(i, j, 0));\n    }\n    for (IndexType j = 3; j < 6; ++j) {\n      VERIFY_IS_EQUAL(concatenation2(i, j, 0), right(i, j - 3, 0));\n    }\n  }\n  sycl_device.deallocate(gpu_out_data2);\n  Tensor<DataType, 3, DataLayout, IndexType> concatenation3(leftDim1, leftDim2, leftDim3+rightDim3);\n  DataType * gpu_out_data3 =  static_cast<DataType*>(sycl_device.allocate(concatenation3.dimensions().TotalSize()*sizeof(DataType)));\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType>> gpu_out3(gpu_out_data3, concatenation3.dimensions());\n  gpu_out3.device(sycl_device) =gpu_in1.concatenate(gpu_in2, 2);\n  sycl_device.memcpyDeviceToHost(concatenation3.data(), gpu_out_data3,(concatenation3.dimensions().TotalSize())*sizeof(DataType));\n\n  //concatenation = left.concatenate(right, 2);\n  VERIFY_IS_EQUAL(concatenation3.dimension(0), 2);\n  VERIFY_IS_EQUAL(concatenation3.dimension(1), 3);\n  VERIFY_IS_EQUAL(concatenation3.dimension(2), 2);\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      VERIFY_IS_EQUAL(concatenation3(i, j, 0), left(i, j, 0));\n      VERIFY_IS_EQUAL(concatenation3(i, j, 1), right(i, j, 0));\n    }\n  }\n  sycl_device.deallocate(gpu_out_data3);\n  sycl_device.deallocate(gpu_in1_data);\n  sycl_device.deallocate(gpu_in2_data);\n}\ntemplate<typename DataType, int DataLayout, typename IndexType>\nstatic void test_concatenation_as_lvalue(const Eigen::SyclDevice& sycl_device)\n{\n\n  IndexType leftDim1 = 2;\n  IndexType leftDim2 = 3;\n  Eigen::array<IndexType, 2> leftRange = {{leftDim1, leftDim2}};\n\n  IndexType rightDim1 = 2;\n  IndexType rightDim2 = 3;\n  Eigen::array<IndexType, 2> rightRange = {{rightDim1, rightDim2}};\n\n  IndexType concatDim1 = 4;\n  IndexType concatDim2 = 3;\n  Eigen::array<IndexType, 2> resRange = {{concatDim1, concatDim2}};\n\n  Tensor<DataType, 2, DataLayout, IndexType> left(leftRange);\n  Tensor<DataType, 2, DataLayout, IndexType> right(rightRange);\n  Tensor<DataType, 2, DataLayout, IndexType> result(resRange);\n\n  left.setRandom();\n  right.setRandom();\n  result.setRandom();\n\n  DataType * gpu_in1_data  = static_cast<DataType*>(sycl_device.allocate(left.dimensions().TotalSize()*sizeof(DataType)));\n  DataType * gpu_in2_data  = static_cast<DataType*>(sycl_device.allocate(right.dimensions().TotalSize()*sizeof(DataType)));\n  DataType * gpu_out_data =  static_cast<DataType*>(sycl_device.allocate(result.dimensions().TotalSize()*sizeof(DataType)));\n\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>> gpu_in1(gpu_in1_data, leftRange);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>> gpu_in2(gpu_in2_data, rightRange);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>> gpu_out(gpu_out_data, resRange);\n\n  sycl_device.memcpyHostToDevice(gpu_in1_data, left.data(),(left.dimensions().TotalSize())*sizeof(DataType));\n  sycl_device.memcpyHostToDevice(gpu_in2_data, right.data(),(right.dimensions().TotalSize())*sizeof(DataType));\n  sycl_device.memcpyHostToDevice(gpu_out_data, result.data(),(result.dimensions().TotalSize())*sizeof(DataType));\n\n//  t1.concatenate(t2, 0) = result;\n gpu_in1.concatenate(gpu_in2, 0).device(sycl_device) =gpu_out;\n sycl_device.memcpyDeviceToHost(left.data(), gpu_in1_data,(left.dimensions().TotalSize())*sizeof(DataType));\n sycl_device.memcpyDeviceToHost(right.data(), gpu_in2_data,(right.dimensions().TotalSize())*sizeof(DataType));\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      VERIFY_IS_EQUAL(left(i, j), result(i, j));\n      VERIFY_IS_EQUAL(right(i, j), result(i+2, j));\n    }\n  }\n  sycl_device.deallocate(gpu_in1_data);\n  sycl_device.deallocate(gpu_in2_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\n\ntemplate <typename DataType, typename Dev_selector> void tensorConcat_perDevice(Dev_selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_simple_concatenation<DataType, RowMajor, int64_t>(sycl_device);\n  test_simple_concatenation<DataType, ColMajor, int64_t>(sycl_device);\n  test_concatenation_as_lvalue<DataType, ColMajor, int64_t>(sycl_device);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_concatenation_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(tensorConcat_perDevice<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_const.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\nusing Eigen::Tensor;\n\n\nstatic void test_simple_assign()\n{\n  Tensor<int, 3> random(2,3,7);\n  random.setRandom();\n\n  TensorMap<Tensor<const int, 3> > constant(random.data(), 2, 3, 7);\n  Tensor<int, 3> result(2,3,7);\n  result = constant;\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL((result(i,j,k)), random(i,j,k));\n      }\n    }\n  }\n}\n\n\nstatic void test_assign_of_const_tensor()\n{\n  Tensor<int, 3> random(2,3,7);\n  random.setRandom();\n\n  TensorMap<Tensor<const int, 3> > constant1(random.data(), 2, 3, 7);\n  TensorMap<const Tensor<int, 3> > constant2(random.data(), 2, 3, 7);\n  const TensorMap<Tensor<int, 3> > constant3(random.data(), 2, 3, 7);\n\n  Tensor<int, 2> result1 = constant1.chip(0, 2);\n  Tensor<int, 2> result2 = constant2.chip(0, 2);\n  Tensor<int, 2> result3 = constant3.chip(0, 2);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_EQUAL((result1(i,j)), random(i,j,0));\n      VERIFY_IS_EQUAL((result2(i,j)), random(i,j,0));\n      VERIFY_IS_EQUAL((result3(i,j)), random(i,j,0));\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_const)\n{\n  CALL_SUBTEST(test_simple_assign());\n  CALL_SUBTEST(test_assign_of_const_tensor());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_contract_gpu.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n// Copyright (C) 2014 Navdeep Jaitly <ndjaitly@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\n#include <unsupported/Eigen/CXX11/src/Tensor/TensorGpuHipCudaDefines.h>\n\nusing Eigen::Tensor;\ntypedef Tensor<float, 1>::DimensionPair DimPair;\n\ntemplate<int DataLayout>\nvoid test_gpu_contraction(int m_size, int k_size, int n_size)\n{\n  std::cout << \"Testing for (\" << m_size << \",\" << k_size << \",\" << n_size << \")\" << std::endl;\n  // with these dimensions, the output has 300 * 140 elements, which is\n  // more than 30 * 1024, which is the number of threads in blocks on\n  // a 15 SM GK110 GPU\n  Tensor<float, 2, DataLayout> t_left(m_size, k_size);\n  Tensor<float, 2, DataLayout> t_right(k_size, n_size);\n  Tensor<float, 2, DataLayout> t_result(m_size, n_size);\n  Tensor<float, 2, DataLayout> t_result_gpu(m_size, n_size);\n  Eigen::array<DimPair, 1> dims(DimPair(1, 0));\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  std::size_t t_left_bytes = t_left.size()  * sizeof(float);\n  std::size_t t_right_bytes = t_right.size() * sizeof(float);\n  std::size_t t_result_bytes = t_result.size() * sizeof(float);\n\n  float* d_t_left;\n  float* d_t_right;\n  float* d_t_result;\n\n  gpuMalloc((void**)(&d_t_left), t_left_bytes);\n  gpuMalloc((void**)(&d_t_right), t_right_bytes);\n  gpuMalloc((void**)(&d_t_result), t_result_bytes);\n\n  gpuMemcpy(d_t_left, t_left.data(), t_left_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_t_right, t_right.data(), t_right_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 2, DataLayout> >\n      gpu_t_left(d_t_left, Eigen::array<int, 2>(m_size, k_size));\n  Eigen::TensorMap<Eigen::Tensor<float, 2, DataLayout> >\n      gpu_t_right(d_t_right, Eigen::array<int, 2>(k_size, n_size));\n  Eigen::TensorMap<Eigen::Tensor<float, 2, DataLayout> >\n      gpu_t_result(d_t_result, Eigen::array<int, 2>(m_size, n_size));\n\n\n  gpu_t_result.device(gpu_device) = gpu_t_left.contract(gpu_t_right, dims);\n  t_result = t_left.contract(t_right, dims);\n\n  gpuMemcpy(t_result_gpu.data(), d_t_result, t_result_bytes, gpuMemcpyDeviceToHost);\n  for (DenseIndex i = 0; i < t_result.size(); i++) {\n    if (fabs(t_result(i) - t_result_gpu(i)) < 1e-4f) {\n      continue;\n    }\n    if (Eigen::internal::isApprox(t_result(i), t_result_gpu(i), 1e-4f)) {\n      continue;\n    }\n    std::cout << \"mismatch detected at index \" << i << \": \" << t_result(i)\n              << \" vs \" <<  t_result_gpu(i) << std::endl;\n    assert(false);\n  }\n\n  gpuFree((void*)d_t_left);\n  gpuFree((void*)d_t_right);\n  gpuFree((void*)d_t_result);\n}\n\n\ntemplate<int DataLayout>\nvoid test_scalar(int m_size, int k_size, int n_size)\n{\n  std::cout << \"Testing for (\" << m_size << \",\" << k_size << \",\" << n_size << \")\" << std::endl;\n  // with these dimensions, the output has 300 * 140 elements, which is\n  // more than 30 * 1024, which is the number of threads in blocks on\n  // a 15 SM GK110 GPU\n  Tensor<float, 2, DataLayout> t_left(m_size, k_size);\n  Tensor<float, 2, DataLayout> t_right(k_size, n_size);\n  Tensor<float, 0, DataLayout> t_result;\n  Tensor<float, 0, DataLayout> t_result_gpu;\n  Eigen::array<DimPair, 2> dims(DimPair(0, 0), DimPair(1, 1));\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  std::size_t t_left_bytes = t_left.size()  * sizeof(float);\n  std::size_t t_right_bytes = t_right.size() * sizeof(float);\n  std::size_t t_result_bytes = sizeof(float);\n\n  float* d_t_left;\n  float* d_t_right;\n  float* d_t_result;\n\n  gpuMalloc((void**)(&d_t_left), t_left_bytes);\n  gpuMalloc((void**)(&d_t_right), t_right_bytes);\n  gpuMalloc((void**)(&d_t_result), t_result_bytes);\n\n  gpuMemcpy(d_t_left, t_left.data(), t_left_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_t_right, t_right.data(), t_right_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 2, DataLayout> >\n      gpu_t_left(d_t_left, m_size, k_size);\n  Eigen::TensorMap<Eigen::Tensor<float, 2, DataLayout> >\n      gpu_t_right(d_t_right, k_size, n_size);\n  Eigen::TensorMap<Eigen::Tensor<float, 0, DataLayout> >\n      gpu_t_result(d_t_result);\n\n  gpu_t_result.device(gpu_device) = gpu_t_left.contract(gpu_t_right, dims);\n  t_result = t_left.contract(t_right, dims);\n\n  gpuMemcpy(t_result_gpu.data(), d_t_result, t_result_bytes, gpuMemcpyDeviceToHost);\n  if (fabs(t_result() - t_result_gpu()) > 1e-4f &&\n      !Eigen::internal::isApprox(t_result(), t_result_gpu(), 1e-4f)) {\n    std::cout << \"mismatch detected: \" << t_result()\n              << \" vs \" <<  t_result_gpu() << std::endl;\n    assert(false);\n  }\n\n  gpuFree((void*)d_t_left);\n  gpuFree((void*)d_t_right);\n  gpuFree((void*)d_t_result);\n}\n\n\ntemplate<int DataLayout>\nvoid test_gpu_contraction_m() {\n  for (int k = 32; k < 256; k++) {\n    test_gpu_contraction<ColMajor>(k, 128, 128);\n    test_gpu_contraction<RowMajor>(k, 128, 128);\n  }\n}\n\ntemplate<int DataLayout>\nvoid test_gpu_contraction_k() {\n  for (int k = 32; k < 256; k++) {\n    test_gpu_contraction<ColMajor>(128, k, 128);\n    test_gpu_contraction<RowMajor>(128, k, 128);\n  }\n}\n\ntemplate<int DataLayout>\nvoid test_gpu_contraction_n() {\n  for (int k = 32; k < 256; k++) {\n    test_gpu_contraction<ColMajor>(128, 128, k);\n    test_gpu_contraction<RowMajor>(128, 128, k);\n  }\n}\n\n\ntemplate<int DataLayout>\nvoid test_gpu_contraction_sizes() {\n  int m_sizes[] = { 31,  39,   63,   64,   65,\n                   127, 129,  255,  257 , 511,\n                   512, 513, 1023, 1024, 1025};\n\n  int n_sizes[] = { 31,  39,   63,   64,   65,\n                   127, 129,  255,  257,  511,\n                   512, 513, 1023, 1024, 1025};\n\n  int k_sizes[] = {  31,   39,  63,  64,   65,\n                     95,   96, 127, 129,  255,\n                    257,  511, 512, 513, 1023,\n                   1024, 1025};\n\n  for (int i = 0; i < 15; i++) {\n    for (int j = 0; j < 15; j++) {\n      for (int k = 0; k < 17; k++) {\n        test_gpu_contraction<DataLayout>(m_sizes[i], n_sizes[j], k_sizes[k]);\n      }\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_contract_gpu)\n{\n  CALL_SUBTEST_1(test_gpu_contraction<ColMajor>(128, 128, 128));\n  CALL_SUBTEST_1(test_gpu_contraction<RowMajor>(128, 128, 128));\n\n  CALL_SUBTEST_1(test_scalar<ColMajor>(128, 128, 128));\n  CALL_SUBTEST_1(test_scalar<RowMajor>(128, 128, 128));\n\n  CALL_SUBTEST_2(test_gpu_contraction_m<ColMajor>());\n  CALL_SUBTEST_3(test_gpu_contraction_m<RowMajor>());\n\n  CALL_SUBTEST_4(test_gpu_contraction_k<ColMajor>());\n  CALL_SUBTEST_5(test_gpu_contraction_k<RowMajor>());\n\n  CALL_SUBTEST_6(test_gpu_contraction_n<ColMajor>());\n  CALL_SUBTEST_7(test_gpu_contraction_n<RowMajor>());\n\n#if !defined(EIGEN_USE_HIP)\n// disable these subtests for HIP\n  CALL_SUBTEST_8(test_gpu_contraction_sizes<ColMajor>());\n  CALL_SUBTEST_9(test_gpu_contraction_sizes<RowMajor>());\n#endif\t\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_contract_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include <algorithm>\n#include <chrono>\n#include <ctime>\n#include <iostream>\n\n#include \"main.h\"\n\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid static test_sycl_contraction(const Device &sycl_device, IndexType m_size,\n                                  IndexType k_size, IndexType n_size) {\n  typedef typename Tensor<DataType, 1, DataLayout, IndexType>::DimensionPair\n      DimPair;\n  static const DataType error_threshold = DataType(1e-4);\n  // with these dimensions, the output has 300 * 140 elements, which is\n  // more than 30 * 1024, which is the number of threads in blocks on\n  // a 15 SM GK110 GPU\n  Tensor<DataType, 2, DataLayout, IndexType> t_left(m_size, k_size);\n  Tensor<DataType, 2, DataLayout, IndexType> t_right(k_size, n_size);\n  Tensor<DataType, 2, DataLayout, IndexType> t_result(m_size, n_size);\n  Tensor<DataType, 2, DataLayout, IndexType> t_result_gpu(m_size, n_size);\n  Eigen::array<DimPair, 1> dims = {{DimPair(1, 0)}};\n  Eigen::array<IndexType, 2> left_dims = {{m_size, k_size}};\n  Eigen::array<IndexType, 2> right_dims = {{k_size, n_size}};\n  Eigen::array<IndexType, 2> result_dims = {{m_size, n_size}};\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  std::size_t t_left_bytes = t_left.size() * sizeof(DataType);\n  std::size_t t_right_bytes = t_right.size() * sizeof(DataType);\n  std::size_t t_result_bytes = t_result.size() * sizeof(DataType);\n\n  DataType *d_t_left =\n      static_cast<DataType *>(sycl_device.allocate(t_left_bytes));\n  DataType *d_t_right =\n      static_cast<DataType *>(sycl_device.allocate(t_right_bytes));\n  DataType *d_t_result =\n      static_cast<DataType *>(sycl_device.allocate(t_result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_left(d_t_left, left_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_right(d_t_right, right_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_result(d_t_result, result_dims);\n\n  sycl_device.memcpyHostToDevice(d_t_left, t_left.data(), t_left_bytes);\n  sycl_device.memcpyHostToDevice(d_t_right, t_right.data(), t_right_bytes);\n\n  gpu_t_result.device(sycl_device) = gpu_t_left.contract(gpu_t_right, dims);\n  sycl_device.memcpyDeviceToHost(t_result_gpu.data(), d_t_result,\n                                 t_result_bytes);\n\n  t_result = t_left.contract(t_right, dims);\n\n  for (IndexType i = 0; i < t_result.size(); i++) {\n    if (static_cast<DataType>(std::fabs(static_cast<DataType>(\n            t_result(i) - t_result_gpu(i)))) < error_threshold) {\n      continue;\n    }\n    if (Eigen::internal::isApprox(t_result(i), t_result_gpu(i),\n                                  error_threshold)) {\n      continue;\n    }\n\n    std::cout << \"M : \" << m_size << \", N : \" << n_size << \", K : \" << k_size\n              << \", mismatch detected at IndexType \" << i << \": \" << t_result(i)\n              << \" vs \" << t_result_gpu(i) << std::endl;\n    VERIFY_IS_APPROX(t_result_gpu(i), t_result(i));\n  }\n  sycl_device.deallocate(d_t_left);\n  sycl_device.deallocate(d_t_right);\n  sycl_device.deallocate(d_t_result);\n}\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid test_sycl_contraction_m(const Device &sycl_device) {\n  for (IndexType k = 32; k < 256; k++) {\n    test_sycl_contraction<DataLayout, DataType, IndexType>(sycl_device, k, 128,\n                                                           128);\n  }\n}\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid test_sycl_contraction_k(const Device &sycl_device) {\n  for (IndexType k = 32; k < 256; k++) {\n    test_sycl_contraction<DataLayout, DataType, IndexType>(sycl_device, 128, k,\n                                                           128);\n  }\n}\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid test_sycl_contraction_n(const Device &sycl_device) {\n  for (IndexType k = 32; k < 256; k++) {\n    test_sycl_contraction<DataLayout, DataType, IndexType>(sycl_device, 128,\n                                                           128, k);\n  }\n}\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid test_sycl_contraction_sizes(const Device &sycl_device) {\n  IndexType m_sizes[] = {31,  39,  63,  64,  65,   127,  129, 255,\n                         257, 511, 512, 513, 1023, 1024, 1025};\n\n  IndexType n_sizes[] = {31,  39,  63,  64,  65,   127,  129, 255,\n                         257, 511, 512, 513, 1023, 1024, 1025};\n\n  IndexType k_sizes[] = {31,  39,  63,  64,  65,  95,   96,   127, 129,\n                         255, 257, 511, 512, 513, 1023, 1024, 1025};\n\n  for (IndexType i = 0; i < 15; i++) {\n    for (IndexType j = 0; j < 15; j++) {\n      for (IndexType k = 0; k < 17; k++) {\n        test_sycl_contraction<DataLayout, DataType, IndexType>(\n            sycl_device, m_sizes[i], n_sizes[j], k_sizes[k]);\n      }\n    }\n  }\n}\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid static test_no_out_of_bounds(const Device &sycl_device, IndexType m_size,\n                                  IndexType k_size, IndexType n_size) {\n  typedef typename Tensor<DataType, 1, DataLayout, IndexType>::DimensionPair\n      DimPair;\n  static const DataType error_threshold = DataType(1e-4);\n  Tensor<DataType, 2, DataLayout, IndexType> t_left(m_size, k_size);\n  Tensor<DataType, 2, DataLayout, IndexType> t_right(k_size, n_size);\n  Tensor<DataType, 2, DataLayout, IndexType> t_result(m_size, n_size);\n\n  Eigen::array<DimPair, 1> dims = {{DimPair(1, 0)}};\n  Eigen::array<IndexType, 2> left_dims = {{m_size, k_size}};\n  Eigen::array<IndexType, 2> right_dims = {{k_size, n_size}};\n  Eigen::array<IndexType, 2> result_dims = {{m_size, n_size}};\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  // Allocate buffers twice as big to check for invalid read and write\n  auto padded_left_size = 2 * t_left.size();\n  auto padded_right_size = 2 * t_right.size();\n  auto padded_result_size = 2 * t_result.size();\n\n  std::size_t t_left_bytes = padded_left_size * sizeof(DataType);\n  std::size_t t_right_bytes = padded_right_size * sizeof(DataType);\n  std::size_t t_result_bytes = padded_result_size * sizeof(DataType);\n\n  DataType *d_t_left =\n      static_cast<DataType *>(sycl_device.allocate(t_left_bytes));\n  DataType *d_t_right =\n      static_cast<DataType *>(sycl_device.allocate(t_right_bytes));\n  DataType *d_t_result =\n      static_cast<DataType *>(sycl_device.allocate(t_result_bytes));\n\n  // TensorMaps are still of the same size than the Tensors\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_left(d_t_left, left_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_right(d_t_right, right_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_result(d_t_result, result_dims);\n\n  // Write nan after the actual buffer to propagate nans everywhere in case of\n  // invalid reads\n  DataType nan = std::numeric_limits<DataType>::quiet_NaN();\n  auto host_left_data = new DataType[padded_left_size];\n  std::copy_n(t_left.data(), t_left.size(), host_left_data);\n  std::fill_n(host_left_data + t_left.size(), t_left.size(), nan);\n  auto host_right_data = new DataType[padded_right_size];\n  std::copy_n(t_right.data(), t_right.size(), host_right_data);\n  std::fill_n(host_right_data + t_right.size(), t_right.size(), nan);\n  auto host_result_data = new DataType[padded_result_size];\n  std::fill_n(host_result_data, padded_result_size, nan);\n\n  sycl_device.memcpyHostToDevice(d_t_left, host_left_data, t_left_bytes);\n  sycl_device.memcpyHostToDevice(d_t_right, host_right_data, t_right_bytes);\n  sycl_device.memcpyHostToDevice(d_t_result, host_result_data, t_result_bytes);\n\n  gpu_t_result.device(sycl_device) = gpu_t_left.contract(gpu_t_right, dims);\n  sycl_device.memcpyDeviceToHost(host_result_data, d_t_result, t_result_bytes);\n\n  t_result = t_left.contract(t_right, dims);\n\n  for (IndexType i = 0; i < t_result.size(); i++) {\n    if (static_cast<DataType>(std::fabs(static_cast<DataType>(\n            t_result(i) - host_result_data[i]))) < error_threshold) {\n      continue;\n    }\n    if (Eigen::internal::isApprox(t_result(i), host_result_data[i],\n                                  error_threshold)) {\n      continue;\n    }\n    if (std::isnan(host_result_data[i])) {\n      std::cout << \"M : \" << m_size << \", N : \" << n_size << \", K : \" << k_size\n                << \", invalid read detected at IndexType \" << i << \": \"\n                << t_result(i) << \" vs \" << host_result_data[i] << std::endl;\n    } else {\n      std::cout << \"M : \" << m_size << \", N : \" << n_size << \", K : \" << k_size\n                << \", mismatch detected at IndexType \" << i << \": \"\n                << t_result(i) << \" vs \" << host_result_data[i] << std::endl;\n    }\n    VERIFY_IS_APPROX(host_result_data[i], t_result(i));\n  }\n  // Make sure that the rest of the result is still nans\n  for (IndexType i = t_result.size(); i < padded_result_size; i++) {\n    if (std::isnan(host_result_data[i])) {\n      continue;\n    }\n    std::cout << \"M : \" << m_size << \", N : \" << n_size << \", K : \" << k_size\n              << \", invalid write detected at IndexType \" << i << \": \"\n              << host_result_data[i] << std::endl;\n    VERIFY_IS_APPROX(host_result_data[i], t_result(i));\n  }\n  sycl_device.deallocate(d_t_left);\n  sycl_device.deallocate(d_t_right);\n  sycl_device.deallocate(d_t_result);\n\n  delete[] host_left_data;\n  delete[] host_right_data;\n  delete[] host_result_data;\n}\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid test_scalar(const Device &sycl_device, IndexType m_size, IndexType k_size,\n                 IndexType n_size) {\n  // std::cout << \"Testing for (\" << m_size << \",\" << k_size << \",\" << n_size <<\n  // \")\" << std::endl;\n  // with these dimensions, the output has 300 * 140 elements, which is\n  // more than 30 * 1024, which is the number of threads in blocks on\n  // a 15 SM GK110 GPU\n  typedef typename Tensor<DataType, 1, DataLayout, IndexType>::DimensionPair\n      DimPair;\n  static const DataType error_threshold = DataType(1e-4);\n  Tensor<DataType, 2, DataLayout, IndexType> t_left(m_size, k_size);\n  Tensor<DataType, 2, DataLayout, IndexType> t_right(k_size, n_size);\n  Tensor<DataType, 0, DataLayout, IndexType> t_result;\n  Tensor<DataType, 0, DataLayout, IndexType> t_result_gpu;\n  Eigen::array<DimPair, 2> dims = {{DimPair(0, 0), DimPair(1, 1)}};\n  Eigen::array<IndexType, 2> left_dims = {{m_size, k_size}};\n  Eigen::array<IndexType, 2> right_dims = {{k_size, n_size}};\n  t_left.setRandom();\n  t_right.setRandom();\n\n  std::size_t t_left_bytes = t_left.size() * sizeof(DataType);\n  std::size_t t_right_bytes = t_right.size() * sizeof(DataType);\n  std::size_t t_result_bytes = sizeof(DataType);\n\n  DataType *d_t_left =\n      static_cast<DataType *>(sycl_device.allocate(t_left_bytes));\n  DataType *d_t_right =\n      static_cast<DataType *>(sycl_device.allocate(t_right_bytes));\n  DataType *d_t_result =\n      static_cast<DataType *>(sycl_device.allocate(t_result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_left(d_t_left, left_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_right(d_t_right, right_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 0, DataLayout, IndexType>>\n      gpu_t_result(d_t_result);\n\n  sycl_device.memcpyHostToDevice(d_t_left, t_left.data(), t_left_bytes);\n  sycl_device.memcpyHostToDevice(d_t_right, t_right.data(), t_right_bytes);\n\n  gpu_t_result.device(sycl_device) = gpu_t_left.contract(gpu_t_right, dims);\n  sycl_device.memcpyDeviceToHost(t_result_gpu.data(), d_t_result,\n                                 t_result_bytes);\n\n  t_result = t_left.contract(t_right, dims);\n\n  if (static_cast<DataType>(std::fabs(static_cast<DataType>(\n          t_result() - t_result_gpu()))) > error_threshold &&\n      !Eigen::internal::isApprox(t_result(), t_result_gpu(), error_threshold)) {\n    std::cout << \"K: \" << k_size << \", N: \" << n_size << \", M: \" << m_size\n              << \" : mismatch detected: \" << t_result() << \" vs \"\n              << t_result_gpu() << std::endl;\n    VERIFY_IS_APPROX(t_result_gpu(), t_result());\n  }\n\n  sycl_device.deallocate(d_t_left);\n  sycl_device.deallocate(d_t_right);\n  sycl_device.deallocate(d_t_result);\n}\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid contraction_batch(const Device &sycl_device, IndexType m_size,\n                       IndexType k_size, IndexType n_size, IndexType m_batch,\n                       IndexType start, IndexType limit) {\n  typedef typename Tensor<DataType, 1, DataLayout, IndexType>::DimensionPair\n      DimPair;\n  static const DataType error_threshold = DataType(1e-4);\n  typedef Eigen::array<IndexType, 3> TensorDim;\n  typedef Eigen::Tensor<DataType, 3, DataLayout, IndexType> TensorType;\n  TensorDim left_dims = {{m_batch, k_size, m_size}};\n  TensorDim right_dims = {{m_batch, n_size, k_size}};\n  TensorDim res_dims = {{m_batch, m_size, n_size}};\n  Eigen::array<DimPair, 1> contract_pairs = {{DimPair(0, 1)}};\n\n  TensorType t_left(left_dims);\n  TensorType t_right(right_dims);\n  TensorType t_result_gpu(res_dims);\n  TensorType t_result(res_dims);\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  std::size_t t_left_bytes = t_left.size() * sizeof(DataType);\n  std::size_t t_right_bytes = t_right.size() * sizeof(DataType);\n  std::size_t t_result_bytes = t_result.size() * sizeof(DataType);\n\n  DataType *d_t_left =\n      static_cast<DataType *>(sycl_device.allocate(t_left_bytes));\n  DataType *d_t_right =\n      static_cast<DataType *>(sycl_device.allocate(t_right_bytes));\n  DataType *d_t_result =\n      static_cast<DataType *>(sycl_device.allocate(t_result_bytes));\n\n  Eigen::TensorMap<TensorType> gpu_t_left(d_t_left, left_dims);\n  Eigen::TensorMap<TensorType> gpu_t_right(d_t_right, right_dims);\n  Eigen::TensorMap<TensorType> gpu_t_result(d_t_result, res_dims);\n\n  sycl_device.memcpyHostToDevice(d_t_left, t_left.data(), t_left_bytes);\n  sycl_device.memcpyHostToDevice(d_t_right, t_right.data(), t_right_bytes);\n  for (int i = start; i < limit; ++i) {\n    auto x = gpu_t_left.template chip<0>(i);\n    auto y = gpu_t_right.template chip<0>(i);\n    auto z = gpu_t_result.template chip<0>(i);\n    z.device(sycl_device) = x.contract(y, contract_pairs);\n  }\n  sycl_device.memcpyDeviceToHost(t_result_gpu.data(), d_t_result,\n                                 t_result_bytes);\n\n  for (int i = start; i < limit; ++i) {\n    auto x = t_left.template chip<0>(i);\n    auto y = t_right.template chip<0>(i);\n    auto z = t_result.template chip<0>(i);\n    z = x.contract(y, contract_pairs);\n  }\n\n  for (IndexType i = 0; i < t_result.size(); i++) {\n    if (static_cast<DataType>(std::fabs(static_cast<DataType>(\n            t_result(i) - t_result_gpu(i)))) < error_threshold) {\n      continue;\n    }\n    if (Eigen::internal::isApprox(t_result(i), t_result_gpu(i),\n                                  error_threshold)) {\n      continue;\n    }\n    std::cout << \"mismatch detected at IndexType \" << i << \": \" << t_result(i)\n              << \" vs \" << t_result_gpu(i) << std::endl;\n    VERIFY_IS_APPROX(t_result_gpu(i), t_result(i));\n  }\n  sycl_device.deallocate(d_t_left);\n  sycl_device.deallocate(d_t_right);\n  sycl_device.deallocate(d_t_result);\n}\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid contraction_rhs_transposed(const Device &sycl_device, IndexType m_size,\n                                IndexType k_size, IndexType n_size) {\n  typedef typename Tensor<DataType, 1, DataLayout, IndexType>::DimensionPair\n      DimPair;\n  static const DataType error_threshold = DataType(1e-4);\n  Eigen::array<IndexType, 2> left_dims = {{m_size, k_size}};\n  Eigen::array<IndexType, 2> right_dims = {{n_size, k_size}};\n  Eigen::array<IndexType, 2> res_dims = {{m_size, n_size}};\n  Eigen::array<DimPair, 1> dims = {{DimPair(1, 1)}};\n\n  Tensor<DataType, 2, DataLayout, IndexType> t_left(left_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> t_right(right_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> t_result_gpu(res_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> t_result(res_dims);\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  std::size_t t_left_bytes = t_left.size() * sizeof(DataType);\n  std::size_t t_right_bytes = t_right.size() * sizeof(DataType);\n  std::size_t t_result_bytes = t_result.size() * sizeof(DataType);\n\n  DataType *d_t_left =\n      static_cast<DataType *>(sycl_device.allocate(t_left_bytes));\n  DataType *d_t_right =\n      static_cast<DataType *>(sycl_device.allocate(t_right_bytes));\n  DataType *d_t_result =\n      static_cast<DataType *>(sycl_device.allocate(t_result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_left(d_t_left, left_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_right(d_t_right, right_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_result(d_t_result, res_dims);\n\n  sycl_device.memcpyHostToDevice(d_t_left, t_left.data(), t_left_bytes);\n  sycl_device.memcpyHostToDevice(d_t_right, t_right.data(), t_right_bytes);\n\n  gpu_t_result.device(sycl_device) = gpu_t_left.contract(gpu_t_right, dims);\n  sycl_device.memcpyDeviceToHost(t_result_gpu.data(), d_t_result,\n                                 t_result_bytes);\n\n  t_result = t_left.contract(t_right, dims);\n\n  for (IndexType j = 0; j < m_size; j++) {\n    for (IndexType i = 0; i < n_size; i++) {\n      if (static_cast<DataType>(std::fabs(static_cast<DataType>(\n              t_result(j, i) - t_result_gpu(j, i)))) < error_threshold) {\n        continue;\n      }\n      if (Eigen::internal::isApprox(t_result(j, i), t_result_gpu(j, i),\n                                    error_threshold)) {\n        continue;\n      }\n      std::cout << \"M : \" << m_size << \", N : \" << n_size << \", K : \" << k_size\n                << \", mismatch detected at IndexType m: \" << j << \" n: \" << i\n                << \" CPU : \" << t_result(j, i)\n                << \" vs SYCL:\" << t_result_gpu(j, i) << std::endl;\n      VERIFY_IS_APPROX(t_result_gpu(j, i), t_result(j, i));\n    }\n  }\n  sycl_device.deallocate(d_t_left);\n  sycl_device.deallocate(d_t_right);\n  sycl_device.deallocate(d_t_result);\n}\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid contraction_lhs_transposed(const Device &sycl_device, IndexType m_size,\n                                IndexType k_size, IndexType n_size) {\n  typedef typename Tensor<DataType, 1, DataLayout, IndexType>::DimensionPair\n      DimPair;\n  static const DataType error_threshold = DataType(1e-4);\n  Eigen::array<IndexType, 2> left_dims = {{k_size, m_size}};\n  Eigen::array<IndexType, 2> right_dims = {{k_size, n_size}};\n  Eigen::array<IndexType, 2> res_dims = {{m_size, n_size}};\n  Eigen::array<DimPair, 1> dims = {{DimPair(0, 0)}};\n\n  Tensor<DataType, 2, DataLayout, IndexType> t_left(left_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> t_right(right_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> t_result_gpu(res_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> t_result(res_dims);\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  std::size_t t_left_bytes = t_left.size() * sizeof(DataType);\n  std::size_t t_right_bytes = t_right.size() * sizeof(DataType);\n  std::size_t t_result_bytes = t_result.size() * sizeof(DataType);\n\n  DataType *d_t_left =\n      static_cast<DataType *>(sycl_device.allocate(t_left_bytes));\n  DataType *d_t_right =\n      static_cast<DataType *>(sycl_device.allocate(t_right_bytes));\n  DataType *d_t_result =\n      static_cast<DataType *>(sycl_device.allocate(t_result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_left(d_t_left, left_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_right(d_t_right, right_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_result(d_t_result, res_dims);\n\n  sycl_device.memcpyHostToDevice(d_t_left, t_left.data(), t_left_bytes);\n  sycl_device.memcpyHostToDevice(d_t_right, t_right.data(), t_right_bytes);\n\n  gpu_t_result.device(sycl_device) = gpu_t_left.contract(gpu_t_right, dims);\n  sycl_device.memcpyDeviceToHost(t_result_gpu.data(), d_t_result,\n                                 t_result_bytes);\n\n  t_result = t_left.contract(t_right, dims);\n\n  for (IndexType i = 0; i < t_result.size(); i++) {\n    if (static_cast<DataType>(std::fabs(static_cast<DataType>(\n            t_result(i) - t_result_gpu(i)))) < error_threshold) {\n      continue;\n    }\n    if (Eigen::internal::isApprox(t_result(i), t_result_gpu(i),\n                                  error_threshold)) {\n      continue;\n    }\n    std::cout << \"M : \" << m_size << \", N : \" << n_size << \", K : \" << k_size\n              << \", mismatch detected at IndexType \" << i << \": \" << t_result(i)\n              << \" vs \" << t_result_gpu(i) << std::endl;\n    VERIFY_IS_APPROX(t_result_gpu(i), t_result(i));\n  }\n  sycl_device.deallocate(d_t_left);\n  sycl_device.deallocate(d_t_right);\n  sycl_device.deallocate(d_t_result);\n}\n\ntemplate <int DataLayout, typename DataType, typename IndexType,\n          typename Device>\nvoid contraction_both_transposed(const Device &sycl_device, IndexType m_size,\n                                 IndexType k_size, IndexType n_size) {\n  typedef typename Tensor<DataType, 1, DataLayout, IndexType>::DimensionPair\n      DimPair;\n  static const DataType error_threshold = DataType(1e-4);\n  Eigen::array<IndexType, 2> left_dims = {{k_size, m_size}};\n  Eigen::array<IndexType, 2> right_dims = {{n_size, k_size}};\n  Eigen::array<IndexType, 2> res_dims = {{m_size, n_size}};\n  Eigen::array<DimPair, 1> dims = {{DimPair(0, 1)}};\n\n  Tensor<DataType, 2, DataLayout, IndexType> t_left(left_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> t_right(right_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> t_result_gpu(res_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> t_result(res_dims);\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  std::size_t t_left_bytes = t_left.size() * sizeof(DataType);\n  std::size_t t_right_bytes = t_right.size() * sizeof(DataType);\n  std::size_t t_result_bytes = t_result.size() * sizeof(DataType);\n\n  DataType *d_t_left =\n      static_cast<DataType *>(sycl_device.allocate(t_left_bytes));\n  DataType *d_t_right =\n      static_cast<DataType *>(sycl_device.allocate(t_right_bytes));\n  DataType *d_t_result =\n      static_cast<DataType *>(sycl_device.allocate(t_result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_left(d_t_left, left_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_right(d_t_right, right_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType>>\n      gpu_t_result(d_t_result, res_dims);\n\n  sycl_device.memcpyHostToDevice(d_t_left, t_left.data(), t_left_bytes);\n  sycl_device.memcpyHostToDevice(d_t_right, t_right.data(), t_right_bytes);\n\n  gpu_t_result.device(sycl_device) = gpu_t_left.contract(gpu_t_right, dims);\n  sycl_device.memcpyDeviceToHost(t_result_gpu.data(), d_t_result,\n                                 t_result_bytes);\n\n  t_result = t_left.contract(t_right, dims);\n\n  for (IndexType i = 0; i < t_result.size(); i++) {\n    if (static_cast<DataType>(std::fabs(static_cast<DataType>(\n            t_result(i) - t_result_gpu(i)))) < error_threshold) {\n      continue;\n    }\n    if (Eigen::internal::isApprox(t_result(i), t_result_gpu(i),\n                                  error_threshold)) {\n      continue;\n    }\n    std::cout << \"M : \" << m_size << \", N : \" << n_size << \", K : \" << k_size\n              << \", mismatch detected at IndexType \" << i << \": \" << t_result(i)\n              << \" vs \" << t_result_gpu(i) << std::endl;\n\n    VERIFY_IS_APPROX(t_result_gpu(i), t_result(i));\n  }\n  sycl_device.deallocate(d_t_left);\n  sycl_device.deallocate(d_t_right);\n  sycl_device.deallocate(d_t_result);\n}\n\ntemplate <typename Dev>\nvoid inline tensorOutofBound(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // Test out of bound for Tensor-Tensor\n  test_no_out_of_bounds<RowMajor, DataType, IndexType>(sycl_device, 10, 1024,\n                                                       1024);\n  test_no_out_of_bounds<RowMajor, DataType, IndexType>(sycl_device, 1024, 1024,\n                                                       4096);\n  test_no_out_of_bounds<RowMajor, DataType, IndexType>(sycl_device, 4096, 1024,\n                                                       2048);\n  test_no_out_of_bounds<ColMajor, DataType, IndexType>(sycl_device, 784, 2048,\n                                                       1024);\n  test_no_out_of_bounds<ColMajor, DataType, IndexType>(sycl_device, 2048, 1024,\n                                                       784);\n  test_no_out_of_bounds<RowMajor, DataType, IndexType>(sycl_device, 10, 1024,\n                                                       10);\n  test_no_out_of_bounds<RowMajor, DataType, IndexType>(sycl_device, 513, 4096,\n                                                       513);\n  test_no_out_of_bounds<RowMajor, DataType, IndexType>(sycl_device, 783, 1024,\n                                                       783);\n  test_no_out_of_bounds<ColMajor, DataType, IndexType>(sycl_device, 784, 2048,\n                                                       784);\n  test_no_out_of_bounds<ColMajor, DataType, IndexType>(sycl_device, 11, 1024,\n                                                       11);\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"tensor out of bound tests finished computation at \"\n            << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensorTensor(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // Tensor Tensor Contraction\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 128, 128,\n                                                       128);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 128, 128,\n                                                       128);\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"tensor tensor tests finished computation at \"\n            << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensorTensor_m(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // Tensor Tensor Contraction\n  test_sycl_contraction_m<ColMajor, DataType, IndexType>(sycl_device);\n  test_sycl_contraction_m<RowMajor, DataType, IndexType>(sycl_device);\n\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"tensor tensor tests finished computation at \"\n            << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensorTensor_n(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // Tensor Tensor Contraction\n  test_sycl_contraction_n<ColMajor, DataType, IndexType>(sycl_device);\n  test_sycl_contraction_n<RowMajor, DataType, IndexType>(sycl_device);\n\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"tensor tensor tests finished computation at \"\n            << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensorTensor_k(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  test_sycl_contraction_k<ColMajor, DataType, IndexType>(sycl_device);\n  test_sycl_contraction_k<RowMajor, DataType, IndexType>(sycl_device);\n\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"tensor tensor tests finished computation at \"\n            << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensorTensor_sizes(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // Tensor Tensor Contraction\n  test_sycl_contraction_sizes<ColMajor, DataType, IndexType>(sycl_device);\n  test_sycl_contraction_sizes<RowMajor, DataType, IndexType>(sycl_device);\n\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"tensor tensor tests finished computation at \"\n            << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\ntemplate <typename Dev>\nvoid inline vectorVector(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // VECTOR-VECTOR\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1025, 1,\n                                                       1025);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1025, 1,\n                                                       1025);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1024, 1,\n                                                       1024);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1024, 1,\n                                                       1024);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1023, 1,\n                                                       1023);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1023, 1,\n                                                       1023);\n\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"contracted tensor tests finished computation at \"\n            << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline vectorTensor(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // Vector-Tensor\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1, 1025,\n                                                       1025);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1, 1025,\n                                                       1025);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1, 1024,\n                                                       1024);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1, 1024,\n                                                       1024);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1, 1023,\n                                                       1023);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1, 1023,\n                                                       1023);\n\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1, 4097,\n                                                       4097);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1, 4097,\n                                                       4097);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1, 4096,\n                                                       4096);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1, 4096,\n                                                       4096);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1, 4095,\n                                                       4095);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1, 4095,\n                                                       4095);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1, 802816,\n                                                       32);\n\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"finished computation at \" << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensorVector(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // Matrix-Vector\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1025, 1025,\n                                                       1);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1125, 1025,\n                                                       1);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1224, 1024,\n                                                       1);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1024, 1024,\n                                                       1);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 1023, 1023,\n                                                       1);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 1023, 1023,\n                                                       1);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 4097, 4197,\n                                                       1);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 4097, 4097,\n                                                       1);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 4096, 4096,\n                                                       1);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 4096, 8196,\n                                                       1);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 4095, 4095,\n                                                       1);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 4095, 4095,\n                                                       1);\n// If the GEMV disabled it will creates one kernel to calculate the contraction.\n// Therefore the acumuation of float number will overflow the precision\n// threshold for float and cause the test to fail. While it the GMV multiple\n// kernel will be created and each one run the overflow of accumutation breaks\n// among the kernels.\n#ifndef EIGEN_SYCL_DISABLE_GEMV\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 32, 802032,\n                                                       1);\n#endif\n\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"finished computation at \" << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensorScalar(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // SCALAR Contraction\n  test_scalar<ColMajor, DataType, IndexType>(sycl_device, 127, 127, 127);\n  test_scalar<RowMajor, DataType, IndexType>(sycl_device, 127, 127, 127);\n  test_scalar<ColMajor, DataType, IndexType>(sycl_device, 128, 128, 128);\n  test_scalar<RowMajor, DataType, IndexType>(sycl_device, 128, 128, 128);\n  test_scalar<ColMajor, DataType, IndexType>(sycl_device, 129, 129, 129);\n  test_scalar<RowMajor, DataType, IndexType>(sycl_device, 129, 129, 129);\n\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"finished computation at \" << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline skinnyTensor_row(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // Tensor Tensor Contraction\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 16, 4, 16);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 257, 131073,\n                                                       257);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 256, 131072,\n                                                       256);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 16, 131073,\n                                                       16);\n  test_sycl_contraction<RowMajor, DataType, IndexType>(sycl_device, 17, 131072,\n                                                       17);\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"finished computation at \" << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline skinnyTensor_col(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n  // Tensor Tensor Contraction\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 16, 4, 16);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 257, 131073,\n                                                       257);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 256, 131072,\n                                                       256);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 16, 131073,\n                                                       16);\n  test_sycl_contraction<ColMajor, DataType, IndexType>(sycl_device, 17, 131072,\n                                                       17);\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"finished computation at \" << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensor_contraction_batch_per_device(const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n\n  contraction_batch<RowMajor, DataType, IndexType>(sycl_device, 64, 75, 30, 4,\n                                                   0, 4);\n  contraction_batch<ColMajor, DataType, IndexType>(sycl_device, 64, 75, 30, 4,\n                                                   0, 4);\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"finished computation at \" << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensor_contraction_lhs_transposed_per_device(\n    const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n\n  contraction_lhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 8, 4,\n                                                            8);\n  contraction_lhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 32, 8,\n                                                            32);\n  contraction_lhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 64, 16,\n                                                            64);\n  contraction_lhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 784,\n                                                            2048, 1024);\n  contraction_lhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 1024,\n                                                            10, 1024);\n  contraction_lhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 4096,\n                                                            1024, 1024);\n  contraction_lhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 2048,\n                                                            4096, 1024);\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"finished computation at \" << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensor_contraction_rhs_transposed_per_device(\n    const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n\n  contraction_rhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 16, 4,\n                                                            16);\n  contraction_rhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 17, 5,\n                                                            17);\n  contraction_rhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 32, 8,\n                                                            32);\n  contraction_rhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 64, 16,\n                                                            64);\n  contraction_rhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 10,\n                                                            1024, 1024);\n  contraction_rhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 1024,\n                                                            1024, 4096);\n  contraction_rhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 4096,\n                                                            1024, 2048);\n  contraction_rhs_transposed<RowMajor, DataType, IndexType>(sycl_device, 2048,\n                                                            1024, 784);\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"finished computation at \" << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\ntemplate <typename Dev>\nvoid inline tensor_contraction_both_transposed_per_device(\n    const Dev &sycl_device) {\n  typedef float DataType;\n  typedef int64_t IndexType;\n  std::chrono::time_point<std::chrono::system_clock> start, end;\n  start = std::chrono::system_clock::now();\n\n  contraction_both_transposed<RowMajor, DataType, IndexType>(sycl_device, 17, 5,\n                                                             17);\n  contraction_both_transposed<RowMajor, DataType, IndexType>(sycl_device, 32, 8,\n                                                             32);\n  contraction_both_transposed<RowMajor, DataType, IndexType>(sycl_device, 64,\n                                                             16, 64);\n  end = std::chrono::system_clock::now();\n  std::chrono::duration<double> elapsed_seconds = end - start;\n  std::time_t end_time = std::chrono::system_clock::to_time_t(end);\n  std::cout << \"finished computation at \" << std::ctime(&end_time)\n            << \"elapsed time: \" << elapsed_seconds.count() << \"s\\n\";\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_contract_sycl) {\n  for (const auto &device : Eigen::get_sycl_supported_devices()) {\n    std::cout << \"Running on \"\n              << device.template get_info<cl::sycl::info::device::name>()\n              << std::endl;\n    QueueInterface queueInterface(device);\n    auto sycl_device = Eigen::SyclDevice(&queueInterface);\n    CALL_SUBTEST_1(tensorOutofBound(sycl_device));\n    CALL_SUBTEST_2(tensorTensor(sycl_device));\n    CALL_SUBTEST_2(tensorTensor_m(sycl_device));\n    CALL_SUBTEST_2(tensorTensor_n(sycl_device));\n    CALL_SUBTEST_2(tensorTensor_k(sycl_device));\n    CALL_SUBTEST_2(tensorTensor_sizes(sycl_device));\n    CALL_SUBTEST_3(vectorVector(sycl_device));\n    CALL_SUBTEST_4(vectorTensor(sycl_device));\n    CALL_SUBTEST_5(tensorVector(sycl_device));\n    CALL_SUBTEST_6(tensorScalar(sycl_device));\n    CALL_SUBTEST_7(skinnyTensor_row(sycl_device));\n    CALL_SUBTEST_7(skinnyTensor_col(sycl_device));\n    CALL_SUBTEST_8(tensor_contraction_batch_per_device(sycl_device));\n    CALL_SUBTEST_9(tensor_contraction_lhs_transposed_per_device(sycl_device));\n    CALL_SUBTEST_10(tensor_contraction_rhs_transposed_per_device(sycl_device));\n    CALL_SUBTEST_11(tensor_contraction_both_transposed_per_device(sycl_device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_contraction.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::DefaultDevice;\nusing Eigen::Tensor;\n\ntypedef Tensor<float, 1>::DimensionPair DimPair;\n\ntemplate<int DataLayout>\nstatic void test_evals()\n{\n  Tensor<float, 2, DataLayout> mat1(2, 3);\n  Tensor<float, 2, DataLayout> mat2(2, 3);\n  Tensor<float, 2, DataLayout> mat3(3, 2);\n\n  mat1.setRandom();\n  mat2.setRandom();\n  mat3.setRandom();\n\n  Tensor<float, 2, DataLayout> mat4(3,3);\n  mat4.setZero();\n  Eigen::array<DimPair, 1> dims3 = {{DimPair(0, 0)}};\n  typedef TensorEvaluator<decltype(mat1.contract(mat2, dims3)), DefaultDevice> Evaluator;\n  Evaluator eval(mat1.contract(mat2, dims3), DefaultDevice());\n  eval.evalTo(mat4.data());\n  EIGEN_STATIC_ASSERT(Evaluator::NumDims==2ul, YOU_MADE_A_PROGRAMMING_MISTAKE);\n  VERIFY_IS_EQUAL(eval.dimensions()[0], 3);\n  VERIFY_IS_EQUAL(eval.dimensions()[1], 3);\n\n  VERIFY_IS_APPROX(mat4(0,0), mat1(0,0)*mat2(0,0) + mat1(1,0)*mat2(1,0));\n  VERIFY_IS_APPROX(mat4(0,1), mat1(0,0)*mat2(0,1) + mat1(1,0)*mat2(1,1));\n  VERIFY_IS_APPROX(mat4(0,2), mat1(0,0)*mat2(0,2) + mat1(1,0)*mat2(1,2));\n  VERIFY_IS_APPROX(mat4(1,0), mat1(0,1)*mat2(0,0) + mat1(1,1)*mat2(1,0));\n  VERIFY_IS_APPROX(mat4(1,1), mat1(0,1)*mat2(0,1) + mat1(1,1)*mat2(1,1));\n  VERIFY_IS_APPROX(mat4(1,2), mat1(0,1)*mat2(0,2) + mat1(1,1)*mat2(1,2));\n  VERIFY_IS_APPROX(mat4(2,0), mat1(0,2)*mat2(0,0) + mat1(1,2)*mat2(1,0));\n  VERIFY_IS_APPROX(mat4(2,1), mat1(0,2)*mat2(0,1) + mat1(1,2)*mat2(1,1));\n  VERIFY_IS_APPROX(mat4(2,2), mat1(0,2)*mat2(0,2) + mat1(1,2)*mat2(1,2));\n\n  Tensor<float, 2, DataLayout> mat5(2,2);\n  mat5.setZero();\n  Eigen::array<DimPair, 1> dims4 = {{DimPair(1, 1)}};\n  typedef TensorEvaluator<decltype(mat1.contract(mat2, dims4)), DefaultDevice> Evaluator2;\n  Evaluator2 eval2(mat1.contract(mat2, dims4), DefaultDevice());\n  eval2.evalTo(mat5.data());\n  EIGEN_STATIC_ASSERT(Evaluator2::NumDims==2ul, YOU_MADE_A_PROGRAMMING_MISTAKE);\n  VERIFY_IS_EQUAL(eval2.dimensions()[0], 2);\n  VERIFY_IS_EQUAL(eval2.dimensions()[1], 2);\n\n  VERIFY_IS_APPROX(mat5(0,0), mat1(0,0)*mat2(0,0) + mat1(0,1)*mat2(0,1) + mat1(0,2)*mat2(0,2));\n  VERIFY_IS_APPROX(mat5(0,1), mat1(0,0)*mat2(1,0) + mat1(0,1)*mat2(1,1) + mat1(0,2)*mat2(1,2));\n  VERIFY_IS_APPROX(mat5(1,0), mat1(1,0)*mat2(0,0) + mat1(1,1)*mat2(0,1) + mat1(1,2)*mat2(0,2));\n  VERIFY_IS_APPROX(mat5(1,1), mat1(1,0)*mat2(1,0) + mat1(1,1)*mat2(1,1) + mat1(1,2)*mat2(1,2));\n\n  Tensor<float, 2, DataLayout> mat6(2,2);\n  mat6.setZero();\n  Eigen::array<DimPair, 1> dims6 = {{DimPair(1, 0)}};\n  typedef TensorEvaluator<decltype(mat1.contract(mat3, dims6)), DefaultDevice> Evaluator3;\n  Evaluator3 eval3(mat1.contract(mat3, dims6), DefaultDevice());\n  eval3.evalTo(mat6.data());\n  EIGEN_STATIC_ASSERT(Evaluator3::NumDims==2ul, YOU_MADE_A_PROGRAMMING_MISTAKE);\n  VERIFY_IS_EQUAL(eval3.dimensions()[0], 2);\n  VERIFY_IS_EQUAL(eval3.dimensions()[1], 2);\n\n  VERIFY_IS_APPROX(mat6(0,0), mat1(0,0)*mat3(0,0) + mat1(0,1)*mat3(1,0) + mat1(0,2)*mat3(2,0));\n  VERIFY_IS_APPROX(mat6(0,1), mat1(0,0)*mat3(0,1) + mat1(0,1)*mat3(1,1) + mat1(0,2)*mat3(2,1));\n  VERIFY_IS_APPROX(mat6(1,0), mat1(1,0)*mat3(0,0) + mat1(1,1)*mat3(1,0) + mat1(1,2)*mat3(2,0));\n  VERIFY_IS_APPROX(mat6(1,1), mat1(1,0)*mat3(0,1) + mat1(1,1)*mat3(1,1) + mat1(1,2)*mat3(2,1));\n}\n\ntemplate<int DataLayout>\nstatic void test_scalar()\n{\n  Tensor<float, 1, DataLayout> vec1({6});\n  Tensor<float, 1, DataLayout> vec2({6});\n\n  vec1.setRandom();\n  vec2.setRandom();\n\n  Eigen::array<DimPair, 1> dims = {{DimPair(0, 0)}};\n  Tensor<float, 0, DataLayout> scalar = vec1.contract(vec2, dims);\n\n  float expected = 0.0f;\n  for (int i = 0; i < 6; ++i) {\n    expected += vec1(i) * vec2(i);\n  }\n  VERIFY_IS_APPROX(scalar(), expected);\n}\n\ntemplate<int DataLayout>\nstatic void test_multidims()\n{\n  Tensor<float, 3, DataLayout> mat1(2, 2, 2);\n  Tensor<float, 4, DataLayout> mat2(2, 2, 2, 2);\n\n  mat1.setRandom();\n  mat2.setRandom();\n\n  Tensor<float, 3, DataLayout> mat3(2, 2, 2);\n  mat3.setZero();\n  Eigen::array<DimPair, 2> dims = {{DimPair(1, 2), DimPair(2, 3)}};\n  typedef TensorEvaluator<decltype(mat1.contract(mat2, dims)), DefaultDevice> Evaluator;\n  Evaluator eval(mat1.contract(mat2, dims), DefaultDevice());\n  eval.evalTo(mat3.data());\n  EIGEN_STATIC_ASSERT(Evaluator::NumDims==3ul, YOU_MADE_A_PROGRAMMING_MISTAKE);\n  VERIFY_IS_EQUAL(eval.dimensions()[0], 2);\n  VERIFY_IS_EQUAL(eval.dimensions()[1], 2);\n  VERIFY_IS_EQUAL(eval.dimensions()[2], 2);\n\n  VERIFY_IS_APPROX(mat3(0,0,0), mat1(0,0,0)*mat2(0,0,0,0) + mat1(0,1,0)*mat2(0,0,1,0) +\n                                mat1(0,0,1)*mat2(0,0,0,1) + mat1(0,1,1)*mat2(0,0,1,1));\n  VERIFY_IS_APPROX(mat3(0,0,1), mat1(0,0,0)*mat2(0,1,0,0) + mat1(0,1,0)*mat2(0,1,1,0) +\n                                mat1(0,0,1)*mat2(0,1,0,1) + mat1(0,1,1)*mat2(0,1,1,1));\n  VERIFY_IS_APPROX(mat3(0,1,0), mat1(0,0,0)*mat2(1,0,0,0) + mat1(0,1,0)*mat2(1,0,1,0) +\n                                mat1(0,0,1)*mat2(1,0,0,1) + mat1(0,1,1)*mat2(1,0,1,1));\n  VERIFY_IS_APPROX(mat3(0,1,1), mat1(0,0,0)*mat2(1,1,0,0) + mat1(0,1,0)*mat2(1,1,1,0) +\n                                mat1(0,0,1)*mat2(1,1,0,1) + mat1(0,1,1)*mat2(1,1,1,1));\n  VERIFY_IS_APPROX(mat3(1,0,0), mat1(1,0,0)*mat2(0,0,0,0) + mat1(1,1,0)*mat2(0,0,1,0) +\n                                mat1(1,0,1)*mat2(0,0,0,1) + mat1(1,1,1)*mat2(0,0,1,1));\n  VERIFY_IS_APPROX(mat3(1,0,1), mat1(1,0,0)*mat2(0,1,0,0) + mat1(1,1,0)*mat2(0,1,1,0) +\n                                mat1(1,0,1)*mat2(0,1,0,1) + mat1(1,1,1)*mat2(0,1,1,1));\n  VERIFY_IS_APPROX(mat3(1,1,0), mat1(1,0,0)*mat2(1,0,0,0) + mat1(1,1,0)*mat2(1,0,1,0) +\n                                mat1(1,0,1)*mat2(1,0,0,1) + mat1(1,1,1)*mat2(1,0,1,1));\n  VERIFY_IS_APPROX(mat3(1,1,1), mat1(1,0,0)*mat2(1,1,0,0) + mat1(1,1,0)*mat2(1,1,1,0) +\n                                mat1(1,0,1)*mat2(1,1,0,1) + mat1(1,1,1)*mat2(1,1,1,1));\n\n  Tensor<float, 2, DataLayout> mat4(2, 2);\n  Tensor<float, 3, DataLayout> mat5(2, 2, 2);\n\n  mat4.setRandom();\n  mat5.setRandom();\n\n  Tensor<float, 1, DataLayout> mat6(2);\n  mat6.setZero();\n  Eigen::array<DimPair, 2> dims2({{DimPair(0, 1), DimPair(1, 0)}});\n  typedef TensorEvaluator<decltype(mat4.contract(mat5, dims2)), DefaultDevice> Evaluator2;\n  Evaluator2 eval2(mat4.contract(mat5, dims2), DefaultDevice());\n  eval2.evalTo(mat6.data());\n  EIGEN_STATIC_ASSERT(Evaluator2::NumDims==1ul, YOU_MADE_A_PROGRAMMING_MISTAKE);\n  VERIFY_IS_EQUAL(eval2.dimensions()[0], 2);\n\n  VERIFY_IS_APPROX(mat6(0), mat4(0,0)*mat5(0,0,0) + mat4(1,0)*mat5(0,1,0) +\n                   mat4(0,1)*mat5(1,0,0) + mat4(1,1)*mat5(1,1,0));\n  VERIFY_IS_APPROX(mat6(1), mat4(0,0)*mat5(0,0,1) + mat4(1,0)*mat5(0,1,1) +\n                   mat4(0,1)*mat5(1,0,1) + mat4(1,1)*mat5(1,1,1));\n}\n\ntemplate<int DataLayout>\nstatic void test_holes() {\n  Tensor<float, 4, DataLayout> t1(2, 5, 7, 3);\n  Tensor<float, 5, DataLayout> t2(2, 7, 11, 13, 3);\n  t1.setRandom();\n  t2.setRandom();\n\n  Eigen::array<DimPair, 2> dims = {{DimPair(0, 0), DimPair(3, 4)}};\n  Tensor<float, 5, DataLayout> result = t1.contract(t2, dims);\n  VERIFY_IS_EQUAL(result.dimension(0), 5);\n  VERIFY_IS_EQUAL(result.dimension(1), 7);\n  VERIFY_IS_EQUAL(result.dimension(2), 7);\n  VERIFY_IS_EQUAL(result.dimension(3), 11);\n  VERIFY_IS_EQUAL(result.dimension(4), 13);\n\n  for (int i = 0; i < 5; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 5; ++l) {\n          for (int m = 0; m < 5; ++m) {\n            VERIFY_IS_APPROX(result(i, j, k, l, m),\n                             t1(0, i, j, 0) * t2(0, k, l, m, 0) +\n                             t1(1, i, j, 0) * t2(1, k, l, m, 0) +\n                             t1(0, i, j, 1) * t2(0, k, l, m, 1) +\n                             t1(1, i, j, 1) * t2(1, k, l, m, 1) +\n                             t1(0, i, j, 2) * t2(0, k, l, m, 2) +\n                             t1(1, i, j, 2) * t2(1, k, l, m, 2));\n          }\n        }\n      }\n    }\n  }\n}\n\ntemplate<int DataLayout>\nstatic void test_full_redux()\n{\n  Tensor<float, 2, DataLayout> t1(2, 2);\n  Tensor<float, 3, DataLayout> t2(2, 2, 2);\n  t1.setRandom();\n  t2.setRandom();\n\n  Eigen::array<DimPair, 2> dims = {{DimPair(0, 0), DimPair(1, 1)}};\n  Tensor<float, 1, DataLayout> result = t1.contract(t2, dims);\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_APPROX(result(0), t1(0, 0) * t2(0, 0, 0) +  t1(1, 0) * t2(1, 0, 0)\n                            + t1(0, 1) * t2(0, 1, 0) +  t1(1, 1) * t2(1, 1, 0));\n  VERIFY_IS_APPROX(result(1), t1(0, 0) * t2(0, 0, 1) +  t1(1, 0) * t2(1, 0, 1)\n                            + t1(0, 1) * t2(0, 1, 1) +  t1(1, 1) * t2(1, 1, 1));\n\n  dims[0] = DimPair(1, 0);\n  dims[1] = DimPair(2, 1);\n  result = t2.contract(t1, dims);\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_APPROX(result(0), t1(0, 0) * t2(0, 0, 0) +  t1(1, 0) * t2(0, 1, 0)\n                            + t1(0, 1) * t2(0, 0, 1) +  t1(1, 1) * t2(0, 1, 1));\n  VERIFY_IS_APPROX(result(1), t1(0, 0) * t2(1, 0, 0) +  t1(1, 0) * t2(1, 1, 0)\n                            + t1(0, 1) * t2(1, 0, 1) +  t1(1, 1) * t2(1, 1, 1));\n}\n\ntemplate<int DataLayout>\nstatic void test_contraction_of_contraction()\n{\n  Tensor<float, 2, DataLayout> t1(2, 2);\n  Tensor<float, 2, DataLayout> t2(2, 2);\n  Tensor<float, 2, DataLayout> t3(2, 2);\n  Tensor<float, 2, DataLayout> t4(2, 2);\n  t1.setRandom();\n  t2.setRandom();\n  t3.setRandom();\n  t4.setRandom();\n\n  Eigen::array<DimPair, 1> dims = {{DimPair(1, 0)}};\n  auto contract1 = t1.contract(t2, dims);\n  auto diff = t3 - contract1;\n  auto contract2 = t1.contract(t4, dims);\n  Tensor<float, 2, DataLayout> result = contract2.contract(diff, dims);\n\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_EQUAL(result.dimension(1), 2);\n\n  Eigen::Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>>\n      m1(t1.data(), 2, 2), m2(t2.data(), 2, 2), m3(t3.data(), 2, 2),\n      m4(t4.data(), 2, 2);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>\n      expected = (m1 * m4) * (m3 - m1 * m2);\n\n  VERIFY_IS_APPROX(result(0, 0), expected(0, 0));\n  VERIFY_IS_APPROX(result(0, 1), expected(0, 1));\n  VERIFY_IS_APPROX(result(1, 0), expected(1, 0));\n  VERIFY_IS_APPROX(result(1, 1), expected(1, 1));\n}\n\ntemplate<int DataLayout>\nstatic void test_expr()\n{\n  Tensor<float, 2, DataLayout> mat1(2, 3);\n  Tensor<float, 2, DataLayout> mat2(3, 2);\n  mat1.setRandom();\n  mat2.setRandom();\n\n  Tensor<float, 2, DataLayout> mat3(2,2);\n\n  Eigen::array<DimPair, 1> dims = {{DimPair(1, 0)}};\n  mat3 = mat1.contract(mat2, dims);\n\n  VERIFY_IS_APPROX(mat3(0,0), mat1(0,0)*mat2(0,0) + mat1(0,1)*mat2(1,0) + mat1(0,2)*mat2(2,0));\n  VERIFY_IS_APPROX(mat3(0,1), mat1(0,0)*mat2(0,1) + mat1(0,1)*mat2(1,1) + mat1(0,2)*mat2(2,1));\n  VERIFY_IS_APPROX(mat3(1,0), mat1(1,0)*mat2(0,0) + mat1(1,1)*mat2(1,0) + mat1(1,2)*mat2(2,0));\n  VERIFY_IS_APPROX(mat3(1,1), mat1(1,0)*mat2(0,1) + mat1(1,1)*mat2(1,1) + mat1(1,2)*mat2(2,1));\n}\n\ntemplate<int DataLayout>\nstatic void test_out_of_order_contraction()\n{\n  Tensor<float, 3, DataLayout> mat1(2, 2, 2);\n  Tensor<float, 3, DataLayout> mat2(2, 2, 2);\n\n  mat1.setRandom();\n  mat2.setRandom();\n\n  Tensor<float, 2, DataLayout> mat3(2, 2);\n\n  Eigen::array<DimPair, 2> dims = {{DimPair(2, 0), DimPair(0, 2)}};\n  mat3 = mat1.contract(mat2, dims);\n\n  VERIFY_IS_APPROX(mat3(0, 0),\n                   mat1(0,0,0)*mat2(0,0,0) + mat1(1,0,0)*mat2(0,0,1) +\n                   mat1(0,0,1)*mat2(1,0,0) + mat1(1,0,1)*mat2(1,0,1));\n  VERIFY_IS_APPROX(mat3(1, 0),\n                   mat1(0,1,0)*mat2(0,0,0) + mat1(1,1,0)*mat2(0,0,1) +\n                   mat1(0,1,1)*mat2(1,0,0) + mat1(1,1,1)*mat2(1,0,1));\n  VERIFY_IS_APPROX(mat3(0, 1),\n                   mat1(0,0,0)*mat2(0,1,0) + mat1(1,0,0)*mat2(0,1,1) +\n                   mat1(0,0,1)*mat2(1,1,0) + mat1(1,0,1)*mat2(1,1,1));\n  VERIFY_IS_APPROX(mat3(1, 1),\n                   mat1(0,1,0)*mat2(0,1,0) + mat1(1,1,0)*mat2(0,1,1) +\n                   mat1(0,1,1)*mat2(1,1,0) + mat1(1,1,1)*mat2(1,1,1));\n\n  Eigen::array<DimPair, 2> dims2 = {{DimPair(0, 2), DimPair(2, 0)}};\n  mat3 = mat1.contract(mat2, dims2);\n\n  VERIFY_IS_APPROX(mat3(0, 0),\n                   mat1(0,0,0)*mat2(0,0,0) + mat1(1,0,0)*mat2(0,0,1) +\n                   mat1(0,0,1)*mat2(1,0,0) + mat1(1,0,1)*mat2(1,0,1));\n  VERIFY_IS_APPROX(mat3(1, 0),\n                   mat1(0,1,0)*mat2(0,0,0) + mat1(1,1,0)*mat2(0,0,1) +\n                   mat1(0,1,1)*mat2(1,0,0) + mat1(1,1,1)*mat2(1,0,1));\n  VERIFY_IS_APPROX(mat3(0, 1),\n                   mat1(0,0,0)*mat2(0,1,0) + mat1(1,0,0)*mat2(0,1,1) +\n                   mat1(0,0,1)*mat2(1,1,0) + mat1(1,0,1)*mat2(1,1,1));\n  VERIFY_IS_APPROX(mat3(1, 1),\n                   mat1(0,1,0)*mat2(0,1,0) + mat1(1,1,0)*mat2(0,1,1) +\n                   mat1(0,1,1)*mat2(1,1,0) + mat1(1,1,1)*mat2(1,1,1));\n\n}\n\ntemplate<int DataLayout>\nstatic void test_consistency()\n{\n  // this does something like testing (A*B)^T = (B^T * A^T)\n\n  Tensor<float, 3, DataLayout> mat1(4, 3, 5);\n  Tensor<float, 5, DataLayout> mat2(3, 2, 1, 5, 4);\n  mat1.setRandom();\n  mat2.setRandom();\n\n  Tensor<float, 4, DataLayout> mat3(5, 2, 1, 5);\n  Tensor<float, 4, DataLayout> mat4(2, 1, 5, 5);\n\n  // contract on dimensions of size 4 and 3\n  Eigen::array<DimPair, 2> dims1 = {{DimPair(0, 4), DimPair(1, 0)}};\n  Eigen::array<DimPair, 2> dims2 = {{DimPair(4, 0), DimPair(0, 1)}};\n\n  mat3 = mat1.contract(mat2, dims1);\n  mat4 = mat2.contract(mat1, dims2);\n\n  // check that these are equal except for ordering of dimensions\n  if (DataLayout == ColMajor) {\n    for (size_t i = 0; i < 5; i++) {\n      for (size_t j = 0; j < 10; j++) {\n        VERIFY_IS_APPROX(mat3.data()[i + 5 * j], mat4.data()[j + 10 * i]);\n      }\n    }\n  } else {\n    // Row major\n    for (size_t i = 0; i < 5; i++) {\n      for (size_t j = 0; j < 10; j++) {\n        VERIFY_IS_APPROX(mat3.data()[10 * i + j], mat4.data()[i + 5 * j]);\n      }\n    }\n  }\n}\n\ntemplate<int DataLayout>\nstatic void test_large_contraction()\n{\n  Tensor<float, 4, DataLayout> t_left(30, 50, 8, 31);\n  Tensor<float, 5, DataLayout> t_right(8, 31, 7, 20, 10);\n  Tensor<float, 5, DataLayout> t_result(30, 50, 7, 20, 10);\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  // Add a little offset so that the results won't be close to zero.\n  t_left += t_left.constant(1.0f);\n  t_right += t_right.constant(1.0f);\n\n  typedef Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 1500, 248);\n  MapXf m_right(t_right.data(), 248, 1400);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result(1500, 1400);\n\n  // this contraction should be equivalent to a single matrix multiplication\n  Eigen::array<DimPair, 2> dims = {{DimPair(2, 0), DimPair(3, 1)}};\n\n  // compute results by separate methods\n  t_result = t_left.contract(t_right, dims);\n  m_result = m_left * m_right;\n\n  for (int i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY(&t_result.data()[i] != &m_result.data()[i]);\n    VERIFY_IS_APPROX(t_result.data()[i], m_result.data()[i]);\n  }\n}\n\ntemplate<int DataLayout>\nstatic void test_matrix_vector()\n{\n  Tensor<float, 2, DataLayout> t_left(30, 50);\n  Tensor<float, 1, DataLayout> t_right(50);\n  Tensor<float, 1, DataLayout> t_result(30);\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  typedef Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 30, 50);\n  MapXf m_right(t_right.data(), 50, 1);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result(30, 1);\n\n  // this contraction should be equivalent to a single matrix multiplication\n  Eigen::array<DimPair, 1> dims{{DimPair(1, 0)}};\n\n  // compute results by separate methods\n  t_result = t_left.contract(t_right, dims);\n  m_result = m_left * m_right;\n\n  for (int i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY(internal::isApprox(t_result(i), m_result(i, 0), 1));\n  }\n}\n\n\ntemplate<int DataLayout>\nstatic void test_tensor_vector()\n{\n  Tensor<float, 3, DataLayout> t_left(7, 13, 17);\n  Tensor<float, 2, DataLayout> t_right(1, 7);\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  typedef typename Tensor<float, 1, DataLayout>::DimensionPair DimensionPair;\n  Eigen::array<DimensionPair, 1> dim_pair01{{{0, 1}}};\n  Tensor<float, 3, DataLayout> t_result = t_left.contract(t_right, dim_pair01);\n\n  typedef Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 7, 13*17);\n  MapXf m_right(t_right.data(), 1, 7);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result = m_left.transpose() * m_right.transpose();\n\n  for (int i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY(internal::isApprox(t_result(i), m_result(i, 0), 1));\n  }\n}\n\n\ntemplate<int DataLayout>\nstatic void test_small_blocking_factors()\n{\n  Tensor<float, 4, DataLayout> t_left(30, 5, 3, 31);\n  Tensor<float, 5, DataLayout> t_right(3, 31, 7, 20, 1);\n  t_left.setRandom();\n  t_right.setRandom();\n\n  // Add a little offset so that the results won't be close to zero.\n  t_left += t_left.constant(1.0f);\n  t_right += t_right.constant(1.0f);\n\n  // Force the cache sizes, which results in smaller blocking factors.\n  Eigen::setCpuCacheSizes(896, 1920, 2944);\n\n  // this contraction should be equivalent to a single matrix multiplication\n  Eigen::array<DimPair, 2> dims = {{DimPair(2, 0), DimPair(3, 1)}};\n  Tensor<float, 5, DataLayout> t_result;\n  t_result = t_left.contract(t_right, dims);\n\n  // compute result using a simple eigen matrix product\n  Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> m_left(t_left.data(), 150, 93);\n  Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> m_right(t_right.data(), 93, 140);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result = m_left * m_right;\n\n  for (int i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY_IS_APPROX(t_result.data()[i], m_result.data()[i]);\n  }\n}\n\ntemplate<int DataLayout>\nstatic void test_tensor_product()\n{\n  Tensor<float, 2, DataLayout> mat1(2, 3);\n  Tensor<float, 2, DataLayout> mat2(4, 1);\n  mat1.setRandom();\n  mat2.setRandom();\n\n  Eigen::array<DimPair, 0> dims;\n  Tensor<float, 4, DataLayout> result = mat1.contract(mat2, dims);\n\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_EQUAL(result.dimension(1), 3);\n  VERIFY_IS_EQUAL(result.dimension(2), 4);\n  VERIFY_IS_EQUAL(result.dimension(3), 1);\n  for (int i = 0; i < result.dimension(0); ++i) {\n    for (int j = 0; j < result.dimension(1); ++j) {\n      for (int k = 0; k < result.dimension(2); ++k) {\n        for (int l = 0; l < result.dimension(3); ++l) {\n\t\t\tVERIFY_IS_APPROX(result(i, j, k, l), mat1(i, j) * mat2(k, l) );\n        }\n      }\n    }\n  }\n}\n\n\ntemplate<int DataLayout>\nstatic void test_const_inputs()\n{\n  Tensor<float, 2, DataLayout> in1(2, 3);\n  Tensor<float, 2, DataLayout> in2(3, 2);\n  in1.setRandom();\n  in2.setRandom();\n\n  TensorMap<Tensor<const float, 2, DataLayout> > mat1(in1.data(), 2, 3);\n  TensorMap<Tensor<const float, 2, DataLayout> > mat2(in2.data(), 3, 2);\n  Tensor<float, 2, DataLayout> mat3(2,2);\n\n  Eigen::array<DimPair, 1> dims = {{DimPair(1, 0)}};\n  mat3 = mat1.contract(mat2, dims);\n\n  VERIFY_IS_APPROX(mat3(0,0), mat1(0,0)*mat2(0,0) + mat1(0,1)*mat2(1,0) + mat1(0,2)*mat2(2,0));\n  VERIFY_IS_APPROX(mat3(0,1), mat1(0,0)*mat2(0,1) + mat1(0,1)*mat2(1,1) + mat1(0,2)*mat2(2,1));\n  VERIFY_IS_APPROX(mat3(1,0), mat1(1,0)*mat2(0,0) + mat1(1,1)*mat2(1,0) + mat1(1,2)*mat2(2,0));\n  VERIFY_IS_APPROX(mat3(1,1), mat1(1,0)*mat2(0,1) + mat1(1,1)*mat2(1,1) + mat1(1,2)*mat2(2,1));\n}\n\n// Apply Sqrt to all output elements.\nstruct SqrtOutputKernel {\n  template <typename Index, typename Scalar>\n  EIGEN_ALWAYS_INLINE void operator()(\n      const internal::blas_data_mapper<Scalar, Index, ColMajor>& output_mapper,\n      const TensorContractionParams&, Index, Index, Index num_rows,\n      Index num_cols) const {\n    for (int i = 0; i < num_rows; ++i) {\n      for (int j = 0; j < num_cols; ++j) {\n        output_mapper(i, j) = std::sqrt(output_mapper(i, j));\n      }\n    }\n  }\n};\n\ntemplate <int DataLayout>\nstatic void test_large_contraction_with_output_kernel() {\n  Tensor<float, 4, DataLayout> t_left(30, 50, 8, 31);\n  Tensor<float, 5, DataLayout> t_right(8, 31, 7, 20, 10);\n  Tensor<float, 5, DataLayout> t_result(30, 50, 7, 20, 10);\n\n  t_left.setRandom();\n  t_right.setRandom();\n  // Put trash in mat4 to verify contraction clears output memory.\n  t_result.setRandom();\n\n  // Add a little offset so that the results won't be close to zero.\n  t_left += t_left.constant(1.0f);\n  t_right += t_right.constant(1.0f);\n\n  typedef Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 1500, 248);\n  MapXf m_right(t_right.data(), 248, 1400);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result(1500, 1400);\n\n  // this contraction should be equivalent to a single matrix multiplication\n  Eigen::array<DimPair, 2> dims({{DimPair(2, 0), DimPair(3, 1)}});\n\n  // compute results by separate methods\n  t_result = t_left.contract(t_right, dims, SqrtOutputKernel());\n\n  m_result = m_left * m_right;\n\n  for (std::ptrdiff_t i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY(&t_result.data()[i] != &m_result.data()[i]);\n    VERIFY_IS_APPROX(t_result.data()[i], std::sqrt(m_result.data()[i]));\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_contraction)\n{\n  CALL_SUBTEST_1(test_evals<ColMajor>());\n  CALL_SUBTEST_1(test_evals<RowMajor>());\n  CALL_SUBTEST_1(test_scalar<ColMajor>());\n  CALL_SUBTEST_1(test_scalar<RowMajor>());\n  CALL_SUBTEST_2(test_multidims<ColMajor>());\n  CALL_SUBTEST_2(test_multidims<RowMajor>());\n  CALL_SUBTEST_2(test_holes<ColMajor>());\n  CALL_SUBTEST_2(test_holes<RowMajor>());\n  CALL_SUBTEST_3(test_full_redux<ColMajor>());\n  CALL_SUBTEST_3(test_full_redux<RowMajor>());\n  CALL_SUBTEST_3(test_contraction_of_contraction<ColMajor>());\n  CALL_SUBTEST_3(test_contraction_of_contraction<RowMajor>());\n  CALL_SUBTEST_4(test_expr<ColMajor>());\n  CALL_SUBTEST_4(test_expr<RowMajor>());\n  CALL_SUBTEST_4(test_out_of_order_contraction<ColMajor>());\n  CALL_SUBTEST_4(test_out_of_order_contraction<RowMajor>());\n  CALL_SUBTEST_5(test_consistency<ColMajor>());\n  CALL_SUBTEST_5(test_consistency<RowMajor>());\n  CALL_SUBTEST_5(test_large_contraction<ColMajor>());\n  CALL_SUBTEST_5(test_large_contraction<RowMajor>());\n  CALL_SUBTEST_6(test_matrix_vector<ColMajor>());\n  CALL_SUBTEST_6(test_matrix_vector<RowMajor>());\n  CALL_SUBTEST_6(test_tensor_vector<ColMajor>());\n  CALL_SUBTEST_6(test_tensor_vector<RowMajor>());\n  CALL_SUBTEST_7(test_small_blocking_factors<ColMajor>());\n  CALL_SUBTEST_7(test_small_blocking_factors<RowMajor>());\n  CALL_SUBTEST_7(test_tensor_product<ColMajor>());\n  CALL_SUBTEST_7(test_tensor_product<RowMajor>());\n  CALL_SUBTEST_8(test_const_inputs<ColMajor>());\n  CALL_SUBTEST_8(test_const_inputs<RowMajor>());\n  CALL_SUBTEST_8(test_large_contraction_with_output_kernel<ColMajor>());\n  CALL_SUBTEST_8(test_large_contraction_with_output_kernel<RowMajor>());\n\n  // Force CMake to split this test.\n  // EIGEN_SUFFIXES;1;2;3;4;5;6;7;8\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_convolution.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::DefaultDevice;\n\ntemplate <int DataLayout>\nstatic void test_evals()\n{\n  Tensor<float, 2, DataLayout> input(3, 3);\n  Tensor<float, 1, DataLayout> kernel(2);\n\n  input.setRandom();\n  kernel.setRandom();\n\n  Tensor<float, 2, DataLayout> result(2,3);\n  result.setZero();\n  Eigen::array<Tensor<float, 2>::Index, 1> dims3;\n  dims3[0] = 0;\n\n  typedef TensorEvaluator<decltype(input.convolve(kernel, dims3)), DefaultDevice> Evaluator;\n  Evaluator eval(input.convolve(kernel, dims3), DefaultDevice());\n  eval.evalTo(result.data());\n  EIGEN_STATIC_ASSERT(Evaluator::NumDims==2ul, YOU_MADE_A_PROGRAMMING_MISTAKE);\n  VERIFY_IS_EQUAL(eval.dimensions()[0], 2);\n  VERIFY_IS_EQUAL(eval.dimensions()[1], 3);\n\n  VERIFY_IS_APPROX(result(0,0), input(0,0)*kernel(0) + input(1,0)*kernel(1));  // index 0\n  VERIFY_IS_APPROX(result(0,1), input(0,1)*kernel(0) + input(1,1)*kernel(1));  // index 2\n  VERIFY_IS_APPROX(result(0,2), input(0,2)*kernel(0) + input(1,2)*kernel(1));  // index 4\n  VERIFY_IS_APPROX(result(1,0), input(1,0)*kernel(0) + input(2,0)*kernel(1));  // index 1\n  VERIFY_IS_APPROX(result(1,1), input(1,1)*kernel(0) + input(2,1)*kernel(1));  // index 3\n  VERIFY_IS_APPROX(result(1,2), input(1,2)*kernel(0) + input(2,2)*kernel(1));  // index 5\n}\n\ntemplate <int DataLayout>\nstatic void test_expr()\n{\n  Tensor<float, 2, DataLayout> input(3, 3);\n  Tensor<float, 2, DataLayout> kernel(2, 2);\n  input.setRandom();\n  kernel.setRandom();\n\n  Tensor<float, 2, DataLayout> result(2,2);\n  Eigen::array<ptrdiff_t, 2> dims;\n  dims[0] = 0;\n  dims[1] = 1;\n  result = input.convolve(kernel, dims);\n\n  VERIFY_IS_APPROX(result(0,0), input(0,0)*kernel(0,0) + input(0,1)*kernel(0,1) +\n                                input(1,0)*kernel(1,0) + input(1,1)*kernel(1,1));\n  VERIFY_IS_APPROX(result(0,1), input(0,1)*kernel(0,0) + input(0,2)*kernel(0,1) +\n                                input(1,1)*kernel(1,0) + input(1,2)*kernel(1,1));\n  VERIFY_IS_APPROX(result(1,0), input(1,0)*kernel(0,0) + input(1,1)*kernel(0,1) +\n                                input(2,0)*kernel(1,0) + input(2,1)*kernel(1,1));\n  VERIFY_IS_APPROX(result(1,1), input(1,1)*kernel(0,0) + input(1,2)*kernel(0,1) +\n                                input(2,1)*kernel(1,0) + input(2,2)*kernel(1,1));\n}\n\ntemplate <int DataLayout>\nstatic void test_modes() {\n  Tensor<float, 1, DataLayout> input(3);\n  Tensor<float, 1, DataLayout> kernel(3);\n  input(0) = 1.0f;\n  input(1) = 2.0f;\n  input(2) = 3.0f;\n  kernel(0) = 0.5f;\n  kernel(1) = 1.0f;\n  kernel(2) = 0.0f;\n\n  Eigen::array<ptrdiff_t, 1> dims;\n  dims[0] = 0;\n  Eigen::array<std::pair<ptrdiff_t, ptrdiff_t>, 1> padding;\n\n  // Emulate VALID mode (as defined in\n  // http://docs.scipy.org/doc/numpy/reference/generated/numpy.convolve.html).\n  padding[0] = std::make_pair(0, 0);\n  Tensor<float, 1, DataLayout> valid(1);\n  valid = input.pad(padding).convolve(kernel, dims);\n  VERIFY_IS_EQUAL(valid.dimension(0), 1);\n  VERIFY_IS_APPROX(valid(0), 2.5f);\n\n  // Emulate SAME mode (as defined in\n  // http://docs.scipy.org/doc/numpy/reference/generated/numpy.convolve.html).\n  padding[0] = std::make_pair(1, 1);\n  Tensor<float, 1, DataLayout> same(3);\n  same = input.pad(padding).convolve(kernel, dims);\n  VERIFY_IS_EQUAL(same.dimension(0), 3);\n  VERIFY_IS_APPROX(same(0), 1.0f);\n  VERIFY_IS_APPROX(same(1), 2.5f);\n  VERIFY_IS_APPROX(same(2), 4.0f);\n\n  // Emulate FULL mode (as defined in\n  // http://docs.scipy.org/doc/numpy/reference/generated/numpy.convolve.html).\n  padding[0] = std::make_pair(2, 2);\n  Tensor<float, 1, DataLayout> full(5);\n  full = input.pad(padding).convolve(kernel, dims);\n  VERIFY_IS_EQUAL(full.dimension(0), 5);\n  VERIFY_IS_APPROX(full(0), 0.0f);\n  VERIFY_IS_APPROX(full(1), 1.0f);\n  VERIFY_IS_APPROX(full(2), 2.5f);\n  VERIFY_IS_APPROX(full(3), 4.0f);\n  VERIFY_IS_APPROX(full(4), 1.5f);\n}\n\ntemplate <int DataLayout>\nstatic void test_strides() {\n  Tensor<float, 1, DataLayout> input(13);\n  Tensor<float, 1, DataLayout> kernel(3);\n  input.setRandom();\n  kernel.setRandom();\n\n  Eigen::array<ptrdiff_t, 1> dims;\n  dims[0] = 0;\n  Eigen::array<ptrdiff_t, 1> stride_of_3;\n  stride_of_3[0] = 3;\n  Eigen::array<ptrdiff_t, 1> stride_of_2;\n  stride_of_2[0] = 2;\n\n  Tensor<float, 1, DataLayout> result;\n  result = input.stride(stride_of_3).convolve(kernel, dims).stride(stride_of_2);\n\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_APPROX(result(0), (input(0)*kernel(0) + input(3)*kernel(1) +\n                               input(6)*kernel(2)));\n  VERIFY_IS_APPROX(result(1), (input(6)*kernel(0) + input(9)*kernel(1) +\n                               input(12)*kernel(2)));\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_convolution)\n{\n  CALL_SUBTEST(test_evals<ColMajor>());\n  CALL_SUBTEST(test_evals<RowMajor>());\n  CALL_SUBTEST(test_expr<ColMajor>());\n  CALL_SUBTEST(test_expr<RowMajor>());\n  CALL_SUBTEST(test_modes<ColMajor>());\n  CALL_SUBTEST(test_modes<RowMajor>());\n  CALL_SUBTEST(test_strides<ColMajor>());\n  CALL_SUBTEST(test_strides<RowMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_convolution_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include <iostream>\n#include <chrono>\n#include <ctime>\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n#include <iomanip>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\nstatic const float error_threshold =1e-4f;\n\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_larg_expr1D(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType indim0 =53;\n  IndexType indim1= 55;\n  IndexType indim2= 51;\n  IndexType outdim0=50;\n  IndexType outdim1=55;\n  IndexType outdim2=51;\n  Eigen::array<IndexType, 3> input_dims = {{indim0, indim1, indim2}};\n  Eigen::array<IndexType, 1> kernel_dims = {{4}};\n  Eigen::array<IndexType, 3> result_dims = {{outdim0, outdim1, outdim2}};\n\n  Tensor<DataType, 3, DataLayout, IndexType> input(input_dims);\n  Tensor<DataType, 1, DataLayout,IndexType> kernel(kernel_dims);\n  Tensor<DataType, 3, DataLayout,IndexType> result(result_dims);\n  Tensor<DataType, 3, DataLayout,IndexType> result_host(result_dims);\n\n  Eigen::array<IndexType, 1> dims3{{0}};\n\n  input.setRandom();\n  kernel.setRandom();\n  result.setZero();\n  result_host.setZero();\n\n  std::size_t input_bytes = input.size()  * sizeof(DataType);\n  std::size_t kernel_bytes = kernel.size() * sizeof(DataType);\n  std::size_t result_bytes = result.size() * sizeof(DataType);\n\n  DataType * d_input  = static_cast<DataType*>(sycl_device.allocate(input_bytes));\n  DataType * d_kernel  = static_cast<DataType*>(sycl_device.allocate(kernel_bytes));\n  DataType * d_result =  static_cast<DataType*>(sycl_device.allocate(result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType> > gpu_input(d_input, input_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 1, DataLayout, IndexType> > gpu_kernel(d_kernel, kernel_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType> > gpu_result(d_result, result_dims);\n  sycl_device.memcpyHostToDevice(d_input, input.data(), input_bytes);\n  sycl_device.memcpyHostToDevice(d_kernel, kernel.data(), kernel_bytes);\n\n  gpu_result.device(sycl_device)=gpu_input.convolve(gpu_kernel, dims3);\n  sycl_device.memcpyDeviceToHost(result.data(), d_result, result_bytes);\n\n  result_host=input.convolve(kernel, dims3);\n\nfor(IndexType i=0; i< outdim0; i++ ){\n  for(IndexType j=0; j< outdim1; j++ ){\n    for(IndexType k=0; k< outdim2; k++ ){\n      if (!(Eigen::internal::isApprox(result(i,j,k), result_host(i,j,k), error_threshold))) {\n        std::cout <<std::setprecision(16)<< \"mismatch detected at index  ( \"<< i  << \" , \"  << j  << \", \" << k << \" ) \" << \" \\t \" << result(i,j,k) << \" vs \"<<  result_host(i,j,k) << std::endl;\n        assert(false);\n      }\n    }\n  }\n}\n  sycl_device.deallocate(d_input);\n  sycl_device.deallocate(d_kernel);\n  sycl_device.deallocate(d_result);\n\n}\n\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_larg_expr2D(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType indim0 =53;\n  IndexType indim1= 55;\n  IndexType indim2= 51;\n  IndexType outdim0=50;\n  IndexType outdim1=51;\n  IndexType outdim2=51;\n  Eigen::array<IndexType, 3> input_dims = {{indim0, indim1, indim2}};\n  Eigen::array<IndexType, 2> kernel_dims = {{4,5}};\n  Eigen::array<IndexType, 3> result_dims = {{outdim0, outdim1, outdim2}};\n\n  Tensor<DataType, 3, DataLayout, IndexType> input(input_dims);\n  Tensor<DataType, 2, DataLayout,IndexType> kernel(kernel_dims);\n  Tensor<DataType, 3, DataLayout,IndexType> result(result_dims);\n  Tensor<DataType, 3, DataLayout,IndexType> result_host(result_dims);\n\n  Eigen::array<IndexType, 2> dims3{{0,1}};\n\n  input.setRandom();\n  kernel.setRandom();\n  result.setZero();\n  result_host.setZero();\n\n  std::size_t input_bytes = input.size()  * sizeof(DataType);\n  std::size_t kernel_bytes = kernel.size() * sizeof(DataType);\n  std::size_t result_bytes = result.size() * sizeof(DataType);\n\n  DataType * d_input  = static_cast<DataType*>(sycl_device.allocate(input_bytes));\n  DataType * d_kernel  = static_cast<DataType*>(sycl_device.allocate(kernel_bytes));\n  DataType * d_result =  static_cast<DataType*>(sycl_device.allocate(result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType> > gpu_input(d_input, input_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType> > gpu_kernel(d_kernel, kernel_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType> > gpu_result(d_result, result_dims);\n  sycl_device.memcpyHostToDevice(d_input, input.data(), input_bytes);\n  sycl_device.memcpyHostToDevice(d_kernel, kernel.data(), kernel_bytes);\n\n  gpu_result.device(sycl_device)=gpu_input.convolve(gpu_kernel, dims3);\n  sycl_device.memcpyDeviceToHost(result.data(), d_result, result_bytes);\n\n  result_host=input.convolve(kernel, dims3);\n\nfor(IndexType i=0; i< outdim0; i++ ){\n  for(IndexType j=0; j< outdim1; j++ ){\n    for(IndexType k=0; k< outdim2; k++ ){\n      if (!(Eigen::internal::isApprox(result(i,j,k), result_host(i,j,k), error_threshold))) {\n        std::cout <<std::setprecision(16)<< \"mismatch detected at index  ( \"<< i  << \" , \"  << j  << \", \" << k << \" ) \" << \" \\t \" << result(i,j,k) << \" vs \"<<  result_host(i,j,k) << std::endl;\n        assert(false);\n      }\n    }\n  }\n}\n  sycl_device.deallocate(d_input);\n  sycl_device.deallocate(d_kernel);\n  sycl_device.deallocate(d_result);\n\n}\n\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_larg_expr3D(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType indim0 =53;\n  IndexType indim1= 55;\n  IndexType indim2= 51;\n  IndexType outdim0=50;\n  IndexType outdim1=51;\n  IndexType outdim2=49;\n  Eigen::array<IndexType, 3> input_dims = {{indim0, indim1, indim2}};\n  Eigen::array<IndexType, 3> kernel_dims = {{4,5,3}};\n  Eigen::array<IndexType, 3> result_dims = {{outdim0, outdim1, outdim2}};\n\n  Tensor<DataType, 3, DataLayout, IndexType> input(input_dims);\n  Tensor<DataType, 3, DataLayout,IndexType> kernel(kernel_dims);\n  Tensor<DataType, 3, DataLayout,IndexType> result(result_dims);\n  Tensor<DataType, 3, DataLayout,IndexType> result_host(result_dims);\n\n  Eigen::array<IndexType, 3> dims3{{0,1,2}};\n\n  input.setRandom();\n  kernel.setRandom();\n  result.setZero();\n  result_host.setZero();\n\n  std::size_t input_bytes = input.size()  * sizeof(DataType);\n  std::size_t kernel_bytes = kernel.size() * sizeof(DataType);\n  std::size_t result_bytes = result.size() * sizeof(DataType);\n\n  DataType * d_input  = static_cast<DataType*>(sycl_device.allocate(input_bytes));\n  DataType * d_kernel  = static_cast<DataType*>(sycl_device.allocate(kernel_bytes));\n  DataType * d_result =  static_cast<DataType*>(sycl_device.allocate(result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType> > gpu_input(d_input, input_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType> > gpu_kernel(d_kernel, kernel_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType> > gpu_result(d_result, result_dims);\n  sycl_device.memcpyHostToDevice(d_input, input.data(), input_bytes);\n  sycl_device.memcpyHostToDevice(d_kernel, kernel.data(), kernel_bytes);\n\n  gpu_result.device(sycl_device)=gpu_input.convolve(gpu_kernel, dims3);\n  sycl_device.memcpyDeviceToHost(result.data(), d_result, result_bytes);\n\n  result_host=input.convolve(kernel, dims3);\n\nfor(IndexType i=0; i< outdim0; i++ ){\n  for(IndexType j=0; j< outdim1; j++ ){\n    for(IndexType k=0; k< outdim2; k++ ){\n      if (!(Eigen::internal::isApprox(result(i,j,k), result_host(i,j,k), error_threshold))) {\n        std::cout <<std::setprecision(16)<< \"mismatch detected at index  ( \"<< i  << \" , \"  << j  << \", \" << k << \" ) \" << \" \\t \" << result(i,j,k) << \" vs \"<<  result_host(i,j,k) << std::endl;\n        assert(false);\n      }\n    }\n  }\n}\n  sycl_device.deallocate(d_input);\n  sycl_device.deallocate(d_kernel);\n  sycl_device.deallocate(d_result);\n\n}\n\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_evals(const Eigen::SyclDevice& sycl_device)\n{\n  Eigen::array<IndexType, 2> input_dims = {{3, 3}};\n  Eigen::array<IndexType, 1> kernel_dims = {{2}};\n  Eigen::array<IndexType, 2> result_dims = {{2, 3}};\n\n  Tensor<DataType, 2, DataLayout, IndexType> input(input_dims);\n  Tensor<DataType, 1, DataLayout,IndexType> kernel(kernel_dims);\n  Tensor<DataType, 2, DataLayout,IndexType> result(result_dims);\n\n  Eigen::array<IndexType, 1> dims3{{0}};\n\n  input.setRandom();\n  kernel.setRandom();\n  result.setZero();\n\n  std::size_t input_bytes = input.size()  * sizeof(DataType);\n  std::size_t kernel_bytes = kernel.size() * sizeof(DataType);\n  std::size_t result_bytes = result.size() * sizeof(DataType);\n\n  DataType * d_input  = static_cast<DataType*>(sycl_device.allocate(input_bytes));\n  DataType * d_kernel  = static_cast<DataType*>(sycl_device.allocate(kernel_bytes));\n  DataType * d_result =  static_cast<DataType*>(sycl_device.allocate(result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType> > gpu_input(d_input, input_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 1, DataLayout, IndexType> > gpu_kernel(d_kernel, kernel_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType> > gpu_result(d_result, result_dims);\n  sycl_device.memcpyHostToDevice(d_input, input.data(), input_bytes);\n  sycl_device.memcpyHostToDevice(d_kernel, kernel.data(), kernel_bytes);\n\n  gpu_result.device(sycl_device)=gpu_input.convolve(gpu_kernel, dims3);\n  sycl_device.memcpyDeviceToHost(result.data(), d_result, result_bytes);\n\n  VERIFY_IS_APPROX(result(0,0), input(0,0)*kernel(0) + input(1,0)*kernel(1));  // index 0\n  VERIFY_IS_APPROX(result(0,1), input(0,1)*kernel(0) + input(1,1)*kernel(1));  // index 2\n  VERIFY_IS_APPROX(result(0,2), input(0,2)*kernel(0) + input(1,2)*kernel(1));  // index 4\n  VERIFY_IS_APPROX(result(1,0), input(1,0)*kernel(0) + input(2,0)*kernel(1));  // index 1\n  VERIFY_IS_APPROX(result(1,1), input(1,1)*kernel(0) + input(2,1)*kernel(1));  // index 3\n  VERIFY_IS_APPROX(result(1,2), input(1,2)*kernel(0) + input(2,2)*kernel(1));  // index 5\n\n  sycl_device.deallocate(d_input);\n  sycl_device.deallocate(d_kernel);\n  sycl_device.deallocate(d_result);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_expr(const Eigen::SyclDevice& sycl_device)\n{\n  Eigen::array<IndexType, 2> input_dims = {{3, 3}};\n  Eigen::array<IndexType, 2> kernel_dims = {{2, 2}};\n  Eigen::array<IndexType, 2> result_dims = {{2, 2}};\n\n  Tensor<DataType, 2, DataLayout, IndexType> input(input_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> kernel(kernel_dims);\n  Tensor<DataType, 2, DataLayout, IndexType> result(result_dims);\n\n  input.setRandom();\n  kernel.setRandom();\n  Eigen::array<IndexType, 2> dims;\n  dims[0] = 0;\n  dims[1] = 1;\n\n  std::size_t input_bytes = input.size()  * sizeof(DataType);\n  std::size_t kernel_bytes = kernel.size() * sizeof(DataType);\n  std::size_t result_bytes = result.size() * sizeof(DataType);\n\n  DataType * d_input  = static_cast<DataType*>(sycl_device.allocate(input_bytes));\n  DataType * d_kernel  = static_cast<DataType*>(sycl_device.allocate(kernel_bytes));\n  DataType * d_result =  static_cast<DataType*>(sycl_device.allocate(result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout,IndexType> > gpu_input(d_input, input_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout,IndexType> > gpu_kernel(d_kernel, kernel_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout,IndexType> > gpu_result(d_result, result_dims);\n  sycl_device.memcpyHostToDevice(d_input, input.data(), input_bytes);\n  sycl_device.memcpyHostToDevice(d_kernel, kernel.data(), kernel_bytes);\n\n  gpu_result.device(sycl_device)=gpu_input.convolve(gpu_kernel, dims);\n  sycl_device.memcpyDeviceToHost(result.data(), d_result, result_bytes);\n\n  VERIFY_IS_APPROX(result(0,0), input(0,0)*kernel(0,0) + input(0,1)*kernel(0,1) +\n                                input(1,0)*kernel(1,0) + input(1,1)*kernel(1,1));\n  VERIFY_IS_APPROX(result(0,1), input(0,1)*kernel(0,0) + input(0,2)*kernel(0,1) +\n                                input(1,1)*kernel(1,0) + input(1,2)*kernel(1,1));\n  VERIFY_IS_APPROX(result(1,0), input(1,0)*kernel(0,0) + input(1,1)*kernel(0,1) +\n                                input(2,0)*kernel(1,0) + input(2,1)*kernel(1,1));\n  VERIFY_IS_APPROX(result(1,1), input(1,1)*kernel(0,0) + input(1,2)*kernel(0,1) +\n                                input(2,1)*kernel(1,0) + input(2,2)*kernel(1,1));\n\n  sycl_device.deallocate(d_input);\n  sycl_device.deallocate(d_kernel);\n  sycl_device.deallocate(d_result);\n}\n\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_modes(const Eigen::SyclDevice& sycl_device){\n\nEigen::array<IndexType, 1> input_dims = {{3}};\nEigen::array<IndexType, 1> kernel_dims = {{3}};\n\nTensor<DataType, 1, DataLayout, IndexType> input(input_dims);\nTensor<DataType, 1, DataLayout, IndexType> kernel(kernel_dims);\n\ninput.setRandom();\nkernel.setRandom();\nEigen::array<IndexType, 1> dims;\ndims[0] = 0;\n\n  input(0) = 1.0f;\n  input(1) = 2.0f;\n  input(2) = 3.0f;\n  kernel(0) = 0.5f;\n  kernel(1) = 1.0f;\n  kernel(2) = 0.0f;\n\n  Eigen::array<std::pair<IndexType, IndexType>, 1> padding;\n\n  // Emulate VALID mode (as defined in\n  // http://docs.scipy.org/doc/numpy/reference/generated/numpy.convolve.html).\n  padding[0] = std::make_pair(0, 0);\n  Tensor<DataType, 1, DataLayout, IndexType> valid(1);\n\n  std::size_t input_bytes = input.size()  * sizeof(DataType);\n  std::size_t kernel_bytes = kernel.size() * sizeof(DataType);\n  std::size_t valid_bytes = valid.size() * sizeof(DataType);\n\n  DataType * d_input  = static_cast<DataType*>(sycl_device.allocate(input_bytes));\n  DataType * d_kernel  = static_cast<DataType*>(sycl_device.allocate(kernel_bytes));\n  DataType * d_valid =  static_cast<DataType*>(sycl_device.allocate(valid_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 1, DataLayout,IndexType> > gpu_input(d_input, input_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 1, DataLayout,IndexType> > gpu_kernel(d_kernel, kernel_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 1, DataLayout,IndexType> > gpu_valid(d_valid, valid.dimensions());\n  sycl_device.memcpyHostToDevice(d_input, input.data(), input_bytes);\n  sycl_device.memcpyHostToDevice(d_kernel, kernel.data(), kernel_bytes);\n\n  gpu_valid.device(sycl_device)=gpu_input.pad(padding).convolve(gpu_kernel, dims);\n  sycl_device.memcpyDeviceToHost(valid.data(), d_valid, valid_bytes);\n\n  VERIFY_IS_EQUAL(valid.dimension(0), 1);\n  VERIFY_IS_APPROX(valid(0), 2.5f);\n\n  // Emulate SAME mode (as defined in\n  // http://docs.scipy.org/doc/numpy/reference/generated/numpy.convolve.html).\n  padding[0] = std::make_pair(1, 1);\n  Tensor<DataType, 1, DataLayout, IndexType> same(3);\n  std::size_t same_bytes = same.size() * sizeof(DataType);\n  DataType * d_same =  static_cast<DataType*>(sycl_device.allocate(same_bytes));\n  Eigen::TensorMap<Eigen::Tensor<DataType, 1, DataLayout,IndexType> > gpu_same(d_same, same.dimensions());\n  gpu_same.device(sycl_device)=gpu_input.pad(padding).convolve(gpu_kernel, dims);\n  sycl_device.memcpyDeviceToHost(same.data(), d_same, same_bytes);\n\n  VERIFY_IS_EQUAL(same.dimension(0), 3);\n  VERIFY_IS_APPROX(same(0), 1.0f);\n  VERIFY_IS_APPROX(same(1), 2.5f);\n  VERIFY_IS_APPROX(same(2), 4.0f);\n\n  // Emulate FULL mode (as defined in\n  // http://docs.scipy.org/doc/numpy/reference/generated/numpy.convolve.html).\n  padding[0] = std::make_pair(2, 2);\n\n  Tensor<DataType, 1, DataLayout, IndexType> full(5);\n  std::size_t full_bytes = full.size() * sizeof(DataType);\n  DataType * d_full =  static_cast<DataType*>(sycl_device.allocate(full_bytes));\n  Eigen::TensorMap<Eigen::Tensor<DataType, 1, DataLayout,IndexType> > gpu_full(d_full, full.dimensions());\n  gpu_full.device(sycl_device)=gpu_input.pad(padding).convolve(gpu_kernel, dims);\n  sycl_device.memcpyDeviceToHost(full.data(), d_full, full_bytes);\n\n  VERIFY_IS_EQUAL(full.dimension(0), 5);\n  VERIFY_IS_APPROX(full(0), 0.0f);\n  VERIFY_IS_APPROX(full(1), 1.0f);\n  VERIFY_IS_APPROX(full(2), 2.5f);\n  VERIFY_IS_APPROX(full(3), 4.0f);\n  VERIFY_IS_APPROX(full(4), 1.5f);\n\n  sycl_device.deallocate(d_input);\n  sycl_device.deallocate(d_kernel);\n  sycl_device.deallocate(d_valid);\n  sycl_device.deallocate(d_same);\n  sycl_device.deallocate(d_full);\n\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_strides(const Eigen::SyclDevice& sycl_device){\n\n  Eigen::array<IndexType, 1> input_dims = {{13}};\n  Eigen::array<IndexType, 1> kernel_dims = {{3}};\n\n  Tensor<DataType, 1, DataLayout, IndexType> input(input_dims);\n  Tensor<DataType, 1, DataLayout, IndexType> kernel(kernel_dims);\n  Tensor<DataType, 1, DataLayout, IndexType> result(2);\n\n  input.setRandom();\n  kernel.setRandom();\n  Eigen::array<IndexType, 1> dims;\n  dims[0] = 0;\n\n  Eigen::array<IndexType, 1> stride_of_3;\n  stride_of_3[0] = 3;\n  Eigen::array<IndexType, 1> stride_of_2;\n  stride_of_2[0] = 2;\n\n  std::size_t input_bytes = input.size()  * sizeof(DataType);\n  std::size_t kernel_bytes = kernel.size() * sizeof(DataType);\n  std::size_t result_bytes = result.size() * sizeof(DataType);\n\n  DataType * d_input  = static_cast<DataType*>(sycl_device.allocate(input_bytes));\n  DataType * d_kernel  = static_cast<DataType*>(sycl_device.allocate(kernel_bytes));\n  DataType * d_result =  static_cast<DataType*>(sycl_device.allocate(result_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 1, DataLayout,IndexType> > gpu_input(d_input, input_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 1, DataLayout,IndexType> > gpu_kernel(d_kernel, kernel_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 1, DataLayout,IndexType> > gpu_result(d_result, result.dimensions());\n  sycl_device.memcpyHostToDevice(d_input, input.data(), input_bytes);\n  sycl_device.memcpyHostToDevice(d_kernel, kernel.data(), kernel_bytes);\n\n  gpu_result.device(sycl_device)=gpu_input.stride(stride_of_3).convolve(gpu_kernel, dims).stride(stride_of_2);\n  sycl_device.memcpyDeviceToHost(result.data(), d_result, result_bytes);\n\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_APPROX(result(0), (input(0)*kernel(0) + input(3)*kernel(1) +\n                               input(6)*kernel(2)));\n  VERIFY_IS_APPROX(result(1), (input(6)*kernel(0) + input(9)*kernel(1) +\n                               input(12)*kernel(2)));\n}\n\ntemplate <typename Dev_selector> void tensorConvolutionPerDevice(Dev_selector& s){\n  QueueInterface queueInterface(s);\n  auto sycl_device=Eigen::SyclDevice(&queueInterface);\n  test_larg_expr1D<float, RowMajor, int64_t>(sycl_device);\n  test_larg_expr1D<float, ColMajor, int64_t>(sycl_device);\n  test_larg_expr2D<float, RowMajor, int64_t>(sycl_device);\n  test_larg_expr2D<float, ColMajor, int64_t>(sycl_device);\n  test_larg_expr3D<float, RowMajor, int64_t>(sycl_device);\n  test_larg_expr3D<float, ColMajor, int64_t>(sycl_device);\n  test_evals<float, ColMajor, int64_t>(sycl_device);\n  test_evals<float, RowMajor, int64_t>(sycl_device);\n  test_expr<float, ColMajor, int64_t>(sycl_device);\n  test_expr<float, RowMajor, int64_t>(sycl_device);\n  test_modes<float, ColMajor, int64_t>(sycl_device);\n  test_modes<float, RowMajor, int64_t>(sycl_device);\n  test_strides<float, ColMajor, int64_t>(sycl_device);\n  test_strides<float, RowMajor, int64_t>(sycl_device);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_convolution_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(tensorConvolutionPerDevice(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_custom_index.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <limits>\n#include <map>\n\n#include <Eigen/Dense>\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\n\ntemplate <int DataLayout>\nstatic void test_map_as_index()\n{\n#ifdef EIGEN_HAS_SFINAE\n  Tensor<float, 4, DataLayout> tensor(2, 3, 5, 7);\n  tensor.setRandom();\n\n  using NormalIndex = DSizes<ptrdiff_t, 4>;\n  using CustomIndex = std::map<ptrdiff_t, ptrdiff_t>;\n  CustomIndex coeffC;\n  coeffC[0] = 1;\n  coeffC[1] = 2;\n  coeffC[2] = 4;\n  coeffC[3] = 1;\n  NormalIndex coeff(1,2,4,1);\n\n  VERIFY_IS_EQUAL(tensor.coeff(coeffC), tensor.coeff(coeff));\n  VERIFY_IS_EQUAL(tensor.coeffRef(coeffC), tensor.coeffRef(coeff));\n#endif\n}\n\n\ntemplate <int DataLayout>\nstatic void test_matrix_as_index()\n{\n#ifdef EIGEN_HAS_SFINAE\n  Tensor<float, 4, DataLayout> tensor(2, 3, 5, 7);\n  tensor.setRandom();\n\n  using NormalIndex = DSizes<ptrdiff_t, 4>;\n  using CustomIndex = Matrix<unsigned int, 4, 1>;\n  CustomIndex coeffC(1,2,4,1);\n  NormalIndex coeff(1,2,4,1);\n\n  VERIFY_IS_EQUAL(tensor.coeff(coeffC), tensor.coeff(coeff));\n  VERIFY_IS_EQUAL(tensor.coeffRef(coeffC), tensor.coeffRef(coeff));\n#endif\n}\n\n\ntemplate <int DataLayout>\nstatic void test_varlist_as_index()\n{\n#ifdef EIGEN_HAS_SFINAE\n  Tensor<float, 4, DataLayout> tensor(2, 3, 5, 7);\n  tensor.setRandom();\n\n  DSizes<ptrdiff_t, 4> coeff(1,2,4,1);\n\n  VERIFY_IS_EQUAL(tensor.coeff({1,2,4,1}), tensor.coeff(coeff));\n  VERIFY_IS_EQUAL(tensor.coeffRef({1,2,4,1}), tensor.coeffRef(coeff));\n#endif\n}\n\n\ntemplate <int DataLayout>\nstatic void test_sizes_as_index()\n{\n#ifdef EIGEN_HAS_SFINAE\n  Tensor<float, 4, DataLayout> tensor(2, 3, 5, 7);\n  tensor.setRandom();\n\n  DSizes<ptrdiff_t, 4> coeff(1,2,4,1);\n  Sizes<1,2,4,1> coeffC;\n\n  VERIFY_IS_EQUAL(tensor.coeff(coeffC), tensor.coeff(coeff));\n  VERIFY_IS_EQUAL(tensor.coeffRef(coeffC), tensor.coeffRef(coeff));\n#endif\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_custom_index) {\n  test_map_as_index<ColMajor>();\n  test_map_as_index<RowMajor>();\n  test_matrix_as_index<ColMajor>();\n  test_matrix_as_index<RowMajor>();\n  test_varlist_as_index<ColMajor>();\n  test_varlist_as_index<RowMajor>();\n  test_sizes_as_index<ColMajor>();\n  test_sizes_as_index<RowMajor>();\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_custom_op.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\n\nstruct InsertZeros {\n  DSizes<DenseIndex, 2> dimensions(const Tensor<float, 2>& input) const {\n    DSizes<DenseIndex, 2> result;\n    result[0] = input.dimension(0) * 2;\n    result[1] = input.dimension(1) * 2;\n    return result;\n  }\n\n  template <typename Output, typename Device>\n  void eval(const Tensor<float, 2>& input, Output& output, const Device& device) const\n  {\n    array<DenseIndex, 2> strides;\n    strides[0] = 2;\n    strides[1] = 2;\n    output.stride(strides).device(device) = input;\n\n    Eigen::DSizes<DenseIndex, 2> offsets(1,1);\n    Eigen::DSizes<DenseIndex, 2> extents(output.dimension(0)-1, output.dimension(1)-1);\n    output.slice(offsets, extents).stride(strides).device(device) = input.constant(0.0f);\n  }\n};\n\nstatic void test_custom_unary_op()\n{\n  Tensor<float, 2> tensor(3,5);\n  tensor.setRandom();\n\n  Tensor<float, 2> result = tensor.customOp(InsertZeros());\n  VERIFY_IS_EQUAL(result.dimension(0), 6);\n  VERIFY_IS_EQUAL(result.dimension(1), 10);\n\n  for (int i = 0; i < 6; i+=2) {\n    for (int j = 0; j < 10; j+=2) {\n      VERIFY_IS_EQUAL(result(i, j), tensor(i/2, j/2));\n    }\n  }\n  for (int i = 1; i < 6; i+=2) {\n    for (int j = 1; j < 10; j+=2) {\n      VERIFY_IS_EQUAL(result(i, j), 0);\n    }\n  }\n}\n\n\nstruct BatchMatMul {\n  DSizes<DenseIndex, 3> dimensions(const Tensor<float, 3>& input1, const Tensor<float, 3>& input2) const {\n    DSizes<DenseIndex, 3> result;\n    result[0] = input1.dimension(0);\n    result[1] = input2.dimension(1);\n    result[2] = input2.dimension(2);\n    return result;\n  }\n\n  template <typename Output, typename Device>\n  void eval(const Tensor<float, 3>& input1, const Tensor<float, 3>& input2,\n            Output& output, const Device& device) const\n  {\n    typedef Tensor<float, 3>::DimensionPair DimPair;\n    array<DimPair, 1> dims;\n    dims[0] = DimPair(1, 0);\n    for (int i = 0; i < output.dimension(2); ++i) {\n      output.template chip<2>(i).device(device) = input1.chip<2>(i).contract(input2.chip<2>(i), dims);\n    }\n  }\n};\n\n\nstatic void test_custom_binary_op()\n{\n  Tensor<float, 3> tensor1(2,3,5);\n  tensor1.setRandom();\n  Tensor<float, 3> tensor2(3,7,5);\n  tensor2.setRandom();\n\n  Tensor<float, 3> result = tensor1.customOp(tensor2, BatchMatMul());\n  for (int i = 0; i < 5; ++i) {\n    typedef Tensor<float, 3>::DimensionPair DimPair;\n    array<DimPair, 1> dims;\n    dims[0] = DimPair(1, 0);\n    Tensor<float, 2> reference = tensor1.chip<2>(i).contract(tensor2.chip<2>(i), dims);\n    TensorRef<Tensor<float, 2> > val = result.chip<2>(i);\n    for (int j = 0; j < 2; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(val(j, k), reference(j, k));\n      }\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_custom_op)\n{\n  CALL_SUBTEST(test_custom_unary_op());\n  CALL_SUBTEST(test_custom_binary_op());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_custom_op_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\ntemplate<typename TensorType>\nstruct InsertZeros {\n  DSizes<DenseIndex, 2> dimensions(const TensorType& input) const {\n    DSizes<DenseIndex, 2> result;\n    result[0] = input.dimension(0) * 2;\n    result[1] = input.dimension(1) * 2;\n    return result;\n  }\n\n  template <typename Output, typename Device>\n  void eval(const TensorType& input, Output& output, const Device& device) const\n  {\n    array<DenseIndex, 2> strides;\n    strides[0] = 2;\n    strides[1] = 2;\n    output.stride(strides).device(device) = input;\n\n    Eigen::DSizes<DenseIndex, 2> offsets(1,1);\n    Eigen::DSizes<DenseIndex, 2> extents(output.dimension(0)-1, output.dimension(1)-1);\n    output.slice(offsets, extents).stride(strides).device(device) = input.constant(0.0f);\n  }\n};\n\ntemplate<typename DataType, int DataLayout, typename IndexType>\nstatic void test_custom_unary_op_sycl(const Eigen::SyclDevice &sycl_device)\n{\n  IndexType sizeDim1 = 3;\n  IndexType sizeDim2 = 5;\n  Eigen::array<IndexType, 2> tensorRange = {{sizeDim1, sizeDim2}};\n  Eigen::array<IndexType, 2> tensorResultRange = {{6, 10}};\n\n  Eigen::Tensor<DataType, 2, DataLayout, IndexType> in1(tensorRange);\n  Eigen::Tensor<DataType, 2, DataLayout, IndexType> out(tensorResultRange);\n\n  DataType * gpu_in1_data  = static_cast<DataType*>(sycl_device.allocate(in1.dimensions().TotalSize()*sizeof(DataType)));\n  DataType * gpu_out_data =  static_cast<DataType*>(sycl_device.allocate(out.dimensions().TotalSize()*sizeof(DataType)));\n\n  typedef Eigen::TensorMap<Eigen::Tensor<DataType, 2, DataLayout, IndexType> > TensorType;\n  TensorType gpu_in1(gpu_in1_data, tensorRange);\n  TensorType gpu_out(gpu_out_data, tensorResultRange);\n\n  in1.setRandom();\n  sycl_device.memcpyHostToDevice(gpu_in1_data, in1.data(),(in1.dimensions().TotalSize())*sizeof(DataType));\n  gpu_out.device(sycl_device) = gpu_in1.customOp(InsertZeros<TensorType>());\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data,(out.dimensions().TotalSize())*sizeof(DataType));\n\n  VERIFY_IS_EQUAL(out.dimension(0), 6);\n  VERIFY_IS_EQUAL(out.dimension(1), 10);\n\n  for (int i = 0; i < 6; i+=2) {\n    for (int j = 0; j < 10; j+=2) {\n      VERIFY_IS_EQUAL(out(i, j), in1(i/2, j/2));\n    }\n  }\n  for (int i = 1; i < 6; i+=2) {\n    for (int j = 1; j < 10; j+=2) {\n      VERIFY_IS_EQUAL(out(i, j), 0);\n    }\n  }\n  sycl_device.deallocate(gpu_in1_data);\nsycl_device.deallocate(gpu_out_data);\n}\n\ntemplate<typename TensorType>\nstruct BatchMatMul {\n  DSizes<DenseIndex, 3> dimensions(const TensorType& input1, const TensorType& input2) const {\n    DSizes<DenseIndex, 3> result;\n    result[0] = input1.dimension(0);\n    result[1] = input2.dimension(1);\n    result[2] = input2.dimension(2);\n    return result;\n  }\n\n  template <typename Output, typename Device>\n  void eval(const TensorType& input1, const TensorType& input2,\n            Output& output, const Device& device) const\n  {\n    typedef typename TensorType::DimensionPair DimPair;\n    array<DimPair, 1> dims;\n    dims[0] = DimPair(1, 0);\n    for (int64_t i = 0; i < output.dimension(2); ++i) {\n      output.template chip<2>(i).device(device) = input1.template chip<2>(i).contract(input2.template chip<2>(i), dims);\n    }\n  }\n};\n\ntemplate<typename DataType, int DataLayout, typename IndexType>\nstatic void test_custom_binary_op_sycl(const Eigen::SyclDevice &sycl_device)\n{\n\n  Eigen::array<IndexType, 3> tensorRange1 = {{2, 3, 5}};\n  Eigen::array<IndexType, 3> tensorRange2 = {{3,7,5}};\n  Eigen::array<IndexType, 3> tensorResultRange  = {{2, 7, 5}};\n\n  Eigen::Tensor<DataType, 3, DataLayout, IndexType> in1(tensorRange1);\n  Eigen::Tensor<DataType, 3, DataLayout, IndexType> in2(tensorRange2);\n  Eigen::Tensor<DataType, 3, DataLayout, IndexType> out(tensorResultRange);\n\n  DataType * gpu_in1_data  = static_cast<DataType*>(sycl_device.allocate(in1.dimensions().TotalSize()*sizeof(DataType)));\n  DataType * gpu_in2_data  = static_cast<DataType*>(sycl_device.allocate(in2.dimensions().TotalSize()*sizeof(DataType)));\n  DataType * gpu_out_data =  static_cast<DataType*>(sycl_device.allocate(out.dimensions().TotalSize()*sizeof(DataType)));\n\n  typedef Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType> > TensorType;\n  TensorType gpu_in1(gpu_in1_data, tensorRange1);\n  TensorType gpu_in2(gpu_in2_data, tensorRange2);\n  TensorType gpu_out(gpu_out_data, tensorResultRange);\n\n  in1.setRandom();\n  in2.setRandom();\n\n  sycl_device.memcpyHostToDevice(gpu_in1_data, in1.data(),(in1.dimensions().TotalSize())*sizeof(DataType));\n  sycl_device.memcpyHostToDevice(gpu_in2_data, in2.data(),(in2.dimensions().TotalSize())*sizeof(DataType));\n\n  gpu_out.device(sycl_device) = gpu_in1.customOp(gpu_in2, BatchMatMul<TensorType>());\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data,(out.dimensions().TotalSize())*sizeof(DataType));\n\n  for (IndexType i = 0; i < 5; ++i) {\n    typedef typename Eigen::Tensor<DataType, 3, DataLayout, IndexType>::DimensionPair DimPair;\n    array<DimPair, 1> dims;\n    dims[0] = DimPair(1, 0);\n    Eigen::Tensor<DataType, 2, DataLayout, IndexType> reference = in1.template chip<2>(i).contract(in2.template chip<2>(i), dims);\n    TensorRef<Eigen::Tensor<DataType, 2, DataLayout, IndexType> > val = out.template chip<2>(i);\n    for (IndexType j = 0; j < 2; ++j) {\n      for (IndexType k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(val(j, k), reference(j, k));\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_in1_data);\n  sycl_device.deallocate(gpu_in2_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, typename Dev_selector> void custom_op_perDevice(Dev_selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_custom_unary_op_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_custom_unary_op_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_custom_binary_op_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_custom_binary_op_sycl<DataType, RowMajor, int64_t>(sycl_device);\n\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_custom_op_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(custom_op_perDevice<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_device.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\n#include <unsupported/Eigen/CXX11/src/Tensor/TensorGpuHipCudaDefines.h>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\n// Context for evaluation on cpu\nstruct CPUContext {\n  CPUContext(const Eigen::Tensor<float, 3>& in1, Eigen::Tensor<float, 3>& in2, Eigen::Tensor<float, 3>& out) : in1_(in1), in2_(in2), out_(out), kernel_1d_(2), kernel_2d_(2,2), kernel_3d_(2,2,2) {\n    kernel_1d_(0) = 3.14f;\n    kernel_1d_(1) = 2.7f;\n\n    kernel_2d_(0,0) = 3.14f;\n    kernel_2d_(1,0) = 2.7f;\n    kernel_2d_(0,1) = 0.2f;\n    kernel_2d_(1,1) = 7.0f;\n\n    kernel_3d_(0,0,0) = 3.14f;\n    kernel_3d_(0,1,0) = 2.7f;\n    kernel_3d_(0,0,1) = 0.2f;\n    kernel_3d_(0,1,1) = 7.0f;\n    kernel_3d_(1,0,0) = -1.0f;\n    kernel_3d_(1,1,0) = -0.3f;\n    kernel_3d_(1,0,1) = -0.7f;\n    kernel_3d_(1,1,1) = -0.5f;\n  }\n\n  const Eigen::DefaultDevice& device() const { return cpu_device_; }\n\n  const Eigen::Tensor<float, 3>& in1() const { return in1_; }\n  const Eigen::Tensor<float, 3>& in2() const { return in2_; }\n  Eigen::Tensor<float, 3>& out() { return out_; }\n  const Eigen::Tensor<float, 1>& kernel1d() const { return kernel_1d_; }\n  const Eigen::Tensor<float, 2>& kernel2d() const { return kernel_2d_; }\n  const Eigen::Tensor<float, 3>& kernel3d() const { return kernel_3d_; }\n\n private:\n  const Eigen::Tensor<float, 3>& in1_;\n  const Eigen::Tensor<float, 3>& in2_;\n  Eigen::Tensor<float, 3>& out_;\n\n  Eigen::Tensor<float, 1> kernel_1d_;\n  Eigen::Tensor<float, 2> kernel_2d_;\n  Eigen::Tensor<float, 3> kernel_3d_;\n\n  Eigen::DefaultDevice cpu_device_;\n};\n\n\n// Context for evaluation on GPU\nstruct GPUContext {\n  GPUContext(const Eigen::TensorMap<Eigen::Tensor<float, 3> >& in1, Eigen::TensorMap<Eigen::Tensor<float, 3> >& in2, Eigen::TensorMap<Eigen::Tensor<float, 3> >& out) : in1_(in1), in2_(in2), out_(out), gpu_device_(&stream_) {\n    assert(gpuMalloc((void**)(&kernel_1d_), 2*sizeof(float)) == gpuSuccess);\n    float kernel_1d_val[] = {3.14f, 2.7f};\n    assert(gpuMemcpy(kernel_1d_, kernel_1d_val, 2*sizeof(float), gpuMemcpyHostToDevice) == gpuSuccess);\n\n    assert(gpuMalloc((void**)(&kernel_2d_), 4*sizeof(float)) == gpuSuccess);\n    float kernel_2d_val[] = {3.14f, 2.7f, 0.2f, 7.0f};\n    assert(gpuMemcpy(kernel_2d_, kernel_2d_val, 4*sizeof(float), gpuMemcpyHostToDevice) == gpuSuccess);\n\n    assert(gpuMalloc((void**)(&kernel_3d_), 8*sizeof(float)) == gpuSuccess);\n    float kernel_3d_val[] = {3.14f, -1.0f, 2.7f, -0.3f, 0.2f, -0.7f, 7.0f, -0.5f};\n    assert(gpuMemcpy(kernel_3d_, kernel_3d_val, 8*sizeof(float), gpuMemcpyHostToDevice) == gpuSuccess);\n  }\n  ~GPUContext() {\n    assert(gpuFree(kernel_1d_) == gpuSuccess);\n    assert(gpuFree(kernel_2d_) == gpuSuccess);\n    assert(gpuFree(kernel_3d_) == gpuSuccess);\n  }\n\n  const Eigen::GpuDevice& device() const { return gpu_device_; }\n\n  const Eigen::TensorMap<Eigen::Tensor<float, 3> >& in1() const { return in1_; }\n  const Eigen::TensorMap<Eigen::Tensor<float, 3> >& in2() const { return in2_; }\n  Eigen::TensorMap<Eigen::Tensor<float, 3> >& out() { return out_; }\n  Eigen::TensorMap<Eigen::Tensor<float, 1> > kernel1d() const { return Eigen::TensorMap<Eigen::Tensor<float, 1> >(kernel_1d_, 2); }\n  Eigen::TensorMap<Eigen::Tensor<float, 2> > kernel2d() const { return Eigen::TensorMap<Eigen::Tensor<float, 2> >(kernel_2d_, 2, 2); }\n  Eigen::TensorMap<Eigen::Tensor<float, 3> > kernel3d() const { return Eigen::TensorMap<Eigen::Tensor<float, 3> >(kernel_3d_, 2, 2, 2); }\n\n private:\n  const Eigen::TensorMap<Eigen::Tensor<float, 3> >& in1_;\n  const Eigen::TensorMap<Eigen::Tensor<float, 3> >& in2_;\n  Eigen::TensorMap<Eigen::Tensor<float, 3> >& out_;\n\n  float* kernel_1d_;\n  float* kernel_2d_;\n  float* kernel_3d_;\n\n  Eigen::GpuStreamDevice stream_;\n  Eigen::GpuDevice gpu_device_;\n};\n\n\n// The actual expression to evaluate\ntemplate <typename Context>\nvoid test_contextual_eval(Context* context)\n{\n  context->out().device(context->device()) = context->in1() + context->in2() * 3.14f + context->in1().constant(2.718f);\n}\n\ntemplate <typename Context>\nvoid test_forced_contextual_eval(Context* context)\n{\n  context->out().device(context->device()) = (context->in1() + context->in2()).eval() * 3.14f + context->in1().constant(2.718f);\n}\n\ntemplate <typename Context>\nvoid test_compound_assignment(Context* context)\n{\n  context->out().device(context->device()) = context->in1().constant(2.718f);\n  context->out().device(context->device()) += context->in1() + context->in2() * 3.14f;\n}\n\n\ntemplate <typename Context>\nvoid test_contraction(Context* context)\n{\n  Eigen::array<std::pair<int, int>, 2> dims;\n  dims[0] = std::make_pair(1, 1);\n  dims[1] = std::make_pair(2, 2);\n\n  Eigen::array<int, 2> shape(40, 50*70);\n\n  Eigen::DSizes<int, 2> indices(0,0);\n  Eigen::DSizes<int, 2> sizes(40,40);\n\n  context->out().reshape(shape).slice(indices, sizes).device(context->device()) = context->in1().contract(context->in2(), dims);\n}\n\n\ntemplate <typename Context>\nvoid test_1d_convolution(Context* context)\n{\n  Eigen::DSizes<int, 3> indices(0,0,0);\n  Eigen::DSizes<int, 3> sizes(40,49,70);\n\n  Eigen::array<int, 1> dims(1);\n  context->out().slice(indices, sizes).device(context->device()) = context->in1().convolve(context->kernel1d(), dims);\n}\n\ntemplate <typename Context>\nvoid test_2d_convolution(Context* context)\n{\n  Eigen::DSizes<int, 3> indices(0,0,0);\n  Eigen::DSizes<int, 3> sizes(40,49,69);\n\n  Eigen::array<int, 2> dims(1,2);\n  context->out().slice(indices, sizes).device(context->device()) = context->in1().convolve(context->kernel2d(), dims);\n}\n\ntemplate <typename Context>\nvoid test_3d_convolution(Context* context)\n{\n  Eigen::DSizes<int, 3> indices(0,0,0);\n  Eigen::DSizes<int, 3> sizes(39,49,69);\n\n  Eigen::array<int, 3> dims(0,1,2);\n  context->out().slice(indices, sizes).device(context->device()) = context->in1().convolve(context->kernel3d(), dims);\n}\n\n\nvoid test_cpu() {\n  Eigen::Tensor<float, 3> in1(40,50,70);\n  Eigen::Tensor<float, 3> in2(40,50,70);\n  Eigen::Tensor<float, 3> out(40,50,70);\n\n  in1 = in1.random() + in1.constant(10.0f);\n  in2 = in2.random() + in2.constant(10.0f);\n\n  CPUContext context(in1, in2, out);\n  test_contextual_eval(&context);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 50; ++j) {\n      for (int k = 0; k < 70; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k), in1(i,j,k) + in2(i,j,k) * 3.14f + 2.718f);\n      }\n    }\n  }\n\n  test_forced_contextual_eval(&context);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 50; ++j) {\n      for (int k = 0; k < 70; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k), (in1(i,j,k) + in2(i,j,k)) * 3.14f + 2.718f);\n      }\n    }\n  }\n\n  test_compound_assignment(&context);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 50; ++j) {\n      for (int k = 0; k < 70; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k), in1(i,j,k) + in2(i,j,k) * 3.14f + 2.718f);\n      }\n    }\n  }\n\n  test_contraction(&context);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 40; ++j) {\n      const float result = out(i,j,0);\n      float expected = 0;\n      for (int k = 0; k < 50; ++k) {\n        for (int l = 0; l < 70; ++l) {\n          expected += in1(i, k, l) * in2(j, k, l);\n        }\n      }\n      VERIFY_IS_APPROX(expected, result);\n    }\n  }\n\n  test_1d_convolution(&context);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 49; ++j) {\n      for (int k = 0; k < 70; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k), (in1(i,j,k) * 3.14f + in1(i,j+1,k) * 2.7f));\n      }\n    }\n  }\n\n  test_2d_convolution(&context);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 49; ++j) {\n      for (int k = 0; k < 69; ++k) {\n        const float result = out(i,j,k);\n        const float expected = (in1(i,j,k) * 3.14f + in1(i,j+1,k) * 2.7f) +\n                               (in1(i,j,k+1) * 0.2f + in1(i,j+1,k+1) * 7.0f);\n        if (fabs(expected) < 1e-4f && fabs(result) < 1e-4f) {\n          continue;\n        }\n        VERIFY_IS_APPROX(expected, result);\n      }\n    }\n  }\n\n  test_3d_convolution(&context);\n  for (int i = 0; i < 39; ++i) {\n    for (int j = 0; j < 49; ++j) {\n      for (int k = 0; k < 69; ++k) {\n        const float result = out(i,j,k);\n        const float expected = (in1(i,j,k) * 3.14f + in1(i,j+1,k) * 2.7f +\n                                in1(i,j,k+1) * 0.2f + in1(i,j+1,k+1) * 7.0f) +\n                               (in1(i+1,j,k) * -1.0f + in1(i+1,j+1,k) * -0.3f +\n                                in1(i+1,j,k+1) * -0.7f + in1(i+1,j+1,k+1) * -0.5f);\n        if (fabs(expected) < 1e-4f && fabs(result) < 1e-4f) {\n          continue;\n        }\n        VERIFY_IS_APPROX(expected, result);\n      }\n    }\n  }\n}\n\nvoid test_gpu() {\n  Eigen::Tensor<float, 3> in1(40,50,70);\n  Eigen::Tensor<float, 3> in2(40,50,70);\n  Eigen::Tensor<float, 3> out(40,50,70);\n  in1 = in1.random() + in1.constant(10.0f);\n  in2 = in2.random() + in2.constant(10.0f);\n\n  std::size_t in1_bytes = in1.size() * sizeof(float);\n  std::size_t in2_bytes = in2.size() * sizeof(float);\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_in1;\n  float* d_in2;\n  float* d_out;\n  gpuMalloc((void**)(&d_in1), in1_bytes);\n  gpuMalloc((void**)(&d_in2), in2_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  gpuMemcpy(d_in1, in1.data(), in1_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_in2, in2.data(), in2_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 3> > gpu_in1(d_in1, 40,50,70);\n  Eigen::TensorMap<Eigen::Tensor<float, 3> > gpu_in2(d_in2, 40,50,70);\n  Eigen::TensorMap<Eigen::Tensor<float, 3> > gpu_out(d_out, 40,50,70);\n\n  GPUContext context(gpu_in1, gpu_in2, gpu_out);\n  test_contextual_eval(&context);\n  assert(gpuMemcpy(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost) == gpuSuccess);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 50; ++j) {\n      for (int k = 0; k < 70; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k), in1(i,j,k) + in2(i,j,k) * 3.14f + 2.718f);\n      }\n    }\n  }\n\n  test_forced_contextual_eval(&context);\n  assert(gpuMemcpy(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost) == gpuSuccess);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 50; ++j) {\n      for (int k = 0; k < 70; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k), (in1(i,j,k) + in2(i,j,k)) * 3.14f + 2.718f);\n      }\n    }\n  }\n\n  test_compound_assignment(&context);\n  assert(gpuMemcpy(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost) == gpuSuccess);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 50; ++j) {\n      for (int k = 0; k < 70; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k), in1(i,j,k) + in2(i,j,k) * 3.14f + 2.718f);\n      }\n    }\n  }\n\n  test_contraction(&context);\n  assert(gpuMemcpy(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost) == gpuSuccess);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 40; ++j) {\n      const float result = out(i,j,0);\n      float expected = 0;\n      for (int k = 0; k < 50; ++k) {\n        for (int l = 0; l < 70; ++l) {\n          expected += in1(i, k, l) * in2(j, k, l);\n        }\n      }\n      VERIFY_IS_APPROX(expected, result);\n    }\n  }\n\n  test_1d_convolution(&context);\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, context.device().stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(context.device().stream()) == gpuSuccess);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 49; ++j) {\n      for (int k = 0; k < 70; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k), (in1(i,j,k) * 3.14f + in1(i,j+1,k) * 2.7f));\n      }\n    }\n  }\n\n  test_2d_convolution(&context);\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, context.device().stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(context.device().stream()) == gpuSuccess);\n  for (int i = 0; i < 40; ++i) {\n    for (int j = 0; j < 49; ++j) {\n      for (int k = 0; k < 69; ++k) {\n        const float result = out(i,j,k);\n        const float expected = (in1(i,j,k) * 3.14f + in1(i,j+1,k) * 2.7f +\n                                in1(i,j,k+1) * 0.2f + in1(i,j+1,k+1) * 7.0f);\n        VERIFY_IS_APPROX(expected, result);\n      }\n    }\n  }\n\n#if !defined(EIGEN_USE_HIP)\n// disable this test on the HIP platform\n// 3D tensor convolutions seem to hang on the HIP platform\n\n  test_3d_convolution(&context);\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, context.device().stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(context.device().stream()) == gpuSuccess);\n  for (int i = 0; i < 39; ++i) {\n    for (int j = 0; j < 49; ++j) {\n      for (int k = 0; k < 69; ++k) {\n       const float result = out(i,j,k);\n        const float expected = (in1(i,j,k) * 3.14f + in1(i,j+1,k) * 2.7f +\n                                in1(i,j,k+1) * 0.2f + in1(i,j+1,k+1) * 7.0f +\n                                in1(i+1,j,k) * -1.0f + in1(i+1,j+1,k) * -0.3f +\n                                in1(i+1,j,k+1) * -0.7f + in1(i+1,j+1,k+1) * -0.5f);\n        VERIFY_IS_APPROX(expected, result);\n      }\n    }\n  }\n\n#endif\n \n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_device)\n{\n  CALL_SUBTEST_1(test_cpu());\n  CALL_SUBTEST_2(test_gpu());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_device_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n#include <stdint.h>\n#include <iostream>\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_device_memory(const Eigen::SyclDevice &sycl_device) {\n  std::cout << \"Running on : \"\n            << sycl_device.sycl_queue().get_device(). template get_info<cl::sycl::info::device::name>()\n            <<std::endl;\n  IndexType sizeDim1 = 100;\n  array<IndexType, 1> tensorRange = {{sizeDim1}};\n  Tensor<DataType, 1, DataLayout,IndexType> in(tensorRange);\n  Tensor<DataType, 1, DataLayout,IndexType> in1(tensorRange);\n  memset(in1.data(), 1, in1.size() * sizeof(DataType));\n  DataType* gpu_in_data  = static_cast<DataType*>(sycl_device.allocate(in.size()*sizeof(DataType)));\n  sycl_device.memset(gpu_in_data, 1, in.size()*sizeof(DataType));\n  sycl_device.memcpyDeviceToHost(in.data(), gpu_in_data, in.size()*sizeof(DataType));\n  for (IndexType i=0; i<in.size(); i++) {\n    VERIFY_IS_EQUAL(in(i), in1(i));\n  }\n  sycl_device.deallocate(gpu_in_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_device_exceptions(const Eigen::SyclDevice &sycl_device) {\n  VERIFY(sycl_device.ok());\n  IndexType sizeDim1 = 100;\n  array<IndexType, 1> tensorDims = {{sizeDim1}};\n  DataType* gpu_data = static_cast<DataType*>(sycl_device.allocate(sizeDim1*sizeof(DataType)));\n  sycl_device.memset(gpu_data, 1, sizeDim1*sizeof(DataType));\n\n  TensorMap<Tensor<DataType, 1, DataLayout,IndexType>> in(gpu_data, tensorDims);\n  TensorMap<Tensor<DataType, 1, DataLayout,IndexType>> out(gpu_data, tensorDims);\n  out.device(sycl_device) = in / in.constant(0);\n\n  sycl_device.synchronize();\n  VERIFY(!sycl_device.ok());\n  sycl_device.deallocate(gpu_data);\n}\n\ntemplate<typename DataType> void sycl_device_test_per_device(const cl::sycl::device& d){\n  std::cout << \"Running on \" << d.template get_info<cl::sycl::info::device::name>() << std::endl;\n  QueueInterface queueInterface(d);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_device_memory<DataType, RowMajor, int64_t>(sycl_device);\n  test_device_memory<DataType, ColMajor, int64_t>(sycl_device);\n  /// this test throw an exception. enable it if you want to see the exception\n  //test_device_exceptions<DataType, RowMajor>(sycl_device);\n  /// this test throw an exception. enable it if you want to see the exception\n  //test_device_exceptions<DataType, ColMajor>(sycl_device);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_device_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_device_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_dimension.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\n\nstatic void test_dynamic_size()\n{\n  Eigen::DSizes<int, 3> dimensions(2,3,7);\n\n  VERIFY_IS_EQUAL((int)Eigen::internal::array_get<0>(dimensions), 2);\n  VERIFY_IS_EQUAL((int)Eigen::internal::array_get<1>(dimensions), 3);\n  VERIFY_IS_EQUAL((int)Eigen::internal::array_get<2>(dimensions), 7);\n  VERIFY_IS_EQUAL((int)dimensions.TotalSize(), 2*3*7);\n  VERIFY_IS_EQUAL((int)dimensions[0], 2);\n  VERIFY_IS_EQUAL((int)dimensions[1], 3);\n  VERIFY_IS_EQUAL((int)dimensions[2], 7);\n}\n\nstatic void test_fixed_size()\n{\n  Eigen::Sizes<2,3,7> dimensions;\n\n  VERIFY_IS_EQUAL((int)Eigen::internal::array_get<0>(dimensions), 2);\n  VERIFY_IS_EQUAL((int)Eigen::internal::array_get<1>(dimensions), 3);\n  VERIFY_IS_EQUAL((int)Eigen::internal::array_get<2>(dimensions), 7);\n  VERIFY_IS_EQUAL((int)dimensions.TotalSize(), 2*3*7);\n}\n\nstatic void test_match()\n{\n  Eigen::DSizes<unsigned int, 3> dyn((unsigned int)2,(unsigned int)3,(unsigned int)7);\n  Eigen::Sizes<2,3,7> stat;\n  VERIFY_IS_EQUAL(Eigen::dimensions_match(dyn, stat), true);\n\n  Eigen::DSizes<int, 3> dyn1(2,3,7);\n  Eigen::DSizes<int, 2> dyn2(2,3);\n  VERIFY_IS_EQUAL(Eigen::dimensions_match(dyn1, dyn2), false);\n}\n\nstatic void test_rank_zero()\n{\n  Eigen::Sizes<> scalar;\n  VERIFY_IS_EQUAL((int)scalar.TotalSize(), 1);\n  VERIFY_IS_EQUAL((int)scalar.rank(), 0);\n  VERIFY_IS_EQUAL((int)internal::array_prod(scalar), 1);\n\n  Eigen::DSizes<ptrdiff_t, 0> dscalar;\n  VERIFY_IS_EQUAL((int)dscalar.TotalSize(), 1);\n  VERIFY_IS_EQUAL((int)dscalar.rank(), 0);\n}\n\nstatic void test_index_type_promotion() {\n  Eigen::DSizes<int, 3> src0(1, 2, 3);\n  Eigen::array<int, 3> src1;\n  src1[0] = 4;\n  src1[1] = 5;\n  src1[2] = 6;\n\n  Eigen::DSizes<long, 3> dst0(src0);\n  Eigen::DSizes<long, 3> dst1(src1);\n\n  VERIFY_IS_EQUAL(dst0[0], 1L);\n  VERIFY_IS_EQUAL(dst0[1], 2L);\n  VERIFY_IS_EQUAL(dst0[2], 3L);\n  VERIFY_IS_EQUAL(dst1[0], 4L);\n  VERIFY_IS_EQUAL(dst1[1], 5L);\n  VERIFY_IS_EQUAL(dst1[2], 6L);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_dimension)\n{\n  CALL_SUBTEST(test_dynamic_size());\n  CALL_SUBTEST(test_fixed_size());\n  CALL_SUBTEST(test_match());\n  CALL_SUBTEST(test_rank_zero());\n  CALL_SUBTEST(test_index_type_promotion());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_empty.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\n\nstatic void test_empty_tensor()\n{\n  Tensor<float, 2> source;\n  Tensor<float, 2> tgt1 = source;\n  Tensor<float, 2> tgt2(source);\n  Tensor<float, 2> tgt3;\n  tgt3 = tgt1;\n  tgt3 = tgt2;\n}\n\nstatic void test_empty_fixed_size_tensor()\n{\n  TensorFixedSize<float, Sizes<0> > source;\n  TensorFixedSize<float, Sizes<0> > tgt1 = source;\n  TensorFixedSize<float, Sizes<0> > tgt2(source);\n  TensorFixedSize<float, Sizes<0> > tgt3;\n  tgt3 = tgt1;\n  tgt3 = tgt2;\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_empty)\n{\n   CALL_SUBTEST(test_empty_tensor());\n   CALL_SUBTEST(test_empty_fixed_size_tensor());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_executor.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2018 Eugene Zhulenev <ezhulenev@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_USE_THREADS\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\nusing Eigen::ColMajor;\nusing Eigen::internal::TiledEvaluation;\n\n// A set of tests to verify that different TensorExecutor strategies yields the\n// same results for all the ops, supporting tiled evaluation.\n\n// Default assignment that does no use block evaluation or vectorization.\n// We assume that default coefficient evaluation is well tested and correct.\ntemplate <typename Dst, typename Expr>\nstatic void DefaultAssign(Dst& dst, Expr expr) {\n  using Assign = Eigen::TensorAssignOp<Dst, const Expr>;\n  using Executor =\n      Eigen::internal::TensorExecutor<const Assign, DefaultDevice,\n                                      /*Vectorizable=*/false,\n                                      /*Tiling=*/TiledEvaluation::Off>;\n\n  Executor::run(Assign(dst, expr), DefaultDevice());\n}\n\n// Assignment with specified device and tiling strategy.\ntemplate <bool Vectorizable, TiledEvaluation Tiling, typename Device,\n          typename Dst, typename Expr>\nstatic void DeviceAssign(Device& d, Dst& dst, Expr expr) {\n  using Assign = Eigen::TensorAssignOp<Dst, const Expr>;\n  using Executor = Eigen::internal::TensorExecutor<const Assign, Device,\n                                                   Vectorizable, Tiling>;\n\n  Executor::run(Assign(dst, expr), d);\n}\n\ntemplate <int NumDims>\nstatic array<Index, NumDims> RandomDims(int min_dim = 1, int max_dim = 20) {\n  array<Index, NumDims> dims;\n  for (int i = 0; i < NumDims; ++i) {\n    dims[i] = internal::random<int>(min_dim, max_dim);\n  }\n  return dims;\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n          TiledEvaluation Tiling, int Layout>\nstatic void test_execute_unary_expr(Device d)\n{\n  static constexpr int Options = 0 | Layout;\n\n  // Pick a large enough tensor size to bypass small tensor block evaluation\n  // optimization.\n  auto dims = RandomDims<NumDims>(50 / NumDims, 100 / NumDims);\n\n  Tensor<T, NumDims, Options, Index> src(dims);\n  Tensor<T, NumDims, Options, Index> dst(dims);\n\n  src.setRandom();\n  const auto expr = src.square();\n\n  using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;\n  using Executor =\n      internal::TensorExecutor<const Assign, Device, Vectorizable, Tiling>;\n\n  Executor::run(Assign(dst, expr), d);\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    T square = src.coeff(i) * src.coeff(i);\n    VERIFY_IS_EQUAL(square, dst.coeff(i));\n  }\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n          TiledEvaluation Tiling, int Layout>\nstatic void test_execute_binary_expr(Device d)\n{\n  static constexpr int Options = 0 | Layout;\n\n  // Pick a large enough tensor size to bypass small tensor block evaluation\n  // optimization.\n  auto dims = RandomDims<NumDims>(50 / NumDims, 100 / NumDims);\n\n  Tensor<T, NumDims, Options, Index> lhs(dims);\n  Tensor<T, NumDims, Options, Index> rhs(dims);\n  Tensor<T, NumDims, Options, Index> dst(dims);\n\n  lhs.setRandom();\n  rhs.setRandom();\n\n  const auto expr = lhs + rhs;\n\n  using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;\n  using Executor =\n      internal::TensorExecutor<const Assign, Device, Vectorizable, Tiling>;\n\n  Executor::run(Assign(dst, expr), d);\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    T sum = lhs.coeff(i) + rhs.coeff(i);\n    VERIFY_IS_EQUAL(sum, dst.coeff(i));\n  }\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n          TiledEvaluation Tiling, int Layout>\nstatic void test_execute_broadcasting(Device d)\n{\n  static constexpr int Options = 0 | Layout;\n\n  auto dims = RandomDims<NumDims>(1, 10);\n  Tensor<T, NumDims, Options, Index> src(dims);\n  src.setRandom();\n\n  const auto broadcasts = RandomDims<NumDims>(1, 7);\n  const auto expr = src.broadcast(broadcasts);\n\n  // We assume that broadcasting on a default device is tested and correct, so\n  // we can rely on it to verify correctness of tensor executor and tiling.\n  Tensor<T, NumDims, Options, Index> golden;\n  golden = expr;\n\n  // Now do the broadcasting using configured tensor executor.\n  Tensor<T, NumDims, Options, Index> dst(golden.dimensions());\n\n  using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;\n  using Executor =\n      internal::TensorExecutor<const Assign, Device, Vectorizable, Tiling>;\n\n  Executor::run(Assign(dst, expr), d);\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));\n  }\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n          TiledEvaluation Tiling, int Layout>\nstatic void test_execute_chipping_rvalue(Device d)\n{\n  auto dims = RandomDims<NumDims>(1, 10);\n  Tensor<T, NumDims, Layout, Index> src(dims);\n  src.setRandom();\n\n#define TEST_CHIPPING(CHIP_DIM)                                           \\\n  if (NumDims > (CHIP_DIM)) {                                             \\\n    const auto offset = internal::random<Index>(0, dims[(CHIP_DIM)] - 1); \\\n    const auto expr = src.template chip<(CHIP_DIM)>(offset);              \\\n                                                                          \\\n    Tensor<T, NumDims - 1, Layout, Index> golden;                         \\\n    golden = expr;                                                        \\\n                                                                          \\\n    Tensor<T, NumDims - 1, Layout, Index> dst(golden.dimensions());       \\\n                                                                          \\\n    using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;   \\\n    using Executor = internal::TensorExecutor<const Assign, Device,       \\\n                                              Vectorizable, Tiling>;      \\\n                                                                          \\\n    Executor::run(Assign(dst, expr), d);                                  \\\n                                                                          \\\n    for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {            \\\n      VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));                     \\\n    }                                                                     \\\n  }\n\n  TEST_CHIPPING(0)\n  TEST_CHIPPING(1)\n  TEST_CHIPPING(2)\n  TEST_CHIPPING(3)\n  TEST_CHIPPING(4)\n  TEST_CHIPPING(5)\n\n#undef TEST_CHIPPING\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n    TiledEvaluation Tiling, int Layout>\nstatic void test_execute_chipping_lvalue(Device d)\n{\n  auto dims = RandomDims<NumDims>(1, 10);\n\n#define TEST_CHIPPING(CHIP_DIM)                                             \\\n  if (NumDims > (CHIP_DIM)) {                                               \\\n    /* Generate random data that we'll assign to the chipped tensor dim. */ \\\n    array<Index, NumDims - 1> src_dims;                                     \\\n    for (int i = 0; i < NumDims - 1; ++i) {                                 \\\n      int dim = i < (CHIP_DIM) ? i : i + 1;                                 \\\n      src_dims[i] = dims[dim];                                              \\\n    }                                                                       \\\n                                                                            \\\n    Tensor<T, NumDims - 1, Layout, Index> src(src_dims);                    \\\n    src.setRandom();                                                        \\\n                                                                            \\\n    const auto offset = internal::random<Index>(0, dims[(CHIP_DIM)] - 1);   \\\n                                                                            \\\n    Tensor<T, NumDims, Layout, Index> random(dims);                         \\\n    random.setZero();                                                       \\\n                                                                            \\\n    Tensor<T, NumDims, Layout, Index> golden(dims);                         \\\n    golden = random;                                                        \\\n    golden.template chip<(CHIP_DIM)>(offset) = src;                         \\\n                                                                            \\\n    Tensor<T, NumDims, Layout, Index> dst(dims);                            \\\n    dst = random;                                                           \\\n    auto expr = dst.template chip<(CHIP_DIM)>(offset);                      \\\n                                                                            \\\n    using Assign = TensorAssignOp<decltype(expr), const decltype(src)>;     \\\n    using Executor = internal::TensorExecutor<const Assign, Device,         \\\n                                              Vectorizable, Tiling>;        \\\n                                                                            \\\n    Executor::run(Assign(expr, src), d);                                    \\\n                                                                            \\\n    for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {              \\\n      VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));                       \\\n    }                                                                       \\\n  }\n\n  TEST_CHIPPING(0)\n  TEST_CHIPPING(1)\n  TEST_CHIPPING(2)\n  TEST_CHIPPING(3)\n  TEST_CHIPPING(4)\n  TEST_CHIPPING(5)\n\n#undef TEST_CHIPPING\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n          TiledEvaluation Tiling, int Layout>\nstatic void test_execute_shuffle_rvalue(Device d)\n{\n  static constexpr int Options = 0 | Layout;\n\n  auto dims = RandomDims<NumDims>(1, 10);\n  Tensor<T, NumDims, Options, Index> src(dims);\n  src.setRandom();\n\n  DSizes<Index, NumDims> shuffle;\n  for (int i = 0; i < NumDims; ++i) shuffle[i] = i;\n\n  // Test all possible shuffle permutations.\n  do {\n    DSizes<Index, NumDims> shuffled_dims;\n    for (int i = 0; i < NumDims; ++i) {\n      shuffled_dims[i] = dims[shuffle[i]];\n    }\n\n    const auto expr = src.shuffle(shuffle);\n\n    // We assume that shuffling on a default device is tested and correct, so\n    // we can rely on it to verify correctness of tensor executor and tiling.\n    Tensor<T, NumDims, Options, Index> golden(shuffled_dims);\n    DefaultAssign(golden, expr);\n\n    // Now do the shuffling using configured tensor executor.\n    Tensor<T, NumDims, Options, Index> dst(shuffled_dims);\n    DeviceAssign<Vectorizable, Tiling>(d, dst, expr);\n\n    for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n      VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));\n    }\n\n  } while (std::next_permutation(&shuffle[0], &shuffle[0] + NumDims));\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n          TiledEvaluation Tiling, int Layout>\nstatic void test_execute_shuffle_lvalue(Device d)\n{\n  static constexpr int Options = 0 | Layout;\n\n  auto dims = RandomDims<NumDims>(5, 10);\n  Tensor<T, NumDims, Options, Index> src(dims);\n  src.setRandom();\n\n  DSizes<Index, NumDims> shuffle;\n  for (int i = 0; i < NumDims; ++i) shuffle[i] = i;\n\n  // Test all possible shuffle permutations.\n  do {\n    DSizes<Index, NumDims> shuffled_dims;\n    for (int i = 0; i < NumDims; ++i) shuffled_dims[shuffle[i]] = dims[i];\n\n    // We assume that shuffling on a default device is tested and correct, so\n    // we can rely on it to verify correctness of tensor executor and tiling.\n    Tensor<T, NumDims, Options, Index> golden(shuffled_dims);\n    auto golden_shuffle = golden.shuffle(shuffle);\n    DefaultAssign(golden_shuffle, src);\n\n    // Now do the shuffling using configured tensor executor.\n    Tensor<T, NumDims, Options, Index> dst(shuffled_dims);\n    auto dst_shuffle = dst.shuffle(shuffle);\n    DeviceAssign<Vectorizable, Tiling>(d, dst_shuffle, src);\n\n    for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n      VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));\n    }\n\n  } while (std::next_permutation(&shuffle[0], &shuffle[0] + NumDims));\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n    TiledEvaluation Tiling, int Layout>\nstatic void test_execute_reshape(Device d)\n{\n  static_assert(NumDims >= 2, \"NumDims must be greater or equal than 2\");\n\n  static constexpr int ReshapedDims = NumDims - 1;\n  static constexpr int Options = 0 | Layout;\n\n  auto dims = RandomDims<NumDims>(5, 10);\n  Tensor<T, NumDims, Options, Index> src(dims);\n  src.setRandom();\n\n  // Multiple 0th dimension and then shuffle.\n  std::vector<Index> shuffle;\n  for (int i = 0; i < ReshapedDims; ++i) shuffle.push_back(i);\n  std::shuffle(shuffle.begin(), shuffle.end(), std::mt19937());\n\n  DSizes<Index, ReshapedDims> reshaped_dims;\n  reshaped_dims[shuffle[0]] = dims[0] * dims[1];\n  for (int i = 1; i < ReshapedDims; ++i) reshaped_dims[shuffle[i]] = dims[i + 1];\n\n  Tensor<T, ReshapedDims, Options, Index> golden = src.reshape(reshaped_dims);\n\n  // Now reshape using configured tensor executor.\n  Tensor<T, ReshapedDims, Options, Index> dst(golden.dimensions());\n\n  auto expr = src.reshape(reshaped_dims);\n\n  using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;\n  using Executor =\n      internal::TensorExecutor<const Assign, Device, Vectorizable, Tiling>;\n\n  Executor::run(Assign(dst, expr), d);\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));\n  }\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n          TiledEvaluation Tiling, int Layout>\nstatic void test_execute_slice_rvalue(Device d)\n{\n  static_assert(NumDims >= 2, \"NumDims must be greater or equal than 2\");\n  static constexpr int Options = 0 | Layout;\n\n  auto dims = RandomDims<NumDims>(5, 10);\n  Tensor<T, NumDims, Options, Index> src(dims);\n  src.setRandom();\n\n  // Pick a random slice of src tensor.\n  auto slice_start = DSizes<Index, NumDims>(RandomDims<NumDims>());\n  auto slice_size = DSizes<Index, NumDims>(RandomDims<NumDims>());\n\n  // Make sure that slice start + size do not overflow tensor dims.\n  for (int i = 0; i < NumDims; ++i) {\n    slice_start[i] = numext::mini(dims[i] - 1, slice_start[i]);\n    slice_size[i] = numext::mini(slice_size[i], dims[i] - slice_start[i]);\n  }\n\n  Tensor<T, NumDims, Options, Index> golden =\n      src.slice(slice_start, slice_size);\n\n  // Now reshape using configured tensor executor.\n  Tensor<T, NumDims, Options, Index> dst(golden.dimensions());\n\n  auto expr = src.slice(slice_start, slice_size);\n\n  using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;\n  using Executor =\n      internal::TensorExecutor<const Assign, Device, Vectorizable, Tiling>;\n\n  Executor::run(Assign(dst, expr), d);\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));\n  }\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n    TiledEvaluation Tiling, int Layout>\nstatic void test_execute_slice_lvalue(Device d)\n{\n  static_assert(NumDims >= 2, \"NumDims must be greater or equal than 2\");\n  static constexpr int Options = 0 | Layout;\n\n  auto dims = RandomDims<NumDims>(5, 10);\n  Tensor<T, NumDims, Options, Index> src(dims);\n  src.setRandom();\n\n  // Pick a random slice of src tensor.\n  auto slice_start = DSizes<Index, NumDims>(RandomDims<NumDims>(1, 10));\n  auto slice_size = DSizes<Index, NumDims>(RandomDims<NumDims>(1, 10));\n\n  // Make sure that slice start + size do not overflow tensor dims.\n  for (int i = 0; i < NumDims; ++i) {\n    slice_start[i] = numext::mini(dims[i] - 1, slice_start[i]);\n    slice_size[i] = numext::mini(slice_size[i], dims[i] - slice_start[i]);\n  }\n\n  Tensor<T, NumDims, Options, Index> slice(slice_size);\n  slice.setRandom();\n\n  // Assign a slice using default executor.\n  Tensor<T, NumDims, Options, Index> golden = src;\n  golden.slice(slice_start, slice_size) = slice;\n\n  // And using configured execution strategy.\n  Tensor<T, NumDims, Options, Index> dst = src;\n  auto expr = dst.slice(slice_start, slice_size);\n\n  using Assign = TensorAssignOp<decltype(expr), const decltype(slice)>;\n  using Executor =\n      internal::TensorExecutor<const Assign, Device, Vectorizable, Tiling>;\n\n  Executor::run(Assign(expr, slice), d);\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));\n  }\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n    TiledEvaluation Tiling, int Layout>\nstatic void test_execute_broadcasting_of_forced_eval(Device d)\n{\n  static constexpr int Options = 0 | Layout;\n\n  auto dims = RandomDims<NumDims>(1, 10);\n  Tensor<T, NumDims, Options, Index> src(dims);\n  src.setRandom();\n\n  const auto broadcasts = RandomDims<NumDims>(1, 7);\n  const auto expr = src.square().eval().broadcast(broadcasts);\n\n  // We assume that broadcasting on a default device is tested and correct, so\n  // we can rely on it to verify correctness of tensor executor and tiling.\n  Tensor<T, NumDims, Options, Index> golden;\n  golden = expr;\n\n  // Now do the broadcasting using configured tensor executor.\n  Tensor<T, NumDims, Options, Index> dst(golden.dimensions());\n\n  using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;\n  using Executor =\n      internal::TensorExecutor<const Assign, Device, Vectorizable, Tiling>;\n\n  Executor::run(Assign(dst, expr), d);\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));\n  }\n}\n\ntemplate<typename T, int NumDims>\nstruct DummyGenerator {\n  EIGEN_DEVICE_FUNC EIGEN_ALWAYS_INLINE\n  T operator()(const array <Index, NumDims>& dims) const {\n    T result = static_cast<T>(0);\n    for (int i = 0; i < NumDims; ++i) {\n      result += static_cast<T>((i + 1) * dims[i]);\n    }\n    return result;\n  }\n};\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n    TiledEvaluation Tiling, int Layout>\nstatic void test_execute_generator_op(Device d)\n{\n  static constexpr int Options = 0 | Layout;\n\n  auto dims = RandomDims<NumDims>(20, 30);\n  Tensor<T, NumDims, Options, Index> src(dims);\n  src.setRandom();\n\n  const auto expr = src.generate(DummyGenerator<T, NumDims>());\n\n  // We assume that generator on a default device is tested and correct, so\n  // we can rely on it to verify correctness of tensor executor and tiling.\n  Tensor<T, NumDims, Options, Index> golden;\n  golden = expr;\n\n  // Now do the broadcasting using configured tensor executor.\n  Tensor<T, NumDims, Options, Index> dst(golden.dimensions());\n\n  using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;\n  using Executor =\n    internal::TensorExecutor<const Assign, Device, Vectorizable, Tiling>;\n\n  Executor::run(Assign(dst, expr), d);\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));\n  }\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n    TiledEvaluation Tiling, int Layout>\nstatic void test_execute_reverse_rvalue(Device d)\n{\n  static constexpr int Options = 0 | Layout;\n\n  auto dims = RandomDims<NumDims>(1, numext::pow(1000000.0, 1.0 / NumDims));\n  Tensor <T, NumDims, Options, Index> src(dims);\n  src.setRandom();\n\n  // Reverse half of the dimensions.\n  Eigen::array<bool, NumDims> reverse;\n  for (int i = 0; i < NumDims; ++i) reverse[i] = internal::random<bool>();\n\n  const auto expr = src.reverse(reverse);\n\n  // We assume that reversing on a default device is tested and correct, so\n  // we can rely on it to verify correctness of tensor executor and tiling.\n  Tensor <T, NumDims, Options, Index> golden;\n  golden = expr;\n\n  // Now do the reversing using configured tensor executor.\n  Tensor <T, NumDims, Options, Index> dst(golden.dimensions());\n\n  using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;\n  using Executor =\n    internal::TensorExecutor<const Assign, Device, Vectorizable, Tiling>;\n\n  Executor::run(Assign(dst, expr), d);\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    VERIFY_IS_EQUAL(dst.coeff(i), golden.coeff(i));\n  }\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n          TiledEvaluation Tiling, int Layout>\nstatic void test_async_execute_unary_expr(Device d)\n{\n  static constexpr int Options = 0 | Layout;\n\n  // Pick a large enough tensor size to bypass small tensor block evaluation\n  // optimization.\n  auto dims = RandomDims<NumDims>(50 / NumDims, 100 / NumDims);\n\n  Tensor<T, NumDims, Options, Index> src(dims);\n  Tensor<T, NumDims, Options, Index> dst(dims);\n\n  src.setRandom();\n  const auto expr = src.square();\n\n  Eigen::Barrier done(1);\n  auto on_done = [&done]() { done.Notify(); };\n\n  using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;\n  using DoneCallback = decltype(on_done);\n  using Executor = internal::TensorAsyncExecutor<const Assign, Device, DoneCallback,\n                                                 Vectorizable, Tiling>;\n\n  Executor::runAsync(Assign(dst, expr), d, on_done);\n  done.Wait();\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    T square = src.coeff(i) * src.coeff(i);\n    VERIFY_IS_EQUAL(square, dst.coeff(i));\n  }\n}\n\ntemplate <typename T, int NumDims, typename Device, bool Vectorizable,\n          TiledEvaluation Tiling, int Layout>\nstatic void test_async_execute_binary_expr(Device d)\n{\n  static constexpr int Options = 0 | Layout;\n\n  // Pick a large enough tensor size to bypass small tensor block evaluation\n  // optimization.\n  auto dims = RandomDims<NumDims>(50 / NumDims, 100 / NumDims);\n\n  Tensor<T, NumDims, Options, Index> lhs(dims);\n  Tensor<T, NumDims, Options, Index> rhs(dims);\n  Tensor<T, NumDims, Options, Index> dst(dims);\n\n  lhs.setRandom();\n  rhs.setRandom();\n\n  const auto expr = lhs + rhs;\n\n  Eigen::Barrier done(1);\n  auto on_done = [&done]() { done.Notify(); };\n\n  using Assign = TensorAssignOp<decltype(dst), const decltype(expr)>;\n  using DoneCallback = decltype(on_done);\n  using Executor = internal::TensorAsyncExecutor<const Assign, Device, DoneCallback,\n                                                 Vectorizable, Tiling>;\n\n  Executor::runAsync(Assign(dst, expr), d, on_done);\n  done.Wait();\n\n  for (Index i = 0; i < dst.dimensions().TotalSize(); ++i) {\n    T sum = lhs.coeff(i) + rhs.coeff(i);\n    VERIFY_IS_EQUAL(sum, dst.coeff(i));\n  }\n}\n\n#ifdef EIGEN_DONT_VECTORIZE\n#define VECTORIZABLE(VAL) !EIGEN_DONT_VECTORIZE && VAL\n#else\n#define VECTORIZABLE(VAL) VAL\n#endif\n\n#define CALL_SUBTEST_PART(PART) \\\n  CALL_SUBTEST_##PART\n\n#define CALL_SUBTEST_COMBINATIONS(PART, NAME, T, NUM_DIMS)                                                                                 \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, DefaultDevice,    false,               TiledEvaluation::Off,     ColMajor>(default_device))); \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, DefaultDevice,    false,               TiledEvaluation::On,  ColMajor>(default_device)));     \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, DefaultDevice,    VECTORIZABLE(true),  TiledEvaluation::Off,     ColMajor>(default_device))); \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, DefaultDevice,    VECTORIZABLE(true),  TiledEvaluation::On,  ColMajor>(default_device)));     \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, DefaultDevice,    false,               TiledEvaluation::Off,     RowMajor>(default_device))); \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, DefaultDevice,    false,               TiledEvaluation::On,  RowMajor>(default_device)));     \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, DefaultDevice,    VECTORIZABLE(true),  TiledEvaluation::Off,     RowMajor>(default_device))); \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, DefaultDevice,    VECTORIZABLE(true),  TiledEvaluation::On,  RowMajor>(default_device)));     \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, false,               TiledEvaluation::Off,     ColMajor>(tp_device)));      \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, false,               TiledEvaluation::On,  ColMajor>(tp_device)));          \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, VECTORIZABLE(true),  TiledEvaluation::Off,     ColMajor>(tp_device)));      \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, VECTORIZABLE(true),  TiledEvaluation::On,  ColMajor>(tp_device)));          \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, false,               TiledEvaluation::Off,     RowMajor>(tp_device)));      \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, false,               TiledEvaluation::On,  RowMajor>(tp_device)));          \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, VECTORIZABLE(true),  TiledEvaluation::Off,     RowMajor>(tp_device)));      \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, VECTORIZABLE(true),  TiledEvaluation::On,  RowMajor>(tp_device)))\n\n// NOTE: Currently only ThreadPoolDevice supports async expression evaluation.\n#define CALL_ASYNC_SUBTEST_COMBINATIONS(PART, NAME, T, NUM_DIMS)                                                                      \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, false,               TiledEvaluation::Off,     ColMajor>(tp_device))); \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, false,               TiledEvaluation::On,  ColMajor>(tp_device)));     \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, VECTORIZABLE(true),  TiledEvaluation::Off,     ColMajor>(tp_device))); \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, VECTORIZABLE(true),  TiledEvaluation::On,  ColMajor>(tp_device)));     \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, false,               TiledEvaluation::Off,     RowMajor>(tp_device))); \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, false,               TiledEvaluation::On,  RowMajor>(tp_device)));     \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, VECTORIZABLE(true),  TiledEvaluation::Off,     RowMajor>(tp_device))); \\\n  CALL_SUBTEST_PART(PART)((NAME<T, NUM_DIMS, ThreadPoolDevice, VECTORIZABLE(true),  TiledEvaluation::On,  RowMajor>(tp_device)))\n\nEIGEN_DECLARE_TEST(cxx11_tensor_executor) {\n  Eigen::DefaultDevice default_device;\n  // Default device is unused in ASYNC tests.\n  EIGEN_UNUSED_VARIABLE(default_device);\n\n  const auto num_threads = internal::random<int>(20, 24);\n  Eigen::ThreadPool tp(num_threads);\n  Eigen::ThreadPoolDevice tp_device(&tp, num_threads);\n\n  CALL_SUBTEST_COMBINATIONS(1, test_execute_unary_expr, float, 3);\n  CALL_SUBTEST_COMBINATIONS(1, test_execute_unary_expr, float, 4);\n  CALL_SUBTEST_COMBINATIONS(1, test_execute_unary_expr, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(2, test_execute_binary_expr, float, 3);\n  CALL_SUBTEST_COMBINATIONS(2, test_execute_binary_expr, float, 4);\n  CALL_SUBTEST_COMBINATIONS(2, test_execute_binary_expr, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(3, test_execute_broadcasting, float, 3);\n  CALL_SUBTEST_COMBINATIONS(3, test_execute_broadcasting, float, 4);\n  CALL_SUBTEST_COMBINATIONS(3, test_execute_broadcasting, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(4, test_execute_chipping_rvalue, float, 3);\n  CALL_SUBTEST_COMBINATIONS(4, test_execute_chipping_rvalue, float, 4);\n  CALL_SUBTEST_COMBINATIONS(4, test_execute_chipping_rvalue, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(5, test_execute_chipping_lvalue, float, 3);\n  CALL_SUBTEST_COMBINATIONS(5, test_execute_chipping_lvalue, float, 4);\n  CALL_SUBTEST_COMBINATIONS(5, test_execute_chipping_lvalue, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(6, test_execute_shuffle_rvalue, float, 3);\n  CALL_SUBTEST_COMBINATIONS(6, test_execute_shuffle_rvalue, float, 4);\n  CALL_SUBTEST_COMBINATIONS(6, test_execute_shuffle_rvalue, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(7, test_execute_shuffle_lvalue, float, 3);\n  CALL_SUBTEST_COMBINATIONS(7, test_execute_shuffle_lvalue, float, 4);\n  CALL_SUBTEST_COMBINATIONS(7, test_execute_shuffle_lvalue, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(9, test_execute_reshape, float, 2);\n  CALL_SUBTEST_COMBINATIONS(9, test_execute_reshape, float, 3);\n  CALL_SUBTEST_COMBINATIONS(9, test_execute_reshape, float, 4);\n  CALL_SUBTEST_COMBINATIONS(9, test_execute_reshape, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(10, test_execute_slice_rvalue, float, 2);\n  CALL_SUBTEST_COMBINATIONS(10, test_execute_slice_rvalue, float, 3);\n  CALL_SUBTEST_COMBINATIONS(10, test_execute_slice_rvalue, float, 4);\n  CALL_SUBTEST_COMBINATIONS(10, test_execute_slice_rvalue, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(11, test_execute_slice_lvalue, float, 2);\n  CALL_SUBTEST_COMBINATIONS(11, test_execute_slice_lvalue, float, 3);\n  CALL_SUBTEST_COMBINATIONS(11, test_execute_slice_lvalue, float, 4);\n  CALL_SUBTEST_COMBINATIONS(11, test_execute_slice_lvalue, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(12, test_execute_broadcasting_of_forced_eval, float, 2);\n  CALL_SUBTEST_COMBINATIONS(12, test_execute_broadcasting_of_forced_eval, float, 3);\n  CALL_SUBTEST_COMBINATIONS(12, test_execute_broadcasting_of_forced_eval, float, 4);\n  CALL_SUBTEST_COMBINATIONS(12, test_execute_broadcasting_of_forced_eval, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(13, test_execute_generator_op, float, 2);\n  CALL_SUBTEST_COMBINATIONS(13, test_execute_generator_op, float, 3);\n  CALL_SUBTEST_COMBINATIONS(13, test_execute_generator_op, float, 4);\n  CALL_SUBTEST_COMBINATIONS(13, test_execute_generator_op, float, 5);\n\n  CALL_SUBTEST_COMBINATIONS(14, test_execute_reverse_rvalue, float, 1);\n  CALL_SUBTEST_COMBINATIONS(14, test_execute_reverse_rvalue, float, 2);\n  CALL_SUBTEST_COMBINATIONS(14, test_execute_reverse_rvalue, float, 3);\n  CALL_SUBTEST_COMBINATIONS(14, test_execute_reverse_rvalue, float, 4);\n  CALL_SUBTEST_COMBINATIONS(14, test_execute_reverse_rvalue, float, 5);\n\n  CALL_ASYNC_SUBTEST_COMBINATIONS(15, test_async_execute_unary_expr, float, 3);\n  CALL_ASYNC_SUBTEST_COMBINATIONS(15, test_async_execute_unary_expr, float, 4);\n  CALL_ASYNC_SUBTEST_COMBINATIONS(15, test_async_execute_unary_expr, float, 5);\n\n  CALL_ASYNC_SUBTEST_COMBINATIONS(16, test_async_execute_binary_expr, float, 3);\n  CALL_ASYNC_SUBTEST_COMBINATIONS(16, test_async_execute_binary_expr, float, 4);\n  CALL_ASYNC_SUBTEST_COMBINATIONS(16, test_async_execute_binary_expr, float, 5);\n\n  // Force CMake to split this test.\n  // EIGEN_SUFFIXES;1;2;3;4;5;6;7;8;9;10;11;12;13;14;15;16\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_expr.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <numeric>\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\nstatic void test_1d()\n{\n  Tensor<float, 1> vec1(6);\n  Tensor<float, 1, RowMajor> vec2(6);\n\n  vec1(0) = 4.0;  vec2(0) = 0.0;\n  vec1(1) = 8.0;  vec2(1) = 1.0;\n  vec1(2) = 15.0; vec2(2) = 2.0;\n  vec1(3) = 16.0; vec2(3) = 3.0;\n  vec1(4) = 23.0; vec2(4) = 4.0;\n  vec1(5) = 42.0; vec2(5) = 5.0;\n\n  float data3[6];\n  TensorMap<Tensor<float, 1>> vec3(data3, 6);\n  vec3 = vec1.sqrt();\n  float data4[6];\n  TensorMap<Tensor<float, 1, RowMajor>> vec4(data4, 6);\n  vec4 = vec2.square();\n  float data5[6];\n  TensorMap<Tensor<float, 1, RowMajor>> vec5(data5, 6);\n  vec5 = vec2.cube();\n\n  VERIFY_IS_APPROX(vec3(0), sqrtf(4.0));\n  VERIFY_IS_APPROX(vec3(1), sqrtf(8.0));\n  VERIFY_IS_APPROX(vec3(2), sqrtf(15.0));\n  VERIFY_IS_APPROX(vec3(3), sqrtf(16.0));\n  VERIFY_IS_APPROX(vec3(4), sqrtf(23.0));\n  VERIFY_IS_APPROX(vec3(5), sqrtf(42.0));\n\n  VERIFY_IS_APPROX(vec4(0), 0.0f);\n  VERIFY_IS_APPROX(vec4(1), 1.0f);\n  VERIFY_IS_APPROX(vec4(2), 2.0f * 2.0f);\n  VERIFY_IS_APPROX(vec4(3), 3.0f * 3.0f);\n  VERIFY_IS_APPROX(vec4(4), 4.0f * 4.0f);\n  VERIFY_IS_APPROX(vec4(5), 5.0f * 5.0f);\n\n  VERIFY_IS_APPROX(vec5(0), 0.0f);\n  VERIFY_IS_APPROX(vec5(1), 1.0f);\n  VERIFY_IS_APPROX(vec5(2), 2.0f * 2.0f * 2.0f);\n  VERIFY_IS_APPROX(vec5(3), 3.0f * 3.0f * 3.0f);\n  VERIFY_IS_APPROX(vec5(4), 4.0f * 4.0f * 4.0f);\n  VERIFY_IS_APPROX(vec5(5), 5.0f * 5.0f * 5.0f);\n\n  vec3 = vec1 + vec2;\n  VERIFY_IS_APPROX(vec3(0), 4.0f + 0.0f);\n  VERIFY_IS_APPROX(vec3(1), 8.0f + 1.0f);\n  VERIFY_IS_APPROX(vec3(2), 15.0f + 2.0f);\n  VERIFY_IS_APPROX(vec3(3), 16.0f + 3.0f);\n  VERIFY_IS_APPROX(vec3(4), 23.0f + 4.0f);\n  VERIFY_IS_APPROX(vec3(5), 42.0f + 5.0f);\n}\n\nstatic void test_2d()\n{\n  float data1[6];\n  TensorMap<Tensor<float, 2>> mat1(data1, 2, 3);\n  float data2[6];\n  TensorMap<Tensor<float, 2, RowMajor>> mat2(data2, 2, 3);\n\n  mat1(0,0) = 0.0;\n  mat1(0,1) = 1.0;\n  mat1(0,2) = 2.0;\n  mat1(1,0) = 3.0;\n  mat1(1,1) = 4.0;\n  mat1(1,2) = 5.0;\n\n  mat2(0,0) = -0.0;\n  mat2(0,1) = -1.0;\n  mat2(0,2) = -2.0;\n  mat2(1,0) = -3.0;\n  mat2(1,1) = -4.0;\n  mat2(1,2) = -5.0;\n\n  Tensor<float, 2> mat3(2,3);\n  Tensor<float, 2, RowMajor> mat4(2,3);\n  mat3 = mat1.abs();\n  mat4 = mat2.abs();\n\n  VERIFY_IS_APPROX(mat3(0,0), 0.0f);\n  VERIFY_IS_APPROX(mat3(0,1), 1.0f);\n  VERIFY_IS_APPROX(mat3(0,2), 2.0f);\n  VERIFY_IS_APPROX(mat3(1,0), 3.0f);\n  VERIFY_IS_APPROX(mat3(1,1), 4.0f);\n  VERIFY_IS_APPROX(mat3(1,2), 5.0f);\n\n  VERIFY_IS_APPROX(mat4(0,0), 0.0f);\n  VERIFY_IS_APPROX(mat4(0,1), 1.0f);\n  VERIFY_IS_APPROX(mat4(0,2), 2.0f);\n  VERIFY_IS_APPROX(mat4(1,0), 3.0f);\n  VERIFY_IS_APPROX(mat4(1,1), 4.0f);\n  VERIFY_IS_APPROX(mat4(1,2), 5.0f);\n}\n\nstatic void test_3d()\n{\n  Tensor<float, 3> mat1(2,3,7);\n  Tensor<float, 3, RowMajor> mat2(2,3,7);\n\n  float val = 1.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        mat1(i,j,k) = val;\n        mat2(i,j,k) = val;\n        val += 1.0f;\n      }\n    }\n  }\n\n  Tensor<float, 3> mat3(2,3,7);\n  mat3 = mat1 + mat1;\n  Tensor<float, 3, RowMajor> mat4(2,3,7);\n  mat4 = mat2 * 3.14f;\n  Tensor<float, 3> mat5(2,3,7);\n  mat5 = mat1.inverse().log();\n  Tensor<float, 3, RowMajor> mat6(2,3,7);\n  mat6 = mat2.pow(0.5f) * 3.14f;\n  Tensor<float, 3> mat7(2,3,7);\n  mat7 = mat1.cwiseMax(mat5 * 2.0f).exp();\n  Tensor<float, 3, RowMajor> mat8(2,3,7);\n  mat8 = (-mat2).exp() * 3.14f;\n  Tensor<float, 3, RowMajor> mat9(2,3,7);\n  mat9 = mat2 + 3.14f;\n  Tensor<float, 3, RowMajor> mat10(2,3,7);\n  mat10 = mat2 - 3.14f;\n  Tensor<float, 3, RowMajor> mat11(2,3,7);\n  mat11 = mat2 / 3.14f;\n\n  val = 1.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(mat3(i,j,k), val + val);\n        VERIFY_IS_APPROX(mat4(i,j,k), val * 3.14f);\n        VERIFY_IS_APPROX(mat5(i,j,k), logf(1.0f/val));\n        VERIFY_IS_APPROX(mat6(i,j,k), sqrtf(val) * 3.14f);\n        VERIFY_IS_APPROX(mat7(i,j,k), expf((std::max)(val, mat5(i,j,k) * 2.0f)));\n        VERIFY_IS_APPROX(mat8(i,j,k), expf(-val) * 3.14f);\n        VERIFY_IS_APPROX(mat9(i,j,k), val + 3.14f);\n        VERIFY_IS_APPROX(mat10(i,j,k), val - 3.14f);\n        VERIFY_IS_APPROX(mat11(i,j,k), val / 3.14f);\n        val += 1.0f;\n      }\n    }\n  }\n}\n\nstatic void test_constants()\n{\n  Tensor<float, 3> mat1(2,3,7);\n  Tensor<float, 3> mat2(2,3,7);\n  Tensor<float, 3> mat3(2,3,7);\n\n  float val = 1.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        mat1(i,j,k) = val;\n        val += 1.0f;\n      }\n    }\n  }\n  mat2 = mat1.constant(3.14f);\n  mat3 = mat1.cwiseMax(7.3f).exp();\n\n  val = 1.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(mat2(i,j,k), 3.14f);\n        VERIFY_IS_APPROX(mat3(i,j,k), expf((std::max)(val, 7.3f)));\n        val += 1.0f;\n      }\n    }\n  }\n}\n\nstatic void test_boolean()\n{\n  const int kSize = 31;\n  Tensor<int, 1> vec(kSize);\n  std::iota(vec.data(), vec.data() + kSize, 0);\n\n  // Test ||.\n  Tensor<bool, 1> bool1 = vec < vec.constant(1) || vec > vec.constant(4);\n  for (int i = 0; i < kSize; ++i) {\n    bool expected = i < 1 || i > 4;\n    VERIFY_IS_EQUAL(bool1[i], expected);\n  }\n\n  // Test &&, including cast of operand vec.\n  Tensor<bool, 1> bool2 = vec.cast<bool>() && vec < vec.constant(4);\n  for (int i = 0; i < kSize; ++i) {\n    bool expected = bool(i) && i < 4;\n    VERIFY_IS_EQUAL(bool2[i], expected);\n  }\n\n  // Compilation tests:\n  // Test Tensor<bool> against results of cast or comparison; verifies that\n  // CoeffReturnType is set to match Op return type of bool for Unary and Binary\n  // Ops.\n  Tensor<bool, 1> bool3 = vec.cast<bool>() && bool2;\n  bool3 = vec < vec.constant(4) && bool2;\n}\n\nstatic void test_functors()\n{\n  Tensor<float, 3> mat1(2,3,7);\n  Tensor<float, 3> mat2(2,3,7);\n  Tensor<float, 3> mat3(2,3,7);\n\n  float val = 1.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        mat1(i,j,k) = val;\n        val += 1.0f;\n      }\n    }\n  }\n  mat2 = mat1.inverse().unaryExpr(&asinf);\n  mat3 = mat1.unaryExpr(&tanhf);\n\n  val = 1.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(mat2(i,j,k), asinf(1.0f / mat1(i,j,k)));\n        VERIFY_IS_APPROX(mat3(i,j,k), tanhf(mat1(i,j,k)));\n        val += 1.0f;\n      }\n    }\n  }\n}\n\nstatic void test_type_casting()\n{\n  Tensor<bool, 3> mat1(2,3,7);\n  Tensor<float, 3> mat2(2,3,7);\n  Tensor<double, 3> mat3(2,3,7);\n  mat1.setRandom();\n  mat2.setRandom();\n\n  mat3 = mat1.cast<double>();\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(mat3(i,j,k), mat1(i,j,k) ? 1.0 : 0.0);\n      }\n    }\n  }\n\n  mat3 = mat2.cast<double>();\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(mat3(i,j,k), static_cast<double>(mat2(i,j,k)));\n      }\n    }\n  }\n}\n\nstatic void test_select()\n{\n  Tensor<float, 3> selector(2,3,7);\n  Tensor<float, 3> mat1(2,3,7);\n  Tensor<float, 3> mat2(2,3,7);\n  Tensor<float, 3> result(2,3,7);\n\n  selector.setRandom();\n  mat1.setRandom();\n  mat2.setRandom();\n  result = (selector > selector.constant(0.5f)).select(mat1, mat2);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(result(i,j,k), (selector(i,j,k) > 0.5f) ? mat1(i,j,k) : mat2(i,j,k));\n      }\n    }\n  }\n}\n\ntemplate <typename Scalar>\nvoid test_minmax_nan_propagation_templ() {\n  for (int size = 1; size < 17; ++size) {\n    const Scalar kNaN = std::numeric_limits<Scalar>::quiet_NaN();\n    const Scalar kInf = std::numeric_limits<Scalar>::infinity();\n    const Scalar kZero(0);\n    Tensor<Scalar, 1> vec_all_nan(size);\n    Tensor<Scalar, 1> vec_one_nan(size);\n    Tensor<Scalar, 1> vec_zero(size);\n    vec_all_nan.setConstant(kNaN);\n    vec_zero.setZero();\n    vec_one_nan.setZero();\n    vec_one_nan(size/2) = kNaN;\n\n    auto verify_all_nan = [&](const Tensor<Scalar, 1>& v) {\n      for (int i = 0; i < size; ++i) {\n        VERIFY((numext::isnan)(v(i)));\n      }\n    };\n\n    auto verify_all_zero = [&](const Tensor<Scalar, 1>& v) {\n      for (int i = 0; i < size; ++i) {\n        VERIFY_IS_EQUAL(v(i), Scalar(0));\n      }\n    };\n\n    // Test NaN propagating max.\n    // max(nan, nan) = nan\n    // max(nan, 0) = nan\n    // max(0, nan) = nan\n    // max(0, 0) = 0\n    verify_all_nan(vec_all_nan.template cwiseMax<PropagateNaN>(kNaN));\n    verify_all_nan(vec_all_nan.template cwiseMax<PropagateNaN>(vec_all_nan));\n    verify_all_nan(vec_all_nan.template cwiseMax<PropagateNaN>(kZero));\n    verify_all_nan(vec_all_nan.template cwiseMax<PropagateNaN>(vec_zero));\n    verify_all_nan(vec_zero.template cwiseMax<PropagateNaN>(kNaN));\n    verify_all_nan(vec_zero.template cwiseMax<PropagateNaN>(vec_all_nan));\n    verify_all_zero(vec_zero.template cwiseMax<PropagateNaN>(kZero));\n    verify_all_zero(vec_zero.template cwiseMax<PropagateNaN>(vec_zero));\n\n    // Test number propagating max.\n    // max(nan, nan) = nan\n    // max(nan, 0) = 0\n    // max(0, nan) = 0\n    // max(0, 0) = 0\n    verify_all_nan(vec_all_nan.template cwiseMax<PropagateNumbers>(kNaN));\n    verify_all_nan(vec_all_nan.template cwiseMax<PropagateNumbers>(vec_all_nan));\n    verify_all_zero(vec_all_nan.template cwiseMax<PropagateNumbers>(kZero));\n    verify_all_zero(vec_all_nan.template cwiseMax<PropagateNumbers>(vec_zero));\n    verify_all_zero(vec_zero.template cwiseMax<PropagateNumbers>(kNaN));\n    verify_all_zero(vec_zero.template cwiseMax<PropagateNumbers>(vec_all_nan));\n    verify_all_zero(vec_zero.template cwiseMax<PropagateNumbers>(kZero));\n    verify_all_zero(vec_zero.template cwiseMax<PropagateNumbers>(vec_zero));\n\n    // Test NaN propagating min.\n    // min(nan, nan) = nan\n    // min(nan, 0) = nan\n    // min(0, nan) = nan\n    // min(0, 0) = 0\n    verify_all_nan(vec_all_nan.template cwiseMin<PropagateNaN>(kNaN));\n    verify_all_nan(vec_all_nan.template cwiseMin<PropagateNaN>(vec_all_nan));\n    verify_all_nan(vec_all_nan.template cwiseMin<PropagateNaN>(kZero));\n    verify_all_nan(vec_all_nan.template cwiseMin<PropagateNaN>(vec_zero));\n    verify_all_nan(vec_zero.template cwiseMin<PropagateNaN>(kNaN));\n    verify_all_nan(vec_zero.template cwiseMin<PropagateNaN>(vec_all_nan));\n    verify_all_zero(vec_zero.template cwiseMin<PropagateNaN>(kZero));\n    verify_all_zero(vec_zero.template cwiseMin<PropagateNaN>(vec_zero));\n\n    // Test number propagating min.\n    // min(nan, nan) = nan\n    // min(nan, 0) = 0\n    // min(0, nan) = 0\n    // min(0, 0) = 0\n    verify_all_nan(vec_all_nan.template cwiseMin<PropagateNumbers>(kNaN));\n    verify_all_nan(vec_all_nan.template cwiseMin<PropagateNumbers>(vec_all_nan));\n    verify_all_zero(vec_all_nan.template cwiseMin<PropagateNumbers>(kZero));\n    verify_all_zero(vec_all_nan.template cwiseMin<PropagateNumbers>(vec_zero));\n    verify_all_zero(vec_zero.template cwiseMin<PropagateNumbers>(kNaN));\n    verify_all_zero(vec_zero.template cwiseMin<PropagateNumbers>(vec_all_nan));\n    verify_all_zero(vec_zero.template cwiseMin<PropagateNumbers>(kZero));\n    verify_all_zero(vec_zero.template cwiseMin<PropagateNumbers>(vec_zero));\n\n    // Test min and max reduction\n    Tensor<Scalar, 0> val;\n    val = vec_zero.minimum();\n    VERIFY_IS_EQUAL(val(), kZero);\n    val = vec_zero.template minimum<PropagateNaN>();\n    VERIFY_IS_EQUAL(val(), kZero);\n    val = vec_zero.template minimum<PropagateNumbers>();\n    VERIFY_IS_EQUAL(val(), kZero);\n    val = vec_zero.maximum();\n    VERIFY_IS_EQUAL(val(), kZero);\n    val = vec_zero.template maximum<PropagateNaN>();\n    VERIFY_IS_EQUAL(val(), kZero);\n    val = vec_zero.template maximum<PropagateNumbers>();\n    VERIFY_IS_EQUAL(val(), kZero);\n\n    // Test NaN propagation for tensor of all NaNs.\n    val = vec_all_nan.template minimum<PropagateNaN>();\n    VERIFY((numext::isnan)(val()));\n    val = vec_all_nan.template minimum<PropagateNumbers>();\n    VERIFY_IS_EQUAL(val(), kInf);\n    val = vec_all_nan.template maximum<PropagateNaN>();\n    VERIFY((numext::isnan)(val()));\n    val = vec_all_nan.template maximum<PropagateNumbers>();\n    VERIFY_IS_EQUAL(val(), -kInf);\n\n    // Test NaN propagation for tensor with a single NaN.\n    val = vec_one_nan.template minimum<PropagateNaN>();\n    VERIFY((numext::isnan)(val()));\n    val = vec_one_nan.template minimum<PropagateNumbers>();\n    VERIFY_IS_EQUAL(val(), (size == 1 ? kInf : kZero));\n    val = vec_one_nan.template maximum<PropagateNaN>();\n    VERIFY((numext::isnan)(val()));\n    val = vec_one_nan.template maximum<PropagateNumbers>();\n    VERIFY_IS_EQUAL(val(), (size == 1 ? -kInf : kZero));\n  }\n}\n\nstatic void test_clip()\n{\n  Tensor<float, 1> vec(6);\n  vec(0) = 4.0;\n  vec(1) = 8.0;\n  vec(2) = 15.0;\n  vec(3) = 16.0;\n  vec(4) = 23.0;\n  vec(5) = 42.0;\n\n  float kMin = 20;\n  float kMax = 30;\n\n  Tensor<float, 1> vec_clipped(6);\n  vec_clipped = vec.clip(kMin, kMax);\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_EQUAL(vec_clipped(i), numext::mini(numext::maxi(vec(i), kMin), kMax));\n  }\n}\n\nstatic void test_minmax_nan_propagation()\n{\n  test_minmax_nan_propagation_templ<float>();\n  test_minmax_nan_propagation_templ<double>();\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_expr)\n{\n  CALL_SUBTEST(test_1d());\n  CALL_SUBTEST(test_2d());\n  CALL_SUBTEST(test_3d());\n  CALL_SUBTEST(test_constants());\n  CALL_SUBTEST(test_boolean());\n  CALL_SUBTEST(test_functors());\n  CALL_SUBTEST(test_type_casting());\n  CALL_SUBTEST(test_select());\n  CALL_SUBTEST(test_clip());\n\n// Nan propagation does currently not work like one would expect from std::max/std::min,\n// so we disable it for now\n#if !EIGEN_ARCH_ARM_OR_ARM64\n  CALL_SUBTEST(test_minmax_nan_propagation());\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_fft.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Jianwei Cui <thucjw@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate <int DataLayout>\nstatic void test_fft_2D_golden() {\n  Tensor<float, 2, DataLayout> input(2, 3);\n  input(0, 0) = 1;\n  input(0, 1) = 2;\n  input(0, 2) = 3;\n  input(1, 0) = 4;\n  input(1, 1) = 5;\n  input(1, 2) = 6;\n\n  array<ptrdiff_t, 2> fft;\n  fft[0] = 0;\n  fft[1] = 1;\n\n  Tensor<std::complex<float>, 2, DataLayout> output = input.template fft<Eigen::BothParts, Eigen::FFT_FORWARD>(fft);\n\n  std::complex<float> output_golden[6]; // in ColMajor order\n  output_golden[0] = std::complex<float>(21, 0);\n  output_golden[1] = std::complex<float>(-9, 0);\n  output_golden[2] = std::complex<float>(-3, 1.73205);\n  output_golden[3] = std::complex<float>( 0, 0);\n  output_golden[4] = std::complex<float>(-3, -1.73205);\n  output_golden[5] = std::complex<float>(0 ,0);\n\n  std::complex<float> c_offset = std::complex<float>(1.0, 1.0);\n\n  if (DataLayout == ColMajor) {\n    VERIFY_IS_APPROX(output(0) + c_offset, output_golden[0] + c_offset);\n    VERIFY_IS_APPROX(output(1) + c_offset, output_golden[1] + c_offset);\n    VERIFY_IS_APPROX(output(2) + c_offset, output_golden[2] + c_offset);\n    VERIFY_IS_APPROX(output(3) + c_offset, output_golden[3] + c_offset);\n    VERIFY_IS_APPROX(output(4) + c_offset, output_golden[4] + c_offset);\n    VERIFY_IS_APPROX(output(5) + c_offset, output_golden[5] + c_offset);\n  }\n  else {\n    VERIFY_IS_APPROX(output(0)+ c_offset, output_golden[0]+ c_offset);\n    VERIFY_IS_APPROX(output(1)+ c_offset, output_golden[2]+ c_offset);\n    VERIFY_IS_APPROX(output(2)+ c_offset, output_golden[4]+ c_offset);\n    VERIFY_IS_APPROX(output(3)+ c_offset, output_golden[1]+ c_offset);\n    VERIFY_IS_APPROX(output(4)+ c_offset, output_golden[3]+ c_offset);\n    VERIFY_IS_APPROX(output(5)+ c_offset, output_golden[5]+ c_offset);\n  }\n}\n\nstatic void test_fft_complex_input_golden() {\n  Tensor<std::complex<float>, 1, ColMajor> input(5);\n  input(0) = std::complex<float>(1, 1);\n  input(1) = std::complex<float>(2, 2);\n  input(2) = std::complex<float>(3, 3);\n  input(3) = std::complex<float>(4, 4);\n  input(4) = std::complex<float>(5, 5);\n\n  array<ptrdiff_t, 1> fft;\n  fft[0] = 0;\n\n  Tensor<std::complex<float>, 1, ColMajor> forward_output_both_parts = input.fft<BothParts, FFT_FORWARD>(fft);\n  Tensor<std::complex<float>, 1, ColMajor> reverse_output_both_parts = input.fft<BothParts, FFT_REVERSE>(fft);\n\n  Tensor<float, 1, ColMajor> forward_output_real_part = input.fft<RealPart, FFT_FORWARD>(fft);\n  Tensor<float, 1, ColMajor> reverse_output_real_part = input.fft<RealPart, FFT_REVERSE>(fft);\n\n  Tensor<float, 1, ColMajor> forward_output_imag_part = input.fft<ImagPart, FFT_FORWARD>(fft);\n  Tensor<float, 1, ColMajor> reverse_output_imag_part = input.fft<ImagPart, FFT_REVERSE>(fft);\n\n  VERIFY_IS_EQUAL(forward_output_both_parts.dimension(0), input.dimension(0));\n  VERIFY_IS_EQUAL(reverse_output_both_parts.dimension(0), input.dimension(0));\n\n  VERIFY_IS_EQUAL(forward_output_real_part.dimension(0), input.dimension(0));\n  VERIFY_IS_EQUAL(reverse_output_real_part.dimension(0), input.dimension(0));\n\n  VERIFY_IS_EQUAL(forward_output_imag_part.dimension(0), input.dimension(0));\n  VERIFY_IS_EQUAL(reverse_output_imag_part.dimension(0), input.dimension(0));\n\n  std::complex<float> forward_golden_result[5];\n  std::complex<float> reverse_golden_result[5];\n\n  forward_golden_result[0] = std::complex<float>(15.000000000000000,+15.000000000000000);\n  forward_golden_result[1] = std::complex<float>(-5.940954801177935, +0.940954801177934);\n  forward_golden_result[2] = std::complex<float>(-3.312299240582266, -1.687700759417735);\n  forward_golden_result[3] = std::complex<float>(-1.687700759417735, -3.312299240582266);\n  forward_golden_result[4] = std::complex<float>( 0.940954801177934, -5.940954801177935);\n\n  reverse_golden_result[0] = std::complex<float>( 3.000000000000000, + 3.000000000000000);\n  reverse_golden_result[1] = std::complex<float>( 0.188190960235587, - 1.188190960235587);\n  reverse_golden_result[2] = std::complex<float>(-0.337540151883547, - 0.662459848116453);\n  reverse_golden_result[3] = std::complex<float>(-0.662459848116453, - 0.337540151883547);\n  reverse_golden_result[4] = std::complex<float>(-1.188190960235587, + 0.188190960235587);\n\n  for(int i = 0; i < 5; ++i) {\n    VERIFY_IS_APPROX(forward_output_both_parts(i), forward_golden_result[i]);\n    VERIFY_IS_APPROX(forward_output_real_part(i), forward_golden_result[i].real());\n    VERIFY_IS_APPROX(forward_output_imag_part(i), forward_golden_result[i].imag());\n  }\n\n  for(int i = 0; i < 5; ++i) {\n    VERIFY_IS_APPROX(reverse_output_both_parts(i), reverse_golden_result[i]);\n    VERIFY_IS_APPROX(reverse_output_real_part(i), reverse_golden_result[i].real());\n    VERIFY_IS_APPROX(reverse_output_imag_part(i), reverse_golden_result[i].imag());\n  }\n}\n\nstatic void test_fft_real_input_golden() {\n  Tensor<float, 1, ColMajor> input(5);\n  input(0) = 1.0;\n  input(1) = 2.0;\n  input(2) = 3.0;\n  input(3) = 4.0;\n  input(4) = 5.0;\n\n  array<ptrdiff_t, 1> fft;\n  fft[0] = 0;\n\n  Tensor<std::complex<float>, 1, ColMajor> forward_output_both_parts = input.fft<BothParts, FFT_FORWARD>(fft);\n  Tensor<std::complex<float>, 1, ColMajor> reverse_output_both_parts = input.fft<BothParts, FFT_REVERSE>(fft);\n\n  Tensor<float, 1, ColMajor> forward_output_real_part = input.fft<RealPart, FFT_FORWARD>(fft);\n  Tensor<float, 1, ColMajor> reverse_output_real_part = input.fft<RealPart, FFT_REVERSE>(fft);\n\n  Tensor<float, 1, ColMajor> forward_output_imag_part = input.fft<ImagPart, FFT_FORWARD>(fft);\n  Tensor<float, 1, ColMajor> reverse_output_imag_part = input.fft<ImagPart, FFT_REVERSE>(fft);\n\n  VERIFY_IS_EQUAL(forward_output_both_parts.dimension(0), input.dimension(0));\n  VERIFY_IS_EQUAL(reverse_output_both_parts.dimension(0), input.dimension(0));\n\n  VERIFY_IS_EQUAL(forward_output_real_part.dimension(0), input.dimension(0));\n  VERIFY_IS_EQUAL(reverse_output_real_part.dimension(0), input.dimension(0));\n\n  VERIFY_IS_EQUAL(forward_output_imag_part.dimension(0), input.dimension(0));\n  VERIFY_IS_EQUAL(reverse_output_imag_part.dimension(0), input.dimension(0));\n\n  std::complex<float> forward_golden_result[5];\n  std::complex<float> reverse_golden_result[5];\n\n\n  forward_golden_result[0] = std::complex<float>(  15, 0);\n  forward_golden_result[1] = std::complex<float>(-2.5, +3.44095480117793);\n  forward_golden_result[2] = std::complex<float>(-2.5, +0.81229924058227);\n  forward_golden_result[3] = std::complex<float>(-2.5, -0.81229924058227);\n  forward_golden_result[4] = std::complex<float>(-2.5, -3.44095480117793);\n\n  reverse_golden_result[0] = std::complex<float>( 3.0, 0);\n  reverse_golden_result[1] = std::complex<float>(-0.5, -0.688190960235587);\n  reverse_golden_result[2] = std::complex<float>(-0.5, -0.162459848116453);\n  reverse_golden_result[3] = std::complex<float>(-0.5, +0.162459848116453);\n  reverse_golden_result[4] = std::complex<float>(-0.5, +0.688190960235587);\n\n  std::complex<float> c_offset(1.0, 1.0);\n  float r_offset = 1.0;\n\n  for(int i = 0; i < 5; ++i) {\n    VERIFY_IS_APPROX(forward_output_both_parts(i) + c_offset, forward_golden_result[i] + c_offset);\n    VERIFY_IS_APPROX(forward_output_real_part(i)  + r_offset, forward_golden_result[i].real() + r_offset);\n    VERIFY_IS_APPROX(forward_output_imag_part(i)  + r_offset, forward_golden_result[i].imag() + r_offset);\n  }\n\n  for(int i = 0; i < 5; ++i) {\n    VERIFY_IS_APPROX(reverse_output_both_parts(i) + c_offset, reverse_golden_result[i] + c_offset);\n    VERIFY_IS_APPROX(reverse_output_real_part(i)  + r_offset, reverse_golden_result[i].real() + r_offset);\n    VERIFY_IS_APPROX(reverse_output_imag_part(i)  + r_offset, reverse_golden_result[i].imag() + r_offset);\n  }\n}\n\n\ntemplate <int DataLayout, typename RealScalar, bool isComplexInput, int FFTResultType, int FFTDirection, int TensorRank>\nstatic void test_fft_real_input_energy() {\n\n  Eigen::DSizes<ptrdiff_t, TensorRank> dimensions;\n  ptrdiff_t total_size = 1;\n  for (int i = 0; i < TensorRank; ++i) {\n    dimensions[i] = rand() % 20 + 1;\n    total_size *= dimensions[i];\n  }\n  const DSizes<ptrdiff_t, TensorRank> arr = dimensions;\n\n  typedef typename internal::conditional<isComplexInput == true, std::complex<RealScalar>, RealScalar>::type InputScalar;\n\n  Tensor<InputScalar, TensorRank, DataLayout> input;\n  input.resize(arr);\n  input.setRandom();\n\n  array<ptrdiff_t, TensorRank> fft;\n  for (int i = 0; i < TensorRank; ++i) {\n    fft[i] = i;\n  }\n\n  typedef typename internal::conditional<FFTResultType == Eigen::BothParts, std::complex<RealScalar>, RealScalar>::type OutputScalar;\n  Tensor<OutputScalar, TensorRank, DataLayout> output;\n  output = input.template fft<FFTResultType, FFTDirection>(fft);\n\n  for (int i = 0; i < TensorRank; ++i) {\n    VERIFY_IS_EQUAL(output.dimension(i), input.dimension(i));\n  }\n\n  RealScalar energy_original = 0.0;\n  RealScalar energy_after_fft = 0.0;\n\n  for (int i = 0; i < total_size; ++i) {\n    energy_original += numext::abs2(input(i));\n  }\n\n  for (int i = 0; i < total_size; ++i) {\n    energy_after_fft += numext::abs2(output(i));\n  }\n\n  if(FFTDirection == FFT_FORWARD) {\n    VERIFY_IS_APPROX(energy_original, energy_after_fft / total_size);\n  }\n  else {\n    VERIFY_IS_APPROX(energy_original, energy_after_fft * total_size);\n  }\n}\n\ntemplate <typename RealScalar>\nstatic void test_fft_non_power_of_2_round_trip(int exponent) {\n  int n = (1 << exponent) + 1;\n\n  Eigen::DSizes<ptrdiff_t, 1> dimensions;\n  dimensions[0] = n;\n  const DSizes<ptrdiff_t, 1> arr = dimensions;\n  Tensor<RealScalar, 1, ColMajor, ptrdiff_t> input;\n\n  input.resize(arr);\n  input.setRandom();\n\n  array<int, 1> fft;\n  fft[0] = 0;\n\n  Tensor<std::complex<RealScalar>, 1, ColMajor> forward =\n      input.template fft<BothParts, FFT_FORWARD>(fft);\n\n  Tensor<RealScalar, 1, ColMajor, ptrdiff_t> output =\n      forward.template fft<RealPart, FFT_REVERSE>(fft);\n\n  for (int i = 0; i < n; ++i) {\n    RealScalar tol = test_precision<RealScalar>() *\n                     (std::abs(input[i]) + std::abs(output[i]) + 1);\n    VERIFY_IS_APPROX_OR_LESS_THAN(std::abs(input[i] - output[i]), tol);\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_fft) {\n    test_fft_complex_input_golden();\n    test_fft_real_input_golden();\n\n    test_fft_2D_golden<ColMajor>();\n    test_fft_2D_golden<RowMajor>();\n\n    test_fft_real_input_energy<ColMajor, float,  true,  Eigen::BothParts, FFT_FORWARD, 1>();\n    test_fft_real_input_energy<ColMajor, double, true,  Eigen::BothParts, FFT_FORWARD, 1>();\n    test_fft_real_input_energy<ColMajor, float,  false,  Eigen::BothParts, FFT_FORWARD, 1>();\n    test_fft_real_input_energy<ColMajor, double, false,  Eigen::BothParts, FFT_FORWARD, 1>();\n\n    test_fft_real_input_energy<ColMajor, float,  true,  Eigen::BothParts, FFT_FORWARD, 2>();\n    test_fft_real_input_energy<ColMajor, double, true,  Eigen::BothParts, FFT_FORWARD, 2>();\n    test_fft_real_input_energy<ColMajor, float,  false,  Eigen::BothParts, FFT_FORWARD, 2>();\n    test_fft_real_input_energy<ColMajor, double, false,  Eigen::BothParts, FFT_FORWARD, 2>();\n\n    test_fft_real_input_energy<ColMajor, float,  true,  Eigen::BothParts, FFT_FORWARD, 3>();\n    test_fft_real_input_energy<ColMajor, double, true,  Eigen::BothParts, FFT_FORWARD, 3>();\n    test_fft_real_input_energy<ColMajor, float,  false,  Eigen::BothParts, FFT_FORWARD, 3>();\n    test_fft_real_input_energy<ColMajor, double, false,  Eigen::BothParts, FFT_FORWARD, 3>();\n\n    test_fft_real_input_energy<ColMajor, float,  true,  Eigen::BothParts, FFT_FORWARD, 4>();\n    test_fft_real_input_energy<ColMajor, double, true,  Eigen::BothParts, FFT_FORWARD, 4>();\n    test_fft_real_input_energy<ColMajor, float,  false,  Eigen::BothParts, FFT_FORWARD, 4>();\n    test_fft_real_input_energy<ColMajor, double, false,  Eigen::BothParts, FFT_FORWARD, 4>();\n\n    test_fft_real_input_energy<RowMajor, float,  true,  Eigen::BothParts, FFT_FORWARD, 1>();\n    test_fft_real_input_energy<RowMajor, double, true,  Eigen::BothParts, FFT_FORWARD, 1>();\n    test_fft_real_input_energy<RowMajor, float,  false,  Eigen::BothParts, FFT_FORWARD, 1>();\n    test_fft_real_input_energy<RowMajor, double, false,  Eigen::BothParts, FFT_FORWARD, 1>();\n\n    test_fft_real_input_energy<RowMajor, float,  true,  Eigen::BothParts, FFT_FORWARD, 2>();\n    test_fft_real_input_energy<RowMajor, double, true,  Eigen::BothParts, FFT_FORWARD, 2>();\n    test_fft_real_input_energy<RowMajor, float,  false,  Eigen::BothParts, FFT_FORWARD, 2>();\n    test_fft_real_input_energy<RowMajor, double, false,  Eigen::BothParts, FFT_FORWARD, 2>();\n\n    test_fft_real_input_energy<RowMajor, float,  true,  Eigen::BothParts, FFT_FORWARD, 3>();\n    test_fft_real_input_energy<RowMajor, double, true,  Eigen::BothParts, FFT_FORWARD, 3>();\n    test_fft_real_input_energy<RowMajor, float,  false,  Eigen::BothParts, FFT_FORWARD, 3>();\n    test_fft_real_input_energy<RowMajor, double, false,  Eigen::BothParts, FFT_FORWARD, 3>();\n\n    test_fft_real_input_energy<RowMajor, float,  true,  Eigen::BothParts, FFT_FORWARD, 4>();\n    test_fft_real_input_energy<RowMajor, double, true,  Eigen::BothParts, FFT_FORWARD, 4>();\n    test_fft_real_input_energy<RowMajor, float,  false,  Eigen::BothParts, FFT_FORWARD, 4>();\n    test_fft_real_input_energy<RowMajor, double, false,  Eigen::BothParts, FFT_FORWARD, 4>();\n\n    test_fft_non_power_of_2_round_trip<float>(7);\n    test_fft_non_power_of_2_round_trip<double>(7);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_fixed_size.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\n\nstatic void test_0d()\n{\n  TensorFixedSize<float, Sizes<> > scalar1;\n  TensorFixedSize<float, Sizes<>, RowMajor> scalar2;\n  VERIFY_IS_EQUAL(scalar1.rank(), 0);\n  VERIFY_IS_EQUAL(scalar1.size(), 1);\n  VERIFY_IS_EQUAL(internal::array_prod(scalar1.dimensions()), 1);\n\n  scalar1() = 7.0;\n  scalar2() = 13.0;\n\n  // Test against shallow copy.\n  TensorFixedSize<float, Sizes<> > copy = scalar1;\n  VERIFY_IS_NOT_EQUAL(scalar1.data(), copy.data());\n  VERIFY_IS_APPROX(scalar1(), copy());\n  copy = scalar1;\n  VERIFY_IS_NOT_EQUAL(scalar1.data(), copy.data());\n  VERIFY_IS_APPROX(scalar1(), copy());\n\n  TensorFixedSize<float, Sizes<> > scalar3 = scalar1.sqrt();\n  TensorFixedSize<float, Sizes<>, RowMajor> scalar4 = scalar2.sqrt();\n  VERIFY_IS_EQUAL(scalar3.rank(), 0);\n  VERIFY_IS_APPROX(scalar3(), sqrtf(7.0));\n  VERIFY_IS_APPROX(scalar4(), sqrtf(13.0));\n\n  scalar3 = scalar1 + scalar2;\n  VERIFY_IS_APPROX(scalar3(), 7.0f + 13.0f);\n}\n\nstatic void test_1d()\n{\n  TensorFixedSize<float, Sizes<6> > vec1;\n  TensorFixedSize<float, Sizes<6>, RowMajor> vec2;\n\n  VERIFY_IS_EQUAL((vec1.size()), 6);\n  //  VERIFY_IS_EQUAL((vec1.dimensions()[0]), 6);\n  //  VERIFY_IS_EQUAL((vec1.dimension(0)), 6);\n\n  vec1(0) = 4.0;  vec2(0) = 0.0;\n  vec1(1) = 8.0;  vec2(1) = 1.0;\n  vec1(2) = 15.0; vec2(2) = 2.0;\n  vec1(3) = 16.0; vec2(3) = 3.0;\n  vec1(4) = 23.0; vec2(4) = 4.0;\n  vec1(5) = 42.0; vec2(5) = 5.0;\n\n  // Test against shallow copy.\n  TensorFixedSize<float, Sizes<6> > copy = vec1;\n  VERIFY_IS_NOT_EQUAL(vec1.data(), copy.data());\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_APPROX(vec1(i), copy(i));\n  }\n  copy = vec1;\n  VERIFY_IS_NOT_EQUAL(vec1.data(), copy.data());\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_APPROX(vec1(i), copy(i));\n  }\n\n  TensorFixedSize<float, Sizes<6> > vec3 = vec1.sqrt();\n  TensorFixedSize<float, Sizes<6>, RowMajor> vec4 = vec2.sqrt();\n\n  VERIFY_IS_EQUAL((vec3.size()), 6);\n  VERIFY_IS_EQUAL(vec3.rank(), 1);\n  //  VERIFY_IS_EQUAL((vec3.dimensions()[0]), 6);\n  //  VERIFY_IS_EQUAL((vec3.dimension(0)), 6);\n\n  VERIFY_IS_APPROX(vec3(0), sqrtf(4.0));\n  VERIFY_IS_APPROX(vec3(1), sqrtf(8.0));\n  VERIFY_IS_APPROX(vec3(2), sqrtf(15.0));\n  VERIFY_IS_APPROX(vec3(3), sqrtf(16.0));\n  VERIFY_IS_APPROX(vec3(4), sqrtf(23.0));\n  VERIFY_IS_APPROX(vec3(5), sqrtf(42.0));\n\n  VERIFY_IS_APPROX(vec4(0), sqrtf(0.0));\n  VERIFY_IS_APPROX(vec4(1), sqrtf(1.0));\n  VERIFY_IS_APPROX(vec4(2), sqrtf(2.0));\n  VERIFY_IS_APPROX(vec4(3), sqrtf(3.0));\n  VERIFY_IS_APPROX(vec4(4), sqrtf(4.0));\n  VERIFY_IS_APPROX(vec4(5), sqrtf(5.0));\n\n  vec3 = vec1 + vec2;\n  VERIFY_IS_APPROX(vec3(0), 4.0f + 0.0f);\n  VERIFY_IS_APPROX(vec3(1), 8.0f + 1.0f);\n  VERIFY_IS_APPROX(vec3(2), 15.0f + 2.0f);\n  VERIFY_IS_APPROX(vec3(3), 16.0f + 3.0f);\n  VERIFY_IS_APPROX(vec3(4), 23.0f + 4.0f);\n  VERIFY_IS_APPROX(vec3(5), 42.0f + 5.0f);\n}\n\nstatic void test_tensor_map()\n{\n  TensorFixedSize<float, Sizes<6> > vec1;\n  TensorFixedSize<float, Sizes<6>, RowMajor> vec2;\n\n  vec1(0) = 4.0;  vec2(0) = 0.0;\n  vec1(1) = 8.0;  vec2(1) = 1.0;\n  vec1(2) = 15.0; vec2(2) = 2.0;\n  vec1(3) = 16.0; vec2(3) = 3.0;\n  vec1(4) = 23.0; vec2(4) = 4.0;\n  vec1(5) = 42.0; vec2(5) = 5.0;\n\n  float data3[6];\n  TensorMap<TensorFixedSize<float, Sizes<6> > > vec3(data3, 6);\n  vec3 = vec1.sqrt() + vec2;\n\n  VERIFY_IS_APPROX(vec3(0), sqrtf(4.0));\n  VERIFY_IS_APPROX(vec3(1), sqrtf(8.0) + 1.0f);\n  VERIFY_IS_APPROX(vec3(2), sqrtf(15.0) + 2.0f);\n  VERIFY_IS_APPROX(vec3(3), sqrtf(16.0) + 3.0f);\n  VERIFY_IS_APPROX(vec3(4), sqrtf(23.0) + 4.0f);\n  VERIFY_IS_APPROX(vec3(5), sqrtf(42.0) + 5.0f);\n}\n\nstatic void test_2d()\n{\n  float data1[6];\n  TensorMap<TensorFixedSize<float, Sizes<2, 3> > > mat1(data1,2,3);\n  float data2[6];\n  TensorMap<TensorFixedSize<float, Sizes<2, 3>, RowMajor> > mat2(data2,2,3);\n\n  VERIFY_IS_EQUAL((mat1.size()), 2*3);\n  VERIFY_IS_EQUAL(mat1.rank(), 2);\n  //  VERIFY_IS_EQUAL((mat1.dimension(0)), 2);\n  //  VERIFY_IS_EQUAL((mat1.dimension(1)), 3);\n\n  mat1(0,0) = 0.0;\n  mat1(0,1) = 1.0;\n  mat1(0,2) = 2.0;\n  mat1(1,0) = 3.0;\n  mat1(1,1) = 4.0;\n  mat1(1,2) = 5.0;\n\n  mat2(0,0) = -0.0;\n  mat2(0,1) = -1.0;\n  mat2(0,2) = -2.0;\n  mat2(1,0) = -3.0;\n  mat2(1,1) = -4.0;\n  mat2(1,2) = -5.0;\n\n  TensorFixedSize<float, Sizes<2, 3> > mat3;\n  TensorFixedSize<float, Sizes<2, 3>, RowMajor> mat4;\n  mat3 = mat1.abs();\n  mat4 = mat2.abs();\n\n  VERIFY_IS_EQUAL((mat3.size()), 2*3);\n    //  VERIFY_IS_EQUAL((mat3.dimension(0)), 2);\n    //  VERIFY_IS_EQUAL((mat3.dimension(1)), 3);\n\n  VERIFY_IS_APPROX(mat3(0,0), 0.0f);\n  VERIFY_IS_APPROX(mat3(0,1), 1.0f);\n  VERIFY_IS_APPROX(mat3(0,2), 2.0f);\n  VERIFY_IS_APPROX(mat3(1,0), 3.0f);\n  VERIFY_IS_APPROX(mat3(1,1), 4.0f);\n  VERIFY_IS_APPROX(mat3(1,2), 5.0f);\n\n  VERIFY_IS_APPROX(mat4(0,0), 0.0f);\n  VERIFY_IS_APPROX(mat4(0,1), 1.0f);\n  VERIFY_IS_APPROX(mat4(0,2), 2.0f);\n  VERIFY_IS_APPROX(mat4(1,0), 3.0f);\n  VERIFY_IS_APPROX(mat4(1,1), 4.0f);\n  VERIFY_IS_APPROX(mat4(1,2), 5.0f);\n}\n\nstatic void test_3d()\n{\n  TensorFixedSize<float, Sizes<2, 3, 7> > mat1;\n  TensorFixedSize<float, Sizes<2, 3, 7>, RowMajor> mat2;\n\n  VERIFY_IS_EQUAL((mat1.size()), 2*3*7);\n  VERIFY_IS_EQUAL(mat1.rank(), 3);\n  //  VERIFY_IS_EQUAL((mat1.dimension(0)), 2);\n  //  VERIFY_IS_EQUAL((mat1.dimension(1)), 3);\n  //  VERIFY_IS_EQUAL((mat1.dimension(2)), 7);\n\n  float val = 0.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        mat1(i,j,k) = val;\n        mat2(i,j,k) = val;\n        val += 1.0f;\n      }\n    }\n  }\n\n  TensorFixedSize<float, Sizes<2, 3, 7> > mat3;\n  mat3 = mat1.sqrt();\n  TensorFixedSize<float, Sizes<2, 3, 7>, RowMajor> mat4;\n  mat4 = mat2.sqrt();\n\n  VERIFY_IS_EQUAL((mat3.size()), 2*3*7);\n  //  VERIFY_IS_EQUAL((mat3.dimension(0)), 2);\n  //  VERIFY_IS_EQUAL((mat3.dimension(1)), 3);\n  //  VERIFY_IS_EQUAL((mat3.dimension(2)), 7);\n\n\n  val = 0.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(mat3(i,j,k), sqrtf(val));\n        VERIFY_IS_APPROX(mat4(i,j,k), sqrtf(val));\n        val += 1.0f;\n      }\n    }\n  }\n}\n\n\nstatic void test_array()\n{\n  TensorFixedSize<float, Sizes<2, 3, 7> > mat1;\n  float val = 0.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        mat1(i,j,k) = val;\n        val += 1.0f;\n      }\n    }\n  }\n\n  TensorFixedSize<float, Sizes<2, 3, 7> > mat3;\n  mat3 = mat1.pow(3.5f);\n\n  val = 0.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(mat3(i,j,k), powf(val, 3.5f));\n        val += 1.0f;\n      }\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_fixed_size)\n{\n  CALL_SUBTEST(test_0d());\n  CALL_SUBTEST(test_1d());\n  CALL_SUBTEST(test_tensor_map());\n  CALL_SUBTEST(test_2d());\n  CALL_SUBTEST(test_3d());\n  CALL_SUBTEST(test_array());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_forced_eval.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/Core>\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::MatrixXf;\nusing Eigen::Tensor;\n\nstatic void test_simple()\n{\n  MatrixXf m1(3,3);\n  MatrixXf m2(3,3);\n  m1.setRandom();\n  m2.setRandom();\n\n  TensorMap<Tensor<float, 2> > mat1(m1.data(), 3,3);\n  TensorMap<Tensor<float, 2> > mat2(m2.data(), 3,3);\n\n  Tensor<float, 2> mat3(3,3);\n  mat3 = mat1;\n\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n  Eigen::array<DimPair, 1> dims;\n  dims[0] = DimPair(1, 0);\n\n  mat3 = mat3.contract(mat2, dims).eval();\n\n  VERIFY_IS_APPROX(mat3(0, 0), (m1*m2).eval()(0,0));\n  VERIFY_IS_APPROX(mat3(0, 1), (m1*m2).eval()(0,1));\n  VERIFY_IS_APPROX(mat3(0, 2), (m1*m2).eval()(0,2));\n  VERIFY_IS_APPROX(mat3(1, 0), (m1*m2).eval()(1,0));\n  VERIFY_IS_APPROX(mat3(1, 1), (m1*m2).eval()(1,1));\n  VERIFY_IS_APPROX(mat3(1, 2), (m1*m2).eval()(1,2));\n  VERIFY_IS_APPROX(mat3(2, 0), (m1*m2).eval()(2,0));\n  VERIFY_IS_APPROX(mat3(2, 1), (m1*m2).eval()(2,1));\n  VERIFY_IS_APPROX(mat3(2, 2), (m1*m2).eval()(2,2));\n}\n\n\nstatic void test_const()\n{\n  MatrixXf input(3,3);\n  input.setRandom();\n  MatrixXf output = input;\n  output.rowwise() -= input.colwise().maxCoeff();\n\n  Eigen::array<int, 1> depth_dim;\n  depth_dim[0] = 0;\n  Tensor<float, 2>::Dimensions dims2d;\n  dims2d[0] = 1;\n  dims2d[1] = 3;\n  Eigen::array<int, 2> bcast;\n  bcast[0] = 3;\n  bcast[1] = 1;\n  const TensorMap<const Tensor<float, 2> > input_tensor(input.data(), 3, 3);\n  Tensor<float, 2> output_tensor= (input_tensor - input_tensor.maximum(depth_dim).eval().reshape(dims2d).broadcast(bcast));\n\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_APPROX(output(i, j), output_tensor(i, j));\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_forced_eval)\n{\n  CALL_SUBTEST(test_simple());\n  CALL_SUBTEST(test_const());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_forced_eval_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_forced_eval_sycl(const Eigen::SyclDevice &sycl_device) {\n\n  IndexType sizeDim1 = 100;\n  IndexType sizeDim2 = 20;\n  IndexType sizeDim3 = 20;\n  Eigen::array<IndexType, 3> tensorRange = {{sizeDim1, sizeDim2, sizeDim3}};\n  Eigen::Tensor<DataType, 3, DataLayout, IndexType> in1(tensorRange);\n  Eigen::Tensor<DataType, 3, DataLayout, IndexType> in2(tensorRange);\n  Eigen::Tensor<DataType, 3, DataLayout, IndexType> out(tensorRange);\n\n  DataType * gpu_in1_data  = static_cast<DataType*>(sycl_device.allocate(in1.dimensions().TotalSize()*sizeof(DataType)));\n  DataType * gpu_in2_data  = static_cast<DataType*>(sycl_device.allocate(in2.dimensions().TotalSize()*sizeof(DataType)));\n  DataType * gpu_out_data =  static_cast<DataType*>(sycl_device.allocate(out.dimensions().TotalSize()*sizeof(DataType)));\n\n  in1 = in1.random() + in1.constant(static_cast<DataType>(10.0f));\n  in2 = in2.random() + in2.constant(static_cast<DataType>(10.0f));\n\n  // creating TensorMap from tensor\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType>> gpu_in1(gpu_in1_data, tensorRange);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType>> gpu_in2(gpu_in2_data, tensorRange);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 3, DataLayout, IndexType>> gpu_out(gpu_out_data, tensorRange);\n  sycl_device.memcpyHostToDevice(gpu_in1_data, in1.data(),(in1.dimensions().TotalSize())*sizeof(DataType));\n  sycl_device.memcpyHostToDevice(gpu_in2_data, in2.data(),(in2.dimensions().TotalSize())*sizeof(DataType));\n  /// c=(a+b)*b\n  gpu_out.device(sycl_device) =(gpu_in1 + gpu_in2).eval() * gpu_in2;\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data,(out.dimensions().TotalSize())*sizeof(DataType));\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        VERIFY_IS_APPROX(out(i, j, k),\n                         (in1(i, j, k) + in2(i, j, k)) * in2(i, j, k));\n      }\n    }\n  }\n  printf(\"(a+b)*b Test Passed\\n\");\n  sycl_device.deallocate(gpu_in1_data);\n  sycl_device.deallocate(gpu_in2_data);\n  sycl_device.deallocate(gpu_out_data);\n\n}\n\ntemplate <typename DataType, typename Dev_selector> void tensorForced_evalperDevice(Dev_selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_forced_eval_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_forced_eval_sycl<DataType, ColMajor, int64_t>(sycl_device);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_forced_eval_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(tensorForced_evalperDevice<float>(device));\n    CALL_SUBTEST(tensorForced_evalperDevice<half>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_generator.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nstruct Generator1D {\n  Generator1D() { }\n\n  float operator()(const array<Eigen::DenseIndex, 1>& coordinates) const {\n    return coordinates[0];\n  }\n};\n\ntemplate <int DataLayout>\nstatic void test_1D()\n{\n  Tensor<float, 1> vec(6);\n  Tensor<float, 1> result = vec.generate(Generator1D());\n\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_EQUAL(result(i), i);\n  }\n}\n\n\nstruct Generator2D {\n  Generator2D() { }\n\n  float operator()(const array<Eigen::DenseIndex, 2>& coordinates) const {\n    return 3 * coordinates[0] + 11 * coordinates[1];\n  }\n};\n\ntemplate <int DataLayout>\nstatic void test_2D()\n{\n  Tensor<float, 2> matrix(512, 512);\n  Tensor<float, 2> result = matrix.generate(Generator2D());\n\n  for (int i = 0; i < 512; ++i) {\n    for (int j = 0; j < 512; ++j) {\n      VERIFY_IS_EQUAL(result(i, j), 3*i + 11*j);\n    }\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_gaussian()\n{\n  int rows = 32;\n  int cols = 48;\n  array<float, 2> means;\n  means[0] = rows / 2.0f;\n  means[1] = cols / 2.0f;\n  array<float, 2> std_devs;\n  std_devs[0] = 3.14f;\n  std_devs[1] = 2.7f;\n  internal::GaussianGenerator<float, Eigen::DenseIndex, 2> gaussian_gen(means, std_devs);\n\n  Tensor<float, 2> matrix(rows, cols);\n  Tensor<float, 2> result = matrix.generate(gaussian_gen);\n\n  for (int i = 0; i < rows; ++i) {\n    for (int j = 0; j < cols; ++j) {\n      float g_rows = powf(rows/2.0f - i, 2) / (3.14f * 3.14f) * 0.5f;\n      float g_cols = powf(cols/2.0f - j, 2) / (2.7f * 2.7f) * 0.5f;\n      float gaussian = expf(-g_rows - g_cols);\n      VERIFY_IS_EQUAL(result(i, j), gaussian);\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_generator)\n{\n  CALL_SUBTEST(test_1D<ColMajor>());\n  CALL_SUBTEST(test_1D<RowMajor>());\n  CALL_SUBTEST(test_2D<ColMajor>());\n  CALL_SUBTEST(test_2D<RowMajor>());\n  CALL_SUBTEST(test_gaussian<ColMajor>());\n  CALL_SUBTEST(test_gaussian<RowMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_generator_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\nstatic const float error_threshold =1e-8f;\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nstruct Generator1D {\n  Generator1D() { }\n\n  float operator()(const array<Eigen::DenseIndex, 1>& coordinates) const {\n    return coordinates[0];\n  }\n};\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_1D_sycl(const Eigen::SyclDevice& sycl_device)\n{\n\n  IndexType sizeDim1 = 6;\n  array<IndexType, 1> tensorRange = {{sizeDim1}};\n  Tensor<DataType, 1, DataLayout,IndexType> vec(tensorRange);\n  Tensor<DataType, 1, DataLayout,IndexType> result(tensorRange);\n\n  const size_t tensorBuffSize =vec.size()*sizeof(DataType);\n  DataType* gpu_data_vec  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  DataType* gpu_data_result  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n\n  TensorMap<Tensor<DataType, 1, DataLayout,IndexType>> gpu_vec(gpu_data_vec, tensorRange);\n  TensorMap<Tensor<DataType, 1, DataLayout,IndexType>> gpu_result(gpu_data_result, tensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_vec, vec.data(), tensorBuffSize);\n  gpu_result.device(sycl_device)=gpu_vec.generate(Generator1D());\n  sycl_device.memcpyDeviceToHost(result.data(), gpu_data_result, tensorBuffSize);\n\n  for (IndexType i = 0; i < 6; ++i) {\n    VERIFY_IS_EQUAL(result(i), i);\n  }\n}\n\n\nstruct Generator2D {\n  Generator2D() { }\n\n  float operator()(const array<Eigen::DenseIndex, 2>& coordinates) const {\n    return 3 * coordinates[0] + 11 * coordinates[1];\n  }\n};\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_2D_sycl(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType sizeDim1 = 5;\n  IndexType sizeDim2 = 7;\n  array<IndexType, 2> tensorRange = {{sizeDim1, sizeDim2}};\n  Tensor<DataType, 2, DataLayout,IndexType> matrix(tensorRange);\n  Tensor<DataType, 2, DataLayout,IndexType> result(tensorRange);\n\n  const size_t tensorBuffSize =matrix.size()*sizeof(DataType);\n  DataType* gpu_data_matrix  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  DataType* gpu_data_result  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n\n  TensorMap<Tensor<DataType, 2, DataLayout,IndexType>> gpu_matrix(gpu_data_matrix, tensorRange);\n  TensorMap<Tensor<DataType, 2, DataLayout,IndexType>> gpu_result(gpu_data_result, tensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_matrix, matrix.data(), tensorBuffSize);\n  gpu_result.device(sycl_device)=gpu_matrix.generate(Generator2D());\n  sycl_device.memcpyDeviceToHost(result.data(), gpu_data_result, tensorBuffSize);\n\n  for (IndexType i = 0; i < 5; ++i) {\n    for (IndexType j = 0; j < 5; ++j) {\n      VERIFY_IS_EQUAL(result(i, j), 3*i + 11*j);\n    }\n  }\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_gaussian_sycl(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType rows = 32;\n  IndexType cols = 48;\n  array<DataType, 2> means;\n  means[0] = rows / 2.0f;\n  means[1] = cols / 2.0f;\n  array<DataType, 2> std_devs;\n  std_devs[0] = 3.14f;\n  std_devs[1] = 2.7f;\n  internal::GaussianGenerator<DataType, Eigen::DenseIndex, 2> gaussian_gen(means, std_devs);\n\n  array<IndexType, 2> tensorRange = {{rows, cols}};\n  Tensor<DataType, 2, DataLayout,IndexType> matrix(tensorRange);\n  Tensor<DataType, 2, DataLayout,IndexType> result(tensorRange);\n\n  const size_t tensorBuffSize =matrix.size()*sizeof(DataType);\n  DataType* gpu_data_matrix  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  DataType* gpu_data_result  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n\n  TensorMap<Tensor<DataType, 2, DataLayout,IndexType>> gpu_matrix(gpu_data_matrix, tensorRange);\n  TensorMap<Tensor<DataType, 2, DataLayout,IndexType>> gpu_result(gpu_data_result, tensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_matrix, matrix.data(), tensorBuffSize);\n  gpu_result.device(sycl_device)=gpu_matrix.generate(gaussian_gen);\n  sycl_device.memcpyDeviceToHost(result.data(), gpu_data_result, tensorBuffSize);\n\n  for (IndexType i = 0; i < rows; ++i) {\n    for (IndexType j = 0; j < cols; ++j) {\n      DataType g_rows = powf(rows/2.0f - i, 2) / (3.14f * 3.14f) * 0.5f;\n      DataType g_cols = powf(cols/2.0f - j, 2) / (2.7f * 2.7f) * 0.5f;\n      DataType gaussian = expf(-g_rows - g_cols);\n      Eigen::internal::isApprox(result(i, j), gaussian, error_threshold);\n    }\n  }\n}\n\ntemplate<typename DataType, typename dev_Selector> void sycl_generator_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_1D_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_1D_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_2D_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_2D_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_gaussian_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_gaussian_sycl<DataType, ColMajor, int64_t>(sycl_device);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_generator_sycl)\n{\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_generator_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_gpu.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\n#include <unsupported/Eigen/CXX11/src/Tensor/TensorGpuHipCudaDefines.h>\n\n#define EIGEN_GPU_TEST_C99_MATH  EIGEN_HAS_CXX11\n\nusing Eigen::Tensor;\n\nvoid test_gpu_nullary() {\n  Tensor<float, 1, 0, int> in1(2);\n  Tensor<float, 1, 0, int> in2(2);\n  in1.setRandom();\n  in2.setRandom();\n\n  std::size_t tensor_bytes = in1.size() * sizeof(float);\n\n  float* d_in1;\n  float* d_in2;\n  gpuMalloc((void**)(&d_in1), tensor_bytes);\n  gpuMalloc((void**)(&d_in2), tensor_bytes);\n  gpuMemcpy(d_in1, in1.data(), tensor_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_in2, in2.data(), tensor_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 1, 0, int>, Eigen::Aligned> gpu_in1(\n      d_in1, 2);\n  Eigen::TensorMap<Eigen::Tensor<float, 1, 0, int>, Eigen::Aligned> gpu_in2(\n      d_in2, 2);\n\n  gpu_in1.device(gpu_device) = gpu_in1.constant(3.14f);\n  gpu_in2.device(gpu_device) = gpu_in2.random();\n\n  Tensor<float, 1, 0, int> new1(2);\n  Tensor<float, 1, 0, int> new2(2);\n\n  assert(gpuMemcpyAsync(new1.data(), d_in1, tensor_bytes, gpuMemcpyDeviceToHost,\n                         gpu_device.stream()) == gpuSuccess);\n  assert(gpuMemcpyAsync(new2.data(), d_in2, tensor_bytes, gpuMemcpyDeviceToHost,\n                         gpu_device.stream()) == gpuSuccess);\n\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 2; ++i) {\n    VERIFY_IS_APPROX(new1(i), 3.14f);\n    VERIFY_IS_NOT_EQUAL(new2(i), in2(i));\n  }\n\n  gpuFree(d_in1);\n  gpuFree(d_in2);\n}\n\nvoid test_gpu_elementwise_small() {\n  Tensor<float, 1> in1(Eigen::array<Eigen::DenseIndex, 1>(2));\n  Tensor<float, 1> in2(Eigen::array<Eigen::DenseIndex, 1>(2));\n  Tensor<float, 1> out(Eigen::array<Eigen::DenseIndex, 1>(2));\n  in1.setRandom();\n  in2.setRandom();\n\n  std::size_t in1_bytes = in1.size() * sizeof(float);\n  std::size_t in2_bytes = in2.size() * sizeof(float);\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_in1;\n  float* d_in2;\n  float* d_out;\n  gpuMalloc((void**)(&d_in1), in1_bytes);\n  gpuMalloc((void**)(&d_in2), in2_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  gpuMemcpy(d_in1, in1.data(), in1_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_in2, in2.data(), in2_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_in1(\n      d_in1, Eigen::array<Eigen::DenseIndex, 1>(2));\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_in2(\n      d_in2, Eigen::array<Eigen::DenseIndex, 1>(2));\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_out(\n      d_out, Eigen::array<Eigen::DenseIndex, 1>(2));\n\n  gpu_out.device(gpu_device) = gpu_in1 + gpu_in2;\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost,\n                         gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 2; ++i) {\n    VERIFY_IS_APPROX(\n        out(Eigen::array<Eigen::DenseIndex, 1>(i)),\n        in1(Eigen::array<Eigen::DenseIndex, 1>(i)) + in2(Eigen::array<Eigen::DenseIndex, 1>(i)));\n  }\n\n  gpuFree(d_in1);\n  gpuFree(d_in2);\n  gpuFree(d_out);\n}\n\nvoid test_gpu_elementwise()\n{\n  Tensor<float, 3> in1(Eigen::array<Eigen::DenseIndex, 3>(72,53,97));\n  Tensor<float, 3> in2(Eigen::array<Eigen::DenseIndex, 3>(72,53,97));\n  Tensor<float, 3> in3(Eigen::array<Eigen::DenseIndex, 3>(72,53,97));\n  Tensor<float, 3> out(Eigen::array<Eigen::DenseIndex, 3>(72,53,97));\n  in1.setRandom();\n  in2.setRandom();\n  in3.setRandom();\n\n  std::size_t in1_bytes = in1.size() * sizeof(float);\n  std::size_t in2_bytes = in2.size() * sizeof(float);\n  std::size_t in3_bytes = in3.size() * sizeof(float);\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_in1;\n  float* d_in2;\n  float* d_in3;\n  float* d_out;\n  gpuMalloc((void**)(&d_in1), in1_bytes);\n  gpuMalloc((void**)(&d_in2), in2_bytes);\n  gpuMalloc((void**)(&d_in3), in3_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  gpuMemcpy(d_in1, in1.data(), in1_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_in2, in2.data(), in2_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_in3, in3.data(), in3_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 3> > gpu_in1(d_in1, Eigen::array<Eigen::DenseIndex, 3>(72,53,97));\n  Eigen::TensorMap<Eigen::Tensor<float, 3> > gpu_in2(d_in2, Eigen::array<Eigen::DenseIndex, 3>(72,53,97));\n  Eigen::TensorMap<Eigen::Tensor<float, 3> > gpu_in3(d_in3, Eigen::array<Eigen::DenseIndex, 3>(72,53,97));\n  Eigen::TensorMap<Eigen::Tensor<float, 3> > gpu_out(d_out, Eigen::array<Eigen::DenseIndex, 3>(72,53,97));\n\n  gpu_out.device(gpu_device) = gpu_in1 + gpu_in2 * gpu_in3;\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 72; ++i) {\n    for (int j = 0; j < 53; ++j) {\n      for (int k = 0; k < 97; ++k) {\n        VERIFY_IS_APPROX(out(Eigen::array<Eigen::DenseIndex, 3>(i,j,k)), in1(Eigen::array<Eigen::DenseIndex, 3>(i,j,k)) + in2(Eigen::array<Eigen::DenseIndex, 3>(i,j,k)) * in3(Eigen::array<Eigen::DenseIndex, 3>(i,j,k)));\n      }\n    }\n  }\n\n  gpuFree(d_in1);\n  gpuFree(d_in2);\n  gpuFree(d_in3);\n  gpuFree(d_out);\n}\n\nvoid test_gpu_props() {\n  Tensor<float, 1> in1(200);\n  Tensor<bool, 1> out(200);\n  in1.setRandom();\n\n  std::size_t in1_bytes = in1.size() * sizeof(float);\n  std::size_t out_bytes = out.size() * sizeof(bool);\n\n  float* d_in1;\n  bool* d_out;\n  gpuMalloc((void**)(&d_in1), in1_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  gpuMemcpy(d_in1, in1.data(), in1_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_in1(\n      d_in1, 200);\n  Eigen::TensorMap<Eigen::Tensor<bool, 1>, Eigen::Aligned> gpu_out(\n      d_out, 200);\n\n  gpu_out.device(gpu_device) = (gpu_in1.isnan)();\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost,\n                         gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 200; ++i) {\n    VERIFY_IS_EQUAL(out(i), (std::isnan)(in1(i)));\n  }\n\n  gpuFree(d_in1);\n  gpuFree(d_out);\n}\n\nvoid test_gpu_reduction()\n{\n  Tensor<float, 4> in1(72,53,97,113);\n  Tensor<float, 2> out(72,97);\n  in1.setRandom();\n\n  std::size_t in1_bytes = in1.size() * sizeof(float);\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_in1;\n  float* d_out;\n  gpuMalloc((void**)(&d_in1), in1_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  gpuMemcpy(d_in1, in1.data(), in1_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 4> > gpu_in1(d_in1, 72,53,97,113);\n  Eigen::TensorMap<Eigen::Tensor<float, 2> > gpu_out(d_out, 72,97);\n\n  array<Eigen::DenseIndex, 2> reduction_axis;\n  reduction_axis[0] = 1;\n  reduction_axis[1] = 3;\n\n  gpu_out.device(gpu_device) = gpu_in1.maximum(reduction_axis);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 72; ++i) {\n    for (int j = 0; j < 97; ++j) {\n      float expected = 0;\n      for (int k = 0; k < 53; ++k) {\n        for (int l = 0; l < 113; ++l) {\n          expected =\n              std::max<float>(expected, in1(i, k, j, l));\n        }\n      }\n      VERIFY_IS_APPROX(out(i,j), expected);\n    }\n  }\n\n  gpuFree(d_in1);\n  gpuFree(d_out);\n}\n\ntemplate<int DataLayout>\nvoid test_gpu_contraction()\n{\n  // with these dimensions, the output has 300 * 140 elements, which is\n  // more than 30 * 1024, which is the number of threads in blocks on\n  // a 15 SM GK110 GPU\n  Tensor<float, 4, DataLayout> t_left(6, 50, 3, 31);\n  Tensor<float, 5, DataLayout> t_right(Eigen::array<Eigen::DenseIndex, 5>(3, 31, 7, 20, 1));\n  Tensor<float, 5, DataLayout> t_result(Eigen::array<Eigen::DenseIndex, 5>(6, 50, 7, 20, 1));\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  std::size_t t_left_bytes = t_left.size()  * sizeof(float);\n  std::size_t t_right_bytes = t_right.size() * sizeof(float);\n  std::size_t t_result_bytes = t_result.size() * sizeof(float);\n\n  float* d_t_left;\n  float* d_t_right;\n  float* d_t_result;\n\n  gpuMalloc((void**)(&d_t_left), t_left_bytes);\n  gpuMalloc((void**)(&d_t_right), t_right_bytes);\n  gpuMalloc((void**)(&d_t_result), t_result_bytes);\n\n  gpuMemcpy(d_t_left, t_left.data(), t_left_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_t_right, t_right.data(), t_right_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 4, DataLayout> > gpu_t_left(d_t_left, 6, 50, 3, 31);\n  Eigen::TensorMap<Eigen::Tensor<float, 5, DataLayout> > gpu_t_right(d_t_right, 3, 31, 7, 20, 1);\n  Eigen::TensorMap<Eigen::Tensor<float, 5, DataLayout> > gpu_t_result(d_t_result, 6, 50, 7, 20, 1);\n\n  typedef Eigen::Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> > MapXf;\n  MapXf m_left(t_left.data(), 300, 93);\n  MapXf m_right(t_right.data(), 93, 140);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result(300, 140);\n\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n  Eigen::array<DimPair, 2> dims;\n  dims[0] = DimPair(2, 0);\n  dims[1] = DimPair(3, 1);\n\n  m_result = m_left * m_right;\n  gpu_t_result.device(gpu_device) = gpu_t_left.contract(gpu_t_right, dims);\n\n  gpuMemcpy(t_result.data(), d_t_result, t_result_bytes, gpuMemcpyDeviceToHost);\n\n  for (DenseIndex i = 0; i < t_result.size(); i++) {\n    if (fabs(t_result.data()[i] - m_result.data()[i]) >= 1e-4f) {\n      std::cout << \"mismatch detected at index \" << i << \": \" << t_result.data()[i] << \" vs \" <<  m_result.data()[i] << std::endl;\n      assert(false);\n    }\n  }\n\n  gpuFree(d_t_left);\n  gpuFree(d_t_right);\n  gpuFree(d_t_result);\n}\n\ntemplate<int DataLayout>\nvoid test_gpu_convolution_1d()\n{\n  Tensor<float, 4, DataLayout> input(74,37,11,137);\n  Tensor<float, 1, DataLayout> kernel(4);\n  Tensor<float, 4, DataLayout> out(74,34,11,137);\n  input = input.constant(10.0f) + input.random();\n  kernel = kernel.constant(7.0f) + kernel.random();\n\n  std::size_t input_bytes = input.size() * sizeof(float);\n  std::size_t kernel_bytes = kernel.size() * sizeof(float);\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_input;\n  float* d_kernel;\n  float* d_out;\n  gpuMalloc((void**)(&d_input), input_bytes);\n  gpuMalloc((void**)(&d_kernel), kernel_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  gpuMemcpy(d_input, input.data(), input_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_kernel, kernel.data(), kernel_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 4, DataLayout> > gpu_input(d_input, 74,37,11,137);\n  Eigen::TensorMap<Eigen::Tensor<float, 1, DataLayout> > gpu_kernel(d_kernel, 4);\n  Eigen::TensorMap<Eigen::Tensor<float, 4, DataLayout> > gpu_out(d_out, 74,34,11,137);\n\n  Eigen::array<Eigen::DenseIndex, 1> dims(1);\n  gpu_out.device(gpu_device) = gpu_input.convolve(gpu_kernel, dims);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 74; ++i) {\n    for (int j = 0; j < 34; ++j) {\n      for (int k = 0; k < 11; ++k) {\n        for (int l = 0; l < 137; ++l) {\n          const float result = out(i,j,k,l);\n          const float expected = input(i,j+0,k,l) * kernel(0) + input(i,j+1,k,l) * kernel(1) +\n                                 input(i,j+2,k,l) * kernel(2) + input(i,j+3,k,l) * kernel(3);\n          VERIFY_IS_APPROX(result, expected);\n        }\n      }\n    }\n  }\n\n  gpuFree(d_input);\n  gpuFree(d_kernel);\n  gpuFree(d_out);\n}\n\nvoid test_gpu_convolution_inner_dim_col_major_1d()\n{\n  Tensor<float, 4, ColMajor> input(74,9,11,7);\n  Tensor<float, 1, ColMajor> kernel(4);\n  Tensor<float, 4, ColMajor> out(71,9,11,7);\n  input = input.constant(10.0f) + input.random();\n  kernel = kernel.constant(7.0f) + kernel.random();\n\n  std::size_t input_bytes = input.size() * sizeof(float);\n  std::size_t kernel_bytes = kernel.size() * sizeof(float);\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_input;\n  float* d_kernel;\n  float* d_out;\n  gpuMalloc((void**)(&d_input), input_bytes);\n  gpuMalloc((void**)(&d_kernel), kernel_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  gpuMemcpy(d_input, input.data(), input_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_kernel, kernel.data(), kernel_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 4, ColMajor> > gpu_input(d_input,74,9,11,7);\n  Eigen::TensorMap<Eigen::Tensor<float, 1, ColMajor> > gpu_kernel(d_kernel,4);\n  Eigen::TensorMap<Eigen::Tensor<float, 4, ColMajor> > gpu_out(d_out,71,9,11,7);\n\n  Eigen::array<Eigen::DenseIndex, 1> dims(0);\n  gpu_out.device(gpu_device) = gpu_input.convolve(gpu_kernel, dims);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 71; ++i) {\n    for (int j = 0; j < 9; ++j) {\n      for (int k = 0; k < 11; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          const float result = out(i,j,k,l);\n          const float expected = input(i+0,j,k,l) * kernel(0) + input(i+1,j,k,l) * kernel(1) +\n                                 input(i+2,j,k,l) * kernel(2) + input(i+3,j,k,l) * kernel(3);\n          VERIFY_IS_APPROX(result, expected);\n        }\n      }\n    }\n  }\n\n  gpuFree(d_input);\n  gpuFree(d_kernel);\n  gpuFree(d_out);\n}\n\nvoid test_gpu_convolution_inner_dim_row_major_1d()\n{\n  Tensor<float, 4, RowMajor> input(7,9,11,74);\n  Tensor<float, 1, RowMajor> kernel(4);\n  Tensor<float, 4, RowMajor> out(7,9,11,71);\n  input = input.constant(10.0f) + input.random();\n  kernel = kernel.constant(7.0f) + kernel.random();\n\n  std::size_t input_bytes = input.size() * sizeof(float);\n  std::size_t kernel_bytes = kernel.size() * sizeof(float);\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_input;\n  float* d_kernel;\n  float* d_out;\n  gpuMalloc((void**)(&d_input), input_bytes);\n  gpuMalloc((void**)(&d_kernel), kernel_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  gpuMemcpy(d_input, input.data(), input_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_kernel, kernel.data(), kernel_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 4, RowMajor> > gpu_input(d_input, 7,9,11,74);\n  Eigen::TensorMap<Eigen::Tensor<float, 1, RowMajor> > gpu_kernel(d_kernel, 4);\n  Eigen::TensorMap<Eigen::Tensor<float, 4, RowMajor> > gpu_out(d_out, 7,9,11,71);\n\n  Eigen::array<Eigen::DenseIndex, 1> dims(3);\n  gpu_out.device(gpu_device) = gpu_input.convolve(gpu_kernel, dims);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 7; ++i) {\n    for (int j = 0; j < 9; ++j) {\n      for (int k = 0; k < 11; ++k) {\n        for (int l = 0; l < 71; ++l) {\n          const float result = out(i,j,k,l);\n          const float expected = input(i,j,k,l+0) * kernel(0) + input(i,j,k,l+1) * kernel(1) +\n                                 input(i,j,k,l+2) * kernel(2) + input(i,j,k,l+3) * kernel(3);\n          VERIFY_IS_APPROX(result, expected);\n        }\n      }\n    }\n  }\n\n  gpuFree(d_input);\n  gpuFree(d_kernel);\n  gpuFree(d_out);\n}\n\ntemplate<int DataLayout>\nvoid test_gpu_convolution_2d()\n{\n  Tensor<float, 4, DataLayout> input(74,37,11,137);\n  Tensor<float, 2, DataLayout> kernel(3,4);\n  Tensor<float, 4, DataLayout> out(74,35,8,137);\n  input = input.constant(10.0f) + input.random();\n  kernel = kernel.constant(7.0f) + kernel.random();\n\n  std::size_t input_bytes = input.size() * sizeof(float);\n  std::size_t kernel_bytes = kernel.size() * sizeof(float);\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_input;\n  float* d_kernel;\n  float* d_out;\n  gpuMalloc((void**)(&d_input), input_bytes);\n  gpuMalloc((void**)(&d_kernel), kernel_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  gpuMemcpy(d_input, input.data(), input_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_kernel, kernel.data(), kernel_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 4, DataLayout> > gpu_input(d_input,74,37,11,137);\n  Eigen::TensorMap<Eigen::Tensor<float, 2, DataLayout> > gpu_kernel(d_kernel,3,4);\n  Eigen::TensorMap<Eigen::Tensor<float, 4, DataLayout> > gpu_out(d_out,74,35,8,137);\n\n  Eigen::array<Eigen::DenseIndex, 2> dims(1,2);\n  gpu_out.device(gpu_device) = gpu_input.convolve(gpu_kernel, dims);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 74; ++i) {\n    for (int j = 0; j < 35; ++j) {\n      for (int k = 0; k < 8; ++k) {\n        for (int l = 0; l < 137; ++l) {\n          const float result = out(i,j,k,l);\n          const float expected = input(i,j+0,k+0,l) * kernel(0,0) +\n                                 input(i,j+1,k+0,l) * kernel(1,0) +\n                                 input(i,j+2,k+0,l) * kernel(2,0) +\n                                 input(i,j+0,k+1,l) * kernel(0,1) +\n                                 input(i,j+1,k+1,l) * kernel(1,1) +\n                                 input(i,j+2,k+1,l) * kernel(2,1) +\n                                 input(i,j+0,k+2,l) * kernel(0,2) +\n                                 input(i,j+1,k+2,l) * kernel(1,2) +\n                                 input(i,j+2,k+2,l) * kernel(2,2) +\n                                 input(i,j+0,k+3,l) * kernel(0,3) +\n                                 input(i,j+1,k+3,l) * kernel(1,3) +\n                                 input(i,j+2,k+3,l) * kernel(2,3);\n          VERIFY_IS_APPROX(result, expected);\n        }\n      }\n    }\n  }\n\n  gpuFree(d_input);\n  gpuFree(d_kernel);\n  gpuFree(d_out);\n}\n\ntemplate<int DataLayout>\nvoid test_gpu_convolution_3d()\n{\n  Tensor<float, 5, DataLayout> input(Eigen::array<Eigen::DenseIndex, 5>(74,37,11,137,17));\n  Tensor<float, 3, DataLayout> kernel(3,4,2);\n  Tensor<float, 5, DataLayout> out(Eigen::array<Eigen::DenseIndex, 5>(74,35,8,136,17));\n  input = input.constant(10.0f) + input.random();\n  kernel = kernel.constant(7.0f) + kernel.random();\n\n  std::size_t input_bytes = input.size() * sizeof(float);\n  std::size_t kernel_bytes = kernel.size() * sizeof(float);\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_input;\n  float* d_kernel;\n  float* d_out;\n  gpuMalloc((void**)(&d_input), input_bytes);\n  gpuMalloc((void**)(&d_kernel), kernel_bytes);\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  gpuMemcpy(d_input, input.data(), input_bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_kernel, kernel.data(), kernel_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;    \n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 5, DataLayout> > gpu_input(d_input,74,37,11,137,17);\n  Eigen::TensorMap<Eigen::Tensor<float, 3, DataLayout> > gpu_kernel(d_kernel,3,4,2);\n  Eigen::TensorMap<Eigen::Tensor<float, 5, DataLayout> > gpu_out(d_out,74,35,8,136,17);\n\n  Eigen::array<Eigen::DenseIndex, 3> dims(1,2,3);\n  gpu_out.device(gpu_device) = gpu_input.convolve(gpu_kernel, dims);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 74; ++i) {\n    for (int j = 0; j < 35; ++j) {\n      for (int k = 0; k < 8; ++k) {\n        for (int l = 0; l < 136; ++l) {\n          for (int m = 0; m < 17; ++m) {\n            const float result = out(i,j,k,l,m);\n            const float expected = input(i,j+0,k+0,l+0,m) * kernel(0,0,0) +\n                                   input(i,j+1,k+0,l+0,m) * kernel(1,0,0) +\n                                   input(i,j+2,k+0,l+0,m) * kernel(2,0,0) +\n                                   input(i,j+0,k+1,l+0,m) * kernel(0,1,0) +\n                                   input(i,j+1,k+1,l+0,m) * kernel(1,1,0) +\n                                   input(i,j+2,k+1,l+0,m) * kernel(2,1,0) +\n                                   input(i,j+0,k+2,l+0,m) * kernel(0,2,0) +\n                                   input(i,j+1,k+2,l+0,m) * kernel(1,2,0) +\n                                   input(i,j+2,k+2,l+0,m) * kernel(2,2,0) +\n                                   input(i,j+0,k+3,l+0,m) * kernel(0,3,0) +\n                                   input(i,j+1,k+3,l+0,m) * kernel(1,3,0) +\n                                   input(i,j+2,k+3,l+0,m) * kernel(2,3,0) +\n                                   input(i,j+0,k+0,l+1,m) * kernel(0,0,1) +\n                                   input(i,j+1,k+0,l+1,m) * kernel(1,0,1) +\n                                   input(i,j+2,k+0,l+1,m) * kernel(2,0,1) +\n                                   input(i,j+0,k+1,l+1,m) * kernel(0,1,1) +\n                                   input(i,j+1,k+1,l+1,m) * kernel(1,1,1) +\n                                   input(i,j+2,k+1,l+1,m) * kernel(2,1,1) +\n                                   input(i,j+0,k+2,l+1,m) * kernel(0,2,1) +\n                                   input(i,j+1,k+2,l+1,m) * kernel(1,2,1) +\n                                   input(i,j+2,k+2,l+1,m) * kernel(2,2,1) +\n                                   input(i,j+0,k+3,l+1,m) * kernel(0,3,1) +\n                                   input(i,j+1,k+3,l+1,m) * kernel(1,3,1) +\n                                   input(i,j+2,k+3,l+1,m) * kernel(2,3,1);\n            VERIFY_IS_APPROX(result, expected);\n          }\n        }\n      }\n    }\n  }\n\n  gpuFree(d_input);\n  gpuFree(d_kernel);\n  gpuFree(d_out);\n}\n\n\n#if EIGEN_GPU_TEST_C99_MATH\ntemplate <typename Scalar>\nvoid test_gpu_lgamma(const Scalar stddev)\n{\n  Tensor<Scalar, 2> in(72,97);\n  in.setRandom();\n  in *= in.constant(stddev);\n  Tensor<Scalar, 2> out(72,97);\n  out.setZero();\n\n  std::size_t bytes = in.size() * sizeof(Scalar);\n\n  Scalar* d_in;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_in), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_in, in.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_in(d_in, 72, 97);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_out(d_out, 72, 97);\n\n  gpu_out.device(gpu_device) = gpu_in.lgamma();\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 72; ++i) {\n    for (int j = 0; j < 97; ++j) {\n      VERIFY_IS_APPROX(out(i,j), (std::lgamma)(in(i,j)));\n    }\n  }\n\n  gpuFree(d_in);\n  gpuFree(d_out);\n}\n#endif\n\ntemplate <typename Scalar>\nvoid test_gpu_digamma()\n{\n  Tensor<Scalar, 1> in(7);\n  Tensor<Scalar, 1> out(7);\n  Tensor<Scalar, 1> expected_out(7);\n  out.setZero();\n\n  in(0) = Scalar(1);\n  in(1) = Scalar(1.5);\n  in(2) = Scalar(4);\n  in(3) = Scalar(-10.5);\n  in(4) = Scalar(10000.5);\n  in(5) = Scalar(0);\n  in(6) = Scalar(-1);\n\n  expected_out(0) = Scalar(-0.5772156649015329);\n  expected_out(1) = Scalar(0.03648997397857645);\n  expected_out(2) = Scalar(1.2561176684318);\n  expected_out(3) = Scalar(2.398239129535781);\n  expected_out(4) = Scalar(9.210340372392849);\n  expected_out(5) = std::numeric_limits<Scalar>::infinity();\n  expected_out(6) = std::numeric_limits<Scalar>::infinity();\n\n  std::size_t bytes = in.size() * sizeof(Scalar);\n\n  Scalar* d_in;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_in), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_in, in.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in(d_in, 7);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_out(d_out, 7);\n\n  gpu_out.device(gpu_device) = gpu_in.digamma();\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 5; ++i) {\n    VERIFY_IS_APPROX(out(i), expected_out(i));\n  }\n  for (int i = 5; i < 7; ++i) {\n    VERIFY_IS_EQUAL(out(i), expected_out(i));\n  }\n\n  gpuFree(d_in);\n  gpuFree(d_out);\n}\n\ntemplate <typename Scalar>\nvoid test_gpu_zeta()\n{\n  Tensor<Scalar, 1> in_x(6);\n  Tensor<Scalar, 1> in_q(6);\n  Tensor<Scalar, 1> out(6);\n  Tensor<Scalar, 1> expected_out(6);\n  out.setZero();\n\n  in_x(0) = Scalar(1);\n  in_x(1) = Scalar(1.5);\n  in_x(2) = Scalar(4);\n  in_x(3) = Scalar(-10.5);\n  in_x(4) = Scalar(10000.5);\n  in_x(5) = Scalar(3);\n  \n  in_q(0) = Scalar(1.2345);\n  in_q(1) = Scalar(2);\n  in_q(2) = Scalar(1.5);\n  in_q(3) = Scalar(3);\n  in_q(4) = Scalar(1.0001);\n  in_q(5) = Scalar(-2.5);\n\n  expected_out(0) = std::numeric_limits<Scalar>::infinity();\n  expected_out(1) = Scalar(1.61237534869);\n  expected_out(2) = Scalar(0.234848505667);\n  expected_out(3) = Scalar(1.03086757337e-5);\n  expected_out(4) = Scalar(0.367879440865);\n  expected_out(5) = Scalar(0.054102025820864097);\n\n  std::size_t bytes = in_x.size() * sizeof(Scalar);\n\n  Scalar* d_in_x;\n  Scalar* d_in_q;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_in_x), bytes);\n  gpuMalloc((void**)(&d_in_q), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_in_x, in_x.data(), bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_in_q, in_q.data(), bytes, gpuMemcpyHostToDevice);\n  \n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in_x(d_in_x, 6);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in_q(d_in_q, 6);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_out(d_out, 6);\n\n  gpu_out.device(gpu_device) = gpu_in_x.zeta(gpu_in_q);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  VERIFY_IS_EQUAL(out(0), expected_out(0));\n  VERIFY((std::isnan)(out(3)));\n\n  for (int i = 1; i < 6; ++i) {\n    if (i != 3) {\n      VERIFY_IS_APPROX(out(i), expected_out(i));\n    }\n  }\n\n  gpuFree(d_in_x);\n  gpuFree(d_in_q);\n  gpuFree(d_out);\n}\n\ntemplate <typename Scalar>\nvoid test_gpu_polygamma()\n{\n  Tensor<Scalar, 1> in_x(7);\n  Tensor<Scalar, 1> in_n(7);\n  Tensor<Scalar, 1> out(7);\n  Tensor<Scalar, 1> expected_out(7);\n  out.setZero();\n\n  in_n(0) = Scalar(1);\n  in_n(1) = Scalar(1);\n  in_n(2) = Scalar(1);\n  in_n(3) = Scalar(17);\n  in_n(4) = Scalar(31);\n  in_n(5) = Scalar(28);\n  in_n(6) = Scalar(8);\n  \n  in_x(0) = Scalar(2);\n  in_x(1) = Scalar(3);\n  in_x(2) = Scalar(25.5);\n  in_x(3) = Scalar(4.7);\n  in_x(4) = Scalar(11.8);\n  in_x(5) = Scalar(17.7);\n  in_x(6) = Scalar(30.2);\n\n  expected_out(0) = Scalar(0.644934066848);\n  expected_out(1) = Scalar(0.394934066848);\n  expected_out(2) = Scalar(0.0399946696496);\n  expected_out(3) = Scalar(293.334565435);\n  expected_out(4) = Scalar(0.445487887616);\n  expected_out(5) = Scalar(-2.47810300902e-07);\n  expected_out(6) = Scalar(-8.29668781082e-09);\n\n  std::size_t bytes = in_x.size() * sizeof(Scalar);\n\n  Scalar* d_in_x;\n  Scalar* d_in_n;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_in_x), bytes);\n  gpuMalloc((void**)(&d_in_n), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_in_x, in_x.data(), bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_in_n, in_n.data(), bytes, gpuMemcpyHostToDevice);\n  \n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in_x(d_in_x, 7);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in_n(d_in_n, 7);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_out(d_out, 7);\n\n  gpu_out.device(gpu_device) = gpu_in_n.polygamma(gpu_in_x);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 7; ++i) {\n    VERIFY_IS_APPROX(out(i), expected_out(i));\n  }\n\n  gpuFree(d_in_x);\n  gpuFree(d_in_n);\n  gpuFree(d_out);\n}\n\ntemplate <typename Scalar>\nvoid test_gpu_igamma()\n{\n  Tensor<Scalar, 2> a(6, 6);\n  Tensor<Scalar, 2> x(6, 6);\n  Tensor<Scalar, 2> out(6, 6);\n  out.setZero();\n\n  Scalar a_s[] = {Scalar(0), Scalar(1), Scalar(1.5), Scalar(4), Scalar(0.0001), Scalar(1000.5)};\n  Scalar x_s[] = {Scalar(0), Scalar(1), Scalar(1.5), Scalar(4), Scalar(0.0001), Scalar(1000.5)};\n\n  for (int i = 0; i < 6; ++i) {\n    for (int j = 0; j < 6; ++j) {\n      a(i, j) = a_s[i];\n      x(i, j) = x_s[j];\n    }\n  }\n\n  Scalar nan = std::numeric_limits<Scalar>::quiet_NaN();\n  Scalar igamma_s[][6] = {{0.0, nan, nan, nan, nan, nan},\n                          {0.0, 0.6321205588285578, 0.7768698398515702,\n                           0.9816843611112658, 9.999500016666262e-05, 1.0},\n                          {0.0, 0.4275932955291202, 0.608374823728911,\n                           0.9539882943107686, 7.522076445089201e-07, 1.0},\n                          {0.0, 0.01898815687615381, 0.06564245437845008,\n                           0.5665298796332909, 4.166333347221828e-18, 1.0},\n                          {0.0, 0.9999780593618628, 0.9999899967080838,\n                           0.9999996219837988, 0.9991370418689945, 1.0},\n                          {0.0, 0.0, 0.0, 0.0, 0.0, 0.5042041932513908}};\n\n\n\n  std::size_t bytes = a.size() * sizeof(Scalar);\n\n  Scalar* d_a;\n  Scalar* d_x;\n  Scalar* d_out;\n  assert(gpuMalloc((void**)(&d_a), bytes) == gpuSuccess);\n  assert(gpuMalloc((void**)(&d_x), bytes) == gpuSuccess);\n  assert(gpuMalloc((void**)(&d_out), bytes) == gpuSuccess);\n\n  gpuMemcpy(d_a, a.data(), bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_x, x.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_a(d_a, 6, 6);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_x(d_x, 6, 6);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_out(d_out, 6, 6);\n\n  gpu_out.device(gpu_device) = gpu_a.igamma(gpu_x);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 6; ++i) {\n    for (int j = 0; j < 6; ++j) {\n      if ((std::isnan)(igamma_s[i][j])) {\n        VERIFY((std::isnan)(out(i, j)));\n      } else {\n        VERIFY_IS_APPROX(out(i, j), igamma_s[i][j]);\n      }\n    }\n  }\n\n  gpuFree(d_a);\n  gpuFree(d_x);\n  gpuFree(d_out);\n}\n\ntemplate <typename Scalar>\nvoid test_gpu_igammac()\n{\n  Tensor<Scalar, 2> a(6, 6);\n  Tensor<Scalar, 2> x(6, 6);\n  Tensor<Scalar, 2> out(6, 6);\n  out.setZero();\n\n  Scalar a_s[] = {Scalar(0), Scalar(1), Scalar(1.5), Scalar(4), Scalar(0.0001), Scalar(1000.5)};\n  Scalar x_s[] = {Scalar(0), Scalar(1), Scalar(1.5), Scalar(4), Scalar(0.0001), Scalar(1000.5)};\n\n  for (int i = 0; i < 6; ++i) {\n    for (int j = 0; j < 6; ++j) {\n      a(i, j) = a_s[i];\n      x(i, j) = x_s[j];\n    }\n  }\n\n  Scalar nan = std::numeric_limits<Scalar>::quiet_NaN();\n  Scalar igammac_s[][6] = {{nan, nan, nan, nan, nan, nan},\n                           {1.0, 0.36787944117144233, 0.22313016014842982,\n                            0.018315638888734182, 0.9999000049998333, 0.0},\n                           {1.0, 0.5724067044708798, 0.3916251762710878,\n                            0.04601170568923136, 0.9999992477923555, 0.0},\n                           {1.0, 0.9810118431238462, 0.9343575456215499,\n                            0.4334701203667089, 1.0, 0.0},\n                           {1.0, 2.1940638138146658e-05, 1.0003291916285e-05,\n                            3.7801620118431334e-07, 0.0008629581310054535,\n                            0.0},\n                           {1.0, 1.0, 1.0, 1.0, 1.0, 0.49579580674813944}};\n\n  std::size_t bytes = a.size() * sizeof(Scalar);\n\n  Scalar* d_a;\n  Scalar* d_x;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_a), bytes);\n  gpuMalloc((void**)(&d_x), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_a, a.data(), bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_x, x.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_a(d_a, 6, 6);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_x(d_x, 6, 6);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_out(d_out, 6, 6);\n\n  gpu_out.device(gpu_device) = gpu_a.igammac(gpu_x);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 6; ++i) {\n    for (int j = 0; j < 6; ++j) {\n      if ((std::isnan)(igammac_s[i][j])) {\n        VERIFY((std::isnan)(out(i, j)));\n      } else {\n        VERIFY_IS_APPROX(out(i, j), igammac_s[i][j]);\n      }\n    }\n  }\n\n  gpuFree(d_a);\n  gpuFree(d_x);\n  gpuFree(d_out);\n}\n\n#if EIGEN_GPU_TEST_C99_MATH\ntemplate <typename Scalar>\nvoid test_gpu_erf(const Scalar stddev)\n{\n  Tensor<Scalar, 2> in(72,97);\n  in.setRandom();\n  in *= in.constant(stddev);\n  Tensor<Scalar, 2> out(72,97);\n  out.setZero();\n\n  std::size_t bytes = in.size() * sizeof(Scalar);\n\n  Scalar* d_in;\n  Scalar* d_out;\n  assert(gpuMalloc((void**)(&d_in), bytes) == gpuSuccess);\n  assert(gpuMalloc((void**)(&d_out), bytes) == gpuSuccess);\n\n  gpuMemcpy(d_in, in.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_in(d_in, 72, 97);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_out(d_out, 72, 97);\n\n  gpu_out.device(gpu_device) = gpu_in.erf();\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 72; ++i) {\n    for (int j = 0; j < 97; ++j) {\n      VERIFY_IS_APPROX(out(i,j), (std::erf)(in(i,j)));\n    }\n  }\n\n  gpuFree(d_in);\n  gpuFree(d_out);\n}\n\ntemplate <typename Scalar>\nvoid test_gpu_erfc(const Scalar stddev)\n{\n  Tensor<Scalar, 2> in(72,97);\n  in.setRandom();\n  in *= in.constant(stddev);\n  Tensor<Scalar, 2> out(72,97);\n  out.setZero();\n\n  std::size_t bytes = in.size() * sizeof(Scalar);\n\n  Scalar* d_in;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_in), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_in, in.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_in(d_in, 72, 97);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 2> > gpu_out(d_out, 72, 97);\n\n  gpu_out.device(gpu_device) = gpu_in.erfc();\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 72; ++i) {\n    for (int j = 0; j < 97; ++j) {\n      VERIFY_IS_APPROX(out(i,j), (std::erfc)(in(i,j)));\n    }\n  }\n\n  gpuFree(d_in);\n  gpuFree(d_out);\n}\n#endif\ntemplate <typename Scalar>\nvoid test_gpu_ndtri()\n{\n  Tensor<Scalar, 1> in_x(8);\n  Tensor<Scalar, 1> out(8);\n  Tensor<Scalar, 1> expected_out(8);\n  out.setZero();\n\n  in_x(0) = Scalar(1);\n  in_x(1) = Scalar(0.);\n  in_x(2) = Scalar(0.5);\n  in_x(3) = Scalar(0.2);\n  in_x(4) = Scalar(0.8);\n  in_x(5) = Scalar(0.9);\n  in_x(6) = Scalar(0.1);\n  in_x(7) = Scalar(0.99);\n  in_x(8) = Scalar(0.01);\n\n  expected_out(0) = std::numeric_limits<Scalar>::infinity();\n  expected_out(1) = -std::numeric_limits<Scalar>::infinity();\n  expected_out(2) = Scalar(0.0);\n  expected_out(3) = Scalar(-0.8416212335729142);\n  expected_out(4) = Scalar(0.8416212335729142);\n  expected_out(5) = Scalar(1.2815515655446004);\n  expected_out(6) = Scalar(-1.2815515655446004);\n  expected_out(7) = Scalar(2.3263478740408408);\n  expected_out(8) = Scalar(-2.3263478740408408);\n\n  std::size_t bytes = in_x.size() * sizeof(Scalar);\n\n  Scalar* d_in_x;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_in_x), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_in_x, in_x.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in_x(d_in_x, 6);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_out(d_out, 6);\n\n  gpu_out.device(gpu_device) = gpu_in_x.ndtri();\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  VERIFY_IS_EQUAL(out(0), expected_out(0));\n  VERIFY((std::isnan)(out(3)));\n\n  for (int i = 1; i < 6; ++i) {\n    if (i != 3) {\n      VERIFY_IS_APPROX(out(i), expected_out(i));\n    }\n  }\n\n  gpuFree(d_in_x);\n  gpuFree(d_out);\n}\n\ntemplate <typename Scalar>\nvoid test_gpu_betainc()\n{\n  Tensor<Scalar, 1> in_x(125);\n  Tensor<Scalar, 1> in_a(125);\n  Tensor<Scalar, 1> in_b(125);\n  Tensor<Scalar, 1> out(125);\n  Tensor<Scalar, 1> expected_out(125);\n  out.setZero();\n\n  Scalar nan = std::numeric_limits<Scalar>::quiet_NaN();\n\n  Array<Scalar, 1, Dynamic> x(125);\n  Array<Scalar, 1, Dynamic> a(125);\n  Array<Scalar, 1, Dynamic> b(125);\n  Array<Scalar, 1, Dynamic> v(125);\n\n  a << 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,\n      0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999,\n      0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999,\n      0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379, 999.999, 999.999,\n      999.999, 999.999, 999.999, 999.999, 999.999, 999.999, 999.999, 999.999,\n      999.999, 999.999, 999.999, 999.999, 999.999, 999.999, 999.999, 999.999,\n      999.999, 999.999, 999.999, 999.999, 999.999, 999.999, 999.999;\n\n  b << 0.0, 0.0, 0.0, 0.0, 0.0, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379, 0.999,\n      0.999, 0.999, 0.999, 0.999, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379, 999.999, 999.999,\n      999.999, 999.999, 999.999, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.999, 0.999, 0.999, 0.999, 0.999, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 999.999, 999.999, 999.999, 999.999, 999.999, 0.0, 0.0,\n      0.0, 0.0, 0.0, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379, 0.999,\n      0.999, 0.999, 0.999, 0.999, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379, 999.999, 999.999,\n      999.999, 999.999, 999.999, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.999, 0.999, 0.999, 0.999, 0.999, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 999.999, 999.999, 999.999, 999.999, 999.999, 0.0, 0.0,\n      0.0, 0.0, 0.0, 0.03062277660168379, 0.03062277660168379,\n      0.03062277660168379, 0.03062277660168379, 0.03062277660168379, 0.999,\n      0.999, 0.999, 0.999, 0.999, 31.62177660168379, 31.62177660168379,\n      31.62177660168379, 31.62177660168379, 31.62177660168379, 999.999, 999.999,\n      999.999, 999.999, 999.999;\n\n  x << -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8,\n      1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5,\n      0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2,\n      0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1,\n      0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1,\n      -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8,\n      1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5,\n      0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2,\n      0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1;\n\n  v << nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan,\n      nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan,\n      nan, nan, 0.47972119876364683, 0.5, 0.5202788012363533, nan, nan,\n      0.9518683957740043, 0.9789663010413743, 0.9931729188073435, nan, nan,\n      0.999995949033062, 0.9999999999993698, 0.9999999999999999, nan, nan,\n      0.9999999999999999, 0.9999999999999999, 0.9999999999999999, nan, nan, nan,\n      nan, nan, nan, nan, 0.006827081192655869, 0.0210336989586256,\n      0.04813160422599567, nan, nan, 0.20014344256217678, 0.5000000000000001,\n      0.7998565574378232, nan, nan, 0.9991401428435834, 0.999999999698403,\n      0.9999999999999999, nan, nan, 0.9999999999999999, 0.9999999999999999,\n      0.9999999999999999, nan, nan, nan, nan, nan, nan, nan,\n      1.0646600232370887e-25, 6.301722877826246e-13, 4.050966937974938e-06, nan,\n      nan, 7.864342668429763e-23, 3.015969667594166e-10, 0.0008598571564165444,\n      nan, nan, 6.031987710123844e-08, 0.5000000000000007, 0.9999999396801229,\n      nan, nan, 0.9999999999999999, 0.9999999999999999, 0.9999999999999999, nan,\n      nan, nan, nan, nan, nan, nan, 0.0, 7.029920380986636e-306,\n      2.2450728208591345e-101, nan, nan, 0.0, 9.275871147869727e-302,\n      1.2232913026152827e-97, nan, nan, 0.0, 3.0891393081932924e-252,\n      2.9303043666183996e-60, nan, nan, 2.248913486879199e-196,\n      0.5000000000004947, 0.9999999999999999, nan;\n\n  for (int i = 0; i < 125; ++i) {\n    in_x(i) = x(i);\n    in_a(i) = a(i);\n    in_b(i) = b(i);\n    expected_out(i) = v(i);\n  }\n\n  std::size_t bytes = in_x.size() * sizeof(Scalar);\n\n  Scalar* d_in_x;\n  Scalar* d_in_a;\n  Scalar* d_in_b;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_in_x), bytes);\n  gpuMalloc((void**)(&d_in_a), bytes);\n  gpuMalloc((void**)(&d_in_b), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_in_x, in_x.data(), bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_in_a, in_a.data(), bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_in_b, in_b.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in_x(d_in_x, 125);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in_a(d_in_a, 125);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in_b(d_in_b, 125);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_out(d_out, 125);\n\n  gpu_out.device(gpu_device) = betainc(gpu_in_a, gpu_in_b, gpu_in_x);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 1; i < 125; ++i) {\n    if ((std::isnan)(expected_out(i))) {\n      VERIFY((std::isnan)(out(i)));\n    } else {\n      VERIFY_IS_APPROX(out(i), expected_out(i));\n    }\n  }\n\n  gpuFree(d_in_x);\n  gpuFree(d_in_a);\n  gpuFree(d_in_b);\n  gpuFree(d_out);\n}\n\ntemplate <typename Scalar>\nvoid test_gpu_i0e()\n{\n  Tensor<Scalar, 1> in_x(21);\n  Tensor<Scalar, 1> out(21);\n  Tensor<Scalar, 1> expected_out(21);\n  out.setZero();\n\n  Array<Scalar, 1, Dynamic> in_x_array(21);\n  Array<Scalar, 1, Dynamic> expected_out_array(21);\n\n  in_x_array << -20.0, -18.0, -16.0, -14.0, -12.0, -10.0, -8.0, -6.0, -4.0,\n      -2.0, 0.0, 2.0, 4.0, 6.0, 8.0, 10.0, 12.0, 14.0, 16.0, 18.0, 20.0;\n\n  expected_out_array << 0.0897803118848, 0.0947062952128, 0.100544127361,\n      0.107615251671, 0.116426221213, 0.127833337163, 0.143431781857,\n      0.16665743264, 0.207001921224, 0.308508322554, 1.0, 0.308508322554,\n      0.207001921224, 0.16665743264, 0.143431781857, 0.127833337163,\n      0.116426221213, 0.107615251671, 0.100544127361, 0.0947062952128,\n      0.0897803118848;\n\n  for (int i = 0; i < 21; ++i) {\n    in_x(i) = in_x_array(i);\n    expected_out(i) = expected_out_array(i);\n  }\n\n  std::size_t bytes = in_x.size() * sizeof(Scalar);\n\n  Scalar* d_in;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_in), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_in, in_x.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in(d_in, 21);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_out(d_out, 21);\n\n  gpu_out.device(gpu_device) = gpu_in.bessel_i0e();\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost,\n                         gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 21; ++i) {\n    VERIFY_IS_APPROX(out(i), expected_out(i));\n  }\n\n  gpuFree(d_in);\n  gpuFree(d_out);\n}\n\ntemplate <typename Scalar>\nvoid test_gpu_i1e()\n{\n  Tensor<Scalar, 1> in_x(21);\n  Tensor<Scalar, 1> out(21);\n  Tensor<Scalar, 1> expected_out(21);\n  out.setZero();\n\n  Array<Scalar, 1, Dynamic> in_x_array(21);\n  Array<Scalar, 1, Dynamic> expected_out_array(21);\n\n  in_x_array << -20.0, -18.0, -16.0, -14.0, -12.0, -10.0, -8.0, -6.0, -4.0,\n      -2.0, 0.0, 2.0, 4.0, 6.0, 8.0, 10.0, 12.0, 14.0, 16.0, 18.0, 20.0;\n\n  expected_out_array << -0.0875062221833, -0.092036796872, -0.0973496147565,\n      -0.103697667463, -0.11146429929, -0.121262681384, -0.134142493293,\n      -0.152051459309, -0.178750839502, -0.215269289249, 0.0, 0.215269289249,\n      0.178750839502, 0.152051459309, 0.134142493293, 0.121262681384,\n      0.11146429929, 0.103697667463, 0.0973496147565, 0.092036796872,\n      0.0875062221833;\n\n  for (int i = 0; i < 21; ++i) {\n    in_x(i) = in_x_array(i);\n    expected_out(i) = expected_out_array(i);\n  }\n\n  std::size_t bytes = in_x.size() * sizeof(Scalar);\n\n  Scalar* d_in;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_in), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_in, in_x.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_in(d_in, 21);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_out(d_out, 21);\n\n  gpu_out.device(gpu_device) = gpu_in.bessel_i1e();\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost,\n                         gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 21; ++i) {\n    VERIFY_IS_APPROX(out(i), expected_out(i));\n  }\n\n  gpuFree(d_in);\n  gpuFree(d_out);\n}\n\ntemplate <typename Scalar>\nvoid test_gpu_igamma_der_a()\n{\n  Tensor<Scalar, 1> in_x(30);\n  Tensor<Scalar, 1> in_a(30);\n  Tensor<Scalar, 1> out(30);\n  Tensor<Scalar, 1> expected_out(30);\n  out.setZero();\n\n  Array<Scalar, 1, Dynamic> in_a_array(30);\n  Array<Scalar, 1, Dynamic> in_x_array(30);\n  Array<Scalar, 1, Dynamic> expected_out_array(30);\n\n  // See special_functions.cpp for the Python code that generates the test data.\n\n  in_a_array << 0.01, 0.01, 0.01, 0.01, 0.01, 0.1, 0.1, 0.1, 0.1, 0.1, 1.0, 1.0,\n      1.0, 1.0, 1.0, 10.0, 10.0, 10.0, 10.0, 10.0, 100.0, 100.0, 100.0, 100.0,\n      100.0, 1000.0, 1000.0, 1000.0, 1000.0, 1000.0;\n\n  in_x_array << 1.25668890405e-26, 1.17549435082e-38, 1.20938905072e-05,\n      1.17549435082e-38, 1.17549435082e-38, 5.66572070696e-16, 0.0132865061065,\n      0.0200034203853, 6.29263709118e-17, 1.37160367764e-06, 0.333412038288,\n      1.18135687766, 0.580629033777, 0.170631439426, 0.786686768458,\n      7.63873279537, 13.1944344379, 11.896042354, 10.5830172417, 10.5020942233,\n      92.8918587747, 95.003720371, 86.3715926467, 96.0330217672, 82.6389930677,\n      968.702906754, 969.463546828, 1001.79726022, 955.047416547, 1044.27458568;\n\n  expected_out_array << -32.7256441441, -36.4394150514, -9.66467612263,\n      -36.4394150514, -36.4394150514, -1.0891900302, -2.66351229645,\n      -2.48666868596, -0.929700494428, -3.56327722764, -0.455320135314,\n      -0.391437214323, -0.491352055991, -0.350454834292, -0.471773162921,\n      -0.104084440522, -0.0723646747909, -0.0992828975532, -0.121638215446,\n      -0.122619605294, -0.0317670267286, -0.0359974812869, -0.0154359225363,\n      -0.0375775365921, -0.00794899153653, -0.00777303219211, -0.00796085782042,\n      -0.0125850719397, -0.00455500206958, -0.00476436993148;\n\n  for (int i = 0; i < 30; ++i) {\n    in_x(i) = in_x_array(i);\n    in_a(i) = in_a_array(i);\n    expected_out(i) = expected_out_array(i);\n  }\n\n  std::size_t bytes = in_x.size() * sizeof(Scalar);\n\n  Scalar* d_a;\n  Scalar* d_x;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_a), bytes);\n  gpuMalloc((void**)(&d_x), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_a, in_a.data(), bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_x, in_x.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_a(d_a, 30);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_x(d_x, 30);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_out(d_out, 30);\n\n  gpu_out.device(gpu_device) = gpu_a.igamma_der_a(gpu_x);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost,\n                         gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 30; ++i) {\n    VERIFY_IS_APPROX(out(i), expected_out(i));\n  }\n\n  gpuFree(d_a);\n  gpuFree(d_x);\n  gpuFree(d_out);\n}\n\ntemplate <typename Scalar>\nvoid test_gpu_gamma_sample_der_alpha()\n{\n  Tensor<Scalar, 1> in_alpha(30);\n  Tensor<Scalar, 1> in_sample(30);\n  Tensor<Scalar, 1> out(30);\n  Tensor<Scalar, 1> expected_out(30);\n  out.setZero();\n\n  Array<Scalar, 1, Dynamic> in_alpha_array(30);\n  Array<Scalar, 1, Dynamic> in_sample_array(30);\n  Array<Scalar, 1, Dynamic> expected_out_array(30);\n\n  // See special_functions.cpp for the Python code that generates the test data.\n\n  in_alpha_array << 0.01, 0.01, 0.01, 0.01, 0.01, 0.1, 0.1, 0.1, 0.1, 0.1, 1.0,\n      1.0, 1.0, 1.0, 1.0, 10.0, 10.0, 10.0, 10.0, 10.0, 100.0, 100.0, 100.0,\n      100.0, 100.0, 1000.0, 1000.0, 1000.0, 1000.0, 1000.0;\n\n  in_sample_array << 1.25668890405e-26, 1.17549435082e-38, 1.20938905072e-05,\n      1.17549435082e-38, 1.17549435082e-38, 5.66572070696e-16, 0.0132865061065,\n      0.0200034203853, 6.29263709118e-17, 1.37160367764e-06, 0.333412038288,\n      1.18135687766, 0.580629033777, 0.170631439426, 0.786686768458,\n      7.63873279537, 13.1944344379, 11.896042354, 10.5830172417, 10.5020942233,\n      92.8918587747, 95.003720371, 86.3715926467, 96.0330217672, 82.6389930677,\n      968.702906754, 969.463546828, 1001.79726022, 955.047416547, 1044.27458568;\n\n  expected_out_array << 7.42424742367e-23, 1.02004297287e-34, 0.0130155240738,\n      1.02004297287e-34, 1.02004297287e-34, 1.96505168277e-13, 0.525575786243,\n      0.713903991771, 2.32077561808e-14, 0.000179348049886, 0.635500453302,\n      1.27561284917, 0.878125852156, 0.41565819538, 1.03606488534,\n      0.885964824887, 1.16424049334, 1.10764479598, 1.04590810812,\n      1.04193666963, 0.965193152414, 0.976217589464, 0.93008035061,\n      0.98153216096, 0.909196397698, 0.98434963993, 0.984738050206,\n      1.00106492525, 0.97734200649, 1.02198794179;\n\n  for (int i = 0; i < 30; ++i) {\n    in_alpha(i) = in_alpha_array(i);\n    in_sample(i) = in_sample_array(i);\n    expected_out(i) = expected_out_array(i);\n  }\n\n  std::size_t bytes = in_alpha.size() * sizeof(Scalar);\n\n  Scalar* d_alpha;\n  Scalar* d_sample;\n  Scalar* d_out;\n  gpuMalloc((void**)(&d_alpha), bytes);\n  gpuMalloc((void**)(&d_sample), bytes);\n  gpuMalloc((void**)(&d_out), bytes);\n\n  gpuMemcpy(d_alpha, in_alpha.data(), bytes, gpuMemcpyHostToDevice);\n  gpuMemcpy(d_sample, in_sample.data(), bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_alpha(d_alpha, 30);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_sample(d_sample, 30);\n  Eigen::TensorMap<Eigen::Tensor<Scalar, 1> > gpu_out(d_out, 30);\n\n  gpu_out.device(gpu_device) = gpu_alpha.gamma_sample_der_alpha(gpu_sample);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, bytes, gpuMemcpyDeviceToHost,\n                         gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  for (int i = 0; i < 30; ++i) {\n    VERIFY_IS_APPROX(out(i), expected_out(i));\n  }\n\n  gpuFree(d_alpha);\n  gpuFree(d_sample);\n  gpuFree(d_out);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_gpu)\n{\n  CALL_SUBTEST_1(test_gpu_nullary());\n  CALL_SUBTEST_1(test_gpu_elementwise_small());\n  CALL_SUBTEST_1(test_gpu_elementwise());\n  CALL_SUBTEST_1(test_gpu_props());\n  CALL_SUBTEST_1(test_gpu_reduction());\n  CALL_SUBTEST_2(test_gpu_contraction<ColMajor>());\n  CALL_SUBTEST_2(test_gpu_contraction<RowMajor>());\n  CALL_SUBTEST_3(test_gpu_convolution_1d<ColMajor>());\n  CALL_SUBTEST_3(test_gpu_convolution_1d<RowMajor>());\n  CALL_SUBTEST_3(test_gpu_convolution_inner_dim_col_major_1d());\n  CALL_SUBTEST_3(test_gpu_convolution_inner_dim_row_major_1d());\n  CALL_SUBTEST_3(test_gpu_convolution_2d<ColMajor>());\n  CALL_SUBTEST_3(test_gpu_convolution_2d<RowMajor>());\n#if !defined(EIGEN_USE_HIP)\n// disable these tests on HIP for now.\n// they hang..need to investigate and fix\n  CALL_SUBTEST_3(test_gpu_convolution_3d<ColMajor>());\n  CALL_SUBTEST_3(test_gpu_convolution_3d<RowMajor>());\n#endif\n\n#if EIGEN_GPU_TEST_C99_MATH\n  // std::erf, std::erfc, and so on where only added in c++11. We use them\n  // as a golden reference to validate the results produced by Eigen. Therefore\n  // we can only run these tests if we use a c++11 compiler.\n  CALL_SUBTEST_4(test_gpu_lgamma<float>(1.0f));\n  CALL_SUBTEST_4(test_gpu_lgamma<float>(100.0f));\n  CALL_SUBTEST_4(test_gpu_lgamma<float>(0.01f));\n  CALL_SUBTEST_4(test_gpu_lgamma<float>(0.001f));\n\n  CALL_SUBTEST_4(test_gpu_lgamma<double>(1.0));\n  CALL_SUBTEST_4(test_gpu_lgamma<double>(100.0));\n  CALL_SUBTEST_4(test_gpu_lgamma<double>(0.01));\n  CALL_SUBTEST_4(test_gpu_lgamma<double>(0.001));\n\n  CALL_SUBTEST_4(test_gpu_erf<float>(1.0f));\n  CALL_SUBTEST_4(test_gpu_erf<float>(100.0f));\n  CALL_SUBTEST_4(test_gpu_erf<float>(0.01f));\n  CALL_SUBTEST_4(test_gpu_erf<float>(0.001f));\n\n  CALL_SUBTEST_4(test_gpu_erfc<float>(1.0f));\n  // CALL_SUBTEST(test_gpu_erfc<float>(100.0f));\n  CALL_SUBTEST_4(test_gpu_erfc<float>(5.0f)); // GPU erfc lacks precision for large inputs\n  CALL_SUBTEST_4(test_gpu_erfc<float>(0.01f));\n  CALL_SUBTEST_4(test_gpu_erfc<float>(0.001f));\n\n  CALL_SUBTEST_4(test_gpu_erf<double>(1.0));\n  CALL_SUBTEST_4(test_gpu_erf<double>(100.0));\n  CALL_SUBTEST_4(test_gpu_erf<double>(0.01));\n  CALL_SUBTEST_4(test_gpu_erf<double>(0.001));\n\n  CALL_SUBTEST_4(test_gpu_erfc<double>(1.0));\n  // CALL_SUBTEST(test_gpu_erfc<double>(100.0));\n  CALL_SUBTEST_4(test_gpu_erfc<double>(5.0)); // GPU erfc lacks precision for large inputs\n  CALL_SUBTEST_4(test_gpu_erfc<double>(0.01));\n  CALL_SUBTEST_4(test_gpu_erfc<double>(0.001));\n\n#if !defined(EIGEN_USE_HIP)\n// disable these tests on HIP for now.\n\n  CALL_SUBTEST_5(test_gpu_ndtri<float>());\n  CALL_SUBTEST_5(test_gpu_ndtri<double>());\n\n  CALL_SUBTEST_5(test_gpu_digamma<float>());\n  CALL_SUBTEST_5(test_gpu_digamma<double>());\n\n  CALL_SUBTEST_5(test_gpu_polygamma<float>());\n  CALL_SUBTEST_5(test_gpu_polygamma<double>());\n\n  CALL_SUBTEST_5(test_gpu_zeta<float>());\n  CALL_SUBTEST_5(test_gpu_zeta<double>());\n#endif\n\n  CALL_SUBTEST_5(test_gpu_igamma<float>());\n  CALL_SUBTEST_5(test_gpu_igammac<float>());\n\n  CALL_SUBTEST_5(test_gpu_igamma<double>());\n  CALL_SUBTEST_5(test_gpu_igammac<double>());\n\n#if !defined(EIGEN_USE_HIP)\n// disable these tests on HIP for now.\n  CALL_SUBTEST_6(test_gpu_betainc<float>());\n  CALL_SUBTEST_6(test_gpu_betainc<double>());\n\n  CALL_SUBTEST_6(test_gpu_i0e<float>());\n  CALL_SUBTEST_6(test_gpu_i0e<double>());\n\n  CALL_SUBTEST_6(test_gpu_i1e<float>());\n  CALL_SUBTEST_6(test_gpu_i1e<double>());\n\n  CALL_SUBTEST_6(test_gpu_i1e<float>());\n  CALL_SUBTEST_6(test_gpu_i1e<double>());\n\n  CALL_SUBTEST_6(test_gpu_igamma_der_a<float>());\n  CALL_SUBTEST_6(test_gpu_igamma_der_a<double>());\n\n  CALL_SUBTEST_6(test_gpu_gamma_sample_der_alpha<float>());\n  CALL_SUBTEST_6(test_gpu_gamma_sample_der_alpha<double>());\n#endif\n\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_ifft.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Jianwei Cui <thucjw@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <complex>\n#include <cmath>\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate <int DataLayout>\nstatic void test_1D_fft_ifft_invariant(int sequence_length) {\n  Tensor<double, 1, DataLayout> tensor(sequence_length);\n  tensor.setRandom();\n\n  array<int, 1> fft;\n  fft[0] = 0;\n\n  Tensor<std::complex<double>, 1, DataLayout> tensor_after_fft;\n  Tensor<std::complex<double>, 1, DataLayout> tensor_after_fft_ifft;\n\n  tensor_after_fft = tensor.template fft<Eigen::BothParts, Eigen::FFT_FORWARD>(fft);\n  tensor_after_fft_ifft = tensor_after_fft.template fft<Eigen::BothParts, Eigen::FFT_REVERSE>(fft);\n\n  VERIFY_IS_EQUAL(tensor_after_fft.dimension(0), sequence_length);\n  VERIFY_IS_EQUAL(tensor_after_fft_ifft.dimension(0), sequence_length);\n\n  for (int i = 0; i < sequence_length; ++i) {\n    VERIFY_IS_APPROX(static_cast<float>(tensor(i)), static_cast<float>(std::real(tensor_after_fft_ifft(i))));\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_2D_fft_ifft_invariant(int dim0, int dim1) {\n  Tensor<double, 2, DataLayout> tensor(dim0, dim1);\n  tensor.setRandom();\n\n  array<int, 2> fft;\n  fft[0] = 0;\n  fft[1] = 1;\n\n  Tensor<std::complex<double>, 2, DataLayout> tensor_after_fft;\n  Tensor<std::complex<double>, 2, DataLayout> tensor_after_fft_ifft;\n\n  tensor_after_fft = tensor.template fft<Eigen::BothParts, Eigen::FFT_FORWARD>(fft);\n  tensor_after_fft_ifft = tensor_after_fft.template fft<Eigen::BothParts, Eigen::FFT_REVERSE>(fft);\n\n  VERIFY_IS_EQUAL(tensor_after_fft.dimension(0), dim0);\n  VERIFY_IS_EQUAL(tensor_after_fft.dimension(1), dim1);\n  VERIFY_IS_EQUAL(tensor_after_fft_ifft.dimension(0), dim0);\n  VERIFY_IS_EQUAL(tensor_after_fft_ifft.dimension(1), dim1);\n\n  for (int i = 0; i < dim0; ++i) {\n    for (int j = 0; j < dim1; ++j) {\n      //std::cout << \"[\" << i << \"][\" << j << \"]\" <<  \"  Original data: \" << tensor(i,j) << \" Transformed data:\" << tensor_after_fft_ifft(i,j) << std::endl;\n      VERIFY_IS_APPROX(static_cast<float>(tensor(i,j)), static_cast<float>(std::real(tensor_after_fft_ifft(i,j))));\n    }\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_3D_fft_ifft_invariant(int dim0, int dim1, int dim2) {\n  Tensor<double, 3, DataLayout> tensor(dim0, dim1, dim2);\n  tensor.setRandom();\n\n  array<int, 3> fft;\n  fft[0] = 0;\n  fft[1] = 1;\n  fft[2] = 2;\n\n  Tensor<std::complex<double>, 3, DataLayout> tensor_after_fft;\n  Tensor<std::complex<double>, 3, DataLayout> tensor_after_fft_ifft;\n\n  tensor_after_fft = tensor.template fft<Eigen::BothParts, Eigen::FFT_FORWARD>(fft);\n  tensor_after_fft_ifft = tensor_after_fft.template fft<Eigen::BothParts, Eigen::FFT_REVERSE>(fft);\n\n  VERIFY_IS_EQUAL(tensor_after_fft.dimension(0), dim0);\n  VERIFY_IS_EQUAL(tensor_after_fft.dimension(1), dim1);\n  VERIFY_IS_EQUAL(tensor_after_fft.dimension(2), dim2);\n  VERIFY_IS_EQUAL(tensor_after_fft_ifft.dimension(0), dim0);\n  VERIFY_IS_EQUAL(tensor_after_fft_ifft.dimension(1), dim1);\n  VERIFY_IS_EQUAL(tensor_after_fft_ifft.dimension(2), dim2);\n\n  for (int i = 0; i < dim0; ++i) {\n    for (int j = 0; j < dim1; ++j) {\n      for (int k = 0; k < dim2; ++k) {\n        VERIFY_IS_APPROX(static_cast<float>(tensor(i,j,k)), static_cast<float>(std::real(tensor_after_fft_ifft(i,j,k))));\n      }\n    }\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_sub_fft_ifft_invariant(int dim0, int dim1, int dim2, int dim3) {\n  Tensor<double, 4, DataLayout> tensor(dim0, dim1, dim2, dim3);\n  tensor.setRandom();\n\n  array<int, 2> fft;\n  fft[0] = 2;\n  fft[1] = 0;\n\n  Tensor<std::complex<double>, 4, DataLayout> tensor_after_fft;\n  Tensor<double, 4, DataLayout> tensor_after_fft_ifft;\n\n  tensor_after_fft = tensor.template fft<Eigen::BothParts, Eigen::FFT_FORWARD>(fft);\n  tensor_after_fft_ifft = tensor_after_fft.template fft<Eigen::RealPart, Eigen::FFT_REVERSE>(fft);\n\n  VERIFY_IS_EQUAL(tensor_after_fft.dimension(0), dim0);\n  VERIFY_IS_EQUAL(tensor_after_fft.dimension(1), dim1);\n  VERIFY_IS_EQUAL(tensor_after_fft.dimension(2), dim2);\n  VERIFY_IS_EQUAL(tensor_after_fft.dimension(3), dim3);\n  VERIFY_IS_EQUAL(tensor_after_fft_ifft.dimension(0), dim0);\n  VERIFY_IS_EQUAL(tensor_after_fft_ifft.dimension(1), dim1);\n  VERIFY_IS_EQUAL(tensor_after_fft_ifft.dimension(2), dim2);\n  VERIFY_IS_EQUAL(tensor_after_fft_ifft.dimension(3), dim3);\n\n  for (int i = 0; i < dim0; ++i) {\n    for (int j = 0; j < dim1; ++j) {\n      for (int k = 0; k < dim2; ++k) {\n        for (int l = 0; l < dim3; ++l) {\n          VERIFY_IS_APPROX(static_cast<float>(tensor(i,j,k,l)), static_cast<float>(tensor_after_fft_ifft(i,j,k,l)));\n        }\n      }\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_ifft) {\n  CALL_SUBTEST(test_1D_fft_ifft_invariant<ColMajor>(4));\n  CALL_SUBTEST(test_1D_fft_ifft_invariant<ColMajor>(16));\n  CALL_SUBTEST(test_1D_fft_ifft_invariant<ColMajor>(32));\n  CALL_SUBTEST(test_1D_fft_ifft_invariant<ColMajor>(1024*1024));\n\n  CALL_SUBTEST(test_2D_fft_ifft_invariant<ColMajor>(4,4));\n  CALL_SUBTEST(test_2D_fft_ifft_invariant<ColMajor>(8,16));\n  CALL_SUBTEST(test_2D_fft_ifft_invariant<ColMajor>(16,32));\n  CALL_SUBTEST(test_2D_fft_ifft_invariant<ColMajor>(1024,1024));\n\n  CALL_SUBTEST(test_3D_fft_ifft_invariant<ColMajor>(4,4,4));\n  CALL_SUBTEST(test_3D_fft_ifft_invariant<ColMajor>(8,16,32));\n  CALL_SUBTEST(test_3D_fft_ifft_invariant<ColMajor>(16,4,8));\n  CALL_SUBTEST(test_3D_fft_ifft_invariant<ColMajor>(256,256,256));\n\n  CALL_SUBTEST(test_sub_fft_ifft_invariant<ColMajor>(4,4,4,4));\n  CALL_SUBTEST(test_sub_fft_ifft_invariant<ColMajor>(8,16,32,64));\n  CALL_SUBTEST(test_sub_fft_ifft_invariant<ColMajor>(16,4,8,12));\n  CALL_SUBTEST(test_sub_fft_ifft_invariant<ColMajor>(64,64,64,64));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_image_op_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_image_op_sycl(const Eigen::SyclDevice &sycl_device)\n{\n  IndexType sizeDim1 = 245;\n  IndexType sizeDim2 = 343;\n  IndexType sizeDim3 = 577;\n\n  array<IndexType, 3> input_range ={{sizeDim1, sizeDim2, sizeDim3}};\n  array<IndexType, 3> slice_range ={{sizeDim1-1, sizeDim2, sizeDim3}};\n\n  Tensor<DataType, 3,DataLayout, IndexType> tensor1(input_range);\n  Tensor<DataType, 3,DataLayout, IndexType> tensor2(input_range);\n  Tensor<DataType, 3, DataLayout, IndexType> tensor3(slice_range);\n  Tensor<DataType, 3, DataLayout, IndexType> tensor3_cpu(slice_range);\n\n\n\n  typedef Eigen::DSizes<IndexType, 3> Index3;\n  Index3 strides1(1L,1L, 1L);\n  Index3 indicesStart1(1L, 0L, 0L);\n  Index3 indicesStop1(sizeDim1, sizeDim2, sizeDim3);\n\n  Index3 strides2(1L,1L, 1L);\n  Index3 indicesStart2(0L, 0L, 0L);\n  Index3 indicesStop2(sizeDim1-1, sizeDim2, sizeDim3);\n  Eigen::DSizes<IndexType, 3> sizes(sizeDim1-1,sizeDim2,sizeDim3);\n\n  tensor1.setRandom();\n  tensor2.setRandom();\n\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(tensor1.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(tensor2.size()*sizeof(DataType)));\n  DataType* gpu_data3  = static_cast<DataType*>(sycl_device.allocate(tensor3.size()*sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu1(gpu_data1, input_range);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu2(gpu_data2, input_range);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu3(gpu_data3, slice_range);\n\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor1.data(),(tensor1.size())*sizeof(DataType));\n  sycl_device.memcpyHostToDevice(gpu_data2, tensor2.data(),(tensor2.size())*sizeof(DataType));\n  gpu3.device(sycl_device)= gpu1.slice(indicesStart1, sizes) - gpu2.slice(indicesStart2, sizes);\n  sycl_device.memcpyDeviceToHost(tensor3.data(), gpu_data3,(tensor3.size())*sizeof(DataType));\n\n  tensor3_cpu = tensor1.stridedSlice(indicesStart1,indicesStop1,strides1) - tensor2.stridedSlice(indicesStart2,indicesStop2,strides2);\n\n\n  for (IndexType i = 0; i <slice_range[0] ; ++i) {\n    for (IndexType j = 0; j < slice_range[1]; ++j) {\n      for (IndexType k = 0; k < slice_range[2]; ++k) {\n        VERIFY_IS_EQUAL(tensor3_cpu(i,j,k), tensor3(i,j,k));\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n  sycl_device.deallocate(gpu_data3);\n}\n\n\ntemplate<typename DataType, typename dev_Selector> void sycl_computing_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_image_op_sycl<DataType, RowMajor, int64_t>(sycl_device);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_image_op_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) { \n   CALL_SUBTEST(sycl_computing_test_per_device<float>(device));\n#ifdef EIGEN_SYCL_DOUBLE_SUPPORT\n   CALL_SUBTEST(sycl_computing_test_per_device<double>(device));\n#endif\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_image_patch.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\nvoid test_simple_patch()\n{\n  Tensor<float, 4> tensor(2,3,5,7);\n  tensor.setRandom();\n  Tensor<float, 4, RowMajor> tensor_row_major = tensor.swap_layout();\n  VERIFY_IS_EQUAL(tensor.dimension(0), tensor_row_major.dimension(3));\n  VERIFY_IS_EQUAL(tensor.dimension(1), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor.dimension(2), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor.dimension(3), tensor_row_major.dimension(0));\n\n  // Single pixel patch: ColMajor\n  Tensor<float, 5> single_pixel_patch;\n  single_pixel_patch = tensor.extract_image_patches(1, 1);\n  VERIFY_IS_EQUAL(single_pixel_patch.dimension(0), 2);\n  VERIFY_IS_EQUAL(single_pixel_patch.dimension(1), 1);\n  VERIFY_IS_EQUAL(single_pixel_patch.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_pixel_patch.dimension(3), 3*5);\n  VERIFY_IS_EQUAL(single_pixel_patch.dimension(4), 7);\n\n  // Single pixel patch: RowMajor\n  Tensor<float, 5, RowMajor> single_pixel_patch_row_major;\n  single_pixel_patch_row_major = tensor_row_major.extract_image_patches(1, 1);\n  VERIFY_IS_EQUAL(single_pixel_patch_row_major.dimension(0), 7);\n  VERIFY_IS_EQUAL(single_pixel_patch_row_major.dimension(1), 3*5);\n  VERIFY_IS_EQUAL(single_pixel_patch_row_major.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_pixel_patch_row_major.dimension(3), 1);\n  VERIFY_IS_EQUAL(single_pixel_patch_row_major.dimension(4), 2);\n\n  for (int i = 0; i < tensor.size(); ++i) {\n    // ColMajor\n    if (tensor.data()[i] != single_pixel_patch.data()[i]) {\n      std::cout << \"Mismatch detected at index \" << i << \" : \"\n           << tensor.data()[i] << \" vs \" << single_pixel_patch.data()[i]\n           << std::endl;\n    }\n    VERIFY_IS_EQUAL(single_pixel_patch.data()[i], tensor.data()[i]);\n    // RowMajor\n    if (tensor_row_major.data()[i] != single_pixel_patch_row_major.data()[i]) {\n      std::cout << \"Mismatch detected at index \" << i << \" : \"\n           << tensor.data()[i] << \" vs \"\n           << single_pixel_patch_row_major.data()[i] << std::endl;\n    }\n    VERIFY_IS_EQUAL(single_pixel_patch_row_major.data()[i],\n                    tensor_row_major.data()[i]);\n    VERIFY_IS_EQUAL(tensor.data()[i], tensor_row_major.data()[i]);\n    VERIFY_IS_EQUAL(single_pixel_patch.data()[i],\n                    single_pixel_patch_row_major.data()[i]);\n  }\n\n  // Entire image patch: ColMajor\n  Tensor<float, 5> entire_image_patch;\n  entire_image_patch = tensor.extract_image_patches(3, 5);\n  VERIFY_IS_EQUAL(entire_image_patch.dimension(0), 2);\n  VERIFY_IS_EQUAL(entire_image_patch.dimension(1), 3);\n  VERIFY_IS_EQUAL(entire_image_patch.dimension(2), 5);\n  VERIFY_IS_EQUAL(entire_image_patch.dimension(3), 3*5);\n  VERIFY_IS_EQUAL(entire_image_patch.dimension(4), 7);\n\n  // Entire image patch: RowMajor\n  Tensor<float, 5, RowMajor> entire_image_patch_row_major;\n  entire_image_patch_row_major = tensor_row_major.extract_image_patches(3, 5);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(0), 7);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(1), 3*5);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(2), 5);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(3), 3);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(4), 2);\n\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      int patchId = i+3*j;\n      for (int r = 0; r < 3; ++r) {\n        for (int c = 0; c < 5; ++c) {\n          for (int d = 0; d < 2; ++d) {\n            for (int b = 0; b < 7; ++b) {\n              float expected = 0.0f;\n              float expected_row_major = 0.0f;\n              if (r-1+i >= 0 && c-2+j >= 0 && r-1+i < 3 && c-2+j < 5) {\n                expected = tensor(d, r-1+i, c-2+j, b);\n                expected_row_major = tensor_row_major(b, c-2+j, r-1+i, d);\n              }\n              // ColMajor\n              if (entire_image_patch(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(entire_image_patch(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (entire_image_patch_row_major(b, patchId, c, r, d) !=\n                  expected_row_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j\n                     << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b\n                     << std::endl;\n              }\n              VERIFY_IS_EQUAL(entire_image_patch_row_major(b, patchId, c, r, d),\n                              expected_row_major);\n              // Check that ColMajor and RowMajor agree.\n              VERIFY_IS_EQUAL(expected, expected_row_major);\n            }\n          }\n        }\n      }\n    }\n  }\n\n  // 2D patch: ColMajor\n  Tensor<float, 5> twod_patch;\n  twod_patch = tensor.extract_image_patches(2, 2);\n  VERIFY_IS_EQUAL(twod_patch.dimension(0), 2);\n  VERIFY_IS_EQUAL(twod_patch.dimension(1), 2);\n  VERIFY_IS_EQUAL(twod_patch.dimension(2), 2);\n  VERIFY_IS_EQUAL(twod_patch.dimension(3), 3*5);\n  VERIFY_IS_EQUAL(twod_patch.dimension(4), 7);\n\n  // 2D patch: RowMajor\n  Tensor<float, 5, RowMajor> twod_patch_row_major;\n  twod_patch_row_major = tensor_row_major.extract_image_patches(2, 2);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(0), 7);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(1), 3*5);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(2), 2);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(3), 2);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(4), 2);\n\n\n  // Based on the calculation described in TensorTraits.h, padding happens to be 0.\n  int row_padding = 0;\n  int col_padding = 0;\n  int stride = 1;\n\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      int patchId = i+3*j;\n      for (int r = 0; r < 2; ++r) {\n        for (int c = 0; c < 2; ++c) {\n          for (int d = 0; d < 2; ++d) {\n            for (int b = 0; b < 7; ++b) {\n              float expected = 0.0f;\n              float expected_row_major = 0.0f;\n              int row_offset = r*stride + i - row_padding;\n              int col_offset = c*stride + j - col_padding;\n              // ColMajor\n              if (row_offset >= 0 && col_offset >= 0 && row_offset < tensor.dimension(1) && col_offset < tensor.dimension(2)) {\n                expected = tensor(d, row_offset, col_offset, b);\n              }\n              if (twod_patch(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(twod_patch(d, r, c, patchId, b), expected);\n\n              // RowMajor\n              if (row_offset >= 0 && col_offset >= 0 && row_offset < tensor_row_major.dimension(2) && col_offset < tensor_row_major.dimension(1)) {\n                expected_row_major = tensor_row_major(b, col_offset, row_offset, d);\n\n              }\n              if (twod_patch_row_major(b, patchId, c, r, d) != expected_row_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(twod_patch_row_major(b, patchId, c, r, d), expected_row_major);\n              // Check that ColMajor and RowMajor agree.\n              VERIFY_IS_EQUAL(expected, expected_row_major);\n            }\n          }\n        }\n      }\n    }\n  }\n}\n\n// Verifies VALID padding (no padding) with incrementing values.\nvoid test_patch_padding_valid()\n{\n  int input_depth = 3;\n  int input_rows = 3;\n  int input_cols = 3;\n  int input_batches = 1;\n  int ksize = 2;  // Corresponds to the Rows and Cols for tensor.extract_image_patches<>.\n  int stride = 2;  // Only same stride is supported.\n  Tensor<float, 4> tensor(input_depth, input_rows, input_cols, input_batches);\n  // Initializes tensor with incrementing numbers.\n  for (int i = 0; i < tensor.size(); ++i) {\n    tensor.data()[i] = i + 1;\n  }\n  // ColMajor\n  Tensor<float, 5> result = tensor.extract_image_patches(ksize, ksize, stride, stride, 1, 1, PADDING_VALID);\n\n  VERIFY_IS_EQUAL(result.dimension(0), input_depth);  // depth\n  VERIFY_IS_EQUAL(result.dimension(1), ksize);  // kernel rows\n  VERIFY_IS_EQUAL(result.dimension(2), ksize);  // kernel cols\n  VERIFY_IS_EQUAL(result.dimension(3), 1);  // number of patches\n  VERIFY_IS_EQUAL(result.dimension(4), input_batches);  // number of batches\n\n  // RowMajor\n  Tensor<float, 4, RowMajor> tensor_row_major = tensor.swap_layout();\n  VERIFY_IS_EQUAL(tensor.dimension(0), tensor_row_major.dimension(3));\n  VERIFY_IS_EQUAL(tensor.dimension(1), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor.dimension(2), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor.dimension(3), tensor_row_major.dimension(0));\n\n  Tensor<float, 5, RowMajor> result_row_major = tensor_row_major.extract_image_patches(ksize, ksize, stride, stride, 1, 1, PADDING_VALID);\n  VERIFY_IS_EQUAL(result.dimension(0), result_row_major.dimension(4));\n  VERIFY_IS_EQUAL(result.dimension(1), result_row_major.dimension(3));\n  VERIFY_IS_EQUAL(result.dimension(2), result_row_major.dimension(2));\n  VERIFY_IS_EQUAL(result.dimension(3), result_row_major.dimension(1));\n  VERIFY_IS_EQUAL(result.dimension(4), result_row_major.dimension(0));\n\n  // No padding is carried out.\n  int row_padding = 0;\n  int col_padding = 0;\n\n  for (int i = 0; (i+stride+ksize-1) < input_rows; i += stride) {  // input rows\n    for (int j = 0; (j+stride+ksize-1) < input_cols; j += stride) {  // input cols\n      int patchId = i+input_rows*j;\n      for (int r = 0; r < ksize; ++r) {  // patch rows\n        for (int c = 0; c < ksize; ++c) {  // patch cols\n          for (int d = 0; d < input_depth; ++d) {  // depth\n            for (int b = 0; b < input_batches; ++b) {  // batch\n              float expected = 0.0f;\n              float expected_row_major = 0.0f;\n              int row_offset = r + i - row_padding;\n              int col_offset = c + j - col_padding;\n              if (row_offset >= 0 && col_offset >= 0 && row_offset < input_rows && col_offset < input_cols) {\n                expected = tensor(d, row_offset, col_offset, b);\n                expected_row_major = tensor_row_major(b, col_offset, row_offset, d);\n              }\n              // ColMajor\n              if (result(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (result_row_major(b, patchId, c, r, d) != expected_row_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result_row_major(b, patchId, c, r, d), expected_row_major);\n              // Check that ColMajor and RowMajor agree.\n              VERIFY_IS_EQUAL(expected, expected_row_major);\n            }\n          }\n        }\n      }\n    }\n  }\n}\n\n// Verifies VALID padding (no padding) with the same value.\nvoid test_patch_padding_valid_same_value()\n{\n  int input_depth = 1;\n  int input_rows = 5;\n  int input_cols = 5;\n  int input_batches = 2;\n  int ksize = 3;  // Corresponds to the Rows and Cols for tensor.extract_image_patches<>.\n  int stride = 2;  // Only same stride is supported.\n  // ColMajor\n  Tensor<float, 4> tensor(input_depth, input_rows, input_cols, input_batches);\n  tensor = tensor.constant(11.0f);\n  Tensor<float, 5> result = tensor.extract_image_patches(ksize, ksize, stride, stride, 1, 1, PADDING_VALID);\n\n  VERIFY_IS_EQUAL(result.dimension(0), input_depth);  // depth\n  VERIFY_IS_EQUAL(result.dimension(1), ksize);  // kernel rows\n  VERIFY_IS_EQUAL(result.dimension(2), ksize);  // kernel cols\n  VERIFY_IS_EQUAL(result.dimension(3), 4);  // number of patches\n  VERIFY_IS_EQUAL(result.dimension(4), input_batches);  // number of batches\n\n  // RowMajor\n  Tensor<float, 4, RowMajor> tensor_row_major = tensor.swap_layout();\n  VERIFY_IS_EQUAL(tensor.dimension(0), tensor_row_major.dimension(3));\n  VERIFY_IS_EQUAL(tensor.dimension(1), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor.dimension(2), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor.dimension(3), tensor_row_major.dimension(0));\n\n  Tensor<float, 5, RowMajor> result_row_major = tensor_row_major.extract_image_patches(ksize, ksize, stride, stride, 1, 1, PADDING_VALID);\n  VERIFY_IS_EQUAL(result.dimension(0), result_row_major.dimension(4));\n  VERIFY_IS_EQUAL(result.dimension(1), result_row_major.dimension(3));\n  VERIFY_IS_EQUAL(result.dimension(2), result_row_major.dimension(2));\n  VERIFY_IS_EQUAL(result.dimension(3), result_row_major.dimension(1));\n  VERIFY_IS_EQUAL(result.dimension(4), result_row_major.dimension(0));\n\n  // No padding is carried out.\n  int row_padding = 0;\n  int col_padding = 0;\n\n  for (int i = 0; (i+stride+ksize-1) <= input_rows; i += stride) {  // input rows\n    for (int j = 0; (j+stride+ksize-1) <= input_cols; j += stride) {  // input cols\n      int patchId = i+input_rows*j;\n      for (int r = 0; r < ksize; ++r) {  // patch rows\n        for (int c = 0; c < ksize; ++c) {  // patch cols\n          for (int d = 0; d < input_depth; ++d) {  // depth\n            for (int b = 0; b < input_batches; ++b) {  // batch\n              float expected = 0.0f;\n              float expected_row_major = 0.0f;\n              int row_offset = r + i - row_padding;\n              int col_offset = c + j - col_padding;\n              if (row_offset >= 0 && col_offset >= 0 && row_offset < input_rows && col_offset < input_cols) {\n                expected = tensor(d, row_offset, col_offset, b);\n                expected_row_major = tensor_row_major(b, col_offset, row_offset, d);\n              }\n              // ColMajor\n              if (result(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (result_row_major(b, patchId, c, r, d) != expected_row_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result_row_major(b, patchId, c, r, d), expected_row_major);\n              // Check that ColMajor and RowMajor agree.\n              VERIFY_IS_EQUAL(expected, expected_row_major);\n            }\n          }\n        }\n      }\n    }\n  }\n}\n\n// Verifies SAME padding.\nvoid test_patch_padding_same()\n{\n  int input_depth = 3;\n  int input_rows = 4;\n  int input_cols = 2;\n  int input_batches = 1;\n  int ksize = 2;  // Corresponds to the Rows and Cols for tensor.extract_image_patches<>.\n  int stride = 2;  // Only same stride is supported.\n  // ColMajor\n  Tensor<float, 4> tensor(input_depth, input_rows, input_cols, input_batches);\n  // Initializes tensor with incrementing numbers.\n  for (int i = 0; i < tensor.size(); ++i) {\n    tensor.data()[i] = i + 1;\n  }\n  Tensor<float, 5> result = tensor.extract_image_patches(ksize, ksize, stride, stride, PADDING_SAME);\n\n  VERIFY_IS_EQUAL(result.dimension(0), input_depth);  // depth\n  VERIFY_IS_EQUAL(result.dimension(1), ksize);  // kernel rows\n  VERIFY_IS_EQUAL(result.dimension(2), ksize);  // kernel cols\n  VERIFY_IS_EQUAL(result.dimension(3), 2);  // number of patches\n  VERIFY_IS_EQUAL(result.dimension(4), input_batches);  // number of batches\n\n  // RowMajor\n  Tensor<float, 4, RowMajor> tensor_row_major = tensor.swap_layout();\n  VERIFY_IS_EQUAL(tensor.dimension(0), tensor_row_major.dimension(3));\n  VERIFY_IS_EQUAL(tensor.dimension(1), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor.dimension(2), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor.dimension(3), tensor_row_major.dimension(0));\n\n  Tensor<float, 5, RowMajor> result_row_major = tensor_row_major.extract_image_patches(ksize, ksize, stride, stride, PADDING_SAME);\n  VERIFY_IS_EQUAL(result.dimension(0), result_row_major.dimension(4));\n  VERIFY_IS_EQUAL(result.dimension(1), result_row_major.dimension(3));\n  VERIFY_IS_EQUAL(result.dimension(2), result_row_major.dimension(2));\n  VERIFY_IS_EQUAL(result.dimension(3), result_row_major.dimension(1));\n  VERIFY_IS_EQUAL(result.dimension(4), result_row_major.dimension(0));\n\n  // Based on the calculation described in TensorTraits.h, padding happens to be\n  // 0.\n  int row_padding = 0;\n  int col_padding = 0;\n\n  for (int i = 0; (i+stride+ksize-1) <= input_rows; i += stride) {  // input rows\n    for (int j = 0; (j+stride+ksize-1) <= input_cols; j += stride) {  // input cols\n      int patchId = i+input_rows*j;\n      for (int r = 0; r < ksize; ++r) {  // patch rows\n        for (int c = 0; c < ksize; ++c) {  // patch cols\n          for (int d = 0; d < input_depth; ++d) {  // depth\n            for (int b = 0; b < input_batches; ++b) {  // batch\n              float expected = 0.0f;\n              float expected_row_major = 0.0f;\n              int row_offset = r*stride + i - row_padding;\n              int col_offset = c*stride + j - col_padding;\n              if (row_offset >= 0 && col_offset >= 0 && row_offset < input_rows && col_offset < input_cols) {\n                expected = tensor(d, row_offset, col_offset, b);\n                expected_row_major = tensor_row_major(b, col_offset, row_offset, d);\n              }\n              // ColMajor\n              if (result(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (result_row_major(b, patchId, c, r, d) != expected_row_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result_row_major(b, patchId, c, r, d), expected_row_major);\n              // Check that ColMajor and RowMajor agree.\n              VERIFY_IS_EQUAL(expected, expected_row_major);\n            }\n          }\n        }\n      }\n    }\n  }\n}\n\n// Verifies that SAME padding, when computed as negative values, will be clipped\n// to zero.\nvoid test_patch_padding_same_negative_padding_clip_to_zero() {\n  int input_depth = 1;\n  int input_rows = 15;\n  int input_cols = 1;\n  int input_batches = 1;\n  int ksize = 1;  // Corresponds to the Rows and Cols for\n                  // tensor.extract_image_patches<>.\n  int row_stride = 5;\n  int col_stride = 1;\n  // ColMajor\n  Tensor<float, 4> tensor(input_depth, input_rows, input_cols, input_batches);\n  // Initializes tensor with incrementing numbers.\n  for (int i = 0; i < tensor.size(); ++i) {\n    tensor.data()[i] = i + 1;\n  }\n  Tensor<float, 5> result = tensor.extract_image_patches(\n      ksize, ksize, row_stride, col_stride, 1, 1, PADDING_SAME);\n  // row padding will be computed as -2 originally and then be clipped to 0.\n  VERIFY_IS_EQUAL(result.coeff(0), 1.0f);\n  VERIFY_IS_EQUAL(result.coeff(1), 6.0f);\n  VERIFY_IS_EQUAL(result.coeff(2), 11.0f);\n\n  VERIFY_IS_EQUAL(result.dimension(0), input_depth);    // depth\n  VERIFY_IS_EQUAL(result.dimension(1), ksize);          // kernel rows\n  VERIFY_IS_EQUAL(result.dimension(2), ksize);          // kernel cols\n  VERIFY_IS_EQUAL(result.dimension(3), 3);              // number of patches\n  VERIFY_IS_EQUAL(result.dimension(4), input_batches);  // number of batches\n\n  // RowMajor\n  Tensor<float, 4, RowMajor> tensor_row_major = tensor.swap_layout();\n  VERIFY_IS_EQUAL(tensor.dimension(0), tensor_row_major.dimension(3));\n  VERIFY_IS_EQUAL(tensor.dimension(1), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor.dimension(2), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor.dimension(3), tensor_row_major.dimension(0));\n\n  Tensor<float, 5, RowMajor> result_row_major =\n      tensor_row_major.extract_image_patches(ksize, ksize, row_stride,\n                                             col_stride, 1, 1, PADDING_SAME);\n  VERIFY_IS_EQUAL(result_row_major.coeff(0), 1.0f);\n  VERIFY_IS_EQUAL(result_row_major.coeff(1), 6.0f);\n  VERIFY_IS_EQUAL(result_row_major.coeff(2), 11.0f);\n\n  VERIFY_IS_EQUAL(result.dimension(0), result_row_major.dimension(4));\n  VERIFY_IS_EQUAL(result.dimension(1), result_row_major.dimension(3));\n  VERIFY_IS_EQUAL(result.dimension(2), result_row_major.dimension(2));\n  VERIFY_IS_EQUAL(result.dimension(3), result_row_major.dimension(1));\n  VERIFY_IS_EQUAL(result.dimension(4), result_row_major.dimension(0));\n}\n\nvoid test_patch_no_extra_dim()\n{\n  Tensor<float, 3> tensor(2,3,5);\n  tensor.setRandom();\n  Tensor<float, 3, RowMajor> tensor_row_major = tensor.swap_layout();\n  VERIFY_IS_EQUAL(tensor.dimension(0), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor.dimension(1), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor.dimension(2), tensor_row_major.dimension(0));\n\n  // Single pixel patch: ColMajor\n  Tensor<float, 4> single_pixel_patch;\n  single_pixel_patch = tensor.extract_image_patches(1, 1);\n  VERIFY_IS_EQUAL(single_pixel_patch.dimension(0), 2);\n  VERIFY_IS_EQUAL(single_pixel_patch.dimension(1), 1);\n  VERIFY_IS_EQUAL(single_pixel_patch.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_pixel_patch.dimension(3), 3*5);\n\n  // Single pixel patch: RowMajor\n  Tensor<float, 4, RowMajor> single_pixel_patch_row_major;\n  single_pixel_patch_row_major = tensor_row_major.extract_image_patches(1, 1);\n  VERIFY_IS_EQUAL(single_pixel_patch_row_major.dimension(0), 3*5);\n  VERIFY_IS_EQUAL(single_pixel_patch_row_major.dimension(1), 1);\n  VERIFY_IS_EQUAL(single_pixel_patch_row_major.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_pixel_patch_row_major.dimension(3), 2);\n\n  for (int i = 0; i < tensor.size(); ++i) {\n    // ColMajor\n    if (tensor.data()[i] != single_pixel_patch.data()[i]) {\n      std::cout << \"Mismatch detected at index \" << i << \" : \" << tensor.data()[i] << \" vs \" << single_pixel_patch.data()[i] << std::endl;\n    }\n    VERIFY_IS_EQUAL(single_pixel_patch.data()[i], tensor.data()[i]);\n    // RowMajor\n    if (tensor_row_major.data()[i] != single_pixel_patch_row_major.data()[i]) {\n      std::cout << \"Mismatch detected at index \" << i << \" : \"\n           << tensor.data()[i] << \" vs \"\n           << single_pixel_patch_row_major.data()[i] << std::endl;\n    }\n    VERIFY_IS_EQUAL(single_pixel_patch_row_major.data()[i],\n                    tensor_row_major.data()[i]);\n    VERIFY_IS_EQUAL(tensor.data()[i], tensor_row_major.data()[i]);\n    VERIFY_IS_EQUAL(single_pixel_patch.data()[i],\n                    single_pixel_patch_row_major.data()[i]);\n  }\n\n  // Entire image patch: ColMajor\n  Tensor<float, 4> entire_image_patch;\n  entire_image_patch = tensor.extract_image_patches(3, 5);\n  VERIFY_IS_EQUAL(entire_image_patch.dimension(0), 2);\n  VERIFY_IS_EQUAL(entire_image_patch.dimension(1), 3);\n  VERIFY_IS_EQUAL(entire_image_patch.dimension(2), 5);\n  VERIFY_IS_EQUAL(entire_image_patch.dimension(3), 3*5);\n\n  // Entire image patch: RowMajor\n  Tensor<float, 4, RowMajor> entire_image_patch_row_major;\n  entire_image_patch_row_major = tensor_row_major.extract_image_patches(3, 5);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(0), 3*5);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(1), 5);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(2), 3);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(3), 2);\n\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      int patchId = i+3*j;\n      for (int r = 0; r < 3; ++r) {\n        for (int c = 0; c < 5; ++c) {\n          for (int d = 0; d < 2; ++d) {\n            float expected = 0.0f;\n            float expected_row_major = 0.0f;\n            if (r-1+i >= 0 && c-2+j >= 0 && r-1+i < 3 && c-2+j < 5) {\n              expected = tensor(d, r-1+i, c-2+j);\n              expected_row_major = tensor_row_major(c-2+j, r-1+i, d);\n            }\n            // ColMajor\n            if (entire_image_patch(d, r, c, patchId) != expected) {\n              std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << std::endl;\n            }\n            VERIFY_IS_EQUAL(entire_image_patch(d, r, c, patchId), expected);\n            // RowMajor\n            if (entire_image_patch_row_major(patchId, c, r, d) !=\n                expected_row_major) {\n              std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << std::endl;\n            }\n            VERIFY_IS_EQUAL(entire_image_patch_row_major(patchId, c, r, d),\n                            expected_row_major);\n            // Check that ColMajor and RowMajor agree.\n            VERIFY_IS_EQUAL(expected, expected_row_major);\n          }\n        }\n      }\n    }\n  }\n\n  // 2D patch: ColMajor\n  Tensor<float, 4> twod_patch;\n  twod_patch = tensor.extract_image_patches(2, 2);\n  VERIFY_IS_EQUAL(twod_patch.dimension(0), 2);\n  VERIFY_IS_EQUAL(twod_patch.dimension(1), 2);\n  VERIFY_IS_EQUAL(twod_patch.dimension(2), 2);\n  VERIFY_IS_EQUAL(twod_patch.dimension(3), 3*5);\n\n  // 2D patch: RowMajor\n  Tensor<float, 4, RowMajor> twod_patch_row_major;\n  twod_patch_row_major = tensor_row_major.extract_image_patches(2, 2);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(0), 3*5);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(1), 2);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(2), 2);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(3), 2);\n\n  // Based on the calculation described in TensorTraits.h, padding happens to be 0.\n  int row_padding = 0;\n  int col_padding = 0;\n  int stride = 1;\n\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      int patchId = i+3*j;\n      for (int r = 0; r < 2; ++r) {\n        for (int c = 0; c < 2; ++c) {\n          for (int d = 0; d < 2; ++d) {\n            float expected = 0.0f;\n            float expected_row_major = 0.0f;\n            int row_offset = r*stride + i - row_padding;\n            int col_offset = c*stride + j - col_padding;\n            // ColMajor\n            if (row_offset >= 0 && col_offset >= 0 && row_offset < tensor.dimension(1) && col_offset < tensor.dimension(2)) {\n              expected = tensor(d, row_offset, col_offset);\n            }\n            if (twod_patch(d, r, c, patchId) != expected) {\n              std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << std::endl;\n            }\n            VERIFY_IS_EQUAL(twod_patch(d, r, c, patchId), expected);\n            // RowMajor\n            if (row_offset >= 0 && col_offset >= 0 && row_offset < tensor_row_major.dimension(1) && col_offset < tensor_row_major.dimension(0)) {\n              expected_row_major = tensor_row_major(col_offset, row_offset, d);\n            }\n            if (twod_patch_row_major(patchId, c, r, d) != expected_row_major) {\n              std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << std::endl;\n            }\n            VERIFY_IS_EQUAL(twod_patch_row_major(patchId, c, r, d), expected_row_major);\n            // Check that ColMajor and RowMajor agree.\n            VERIFY_IS_EQUAL(expected, expected_row_major);\n          }\n        }\n      }\n    }\n  }\n}\n\nvoid test_imagenet_patches()\n{\n  // Test the code on typical configurations used by the 'imagenet' benchmarks at\n  // https://github.com/soumith/convnet-benchmarks\n  // ColMajor\n  Tensor<float, 4> l_in(3, 128, 128, 16);\n  l_in.setRandom();\n  Tensor<float, 5> l_out = l_in.extract_image_patches(11, 11);\n  VERIFY_IS_EQUAL(l_out.dimension(0), 3);\n  VERIFY_IS_EQUAL(l_out.dimension(1), 11);\n  VERIFY_IS_EQUAL(l_out.dimension(2), 11);\n  VERIFY_IS_EQUAL(l_out.dimension(3), 128*128);\n  VERIFY_IS_EQUAL(l_out.dimension(4), 16);\n\n  // RowMajor\n  Tensor<float, 5, RowMajor> l_out_row_major = l_in.swap_layout().extract_image_patches(11, 11);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(0), 16);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(1), 128*128);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(2), 11);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(3), 11);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(4), 3);\n\n  for (int b = 0; b < 16; ++b) {\n    for (int i = 0; i < 128; ++i) {\n      for (int j = 0; j < 128; ++j) {\n        int patchId = i+128*j;\n        for (int c = 0; c < 11; ++c) {\n          for (int r = 0; r < 11; ++r) {\n            for (int d = 0; d < 3; ++d) {\n              float expected = 0.0f;\n              if (r-5+i >= 0 && c-5+j >= 0 && r-5+i < 128 && c-5+j < 128) {\n                expected = l_in(d, r-5+i, c-5+j, b);\n              }\n              // ColMajor\n              if (l_out(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (l_out_row_major(b, patchId, c, r, d) !=\n                  expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j\n                     << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b\n                     << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_row_major(b, patchId, c, r, d),\n                              expected);\n            }\n          }\n        }\n      }\n    }\n  }\n\n  // ColMajor\n  l_in.resize(16, 64, 64, 32);\n  l_in.setRandom();\n  l_out = l_in.extract_image_patches(9, 9);\n  VERIFY_IS_EQUAL(l_out.dimension(0), 16);\n  VERIFY_IS_EQUAL(l_out.dimension(1), 9);\n  VERIFY_IS_EQUAL(l_out.dimension(2), 9);\n  VERIFY_IS_EQUAL(l_out.dimension(3), 64*64);\n  VERIFY_IS_EQUAL(l_out.dimension(4), 32);\n\n  // RowMajor\n  l_out_row_major = l_in.swap_layout().extract_image_patches(9, 9);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(0), 32);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(1), 64*64);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(2), 9);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(3), 9);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(4), 16);\n\n  for (int b = 0; b < 32; ++b) {\n    for (int i = 0; i < 64; ++i) {\n      for (int j = 0; j < 64; ++j) {\n        int patchId = i+64*j;\n        for (int c = 0; c < 9; ++c) {\n          for (int r = 0; r < 9; ++r) {\n            for (int d = 0; d < 16; ++d) {\n              float expected = 0.0f;\n              if (r-4+i >= 0 && c-4+j >= 0 && r-4+i < 64 && c-4+j < 64) {\n                expected = l_in(d, r-4+i, c-4+j, b);\n              }\n              // ColMajor\n              if (l_out(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (l_out_row_major(b, patchId, c, r, d) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_row_major(b, patchId, c, r, d), expected);\n            }\n          }\n        }\n      }\n    }\n  }\n\n  // ColMajor\n  l_in.resize(32, 16, 16, 32);\n  l_in.setRandom();\n  l_out = l_in.extract_image_patches(7, 7);\n  VERIFY_IS_EQUAL(l_out.dimension(0), 32);\n  VERIFY_IS_EQUAL(l_out.dimension(1), 7);\n  VERIFY_IS_EQUAL(l_out.dimension(2), 7);\n  VERIFY_IS_EQUAL(l_out.dimension(3), 16*16);\n  VERIFY_IS_EQUAL(l_out.dimension(4), 32);\n\n  // RowMajor\n  l_out_row_major = l_in.swap_layout().extract_image_patches(7, 7);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(0), 32);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(1), 16*16);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(2), 7);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(3), 7);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(4), 32);\n\n  for (int b = 0; b < 32; ++b) {\n    for (int i = 0; i < 16; ++i) {\n      for (int j = 0; j < 16; ++j) {\n        int patchId = i+16*j;\n        for (int c = 0; c < 7; ++c) {\n          for (int r = 0; r < 7; ++r) {\n            for (int d = 0; d < 32; ++d) {\n              float expected = 0.0f;\n              if (r-3+i >= 0 && c-3+j >= 0 && r-3+i < 16 && c-3+j < 16) {\n                expected = l_in(d, r-3+i, c-3+j, b);\n              }\n              // ColMajor\n              if (l_out(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (l_out_row_major(b, patchId, c, r, d) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_row_major(b, patchId, c, r, d), expected);\n            }\n          }\n        }\n      }\n    }\n  }\n\n  // ColMajor\n  l_in.resize(64, 13, 13, 32);\n  l_in.setRandom();\n  l_out = l_in.extract_image_patches(3, 3);\n  VERIFY_IS_EQUAL(l_out.dimension(0), 64);\n  VERIFY_IS_EQUAL(l_out.dimension(1), 3);\n  VERIFY_IS_EQUAL(l_out.dimension(2), 3);\n  VERIFY_IS_EQUAL(l_out.dimension(3), 13*13);\n  VERIFY_IS_EQUAL(l_out.dimension(4), 32);\n\n  // RowMajor\n  l_out_row_major = l_in.swap_layout().extract_image_patches(3, 3);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(0), 32);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(1), 13*13);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(2), 3);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(3), 3);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(4), 64);\n\n  for (int b = 0; b < 32; ++b) {\n    for (int i = 0; i < 13; ++i) {\n      for (int j = 0; j < 13; ++j) {\n        int patchId = i+13*j;\n        for (int c = 0; c < 3; ++c) {\n          for (int r = 0; r < 3; ++r) {\n            for (int d = 0; d < 64; ++d) {\n              float expected = 0.0f;\n              if (r-1+i >= 0 && c-1+j >= 0 && r-1+i < 13 && c-1+j < 13) {\n                expected = l_in(d, r-1+i, c-1+j, b);\n              }\n              // ColMajor\n              if (l_out(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (l_out_row_major(b, patchId, c, r, d) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_row_major(b, patchId, c, r, d), expected);\n            }\n          }\n        }\n      }\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_image_patch)\n{\n  CALL_SUBTEST_1(test_simple_patch());\n  CALL_SUBTEST_2(test_patch_no_extra_dim());\n  CALL_SUBTEST_3(test_patch_padding_valid());\n  CALL_SUBTEST_4(test_patch_padding_valid_same_value());\n  CALL_SUBTEST_5(test_patch_padding_same());\n  CALL_SUBTEST_6(test_imagenet_patches());\n  CALL_SUBTEST_7(test_patch_padding_same_negative_padding_clip_to_zero());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_image_patch_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nstatic const int DataLayout = ColMajor;\n\ntemplate <typename DataType, typename IndexType>\nstatic void test_simple_image_patch_sycl(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  array<IndexType, 4> tensorColMajorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  array<IndexType, 4> tensorRowMajorRange = {{sizeDim4, sizeDim3, sizeDim2, sizeDim1}};\n  Tensor<DataType, 4, DataLayout,IndexType> tensor_col_major(tensorColMajorRange);\n  Tensor<DataType, 4, RowMajor,IndexType> tensor_row_major(tensorRowMajorRange);\n  tensor_col_major.setRandom();\n\n  DataType* gpu_data_col_major  = static_cast<DataType*>(sycl_device.allocate(tensor_col_major.size()*sizeof(DataType)));\n  DataType* gpu_data_row_major  = static_cast<DataType*>(sycl_device.allocate(tensor_row_major.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 4, ColMajor, IndexType>> gpu_col_major(gpu_data_col_major, tensorColMajorRange);\n  TensorMap<Tensor<DataType, 4, RowMajor, IndexType>> gpu_row_major(gpu_data_row_major, tensorRowMajorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_col_major, tensor_col_major.data(),(tensor_col_major.size())*sizeof(DataType));\n  gpu_row_major.device(sycl_device)=gpu_col_major.swap_layout();\n  sycl_device.memcpyDeviceToHost(tensor_row_major.data(), gpu_data_row_major, (tensor_col_major.size())*sizeof(DataType));\n\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(0), tensor_row_major.dimension(3));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(1), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(2), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(3), tensor_row_major.dimension(0));\n\n  // Single pixel patch: ColMajor\n  array<IndexType, 5> patchColMajorTensorRange={{sizeDim1, 1, 1, sizeDim2*sizeDim3, sizeDim4}};\n  Tensor<DataType, 5, DataLayout,IndexType> single_patch_col_major(patchColMajorTensorRange);\n  size_t patchTensorBuffSize =single_patch_col_major.size()*sizeof(DataType);\n  DataType* gpu_data_single_patch_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_single_patch_col_major(gpu_data_single_patch_col_major, patchColMajorTensorRange);\n  gpu_single_patch_col_major.device(sycl_device)=gpu_col_major.extract_image_patches(1, 1);\n  sycl_device.memcpyDeviceToHost(single_patch_col_major.data(), gpu_data_single_patch_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(single_patch_col_major.dimension(0), 2);\n  VERIFY_IS_EQUAL(single_patch_col_major.dimension(1), 1);\n  VERIFY_IS_EQUAL(single_patch_col_major.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_patch_col_major.dimension(3), 3*5);\n  VERIFY_IS_EQUAL(single_patch_col_major.dimension(4), 7);\n\n  // Single pixel patch: RowMajor\n  array<IndexType, 5> patchRowMajorTensorRange={{sizeDim4, sizeDim2*sizeDim3, 1, 1, sizeDim1}};\n  Tensor<DataType, 5, RowMajor,IndexType> single_patch_row_major(patchRowMajorTensorRange);\n  patchTensorBuffSize =single_patch_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_single_patch_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, RowMajor,IndexType>> gpu_single_patch_row_major(gpu_data_single_patch_row_major, patchRowMajorTensorRange);\n  gpu_single_patch_row_major.device(sycl_device)=gpu_row_major.extract_image_patches(1, 1);\n  sycl_device.memcpyDeviceToHost(single_patch_row_major.data(), gpu_data_single_patch_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(single_patch_row_major.dimension(0), 7);\n  VERIFY_IS_EQUAL(single_patch_row_major.dimension(1), 3*5);\n  VERIFY_IS_EQUAL(single_patch_row_major.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_patch_row_major.dimension(3), 1);\n  VERIFY_IS_EQUAL(single_patch_row_major.dimension(4), 2);\n\n  for (IndexType i = 0; i < tensor_col_major.size(); ++i) {\n    // ColMajor\n    if (tensor_col_major.data()[i] != single_patch_col_major.data()[i]) {\n      std::cout << \"Mismatch detected at index colmajor \" << i << \" : \"\n           << tensor_col_major.data()[i] << \" vs \" << single_patch_col_major.data()[i]\n           << std::endl;\n    }\n    VERIFY_IS_EQUAL(single_patch_col_major.data()[i], tensor_col_major.data()[i]);\n    // RowMajor\n    if (tensor_row_major.data()[i] != single_patch_row_major.data()[i]) {\n      std::cout << \"Mismatch detected at index row major\" << i << \" : \"\n           << tensor_row_major.data()[i] << \" vs \"\n           << single_patch_row_major.data()[i] << std::endl;\n    }\n    VERIFY_IS_EQUAL(single_patch_row_major.data()[i],\n                    tensor_row_major.data()[i]);\n    VERIFY_IS_EQUAL(tensor_col_major.data()[i], tensor_row_major.data()[i]);\n    VERIFY_IS_EQUAL(single_patch_col_major.data()[i],\n                    single_patch_row_major.data()[i]);\n  }\n\n\n  // Entire image patch: ColMajor\n  patchColMajorTensorRange={{sizeDim1, sizeDim2, sizeDim3, sizeDim2*sizeDim3, sizeDim4}};\n  Tensor<DataType, 5, DataLayout,IndexType> entire_image_patch_col_major(patchColMajorTensorRange);\n  patchTensorBuffSize =entire_image_patch_col_major.size()*sizeof(DataType);\n  DataType* gpu_data_entire_image_patch_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_entire_image_patch_col_major(gpu_data_entire_image_patch_col_major, patchColMajorTensorRange);\n  gpu_entire_image_patch_col_major.device(sycl_device)=gpu_col_major.extract_image_patches(3, 5);\n  sycl_device.memcpyDeviceToHost(entire_image_patch_col_major.data(), gpu_data_entire_image_patch_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(entire_image_patch_col_major.dimension(0), 2);\n  VERIFY_IS_EQUAL(entire_image_patch_col_major.dimension(1), 3);\n  VERIFY_IS_EQUAL(entire_image_patch_col_major.dimension(2), 5);\n  VERIFY_IS_EQUAL(entire_image_patch_col_major.dimension(3), 3*5);\n  VERIFY_IS_EQUAL(entire_image_patch_col_major.dimension(4), 7);\n\n  // Entire image patch: RowMajor\n  patchRowMajorTensorRange={{sizeDim4, sizeDim2*sizeDim3, sizeDim3, sizeDim2, sizeDim1}};\n  Tensor<DataType, 5, RowMajor,IndexType> entire_image_patch_row_major(patchRowMajorTensorRange);\n  patchTensorBuffSize =entire_image_patch_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_entire_image_patch_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, RowMajor,IndexType>> gpu_entire_image_patch_row_major(gpu_data_entire_image_patch_row_major, patchRowMajorTensorRange);\n  gpu_entire_image_patch_row_major.device(sycl_device)=gpu_row_major.extract_image_patches(3, 5);\n  sycl_device.memcpyDeviceToHost(entire_image_patch_row_major.data(), gpu_data_entire_image_patch_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(0), 7);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(1), 3*5);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(2), 5);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(3), 3);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(4), 2);\n\n  for (IndexType i = 0; i < 3; ++i) {\n    for (IndexType j = 0; j < 5; ++j) {\n      IndexType patchId = i+3*j;\n      for (IndexType r = 0; r < 3; ++r) {\n        for (IndexType c = 0; c < 5; ++c) {\n          for (IndexType d = 0; d < 2; ++d) {\n            for (IndexType b = 0; b < 7; ++b) {\n              DataType expected_col_major = 0.0f;\n              DataType expected_row_major = 0.0f;\n              if (r-1+i >= 0 && c-2+j >= 0 && r-1+i < 3 && c-2+j < 5) {\n                expected_col_major = tensor_col_major(d, r-1+i, c-2+j, b);\n                expected_row_major = tensor_row_major(b, c-2+j, r-1+i, d);\n              }\n              // ColMajor\n              if (entire_image_patch_col_major(d, r, c, patchId, b) != expected_col_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(entire_image_patch_col_major(d, r, c, patchId, b), expected_col_major);\n              // RowMajor\n              if (entire_image_patch_row_major(b, patchId, c, r, d) !=\n                  expected_row_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j\n                     << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b\n                     << std::endl;\n              }\n              VERIFY_IS_EQUAL(entire_image_patch_row_major(b, patchId, c, r, d),\n                              expected_row_major);\n              // Check that ColMajor and RowMajor agree.\n              VERIFY_IS_EQUAL(expected_col_major, expected_row_major);\n            }\n          }\n        }\n      }\n    }\n  }\n\n  // 2D patch: ColMajor\n  patchColMajorTensorRange={{sizeDim1, 2, 2, sizeDim2*sizeDim3, sizeDim4}};\n  Tensor<DataType, 5, DataLayout,IndexType> twod_patch_col_major(patchColMajorTensorRange);\n  patchTensorBuffSize =twod_patch_col_major.size()*sizeof(DataType);\n  DataType* gpu_data_twod_patch_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_twod_patch_col_major(gpu_data_twod_patch_col_major, patchColMajorTensorRange);\n  gpu_twod_patch_col_major.device(sycl_device)=gpu_col_major.extract_image_patches(2, 2);\n  sycl_device.memcpyDeviceToHost(twod_patch_col_major.data(), gpu_data_twod_patch_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(twod_patch_col_major.dimension(0), 2);\n  VERIFY_IS_EQUAL(twod_patch_col_major.dimension(1), 2);\n  VERIFY_IS_EQUAL(twod_patch_col_major.dimension(2), 2);\n  VERIFY_IS_EQUAL(twod_patch_col_major.dimension(3), 3*5);\n  VERIFY_IS_EQUAL(twod_patch_col_major.dimension(4), 7);\n\n  // 2D patch: RowMajor\n  patchRowMajorTensorRange={{sizeDim4, sizeDim2*sizeDim3, 2, 2, sizeDim1}};\n  Tensor<DataType, 5, RowMajor,IndexType> twod_patch_row_major(patchRowMajorTensorRange);\n  patchTensorBuffSize =twod_patch_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_twod_patch_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, RowMajor,IndexType>> gpu_twod_patch_row_major(gpu_data_twod_patch_row_major, patchRowMajorTensorRange);\n  gpu_twod_patch_row_major.device(sycl_device)=gpu_row_major.extract_image_patches(2, 2);\n  sycl_device.memcpyDeviceToHost(twod_patch_row_major.data(), gpu_data_twod_patch_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(0), 7);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(1), 3*5);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(2), 2);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(3), 2);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(4), 2);\n\n\n  // Based on the calculation described in TensorTraits.h, padding happens to be 0.\n  IndexType row_padding = 0;\n  IndexType col_padding = 0;\n  IndexType stride = 1;\n\n  for (IndexType i = 0; i < 3; ++i) {\n    for (IndexType j = 0; j < 5; ++j) {\n      IndexType patchId = i+3*j;\n      for (IndexType r = 0; r < 2; ++r) {\n        for (IndexType c = 0; c < 2; ++c) {\n          for (IndexType d = 0; d < 2; ++d) {\n            for (IndexType b = 0; b < 7; ++b) {\n              DataType expected_col_major = 0.0f;\n              DataType expected_row_major = 0.0f;\n              IndexType row_offset = r*stride + i - row_padding;\n              IndexType col_offset = c*stride + j - col_padding;\n              // ColMajor\n              if (row_offset >= 0 && col_offset >= 0 && row_offset < tensor_col_major.dimension(1) && col_offset < tensor_col_major.dimension(2)) {\n                expected_col_major = tensor_col_major(d, row_offset, col_offset, b);\n              }\n              if (twod_patch_col_major(d, r, c, patchId, b) != expected_col_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(twod_patch_col_major(d, r, c, patchId, b), expected_col_major);\n\n              // RowMajor\n              if (row_offset >= 0 && col_offset >= 0 && row_offset < tensor_row_major.dimension(2) && col_offset < tensor_row_major.dimension(1)) {\n                expected_row_major = tensor_row_major(b, col_offset, row_offset, d);\n\n              }\n              if (twod_patch_row_major(b, patchId, c, r, d) != expected_row_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(twod_patch_row_major(b, patchId, c, r, d), expected_row_major);\n              // Check that ColMajor and RowMajor agree.\n              VERIFY_IS_EQUAL(expected_col_major, expected_row_major);\n            }\n          }\n        }\n      }\n    }\n  }\n\n  sycl_device.deallocate(gpu_data_col_major);\n  sycl_device.deallocate(gpu_data_row_major);\n  sycl_device.deallocate(gpu_data_single_patch_col_major);\n  sycl_device.deallocate(gpu_data_single_patch_row_major);\n  sycl_device.deallocate(gpu_data_entire_image_patch_col_major);\n  sycl_device.deallocate(gpu_data_entire_image_patch_row_major);\n  sycl_device.deallocate(gpu_data_twod_patch_col_major);\n  sycl_device.deallocate(gpu_data_twod_patch_row_major);\n\n}\n\n\n// Verifies VALID padding (no padding) with incrementing values.\ntemplate <typename DataType, typename IndexType>\nstatic void test_patch_padding_valid_sycl(const Eigen::SyclDevice& sycl_device){\n  IndexType input_depth = 3;\n  IndexType input_rows = 3;\n  IndexType input_cols = 3;\n  IndexType input_batches = 1;\n  IndexType ksize = 2;  // Corresponds to the Rows and Cols for tensor.extract_image_patches<>.\n  IndexType stride = 2;  // Only same stride is supported.\n\n  array<IndexType, 4> tensorColMajorRange = {{input_depth, input_rows, input_cols, input_batches}};\n  array<IndexType, 4> tensorRowMajorRange = {{input_batches, input_cols, input_rows, input_depth}};\n  Tensor<DataType, 4, DataLayout,IndexType> tensor_col_major(tensorColMajorRange);\n  Tensor<DataType, 4, RowMajor,IndexType> tensor_row_major(tensorRowMajorRange);\n\n  DataType* gpu_data_col_major  = static_cast<DataType*>(sycl_device.allocate(tensor_col_major.size()*sizeof(DataType)));\n  DataType* gpu_data_row_major  = static_cast<DataType*>(sycl_device.allocate(tensor_row_major.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 4, ColMajor, IndexType>> gpu_col_major(gpu_data_col_major, tensorColMajorRange);\n  TensorMap<Tensor<DataType, 4, RowMajor, IndexType>> gpu_row_major(gpu_data_row_major, tensorRowMajorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_col_major, tensor_col_major.data(),(tensor_col_major.size())*sizeof(DataType));\n  gpu_row_major.device(sycl_device)=gpu_col_major.swap_layout();\n  sycl_device.memcpyDeviceToHost(tensor_row_major.data(), gpu_data_row_major, (tensor_col_major.size())*sizeof(DataType));\n\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(0), tensor_row_major.dimension(3));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(1), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(2), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(3), tensor_row_major.dimension(0));\n\n  // Initializes tensor with incrementing numbers.\n  for (IndexType i = 0; i < tensor_col_major.size(); ++i) {\n    tensor_col_major.data()[i] = i + 1;\n  }\n  // ColMajor\n  array<IndexType, 5> patchColMajorTensorRange={{input_depth, ksize, ksize, 1, input_batches}};\n  Tensor<DataType, 5, DataLayout,IndexType> result_col_major(patchColMajorTensorRange);\n  size_t patchTensorBuffSize =result_col_major.size()*sizeof(DataType);\n  DataType* gpu_data_result_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_result_col_major(gpu_data_result_col_major, patchColMajorTensorRange);\n  gpu_result_col_major.device(sycl_device)=gpu_col_major.extract_image_patches(ksize, ksize, stride, stride, 1, 1, PADDING_VALID);\n  sycl_device.memcpyDeviceToHost(result_col_major.data(), gpu_data_result_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(result_col_major.dimension(0), input_depth);  // depth\n  VERIFY_IS_EQUAL(result_col_major.dimension(1), ksize);  // kernel rows\n  VERIFY_IS_EQUAL(result_col_major.dimension(2), ksize);  // kernel cols\n  VERIFY_IS_EQUAL(result_col_major.dimension(3), 1);  // number of patches\n  VERIFY_IS_EQUAL(result_col_major.dimension(4), input_batches);  // number of batches\n\n  // RowMajor\n  array<IndexType, 5> patchRowMajorTensorRange={{input_batches, 1, ksize, ksize, input_depth }};\n  Tensor<DataType, 5, RowMajor,IndexType> result_row_major(patchRowMajorTensorRange);\n  patchTensorBuffSize =result_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_result_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, RowMajor,IndexType>> gpu_result_row_major(gpu_data_result_row_major, patchRowMajorTensorRange);\n  gpu_result_row_major.device(sycl_device)=gpu_row_major.extract_image_patches(ksize, ksize, stride, stride, 1, 1, PADDING_VALID);\n  sycl_device.memcpyDeviceToHost(result_row_major.data(), gpu_data_result_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(result_col_major.dimension(0), result_row_major.dimension(4));\n  VERIFY_IS_EQUAL(result_col_major.dimension(1), result_row_major.dimension(3));\n  VERIFY_IS_EQUAL(result_col_major.dimension(2), result_row_major.dimension(2));\n  VERIFY_IS_EQUAL(result_col_major.dimension(3), result_row_major.dimension(1));\n  VERIFY_IS_EQUAL(result_col_major.dimension(4), result_row_major.dimension(0));\n\n  // No padding is carried out.\n  IndexType row_padding = 0;\n  IndexType col_padding = 0;\n\n  for (IndexType i = 0; (i+stride+ksize-1) < input_rows; i += stride) {  // input rows\n    for (IndexType j = 0; (j+stride+ksize-1) < input_cols; j += stride) {  // input cols\n      IndexType patchId = i+input_rows*j;\n      for (IndexType r = 0; r < ksize; ++r) {  // patch rows\n        for (IndexType c = 0; c < ksize; ++c) {  // patch cols\n          for (IndexType d = 0; d < input_depth; ++d) {  // depth\n            for (IndexType b = 0; b < input_batches; ++b) {  // batch\n              DataType expected_col_major = 0.0f;\n              DataType expected_row_major = 0.0f;\n              IndexType row_offset = r + i - row_padding;\n              IndexType col_offset = c + j - col_padding;\n              if (row_offset >= 0 && col_offset >= 0 && row_offset < input_rows && col_offset < input_cols) {\n                expected_col_major = tensor_col_major(d, row_offset, col_offset, b);\n                expected_row_major = tensor_row_major(b, col_offset, row_offset, d);\n              }\n              // ColMajor\n              if (result_col_major(d, r, c, patchId, b) != expected_col_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result_col_major(d, r, c, patchId, b), expected_col_major);\n              // RowMajor\n              if (result_row_major(b, patchId, c, r, d) != expected_row_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result_row_major(b, patchId, c, r, d), expected_row_major);\n              // Check that ColMajor and RowMajor agree.\n              VERIFY_IS_EQUAL(expected_col_major, expected_row_major);\n            }\n          }\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data_col_major);\n  sycl_device.deallocate(gpu_data_row_major);\n  sycl_device.deallocate(gpu_data_result_col_major);\n  sycl_device.deallocate(gpu_data_result_row_major);\n}\n\n// Verifies VALID padding (no padding) with the same value.\ntemplate <typename DataType, typename IndexType>\nstatic void test_patch_padding_valid_same_value_sycl(const Eigen::SyclDevice& sycl_device){\n  IndexType input_depth = 1;\n  IndexType input_rows = 5;\n  IndexType input_cols = 5;\n  IndexType input_batches = 2;\n  IndexType ksize = 3;  // Corresponds to the Rows and Cols for tensor.extract_image_patches<>.\n  IndexType stride = 2;  // Only same stride is supported.\n  // ColMajor\n\n  array<IndexType, 4> tensorColMajorRange = {{input_depth, input_rows, input_cols, input_batches}};\n  array<IndexType, 4> tensorRowMajorRange = {{input_batches, input_cols, input_rows, input_depth}};\n  Tensor<DataType, 4, DataLayout,IndexType> tensor_col_major(tensorColMajorRange);\n  Tensor<DataType, 4, RowMajor,IndexType> tensor_row_major(tensorRowMajorRange);\n\n  DataType* gpu_data_col_major  = static_cast<DataType*>(sycl_device.allocate(tensor_col_major.size()*sizeof(DataType)));\n  DataType* gpu_data_row_major  = static_cast<DataType*>(sycl_device.allocate(tensor_row_major.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 4, ColMajor, IndexType>> gpu_col_major(gpu_data_col_major, tensorColMajorRange);\n  TensorMap<Tensor<DataType, 4, RowMajor, IndexType>> gpu_row_major(gpu_data_row_major, tensorRowMajorRange);\n  gpu_col_major.device(sycl_device)=gpu_col_major.constant(11.0f);\n  gpu_row_major.device(sycl_device)=gpu_col_major.swap_layout();\n  sycl_device.memcpyDeviceToHost(tensor_col_major.data(), gpu_data_col_major, (tensor_col_major.size())*sizeof(DataType));\n  sycl_device.memcpyDeviceToHost(tensor_row_major.data(), gpu_data_row_major, (tensor_row_major.size())*sizeof(DataType));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(0), tensor_row_major.dimension(3));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(1), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(2), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(3), tensor_row_major.dimension(0));\n\n  array<IndexType, 5> patchColMajorTensorRange={{input_depth, ksize, ksize, 4, input_batches}};\n  Tensor<DataType, 5, DataLayout,IndexType> result_col_major(patchColMajorTensorRange);\n  size_t patchTensorBuffSize =result_col_major.size()*sizeof(DataType);\n  DataType* gpu_data_result_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_result_col_major(gpu_data_result_col_major, patchColMajorTensorRange);\n  gpu_result_col_major.device(sycl_device)=gpu_col_major.extract_image_patches(ksize, ksize, stride, stride, 1, 1, PADDING_VALID);\n  sycl_device.memcpyDeviceToHost(result_col_major.data(), gpu_data_result_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(result_col_major.dimension(0), input_depth);  // depth\n  VERIFY_IS_EQUAL(result_col_major.dimension(1), ksize);  // kernel rows\n  VERIFY_IS_EQUAL(result_col_major.dimension(2), ksize);  // kernel cols\n  VERIFY_IS_EQUAL(result_col_major.dimension(3), 4);  // number of patches\n  VERIFY_IS_EQUAL(result_col_major.dimension(4), input_batches);  // number of batches\n\n  // RowMajor\n  array<IndexType, 5> patchRowMajorTensorRange={{input_batches, 4, ksize, ksize, input_depth }};\n  Tensor<DataType, 5, RowMajor,IndexType> result_row_major(patchRowMajorTensorRange);\n  patchTensorBuffSize =result_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_result_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, RowMajor,IndexType>> gpu_result_row_major(gpu_data_result_row_major, patchRowMajorTensorRange);\n  gpu_result_row_major.device(sycl_device)=gpu_row_major.extract_image_patches(ksize, ksize, stride, stride, 1, 1, PADDING_VALID);\n  sycl_device.memcpyDeviceToHost(result_row_major.data(), gpu_data_result_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(result_col_major.dimension(0), result_row_major.dimension(4));\n  VERIFY_IS_EQUAL(result_col_major.dimension(1), result_row_major.dimension(3));\n  VERIFY_IS_EQUAL(result_col_major.dimension(2), result_row_major.dimension(2));\n  VERIFY_IS_EQUAL(result_col_major.dimension(3), result_row_major.dimension(1));\n  VERIFY_IS_EQUAL(result_col_major.dimension(4), result_row_major.dimension(0));\n\n  // No padding is carried out.\n  IndexType row_padding = 0;\n  IndexType col_padding = 0;\n\n  for (IndexType i = 0; (i+stride+ksize-1) <= input_rows; i += stride) {  // input rows\n    for (IndexType j = 0; (j+stride+ksize-1) <= input_cols; j += stride) {  // input cols\n      IndexType patchId = i+input_rows*j;\n      for (IndexType r = 0; r < ksize; ++r) {  // patch rows\n        for (IndexType c = 0; c < ksize; ++c) {  // patch cols\n          for (IndexType d = 0; d < input_depth; ++d) {  // depth\n            for (IndexType b = 0; b < input_batches; ++b) {  // batch\n              DataType expected_col_major = 0.0f;\n              DataType expected_row_major = 0.0f;\n              IndexType row_offset = r + i - row_padding;\n              IndexType col_offset = c + j - col_padding;\n              if (row_offset >= 0 && col_offset >= 0 && row_offset < input_rows && col_offset < input_cols) {\n                expected_col_major = tensor_col_major(d, row_offset, col_offset, b);\n                expected_row_major = tensor_row_major(b, col_offset, row_offset, d);\n              }\n              // ColMajor\n              if (result_col_major(d, r, c, patchId, b) != expected_col_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result_col_major(d, r, c, patchId, b), expected_col_major);\n              // RowMajor\n              if (result_row_major(b, patchId, c, r, d) != expected_row_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result_row_major(b, patchId, c, r, d), expected_row_major);\n              // Check that ColMajor and RowMajor agree.\n              VERIFY_IS_EQUAL(expected_col_major, expected_row_major);\n            }\n          }\n        }\n      }\n    }\n  }\n}\n\n// Verifies SAME padding.\ntemplate <typename DataType, typename IndexType>\nstatic void test_patch_padding_same_sycl(const Eigen::SyclDevice& sycl_device){\n  IndexType input_depth = 3;\n  IndexType input_rows = 4;\n  IndexType input_cols = 2;\n  IndexType input_batches = 1;\n  IndexType ksize = 2;  // Corresponds to the Rows and Cols for tensor.extract_image_patches<>.\n  IndexType stride = 2;  // Only same stride is supported.\n\n  // ColMajor\n  array<IndexType, 4> tensorColMajorRange = {{input_depth, input_rows, input_cols, input_batches}};\n  array<IndexType, 4> tensorRowMajorRange = {{input_batches, input_cols, input_rows, input_depth}};\n  Tensor<DataType, 4, DataLayout,IndexType> tensor_col_major(tensorColMajorRange);\n  Tensor<DataType, 4, RowMajor,IndexType> tensor_row_major(tensorRowMajorRange);\n\n  DataType* gpu_data_col_major  = static_cast<DataType*>(sycl_device.allocate(tensor_col_major.size()*sizeof(DataType)));\n  DataType* gpu_data_row_major  = static_cast<DataType*>(sycl_device.allocate(tensor_row_major.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 4, ColMajor, IndexType>> gpu_col_major(gpu_data_col_major, tensorColMajorRange);\n  TensorMap<Tensor<DataType, 4, RowMajor, IndexType>> gpu_row_major(gpu_data_row_major, tensorRowMajorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_col_major, tensor_col_major.data(),(tensor_col_major.size())*sizeof(DataType));\n  gpu_row_major.device(sycl_device)=gpu_col_major.swap_layout();\n  sycl_device.memcpyDeviceToHost(tensor_row_major.data(), gpu_data_row_major, (tensor_col_major.size())*sizeof(DataType));\n\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(0), tensor_row_major.dimension(3));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(1), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(2), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(3), tensor_row_major.dimension(0));\n\n  // Initializes tensor with incrementing numbers.\n  for (IndexType i = 0; i < tensor_col_major.size(); ++i) {\n    tensor_col_major.data()[i] = i + 1;\n  }\n\narray<IndexType, 5> patchColMajorTensorRange={{input_depth, ksize, ksize, 2, input_batches}};\nTensor<DataType, 5, DataLayout,IndexType> result_col_major(patchColMajorTensorRange);\nsize_t patchTensorBuffSize =result_col_major.size()*sizeof(DataType);\nDataType* gpu_data_result_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\nTensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_result_col_major(gpu_data_result_col_major, patchColMajorTensorRange);\ngpu_result_col_major.device(sycl_device)=gpu_col_major.extract_image_patches(ksize, ksize, stride, stride, PADDING_SAME);\nsycl_device.memcpyDeviceToHost(result_col_major.data(), gpu_data_result_col_major, patchTensorBuffSize);\n\n\n  VERIFY_IS_EQUAL(result_col_major.dimension(0), input_depth);  // depth\n  VERIFY_IS_EQUAL(result_col_major.dimension(1), ksize);  // kernel rows\n  VERIFY_IS_EQUAL(result_col_major.dimension(2), ksize);  // kernel cols\n  VERIFY_IS_EQUAL(result_col_major.dimension(3), 2);  // number of patches\n  VERIFY_IS_EQUAL(result_col_major.dimension(4), input_batches);  // number of batches\n\n  // RowMajor\n\n  array<IndexType, 5> patchRowMajorTensorRange={{input_batches, 2, ksize, ksize, input_depth }};\n  Tensor<DataType, 5, RowMajor,IndexType> result_row_major(patchRowMajorTensorRange);\n  patchTensorBuffSize =result_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_result_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, RowMajor,IndexType>> gpu_result_row_major(gpu_data_result_row_major, patchRowMajorTensorRange);\n  gpu_result_row_major.device(sycl_device)=gpu_row_major.extract_image_patches(ksize, ksize, stride, stride, PADDING_SAME);\n  sycl_device.memcpyDeviceToHost(result_row_major.data(), gpu_data_result_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(result_col_major.dimension(0), result_row_major.dimension(4));\n  VERIFY_IS_EQUAL(result_col_major.dimension(1), result_row_major.dimension(3));\n  VERIFY_IS_EQUAL(result_col_major.dimension(2), result_row_major.dimension(2));\n  VERIFY_IS_EQUAL(result_col_major.dimension(3), result_row_major.dimension(1));\n  VERIFY_IS_EQUAL(result_col_major.dimension(4), result_row_major.dimension(0));\n\n  // Based on the calculation described in TensorTraits.h, padding happens to be 0.\n  IndexType row_padding = 0;\n  IndexType col_padding = 0;\n\n  for (IndexType i = 0; (i+stride+ksize-1) <= input_rows; i += stride) {  // input rows\n    for (IndexType j = 0; (j+stride+ksize-1) <= input_cols; j += stride) {  // input cols\n      IndexType patchId = i+input_rows*j;\n      for (IndexType r = 0; r < ksize; ++r) {  // patch rows\n        for (IndexType c = 0; c < ksize; ++c) {  // patch cols\n          for (IndexType d = 0; d < input_depth; ++d) {  // depth\n            for (IndexType b = 0; b < input_batches; ++b) {  // batch\n              DataType expected_col_major = 0.0f;\n              DataType expected_row_major = 0.0f;\n              IndexType row_offset = r*stride + i - row_padding;\n              IndexType col_offset = c*stride + j - col_padding;\n              if (row_offset >= 0 && col_offset >= 0 && row_offset < input_rows && col_offset < input_cols) {\n                expected_col_major = tensor_col_major(d, row_offset, col_offset, b);\n                expected_row_major = tensor_row_major(b, col_offset, row_offset, d);\n              }\n              // ColMajor\n              if (result_col_major(d, r, c, patchId, b) != expected_col_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result_col_major(d, r, c, patchId, b), expected_col_major);\n              // RowMajor\n              if (result_row_major(b, patchId, c, r, d) != expected_row_major) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(result_row_major(b, patchId, c, r, d), expected_row_major);\n              // Check that ColMajor and RowMajor agree.\n              VERIFY_IS_EQUAL(expected_col_major, expected_row_major);\n            }\n          }\n        }\n      }\n    }\n  }\n}\n\n\ntemplate <typename DataType, typename IndexType>\nstatic void test_patch_no_extra_dim_sycl(const Eigen::SyclDevice& sycl_device){\n\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n\n  // ColMajor\n  array<IndexType, 3> tensorColMajorRange = {{sizeDim1, sizeDim2, sizeDim3}};\n  array<IndexType, 3> tensorRowMajorRange = {{sizeDim3, sizeDim2, sizeDim1}};\n  Tensor<DataType, 3, DataLayout,IndexType> tensor_col_major(tensorColMajorRange);\n  tensor_col_major.setRandom();\n  Tensor<DataType, 3, RowMajor,IndexType> tensor_row_major(tensorRowMajorRange);\n\n  DataType* gpu_data_col_major  = static_cast<DataType*>(sycl_device.allocate(tensor_col_major.size()*sizeof(DataType)));\n  DataType* gpu_data_row_major  = static_cast<DataType*>(sycl_device.allocate(tensor_row_major.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 3, ColMajor, IndexType>> gpu_col_major(gpu_data_col_major, tensorColMajorRange);\n  TensorMap<Tensor<DataType, 3, RowMajor, IndexType>> gpu_row_major(gpu_data_row_major, tensorRowMajorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_col_major, tensor_col_major.data(),(tensor_col_major.size())*sizeof(DataType));\n  gpu_row_major.device(sycl_device)=gpu_col_major.swap_layout();\n  sycl_device.memcpyDeviceToHost(tensor_row_major.data(), gpu_data_row_major, (tensor_row_major.size())*sizeof(DataType));\n\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(0), tensor_row_major.dimension(2));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(1), tensor_row_major.dimension(1));\n  VERIFY_IS_EQUAL(tensor_col_major.dimension(2), tensor_row_major.dimension(0));\n\n\n  // Single pixel patch: ColMajor\n  array<IndexType, 4> patchColMajorTensorRange={{sizeDim1, 1, 1, sizeDim2*sizeDim3}};\n  Tensor<DataType, 4, DataLayout,IndexType> single_patch_col_major(patchColMajorTensorRange);\n  size_t patchTensorBuffSize =single_patch_col_major.size()*sizeof(DataType);\n  DataType* gpu_data_single_patch_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_single_patch_col_major(gpu_data_single_patch_col_major, patchColMajorTensorRange);\n  gpu_single_patch_col_major.device(sycl_device)=gpu_col_major.extract_image_patches(1, 1);\n  sycl_device.memcpyDeviceToHost(single_patch_col_major.data(), gpu_data_single_patch_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(single_patch_col_major.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(single_patch_col_major.dimension(1), 1);\n  VERIFY_IS_EQUAL(single_patch_col_major.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_patch_col_major.dimension(3), sizeDim2*sizeDim3);\n\n  // Single pixel patch: RowMajor\n  array<IndexType, 4> patchRowMajorTensorRange={{sizeDim2*sizeDim3, 1, 1, sizeDim1}};\n  Tensor<DataType, 4, RowMajor,IndexType> single_patch_row_major(patchRowMajorTensorRange);\n  patchTensorBuffSize =single_patch_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_single_patch_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 4, RowMajor,IndexType>> gpu_single_patch_row_major(gpu_data_single_patch_row_major, patchRowMajorTensorRange);\n  gpu_single_patch_row_major.device(sycl_device)=gpu_row_major.extract_image_patches(1, 1);\n  sycl_device.memcpyDeviceToHost(single_patch_row_major.data(), gpu_data_single_patch_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(single_patch_row_major.dimension(0), sizeDim2*sizeDim3);\n  VERIFY_IS_EQUAL(single_patch_row_major.dimension(1), 1);\n  VERIFY_IS_EQUAL(single_patch_row_major.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_patch_row_major.dimension(3), sizeDim1);\n\n  for (IndexType i = 0; i < tensor_col_major.size(); ++i) {\n    // ColMajor\n    if (tensor_col_major.data()[i] != single_patch_col_major.data()[i]) {\n      std::cout << \"Mismatch detected at index \" << i << \" : \" << tensor_col_major.data()[i] << \" vs \" << single_patch_col_major.data()[i] << std::endl;\n    }\n    VERIFY_IS_EQUAL(single_patch_col_major.data()[i], tensor_col_major.data()[i]);\n    // RowMajor\n    if (tensor_row_major.data()[i] != single_patch_row_major.data()[i]) {\n      std::cout << \"Mismatch detected at index \" << i << \" : \"\n           << tensor_col_major.data()[i] << \" vs \"\n           << single_patch_row_major.data()[i] << std::endl;\n    }\n    VERIFY_IS_EQUAL(single_patch_row_major.data()[i],\n                    tensor_row_major.data()[i]);\n    VERIFY_IS_EQUAL(tensor_col_major.data()[i], tensor_row_major.data()[i]);\n    VERIFY_IS_EQUAL(single_patch_col_major.data()[i],\n                    single_patch_row_major.data()[i]);\n  }\n\n  // Entire image patch: ColMajor\n  patchColMajorTensorRange={{sizeDim1, sizeDim2, sizeDim3, sizeDim2*sizeDim3}};\n  Tensor<DataType, 4, DataLayout,IndexType> entire_image_patch_col_major(patchColMajorTensorRange);\n  patchTensorBuffSize =entire_image_patch_col_major.size()*sizeof(DataType);\n  DataType* gpu_data_entire_image_patch_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_entire_image_patch_col_major(gpu_data_entire_image_patch_col_major, patchColMajorTensorRange);\n  gpu_entire_image_patch_col_major.device(sycl_device)=gpu_col_major.extract_image_patches(3, 5);\n  sycl_device.memcpyDeviceToHost(entire_image_patch_col_major.data(), gpu_data_entire_image_patch_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(entire_image_patch_col_major.dimension(0), 2);\n  VERIFY_IS_EQUAL(entire_image_patch_col_major.dimension(1), 3);\n  VERIFY_IS_EQUAL(entire_image_patch_col_major.dimension(2), 5);\n  VERIFY_IS_EQUAL(entire_image_patch_col_major.dimension(3), 3*5);\n\n  // Entire image patch: RowMajor\npatchRowMajorTensorRange={{sizeDim2*sizeDim3, sizeDim3, sizeDim2, sizeDim1}};\nTensor<DataType, 4, RowMajor,IndexType> entire_image_patch_row_major(patchRowMajorTensorRange);\npatchTensorBuffSize =entire_image_patch_row_major.size()*sizeof(DataType);\nDataType* gpu_data_entire_image_patch_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\nTensorMap<Tensor<DataType, 4, RowMajor,IndexType>> gpu_entire_image_patch_row_major(gpu_data_entire_image_patch_row_major, patchRowMajorTensorRange);\ngpu_entire_image_patch_row_major.device(sycl_device)=gpu_row_major.extract_image_patches(3, 5);\nsycl_device.memcpyDeviceToHost(entire_image_patch_row_major.data(), gpu_data_entire_image_patch_row_major, patchTensorBuffSize);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(0), 3*5);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(1), 5);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(2), 3);\n  VERIFY_IS_EQUAL(entire_image_patch_row_major.dimension(3), 2);\n\n  for (IndexType i = 0; i < 3; ++i) {\n    for (IndexType j = 0; j < 5; ++j) {\n      IndexType patchId = i+3*j;\n      for (IndexType r = 0; r < 3; ++r) {\n        for (IndexType c = 0; c < 5; ++c) {\n          for (IndexType d = 0; d < 2; ++d) {\n            DataType expected_col_major = 0.0f;\n            DataType expected_row_major = 0.0f;\n            if (r-1+i >= 0 && c-2+j >= 0 && r-1+i < 3 && c-2+j < 5) {\n              expected_col_major = tensor_col_major(d, r-1+i, c-2+j);\n              expected_row_major = tensor_row_major(c-2+j, r-1+i, d);\n            }\n            // ColMajor\n            if (entire_image_patch_col_major(d, r, c, patchId) != expected_col_major) {\n              std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << std::endl;\n            }\n            VERIFY_IS_EQUAL(entire_image_patch_col_major(d, r, c, patchId), expected_col_major);\n            // RowMajor\n            if (entire_image_patch_row_major(patchId, c, r, d) !=\n                expected_row_major) {\n              std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << std::endl;\n            }\n            VERIFY_IS_EQUAL(entire_image_patch_row_major(patchId, c, r, d),\n                            expected_row_major);\n            // Check that ColMajor and RowMajor agree.\n            VERIFY_IS_EQUAL(expected_col_major, expected_row_major);\n          }\n        }\n      }\n    }\n  }\n\n  // 2D patch: ColMajor\n  patchColMajorTensorRange={{sizeDim1, 2, 2, sizeDim2*sizeDim3}};\n  Tensor<DataType, 4, DataLayout,IndexType> twod_patch_col_major(patchColMajorTensorRange);\n  patchTensorBuffSize =twod_patch_col_major.size()*sizeof(DataType);\n  DataType* gpu_data_twod_patch_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_twod_patch_col_major(gpu_data_twod_patch_col_major, patchColMajorTensorRange);\n  gpu_twod_patch_col_major.device(sycl_device)=gpu_col_major.extract_image_patches(2, 2);\n  sycl_device.memcpyDeviceToHost(twod_patch_col_major.data(), gpu_data_twod_patch_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(twod_patch_col_major.dimension(0), 2);\n  VERIFY_IS_EQUAL(twod_patch_col_major.dimension(1), 2);\n  VERIFY_IS_EQUAL(twod_patch_col_major.dimension(2), 2);\n  VERIFY_IS_EQUAL(twod_patch_col_major.dimension(3), 3*5);\n\n  // 2D patch: RowMajor\n  patchRowMajorTensorRange={{sizeDim2*sizeDim3, 2, 2, sizeDim1}};\n  Tensor<DataType, 4, RowMajor,IndexType> twod_patch_row_major(patchRowMajorTensorRange);\n  patchTensorBuffSize =twod_patch_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_twod_patch_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 4, RowMajor,IndexType>> gpu_twod_patch_row_major(gpu_data_twod_patch_row_major, patchRowMajorTensorRange);\n  gpu_twod_patch_row_major.device(sycl_device)=gpu_row_major.extract_image_patches(2, 2);\n  sycl_device.memcpyDeviceToHost(twod_patch_row_major.data(), gpu_data_twod_patch_row_major, patchTensorBuffSize);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(0), 3*5);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(1), 2);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(2), 2);\n  VERIFY_IS_EQUAL(twod_patch_row_major.dimension(3), 2);\n\n  // Based on the calculation described in TensorTraits.h, padding happens to be 0.\n  IndexType row_padding = 0;\n  IndexType col_padding = 0;\n  IndexType stride = 1;\n\n  for (IndexType i = 0; i < 3; ++i) {\n    for (IndexType j = 0; j < 5; ++j) {\n      IndexType patchId = i+3*j;\n      for (IndexType r = 0; r < 2; ++r) {\n        for (IndexType c = 0; c < 2; ++c) {\n          for (IndexType d = 0; d < 2; ++d) {\n            DataType expected_col_major = 0.0f;\n            DataType expected_row_major = 0.0f;\n            IndexType row_offset = r*stride + i - row_padding;\n            IndexType col_offset = c*stride + j - col_padding;\n            // ColMajor\n            if (row_offset >= 0 && col_offset >= 0 && row_offset < tensor_col_major.dimension(1) && col_offset < tensor_col_major.dimension(2)) {\n              expected_col_major = tensor_col_major(d, row_offset, col_offset);\n            }\n            if (twod_patch_col_major(d, r, c, patchId) != expected_col_major) {\n              std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << std::endl;\n            }\n            VERIFY_IS_EQUAL(twod_patch_col_major(d, r, c, patchId), expected_col_major);\n            // RowMajor\n            if (row_offset >= 0 && col_offset >= 0 && row_offset < tensor_row_major.dimension(1) && col_offset < tensor_row_major.dimension(0)) {\n              expected_row_major = tensor_row_major(col_offset, row_offset, d);\n            }\n            if (twod_patch_row_major(patchId, c, r, d) != expected_row_major) {\n              std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << std::endl;\n            }\n            VERIFY_IS_EQUAL(twod_patch_row_major(patchId, c, r, d), expected_row_major);\n            // Check that ColMajor and RowMajor agree.\n            VERIFY_IS_EQUAL(expected_col_major, expected_row_major);\n          }\n        }\n      }\n    }\n  }\n\n  sycl_device.deallocate(gpu_data_col_major);\n  sycl_device.deallocate(gpu_data_row_major);\n  sycl_device.deallocate(gpu_data_single_patch_col_major);\n  sycl_device.deallocate(gpu_data_single_patch_row_major);\n  sycl_device.deallocate(gpu_data_entire_image_patch_col_major);\n  sycl_device.deallocate(gpu_data_entire_image_patch_row_major);\n  sycl_device.deallocate(gpu_data_twod_patch_col_major);\n  sycl_device.deallocate(gpu_data_twod_patch_row_major);\n}\n\ntemplate <typename DataType, typename IndexType>\nstatic void test_imagenet_patches_sycl(const Eigen::SyclDevice& sycl_device)\n{\n  // Test the code on typical configurations used by the 'imagenet' benchmarks at\n  // https://github.com/soumith/convnet-benchmarks\n  // ColMajor\n  IndexType sizeDim1 = 3;\n  IndexType sizeDim2 = 128;\n  IndexType sizeDim3 = 128;\n  IndexType sizeDim4 = 16;\n  array<IndexType, 4> tensorColMajorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  Tensor<DataType, 4, DataLayout,IndexType> l_in_col_major(tensorColMajorRange);\n  l_in_col_major.setRandom();\n\n  DataType* gpu_data_l_in_col_major  = static_cast<DataType*>(sycl_device.allocate(l_in_col_major.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 4, ColMajor, IndexType>> gpu_l_in_col_major(gpu_data_l_in_col_major, tensorColMajorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_l_in_col_major, l_in_col_major.data(),(l_in_col_major.size())*sizeof(DataType));\n\n  array<IndexType, 5> patchTensorRange={{sizeDim1, 11, 11, sizeDim2*sizeDim3, sizeDim4}};\n  Tensor<DataType, 5, DataLayout,IndexType> l_out_col_major(patchTensorRange);\n  size_t patchTensorBuffSize =l_out_col_major.size()*sizeof(DataType);\n  DataType* gpu_data_l_out_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_l_out_col_major(gpu_data_l_out_col_major, patchTensorRange);\n  gpu_l_out_col_major.device(sycl_device)=gpu_l_in_col_major.extract_image_patches(11, 11);\n  sycl_device.memcpyDeviceToHost(l_out_col_major.data(), gpu_data_l_out_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(1), 11);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(2), 11);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(3), sizeDim2*sizeDim3);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(4), sizeDim4);\n\n  // RowMajor\n  patchTensorRange={{sizeDim4, sizeDim2*sizeDim3, 11, 11, sizeDim1}};\n  Tensor<DataType, 5, RowMajor,IndexType> l_out_row_major(patchTensorRange);\n  patchTensorBuffSize =l_out_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_l_out_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, RowMajor,IndexType>> gpu_l_out_row_major(gpu_data_l_out_row_major, patchTensorRange);\n  gpu_l_out_row_major.device(sycl_device)=gpu_l_in_col_major.swap_layout().extract_image_patches(11, 11);\n  sycl_device.memcpyDeviceToHost(l_out_row_major.data(), gpu_data_l_out_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(0), sizeDim4);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(1), sizeDim2*sizeDim3);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(2), 11);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(3), 11);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(4), sizeDim1);\n\n  for (IndexType b = 0; b < 16; ++b) {\n    for (IndexType i = 0; i < 128; ++i) {\n      for (IndexType j = 0; j < 128; ++j) {\n        IndexType patchId = i+128*j;\n        for (IndexType c = 0; c < 11; ++c) {\n          for (IndexType r = 0; r < 11; ++r) {\n            for (IndexType d = 0; d < 3; ++d) {\n              DataType expected = 0.0f;\n              if (r-5+i >= 0 && c-5+j >= 0 && r-5+i < 128 && c-5+j < 128) {\n                expected = l_in_col_major(d, r-5+i, c-5+j, b);\n              }\n              // ColMajor\n              if (l_out_col_major(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_col_major(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (l_out_row_major(b, patchId, c, r, d) !=\n                  expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j\n                     << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b\n                     << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_row_major(b, patchId, c, r, d),\n                              expected);\n            }\n          }\n        }\n      }\n    }\n  }\n\n  // ColMajor\n  sycl_device.deallocate(gpu_data_l_in_col_major);\n  sycl_device.deallocate(gpu_data_l_out_col_major);\n  sizeDim1 = 16;\n  sizeDim2 = 64;\n  sizeDim3 = 64;\n  sizeDim4 = 32;\n  tensorColMajorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  l_in_col_major.resize(tensorColMajorRange);\n  l_in_col_major.setRandom();\n  gpu_data_l_in_col_major  = static_cast<DataType*>(sycl_device.allocate(l_in_col_major.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 4, ColMajor, IndexType>>gpu_l_in_col_major_resize1(gpu_data_l_in_col_major, tensorColMajorRange);\n\n  patchTensorRange={{sizeDim1, 9, 9, sizeDim2*sizeDim3, sizeDim4}};\n  l_out_col_major.resize(patchTensorRange);\n  patchTensorBuffSize =l_out_col_major.size()*sizeof(DataType);\n  gpu_data_l_out_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>>gpu_l_out_col_major_resize1(gpu_data_l_out_col_major, patchTensorRange);\n  sycl_device.memcpyHostToDevice(gpu_data_l_in_col_major, l_in_col_major.data(),(l_in_col_major.size())*sizeof(DataType));\n  gpu_l_out_col_major_resize1.device(sycl_device)=gpu_l_in_col_major_resize1.extract_image_patches(9, 9);\n  sycl_device.memcpyDeviceToHost(l_out_col_major.data(), gpu_data_l_out_col_major, patchTensorBuffSize);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(0), 16);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(1), 9);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(2), 9);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(3), 64*64);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(4), 32);\n\n// RowMajor\n  sycl_device.deallocate(gpu_data_l_out_row_major);\n  patchTensorRange={{sizeDim4, sizeDim2*sizeDim3, 9, 9 ,sizeDim1}};\n  l_out_row_major.resize(patchTensorRange);\n  patchTensorBuffSize =l_out_row_major.size()*sizeof(DataType);\n  gpu_data_l_out_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, RowMajor,IndexType>>gpu_l_out_row_major_resize1(gpu_data_l_out_row_major, patchTensorRange);\n  gpu_l_out_row_major_resize1.device(sycl_device)=gpu_l_in_col_major_resize1.swap_layout().extract_image_patches(9, 9);\n  sycl_device.memcpyDeviceToHost(l_out_row_major.data(), gpu_data_l_out_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(0), 32);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(1), 64*64);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(2), 9);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(3), 9);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(4), 16);\n\n  for (IndexType b = 0; b < 32; ++b) {\n    for (IndexType i = 0; i < 64; ++i) {\n      for (IndexType j = 0; j < 64; ++j) {\n        IndexType patchId = i+64*j;\n        for (IndexType c = 0; c < 9; ++c) {\n          for (IndexType r = 0; r < 9; ++r) {\n            for (IndexType d = 0; d < 16; ++d) {\n              DataType expected = 0.0f;\n              if (r-4+i >= 0 && c-4+j >= 0 && r-4+i < 64 && c-4+j < 64) {\n                expected = l_in_col_major(d, r-4+i, c-4+j, b);\n              }\n              // ColMajor\n              if (l_out_col_major(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_col_major(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (l_out_row_major(b, patchId, c, r, d) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_row_major(b, patchId, c, r, d), expected);\n            }\n          }\n        }\n      }\n    }\n  }\n\n  // ColMajor\n\n  sycl_device.deallocate(gpu_data_l_in_col_major);\n  sycl_device.deallocate(gpu_data_l_out_col_major);\n  sizeDim1 = 32;\n  sizeDim2 = 16;\n  sizeDim3 = 16;\n  sizeDim4 = 32;\n  tensorColMajorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  l_in_col_major.resize(tensorColMajorRange);\n  l_in_col_major.setRandom();\n  gpu_data_l_in_col_major  = static_cast<DataType*>(sycl_device.allocate(l_in_col_major.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 4, ColMajor, IndexType>>gpu_l_in_col_major_resize2(gpu_data_l_in_col_major, tensorColMajorRange);\n\n  patchTensorRange={{sizeDim1, 7, 7, sizeDim2*sizeDim3, sizeDim4}};\n  l_out_col_major.resize(patchTensorRange);\n  patchTensorBuffSize =l_out_col_major.size()*sizeof(DataType);\n  gpu_data_l_out_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>>gpu_l_out_col_major_resize2(gpu_data_l_out_col_major, patchTensorRange);\n  sycl_device.memcpyHostToDevice(gpu_data_l_in_col_major, l_in_col_major.data(),(l_in_col_major.size())*sizeof(DataType));\n  gpu_l_out_col_major_resize2.device(sycl_device)=gpu_l_in_col_major_resize2.extract_image_patches(7, 7);\n  sycl_device.memcpyDeviceToHost(l_out_col_major.data(), gpu_data_l_out_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(0), 32);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(1), 7);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(2), 7);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(3), 16*16);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(4), 32);\n\n  // RowMajor\n  sycl_device.deallocate(gpu_data_l_out_row_major);\n  patchTensorRange={{sizeDim4, sizeDim2*sizeDim3, 7, 7 ,sizeDim1}};\n  l_out_row_major.resize(patchTensorRange);\n  patchTensorBuffSize =l_out_row_major.size()*sizeof(DataType);\n  gpu_data_l_out_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, RowMajor,IndexType>>gpu_l_out_row_major_resize2(gpu_data_l_out_row_major, patchTensorRange);\n  gpu_l_out_row_major_resize2.device(sycl_device)=gpu_l_in_col_major_resize2.swap_layout().extract_image_patches(7, 7);\n  sycl_device.memcpyDeviceToHost(l_out_row_major.data(), gpu_data_l_out_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(0), 32);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(1), 16*16);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(2), 7);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(3), 7);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(4), 32);\n\n  for (IndexType b = 0; b < 32; ++b) {\n    for (IndexType i = 0; i < 16; ++i) {\n      for (IndexType j = 0; j < 16; ++j) {\n        IndexType patchId = i+16*j;\n        for (IndexType c = 0; c < 7; ++c) {\n          for (IndexType r = 0; r < 7; ++r) {\n            for (IndexType d = 0; d < 32; ++d) {\n              DataType expected = 0.0f;\n              if (r-3+i >= 0 && c-3+j >= 0 && r-3+i < 16 && c-3+j < 16) {\n                expected = l_in_col_major(d, r-3+i, c-3+j, b);\n              }\n              // ColMajor\n              if (l_out_col_major(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_col_major(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (l_out_row_major(b, patchId, c, r, d) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_row_major(b, patchId, c, r, d), expected);\n            }\n          }\n        }\n      }\n    }\n  }\n\n  // ColMajor\n  sycl_device.deallocate(gpu_data_l_in_col_major);\n  sycl_device.deallocate(gpu_data_l_out_col_major);\n  sizeDim1 = 64;\n  sizeDim2 = 13;\n  sizeDim3 = 13;\n  sizeDim4 = 32;\n  tensorColMajorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  l_in_col_major.resize(tensorColMajorRange);\n  l_in_col_major.setRandom();\n  gpu_data_l_in_col_major  = static_cast<DataType*>(sycl_device.allocate(l_in_col_major.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 4, ColMajor, IndexType>>gpu_l_in_col_major_resize3(gpu_data_l_in_col_major, tensorColMajorRange);\n\n  patchTensorRange={{sizeDim1, 3, 3, sizeDim2*sizeDim3, sizeDim4}};\n  l_out_col_major.resize(patchTensorRange);\n  patchTensorBuffSize =l_out_col_major.size()*sizeof(DataType);\n  gpu_data_l_out_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>>gpu_l_out_col_major_resize3(gpu_data_l_out_col_major, patchTensorRange);\n  sycl_device.memcpyHostToDevice(gpu_data_l_in_col_major, l_in_col_major.data(),(l_in_col_major.size())*sizeof(DataType));\n  gpu_l_out_col_major_resize3.device(sycl_device)=gpu_l_in_col_major_resize3.extract_image_patches(3, 3);\n  sycl_device.memcpyDeviceToHost(l_out_col_major.data(), gpu_data_l_out_col_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(0), 64);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(1), 3);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(2), 3);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(3), 13*13);\n  VERIFY_IS_EQUAL(l_out_col_major.dimension(4), 32);\n\n  // RowMajor\n  sycl_device.deallocate(gpu_data_l_out_row_major);\n  patchTensorRange={{sizeDim4, sizeDim2*sizeDim3, 3, 3 ,sizeDim1}};\n  l_out_row_major.resize(patchTensorRange);\n  patchTensorBuffSize =l_out_row_major.size()*sizeof(DataType);\n  gpu_data_l_out_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, RowMajor,IndexType>>gpu_l_out_row_major_resize3(gpu_data_l_out_row_major, patchTensorRange);\n  gpu_l_out_row_major_resize3.device(sycl_device)=gpu_l_in_col_major_resize3.swap_layout().extract_image_patches(3, 3);\n  sycl_device.memcpyDeviceToHost(l_out_row_major.data(), gpu_data_l_out_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(0), 32);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(1), 13*13);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(2), 3);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(3), 3);\n  VERIFY_IS_EQUAL(l_out_row_major.dimension(4), 64);\n\n  for (IndexType b = 0; b < 32; ++b) {\n    for (IndexType i = 0; i < 13; ++i) {\n      for (IndexType j = 0; j < 13; ++j) {\n        IndexType patchId = i+13*j;\n        for (IndexType c = 0; c < 3; ++c) {\n          for (IndexType r = 0; r < 3; ++r) {\n            for (IndexType d = 0; d < 64; ++d) {\n              DataType expected = 0.0f;\n              if (r-1+i >= 0 && c-1+j >= 0 && r-1+i < 13 && c-1+j < 13) {\n                expected = l_in_col_major(d, r-1+i, c-1+j, b);\n              }\n              // ColMajor\n              if (l_out_col_major(d, r, c, patchId, b) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_col_major(d, r, c, patchId, b), expected);\n              // RowMajor\n              if (l_out_row_major(b, patchId, c, r, d) != expected) {\n                std::cout << \"Mismatch detected at index i=\" << i << \" j=\" << j << \" r=\" << r << \" c=\" << c << \" d=\" << d << \" b=\" << b << std::endl;\n              }\n              VERIFY_IS_EQUAL(l_out_row_major(b, patchId, c, r, d), expected);\n            }\n          }\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data_l_in_col_major);\n  sycl_device.deallocate(gpu_data_l_out_col_major);\n  sycl_device.deallocate(gpu_data_l_out_row_major);\n}\n\n\ntemplate<typename DataType, typename dev_Selector> void sycl_tensor_image_patch_test_per_device(dev_Selector s){\nQueueInterface queueInterface(s);\nauto sycl_device = Eigen::SyclDevice(&queueInterface);\ntest_simple_image_patch_sycl<DataType, int64_t>(sycl_device);\ntest_patch_padding_valid_sycl<DataType, int64_t>(sycl_device);\ntest_patch_padding_valid_same_value_sycl<DataType, int64_t>(sycl_device);\ntest_patch_padding_same_sycl<DataType, int64_t>(sycl_device);\ntest_patch_no_extra_dim_sycl<DataType, int64_t>(sycl_device);\ntest_imagenet_patches_sycl<DataType, int64_t>(sycl_device);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_image_patch_sycl)\n{\nfor (const auto& device :Eigen::get_sycl_supported_devices()) {\n  CALL_SUBTEST(sycl_tensor_image_patch_test_per_device<float>(device));\n}\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_index_list.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\n#ifdef EIGEN_HAS_INDEX_LIST\n\nstatic void test_static_index_list()\n{\n  Tensor<float, 4> tensor(2,3,5,7);\n  tensor.setRandom();\n\n  constexpr auto reduction_axis = make_index_list(0, 1, 2);\n  VERIFY_IS_EQUAL(internal::array_get<0>(reduction_axis), 0);\n  VERIFY_IS_EQUAL(internal::array_get<1>(reduction_axis), 1);\n  VERIFY_IS_EQUAL(internal::array_get<2>(reduction_axis), 2);\n  VERIFY_IS_EQUAL(static_cast<Index>(reduction_axis[0]), 0);\n  VERIFY_IS_EQUAL(static_cast<Index>(reduction_axis[1]), 1);\n  VERIFY_IS_EQUAL(static_cast<Index>(reduction_axis[2]), 2);\n\n  EIGEN_STATIC_ASSERT((internal::array_get<0>(reduction_axis) == 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::array_get<1>(reduction_axis) == 1), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::array_get<2>(reduction_axis) == 2), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  Tensor<float, 1> result = tensor.sum(reduction_axis);\n  for (int i = 0; i < result.size(); ++i) {\n    float expected = 0.0f;\n    for (int j = 0; j < 2; ++j) {\n      for (int k = 0; k < 3; ++k) {\n        for (int l = 0; l < 5; ++l) {\n          expected += tensor(j,k,l,i);\n        }\n      }\n    }\n    VERIFY_IS_APPROX(result(i), expected);\n  }\n}\n\n\nstatic void test_type2index_list()\n{\n  Tensor<float, 5> tensor(2,3,5,7,11);\n  tensor.setRandom();\n  tensor += tensor.constant(10.0f);\n\n  typedef Eigen::IndexList<Eigen::type2index<0>> Dims0;\n  typedef Eigen::IndexList<Eigen::type2index<0>, Eigen::type2index<1>> Dims1;\n  typedef Eigen::IndexList<Eigen::type2index<0>, Eigen::type2index<1>, Eigen::type2index<2>> Dims2;\n  typedef Eigen::IndexList<Eigen::type2index<0>, Eigen::type2index<1>, Eigen::type2index<2>, Eigen::type2index<3>> Dims3;\n  typedef Eigen::IndexList<Eigen::type2index<0>, Eigen::type2index<1>, Eigen::type2index<2>, Eigen::type2index<3>, Eigen::type2index<4>> Dims4;\n\n#if 0\n  EIGEN_STATIC_ASSERT((internal::indices_statically_known_to_increase<Dims0>() == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::indices_statically_known_to_increase<Dims1>() == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::indices_statically_known_to_increase<Dims2>() == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::indices_statically_known_to_increase<Dims3>() == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::indices_statically_known_to_increase<Dims4>() == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n#endif\n\n  EIGEN_STATIC_ASSERT((internal::are_inner_most_dims<Dims0, 1, ColMajor>::value == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::are_inner_most_dims<Dims1, 2, ColMajor>::value == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::are_inner_most_dims<Dims2, 3, ColMajor>::value == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::are_inner_most_dims<Dims3, 4, ColMajor>::value == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::are_inner_most_dims<Dims4, 5, ColMajor>::value == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((internal::are_inner_most_dims<Dims0, 1, RowMajor>::value == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::are_inner_most_dims<Dims1, 2, RowMajor>::value == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::are_inner_most_dims<Dims2, 3, RowMajor>::value == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::are_inner_most_dims<Dims3, 4, RowMajor>::value == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::are_inner_most_dims<Dims4, 5, RowMajor>::value == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  const Dims0 reduction_axis0;\n  Tensor<float, 4> result0 = tensor.sum(reduction_axis0);\n  for (int m = 0; m < 11; ++m) {\n    for (int l = 0; l < 7; ++l) {\n      for (int k = 0; k < 5; ++k) {\n        for (int j = 0; j < 3; ++j) {\n          float expected = 0.0f;\n          for (int i = 0; i < 2; ++i) {\n            expected += tensor(i,j,k,l,m);\n          }\n          VERIFY_IS_APPROX(result0(j,k,l,m), expected);\n        }\n      }\n    }\n  }\n\n  const Dims1 reduction_axis1;\n  Tensor<float, 3> result1 = tensor.sum(reduction_axis1);\n  for (int m = 0; m < 11; ++m) {\n    for (int l = 0; l < 7; ++l) {\n      for (int k = 0; k < 5; ++k) {\n        float expected = 0.0f;\n        for (int j = 0; j < 3; ++j) {\n          for (int i = 0; i < 2; ++i) {\n            expected += tensor(i,j,k,l,m);\n          }\n        }\n        VERIFY_IS_APPROX(result1(k,l,m), expected);\n      }\n    }\n  }\n\n  const Dims2 reduction_axis2;\n  Tensor<float, 2> result2 = tensor.sum(reduction_axis2);\n  for (int m = 0; m < 11; ++m) {\n    for (int l = 0; l < 7; ++l) {\n      float expected = 0.0f;\n      for (int k = 0; k < 5; ++k) {\n        for (int j = 0; j < 3; ++j) {\n          for (int i = 0; i < 2; ++i) {\n            expected += tensor(i,j,k,l,m);\n          }\n        }\n      }\n      VERIFY_IS_APPROX(result2(l,m), expected);\n    }\n  }\n\n  const Dims3 reduction_axis3;\n  Tensor<float, 1> result3 = tensor.sum(reduction_axis3);\n  for (int m = 0; m < 11; ++m) {\n    float expected = 0.0f;\n    for (int l = 0; l < 7; ++l) {\n      for (int k = 0; k < 5; ++k) {\n        for (int j = 0; j < 3; ++j) {\n          for (int i = 0; i < 2; ++i) {\n            expected += tensor(i,j,k,l,m);\n          }\n        }\n      }\n    }\n    VERIFY_IS_APPROX(result3(m), expected);\n  }\n\n  const Dims4 reduction_axis4;\n  Tensor<float, 0> result4 = tensor.sum(reduction_axis4);\n  float expected = 0.0f;\n  for (int m = 0; m < 11; ++m) {\n    for (int l = 0; l < 7; ++l) {\n      for (int k = 0; k < 5; ++k) {\n        for (int j = 0; j < 3; ++j) {\n          for (int i = 0; i < 2; ++i) {\n            expected += tensor(i,j,k,l,m);\n          }\n        }\n      }\n    }\n  }\n  VERIFY_IS_APPROX(result4(), expected);\n}\n\n\nstatic void test_type2indexpair_list()\n{\n  Tensor<float, 5> tensor(2,3,5,7,11);\n  tensor.setRandom();\n  tensor += tensor.constant(10.0f);\n\n  typedef Eigen::IndexPairList<Eigen::type2indexpair<0,10>> Dims0;\n  typedef Eigen::IndexPairList<Eigen::type2indexpair<0,10>, Eigen::type2indexpair<1,11>, Eigen::type2indexpair<2,12>> Dims2_a;\n  typedef Eigen::IndexPairList<Eigen::type2indexpair<0,10>, Eigen::IndexPair<Index>, Eigen::type2indexpair<2,12>> Dims2_b;\n  typedef Eigen::IndexPairList<Eigen::IndexPair<Index>, Eigen::type2indexpair<1,11>, Eigen::IndexPair<Index>> Dims2_c;\n\n  Dims2_a d2_a;\n\n  Dims2_b d2_b;\n  d2_b.set(1, Eigen::IndexPair<Index>(1,11));\n\n  Dims2_c d2_c;\n  d2_c.set(0, Eigen::IndexPair<Index>(Eigen::IndexPair<Index>(0,10)));\n  d2_c.set(1, Eigen::IndexPair<Index>(1,11));  // setting type2indexpair to correct value.\n  d2_c.set(2, Eigen::IndexPair<Index>(2,12));\n\n  VERIFY_IS_EQUAL(d2_a[0].first, 0);\n  VERIFY_IS_EQUAL(d2_a[0].second, 10);\n  VERIFY_IS_EQUAL(d2_a[1].first, 1);\n  VERIFY_IS_EQUAL(d2_a[1].second, 11);\n  VERIFY_IS_EQUAL(d2_a[2].first, 2);\n  VERIFY_IS_EQUAL(d2_a[2].second, 12);\n\n  VERIFY_IS_EQUAL(d2_b[0].first, 0);\n  VERIFY_IS_EQUAL(d2_b[0].second, 10);\n  VERIFY_IS_EQUAL(d2_b[1].first, 1);\n  VERIFY_IS_EQUAL(d2_b[1].second, 11);\n  VERIFY_IS_EQUAL(d2_b[2].first, 2);\n  VERIFY_IS_EQUAL(d2_b[2].second, 12);\n\n  VERIFY_IS_EQUAL(d2_c[0].first, 0);\n  VERIFY_IS_EQUAL(d2_c[0].second, 10);\n  VERIFY_IS_EQUAL(d2_c[1].first, 1);\n  VERIFY_IS_EQUAL(d2_c[1].second, 11);\n  VERIFY_IS_EQUAL(d2_c[2].first, 2);\n  VERIFY_IS_EQUAL(d2_c[2].second, 12);\n\n  EIGEN_STATIC_ASSERT((d2_a.value_known_statically(0) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((d2_a.value_known_statically(1) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((d2_a.value_known_statically(2) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((d2_b.value_known_statically(0) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((d2_b.value_known_statically(1) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((d2_b.value_known_statically(2) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((d2_c.value_known_statically(0) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((d2_c.value_known_statically(1) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((d2_c.value_known_statically(2) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims0>(0, 0) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims0>(0, 1) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_a>(0, 0) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_a>(0, 1) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_a>(1, 1) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_a>(1, 2) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_a>(2, 2) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_a>(2, 3) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_b>(0, 0) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_b>(0, 1) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_b>(1, 1) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_b>(1, 2) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_b>(2, 2) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_b>(2, 3) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_c>(0, 0) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_c>(0, 1) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_c>(1, 1) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_c>(1, 2) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_c>(2, 2) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_first_statically_eq<Dims2_c>(2, 3) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims0>(0, 10) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims0>(0, 11) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_a>(0, 10) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_a>(0, 11) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_a>(1, 11) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_a>(1, 12) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_a>(2, 12) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_a>(2, 13) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_b>(0, 10) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_b>(0, 11) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_b>(1, 11) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_b>(1, 12) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_b>(2, 12) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_b>(2, 13) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_c>(0, 10) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_c>(0, 11) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_c>(1, 11) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_c>(1, 12) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_c>(2, 12) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((Eigen::internal::index_pair_second_statically_eq<Dims2_c>(2, 13) == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n}\n\n\nstatic void test_dynamic_index_list()\n{\n  Tensor<float, 4> tensor(2,3,5,7);\n  tensor.setRandom();\n\n  int dim1 = 2;\n  int dim2 = 1;\n  int dim3 = 0;\n\n  auto reduction_axis = make_index_list(dim1, dim2, dim3);\n\n  VERIFY_IS_EQUAL(internal::array_get<0>(reduction_axis), 2);\n  VERIFY_IS_EQUAL(internal::array_get<1>(reduction_axis), 1);\n  VERIFY_IS_EQUAL(internal::array_get<2>(reduction_axis), 0);\n  VERIFY_IS_EQUAL(static_cast<Index>(reduction_axis[0]), 2);\n  VERIFY_IS_EQUAL(static_cast<Index>(reduction_axis[1]), 1);\n  VERIFY_IS_EQUAL(static_cast<Index>(reduction_axis[2]), 0);\n\n  Tensor<float, 1> result = tensor.sum(reduction_axis);\n  for (int i = 0; i < result.size(); ++i) {\n    float expected = 0.0f;\n    for (int j = 0; j < 2; ++j) {\n      for (int k = 0; k < 3; ++k) {\n        for (int l = 0; l < 5; ++l) {\n          expected += tensor(j,k,l,i);\n        }\n      }\n    }\n    VERIFY_IS_APPROX(result(i), expected);\n  }\n}\n\nstatic void test_mixed_index_list()\n{\n  Tensor<float, 4> tensor(2,3,5,7);\n  tensor.setRandom();\n\n  int dim2 = 1;\n  int dim4 = 3;\n\n  auto reduction_axis = make_index_list(0, dim2, 2, dim4);\n\n  VERIFY_IS_EQUAL(internal::array_get<0>(reduction_axis), 0);\n  VERIFY_IS_EQUAL(internal::array_get<1>(reduction_axis), 1);\n  VERIFY_IS_EQUAL(internal::array_get<2>(reduction_axis), 2);\n  VERIFY_IS_EQUAL(internal::array_get<3>(reduction_axis), 3);\n  VERIFY_IS_EQUAL(static_cast<Index>(reduction_axis[0]), 0);\n  VERIFY_IS_EQUAL(static_cast<Index>(reduction_axis[1]), 1);\n  VERIFY_IS_EQUAL(static_cast<Index>(reduction_axis[2]), 2);\n  VERIFY_IS_EQUAL(static_cast<Index>(reduction_axis[3]), 3);\n\n  typedef IndexList<type2index<0>, int, type2index<2>, int> ReductionIndices;\n  ReductionIndices reduction_indices;\n  reduction_indices.set(1, 1);\n  reduction_indices.set(3, 3);\n  EIGEN_STATIC_ASSERT((internal::array_get<0>(reduction_indices) == 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::array_get<2>(reduction_indices) == 2), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::index_known_statically<ReductionIndices>(0) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::index_known_statically<ReductionIndices>(2) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::index_statically_eq<ReductionIndices>(0, 0) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::index_statically_eq<ReductionIndices>(2, 2) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n#if 0\n  EIGEN_STATIC_ASSERT((internal::all_indices_known_statically<ReductionIndices>() == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::indices_statically_known_to_increase<ReductionIndices>() == false), YOU_MADE_A_PROGRAMMING_MISTAKE);\n#endif\n\n  typedef IndexList<type2index<0>, type2index<1>, type2index<2>, type2index<3>> ReductionList;\n  ReductionList reduction_list;\n  EIGEN_STATIC_ASSERT((internal::index_statically_eq<ReductionList>(0, 0) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::index_statically_eq<ReductionList>(1, 1) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::index_statically_eq<ReductionList>(2, 2) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::index_statically_eq<ReductionList>(3, 3) == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n#if 0\n  EIGEN_STATIC_ASSERT((internal::all_indices_known_statically<ReductionList>() == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::indices_statically_known_to_increase<ReductionList>() == true), YOU_MADE_A_PROGRAMMING_MISTAKE);\n#endif\n\n  Tensor<float, 0> result1 = tensor.sum(reduction_axis);\n  Tensor<float, 0> result2 = tensor.sum(reduction_indices);\n  Tensor<float, 0> result3 = tensor.sum(reduction_list);\n\n  float expected = 0.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          expected += tensor(i,j,k,l);\n        }\n      }\n    }\n  }\n  VERIFY_IS_APPROX(result1(), expected);\n  VERIFY_IS_APPROX(result2(), expected);\n  VERIFY_IS_APPROX(result3(), expected);\n}\n\n\nstatic void test_dim_check()\n{\n  Eigen::IndexList<Eigen::type2index<1>, int> dim1;\n  dim1.set(1, 2);\n  Eigen::IndexList<Eigen::type2index<1>, int> dim2;\n  dim2.set(1, 2);\n  VERIFY(dimensions_match(dim1, dim2));\n}\n\n\n#endif\n\nEIGEN_DECLARE_TEST(cxx11_tensor_index_list)\n{\n#ifdef EIGEN_HAS_INDEX_LIST\n  CALL_SUBTEST(test_static_index_list());\n  CALL_SUBTEST(test_type2index_list());\n  CALL_SUBTEST(test_type2indexpair_list());\n  CALL_SUBTEST(test_dynamic_index_list());\n  CALL_SUBTEST(test_mixed_index_list());\n  CALL_SUBTEST(test_dim_check());\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_inflation.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Ke Yang <yangke@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate<int DataLayout>\nstatic void test_simple_inflation()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> strides;\n\n  strides[0] = 1;\n  strides[1] = 1;\n  strides[2] = 1;\n  strides[3] = 1;\n\n  Tensor<float, 4, DataLayout> no_stride;\n  no_stride = tensor.inflate(strides);\n\n  VERIFY_IS_EQUAL(no_stride.dimension(0), 2);\n  VERIFY_IS_EQUAL(no_stride.dimension(1), 3);\n  VERIFY_IS_EQUAL(no_stride.dimension(2), 5);\n  VERIFY_IS_EQUAL(no_stride.dimension(3), 7);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), no_stride(i,j,k,l));\n        }\n      }\n    }\n  }\n\n  strides[0] = 2;\n  strides[1] = 4;\n  strides[2] = 2;\n  strides[3] = 3;\n  Tensor<float, 4, DataLayout> inflated;\n  inflated = tensor.inflate(strides);\n\n  VERIFY_IS_EQUAL(inflated.dimension(0), 3);\n  VERIFY_IS_EQUAL(inflated.dimension(1), 9);\n  VERIFY_IS_EQUAL(inflated.dimension(2), 9);\n  VERIFY_IS_EQUAL(inflated.dimension(3), 19);\n\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 9; ++j) {\n      for (int k = 0; k < 9; ++k) {\n        for (int l = 0; l < 19; ++l) {\n          if (i % 2 == 0 &&\n              j % 4 == 0 &&\n              k % 2 == 0 &&\n              l % 3 == 0) {\n            VERIFY_IS_EQUAL(inflated(i,j,k,l),\n                            tensor(i/2, j/4, k/2, l/3));\n          } else {\n            VERIFY_IS_EQUAL(0, inflated(i,j,k,l));\n          }\n        }\n      }\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_inflation)\n{\n  CALL_SUBTEST(test_simple_inflation<ColMajor>());\n  CALL_SUBTEST(test_simple_inflation<RowMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_inflation_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\n// Inflation Definition for each dimension the inflated val would be\n//((dim-1)*strid[dim] +1)\n\n// for 1 dimension vector of size 3 with value (4,4,4) with the inflated stride value of 3 would be changed to\n// tensor of size (2*3) +1 = 7 with the value of\n// (4, 0, 0, 4, 0, 0, 4).\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_simple_inflation_sycl(const Eigen::SyclDevice &sycl_device) {\n\n\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  array<IndexType, 4> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  Tensor<DataType, 4, DataLayout,IndexType> tensor(tensorRange);\n  Tensor<DataType, 4, DataLayout,IndexType> no_stride(tensorRange);\n  tensor.setRandom();\n\n  array<IndexType, 4> strides;\n  strides[0] = 1;\n  strides[1] = 1;\n  strides[2] = 1;\n  strides[3] = 1;\n\n\n  const size_t tensorBuffSize =tensor.size()*sizeof(DataType);\n  DataType* gpu_data_tensor  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  DataType* gpu_data_no_stride  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_tensor(gpu_data_tensor, tensorRange);\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_no_stride(gpu_data_no_stride, tensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_tensor, tensor.data(), tensorBuffSize);\n  gpu_no_stride.device(sycl_device)=gpu_tensor.inflate(strides);\n  sycl_device.memcpyDeviceToHost(no_stride.data(), gpu_data_no_stride, tensorBuffSize);\n\n  VERIFY_IS_EQUAL(no_stride.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(no_stride.dimension(1), sizeDim2);\n  VERIFY_IS_EQUAL(no_stride.dimension(2), sizeDim3);\n  VERIFY_IS_EQUAL(no_stride.dimension(3), sizeDim4);\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      for (IndexType k = 0; k < 5; ++k) {\n        for (IndexType l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), no_stride(i,j,k,l));\n        }\n      }\n    }\n  }\n\n\n  strides[0] = 2;\n  strides[1] = 4;\n  strides[2] = 2;\n  strides[3] = 3;\n\n  IndexType inflatedSizeDim1 = 3;\n  IndexType inflatedSizeDim2 = 9;\n  IndexType inflatedSizeDim3 = 9;\n  IndexType inflatedSizeDim4 = 19;\n  array<IndexType, 4> inflatedTensorRange = {{inflatedSizeDim1, inflatedSizeDim2, inflatedSizeDim3, inflatedSizeDim4}};\n\n  Tensor<DataType, 4, DataLayout, IndexType> inflated(inflatedTensorRange);\n\n  const size_t inflatedTensorBuffSize =inflated.size()*sizeof(DataType);\n  DataType* gpu_data_inflated  = static_cast<DataType*>(sycl_device.allocate(inflatedTensorBuffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType>> gpu_inflated(gpu_data_inflated, inflatedTensorRange);\n  gpu_inflated.device(sycl_device)=gpu_tensor.inflate(strides);\n  sycl_device.memcpyDeviceToHost(inflated.data(), gpu_data_inflated, inflatedTensorBuffSize);\n\n  VERIFY_IS_EQUAL(inflated.dimension(0), inflatedSizeDim1);\n  VERIFY_IS_EQUAL(inflated.dimension(1), inflatedSizeDim2);\n  VERIFY_IS_EQUAL(inflated.dimension(2), inflatedSizeDim3);\n  VERIFY_IS_EQUAL(inflated.dimension(3), inflatedSizeDim4);\n\n  for (IndexType i = 0; i < inflatedSizeDim1; ++i) {\n    for (IndexType j = 0; j < inflatedSizeDim2; ++j) {\n      for (IndexType k = 0; k < inflatedSizeDim3; ++k) {\n        for (IndexType l = 0; l < inflatedSizeDim4; ++l) {\n          if (i % strides[0] == 0 &&\n              j % strides[1] == 0 &&\n              k % strides[2] == 0 &&\n              l % strides[3] == 0) {\n            VERIFY_IS_EQUAL(inflated(i,j,k,l),\n                            tensor(i/strides[0], j/strides[1], k/strides[2], l/strides[3]));\n          } else {\n            VERIFY_IS_EQUAL(0, inflated(i,j,k,l));\n          }\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data_tensor);\n  sycl_device.deallocate(gpu_data_no_stride);\n  sycl_device.deallocate(gpu_data_inflated);\n}\n\ntemplate<typename DataType, typename dev_Selector> void sycl_inflation_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_simple_inflation_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_simple_inflation_sycl<DataType, ColMajor, int64_t>(sycl_device);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_inflation_sycl)\n{\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_inflation_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_intdiv.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014-2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\n\nvoid test_signed_32bit()\n{\n  // Divide by one\n  const Eigen::internal::TensorIntDivisor<int32_t, false> div_by_one(1);\n\n  for (int32_t j = 0; j < 25000; ++j) {\n    const int32_t fast_div = j / div_by_one;\n    const int32_t slow_div = j / 1;\n    VERIFY_IS_EQUAL(fast_div, slow_div);\n  }\n\n  // Standard divide by 2 or more\n  for (int32_t i = 2; i < 25000; ++i) {\n    const Eigen::internal::TensorIntDivisor<int32_t, false> div(i);\n\n    for (int32_t j = 0; j < 25000; ++j) {\n      const int32_t fast_div = j / div;\n      const int32_t slow_div = j / i;\n      VERIFY_IS_EQUAL(fast_div, slow_div);\n    }\n  }\n\n  // Optimized divide by 2 or more\n  for (int32_t i = 2; i < 25000; ++i) {\n    const Eigen::internal::TensorIntDivisor<int32_t, true> div(i);\n\n    for (int32_t j = 0; j < 25000; ++j) {\n      const int32_t fast_div = j / div;\n      const int32_t slow_div = j / i;\n      VERIFY_IS_EQUAL(fast_div, slow_div);\n    }\n  }\n}\n\n\nvoid test_unsigned_32bit()\n{\n  for (uint32_t i = 1; i < 25000; ++i) {\n    const Eigen::internal::TensorIntDivisor<uint32_t> div(i);\n\n    for (uint32_t j = 0; j < 25000; ++j) {\n      const uint32_t fast_div = j / div;\n      const uint32_t slow_div = j / i;\n      VERIFY_IS_EQUAL(fast_div, slow_div);\n    }\n  }\n}\n\n\nvoid test_signed_64bit()\n{\n  for (int64_t i = 1; i < 25000; ++i) {\n    const Eigen::internal::TensorIntDivisor<int64_t> div(i);\n\n    for (int64_t j = 0; j < 25000; ++j) {\n      const int64_t fast_div = j / div;\n      const int64_t slow_div = j / i;\n      VERIFY_IS_EQUAL(fast_div, slow_div);\n    }\n  }\n}\n\n\nvoid test_unsigned_64bit()\n{\n  for (uint64_t i = 1; i < 25000; ++i) {\n    const Eigen::internal::TensorIntDivisor<uint64_t> div(i);\n\n    for (uint64_t j = 0; j < 25000; ++j) {\n      const uint64_t fast_div = j / div;\n      const uint64_t slow_div = j / i;\n      VERIFY_IS_EQUAL(fast_div, slow_div);\n    }\n  }\n}\n\nvoid test_powers_32bit() {\n  for (int expon = 1; expon < 31; expon++) {\n    int32_t div = (1 << expon);\n    for (int num_expon = 0; num_expon < 32; num_expon++) {\n      int32_t start_num = (1 << num_expon) - 100;\n      int32_t end_num = (1 << num_expon) + 100;\n      if (start_num < 0)\n        start_num = 0;\n      for (int32_t num = start_num; num < end_num; num++) {\n        Eigen::internal::TensorIntDivisor<int32_t> divider =\n          Eigen::internal::TensorIntDivisor<int32_t>(div);\n        int32_t result = num/div;\n        int32_t result_op = divider.divide(num);\n        VERIFY_IS_EQUAL(result_op, result);\n      }\n    }\n  }\n}\n\nvoid test_powers_64bit() {\n  for (int expon = 0; expon < 63; expon++) {\n    int64_t div = (1ull << expon);\n    for (int num_expon = 0; num_expon < 63; num_expon++) {\n      int64_t start_num = (1ull << num_expon) - 10;\n      int64_t end_num = (1ull << num_expon) + 10;\n      if (start_num < 0)\n        start_num = 0;\n      for (int64_t num = start_num; num < end_num; num++) {\n        Eigen::internal::TensorIntDivisor<int64_t> divider(div);\n        int64_t result = num/div;\n        int64_t result_op = divider.divide(num);\n        VERIFY_IS_EQUAL(result_op, result);\n      }\n    }\n  }\n}\n\nvoid test_specific() {\n  // A particular combination that was previously failing\n  int64_t div = 209715200;\n  int64_t num = 3238002688ll;\n  Eigen::internal::TensorIntDivisor<int64_t> divider(div);\n  int64_t result = num/div;\n  int64_t result_op = divider.divide(num);\n  VERIFY_IS_EQUAL(result, result_op);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_intdiv)\n{\n  CALL_SUBTEST_1(test_signed_32bit());\n  CALL_SUBTEST_2(test_unsigned_32bit());\n  CALL_SUBTEST_3(test_signed_64bit());\n  CALL_SUBTEST_4(test_unsigned_64bit());\n  CALL_SUBTEST_5(test_powers_32bit());\n  CALL_SUBTEST_6(test_powers_64bit());\n  CALL_SUBTEST_7(test_specific());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_io.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <sstream>\n#include <string>\n#include <Eigen/CXX11/Tensor>\n\n\ntemplate<int DataLayout>\nstatic void test_output_0d()\n{\n  Tensor<int, 0, DataLayout> tensor;\n  tensor() = 123;\n\n  std::stringstream os;\n  os << tensor;\n\n  std::string expected(\"123\");\n  VERIFY_IS_EQUAL(std::string(os.str()), expected);\n}\n\n\ntemplate<int DataLayout>\nstatic void test_output_1d()\n{\n  Tensor<int, 1, DataLayout> tensor(5);\n  for (int i = 0; i < 5; ++i) {\n    tensor(i) = i;\n  }\n\n  std::stringstream os;\n  os << tensor;\n\n  std::string expected(\"0\\n1\\n2\\n3\\n4\");\n  VERIFY_IS_EQUAL(std::string(os.str()), expected);\n\n  Eigen::Tensor<double,1,DataLayout> empty_tensor(0);\n  std::stringstream empty_os;\n  empty_os << empty_tensor;\n  std::string empty_string;\n  VERIFY_IS_EQUAL(std::string(empty_os.str()), empty_string);\n}\n\n\ntemplate<int DataLayout>\nstatic void test_output_2d()\n{\n  Tensor<int, 2, DataLayout> tensor(5, 3);\n  for (int i = 0; i < 5; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      tensor(i, j) = i*j;\n    }\n  }\n\n  std::stringstream os;\n  os << tensor;\n\n  std::string expected(\"0  0  0\\n0  1  2\\n0  2  4\\n0  3  6\\n0  4  8\");\n  VERIFY_IS_EQUAL(std::string(os.str()), expected);\n}\n\n\ntemplate<int DataLayout>\nstatic void test_output_expr()\n{\n  Tensor<int, 1, DataLayout> tensor1(5);\n  Tensor<int, 1, DataLayout> tensor2(5);\n  for (int i = 0; i < 5; ++i) {\n    tensor1(i) = i;\n    tensor2(i) = 7;\n  }\n\n  std::stringstream os;\n  os << tensor1 + tensor2;\n\n  std::string expected(\" 7\\n 8\\n 9\\n10\\n11\");\n  VERIFY_IS_EQUAL(std::string(os.str()), expected);\n}\n\n\ntemplate<int DataLayout>\nstatic void test_output_string()\n{\n  Tensor<std::string, 2, DataLayout> tensor(5, 3);\n  tensor.setConstant(std::string(\"foo\"));\n\n  std::cout << tensor << std::endl;\n\n  std::stringstream os;\n  os << tensor;\n\n  std::string expected(\"foo  foo  foo\\nfoo  foo  foo\\nfoo  foo  foo\\nfoo  foo  foo\\nfoo  foo  foo\");\n  VERIFY_IS_EQUAL(std::string(os.str()), expected);\n}\n\n\ntemplate<int DataLayout>\nstatic void test_output_const()\n{\n  Tensor<int, 1, DataLayout> tensor(5);\n  for (int i = 0; i < 5; ++i) {\n    tensor(i) = i;\n  }\n\n  TensorMap<Tensor<const int, 1, DataLayout> > tensor_map(tensor.data(), 5);\n\n  std::stringstream os;\n  os << tensor_map;\n\n  std::string expected(\"0\\n1\\n2\\n3\\n4\");\n  VERIFY_IS_EQUAL(std::string(os.str()), expected);\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_io)\n{\n  CALL_SUBTEST(test_output_0d<ColMajor>());\n  CALL_SUBTEST(test_output_0d<RowMajor>());\n  CALL_SUBTEST(test_output_1d<ColMajor>());\n  CALL_SUBTEST(test_output_1d<RowMajor>());\n  CALL_SUBTEST(test_output_2d<ColMajor>());\n  CALL_SUBTEST(test_output_2d<RowMajor>());\n  CALL_SUBTEST(test_output_expr<ColMajor>());\n  CALL_SUBTEST(test_output_expr<RowMajor>());\n  CALL_SUBTEST(test_output_string<ColMajor>());\n  CALL_SUBTEST(test_output_string<RowMajor>());\n  CALL_SUBTEST(test_output_const<ColMajor>());\n  CALL_SUBTEST(test_output_const<RowMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_layout_swap.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\nstatic void test_simple_swap()\n{\n  Tensor<float, 3, ColMajor> tensor(2,3,7);\n  tensor.setRandom();\n\n  Tensor<float, 3, RowMajor> tensor2 = tensor.swap_layout();\n  VERIFY_IS_EQUAL(tensor.dimension(0), tensor2.dimension(2));\n  VERIFY_IS_EQUAL(tensor.dimension(1), tensor2.dimension(1));\n  VERIFY_IS_EQUAL(tensor.dimension(2), tensor2.dimension(0));\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(tensor(i,j,k), tensor2(k,j,i));\n      }\n    }\n  }\n}\n\n\nstatic void test_swap_as_lvalue()\n{\n  Tensor<float, 3, ColMajor> tensor(2,3,7);\n  tensor.setRandom();\n\n  Tensor<float, 3, RowMajor> tensor2(7,3,2);\n  tensor2.swap_layout() = tensor;\n  VERIFY_IS_EQUAL(tensor.dimension(0), tensor2.dimension(2));\n  VERIFY_IS_EQUAL(tensor.dimension(1), tensor2.dimension(1));\n  VERIFY_IS_EQUAL(tensor.dimension(2), tensor2.dimension(0));\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(tensor(i,j,k), tensor2(k,j,i));\n      }\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_layout_swap)\n{\n  CALL_SUBTEST(test_simple_swap());\n  CALL_SUBTEST(test_swap_as_lvalue());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_layout_swap_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate <typename DataType, typename IndexType>\nstatic void test_simple_swap_sycl(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 7;\n  array<IndexType, 3> tensorColRange = {{sizeDim1, sizeDim2, sizeDim3}};\n  array<IndexType, 3> tensorRowRange = {{sizeDim3, sizeDim2, sizeDim1}};\n\n\n  Tensor<DataType, 3, ColMajor, IndexType> tensor1(tensorColRange);\n  Tensor<DataType, 3, RowMajor, IndexType> tensor2(tensorRowRange);\n  tensor1.setRandom();\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(tensor1.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(tensor2.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 3, ColMajor, IndexType>> gpu1(gpu_data1, tensorColRange);\n  TensorMap<Tensor<DataType, 3, RowMajor, IndexType>> gpu2(gpu_data2, tensorRowRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor1.data(),(tensor1.size())*sizeof(DataType));\n  gpu2.device(sycl_device)=gpu1.swap_layout();\n  sycl_device.memcpyDeviceToHost(tensor2.data(), gpu_data2,(tensor2.size())*sizeof(DataType));\n\n\n//  Tensor<float, 3, ColMajor> tensor(2,3,7);\n  //tensor.setRandom();\n\n//  Tensor<float, 3, RowMajor> tensor2 = tensor.swap_layout();\n  VERIFY_IS_EQUAL(tensor1.dimension(0), tensor2.dimension(2));\n  VERIFY_IS_EQUAL(tensor1.dimension(1), tensor2.dimension(1));\n  VERIFY_IS_EQUAL(tensor1.dimension(2), tensor2.dimension(0));\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      for (IndexType k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(tensor1(i,j,k), tensor2(k,j,i));\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n}\n\ntemplate <typename DataType, typename IndexType>\nstatic void test_swap_as_lvalue_sycl(const Eigen::SyclDevice& sycl_device)\n{\n\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 7;\n  array<IndexType, 3> tensorColRange = {{sizeDim1, sizeDim2, sizeDim3}};\n  array<IndexType, 3> tensorRowRange = {{sizeDim3, sizeDim2, sizeDim1}};\n\n  Tensor<DataType, 3, ColMajor, IndexType> tensor1(tensorColRange);\n  Tensor<DataType, 3, RowMajor, IndexType> tensor2(tensorRowRange);\n  tensor1.setRandom();\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(tensor1.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(tensor2.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 3, ColMajor, IndexType>> gpu1(gpu_data1, tensorColRange);\n  TensorMap<Tensor<DataType, 3, RowMajor, IndexType>> gpu2(gpu_data2, tensorRowRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor1.data(),(tensor1.size())*sizeof(DataType));\n  gpu2.swap_layout().device(sycl_device)=gpu1;\n  sycl_device.memcpyDeviceToHost(tensor2.data(), gpu_data2,(tensor2.size())*sizeof(DataType));\n\n\n//  Tensor<float, 3, ColMajor> tensor(2,3,7);\n//  tensor.setRandom();\n\n  //Tensor<float, 3, RowMajor> tensor2(7,3,2);\n//  tensor2.swap_layout() = tensor;\n  VERIFY_IS_EQUAL(tensor1.dimension(0), tensor2.dimension(2));\n  VERIFY_IS_EQUAL(tensor1.dimension(1), tensor2.dimension(1));\n  VERIFY_IS_EQUAL(tensor1.dimension(2), tensor2.dimension(0));\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      for (IndexType k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(tensor1(i,j,k), tensor2(k,j,i));\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n}\n\n\ntemplate<typename DataType, typename dev_Selector> void sycl_tensor_layout_swap_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_simple_swap_sycl<DataType, int64_t>(sycl_device);\n  test_swap_as_lvalue_sycl<DataType, int64_t>(sycl_device);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_layout_swap_sycl)\n{\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_tensor_layout_swap_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_lvalue.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\n\nstatic void test_compound_assignment()\n{\n  Tensor<float, 3> mat1(2,3,7);\n  Tensor<float, 3> mat2(2,3,7);\n  Tensor<float, 3> mat3(2,3,7);\n\n  mat1.setRandom();\n  mat2.setRandom();\n  mat3 = mat1;\n  mat3 += mat2;\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(mat3(i,j,k), mat1(i,j,k) + mat2(i,j,k));\n      }\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_lvalue)\n{\n  CALL_SUBTEST(test_compound_assignment());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_map.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\nstatic void test_0d()\n{\n  Tensor<int, 0> scalar1;\n  Tensor<int, 0, RowMajor> scalar2;\n\n  TensorMap<const Tensor<int, 0> > scalar3(scalar1.data());\n  TensorMap<const Tensor<int, 0, RowMajor> > scalar4(scalar2.data());\n\n  scalar1() = 7;\n  scalar2() = 13;\n\n  VERIFY_IS_EQUAL(scalar1.rank(), 0);\n  VERIFY_IS_EQUAL(scalar1.size(), 1);\n\n  VERIFY_IS_EQUAL(scalar3(), 7);\n  VERIFY_IS_EQUAL(scalar4(), 13);\n}\n\nstatic void test_1d()\n{\n  Tensor<int, 1> vec1(6);\n  Tensor<int, 1, RowMajor> vec2(6);\n\n  TensorMap<const Tensor<int, 1> > vec3(vec1.data(), 6);\n  TensorMap<const Tensor<int, 1, RowMajor> > vec4(vec2.data(), 6);\n\n  vec1(0) = 4;  vec2(0) = 0;\n  vec1(1) = 8;  vec2(1) = 1;\n  vec1(2) = 15; vec2(2) = 2;\n  vec1(3) = 16; vec2(3) = 3;\n  vec1(4) = 23; vec2(4) = 4;\n  vec1(5) = 42; vec2(5) = 5;\n\n  VERIFY_IS_EQUAL(vec1.rank(), 1);\n  VERIFY_IS_EQUAL(vec1.size(), 6);\n  VERIFY_IS_EQUAL(vec1.dimension(0), 6);\n\n  VERIFY_IS_EQUAL(vec3(0), 4);\n  VERIFY_IS_EQUAL(vec3(1), 8);\n  VERIFY_IS_EQUAL(vec3(2), 15);\n  VERIFY_IS_EQUAL(vec3(3), 16);\n  VERIFY_IS_EQUAL(vec3(4), 23);\n  VERIFY_IS_EQUAL(vec3(5), 42);\n\n  VERIFY_IS_EQUAL(vec4(0), 0);\n  VERIFY_IS_EQUAL(vec4(1), 1);\n  VERIFY_IS_EQUAL(vec4(2), 2);\n  VERIFY_IS_EQUAL(vec4(3), 3);\n  VERIFY_IS_EQUAL(vec4(4), 4);\n  VERIFY_IS_EQUAL(vec4(5), 5);\n}\n\nstatic void test_2d()\n{\n  Tensor<int, 2> mat1(2,3);\n  Tensor<int, 2, RowMajor> mat2(2,3);\n\n  mat1(0,0) = 0;\n  mat1(0,1) = 1;\n  mat1(0,2) = 2;\n  mat1(1,0) = 3;\n  mat1(1,1) = 4;\n  mat1(1,2) = 5;\n\n  mat2(0,0) = 0;\n  mat2(0,1) = 1;\n  mat2(0,2) = 2;\n  mat2(1,0) = 3;\n  mat2(1,1) = 4;\n  mat2(1,2) = 5;\n\n  TensorMap<const Tensor<int, 2> > mat3(mat1.data(), 2, 3);\n  TensorMap<const Tensor<int, 2, RowMajor> > mat4(mat2.data(), 2, 3);\n\n  VERIFY_IS_EQUAL(mat3.rank(), 2);\n  VERIFY_IS_EQUAL(mat3.size(), 6);\n  VERIFY_IS_EQUAL(mat3.dimension(0), 2);\n  VERIFY_IS_EQUAL(mat3.dimension(1), 3);\n\n  VERIFY_IS_EQUAL(mat4.rank(), 2);\n  VERIFY_IS_EQUAL(mat4.size(), 6);\n  VERIFY_IS_EQUAL(mat4.dimension(0), 2);\n  VERIFY_IS_EQUAL(mat4.dimension(1), 3);\n\n  VERIFY_IS_EQUAL(mat3(0,0), 0);\n  VERIFY_IS_EQUAL(mat3(0,1), 1);\n  VERIFY_IS_EQUAL(mat3(0,2), 2);\n  VERIFY_IS_EQUAL(mat3(1,0), 3);\n  VERIFY_IS_EQUAL(mat3(1,1), 4);\n  VERIFY_IS_EQUAL(mat3(1,2), 5);\n\n  VERIFY_IS_EQUAL(mat4(0,0), 0);\n  VERIFY_IS_EQUAL(mat4(0,1), 1);\n  VERIFY_IS_EQUAL(mat4(0,2), 2);\n  VERIFY_IS_EQUAL(mat4(1,0), 3);\n  VERIFY_IS_EQUAL(mat4(1,1), 4);\n  VERIFY_IS_EQUAL(mat4(1,2), 5);\n}\n\nstatic void test_3d()\n{\n  Tensor<int, 3> mat1(2,3,7);\n  Tensor<int, 3, RowMajor> mat2(2,3,7);\n\n  int val = 0;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        mat1(i,j,k) = val;\n        mat2(i,j,k) = val;\n        val++;\n      }\n    }\n  }\n\n  TensorMap<const Tensor<int, 3> > mat3(mat1.data(), 2, 3, 7);\n  TensorMap<const Tensor<int, 3, RowMajor> > mat4(mat2.data(), 2, 3, 7);\n\n  VERIFY_IS_EQUAL(mat3.rank(), 3);\n  VERIFY_IS_EQUAL(mat3.size(), 2*3*7);\n  VERIFY_IS_EQUAL(mat3.dimension(0), 2);\n  VERIFY_IS_EQUAL(mat3.dimension(1), 3);\n  VERIFY_IS_EQUAL(mat3.dimension(2), 7);\n\n  VERIFY_IS_EQUAL(mat4.rank(), 3);\n  VERIFY_IS_EQUAL(mat4.size(), 2*3*7);\n  VERIFY_IS_EQUAL(mat4.dimension(0), 2);\n  VERIFY_IS_EQUAL(mat4.dimension(1), 3);\n  VERIFY_IS_EQUAL(mat4.dimension(2), 7);\n\n  val = 0;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(mat3(i,j,k), val);\n        VERIFY_IS_EQUAL(mat4(i,j,k), val);\n        val++;\n      }\n    }\n  }\n}\n\n\nstatic void test_from_tensor()\n{\n  Tensor<int, 3> mat1(2,3,7);\n  Tensor<int, 3, RowMajor> mat2(2,3,7);\n\n  int val = 0;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        mat1(i,j,k) = val;\n        mat2(i,j,k) = val;\n        val++;\n      }\n    }\n  }\n\n  TensorMap<Tensor<int, 3> > mat3(mat1);\n  TensorMap<Tensor<int, 3, RowMajor> > mat4(mat2);\n\n  VERIFY_IS_EQUAL(mat3.rank(), 3);\n  VERIFY_IS_EQUAL(mat3.size(), 2*3*7);\n  VERIFY_IS_EQUAL(mat3.dimension(0), 2);\n  VERIFY_IS_EQUAL(mat3.dimension(1), 3);\n  VERIFY_IS_EQUAL(mat3.dimension(2), 7);\n\n  VERIFY_IS_EQUAL(mat4.rank(), 3);\n  VERIFY_IS_EQUAL(mat4.size(), 2*3*7);\n  VERIFY_IS_EQUAL(mat4.dimension(0), 2);\n  VERIFY_IS_EQUAL(mat4.dimension(1), 3);\n  VERIFY_IS_EQUAL(mat4.dimension(2), 7);\n\n  val = 0;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(mat3(i,j,k), val);\n        VERIFY_IS_EQUAL(mat4(i,j,k), val);\n        val++;\n      }\n    }\n  }\n\n  TensorFixedSize<int, Sizes<2,3,7> > mat5;\n\n  val = 0;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        array<ptrdiff_t, 3> coords;\n        coords[0] = i;\n        coords[1] = j;\n        coords[2] = k;\n        mat5(coords) = val;\n        val++;\n      }\n    }\n  }\n\n  TensorMap<TensorFixedSize<int, Sizes<2,3,7> > > mat6(mat5);\n\n  VERIFY_IS_EQUAL(mat6.rank(), 3);\n  VERIFY_IS_EQUAL(mat6.size(), 2*3*7);\n  VERIFY_IS_EQUAL(mat6.dimension(0), 2);\n  VERIFY_IS_EQUAL(mat6.dimension(1), 3);\n  VERIFY_IS_EQUAL(mat6.dimension(2), 7);\n\n  val = 0;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(mat6(i,j,k), val);\n        val++;\n      }\n    }\n  }\n}\n\n\nstatic int f(const TensorMap<Tensor<int, 3> >& tensor) {\n  //  Size<0> empty;\n  EIGEN_STATIC_ASSERT((internal::array_size<Sizes<> >::value == 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  EIGEN_STATIC_ASSERT((internal::array_size<DSizes<int, 0> >::value == 0), YOU_MADE_A_PROGRAMMING_MISTAKE);\n  Tensor<int, 0> result = tensor.sum();\n  return result();\n}\n\nstatic void test_casting()\n{\n  Tensor<int, 3> tensor(2,3,7);\n\n  int val = 0;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        tensor(i,j,k) = val;\n        val++;\n      }\n    }\n  }\n\n  TensorMap<Tensor<int, 3> > map(tensor);\n  int sum1 = f(map);\n  int sum2 = f(tensor);\n\n  VERIFY_IS_EQUAL(sum1, sum2);\n  VERIFY_IS_EQUAL(sum1, 861);\n}\n\ntemplate<typename T>\nstatic const T& add_const(T& value) {\n  return value;\n}\n\nstatic void test_0d_const_tensor()\n{\n  Tensor<int, 0> scalar1;\n  Tensor<int, 0, RowMajor> scalar2;\n\n  TensorMap<const Tensor<int, 0> > scalar3(add_const(scalar1).data());\n  TensorMap<const Tensor<int, 0, RowMajor> > scalar4(add_const(scalar2).data());\n\n  scalar1() = 7;\n  scalar2() = 13;\n\n  VERIFY_IS_EQUAL(scalar1.rank(), 0);\n  VERIFY_IS_EQUAL(scalar1.size(), 1);\n\n  VERIFY_IS_EQUAL(scalar3(), 7);\n  VERIFY_IS_EQUAL(scalar4(), 13);\n}\n\nstatic void test_0d_const_tensor_map()\n{\n  Tensor<int, 0> scalar1;\n  Tensor<int, 0, RowMajor> scalar2;\n\n  const TensorMap<Tensor<int, 0> > scalar3(scalar1.data());\n  const TensorMap<Tensor<int, 0, RowMajor> > scalar4(scalar2.data());\n\n  // Although TensorMap is constant, we still can write to the underlying\n  // storage, because we map over non-constant Tensor.\n  scalar3() = 7;\n  scalar4() = 13;\n\n  VERIFY_IS_EQUAL(scalar1(), 7);\n  VERIFY_IS_EQUAL(scalar2(), 13);\n\n  // Pointer to the underlying storage is also non-const.\n  scalar3.data()[0] = 8;\n  scalar4.data()[0] = 14;\n\n  VERIFY_IS_EQUAL(scalar1(), 8);\n  VERIFY_IS_EQUAL(scalar2(), 14);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_map)\n{\n  CALL_SUBTEST(test_0d());\n  CALL_SUBTEST(test_1d());\n  CALL_SUBTEST(test_2d());\n  CALL_SUBTEST(test_3d());\n\n  CALL_SUBTEST(test_from_tensor());\n  CALL_SUBTEST(test_casting());\n\n  CALL_SUBTEST(test_0d_const_tensor());\n  CALL_SUBTEST(test_0d_const_tensor_map());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_math.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\nstatic void test_tanh()\n{\n  Tensor<float, 1> vec1(6);\n  vec1.setRandom();\n\n  Tensor<float, 1> vec2 = vec1.tanh();\n\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_APPROX(vec2(i), tanhf(vec1(i)));\n  }\n}\n\nstatic void test_sigmoid()\n{\n  Tensor<float, 1> vec1(6);\n  vec1.setRandom();\n\n  Tensor<float, 1> vec2 = vec1.sigmoid();\n\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_APPROX(vec2(i), 1.0f / (1.0f + std::exp(-vec1(i))));\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_math)\n{\n  CALL_SUBTEST(test_tanh());\n  CALL_SUBTEST(test_sigmoid());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_math_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_tanh_sycl(const Eigen::SyclDevice &sycl_device)\n{\n\n  IndexType sizeDim1 = 4;\n  IndexType sizeDim2 = 4;\n  IndexType sizeDim3 = 1;\n  array<IndexType, 3> tensorRange = {{sizeDim1, sizeDim2, sizeDim3}};\n  Tensor<DataType, 3, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 3, DataLayout, IndexType> out(tensorRange);\n  Tensor<DataType, 3, DataLayout, IndexType> out_cpu(tensorRange);\n\n  in = in.random();\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(in.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(out.size()*sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu1(gpu_data1, tensorRange);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu2(gpu_data2, tensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data1, in.data(),(in.size())*sizeof(DataType));\n  gpu2.device(sycl_device) = gpu1.tanh();\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_data2,(out.size())*sizeof(DataType));\n\n  out_cpu=in.tanh();\n\n  for (int i = 0; i < in.size(); ++i) {\n    VERIFY_IS_APPROX(out(i), out_cpu(i));\n  }\n}\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_sigmoid_sycl(const Eigen::SyclDevice &sycl_device)\n{\n\n  IndexType sizeDim1 = 4;\n  IndexType sizeDim2 = 4;\n  IndexType sizeDim3 = 1;\n  array<IndexType, 3> tensorRange = {{sizeDim1, sizeDim2, sizeDim3}};\n  Tensor<DataType, 3, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 3, DataLayout, IndexType> out(tensorRange);\n  Tensor<DataType, 3, DataLayout, IndexType> out_cpu(tensorRange);\n\n  in = in.random();\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(in.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(out.size()*sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu1(gpu_data1, tensorRange);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu2(gpu_data2, tensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data1, in.data(),(in.size())*sizeof(DataType));\n  gpu2.device(sycl_device) = gpu1.sigmoid();\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_data2,(out.size())*sizeof(DataType));\n\n  out_cpu=in.sigmoid();\n\n  for (int i = 0; i < in.size(); ++i) {\n    VERIFY_IS_APPROX(out(i), out_cpu(i));\n  }\n}\n\n\ntemplate<typename DataType, typename dev_Selector> void sycl_computing_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_tanh_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_tanh_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_sigmoid_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_sigmoid_sycl<DataType, ColMajor, int64_t>(sycl_device);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_math_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_computing_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_mixed_indices.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\n\nstatic void test_simple()\n{\n  Tensor<float, 1, ColMajor> vec1(6);\n  Tensor<float, 1, ColMajor, int> vec2(6);\n\n  vec1(0) = 4.0;  vec2(0) = 0.0;\n  vec1(1) = 8.0;  vec2(1) = 1.0;\n  vec1(2) = 15.0; vec2(2) = 2.0;\n  vec1(3) = 16.0; vec2(3) = 3.0;\n  vec1(4) = 23.0; vec2(4) = 4.0;\n  vec1(5) = 42.0; vec2(5) = 5.0;\n\n  float data3[6];\n  TensorMap<Tensor<float, 1, ColMajor>> vec3(data3, 6);\n  vec3 = vec1.sqrt();\n  float data4[6];\n  TensorMap<Tensor<float, 1, ColMajor, int>> vec4(data4, 6);\n  vec4 = vec2.square();\n\n  VERIFY_IS_APPROX(vec3(0), sqrtf(4.0));\n  VERIFY_IS_APPROX(vec3(1), sqrtf(8.0));\n  VERIFY_IS_APPROX(vec3(2), sqrtf(15.0));\n  VERIFY_IS_APPROX(vec3(3), sqrtf(16.0));\n  VERIFY_IS_APPROX(vec3(4), sqrtf(23.0));\n  VERIFY_IS_APPROX(vec3(5), sqrtf(42.0));\n\n  VERIFY_IS_APPROX(vec4(0), 0.0f);\n  VERIFY_IS_APPROX(vec4(1), 1.0f);\n  VERIFY_IS_APPROX(vec4(2), 2.0f * 2.0f);\n  VERIFY_IS_APPROX(vec4(3), 3.0f * 3.0f);\n  VERIFY_IS_APPROX(vec4(4), 4.0f * 4.0f);\n  VERIFY_IS_APPROX(vec4(5), 5.0f * 5.0f);\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_mixed_indices)\n{\n  CALL_SUBTEST(test_simple());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_morphing.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate<typename>\nstatic void test_simple_reshape()\n{\n  Tensor<float, 5> tensor1(2,3,1,7,1);\n  tensor1.setRandom();\n\n  Tensor<float, 3> tensor2(2,3,7);\n  Tensor<float, 2> tensor3(6,7);\n  Tensor<float, 2> tensor4(2,21);\n\n  Tensor<float, 3>::Dimensions dim1(2,3,7);\n  tensor2 = tensor1.reshape(dim1);\n  Tensor<float, 2>::Dimensions dim2(6,7);\n  tensor3 = tensor1.reshape(dim2);\n  Tensor<float, 2>::Dimensions dim3(2,21);\n  tensor4 = tensor1.reshape(dim1).reshape(dim3);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(tensor1(i,j,0,k,0), tensor2(i,j,k));\n        VERIFY_IS_EQUAL(tensor1(i,j,0,k,0), tensor3(i+2*j,k));\n        VERIFY_IS_EQUAL(tensor1(i,j,0,k,0), tensor4(i,j+3*k));\n      }\n    }\n  }\n}\n\ntemplate <typename>\nstatic void test_static_reshape() {\n#if defined(EIGEN_HAS_INDEX_LIST)\n  using Eigen::type2index;\n\n  Tensor<float, 5> tensor(2, 3, 1, 7, 1);\n  tensor.setRandom();\n\n  // New dimensions: [2, 3, 7]\n  Eigen::IndexList<type2index<2>, type2index<3>, type2index<7>> dim;\n  Tensor<float, 3> reshaped = tensor.reshape(static_cast<Eigen::DSizes<ptrdiff_t,3>>(dim));\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(tensor(i, j, 0, k, 0), reshaped(i, j, k));\n      }\n    }\n  }\n#endif\n}\n\ntemplate <typename>\nstatic void test_reshape_in_expr() {\n  MatrixXf m1(2,3*5*7*11);\n  MatrixXf m2(3*5*7*11,13);\n  m1.setRandom();\n  m2.setRandom();\n  MatrixXf m3 = m1 * m2;\n\n  TensorMap<Tensor<float, 5>> tensor1(m1.data(), 2,3,5,7,11);\n  TensorMap<Tensor<float, 5>> tensor2(m2.data(), 3,5,7,11,13);\n  Tensor<float, 2>::Dimensions newDims1(2,3*5*7*11);\n  Tensor<float, 2>::Dimensions newDims2(3*5*7*11,13);\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n  array<DimPair, 1> contract_along{{DimPair(1, 0)}};\n  Tensor<float, 2> tensor3(2,13);\n  tensor3 = tensor1.reshape(newDims1).contract(tensor2.reshape(newDims2), contract_along);\n\n  Map<MatrixXf> res(tensor3.data(), 2, 13);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 13; ++j) {\n      VERIFY_IS_APPROX(res(i,j), m3(i,j));\n    }\n  }\n}\n\ntemplate<typename>\nstatic void test_reshape_as_lvalue()\n{\n  Tensor<float, 3> tensor(2,3,7);\n  tensor.setRandom();\n\n  Tensor<float, 2> tensor2d(6,7);\n  Tensor<float, 3>::Dimensions dim(2,3,7);\n  tensor2d.reshape(dim) = tensor;\n\n  float scratch[2*3*1*7*1];\n  TensorMap<Tensor<float, 5>> tensor5d(scratch, 2,3,1,7,1);\n  tensor5d.reshape(dim).device(Eigen::DefaultDevice()) = tensor;\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(tensor2d(i+2*j,k), tensor(i,j,k));\n        VERIFY_IS_EQUAL(tensor5d(i,j,0,k,0), tensor(i,j,k));\n      }\n    }\n  }\n}\n\ntemplate<typename T, int DataLayout>\nstatic void test_simple_slice()\n{\n  Tensor<T, 5, DataLayout> tensor(2,3,5,7,11);\n  tensor.setRandom();\n\n  Tensor<T, 5, DataLayout> slice1(1,1,1,1,1);\n  Eigen::DSizes<ptrdiff_t, 5> indices(1,2,3,4,5);\n  Eigen::DSizes<ptrdiff_t, 5> sizes(1,1,1,1,1);\n  slice1 = tensor.slice(indices, sizes);\n  VERIFY_IS_EQUAL(slice1(0,0,0,0,0), tensor(1,2,3,4,5));\n\n  Tensor<T, 5, DataLayout> slice2(1,1,2,2,3);\n  Eigen::DSizes<ptrdiff_t, 5> indices2(1,1,3,4,5);\n  Eigen::DSizes<ptrdiff_t, 5> sizes2(1,1,2,2,3);\n  slice2 = tensor.slice(indices2, sizes2);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 2; ++j) {\n      for (int k = 0; k < 3; ++k) {\n        VERIFY_IS_EQUAL(slice2(0,0,i,j,k), tensor(1,1,3+i,4+j,5+k));\n      }\n    }\n  }\n}\n\ntemplate<typename T>\nstatic void test_const_slice()\n{\n  const T b[1] = {42};\n  TensorMap<Tensor<const T, 1> > m(b, 1);\n  DSizes<DenseIndex, 1> offsets;\n  offsets[0] = 0;\n  TensorRef<Tensor<const T, 1> > slice_ref(m.slice(offsets, m.dimensions()));\n  VERIFY_IS_EQUAL(slice_ref(0), 42);\n}\n\ntemplate<typename T, int DataLayout>\nstatic void test_slice_in_expr() {\n  typedef Matrix<T, Dynamic, Dynamic, DataLayout> Mtx;\n  Mtx m1(7,7);\n  Mtx m2(3,3);\n  m1.setRandom();\n  m2.setRandom();\n\n  Mtx m3 = m1.block(1, 2, 3, 3) * m2.block(0, 2, 3, 1);\n\n  TensorMap<Tensor<T, 2, DataLayout>> tensor1(m1.data(), 7, 7);\n  TensorMap<Tensor<T, 2, DataLayout>> tensor2(m2.data(), 3, 3);\n  Tensor<T, 2, DataLayout> tensor3(3,1);\n  typedef typename Tensor<T, 1>::DimensionPair DimPair;\n  array<DimPair, 1> contract_along{{DimPair(1, 0)}};\n\n  Eigen::DSizes<ptrdiff_t, 2> indices1(1,2);\n  Eigen::DSizes<ptrdiff_t, 2> sizes1(3,3);\n  Eigen::DSizes<ptrdiff_t, 2> indices2(0,2);\n  Eigen::DSizes<ptrdiff_t, 2> sizes2(3,1);\n  tensor3 = tensor1.slice(indices1, sizes1).contract(tensor2.slice(indices2, sizes2), contract_along);\n\n  Map<Mtx> res(tensor3.data(), 3, 1);\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 1; ++j) {\n      VERIFY_IS_APPROX(res(i,j), m3(i,j));\n    }\n  }\n\n  // Take an arbitrary slice of an arbitrarily sized tensor.\n  TensorMap<Tensor<const T, 2, DataLayout>> tensor4(m1.data(), 7, 7);\n  Tensor<T, 1, DataLayout> tensor6 = tensor4.reshape(DSizes<ptrdiff_t, 1>(7*7)).exp().slice(DSizes<ptrdiff_t, 1>(0), DSizes<ptrdiff_t, 1>(35));\n  for (int i = 0; i < 35; ++i) {\n    VERIFY_IS_APPROX(tensor6(i), expf(tensor4.data()[i]));\n  }\n}\n\ntemplate<typename T, int DataLayout>\nstatic void test_slice_as_lvalue()\n{\n  Tensor<T, 3, DataLayout> tensor1(2,2,7);\n  tensor1.setRandom();\n  Tensor<T, 3, DataLayout> tensor2(2,2,7);\n  tensor2.setRandom();\n  Tensor<T, 3, DataLayout> tensor3(4,3,5);\n  tensor3.setRandom();\n  Tensor<T, 3, DataLayout> tensor4(4,3,2);\n  tensor4.setRandom();\n  Tensor<T, 3, DataLayout> tensor5(10,13,12);\n  tensor5.setRandom();\n\n  Tensor<T, 3, DataLayout> result(4,5,7);\n  Eigen::DSizes<ptrdiff_t, 3> sizes12(2,2,7);\n  Eigen::DSizes<ptrdiff_t, 3> first_slice(0,0,0);\n  result.slice(first_slice, sizes12) = tensor1;\n  Eigen::DSizes<ptrdiff_t, 3> second_slice(2,0,0);\n  result.slice(second_slice, sizes12).device(Eigen::DefaultDevice()) = tensor2;\n\n  Eigen::DSizes<ptrdiff_t, 3> sizes3(4,3,5);\n  Eigen::DSizes<ptrdiff_t, 3> third_slice(0,2,0);\n  result.slice(third_slice, sizes3) = tensor3;\n\n  Eigen::DSizes<ptrdiff_t, 3> sizes4(4,3,2);\n  Eigen::DSizes<ptrdiff_t, 3> fourth_slice(0,2,5);\n  result.slice(fourth_slice, sizes4) = tensor4;\n\n  for (int j = 0; j < 2; ++j) {\n    for (int k = 0; k < 7; ++k) {\n      for (int i = 0; i < 2; ++i) {\n        VERIFY_IS_EQUAL(result(i,j,k), tensor1(i,j,k));\n        VERIFY_IS_EQUAL(result(i+2,j,k), tensor2(i,j,k));\n      }\n    }\n  }\n  for (int i = 0; i < 4; ++i) {\n    for (int j = 2; j < 5; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        VERIFY_IS_EQUAL(result(i,j,k), tensor3(i,j-2,k));\n      }\n      for (int k = 5; k < 7; ++k) {\n        VERIFY_IS_EQUAL(result(i,j,k), tensor4(i,j-2,k-5));\n      }\n    }\n  }\n\n  Eigen::DSizes<ptrdiff_t, 3> sizes5(4,5,7);\n  Eigen::DSizes<ptrdiff_t, 3> fifth_slice(0,0,0);\n  result.slice(fifth_slice, sizes5) = tensor5.slice(fifth_slice, sizes5);\n  for (int i = 0; i < 4; ++i) {\n    for (int j = 2; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(result(i,j,k), tensor5(i,j,k));\n      }\n    }\n  }\n}\n\ntemplate<typename T, int DataLayout>\nstatic void test_slice_raw_data()\n{\n  Tensor<T, 4, DataLayout> tensor(3,5,7,11);\n  tensor.setRandom();\n\n  Eigen::DSizes<ptrdiff_t, 4> offsets(1,2,3,4);\n  Eigen::DSizes<ptrdiff_t, 4> extents(1,1,1,1);\n  typedef TensorEvaluator<decltype(tensor.slice(offsets, extents)), DefaultDevice> SliceEvaluator;\n  auto slice1 = SliceEvaluator(tensor.slice(offsets, extents), DefaultDevice());\n  VERIFY_IS_EQUAL(slice1.dimensions().TotalSize(), 1);\n  VERIFY_IS_EQUAL(slice1.data()[0], tensor(1,2,3,4));\n\n  if (DataLayout == ColMajor) {\n    extents = Eigen::DSizes<ptrdiff_t, 4>(2,1,1,1);\n    auto slice2 = SliceEvaluator(tensor.slice(offsets, extents), DefaultDevice());\n    VERIFY_IS_EQUAL(slice2.dimensions().TotalSize(), 2);\n    VERIFY_IS_EQUAL(slice2.data()[0], tensor(1,2,3,4));\n    VERIFY_IS_EQUAL(slice2.data()[1], tensor(2,2,3,4));\n  } else {\n    extents = Eigen::DSizes<ptrdiff_t, 4>(1,1,1,2);\n    auto slice2 = SliceEvaluator(tensor.slice(offsets, extents), DefaultDevice());\n    VERIFY_IS_EQUAL(slice2.dimensions().TotalSize(), 2);\n    VERIFY_IS_EQUAL(slice2.data()[0], tensor(1,2,3,4));\n    VERIFY_IS_EQUAL(slice2.data()[1], tensor(1,2,3,5));\n  }\n\n  extents = Eigen::DSizes<ptrdiff_t, 4>(1,2,1,1);\n  auto slice3 = SliceEvaluator(tensor.slice(offsets, extents), DefaultDevice());\n  VERIFY_IS_EQUAL(slice3.dimensions().TotalSize(), 2);\n  VERIFY_IS_EQUAL(slice3.data(), static_cast<T*>(0));\n\n  if (DataLayout == ColMajor) {\n    offsets = Eigen::DSizes<ptrdiff_t, 4>(0,2,3,4);\n    extents = Eigen::DSizes<ptrdiff_t, 4>(3,2,1,1);\n    auto slice4 = SliceEvaluator(tensor.slice(offsets, extents), DefaultDevice());\n    VERIFY_IS_EQUAL(slice4.dimensions().TotalSize(), 6);\n    for (int i = 0; i < 3; ++i) {\n      for (int j = 0; j < 2; ++j) {\n        VERIFY_IS_EQUAL(slice4.data()[i+3*j], tensor(i,2+j,3,4));\n      }\n    }\n  } else {\n    offsets = Eigen::DSizes<ptrdiff_t, 4>(1,2,3,0);\n    extents = Eigen::DSizes<ptrdiff_t, 4>(1,1,2,11);\n    auto slice4 = SliceEvaluator(tensor.slice(offsets, extents), DefaultDevice());\n    VERIFY_IS_EQUAL(slice4.dimensions().TotalSize(), 22);\n    for (int l = 0; l < 11; ++l) {\n      for (int k = 0; k < 2; ++k) {\n        VERIFY_IS_EQUAL(slice4.data()[l+11*k], tensor(1,2,3+k,l));\n      }\n    }\n  }\n\n  if (DataLayout == ColMajor) {\n    offsets = Eigen::DSizes<ptrdiff_t, 4>(0,0,0,4);\n    extents = Eigen::DSizes<ptrdiff_t, 4>(3,5,7,2);\n    auto slice5 = SliceEvaluator(tensor.slice(offsets, extents), DefaultDevice());\n    VERIFY_IS_EQUAL(slice5.dimensions().TotalSize(), 210);\n    for (int i = 0; i < 3; ++i) {\n      for (int j = 0; j < 5; ++j) {\n        for (int k = 0; k < 7; ++k) {\n          for (int l = 0; l < 2; ++l) {\n            int slice_index = i + 3 * (j + 5 * (k + 7 * l));\n            VERIFY_IS_EQUAL(slice5.data()[slice_index], tensor(i,j,k,l+4));\n          }\n        }\n      }\n    }\n  } else {\n    offsets = Eigen::DSizes<ptrdiff_t, 4>(1,0,0,0);\n    extents = Eigen::DSizes<ptrdiff_t, 4>(2,5,7,11);\n    auto slice5 = SliceEvaluator(tensor.slice(offsets, extents), DefaultDevice());\n    VERIFY_IS_EQUAL(slice5.dimensions().TotalSize(), 770);\n    for (int l = 0; l < 11; ++l) {\n      for (int k = 0; k < 7; ++k) {\n        for (int j = 0; j < 5; ++j) {\n          for (int i = 0; i < 2; ++i) {\n            int slice_index = l + 11 * (k + 7 * (j + 5 * i));\n            VERIFY_IS_EQUAL(slice5.data()[slice_index], tensor(i+1,j,k,l));\n          }\n        }\n      }\n    }\n\n  }\n\n  offsets = Eigen::DSizes<ptrdiff_t, 4>(0,0,0,0);\n  extents = Eigen::DSizes<ptrdiff_t, 4>(3,5,7,11);\n  auto slice6 = SliceEvaluator(tensor.slice(offsets, extents), DefaultDevice());\n  VERIFY_IS_EQUAL(slice6.dimensions().TotalSize(), 3*5*7*11);\n  VERIFY_IS_EQUAL(slice6.data(), tensor.data());\n}\n\n\ntemplate<typename T, int DataLayout>\nstatic void test_strided_slice()\n{\n  typedef Tensor<T, 5, DataLayout> Tensor5f;\n  typedef Eigen::DSizes<Eigen::DenseIndex, 5> Index5;\n  typedef Tensor<T, 2, DataLayout> Tensor2f;\n  typedef Eigen::DSizes<Eigen::DenseIndex, 2> Index2;\n  Tensor<T, 5, DataLayout> tensor(2,3,5,7,11);\n  Tensor<T, 2, DataLayout> tensor2(7,11);\n  tensor.setRandom();\n  tensor2.setRandom();\n\n  if (true) {\n    Tensor2f slice(2,3);\n    Index2 strides(-2,-1);\n    Index2 indicesStart(5,7);\n    Index2 indicesStop(0,4);\n    slice = tensor2.stridedSlice(indicesStart, indicesStop, strides);\n    for (int j = 0; j < 2; ++j) {\n      for (int k = 0; k < 3; ++k) {\n        VERIFY_IS_EQUAL(slice(j,k), tensor2(5-2*j,7-k));\n      }\n    }\n  }\n\n  if(true) {\n    Tensor2f slice(0,1);\n    Index2 strides(1,1);\n    Index2 indicesStart(5,4);\n    Index2 indicesStop(5,5);\n    slice = tensor2.stridedSlice(indicesStart, indicesStop, strides);\n  }\n\n  if(true) { // test clamped degenerate interavls\n    Tensor2f slice(7,11);\n    Index2 strides(1,-1);\n    Index2 indicesStart(-3,20); // should become 0,10\n    Index2 indicesStop(20,-11); // should become 11, -1\n    slice = tensor2.stridedSlice(indicesStart, indicesStop, strides);\n    for (int j = 0; j < 7; ++j) {\n      for (int k = 0; k < 11; ++k) {\n        VERIFY_IS_EQUAL(slice(j,k), tensor2(j,10-k));\n      }\n    }\n  }\n\n  if(true) {\n    Tensor5f slice1(1,1,1,1,1);\n    Eigen::DSizes<Eigen::DenseIndex, 5> indicesStart(1, 2, 3, 4, 5);\n    Eigen::DSizes<Eigen::DenseIndex, 5> indicesStop(2, 3, 4, 5, 6);\n    Eigen::DSizes<Eigen::DenseIndex, 5> strides(1, 1, 1, 1, 1);\n    slice1 = tensor.stridedSlice(indicesStart, indicesStop, strides);\n    VERIFY_IS_EQUAL(slice1(0,0,0,0,0), tensor(1,2,3,4,5));\n  }\n\n  if(true) {\n    Tensor5f slice(1,1,2,2,3);\n    Index5 start(1, 1, 3, 4, 5);\n    Index5 stop(2, 2, 5, 6, 8);\n    Index5 strides(1, 1, 1, 1, 1);\n    slice = tensor.stridedSlice(start, stop, strides);\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 2; ++j) {\n        for (int k = 0; k < 3; ++k) {\n          VERIFY_IS_EQUAL(slice(0,0,i,j,k), tensor(1,1,3+i,4+j,5+k));\n        }\n      }\n    }\n  }\n\n  if(true) {\n    Tensor5f slice(1,1,2,2,3);\n    Index5 strides3(1, 1, -2, 1, -1);\n    Index5 indices3Start(1, 1, 4, 4, 7);\n    Index5 indices3Stop(2, 2, 0, 6, 4);\n    slice = tensor.stridedSlice(indices3Start, indices3Stop, strides3);\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 2; ++j) {\n        for (int k = 0; k < 3; ++k) {\n          VERIFY_IS_EQUAL(slice(0,0,i,j,k), tensor(1,1,4-2*i,4+j,7-k));\n        }\n      }\n    }\n  }\n\n  if(false) { // tests degenerate interval\n    Tensor5f slice(1,1,2,2,3);\n    Index5 strides3(1, 1, 2, 1, 1);\n    Index5 indices3Start(1, 1, 4, 4, 7);\n    Index5 indices3Stop(2, 2, 0, 6, 4);\n    slice = tensor.stridedSlice(indices3Start, indices3Stop, strides3);\n  }\n}\n\ntemplate<typename T, int DataLayout>\nstatic void test_strided_slice_write()\n{\n  typedef Tensor<T, 2, DataLayout> Tensor2f;\n  typedef Eigen::DSizes<Eigen::DenseIndex, 2> Index2;\n\n  Tensor<T, 2, DataLayout> tensor(7,11),tensor2(7,11);\n  tensor.setRandom();\n  tensor2=tensor;\n  Tensor2f slice(2,3);\n\n  slice.setRandom();\n\n  Index2 strides(1,1);\n  Index2 indicesStart(3,4);\n  Index2 indicesStop(5,7);\n  Index2 lengths(2,3);\n\n  tensor.slice(indicesStart,lengths)=slice;\n  tensor2.stridedSlice(indicesStart,indicesStop,strides)=slice;\n\n  for(int i=0;i<7;i++) for(int j=0;j<11;j++){\n    VERIFY_IS_EQUAL(tensor(i,j), tensor2(i,j));\n  }\n}\n\ntemplate<typename T, int DataLayout>\nstatic void test_composition()\n{\n  Eigen::Tensor<T, 2, DataLayout> matrix(7, 11);\n  matrix.setRandom();\n\n  const DSizes<ptrdiff_t, 3> newDims(1, 1, 11);\n  Eigen::Tensor<T, 3, DataLayout> tensor =\n      matrix.slice(DSizes<ptrdiff_t, 2>(2, 0), DSizes<ptrdiff_t, 2>(1, 11)).reshape(newDims);\n\n  VERIFY_IS_EQUAL(tensor.dimensions().TotalSize(), 11);\n  VERIFY_IS_EQUAL(tensor.dimension(0), 1);\n  VERIFY_IS_EQUAL(tensor.dimension(1), 1);\n  VERIFY_IS_EQUAL(tensor.dimension(2), 11);\n  for (int i = 0; i < 11; ++i) {\n    VERIFY_IS_EQUAL(tensor(0,0,i), matrix(2,i));\n  }\n}\n\ntemplate<typename T, int DataLayout>\nstatic void test_empty_slice()\n{\n  Tensor<T, 3, DataLayout> tensor(2,3,5);\n  tensor.setRandom();\n  Tensor<T, 3, DataLayout> copy = tensor;\n\n  // empty size in first dimension\n  Eigen::DSizes<ptrdiff_t, 3> indices1(1,2,3);\n  Eigen::DSizes<ptrdiff_t, 3> sizes1(0,1,2);\n  Tensor<T, 3, DataLayout> slice1(0,1,2);\n  slice1.setRandom();\n  tensor.slice(indices1, sizes1) = slice1;\n\n  // empty size in second dimension\n  Eigen::DSizes<ptrdiff_t, 3> indices2(1,2,3);\n  Eigen::DSizes<ptrdiff_t, 3> sizes2(1,0,2);\n  Tensor<T, 3, DataLayout> slice2(1,0,2);\n  slice2.setRandom();\n  tensor.slice(indices2, sizes2) = slice2;\n\n  // empty size in third dimension\n  Eigen::DSizes<ptrdiff_t, 3> indices3(1,2,3);\n  Eigen::DSizes<ptrdiff_t, 3> sizes3(1,1,0);\n  Tensor<T, 3, DataLayout> slice3(1,1,0);\n  slice3.setRandom();\n  tensor.slice(indices3, sizes3) = slice3;\n\n  // empty size in first and second dimension\n  Eigen::DSizes<ptrdiff_t, 3> indices4(1,2,3);\n  Eigen::DSizes<ptrdiff_t, 3> sizes4(0,0,2);\n  Tensor<T, 3, DataLayout> slice4(0,0,2);\n  slice4.setRandom();\n  tensor.slice(indices4, sizes4) = slice4;\n\n  // empty size in second and third dimension\n  Eigen::DSizes<ptrdiff_t, 3> indices5(1,2,3);\n  Eigen::DSizes<ptrdiff_t, 3> sizes5(1,0,0);\n  Tensor<T, 3, DataLayout> slice5(1,0,0);\n  slice5.setRandom();\n  tensor.slice(indices5, sizes5) = slice5;\n\n  // empty size in all dimensions\n  Eigen::DSizes<ptrdiff_t, 3> indices6(1,2,3);\n  Eigen::DSizes<ptrdiff_t, 3> sizes6(0,0,0);\n  Tensor<T, 3, DataLayout> slice6(0,0,0);\n  slice6.setRandom();\n  tensor.slice(indices6, sizes6) = slice6;\n\n  // none of these operations should change the tensor's components\n  // because all of the rvalue slices have at least one zero dimension\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n          VERIFY_IS_EQUAL(tensor(i,j,k), copy(i,j,k));\n      }\n    }\n  }\n}\n\n#define CALL_SUBTEST_PART(PART) \\\n  CALL_SUBTEST_##PART\n\n#define CALL_SUBTESTS_TYPES_LAYOUTS(PART, NAME)       \\\n  CALL_SUBTEST_PART(PART)((NAME<float, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<float, RowMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, ColMajor>())); \\\n  CALL_SUBTEST_PART(PART)((NAME<bool, RowMajor>()))\n\nEIGEN_DECLARE_TEST(cxx11_tensor_morphing)\n{\n  CALL_SUBTEST_1(test_simple_reshape<void>());\n  CALL_SUBTEST_1(test_static_reshape<void>());\n  CALL_SUBTEST_1(test_reshape_as_lvalue<void>());\n  CALL_SUBTEST_1(test_reshape_in_expr<void>());\n  CALL_SUBTEST_1(test_const_slice<float>());\n\n  CALL_SUBTESTS_TYPES_LAYOUTS(2, test_simple_slice);\n  CALL_SUBTESTS_TYPES_LAYOUTS(3, test_slice_as_lvalue);\n  CALL_SUBTESTS_TYPES_LAYOUTS(4, test_slice_raw_data);\n  CALL_SUBTESTS_TYPES_LAYOUTS(5, test_strided_slice_write);\n  CALL_SUBTESTS_TYPES_LAYOUTS(6, test_strided_slice);\n  CALL_SUBTESTS_TYPES_LAYOUTS(7, test_composition);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_morphing_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_simple_reshape(const Eigen::SyclDevice& sycl_device)\n{\n  typename Tensor<DataType, 5 ,DataLayout, IndexType>::Dimensions dim1(2,3,1,7,1);\n  typename Tensor<DataType, 3 ,DataLayout, IndexType>::Dimensions dim2(2,3,7);\n  typename Tensor<DataType, 2 ,DataLayout, IndexType>::Dimensions dim3(6,7);\n  typename Tensor<DataType, 2 ,DataLayout, IndexType>::Dimensions dim4(2,21);\n\n  Tensor<DataType, 5, DataLayout, IndexType> tensor1(dim1);\n  Tensor<DataType, 3, DataLayout, IndexType> tensor2(dim2);\n  Tensor<DataType, 2, DataLayout, IndexType> tensor3(dim3);\n  Tensor<DataType, 2, DataLayout, IndexType> tensor4(dim4);\n\n  tensor1.setRandom();\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(tensor1.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(tensor2.size()*sizeof(DataType)));\n  DataType* gpu_data3  = static_cast<DataType*>(sycl_device.allocate(tensor3.size()*sizeof(DataType)));\n  DataType* gpu_data4  = static_cast<DataType*>(sycl_device.allocate(tensor4.size()*sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 5,DataLayout, IndexType>> gpu1(gpu_data1, dim1);\n  TensorMap<Tensor<DataType, 3,DataLayout, IndexType>> gpu2(gpu_data2, dim2);\n  TensorMap<Tensor<DataType, 2,DataLayout, IndexType>> gpu3(gpu_data3, dim3);\n  TensorMap<Tensor<DataType, 2,DataLayout, IndexType>> gpu4(gpu_data4, dim4);\n\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor1.data(),(tensor1.size())*sizeof(DataType));\n\n  gpu2.device(sycl_device)=gpu1.reshape(dim2);\n  sycl_device.memcpyDeviceToHost(tensor2.data(), gpu_data2,(tensor1.size())*sizeof(DataType));\n\n  gpu3.device(sycl_device)=gpu1.reshape(dim3);\n  sycl_device.memcpyDeviceToHost(tensor3.data(), gpu_data3,(tensor3.size())*sizeof(DataType));\n\n  gpu4.device(sycl_device)=gpu1.reshape(dim2).reshape(dim4);\n  sycl_device.memcpyDeviceToHost(tensor4.data(), gpu_data4,(tensor4.size())*sizeof(DataType));\n  for (IndexType i = 0; i < 2; ++i){\n    for (IndexType j = 0; j < 3; ++j){\n      for (IndexType k = 0; k < 7; ++k){\n        VERIFY_IS_EQUAL(tensor1(i,j,0,k,0), tensor2(i,j,k));      ///ColMajor\n        if (static_cast<int>(DataLayout) == static_cast<int>(ColMajor)) {\n          VERIFY_IS_EQUAL(tensor1(i,j,0,k,0), tensor3(i+2*j,k));    ///ColMajor\n          VERIFY_IS_EQUAL(tensor1(i,j,0,k,0), tensor4(i,j+3*k));    ///ColMajor\n        }\n        else{\n          //VERIFY_IS_EQUAL(tensor1(i,j,0,k,0), tensor2(i,j,k));      /// RowMajor\n          VERIFY_IS_EQUAL(tensor1(i,j,0,k,0), tensor4(i,j*7 +k));   /// RowMajor\n          VERIFY_IS_EQUAL(tensor1(i,j,0,k,0), tensor3(i*3 +j,k));   /// RowMajor\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n  sycl_device.deallocate(gpu_data3);\n  sycl_device.deallocate(gpu_data4);\n}\n\n\ntemplate<typename DataType, int DataLayout, typename IndexType>\nstatic void test_reshape_as_lvalue(const Eigen::SyclDevice& sycl_device)\n{\n  typename Tensor<DataType, 3, DataLayout, IndexType>::Dimensions dim1(2,3,7);\n  typename Tensor<DataType, 2, DataLayout, IndexType>::Dimensions dim2(6,7);\n  typename Tensor<DataType, 5, DataLayout, IndexType>::Dimensions dim3(2,3,1,7,1);\n  Tensor<DataType, 3, DataLayout, IndexType> tensor(dim1);\n  Tensor<DataType, 2, DataLayout, IndexType> tensor2d(dim2);\n  Tensor<DataType, 5, DataLayout, IndexType> tensor5d(dim3);\n\n  tensor.setRandom();\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(tensor.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(tensor2d.size()*sizeof(DataType)));\n  DataType* gpu_data3  = static_cast<DataType*>(sycl_device.allocate(tensor5d.size()*sizeof(DataType)));\n\n  TensorMap< Tensor<DataType, 3, DataLayout, IndexType> > gpu1(gpu_data1, dim1);\n  TensorMap< Tensor<DataType, 2, DataLayout, IndexType> > gpu2(gpu_data2, dim2);\n  TensorMap< Tensor<DataType, 5, DataLayout, IndexType> > gpu3(gpu_data3, dim3);\n\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor.data(),(tensor.size())*sizeof(DataType));\n\n  gpu2.reshape(dim1).device(sycl_device)=gpu1;\n  sycl_device.memcpyDeviceToHost(tensor2d.data(), gpu_data2,(tensor2d.size())*sizeof(DataType));\n\n  gpu3.reshape(dim1).device(sycl_device)=gpu1;\n  sycl_device.memcpyDeviceToHost(tensor5d.data(), gpu_data3,(tensor5d.size())*sizeof(DataType));\n\n\n  for (IndexType i = 0; i < 2; ++i){\n    for (IndexType j = 0; j < 3; ++j){\n      for (IndexType k = 0; k < 7; ++k){\n        VERIFY_IS_EQUAL(tensor5d(i,j,0,k,0), tensor(i,j,k));\n        if (static_cast<int>(DataLayout) == static_cast<int>(ColMajor)) {\n          VERIFY_IS_EQUAL(tensor2d(i+2*j,k), tensor(i,j,k));    ///ColMajor\n        }\n        else{\n          VERIFY_IS_EQUAL(tensor2d(i*3 +j,k),tensor(i,j,k));   /// RowMajor\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n  sycl_device.deallocate(gpu_data3);\n}\n\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_simple_slice(const Eigen::SyclDevice &sycl_device)\n{\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  IndexType sizeDim5 = 11;\n  array<IndexType, 5> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4, sizeDim5}};\n  Tensor<DataType, 5,DataLayout, IndexType> tensor(tensorRange);\n  tensor.setRandom();\n  array<IndexType, 5> slice1_range ={{1, 1, 1, 1, 1}};\n  Tensor<DataType, 5,DataLayout, IndexType> slice1(slice1_range);\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(tensor.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(slice1.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 5,DataLayout, IndexType>> gpu1(gpu_data1, tensorRange);\n  TensorMap<Tensor<DataType, 5,DataLayout, IndexType>> gpu2(gpu_data2, slice1_range);\n  Eigen::DSizes<IndexType, 5> indices(1,2,3,4,5);\n  Eigen::DSizes<IndexType, 5> sizes(1,1,1,1,1);\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor.data(),(tensor.size())*sizeof(DataType));\n  gpu2.device(sycl_device)=gpu1.slice(indices, sizes);\n  sycl_device.memcpyDeviceToHost(slice1.data(), gpu_data2,(slice1.size())*sizeof(DataType));\n  VERIFY_IS_EQUAL(slice1(0,0,0,0,0), tensor(1,2,3,4,5));\n\n\n  array<IndexType, 5> slice2_range ={{1,1,2,2,3}};\n  Tensor<DataType, 5,DataLayout, IndexType> slice2(slice2_range);\n  DataType* gpu_data3  = static_cast<DataType*>(sycl_device.allocate(slice2.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 5,DataLayout, IndexType>> gpu3(gpu_data3, slice2_range);\n  Eigen::DSizes<IndexType, 5> indices2(1,1,3,4,5);\n  Eigen::DSizes<IndexType, 5> sizes2(1,1,2,2,3);\n  gpu3.device(sycl_device)=gpu1.slice(indices2, sizes2);\n  sycl_device.memcpyDeviceToHost(slice2.data(), gpu_data3,(slice2.size())*sizeof(DataType));\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 2; ++j) {\n      for (IndexType k = 0; k < 3; ++k) {\n        VERIFY_IS_EQUAL(slice2(0,0,i,j,k), tensor(1,1,3+i,4+j,5+k));\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n  sycl_device.deallocate(gpu_data3);\n}\n\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_strided_slice_as_rhs_sycl(const Eigen::SyclDevice &sycl_device)\n{\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  IndexType sizeDim5 = 11;\n  typedef Eigen::DSizes<IndexType, 5> Index5;\n  Index5 strides(1L,1L,1L,1L,1L);\n  Index5 indicesStart(1L,2L,3L,4L,5L);\n  Index5 indicesStop(2L,3L,4L,5L,6L);\n  Index5 lengths(1L,1L,1L,1L,1L);\n\n  array<IndexType, 5> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4, sizeDim5}};\n  Tensor<DataType, 5, DataLayout, IndexType> tensor(tensorRange);\n  tensor.setRandom();\n\n  array<IndexType, 5> slice1_range ={{1, 1, 1, 1, 1}};\n  Tensor<DataType, 5,DataLayout, IndexType> slice1(slice1_range);\n  Tensor<DataType, 5, DataLayout, IndexType> slice_stride1(slice1_range);\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(tensor.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(slice1.size()*sizeof(DataType)));\n  DataType* gpu_data_stride2  = static_cast<DataType*>(sycl_device.allocate(slice_stride1.size()*sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 5,DataLayout, IndexType>> gpu1(gpu_data1, tensorRange);\n  TensorMap<Tensor<DataType, 5,DataLayout, IndexType>> gpu2(gpu_data2, slice1_range);\n  TensorMap<Tensor<DataType, 5,DataLayout, IndexType>> gpu_stride2(gpu_data_stride2, slice1_range);\n\n  Eigen::DSizes<IndexType, 5> indices(1,2,3,4,5);\n  Eigen::DSizes<IndexType, 5> sizes(1,1,1,1,1);\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor.data(),(tensor.size())*sizeof(DataType));\n  gpu2.device(sycl_device)=gpu1.slice(indices, sizes);\n  sycl_device.memcpyDeviceToHost(slice1.data(), gpu_data2,(slice1.size())*sizeof(DataType));\n\n  gpu_stride2.device(sycl_device)=gpu1.stridedSlice(indicesStart,indicesStop,strides);\n  sycl_device.memcpyDeviceToHost(slice_stride1.data(), gpu_data_stride2,(slice_stride1.size())*sizeof(DataType));\n\n  VERIFY_IS_EQUAL(slice1(0,0,0,0,0), tensor(1,2,3,4,5));\n  VERIFY_IS_EQUAL(slice_stride1(0,0,0,0,0), tensor(1,2,3,4,5));\n\n  array<IndexType, 5> slice2_range ={{1,1,2,2,3}};\n  Tensor<DataType, 5,DataLayout, IndexType> slice2(slice2_range);\n  Tensor<DataType, 5, DataLayout, IndexType> strideSlice2(slice2_range);\n\n  DataType* gpu_data3  = static_cast<DataType*>(sycl_device.allocate(slice2.size()*sizeof(DataType)));\n  DataType* gpu_data_stride3  = static_cast<DataType*>(sycl_device.allocate(strideSlice2.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 5,DataLayout, IndexType>> gpu3(gpu_data3, slice2_range);\n  TensorMap<Tensor<DataType, 5,DataLayout, IndexType>> gpu_stride3(gpu_data_stride3, slice2_range);\n  Eigen::DSizes<IndexType, 5> indices2(1,1,3,4,5);\n  Eigen::DSizes<IndexType, 5> sizes2(1,1,2,2,3);\n  Index5 strides2(1L,1L,1L,1L,1L);\n  Index5 indicesStart2(1L,1L,3L,4L,5L);\n  Index5 indicesStop2(2L,2L,5L,6L,8L);\n\n  gpu3.device(sycl_device)=gpu1.slice(indices2, sizes2);\n  sycl_device.memcpyDeviceToHost(slice2.data(), gpu_data3,(slice2.size())*sizeof(DataType));\n\n  gpu_stride3.device(sycl_device)=gpu1.stridedSlice(indicesStart2,indicesStop2,strides2);\n  sycl_device.memcpyDeviceToHost(strideSlice2.data(), gpu_data_stride3,(strideSlice2.size())*sizeof(DataType));\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 2; ++j) {\n      for (IndexType k = 0; k < 3; ++k) {\n        VERIFY_IS_EQUAL(slice2(0,0,i,j,k), tensor(1,1,3+i,4+j,5+k));\n        VERIFY_IS_EQUAL(strideSlice2(0,0,i,j,k), tensor(1,1,3+i,4+j,5+k));\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n  sycl_device.deallocate(gpu_data3);\n}\n\ntemplate<typename DataType, int DataLayout, typename IndexType>\nstatic void test_strided_slice_write_sycl(const Eigen::SyclDevice& sycl_device)\n{\n  typedef Tensor<DataType, 2, DataLayout, IndexType> Tensor2f;\n  typedef Eigen::DSizes<IndexType, 2> Index2;\n  IndexType sizeDim1 = 7L;\n  IndexType sizeDim2 = 11L;\n  array<IndexType, 2> tensorRange = {{sizeDim1, sizeDim2}};\n  Tensor<DataType, 2, DataLayout, IndexType> tensor(tensorRange),tensor2(tensorRange);\n  IndexType sliceDim1 = 2;\n  IndexType sliceDim2 = 3;\n  array<IndexType, 2> sliceRange = {{sliceDim1, sliceDim2}};\n  Tensor2f slice(sliceRange);\n  Index2 strides(1L,1L);\n  Index2 indicesStart(3L,4L);\n  Index2 indicesStop(5L,7L);\n  Index2 lengths(2L,3L);\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(tensor.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(tensor2.size()*sizeof(DataType)));\n  DataType* gpu_data3  = static_cast<DataType*>(sycl_device.allocate(slice.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 2,DataLayout,IndexType>> gpu1(gpu_data1, tensorRange);\n  TensorMap<Tensor<DataType, 2,DataLayout,IndexType>> gpu2(gpu_data2, tensorRange);\n  TensorMap<Tensor<DataType, 2,DataLayout,IndexType>> gpu3(gpu_data3, sliceRange);\n\n\n  tensor.setRandom();\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor.data(),(tensor.size())*sizeof(DataType));\n  gpu2.device(sycl_device)=gpu1;\n\n  slice.setRandom();\n  sycl_device.memcpyHostToDevice(gpu_data3, slice.data(),(slice.size())*sizeof(DataType));\n\n\n  gpu1.slice(indicesStart,lengths).device(sycl_device)=gpu3;\n  gpu2.stridedSlice(indicesStart,indicesStop,strides).device(sycl_device)=gpu3;\n  sycl_device.memcpyDeviceToHost(tensor.data(), gpu_data1,(tensor.size())*sizeof(DataType));\n  sycl_device.memcpyDeviceToHost(tensor2.data(), gpu_data2,(tensor2.size())*sizeof(DataType));\n\n  for(IndexType i=0;i<sizeDim1;i++)\n    for(IndexType j=0;j<sizeDim2;j++){\n    VERIFY_IS_EQUAL(tensor(i,j), tensor2(i,j));\n  }\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n  sycl_device.deallocate(gpu_data3);\n}\n\ntemplate <typename OutIndex, typename DSizes>\nEigen::array<OutIndex, DSizes::count> To32BitDims(const DSizes& in) {\n  Eigen::array<OutIndex, DSizes::count> out;\n  for (int i = 0; i < DSizes::count; ++i) {\n    out[i] = in[i];\n  }\n  return out;\n}\n\ntemplate <class DataType, int DataLayout, typename IndexType, typename ConvertedIndexType>\nint run_eigen(const SyclDevice& sycl_device) {\n  using TensorI64 = Tensor<DataType, 5, DataLayout, IndexType>;\n  using TensorI32 = Tensor<DataType, 5, DataLayout, ConvertedIndexType>;\n  using TensorMI64 = TensorMap<TensorI64>;\n  using TensorMI32 = TensorMap<TensorI32>;\n  Eigen::array<IndexType, 5> tensor_range{{4, 1, 1, 1, 6}};\n  Eigen::array<IndexType, 5> slice_range{{4, 1, 1, 1, 3}};\n\n  TensorI64 out_tensor_gpu(tensor_range);\n  TensorI64 out_tensor_cpu(tensor_range);\n  out_tensor_cpu.setRandom();\n\n  TensorI64 sub_tensor(slice_range);\n  sub_tensor.setRandom();\n\n  DataType* out_gpu_data = static_cast<DataType*>(sycl_device.allocate(out_tensor_cpu.size() * sizeof(DataType)));\n  DataType* sub_gpu_data = static_cast<DataType*>(sycl_device.allocate(sub_tensor.size() * sizeof(DataType)));\n  TensorMI64 out_gpu(out_gpu_data, tensor_range);\n  TensorMI64 sub_gpu(sub_gpu_data, slice_range);\n\n  sycl_device.memcpyHostToDevice(out_gpu_data, out_tensor_cpu.data(), out_tensor_cpu.size() * sizeof(DataType));\n  sycl_device.memcpyHostToDevice(sub_gpu_data, sub_tensor.data(), sub_tensor.size() * sizeof(DataType));\n\n  Eigen::array<ConvertedIndexType, 5> slice_offset_32{{0, 0, 0, 0, 3}};\n  Eigen::array<ConvertedIndexType, 5> slice_range_32{{4, 1, 1, 1, 3}};\n  TensorMI32 out_cpu_32(out_tensor_cpu.data(), To32BitDims<ConvertedIndexType>(out_tensor_cpu.dimensions()));\n  TensorMI32 sub_cpu_32(sub_tensor.data(), To32BitDims<ConvertedIndexType>(sub_tensor.dimensions()));\n  TensorMI32 out_gpu_32(out_gpu.data(), To32BitDims<ConvertedIndexType>(out_gpu.dimensions()));\n  TensorMI32 sub_gpu_32(sub_gpu.data(), To32BitDims<ConvertedIndexType>(sub_gpu.dimensions()));\n\n  out_gpu_32.slice(slice_offset_32, slice_range_32).device(sycl_device) = sub_gpu_32;\n\n  out_cpu_32.slice(slice_offset_32, slice_range_32) = sub_cpu_32;\n\n  sycl_device.memcpyDeviceToHost(out_tensor_gpu.data(), out_gpu_data, out_tensor_cpu.size() * sizeof(DataType));\n  int has_err = 0;\n  for (IndexType i = 0; i < out_tensor_cpu.size(); ++i) {\n    auto exp = out_tensor_cpu(i);\n    auto val = out_tensor_gpu(i);\n    if (val != exp) {\n      std::cout << \"#\" << i << \" got \" << val << \" but expected \" << exp << std::endl;\n      has_err = 1;\n    }\n  }\n  sycl_device.deallocate(out_gpu_data);\n  sycl_device.deallocate(sub_gpu_data);\n  return has_err;\n}\n\ntemplate<typename DataType, typename dev_Selector> void sycl_morphing_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_simple_slice<DataType, RowMajor, int64_t>(sycl_device);\n  test_simple_slice<DataType, ColMajor, int64_t>(sycl_device);\n  test_simple_reshape<DataType, RowMajor, int64_t>(sycl_device);\n  test_simple_reshape<DataType, ColMajor, int64_t>(sycl_device);\n  test_reshape_as_lvalue<DataType, RowMajor, int64_t>(sycl_device);\n  test_reshape_as_lvalue<DataType, ColMajor, int64_t>(sycl_device);\n  test_strided_slice_write_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_strided_slice_write_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_strided_slice_as_rhs_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_strided_slice_as_rhs_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  run_eigen<float, RowMajor, long, int>(sycl_device); \n}\nEIGEN_DECLARE_TEST(cxx11_tensor_morphing_sycl)\n{\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_morphing_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_move.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2017 Viktor Csomor <viktor.csomor@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n#include <utility>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\nstatic void calc_indices(int i, int& x, int& y, int& z)\n{\n  x = i / 4;\n  y = (i % 4) / 2;\n  z = i % 2;\n}\n\nstatic void test_move()\n{\n  int x;\n  int y;\n  int z;\n\n  Tensor<int,3> tensor1(2, 2, 2);\n  Tensor<int,3,RowMajor> tensor2(2, 2, 2);\n\n  for (int i = 0; i < 8; i++)\n  {\n    calc_indices(i, x, y, z);\n    tensor1(x,y,z) = i;\n    tensor2(x,y,z) = 2 * i;\n  }\n\n  // Invokes the move constructor.\n  Tensor<int,3> moved_tensor1 = std::move(tensor1);\n  Tensor<int,3,RowMajor> moved_tensor2 = std::move(tensor2);\n\n  VERIFY_IS_EQUAL(tensor1.size(), 0);\n  VERIFY_IS_EQUAL(tensor2.size(), 0);\n\n  for (int i = 0; i < 8; i++)\n  {\n    calc_indices(i, x, y, z);\n    VERIFY_IS_EQUAL(moved_tensor1(x,y,z), i);\n    VERIFY_IS_EQUAL(moved_tensor2(x,y,z), 2 * i);\n  }\n\n  Tensor<int,3> moved_tensor3(2,2,2);\n  Tensor<int,3,RowMajor> moved_tensor4(2,2,2);\n\n  moved_tensor3.setZero();\n  moved_tensor4.setZero();\n\n  // Invokes the move assignment operator.\n  moved_tensor3 = std::move(moved_tensor1);\n  moved_tensor4 = std::move(moved_tensor2);\n\n  for (int i = 0; i < 8; i++)\n  {\n    calc_indices(i, x, y, z);\n    VERIFY_IS_EQUAL(moved_tensor3(x,y,z), i);\n    VERIFY_IS_EQUAL(moved_tensor4(x,y,z), 2 * i);\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_move)\n{\n  CALL_SUBTEST(test_move());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_notification.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Vijay Vasudevan <vrv@google.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_USE_THREADS\n\n#include <atomic>\n\n#include <stdlib.h>\n#include \"main.h\"\n#include <Eigen/CXX11/Tensor>\n\nstatic void test_notification_single()\n{\n  ThreadPool thread_pool(1);\n\n  std::atomic<int> counter(0);\n  Eigen::Notification n;\n  auto func = [&n, &counter](){ n.Wait(); ++counter;};\n  thread_pool.Schedule(func);\n  std::this_thread::sleep_for(std::chrono::milliseconds(1000));\n\n  // The thread should be waiting for the notification.\n  VERIFY_IS_EQUAL(counter, 0);\n\n  // Unblock the thread\n  n.Notify();\n\n  std::this_thread::sleep_for(std::chrono::milliseconds(1000));\n\n  // Verify the counter has been incremented\n  VERIFY_IS_EQUAL(counter, 1);\n}\n\n// Like test_notification_single() but enqueues multiple threads to\n// validate that all threads get notified by Notify().\nstatic void test_notification_multiple()\n{\n  ThreadPool thread_pool(1);\n\n  std::atomic<int> counter(0);\n  Eigen::Notification n;\n  auto func = [&n, &counter](){ n.Wait(); ++counter;};\n  thread_pool.Schedule(func);\n  thread_pool.Schedule(func);\n  thread_pool.Schedule(func);\n  thread_pool.Schedule(func);\n  std::this_thread::sleep_for(std::chrono::milliseconds(1000));\n  VERIFY_IS_EQUAL(counter, 0);\n  n.Notify();\n  std::this_thread::sleep_for(std::chrono::milliseconds(1000));\n  VERIFY_IS_EQUAL(counter, 4);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_notification)\n{\n  CALL_SUBTEST(test_notification_single());\n  CALL_SUBTEST(test_notification_multiple());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_of_complex.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\n\n\nstatic void test_additions()\n{\n  Tensor<std::complex<float>, 1> data1(3);\n  Tensor<std::complex<float>, 1> data2(3);\n  for (int i = 0; i < 3; ++i) {\n    data1(i) = std::complex<float>(i, -i);\n    data2(i) = std::complex<float>(i, 7 * i);\n  }\n\n  Tensor<std::complex<float>, 1> sum = data1 + data2;\n  for (int i = 0; i < 3; ++i) {\n    VERIFY_IS_EQUAL(sum(i),  std::complex<float>(2*i, 6*i));\n  }\n}\n\n\nstatic void test_abs()\n{\n  Tensor<std::complex<float>, 1> data1(3);\n  Tensor<std::complex<double>, 1> data2(3);\n  data1.setRandom();\n  data2.setRandom();\n\n  Tensor<float, 1> abs1 = data1.abs();\n  Tensor<double, 1> abs2 = data2.abs();\n  for (int i = 0; i < 3; ++i) {\n    VERIFY_IS_APPROX(abs1(i), std::abs(data1(i)));\n    VERIFY_IS_APPROX(abs2(i), std::abs(data2(i)));\n  }\n}\n\n\nstatic void test_conjugate()\n{\n  Tensor<std::complex<float>, 1> data1(3);\n  Tensor<std::complex<double>, 1> data2(3);\n  Tensor<int, 1> data3(3);\n  data1.setRandom();\n  data2.setRandom();\n  data3.setRandom();\n\n  Tensor<std::complex<float>, 1> conj1 = data1.conjugate();\n  Tensor<std::complex<double>, 1> conj2 = data2.conjugate();\n  Tensor<int, 1> conj3 = data3.conjugate();\n  for (int i = 0; i < 3; ++i) {\n    VERIFY_IS_APPROX(conj1(i), std::conj(data1(i)));\n    VERIFY_IS_APPROX(conj2(i), std::conj(data2(i)));\n    VERIFY_IS_APPROX(conj3(i), data3(i));\n  }\n}\n\nstatic void test_contractions()\n{\n  Tensor<std::complex<float>, 4> t_left(30, 50, 8, 31);\n  Tensor<std::complex<float>, 5> t_right(8, 31, 7, 20, 10);\n  Tensor<std::complex<float>, 5> t_result(30, 50, 7, 20, 10);\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  typedef Map<Matrix<std::complex<float>, Dynamic, Dynamic>> MapXcf;\n  MapXcf m_left(t_left.data(), 1500, 248);\n  MapXcf m_right(t_right.data(), 248, 1400);\n  Matrix<std::complex<float>, Dynamic, Dynamic> m_result(1500, 1400);\n\n  // This contraction should be equivalent to a regular matrix multiplication\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n  Eigen::array<DimPair, 2> dims;\n  dims[0] = DimPair(2, 0);\n  dims[1] = DimPair(3, 1);\n  t_result = t_left.contract(t_right, dims);\n  m_result = m_left * m_right;\n  for (int i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY_IS_APPROX(t_result.data()[i], m_result.data()[i]);\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_of_complex)\n{\n  CALL_SUBTEST(test_additions());\n  CALL_SUBTEST(test_abs());\n  CALL_SUBTEST(test_conjugate());\n  CALL_SUBTEST(test_contractions());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_of_const_values.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\nstatic void test_assign()\n{\n  float data1[6];\n  TensorMap<Tensor<const float, 2>> mat1(data1, 2, 3);\n  float data2[6];\n  const TensorMap<Tensor<float, 2>> mat2(data2, 2, 3);\n\n  for (int i = 0; i < 6; ++i) {\n    data1[i] = i;\n    data2[i] = -i;\n  }\n\n  Tensor<float, 2> rslt1;\n  rslt1 = mat1;\n  Tensor<float, 2> rslt2;\n  rslt2 = mat2;\n\n  Tensor<float, 2> rslt3 = mat1;\n  Tensor<float, 2> rslt4 = mat2;\n\n  Tensor<float, 2> rslt5(mat1);\n  Tensor<float, 2> rslt6(mat2);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_APPROX(rslt1(i,j), static_cast<float>(i + 2*j));\n      VERIFY_IS_APPROX(rslt2(i,j), static_cast<float>(-i - 2*j));\n      VERIFY_IS_APPROX(rslt3(i,j), static_cast<float>(i + 2*j));\n      VERIFY_IS_APPROX(rslt4(i,j), static_cast<float>(-i - 2*j));\n      VERIFY_IS_APPROX(rslt5(i,j), static_cast<float>(i + 2*j));\n      VERIFY_IS_APPROX(rslt6(i,j), static_cast<float>(-i - 2*j));\n    }\n  }\n}\n\n\nstatic void test_plus()\n{\n  float data1[6];\n  TensorMap<Tensor<const float, 2>> mat1(data1, 2, 3);\n  float data2[6];\n  TensorMap<Tensor<float, 2>> mat2(data2, 2, 3);\n\n  for (int i = 0; i < 6; ++i) {\n    data1[i] = i;\n    data2[i] = -i;\n  }\n\n  Tensor<float, 2> sum1;\n  sum1 = mat1 + mat2;\n  Tensor<float, 2> sum2;\n  sum2 = mat2 + mat1;\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_APPROX(sum1(i,j), 0.0f);\n      VERIFY_IS_APPROX(sum2(i,j), 0.0f);\n    }\n  }\n}\n\n\nstatic void test_plus_equal()\n{\n  float data1[6];\n  TensorMap<Tensor<const float, 2>> mat1(data1, 2, 3);\n  float data2[6];\n  TensorMap<Tensor<float, 2>> mat2(data2, 2, 3);\n\n  for (int i = 0; i < 6; ++i) {\n    data1[i] = i;\n    data2[i] = -i;\n  }\n  mat2 += mat1;\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_APPROX(mat2(i,j), 0.0f);\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_of_const_values)\n{\n  CALL_SUBTEST(test_assign());\n  CALL_SUBTEST(test_plus());\n  CALL_SUBTEST(test_plus_equal());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_of_float16_gpu.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\n\nusing Eigen::Tensor;\n\ntemplate<typename>\nvoid test_gpu_numext() {\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n  int num_elem = 101;\n\n  float* d_float = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  bool* d_res_half = (bool*)gpu_device.allocate(num_elem * sizeof(bool));\n  bool* d_res_float = (bool*)gpu_device.allocate(num_elem * sizeof(bool));\n\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_float(\n      d_float, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<bool, 1>, Eigen::Aligned> gpu_res_half(\n      d_res_half, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<bool, 1>, Eigen::Aligned> gpu_res_float(\n      d_res_float, num_elem);\n\n  gpu_float.device(gpu_device) = gpu_float.random() - gpu_float.constant(0.5f);\n  gpu_res_float.device(gpu_device) = gpu_float.unaryExpr(Eigen::internal::scalar_isnan_op<float>());\n  gpu_res_half.device(gpu_device) = gpu_float.cast<Eigen::half>().unaryExpr(Eigen::internal::scalar_isnan_op<Eigen::half>());\n\n  Tensor<bool, 1> half_prec(num_elem);\n  Tensor<bool, 1> full_prec(num_elem);\n  gpu_device.memcpyDeviceToHost(half_prec.data(), d_res_half, num_elem*sizeof(bool));\n  gpu_device.memcpyDeviceToHost(full_prec.data(), d_res_float, num_elem*sizeof(bool));\n  gpu_device.synchronize();\n\n  for (int i = 0; i < num_elem; ++i) {\n    std::cout << \"Checking numext \" << i << std::endl;\n    VERIFY_IS_EQUAL(full_prec(i), half_prec(i));\n  }\n\n  gpu_device.deallocate(d_float);\n  gpu_device.deallocate(d_res_half);\n  gpu_device.deallocate(d_res_float);\n}\n\n\n#ifdef EIGEN_HAS_GPU_FP16\n\ntemplate<typename>\nvoid test_gpu_conversion() {\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n  int num_elem = 101;\n\n  float* d_float = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  Eigen::half* d_half = (Eigen::half*)gpu_device.allocate(num_elem * sizeof(Eigen::half));\n  float* d_conv = (float*)gpu_device.allocate(num_elem * sizeof(float));\n\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_float(\n      d_float, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_half(\n      d_half, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_conv(\n      d_conv, num_elem);\n\n  gpu_float.device(gpu_device) = gpu_float.random();\n  gpu_half.device(gpu_device) = gpu_float.cast<Eigen::half>();\n  gpu_conv.device(gpu_device) = gpu_half.cast<float>();\n\n  Tensor<float, 1> initial(num_elem);\n  Tensor<float, 1> final(num_elem);\n  gpu_device.memcpyDeviceToHost(initial.data(), d_float, num_elem*sizeof(float));\n  gpu_device.memcpyDeviceToHost(final.data(), d_conv, num_elem*sizeof(float));\n\n  for (int i = 0; i < num_elem; ++i) {\n    VERIFY_IS_APPROX(initial(i), final(i));\n  }\n\n  gpu_device.deallocate(d_float);\n  gpu_device.deallocate(d_half);\n  gpu_device.deallocate(d_conv);\n}\n\ntemplate<typename>\nvoid test_gpu_unary() {\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n  int num_elem = 101;\n\n  float* d_float = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_res_half = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_res_float = (float*)gpu_device.allocate(num_elem * sizeof(float));\n\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_float(\n      d_float, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_res_half(\n      d_res_half, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_res_float(\n      d_res_float, num_elem);\n\n  gpu_float.device(gpu_device) = gpu_float.random() - gpu_float.constant(0.5f);\n  gpu_res_float.device(gpu_device) = gpu_float.abs();\n  gpu_res_half.device(gpu_device) = gpu_float.cast<Eigen::half>().abs().cast<float>();\n\n  Tensor<float, 1> half_prec(num_elem);\n  Tensor<float, 1> full_prec(num_elem);\n  gpu_device.memcpyDeviceToHost(half_prec.data(), d_res_half, num_elem*sizeof(float));\n  gpu_device.memcpyDeviceToHost(full_prec.data(), d_res_float, num_elem*sizeof(float));\n  gpu_device.synchronize();\n\n  for (int i = 0; i < num_elem; ++i) {\n    std::cout << \"Checking unary \" << i << std::endl;\n    VERIFY_IS_APPROX(full_prec(i), half_prec(i));\n  }\n\n  gpu_device.deallocate(d_float);\n  gpu_device.deallocate(d_res_half);\n  gpu_device.deallocate(d_res_float);\n}\n\ntemplate<typename>\nvoid test_gpu_elementwise() {\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n  int num_elem = 101;\n\n  float* d_float1 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_float2 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_res_half = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_res_float = (float*)gpu_device.allocate(num_elem * sizeof(float));\n\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_float1(\n      d_float1, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_float2(\n      d_float2, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_res_half(\n      d_res_half, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_res_float(\n      d_res_float, num_elem);\n\n  gpu_float1.device(gpu_device) = gpu_float1.random();\n  gpu_float2.device(gpu_device) = gpu_float2.random();\n  gpu_res_float.device(gpu_device) = (gpu_float1 + gpu_float2) * gpu_float1;\n  gpu_res_half.device(gpu_device) = ((gpu_float1.cast<Eigen::half>() + gpu_float2.cast<Eigen::half>()) * gpu_float1.cast<Eigen::half>()).cast<float>();\n\n  Tensor<float, 1> half_prec(num_elem);\n  Tensor<float, 1> full_prec(num_elem);\n  gpu_device.memcpyDeviceToHost(half_prec.data(), d_res_half, num_elem*sizeof(float));\n  gpu_device.memcpyDeviceToHost(full_prec.data(), d_res_float, num_elem*sizeof(float));\n  gpu_device.synchronize();\n\n  for (int i = 0; i < num_elem; ++i) {\n    std::cout << \"Checking elemwise \" << i << \": full prec = \" << full_prec(i) << \" vs half prec = \" << half_prec(i) << std::endl;\n    VERIFY_IS_APPROX(static_cast<Eigen::half>(full_prec(i)), static_cast<Eigen::half>(half_prec(i)));\n  }\n\n  gpu_device.deallocate(d_float1);\n  gpu_device.deallocate(d_float2);\n  gpu_device.deallocate(d_res_half);\n  gpu_device.deallocate(d_res_float);\n}\n\ntemplate<typename>\nvoid test_gpu_trancendental() {\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n  int num_elem = 101;\n\n  float* d_float1 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_float2 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_float3 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  Eigen::half* d_res1_half = (Eigen::half*)gpu_device.allocate(num_elem * sizeof(Eigen::half));\n  Eigen::half* d_res1_float = (Eigen::half*)gpu_device.allocate(num_elem * sizeof(Eigen::half));\n  Eigen::half* d_res2_half = (Eigen::half*)gpu_device.allocate(num_elem * sizeof(Eigen::half));\n  Eigen::half* d_res2_float = (Eigen::half*)gpu_device.allocate(num_elem * sizeof(Eigen::half));\n  Eigen::half* d_res3_half = (Eigen::half*)gpu_device.allocate(num_elem * sizeof(Eigen::half));\n  Eigen::half* d_res3_float = (Eigen::half*)gpu_device.allocate(num_elem * sizeof(Eigen::half));\n\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_float1(d_float1, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_float2(d_float2, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_float3(d_float3, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_res1_half(d_res1_half, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_res1_float(d_res1_float, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_res2_half(d_res2_half, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_res2_float(d_res2_float, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_res3_half(d_res3_half, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_res3_float(d_res3_float, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_res4_half(d_res3_half, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_res4_float(d_res3_float, num_elem);\n\n  gpu_float1.device(gpu_device) = gpu_float1.random() - gpu_float1.constant(0.5f);\n  gpu_float2.device(gpu_device) = gpu_float2.random() + gpu_float1.constant(0.5f);\n  gpu_float3.device(gpu_device) = gpu_float3.random();\n  gpu_res1_float.device(gpu_device) = gpu_float1.exp().cast<Eigen::half>();\n  gpu_res2_float.device(gpu_device) = gpu_float2.log().cast<Eigen::half>();\n  gpu_res3_float.device(gpu_device) = gpu_float3.log1p().cast<Eigen::half>();\n  gpu_res4_float.device(gpu_device) = gpu_float3.expm1().cast<Eigen::half>();\n\n  gpu_res1_half.device(gpu_device) = gpu_float1.cast<Eigen::half>();\n  gpu_res1_half.device(gpu_device) = gpu_res1_half.exp();\n\n  gpu_res2_half.device(gpu_device) = gpu_float2.cast<Eigen::half>();\n  gpu_res2_half.device(gpu_device) = gpu_res2_half.log();\n\n  gpu_res3_half.device(gpu_device) = gpu_float3.cast<Eigen::half>();\n  gpu_res3_half.device(gpu_device) = gpu_res3_half.log1p();\n\n  gpu_res3_half.device(gpu_device) = gpu_float3.cast<Eigen::half>();\n  gpu_res3_half.device(gpu_device) = gpu_res3_half.expm1();\n\n  Tensor<float, 1> input1(num_elem);\n  Tensor<Eigen::half, 1> half_prec1(num_elem);\n  Tensor<Eigen::half, 1> full_prec1(num_elem);\n  Tensor<float, 1> input2(num_elem);\n  Tensor<Eigen::half, 1> half_prec2(num_elem);\n  Tensor<Eigen::half, 1> full_prec2(num_elem);\n  Tensor<float, 1> input3(num_elem);\n  Tensor<Eigen::half, 1> half_prec3(num_elem);\n  Tensor<Eigen::half, 1> full_prec3(num_elem);\n  gpu_device.memcpyDeviceToHost(input1.data(), d_float1, num_elem*sizeof(float));\n  gpu_device.memcpyDeviceToHost(input2.data(), d_float2, num_elem*sizeof(float));\n  gpu_device.memcpyDeviceToHost(input3.data(), d_float3, num_elem*sizeof(float));\n  gpu_device.memcpyDeviceToHost(half_prec1.data(), d_res1_half, num_elem*sizeof(Eigen::half));\n  gpu_device.memcpyDeviceToHost(full_prec1.data(), d_res1_float, num_elem*sizeof(Eigen::half));\n  gpu_device.memcpyDeviceToHost(half_prec2.data(), d_res2_half, num_elem*sizeof(Eigen::half));\n  gpu_device.memcpyDeviceToHost(full_prec2.data(), d_res2_float, num_elem*sizeof(Eigen::half));\n  gpu_device.memcpyDeviceToHost(half_prec3.data(), d_res3_half, num_elem*sizeof(Eigen::half));\n  gpu_device.memcpyDeviceToHost(full_prec3.data(), d_res3_float, num_elem*sizeof(Eigen::half));\n  gpu_device.synchronize();\n\n  for (int i = 0; i < num_elem; ++i) {\n    std::cout << \"Checking elemwise exp \" << i << \" input = \" << input1(i) << \" full = \" << full_prec1(i) << \" half = \" << half_prec1(i) << std::endl;\n    VERIFY_IS_APPROX(full_prec1(i), half_prec1(i));\n  }\n  for (int i = 0; i < num_elem; ++i) {\n    std::cout << \"Checking elemwise log \" << i << \" input = \" << input2(i) << \" full = \" << full_prec2(i) << \" half = \" << half_prec2(i) << std::endl;\n    if(std::abs(input2(i)-1.f)<0.05f) // log lacks accuracy nearby 1\n      VERIFY_IS_APPROX(full_prec2(i)+Eigen::half(0.1f), half_prec2(i)+Eigen::half(0.1f));\n    else\n      VERIFY_IS_APPROX(full_prec2(i), half_prec2(i));\n  }\n  for (int i = 0; i < num_elem; ++i) {\n    std::cout << \"Checking elemwise plog1 \" << i << \" input = \" << input3(i) << \" full = \" << full_prec3(i) << \" half = \" << half_prec3(i) << std::endl;\n    VERIFY_IS_APPROX(full_prec3(i), half_prec3(i));\n  }\n  gpu_device.deallocate(d_float1);\n  gpu_device.deallocate(d_float2);\n  gpu_device.deallocate(d_float3);\n  gpu_device.deallocate(d_res1_half);\n  gpu_device.deallocate(d_res1_float);\n  gpu_device.deallocate(d_res2_half);\n  gpu_device.deallocate(d_res2_float);\n  gpu_device.deallocate(d_res3_float);\n  gpu_device.deallocate(d_res3_half);\n}\n\ntemplate<typename>\nvoid test_gpu_contractions() {\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n  int rows = 23;\n  int cols = 23;\n  int num_elem = rows*cols;\n\n  float* d_float1 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_float2 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  Eigen::half* d_res_half = (Eigen::half*)gpu_device.allocate(num_elem * sizeof(Eigen::half));\n  Eigen::half* d_res_float = (Eigen::half*)gpu_device.allocate(num_elem * sizeof(Eigen::half));\n\n  Eigen::TensorMap<Eigen::Tensor<float, 2>, Eigen::Aligned> gpu_float1(\n      d_float1, rows, cols);\n  Eigen::TensorMap<Eigen::Tensor<float, 2>, Eigen::Aligned> gpu_float2(\n      d_float2, rows, cols);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 2>, Eigen::Aligned> gpu_res_half(\n      d_res_half, rows, cols);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 2>, Eigen::Aligned> gpu_res_float(\n      d_res_float, rows, cols);\n\n  gpu_float1.device(gpu_device) = gpu_float1.random() - gpu_float1.constant(0.5f);\n  gpu_float2.device(gpu_device) = gpu_float2.random() - gpu_float2.constant(0.5f);\n\n  typedef Tensor<float, 2>::DimensionPair DimPair;\n  Eigen::array<DimPair, 1> dims(DimPair(1, 0));\n  gpu_res_float.device(gpu_device) = gpu_float1.contract(gpu_float2, dims).cast<Eigen::half>();\n  gpu_res_half.device(gpu_device) = gpu_float1.cast<Eigen::half>().contract(gpu_float2.cast<Eigen::half>(), dims);\n\n  Tensor<Eigen::half, 2> half_prec(rows, cols);\n  Tensor<Eigen::half, 2> full_prec(rows, cols);\n  gpu_device.memcpyDeviceToHost(half_prec.data(), d_res_half, num_elem*sizeof(Eigen::half));\n  gpu_device.memcpyDeviceToHost(full_prec.data(), d_res_float, num_elem*sizeof(Eigen::half));\n  gpu_device.synchronize();\n\n  for (int i = 0; i < rows; ++i) {\n    for (int j = 0; j < cols; ++j) {\n      std::cout << \"Checking contract \" << i << \" \" << j << full_prec(i, j) << \" \" << half_prec(i, j) << std::endl;\n      if (numext::abs(full_prec(i, j) - half_prec(i, j)) > Eigen::half(1e-2f)) {\n        VERIFY_IS_APPROX(full_prec(i, j), half_prec(i, j));\n      }\n    }\n  }\n\n  gpu_device.deallocate(d_float1);\n  gpu_device.deallocate(d_float2);\n  gpu_device.deallocate(d_res_half);\n  gpu_device.deallocate(d_res_float);\n}\n\ntemplate<typename>\nvoid test_gpu_reductions(int size1, int size2, int redux) {\n\n   std::cout << \"Reducing \" << size1 << \" by \" << size2\n             << \" tensor along dim \" << redux << std::endl;\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n  int num_elem = size1*size2;\n  int result_size = (redux == 1 ? size1 : size2);\n\n  float* d_float1 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_float2 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  Eigen::half* d_res_half = (Eigen::half*)gpu_device.allocate(result_size * sizeof(Eigen::half));\n  Eigen::half* d_res_float = (Eigen::half*)gpu_device.allocate(result_size * sizeof(Eigen::half));\n\n  Eigen::TensorMap<Eigen::Tensor<float, 2>, Eigen::Aligned> gpu_float1(\n      d_float1, size1, size2);\n  Eigen::TensorMap<Eigen::Tensor<float, 2>, Eigen::Aligned> gpu_float2(\n      d_float2, size1, size2);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_res_half(\n      d_res_half, result_size);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 1>, Eigen::Aligned> gpu_res_float(\n      d_res_float, result_size);\n\n  gpu_float1.device(gpu_device) = gpu_float1.random() * 2.0f;\n  gpu_float2.device(gpu_device) = gpu_float2.random() * 2.0f;\n\n  Eigen::array<int, 1> redux_dim = {redux};\n  gpu_res_float.device(gpu_device) = gpu_float1.sum(redux_dim).cast<Eigen::half>();\n  gpu_res_half.device(gpu_device) = gpu_float1.cast<Eigen::half>().sum(redux_dim);\n\n  Tensor<Eigen::half, 1> half_prec(result_size);\n  Tensor<Eigen::half, 1> full_prec(result_size);\n  gpu_device.memcpyDeviceToHost(half_prec.data(), d_res_half, result_size*sizeof(Eigen::half));\n  gpu_device.memcpyDeviceToHost(full_prec.data(), d_res_float, result_size*sizeof(Eigen::half));\n  gpu_device.synchronize();\n\n  for (int i = 0; i < result_size; ++i) {\n    std::cout << \"EXPECTED \" << full_prec(i) << \" GOT \" << half_prec(i) << std::endl;\n    VERIFY_IS_APPROX(full_prec(i), half_prec(i));\n  }\n\n  gpu_device.deallocate(d_float1);\n  gpu_device.deallocate(d_float2);\n  gpu_device.deallocate(d_res_half);\n  gpu_device.deallocate(d_res_float);\n}\n\ntemplate<typename>\nvoid test_gpu_reductions() {\n  test_gpu_reductions<void>(13, 13, 0);\n  test_gpu_reductions<void>(13, 13, 1);\n\n  test_gpu_reductions<void>(35, 36, 0);\n  test_gpu_reductions<void>(35, 36, 1);\n\n  test_gpu_reductions<void>(36, 35, 0);\n  test_gpu_reductions<void>(36, 35, 1);\n}\n\ntemplate<typename>\nvoid test_gpu_full_reductions() {\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n  int size = 13;\n  int num_elem = size*size;\n\n  float* d_float1 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_float2 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  Eigen::half* d_res_half = (Eigen::half*)gpu_device.allocate(1 * sizeof(Eigen::half));\n  Eigen::half* d_res_float = (Eigen::half*)gpu_device.allocate(1 * sizeof(Eigen::half));\n\n  Eigen::TensorMap<Eigen::Tensor<float, 2>, Eigen::Aligned> gpu_float1(\n      d_float1, size, size);\n  Eigen::TensorMap<Eigen::Tensor<float, 2>, Eigen::Aligned> gpu_float2(\n      d_float2, size, size);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 0>, Eigen::Aligned> gpu_res_half(\n      d_res_half);\n  Eigen::TensorMap<Eigen::Tensor<Eigen::half, 0>, Eigen::Aligned> gpu_res_float(\n      d_res_float);\n\n  gpu_float1.device(gpu_device) = gpu_float1.random();\n  gpu_float2.device(gpu_device) = gpu_float2.random();\n\n  gpu_res_float.device(gpu_device) = gpu_float1.sum().cast<Eigen::half>();\n  gpu_res_half.device(gpu_device) = gpu_float1.cast<Eigen::half>().sum();\n\n  Tensor<Eigen::half, 0> half_prec;\n  Tensor<Eigen::half, 0> full_prec;\n  gpu_device.memcpyDeviceToHost(half_prec.data(), d_res_half, sizeof(Eigen::half));\n  gpu_device.memcpyDeviceToHost(full_prec.data(), d_res_float, sizeof(Eigen::half));\n  gpu_device.synchronize();\n\n  VERIFY_IS_APPROX(full_prec(), half_prec());\n\n  gpu_res_float.device(gpu_device) = gpu_float1.maximum().cast<Eigen::half>();\n  gpu_res_half.device(gpu_device) = gpu_float1.cast<Eigen::half>().maximum();\n  gpu_device.memcpyDeviceToHost(half_prec.data(), d_res_half, sizeof(Eigen::half));\n  gpu_device.memcpyDeviceToHost(full_prec.data(), d_res_float, sizeof(Eigen::half));\n  gpu_device.synchronize();\n\n  VERIFY_IS_APPROX(full_prec(), half_prec());\n\n  gpu_device.deallocate(d_float1);\n  gpu_device.deallocate(d_float2);\n  gpu_device.deallocate(d_res_half);\n  gpu_device.deallocate(d_res_float);\n}\n\ntemplate<typename>\nvoid test_gpu_forced_evals() {\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n  int num_elem = 101;\n\n  float* d_float = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_res_half1 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_res_half2 = (float*)gpu_device.allocate(num_elem * sizeof(float));\n  float* d_res_float = (float*)gpu_device.allocate(num_elem * sizeof(float));\n\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_float(\n      d_float, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_res_half1(\n      d_res_half1, num_elem);\n Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Unaligned> gpu_res_half2(\n      d_res_half2, num_elem);\n  Eigen::TensorMap<Eigen::Tensor<float, 1>, Eigen::Aligned> gpu_res_float(\n      d_res_float, num_elem);\n\n  Eigen::array<int, 1> no_bcast;\n  no_bcast[0] = 1;\n\n  gpu_float.device(gpu_device) = gpu_float.random() - gpu_float.constant(0.5f);\n  gpu_res_float.device(gpu_device) = gpu_float.abs();\n  gpu_res_half1.device(gpu_device) = gpu_float.cast<Eigen::half>().abs().eval().cast<float>();\n  gpu_res_half2.device(gpu_device) = gpu_float.cast<Eigen::half>().abs().broadcast(no_bcast).eval().cast<float>();\n\n  Tensor<float, 1> half_prec1(num_elem);\n  Tensor<float, 1> half_prec2(num_elem);\n  Tensor<float, 1> full_prec(num_elem);\n  gpu_device.memcpyDeviceToHost(half_prec1.data(), d_res_half1, num_elem*sizeof(float));\n  gpu_device.memcpyDeviceToHost(half_prec2.data(), d_res_half1, num_elem*sizeof(float));\n  gpu_device.memcpyDeviceToHost(full_prec.data(), d_res_float, num_elem*sizeof(float));\n  gpu_device.synchronize();\n\n  for (int i = 0; i < num_elem; ++i) {\n    std::cout << \"Checking forced eval \" << i << full_prec(i) << \" vs \" << half_prec1(i) << \" vs \" << half_prec2(i) << std::endl;\n    VERIFY_IS_APPROX(full_prec(i), half_prec1(i));\n    VERIFY_IS_APPROX(full_prec(i), half_prec2(i));\n  }\n\n  gpu_device.deallocate(d_float);\n  gpu_device.deallocate(d_res_half1);\n  gpu_device.deallocate(d_res_half2);\n  gpu_device.deallocate(d_res_float);\n}\n#endif\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_of_float16_gpu)\n{\n  CALL_SUBTEST_1(test_gpu_numext<void>());\n\n#ifdef EIGEN_HAS_GPU_FP16\n  CALL_SUBTEST_1(test_gpu_conversion<void>());\n  CALL_SUBTEST_1(test_gpu_unary<void>());\n  CALL_SUBTEST_1(test_gpu_elementwise<void>());\n  CALL_SUBTEST_1(test_gpu_trancendental<void>());\n  CALL_SUBTEST_2(test_gpu_contractions<void>());\n  CALL_SUBTEST_3(test_gpu_reductions<void>());\n  CALL_SUBTEST_4(test_gpu_full_reductions<void>());\n  CALL_SUBTEST_5(test_gpu_forced_evals<void>());\n#else\n  std::cout << \"Half floats are not supported by this version of gpu: skipping the test\" << std::endl;\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_of_strings.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\nstatic void test_assign()\n{\n  std::string data1[6];\n  TensorMap<Tensor<std::string, 2>> mat1(data1, 2, 3);\n  std::string data2[6];\n  const TensorMap<Tensor<const std::string, 2>> mat2(data2, 2, 3);\n\n  for (int i = 0; i < 6; ++i) {\n    std::ostringstream s1;\n    s1 << \"abc\" << i*3;\n    data1[i] = s1.str();\n    std::ostringstream s2;\n    s2 << \"def\" << i*5;\n    data2[i] = s2.str();\n  }\n\n  Tensor<std::string, 2> rslt1;\n  rslt1 = mat1;\n  Tensor<std::string, 2> rslt2;\n  rslt2 = mat2;\n\n  Tensor<std::string, 2> rslt3 = mat1;\n  Tensor<std::string, 2> rslt4 = mat2;\n\n  Tensor<std::string, 2> rslt5(mat1);\n  Tensor<std::string, 2> rslt6(mat2);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_EQUAL(rslt1(i,j), data1[i+2*j]);\n      VERIFY_IS_EQUAL(rslt2(i,j), data2[i+2*j]);\n      VERIFY_IS_EQUAL(rslt3(i,j), data1[i+2*j]);\n      VERIFY_IS_EQUAL(rslt4(i,j), data2[i+2*j]);\n      VERIFY_IS_EQUAL(rslt5(i,j), data1[i+2*j]);\n      VERIFY_IS_EQUAL(rslt6(i,j), data2[i+2*j]);\n    }\n  }\n}\n\n\nstatic void test_concat()\n{\n  Tensor<std::string, 2> t1(2, 3);\n  Tensor<std::string, 2> t2(2, 3);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      std::ostringstream s1;\n      s1 << \"abc\" << i + j*2;\n      t1(i, j) = s1.str();\n      std::ostringstream s2;\n      s2 << \"def\" << i*5 + j*32;\n      t2(i, j) = s2.str();\n    }\n  }\n\n  Tensor<std::string, 2> result = t1.concatenate(t2, 1);\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_EQUAL(result.dimension(1), 6);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_EQUAL(result(i, j),   t1(i, j));\n      VERIFY_IS_EQUAL(result(i, j+3), t2(i, j));\n    }\n  }\n}\n\n\nstatic void test_slices()\n{\n  Tensor<std::string, 2> data(2, 6);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      std::ostringstream s1;\n      s1 << \"abc\" << i + j*2;\n      data(i, j) = s1.str();\n    }\n  }\n\n  const Eigen::DSizes<ptrdiff_t, 2> half_size(2, 3);\n  const Eigen::DSizes<ptrdiff_t, 2> first_half(0, 0);\n  const Eigen::DSizes<ptrdiff_t, 2> second_half(0, 3);\n\n  Tensor<std::string, 2> t1 = data.slice(first_half, half_size);\n  Tensor<std::string, 2> t2 = data.slice(second_half, half_size);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      VERIFY_IS_EQUAL(data(i, j),   t1(i, j));\n      VERIFY_IS_EQUAL(data(i, j+3), t2(i, j));\n    }\n  }\n}\n\n\nstatic void test_additions()\n{\n  Tensor<std::string, 1> data1(3);\n  Tensor<std::string, 1> data2(3);\n  for (int i = 0; i < 3; ++i) {\n    data1(i) = \"abc\";\n    std::ostringstream s1;\n    s1 << i;\n    data2(i) = s1.str();\n  }\n\n  Tensor<std::string, 1> sum = data1 + data2;\n  for (int i = 0; i < 3; ++i) {\n    std::ostringstream concat;\n    concat << \"abc\" << i;\n    std::string expected = concat.str();\n    VERIFY_IS_EQUAL(sum(i), expected);\n  }\n}\n\n\nstatic void test_initialization()\n{\n  Tensor<std::string, 2> a(2, 3);\n  a.setConstant(std::string(\"foo\"));\n  for (int i = 0; i < 2*3; ++i) {\n    VERIFY_IS_EQUAL(a(i), std::string(\"foo\"));\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_of_strings)\n{\n  // Beware: none of this is likely to ever work on a GPU.\n  CALL_SUBTEST(test_assign());\n  CALL_SUBTEST(test_concat());\n  CALL_SUBTEST(test_slices());\n  CALL_SUBTEST(test_additions());\n  CALL_SUBTEST(test_initialization());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_padding.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate<int DataLayout>\nstatic void test_simple_padding()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n\n  array<std::pair<ptrdiff_t, ptrdiff_t>, 4> paddings;\n  paddings[0] = std::make_pair(0, 0);\n  paddings[1] = std::make_pair(2, 1);\n  paddings[2] = std::make_pair(3, 4);\n  paddings[3] = std::make_pair(0, 0);\n\n  Tensor<float, 4, DataLayout> padded;\n  padded = tensor.pad(paddings);\n\n  VERIFY_IS_EQUAL(padded.dimension(0), 2+0);\n  VERIFY_IS_EQUAL(padded.dimension(1), 3+3);\n  VERIFY_IS_EQUAL(padded.dimension(2), 5+7);\n  VERIFY_IS_EQUAL(padded.dimension(3), 7+0);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 6; ++j) {\n      for (int k = 0; k < 12; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          if (j >= 2 && j < 5 && k >= 3 && k < 8) {\n            VERIFY_IS_EQUAL(padded(i,j,k,l), tensor(i,j-2,k-3,l));\n          } else {\n            VERIFY_IS_EQUAL(padded(i,j,k,l), 0.0f);\n          }\n        }\n      }\n    }\n  }\n}\n\ntemplate<int DataLayout>\nstatic void test_padded_expr()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n\n  array<std::pair<ptrdiff_t, ptrdiff_t>, 4> paddings;\n  paddings[0] = std::make_pair(0, 0);\n  paddings[1] = std::make_pair(2, 1);\n  paddings[2] = std::make_pair(3, 4);\n  paddings[3] = std::make_pair(0, 0);\n\n  Eigen::DSizes<ptrdiff_t, 2> reshape_dims;\n  reshape_dims[0] = 12;\n  reshape_dims[1] = 84;\n\n  Tensor<float, 2, DataLayout> result;\n  result = tensor.pad(paddings).reshape(reshape_dims);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 6; ++j) {\n      for (int k = 0; k < 12; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          const float result_value = DataLayout == ColMajor ?\n              result(i+2*j,k+12*l) : result(j+6*i,l+7*k);\n          if (j >= 2 && j < 5 && k >= 3 && k < 8) {\n            VERIFY_IS_EQUAL(result_value, tensor(i,j-2,k-3,l));\n          } else {\n            VERIFY_IS_EQUAL(result_value, 0.0f);\n          }\n        }\n      }\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_padding)\n{\n  CALL_SUBTEST(test_simple_padding<ColMajor>());\n  CALL_SUBTEST(test_simple_padding<RowMajor>());\n  CALL_SUBTEST(test_padded_expr<ColMajor>());\n  CALL_SUBTEST(test_padded_expr<RowMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_padding_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\n\ntemplate<typename DataType, int DataLayout, typename IndexType>\nstatic void test_simple_padding(const Eigen::SyclDevice& sycl_device)\n{\n\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  array<IndexType, 4> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n\n  Tensor<DataType, 4, DataLayout, IndexType> tensor(tensorRange);\n  tensor.setRandom();\n\n  array<std::pair<IndexType, IndexType>, 4> paddings;\n  paddings[0] = std::make_pair(0, 0);\n  paddings[1] = std::make_pair(2, 1);\n  paddings[2] = std::make_pair(3, 4);\n  paddings[3] = std::make_pair(0, 0);\n\n  IndexType padedSizeDim1 = 2;\n  IndexType padedSizeDim2 = 6;\n  IndexType padedSizeDim3 = 12;\n  IndexType padedSizeDim4 = 7;\n  array<IndexType, 4> padedtensorRange = {{padedSizeDim1, padedSizeDim2, padedSizeDim3, padedSizeDim4}};\n\n  Tensor<DataType, 4, DataLayout, IndexType> padded(padedtensorRange);\n\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(tensor.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(padded.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 4,DataLayout,IndexType>> gpu1(gpu_data1, tensorRange);\n  TensorMap<Tensor<DataType, 4,DataLayout,IndexType>> gpu2(gpu_data2, padedtensorRange);\n\n  VERIFY_IS_EQUAL(padded.dimension(0), 2+0);\n  VERIFY_IS_EQUAL(padded.dimension(1), 3+3);\n  VERIFY_IS_EQUAL(padded.dimension(2), 5+7);\n  VERIFY_IS_EQUAL(padded.dimension(3), 7+0);\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor.data(),(tensor.size())*sizeof(DataType));\n  gpu2.device(sycl_device)=gpu1.pad(paddings);\n  sycl_device.memcpyDeviceToHost(padded.data(), gpu_data2,(padded.size())*sizeof(DataType));\n  for (IndexType i = 0; i < padedSizeDim1; ++i) {\n    for (IndexType j = 0; j < padedSizeDim2; ++j) {\n      for (IndexType k = 0; k < padedSizeDim3; ++k) {\n        for (IndexType l = 0; l < padedSizeDim4; ++l) {\n          if (j >= 2 && j < 5 && k >= 3 && k < 8) {\n            VERIFY_IS_EQUAL(padded(i,j,k,l), tensor(i,j-2,k-3,l));\n          } else {\n            VERIFY_IS_EQUAL(padded(i,j,k,l), 0.0f);\n          }\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n}\n\ntemplate<typename DataType, int DataLayout, typename IndexType>\nstatic void test_padded_expr(const Eigen::SyclDevice& sycl_device)\n{\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  array<IndexType, 4> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n\n  Tensor<DataType, 4, DataLayout, IndexType> tensor(tensorRange);\n  tensor.setRandom();\n\n  array<std::pair<IndexType, IndexType>, 4> paddings;\n  paddings[0] = std::make_pair(0, 0);\n  paddings[1] = std::make_pair(2, 1);\n  paddings[2] = std::make_pair(3, 4);\n  paddings[3] = std::make_pair(0, 0);\n\n  Eigen::DSizes<IndexType, 2> reshape_dims;\n  reshape_dims[0] = 12;\n  reshape_dims[1] = 84;\n\n\n  Tensor<DataType, 2, DataLayout, IndexType>  result(reshape_dims);\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(tensor.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(result.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 4,DataLayout,IndexType>> gpu1(gpu_data1, tensorRange);\n  TensorMap<Tensor<DataType, 2,DataLayout,IndexType>> gpu2(gpu_data2, reshape_dims);\n\n\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor.data(),(tensor.size())*sizeof(DataType));\n  gpu2.device(sycl_device)=gpu1.pad(paddings).reshape(reshape_dims);\n  sycl_device.memcpyDeviceToHost(result.data(), gpu_data2,(result.size())*sizeof(DataType));\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 6; ++j) {\n      for (IndexType k = 0; k < 12; ++k) {\n        for (IndexType l = 0; l < 7; ++l) {\n          const float result_value = DataLayout == ColMajor ?\n              result(i+2*j,k+12*l) : result(j+6*i,l+7*k);\n          if (j >= 2 && j < 5 && k >= 3 && k < 8) {\n            VERIFY_IS_EQUAL(result_value, tensor(i,j-2,k-3,l));\n          } else {\n            VERIFY_IS_EQUAL(result_value, 0.0f);\n          }\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n}\n\ntemplate<typename DataType, typename dev_Selector> void sycl_padding_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_simple_padding<DataType, RowMajor, int64_t>(sycl_device);\n  test_simple_padding<DataType, ColMajor, int64_t>(sycl_device);\n  test_padded_expr<DataType, RowMajor, int64_t>(sycl_device);\n  test_padded_expr<DataType, ColMajor, int64_t>(sycl_device);\n\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_padding_sycl)\n{\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_padding_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_patch.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate<int DataLayout>\nstatic void test_simple_patch()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> patch_dims;\n\n  patch_dims[0] = 1;\n  patch_dims[1] = 1;\n  patch_dims[2] = 1;\n  patch_dims[3] = 1;\n\n  Tensor<float, 5, DataLayout> no_patch;\n  no_patch = tensor.extract_patches(patch_dims);\n\n  if (DataLayout == ColMajor) {\n    VERIFY_IS_EQUAL(no_patch.dimension(0), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(1), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(2), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(3), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(4), tensor.size());\n  } else {\n    VERIFY_IS_EQUAL(no_patch.dimension(0), tensor.size());\n    VERIFY_IS_EQUAL(no_patch.dimension(1), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(2), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(3), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(4), 1);\n  }\n\n  for (int i = 0; i < tensor.size(); ++i) {\n    VERIFY_IS_EQUAL(tensor.data()[i], no_patch.data()[i]);\n  }\n\n  patch_dims[0] = 2;\n  patch_dims[1] = 3;\n  patch_dims[2] = 5;\n  patch_dims[3] = 7;\n  Tensor<float, 5, DataLayout> single_patch;\n  single_patch = tensor.extract_patches(patch_dims);\n\n  if (DataLayout == ColMajor) {\n    VERIFY_IS_EQUAL(single_patch.dimension(0), 2);\n    VERIFY_IS_EQUAL(single_patch.dimension(1), 3);\n    VERIFY_IS_EQUAL(single_patch.dimension(2), 5);\n    VERIFY_IS_EQUAL(single_patch.dimension(3), 7);\n    VERIFY_IS_EQUAL(single_patch.dimension(4), 1);\n  } else {\n    VERIFY_IS_EQUAL(single_patch.dimension(0), 1);\n    VERIFY_IS_EQUAL(single_patch.dimension(1), 2);\n    VERIFY_IS_EQUAL(single_patch.dimension(2), 3);\n    VERIFY_IS_EQUAL(single_patch.dimension(3), 5);\n    VERIFY_IS_EQUAL(single_patch.dimension(4), 7);\n  }\n\n  for (int i = 0; i < tensor.size(); ++i) {\n    VERIFY_IS_EQUAL(tensor.data()[i], single_patch.data()[i]);\n  }\n\n  patch_dims[0] = 1;\n  patch_dims[1] = 2;\n  patch_dims[2] = 2;\n  patch_dims[3] = 1;\n  Tensor<float, 5, DataLayout> twod_patch;\n  twod_patch = tensor.extract_patches(patch_dims);\n\n  if (DataLayout == ColMajor) {\n    VERIFY_IS_EQUAL(twod_patch.dimension(0), 1);\n    VERIFY_IS_EQUAL(twod_patch.dimension(1), 2);\n    VERIFY_IS_EQUAL(twod_patch.dimension(2), 2);\n    VERIFY_IS_EQUAL(twod_patch.dimension(3), 1);\n    VERIFY_IS_EQUAL(twod_patch.dimension(4), 2*2*4*7);\n  } else {\n    VERIFY_IS_EQUAL(twod_patch.dimension(0), 2*2*4*7);\n    VERIFY_IS_EQUAL(twod_patch.dimension(1), 1);\n    VERIFY_IS_EQUAL(twod_patch.dimension(2), 2);\n    VERIFY_IS_EQUAL(twod_patch.dimension(3), 2);\n    VERIFY_IS_EQUAL(twod_patch.dimension(4), 1);\n  }\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 2; ++j) {\n      for (int k = 0; k < 4; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          int patch_loc;\n          if (DataLayout == ColMajor) {\n            patch_loc = i + 2 * (j + 2 * (k + 4 * l));\n          } else {\n            patch_loc = l + 7 * (k + 4 * (j + 2 * i));\n          }\n          for (int x = 0; x < 2; ++x) {\n            for (int y = 0; y < 2; ++y) {\n              if (DataLayout == ColMajor) {\n                VERIFY_IS_EQUAL(tensor(i,j+x,k+y,l), twod_patch(0,x,y,0,patch_loc));\n              } else {\n                VERIFY_IS_EQUAL(tensor(i,j+x,k+y,l), twod_patch(patch_loc,0,x,y,0));\n              }\n            }\n          }\n        }\n      }\n    }\n  }\n\n  patch_dims[0] = 1;\n  patch_dims[1] = 2;\n  patch_dims[2] = 3;\n  patch_dims[3] = 5;\n  Tensor<float, 5, DataLayout> threed_patch;\n  threed_patch = tensor.extract_patches(patch_dims);\n\n  if (DataLayout == ColMajor) {\n    VERIFY_IS_EQUAL(threed_patch.dimension(0), 1);\n    VERIFY_IS_EQUAL(threed_patch.dimension(1), 2);\n    VERIFY_IS_EQUAL(threed_patch.dimension(2), 3);\n    VERIFY_IS_EQUAL(threed_patch.dimension(3), 5);\n    VERIFY_IS_EQUAL(threed_patch.dimension(4), 2*2*3*3);\n  } else {\n    VERIFY_IS_EQUAL(threed_patch.dimension(0), 2*2*3*3);\n    VERIFY_IS_EQUAL(threed_patch.dimension(1), 1);\n    VERIFY_IS_EQUAL(threed_patch.dimension(2), 2);\n    VERIFY_IS_EQUAL(threed_patch.dimension(3), 3);\n    VERIFY_IS_EQUAL(threed_patch.dimension(4), 5);\n  }\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 2; ++j) {\n      for (int k = 0; k < 3; ++k) {\n        for (int l = 0; l < 3; ++l) {\n          int patch_loc;\n          if (DataLayout == ColMajor) {\n            patch_loc = i + 2 * (j + 2 * (k + 3 * l));\n          } else {\n            patch_loc = l + 3 * (k + 3 * (j + 2 * i));\n          }\n          for (int x = 0; x < 2; ++x) {\n            for (int y = 0; y < 3; ++y) {\n              for (int z = 0; z < 5; ++z) {\n                if (DataLayout == ColMajor) {\n                  VERIFY_IS_EQUAL(tensor(i,j+x,k+y,l+z), threed_patch(0,x,y,z,patch_loc));\n                } else {\n                  VERIFY_IS_EQUAL(tensor(i,j+x,k+y,l+z), threed_patch(patch_loc,0,x,y,z));\n                }\n              }\n            }\n          }\n        }\n      }\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_patch)\n{\n   CALL_SUBTEST(test_simple_patch<ColMajor>());\n   CALL_SUBTEST(test_simple_patch<RowMajor>());\n   //   CALL_SUBTEST(test_expr_shuffling());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_patch_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_simple_patch_sycl(const Eigen::SyclDevice& sycl_device){\n\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  array<IndexType, 4> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  array<IndexType, 5> patchTensorRange;\n  if (DataLayout == ColMajor) {\n   patchTensorRange = {{1, 1, 1, 1, sizeDim1*sizeDim2*sizeDim3*sizeDim4}};\n  }else{\n     patchTensorRange = {{sizeDim1*sizeDim2*sizeDim3*sizeDim4,1, 1, 1, 1}};\n  }\n\n  Tensor<DataType, 4, DataLayout,IndexType> tensor(tensorRange);\n  Tensor<DataType, 5, DataLayout,IndexType> no_patch(patchTensorRange);\n\n  tensor.setRandom();\n\n  array<ptrdiff_t, 4> patch_dims;\n  patch_dims[0] = 1;\n  patch_dims[1] = 1;\n  patch_dims[2] = 1;\n  patch_dims[3] = 1;\n\n  const size_t tensorBuffSize =tensor.size()*sizeof(DataType);\n  size_t patchTensorBuffSize =no_patch.size()*sizeof(DataType);\n  DataType* gpu_data_tensor  = static_cast<DataType*>(sycl_device.allocate(tensorBuffSize));\n  DataType* gpu_data_no_patch  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n\n  TensorMap<Tensor<DataType, 4, DataLayout,IndexType>> gpu_tensor(gpu_data_tensor, tensorRange);\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_no_patch(gpu_data_no_patch, patchTensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_tensor, tensor.data(), tensorBuffSize);\n  gpu_no_patch.device(sycl_device)=gpu_tensor.extract_patches(patch_dims);\n  sycl_device.memcpyDeviceToHost(no_patch.data(), gpu_data_no_patch, patchTensorBuffSize);\n\n  if (DataLayout == ColMajor) {\n    VERIFY_IS_EQUAL(no_patch.dimension(0), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(1), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(2), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(3), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(4), tensor.size());\n  } else {\n    VERIFY_IS_EQUAL(no_patch.dimension(0), tensor.size());\n    VERIFY_IS_EQUAL(no_patch.dimension(1), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(2), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(3), 1);\n    VERIFY_IS_EQUAL(no_patch.dimension(4), 1);\n  }\n\n  for (int i = 0; i < tensor.size(); ++i) {\n    VERIFY_IS_EQUAL(tensor.data()[i], no_patch.data()[i]);\n  }\n\n  patch_dims[0] = 2;\n  patch_dims[1] = 3;\n  patch_dims[2] = 5;\n  patch_dims[3] = 7;\n\n  if (DataLayout == ColMajor) {\n   patchTensorRange = {{sizeDim1,sizeDim2,sizeDim3,sizeDim4,1}};\n  }else{\n     patchTensorRange = {{1,sizeDim1,sizeDim2,sizeDim3,sizeDim4}};\n  }\n  Tensor<DataType, 5, DataLayout,IndexType> single_patch(patchTensorRange);\n  patchTensorBuffSize =single_patch.size()*sizeof(DataType);\n  DataType* gpu_data_single_patch  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_single_patch(gpu_data_single_patch, patchTensorRange);\n\n  gpu_single_patch.device(sycl_device)=gpu_tensor.extract_patches(patch_dims);\n  sycl_device.memcpyDeviceToHost(single_patch.data(), gpu_data_single_patch, patchTensorBuffSize);\n\n  if (DataLayout == ColMajor) {\n    VERIFY_IS_EQUAL(single_patch.dimension(0), 2);\n    VERIFY_IS_EQUAL(single_patch.dimension(1), 3);\n    VERIFY_IS_EQUAL(single_patch.dimension(2), 5);\n    VERIFY_IS_EQUAL(single_patch.dimension(3), 7);\n    VERIFY_IS_EQUAL(single_patch.dimension(4), 1);\n  } else {\n    VERIFY_IS_EQUAL(single_patch.dimension(0), 1);\n    VERIFY_IS_EQUAL(single_patch.dimension(1), 2);\n    VERIFY_IS_EQUAL(single_patch.dimension(2), 3);\n    VERIFY_IS_EQUAL(single_patch.dimension(3), 5);\n    VERIFY_IS_EQUAL(single_patch.dimension(4), 7);\n  }\n\n  for (int i = 0; i < tensor.size(); ++i) {\n    VERIFY_IS_EQUAL(tensor.data()[i], single_patch.data()[i]);\n  }\n  patch_dims[0] = 1;\n  patch_dims[1] = 2;\n  patch_dims[2] = 2;\n  patch_dims[3] = 1;\n  \n  if (DataLayout == ColMajor) {\n   patchTensorRange = {{1,2,2,1,2*2*4*7}};\n  }else{\n     patchTensorRange = {{2*2*4*7, 1, 2,2,1}};\n  }\n  Tensor<DataType, 5, DataLayout,IndexType> twod_patch(patchTensorRange);\n  patchTensorBuffSize =twod_patch.size()*sizeof(DataType);\n  DataType* gpu_data_twod_patch  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_twod_patch(gpu_data_twod_patch, patchTensorRange);\n\n  gpu_twod_patch.device(sycl_device)=gpu_tensor.extract_patches(patch_dims);\n  sycl_device.memcpyDeviceToHost(twod_patch.data(), gpu_data_twod_patch, patchTensorBuffSize);\n\n  if (DataLayout == ColMajor) {\n    VERIFY_IS_EQUAL(twod_patch.dimension(0), 1);\n    VERIFY_IS_EQUAL(twod_patch.dimension(1), 2);\n    VERIFY_IS_EQUAL(twod_patch.dimension(2), 2);\n    VERIFY_IS_EQUAL(twod_patch.dimension(3), 1);\n    VERIFY_IS_EQUAL(twod_patch.dimension(4), 2*2*4*7);\n  } else {\n    VERIFY_IS_EQUAL(twod_patch.dimension(0), 2*2*4*7);\n    VERIFY_IS_EQUAL(twod_patch.dimension(1), 1);\n    VERIFY_IS_EQUAL(twod_patch.dimension(2), 2);\n    VERIFY_IS_EQUAL(twod_patch.dimension(3), 2);\n    VERIFY_IS_EQUAL(twod_patch.dimension(4), 1);\n  }\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 2; ++j) {\n      for (int k = 0; k < 4; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          int patch_loc;\n          if (DataLayout == ColMajor) {\n            patch_loc = i + 2 * (j + 2 * (k + 4 * l));\n          } else {\n            patch_loc = l + 7 * (k + 4 * (j + 2 * i));\n          }\n          for (int x = 0; x < 2; ++x) {\n            for (int y = 0; y < 2; ++y) {\n              if (DataLayout == ColMajor) {\n                VERIFY_IS_EQUAL(tensor(i,j+x,k+y,l), twod_patch(0,x,y,0,patch_loc));\n              } else {\n                VERIFY_IS_EQUAL(tensor(i,j+x,k+y,l), twod_patch(patch_loc,0,x,y,0));\n              }\n            }\n          }\n        }\n      }\n    }\n  }\n\n  patch_dims[0] = 1;\n  patch_dims[1] = 2;\n  patch_dims[2] = 3;\n  patch_dims[3] = 5;\n\n  if (DataLayout == ColMajor) {\n   patchTensorRange = {{1,2,3,5,2*2*3*3}};\n  }else{\n     patchTensorRange = {{2*2*3*3, 1, 2,3,5}};\n  }\n  Tensor<DataType, 5, DataLayout,IndexType> threed_patch(patchTensorRange);\n  patchTensorBuffSize =threed_patch.size()*sizeof(DataType);\n  DataType* gpu_data_threed_patch  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 5, DataLayout,IndexType>> gpu_threed_patch(gpu_data_threed_patch, patchTensorRange);\n\n  gpu_threed_patch.device(sycl_device)=gpu_tensor.extract_patches(patch_dims);\n  sycl_device.memcpyDeviceToHost(threed_patch.data(), gpu_data_threed_patch, patchTensorBuffSize);\n\n  if (DataLayout == ColMajor) {\n    VERIFY_IS_EQUAL(threed_patch.dimension(0), 1);\n    VERIFY_IS_EQUAL(threed_patch.dimension(1), 2);\n    VERIFY_IS_EQUAL(threed_patch.dimension(2), 3);\n    VERIFY_IS_EQUAL(threed_patch.dimension(3), 5);\n    VERIFY_IS_EQUAL(threed_patch.dimension(4), 2*2*3*3);\n  } else {\n    VERIFY_IS_EQUAL(threed_patch.dimension(0), 2*2*3*3);\n    VERIFY_IS_EQUAL(threed_patch.dimension(1), 1);\n    VERIFY_IS_EQUAL(threed_patch.dimension(2), 2);\n    VERIFY_IS_EQUAL(threed_patch.dimension(3), 3);\n    VERIFY_IS_EQUAL(threed_patch.dimension(4), 5);\n  }\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 2; ++j) {\n      for (int k = 0; k < 3; ++k) {\n        for (int l = 0; l < 3; ++l) {\n          int patch_loc;\n          if (DataLayout == ColMajor) {\n            patch_loc = i + 2 * (j + 2 * (k + 3 * l));\n          } else {\n            patch_loc = l + 3 * (k + 3 * (j + 2 * i));\n          }\n          for (int x = 0; x < 2; ++x) {\n            for (int y = 0; y < 3; ++y) {\n              for (int z = 0; z < 5; ++z) {\n                if (DataLayout == ColMajor) {\n                  VERIFY_IS_EQUAL(tensor(i,j+x,k+y,l+z), threed_patch(0,x,y,z,patch_loc));\n                } else {\n                  VERIFY_IS_EQUAL(tensor(i,j+x,k+y,l+z), threed_patch(patch_loc,0,x,y,z));\n                }\n              }\n            }\n          }\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data_tensor);\n  sycl_device.deallocate(gpu_data_no_patch);\n  sycl_device.deallocate(gpu_data_single_patch);\n  sycl_device.deallocate(gpu_data_twod_patch);\n  sycl_device.deallocate(gpu_data_threed_patch);\n}\n\ntemplate<typename DataType, typename dev_Selector> void sycl_tensor_patch_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_simple_patch_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_simple_patch_sycl<DataType, ColMajor, int64_t>(sycl_device);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_patch_sycl)\n{\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_tensor_patch_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_random.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\ntemplate<typename Scalar>\nstatic void test_default()\n{\n  Tensor<Scalar, 1> vec(6);\n  vec.setRandom();\n\n  // Fixme: we should check that the generated numbers follow a uniform\n  // distribution instead.\n  for (int i = 1; i < 6; ++i) {\n    VERIFY_IS_NOT_EQUAL(vec(i), vec(i-1));\n  }\n}\n\ntemplate<typename Scalar>\nstatic void test_normal()\n{\n  Tensor<Scalar, 1> vec(6);\n  vec.template setRandom<Eigen::internal::NormalRandomGenerator<Scalar>>();\n\n  // Fixme: we should check that the generated numbers follow a gaussian\n  // distribution instead.\n  for (int i = 1; i < 6; ++i) {\n    VERIFY_IS_NOT_EQUAL(vec(i), vec(i-1));\n  }\n}\n\n\nstruct MyGenerator {\n  MyGenerator() { }\n  MyGenerator(const MyGenerator&) { }\n\n  // Return a random value to be used.  \"element_location\" is the\n  // location of the entry to set in the tensor, it can typically\n  // be ignored.\n  int operator()(Eigen::DenseIndex element_location, Eigen::DenseIndex /*unused*/ = 0) const {\n    return static_cast<int>(3 * element_location);\n  }\n\n  // Same as above but generates several numbers at a time.\n  internal::packet_traits<int>::type packetOp(\n      Eigen::DenseIndex packet_location, Eigen::DenseIndex /*unused*/ = 0) const {\n    const int packetSize = internal::packet_traits<int>::size;\n    EIGEN_ALIGN_MAX int values[packetSize];\n    for (int i = 0; i < packetSize; ++i) {\n      values[i] = static_cast<int>(3 * (packet_location + i));\n    }\n    return internal::pload<typename internal::packet_traits<int>::type>(values);\n  }\n};\n\n\nstatic void test_custom()\n{\n  Tensor<int, 1> vec(6);\n  vec.setRandom<MyGenerator>();\n\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_EQUAL(vec(i), 3*i);\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_random)\n{\n  CALL_SUBTEST((test_default<float>()));\n  CALL_SUBTEST((test_normal<float>()));\n  CALL_SUBTEST((test_default<double>()));\n  CALL_SUBTEST((test_normal<double>()));\n  CALL_SUBTEST((test_default<Eigen::half>()));\n  CALL_SUBTEST((test_normal<Eigen::half>()));\n  CALL_SUBTEST((test_default<Eigen::bfloat16>()));\n  CALL_SUBTEST((test_normal<Eigen::bfloat16>()));\n  CALL_SUBTEST(test_custom());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_random_gpu.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <Eigen/CXX11/Tensor>\n\n#include <Eigen/CXX11/src/Tensor/TensorGpuHipCudaDefines.h>\n\nvoid test_gpu_random_uniform()\n{\n  Tensor<float, 2> out(72,97);\n  out.setZero();\n\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_out;\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 2> > gpu_out(d_out, 72,97);\n\n  gpu_out.device(gpu_device) = gpu_out.random();\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n\n  // For now we just check this code doesn't crash.\n  // TODO: come up with a valid test of randomness\n}\n\n\nvoid test_gpu_random_normal()\n{\n  Tensor<float, 2> out(72,97);\n  out.setZero();\n\n  std::size_t out_bytes = out.size() * sizeof(float);\n\n  float* d_out;\n  gpuMalloc((void**)(&d_out), out_bytes);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 2> > gpu_out(d_out, 72,97);\n\n  Eigen::internal::NormalRandomGenerator<float> gen(true);\n  gpu_out.device(gpu_device) = gpu_out.random(gen);\n\n  assert(gpuMemcpyAsync(out.data(), d_out, out_bytes, gpuMemcpyDeviceToHost, gpu_device.stream()) == gpuSuccess);\n  assert(gpuStreamSynchronize(gpu_device.stream()) == gpuSuccess);\n}\n\nstatic void test_complex()\n{\n  Tensor<std::complex<float>, 1> vec(6);\n  vec.setRandom();\n\n  // Fixme: we should check that the generated numbers follow a uniform\n  // distribution instead.\n  for (int i = 1; i < 6; ++i) {\n    VERIFY_IS_NOT_EQUAL(vec(i), vec(i-1));\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_random_gpu)\n{\n  CALL_SUBTEST(test_gpu_random_uniform());\n  CALL_SUBTEST(test_gpu_random_normal());\n  CALL_SUBTEST(test_complex());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_random_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_sycl_random_uniform(const Eigen::SyclDevice& sycl_device)\n{\n  Tensor<DataType, 2,DataLayout, IndexType> out(72,97);\n  out.setZero();\n\n  std::size_t out_bytes = out.size() * sizeof(DataType);\n\n  IndexType sizeDim0 = 72;\n  IndexType sizeDim1 = 97;\n\n  array<IndexType, 2> tensorRange = {{sizeDim0, sizeDim1}};\n\n  DataType* d_out  = static_cast<DataType*>(sycl_device.allocate(out_bytes));\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> gpu_out(d_out, tensorRange);\n\n  gpu_out.device(sycl_device)=gpu_out.random();\n  sycl_device.memcpyDeviceToHost(out.data(), d_out,out_bytes);\n  for(IndexType i=1; i<sizeDim0; i++)\n    for(IndexType j=1; j<sizeDim1; j++)\n    {\n      VERIFY_IS_NOT_EQUAL(out(i,j), out(i-1,j));\n      VERIFY_IS_NOT_EQUAL(out(i,j), out(i,j-1));\n      VERIFY_IS_NOT_EQUAL(out(i,j), out(i-1,j-1));    }\n\n  // For now we just check thes code doesn't crash.\n  // TODO: come up with a valid test of randomness\n  sycl_device.deallocate(d_out);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_sycl_random_normal(const Eigen::SyclDevice& sycl_device)\n{\n  Tensor<DataType, 2,DataLayout,IndexType> out(72,97);\n  out.setZero();\n  std::size_t out_bytes = out.size() * sizeof(DataType);\n\n  IndexType sizeDim0 = 72;\n  IndexType sizeDim1 = 97;\n\n  array<IndexType, 2> tensorRange = {{sizeDim0, sizeDim1}};\n\n  DataType* d_out  = static_cast<DataType*>(sycl_device.allocate(out_bytes));\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> gpu_out(d_out, tensorRange);\n  Eigen::internal::NormalRandomGenerator<DataType> gen(true);\n  gpu_out.device(sycl_device)=gpu_out.random(gen);\n  sycl_device.memcpyDeviceToHost(out.data(), d_out,out_bytes);\n  for(IndexType i=1; i<sizeDim0; i++)\n    for(IndexType j=1; j<sizeDim1; j++)\n    {\n      VERIFY_IS_NOT_EQUAL(out(i,j), out(i-1,j));\n      VERIFY_IS_NOT_EQUAL(out(i,j), out(i,j-1));\n      VERIFY_IS_NOT_EQUAL(out(i,j), out(i-1,j-1));\n\n    }\n\n  // For now we just check thes code doesn't crash.\n  // TODO: come up with a valid test of randomness\n  sycl_device.deallocate(d_out);\n}\n\ntemplate<typename DataType, typename dev_Selector> void sycl_random_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_sycl_random_uniform<DataType, RowMajor, int64_t>(sycl_device);\n  test_sycl_random_uniform<DataType, ColMajor, int64_t>(sycl_device);\n  test_sycl_random_normal<DataType, RowMajor, int64_t>(sycl_device);\n  test_sycl_random_normal<DataType, ColMajor, int64_t>(sycl_device);\n\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_random_sycl)\n{\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_random_test_per_device<float>(device));\n#ifdef EIGEN_SYCL_DOUBLE_SUPPORT\n    CALL_SUBTEST(sycl_random_test_per_device<double>(device));\n#endif\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_reduction.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <limits>\n#include <numeric>\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate <int DataLayout>\nstatic void test_trivial_reductions() {\n  {\n    Tensor<float, 0, DataLayout> tensor;\n    tensor.setRandom();\n    array<ptrdiff_t, 0> reduction_axis;\n\n    Tensor<float, 0, DataLayout> result = tensor.sum(reduction_axis);\n    VERIFY_IS_EQUAL(result(), tensor());\n  }\n\n  {\n    Tensor<float, 1, DataLayout> tensor(7);\n    tensor.setRandom();\n    array<ptrdiff_t, 0> reduction_axis;\n\n    Tensor<float, 1, DataLayout> result = tensor.sum(reduction_axis);\n    VERIFY_IS_EQUAL(result.dimension(0), 7);\n    for (int i = 0; i < 7; ++i) {\n      VERIFY_IS_EQUAL(result(i), tensor(i));\n    }\n  }\n\n  {\n    Tensor<float, 2, DataLayout> tensor(2, 3);\n    tensor.setRandom();\n    array<ptrdiff_t, 0> reduction_axis;\n\n    Tensor<float, 2, DataLayout> result = tensor.sum(reduction_axis);\n    VERIFY_IS_EQUAL(result.dimension(0), 2);\n    VERIFY_IS_EQUAL(result.dimension(1), 3);\n    for (int i = 0; i < 2; ++i) {\n      for (int j = 0; j < 3; ++j) {\n        VERIFY_IS_EQUAL(result(i, j), tensor(i, j));\n      }\n    }\n  }\n}\n\ntemplate <typename Scalar,int DataLayout>\nstatic void test_simple_reductions() {\n  Tensor<Scalar, 4, DataLayout> tensor(2, 3, 5, 7);\n  tensor.setRandom();\n  // Add a little offset so that the product reductions won't be close to zero.\n  tensor += tensor.constant(Scalar(0.5f));\n  array<ptrdiff_t, 2> reduction_axis2;\n  reduction_axis2[0] = 1;\n  reduction_axis2[1] = 3;\n\n  Tensor<Scalar, 2, DataLayout> result = tensor.sum(reduction_axis2);\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_EQUAL(result.dimension(1), 5);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      Scalar sum = Scalar(0.0f);\n      for (int k = 0; k < 3; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          sum += tensor(i, k, j, l);\n        }\n      }\n      VERIFY_IS_APPROX(result(i, j), sum);\n    }\n  }\n\n  {\n    Tensor<Scalar, 0, DataLayout> sum1 = tensor.sum();\n    VERIFY_IS_EQUAL(sum1.rank(), 0);\n\n    array<ptrdiff_t, 4> reduction_axis4;\n    reduction_axis4[0] = 0;\n    reduction_axis4[1] = 1;\n    reduction_axis4[2] = 2;\n    reduction_axis4[3] = 3;\n    Tensor<Scalar, 0, DataLayout> sum2 = tensor.sum(reduction_axis4);\n    VERIFY_IS_EQUAL(sum2.rank(), 0);\n\n    VERIFY_IS_APPROX(sum1(), sum2());\n  }\n\n  reduction_axis2[0] = 0;\n  reduction_axis2[1] = 2;\n  result = tensor.prod(reduction_axis2);\n  VERIFY_IS_EQUAL(result.dimension(0), 3);\n  VERIFY_IS_EQUAL(result.dimension(1), 7);\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 7; ++j) {\n      Scalar prod = Scalar(1.0f);\n      for (int k = 0; k < 2; ++k) {\n        for (int l = 0; l < 5; ++l) {\n          prod *= tensor(k, i, l, j);\n        }\n      }\n      VERIFY_IS_APPROX(result(i, j), prod);\n    }\n  }\n\n  {\n    Tensor<Scalar, 0, DataLayout> prod1 = tensor.prod();\n    VERIFY_IS_EQUAL(prod1.rank(), 0);\n\n    array<ptrdiff_t, 4> reduction_axis4;\n    reduction_axis4[0] = 0;\n    reduction_axis4[1] = 1;\n    reduction_axis4[2] = 2;\n    reduction_axis4[3] = 3;\n    Tensor<Scalar, 0, DataLayout> prod2 = tensor.prod(reduction_axis4);\n    VERIFY_IS_EQUAL(prod2.rank(), 0);\n\n    VERIFY_IS_APPROX(prod1(), prod2());\n  }\n\n  reduction_axis2[0] = 0;\n  reduction_axis2[1] = 2;\n  result = tensor.maximum(reduction_axis2);\n  VERIFY_IS_EQUAL(result.dimension(0), 3);\n  VERIFY_IS_EQUAL(result.dimension(1), 7);\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 7; ++j) {\n      Scalar max_val = std::numeric_limits<Scalar>::lowest();\n      for (int k = 0; k < 2; ++k) {\n        for (int l = 0; l < 5; ++l) {\n          max_val = (std::max)(max_val, tensor(k, i, l, j));\n        }\n      }\n      VERIFY_IS_APPROX(result(i, j), max_val);\n    }\n  }\n\n  {\n    Tensor<Scalar, 0, DataLayout> max1 = tensor.maximum();\n    VERIFY_IS_EQUAL(max1.rank(), 0);\n\n    array<ptrdiff_t, 4> reduction_axis4;\n    reduction_axis4[0] = 0;\n    reduction_axis4[1] = 1;\n    reduction_axis4[2] = 2;\n    reduction_axis4[3] = 3;\n    Tensor<Scalar, 0, DataLayout> max2 = tensor.maximum(reduction_axis4);\n    VERIFY_IS_EQUAL(max2.rank(), 0);\n\n    VERIFY_IS_APPROX(max1(), max2());\n  }\n\n  reduction_axis2[0] = 0;\n  reduction_axis2[1] = 1;\n  result = tensor.minimum(reduction_axis2);\n  VERIFY_IS_EQUAL(result.dimension(0), 5);\n  VERIFY_IS_EQUAL(result.dimension(1), 7);\n  for (int i = 0; i < 5; ++i) {\n    for (int j = 0; j < 7; ++j) {\n      Scalar min_val = (std::numeric_limits<Scalar>::max)();\n      for (int k = 0; k < 2; ++k) {\n        for (int l = 0; l < 3; ++l) {\n          min_val = (std::min)(min_val, tensor(k, l, i, j));\n        }\n      }\n      VERIFY_IS_APPROX(result(i, j), min_val);\n    }\n  }\n\n  {\n    Tensor<Scalar, 0, DataLayout> min1 = tensor.minimum();\n    VERIFY_IS_EQUAL(min1.rank(), 0);\n\n    array<ptrdiff_t, 4> reduction_axis4;\n    reduction_axis4[0] = 0;\n    reduction_axis4[1] = 1;\n    reduction_axis4[2] = 2;\n    reduction_axis4[3] = 3;\n    Tensor<Scalar, 0, DataLayout> min2 = tensor.minimum(reduction_axis4);\n    VERIFY_IS_EQUAL(min2.rank(), 0);\n\n    VERIFY_IS_APPROX(min1(), min2());\n  }\n\n  reduction_axis2[0] = 0;\n  reduction_axis2[1] = 1;\n  result = tensor.mean(reduction_axis2);\n  VERIFY_IS_EQUAL(result.dimension(0), 5);\n  VERIFY_IS_EQUAL(result.dimension(1), 7);\n  for (int i = 0; i < 5; ++i) {\n    for (int j = 0; j < 7; ++j) {\n      Scalar sum = Scalar(0.0f);\n      int count = 0;\n      for (int k = 0; k < 2; ++k) {\n        for (int l = 0; l < 3; ++l) {\n          sum += tensor(k, l, i, j);\n          ++count;\n        }\n      }\n      VERIFY_IS_APPROX(result(i, j), sum / Scalar(count));\n    }\n  }\n\n  {\n    Tensor<Scalar, 0, DataLayout> mean1 = tensor.mean();\n    VERIFY_IS_EQUAL(mean1.rank(), 0);\n\n    array<ptrdiff_t, 4> reduction_axis4;\n    reduction_axis4[0] = 0;\n    reduction_axis4[1] = 1;\n    reduction_axis4[2] = 2;\n    reduction_axis4[3] = 3;\n    Tensor<Scalar, 0, DataLayout> mean2 = tensor.mean(reduction_axis4);\n    VERIFY_IS_EQUAL(mean2.rank(), 0);\n\n    VERIFY_IS_APPROX(mean1(), mean2());\n  }\n\n  {\n    Tensor<int, 1> ints(10);\n    std::iota(ints.data(), ints.data() + ints.dimension(0), 0);\n\n    TensorFixedSize<bool, Sizes<> > all_;\n    all_ = ints.all();\n    VERIFY(!all_());\n    all_ = (ints >= ints.constant(0)).all();\n    VERIFY(all_());\n\n    TensorFixedSize<bool, Sizes<> > any;\n    any = (ints > ints.constant(10)).any();\n    VERIFY(!any());\n    any = (ints < ints.constant(1)).any();\n    VERIFY(any());\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_reductions_in_expr() {\n  Tensor<float, 4, DataLayout> tensor(2, 3, 5, 7);\n  tensor.setRandom();\n  array<ptrdiff_t, 2> reduction_axis2;\n  reduction_axis2[0] = 1;\n  reduction_axis2[1] = 3;\n\n  Tensor<float, 2, DataLayout> result(2, 5);\n  result = result.constant(1.0f) - tensor.sum(reduction_axis2);\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_EQUAL(result.dimension(1), 5);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      float sum = 0.0f;\n      for (int k = 0; k < 3; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          sum += tensor(i, k, j, l);\n        }\n      }\n      VERIFY_IS_APPROX(result(i, j), 1.0f - sum);\n    }\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_full_reductions() {\n  Tensor<float, 2, DataLayout> tensor(2, 3);\n  tensor.setRandom();\n  array<ptrdiff_t, 2> reduction_axis;\n  reduction_axis[0] = 0;\n  reduction_axis[1] = 1;\n\n  Tensor<float, 0, DataLayout> result = tensor.sum(reduction_axis);\n  VERIFY_IS_EQUAL(result.rank(), 0);\n\n  float sum = 0.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      sum += tensor(i, j);\n    }\n  }\n  VERIFY_IS_APPROX(result(0), sum);\n\n  result = tensor.square().sum(reduction_axis).sqrt();\n  VERIFY_IS_EQUAL(result.rank(), 0);\n\n  sum = 0.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      sum += tensor(i, j) * tensor(i, j);\n    }\n  }\n  VERIFY_IS_APPROX(result(), sqrtf(sum));\n}\n\nstruct UserReducer {\n  static const bool PacketAccess = false;\n  UserReducer(float offset) : offset_(offset) {}\n  void reduce(const float val, float* accum) { *accum += val * val; }\n  float initialize() const { return 0; }\n  float finalize(const float accum) const { return 1.0f / (accum + offset_); }\n\n private:\n  const float offset_;\n};\n\ntemplate <int DataLayout>\nstatic void test_user_defined_reductions() {\n  Tensor<float, 2, DataLayout> tensor(5, 7);\n  tensor.setRandom();\n  array<ptrdiff_t, 1> reduction_axis;\n  reduction_axis[0] = 1;\n\n  UserReducer reducer(10.0f);\n  Tensor<float, 1, DataLayout> result = tensor.reduce(reduction_axis, reducer);\n  VERIFY_IS_EQUAL(result.dimension(0), 5);\n  for (int i = 0; i < 5; ++i) {\n    float expected = 10.0f;\n    for (int j = 0; j < 7; ++j) {\n      expected += tensor(i, j) * tensor(i, j);\n    }\n    expected = 1.0f / expected;\n    VERIFY_IS_APPROX(result(i), expected);\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_tensor_maps() {\n  int inputs[2 * 3 * 5 * 7];\n  TensorMap<Tensor<int, 4, DataLayout> > tensor_map(inputs, 2, 3, 5, 7);\n  TensorMap<Tensor<const int, 4, DataLayout> > tensor_map_const(inputs, 2, 3, 5,\n                                                                7);\n  const TensorMap<Tensor<const int, 4, DataLayout> > tensor_map_const_const(\n      inputs, 2, 3, 5, 7);\n\n  tensor_map.setRandom();\n  array<ptrdiff_t, 2> reduction_axis;\n  reduction_axis[0] = 1;\n  reduction_axis[1] = 3;\n\n  Tensor<int, 2, DataLayout> result = tensor_map.sum(reduction_axis);\n  Tensor<int, 2, DataLayout> result2 = tensor_map_const.sum(reduction_axis);\n  Tensor<int, 2, DataLayout> result3 =\n      tensor_map_const_const.sum(reduction_axis);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      int sum = 0;\n      for (int k = 0; k < 3; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          sum += tensor_map(i, k, j, l);\n        }\n      }\n      VERIFY_IS_EQUAL(result(i, j), sum);\n      VERIFY_IS_EQUAL(result2(i, j), sum);\n      VERIFY_IS_EQUAL(result3(i, j), sum);\n    }\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_static_dims() {\n  Tensor<float, 4, DataLayout> in(72, 53, 97, 113);\n  Tensor<float, 2, DataLayout> out(72, 97);\n  in.setRandom();\n\n#if !EIGEN_HAS_CONSTEXPR\n  array<int, 2> reduction_axis;\n  reduction_axis[0] = 1;\n  reduction_axis[1] = 3;\n#else\n  Eigen::IndexList<Eigen::type2index<1>, Eigen::type2index<3> > reduction_axis;\n#endif\n\n  out = in.maximum(reduction_axis);\n\n  for (int i = 0; i < 72; ++i) {\n    for (int j = 0; j < 97; ++j) {\n      float expected = -1e10f;\n      for (int k = 0; k < 53; ++k) {\n        for (int l = 0; l < 113; ++l) {\n          expected = (std::max)(expected, in(i, k, j, l));\n        }\n      }\n      VERIFY_IS_EQUAL(out(i, j), expected);\n    }\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_innermost_last_dims() {\n  Tensor<float, 4, DataLayout> in(72, 53, 97, 113);\n  Tensor<float, 2, DataLayout> out(97, 113);\n  in.setRandom();\n\n// Reduce on the innermost dimensions.\n#if !EIGEN_HAS_CONSTEXPR\n  array<int, 2> reduction_axis;\n  reduction_axis[0] = 0;\n  reduction_axis[1] = 1;\n#else\n  // This triggers the use of packets for ColMajor.\n  Eigen::IndexList<Eigen::type2index<0>, Eigen::type2index<1> > reduction_axis;\n#endif\n\n  out = in.maximum(reduction_axis);\n\n  for (int i = 0; i < 97; ++i) {\n    for (int j = 0; j < 113; ++j) {\n      float expected = -1e10f;\n      for (int k = 0; k < 53; ++k) {\n        for (int l = 0; l < 72; ++l) {\n          expected = (std::max)(expected, in(l, k, i, j));\n        }\n      }\n      VERIFY_IS_EQUAL(out(i, j), expected);\n    }\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_innermost_first_dims() {\n  Tensor<float, 4, DataLayout> in(72, 53, 97, 113);\n  Tensor<float, 2, DataLayout> out(72, 53);\n  in.setRandom();\n\n// Reduce on the innermost dimensions.\n#if !EIGEN_HAS_CONSTEXPR\n  array<int, 2> reduction_axis;\n  reduction_axis[0] = 2;\n  reduction_axis[1] = 3;\n#else\n  // This triggers the use of packets for RowMajor.\n  Eigen::IndexList<Eigen::type2index<2>, Eigen::type2index<3>> reduction_axis;\n#endif\n\n  out = in.maximum(reduction_axis);\n\n  for (int i = 0; i < 72; ++i) {\n    for (int j = 0; j < 53; ++j) {\n      float expected = -1e10f;\n      for (int k = 0; k < 97; ++k) {\n        for (int l = 0; l < 113; ++l) {\n          expected = (std::max)(expected, in(i, j, k, l));\n        }\n      }\n      VERIFY_IS_EQUAL(out(i, j), expected);\n    }\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_reduce_middle_dims() {\n  Tensor<float, 4, DataLayout> in(72, 53, 97, 113);\n  Tensor<float, 2, DataLayout> out(72, 53);\n  in.setRandom();\n\n// Reduce on the innermost dimensions.\n#if !EIGEN_HAS_CONSTEXPR\n  array<int, 2> reduction_axis;\n  reduction_axis[0] = 1;\n  reduction_axis[1] = 2;\n#else\n  // This triggers the use of packets for RowMajor.\n  Eigen::IndexList<Eigen::type2index<1>, Eigen::type2index<2>> reduction_axis;\n#endif\n\n  out = in.maximum(reduction_axis);\n\n  for (int i = 0; i < 72; ++i) {\n    for (int j = 0; j < 113; ++j) {\n      float expected = -1e10f;\n      for (int k = 0; k < 53; ++k) {\n        for (int l = 0; l < 97; ++l) {\n          expected = (std::max)(expected, in(i, k, l, j));\n        }\n      }\n      VERIFY_IS_EQUAL(out(i, j), expected);\n    }\n  }\n}\n\nstatic void test_sum_accuracy() {\n  Tensor<float, 3> tensor(101, 101, 101);\n  for (float prescribed_mean : {1.0f, 10.0f, 100.0f, 1000.0f, 10000.0f}) {\n    tensor.setRandom();\n    tensor += tensor.constant(prescribed_mean);\n\n    Tensor<float, 0> sum = tensor.sum();\n    double expected_sum = 0.0;\n    for (int i = 0; i < 101; ++i) {\n      for (int j = 0; j < 101; ++j) {\n        for (int k = 0; k < 101; ++k) {\n          expected_sum += static_cast<double>(tensor(i, j, k));\n        }\n      }\n    }\n    VERIFY_IS_APPROX(sum(), static_cast<float>(expected_sum));\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_reduction) {\n  CALL_SUBTEST(test_trivial_reductions<ColMajor>());\n  CALL_SUBTEST(test_trivial_reductions<RowMajor>());\n  CALL_SUBTEST(( test_simple_reductions<float,ColMajor>() ));\n  CALL_SUBTEST(( test_simple_reductions<float,RowMajor>() ));\n  CALL_SUBTEST(( test_simple_reductions<Eigen::half,ColMajor>() ));\n  CALL_SUBTEST(( test_simple_reductions<Eigen::bfloat16,ColMajor>() ));\n  CALL_SUBTEST(test_reductions_in_expr<ColMajor>());\n  CALL_SUBTEST(test_reductions_in_expr<RowMajor>());\n  CALL_SUBTEST(test_full_reductions<ColMajor>());\n  CALL_SUBTEST(test_full_reductions<RowMajor>());\n  CALL_SUBTEST(test_user_defined_reductions<ColMajor>());\n  CALL_SUBTEST(test_user_defined_reductions<RowMajor>());\n  CALL_SUBTEST(test_tensor_maps<ColMajor>());\n  CALL_SUBTEST(test_tensor_maps<RowMajor>());\n  CALL_SUBTEST(test_static_dims<ColMajor>());\n  CALL_SUBTEST(test_static_dims<RowMajor>());\n  CALL_SUBTEST(test_innermost_last_dims<ColMajor>());\n  CALL_SUBTEST(test_innermost_last_dims<RowMajor>());\n  CALL_SUBTEST(test_innermost_first_dims<ColMajor>());\n  CALL_SUBTEST(test_innermost_first_dims<RowMajor>());\n  CALL_SUBTEST(test_reduce_middle_dims<ColMajor>());\n  CALL_SUBTEST(test_reduce_middle_dims<RowMajor>());\n  CALL_SUBTEST(test_sum_accuracy());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_reduction_gpu.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\n\ntemplate<typename Type, int DataLayout>\nstatic void test_full_reductions() {\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  const int num_rows = internal::random<int>(1024, 5*1024);\n  const int num_cols = internal::random<int>(1024, 5*1024);\n\n  Tensor<Type, 2, DataLayout> in(num_rows, num_cols);\n  in.setRandom();\n\n  Tensor<Type, 0, DataLayout> full_redux;\n  full_redux = in.sum();\n\n  std::size_t in_bytes = in.size() * sizeof(Type);\n  std::size_t out_bytes = full_redux.size() * sizeof(Type);\n  Type* gpu_in_ptr = static_cast<Type*>(gpu_device.allocate(in_bytes));\n  Type* gpu_out_ptr = static_cast<Type*>(gpu_device.allocate(out_bytes));\n  gpu_device.memcpyHostToDevice(gpu_in_ptr, in.data(), in_bytes);\n\n  TensorMap<Tensor<Type, 2, DataLayout> > in_gpu(gpu_in_ptr, num_rows, num_cols);\n  TensorMap<Tensor<Type, 0, DataLayout> > out_gpu(gpu_out_ptr);\n\n  out_gpu.device(gpu_device) = in_gpu.sum();\n\n  Tensor<Type, 0, DataLayout> full_redux_gpu;\n  gpu_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_ptr, out_bytes);\n  gpu_device.synchronize();\n\n  // Check that the CPU and GPU reductions return the same result.\n  VERIFY_IS_APPROX(full_redux(), full_redux_gpu());\n\n  gpu_device.deallocate(gpu_in_ptr);\n  gpu_device.deallocate(gpu_out_ptr);\n}\n\ntemplate<typename Type, int DataLayout>\nstatic void test_first_dim_reductions() {\n  int dim_x = 33;\n  int dim_y = 1;\n  int dim_z = 128;\n\n  Tensor<Type, 3, DataLayout> in(dim_x, dim_y, dim_z);\n  in.setRandom();\n\n  Eigen::array<int, 1> red_axis;\n  red_axis[0] = 0;\n  Tensor<Type, 2, DataLayout> redux = in.sum(red_axis);\n\n  // Create device\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice dev(&stream);\n  \n  // Create data(T)\n  Type* in_data = (Type*)dev.allocate(dim_x*dim_y*dim_z*sizeof(Type));\n  Type* out_data = (Type*)dev.allocate(dim_z*dim_y*sizeof(Type));\n  Eigen::TensorMap<Eigen::Tensor<Type, 3, DataLayout> > gpu_in(in_data, dim_x, dim_y, dim_z);\n  Eigen::TensorMap<Eigen::Tensor<Type, 2, DataLayout> > gpu_out(out_data, dim_y, dim_z);\n  \n  // Perform operation\n  dev.memcpyHostToDevice(in_data, in.data(), in.size()*sizeof(Type));\n  gpu_out.device(dev) = gpu_in.sum(red_axis);\n  gpu_out.device(dev) += gpu_in.sum(red_axis);\n  Tensor<Type, 2, DataLayout> redux_gpu(dim_y, dim_z);\n  dev.memcpyDeviceToHost(redux_gpu.data(), out_data, gpu_out.size()*sizeof(Type));\n  dev.synchronize();\n\n  // Check that the CPU and GPU reductions return the same result.\n  for (int i = 0; i < gpu_out.size(); ++i) {\n    VERIFY_IS_APPROX(2*redux(i), redux_gpu(i));\n  }\n\n  dev.deallocate(in_data);\n  dev.deallocate(out_data);\n}\n\ntemplate<typename Type, int DataLayout>\nstatic void test_last_dim_reductions() {\n  int dim_x = 128;\n  int dim_y = 1;\n  int dim_z = 33;\n\n  Tensor<Type, 3, DataLayout> in(dim_x, dim_y, dim_z);\n  in.setRandom();\n\n  Eigen::array<int, 1> red_axis;\n  red_axis[0] = 2;\n  Tensor<Type, 2, DataLayout> redux = in.sum(red_axis);\n\n  // Create device\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice dev(&stream);\n  \n  // Create data\n  Type* in_data = (Type*)dev.allocate(dim_x*dim_y*dim_z*sizeof(Type));\n  Type* out_data = (Type*)dev.allocate(dim_x*dim_y*sizeof(Type));\n  Eigen::TensorMap<Eigen::Tensor<Type, 3, DataLayout> > gpu_in(in_data, dim_x, dim_y, dim_z);\n  Eigen::TensorMap<Eigen::Tensor<Type, 2, DataLayout> > gpu_out(out_data, dim_x, dim_y);\n  \n  // Perform operation\n  dev.memcpyHostToDevice(in_data, in.data(), in.size()*sizeof(Type));\n  gpu_out.device(dev) = gpu_in.sum(red_axis);\n  gpu_out.device(dev) += gpu_in.sum(red_axis);\n  Tensor<Type, 2, DataLayout> redux_gpu(dim_x, dim_y);\n  dev.memcpyDeviceToHost(redux_gpu.data(), out_data, gpu_out.size()*sizeof(Type));\n  dev.synchronize();\n\n  // Check that the CPU and GPU reductions return the same result.\n  for (int i = 0; i < gpu_out.size(); ++i) {\n    VERIFY_IS_APPROX(2*redux(i), redux_gpu(i));\n  }\n\n  dev.deallocate(in_data);\n  dev.deallocate(out_data);\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_reduction_gpu) {\n  CALL_SUBTEST_1((test_full_reductions<float, ColMajor>()));\n  CALL_SUBTEST_1((test_full_reductions<double, ColMajor>()));\n  CALL_SUBTEST_2((test_full_reductions<float, RowMajor>()));\n  CALL_SUBTEST_2((test_full_reductions<double, RowMajor>()));\n  \n  CALL_SUBTEST_3((test_first_dim_reductions<float, ColMajor>()));\n  CALL_SUBTEST_3((test_first_dim_reductions<double, ColMajor>()));\n  CALL_SUBTEST_4((test_first_dim_reductions<float, RowMajor>()));\n// Outer reductions of doubles aren't supported just yet.  \t\t\t\t\t      \n//  CALL_SUBTEST_4((test_first_dim_reductions<double, RowMajor>()))\n\n  CALL_SUBTEST_5((test_last_dim_reductions<float, ColMajor>()));\n// Outer reductions of doubles aren't supported just yet.  \t\t\t\t\t      \n//  CALL_SUBTEST_5((test_last_dim_reductions<double, ColMajor>()));\n  CALL_SUBTEST_6((test_last_dim_reductions<float, RowMajor>()));\n  CALL_SUBTEST_6((test_last_dim_reductions<double, RowMajor>()));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_reduction_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n#define EIGEN_HAS_CONSTEXPR 1\n\n#include \"main.h\"\n\n#include <unsupported/Eigen/CXX11/Tensor>\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_full_reductions_sum_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  const IndexType num_rows = 753;\n  const IndexType num_cols = 537;\n  array<IndexType, 2> tensorRange = {{num_rows, num_cols}};\n\n  array<IndexType, 2> outRange = {{1, 1}};\n\n  Tensor<DataType, 2, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> full_redux(outRange);\n  Tensor<DataType, 2, DataLayout, IndexType> full_redux_gpu(outRange);\n\n  in.setRandom();\n  auto dim = DSizes<IndexType, 2>(1, 1);\n  full_redux = in.sum().reshape(dim);\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = (DataType*)sycl_device.allocate(\n      sizeof(DataType) * (full_redux_gpu.dimensions().TotalSize()));\n\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> in_gpu(gpu_in_data,\n                                                               tensorRange);\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> out_gpu(gpu_out_data,\n                                                                outRange);\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in.data(), (in.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.sum().reshape(dim);\n  sycl_device.memcpyDeviceToHost(\n      full_redux_gpu.data(), gpu_out_data,\n      (full_redux_gpu.dimensions().TotalSize()) * sizeof(DataType));\n  // Check that the CPU and GPU reductions return the same result.\n  std::cout << \"SYCL FULL :\" << full_redux_gpu(0, 0)\n            << \", CPU FULL: \" << full_redux(0, 0) << \"\\n\";\n  VERIFY_IS_APPROX(full_redux_gpu(0, 0), full_redux(0, 0));\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_full_reductions_sum_with_offset_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  using data_tensor = Tensor<DataType, 2, DataLayout, IndexType>;\n  using scalar_tensor = Tensor<DataType, 0, DataLayout, IndexType>;\n  const IndexType num_rows = 64;\n  const IndexType num_cols = 64;\n  array<IndexType, 2> tensor_range = {{num_rows, num_cols}};\n  const IndexType n_elems = internal::array_prod(tensor_range);\n\n  data_tensor in(tensor_range);\n  scalar_tensor full_redux;\n  scalar_tensor full_redux_gpu;\n\n  in.setRandom();\n  array<IndexType, 2> tensor_offset_range(tensor_range);\n  tensor_offset_range[0] -= 1;\n\n  const IndexType offset = 64;\n  TensorMap<data_tensor> in_offset(in.data() + offset, tensor_offset_range);\n  full_redux = in_offset.sum();\n\n  DataType* gpu_in_data =\n      static_cast<DataType*>(sycl_device.allocate(n_elems * sizeof(DataType)));\n  DataType* gpu_out_data =\n      static_cast<DataType*>(sycl_device.allocate(sizeof(DataType)));\n\n  TensorMap<data_tensor> in_gpu(gpu_in_data + offset, tensor_offset_range);\n  TensorMap<scalar_tensor> out_gpu(gpu_out_data);\n  sycl_device.memcpyHostToDevice(gpu_in_data, in.data(),\n                                 n_elems * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.sum();\n  sycl_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_data,\n                                 sizeof(DataType));\n\n  // Check that the CPU and GPU reductions return the same result.\n  VERIFY_IS_APPROX(full_redux_gpu(), full_redux());\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_full_reductions_max_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  const IndexType num_rows = 4096;\n  const IndexType num_cols = 4096;\n  array<IndexType, 2> tensorRange = {{num_rows, num_cols}};\n\n  Tensor<DataType, 2, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 0, DataLayout, IndexType> full_redux;\n  Tensor<DataType, 0, DataLayout, IndexType> full_redux_gpu;\n\n  in.setRandom();\n\n  full_redux = in.maximum();\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = (DataType*)sycl_device.allocate(sizeof(DataType));\n\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> in_gpu(gpu_in_data,\n                                                               tensorRange);\n  TensorMap<Tensor<DataType, 0, DataLayout, IndexType>> out_gpu(gpu_out_data);\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in.data(), (in.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.maximum();\n  sycl_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_data,\n                                 sizeof(DataType));\n  VERIFY_IS_APPROX(full_redux_gpu(), full_redux());\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_full_reductions_max_with_offset_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  using data_tensor = Tensor<DataType, 2, DataLayout, IndexType>;\n  using scalar_tensor = Tensor<DataType, 0, DataLayout, IndexType>;\n  const IndexType num_rows = 64;\n  const IndexType num_cols = 64;\n  array<IndexType, 2> tensor_range = {{num_rows, num_cols}};\n  const IndexType n_elems = internal::array_prod(tensor_range);\n\n  data_tensor in(tensor_range);\n  scalar_tensor full_redux;\n  scalar_tensor full_redux_gpu;\n\n  in.setRandom();\n  array<IndexType, 2> tensor_offset_range(tensor_range);\n  tensor_offset_range[0] -= 1;\n  // Set the initial value to be the max.\n  // As we don't include this in the reduction the result should not be 2.\n  in(0) = static_cast<DataType>(2);\n\n  const IndexType offset = 64;\n  TensorMap<data_tensor> in_offset(in.data() + offset, tensor_offset_range);\n  full_redux = in_offset.maximum();\n  VERIFY_IS_NOT_EQUAL(full_redux(), in(0));\n\n  DataType* gpu_in_data =\n      static_cast<DataType*>(sycl_device.allocate(n_elems * sizeof(DataType)));\n  DataType* gpu_out_data =\n      static_cast<DataType*>(sycl_device.allocate(sizeof(DataType)));\n\n  TensorMap<data_tensor> in_gpu(gpu_in_data + offset, tensor_offset_range);\n  TensorMap<scalar_tensor> out_gpu(gpu_out_data);\n  sycl_device.memcpyHostToDevice(gpu_in_data, in.data(),\n                                 n_elems * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.maximum();\n  sycl_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_data,\n                                 sizeof(DataType));\n\n  // Check that the CPU and GPU reductions return the same result.\n  VERIFY_IS_APPROX(full_redux_gpu(), full_redux());\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_full_reductions_mean_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  const IndexType num_rows = 4096;\n  const IndexType num_cols = 4096;\n  array<IndexType, 2> tensorRange = {{num_rows, num_cols}};\n  array<IndexType, 1> argRange = {{num_cols}};\n  Eigen::array<IndexType, 1> red_axis;\n  red_axis[0] = 0;\n  //  red_axis[1]=1;\n  Tensor<DataType, 2, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> in_arg1(tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> in_arg2(tensorRange);\n  Tensor<bool, 1, DataLayout, IndexType> out_arg_cpu(argRange);\n  Tensor<bool, 1, DataLayout, IndexType> out_arg_gpu(argRange);\n  Tensor<bool, 1, DataLayout, IndexType> out_arg_gpu_helper(argRange);\n  Tensor<DataType, 0, DataLayout, IndexType> full_redux;\n  Tensor<DataType, 0, DataLayout, IndexType> full_redux_gpu;\n\n  in.setRandom();\n  in_arg1.setRandom();\n  in_arg2.setRandom();\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_in_arg1_data = static_cast<DataType*>(sycl_device.allocate(\n      in_arg1.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_in_arg2_data = static_cast<DataType*>(sycl_device.allocate(\n      in_arg2.dimensions().TotalSize() * sizeof(DataType)));\n  bool* gpu_out_arg__gpu_helper_data = static_cast<bool*>(sycl_device.allocate(\n      out_arg_gpu.dimensions().TotalSize() * sizeof(DataType)));\n  bool* gpu_out_arg_data = static_cast<bool*>(sycl_device.allocate(\n      out_arg_gpu.dimensions().TotalSize() * sizeof(DataType)));\n\n  DataType* gpu_out_data = (DataType*)sycl_device.allocate(sizeof(DataType));\n\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> in_gpu(gpu_in_data,\n                                                               tensorRange);\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> in_Arg1_gpu(\n      gpu_in_arg1_data, tensorRange);\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> in_Arg2_gpu(\n      gpu_in_arg2_data, tensorRange);\n  TensorMap<Tensor<bool, 1, DataLayout, IndexType>> out_Argout_gpu(\n      gpu_out_arg_data, argRange);\n  TensorMap<Tensor<bool, 1, DataLayout, IndexType>> out_Argout_gpu_helper(\n      gpu_out_arg__gpu_helper_data, argRange);\n  TensorMap<Tensor<DataType, 0, DataLayout, IndexType>> out_gpu(gpu_out_data);\n\n  // CPU VERSION\n  out_arg_cpu =\n      (in_arg1.argmax(1) == in_arg2.argmax(1))\n          .select(out_arg_cpu.constant(true), out_arg_cpu.constant(false));\n  full_redux = (out_arg_cpu.template cast<float>())\n                   .reduce(red_axis, Eigen::internal::MeanReducer<DataType>());\n\n  // GPU VERSION\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in.data(), (in.dimensions().TotalSize()) * sizeof(DataType));\n  sycl_device.memcpyHostToDevice(\n      gpu_in_arg1_data, in_arg1.data(),\n      (in_arg1.dimensions().TotalSize()) * sizeof(DataType));\n  sycl_device.memcpyHostToDevice(\n      gpu_in_arg2_data, in_arg2.data(),\n      (in_arg2.dimensions().TotalSize()) * sizeof(DataType));\n  out_Argout_gpu_helper.device(sycl_device) =\n      (in_Arg1_gpu.argmax(1) == in_Arg2_gpu.argmax(1));\n  out_Argout_gpu.device(sycl_device) =\n      (out_Argout_gpu_helper)\n          .select(out_Argout_gpu.constant(true),\n                  out_Argout_gpu.constant(false));\n  out_gpu.device(sycl_device) =\n      (out_Argout_gpu.template cast<float>())\n          .reduce(red_axis, Eigen::internal::MeanReducer<DataType>());\n  sycl_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_data,\n                                 sizeof(DataType));\n  // Check that the CPU and GPU reductions return the same result.\n  std::cout << \"SYCL : \" << full_redux_gpu() << \" , CPU : \" << full_redux()\n            << '\\n';\n  VERIFY_IS_EQUAL(full_redux_gpu(), full_redux());\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_in_arg1_data);\n  sycl_device.deallocate(gpu_in_arg2_data);\n  sycl_device.deallocate(gpu_out_arg__gpu_helper_data);\n  sycl_device.deallocate(gpu_out_arg_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_full_reductions_mean_with_offset_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  using data_tensor = Tensor<DataType, 2, DataLayout, IndexType>;\n  using scalar_tensor = Tensor<DataType, 0, DataLayout, IndexType>;\n  const IndexType num_rows = 64;\n  const IndexType num_cols = 64;\n  array<IndexType, 2> tensor_range = {{num_rows, num_cols}};\n  const IndexType n_elems = internal::array_prod(tensor_range);\n\n  data_tensor in(tensor_range);\n  scalar_tensor full_redux;\n  scalar_tensor full_redux_gpu;\n\n  in.setRandom();\n  array<IndexType, 2> tensor_offset_range(tensor_range);\n  tensor_offset_range[0] -= 1;\n\n  const IndexType offset = 64;\n  TensorMap<data_tensor> in_offset(in.data() + offset, tensor_offset_range);\n  full_redux = in_offset.mean();\n  VERIFY_IS_NOT_EQUAL(full_redux(), in(0));\n\n  DataType* gpu_in_data =\n      static_cast<DataType*>(sycl_device.allocate(n_elems * sizeof(DataType)));\n  DataType* gpu_out_data =\n      static_cast<DataType*>(sycl_device.allocate(sizeof(DataType)));\n\n  TensorMap<data_tensor> in_gpu(gpu_in_data + offset, tensor_offset_range);\n  TensorMap<scalar_tensor> out_gpu(gpu_out_data);\n  sycl_device.memcpyHostToDevice(gpu_in_data, in.data(),\n                                 n_elems * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.mean();\n  sycl_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_data,\n                                 sizeof(DataType));\n\n  // Check that the CPU and GPU reductions return the same result.\n  VERIFY_IS_APPROX(full_redux_gpu(), full_redux());\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_full_reductions_mean_with_odd_offset_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  // This is a particular case which illustrates a possible problem when the\n  // number of local threads in a workgroup is even, but is not a power of two.\n  using data_tensor = Tensor<DataType, 1, DataLayout, IndexType>;\n  using scalar_tensor = Tensor<DataType, 0, DataLayout, IndexType>;\n  // 2177 = (17 * 128) + 1 gives rise to 18 local threads.\n  // 8708 = 4 * 2177 = 4 * (17 * 128) + 4 uses 18 vectorised local threads.\n  const IndexType n_elems = 8707;\n  array<IndexType, 1> tensor_range = {{n_elems}};\n\n  data_tensor in(tensor_range);\n  DataType full_redux;\n  DataType full_redux_gpu;\n  TensorMap<scalar_tensor> red_cpu(&full_redux);\n  TensorMap<scalar_tensor> red_gpu(&full_redux_gpu);\n\n  const DataType const_val = static_cast<DataType>(0.6391);\n  in = in.constant(const_val);\n\n  Eigen::IndexList<Eigen::type2index<0>> red_axis;\n  red_cpu = in.reduce(red_axis, Eigen::internal::MeanReducer<DataType>());\n  VERIFY_IS_APPROX(const_val, red_cpu());\n\n  DataType* gpu_in_data =\n      static_cast<DataType*>(sycl_device.allocate(n_elems * sizeof(DataType)));\n  DataType* gpu_out_data =\n      static_cast<DataType*>(sycl_device.allocate(sizeof(DataType)));\n\n  TensorMap<data_tensor> in_gpu(gpu_in_data, tensor_range);\n  TensorMap<scalar_tensor> out_gpu(gpu_out_data);\n  sycl_device.memcpyHostToDevice(gpu_in_data, in.data(),\n                                 n_elems * sizeof(DataType));\n  out_gpu.device(sycl_device) =\n      in_gpu.reduce(red_axis, Eigen::internal::MeanReducer<DataType>());\n  sycl_device.memcpyDeviceToHost(red_gpu.data(), gpu_out_data,\n                                 sizeof(DataType));\n\n  // Check that the CPU and GPU reductions return the same result.\n  VERIFY_IS_APPROX(full_redux_gpu, full_redux);\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_full_reductions_min_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  const IndexType num_rows = 876;\n  const IndexType num_cols = 953;\n  array<IndexType, 2> tensorRange = {{num_rows, num_cols}};\n\n  Tensor<DataType, 2, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 0, DataLayout, IndexType> full_redux;\n  Tensor<DataType, 0, DataLayout, IndexType> full_redux_gpu;\n\n  in.setRandom();\n\n  full_redux = in.minimum();\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = (DataType*)sycl_device.allocate(sizeof(DataType));\n\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> in_gpu(gpu_in_data,\n                                                               tensorRange);\n  TensorMap<Tensor<DataType, 0, DataLayout, IndexType>> out_gpu(gpu_out_data);\n\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in.data(), (in.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.minimum();\n  sycl_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_data,\n                                 sizeof(DataType));\n  // Check that the CPU and GPU reductions return the same result.\n  VERIFY_IS_APPROX(full_redux_gpu(), full_redux());\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_full_reductions_min_with_offset_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  using data_tensor = Tensor<DataType, 2, DataLayout, IndexType>;\n  using scalar_tensor = Tensor<DataType, 0, DataLayout, IndexType>;\n  const IndexType num_rows = 64;\n  const IndexType num_cols = 64;\n  array<IndexType, 2> tensor_range = {{num_rows, num_cols}};\n  const IndexType n_elems = internal::array_prod(tensor_range);\n\n  data_tensor in(tensor_range);\n  scalar_tensor full_redux;\n  scalar_tensor full_redux_gpu;\n\n  in.setRandom();\n  array<IndexType, 2> tensor_offset_range(tensor_range);\n  tensor_offset_range[0] -= 1;\n  // Set the initial value to be the min.\n  // As we don't include this in the reduction the result should not be -2.\n  in(0) = static_cast<DataType>(-2);\n\n  const IndexType offset = 64;\n  TensorMap<data_tensor> in_offset(in.data() + offset, tensor_offset_range);\n  full_redux = in_offset.minimum();\n  VERIFY_IS_NOT_EQUAL(full_redux(), in(0));\n\n  DataType* gpu_in_data =\n      static_cast<DataType*>(sycl_device.allocate(n_elems * sizeof(DataType)));\n  DataType* gpu_out_data =\n      static_cast<DataType*>(sycl_device.allocate(sizeof(DataType)));\n\n  TensorMap<data_tensor> in_gpu(gpu_in_data + offset, tensor_offset_range);\n  TensorMap<scalar_tensor> out_gpu(gpu_out_data);\n  sycl_device.memcpyHostToDevice(gpu_in_data, in.data(),\n                                 n_elems * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.minimum();\n  sycl_device.memcpyDeviceToHost(full_redux_gpu.data(), gpu_out_data,\n                                 sizeof(DataType));\n\n  // Check that the CPU and GPU reductions return the same result.\n  VERIFY_IS_APPROX(full_redux_gpu(), full_redux());\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_first_dim_reductions_max_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  IndexType dim_x = 145;\n  IndexType dim_y = 1;\n  IndexType dim_z = 67;\n\n  array<IndexType, 3> tensorRange = {{dim_x, dim_y, dim_z}};\n  Eigen::array<IndexType, 1> red_axis;\n  red_axis[0] = 0;\n  array<IndexType, 2> reduced_tensorRange = {{dim_y, dim_z}};\n\n  Tensor<DataType, 3, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> redux(reduced_tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> redux_gpu(reduced_tensorRange);\n\n  in.setRandom();\n\n  redux = in.maximum(red_axis);\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = static_cast<DataType*>(sycl_device.allocate(\n      redux_gpu.dimensions().TotalSize() * sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> in_gpu(gpu_in_data,\n                                                               tensorRange);\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> out_gpu(\n      gpu_out_data, reduced_tensorRange);\n\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in.data(), (in.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.maximum(red_axis);\n  sycl_device.memcpyDeviceToHost(\n      redux_gpu.data(), gpu_out_data,\n      redux_gpu.dimensions().TotalSize() * sizeof(DataType));\n\n  // Check that the CPU and GPU reductions return the same result.\n  for (IndexType j = 0; j < reduced_tensorRange[0]; j++)\n    for (IndexType k = 0; k < reduced_tensorRange[1]; k++)\n      VERIFY_IS_APPROX(redux_gpu(j, k), redux(j, k));\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_first_dim_reductions_max_with_offset_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  using data_tensor = Tensor<DataType, 2, DataLayout, IndexType>;\n  using reduced_tensor = Tensor<DataType, 1, DataLayout, IndexType>;\n\n  const IndexType num_rows = 64;\n  const IndexType num_cols = 64;\n  array<IndexType, 2> tensor_range = {{num_rows, num_cols}};\n  array<IndexType, 1> reduced_range = {{num_cols}};\n  const IndexType n_elems = internal::array_prod(tensor_range);\n  const IndexType n_reduced = num_cols;\n\n  data_tensor in(tensor_range);\n  reduced_tensor redux;\n  reduced_tensor redux_gpu(reduced_range);\n\n  in.setRandom();\n  array<IndexType, 2> tensor_offset_range(tensor_range);\n  tensor_offset_range[0] -= 1;\n  // Set maximum value outside of the considered range.\n  for (IndexType i = 0; i < n_reduced; i++) {\n    in(i) = static_cast<DataType>(2);\n  }\n\n  Eigen::array<IndexType, 1> red_axis;\n  red_axis[0] = 0;\n\n  const IndexType offset = 64;\n  TensorMap<data_tensor> in_offset(in.data() + offset, tensor_offset_range);\n  redux = in_offset.maximum(red_axis);\n  for (IndexType i = 0; i < n_reduced; i++) {\n    VERIFY_IS_NOT_EQUAL(redux(i), in(i));\n  }\n\n  DataType* gpu_in_data =\n      static_cast<DataType*>(sycl_device.allocate(n_elems * sizeof(DataType)));\n  DataType* gpu_out_data = static_cast<DataType*>(\n      sycl_device.allocate(n_reduced * sizeof(DataType)));\n\n  TensorMap<data_tensor> in_gpu(gpu_in_data + offset, tensor_offset_range);\n  TensorMap<reduced_tensor> out_gpu(gpu_out_data, reduced_range);\n  sycl_device.memcpyHostToDevice(gpu_in_data, in.data(),\n                                 n_elems * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.maximum(red_axis);\n  sycl_device.memcpyDeviceToHost(redux_gpu.data(), gpu_out_data,\n                                 n_reduced * sizeof(DataType));\n\n  // Check that the CPU and GPU reductions return the same result.\n  for (IndexType i = 0; i < n_reduced; i++) {\n    VERIFY_IS_APPROX(redux_gpu(i), redux(i));\n  }\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_last_dim_reductions_max_with_offset_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  using data_tensor = Tensor<DataType, 2, DataLayout, IndexType>;\n  using reduced_tensor = Tensor<DataType, 1, DataLayout, IndexType>;\n\n  const IndexType num_rows = 64;\n  const IndexType num_cols = 64;\n  array<IndexType, 2> tensor_range = {{num_rows, num_cols}};\n  array<IndexType, 1> full_reduced_range = {{num_rows}};\n  array<IndexType, 1> reduced_range = {{num_rows - 1}};\n  const IndexType n_elems = internal::array_prod(tensor_range);\n  const IndexType n_reduced = reduced_range[0];\n\n  data_tensor in(tensor_range);\n  reduced_tensor redux(full_reduced_range);\n  reduced_tensor redux_gpu(reduced_range);\n\n  in.setRandom();\n  redux.setZero();\n  array<IndexType, 2> tensor_offset_range(tensor_range);\n  tensor_offset_range[0] -= 1;\n  // Set maximum value outside of the considered range.\n  for (IndexType i = 0; i < n_reduced; i++) {\n    in(i) = static_cast<DataType>(2);\n  }\n\n  Eigen::array<IndexType, 1> red_axis;\n  red_axis[0] = 1;\n\n  const IndexType offset = 64;\n  // Introduce an offset in both the input and the output.\n  TensorMap<data_tensor> in_offset(in.data() + offset, tensor_offset_range);\n  TensorMap<reduced_tensor> red_offset(redux.data() + 1, reduced_range);\n  red_offset = in_offset.maximum(red_axis);\n\n  // Check that the first value hasn't been changed and that the reduced values\n  // are not equal to the previously set maximum in the input outside the range.\n  VERIFY_IS_EQUAL(redux(0), static_cast<DataType>(0));\n  for (IndexType i = 0; i < n_reduced; i++) {\n    VERIFY_IS_NOT_EQUAL(red_offset(i), in(i));\n  }\n\n  DataType* gpu_in_data =\n      static_cast<DataType*>(sycl_device.allocate(n_elems * sizeof(DataType)));\n  DataType* gpu_out_data = static_cast<DataType*>(\n      sycl_device.allocate((n_reduced + 1) * sizeof(DataType)));\n\n  TensorMap<data_tensor> in_gpu(gpu_in_data + offset, tensor_offset_range);\n  TensorMap<reduced_tensor> out_gpu(gpu_out_data + 1, reduced_range);\n  sycl_device.memcpyHostToDevice(gpu_in_data, in.data(),\n                                 n_elems * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.maximum(red_axis);\n  sycl_device.memcpyDeviceToHost(redux_gpu.data(), out_gpu.data(),\n                                 n_reduced * sizeof(DataType));\n\n  // Check that the CPU and GPU reductions return the same result.\n  for (IndexType i = 0; i < n_reduced; i++) {\n    VERIFY_IS_APPROX(redux_gpu(i), red_offset(i));\n  }\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_first_dim_reductions_sum_sycl(\n    const Eigen::SyclDevice& sycl_device, IndexType dim_x, IndexType dim_y) {\n  array<IndexType, 2> tensorRange = {{dim_x, dim_y}};\n  Eigen::array<IndexType, 1> red_axis;\n  red_axis[0] = 0;\n  array<IndexType, 1> reduced_tensorRange = {{dim_y}};\n\n  Tensor<DataType, 2, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 1, DataLayout, IndexType> redux(reduced_tensorRange);\n  Tensor<DataType, 1, DataLayout, IndexType> redux_gpu(reduced_tensorRange);\n\n  in.setRandom();\n  redux = in.sum(red_axis);\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = static_cast<DataType*>(sycl_device.allocate(\n      redux_gpu.dimensions().TotalSize() * sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> in_gpu(gpu_in_data,\n                                                               tensorRange);\n  TensorMap<Tensor<DataType, 1, DataLayout, IndexType>> out_gpu(\n      gpu_out_data, reduced_tensorRange);\n\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in.data(), (in.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.sum(red_axis);\n  sycl_device.memcpyDeviceToHost(\n      redux_gpu.data(), gpu_out_data,\n      redux_gpu.dimensions().TotalSize() * sizeof(DataType));\n\n  // Check that the CPU and GPU reductions return the same result.\n  for (IndexType i = 0; i < redux.size(); i++) {\n    VERIFY_IS_APPROX(redux_gpu.data()[i], redux.data()[i]);\n  }\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_first_dim_reductions_mean_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  IndexType dim_x = 145;\n  IndexType dim_y = 1;\n  IndexType dim_z = 67;\n\n  array<IndexType, 3> tensorRange = {{dim_x, dim_y, dim_z}};\n  Eigen::array<IndexType, 1> red_axis;\n  red_axis[0] = 0;\n  array<IndexType, 2> reduced_tensorRange = {{dim_y, dim_z}};\n\n  Tensor<DataType, 3, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> redux(reduced_tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> redux_gpu(reduced_tensorRange);\n\n  in.setRandom();\n\n  redux = in.mean(red_axis);\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = static_cast<DataType*>(sycl_device.allocate(\n      redux_gpu.dimensions().TotalSize() * sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> in_gpu(gpu_in_data,\n                                                               tensorRange);\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> out_gpu(\n      gpu_out_data, reduced_tensorRange);\n\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in.data(), (in.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.mean(red_axis);\n  sycl_device.memcpyDeviceToHost(\n      redux_gpu.data(), gpu_out_data,\n      redux_gpu.dimensions().TotalSize() * sizeof(DataType));\n\n  // Check that the CPU and GPU reductions return the same result.\n  for (IndexType j = 0; j < reduced_tensorRange[0]; j++)\n    for (IndexType k = 0; k < reduced_tensorRange[1]; k++)\n      VERIFY_IS_APPROX(redux_gpu(j, k), redux(j, k));\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_last_dim_reductions_mean_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  IndexType dim_x = 64;\n  IndexType dim_y = 1;\n  IndexType dim_z = 32;\n\n  array<IndexType, 3> tensorRange = {{dim_x, dim_y, dim_z}};\n  Eigen::array<IndexType, 1> red_axis;\n  red_axis[0] = 2;\n  array<IndexType, 2> reduced_tensorRange = {{dim_x, dim_y}};\n\n  Tensor<DataType, 3, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> redux(reduced_tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> redux_gpu(reduced_tensorRange);\n\n  in.setRandom();\n\n  redux = in.mean(red_axis);\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = static_cast<DataType*>(sycl_device.allocate(\n      redux_gpu.dimensions().TotalSize() * sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> in_gpu(gpu_in_data,\n                                                               tensorRange);\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> out_gpu(\n      gpu_out_data, reduced_tensorRange);\n\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in.data(), (in.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.mean(red_axis);\n  sycl_device.memcpyDeviceToHost(\n      redux_gpu.data(), gpu_out_data,\n      redux_gpu.dimensions().TotalSize() * sizeof(DataType));\n  // Check that the CPU and GPU reductions return the same result.\n  for (IndexType j = 0; j < reduced_tensorRange[0]; j++)\n    for (IndexType k = 0; k < reduced_tensorRange[1]; k++)\n      VERIFY_IS_APPROX(redux_gpu(j, k), redux(j, k));\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_last_dim_reductions_sum_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  IndexType dim_x = 64;\n  IndexType dim_y = 1;\n  IndexType dim_z = 32;\n\n  array<IndexType, 3> tensorRange = {{dim_x, dim_y, dim_z}};\n  Eigen::array<IndexType, 1> red_axis;\n  red_axis[0] = 2;\n  array<IndexType, 2> reduced_tensorRange = {{dim_x, dim_y}};\n\n  Tensor<DataType, 3, DataLayout, IndexType> in(tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> redux(reduced_tensorRange);\n  Tensor<DataType, 2, DataLayout, IndexType> redux_gpu(reduced_tensorRange);\n\n  in.setRandom();\n\n  redux = in.sum(red_axis);\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = static_cast<DataType*>(sycl_device.allocate(\n      redux_gpu.dimensions().TotalSize() * sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> in_gpu(gpu_in_data,\n                                                               tensorRange);\n  TensorMap<Tensor<DataType, 2, DataLayout, IndexType>> out_gpu(\n      gpu_out_data, reduced_tensorRange);\n\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in.data(), (in.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.sum(red_axis);\n  sycl_device.memcpyDeviceToHost(\n      redux_gpu.data(), gpu_out_data,\n      redux_gpu.dimensions().TotalSize() * sizeof(DataType));\n  // Check that the CPU and GPU reductions return the same result.\n  for (IndexType j = 0; j < reduced_tensorRange[0]; j++)\n    for (IndexType k = 0; k < reduced_tensorRange[1]; k++)\n      VERIFY_IS_APPROX(redux_gpu(j, k), redux(j, k));\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_last_reductions_sum_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  auto tensorRange = Sizes<64, 32>(64, 32);\n  // auto red_axis =  Sizes<0,1>(0,1);\n  Eigen::IndexList<Eigen::type2index<1>> red_axis;\n  auto reduced_tensorRange = Sizes<64>(64);\n  TensorFixedSize<DataType, Sizes<64, 32>, DataLayout> in_fix;\n  TensorFixedSize<DataType, Sizes<64>, DataLayout> redux_fix;\n  TensorFixedSize<DataType, Sizes<64>, DataLayout> redux_gpu_fix;\n\n  in_fix.setRandom();\n\n  redux_fix = in_fix.sum(red_axis);\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in_fix.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = static_cast<DataType*>(sycl_device.allocate(\n      redux_gpu_fix.dimensions().TotalSize() * sizeof(DataType)));\n\n  TensorMap<TensorFixedSize<DataType, Sizes<64, 32>, DataLayout>> in_gpu_fix(\n      gpu_in_data, tensorRange);\n  TensorMap<TensorFixedSize<DataType, Sizes<64>, DataLayout>> out_gpu_fix(\n      gpu_out_data, reduced_tensorRange);\n\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in_fix.data(),\n      (in_fix.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu_fix.device(sycl_device) = in_gpu_fix.sum(red_axis);\n  sycl_device.memcpyDeviceToHost(\n      redux_gpu_fix.data(), gpu_out_data,\n      redux_gpu_fix.dimensions().TotalSize() * sizeof(DataType));\n  // Check that the CPU and GPU reductions return the same result.\n  for (IndexType j = 0; j < reduced_tensorRange[0]; j++) {\n    VERIFY_IS_APPROX(redux_gpu_fix(j), redux_fix(j));\n  }\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_last_reductions_mean_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  auto tensorRange = Sizes<64, 32>(64, 32);\n  Eigen::IndexList<Eigen::type2index<1>> red_axis;\n  auto reduced_tensorRange = Sizes<64>(64);\n  TensorFixedSize<DataType, Sizes<64, 32>, DataLayout> in_fix;\n  TensorFixedSize<DataType, Sizes<64>, DataLayout> redux_fix;\n  TensorFixedSize<DataType, Sizes<64>, DataLayout> redux_gpu_fix;\n\n  in_fix.setRandom();\n  redux_fix = in_fix.mean(red_axis);\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(in_fix.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = static_cast<DataType*>(sycl_device.allocate(\n      redux_gpu_fix.dimensions().TotalSize() * sizeof(DataType)));\n\n  TensorMap<TensorFixedSize<DataType, Sizes<64, 32>, DataLayout>> in_gpu_fix(\n      gpu_in_data, tensorRange);\n  TensorMap<TensorFixedSize<DataType, Sizes<64>, DataLayout>> out_gpu_fix(\n      gpu_out_data, reduced_tensorRange);\n\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, in_fix.data(),\n      (in_fix.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu_fix.device(sycl_device) = in_gpu_fix.mean(red_axis);\n  sycl_device.memcpyDeviceToHost(\n      redux_gpu_fix.data(), gpu_out_data,\n      redux_gpu_fix.dimensions().TotalSize() * sizeof(DataType));\n  sycl_device.synchronize();\n  // Check that the CPU and GPU reductions return the same result.\n  for (IndexType j = 0; j < reduced_tensorRange[0]; j++) {\n    VERIFY_IS_APPROX(redux_gpu_fix(j), redux_fix(j));\n  }\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\n// SYCL supports a generic case of reduction where the accumulator is a\n// different type than the input data This is an example on how to get if a\n// Tensor contains nan and/or inf in one reduction\ntemplate <typename InT, typename OutT>\nstruct CustomReducer {\n  static const bool PacketAccess = false;\n  static const bool IsStateful = false;\n\n  static constexpr OutT InfBit = 1;\n  static constexpr OutT NanBit = 2;\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const InT x,\n                                                    OutT* accum) const {\n    if (Eigen::numext::isinf(x))\n      *accum |= InfBit;\n    else if (Eigen::numext::isnan(x))\n      *accum |= NanBit;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE void reduce(const OutT x,\n                                                    OutT* accum) const {\n    *accum |= x;\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE OutT initialize() const {\n    return OutT(0);\n  }\n\n  EIGEN_DEVICE_FUNC EIGEN_STRONG_INLINE OutT finalize(const OutT accum) const {\n    return accum;\n  }\n};\n\ntemplate <typename DataType, typename AccumType, int DataLayout,\n          typename IndexType>\nstatic void test_full_reductions_custom_sycl(\n    const Eigen::SyclDevice& sycl_device) {\n  constexpr IndexType InSize = 64;\n  auto tensorRange = Sizes<InSize>(InSize);\n  Eigen::IndexList<Eigen::type2index<0>> dims;\n  auto reduced_tensorRange = Sizes<>();\n  TensorFixedSize<DataType, Sizes<InSize>, DataLayout> in_fix;\n  TensorFixedSize<AccumType, Sizes<>, DataLayout> redux_gpu_fix;\n\n  CustomReducer<DataType, AccumType> reducer;\n\n  in_fix.setRandom();\n\n  size_t in_size_bytes = in_fix.dimensions().TotalSize() * sizeof(DataType);\n  DataType* gpu_in_data =\n      static_cast<DataType*>(sycl_device.allocate(in_size_bytes));\n  AccumType* gpu_out_data =\n      static_cast<AccumType*>(sycl_device.allocate(sizeof(AccumType)));\n\n  TensorMap<TensorFixedSize<DataType, Sizes<InSize>, DataLayout>> in_gpu_fix(\n      gpu_in_data, tensorRange);\n  TensorMap<TensorFixedSize<AccumType, Sizes<>, DataLayout>> out_gpu_fix(\n      gpu_out_data, reduced_tensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_in_data, in_fix.data(), in_size_bytes);\n  out_gpu_fix.device(sycl_device) = in_gpu_fix.reduce(dims, reducer);\n  sycl_device.memcpyDeviceToHost(redux_gpu_fix.data(), gpu_out_data,\n                                 sizeof(AccumType));\n  VERIFY_IS_EQUAL(redux_gpu_fix(0), AccumType(0));\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, typename Dev>\nvoid sycl_reduction_test_full_per_device(const Dev& sycl_device) {\n  test_full_reductions_sum_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_full_reductions_sum_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_full_reductions_min_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_full_reductions_min_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_full_reductions_max_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_full_reductions_max_sycl<DataType, RowMajor, int64_t>(sycl_device);\n\n  test_full_reductions_mean_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_full_reductions_mean_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_full_reductions_custom_sycl<DataType, int, RowMajor, int64_t>(\n      sycl_device);\n  test_full_reductions_custom_sycl<DataType, int, ColMajor, int64_t>(\n      sycl_device);\n  sycl_device.synchronize();\n}\n\ntemplate <typename DataType, typename Dev>\nvoid sycl_reduction_full_offset_per_device(const Dev& sycl_device) {\n  test_full_reductions_sum_with_offset_sycl<DataType, RowMajor, int64_t>(\n      sycl_device);\n  test_full_reductions_sum_with_offset_sycl<DataType, ColMajor, int64_t>(\n      sycl_device);\n  test_full_reductions_min_with_offset_sycl<DataType, RowMajor, int64_t>(\n      sycl_device);\n  test_full_reductions_min_with_offset_sycl<DataType, ColMajor, int64_t>(\n      sycl_device);\n  test_full_reductions_max_with_offset_sycl<DataType, ColMajor, int64_t>(\n      sycl_device);\n  test_full_reductions_max_with_offset_sycl<DataType, RowMajor, int64_t>(\n      sycl_device);\n  test_full_reductions_mean_with_offset_sycl<DataType, RowMajor, int64_t>(\n      sycl_device);\n  test_full_reductions_mean_with_offset_sycl<DataType, ColMajor, int64_t>(\n      sycl_device);\n  test_full_reductions_mean_with_odd_offset_sycl<DataType, RowMajor, int64_t>(\n      sycl_device);\n  sycl_device.synchronize();\n}\n\ntemplate <typename DataType, typename Dev>\nvoid sycl_reduction_test_first_dim_per_device(const Dev& sycl_device) {\n  test_first_dim_reductions_sum_sycl<DataType, ColMajor, int64_t>(sycl_device,\n                                                                  4197, 4097);\n  test_first_dim_reductions_sum_sycl<DataType, RowMajor, int64_t>(sycl_device,\n                                                                  4197, 4097);\n  test_first_dim_reductions_sum_sycl<DataType, RowMajor, int64_t>(sycl_device,\n                                                                  129, 8);\n  test_first_dim_reductions_max_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_first_dim_reductions_max_with_offset_sycl<DataType, RowMajor, int64_t>(\n      sycl_device);\n  sycl_device.synchronize();\n}\n\ntemplate <typename DataType, typename Dev>\nvoid sycl_reduction_test_last_dim_per_device(const Dev& sycl_device) {\n  test_last_dim_reductions_sum_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_last_dim_reductions_max_with_offset_sycl<DataType, RowMajor, int64_t>(\n      sycl_device);\n  test_last_reductions_sum_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_last_reductions_sum_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_last_reductions_mean_sycl<DataType, ColMajor, int64_t>(sycl_device);\n  test_last_reductions_mean_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  sycl_device.synchronize();\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_reduction_sycl) {\n  for (const auto& device : Eigen::get_sycl_supported_devices()) {\n    std::cout << \"Running on \"\n              << device.template get_info<cl::sycl::info::device::name>()\n              << std::endl;\n    QueueInterface queueInterface(device);\n    auto sycl_device = Eigen::SyclDevice(&queueInterface);\n    CALL_SUBTEST_1(sycl_reduction_test_full_per_device<float>(sycl_device));\n    CALL_SUBTEST_2(sycl_reduction_full_offset_per_device<float>(sycl_device));\n    CALL_SUBTEST_3(\n        sycl_reduction_test_first_dim_per_device<float>(sycl_device));\n    CALL_SUBTEST_4(sycl_reduction_test_last_dim_per_device<float>(sycl_device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_ref.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\nstatic void test_simple_lvalue_ref()\n{\n  Tensor<int, 1> input(6);\n  input.setRandom();\n\n  TensorRef<Tensor<int, 1>> ref3(input);\n  TensorRef<Tensor<int, 1>> ref4 = input;\n\n  VERIFY_IS_EQUAL(ref3.data(), input.data());\n  VERIFY_IS_EQUAL(ref4.data(), input.data());\n\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_EQUAL(ref3(i), input(i));\n    VERIFY_IS_EQUAL(ref4(i), input(i));\n  }\n\n  for (int i = 0; i < 6; ++i) {\n    ref3.coeffRef(i) = i;\n  }\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_EQUAL(input(i), i);\n  }\n  for (int i = 0; i < 6; ++i) {\n    ref4.coeffRef(i) = -i * 2;\n  }\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_EQUAL(input(i), -i*2);\n  }\n}\n\n\nstatic void test_simple_rvalue_ref()\n{\n  Tensor<int, 1> input1(6);\n  input1.setRandom();\n  Tensor<int, 1> input2(6);\n  input2.setRandom();\n\n  TensorRef<Tensor<int, 1>> ref3(input1 + input2);\n  TensorRef<Tensor<int, 1>> ref4 = input1 + input2;\n\n  VERIFY_IS_NOT_EQUAL(ref3.data(), input1.data());\n  VERIFY_IS_NOT_EQUAL(ref4.data(), input1.data());\n  VERIFY_IS_NOT_EQUAL(ref3.data(), input2.data());\n  VERIFY_IS_NOT_EQUAL(ref4.data(), input2.data());\n\n  for (int i = 0; i < 6; ++i) {\n    VERIFY_IS_EQUAL(ref3(i), input1(i) + input2(i));\n    VERIFY_IS_EQUAL(ref4(i), input1(i) + input2(i));\n  }\n}\n\n\nstatic void test_multiple_dims()\n{\n  Tensor<float, 3> input(3,5,7);\n  input.setRandom();\n\n  TensorRef<Tensor<float, 3>> ref(input);\n  VERIFY_IS_EQUAL(ref.data(), input.data());\n  VERIFY_IS_EQUAL(ref.dimension(0), 3);\n  VERIFY_IS_EQUAL(ref.dimension(1), 5);\n  VERIFY_IS_EQUAL(ref.dimension(2), 7);\n\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(ref(i,j,k), input(i,j,k));\n      }\n    }\n  }\n}\n\n\nstatic void test_slice()\n{\n  Tensor<float, 5> tensor(2,3,5,7,11);\n  tensor.setRandom();\n\n  Eigen::DSizes<ptrdiff_t, 5> indices(1,2,3,4,5);\n  Eigen::DSizes<ptrdiff_t, 5> sizes(1,1,1,1,1);\n  TensorRef<Tensor<float, 5>> slice = tensor.slice(indices, sizes);\n  VERIFY_IS_EQUAL(slice(0,0,0,0,0), tensor(1,2,3,4,5));\n\n  Eigen::DSizes<ptrdiff_t, 5> indices2(1,1,3,4,5);\n  Eigen::DSizes<ptrdiff_t, 5> sizes2(1,1,2,2,3);\n  slice = tensor.slice(indices2, sizes2);\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 2; ++j) {\n      for (int k = 0; k < 3; ++k) {\n        VERIFY_IS_EQUAL(slice(0,0,i,j,k), tensor(1,1,3+i,4+j,5+k));\n      }\n    }\n  }\n\n  Eigen::DSizes<ptrdiff_t, 5> indices3(0,0,0,0,0);\n  Eigen::DSizes<ptrdiff_t, 5> sizes3(2,3,1,1,1);\n  slice = tensor.slice(indices3, sizes3);\n  VERIFY_IS_EQUAL(slice.data(), tensor.data());\n}\n\n\nstatic void test_ref_of_ref()\n{\n  Tensor<float, 3> input(3,5,7);\n  input.setRandom();\n\n  TensorRef<Tensor<float, 3>> ref(input);\n  TensorRef<Tensor<float, 3>> ref_of_ref(ref);\n  TensorRef<Tensor<float, 3>> ref_of_ref2;\n  ref_of_ref2 = ref;\n\n  VERIFY_IS_EQUAL(ref_of_ref.data(), input.data());\n  VERIFY_IS_EQUAL(ref_of_ref.dimension(0), 3);\n  VERIFY_IS_EQUAL(ref_of_ref.dimension(1), 5);\n  VERIFY_IS_EQUAL(ref_of_ref.dimension(2), 7);\n\n  VERIFY_IS_EQUAL(ref_of_ref2.data(), input.data());\n  VERIFY_IS_EQUAL(ref_of_ref2.dimension(0), 3);\n  VERIFY_IS_EQUAL(ref_of_ref2.dimension(1), 5);\n  VERIFY_IS_EQUAL(ref_of_ref2.dimension(2), 7);\n\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(ref_of_ref(i,j,k), input(i,j,k));\n        VERIFY_IS_EQUAL(ref_of_ref2(i,j,k), input(i,j,k));\n     }\n    }\n  }\n}\n\n\nstatic void test_ref_in_expr()\n{\n  Tensor<float, 3> input(3,5,7);\n  input.setRandom();\n  TensorRef<Tensor<float, 3>> input_ref(input);\n\n  Tensor<float, 3> result(3,5,7);\n  result.setRandom();\n  TensorRef<Tensor<float, 3>> result_ref(result);\n\n  Tensor<float, 3> bias(3,5,7);\n  bias.setRandom();\n\n  result_ref = input_ref + bias;\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(result_ref(i,j,k), input(i,j,k) + bias(i,j,k));\n        VERIFY_IS_NOT_EQUAL(result(i,j,k), input(i,j,k) + bias(i,j,k));\n      }\n    }\n  }\n\n  result = result_ref;\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_EQUAL(result(i,j,k), input(i,j,k) + bias(i,j,k));\n      }\n    }\n  }\n}\n\n\nstatic void test_coeff_ref()\n{\n  Tensor<float, 5> tensor(2,3,5,7,11);\n  tensor.setRandom();\n  Tensor<float, 5> original = tensor;\n\n  TensorRef<Tensor<float, 4>> slice = tensor.chip(7, 4);\n  slice.coeffRef(0, 0, 0, 0) = 1.0f;\n  slice.coeffRef(1, 0, 0, 0) += 2.0f;\n\n  VERIFY_IS_EQUAL(tensor(0,0,0,0,7), 1.0f);\n  VERIFY_IS_EQUAL(tensor(1,0,0,0,7), original(1,0,0,0,7) + 2.0f);\n}\n\n\nstatic void test_nested_ops_with_ref()\n{\n  Tensor<float, 4> t(2, 3, 5, 7);\n  t.setRandom();\n  TensorMap<Tensor<const float, 4> > m(t.data(), 2, 3, 5, 7);\n  array<std::pair<ptrdiff_t, ptrdiff_t>, 4> paddings;\n  paddings[0] = std::make_pair(0, 0);\n  paddings[1] = std::make_pair(2, 1);\n  paddings[2] = std::make_pair(3, 4);\n  paddings[3] = std::make_pair(0, 0);\n  DSizes<Eigen::DenseIndex, 4> shuffle_dims(0, 1, 2, 3);\n  TensorRef<Tensor<const float, 4> > ref(m.pad(paddings));\n  array<std::pair<ptrdiff_t, ptrdiff_t>, 4> trivial;\n  trivial[0] = std::make_pair(0, 0);\n  trivial[1] = std::make_pair(0, 0);\n  trivial[2] = std::make_pair(0, 0);\n  trivial[3] = std::make_pair(0, 0);\n  Tensor<float, 4> padded = ref.shuffle(shuffle_dims).pad(trivial);\n  VERIFY_IS_EQUAL(padded.dimension(0), 2+0);\n  VERIFY_IS_EQUAL(padded.dimension(1), 3+3);\n  VERIFY_IS_EQUAL(padded.dimension(2), 5+7);\n  VERIFY_IS_EQUAL(padded.dimension(3), 7+0);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 6; ++j) {\n      for (int k = 0; k < 12; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          if (j >= 2 && j < 5 && k >= 3 && k < 8) {\n            VERIFY_IS_EQUAL(padded(i,j,k,l), t(i,j-2,k-3,l));\n          } else {\n            VERIFY_IS_EQUAL(padded(i,j,k,l), 0.0f);\n          }\n        }\n      }\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_ref)\n{\n  CALL_SUBTEST(test_simple_lvalue_ref());\n  CALL_SUBTEST(test_simple_rvalue_ref());\n  CALL_SUBTEST(test_multiple_dims());\n  CALL_SUBTEST(test_slice());\n  CALL_SUBTEST(test_ref_of_ref());\n  CALL_SUBTEST(test_ref_in_expr());\n  CALL_SUBTEST(test_coeff_ref());\n  CALL_SUBTEST(test_nested_ops_with_ref());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_reverse.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Navdeep Jaitly <ndjaitly@google.com and\n//                    Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::array;\n\ntemplate <int DataLayout>\nstatic void test_simple_reverse()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n\n  array<bool, 4> dim_rev;\n  dim_rev[0] = false;\n  dim_rev[1] = true;\n  dim_rev[2] = true;\n  dim_rev[3] = false;\n\n  Tensor<float, 4, DataLayout> reversed_tensor;\n  reversed_tensor = tensor.reverse(dim_rev);\n\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(0), 2);\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(1), 3);\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(2), 5);\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(3), 7);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), reversed_tensor(i,2-j,4-k,l));\n        }\n      }\n    }\n  }\n\n  dim_rev[0] = true;\n  dim_rev[1] = false;\n  dim_rev[2] = false;\n  dim_rev[3] = false;\n\n  reversed_tensor = tensor.reverse(dim_rev);\n\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(0), 2);\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(1), 3);\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(2), 5);\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(3), 7);\n\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), reversed_tensor(1-i,j,k,l));\n        }\n      }\n    }\n  }\n\n  dim_rev[0] = true;\n  dim_rev[1] = false;\n  dim_rev[2] = false;\n  dim_rev[3] = true;\n\n  reversed_tensor = tensor.reverse(dim_rev);\n\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(0), 2);\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(1), 3);\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(2), 5);\n  VERIFY_IS_EQUAL(reversed_tensor.dimension(3), 7);\n\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), reversed_tensor(1-i,j,k,6-l));\n        }\n      }\n    }\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_expr_reverse(bool LValue)\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n\n  array<bool, 4> dim_rev;\n  dim_rev[0] = false;\n  dim_rev[1] = true;\n  dim_rev[2] = false;\n  dim_rev[3] = true;\n\n  Tensor<float, 4, DataLayout> expected(2, 3, 5, 7);\n  if (LValue) {\n    expected.reverse(dim_rev) = tensor;\n  } else {\n    expected = tensor.reverse(dim_rev);\n  }\n\n  Tensor<float, 4, DataLayout> result(2,3,5,7);\n\n  array<ptrdiff_t, 4> src_slice_dim;\n  src_slice_dim[0] = 2;\n  src_slice_dim[1] = 3;\n  src_slice_dim[2] = 1;\n  src_slice_dim[3] = 7;\n  array<ptrdiff_t, 4> src_slice_start;\n  src_slice_start[0] = 0;\n  src_slice_start[1] = 0;\n  src_slice_start[2] = 0;\n  src_slice_start[3] = 0;\n  array<ptrdiff_t, 4> dst_slice_dim = src_slice_dim;\n  array<ptrdiff_t, 4> dst_slice_start = src_slice_start;\n\n  for (int i = 0; i < 5; ++i) {\n    if (LValue) {\n      result.slice(dst_slice_start, dst_slice_dim).reverse(dim_rev) =\n          tensor.slice(src_slice_start, src_slice_dim);\n    } else {\n      result.slice(dst_slice_start, dst_slice_dim) =\n          tensor.slice(src_slice_start, src_slice_dim).reverse(dim_rev);\n    }\n    src_slice_start[2] += 1;\n    dst_slice_start[2] += 1;\n  }\n\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_EQUAL(result.dimension(1), 3);\n  VERIFY_IS_EQUAL(result.dimension(2), 5);\n  VERIFY_IS_EQUAL(result.dimension(3), 7);\n\n  for (int i = 0; i < expected.dimension(0); ++i) {\n    for (int j = 0; j < expected.dimension(1); ++j) {\n      for (int k = 0; k < expected.dimension(2); ++k) {\n        for (int l = 0; l < expected.dimension(3); ++l) {\n          VERIFY_IS_EQUAL(result(i,j,k,l), expected(i,j,k,l));\n        }\n      }\n    }\n  }\n\n  dst_slice_start[2] = 0;\n  result.setRandom();\n  for (int i = 0; i < 5; ++i) {\n     if (LValue) {\n       result.slice(dst_slice_start, dst_slice_dim).reverse(dim_rev) =\n           tensor.slice(dst_slice_start, dst_slice_dim);\n     } else {\n       result.slice(dst_slice_start, dst_slice_dim) =\n           tensor.reverse(dim_rev).slice(dst_slice_start, dst_slice_dim);\n     }\n    dst_slice_start[2] += 1;\n  }\n\n  for (int i = 0; i < expected.dimension(0); ++i) {\n    for (int j = 0; j < expected.dimension(1); ++j) {\n      for (int k = 0; k < expected.dimension(2); ++k) {\n        for (int l = 0; l < expected.dimension(3); ++l) {\n          VERIFY_IS_EQUAL(result(i,j,k,l), expected(i,j,k,l));\n        }\n      }\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_reverse)\n{\n  CALL_SUBTEST(test_simple_reverse<ColMajor>());\n  CALL_SUBTEST(test_simple_reverse<RowMajor>());\n  CALL_SUBTEST(test_expr_reverse<ColMajor>(true));\n  CALL_SUBTEST(test_expr_reverse<RowMajor>(true));\n  CALL_SUBTEST(test_expr_reverse<ColMajor>(false));\n  CALL_SUBTEST(test_expr_reverse<RowMajor>(false));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_reverse_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_simple_reverse(const Eigen::SyclDevice& sycl_device) {\n  IndexType dim1 = 2;\n  IndexType dim2 = 3;\n  IndexType dim3 = 5;\n  IndexType dim4 = 7;\n\n  array<IndexType, 4> tensorRange = {{dim1, dim2, dim3, dim4}};\n  Tensor<DataType, 4, DataLayout, IndexType> tensor(tensorRange);\n  Tensor<DataType, 4, DataLayout, IndexType> reversed_tensor(tensorRange);\n  tensor.setRandom();\n\n  array<bool, 4> dim_rev;\n  dim_rev[0] = false;\n  dim_rev[1] = true;\n  dim_rev[2] = true;\n  dim_rev[3] = false;\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(tensor.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data = static_cast<DataType*>(sycl_device.allocate(\n      reversed_tensor.dimensions().TotalSize() * sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType> > in_gpu(gpu_in_data,\n                                                                tensorRange);\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType> > out_gpu(gpu_out_data,\n                                                                 tensorRange);\n\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, tensor.data(),\n      (tensor.dimensions().TotalSize()) * sizeof(DataType));\n  out_gpu.device(sycl_device) = in_gpu.reverse(dim_rev);\n  sycl_device.memcpyDeviceToHost(\n      reversed_tensor.data(), gpu_out_data,\n      reversed_tensor.dimensions().TotalSize() * sizeof(DataType));\n  // Check that the CPU and GPU reductions return the same result.\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      for (IndexType k = 0; k < 5; ++k) {\n        for (IndexType l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i, j, k, l),\n                          reversed_tensor(i, 2 - j, 4 - k, l));\n        }\n      }\n    }\n  }\n  dim_rev[0] = true;\n  dim_rev[1] = false;\n  dim_rev[2] = false;\n  dim_rev[3] = false;\n\n  out_gpu.device(sycl_device) = in_gpu.reverse(dim_rev);\n  sycl_device.memcpyDeviceToHost(\n      reversed_tensor.data(), gpu_out_data,\n      reversed_tensor.dimensions().TotalSize() * sizeof(DataType));\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      for (IndexType k = 0; k < 5; ++k) {\n        for (IndexType l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i, j, k, l), reversed_tensor(1 - i, j, k, l));\n        }\n      }\n    }\n  }\n\n  dim_rev[0] = true;\n  dim_rev[1] = false;\n  dim_rev[2] = false;\n  dim_rev[3] = true;\n  out_gpu.device(sycl_device) = in_gpu.reverse(dim_rev);\n  sycl_device.memcpyDeviceToHost(\n      reversed_tensor.data(), gpu_out_data,\n      reversed_tensor.dimensions().TotalSize() * sizeof(DataType));\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      for (IndexType k = 0; k < 5; ++k) {\n        for (IndexType l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i, j, k, l),\n                          reversed_tensor(1 - i, j, k, 6 - l));\n        }\n      }\n    }\n  }\n\n  sycl_device.deallocate(gpu_in_data);\n  sycl_device.deallocate(gpu_out_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_expr_reverse(const Eigen::SyclDevice& sycl_device,\n                              bool LValue) {\n  IndexType dim1 = 2;\n  IndexType dim2 = 3;\n  IndexType dim3 = 5;\n  IndexType dim4 = 7;\n\n  array<IndexType, 4> tensorRange = {{dim1, dim2, dim3, dim4}};\n  Tensor<DataType, 4, DataLayout, IndexType> tensor(tensorRange);\n  Tensor<DataType, 4, DataLayout, IndexType> expected(tensorRange);\n  Tensor<DataType, 4, DataLayout, IndexType> result(tensorRange);\n  tensor.setRandom();\n\n  array<bool, 4> dim_rev;\n  dim_rev[0] = false;\n  dim_rev[1] = true;\n  dim_rev[2] = false;\n  dim_rev[3] = true;\n\n  DataType* gpu_in_data = static_cast<DataType*>(\n      sycl_device.allocate(tensor.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data_expected = static_cast<DataType*>(sycl_device.allocate(\n      expected.dimensions().TotalSize() * sizeof(DataType)));\n  DataType* gpu_out_data_result = static_cast<DataType*>(\n      sycl_device.allocate(result.dimensions().TotalSize() * sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType> > in_gpu(gpu_in_data,\n                                                                tensorRange);\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType> > out_gpu_expected(\n      gpu_out_data_expected, tensorRange);\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType> > out_gpu_result(\n      gpu_out_data_result, tensorRange);\n\n  sycl_device.memcpyHostToDevice(\n      gpu_in_data, tensor.data(),\n      (tensor.dimensions().TotalSize()) * sizeof(DataType));\n\n  if (LValue) {\n    out_gpu_expected.reverse(dim_rev).device(sycl_device) = in_gpu;\n  } else {\n    out_gpu_expected.device(sycl_device) = in_gpu.reverse(dim_rev);\n  }\n  sycl_device.memcpyDeviceToHost(\n      expected.data(), gpu_out_data_expected,\n      expected.dimensions().TotalSize() * sizeof(DataType));\n\n  array<IndexType, 4> src_slice_dim;\n  src_slice_dim[0] = 2;\n  src_slice_dim[1] = 3;\n  src_slice_dim[2] = 1;\n  src_slice_dim[3] = 7;\n  array<IndexType, 4> src_slice_start;\n  src_slice_start[0] = 0;\n  src_slice_start[1] = 0;\n  src_slice_start[2] = 0;\n  src_slice_start[3] = 0;\n  array<IndexType, 4> dst_slice_dim = src_slice_dim;\n  array<IndexType, 4> dst_slice_start = src_slice_start;\n\n  for (IndexType i = 0; i < 5; ++i) {\n    if (LValue) {\n      out_gpu_result.slice(dst_slice_start, dst_slice_dim)\n          .reverse(dim_rev)\n          .device(sycl_device) = in_gpu.slice(src_slice_start, src_slice_dim);\n    } else {\n      out_gpu_result.slice(dst_slice_start, dst_slice_dim).device(sycl_device) =\n          in_gpu.slice(src_slice_start, src_slice_dim).reverse(dim_rev);\n    }\n    src_slice_start[2] += 1;\n    dst_slice_start[2] += 1;\n  }\n  sycl_device.memcpyDeviceToHost(\n      result.data(), gpu_out_data_result,\n      result.dimensions().TotalSize() * sizeof(DataType));\n\n  for (IndexType i = 0; i < expected.dimension(0); ++i) {\n    for (IndexType j = 0; j < expected.dimension(1); ++j) {\n      for (IndexType k = 0; k < expected.dimension(2); ++k) {\n        for (IndexType l = 0; l < expected.dimension(3); ++l) {\n          VERIFY_IS_EQUAL(result(i, j, k, l), expected(i, j, k, l));\n        }\n      }\n    }\n  }\n\n  dst_slice_start[2] = 0;\n  result.setRandom();\n  sycl_device.memcpyHostToDevice(\n      gpu_out_data_result, result.data(),\n      (result.dimensions().TotalSize()) * sizeof(DataType));\n  for (IndexType i = 0; i < 5; ++i) {\n    if (LValue) {\n      out_gpu_result.slice(dst_slice_start, dst_slice_dim)\n          .reverse(dim_rev)\n          .device(sycl_device) = in_gpu.slice(dst_slice_start, dst_slice_dim);\n    } else {\n      out_gpu_result.slice(dst_slice_start, dst_slice_dim).device(sycl_device) =\n          in_gpu.reverse(dim_rev).slice(dst_slice_start, dst_slice_dim);\n    }\n    dst_slice_start[2] += 1;\n  }\n  sycl_device.memcpyDeviceToHost(\n      result.data(), gpu_out_data_result,\n      result.dimensions().TotalSize() * sizeof(DataType));\n\n  for (IndexType i = 0; i < expected.dimension(0); ++i) {\n    for (IndexType j = 0; j < expected.dimension(1); ++j) {\n      for (IndexType k = 0; k < expected.dimension(2); ++k) {\n        for (IndexType l = 0; l < expected.dimension(3); ++l) {\n          VERIFY_IS_EQUAL(result(i, j, k, l), expected(i, j, k, l));\n        }\n      }\n    }\n  }\n}\n\ntemplate <typename DataType>\nvoid sycl_reverse_test_per_device(const cl::sycl::device& d) {\n  QueueInterface queueInterface(d);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_simple_reverse<DataType, RowMajor, int64_t>(sycl_device);\n  test_simple_reverse<DataType, ColMajor, int64_t>(sycl_device);\n  test_expr_reverse<DataType, RowMajor, int64_t>(sycl_device, false);\n  test_expr_reverse<DataType, ColMajor, int64_t>(sycl_device, false);\n  test_expr_reverse<DataType, RowMajor, int64_t>(sycl_device, true);\n  test_expr_reverse<DataType, ColMajor, int64_t>(sycl_device, true);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_reverse_sycl) {\n  for (const auto& device : Eigen::get_sycl_supported_devices()) {\n    std::cout << \"Running on \"\n              << device.get_info<cl::sycl::info::device::name>() << std::endl;\n    CALL_SUBTEST_1(sycl_reverse_test_per_device<short>(device));\n    CALL_SUBTEST_2(sycl_reverse_test_per_device<int>(device));\n    CALL_SUBTEST_3(sycl_reverse_test_per_device<unsigned int>(device));\n#ifdef EIGEN_SYCL_DOUBLE_SUPPORT\n    CALL_SUBTEST_4(sycl_reverse_test_per_device<double>(device));\n#endif\n    CALL_SUBTEST_5(sycl_reverse_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_roundings.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\n\nstatic void test_float_rounding()\n{\n  Tensor<float, 2> ftensor(20,30);\n  ftensor = ftensor.random() * 100.f;\n\n  Tensor<float, 2> result = ftensor.round();\n\n  for (int i = 0; i < 20; ++i) {\n    for (int j = 0; j < 30; ++j) {\n      VERIFY_IS_EQUAL(result(i,j), numext::round(ftensor(i,j)));\n    }\n  }\n}\n\nstatic void test_float_flooring()\n{\n  Tensor<float, 2> ftensor(20,30);\n  ftensor = ftensor.random() * 100.f;\n\n  Tensor<float, 2> result = ftensor.floor();\n\n  for (int i = 0; i < 20; ++i) {\n    for (int j = 0; j < 30; ++j) {\n      VERIFY_IS_EQUAL(result(i,j), numext::floor(ftensor(i,j)));\n    }\n  }\n}\n\nstatic void test_float_ceiling()\n{\n  Tensor<float, 2> ftensor(20,30);\n  ftensor = ftensor.random() * 100.f;\n\n  Tensor<float, 2> result = ftensor.ceil();\n\n  for (int i = 0; i < 20; ++i) {\n    for (int j = 0; j < 30; ++j) {\n      VERIFY_IS_EQUAL(result(i,j), numext::ceil(ftensor(i,j)));\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_roundings)\n{\n   CALL_SUBTEST(test_float_rounding());\n   CALL_SUBTEST(test_float_ceiling());\n   CALL_SUBTEST(test_float_flooring());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_scan.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Igor Babuschkin <igor@babuschk.in>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <limits>\n#include <numeric>\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate <int DataLayout, typename Type=float, bool Exclusive = false>\nstatic void test_1d_scan()\n{\n  int size = 50;\n  Tensor<Type, 1, DataLayout> tensor(size);\n  tensor.setRandom();\n  Tensor<Type, 1, DataLayout> result = tensor.cumsum(0, Exclusive);\n\n  VERIFY_IS_EQUAL(tensor.dimension(0), result.dimension(0));\n\n  float accum = 0;\n  for (int i = 0; i < size; i++) {\n    if (Exclusive) {\n      VERIFY_IS_EQUAL(result(i), accum);\n      accum += tensor(i);\n    } else {\n      accum += tensor(i);\n      VERIFY_IS_EQUAL(result(i), accum);\n    }\n  }\n\n  accum = 1;\n  result = tensor.cumprod(0, Exclusive);\n  for (int i = 0; i < size; i++) {\n    if (Exclusive) {\n      VERIFY_IS_EQUAL(result(i), accum);\n      accum *= tensor(i);\n    } else {\n      accum *= tensor(i);\n      VERIFY_IS_EQUAL(result(i), accum);\n    }\n  }\n}\n\ntemplate <int DataLayout, typename Type=float>\nstatic void test_4d_scan()\n{\n  int size = 5;\n  Tensor<Type, 4, DataLayout> tensor(size, size, size, size);\n  tensor.setRandom();\n\n  Tensor<Type, 4, DataLayout> result(size, size, size, size);\n\n  result = tensor.cumsum(0);\n  float accum = 0;\n  for (int i = 0; i < size; i++) {\n    accum += tensor(i, 1, 2, 3);\n    VERIFY_IS_EQUAL(result(i, 1, 2, 3), accum);\n  }\n  result = tensor.cumsum(1);\n  accum = 0;\n  for (int i = 0; i < size; i++) {\n    accum += tensor(1, i, 2, 3);\n    VERIFY_IS_EQUAL(result(1, i, 2, 3), accum);\n  }\n  result = tensor.cumsum(2);\n  accum = 0;\n  for (int i = 0; i < size; i++) {\n    accum += tensor(1, 2, i, 3);\n    VERIFY_IS_EQUAL(result(1, 2, i, 3), accum);\n  }\n  result = tensor.cumsum(3);\n  accum = 0;\n  for (int i = 0; i < size; i++) {\n    accum += tensor(1, 2, 3, i);\n    VERIFY_IS_EQUAL(result(1, 2, 3, i), accum);\n  }\n}\n\ntemplate <int DataLayout>\nstatic void test_tensor_maps() {\n  int inputs[20];\n  TensorMap<Tensor<int, 1, DataLayout> > tensor_map(inputs, 20);\n  tensor_map.setRandom();\n\n  Tensor<int, 1, DataLayout> result = tensor_map.cumsum(0);\n\n  int accum = 0;\n  for (int i = 0; i < 20; ++i) {\n    accum += tensor_map(i);\n    VERIFY_IS_EQUAL(result(i), accum);\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_scan) {\n  CALL_SUBTEST((test_1d_scan<ColMajor, float, true>()));\n  CALL_SUBTEST((test_1d_scan<ColMajor, float, false>()));\n  CALL_SUBTEST((test_1d_scan<RowMajor, float, true>()));\n  CALL_SUBTEST((test_1d_scan<RowMajor, float, false>()));\n  CALL_SUBTEST(test_4d_scan<ColMajor>());\n  CALL_SUBTEST(test_4d_scan<RowMajor>());\n  CALL_SUBTEST(test_tensor_maps<ColMajor>());\n  CALL_SUBTEST(test_tensor_maps<RowMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_scan_gpu.cu",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int\n#define EIGEN_USE_GPU\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\n#include <Eigen/CXX11/src/Tensor/TensorGpuHipCudaDefines.h>\n\nusing Eigen::Tensor;\ntypedef Tensor<float, 1>::DimensionPair DimPair;\n\ntemplate<int DataLayout>\nvoid test_gpu_cumsum(int m_size, int k_size, int n_size)\n{\n  std::cout << \"Testing for (\" << m_size << \",\" << k_size << \",\" << n_size << \")\" << std::endl;\n  Tensor<float, 3, DataLayout> t_input(m_size, k_size, n_size);\n  Tensor<float, 3, DataLayout> t_result(m_size, k_size, n_size);\n  Tensor<float, 3, DataLayout> t_result_gpu(m_size, k_size, n_size);\n\n  t_input.setRandom();\n\n  std::size_t t_input_bytes = t_input.size()  * sizeof(float);\n  std::size_t t_result_bytes = t_result.size() * sizeof(float);\n\n  float* d_t_input;\n  float* d_t_result;\n\n  gpuMalloc((void**)(&d_t_input), t_input_bytes);\n  gpuMalloc((void**)(&d_t_result), t_result_bytes);\n\n  gpuMemcpy(d_t_input, t_input.data(), t_input_bytes, gpuMemcpyHostToDevice);\n\n  Eigen::GpuStreamDevice stream;\n  Eigen::GpuDevice gpu_device(&stream);\n\n  Eigen::TensorMap<Eigen::Tensor<float, 3, DataLayout> >\n      gpu_t_input(d_t_input, Eigen::array<int, 3>(m_size, k_size, n_size));\n  Eigen::TensorMap<Eigen::Tensor<float, 3, DataLayout> >\n      gpu_t_result(d_t_result, Eigen::array<int, 3>(m_size, k_size, n_size));\n\n  gpu_t_result.device(gpu_device) = gpu_t_input.cumsum(1);\n  t_result = t_input.cumsum(1);\n\n  gpuMemcpy(t_result_gpu.data(), d_t_result, t_result_bytes, gpuMemcpyDeviceToHost);\n  for (DenseIndex i = 0; i < t_result.size(); i++) {\n    if (fabs(t_result(i) - t_result_gpu(i)) < 1e-4f) {\n      continue;\n    }\n    if (Eigen::internal::isApprox(t_result(i), t_result_gpu(i), 1e-4f)) {\n      continue;\n    }\n    std::cout << \"mismatch detected at index \" << i << \": \" << t_result(i)\n              << \" vs \" <<  t_result_gpu(i) << std::endl;\n    assert(false);\n  }\n\n  gpuFree((void*)d_t_input);\n  gpuFree((void*)d_t_result);\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_scan_gpu)\n{\n  CALL_SUBTEST_1(test_gpu_cumsum<ColMajor>(128, 128, 128));\n  CALL_SUBTEST_2(test_gpu_cumsum<RowMajor>(128, 128, 128));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_scan_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\ntypedef Tensor<float, 1>::DimensionPair DimPair;\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_sycl_cumsum(const Eigen::SyclDevice& sycl_device, IndexType m_size,\n                      IndexType k_size, IndexType n_size, int consume_dim,\n                      bool exclusive) {\n  static const DataType error_threshold = 1e-4f;\n  std::cout << \"Testing for (\" << m_size << \",\" << k_size << \",\" << n_size\n            << \" consume_dim : \" << consume_dim << \")\" << std::endl;\n  Tensor<DataType, 3, DataLayout, IndexType> t_input(m_size, k_size, n_size);\n  Tensor<DataType, 3, DataLayout, IndexType> t_result(m_size, k_size, n_size);\n  Tensor<DataType, 3, DataLayout, IndexType> t_result_gpu(m_size, k_size,\n                                                          n_size);\n\n  t_input.setRandom();\n  std::size_t t_input_bytes = t_input.size() * sizeof(DataType);\n  std::size_t t_result_bytes = t_result.size() * sizeof(DataType);\n\n  DataType* gpu_data_in =\n      static_cast<DataType*>(sycl_device.allocate(t_input_bytes));\n  DataType* gpu_data_out =\n      static_cast<DataType*>(sycl_device.allocate(t_result_bytes));\n\n  array<IndexType, 3> tensorRange = {{m_size, k_size, n_size}};\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu_t_input(\n      gpu_data_in, tensorRange);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu_t_result(\n      gpu_data_out, tensorRange);\n  sycl_device.memcpyHostToDevice(gpu_data_in, t_input.data(), t_input_bytes);\n  sycl_device.memcpyHostToDevice(gpu_data_out, t_input.data(), t_input_bytes);\n\n  gpu_t_result.device(sycl_device) = gpu_t_input.cumsum(consume_dim, exclusive);\n\n  t_result = t_input.cumsum(consume_dim, exclusive);\n\n  sycl_device.memcpyDeviceToHost(t_result_gpu.data(), gpu_data_out,\n                                 t_result_bytes);\n  sycl_device.synchronize();\n\n  for (IndexType i = 0; i < t_result.size(); i++) {\n    if (static_cast<DataType>(std::fabs(static_cast<DataType>(\n            t_result(i) - t_result_gpu(i)))) < error_threshold) {\n      continue;\n    }\n    if (Eigen::internal::isApprox(t_result(i), t_result_gpu(i),\n                                  error_threshold)) {\n      continue;\n    }\n    std::cout << \"mismatch detected at index \" << i << \" CPU : \" << t_result(i)\n              << \" vs SYCL : \" << t_result_gpu(i) << std::endl;\n    assert(false);\n  }\n  sycl_device.deallocate(gpu_data_in);\n  sycl_device.deallocate(gpu_data_out);\n}\n\ntemplate <typename DataType, typename Dev>\nvoid sycl_scan_test_exclusive_dim0_per_device(const Dev& sycl_device) {\n  test_sycl_cumsum<DataType, ColMajor, int64_t>(sycl_device, 2049, 1023, 127, 0,\n                                                true);\n  test_sycl_cumsum<DataType, RowMajor, int64_t>(sycl_device, 2049, 1023, 127, 0,\n                                                true);\n}\ntemplate <typename DataType, typename Dev>\nvoid sycl_scan_test_exclusive_dim1_per_device(const Dev& sycl_device) {\n  test_sycl_cumsum<DataType, ColMajor, int64_t>(sycl_device, 1023, 2049, 127, 1,\n                                                true);\n  test_sycl_cumsum<DataType, RowMajor, int64_t>(sycl_device, 1023, 2049, 127, 1,\n                                                true);\n}\ntemplate <typename DataType, typename Dev>\nvoid sycl_scan_test_exclusive_dim2_per_device(const Dev& sycl_device) {\n  test_sycl_cumsum<DataType, ColMajor, int64_t>(sycl_device, 1023, 127, 2049, 2,\n                                                true);\n  test_sycl_cumsum<DataType, RowMajor, int64_t>(sycl_device, 1023, 127, 2049, 2,\n                                                true);\n}\ntemplate <typename DataType, typename Dev>\nvoid sycl_scan_test_inclusive_dim0_per_device(const Dev& sycl_device) {\n  test_sycl_cumsum<DataType, ColMajor, int64_t>(sycl_device, 2049, 1023, 127, 0,\n                                                false);\n  test_sycl_cumsum<DataType, RowMajor, int64_t>(sycl_device, 2049, 1023, 127, 0,\n                                                false);\n}\ntemplate <typename DataType, typename Dev>\nvoid sycl_scan_test_inclusive_dim1_per_device(const Dev& sycl_device) {\n  test_sycl_cumsum<DataType, ColMajor, int64_t>(sycl_device, 1023, 2049, 127, 1,\n                                                false);\n  test_sycl_cumsum<DataType, RowMajor, int64_t>(sycl_device, 1023, 2049, 127, 1,\n                                                false);\n}\ntemplate <typename DataType, typename Dev>\nvoid sycl_scan_test_inclusive_dim2_per_device(const Dev& sycl_device) {\n  test_sycl_cumsum<DataType, ColMajor, int64_t>(sycl_device, 1023, 127, 2049, 2,\n                                                false);\n  test_sycl_cumsum<DataType, RowMajor, int64_t>(sycl_device, 1023, 127, 2049, 2,\n                                                false);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_scan_sycl) {\n  for (const auto& device : Eigen::get_sycl_supported_devices()) {\n    std::cout << \"Running on \"\n              << device.template get_info<cl::sycl::info::device::name>()\n              << std::endl;\n    QueueInterface queueInterface(device);\n    auto sycl_device = Eigen::SyclDevice(&queueInterface);\n    CALL_SUBTEST_1(\n        sycl_scan_test_exclusive_dim0_per_device<float>(sycl_device));\n    CALL_SUBTEST_2(\n        sycl_scan_test_exclusive_dim1_per_device<float>(sycl_device));\n    CALL_SUBTEST_3(\n        sycl_scan_test_exclusive_dim2_per_device<float>(sycl_device));\n    CALL_SUBTEST_4(\n        sycl_scan_test_inclusive_dim0_per_device<float>(sycl_device));\n    CALL_SUBTEST_5(\n        sycl_scan_test_inclusive_dim1_per_device<float>(sycl_device));\n    CALL_SUBTEST_6(\n        sycl_scan_test_inclusive_dim2_per_device<float>(sycl_device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_shuffling.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::array;\n\ntemplate <int DataLayout>\nstatic void test_simple_shuffling()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> shuffles;\n  shuffles[0] = 0;\n  shuffles[1] = 1;\n  shuffles[2] = 2;\n  shuffles[3] = 3;\n\n  Tensor<float, 4, DataLayout> no_shuffle;\n  no_shuffle = tensor.shuffle(shuffles);\n\n  VERIFY_IS_EQUAL(no_shuffle.dimension(0), 2);\n  VERIFY_IS_EQUAL(no_shuffle.dimension(1), 3);\n  VERIFY_IS_EQUAL(no_shuffle.dimension(2), 5);\n  VERIFY_IS_EQUAL(no_shuffle.dimension(3), 7);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), no_shuffle(i,j,k,l));\n        }\n      }\n    }\n  }\n\n  shuffles[0] = 2;\n  shuffles[1] = 3;\n  shuffles[2] = 1;\n  shuffles[3] = 0;\n  Tensor<float, 4, DataLayout> shuffle;\n  shuffle = tensor.shuffle(shuffles);\n\n  VERIFY_IS_EQUAL(shuffle.dimension(0), 5);\n  VERIFY_IS_EQUAL(shuffle.dimension(1), 7);\n  VERIFY_IS_EQUAL(shuffle.dimension(2), 3);\n  VERIFY_IS_EQUAL(shuffle.dimension(3), 2);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), shuffle(k,l,j,i));\n        }\n      }\n    }\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_expr_shuffling()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n\n  array<ptrdiff_t, 4> shuffles;\n  shuffles[0] = 2;\n  shuffles[1] = 3;\n  shuffles[2] = 1;\n  shuffles[3] = 0;\n  Tensor<float, 4, DataLayout> expected;\n  expected = tensor.shuffle(shuffles);\n\n  Tensor<float, 4, DataLayout> result(5, 7, 3, 2);\n\n  array<ptrdiff_t, 4> src_slice_dim{{2, 3, 1, 7}};\n  array<ptrdiff_t, 4> src_slice_start{{0, 0, 0, 0}};\n  array<ptrdiff_t, 4> dst_slice_dim{{1, 7, 3, 2}};\n  array<ptrdiff_t, 4> dst_slice_start{{0, 0, 0, 0}};\n\n  for (int i = 0; i < 5; ++i) {\n    result.slice(dst_slice_start, dst_slice_dim) =\n        tensor.slice(src_slice_start, src_slice_dim).shuffle(shuffles);\n    src_slice_start[2] += 1;\n    dst_slice_start[0] += 1;\n  }\n\n  VERIFY_IS_EQUAL(result.dimension(0), 5);\n  VERIFY_IS_EQUAL(result.dimension(1), 7);\n  VERIFY_IS_EQUAL(result.dimension(2), 3);\n  VERIFY_IS_EQUAL(result.dimension(3), 2);\n\n  for (int i = 0; i < expected.dimension(0); ++i) {\n    for (int j = 0; j < expected.dimension(1); ++j) {\n      for (int k = 0; k < expected.dimension(2); ++k) {\n        for (int l = 0; l < expected.dimension(3); ++l) {\n          VERIFY_IS_EQUAL(result(i,j,k,l), expected(i,j,k,l));\n        }\n      }\n    }\n  }\n\n  dst_slice_start[0] = 0;\n  result.setRandom();\n  for (int i = 0; i < 5; ++i) {\n    result.slice(dst_slice_start, dst_slice_dim) =\n        tensor.shuffle(shuffles).slice(dst_slice_start, dst_slice_dim);\n    dst_slice_start[0] += 1;\n  }\n\n  for (int i = 0; i < expected.dimension(0); ++i) {\n    for (int j = 0; j < expected.dimension(1); ++j) {\n      for (int k = 0; k < expected.dimension(2); ++k) {\n        for (int l = 0; l < expected.dimension(3); ++l) {\n          VERIFY_IS_EQUAL(result(i,j,k,l), expected(i,j,k,l));\n        }\n      }\n    }\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_shuffling_as_value()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> shuffles;\n  shuffles[2] = 0;\n  shuffles[3] = 1;\n  shuffles[1] = 2;\n  shuffles[0] = 3;\n  Tensor<float, 4, DataLayout> shuffle(5,7,3,2);\n  shuffle.shuffle(shuffles) = tensor;\n\n  VERIFY_IS_EQUAL(shuffle.dimension(0), 5);\n  VERIFY_IS_EQUAL(shuffle.dimension(1), 7);\n  VERIFY_IS_EQUAL(shuffle.dimension(2), 3);\n  VERIFY_IS_EQUAL(shuffle.dimension(3), 2);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), shuffle(k,l,j,i));\n        }\n      }\n    }\n  }\n\n  array<ptrdiff_t, 4> no_shuffle;\n  no_shuffle[0] = 0;\n  no_shuffle[1] = 1;\n  no_shuffle[2] = 2;\n  no_shuffle[3] = 3;\n  Tensor<float, 4, DataLayout> shuffle2(5,7,3,2);\n  shuffle2.shuffle(shuffles) = tensor.shuffle(no_shuffle);\n  for (int i = 0; i < 5; ++i) {\n    for (int j = 0; j < 7; ++j) {\n      for (int k = 0; k < 3; ++k) {\n        for (int l = 0; l < 2; ++l) {\n          VERIFY_IS_EQUAL(shuffle2(i,j,k,l), shuffle(i,j,k,l));\n        }\n      }\n    }\n  }\n}\n\n\ntemplate <int DataLayout>\nstatic void test_shuffle_unshuffle()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n\n  // Choose a random permutation.\n  array<ptrdiff_t, 4> shuffles;\n  for (int i = 0; i < 4; ++i) {\n    shuffles[i] = i;\n  }\n  array<ptrdiff_t, 4> shuffles_inverse;\n  for (int i = 0; i < 4; ++i) {\n    const ptrdiff_t index = internal::random<ptrdiff_t>(i, 3);\n    shuffles_inverse[shuffles[index]] = i;\n    std::swap(shuffles[i], shuffles[index]);\n  }\n\n  Tensor<float, 4, DataLayout> shuffle;\n  shuffle = tensor.shuffle(shuffles).shuffle(shuffles_inverse);\n\n  VERIFY_IS_EQUAL(shuffle.dimension(0), 2);\n  VERIFY_IS_EQUAL(shuffle.dimension(1), 3);\n  VERIFY_IS_EQUAL(shuffle.dimension(2), 5);\n  VERIFY_IS_EQUAL(shuffle.dimension(3), 7);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), shuffle(i,j,k,l));\n        }\n      }\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_shuffling)\n{\n  CALL_SUBTEST(test_simple_shuffling<ColMajor>());\n  CALL_SUBTEST(test_simple_shuffling<RowMajor>());\n  CALL_SUBTEST(test_expr_shuffling<ColMajor>());\n  CALL_SUBTEST(test_expr_shuffling<RowMajor>());\n  CALL_SUBTEST(test_shuffling_as_value<ColMajor>());\n  CALL_SUBTEST(test_shuffling_as_value<RowMajor>());\n  CALL_SUBTEST(test_shuffle_unshuffle<ColMajor>());\n  CALL_SUBTEST(test_shuffle_unshuffle<RowMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_shuffling_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_simple_shuffling_sycl(const Eigen::SyclDevice& sycl_device) {\n  IndexType sizeDim1 = 2;\n  IndexType sizeDim2 = 3;\n  IndexType sizeDim3 = 5;\n  IndexType sizeDim4 = 7;\n  array<IndexType, 4> tensorRange = {{sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\n  Tensor<DataType, 4, DataLayout, IndexType> tensor(tensorRange);\n  Tensor<DataType, 4, DataLayout, IndexType> no_shuffle(tensorRange);\n  tensor.setRandom();\n\n  const size_t buffSize = tensor.size() * sizeof(DataType);\n  array<IndexType, 4> shuffles;\n  shuffles[0] = 0;\n  shuffles[1] = 1;\n  shuffles[2] = 2;\n  shuffles[3] = 3;\n  DataType* gpu_data1 = static_cast<DataType*>(sycl_device.allocate(buffSize));\n  DataType* gpu_data2 = static_cast<DataType*>(sycl_device.allocate(buffSize));\n\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType>> gpu1(gpu_data1,\n                                                             tensorRange);\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType>> gpu2(gpu_data2,\n                                                             tensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data1, tensor.data(), buffSize);\n\n  gpu2.device(sycl_device) = gpu1.shuffle(shuffles);\n  sycl_device.memcpyDeviceToHost(no_shuffle.data(), gpu_data2, buffSize);\n  sycl_device.synchronize();\n\n  VERIFY_IS_EQUAL(no_shuffle.dimension(0), sizeDim1);\n  VERIFY_IS_EQUAL(no_shuffle.dimension(1), sizeDim2);\n  VERIFY_IS_EQUAL(no_shuffle.dimension(2), sizeDim3);\n  VERIFY_IS_EQUAL(no_shuffle.dimension(3), sizeDim4);\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        for (IndexType l = 0; l < sizeDim4; ++l) {\n          VERIFY_IS_EQUAL(tensor(i, j, k, l), no_shuffle(i, j, k, l));\n        }\n      }\n    }\n  }\n\n  shuffles[0] = 2;\n  shuffles[1] = 3;\n  shuffles[2] = 1;\n  shuffles[3] = 0;\n  array<IndexType, 4> tensorrangeShuffle = {\n      {sizeDim3, sizeDim4, sizeDim2, sizeDim1}};\n  Tensor<DataType, 4, DataLayout, IndexType> shuffle(tensorrangeShuffle);\n  DataType* gpu_data3 = static_cast<DataType*>(sycl_device.allocate(buffSize));\n  TensorMap<Tensor<DataType, 4, DataLayout, IndexType>> gpu3(\n      gpu_data3, tensorrangeShuffle);\n\n  gpu3.device(sycl_device) = gpu1.shuffle(shuffles);\n  sycl_device.memcpyDeviceToHost(shuffle.data(), gpu_data3, buffSize);\n  sycl_device.synchronize();\n\n  VERIFY_IS_EQUAL(shuffle.dimension(0), sizeDim3);\n  VERIFY_IS_EQUAL(shuffle.dimension(1), sizeDim4);\n  VERIFY_IS_EQUAL(shuffle.dimension(2), sizeDim2);\n  VERIFY_IS_EQUAL(shuffle.dimension(3), sizeDim1);\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        for (IndexType l = 0; l < sizeDim4; ++l) {\n          VERIFY_IS_EQUAL(tensor(i, j, k, l), shuffle(k, l, j, i));\n        }\n      }\n    }\n  }\n}\n\ntemplate <typename DataType, typename dev_Selector>\nvoid sycl_shuffling_test_per_device(dev_Selector s) {\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_simple_shuffling_sycl<DataType, RowMajor, int64_t>(sycl_device);\n  test_simple_shuffling_sycl<DataType, ColMajor, int64_t>(sycl_device);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_shuffling_sycl) {\n  for (const auto& device : Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_shuffling_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_simple.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\nstatic void test_0d()\n{\n  Tensor<int, 0> scalar1;\n  Tensor<int, 0, RowMajor> scalar2;\n  Tensor<int, 0> scalar3;\n  Tensor<int, 0, RowMajor> scalar4;\n\n  scalar3.resize();\n  scalar4.resize();\n\n  scalar1() = 7;\n  scalar2() = 13;\n  scalar3.setValues(17);\n  scalar4.setZero();\n\n  VERIFY_IS_EQUAL(scalar1.rank(), 0);\n  VERIFY_IS_EQUAL(scalar1.size(), 1);\n\n  VERIFY_IS_EQUAL(scalar1(), 7);\n  VERIFY_IS_EQUAL(scalar2(), 13);\n  VERIFY_IS_EQUAL(scalar3(), 17);\n  VERIFY_IS_EQUAL(scalar4(), 0);\n\n  Tensor<int, 0> scalar5(scalar1);\n\n  VERIFY_IS_EQUAL(scalar5(), 7);\n  VERIFY_IS_EQUAL(scalar5.data()[0], 7);\n}\n\nstatic void test_1d()\n{\n  Tensor<int, 1> vec1(6);\n  Tensor<int, 1, RowMajor> vec2(6);\n  Tensor<int, 1> vec3;\n  Tensor<int, 1, RowMajor> vec4;\n\n  vec3.resize(6);\n  vec4.resize(6);\n\n  vec1(0) = 4;  vec2(0) = 0; vec3(0) = 5;\n  vec1(1) = 8;  vec2(1) = 1; vec3(1) = 4;\n  vec1(2) = 15; vec2(2) = 2; vec3(2) = 3;\n  vec1(3) = 16; vec2(3) = 3; vec3(3) = 2;\n  vec1(4) = 23; vec2(4) = 4; vec3(4) = 1;\n  vec1(5) = 42; vec2(5) = 5; vec3(5) = 0;\n  vec4.setZero();\n\n  VERIFY_IS_EQUAL((vec1.rank()), 1);\n  VERIFY_IS_EQUAL((vec1.size()), 6);\n  VERIFY_IS_EQUAL((vec1.dimensions()[0]), 6);\n\n  VERIFY_IS_EQUAL((vec1[0]), 4);\n  VERIFY_IS_EQUAL((vec1[1]), 8);\n  VERIFY_IS_EQUAL((vec1[2]), 15);\n  VERIFY_IS_EQUAL((vec1[3]), 16);\n  VERIFY_IS_EQUAL((vec1[4]), 23);\n  VERIFY_IS_EQUAL((vec1[5]), 42);\n\n  VERIFY_IS_EQUAL((vec2[0]), 0);\n  VERIFY_IS_EQUAL((vec2[1]), 1);\n  VERIFY_IS_EQUAL((vec2[2]), 2);\n  VERIFY_IS_EQUAL((vec2[3]), 3);\n  VERIFY_IS_EQUAL((vec2[4]), 4);\n  VERIFY_IS_EQUAL((vec2[5]), 5);\n\n  VERIFY_IS_EQUAL((vec3[0]), 5);\n  VERIFY_IS_EQUAL((vec3[1]), 4);\n  VERIFY_IS_EQUAL((vec3[2]), 3);\n  VERIFY_IS_EQUAL((vec3[3]), 2);\n  VERIFY_IS_EQUAL((vec3[4]), 1);\n  VERIFY_IS_EQUAL((vec3[5]), 0);\n\n  VERIFY_IS_EQUAL((vec4[0]), 0);\n  VERIFY_IS_EQUAL((vec4[1]), 0);\n  VERIFY_IS_EQUAL((vec4[2]), 0);\n  VERIFY_IS_EQUAL((vec4[3]), 0);\n  VERIFY_IS_EQUAL((vec4[4]), 0);\n  VERIFY_IS_EQUAL((vec4[5]), 0);\n\n  Tensor<int, 1> vec5(vec1);\n\n  VERIFY_IS_EQUAL((vec5(0)), 4);\n  VERIFY_IS_EQUAL((vec5(1)), 8);\n  VERIFY_IS_EQUAL((vec5(2)), 15);\n  VERIFY_IS_EQUAL((vec5(3)), 16);\n  VERIFY_IS_EQUAL((vec5(4)), 23);\n  VERIFY_IS_EQUAL((vec5(5)), 42);\n\n  VERIFY_IS_EQUAL((vec5.data()[0]), 4);\n  VERIFY_IS_EQUAL((vec5.data()[1]), 8);\n  VERIFY_IS_EQUAL((vec5.data()[2]), 15);\n  VERIFY_IS_EQUAL((vec5.data()[3]), 16);\n  VERIFY_IS_EQUAL((vec5.data()[4]), 23);\n  VERIFY_IS_EQUAL((vec5.data()[5]), 42);\n}\n\nstatic void test_2d()\n{\n  Tensor<int, 2> mat1(2,3);\n  Tensor<int, 2, RowMajor> mat2(2,3);\n\n  mat1(0,0) = 0;\n  mat1(0,1) = 1;\n  mat1(0,2) = 2;\n  mat1(1,0) = 3;\n  mat1(1,1) = 4;\n  mat1(1,2) = 5;\n\n  mat2(0,0) = 0;\n  mat2(0,1) = 1;\n  mat2(0,2) = 2;\n  mat2(1,0) = 3;\n  mat2(1,1) = 4;\n  mat2(1,2) = 5;\n\n  VERIFY_IS_EQUAL((mat1.rank()), 2);\n  VERIFY_IS_EQUAL((mat1.size()), 6);\n  VERIFY_IS_EQUAL((mat1.dimensions()[0]), 2);\n  VERIFY_IS_EQUAL((mat1.dimensions()[1]), 3);\n\n  VERIFY_IS_EQUAL((mat2.rank()), 2);\n  VERIFY_IS_EQUAL((mat2.size()), 6);\n  VERIFY_IS_EQUAL((mat2.dimensions()[0]), 2);\n  VERIFY_IS_EQUAL((mat2.dimensions()[1]), 3);\n\n  VERIFY_IS_EQUAL((mat1.data()[0]), 0);\n  VERIFY_IS_EQUAL((mat1.data()[1]), 3);\n  VERIFY_IS_EQUAL((mat1.data()[2]), 1);\n  VERIFY_IS_EQUAL((mat1.data()[3]), 4);\n  VERIFY_IS_EQUAL((mat1.data()[4]), 2);\n  VERIFY_IS_EQUAL((mat1.data()[5]), 5);\n\n  VERIFY_IS_EQUAL((mat2.data()[0]), 0);\n  VERIFY_IS_EQUAL((mat2.data()[1]), 1);\n  VERIFY_IS_EQUAL((mat2.data()[2]), 2);\n  VERIFY_IS_EQUAL((mat2.data()[3]), 3);\n  VERIFY_IS_EQUAL((mat2.data()[4]), 4);\n  VERIFY_IS_EQUAL((mat2.data()[5]), 5);\n}\n\nstatic void test_3d()\n{\n  Tensor<int, 3> epsilon(3,3,3);\n  epsilon.setZero();\n  epsilon(0,1,2) = epsilon(2,0,1) = epsilon(1,2,0) = 1;\n  epsilon(2,1,0) = epsilon(0,2,1) = epsilon(1,0,2) = -1;\n\n  VERIFY_IS_EQUAL((epsilon.size()), 27);\n  VERIFY_IS_EQUAL((epsilon.dimensions()[0]), 3);\n  VERIFY_IS_EQUAL((epsilon.dimensions()[1]), 3);\n  VERIFY_IS_EQUAL((epsilon.dimensions()[2]), 3);\n\n  VERIFY_IS_EQUAL((epsilon(0,0,0)), 0);\n  VERIFY_IS_EQUAL((epsilon(0,0,1)), 0);\n  VERIFY_IS_EQUAL((epsilon(0,0,2)), 0);\n  VERIFY_IS_EQUAL((epsilon(0,1,0)), 0);\n  VERIFY_IS_EQUAL((epsilon(0,1,1)), 0);\n  VERIFY_IS_EQUAL((epsilon(0,2,0)), 0);\n  VERIFY_IS_EQUAL((epsilon(0,2,2)), 0);\n  VERIFY_IS_EQUAL((epsilon(1,0,0)), 0);\n  VERIFY_IS_EQUAL((epsilon(1,0,1)), 0);\n  VERIFY_IS_EQUAL((epsilon(1,1,0)), 0);\n  VERIFY_IS_EQUAL((epsilon(1,1,1)), 0);\n  VERIFY_IS_EQUAL((epsilon(1,1,2)), 0);\n  VERIFY_IS_EQUAL((epsilon(1,2,1)), 0);\n  VERIFY_IS_EQUAL((epsilon(1,2,2)), 0);\n  VERIFY_IS_EQUAL((epsilon(2,0,0)), 0);\n  VERIFY_IS_EQUAL((epsilon(2,0,2)), 0);\n  VERIFY_IS_EQUAL((epsilon(2,1,1)), 0);\n  VERIFY_IS_EQUAL((epsilon(2,1,2)), 0);\n  VERIFY_IS_EQUAL((epsilon(2,2,0)), 0);\n  VERIFY_IS_EQUAL((epsilon(2,2,1)), 0);\n  VERIFY_IS_EQUAL((epsilon(2,2,2)), 0);\n\n  VERIFY_IS_EQUAL((epsilon(0,1,2)), 1);\n  VERIFY_IS_EQUAL((epsilon(2,0,1)), 1);\n  VERIFY_IS_EQUAL((epsilon(1,2,0)), 1);\n  VERIFY_IS_EQUAL((epsilon(2,1,0)), -1);\n  VERIFY_IS_EQUAL((epsilon(0,2,1)), -1);\n  VERIFY_IS_EQUAL((epsilon(1,0,2)), -1);\n\n  array<Eigen::DenseIndex, 3> dims;\n  dims[0] = 2;\n  dims[1] = 3;\n  dims[2] = 4;\n  Tensor<int, 3> t1(dims);\n  Tensor<int, 3, RowMajor> t2(dims);\n\n  VERIFY_IS_EQUAL((t1.size()), 24);\n  VERIFY_IS_EQUAL((t1.dimensions()[0]), 2);\n  VERIFY_IS_EQUAL((t1.dimensions()[1]), 3);\n  VERIFY_IS_EQUAL((t1.dimensions()[2]), 4);\n\n  VERIFY_IS_EQUAL((t2.size()), 24);\n  VERIFY_IS_EQUAL((t2.dimensions()[0]), 2);\n  VERIFY_IS_EQUAL((t2.dimensions()[1]), 3);\n  VERIFY_IS_EQUAL((t2.dimensions()[2]), 4);\n\n  for (int i = 0; i < 2; i++) {\n    for (int j = 0; j < 3; j++) {\n      for (int k = 0; k < 4; k++) {\n        t1(i, j, k) = 100 * i + 10 * j + k;\n        t2(i, j, k) = 100 * i + 10 * j + k;\n      }\n    }\n  }\n\n  VERIFY_IS_EQUAL((t1.data()[0]),    0);\n  VERIFY_IS_EQUAL((t1.data()[1]),  100);\n  VERIFY_IS_EQUAL((t1.data()[2]),   10);\n  VERIFY_IS_EQUAL((t1.data()[3]),  110);\n  VERIFY_IS_EQUAL((t1.data()[4]),   20);\n  VERIFY_IS_EQUAL((t1.data()[5]),  120);\n  VERIFY_IS_EQUAL((t1.data()[6]),    1);\n  VERIFY_IS_EQUAL((t1.data()[7]),  101);\n  VERIFY_IS_EQUAL((t1.data()[8]),   11);\n  VERIFY_IS_EQUAL((t1.data()[9]),  111);\n  VERIFY_IS_EQUAL((t1.data()[10]),  21);\n  VERIFY_IS_EQUAL((t1.data()[11]), 121);\n  VERIFY_IS_EQUAL((t1.data()[12]),   2);\n  VERIFY_IS_EQUAL((t1.data()[13]), 102);\n  VERIFY_IS_EQUAL((t1.data()[14]),  12);\n  VERIFY_IS_EQUAL((t1.data()[15]), 112);\n  VERIFY_IS_EQUAL((t1.data()[16]),  22);\n  VERIFY_IS_EQUAL((t1.data()[17]), 122);\n  VERIFY_IS_EQUAL((t1.data()[18]),   3);\n  VERIFY_IS_EQUAL((t1.data()[19]), 103);\n  VERIFY_IS_EQUAL((t1.data()[20]),  13);\n  VERIFY_IS_EQUAL((t1.data()[21]), 113);\n  VERIFY_IS_EQUAL((t1.data()[22]),  23);\n  VERIFY_IS_EQUAL((t1.data()[23]), 123);\n\n  VERIFY_IS_EQUAL((t2.data()[0]),    0);\n  VERIFY_IS_EQUAL((t2.data()[1]),    1);\n  VERIFY_IS_EQUAL((t2.data()[2]),    2);\n  VERIFY_IS_EQUAL((t2.data()[3]),    3);\n  VERIFY_IS_EQUAL((t2.data()[4]),   10);\n  VERIFY_IS_EQUAL((t2.data()[5]),   11);\n  VERIFY_IS_EQUAL((t2.data()[6]),   12);\n  VERIFY_IS_EQUAL((t2.data()[7]),   13);\n  VERIFY_IS_EQUAL((t2.data()[8]),   20);\n  VERIFY_IS_EQUAL((t2.data()[9]),   21);\n  VERIFY_IS_EQUAL((t2.data()[10]),  22);\n  VERIFY_IS_EQUAL((t2.data()[11]),  23);\n  VERIFY_IS_EQUAL((t2.data()[12]), 100);\n  VERIFY_IS_EQUAL((t2.data()[13]), 101);\n  VERIFY_IS_EQUAL((t2.data()[14]), 102);\n  VERIFY_IS_EQUAL((t2.data()[15]), 103);\n  VERIFY_IS_EQUAL((t2.data()[16]), 110);\n  VERIFY_IS_EQUAL((t2.data()[17]), 111);\n  VERIFY_IS_EQUAL((t2.data()[18]), 112);\n  VERIFY_IS_EQUAL((t2.data()[19]), 113);\n  VERIFY_IS_EQUAL((t2.data()[20]), 120);\n  VERIFY_IS_EQUAL((t2.data()[21]), 121);\n  VERIFY_IS_EQUAL((t2.data()[22]), 122);\n  VERIFY_IS_EQUAL((t2.data()[23]), 123);\n}\n\nstatic void test_simple_assign()\n{\n  Tensor<int, 3> epsilon(3,3,3);\n  epsilon.setZero();\n  epsilon(0,1,2) = epsilon(2,0,1) = epsilon(1,2,0) = 1;\n  epsilon(2,1,0) = epsilon(0,2,1) = epsilon(1,0,2) = -1;\n\n  Tensor<int, 3> e2(3,3,3);\n  e2.setZero();\n  VERIFY_IS_EQUAL((e2(1,2,0)), 0);\n\n  e2 = epsilon;\n  VERIFY_IS_EQUAL((e2(1,2,0)), 1);\n  VERIFY_IS_EQUAL((e2(0,1,2)), 1);\n  VERIFY_IS_EQUAL((e2(2,0,1)), 1);\n  VERIFY_IS_EQUAL((e2(2,1,0)), -1);\n  VERIFY_IS_EQUAL((e2(0,2,1)), -1);\n  VERIFY_IS_EQUAL((e2(1,0,2)), -1);\n}\n\nstatic void test_resize()\n{\n  Tensor<int, 3> epsilon;\n  epsilon.resize(2,3,7);\n  VERIFY_IS_EQUAL(epsilon.dimension(0), 2);\n  VERIFY_IS_EQUAL(epsilon.dimension(1), 3);\n  VERIFY_IS_EQUAL(epsilon.dimension(2), 7);\n  VERIFY_IS_EQUAL(epsilon.size(), 2*3*7);\n\n  const int* old_data = epsilon.data();\n  epsilon.resize(3,2,7);\n  VERIFY_IS_EQUAL(epsilon.dimension(0), 3);\n  VERIFY_IS_EQUAL(epsilon.dimension(1), 2);\n  VERIFY_IS_EQUAL(epsilon.dimension(2), 7);\n  VERIFY_IS_EQUAL(epsilon.size(), 2*3*7);\n  VERIFY_IS_EQUAL(epsilon.data(), old_data);\n\n  epsilon.resize(3,5,7);\n  VERIFY_IS_EQUAL(epsilon.dimension(0), 3);\n  VERIFY_IS_EQUAL(epsilon.dimension(1), 5);\n  VERIFY_IS_EQUAL(epsilon.dimension(2), 7);\n  VERIFY_IS_EQUAL(epsilon.size(), 3*5*7);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_simple)\n{\n  CALL_SUBTEST(test_0d());\n  CALL_SUBTEST(test_1d());\n  CALL_SUBTEST(test_2d());\n  CALL_SUBTEST(test_3d());\n  CALL_SUBTEST(test_simple_assign());\n  CALL_SUBTEST(test_resize());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_striding.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\ntemplate<int DataLayout>\nstatic void test_simple_striding()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> strides;\n  strides[0] = 1;\n  strides[1] = 1;\n  strides[2] = 1;\n  strides[3] = 1;\n\n  Tensor<float, 4, DataLayout> no_stride;\n  no_stride = tensor.stride(strides);\n\n  VERIFY_IS_EQUAL(no_stride.dimension(0), 2);\n  VERIFY_IS_EQUAL(no_stride.dimension(1), 3);\n  VERIFY_IS_EQUAL(no_stride.dimension(2), 5);\n  VERIFY_IS_EQUAL(no_stride.dimension(3), 7);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), no_stride(i,j,k,l));\n        }\n      }\n    }\n  }\n\n  strides[0] = 2;\n  strides[1] = 4;\n  strides[2] = 2;\n  strides[3] = 3;\n  Tensor<float, 4, DataLayout> stride;\n  stride = tensor.stride(strides);\n\n  VERIFY_IS_EQUAL(stride.dimension(0), 1);\n  VERIFY_IS_EQUAL(stride.dimension(1), 1);\n  VERIFY_IS_EQUAL(stride.dimension(2), 3);\n  VERIFY_IS_EQUAL(stride.dimension(3), 3);\n\n  for (int i = 0; i < 1; ++i) {\n    for (int j = 0; j < 1; ++j) {\n      for (int k = 0; k < 3; ++k) {\n        for (int l = 0; l < 3; ++l) {\n          VERIFY_IS_EQUAL(tensor(2*i,4*j,2*k,3*l), stride(i,j,k,l));\n        }\n      }\n    }\n  }\n}\n\n\ntemplate<int DataLayout>\nstatic void test_striding_as_lvalue()\n{\n  Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  array<ptrdiff_t, 4> strides;\n  strides[0] = 2;\n  strides[1] = 4;\n  strides[2] = 2;\n  strides[3] = 3;\n\n  Tensor<float, 4, DataLayout> result(3, 12, 10, 21);\n  result.stride(strides) = tensor;\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), result(2*i,4*j,2*k,3*l));\n        }\n      }\n    }\n  }\n\n  array<ptrdiff_t, 4> no_strides;\n  no_strides[0] = 1;\n  no_strides[1] = 1;\n  no_strides[2] = 1;\n  no_strides[3] = 1;\n  Tensor<float, 4, DataLayout> result2(3, 12, 10, 21);\n  result2.stride(strides) = tensor.stride(no_strides);\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        for (int l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), result2(2*i,4*j,2*k,3*l));\n        }\n      }\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_striding)\n{\n  CALL_SUBTEST(test_simple_striding<ColMajor>());\n  CALL_SUBTEST(test_simple_striding<RowMajor>());\n  CALL_SUBTEST(test_striding_as_lvalue<ColMajor>());\n  CALL_SUBTEST(test_striding_as_lvalue<RowMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_striding_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include <iostream>\n#include <chrono>\n#include <ctime>\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_simple_striding(const Eigen::SyclDevice& sycl_device)\n{\n\n  Eigen::array<IndexType, 4> tensor_dims = {{2,3,5,7}};\n  Eigen::array<IndexType, 4> stride_dims = {{1,1,3,3}};\n\n\n  Tensor<DataType, 4, DataLayout, IndexType> tensor(tensor_dims);\n  Tensor<DataType, 4, DataLayout,IndexType> no_stride(tensor_dims);\n  Tensor<DataType, 4, DataLayout,IndexType> stride(stride_dims);\n\n\n  std::size_t tensor_bytes = tensor.size()  * sizeof(DataType);\n  std::size_t no_stride_bytes = no_stride.size() * sizeof(DataType);\n  std::size_t stride_bytes = stride.size() * sizeof(DataType);\n  DataType * d_tensor = static_cast<DataType*>(sycl_device.allocate(tensor_bytes));\n  DataType * d_no_stride = static_cast<DataType*>(sycl_device.allocate(no_stride_bytes));\n  DataType * d_stride = static_cast<DataType*>(sycl_device.allocate(stride_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 4, DataLayout, IndexType> > gpu_tensor(d_tensor, tensor_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 4, DataLayout, IndexType> > gpu_no_stride(d_no_stride, tensor_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 4, DataLayout, IndexType> > gpu_stride(d_stride, stride_dims);\n\n\n  tensor.setRandom();\n  array<IndexType, 4> strides;\n  strides[0] = 1;\n  strides[1] = 1;\n  strides[2] = 1;\n  strides[3] = 1;\n  sycl_device.memcpyHostToDevice(d_tensor, tensor.data(), tensor_bytes);\n  gpu_no_stride.device(sycl_device)=gpu_tensor.stride(strides);\n  sycl_device.memcpyDeviceToHost(no_stride.data(), d_no_stride, no_stride_bytes);\n\n  //no_stride = tensor.stride(strides);\n\n  VERIFY_IS_EQUAL(no_stride.dimension(0), 2);\n  VERIFY_IS_EQUAL(no_stride.dimension(1), 3);\n  VERIFY_IS_EQUAL(no_stride.dimension(2), 5);\n  VERIFY_IS_EQUAL(no_stride.dimension(3), 7);\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      for (IndexType k = 0; k < 5; ++k) {\n        for (IndexType l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), no_stride(i,j,k,l));\n        }\n      }\n    }\n  }\n\n  strides[0] = 2;\n  strides[1] = 4;\n  strides[2] = 2;\n  strides[3] = 3;\n//Tensor<float, 4, DataLayout> stride;\n//  stride = tensor.stride(strides);\n\n  gpu_stride.device(sycl_device)=gpu_tensor.stride(strides);\n  sycl_device.memcpyDeviceToHost(stride.data(), d_stride, stride_bytes);\n\n  VERIFY_IS_EQUAL(stride.dimension(0), 1);\n  VERIFY_IS_EQUAL(stride.dimension(1), 1);\n  VERIFY_IS_EQUAL(stride.dimension(2), 3);\n  VERIFY_IS_EQUAL(stride.dimension(3), 3);\n\n  for (IndexType i = 0; i < 1; ++i) {\n    for (IndexType j = 0; j < 1; ++j) {\n      for (IndexType k = 0; k < 3; ++k) {\n        for (IndexType l = 0; l < 3; ++l) {\n          VERIFY_IS_EQUAL(tensor(2*i,4*j,2*k,3*l), stride(i,j,k,l));\n        }\n      }\n    }\n  }\n\n  sycl_device.deallocate(d_tensor);\n  sycl_device.deallocate(d_no_stride);\n  sycl_device.deallocate(d_stride);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nstatic void test_striding_as_lvalue(const Eigen::SyclDevice& sycl_device)\n{\n\n  Eigen::array<IndexType, 4> tensor_dims = {{2,3,5,7}};\n  Eigen::array<IndexType, 4> stride_dims = {{3,12,10,21}};\n\n\n  Tensor<DataType, 4, DataLayout, IndexType> tensor(tensor_dims);\n  Tensor<DataType, 4, DataLayout,IndexType> no_stride(stride_dims);\n  Tensor<DataType, 4, DataLayout,IndexType> stride(stride_dims);\n\n\n  std::size_t tensor_bytes = tensor.size()  * sizeof(DataType);\n  std::size_t no_stride_bytes = no_stride.size() * sizeof(DataType);\n  std::size_t stride_bytes = stride.size() * sizeof(DataType);\n\n  DataType * d_tensor = static_cast<DataType*>(sycl_device.allocate(tensor_bytes));\n  DataType * d_no_stride = static_cast<DataType*>(sycl_device.allocate(no_stride_bytes));\n  DataType * d_stride = static_cast<DataType*>(sycl_device.allocate(stride_bytes));\n\n  Eigen::TensorMap<Eigen::Tensor<DataType, 4, DataLayout, IndexType> > gpu_tensor(d_tensor, tensor_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 4, DataLayout, IndexType> > gpu_no_stride(d_no_stride, stride_dims);\n  Eigen::TensorMap<Eigen::Tensor<DataType, 4, DataLayout, IndexType> > gpu_stride(d_stride, stride_dims);\n\n  //Tensor<float, 4, DataLayout> tensor(2,3,5,7);\n  tensor.setRandom();\n  array<IndexType, 4> strides;\n  strides[0] = 2;\n  strides[1] = 4;\n  strides[2] = 2;\n  strides[3] = 3;\n\n//  Tensor<float, 4, DataLayout> result(3, 12, 10, 21);\n//  result.stride(strides) = tensor;\n  sycl_device.memcpyHostToDevice(d_tensor, tensor.data(), tensor_bytes);\n  gpu_stride.stride(strides).device(sycl_device)=gpu_tensor;\n  sycl_device.memcpyDeviceToHost(stride.data(), d_stride, stride_bytes);\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      for (IndexType k = 0; k < 5; ++k) {\n        for (IndexType l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), stride(2*i,4*j,2*k,3*l));\n        }\n      }\n    }\n  }\n\n  array<IndexType, 4> no_strides;\n  no_strides[0] = 1;\n  no_strides[1] = 1;\n  no_strides[2] = 1;\n  no_strides[3] = 1;\n//  Tensor<float, 4, DataLayout> result2(3, 12, 10, 21);\n//  result2.stride(strides) = tensor.stride(no_strides);\n\n  gpu_no_stride.stride(strides).device(sycl_device)=gpu_tensor.stride(no_strides);\n  sycl_device.memcpyDeviceToHost(no_stride.data(), d_no_stride, no_stride_bytes);\n\n  for (IndexType i = 0; i < 2; ++i) {\n    for (IndexType j = 0; j < 3; ++j) {\n      for (IndexType k = 0; k < 5; ++k) {\n        for (IndexType l = 0; l < 7; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), no_stride(2*i,4*j,2*k,3*l));\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(d_tensor);\n  sycl_device.deallocate(d_no_stride);\n  sycl_device.deallocate(d_stride);\n}\n\n\ntemplate <typename Dev_selector> void tensorStridingPerDevice(Dev_selector& s){\n  QueueInterface queueInterface(s);\n  auto sycl_device=Eigen::SyclDevice(&queueInterface);\n  test_simple_striding<float, ColMajor, int64_t>(sycl_device);\n  test_simple_striding<float, RowMajor, int64_t>(sycl_device);\n  test_striding_as_lvalue<float, ColMajor, int64_t>(sycl_device);\n  test_striding_as_lvalue<float, RowMajor, int64_t>(sycl_device);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_striding_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(tensorStridingPerDevice(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_sugar.cpp",
    "content": "#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::RowMajor;\n\nstatic void test_comparison_sugar() {\n  // we already trust comparisons between tensors, we're simply checking that\n  // the sugared versions are doing the same thing\n  Tensor<int, 3> t(6, 7, 5);\n\n  t.setRandom();\n  // make sure we have at least one value == 0\n  t(0,0,0) = 0;\n\n  Tensor<bool,0> b;\n\n#define TEST_TENSOR_EQUAL(e1, e2) \\\n  b = ((e1) == (e2)).all();       \\\n  VERIFY(b())\n\n#define TEST_OP(op) TEST_TENSOR_EQUAL(t op 0, t op t.constant(0))\n\n  TEST_OP(==);\n  TEST_OP(!=);\n  TEST_OP(<=);\n  TEST_OP(>=);\n  TEST_OP(<);\n  TEST_OP(>);\n#undef TEST_OP\n#undef TEST_TENSOR_EQUAL\n}\n\n\nstatic void test_scalar_sugar_add_mul() {\n  Tensor<float, 3> A(6, 7, 5);\n  Tensor<float, 3> B(6, 7, 5);\n  A.setRandom();\n  B.setRandom();\n\n  const float alpha = 0.43f;\n  const float beta = 0.21f;\n  const float gamma = 0.14f;\n\n  Tensor<float, 3> R = A.constant(gamma) + A * A.constant(alpha) + B * B.constant(beta);\n  Tensor<float, 3> S = A * alpha + B * beta + gamma;\n  Tensor<float, 3> T = gamma + alpha * A + beta * B;\n\n  for (int i = 0; i < 6*7*5; ++i) {\n    VERIFY_IS_APPROX(R(i), S(i));\n    VERIFY_IS_APPROX(R(i), T(i));\n  }\n}\n\nstatic void test_scalar_sugar_sub_div() {\n  Tensor<float, 3> A(6, 7, 5);\n  Tensor<float, 3> B(6, 7, 5);\n  A.setRandom();\n  B.setRandom();\n\n  const float alpha = 0.43f;\n  const float beta = 0.21f;\n  const float gamma = 0.14f;\n  const float delta = 0.32f;\n\n  Tensor<float, 3> R = A.constant(gamma) - A / A.constant(alpha)\n      - B.constant(beta) / B - A.constant(delta);\n  Tensor<float, 3> S = gamma - A / alpha - beta / B - delta;\n\n  for (int i = 0; i < 6*7*5; ++i) {\n    VERIFY_IS_APPROX(R(i), S(i));\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_sugar)\n{\n  CALL_SUBTEST(test_comparison_sugar());\n  CALL_SUBTEST(test_scalar_sugar_add_mul());\n  CALL_SUBTEST(test_scalar_sugar_sub_div());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n// Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::array;\nusing Eigen::SyclDevice;\nusing Eigen::Tensor;\nusing Eigen::TensorMap;\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_sycl_mem_transfers(const Eigen::SyclDevice &sycl_device) {\n  IndexType sizeDim1 = 5;\n  IndexType sizeDim2 = 5;\n  IndexType sizeDim3 = 1;\n  array<IndexType, 3> tensorRange = {{sizeDim1, sizeDim2, sizeDim3}};\n  Tensor<DataType, 3, DataLayout, IndexType> in1(tensorRange);\n  Tensor<DataType, 3, DataLayout, IndexType> out1(tensorRange);\n  Tensor<DataType, 3, DataLayout, IndexType> out2(tensorRange);\n  Tensor<DataType, 3, DataLayout, IndexType> out3(tensorRange);\n\n  in1 = in1.random();\n\n  DataType* gpu_data1  = static_cast<DataType*>(sycl_device.allocate(in1.size()*sizeof(DataType)));\n  DataType* gpu_data2  = static_cast<DataType*>(sycl_device.allocate(out1.size()*sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu1(gpu_data1, tensorRange);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu2(gpu_data2, tensorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data1, in1.data(),(in1.size())*sizeof(DataType));\n  sycl_device.memcpyHostToDevice(gpu_data2, in1.data(),(in1.size())*sizeof(DataType));\n  gpu1.device(sycl_device) = gpu1 * 3.14f;\n  gpu2.device(sycl_device) = gpu2 * 2.7f;\n  sycl_device.memcpyDeviceToHost(out1.data(), gpu_data1,(out1.size())*sizeof(DataType));\n  sycl_device.memcpyDeviceToHost(out2.data(), gpu_data1,(out2.size())*sizeof(DataType));\n  sycl_device.memcpyDeviceToHost(out3.data(), gpu_data2,(out3.size())*sizeof(DataType));\n  sycl_device.synchronize();\n\n  for (IndexType i = 0; i < in1.size(); ++i) {\n  //  std::cout << \"SYCL DATA : \" << out1(i) << \"  vs  CPU DATA : \" << in1(i) * 3.14f << \"\\n\";\n    VERIFY_IS_APPROX(out1(i), in1(i) * 3.14f);\n    VERIFY_IS_APPROX(out2(i), in1(i) * 3.14f);\n    VERIFY_IS_APPROX(out3(i), in1(i) * 2.7f);\n  }\n\n  sycl_device.deallocate(gpu_data1);\n  sycl_device.deallocate(gpu_data2);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_sycl_mem_sync(const Eigen::SyclDevice &sycl_device) {\n  IndexType size = 20;\n  array<IndexType, 1> tensorRange = {{size}};\n  Tensor<DataType, 1, DataLayout, IndexType> in1(tensorRange);\n  Tensor<DataType, 1, DataLayout, IndexType> in2(tensorRange);\n  Tensor<DataType, 1, DataLayout, IndexType> out(tensorRange);\n\n  in1 = in1.random();\n  in2 = in1;\n\n  DataType* gpu_data  = static_cast<DataType*>(sycl_device.allocate(in1.size()*sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 1, DataLayout, IndexType>> gpu1(gpu_data, tensorRange);\n  sycl_device.memcpyHostToDevice(gpu_data, in1.data(),(in1.size())*sizeof(DataType));\n  sycl_device.synchronize();\n  in1.setZero();\n\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_data, out.size()*sizeof(DataType));\n  sycl_device.synchronize();\n\n  for (IndexType i = 0; i < in1.size(); ++i) {\n    VERIFY_IS_APPROX(out(i), in2(i));\n  }\n\n  sycl_device.deallocate(gpu_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_sycl_mem_sync_offsets(const Eigen::SyclDevice &sycl_device) {\n  using tensor_type = Tensor<DataType, 1, DataLayout, IndexType>;\n  IndexType full_size = 32;\n  IndexType half_size = full_size / 2;\n  array<IndexType, 1> tensorRange = {{full_size}};\n  tensor_type in1(tensorRange);\n  tensor_type out(tensorRange);\n\n  DataType* gpu_data  = static_cast<DataType*>(sycl_device.allocate(full_size * sizeof(DataType)));\n  TensorMap<tensor_type> gpu1(gpu_data, tensorRange);\n\n  in1 = in1.random();\n  // Copy all data to device, then permute on copy back to host\n  sycl_device.memcpyHostToDevice(gpu_data, in1.data(), full_size * sizeof(DataType));\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_data + half_size, half_size * sizeof(DataType));\n  sycl_device.memcpyDeviceToHost(out.data() + half_size, gpu_data, half_size * sizeof(DataType));\n\n  for (IndexType i = 0; i < half_size; ++i) {\n    VERIFY_IS_APPROX(out(i), in1(i + half_size));\n    VERIFY_IS_APPROX(out(i + half_size), in1(i));\n  }\n\n  in1 = in1.random();\n  out.setZero();\n  // Permute copies to device, then copy all back to host\n  sycl_device.memcpyHostToDevice(gpu_data + half_size, in1.data(), half_size * sizeof(DataType));\n  sycl_device.memcpyHostToDevice(gpu_data, in1.data() + half_size, half_size * sizeof(DataType));\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_data, full_size * sizeof(DataType));\n\n  for (IndexType i = 0; i < half_size; ++i) {\n    VERIFY_IS_APPROX(out(i), in1(i + half_size));\n    VERIFY_IS_APPROX(out(i + half_size), in1(i));\n  }\n\n  in1 = in1.random();\n  out.setZero();\n  DataType* gpu_data_out  = static_cast<DataType*>(sycl_device.allocate(full_size * sizeof(DataType)));\n  TensorMap<tensor_type> gpu2(gpu_data_out, tensorRange);\n  // Copy all to device, permute copies on device, then copy all back to host\n  sycl_device.memcpyHostToDevice(gpu_data, in1.data(), full_size * sizeof(DataType));\n  sycl_device.memcpy(gpu_data_out + half_size, gpu_data, half_size * sizeof(DataType));\n  sycl_device.memcpy(gpu_data_out, gpu_data + half_size, half_size * sizeof(DataType));\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_data_out, full_size * sizeof(DataType));\n\n  for (IndexType i = 0; i < half_size; ++i) {\n    VERIFY_IS_APPROX(out(i), in1(i + half_size));\n    VERIFY_IS_APPROX(out(i + half_size), in1(i));\n  }\n\n  sycl_device.deallocate(gpu_data_out);\n  sycl_device.deallocate(gpu_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_sycl_memset_offsets(const Eigen::SyclDevice &sycl_device) {\n  using tensor_type = Tensor<DataType, 1, DataLayout, IndexType>;\n  IndexType full_size = 32;\n  IndexType half_size = full_size / 2;\n  array<IndexType, 1> tensorRange = {{full_size}};\n  tensor_type cpu_out(tensorRange);\n  tensor_type out(tensorRange);\n\n  cpu_out.setZero();\n\n  std::memset(cpu_out.data(), 0, half_size * sizeof(DataType));\n  std::memset(cpu_out.data() + half_size, 1, half_size * sizeof(DataType));\n\n  DataType* gpu_data  = static_cast<DataType*>(sycl_device.allocate(full_size * sizeof(DataType)));\n  TensorMap<tensor_type> gpu1(gpu_data, tensorRange);\n\n  sycl_device.memset(gpu_data, 0, half_size * sizeof(DataType));\n  sycl_device.memset(gpu_data + half_size, 1, half_size * sizeof(DataType));\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_data, full_size * sizeof(DataType));\n\n  for (IndexType i = 0; i < full_size; ++i) {\n    VERIFY_IS_APPROX(out(i), cpu_out(i));\n  }\n\n  sycl_device.deallocate(gpu_data);\n}\n\ntemplate <typename DataType, int DataLayout, typename IndexType>\nvoid test_sycl_computations(const Eigen::SyclDevice &sycl_device) {\n\n  IndexType sizeDim1 = 100;\n  IndexType sizeDim2 = 10;\n  IndexType sizeDim3 = 20;\n  array<IndexType, 3> tensorRange = {{sizeDim1, sizeDim2, sizeDim3}};\n  Tensor<DataType, 3,DataLayout, IndexType> in1(tensorRange);\n  Tensor<DataType, 3,DataLayout, IndexType> in2(tensorRange);\n  Tensor<DataType, 3,DataLayout, IndexType> in3(tensorRange);\n  Tensor<DataType, 3,DataLayout, IndexType> out(tensorRange);\n\n  in2 = in2.random();\n  in3 = in3.random();\n\n  DataType * gpu_in1_data  = static_cast<DataType*>(sycl_device.allocate(in1.size()*sizeof(DataType)));\n  DataType * gpu_in2_data  = static_cast<DataType*>(sycl_device.allocate(in2.size()*sizeof(DataType)));\n  DataType * gpu_in3_data  = static_cast<DataType*>(sycl_device.allocate(in3.size()*sizeof(DataType)));\n  DataType * gpu_out_data =  static_cast<DataType*>(sycl_device.allocate(out.size()*sizeof(DataType)));\n\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu_in1(gpu_in1_data, tensorRange);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu_in2(gpu_in2_data, tensorRange);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu_in3(gpu_in3_data, tensorRange);\n  TensorMap<Tensor<DataType, 3, DataLayout, IndexType>> gpu_out(gpu_out_data, tensorRange);\n\n  /// a=1.2f\n  gpu_in1.device(sycl_device) = gpu_in1.constant(1.2f);\n  sycl_device.memcpyDeviceToHost(in1.data(), gpu_in1_data ,(in1.size())*sizeof(DataType));\n  sycl_device.synchronize();\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        VERIFY_IS_APPROX(in1(i,j,k), 1.2f);\n      }\n    }\n  }\n  printf(\"a=1.2f Test passed\\n\");\n\n  /// a=b*1.2f\n  gpu_out.device(sycl_device) = gpu_in1 * 1.2f;\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data ,(out.size())*sizeof(DataType));\n  sycl_device.synchronize();\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k),\n                         in1(i,j,k) * 1.2f);\n      }\n    }\n  }\n  printf(\"a=b*1.2f Test Passed\\n\");\n\n  /// c=a*b\n  sycl_device.memcpyHostToDevice(gpu_in2_data, in2.data(),(in2.size())*sizeof(DataType));\n  gpu_out.device(sycl_device) = gpu_in1 * gpu_in2;\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data,(out.size())*sizeof(DataType));\n  sycl_device.synchronize();\n\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k),\n                         in1(i,j,k) *\n                             in2(i,j,k));\n      }\n    }\n  }\n  printf(\"c=a*b Test Passed\\n\");\n\n  /// c=a+b\n  gpu_out.device(sycl_device) = gpu_in1 + gpu_in2;\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data,(out.size())*sizeof(DataType));\n  sycl_device.synchronize();\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k),\n                         in1(i,j,k) +\n                             in2(i,j,k));\n      }\n    }\n  }\n  printf(\"c=a+b Test Passed\\n\");\n\n  /// c=a*a\n  gpu_out.device(sycl_device) = gpu_in1 * gpu_in1;\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data,(out.size())*sizeof(DataType));\n  sycl_device.synchronize();\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k),\n                         in1(i,j,k) *\n                             in1(i,j,k));\n      }\n    }\n  }\n  printf(\"c= a*a Test Passed\\n\");\n\n  //a*3.14f + b*2.7f\n  gpu_out.device(sycl_device) =  gpu_in1 * gpu_in1.constant(3.14f) + gpu_in2 * gpu_in2.constant(2.7f);\n  sycl_device.memcpyDeviceToHost(out.data(),gpu_out_data,(out.size())*sizeof(DataType));\n  sycl_device.synchronize();\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k),\n                         in1(i,j,k) * 3.14f\n                       + in2(i,j,k) * 2.7f);\n      }\n    }\n  }\n  printf(\"a*3.14f + b*2.7f Test Passed\\n\");\n\n  ///d= (a>0.5? b:c)\n  sycl_device.memcpyHostToDevice(gpu_in3_data, in3.data(),(in3.size())*sizeof(DataType));\n  gpu_out.device(sycl_device) =(gpu_in1 > gpu_in1.constant(0.5f)).select(gpu_in2, gpu_in3);\n  sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data,(out.size())*sizeof(DataType));\n  sycl_device.synchronize();\n  for (IndexType i = 0; i < sizeDim1; ++i) {\n    for (IndexType j = 0; j < sizeDim2; ++j) {\n      for (IndexType k = 0; k < sizeDim3; ++k) {\n        VERIFY_IS_APPROX(out(i, j, k), (in1(i, j, k) > 0.5f)\n                                                ? in2(i, j, k)\n                                                : in3(i, j, k));\n      }\n    }\n  }\n  printf(\"d= (a>0.5? b:c) Test Passed\\n\");\n  sycl_device.deallocate(gpu_in1_data);\n  sycl_device.deallocate(gpu_in2_data);\n  sycl_device.deallocate(gpu_in3_data);\n  sycl_device.deallocate(gpu_out_data);\n}\ntemplate<typename Scalar1, typename Scalar2,  int DataLayout, typename IndexType>\nstatic void test_sycl_cast(const Eigen::SyclDevice& sycl_device){\n    IndexType size = 20;\n    array<IndexType, 1> tensorRange = {{size}};\n    Tensor<Scalar1, 1, DataLayout, IndexType> in(tensorRange);\n    Tensor<Scalar2, 1, DataLayout, IndexType> out(tensorRange);\n    Tensor<Scalar2, 1, DataLayout, IndexType> out_host(tensorRange);\n\n    in = in.random();\n\n    Scalar1* gpu_in_data  = static_cast<Scalar1*>(sycl_device.allocate(in.size()*sizeof(Scalar1)));\n    Scalar2 * gpu_out_data =  static_cast<Scalar2*>(sycl_device.allocate(out.size()*sizeof(Scalar2)));\n\n    TensorMap<Tensor<Scalar1, 1, DataLayout, IndexType>> gpu_in(gpu_in_data, tensorRange);\n    TensorMap<Tensor<Scalar2, 1, DataLayout, IndexType>> gpu_out(gpu_out_data, tensorRange);\n    sycl_device.memcpyHostToDevice(gpu_in_data, in.data(),(in.size())*sizeof(Scalar1));\n    gpu_out.device(sycl_device) = gpu_in. template cast<Scalar2>();\n    sycl_device.memcpyDeviceToHost(out.data(), gpu_out_data, out.size()*sizeof(Scalar2));\n    out_host = in. template cast<Scalar2>();\n    for(IndexType i=0; i< size; i++)\n    {\n      VERIFY_IS_APPROX(out(i), out_host(i));\n    }\n    printf(\"cast Test Passed\\n\");\n    sycl_device.deallocate(gpu_in_data);\n    sycl_device.deallocate(gpu_out_data);\n}\ntemplate<typename DataType, typename dev_Selector> void sycl_computing_test_per_device(dev_Selector s){\n  QueueInterface queueInterface(s);\n  auto sycl_device = Eigen::SyclDevice(&queueInterface);\n  test_sycl_mem_transfers<DataType, RowMajor, int64_t>(sycl_device);\n  test_sycl_computations<DataType, RowMajor, int64_t>(sycl_device);\n  test_sycl_mem_sync<DataType, RowMajor, int64_t>(sycl_device);\n  test_sycl_mem_sync_offsets<DataType, RowMajor, int64_t>(sycl_device);\n  test_sycl_memset_offsets<DataType, RowMajor, int64_t>(sycl_device);\n  test_sycl_mem_transfers<DataType, ColMajor, int64_t>(sycl_device);\n  test_sycl_computations<DataType, ColMajor, int64_t>(sycl_device);\n  test_sycl_mem_sync<DataType, ColMajor, int64_t>(sycl_device);\n  test_sycl_cast<DataType, int, RowMajor, int64_t>(sycl_device);\n  test_sycl_cast<DataType, int, ColMajor, int64_t>(sycl_device);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_sycl) {\n  for (const auto& device :Eigen::get_sycl_supported_devices()) {\n    CALL_SUBTEST(sycl_computing_test_per_device<float>(device));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_symmetry.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2013 Christian Seiler <christian@iwakd.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n#include <Eigen/CXX11/TensorSymmetry>\n\n#include <map>\n#include <set>\n\nusing Eigen::Tensor;\nusing Eigen::SGroup;\nusing Eigen::DynamicSGroup;\nusing Eigen::StaticSGroup;\nusing Eigen::Symmetry;\nusing Eigen::AntiSymmetry;\nusing Eigen::Hermiticity;\nusing Eigen::AntiHermiticity;\n\nusing Eigen::NegationFlag;\nusing Eigen::ConjugationFlag;\nusing Eigen::GlobalZeroFlag;\nusing Eigen::GlobalRealFlag;\nusing Eigen::GlobalImagFlag;\n\n// helper function to determine if the compiler intantiated a static\n// or dynamic symmetry group\ntemplate<typename... Sym>\nbool isDynGroup(StaticSGroup<Sym...> const& dummy)\n{\n  (void)dummy;\n  return false;\n}\n\nbool isDynGroup(DynamicSGroup const& dummy)\n{\n  (void)dummy;\n  return true;\n}\n\n// helper class for checking that the symmetry groups are correct\nstruct checkIdx {\n  template<typename ArrType>\n  static inline int doCheck_(ArrType e, int flags, int dummy, std::set<uint64_t>& found, std::map<uint64_t, int> const& expected)\n  {\n    // use decimal representation of value\n    uint64_t value = e[0];\n    for (std::size_t i = 1; i < e.size(); i++)\n      value = value * 10 + e[i];\n\n    // we want to make sure that we find each element\n    auto it = expected.find(value);\n    VERIFY((it != expected.end()));\n    VERIFY_IS_EQUAL(it->second, flags);\n\n    // we want to make sure we only have each element once;\n    // set::insert returns true for the second part of the pair\n    // if the element was really inserted and not already there\n    auto p = found.insert(value);\n    VERIFY((p.second));\n\n    return dummy;\n  }\n\n  static inline int run(std::vector<int> e, int flags, int dummy, std::set<uint64_t>& found, std::map<uint64_t, int> const& expected)\n  {\n    return doCheck_(e, flags, dummy, found, expected);\n  }\n\n  template<std::size_t N>\n  static inline int run(std::array<int, N> e, int flags, int dummy, std::set<uint64_t>& found, std::map<uint64_t, int> const& expected)\n  {\n    return doCheck_(e, flags, dummy, found, expected);\n  }\n};\n\nstatic void test_symgroups_static()\n{\n  std::array<int, 7> identity{{0,1,2,3,4,5,6}};\n\n  // Simple static symmetry group\n  StaticSGroup<\n    AntiSymmetry<0,1>,\n    Hermiticity<0,2>\n  > group;\n\n  std::set<uint64_t> found;\n  std::map<uint64_t, int> expected;\n  expected[ 123456] = 0;\n  expected[1023456] = NegationFlag;\n  expected[2103456] = ConjugationFlag;\n  expected[1203456] = ConjugationFlag | NegationFlag;\n  expected[2013456] = ConjugationFlag | NegationFlag;\n  expected[ 213456] = ConjugationFlag;\n\n  VERIFY_IS_EQUAL(group.size(), 6u);\n  VERIFY_IS_EQUAL(group.globalFlags(), GlobalImagFlag);\n  group.apply<checkIdx, int>(identity, 0, found, expected);\n  VERIFY_IS_EQUAL(found.size(), 6u);\n}\n\nstatic void test_symgroups_dynamic()\n{\n  std::vector<int> identity;\n  for (int i = 0; i <= 6; i++)\n    identity.push_back(i);\n\n  // Simple dynamic symmetry group\n  DynamicSGroup group;\n  group.add(0,1,NegationFlag);\n  group.add(0,2,ConjugationFlag);\n\n  VERIFY_IS_EQUAL(group.size(), 6u);\n  VERIFY_IS_EQUAL(group.globalFlags(), GlobalImagFlag);\n\n  std::set<uint64_t> found;\n  std::map<uint64_t, int> expected;\n  expected[ 123456] = 0;\n  expected[1023456] = NegationFlag;\n  expected[2103456] = ConjugationFlag;\n  expected[1203456] = ConjugationFlag | NegationFlag;\n  expected[2013456] = ConjugationFlag | NegationFlag;\n  expected[ 213456] = ConjugationFlag;\n\n  VERIFY_IS_EQUAL(group.size(), 6u);\n  VERIFY_IS_EQUAL(group.globalFlags(), GlobalImagFlag);\n  group.apply<checkIdx, int>(identity, 0, found, expected);\n  VERIFY_IS_EQUAL(found.size(), 6u);\n}\n\nstatic void test_symgroups_selection()\n{\n  std::array<int, 7> identity7{{0,1,2,3,4,5,6}};\n  std::array<int, 10> identity10{{0,1,2,3,4,5,6,7,8,9}};\n\n  {\n    // Do the same test as in test_symgroups_static but\n    // require selection via SGroup\n    SGroup<\n      AntiSymmetry<0,1>,\n      Hermiticity<0,2>\n    > group;\n\n    std::set<uint64_t> found;\n    std::map<uint64_t, int> expected;\n    expected[ 123456] = 0;\n    expected[1023456] = NegationFlag;\n    expected[2103456] = ConjugationFlag;\n    expected[1203456] = ConjugationFlag | NegationFlag;\n    expected[2013456] = ConjugationFlag | NegationFlag;\n    expected[ 213456] = ConjugationFlag;\n\n    VERIFY(!isDynGroup(group));\n    VERIFY_IS_EQUAL(group.size(), 6u);\n    VERIFY_IS_EQUAL(group.globalFlags(), GlobalImagFlag);\n    group.apply<checkIdx, int>(identity7, 0, found, expected);\n    VERIFY_IS_EQUAL(found.size(), 6u);\n  }\n\n  {\n    // simple factorizing group: 5 generators, 2^5 = 32 elements\n    // selection should make this dynamic, although static group\n    // can still be reasonably generated\n    SGroup<\n      Symmetry<0,1>,\n      Symmetry<2,3>,\n      Symmetry<4,5>,\n      Symmetry<6,7>,\n      Symmetry<8,9>\n    > group;\n\n    std::set<uint64_t> found;\n    std::map<uint64_t, int> expected;\n    expected[ 123456789] = 0; expected[ 123456798] = 0; expected[ 123457689] = 0; expected[ 123457698] = 0;\n    expected[ 123546789] = 0; expected[ 123546798] = 0; expected[ 123547689] = 0; expected[ 123547698] = 0;\n    expected[ 132456789] = 0; expected[ 132456798] = 0; expected[ 132457689] = 0; expected[ 132457698] = 0;\n    expected[ 132546789] = 0; expected[ 132546798] = 0; expected[ 132547689] = 0; expected[ 132547698] = 0;\n    expected[1023456789] = 0; expected[1023456798] = 0; expected[1023457689] = 0; expected[1023457698] = 0;\n    expected[1023546789] = 0; expected[1023546798] = 0; expected[1023547689] = 0; expected[1023547698] = 0;\n    expected[1032456789] = 0; expected[1032456798] = 0; expected[1032457689] = 0; expected[1032457698] = 0;\n    expected[1032546789] = 0; expected[1032546798] = 0; expected[1032547689] = 0; expected[1032547698] = 0;\n\n    VERIFY(isDynGroup(group));\n    VERIFY_IS_EQUAL(group.size(), 32u);\n    VERIFY_IS_EQUAL(group.globalFlags(), 0);\n    group.apply<checkIdx, int>(identity10, 0, found, expected);\n    VERIFY_IS_EQUAL(found.size(), 32u);\n\n    // no verify that we could also generate a static group\n    // with these generators\n    found.clear();\n    StaticSGroup<\n      Symmetry<0,1>,\n      Symmetry<2,3>,\n      Symmetry<4,5>,\n      Symmetry<6,7>,\n      Symmetry<8,9>\n    > group_static;\n    VERIFY_IS_EQUAL(group_static.size(), 32u);\n    VERIFY_IS_EQUAL(group_static.globalFlags(), 0);\n    group_static.apply<checkIdx, int>(identity10, 0, found, expected);\n    VERIFY_IS_EQUAL(found.size(), 32u);\n  }\n\n  {\n    // try to create a HUGE group\n    SGroup<\n      Symmetry<0,1>,\n      Symmetry<1,2>,\n      Symmetry<2,3>,\n      Symmetry<3,4>,\n      Symmetry<4,5>,\n      Symmetry<5,6>\n    > group;\n\n    std::set<uint64_t> found;\n    uint64_t pre_expected[5040] = {\n       123456, 1023456,  213456, 2013456, 1203456, 2103456,  132456, 1032456,  312456, 3012456, 1302456, 3102456,\n       231456, 2031456,  321456, 3021456, 2301456, 3201456, 1230456, 2130456, 1320456, 3120456, 2310456, 3210456,\n       124356, 1024356,  214356, 2014356, 1204356, 2104356,  142356, 1042356,  412356, 4012356, 1402356, 4102356,\n       241356, 2041356,  421356, 4021356, 2401356, 4201356, 1240356, 2140356, 1420356, 4120356, 2410356, 4210356,\n       134256, 1034256,  314256, 3014256, 1304256, 3104256,  143256, 1043256,  413256, 4013256, 1403256, 4103256,\n       341256, 3041256,  431256, 4031256, 3401256, 4301256, 1340256, 3140256, 1430256, 4130256, 3410256, 4310256,\n       234156, 2034156,  324156, 3024156, 2304156, 3204156,  243156, 2043156,  423156, 4023156, 2403156, 4203156,\n       342156, 3042156,  432156, 4032156, 3402156, 4302156, 2340156, 3240156, 2430156, 4230156, 3420156, 4320156,\n      1234056, 2134056, 1324056, 3124056, 2314056, 3214056, 1243056, 2143056, 1423056, 4123056, 2413056, 4213056,\n      1342056, 3142056, 1432056, 4132056, 3412056, 4312056, 2341056, 3241056, 2431056, 4231056, 3421056, 4321056,\n       123546, 1023546,  213546, 2013546, 1203546, 2103546,  132546, 1032546,  312546, 3012546, 1302546, 3102546,\n       231546, 2031546,  321546, 3021546, 2301546, 3201546, 1230546, 2130546, 1320546, 3120546, 2310546, 3210546,\n       125346, 1025346,  215346, 2015346, 1205346, 2105346,  152346, 1052346,  512346, 5012346, 1502346, 5102346,\n       251346, 2051346,  521346, 5021346, 2501346, 5201346, 1250346, 2150346, 1520346, 5120346, 2510346, 5210346,\n       135246, 1035246,  315246, 3015246, 1305246, 3105246,  153246, 1053246,  513246, 5013246, 1503246, 5103246,\n       351246, 3051246,  531246, 5031246, 3501246, 5301246, 1350246, 3150246, 1530246, 5130246, 3510246, 5310246,\n       235146, 2035146,  325146, 3025146, 2305146, 3205146,  253146, 2053146,  523146, 5023146, 2503146, 5203146,\n       352146, 3052146,  532146, 5032146, 3502146, 5302146, 2350146, 3250146, 2530146, 5230146, 3520146, 5320146,\n      1235046, 2135046, 1325046, 3125046, 2315046, 3215046, 1253046, 2153046, 1523046, 5123046, 2513046, 5213046,\n      1352046, 3152046, 1532046, 5132046, 3512046, 5312046, 2351046, 3251046, 2531046, 5231046, 3521046, 5321046,\n       124536, 1024536,  214536, 2014536, 1204536, 2104536,  142536, 1042536,  412536, 4012536, 1402536, 4102536,\n       241536, 2041536,  421536, 4021536, 2401536, 4201536, 1240536, 2140536, 1420536, 4120536, 2410536, 4210536,\n       125436, 1025436,  215436, 2015436, 1205436, 2105436,  152436, 1052436,  512436, 5012436, 1502436, 5102436,\n       251436, 2051436,  521436, 5021436, 2501436, 5201436, 1250436, 2150436, 1520436, 5120436, 2510436, 5210436,\n       145236, 1045236,  415236, 4015236, 1405236, 4105236,  154236, 1054236,  514236, 5014236, 1504236, 5104236,\n       451236, 4051236,  541236, 5041236, 4501236, 5401236, 1450236, 4150236, 1540236, 5140236, 4510236, 5410236,\n       245136, 2045136,  425136, 4025136, 2405136, 4205136,  254136, 2054136,  524136, 5024136, 2504136, 5204136,\n       452136, 4052136,  542136, 5042136, 4502136, 5402136, 2450136, 4250136, 2540136, 5240136, 4520136, 5420136,\n      1245036, 2145036, 1425036, 4125036, 2415036, 4215036, 1254036, 2154036, 1524036, 5124036, 2514036, 5214036,\n      1452036, 4152036, 1542036, 5142036, 4512036, 5412036, 2451036, 4251036, 2541036, 5241036, 4521036, 5421036,\n       134526, 1034526,  314526, 3014526, 1304526, 3104526,  143526, 1043526,  413526, 4013526, 1403526, 4103526,\n       341526, 3041526,  431526, 4031526, 3401526, 4301526, 1340526, 3140526, 1430526, 4130526, 3410526, 4310526,\n       135426, 1035426,  315426, 3015426, 1305426, 3105426,  153426, 1053426,  513426, 5013426, 1503426, 5103426,\n       351426, 3051426,  531426, 5031426, 3501426, 5301426, 1350426, 3150426, 1530426, 5130426, 3510426, 5310426,\n       145326, 1045326,  415326, 4015326, 1405326, 4105326,  154326, 1054326,  514326, 5014326, 1504326, 5104326,\n       451326, 4051326,  541326, 5041326, 4501326, 5401326, 1450326, 4150326, 1540326, 5140326, 4510326, 5410326,\n       345126, 3045126,  435126, 4035126, 3405126, 4305126,  354126, 3054126,  534126, 5034126, 3504126, 5304126,\n       453126, 4053126,  543126, 5043126, 4503126, 5403126, 3450126, 4350126, 3540126, 5340126, 4530126, 5430126,\n      1345026, 3145026, 1435026, 4135026, 3415026, 4315026, 1354026, 3154026, 1534026, 5134026, 3514026, 5314026,\n      1453026, 4153026, 1543026, 5143026, 4513026, 5413026, 3451026, 4351026, 3541026, 5341026, 4531026, 5431026,\n       234516, 2034516,  324516, 3024516, 2304516, 3204516,  243516, 2043516,  423516, 4023516, 2403516, 4203516,\n       342516, 3042516,  432516, 4032516, 3402516, 4302516, 2340516, 3240516, 2430516, 4230516, 3420516, 4320516,\n       235416, 2035416,  325416, 3025416, 2305416, 3205416,  253416, 2053416,  523416, 5023416, 2503416, 5203416,\n       352416, 3052416,  532416, 5032416, 3502416, 5302416, 2350416, 3250416, 2530416, 5230416, 3520416, 5320416,\n       245316, 2045316,  425316, 4025316, 2405316, 4205316,  254316, 2054316,  524316, 5024316, 2504316, 5204316,\n       452316, 4052316,  542316, 5042316, 4502316, 5402316, 2450316, 4250316, 2540316, 5240316, 4520316, 5420316,\n       345216, 3045216,  435216, 4035216, 3405216, 4305216,  354216, 3054216,  534216, 5034216, 3504216, 5304216,\n       453216, 4053216,  543216, 5043216, 4503216, 5403216, 3450216, 4350216, 3540216, 5340216, 4530216, 5430216,\n      2345016, 3245016, 2435016, 4235016, 3425016, 4325016, 2354016, 3254016, 2534016, 5234016, 3524016, 5324016,\n      2453016, 4253016, 2543016, 5243016, 4523016, 5423016, 3452016, 4352016, 3542016, 5342016, 4532016, 5432016,\n      1234506, 2134506, 1324506, 3124506, 2314506, 3214506, 1243506, 2143506, 1423506, 4123506, 2413506, 4213506,\n      1342506, 3142506, 1432506, 4132506, 3412506, 4312506, 2341506, 3241506, 2431506, 4231506, 3421506, 4321506,\n      1235406, 2135406, 1325406, 3125406, 2315406, 3215406, 1253406, 2153406, 1523406, 5123406, 2513406, 5213406,\n      1352406, 3152406, 1532406, 5132406, 3512406, 5312406, 2351406, 3251406, 2531406, 5231406, 3521406, 5321406,\n      1245306, 2145306, 1425306, 4125306, 2415306, 4215306, 1254306, 2154306, 1524306, 5124306, 2514306, 5214306,\n      1452306, 4152306, 1542306, 5142306, 4512306, 5412306, 2451306, 4251306, 2541306, 5241306, 4521306, 5421306,\n      1345206, 3145206, 1435206, 4135206, 3415206, 4315206, 1354206, 3154206, 1534206, 5134206, 3514206, 5314206,\n      1453206, 4153206, 1543206, 5143206, 4513206, 5413206, 3451206, 4351206, 3541206, 5341206, 4531206, 5431206,\n      2345106, 3245106, 2435106, 4235106, 3425106, 4325106, 2354106, 3254106, 2534106, 5234106, 3524106, 5324106,\n      2453106, 4253106, 2543106, 5243106, 4523106, 5423106, 3452106, 4352106, 3542106, 5342106, 4532106, 5432106,\n       123465, 1023465,  213465, 2013465, 1203465, 2103465,  132465, 1032465,  312465, 3012465, 1302465, 3102465,\n       231465, 2031465,  321465, 3021465, 2301465, 3201465, 1230465, 2130465, 1320465, 3120465, 2310465, 3210465,\n       124365, 1024365,  214365, 2014365, 1204365, 2104365,  142365, 1042365,  412365, 4012365, 1402365, 4102365,\n       241365, 2041365,  421365, 4021365, 2401365, 4201365, 1240365, 2140365, 1420365, 4120365, 2410365, 4210365,\n       134265, 1034265,  314265, 3014265, 1304265, 3104265,  143265, 1043265,  413265, 4013265, 1403265, 4103265,\n       341265, 3041265,  431265, 4031265, 3401265, 4301265, 1340265, 3140265, 1430265, 4130265, 3410265, 4310265,\n       234165, 2034165,  324165, 3024165, 2304165, 3204165,  243165, 2043165,  423165, 4023165, 2403165, 4203165,\n       342165, 3042165,  432165, 4032165, 3402165, 4302165, 2340165, 3240165, 2430165, 4230165, 3420165, 4320165,\n      1234065, 2134065, 1324065, 3124065, 2314065, 3214065, 1243065, 2143065, 1423065, 4123065, 2413065, 4213065,\n      1342065, 3142065, 1432065, 4132065, 3412065, 4312065, 2341065, 3241065, 2431065, 4231065, 3421065, 4321065,\n       123645, 1023645,  213645, 2013645, 1203645, 2103645,  132645, 1032645,  312645, 3012645, 1302645, 3102645,\n       231645, 2031645,  321645, 3021645, 2301645, 3201645, 1230645, 2130645, 1320645, 3120645, 2310645, 3210645,\n       126345, 1026345,  216345, 2016345, 1206345, 2106345,  162345, 1062345,  612345, 6012345, 1602345, 6102345,\n       261345, 2061345,  621345, 6021345, 2601345, 6201345, 1260345, 2160345, 1620345, 6120345, 2610345, 6210345,\n       136245, 1036245,  316245, 3016245, 1306245, 3106245,  163245, 1063245,  613245, 6013245, 1603245, 6103245,\n       361245, 3061245,  631245, 6031245, 3601245, 6301245, 1360245, 3160245, 1630245, 6130245, 3610245, 6310245,\n       236145, 2036145,  326145, 3026145, 2306145, 3206145,  263145, 2063145,  623145, 6023145, 2603145, 6203145,\n       362145, 3062145,  632145, 6032145, 3602145, 6302145, 2360145, 3260145, 2630145, 6230145, 3620145, 6320145,\n      1236045, 2136045, 1326045, 3126045, 2316045, 3216045, 1263045, 2163045, 1623045, 6123045, 2613045, 6213045,\n      1362045, 3162045, 1632045, 6132045, 3612045, 6312045, 2361045, 3261045, 2631045, 6231045, 3621045, 6321045,\n       124635, 1024635,  214635, 2014635, 1204635, 2104635,  142635, 1042635,  412635, 4012635, 1402635, 4102635,\n       241635, 2041635,  421635, 4021635, 2401635, 4201635, 1240635, 2140635, 1420635, 4120635, 2410635, 4210635,\n       126435, 1026435,  216435, 2016435, 1206435, 2106435,  162435, 1062435,  612435, 6012435, 1602435, 6102435,\n       261435, 2061435,  621435, 6021435, 2601435, 6201435, 1260435, 2160435, 1620435, 6120435, 2610435, 6210435,\n       146235, 1046235,  416235, 4016235, 1406235, 4106235,  164235, 1064235,  614235, 6014235, 1604235, 6104235,\n       461235, 4061235,  641235, 6041235, 4601235, 6401235, 1460235, 4160235, 1640235, 6140235, 4610235, 6410235,\n       246135, 2046135,  426135, 4026135, 2406135, 4206135,  264135, 2064135,  624135, 6024135, 2604135, 6204135,\n       462135, 4062135,  642135, 6042135, 4602135, 6402135, 2460135, 4260135, 2640135, 6240135, 4620135, 6420135,\n      1246035, 2146035, 1426035, 4126035, 2416035, 4216035, 1264035, 2164035, 1624035, 6124035, 2614035, 6214035,\n      1462035, 4162035, 1642035, 6142035, 4612035, 6412035, 2461035, 4261035, 2641035, 6241035, 4621035, 6421035,\n       134625, 1034625,  314625, 3014625, 1304625, 3104625,  143625, 1043625,  413625, 4013625, 1403625, 4103625,\n       341625, 3041625,  431625, 4031625, 3401625, 4301625, 1340625, 3140625, 1430625, 4130625, 3410625, 4310625,\n       136425, 1036425,  316425, 3016425, 1306425, 3106425,  163425, 1063425,  613425, 6013425, 1603425, 6103425,\n       361425, 3061425,  631425, 6031425, 3601425, 6301425, 1360425, 3160425, 1630425, 6130425, 3610425, 6310425,\n       146325, 1046325,  416325, 4016325, 1406325, 4106325,  164325, 1064325,  614325, 6014325, 1604325, 6104325,\n       461325, 4061325,  641325, 6041325, 4601325, 6401325, 1460325, 4160325, 1640325, 6140325, 4610325, 6410325,\n       346125, 3046125,  436125, 4036125, 3406125, 4306125,  364125, 3064125,  634125, 6034125, 3604125, 6304125,\n       463125, 4063125,  643125, 6043125, 4603125, 6403125, 3460125, 4360125, 3640125, 6340125, 4630125, 6430125,\n      1346025, 3146025, 1436025, 4136025, 3416025, 4316025, 1364025, 3164025, 1634025, 6134025, 3614025, 6314025,\n      1463025, 4163025, 1643025, 6143025, 4613025, 6413025, 3461025, 4361025, 3641025, 6341025, 4631025, 6431025,\n       234615, 2034615,  324615, 3024615, 2304615, 3204615,  243615, 2043615,  423615, 4023615, 2403615, 4203615,\n       342615, 3042615,  432615, 4032615, 3402615, 4302615, 2340615, 3240615, 2430615, 4230615, 3420615, 4320615,\n       236415, 2036415,  326415, 3026415, 2306415, 3206415,  263415, 2063415,  623415, 6023415, 2603415, 6203415,\n       362415, 3062415,  632415, 6032415, 3602415, 6302415, 2360415, 3260415, 2630415, 6230415, 3620415, 6320415,\n       246315, 2046315,  426315, 4026315, 2406315, 4206315,  264315, 2064315,  624315, 6024315, 2604315, 6204315,\n       462315, 4062315,  642315, 6042315, 4602315, 6402315, 2460315, 4260315, 2640315, 6240315, 4620315, 6420315,\n       346215, 3046215,  436215, 4036215, 3406215, 4306215,  364215, 3064215,  634215, 6034215, 3604215, 6304215,\n       463215, 4063215,  643215, 6043215, 4603215, 6403215, 3460215, 4360215, 3640215, 6340215, 4630215, 6430215,\n      2346015, 3246015, 2436015, 4236015, 3426015, 4326015, 2364015, 3264015, 2634015, 6234015, 3624015, 6324015,\n      2463015, 4263015, 2643015, 6243015, 4623015, 6423015, 3462015, 4362015, 3642015, 6342015, 4632015, 6432015,\n      1234605, 2134605, 1324605, 3124605, 2314605, 3214605, 1243605, 2143605, 1423605, 4123605, 2413605, 4213605,\n      1342605, 3142605, 1432605, 4132605, 3412605, 4312605, 2341605, 3241605, 2431605, 4231605, 3421605, 4321605,\n      1236405, 2136405, 1326405, 3126405, 2316405, 3216405, 1263405, 2163405, 1623405, 6123405, 2613405, 6213405,\n      1362405, 3162405, 1632405, 6132405, 3612405, 6312405, 2361405, 3261405, 2631405, 6231405, 3621405, 6321405,\n      1246305, 2146305, 1426305, 4126305, 2416305, 4216305, 1264305, 2164305, 1624305, 6124305, 2614305, 6214305,\n      1462305, 4162305, 1642305, 6142305, 4612305, 6412305, 2461305, 4261305, 2641305, 6241305, 4621305, 6421305,\n      1346205, 3146205, 1436205, 4136205, 3416205, 4316205, 1364205, 3164205, 1634205, 6134205, 3614205, 6314205,\n      1463205, 4163205, 1643205, 6143205, 4613205, 6413205, 3461205, 4361205, 3641205, 6341205, 4631205, 6431205,\n      2346105, 3246105, 2436105, 4236105, 3426105, 4326105, 2364105, 3264105, 2634105, 6234105, 3624105, 6324105,\n      2463105, 4263105, 2643105, 6243105, 4623105, 6423105, 3462105, 4362105, 3642105, 6342105, 4632105, 6432105,\n       123564, 1023564,  213564, 2013564, 1203564, 2103564,  132564, 1032564,  312564, 3012564, 1302564, 3102564,\n       231564, 2031564,  321564, 3021564, 2301564, 3201564, 1230564, 2130564, 1320564, 3120564, 2310564, 3210564,\n       125364, 1025364,  215364, 2015364, 1205364, 2105364,  152364, 1052364,  512364, 5012364, 1502364, 5102364,\n       251364, 2051364,  521364, 5021364, 2501364, 5201364, 1250364, 2150364, 1520364, 5120364, 2510364, 5210364,\n       135264, 1035264,  315264, 3015264, 1305264, 3105264,  153264, 1053264,  513264, 5013264, 1503264, 5103264,\n       351264, 3051264,  531264, 5031264, 3501264, 5301264, 1350264, 3150264, 1530264, 5130264, 3510264, 5310264,\n       235164, 2035164,  325164, 3025164, 2305164, 3205164,  253164, 2053164,  523164, 5023164, 2503164, 5203164,\n       352164, 3052164,  532164, 5032164, 3502164, 5302164, 2350164, 3250164, 2530164, 5230164, 3520164, 5320164,\n      1235064, 2135064, 1325064, 3125064, 2315064, 3215064, 1253064, 2153064, 1523064, 5123064, 2513064, 5213064,\n      1352064, 3152064, 1532064, 5132064, 3512064, 5312064, 2351064, 3251064, 2531064, 5231064, 3521064, 5321064,\n       123654, 1023654,  213654, 2013654, 1203654, 2103654,  132654, 1032654,  312654, 3012654, 1302654, 3102654,\n       231654, 2031654,  321654, 3021654, 2301654, 3201654, 1230654, 2130654, 1320654, 3120654, 2310654, 3210654,\n       126354, 1026354,  216354, 2016354, 1206354, 2106354,  162354, 1062354,  612354, 6012354, 1602354, 6102354,\n       261354, 2061354,  621354, 6021354, 2601354, 6201354, 1260354, 2160354, 1620354, 6120354, 2610354, 6210354,\n       136254, 1036254,  316254, 3016254, 1306254, 3106254,  163254, 1063254,  613254, 6013254, 1603254, 6103254,\n       361254, 3061254,  631254, 6031254, 3601254, 6301254, 1360254, 3160254, 1630254, 6130254, 3610254, 6310254,\n       236154, 2036154,  326154, 3026154, 2306154, 3206154,  263154, 2063154,  623154, 6023154, 2603154, 6203154,\n       362154, 3062154,  632154, 6032154, 3602154, 6302154, 2360154, 3260154, 2630154, 6230154, 3620154, 6320154,\n      1236054, 2136054, 1326054, 3126054, 2316054, 3216054, 1263054, 2163054, 1623054, 6123054, 2613054, 6213054,\n      1362054, 3162054, 1632054, 6132054, 3612054, 6312054, 2361054, 3261054, 2631054, 6231054, 3621054, 6321054,\n       125634, 1025634,  215634, 2015634, 1205634, 2105634,  152634, 1052634,  512634, 5012634, 1502634, 5102634,\n       251634, 2051634,  521634, 5021634, 2501634, 5201634, 1250634, 2150634, 1520634, 5120634, 2510634, 5210634,\n       126534, 1026534,  216534, 2016534, 1206534, 2106534,  162534, 1062534,  612534, 6012534, 1602534, 6102534,\n       261534, 2061534,  621534, 6021534, 2601534, 6201534, 1260534, 2160534, 1620534, 6120534, 2610534, 6210534,\n       156234, 1056234,  516234, 5016234, 1506234, 5106234,  165234, 1065234,  615234, 6015234, 1605234, 6105234,\n       561234, 5061234,  651234, 6051234, 5601234, 6501234, 1560234, 5160234, 1650234, 6150234, 5610234, 6510234,\n       256134, 2056134,  526134, 5026134, 2506134, 5206134,  265134, 2065134,  625134, 6025134, 2605134, 6205134,\n       562134, 5062134,  652134, 6052134, 5602134, 6502134, 2560134, 5260134, 2650134, 6250134, 5620134, 6520134,\n      1256034, 2156034, 1526034, 5126034, 2516034, 5216034, 1265034, 2165034, 1625034, 6125034, 2615034, 6215034,\n      1562034, 5162034, 1652034, 6152034, 5612034, 6512034, 2561034, 5261034, 2651034, 6251034, 5621034, 6521034,\n       135624, 1035624,  315624, 3015624, 1305624, 3105624,  153624, 1053624,  513624, 5013624, 1503624, 5103624,\n       351624, 3051624,  531624, 5031624, 3501624, 5301624, 1350624, 3150624, 1530624, 5130624, 3510624, 5310624,\n       136524, 1036524,  316524, 3016524, 1306524, 3106524,  163524, 1063524,  613524, 6013524, 1603524, 6103524,\n       361524, 3061524,  631524, 6031524, 3601524, 6301524, 1360524, 3160524, 1630524, 6130524, 3610524, 6310524,\n       156324, 1056324,  516324, 5016324, 1506324, 5106324,  165324, 1065324,  615324, 6015324, 1605324, 6105324,\n       561324, 5061324,  651324, 6051324, 5601324, 6501324, 1560324, 5160324, 1650324, 6150324, 5610324, 6510324,\n       356124, 3056124,  536124, 5036124, 3506124, 5306124,  365124, 3065124,  635124, 6035124, 3605124, 6305124,\n       563124, 5063124,  653124, 6053124, 5603124, 6503124, 3560124, 5360124, 3650124, 6350124, 5630124, 6530124,\n      1356024, 3156024, 1536024, 5136024, 3516024, 5316024, 1365024, 3165024, 1635024, 6135024, 3615024, 6315024,\n      1563024, 5163024, 1653024, 6153024, 5613024, 6513024, 3561024, 5361024, 3651024, 6351024, 5631024, 6531024,\n       235614, 2035614,  325614, 3025614, 2305614, 3205614,  253614, 2053614,  523614, 5023614, 2503614, 5203614,\n       352614, 3052614,  532614, 5032614, 3502614, 5302614, 2350614, 3250614, 2530614, 5230614, 3520614, 5320614,\n       236514, 2036514,  326514, 3026514, 2306514, 3206514,  263514, 2063514,  623514, 6023514, 2603514, 6203514,\n       362514, 3062514,  632514, 6032514, 3602514, 6302514, 2360514, 3260514, 2630514, 6230514, 3620514, 6320514,\n       256314, 2056314,  526314, 5026314, 2506314, 5206314,  265314, 2065314,  625314, 6025314, 2605314, 6205314,\n       562314, 5062314,  652314, 6052314, 5602314, 6502314, 2560314, 5260314, 2650314, 6250314, 5620314, 6520314,\n       356214, 3056214,  536214, 5036214, 3506214, 5306214,  365214, 3065214,  635214, 6035214, 3605214, 6305214,\n       563214, 5063214,  653214, 6053214, 5603214, 6503214, 3560214, 5360214, 3650214, 6350214, 5630214, 6530214,\n      2356014, 3256014, 2536014, 5236014, 3526014, 5326014, 2365014, 3265014, 2635014, 6235014, 3625014, 6325014,\n      2563014, 5263014, 2653014, 6253014, 5623014, 6523014, 3562014, 5362014, 3652014, 6352014, 5632014, 6532014,\n      1235604, 2135604, 1325604, 3125604, 2315604, 3215604, 1253604, 2153604, 1523604, 5123604, 2513604, 5213604,\n      1352604, 3152604, 1532604, 5132604, 3512604, 5312604, 2351604, 3251604, 2531604, 5231604, 3521604, 5321604,\n      1236504, 2136504, 1326504, 3126504, 2316504, 3216504, 1263504, 2163504, 1623504, 6123504, 2613504, 6213504,\n      1362504, 3162504, 1632504, 6132504, 3612504, 6312504, 2361504, 3261504, 2631504, 6231504, 3621504, 6321504,\n      1256304, 2156304, 1526304, 5126304, 2516304, 5216304, 1265304, 2165304, 1625304, 6125304, 2615304, 6215304,\n      1562304, 5162304, 1652304, 6152304, 5612304, 6512304, 2561304, 5261304, 2651304, 6251304, 5621304, 6521304,\n      1356204, 3156204, 1536204, 5136204, 3516204, 5316204, 1365204, 3165204, 1635204, 6135204, 3615204, 6315204,\n      1563204, 5163204, 1653204, 6153204, 5613204, 6513204, 3561204, 5361204, 3651204, 6351204, 5631204, 6531204,\n      2356104, 3256104, 2536104, 5236104, 3526104, 5326104, 2365104, 3265104, 2635104, 6235104, 3625104, 6325104,\n      2563104, 5263104, 2653104, 6253104, 5623104, 6523104, 3562104, 5362104, 3652104, 6352104, 5632104, 6532104,\n       124563, 1024563,  214563, 2014563, 1204563, 2104563,  142563, 1042563,  412563, 4012563, 1402563, 4102563,\n       241563, 2041563,  421563, 4021563, 2401563, 4201563, 1240563, 2140563, 1420563, 4120563, 2410563, 4210563,\n       125463, 1025463,  215463, 2015463, 1205463, 2105463,  152463, 1052463,  512463, 5012463, 1502463, 5102463,\n       251463, 2051463,  521463, 5021463, 2501463, 5201463, 1250463, 2150463, 1520463, 5120463, 2510463, 5210463,\n       145263, 1045263,  415263, 4015263, 1405263, 4105263,  154263, 1054263,  514263, 5014263, 1504263, 5104263,\n       451263, 4051263,  541263, 5041263, 4501263, 5401263, 1450263, 4150263, 1540263, 5140263, 4510263, 5410263,\n       245163, 2045163,  425163, 4025163, 2405163, 4205163,  254163, 2054163,  524163, 5024163, 2504163, 5204163,\n       452163, 4052163,  542163, 5042163, 4502163, 5402163, 2450163, 4250163, 2540163, 5240163, 4520163, 5420163,\n      1245063, 2145063, 1425063, 4125063, 2415063, 4215063, 1254063, 2154063, 1524063, 5124063, 2514063, 5214063,\n      1452063, 4152063, 1542063, 5142063, 4512063, 5412063, 2451063, 4251063, 2541063, 5241063, 4521063, 5421063,\n       124653, 1024653,  214653, 2014653, 1204653, 2104653,  142653, 1042653,  412653, 4012653, 1402653, 4102653,\n       241653, 2041653,  421653, 4021653, 2401653, 4201653, 1240653, 2140653, 1420653, 4120653, 2410653, 4210653,\n       126453, 1026453,  216453, 2016453, 1206453, 2106453,  162453, 1062453,  612453, 6012453, 1602453, 6102453,\n       261453, 2061453,  621453, 6021453, 2601453, 6201453, 1260453, 2160453, 1620453, 6120453, 2610453, 6210453,\n       146253, 1046253,  416253, 4016253, 1406253, 4106253,  164253, 1064253,  614253, 6014253, 1604253, 6104253,\n       461253, 4061253,  641253, 6041253, 4601253, 6401253, 1460253, 4160253, 1640253, 6140253, 4610253, 6410253,\n       246153, 2046153,  426153, 4026153, 2406153, 4206153,  264153, 2064153,  624153, 6024153, 2604153, 6204153,\n       462153, 4062153,  642153, 6042153, 4602153, 6402153, 2460153, 4260153, 2640153, 6240153, 4620153, 6420153,\n      1246053, 2146053, 1426053, 4126053, 2416053, 4216053, 1264053, 2164053, 1624053, 6124053, 2614053, 6214053,\n      1462053, 4162053, 1642053, 6142053, 4612053, 6412053, 2461053, 4261053, 2641053, 6241053, 4621053, 6421053,\n       125643, 1025643,  215643, 2015643, 1205643, 2105643,  152643, 1052643,  512643, 5012643, 1502643, 5102643,\n       251643, 2051643,  521643, 5021643, 2501643, 5201643, 1250643, 2150643, 1520643, 5120643, 2510643, 5210643,\n       126543, 1026543,  216543, 2016543, 1206543, 2106543,  162543, 1062543,  612543, 6012543, 1602543, 6102543,\n       261543, 2061543,  621543, 6021543, 2601543, 6201543, 1260543, 2160543, 1620543, 6120543, 2610543, 6210543,\n       156243, 1056243,  516243, 5016243, 1506243, 5106243,  165243, 1065243,  615243, 6015243, 1605243, 6105243,\n       561243, 5061243,  651243, 6051243, 5601243, 6501243, 1560243, 5160243, 1650243, 6150243, 5610243, 6510243,\n       256143, 2056143,  526143, 5026143, 2506143, 5206143,  265143, 2065143,  625143, 6025143, 2605143, 6205143,\n       562143, 5062143,  652143, 6052143, 5602143, 6502143, 2560143, 5260143, 2650143, 6250143, 5620143, 6520143,\n      1256043, 2156043, 1526043, 5126043, 2516043, 5216043, 1265043, 2165043, 1625043, 6125043, 2615043, 6215043,\n      1562043, 5162043, 1652043, 6152043, 5612043, 6512043, 2561043, 5261043, 2651043, 6251043, 5621043, 6521043,\n       145623, 1045623,  415623, 4015623, 1405623, 4105623,  154623, 1054623,  514623, 5014623, 1504623, 5104623,\n       451623, 4051623,  541623, 5041623, 4501623, 5401623, 1450623, 4150623, 1540623, 5140623, 4510623, 5410623,\n       146523, 1046523,  416523, 4016523, 1406523, 4106523,  164523, 1064523,  614523, 6014523, 1604523, 6104523,\n       461523, 4061523,  641523, 6041523, 4601523, 6401523, 1460523, 4160523, 1640523, 6140523, 4610523, 6410523,\n       156423, 1056423,  516423, 5016423, 1506423, 5106423,  165423, 1065423,  615423, 6015423, 1605423, 6105423,\n       561423, 5061423,  651423, 6051423, 5601423, 6501423, 1560423, 5160423, 1650423, 6150423, 5610423, 6510423,\n       456123, 4056123,  546123, 5046123, 4506123, 5406123,  465123, 4065123,  645123, 6045123, 4605123, 6405123,\n       564123, 5064123,  654123, 6054123, 5604123, 6504123, 4560123, 5460123, 4650123, 6450123, 5640123, 6540123,\n      1456023, 4156023, 1546023, 5146023, 4516023, 5416023, 1465023, 4165023, 1645023, 6145023, 4615023, 6415023,\n      1564023, 5164023, 1654023, 6154023, 5614023, 6514023, 4561023, 5461023, 4651023, 6451023, 5641023, 6541023,\n       245613, 2045613,  425613, 4025613, 2405613, 4205613,  254613, 2054613,  524613, 5024613, 2504613, 5204613,\n       452613, 4052613,  542613, 5042613, 4502613, 5402613, 2450613, 4250613, 2540613, 5240613, 4520613, 5420613,\n       246513, 2046513,  426513, 4026513, 2406513, 4206513,  264513, 2064513,  624513, 6024513, 2604513, 6204513,\n       462513, 4062513,  642513, 6042513, 4602513, 6402513, 2460513, 4260513, 2640513, 6240513, 4620513, 6420513,\n       256413, 2056413,  526413, 5026413, 2506413, 5206413,  265413, 2065413,  625413, 6025413, 2605413, 6205413,\n       562413, 5062413,  652413, 6052413, 5602413, 6502413, 2560413, 5260413, 2650413, 6250413, 5620413, 6520413,\n       456213, 4056213,  546213, 5046213, 4506213, 5406213,  465213, 4065213,  645213, 6045213, 4605213, 6405213,\n       564213, 5064213,  654213, 6054213, 5604213, 6504213, 4560213, 5460213, 4650213, 6450213, 5640213, 6540213,\n      2456013, 4256013, 2546013, 5246013, 4526013, 5426013, 2465013, 4265013, 2645013, 6245013, 4625013, 6425013,\n      2564013, 5264013, 2654013, 6254013, 5624013, 6524013, 4562013, 5462013, 4652013, 6452013, 5642013, 6542013,\n      1245603, 2145603, 1425603, 4125603, 2415603, 4215603, 1254603, 2154603, 1524603, 5124603, 2514603, 5214603,\n      1452603, 4152603, 1542603, 5142603, 4512603, 5412603, 2451603, 4251603, 2541603, 5241603, 4521603, 5421603,\n      1246503, 2146503, 1426503, 4126503, 2416503, 4216503, 1264503, 2164503, 1624503, 6124503, 2614503, 6214503,\n      1462503, 4162503, 1642503, 6142503, 4612503, 6412503, 2461503, 4261503, 2641503, 6241503, 4621503, 6421503,\n      1256403, 2156403, 1526403, 5126403, 2516403, 5216403, 1265403, 2165403, 1625403, 6125403, 2615403, 6215403,\n      1562403, 5162403, 1652403, 6152403, 5612403, 6512403, 2561403, 5261403, 2651403, 6251403, 5621403, 6521403,\n      1456203, 4156203, 1546203, 5146203, 4516203, 5416203, 1465203, 4165203, 1645203, 6145203, 4615203, 6415203,\n      1564203, 5164203, 1654203, 6154203, 5614203, 6514203, 4561203, 5461203, 4651203, 6451203, 5641203, 6541203,\n      2456103, 4256103, 2546103, 5246103, 4526103, 5426103, 2465103, 4265103, 2645103, 6245103, 4625103, 6425103,\n      2564103, 5264103, 2654103, 6254103, 5624103, 6524103, 4562103, 5462103, 4652103, 6452103, 5642103, 6542103,\n       134562, 1034562,  314562, 3014562, 1304562, 3104562,  143562, 1043562,  413562, 4013562, 1403562, 4103562,\n       341562, 3041562,  431562, 4031562, 3401562, 4301562, 1340562, 3140562, 1430562, 4130562, 3410562, 4310562,\n       135462, 1035462,  315462, 3015462, 1305462, 3105462,  153462, 1053462,  513462, 5013462, 1503462, 5103462,\n       351462, 3051462,  531462, 5031462, 3501462, 5301462, 1350462, 3150462, 1530462, 5130462, 3510462, 5310462,\n       145362, 1045362,  415362, 4015362, 1405362, 4105362,  154362, 1054362,  514362, 5014362, 1504362, 5104362,\n       451362, 4051362,  541362, 5041362, 4501362, 5401362, 1450362, 4150362, 1540362, 5140362, 4510362, 5410362,\n       345162, 3045162,  435162, 4035162, 3405162, 4305162,  354162, 3054162,  534162, 5034162, 3504162, 5304162,\n       453162, 4053162,  543162, 5043162, 4503162, 5403162, 3450162, 4350162, 3540162, 5340162, 4530162, 5430162,\n      1345062, 3145062, 1435062, 4135062, 3415062, 4315062, 1354062, 3154062, 1534062, 5134062, 3514062, 5314062,\n      1453062, 4153062, 1543062, 5143062, 4513062, 5413062, 3451062, 4351062, 3541062, 5341062, 4531062, 5431062,\n       134652, 1034652,  314652, 3014652, 1304652, 3104652,  143652, 1043652,  413652, 4013652, 1403652, 4103652,\n       341652, 3041652,  431652, 4031652, 3401652, 4301652, 1340652, 3140652, 1430652, 4130652, 3410652, 4310652,\n       136452, 1036452,  316452, 3016452, 1306452, 3106452,  163452, 1063452,  613452, 6013452, 1603452, 6103452,\n       361452, 3061452,  631452, 6031452, 3601452, 6301452, 1360452, 3160452, 1630452, 6130452, 3610452, 6310452,\n       146352, 1046352,  416352, 4016352, 1406352, 4106352,  164352, 1064352,  614352, 6014352, 1604352, 6104352,\n       461352, 4061352,  641352, 6041352, 4601352, 6401352, 1460352, 4160352, 1640352, 6140352, 4610352, 6410352,\n       346152, 3046152,  436152, 4036152, 3406152, 4306152,  364152, 3064152,  634152, 6034152, 3604152, 6304152,\n       463152, 4063152,  643152, 6043152, 4603152, 6403152, 3460152, 4360152, 3640152, 6340152, 4630152, 6430152,\n      1346052, 3146052, 1436052, 4136052, 3416052, 4316052, 1364052, 3164052, 1634052, 6134052, 3614052, 6314052,\n      1463052, 4163052, 1643052, 6143052, 4613052, 6413052, 3461052, 4361052, 3641052, 6341052, 4631052, 6431052,\n       135642, 1035642,  315642, 3015642, 1305642, 3105642,  153642, 1053642,  513642, 5013642, 1503642, 5103642,\n       351642, 3051642,  531642, 5031642, 3501642, 5301642, 1350642, 3150642, 1530642, 5130642, 3510642, 5310642,\n       136542, 1036542,  316542, 3016542, 1306542, 3106542,  163542, 1063542,  613542, 6013542, 1603542, 6103542,\n       361542, 3061542,  631542, 6031542, 3601542, 6301542, 1360542, 3160542, 1630542, 6130542, 3610542, 6310542,\n       156342, 1056342,  516342, 5016342, 1506342, 5106342,  165342, 1065342,  615342, 6015342, 1605342, 6105342,\n       561342, 5061342,  651342, 6051342, 5601342, 6501342, 1560342, 5160342, 1650342, 6150342, 5610342, 6510342,\n       356142, 3056142,  536142, 5036142, 3506142, 5306142,  365142, 3065142,  635142, 6035142, 3605142, 6305142,\n       563142, 5063142,  653142, 6053142, 5603142, 6503142, 3560142, 5360142, 3650142, 6350142, 5630142, 6530142,\n      1356042, 3156042, 1536042, 5136042, 3516042, 5316042, 1365042, 3165042, 1635042, 6135042, 3615042, 6315042,\n      1563042, 5163042, 1653042, 6153042, 5613042, 6513042, 3561042, 5361042, 3651042, 6351042, 5631042, 6531042,\n       145632, 1045632,  415632, 4015632, 1405632, 4105632,  154632, 1054632,  514632, 5014632, 1504632, 5104632,\n       451632, 4051632,  541632, 5041632, 4501632, 5401632, 1450632, 4150632, 1540632, 5140632, 4510632, 5410632,\n       146532, 1046532,  416532, 4016532, 1406532, 4106532,  164532, 1064532,  614532, 6014532, 1604532, 6104532,\n       461532, 4061532,  641532, 6041532, 4601532, 6401532, 1460532, 4160532, 1640532, 6140532, 4610532, 6410532,\n       156432, 1056432,  516432, 5016432, 1506432, 5106432,  165432, 1065432,  615432, 6015432, 1605432, 6105432,\n       561432, 5061432,  651432, 6051432, 5601432, 6501432, 1560432, 5160432, 1650432, 6150432, 5610432, 6510432,\n       456132, 4056132,  546132, 5046132, 4506132, 5406132,  465132, 4065132,  645132, 6045132, 4605132, 6405132,\n       564132, 5064132,  654132, 6054132, 5604132, 6504132, 4560132, 5460132, 4650132, 6450132, 5640132, 6540132,\n      1456032, 4156032, 1546032, 5146032, 4516032, 5416032, 1465032, 4165032, 1645032, 6145032, 4615032, 6415032,\n      1564032, 5164032, 1654032, 6154032, 5614032, 6514032, 4561032, 5461032, 4651032, 6451032, 5641032, 6541032,\n       345612, 3045612,  435612, 4035612, 3405612, 4305612,  354612, 3054612,  534612, 5034612, 3504612, 5304612,\n       453612, 4053612,  543612, 5043612, 4503612, 5403612, 3450612, 4350612, 3540612, 5340612, 4530612, 5430612,\n       346512, 3046512,  436512, 4036512, 3406512, 4306512,  364512, 3064512,  634512, 6034512, 3604512, 6304512,\n       463512, 4063512,  643512, 6043512, 4603512, 6403512, 3460512, 4360512, 3640512, 6340512, 4630512, 6430512,\n       356412, 3056412,  536412, 5036412, 3506412, 5306412,  365412, 3065412,  635412, 6035412, 3605412, 6305412,\n       563412, 5063412,  653412, 6053412, 5603412, 6503412, 3560412, 5360412, 3650412, 6350412, 5630412, 6530412,\n       456312, 4056312,  546312, 5046312, 4506312, 5406312,  465312, 4065312,  645312, 6045312, 4605312, 6405312,\n       564312, 5064312,  654312, 6054312, 5604312, 6504312, 4560312, 5460312, 4650312, 6450312, 5640312, 6540312,\n      3456012, 4356012, 3546012, 5346012, 4536012, 5436012, 3465012, 4365012, 3645012, 6345012, 4635012, 6435012,\n      3564012, 5364012, 3654012, 6354012, 5634012, 6534012, 4563012, 5463012, 4653012, 6453012, 5643012, 6543012,\n      1345602, 3145602, 1435602, 4135602, 3415602, 4315602, 1354602, 3154602, 1534602, 5134602, 3514602, 5314602,\n      1453602, 4153602, 1543602, 5143602, 4513602, 5413602, 3451602, 4351602, 3541602, 5341602, 4531602, 5431602,\n      1346502, 3146502, 1436502, 4136502, 3416502, 4316502, 1364502, 3164502, 1634502, 6134502, 3614502, 6314502,\n      1463502, 4163502, 1643502, 6143502, 4613502, 6413502, 3461502, 4361502, 3641502, 6341502, 4631502, 6431502,\n      1356402, 3156402, 1536402, 5136402, 3516402, 5316402, 1365402, 3165402, 1635402, 6135402, 3615402, 6315402,\n      1563402, 5163402, 1653402, 6153402, 5613402, 6513402, 3561402, 5361402, 3651402, 6351402, 5631402, 6531402,\n      1456302, 4156302, 1546302, 5146302, 4516302, 5416302, 1465302, 4165302, 1645302, 6145302, 4615302, 6415302,\n      1564302, 5164302, 1654302, 6154302, 5614302, 6514302, 4561302, 5461302, 4651302, 6451302, 5641302, 6541302,\n      3456102, 4356102, 3546102, 5346102, 4536102, 5436102, 3465102, 4365102, 3645102, 6345102, 4635102, 6435102,\n      3564102, 5364102, 3654102, 6354102, 5634102, 6534102, 4563102, 5463102, 4653102, 6453102, 5643102, 6543102,\n       234561, 2034561,  324561, 3024561, 2304561, 3204561,  243561, 2043561,  423561, 4023561, 2403561, 4203561,\n       342561, 3042561,  432561, 4032561, 3402561, 4302561, 2340561, 3240561, 2430561, 4230561, 3420561, 4320561,\n       235461, 2035461,  325461, 3025461, 2305461, 3205461,  253461, 2053461,  523461, 5023461, 2503461, 5203461,\n       352461, 3052461,  532461, 5032461, 3502461, 5302461, 2350461, 3250461, 2530461, 5230461, 3520461, 5320461,\n       245361, 2045361,  425361, 4025361, 2405361, 4205361,  254361, 2054361,  524361, 5024361, 2504361, 5204361,\n       452361, 4052361,  542361, 5042361, 4502361, 5402361, 2450361, 4250361, 2540361, 5240361, 4520361, 5420361,\n       345261, 3045261,  435261, 4035261, 3405261, 4305261,  354261, 3054261,  534261, 5034261, 3504261, 5304261,\n       453261, 4053261,  543261, 5043261, 4503261, 5403261, 3450261, 4350261, 3540261, 5340261, 4530261, 5430261,\n      2345061, 3245061, 2435061, 4235061, 3425061, 4325061, 2354061, 3254061, 2534061, 5234061, 3524061, 5324061,\n      2453061, 4253061, 2543061, 5243061, 4523061, 5423061, 3452061, 4352061, 3542061, 5342061, 4532061, 5432061,\n       234651, 2034651,  324651, 3024651, 2304651, 3204651,  243651, 2043651,  423651, 4023651, 2403651, 4203651,\n       342651, 3042651,  432651, 4032651, 3402651, 4302651, 2340651, 3240651, 2430651, 4230651, 3420651, 4320651,\n       236451, 2036451,  326451, 3026451, 2306451, 3206451,  263451, 2063451,  623451, 6023451, 2603451, 6203451,\n       362451, 3062451,  632451, 6032451, 3602451, 6302451, 2360451, 3260451, 2630451, 6230451, 3620451, 6320451,\n       246351, 2046351,  426351, 4026351, 2406351, 4206351,  264351, 2064351,  624351, 6024351, 2604351, 6204351,\n       462351, 4062351,  642351, 6042351, 4602351, 6402351, 2460351, 4260351, 2640351, 6240351, 4620351, 6420351,\n       346251, 3046251,  436251, 4036251, 3406251, 4306251,  364251, 3064251,  634251, 6034251, 3604251, 6304251,\n       463251, 4063251,  643251, 6043251, 4603251, 6403251, 3460251, 4360251, 3640251, 6340251, 4630251, 6430251,\n      2346051, 3246051, 2436051, 4236051, 3426051, 4326051, 2364051, 3264051, 2634051, 6234051, 3624051, 6324051,\n      2463051, 4263051, 2643051, 6243051, 4623051, 6423051, 3462051, 4362051, 3642051, 6342051, 4632051, 6432051,\n       235641, 2035641,  325641, 3025641, 2305641, 3205641,  253641, 2053641,  523641, 5023641, 2503641, 5203641,\n       352641, 3052641,  532641, 5032641, 3502641, 5302641, 2350641, 3250641, 2530641, 5230641, 3520641, 5320641,\n       236541, 2036541,  326541, 3026541, 2306541, 3206541,  263541, 2063541,  623541, 6023541, 2603541, 6203541,\n       362541, 3062541,  632541, 6032541, 3602541, 6302541, 2360541, 3260541, 2630541, 6230541, 3620541, 6320541,\n       256341, 2056341,  526341, 5026341, 2506341, 5206341,  265341, 2065341,  625341, 6025341, 2605341, 6205341,\n       562341, 5062341,  652341, 6052341, 5602341, 6502341, 2560341, 5260341, 2650341, 6250341, 5620341, 6520341,\n       356241, 3056241,  536241, 5036241, 3506241, 5306241,  365241, 3065241,  635241, 6035241, 3605241, 6305241,\n       563241, 5063241,  653241, 6053241, 5603241, 6503241, 3560241, 5360241, 3650241, 6350241, 5630241, 6530241,\n      2356041, 3256041, 2536041, 5236041, 3526041, 5326041, 2365041, 3265041, 2635041, 6235041, 3625041, 6325041,\n      2563041, 5263041, 2653041, 6253041, 5623041, 6523041, 3562041, 5362041, 3652041, 6352041, 5632041, 6532041,\n       245631, 2045631,  425631, 4025631, 2405631, 4205631,  254631, 2054631,  524631, 5024631, 2504631, 5204631,\n       452631, 4052631,  542631, 5042631, 4502631, 5402631, 2450631, 4250631, 2540631, 5240631, 4520631, 5420631,\n       246531, 2046531,  426531, 4026531, 2406531, 4206531,  264531, 2064531,  624531, 6024531, 2604531, 6204531,\n       462531, 4062531,  642531, 6042531, 4602531, 6402531, 2460531, 4260531, 2640531, 6240531, 4620531, 6420531,\n       256431, 2056431,  526431, 5026431, 2506431, 5206431,  265431, 2065431,  625431, 6025431, 2605431, 6205431,\n       562431, 5062431,  652431, 6052431, 5602431, 6502431, 2560431, 5260431, 2650431, 6250431, 5620431, 6520431,\n       456231, 4056231,  546231, 5046231, 4506231, 5406231,  465231, 4065231,  645231, 6045231, 4605231, 6405231,\n       564231, 5064231,  654231, 6054231, 5604231, 6504231, 4560231, 5460231, 4650231, 6450231, 5640231, 6540231,\n      2456031, 4256031, 2546031, 5246031, 4526031, 5426031, 2465031, 4265031, 2645031, 6245031, 4625031, 6425031,\n      2564031, 5264031, 2654031, 6254031, 5624031, 6524031, 4562031, 5462031, 4652031, 6452031, 5642031, 6542031,\n       345621, 3045621,  435621, 4035621, 3405621, 4305621,  354621, 3054621,  534621, 5034621, 3504621, 5304621,\n       453621, 4053621,  543621, 5043621, 4503621, 5403621, 3450621, 4350621, 3540621, 5340621, 4530621, 5430621,\n       346521, 3046521,  436521, 4036521, 3406521, 4306521,  364521, 3064521,  634521, 6034521, 3604521, 6304521,\n       463521, 4063521,  643521, 6043521, 4603521, 6403521, 3460521, 4360521, 3640521, 6340521, 4630521, 6430521,\n       356421, 3056421,  536421, 5036421, 3506421, 5306421,  365421, 3065421,  635421, 6035421, 3605421, 6305421,\n       563421, 5063421,  653421, 6053421, 5603421, 6503421, 3560421, 5360421, 3650421, 6350421, 5630421, 6530421,\n       456321, 4056321,  546321, 5046321, 4506321, 5406321,  465321, 4065321,  645321, 6045321, 4605321, 6405321,\n       564321, 5064321,  654321, 6054321, 5604321, 6504321, 4560321, 5460321, 4650321, 6450321, 5640321, 6540321,\n      3456021, 4356021, 3546021, 5346021, 4536021, 5436021, 3465021, 4365021, 3645021, 6345021, 4635021, 6435021,\n      3564021, 5364021, 3654021, 6354021, 5634021, 6534021, 4563021, 5463021, 4653021, 6453021, 5643021, 6543021,\n      2345601, 3245601, 2435601, 4235601, 3425601, 4325601, 2354601, 3254601, 2534601, 5234601, 3524601, 5324601,\n      2453601, 4253601, 2543601, 5243601, 4523601, 5423601, 3452601, 4352601, 3542601, 5342601, 4532601, 5432601,\n      2346501, 3246501, 2436501, 4236501, 3426501, 4326501, 2364501, 3264501, 2634501, 6234501, 3624501, 6324501,\n      2463501, 4263501, 2643501, 6243501, 4623501, 6423501, 3462501, 4362501, 3642501, 6342501, 4632501, 6432501,\n      2356401, 3256401, 2536401, 5236401, 3526401, 5326401, 2365401, 3265401, 2635401, 6235401, 3625401, 6325401,\n      2563401, 5263401, 2653401, 6253401, 5623401, 6523401, 3562401, 5362401, 3652401, 6352401, 5632401, 6532401,\n      2456301, 4256301, 2546301, 5246301, 4526301, 5426301, 2465301, 4265301, 2645301, 6245301, 4625301, 6425301,\n      2564301, 5264301, 2654301, 6254301, 5624301, 6524301, 4562301, 5462301, 4652301, 6452301, 5642301, 6542301,\n      3456201, 4356201, 3546201, 5346201, 4536201, 5436201, 3465201, 4365201, 3645201, 6345201, 4635201, 6435201,\n      3564201, 5364201, 3654201, 6354201, 5634201, 6534201, 4563201, 5463201, 4653201, 6453201, 5643201, 6543201,\n      1234560, 2134560, 1324560, 3124560, 2314560, 3214560, 1243560, 2143560, 1423560, 4123560, 2413560, 4213560,\n      1342560, 3142560, 1432560, 4132560, 3412560, 4312560, 2341560, 3241560, 2431560, 4231560, 3421560, 4321560,\n      1235460, 2135460, 1325460, 3125460, 2315460, 3215460, 1253460, 2153460, 1523460, 5123460, 2513460, 5213460,\n      1352460, 3152460, 1532460, 5132460, 3512460, 5312460, 2351460, 3251460, 2531460, 5231460, 3521460, 5321460,\n      1245360, 2145360, 1425360, 4125360, 2415360, 4215360, 1254360, 2154360, 1524360, 5124360, 2514360, 5214360,\n      1452360, 4152360, 1542360, 5142360, 4512360, 5412360, 2451360, 4251360, 2541360, 5241360, 4521360, 5421360,\n      1345260, 3145260, 1435260, 4135260, 3415260, 4315260, 1354260, 3154260, 1534260, 5134260, 3514260, 5314260,\n      1453260, 4153260, 1543260, 5143260, 4513260, 5413260, 3451260, 4351260, 3541260, 5341260, 4531260, 5431260,\n      2345160, 3245160, 2435160, 4235160, 3425160, 4325160, 2354160, 3254160, 2534160, 5234160, 3524160, 5324160,\n      2453160, 4253160, 2543160, 5243160, 4523160, 5423160, 3452160, 4352160, 3542160, 5342160, 4532160, 5432160,\n      1234650, 2134650, 1324650, 3124650, 2314650, 3214650, 1243650, 2143650, 1423650, 4123650, 2413650, 4213650,\n      1342650, 3142650, 1432650, 4132650, 3412650, 4312650, 2341650, 3241650, 2431650, 4231650, 3421650, 4321650,\n      1236450, 2136450, 1326450, 3126450, 2316450, 3216450, 1263450, 2163450, 1623450, 6123450, 2613450, 6213450,\n      1362450, 3162450, 1632450, 6132450, 3612450, 6312450, 2361450, 3261450, 2631450, 6231450, 3621450, 6321450,\n      1246350, 2146350, 1426350, 4126350, 2416350, 4216350, 1264350, 2164350, 1624350, 6124350, 2614350, 6214350,\n      1462350, 4162350, 1642350, 6142350, 4612350, 6412350, 2461350, 4261350, 2641350, 6241350, 4621350, 6421350,\n      1346250, 3146250, 1436250, 4136250, 3416250, 4316250, 1364250, 3164250, 1634250, 6134250, 3614250, 6314250,\n      1463250, 4163250, 1643250, 6143250, 4613250, 6413250, 3461250, 4361250, 3641250, 6341250, 4631250, 6431250,\n      2346150, 3246150, 2436150, 4236150, 3426150, 4326150, 2364150, 3264150, 2634150, 6234150, 3624150, 6324150,\n      2463150, 4263150, 2643150, 6243150, 4623150, 6423150, 3462150, 4362150, 3642150, 6342150, 4632150, 6432150,\n      1235640, 2135640, 1325640, 3125640, 2315640, 3215640, 1253640, 2153640, 1523640, 5123640, 2513640, 5213640,\n      1352640, 3152640, 1532640, 5132640, 3512640, 5312640, 2351640, 3251640, 2531640, 5231640, 3521640, 5321640,\n      1236540, 2136540, 1326540, 3126540, 2316540, 3216540, 1263540, 2163540, 1623540, 6123540, 2613540, 6213540,\n      1362540, 3162540, 1632540, 6132540, 3612540, 6312540, 2361540, 3261540, 2631540, 6231540, 3621540, 6321540,\n      1256340, 2156340, 1526340, 5126340, 2516340, 5216340, 1265340, 2165340, 1625340, 6125340, 2615340, 6215340,\n      1562340, 5162340, 1652340, 6152340, 5612340, 6512340, 2561340, 5261340, 2651340, 6251340, 5621340, 6521340,\n      1356240, 3156240, 1536240, 5136240, 3516240, 5316240, 1365240, 3165240, 1635240, 6135240, 3615240, 6315240,\n      1563240, 5163240, 1653240, 6153240, 5613240, 6513240, 3561240, 5361240, 3651240, 6351240, 5631240, 6531240,\n      2356140, 3256140, 2536140, 5236140, 3526140, 5326140, 2365140, 3265140, 2635140, 6235140, 3625140, 6325140,\n      2563140, 5263140, 2653140, 6253140, 5623140, 6523140, 3562140, 5362140, 3652140, 6352140, 5632140, 6532140,\n      1245630, 2145630, 1425630, 4125630, 2415630, 4215630, 1254630, 2154630, 1524630, 5124630, 2514630, 5214630,\n      1452630, 4152630, 1542630, 5142630, 4512630, 5412630, 2451630, 4251630, 2541630, 5241630, 4521630, 5421630,\n      1246530, 2146530, 1426530, 4126530, 2416530, 4216530, 1264530, 2164530, 1624530, 6124530, 2614530, 6214530,\n      1462530, 4162530, 1642530, 6142530, 4612530, 6412530, 2461530, 4261530, 2641530, 6241530, 4621530, 6421530,\n      1256430, 2156430, 1526430, 5126430, 2516430, 5216430, 1265430, 2165430, 1625430, 6125430, 2615430, 6215430,\n      1562430, 5162430, 1652430, 6152430, 5612430, 6512430, 2561430, 5261430, 2651430, 6251430, 5621430, 6521430,\n      1456230, 4156230, 1546230, 5146230, 4516230, 5416230, 1465230, 4165230, 1645230, 6145230, 4615230, 6415230,\n      1564230, 5164230, 1654230, 6154230, 5614230, 6514230, 4561230, 5461230, 4651230, 6451230, 5641230, 6541230,\n      2456130, 4256130, 2546130, 5246130, 4526130, 5426130, 2465130, 4265130, 2645130, 6245130, 4625130, 6425130,\n      2564130, 5264130, 2654130, 6254130, 5624130, 6524130, 4562130, 5462130, 4652130, 6452130, 5642130, 6542130,\n      1345620, 3145620, 1435620, 4135620, 3415620, 4315620, 1354620, 3154620, 1534620, 5134620, 3514620, 5314620,\n      1453620, 4153620, 1543620, 5143620, 4513620, 5413620, 3451620, 4351620, 3541620, 5341620, 4531620, 5431620,\n      1346520, 3146520, 1436520, 4136520, 3416520, 4316520, 1364520, 3164520, 1634520, 6134520, 3614520, 6314520,\n      1463520, 4163520, 1643520, 6143520, 4613520, 6413520, 3461520, 4361520, 3641520, 6341520, 4631520, 6431520,\n      1356420, 3156420, 1536420, 5136420, 3516420, 5316420, 1365420, 3165420, 1635420, 6135420, 3615420, 6315420,\n      1563420, 5163420, 1653420, 6153420, 5613420, 6513420, 3561420, 5361420, 3651420, 6351420, 5631420, 6531420,\n      1456320, 4156320, 1546320, 5146320, 4516320, 5416320, 1465320, 4165320, 1645320, 6145320, 4615320, 6415320,\n      1564320, 5164320, 1654320, 6154320, 5614320, 6514320, 4561320, 5461320, 4651320, 6451320, 5641320, 6541320,\n      3456120, 4356120, 3546120, 5346120, 4536120, 5436120, 3465120, 4365120, 3645120, 6345120, 4635120, 6435120,\n      3564120, 5364120, 3654120, 6354120, 5634120, 6534120, 4563120, 5463120, 4653120, 6453120, 5643120, 6543120,\n      2345610, 3245610, 2435610, 4235610, 3425610, 4325610, 2354610, 3254610, 2534610, 5234610, 3524610, 5324610,\n      2453610, 4253610, 2543610, 5243610, 4523610, 5423610, 3452610, 4352610, 3542610, 5342610, 4532610, 5432610,\n      2346510, 3246510, 2436510, 4236510, 3426510, 4326510, 2364510, 3264510, 2634510, 6234510, 3624510, 6324510,\n      2463510, 4263510, 2643510, 6243510, 4623510, 6423510, 3462510, 4362510, 3642510, 6342510, 4632510, 6432510,\n      2356410, 3256410, 2536410, 5236410, 3526410, 5326410, 2365410, 3265410, 2635410, 6235410, 3625410, 6325410,\n      2563410, 5263410, 2653410, 6253410, 5623410, 6523410, 3562410, 5362410, 3652410, 6352410, 5632410, 6532410,\n      2456310, 4256310, 2546310, 5246310, 4526310, 5426310, 2465310, 4265310, 2645310, 6245310, 4625310, 6425310,\n      2564310, 5264310, 2654310, 6254310, 5624310, 6524310, 4562310, 5462310, 4652310, 6452310, 5642310, 6542310,\n      3456210, 4356210, 3546210, 5346210, 4536210, 5436210, 3465210, 4365210, 3645210, 6345210, 4635210, 6435210,\n      3564210, 5364210, 3654210, 6354210, 5634210, 6534210, 4563210, 5463210, 4653210, 6453210, 5643210, 6543210\n    };\n    std::map<uint64_t, int> expected;\n    for (std::size_t i = 0; i < 5040; i++)\n      expected[pre_expected[i]] = 0; // flags are 0, everything is symmetric here\n\n    VERIFY(isDynGroup(group));\n    VERIFY_IS_EQUAL(group.size(), 5040u);\n    VERIFY_IS_EQUAL(group.globalFlags(), 0);\n    group.apply<checkIdx, int>(identity7, 0, found, expected);\n    VERIFY_IS_EQUAL(found.size(), 5040u);\n  }\n}\n\nstatic void test_tensor_epsilon()\n{\n  SGroup<AntiSymmetry<0,1>, AntiSymmetry<1,2>> sym;\n  Tensor<int, 3> epsilon(3,3,3);\n\n  epsilon.setZero();\n  sym(epsilon, 0, 1, 2) = 1;\n\n  for (int i = 0; i < 3; i++) {\n    for (int j = 0; j < 3; j++) {\n      for (int k = 0; k < 3; k++) {\n        VERIFY_IS_EQUAL((epsilon(i,j,k)), (- (j - i) * (k - j) * (i - k) / 2) );\n      }\n    }\n  }\n}\n\nstatic void test_tensor_sym()\n{\n  SGroup<Symmetry<0,1>, Symmetry<2,3>> sym;\n  Tensor<int, 4> t(10,10,10,10);\n\n  t.setZero();\n\n  for (int l = 0; l < 10; l++) {\n    for (int k = l; k < 10; k++) {\n      for (int j = 0; j < 10; j++) {\n        for (int i = j; i < 10; i++) {\n          sym(t, i, j, k, l) = (i + j) * (k + l);\n        }\n      }\n    }\n  }\n\n  for (int l = 0; l < 10; l++) {\n    for (int k = 0; k < 10; k++) {\n      for (int j = 0; j < 10; j++) {\n        for (int i = 0; i < 10; i++) {\n          VERIFY_IS_EQUAL((t(i, j, k, l)), ((i + j) * (k + l)));\n        }\n      }\n    }\n  }\n\n}\n\nstatic void test_tensor_asym()\n{\n  SGroup<AntiSymmetry<0,1>, AntiSymmetry<2,3>> sym;\n  Tensor<int, 4> t(10,10,10,10);\n\n  t.setZero();\n\n  for (int l = 0; l < 10; l++) {\n    for (int k = l + 1; k < 10; k++) {\n      for (int j = 0; j < 10; j++) {\n        for (int i = j + 1; i < 10; i++) {\n          sym(t, i, j, k, l) = ((i * j) + (k * l));\n        }\n      }\n    }\n  }\n\n  for (int l = 0; l < 10; l++) {\n    for (int k = 0; k < 10; k++) {\n      for (int j = 0; j < 10; j++) {\n        for (int i = 0; i < 10; i++) {\n          if (i < j && k < l)\n            VERIFY_IS_EQUAL((t(i, j, k, l)), (((i * j) + (k * l))));\n          else if (i > j && k > l)\n            VERIFY_IS_EQUAL((t(i, j, k, l)), (((i * j) + (k * l))));\n          else if (i < j && k > l)\n            VERIFY_IS_EQUAL((t(i, j, k, l)), (- ((i * j) + (k * l))));\n          else if (i > j && k < l)\n            VERIFY_IS_EQUAL((t(i, j, k, l)), (- ((i * j) + (k * l))));\n          else\n            VERIFY_IS_EQUAL((t(i, j, k, l)), 0);\n        }\n      }\n    }\n  }\n}\n\nstatic void test_tensor_dynsym()\n{\n  DynamicSGroup sym;\n  sym.addSymmetry(0,1);\n  sym.addSymmetry(2,3);\n  Tensor<int, 4> t(10,10,10,10);\n\n  t.setZero();\n\n  for (int l = 0; l < 10; l++) {\n    for (int k = l; k < 10; k++) {\n      for (int j = 0; j < 10; j++) {\n        for (int i = j; i < 10; i++) {\n          sym(t, i, j, k, l) = (i + j) * (k + l);\n        }\n      }\n    }\n  }\n\n  for (int l = 0; l < 10; l++) {\n    for (int k = 0; k < 10; k++) {\n      for (int j = 0; j < 10; j++) {\n        for (int i = 0; i < 10; i++) {\n          VERIFY_IS_EQUAL((t(i, j, k, l)), ((i + j) * (k + l)));\n        }\n      }\n    }\n  }\n}\n\nstatic void test_tensor_randacc()\n{\n  SGroup<Symmetry<0,1>, Symmetry<2,3>> sym;\n  Tensor<int, 4> t(10,10,10,10);\n\n  t.setZero();\n\n  // set elements 1 million times, that way we access the\n  // entire matrix\n  for (int n = 0; n < 1000000; n++) {\n    int i = rand() % 10;\n    int j = rand() % 10;\n    int k = rand() % 10;\n    int l = rand() % 10;\n    // only access those indices in a given order\n    if (i < j)\n      std::swap(i, j);\n    if (k < l)\n      std::swap(k, l);\n    sym(t, i, j, k, l) = (i + j) * (k + l);\n  }\n\n  for (int l = 0; l < 10; l++) {\n    for (int k = 0; k < 10; k++) {\n      for (int j = 0; j < 10; j++) {\n        for (int i = 0; i < 10; i++) {\n          VERIFY_IS_EQUAL((t(i, j, k, l)), ((i + j) * (k + l)));\n        }\n      }\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_symmetry)\n{\n  CALL_SUBTEST(test_symgroups_static());\n  CALL_SUBTEST(test_symgroups_dynamic());\n  CALL_SUBTEST(test_symgroups_selection());\n  CALL_SUBTEST(test_tensor_epsilon());\n  CALL_SUBTEST(test_tensor_sym());\n  CALL_SUBTEST(test_tensor_asym());\n  CALL_SUBTEST(test_tensor_dynsym());\n  CALL_SUBTEST(test_tensor_randacc());\n}\n\n/*\n * kate: space-indent on; indent-width 2; mixedindent off; indent-mode cstyle;\n */\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_thread_local.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_USE_THREADS\n\n#include <iostream>\n#include <unordered_set>\n\n#include \"main.h\"\n#include <Eigen/CXX11/ThreadPool>\n\nstruct Counter {\n  Counter() = default;\n\n  void inc() {\n    // Check that mutation happens only in a thread that created this counter.\n    VERIFY_IS_EQUAL(std::this_thread::get_id(), created_by);\n    counter_value++;\n  }\n  int value() { return counter_value; }\n\n  std::thread::id created_by;\n  int counter_value = 0;\n};\n\nstruct InitCounter {\n  void operator()(Counter& counter) {\n    counter.created_by = std::this_thread::get_id();\n  }\n};\n\nvoid test_simple_thread_local() {\n  int num_threads = internal::random<int>(4, 32);\n  Eigen::ThreadPool thread_pool(num_threads);\n  Eigen::ThreadLocal<Counter, InitCounter> counter(num_threads, InitCounter());\n\n  int num_tasks = 3 * num_threads;\n  Eigen::Barrier barrier(num_tasks);\n\n  for (int i = 0; i < num_tasks; ++i) {\n    thread_pool.Schedule([&counter, &barrier]() {\n      Counter& local = counter.local();\n      local.inc();\n\n      std::this_thread::sleep_for(std::chrono::milliseconds(100));\n      barrier.Notify();\n    });\n  }\n\n  barrier.Wait();\n\n  counter.ForEach(\n      [](std::thread::id, Counter& cnt) { VERIFY_IS_EQUAL(cnt.value(), 3); });\n}\n\nvoid test_zero_sized_thread_local() {\n  Eigen::ThreadLocal<Counter, InitCounter> counter(0, InitCounter());\n\n  Counter& local = counter.local();\n  local.inc();\n\n  int total = 0;\n  counter.ForEach([&total](std::thread::id, Counter& cnt) {\n    total += cnt.value();\n    VERIFY_IS_EQUAL(cnt.value(), 1);\n  });\n\n  VERIFY_IS_EQUAL(total, 1);\n}\n\n// All thread local values fits into the lock-free storage.\nvoid test_large_number_of_tasks_no_spill() {\n  int num_threads = internal::random<int>(4, 32);\n  Eigen::ThreadPool thread_pool(num_threads);\n  Eigen::ThreadLocal<Counter, InitCounter> counter(num_threads, InitCounter());\n\n  int num_tasks = 10000;\n  Eigen::Barrier barrier(num_tasks);\n\n  for (int i = 0; i < num_tasks; ++i) {\n    thread_pool.Schedule([&counter, &barrier]() {\n      Counter& local = counter.local();\n      local.inc();\n      barrier.Notify();\n    });\n  }\n\n  barrier.Wait();\n\n  int total = 0;\n  std::unordered_set<std::thread::id> unique_threads;\n\n  counter.ForEach([&](std::thread::id id, Counter& cnt) {\n    total += cnt.value();\n    unique_threads.insert(id);\n  });\n\n  VERIFY_IS_EQUAL(total, num_tasks);\n  // Not all threads in a pool might be woken up to execute submitted tasks.\n  // Also thread_pool.Schedule() might use current thread if queue is full.\n  VERIFY_IS_EQUAL(\n      unique_threads.size() <= (static_cast<size_t>(num_threads + 1)), true);\n}\n\n// Lock free thread local storage is too small to fit all the unique threads,\n// and it spills to a map guarded by a mutex.\nvoid test_large_number_of_tasks_with_spill() {\n  int num_threads = internal::random<int>(4, 32);\n  Eigen::ThreadPool thread_pool(num_threads);\n  Eigen::ThreadLocal<Counter, InitCounter> counter(1, InitCounter());\n\n  int num_tasks = 10000;\n  Eigen::Barrier barrier(num_tasks);\n\n  for (int i = 0; i < num_tasks; ++i) {\n    thread_pool.Schedule([&counter, &barrier]() {\n      Counter& local = counter.local();\n      local.inc();\n      barrier.Notify();\n    });\n  }\n\n  barrier.Wait();\n\n  int total = 0;\n  std::unordered_set<std::thread::id> unique_threads;\n\n  counter.ForEach([&](std::thread::id id, Counter& cnt) {\n    total += cnt.value();\n    unique_threads.insert(id);\n  });\n\n  VERIFY_IS_EQUAL(total, num_tasks);\n  // Not all threads in a pool might be woken up to execute submitted tasks.\n  // Also thread_pool.Schedule() might use current thread if queue is full.\n  VERIFY_IS_EQUAL(\n      unique_threads.size() <= (static_cast<size_t>(num_threads + 1)), true);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_thread_local) {\n  CALL_SUBTEST(test_simple_thread_local());\n  CALL_SUBTEST(test_zero_sized_thread_local());\n  CALL_SUBTEST(test_large_number_of_tasks_no_spill());\n  CALL_SUBTEST(test_large_number_of_tasks_with_spill());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_thread_pool.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2014 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_USE_THREADS\n\n\n#include \"main.h\"\n#include <iostream>\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\nclass TestAllocator : public Allocator {\n public:\n  ~TestAllocator() EIGEN_OVERRIDE {}\n  EIGEN_DEVICE_FUNC void* allocate(size_t num_bytes) const EIGEN_OVERRIDE {\n    const_cast<TestAllocator*>(this)->alloc_count_++;\n    return internal::aligned_malloc(num_bytes);\n  }\n  EIGEN_DEVICE_FUNC void deallocate(void* buffer) const EIGEN_OVERRIDE {\n    const_cast<TestAllocator*>(this)->dealloc_count_++;\n    internal::aligned_free(buffer);\n  }\n\n  int alloc_count() const { return alloc_count_; }\n  int dealloc_count() const { return dealloc_count_; }\n\n private:\n  int alloc_count_ = 0;\n  int dealloc_count_ = 0;\n};\n\nvoid test_multithread_elementwise()\n{\n  Tensor<float, 3> in1(200, 30, 70);\n  Tensor<float, 3> in2(200, 30, 70);\n  Tensor<double, 3> out(200, 30, 70);\n\n  in1.setRandom();\n  in2.setRandom();\n\n  Eigen::ThreadPool tp(internal::random<int>(3, 11));\n  Eigen::ThreadPoolDevice thread_pool_device(&tp, internal::random<int>(3, 11));\n  out.device(thread_pool_device) = (in1 + in2 * 3.14f).cast<double>();\n\n  for (int i = 0; i < 200; ++i) {\n    for (int j = 0; j < 30; ++j) {\n      for (int k = 0; k < 70; ++k) {\n        VERIFY_IS_APPROX(out(i, j, k), static_cast<double>(in1(i, j, k) + in2(i, j, k) * 3.14f));\n      }\n    }\n  }\n}\n\nvoid test_async_multithread_elementwise()\n{\n  Tensor<float, 3> in1(200, 30, 70);\n  Tensor<float, 3> in2(200, 30, 70);\n  Tensor<double, 3> out(200, 30, 70);\n\n  in1.setRandom();\n  in2.setRandom();\n\n  Eigen::ThreadPool tp(internal::random<int>(3, 11));\n  Eigen::ThreadPoolDevice thread_pool_device(&tp, internal::random<int>(3, 11));\n\n  Eigen::Barrier b(1);\n  out.device(thread_pool_device, [&b]() { b.Notify(); }) = (in1 + in2 * 3.14f).cast<double>();\n  b.Wait();\n\n  for (int i = 0; i < 200; ++i) {\n    for (int j = 0; j < 30; ++j) {\n      for (int k = 0; k < 70; ++k) {\n        VERIFY_IS_APPROX(out(i, j, k), static_cast<double>(in1(i, j, k) + in2(i, j, k) * 3.14f));\n      }\n    }\n  }\n}\n\nvoid test_multithread_compound_assignment()\n{\n  Tensor<float, 3> in1(2,3,7);\n  Tensor<float, 3> in2(2,3,7);\n  Tensor<float, 3> out(2,3,7);\n\n  in1.setRandom();\n  in2.setRandom();\n\n  Eigen::ThreadPool tp(internal::random<int>(3, 11));\n  Eigen::ThreadPoolDevice thread_pool_device(&tp, internal::random<int>(3, 11));\n  out.device(thread_pool_device) = in1;\n  out.device(thread_pool_device) += in2 * 3.14f;\n\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 3; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        VERIFY_IS_APPROX(out(i,j,k), in1(i,j,k) + in2(i,j,k) * 3.14f);\n      }\n    }\n  }\n}\n\ntemplate<int DataLayout>\nvoid test_multithread_contraction()\n{\n  Tensor<float, 4, DataLayout> t_left(30, 50, 37, 31);\n  Tensor<float, 5, DataLayout> t_right(37, 31, 70, 2, 10);\n  Tensor<float, 5, DataLayout> t_result(30, 50, 70, 2, 10);\n\n  t_left.setRandom();\n  t_right.setRandom();\n\n  // this contraction should be equivalent to a single matrix multiplication\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n  Eigen::array<DimPair, 2> dims({{DimPair(2, 0), DimPair(3, 1)}});\n\n  typedef Map<Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 1500, 1147);\n  MapXf m_right(t_right.data(), 1147, 1400);\n  Matrix<float, Dynamic, Dynamic, DataLayout> m_result(1500, 1400);\n\n  Eigen::ThreadPool tp(4);\n  Eigen::ThreadPoolDevice thread_pool_device(&tp, 4);\n\n  // compute results by separate methods\n  t_result.device(thread_pool_device) = t_left.contract(t_right, dims);\n  m_result = m_left * m_right;\n\n for (ptrdiff_t i = 0; i < t_result.size(); i++) {\n    VERIFY(&t_result.data()[i] != &m_result.data()[i]);\n    if (fabsf(t_result(i) - m_result(i)) < 1e-4f) {\n      continue;\n    }\n    if (Eigen::internal::isApprox(t_result(i), m_result(i), 1e-4f)) {\n      continue;\n    }\n    std::cout << \"mismatch detected at index \" << i << \": \" << t_result(i)\n              << \" vs \" <<  m_result(i) << std::endl;\n    assert(false);\n  }\n}\n\ntemplate<int DataLayout>\nvoid test_contraction_corner_cases()\n{\n  Tensor<float, 2, DataLayout> t_left(32, 500);\n  Tensor<float, 2, DataLayout> t_right(32, 28*28);\n  Tensor<float, 2, DataLayout> t_result(500, 28*28);\n\n  t_left = (t_left.constant(-0.5f) + t_left.random()) * 2.0f;\n  t_right = (t_right.constant(-0.6f) + t_right.random()) * 2.0f;\n  t_result = t_result.constant(NAN);\n\n  // this contraction should be equivalent to a single matrix multiplication\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n  Eigen::array<DimPair, 1> dims{{DimPair(0, 0)}};\n\n  typedef Map<Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 32, 500);\n  MapXf m_right(t_right.data(), 32, 28*28);\n  Matrix<float, Dynamic, Dynamic, DataLayout> m_result(500, 28*28);\n\n  Eigen::ThreadPool tp(12);\n  Eigen::ThreadPoolDevice thread_pool_device(&tp, 12);\n\n  // compute results by separate methods\n  t_result.device(thread_pool_device) = t_left.contract(t_right, dims);\n  m_result = m_left.transpose() * m_right;\n\n  for (ptrdiff_t i = 0; i < t_result.size(); i++) {\n    assert(!(numext::isnan)(t_result.data()[i]));\n    if (fabsf(t_result.data()[i] - m_result.data()[i]) >= 1e-4f) {\n      std::cout << \"mismatch detected at index \" << i << \" : \" << t_result.data()[i] << \" vs \" <<  m_result.data()[i] << std::endl;\n      assert(false);\n    }\n  }\n\n  t_left.resize(32, 1);\n  t_left = (t_left.constant(-0.5f) + t_left.random()) * 2.0f;\n  t_result.resize (1, 28*28);\n  t_result = t_result.constant(NAN);\n  t_result.device(thread_pool_device) = t_left.contract(t_right, dims);\n  new(&m_left) MapXf(t_left.data(), 32, 1);\n  m_result = m_left.transpose() * m_right;\n  for (ptrdiff_t i = 0; i < t_result.size(); i++) {\n    assert(!(numext::isnan)(t_result.data()[i]));\n    if (fabsf(t_result.data()[i] - m_result.data()[i]) >= 1e-4f) {\n      std::cout << \"mismatch detected: \" << t_result.data()[i] << \" vs \" <<  m_result.data()[i] << std::endl;\n      assert(false);\n    }\n  }\n\n  t_left.resize(32, 500);\n  t_right.resize(32, 4);\n  t_left = (t_left.constant(-0.5f) + t_left.random()) * 2.0f;\n  t_right = (t_right.constant(-0.6f) + t_right.random()) * 2.0f;\n  t_result.resize (500, 4);\n  t_result = t_result.constant(NAN);\n  t_result.device(thread_pool_device) = t_left.contract(t_right, dims);\n  new(&m_left) MapXf(t_left.data(), 32, 500);\n  new(&m_right) MapXf(t_right.data(), 32, 4);\n  m_result = m_left.transpose() * m_right;\n  for (ptrdiff_t i = 0; i < t_result.size(); i++) {\n    assert(!(numext::isnan)(t_result.data()[i]));\n    if (fabsf(t_result.data()[i] - m_result.data()[i]) >= 1e-4f) {\n      std::cout << \"mismatch detected: \" << t_result.data()[i] << \" vs \" <<  m_result.data()[i] << std::endl;\n      assert(false);\n    }\n  }\n\n  t_left.resize(32, 1);\n  t_right.resize(32, 4);\n  t_left = (t_left.constant(-0.5f) + t_left.random()) * 2.0f;\n  t_right = (t_right.constant(-0.6f) + t_right.random()) * 2.0f;\n  t_result.resize (1, 4);\n  t_result = t_result.constant(NAN);\n  t_result.device(thread_pool_device) = t_left.contract(t_right, dims);\n  new(&m_left) MapXf(t_left.data(), 32, 1);\n  new(&m_right) MapXf(t_right.data(), 32, 4);\n  m_result = m_left.transpose() * m_right;\n  for (ptrdiff_t i = 0; i < t_result.size(); i++) {\n    assert(!(numext::isnan)(t_result.data()[i]));\n    if (fabsf(t_result.data()[i] - m_result.data()[i]) >= 1e-4f) {\n      std::cout << \"mismatch detected: \" << t_result.data()[i] << \" vs \" <<  m_result.data()[i] << std::endl;\n      assert(false);\n    }\n  }\n}\n\ntemplate<int DataLayout>\nvoid test_multithread_contraction_agrees_with_singlethread() {\n  int contract_size = internal::random<int>(1, 5000);\n\n  Tensor<float, 3, DataLayout> left(internal::random<int>(1, 80),\n                                    contract_size,\n                                    internal::random<int>(1, 100));\n\n  Tensor<float, 4, DataLayout> right(internal::random<int>(1, 25),\n                                     internal::random<int>(1, 37),\n                                     contract_size,\n                                     internal::random<int>(1, 51));\n\n  left.setRandom();\n  right.setRandom();\n\n  // add constants to shift values away from 0 for more precision\n  left += left.constant(1.5f);\n  right += right.constant(1.5f);\n\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n  Eigen::array<DimPair, 1> dims({{DimPair(1, 2)}});\n\n  Eigen::ThreadPool tp(internal::random<int>(2, 11));\n  Eigen::ThreadPoolDevice thread_pool_device(&tp, internal::random<int>(2, 11));\n\n  Tensor<float, 5, DataLayout> st_result;\n  st_result = left.contract(right, dims);\n\n  Tensor<float, 5, DataLayout> tp_result(st_result.dimensions());\n  tp_result.device(thread_pool_device) = left.contract(right, dims);\n\n  VERIFY(dimensions_match(st_result.dimensions(), tp_result.dimensions()));\n  for (ptrdiff_t i = 0; i < st_result.size(); i++) {\n    // if both of the values are very small, then do nothing (because the test will fail\n    // due to numerical precision issues when values are small)\n    if (numext::abs(st_result.data()[i] - tp_result.data()[i]) >= 1e-4f) {\n      VERIFY_IS_APPROX(st_result.data()[i], tp_result.data()[i]);\n    }\n  }\n}\n\n// Apply Sqrt to all output elements.\nstruct SqrtOutputKernel {\n  template <typename Index, typename Scalar>\n  EIGEN_ALWAYS_INLINE void operator()(\n      const internal::blas_data_mapper<Scalar, Index, ColMajor>& output_mapper,\n      const TensorContractionParams&, Index, Index, Index num_rows,\n      Index num_cols) const {\n    for (int i = 0; i < num_rows; ++i) {\n      for (int j = 0; j < num_cols; ++j) {\n        output_mapper(i, j) = std::sqrt(output_mapper(i, j));\n      }\n    }\n  }\n};\n\ntemplate <int DataLayout>\nstatic void test_multithread_contraction_with_output_kernel() {\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n\n  const int num_threads = internal::random<int>(2, 11);\n  ThreadPool threads(num_threads);\n  Eigen::ThreadPoolDevice device(&threads, num_threads);\n\n  Tensor<float, 4, DataLayout> t_left(30, 50, 8, 31);\n  Tensor<float, 5, DataLayout> t_right(8, 31, 7, 20, 10);\n  Tensor<float, 5, DataLayout> t_result(30, 50, 7, 20, 10);\n\n  t_left.setRandom();\n  t_right.setRandom();\n  // Put trash in mat4 to verify contraction clears output memory.\n  t_result.setRandom();\n\n  // Add a little offset so that the results won't be close to zero.\n  t_left += t_left.constant(1.0f);\n  t_right += t_right.constant(1.0f);\n\n  typedef Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 1500, 248);\n  MapXf m_right(t_right.data(), 248, 1400);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result(1500, 1400);\n\n  // this contraction should be equivalent to a single matrix multiplication\n  Eigen::array<DimPair, 2> dims({{DimPair(2, 0), DimPair(3, 1)}});\n\n  // compute results by separate methods\n  t_result.device(device) = t_left.contract(t_right, dims, SqrtOutputKernel());\n\n  m_result = m_left * m_right;\n\n  for (Index i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY(&t_result.data()[i] != &m_result.data()[i]);\n    VERIFY_IS_APPROX(t_result.data()[i], std::sqrt(m_result.data()[i]));\n  }\n}\n\ntemplate<int DataLayout>\nvoid test_async_multithread_contraction_agrees_with_singlethread()\n{\n  int contract_size = internal::random<int>(100, 500);\n\n  Tensor<float, 3, DataLayout> left(internal::random<int>(10, 40),\n                                    contract_size,\n                                    internal::random<int>(10, 40));\n\n  Tensor<float, 4, DataLayout> right(\n      internal::random<int>(1, 20), internal::random<int>(1, 20), contract_size,\n      internal::random<int>(1, 20));\n\n  left.setRandom();\n  right.setRandom();\n\n  // add constants to shift values away from 0 for more precision\n  left += left.constant(1.5f);\n  right += right.constant(1.5f);\n\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n  Eigen::array<DimPair, 1> dims({{DimPair(1, 2)}});\n\n  Eigen::ThreadPool tp(internal::random<int>(2, 11));\n  Eigen::ThreadPoolDevice thread_pool_device(&tp, internal::random<int>(8, 32));\n\n  Tensor<float, 5, DataLayout> st_result;\n  st_result = left.contract(right, dims);\n\n  Tensor<float, 5, DataLayout> tp_result(st_result.dimensions());\n\n  Eigen::Barrier barrier(1);\n  tp_result.device(thread_pool_device, [&barrier]() { barrier.Notify(); }) =\n      left.contract(right, dims);\n  barrier.Wait();\n\n  VERIFY(dimensions_match(st_result.dimensions(), tp_result.dimensions()));\n  for (ptrdiff_t i = 0; i < st_result.size(); i++) {\n    // if both of the values are very small, then do nothing (because the test\n    // will fail due to numerical precision issues when values are small)\n    if (numext::abs(st_result.data()[i] - tp_result.data()[i]) >= 1e-4f) {\n      VERIFY_IS_APPROX(st_result.data()[i], tp_result.data()[i]);\n    }\n  }\n}\n\n// We are triggering 'evalShardedByInnerDim' optimization.\ntemplate <int DataLayout>\nstatic void test_sharded_by_inner_dim_contraction()\n{\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n\n  const int num_threads = internal::random<int>(4, 16);\n  ThreadPool threads(num_threads);\n  Eigen::ThreadPoolDevice device(&threads, num_threads);\n\n  Tensor<float, 2, DataLayout> t_left(2, 10000);\n  Tensor<float, 2, DataLayout> t_right(10000, 10);\n  Tensor<float, 2, DataLayout> t_result(2, 10);\n\n  t_left.setRandom();\n  t_right.setRandom();\n  // Put trash in t_result to verify contraction clears output memory.\n  t_result.setRandom();\n\n  // Add a little offset so that the results won't be close to zero.\n  t_left += t_left.constant(1.0f);\n  t_right += t_right.constant(1.0f);\n\n  typedef Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 2, 10000);\n  MapXf m_right(t_right.data(), 10000, 10);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result(2, 10);\n\n  // this contraction should be equivalent to a single matrix multiplication\n  Eigen::array<DimPair, 1> dims({{DimPair(1, 0)}});\n\n  // compute results by separate methods\n  t_result.device(device) = t_left.contract(t_right, dims);\n  m_result = m_left * m_right;\n\n  for (Index i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY_IS_APPROX(t_result.data()[i], m_result.data()[i]);\n  }\n}\n\n// We are triggering 'evalShardedByInnerDim' optimization with output kernel.\ntemplate <int DataLayout>\nstatic void test_sharded_by_inner_dim_contraction_with_output_kernel()\n{\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n\n  const int num_threads = internal::random<int>(4, 16);\n  ThreadPool threads(num_threads);\n  Eigen::ThreadPoolDevice device(&threads, num_threads);\n\n  Tensor<float, 2, DataLayout> t_left(2, 10000);\n  Tensor<float, 2, DataLayout> t_right(10000, 10);\n  Tensor<float, 2, DataLayout> t_result(2, 10);\n\n  t_left.setRandom();\n  t_right.setRandom();\n  // Put trash in t_result to verify contraction clears output memory.\n  t_result.setRandom();\n\n  // Add a little offset so that the results won't be close to zero.\n  t_left += t_left.constant(1.0f);\n  t_right += t_right.constant(1.0f);\n\n  typedef Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 2, 10000);\n  MapXf m_right(t_right.data(), 10000, 10);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result(2, 10);\n\n  // this contraction should be equivalent to a single matrix multiplication\n  Eigen::array<DimPair, 1> dims({{DimPair(1, 0)}});\n\n  // compute results by separate methods\n  t_result.device(device) = t_left.contract(t_right, dims, SqrtOutputKernel());\n  m_result = m_left * m_right;\n\n  for (Index i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY_IS_APPROX(t_result.data()[i], std::sqrt(m_result.data()[i]));\n  }\n}\n\n// We are triggering 'evalShardedByInnerDim' optimization.\ntemplate <int DataLayout>\nstatic void test_async_sharded_by_inner_dim_contraction()\n{\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n\n  const int num_threads = internal::random<int>(4, 16);\n  ThreadPool threads(num_threads);\n  Eigen::ThreadPoolDevice device(&threads, num_threads);\n\n  Tensor<float, 2, DataLayout> t_left(2, 10000);\n  Tensor<float, 2, DataLayout> t_right(10000, 10);\n  Tensor<float, 2, DataLayout> t_result(2, 10);\n\n  t_left.setRandom();\n  t_right.setRandom();\n  // Put trash in t_result to verify contraction clears output memory.\n  t_result.setRandom();\n\n  // Add a little offset so that the results won't be close to zero.\n  t_left += t_left.constant(1.0f);\n  t_right += t_right.constant(1.0f);\n\n  typedef Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 2, 10000);\n  MapXf m_right(t_right.data(), 10000, 10);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result(2, 10);\n\n  // this contraction should be equivalent to a single matrix multiplication\n  Eigen::array<DimPair, 1> dims({{DimPair(1, 0)}});\n\n  // compute results by separate methods\n  Eigen::Barrier barrier(1);\n  t_result.device(device, [&barrier]() { barrier.Notify(); }) =\n      t_left.contract(t_right, dims);\n  barrier.Wait();\n\n  m_result = m_left * m_right;\n\n  for (Index i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY_IS_APPROX(t_result.data()[i], m_result.data()[i]);\n  }\n}\n\n// We are triggering 'evalShardedByInnerDim' optimization with output kernel.\ntemplate <int DataLayout>\nstatic void test_async_sharded_by_inner_dim_contraction_with_output_kernel()\n{\n  typedef Tensor<float, 1>::DimensionPair DimPair;\n\n  const int num_threads = internal::random<int>(4, 16);\n  ThreadPool threads(num_threads);\n  Eigen::ThreadPoolDevice device(&threads, num_threads);\n\n  Tensor<float, 2, DataLayout> t_left(2, 10000);\n  Tensor<float, 2, DataLayout> t_right(10000, 10);\n  Tensor<float, 2, DataLayout> t_result(2, 10);\n\n  t_left.setRandom();\n  t_right.setRandom();\n  // Put trash in t_result to verify contraction clears output memory.\n  t_result.setRandom();\n\n  // Add a little offset so that the results won't be close to zero.\n  t_left += t_left.constant(1.0f);\n  t_right += t_right.constant(1.0f);\n\n  typedef Map<Eigen::Matrix<float, Dynamic, Dynamic, DataLayout>> MapXf;\n  MapXf m_left(t_left.data(), 2, 10000);\n  MapXf m_right(t_right.data(), 10000, 10);\n  Eigen::Matrix<float, Dynamic, Dynamic, DataLayout> m_result(2, 10);\n\n  // this contraction should be equivalent to a single matrix multiplication\n  Eigen::array<DimPair, 1> dims({{DimPair(1, 0)}});\n\n  // compute results by separate methods\n  Eigen::Barrier barrier(1);\n  t_result.device(device, [&barrier]() { barrier.Notify(); }) =\n      t_left.contract(t_right, dims, SqrtOutputKernel());\n  barrier.Wait();\n  m_result = m_left * m_right;\n\n  for (Index i = 0; i < t_result.dimensions().TotalSize(); i++) {\n    VERIFY_IS_APPROX(t_result.data()[i], std::sqrt(m_result.data()[i]));\n  }\n}\n\ntemplate<int DataLayout>\nvoid test_full_contraction() {\n  int contract_size1 = internal::random<int>(1, 500);\n  int contract_size2 = internal::random<int>(1, 500);\n\n  Tensor<float, 2, DataLayout> left(contract_size1,\n                                    contract_size2);\n  Tensor<float, 2, DataLayout> right(contract_size1,\n                                    contract_size2);\n  left.setRandom();\n  right.setRandom();\n\n  // add constants to shift values away from 0 for more precision\n  left += left.constant(1.5f);\n  right += right.constant(1.5f);\n\n  typedef Tensor<float, 2>::DimensionPair DimPair;\n  Eigen::array<DimPair, 2> dims({{DimPair(0, 0), DimPair(1, 1)}});\n\n  Eigen::ThreadPool tp(internal::random<int>(2, 11));\n  Eigen::ThreadPoolDevice thread_pool_device(&tp, internal::random<int>(2, 11));\n\n  Tensor<float, 0, DataLayout> st_result;\n  st_result = left.contract(right, dims);\n\n  Tensor<float, 0, DataLayout> tp_result;\n  tp_result.device(thread_pool_device) = left.contract(right, dims);\n\n  VERIFY(dimensions_match(st_result.dimensions(), tp_result.dimensions()));\n  // if both of the values are very small, then do nothing (because the test will fail\n  // due to numerical precision issues when values are small)\n  if (numext::abs(st_result() - tp_result()) >= 1e-4f) {\n    VERIFY_IS_APPROX(st_result(), tp_result());\n  }\n}\n\ntemplate<int DataLayout>\nvoid test_multithreaded_reductions() {\n  const int num_threads = internal::random<int>(3, 11);\n  ThreadPool thread_pool(num_threads);\n  Eigen::ThreadPoolDevice thread_pool_device(&thread_pool, num_threads);\n\n  const int num_rows = internal::random<int>(13, 732);\n  const int num_cols = internal::random<int>(13, 732);\n  Tensor<float, 2, DataLayout> t1(num_rows, num_cols);\n  t1.setRandom();\n\n  Tensor<float, 0, DataLayout> full_redux;\n  full_redux = t1.sum();\n\n  Tensor<float, 0, DataLayout> full_redux_tp;\n  full_redux_tp.device(thread_pool_device) = t1.sum();\n\n  // Check that the single threaded and the multi threaded reductions return\n  // the same result.\n  VERIFY_IS_APPROX(full_redux(), full_redux_tp());\n}\n\n\nvoid test_memcpy() {\n\n  for (int i = 0; i < 5; ++i) {\n    const int num_threads = internal::random<int>(3, 11);\n    Eigen::ThreadPool tp(num_threads);\n    Eigen::ThreadPoolDevice thread_pool_device(&tp, num_threads);\n\n    const int size = internal::random<int>(13, 7632);\n    Tensor<float, 1> t1(size);\n    t1.setRandom();\n    std::vector<float> result(size);\n    thread_pool_device.memcpy(&result[0], t1.data(), size*sizeof(float));\n    for (int j = 0; j < size; j++) {\n      VERIFY_IS_EQUAL(t1(j), result[j]);\n    }\n  }\n}\n\n\nvoid test_multithread_random()\n{\n  Eigen::ThreadPool tp(2);\n  Eigen::ThreadPoolDevice device(&tp, 2);\n  Tensor<float, 1> t(1 << 20);\n  t.device(device) = t.random<Eigen::internal::NormalRandomGenerator<float>>();\n}\n\ntemplate<int DataLayout>\nvoid test_multithread_shuffle(Allocator* allocator)\n{\n  Tensor<float, 4, DataLayout> tensor(17,5,7,11);\n  tensor.setRandom();\n\n  const int num_threads = internal::random<int>(2, 11);\n  ThreadPool threads(num_threads);\n  Eigen::ThreadPoolDevice device(&threads, num_threads, allocator);\n\n  Tensor<float, 4, DataLayout> shuffle(7,5,11,17);\n  array<ptrdiff_t, 4> shuffles = {{2,1,3,0}};\n  shuffle.device(device) = tensor.shuffle(shuffles);\n\n  for (int i = 0; i < 17; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      for (int k = 0; k < 7; ++k) {\n        for (int l = 0; l < 11; ++l) {\n          VERIFY_IS_EQUAL(tensor(i,j,k,l), shuffle(k,j,l,i));\n        }\n      }\n    }\n  }\n}\n\nvoid test_threadpool_allocate(TestAllocator* allocator)\n{\n  const int num_threads = internal::random<int>(2, 11);\n  const int num_allocs = internal::random<int>(2, 11);\n  ThreadPool threads(num_threads);\n  Eigen::ThreadPoolDevice device(&threads, num_threads, allocator);\n\n  for (int a = 0; a < num_allocs; ++a) {\n    void* ptr = device.allocate(512);\n    device.deallocate(ptr);\n  }\n  VERIFY(allocator != NULL);\n  VERIFY_IS_EQUAL(allocator->alloc_count(), num_allocs);\n  VERIFY_IS_EQUAL(allocator->dealloc_count(), num_allocs);\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_thread_pool)\n{\n  CALL_SUBTEST_1(test_multithread_elementwise());\n  CALL_SUBTEST_1(test_async_multithread_elementwise());\n  CALL_SUBTEST_1(test_multithread_compound_assignment());\n\n  CALL_SUBTEST_2(test_multithread_contraction<ColMajor>());\n  CALL_SUBTEST_2(test_multithread_contraction<RowMajor>());\n\n  CALL_SUBTEST_3(test_multithread_contraction_agrees_with_singlethread<ColMajor>());\n  CALL_SUBTEST_3(test_multithread_contraction_agrees_with_singlethread<RowMajor>());\n  CALL_SUBTEST_3(test_multithread_contraction_with_output_kernel<ColMajor>());\n  CALL_SUBTEST_3(test_multithread_contraction_with_output_kernel<RowMajor>());\n\n  CALL_SUBTEST_4(test_async_multithread_contraction_agrees_with_singlethread<ColMajor>());\n  CALL_SUBTEST_4(test_async_multithread_contraction_agrees_with_singlethread<RowMajor>());\n\n  // Test EvalShardedByInnerDimContext parallelization strategy.\n  CALL_SUBTEST_5(test_sharded_by_inner_dim_contraction<ColMajor>());\n  CALL_SUBTEST_5(test_sharded_by_inner_dim_contraction<RowMajor>());\n  CALL_SUBTEST_5(test_sharded_by_inner_dim_contraction_with_output_kernel<ColMajor>());\n  CALL_SUBTEST_5(test_sharded_by_inner_dim_contraction_with_output_kernel<RowMajor>());\n\n  CALL_SUBTEST_6(test_async_sharded_by_inner_dim_contraction<ColMajor>());\n  CALL_SUBTEST_6(test_async_sharded_by_inner_dim_contraction<RowMajor>());\n  CALL_SUBTEST_6(test_async_sharded_by_inner_dim_contraction_with_output_kernel<ColMajor>());\n  CALL_SUBTEST_6(test_async_sharded_by_inner_dim_contraction_with_output_kernel<RowMajor>());\n\n  // Exercise various cases that have been problematic in the past.\n  CALL_SUBTEST_7(test_contraction_corner_cases<ColMajor>());\n  CALL_SUBTEST_7(test_contraction_corner_cases<RowMajor>());\n\n  CALL_SUBTEST_8(test_full_contraction<ColMajor>());\n  CALL_SUBTEST_8(test_full_contraction<RowMajor>());\n\n  CALL_SUBTEST_9(test_multithreaded_reductions<ColMajor>());\n  CALL_SUBTEST_9(test_multithreaded_reductions<RowMajor>());\n\n  CALL_SUBTEST_10(test_memcpy());\n  CALL_SUBTEST_10(test_multithread_random());\n\n  TestAllocator test_allocator;\n  CALL_SUBTEST_11(test_multithread_shuffle<ColMajor>(NULL));\n  CALL_SUBTEST_11(test_multithread_shuffle<RowMajor>(&test_allocator));\n  CALL_SUBTEST_11(test_threadpool_allocate(&test_allocator));\n\n  // Force CMake to split this test.\n  // EIGEN_SUFFIXES;1;2;3;4;5;6;7;8;9;10;11\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_trace.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2017 Gagan Goel <gagan.nith@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nusing Eigen::array;\n\ntemplate <int DataLayout>\nstatic void test_0D_trace() {\n  Tensor<float, 0, DataLayout> tensor;\n  tensor.setRandom();\n  array<ptrdiff_t, 0> dims;\n  Tensor<float, 0, DataLayout> result = tensor.trace(dims);\n  VERIFY_IS_EQUAL(result(), tensor());\n}\n\n\ntemplate <int DataLayout>\nstatic void test_all_dimensions_trace() {\n  Tensor<float, 3, DataLayout> tensor1(5, 5, 5);\n  tensor1.setRandom();\n  Tensor<float, 0, DataLayout> result1 = tensor1.trace();\n  VERIFY_IS_EQUAL(result1.rank(), 0);\n  float sum = 0.0f;\n  for (int i = 0; i < 5; ++i) {\n    sum += tensor1(i, i, i);\n  }\n  VERIFY_IS_EQUAL(result1(), sum);\n\n  Tensor<float, 5, DataLayout> tensor2(7, 7, 7, 7, 7);\n  tensor2.setRandom();\n  array<ptrdiff_t, 5> dims = { { 2, 1, 0, 3, 4 } };\n  Tensor<float, 0, DataLayout> result2 = tensor2.trace(dims);\n  VERIFY_IS_EQUAL(result2.rank(), 0);\n  sum = 0.0f;\n  for (int i = 0; i < 7; ++i) {\n    sum += tensor2(i, i, i, i, i);\n  }\n  VERIFY_IS_EQUAL(result2(), sum);\n}\n\n\ntemplate <int DataLayout>\nstatic void test_simple_trace() {\n  Tensor<float, 3, DataLayout> tensor1(3, 5, 3);\n  tensor1.setRandom();\n  array<ptrdiff_t, 2> dims1 = { { 0, 2 } };\n  Tensor<float, 1, DataLayout> result1 = tensor1.trace(dims1);\n  VERIFY_IS_EQUAL(result1.rank(), 1);\n  VERIFY_IS_EQUAL(result1.dimension(0), 5);\n  float sum = 0.0f;\n  for (int i = 0; i < 5; ++i) {\n    sum = 0.0f;\n    for (int j = 0; j < 3; ++j) {\n      sum += tensor1(j, i, j);\n    }\n    VERIFY_IS_EQUAL(result1(i), sum);\n  }\n\n  Tensor<float, 4, DataLayout> tensor2(5, 5, 7, 7);\n  tensor2.setRandom();\n  array<ptrdiff_t, 2> dims2 = { { 2, 3 } };\n  Tensor<float, 2, DataLayout> result2 = tensor2.trace(dims2);\n  VERIFY_IS_EQUAL(result2.rank(), 2);\n  VERIFY_IS_EQUAL(result2.dimension(0), 5);\n  VERIFY_IS_EQUAL(result2.dimension(1), 5);\n  for (int i = 0; i < 5; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      sum = 0.0f;\n      for (int k = 0; k < 7; ++k) {\n        sum += tensor2(i, j, k, k);\n      }\n      VERIFY_IS_EQUAL(result2(i, j), sum);\n    }\n  }\n\n  array<ptrdiff_t, 2> dims3 = { { 1, 0 } };\n  Tensor<float, 2, DataLayout> result3 = tensor2.trace(dims3);\n  VERIFY_IS_EQUAL(result3.rank(), 2);\n  VERIFY_IS_EQUAL(result3.dimension(0), 7);\n  VERIFY_IS_EQUAL(result3.dimension(1), 7);\n  for (int i = 0; i < 7; ++i) {\n    for (int j = 0; j < 7; ++j) {\n      sum = 0.0f;\n      for (int k = 0; k < 5; ++k) {\n        sum += tensor2(k, k, i, j);\n      }\n      VERIFY_IS_EQUAL(result3(i, j), sum);\n    }\n  }\n\n  Tensor<float, 5, DataLayout> tensor3(3, 7, 3, 7, 3);\n  tensor3.setRandom();\n  array<ptrdiff_t, 3> dims4 = { { 0, 2, 4 } };\n  Tensor<float, 2, DataLayout> result4 = tensor3.trace(dims4);\n  VERIFY_IS_EQUAL(result4.rank(), 2);\n  VERIFY_IS_EQUAL(result4.dimension(0), 7);\n  VERIFY_IS_EQUAL(result4.dimension(1), 7);\n  for (int i = 0; i < 7; ++i) {\n    for (int j = 0; j < 7; ++j) {\n      sum = 0.0f;\n      for (int k = 0; k < 3; ++k) {\n        sum += tensor3(k, i, k, j, k);\n      }\n      VERIFY_IS_EQUAL(result4(i, j), sum);\n    }\n  }\n\n  Tensor<float, 5, DataLayout> tensor4(3, 7, 4, 7, 5);\n  tensor4.setRandom();\n  array<ptrdiff_t, 2> dims5 = { { 1, 3 } };\n  Tensor<float, 3, DataLayout> result5 = tensor4.trace(dims5);\n  VERIFY_IS_EQUAL(result5.rank(), 3);\n  VERIFY_IS_EQUAL(result5.dimension(0), 3);\n  VERIFY_IS_EQUAL(result5.dimension(1), 4);\n  VERIFY_IS_EQUAL(result5.dimension(2), 5);\n  for (int i = 0; i < 3; ++i) {\n    for (int j = 0; j < 4; ++j) {\n      for (int k = 0; k < 5; ++k) {\n        sum = 0.0f;\n        for (int l = 0; l < 7; ++l) {\n          sum += tensor4(i, l, j, l, k);\n        }\n        VERIFY_IS_EQUAL(result5(i, j, k), sum);\n      }\n    }\n  }\n}\n\n\ntemplate<int DataLayout>\nstatic void test_trace_in_expr() {\n  Tensor<float, 4, DataLayout> tensor(2, 3, 5, 3);\n  tensor.setRandom();\n  array<ptrdiff_t, 2> dims = { { 1, 3 } };\n  Tensor<float, 2, DataLayout> result(2, 5);\n  result = result.constant(1.0f) - tensor.trace(dims);\n  VERIFY_IS_EQUAL(result.rank(), 2);\n  VERIFY_IS_EQUAL(result.dimension(0), 2);\n  VERIFY_IS_EQUAL(result.dimension(1), 5);\n  float sum = 0.0f;\n  for (int i = 0; i < 2; ++i) {\n    for (int j = 0; j < 5; ++j) {\n      sum = 0.0f;\n      for (int k = 0; k < 3; ++k) {\n        sum += tensor(i, k, j, k);\n      }\n      VERIFY_IS_EQUAL(result(i, j), 1.0f - sum);\n    }\n  }\n}\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_trace) {\n  CALL_SUBTEST(test_0D_trace<ColMajor>());\n  CALL_SUBTEST(test_0D_trace<RowMajor>());\n  CALL_SUBTEST(test_all_dimensions_trace<ColMajor>());\n  CALL_SUBTEST(test_all_dimensions_trace<RowMajor>());\n  CALL_SUBTEST(test_simple_trace<ColMajor>());\n  CALL_SUBTEST(test_simple_trace<RowMajor>());\n  CALL_SUBTEST(test_trace_in_expr<ColMajor>());\n  CALL_SUBTEST(test_trace_in_expr<RowMajor>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_uint128.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2015 Benoit Steiner <benoit.steiner.goog@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\n\n#if EIGEN_COMP_MSVC || !defined(__SIZEOF_INT128__)\n#define EIGEN_NO_INT128\n#else\ntypedef __uint128_t uint128_t;\n#endif\n\n// Only run the test on compilers that support 128bit integers natively\n#ifndef EIGEN_NO_INT128\n\nusing Eigen::internal::TensorUInt128;\nusing Eigen::internal::static_val;\n\nvoid VERIFY_EQUAL(TensorUInt128<uint64_t, uint64_t> actual, uint128_t expected) {\n  bool matchl = actual.lower() == static_cast<uint64_t>(expected);\n  bool matchh = actual.upper() == static_cast<uint64_t>(expected >> 64);\n  if (!matchl || !matchh) {\n    const char* testname = g_test_stack.back().c_str();\n    std::cerr << \"Test \" << testname << \" failed in \" << __FILE__\n              << \" (\" << __LINE__ << \")\"\n              << std::endl;\n    abort();\n  }\n}\n\n\nvoid test_add() {\n  uint64_t incr = internal::random<uint64_t>(1, 9999999999);\n  for (uint64_t i1 = 0; i1 < 100; ++i1) {\n    for (uint64_t i2 = 1; i2 < 100 * incr; i2 += incr) {\n      TensorUInt128<uint64_t, uint64_t> i(i1, i2);\n      uint128_t a = (static_cast<uint128_t>(i1) << 64) + static_cast<uint128_t>(i2);\n      for (uint64_t j1 = 0; j1 < 100; ++j1) {\n        for (uint64_t j2 = 1; j2 < 100 * incr; j2 += incr) {\n          TensorUInt128<uint64_t, uint64_t> j(j1, j2);\n          uint128_t b = (static_cast<uint128_t>(j1) << 64) + static_cast<uint128_t>(j2);\n          TensorUInt128<uint64_t, uint64_t> actual = i + j;\n          uint128_t expected = a + b;\n          VERIFY_EQUAL(actual, expected);\n        }\n      }\n    }\n  }\n}\n\nvoid test_sub() {\n  uint64_t incr = internal::random<uint64_t>(1, 9999999999);\n  for (uint64_t i1 = 0; i1 < 100; ++i1) {\n    for (uint64_t i2 = 1; i2 < 100 * incr; i2 += incr) {\n      TensorUInt128<uint64_t, uint64_t> i(i1, i2);\n      uint128_t a = (static_cast<uint128_t>(i1) << 64) + static_cast<uint128_t>(i2);\n      for (uint64_t j1 = 0; j1 < 100; ++j1) {\n        for (uint64_t j2 = 1; j2 < 100 * incr; j2 += incr) {\n          TensorUInt128<uint64_t, uint64_t> j(j1, j2);\n          uint128_t b = (static_cast<uint128_t>(j1) << 64) + static_cast<uint128_t>(j2);\n          TensorUInt128<uint64_t, uint64_t> actual = i - j;\n          uint128_t expected = a - b;\n          VERIFY_EQUAL(actual, expected);\n        }\n      }\n    }\n  }\n}\n\nvoid test_mul() {\n  uint64_t incr = internal::random<uint64_t>(1, 9999999999);\n  for (uint64_t i1 = 0; i1 < 100; ++i1) {\n    for (uint64_t i2 = 1; i2 < 100 * incr; i2 += incr) {\n      TensorUInt128<uint64_t, uint64_t> i(i1, i2);\n      uint128_t a = (static_cast<uint128_t>(i1) << 64) + static_cast<uint128_t>(i2);\n      for (uint64_t j1 = 0; j1 < 100; ++j1) {\n        for (uint64_t j2 = 1; j2 < 100 * incr; j2 += incr) {\n          TensorUInt128<uint64_t, uint64_t> j(j1, j2);\n          uint128_t b = (static_cast<uint128_t>(j1) << 64) + static_cast<uint128_t>(j2);\n          TensorUInt128<uint64_t, uint64_t> actual = i * j;\n          uint128_t expected = a * b;\n          VERIFY_EQUAL(actual, expected);\n        }\n      }\n    }\n  }\n}\n\nvoid test_div() {\n  uint64_t incr = internal::random<uint64_t>(1, 9999999999);\n  for (uint64_t i1 = 0; i1 < 100; ++i1) {\n    for (uint64_t i2 = 1; i2 < 100 * incr; i2 += incr) {\n      TensorUInt128<uint64_t, uint64_t> i(i1, i2);\n      uint128_t a = (static_cast<uint128_t>(i1) << 64) + static_cast<uint128_t>(i2);\n      for (uint64_t j1 = 0; j1 < 100; ++j1) {\n        for (uint64_t j2 = 1; j2 < 100 * incr; j2 += incr) {\n          TensorUInt128<uint64_t, uint64_t> j(j1, j2);\n          uint128_t b = (static_cast<uint128_t>(j1) << 64) + static_cast<uint128_t>(j2);\n          TensorUInt128<uint64_t, uint64_t> actual = i / j;\n          uint128_t expected = a / b;\n          VERIFY_EQUAL(actual, expected);\n        }\n      }\n    }\n  }\n}\n\nvoid test_misc1() {\n  uint64_t incr = internal::random<uint64_t>(1, 9999999999);\n  for (uint64_t i2 = 1; i2 < 100 * incr; i2 += incr) {\n    TensorUInt128<static_val<0>, uint64_t> i(0, i2);\n    uint128_t a = static_cast<uint128_t>(i2);\n    for (uint64_t j2 = 1; j2 < 100 * incr; j2 += incr) {\n      TensorUInt128<static_val<0>, uint64_t> j(0, j2);\n      uint128_t b = static_cast<uint128_t>(j2);\n      uint64_t actual = (i * j).upper();\n      uint64_t expected = (a * b) >> 64;\n      VERIFY_IS_EQUAL(actual, expected);\n    }\n  }\n}\n\nvoid test_misc2() {\n  int64_t incr = internal::random<int64_t>(1, 100);\n  for (int64_t log_div = 0; log_div < 63; ++log_div) {\n    for (int64_t divider = 1; divider <= 1000000 * incr; divider += incr) {\n      uint64_t expected = (static_cast<uint128_t>(1) << (64+log_div)) / static_cast<uint128_t>(divider) - (static_cast<uint128_t>(1) << 64) + 1;\n      uint64_t shift = 1ULL << log_div;\n\n      TensorUInt128<uint64_t, uint64_t> result = (TensorUInt128<uint64_t, static_val<0> >(shift, 0) / TensorUInt128<static_val<0>, uint64_t>(divider) - TensorUInt128<static_val<1>, static_val<0> >(1, 0) + TensorUInt128<static_val<0>, static_val<1> >(1));\n      uint64_t actual = static_cast<uint64_t>(result);\n      VERIFY_IS_EQUAL(actual, expected);\n    }\n  }\n}\n#endif\n\n\nEIGEN_DECLARE_TEST(cxx11_tensor_uint128)\n{\n#ifdef EIGEN_NO_INT128\n  // Skip the test on compilers that don't support 128bit integers natively\n  return;\n#else\n  CALL_SUBTEST_1(test_add());\n  CALL_SUBTEST_2(test_sub());\n  CALL_SUBTEST_3(test_mul());\n  CALL_SUBTEST_4(test_div());\n  CALL_SUBTEST_5(test_misc1());\n  CALL_SUBTEST_6(test_misc2());\n#endif\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_volume_patch.cpp",
    "content": "#include \"main.h\"\n\n#include <Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\n\nstatic void test_single_voxel_patch()\n{\n  Tensor<float, 5> tensor(4,2,3,5,7);\n  tensor.setRandom();\n  Tensor<float, 5, RowMajor> tensor_row_major = tensor.swap_layout();\n\n  Tensor<float, 6> single_voxel_patch;\n  single_voxel_patch = tensor.extract_volume_patches(1, 1, 1);\n  VERIFY_IS_EQUAL(single_voxel_patch.dimension(0), 4);\n  VERIFY_IS_EQUAL(single_voxel_patch.dimension(1), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch.dimension(3), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch.dimension(4), 2 * 3 * 5);\n  VERIFY_IS_EQUAL(single_voxel_patch.dimension(5), 7);\n\n  Tensor<float, 6, RowMajor> single_voxel_patch_row_major;\n  single_voxel_patch_row_major = tensor_row_major.extract_volume_patches(1, 1, 1);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(0), 7);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(1), 2 * 3 * 5);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(3), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(4), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(5), 4);\n\n  for (int i = 0; i < tensor.size(); ++i) {\n    VERIFY_IS_EQUAL(tensor.data()[i], single_voxel_patch.data()[i]);\n    VERIFY_IS_EQUAL(tensor_row_major.data()[i], single_voxel_patch_row_major.data()[i]);\n    VERIFY_IS_EQUAL(tensor.data()[i], tensor_row_major.data()[i]);\n  }\n}\n\n\nstatic void test_entire_volume_patch()\n{\n  const int depth = 4;\n  const int patch_z = 2;\n  const int patch_y = 3;\n  const int patch_x = 5;\n  const int batch = 7;\n\n  Tensor<float, 5> tensor(depth, patch_z, patch_y, patch_x, batch);\n  tensor.setRandom();\n  Tensor<float, 5, RowMajor> tensor_row_major = tensor.swap_layout();\n\n  Tensor<float, 6> entire_volume_patch;\n  entire_volume_patch = tensor.extract_volume_patches(patch_z, patch_y, patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch.dimension(0), depth);\n  VERIFY_IS_EQUAL(entire_volume_patch.dimension(1), patch_z);\n  VERIFY_IS_EQUAL(entire_volume_patch.dimension(2), patch_y);\n  VERIFY_IS_EQUAL(entire_volume_patch.dimension(3), patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch.dimension(4), patch_z * patch_y * patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch.dimension(5), batch);\n\n  Tensor<float, 6, RowMajor> entire_volume_patch_row_major;\n  entire_volume_patch_row_major = tensor_row_major.extract_volume_patches(patch_z, patch_y, patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(0), batch);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(1), patch_z * patch_y * patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(2), patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(3), patch_y);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(4), patch_z);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(5), depth);\n\n  const int dz = patch_z - 1;\n  const int dy = patch_y - 1;\n  const int dx = patch_x - 1;\n\n  const int forward_pad_z = dz / 2;\n  const int forward_pad_y = dy / 2;\n  const int forward_pad_x = dx / 2;\n\n  for (int pz = 0; pz < patch_z; pz++) {\n    for (int py = 0; py < patch_y; py++) {\n      for (int px = 0; px < patch_x; px++) {\n        const int patchId = pz + patch_z * (py + px * patch_y);\n        for (int z = 0; z < patch_z; z++) {\n          for (int y = 0; y < patch_y; y++) {\n            for (int x = 0; x < patch_x; x++) {\n              for (int b = 0; b < batch; b++) {\n                for (int d = 0; d < depth; d++) {\n                  float expected = 0.0f;\n                  float expected_row_major = 0.0f;\n                  const int eff_z = z - forward_pad_z + pz;\n                  const int eff_y = y - forward_pad_y + py;\n                  const int eff_x = x - forward_pad_x + px;\n                  if (eff_z >= 0 && eff_y >= 0 && eff_x >= 0 &&\n                      eff_z < patch_z && eff_y < patch_y && eff_x < patch_x) {\n                    expected = tensor(d, eff_z, eff_y, eff_x, b);\n                    expected_row_major = tensor_row_major(b, eff_x, eff_y, eff_z, d);\n                  }\n                  VERIFY_IS_EQUAL(entire_volume_patch(d, z, y, x, patchId, b), expected);\n                  VERIFY_IS_EQUAL(entire_volume_patch_row_major(b, patchId, x, y, z, d), expected_row_major);\n                }\n              }\n            }\n          }\n        }\n      }\n    }\n  }\n}\n\nEIGEN_DECLARE_TEST(cxx11_tensor_volume_patch)\n{\n  CALL_SUBTEST(test_single_voxel_patch());\n  CALL_SUBTEST(test_entire_volume_patch());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/cxx11_tensor_volume_patch_sycl.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016\n// Mehdi Goli    Codeplay Software Ltd.\n// Ralph Potter  Codeplay Software Ltd.\n// Luke Iwanski  Codeplay Software Ltd.\n// Contact: <eigen@codeplay.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#define EIGEN_TEST_NO_LONGDOUBLE\n#define EIGEN_TEST_NO_COMPLEX\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int64_t\n#define EIGEN_USE_SYCL\n\n#include \"main.h\"\n#include <unsupported/Eigen/CXX11/Tensor>\n\nusing Eigen::Tensor;\nstatic const int DataLayout = ColMajor;\n\ntemplate <typename DataType, typename IndexType>\nstatic void test_single_voxel_patch_sycl(const Eigen::SyclDevice& sycl_device)\n{\n\nIndexType sizeDim0 = 4;\nIndexType sizeDim1 = 2;\nIndexType sizeDim2 = 3;\nIndexType sizeDim3 = 5;\nIndexType sizeDim4 = 7;\narray<IndexType, 5> tensorColMajorRange = {{sizeDim0, sizeDim1, sizeDim2, sizeDim3, sizeDim4}};\narray<IndexType, 5> tensorRowMajorRange = {{sizeDim4, sizeDim3, sizeDim2, sizeDim1, sizeDim0}};\nTensor<DataType, 5, DataLayout,IndexType> tensor_col_major(tensorColMajorRange);\nTensor<DataType, 5, RowMajor,IndexType> tensor_row_major(tensorRowMajorRange);\ntensor_col_major.setRandom();\n\n\n  DataType* gpu_data_col_major  = static_cast<DataType*>(sycl_device.allocate(tensor_col_major.size()*sizeof(DataType)));\n  DataType* gpu_data_row_major  = static_cast<DataType*>(sycl_device.allocate(tensor_row_major.size()*sizeof(DataType)));\n  TensorMap<Tensor<DataType, 5, ColMajor, IndexType>> gpu_col_major(gpu_data_col_major, tensorColMajorRange);\n  TensorMap<Tensor<DataType, 5, RowMajor, IndexType>> gpu_row_major(gpu_data_row_major, tensorRowMajorRange);\n\n  sycl_device.memcpyHostToDevice(gpu_data_col_major, tensor_col_major.data(),(tensor_col_major.size())*sizeof(DataType));\n  gpu_row_major.device(sycl_device)=gpu_col_major.swap_layout();\n\n\n  // single volume patch: ColMajor\n  array<IndexType, 6> patchColMajorTensorRange={{sizeDim0,1, 1, 1, sizeDim1*sizeDim2*sizeDim3, sizeDim4}};\n  Tensor<DataType, 6, DataLayout,IndexType> single_voxel_patch_col_major(patchColMajorTensorRange);\n  size_t patchTensorBuffSize =single_voxel_patch_col_major.size()*sizeof(DataType);\n  DataType* gpu_data_single_voxel_patch_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 6, DataLayout,IndexType>> gpu_single_voxel_patch_col_major(gpu_data_single_voxel_patch_col_major, patchColMajorTensorRange);\n  gpu_single_voxel_patch_col_major.device(sycl_device)=gpu_col_major.extract_volume_patches(1, 1, 1);\n  sycl_device.memcpyDeviceToHost(single_voxel_patch_col_major.data(), gpu_data_single_voxel_patch_col_major, patchTensorBuffSize);\n\n\n  VERIFY_IS_EQUAL(single_voxel_patch_col_major.dimension(0), 4);\n  VERIFY_IS_EQUAL(single_voxel_patch_col_major.dimension(1), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch_col_major.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch_col_major.dimension(3), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch_col_major.dimension(4), 2 * 3 * 5);\n  VERIFY_IS_EQUAL(single_voxel_patch_col_major.dimension(5), 7);\n\n  array<IndexType, 6> patchRowMajorTensorRange={{sizeDim4, sizeDim1*sizeDim2*sizeDim3, 1, 1, 1, sizeDim0}};\n  Tensor<DataType, 6, RowMajor,IndexType> single_voxel_patch_row_major(patchRowMajorTensorRange);\n  patchTensorBuffSize =single_voxel_patch_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_single_voxel_patch_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 6, RowMajor,IndexType>> gpu_single_voxel_patch_row_major(gpu_data_single_voxel_patch_row_major, patchRowMajorTensorRange);\n  gpu_single_voxel_patch_row_major.device(sycl_device)=gpu_row_major.extract_volume_patches(1, 1, 1);\n  sycl_device.memcpyDeviceToHost(single_voxel_patch_row_major.data(), gpu_data_single_voxel_patch_row_major, patchTensorBuffSize);\n\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(0), 7);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(1), 2 * 3 * 5);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(2), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(3), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(4), 1);\n  VERIFY_IS_EQUAL(single_voxel_patch_row_major.dimension(5), 4);\n\n sycl_device.memcpyDeviceToHost(tensor_row_major.data(), gpu_data_row_major, (tensor_col_major.size())*sizeof(DataType));\n for (IndexType i = 0; i < tensor_col_major.size(); ++i) {\n       VERIFY_IS_EQUAL(tensor_col_major.data()[i], single_voxel_patch_col_major.data()[i]);\n    VERIFY_IS_EQUAL(tensor_row_major.data()[i], single_voxel_patch_row_major.data()[i]);\n    VERIFY_IS_EQUAL(tensor_col_major.data()[i], tensor_row_major.data()[i]);\n  }\n\n\n  sycl_device.deallocate(gpu_data_col_major);\n  sycl_device.deallocate(gpu_data_row_major);\n  sycl_device.deallocate(gpu_data_single_voxel_patch_col_major);\n  sycl_device.deallocate(gpu_data_single_voxel_patch_row_major);\n}\n\ntemplate <typename DataType, typename IndexType>\nstatic void test_entire_volume_patch_sycl(const Eigen::SyclDevice& sycl_device)\n{\n  const int depth = 4;\n  const int patch_z = 2;\n  const int patch_y = 3;\n  const int patch_x = 5;\n  const int batch = 7;\n\n  array<IndexType, 5> tensorColMajorRange = {{depth, patch_z, patch_y, patch_x, batch}};\n  array<IndexType, 5> tensorRowMajorRange = {{batch, patch_x, patch_y, patch_z, depth}};\n  Tensor<DataType, 5, DataLayout,IndexType> tensor_col_major(tensorColMajorRange);\n  Tensor<DataType, 5, RowMajor,IndexType> tensor_row_major(tensorRowMajorRange);\n  tensor_col_major.setRandom();\n\n\n    DataType* gpu_data_col_major  = static_cast<DataType*>(sycl_device.allocate(tensor_col_major.size()*sizeof(DataType)));\n    DataType* gpu_data_row_major  = static_cast<DataType*>(sycl_device.allocate(tensor_row_major.size()*sizeof(DataType)));\n    TensorMap<Tensor<DataType, 5, ColMajor, IndexType>> gpu_col_major(gpu_data_col_major, tensorColMajorRange);\n    TensorMap<Tensor<DataType, 5, RowMajor, IndexType>> gpu_row_major(gpu_data_row_major, tensorRowMajorRange);\n\n    sycl_device.memcpyHostToDevice(gpu_data_col_major, tensor_col_major.data(),(tensor_col_major.size())*sizeof(DataType));\n    gpu_row_major.device(sycl_device)=gpu_col_major.swap_layout();\n    sycl_device.memcpyDeviceToHost(tensor_row_major.data(), gpu_data_row_major, (tensor_col_major.size())*sizeof(DataType));\n\n\n    // single volume patch: ColMajor\n    array<IndexType, 6> patchColMajorTensorRange={{depth,patch_z, patch_y, patch_x, patch_z*patch_y*patch_x, batch}};\n    Tensor<DataType, 6, DataLayout,IndexType> entire_volume_patch_col_major(patchColMajorTensorRange);\n    size_t patchTensorBuffSize =entire_volume_patch_col_major.size()*sizeof(DataType);\n    DataType* gpu_data_entire_volume_patch_col_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n    TensorMap<Tensor<DataType, 6, DataLayout,IndexType>> gpu_entire_volume_patch_col_major(gpu_data_entire_volume_patch_col_major, patchColMajorTensorRange);\n    gpu_entire_volume_patch_col_major.device(sycl_device)=gpu_col_major.extract_volume_patches(patch_z, patch_y, patch_x);\n    sycl_device.memcpyDeviceToHost(entire_volume_patch_col_major.data(), gpu_data_entire_volume_patch_col_major, patchTensorBuffSize);\n\n\n//  Tensor<float, 5> tensor(depth, patch_z, patch_y, patch_x, batch);\n//  tensor.setRandom();\n//  Tensor<float, 5, RowMajor> tensor_row_major = tensor.swap_layout();\n\n  //Tensor<float, 6> entire_volume_patch;\n  //entire_volume_patch = tensor.extract_volume_patches(patch_z, patch_y, patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch_col_major.dimension(0), depth);\n  VERIFY_IS_EQUAL(entire_volume_patch_col_major.dimension(1), patch_z);\n  VERIFY_IS_EQUAL(entire_volume_patch_col_major.dimension(2), patch_y);\n  VERIFY_IS_EQUAL(entire_volume_patch_col_major.dimension(3), patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch_col_major.dimension(4), patch_z * patch_y * patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch_col_major.dimension(5), batch);\n\n//  Tensor<float, 6, RowMajor> entire_volume_patch_row_major;\n  //entire_volume_patch_row_major = tensor_row_major.extract_volume_patches(patch_z, patch_y, patch_x);\n\n  array<IndexType, 6> patchRowMajorTensorRange={{batch,patch_z*patch_y*patch_x, patch_x, patch_y, patch_z, depth}};\n  Tensor<DataType, 6, RowMajor,IndexType> entire_volume_patch_row_major(patchRowMajorTensorRange);\n  patchTensorBuffSize =entire_volume_patch_row_major.size()*sizeof(DataType);\n  DataType* gpu_data_entire_volume_patch_row_major  = static_cast<DataType*>(sycl_device.allocate(patchTensorBuffSize));\n  TensorMap<Tensor<DataType, 6, RowMajor,IndexType>> gpu_entire_volume_patch_row_major(gpu_data_entire_volume_patch_row_major, patchRowMajorTensorRange);\n  gpu_entire_volume_patch_row_major.device(sycl_device)=gpu_row_major.extract_volume_patches(patch_z, patch_y, patch_x);\n  sycl_device.memcpyDeviceToHost(entire_volume_patch_row_major.data(), gpu_data_entire_volume_patch_row_major, patchTensorBuffSize);\n\n\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(0), batch);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(1), patch_z * patch_y * patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(2), patch_x);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(3), patch_y);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(4), patch_z);\n  VERIFY_IS_EQUAL(entire_volume_patch_row_major.dimension(5), depth);\n\n  const int dz = patch_z - 1;\n  const int dy = patch_y - 1;\n  const int dx = patch_x - 1;\n\n  const int forward_pad_z = dz / 2;\n  const int forward_pad_y = dy / 2;\n  const int forward_pad_x = dx / 2;\n\n  for (int pz = 0; pz < patch_z; pz++) {\n    for (int py = 0; py < patch_y; py++) {\n      for (int px = 0; px < patch_x; px++) {\n        const int patchId = pz + patch_z * (py + px * patch_y);\n        for (int z = 0; z < patch_z; z++) {\n          for (int y = 0; y < patch_y; y++) {\n            for (int x = 0; x < patch_x; x++) {\n              for (int b = 0; b < batch; b++) {\n                for (int d = 0; d < depth; d++) {\n                  float expected = 0.0f;\n                  float expected_row_major = 0.0f;\n                  const int eff_z = z - forward_pad_z + pz;\n                  const int eff_y = y - forward_pad_y + py;\n                  const int eff_x = x - forward_pad_x + px;\n                  if (eff_z >= 0 && eff_y >= 0 && eff_x >= 0 &&\n                      eff_z < patch_z && eff_y < patch_y && eff_x < patch_x) {\n                    expected = tensor_col_major(d, eff_z, eff_y, eff_x, b);\n                    expected_row_major = tensor_row_major(b, eff_x, eff_y, eff_z, d);\n                  }\n                  VERIFY_IS_EQUAL(entire_volume_patch_col_major(d, z, y, x, patchId, b), expected);\n                  VERIFY_IS_EQUAL(entire_volume_patch_row_major(b, patchId, x, y, z, d), expected_row_major);\n                }\n              }\n            }\n          }\n        }\n      }\n    }\n  }\n  sycl_device.deallocate(gpu_data_col_major);\n  sycl_device.deallocate(gpu_data_row_major);\n  sycl_device.deallocate(gpu_data_entire_volume_patch_col_major);\n  sycl_device.deallocate(gpu_data_entire_volume_patch_row_major);\n}\n\n\n\ntemplate<typename DataType, typename dev_Selector> void sycl_tensor_volume_patch_test_per_device(dev_Selector s){\nQueueInterface queueInterface(s);\nauto sycl_device = Eigen::SyclDevice(&queueInterface);\nstd::cout << \"Running on \" << s.template get_info<cl::sycl::info::device::name>() << std::endl;\ntest_single_voxel_patch_sycl<DataType, int64_t>(sycl_device);\ntest_entire_volume_patch_sycl<DataType, int64_t>(sycl_device);\n}\nEIGEN_DECLARE_TEST(cxx11_tensor_volume_patch_sycl)\n{\nfor (const auto& device :Eigen::get_sycl_supported_devices()) {\n  CALL_SUBTEST(sycl_tensor_volume_patch_test_per_device<float>(device));\n}\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/dgmres.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n// Copyright (C) 2012 desire Nuentsa <desire.nuentsa_wakam@inria.fr\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"../../test/sparse_solver.h\"\n#include <unsupported/Eigen/IterativeSolvers>\n\ntemplate<typename T> void test_dgmres_T()\n{\n  DGMRES<SparseMatrix<T>, DiagonalPreconditioner<T> > dgmres_colmajor_diag;\n  DGMRES<SparseMatrix<T>, IdentityPreconditioner    > dgmres_colmajor_I;\n  DGMRES<SparseMatrix<T>, IncompleteLUT<T> >           dgmres_colmajor_ilut;\n  //GMRES<SparseMatrix<T>, SSORPreconditioner<T> >     dgmres_colmajor_ssor;\n\n  CALL_SUBTEST( check_sparse_square_solving(dgmres_colmajor_diag)  );\n//   CALL_SUBTEST( check_sparse_square_solving(dgmres_colmajor_I)     );\n  CALL_SUBTEST( check_sparse_square_solving(dgmres_colmajor_ilut)     );\n  //CALL_SUBTEST( check_sparse_square_solving(dgmres_colmajor_ssor)     );\n}\n\nEIGEN_DECLARE_TEST(dgmres)\n{\n  CALL_SUBTEST_1(test_dgmres_T<double>());\n  CALL_SUBTEST_2(test_dgmres_T<std::complex<double> >());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/forward_adolc.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <Eigen/Dense>\n\n#define NUMBER_DIRECTIONS 16\n#include <unsupported/Eigen/AdolcForward>\n\ntemplate<typename Vector>\nEIGEN_DONT_INLINE typename Vector::Scalar foo(const Vector& p)\n{\n  typedef typename Vector::Scalar Scalar;\n  return (p-Vector(Scalar(-1),Scalar(1.))).norm() + (p.array().sqrt().abs() * p.array().sin()).sum() + p.dot(p);\n}\n\ntemplate<typename _Scalar, int NX=Dynamic, int NY=Dynamic>\nstruct TestFunc1\n{\n  typedef _Scalar Scalar;\n  enum {\n    InputsAtCompileTime = NX,\n    ValuesAtCompileTime = NY\n  };\n  typedef Matrix<Scalar,InputsAtCompileTime,1> InputType;\n  typedef Matrix<Scalar,ValuesAtCompileTime,1> ValueType;\n  typedef Matrix<Scalar,ValuesAtCompileTime,InputsAtCompileTime> JacobianType;\n\n  int m_inputs, m_values;\n\n  TestFunc1() : m_inputs(InputsAtCompileTime), m_values(ValuesAtCompileTime) {}\n  TestFunc1(int inputs_, int values_) : m_inputs(inputs_), m_values(values_) {}\n\n  int inputs() const { return m_inputs; }\n  int values() const { return m_values; }\n\n  template<typename T>\n  void operator() (const Matrix<T,InputsAtCompileTime,1>& x, Matrix<T,ValuesAtCompileTime,1>* _v) const\n  {\n    Matrix<T,ValuesAtCompileTime,1>& v = *_v;\n\n    v[0] = 2 * x[0] * x[0] + x[0] * x[1];\n    v[1] = 3 * x[1] * x[0] + 0.5 * x[1] * x[1];\n    if(inputs()>2)\n    {\n      v[0] += 0.5 * x[2];\n      v[1] += x[2];\n    }\n    if(values()>2)\n    {\n      v[2] = 3 * x[1] * x[0] * x[0];\n    }\n    if (inputs()>2 && values()>2)\n      v[2] *= x[2];\n  }\n\n  void operator() (const InputType& x, ValueType* v, JacobianType* _j) const\n  {\n    (*this)(x, v);\n\n    if(_j)\n    {\n      JacobianType& j = *_j;\n\n      j(0,0) = 4 * x[0] + x[1];\n      j(1,0) = 3 * x[1];\n\n      j(0,1) = x[0];\n      j(1,1) = 3 * x[0] + 2 * 0.5 * x[1];\n\n      if (inputs()>2)\n      {\n        j(0,2) = 0.5;\n        j(1,2) = 1;\n      }\n      if(values()>2)\n      {\n        j(2,0) = 3 * x[1] * 2 * x[0];\n        j(2,1) = 3 * x[0] * x[0];\n      }\n      if (inputs()>2 && values()>2)\n      {\n        j(2,0) *= x[2];\n        j(2,1) *= x[2];\n\n        j(2,2) = 3 * x[1] * x[0] * x[0];\n        j(2,2) = 3 * x[1] * x[0] * x[0];\n      }\n    }\n  }\n};\n\ntemplate<typename Func> void adolc_forward_jacobian(const Func& f)\n{\n    typename Func::InputType x = Func::InputType::Random(f.inputs());\n    typename Func::ValueType y(f.values()), yref(f.values());\n    typename Func::JacobianType j(f.values(),f.inputs()), jref(f.values(),f.inputs());\n\n    jref.setZero();\n    yref.setZero();\n    f(x,&yref,&jref);\n//     std::cerr << y.transpose() << \"\\n\\n\";;\n//     std::cerr << j << \"\\n\\n\";;\n\n    j.setZero();\n    y.setZero();\n    AdolcForwardJacobian<Func> autoj(f);\n    autoj(x, &y, &j);\n//     std::cerr << y.transpose() << \"\\n\\n\";;\n//     std::cerr << j << \"\\n\\n\";;\n\n    VERIFY_IS_APPROX(y, yref);\n    VERIFY_IS_APPROX(j, jref);\n}\n\nEIGEN_DECLARE_TEST(forward_adolc)\n{\n  adtl::setNumDir(NUMBER_DIRECTIONS);\n\n  for(int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST(( adolc_forward_jacobian(TestFunc1<double,2,2>()) ));\n    CALL_SUBTEST(( adolc_forward_jacobian(TestFunc1<double,2,3>()) ));\n    CALL_SUBTEST(( adolc_forward_jacobian(TestFunc1<double,3,2>()) ));\n    CALL_SUBTEST(( adolc_forward_jacobian(TestFunc1<double,3,3>()) ));\n    CALL_SUBTEST(( adolc_forward_jacobian(TestFunc1<double>(3,3)) ));\n  }\n\n  {\n    // simple instantiation tests\n    Matrix<adtl::adouble,2,1> x;\n    foo(x);\n    Matrix<adtl::adouble,Dynamic,Dynamic> A(4,4);;\n    A.selfadjointView<Lower>().eigenvalues();\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/gmres.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n// Copyright (C) 2012 Kolja Brix <brix@igpm.rwth-aaachen.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"../../test/sparse_solver.h\"\n#include <Eigen/IterativeSolvers>\n\ntemplate<typename T> void test_gmres_T()\n{\n  GMRES<SparseMatrix<T>, DiagonalPreconditioner<T> > gmres_colmajor_diag;\n  GMRES<SparseMatrix<T>, IdentityPreconditioner    > gmres_colmajor_I;\n  GMRES<SparseMatrix<T>, IncompleteLUT<T> >           gmres_colmajor_ilut;\n  //GMRES<SparseMatrix<T>, SSORPreconditioner<T> >     gmres_colmajor_ssor;\n\n  CALL_SUBTEST( check_sparse_square_solving(gmres_colmajor_diag)  );\n//   CALL_SUBTEST( check_sparse_square_solving(gmres_colmajor_I)     );\n  CALL_SUBTEST( check_sparse_square_solving(gmres_colmajor_ilut)     );\n  //CALL_SUBTEST( check_sparse_square_solving(gmres_colmajor_ssor)     );\n}\n\nEIGEN_DECLARE_TEST(gmres)\n{\n  CALL_SUBTEST_1(test_gmres_T<double>());\n  CALL_SUBTEST_2(test_gmres_T<std::complex<double> >());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/idrs.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n// Copyright (C) 2012 Kolja Brix <brix@igpm.rwth-aaachen.de>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"../../test/sparse_solver.h\"\n#include <Eigen/IterativeSolvers>\n\ntemplate<typename T> void test_idrs_T()\n{\n  IDRS<SparseMatrix<T>, DiagonalPreconditioner<T> > idrs_colmajor_diag;\n  IDRS<SparseMatrix<T>, IncompleteLUT<T> >           idrs_colmajor_ilut;\n\n  CALL_SUBTEST( check_sparse_square_solving(idrs_colmajor_diag)  );\n  CALL_SUBTEST( check_sparse_square_solving(idrs_colmajor_ilut)     );\n}\n\nEIGEN_DECLARE_TEST(idrs)\n{\n  CALL_SUBTEST_1(test_idrs_T<double>());\n  CALL_SUBTEST_2(test_idrs_T<std::complex<double> >());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/kronecker_product.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Kolja Brix <brix@igpm.rwth-aachen.de>\n// Copyright (C) 2011 Andreas Platen <andiplaten@gmx.de>\n// Copyright (C) 2012 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n#ifdef EIGEN_TEST_PART_1\n\n#include \"sparse.h\"\n#include <Eigen/SparseExtra>\n#include <Eigen/KroneckerProduct>\n\ntemplate<typename MatrixType>\nvoid check_dimension(const MatrixType& ab, const int rows,  const int cols)\n{\n  VERIFY_IS_EQUAL(ab.rows(), rows);\n  VERIFY_IS_EQUAL(ab.cols(), cols);\n}\n\n\ntemplate<typename MatrixType>\nvoid check_kronecker_product(const MatrixType& ab)\n{\n  VERIFY_IS_EQUAL(ab.rows(), 6);\n  VERIFY_IS_EQUAL(ab.cols(), 6);\n  VERIFY_IS_EQUAL(ab.nonZeros(),  36);\n  VERIFY_IS_APPROX(ab.coeff(0,0), -0.4017367630386106);\n  VERIFY_IS_APPROX(ab.coeff(0,1),  0.1056863433932735);\n  VERIFY_IS_APPROX(ab.coeff(0,2), -0.7255206194554212);\n  VERIFY_IS_APPROX(ab.coeff(0,3),  0.1908653336744706);\n  VERIFY_IS_APPROX(ab.coeff(0,4),  0.350864567234111);\n  VERIFY_IS_APPROX(ab.coeff(0,5), -0.0923032108308013);\n  VERIFY_IS_APPROX(ab.coeff(1,0),  0.415417514804677);\n  VERIFY_IS_APPROX(ab.coeff(1,1), -0.2369227701722048);\n  VERIFY_IS_APPROX(ab.coeff(1,2),  0.7502275131458511);\n  VERIFY_IS_APPROX(ab.coeff(1,3), -0.4278731019742696);\n  VERIFY_IS_APPROX(ab.coeff(1,4), -0.3628129162264507);\n  VERIFY_IS_APPROX(ab.coeff(1,5),  0.2069210808481275);\n  VERIFY_IS_APPROX(ab.coeff(2,0),  0.05465890160863986);\n  VERIFY_IS_APPROX(ab.coeff(2,1), -0.2634092511419858);\n  VERIFY_IS_APPROX(ab.coeff(2,2),  0.09871180285793758);\n  VERIFY_IS_APPROX(ab.coeff(2,3), -0.4757066334017702);\n  VERIFY_IS_APPROX(ab.coeff(2,4), -0.04773740823058334);\n  VERIFY_IS_APPROX(ab.coeff(2,5),  0.2300535609645254);\n  VERIFY_IS_APPROX(ab.coeff(3,0), -0.8172945853260133);\n  VERIFY_IS_APPROX(ab.coeff(3,1),  0.2150086428359221);\n  VERIFY_IS_APPROX(ab.coeff(3,2),  0.5825113847292743);\n  VERIFY_IS_APPROX(ab.coeff(3,3), -0.1532433770097174);\n  VERIFY_IS_APPROX(ab.coeff(3,4), -0.329383387282399);\n  VERIFY_IS_APPROX(ab.coeff(3,5),  0.08665207912033064);\n  VERIFY_IS_APPROX(ab.coeff(4,0),  0.8451267514863225);\n  VERIFY_IS_APPROX(ab.coeff(4,1), -0.481996458918977);\n  VERIFY_IS_APPROX(ab.coeff(4,2), -0.6023482390791535);\n  VERIFY_IS_APPROX(ab.coeff(4,3),  0.3435339347164565);\n  VERIFY_IS_APPROX(ab.coeff(4,4),  0.3406002157428891);\n  VERIFY_IS_APPROX(ab.coeff(4,5), -0.1942526344200915);\n  VERIFY_IS_APPROX(ab.coeff(5,0),  0.1111982482925399);\n  VERIFY_IS_APPROX(ab.coeff(5,1), -0.5358806424754169);\n  VERIFY_IS_APPROX(ab.coeff(5,2), -0.07925446559335647);\n  VERIFY_IS_APPROX(ab.coeff(5,3),  0.3819388757769038);\n  VERIFY_IS_APPROX(ab.coeff(5,4),  0.04481475387219876);\n  VERIFY_IS_APPROX(ab.coeff(5,5), -0.2159688616158057);\n}\n\n\ntemplate<typename MatrixType>\nvoid check_sparse_kronecker_product(const MatrixType& ab)\n{\n  VERIFY_IS_EQUAL(ab.rows(), 12);\n  VERIFY_IS_EQUAL(ab.cols(), 10);\n  VERIFY_IS_EQUAL(ab.nonZeros(), 3*2);\n  VERIFY_IS_APPROX(ab.coeff(3,0), -0.04);\n  VERIFY_IS_APPROX(ab.coeff(5,1),  0.05);\n  VERIFY_IS_APPROX(ab.coeff(0,6), -0.08);\n  VERIFY_IS_APPROX(ab.coeff(2,7),  0.10);\n  VERIFY_IS_APPROX(ab.coeff(6,8),  0.12);\n  VERIFY_IS_APPROX(ab.coeff(8,9), -0.15);\n}\n\n\nEIGEN_DECLARE_TEST(kronecker_product)\n{\n  // DM = dense matrix; SM = sparse matrix\n\n  Matrix<double, 2, 3> DM_a;\n  SparseMatrix<double> SM_a(2,3);\n  SM_a.insert(0,0) = DM_a.coeffRef(0,0) = -0.4461540300782201;\n  SM_a.insert(0,1) = DM_a.coeffRef(0,1) = -0.8057364375283049;\n  SM_a.insert(0,2) = DM_a.coeffRef(0,2) =  0.3896572459516341;\n  SM_a.insert(1,0) = DM_a.coeffRef(1,0) = -0.9076572187376921;\n  SM_a.insert(1,1) = DM_a.coeffRef(1,1) =  0.6469156566545853;\n  SM_a.insert(1,2) = DM_a.coeffRef(1,2) = -0.3658010398782789;\n\n  MatrixXd             DM_b(3,2);\n  SparseMatrix<double> SM_b(3,2);\n  SM_b.insert(0,0) = DM_b.coeffRef(0,0) =  0.9004440976767099;\n  SM_b.insert(0,1) = DM_b.coeffRef(0,1) = -0.2368830858139832;\n  SM_b.insert(1,0) = DM_b.coeffRef(1,0) = -0.9311078389941825;\n  SM_b.insert(1,1) = DM_b.coeffRef(1,1) =  0.5310335762980047;\n  SM_b.insert(2,0) = DM_b.coeffRef(2,0) = -0.1225112806872035;\n  SM_b.insert(2,1) = DM_b.coeffRef(2,1) =  0.5903998022741264;\n\n  SparseMatrix<double,RowMajor> SM_row_a(SM_a), SM_row_b(SM_b);\n\n  // test DM_fixedSize = kroneckerProduct(DM_block,DM)\n  Matrix<double, 6, 6> DM_fix_ab = kroneckerProduct(DM_a.topLeftCorner<2,3>(),DM_b);\n\n  CALL_SUBTEST(check_kronecker_product(DM_fix_ab));\n  CALL_SUBTEST(check_kronecker_product(kroneckerProduct(DM_a.topLeftCorner<2,3>(),DM_b)));\n\n  for(int i=0;i<DM_fix_ab.rows();++i)\n    for(int j=0;j<DM_fix_ab.cols();++j)\n       VERIFY_IS_APPROX(kroneckerProduct(DM_a,DM_b).coeff(i,j), DM_fix_ab(i,j));\n\n  // test DM_block = kroneckerProduct(DM,DM)\n  MatrixXd DM_block_ab(10,15);\n  DM_block_ab.block<6,6>(2,5) = kroneckerProduct(DM_a,DM_b);\n  CALL_SUBTEST(check_kronecker_product(DM_block_ab.block<6,6>(2,5)));\n\n  // test DM = kroneckerProduct(DM,DM)\n  MatrixXd DM_ab = kroneckerProduct(DM_a,DM_b);\n  CALL_SUBTEST(check_kronecker_product(DM_ab));\n  CALL_SUBTEST(check_kronecker_product(kroneckerProduct(DM_a,DM_b)));\n\n  // test SM = kroneckerProduct(SM,DM)\n  SparseMatrix<double> SM_ab = kroneckerProduct(SM_a,DM_b);\n  CALL_SUBTEST(check_kronecker_product(SM_ab));\n  SparseMatrix<double,RowMajor> SM_ab2 = kroneckerProduct(SM_a,DM_b);\n  CALL_SUBTEST(check_kronecker_product(SM_ab2));\n  CALL_SUBTEST(check_kronecker_product(kroneckerProduct(SM_a,DM_b)));\n\n  // test SM = kroneckerProduct(DM,SM)\n  SM_ab.setZero();\n  SM_ab.insert(0,0)=37.0;\n  SM_ab = kroneckerProduct(DM_a,SM_b);\n  CALL_SUBTEST(check_kronecker_product(SM_ab));\n  SM_ab2.setZero();\n  SM_ab2.insert(0,0)=37.0;\n  SM_ab2 = kroneckerProduct(DM_a,SM_b);\n  CALL_SUBTEST(check_kronecker_product(SM_ab2));\n  CALL_SUBTEST(check_kronecker_product(kroneckerProduct(DM_a,SM_b)));\n\n  // test SM = kroneckerProduct(SM,SM)\n  SM_ab.resize(2,33);\n  SM_ab.insert(0,0)=37.0;\n  SM_ab = kroneckerProduct(SM_a,SM_b);\n  CALL_SUBTEST(check_kronecker_product(SM_ab));\n  SM_ab2.resize(5,11);\n  SM_ab2.insert(0,0)=37.0;\n  SM_ab2 = kroneckerProduct(SM_a,SM_b);\n  CALL_SUBTEST(check_kronecker_product(SM_ab2));\n  CALL_SUBTEST(check_kronecker_product(kroneckerProduct(SM_a,SM_b)));\n\n  // test SM = kroneckerProduct(SM,SM) with sparse pattern\n  SM_a.resize(4,5);\n  SM_b.resize(3,2);\n  SM_a.resizeNonZeros(0);\n  SM_b.resizeNonZeros(0);\n  SM_a.insert(1,0) = -0.1;\n  SM_a.insert(0,3) = -0.2;\n  SM_a.insert(2,4) =  0.3;\n  SM_a.finalize();\n\n  SM_b.insert(0,0) =  0.4;\n  SM_b.insert(2,1) = -0.5;\n  SM_b.finalize();\n  SM_ab.resize(1,1);\n  SM_ab.insert(0,0)=37.0;\n  SM_ab = kroneckerProduct(SM_a,SM_b);\n  CALL_SUBTEST(check_sparse_kronecker_product(SM_ab));\n\n  // test dimension of result of DM = kroneckerProduct(DM,DM)\n  MatrixXd DM_a2(2,1);\n  MatrixXd DM_b2(5,4);\n  MatrixXd DM_ab2 = kroneckerProduct(DM_a2,DM_b2);\n  CALL_SUBTEST(check_dimension(DM_ab2,2*5,1*4));\n  DM_a2.resize(10,9);\n  DM_b2.resize(4,8);\n  DM_ab2 = kroneckerProduct(DM_a2,DM_b2);\n  CALL_SUBTEST(check_dimension(DM_ab2,10*4,9*8));\n\n  for(int i = 0; i < g_repeat; i++)\n  {\n    double density = Eigen::internal::random<double>(0.01,0.5);\n    int ra = Eigen::internal::random<int>(1,50);\n    int ca = Eigen::internal::random<int>(1,50);\n    int rb = Eigen::internal::random<int>(1,50);\n    int cb = Eigen::internal::random<int>(1,50);\n    SparseMatrix<float,ColMajor> sA(ra,ca), sB(rb,cb), sC;\n    SparseMatrix<float,RowMajor> sC2;\n    MatrixXf dA(ra,ca), dB(rb,cb), dC;\n    initSparse(density, dA, sA);\n    initSparse(density, dB, sB);\n\n    sC = kroneckerProduct(sA,sB);\n    dC = kroneckerProduct(dA,dB);\n    VERIFY_IS_APPROX(MatrixXf(sC),dC);\n\n    sC = kroneckerProduct(sA.transpose(),sB);\n    dC = kroneckerProduct(dA.transpose(),dB);\n    VERIFY_IS_APPROX(MatrixXf(sC),dC);\n\n    sC = kroneckerProduct(sA.transpose(),sB.transpose());\n    dC = kroneckerProduct(dA.transpose(),dB.transpose());\n    VERIFY_IS_APPROX(MatrixXf(sC),dC);\n\n    sC = kroneckerProduct(sA,sB.transpose());\n    dC = kroneckerProduct(dA,dB.transpose());\n    VERIFY_IS_APPROX(MatrixXf(sC),dC);\n\n    sC2 = kroneckerProduct(sA,sB);\n    dC = kroneckerProduct(dA,dB);\n    VERIFY_IS_APPROX(MatrixXf(sC2),dC);\n\n    sC2 = kroneckerProduct(dA,sB);\n    dC = kroneckerProduct(dA,dB);\n    VERIFY_IS_APPROX(MatrixXf(sC2),dC);\n\n    sC2 = kroneckerProduct(sA,dB);\n    dC = kroneckerProduct(dA,dB);\n    VERIFY_IS_APPROX(MatrixXf(sC2),dC);\n\n    sC2 = kroneckerProduct(2*sA,sB);\n    dC = kroneckerProduct(2*dA,dB);\n    VERIFY_IS_APPROX(MatrixXf(sC2),dC);\n  }\n}\n\n#endif\n\n#ifdef EIGEN_TEST_PART_2\n\n// simply check that for a dense kronecker product, sparse module is not needed\n#include \"main.h\"\n#include <Eigen/KroneckerProduct>\n\nEIGEN_DECLARE_TEST(kronecker_product)\n{\n  MatrixXd a(2,2), b(3,3), c;\n  a.setRandom();\n  b.setRandom();\n  c = kroneckerProduct(a,b);\n  VERIFY_IS_APPROX(c.block(3,3,3,3), a(1,1)*b);\n}\n\n#endif\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/levenberg_marquardt.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Thomas Capricelli <orzel@freehackers.org>\n// Copyright (C) 2012 desire Nuentsa <desire.nuentsa_wakam@inria.fr\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n// FIXME: These tests all check for hard-coded values. Ideally, parameters and start estimates should be randomized.\n\n\n#include <stdio.h>\n\n#include \"main.h\"\n#include <unsupported/Eigen/LevenbergMarquardt>\n\n// This disables some useless Warnings on MSVC.\n// It is intended to be done for this test only.\n#include <Eigen/src/Core/util/DisableStupidWarnings.h>\n\nusing std::sqrt;\n\n// tolerance for chekcing number of iterations\n#define LM_EVAL_COUNT_TOL 4/3\n\nstruct lmder_functor : DenseFunctor<double>\n{\n    lmder_functor(void): DenseFunctor<double>(3,15) {}\n    int operator()(const VectorXd &x, VectorXd &fvec) const\n    {\n        double tmp1, tmp2, tmp3;\n        static const double y[15] = {1.4e-1, 1.8e-1, 2.2e-1, 2.5e-1, 2.9e-1, 3.2e-1, 3.5e-1,\n            3.9e-1, 3.7e-1, 5.8e-1, 7.3e-1, 9.6e-1, 1.34, 2.1, 4.39};\n\n        for (int i = 0; i < values(); i++)\n        {\n            tmp1 = i+1;\n            tmp2 = 16 - i - 1;\n            tmp3 = (i>=8)? tmp2 : tmp1;\n            fvec[i] = y[i] - (x[0] + tmp1/(x[1]*tmp2 + x[2]*tmp3));\n        }\n        return 0;\n    }\n\n    int df(const VectorXd &x, MatrixXd &fjac) const\n    {\n        double tmp1, tmp2, tmp3, tmp4;\n        for (int i = 0; i < values(); i++)\n        {\n            tmp1 = i+1;\n            tmp2 = 16 - i - 1;\n            tmp3 = (i>=8)? tmp2 : tmp1;\n            tmp4 = (x[1]*tmp2 + x[2]*tmp3); tmp4 = tmp4*tmp4;\n            fjac(i,0) = -1;\n            fjac(i,1) = tmp1*tmp2/tmp4;\n            fjac(i,2) = tmp1*tmp3/tmp4;\n        }\n        return 0;\n    }\n};\n\nvoid testLmder1()\n{\n  int n=3, info;\n\n  VectorXd x;\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, 1.);\n\n  // do the computation\n  lmder_functor functor;\n  LevenbergMarquardt<lmder_functor> lm(functor);\n  info = lm.lmder1(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 6);\n  VERIFY_IS_EQUAL(lm.njev(), 5);\n\n  // check norm\n  VERIFY_IS_APPROX(lm.fvec().blueNorm(), 0.09063596);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << 0.08241058, 1.133037, 2.343695;\n  VERIFY_IS_APPROX(x, x_ref);\n}\n\nvoid testLmder()\n{\n  const int m=15, n=3;\n  int info;\n  double fnorm, covfac;\n  VectorXd x;\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, 1.);\n\n  // do the computation\n  lmder_functor functor;\n  LevenbergMarquardt<lmder_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return values\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 6);\n  VERIFY_IS_EQUAL(lm.njev(), 5);\n\n  // check norm\n  fnorm = lm.fvec().blueNorm();\n  VERIFY_IS_APPROX(fnorm, 0.09063596);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << 0.08241058, 1.133037, 2.343695;\n  VERIFY_IS_APPROX(x, x_ref);\n\n  // check covariance\n  covfac = fnorm*fnorm/(m-n);\n  internal::covar(lm.matrixR(), lm.permutation().indices()); // TODO : move this as a function of lm\n\n  MatrixXd cov_ref(n,n);\n  cov_ref <<\n      0.0001531202,   0.002869941,  -0.002656662,\n      0.002869941,    0.09480935,   -0.09098995,\n      -0.002656662,   -0.09098995,    0.08778727;\n\n//  std::cout << fjac*covfac << std::endl;\n\n  MatrixXd cov;\n  cov =  covfac*lm.matrixR().topLeftCorner<n,n>();\n  VERIFY_IS_APPROX( cov, cov_ref);\n  // TODO: why isn't this allowed ? :\n  // VERIFY_IS_APPROX( covfac*fjac.topLeftCorner<n,n>() , cov_ref);\n}\n\nstruct lmdif_functor : DenseFunctor<double>\n{\n    lmdif_functor(void) : DenseFunctor<double>(3,15) {}\n    int operator()(const VectorXd &x, VectorXd &fvec) const\n    {\n        int i;\n        double tmp1,tmp2,tmp3;\n        static const double y[15]={1.4e-1,1.8e-1,2.2e-1,2.5e-1,2.9e-1,3.2e-1,3.5e-1,3.9e-1,\n            3.7e-1,5.8e-1,7.3e-1,9.6e-1,1.34e0,2.1e0,4.39e0};\n\n        assert(x.size()==3);\n        assert(fvec.size()==15);\n        for (i=0; i<15; i++)\n        {\n            tmp1 = i+1;\n            tmp2 = 15 - i;\n            tmp3 = tmp1;\n\n            if (i >= 8) tmp3 = tmp2;\n            fvec[i] = y[i] - (x[0] + tmp1/(x[1]*tmp2 + x[2]*tmp3));\n        }\n        return 0;\n    }\n};\n\nvoid testLmdif1()\n{\n  const int n=3;\n  int info;\n\n  VectorXd x(n), fvec(15);\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, 1.);\n\n  // do the computation\n  lmdif_functor functor;\n  DenseIndex nfev;\n  info = LevenbergMarquardt<lmdif_functor>::lmdif1(functor, x, &nfev);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n//   VERIFY_IS_EQUAL(nfev, 26);\n\n  // check norm\n  functor(x, fvec);\n  VERIFY_IS_APPROX(fvec.blueNorm(), 0.09063596);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << 0.0824106, 1.1330366, 2.3436947;\n  VERIFY_IS_APPROX(x, x_ref);\n\n}\n\nvoid testLmdif()\n{\n  const int m=15, n=3;\n  int info;\n  double fnorm, covfac;\n  VectorXd x(n);\n\n  /* the following starting values provide a rough fit. */\n  x.setConstant(n, 1.);\n\n  // do the computation\n  lmdif_functor functor;\n  NumericalDiff<lmdif_functor> numDiff(functor);\n  LevenbergMarquardt<NumericalDiff<lmdif_functor> > lm(numDiff);\n  info = lm.minimize(x);\n\n  // check return values\n  VERIFY_IS_EQUAL(info, 1);\n//   VERIFY_IS_EQUAL(lm.nfev(), 26);\n\n  // check norm\n  fnorm = lm.fvec().blueNorm();\n  VERIFY_IS_APPROX(fnorm, 0.09063596);\n\n  // check x\n  VectorXd x_ref(n);\n  x_ref << 0.08241058, 1.133037, 2.343695;\n  VERIFY_IS_APPROX(x, x_ref);\n\n  // check covariance\n  covfac = fnorm*fnorm/(m-n);\n  internal::covar(lm.matrixR(), lm.permutation().indices()); // TODO : move this as a function of lm\n\n  MatrixXd cov_ref(n,n);\n  cov_ref <<\n      0.0001531202,   0.002869942,  -0.002656662,\n      0.002869942,    0.09480937,   -0.09098997,\n      -0.002656662,   -0.09098997,    0.08778729;\n\n//  std::cout << fjac*covfac << std::endl;\n\n  MatrixXd cov;\n  cov =  covfac*lm.matrixR().topLeftCorner<n,n>();\n  VERIFY_IS_APPROX( cov, cov_ref);\n  // TODO: why isn't this allowed ? :\n  // VERIFY_IS_APPROX( covfac*fjac.topLeftCorner<n,n>() , cov_ref);\n}\n\nstruct chwirut2_functor : DenseFunctor<double>\n{\n    chwirut2_functor(void) : DenseFunctor<double>(3,54) {}\n    static const double m_x[54];\n    static const double m_y[54];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        int i;\n\n        assert(b.size()==3);\n        assert(fvec.size()==54);\n        for(i=0; i<54; i++) {\n            double x = m_x[i];\n            fvec[i] = exp(-b[0]*x)/(b[1]+b[2]*x) - m_y[i];\n        }\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==3);\n        assert(fjac.rows()==54);\n        assert(fjac.cols()==3);\n        for(int i=0; i<54; i++) {\n            double x = m_x[i];\n            double factor = 1./(b[1]+b[2]*x);\n            double e = exp(-b[0]*x);\n            fjac(i,0) = -x*e*factor;\n            fjac(i,1) = -e*factor*factor;\n            fjac(i,2) = -x*e*factor*factor;\n        }\n        return 0;\n    }\n};\nconst double chwirut2_functor::m_x[54] = { 0.500E0, 1.000E0, 1.750E0, 3.750E0, 5.750E0, 0.875E0, 2.250E0, 3.250E0, 5.250E0, 0.750E0, 1.750E0, 2.750E0, 4.750E0, 0.625E0, 1.250E0, 2.250E0, 4.250E0, .500E0, 3.000E0, .750E0, 3.000E0, 1.500E0, 6.000E0, 3.000E0, 6.000E0, 1.500E0, 3.000E0, .500E0, 2.000E0, 4.000E0, .750E0, 2.000E0, 5.000E0, .750E0, 2.250E0, 3.750E0, 5.750E0, 3.000E0, .750E0, 2.500E0, 4.000E0, .750E0, 2.500E0, 4.000E0, .750E0, 2.500E0, 4.000E0, .500E0, 6.000E0, 3.000E0, .500E0, 2.750E0, .500E0, 1.750E0};\nconst double chwirut2_functor::m_y[54] = { 92.9000E0 ,57.1000E0 ,31.0500E0 ,11.5875E0 ,8.0250E0 ,63.6000E0 ,21.4000E0 ,14.2500E0 ,8.4750E0 ,63.8000E0 ,26.8000E0 ,16.4625E0 ,7.1250E0 ,67.3000E0 ,41.0000E0 ,21.1500E0 ,8.1750E0 ,81.5000E0 ,13.1200E0 ,59.9000E0 ,14.6200E0 ,32.9000E0 ,5.4400E0 ,12.5600E0 ,5.4400E0 ,32.0000E0 ,13.9500E0 ,75.8000E0 ,20.0000E0 ,10.4200E0 ,59.5000E0 ,21.6700E0 ,8.5500E0 ,62.0000E0 ,20.2000E0 ,7.7600E0 ,3.7500E0 ,11.8100E0 ,54.7000E0 ,23.7000E0 ,11.5500E0 ,61.3000E0 ,17.7000E0 ,8.7400E0 ,59.2000E0 ,16.3000E0 ,8.6200E0 ,81.0000E0 ,4.8700E0 ,14.6200E0 ,81.7000E0 ,17.1700E0 ,81.3000E0 ,28.9000E0  };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/chwirut2.shtml\nvoid testNistChwirut2(void)\n{\n  const int n=3;\n  LevenbergMarquardtSpace::Status info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 0.1, 0.01, 0.02;\n  // do the computation\n  chwirut2_functor functor;\n  LevenbergMarquardt<chwirut2_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n//   VERIFY_IS_EQUAL(lm.nfev(), 10);\n  VERIFY_IS_EQUAL(lm.njev(), 8);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 5.1304802941E+02);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.6657666537E-01);\n  VERIFY_IS_APPROX(x[1], 5.1653291286E-03);\n  VERIFY_IS_APPROX(x[2], 1.2150007096E-02);\n\n  /*\n   * Second try\n   */\n  x<< 0.15, 0.008, 0.010;\n  // do the computation\n  lm.resetParameters();\n  lm.setFtol(1.E6*NumTraits<double>::epsilon());\n  lm.setXtol(1.E6*NumTraits<double>::epsilon());\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n//   VERIFY_IS_EQUAL(lm.nfev(), 7);\n  VERIFY_IS_EQUAL(lm.njev(), 6);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 5.1304802941E+02);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.6657666537E-01);\n  VERIFY_IS_APPROX(x[1], 5.1653291286E-03);\n  VERIFY_IS_APPROX(x[2], 1.2150007096E-02);\n}\n\n\nstruct misra1a_functor : DenseFunctor<double>\n{\n    misra1a_functor(void) : DenseFunctor<double>(2,14) {}\n    static const double m_x[14];\n    static const double m_y[14];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==2);\n        assert(fvec.size()==14);\n        for(int i=0; i<14; i++) {\n            fvec[i] = b[0]*(1.-exp(-b[1]*m_x[i])) - m_y[i] ;\n        }\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==2);\n        assert(fjac.rows()==14);\n        assert(fjac.cols()==2);\n        for(int i=0; i<14; i++) {\n            fjac(i,0) = (1.-exp(-b[1]*m_x[i]));\n            fjac(i,1) = (b[0]*m_x[i]*exp(-b[1]*m_x[i]));\n        }\n        return 0;\n    }\n};\nconst double misra1a_functor::m_x[14] = { 77.6E0, 114.9E0, 141.1E0, 190.8E0, 239.9E0, 289.0E0, 332.8E0, 378.4E0, 434.8E0, 477.3E0, 536.8E0, 593.1E0, 689.1E0, 760.0E0};\nconst double misra1a_functor::m_y[14] = { 10.07E0, 14.73E0, 17.94E0, 23.93E0, 29.61E0, 35.18E0, 40.02E0, 44.82E0, 50.76E0, 55.05E0, 61.01E0, 66.40E0, 75.47E0, 81.78E0};\n\n// http://www.itl.nist.gov/div898/strd/nls/data/misra1a.shtml\nvoid testNistMisra1a(void)\n{\n  const int n=2;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 500., 0.0001;\n  // do the computation\n  misra1a_functor functor;\n  LevenbergMarquardt<misra1a_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 19);\n  VERIFY_IS_EQUAL(lm.njev(), 15);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 1.2455138894E-01);\n  // check x\n  VERIFY_IS_APPROX(x[0], 2.3894212918E+02);\n  VERIFY_IS_APPROX(x[1], 5.5015643181E-04);\n\n  /*\n   * Second try\n   */\n  x<< 250., 0.0005;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 5);\n  VERIFY_IS_EQUAL(lm.njev(), 4);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 1.2455138894E-01);\n  // check x\n  VERIFY_IS_APPROX(x[0], 2.3894212918E+02);\n  VERIFY_IS_APPROX(x[1], 5.5015643181E-04);\n}\n\nstruct hahn1_functor : DenseFunctor<double>\n{\n    hahn1_functor(void) : DenseFunctor<double>(7,236) {}\n    static const double m_x[236];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        static const double m_y[236] = { .591E0 , 1.547E0 , 2.902E0 , 2.894E0 , 4.703E0 , 6.307E0 , 7.03E0  , 7.898E0 , 9.470E0 , 9.484E0 , 10.072E0 , 10.163E0 , 11.615E0 , 12.005E0 , 12.478E0 , 12.982E0 , 12.970E0 , 13.926E0 , 14.452E0 , 14.404E0 , 15.190E0 , 15.550E0 , 15.528E0 , 15.499E0 , 16.131E0 , 16.438E0 , 16.387E0 , 16.549E0 , 16.872E0 , 16.830E0 , 16.926E0 , 16.907E0 , 16.966E0 , 17.060E0 , 17.122E0 , 17.311E0 , 17.355E0 , 17.668E0 , 17.767E0 , 17.803E0 , 17.765E0 , 17.768E0 , 17.736E0 , 17.858E0 , 17.877E0 , 17.912E0 , 18.046E0 , 18.085E0 , 18.291E0 , 18.357E0 , 18.426E0 , 18.584E0 , 18.610E0 , 18.870E0 , 18.795E0 , 19.111E0 , .367E0 , .796E0 , 0.892E0 , 1.903E0 , 2.150E0 , 3.697E0 , 5.870E0 , 6.421E0 , 7.422E0 , 9.944E0 , 11.023E0 , 11.87E0  , 12.786E0 , 14.067E0 , 13.974E0 , 14.462E0 , 14.464E0 , 15.381E0 , 15.483E0 , 15.59E0  , 16.075E0 , 16.347E0 , 16.181E0 , 16.915E0 , 17.003E0 , 16.978E0 , 17.756E0 , 17.808E0 , 17.868E0 , 18.481E0 , 18.486E0 , 19.090E0 , 16.062E0 , 16.337E0 , 16.345E0 ,\n        16.388E0 , 17.159E0 , 17.116E0 , 17.164E0 , 17.123E0 , 17.979E0 , 17.974E0 , 18.007E0 , 17.993E0 , 18.523E0 , 18.669E0 , 18.617E0 , 19.371E0 , 19.330E0 , 0.080E0 , 0.248E0 , 1.089E0 , 1.418E0 , 2.278E0 , 3.624E0 , 4.574E0 , 5.556E0 , 7.267E0 , 7.695E0 , 9.136E0 , 9.959E0 , 9.957E0 , 11.600E0 , 13.138E0 , 13.564E0 , 13.871E0 , 13.994E0 , 14.947E0 , 15.473E0 , 15.379E0 , 15.455E0 , 15.908E0 , 16.114E0 , 17.071E0 , 17.135E0 , 17.282E0 , 17.368E0 , 17.483E0 , 17.764E0 , 18.185E0 , 18.271E0 , 18.236E0 , 18.237E0 , 18.523E0 , 18.627E0 , 18.665E0 , 19.086E0 , 0.214E0 , 0.943E0 , 1.429E0 , 2.241E0 , 2.951E0 , 3.782E0 , 4.757E0 , 5.602E0 , 7.169E0 , 8.920E0 , 10.055E0 , 12.035E0 , 12.861E0 , 13.436E0 , 14.167E0 , 14.755E0 , 15.168E0 , 15.651E0 , 15.746E0 , 16.216E0 , 16.445E0 , 16.965E0 , 17.121E0 , 17.206E0 , 17.250E0 , 17.339E0 , 17.793E0 , 18.123E0 , 18.49E0  , 18.566E0 , 18.645E0 , 18.706E0 , 18.924E0 , 19.1E0   , 0.375E0 , 0.471E0 , 1.504E0 , 2.204E0 , 2.813E0 , 4.765E0 , 9.835E0 , 10.040E0 , 11.946E0 , \n12.596E0 , \n13.303E0 , 13.922E0 , 14.440E0 , 14.951E0 , 15.627E0 , 15.639E0 , 15.814E0 , 16.315E0 , 16.334E0 , 16.430E0 , 16.423E0 , 17.024E0 , 17.009E0 , 17.165E0 , 17.134E0 , 17.349E0 , 17.576E0 , 17.848E0 , 18.090E0 , 18.276E0 , 18.404E0 , 18.519E0 , 19.133E0 , 19.074E0 , 19.239E0 , 19.280E0 , 19.101E0 , 19.398E0 , 19.252E0 , 19.89E0  , 20.007E0 , 19.929E0 , 19.268E0 , 19.324E0 , 20.049E0 , 20.107E0 , 20.062E0 , 20.065E0 , 19.286E0 , 19.972E0 , 20.088E0 , 20.743E0 , 20.83E0  , 20.935E0 , 21.035E0 , 20.93E0  , 21.074E0 , 21.085E0 , 20.935E0 };\n\n        //        int called=0; printf(\"call hahn1_functor with  iflag=%d, called=%d\\n\", iflag, called); if (iflag==1) called++;\n\n        assert(b.size()==7);\n        assert(fvec.size()==236);\n        for(int i=0; i<236; i++) {\n            double x=m_x[i], xx=x*x, xxx=xx*x;\n            fvec[i] = (b[0]+b[1]*x+b[2]*xx+b[3]*xxx) / (1.+b[4]*x+b[5]*xx+b[6]*xxx) - m_y[i];\n        }\n        return 0;\n    }\n\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==7);\n        assert(fjac.rows()==236);\n        assert(fjac.cols()==7);\n        for(int i=0; i<236; i++) {\n            double x=m_x[i], xx=x*x, xxx=xx*x;\n            double fact = 1./(1.+b[4]*x+b[5]*xx+b[6]*xxx);\n            fjac(i,0) = 1.*fact;\n            fjac(i,1) = x*fact;\n            fjac(i,2) = xx*fact;\n            fjac(i,3) = xxx*fact;\n            fact = - (b[0]+b[1]*x+b[2]*xx+b[3]*xxx) * fact * fact;\n            fjac(i,4) = x*fact;\n            fjac(i,5) = xx*fact;\n            fjac(i,6) = xxx*fact;\n        }\n        return 0;\n    }\n};\nconst double hahn1_functor::m_x[236] = { 24.41E0 , 34.82E0 , 44.09E0 , 45.07E0 , 54.98E0 , 65.51E0 , 70.53E0 , 75.70E0 , 89.57E0 , 91.14E0 , 96.40E0 , 97.19E0 , 114.26E0 , 120.25E0 , 127.08E0 , 133.55E0 , 133.61E0 , 158.67E0 , 172.74E0 , 171.31E0 , 202.14E0 , 220.55E0 , 221.05E0 , 221.39E0 , 250.99E0 , 268.99E0 , 271.80E0 , 271.97E0 , 321.31E0 , 321.69E0 , 330.14E0 , 333.03E0 , 333.47E0 , 340.77E0 , 345.65E0 , 373.11E0 , 373.79E0 , 411.82E0 , 419.51E0 , 421.59E0 , 422.02E0 , 422.47E0 , 422.61E0 , 441.75E0 , 447.41E0 , 448.7E0  , 472.89E0 , 476.69E0 , 522.47E0 , 522.62E0 , 524.43E0 , 546.75E0 , 549.53E0 , 575.29E0 , 576.00E0 , 625.55E0 , 20.15E0 , 28.78E0 , 29.57E0 , 37.41E0 , 39.12E0 , 50.24E0 , 61.38E0 , 66.25E0 , 73.42E0 , 95.52E0 , 107.32E0 , 122.04E0 , 134.03E0 , 163.19E0 , 163.48E0 , 175.70E0 , 179.86E0 , 211.27E0 , 217.78E0 , 219.14E0 , 262.52E0 , 268.01E0 , 268.62E0 , 336.25E0 , 337.23E0 , 339.33E0 , 427.38E0 , 428.58E0 , 432.68E0 , 528.99E0 , 531.08E0 , 628.34E0 , 253.24E0 , 273.13E0 , 273.66E0 ,\n282.10E0 , 346.62E0 , 347.19E0 , 348.78E0 , 351.18E0 , 450.10E0 , 450.35E0 , 451.92E0 , 455.56E0 , 552.22E0 , 553.56E0 , 555.74E0 , 652.59E0 , 656.20E0 , 14.13E0 , 20.41E0 , 31.30E0 , 33.84E0 , 39.70E0 , 48.83E0 , 54.50E0 , 60.41E0 , 72.77E0 , 75.25E0 , 86.84E0 , 94.88E0 , 96.40E0 , 117.37E0 , 139.08E0 , 147.73E0 , 158.63E0 , 161.84E0 , 192.11E0 , 206.76E0 , 209.07E0 , 213.32E0 , 226.44E0 , 237.12E0 , 330.90E0 , 358.72E0 , 370.77E0 , 372.72E0 , 396.24E0 , 416.59E0 , 484.02E0 , 495.47E0 , 514.78E0 , 515.65E0 , 519.47E0 , 544.47E0 , 560.11E0 , 620.77E0 , 18.97E0 , 28.93E0 , 33.91E0 , 40.03E0 , 44.66E0 , 49.87E0 , 55.16E0 , 60.90E0 , 72.08E0 , 85.15E0 , 97.06E0 , 119.63E0 , 133.27E0 , 143.84E0 , 161.91E0 , 180.67E0 , 198.44E0 , 226.86E0 , 229.65E0 , 258.27E0 , 273.77E0 , 339.15E0 , 350.13E0 , 362.75E0 , 371.03E0 , 393.32E0 , 448.53E0 , 473.78E0 , 511.12E0 , 524.70E0 , 548.75E0 , 551.64E0 , 574.02E0 , 623.86E0 , 21.46E0 , 24.33E0 , 33.43E0 , 39.22E0 , 44.18E0 , 55.02E0 , 94.33E0 , 96.44E0 , 118.82E0 , 128.48E0 ,\n141.94E0 , 156.92E0 , 171.65E0 , 190.00E0 , 223.26E0 , 223.88E0 , 231.50E0 , 265.05E0 , 269.44E0 , 271.78E0 , 273.46E0 , 334.61E0 , 339.79E0 , 349.52E0 , 358.18E0 , 377.98E0 , 394.77E0 , 429.66E0 , 468.22E0 , 487.27E0 , 519.54E0 , 523.03E0 , 612.99E0 , 638.59E0 , 641.36E0 , 622.05E0 , 631.50E0 , 663.97E0 , 646.9E0  , 748.29E0 , 749.21E0 , 750.14E0 , 647.04E0 , 646.89E0 , 746.9E0  , 748.43E0 , 747.35E0 , 749.27E0 , 647.61E0 , 747.78E0 , 750.51E0 , 851.37E0 , 845.97E0 , 847.54E0 , 849.93E0 , 851.61E0 , 849.75E0 , 850.98E0 , 848.23E0};\n\n// http://www.itl.nist.gov/div898/strd/nls/data/hahn1.shtml\nvoid testNistHahn1(void)\n{\n  const int  n=7;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 10., -1., .05, -.00001, -.05, .001, -.000001;\n  // do the computation\n  hahn1_functor functor;\n  LevenbergMarquardt<hahn1_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 11);\n  VERIFY_IS_EQUAL(lm.njev(), 10);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 1.5324382854E+00);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.0776351733E+00);\n  VERIFY_IS_APPROX(x[1],-1.2269296921E-01);\n  VERIFY_IS_APPROX(x[2], 4.0863750610E-03);\n  VERIFY_IS_APPROX(x[3],-1.426264e-06); // shoulde be : -1.4262662514E-06\n  VERIFY_IS_APPROX(x[4],-5.7609940901E-03);\n  VERIFY_IS_APPROX(x[5], 2.4053735503E-04);\n  VERIFY_IS_APPROX(x[6],-1.2314450199E-07);\n\n  /*\n   * Second try\n   */\n  x<< .1, -.1, .005, -.000001, -.005, .0001, -.0000001;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n//   VERIFY_IS_EQUAL(lm.nfev(), 11);\n  VERIFY_IS_EQUAL(lm.njev(), 10);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 1.5324382854E+00);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.077640); // should be :  1.0776351733E+00\n  VERIFY_IS_APPROX(x[1], -0.1226933); // should be : -1.2269296921E-01\n  VERIFY_IS_APPROX(x[2], 0.004086383); // should be : 4.0863750610E-03\n  VERIFY_IS_APPROX(x[3], -1.426277e-06); // shoulde be : -1.4262662514E-06\n  VERIFY_IS_APPROX(x[4],-5.7609940901E-03);\n  VERIFY_IS_APPROX(x[5], 0.00024053772); // should be : 2.4053735503E-04\n  VERIFY_IS_APPROX(x[6], -1.231450e-07); // should be : -1.2314450199E-07\n\n}\n\nstruct misra1d_functor : DenseFunctor<double>\n{\n    misra1d_functor(void) : DenseFunctor<double>(2,14) {}\n    static const double x[14];\n    static const double y[14];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==2);\n        assert(fvec.size()==14);\n        for(int i=0; i<14; i++) {\n            fvec[i] = b[0]*b[1]*x[i]/(1.+b[1]*x[i]) - y[i];\n        }\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==2);\n        assert(fjac.rows()==14);\n        assert(fjac.cols()==2);\n        for(int i=0; i<14; i++) {\n            double den = 1.+b[1]*x[i];\n            fjac(i,0) = b[1]*x[i] / den;\n            fjac(i,1) = b[0]*x[i]*(den-b[1]*x[i])/den/den;\n        }\n        return 0;\n    }\n};\nconst double misra1d_functor::x[14] = { 77.6E0, 114.9E0, 141.1E0, 190.8E0, 239.9E0, 289.0E0, 332.8E0, 378.4E0, 434.8E0, 477.3E0, 536.8E0, 593.1E0, 689.1E0, 760.0E0};\nconst double misra1d_functor::y[14] = { 10.07E0, 14.73E0, 17.94E0, 23.93E0, 29.61E0, 35.18E0, 40.02E0, 44.82E0, 50.76E0, 55.05E0, 61.01E0, 66.40E0, 75.47E0, 81.78E0};\n\n// http://www.itl.nist.gov/div898/strd/nls/data/misra1d.shtml\nvoid testNistMisra1d(void)\n{\n  const int n=2;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 500., 0.0001;\n  // do the computation\n  misra1d_functor functor;\n  LevenbergMarquardt<misra1d_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 9);\n  VERIFY_IS_EQUAL(lm.njev(), 7);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 5.6419295283E-02);\n  // check x\n  VERIFY_IS_APPROX(x[0], 4.3736970754E+02);\n  VERIFY_IS_APPROX(x[1], 3.0227324449E-04);\n\n  /*\n   * Second try\n   */\n  x<< 450., 0.0003;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 4);\n  VERIFY_IS_EQUAL(lm.njev(), 3);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 5.6419295283E-02);\n  // check x\n  VERIFY_IS_APPROX(x[0], 4.3736970754E+02);\n  VERIFY_IS_APPROX(x[1], 3.0227324449E-04);\n}\n\n\nstruct lanczos1_functor : DenseFunctor<double>\n{\n    lanczos1_functor(void) : DenseFunctor<double>(6,24) {}\n    static const double x[24];\n    static const double y[24];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==6);\n        assert(fvec.size()==24);\n        for(int i=0; i<24; i++)\n            fvec[i] = b[0]*exp(-b[1]*x[i]) + b[2]*exp(-b[3]*x[i]) + b[4]*exp(-b[5]*x[i])  - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==6);\n        assert(fjac.rows()==24);\n        assert(fjac.cols()==6);\n        for(int i=0; i<24; i++) {\n            fjac(i,0) = exp(-b[1]*x[i]);\n            fjac(i,1) = -b[0]*x[i]*exp(-b[1]*x[i]);\n            fjac(i,2) = exp(-b[3]*x[i]);\n            fjac(i,3) = -b[2]*x[i]*exp(-b[3]*x[i]);\n            fjac(i,4) = exp(-b[5]*x[i]);\n            fjac(i,5) = -b[4]*x[i]*exp(-b[5]*x[i]);\n        }\n        return 0;\n    }\n};\nconst double lanczos1_functor::x[24] = { 0.000000000000E+00, 5.000000000000E-02, 1.000000000000E-01, 1.500000000000E-01, 2.000000000000E-01, 2.500000000000E-01, 3.000000000000E-01, 3.500000000000E-01, 4.000000000000E-01, 4.500000000000E-01, 5.000000000000E-01, 5.500000000000E-01, 6.000000000000E-01, 6.500000000000E-01, 7.000000000000E-01, 7.500000000000E-01, 8.000000000000E-01, 8.500000000000E-01, 9.000000000000E-01, 9.500000000000E-01, 1.000000000000E+00, 1.050000000000E+00, 1.100000000000E+00, 1.150000000000E+00 };\nconst double lanczos1_functor::y[24] = { 2.513400000000E+00 ,2.044333373291E+00 ,1.668404436564E+00 ,1.366418021208E+00 ,1.123232487372E+00 ,9.268897180037E-01 ,7.679338563728E-01 ,6.388775523106E-01 ,5.337835317402E-01 ,4.479363617347E-01 ,3.775847884350E-01 ,3.197393199326E-01 ,2.720130773746E-01 ,2.324965529032E-01 ,1.996589546065E-01 ,1.722704126914E-01 ,1.493405660168E-01 ,1.300700206922E-01 ,1.138119324644E-01 ,1.000415587559E-01 ,8.833209084540E-02 ,7.833544019350E-02 ,6.976693743449E-02 ,6.239312536719E-02 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/lanczos1.shtml\nvoid testNistLanczos1(void)\n{\n  const int n=6;\n  LevenbergMarquardtSpace::Status info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 1.2, 0.3, 5.6, 5.5, 6.5, 7.6;\n  // do the computation\n  lanczos1_functor functor;\n  LevenbergMarquardt<lanczos1_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, LevenbergMarquardtSpace::RelativeErrorTooSmall);\n  VERIFY_IS_EQUAL(lm.nfev(), 79);\n  VERIFY_IS_EQUAL(lm.njev(), 72);\n  // check norm^2\n  VERIFY(lm.fvec().squaredNorm() <= 1.4307867721E-25);\n  // check x\n  VERIFY_IS_APPROX(x[0], 9.5100000027E-02);\n  VERIFY_IS_APPROX(x[1], 1.0000000001E+00);\n  VERIFY_IS_APPROX(x[2], 8.6070000013E-01);\n  VERIFY_IS_APPROX(x[3], 3.0000000002E+00);\n  VERIFY_IS_APPROX(x[4], 1.5575999998E+00);\n  VERIFY_IS_APPROX(x[5], 5.0000000001E+00);\n\n  /*\n   * Second try\n   */\n  x<< 0.5, 0.7, 3.6, 4.2, 4., 6.3;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, LevenbergMarquardtSpace::RelativeErrorTooSmall);\n  VERIFY_IS_EQUAL(lm.nfev(), 9);\n  VERIFY_IS_EQUAL(lm.njev(), 8);\n  // check norm^2\n  VERIFY(lm.fvec().squaredNorm() <= 1.4307867721E-25);\n  // check x\n  VERIFY_IS_APPROX(x[0], 9.5100000027E-02);\n  VERIFY_IS_APPROX(x[1], 1.0000000001E+00);\n  VERIFY_IS_APPROX(x[2], 8.6070000013E-01);\n  VERIFY_IS_APPROX(x[3], 3.0000000002E+00);\n  VERIFY_IS_APPROX(x[4], 1.5575999998E+00);\n  VERIFY_IS_APPROX(x[5], 5.0000000001E+00);\n\n}\n\nstruct rat42_functor : DenseFunctor<double>\n{\n    rat42_functor(void) : DenseFunctor<double>(3,9) {}\n    static const double x[9];\n    static const double y[9];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==3);\n        assert(fvec.size()==9);\n        for(int i=0; i<9; i++) {\n            fvec[i] = b[0] / (1.+exp(b[1]-b[2]*x[i])) - y[i];\n        }\n        return 0;\n    }\n\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==3);\n        assert(fjac.rows()==9);\n        assert(fjac.cols()==3);\n        for(int i=0; i<9; i++) {\n            double e = exp(b[1]-b[2]*x[i]);\n            fjac(i,0) = 1./(1.+e);\n            fjac(i,1) = -b[0]*e/(1.+e)/(1.+e);\n            fjac(i,2) = +b[0]*e*x[i]/(1.+e)/(1.+e);\n        }\n        return 0;\n    }\n};\nconst double rat42_functor::x[9] = { 9.000E0, 14.000E0, 21.000E0, 28.000E0, 42.000E0, 57.000E0, 63.000E0, 70.000E0, 79.000E0 };\nconst double rat42_functor::y[9] = { 8.930E0 ,10.800E0 ,18.590E0 ,22.330E0 ,39.350E0 ,56.110E0 ,61.730E0 ,64.620E0 ,67.080E0 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/ratkowsky2.shtml\nvoid testNistRat42(void)\n{\n  const int n=3;\n  LevenbergMarquardtSpace::Status info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 100., 1., 0.1;\n  // do the computation\n  rat42_functor functor;\n  LevenbergMarquardt<rat42_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, LevenbergMarquardtSpace::RelativeReductionTooSmall);\n  VERIFY_IS_EQUAL(lm.nfev(), 10);\n  VERIFY_IS_EQUAL(lm.njev(), 8);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 8.0565229338E+00);\n  // check x\n  VERIFY_IS_APPROX(x[0], 7.2462237576E+01);\n  VERIFY_IS_APPROX(x[1], 2.6180768402E+00);\n  VERIFY_IS_APPROX(x[2], 6.7359200066E-02);\n\n  /*\n   * Second try\n   */\n  x<< 75., 2.5, 0.07;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, LevenbergMarquardtSpace::RelativeReductionTooSmall);\n  VERIFY_IS_EQUAL(lm.nfev(), 6);\n  VERIFY_IS_EQUAL(lm.njev(), 5);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 8.0565229338E+00);\n  // check x\n  VERIFY_IS_APPROX(x[0], 7.2462237576E+01);\n  VERIFY_IS_APPROX(x[1], 2.6180768402E+00);\n  VERIFY_IS_APPROX(x[2], 6.7359200066E-02);\n}\n\nstruct MGH10_functor : DenseFunctor<double>\n{\n    MGH10_functor(void) : DenseFunctor<double>(3,16) {}\n    static const double x[16];\n    static const double y[16];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==3);\n        assert(fvec.size()==16);\n        for(int i=0; i<16; i++)\n            fvec[i] =  b[0] * exp(b[1]/(x[i]+b[2])) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==3);\n        assert(fjac.rows()==16);\n        assert(fjac.cols()==3);\n        for(int i=0; i<16; i++) {\n            double factor = 1./(x[i]+b[2]);\n            double e = exp(b[1]*factor);\n            fjac(i,0) = e;\n            fjac(i,1) = b[0]*factor*e;\n            fjac(i,2) = -b[1]*b[0]*factor*factor*e;\n        }\n        return 0;\n    }\n};\nconst double MGH10_functor::x[16] = { 5.000000E+01, 5.500000E+01, 6.000000E+01, 6.500000E+01, 7.000000E+01, 7.500000E+01, 8.000000E+01, 8.500000E+01, 9.000000E+01, 9.500000E+01, 1.000000E+02, 1.050000E+02, 1.100000E+02, 1.150000E+02, 1.200000E+02, 1.250000E+02 };\nconst double MGH10_functor::y[16] = { 3.478000E+04, 2.861000E+04, 2.365000E+04, 1.963000E+04, 1.637000E+04, 1.372000E+04, 1.154000E+04, 9.744000E+03, 8.261000E+03, 7.030000E+03, 6.005000E+03, 5.147000E+03, 4.427000E+03, 3.820000E+03, 3.307000E+03, 2.872000E+03 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/mgh10.shtml\nvoid testNistMGH10(void)\n{\n  const int n=3;\n  LevenbergMarquardtSpace::Status info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 2., 400000., 25000.;\n  // do the computation\n  MGH10_functor functor;\n  LevenbergMarquardt<MGH10_functor> lm(functor);\n  info = lm.minimize(x);\n  ++g_test_level;\n  VERIFY_IS_EQUAL(info, LevenbergMarquardtSpace::RelativeReductionTooSmall);\n  --g_test_level;\n  // was: VERIFY_IS_EQUAL(info, 1);\n\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 8.7945855171E+01);\n  // check x\n  VERIFY_IS_APPROX(x[0], 5.6096364710E-03);\n  VERIFY_IS_APPROX(x[1], 6.1813463463E+03);\n  VERIFY_IS_APPROX(x[2], 3.4522363462E+02);\n  \n  // check return value\n\n  ++g_test_level;\n  VERIFY_IS_EQUAL(lm.nfev(), 284 );\n  VERIFY_IS_EQUAL(lm.njev(), 249 );\n  --g_test_level;\n  VERIFY(lm.nfev() < 284 * LM_EVAL_COUNT_TOL);\n  VERIFY(lm.njev() < 249 * LM_EVAL_COUNT_TOL);\n\n  /*\n   * Second try\n   */\n  x<< 0.02, 4000., 250.;\n  // do the computation\n  info = lm.minimize(x);\n  ++g_test_level;\n  VERIFY_IS_EQUAL(info, LevenbergMarquardtSpace::RelativeReductionTooSmall);\n  // was: VERIFY_IS_EQUAL(info, 1);\n  --g_test_level;\n\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 8.7945855171E+01);\n  // check x\n  VERIFY_IS_APPROX(x[0], 5.6096364710E-03);\n  VERIFY_IS_APPROX(x[1], 6.1813463463E+03);\n  VERIFY_IS_APPROX(x[2], 3.4522363462E+02);\n  \n  // check return value\n  ++g_test_level;\n  VERIFY_IS_EQUAL(lm.nfev(), 126);\n  VERIFY_IS_EQUAL(lm.njev(), 116);\n  --g_test_level;\n  VERIFY(lm.nfev() < 126 * LM_EVAL_COUNT_TOL);\n  VERIFY(lm.njev() < 116 * LM_EVAL_COUNT_TOL);\n}\n\n\nstruct BoxBOD_functor : DenseFunctor<double>\n{\n    BoxBOD_functor(void) : DenseFunctor<double>(2,6) {}\n    static const double x[6];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        static const double y[6] = { 109., 149., 149., 191., 213., 224. };\n        assert(b.size()==2);\n        assert(fvec.size()==6);\n        for(int i=0; i<6; i++)\n            fvec[i] =  b[0]*(1.-exp(-b[1]*x[i])) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==2);\n        assert(fjac.rows()==6);\n        assert(fjac.cols()==2);\n        for(int i=0; i<6; i++) {\n            double e = exp(-b[1]*x[i]);\n            fjac(i,0) = 1.-e;\n            fjac(i,1) = b[0]*x[i]*e;\n        }\n        return 0;\n    }\n};\nconst double BoxBOD_functor::x[6] = { 1., 2., 3., 5., 7., 10. };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/boxbod.shtml\nvoid testNistBoxBOD(void)\n{\n  const int n=2;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 1., 1.;\n  // do the computation\n  BoxBOD_functor functor;\n  LevenbergMarquardt<BoxBOD_functor> lm(functor);\n  lm.setFtol(1.E6*NumTraits<double>::epsilon());\n  lm.setXtol(1.E6*NumTraits<double>::epsilon());\n  lm.setFactor(10);\n  info = lm.minimize(x);\n\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 1.1680088766E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 2.1380940889E+02);\n  VERIFY_IS_APPROX(x[1], 5.4723748542E-01);\n  \n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY(lm.nfev() < 31); // 31\n  VERIFY(lm.njev() < 25); // 25\n\n  /*\n   * Second try\n   */\n  x<< 100., 0.75;\n  // do the computation\n  lm.resetParameters();\n  lm.setFtol(NumTraits<double>::epsilon());\n  lm.setXtol( NumTraits<double>::epsilon());\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1); \n  ++g_test_level;\n  VERIFY_IS_EQUAL(lm.nfev(), 16 );\n  VERIFY_IS_EQUAL(lm.njev(), 15 );\n  --g_test_level;\n  VERIFY(lm.nfev() < 16 * LM_EVAL_COUNT_TOL);\n  VERIFY(lm.njev() < 15 * LM_EVAL_COUNT_TOL);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 1.1680088766E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 2.1380940889E+02);\n  VERIFY_IS_APPROX(x[1], 5.4723748542E-01);\n}\n\nstruct MGH17_functor : DenseFunctor<double>\n{\n    MGH17_functor(void) : DenseFunctor<double>(5,33) {}\n    static const double x[33];\n    static const double y[33];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==5);\n        assert(fvec.size()==33);\n        for(int i=0; i<33; i++)\n            fvec[i] =  b[0] + b[1]*exp(-b[3]*x[i]) +  b[2]*exp(-b[4]*x[i]) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==5);\n        assert(fjac.rows()==33);\n        assert(fjac.cols()==5);\n        for(int i=0; i<33; i++) {\n            fjac(i,0) = 1.;\n            fjac(i,1) = exp(-b[3]*x[i]);\n            fjac(i,2) = exp(-b[4]*x[i]);\n            fjac(i,3) = -x[i]*b[1]*exp(-b[3]*x[i]);\n            fjac(i,4) = -x[i]*b[2]*exp(-b[4]*x[i]);\n        }\n        return 0;\n    }\n};\nconst double MGH17_functor::x[33] = { 0.000000E+00, 1.000000E+01, 2.000000E+01, 3.000000E+01, 4.000000E+01, 5.000000E+01, 6.000000E+01, 7.000000E+01, 8.000000E+01, 9.000000E+01, 1.000000E+02, 1.100000E+02, 1.200000E+02, 1.300000E+02, 1.400000E+02, 1.500000E+02, 1.600000E+02, 1.700000E+02, 1.800000E+02, 1.900000E+02, 2.000000E+02, 2.100000E+02, 2.200000E+02, 2.300000E+02, 2.400000E+02, 2.500000E+02, 2.600000E+02, 2.700000E+02, 2.800000E+02, 2.900000E+02, 3.000000E+02, 3.100000E+02, 3.200000E+02 };\nconst double MGH17_functor::y[33] = { 8.440000E-01, 9.080000E-01, 9.320000E-01, 9.360000E-01, 9.250000E-01, 9.080000E-01, 8.810000E-01, 8.500000E-01, 8.180000E-01, 7.840000E-01, 7.510000E-01, 7.180000E-01, 6.850000E-01, 6.580000E-01, 6.280000E-01, 6.030000E-01, 5.800000E-01, 5.580000E-01, 5.380000E-01, 5.220000E-01, 5.060000E-01, 4.900000E-01, 4.780000E-01, 4.670000E-01, 4.570000E-01, 4.480000E-01, 4.380000E-01, 4.310000E-01, 4.240000E-01, 4.200000E-01, 4.140000E-01, 4.110000E-01, 4.060000E-01 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/mgh17.shtml\nvoid testNistMGH17(void)\n{\n  const int n=5;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 50., 150., -100., 1., 2.;\n  // do the computation\n  MGH17_functor functor;\n  LevenbergMarquardt<MGH17_functor> lm(functor);\n  lm.setFtol(NumTraits<double>::epsilon());\n  lm.setXtol(NumTraits<double>::epsilon());\n  lm.setMaxfev(1000);\n  info = lm.minimize(x);\n\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 5.4648946975E-05);\n  // check x\n  VERIFY_IS_APPROX(x[0], 3.7541005211E-01);\n  VERIFY_IS_APPROX(x[1], 1.9358469127E+00);\n  VERIFY_IS_APPROX(x[2], -1.4646871366E+00);\n  VERIFY_IS_APPROX(x[3], 1.2867534640E-02);\n  VERIFY_IS_APPROX(x[4], 2.2122699662E-02);\n  \n    // check return value\n//   VERIFY_IS_EQUAL(info, 2);  //FIXME Use (lm.info() == Success)\n  VERIFY(lm.nfev() < 700 ); // 602\n  VERIFY(lm.njev() < 600 ); // 545\n\n  /*\n   * Second try\n   */\n  x<< 0.5  ,1.5  ,-1   ,0.01 ,0.02;\n  // do the computation\n  lm.resetParameters();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 18);\n  VERIFY_IS_EQUAL(lm.njev(), 15);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 5.4648946975E-05);\n  // check x\n  VERIFY_IS_APPROX(x[0], 3.7541005211E-01);\n  VERIFY_IS_APPROX(x[1], 1.9358469127E+00);\n  VERIFY_IS_APPROX(x[2], -1.4646871366E+00);\n  VERIFY_IS_APPROX(x[3], 1.2867534640E-02);\n  VERIFY_IS_APPROX(x[4], 2.2122699662E-02);\n}\n\nstruct MGH09_functor : DenseFunctor<double>\n{\n    MGH09_functor(void) : DenseFunctor<double>(4,11) {}\n    static const double _x[11];\n    static const double y[11];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==4);\n        assert(fvec.size()==11);\n        for(int i=0; i<11; i++) {\n            double x = _x[i], xx=x*x;\n            fvec[i] = b[0]*(xx+x*b[1])/(xx+x*b[2]+b[3]) - y[i];\n        }\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==4);\n        assert(fjac.rows()==11);\n        assert(fjac.cols()==4);\n        for(int i=0; i<11; i++) {\n            double x = _x[i], xx=x*x;\n            double factor = 1./(xx+x*b[2]+b[3]);\n            fjac(i,0) = (xx+x*b[1]) * factor;\n            fjac(i,1) = b[0]*x* factor;\n            fjac(i,2) = - b[0]*(xx+x*b[1]) * x * factor * factor;\n            fjac(i,3) = - b[0]*(xx+x*b[1]) * factor * factor;\n        }\n        return 0;\n    }\n};\nconst double MGH09_functor::_x[11] = { 4., 2., 1., 5.E-1 , 2.5E-01, 1.670000E-01, 1.250000E-01,  1.E-01, 8.330000E-02, 7.140000E-02, 6.250000E-02 };\nconst double MGH09_functor::y[11] = { 1.957000E-01, 1.947000E-01, 1.735000E-01, 1.600000E-01, 8.440000E-02, 6.270000E-02, 4.560000E-02, 3.420000E-02, 3.230000E-02, 2.350000E-02, 2.460000E-02 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/mgh09.shtml\nvoid testNistMGH09(void)\n{\n  const int n=4;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 25., 39, 41.5, 39.;\n  // do the computation\n  MGH09_functor functor;\n  LevenbergMarquardt<MGH09_functor> lm(functor);\n  lm.setMaxfev(1000);\n  info = lm.minimize(x);\n\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 3.0750560385E-04);\n  // check x\n  VERIFY_IS_APPROX(x[0], 0.1928077089); // should be 1.9280693458E-01\n  VERIFY_IS_APPROX(x[1], 0.19126423573); // should be 1.9128232873E-01\n  VERIFY_IS_APPROX(x[2], 0.12305309914); // should be 1.2305650693E-01\n  VERIFY_IS_APPROX(x[3], 0.13605395375); // should be 1.3606233068E-01\n  // check return value\n  VERIFY_IS_EQUAL(info, 1); \n  VERIFY(lm.nfev() < 510 ); // 490\n  VERIFY(lm.njev() < 400 ); // 376\n\n  /*\n   * Second try\n   */\n  x<< 0.25, 0.39, 0.415, 0.39;\n  // do the computation\n  lm.resetParameters();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 18);\n  VERIFY_IS_EQUAL(lm.njev(), 16);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 3.0750560385E-04);\n  // check x\n  VERIFY_IS_APPROX(x[0], 0.19280781); // should be 1.9280693458E-01\n  VERIFY_IS_APPROX(x[1], 0.19126265); // should be 1.9128232873E-01\n  VERIFY_IS_APPROX(x[2], 0.12305280); // should be 1.2305650693E-01\n  VERIFY_IS_APPROX(x[3], 0.13605322); // should be 1.3606233068E-01\n}\n\n\n\nstruct Bennett5_functor : DenseFunctor<double>\n{\n    Bennett5_functor(void) : DenseFunctor<double>(3,154) {}\n    static const double x[154];\n    static const double y[154];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==3);\n        assert(fvec.size()==154);\n        for(int i=0; i<154; i++)\n            fvec[i] = b[0]* pow(b[1]+x[i],-1./b[2]) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==3);\n        assert(fjac.rows()==154);\n        assert(fjac.cols()==3);\n        for(int i=0; i<154; i++) {\n            double e = pow(b[1]+x[i],-1./b[2]);\n            fjac(i,0) = e;\n            fjac(i,1) = - b[0]*e/b[2]/(b[1]+x[i]);\n            fjac(i,2) = b[0]*e*log(b[1]+x[i])/b[2]/b[2];\n        }\n        return 0;\n    }\n};\nconst double Bennett5_functor::x[154] = { 7.447168E0, 8.102586E0, 8.452547E0, 8.711278E0, 8.916774E0, 9.087155E0, 9.232590E0, 9.359535E0, 9.472166E0, 9.573384E0, 9.665293E0, 9.749461E0, 9.827092E0, 9.899128E0, 9.966321E0, 10.029280E0, 10.088510E0, 10.144430E0, 10.197380E0, 10.247670E0, 10.295560E0, 10.341250E0, 10.384950E0, 10.426820E0, 10.467000E0, 10.505640E0, 10.542830E0, 10.578690E0, 10.613310E0, 10.646780E0, 10.679150E0, 10.710520E0, 10.740920E0, 10.770440E0, 10.799100E0, 10.826970E0, 10.854080E0, 10.880470E0, 10.906190E0, 10.931260E0, 10.955720E0, 10.979590E0, 11.002910E0, 11.025700E0, 11.047980E0, 11.069770E0, 11.091100E0, 11.111980E0, 11.132440E0, 11.152480E0, 11.172130E0, 11.191410E0, 11.210310E0, 11.228870E0, 11.247090E0, 11.264980E0, 11.282560E0, 11.299840E0, 11.316820E0, 11.333520E0, 11.349940E0, 11.366100E0, 11.382000E0, 11.397660E0, 11.413070E0, 11.428240E0, 11.443200E0, 11.457930E0, 11.472440E0, 11.486750E0, 11.500860E0, 11.514770E0, 11.528490E0, 11.542020E0, 11.555380E0, 11.568550E0,\n11.581560E0, 11.594420E0, 11.607121E0, 11.619640E0, 11.632000E0, 11.644210E0, 11.656280E0, 11.668200E0, 11.679980E0, 11.691620E0, 11.703130E0, 11.714510E0, 11.725760E0, 11.736880E0, 11.747890E0, 11.758780E0, 11.769550E0, 11.780200E0, 11.790730E0, 11.801160E0, 11.811480E0, 11.821700E0, 11.831810E0, 11.841820E0, 11.851730E0, 11.861550E0, 11.871270E0, 11.880890E0, 11.890420E0, 11.899870E0, 11.909220E0, 11.918490E0, 11.927680E0, 11.936780E0, 11.945790E0, 11.954730E0, 11.963590E0, 11.972370E0, 11.981070E0, 11.989700E0, 11.998260E0, 12.006740E0, 12.015150E0, 12.023490E0, 12.031760E0, 12.039970E0, 12.048100E0, 12.056170E0, 12.064180E0, 12.072120E0, 12.080010E0, 12.087820E0, 12.095580E0, 12.103280E0, 12.110920E0, 12.118500E0, 12.126030E0, 12.133500E0, 12.140910E0, 12.148270E0, 12.155570E0, 12.162830E0, 12.170030E0, 12.177170E0, 12.184270E0, 12.191320E0, 12.198320E0, 12.205270E0, 12.212170E0, 12.219030E0, 12.225840E0, 12.232600E0, 12.239320E0, 12.245990E0, 12.252620E0, 12.259200E0, 12.265750E0, 12.272240E0 };\nconst double Bennett5_functor::y[154] = { -34.834702E0 ,-34.393200E0 ,-34.152901E0 ,-33.979099E0 ,-33.845901E0 ,-33.732899E0 ,-33.640301E0 ,-33.559200E0 ,-33.486801E0 ,-33.423100E0 ,-33.365101E0 ,-33.313000E0 ,-33.260899E0 ,-33.217400E0 ,-33.176899E0 ,-33.139198E0 ,-33.101601E0 ,-33.066799E0 ,-33.035000E0 ,-33.003101E0 ,-32.971298E0 ,-32.942299E0 ,-32.916302E0 ,-32.890202E0 ,-32.864101E0 ,-32.841000E0 ,-32.817799E0 ,-32.797501E0 ,-32.774300E0 ,-32.757000E0 ,-32.733799E0 ,-32.716400E0 ,-32.699100E0 ,-32.678799E0 ,-32.661400E0 ,-32.644001E0 ,-32.626701E0 ,-32.612202E0 ,-32.597698E0 ,-32.583199E0 ,-32.568699E0 ,-32.554298E0 ,-32.539799E0 ,-32.525299E0 ,-32.510799E0 ,-32.499199E0 ,-32.487598E0 ,-32.473202E0 ,-32.461601E0 ,-32.435501E0 ,-32.435501E0 ,-32.426800E0 ,-32.412300E0 ,-32.400799E0 ,-32.392101E0 ,-32.380501E0 ,-32.366001E0 ,-32.357300E0 ,-32.348598E0 ,-32.339901E0 ,-32.328400E0 ,-32.319698E0 ,-32.311001E0 ,-32.299400E0 ,-32.290699E0 ,-32.282001E0 ,-32.273300E0 ,-32.264599E0 ,-32.256001E0 ,-32.247299E0\n,-32.238602E0 ,-32.229900E0 ,-32.224098E0 ,-32.215401E0 ,-32.203800E0 ,-32.198002E0 ,-32.189400E0 ,-32.183601E0 ,-32.174900E0 ,-32.169102E0 ,-32.163300E0 ,-32.154598E0 ,-32.145901E0 ,-32.140099E0 ,-32.131401E0 ,-32.125599E0 ,-32.119801E0 ,-32.111198E0 ,-32.105400E0 ,-32.096699E0 ,-32.090900E0 ,-32.088001E0 ,-32.079300E0 ,-32.073502E0 ,-32.067699E0 ,-32.061901E0 ,-32.056099E0 ,-32.050301E0 ,-32.044498E0 ,-32.038799E0 ,-32.033001E0 ,-32.027199E0 ,-32.024300E0 ,-32.018501E0 ,-32.012699E0 ,-32.004002E0 ,-32.001099E0 ,-31.995300E0 ,-31.989500E0 ,-31.983700E0 ,-31.977900E0 ,-31.972099E0 ,-31.969299E0 ,-31.963501E0 ,-31.957701E0 ,-31.951900E0 ,-31.946100E0 ,-31.940300E0 ,-31.937401E0 ,-31.931601E0 ,-31.925800E0 ,-31.922899E0 ,-31.917101E0 ,-31.911301E0 ,-31.908400E0 ,-31.902599E0 ,-31.896900E0 ,-31.893999E0 ,-31.888201E0 ,-31.885300E0 ,-31.882401E0 ,-31.876600E0 ,-31.873699E0 ,-31.867901E0 ,-31.862101E0 ,-31.859200E0 ,-31.856300E0 ,-31.850500E0 ,-31.844700E0 ,-31.841801E0 ,-31.838900E0 ,-31.833099E0 ,-31.830200E0 ,\n-31.827299E0 ,-31.821600E0 ,-31.818701E0 ,-31.812901E0 ,-31.809999E0 ,-31.807100E0 ,-31.801300E0 ,-31.798401E0 ,-31.795500E0 ,-31.789700E0 ,-31.786800E0 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/bennett5.shtml\nvoid testNistBennett5(void)\n{\n  const int  n=3;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< -2000., 50., 0.8;\n  // do the computation\n  Bennett5_functor functor;\n  LevenbergMarquardt<Bennett5_functor> lm(functor);\n  lm.setMaxfev(1000);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 758);\n  VERIFY_IS_EQUAL(lm.njev(), 744);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 5.2404744073E-04);\n  // check x\n  VERIFY_IS_APPROX(x[0], -2.5235058043E+03);\n  VERIFY_IS_APPROX(x[1], 4.6736564644E+01);\n  VERIFY_IS_APPROX(x[2], 9.3218483193E-01);\n  /*\n   * Second try\n   */\n  x<< -1500., 45., 0.85;\n  // do the computation\n  lm.resetParameters();\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 203);\n  VERIFY_IS_EQUAL(lm.njev(), 192);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 5.2404744073E-04);\n  // check x\n  VERIFY_IS_APPROX(x[0], -2523.3007865); // should be -2.5235058043E+03\n  VERIFY_IS_APPROX(x[1], 46.735705771); // should be 4.6736564644E+01);\n  VERIFY_IS_APPROX(x[2], 0.93219881891); // should be 9.3218483193E-01);\n}\n\nstruct thurber_functor : DenseFunctor<double>\n{\n    thurber_functor(void) : DenseFunctor<double>(7,37) {}\n    static const double _x[37];\n    static const double _y[37];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        //        int called=0; printf(\"call hahn1_functor with  iflag=%d, called=%d\\n\", iflag, called); if (iflag==1) called++;\n        assert(b.size()==7);\n        assert(fvec.size()==37);\n        for(int i=0; i<37; i++) {\n            double x=_x[i], xx=x*x, xxx=xx*x;\n            fvec[i] = (b[0]+b[1]*x+b[2]*xx+b[3]*xxx) / (1.+b[4]*x+b[5]*xx+b[6]*xxx) - _y[i];\n        }\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==7);\n        assert(fjac.rows()==37);\n        assert(fjac.cols()==7);\n        for(int i=0; i<37; i++) {\n            double x=_x[i], xx=x*x, xxx=xx*x;\n            double fact = 1./(1.+b[4]*x+b[5]*xx+b[6]*xxx);\n            fjac(i,0) = 1.*fact;\n            fjac(i,1) = x*fact;\n            fjac(i,2) = xx*fact;\n            fjac(i,3) = xxx*fact;\n            fact = - (b[0]+b[1]*x+b[2]*xx+b[3]*xxx) * fact * fact;\n            fjac(i,4) = x*fact;\n            fjac(i,5) = xx*fact;\n            fjac(i,6) = xxx*fact;\n        }\n        return 0;\n    }\n};\nconst double thurber_functor::_x[37] = { -3.067E0, -2.981E0, -2.921E0, -2.912E0, -2.840E0, -2.797E0, -2.702E0, -2.699E0, -2.633E0, -2.481E0, -2.363E0, -2.322E0, -1.501E0, -1.460E0, -1.274E0, -1.212E0, -1.100E0, -1.046E0, -0.915E0, -0.714E0, -0.566E0, -0.545E0, -0.400E0, -0.309E0, -0.109E0, -0.103E0, 0.010E0, 0.119E0, 0.377E0, 0.790E0, 0.963E0, 1.006E0, 1.115E0, 1.572E0, 1.841E0, 2.047E0, 2.200E0 };\nconst double thurber_functor::_y[37] = { 80.574E0, 84.248E0, 87.264E0, 87.195E0, 89.076E0, 89.608E0, 89.868E0, 90.101E0, 92.405E0, 95.854E0, 100.696E0, 101.060E0, 401.672E0, 390.724E0, 567.534E0, 635.316E0, 733.054E0, 759.087E0, 894.206E0, 990.785E0, 1090.109E0, 1080.914E0, 1122.643E0, 1178.351E0, 1260.531E0, 1273.514E0, 1288.339E0, 1327.543E0, 1353.863E0, 1414.509E0, 1425.208E0, 1421.384E0, 1442.962E0, 1464.350E0, 1468.705E0, 1447.894E0, 1457.628E0};\n\n// http://www.itl.nist.gov/div898/strd/nls/data/thurber.shtml\nvoid testNistThurber(void)\n{\n  const int n=7;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 1000 ,1000 ,400 ,40 ,0.7,0.3,0.0 ;\n  // do the computation\n  thurber_functor functor;\n  LevenbergMarquardt<thurber_functor> lm(functor);\n  lm.setFtol(1.E4*NumTraits<double>::epsilon());\n  lm.setXtol(1.E4*NumTraits<double>::epsilon());\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 39);\n  VERIFY_IS_EQUAL(lm.njev(), 36);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 5.6427082397E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.2881396800E+03);\n  VERIFY_IS_APPROX(x[1], 1.4910792535E+03);\n  VERIFY_IS_APPROX(x[2], 5.8323836877E+02);\n  VERIFY_IS_APPROX(x[3], 7.5416644291E+01);\n  VERIFY_IS_APPROX(x[4], 9.6629502864E-01);\n  VERIFY_IS_APPROX(x[5], 3.9797285797E-01);\n  VERIFY_IS_APPROX(x[6], 4.9727297349E-02);\n\n  /*\n   * Second try\n   */\n  x<< 1300 ,1500 ,500  ,75   ,1    ,0.4  ,0.05  ;\n  // do the computation\n  lm.resetParameters();\n  lm.setFtol(1.E4*NumTraits<double>::epsilon());\n  lm.setXtol(1.E4*NumTraits<double>::epsilon());\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 29);\n  VERIFY_IS_EQUAL(lm.njev(), 28);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 5.6427082397E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.2881396800E+03);\n  VERIFY_IS_APPROX(x[1], 1.4910792535E+03);\n  VERIFY_IS_APPROX(x[2], 5.8323836877E+02);\n  VERIFY_IS_APPROX(x[3], 7.5416644291E+01);\n  VERIFY_IS_APPROX(x[4], 9.6629502864E-01);\n  VERIFY_IS_APPROX(x[5], 3.9797285797E-01);\n  VERIFY_IS_APPROX(x[6], 4.9727297349E-02);\n}\n\nstruct rat43_functor : DenseFunctor<double>\n{\n    rat43_functor(void) : DenseFunctor<double>(4,15) {}\n    static const double x[15];\n    static const double y[15];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==4);\n        assert(fvec.size()==15);\n        for(int i=0; i<15; i++)\n            fvec[i] = b[0] * pow(1.+exp(b[1]-b[2]*x[i]),-1./b[3]) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==4);\n        assert(fjac.rows()==15);\n        assert(fjac.cols()==4);\n        for(int i=0; i<15; i++) {\n            double e = exp(b[1]-b[2]*x[i]);\n            double power = -1./b[3];\n            fjac(i,0) = pow(1.+e, power);\n            fjac(i,1) = power*b[0]*e*pow(1.+e, power-1.);\n            fjac(i,2) = -power*b[0]*e*x[i]*pow(1.+e, power-1.);\n            fjac(i,3) = b[0]*power*power*log(1.+e)*pow(1.+e, power);\n        }\n        return 0;\n    }\n};\nconst double rat43_functor::x[15] = { 1., 2., 3., 4., 5., 6., 7., 8., 9., 10., 11., 12., 13., 14., 15. };\nconst double rat43_functor::y[15] = { 16.08, 33.83, 65.80, 97.20, 191.55, 326.20, 386.87, 520.53, 590.03, 651.92, 724.93, 699.56, 689.96, 637.56, 717.41 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/ratkowsky3.shtml\nvoid testNistRat43(void)\n{\n  const int n=4;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 100., 10., 1., 1.;\n  // do the computation\n  rat43_functor functor;\n  LevenbergMarquardt<rat43_functor> lm(functor);\n  lm.setFtol(1.E6*NumTraits<double>::epsilon());\n  lm.setXtol(1.E6*NumTraits<double>::epsilon());\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 27);\n  VERIFY_IS_EQUAL(lm.njev(), 20);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 8.7864049080E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 6.9964151270E+02);\n  VERIFY_IS_APPROX(x[1], 5.2771253025E+00);\n  VERIFY_IS_APPROX(x[2], 7.5962938329E-01);\n  VERIFY_IS_APPROX(x[3], 1.2792483859E+00);\n\n  /*\n   * Second try\n   */\n  x<< 700., 5., 0.75, 1.3;\n  // do the computation\n  lm.resetParameters();\n  lm.setFtol(1.E5*NumTraits<double>::epsilon());\n  lm.setXtol(1.E5*NumTraits<double>::epsilon());\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 9);\n  VERIFY_IS_EQUAL(lm.njev(), 8);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 8.7864049080E+03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 6.9964151270E+02);\n  VERIFY_IS_APPROX(x[1], 5.2771253025E+00);\n  VERIFY_IS_APPROX(x[2], 7.5962938329E-01);\n  VERIFY_IS_APPROX(x[3], 1.2792483859E+00);\n}\n\n\n\nstruct eckerle4_functor : DenseFunctor<double>\n{\n    eckerle4_functor(void) : DenseFunctor<double>(3,35) {}\n    static const double x[35];\n    static const double y[35];\n    int operator()(const VectorXd &b, VectorXd &fvec)\n    {\n        assert(b.size()==3);\n        assert(fvec.size()==35);\n        for(int i=0; i<35; i++)\n            fvec[i] = b[0]/b[1] * exp(-0.5*(x[i]-b[2])*(x[i]-b[2])/(b[1]*b[1])) - y[i];\n        return 0;\n    }\n    int df(const VectorXd &b, MatrixXd &fjac)\n    {\n        assert(b.size()==3);\n        assert(fjac.rows()==35);\n        assert(fjac.cols()==3);\n        for(int i=0; i<35; i++) {\n            double b12 = b[1]*b[1];\n            double e = exp(-0.5*(x[i]-b[2])*(x[i]-b[2])/b12);\n            fjac(i,0) = e / b[1];\n            fjac(i,1) = ((x[i]-b[2])*(x[i]-b[2])/b12-1.) * b[0]*e/b12;\n            fjac(i,2) = (x[i]-b[2])*e*b[0]/b[1]/b12;\n        }\n        return 0;\n    }\n};\nconst double eckerle4_functor::x[35] = { 400.0, 405.0, 410.0, 415.0, 420.0, 425.0, 430.0, 435.0, 436.5, 438.0, 439.5, 441.0, 442.5, 444.0, 445.5, 447.0, 448.5, 450.0, 451.5, 453.0, 454.5, 456.0, 457.5, 459.0, 460.5, 462.0, 463.5, 465.0, 470.0, 475.0, 480.0, 485.0, 490.0, 495.0, 500.0};\nconst double eckerle4_functor::y[35] = { 0.0001575, 0.0001699, 0.0002350, 0.0003102, 0.0004917, 0.0008710, 0.0017418, 0.0046400, 0.0065895, 0.0097302, 0.0149002, 0.0237310, 0.0401683, 0.0712559, 0.1264458, 0.2073413, 0.2902366, 0.3445623, 0.3698049, 0.3668534, 0.3106727, 0.2078154, 0.1164354, 0.0616764, 0.0337200, 0.0194023, 0.0117831, 0.0074357, 0.0022732, 0.0008800, 0.0004579, 0.0002345, 0.0001586, 0.0001143, 0.0000710 };\n\n// http://www.itl.nist.gov/div898/strd/nls/data/eckerle4.shtml\nvoid testNistEckerle4(void)\n{\n  const int n=3;\n  int info;\n\n  VectorXd x(n);\n\n  /*\n   * First try\n   */\n  x<< 1., 10., 500.;\n  // do the computation\n  eckerle4_functor functor;\n  LevenbergMarquardt<eckerle4_functor> lm(functor);\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 18);\n  VERIFY_IS_EQUAL(lm.njev(), 15);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 1.4635887487E-03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.5543827178);\n  VERIFY_IS_APPROX(x[1], 4.0888321754);\n  VERIFY_IS_APPROX(x[2], 4.5154121844E+02);\n\n  /*\n   * Second try\n   */\n  x<< 1.5, 5., 450.;\n  // do the computation\n  info = lm.minimize(x);\n\n  // check return value\n  VERIFY_IS_EQUAL(info, 1);\n  VERIFY_IS_EQUAL(lm.nfev(), 7);\n  VERIFY_IS_EQUAL(lm.njev(), 6);\n  // check norm^2\n  VERIFY_IS_APPROX(lm.fvec().squaredNorm(), 1.4635887487E-03);\n  // check x\n  VERIFY_IS_APPROX(x[0], 1.5543827178);\n  VERIFY_IS_APPROX(x[1], 4.0888321754);\n  VERIFY_IS_APPROX(x[2], 4.5154121844E+02);\n}\n\nEIGEN_DECLARE_TEST(levenberg_marquardt)\n{\n    // Tests using the examples provided by (c)minpack\n    CALL_SUBTEST(testLmder1());\n    CALL_SUBTEST(testLmder());\n    CALL_SUBTEST(testLmdif1());\n//     CALL_SUBTEST(testLmstr1());\n//     CALL_SUBTEST(testLmstr());\n    CALL_SUBTEST(testLmdif());\n\n    // NIST tests, level of difficulty = \"Lower\"\n    CALL_SUBTEST(testNistMisra1a());\n    CALL_SUBTEST(testNistChwirut2());\n\n    // NIST tests, level of difficulty = \"Average\"\n    CALL_SUBTEST(testNistHahn1());\n    CALL_SUBTEST(testNistMisra1d());\n    CALL_SUBTEST(testNistMGH17());\n    CALL_SUBTEST(testNistLanczos1());\n\n//     // NIST tests, level of difficulty = \"Higher\"\n    CALL_SUBTEST(testNistRat42());\n    CALL_SUBTEST(testNistMGH10());\n    CALL_SUBTEST(testNistBoxBOD());\n//     CALL_SUBTEST(testNistMGH09());\n    CALL_SUBTEST(testNistBennett5());\n    CALL_SUBTEST(testNistThurber());\n    CALL_SUBTEST(testNistRat43());\n    CALL_SUBTEST(testNistEckerle4());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/matrix_exponential.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"matrix_functions.h\"\n\ndouble binom(int n, int k)\n{\n  double res = 1;\n  for (int i=0; i<k; i++)\n    res = res * (n-k+i+1) / (i+1);\n  return res;\n}\n\ntemplate <typename T>\nT expfn(T x, int)\n{\n  return std::exp(x);\n}\n\ntemplate <typename T>\nvoid test2dRotation(double tol)\n{\n  Matrix<T,2,2> A, B, C;\n  T angle;\n\n  A << 0, 1, -1, 0;\n  for (int i=0; i<=20; i++)\n  {\n    angle = static_cast<T>(pow(10, i / 5. - 2));\n    B << std::cos(angle), std::sin(angle), -std::sin(angle), std::cos(angle);\n\n    C = (angle*A).matrixFunction(expfn);\n    std::cout << \"test2dRotation: i = \" << i << \"   error funm = \" << relerr(C, B);\n    VERIFY(C.isApprox(B, static_cast<T>(tol)));\n\n    C = (angle*A).exp();\n    std::cout << \"   error expm = \" << relerr(C, B) << \"\\n\";\n    VERIFY(C.isApprox(B, static_cast<T>(tol)));\n  }\n}\n\ntemplate <typename T>\nvoid test2dHyperbolicRotation(double tol)\n{\n  Matrix<std::complex<T>,2,2> A, B, C;\n  std::complex<T> imagUnit(0,1);\n  T angle, ch, sh;\n\n  for (int i=0; i<=20; i++)\n  {\n    angle = static_cast<T>((i-10) / 2.0);\n    ch = std::cosh(angle);\n    sh = std::sinh(angle);\n    A << 0, angle*imagUnit, -angle*imagUnit, 0;\n    B << ch, sh*imagUnit, -sh*imagUnit, ch;\n\n    C = A.matrixFunction(expfn);\n    std::cout << \"test2dHyperbolicRotation: i = \" << i << \"   error funm = \" << relerr(C, B);\n    VERIFY(C.isApprox(B, static_cast<T>(tol)));\n\n    C = A.exp();\n    std::cout << \"   error expm = \" << relerr(C, B) << \"\\n\";\n    VERIFY(C.isApprox(B, static_cast<T>(tol)));\n  }\n}\n\ntemplate <typename T>\nvoid testPascal(double tol)\n{\n  for (int size=1; size<20; size++)\n  {\n    Matrix<T,Dynamic,Dynamic> A(size,size), B(size,size), C(size,size);\n    A.setZero();\n    for (int i=0; i<size-1; i++)\n      A(i+1,i) = static_cast<T>(i+1);\n    B.setZero();\n    for (int i=0; i<size; i++)\n      for (int j=0; j<=i; j++)\n    B(i,j) = static_cast<T>(binom(i,j));\n\n    C = A.matrixFunction(expfn);\n    std::cout << \"testPascal: size = \" << size << \"   error funm = \" << relerr(C, B);\n    VERIFY(C.isApprox(B, static_cast<T>(tol)));\n\n    C = A.exp();\n    std::cout << \"   error expm = \" << relerr(C, B) << \"\\n\";\n    VERIFY(C.isApprox(B, static_cast<T>(tol)));\n  }\n}\n\ntemplate<typename MatrixType>\nvoid randomTest(const MatrixType& m, double tol)\n{\n  /* this test covers the following files:\n     Inverse.h\n  */\n  typename MatrixType::Index rows = m.rows();\n  typename MatrixType::Index cols = m.cols();\n  MatrixType m1(rows, cols), m2(rows, cols), identity = MatrixType::Identity(rows, cols);\n\n  typedef typename NumTraits<typename internal::traits<MatrixType>::Scalar>::Real RealScalar;\n\n  for(int i = 0; i < g_repeat; i++) {\n    m1 = MatrixType::Random(rows, cols);\n\n    m2 = m1.matrixFunction(expfn) * (-m1).matrixFunction(expfn);\n    std::cout << \"randomTest: error funm = \" << relerr(identity, m2);\n    VERIFY(identity.isApprox(m2, static_cast<RealScalar>(tol)));\n\n    m2 = m1.exp() * (-m1).exp();\n    std::cout << \"   error expm = \" << relerr(identity, m2) << \"\\n\";\n    VERIFY(identity.isApprox(m2, static_cast<RealScalar>(tol)));\n  }\n}\n\nEIGEN_DECLARE_TEST(matrix_exponential)\n{\n  CALL_SUBTEST_2(test2dRotation<double>(1e-13));\n  CALL_SUBTEST_1(test2dRotation<float>(2e-5));  // was 1e-5, relaxed for clang 2.8 / linux / x86-64\n  CALL_SUBTEST_8(test2dRotation<long double>(1e-13)); \n  CALL_SUBTEST_2(test2dHyperbolicRotation<double>(1e-14));\n  CALL_SUBTEST_1(test2dHyperbolicRotation<float>(1e-5));\n  CALL_SUBTEST_8(test2dHyperbolicRotation<long double>(1e-14));\n  CALL_SUBTEST_6(testPascal<float>(1e-6));\n  CALL_SUBTEST_5(testPascal<double>(1e-15));\n  CALL_SUBTEST_2(randomTest(Matrix2d(), 1e-13));\n  CALL_SUBTEST_7(randomTest(Matrix<double,3,3,RowMajor>(), 1e-13));\n  CALL_SUBTEST_3(randomTest(Matrix4cd(), 1e-13));\n  CALL_SUBTEST_4(randomTest(MatrixXd(8,8), 1e-13));\n  CALL_SUBTEST_1(randomTest(Matrix2f(), 1e-4));\n  CALL_SUBTEST_5(randomTest(Matrix3cf(), 1e-4));\n  CALL_SUBTEST_1(randomTest(Matrix4f(), 1e-4));\n  CALL_SUBTEST_6(randomTest(MatrixXf(8,8), 1e-4));\n  CALL_SUBTEST_9(randomTest(Matrix<long double,Dynamic,Dynamic>(7,7), 1e-13));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/matrix_function.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <unsupported/Eigen/MatrixFunctions>\n\n// Variant of VERIFY_IS_APPROX which uses absolute error instead of\n// relative error.\n#define VERIFY_IS_APPROX_ABS(a, b) VERIFY(test_isApprox_abs(a, b))\n\ntemplate<typename Type1, typename Type2>\ninline bool test_isApprox_abs(const Type1& a, const Type2& b)\n{\n  return ((a-b).array().abs() < test_precision<typename Type1::RealScalar>()).all();\n}\n\n\n// Returns a matrix with eigenvalues clustered around 0, 1 and 2.\ntemplate<typename MatrixType>\nMatrixType randomMatrixWithRealEivals(const Index size)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename MatrixType::RealScalar RealScalar;\n  MatrixType diag = MatrixType::Zero(size, size);\n  for (Index i = 0; i < size; ++i) {\n    diag(i, i) = Scalar(RealScalar(internal::random<int>(0,2)))\n      + internal::random<Scalar>() * Scalar(RealScalar(0.01));\n  }\n  MatrixType A = MatrixType::Random(size, size);\n  HouseholderQR<MatrixType> QRofA(A);\n  return QRofA.householderQ().inverse() * diag * QRofA.householderQ();\n}\n\ntemplate <typename MatrixType, int IsComplex = NumTraits<typename internal::traits<MatrixType>::Scalar>::IsComplex>\nstruct randomMatrixWithImagEivals\n{\n  // Returns a matrix with eigenvalues clustered around 0 and +/- i.\n  static MatrixType run(const Index size);\n};\n\n// Partial specialization for real matrices\ntemplate<typename MatrixType>\nstruct randomMatrixWithImagEivals<MatrixType, 0>\n{\n  static MatrixType run(const Index size)\n  {\n    typedef typename MatrixType::Scalar Scalar;\n    MatrixType diag = MatrixType::Zero(size, size);\n    Index i = 0;\n    while (i < size) {\n      Index randomInt = internal::random<Index>(-1, 1);\n      if (randomInt == 0 || i == size-1) {\n        diag(i, i) = internal::random<Scalar>() * Scalar(0.01);\n        ++i;\n      } else {\n        Scalar alpha = Scalar(randomInt) + internal::random<Scalar>() * Scalar(0.01);\n        diag(i, i+1) = alpha;\n        diag(i+1, i) = -alpha;\n        i += 2;\n      }\n    }\n    MatrixType A = MatrixType::Random(size, size);\n    HouseholderQR<MatrixType> QRofA(A);\n    return QRofA.householderQ().inverse() * diag * QRofA.householderQ();\n  }\n};\n\n// Partial specialization for complex matrices\ntemplate<typename MatrixType>\nstruct randomMatrixWithImagEivals<MatrixType, 1>\n{\n  static MatrixType run(const Index size)\n  {\n    typedef typename MatrixType::Scalar Scalar;\n    typedef typename MatrixType::RealScalar RealScalar;\n    const Scalar imagUnit(0, 1);\n    MatrixType diag = MatrixType::Zero(size, size);\n    for (Index i = 0; i < size; ++i) {\n      diag(i, i) = Scalar(RealScalar(internal::random<Index>(-1, 1))) * imagUnit\n        + internal::random<Scalar>() * Scalar(RealScalar(0.01));\n    }\n    MatrixType A = MatrixType::Random(size, size);\n    HouseholderQR<MatrixType> QRofA(A);\n    return QRofA.householderQ().inverse() * diag * QRofA.householderQ();\n  }\n};\n\n\ntemplate<typename MatrixType>\nvoid testMatrixExponential(const MatrixType& A)\n{\n  typedef typename internal::traits<MatrixType>::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef std::complex<RealScalar> ComplexScalar;\n\n  VERIFY_IS_APPROX(A.exp(), A.matrixFunction(internal::stem_function_exp<ComplexScalar>));\n}\n\ntemplate<typename MatrixType>\nvoid testMatrixLogarithm(const MatrixType& A)\n{\n  typedef typename internal::traits<MatrixType>::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  MatrixType scaledA;\n  RealScalar maxImagPartOfSpectrum = A.eigenvalues().imag().cwiseAbs().maxCoeff();\n  if (maxImagPartOfSpectrum >= RealScalar(0.9L * EIGEN_PI))\n    scaledA = A * RealScalar(0.9L * EIGEN_PI) / maxImagPartOfSpectrum;\n  else\n    scaledA = A;\n\n  // identity X.exp().log() = X only holds if Im(lambda) < pi for all eigenvalues of X\n  MatrixType expA = scaledA.exp();\n  MatrixType logExpA = expA.log();\n  VERIFY_IS_APPROX(logExpA, scaledA);\n}\n\ntemplate<typename MatrixType>\nvoid testHyperbolicFunctions(const MatrixType& A)\n{\n  // Need to use absolute error because of possible cancellation when\n  // adding/subtracting expA and expmA.\n  VERIFY_IS_APPROX_ABS(A.sinh(), (A.exp() - (-A).exp()) / 2);\n  VERIFY_IS_APPROX_ABS(A.cosh(), (A.exp() + (-A).exp()) / 2);\n}\n\ntemplate<typename MatrixType>\nvoid testGonioFunctions(const MatrixType& A)\n{\n  typedef typename MatrixType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n  typedef std::complex<RealScalar> ComplexScalar;\n  typedef Matrix<ComplexScalar, MatrixType::RowsAtCompileTime, \n                 MatrixType::ColsAtCompileTime, MatrixType::Options> ComplexMatrix;\n\n  ComplexScalar imagUnit(0,1);\n  ComplexScalar two(2,0);\n\n  ComplexMatrix Ac = A.template cast<ComplexScalar>();\n  \n  ComplexMatrix exp_iA = (imagUnit * Ac).exp();\n  ComplexMatrix exp_miA = (-imagUnit * Ac).exp();\n  \n  ComplexMatrix sinAc = A.sin().template cast<ComplexScalar>();\n  VERIFY_IS_APPROX_ABS(sinAc, (exp_iA - exp_miA) / (two*imagUnit));\n  \n  ComplexMatrix cosAc = A.cos().template cast<ComplexScalar>();\n  VERIFY_IS_APPROX_ABS(cosAc, (exp_iA + exp_miA) / 2);\n}\n\ntemplate<typename MatrixType>\nvoid testMatrix(const MatrixType& A)\n{\n  testMatrixExponential(A);\n  testMatrixLogarithm(A);\n  testHyperbolicFunctions(A);\n  testGonioFunctions(A);\n}\n\ntemplate<typename MatrixType>\nvoid testMatrixType(const MatrixType& m)\n{\n  // Matrices with clustered eigenvalue lead to different code paths\n  // in MatrixFunction.h and are thus useful for testing.\n\n  const Index size = m.rows();\n  for (int i = 0; i < g_repeat; i++) {\n    testMatrix(MatrixType::Random(size, size).eval());\n    testMatrix(randomMatrixWithRealEivals<MatrixType>(size));\n    testMatrix(randomMatrixWithImagEivals<MatrixType>::run(size));\n  }\n}\n\ntemplate<typename MatrixType>\nvoid testMapRef(const MatrixType& A)\n{\n  // Test if passing Ref and Map objects is possible\n  // (Regression test for Bug #1796)\n  Index size = A.rows();\n  MatrixType X; X.setRandom(size, size);\n  MatrixType Y(size,size);\n  Ref<      MatrixType> R(Y);\n  Ref<const MatrixType> Rc(X);\n  Map<      MatrixType> M(Y.data(), size, size);\n  Map<const MatrixType> Mc(X.data(), size, size);\n\n  X = X*X; // make sure sqrt is possible\n  Y = X.sqrt();\n  R = Rc.sqrt();\n  M = Mc.sqrt();\n  Y = X.exp();\n  R = Rc.exp();\n  M = Mc.exp();\n  X = Y; // make sure log is possible\n  Y = X.log();\n  R = Rc.log();\n  M = Mc.log();\n\n  Y = X.cos() + Rc.cos() + Mc.cos();\n  Y = X.sin() + Rc.sin() + Mc.sin();\n\n  Y = X.cosh() + Rc.cosh() + Mc.cosh();\n  Y = X.sinh() + Rc.sinh() + Mc.sinh();\n}\n\n\nEIGEN_DECLARE_TEST(matrix_function)\n{\n  CALL_SUBTEST_1(testMatrixType(Matrix<float,1,1>()));\n  CALL_SUBTEST_2(testMatrixType(Matrix3cf()));\n  CALL_SUBTEST_3(testMatrixType(MatrixXf(8,8)));\n  CALL_SUBTEST_4(testMatrixType(Matrix2d()));\n  CALL_SUBTEST_5(testMatrixType(Matrix<double,5,5,RowMajor>()));\n  CALL_SUBTEST_6(testMatrixType(Matrix4cd()));\n  CALL_SUBTEST_7(testMatrixType(MatrixXd(13,13)));\n\n  CALL_SUBTEST_1(testMapRef(Matrix<float,1,1>()));\n  CALL_SUBTEST_2(testMapRef(Matrix3cf()));\n  CALL_SUBTEST_3(testMapRef(MatrixXf(8,8)));\n  CALL_SUBTEST_7(testMapRef(MatrixXd(13,13)));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/matrix_functions.h",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2009-2011 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <unsupported/Eigen/MatrixFunctions>\n\n// For complex matrices, any matrix is fine.\ntemplate<typename MatrixType, int IsComplex = NumTraits<typename internal::traits<MatrixType>::Scalar>::IsComplex>\nstruct processTriangularMatrix\n{\n  static void run(MatrixType&, MatrixType&, const MatrixType&)\n  { }\n};\n\n// For real matrices, make sure none of the eigenvalues are negative.\ntemplate<typename MatrixType>\nstruct processTriangularMatrix<MatrixType,0>\n{\n  static void run(MatrixType& m, MatrixType& T, const MatrixType& U)\n  {\n    const Index size = m.cols();\n\n    for (Index i=0; i < size; ++i) {\n      if (i == size - 1 || T.coeff(i+1,i) == 0)\n        T.coeffRef(i,i) = std::abs(T.coeff(i,i));\n      else\n        ++i;\n    }\n    m = U * T * U.transpose();\n  }\n};\n\ntemplate <typename MatrixType, int IsComplex = NumTraits<typename internal::traits<MatrixType>::Scalar>::IsComplex>\nstruct generateTestMatrix;\n\ntemplate <typename MatrixType>\nstruct generateTestMatrix<MatrixType,0>\n{\n  static void run(MatrixType& result, typename MatrixType::Index size)\n  {\n    result = MatrixType::Random(size, size);\n    RealSchur<MatrixType> schur(result);\n    MatrixType T = schur.matrixT();\n    processTriangularMatrix<MatrixType>::run(result, T, schur.matrixU());\n  }\n};\n\ntemplate <typename MatrixType>\nstruct generateTestMatrix<MatrixType,1>\n{\n  static void run(MatrixType& result, typename MatrixType::Index size)\n  {\n    result = MatrixType::Random(size, size);\n  }\n};\n\ntemplate <typename Derived, typename OtherDerived>\ntypename Derived::RealScalar relerr(const MatrixBase<Derived>& A, const MatrixBase<OtherDerived>& B)\n{\n  return std::sqrt((A - B).cwiseAbs2().sum() / (std::min)(A.cwiseAbs2().sum(), B.cwiseAbs2().sum()));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/matrix_power.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012, 2013 Chen-Pang He <jdh8@ms63.hinet.net>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"matrix_functions.h\"\n\ntemplate<typename T>\nvoid test2dRotation(const T& tol)\n{\n  Matrix<T,2,2> A, B, C;\n  T angle, c, s;\n\n  A << 0, 1, -1, 0;\n  MatrixPower<Matrix<T,2,2> > Apow(A);\n\n  for (int i=0; i<=20; ++i) {\n    angle = std::pow(T(10), T(i-10) / T(5.));\n    c = std::cos(angle);\n    s = std::sin(angle);\n    B << c, s, -s, c;\n\n    C = Apow(std::ldexp(angle,1) / T(EIGEN_PI));\n    std::cout << \"test2dRotation: i = \" << i << \"   error powerm = \" << relerr(C,B) << '\\n';\n    VERIFY(C.isApprox(B, tol));\n  }\n}\n\ntemplate<typename T>\nvoid test2dHyperbolicRotation(const T& tol)\n{\n  Matrix<std::complex<T>,2,2> A, B, C;\n  T angle, ch = std::cosh((T)1);\n  std::complex<T> ish(0, std::sinh((T)1));\n\n  A << ch, ish, -ish, ch;\n  MatrixPower<Matrix<std::complex<T>,2,2> > Apow(A);\n\n  for (int i=0; i<=20; ++i) {\n    angle = std::ldexp(static_cast<T>(i-10), -1);\n    ch = std::cosh(angle);\n    ish = std::complex<T>(0, std::sinh(angle));\n    B << ch, ish, -ish, ch;\n\n    C = Apow(angle);\n    std::cout << \"test2dHyperbolicRotation: i = \" << i << \"   error powerm = \" << relerr(C,B) << '\\n';\n    VERIFY(C.isApprox(B, tol));\n  }\n}\n\ntemplate<typename T>\nvoid test3dRotation(const T& tol)\n{\n  Matrix<T,3,1> v;\n  T angle;\n\n  for (int i=0; i<=20; ++i) {\n    v = Matrix<T,3,1>::Random();\n    v.normalize();\n    angle = std::pow(T(10), T(i-10) / T(5.));\n    VERIFY(AngleAxis<T>(angle, v).matrix().isApprox(AngleAxis<T>(1,v).matrix().pow(angle), tol));\n  }\n}\n\ntemplate<typename MatrixType>\nvoid testGeneral(const MatrixType& m, const typename MatrixType::RealScalar& tol)\n{\n  typedef typename MatrixType::RealScalar RealScalar;\n  MatrixType m1, m2, m3, m4, m5;\n  RealScalar x, y;\n\n  for (int i=0; i < g_repeat; ++i) {\n    generateTestMatrix<MatrixType>::run(m1, m.rows());\n    MatrixPower<MatrixType> mpow(m1);\n\n    x = internal::random<RealScalar>();\n    y = internal::random<RealScalar>();\n    m2 = mpow(x);\n    m3 = mpow(y);\n\n    m4 = mpow(x+y);\n    m5.noalias() = m2 * m3;\n    VERIFY(m4.isApprox(m5, tol));\n\n    m4 = mpow(x*y);\n    m5 = m2.pow(y);\n    VERIFY(m4.isApprox(m5, tol));\n\n    m4 = (std::abs(x) * m1).pow(y);\n    m5 = std::pow(std::abs(x), y) * m3;\n    VERIFY(m4.isApprox(m5, tol));\n  }\n}\n\ntemplate<typename MatrixType>\nvoid testSingular(const MatrixType& m_const, const typename MatrixType::RealScalar& tol)\n{\n  // we need to pass by reference in order to prevent errors with\n  // MSVC for aligned data types ...\n  MatrixType& m = const_cast<MatrixType&>(m_const);\n\n  const int IsComplex = NumTraits<typename internal::traits<MatrixType>::Scalar>::IsComplex;\n  typedef typename internal::conditional<IsComplex, TriangularView<MatrixType,Upper>, const MatrixType&>::type TriangularType;\n  typename internal::conditional< IsComplex, ComplexSchur<MatrixType>, RealSchur<MatrixType> >::type schur;\n  MatrixType T;\n\n  for (int i=0; i < g_repeat; ++i) {\n    m.setRandom();\n    m.col(0).fill(0);\n\n    schur.compute(m);\n    T = schur.matrixT();\n    const MatrixType& U = schur.matrixU();\n    processTriangularMatrix<MatrixType>::run(m, T, U);\n    MatrixPower<MatrixType> mpow(m);\n\n    T = T.sqrt();\n    VERIFY(mpow(0.5L).isApprox(U * (TriangularType(T) * U.adjoint()), tol));\n\n    T = T.sqrt();\n    VERIFY(mpow(0.25L).isApprox(U * (TriangularType(T) * U.adjoint()), tol));\n\n    T = T.sqrt();\n    VERIFY(mpow(0.125L).isApprox(U * (TriangularType(T) * U.adjoint()), tol));\n  }\n}\n\ntemplate<typename MatrixType>\nvoid testLogThenExp(const MatrixType& m_const, const typename MatrixType::RealScalar& tol)\n{\n  // we need to pass by reference in order to prevent errors with\n  // MSVC for aligned data types ...\n  MatrixType& m = const_cast<MatrixType&>(m_const);\n\n  typedef typename MatrixType::Scalar Scalar;\n  Scalar x;\n\n  for (int i=0; i < g_repeat; ++i) {\n    generateTestMatrix<MatrixType>::run(m, m.rows());\n    x = internal::random<Scalar>();\n    VERIFY(m.pow(x).isApprox((x * m.log()).exp(), tol));\n  }\n}\n\ntypedef Matrix<double,3,3,RowMajor>         Matrix3dRowMajor;\ntypedef Matrix<long double,3,3>             Matrix3e;\ntypedef Matrix<long double,Dynamic,Dynamic> MatrixXe;\n \nEIGEN_DECLARE_TEST(matrix_power)\n{\n  CALL_SUBTEST_2(test2dRotation<double>(1e-13));\n  CALL_SUBTEST_1(test2dRotation<float>(2e-5f));  // was 1e-5, relaxed for clang 2.8 / linux / x86-64\n  CALL_SUBTEST_9(test2dRotation<long double>(1e-13L));\n  CALL_SUBTEST_2(test2dHyperbolicRotation<double>(1e-14));\n  CALL_SUBTEST_1(test2dHyperbolicRotation<float>(1e-5f));\n  CALL_SUBTEST_9(test2dHyperbolicRotation<long double>(1e-14L));\n\n  CALL_SUBTEST_10(test3dRotation<double>(1e-13));\n  CALL_SUBTEST_11(test3dRotation<float>(1e-5f));\n  CALL_SUBTEST_12(test3dRotation<long double>(1e-13L));\n\n  CALL_SUBTEST_2(testGeneral(Matrix2d(),         1e-13));\n  CALL_SUBTEST_7(testGeneral(Matrix3dRowMajor(), 1e-13));\n  CALL_SUBTEST_3(testGeneral(Matrix4cd(),        1e-13));\n  CALL_SUBTEST_4(testGeneral(MatrixXd(8,8),      2e-12));\n  CALL_SUBTEST_1(testGeneral(Matrix2f(),         1e-4f));\n  CALL_SUBTEST_5(testGeneral(Matrix3cf(),        1e-4f));\n  CALL_SUBTEST_8(testGeneral(Matrix4f(),         1e-4f));\n  CALL_SUBTEST_6(testGeneral(MatrixXf(2,2),      1e-3f)); // see bug 614\n  CALL_SUBTEST_9(testGeneral(MatrixXe(7,7),      1e-13L));\n  CALL_SUBTEST_10(testGeneral(Matrix3d(),        1e-13));\n  CALL_SUBTEST_11(testGeneral(Matrix3f(),        1e-4f));\n  CALL_SUBTEST_12(testGeneral(Matrix3e(),        1e-13L));\n\n  CALL_SUBTEST_2(testSingular(Matrix2d(),         1e-13));\n  CALL_SUBTEST_7(testSingular(Matrix3dRowMajor(), 1e-13));\n  CALL_SUBTEST_3(testSingular(Matrix4cd(),        1e-13));\n  CALL_SUBTEST_4(testSingular(MatrixXd(8,8),      2e-12));\n  CALL_SUBTEST_1(testSingular(Matrix2f(),         1e-4f));\n  CALL_SUBTEST_5(testSingular(Matrix3cf(),        1e-4f));\n  CALL_SUBTEST_8(testSingular(Matrix4f(),         1e-4f));\n  CALL_SUBTEST_6(testSingular(MatrixXf(2,2),      1e-3f));\n  CALL_SUBTEST_9(testSingular(MatrixXe(7,7),      1e-13L));\n  CALL_SUBTEST_10(testSingular(Matrix3d(),        1e-13));\n  CALL_SUBTEST_11(testSingular(Matrix3f(),        1e-4f));\n  CALL_SUBTEST_12(testSingular(Matrix3e(),        1e-13L));\n\n  CALL_SUBTEST_2(testLogThenExp(Matrix2d(),         1e-13));\n  CALL_SUBTEST_7(testLogThenExp(Matrix3dRowMajor(), 1e-13));\n  CALL_SUBTEST_3(testLogThenExp(Matrix4cd(),        1e-13));\n  CALL_SUBTEST_4(testLogThenExp(MatrixXd(8,8),      2e-12));\n  CALL_SUBTEST_1(testLogThenExp(Matrix2f(),         1e-4f));\n  CALL_SUBTEST_5(testLogThenExp(Matrix3cf(),        1e-4f));\n  CALL_SUBTEST_8(testLogThenExp(Matrix4f(),         1e-4f));\n  CALL_SUBTEST_6(testLogThenExp(MatrixXf(2,2),      1e-3f));\n  CALL_SUBTEST_9(testLogThenExp(MatrixXe(7,7),      1e-13L));\n  CALL_SUBTEST_10(testLogThenExp(Matrix3d(),        1e-13));\n  CALL_SUBTEST_11(testLogThenExp(Matrix3f(),        1e-4f));\n  CALL_SUBTEST_12(testLogThenExp(Matrix3e(),        1e-13L));\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/matrix_square_root.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2011 Jitse Niesen <jitse@maths.leeds.ac.uk>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"matrix_functions.h\"\n\ntemplate<typename MatrixType>\nvoid testMatrixSqrt(const MatrixType& m)\n{\n  MatrixType A;\n  generateTestMatrix<MatrixType>::run(A, m.rows());\n  MatrixType sqrtA = A.sqrt();\n  VERIFY_IS_APPROX(sqrtA * sqrtA, A);\n}\n\nEIGEN_DECLARE_TEST(matrix_square_root)\n{\n  for (int i = 0; i < g_repeat; i++) {\n    CALL_SUBTEST_1(testMatrixSqrt(Matrix3cf()));\n    CALL_SUBTEST_2(testMatrixSqrt(MatrixXcd(12,12)));\n    CALL_SUBTEST_3(testMatrixSqrt(Matrix4f()));\n    CALL_SUBTEST_4(testMatrixSqrt(Matrix<double,Dynamic,Dynamic,RowMajor>(9, 9)));\n    CALL_SUBTEST_5(testMatrixSqrt(Matrix<float,1,1>()));\n    CALL_SUBTEST_5(testMatrixSqrt(Matrix<std::complex<float>,1,1>()));\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/minres.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2012 Giacomo Po <gpo@ucla.edu>\n// Copyright (C) 2011 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n#include <cmath>\n\n#include \"../../test/sparse_solver.h\"\n#include <Eigen/IterativeSolvers>\n\ntemplate<typename T> void test_minres_T()\n{\n  // Identity preconditioner\n  MINRES<SparseMatrix<T>, Lower, IdentityPreconditioner    > minres_colmajor_lower_I;\n  MINRES<SparseMatrix<T>, Upper, IdentityPreconditioner    > minres_colmajor_upper_I;\n\n  // Diagonal preconditioner\n  MINRES<SparseMatrix<T>, Lower, DiagonalPreconditioner<T> > minres_colmajor_lower_diag;\n  MINRES<SparseMatrix<T>, Upper, DiagonalPreconditioner<T> > minres_colmajor_upper_diag;\n  MINRES<SparseMatrix<T>, Lower|Upper, DiagonalPreconditioner<T> > minres_colmajor_uplo_diag;\n  \n  // call tests for SPD matrix\n  CALL_SUBTEST( check_sparse_spd_solving(minres_colmajor_lower_I) );\n  CALL_SUBTEST( check_sparse_spd_solving(minres_colmajor_upper_I) );\n    \n  CALL_SUBTEST( check_sparse_spd_solving(minres_colmajor_lower_diag)  );\n  CALL_SUBTEST( check_sparse_spd_solving(minres_colmajor_upper_diag)  );\n  CALL_SUBTEST( check_sparse_spd_solving(minres_colmajor_uplo_diag)  );\n    \n  // TO DO: symmetric semi-definite matrix\n  // TO DO: symmetric indefinite matrix\n\n}\n\nEIGEN_DECLARE_TEST(minres)\n{\n  CALL_SUBTEST_1(test_minres_T<double>());\n//  CALL_SUBTEST_2(test_minres_T<std::compex<double> >());\n\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/mpreal/mpreal.h",
    "content": "/*\n    MPFR C++: Multi-precision floating point number class for C++. \n    Based on MPFR library:    http://mpfr.org\n\n    Project homepage:    http://www.holoborodko.com/pavel/mpfr\n    Contact e-mail:      pavel@holoborodko.com\n\n    Copyright (c) 2008-2016 Pavel Holoborodko\n\n    Contributors:\n    Dmitriy Gubanov, Konstantin Holoborodko, Brian Gladman, \n    Helmut Jarausch, Fokko Beekhof, Ulrich Mutze, Heinz van Saanen, \n    Pere Constans, Peter van Hoof, Gael Guennebaud, Tsai Chia Cheng, \n    Alexei Zubanov, Jauhien Piatlicki, Victor Berger, John Westwood,\n    Petr Aleksandrov, Orion Poplawski, Charles Karney, Arash Partow,\n    Rodney James, Jorge Leitao, Jerome Benoit.\n\n    Licensing:\n    (A) MPFR C++ is under GNU General Public License (\"GPL\").\n    \n    (B) Non-free licenses may also be purchased from the author, for users who \n        do not want their programs protected by the GPL.\n\n        The non-free licenses are for users that wish to use MPFR C++ in \n        their products but are unwilling to release their software \n        under the GPL (which would require them to release source code \n        and allow free redistribution).\n\n        Such users can purchase an unlimited-use license from the author.\n        Contact us for more details.\n    \n    GNU General Public License (\"GPL\") copyright permissions statement:\n    **************************************************************************\n    This program is free software: you can redistribute it and/or modify\n    it under the terms of the GNU General Public License as published by\n    the Free Software Foundation, either version 3 of the License, or\n    (at your option) any later version.\n\n    This program is distributed in the hope that it will be useful,\n    but WITHOUT ANY WARRANTY; without even the implied warranty of\n    MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the\n    GNU General Public License for more details.\n\n    You should have received a copy of the GNU General Public License\n    along with this program.  If not, see <http://www.gnu.org/licenses/>.\n*/\n\n#ifndef __MPREAL_H__\n#define __MPREAL_H__\n\n#include <string>\n#include <iostream>\n#include <sstream>\n#include <stdexcept>\n#include <cfloat>\n#include <cmath>\n#include <cstring>\n#include <limits>\n#include <complex>\n#include <algorithm>\n#include <stdint.h>\n\n// Options\n#define MPREAL_HAVE_MSVC_DEBUGVIEW              // Enable Debugger Visualizer for \"Debug\" builds in MSVC.\n#define MPREAL_HAVE_DYNAMIC_STD_NUMERIC_LIMITS  // Enable extended std::numeric_limits<mpfr::mpreal> specialization.\n                                                // Meaning that \"digits\", \"round_style\" and similar members are defined as functions, not constants.\n                                                // See std::numeric_limits<mpfr::mpreal> at the end of the file for more information.\n\n// Library version\n#define MPREAL_VERSION_MAJOR 3\n#define MPREAL_VERSION_MINOR 6\n#define MPREAL_VERSION_PATCHLEVEL 5\n#define MPREAL_VERSION_STRING \"3.6.5\"\n\n// Detect compiler using signatures from http://predef.sourceforge.net/\n#if defined(__GNUC__) && defined(__INTEL_COMPILER)\n    #define IsInf(x) isinf EIGEN_NOT_A_MACRO (x)                   // Intel ICC compiler on Linux \n\n#elif defined(_MSC_VER)                         // Microsoft Visual C++ \n    #define IsInf(x) (!_finite(x))                           \n\n#else\n    #define IsInf(x) std::isinf EIGEN_NOT_A_MACRO  (x)              // GNU C/C++ (and/or other compilers), just hope for C99 conformance\n#endif\n\n// A Clang feature extension to determine compiler features.\n#ifndef __has_feature\n    #define __has_feature(x) 0\n#endif\n\n// Detect support for r-value references (move semantic).\n// Move semantic should be enabled with great care in multi-threading environments,\n// especially if MPFR uses custom memory allocators.\n// Everything should be thread-safe and support passing ownership over thread boundary.\n#if (__has_feature(cxx_rvalue_references) || \\\n       defined(__GXX_EXPERIMENTAL_CXX0X__) || __cplusplus >= 201103L || \\\n      (defined(_MSC_VER) && _MSC_VER >= 1600) && !defined(MPREAL_DISABLE_MOVE_SEMANTIC))\n\n    #define MPREAL_HAVE_MOVE_SUPPORT\n\n    // Use fields in mpfr_t structure to check if it was initialized / set dummy initialization \n    #define mpfr_is_initialized(x)      (0 != (x)->_mpfr_d)\n    #define mpfr_set_uninitialized(x)   ((x)->_mpfr_d = 0 )\n#endif\n\n// Detect support for explicit converters. \n#if (__has_feature(cxx_explicit_conversions) || \\\n       (defined(__GXX_EXPERIMENTAL_CXX0X__) && __GNUC_MINOR__ >= 5) || __cplusplus >= 201103L || \\\n       (defined(_MSC_VER) && _MSC_VER >= 1800) || \\\n       (defined(__INTEL_COMPILER) && __INTEL_COMPILER >= 1300))\n\n    #define MPREAL_HAVE_EXPLICIT_CONVERTERS\n#endif\n\n#define MPFR_USE_INTMAX_T   // Enable 64-bit integer types - should be defined before mpfr.h\n\n#if defined(MPREAL_HAVE_MSVC_DEBUGVIEW) && defined(_MSC_VER) && defined(_DEBUG)\n    #define MPREAL_MSVC_DEBUGVIEW_CODE     DebugView = toString();\n    #define MPREAL_MSVC_DEBUGVIEW_DATA     std::string DebugView;\n#else\n    #define MPREAL_MSVC_DEBUGVIEW_CODE \n    #define MPREAL_MSVC_DEBUGVIEW_DATA \n#endif\n\n#include <mpfr.h>\n\n#if (MPFR_VERSION < MPFR_VERSION_NUM(3,0,0))\n    #include <cstdlib>                          // Needed for random()\n#endif\n\n// Less important options\n#define MPREAL_DOUBLE_BITS_OVERFLOW -1          // Triggers overflow exception during conversion to double if mpreal \n                                                // cannot fit in MPREAL_DOUBLE_BITS_OVERFLOW bits\n                                                // = -1 disables overflow checks (default)\n\n// Fast replacement for mpfr_set_zero(x, +1):\n// (a) uses low-level data members, might not be forward compatible\n// (b) sign is not set, add (x)->_mpfr_sign = 1;\n#define mpfr_set_zero_fast(x)  ((x)->_mpfr_exp = __MPFR_EXP_ZERO)\n\n#if defined(__GNUC__)\n  #define MPREAL_PERMISSIVE_EXPR __extension__\n#else\n  #define MPREAL_PERMISSIVE_EXPR\n#endif\n\nnamespace mpfr {\n\nclass mpreal {\nprivate:\n    mpfr_t mp;\n    \npublic:\n    \n    // Get default rounding mode & precision\n    inline static mp_rnd_t   get_default_rnd()    {    return (mp_rnd_t)(mpfr_get_default_rounding_mode());       }\n    inline static mp_prec_t  get_default_prec()   {    return (mpfr_get_default_prec)();                          }\n\n    // Constructors && type conversions\n    mpreal();\n    mpreal(const mpreal& u);\n    mpreal(const mpf_t u);    \n    mpreal(const mpz_t u,                  mp_prec_t prec = mpreal::get_default_prec(), mp_rnd_t mode = mpreal::get_default_rnd());    \n    mpreal(const mpq_t u,                  mp_prec_t prec = mpreal::get_default_prec(), mp_rnd_t mode = mpreal::get_default_rnd());    \n    mpreal(const double u,                 mp_prec_t prec = mpreal::get_default_prec(), mp_rnd_t mode = mpreal::get_default_rnd());\n    mpreal(const long double u,            mp_prec_t prec = mpreal::get_default_prec(), mp_rnd_t mode = mpreal::get_default_rnd());\n    mpreal(const unsigned long long int u, mp_prec_t prec = mpreal::get_default_prec(), mp_rnd_t mode = mpreal::get_default_rnd());\n    mpreal(const long long int u,          mp_prec_t prec = mpreal::get_default_prec(), mp_rnd_t mode = mpreal::get_default_rnd());\n    mpreal(const unsigned long int u,      mp_prec_t prec = mpreal::get_default_prec(), mp_rnd_t mode = mpreal::get_default_rnd());\n    mpreal(const unsigned int u,           mp_prec_t prec = mpreal::get_default_prec(), mp_rnd_t mode = mpreal::get_default_rnd());\n    mpreal(const long int u,               mp_prec_t prec = mpreal::get_default_prec(), mp_rnd_t mode = mpreal::get_default_rnd());\n    mpreal(const int u,                    mp_prec_t prec = mpreal::get_default_prec(), mp_rnd_t mode = mpreal::get_default_rnd());\n    \n    // Construct mpreal from mpfr_t structure.\n    // shared = true allows to avoid deep copy, so that mpreal and 'u' share the same data & pointers.    \n    mpreal(const mpfr_t  u, bool shared = false);   \n\n    mpreal(const char* s,             mp_prec_t prec = mpreal::get_default_prec(), int base = 10, mp_rnd_t mode = mpreal::get_default_rnd());\n    mpreal(const std::string& s,      mp_prec_t prec = mpreal::get_default_prec(), int base = 10, mp_rnd_t mode = mpreal::get_default_rnd());\n\n    ~mpreal();                           \n\n#ifdef MPREAL_HAVE_MOVE_SUPPORT\n    mpreal& operator=(mpreal&& v);\n    mpreal(mpreal&& u);\n#endif\n\n    // Operations\n    // =\n    // +, -, *, /, ++, --, <<, >> \n    // *=, +=, -=, /=,\n    // <, >, ==, <=, >=\n\n    // =\n    mpreal& operator=(const mpreal& v);\n    mpreal& operator=(const mpf_t v);\n    mpreal& operator=(const mpz_t v);\n    mpreal& operator=(const mpq_t v);\n    mpreal& operator=(const long double v);\n    mpreal& operator=(const double v);        \n    mpreal& operator=(const unsigned long int v);\n    mpreal& operator=(const unsigned long long int v);\n    mpreal& operator=(const long long int v);\n    mpreal& operator=(const unsigned int v);\n    mpreal& operator=(const long int v);\n    mpreal& operator=(const int v);\n    mpreal& operator=(const char* s);\n    mpreal& operator=(const std::string& s);\n    template <typename real_t> mpreal& operator= (const std::complex<real_t>& z);\n\n    // +\n    mpreal& operator+=(const mpreal& v);\n    mpreal& operator+=(const mpf_t v);\n    mpreal& operator+=(const mpz_t v);\n    mpreal& operator+=(const mpq_t v);\n    mpreal& operator+=(const long double u);\n    mpreal& operator+=(const double u);\n    mpreal& operator+=(const unsigned long int u);\n    mpreal& operator+=(const unsigned int u);\n    mpreal& operator+=(const long int u);\n    mpreal& operator+=(const int u);\n\n    mpreal& operator+=(const long long int  u);\n    mpreal& operator+=(const unsigned long long int u);\n    mpreal& operator-=(const long long int  u);\n    mpreal& operator-=(const unsigned long long int u);\n    mpreal& operator*=(const long long int  u);\n    mpreal& operator*=(const unsigned long long int u);\n    mpreal& operator/=(const long long int  u);\n    mpreal& operator/=(const unsigned long long int u);\n\n    const mpreal operator+() const;\n    mpreal& operator++ ();\n    const mpreal  operator++ (int); \n\n    // -\n    mpreal& operator-=(const mpreal& v);\n    mpreal& operator-=(const mpz_t v);\n    mpreal& operator-=(const mpq_t v);\n    mpreal& operator-=(const long double u);\n    mpreal& operator-=(const double u);\n    mpreal& operator-=(const unsigned long int u);\n    mpreal& operator-=(const unsigned int u);\n    mpreal& operator-=(const long int u);\n    mpreal& operator-=(const int u);\n    const mpreal operator-() const;\n    friend const mpreal operator-(const unsigned long int b, const mpreal& a);\n    friend const mpreal operator-(const unsigned int b,      const mpreal& a);\n    friend const mpreal operator-(const long int b,          const mpreal& a);\n    friend const mpreal operator-(const int b,               const mpreal& a);\n    friend const mpreal operator-(const double b,            const mpreal& a);\n    mpreal& operator-- ();    \n    const mpreal  operator-- (int);\n\n    // *\n    mpreal& operator*=(const mpreal& v);\n    mpreal& operator*=(const mpz_t v);\n    mpreal& operator*=(const mpq_t v);\n    mpreal& operator*=(const long double v);\n    mpreal& operator*=(const double v);\n    mpreal& operator*=(const unsigned long int v);\n    mpreal& operator*=(const unsigned int v);\n    mpreal& operator*=(const long int v);\n    mpreal& operator*=(const int v);\n    \n    // /\n    mpreal& operator/=(const mpreal& v);\n    mpreal& operator/=(const mpz_t v);\n    mpreal& operator/=(const mpq_t v);\n    mpreal& operator/=(const long double v);\n    mpreal& operator/=(const double v);\n    mpreal& operator/=(const unsigned long int v);\n    mpreal& operator/=(const unsigned int v);\n    mpreal& operator/=(const long int v);\n    mpreal& operator/=(const int v);\n    friend const mpreal operator/(const unsigned long int b, const mpreal& a);\n    friend const mpreal operator/(const unsigned int b,      const mpreal& a);\n    friend const mpreal operator/(const long int b,          const mpreal& a);\n    friend const mpreal operator/(const int b,               const mpreal& a);\n    friend const mpreal operator/(const double b,            const mpreal& a);\n\n    //<<= Fast Multiplication by 2^u\n    mpreal& operator<<=(const unsigned long int u);\n    mpreal& operator<<=(const unsigned int u);\n    mpreal& operator<<=(const long int u);\n    mpreal& operator<<=(const int u);\n\n    //>>= Fast Division by 2^u\n    mpreal& operator>>=(const unsigned long int u);\n    mpreal& operator>>=(const unsigned int u);\n    mpreal& operator>>=(const long int u);\n    mpreal& operator>>=(const int u);\n\n    // Type Conversion operators\n    bool               toBool      (                        )    const;\n    long               toLong      (mp_rnd_t mode = GMP_RNDZ)    const;\n    unsigned long      toULong     (mp_rnd_t mode = GMP_RNDZ)    const;\n    long long          toLLong     (mp_rnd_t mode = GMP_RNDZ)    const;\n    unsigned long long toULLong    (mp_rnd_t mode = GMP_RNDZ)    const;\n    float              toFloat     (mp_rnd_t mode = GMP_RNDN)    const;\n    double             toDouble    (mp_rnd_t mode = GMP_RNDN)    const;\n    long double        toLDouble   (mp_rnd_t mode = GMP_RNDN)    const;\n\n#if defined (MPREAL_HAVE_EXPLICIT_CONVERTERS)\n    explicit operator bool               () const { return toBool();                 }\n    explicit operator int                () const { return int(toLong());            }\n    explicit operator long               () const { return toLong();                 }\n    explicit operator long long          () const { return toLLong();                }\n    explicit operator unsigned           () const { return unsigned(toULong());      }\n    explicit operator unsigned long      () const { return toULong();                }\n    explicit operator unsigned long long () const { return toULLong();               }\n    explicit operator float              () const { return toFloat();                }\n    explicit operator double             () const { return toDouble();               }\n    explicit operator long double        () const { return toLDouble();              }\n#endif\n\n    // Get raw pointers so that mpreal can be directly used in raw mpfr_* functions\n    ::mpfr_ptr    mpfr_ptr();\n    ::mpfr_srcptr mpfr_ptr()    const;\n    ::mpfr_srcptr mpfr_srcptr() const;\n\n    // Convert mpreal to string with n significant digits in base b\n    // n = -1 -> convert with the maximum available digits\n    std::string toString(int n = -1, int b = 10, mp_rnd_t mode = mpreal::get_default_rnd()) const;\n\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(2,4,0))\n    std::string toString(const std::string& format) const;\n#endif\n\n    std::ostream& output(std::ostream& os) const;\n\n    // Math Functions\n    friend const mpreal sqr (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal sqrt(const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal sqrt(const unsigned long int v, mp_rnd_t rnd_mode);\n    friend const mpreal cbrt(const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal root(const mpreal& v, unsigned long int k, mp_rnd_t rnd_mode);\n    friend const mpreal pow (const mpreal& a, const mpreal& b, mp_rnd_t rnd_mode);\n    friend const mpreal pow (const mpreal& a, const mpz_t b, mp_rnd_t rnd_mode);\n    friend const mpreal pow (const mpreal& a, const unsigned long int b, mp_rnd_t rnd_mode);\n    friend const mpreal pow (const mpreal& a, const long int b, mp_rnd_t rnd_mode);\n    friend const mpreal pow (const unsigned long int a, const mpreal& b, mp_rnd_t rnd_mode);\n    friend const mpreal pow (const unsigned long int a, const unsigned long int b, mp_rnd_t rnd_mode);\n    friend const mpreal fabs(const mpreal& v, mp_rnd_t rnd_mode);\n\n    friend const mpreal abs(const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal dim(const mpreal& a, const mpreal& b, mp_rnd_t rnd_mode);\n    friend inline const mpreal mul_2ui(const mpreal& v, unsigned long int k, mp_rnd_t rnd_mode);\n    friend inline const mpreal mul_2si(const mpreal& v, long int k, mp_rnd_t rnd_mode);\n    friend inline const mpreal div_2ui(const mpreal& v, unsigned long int k, mp_rnd_t rnd_mode);\n    friend inline const mpreal div_2si(const mpreal& v, long int k, mp_rnd_t rnd_mode);\n    friend int cmpabs(const mpreal& a,const mpreal& b);\n    \n    friend const mpreal log  (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal log2 (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal logb (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal log10(const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal exp  (const mpreal& v, mp_rnd_t rnd_mode); \n    friend const mpreal exp2 (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal exp10(const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal log1p(const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal expm1(const mpreal& v, mp_rnd_t rnd_mode);\n\n    friend const mpreal nextpow2(const mpreal& v, mp_rnd_t rnd_mode);\n\n    friend const mpreal cos(const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal sin(const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal tan(const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal sec(const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal csc(const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal cot(const mpreal& v, mp_rnd_t rnd_mode);\n    friend int sin_cos(mpreal& s, mpreal& c, const mpreal& v, mp_rnd_t rnd_mode);\n\n    friend const mpreal acos  (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal asin  (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal atan  (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal atan2 (const mpreal& y, const mpreal& x, mp_rnd_t rnd_mode);\n    friend const mpreal acot  (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal asec  (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal acsc  (const mpreal& v, mp_rnd_t rnd_mode);\n\n    friend const mpreal cosh  (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal sinh  (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal tanh  (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal sech  (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal csch  (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal coth  (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal acosh (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal asinh (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal atanh (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal acoth (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal asech (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal acsch (const mpreal& v, mp_rnd_t rnd_mode);\n\n    friend const mpreal hypot (const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode);\n\n    friend const mpreal fac_ui (unsigned long int v,  mp_prec_t prec, mp_rnd_t rnd_mode);\n    friend const mpreal eint   (const mpreal& v, mp_rnd_t rnd_mode);\n\n    friend const mpreal gamma    (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal tgamma   (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal lngamma  (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal lgamma   (const mpreal& v, int *signp, mp_rnd_t rnd_mode);\n    friend const mpreal zeta     (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal erf      (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal erfc     (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal besselj0 (const mpreal& v, mp_rnd_t rnd_mode); \n    friend const mpreal besselj1 (const mpreal& v, mp_rnd_t rnd_mode); \n    friend const mpreal besseljn (long n, const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal bessely0 (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal bessely1 (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal besselyn (long n, const mpreal& v, mp_rnd_t rnd_mode); \n    friend const mpreal fma      (const mpreal& v1, const mpreal& v2, const mpreal& v3, mp_rnd_t rnd_mode);\n    friend const mpreal fms      (const mpreal& v1, const mpreal& v2, const mpreal& v3, mp_rnd_t rnd_mode);\n    friend const mpreal agm      (const mpreal& v1, const mpreal& v2, mp_rnd_t rnd_mode);\n    friend const mpreal sum      (const mpreal tab[], const unsigned long int n, int& status, mp_rnd_t rnd_mode);\n    friend int          sgn      (const mpreal& v);\n\n// MPFR 2.4.0 Specifics\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(2,4,0))\n    friend int          sinh_cosh   (mpreal& s, mpreal& c, const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal li2         (const mpreal& v,                       mp_rnd_t rnd_mode);\n    friend const mpreal fmod        (const mpreal& x, const mpreal& y,      mp_rnd_t rnd_mode);\n    friend const mpreal rec_sqrt    (const mpreal& v,                       mp_rnd_t rnd_mode);\n\n    // MATLAB's semantic equivalents\n    friend const mpreal rem (const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode); // Remainder after division\n    friend const mpreal mod (const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode); // Modulus after division\n#endif\n\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(3,0,0))\n    friend const mpreal digamma (const mpreal& v,        mp_rnd_t rnd_mode);\n    friend const mpreal ai      (const mpreal& v,        mp_rnd_t rnd_mode);\n    friend const mpreal urandom (gmp_randstate_t& state, mp_rnd_t rnd_mode);     // use gmp_randinit_default() to init state, gmp_randclear() to clear\n#endif\n\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(3,1,0))\n    friend const mpreal grandom (gmp_randstate_t& state, mp_rnd_t rnd_mode);     // use gmp_randinit_default() to init state, gmp_randclear() to clear\n    friend const mpreal grandom (unsigned int seed);\n#endif\n\n    // Uniformly distributed random number generation in [0,1] using\n    // Mersenne-Twister algorithm by default.\n    // Use parameter to setup seed, e.g.: random((unsigned)time(NULL))\n    // Check urandom() for more precise control.\n    friend const mpreal random(unsigned int seed);\n\n    // Splits mpreal value into fractional and integer parts.\n    // Returns fractional part and stores integer part in n.\n    friend const mpreal modf(const mpreal& v, mpreal& n);    \n\n    // Constants\n    // don't forget to call mpfr_free_cache() for every thread where you are using const-functions\n    friend const mpreal const_log2      (mp_prec_t prec, mp_rnd_t rnd_mode);\n    friend const mpreal const_pi        (mp_prec_t prec, mp_rnd_t rnd_mode);\n    friend const mpreal const_euler     (mp_prec_t prec, mp_rnd_t rnd_mode);\n    friend const mpreal const_catalan   (mp_prec_t prec, mp_rnd_t rnd_mode);\n\n    // returns +inf iff sign>=0 otherwise -inf\n    friend const mpreal const_infinity(int sign, mp_prec_t prec);\n\n    // Output/ Input\n    friend std::ostream& operator<<(std::ostream& os, const mpreal& v);\n    friend std::istream& operator>>(std::istream& is, mpreal& v);\n\n    // Integer Related Functions\n    friend const mpreal rint (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal ceil (const mpreal& v);\n    friend const mpreal floor(const mpreal& v);\n    friend const mpreal round(const mpreal& v);\n    friend const mpreal trunc(const mpreal& v);\n    friend const mpreal rint_ceil   (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal rint_floor  (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal rint_round  (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal rint_trunc  (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal frac        (const mpreal& v, mp_rnd_t rnd_mode);\n    friend const mpreal remainder   (         const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode);\n    friend const mpreal remquo      (long* q, const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode);\n    \n    // Miscellaneous Functions\n    friend const mpreal nexttoward (const mpreal& x, const mpreal& y);\n    friend const mpreal nextabove  (const mpreal& x);\n    friend const mpreal nextbelow  (const mpreal& x);\n\n    // use gmp_randinit_default() to init state, gmp_randclear() to clear\n    friend const mpreal urandomb (gmp_randstate_t& state); \n\n// MPFR < 2.4.2 Specifics\n#if (MPFR_VERSION <= MPFR_VERSION_NUM(2,4,2))\n    friend const mpreal random2 (mp_size_t size, mp_exp_t exp);\n#endif\n\n    // Instance Checkers\n    friend bool isnan EIGEN_NOT_A_MACRO     (const mpreal& v);\n    friend bool (isinf)    (const mpreal& v);\n    friend bool (isfinite) (const mpreal& v);\n\n    friend bool isnum    (const mpreal& v);\n    friend bool iszero   (const mpreal& v);\n    friend bool isint    (const mpreal& v);\n\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(3,0,0))\n    friend bool isregular(const mpreal& v);\n#endif\n\n    // Set/Get instance properties\n    inline mp_prec_t    get_prec() const;\n    inline void         set_prec(mp_prec_t prec, mp_rnd_t rnd_mode = get_default_rnd());    // Change precision with rounding mode\n\n    // Aliases for get_prec(), set_prec() - needed for compatibility with std::complex<mpreal> interface\n    inline mpreal&      setPrecision(int Precision, mp_rnd_t RoundingMode = get_default_rnd());\n    inline int          getPrecision() const;\n    \n    // Set mpreal to +/- inf, NaN, +/-0\n    mpreal&        setInf  (int Sign = +1);    \n    mpreal&        setNan  ();\n    mpreal&        setZero (int Sign = +1);\n    mpreal&        setSign (int Sign, mp_rnd_t RoundingMode = get_default_rnd());\n\n    //Exponent\n    mp_exp_t get_exp() const;\n    int set_exp(mp_exp_t e);\n    int check_range  (int t, mp_rnd_t rnd_mode = get_default_rnd());\n    int subnormalize (int t, mp_rnd_t rnd_mode = get_default_rnd());\n\n    // Inexact conversion from float\n    inline bool fits_in_bits(double x, int n);\n\n    // Set/Get global properties\n    static void            set_default_prec(mp_prec_t prec);\n    static void            set_default_rnd(mp_rnd_t rnd_mode);\n\n    static mp_exp_t  get_emin (void);\n    static mp_exp_t  get_emax (void);\n    static mp_exp_t  get_emin_min (void);\n    static mp_exp_t  get_emin_max (void);\n    static mp_exp_t  get_emax_min (void);\n    static mp_exp_t  get_emax_max (void);\n    static int       set_emin (mp_exp_t exp);\n    static int       set_emax (mp_exp_t exp);\n\n    // Efficient swapping of two mpreal values - needed for std algorithms\n    friend void swap(mpreal& x, mpreal& y);\n    \n    friend const mpreal fmax(const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode);\n    friend const mpreal fmin(const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode);\n\nprivate:\n    // Human friendly Debug Preview in Visual Studio.\n    // Put one of these lines:\n    //\n    // mpfr::mpreal=<DebugView>                              ; Show value only\n    // mpfr::mpreal=<DebugView>, <mp[0]._mpfr_prec,u>bits    ; Show value & precision\n    // \n    // at the beginning of\n    // [Visual Studio Installation Folder]\\Common7\\Packages\\Debugger\\autoexp.dat\n    MPREAL_MSVC_DEBUGVIEW_DATA\n\n    // \"Smart\" resources deallocation. Checks if instance initialized before deletion.\n    void clear(::mpfr_ptr);\n};\n\n//////////////////////////////////////////////////////////////////////////\n// Exceptions\nclass conversion_overflow : public std::exception {\npublic:\n    std::string why() { return \"inexact conversion from floating point\"; }\n};\n\n//////////////////////////////////////////////////////////////////////////\n// Constructors & converters\n// Default constructor: creates mp number and initializes it to 0.\ninline mpreal::mpreal() \n{ \n    mpfr_init2(mpfr_ptr(), mpreal::get_default_prec()); \n    mpfr_set_zero_fast(mpfr_ptr());\n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n}\n\ninline mpreal::mpreal(const mpreal& u) \n{\n    mpfr_init2(mpfr_ptr(),mpfr_get_prec(u.mpfr_srcptr()));\n    mpfr_set  (mpfr_ptr(),u.mpfr_srcptr(),mpreal::get_default_rnd());\n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n}\n\n#ifdef MPREAL_HAVE_MOVE_SUPPORT\ninline mpreal::mpreal(mpreal&& other)\n{\n    mpfr_set_uninitialized(mpfr_ptr());      // make sure \"other\" holds null-pointer (in uninitialized state)\n    mpfr_swap(mpfr_ptr(), other.mpfr_ptr());\n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n}\n\ninline mpreal& mpreal::operator=(mpreal&& other)\n{\n    if (this != &other)\n    {\n        mpfr_swap(mpfr_ptr(), other.mpfr_ptr()); // destructor for \"other\" will be called just afterwards\n        MPREAL_MSVC_DEBUGVIEW_CODE;\n    }\n    return *this;\n}\n#endif\n\ninline mpreal::mpreal(const mpfr_t  u, bool shared)\n{\n    if(shared)\n    {\n        std::memcpy(mpfr_ptr(), u, sizeof(mpfr_t));\n    }\n    else\n    {\n        mpfr_init2(mpfr_ptr(), mpfr_get_prec(u));\n        mpfr_set  (mpfr_ptr(), u, mpreal::get_default_rnd());\n    }\n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n}\n\ninline mpreal::mpreal(const mpf_t u)\n{\n    mpfr_init2(mpfr_ptr(),(mp_prec_t) mpf_get_prec(u)); // (gmp: mp_bitcnt_t) unsigned long -> long (mpfr: mp_prec_t)\n    mpfr_set_f(mpfr_ptr(),u,mpreal::get_default_rnd());\n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n}\n\ninline mpreal::mpreal(const mpz_t u, mp_prec_t prec, mp_rnd_t mode)\n{\n    mpfr_init2(mpfr_ptr(), prec);\n    mpfr_set_z(mpfr_ptr(), u, mode);\n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n}\n\ninline mpreal::mpreal(const mpq_t u, mp_prec_t prec, mp_rnd_t mode)\n{\n    mpfr_init2(mpfr_ptr(), prec);\n    mpfr_set_q(mpfr_ptr(), u, mode);\n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n}\n\ninline mpreal::mpreal(const double u, mp_prec_t prec, mp_rnd_t mode)\n{\n     mpfr_init2(mpfr_ptr(), prec);\n\n#if (MPREAL_DOUBLE_BITS_OVERFLOW > -1)\n\tif(fits_in_bits(u, MPREAL_DOUBLE_BITS_OVERFLOW))\n\t{\n\t\tmpfr_set_d(mpfr_ptr(), u, mode);\n\t}else\n\t\tthrow conversion_overflow();\n#else\n\tmpfr_set_d(mpfr_ptr(), u, mode);\n#endif\n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n}\n\ninline mpreal::mpreal(const long double u, mp_prec_t prec, mp_rnd_t mode)\n{ \n    mpfr_init2 (mpfr_ptr(), prec);\n    mpfr_set_ld(mpfr_ptr(), u, mode);\n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n}\n\ninline mpreal::mpreal(const unsigned long long int u, mp_prec_t prec, mp_rnd_t mode)\n{ \n    mpfr_init2 (mpfr_ptr(), prec);\n    mpfr_set_uj(mpfr_ptr(), u, mode);\n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n}\n\ninline mpreal::mpreal(const long long int u, mp_prec_t prec, mp_rnd_t mode)\n{ \n    mpfr_init2 (mpfr_ptr(), prec);\n    mpfr_set_sj(mpfr_ptr(), u, mode);\n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n}\n\ninline mpreal::mpreal(const unsigned long int u, mp_prec_t prec, mp_rnd_t mode)\n{ \n    mpfr_init2 (mpfr_ptr(), prec);\n    mpfr_set_ui(mpfr_ptr(), u, mode);\n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n}\n\ninline mpreal::mpreal(const unsigned int u, mp_prec_t prec, mp_rnd_t mode)\n{ \n    mpfr_init2 (mpfr_ptr(), prec);\n    mpfr_set_ui(mpfr_ptr(), u, mode);\n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n}\n\ninline mpreal::mpreal(const long int u, mp_prec_t prec, mp_rnd_t mode)\n{ \n    mpfr_init2 (mpfr_ptr(), prec);\n    mpfr_set_si(mpfr_ptr(), u, mode);\n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n}\n\ninline mpreal::mpreal(const int u, mp_prec_t prec, mp_rnd_t mode)\n{ \n    mpfr_init2 (mpfr_ptr(), prec);\n    mpfr_set_si(mpfr_ptr(), u, mode);\n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n}\n\ninline mpreal::mpreal(const char* s, mp_prec_t prec, int base, mp_rnd_t mode)\n{\n    mpfr_init2  (mpfr_ptr(), prec);\n    mpfr_set_str(mpfr_ptr(), s, base, mode); \n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n}\n\ninline mpreal::mpreal(const std::string& s, mp_prec_t prec, int base, mp_rnd_t mode)\n{\n    mpfr_init2  (mpfr_ptr(), prec);\n    mpfr_set_str(mpfr_ptr(), s.c_str(), base, mode); \n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n}\n\ninline void mpreal::clear(::mpfr_ptr x)\n{\n#ifdef MPREAL_HAVE_MOVE_SUPPORT\n    if(mpfr_is_initialized(x)) \n#endif\n    mpfr_clear(x);\n}\n\ninline mpreal::~mpreal() \n{ \n    clear(mpfr_ptr());\n}                           \n\n// internal namespace needed for template magic\nnamespace internal{\n\n    // Use SFINAE to restrict arithmetic operations instantiation only for numeric types\n    // This is needed for smooth integration with libraries based on expression templates, like Eigen.\n    // TODO: Do the same for boolean operators.\n    template <typename ArgumentType> struct result_type {};    \n    \n    template <> struct result_type<mpreal>              {typedef mpreal type;};    \n    template <> struct result_type<mpz_t>               {typedef mpreal type;};    \n    template <> struct result_type<mpq_t>               {typedef mpreal type;};    \n    template <> struct result_type<long double>         {typedef mpreal type;};    \n    template <> struct result_type<double>              {typedef mpreal type;};    \n    template <> struct result_type<unsigned long int>   {typedef mpreal type;};    \n    template <> struct result_type<unsigned int>        {typedef mpreal type;};    \n    template <> struct result_type<long int>            {typedef mpreal type;};    \n    template <> struct result_type<int>                 {typedef mpreal type;};    \n    template <> struct result_type<long long>           {typedef mpreal type;};    \n    template <> struct result_type<unsigned long long>  {typedef mpreal type;};    \n}\n\n// + Addition\ntemplate <typename Rhs> \ninline const typename internal::result_type<Rhs>::type \n    operator+(const mpreal& lhs, const Rhs& rhs){ return mpreal(lhs) += rhs;    }\n\ntemplate <typename Lhs> \ninline const typename internal::result_type<Lhs>::type \n    operator+(const Lhs& lhs, const mpreal& rhs){ return mpreal(rhs) += lhs;    } \n\n// - Subtraction\ntemplate <typename Rhs> \ninline const typename internal::result_type<Rhs>::type \n    operator-(const mpreal& lhs, const Rhs& rhs){ return mpreal(lhs) -= rhs;    }\n\ntemplate <typename Lhs> \ninline const typename internal::result_type<Lhs>::type \n    operator-(const Lhs& lhs, const mpreal& rhs){ return mpreal(lhs) -= rhs;    }\n\n// * Multiplication\ntemplate <typename Rhs> \ninline const typename internal::result_type<Rhs>::type \n    operator*(const mpreal& lhs, const Rhs& rhs){ return mpreal(lhs) *= rhs;    }\n\ntemplate <typename Lhs> \ninline const typename internal::result_type<Lhs>::type \n    operator*(const Lhs& lhs, const mpreal& rhs){ return mpreal(rhs) *= lhs;    } \n\n// / Division\ntemplate <typename Rhs> \ninline const typename internal::result_type<Rhs>::type \n    operator/(const mpreal& lhs, const Rhs& rhs){ return mpreal(lhs) /= rhs;    }\n\ntemplate <typename Lhs> \ninline const typename internal::result_type<Lhs>::type \n    operator/(const Lhs& lhs, const mpreal& rhs){ return mpreal(lhs) /= rhs;    }\n\n//////////////////////////////////////////////////////////////////////////\n// sqrt\nconst mpreal sqrt(const unsigned int v, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal sqrt(const long int v, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal sqrt(const int v, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal sqrt(const long double v, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal sqrt(const double v, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\n\n// abs\ninline const mpreal abs(const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd());\n\n//////////////////////////////////////////////////////////////////////////\n// pow\nconst mpreal pow(const mpreal& a, const unsigned int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const mpreal& a, const int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const mpreal& a, const long double b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const mpreal& a, const double b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\n\nconst mpreal pow(const unsigned int a, const mpreal& b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const long int a, const mpreal& b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const int a, const mpreal& b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const long double a, const mpreal& b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const double a, const mpreal& b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\n\nconst mpreal pow(const unsigned long int a, const unsigned int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const unsigned long int a, const long int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const unsigned long int a, const int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const unsigned long int a, const long double b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const unsigned long int a, const double b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\n\nconst mpreal pow(const unsigned int a, const unsigned long int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const unsigned int a, const unsigned int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const unsigned int a, const long int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const unsigned int a, const int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const unsigned int a, const long double b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const unsigned int a, const double b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\n\nconst mpreal pow(const long int a, const unsigned long int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const long int a, const unsigned int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const long int a, const long int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const long int a, const int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const long int a, const long double b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const long int a, const double b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\n\nconst mpreal pow(const int a, const unsigned long int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const int a, const unsigned int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const int a, const long int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const int a, const int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd()); \nconst mpreal pow(const int a, const long double b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const int a, const double b, mp_rnd_t rnd_mode = mpreal::get_default_rnd()); \n\nconst mpreal pow(const long double a, const long double b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());    \nconst mpreal pow(const long double a, const unsigned long int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const long double a, const unsigned int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const long double a, const long int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const long double a, const int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\n\nconst mpreal pow(const double a, const double b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());    \nconst mpreal pow(const double a, const unsigned long int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const double a, const unsigned int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const double a, const long int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\nconst mpreal pow(const double a, const int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\n\ninline const mpreal mul_2ui(const mpreal& v, unsigned long int k, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\ninline const mpreal mul_2si(const mpreal& v, long int k, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\ninline const mpreal div_2ui(const mpreal& v, unsigned long int k, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\ninline const mpreal div_2si(const mpreal& v, long int k, mp_rnd_t rnd_mode = mpreal::get_default_rnd());\n\n//////////////////////////////////////////////////////////////////////////\n// Estimate machine epsilon for the given precision\n// Returns smallest eps such that 1.0 + eps != 1.0\ninline mpreal machine_epsilon(mp_prec_t prec = mpreal::get_default_prec());\n\n// Returns smallest eps such that x + eps != x (relative machine epsilon)\ninline mpreal machine_epsilon(const mpreal& x);        \n\n// Gives max & min values for the required precision, \n// minval is 'safe' meaning 1 / minval does not overflow\n// maxval is 'safe' meaning 1 / maxval does not underflow\ninline mpreal minval(mp_prec_t prec = mpreal::get_default_prec());\ninline mpreal maxval(mp_prec_t prec = mpreal::get_default_prec());\n\n// 'Dirty' equality check 1: |a-b| < min{|a|,|b|} * eps\ninline bool isEqualFuzzy(const mpreal& a, const mpreal& b, const mpreal& eps);\n\n// 'Dirty' equality check 2: |a-b| < min{|a|,|b|} * eps( min{|a|,|b|} )\ninline bool isEqualFuzzy(const mpreal& a, const mpreal& b);\n\n// 'Bitwise' equality check\n//  maxUlps - a and b can be apart by maxUlps binary numbers. \ninline bool isEqualUlps(const mpreal& a, const mpreal& b, int maxUlps);\n\n//////////////////////////////////////////////////////////////////////////\n// Convert precision in 'bits' to decimal digits and vice versa.\n//    bits   = ceil(digits*log[2](10))\n//    digits = floor(bits*log[10](2))\n\ninline mp_prec_t digits2bits(int d);\ninline int       bits2digits(mp_prec_t b);\n\n//////////////////////////////////////////////////////////////////////////\n// min, max\nconst mpreal (max)(const mpreal& x, const mpreal& y);\nconst mpreal (min)(const mpreal& x, const mpreal& y);\n\n//////////////////////////////////////////////////////////////////////////\n// Implementation\n//////////////////////////////////////////////////////////////////////////\n\n//////////////////////////////////////////////////////////////////////////\n// Operators - Assignment\ninline mpreal& mpreal::operator=(const mpreal& v)\n{\n    if (this != &v)\n    {\n\t\tmp_prec_t tp = mpfr_get_prec(  mpfr_srcptr());\n\t\tmp_prec_t vp = mpfr_get_prec(v.mpfr_srcptr());\n\n\t\tif(tp != vp){\n\t\t\tclear(mpfr_ptr());\n\t\t\tmpfr_init2(mpfr_ptr(), vp);\n\t\t}\n\n        mpfr_set(mpfr_ptr(), v.mpfr_srcptr(), mpreal::get_default_rnd());\n\n        MPREAL_MSVC_DEBUGVIEW_CODE;\n    }\n    return *this;\n}\n\ninline mpreal& mpreal::operator=(const mpf_t v)\n{\n    mpfr_set_f(mpfr_ptr(), v, mpreal::get_default_rnd());\n    \n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator=(const mpz_t v)\n{\n    mpfr_set_z(mpfr_ptr(), v, mpreal::get_default_rnd());\n    \n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator=(const mpq_t v)\n{\n    mpfr_set_q(mpfr_ptr(), v, mpreal::get_default_rnd());\n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator=(const long double v)        \n{    \n    mpfr_set_ld(mpfr_ptr(), v, mpreal::get_default_rnd());\n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator=(const double v)                \n{   \n#if (MPREAL_DOUBLE_BITS_OVERFLOW > -1)\n\tif(fits_in_bits(v, MPREAL_DOUBLE_BITS_OVERFLOW))\n\t{\n\t\tmpfr_set_d(mpfr_ptr(),v,mpreal::get_default_rnd());\n\t}else\n\t\tthrow conversion_overflow();\n#else\n\tmpfr_set_d(mpfr_ptr(),v,mpreal::get_default_rnd());\n#endif\n\n\tMPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator=(const unsigned long int v)    \n{    \n    mpfr_set_ui(mpfr_ptr(), v, mpreal::get_default_rnd());    \n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator=(const unsigned int v)        \n{    \n    mpfr_set_ui(mpfr_ptr(), v, mpreal::get_default_rnd());    \n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator=(const unsigned long long int v)    \n{    \n    mpfr_set_uj(mpfr_ptr(), v, mpreal::get_default_rnd());    \n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator=(const long long int v)    \n{    \n    mpfr_set_sj(mpfr_ptr(), v, mpreal::get_default_rnd());    \n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator=(const long int v)            \n{    \n    mpfr_set_si(mpfr_ptr(), v, mpreal::get_default_rnd());    \n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator=(const int v)\n{    \n    mpfr_set_si(mpfr_ptr(), v, mpreal::get_default_rnd());    \n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator=(const char* s)\n{\n    // Use other converters for more precise control on base & precision & rounding:\n    //\n    //        mpreal(const char* s,        mp_prec_t prec, int base, mp_rnd_t mode)\n    //        mpreal(const std::string& s,mp_prec_t prec, int base, mp_rnd_t mode)\n    //\n    // Here we assume base = 10 and we use precision of target variable.\n\n    mpfr_t t;\n\n    mpfr_init2(t, mpfr_get_prec(mpfr_srcptr()));\n\n    if(0 == mpfr_set_str(t, s, 10, mpreal::get_default_rnd()))\n    {\n        mpfr_set(mpfr_ptr(), t, mpreal::get_default_rnd()); \n        MPREAL_MSVC_DEBUGVIEW_CODE;\n    }\n\n    clear(t);\n    return *this;\n}\n\ninline mpreal& mpreal::operator=(const std::string& s)\n{\n    // Use other converters for more precise control on base & precision & rounding:\n    //\n    //        mpreal(const char* s,        mp_prec_t prec, int base, mp_rnd_t mode)\n    //        mpreal(const std::string& s,mp_prec_t prec, int base, mp_rnd_t mode)\n    //\n    // Here we assume base = 10 and we use precision of target variable.\n\n    mpfr_t t;\n\n    mpfr_init2(t, mpfr_get_prec(mpfr_srcptr()));\n\n    if(0 == mpfr_set_str(t, s.c_str(), 10, mpreal::get_default_rnd()))\n    {\n        mpfr_set(mpfr_ptr(), t, mpreal::get_default_rnd()); \n        MPREAL_MSVC_DEBUGVIEW_CODE;\n    }\n\n    clear(t);\n    return *this;\n}\n\ntemplate <typename real_t> \ninline mpreal& mpreal::operator= (const std::complex<real_t>& z)\n{\n    return *this = z.real();\n}\n\n//////////////////////////////////////////////////////////////////////////\n// + Addition\ninline mpreal& mpreal::operator+=(const mpreal& v)\n{\n    mpfr_add(mpfr_ptr(), mpfr_srcptr(), v.mpfr_srcptr(), mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator+=(const mpf_t u)\n{\n    *this += mpreal(u);\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator+=(const mpz_t u)\n{\n    mpfr_add_z(mpfr_ptr(),mpfr_srcptr(),u,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator+=(const mpq_t u)\n{\n    mpfr_add_q(mpfr_ptr(),mpfr_srcptr(),u,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator+= (const long double u)\n{\n    *this += mpreal(u);    \n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;    \n}\n\ninline mpreal& mpreal::operator+= (const double u)\n{\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(2,4,0))\n    mpfr_add_d(mpfr_ptr(),mpfr_srcptr(),u,mpreal::get_default_rnd());\n#else\n    *this += mpreal(u);\n#endif\n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator+=(const unsigned long int u)\n{\n    mpfr_add_ui(mpfr_ptr(),mpfr_srcptr(),u,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator+=(const unsigned int u)\n{\n    mpfr_add_ui(mpfr_ptr(),mpfr_srcptr(),u,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator+=(const long int u)\n{\n    mpfr_add_si(mpfr_ptr(),mpfr_srcptr(),u,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator+=(const int u)\n{\n    mpfr_add_si(mpfr_ptr(),mpfr_srcptr(),u,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator+=(const long long int u)         {    *this += mpreal(u); MPREAL_MSVC_DEBUGVIEW_CODE; return *this;    }\ninline mpreal& mpreal::operator+=(const unsigned long long int u){    *this += mpreal(u); MPREAL_MSVC_DEBUGVIEW_CODE; return *this;    }\ninline mpreal& mpreal::operator-=(const long long int  u)        {    *this -= mpreal(u); MPREAL_MSVC_DEBUGVIEW_CODE; return *this;    }\ninline mpreal& mpreal::operator-=(const unsigned long long int u){    *this -= mpreal(u); MPREAL_MSVC_DEBUGVIEW_CODE; return *this;    }\ninline mpreal& mpreal::operator*=(const long long int  u)        {    *this *= mpreal(u); MPREAL_MSVC_DEBUGVIEW_CODE; return *this;    }\ninline mpreal& mpreal::operator*=(const unsigned long long int u){    *this *= mpreal(u); MPREAL_MSVC_DEBUGVIEW_CODE; return *this;    }\ninline mpreal& mpreal::operator/=(const long long int  u)        {    *this /= mpreal(u); MPREAL_MSVC_DEBUGVIEW_CODE; return *this;    }\ninline mpreal& mpreal::operator/=(const unsigned long long int u){    *this /= mpreal(u); MPREAL_MSVC_DEBUGVIEW_CODE; return *this;    }\n\ninline const mpreal mpreal::operator+()const    {    return mpreal(*this); }\n\ninline const mpreal operator+(const mpreal& a, const mpreal& b)\n{\n\tmpreal c(0, (std::max)(mpfr_get_prec(a.mpfr_ptr()), mpfr_get_prec(b.mpfr_ptr())));\n\tmpfr_add(c.mpfr_ptr(), a.mpfr_srcptr(), b.mpfr_srcptr(), mpreal::get_default_rnd());\n\treturn c;\n}\n\ninline mpreal& mpreal::operator++() \n{\n    return *this += 1;\n}\n\ninline const mpreal mpreal::operator++ (int)\n{\n    mpreal x(*this);\n    *this += 1;\n    return x;\n}\n\ninline mpreal& mpreal::operator--() \n{\n    return *this -= 1;\n}\n\ninline const mpreal mpreal::operator-- (int)\n{\n    mpreal x(*this);\n    *this -= 1;\n    return x;\n}\n\n//////////////////////////////////////////////////////////////////////////\n// - Subtraction\ninline mpreal& mpreal::operator-=(const mpreal& v)\n{\n    mpfr_sub(mpfr_ptr(),mpfr_srcptr(),v.mpfr_srcptr(),mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator-=(const mpz_t v)\n{\n    mpfr_sub_z(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator-=(const mpq_t v)\n{\n    mpfr_sub_q(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator-=(const long double v)\n{\n    *this -= mpreal(v);    \n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;    \n}\n\ninline mpreal& mpreal::operator-=(const double v)\n{\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(2,4,0))\n    mpfr_sub_d(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n#else\n    *this -= mpreal(v);    \n#endif\n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator-=(const unsigned long int v)\n{\n    mpfr_sub_ui(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator-=(const unsigned int v)\n{\n    mpfr_sub_ui(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator-=(const long int v)\n{\n    mpfr_sub_si(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator-=(const int v)\n{\n    mpfr_sub_si(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline const mpreal mpreal::operator-()const\n{\n    mpreal u(*this);\n    mpfr_neg(u.mpfr_ptr(),u.mpfr_srcptr(),mpreal::get_default_rnd());\n    return u;\n}\n\ninline const mpreal operator-(const mpreal& a, const mpreal& b)\n{\n\tmpreal c(0, (std::max)(mpfr_get_prec(a.mpfr_ptr()), mpfr_get_prec(b.mpfr_ptr())));\n\tmpfr_sub(c.mpfr_ptr(), a.mpfr_srcptr(), b.mpfr_srcptr(), mpreal::get_default_rnd());\n\treturn c;\n}\n\ninline const mpreal operator-(const double  b, const mpreal& a)\n{\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(2,4,0))\n    mpreal x(0, mpfr_get_prec(a.mpfr_ptr()));\n    mpfr_d_sub(x.mpfr_ptr(), b, a.mpfr_srcptr(), mpreal::get_default_rnd());\n    return x;\n#else\n    mpreal x(b, mpfr_get_prec(a.mpfr_ptr()));\n    x -= a;\n    return x;\n#endif\n}\n\ninline const mpreal operator-(const unsigned long int b, const mpreal& a)\n{\n    mpreal x(0, mpfr_get_prec(a.mpfr_ptr()));\n    mpfr_ui_sub(x.mpfr_ptr(), b, a.mpfr_srcptr(), mpreal::get_default_rnd());\n    return x;\n}\n\ninline const mpreal operator-(const unsigned int b, const mpreal& a)\n{\n    mpreal x(0, mpfr_get_prec(a.mpfr_ptr()));\n    mpfr_ui_sub(x.mpfr_ptr(), b, a.mpfr_srcptr(), mpreal::get_default_rnd());\n    return x;\n}\n\ninline const mpreal operator-(const long int b, const mpreal& a)\n{\n    mpreal x(0, mpfr_get_prec(a.mpfr_ptr()));\n    mpfr_si_sub(x.mpfr_ptr(), b, a.mpfr_srcptr(), mpreal::get_default_rnd());\n    return x;\n}\n\ninline const mpreal operator-(const int b, const mpreal& a)\n{\n    mpreal x(0, mpfr_get_prec(a.mpfr_ptr()));\n    mpfr_si_sub(x.mpfr_ptr(), b, a.mpfr_srcptr(), mpreal::get_default_rnd());\n    return x;\n}\n\n//////////////////////////////////////////////////////////////////////////\n// * Multiplication\ninline mpreal& mpreal::operator*= (const mpreal& v)\n{\n    mpfr_mul(mpfr_ptr(),mpfr_srcptr(),v.mpfr_srcptr(),mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator*=(const mpz_t v)\n{\n    mpfr_mul_z(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator*=(const mpq_t v)\n{\n    mpfr_mul_q(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator*=(const long double v)\n{\n    *this *= mpreal(v);    \n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;    \n}\n\ninline mpreal& mpreal::operator*=(const double v)\n{\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(2,4,0))\n    mpfr_mul_d(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n#else\n    *this *= mpreal(v);    \n#endif\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator*=(const unsigned long int v)\n{\n    mpfr_mul_ui(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator*=(const unsigned int v)\n{\n    mpfr_mul_ui(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator*=(const long int v)\n{\n    mpfr_mul_si(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator*=(const int v)\n{\n    mpfr_mul_si(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline const mpreal operator*(const mpreal& a, const mpreal& b)\n{\n\tmpreal c(0, (std::max)(mpfr_get_prec(a.mpfr_ptr()), mpfr_get_prec(b.mpfr_ptr())));\n\tmpfr_mul(c.mpfr_ptr(), a.mpfr_srcptr(), b.mpfr_srcptr(), mpreal::get_default_rnd());\n\treturn c;\n}\n\n//////////////////////////////////////////////////////////////////////////\n// / Division\ninline mpreal& mpreal::operator/=(const mpreal& v)\n{\n    mpfr_div(mpfr_ptr(),mpfr_srcptr(),v.mpfr_srcptr(),mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator/=(const mpz_t v)\n{\n    mpfr_div_z(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator/=(const mpq_t v)\n{\n    mpfr_div_q(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator/=(const long double v)\n{\n    *this /= mpreal(v);\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;    \n}\n\ninline mpreal& mpreal::operator/=(const double v)\n{\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(2,4,0))\n    mpfr_div_d(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n#else\n    *this /= mpreal(v);    \n#endif\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator/=(const unsigned long int v)\n{\n    mpfr_div_ui(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator/=(const unsigned int v)\n{\n    mpfr_div_ui(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator/=(const long int v)\n{\n    mpfr_div_si(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator/=(const int v)\n{\n    mpfr_div_si(mpfr_ptr(),mpfr_srcptr(),v,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline const mpreal operator/(const mpreal& a, const mpreal& b)\n{\n\tmpreal c(0, (std::max)(mpfr_get_prec(a.mpfr_srcptr()), mpfr_get_prec(b.mpfr_srcptr())));\n\tmpfr_div(c.mpfr_ptr(), a.mpfr_srcptr(), b.mpfr_srcptr(), mpreal::get_default_rnd());\n\treturn c;\n}\n\ninline const mpreal operator/(const unsigned long int b, const mpreal& a)\n{\n    mpreal x(0, mpfr_get_prec(a.mpfr_srcptr()));\n    mpfr_ui_div(x.mpfr_ptr(), b, a.mpfr_srcptr(), mpreal::get_default_rnd());\n    return x;\n}\n\ninline const mpreal operator/(const unsigned int b, const mpreal& a)\n{\n    mpreal x(0, mpfr_get_prec(a.mpfr_srcptr()));\n    mpfr_ui_div(x.mpfr_ptr(), b, a.mpfr_srcptr(), mpreal::get_default_rnd());\n    return x;\n}\n\ninline const mpreal operator/(const long int b, const mpreal& a)\n{\n    mpreal x(0, mpfr_get_prec(a.mpfr_srcptr()));\n    mpfr_si_div(x.mpfr_ptr(), b, a.mpfr_srcptr(), mpreal::get_default_rnd());\n    return x;\n}\n\ninline const mpreal operator/(const int b, const mpreal& a)\n{\n    mpreal x(0, mpfr_get_prec(a.mpfr_srcptr()));\n    mpfr_si_div(x.mpfr_ptr(), b, a.mpfr_srcptr(), mpreal::get_default_rnd());\n    return x;\n}\n\ninline const mpreal operator/(const double  b, const mpreal& a)\n{\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(2,4,0))\n    mpreal x(0, mpfr_get_prec(a.mpfr_srcptr()));\n    mpfr_d_div(x.mpfr_ptr(), b, a.mpfr_srcptr(), mpreal::get_default_rnd());\n    return x;\n#else\n    mpreal x(0, mpfr_get_prec(a.mpfr_ptr()));\n    x /= a;\n    return x;\n#endif\n}\n\n//////////////////////////////////////////////////////////////////////////\n// Shifts operators - Multiplication/Division by power of 2\ninline mpreal& mpreal::operator<<=(const unsigned long int u)\n{\n    mpfr_mul_2ui(mpfr_ptr(),mpfr_srcptr(),u,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator<<=(const unsigned int u)\n{\n    mpfr_mul_2ui(mpfr_ptr(),mpfr_srcptr(),static_cast<unsigned long int>(u),mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator<<=(const long int u)\n{\n    mpfr_mul_2si(mpfr_ptr(),mpfr_srcptr(),u,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator<<=(const int u)\n{\n    mpfr_mul_2si(mpfr_ptr(),mpfr_srcptr(),static_cast<long int>(u),mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator>>=(const unsigned long int u)\n{\n    mpfr_div_2ui(mpfr_ptr(),mpfr_srcptr(),u,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator>>=(const unsigned int u)\n{\n    mpfr_div_2ui(mpfr_ptr(),mpfr_srcptr(),static_cast<unsigned long int>(u),mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator>>=(const long int u)\n{\n    mpfr_div_2si(mpfr_ptr(),mpfr_srcptr(),u,mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::operator>>=(const int u)\n{\n    mpfr_div_2si(mpfr_ptr(),mpfr_srcptr(),static_cast<long int>(u),mpreal::get_default_rnd());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline const mpreal operator<<(const mpreal& v, const unsigned long int k)\n{\n    return mul_2ui(v,k);\n}\n\ninline const mpreal operator<<(const mpreal& v, const unsigned int k)\n{\n    return mul_2ui(v,static_cast<unsigned long int>(k));\n}\n\ninline const mpreal operator<<(const mpreal& v, const long int k)\n{\n    return mul_2si(v,k);\n}\n\ninline const mpreal operator<<(const mpreal& v, const int k)\n{\n    return mul_2si(v,static_cast<long int>(k));\n}\n\ninline const mpreal operator>>(const mpreal& v, const unsigned long int k)\n{\n    return div_2ui(v,k);\n}\n\ninline const mpreal operator>>(const mpreal& v, const long int k)\n{\n    return div_2si(v,k);\n}\n\ninline const mpreal operator>>(const mpreal& v, const unsigned int k)\n{\n    return div_2ui(v,static_cast<unsigned long int>(k));\n}\n\ninline const mpreal operator>>(const mpreal& v, const int k)\n{\n    return div_2si(v,static_cast<long int>(k));\n}\n\n// mul_2ui\ninline const mpreal mul_2ui(const mpreal& v, unsigned long int k, mp_rnd_t rnd_mode)\n{\n    mpreal x(v);\n    mpfr_mul_2ui(x.mpfr_ptr(),v.mpfr_srcptr(),k,rnd_mode);\n    return x;\n}\n\n// mul_2si\ninline const mpreal mul_2si(const mpreal& v, long int k, mp_rnd_t rnd_mode)\n{\n    mpreal x(v);\n    mpfr_mul_2si(x.mpfr_ptr(),v.mpfr_srcptr(),k,rnd_mode);\n    return x;\n}\n\ninline const mpreal div_2ui(const mpreal& v, unsigned long int k, mp_rnd_t rnd_mode)\n{\n    mpreal x(v);\n    mpfr_div_2ui(x.mpfr_ptr(),v.mpfr_srcptr(),k,rnd_mode);\n    return x;\n}\n\ninline const mpreal div_2si(const mpreal& v, long int k, mp_rnd_t rnd_mode)\n{\n    mpreal x(v);\n    mpfr_div_2si(x.mpfr_ptr(),v.mpfr_srcptr(),k,rnd_mode);\n    return x;\n}\n\n//////////////////////////////////////////////////////////////////////////\n//Relational operators\n\n// WARNING: \n//\n// Please note that following checks for double-NaN are guaranteed to work only in IEEE math mode: \n//\n// isnan(b) =  (b != b)\n// isnan(b) = !(b == b)  (we use in code below)\n//\n// Be cautions if you use compiler options which break strict IEEE compliance (e.g. -ffast-math in GCC).\n// Use std::isnan instead (C++11).\n\ninline bool operator >  (const mpreal& a, const mpreal& b           ){  return (mpfr_greater_p(a.mpfr_srcptr(),b.mpfr_srcptr()) != 0 );            }\ninline bool operator >  (const mpreal& a, const unsigned long int b ){  return !isnan EIGEN_NOT_A_MACRO (a) && (mpfr_cmp_ui(a.mpfr_srcptr(),b) > 0 );                 }\ninline bool operator >  (const mpreal& a, const unsigned int b      ){  return !isnan EIGEN_NOT_A_MACRO (a) && (mpfr_cmp_ui(a.mpfr_srcptr(),b) > 0 );                 }\ninline bool operator >  (const mpreal& a, const long int b          ){  return !isnan EIGEN_NOT_A_MACRO (a) && (mpfr_cmp_si(a.mpfr_srcptr(),b) > 0 );                 }\ninline bool operator >  (const mpreal& a, const int b               ){  return !isnan EIGEN_NOT_A_MACRO (a) && (mpfr_cmp_si(a.mpfr_srcptr(),b) > 0 );                 }\ninline bool operator >  (const mpreal& a, const long double b       ){  return !isnan EIGEN_NOT_A_MACRO (a) && (b == b) && (mpfr_cmp_ld(a.mpfr_srcptr(),b) > 0 );    }\ninline bool operator >  (const mpreal& a, const double b            ){  return !isnan EIGEN_NOT_A_MACRO (a) && (b == b) && (mpfr_cmp_d (a.mpfr_srcptr(),b) > 0 );    }\n\ninline bool operator >= (const mpreal& a, const mpreal& b           ){  return (mpfr_greaterequal_p(a.mpfr_srcptr(),b.mpfr_srcptr()) != 0 );       }\ninline bool operator >= (const mpreal& a, const unsigned long int b ){  return !isnan EIGEN_NOT_A_MACRO (a) && (mpfr_cmp_ui(a.mpfr_srcptr(),b) >= 0 );                }\ninline bool operator >= (const mpreal& a, const unsigned int b      ){  return !isnan EIGEN_NOT_A_MACRO (a) && (mpfr_cmp_ui(a.mpfr_srcptr(),b) >= 0 );                }\ninline bool operator >= (const mpreal& a, const long int b          ){  return !isnan EIGEN_NOT_A_MACRO (a) && (mpfr_cmp_si(a.mpfr_srcptr(),b) >= 0 );                }\ninline bool operator >= (const mpreal& a, const int b               ){  return !isnan EIGEN_NOT_A_MACRO (a) && (mpfr_cmp_si(a.mpfr_srcptr(),b) >= 0 );                }\ninline bool operator >= (const mpreal& a, const long double b       ){  return !isnan EIGEN_NOT_A_MACRO (a) && (b == b) && (mpfr_cmp_ld(a.mpfr_srcptr(),b) >= 0 );   }\ninline bool operator >= (const mpreal& a, const double b            ){  return !isnan EIGEN_NOT_A_MACRO (a) && (b == b) && (mpfr_cmp_d (a.mpfr_srcptr(),b) >= 0 );   }\n\ninline bool operator <  (const mpreal& a, const mpreal& b           ){  return (mpfr_less_p(a.mpfr_srcptr(),b.mpfr_srcptr()) != 0 );               }\ninline bool operator <  (const mpreal& a, const unsigned long int b ){  return !isnan EIGEN_NOT_A_MACRO (a) && (mpfr_cmp_ui(a.mpfr_srcptr(),b) < 0 );                 }\ninline bool operator <  (const mpreal& a, const unsigned int b      ){  return !isnan EIGEN_NOT_A_MACRO (a) && (mpfr_cmp_ui(a.mpfr_srcptr(),b) < 0 );                 }\ninline bool operator <  (const mpreal& a, const long int b          ){  return !isnan EIGEN_NOT_A_MACRO (a) && (mpfr_cmp_si(a.mpfr_srcptr(),b) < 0 );                 }\ninline bool operator <  (const mpreal& a, const int b               ){  return !isnan EIGEN_NOT_A_MACRO (a) && (mpfr_cmp_si(a.mpfr_srcptr(),b) < 0 );                 }\ninline bool operator <  (const mpreal& a, const long double b       ){  return !isnan EIGEN_NOT_A_MACRO (a) && (b == b) && (mpfr_cmp_ld(a.mpfr_srcptr(),b) < 0 );    }\ninline bool operator <  (const mpreal& a, const double b            ){  return !isnan EIGEN_NOT_A_MACRO (a) && (b == b) && (mpfr_cmp_d (a.mpfr_srcptr(),b) < 0 );    }\n\ninline bool operator <= (const mpreal& a, const mpreal& b           ){  return (mpfr_lessequal_p(a.mpfr_srcptr(),b.mpfr_srcptr()) != 0 );          }\ninline bool operator <= (const mpreal& a, const unsigned long int b ){  return !isnan EIGEN_NOT_A_MACRO (a) && (mpfr_cmp_ui(a.mpfr_srcptr(),b) <= 0 );                }\ninline bool operator <= (const mpreal& a, const unsigned int b      ){  return !isnan EIGEN_NOT_A_MACRO (a) && (mpfr_cmp_ui(a.mpfr_srcptr(),b) <= 0 );                }\ninline bool operator <= (const mpreal& a, const long int b          ){  return !isnan EIGEN_NOT_A_MACRO (a) && (mpfr_cmp_si(a.mpfr_srcptr(),b) <= 0 );                }\ninline bool operator <= (const mpreal& a, const int b               ){  return !isnan EIGEN_NOT_A_MACRO (a) && (mpfr_cmp_si(a.mpfr_srcptr(),b) <= 0 );                }\ninline bool operator <= (const mpreal& a, const long double b       ){  return !isnan EIGEN_NOT_A_MACRO (a) && (b == b) && (mpfr_cmp_ld(a.mpfr_srcptr(),b) <= 0 );   }\ninline bool operator <= (const mpreal& a, const double b            ){  return !isnan EIGEN_NOT_A_MACRO (a) && (b == b) && (mpfr_cmp_d (a.mpfr_srcptr(),b) <= 0 );   }\n\ninline bool operator == (const mpreal& a, const mpreal& b           ){  return (mpfr_equal_p(a.mpfr_srcptr(),b.mpfr_srcptr()) != 0 );              }\ninline bool operator == (const mpreal& a, const unsigned long int b ){  return !isnan EIGEN_NOT_A_MACRO (a) && (mpfr_cmp_ui(a.mpfr_srcptr(),b) == 0 );                }\ninline bool operator == (const mpreal& a, const unsigned int b      ){  return !isnan EIGEN_NOT_A_MACRO (a) && (mpfr_cmp_ui(a.mpfr_srcptr(),b) == 0 );                }\ninline bool operator == (const mpreal& a, const long int b          ){  return !isnan EIGEN_NOT_A_MACRO (a) && (mpfr_cmp_si(a.mpfr_srcptr(),b) == 0 );                }\ninline bool operator == (const mpreal& a, const int b               ){  return !isnan EIGEN_NOT_A_MACRO (a) && (mpfr_cmp_si(a.mpfr_srcptr(),b) == 0 );                }\ninline bool operator == (const mpreal& a, const long double b       ){  return !isnan EIGEN_NOT_A_MACRO (a) && (b == b) && (mpfr_cmp_ld(a.mpfr_srcptr(),b) == 0 );   }\ninline bool operator == (const mpreal& a, const double b            ){  return !isnan EIGEN_NOT_A_MACRO (a) && (b == b) && (mpfr_cmp_d (a.mpfr_srcptr(),b) == 0 );   }\n\ninline bool operator != (const mpreal& a, const mpreal& b           ){  return !(a == b);  }\ninline bool operator != (const mpreal& a, const unsigned long int b ){  return !(a == b);  }\ninline bool operator != (const mpreal& a, const unsigned int b      ){  return !(a == b);  }\ninline bool operator != (const mpreal& a, const long int b          ){  return !(a == b);  }\ninline bool operator != (const mpreal& a, const int b               ){  return !(a == b);  }\ninline bool operator != (const mpreal& a, const long double b       ){  return !(a == b);  }\ninline bool operator != (const mpreal& a, const double b            ){  return !(a == b);  }\n\ninline bool isnan EIGEN_NOT_A_MACRO     (const mpreal& op){    return (mpfr_nan_p    (op.mpfr_srcptr()) != 0 );    }\ninline bool (isinf)    (const mpreal& op){    return (mpfr_inf_p    (op.mpfr_srcptr()) != 0 );    }\ninline bool (isfinite) (const mpreal& op){    return (mpfr_number_p (op.mpfr_srcptr()) != 0 );    }\ninline bool iszero   (const mpreal& op){    return (mpfr_zero_p   (op.mpfr_srcptr()) != 0 );    }\ninline bool isint    (const mpreal& op){    return (mpfr_integer_p(op.mpfr_srcptr()) != 0 );    }\n\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(3,0,0))\ninline bool isregular(const mpreal& op){    return (mpfr_regular_p(op.mpfr_srcptr()));}\n#endif \n\n//////////////////////////////////////////////////////////////////////////\n// Type Converters\ninline bool               mpreal::toBool   (             )  const    {    return  mpfr_zero_p (mpfr_srcptr()) == 0;     }\ninline long               mpreal::toLong   (mp_rnd_t mode)  const    {    return  mpfr_get_si (mpfr_srcptr(), mode);    }\ninline unsigned long      mpreal::toULong  (mp_rnd_t mode)  const    {    return  mpfr_get_ui (mpfr_srcptr(), mode);    }\ninline float              mpreal::toFloat  (mp_rnd_t mode)  const    {    return  mpfr_get_flt(mpfr_srcptr(), mode);    }\ninline double             mpreal::toDouble (mp_rnd_t mode)  const    {    return  mpfr_get_d  (mpfr_srcptr(), mode);    }\ninline long double        mpreal::toLDouble(mp_rnd_t mode)  const    {    return  mpfr_get_ld (mpfr_srcptr(), mode);    }\ninline long long          mpreal::toLLong  (mp_rnd_t mode)  const    {    return  mpfr_get_sj (mpfr_srcptr(), mode);    }\ninline unsigned long long mpreal::toULLong (mp_rnd_t mode)  const    {    return  mpfr_get_uj (mpfr_srcptr(), mode);    }\n\ninline ::mpfr_ptr     mpreal::mpfr_ptr()             { return mp; }\ninline ::mpfr_srcptr  mpreal::mpfr_ptr()    const    { return mp; }\ninline ::mpfr_srcptr  mpreal::mpfr_srcptr() const    { return mp; }\n\ntemplate <class T>\ninline std::string toString(T t, std::ios_base & (*f)(std::ios_base&))\n{\n    std::ostringstream oss;\n    oss << f << t;\n    return oss.str();\n}\n\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(2,4,0))\n\ninline std::string mpreal::toString(const std::string& format) const\n{\n    char *s = NULL;\n    std::string out;\n\n    if( !format.empty() )\n    {\n        if(!(mpfr_asprintf(&s, format.c_str(), mpfr_srcptr()) < 0))\n        {\n            out = std::string(s);\n\n            mpfr_free_str(s);\n        }\n    }\n\n    return out;\n}\n\n#endif\n\ninline std::string mpreal::toString(int n, int b, mp_rnd_t mode) const\n{\n    // TODO: Add extended format specification (f, e, rounding mode) as it done in output operator\n    (void)b;\n    (void)mode;\n\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(2,4,0))\n\n    std::ostringstream format;\n\n    int digits = (n >= 0) ? n : 2 + bits2digits(mpfr_get_prec(mpfr_srcptr()));\n    \n    format << \"%.\" << digits << \"RNg\";\n\n    return toString(format.str());\n\n#else\n\n    char *s, *ns = NULL; \n    size_t slen, nslen;\n    mp_exp_t exp;\n    std::string out;\n\n    if(mpfr_inf_p(mp))\n    { \n        if(mpfr_sgn(mp)>0) return \"+Inf\";\n        else               return \"-Inf\";\n    }\n\n    if(mpfr_zero_p(mp)) return \"0\";\n    if(mpfr_nan_p(mp))  return \"NaN\";\n\n    s  = mpfr_get_str(NULL, &exp, b, 0, mp, mode);\n    ns = mpfr_get_str(NULL, &exp, b, (std::max)(0,n), mp, mode);\n\n    if(s!=NULL && ns!=NULL)\n    {\n        slen  = strlen(s);\n        nslen = strlen(ns);\n        if(nslen<=slen) \n        {\n            mpfr_free_str(s);\n            s = ns;\n            slen = nslen;\n        }\n        else {\n            mpfr_free_str(ns);\n        }\n\n        // Make human eye-friendly formatting if possible\n        if (exp>0 && static_cast<size_t>(exp)<slen)\n        {\n            if(s[0]=='-')\n            {\n                // Remove zeros starting from right end\n                char* ptr = s+slen-1;\n                while (*ptr=='0' && ptr>s+exp) ptr--; \n\n                if(ptr==s+exp) out = std::string(s,exp+1);\n                else           out = std::string(s,exp+1)+'.'+std::string(s+exp+1,ptr-(s+exp+1)+1);\n\n                //out = string(s,exp+1)+'.'+string(s+exp+1);\n            }\n            else\n            {\n                // Remove zeros starting from right end\n                char* ptr = s+slen-1;\n                while (*ptr=='0' && ptr>s+exp-1) ptr--; \n\n                if(ptr==s+exp-1) out = std::string(s,exp);\n                else             out = std::string(s,exp)+'.'+std::string(s+exp,ptr-(s+exp)+1);\n\n                //out = string(s,exp)+'.'+string(s+exp);\n            }\n\n        }else{ // exp<0 || exp>slen\n            if(s[0]=='-')\n            {\n                // Remove zeros starting from right end\n                char* ptr = s+slen-1;\n                while (*ptr=='0' && ptr>s+1) ptr--; \n\n                if(ptr==s+1) out = std::string(s,2);\n                else         out = std::string(s,2)+'.'+std::string(s+2,ptr-(s+2)+1);\n\n                //out = string(s,2)+'.'+string(s+2);\n            }\n            else\n            {\n                // Remove zeros starting from right end\n                char* ptr = s+slen-1;\n                while (*ptr=='0' && ptr>s) ptr--; \n\n                if(ptr==s) out = std::string(s,1);\n                else       out = std::string(s,1)+'.'+std::string(s+1,ptr-(s+1)+1);\n\n                //out = string(s,1)+'.'+string(s+1);\n            }\n\n            // Make final string\n            if(--exp)\n            {\n                if(exp>0) out += \"e+\"+mpfr::toString<mp_exp_t>(exp,std::dec);\n                else       out += \"e\"+mpfr::toString<mp_exp_t>(exp,std::dec);\n            }\n        }\n\n        mpfr_free_str(s);\n        return out;\n    }else{\n        return \"conversion error!\";\n    }\n#endif\n}\n\n\n//////////////////////////////////////////////////////////////////////////\n// I/O\ninline std::ostream& mpreal::output(std::ostream& os) const \n{\n    std::ostringstream format;\n    const std::ios::fmtflags flags = os.flags();\n\n    format << ((flags & std::ios::showpos) ? \"%+\" : \"%\");\n    if (os.precision() >= 0)\n        format << '.' << os.precision() << \"R*\"\n               << ((flags & std::ios::floatfield) == std::ios::fixed ? 'f' :\n                   (flags & std::ios::floatfield) == std::ios::scientific ? 'e' :\n                   'g');\n    else\n        format << \"R*e\";\n\n    char *s = NULL;\n    if(!(mpfr_asprintf(&s, format.str().c_str(),\n                        mpfr::mpreal::get_default_rnd(),\n                        mpfr_srcptr())\n        < 0))\n    {\n        os << std::string(s);\n        mpfr_free_str(s);\n    }\n    return os;\n}\n\ninline std::ostream& operator<<(std::ostream& os, const mpreal& v)\n{\n    return v.output(os);\n}\n\ninline std::istream& operator>>(std::istream &is, mpreal& v)\n{\n    // TODO: use cout::hexfloat and other flags to setup base\n    std::string tmp;\n    is >> tmp;\n    mpfr_set_str(v.mpfr_ptr(), tmp.c_str(), 10, mpreal::get_default_rnd());\n    return is;\n}\n\n//////////////////////////////////////////////////////////////////////////\n//     Bits - decimal digits relation\n//        bits   = ceil(digits*log[2](10))\n//        digits = floor(bits*log[10](2))\n\ninline mp_prec_t digits2bits(int d)\n{\n    const double LOG2_10 = 3.3219280948873624;\n\n    return mp_prec_t(std::ceil( d * LOG2_10 ));\n}\n\ninline int bits2digits(mp_prec_t b)\n{\n    const double LOG10_2 = 0.30102999566398119;\n\n    return int(std::floor( b * LOG10_2 ));\n}\n\n//////////////////////////////////////////////////////////////////////////\n// Set/Get number properties\ninline mpreal& mpreal::setSign(int sign, mp_rnd_t RoundingMode)\n{\n    mpfr_setsign(mpfr_ptr(), mpfr_srcptr(), sign < 0, RoundingMode);\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline int mpreal::getPrecision() const\n{\n    return int(mpfr_get_prec(mpfr_srcptr()));\n}\n\ninline mpreal& mpreal::setPrecision(int Precision, mp_rnd_t RoundingMode)\n{\n    mpfr_prec_round(mpfr_ptr(), Precision, RoundingMode);\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::setInf(int sign) \n{ \n    mpfr_set_inf(mpfr_ptr(), sign);\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}    \n\ninline mpreal& mpreal::setNan() \n{\n    mpfr_set_nan(mpfr_ptr());\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mpreal& mpreal::setZero(int sign)\n{\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(3,0,0))\n    mpfr_set_zero(mpfr_ptr(), sign);\n#else\n    mpfr_set_si(mpfr_ptr(), 0, (mpfr_get_default_rounding_mode)());\n    setSign(sign);\n#endif \n\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return *this;\n}\n\ninline mp_prec_t mpreal::get_prec() const\n{\n    return mpfr_get_prec(mpfr_srcptr());\n}\n\ninline void mpreal::set_prec(mp_prec_t prec, mp_rnd_t rnd_mode)\n{\n    mpfr_prec_round(mpfr_ptr(),prec,rnd_mode);\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n}\n\ninline mp_exp_t mpreal::get_exp () const\n{\n    return mpfr_get_exp(mpfr_srcptr());\n}\n\ninline int mpreal::set_exp (mp_exp_t e)\n{\n    int x = mpfr_set_exp(mpfr_ptr(), e);\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return x;\n}\n\ninline const mpreal frexp(const mpreal& x, mp_exp_t* exp, mp_rnd_t mode = mpreal::get_default_rnd())\n{\n    mpreal y(x);\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(3,1,0))\n    mpfr_frexp(exp,y.mpfr_ptr(),x.mpfr_srcptr(),mode);\n#else\n    *exp = mpfr_get_exp(y.mpfr_srcptr());\n    mpfr_set_exp(y.mpfr_ptr(),0);\n#endif\n    return y;\n}\n\ninline const mpreal ldexp(const mpreal& v, mp_exp_t exp)\n{\n    mpreal x(v);\n\n    // rounding is not important since we are just increasing the exponent (= exact operation)\n    mpfr_mul_2si(x.mpfr_ptr(), x.mpfr_srcptr(), exp, mpreal::get_default_rnd()); \n    return x;\n}\n\ninline const mpreal scalbn(const mpreal& v, mp_exp_t exp)\n{\n    return ldexp(v, exp);\n}\n\ninline mpreal machine_epsilon(mp_prec_t prec)\n{\n    /* the smallest eps such that 1 + eps != 1 */\n    return machine_epsilon(mpreal(1, prec));\n}\n\ninline mpreal machine_epsilon(const mpreal& x)\n{    \n    /* the smallest eps such that x + eps != x */\n    if( x < 0)\n    {\n        return nextabove(-x) + x;\n    }else{\n        return nextabove( x) - x;\n    }\n}\n\n// minval is 'safe' meaning 1 / minval does not overflow\ninline mpreal minval(mp_prec_t prec)\n{\n    /* min = 1/2 * 2^emin = 2^(emin - 1) */\n    return mpreal(1, prec) << mpreal::get_emin()-1;\n}\n\n// maxval is 'safe' meaning 1 / maxval does not underflow\ninline mpreal maxval(mp_prec_t prec)\n{\n    /* max = (1 - eps) * 2^emax, eps is machine epsilon */\n    return (mpreal(1, prec) - machine_epsilon(prec)) << mpreal::get_emax(); \n}\n\ninline bool isEqualUlps(const mpreal& a, const mpreal& b, int maxUlps)\n{\n    return abs(a - b) <= machine_epsilon((max)(abs(a), abs(b))) * maxUlps;\n}\n\ninline bool isEqualFuzzy(const mpreal& a, const mpreal& b, const mpreal& eps)\n{\n    return abs(a - b) <= eps;\n}\n\ninline bool isEqualFuzzy(const mpreal& a, const mpreal& b)\n{\n    return isEqualFuzzy(a, b, machine_epsilon((max)(1, (min)(abs(a), abs(b)))));\n}\n\n//////////////////////////////////////////////////////////////////////////\n// C++11 sign functions.\ninline mpreal copysign(const mpreal& x, const  mpreal& y, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    mpreal rop(0, mpfr_get_prec(x.mpfr_ptr()));\n    mpfr_setsign(rop.mpfr_ptr(), x.mpfr_srcptr(), mpfr_signbit(y.mpfr_srcptr()), rnd_mode);\n    return rop;\n}\n\ninline bool signbit(const mpreal& x)\n{\n    return mpfr_signbit(x.mpfr_srcptr());\n}\n\ninline mpreal& setsignbit(mpreal& x, bool minus, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    mpfr_setsign(x.mpfr_ptr(), x.mpfr_srcptr(), minus, rnd_mode);\n    return x;\n}\n\ninline const mpreal modf(const mpreal& v, mpreal& n)\n{\n    mpreal f(v);\n\n    // rounding is not important since we are using the same number\n    mpfr_frac (f.mpfr_ptr(),f.mpfr_srcptr(),mpreal::get_default_rnd());    \n    mpfr_trunc(n.mpfr_ptr(),v.mpfr_srcptr());\n    return f;\n}\n\ninline int mpreal::check_range (int t, mp_rnd_t rnd_mode)\n{\n    return mpfr_check_range(mpfr_ptr(),t,rnd_mode);\n}\n\ninline int mpreal::subnormalize (int t,mp_rnd_t rnd_mode)\n{\n    int r = mpfr_subnormalize(mpfr_ptr(),t,rnd_mode);\n    MPREAL_MSVC_DEBUGVIEW_CODE;\n    return r;\n}\n\ninline mp_exp_t mpreal::get_emin (void)\n{\n    return mpfr_get_emin();\n}\n\ninline int mpreal::set_emin (mp_exp_t exp)\n{\n    return mpfr_set_emin(exp);\n}\n\ninline mp_exp_t mpreal::get_emax (void)\n{\n    return mpfr_get_emax();\n}\n\ninline int mpreal::set_emax (mp_exp_t exp)\n{\n    return mpfr_set_emax(exp);\n}\n\ninline mp_exp_t mpreal::get_emin_min (void)\n{\n    return mpfr_get_emin_min();\n}\n\ninline mp_exp_t mpreal::get_emin_max (void)\n{\n    return mpfr_get_emin_max();\n}\n\ninline mp_exp_t mpreal::get_emax_min (void)\n{\n    return mpfr_get_emax_min();\n}\n\ninline mp_exp_t mpreal::get_emax_max (void)\n{\n    return mpfr_get_emax_max();\n}\n\n//////////////////////////////////////////////////////////////////////////\n// Mathematical Functions\n//////////////////////////////////////////////////////////////////////////\n#define MPREAL_UNARY_MATH_FUNCTION_BODY(f)                    \\\n        mpreal y(0, mpfr_get_prec(x.mpfr_srcptr()));          \\\n        mpfr_##f(y.mpfr_ptr(), x.mpfr_srcptr(), r);           \\\n        return y; \n\ninline const mpreal sqr  (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd())\n{   MPREAL_UNARY_MATH_FUNCTION_BODY(sqr );    }\n\ninline const mpreal sqrt (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd())\n{   MPREAL_UNARY_MATH_FUNCTION_BODY(sqrt);    }\n\ninline const mpreal sqrt(const unsigned long int x, mp_rnd_t r)\n{\n    mpreal y;\n    mpfr_sqrt_ui(y.mpfr_ptr(), x, r);\n    return y;\n}\n\ninline const mpreal sqrt(const unsigned int v, mp_rnd_t rnd_mode)\n{\n    return sqrt(static_cast<unsigned long int>(v),rnd_mode);\n}\n\ninline const mpreal sqrt(const long int v, mp_rnd_t rnd_mode)\n{\n    if (v>=0)   return sqrt(static_cast<unsigned long int>(v),rnd_mode);\n    else        return mpreal().setNan(); // NaN  \n}\n\ninline const mpreal sqrt(const int v, mp_rnd_t rnd_mode)\n{\n    if (v>=0)   return sqrt(static_cast<unsigned long int>(v),rnd_mode);\n    else        return mpreal().setNan(); // NaN\n}\n\ninline const mpreal root(const mpreal& x, unsigned long int k, mp_rnd_t r = mpreal::get_default_rnd())\n{\n    mpreal y(0, mpfr_get_prec(x.mpfr_srcptr())); \n    #if (MPFR_VERSION >= MPFR_VERSION_NUM(4,0,0))\n    mpfr_rootn_ui(y.mpfr_ptr(), x.mpfr_srcptr(), k, r);\n    #else\n    mpfr_root(y.mpfr_ptr(), x.mpfr_srcptr(), k, r);\n    #endif\n    return y; \n}\n\ninline const mpreal dim(const mpreal& a, const mpreal& b, mp_rnd_t r = mpreal::get_default_rnd())\n{\n    mpreal y(0, mpfr_get_prec(a.mpfr_srcptr()));\n    mpfr_dim(y.mpfr_ptr(), a.mpfr_srcptr(), b.mpfr_srcptr(), r);\n    return y;\n}\n\ninline int cmpabs(const mpreal& a,const mpreal& b)\n{\n    return mpfr_cmpabs(a.mpfr_ptr(), b.mpfr_srcptr());\n}\n\ninline int sin_cos(mpreal& s, mpreal& c, const mpreal& v, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    return mpfr_sin_cos(s.mpfr_ptr(), c.mpfr_ptr(), v.mpfr_srcptr(), rnd_mode);\n}\n\ninline const mpreal sqrt  (const long double v, mp_rnd_t rnd_mode)    {   return sqrt(mpreal(v),rnd_mode);    }\ninline const mpreal sqrt  (const double v, mp_rnd_t rnd_mode)         {   return sqrt(mpreal(v),rnd_mode);    }\n\ninline const mpreal cbrt  (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(cbrt );    }\ninline const mpreal fabs  (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(abs  );    }\ninline const mpreal abs   (const mpreal& x, mp_rnd_t r)                             {   MPREAL_UNARY_MATH_FUNCTION_BODY(abs  );    }\ninline const mpreal log   (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(log  );    }\ninline const mpreal log2  (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(log2 );    }\ninline const mpreal log10 (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(log10);    }\ninline const mpreal exp   (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(exp  );    }\ninline const mpreal exp2  (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(exp2 );    }\ninline const mpreal exp10 (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(exp10);    }\ninline const mpreal cos   (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(cos  );    }\ninline const mpreal sin   (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(sin  );    }\ninline const mpreal tan   (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(tan  );    }\ninline const mpreal sec   (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(sec  );    }\ninline const mpreal csc   (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(csc  );    }\ninline const mpreal cot   (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(cot  );    }\ninline const mpreal acos  (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(acos );    }\ninline const mpreal asin  (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(asin );    }\ninline const mpreal atan  (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(atan );    }\n\ninline const mpreal logb  (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   return log2 (abs(x),r);                    }\n\ninline const mpreal acot  (const mpreal& v, mp_rnd_t r = mpreal::get_default_rnd()) {   return atan (1/v, r);                      }\ninline const mpreal asec  (const mpreal& v, mp_rnd_t r = mpreal::get_default_rnd()) {   return acos (1/v, r);                      }\ninline const mpreal acsc  (const mpreal& v, mp_rnd_t r = mpreal::get_default_rnd()) {   return asin (1/v, r);                      }\ninline const mpreal acoth (const mpreal& v, mp_rnd_t r = mpreal::get_default_rnd()) {   return atanh(1/v, r);                      }\ninline const mpreal asech (const mpreal& v, mp_rnd_t r = mpreal::get_default_rnd()) {   return acosh(1/v, r);                      }\ninline const mpreal acsch (const mpreal& v, mp_rnd_t r = mpreal::get_default_rnd()) {   return asinh(1/v, r);                      }\n\ninline const mpreal cosh  (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(cosh );    }\ninline const mpreal sinh  (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(sinh );    }\ninline const mpreal tanh  (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(tanh );    }\ninline const mpreal sech  (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(sech );    }\ninline const mpreal csch  (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(csch );    }\ninline const mpreal coth  (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(coth );    }\ninline const mpreal acosh (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(acosh);    }\ninline const mpreal asinh (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(asinh);    }\ninline const mpreal atanh (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(atanh);    }\n\ninline const mpreal log1p   (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(log1p  );    }\ninline const mpreal expm1   (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(expm1  );    }\ninline const mpreal eint    (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(eint   );    }\ninline const mpreal gamma   (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(gamma  );    }\ninline const mpreal tgamma  (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(gamma  );    }\ninline const mpreal lngamma (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(lngamma);    }\ninline const mpreal zeta    (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(zeta   );    }\ninline const mpreal erf     (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(erf    );    }\ninline const mpreal erfc    (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(erfc   );    }\ninline const mpreal besselj0(const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(j0     );    }\ninline const mpreal besselj1(const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(j1     );    }\ninline const mpreal bessely0(const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(y0     );    }\ninline const mpreal bessely1(const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(y1     );    }\n\ninline const mpreal nextpow2(const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) \n{   \n    mpreal y(0, x.getPrecision());\n\n    if(!iszero(x)) \n        y = ceil(log2(abs(x,r),r));\n\n    return y;\n}\n\ninline const mpreal atan2 (const mpreal& y, const mpreal& x, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    mpreal a(0,(std::max)(y.getPrecision(), x.getPrecision()));\n    mpfr_atan2(a.mpfr_ptr(), y.mpfr_srcptr(), x.mpfr_srcptr(), rnd_mode);\n    return a;\n}\n\ninline const mpreal hypot (const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    mpreal a(0,(std::max)(y.getPrecision(), x.getPrecision()));\n    mpfr_hypot(a.mpfr_ptr(), x.mpfr_srcptr(), y.mpfr_srcptr(), rnd_mode);\n    return a;\n}\n\ninline const mpreal hypot(const mpreal& a, const mpreal& b, const mpreal& c)  \n{\n    if(isnan EIGEN_NOT_A_MACRO (a) || isnan EIGEN_NOT_A_MACRO (b) || isnan EIGEN_NOT_A_MACRO(c)) return mpreal().setNan();\n    else\n    {\n        mpreal absa = abs(a), absb = abs(b), absc = abs(c);\n        mpreal w = (std::max)(absa, (std::max)(absb, absc));\n        mpreal r;\n\n        if (!iszero(w))\n        {\n            mpreal iw = 1/w;\n            r = w * sqrt(sqr(absa*iw) + sqr(absb*iw) + sqr(absc*iw));\n        }\n\n        return r; \n    }\n}\n\ninline const mpreal hypot(const mpreal& a, const mpreal& b, const mpreal& c, const mpreal& d)  \n{\n    if(isnan EIGEN_NOT_A_MACRO (a) || isnan EIGEN_NOT_A_MACRO (b) || isnan EIGEN_NOT_A_MACRO (c) || isnan EIGEN_NOT_A_MACRO (d)) return mpreal().setNan();\n    else\n    {\n        mpreal absa = abs(a), absb = abs(b), absc = abs(c), absd = abs(d);\n        mpreal w = (std::max)(absa, (std::max)(absb, (std::max)(absc, absd)));\n        mpreal r;\n\n        if (!iszero(w))\n        {\n            mpreal iw = 1/w;\n            r = w * sqrt(sqr(absa*iw) + sqr(absb*iw) + sqr(absc*iw) + sqr(absd*iw));\n        }\n\n        return r; \n    }\n}\n\ninline const mpreal remainder (const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{    \n    mpreal a(0,(std::max)(y.getPrecision(), x.getPrecision()));\n    mpfr_remainder(a.mpfr_ptr(), x.mpfr_srcptr(), y.mpfr_srcptr(), rnd_mode);\n    return a;\n}\n\ninline const mpreal remquo (long* q, const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    mpreal a(0,(std::max)(y.getPrecision(), x.getPrecision()));\n    mpfr_remquo(a.mpfr_ptr(),q, x.mpfr_srcptr(), y.mpfr_srcptr(), rnd_mode);\n    return a;\n}\n\ninline const mpreal fac_ui (unsigned long int v, mp_prec_t prec     = mpreal::get_default_prec(),\n\t\t\t                                     mp_rnd_t  rnd_mode = mpreal::get_default_rnd())\n{\n    mpreal x(0, prec);\n    mpfr_fac_ui(x.mpfr_ptr(),v,rnd_mode);\n    return x;\n}\n\n\ninline const mpreal lgamma (const mpreal& v, int *signp = 0, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    mpreal x(v);\n    int tsignp;\n\n    if(signp)   mpfr_lgamma(x.mpfr_ptr(),  signp,v.mpfr_srcptr(),rnd_mode);\n    else        mpfr_lgamma(x.mpfr_ptr(),&tsignp,v.mpfr_srcptr(),rnd_mode);\n\n    return x;\n}\n\n\ninline const mpreal besseljn (long n, const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd())\n{\n    mpreal  y(0, x.getPrecision());\n    mpfr_jn(y.mpfr_ptr(), n, x.mpfr_srcptr(), r);\n    return y;\n}\n\ninline const mpreal besselyn (long n, const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd())\n{\n    mpreal  y(0, x.getPrecision());\n    mpfr_yn(y.mpfr_ptr(), n, x.mpfr_srcptr(), r);\n    return y;\n}\n\ninline const mpreal fma (const mpreal& v1, const mpreal& v2, const mpreal& v3, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    mpreal a;\n    mp_prec_t p1, p2, p3;\n\n    p1 = v1.get_prec(); \n    p2 = v2.get_prec(); \n    p3 = v3.get_prec(); \n\n    a.set_prec(p3>p2?(p3>p1?p3:p1):(p2>p1?p2:p1));\n\n    mpfr_fma(a.mp,v1.mp,v2.mp,v3.mp,rnd_mode);\n    return a;\n}\n\ninline const mpreal fms (const mpreal& v1, const mpreal& v2, const mpreal& v3, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    mpreal a;\n    mp_prec_t p1, p2, p3;\n\n    p1 = v1.get_prec(); \n    p2 = v2.get_prec(); \n    p3 = v3.get_prec(); \n\n    a.set_prec(p3>p2?(p3>p1?p3:p1):(p2>p1?p2:p1));\n\n    mpfr_fms(a.mp,v1.mp,v2.mp,v3.mp,rnd_mode);\n    return a;\n}\n\ninline const mpreal agm (const mpreal& v1, const mpreal& v2, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    mpreal a;\n    mp_prec_t p1, p2;\n\n    p1 = v1.get_prec(); \n    p2 = v2.get_prec(); \n\n    a.set_prec(p1>p2?p1:p2);\n\n    mpfr_agm(a.mp, v1.mp, v2.mp, rnd_mode);\n\n    return a;\n}\n\ninline const mpreal sum (const mpreal tab[], const unsigned long int n, int& status, mp_rnd_t mode = mpreal::get_default_rnd())\n{\n    mpfr_srcptr *p = new mpfr_srcptr[n];\n\n    for (unsigned long int  i = 0; i < n; i++)\n        p[i] = tab[i].mpfr_srcptr();\n\n    mpreal x;\n    status = mpfr_sum(x.mpfr_ptr(), (mpfr_ptr*)p, n, mode);\n    \n    delete [] p;\n    return x;\n}\n\n//////////////////////////////////////////////////////////////////////////\n// MPFR 2.4.0 Specifics\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(2,4,0))\n\ninline int sinh_cosh(mpreal& s, mpreal& c, const mpreal& v, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    return mpfr_sinh_cosh(s.mp,c.mp,v.mp,rnd_mode);\n}\n\ninline const mpreal li2 (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) \n{   \n    MPREAL_UNARY_MATH_FUNCTION_BODY(li2);    \n}\n\ninline const mpreal rem (const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    /*  R = rem(X,Y) if Y != 0, returns X - n * Y where n = trunc(X/Y). */\n    return fmod(x, y, rnd_mode);\n}\n\ninline const mpreal mod (const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    (void)rnd_mode;\n    \n    /*  \n\n    m = mod(x,y) if y != 0, returns x - n*y where n = floor(x/y)\n\n    The following are true by convention:\n    - mod(x,0) is x\n    - mod(x,x) is 0\n    - mod(x,y) for x != y and y != 0 has the same sign as y.    \n    \n    */\n\n    if(iszero(y)) return x;\n    if(x == y) return 0;\n\n    mpreal m = x - floor(x / y) * y;\n\n    return copysign(abs(m),y); // make sure result has the same sign as Y\n}\n\ninline const mpreal fmod (const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    mpreal a;\n    mp_prec_t yp, xp;\n\n    yp = y.get_prec(); \n    xp = x.get_prec(); \n\n    a.set_prec(yp>xp?yp:xp);\n\n    mpfr_fmod(a.mp, x.mp, y.mp, rnd_mode);\n\n    return a;\n}\n\ninline const mpreal rec_sqrt(const mpreal& v, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    mpreal x(v);\n    mpfr_rec_sqrt(x.mp,v.mp,rnd_mode);\n    return x;\n}\n#endif //  MPFR 2.4.0 Specifics\n\n//////////////////////////////////////////////////////////////////////////\n// MPFR 3.0.0 Specifics\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(3,0,0))\ninline const mpreal digamma (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(digamma);     }\ninline const mpreal ai      (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(ai);          }\n#endif // MPFR 3.0.0 Specifics\n\n//////////////////////////////////////////////////////////////////////////\n// Constants\ninline const mpreal const_log2 (mp_prec_t p = mpreal::get_default_prec(), mp_rnd_t r = mpreal::get_default_rnd())\n{\n    mpreal x(0, p);\n    mpfr_const_log2(x.mpfr_ptr(), r);\n    return x;\n}\n\ninline const mpreal const_pi (mp_prec_t p = mpreal::get_default_prec(), mp_rnd_t r = mpreal::get_default_rnd())\n{\n    mpreal x(0, p);\n    mpfr_const_pi(x.mpfr_ptr(), r);\n    return x;\n}\n\ninline const mpreal const_euler (mp_prec_t p = mpreal::get_default_prec(), mp_rnd_t r = mpreal::get_default_rnd())\n{\n    mpreal x(0, p);\n    mpfr_const_euler(x.mpfr_ptr(), r);\n    return x;\n}\n\ninline const mpreal const_catalan (mp_prec_t p = mpreal::get_default_prec(), mp_rnd_t r = mpreal::get_default_rnd())\n{\n    mpreal x(0, p);\n    mpfr_const_catalan(x.mpfr_ptr(), r);\n    return x;\n}\n\ninline const mpreal const_infinity (int sign = 1, mp_prec_t p = mpreal::get_default_prec())\n{\n    mpreal x(0, p);\n    mpfr_set_inf(x.mpfr_ptr(), sign);\n    return x;\n}\n\n//////////////////////////////////////////////////////////////////////////\n// Integer Related Functions\ninline const mpreal ceil(const mpreal& v)\n{\n    mpreal x(v);\n    mpfr_ceil(x.mp,v.mp);\n    return x;\n}\n\ninline const mpreal floor(const mpreal& v)\n{\n    mpreal x(v);\n    mpfr_floor(x.mp,v.mp);\n    return x;\n}\n\ninline const mpreal round(const mpreal& v)\n{\n    mpreal x(v);\n    mpfr_round(x.mp,v.mp);\n    return x;\n}\n\ninline const mpreal trunc(const mpreal& v)\n{\n    mpreal x(v);\n    mpfr_trunc(x.mp,v.mp);\n    return x;\n}\n\ninline const mpreal rint       (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(rint      );     }\ninline const mpreal rint_ceil  (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(rint_ceil );     }\ninline const mpreal rint_floor (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(rint_floor);     }\ninline const mpreal rint_round (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(rint_round);     }\ninline const mpreal rint_trunc (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(rint_trunc);     }\ninline const mpreal frac       (const mpreal& x, mp_rnd_t r = mpreal::get_default_rnd()) {   MPREAL_UNARY_MATH_FUNCTION_BODY(frac      );     }\n\n//////////////////////////////////////////////////////////////////////////\n// Miscellaneous Functions\ninline int sgn(const mpreal& op)\n{\n    // Please note, this is classic signum function which ignores sign of zero.\n    // Use signbit if you need sign of zero.\n    return mpfr_sgn(op.mpfr_srcptr());\n}\n\n//////////////////////////////////////////////////////////////////////////\n// Miscellaneous Functions\ninline void         swap (mpreal& a, mpreal& b)            {    mpfr_swap(a.mpfr_ptr(),b.mpfr_ptr());   }\ninline const mpreal (max)(const mpreal& x, const mpreal& y){    return (x>y?x:y);       }\ninline const mpreal (min)(const mpreal& x, const mpreal& y){    return (x<y?x:y);       }\n\ninline const mpreal fmax(const mpreal& x, const mpreal& y, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    mpreal a;\n    mpfr_max(a.mp,x.mp,y.mp,rnd_mode);\n    return a;\n}\n\ninline const mpreal fmin(const mpreal& x, const mpreal& y,  mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    mpreal a;\n    mpfr_min(a.mp,x.mp,y.mp,rnd_mode);\n    return a;\n}\n\ninline const mpreal nexttoward (const mpreal& x, const mpreal& y)\n{\n    mpreal a(x);\n    mpfr_nexttoward(a.mp,y.mp);\n    return a;\n}\n\ninline const mpreal nextabove  (const mpreal& x)\n{\n    mpreal a(x);\n    mpfr_nextabove(a.mp);\n    return a;\n}\n\ninline const mpreal nextbelow  (const mpreal& x)\n{\n    mpreal a(x);\n    mpfr_nextbelow(a.mp);\n    return a;\n}\n\ninline const mpreal urandomb (gmp_randstate_t& state)\n{\n    mpreal x;\n    mpfr_urandomb(x.mpfr_ptr(),state);\n    return x;\n}\n\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(3,0,0))\ninline const mpreal urandom (gmp_randstate_t& state, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    mpreal x;\n    mpfr_urandom(x.mpfr_ptr(), state, rnd_mode);\n    return x;\n}\n#endif\n\n#if (MPFR_VERSION <= MPFR_VERSION_NUM(2,4,2))\ninline const mpreal random2 (mp_size_t size, mp_exp_t exp)\n{\n    mpreal x;\n    mpfr_random2(x.mpfr_ptr(),size,exp);\n    return x;\n}\n#endif\n\n// Uniformly distributed random number generation\n// a = random(seed); <- initialization & first random number generation\n// a = random();     <- next random numbers generation\n// seed != 0\ninline const mpreal random(unsigned int seed = 0)\n{\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(3,0,0))\n    static gmp_randstate_t state;\n    static bool initialize = true;\n\n    if(initialize)\n    {\n        gmp_randinit_default(state);\n        gmp_randseed_ui(state,0);\n        initialize = false;\n    }\n\n    if(seed != 0)    gmp_randseed_ui(state,seed);\n\n    return mpfr::urandom(state);\n#else\n    if(seed != 0)    std::srand(seed);\n    return mpfr::mpreal(std::rand()/(double)RAND_MAX);\n#endif\n\n}\n\n#if (MPFR_VERSION >= MPFR_VERSION_NUM(3,1,0) && MPFR_VERSION < MPFR_VERSION_NUM(4,0,0))\n\n// TODO: \n// Use mpfr_nrandom since mpfr_grandom is deprecated\n#if defined(_MSC_VER)\n#pragma warning( push )\n#pragma warning( disable : 1478)\n#endif\ninline const mpreal grandom (gmp_randstate_t& state, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    mpreal x;\n    mpfr_grandom(x.mpfr_ptr(), NULL, state, rnd_mode);\n    return x;\n}\n#if defined(_MSC_VER)\n#pragma warning( pop )\n#endif\n\ninline const mpreal grandom(unsigned int seed = 0)\n{\n    static gmp_randstate_t state;\n    static bool initialize = true;\n\n    if(initialize)\n    {\n        gmp_randinit_default(state);\n        gmp_randseed_ui(state,0);\n        initialize = false;\n    }\n\n    if(seed != 0) gmp_randseed_ui(state,seed);\n\n    return mpfr::grandom(state);\n}\n#endif\n\n//////////////////////////////////////////////////////////////////////////\n// Set/Get global properties\ninline void mpreal::set_default_prec(mp_prec_t prec)\n{ \n    mpfr_set_default_prec(prec); \n}\n\ninline void mpreal::set_default_rnd(mp_rnd_t rnd_mode)\n{ \n    mpfr_set_default_rounding_mode(rnd_mode); \n}\n\ninline bool mpreal::fits_in_bits(double x, int n)\n{   \n    int i;\n    double t;\n    return IsInf(x) || (std::modf ( std::ldexp ( std::frexp ( x, &i ), n ), &t ) == 0.0);\n}\n\ninline const mpreal pow(const mpreal& a, const mpreal& b, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    mpreal x(a);\n    mpfr_pow(x.mp,x.mp,b.mp,rnd_mode);\n    return x;\n}\n\ninline const mpreal pow(const mpreal& a, const mpz_t b, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    mpreal x(a);\n    mpfr_pow_z(x.mp,x.mp,b,rnd_mode);\n    return x;\n}\n\ninline const mpreal pow(const mpreal& a, const unsigned long int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    mpreal x(a);\n    mpfr_pow_ui(x.mp,x.mp,b,rnd_mode);\n    return x;\n}\n\ninline const mpreal pow(const mpreal& a, const unsigned int b, mp_rnd_t rnd_mode)\n{\n    return pow(a,static_cast<unsigned long int>(b),rnd_mode);\n}\n\ninline const mpreal pow(const mpreal& a, const long int b, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    mpreal x(a);\n    mpfr_pow_si(x.mp,x.mp,b,rnd_mode);\n    return x;\n}\n\ninline const mpreal pow(const mpreal& a, const int b, mp_rnd_t rnd_mode)\n{\n    return pow(a,static_cast<long int>(b),rnd_mode);\n}\n\ninline const mpreal pow(const mpreal& a, const long double b, mp_rnd_t rnd_mode)\n{\n    return pow(a,mpreal(b),rnd_mode);\n}\n\ninline const mpreal pow(const mpreal& a, const double b, mp_rnd_t rnd_mode)\n{\n    return pow(a,mpreal(b),rnd_mode);\n}\n\ninline const mpreal pow(const unsigned long int a, const mpreal& b, mp_rnd_t rnd_mode = mpreal::get_default_rnd())\n{\n    mpreal x(a);\n    mpfr_ui_pow(x.mp,a,b.mp,rnd_mode);\n    return x;\n}\n\ninline const mpreal pow(const unsigned int a, const mpreal& b, mp_rnd_t rnd_mode)\n{\n    return pow(static_cast<unsigned long int>(a),b,rnd_mode);\n}\n\ninline const mpreal pow(const long int a, const mpreal& b, mp_rnd_t rnd_mode)\n{\n    if (a>=0)     return pow(static_cast<unsigned long int>(a),b,rnd_mode);\n    else          return pow(mpreal(a),b,rnd_mode);\n}\n\ninline const mpreal pow(const int a, const mpreal& b, mp_rnd_t rnd_mode)\n{\n    if (a>=0)     return pow(static_cast<unsigned long int>(a),b,rnd_mode);\n    else          return pow(mpreal(a),b,rnd_mode);\n}\n\ninline const mpreal pow(const long double a, const mpreal& b, mp_rnd_t rnd_mode)\n{\n    return pow(mpreal(a),b,rnd_mode);\n}\n\ninline const mpreal pow(const double a, const mpreal& b, mp_rnd_t rnd_mode)\n{\n    return pow(mpreal(a),b,rnd_mode);\n}\n\n// pow unsigned long int\ninline const mpreal pow(const unsigned long int a, const unsigned long int b, mp_rnd_t rnd_mode)\n{\n    mpreal x(a);\n    mpfr_ui_pow_ui(x.mp,a,b,rnd_mode);\n    return x;\n}\n\ninline const mpreal pow(const unsigned long int a, const unsigned int b, mp_rnd_t rnd_mode)\n{\n    return pow(a,static_cast<unsigned long int>(b),rnd_mode); //mpfr_ui_pow_ui\n}\n\ninline const mpreal pow(const unsigned long int a, const long int b, mp_rnd_t rnd_mode)\n{\n    if(b>0)    return pow(a,static_cast<unsigned long int>(b),rnd_mode); //mpfr_ui_pow_ui\n    else       return pow(a,mpreal(b),rnd_mode); //mpfr_ui_pow\n}\n\ninline const mpreal pow(const unsigned long int a, const int b, mp_rnd_t rnd_mode)\n{\n    if(b>0)    return pow(a,static_cast<unsigned long int>(b),rnd_mode); //mpfr_ui_pow_ui\n    else       return pow(a,mpreal(b),rnd_mode); //mpfr_ui_pow\n}\n\ninline const mpreal pow(const unsigned long int a, const long double b, mp_rnd_t rnd_mode)\n{\n    return pow(a,mpreal(b),rnd_mode); //mpfr_ui_pow\n}\n\ninline const mpreal pow(const unsigned long int a, const double b, mp_rnd_t rnd_mode)\n{\n    return pow(a,mpreal(b),rnd_mode); //mpfr_ui_pow\n}\n\n// pow unsigned int\ninline const mpreal pow(const unsigned int a, const unsigned long int b, mp_rnd_t rnd_mode)\n{\n    return pow(static_cast<unsigned long int>(a),b,rnd_mode); //mpfr_ui_pow_ui\n}\n\ninline const mpreal pow(const unsigned int a, const unsigned int b, mp_rnd_t rnd_mode)\n{\n    return pow(static_cast<unsigned long int>(a),static_cast<unsigned long int>(b),rnd_mode); //mpfr_ui_pow_ui\n}\n\ninline const mpreal pow(const unsigned int a, const long int b, mp_rnd_t rnd_mode)\n{\n    if(b>0) return pow(static_cast<unsigned long int>(a),static_cast<unsigned long int>(b),rnd_mode); //mpfr_ui_pow_ui\n    else    return pow(static_cast<unsigned long int>(a),mpreal(b),rnd_mode); //mpfr_ui_pow\n}\n\ninline const mpreal pow(const unsigned int a, const int b, mp_rnd_t rnd_mode)\n{\n    if(b>0) return pow(static_cast<unsigned long int>(a),static_cast<unsigned long int>(b),rnd_mode); //mpfr_ui_pow_ui\n    else    return pow(static_cast<unsigned long int>(a),mpreal(b),rnd_mode); //mpfr_ui_pow\n}\n\ninline const mpreal pow(const unsigned int a, const long double b, mp_rnd_t rnd_mode)\n{\n    return pow(static_cast<unsigned long int>(a),mpreal(b),rnd_mode); //mpfr_ui_pow\n}\n\ninline const mpreal pow(const unsigned int a, const double b, mp_rnd_t rnd_mode)\n{\n    return pow(static_cast<unsigned long int>(a),mpreal(b),rnd_mode); //mpfr_ui_pow\n}\n\n// pow long int\ninline const mpreal pow(const long int a, const unsigned long int b, mp_rnd_t rnd_mode)\n{\n    if (a>0) return pow(static_cast<unsigned long int>(a),b,rnd_mode); //mpfr_ui_pow_ui\n    else     return pow(mpreal(a),b,rnd_mode); //mpfr_pow_ui\n}\n\ninline const mpreal pow(const long int a, const unsigned int b, mp_rnd_t rnd_mode)\n{\n    if (a>0) return pow(static_cast<unsigned long int>(a),static_cast<unsigned long int>(b),rnd_mode);  //mpfr_ui_pow_ui\n    else     return pow(mpreal(a),static_cast<unsigned long int>(b),rnd_mode); //mpfr_pow_ui\n}\n\ninline const mpreal pow(const long int a, const long int b, mp_rnd_t rnd_mode)\n{\n    if (a>0)\n    {\n        if(b>0) return pow(static_cast<unsigned long int>(a),static_cast<unsigned long int>(b),rnd_mode); //mpfr_ui_pow_ui\n        else    return pow(static_cast<unsigned long int>(a),mpreal(b),rnd_mode); //mpfr_ui_pow\n    }else{\n        return pow(mpreal(a),b,rnd_mode); // mpfr_pow_si\n    }\n}\n\ninline const mpreal pow(const long int a, const int b, mp_rnd_t rnd_mode)\n{\n    if (a>0)\n    {\n        if(b>0) return pow(static_cast<unsigned long int>(a),static_cast<unsigned long int>(b),rnd_mode); //mpfr_ui_pow_ui\n        else    return pow(static_cast<unsigned long int>(a),mpreal(b),rnd_mode); //mpfr_ui_pow\n    }else{\n        return pow(mpreal(a),static_cast<long int>(b),rnd_mode); // mpfr_pow_si\n    }\n}\n\ninline const mpreal pow(const long int a, const long double b, mp_rnd_t rnd_mode)\n{\n    if (a>=0)   return pow(static_cast<unsigned long int>(a),mpreal(b),rnd_mode); //mpfr_ui_pow\n    else        return pow(mpreal(a),mpreal(b),rnd_mode); //mpfr_pow\n}\n\ninline const mpreal pow(const long int a, const double b, mp_rnd_t rnd_mode)\n{\n    if (a>=0)   return pow(static_cast<unsigned long int>(a),mpreal(b),rnd_mode); //mpfr_ui_pow\n    else        return pow(mpreal(a),mpreal(b),rnd_mode); //mpfr_pow\n}\n\n// pow int\ninline const mpreal pow(const int a, const unsigned long int b, mp_rnd_t rnd_mode)\n{\n    if (a>0) return pow(static_cast<unsigned long int>(a),b,rnd_mode); //mpfr_ui_pow_ui\n    else     return pow(mpreal(a),b,rnd_mode); //mpfr_pow_ui\n}\n\ninline const mpreal pow(const int a, const unsigned int b, mp_rnd_t rnd_mode)\n{\n    if (a>0) return pow(static_cast<unsigned long int>(a),static_cast<unsigned long int>(b),rnd_mode);  //mpfr_ui_pow_ui\n    else     return pow(mpreal(a),static_cast<unsigned long int>(b),rnd_mode); //mpfr_pow_ui\n}\n\ninline const mpreal pow(const int a, const long int b, mp_rnd_t rnd_mode)\n{\n    if (a>0)\n    {\n        if(b>0) return pow(static_cast<unsigned long int>(a),static_cast<unsigned long int>(b),rnd_mode); //mpfr_ui_pow_ui\n        else    return pow(static_cast<unsigned long int>(a),mpreal(b),rnd_mode); //mpfr_ui_pow\n    }else{\n        return pow(mpreal(a),b,rnd_mode); // mpfr_pow_si\n    }\n}\n\ninline const mpreal pow(const int a, const int b, mp_rnd_t rnd_mode)\n{\n    if (a>0)\n    {\n        if(b>0) return pow(static_cast<unsigned long int>(a),static_cast<unsigned long int>(b),rnd_mode); //mpfr_ui_pow_ui\n        else    return pow(static_cast<unsigned long int>(a),mpreal(b),rnd_mode); //mpfr_ui_pow\n    }else{\n        return pow(mpreal(a),static_cast<long int>(b),rnd_mode); // mpfr_pow_si\n    }\n}\n\ninline const mpreal pow(const int a, const long double b, mp_rnd_t rnd_mode)\n{\n    if (a>=0)   return pow(static_cast<unsigned long int>(a),mpreal(b),rnd_mode); //mpfr_ui_pow\n    else        return pow(mpreal(a),mpreal(b),rnd_mode); //mpfr_pow\n}\n\ninline const mpreal pow(const int a, const double b, mp_rnd_t rnd_mode)\n{\n    if (a>=0)   return pow(static_cast<unsigned long int>(a),mpreal(b),rnd_mode); //mpfr_ui_pow\n    else        return pow(mpreal(a),mpreal(b),rnd_mode); //mpfr_pow\n}\n\n// pow long double \ninline const mpreal pow(const long double a, const long double b, mp_rnd_t rnd_mode)\n{\n    return pow(mpreal(a),mpreal(b),rnd_mode);\n}\n\ninline const mpreal pow(const long double a, const unsigned long int b, mp_rnd_t rnd_mode)\n{\n    return pow(mpreal(a),b,rnd_mode); //mpfr_pow_ui\n}\n\ninline const mpreal pow(const long double a, const unsigned int b, mp_rnd_t rnd_mode)\n{\n    return pow(mpreal(a),static_cast<unsigned long int>(b),rnd_mode); //mpfr_pow_ui\n}\n\ninline const mpreal pow(const long double a, const long int b, mp_rnd_t rnd_mode)\n{\n    return pow(mpreal(a),b,rnd_mode); // mpfr_pow_si\n}\n\ninline const mpreal pow(const long double a, const int b, mp_rnd_t rnd_mode)\n{\n    return pow(mpreal(a),static_cast<long int>(b),rnd_mode); // mpfr_pow_si\n}\n\ninline const mpreal pow(const double a, const double b, mp_rnd_t rnd_mode)\n{\n    return pow(mpreal(a),mpreal(b),rnd_mode);\n}\n\ninline const mpreal pow(const double a, const unsigned long int b, mp_rnd_t rnd_mode)\n{\n    return pow(mpreal(a),b,rnd_mode); // mpfr_pow_ui\n}\n\ninline const mpreal pow(const double a, const unsigned int b, mp_rnd_t rnd_mode)\n{\n    return pow(mpreal(a),static_cast<unsigned long int>(b),rnd_mode); // mpfr_pow_ui\n}\n\ninline const mpreal pow(const double a, const long int b, mp_rnd_t rnd_mode)\n{\n    return pow(mpreal(a),b,rnd_mode); // mpfr_pow_si\n}\n\ninline const mpreal pow(const double a, const int b, mp_rnd_t rnd_mode)\n{\n    return pow(mpreal(a),static_cast<long int>(b),rnd_mode); // mpfr_pow_si\n}\n} // End of mpfr namespace\n\n// Explicit specialization of std::swap for mpreal numbers\n// Thus standard algorithms will use efficient version of swap (due to Koenig lookup)\n// Non-throwing swap C++ idiom: http://en.wikibooks.org/wiki/More_C%2B%2B_Idioms/Non-throwing_swap\nnamespace std\n{\n\t// we are allowed to extend namespace std with specializations only\n    template <>\n    inline void swap(mpfr::mpreal& x, mpfr::mpreal& y) \n    { \n        return mpfr::swap(x, y); \n    }\n\n    template<>\n    class numeric_limits<mpfr::mpreal>\n    {\n    public:\n        static const bool is_specialized    = true;\n        static const bool is_signed         = true;\n        static const bool is_integer        = false;\n        static const bool is_exact          = false;\n        static const int  radix             = 2;    \n\n        static const bool has_infinity      = true;\n        static const bool has_quiet_NaN     = true;\n        static const bool has_signaling_NaN = true;\n\n        static const bool is_iec559         = true;        // = IEEE 754\n        static const bool is_bounded        = true;\n        static const bool is_modulo         = false;\n        static const bool traps             = true;\n        static const bool tinyness_before   = true;\n\n        static const float_denorm_style has_denorm  = denorm_absent;\n\n        inline static mpfr::mpreal (min)    (mp_prec_t precision = mpfr::mpreal::get_default_prec()) {  return  mpfr::minval(precision);  }\n        inline static mpfr::mpreal (max)    (mp_prec_t precision = mpfr::mpreal::get_default_prec()) {  return  mpfr::maxval(precision);  }\n        inline static mpfr::mpreal lowest   (mp_prec_t precision = mpfr::mpreal::get_default_prec()) {  return -mpfr::maxval(precision);  }\n\n        // Returns smallest eps such that 1 + eps != 1 (classic machine epsilon)\n        inline static mpfr::mpreal epsilon(mp_prec_t precision = mpfr::mpreal::get_default_prec()) {  return  mpfr::machine_epsilon(precision); }\n\t\t\n        // Returns smallest eps such that x + eps != x (relative machine epsilon)\n        inline static mpfr::mpreal epsilon(const mpfr::mpreal& x) {  return mpfr::machine_epsilon(x);  }\n\n        inline static mpfr::mpreal round_error(mp_prec_t precision = mpfr::mpreal::get_default_prec())\n        {\n            mp_rnd_t r = mpfr::mpreal::get_default_rnd();\n\n            if(r == GMP_RNDN)  return mpfr::mpreal(0.5, precision); \n            else               return mpfr::mpreal(1.0, precision);    \n        }\n\n        inline static const mpfr::mpreal infinity()         { return mpfr::const_infinity();     }\n        inline static const mpfr::mpreal quiet_NaN()        { return mpfr::mpreal().setNan();    }\n        inline static const mpfr::mpreal signaling_NaN()    { return mpfr::mpreal().setNan();    }\n        inline static const mpfr::mpreal denorm_min()       { return (min)();                    }\n\n        // Please note, exponent range is not fixed in MPFR\n        static const int min_exponent = MPFR_EMIN_DEFAULT;\n        static const int max_exponent = MPFR_EMAX_DEFAULT;\n        MPREAL_PERMISSIVE_EXPR static const int min_exponent10 = (int) (MPFR_EMIN_DEFAULT * 0.3010299956639811); \n        MPREAL_PERMISSIVE_EXPR static const int max_exponent10 = (int) (MPFR_EMAX_DEFAULT * 0.3010299956639811); \n\n#ifdef MPREAL_HAVE_DYNAMIC_STD_NUMERIC_LIMITS\n\n        // Following members should be constant according to standard, but they can be variable in MPFR\n        // So we define them as functions here. \n        //\n        // This is preferable way for std::numeric_limits<mpfr::mpreal> specialization.\n        // But it is incompatible with standard std::numeric_limits and might not work with other libraries, e.g. boost. \n        // See below for compatible implementation. \n        inline static float_round_style round_style()\n        {\n            mp_rnd_t r = mpfr::mpreal::get_default_rnd();\n\n            switch (r)\n            {\n            case GMP_RNDN: return round_to_nearest;\n            case GMP_RNDZ: return round_toward_zero; \n            case GMP_RNDU: return round_toward_infinity; \n            case GMP_RNDD: return round_toward_neg_infinity; \n            default: return round_indeterminate;\n            }\n        }\n\n        inline static int digits()                        {    return int(mpfr::mpreal::get_default_prec());    }\n        inline static int digits(const mpfr::mpreal& x)   {    return x.getPrecision();                         }\n\n        inline static int digits10(mp_prec_t precision = mpfr::mpreal::get_default_prec())\n        {\n            return mpfr::bits2digits(precision);\n        }\n\n        inline static int digits10(const mpfr::mpreal& x)\n        {\n            return mpfr::bits2digits(x.getPrecision());\n        }\n\n        inline static int max_digits10(mp_prec_t precision = mpfr::mpreal::get_default_prec())\n        {\n            return digits10(precision);\n        }\n#else\n        // Digits and round_style are NOT constants when it comes to mpreal.\n        // If possible, please use functions digits() and round_style() defined above.\n        //\n        // These (default) values are preserved for compatibility with existing libraries, e.g. boost.\n        // Change them accordingly to your application. \n        //\n        // For example, if you use 256 bits of precision uniformly in your program, then:\n        // digits       = 256\n        // digits10     = 77 \n        // max_digits10 = 78\n        // \n        // Approximate formula for decimal digits is: digits10 = floor(log10(2) * digits). See bits2digits() for more details.\n\n        static const std::float_round_style round_style = round_to_nearest;\n        static const int digits       = 53;\n        static const int digits10     = 15;\n        static const int max_digits10 = 16;\n#endif\n    };\n\n}\n\n#endif /* __MPREAL_H__ */\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/mpreal_support.cpp",
    "content": "#include \"main.h\"\n#include <Eigen/MPRealSupport>\n#include <Eigen/LU>\n#include <Eigen/Eigenvalues>\n#include <sstream>\n\nusing namespace mpfr;\nusing namespace Eigen;\n\nEIGEN_DECLARE_TEST(mpreal_support)\n{\n  // set precision to 256 bits (double has only 53 bits)\n  mpreal::set_default_prec(256);\n  typedef Matrix<mpreal,Eigen::Dynamic,Eigen::Dynamic> MatrixXmp;\n  typedef Matrix<std::complex<mpreal>,Eigen::Dynamic,Eigen::Dynamic> MatrixXcmp;\n\n  std::cerr << \"epsilon =         \" << NumTraits<mpreal>::epsilon() << \"\\n\";\n  std::cerr << \"dummy_precision = \" << NumTraits<mpreal>::dummy_precision() << \"\\n\";\n  std::cerr << \"highest =         \" << NumTraits<mpreal>::highest() << \"\\n\";\n  std::cerr << \"lowest =          \" << NumTraits<mpreal>::lowest() << \"\\n\";\n  std::cerr << \"digits10 =        \" << NumTraits<mpreal>::digits10() << \"\\n\";\n\n  for(int i = 0; i < g_repeat; i++) {\n    int s = Eigen::internal::random<int>(1,100);\n    MatrixXmp A = MatrixXmp::Random(s,s);\n    MatrixXmp B = MatrixXmp::Random(s,s);\n    MatrixXmp S = A.adjoint() * A;\n    MatrixXmp X;\n    MatrixXcmp Ac = MatrixXcmp::Random(s,s);\n    MatrixXcmp Bc = MatrixXcmp::Random(s,s);\n    MatrixXcmp Sc = Ac.adjoint() * Ac;\n    MatrixXcmp Xc;\n    \n    // Basic stuffs\n    VERIFY_IS_APPROX(A.real(), A);\n    VERIFY(Eigen::internal::isApprox(A.array().abs2().sum(), A.squaredNorm()));\n    VERIFY_IS_APPROX(A.array().exp(),         exp(A.array()));\n    VERIFY_IS_APPROX(A.array().abs2().sqrt(), A.array().abs());\n    VERIFY_IS_APPROX(A.array().sin(),         sin(A.array()));\n    VERIFY_IS_APPROX(A.array().cos(),         cos(A.array()));\n\n    // Cholesky\n    X = S.selfadjointView<Lower>().llt().solve(B);\n    VERIFY_IS_APPROX((S.selfadjointView<Lower>()*X).eval(),B);\n\n    Xc = Sc.selfadjointView<Lower>().llt().solve(Bc);\n    VERIFY_IS_APPROX((Sc.selfadjointView<Lower>()*Xc).eval(),Bc);\n    \n    // partial LU\n    X = A.lu().solve(B);\n    VERIFY_IS_APPROX((A*X).eval(),B);\n\n    // symmetric eigenvalues\n    SelfAdjointEigenSolver<MatrixXmp> eig(S);\n    VERIFY_IS_EQUAL(eig.info(), Success);\n    VERIFY( (S.selfadjointView<Lower>() * eig.eigenvectors()).isApprox(eig.eigenvectors() * eig.eigenvalues().asDiagonal(), NumTraits<mpreal>::dummy_precision()*1e3) );\n  }\n  \n  {\n    MatrixXmp A(8,3); A.setRandom();\n    // test output (interesting things happen in this code)\n    std::stringstream stream;\n    stream << A;\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/openglsupport.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <main.h>\n#include <iostream>\n#include <string>\n\n#if defined(__APPLE_CC__)\n  // Prevent deprecation warnings caused by GLEW on MacOS.\n  #define GL_SILENCE_DEPRECATION 1\n#endif\n#include <GL/glew.h>\n#include <Eigen/OpenGLSupport>\n#if defined(__APPLE_CC__)\n  #include <GLUT/glut.h>\n#else\n  #include <GL/freeglut.h>\n#endif\n\nusing namespace Eigen;\n\n#define VERIFY_MATRIX(CODE,REF) { \\\n    glMatrixMode(GL_MODELVIEW); \\\n    glLoadIdentity(); \\\n    CODE; \\\n    Matrix<float,4,4,ColMajor> m; m.setZero(); \\\n    glGet(GL_MODELVIEW_MATRIX, m); \\\n    if(!(REF).cast<float>().isApprox(m)) { \\\n      std::cerr << \"Expected:\\n\" << ((REF).cast<float>()) << \"\\n\" << \"got\\n\" << m << \"\\n\\n\"; \\\n    } \\\n    VERIFY_IS_APPROX((REF).cast<float>(), m); \\\n  }\n\n#define VERIFY_UNIFORM(SUFFIX,NAME,TYPE) { \\\n    TYPE value; value.setRandom(); \\\n    TYPE data; \\\n    int loc = glGetUniformLocation(prg_id, #NAME); \\\n    VERIFY((loc!=-1) && \"uniform not found\"); \\\n    glUniform(loc,value); \\\n    EIGEN_CAT(glGetUniform,SUFFIX)(prg_id,loc,data.data()); \\\n    if(!value.isApprox(data)) { \\\n      std::cerr << \"Expected:\\n\" << value << \"\\n\" << \"got\\n\" << data << \"\\n\\n\"; \\\n    } \\\n    VERIFY_IS_APPROX(value, data); \\\n  }\n\n#define VERIFY_UNIFORMi(NAME,TYPE) { \\\n    TYPE value = TYPE::Random().eval().cast<float>().cast<TYPE::Scalar>(); \\\n    TYPE data; \\\n    int loc = glGetUniformLocation(prg_id, #NAME); \\\n    VERIFY((loc!=-1) && \"uniform not found\"); \\\n    glUniform(loc,value); \\\n    glGetUniformiv(prg_id,loc,(GLint*)data.data()); \\\n    if(!value.isApprox(data)) { \\\n      std::cerr << \"Expected:\\n\" << value << \"\\n\" << \"got\\n\" << data << \"\\n\\n\"; \\\n    } \\\n    VERIFY_IS_APPROX(value, data); \\\n  }\n\nvoid printProgramInfoLog(GLuint objectID)\n{\n    int infologLength, charsWritten;\n    GLchar *infoLog;\n    glGetProgramiv(objectID, GL_INFO_LOG_LENGTH, &infologLength);\n    if(infologLength > 0)\n    {\n        infoLog = new GLchar[infologLength];\n        glGetProgramInfoLog(objectID, infologLength, &charsWritten, infoLog);\n        if (charsWritten > 0)\n          std::cerr << \"Program info : \\n\" << infoLog << std::endl;\n        delete[] infoLog;\n    }\n}\n\nvoid printShaderInfoLog(GLuint objectID)\n{\n    int infologLength, charsWritten;\n    GLchar *infoLog;\n    glGetShaderiv(objectID, GL_INFO_LOG_LENGTH, &infologLength);\n    if(infologLength > 0)\n    {\n        infoLog = new GLchar[infologLength];\n        glGetShaderInfoLog(objectID, infologLength, &charsWritten, infoLog);\n        if (charsWritten > 0)\n          std::cerr << \"Shader info : \\n\" << infoLog << std::endl;\n        delete[] infoLog;\n    }\n}\n\nGLint createProgram(const char* vtx, const char* frg, bool print_errors = true)\n{\n  GLint prg_id = glCreateProgram();\n  GLint vtx_id = glCreateShader(GL_VERTEX_SHADER);\n  GLint frg_id = glCreateShader(GL_FRAGMENT_SHADER);\n  GLint ok;\n\n  glShaderSource(vtx_id, 1, &vtx, 0);\n  glCompileShader(vtx_id);\n  glGetShaderiv(vtx_id, GL_COMPILE_STATUS, &ok);\n  if(!ok)\n  {\n    if (print_errors)\n    {\n      std::cerr << \"vtx compilation failed\\n\";\n      std::cerr << \"Source:\\n\" << vtx << \"\\n\";\n      printShaderInfoLog(vtx_id);\n    }\n    glDeleteShader(vtx_id);\n    return GL_ZERO;\n  }\n\n  glShaderSource(frg_id, 1, &frg, 0);\n  glCompileShader(frg_id);\n  glGetShaderiv(frg_id, GL_COMPILE_STATUS, &ok);\n  if(!ok)\n  {\n    if (print_errors)\n    {\n      std::cerr << \"frg compilation failed.\\n\";\n      std::cerr << \"Source:\\n\" << frg << \"\\n\";\n      printShaderInfoLog(frg_id);\n    }\n    glDeleteShader(vtx_id);\n    glDeleteShader(frg_id);\n    return GL_ZERO;\n  }\n\n  glAttachShader(prg_id, vtx_id);\n  glAttachShader(prg_id, frg_id);\n  glLinkProgram(prg_id);\n\n  // Delete shaders once linked.\n  glDeleteShader(vtx_id);\n  glDeleteShader(frg_id);\n  glGetProgramiv(prg_id, GL_LINK_STATUS, &ok);\n  if(!ok)\n  {\n    if (print_errors)\n    {\n      std::cerr << \"linking failed.\\n\";\n      printProgramInfoLog(prg_id);\n    }\n    glDeleteProgram(prg_id);\n    return GL_ZERO;\n  }\n\n  glUseProgram(prg_id);\n  return prg_id;\n}\n\nGLint createProgram(const std::string& vtx, const std::string& frg, bool print_errors = true)\n{\n  return createProgram(vtx.c_str(), frg.c_str(), print_errors);\n}\n\nstd::string getGlslVersionString(int gl_major_version, int gl_minor_version)\n{\n  switch (gl_major_version)\n  {\n    case 2:\n      switch (gl_minor_version)\n      {\n        case 0:\n          return \"#version 110\";\n        case 1:\n          return \"#version 120\";\n      }\n      break;\n    case 3:\n      switch (gl_minor_version)\n      {\n        case 0:\n          return \"#version 130\";\n        case 1:\n          return \"#version 140\";\n        case 2:\n          return \"#version 150\";\n        case 3:\n          return \"#version 330\";\n      }\n      break;\n    case 4:\n      switch (gl_minor_version)\n      {\n        case 0:\n          return \"#version 400\";\n        case 1:\n          return \"#version 410\";\n        case 2:\n          return \"#version 420\";\n        case 3:\n          return \"#version 430\";\n        case 4:\n          return \"#version 440\";\n        case 5:\n          return \"#version 450\";\n        case 6:\n          return \"#version 460\";\n      }\n      break;\n  }\n  return \"\";\n}\n\nvoid find_and_replace(\n  std::string& str,\n  const std::string& find,\n  const std::string& replace)\n{\n  size_t loc = 0;\n  size_t flen = find.length();\n  size_t rlen = replace.length();\n  while ( (loc = str.find(find, loc)) != std::string::npos) {\n    str.replace(loc, flen, replace);\n    loc += rlen;\n  }\n}\n\n// Finds and replaces a set of substrings in a string.\nstd::string format(\n  const std::string& str,\n  const std::vector<std::string>& find,\n  const std::vector<std::string>& replace)\n{\n  std::string out = str;\n  for (std::size_t i=0; i<find.size(); ++i) {\n    find_and_replace(out, find[i], replace[i]);\n  }\n  return out;\n}\n\n// GLUT display function that runs test.  Must be run within the display loop\n// in order to properly destroy resources.\nvoid openglsupport_test_loop()\n{\n  // Get context info.\n  const GLubyte* gl_version_string = glGetString(GL_VERSION);\n  std::cerr << \"GL version: \" << gl_version_string << std::endl;\n  std::cerr << \"GLSL version: \" << glGetString(GL_SHADING_LANGUAGE_VERSION) << std::endl;\n  // Parse version from string since GL_MAJOR_VERSION is only supported in GL 3.0+.\n  // Version string guaranteed to be <major>.<minor><vender extension>.\n  GLint gl_major_version = gl_version_string[0] - '0';\n  GLint gl_minor_version = gl_version_string[2] - '0';\n  bool legacy_gl = gl_major_version < 3 || (gl_major_version == 3 && gl_minor_version < 2);\n\n  // Fixed-function pipeline removed in OpenGL 3.2.\n  if (legacy_gl)\n  {\n    // Draw a basic triangle.\n    Vector3f v3f;\n    Matrix3f rot;\n    glBegin(GL_POINTS);\n    {\n      glVertex(v3f);\n      glVertex(2*v3f+v3f);\n      glVertex(rot*v3f);\n    }\n    glEnd();\n\n    // 4x4 matrices\n    Matrix4f mf44; mf44.setRandom();\n    VERIFY_MATRIX(glLoadMatrix(mf44), mf44);\n    VERIFY_MATRIX(glMultMatrix(mf44), mf44);\n    Matrix4d md44; md44.setRandom();\n    VERIFY_MATRIX(glLoadMatrix(md44), md44);\n    VERIFY_MATRIX(glMultMatrix(md44), md44);\n\n    // Quaternion\n    Quaterniond qd(AngleAxisd(internal::random<double>(), Vector3d::Random()));\n    VERIFY_MATRIX(glRotate(qd), Projective3d(qd).matrix());\n\n    Quaternionf qf(AngleAxisf(internal::random<double>(), Vector3f::Random()));\n    VERIFY_MATRIX(glRotate(qf), Projective3f(qf).matrix());\n\n    // 3D Transform\n    Transform<float,3,AffineCompact> acf3; acf3.matrix().setRandom();\n    VERIFY_MATRIX(glLoadMatrix(acf3), Projective3f(acf3).matrix());\n    VERIFY_MATRIX(glMultMatrix(acf3), Projective3f(acf3).matrix());\n\n    Transform<float,3,Affine> af3(acf3);\n    VERIFY_MATRIX(glLoadMatrix(af3), Projective3f(af3).matrix());\n    VERIFY_MATRIX(glMultMatrix(af3), Projective3f(af3).matrix());\n\n    Transform<float,3,Projective> pf3; pf3.matrix().setRandom();\n    VERIFY_MATRIX(glLoadMatrix(pf3), Projective3f(pf3).matrix());\n    VERIFY_MATRIX(glMultMatrix(pf3), Projective3f(pf3).matrix());\n\n    Transform<double,3,AffineCompact> acd3; acd3.matrix().setRandom();\n    VERIFY_MATRIX(glLoadMatrix(acd3), Projective3d(acd3).matrix());\n    VERIFY_MATRIX(glMultMatrix(acd3), Projective3d(acd3).matrix());\n\n    Transform<double,3,Affine> ad3(acd3);\n    VERIFY_MATRIX(glLoadMatrix(ad3), Projective3d(ad3).matrix());\n    VERIFY_MATRIX(glMultMatrix(ad3), Projective3d(ad3).matrix());\n\n    Transform<double,3,Projective> pd3; pd3.matrix().setRandom();\n    VERIFY_MATRIX(glLoadMatrix(pd3), Projective3d(pd3).matrix());\n    VERIFY_MATRIX(glMultMatrix(pd3), Projective3d(pd3).matrix());\n\n    // translations (2D and 3D)\n    {\n      Vector2f vf2; vf2.setRandom(); Vector3f vf23; vf23 << vf2, 0;\n      VERIFY_MATRIX(glTranslate(vf2), Projective3f(Translation3f(vf23)).matrix());\n      Vector2d vd2; vd2.setRandom(); Vector3d vd23; vd23 << vd2, 0;\n      VERIFY_MATRIX(glTranslate(vd2), Projective3d(Translation3d(vd23)).matrix());\n\n      Vector3f vf3; vf3.setRandom();\n      VERIFY_MATRIX(glTranslate(vf3), Projective3f(Translation3f(vf3)).matrix());\n      Vector3d vd3; vd3.setRandom();\n      VERIFY_MATRIX(glTranslate(vd3), Projective3d(Translation3d(vd3)).matrix());\n\n      Translation<float,3> tf3; tf3.vector().setRandom();\n      VERIFY_MATRIX(glTranslate(tf3), Projective3f(tf3).matrix());\n\n      Translation<double,3> td3;  td3.vector().setRandom();\n      VERIFY_MATRIX(glTranslate(td3), Projective3d(td3).matrix());\n    }\n\n    // scaling (2D and 3D)\n    {\n      Vector2f vf2; vf2.setRandom(); Vector3f vf23; vf23 << vf2, 1;\n      VERIFY_MATRIX(glScale(vf2), Projective3f(Scaling(vf23)).matrix());\n      Vector2d vd2; vd2.setRandom(); Vector3d vd23; vd23 << vd2, 1;\n      VERIFY_MATRIX(glScale(vd2), Projective3d(Scaling(vd23)).matrix());\n\n      Vector3f vf3; vf3.setRandom();\n      VERIFY_MATRIX(glScale(vf3), Projective3f(Scaling(vf3)).matrix());\n      Vector3d vd3; vd3.setRandom();\n      VERIFY_MATRIX(glScale(vd3), Projective3d(Scaling(vd3)).matrix());\n\n      UniformScaling<float> usf(internal::random<float>());\n      VERIFY_MATRIX(glScale(usf), Projective3f(usf).matrix());\n\n      UniformScaling<double> usd(internal::random<double>());\n      VERIFY_MATRIX(glScale(usd), Projective3d(usd).matrix());\n    }\n  } else {\n    std::cerr << \"Warning: fixed-function pipeline was not tested.\\n\";\n  }\n\n  // Dynamic shader substitution variables.\n  // Modern shaders require a version string, and newer runtimes fail to\n  // compile old GLSL versions. Thus, we dynamically set the GLSL version\n  // string based on runtime. Also, pre OpenGL 3.0, the output gl_FragColor was\n  // built-in. This was deprecated in OpenGL 3.0, requiring us to explicitly\n  // define the output variable.\n  std::vector<std::string> glsl_vars;\n  glsl_vars.push_back(\"${GLSL_VERSION}\");\n  glsl_vars.push_back(\"${FRAG_OUTPUT_DECLARATION}\");\n  glsl_vars.push_back(\"${FRAG_OUTPUT_VARIABLE}\");\n\n  std::vector<std::string> glsl_vals;\n  glsl_vals.push_back(getGlslVersionString(gl_major_version, gl_minor_version));\n  if (gl_major_version >= 3) {\n    glsl_vals.push_back(\"out vec4 fragColor;\");\n    glsl_vals.push_back(\"fragColor\");\n  } else {\n    glsl_vals.push_back(\"\");\n    glsl_vals.push_back(\"gl_FragColor\");\n  }\n\n  // uniform\n  {\n    // vertex shader.\n    std::string vtx = format(\n      \"${GLSL_VERSION}\\n\"\n      \"void main(void) {\\n\"\n      \"  gl_Position = vec4(0,0,0,1);\\n\"\n      \"}\\n\",\n      glsl_vars, glsl_vals);\n\n#ifdef GL_VERSION_2_0\n    if(GLEW_VERSION_2_0 && GL_VERSION_2_0)\n    {\n      std::string frg = format(\n        \"${GLSL_VERSION}\\n\"\n        \"uniform vec2 v2f;\\n\"\n        \"uniform vec3 v3f;\\n\"\n        \"uniform vec4 v4f;\\n\"\n        \"uniform ivec2 v2i;\\n\"\n        \"uniform ivec3 v3i;\\n\"\n        \"uniform ivec4 v4i;\\n\"\n        \"uniform mat2 m2f;\\n\"\n        \"uniform mat3 m3f;\\n\"\n        \"uniform mat4 m4f;\\n\"\n        \"${FRAG_OUTPUT_DECLARATION}\\n\"\n        \"void main(void) { \\n\"\n        \"  ${FRAG_OUTPUT_VARIABLE} = vec4(v2f[0]+v3f[0]+v4f[0])+vec4(v2i[0]+v3i[0]+v4i[0])+vec4(m2f[0][0]+m3f[0][0]+m4f[0][0]);\\n\"\n        \"}\\n\",\n        glsl_vars, glsl_vals);\n\n      GLint prg_id = createProgram(vtx, frg);\n      VERIFY(prg_id > 0 && \"Failed to create program.\");\n      VERIFY_UNIFORM(fv, v2f, Vector2f);\n      VERIFY_UNIFORM(fv, v3f, Vector3f);\n      VERIFY_UNIFORM(fv, v4f, Vector4f);\n      VERIFY_UNIFORMi(v2i, Vector2i);\n      VERIFY_UNIFORMi(v3i, Vector3i);\n      VERIFY_UNIFORMi(v4i, Vector4i);\n      VERIFY_UNIFORM(fv, m2f, Matrix2f);\n      VERIFY_UNIFORM(fv, m3f, Matrix3f);\n      VERIFY_UNIFORM(fv, m4f, Matrix4f);\n      glDeleteProgram(prg_id);\n    }\n    else\n#endif\n      std::cerr << \"Warning: opengl 2.0 was not tested.\\n\";\n\n#ifdef GL_VERSION_2_1\n    if(GLEW_VERSION_2_1 && GL_VERSION_2_1 &&\n        (gl_major_version > 2 || (gl_major_version == 2 && gl_minor_version >= 1)))\n    {\n      std::string frg = format(\n        \"${GLSL_VERSION}\\n\"\n        \"uniform mat2x3 m23f;\\n\"\n        \"uniform mat3x2 m32f;\\n\"\n        \"uniform mat2x4 m24f;\\n\"\n        \"uniform mat4x2 m42f;\\n\"\n        \"uniform mat3x4 m34f;\\n\"\n        \"uniform mat4x3 m43f;\\n\"\n        \"${FRAG_OUTPUT_DECLARATION}\\n\"\n        \"void main(void) {\\n\"\n        \"  ${FRAG_OUTPUT_VARIABLE} = vec4(m23f[0][0]+m32f[0][0]+m24f[0][0]+m42f[0][0]+m34f[0][0]+m43f[0][0]);\\n\"\n        \"}\\n\",\n        glsl_vars, glsl_vals);\n\n      GLint prg_id = createProgram(vtx, frg);\n      VERIFY(prg_id > 0 && \"Failed to create program.\");\n      typedef Matrix<float,2,3> Matrix23f;\n      typedef Matrix<float,3,2> Matrix32f;\n      typedef Matrix<float,2,4> Matrix24f;\n      typedef Matrix<float,4,2> Matrix42f;\n      typedef Matrix<float,3,4> Matrix34f;\n      typedef Matrix<float,4,3> Matrix43f;\n\n      VERIFY_UNIFORM(fv, m23f, Matrix23f);\n      VERIFY_UNIFORM(fv, m32f, Matrix32f);\n      VERIFY_UNIFORM(fv, m24f, Matrix24f);\n      VERIFY_UNIFORM(fv, m42f, Matrix42f);\n      VERIFY_UNIFORM(fv, m34f, Matrix34f);\n      VERIFY_UNIFORM(fv, m43f, Matrix43f);\n      glDeleteProgram(prg_id);\n    }\n    else\n#endif\n      std::cerr << \"Warning: opengl 2.1 was not tested.\\n\";\n\n#ifdef GL_VERSION_3_0\n    if(GLEW_VERSION_3_0 && GL_VERSION_3_0 && gl_major_version >= 3)\n    {\n      std::string frg = format(\n        \"${GLSL_VERSION}\\n\"\n        \"uniform uvec2 v2ui;\\n\"\n        \"uniform uvec3 v3ui;\\n\"\n        \"uniform uvec4 v4ui;\\n\"\n        \"${FRAG_OUTPUT_DECLARATION}\\n\"\n        \"void main(void) {\\n\"\n        \"  ${FRAG_OUTPUT_VARIABLE} = vec4(v2ui[0]+v3ui[0]+v4ui[0]);\\n\"\n        \"}\\n\",\n        glsl_vars, glsl_vals);\n\n      GLint prg_id = createProgram(vtx, frg);\n      VERIFY(prg_id > 0 && \"Failed to create program.\");\n      typedef Matrix<unsigned int,2,1> Vector2ui;\n      typedef Matrix<unsigned int,3,1> Vector3ui;\n      typedef Matrix<unsigned int,4,1> Vector4ui;\n\n      VERIFY_UNIFORMi(v2ui, Vector2ui);\n      VERIFY_UNIFORMi(v3ui, Vector3ui);\n      VERIFY_UNIFORMi(v4ui, Vector4ui);\n      glDeleteProgram(prg_id);\n    }\n    else\n#endif\n      std::cerr << \"Warning: opengl 3.0 was not tested.\\n\";\n\n    // dvecn supported if >= 4.1 or ARB_vertex_attrib_64bit\n    bool has_fp64_native = (gl_major_version == 4 && gl_minor_version >= 1);\n    bool has_fp64_extension = false;\n#ifdef GLEW_ARB_gpu_shader_fp64\n    if(GLEW_ARB_gpu_shader_fp64)\n    {\n      // Check that extension can actually be compiled.\n      if (has_fp64_extension)\n      {\n        std::string frg = format(\n          \"${GLSL_VERSION}\\n\"\n          \"#extension GL_ARB_gpu_shader_fp64 : enable\\n\"\n          \"uniform dvec2 dv2;\\n\"\n          \"${FRAG_OUTPUT_DECLARATION}\\n\"\n          \"void main(void) {\\n\"\n          \"  ${FRAG_OUTPUT_VARIABLE} = vec4(dv2.x, dv2.y, dv2.x, dv2.y);\\n\"\n          \"}\\n\",\n          glsl_vars, glsl_vals);\n        GLint prg_id = createProgram(vtx, frg, /*print_errors=*/false);\n        if (prg_id)\n        {\n          has_fp64_extension = true;\n          glDeleteProgram(prg_id);\n        }\n      }\n    }\n#endif\n\n    if( has_fp64_native || has_fp64_extension )\n    {\n      std::vector<std::string> glsl_vars_with_extension = glsl_vars;\n      glsl_vars_with_extension.push_back(\"${GLSL_EXTENSIONS}\");\n      std::vector<std::string> glsl_vals_with_extension = glsl_vals;\n      if (has_fp64_extension)\n      {\n        glsl_vals_with_extension.push_back(\"#extension GL_ARB_gpu_shader_fp64 : enable\");\n      }\n      else\n      {\n        glsl_vals_with_extension.push_back(\"\");\n      }\n\n      std::string frg = format(\n        \"${GLSL_VERSION}\\n\"\n        \"${GLSL_EXTENSIONS}\\n\"\n        \"uniform dvec2 v2d;\\n\"\n        \"uniform dvec3 v3d;\\n\"\n        \"uniform dvec4 v4d;\\n\"\n        \"${FRAG_OUTPUT_DECLARATION}\\n\"\n        \"void main(void) {\\n\"\n        \"  ${FRAG_OUTPUT_VARIABLE} = vec4(v2d[0]+v3d[0]+v4d[0]);\\n\"\n        \"}\\n\",\n        glsl_vars_with_extension, glsl_vals_with_extension);\n\n      GLint prg_id = createProgram(vtx,frg);\n      VERIFY(prg_id > 0 && \"Failed to create program.\");\n      VERIFY_UNIFORM(dv, v2d, Vector2d);\n      VERIFY_UNIFORM(dv, v3d, Vector3d);\n      VERIFY_UNIFORM(dv, v4d, Vector4d);\n      glDeleteProgram(prg_id);\n    }\n    else\n      std::cerr << \"Warning: dvec (fp64) was not tested.\\n\";\n  }\n\n  // Exit loop - Leaving main loop is supported by freeglut, otherwise we\n  // are forced to exit.\n#ifdef FREEGLUT\n  glutLeaveMainLoop();\n  // Trigger another display loop iteration. Otherwise, it just hangs.\n  glutPostRedisplay();\n#else\n  exit(0);\n#endif\n}\n\nEIGEN_DECLARE_TEST(openglsupport)\n{\n  int argc = 0;\n  glutInit(&argc, 0);\n\n  GLint glut_display_mode = GLUT_DOUBLE | GLUT_RGB | GLUT_DEPTH;\n\n#ifndef EIGEN_LEGACY_OPENGL\n  // Initialize 3.2+ OpenGL context.\n#if defined(__APPLE_CC__)\n  glut_display_mode |= GLUT_3_2_CORE_PROFILE;\n#elif defined(FREEGLUT)\n  glutInitContextVersion(3, 2);\n  glutInitContextFlags(GLUT_FORWARD_COMPATIBLE);\n  glutInitContextProfile(GLUT_CORE_PROFILE);\n#endif\n#endif\n\n  glutInitDisplayMode(glut_display_mode);\n  glutInitWindowPosition(0, 0);\n  glutInitWindowSize(10, 10);\n\n  int window = glutCreateWindow(\"Eigen\");\n  if(window <= 0)\n  {\n    std::cerr << \"Error: Unable to create GLUT Window.\\n\";\n    exit(1);\n  }\n\n  glewExperimental = GL_TRUE;\n  if(glewInit() != GLEW_OK)\n  {\n    std::cerr << \"Warning: Failed to initialize GLEW.\\n\";\n    exit(1);\n  }\n\n  // Run test in display, otherwise GLUT fails to clean up and leads to memory\n  // access errors on exit.\n  glutDisplayFunc(openglsupport_test_loop);\n  glutMainLoop();\n  glutDestroyWindow(window);\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/polynomialsolver.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Manuel Yguel <manuel.yguel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <unsupported/Eigen/Polynomials>\n#include <iostream>\n#include <algorithm>\n\nusing namespace std;\n\nnamespace Eigen {\nnamespace internal {\ntemplate<int Size>\nstruct increment_if_fixed_size\n{\n  enum {\n    ret = (Size == Dynamic) ? Dynamic : Size+1\n  };\n};\n}\n}\n\ntemplate<typename PolynomialType>\nPolynomialType polyder(const PolynomialType& p)\n{\n  typedef typename PolynomialType::Scalar Scalar;\n  PolynomialType res(p.size());\n  for(Index i=1; i<p.size(); ++i)\n    res[i-1] = p[i]*Scalar(i);\n  res[p.size()-1] = 0.;\n  return res;\n}\n\ntemplate<int Deg, typename POLYNOMIAL, typename SOLVER>\nbool aux_evalSolver( const POLYNOMIAL& pols, SOLVER& psolve )\n{\n  typedef typename POLYNOMIAL::Scalar Scalar;\n  typedef typename POLYNOMIAL::RealScalar RealScalar;\n\n  typedef typename SOLVER::RootsType    RootsType;\n  typedef Matrix<RealScalar,Deg,1>      EvalRootsType;\n\n  const Index deg = pols.size()-1;\n\n  // Test template constructor from coefficient vector\n  SOLVER solve_constr (pols);\n\n  psolve.compute( pols );\n  const RootsType& roots( psolve.roots() );\n  EvalRootsType evr( deg );\n  POLYNOMIAL pols_der = polyder(pols);\n  EvalRootsType der( deg );\n  for( int i=0; i<roots.size(); ++i ){\n    evr[i] = std::abs( poly_eval( pols, roots[i] ) );\n    der[i] = numext::maxi(RealScalar(1.), std::abs( poly_eval( pols_der, roots[i] ) ));\n  }\n\n  // we need to divide by the magnitude of the derivative because\n  // with a high derivative is very small error in the value of the root\n  // yiels a very large error in the polynomial evaluation.\n  bool evalToZero = (evr.cwiseQuotient(der)).isZero( test_precision<Scalar>() );\n  if( !evalToZero )\n  {\n    cerr << \"WRONG root: \" << endl;\n    cerr << \"Polynomial: \" << pols.transpose() << endl;\n    cerr << \"Roots found: \" << roots.transpose() << endl;\n    cerr << \"Abs value of the polynomial at the roots: \" << evr.transpose() << endl;\n    cerr << endl;\n  }\n\n  std::vector<RealScalar> rootModuli( roots.size() );\n  Map< EvalRootsType > aux( &rootModuli[0], roots.size() );\n  aux = roots.array().abs();\n  std::sort( rootModuli.begin(), rootModuli.end() );\n  bool distinctModuli=true;\n  for( size_t i=1; i<rootModuli.size() && distinctModuli; ++i )\n  {\n    if( internal::isApprox( rootModuli[i], rootModuli[i-1] ) ){\n      distinctModuli = false; }\n  }\n  VERIFY( evalToZero || !distinctModuli );\n\n  return distinctModuli;\n}\n\n\n\n\n\n\n\ntemplate<int Deg, typename POLYNOMIAL>\nvoid evalSolver( const POLYNOMIAL& pols )\n{\n  typedef typename POLYNOMIAL::Scalar Scalar;\n\n  typedef PolynomialSolver<Scalar, Deg > PolynomialSolverType;\n\n  PolynomialSolverType psolve;\n  aux_evalSolver<Deg, POLYNOMIAL, PolynomialSolverType>( pols, psolve );\n}\n\n\n\n\ntemplate< int Deg, typename POLYNOMIAL, typename ROOTS, typename REAL_ROOTS >\nvoid evalSolverSugarFunction( const POLYNOMIAL& pols, const ROOTS& roots, const REAL_ROOTS& real_roots )\n{\n  using std::sqrt;\n  typedef typename POLYNOMIAL::Scalar Scalar;\n  typedef typename POLYNOMIAL::RealScalar RealScalar;\n\n  typedef PolynomialSolver<Scalar, Deg >              PolynomialSolverType;\n\n  PolynomialSolverType psolve;\n  if( aux_evalSolver<Deg, POLYNOMIAL, PolynomialSolverType>( pols, psolve ) )\n  {\n    //It is supposed that\n    // 1) the roots found are correct\n    // 2) the roots have distinct moduli\n\n    //Test realRoots\n    std::vector< RealScalar > calc_realRoots;\n    psolve.realRoots( calc_realRoots,  test_precision<RealScalar>());\n    VERIFY_IS_EQUAL( calc_realRoots.size() , (size_t)real_roots.size() );\n\n    const RealScalar psPrec = sqrt( test_precision<RealScalar>() );\n\n    for( size_t i=0; i<calc_realRoots.size(); ++i )\n    {\n      bool found = false;\n      for( size_t j=0; j<calc_realRoots.size()&& !found; ++j )\n      {\n        if( internal::isApprox( calc_realRoots[i], real_roots[j], psPrec ) ){\n          found = true; }\n      }\n      VERIFY( found );\n    }\n\n    //Test greatestRoot\n    VERIFY( internal::isApprox( roots.array().abs().maxCoeff(),\n          abs( psolve.greatestRoot() ), psPrec ) );\n\n    //Test smallestRoot\n    VERIFY( internal::isApprox( roots.array().abs().minCoeff(),\n          abs( psolve.smallestRoot() ), psPrec ) );\n\n    bool hasRealRoot;\n    //Test absGreatestRealRoot\n    RealScalar r = psolve.absGreatestRealRoot( hasRealRoot );\n    VERIFY( hasRealRoot == (real_roots.size() > 0 ) );\n    if( hasRealRoot ){\n      VERIFY( internal::isApprox( real_roots.array().abs().maxCoeff(), abs(r), psPrec ) );  }\n\n    //Test absSmallestRealRoot\n    r = psolve.absSmallestRealRoot( hasRealRoot );\n    VERIFY( hasRealRoot == (real_roots.size() > 0 ) );\n    if( hasRealRoot ){\n      VERIFY( internal::isApprox( real_roots.array().abs().minCoeff(), abs( r ), psPrec ) ); }\n\n    //Test greatestRealRoot\n    r = psolve.greatestRealRoot( hasRealRoot );\n    VERIFY( hasRealRoot == (real_roots.size() > 0 ) );\n    if( hasRealRoot ){\n      VERIFY( internal::isApprox( real_roots.array().maxCoeff(), r, psPrec ) ); }\n\n    //Test smallestRealRoot\n    r = psolve.smallestRealRoot( hasRealRoot );\n    VERIFY( hasRealRoot == (real_roots.size() > 0 ) );\n    if( hasRealRoot ){\n    VERIFY( internal::isApprox( real_roots.array().minCoeff(), r, psPrec ) ); }\n  }\n}\n\n\ntemplate<typename _Scalar, int _Deg>\nvoid polynomialsolver(int deg)\n{\n  typedef typename NumTraits<_Scalar>::Real RealScalar;\n  typedef internal::increment_if_fixed_size<_Deg>     Dim;\n  typedef Matrix<_Scalar,Dim::ret,1>                  PolynomialType;\n  typedef Matrix<_Scalar,_Deg,1>                      EvalRootsType;\n  typedef Matrix<RealScalar,_Deg,1>                   RealRootsType;\n\n  cout << \"Standard cases\" << endl;\n  PolynomialType pols = PolynomialType::Random(deg+1);\n  evalSolver<_Deg,PolynomialType>( pols );\n\n  cout << \"Hard cases\" << endl;\n  _Scalar multipleRoot = internal::random<_Scalar>();\n  EvalRootsType allRoots = EvalRootsType::Constant(deg,multipleRoot);\n  roots_to_monicPolynomial( allRoots, pols );\n  evalSolver<_Deg,PolynomialType>( pols );\n\n  cout << \"Test sugar\" << endl;\n  RealRootsType realRoots = RealRootsType::Random(deg);\n  roots_to_monicPolynomial( realRoots, pols );\n  evalSolverSugarFunction<_Deg>(\n      pols,\n      realRoots.template cast <std::complex<RealScalar> >().eval(),\n      realRoots );\n}\n\nEIGEN_DECLARE_TEST(polynomialsolver)\n{\n  for(int i = 0; i < g_repeat; i++)\n  {\n    CALL_SUBTEST_1( (polynomialsolver<float,1>(1)) );\n    CALL_SUBTEST_2( (polynomialsolver<double,2>(2)) );\n    CALL_SUBTEST_3( (polynomialsolver<double,3>(3)) );\n    CALL_SUBTEST_4( (polynomialsolver<float,4>(4)) );\n    CALL_SUBTEST_5( (polynomialsolver<double,5>(5)) );\n    CALL_SUBTEST_6( (polynomialsolver<float,6>(6)) );\n    CALL_SUBTEST_7( (polynomialsolver<float,7>(7)) );\n    CALL_SUBTEST_8( (polynomialsolver<double,8>(8)) );\n\n    CALL_SUBTEST_9( (polynomialsolver<float,Dynamic>(\n            internal::random<int>(9,13)\n            )) );\n    CALL_SUBTEST_10((polynomialsolver<double,Dynamic>(\n            internal::random<int>(9,13)\n            )) );\n    CALL_SUBTEST_11((polynomialsolver<float,Dynamic>(1)) );\n    CALL_SUBTEST_12((polynomialsolver<std::complex<double>,Dynamic>(internal::random<int>(2,13))) );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/polynomialutils.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010 Manuel Yguel <manuel.yguel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n#include <unsupported/Eigen/Polynomials>\n#include <iostream>\n\nusing namespace std;\n\nnamespace Eigen {\nnamespace internal {\ntemplate<int Size>\nstruct increment_if_fixed_size\n{\n  enum {\n    ret = (Size == Dynamic) ? Dynamic : Size+1\n  };\n};\n}\n}\n\ntemplate<typename _Scalar, int _Deg>\nvoid realRoots_to_monicPolynomial_test(int deg)\n{\n  typedef internal::increment_if_fixed_size<_Deg>            Dim;\n  typedef Matrix<_Scalar,Dim::ret,1>                  PolynomialType;\n  typedef Matrix<_Scalar,_Deg,1>                      EvalRootsType;\n\n  PolynomialType pols(deg+1);\n  EvalRootsType roots = EvalRootsType::Random(deg);\n  roots_to_monicPolynomial( roots, pols );\n\n  EvalRootsType evr( deg );\n  for( int i=0; i<roots.size(); ++i ){\n    evr[i] = std::abs( poly_eval( pols, roots[i] ) ); }\n\n  bool evalToZero = evr.isZero( test_precision<_Scalar>() );\n  if( !evalToZero ){\n    cerr << evr.transpose() << endl; }\n  VERIFY( evalToZero );\n}\n\ntemplate<typename _Scalar> void realRoots_to_monicPolynomial_scalar()\n{\n  CALL_SUBTEST_2( (realRoots_to_monicPolynomial_test<_Scalar,2>(2)) );\n  CALL_SUBTEST_3( (realRoots_to_monicPolynomial_test<_Scalar,3>(3)) );\n  CALL_SUBTEST_4( (realRoots_to_monicPolynomial_test<_Scalar,4>(4)) );\n  CALL_SUBTEST_5( (realRoots_to_monicPolynomial_test<_Scalar,5>(5)) );\n  CALL_SUBTEST_6( (realRoots_to_monicPolynomial_test<_Scalar,6>(6)) );\n  CALL_SUBTEST_7( (realRoots_to_monicPolynomial_test<_Scalar,7>(7)) );\n  CALL_SUBTEST_8( (realRoots_to_monicPolynomial_test<_Scalar,17>(17)) );\n\n  CALL_SUBTEST_9( (realRoots_to_monicPolynomial_test<_Scalar,Dynamic>(\n          internal::random<int>(18,26) )) );\n}\n\n\n\n\ntemplate<typename _Scalar, int _Deg>\nvoid CauchyBounds(int deg)\n{\n  typedef internal::increment_if_fixed_size<_Deg>            Dim;\n  typedef Matrix<_Scalar,Dim::ret,1>                  PolynomialType;\n  typedef Matrix<_Scalar,_Deg,1>                      EvalRootsType;\n\n  PolynomialType pols(deg+1);\n  EvalRootsType roots = EvalRootsType::Random(deg);\n  roots_to_monicPolynomial( roots, pols );\n  _Scalar M = cauchy_max_bound( pols );\n  _Scalar m = cauchy_min_bound( pols );\n  _Scalar Max = roots.array().abs().maxCoeff();\n  _Scalar min = roots.array().abs().minCoeff();\n  bool eval = (M >= Max) && (m <= min);\n  if( !eval )\n  {\n    cerr << \"Roots: \" << roots << endl;\n    cerr << \"Bounds: (\" << m << \", \" << M << \")\" << endl;\n    cerr << \"Min,Max: (\" << min << \", \" << Max << \")\" << endl;\n  }\n  VERIFY( eval );\n}\n\ntemplate<typename _Scalar> void CauchyBounds_scalar()\n{\n  CALL_SUBTEST_2( (CauchyBounds<_Scalar,2>(2)) );\n  CALL_SUBTEST_3( (CauchyBounds<_Scalar,3>(3)) );\n  CALL_SUBTEST_4( (CauchyBounds<_Scalar,4>(4)) );\n  CALL_SUBTEST_5( (CauchyBounds<_Scalar,5>(5)) );\n  CALL_SUBTEST_6( (CauchyBounds<_Scalar,6>(6)) );\n  CALL_SUBTEST_7( (CauchyBounds<_Scalar,7>(7)) );\n  CALL_SUBTEST_8( (CauchyBounds<_Scalar,17>(17)) );\n\n  CALL_SUBTEST_9( (CauchyBounds<_Scalar,Dynamic>(\n          internal::random<int>(18,26) )) );\n}\n\nEIGEN_DECLARE_TEST(polynomialutils)\n{\n  for(int i = 0; i < g_repeat; i++)\n  {\n    realRoots_to_monicPolynomial_scalar<double>();\n    realRoots_to_monicPolynomial_scalar<float>();\n    CauchyBounds_scalar<double>();\n    CauchyBounds_scalar<float>();\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/sparse_extra.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2010 Gael Guennebaud <g.gael@free.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n\n// import basic and product tests for deprecated DynamicSparseMatrix\n#if 0 // sparse_basic(DynamicSparseMatrix) does not compile at all -> disabled\nstatic long g_realloc_count = 0;\n#define EIGEN_SPARSE_COMPRESSED_STORAGE_REALLOCATE_PLUGIN g_realloc_count++;\n\nstatic long g_dense_op_sparse_count = 0;\n#define EIGEN_SPARSE_ASSIGNMENT_FROM_DENSE_OP_SPARSE_PLUGIN g_dense_op_sparse_count++;\n#define EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_ADD_DENSE_PLUGIN g_dense_op_sparse_count+=10;\n#define EIGEN_SPARSE_ASSIGNMENT_FROM_SPARSE_SUB_DENSE_PLUGIN g_dense_op_sparse_count+=20;\n\n#define EIGEN_SPARSE_TEST_INCLUDED_FROM_SPARSE_EXTRA 1\n#endif\n\n#define EIGEN_NO_DEPRECATED_WARNING\n// Disable counting of temporaries, since sparse_product(DynamicSparseMatrix)\n// has an extra copy-assignment.\n#define EIGEN_SPARSE_PRODUCT_IGNORE_TEMPORARY_COUNT\n#include \"sparse_product.cpp\"\n\n#if 0 // sparse_basic(DynamicSparseMatrix) does not compile at all -> disabled\n#include \"sparse_basic.cpp\"\n#endif\n\n#include <Eigen/SparseExtra>\n\ntemplate<typename SetterType,typename DenseType, typename Scalar, int Options>\nbool test_random_setter(SparseMatrix<Scalar,Options>& sm, const DenseType& ref, const std::vector<Vector2i>& nonzeroCoords)\n{\n  {\n    sm.setZero();\n    SetterType w(sm);\n    std::vector<Vector2i> remaining = nonzeroCoords;\n    while(!remaining.empty())\n    {\n      int i = internal::random<int>(0,static_cast<int>(remaining.size())-1);\n      w(remaining[i].x(),remaining[i].y()) = ref.coeff(remaining[i].x(),remaining[i].y());\n      remaining[i] = remaining.back();\n      remaining.pop_back();\n    }\n  }\n  return sm.isApprox(ref);\n}\n\ntemplate<typename SetterType,typename DenseType, typename T>\nbool test_random_setter(DynamicSparseMatrix<T>& sm, const DenseType& ref, const std::vector<Vector2i>& nonzeroCoords)\n{\n  sm.setZero();\n  std::vector<Vector2i> remaining = nonzeroCoords;\n  while(!remaining.empty())\n  {\n    int i = internal::random<int>(0,static_cast<int>(remaining.size())-1);\n    sm.coeffRef(remaining[i].x(),remaining[i].y()) = ref.coeff(remaining[i].x(),remaining[i].y());\n    remaining[i] = remaining.back();\n    remaining.pop_back();\n  }\n  return sm.isApprox(ref);\n}\n\ntemplate<typename SparseMatrixType> void sparse_extra(const SparseMatrixType& ref)\n{\n  const Index rows = ref.rows();\n  const Index cols = ref.cols();\n  typedef typename SparseMatrixType::Scalar Scalar;\n  enum { Flags = SparseMatrixType::Flags };\n\n  double density = (std::max)(8./(rows*cols), 0.01);\n  typedef Matrix<Scalar,Dynamic,Dynamic> DenseMatrix;\n  typedef Matrix<Scalar,Dynamic,1> DenseVector;\n  Scalar eps = 1e-6;\n\n  SparseMatrixType m(rows, cols);\n  DenseMatrix refMat = DenseMatrix::Zero(rows, cols);\n  DenseVector vec1 = DenseVector::Random(rows);\n\n  std::vector<Vector2i> zeroCoords;\n  std::vector<Vector2i> nonzeroCoords;\n  initSparse<Scalar>(density, refMat, m, 0, &zeroCoords, &nonzeroCoords);\n\n  if (zeroCoords.size()==0 || nonzeroCoords.size()==0)\n    return;\n\n  // test coeff and coeffRef\n  for (int i=0; i<(int)zeroCoords.size(); ++i)\n  {\n    VERIFY_IS_MUCH_SMALLER_THAN( m.coeff(zeroCoords[i].x(),zeroCoords[i].y()), eps );\n    if(internal::is_same<SparseMatrixType,SparseMatrix<Scalar,Flags> >::value)\n      VERIFY_RAISES_ASSERT( m.coeffRef(zeroCoords[0].x(),zeroCoords[0].y()) = 5 );\n  }\n  VERIFY_IS_APPROX(m, refMat);\n\n  m.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5);\n  refMat.coeffRef(nonzeroCoords[0].x(), nonzeroCoords[0].y()) = Scalar(5);\n\n  VERIFY_IS_APPROX(m, refMat);\n\n  // random setter\n//   {\n//     m.setZero();\n//     VERIFY_IS_NOT_APPROX(m, refMat);\n//     SparseSetter<SparseMatrixType, RandomAccessPattern> w(m);\n//     std::vector<Vector2i> remaining = nonzeroCoords;\n//     while(!remaining.empty())\n//     {\n//       int i = internal::random<int>(0,remaining.size()-1);\n//       w->coeffRef(remaining[i].x(),remaining[i].y()) = refMat.coeff(remaining[i].x(),remaining[i].y());\n//       remaining[i] = remaining.back();\n//       remaining.pop_back();\n//     }\n//   }\n//   VERIFY_IS_APPROX(m, refMat);\n\n    VERIFY(( test_random_setter<RandomSetter<SparseMatrixType, StdMapTraits> >(m,refMat,nonzeroCoords) ));\n    #ifdef EIGEN_UNORDERED_MAP_SUPPORT\n    VERIFY(( test_random_setter<RandomSetter<SparseMatrixType, StdUnorderedMapTraits> >(m,refMat,nonzeroCoords) ));\n    #endif\n    #ifdef _DENSE_HASH_MAP_H_\n    VERIFY(( test_random_setter<RandomSetter<SparseMatrixType, GoogleDenseHashMapTraits> >(m,refMat,nonzeroCoords) ));\n    #endif\n    #ifdef _SPARSE_HASH_MAP_H_\n    VERIFY(( test_random_setter<RandomSetter<SparseMatrixType, GoogleSparseHashMapTraits> >(m,refMat,nonzeroCoords) ));\n    #endif\n\n\n  // test RandomSetter\n  /*{\n    SparseMatrixType m1(rows,cols), m2(rows,cols);\n    DenseMatrix refM1 = DenseMatrix::Zero(rows, rows);\n    initSparse<Scalar>(density, refM1, m1);\n    {\n      Eigen::RandomSetter<SparseMatrixType > setter(m2);\n      for (int j=0; j<m1.outerSize(); ++j)\n        for (typename SparseMatrixType::InnerIterator i(m1,j); i; ++i)\n          setter(i.index(), j) = i.value();\n    }\n    VERIFY_IS_APPROX(m1, m2);\n  }*/\n\n\n}\n\ntemplate<typename SparseMatrixType>\nvoid check_marketio()\n{\n  typedef Matrix<typename SparseMatrixType::Scalar, Dynamic, Dynamic> DenseMatrix;\n  Index rows = internal::random<Index>(1,100);\n  Index cols = internal::random<Index>(1,100);\n  SparseMatrixType m1, m2;\n  m1 = DenseMatrix::Random(rows, cols).sparseView();\n  saveMarket(m1, \"sparse_extra.mtx\");\n  loadMarket(m2, \"sparse_extra.mtx\");\n  VERIFY_IS_EQUAL(DenseMatrix(m1),DenseMatrix(m2));\n}\n\ntemplate<typename VectorType>\nvoid check_marketio_vector()\n{\n  Index size = internal::random<Index>(1,100);\n  VectorType v1, v2;\n  v1 = VectorType::Random(size);\n  saveMarketVector(v1, \"vector_extra.mtx\");\n  loadMarketVector(v2, \"vector_extra.mtx\");\n  VERIFY_IS_EQUAL(v1,v2);\n}\n\nEIGEN_DECLARE_TEST(sparse_extra)\n{\n  for(int i = 0; i < g_repeat; i++) {\n    int s = Eigen::internal::random<int>(1,50);\n    CALL_SUBTEST_1( sparse_extra(SparseMatrix<double>(8, 8)) );\n    CALL_SUBTEST_2( sparse_extra(SparseMatrix<std::complex<double> >(s, s)) );\n    CALL_SUBTEST_1( sparse_extra(SparseMatrix<double>(s, s)) );\n\n    CALL_SUBTEST_3( sparse_extra(DynamicSparseMatrix<double>(s, s)) );\n//    CALL_SUBTEST_3(( sparse_basic(DynamicSparseMatrix<double>(s, s)) ));\n//    CALL_SUBTEST_3(( sparse_basic(DynamicSparseMatrix<double,ColMajor,long int>(s, s)) ));\n\n    CALL_SUBTEST_3( (sparse_product<DynamicSparseMatrix<float, ColMajor> >()) );\n    CALL_SUBTEST_3( (sparse_product<DynamicSparseMatrix<float, RowMajor> >()) );\n\n    CALL_SUBTEST_4( (check_marketio<SparseMatrix<float,ColMajor,int> >()) );\n    CALL_SUBTEST_4( (check_marketio<SparseMatrix<double,ColMajor,int> >()) );\n    CALL_SUBTEST_4( (check_marketio<SparseMatrix<std::complex<float>,ColMajor,int> >()) );\n    CALL_SUBTEST_4( (check_marketio<SparseMatrix<std::complex<double>,ColMajor,int> >()) );\n    CALL_SUBTEST_4( (check_marketio<SparseMatrix<float,ColMajor,long int> >()) );\n    CALL_SUBTEST_4( (check_marketio<SparseMatrix<double,ColMajor,long int> >()) );\n    CALL_SUBTEST_4( (check_marketio<SparseMatrix<std::complex<float>,ColMajor,long int> >()) );\n    CALL_SUBTEST_4( (check_marketio<SparseMatrix<std::complex<double>,ColMajor,long int> >()) );\n\n\n    CALL_SUBTEST_5( (check_marketio_vector<Matrix<float,1,Dynamic> >()) );\n    CALL_SUBTEST_5( (check_marketio_vector<Matrix<double,1,Dynamic> >()) );\n    CALL_SUBTEST_5( (check_marketio_vector<Matrix<std::complex<float>,1,Dynamic> >()) );\n    CALL_SUBTEST_5( (check_marketio_vector<Matrix<std::complex<double>,1,Dynamic> >()) );\n    CALL_SUBTEST_5( (check_marketio_vector<Matrix<float,Dynamic,1> >()) );\n    CALL_SUBTEST_5( (check_marketio_vector<Matrix<double,Dynamic,1> >()) );\n    CALL_SUBTEST_5( (check_marketio_vector<Matrix<std::complex<float>,Dynamic,1> >()) );\n    CALL_SUBTEST_5( (check_marketio_vector<Matrix<std::complex<double>,Dynamic,1> >()) );\n\n    TEST_SET_BUT_UNUSED_VARIABLE(s);\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/special_functions.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2016 Gael Guennebaud <gael.guennebaud@inria.fr>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <limits.h>\n#include \"main.h\"\n#include \"../Eigen/SpecialFunctions\"\n\n// Hack to allow \"implicit\" conversions from double to Scalar via comma-initialization.\ntemplate<typename Derived>\nEigen::CommaInitializer<Derived> operator<<(Eigen::DenseBase<Derived>& dense, double v) {\n  return (dense << static_cast<typename Derived::Scalar>(v));\n}\n\ntemplate<typename XprType>\nEigen::CommaInitializer<XprType>& operator,(Eigen::CommaInitializer<XprType>& ci, double v) {\n  return (ci, static_cast<typename XprType::Scalar>(v));\n}\n\ntemplate<typename X, typename Y>\nvoid verify_component_wise(const X& x, const Y& y)\n{\n  for(Index i=0; i<x.size(); ++i)\n  {\n    if((numext::isfinite)(y(i)))\n      VERIFY_IS_APPROX( x(i), y(i) );\n    else if((numext::isnan)(y(i)))\n      VERIFY((numext::isnan)(x(i)));\n    else\n      VERIFY_IS_EQUAL( x(i), y(i) );\n  }\n}\n\ntemplate<typename ArrayType> void array_special_functions()\n{\n  using std::abs;\n  using std::sqrt;\n  typedef typename ArrayType::Scalar Scalar;\n  typedef typename NumTraits<Scalar>::Real RealScalar;\n\n  Scalar plusinf = std::numeric_limits<Scalar>::infinity();\n  Scalar nan = std::numeric_limits<Scalar>::quiet_NaN();\n\n  Index rows = internal::random<Index>(1,30);\n  Index cols = 1;\n\n  // API\n  {\n    ArrayType m1 = ArrayType::Random(rows,cols);\n#if EIGEN_HAS_C99_MATH\n    VERIFY_IS_APPROX(m1.lgamma(), lgamma(m1));\n    VERIFY_IS_APPROX(m1.digamma(), digamma(m1));\n    VERIFY_IS_APPROX(m1.erf(), erf(m1));\n    VERIFY_IS_APPROX(m1.erfc(), erfc(m1));\n#endif  // EIGEN_HAS_C99_MATH\n  }\n\n\n#if EIGEN_HAS_C99_MATH\n  // check special functions (comparing against numpy implementation)\n  if (!NumTraits<Scalar>::IsComplex)\n  {\n\n    {\n      ArrayType m1 = ArrayType::Random(rows,cols);\n      ArrayType m2 = ArrayType::Random(rows,cols);\n\n      // Test various propreties of igamma & igammac.  These are normalized\n      // gamma integrals where\n      //   igammac(a, x) = Gamma(a, x) / Gamma(a)\n      //   igamma(a, x) = gamma(a, x) / Gamma(a)\n      // where Gamma and gamma are considered the standard unnormalized\n      // upper and lower incomplete gamma functions, respectively.\n      ArrayType a = m1.abs() + Scalar(2);\n      ArrayType x = m2.abs() + Scalar(2);\n      ArrayType zero = ArrayType::Zero(rows, cols);\n      ArrayType one = ArrayType::Constant(rows, cols, Scalar(1.0));\n      ArrayType a_m1 = a - one;\n      ArrayType Gamma_a_x = Eigen::igammac(a, x) * a.lgamma().exp();\n      ArrayType Gamma_a_m1_x = Eigen::igammac(a_m1, x) * a_m1.lgamma().exp();\n      ArrayType gamma_a_x = Eigen::igamma(a, x) * a.lgamma().exp();\n      ArrayType gamma_a_m1_x = Eigen::igamma(a_m1, x) * a_m1.lgamma().exp();\n\n\n      // Gamma(a, 0) == Gamma(a)\n      VERIFY_IS_APPROX(Eigen::igammac(a, zero), one);\n\n      // Gamma(a, x) + gamma(a, x) == Gamma(a)\n      VERIFY_IS_APPROX(Gamma_a_x + gamma_a_x, a.lgamma().exp());\n\n      // Gamma(a, x) == (a - 1) * Gamma(a-1, x) + x^(a-1) * exp(-x)\n      VERIFY_IS_APPROX(Gamma_a_x, (a - Scalar(1)) * Gamma_a_m1_x + x.pow(a-Scalar(1)) * (-x).exp());\n\n      // gamma(a, x) == (a - 1) * gamma(a-1, x) - x^(a-1) * exp(-x)\n      VERIFY_IS_APPROX(gamma_a_x, (a - Scalar(1)) * gamma_a_m1_x - x.pow(a-Scalar(1)) * (-x).exp());\n    }\n    {\n      // Verify for large a and x that values are between 0 and 1.\n      ArrayType m1 = ArrayType::Random(rows,cols);\n      ArrayType m2 = ArrayType::Random(rows,cols);\n      int max_exponent = std::numeric_limits<Scalar>::max_exponent10;\n      ArrayType a = m1.abs() *  Scalar(pow(10., max_exponent - 1));\n      ArrayType x = m2.abs() *  Scalar(pow(10., max_exponent - 1));\n      for (int i = 0; i < a.size(); ++i) {\n        Scalar igam = numext::igamma(a(i), x(i));\n        VERIFY(0 <= igam);\n        VERIFY(igam <= 1);\n      }\n    }\n\n    {\n      // Check exact values of igamma and igammac against a third party calculation.\n      Scalar a_s[] = {Scalar(0), Scalar(1), Scalar(1.5), Scalar(4), Scalar(0.0001), Scalar(1000.5)};\n      Scalar x_s[] = {Scalar(0), Scalar(1), Scalar(1.5), Scalar(4), Scalar(0.0001), Scalar(1000.5)};\n\n      // location i*6+j corresponds to a_s[i], x_s[j].\n      Scalar igamma_s[][6] = {\n          {Scalar(0.0), nan, nan, nan, nan, nan},\n          {Scalar(0.0), Scalar(0.6321205588285578), Scalar(0.7768698398515702),\n           Scalar(0.9816843611112658), Scalar(9.999500016666262e-05),\n           Scalar(1.0)},\n          {Scalar(0.0), Scalar(0.4275932955291202), Scalar(0.608374823728911),\n           Scalar(0.9539882943107686), Scalar(7.522076445089201e-07),\n           Scalar(1.0)},\n          {Scalar(0.0), Scalar(0.01898815687615381),\n           Scalar(0.06564245437845008), Scalar(0.5665298796332909),\n           Scalar(4.166333347221828e-18), Scalar(1.0)},\n          {Scalar(0.0), Scalar(0.9999780593618628), Scalar(0.9999899967080838),\n           Scalar(0.9999996219837988), Scalar(0.9991370418689945), Scalar(1.0)},\n          {Scalar(0.0), Scalar(0.0), Scalar(0.0), Scalar(0.0), Scalar(0.0),\n           Scalar(0.5042041932513908)}};\n      Scalar igammac_s[][6] = {\n          {nan, nan, nan, nan, nan, nan},\n          {Scalar(1.0), Scalar(0.36787944117144233),\n           Scalar(0.22313016014842982), Scalar(0.018315638888734182),\n           Scalar(0.9999000049998333), Scalar(0.0)},\n          {Scalar(1.0), Scalar(0.5724067044708798), Scalar(0.3916251762710878),\n           Scalar(0.04601170568923136), Scalar(0.9999992477923555),\n           Scalar(0.0)},\n          {Scalar(1.0), Scalar(0.9810118431238462), Scalar(0.9343575456215499),\n           Scalar(0.4334701203667089), Scalar(1.0), Scalar(0.0)},\n          {Scalar(1.0), Scalar(2.1940638138146658e-05),\n           Scalar(1.0003291916285e-05), Scalar(3.7801620118431334e-07),\n           Scalar(0.0008629581310054535), Scalar(0.0)},\n          {Scalar(1.0), Scalar(1.0), Scalar(1.0), Scalar(1.0), Scalar(1.0),\n           Scalar(0.49579580674813944)}};\n\n      for (int i = 0; i < 6; ++i) {\n        for (int j = 0; j < 6; ++j) {\n          if ((std::isnan)(igamma_s[i][j])) {\n            VERIFY((std::isnan)(numext::igamma(a_s[i], x_s[j])));\n          } else {\n            VERIFY_IS_APPROX(numext::igamma(a_s[i], x_s[j]), igamma_s[i][j]);\n          }\n\n          if ((std::isnan)(igammac_s[i][j])) {\n            VERIFY((std::isnan)(numext::igammac(a_s[i], x_s[j])));\n          } else {\n            VERIFY_IS_APPROX(numext::igammac(a_s[i], x_s[j]), igammac_s[i][j]);\n          }\n        }\n      }\n    }\n  }\n#endif  // EIGEN_HAS_C99_MATH\n\n  // Check the ndtri function against scipy.special.ndtri\n  {\n    ArrayType x(7), res(7), ref(7);\n    x << 0.5, 0.2, 0.8, 0.9, 0.1, 0.99, 0.01;\n    ref << 0., -0.8416212335729142, 0.8416212335729142, 1.2815515655446004, -1.2815515655446004, 2.3263478740408408, -2.3263478740408408;\n    CALL_SUBTEST( verify_component_wise(ref, ref); );\n    CALL_SUBTEST( res = x.ndtri(); verify_component_wise(res, ref); );\n    CALL_SUBTEST( res = ndtri(x); verify_component_wise(res, ref); );\n\n    // ndtri(normal_cdf(x)) ~= x\n    CALL_SUBTEST(\n        ArrayType m1 = ArrayType::Random(32);\n        using std::sqrt;\n\n        ArrayType cdf_val = (m1 / Scalar(sqrt(2.))).erf();\n        cdf_val = (cdf_val + Scalar(1)) / Scalar(2);\n        verify_component_wise(cdf_val.ndtri(), m1););\n\n  }\n\n  // Check the zeta function against scipy.special.zeta\n  {\n    ArrayType x(10), q(10), res(10), ref(10);\n    x << 1.5,   4, 10.5, 10000.5,    3,      1,    0.9,  2,  3,  4;\n    q <<   2, 1.5,    3,  1.0001, -2.5, 1.2345, 1.2345, -1, -2, -3;\n    ref << 1.61237534869, 0.234848505667, 1.03086757337e-5, 0.367879440865, 0.054102025820864097, plusinf, nan, plusinf, nan, plusinf;\n    CALL_SUBTEST( verify_component_wise(ref, ref); );\n    CALL_SUBTEST( res = x.zeta(q); verify_component_wise(res, ref); );\n    CALL_SUBTEST( res = zeta(x,q); verify_component_wise(res, ref); );\n  }\n\n  // digamma\n  {\n    ArrayType x(9), res(9), ref(9);\n    x << 1, 1.5, 4, -10.5, 10000.5, 0, -1, -2, -3;\n    ref << -0.5772156649015329, 0.03648997397857645, 1.2561176684318, 2.398239129535781, 9.210340372392849, nan, nan, nan, nan;\n    CALL_SUBTEST( verify_component_wise(ref, ref); );\n\n    CALL_SUBTEST( res = x.digamma(); verify_component_wise(res, ref); );\n    CALL_SUBTEST( res = digamma(x);  verify_component_wise(res, ref); );\n  }\n\n#if EIGEN_HAS_C99_MATH\n  {\n    ArrayType n(16), x(16), res(16), ref(16);\n    n << 1, 1,    1, 1.5,   17,   31,   28,    8,   42,  147, 170, -1,  0,  1,  2,  3;\n    x << 2, 3, 25.5, 1.5,  4.7, 11.8, 17.7, 30.2, 15.8, 54.1,  64, -1, -2, -3, -4, -5;\n    ref << 0.644934066848, 0.394934066848, 0.0399946696496, nan, 293.334565435, 0.445487887616, -2.47810300902e-07, -8.29668781082e-09, -0.434562276666, 0.567742190178, -0.0108615497927, nan, nan, plusinf, nan, plusinf;\n    CALL_SUBTEST( verify_component_wise(ref, ref); );\n\n    if(sizeof(RealScalar)>=8) {  // double\n      // Reason for commented line: http://eigen.tuxfamily.org/bz/show_bug.cgi?id=1232\n      //       CALL_SUBTEST( res = x.polygamma(n); verify_component_wise(res, ref); );\n      CALL_SUBTEST( res = polygamma(n,x);  verify_component_wise(res, ref); );\n    }\n    else {\n      //       CALL_SUBTEST( res = x.polygamma(n); verify_component_wise(res.head(8), ref.head(8)); );\n      CALL_SUBTEST( res = polygamma(n,x); verify_component_wise(res.head(8), ref.head(8)); );\n    }\n  }\n#endif\n\n#if EIGEN_HAS_C99_MATH\n  {\n    // Inputs and ground truth generated with scipy via:\n    //   a = np.logspace(-3, 3, 5) - 1e-3\n    //   b = np.logspace(-3, 3, 5) - 1e-3\n    //   x = np.linspace(-0.1, 1.1, 5)\n    //   (full_a, full_b, full_x) = np.vectorize(lambda a, b, x: (a, b, x))(*np.ix_(a, b, x))\n    //   full_a = full_a.flatten().tolist()  # same for full_b, full_x\n    //   v = scipy.special.betainc(full_a, full_b, full_x).flatten().tolist()\n    //\n    // Note in Eigen, we call betainc with arguments in the order (x, a, b).\n    ArrayType a(125);\n    ArrayType b(125);\n    ArrayType x(125);\n    ArrayType v(125);\n    ArrayType res(125);\n\n    a << 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,\n        0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 0.0,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999,\n        0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999,\n        0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999, 0.999,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 999.999, 999.999, 999.999, 999.999, 999.999, 999.999,\n        999.999, 999.999, 999.999, 999.999, 999.999, 999.999, 999.999, 999.999,\n        999.999, 999.999, 999.999, 999.999, 999.999, 999.999, 999.999, 999.999,\n        999.999, 999.999, 999.999;\n\n    b << 0.0, 0.0, 0.0, 0.0, 0.0, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379, 0.999,\n        0.999, 0.999, 0.999, 0.999, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 31.62177660168379, 999.999,\n        999.999, 999.999, 999.999, 999.999, 0.0, 0.0, 0.0, 0.0, 0.0,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.999, 0.999, 0.999, 0.999,\n        0.999, 31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 999.999, 999.999, 999.999,\n        999.999, 999.999, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.999, 0.999, 0.999, 0.999, 0.999,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 999.999, 999.999, 999.999,\n        999.999, 999.999, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.999, 0.999, 0.999, 0.999, 0.999,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 999.999, 999.999, 999.999,\n        999.999, 999.999, 0.0, 0.0, 0.0, 0.0, 0.0, 0.03062277660168379,\n        0.03062277660168379, 0.03062277660168379, 0.03062277660168379,\n        0.03062277660168379, 0.999, 0.999, 0.999, 0.999, 0.999,\n        31.62177660168379, 31.62177660168379, 31.62177660168379,\n        31.62177660168379, 31.62177660168379, 999.999, 999.999, 999.999,\n        999.999, 999.999;\n\n    x << -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5,\n        0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2,\n        0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1,\n        0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1,\n        -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8,\n        1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5,\n        0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2,\n        0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1,\n        0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5, 0.8, 1.1, -0.1, 0.2, 0.5,\n        0.8, 1.1;\n\n    v << nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan,\n        nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan, nan,\n        nan, nan, nan, 0.47972119876364683, 0.5, 0.5202788012363533, nan, nan,\n        0.9518683957740043, 0.9789663010413743, 0.9931729188073435, nan, nan,\n        0.999995949033062, 0.9999999999993698, 0.9999999999999999, nan, nan,\n        0.9999999999999999, 0.9999999999999999, 0.9999999999999999, nan, nan,\n        nan, nan, nan, nan, nan, 0.006827081192655869, 0.0210336989586256,\n        0.04813160422599567, nan, nan, 0.20014344256217678, 0.5000000000000001,\n        0.7998565574378232, nan, nan, 0.9991401428435834, 0.999999999698403,\n        0.9999999999999999, nan, nan, 0.9999999999999999, 0.9999999999999999,\n        0.9999999999999999, nan, nan, nan, nan, nan, nan, nan,\n        1.0646600232370887e-25, 6.301722877826246e-13, 4.050966937974938e-06,\n        nan, nan, 7.864342668429763e-23, 3.015969667594166e-10,\n        0.0008598571564165444, nan, nan, 6.031987710123844e-08,\n        0.5000000000000007, 0.9999999396801229, nan, nan, 0.9999999999999999,\n        0.9999999999999999, 0.9999999999999999, nan, nan, nan, nan, nan, nan,\n        nan, 0.0, 7.029920380986636e-306, 2.2450728208591345e-101, nan, nan,\n        0.0, 9.275871147869727e-302, 1.2232913026152827e-97, nan, nan, 0.0,\n        3.0891393081932924e-252, 2.9303043666183996e-60, nan, nan,\n        2.248913486879199e-196, 0.5000000000004947, 0.9999999999999999, nan;\n\n    CALL_SUBTEST(res = betainc(a, b, x);\n                 verify_component_wise(res, v););\n  }\n\n  // Test various properties of betainc\n  {\n    ArrayType m1 = ArrayType::Random(32);\n    ArrayType m2 = ArrayType::Random(32);\n    ArrayType m3 = ArrayType::Random(32);\n    ArrayType one = ArrayType::Constant(32, Scalar(1.0));\n    const Scalar eps = std::numeric_limits<Scalar>::epsilon();\n    ArrayType a = (m1 * Scalar(4)).exp();\n    ArrayType b = (m2 * Scalar(4)).exp();\n    ArrayType x = m3.abs();\n\n    // betainc(a, 1, x) == x**a\n    CALL_SUBTEST(\n        ArrayType test = betainc(a, one, x);\n        ArrayType expected = x.pow(a);\n        verify_component_wise(test, expected););\n\n    // betainc(1, b, x) == 1 - (1 - x)**b\n    CALL_SUBTEST(\n        ArrayType test = betainc(one, b, x);\n        ArrayType expected = one - (one - x).pow(b);\n        verify_component_wise(test, expected););\n\n    // betainc(a, b, x) == 1 - betainc(b, a, 1-x)\n    CALL_SUBTEST(\n        ArrayType test = betainc(a, b, x) + betainc(b, a, one - x);\n        ArrayType expected = one;\n        verify_component_wise(test, expected););\n\n    // betainc(a+1, b, x) = betainc(a, b, x) - x**a * (1 - x)**b / (a * beta(a, b))\n    CALL_SUBTEST(\n        ArrayType num = x.pow(a) * (one - x).pow(b);\n        ArrayType denom = a * (a.lgamma() + b.lgamma() - (a + b).lgamma()).exp();\n        // Add eps to rhs and lhs so that component-wise test doesn't result in\n        // nans when both outputs are zeros.\n        ArrayType expected = betainc(a, b, x) - num / denom + eps;\n        ArrayType test = betainc(a + one, b, x) + eps;\n        if (sizeof(Scalar) >= 8) { // double\n          verify_component_wise(test, expected);\n        } else {\n          // Reason for limited test: http://eigen.tuxfamily.org/bz/show_bug.cgi?id=1232\n          verify_component_wise(test.head(8), expected.head(8));\n        });\n\n    // betainc(a, b+1, x) = betainc(a, b, x) + x**a * (1 - x)**b / (b * beta(a, b))\n    CALL_SUBTEST(\n        // Add eps to rhs and lhs so that component-wise test doesn't result in\n        // nans when both outputs are zeros.\n        ArrayType num = x.pow(a) * (one - x).pow(b);\n        ArrayType denom = b * (a.lgamma() + b.lgamma() - (a + b).lgamma()).exp();\n        ArrayType expected = betainc(a, b, x) + num / denom + eps;\n        ArrayType test = betainc(a, b + one, x) + eps;\n        verify_component_wise(test, expected););\n  }\n#endif  // EIGEN_HAS_C99_MATH\n\n    /* Code to generate the data for the following two test cases.\n    N = 5\n    np.random.seed(3)\n\n    a = np.logspace(-2, 3, 6)\n    a = np.ravel(np.tile(np.reshape(a, [-1, 1]), [1, N]))\n    x = np.random.gamma(a, 1.0)\n    x = np.maximum(x, np.finfo(np.float32).tiny)\n\n    def igamma(a, x):\n      return mpmath.gammainc(a, 0, x, regularized=True)\n\n    def igamma_der_a(a, x):\n      res = mpmath.diff(lambda a_prime: igamma(a_prime, x), a)\n      return np.float64(res)\n\n    def gamma_sample_der_alpha(a, x):\n      igamma_x = igamma(a, x)\n      def igammainv_of_igamma(a_prime):\n        return mpmath.findroot(lambda x_prime: igamma(a_prime, x_prime) -\n            igamma_x, x, solver='newton')\n      return np.float64(mpmath.diff(igammainv_of_igamma, a))\n\n    v_igamma_der_a = np.vectorize(igamma_der_a)(a, x)\n    v_gamma_sample_der_alpha = np.vectorize(gamma_sample_der_alpha)(a, x)\n  */\n\n#if EIGEN_HAS_C99_MATH\n  // Test igamma_der_a\n  {\n    ArrayType a(30);\n    ArrayType x(30);\n    ArrayType res(30);\n    ArrayType v(30);\n\n    a << 0.01, 0.01, 0.01, 0.01, 0.01, 0.1, 0.1, 0.1, 0.1, 0.1, 1.0, 1.0, 1.0,\n        1.0, 1.0, 10.0, 10.0, 10.0, 10.0, 10.0, 100.0, 100.0, 100.0, 100.0,\n        100.0, 1000.0, 1000.0, 1000.0, 1000.0, 1000.0;\n\n    x << 1.25668890405e-26, 1.17549435082e-38, 1.20938905072e-05,\n        1.17549435082e-38, 1.17549435082e-38, 5.66572070696e-16,\n        0.0132865061065, 0.0200034203853, 6.29263709118e-17, 1.37160367764e-06,\n        0.333412038288, 1.18135687766, 0.580629033777, 0.170631439426,\n        0.786686768458, 7.63873279537, 13.1944344379, 11.896042354,\n        10.5830172417, 10.5020942233, 92.8918587747, 95.003720371,\n        86.3715926467, 96.0330217672, 82.6389930677, 968.702906754,\n        969.463546828, 1001.79726022, 955.047416547, 1044.27458568;\n\n    v << -32.7256441441, -36.4394150514, -9.66467612263, -36.4394150514,\n        -36.4394150514, -1.0891900302, -2.66351229645, -2.48666868596,\n        -0.929700494428, -3.56327722764, -0.455320135314, -0.391437214323,\n        -0.491352055991, -0.350454834292, -0.471773162921, -0.104084440522,\n        -0.0723646747909, -0.0992828975532, -0.121638215446, -0.122619605294,\n        -0.0317670267286, -0.0359974812869, -0.0154359225363, -0.0375775365921,\n        -0.00794899153653, -0.00777303219211, -0.00796085782042,\n        -0.0125850719397, -0.00455500206958, -0.00476436993148;\n\n    CALL_SUBTEST(res = igamma_der_a(a, x); verify_component_wise(res, v););\n  }\n\n  // Test gamma_sample_der_alpha\n  {\n    ArrayType alpha(30);\n    ArrayType sample(30);\n    ArrayType res(30);\n    ArrayType v(30);\n\n    alpha << 0.01, 0.01, 0.01, 0.01, 0.01, 0.1, 0.1, 0.1, 0.1, 0.1, 1.0, 1.0,\n        1.0, 1.0, 1.0, 10.0, 10.0, 10.0, 10.0, 10.0, 100.0, 100.0, 100.0, 100.0,\n        100.0, 1000.0, 1000.0, 1000.0, 1000.0, 1000.0;\n\n    sample << 1.25668890405e-26, 1.17549435082e-38, 1.20938905072e-05,\n        1.17549435082e-38, 1.17549435082e-38, 5.66572070696e-16,\n        0.0132865061065, 0.0200034203853, 6.29263709118e-17, 1.37160367764e-06,\n        0.333412038288, 1.18135687766, 0.580629033777, 0.170631439426,\n        0.786686768458, 7.63873279537, 13.1944344379, 11.896042354,\n        10.5830172417, 10.5020942233, 92.8918587747, 95.003720371,\n        86.3715926467, 96.0330217672, 82.6389930677, 968.702906754,\n        969.463546828, 1001.79726022, 955.047416547, 1044.27458568;\n\n    v << 7.42424742367e-23, 1.02004297287e-34, 0.0130155240738,\n        1.02004297287e-34, 1.02004297287e-34, 1.96505168277e-13, 0.525575786243,\n        0.713903991771, 2.32077561808e-14, 0.000179348049886, 0.635500453302,\n        1.27561284917, 0.878125852156, 0.41565819538, 1.03606488534,\n        0.885964824887, 1.16424049334, 1.10764479598, 1.04590810812,\n        1.04193666963, 0.965193152414, 0.976217589464, 0.93008035061,\n        0.98153216096, 0.909196397698, 0.98434963993, 0.984738050206,\n        1.00106492525, 0.97734200649, 1.02198794179;\n\n    CALL_SUBTEST(res = gamma_sample_der_alpha(alpha, sample);\n                 verify_component_wise(res, v););\n  }\n#endif  // EIGEN_HAS_C99_MATH\n}\n\nEIGEN_DECLARE_TEST(special_functions)\n{\n  CALL_SUBTEST_1(array_special_functions<ArrayXf>());\n  CALL_SUBTEST_2(array_special_functions<ArrayXd>());\n  // TODO(cantonios): half/bfloat16 don't have enough precision to reproduce results above.\n  // CALL_SUBTEST_3(array_special_functions<ArrayX<Eigen::half>>());\n  // CALL_SUBTEST_4(array_special_functions<ArrayX<Eigen::bfloat16>>());\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/special_packetmath.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2008-2009 Gael Guennebaud <gael.guennebaud@inria.fr>\n// Copyright (C) 2006-2008 Benoit Jacob <jacob.benoit.1@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include <limits>\n#include \"packetmath_test_shared.h\"\n#include \"../Eigen/SpecialFunctions\"\n\ntemplate<typename Scalar,typename Packet> void packetmath_real()\n{\n  using std::abs;\n  typedef internal::packet_traits<Scalar> PacketTraits;\n  const int PacketSize = internal::unpacket_traits<Packet>::size;\n\n  const int size = PacketSize*4;\n  EIGEN_ALIGN_MAX Scalar data1[PacketSize*4];\n  EIGEN_ALIGN_MAX Scalar data2[PacketSize*4];\n  EIGEN_ALIGN_MAX Scalar ref[PacketSize*4];\n\n#if EIGEN_HAS_C99_MATH\n  {\n    data1[0] = std::numeric_limits<Scalar>::quiet_NaN();\n    test::packet_helper<internal::packet_traits<Scalar>::HasLGamma,Packet> h;\n    h.store(data2, internal::plgamma(h.load(data1)));\n    VERIFY((numext::isnan)(data2[0]));\n  }\n  if (internal::packet_traits<Scalar>::HasErf) {\n    data1[0] = std::numeric_limits<Scalar>::quiet_NaN();\n    test::packet_helper<internal::packet_traits<Scalar>::HasErf,Packet> h;\n    h.store(data2, internal::perf(h.load(data1)));\n    VERIFY((numext::isnan)(data2[0]));\n  }\n  {\n    data1[0] = std::numeric_limits<Scalar>::quiet_NaN();\n    test::packet_helper<internal::packet_traits<Scalar>::HasErfc,Packet> h;\n    h.store(data2, internal::perfc(h.load(data1)));\n    VERIFY((numext::isnan)(data2[0]));\n  }\n  {\n    for (int i=0; i<size; ++i) {\n      data1[i] = internal::random<Scalar>(Scalar(0),Scalar(1));\n    }\n    CHECK_CWISE1_IF(internal::packet_traits<Scalar>::HasNdtri, numext::ndtri, internal::pndtri);\n  }\n#endif  // EIGEN_HAS_C99_MATH\n\n  // For bessel_i*e and bessel_j*, the valid range is negative reals.\n  {\n    const int max_exponent = numext::mini(std::numeric_limits<Scalar>::max_exponent10-1, 6);\n    for (int i=0; i<size; ++i)\n    {\n      data1[i] = internal::random<Scalar>(Scalar(-1),Scalar(1)) * Scalar(std::pow(Scalar(10), internal::random<Scalar>(Scalar(-max_exponent),Scalar(max_exponent))));\n      data2[i] = internal::random<Scalar>(Scalar(-1),Scalar(1)) * Scalar(std::pow(Scalar(10), internal::random<Scalar>(Scalar(-max_exponent),Scalar(max_exponent))));\n    }\n\n    CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_i0e, internal::pbessel_i0e);\n    CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_i1e, internal::pbessel_i1e);\n    CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_j0, internal::pbessel_j0);\n    CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_j1, internal::pbessel_j1);\n  }\n\n  // Use a smaller data range for the bessel_i* as these can become very large.\n  // Following #1693, we also restrict this range further to avoid inf's due to\n  // differences in pexp and exp.\n  for (int i=0; i<size; ++i) {\n      data1[i] = internal::random<Scalar>(Scalar(0.01),Scalar(1)) *\n                  Scalar(std::pow(Scalar(9), internal::random<Scalar>(Scalar(-1),Scalar(2))));\n      data2[i] = internal::random<Scalar>(Scalar(0.01),Scalar(1)) *\n                  Scalar(std::pow(Scalar(9), internal::random<Scalar>(Scalar(-1),Scalar(2))));\n  }\n  CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_i0, internal::pbessel_i0);\n  CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_i1, internal::pbessel_i1);\n\n\n  // y_i, and k_i are valid for x > 0.\n  {\n    const int max_exponent = numext::mini(std::numeric_limits<Scalar>::max_exponent10-1, 5);\n    for (int i=0; i<size; ++i)\n    {\n      data1[i] = internal::random<Scalar>(Scalar(0.01),Scalar(1)) * Scalar(std::pow(Scalar(10), internal::random<Scalar>(Scalar(-2),Scalar(max_exponent))));\n      data2[i] = internal::random<Scalar>(Scalar(0.01),Scalar(1)) * Scalar(std::pow(Scalar(10), internal::random<Scalar>(Scalar(-2),Scalar(max_exponent))));\n    }\n  }\n\n  // TODO(srvasude): Re-enable this test once properly investigated why the\n  // scalar and vector paths differ.\n  // CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_y0, internal::pbessel_y0);\n  CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_y1, internal::pbessel_y1);\n  CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_k0e, internal::pbessel_k0e);\n  CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_k1e, internal::pbessel_k1e);\n\n  // Following #1693, we restrict the range for exp to avoid zeroing out too\n  // fast.\n  for (int i=0; i<size; ++i) {\n      data1[i] = internal::random<Scalar>(Scalar(0.01),Scalar(1)) *\n                  Scalar(std::pow(Scalar(9), internal::random<Scalar>(Scalar(-1),Scalar(2))));\n      data2[i] = internal::random<Scalar>(Scalar(0.01),Scalar(1)) *\n                  Scalar(std::pow(Scalar(9), internal::random<Scalar>(Scalar(-1),Scalar(2))));\n  }\n  CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_k0, internal::pbessel_k0);\n  CHECK_CWISE1_IF(PacketTraits::HasBessel, numext::bessel_k1, internal::pbessel_k1);\n\n\n  for (int i=0; i<size; ++i) {\n      data1[i] = internal::random<Scalar>(Scalar(0.01),Scalar(1)) *\n                  Scalar(std::pow(Scalar(10), internal::random<Scalar>(Scalar(-1),Scalar(2))));\n      data2[i] = internal::random<Scalar>(Scalar(0.01),Scalar(1)) *\n                  Scalar(std::pow(Scalar(10), internal::random<Scalar>(Scalar(-1),Scalar(2))));\n  }\n\n#if EIGEN_HAS_C99_MATH && (EIGEN_COMP_CXXVER >= 11)\n  CHECK_CWISE1_IF(internal::packet_traits<Scalar>::HasLGamma, std::lgamma, internal::plgamma);\n  CHECK_CWISE1_IF(internal::packet_traits<Scalar>::HasErf, std::erf, internal::perf);\n  CHECK_CWISE1_IF(internal::packet_traits<Scalar>::HasErfc, std::erfc, internal::perfc);\n#endif\n\n}\n\nnamespace Eigen {\nnamespace test {\n\ntemplate<typename Scalar,typename PacketType, bool IsComplex, bool IsInteger>\nstruct runall {\n  static void run() {\n    packetmath_real<Scalar,PacketType>();\n  }\n};\n\n}\n}\n\nEIGEN_DECLARE_TEST(special_packetmath)\n{\n  g_first_pass = true;\n  for(int i = 0; i < g_repeat; i++) {\n\n    CALL_SUBTEST_1( test::runner<float>::run() );\n    CALL_SUBTEST_2( test::runner<double>::run() );\n    CALL_SUBTEST_3( test::runner<Eigen::half>::run() );\n    CALL_SUBTEST_4( test::runner<Eigen::bfloat16>::run() );\n    g_first_pass = false;\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/eigen/unsupported/test/splines.cpp",
    "content": "// This file is part of Eigen, a lightweight C++ template library\n// for linear algebra.\n//\n// Copyright (C) 2010-2011 Hauke Heibel <heibel@gmail.com>\n//\n// This Source Code Form is subject to the terms of the Mozilla\n// Public License v. 2.0. If a copy of the MPL was not distributed\n// with this file, You can obtain one at http://mozilla.org/MPL/2.0/.\n\n#include \"main.h\"\n\n#include <unsupported/Eigen/Splines>\n\nnamespace Eigen {\n  \n  // lets do some explicit instantiations and thus\n  // force the compilation of all spline functions...\n  template class Spline<double, 2, Dynamic>;\n  template class Spline<double, 3, Dynamic>;\n\n  template class Spline<double, 2, 2>;\n  template class Spline<double, 2, 3>;\n  template class Spline<double, 2, 4>;\n  template class Spline<double, 2, 5>;\n\n  template class Spline<float, 2, Dynamic>;\n  template class Spline<float, 3, Dynamic>;\n\n  template class Spline<float, 3, 2>;\n  template class Spline<float, 3, 3>;\n  template class Spline<float, 3, 4>;\n  template class Spline<float, 3, 5>;\n\n}\n\nSpline<double, 2, Dynamic> closed_spline2d()\n{\n  RowVectorXd knots(12);\n  knots << 0,\n    0,\n    0,\n    0,\n    0.867193179093898,\n    1.660330955342408,\n    2.605084834823134,\n    3.484154586374428,\n    4.252699478956276,\n    4.252699478956276,\n    4.252699478956276,\n    4.252699478956276;\n\n  MatrixXd ctrls(8,2);\n  ctrls << -0.370967741935484,   0.236842105263158,\n    -0.231401860693277,   0.442245185027632,\n    0.344361228532831,   0.773369994120753,\n    0.828990216203802,   0.106550882647595,\n    0.407270163678382,  -1.043452922172848,\n    -0.488467813584053,  -0.390098582530090,\n    -0.494657189446427,   0.054804824897884,\n    -0.370967741935484,   0.236842105263158;\n  ctrls.transposeInPlace();\n\n  return Spline<double, 2, Dynamic>(knots, ctrls);\n}\n\n/* create a reference spline */\nSpline<double, 3, Dynamic> spline3d()\n{\n  RowVectorXd knots(11);\n  knots << 0,\n    0,\n    0,\n    0.118997681558377,\n    0.162611735194631,\n    0.498364051982143,\n    0.655098003973841,\n    0.679702676853675,\n    1.000000000000000,\n    1.000000000000000,\n    1.000000000000000;\n\n  MatrixXd ctrls(8,3);\n  ctrls <<    0.959743958516081,   0.340385726666133,   0.585267750979777,\n    0.223811939491137,   0.751267059305653,   0.255095115459269,\n    0.505957051665142,   0.699076722656686,   0.890903252535799,\n    0.959291425205444,   0.547215529963803,   0.138624442828679,\n    0.149294005559057,   0.257508254123736,   0.840717255983663,\n    0.254282178971531,   0.814284826068816,   0.243524968724989,\n    0.929263623187228,   0.349983765984809,   0.196595250431208,\n    0.251083857976031,   0.616044676146639,   0.473288848902729;\n  ctrls.transposeInPlace();\n\n  return Spline<double, 3, Dynamic>(knots, ctrls);\n}\n\n/* compares evaluations against known results */\nvoid eval_spline3d()\n{\n  Spline3d spline = spline3d();\n\n  RowVectorXd u(10);\n  u << 0.351659507062997,\n    0.830828627896291,\n    0.585264091152724,\n    0.549723608291140,\n    0.917193663829810,\n    0.285839018820374,\n    0.757200229110721,\n    0.753729094278495,\n    0.380445846975357,\n    0.567821640725221;\n\n  MatrixXd pts(10,3);\n  pts << 0.707620811535916,   0.510258911240815,   0.417485437023409,\n    0.603422256426978,   0.529498282727551,   0.270351549348981,\n    0.228364197569334,   0.423745615677815,   0.637687289287490,\n    0.275556796335168,   0.350856706427970,   0.684295784598905,\n    0.514519311047655,   0.525077224890754,   0.351628308305896,\n    0.724152914315666,   0.574461155457304,   0.469860285484058,\n    0.529365063753288,   0.613328702656816,   0.237837040141739,\n    0.522469395136878,   0.619099658652895,   0.237139665242069,\n    0.677357023849552,   0.480655768435853,   0.422227610314397,\n    0.247046593173758,   0.380604672404750,   0.670065791405019;\n  pts.transposeInPlace();\n\n  for (int i=0; i<u.size(); ++i)\n  {\n    Vector3d pt = spline(u(i));\n    VERIFY( (pt - pts.col(i)).norm() < 1e-14 );\n  }\n}\n\n/* compares evaluations on corner cases */\nvoid eval_spline3d_onbrks()\n{\n  Spline3d spline = spline3d();\n\n  RowVectorXd u = spline.knots();\n\n  MatrixXd pts(11,3);\n  pts <<    0.959743958516081,   0.340385726666133,   0.585267750979777,\n    0.959743958516081,   0.340385726666133,   0.585267750979777,\n    0.959743958516081,   0.340385726666133,   0.585267750979777,\n    0.430282980289940,   0.713074680056118,   0.720373307943349,\n    0.558074875553060,   0.681617921034459,   0.804417124839942,\n    0.407076008291750,   0.349707710518163,   0.617275937419545,\n    0.240037008286602,   0.738739390398014,   0.324554153129411,\n    0.302434111480572,   0.781162443963899,   0.240177089094644,\n    0.251083857976031,   0.616044676146639,   0.473288848902729,\n    0.251083857976031,   0.616044676146639,   0.473288848902729,\n    0.251083857976031,   0.616044676146639,   0.473288848902729;\n  pts.transposeInPlace();\n\n  for (int i=0; i<u.size(); ++i)\n  {\n    Vector3d pt = spline(u(i));\n    VERIFY( (pt - pts.col(i)).norm() < 1e-14 );\n  }\n}\n\nvoid eval_closed_spline2d()\n{\n  Spline2d spline = closed_spline2d();\n\n  RowVectorXd u(12);\n  u << 0,\n    0.332457030395796,\n    0.356467130532952,\n    0.453562180176215,\n    0.648017921874804,\n    0.973770235555003,\n    1.882577647219307,\n    2.289408593930498,\n    3.511951429883045,\n    3.884149321369450,\n    4.236261590369414,\n    4.252699478956276;\n\n  MatrixXd pts(12,2);\n  pts << -0.370967741935484,   0.236842105263158,\n    -0.152576775123250,   0.448975001279334,\n    -0.133417538277668,   0.461615613865667,\n    -0.053199060826740,   0.507630360006299,\n    0.114249591147281,   0.570414135097409,\n    0.377810316891987,   0.560497102875315,\n    0.665052120135908,  -0.157557441109611,\n    0.516006487053228,  -0.559763292174825,\n    -0.379486035348887,  -0.331959640488223,\n    -0.462034726249078,  -0.039105670080824,\n    -0.378730600917982,   0.225127015099919,\n    -0.370967741935484,   0.236842105263158;\n  pts.transposeInPlace();\n\n  for (int i=0; i<u.size(); ++i)\n  {\n    Vector2d pt = spline(u(i));\n    VERIFY( (pt - pts.col(i)).norm() < 1e-14 );\n  }\n}\n\nvoid check_global_interpolation2d()\n{\n  typedef Spline2d::PointType PointType;\n  typedef Spline2d::KnotVectorType KnotVectorType;\n  typedef Spline2d::ControlPointVectorType ControlPointVectorType;\n\n  ControlPointVectorType points = ControlPointVectorType::Random(2,100);\n\n  KnotVectorType chord_lengths; // knot parameters\n  Eigen::ChordLengths(points, chord_lengths);\n\n  // interpolation without knot parameters\n  {\n    const Spline2d spline = SplineFitting<Spline2d>::Interpolate(points,3);  \n\n    for (Eigen::DenseIndex i=0; i<points.cols(); ++i)\n    {\n      PointType pt = spline( chord_lengths(i) );\n      PointType ref = points.col(i);\n      VERIFY( (pt - ref).matrix().norm() < 1e-14 );\n    }\n  }\n\n  // interpolation with given knot parameters\n  {\n    const Spline2d spline = SplineFitting<Spline2d>::Interpolate(points,3,chord_lengths);  \n\n    for (Eigen::DenseIndex i=0; i<points.cols(); ++i)\n    {\n      PointType pt = spline( chord_lengths(i) );\n      PointType ref = points.col(i);\n      VERIFY( (pt - ref).matrix().norm() < 1e-14 );\n    }\n  }\n}\n\nvoid check_global_interpolation_with_derivatives2d()\n{\n  typedef Spline2d::PointType PointType;\n  typedef Spline2d::KnotVectorType KnotVectorType;\n\n  const Eigen::DenseIndex numPoints = 100;\n  const unsigned int dimension = 2;\n  const unsigned int degree = 3;\n\n  ArrayXXd points = ArrayXXd::Random(dimension, numPoints);\n\n  KnotVectorType knots;\n  Eigen::ChordLengths(points, knots);\n\n  ArrayXXd derivatives = ArrayXXd::Random(dimension, numPoints);\n  VectorXd derivativeIndices(numPoints);\n\n  for (Eigen::DenseIndex i = 0; i < numPoints; ++i)\n      derivativeIndices(i) = static_cast<double>(i);\n\n  const Spline2d spline = SplineFitting<Spline2d>::InterpolateWithDerivatives(\n    points, derivatives, derivativeIndices, degree);  \n    \n  for (Eigen::DenseIndex i = 0; i < points.cols(); ++i)\n  {\n    PointType point = spline(knots(i));\n    PointType referencePoint = points.col(i);\n    VERIFY_IS_APPROX(point, referencePoint);\n    PointType derivative = spline.derivatives(knots(i), 1).col(1);\n    PointType referenceDerivative = derivatives.col(i);\n    VERIFY_IS_APPROX(derivative, referenceDerivative);\n  }\n}\n\nEIGEN_DECLARE_TEST(splines)\n{\n  for (int i = 0; i < g_repeat; ++i)\n  {\n    CALL_SUBTEST( eval_spline3d() );\n    CALL_SUBTEST( eval_spline3d_onbrks() );\n    CALL_SUBTEST( eval_closed_spline2d() );\n    CALL_SUBTEST( check_global_interpolation2d() );\n    CALL_SUBTEST( check_global_interpolation_with_derivatives2d() );\n  }\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/__init__.py",
    "content": ""
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/data_readers/__init__.py",
    "content": "\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/data_readers/augmentation.py",
    "content": "import torch\nimport torchvision.transforms as transforms\nimport numpy as np\nimport torch.nn.functional as F\n\n\nclass RGBDAugmentor:\n    \"\"\" perform augmentation on RGB-D video \"\"\"\n\n    def __init__(self, crop_size):\n        self.crop_size = crop_size\n        self.augcolor = transforms.Compose([\n            transforms.ToPILImage(),\n            transforms.ColorJitter(brightness=0.2, contrast=0.2, saturation=0.2, hue=0.4/3.14),\n            transforms.ToTensor()])\n\n        self.max_scale = 0.25\n\n    def spatial_transform(self, images, depths, poses, intrinsics):\n        \"\"\" cropping and resizing \"\"\"\n        ht, wd = images.shape[2:]\n\n        max_scale = self.max_scale\n        min_scale = np.log2(np.maximum(\n            (self.crop_size[0] + 1) / float(ht),\n            (self.crop_size[1] + 1) / float(wd)))\n\n        scale = 2 ** np.random.uniform(min_scale, max_scale)\n        intrinsics = scale * intrinsics\n        depths = depths.unsqueeze(dim=1)\n\n        images = F.interpolate(images, scale_factor=scale, mode='bilinear', \n            align_corners=True, recompute_scale_factor=True)\n        \n        depths = F.interpolate(depths, scale_factor=scale, recompute_scale_factor=True)\n\n        # always perform center crop (TODO: try non-center crops)\n        y0 = (images.shape[2] - self.crop_size[0]) // 2\n        x0 = (images.shape[3] - self.crop_size[1]) // 2\n\n        intrinsics = intrinsics - torch.tensor([0.0, 0.0, x0, y0])\n        images = images[:, :, y0:y0+self.crop_size[0], x0:x0+self.crop_size[1]]\n        depths = depths[:, :, y0:y0+self.crop_size[0], x0:x0+self.crop_size[1]]\n\n        depths = depths.squeeze(dim=1)\n        return images, poses, depths, intrinsics\n\n    def color_transform(self, images):\n        \"\"\" color jittering \"\"\"\n        num, ch, ht, wd = images.shape\n        images = images.permute(1, 2, 3, 0).reshape(ch, ht, wd*num)\n        images = 255 * self.augcolor(images[[2,1,0]] / 255.0)\n        return images[[2,1,0]].reshape(ch, ht, wd, num).permute(3,0,1,2).contiguous()\n\n    def __call__(self, images, poses, depths, intrinsics):\n        images = self.color_transform(images)\n        return self.spatial_transform(images, depths, poses, intrinsics)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/data_readers/base.py",
    "content": "\nimport numpy as np\nimport torch\nimport torch.utils.data as data\nimport torch.nn.functional as F\n\nimport csv\nimport os\nimport cv2\nimport math\nimport random\nimport json\nimport pickle\nimport os.path as osp\n\nfrom .augmentation import RGBDAugmentor\nfrom .rgbd_utils import *\n\nclass RGBDDataset(data.Dataset):\n    def __init__(self, root, name, n_frames=4, crop_size=[384,512], fmin=8.0, fmax=75.0, do_aug=True):\n        \"\"\" Base class for RGBD dataset \"\"\"\n        self.aug = None\n        self.root = root\n        self.name = name\n\n        self.n_frames = n_frames\n        self.fmin = fmin # exclude very easy examples\n        self.fmax = fmax # exclude very hard examples\n        \n        if do_aug:\n            self.aug = RGBDAugmentor(crop_size=crop_size)\n\n        # building dataset is expensive, cache so only needs to be performed once\n        cur_path = osp.dirname(osp.abspath(__file__))\n        cache_path = osp.join(cur_path, 'cache', '{}.pickle'.format(self.name))\n\n        if not osp.isdir(osp.join(cur_path, 'cache')):\n            os.mkdir(osp.join(cur_path, 'cache'))\n\n        if osp.isfile(cache_path):\n            scene_info = pickle.load(open(cache_path, 'rb'))[0]\n        else:\n            scene_info = self._build_dataset()\n            with open(cache_path, 'wb') as cachefile:\n                pickle.dump((scene_info,), cachefile)\n\n        self.scene_info = scene_info\n        self._build_dataset_index()\n                \n    def _build_dataset_index(self):\n        self.dataset_index = []\n        for scene in self.scene_info:\n            if not self.__class__.is_test_scene(scene):\n                graph = self.scene_info[scene]['graph']\n                for i in graph:\n                    if len(graph[i][0]) > self.n_frames:\n                        self.dataset_index.append((scene, i))\n\n    @staticmethod\n    def image_read(image_file):\n        return cv2.imread(image_file)\n\n    @staticmethod\n    def depth_read(depth_file):\n        return np.load(depth_file)\n\n    def build_frame_graph(self, poses, depths, intrinsics, f=16, max_flow=256):\n        \"\"\" compute optical flow distance between all pairs of frames \"\"\"\n        def read_disp(fn):\n            depth = self.__class__.depth_read(fn)[f//2::f, f//2::f]\n            depth[depth < 0.01] = np.mean(depth)\n            return 1.0 / depth\n\n        poses = np.array(poses)\n        intrinsics = np.array(intrinsics) / f\n        \n        disps = np.stack(list(map(read_disp, depths)), 0)\n        d = f * compute_distance_matrix_flow(poses, disps, intrinsics)\n\n        # uncomment for nice visualization\n        # import matplotlib.pyplot as plt\n        # plt.imshow(d)\n        # plt.show()\n\n        graph = {}\n        for i in range(d.shape[0]):\n            j, = np.where(d[i] < max_flow)\n            graph[i] = (j, d[i,j])\n\n        return graph\n\n    def __getitem__(self, index):\n        \"\"\" return training video \"\"\"\n\n        index = index % len(self.dataset_index)\n        scene_id, ix = self.dataset_index[index]\n\n        frame_graph = self.scene_info[scene_id]['graph']\n        images_list = self.scene_info[scene_id]['images']\n        depths_list = self.scene_info[scene_id]['depths']\n        poses_list = self.scene_info[scene_id]['poses']\n        intrinsics_list = self.scene_info[scene_id]['intrinsics']\n\n        inds = [ ix ]\n        while len(inds) < self.n_frames:\n            # get other frames within flow threshold\n            k = (frame_graph[ix][1] > self.fmin) & (frame_graph[ix][1] < self.fmax)\n            frames = frame_graph[ix][0][k]\n\n            # prefer frames forward in time\n            if np.count_nonzero(frames[frames > ix]):\n                ix = np.random.choice(frames[frames > ix])\n            \n            elif np.count_nonzero(frames):\n                ix = np.random.choice(frames)\n\n            inds += [ ix ]\n\n        images, depths, poses, intrinsics = [], [], [], []\n        for i in inds:\n            images.append(self.__class__.image_read(images_list[i]))\n            depths.append(self.__class__.depth_read(depths_list[i]))\n            poses.append(poses_list[i])\n            intrinsics.append(intrinsics_list[i])\n\n        images = np.stack(images).astype(np.float32)\n        depths = np.stack(depths).astype(np.float32)\n        poses = np.stack(poses).astype(np.float32)\n        intrinsics = np.stack(intrinsics).astype(np.float32)\n\n        images = torch.from_numpy(images).float()\n        images = images.permute(0, 3, 1, 2)\n\n        depths = torch.from_numpy(depths)\n        poses = torch.from_numpy(poses)\n        intrinsics = torch.from_numpy(intrinsics)\n\n        if self.aug is not None:\n            images, poses, depths, intrinsics = \\\n                self.aug(images, poses, depths, intrinsics)\n\n        return images, poses, depths, intrinsics \n\n    def __len__(self):\n        return len(self.dataset_index)\n\n    def __imul__(self, x):\n        self.dataset_index *= x\n        return self\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/data_readers/eth3d.py",
    "content": "\nimport numpy as np\nimport torch\nimport torch.utils.data as data\nimport torch.nn.functional as F\n\nimport csv\nimport os\nimport cv2\nimport math\nimport random\nimport json\nimport pickle\nimport os.path as osp\n\nfrom lietorch import SE3\nfrom .base import RGBDDataset\nfrom .stream import RGBDStream\nfrom .augmentation import RGBDAugmentor\nfrom .rgbd_utils import loadtum, all_pairs_distance_matrix\n\nclass ETH3D(RGBDDataset):\n    def __init__(self, **kwargs):\n        super(ETH3D, self).__init__(root='datasets/ETH3D', name='ETH3D', **kwargs)\n\n    @staticmethod \n    def is_test_scene(scene):\n        return False\n\n    def _build_dataset(self):\n        from tqdm import tqdm\n        print(\"Building ETH3D dataset\")\n\n        scene_info = {}\n        dataset_index = []\n\n        for scene in tqdm(os.listdir(self.root)):\n            scene_path = osp.join(self.root, scene)\n            \n            if not osp.isdir(scene_path):\n                continue\n            \n            # don't use scenes with no rgb info\n            if 'dark' in scene or 'kidnap' in scene:\n                continue\n\n            scene_data, graph = {}, {}\n            images, depths, poses, intrinsics = loadtum(scene_path, skip=2)\n\n            # graph of co-visible frames based on flow\n            graph = self.build_frame_graph(poses, depths, intrinsics)\n\n            scene_info[scene] = {'images': images, 'depths': depths, \n                'poses': poses, 'intrinsics': intrinsics, 'graph': graph}\n\n        return scene_info\n\n    @staticmethod\n    def image_read(image_file):\n        return cv2.imread(image_file)\n\n    @staticmethod\n    def depth_read(depth_file):\n        depth = cv2.imread(depth_file, cv2.IMREAD_ANYDEPTH)\n        return depth.astype(np.float32) / 5000.0\n\n\nclass ETH3DStream(RGBDStream):\n    def __init__(self, datapath, **kwargs):\n        super(ETH3DStream, self).__init__(datapath=datapath, **kwargs)\n\n    def _build_dataset_index(self):\n        \"\"\" build list of images, poses, depths, and intrinsics \"\"\"\n        images, depths, poses, intrinsics = loadtum(self.datapath, self.frame_rate)\n\n        # set first pose to identity\n        poses = SE3(torch.as_tensor(poses))\n        poses = poses[[0]].inv() * poses\n        poses = poses.data.cpu().numpy()\n\n        self.images = images\n        self.poses = poses\n        self.depths = depths\n        self.intrinsics = intrinsics\n\n    @staticmethod\n    def image_read(image_file):\n        return cv2.imread(image_file)\n\n    @staticmethod\n    def depth_read(depth_file):\n        depth = cv2.imread(depth_file, cv2.IMREAD_ANYDEPTH)\n        return depth.astype(np.float32) / 5000.0\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/data_readers/factory.py",
    "content": "\nimport pickle\nimport os\nimport os.path as osp\n\n# RGBD-Dataset\nfrom .tartan import TartanAir\nfrom .nyu2 import NYUv2\nfrom .eth3d import ETH3D\nfrom .scannet import ScanNet\n\n# streaming datasets for inference\nfrom .eth3d import ETH3DStream\nfrom .tum import TUMStream\nfrom .tartan import TartanAirStream\n\n\ndef dataset_factory(dataset_list, **kwargs):\n    \"\"\" create a combined dataset \"\"\"\n\n    from torch.utils.data import ConcatDataset\n\n    dataset_map = {\n        'tartan': (TartanAir, 1),\n        'nyu': (NYUv2, 2),\n        'eth': (ETH3D, 5),\n        'scannet': (ScanNet, 1)}\n\n    db_list = []\n    for key in dataset_list:\n        # cache datasets for faster future loading\n        db = dataset_map[key][0](**kwargs)\n        db *= dataset_map[key][1]\n\n        print(\"Dataset {} has {} images\".format(key, len(db)))\n        db_list.append(db)\n\n    return ConcatDataset(db_list)\n            \n\ndef create_datastream(dataset_path, **kwargs):\n    \"\"\" create data_loader to stream images 1 by 1 \"\"\"\n\n    from torch.utils.data import DataLoader\n\n    if osp.isfile(osp.join(dataset_path, 'calibration.txt')):\n        db = ETH3DStream(dataset_path, **kwargs)\n\n    elif osp.isfile(osp.join(dataset_path, 'rgb.txt')):\n        db = TUMStream(dataset_path, **kwargs)\n    \n    elif osp.isdir(osp.join(dataset_path, 'image_left')):\n        db = TartanStream(dataset_path, **kwargs)\n\n    stream = DataLoader(db, shuffle=False, batch_size=1, num_workers=4)\n    return stream\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/data_readers/nyu2.py",
    "content": "\nimport numpy as np\nimport torch\nimport glob\nimport cv2\nimport os\nimport os.path as osp\n\nfrom .base import RGBDDataset\nfrom .augmentation import RGBDAugmentor\nfrom .rgbd_utils import all_pairs_distance_matrix, loadtum\n\nclass NYUv2(RGBDDataset):\n    def __init__(self, **kwargs):\n        super(NYUv2, self).__init__(root='datasets/NYUv2', name='NYUv2', **kwargs)\n\n    @staticmethod \n    def is_test_scene(scene):\n        return False\n\n    def _build_dataset(self):\n\n        from tqdm import tqdm\n        print(\"Building NYUv2 dataset\")\n\n        scene_info = {}\n        dataset_index = []\n\n        scenes = os.listdir(self.root)\n        for scene in tqdm(scenes):\n            scene_path = osp.join(self.root, scene)\n            images, depths, poses, intrinsics = loadtum(scene_path, frame_rate=10)\n\n            # filter out some errors in dataset\n            if images is None or len(images) < 8:\n                continue\n\n            intrinsic = NYUv2.calib_read()\n            intrinsics = [intrinsic] * len(images)\n\n            # graph of co-visible frames based on flow\n            graph = self.build_frame_graph(poses, depths, intrinsics)\n\n            scene_info[scene] = {'images': images, 'depths': depths, \n                'poses': poses, 'intrinsics': intrinsics, 'graph': graph}\n\n        return scene_info\n\n    @staticmethod\n    def calib_read():\n        fx = 5.1885790117450188e+02\n        fy = 5.1946961112127485e+02\n        cx = 3.2558244941119034e+02\n        cy = 2.5373616633400465e+02\n        return np.array([fx, fy, cx, cy])\n\n    @staticmethod\n    def image_read(image_file):\n        return cv2.imread(image_file)\n\n    @staticmethod\n    def depth_read(depth_file):\n        depth = cv2.imread(depth_file, cv2.IMREAD_ANYDEPTH)\n        return depth.astype(np.float32) / 5000.0\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/data_readers/rgbd_utils.py",
    "content": "import numpy as np\nimport os.path as osp\n\nimport torch\nfrom lietorch import SE3\n\nimport geom.projective_ops as pops\nfrom scipy.spatial.transform import Rotation\n\n\ndef parse_list(filepath, skiprows=0):\n    \"\"\" read list data \"\"\"\n    data = np.loadtxt(filepath, delimiter=' ', dtype=np.unicode_, skiprows=skiprows)\n    return data\n\ndef associate_frames(tstamp_image, tstamp_depth, tstamp_pose, max_dt=0.08):\n    \"\"\" pair images, depths, and poses \"\"\"\n    associations = []\n    for i, t in enumerate(tstamp_image):\n        if tstamp_pose is None:\n            j = np.argmin(np.abs(tstamp_depth - t))\n            if (np.abs(tstamp_depth[j] - t) < max_dt):\n                associations.append((i, j))\n\n        else:\n            j = np.argmin(np.abs(tstamp_depth - t))\n            k = np.argmin(np.abs(tstamp_pose - t))\n        \n            if (np.abs(tstamp_depth[j] - t) < max_dt) and \\\n                    (np.abs(tstamp_pose[k] - t) < max_dt):\n                associations.append((i, j, k))\n            \n    return associations\n\ndef loadtum(datapath, frame_rate=-1):\n    \"\"\" read video data in tum-rgbd format \"\"\"\n    if osp.isfile(osp.join(datapath, 'groundtruth.txt')):\n        pose_list = osp.join(datapath, 'groundtruth.txt')\n    elif osp.isfile(osp.join(datapath, 'pose.txt')):\n        pose_list = osp.join(datapath, 'pose.txt')\n\n    image_list = osp.join(datapath, 'rgb.txt')\n    depth_list = osp.join(datapath, 'depth.txt')\n\n    calib_path = osp.join(datapath, 'calibration.txt')\n    intrinsic = None\n    if osp.isfile(calib_path):\n        intrinsic = np.loadtxt(calib_path, delimiter=' ')\n        intrinsic = intrinsic.astype(np.float64)\n\n    image_data = parse_list(image_list)\n    depth_data = parse_list(depth_list)\n    pose_data = parse_list(pose_list, skiprows=1)\n    pose_vecs = pose_data[:,1:].astype(np.float64)\n\n    tstamp_image = image_data[:,0].astype(np.float64)\n    tstamp_depth = depth_data[:,0].astype(np.float64)\n    tstamp_pose = pose_data[:,0].astype(np.float64)\n    associations = associate_frames(tstamp_image, tstamp_depth, tstamp_pose)\n\n    indicies = [ 0 ]\n    for i in range(1, len(associations)):\n        t0 = tstamp_image[associations[indicies[-1]][0]]\n        t1 = tstamp_image[associations[i][0]]\n        if t1 - t0 > 1.0 / frame_rate:\n            indicies += [ i ]\n\n    images, poses, depths, intrinsics = [], [], [], []\n    for ix in indicies:\n        (i, j, k) = associations[ix]\n        images += [ osp.join(datapath, image_data[i,1]) ]\n        depths += [ osp.join(datapath, depth_data[j,1]) ]\n        poses += [ pose_vecs[k] ]\n        \n        if intrinsic is not None:\n            intrinsics += [ intrinsic ]\n\n    return images, depths, poses, intrinsics\n\n\ndef all_pairs_distance_matrix(poses, beta=2.5):\n    \"\"\" compute distance matrix between all pairs of poses \"\"\"\n    poses = np.array(poses, dtype=np.float32)\n    poses[:,:3] *= beta # scale to balence rot + trans\n    poses = SE3(torch.from_numpy(poses))\n\n    r = (poses[:,None].inv() * poses[None,:]).log()\n    return r.norm(dim=-1).cpu().numpy()\n\ndef pose_matrix_to_quaternion(pose):\n    \"\"\" convert 4x4 pose matrix to (t, q) \"\"\"\n    q = Rotation.from_matrix(pose[:3, :3]).as_quat()\n    return np.concatenate([pose[:3, 3], q], axis=0)\n\ndef compute_distance_matrix_flow(poses, disps, intrinsics):\n    \"\"\" compute flow magnitude between all pairs of frames \"\"\"\n    if not isinstance(poses, SE3):\n        poses = torch.from_numpy(poses).float().cuda()[None]\n        poses = SE3(poses).inv()\n\n        disps = torch.from_numpy(disps).float().cuda()[None]\n        intrinsics = torch.from_numpy(intrinsics).float().cuda()[None]\n\n    N = poses.shape[1]\n    \n    ii, jj = torch.meshgrid(torch.arange(N), torch.arange(N))\n    ii = ii.reshape(-1).cuda()\n    jj = jj.reshape(-1).cuda()\n\n    MAX_FLOW = 100.0\n    matrix = np.zeros((N, N), dtype=np.float32)\n\n    s = 2048\n    for i in range(0, ii.shape[0], s):\n        flow1, val1 = pops.induced_flow(poses, disps, intrinsics, ii[i:i+s], jj[i:i+s])\n        flow2, val2 = pops.induced_flow(poses, disps, intrinsics, jj[i:i+s], ii[i:i+s])\n        \n        flow = torch.stack([flow1, flow2], dim=2)\n        val = torch.stack([val1, val2], dim=2)\n        \n        mag = flow.norm(dim=-1).clamp(max=MAX_FLOW)\n        mag = mag.view(mag.shape[1], -1)\n        val = val.view(val.shape[1], -1)\n\n        mag = (mag * val).mean(-1) / val.mean(-1)\n        mag[val.mean(-1) < 0.7] = np.inf\n\n        i1 = ii[i:i+s].cpu().numpy()\n        j1 = jj[i:i+s].cpu().numpy()\n        matrix[i1, j1] = mag.cpu().numpy()\n\n    return matrix\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/data_readers/scannet.py",
    "content": "\nimport numpy as np\nimport pickle\nimport torch\nimport glob\nimport cv2\nimport os\nimport os.path as osp\n\nfrom .base import RGBDDataset\nfrom .augmentation import RGBDAugmentor\nfrom .rgbd_utils import pose_matrix_to_quaternion\nfrom .rgbd_utils import  all_pairs_distance_matrix\n\n\nclass ScanNet(RGBDDataset):\n    def __init__(self, **kwargs):\n        super(ScanNet, self).__init__(root='datasets/ScanNet', name='ScanNet', **kwargs)\n\n    @staticmethod\n    def is_test_scene(scene):\n        scanid = int(re.findall(r'scene(.+?)_', scene)[0])\n        return scanid > 660\n\n    def _build_dataset_index(self):\n        \"\"\" construct scene_info and dataset_index objects \"\"\"\n\n        from tqdm import tqdm\n        print(\"Building ScanNet dataset\")\n\n        scene_info = {}\n        dataset_index = []\n\n        for scene in tqdm(os.listdir(self.root)):\n            scene_path = osp.join(self.root, scene)\n            depth_glob = osp.join(scene_path, 'depth', '*.png')\n            depth_list = glob.glob(depth_glob)\n\n            get_indicies = lambda x: int(osp.basename(x).split('.')[0])\n            get_images = lambda i: osp.join(scene_path, 'color', '%d.jpg' % i)\n            get_depths = lambda i: osp.join(scene_path, 'depth', '%d.png' % i)\n            get_poses = lambda i: osp.join(scene_path, 'pose', '%d.txt' % i)\n\n            indicies = sorted(map(get_indicies, depth_list))[::2]\n            image_list = list(map(get_images, indicies))\n            depth_list = list(map(get_depths, indicies))\n\n            pose_list = map(get_poses, indicies)\n            pose_list = list(map(ScanNet.pose_read, pose_list))\n\n            # remove nan poses\n            pvecs = np.stack(pose_list, 0)\n            keep, = np.where(~np.any(np.isnan(pvecs) | np.isinf(pvecs), axis=1))\n            images = [image_list[i] for i in keep]\n            depths = [depth_list[i] for i in keep]\n            poses = [pose_list[i] for i in keep]\n\n            intrinsic = ScanNet.calib_read(scene_path)\n            intrinsics = [intrinsic] * len(images)\n\n            graph = self.build_frame_graph(poses, depths, intrinsics)\n\n            scene_info[scene] = {'images': images, 'depths': depths, \n                'poses': poses, 'intrinsics': intrinsics, 'graph': graph}\n\n            for i in range(len(images)):\n                if len(graph[i][0]) > 1:\n                    dataset_index.append((scene, i))\n\n        return scene_info, dataset_index\n            \n    @staticmethod\n    def calib_read(scene_path):\n        intrinsic_file = osp.join(scene_path, 'intrinsic', 'intrinsic_depth.txt')\n        K = np.loadtxt(intrinsic_file, delimiter=' ')\n        return np.array([K[0,0], K[1,1], K[0,2], K[1,2]])\n\n    @staticmethod\n    def pose_read(pose_file):\n        pose = np.loadtxt(pose_file, delimiter=' ').astype(np.float64)\n        return pose_matrix_to_quaternion(pose)\n\n    @staticmethod\n    def image_read(image_file):\n        image = cv2.imread(image_file)\n        return cv2.resize(image, (640, 480))\n\n    @staticmethod\n    def depth_read(depth_file):\n        depth = cv2.imread(depth_file, cv2.IMREAD_ANYDEPTH)\n        return depth.astype(np.float32) / 1000.0"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/data_readers/stream.py",
    "content": "\nimport numpy as np\nimport torch\nimport torch.utils.data as data\nimport torch.nn.functional as F\n\nimport csv\nimport os\nimport cv2\nimport math\nimport random\nimport json\nimport pickle\nimport os.path as osp\n\nfrom .rgbd_utils import *\n\nclass RGBDStream(data.Dataset):\n    def __init__(self, datapath, frame_rate=-1, crop_size=[384,512]):\n        self.datapath = datapath\n        self.frame_rate = frame_rate\n        self.crop_size = crop_size\n        self._build_dataset_index()\n    \n    @staticmethod\n    def image_read(image_file):\n        return cv2.imread(image_file)\n\n    @staticmethod\n    def depth_read(depth_file):\n        return np.load(depth_file)\n\n    def __len__(self):\n        return len(self.images)\n\n    def __getitem__(self, index):\n        \"\"\" return training video \"\"\"\n        image = self.__class__.image_read(self.images[index])\n        image = torch.from_numpy(image).float()\n        image = image.permute(2, 0, 1)\n\n        depth = self.__class__.depth_read(self.depths[index])\n        depth = torch.from_numpy(depth).float()\n\n        pose = torch.from_numpy(self.poses[index]).float()\n        intrinsic = torch.from_numpy(self.intrinsics[index]).float()\n\n        sx = self.crop_size[1] / depth.shape[1]\n        sy = self.crop_size[0] / depth.shape[0]\n        image = F.interpolate(image[None], self.crop_size, mode='bilinear', align_corners=True)[0]\n        depth = F.interpolate(depth[None,None], self.crop_size, mode='nearest')[0,0]\n\n        image = image[..., 8:-8, 8:-8]\n        depth = depth[..., 8:-8, 8:-8]\n\n        fx, fy, cx, cy = intrinsic.unbind(dim=0)\n        intrinsic = torch.stack([sx*fx, sy*fy, sx*cx - 8, sy*cy - 8])\n\n        # intrinsic *= torch.as_tensor([sx, sy, sx, sy])\n        return index, image, depth, pose, intrinsic\n\n\n\n                "
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/data_readers/tartan.py",
    "content": "\nimport numpy as np\nimport torch\nimport glob\nimport cv2\nimport os\nimport os.path as osp\n\nfrom .base import RGBDDataset\nfrom .stream import RGBDStream\n\nclass TartanAir(RGBDDataset):\n\n    # scale depths to balance rot & trans\n    DEPTH_SCALE = 5.0\n    TEST_SET = ['westerndesert', 'seasidetown', 'seasonsforest_winter', 'office2', 'gascola']\n\n    def __init__(self, mode='training', **kwargs):\n        self.mode = mode\n        self.n_frames = 2\n        super(TartanAir, self).__init__(root='datasets/TartanAir', name='TartanAir', **kwargs)\n\n    @staticmethod\n    def is_test_scene(scene):\n        return scene.split('/')[-3] in TartanAir.TEST_SET\n\n    def _build_dataset(self):\n        from tqdm import tqdm\n        print(\"Building TartanAir dataset\")\n\n        scene_info = {}\n        scenes = glob.glob(osp.join(self.root, '*/*/*/*'))\n        for scene in tqdm(sorted(scenes)):\n            images = sorted(glob.glob(osp.join(scene, 'image_left/*.png')))\n            depths = sorted(glob.glob(osp.join(scene, 'depth_left/*.npy')))\n            \n            poses = np.loadtxt(osp.join(scene, 'pose_left.txt'), delimiter=' ')\n            poses = poses[:, [1, 2, 0, 4, 5, 3, 6]]\n            poses[:,:3] /= TartanAir.DEPTH_SCALE\n            intrinsics = [TartanAir.calib_read()] * len(images)\n\n            # graph of co-visible frames based on flow\n            graph = self.build_frame_graph(poses, depths, intrinsics)\n\n            scene = '/'.join(scene.split('/'))\n            scene_info[scene] = {'images': images, 'depths': depths, \n                'poses': poses, 'intrinsics': intrinsics, 'graph': graph}\n\n        return scene_info\n\n    @staticmethod\n    def calib_read():\n        return np.array([320.0, 320.0, 320.0, 240.0])\n\n    @staticmethod\n    def image_read(image_file):\n        return cv2.imread(image_file)\n\n    @staticmethod\n    def depth_read(depth_file):\n        depth = np.load(depth_file) / TartanAir.DEPTH_SCALE\n        depth[depth==np.nan] = 1.0\n        depth[depth==np.inf] = 1.0\n        return depth\n\n\nclass TartanAirTest(torch.utils.data.Dataset):\n    def __init__(self, root='datasets/Tartan'):\n        self.root = root\n        self.dataset_index = []\n\n        self.scene_info = {}\n        scenes = glob.glob(osp.join(self.root, '*/*/*/*'))\n        \n        for scene in sorted(scenes):\n            image_glob = osp.join(scene, 'image_left/*.png')\n            depth_glob = osp.join(scene, 'depth_left/*.npy')            \n            images = sorted(glob.glob(image_glob))\n            depths = sorted(glob.glob(depth_glob))\n\n            poses = np.loadtxt(osp.join(scene, 'pose_left.txt'), delimiter=' ')\n            poses = poses[:, [1, 2, 0, 4, 5, 3, 6]]\n            poses[:,:3] /= TartanAir.DEPTH_SCALE\n            intrinsics = [TartanAir.calib_read()] * len(images)\n            \n            self.scene_info[scene] = {'images': images, \n                'depths': depths, 'poses': poses, 'intrinsics': intrinsics}\n        \n        with open('assets/tartan_test.txt') as f:\n            self.dataset_index = f.readlines()\n        \n    def __getitem__(self, index):\n        \"\"\" load test example \"\"\"\n\n        scene_id, ix1, ix2 = self.dataset_index[index].split()\n        inds = [int(ix1), int(ix2)]\n\n        images_list = self.scene_info[scene_id]['images']\n        depths_list = self.scene_info[scene_id]['depths']\n        poses_list = self.scene_info[scene_id]['poses']\n        intrinsics_list = self.scene_info[scene_id]['intrinsics']\n\n        images, depths, poses, intrinsics = [], [], [], []\n        for i in inds:\n            images.append(TartanAir.image_read(images_list[i]))\n            depths.append(TartanAir.depth_read(depths_list[i]))\n            poses.append(poses_list[i])\n            intrinsics.append(intrinsics_list[i])\n\n        images = np.stack(images).astype(np.float32)\n        depths = np.stack(depths).astype(np.float32)\n        poses = np.stack(poses).astype(np.float32)\n        intrinsics = np.stack(intrinsics).astype(np.float32)\n\n        images = torch.from_numpy(images).float()\n        images = images.permute(0, 3, 1, 2)\n\n        depths = torch.from_numpy(depths)\n        poses = torch.from_numpy(poses)\n        intrinsics = torch.from_numpy(intrinsics)\n\n        return images, poses, depths, intrinsics \n\n    def __len__(self):\n        return len(self.dataset_index)\n\nclass TartanAirStream(RGBDStream):\n    def __init__(self, datapath, **kwargs):\n        super(TartanAirStream, self).__init__(datapath=datapath, **kwargs)\n\n    def _build_dataset_index(self):\n        \"\"\" build list of images, poses, depths, and intrinsics \"\"\"\n        images, poses, depths, intrinsics = loadtum(self.datapath)\n        intrinsic = NYUv2.TUMStream(self.datapath)\n        intrinsics = np.tile(intrinsic[None], (len(images), 1))\n\n        self.images = images\n        self.poses = poses\n        self.depths = depths\n        self.intrinsics = intrinsics\n\n    @staticmethod\n    def calib_read(datapath):\n        return np.array([320.0, 320.0, 320.0, 240.0])\n\n    @staticmethod\n    def image_read(image_file):\n        return cv2.imread(image_file)\n\n    @staticmethod\n    def depth_read(depth_file):\n        depth = cv2.imread(depth_file, cv2.IMREAD_ANYDEPTH)\n        return depth.astype(np.float32) / 5000.0\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/data_readers/tum.py",
    "content": "\nimport numpy as np\nimport torch\n\nimport csv\nimport os\nimport cv2\nimport math\nimport random\nimport json\nimport pickle\nimport os.path as osp\n\nfrom lietorch import SE3\nfrom .stream import RGBDStream\nfrom .rgbd_utils import loadtum\n\nintrinsics_dict = {\n    'freiburg1': [517.3, 516.5, 318.6, 255.3],\n    'freiburg2': [520.9, 521.0, 325.1, 249.7],\n    'freiburg3': [535.4, 539.2, 320.1, 247.6], \n}\n\ndistortion_dict = {\n    'freiburg1': [0.2624, -0.9531, -0.0054, 0.0026, 1.1633],\n    'freiburg2': [0.2312, -0.7849, -0.0033, -0.0001, 0.9172],\n    'freiburg3': [0, 0, 0, 0, 0],\n}\n\ndef as_intrinsics_matrix(intrinsics):\n    K = np.eye(3)\n    K[0,0] = intrinsics[0]\n    K[1,1] = intrinsics[1]\n    K[0,2] = intrinsics[2]\n    K[1,2] = intrinsics[3]\n    return K\n\n\nclass TUMStream(RGBDStream):\n    def __init__(self, datapath, **kwargs):\n        super(TUMStream, self).__init__(datapath=datapath, **kwargs)\n\n    def _build_dataset_index(self):\n        \"\"\" build list of images, poses, depths, and intrinsics \"\"\"\n        images, depths, poses, intrinsics = loadtum(self.datapath, self.frame_rate)\n        intrinsic, _ = TUMStream.calib_read(self.datapath)\n        intrinsics = np.tile(intrinsic[None], (len(images), 1))\n\n        # set first pose to identity\n        poses = SE3(torch.as_tensor(poses))\n        poses = poses[[0]].inv() * poses\n        poses = poses.data.cpu().numpy()\n\n        self.images = images\n        self.poses = poses\n        self.depths = depths\n        self.intrinsics = intrinsics\n\n    @staticmethod\n    def calib_read(datapath):\n        if 'freiburg1' in datapath:\n            intrinsic = intrinsics_dict['freiburg1']\n            d_coef = distortion_dict['freiburg1']\n\n        elif 'freiburg2' in datapath:\n            intrinsic = intrinsics_dict['freiburg2']\n            d_coef = distortion_dict['freiburg2']\n\n        elif 'freiburg3' in datapath:\n            intrinsic = intrinsics_dict['freiburg3']\n            d_coef = distortion_dict['freiburg3']\n\n        return np.array(intrinsic), np.array(d_coef)\n\n    @staticmethod\n    def image_read(image_file):\n        intrinsics, d_coef = TUMStream.calib_read(image_file)\n        K = as_intrinsics_matrix(intrinsics)\n        image = cv2.imread(image_file)\n        return cv2.undistort(image, K, d_coef)\n\n    @staticmethod\n    def depth_read(depth_file):\n        depth = cv2.imread(depth_file, cv2.IMREAD_ANYDEPTH)\n        return depth.astype(np.float32) / 5000.0\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/geom/__init__.py",
    "content": ""
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/geom/ba.py",
    "content": "import lietorch\nimport torch\nimport torch.nn.functional as F\n\nfrom .chol import block_solve\nimport geom.projective_ops as pops\n\n# utility functions for scattering ops\ndef safe_scatter_add_mat(H, data, ii, jj, B, M, D):\n    v = (ii >= 0) & (jj >= 0)\n    H.scatter_add_(1, (ii[v]*M + jj[v]).view(1,-1,1,1).repeat(B,1,D,D), data[:,v])\n\ndef safe_scatter_add_vec(b, data, ii, B, M, D):\n    v = ii >= 0\n    b.scatter_add_(1, ii[v].view(1,-1,1).repeat(B,1,D), data[:,v])\n\ndef MoBA(target, weight, poses, disps, intrinsics, ii, jj, fixedp=1, lm=0.0001, ep=0.1):\n    \"\"\" MoBA: Motion Only Bundle Adjustment \"\"\"\n\n    B, M = poses.shape[:2]\n    D = poses.manifold_dim\n    N = ii.shape[0]\n\n    ### 1: commpute jacobians and residuals ###\n    coords, valid, (Ji, Jj) = pops.projective_transform(\n        poses, disps, intrinsics, ii, jj, jacobian=True)\n\n    r = (target - coords).view(B, N, -1, 1)\n    w = (valid * weight).view(B, N, -1, 1)\n\n    ### 2: construct linear system ###\n    Ji = Ji.view(B, N, -1, D)\n    Jj = Jj.view(B, N, -1, D)\n    wJiT = (.001 * w * Ji).transpose(2,3)\n    wJjT = (.001 * w * Jj).transpose(2,3)\n\n    Hii = torch.matmul(wJiT, Ji)\n    Hij = torch.matmul(wJiT, Jj)\n    Hji = torch.matmul(wJjT, Ji)\n    Hjj = torch.matmul(wJjT, Jj)\n\n    vi = torch.matmul(wJiT, r).squeeze(-1)\n    vj = torch.matmul(wJjT, r).squeeze(-1)\n\n    # only optimize keyframe poses\n    M = M - fixedp\n    ii = ii - fixedp\n    jj = jj - fixedp\n\n    H = torch.zeros(B, M*M, D, D, device=target.device)\n    safe_scatter_add_mat(H, Hii, ii, ii, B, M, D)\n    safe_scatter_add_mat(H, Hij, ii, jj, B, M, D)\n    safe_scatter_add_mat(H, Hji, jj, ii, B, M, D)\n    safe_scatter_add_mat(H, Hjj, jj, jj, B, M, D)\n    H = H.reshape(B, M, M, D, D)\n\n    v = torch.zeros(B, M, D, device=target.device)\n    safe_scatter_add_vec(v, vi, ii, B, M, D)\n    safe_scatter_add_vec(v, vj, jj, B, M, D)\n\n    ### 3: solve the system + apply retraction ###\n    dx = block_solve(H, v, ep=ep, lm=lm)\n    \n    poses1, poses2 = poses[:,:fixedp], poses[:,fixedp:]\n    poses2 = poses2.retr(dx)\n    \n    poses = lietorch.cat([poses1, poses2], dim=1)\n    return poses\n\ndef SLessBA(target, weight, poses, disps, intrinsics, ii, jj, fixedp=1):\n    \"\"\" Structureless Bundle Adjustment \"\"\"\n    pass\n\n\ndef BA(target, weight, poses, disps, intrinsics, ii, jj, fixedp=1):\n    \"\"\" Full Bundle Adjustment \"\"\"\n    pass"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/geom/chol.py",
    "content": "import torch\nimport torch.nn.functional as F\nimport geom.projective_ops as pops\n\nclass CholeskySolver(torch.autograd.Function):\n    @staticmethod\n    def forward(ctx, H, b):\n        # don't crash training if cholesky decomp fails\n        try:\n            U = torch.cholesky(H)\n            xs = torch.cholesky_solve(b, U)\n            ctx.save_for_backward(U, xs)\n            ctx.failed = False\n        except Exception as e:\n            print(e)\n            ctx.failed = True\n            xs = torch.zeros_like(b)\n\n        return xs\n\n    @staticmethod\n    def backward(ctx, grad_x):\n        if ctx.failed:\n            return None, None\n\n        U, xs = ctx.saved_tensors\n        dz = torch.cholesky_solve(grad_x, U)\n        dH = -torch.matmul(xs, dz.transpose(-1,-2))\n\n        return dH, dz\n\ndef block_solve(H, b, ep=0.1, lm=0.0001):\n    \"\"\" solve normal equations \"\"\"\n    B, N, _, D, _ = H.shape\n    I = torch.eye(D).to(H.device)\n    H = H + (ep + lm*H) * I\n\n    H = H.permute(0,1,3,2,4)\n    H = H.reshape(B, N*D, N*D)\n    b = b.reshape(B, N*D, 1)\n\n    x = CholeskySolver.apply(H,b)\n    return x.reshape(B, N, D)"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/geom/graph_utils.py",
    "content": "\nimport torch\nimport numpy as np\nfrom collections import OrderedDict\n\nimport lietorch\nfrom data_readers.rgbd_utils import compute_distance_matrix_flow\n\n\ndef graph_to_edge_list(graph):\n    ii, jj, kk = [], [], []\n    for s, u in enumerate(graph):\n        for v in graph[u]:\n            ii.append(u)\n            jj.append(v)\n            kk.append(s)\n\n    ii = torch.as_tensor(ii).cuda()\n    jj = torch.as_tensor(jj).cuda()\n    kk = torch.as_tensor(kk).cuda()\n    return ii, jj, kk\n\ndef keyframe_indicies(graph):\n    return torch.as_tensor([u for u in graph]).cuda()\n\n\ndef meshgrid(m, n, device='cuda'):\n    ii, jj = torch.meshgrid(torch.arange(m), torch.arange(n))\n    return ii.reshape(-1).to(device), jj.reshape(-1).to(device)\n\n\nclass KeyframeGraph:\n    def __init__(self, images, poses, depths, intrinsics):\n        self.images = images.cpu()\n        self.depths = depths.cpu()\n        self.poses = poses\n        self.intrinsics = intrinsics\n\n        depths = depths[..., 3::8, 3::8].float().cuda()\n        disps = torch.where(depths>0.1, 1.0/depths, depths)\n\n        N = poses.shape[1]\n        d = compute_distance_matrix_flow(poses, disps, intrinsics / 8.0)\n\n        i, j = 0, 0\n        ixs = [ i ]\n\n        while j < N-1:\n            if d[i, j+1] > 7.5:\n                ixs += [ j ]\n                i = j\n            j += 1\n\n        # indicies of keyframes\n        self.distance_matrix = d[ixs][:,ixs]\n        self.ixs = np.array(ixs)\n        self.frame_graph = {}\n\n        for i in range(N):\n            k = np.argmin(np.abs(i - self.ixs))\n            j = self.ixs[k]\n            self.frame_graph[i] = (k, poses[:,i] * poses[:,j].inv())\n\n    def get_keyframes(self):\n        ix = torch.as_tensor(self.ixs).cuda()\n        return self.images[:,ix], self.poses[:,ix], self.depths[:,ix], self.intrinsics[:,ix]\n\n    def get_graph(self, num=-1, thresh=24.0, r=2):\n        d = self.distance_matrix.copy()\n        \n        N = d.shape[0]\n        if num < 0:\n            num = N\n\n        graph = OrderedDict()\n        for i in range(N):\n            graph[i] = [j for j in range(N) if i!=j and abs(i-j) <= 2]\n\n        for i in range(N):\n            for j in range(i-r, i+r+1):\n                if j >= 0 and j < N:\n                    d[i,j] = np.inf\n\n        for _ in range(num):\n            ix = np.argmin(d)\n            i, j = ix // N, ix % N\n\n            if d[i,j] < thresh:\n                graph[i].append(j)\n                for ii in range(i-r, i+r+1):\n                    for jj in range(j-r, j+r+1):\n                        if ii>=0 and jj>=0 and ii<N and jj<N:\n                            d[ii,jj] = np.inf\n            else:\n                break\n        \n        return graph\n\n    def get_poses(self, keyframe_poses):\n        \n        poses_list = []\n        for i in range(self.poses.shape[1]):\n            k, dP = self.frame_graph[i]\n            poses_list += [dP * keyframe_poses[:,k]]\n\n        return lietorch.stack(poses_list, 1)"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/geom/losses.py",
    "content": "import numpy as np\nimport torch\nfrom lietorch import SO3, SE3, Sim3\nfrom .graph_utils import graph_to_edge_list\n\ndef pose_metrics(dE):\n    \"\"\" Translation/Rotation/Scaling metrics from Sim3 \"\"\"\n    t, q, s = dE.data.split([3, 4, 1], -1)\n    ang = SO3(q).log().norm(dim=-1)\n\n    # convert radians to degrees\n    r_err = (180 / np.pi) * ang\n    t_err = t.norm(dim=-1)\n    s_err = (s - 1.0).abs()\n    return r_err, t_err, s_err\n\ndef geodesic_loss(Ps, Gs, graph, gamma=0.9):\n    \"\"\" Loss function for training network \"\"\"\n\n    # relative pose\n    ii, jj, kk = graph_to_edge_list(graph)\n    dP = Ps[:,jj] * Ps[:,ii].inv()\n\n    n = len(Gs)\n    geodesic_loss = 0.0\n\n    for i in range(n):\n        w = gamma ** (n - i - 1)\n        dG = Gs[i][:,jj] * Gs[i][:,ii].inv()\n        \n        # pose error\n        d = (dG * dP.inv()).log()\n\n        if isinstance(dG, SE3):\n            tau, phi = d.split([3,3], dim=-1)\n            geodesic_loss += w * (\n                tau.norm(dim=-1).mean() + \n                phi.norm(dim=-1).mean())\n\n        elif isinstance(dG, Sim3):\n            tau, phi, sig = d.split([3,3,1], dim=-1)\n            geodesic_loss += w * (\n                tau.norm(dim=-1).mean() + \n                phi.norm(dim=-1).mean() + \n                0.05 * sig.norm(dim=-1).mean())\n            \n        dE = Sim3(dG * dP.inv()).detach()\n        r_err, t_err, s_err = pose_metrics(dE)\n\n    metrics = {\n        'r_error': r_err.mean().item(),\n        't_error': t_err.mean().item(),\n        's_error': s_err.mean().item(),\n    }\n\n    return geodesic_loss, metrics\n\n\ndef residual_loss(residuals, gamma=0.9):\n    \"\"\" loss on system residuals \"\"\"\n    residual_loss = 0.0\n    n = len(residuals)\n\n    for i in range(n):\n        w = gamma ** (n - i - 1)\n        residual_loss += w * residuals[i].abs().mean()\n\n    return residual_loss, {'residual': residual_loss.item()}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/geom/projective_ops.py",
    "content": "import torch\nimport torch.nn.functional as F\n\nfrom lietorch import SE3, Sim3\n\nMIN_DEPTH = 0.1\n\ndef extract_intrinsics(intrinsics):\n    return intrinsics[...,None,None,:].unbind(dim=-1)\n\ndef iproj(disps, intrinsics):\n    \"\"\" pinhole camera inverse projection \"\"\"\n    ht, wd = disps.shape[2:]\n    fx, fy, cx, cy = extract_intrinsics(intrinsics)\n    \n    y, x = torch.meshgrid(\n        torch.arange(ht).to(disps.device).float(),\n        torch.arange(wd).to(disps.device).float())\n\n    i = torch.ones_like(disps)\n    X = (x - cx) / fx\n    Y = (y - cy) / fy\n    return torch.stack([X, Y, i, disps], dim=-1)\n\ndef proj(Xs, intrinsics, jacobian=False):\n    \"\"\" pinhole camera projection \"\"\"\n    fx, fy, cx, cy = extract_intrinsics(intrinsics)\n    X, Y, Z, D = Xs.unbind(dim=-1)\n    d = torch.where(Z.abs() < 0.001, torch.zeros_like(Z), 1.0/Z)\n\n    x = fx * (X * d) + cx\n    y = fy * (Y * d) + cy\n    coords = torch.stack([x,y, D*d], dim=-1)\n\n    if jacobian:\n        B, N, H, W = d.shape\n        o = torch.zeros_like(d)\n        proj_jac = torch.stack([\n             fx*d,     o, -fx*X*d*d,  o,\n                o,  fy*d, -fy*Y*d*d,  o,\n                o,     o,    -D*d*d,  d,\n        ], dim=-1).view(B, N, H, W, 3, 4)\n\n        return coords, proj_jac\n\n    return coords, None\n\ndef actp(Gij, X0, jacobian=False):\n    \"\"\" action on point cloud \"\"\"\n    X1 = Gij[:,:,None,None] * X0\n    \n    if jacobian:\n        X, Y, Z, d = X1.unbind(dim=-1)\n        o = torch.zeros_like(d)\n        B, N, H, W = d.shape\n\n        if isinstance(Gij, SE3):\n            Ja = torch.stack([\n                d,  o,  o,  o,  Z, -Y,\n                o,  d,  o, -Z,  o,  X, \n                o,  o,  d,  Y, -X,  o,\n                o,  o,  o,  o,  o,  o,\n            ], dim=-1).view(B, N, H, W, 4, 6)\n\n        elif isinstance(Gij, Sim3):\n            Ja = torch.stack([\n                d,  o,  o,  o,  Z, -Y,  X,\n                o,  d,  o, -Z,  o,  X,  Y,\n                o,  o,  d,  Y, -X,  o,  Z,\n                o,  o,  o,  o,  o,  o,  o\n            ], dim=-1).view(B, N, H, W, 4, 7)\n\n        return X1, Ja\n\n    return X1, None\n\ndef projective_transform(poses, depths, intrinsics, ii, jj, jacobian=False):\n    \"\"\" map points from ii->jj \"\"\"\n\n    # inverse project (pinhole)\n    X0 = iproj(depths[:,ii], intrinsics[:,ii])\n    \n    # transform\n    Gij = poses[:,jj] * poses[:,ii].inv()\n    X1, Ja = actp(Gij, X0, jacobian=jacobian)\n    \n    # project (pinhole)\n    x1, Jp = proj(X1, intrinsics[:,jj], jacobian=jacobian)\n\n    # exclude points too close to camera\n    valid = ((X1[...,2] > MIN_DEPTH) & (X0[...,2] > MIN_DEPTH)).float()\n    valid = valid.unsqueeze(-1)\n\n    if jacobian:\n        Jj = torch.matmul(Jp, Ja)\n        Ji = -Gij[:,:,None,None,None].adjT(Jj)\n        return x1, valid, (Ji, Jj)\n\n    return x1, valid\n\n\ndef induced_flow(poses, disps, intrinsics, ii, jj):\n    \"\"\" optical flow induced by camera motion \"\"\"\n\n    ht, wd = disps.shape[2:]\n    y, x = torch.meshgrid(\n        torch.arange(ht).to(disps.device).float(),\n        torch.arange(wd).to(disps.device).float())\n\n    coords0 = torch.stack([x, y], dim=-1)\n    coords1, valid = projective_transform(poses, disps, intrinsics, ii, jj)\n\n    return coords1[...,:2] - coords0, valid\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/geom/sampler_utils.py",
    "content": "import torch\nimport torch.nn.functional as F\n\ndef _bilinear_sampler(img, coords, mode='bilinear', mask=False):\n    \"\"\" Wrapper for grid_sample, uses pixel coordinates \"\"\"\n    H, W = img.shape[-2:]\n    xgrid, ygrid = coords.split([1,1], dim=-1)\n    xgrid = 2*xgrid/(W-1) - 1\n    ygrid = 2*ygrid/(H-1) - 1\n\n    grid = torch.cat([xgrid, ygrid], dim=-1)\n    img = F.grid_sample(img, grid, align_corners=True)\n\n    if mask:\n        mask = (xgrid > -1) & (ygrid > -1) & (xgrid < 1) & (ygrid < 1)\n        return img, mask.float()\n\n    return img\n\ndef bilinear_sampler(img, coords):\n    \"\"\" Wrapper for bilinear sampler for inputs with extra batch dimensions \"\"\"\n    unflatten = False\n    if len(img.shape) == 5:\n        unflatten = True\n        b, n, c, h, w = img.shape\n        img = img.view(b*n, c, h, w)\n        coords = coords.view(b*n, h, w, 2)\n\n    img1 = _bilinear_sampler(img, coords)\n    \n    if unflatten:\n        return img1.view(b, n, c, h, w)\n\n    return img1\n\ndef sample_depths(depths, coords):\n    batch, num, ht, wd = depths.shape\n    depths = depths.view(batch, num, 1, ht, wd)\n    coords = coords.view(batch, num, ht, wd, 2)\n    \n    depths_proj = bilinear_sampler(depths, coords)\n    return depths_proj.view(batch, num, ht, wd, 1)\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/logger.py",
    "content": "\nimport torch\nfrom torch.utils.tensorboard import SummaryWriter\n\n\nSUM_FREQ = 100\n\nclass Logger:\n    def __init__(self, name, scheduler):\n        self.total_steps = 0\n        self.running_loss = {}\n        self.writer = None\n        self.name = name\n        self.scheduler = scheduler\n\n    def _print_training_status(self):\n        if self.writer is None:\n            self.writer = SummaryWriter('runs/%s' % self.name)\n            print([k for k in self.running_loss])\n\n        lr = self.scheduler.get_lr().pop()\n        metrics_data = [self.running_loss[k]/SUM_FREQ for k in self.running_loss.keys()]\n        training_str = \"[{:6d}, {:10.7f}] \".format(self.total_steps+1, lr)\n        metrics_str = (\"{:10.4f}, \"*len(metrics_data)).format(*metrics_data)\n        \n        # print the training status\n        print(training_str + metrics_str)\n\n        for key in self.running_loss:\n            val = self.running_loss[key] / SUM_FREQ\n            self.writer.add_scalar(key, val, self.total_steps)\n            self.running_loss[key] = 0.0\n\n    def push(self, metrics):\n\n        for key in metrics:\n            if key not in self.running_loss:\n                self.running_loss[key] = 0.0\n\n            self.running_loss[key] += metrics[key]\n\n        if self.total_steps % SUM_FREQ == SUM_FREQ-1:\n            self._print_training_status()\n            self.running_loss = {}\n\n        self.total_steps += 1\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/networks/__init__.py",
    "content": ""
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/networks/modules/__init__.py",
    "content": ""
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/networks/modules/clipping.py",
    "content": "import torch\nimport torch.nn as nn\nimport torch.nn.functional as F\n\nGRAD_CLIP = .01\n\nclass GradClip(torch.autograd.Function):\n    @staticmethod\n    def forward(ctx, x):\n        return x\n\n    @staticmethod\n    def backward(ctx, grad_x):\n        o = torch.zeros_like(grad_x)\n        grad_x = torch.where(grad_x.abs()>GRAD_CLIP, o, grad_x)\n        grad_x = torch.where(torch.isnan(grad_x), o, grad_x)\n        return grad_x\n\nclass GradientClip(nn.Module):\n    def __init__(self):\n        super(GradientClip, self).__init__()\n\n    def forward(self, x):\n        return GradClip.apply(x)"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/networks/modules/corr.py",
    "content": "import torch\nimport torch.nn.functional as F\n\nfrom geom.sampler_utils import bilinear_sampler\nimport lietorch_extras\n\n\nclass CorrSampler(torch.autograd.Function):\n\n    @staticmethod\n    def forward(ctx, volume, coords, radius):\n        ctx.save_for_backward(volume,coords)\n        ctx.radius = radius\n        corr, = lietorch_extras.corr_index_forward(volume, coords, radius)\n        return corr\n\n    @staticmethod\n    def backward(ctx, grad_output):\n        volume, coords = ctx.saved_tensors\n        grad_output = grad_output.contiguous()\n        grad_volume, = lietorch_extras.corr_index_backward(volume, coords, grad_output, ctx.radius)\n        return grad_volume, None, None\n\n\nclass CorrBlock:\n    def __init__(self, fmap1, fmap2, num_levels=4, radius=4):\n        self.num_levels = num_levels\n        self.radius = radius\n        self.corr_pyramid = []\n\n        # all pairs correlation\n        corr = CorrBlock.corr(fmap1, fmap2)\n\n        batch, num, h1, w1, h2, w2 = corr.shape\n        corr = corr.reshape(batch*num*h1*w1, 1, h2, w2)\n        \n        for i in range(self.num_levels):\n            self.corr_pyramid.append(\n                corr.view(batch*num, h1, w1, h2//2**i, w2//2**i))\n            corr = F.avg_pool2d(corr, 2, stride=2)\n            \n    def __call__(self, coords):\n        out_pyramid = []\n        batch, num, ht, wd, _ = coords.shape\n        coords = coords.permute(0,1,4,2,3)\n        coords = coords.contiguous().view(batch*num, 2, ht, wd)\n        \n        for i in range(self.num_levels):\n            corr = CorrSampler.apply(self.corr_pyramid[i], coords/2**i, self.radius)\n            out_pyramid.append(corr.view(batch, num, -1, ht, wd))\n\n        return torch.cat(out_pyramid, dim=2)\n\n    def append(self, other):\n        for i in range(self.num_levels):\n            self.corr_pyramid[i] = torch.cat([self.corr_pyramid[i], other.corr_pyramid[i]], 0)\n\n    def remove(self, ix):\n        for i in range(self.num_levels):\n            self.corr_pyramid[i] = self.corr_pyramid[i][ix].contiguous()\n\n    @staticmethod\n    def corr(fmap1, fmap2):\n        \"\"\" all-pairs correlation \"\"\"\n        batch, num, dim, ht, wd = fmap1.shape\n        fmap1 = fmap1.reshape(batch*num, dim, ht*wd) / 4.0\n        fmap2 = fmap2.reshape(batch*num, dim, ht*wd) / 4.0\n        \n        corr = torch.matmul(fmap1.transpose(1,2), fmap2)\n        return corr.view(batch, num, ht, wd, ht, wd)\n\n\nclass CorrLayer(torch.autograd.Function):\n    @staticmethod\n    def forward(ctx, fmap1, fmap2, coords, r):\n        ctx.r = r\n        fmap1 = fmap1.contiguous()\n        fmap2 = fmap2.contiguous()\n        coords = coords.contiguous()\n        ctx.save_for_backward(fmap1, fmap2, coords)\n        corr, = lietorch_extras.altcorr_forward(fmap1, fmap2, coords, ctx.r)\n        return corr\n\n    @staticmethod\n    def backward(ctx, grad_corr):\n        fmap1, fmap2, coords = ctx.saved_tensors\n        grad_corr = grad_corr.contiguous()\n        fmap1_grad, fmap2_grad, coords_grad = \\\n            lietorch_extras.altcorr_backward(fmap1, fmap2, coords, grad_corr, ctx.r)\n        return fmap1_grad, fmap2_grad, coords_grad, None\n\n\n\nclass AltCorrBlock:\n    def __init__(self, fmaps, inds, num_levels=4, radius=3):\n        self.num_levels = num_levels\n        self.radius = radius\n        self.inds = inds\n\n        B, N, C, H, W = fmaps.shape\n        fmaps = fmaps.view(B*N, C, H, W)\n        \n        self.pyramid = []\n        for i in range(self.num_levels):\n            sz = (B, N, H//2**i, W//2**i, C)\n            fmap_lvl = fmaps.permute(0, 2, 3, 1)\n            self.pyramid.append(fmap_lvl.reshape(*sz))\n            fmaps = F.avg_pool2d(fmaps, 2, stride=2)\n  \n    def corr_fn(self, coords, ii, jj):\n        B, N, H, W, S, _ = coords.shape\n        coords = coords.permute(0, 1, 4, 2, 3, 5)\n\n        corr_list = []\n        for i in range(self.num_levels):\n            r = self.radius\n            fmap1_i = self.pyramid[0][:, ii]\n            fmap2_i = self.pyramid[i][:, jj]\n\n            coords_i = (coords / 2**i).reshape(B*N, S, H, W, 2).contiguous()\n            fmap1_i = fmap1_i.reshape((B*N,) + fmap1_i.shape[2:])\n            fmap2_i = fmap2_i.reshape((B*N,) + fmap2_i.shape[2:])\n\n            corr = CorrLayer.apply(fmap1_i, fmap2_i, coords_i, self.radius)\n            corr = corr.view(B, N, S, -1, H, W).permute(0, 1, 3, 4, 5, 2)\n            corr_list.append(corr)\n\n        corr = torch.cat(corr_list, dim=2)\n        return corr / 16.0\n\n\n    def __call__(self, coords, ii, jj):\n        squeeze_output = False\n        if len(coords.shape) == 5:\n            coords = coords.unsqueeze(dim=-2)\n            squeeze_output = True\n\n        corr = self.corr_fn(coords, ii, jj)\n        \n        if squeeze_output:\n            corr = corr.squeeze(dim=-1)\n\n        return corr.contiguous()\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/networks/modules/extractor.py",
    "content": "import torch\nimport torch.nn as nn\nimport torch.nn.functional as F\n\n\nclass ResidualBlock(nn.Module):\n    def __init__(self, in_planes, planes, norm_fn='group', stride=1):\n        super(ResidualBlock, self).__init__()\n  \n        self.conv1 = nn.Conv2d(in_planes, planes, kernel_size=3, padding=1, stride=stride)\n        self.conv2 = nn.Conv2d(planes, planes, kernel_size=3, padding=1)\n        self.relu = nn.ReLU(inplace=True)\n\n        num_groups = planes // 8\n\n        if norm_fn == 'group':\n            self.norm1 = nn.GroupNorm(num_groups=num_groups, num_channels=planes)\n            self.norm2 = nn.GroupNorm(num_groups=num_groups, num_channels=planes)\n            if not stride == 1:\n                self.norm3 = nn.GroupNorm(num_groups=num_groups, num_channels=planes)\n        \n        elif norm_fn == 'batch':\n            self.norm1 = nn.BatchNorm2d(planes)\n            self.norm2 = nn.BatchNorm2d(planes)\n            if not stride == 1:\n                self.norm3 = nn.BatchNorm2d(planes)\n        \n        elif norm_fn == 'instance':\n            self.norm1 = nn.InstanceNorm2d(planes)\n            self.norm2 = nn.InstanceNorm2d(planes)\n            if not stride == 1:\n                self.norm3 = nn.InstanceNorm2d(planes)\n\n        elif norm_fn == 'none':\n            self.norm1 = nn.Sequential()\n            self.norm2 = nn.Sequential()\n            if not stride == 1:\n                self.norm3 = nn.Sequential()\n\n        if stride == 1:\n            self.downsample = None\n        \n        else:    \n            self.downsample = nn.Sequential(\n                nn.Conv2d(in_planes, planes, kernel_size=1, stride=stride), self.norm3)\n\n    def forward(self, x):\n        y = x\n        y = self.relu(self.norm1(self.conv1(y)))\n        y = self.relu(self.norm2(self.conv2(y)))\n\n        if self.downsample is not None:\n            x = self.downsample(x)\n\n        return self.relu(x+y)\n\n\nclass BottleneckBlock(nn.Module):\n    def __init__(self, in_planes, planes, norm_fn='group', stride=1):\n        super(BottleneckBlock, self).__init__()\n  \n        self.conv1 = nn.Conv2d(in_planes, planes//4, kernel_size=1, padding=0)\n        self.conv2 = nn.Conv2d(planes//4, planes//4, kernel_size=3, padding=1, stride=stride)\n        self.conv3 = nn.Conv2d(planes//4, planes, kernel_size=1, padding=0)\n        self.relu = nn.ReLU(inplace=True)\n\n        num_groups = planes // 8\n\n        if norm_fn == 'group':\n            self.norm1 = nn.GroupNorm(num_groups=num_groups, num_channels=planes//4)\n            self.norm2 = nn.GroupNorm(num_groups=num_groups, num_channels=planes//4)\n            self.norm3 = nn.GroupNorm(num_groups=num_groups, num_channels=planes)\n            if not stride == 1:\n                self.norm4 = nn.GroupNorm(num_groups=num_groups, num_channels=planes)\n        \n        elif norm_fn == 'batch':\n            self.norm1 = nn.BatchNorm2d(planes//4)\n            self.norm2 = nn.BatchNorm2d(planes//4)\n            self.norm3 = nn.BatchNorm2d(planes)\n            if not stride == 1:\n                self.norm4 = nn.BatchNorm2d(planes)\n        \n        elif norm_fn == 'instance':\n            self.norm1 = nn.InstanceNorm2d(planes//4)\n            self.norm2 = nn.InstanceNorm2d(planes//4)\n            self.norm3 = nn.InstanceNorm2d(planes)\n            if not stride == 1:\n                self.norm4 = nn.InstanceNorm2d(planes)\n\n        elif norm_fn == 'none':\n            self.norm1 = nn.Sequential()\n            self.norm2 = nn.Sequential()\n            self.norm3 = nn.Sequential()\n            if not stride == 1:\n                self.norm4 = nn.Sequential()\n\n        if stride == 1:\n            self.downsample = None\n        \n        else:    \n            self.downsample = nn.Sequential(\n                nn.Conv2d(in_planes, planes, kernel_size=1, stride=stride), self.norm4)\n\n    def forward(self, x):\n        y = x\n        y = self.relu(self.norm1(self.conv1(y)))\n        y = self.relu(self.norm2(self.conv2(y)))\n        y = self.relu(self.norm3(self.conv3(y)))\n\n        if self.downsample is not None:\n            x = self.downsample(x)\n\n        return self.relu(x+y)\n\n\nDIM=32\n\nclass BasicEncoder(nn.Module):\n    def __init__(self, output_dim=128, norm_fn='batch', dropout=0.0, multidim=False):\n        super(BasicEncoder, self).__init__()\n        self.norm_fn = norm_fn\n        self.multidim = multidim\n\n        if self.norm_fn == 'group':\n            self.norm1 = nn.GroupNorm(num_groups=8, num_channels=DIM)\n            \n        elif self.norm_fn == 'batch':\n            self.norm1 = nn.BatchNorm2d(DIM)\n\n        elif self.norm_fn == 'instance':\n            self.norm1 = nn.InstanceNorm2d(DIM)\n\n        elif self.norm_fn == 'none':\n            self.norm1 = nn.Sequential()\n\n        self.conv1 = nn.Conv2d(3, DIM, kernel_size=7, stride=2, padding=3)\n        self.relu1 = nn.ReLU(inplace=True)\n\n        self.in_planes = DIM\n        self.layer1 = self._make_layer(DIM,  stride=1)\n        self.layer2 = self._make_layer(2*DIM, stride=2)\n        self.layer3 = self._make_layer(4*DIM, stride=2)\n\n        # output convolution\n        self.conv2 = nn.Conv2d(4*DIM, output_dim, kernel_size=1)\n\n        if self.multidim:\n            self.layer4 = self._make_layer(256, stride=2)\n            self.layer5 = self._make_layer(512, stride=2)\n\n            self.in_planes = 256\n            self.layer6 = self._make_layer(256, stride=1)\n\n            self.in_planes = 128\n            self.layer7 = self._make_layer(128, stride=1)\n\n            self.up1 = nn.Conv2d(512, 256, 1)\n            self.up2 = nn.Conv2d(256, 128, 1)\n            self.conv3 = nn.Conv2d(128, output_dim, kernel_size=1)\n\n        if dropout > 0:\n            self.dropout = nn.Dropout2d(p=dropout)\n        else:\n            self.dropout = None\n\n        for m in self.modules():\n            if isinstance(m, nn.Conv2d):\n                nn.init.kaiming_normal_(m.weight, mode='fan_out', nonlinearity='relu')\n            elif isinstance(m, (nn.BatchNorm2d, nn.InstanceNorm2d, nn.GroupNorm)):\n                if m.weight is not None:\n                    nn.init.constant_(m.weight, 1)\n                if m.bias is not None:\n                    nn.init.constant_(m.bias, 0)\n\n    def _make_layer(self, dim, stride=1):\n        layer1 = ResidualBlock(self.in_planes, dim, self.norm_fn, stride=stride)\n        layer2 = ResidualBlock(dim, dim, self.norm_fn, stride=1)\n        layers = (layer1, layer2)\n        \n        self.in_planes = dim\n        return nn.Sequential(*layers)\n\n    def forward(self, x):\n        b, n, c1, h1, w1 = x.shape\n        x = x.view(b*n, c1, h1, w1)\n\n        x = self.conv1(x)\n        x = self.norm1(x)\n        x = self.relu1(x)\n\n        x = self.layer1(x)\n        x = self.layer2(x)\n        x = self.layer3(x)\n\n        x = self.conv2(x)\n\n        _, c2, h2, w2 = x.shape\n        return x.view(b, n, c2, h2, w2)\n\n\n\nclass BasicEncoder16(nn.Module):\n    def __init__(self, output_dim=128, norm_fn='batch', dropout=0.0, multidim=False):\n        super(BasicEncoder16, self).__init__()\n        self.norm_fn = norm_fn\n        self.multidim = multidim\n\n        if self.norm_fn == 'group':\n            self.norm1 = nn.GroupNorm(num_groups=8, num_channels=DIM)\n            \n        elif self.norm_fn == 'batch':\n            self.norm1 = nn.BatchNorm2d(DIM)\n\n        elif self.norm_fn == 'instance':\n            self.norm1 = nn.InstanceNorm2d(DIM)\n\n        elif self.norm_fn == 'none':\n            self.norm1 = nn.Sequential()\n\n        self.conv1 = nn.Conv2d(3, DIM, kernel_size=7, stride=2, padding=3)\n        self.relu1 = nn.ReLU(inplace=True)\n\n        self.in_planes = DIM\n        self.layer1 = self._make_layer(DIM,  stride=1)\n        self.layer2 = self._make_layer(2*DIM, stride=2)\n        self.layer3 = self._make_layer(4*DIM, stride=2)\n        self.layer4 = self._make_layer(4*DIM, stride=2)\n\n\n        # output convolution\n        self.conv2 = nn.Conv2d(4*DIM, output_dim, kernel_size=1)\n\n        if dropout > 0:\n            self.dropout = nn.Dropout2d(p=dropout)\n        else:\n            self.dropout = None\n\n        for m in self.modules():\n            if isinstance(m, nn.Conv2d):\n                nn.init.kaiming_normal_(m.weight, mode='fan_out', nonlinearity='relu')\n            elif isinstance(m, (nn.BatchNorm2d, nn.InstanceNorm2d, nn.GroupNorm)):\n                if m.weight is not None:\n                    nn.init.constant_(m.weight, 1)\n                if m.bias is not None:\n                    nn.init.constant_(m.bias, 0)\n\n    def _make_layer(self, dim, stride=1):\n        layer1 = ResidualBlock(self.in_planes, dim, self.norm_fn, stride=stride)\n        layer2 = ResidualBlock(dim, dim, self.norm_fn, stride=1)\n        layers = (layer1, layer2)\n        \n        self.in_planes = dim\n        return nn.Sequential(*layers)\n\n    def forward(self, x):\n        b, n, c1, h1, w1 = x.shape\n        x = x.view(b*n, c1, h1, w1)\n\n        x = self.conv1(x)\n        x = self.norm1(x)\n        x = self.relu1(x)\n\n        x = self.layer1(x)\n        x = self.layer2(x)\n        x = self.layer3(x)\n        x = self.layer4(x)\n\n        x = self.conv2(x)\n\n        _, c2, h2, w2 = x.shape\n        return x.view(b, n, c2, h2, w2)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/networks/modules/gru.py",
    "content": "import torch\nimport torch.nn as nn\n\nclass ConvGRU(nn.Module):\n    def __init__(self, h_planes=128, i_planes=128):\n        super(ConvGRU, self).__init__()\n        self.do_checkpoint = False\n        self.convz = nn.Conv2d(h_planes+i_planes, h_planes, 3, padding=1)\n        self.convr = nn.Conv2d(h_planes+i_planes, h_planes, 3, padding=1)\n        self.convq = nn.Conv2d(h_planes+i_planes, h_planes, 3, padding=1)\n\n    def forward(self, net, *inputs):\n        inp = torch.cat(inputs, dim=1)\n        net_inp = torch.cat([net, inp], dim=1)\n\n        z = torch.sigmoid(self.convz(net_inp))\n        r = torch.sigmoid(self.convr(net_inp))\n        q = torch.tanh(self.convq(torch.cat([r*net, inp], dim=1)))\n\n        net = (1-z) * net + z * q\n        return net\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/networks/modules/unet.py",
    "content": "import torch\nimport torch.nn as nn\n\n# Unet model from https://github.com/usuyama/pytorch-unet\n\n\n\nGRAD_CLIP = .01\n\nclass GradClip(torch.autograd.Function):\n    @staticmethod\n    def forward(ctx, x):\n        return x\n\n    @staticmethod\n    def backward(ctx, grad_x):\n        o = torch.zeros_like(grad_x)\n        grad_x = torch.where(grad_x.abs()>GRAD_CLIP, o, grad_x)\n        grad_x = torch.where(torch.isnan(grad_x), o, grad_x)\n        return grad_x\n\n\ndef double_conv(in_channels, out_channels):\n    return nn.Sequential(\n        nn.Conv2d(in_channels, out_channels, 5, padding=2),\n        nn.ReLU(inplace=True),\n        nn.Conv2d(out_channels, out_channels, 5, padding=2),\n        nn.ReLU(inplace=True)\n    )\n\n\nclass UNet(nn.Module):\n\n    def __init__(self):\n        super().__init__()\n                \n        self.dconv_down1 = double_conv(128, 128)\n        self.dconv_down2 = double_conv(128, 256)\n        self.dconv_down3 = double_conv(256, 256)\n        # self.dconv_down4 = double_conv(256, 512)        \n\n        self.maxpool = nn.AvgPool2d(2)\n        self.upsample = nn.Upsample(scale_factor=2, mode='bilinear', align_corners=True)        \n        \n        self.dconv_up3 = double_conv(256 + 256, 256)\n        self.dconv_up2 = double_conv(256 + 256, 128)\n        self.dconv_up1 = double_conv(128 + 128, 128)\n\n        self.conv_r = nn.Conv2d(128, 3, 1)\n        self.conv_w = nn.Conv2d(128, 3, 1)\n\n\n    def forward(self, x):\n        b, n, c, ht, wd = x.shape\n        x = x.view(b*n, c, ht, wd)\n\n        conv1 = self.dconv_down1(x)\n        x = self.maxpool(conv1)\n\n        conv2 = self.dconv_down2(x)\n        x = self.maxpool(conv2)\n        \n        conv3 = self.dconv_down3(x)\n        x = torch.cat([x, conv3], dim=1)\n        \n        x = self.dconv_up3(x)\n        x = self.upsample(x)        \n        x = torch.cat([x, conv2], dim=1)       \n\n        x = self.dconv_up2(x)\n        x = self.upsample(x)        \n        x = torch.cat([x, conv1], dim=1)   \n        \n        x = self.dconv_up1(x)\n        r = self.conv_r(x)\n        w = self.conv_w(x)\n\n        w = torch.sigmoid(w)\n        w = w.view(b, n, 3, ht, wd).permute(0,1,3,4,2)\n        r = r.view(b, n, 3, ht, wd).permute(0,1,3,4,2)\n\n        # w = GradClip.apply(w)\n        # r = GradClip.apply(r)\n        return r, w"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/networks/rslam.py",
    "content": "import numpy as np\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom collections import OrderedDict\n\nfrom networks.modules.extractor import BasicEncoder\nfrom networks.modules.corr import CorrBlock\nfrom networks.modules.gru import ConvGRU\nfrom networks.modules.clipping import GradientClip\n\nfrom lietorch import SE3, Sim3\nfrom geom.ba import MoBA\n\nimport geom.projective_ops as pops\nfrom geom.sampler_utils import bilinear_sampler, sample_depths\nfrom geom.graph_utils import graph_to_edge_list, keyframe_indicies\n\n\nclass UpdateModule(nn.Module):\n    def __init__(self, args):\n        super(UpdateModule, self).__init__()\n        self.args = args\n\n        cor_planes = 4 * (2*3 + 1)**2 + 1\n\n        self.corr_encoder = nn.Sequential(\n            nn.Conv2d(cor_planes, 128, 1, padding=0),\n            nn.ReLU(inplace=True),\n            nn.Conv2d(128, 128, 3, padding=1),\n            nn.ReLU(inplace=True))\n\n        self.flow_encoder = nn.Sequential(\n            nn.Conv2d(3, 128, 7, padding=3),\n            nn.ReLU(inplace=True),\n            nn.Conv2d(128, 64, 3, padding=1),\n            nn.ReLU(inplace=True))\n\n        self.weight = nn.Sequential(\n            nn.Conv2d(128, 128, 3, padding=1),\n            nn.ReLU(inplace=True),\n            nn.Conv2d(128, 3, 3, padding=1),\n            GradientClip(),\n            nn.Sigmoid())\n\n        self.delta = nn.Sequential(\n            nn.Conv2d(128, 128, 3, padding=1),\n            nn.ReLU(inplace=True),\n            nn.Conv2d(128, 3, 3, padding=1),\n            GradientClip())\n\n        self.gru = ConvGRU(128, 128+128+64)\n\n    def forward(self, net, inp, corr, flow):\n        \"\"\" RaftSLAM update operator \"\"\"\n\n        batch, num, ch, ht, wd = net.shape\n        output_dim = (batch, num, -1, ht, wd)\n        net = net.view(batch*num, -1, ht, wd)\n        inp = inp.view(batch*num, -1, ht, wd)        \n        corr = corr.view(batch*num, -1, ht, wd)\n        flow = flow.view(batch*num, -1, ht, wd)\n\n        corr = self.corr_encoder(corr)\n        flow = self.flow_encoder(flow)\n        net = self.gru(net, inp, corr, flow)\n\n        ### update variables ###\n        delta = self.delta(net).view(*output_dim)\n        weight = self.weight(net).view(*output_dim)\n\n        delta = delta.permute(0,1,3,4,2).contiguous()\n        weight = weight.permute(0,1,3,4,2).contiguous()\n\n        net = net.view(*output_dim)\n        return net, delta, weight\n\n\nclass RaftSLAM(nn.Module):\n    def __init__(self, args):\n        super(RaftSLAM, self).__init__()\n        self.args = args\n        self.fnet = BasicEncoder(output_dim=128, norm_fn='instance')\n        self.cnet = BasicEncoder(output_dim=256, norm_fn='none')\n        self.update = UpdateModule(args)\n\n    def extract_features(self, images):\n        \"\"\" run feeature extraction networks \"\"\"\n        fmaps = self.fnet(images)\n        net = self.cnet(images)\n        \n        net, inp = net.split([128,128], dim=2)\n        net = torch.tanh(net)\n        inp = torch.relu(inp)\n        return fmaps, net, inp\n\n    def forward(self, Gs, images, depths, intrinsics, graph=None, num_steps=12):\n        \"\"\" Estimates SE3 or Sim3 between pair of frames \"\"\"\n\n        u = keyframe_indicies(graph)\n        ii, jj, kk = graph_to_edge_list(graph)\n\n        depths = depths[:, :, 3::8, 3::8]\n        intrinsics = intrinsics / 8\n        mask = (depths > 0.1).float()\n        disps = torch.where(depths>0.1, 1.0/depths, depths)\n\n        fmaps, net, inp = self.extract_features(images)\n        net, inp = net[:,ii], inp[:,ii]\n        corr_fn = CorrBlock(fmaps[:,ii], fmaps[:,jj], num_levels=4, radius=3)\n\n        coords, valid_mask = pops.projective_transform(Gs, disps, intrinsics, ii, jj)\n        residual = torch.zeros_like(coords[...,:2])\n\n        Gs_list, coords_list, residual_list = [], [], []\n        for step in range(num_steps):\n            Gs = Gs.detach()\n            coords = coords.detach()\n            residual = residual.detach()\n\n            corr = corr_fn(coords[...,:2])\n            flow = residual.permute(0,1,4,2,3).clamp(-32.0, 32.0)\n            \n            corr = torch.cat([corr, mask[:,ii,None]], dim=2)\n            flow = torch.cat([flow, mask[:,ii,None]], dim=2)\n            net, delta, weight = self.update(net, inp, corr, flow)\n\n            target = coords + delta\n            weight[...,2] = 0.0\n\n            for i in range(3):\n                Gs = MoBA(target, weight, Gs, disps, intrinsics, ii, jj)\n\n            coords, valid_mask = pops.projective_transform(Gs, disps, intrinsics, ii, jj)\n            residual = (target - coords)[...,:2]\n\n            Gs_list.append(Gs)\n            coords_list.append(target)\n\n            valid_mask = valid_mask * mask[:,ii].unsqueeze(-1)\n            residual_list.append(valid_mask * residual)\n\n        return Gs_list, residual_list\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/networks/sim3_net.py",
    "content": "import numpy as np\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom collections import OrderedDict\n\nfrom networks.modules.extractor import BasicEncoder\nfrom networks.modules.corr import CorrBlock\nfrom networks.modules.gru import ConvGRU\nfrom networks.modules.clipping import GradientClip\n\nfrom lietorch import SE3, Sim3\nfrom geom.ba import MoBA\n\nimport geom.projective_ops as pops\nfrom geom.sampler_utils import bilinear_sampler, sample_depths\nfrom geom.graph_utils import graph_to_edge_list, keyframe_indicies\n\n\nclass UpdateModule(nn.Module):\n    def __init__(self, args):\n        super(UpdateModule, self).__init__()\n        self.args = args\n\n        cor_planes = 4 * (2*3 + 1)**2\n\n        self.encoder = nn.Sequential(\n            nn.Conv2d(cor_planes, 128, 1, padding=0),\n            nn.ReLU(inplace=True),\n            nn.Conv2d(128, 128, 3, padding=1),\n            nn.ReLU(inplace=True),\n            nn.Conv2d(128, 128, 3, padding=1),\n            nn.ReLU(inplace=True))\n\n        self.weight = nn.Sequential(\n            nn.Conv2d(128, 128, 3, padding=1),\n            nn.ReLU(inplace=True),\n            nn.Conv2d(128, 3, 3, padding=1),\n            GradientClip(),\n            nn.Sigmoid())\n\n        self.delta = nn.Sequential(\n            nn.Conv2d(128, 128, 3, padding=1),\n            nn.ReLU(inplace=True),\n            nn.Conv2d(128, 3, 3, padding=1),\n            GradientClip())\n\n        self.gru = ConvGRU(128, 128+128+1)\n\n    def forward(self, net, inp, corr, dz):\n        \"\"\" update operator \"\"\"\n\n        batch, num, ch, ht, wd = net.shape\n        output_dim = (batch, num, -1, ht, wd)\n        net = net.view(batch*num, -1, ht, wd)\n        inp = inp.view(batch*num, -1, ht, wd)        \n\n        corr = corr.view(batch*num, -1, ht, wd)\n        dz = dz.view(batch*num, 1, ht, wd)\n        corr = self.encoder(corr)\n        net = self.gru(net, inp, corr, dz)\n\n        ### update variables ###\n        delta = self.delta(net).view(*output_dim)\n        weight = self.weight(net).view(*output_dim)\n\n        delta = delta.permute(0,1,3,4,2).contiguous()\n        weight = weight.permute(0,1,3,4,2).contiguous()\n\n        net = net.view(*output_dim)\n        return net, delta, weight\n\n\nclass Sim3Net(nn.Module):\n    def __init__(self, args):\n        super(Sim3Net, self).__init__()\n        self.args = args\n        self.fnet = BasicEncoder(output_dim=128, norm_fn='instance')\n        self.cnet = BasicEncoder(output_dim=256, norm_fn='none')\n        self.update = UpdateModule(args)\n\n    def extract_features(self, images):\n        \"\"\" run feeature extraction networks \"\"\"\n        fmaps = self.fnet(images)\n        net = self.cnet(images)\n        \n        net, inp = net.split([128,128], dim=2)\n        net = torch.tanh(net)\n        inp = torch.relu(inp)\n        return fmaps, net, inp\n\n    def forward(self, Gs, images, depths, intrinsics, graph=None, num_steps=12):\n        \"\"\" Estimates SE3 or Sim3 between pair of frames \"\"\"\n\n        if graph is None:\n            graph = OrderedDict()\n            graph[0] = [1]\n            graph[1] = [0]\n\n        u = keyframe_indicies(graph)\n        ii, jj, kk = graph_to_edge_list(graph)\n\n        # use inverse depth parameterization\n        depths = depths.clamp(min=0.1, max=1000.0)\n        disps = 1.0 / depths[:, :, 3::8, 3::8]\n        intrinsics = intrinsics / 8.0\n\n        fmaps, net, inp = self.extract_features(images)\n        corr_fn = CorrBlock(fmaps[:,ii], fmaps[:,jj], num_levels=4, radius=3)\n\n        Gs_list, coords_list, residual_list = [], [], []\n        for step in range(num_steps):\n            Gs = Gs.detach()\n            coords1_xyz, _ = pops.projective_transform(Gs, disps, intrinsics, ii, jj)\n\n            coords1, zinv_proj = coords1_xyz.split([2,1], dim=-1)\n            zinv = sample_depths(disps[:,jj], coords1)\n            dz = (zinv - zinv_proj).clamp(-1.0, 1.0)\n\n            corr = corr_fn(coords1)\n            net, delta, weight = self.update(net, inp, corr, dz)\n\n            target = coords1_xyz + delta\n            for i in range(3):\n                Gs = MoBA(target, weight, Gs, disps, intrinsics, ii, jj)\n\n            coords1_xyz, valid_mask = pops.projective_transform(Gs, disps, intrinsics, ii, jj)\n            residual = valid_mask * (target - coords1_xyz)\n\n            Gs_list.append(Gs)\n            coords_list.append(target)\n            residual_list.append(residual)\n\n        return Gs_list, residual_list\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/core/networks/slam_system.py",
    "content": "import numpy as np\nimport torch\nfrom collections import OrderedDict\nfrom torch.cuda.amp import autocast\n\nimport matplotlib.pyplot as plt\nimport lietorch\nfrom lietorch import SE3, Sim3\n\nfrom geom.ba import MoBA\nfrom .modules.corr import CorrBlock, AltCorrBlock\nfrom .rslam import RaftSLAM\n\nimport geom.projective_ops as pops\nfrom geom.sampler_utils import bilinear_sampler\nfrom geom.graph_utils import KeyframeGraph, graph_to_edge_list\n\ndef meshgrid(m, n, device='cuda'):\n    ii, jj = torch.meshgrid(torch.arange(m), torch.arange(n))\n    return ii.reshape(-1).to(device), jj.reshape(-1).to(device)\n\ndef normalize_images(images):\n    images = images[:, :, [2,1,0]]\n    mean = torch.as_tensor([0.485, 0.456, 0.406], device=images.device)\n    std = torch.as_tensor([0.229, 0.224, 0.225], device=images.device)\n    return (images/255.0).sub_(mean[:, None, None]).div_(std[:, None, None])\n\nclass FactorGraph:\n    def __init__(self, hidden=None, inputs=None, residu=None, ii=None, jj=None):\n        self.hidden = hidden\n        self.inputs = inputs\n        self.residu = residu\n        self.ii = ii\n        self.jj = jj\n\n    def __iadd__(self, other):\n        if self.hidden is None:\n            self.hidden = other.hidden\n            self.inputs = other.inputs\n            self.residu = other.residu\n            self.ii = other.ii\n            self.jj = other.jj\n        else:\n            self.hidden = torch.cat([self.hidden, other.hidden], 1)\n            self.inputs = torch.cat([self.inputs, other.inputs], 1)\n            self.residu = torch.cat([self.residu, other.residu], 1)\n            self.ii = torch.cat([self.ii, other.ii], 0)\n            self.jj = torch.cat([self.jj, other.jj], 0)\n\n        return self\n\n    def rm(self, keep):\n        self.hidden = self.hidden[:,keep]\n        self.inputs = self.inputs[:,keep]\n        self.residu = self.residu[:,keep]\n        self.ii = self.ii[keep]\n        self.jj = self.jj[keep]\n\n\nclass SLAMSystem(RaftSLAM):\n    def __init__(self, args):\n        super(SLAMSystem, self).__init__(args)\n        self.mem = 32\n        self.num_keyframes = 5\n\n        self.frontend = None\n        self.factors = FactorGraph()\n        self.count = 0\n        self.fixed_poses = 1\n\n        self.images_list = []\n        self.depths_list = []\n        self.intrinsics_list = []\n        \n    def initialize(self, ht, wd):\n        \"\"\" initialize slam buffers \"\"\"\n\n        self.ht, self.wd = ht, wd\n        ht, wd = ht // 8, wd // 8\n\n        self.fmaps = torch.zeros(1, self.mem, 128, ht, wd, device='cuda', dtype=torch.half)\n        self.nets = torch.zeros(1, self.mem, 128, ht, wd, device='cuda', dtype=torch.half)\n        self.inps = torch.zeros(1, self.mem, 128, ht, wd, device='cuda', dtype=torch.half)\n\n        self.poses = SE3.Identity(1, 2048, device='cuda')\n        self.disps = torch.ones(1, 2048, ht, wd, device='cuda')\n        self.intrinsics = torch.zeros(1, 2048, 4, device='cuda')\n        self.tstamps = torch.zeros(2048, dtype=torch.long)\n\n    def set_frontend(self, frontend):\n        self.frontend = frontend\n\n    def add_point_cloud(self, index, image, pose, depth, intrinsics, s=8):\n        \"\"\" add point cloud to visualization \"\"\"\n\n        if self.frontend is None:\n            return -1\n\n        image = image[...,s//2::s,s//2::s]\n        depth = depth[...,s//2::s,s//2::s]\n        intrinsics = intrinsics / s\n\n        # backproject\n        points = pops.iproj(1.0/depth[None], intrinsics[None])\n        points = points[...,:3] / points[...,[3]]\n        \n        points = points.reshape(-1, 3)\n        valid = (depth > 0).reshape(-1)\n        colors = image.reshape(3,-1).t() / 255.0\n        \n        point_data = points[valid].cpu().numpy()\n        color_data = colors[valid].cpu().numpy()\n        color_data = color_data[:, [2,1,0]]\n\n        pose_data = pose.inv()[0].data\n        self.frontend.update_pose(index, pose_data)\n        self.frontend.update_points(index, point_data, color_data)\n\n    def get_keyframes(self):\n        \"\"\" return keyframe poses and timestamps \"\"\"\n        return self.poses[0, :self.count], self.tstamps[:self.count]\n\n    def raw_poses(self):\n        return self.poses[0, :self.count].inv().data\n\n    def add_keyframe(self, tstamp, image, depth, intrinsics):\n        \"\"\" add keyframe to factor graph \"\"\"\n\n        if self.count == 0:\n            ht, wd = image.shape[3:]\n            self.initialize(ht, wd)\n\n        inputs = normalize_images(image)\n        with autocast(enabled=True):\n            fmaps, net, inp = self.extract_features(inputs)\n\n        ix = self.count % self.mem\n        self.fmaps[:, ix] = fmaps.squeeze(1)\n        self.nets[:, ix] = net.squeeze(1)\n        self.inps[:, ix] = inp.squeeze(1)\n\n        self.tstamps[self.count] = tstamp\n        self.intrinsics[:, self.count] = intrinsics / 8.0\n\n        disp = torch.where(depth > 0, 1.0/depth, depth)\n        self.disps[:, self.count] = disp[:,3::8,3::8]\n\n        pose = self.poses[:, self.count-1]\n        self.add_point_cloud(self.count, image, pose, depth, intrinsics)\n        self.count += 1\n        \n    def get_node_attributes(self, index):\n        index = index % self.mem\n        return self.fmaps[:, index], self.nets[:, index], self.inps[:, index]\n\n    def add_factors(self, ii, jj):\n        \"\"\" add factors to slam graph \"\"\"\n        fmaps, hidden, inputs = self.get_node_attributes(ii)\n        residu_shape = (1, ii.shape[0], self.ht//8, self.wd//8, 2)\n        residu = torch.zeros(*residu_shape).cuda()\n        self.factors += FactorGraph(hidden, inputs, residu, ii, jj)\n\n    def transform_project(self, ii, jj, **kwargs):\n        \"\"\" helper function, compute project transform \"\"\"\n        return pops.projective_transform(self.poses, self.disps, self.intrinsics, ii, jj, **kwargs)\n\n    def moba(self, num_steps=5, is_init=False):\n        \"\"\" motion only bundle adjustment \"\"\"\n\n        ii, jj = self.factors.ii, self.factors.jj\n        ixs = torch.cat([ii, jj], 0)\n\n        with autocast(enabled=True):\n            fmap1 = self.fmaps[:, ii % self.mem]\n            fmap2 = self.fmaps[:, jj % self.mem]\n            poses = self.poses[:, :jj.max()+1]\n\n            corr_fn = CorrBlock(fmap1, fmap2, num_levels=4, radius=3)\n            mask = (self.disps[:,ii] > 0.01).float()\n\n            with autocast(enabled=False):\n                coords, valid_mask = pops.projective_transform(poses, self.disps, self.intrinsics, ii, jj)\n\n            for i in range(num_steps):\n                corr = corr_fn(coords[...,:2])\n                corr = torch.cat([corr, mask[:,:,None]], dim=2)\n\n                with autocast(enabled=False):\n                    flow = self.factors.residu.permute(0,1,4,2,3).clamp(-32.0, 32.0)\n                    flow = torch.cat([flow, mask[:,:,None]], dim=2)\n                \n                self.factors.hidden, delta, weight = \\\n                    self.update(self.factors.hidden, self.factors.inputs, corr, flow)\n\n                with autocast(enabled=False):\n                    target = coords + delta\n                    weight[...,2] = 0.0\n\n                    for i in range(3):\n                        poses = MoBA(target, weight, poses, self.disps, \n                            self.intrinsics, ii, jj, self.fixed_poses)\n\n                    coords, valid_mask = pops.projective_transform(poses, self.disps, self.intrinsics, ii, jj)\n                    self.factors.residu = (target - coords)[...,:2]\n\n        self.poses[:, :jj.max()+1] = poses\n\n        # update visualization\n        if self.frontend is not None:\n            for ix in ixs.cpu().numpy():\n                self.frontend.update_pose(ix, self.poses[:,ix].inv()[0].data)\n\n\n    def track(self, tstamp, image, depth, intrinsics):\n        \"\"\" main thread \"\"\"\n\n        self.images_list.append(image)\n        self.depths_list.append(depth)\n        self.intrinsics_list.append(intrinsics)\n\n        # collect frames for initialization\n        if self.count < self.num_keyframes:\n            self.add_keyframe(tstamp, image, depth, intrinsics)\n\n            if self.count == self.num_keyframes:\n                ii, jj = meshgrid(self.num_keyframes, self.num_keyframes)\n                keep = ((ii - jj).abs() > 0) & (((ii - jj).abs() <= 3))\n\n                self.add_factors(ii[keep], jj[keep])\n                self.moba(num_steps=8, is_init=True)\n\n        else:\n            self.poses[:,self.count] = self.poses[:,self.count-1]\n            self.add_keyframe(tstamp, image, depth, intrinsics)\n\n            N = self.count\n            ii = torch.as_tensor([N-3, N-2, N-1, N-1, N-1], device='cuda')\n            jj = torch.as_tensor([N-1, N-1, N-2, N-3, N-4], device='cuda')\n            \n            self.add_factors(ii, jj)\n            self.moba(num_steps=4)\n\n            self.fixed_poses += 1\n            self.factors.rm(self.factors.ii + 2 >= self.fixed_poses)\n\n\n    def forward(self, poses, images, depths, intrinsics, num_steps=12):\n        \"\"\" Estimates SE3 or Sim3 between pair of frames \"\"\"\n\n        keyframe_graph = KeyframeGraph(images, poses, depths, intrinsics)\n        images, Gs, depths, intrinsics = keyframe_graph.get_keyframes()\n\n        images = images.cuda()\n        depths = depths.cuda()\n\n        if self.frontend is not None:\n            self.frontend.reset()\n            for i, ix in enumerate(keyframe_graph.ixs):\n                self.add_point_cloud(ix, images[:,i], Gs[:,i], depths[:,i], intrinsics[:,i], s=4)\n            for i in range(poses.shape[1]):\n                self.frontend.update_pose(i, poses[:,i].inv()[0].data)\n\n        graph = keyframe_graph.get_graph()\n        ii, jj, kk = graph_to_edge_list(graph)\n        ixs = torch.cat([ii, jj], 0)\n\n        images = normalize_images(images.cuda())\n        depths = depths[:, :, 3::8, 3::8].cuda()\n        mask = (depths > 0.1).float()\n        disps = torch.where(depths>0.1, 1.0/depths, depths)\n        intrinsics = intrinsics / 8\n\n        with autocast(True):\n\n            fmaps, net, inp = self.extract_features(images)\n            net = net[:,ii]\n            \n            # alternate corr implementation uses less memory but 4x slower\n            corr_fn = AltCorrBlock(fmaps.float(), (ii, jj), num_levels=4, radius=3)\n            # corr_fn = CorrBlock(fmaps[:,ii], fmaps[:,jj], num_levels=4, radius=3)\n\n            with autocast(False):\n                coords, valid_mask = pops.projective_transform(Gs, disps, intrinsics, ii, jj)\n                residual = torch.zeros_like(coords[...,:2])\n\n            for step in range(num_steps):\n                print(\"Global refinement iteration #{}\".format(step))                \n                net_list = []\n                targets_list = []\n                weights_list = []\n\n                s = 64\n                for i in range(0, ii.shape[0], s):\n                    ii1 = ii[i:i+s]\n                    jj1 = jj[i:i+s]\n\n                    corr1 = corr_fn(coords[:,i:i+s,:,:,:2], ii1, jj1)\n                    flow1 = residual[:, i:i+s].permute(0,1,4,2,3).clamp(-32.0, 32.0)\n                    \n                    corr1 = torch.cat([corr1, mask[:,ii1,None]], dim=2)\n                    flow1 = torch.cat([flow1, mask[:,ii1,None]], dim=2)\n\n                    net1, delta, weight = self.update(net[:,i:i+s], inp[:,ii1], corr1, flow1)\n                    net[:,i:i+s] = net1\n\n                    targets_list += [ coords[:,i:i+s] + delta.float() ]\n                    weights_list += [ weight.float() * torch.as_tensor([1.0, 1.0, 0.0]).cuda() ]\n\n                target = torch.cat(targets_list, 1)\n                weight = torch.cat(weights_list, 1)\n\n                with autocast(False):\n                    for i in range(3):\n                        Gs = MoBA(target, weight, Gs, disps, intrinsics, ii, jj, lm=0.00001, ep=.01)\n\n                    coords, valid_mask = pops.projective_transform(Gs, disps, intrinsics, ii, jj)\n                    residual = (target - coords)[...,:2]\n\n                poses = keyframe_graph.get_poses(Gs)\n                if self.frontend is not None:\n                    for i in range(poses.shape[1]):\n                        self.frontend.update_pose(i, poses[:,i].inv()[0].data)\n\n        return poses\n        \n    def global_refinement(self):\n        \"\"\" run global refinement \"\"\"\n\n        poses = self.poses[:, :self.count]\n        images = torch.cat(self.images_list, 1).cpu()\n        depths = torch.stack(self.depths_list, 1).cpu()\n        intrinsics = torch.stack(self.intrinsics_list, 1)\n\n        poses = self.forward(poses, images, depths, intrinsics, num_steps=16)\n        self.poses[:, :self.count] = poses\n\n\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/pgo/main.py",
    "content": "import torch\nfrom lietorch import SO3, SE3, LieGroupParameter\n\nimport argparse\nimport numpy as np\nimport time\nimport torch.optim as optim\nimport torch.nn.functional as F\n\n\ndef draw(verticies):\n    \"\"\" draw pose graph \"\"\"\n    import open3d as o3d\n\n    n = len(verticies)\n    points = np.array([x[1][:3] for x in verticies])\n    lines = np.stack([np.arange(0,n-1), np.arange(1,n)], 1)\n\n    line_set = o3d.geometry.LineSet(\n        points=o3d.utility.Vector3dVector(points),\n        lines=o3d.utility.Vector2iVector(lines),\n    )\n    o3d.visualization.draw_geometries([line_set])\n\ndef info2mat(info):\n    mat = np.zeros((6,6))\n    ix = 0\n    for i in range(mat.shape[0]):\n        mat[i,i:] = info[ix:ix+(6-i)]\n        mat[i:,i] = info[ix:ix+(6-i)]\n        ix += (6-i)\n\n    return mat\n\ndef read_g2o(fn):\n    verticies, edges = [], []\n    with open(fn) as f:\n        for line in f:\n            line = line.split()\n            if line[0] == 'VERTEX_SE3:QUAT':\n                v = int(line[1])\n                pose = np.array(line[2:], dtype=np.float32)\n                verticies.append([v, pose])\n\n            elif line[0] == 'EDGE_SE3:QUAT':\n                u = int(line[1])\n                v = int(line[2])\n                pose = np.array(line[3:10], dtype=np.float32)\n                info = np.array(line[10:], dtype=np.float32)\n\n                info = info2mat(info)\n                edges.append([u, v, pose, info, line])\n\n    return verticies, edges\n\ndef write_g2o(pose_graph, fn):\n    import csv\n    verticies, edges = pose_graph\n    with open(fn, 'w') as f:\n        writer = csv.writer(f, delimiter=' ')\n        for (v, pose) in verticies:\n            row = ['VERTEX_SE3:QUAT', v] + pose.tolist()\n            writer.writerow(row)\n        for edge in edges:\n            writer.writerow(edge[-1])\n\ndef reshaping_fn(dE, b=1.5):\n    \"\"\" Reshaping function from \"Intrinsic consensus on SO(3), Tron et al.\"\"\"\n    ang = dE.log().norm(dim=-1)\n    err = 1/b - (1/b + ang) * torch.exp(-b*ang)\n    return err.sum()\n\ndef gradient_initializer(pose_graph, n_steps=500, lr_init=0.2):\n    \"\"\" Riemannian Gradient Descent \"\"\"\n\n    verticies, edges = pose_graph\n\n    # edge indicies (ii, jj)\n    ii = np.array([x[0] for x in edges])\n    jj = np.array([x[1] for x in edges])\n    ii = torch.from_numpy(ii).cuda()\n    jj = torch.from_numpy(jj).cuda()\n\n    Eij = np.stack([x[2][3:] for x in edges])\n    Eij = SO3(torch.from_numpy(Eij).float().cuda())\n\n    R = np.stack([x[1][3:] for x in verticies])\n    R = SO3(torch.from_numpy(R).float().cuda())\n    R = LieGroupParameter(R)\n\n    # use gradient descent with momentum\n    optimizer = optim.SGD([R], lr=lr_init, momentum=0.5)\n\n    start = time.time()\n    for i in range(n_steps):\n        optimizer.zero_grad()\n\n        for param_group in optimizer.param_groups:\n            param_group['lr'] = lr_init * .995**i\n\n        # rotation error\n        dE = (R[ii].inv() * R[jj]) * Eij.inv()\n        loss = reshaping_fn(dE)\n\n        loss.backward()\n        optimizer.step()\n\n        if i%25 == 0:\n            print(i, lr_init * .995**i, loss.item())\n\n    # convert rotations to pose3\n    quats = R.group.data.detach().cpu().numpy()\n\n    for i in range(len(verticies)):\n        verticies[i][1][3:] = quats[i]\n\n    return verticies, edges\n\n\nif __name__ == '__main__':\n    parser = argparse.ArgumentParser()\n    parser.add_argument('--problem', help=\"input pose graph optimization file (.g2o format)\")\n    args = parser.parse_args()\n\n    output_path = args.problem.replace('.g2o', '_rotavg.g2o')\n    input_pose_graph = read_g2o(args.problem)\n\n    rot_pose_graph = gradient_initializer(input_pose_graph)\n    write_g2o(rot_pose_graph, output_path)\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/pgo/readme.md",
    "content": "## Pose Graph Optimization / Rotation Averaging\n\nPose Graph Optimization (PGO) is the problem of estimating the global trajectory from a set of relative pose measurements. PGO is typically performed using nonlinear least-squares algorithms (e.g Levenberg-Marquardt) and requires a good initialization in order to converge.\n\nIn this experiment, we implement Riemannian Gradient Descent with a reshaping function (Tron et al. 2012). The algorithm is implemented in the function `gradient_initializer` and runs on the GPU using lietorch.\n\n### Running on a .g2o file\n\nDownload a 3D problem from [datasets](https://lucacarlone.mit.edu/datasets/) (our implementation currently only supports uniform information matricies in Sphere-A, Torus, Cube, and Garage).\n\nThen run the `gradient_initializer` on the problem\n```python\npython main.py --problem=torus3D.g2o --steps=500\n```\n\nThe output graph, `torus3D_rotavg.g2o`, can then be used as the initialization for non-linear least squares optimizers such as `ceres`, `g2o`, and `gtsam`.\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/readme.md",
    "content": "# Examples\n\nInstructions for running demos and experiments can be found in each of the example directories\n1. [Pose Graph Optimization](pgo/readme.md) -> `pgo`\n1. [Sim3 Registration](registration/readme.md) -> `registration`\n1. [RGBD-SLAM](rgbdslam/readme.md) -> `rgbdslam`\n2. [RAFT-3D (SceneFlow)]()\n\n`core` contains networks, data loaders, and other common utility functions.\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/registration/assets/renderoption.json",
    "content": "{\n\t\"background_color\" : [ 1, 1, 1 ],\n\t\"class_name\" : \"RenderOption\",\n\t\"default_mesh_color\" : [ 0.69999999999999996, 0.69999999999999996, 0.69999999999999996 ],\n\t\"image_max_depth\" : 3000,\n\t\"image_stretch_option\" : 0,\n\t\"interpolation_option\" : 0,\n\t\"light0_color\" : [ 1, 1, 1 ],\n\t\"light0_diffuse_power\" : 0.66000000000000003,\n\t\"light0_position\" : [ 0, 0, 2 ],\n\t\"light0_specular_power\" : 0.20000000000000001,\n\t\"light0_specular_shininess\" : 100,\n\t\"light1_color\" : [ 1, 1, 1 ],\n\t\"light1_diffuse_power\" : 0.66000000000000003,\n\t\"light1_position\" : [ 0, 0, 2 ],\n\t\"light1_specular_power\" : 0.20000000000000001,\n\t\"light1_specular_shininess\" : 100,\n\t\"light2_color\" : [ 1, 1, 1 ],\n\t\"light2_diffuse_power\" : 0.66000000000000003,\n\t\"light2_position\" : [ 0, 0, -2 ],\n\t\"light2_specular_power\" : 0.20000000000000001,\n\t\"light2_specular_shininess\" : 100,\n\t\"light3_color\" : [ 1, 1, 1 ],\n\t\"light3_diffuse_power\" : 0.66000000000000003,\n\t\"light3_position\" : [ 0, 0, -2 ],\n\t\"light3_specular_power\" : 0.20000000000000001,\n\t\"light3_specular_shininess\" : 100,\n\t\"light_ambient_color\" : [ 0, 0, 0 ],\n\t\"light_on\" : true,\n\t\"mesh_color_option\" : 1,\n\t\"mesh_shade_option\" : 0,\n\t\"mesh_show_back_face\" : false,\n\t\"mesh_show_wireframe\" : false,\n\t\"point_color_option\" : 9,\n\t\"point_show_normal\" : false,\n\t\"point_size\" : 2,\n\t\"show_coordinate_frame\" : false,\n\t\"version_major\" : 1,\n\t\"version_minor\" : 0\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/registration/assets/tartan_test.txt",
    "content": "datasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 524 520\ndatasets/Tartan/office2/office2/Easy/P009 638 642\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 679 681\ndatasets/Tartan/gascola/gascola/Hard/P007 327 324\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 366 363\ndatasets/Tartan/office2/office2/Hard/P005 669 668\ndatasets/Tartan/office2/office2/Hard/P007 74 70\ndatasets/Tartan/gascola/gascola/Hard/P008 1042 1048\ndatasets/Tartan/gascola/gascola/Easy/P004 2941 2946\ndatasets/Tartan/office2/office2/Hard/P008 782 786\ndatasets/Tartan/gascola/gascola/Hard/P009 212 215\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P016 84 81\ndatasets/Tartan/office2/office2/Hard/P005 707 713\ndatasets/Tartan/gascola/gascola/Easy/P006 1842 1832\ndatasets/Tartan/gascola/gascola/Hard/P002 1390 1395\ndatasets/Tartan/seasidetown/seasidetown/Easy/P001 213 219\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 234 232\ndatasets/Tartan/gascola/gascola/Hard/P003 251 245\ndatasets/Tartan/gascola/gascola/Easy/P008 33 27\ndatasets/Tartan/gascola/gascola/Easy/P004 114 129\ndatasets/Tartan/seasidetown/seasidetown/Easy/P003 171 170\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 535 516\ndatasets/Tartan/office2/office2/Hard/P005 131 134\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 1032 1039\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 520 525\ndatasets/Tartan/seasidetown/seasidetown/Easy/P000 380 372\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 398 384\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 26 31\ndatasets/Tartan/office2/office2/Hard/P008 569 566\ndatasets/Tartan/office2/office2/Easy/P004 624 608\ndatasets/Tartan/gascola/gascola/Easy/P005 1304 1291\ndatasets/Tartan/gascola/gascola/Hard/P008 722 715\ndatasets/Tartan/gascola/gascola/Easy/P003 1375 1366\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 930 928\ndatasets/Tartan/gascola/gascola/Easy/P004 12 16\ndatasets/Tartan/gascola/gascola/Easy/P004 1872 1873\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 286 294\ndatasets/Tartan/westerndesert/westerndesert/Hard/P004 326 329\ndatasets/Tartan/gascola/gascola/Easy/P005 1219 1221\ndatasets/Tartan/office2/office2/Easy/P006 408 402\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 1251 1239\ndatasets/Tartan/westerndesert/westerndesert/Easy/P009 415 254\ndatasets/Tartan/westerndesert/westerndesert/Easy/P006 118 120\ndatasets/Tartan/gascola/gascola/Easy/P008 1171 1146\ndatasets/Tartan/westerndesert/westerndesert/Easy/P005 67 63\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 196 199\ndatasets/Tartan/gascola/gascola/Hard/P002 1366 1368\ndatasets/Tartan/gascola/gascola/Easy/P006 131 121\ndatasets/Tartan/seasidetown/seasidetown/Easy/P001 12 10\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 546 540\ndatasets/Tartan/gascola/gascola/Hard/P004 584 577\ndatasets/Tartan/gascola/gascola/Easy/P008 632 630\ndatasets/Tartan/gascola/gascola/Hard/P002 287 282\ndatasets/Tartan/office2/office2/Hard/P003 337 335\ndatasets/Tartan/westerndesert/westerndesert/Easy/P010 157 178\ndatasets/Tartan/gascola/gascola/Hard/P009 744 747\ndatasets/Tartan/seasidetown/seasidetown/Easy/P004 453 451\ndatasets/Tartan/gascola/gascola/Easy/P005 1116 1103\ndatasets/Tartan/gascola/gascola/Easy/P003 156 113\ndatasets/Tartan/office2/office2/Hard/P005 673 676\ndatasets/Tartan/westerndesert/westerndesert/Easy/P008 64 61\ndatasets/Tartan/westerndesert/westerndesert/Hard/P001 83 78\ndatasets/Tartan/office2/office2/Easy/P011 59 55\ndatasets/Tartan/seasidetown/seasidetown/Hard/P003 229 230\ndatasets/Tartan/westerndesert/westerndesert/Easy/P005 211 218\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 195 193\ndatasets/Tartan/gascola/gascola/Easy/P001 52 58\ndatasets/Tartan/seasidetown/seasidetown/Hard/P003 92 84\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P013 101 104\ndatasets/Tartan/westerndesert/westerndesert/Easy/P010 441 436\ndatasets/Tartan/gascola/gascola/Hard/P007 55 56\ndatasets/Tartan/office2/office2/Easy/P004 718 724\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 315 328\ndatasets/Tartan/office2/office2/Easy/P009 1201 1232\ndatasets/Tartan/gascola/gascola/Easy/P005 388 408\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 1117 1135\ndatasets/Tartan/gascola/gascola/Easy/P006 299 290\ndatasets/Tartan/gascola/gascola/Easy/P005 933 906\ndatasets/Tartan/office2/office2/Easy/P009 128 136\ndatasets/Tartan/westerndesert/westerndesert/Hard/P005 231 234\ndatasets/Tartan/gascola/gascola/Easy/P008 1413 1386\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P012 485 479\ndatasets/Tartan/gascola/gascola/Hard/P002 275 258\ndatasets/Tartan/office2/office2/Hard/P003 1378 1375\ndatasets/Tartan/gascola/gascola/Easy/P008 66 73\ndatasets/Tartan/office2/office2/Easy/P005 243 255\ndatasets/Tartan/gascola/gascola/Easy/P007 28 8\ndatasets/Tartan/office2/office2/Easy/P008 1470 1460\ndatasets/Tartan/office2/office2/Easy/P004 1060 1063\ndatasets/Tartan/office2/office2/Easy/P009 984 989\ndatasets/Tartan/office2/office2/Easy/P009 327 324\ndatasets/Tartan/office2/office2/Easy/P006 380 395\ndatasets/Tartan/gascola/gascola/Easy/P006 2501 2481\ndatasets/Tartan/gascola/gascola/Easy/P006 2338 2331\ndatasets/Tartan/gascola/gascola/Hard/P004 1144 1145\ndatasets/Tartan/gascola/gascola/Easy/P003 338 332\ndatasets/Tartan/westerndesert/westerndesert/Hard/P001 264 256\ndatasets/Tartan/office2/office2/Hard/P009 184 187\ndatasets/Tartan/westerndesert/westerndesert/Easy/P012 320 321\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 851 859\ndatasets/Tartan/gascola/gascola/Easy/P006 1233 1244\ndatasets/Tartan/office2/office2/Easy/P007 246 252\ndatasets/Tartan/westerndesert/westerndesert/Hard/P004 393 392\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 1431 1427\ndatasets/Tartan/gascola/gascola/Hard/P006 1017 1013\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 1374 1375\ndatasets/Tartan/gascola/gascola/Easy/P004 2911 2912\ndatasets/Tartan/office2/office2/Hard/P003 698 695\ndatasets/Tartan/office2/office2/Easy/P006 793 136\ndatasets/Tartan/gascola/gascola/Easy/P006 1735 1739\ndatasets/Tartan/gascola/gascola/Hard/P006 887 890\ndatasets/Tartan/gascola/gascola/Hard/P008 733 735\ndatasets/Tartan/gascola/gascola/Easy/P004 1545 1569\ndatasets/Tartan/gascola/gascola/Hard/P007 611 596\ndatasets/Tartan/gascola/gascola/Hard/P008 568 570\ndatasets/Tartan/westerndesert/westerndesert/Hard/P002 220 222\ndatasets/Tartan/gascola/gascola/Hard/P009 402 400\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 228 232\ndatasets/Tartan/westerndesert/westerndesert/Easy/P010 263 233\ndatasets/Tartan/gascola/gascola/Easy/P007 1656 1662\ndatasets/Tartan/gascola/gascola/Easy/P006 2591 2586\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 917 913\ndatasets/Tartan/westerndesert/westerndesert/Hard/P002 764 769\ndatasets/Tartan/gascola/gascola/Hard/P004 823 815\ndatasets/Tartan/gascola/gascola/Easy/P003 231 233\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 537 536\ndatasets/Tartan/gascola/gascola/Hard/P004 992 990\ndatasets/Tartan/gascola/gascola/Hard/P005 728 739\ndatasets/Tartan/office2/office2/Hard/P005 653 655\ndatasets/Tartan/office2/office2/Easy/P010 261 75\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P013 165 161\ndatasets/Tartan/office2/office2/Hard/P009 750 747\ndatasets/Tartan/gascola/gascola/Easy/P006 1724 1723\ndatasets/Tartan/westerndesert/westerndesert/Easy/P002 89 94\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 799 803\ndatasets/Tartan/gascola/gascola/Easy/P007 2167 2162\ndatasets/Tartan/westerndesert/westerndesert/Hard/P007 41 44\ndatasets/Tartan/westerndesert/westerndesert/Hard/P005 232 229\ndatasets/Tartan/westerndesert/westerndesert/Easy/P010 363 360\ndatasets/Tartan/office2/office2/Hard/P009 616 674\ndatasets/Tartan/gascola/gascola/Easy/P006 1760 1769\ndatasets/Tartan/office2/office2/Hard/P005 230 225\ndatasets/Tartan/westerndesert/westerndesert/Easy/P008 239 140\ndatasets/Tartan/office2/office2/Easy/P004 1552 1559\ndatasets/Tartan/office2/office2/Easy/P009 240 1074\ndatasets/Tartan/gascola/gascola/Hard/P006 1382 1378\ndatasets/Tartan/seasidetown/seasidetown/Easy/P009 828 824\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 895 891\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 608 612\ndatasets/Tartan/gascola/gascola/Hard/P005 135 142\ndatasets/Tartan/seasidetown/seasidetown/Hard/P003 129 175\ndatasets/Tartan/office2/office2/Easy/P003 509 516\ndatasets/Tartan/gascola/gascola/Easy/P005 498 487\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 554 552\ndatasets/Tartan/office2/office2/Easy/P009 282 293\ndatasets/Tartan/westerndesert/westerndesert/Easy/P011 92 175\ndatasets/Tartan/gascola/gascola/Easy/P006 947 949\ndatasets/Tartan/gascola/gascola/Hard/P004 258 252\ndatasets/Tartan/gascola/gascola/Easy/P004 1592 1590\ndatasets/Tartan/office2/office2/Easy/P003 90 91\ndatasets/Tartan/westerndesert/westerndesert/Hard/P003 157 156\ndatasets/Tartan/gascola/gascola/Easy/P004 2711 2713\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P012 202 200\ndatasets/Tartan/office2/office2/Easy/P009 1389 1390\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 696 698\ndatasets/Tartan/gascola/gascola/Hard/P006 1461 1460\ndatasets/Tartan/westerndesert/westerndesert/Hard/P005 48 44\ndatasets/Tartan/gascola/gascola/Hard/P004 240 242\ndatasets/Tartan/gascola/gascola/Easy/P006 475 480\ndatasets/Tartan/gascola/gascola/Easy/P008 913 907\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 483 490\ndatasets/Tartan/office2/office2/Hard/P010 373 371\ndatasets/Tartan/gascola/gascola/Easy/P008 719 715\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 858 859\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P016 212 228\ndatasets/Tartan/westerndesert/westerndesert/Easy/P009 288 300\ndatasets/Tartan/westerndesert/westerndesert/Hard/P005 150 155\ndatasets/Tartan/gascola/gascola/Easy/P006 53 51\ndatasets/Tartan/office2/office2/Easy/P009 284 286\ndatasets/Tartan/westerndesert/westerndesert/Easy/P010 76 82\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 253 244\ndatasets/Tartan/office2/office2/Easy/P008 1266 1259\ndatasets/Tartan/gascola/gascola/Hard/P005 579 582\ndatasets/Tartan/office2/office2/Hard/P007 299 293\ndatasets/Tartan/office2/office2/Hard/P005 355 360\ndatasets/Tartan/westerndesert/westerndesert/Hard/P003 183 181\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 172 169\ndatasets/Tartan/westerndesert/westerndesert/Hard/P007 289 288\ndatasets/Tartan/gascola/gascola/Easy/P004 1390 1395\ndatasets/Tartan/office2/office2/Easy/P006 524 528\ndatasets/Tartan/gascola/gascola/Hard/P007 14 19\ndatasets/Tartan/office2/office2/Hard/P003 430 437\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 616 626\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 123 129\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 818 816\ndatasets/Tartan/gascola/gascola/Hard/P004 422 416\ndatasets/Tartan/westerndesert/westerndesert/Easy/P009 304 264\ndatasets/Tartan/gascola/gascola/Hard/P002 323 337\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 280 284\ndatasets/Tartan/gascola/gascola/Easy/P006 1074 1066\ndatasets/Tartan/gascola/gascola/Hard/P002 672 673\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 1445 1448\ndatasets/Tartan/office2/office2/Hard/P009 786 791\ndatasets/Tartan/seasidetown/seasidetown/Easy/P000 499 507\ndatasets/Tartan/gascola/gascola/Hard/P008 820 824\ndatasets/Tartan/gascola/gascola/Easy/P007 386 374\ndatasets/Tartan/office2/office2/Hard/P010 58 62\ndatasets/Tartan/gascola/gascola/Easy/P004 1911 1908\ndatasets/Tartan/westerndesert/westerndesert/Easy/P009 249 242\ndatasets/Tartan/gascola/gascola/Hard/P004 193 176\ndatasets/Tartan/gascola/gascola/Easy/P001 315 307\ndatasets/Tartan/gascola/gascola/Easy/P003 1529 1534\ndatasets/Tartan/westerndesert/westerndesert/Hard/P005 290 295\ndatasets/Tartan/gascola/gascola/Hard/P002 643 652\ndatasets/Tartan/gascola/gascola/Hard/P001 58 62\ndatasets/Tartan/gascola/gascola/Hard/P002 436 445\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P013 476 477\ndatasets/Tartan/office2/office2/Hard/P003 710 705\ndatasets/Tartan/gascola/gascola/Hard/P007 278 275\ndatasets/Tartan/gascola/gascola/Easy/P004 2742 2721\ndatasets/Tartan/gascola/gascola/Hard/P009 676 684\ndatasets/Tartan/office2/office2/Easy/P010 178 210\ndatasets/Tartan/office2/office2/Easy/P009 924 923\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 222 215\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 218 219\ndatasets/Tartan/gascola/gascola/Hard/P008 607 611\ndatasets/Tartan/gascola/gascola/Hard/P008 691 684\ndatasets/Tartan/seasidetown/seasidetown/Easy/P001 288 292\ndatasets/Tartan/gascola/gascola/Hard/P001 179 173\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 152 142\ndatasets/Tartan/gascola/gascola/Easy/P004 2024 2020\ndatasets/Tartan/westerndesert/westerndesert/Easy/P008 258 108\ndatasets/Tartan/office2/office2/Easy/P000 127 125\ndatasets/Tartan/office2/office2/Hard/P003 468 472\ndatasets/Tartan/office2/office2/Hard/P010 9 7\ndatasets/Tartan/gascola/gascola/Hard/P008 138 145\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 377 360\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P014 441 442\ndatasets/Tartan/gascola/gascola/Hard/P005 508 498\ndatasets/Tartan/gascola/gascola/Easy/P007 711 708\ndatasets/Tartan/gascola/gascola/Easy/P004 1738 1735\ndatasets/Tartan/gascola/gascola/Hard/P005 130 126\ndatasets/Tartan/gascola/gascola/Easy/P008 5 7\ndatasets/Tartan/office2/office2/Easy/P006 525 539\ndatasets/Tartan/office2/office2/Hard/P005 8 13\ndatasets/Tartan/gascola/gascola/Hard/P004 914 918\ndatasets/Tartan/gascola/gascola/Hard/P002 313 308\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 197 195\ndatasets/Tartan/gascola/gascola/Hard/P006 125 113\ndatasets/Tartan/seasidetown/seasidetown/Easy/P009 367 390\ndatasets/Tartan/westerndesert/westerndesert/Easy/P009 214 218\ndatasets/Tartan/westerndesert/westerndesert/Hard/P001 296 298\ndatasets/Tartan/gascola/gascola/Easy/P004 2150 2145\ndatasets/Tartan/seasidetown/seasidetown/Easy/P001 36 43\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 1259 1257\ndatasets/Tartan/gascola/gascola/Easy/P004 2452 2470\ndatasets/Tartan/westerndesert/westerndesert/Easy/P008 57 58\ndatasets/Tartan/gascola/gascola/Easy/P006 1317 1312\ndatasets/Tartan/gascola/gascola/Hard/P009 464 462\ndatasets/Tartan/office2/office2/Easy/P003 221 228\ndatasets/Tartan/westerndesert/westerndesert/Hard/P002 319 321\ndatasets/Tartan/gascola/gascola/Hard/P000 234 239\ndatasets/Tartan/gascola/gascola/Easy/P005 764 762\ndatasets/Tartan/seasidetown/seasidetown/Easy/P001 368 365\ndatasets/Tartan/office2/office2/Hard/P009 11 24\ndatasets/Tartan/westerndesert/westerndesert/Hard/P002 312 306\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 18 15\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 505 508\ndatasets/Tartan/office2/office2/Hard/P003 799 792\ndatasets/Tartan/gascola/gascola/Hard/P008 1242 1240\ndatasets/Tartan/office2/office2/Easy/P009 1127 1117\ndatasets/Tartan/office2/office2/Easy/P004 66 76\ndatasets/Tartan/gascola/gascola/Hard/P005 738 751\ndatasets/Tartan/office2/office2/Easy/P008 1281 1289\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 161 165\ndatasets/Tartan/office2/office2/Hard/P010 299 298\ndatasets/Tartan/office2/office2/Easy/P004 1244 1250\ndatasets/Tartan/office2/office2/Easy/P004 1204 1208\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 697 698\ndatasets/Tartan/gascola/gascola/Easy/P006 2528 2532\ndatasets/Tartan/gascola/gascola/Easy/P007 334 313\ndatasets/Tartan/seasidetown/seasidetown/Hard/P001 135 127\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 59 67\ndatasets/Tartan/office2/office2/Easy/P007 84 77\ndatasets/Tartan/office2/office2/Easy/P006 903 895\ndatasets/Tartan/office2/office2/Easy/P009 969 971\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 598 606\ndatasets/Tartan/seasidetown/seasidetown/Easy/P001 90 67\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 464 459\ndatasets/Tartan/gascola/gascola/Easy/P006 214 207\ndatasets/Tartan/office2/office2/Easy/P004 287 290\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 832 834\ndatasets/Tartan/gascola/gascola/Easy/P004 1959 1965\ndatasets/Tartan/gascola/gascola/Easy/P005 912 936\ndatasets/Tartan/seasidetown/seasidetown/Easy/P009 181 180\ndatasets/Tartan/office2/office2/Hard/P008 664 668\ndatasets/Tartan/gascola/gascola/Hard/P004 910 905\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P014 81 84\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P016 148 145\ndatasets/Tartan/westerndesert/westerndesert/Hard/P002 810 802\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 3 2\ndatasets/Tartan/office2/office2/Hard/P008 343 339\ndatasets/Tartan/gascola/gascola/Easy/P005 1641 1639\ndatasets/Tartan/gascola/gascola/Easy/P008 1218 1223\ndatasets/Tartan/office2/office2/Easy/P006 850 852\ndatasets/Tartan/office2/office2/Hard/P004 152 149\ndatasets/Tartan/gascola/gascola/Hard/P004 131 140\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P012 583 599\ndatasets/Tartan/office2/office2/Hard/P003 496 493\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 799 810\ndatasets/Tartan/gascola/gascola/Hard/P004 791 798\ndatasets/Tartan/gascola/gascola/Hard/P008 811 813\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 401 403\ndatasets/Tartan/gascola/gascola/Hard/P002 1095 1056\ndatasets/Tartan/seasidetown/seasidetown/Easy/P002 235 269\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 1388 1391\ndatasets/Tartan/gascola/gascola/Easy/P007 1336 1338\ndatasets/Tartan/office2/office2/Easy/P004 1063 1055\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P013 272 271\ndatasets/Tartan/office2/office2/Hard/P003 1469 1471\ndatasets/Tartan/office2/office2/Hard/P004 182 184\ndatasets/Tartan/gascola/gascola/Hard/P008 1343 1342\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 280 282\ndatasets/Tartan/gascola/gascola/Hard/P006 1272 1270\ndatasets/Tartan/gascola/gascola/Easy/P004 2541 2539\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 214 217\ndatasets/Tartan/gascola/gascola/Easy/P006 1987 1995\ndatasets/Tartan/office2/office2/Easy/P000 260 262\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P012 600 592\ndatasets/Tartan/office2/office2/Hard/P003 340 344\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 1011 1028\ndatasets/Tartan/seasidetown/seasidetown/Hard/P001 68 55\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 522 511\ndatasets/Tartan/seasidetown/seasidetown/Easy/P004 198 196\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 625 615\ndatasets/Tartan/gascola/gascola/Hard/P003 250 236\ndatasets/Tartan/seasidetown/seasidetown/Easy/P009 768 769\ndatasets/Tartan/office2/office2/Easy/P011 16 17\ndatasets/Tartan/gascola/gascola/Hard/P004 343 348\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 568 566\ndatasets/Tartan/gascola/gascola/Easy/P004 607 603\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 793 792\ndatasets/Tartan/seasidetown/seasidetown/Hard/P001 105 115\ndatasets/Tartan/gascola/gascola/Easy/P007 642 636\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 840 842\ndatasets/Tartan/office2/office2/Hard/P003 79 80\ndatasets/Tartan/office2/office2/Hard/P010 275 273\ndatasets/Tartan/office2/office2/Hard/P002 26 25\ndatasets/Tartan/seasidetown/seasidetown/Hard/P000 107 104\ndatasets/Tartan/seasidetown/seasidetown/Easy/P001 284 279\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P013 117 119\ndatasets/Tartan/gascola/gascola/Easy/P001 360 365\ndatasets/Tartan/seasidetown/seasidetown/Easy/P009 742 743\ndatasets/Tartan/gascola/gascola/Easy/P005 671 673\ndatasets/Tartan/seasidetown/seasidetown/Hard/P000 127 130\ndatasets/Tartan/office2/office2/Easy/P011 529 540\ndatasets/Tartan/office2/office2/Hard/P003 1140 1136\ndatasets/Tartan/office2/office2/Easy/P011 186 204\ndatasets/Tartan/westerndesert/westerndesert/Hard/P002 675 660\ndatasets/Tartan/gascola/gascola/Hard/P009 367 371\ndatasets/Tartan/westerndesert/westerndesert/Easy/P006 126 125\ndatasets/Tartan/gascola/gascola/Easy/P007 643 636\ndatasets/Tartan/office2/office2/Hard/P005 563 573\ndatasets/Tartan/office2/office2/Hard/P008 273 279\ndatasets/Tartan/office2/office2/Hard/P002 125 123\ndatasets/Tartan/westerndesert/westerndesert/Easy/P006 248 232\ndatasets/Tartan/gascola/gascola/Hard/P008 1377 1376\ndatasets/Tartan/westerndesert/westerndesert/Easy/P011 52 53\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P012 383 377\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 209 212\ndatasets/Tartan/gascola/gascola/Hard/P002 720 715\ndatasets/Tartan/gascola/gascola/Hard/P004 57 60\ndatasets/Tartan/gascola/gascola/Easy/P008 1178 1182\ndatasets/Tartan/seasidetown/seasidetown/Easy/P000 332 370\ndatasets/Tartan/gascola/gascola/Hard/P006 916 922\ndatasets/Tartan/office2/office2/Hard/P001 312 302\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 1465 1467\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 84 85\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 46 53\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 811 813\ndatasets/Tartan/office2/office2/Easy/P005 319 310\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 1073 1065\ndatasets/Tartan/gascola/gascola/Hard/P002 892 893\ndatasets/Tartan/office2/office2/Easy/P008 309 306\ndatasets/Tartan/seasidetown/seasidetown/Easy/P001 287 291\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 844 838\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 36 39\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 65 58\ndatasets/Tartan/office2/office2/Hard/P009 546 544\ndatasets/Tartan/office2/office2/Easy/P008 779 774\ndatasets/Tartan/westerndesert/westerndesert/Hard/P002 613 610\ndatasets/Tartan/westerndesert/westerndesert/Easy/P006 317 323\ndatasets/Tartan/westerndesert/westerndesert/Hard/P006 296 295\ndatasets/Tartan/gascola/gascola/Hard/P003 198 203\ndatasets/Tartan/gascola/gascola/Easy/P006 823 820\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P012 570 567\ndatasets/Tartan/seasidetown/seasidetown/Hard/P003 125 187\ndatasets/Tartan/gascola/gascola/Hard/P006 462 485\ndatasets/Tartan/office2/office2/Easy/P009 793 890\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 658 651\ndatasets/Tartan/gascola/gascola/Hard/P004 1557 1551\ndatasets/Tartan/office2/office2/Easy/P004 1498 1499\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P012 52 53\ndatasets/Tartan/gascola/gascola/Easy/P006 468 480\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 862 859\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 1065 1062\ndatasets/Tartan/office2/office2/Easy/P004 187 193\ndatasets/Tartan/office2/office2/Hard/P005 445 451\ndatasets/Tartan/seasidetown/seasidetown/Easy/P001 21 22\ndatasets/Tartan/gascola/gascola/Hard/P002 685 692\ndatasets/Tartan/office2/office2/Hard/P006 78 75\ndatasets/Tartan/westerndesert/westerndesert/Easy/P010 139 141\ndatasets/Tartan/gascola/gascola/Easy/P005 1406 1409\ndatasets/Tartan/gascola/gascola/Hard/P005 318 313\ndatasets/Tartan/gascola/gascola/Hard/P002 1313 1369\ndatasets/Tartan/gascola/gascola/Easy/P004 1049 1051\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 452 448\ndatasets/Tartan/gascola/gascola/Hard/P003 415 412\ndatasets/Tartan/gascola/gascola/Easy/P007 1608 1594\ndatasets/Tartan/gascola/gascola/Hard/P005 526 524\ndatasets/Tartan/office2/office2/Hard/P005 68 64\ndatasets/Tartan/gascola/gascola/Hard/P002 706 712\ndatasets/Tartan/westerndesert/westerndesert/Hard/P001 207 199\ndatasets/Tartan/office2/office2/Easy/P003 489 492\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P016 256 240\ndatasets/Tartan/seasidetown/seasidetown/Easy/P000 39 46\ndatasets/Tartan/office2/office2/Hard/P005 747 733\ndatasets/Tartan/office2/office2/Hard/P008 396 387\ndatasets/Tartan/gascola/gascola/Hard/P006 1359 1362\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 316 313\ndatasets/Tartan/gascola/gascola/Hard/P003 193 183\ndatasets/Tartan/gascola/gascola/Easy/P005 1233 1234\ndatasets/Tartan/gascola/gascola/Easy/P005 876 879\ndatasets/Tartan/gascola/gascola/Easy/P005 238 234\ndatasets/Tartan/office2/office2/Hard/P000 116 62\ndatasets/Tartan/gascola/gascola/Hard/P001 308 307\ndatasets/Tartan/gascola/gascola/Hard/P004 925 924\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 346 351\ndatasets/Tartan/seasidetown/seasidetown/Hard/P000 302 301\ndatasets/Tartan/office2/office2/Hard/P001 30 31\ndatasets/Tartan/gascola/gascola/Hard/P005 724 722\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P012 644 646\ndatasets/Tartan/gascola/gascola/Hard/P008 288 286\ndatasets/Tartan/gascola/gascola/Easy/P008 399 398\ndatasets/Tartan/gascola/gascola/Hard/P007 329 342\ndatasets/Tartan/office2/office2/Easy/P011 460 469\ndatasets/Tartan/gascola/gascola/Hard/P005 1187 1165\ndatasets/Tartan/westerndesert/westerndesert/Easy/P008 62 60\ndatasets/Tartan/gascola/gascola/Hard/P009 659 662\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 221 231\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 297 300\ndatasets/Tartan/office2/office2/Hard/P001 277 276\ndatasets/Tartan/office2/office2/Easy/P011 101 99\ndatasets/Tartan/westerndesert/westerndesert/Hard/P007 7 9\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 694 693\ndatasets/Tartan/gascola/gascola/Easy/P006 2318 2325\ndatasets/Tartan/office2/office2/Easy/P000 6 4\ndatasets/Tartan/gascola/gascola/Hard/P003 328 218\ndatasets/Tartan/gascola/gascola/Easy/P003 1203 1198\ndatasets/Tartan/westerndesert/westerndesert/Easy/P005 354 355\ndatasets/Tartan/office2/office2/Easy/P005 116 113\ndatasets/Tartan/westerndesert/westerndesert/Easy/P007 193 183\ndatasets/Tartan/gascola/gascola/Hard/P008 328 331\ndatasets/Tartan/gascola/gascola/Hard/P004 120 115\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 319 316\ndatasets/Tartan/office2/office2/Hard/P010 18 20\ndatasets/Tartan/gascola/gascola/Hard/P004 298 290\ndatasets/Tartan/westerndesert/westerndesert/Easy/P011 210 97\ndatasets/Tartan/office2/office2/Easy/P004 3 0\ndatasets/Tartan/office2/office2/Easy/P004 1529 1535\ndatasets/Tartan/gascola/gascola/Easy/P004 1527 1534\ndatasets/Tartan/office2/office2/Hard/P003 748 751\ndatasets/Tartan/office2/office2/Hard/P006 326 323\ndatasets/Tartan/westerndesert/westerndesert/Hard/P003 143 148\ndatasets/Tartan/office2/office2/Hard/P001 167 182\ndatasets/Tartan/westerndesert/westerndesert/Easy/P007 144 145\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 75 83\ndatasets/Tartan/westerndesert/westerndesert/Easy/P007 125 123\ndatasets/Tartan/westerndesert/westerndesert/Easy/P006 453 456\ndatasets/Tartan/gascola/gascola/Easy/P007 381 372\ndatasets/Tartan/gascola/gascola/Easy/P004 1687 1686\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P014 387 386\ndatasets/Tartan/office2/office2/Easy/P009 1468 1453\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 584 582\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 115 103\ndatasets/Tartan/gascola/gascola/Easy/P005 859 864\ndatasets/Tartan/gascola/gascola/Hard/P006 741 745\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 1342 1320\ndatasets/Tartan/office2/office2/Hard/P002 544 542\ndatasets/Tartan/office2/office2/Hard/P007 56 57\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 773 778\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 420 429\ndatasets/Tartan/westerndesert/westerndesert/Easy/P005 264 254\ndatasets/Tartan/seasidetown/seasidetown/Easy/P002 206 203\ndatasets/Tartan/westerndesert/westerndesert/Easy/P005 122 123\ndatasets/Tartan/gascola/gascola/Hard/P008 338 340\ndatasets/Tartan/gascola/gascola/Easy/P007 516 511\ndatasets/Tartan/gascola/gascola/Easy/P003 125 119\ndatasets/Tartan/seasidetown/seasidetown/Hard/P003 104 100\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 473 481\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 562 569\ndatasets/Tartan/westerndesert/westerndesert/Easy/P011 195 85\ndatasets/Tartan/gascola/gascola/Easy/P004 2331 2328\ndatasets/Tartan/gascola/gascola/Hard/P008 1285 1282\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 16 21\ndatasets/Tartan/gascola/gascola/Hard/P009 284 280\ndatasets/Tartan/gascola/gascola/Hard/P008 1027 1012\ndatasets/Tartan/office2/office2/Easy/P005 496 493\ndatasets/Tartan/gascola/gascola/Easy/P007 143 140\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P013 363 359\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 147 148\ndatasets/Tartan/gascola/gascola/Easy/P003 498 501\ndatasets/Tartan/gascola/gascola/Easy/P006 1989 2002\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 17 26\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 47 60\ndatasets/Tartan/seasidetown/seasidetown/Easy/P001 93 64\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 537 543\ndatasets/Tartan/office2/office2/Easy/P005 196 194\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 167 168\ndatasets/Tartan/westerndesert/westerndesert/Hard/P006 110 117\ndatasets/Tartan/office2/office2/Hard/P003 667 669\ndatasets/Tartan/seasidetown/seasidetown/Hard/P001 221 218\ndatasets/Tartan/gascola/gascola/Easy/P006 2682 2649\ndatasets/Tartan/westerndesert/westerndesert/Hard/P005 355 367\ndatasets/Tartan/office2/office2/Easy/P009 1483 1487\ndatasets/Tartan/gascola/gascola/Easy/P004 2063 2069\ndatasets/Tartan/office2/office2/Hard/P002 472 477\ndatasets/Tartan/gascola/gascola/Hard/P006 411 418\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 560 559\ndatasets/Tartan/office2/office2/Easy/P009 805 802\ndatasets/Tartan/gascola/gascola/Hard/P008 641 632\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 288 276\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 549 546\ndatasets/Tartan/gascola/gascola/Hard/P003 170 172\ndatasets/Tartan/gascola/gascola/Easy/P004 1475 1477\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P014 269 273\ndatasets/Tartan/office2/office2/Easy/P009 1034 1045\ndatasets/Tartan/office2/office2/Hard/P003 763 772\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 552 546\ndatasets/Tartan/office2/office2/Easy/P011 658 654\ndatasets/Tartan/gascola/gascola/Hard/P008 1351 1350\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 281 270\ndatasets/Tartan/westerndesert/westerndesert/Easy/P007 139 140\ndatasets/Tartan/gascola/gascola/Hard/P009 618 626\ndatasets/Tartan/westerndesert/westerndesert/Easy/P010 206 203\ndatasets/Tartan/westerndesert/westerndesert/Easy/P009 570 581\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 823 821\ndatasets/Tartan/gascola/gascola/Hard/P006 1336 1338\ndatasets/Tartan/gascola/gascola/Hard/P003 406 398\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P015 138 136\ndatasets/Tartan/office2/office2/Easy/P004 1657 1668\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 287 289\ndatasets/Tartan/westerndesert/westerndesert/Hard/P004 303 291\ndatasets/Tartan/office2/office2/Easy/P008 1062 1059\ndatasets/Tartan/office2/office2/Hard/P002 347 344\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P015 335 333\ndatasets/Tartan/westerndesert/westerndesert/Easy/P008 284 304\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P015 85 86\ndatasets/Tartan/seasidetown/seasidetown/Easy/P002 134 126\ndatasets/Tartan/westerndesert/westerndesert/Easy/P009 170 154\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 254 252\ndatasets/Tartan/office2/office2/Hard/P009 859 856\ndatasets/Tartan/gascola/gascola/Easy/P003 629 623\ndatasets/Tartan/westerndesert/westerndesert/Hard/P004 300 294\ndatasets/Tartan/gascola/gascola/Hard/P002 1328 1337\ndatasets/Tartan/gascola/gascola/Easy/P007 317 331\ndatasets/Tartan/office2/office2/Hard/P010 142 135\ndatasets/Tartan/gascola/gascola/Easy/P007 151 153\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P016 105 100\ndatasets/Tartan/gascola/gascola/Easy/P004 1789 1787\ndatasets/Tartan/seasidetown/seasidetown/Hard/P001 8 6\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 430 427\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 392 402\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P016 265 257\ndatasets/Tartan/office2/office2/Hard/P008 766 758\ndatasets/Tartan/gascola/gascola/Hard/P006 493 496\ndatasets/Tartan/gascola/gascola/Easy/P003 1248 1252\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P013 67 52\ndatasets/Tartan/gascola/gascola/Hard/P007 323 325\ndatasets/Tartan/gascola/gascola/Easy/P004 2194 2192\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 449 447\ndatasets/Tartan/westerndesert/westerndesert/Hard/P004 175 184\ndatasets/Tartan/office2/office2/Easy/P010 1 4\ndatasets/Tartan/gascola/gascola/Easy/P003 979 1005\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P014 457 456\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 312 313\ndatasets/Tartan/seasidetown/seasidetown/Easy/P002 59 113\ndatasets/Tartan/gascola/gascola/Easy/P004 1736 1739\ndatasets/Tartan/westerndesert/westerndesert/Easy/P002 286 289\ndatasets/Tartan/westerndesert/westerndesert/Easy/P001 116 70\ndatasets/Tartan/gascola/gascola/Hard/P006 430 408\ndatasets/Tartan/gascola/gascola/Easy/P004 2876 2869\ndatasets/Tartan/seasidetown/seasidetown/Hard/P003 80 73\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P016 99 102\ndatasets/Tartan/office2/office2/Easy/P009 1506 1499\ndatasets/Tartan/westerndesert/westerndesert/Easy/P002 151 150\ndatasets/Tartan/gascola/gascola/Easy/P006 40 42\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 512 470\ndatasets/Tartan/office2/office2/Hard/P010 526 510\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 224 220\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 467 469\ndatasets/Tartan/gascola/gascola/Easy/P004 2427 2431\ndatasets/Tartan/gascola/gascola/Easy/P004 2157 2153\ndatasets/Tartan/gascola/gascola/Easy/P004 2765 2772\ndatasets/Tartan/seasidetown/seasidetown/Hard/P000 110 106\ndatasets/Tartan/gascola/gascola/Hard/P003 605 603\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 1359 1358\ndatasets/Tartan/gascola/gascola/Easy/P003 1089 1087\ndatasets/Tartan/gascola/gascola/Hard/P002 995 997\ndatasets/Tartan/gascola/gascola/Easy/P005 172 166\ndatasets/Tartan/gascola/gascola/Easy/P006 31 23\ndatasets/Tartan/office2/office2/Hard/P008 104 111\ndatasets/Tartan/westerndesert/westerndesert/Easy/P002 90 93\ndatasets/Tartan/gascola/gascola/Easy/P004 1225 1270\ndatasets/Tartan/office2/office2/Easy/P008 458 463\ndatasets/Tartan/gascola/gascola/Hard/P004 855 851\ndatasets/Tartan/seasidetown/seasidetown/Hard/P000 155 153\ndatasets/Tartan/gascola/gascola/Easy/P004 1228 1210\ndatasets/Tartan/gascola/gascola/Easy/P006 1325 1302\ndatasets/Tartan/westerndesert/westerndesert/Hard/P002 194 188\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 303 301\ndatasets/Tartan/seasidetown/seasidetown/Easy/P002 10 11\ndatasets/Tartan/seasidetown/seasidetown/Hard/P001 12 11\ndatasets/Tartan/gascola/gascola/Hard/P005 660 678\ndatasets/Tartan/seasidetown/seasidetown/Hard/P001 307 305\ndatasets/Tartan/office2/office2/Hard/P007 20 23\ndatasets/Tartan/gascola/gascola/Easy/P003 1343 1360\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P012 92 91\ndatasets/Tartan/gascola/gascola/Hard/P005 619 634\ndatasets/Tartan/gascola/gascola/Hard/P008 388 389\ndatasets/Tartan/gascola/gascola/Easy/P006 2633 2635\ndatasets/Tartan/gascola/gascola/Easy/P006 1119 1129\ndatasets/Tartan/gascola/gascola/Hard/P006 1337 1339\ndatasets/Tartan/gascola/gascola/Easy/P006 2634 2633\ndatasets/Tartan/gascola/gascola/Hard/P004 1381 1379\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 809 796\ndatasets/Tartan/gascola/gascola/Easy/P006 1201 1199\ndatasets/Tartan/office2/office2/Easy/P006 206 200\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 139 132\ndatasets/Tartan/office2/office2/Easy/P004 1617 1612\ndatasets/Tartan/seasidetown/seasidetown/Easy/P002 112 235\ndatasets/Tartan/westerndesert/westerndesert/Hard/P002 581 578\ndatasets/Tartan/gascola/gascola/Easy/P008 1416 1418\ndatasets/Tartan/gascola/gascola/Hard/P006 543 554\ndatasets/Tartan/gascola/gascola/Easy/P004 877 880\ndatasets/Tartan/gascola/gascola/Easy/P008 734 738\ndatasets/Tartan/gascola/gascola/Easy/P006 566 558\ndatasets/Tartan/gascola/gascola/Hard/P006 697 692\ndatasets/Tartan/gascola/gascola/Easy/P004 990 994\ndatasets/Tartan/office2/office2/Easy/P006 812 834\ndatasets/Tartan/gascola/gascola/Easy/P006 1698 1683\ndatasets/Tartan/gascola/gascola/Hard/P000 309 305\ndatasets/Tartan/office2/office2/Hard/P009 459 261\ndatasets/Tartan/westerndesert/westerndesert/Hard/P005 512 507\ndatasets/Tartan/gascola/gascola/Hard/P001 213 216\ndatasets/Tartan/office2/office2/Hard/P007 54 55\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P015 164 165\ndatasets/Tartan/gascola/gascola/Hard/P005 43 47\ndatasets/Tartan/office2/office2/Hard/P005 745 722\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 31 28\ndatasets/Tartan/gascola/gascola/Hard/P008 234 236\ndatasets/Tartan/gascola/gascola/Hard/P001 230 225\ndatasets/Tartan/office2/office2/Easy/P003 421 441\ndatasets/Tartan/office2/office2/Hard/P005 288 279\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 548 568\ndatasets/Tartan/office2/office2/Easy/P011 458 475\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P012 515 524\ndatasets/Tartan/office2/office2/Easy/P011 222 225\ndatasets/Tartan/westerndesert/westerndesert/Easy/P010 374 369\ndatasets/Tartan/gascola/gascola/Easy/P006 2254 2252\ndatasets/Tartan/gascola/gascola/Easy/P007 2387 2386\ndatasets/Tartan/gascola/gascola/Easy/P007 1696 1693\ndatasets/Tartan/gascola/gascola/Hard/P004 1368 1370\ndatasets/Tartan/gascola/gascola/Hard/P002 1207 1208\ndatasets/Tartan/westerndesert/westerndesert/Easy/P008 134 130\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 27 21\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 216 225\ndatasets/Tartan/gascola/gascola/Easy/P005 1540 1544\ndatasets/Tartan/gascola/gascola/Easy/P004 1455 1445\ndatasets/Tartan/seasidetown/seasidetown/Easy/P000 325 329\ndatasets/Tartan/gascola/gascola/Easy/P004 1206 1201\ndatasets/Tartan/office2/office2/Hard/P008 108 105\ndatasets/Tartan/gascola/gascola/Hard/P008 609 605\ndatasets/Tartan/gascola/gascola/Hard/P002 131 205\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 604 599\ndatasets/Tartan/westerndesert/westerndesert/Hard/P005 58 84\ndatasets/Tartan/gascola/gascola/Easy/P003 1465 1466\ndatasets/Tartan/gascola/gascola/Hard/P009 290 292\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 340 342\ndatasets/Tartan/office2/office2/Easy/P003 36 29\ndatasets/Tartan/gascola/gascola/Hard/P004 1288 1285\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 658 680\ndatasets/Tartan/gascola/gascola/Hard/P003 136 133\ndatasets/Tartan/gascola/gascola/Easy/P007 1676 1659\ndatasets/Tartan/office2/office2/Hard/P008 457 455\ndatasets/Tartan/westerndesert/westerndesert/Hard/P001 44 50\ndatasets/Tartan/gascola/gascola/Hard/P003 29 32\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 98 96\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 549 546\ndatasets/Tartan/gascola/gascola/Easy/P006 79 74\ndatasets/Tartan/gascola/gascola/Hard/P005 948 938\ndatasets/Tartan/gascola/gascola/Hard/P006 301 308\ndatasets/Tartan/office2/office2/Hard/P009 362 350\ndatasets/Tartan/gascola/gascola/Easy/P007 1735 1737\ndatasets/Tartan/gascola/gascola/Easy/P001 125 119\ndatasets/Tartan/gascola/gascola/Hard/P004 1211 1210\ndatasets/Tartan/gascola/gascola/Hard/P006 1463 1461\ndatasets/Tartan/gascola/gascola/Easy/P004 58 35\ndatasets/Tartan/gascola/gascola/Easy/P004 1552 1562\ndatasets/Tartan/gascola/gascola/Easy/P008 368 369\ndatasets/Tartan/office2/office2/Hard/P003 69 70\ndatasets/Tartan/office2/office2/Hard/P004 160 161\ndatasets/Tartan/seasidetown/seasidetown/Easy/P002 303 123\ndatasets/Tartan/office2/office2/Easy/P004 1676 1671\ndatasets/Tartan/gascola/gascola/Hard/P000 254 262\ndatasets/Tartan/gascola/gascola/Hard/P009 418 415\ndatasets/Tartan/office2/office2/Hard/P004 310 316\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 477 416\ndatasets/Tartan/gascola/gascola/Hard/P007 113 128\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 8 0\ndatasets/Tartan/gascola/gascola/Hard/P002 104 119\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 948 949\ndatasets/Tartan/office2/office2/Hard/P008 419 432\ndatasets/Tartan/gascola/gascola/Easy/P007 2234 2237\ndatasets/Tartan/office2/office2/Easy/P005 190 188\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P015 10 5\ndatasets/Tartan/office2/office2/Easy/P010 68 53\ndatasets/Tartan/gascola/gascola/Easy/P003 188 184\ndatasets/Tartan/gascola/gascola/Easy/P003 550 556\ndatasets/Tartan/gascola/gascola/Easy/P005 946 941\ndatasets/Tartan/gascola/gascola/Hard/P008 978 955\ndatasets/Tartan/gascola/gascola/Easy/P001 340 338\ndatasets/Tartan/office2/office2/Hard/P010 509 516\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 67 65\ndatasets/Tartan/gascola/gascola/Hard/P003 601 602\ndatasets/Tartan/office2/office2/Hard/P008 145 147\ndatasets/Tartan/gascola/gascola/Easy/P004 2346 2345\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 457 461\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 607 609\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 369 376\ndatasets/Tartan/office2/office2/Easy/P010 85 92\ndatasets/Tartan/office2/office2/Easy/P009 1319 1321\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 278 270\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 69 50\ndatasets/Tartan/gascola/gascola/Easy/P006 1438 1416\ndatasets/Tartan/westerndesert/westerndesert/Hard/P005 562 561\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 162 164\ndatasets/Tartan/gascola/gascola/Hard/P007 487 486\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 251 253\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 1029 1041\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 88 89\ndatasets/Tartan/gascola/gascola/Easy/P003 1117 1118\ndatasets/Tartan/office2/office2/Easy/P006 99 90\ndatasets/Tartan/gascola/gascola/Easy/P005 1097 1107\ndatasets/Tartan/office2/office2/Easy/P006 448 453\ndatasets/Tartan/office2/office2/Hard/P005 961 945\ndatasets/Tartan/gascola/gascola/Easy/P004 2169 2167\ndatasets/Tartan/seasidetown/seasidetown/Easy/P009 36 39\ndatasets/Tartan/gascola/gascola/Easy/P007 1777 1779\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 456 453\ndatasets/Tartan/gascola/gascola/Easy/P003 1006 977\ndatasets/Tartan/westerndesert/westerndesert/Hard/P001 242 269\ndatasets/Tartan/gascola/gascola/Hard/P004 287 281\ndatasets/Tartan/gascola/gascola/Easy/P003 1457 1445\ndatasets/Tartan/westerndesert/westerndesert/Hard/P005 443 454\ndatasets/Tartan/gascola/gascola/Easy/P006 1676 1678\ndatasets/Tartan/gascola/gascola/Hard/P005 3 0\ndatasets/Tartan/westerndesert/westerndesert/Easy/P001 132 80\ndatasets/Tartan/westerndesert/westerndesert/Easy/P010 320 312\ndatasets/Tartan/westerndesert/westerndesert/Easy/P007 153 156\ndatasets/Tartan/gascola/gascola/Hard/P006 1197 1204\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 574 571\ndatasets/Tartan/gascola/gascola/Easy/P005 224 207\ndatasets/Tartan/gascola/gascola/Hard/P008 1150 1143\ndatasets/Tartan/office2/office2/Easy/P011 524 515\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 703 698\ndatasets/Tartan/gascola/gascola/Easy/P007 1687 1685\ndatasets/Tartan/office2/office2/Hard/P008 669 666\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 351 344\ndatasets/Tartan/office2/office2/Hard/P001 184 181\ndatasets/Tartan/office2/office2/Easy/P008 113 102\ndatasets/Tartan/gascola/gascola/Easy/P003 551 548\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 411 407\ndatasets/Tartan/gascola/gascola/Hard/P009 275 276\ndatasets/Tartan/gascola/gascola/Hard/P004 83 74\ndatasets/Tartan/westerndesert/westerndesert/Hard/P007 40 35\ndatasets/Tartan/westerndesert/westerndesert/Easy/P007 411 414\ndatasets/Tartan/gascola/gascola/Hard/P002 165 151\ndatasets/Tartan/office2/office2/Easy/P004 543 547\ndatasets/Tartan/westerndesert/westerndesert/Hard/P004 290 297\ndatasets/Tartan/office2/office2/Hard/P008 128 131\ndatasets/Tartan/gascola/gascola/Easy/P006 805 807\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 140 185\ndatasets/Tartan/gascola/gascola/Hard/P004 770 783\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P012 358 360\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 258 259\ndatasets/Tartan/gascola/gascola/Hard/P006 639 630\ndatasets/Tartan/office2/office2/Hard/P007 210 208\ndatasets/Tartan/office2/office2/Easy/P004 1401 1409\ndatasets/Tartan/gascola/gascola/Hard/P006 1146 1140\ndatasets/Tartan/westerndesert/westerndesert/Hard/P005 272 271\ndatasets/Tartan/westerndesert/westerndesert/Hard/P003 391 389\ndatasets/Tartan/seasidetown/seasidetown/Easy/P000 263 264\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P014 13 10\ndatasets/Tartan/seasidetown/seasidetown/Hard/P001 21 20\ndatasets/Tartan/gascola/gascola/Easy/P006 1279 1249\ndatasets/Tartan/gascola/gascola/Easy/P007 1359 1354\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 173 182\ndatasets/Tartan/gascola/gascola/Easy/P007 2112 2110\ndatasets/Tartan/office2/office2/Hard/P008 638 637\ndatasets/Tartan/office2/office2/Hard/P004 288 292\ndatasets/Tartan/gascola/gascola/Easy/P007 18 32\ndatasets/Tartan/gascola/gascola/Easy/P007 495 489\ndatasets/Tartan/office2/office2/Easy/P004 1224 1229\ndatasets/Tartan/office2/office2/Easy/P009 397 400\ndatasets/Tartan/gascola/gascola/Easy/P004 1286 1296\ndatasets/Tartan/gascola/gascola/Hard/P001 35 29\ndatasets/Tartan/gascola/gascola/Easy/P006 163 170\ndatasets/Tartan/office2/office2/Easy/P006 20 29\ndatasets/Tartan/gascola/gascola/Easy/P004 979 982\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 512 536\ndatasets/Tartan/gascola/gascola/Hard/P006 935 939\ndatasets/Tartan/office2/office2/Easy/P005 144 140\ndatasets/Tartan/gascola/gascola/Easy/P004 2829 2826\ndatasets/Tartan/gascola/gascola/Hard/P002 772 768\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 1034 1016\ndatasets/Tartan/office2/office2/Easy/P008 3 21\ndatasets/Tartan/office2/office2/Easy/P004 1067 1070\ndatasets/Tartan/gascola/gascola/Hard/P005 472 483\ndatasets/Tartan/gascola/gascola/Easy/P004 518 528\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 497 495\ndatasets/Tartan/gascola/gascola/Hard/P008 1099 1097\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 322 324\ndatasets/Tartan/westerndesert/westerndesert/Hard/P006 173 179\ndatasets/Tartan/gascola/gascola/Easy/P004 1518 1514\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P015 327 328\ndatasets/Tartan/office2/office2/Easy/P008 719 661\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 995 994\ndatasets/Tartan/gascola/gascola/Easy/P006 894 891\ndatasets/Tartan/gascola/gascola/Hard/P008 792 793\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 471 430\ndatasets/Tartan/office2/office2/Hard/P005 366 364\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 355 356\ndatasets/Tartan/gascola/gascola/Easy/P005 654 648\ndatasets/Tartan/gascola/gascola/Easy/P006 1452 1433\ndatasets/Tartan/gascola/gascola/Hard/P006 759 760\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 130 127\ndatasets/Tartan/westerndesert/westerndesert/Easy/P007 160 161\ndatasets/Tartan/gascola/gascola/Hard/P006 41 80\ndatasets/Tartan/gascola/gascola/Hard/P005 1127 1122\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 455 456\ndatasets/Tartan/westerndesert/westerndesert/Hard/P003 333 323\ndatasets/Tartan/office2/office2/Hard/P009 776 771\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 112 106\ndatasets/Tartan/seasidetown/seasidetown/Easy/P009 20 22\ndatasets/Tartan/westerndesert/westerndesert/Hard/P002 504 481\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 566 561\ndatasets/Tartan/seasidetown/seasidetown/Easy/P001 174 182\ndatasets/Tartan/gascola/gascola/Hard/P008 1415 1419\ndatasets/Tartan/office2/office2/Hard/P009 790 811\ndatasets/Tartan/gascola/gascola/Easy/P006 2703 2700\ndatasets/Tartan/seasidetown/seasidetown/Easy/P009 104 103\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 314 315\ndatasets/Tartan/westerndesert/westerndesert/Easy/P005 9 8\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P016 293 295\ndatasets/Tartan/gascola/gascola/Hard/P006 1174 1176\ndatasets/Tartan/westerndesert/westerndesert/Easy/P012 262 265\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 55 57\ndatasets/Tartan/gascola/gascola/Easy/P004 867 860\ndatasets/Tartan/office2/office2/Easy/P003 105 102\ndatasets/Tartan/office2/office2/Hard/P004 105 107\ndatasets/Tartan/office2/office2/Easy/P008 0 22\ndatasets/Tartan/gascola/gascola/Hard/P006 321 325\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 132 129\ndatasets/Tartan/gascola/gascola/Easy/P005 673 683\ndatasets/Tartan/office2/office2/Hard/P002 565 564\ndatasets/Tartan/office2/office2/Hard/P008 739 740\ndatasets/Tartan/gascola/gascola/Easy/P004 1809 1813\ndatasets/Tartan/office2/office2/Hard/P003 1320 1321\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 11 8\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 821 824\ndatasets/Tartan/gascola/gascola/Easy/P006 2312 2314\ndatasets/Tartan/westerndesert/westerndesert/Easy/P009 168 139\ndatasets/Tartan/office2/office2/Easy/P008 930 934\ndatasets/Tartan/office2/office2/Easy/P000 159 153\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 656 655\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 820 817\ndatasets/Tartan/office2/office2/Easy/P011 679 682\ndatasets/Tartan/seasidetown/seasidetown/Hard/P000 253 248\ndatasets/Tartan/office2/office2/Easy/P000 142 147\ndatasets/Tartan/gascola/gascola/Hard/P008 1349 1350\ndatasets/Tartan/gascola/gascola/Hard/P004 1729 1730\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 139 137\ndatasets/Tartan/office2/office2/Easy/P000 246 239\ndatasets/Tartan/office2/office2/Easy/P000 301 294\ndatasets/Tartan/gascola/gascola/Easy/P006 1110 1117\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 306 303\ndatasets/Tartan/office2/office2/Easy/P005 160 157\ndatasets/Tartan/office2/office2/Easy/P008 1178 1170\ndatasets/Tartan/gascola/gascola/Easy/P006 301 312\ndatasets/Tartan/office2/office2/Hard/P000 136 134\ndatasets/Tartan/gascola/gascola/Easy/P004 2374 2372\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 830 833\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 45 39\ndatasets/Tartan/gascola/gascola/Easy/P006 1393 1389\ndatasets/Tartan/westerndesert/westerndesert/Easy/P008 264 263\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 684 676\ndatasets/Tartan/gascola/gascola/Easy/P005 1572 1571\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 304 316\ndatasets/Tartan/gascola/gascola/Easy/P004 603 606\ndatasets/Tartan/gascola/gascola/Easy/P004 20 8\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 644 642\ndatasets/Tartan/gascola/gascola/Easy/P004 2168 2167\ndatasets/Tartan/westerndesert/westerndesert/Hard/P001 139 140\ndatasets/Tartan/westerndesert/westerndesert/Easy/P008 42 40\ndatasets/Tartan/seasidetown/seasidetown/Easy/P004 442 441\ndatasets/Tartan/gascola/gascola/Hard/P002 1039 1056\ndatasets/Tartan/office2/office2/Hard/P002 626 621\ndatasets/Tartan/office2/office2/Easy/P008 1408 1427\ndatasets/Tartan/westerndesert/westerndesert/Hard/P001 84 88\ndatasets/Tartan/gascola/gascola/Easy/P003 755 759\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 501 507\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 1558 1551\ndatasets/Tartan/westerndesert/westerndesert/Hard/P003 429 431\ndatasets/Tartan/office2/office2/Hard/P010 105 100\ndatasets/Tartan/office2/office2/Easy/P011 31 33\ndatasets/Tartan/gascola/gascola/Hard/P002 1350 1341\ndatasets/Tartan/office2/office2/Easy/P005 513 516\ndatasets/Tartan/gascola/gascola/Hard/P004 654 652\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 503 506\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 244 241\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 545 528\ndatasets/Tartan/office2/office2/Easy/P008 337 339\ndatasets/Tartan/seasidetown/seasidetown/Hard/P001 280 287\ndatasets/Tartan/office2/office2/Hard/P003 674 671\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 299 304\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 553 545\ndatasets/Tartan/gascola/gascola/Easy/P004 1763 1773\ndatasets/Tartan/gascola/gascola/Hard/P006 613 600\ndatasets/Tartan/seasidetown/seasidetown/Easy/P009 379 373\ndatasets/Tartan/seasidetown/seasidetown/Easy/P000 337 356\ndatasets/Tartan/office2/office2/Easy/P007 256 259\ndatasets/Tartan/gascola/gascola/Hard/P006 773 763\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P012 506 514\ndatasets/Tartan/gascola/gascola/Hard/P004 903 898\ndatasets/Tartan/gascola/gascola/Hard/P009 192 186\ndatasets/Tartan/westerndesert/westerndesert/Easy/P009 554 546\ndatasets/Tartan/office2/office2/Hard/P008 587 588\ndatasets/Tartan/gascola/gascola/Easy/P005 367 364\ndatasets/Tartan/gascola/gascola/Hard/P000 16 5\ndatasets/Tartan/gascola/gascola/Easy/P008 1284 1272\ndatasets/Tartan/gascola/gascola/Easy/P006 2706 2702\ndatasets/Tartan/westerndesert/westerndesert/Easy/P006 158 164\ndatasets/Tartan/westerndesert/westerndesert/Easy/P006 392 438\ndatasets/Tartan/gascola/gascola/Easy/P003 1408 1415\ndatasets/Tartan/gascola/gascola/Hard/P008 491 490\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 834 835\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 209 211\ndatasets/Tartan/gascola/gascola/Hard/P000 179 175\ndatasets/Tartan/westerndesert/westerndesert/Easy/P010 224 246\ndatasets/Tartan/gascola/gascola/Hard/P005 173 182\ndatasets/Tartan/office2/office2/Hard/P009 318 320\ndatasets/Tartan/gascola/gascola/Easy/P006 1380 1377\ndatasets/Tartan/seasidetown/seasidetown/Easy/P001 108 101\ndatasets/Tartan/westerndesert/westerndesert/Easy/P002 266 263\ndatasets/Tartan/gascola/gascola/Hard/P006 1124 1127\ndatasets/Tartan/seasidetown/seasidetown/Easy/P000 294 299\ndatasets/Tartan/westerndesert/westerndesert/Hard/P005 440 434\ndatasets/Tartan/westerndesert/westerndesert/Hard/P005 438 433\ndatasets/Tartan/gascola/gascola/Easy/P007 1980 2025\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 822 833\ndatasets/Tartan/office2/office2/Hard/P002 429 428\ndatasets/Tartan/gascola/gascola/Hard/P007 549 552\ndatasets/Tartan/office2/office2/Easy/P008 938 928\ndatasets/Tartan/office2/office2/Hard/P008 481 473\ndatasets/Tartan/gascola/gascola/Easy/P007 2147 2149\ndatasets/Tartan/gascola/gascola/Easy/P004 2734 2717\ndatasets/Tartan/office2/office2/Easy/P004 230 212\ndatasets/Tartan/gascola/gascola/Easy/P005 232 241\ndatasets/Tartan/office2/office2/Hard/P010 170 174\ndatasets/Tartan/gascola/gascola/Hard/P008 26 28\ndatasets/Tartan/westerndesert/westerndesert/Hard/P006 225 223\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P012 279 277\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 556 555\ndatasets/Tartan/gascola/gascola/Easy/P006 833 840\ndatasets/Tartan/gascola/gascola/Hard/P004 1432 1433\ndatasets/Tartan/office2/office2/Easy/P010 266 29\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 131 133\ndatasets/Tartan/gascola/gascola/Easy/P007 2396 2399\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 684 681\ndatasets/Tartan/seasidetown/seasidetown/Easy/P009 654 661\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 423 429\ndatasets/Tartan/gascola/gascola/Easy/P007 2449 2447\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 809 812\ndatasets/Tartan/office2/office2/Hard/P010 426 432\ndatasets/Tartan/westerndesert/westerndesert/Easy/P005 181 183\ndatasets/Tartan/office2/office2/Hard/P010 27 22\ndatasets/Tartan/gascola/gascola/Easy/P004 112 123\ndatasets/Tartan/office2/office2/Easy/P005 84 76\ndatasets/Tartan/seasidetown/seasidetown/Easy/P009 478 473\ndatasets/Tartan/gascola/gascola/Easy/P008 653 650\ndatasets/Tartan/gascola/gascola/Hard/P006 932 962\ndatasets/Tartan/gascola/gascola/Hard/P009 726 722\ndatasets/Tartan/office2/office2/Easy/P008 188 189\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 889 895\ndatasets/Tartan/office2/office2/Easy/P009 83 79\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 670 667\ndatasets/Tartan/office2/office2/Easy/P004 1024 1027\ndatasets/Tartan/gascola/gascola/Hard/P002 133 205\ndatasets/Tartan/westerndesert/westerndesert/Easy/P007 6 5\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 74 83\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 851 850\ndatasets/Tartan/seasidetown/seasidetown/Easy/P001 242 236\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 141 140\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 356 375\ndatasets/Tartan/gascola/gascola/Easy/P004 2485 2488\ndatasets/Tartan/gascola/gascola/Easy/P005 958 962\ndatasets/Tartan/seasidetown/seasidetown/Easy/P003 202 271\ndatasets/Tartan/seasidetown/seasidetown/Hard/P001 202 188\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 689 684\ndatasets/Tartan/office2/office2/Hard/P005 472 497\ndatasets/Tartan/gascola/gascola/Easy/P003 976 979\ndatasets/Tartan/gascola/gascola/Easy/P007 2086 2090\ndatasets/Tartan/office2/office2/Hard/P008 5 3\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 1205 1202\ndatasets/Tartan/gascola/gascola/Easy/P004 662 661\ndatasets/Tartan/office2/office2/Easy/P003 385 387\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 198 196\ndatasets/Tartan/gascola/gascola/Hard/P004 290 287\ndatasets/Tartan/seasidetown/seasidetown/Easy/P009 581 584\ndatasets/Tartan/gascola/gascola/Hard/P007 661 654\ndatasets/Tartan/office2/office2/Hard/P003 871 868\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 527 530\ndatasets/Tartan/gascola/gascola/Hard/P008 452 450\ndatasets/Tartan/office2/office2/Easy/P009 988 986\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 749 755\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P015 111 109\ndatasets/Tartan/westerndesert/westerndesert/Easy/P008 329 331\ndatasets/Tartan/office2/office2/Easy/P004 1152 1150\ndatasets/Tartan/gascola/gascola/Easy/P003 682 678\ndatasets/Tartan/gascola/gascola/Easy/P006 2522 2533\ndatasets/Tartan/gascola/gascola/Easy/P005 79 80\ndatasets/Tartan/gascola/gascola/Easy/P006 1616 1612\ndatasets/Tartan/gascola/gascola/Hard/P008 469 471\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 320 316\ndatasets/Tartan/westerndesert/westerndesert/Easy/P002 219 213\ndatasets/Tartan/gascola/gascola/Hard/P004 406 399\ndatasets/Tartan/gascola/gascola/Hard/P004 1609 1611\ndatasets/Tartan/office2/office2/Hard/P005 1131 1127\ndatasets/Tartan/gascola/gascola/Easy/P004 1599 1602\ndatasets/Tartan/gascola/gascola/Easy/P005 197 220\ndatasets/Tartan/seasidetown/seasidetown/Easy/P000 533 518\ndatasets/Tartan/gascola/gascola/Easy/P003 1494 1487\ndatasets/Tartan/gascola/gascola/Easy/P006 838 840\ndatasets/Tartan/office2/office2/Easy/P006 905 899\ndatasets/Tartan/gascola/gascola/Easy/P003 1229 1232\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P015 4 2\ndatasets/Tartan/office2/office2/Easy/P008 980 1003\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P013 121 158\ndatasets/Tartan/gascola/gascola/Hard/P006 391 388\ndatasets/Tartan/gascola/gascola/Easy/P008 1348 1346\ndatasets/Tartan/gascola/gascola/Easy/P007 1349 1358\ndatasets/Tartan/westerndesert/westerndesert/Hard/P003 480 481\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 161 158\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 538 535\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P015 273 270\ndatasets/Tartan/office2/office2/Easy/P011 24 19\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 57 60\ndatasets/Tartan/gascola/gascola/Easy/P004 2123 2143\ndatasets/Tartan/seasidetown/seasidetown/Easy/P000 462 469\ndatasets/Tartan/gascola/gascola/Hard/P004 1117 1120\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 556 550\ndatasets/Tartan/gascola/gascola/Easy/P006 964 953\ndatasets/Tartan/office2/office2/Hard/P002 466 473\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 408 409\ndatasets/Tartan/gascola/gascola/Easy/P007 1321 1315\ndatasets/Tartan/gascola/gascola/Easy/P007 2401 2403\ndatasets/Tartan/gascola/gascola/Hard/P008 1212 1210\ndatasets/Tartan/seasidetown/seasidetown/Easy/P009 169 171\ndatasets/Tartan/office2/office2/Hard/P001 330 326\ndatasets/Tartan/seasidetown/seasidetown/Easy/P003 187 192\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 94 102\ndatasets/Tartan/westerndesert/westerndesert/Hard/P002 530 549\ndatasets/Tartan/gascola/gascola/Easy/P004 1100 1097\ndatasets/Tartan/gascola/gascola/Hard/P001 109 106\ndatasets/Tartan/office2/office2/Hard/P010 106 102\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 189 192\ndatasets/Tartan/gascola/gascola/Easy/P007 684 682\ndatasets/Tartan/office2/office2/Easy/P005 98 102\ndatasets/Tartan/gascola/gascola/Easy/P006 1425 1448\ndatasets/Tartan/westerndesert/westerndesert/Easy/P011 61 62\ndatasets/Tartan/gascola/gascola/Easy/P007 279 277\ndatasets/Tartan/gascola/gascola/Hard/P008 199 204\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 844 842\ndatasets/Tartan/gascola/gascola/Easy/P006 1069 1064\ndatasets/Tartan/westerndesert/westerndesert/Hard/P002 381 378\ndatasets/Tartan/office2/office2/Hard/P008 136 135\ndatasets/Tartan/office2/office2/Easy/P011 312 306\ndatasets/Tartan/office2/office2/Easy/P010 256 78\ndatasets/Tartan/office2/office2/Hard/P009 1031 1030\ndatasets/Tartan/office2/office2/Easy/P006 715 722\ndatasets/Tartan/gascola/gascola/Hard/P008 530 531\ndatasets/Tartan/office2/office2/Easy/P000 289 283\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 513 515\ndatasets/Tartan/office2/office2/Easy/P000 361 363\ndatasets/Tartan/gascola/gascola/Hard/P005 581 596\ndatasets/Tartan/office2/office2/Easy/P008 1161 1191\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 1054 1055\ndatasets/Tartan/gascola/gascola/Easy/P008 182 188\ndatasets/Tartan/gascola/gascola/Easy/P007 1805 1833\ndatasets/Tartan/seasidetown/seasidetown/Easy/P000 444 438\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 435 429\ndatasets/Tartan/gascola/gascola/Hard/P002 1361 1333\ndatasets/Tartan/office2/office2/Hard/P003 1363 1371\ndatasets/Tartan/office2/office2/Hard/P003 393 378\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 708 706\ndatasets/Tartan/office2/office2/Easy/P007 137 154\ndatasets/Tartan/gascola/gascola/Easy/P006 1866 1871\ndatasets/Tartan/gascola/gascola/Easy/P004 1793 1791\ndatasets/Tartan/westerndesert/westerndesert/Easy/P006 50 80\ndatasets/Tartan/office2/office2/Easy/P006 537 523\ndatasets/Tartan/office2/office2/Easy/P011 576 572\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 292 294\ndatasets/Tartan/gascola/gascola/Hard/P007 247 248\ndatasets/Tartan/seasidetown/seasidetown/Easy/P009 467 470\ndatasets/Tartan/gascola/gascola/Hard/P000 119 113\ndatasets/Tartan/gascola/gascola/Easy/P005 1665 1663\ndatasets/Tartan/gascola/gascola/Easy/P004 850 860\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P014 336 334\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 617 615\ndatasets/Tartan/office2/office2/Hard/P007 37 36\ndatasets/Tartan/westerndesert/westerndesert/Hard/P003 261 264\ndatasets/Tartan/seasidetown/seasidetown/Easy/P004 26 40\ndatasets/Tartan/seasidetown/seasidetown/Hard/P000 292 295\ndatasets/Tartan/office2/office2/Easy/P005 1 2\ndatasets/Tartan/gascola/gascola/Easy/P003 472 476\ndatasets/Tartan/office2/office2/Hard/P008 620 621\ndatasets/Tartan/gascola/gascola/Easy/P001 220 231\ndatasets/Tartan/office2/office2/Easy/P005 157 160\ndatasets/Tartan/seasidetown/seasidetown/Easy/P001 207 211\ndatasets/Tartan/gascola/gascola/Easy/P007 2224 2225\ndatasets/Tartan/office2/office2/Easy/P003 346 349\ndatasets/Tartan/office2/office2/Hard/P002 363 627\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 31 35\ndatasets/Tartan/gascola/gascola/Hard/P006 147 149\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 159 156\ndatasets/Tartan/seasidetown/seasidetown/Easy/P004 51 60\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 309 313\ndatasets/Tartan/gascola/gascola/Hard/P003 548 555\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 522 520\ndatasets/Tartan/office2/office2/Hard/P005 493 485\ndatasets/Tartan/office2/office2/Easy/P004 1389 1376\ndatasets/Tartan/office2/office2/Easy/P011 623 588\ndatasets/Tartan/gascola/gascola/Easy/P003 776 772\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 55 51\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 756 753\ndatasets/Tartan/westerndesert/westerndesert/Easy/P006 388 435\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 362 187\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P012 384 379\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 15 14\ndatasets/Tartan/office2/office2/Hard/P009 784 792\ndatasets/Tartan/gascola/gascola/Easy/P008 578 590\ndatasets/Tartan/gascola/gascola/Easy/P008 1379 1425\ndatasets/Tartan/gascola/gascola/Hard/P002 461 454\ndatasets/Tartan/gascola/gascola/Easy/P008 452 454\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 472 468\ndatasets/Tartan/gascola/gascola/Easy/P004 1000 1014\ndatasets/Tartan/gascola/gascola/Easy/P006 302 314\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 926 922\ndatasets/Tartan/seasidetown/seasidetown/Easy/P009 85 91\ndatasets/Tartan/gascola/gascola/Hard/P006 1068 1074\ndatasets/Tartan/office2/office2/Easy/P003 596 595\ndatasets/Tartan/office2/office2/Hard/P001 96 93\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 1066 1058\ndatasets/Tartan/gascola/gascola/Hard/P001 246 248\ndatasets/Tartan/gascola/gascola/Hard/P001 186 181\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 936 937\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 445 432\ndatasets/Tartan/office2/office2/Hard/P005 981 961\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 673 661\ndatasets/Tartan/gascola/gascola/Hard/P005 510 506\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 790 776\ndatasets/Tartan/seasidetown/seasidetown/Easy/P003 225 246\ndatasets/Tartan/westerndesert/westerndesert/Easy/P007 366 374\ndatasets/Tartan/gascola/gascola/Hard/P005 897 892\ndatasets/Tartan/gascola/gascola/Easy/P006 1921 1918\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 817 815\ndatasets/Tartan/gascola/gascola/Easy/P003 1340 1379\ndatasets/Tartan/gascola/gascola/Easy/P003 1010 1005\ndatasets/Tartan/seasidetown/seasidetown/Easy/P003 234 248\ndatasets/Tartan/gascola/gascola/Hard/P008 819 823\ndatasets/Tartan/office2/office2/Easy/P003 350 324\ndatasets/Tartan/seasidetown/seasidetown/Easy/P001 148 132\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 614 612\ndatasets/Tartan/office2/office2/Hard/P005 927 924\ndatasets/Tartan/office2/office2/Hard/P010 515 504\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 207 208\ndatasets/Tartan/office2/office2/Hard/P004 295 299\ndatasets/Tartan/office2/office2/Easy/P008 386 352\ndatasets/Tartan/gascola/gascola/Easy/P007 1373 1364\ndatasets/Tartan/office2/office2/Hard/P005 616 614\ndatasets/Tartan/westerndesert/westerndesert/Easy/P002 315 318\ndatasets/Tartan/gascola/gascola/Hard/P008 1410 1414\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 908 906\ndatasets/Tartan/office2/office2/Easy/P008 28 25\ndatasets/Tartan/office2/office2/Hard/P004 244 235\ndatasets/Tartan/office2/office2/Hard/P001 122 129\ndatasets/Tartan/gascola/gascola/Easy/P005 335 334\ndatasets/Tartan/gascola/gascola/Easy/P008 12 32\ndatasets/Tartan/office2/office2/Easy/P004 1220 1217\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 484 475\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P014 380 381\ndatasets/Tartan/westerndesert/westerndesert/Easy/P007 59 79\ndatasets/Tartan/seasidetown/seasidetown/Easy/P004 396 393\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 468 470\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 1143 1146\ndatasets/Tartan/gascola/gascola/Easy/P006 2017 2005\ndatasets/Tartan/gascola/gascola/Hard/P008 1344 1340\ndatasets/Tartan/office2/office2/Hard/P002 703 698\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 285 274\ndatasets/Tartan/office2/office2/Hard/P003 529 506\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 860 861\ndatasets/Tartan/office2/office2/Easy/P000 34 28\ndatasets/Tartan/gascola/gascola/Easy/P006 1146 1152\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 239 238\ndatasets/Tartan/gascola/gascola/Easy/P006 2612 2611\ndatasets/Tartan/gascola/gascola/Hard/P002 1203 1197\ndatasets/Tartan/gascola/gascola/Easy/P003 67 18\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P012 239 236\ndatasets/Tartan/seasidetown/seasidetown/Hard/P003 101 99\ndatasets/Tartan/office2/office2/Hard/P005 598 599\ndatasets/Tartan/office2/office2/Hard/P001 247 243\ndatasets/Tartan/gascola/gascola/Hard/P003 445 446\ndatasets/Tartan/gascola/gascola/Hard/P002 1376 1373\ndatasets/Tartan/gascola/gascola/Hard/P008 793 795\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 1379 1378\ndatasets/Tartan/office2/office2/Hard/P005 520 516\ndatasets/Tartan/gascola/gascola/Easy/P003 508 501\ndatasets/Tartan/office2/office2/Hard/P005 823 824\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 121 114\ndatasets/Tartan/gascola/gascola/Easy/P005 753 754\ndatasets/Tartan/westerndesert/westerndesert/Easy/P002 26 31\ndatasets/Tartan/gascola/gascola/Easy/P003 133 134\ndatasets/Tartan/gascola/gascola/Easy/P003 1479 1482\ndatasets/Tartan/gascola/gascola/Hard/P004 121 127\ndatasets/Tartan/gascola/gascola/Hard/P006 315 330\ndatasets/Tartan/westerndesert/westerndesert/Hard/P002 181 177\ndatasets/Tartan/office2/office2/Easy/P009 247 243\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P016 111 121\ndatasets/Tartan/office2/office2/Hard/P003 268 276\ndatasets/Tartan/office2/office2/Easy/P008 1002 1017\ndatasets/Tartan/gascola/gascola/Hard/P002 1241 1230\ndatasets/Tartan/office2/office2/Easy/P006 517 520\ndatasets/Tartan/gascola/gascola/Easy/P004 2381 2378\ndatasets/Tartan/seasidetown/seasidetown/Easy/P000 208 210\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 103 97\ndatasets/Tartan/office2/office2/Hard/P005 686 685\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 200 204\ndatasets/Tartan/office2/office2/Hard/P010 6 8\ndatasets/Tartan/westerndesert/westerndesert/Hard/P007 227 225\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 485 430\ndatasets/Tartan/gascola/gascola/Hard/P002 39 46\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 521 490\ndatasets/Tartan/gascola/gascola/Easy/P008 1031 1036\ndatasets/Tartan/gascola/gascola/Easy/P004 2523 2520\ndatasets/Tartan/westerndesert/westerndesert/Easy/P011 250 247\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 563 562\ndatasets/Tartan/westerndesert/westerndesert/Hard/P002 44 49\ndatasets/Tartan/gascola/gascola/Hard/P003 229 232\ndatasets/Tartan/westerndesert/westerndesert/Hard/P006 220 226\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 643 640\ndatasets/Tartan/westerndesert/westerndesert/Easy/P007 409 404\ndatasets/Tartan/gascola/gascola/Hard/P008 833 835\ndatasets/Tartan/seasidetown/seasidetown/Hard/P001 291 282\ndatasets/Tartan/gascola/gascola/Easy/P005 959 953\ndatasets/Tartan/gascola/gascola/Easy/P008 712 706\ndatasets/Tartan/gascola/gascola/Easy/P007 1324 1323\ndatasets/Tartan/gascola/gascola/Hard/P002 776 797\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 178 173\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 394 393\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P013 433 432\ndatasets/Tartan/seasidetown/seasidetown/Hard/P003 349 351\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 847 844\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 327 325\ndatasets/Tartan/gascola/gascola/Hard/P005 1237 1225\ndatasets/Tartan/gascola/gascola/Hard/P004 62 57\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 509 511\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 770 512\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 410 403\ndatasets/Tartan/gascola/gascola/Hard/P006 948 938\ndatasets/Tartan/office2/office2/Hard/P005 791 803\ndatasets/Tartan/office2/office2/Easy/P004 732 747\ndatasets/Tartan/westerndesert/westerndesert/Hard/P007 116 119\ndatasets/Tartan/gascola/gascola/Hard/P005 128 134\ndatasets/Tartan/seasidetown/seasidetown/Easy/P002 216 220\ndatasets/Tartan/gascola/gascola/Easy/P008 127 119\ndatasets/Tartan/office2/office2/Hard/P002 522 511\ndatasets/Tartan/westerndesert/westerndesert/Hard/P001 1 0\ndatasets/Tartan/gascola/gascola/Easy/P003 1460 1447\ndatasets/Tartan/gascola/gascola/Easy/P008 863 855\ndatasets/Tartan/gascola/gascola/Hard/P001 313 315\ndatasets/Tartan/gascola/gascola/Easy/P003 800 791\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 16 11\ndatasets/Tartan/office2/office2/Easy/P007 1 14\ndatasets/Tartan/office2/office2/Easy/P006 562 554\ndatasets/Tartan/gascola/gascola/Hard/P008 124 133\ndatasets/Tartan/office2/office2/Hard/P008 193 196\ndatasets/Tartan/gascola/gascola/Hard/P007 691 682\ndatasets/Tartan/gascola/gascola/Easy/P004 813 820\ndatasets/Tartan/office2/office2/Hard/P010 65 54\ndatasets/Tartan/office2/office2/Easy/P008 8 30\ndatasets/Tartan/gascola/gascola/Easy/P005 725 720\ndatasets/Tartan/office2/office2/Easy/P009 1283 1284\ndatasets/Tartan/westerndesert/westerndesert/Easy/P010 205 207\ndatasets/Tartan/gascola/gascola/Easy/P004 289 285\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 827 830\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 443 453\ndatasets/Tartan/westerndesert/westerndesert/Easy/P001 282 283\ndatasets/Tartan/gascola/gascola/Easy/P004 1579 1575\ndatasets/Tartan/gascola/gascola/Hard/P005 1154 1151\ndatasets/Tartan/westerndesert/westerndesert/Easy/P002 222 218\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 648 650\ndatasets/Tartan/office2/office2/Easy/P009 878 882\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 829 823\ndatasets/Tartan/office2/office2/Hard/P009 518 522\ndatasets/Tartan/westerndesert/westerndesert/Easy/P007 447 450\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 432 425\ndatasets/Tartan/gascola/gascola/Hard/P004 723 722\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 265 274\ndatasets/Tartan/gascola/gascola/Easy/P007 2195 2193\ndatasets/Tartan/westerndesert/westerndesert/Hard/P004 82 81\ndatasets/Tartan/gascola/gascola/Easy/P003 312 322\ndatasets/Tartan/office2/office2/Easy/P006 788 776\ndatasets/Tartan/gascola/gascola/Hard/P006 1406 1414\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 349 373\ndatasets/Tartan/gascola/gascola/Hard/P004 641 644\ndatasets/Tartan/seasidetown/seasidetown/Easy/P002 4 5\ndatasets/Tartan/gascola/gascola/Easy/P004 2449 2451\ndatasets/Tartan/westerndesert/westerndesert/Hard/P006 200 205\ndatasets/Tartan/office2/office2/Easy/P006 357 352\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 282 278\ndatasets/Tartan/office2/office2/Hard/P003 1288 1309\ndatasets/Tartan/gascola/gascola/Easy/P004 1662 1660\ndatasets/Tartan/office2/office2/Hard/P003 1484 1481\ndatasets/Tartan/office2/office2/Easy/P008 735 741\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 941 940\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 39 38\ndatasets/Tartan/office2/office2/Easy/P006 350 352\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 392 385\ndatasets/Tartan/gascola/gascola/Easy/P006 2108 2104\ndatasets/Tartan/gascola/gascola/Hard/P008 121 123\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P012 643 644\ndatasets/Tartan/seasidetown/seasidetown/Hard/P003 209 218\ndatasets/Tartan/office2/office2/Hard/P007 197 196\ndatasets/Tartan/westerndesert/westerndesert/Hard/P004 163 171\ndatasets/Tartan/gascola/gascola/Easy/P004 450 456\ndatasets/Tartan/office2/office2/Easy/P008 1362 1367\ndatasets/Tartan/office2/office2/Hard/P009 985 987\ndatasets/Tartan/westerndesert/westerndesert/Easy/P007 284 272\ndatasets/Tartan/office2/office2/Hard/P003 442 434\ndatasets/Tartan/gascola/gascola/Easy/P006 1680 1693\ndatasets/Tartan/gascola/gascola/Hard/P002 273 263\ndatasets/Tartan/office2/office2/Easy/P011 87 86\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P013 250 261\ndatasets/Tartan/westerndesert/westerndesert/Easy/P010 118 125\ndatasets/Tartan/gascola/gascola/Easy/P003 692 696\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P012 357 354\ndatasets/Tartan/seasidetown/seasidetown/Easy/P009 723 726\ndatasets/Tartan/gascola/gascola/Easy/P003 70 44\ndatasets/Tartan/gascola/gascola/Hard/P009 55 62\ndatasets/Tartan/gascola/gascola/Hard/P001 105 108\ndatasets/Tartan/gascola/gascola/Hard/P005 10 4\ndatasets/Tartan/office2/office2/Easy/P006 593 590\ndatasets/Tartan/office2/office2/Hard/P008 614 616\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 64 67\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 267 258\ndatasets/Tartan/office2/office2/Hard/P009 216 461\ndatasets/Tartan/office2/office2/Hard/P002 230 231\ndatasets/Tartan/office2/office2/Hard/P009 331 334\ndatasets/Tartan/westerndesert/westerndesert/Easy/P012 305 308\ndatasets/Tartan/office2/office2/Hard/P005 714 710\ndatasets/Tartan/gascola/gascola/Hard/P002 380 373\ndatasets/Tartan/westerndesert/westerndesert/Hard/P001 165 150\ndatasets/Tartan/gascola/gascola/Easy/P007 1593 1633\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P015 239 242\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 329 343\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P012 120 121\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 754 757\ndatasets/Tartan/seasidetown/seasidetown/Easy/P004 487 491\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 295 293\ndatasets/Tartan/westerndesert/westerndesert/Easy/P005 240 260\ndatasets/Tartan/gascola/gascola/Easy/P004 1408 1407\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 447 446\ndatasets/Tartan/office2/office2/Hard/P003 1145 1146\ndatasets/Tartan/office2/office2/Easy/P004 800 807\ndatasets/Tartan/gascola/gascola/Easy/P004 1796 1793\ndatasets/Tartan/westerndesert/westerndesert/Hard/P003 186 190\ndatasets/Tartan/westerndesert/westerndesert/Hard/P007 139 141\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P015 42 43\ndatasets/Tartan/gascola/gascola/Hard/P008 355 352\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 683 684\ndatasets/Tartan/gascola/gascola/Hard/P003 539 533\ndatasets/Tartan/gascola/gascola/Hard/P004 1570 1584\ndatasets/Tartan/gascola/gascola/Easy/P003 1280 1285\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 641 645\ndatasets/Tartan/office2/office2/Easy/P005 205 201\ndatasets/Tartan/westerndesert/westerndesert/Easy/P001 257 263\ndatasets/Tartan/westerndesert/westerndesert/Hard/P005 461 467\ndatasets/Tartan/gascola/gascola/Hard/P002 1115 1122\ndatasets/Tartan/office2/office2/Easy/P006 555 549\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 923 919\ndatasets/Tartan/gascola/gascola/Hard/P009 235 232\ndatasets/Tartan/westerndesert/westerndesert/Easy/P008 300 294\ndatasets/Tartan/gascola/gascola/Hard/P004 961 960\ndatasets/Tartan/gascola/gascola/Easy/P006 2675 2671\ndatasets/Tartan/seasidetown/seasidetown/Easy/P009 416 413\ndatasets/Tartan/office2/office2/Hard/P010 225 235\ndatasets/Tartan/gascola/gascola/Hard/P006 1520 1519\ndatasets/Tartan/westerndesert/westerndesert/Easy/P009 460 462\ndatasets/Tartan/gascola/gascola/Hard/P005 459 500\ndatasets/Tartan/office2/office2/Hard/P005 749 757\ndatasets/Tartan/office2/office2/Hard/P003 868 869\ndatasets/Tartan/office2/office2/Hard/P005 834 832\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 394 387\ndatasets/Tartan/office2/office2/Hard/P006 245 243\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 436 438\ndatasets/Tartan/gascola/gascola/Hard/P007 706 698\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 779 769\ndatasets/Tartan/gascola/gascola/Hard/P008 810 814\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 106 104\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P014 84 86\ndatasets/Tartan/office2/office2/Easy/P004 469 454\ndatasets/Tartan/westerndesert/westerndesert/Hard/P007 71 77\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 747 743\ndatasets/Tartan/gascola/gascola/Hard/P008 74 76\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 1532 1531\ndatasets/Tartan/office2/office2/Easy/P000 94 99\ndatasets/Tartan/office2/office2/Easy/P008 245 241\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 1288 1292\ndatasets/Tartan/office2/office2/Easy/P004 1553 1534\ndatasets/Tartan/office2/office2/Easy/P011 473 468\ndatasets/Tartan/gascola/gascola/Hard/P001 304 303\ndatasets/Tartan/gascola/gascola/Easy/P008 1047 1051\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 610 608\ndatasets/Tartan/seasidetown/seasidetown/Easy/P009 849 845\ndatasets/Tartan/office2/office2/Hard/P000 287 293\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 37 41\ndatasets/Tartan/gascola/gascola/Hard/P005 1074 1070\ndatasets/Tartan/office2/office2/Hard/P003 618 613\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 471 838\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 579 583\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 787 797\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P012 310 312\ndatasets/Tartan/westerndesert/westerndesert/Hard/P005 245 248\ndatasets/Tartan/gascola/gascola/Hard/P004 1788 1796\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 809 802\ndatasets/Tartan/office2/office2/Hard/P004 106 103\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 720 715\ndatasets/Tartan/westerndesert/westerndesert/Hard/P004 285 301\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 519 518\ndatasets/Tartan/gascola/gascola/Easy/P003 141 148\ndatasets/Tartan/gascola/gascola/Easy/P006 2714 2707\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 38 36\ndatasets/Tartan/office2/office2/Hard/P010 540 543\ndatasets/Tartan/gascola/gascola/Easy/P006 1125 1122\ndatasets/Tartan/gascola/gascola/Hard/P004 35 39\ndatasets/Tartan/office2/office2/Easy/P003 398 400\ndatasets/Tartan/seasidetown/seasidetown/Easy/P000 163 154\ndatasets/Tartan/gascola/gascola/Easy/P008 1225 1228\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 89 99\ndatasets/Tartan/office2/office2/Hard/P008 666 670\ndatasets/Tartan/seasidetown/seasidetown/Easy/P003 318 320\ndatasets/Tartan/office2/office2/Hard/P001 154 149\ndatasets/Tartan/office2/office2/Easy/P008 559 557\ndatasets/Tartan/gascola/gascola/Easy/P008 455 466\ndatasets/Tartan/westerndesert/westerndesert/Hard/P004 146 144\ndatasets/Tartan/office2/office2/Hard/P007 160 162\ndatasets/Tartan/westerndesert/westerndesert/Easy/P009 118 116\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P015 123 120\ndatasets/Tartan/westerndesert/westerndesert/Easy/P006 192 185\ndatasets/Tartan/gascola/gascola/Hard/P005 560 563\ndatasets/Tartan/gascola/gascola/Easy/P006 630 627\ndatasets/Tartan/office2/office2/Easy/P011 156 158\ndatasets/Tartan/gascola/gascola/Easy/P004 1355 1361\ndatasets/Tartan/gascola/gascola/Easy/P004 2507 2497\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P014 369 368\ndatasets/Tartan/office2/office2/Easy/P009 676 680\ndatasets/Tartan/office2/office2/Hard/P003 53 46\ndatasets/Tartan/office2/office2/Hard/P008 679 691\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P016 267 270\ndatasets/Tartan/gascola/gascola/Easy/P006 2497 2503\ndatasets/Tartan/westerndesert/westerndesert/Easy/P012 29 31\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 932 936\ndatasets/Tartan/gascola/gascola/Easy/P008 201 204\ndatasets/Tartan/gascola/gascola/Hard/P004 1550 1552\ndatasets/Tartan/gascola/gascola/Hard/P004 183 190\ndatasets/Tartan/gascola/gascola/Hard/P002 808 804\ndatasets/Tartan/gascola/gascola/Easy/P005 449 443\ndatasets/Tartan/gascola/gascola/Easy/P004 179 183\ndatasets/Tartan/gascola/gascola/Hard/P005 447 444\ndatasets/Tartan/gascola/gascola/Easy/P006 1210 1212\ndatasets/Tartan/seasidetown/seasidetown/Easy/P000 83 84\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 858 849\ndatasets/Tartan/gascola/gascola/Easy/P008 320 315\ndatasets/Tartan/gascola/gascola/Hard/P003 278 287\ndatasets/Tartan/office2/office2/Hard/P003 588 593\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 1150 1149\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 146 178\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P015 233 230\ndatasets/Tartan/gascola/gascola/Easy/P007 569 567\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 137 134\ndatasets/Tartan/office2/office2/Easy/P009 15 9\ndatasets/Tartan/seasidetown/seasidetown/Hard/P000 267 271\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 228 212\ndatasets/Tartan/office2/office2/Hard/P002 111 112\ndatasets/Tartan/westerndesert/westerndesert/Hard/P005 351 345\ndatasets/Tartan/office2/office2/Hard/P009 169 166\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 849 846\ndatasets/Tartan/seasidetown/seasidetown/Easy/P001 196 161\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 1394 1390\ndatasets/Tartan/office2/office2/Easy/P011 347 349\ndatasets/Tartan/office2/office2/Hard/P005 1084 1081\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P015 330 328\ndatasets/Tartan/office2/office2/Hard/P008 801 809\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 902 903\ndatasets/Tartan/gascola/gascola/Hard/P008 1097 1093\ndatasets/Tartan/office2/office2/Easy/P010 146 118\ndatasets/Tartan/office2/office2/Easy/P009 1517 1512\ndatasets/Tartan/office2/office2/Hard/P006 325 324\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 205 209\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 752 755\ndatasets/Tartan/gascola/gascola/Easy/P006 1424 1420\ndatasets/Tartan/office2/office2/Easy/P010 299 290\ndatasets/Tartan/gascola/gascola/Easy/P006 2140 2141\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 333 304\ndatasets/Tartan/office2/office2/Easy/P011 297 302\ndatasets/Tartan/gascola/gascola/Hard/P003 414 410\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P015 113 114\ndatasets/Tartan/gascola/gascola/Easy/P008 889 881\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 283 276\ndatasets/Tartan/seasidetown/seasidetown/Easy/P004 202 203\ndatasets/Tartan/gascola/gascola/Easy/P001 227 209\ndatasets/Tartan/gascola/gascola/Hard/P003 115 114\ndatasets/Tartan/westerndesert/westerndesert/Hard/P004 327 332\ndatasets/Tartan/office2/office2/Easy/P007 263 259\ndatasets/Tartan/office2/office2/Easy/P009 1576 1572\ndatasets/Tartan/office2/office2/Hard/P002 18 15\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 721 723\ndatasets/Tartan/gascola/gascola/Hard/P004 1104 1105\ndatasets/Tartan/westerndesert/westerndesert/Easy/P010 200 202\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 885 888\ndatasets/Tartan/gascola/gascola/Hard/P005 479 495\ndatasets/Tartan/seasidetown/seasidetown/Easy/P004 409 404\ndatasets/Tartan/gascola/gascola/Easy/P003 241 232\ndatasets/Tartan/gascola/gascola/Easy/P007 934 929\ndatasets/Tartan/office2/office2/Easy/P011 493 490\ndatasets/Tartan/gascola/gascola/Easy/P006 1677 1681\ndatasets/Tartan/gascola/gascola/Easy/P005 735 733\ndatasets/Tartan/seasidetown/seasidetown/Easy/P004 208 209\ndatasets/Tartan/gascola/gascola/Easy/P007 1767 1760\ndatasets/Tartan/office2/office2/Hard/P008 164 162\ndatasets/Tartan/office2/office2/Easy/P009 981 978\ndatasets/Tartan/office2/office2/Easy/P004 910 908\ndatasets/Tartan/gascola/gascola/Easy/P008 1123 1121\ndatasets/Tartan/office2/office2/Hard/P001 251 259\ndatasets/Tartan/gascola/gascola/Easy/P007 550 543\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 589 592\ndatasets/Tartan/office2/office2/Easy/P006 883 875\ndatasets/Tartan/westerndesert/westerndesert/Hard/P006 116 113\ndatasets/Tartan/gascola/gascola/Easy/P004 564 565\ndatasets/Tartan/westerndesert/westerndesert/Hard/P002 108 104\ndatasets/Tartan/gascola/gascola/Easy/P003 1141 1145\ndatasets/Tartan/office2/office2/Easy/P006 81 103\ndatasets/Tartan/office2/office2/Hard/P006 175 179\ndatasets/Tartan/gascola/gascola/Easy/P007 1061 1055\ndatasets/Tartan/office2/office2/Hard/P004 17 23\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 585 583\ndatasets/Tartan/gascola/gascola/Hard/P002 1040 1037\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 260 232\ndatasets/Tartan/gascola/gascola/Easy/P006 526 529\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 463 466\ndatasets/Tartan/gascola/gascola/Easy/P006 1848 1855\ndatasets/Tartan/seasidetown/seasidetown/Easy/P003 16 22\ndatasets/Tartan/gascola/gascola/Hard/P002 1154 1159\ndatasets/Tartan/office2/office2/Easy/P008 763 769\ndatasets/Tartan/gascola/gascola/Easy/P005 621 614\ndatasets/Tartan/westerndesert/westerndesert/Easy/P001 20 19\ndatasets/Tartan/office2/office2/Easy/P008 745 747\ndatasets/Tartan/gascola/gascola/Easy/P005 1100 1118\ndatasets/Tartan/office2/office2/Easy/P011 605 612\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 239 225\ndatasets/Tartan/seasidetown/seasidetown/Easy/P003 160 161\ndatasets/Tartan/westerndesert/westerndesert/Hard/P001 284 287\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P013 123 156\ndatasets/Tartan/office2/office2/Easy/P000 4 3\ndatasets/Tartan/gascola/gascola/Easy/P004 1130 1165\ndatasets/Tartan/gascola/gascola/Easy/P003 46 28\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 687 685\ndatasets/Tartan/gascola/gascola/Hard/P007 476 473\ndatasets/Tartan/westerndesert/westerndesert/Hard/P003 104 101\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 556 574\ndatasets/Tartan/office2/office2/Hard/P005 600 603\ndatasets/Tartan/gascola/gascola/Hard/P008 994 989\ndatasets/Tartan/gascola/gascola/Hard/P004 1246 1235\ndatasets/Tartan/office2/office2/Hard/P008 99 103\ndatasets/Tartan/office2/office2/Hard/P009 278 272\ndatasets/Tartan/westerndesert/westerndesert/Easy/P009 388 389\ndatasets/Tartan/office2/office2/Hard/P009 440 441\ndatasets/Tartan/gascola/gascola/Easy/P008 957 945\ndatasets/Tartan/gascola/gascola/Hard/P000 206 205\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 422 399\ndatasets/Tartan/westerndesert/westerndesert/Hard/P001 97 94\ndatasets/Tartan/westerndesert/westerndesert/Easy/P009 285 320\ndatasets/Tartan/gascola/gascola/Easy/P005 710 715\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 38 34\ndatasets/Tartan/westerndesert/westerndesert/Easy/P012 138 106\ndatasets/Tartan/gascola/gascola/Easy/P007 2043 2083\ndatasets/Tartan/gascola/gascola/Easy/P005 884 874\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P014 116 117\ndatasets/Tartan/gascola/gascola/Hard/P007 205 206\ndatasets/Tartan/office2/office2/Easy/P009 665 673\ndatasets/Tartan/gascola/gascola/Easy/P003 1088 1075\ndatasets/Tartan/office2/office2/Hard/P005 170 197\ndatasets/Tartan/gascola/gascola/Hard/P004 540 547\ndatasets/Tartan/westerndesert/westerndesert/Hard/P005 484 480\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 768 766\ndatasets/Tartan/westerndesert/westerndesert/Easy/P009 92 559\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 227 220\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 157 156\ndatasets/Tartan/westerndesert/westerndesert/Hard/P002 280 278\ndatasets/Tartan/office2/office2/Hard/P009 138 140\ndatasets/Tartan/westerndesert/westerndesert/Easy/P010 195 199\ndatasets/Tartan/westerndesert/westerndesert/Hard/P004 140 139\ndatasets/Tartan/westerndesert/westerndesert/Hard/P006 258 253\ndatasets/Tartan/gascola/gascola/Easy/P005 976 980\ndatasets/Tartan/gascola/gascola/Hard/P002 849 856\ndatasets/Tartan/gascola/gascola/Easy/P004 1193 1248\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 471 472\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 502 501\ndatasets/Tartan/office2/office2/Hard/P009 424 367\ndatasets/Tartan/office2/office2/Hard/P005 920 919\ndatasets/Tartan/office2/office2/Easy/P006 321 315\ndatasets/Tartan/office2/office2/Easy/P010 200 221\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 830 829\ndatasets/Tartan/westerndesert/westerndesert/Easy/P011 302 275\ndatasets/Tartan/office2/office2/Easy/P009 202 1012\ndatasets/Tartan/office2/office2/Easy/P008 1396 1393\ndatasets/Tartan/westerndesert/westerndesert/Hard/P005 160 156\ndatasets/Tartan/gascola/gascola/Hard/P009 108 105\ndatasets/Tartan/gascola/gascola/Easy/P006 152 147\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 283 252\ndatasets/Tartan/office2/office2/Hard/P003 560 558\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 722 724\ndatasets/Tartan/gascola/gascola/Easy/P005 1358 1343\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 36 26\ndatasets/Tartan/office2/office2/Easy/P011 499 503\ndatasets/Tartan/gascola/gascola/Easy/P003 364 363\ndatasets/Tartan/office2/office2/Hard/P003 927 931\ndatasets/Tartan/office2/office2/Easy/P006 556 533\ndatasets/Tartan/gascola/gascola/Easy/P006 346 349\ndatasets/Tartan/gascola/gascola/Easy/P004 2299 2304\ndatasets/Tartan/office2/office2/Easy/P004 1229 1225\ndatasets/Tartan/gascola/gascola/Easy/P004 2004 2007\ndatasets/Tartan/gascola/gascola/Hard/P005 32 40\ndatasets/Tartan/gascola/gascola/Easy/P006 1387 1384\ndatasets/Tartan/gascola/gascola/Hard/P006 1394 1398\ndatasets/Tartan/office2/office2/Easy/P009 651 669\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 668 665\ndatasets/Tartan/gascola/gascola/Hard/P008 1316 1314\ndatasets/Tartan/office2/office2/Easy/P008 1193 1218\ndatasets/Tartan/gascola/gascola/Easy/P004 1700 1704\ndatasets/Tartan/gascola/gascola/Hard/P007 556 567\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 822 825\ndatasets/Tartan/office2/office2/Hard/P009 63 64\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 546 541\ndatasets/Tartan/office2/office2/Easy/P009 238 1075\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 181 176\ndatasets/Tartan/gascola/gascola/Hard/P000 150 158\ndatasets/Tartan/gascola/gascola/Easy/P008 1433 1430\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 548 547\ndatasets/Tartan/westerndesert/westerndesert/Hard/P003 176 173\ndatasets/Tartan/gascola/gascola/Easy/P008 934 929\ndatasets/Tartan/gascola/gascola/Easy/P004 1753 1748\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 130 124\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 1389 1385\ndatasets/Tartan/office2/office2/Easy/P005 224 228\ndatasets/Tartan/gascola/gascola/Hard/P004 983 981\ndatasets/Tartan/gascola/gascola/Hard/P008 1453 1456\ndatasets/Tartan/gascola/gascola/Easy/P004 1670 1667\ndatasets/Tartan/gascola/gascola/Easy/P007 1020 1013\ndatasets/Tartan/office2/office2/Hard/P003 453 489\ndatasets/Tartan/westerndesert/westerndesert/Hard/P003 431 435\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 873 865\ndatasets/Tartan/office2/office2/Easy/P008 1464 1468\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 9 4\ndatasets/Tartan/gascola/gascola/Hard/P004 1184 1182\ndatasets/Tartan/office2/office2/Hard/P009 60 59\ndatasets/Tartan/seasidetown/seasidetown/Easy/P000 543 525\ndatasets/Tartan/office2/office2/Easy/P003 450 440\ndatasets/Tartan/office2/office2/Hard/P004 301 306\ndatasets/Tartan/office2/office2/Easy/P000 225 216\ndatasets/Tartan/westerndesert/westerndesert/Easy/P002 363 365\ndatasets/Tartan/gascola/gascola/Hard/P004 1138 1137\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 517 514\ndatasets/Tartan/westerndesert/westerndesert/Hard/P003 59 56\ndatasets/Tartan/westerndesert/westerndesert/Hard/P003 20 23\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 243 237\ndatasets/Tartan/gascola/gascola/Easy/P005 932 936\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 214 216\ndatasets/Tartan/westerndesert/westerndesert/Easy/P007 453 449\ndatasets/Tartan/office2/office2/Hard/P000 292 281\ndatasets/Tartan/office2/office2/Easy/P006 579 701\ndatasets/Tartan/gascola/gascola/Hard/P002 7 2\ndatasets/Tartan/gascola/gascola/Easy/P003 846 860\ndatasets/Tartan/gascola/gascola/Hard/P004 1724 1723\ndatasets/Tartan/office2/office2/Hard/P009 54 52\ndatasets/Tartan/office2/office2/Easy/P006 605 610\ndatasets/Tartan/gascola/gascola/Easy/P004 1187 1182\ndatasets/Tartan/office2/office2/Hard/P010 410 409\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 12 21\ndatasets/Tartan/gascola/gascola/Easy/P008 141 174\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P016 276 267\ndatasets/Tartan/gascola/gascola/Easy/P008 835 840\ndatasets/Tartan/gascola/gascola/Hard/P004 210 182\ndatasets/Tartan/gascola/gascola/Easy/P005 1483 1487\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 61 64\ndatasets/Tartan/office2/office2/Hard/P008 561 564\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 609 614\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 436 438\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P013 256 240\ndatasets/Tartan/westerndesert/westerndesert/Hard/P004 9 10\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 321 319\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 236 238\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 88 89\ndatasets/Tartan/gascola/gascola/Easy/P007 734 732\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 665 659\ndatasets/Tartan/gascola/gascola/Easy/P004 1111 1121\ndatasets/Tartan/office2/office2/Hard/P008 540 527\ndatasets/Tartan/office2/office2/Hard/P001 25 22\ndatasets/Tartan/gascola/gascola/Hard/P002 5 17\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 429 229\ndatasets/Tartan/gascola/gascola/Easy/P007 1564 1565\ndatasets/Tartan/gascola/gascola/Hard/P009 23 27\ndatasets/Tartan/office2/office2/Hard/P005 102 113\ndatasets/Tartan/westerndesert/westerndesert/Hard/P004 364 366\ndatasets/Tartan/gascola/gascola/Hard/P006 129 122\ndatasets/Tartan/gascola/gascola/Hard/P002 762 764\ndatasets/Tartan/office2/office2/Hard/P000 249 244\ndatasets/Tartan/gascola/gascola/Hard/P006 957 933\ndatasets/Tartan/gascola/gascola/Easy/P004 920 926\ndatasets/Tartan/office2/office2/Easy/P008 981 1007\ndatasets/Tartan/office2/office2/Hard/P010 469 467\ndatasets/Tartan/gascola/gascola/Hard/P008 586 581\ndatasets/Tartan/seasidetown/seasidetown/Hard/P000 254 249\ndatasets/Tartan/office2/office2/Hard/P002 268 267\ndatasets/Tartan/gascola/gascola/Hard/P006 567 575\ndatasets/Tartan/seasidetown/seasidetown/Easy/P009 349 345\ndatasets/Tartan/gascola/gascola/Hard/P004 531 536\ndatasets/Tartan/westerndesert/westerndesert/Easy/P007 142 141\ndatasets/Tartan/office2/office2/Hard/P002 689 687\ndatasets/Tartan/gascola/gascola/Easy/P003 117 96\ndatasets/Tartan/gascola/gascola/Hard/P004 282 279\ndatasets/Tartan/office2/office2/Easy/P003 9 19\ndatasets/Tartan/gascola/gascola/Easy/P001 103 98\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 203 204\ndatasets/Tartan/gascola/gascola/Hard/P001 83 84\ndatasets/Tartan/office2/office2/Hard/P003 1155 1156\ndatasets/Tartan/gascola/gascola/Hard/P008 1234 1236\ndatasets/Tartan/westerndesert/westerndesert/Easy/P006 426 422\ndatasets/Tartan/gascola/gascola/Easy/P004 437 446\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P014 204 215\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 161 152\ndatasets/Tartan/gascola/gascola/Hard/P008 162 182\ndatasets/Tartan/office2/office2/Easy/P011 379 385\ndatasets/Tartan/gascola/gascola/Easy/P005 1042 1055\ndatasets/Tartan/gascola/gascola/Hard/P003 528 526\ndatasets/Tartan/office2/office2/Easy/P008 481 472\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P016 26 36\ndatasets/Tartan/office2/office2/Easy/P008 630 633\ndatasets/Tartan/gascola/gascola/Hard/P004 49 57\ndatasets/Tartan/gascola/gascola/Easy/P004 2615 2620\ndatasets/Tartan/gascola/gascola/Easy/P004 2087 2076\ndatasets/Tartan/gascola/gascola/Hard/P006 749 751\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 89 83\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 121 126\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 631 641\ndatasets/Tartan/gascola/gascola/Easy/P001 226 247\ndatasets/Tartan/gascola/gascola/Easy/P005 475 483\ndatasets/Tartan/gascola/gascola/Hard/P004 1190 1191\ndatasets/Tartan/gascola/gascola/Easy/P007 606 609\ndatasets/Tartan/gascola/gascola/Easy/P008 278 276\ndatasets/Tartan/gascola/gascola/Easy/P007 1909 1917\ndatasets/Tartan/office2/office2/Easy/P005 172 170\ndatasets/Tartan/gascola/gascola/Easy/P004 829 825\ndatasets/Tartan/gascola/gascola/Easy/P006 523 528\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 195 196\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 809 794\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 642 638\ndatasets/Tartan/westerndesert/westerndesert/Easy/P011 69 71\ndatasets/Tartan/westerndesert/westerndesert/Hard/P004 227 225\ndatasets/Tartan/office2/office2/Hard/P006 135 132\ndatasets/Tartan/gascola/gascola/Hard/P008 353 357\ndatasets/Tartan/gascola/gascola/Hard/P005 674 659\ndatasets/Tartan/gascola/gascola/Hard/P007 303 309\ndatasets/Tartan/gascola/gascola/Easy/P003 296 303\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 482 480\ndatasets/Tartan/gascola/gascola/Easy/P007 1092 1077\ndatasets/Tartan/gascola/gascola/Easy/P007 404 409\ndatasets/Tartan/office2/office2/Easy/P011 128 122\ndatasets/Tartan/gascola/gascola/Easy/P004 2135 2139\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 135 138\ndatasets/Tartan/office2/office2/Easy/P004 376 368\ndatasets/Tartan/office2/office2/Easy/P009 858 827\ndatasets/Tartan/gascola/gascola/Hard/P003 290 301\ndatasets/Tartan/gascola/gascola/Hard/P004 1662 1691\ndatasets/Tartan/office2/office2/Easy/P005 509 512\ndatasets/Tartan/office2/office2/Easy/P000 67 78\ndatasets/Tartan/gascola/gascola/Hard/P008 1116 1118\ndatasets/Tartan/gascola/gascola/Easy/P007 757 753\ndatasets/Tartan/gascola/gascola/Hard/P008 346 350\ndatasets/Tartan/office2/office2/Easy/P006 728 725\ndatasets/Tartan/office2/office2/Hard/P008 360 357\ndatasets/Tartan/seasidetown/seasidetown/Easy/P001 269 252\ndatasets/Tartan/gascola/gascola/Easy/P005 219 198\ndatasets/Tartan/office2/office2/Hard/P008 50 51\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P015 361 364\ndatasets/Tartan/gascola/gascola/Easy/P008 1248 1242\ndatasets/Tartan/gascola/gascola/Hard/P006 1131 1126\ndatasets/Tartan/westerndesert/westerndesert/Easy/P010 283 300\ndatasets/Tartan/gascola/gascola/Easy/P007 2201 2198\ndatasets/Tartan/gascola/gascola/Hard/P006 406 427\ndatasets/Tartan/gascola/gascola/Easy/P003 412 404\ndatasets/Tartan/gascola/gascola/Easy/P004 1041 1035\ndatasets/Tartan/gascola/gascola/Hard/P006 1480 1477\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P013 228 211\ndatasets/Tartan/seasidetown/seasidetown/Easy/P007 529 527\ndatasets/Tartan/office2/office2/Hard/P002 501 510\ndatasets/Tartan/westerndesert/westerndesert/Easy/P002 133 142\ndatasets/Tartan/office2/office2/Easy/P006 644 642\ndatasets/Tartan/westerndesert/westerndesert/Easy/P010 290 299\ndatasets/Tartan/gascola/gascola/Easy/P005 1513 1511\ndatasets/Tartan/office2/office2/Easy/P008 595 592\ndatasets/Tartan/gascola/gascola/Hard/P004 1218 1226\ndatasets/Tartan/gascola/gascola/Hard/P008 963 987\ndatasets/Tartan/gascola/gascola/Easy/P007 909 904\ndatasets/Tartan/gascola/gascola/Easy/P006 2087 2058\ndatasets/Tartan/gascola/gascola/Easy/P005 430 398\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P016 315 296\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P013 20 33\ndatasets/Tartan/gascola/gascola/Hard/P004 1781 1797\ndatasets/Tartan/gascola/gascola/Easy/P006 2025 2021\ndatasets/Tartan/gascola/gascola/Hard/P005 1230 1236\ndatasets/Tartan/office2/office2/Easy/P009 56 39\ndatasets/Tartan/gascola/gascola/Hard/P003 481 478\ndatasets/Tartan/westerndesert/westerndesert/Hard/P003 456 458\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 247 238\ndatasets/Tartan/office2/office2/Easy/P008 586 584\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 182 175\ndatasets/Tartan/gascola/gascola/Easy/P004 1027 1014\ndatasets/Tartan/office2/office2/Hard/P005 311 309\ndatasets/Tartan/gascola/gascola/Easy/P005 291 264\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 402 389\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 65 64\ndatasets/Tartan/gascola/gascola/Hard/P008 1138 1147\ndatasets/Tartan/office2/office2/Hard/P004 219 214\ndatasets/Tartan/westerndesert/westerndesert/Hard/P002 807 810\ndatasets/Tartan/gascola/gascola/Hard/P008 308 305\ndatasets/Tartan/office2/office2/Easy/P010 61 84\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 459 465\ndatasets/Tartan/westerndesert/westerndesert/Hard/P003 39 44\ndatasets/Tartan/gascola/gascola/Easy/P003 1046 1034\ndatasets/Tartan/westerndesert/westerndesert/Hard/P004 108 115\ndatasets/Tartan/office2/office2/Easy/P004 206 224\ndatasets/Tartan/gascola/gascola/Hard/P003 332 354\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 603 594\ndatasets/Tartan/gascola/gascola/Hard/P006 1007 1011\ndatasets/Tartan/gascola/gascola/Hard/P008 1256 1249\ndatasets/Tartan/office2/office2/Hard/P009 473 467\ndatasets/Tartan/westerndesert/westerndesert/Hard/P005 225 226\ndatasets/Tartan/seasidetown/seasidetown/Hard/P003 227 229\ndatasets/Tartan/gascola/gascola/Easy/P003 1493 1489\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 985 986\ndatasets/Tartan/gascola/gascola/Easy/P008 845 835\ndatasets/Tartan/office2/office2/Easy/P004 1289 1285\ndatasets/Tartan/westerndesert/westerndesert/Hard/P002 179 174\ndatasets/Tartan/seasidetown/seasidetown/Easy/P000 281 273\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P011 1369 1370\ndatasets/Tartan/office2/office2/Hard/P008 543 546\ndatasets/Tartan/office2/office2/Hard/P002 265 266\ndatasets/Tartan/seasidetown/seasidetown/Easy/P003 273 279\ndatasets/Tartan/office2/office2/Easy/P009 1225 1203\ndatasets/Tartan/office2/office2/Easy/P004 1391 1397\ndatasets/Tartan/gascola/gascola/Easy/P008 912 908\ndatasets/Tartan/office2/office2/Easy/P000 175 180\ndatasets/Tartan/gascola/gascola/Easy/P004 929 912\ndatasets/Tartan/gascola/gascola/Hard/P006 1277 1278\ndatasets/Tartan/office2/office2/Easy/P008 242 239\ndatasets/Tartan/westerndesert/westerndesert/Easy/P006 156 167\ndatasets/Tartan/westerndesert/westerndesert/Easy/P013 512 515\ndatasets/Tartan/seasidetown/seasidetown/Easy/P002 269 110\ndatasets/Tartan/gascola/gascola/Easy/P004 2486 2482\ndatasets/Tartan/office2/office2/Easy/P008 908 909\ndatasets/Tartan/gascola/gascola/Hard/P003 177 178\ndatasets/Tartan/office2/office2/Hard/P009 923 925\ndatasets/Tartan/gascola/gascola/Hard/P006 990 986\ndatasets/Tartan/gascola/gascola/Hard/P004 1792 1801\ndatasets/Tartan/gascola/gascola/Easy/P008 723 728\ndatasets/Tartan/gascola/gascola/Easy/P006 2224 2227\ndatasets/Tartan/gascola/gascola/Easy/P007 373 388\ndatasets/Tartan/gascola/gascola/Hard/P006 80 45\ndatasets/Tartan/office2/office2/Hard/P005 197 195\ndatasets/Tartan/westerndesert/westerndesert/Hard/P000 193 196\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 486 485\ndatasets/Tartan/gascola/gascola/Hard/P004 1154 1153\ndatasets/Tartan/gascola/gascola/Easy/P004 2359 2352\ndatasets/Tartan/westerndesert/westerndesert/Hard/P005 46 91\ndatasets/Tartan/westerndesert/westerndesert/Hard/P006 154 152\ndatasets/Tartan/gascola/gascola/Hard/P005 104 97\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 193 197\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 547 552\ndatasets/Tartan/office2/office2/Easy/P004 1363 1377\ndatasets/Tartan/westerndesert/westerndesert/Easy/P009 13 30\ndatasets/Tartan/office2/office2/Hard/P004 328 327\ndatasets/Tartan/seasidetown/seasidetown/Easy/P008 219 218\ndatasets/Tartan/westerndesert/westerndesert/Easy/P009 105 109\ndatasets/Tartan/office2/office2/Hard/P009 906 904\ndatasets/Tartan/office2/office2/Easy/P005 12 15\ndatasets/Tartan/gascola/gascola/Easy/P004 646 645\ndatasets/Tartan/office2/office2/Easy/P004 1318 1321\ndatasets/Tartan/gascola/gascola/Easy/P005 86 92\ndatasets/Tartan/office2/office2/Easy/P009 1500 1497\ndatasets/Tartan/gascola/gascola/Hard/P004 958 955\ndatasets/Tartan/office2/office2/Easy/P009 63 77\ndatasets/Tartan/gascola/gascola/Easy/P007 878 893\ndatasets/Tartan/office2/office2/Easy/P008 888 886\ndatasets/Tartan/office2/office2/Easy/P008 1048 1044\ndatasets/Tartan/gascola/gascola/Easy/P005 1155 1152\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 495 497\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 64 61\ndatasets/Tartan/gascola/gascola/Easy/P005 1197 1202\ndatasets/Tartan/gascola/gascola/Hard/P008 830 828\ndatasets/Tartan/gascola/gascola/Easy/P004 309 313\ndatasets/Tartan/gascola/gascola/Easy/P006 2082 2098\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 1004 1007\ndatasets/Tartan/gascola/gascola/Easy/P005 1505 1509\ndatasets/Tartan/gascola/gascola/Hard/P006 1433 1439\ndatasets/Tartan/gascola/gascola/Hard/P000 155 145\ndatasets/Tartan/office2/office2/Easy/P011 124 120\ndatasets/Tartan/office2/office2/Hard/P010 377 376\ndatasets/Tartan/westerndesert/westerndesert/Easy/P012 88 91\ndatasets/Tartan/gascola/gascola/Easy/P003 434 426\ndatasets/Tartan/office2/office2/Hard/P001 77 73\ndatasets/Tartan/office2/office2/Easy/P006 238 259\ndatasets/Tartan/office2/office2/Easy/P000 151 146\ndatasets/Tartan/gascola/gascola/Easy/P007 1438 1432\ndatasets/Tartan/westerndesert/westerndesert/Hard/P004 23 24\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P010 1529 1525\ndatasets/Tartan/gascola/gascola/Hard/P004 1285 1286\ndatasets/Tartan/seasidetown/seasidetown/Easy/P003 146 145\ndatasets/Tartan/gascola/gascola/Easy/P008 1182 1188\ndatasets/Tartan/office2/office2/Easy/P004 225 237\ndatasets/Tartan/seasidetown/seasidetown/Hard/P003 39 331\ndatasets/Tartan/westerndesert/westerndesert/Hard/P007 0 1\ndatasets/Tartan/office2/office2/Easy/P011 671 684\ndatasets/Tartan/gascola/gascola/Hard/P003 490 491\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 953 962\ndatasets/Tartan/westerndesert/westerndesert/Easy/P008 261 118\ndatasets/Tartan/westerndesert/westerndesert/Easy/P007 123 119\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P018 245 243\ndatasets/Tartan/westerndesert/westerndesert/Hard/P004 413 421\ndatasets/Tartan/office2/office2/Easy/P006 495 491\ndatasets/Tartan/gascola/gascola/Easy/P008 158 169\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P012 192 195\ndatasets/Tartan/gascola/gascola/Easy/P001 0 8\ndatasets/Tartan/seasidetown/seasidetown/Easy/P005 578 582\ndatasets/Tartan/seasonsforest_winter/seasonsforest_winter/Hard/P017 143 136\ndatasets/Tartan/gascola/gascola/Hard/P002 484 492\ndatasets/Tartan/gascola/gascola/Easy/P008 360 355\ndatasets/Tartan/office2/office2/Easy/P006 32 25\ndatasets/Tartan/gascola/gascola/Hard/P007 361 343\ndatasets/Tartan/office2/office2/Hard/P010 41 46\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 451 452\ndatasets/Tartan/seasidetown/seasidetown/Hard/P002 795 798\ndatasets/Tartan/seasidetown/seasidetown/Easy/P003 20 24\ndatasets/Tartan/gascola/gascola/Hard/P002 24 33\ndatasets/Tartan/office2/office2/Easy/P011 558 545\ndatasets/Tartan/gascola/gascola/Easy/P006 2382 2380\ndatasets/Tartan/office2/office2/Hard/P008 205 221\ndatasets/Tartan/gascola/gascola/Hard/P004 640 634\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 367 377\ndatasets/Tartan/westerndesert/westerndesert/Easy/P006 410 403\ndatasets/Tartan/office2/office2/Hard/P003 76 75\ndatasets/Tartan/gascola/gascola/Hard/P007 516 525\ndatasets/Tartan/seasidetown/seasidetown/Hard/P004 409 378\ndatasets/Tartan/westerndesert/westerndesert/Easy/P004 270 266\ndatasets/Tartan/office2/office2/Easy/P009 552 547\ndatasets/Tartan/gascola/gascola/Easy/P004 1496 1493\ndatasets/Tartan/office2/office2/Easy/P008 520 532\ndatasets/Tartan/gascola/gascola/Easy/P006 1446 1416\ndatasets/Tartan/seasidetown/seasidetown/Easy/P006 440 445\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/registration/demo.py",
    "content": "import sys\nsys.path.append('../core')\n\nimport argparse\nimport torch\nimport cv2\nimport numpy as np\n\nfrom viz import sim3_visualization\nfrom lietorch import SO3, SE3, Sim3\nfrom networks.sim3_net import Sim3Net\n\ndef normalize_images(images):\n    images = images[:, :, [2,1,0]]\n    mean = torch.as_tensor([0.485, 0.456, 0.406], device=images.device)\n    std = torch.as_tensor([0.229, 0.224, 0.225], device=images.device)\n    return (images/255.0).sub_(mean[:, None, None]).div_(std[:, None, None])\n\ndef load_example(i=0):\n    \"\"\" get demo example \"\"\"\n    DEPTH_SCALE = 5.0\n    if i==0:\n        image1 = cv2.imread('assets/image1.png')\n        image2 = cv2.imread('assets/image2.png')\n        depth1 = np.load('assets/depth1.npy') / DEPTH_SCALE\n        depth2 = np.load('assets/depth2.npy') / DEPTH_SCALE\n    \n    elif i==1:\n        image1 = cv2.imread('assets/image3.png')\n        image2 = cv2.imread('assets/image4.png')\n        depth1 = np.load('assets/depth3.npy') / DEPTH_SCALE\n        depth2 = np.load('assets/depth4.npy') / DEPTH_SCALE\n\n    images = np.stack([image1, image2], 0)\n    images = torch.from_numpy(images).permute(0,3,1,2)\n\n    depths = np.stack([depth1, depth2], 0)\n    depths = torch.from_numpy(depths).float()\n\n    intrinsics = np.array([320.0, 320.0, 320.0, 240.0])\n    intrinsics = np.tile(intrinsics[None], (2,1))\n    intrinsics = torch.from_numpy(intrinsics).float()\n\n    return images[None].cuda(), depths[None].cuda(), intrinsics[None].cuda()\n\n\n@torch.no_grad()\ndef demo(model, index=0):\n\n    images, depths, intrinsics = load_example(index)\n\n    # initial transformation estimate\n    if args.transformation == 'SE3':\n        Gs = SE3.Identity(1, 2, device='cuda')\n\n    elif args.transformation == 'Sim3':\n        Gs = Sim3.Identity(1, 2, device='cuda')\n        depths[:,0] *= 2**(2*torch.rand(1) - 1.0).cuda()\n\n    images1 = normalize_images(images)\n    ests, _ = model(Gs, images1, depths, intrinsics, num_steps=12)\n\n    # only care about last transformation\n    Gs = ests[-1] \n    T = Gs[:,0] * Gs[:,1].inv()\n    \n    T = T[0].matrix().double().cpu().numpy()\n    sim3_visualization(T, images, depths, intrinsics)\n\n\nif __name__ == '__main__':\n    parser = argparse.ArgumentParser()\n    parser.add_argument('--transformation', default='SE3', help='checkpoint to restore')\n    parser.add_argument('--ckpt', help='checkpoint to restore')\n    args = parser.parse_args()\n\n    model = Sim3Net(args)\n    model.load_state_dict(torch.load(args.ckpt))\n\n    model.cuda()\n    model.eval()\n\n    # run two demos\n    demo(model, 0)\n    demo(model, 1)\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/registration/main.py",
    "content": "import sys\nsys.path.append('../core')\n\nimport argparse\nimport torch\nimport cv2\nimport numpy as np\nfrom collections import OrderedDict\n\nimport torch.optim as optim\nimport torch.nn.functional as F\nfrom torch.utils.data import DataLoader\nfrom data_readers.tartan import TartanAir, TartanAirTest\n\nfrom lietorch import SO3, SE3, Sim3\nfrom geom.losses import *\n\n# network\nfrom networks.sim3_net import Sim3Net\nfrom logger import Logger\n\n\ndef show_image(image):\n    image = image.permute(1, 2, 0).cpu().numpy()\n    cv2.imshow('image', image / 255.0)\n    cv2.waitKey()\n\ndef normalize_images(images):\n    images = images[:, :, [2,1,0]]\n    mean = torch.as_tensor([0.485, 0.456, 0.406], device=images.device)\n    std = torch.as_tensor([0.229, 0.224, 0.225], device=images.device)\n    return (images/255.0).sub_(mean[:, None, None]).div_(std[:, None, None])\n\n@torch.no_grad()\ndef evaluate(model):\n    \"\"\" evaluate trained model \"\"\"\n\n    model.cuda()\n    model.eval()\n\n    R_THRESHOLD = 0.1\n    T_THRESHOLD = 0.01\n    S_THRESHOLD = 0.01\n\n    model.eval()\n    db = TartanAirTest()\n    test_loader = DataLoader(db, batch_size=1, shuffle=False, num_workers=4)\n\n    # random scales, make sure they are the same every time\n    from numpy.random import default_rng\n    rng = default_rng(1234)\n    scales = 2 ** rng.uniform(-1.0, 1.0, 2000)\n    scales = scales.astype(np.float32)\n\n    metrics = {'t': [], 'r': [], 's': []}\n    for i_batch, item in enumerate(test_loader):\n        images, poses, depths, intrinsics = [x.to('cuda') for x in item]\n\n        # convert poses w2c -> c2w\n        Ps = SE3(poses).inv()\n        batch, num = images.shape[:2]\n\n        if args.transformation == 'SE3':\n            Gs = SE3.Identity(Ps.shape, device='cuda')\n\n        elif args.transformation == 'Sim3':\n            Ps = Sim3(Ps)\n            Gs = Sim3.Identity(Ps.shape, device='cuda')\n\n            s = torch.as_tensor(scales[i_batch]).cuda().unsqueeze(0)\n            phi = torch.zeros(batch, num, 7, device='cuda')\n            phi[:,0,6] = s.log()\n\n            Ps = Sim3.exp(phi) * Ps\n            depths[:,0] *= s[:,None,None]\n\n        images = normalize_images(images)\n        Gs, _ = model(Gs, images, depths, intrinsics, num_steps=16)\n\n        Gs = Gs[-1]\n        dP = Ps[:,1] * Ps[:,0].inv()\n        dG = Gs[:,1] * Gs[:,0].inv()\n\n        dE = Sim3(dP.inv() * dG)\n        r_err, t_err, s_err = pose_metrics(dE)\n\n        t_err = t_err * TartanAir.DEPTH_SCALE\n\n        metrics['t'].append(t_err.item())\n        metrics['r'].append(r_err.item())\n        metrics['s'].append(s_err.item())\n\n    rlist = np.array(metrics['r'])\n    tlist = np.array(metrics['t'])\n    slist = np.array(metrics['s'])\n    \n    r_all = np.count_nonzero(rlist < R_THRESHOLD) / len(metrics['r'])\n    t_all = np.count_nonzero(tlist < T_THRESHOLD) / len(metrics['t'])\n    s_all = np.count_nonzero(slist < S_THRESHOLD) / len(metrics['s'])\n\n    print(\"Rotation Acc: \", r_all)\n    print(\"Translation Acc: \", t_all)\n    print(\"Scale Acc: \", s_all)\n\n\ndef train(args):\n    \"\"\" Test to make sure project transform correctly maps points \"\"\"\n\n    model = Sim3Net(args)\n    model.cuda()\n    model.train()\n\n    if args.ckpt is not None:\n        model.load_state_dict(torch.load(args.ckpt))\n\n    db = TartanAir(mode='training', n_frames=2, do_aug=True, fmin=8.0, fmax=100.0)\n    train_loader = DataLoader(db, batch_size=args.batch, shuffle=True, num_workers=4)\n\n    optimizer = optim.Adam(model.parameters(), lr=args.lr, weight_decay=1e-5)\n    scheduler = optim.lr_scheduler.OneCycleLR(optimizer, \n        args.lr, 100000, pct_start=0.01, cycle_momentum=False)\n\n    from collections import OrderedDict\n    graph = OrderedDict()\n    graph[0] = [1]\n    graph[1] = [0]\n\n    logger = Logger(args.name, scheduler)\n    should_keep_training = True\n    total_steps = 0\n\n    while should_keep_training:\n        for i_batch, item in enumerate(train_loader):\n            optimizer.zero_grad()\n            images, poses, depths, intrinsics = [x.to('cuda') for x in item]\n            \n            # convert poses w2c -> c2w\n            Ps = SE3(poses).inv()\n            batch, num = images.shape[:2]\n\n            if args.transformation == 'SE3':\n                Gs = SE3.Identity(Ps.shape, device='cuda')\n\n            elif args.transformation == 'Sim3':\n                Ps = Sim3(Ps)\n                Gs = Sim3.Identity(Ps.shape, device='cuda')\n\n                s = 2**(2*torch.rand(batch) - 1.0).cuda()\n                phi = torch.zeros(batch, num, 7, device='cuda')\n                phi[:,0,6] = s.log()\n\n                Ps = Sim3.exp(phi) * Ps\n                depths[:,0] *= s[:,None,None]\n\n            images = normalize_images(images)\n            Gs, residuals = model(Gs, images, depths, intrinsics, num_steps=args.iters)\n\n            geo_loss, geo_metrics = geodesic_loss(Ps, Gs, graph)\n            res_loss, res_metrics = residual_loss(residuals)\n\n            metrics = {}\n            metrics.update(geo_metrics)\n            metrics.update(res_metrics)\n\n            loss = args.w1 * geo_loss + args.w2 * res_loss\n            loss.backward()\n            \n            torch.nn.utils.clip_grad_norm_(model.parameters(), args.clip)\n            optimizer.step()\n            scheduler.step()\n            \n            logger.push(metrics)\n            total_steps += 1\n\n            if total_steps % 5000 == 0:\n                PATH = 'checkpoints/%s_%06d.pth' % (args.name, total_steps)\n                torch.save(model.state_dict(), PATH)\n\n                model.train()\n\n    return model\n                \n\nif __name__ == '__main__':\n    parser = argparse.ArgumentParser()\n    parser.add_argument('--name', default='bla', help='name your experiment')\n    parser.add_argument('--transformation', default='SE3', help='checkpoint to restore')\n    parser.add_argument('--ckpt', help='checkpoint to restore')\n    parser.add_argument('--train', action='store_true')\n\n    parser.add_argument('--batch', type=int, default=4)\n    parser.add_argument('--iters', type=int, default=8)\n    parser.add_argument('--lr', type=float, default=0.00025)\n    parser.add_argument('--clip', type=float, default=2.5)\n\n    parser.add_argument('--w1', type=float, default=10.0)\n    parser.add_argument('--w2', type=float, default=0.1)\n\n\n    args = parser.parse_args()\n\n    if args.train:\n        import os\n        if not os.path.isdir('checkpoints'):\n            os.mkdir('checkpoints')\n\n        model = train(args)\n    \n    else:\n        model = Sim3Net(args)\n        model.load_state_dict(torch.load(args.ckpt))\n\n    evaluate(model)\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/registration/readme.md",
    "content": "## SE3 / Sim3 Registration\nEstimate the 3D transformation between two RGB-D frames\n\n<img src=\"assets/registration.gif\" width=\"480\">\n\n### Models\n| Model     | Rot. Acc. | Tr. Acc. | Scale Acc. |\n| --------- | --------- | -------- | ---------- |\n| [se3.pth](https://drive.google.com/file/d/17pgeY5m-GXnrY3oFLPRaIrTZYvae_l9u/view?usp=sharing)   | 91.90         | 77.70 | -     |\n| [sim3.pth](https://drive.google.com/file/d/1LMnKND_4DAmd9DMTSKdz_zAoCgja6X43/view?usp=sharing)  | 93.45         | 76.05 | 98.70 |\n\nfor thresholds 0.1 deg. rotation error, 1cm translation error, and 1% scale error.\n\n### Demo \nDownload one of the models to run the demo (requres Open3D)\n```python\npython demo.py --transformation=SE3 --ckpt=se3.pth\npython demo.py --transformation=Sim3 --ckpt=sim3.pth\n```\n\n### Training and Evaluation\nTraining and evaluation is performed on the [TartanAir](https://theairlab.org/tartanair-dataset/) (only depth_left and image_left need to be downloaded). Note: our dataloader computes the optical flow between every pair of frames which can take several hours on the first run. However, this result is cached so that future loads will only take a few seconds.\n\nThe training script expects the dataset to be in the directory datasets/TartanAir.\n\nTo train a Sim3 network:\n```python\npython main.py --train --transformation=Sim3 --name=sim3\n```\nA trained model can then be evaluated:\n```python\npython main.py --transformation=Sim3 --ckpt=sim3.pth\n```\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/registration/viz.py",
    "content": "import sys\nsys.path.append('../core')\n\nimport argparse\nimport torch\nimport scipy\nimport numpy as np\n\nimport geom.projective_ops as pops\nimport open3d as o3d\n\ndef make_point_cloud(image, depth, intrinsics, max_depth=5.0):\n    \"\"\" create a point cloud \"\"\"\n    colors = image.permute(1,2,0).view(-1,3)\n    colors = colors[...,[2,1,0]] / 255.0\n    clr = colors.cpu().numpy()\n\n    inv_depth = 1.0 / depth[None,None]\n    points = pops.iproj(inv_depth, intrinsics[None,None])\n    points = (points[..., :3] / points[..., 3:]).view(-1,3)\n    pts = points.cpu().numpy()\n\n    # open3d point cloud\n    pc = o3d.geometry.PointCloud()\n\n    keep = pts[:,2] < max_depth\n    pc.points = o3d.utility.Vector3dVector(pts[keep])\n    pc.colors = o3d.utility.Vector3dVector(clr[keep])\n\n    return pc\n\ndef set_camera_pose(vis):\n    \"\"\" set initial camera position \"\"\"\n    cam = vis.get_view_control().convert_to_pinhole_camera_parameters()\n\n    cam.extrinsic = np.array(\n        [[ 0.91396544,  0.1462376,  -0.37852575, 0.94374719],\n         [-0.13923432,  0.98919177,  0.04597225,  1.01177687],\n         [ 0.38115743,  0.01068673,  0.92444838,  3.35964868],\n         [ 0.,          0.,          0.,          1.        ]])\n    \n    vis.get_view_control().convert_from_pinhole_camera_parameters(cam)\n\n\ndef sim3_visualization(T, images, depths, intrinsics):\n    \"\"\" convert depth to open3d point clouds \"\"\"\n\n    images = images.squeeze(0)\n    depths = depths.squeeze(0)\n    intrinsics = intrinsics.squeeze(0)\n\n    pc1 = make_point_cloud(images[0], depths[0], intrinsics[0])\n    pc2 = make_point_cloud(images[1], depths[1], intrinsics[1])\n\n    sim3_visualization.index = 1\n    sim3_visualization.pc2 = pc2\n\n    NUM_STEPS = 100\n    dt = scipy.linalg.logm(T) / NUM_STEPS\n    dT = scipy.linalg.expm(dt)\n    sim3_visualization.transform = dT\n\n    def animation_callback(vis):\n        sim3_visualization.index += 1\n\n        pc2 = sim3_visualization.pc2\n        if sim3_visualization.index >= NUM_STEPS and \\\n                sim3_visualization.index < 2*NUM_STEPS:\n            pc2.transform(sim3_visualization.transform)\n\n            vis.update_geometry(pc2)\n            vis.poll_events()\n            vis.update_renderer()\n\n    vis = o3d.visualization.Visualizer()\n    vis.register_animation_callback(animation_callback)\n    vis.create_window(height=540, width=960)\n\n    vis.add_geometry(pc1)\n    vis.add_geometry(pc2)\n\n    vis.get_render_option().load_from_json(\"assets/renderoption.json\")\n    set_camera_pose(vis)\n\n    print(\"Press q to move to next example\")\n    vis.run()\n    vis.destroy_window()\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/rgbdslam/assets/renderoption.json",
    "content": "{\n\t\"background_color\" : [ 1, 1, 1 ],\n\t\"class_name\" : \"RenderOption\",\n\t\"default_mesh_color\" : [ 0.69999999999999996, 0.69999999999999996, 0.69999999999999996 ],\n\t\"image_max_depth\" : 3000,\n\t\"image_stretch_option\" : 0,\n\t\"interpolation_option\" : 0,\n\t\"light0_color\" : [ 1, 1, 1 ],\n\t\"light0_diffuse_power\" : 0.66000000000000003,\n\t\"light0_position\" : [ 0, 0, 2 ],\n\t\"light0_specular_power\" : 0.20000000000000001,\n\t\"light0_specular_shininess\" : 100,\n\t\"light1_color\" : [ 1, 1, 1 ],\n\t\"light1_diffuse_power\" : 0.66000000000000003,\n\t\"light1_position\" : [ 0, 0, 2 ],\n\t\"light1_specular_power\" : 0.20000000000000001,\n\t\"light1_specular_shininess\" : 100,\n\t\"light2_color\" : [ 1, 1, 1 ],\n\t\"light2_diffuse_power\" : 0.66000000000000003,\n\t\"light2_position\" : [ 0, 0, -2 ],\n\t\"light2_specular_power\" : 0.20000000000000001,\n\t\"light2_specular_shininess\" : 100,\n\t\"light3_color\" : [ 1, 1, 1 ],\n\t\"light3_diffuse_power\" : 0.66000000000000003,\n\t\"light3_position\" : [ 0, 0, -2 ],\n\t\"light3_specular_power\" : 0.20000000000000001,\n\t\"light3_specular_shininess\" : 100,\n\t\"light_ambient_color\" : [ 0, 0, 0 ],\n\t\"light_on\" : true,\n\t\"mesh_color_option\" : 1,\n\t\"mesh_shade_option\" : 0,\n\t\"mesh_show_back_face\" : false,\n\t\"mesh_show_wireframe\" : false,\n\t\"point_color_option\" : 9,\n\t\"point_show_normal\" : false,\n\t\"point_size\" : 2,\n\t\"show_coordinate_frame\" : false,\n\t\"version_major\" : 1,\n\t\"version_minor\" : 0\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/rgbdslam/demo.py",
    "content": "import sys\nsys.path.append('../core')\n\nfrom tqdm import tqdm\nimport numpy as np\nimport torch\nimport cv2\nimport os\n\nfrom viz import SLAMFrontend\nfrom lietorch import SE3\nfrom networks.slam_system import SLAMSystem\nfrom data_readers import factory\n\n\ndef show_image(image):\n    image = image.permute(1, 2, 0).cpu().numpy()\n    cv2.imshow('image', image / 255.0)\n    cv2.waitKey(10)\n\ndef evaluate(poses_gt, poses_est):\n    from rgbd_benchmark.evaluate_ate import evaluate_ate\n\n    poses_gt = poses_gt.cpu().numpy()\n    poses_est = poses_est.cpu().numpy()\n\n    N = poses_gt.shape[0]\n    poses_gt = dict([(i, poses_gt[i]) for i in range(N)])\n    poses_est = dict([(i, poses_est[i]) for i in range(N)])\n\n    results = evaluate_ate(poses_gt, poses_est)\n    print(results)\n\n\n@torch.no_grad()\ndef run_slam(tracker, datapath, frame_rate=8.0):\n    \"\"\" run slam over full sequence \"\"\"\n\n    torch.multiprocessing.set_sharing_strategy('file_system')\n    stream = factory.create_datastream(args.datapath, frame_rate=frame_rate)\n\n    # start the frontend thread\n    if args.viz:\n        frontend = SLAMFrontend().start()\n        tracker.set_frontend(frontend)\n\n    # store groundtruth poses for evaluation\n    poses_gt = []\n\n    for (tstamp, image, depth, pose, intrinsics) in tqdm(stream):\n        tracker.track(tstamp, image[None].cuda(), depth.cuda(), intrinsics.cuda())\n        poses_gt.append(pose)\n\n        if args.viz:\n            show_image(image[0])\n            frontend.update_pose(tstamp, pose[0], gt=True)\n\n    # global optimization / loop closure\n    if args.go:\n        tracker.global_refinement()\n\n    poses_gt = torch.cat(poses_gt, 0)\n    poses_est = tracker.raw_poses()\n    evaluate(poses_gt, poses_est) \n        \n\nif __name__ == '__main__':\n    import argparse\n    parser = argparse.ArgumentParser()\n    parser.add_argument('--datapath', help='path to video for slam')\n    parser.add_argument('--ckpt', help='saved network weights')\n    parser.add_argument('--viz', action='store_true', help='run visualization frontent')\n    parser.add_argument('--go', action='store_true', help='use global optimization')\n    parser.add_argument('--frame_rate', type=float, default=8.0, help='frame rate')\n    args = parser.parse_args()\n\n    # initialize tracker / load weights\n    tracker = SLAMSystem(args)\n    tracker.load_state_dict(torch.load(args.ckpt))\n    tracker.eval()\n    tracker.cuda()\n\n    run_slam(tracker, args.datapath, args.frame_rate)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/rgbdslam/evaluate.py",
    "content": "import sys\nsys.path.append('../core')\n\nfrom tqdm import tqdm\nimport numpy as np\nimport torch\nimport cv2\nimport os\n\nfrom lietorch import SE3\nfrom networks.slam_system import SLAMSystem\nfrom data_readers import factory\n\ndef evaluate(poses_gt, poses_est):\n    from rgbd_benchmark.evaluate_ate import evaluate_ate\n\n    poses_gt = poses_gt.cpu().numpy()\n    poses_est = poses_est.cpu().numpy()\n\n    N = poses_gt.shape[0]\n    poses_gt = dict([(i, poses_gt[i]) for i in range(N)])\n    poses_est = dict([(i, poses_est[i]) for i in range(N)])\n\n    results = evaluate_ate(poses_gt, poses_est)\n    print(results)\n    return results['absolute_translational_error.rmse']\n\n@torch.no_grad()\ndef run_slam(tracker, datapath, global_optimization=False, frame_rate=3):\n    \"\"\" run slam over full sequence \"\"\"\n\n    torch.multiprocessing.set_sharing_strategy('file_system')\n    stream = factory.create_datastream(datapath, frame_rate=frame_rate)\n\n    # store groundtruth poses for evaluatino\n    poses_gt = []\n    for (tstamp, image, depth, pose, intrinsics) in tqdm(stream):\n        tracker.track(tstamp, image[None].cuda(), depth.cuda(), intrinsics.cuda())\n        poses_gt.append(pose)\n\n    if global_optimization:\n        tracker.global_refinement()\n\n    poses_gt = torch.cat(poses_gt, 0)\n    poses_est = tracker.raw_poses()   \n\n    ate = evaluate(poses_gt, poses_est) \n    return ate\n\ndef run_evaluation(ckpt, frame_rate=8.0):\n    validation_scenes = [\n        'rgbd_dataset_freiburg1_360',\n        'rgbd_dataset_freiburg1_desk',\n        'rgbd_dataset_freiburg1_desk2',\n        'rgbd_dataset_freiburg1_floor',\n        'rgbd_dataset_freiburg1_plant',\n        'rgbd_dataset_freiburg1_room',\n        'rgbd_dataset_freiburg1_rpy',\n        'rgbd_dataset_freiburg1_teddy',\n        'rgbd_dataset_freiburg1_xyz',\n    ]\n\n    results = {}\n    for scene in validation_scenes:\n        # initialize tracker / load weights\n        tracker = SLAMSystem(None)\n        tracker.load_state_dict(torch.load(ckpt))\n        tracker.eval()\n        tracker.cuda()\n        \n        datapath = os.path.join('datasets/TUM-RGBD', scene)\n        results[scene] = run_slam(tracker, datapath, \n            global_optimization=args.go, frame_rate=frame_rate)\n\n    print(\"Aggregate Results: \")\n    for scene in results:\n        print(scene, results[scene])\n\n    print(\"MEAN: \", np.mean([results[key] for key in results]))\n\nif __name__ == '__main__':\n    import argparse\n    parser = argparse.ArgumentParser()\n    parser.add_argument('--ckpt', help='saved network weights')\n    parser.add_argument('--frame_rate', type=float, default=8.0, help='frame rate')\n    parser.add_argument('--go', action='store_true', help='use global optimization')\n    args = parser.parse_args()\n\n    run_evaluation(args.ckpt, frame_rate=args.frame_rate)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/rgbdslam/readme.md",
    "content": "## RGB-D SLAM / VO\n\n\n<img src=\"assets/floor.png\" alt=\"floor\" height=\"280\"/> <img src=\"assets/room.png\" alt=\"room\" height=\"280\"/>\n\n\n### Pretrained Model\n\nAbsolute Trajectory Error (ATE) on all freiburg1 sequences. The default model acts as a visual odometry system (no loop closure). The model rgbdslam.pth + go performs global optimization at the end of tracking to correct for drift.\n\n| Model  | 360 | desk | desk2 | floor | plant | room | rpy | teddy | xyz | avg |\n| -----  | --- | ---- | ----- | ----- | ----- | ---- | --- | ----- | --- | --- |\n| DeepV2D | 0.072 | 0.069 | 0.074 | 0.317 | 0.046 | 0.213 | 0.082 | 0.114 | 0.028 | 0.113 |\n| [lietorch_rgbdslam.pth](https://drive.google.com/file/d/1SVQTFCchZuhFeSucS5jLeNbOWyff4BA8/view?usp=sharing) | 0.076 | 0.045 | 0.054 | 0.057 | 0.032 | 0.143 | 0.064 | 0.092 | 0.033 | 0.066 |\n| [lietorch_rgbdslam.pth](https://drive.google.com/file/d/1SVQTFCchZuhFeSucS5jLeNbOWyff4BA8/view?usp=sharing) + go | 0.047 | 0.018 | 0.023 | 0.017 | 0.015 | 0.029 | 0.019 | 0.030 | 0.009 | 0.023 |\n\n### Demo\nRequires a GPU with at least 8gb of memory. First download a sequence from the [TUM-RGBD dataset](https://vision.in.tum.de/data/datasets/rgbd-dataset/download), then run the demo. You can interact with the Open3D window during tracking.\n\n```python\npython demo.py --ckpt=lietorch_rgbdslam.pth --datapath=<sequence path> --frame_rate=8.0 --go --viz\n```\n\nThe `--frame_rate` flag determines the rate images are subsampled from the video (e.g `--frame_rate=8.0` subsamples the video at a rate of 8 fps). With a RTX-3090 GPU and visualization disabled, `--frame_rate <= 8.0` gives real-time performance.\n\n\n### Evaluation\nAssuming all TUM-RGBD sequences have been download, a trained model can be evaluated on the TUM-RGBD dataset\n```\npython evaluate.py --ckpt=rgbdslam.pth --datapath=<tum-rgbd root> --go --frame_rate=8.0\n```\n\n### Training\nWe provide data_loaders for [NYUv2](https://cs.nyu.edu/~silberman/datasets/nyu_depth_v2.html), [ScanNet](http://www.scan-net.org/), [ETH3D-SLAM](https://www.eth3d.net/slam_datasets), and [TartanAir](https://theairlab.org/tartanair-dataset/). The dataloaders will work directly on ScanNet, ETH3D, and TartanAir. For NYUv2, you will need to first extract the depths and images from the raw format then run ORB-SLAM2 to generate psuedo-groundtruth poses. Send me an email (Zachary Teed) if you need a link to the preprocessed NYU data.\n\nYou can train on any subset of the datasets by listing their keys {`nyu`, `scannet`, `eth`, `tartan`}. The provided models are trained on scannet and nyu. Note: our dataloader computes the optical flow between every pair of frames which can take several hours on the first run. However, this result is cached so that future loads will only take a few seconds. The default training setttings require a GPU with 24 Gb of memory.\n\n```\npython train.py --batch=3 --iters=12 --lr=0.00025 --name nyu_scannet_eth_v2 --datasets nyu scannet\n```\n\n#### Training on your own dataset\nAdditional datasets can easily be added by subclassing `RGBDDataset`, see `nyu2.py` or `scannet.py` as examples. To verify the dataloading is correct, you can use the `reprojection_test.py` script to verify that the warped images align.\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/rgbdslam/reprojection_test.py",
    "content": "import sys\nsys.path.append('../core')\n\nimport torch\nimport cv2\nimport numpy as np\n\nfrom torch.utils.data import DataLoader\nfrom data_readers.factory import dataset_factory\n\nfrom lietorch import SO3, SE3, Sim3\nimport geom.projective_ops as pops\nfrom geom.sampler_utils import bilinear_sampler\n\ndef show_image(image):\n    if len(image.shape) == 3:\n        image = image.permute(1, 2, 0)\n    image = image.cpu().numpy()\n    cv2.imshow('image', image / 255.0)\n    cv2.waitKey()\n\ndef reproj_test(args, N=2):\n    \"\"\" Test to make sure project transform correctly maps points \"\"\"\n\n    db = dataset_factory(args.datasets, n_frames=N)\n    train_loader = DataLoader(db, batch_size=1, shuffle=True, num_workers=0)\n\n    for item in train_loader:\n        images, poses, depths, intrinsics = [x.to('cuda') for x in item]        \n        poses = SE3(poses).inv()\n        disps = 1.0 / depths\n\n        coords, _ = pops.projective_transform(poses, disps, intrinsics, [0], [1])\n        imagew = bilinear_sampler(images[:,[1]], coords[...,[0,1]])\n\n        # these two image should show camera motion\n        show_image(images[0,0])\n        show_image(images[0,1])\n\n        # these two images should show the camera motion removed by reprojection / warping\n        show_image(images[0,0])\n        show_image(imagew[0,0])\n\n\nif __name__ == '__main__':\n    import argparse\n    parser = argparse.ArgumentParser()\n    parser.add_argument('--datasets', nargs='+', help='lists of datasets for training')\n    args = parser.parse_args()\n\n    reproj_test(args)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/rgbdslam/rgbd_benchmark/__init__.py",
    "content": ""
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/rgbdslam/rgbd_benchmark/associate.py",
    "content": "#!/usr/bin/python\n# Software License Agreement (BSD License)\n#\n# Copyright (c) 2013, Juergen Sturm, TUM\n# All rights reserved.\n#\n# Redistribution and use in source and binary forms, with or without\n# modification, are permitted provided that the following conditions\n# are met:\n#\n#  * Redistributions of source code must retain the above copyright\n#    notice, this list of conditions and the following disclaimer.\n#  * Redistributions in binary form must reproduce the above\n#    copyright notice, this list of conditions and the following\n#    disclaimer in the documentation and/or other materials provided\n#    with the distribution.\n#  * Neither the name of TUM nor the names of its\n#    contributors may be used to endorse or promote products derived\n#    from this software without specific prior written permission.\n#\n# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n# \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n# POSSIBILITY OF SUCH DAMAGE.\n#\n# Requirements: \n# sudo apt-get install python-argparse\n\n\"\"\"\nThe Kinect provides the color and depth images in an un-synchronized way. This means that the set of time stamps from the color images do not intersect with those of the depth images. Therefore, we need some way of associating color images to depth images.\n\nFor this purpose, you can use the ''associate.py'' script. It reads the time stamps from the rgb.txt file and the depth.txt file, and joins them by finding the best matches.\n\"\"\"\n\nimport argparse\nimport sys\nimport os\nimport numpy\n\n\ndef read_file_list(filename):\n    \"\"\"\n    Reads a trajectory from a text file. \n    \n    File format:\n    The file format is \"stamp d1 d2 d3 ...\", where stamp denotes the time stamp (to be matched)\n    and \"d1 d2 d3..\" is arbitary data (e.g., a 3D position and 3D orientation) associated to this timestamp. \n    \n    Input:\n    filename -- File name\n    \n    Output:\n    dict -- dictionary of (stamp,data) tuples\n    \n    \"\"\"\n    file = open(filename)\n    data = file.read()\n    lines = data.replace(\",\",\" \").replace(\"\\t\",\" \").split(\"\\n\") \n    list = [[v.strip() for v in line.split(\" \") if v.strip()!=\"\"] for line in lines if len(line)>0 and line[0]!=\"#\"]\n    list = [(float(l[0]),l[1:]) for l in list if len(l)>1]\n    return dict(list)\n\ndef associate(first_list, second_list,offset=0.0,max_difference=0.02):\n    \"\"\"\n    Associate two dictionaries of (stamp,data). As the time stamps never match exactly, we aim \n    to find the closest match for every input tuple.\n    \n    Input:\n    first_list -- first dictionary of (stamp,data) tuples\n    second_list -- second dictionary of (stamp,data) tuples\n    offset -- time offset between both dictionaries (e.g., to model the delay between the sensors)\n    max_difference -- search radius for candidate generation\n\n    Output:\n    matches -- list of matched tuples ((stamp1,data1),(stamp2,data2))\n    \n    \"\"\"\n    first_keys = list(first_list.keys())\n    second_keys = list(second_list.keys())\n    potential_matches = [(abs(a - (b + offset)), a, b) \n                         for a in first_keys \n                         for b in second_keys \n                         if abs(a - (b + offset)) < max_difference]\n    potential_matches.sort()\n    matches = []\n    for diff, a, b in potential_matches:\n        if a in first_keys and b in second_keys:\n            first_keys.remove(a)\n            second_keys.remove(b)\n            matches.append((a, b))\n    \n    matches.sort()\n    return matches\n\nif __name__ == '__main__':\n    \n    # parse command line\n    parser = argparse.ArgumentParser(description='''\n    This script takes two data files with timestamps and associates them   \n    ''')\n    parser.add_argument('first_file', help='first text file (format: timestamp data)')\n    parser.add_argument('second_file', help='second text file (format: timestamp data)')\n    parser.add_argument('--first_only', help='only output associated lines from first file', action='store_true')\n    parser.add_argument('--offset', help='time offset added to the timestamps of the second file (default: 0.0)',default=0.0)\n    parser.add_argument('--max_difference', help='maximally allowed time difference for matching entries (default: 0.02)',default=0.02)\n    args = parser.parse_args()\n\n    first_list = read_file_list(args.first_file)\n    second_list = read_file_list(args.second_file)\n\n    matches = associate(first_list, second_list,float(args.offset),float(args.max_difference))    \n\n    if args.first_only:\n        for a,b in matches:\n            print(\"%f %s\"%(a,\" \".join(first_list[a])))\n    else:\n        for a,b in matches:\n            print(\"%f %s %f %s\"%(a,\" \".join(first_list[a]),b-float(args.offset),\" \".join(second_list[b])))\n            \n        \n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/rgbdslam/rgbd_benchmark/evaluate_ate.py",
    "content": "#!/usr/bin/python\n# Software License Agreement (BSD License)\n#\n# Copyright (c) 2013, Juergen Sturm, TUM\n# All rights reserved.\n#\n# Redistribution and use in source and binary forms, with or without\n# modification, are permitted provided that the following conditions\n# are met:\n#\n#  * Redistributions of source code must retain the above copyright\n#    notice, this list of conditions and the following disclaimer.\n#  * Redistributions in binary form must reproduce the above\n#    copyright notice, this list of conditions and the following\n#    disclaimer in the documentation and/or other materials provided\n#    with the distribution.\n#  * Neither the name of TUM nor the names of its\n#    contributors may be used to endorse or promote products derived\n#    from this software without specific prior written permission.\n#\n# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n# \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n# POSSIBILITY OF SUCH DAMAGE.\n#\n# Requirements: \n# sudo apt-get install python-argparse\n\n\"\"\"\nThis script computes the absolute trajectory error from the ground truth\ntrajectory and the estimated trajectory.\n\"\"\"\n\nimport sys\nimport numpy\nimport argparse\nif __name__==\"__main__\":\n    import associate\nelse:\n    from . import associate\n\ndef align(model,data):\n    \"\"\"Align two trajectories using the method of Horn (closed-form).\n    \n    Input:\n    model -- first trajectory (3xn)\n    data -- second trajectory (3xn)\n    \n    Output:\n    rot -- rotation matrix (3x3)\n    trans -- translation vector (3x1)\n    trans_error -- translational error per point (1xn)\n    \n    \"\"\"\n    numpy.set_printoptions(precision=3,suppress=True)\n    model_zerocentered = model - model.mean(1)\n    data_zerocentered = data - data.mean(1)\n    \n    W = numpy.zeros( (3,3) )\n    for column in range(model.shape[1]):\n        W += numpy.outer(model_zerocentered[:,column],data_zerocentered[:,column])\n    U,d,Vh = numpy.linalg.linalg.svd(W.transpose())\n    S = numpy.matrix(numpy.identity( 3 ))\n    if(numpy.linalg.det(U) * numpy.linalg.det(Vh)<0):\n        S[2,2] = -1\n    rot = U*S*Vh\n    trans = data.mean(1) - rot * model.mean(1)\n    \n    model_aligned = rot * model + trans\n    alignment_error = model_aligned - data\n    \n    trans_error = numpy.sqrt(numpy.sum(numpy.multiply(alignment_error,alignment_error),0)).A[0]\n        \n    return rot,trans,trans_error\n\ndef plot_traj(ax,stamps,traj,style,color,label):\n    \"\"\"\n    Plot a trajectory using matplotlib. \n    \n    Input:\n    ax -- the plot\n    stamps -- time stamps (1xn)\n    traj -- trajectory (3xn)\n    style -- line style\n    color -- line color\n    label -- plot legend\n    \n    \"\"\"\n    stamps.sort()\n    interval = numpy.median([s-t for s,t in zip(stamps[1:],stamps[:-1])])\n    x = []\n    y = []\n    last = stamps[0]\n    for i in range(len(stamps)):\n        if stamps[i]-last < 2*interval:\n            x.append(traj[i][0])\n            y.append(traj[i][1])\n        elif len(x)>0:\n            ax.plot(x,y,style,color=color,label=label)\n            label=\"\"\n            x=[]\n            y=[]\n        last= stamps[i]\n    if len(x)>0:\n        ax.plot(x,y,style,color=color,label=label)\n            \n\ndef evaluate_ate(first_list, second_list, _args=\"\"):\n    # parse command line\n    parser = argparse.ArgumentParser(\n        description='This script computes the absolute trajectory error from the ground truth trajectory and the estimated trajectory.')\n    # parser.add_argument('first_file', help='ground truth trajectory (format: timestamp tx ty tz qx qy qz qw)')\n    # parser.add_argument('second_file', help='estimated trajectory (format: timestamp tx ty tz qx qy qz qw)')\n    parser.add_argument('--offset', help='time offset added to the timestamps of the second file (default: 0.0)',default=0.0)\n    parser.add_argument('--scale', help='scaling factor for the second trajectory (default: 1.0)',default=1.0)\n    parser.add_argument('--max_difference', help='maximally allowed time difference for matching entries (default: 0.02)',default=0.02)\n    parser.add_argument('--save', help='save aligned second trajectory to disk (format: stamp2 x2 y2 z2)')\n    parser.add_argument('--save_associations', help='save associated first and aligned second trajectory to disk (format: stamp1 x1 y1 z1 stamp2 x2 y2 z2)')\n    parser.add_argument('--plot', help='plot the first and the aligned second trajectory to an image (format: png)')\n    parser.add_argument('--verbose', help='print all evaluation data (otherwise, only the RMSE absolute translational error in meters after alignment will be printed)', action='store_true')\n    args = parser.parse_args(_args)\n\n    # first_list = associate.read_file_list(args.first_file)\n    # second_list = associate.read_file_list(args.second_file)\n\n    matches = associate.associate(first_list, second_list,float(args.offset),float(args.max_difference))    \n    if len(matches)<2:\n        raise ValueError(\"Couldn't find matching timestamp pairs between groundtruth and estimated trajectory! Did you choose the correct sequence?\")\n\n    first_xyz = numpy.matrix([[float(value) for value in first_list[a][0:3]] for a,b in matches]).transpose()\n    second_xyz = numpy.matrix([[float(value)*float(args.scale) for value in second_list[b][0:3]] for a,b in matches]).transpose()\n    rot,trans,trans_error = align(second_xyz,first_xyz)\n    \n    second_xyz_aligned = rot * second_xyz + trans\n    \n    first_stamps = list(first_list.keys())\n    first_stamps.sort()\n    first_xyz_full = numpy.matrix([[float(value) for value in first_list[b][0:3]] for b in first_stamps]).transpose()\n    \n    second_stamps = list(second_list.keys())\n    second_stamps.sort()\n    second_xyz_full = numpy.matrix([[float(value)*float(args.scale) for value in second_list[b][0:3]] for b in second_stamps]).transpose()\n    second_xyz_full_aligned = rot * second_xyz_full + trans\n    \n    if args.verbose:\n        print( \"compared_pose_pairs %d pairs\"%(len(trans_error)))\n             \n        print( \"absolute_translational_error.rmse %f m\"%numpy.sqrt(numpy.dot(trans_error,trans_error) / len(trans_error)))\n        print( \"absolute_translational_error.mean %f m\"%numpy.mean(trans_error))\n        print( \"absolute_translational_error.median %f m\"%numpy.median(trans_error))\n        print( \"absolute_translational_error.std %f m\"%numpy.std(trans_error))\n        print( \"absolute_translational_error.min %f m\"%numpy.min(trans_error))\n        print( \"absolute_translational_error.max %f m\"%numpy.max(trans_error))\n    \n        \n    if args.save_associations:\n        file = open(args.save_associations,\"w\")\n        file.write(\"\\n\".join([\"%f %f %f %f %f %f %f %f\"%(a,x1,y1,z1,b,x2,y2,z2) for (a,b),(x1,y1,z1),(x2,y2,z2) in zip(matches,first_xyz.transpose().A,second_xyz_aligned.transpose().A)]))\n        file.close()\n        \n    if args.save:\n        file = open(args.save,\"w\")\n        file.write(\"\\n\".join([\"%f \"%stamp+\" \".join([\"%f\"%d for d in line]) for stamp,line in zip(second_stamps,second_xyz_full_aligned.transpose().A)]))\n        file.close()\n\n    if args.plot:\n        import matplotlib\n        matplotlib.use('Agg')\n        import matplotlib.pyplot as plt\n        import matplotlib.pylab as pylab\n        from matplotlib.patches import Ellipse\n        fig = plt.figure()\n        ax = fig.add_subplot(111)\n        plot_traj(ax,first_stamps,first_xyz_full.transpose().A,'-',\"black\",\"ground truth\")\n        plot_traj(ax,second_stamps,second_xyz_full_aligned.transpose().A,'-',\"blue\",\"estimated\")\n\n        label=\"difference\"\n        for (a,b),(x1,y1,z1),(x2,y2,z2) in zip(matches,first_xyz.transpose().A,second_xyz_aligned.transpose().A):\n            ax.plot([x1,x2],[y1,y2],'-',color=\"red\",label=label)\n            label=\"\"\n            \n        ax.legend()\n            \n        ax.set_xlabel('x [m]')\n        ax.set_ylabel('y [m]')\n        plt.savefig(args.plot,dpi=90)\n        \n    return {\n        \"compared_pose_pairs\": (len(trans_error)),\n        \"absolute_translational_error.rmse\": numpy.sqrt(numpy.dot(trans_error,trans_error) / len(trans_error)),\n        \"absolute_translational_error.mean\": numpy.mean(trans_error),\n        \"absolute_translational_error.median\": numpy.median(trans_error),\n        \"absolute_translational_error.std\": numpy.std(trans_error),\n        \"absolute_translational_error.min\": numpy.min(trans_error),\n        \"absolute_translational_error.max\": numpy.max(trans_error),\n    }\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/rgbdslam/rgbd_benchmark/evaluate_rpe.py",
    "content": "#!/usr/bin/python\n# Software License Agreement (BSD License)\n#\n# Copyright (c) 2013, Juergen Sturm, TUM\n# All rights reserved.\n#\n# Redistribution and use in source and binary forms, with or without\n# modification, are permitted provided that the following conditions\n# are met:\n#\n#  * Redistributions of source code must retain the above copyright\n#    notice, this list of conditions and the following disclaimer.\n#  * Redistributions in binary form must reproduce the above\n#    copyright notice, this list of conditions and the following\n#    disclaimer in the documentation and/or other materials provided\n#    with the distribution.\n#  * Neither the name of TUM nor the names of its\n#    contributors may be used to endorse or promote products derived\n#    from this software without specific prior written permission.\n#\n# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n# \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n# POSSIBILITY OF SUCH DAMAGE.\n\n\"\"\"\nThis script computes the relative pose error from the ground truth trajectory\nand the estimated trajectory.\n\"\"\"\n\nimport argparse\nimport random\nimport numpy\nimport sys\n\n_EPS = numpy.finfo(float).eps * 4.0\n\ndef transform44(l):\n    \"\"\"\n    Generate a 4x4 homogeneous transformation matrix from a 3D point and unit quaternion.\n    \n    Input:\n    l -- tuple consisting of (stamp,tx,ty,tz,qx,qy,qz,qw) where\n         (tx,ty,tz) is the 3D position and (qx,qy,qz,qw) is the unit quaternion.\n         \n    Output:\n    matrix -- 4x4 homogeneous transformation matrix\n    \"\"\"\n    t = l[1:4]\n    q = numpy.array(l[4:8], dtype=numpy.float64, copy=True)\n    nq = numpy.dot(q, q)\n    if nq < _EPS:\n        return numpy.array((\n        (                1.0,                 0.0,                 0.0, t[0])\n        (                0.0,                 1.0,                 0.0, t[1])\n        (                0.0,                 0.0,                 1.0, t[2])\n        (                0.0,                 0.0,                 0.0, 1.0)\n        ), dtype=numpy.float64)\n    q *= numpy.sqrt(2.0 / nq)\n    q = numpy.outer(q, q)\n    return numpy.array((\n        (1.0-q[1, 1]-q[2, 2],     q[0, 1]-q[2, 3],     q[0, 2]+q[1, 3], t[0]),\n        (    q[0, 1]+q[2, 3], 1.0-q[0, 0]-q[2, 2],     q[1, 2]-q[0, 3], t[1]),\n        (    q[0, 2]-q[1, 3],     q[1, 2]+q[0, 3], 1.0-q[0, 0]-q[1, 1], t[2]),\n        (                0.0,                 0.0,                 0.0, 1.0)\n        ), dtype=numpy.float64)\n\ndef read_trajectory(filename, matrix=True):\n    \"\"\"\n    Read a trajectory from a text file. \n    \n    Input:\n    filename -- file to be read\n    matrix -- convert poses to 4x4 matrices\n    \n    Output:\n    dictionary of stamped 3D poses\n    \"\"\"\n    file = open(filename)\n    data = file.read()\n    lines = data.replace(\",\",\" \").replace(\"\\t\",\" \").split(\"\\n\") \n    list = [[float(v.strip()) for v in line.split(\" \") if v.strip()!=\"\"] for line in lines if len(line)>0 and line[0]!=\"#\"]\n    list_ok = []\n    for i,l in enumerate(list):\n        if l[4:8]==[0,0,0,0]:\n            continue\n        isnan = False\n        for v in l:\n            if numpy.isnan(v): \n                isnan = True\n                break\n        if isnan:\n            sys.stderr.write(\"Warning: line %d of file '%s' has NaNs, skipping line\\n\"%(i,filename))\n            continue\n        list_ok.append(l)\n    if matrix :\n      traj = dict([(l[0],transform44(l[0:])) for l in list_ok])\n    else:\n      traj = dict([(l[0],l[1:8]) for l in list_ok])\n    return traj\n\ndef find_closest_index(L,t):\n    \"\"\"\n    Find the index of the closest value in a list.\n    \n    Input:\n    L -- the list\n    t -- value to be found\n    \n    Output:\n    index of the closest element\n    \"\"\"\n    beginning = 0\n    difference = abs(L[0] - t)\n    best = 0\n    end = len(L)\n    while beginning < end:\n        middle = int((end+beginning)/2)\n        if abs(L[middle] - t) < difference:\n            difference = abs(L[middle] - t)\n            best = middle\n        if t == L[middle]:\n            return middle\n        elif L[middle] > t:\n            end = middle\n        else:\n            beginning = middle + 1\n    return best\n\ndef ominus(a,b):\n    \"\"\"\n    Compute the relative 3D transformation between a and b.\n    \n    Input:\n    a -- first pose (homogeneous 4x4 matrix)\n    b -- second pose (homogeneous 4x4 matrix)\n    \n    Output:\n    Relative 3D transformation from a to b.\n    \"\"\"\n    return numpy.dot(numpy.linalg.inv(a),b)\n\ndef scale(a,scalar):\n    \"\"\"\n    Scale the translational components of a 4x4 homogeneous matrix by a scale factor.\n    \"\"\"\n    return numpy.array(\n        [[a[0,0], a[0,1], a[0,2], a[0,3]*scalar],\n         [a[1,0], a[1,1], a[1,2], a[1,3]*scalar],\n         [a[2,0], a[2,1], a[2,2], a[2,3]*scalar],\n         [a[3,0], a[3,1], a[3,2], a[3,3]]]\n                       )\n\ndef compute_distance(transform):\n    \"\"\"\n    Compute the distance of the translational component of a 4x4 homogeneous matrix.\n    \"\"\"\n    return numpy.linalg.norm(transform[0:3,3])\n\ndef compute_angle(transform):\n    \"\"\"\n    Compute the rotation angle from a 4x4 homogeneous matrix.\n    \"\"\"\n    # an invitation to 3-d vision, p 27\n    return numpy.arccos( min(1,max(-1, (numpy.trace(transform[0:3,0:3]) - 1)/2) ))\n\ndef distances_along_trajectory(traj):\n    \"\"\"\n    Compute the translational distances along a trajectory. \n    \"\"\"\n    keys = traj.keys()\n    keys.sort()\n    motion = [ominus(traj[keys[i+1]],traj[keys[i]]) for i in range(len(keys)-1)]\n    distances = [0]\n    sum = 0\n    for t in motion:\n        sum += compute_distance(t)\n        distances.append(sum)\n    return distances\n    \ndef rotations_along_trajectory(traj,scale):\n    \"\"\"\n    Compute the angular rotations along a trajectory. \n    \"\"\"\n    keys = traj.keys()\n    keys.sort()\n    motion = [ominus(traj[keys[i+1]],traj[keys[i]]) for i in range(len(keys)-1)]\n    distances = [0]\n    sum = 0\n    for t in motion:\n        sum += compute_angle(t)*scale\n        distances.append(sum)\n    return distances\n    \n\ndef evaluate_trajectory(traj_gt,traj_est,param_max_pairs=10000,param_fixed_delta=False,param_delta=1.00,param_delta_unit=\"s\",param_offset=0.00,param_scale=1.00):\n    \"\"\"\n    Compute the relative pose error between two trajectories.\n    \n    Input:\n    traj_gt -- the first trajectory (ground truth)\n    traj_est -- the second trajectory (estimated trajectory)\n    param_max_pairs -- number of relative poses to be evaluated\n    param_fixed_delta -- false: evaluate over all possible pairs\n                         true: only evaluate over pairs with a given distance (delta)\n    param_delta -- distance between the evaluated pairs\n    param_delta_unit -- unit for comparison:\n                        \"s\": seconds\n                        \"m\": meters\n                        \"rad\": radians\n                        \"deg\": degrees\n                        \"f\": frames\n    param_offset -- time offset between two trajectories (to model the delay)\n    param_scale -- scale to be applied to the second trajectory\n    \n    Output:\n    list of compared poses and the resulting translation and rotation error\n    \"\"\"\n    stamps_gt = list(traj_gt.keys())\n    stamps_est = list(traj_est.keys())\n    stamps_gt.sort()\n    stamps_est.sort()\n    \n    stamps_est_return = []\n    for t_est in stamps_est:\n        t_gt = stamps_gt[find_closest_index(stamps_gt,t_est + param_offset)]\n        t_est_return = stamps_est[find_closest_index(stamps_est,t_gt - param_offset)]\n        t_gt_return = stamps_gt[find_closest_index(stamps_gt,t_est_return + param_offset)]\n        if not t_est_return in stamps_est_return:\n            stamps_est_return.append(t_est_return)\n    if(len(stamps_est_return)<2):\n        raise Exception(\"Number of overlap in the timestamps is too small. Did you run the evaluation on the right files?\")\n\n    if param_delta_unit==\"s\":\n        index_est = list(traj_est.keys())\n        index_est.sort()\n    elif param_delta_unit==\"m\":\n        index_est = distances_along_trajectory(traj_est)\n    elif param_delta_unit==\"rad\":\n        index_est = rotations_along_trajectory(traj_est,1)\n    elif param_delta_unit==\"deg\":\n        index_est = rotations_along_trajectory(traj_est,180/numpy.pi)\n    elif param_delta_unit==\"f\":\n        index_est = range(len(traj_est))\n    else:\n        raise Exception(\"Unknown unit for delta: '%s'\"%param_delta_unit)\n\n    if not param_fixed_delta:\n        if(param_max_pairs==0 or len(traj_est)<numpy.sqrt(param_max_pairs)):\n            pairs = [(i,j) for i in range(len(traj_est)) for j in range(len(traj_est))]\n        else:\n            pairs = [(random.randint(0,len(traj_est)-1),random.randint(0,len(traj_est)-1)) for i in range(param_max_pairs)]\n    else:\n        pairs = []\n        for i in range(len(traj_est)):\n            j = find_closest_index(index_est,index_est[i] + param_delta)\n            if j!=len(traj_est)-1: \n                pairs.append((i,j))\n        if(param_max_pairs!=0 and len(pairs)>param_max_pairs):\n            pairs = random.sample(pairs,param_max_pairs)\n    \n    gt_interval = numpy.median([s-t for s,t in zip(stamps_gt[1:],stamps_gt[:-1])])\n    gt_max_time_difference = 2*gt_interval\n    \n    result = []\n    for i,j in pairs:\n        stamp_est_0 = stamps_est[i]\n        stamp_est_1 = stamps_est[j]\n\n        stamp_gt_0 = stamps_gt[ find_closest_index(stamps_gt,stamp_est_0 + param_offset) ]\n        stamp_gt_1 = stamps_gt[ find_closest_index(stamps_gt,stamp_est_1 + param_offset) ]\n        \n        if(abs(stamp_gt_0 - (stamp_est_0 + param_offset)) > gt_max_time_difference  or\n           abs(stamp_gt_1 - (stamp_est_1 + param_offset)) > gt_max_time_difference):\n            continue\n        \n        error44 = ominus(  scale(\n                           ominus( traj_est[stamp_est_1], traj_est[stamp_est_0] ),param_scale),\n                           ominus( traj_gt[stamp_gt_1], traj_gt[stamp_gt_0] ) )\n        \n        trans = compute_distance(error44)\n        rot = compute_angle(error44)\n        \n        result.append([stamp_est_0,stamp_est_1,stamp_gt_0,stamp_gt_1,trans,rot])\n        \n    if len(result)<2:\n        raise Exception(\"Couldn't find matching timestamp pairs between groundtruth and estimated trajectory!\")\n        \n    return result\n\ndef percentile(seq,q):\n    \"\"\"\n    Return the q-percentile of a list\n    \"\"\"\n    seq_sorted = list(seq)\n    seq_sorted.sort()\n    return seq_sorted[int((len(seq_sorted)-1)*q)]\n\n\ndef evaluate_rpe(_args):\n    random.seed(0)\n\n    parser = argparse.ArgumentParser(description='''\n    This script computes the relative pose error from the ground truth trajectory and the estimated trajectory. \n    ''')\n    parser.add_argument('groundtruth_file', help='ground-truth trajectory file (format: \"timestamp tx ty tz qx qy qz qw\")')\n    parser.add_argument('estimated_file', help='estimated trajectory file (format: \"timestamp tx ty tz qx qy qz qw\")')\n    parser.add_argument('--max_pairs', help='maximum number of pose comparisons (default: 10000, set to zero to disable downsampling)', default=10000)\n    parser.add_argument('--fixed_delta', help='only consider pose pairs that have a distance of delta delta_unit (e.g., for evaluating the drift per second/meter/radian)', action='store_true')\n    parser.add_argument('--delta', help='delta for evaluation (default: 1.0)',default=1.0)\n    parser.add_argument('--delta_unit', help='unit of delta (options: \\'s\\' for seconds, \\'m\\' for meters, \\'rad\\' for radians, \\'f\\' for frames; default: \\'s\\')',default='s')\n    parser.add_argument('--offset', help='time offset between ground-truth and estimated trajectory (default: 0.0)',default=0.0)\n    parser.add_argument('--scale', help='scaling factor for the estimated trajectory (default: 1.0)',default=1.0)\n    parser.add_argument('--save', help='text file to which the evaluation will be saved (format: stamp_est0 stamp_est1 stamp_gt0 stamp_gt1 trans_error rot_error)')\n    parser.add_argument('--plot', help='plot the result to a file (requires --fixed_delta, output format: png)')\n    parser.add_argument('--verbose', help='print all evaluation data (otherwise, only the mean translational error measured in meters will be printed)', action='store_true')\n    args = parser.parse_args(_args)\n    \n    if args.plot and not args.fixed_delta:\n        raise ValueError(\"The '--plot' option can only be used in combination with '--fixed_delta'\")\n    \n    traj_gt = read_trajectory(args.groundtruth_file)\n    traj_est = read_trajectory(args.estimated_file)\n    \n    result = evaluate_trajectory(traj_gt,\n                                 traj_est,\n                                 int(args.max_pairs),\n                                 args.fixed_delta,\n                                 float(args.delta),\n                                 args.delta_unit,\n                                 float(args.offset),\n                                 float(args.scale))\n    \n    stamps = numpy.array(result)[:,0]\n    trans_error = numpy.array(result)[:,4]\n    rot_error = numpy.array(result)[:,5]\n    \n    if args.save:\n        f = open(args.save,\"w\")\n        f.write(\"\\n\".join([\" \".join([\"%f\"%v for v in line]) for line in result]))\n        f.close()\n    \n    if args.verbose:\n        print( \"compared_pose_pairs %d pairs\"%(len(trans_error)))\n\n        print( \"translational_error.rmse %f m\"%numpy.sqrt(numpy.dot(trans_error,trans_error) / len(trans_error)))\n        print( \"translational_error.mean %f m\"%numpy.mean(trans_error))\n        print( \"translational_error.median %f m\"%numpy.median(trans_error))\n        print( \"translational_error.std %f m\"%numpy.std(trans_error))\n        print( \"translational_error.min %f m\"%numpy.min(trans_error))\n        print( \"translational_error.max %f m\"%numpy.max(trans_error))\n\n        print( \"rotational_error.rmse %f deg\"%(numpy.sqrt(numpy.dot(rot_error,rot_error) / len(rot_error)) * 180.0 / numpy.pi))\n        print( \"rotational_error.mean %f deg\"%(numpy.mean(rot_error) * 180.0 / numpy.pi))\n        print( \"rotational_error.median %f deg\"%(numpy.median(rot_error) * 180.0 / numpy.pi))\n        print( \"rotational_error.std %f deg\"%(numpy.std(rot_error) * 180.0 / numpy.pi))\n        print( \"rotational_error.min %f deg\"%(numpy.min(rot_error) * 180.0 / numpy.pi))\n        print( \"rotational_error.max %f deg\"%(numpy.max(rot_error) * 180.0 / numpy.pi))\n    else:\n        print( numpy.mean(trans_error))\n\n    if args.plot:    \n        import matplotlib\n        matplotlib.use('Agg')\n        import matplotlib.pyplot as plt\n        import matplotlib.pylab as pylab\n        fig = plt.figure()\n        ax = fig.add_subplot(111)        \n        ax.plot(stamps - stamps[0],trans_error,'-',color=\"blue\")\n        #ax.plot([t for t,e in err_rot],[e for t,e in err_rot],'-',color=\"red\")\n        ax.set_xlabel('time [s]')\n        ax.set_ylabel('translational error [m]')\n        plt.savefig(args.plot,dpi=300)\n        \n    return {\n        \"translational_error.rmse\": numpy.sqrt(numpy.dot(trans_error,trans_error) / len(trans_error)),\n        \"translational_error.mean\": numpy.mean(trans_error),\n        \"translational_error.median\": numpy.median(trans_error),\n        \"translational_error.std\": numpy.std(trans_error),\n        \"translational_error.min\": numpy.min(trans_error),\n        \"translational_error.max\": numpy.max(trans_error),\n\n        \"rotational_error.rmse\": (numpy.sqrt(numpy.dot(rot_error,rot_error) / len(rot_error)) * 180.0 / numpy.pi),\n        \"rotational_error.mean\": (numpy.mean(rot_error) * 180.0 / numpy.pi),\n        \"rotational_error.median\": (numpy.median(rot_error) * 180.0 / numpy.pi),\n        \"rotational_error.std\": (numpy.std(rot_error) * 180.0 / numpy.pi),\n        \"rotational_error.min\": (numpy.min(rot_error) * 180.0 / numpy.pi),\n        \"rotational_error.max\": (numpy.max(rot_error) * 180.0 / numpy.pi),\n    }\n\n\n\nif __name__ == '__main__':\n    random.seed(0)\n\n    parser = argparse.ArgumentParser(description='''\n    This script computes the relative pose error from the ground truth trajectory and the estimated trajectory. \n    ''')\n    parser.add_argument('groundtruth_file', help='ground-truth trajectory file (format: \"timestamp tx ty tz qx qy qz qw\")')\n    parser.add_argument('estimated_file', help='estimated trajectory file (format: \"timestamp tx ty tz qx qy qz qw\")')\n    parser.add_argument('--max_pairs', help='maximum number of pose comparisons (default: 10000, set to zero to disable downsampling)', default=10000)\n    parser.add_argument('--fixed_delta', help='only consider pose pairs that have a distance of delta delta_unit (e.g., for evaluating the drift per second/meter/radian)', action='store_true')\n    parser.add_argument('--delta', help='delta for evaluation (default: 1.0)',default=1.0)\n    parser.add_argument('--delta_unit', help='unit of delta (options: \\'s\\' for seconds, \\'m\\' for meters, \\'rad\\' for radians, \\'f\\' for frames; default: \\'s\\')',default='s')\n    parser.add_argument('--offset', help='time offset between ground-truth and estimated trajectory (default: 0.0)',default=0.0)\n    parser.add_argument('--scale', help='scaling factor for the estimated trajectory (default: 1.0)',default=1.0)\n    parser.add_argument('--save', help='text file to which the evaluation will be saved (format: stamp_est0 stamp_est1 stamp_gt0 stamp_gt1 trans_error rot_error)')\n    parser.add_argument('--plot', help='plot the result to a file (requires --fixed_delta, output format: png)')\n    parser.add_argument('--verbose', help='print all evaluation data (otherwise, only the mean translational error measured in meters will be printed)', action='store_true')\n    args = parser.parse_args()\n    \n    if args.plot and not args.fixed_delta:\n        sys.exit(\"The '--plot' option can only be used in combination with '--fixed_delta'\")\n    \n    traj_gt = read_trajectory(args.groundtruth_file)\n    traj_est = read_trajectory(args.estimated_file)\n    \n    result = evaluate_trajectory(traj_gt,\n                                 traj_est,\n                                 int(args.max_pairs),\n                                 args.fixed_delta,\n                                 float(args.delta),\n                                 args.delta_unit,\n                                 float(args.offset),\n                                 float(args.scale))\n    \n    stamps = numpy.array(result)[:,0]\n    trans_error = numpy.array(result)[:,4]\n    rot_error = numpy.array(result)[:,5]\n    \n    if args.save:\n        f = open(args.save,\"w\")\n        f.write(\"\\n\".join([\" \".join([\"%f\"%v for v in line]) for line in result]))\n        f.close()\n    \n    if args.verbose:\n        print( \"compared_pose_pairs %d pairs\"%(len(trans_error)))\n\n        print( \"translational_error.rmse %f m\"%numpy.sqrt(numpy.dot(trans_error,trans_error) / len(trans_error)))\n        print( \"translational_error.mean %f m\"%numpy.mean(trans_error))\n        print( \"translational_error.median %f m\"%numpy.median(trans_error))\n        print( \"translational_error.std %f m\"%numpy.std(trans_error))\n        print( \"translational_error.min %f m\"%numpy.min(trans_error))\n        print( \"translational_error.max %f m\"%numpy.max(trans_error))\n\n        print( \"rotational_error.rmse %f deg\"%(numpy.sqrt(numpy.dot(rot_error,rot_error) / len(rot_error)) * 180.0 / numpy.pi))\n        print( \"rotational_error.mean %f deg\"%(numpy.mean(rot_error) * 180.0 / numpy.pi))\n        print( \"rotational_error.median %f deg\"%(numpy.median(rot_error) * 180.0 / numpy.pi))\n        print( \"rotational_error.std %f deg\"%(numpy.std(rot_error) * 180.0 / numpy.pi))\n        print( \"rotational_error.min %f deg\"%(numpy.min(rot_error) * 180.0 / numpy.pi))\n        print( \"rotational_error.max %f deg\"%(numpy.max(rot_error) * 180.0 / numpy.pi))\n    else:\n        print( numpy.mean(trans_error))\n\n    if args.plot:    \n        import matplotlib\n        matplotlib.use('Agg')\n        import matplotlib.pyplot as plt\n        import matplotlib.pylab as pylab\n        fig = plt.figure()\n        ax = fig.add_subplot(111)        \n        ax.plot(stamps - stamps[0],trans_error,'-',color=\"blue\")\n        #ax.plot([t for t,e in err_rot],[e for t,e in err_rot],'-',color=\"red\")\n        ax.set_xlabel('time [s]')\n        ax.set_ylabel('translational error [m]')\n        plt.savefig(args.plot,dpi=300)\n        \n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/rgbdslam/train.py",
    "content": "import sys\nsys.path.append('../core')\n\nimport cv2\nimport numpy as np\nfrom collections import OrderedDict\n\nimport torch\nimport torch.optim as optim\nfrom torch.utils.data import DataLoader\nfrom data_readers.factory import dataset_factory\n\nfrom lietorch import SO3, SE3, Sim3\nfrom geom.losses import geodesic_loss, residual_loss\n\n# network\nfrom networks.rslam import RaftSLAM\nfrom logger import Logger\nfrom evaluate import run_evaluation\n\ndef show_image(image):\n    image = image.permute(1, 2, 0).cpu().numpy()\n    cv2.imshow('image', image / 255.0)\n    cv2.waitKey()\n\ndef normalize_images(images):\n    images = images[:, :, [2,1,0]]\n    mean = torch.as_tensor([0.485, 0.456, 0.406], device=images.device)\n    std = torch.as_tensor([0.229, 0.224, 0.225], device=images.device)\n    return (images/255.0).sub_(mean[:, None, None]).div_(std[:, None, None])\n\ndef train(args):\n    \"\"\" Test to make sure project transform correctly maps points \"\"\"\n\n    N = args.n_frames\n    model = RaftSLAM(args)\n    model.cuda()\n    model.train()\n\n    if args.ckpt is not None:\n        model.load_state_dict(torch.load(args.ckpt))\n\n    db = dataset_factory(args.datasets, n_frames=N, fmin=16.0, fmax=96.0)\n    train_loader = DataLoader(db, batch_size=args.batch, shuffle=True, num_workers=4)\n\n    optimizer = optim.Adam(model.parameters(), lr=args.lr, weight_decay=1e-5)\n    scheduler = optim.lr_scheduler.OneCycleLR(optimizer, \n        args.lr, args.steps, pct_start=0.01, cycle_momentum=False)\n\n    logger = Logger(args.name, scheduler)\n    should_keep_training = True\n    total_steps = 0\n\n    while should_keep_training:\n        for i_batch, item in enumerate(train_loader):\n            optimizer.zero_grad()\n\n            graph = OrderedDict()\n            for i in range(N):\n                graph[i] = [j for j in range(N) if i!=j and abs(i-j) <= 2]\n            \n            images, poses, depths, intrinsics = [x.to('cuda') for x in item]\n            \n            # convert poses w2c -> c2w\n            Ps = SE3(poses).inv()\n            Gs = SE3.Identity(Ps.shape, device='cuda')\n\n            images = normalize_images(images)\n            Gs, residuals = model(Gs, images, depths, intrinsics, graph, num_steps=args.iters)\n\n            geo_loss, geo_metrics = geodesic_loss(Ps, Gs, graph)\n            res_loss, res_metrics = residual_loss(residuals)\n\n            metrics = {}\n            metrics.update(geo_metrics)\n            metrics.update(res_metrics)\n\n            loss = args.w1 * geo_loss + args.w2 * res_loss\n            loss.backward()\n\n            torch.nn.utils.clip_grad_norm_(model.parameters(), args.clip)\n            optimizer.step()\n            scheduler.step()\n            \n            logger.push(metrics)\n            total_steps += 1\n\n            if total_steps % 10000 == 0:\n                PATH = 'checkpoints/%s_%06d.pth' % (args.name, total_steps)\n                torch.save(model.state_dict(), PATH)\n\n                run_evaluation(PATH)\n\n            if total_steps >= args.steps:\n                should_keep_training = False\n                break\n\n    return model\n                \n\nif __name__ == '__main__':\n    import argparse\n    parser = argparse.ArgumentParser()\n    parser.add_argument('--name', default='bla', help='name your experiment')\n    parser.add_argument('--ckpt', help='checkpoint to restore')\n    parser.add_argument('--datasets', nargs='+', help='lists of datasets for training')\n\n    parser.add_argument('--batch', type=int, default=2)\n    parser.add_argument('--iters', type=int, default=8)\n    parser.add_argument('--steps', type=int, default=100000)\n    parser.add_argument('--lr', type=float, default=0.0001)\n    parser.add_argument('--clip', type=float, default=2.5)\n    parser.add_argument('--n_frames', type=int, default=4)\n\n    parser.add_argument('--w1', type=float, default=10.0)\n    parser.add_argument('--w2', type=float, default=0.1)\n\n    args = parser.parse_args()\n\n    import os\n    if not os.path.isdir('checkpoints'):\n        os.mkdir('checkpoints')\n\n    model = train(args)\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/examples/rgbdslam/viz.py",
    "content": "import time\nimport argparse\nimport torch\nimport scipy\nimport numpy as np\nimport open3d as o3d\n\nfrom queue import Empty\nfrom multiprocessing import Queue, Process\nfrom scipy.spatial.transform import Rotation\n\ndef pose_matrix_from_quaternion(pvec):\n    \"\"\" convert 4x4 pose matrix to (t, q) \"\"\"\n    pose = np.eye(4)\n    pose[:3,:3] = Rotation.from_quat(pvec[3:]).as_matrix()\n    pose[:3, 3] = pvec[:3]\n    return pose\n\ndef create_camera_actor(is_gt=False, scale=0.05):\n    \"\"\" build open3d camera polydata \"\"\"\n\n    cam_points = scale * np.array([\n        [ 0,   0,   0],\n        [-1,  -1, 1.5],\n        [ 1,  -1, 1.5],\n        [ 1,   1, 1.5],\n        [-1,   1, 1.5],\n        [-0.5, 1, 1.5],\n        [ 0.5, 1, 1.5],\n        [ 0, 1.2, 1.5]])\n\n    cam_lines = np.array([[1, 2], [2, 3], [3, 4], [4, 1],\n        [1, 0], [0, 2], [3, 0], [0, 4], [5, 7], [7, 6]])\n\n    camera_actor = o3d.geometry.LineSet(\n        points=o3d.utility.Vector3dVector(cam_points),\n        lines=o3d.utility.Vector2iVector(cam_lines))\n\n    color = (0.0, 0.0, 0.0) if is_gt else (0.0, 0.8, 0.8)\n    camera_actor.paint_uniform_color(color)\n\n    return camera_actor\n\ndef create_point_cloud_actor(points, colors):\n    \"\"\" open3d point cloud from numpy array \"\"\"\n\n    point_cloud = o3d.geometry.PointCloud()\n    point_cloud.points = o3d.utility.Vector3dVector(points)\n    point_cloud.colors = o3d.utility.Vector3dVector(colors)\n\n    return point_cloud\n\ndef draw_trajectory(queue):\n\n    draw_trajectory.queue = queue\n    draw_trajectory.cameras = {}\n    draw_trajectory.points = {}\n    draw_trajectory.ix = 0\n    draw_trajectory.warmup = 8\n\n    def animation_callback(vis):\n        cam = vis.get_view_control().convert_to_pinhole_camera_parameters()\n        while True:\n            try:\n                data = draw_trajectory.queue.get_nowait()\n                if data[0] == 'pose':\n                    i, pose, is_gt = data[1:]\n                    \n                    # convert to 4x4 matrix\n                    pose = pose_matrix_from_quaternion(pose)\n\n                    if i in draw_trajectory.cameras:\n                        cam_actor, pose_prev = draw_trajectory.cameras[i]\n                        pose_change = pose @ np.linalg.inv(pose_prev)\n                        \n                        cam_actor.transform(pose_change)\n                        vis.update_geometry(cam_actor)\n\n                        if i in draw_trajectory.points:\n                            pc = draw_trajectory.points[i]\n                            pc.transform(pose_change)\n                            vis.update_geometry(pc)\n\n                    else:\n                        cam_actor = create_camera_actor(is_gt)\n                        cam_actor.transform(pose)\n                        vis.add_geometry(cam_actor)\n\n                    if not is_gt:\n                        draw_trajectory.cameras[i] = (cam_actor, pose)\n\n                elif data[0] == 'points':\n                    i, points, colors = data[1:]\n                    point_actor = create_point_cloud_actor(points, colors)\n\n                    pose = draw_trajectory.cameras[i][1]\n                    point_actor.transform(pose)\n                    vis.add_geometry(point_actor)\n\n                    draw_trajectory.points[i] = point_actor\n\n                elif data[0] == 'reset':\n                    draw_trajectory.warmup = -1\n                    \n                    for i in draw_trajectory.points:\n                        vis.remove_geometry(draw_trajectory.points[i])\n\n                    for i in draw_trajectory.cameras:\n                        vis.remove_geometry(draw_trajectory.cameras[i][0])\n\n                    draw_trajectory.cameras = {}\n                    draw_trajectory.points = {}\n\n            except Empty:\n                break\n\n        # hack to allow interacting with vizualization during inference\n        if len(draw_trajectory.cameras) >= draw_trajectory.warmup:\n            cam = vis.get_view_control().convert_from_pinhole_camera_parameters(cam)\n\n        vis.poll_events()\n        vis.update_renderer()\n\n    vis = o3d.visualization.Visualizer()\n\n    vis.register_animation_callback(animation_callback)\n    vis.create_window(height=540, width=960)\n    vis.get_render_option().load_from_json(\"assets/renderoption.json\")\n\n    vis.run()\n    vis.destroy_window()\n\n\nclass SLAMFrontend:\n    def __init__(self):\n        self.queue = Queue()\n        self.p = Process(target=draw_trajectory, args=(self.queue, ))\n\n    def update_pose(self, index, pose, gt=False):\n        if isinstance(pose, torch.Tensor):\n            pose = pose.cpu().numpy()\n        self.queue.put_nowait(('pose', index, pose, gt))\n\n    def update_points(self, index, points, colors):\n        if isinstance(points, torch.Tensor):\n            points = points.cpu().numpy()\n        self.queue.put_nowait(('points', index, points, colors))\n    \n    def reset(self):\n        self.queue.put_nowait(('reset', ))\n\n    def start(self):\n        self.p.start()\n        return self\n\n    def join(self):\n        self.p.join()\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/__init__.py",
    "content": "__all__ = ['groups']\nfrom .groups import LieGroupParameter, SO3, RxSO3, SE3, Sim3, cat, stack\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/broadcasting.py",
    "content": "import torch\nimport numpy as np\n\ndef check_broadcastable(x, y):\n    assert len(x.shape) == len(y.shape)\n    for (n, m) in zip(x.shape[:-1], y.shape[:-1]):\n        assert n==m or n==1 or m==1\n\ndef broadcast_inputs(x, y):\n    \"\"\" Automatic broadcasting of missing dimensions \"\"\"\n    if y is None:\n        xs, xd = x.shape[:-1], x.shape[-1] \n        return (x.view(-1, xd).contiguous(), ), x.shape[:-1]\n\n    check_broadcastable(x, y)\n\n    xs, xd = x.shape[:-1], x.shape[-1] \n    ys, yd = y.shape[:-1], y.shape[-1]\n    out_shape = [max(n,m) for (n,m) in zip(xs,ys)]\n\n    if x.shape[:-1] == y.shape[-1]:\n        x1 = x.view(-1, xd)\n        y1 = y.view(-1, yd)\n\n    else:\n        x_expand = [m if n==1 else 1 for (n,m) in zip(xs, ys)]\n        y_expand = [n if m==1 else 1 for (n,m) in zip(xs, ys)]\n        x1 = x.repeat(x_expand + [1]).reshape(-1, xd).contiguous()\n        y1 = y.repeat(y_expand + [1]).reshape(-1, yd).contiguous()\n\n    return (x1, y1), tuple(out_shape)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/extras/altcorr_kernel.cu",
    "content": "#include <torch/extension.h>\n#include <cuda.h>\n#include <cuda_runtime.h>\n#include <vector>\n\n\n#define BLOCK_H 4\n#define BLOCK_W 8\n#define BLOCK_HW BLOCK_H * BLOCK_W\n#define CHANNEL_STRIDE 32\n\n\n__forceinline__ __device__\nbool within_bounds(int h, int w, int H, int W) {\n  return h >= 0 && h < H && w >= 0 && w < W;\n}\n\ntemplate <typename scalar_t>\n__global__ void altcorr_forward_kernel(\n    const torch::PackedTensorAccessor32<scalar_t,4,torch::RestrictPtrTraits> fmap1,\n    const torch::PackedTensorAccessor32<scalar_t,4,torch::RestrictPtrTraits> fmap2,\n    const torch::PackedTensorAccessor32<scalar_t,5,torch::RestrictPtrTraits> coords,\n    torch::PackedTensorAccessor32<scalar_t,5,torch::RestrictPtrTraits> corr,\n    int r)\n{\n  const int b = blockIdx.x;\n  const int h0 = blockIdx.y * blockDim.x;\n  const int w0 = blockIdx.z * blockDim.y;\n  const int tid = threadIdx.x * blockDim.y + threadIdx.y;\n\n  const int H1 = fmap1.size(1);\n  const int W1 = fmap1.size(2);\n  const int H2 = fmap2.size(1);\n  const int W2 = fmap2.size(2);\n  const int N = coords.size(1);\n  const int C = fmap1.size(3);\n\n  __shared__ scalar_t f1[CHANNEL_STRIDE][BLOCK_HW+1];\n  __shared__ scalar_t f2[CHANNEL_STRIDE][BLOCK_HW+1];\n  __shared__ scalar_t x2s[BLOCK_HW];\n  __shared__ scalar_t y2s[BLOCK_HW];\n\n  for (int c=0; c<C; c+=CHANNEL_STRIDE) {\n    for (int k=0; k<BLOCK_HW; k+=BLOCK_HW/CHANNEL_STRIDE) {\n      int k1 = k + tid / CHANNEL_STRIDE;\n      int h1 = h0 + k1 / BLOCK_W;\n      int w1 = w0 + k1 % BLOCK_W;\n      int c1 = tid % CHANNEL_STRIDE;\n\n      auto fptr = fmap1[b][h1][w1];\n      if (within_bounds(h1, w1, H1, W1))\n        f1[c1][k1] = fptr[c+c1];\n      else\n        f1[c1][k1] = 0.0;\n    }\n\n    __syncthreads();\n\n    for (int n=0; n<N; n++) {\n      int h1 = h0 + threadIdx.x;\n      int w1 = w0 + threadIdx.y;\n      if (within_bounds(h1, w1, H1, W1)) {\n        x2s[tid] = coords[b][n][h1][w1][0];\n        y2s[tid] = coords[b][n][h1][w1][1];\n      }\n\n      scalar_t dx = x2s[tid] - floor(x2s[tid]);\n      scalar_t dy = y2s[tid] - floor(y2s[tid]);\n\n      int rd = 2*r + 1;\n      for (int iy=0; iy<rd+1; iy++) {\n        for (int ix=0; ix<rd+1; ix++) {\n          for (int k=0; k<BLOCK_HW; k+=BLOCK_HW/CHANNEL_STRIDE) {\n            int k1 = k + tid / CHANNEL_STRIDE;\n            int h2 = static_cast<int>(floor(y2s[k1]))-r+iy;\n            int w2 = static_cast<int>(floor(x2s[k1]))-r+ix;\n            int c2 = tid % CHANNEL_STRIDE;\n\n            auto fptr = fmap2[b][h2][w2];\n            if (within_bounds(h2, w2, H2, W2))\n              f2[c2][k1] = fptr[c+c2];\n            else\n              f2[c2][k1] = 0.0;\n          }\n\n          __syncthreads();\n      \n          scalar_t s = 0.0;\n          for (int k=0; k<CHANNEL_STRIDE; k++)\n            s += f1[k][tid] * f2[k][tid];\n\n          int ix_nw = H1*W1*((iy-1) + rd*(ix-1));\n          int ix_ne = H1*W1*((iy-1) + rd*ix);\n          int ix_sw = H1*W1*(iy + rd*(ix-1));\n          int ix_se = H1*W1*(iy + rd*ix);\n\n          scalar_t nw = s * (dy) * (dx);\n          scalar_t ne = s * (dy) * (1-dx);\n          scalar_t sw = s * (1-dy) * (dx);\n          scalar_t se = s * (1-dy) * (1-dx);\n\n          scalar_t* corr_ptr = &corr[b][n][0][h1][w1];\n\n          if (iy > 0 && ix > 0 && within_bounds(h1, w1, H1, W1))\n            *(corr_ptr + ix_nw) += nw;\n\n          if (iy > 0 && ix < rd && within_bounds(h1, w1, H1, W1))\n            *(corr_ptr + ix_ne) += ne;\n\n          if (iy < rd && ix > 0 && within_bounds(h1, w1, H1, W1))\n            *(corr_ptr + ix_sw) += sw;\n\n          if (iy < rd && ix < rd && within_bounds(h1, w1, H1, W1))\n            *(corr_ptr + ix_se) += se;\n        }\n      } \n    }\n  }\n}\n\n\ntemplate <typename scalar_t>\n__global__ void altcorr_backward_kernel(\n    const torch::PackedTensorAccessor32<scalar_t,4,torch::RestrictPtrTraits> fmap1,\n    const torch::PackedTensorAccessor32<scalar_t,4,torch::RestrictPtrTraits> fmap2,\n    const torch::PackedTensorAccessor32<scalar_t,5,torch::RestrictPtrTraits> coords,\n    const torch::PackedTensorAccessor32<scalar_t,5,torch::RestrictPtrTraits> corr_grad,\n    torch::PackedTensorAccessor32<scalar_t,4,torch::RestrictPtrTraits> fmap1_grad,\n    torch::PackedTensorAccessor32<scalar_t,4,torch::RestrictPtrTraits> fmap2_grad,\n    torch::PackedTensorAccessor32<scalar_t,5,torch::RestrictPtrTraits> coords_grad,\n    int r)\n{\n\n  const int b = blockIdx.x;\n  const int h0 = blockIdx.y * blockDim.x;\n  const int w0 = blockIdx.z * blockDim.y;\n  const int tid = threadIdx.x * blockDim.y + threadIdx.y;\n\n  const int H1 = fmap1.size(1);\n  const int W1 = fmap1.size(2);\n  const int H2 = fmap2.size(1);\n  const int W2 = fmap2.size(2);\n  const int N = coords.size(1);\n  const int C = fmap1.size(3);\n\n  __shared__ scalar_t f1[CHANNEL_STRIDE][BLOCK_HW+1];\n  __shared__ scalar_t f2[CHANNEL_STRIDE][BLOCK_HW+1];\n\n  __shared__ scalar_t f1_grad[CHANNEL_STRIDE][BLOCK_HW+1];\n  __shared__ scalar_t f2_grad[CHANNEL_STRIDE][BLOCK_HW+1];\n\n  __shared__ scalar_t x2s[BLOCK_HW];\n  __shared__ scalar_t y2s[BLOCK_HW];\n\n  for (int c=0; c<C; c+=CHANNEL_STRIDE) {\n\n    for (int k=0; k<BLOCK_HW; k+=BLOCK_HW/CHANNEL_STRIDE) {\n      int k1 = k + tid / CHANNEL_STRIDE;\n      int h1 = h0 + k1 / BLOCK_W;\n      int w1 = w0 + k1 % BLOCK_W;\n      int c1 = tid % CHANNEL_STRIDE;\n\n      auto fptr = fmap1[b][h1][w1];\n      if (within_bounds(h1, w1, H1, W1))\n        f1[c1][k1] = fptr[c+c1];\n      else\n        f1[c1][k1] = 0.0;\n\n      f1_grad[c1][k1] = 0.0;\n    }\n\n    __syncthreads();\n\n    int h1 = h0 + threadIdx.x;\n    int w1 = w0 + threadIdx.y;\n\n    for (int n=0; n<N; n++) {  \n      x2s[tid] = coords[b][n][h1][w1][0];\n      y2s[tid] = coords[b][n][h1][w1][1];\n\n      scalar_t dx = x2s[tid] - floor(x2s[tid]);\n      scalar_t dy = y2s[tid] - floor(y2s[tid]);\n\n      int rd = 2*r + 1;\n      for (int iy=0; iy<rd+1; iy++) {\n        for (int ix=0; ix<rd+1; ix++) {\n          for (int k=0; k<BLOCK_HW; k+=BLOCK_HW/CHANNEL_STRIDE) {\n            int k1 = k + tid / CHANNEL_STRIDE;\n            int h2 = static_cast<int>(floor(y2s[k1]))-r+iy;\n            int w2 = static_cast<int>(floor(x2s[k1]))-r+ix;\n            int c2 = tid % CHANNEL_STRIDE;\n\n            auto fptr = fmap2[b][h2][w2];\n            if (within_bounds(h2, w2, H2, W2))\n              f2[c2][k1] = fptr[c+c2];\n            else\n              f2[c2][k1] = 0.0;\n\n            f2_grad[c2][k1] = 0.0;\n          }\n\n          __syncthreads();\n      \n          const scalar_t* grad_ptr = &corr_grad[b][n][0][h1][w1];\n          scalar_t g = 0.0;\n\n          int ix_nw = H1*W1*((iy-1) + rd*(ix-1));\n          int ix_ne = H1*W1*((iy-1) + rd*ix);\n          int ix_sw = H1*W1*(iy + rd*(ix-1));\n          int ix_se = H1*W1*(iy + rd*ix);\n\n          if (iy > 0 && ix > 0 && within_bounds(h1, w1, H1, W1))\n            g +=  *(grad_ptr + ix_nw) * dy * dx;\n\n          if (iy > 0 && ix < rd && within_bounds(h1, w1, H1, W1))\n            g += *(grad_ptr + ix_ne) * dy * (1-dx);\n\n          if (iy < rd && ix > 0 && within_bounds(h1, w1, H1, W1))\n            g += *(grad_ptr + ix_sw) * (1-dy) * dx;\n\n          if (iy < rd && ix < rd && within_bounds(h1, w1, H1, W1))\n            g += *(grad_ptr + ix_se) * (1-dy) * (1-dx);\n            \n          for (int k=0; k<CHANNEL_STRIDE; k++) {\n            f1_grad[k][tid] += g * f2[k][tid];\n            f2_grad[k][tid] += g * f1[k][tid];\n          }\n\n          for (int k=0; k<BLOCK_HW; k+=BLOCK_HW/CHANNEL_STRIDE) {\n            int k1 = k + tid / CHANNEL_STRIDE;\n            int h2 = static_cast<int>(floor(y2s[k1]))-r+iy;\n            int w2 = static_cast<int>(floor(x2s[k1]))-r+ix;\n            int c2 = tid % CHANNEL_STRIDE;\n\n            scalar_t* fptr = &fmap2_grad[b][h2][w2][0];\n            if (within_bounds(h2, w2, H2, W2))\n              atomicAdd(fptr+c+c2, f2_grad[c2][k1]);\n          }\n        }\n      } \n    }\n    __syncthreads();\n\n\n    for (int k=0; k<BLOCK_HW; k+=BLOCK_HW/CHANNEL_STRIDE) {\n      int k1 = k + tid / CHANNEL_STRIDE;\n      int h1 = h0 + k1 / BLOCK_W;\n      int w1 = w0 + k1 % BLOCK_W;\n      int c1 = tid % CHANNEL_STRIDE;\n\n      scalar_t* fptr = &fmap1_grad[b][h1][w1][0];\n      if (within_bounds(h1, w1, H1, W1))\n        fptr[c+c1] += f1_grad[c1][k1];\n    }\n  }\n}\n\n\n\nstd::vector<torch::Tensor> altcorr_cuda_forward(\n  torch::Tensor fmap1,\n  torch::Tensor fmap2,\n  torch::Tensor coords,\n  int radius)\n{\n  const auto B = coords.size(0);\n  const auto N = coords.size(1);\n  const auto H = coords.size(2);\n  const auto W = coords.size(3);\n\n  const auto rd = 2 * radius + 1;\n  auto opts = fmap1.options();\n  auto corr = torch::zeros({B, N, rd*rd, H, W}, opts);\n  \n  const dim3 blocks(B, (H+BLOCK_H-1)/BLOCK_H, (W+BLOCK_W-1)/BLOCK_W);\n  const dim3 threads(BLOCK_H, BLOCK_W);\n\n  altcorr_forward_kernel<float><<<blocks, threads>>>(\n    fmap1.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    fmap2.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    coords.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    corr.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    radius);\n\n  return {corr};\n}\n\nstd::vector<torch::Tensor> altcorr_cuda_backward(\n  torch::Tensor fmap1,\n  torch::Tensor fmap2,\n  torch::Tensor coords,\n  torch::Tensor corr_grad,\n  int radius)\n{\n  const auto B = coords.size(0);\n  const auto N = coords.size(1);\n\n  const auto H1 = fmap1.size(1);\n  const auto W1 = fmap1.size(2);\n  const auto H2 = fmap2.size(1);\n  const auto W2 = fmap2.size(2);\n  const auto C = fmap1.size(3);\n\n  auto opts = fmap1.options();\n  auto fmap1_grad = torch::zeros({B, H1, W1, C}, opts);\n  auto fmap2_grad = torch::zeros({B, H2, W2, C}, opts);\n  auto coords_grad = torch::zeros({B, N, H1, W1, 2}, opts);\n    \n  const dim3 blocks(B, (H1+BLOCK_H-1)/BLOCK_H, (W1+BLOCK_W-1)/BLOCK_W);\n  const dim3 threads(BLOCK_H, BLOCK_W);\n\n  altcorr_backward_kernel<float><<<blocks, threads>>>(\n    fmap1.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    fmap2.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    coords.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    corr_grad.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    fmap1_grad.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    fmap2_grad.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    coords_grad.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    radius);\n\n  return {fmap1_grad, fmap2_grad, coords_grad};\n}"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/extras/corr_index_kernel.cu",
    "content": "#include <torch/extension.h>\n#include <cuda.h>\n#include <cuda_runtime.h>\n#include <vector>\n#include <cuda_fp16.h>\n#include <cuda_runtime.h>\n\n\n#include <ATen/ATen.h>\n#include <ATen/NativeFunctions.h>\n#include <ATen/Parallel.h>\n\n#define BLOCK 16\n\n__forceinline__ __device__ bool within_bounds(int h, int w, int H, int W) {\n  return h >= 0 && h < H && w >= 0 && w < W;\n}\n\ntemplate <typename scalar_t>\n__global__ void corr_index_forward_kernel(\n    const torch::PackedTensorAccessor32<scalar_t,5,torch::RestrictPtrTraits> volume,\n    const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> coords,\n    torch::PackedTensorAccessor32<scalar_t,5,torch::RestrictPtrTraits> corr,\n    int r)\n{\n  // batch index\n  const int x = blockIdx.x * blockDim.x + threadIdx.x;\n  const int y = blockIdx.y * blockDim.y + threadIdx.y;\n  const int n = blockIdx.z;\n\n  const int h1 = volume.size(1);\n  const int w1 = volume.size(2);\n  const int h2 = volume.size(3);\n  const int w2 = volume.size(4);\n\n  if (!within_bounds(y, x, h1, w1)) {\n    return;\n  }\n\n  float x0 = coords[n][0][y][x];\n  float y0 = coords[n][1][y][x];\n\n  float dx = x0 - floor(x0);\n  float dy = y0 - floor(y0);\n\n  int rd = 2*r + 1;\n  for (int i=0; i<rd+1; i++) {\n    for (int j=0; j<rd+1; j++) {\n      int x1 = static_cast<int>(floor(x0)) - r + i;\n      int y1 = static_cast<int>(floor(y0)) - r + j;\n\n      if (within_bounds(y1, x1, h2, w2)) {\n        scalar_t s = volume[n][y][x][y1][x1];\n\n        if (i > 0 && j > 0)\n          corr[n][i-1][j-1][y][x] += s * scalar_t(dx * dy);\n\n        if (i > 0 && j < rd)\n          corr[n][i-1][j][y][x] += s * scalar_t(dx * (1.0f-dy));\n\n        if (i < rd && j > 0)\n          corr[n][i][j-1][y][x] += s * scalar_t((1.0f-dx) * dy);\n\n        if (i < rd && j < rd)\n          corr[n][i][j][y][x] += s * scalar_t((1.0f-dx) * (1.0f-dy));\n\n      }\n    }\n  }\n}\n\n\ntemplate <typename scalar_t>\n__global__ void corr_index_backward_kernel(\n    const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> coords,\n    const torch::PackedTensorAccessor32<scalar_t,5,torch::RestrictPtrTraits> corr_grad,\n    torch::PackedTensorAccessor32<scalar_t,5,torch::RestrictPtrTraits> volume_grad,\n    int r)\n{\n  // batch index\n  const int x = blockIdx.x * blockDim.x + threadIdx.x;\n  const int y = blockIdx.y * blockDim.y + threadIdx.y;\n  const int n = blockIdx.z;\n\n  const int h1 = volume_grad.size(1);\n  const int w1 = volume_grad.size(2);\n  const int h2 = volume_grad.size(3);\n  const int w2 = volume_grad.size(4);\n\n  if (!within_bounds(y, x, h1, w1)) {\n    return;\n  }\n\n  float x0 = coords[n][0][y][x];\n  float y0 = coords[n][1][y][x];\n\n  float dx = x0 - floor(x0);\n  float dy = y0 - floor(y0);\n\n  int rd = 2*r + 1;\n  for (int i=0; i<rd+1; i++) {\n    for (int j=0; j<rd+1; j++) {\n      int x1 = static_cast<int>(floor(x0)) - r + i;\n      int y1 = static_cast<int>(floor(y0)) - r + j;\n\n      if (within_bounds(y1, x1, h2, w2)) {\n        scalar_t g = 0.0;\n        if (i > 0 && j > 0)\n          g += corr_grad[n][i-1][j-1][y][x] * scalar_t(dx * dy);\n\n        if (i > 0 && j < rd)\n          g += corr_grad[n][i-1][j][y][x] * scalar_t(dx * (1.0f-dy));\n\n        if (i < rd && j > 0)\n          g += corr_grad[n][i][j-1][y][x] * scalar_t((1.0f-dx) * dy);\n\n        if (i < rd && j < rd)\n          g += corr_grad[n][i][j][y][x] * scalar_t((1.0f-dx) * (1.0f-dy));\n\n        volume_grad[n][y][x][y1][x1] += g;\n      }\n    }\n  }\n}\n\nstd::vector<torch::Tensor> corr_index_cuda_forward(\n    torch::Tensor volume,\n    torch::Tensor coords,\n    int radius)\n{\n  const auto batch_size = volume.size(0);\n  const auto ht = volume.size(1);\n  const auto wd = volume.size(2);\n\n  const dim3 blocks((wd + BLOCK - 1) / BLOCK, \n                    (ht + BLOCK - 1) / BLOCK, \n                    batch_size);\n  \n  const dim3 threads(BLOCK, BLOCK);\n\n  auto opts = volume.options();\n  torch::Tensor corr = torch::zeros(\n    {batch_size, 2*radius+1, 2*radius+1, ht, wd}, opts);\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(volume.type(), \"sampler_forward_kernel\", ([&] {\n    corr_index_forward_kernel<scalar_t><<<blocks, threads>>>(\n      volume.packed_accessor32<scalar_t,5,torch::RestrictPtrTraits>(),\n      coords.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n      corr.packed_accessor32<scalar_t,5,torch::RestrictPtrTraits>(),\n      radius);\n   }));\n\n  return {corr};\n\n}\n\nstd::vector<torch::Tensor> corr_index_cuda_backward(\n  torch::Tensor volume,\n  torch::Tensor coords,\n  torch::Tensor corr_grad,\n  int radius)\n{\n  const auto batch_size = volume.size(0);\n  const auto ht = volume.size(1);\n  const auto wd = volume.size(2);\n\n  auto volume_grad = torch::zeros_like(volume);\n\n  const dim3 blocks((wd + BLOCK - 1) / BLOCK, \n                    (ht + BLOCK - 1) / BLOCK, \n                    batch_size);\n\n  const dim3 threads(BLOCK, BLOCK);\n\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(volume.type(), \"sampler_backward_kernel\", ([&] {\n    corr_index_backward_kernel<scalar_t><<<blocks, threads>>>(\n      coords.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n      corr_grad.packed_accessor32<scalar_t,5,torch::RestrictPtrTraits>(),\n      volume_grad.packed_accessor32<scalar_t,5,torch::RestrictPtrTraits>(),\n      radius);\n   }));\n\n  return {volume_grad};\n}\n\n\n\n\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/extras/extras.cpp",
    "content": "#include <torch/extension.h>\n#include <vector>\n\n\n// C++ interface\n#define CHECK_CUDA(x) TORCH_CHECK(x.type().is_cuda(), #x \" must be a CUDA tensor\")\n#define CHECK_CONTIGUOUS(x) TORCH_CHECK(x.is_contiguous(), #x \" must be contiguous\")\n#define CHECK_INPUT(x) CHECK_CUDA(x); CHECK_CONTIGUOUS(x)\n\n\n// CUDA forward declarations\nstd::vector<torch::Tensor> corr_index_cuda_forward(\n  torch::Tensor volume,\n  torch::Tensor coords,\n  int radius);\n\nstd::vector<torch::Tensor> corr_index_cuda_backward(\n  torch::Tensor volume,\n  torch::Tensor coords,\n  torch::Tensor corr_grad,\n  int radius);\n\nstd::vector<torch::Tensor> altcorr_cuda_forward(\n  torch::Tensor fmap1,\n  torch::Tensor fmap2,\n  torch::Tensor coords,\n  int radius);\n\nstd::vector<torch::Tensor> altcorr_cuda_backward(\n  torch::Tensor fmap1,\n  torch::Tensor fmap2,\n  torch::Tensor coords,\n  torch::Tensor corr_grad,\n  int radius);\n\nstd::vector<torch::Tensor> dense_se3_forward_cuda(\n  torch::Tensor transforms,\n  torch::Tensor embeddings,\n  torch::Tensor points,\n  torch::Tensor targets,\n  torch::Tensor weights,\n  torch::Tensor intrinsics,\n  int radius);\n\nstd::vector<torch::Tensor> dense_se3_backward_cuda(\n  torch::Tensor transforms,\n  torch::Tensor embeddings,\n  torch::Tensor points,\n  torch::Tensor targets,\n  torch::Tensor weights,\n  torch::Tensor intrinsics,\n  torch::Tensor H_grad,\n  torch::Tensor b_grad,\n  int radius);\n\n\nstd::vector<torch::Tensor> se3_build_cuda(\n  torch::Tensor attention,\n  torch::Tensor transforms,\n  torch::Tensor points,\n  torch::Tensor targets,\n  torch::Tensor weights,\n  torch::Tensor intrinsics,\n  int radius);\n\n\nstd::vector<torch::Tensor> se3_build_backward_cuda(\n  torch::Tensor attention,\n  torch::Tensor transforms,\n  torch::Tensor points,\n  torch::Tensor targets,\n  torch::Tensor weights,\n  torch::Tensor intrinsics,\n  torch::Tensor H_grad,\n  torch::Tensor b_grad,\n  int radius);\n\n\nstd::vector<torch::Tensor> cholesky_solve6x6_forward_cuda(\n  torch::Tensor H, torch::Tensor b);\n\nstd::vector<torch::Tensor> cholesky_solve6x6_backward_cuda(\n  torch::Tensor H, torch::Tensor b, torch::Tensor dx);\n\n// c++ python binding\nstd::vector<torch::Tensor> corr_index_forward(\n    torch::Tensor volume,\n    torch::Tensor coords,\n    int radius) {\n  CHECK_INPUT(volume);\n  CHECK_INPUT(coords);\n\n  return corr_index_cuda_forward(volume, coords, radius);\n}\n\nstd::vector<torch::Tensor> corr_index_backward(\n    torch::Tensor volume,\n    torch::Tensor coords,\n    torch::Tensor corr_grad,\n    int radius) {\n  CHECK_INPUT(volume);\n  CHECK_INPUT(coords);\n  CHECK_INPUT(corr_grad);\n\n  auto volume_grad = corr_index_cuda_backward(volume, coords, corr_grad, radius);\n  return {volume_grad};\n}\n\nstd::vector<torch::Tensor> altcorr_forward(\n    torch::Tensor fmap1,\n    torch::Tensor fmap2,\n    torch::Tensor coords,\n    int radius) {\n  CHECK_INPUT(fmap1);\n  CHECK_INPUT(fmap2);\n  CHECK_INPUT(coords);\n\n  return altcorr_cuda_forward(fmap1, fmap2, coords, radius);\n}\n\nstd::vector<torch::Tensor> altcorr_backward(\n    torch::Tensor fmap1,\n    torch::Tensor fmap2,\n    torch::Tensor coords,\n    torch::Tensor corr_grad,\n    int radius) {\n  CHECK_INPUT(fmap1);\n  CHECK_INPUT(fmap2);\n  CHECK_INPUT(coords);\n  CHECK_INPUT(corr_grad);\n\n  return altcorr_cuda_backward(fmap1, fmap2, coords, corr_grad, radius);\n}\n\n\nstd::vector<torch::Tensor> se3_build(\n    torch::Tensor attention,\n    torch::Tensor transforms,\n    torch::Tensor points,\n    torch::Tensor targets,\n    torch::Tensor weights,\n    torch::Tensor intrinsics,\n    int radius) {\n\n  CHECK_INPUT(transforms);\n  CHECK_INPUT(attention);\n  CHECK_INPUT(points);\n  CHECK_INPUT(targets);\n  CHECK_INPUT(weights);\n  CHECK_INPUT(intrinsics);\n\n  return se3_build_cuda(attention, transforms, \n    points, targets, weights, intrinsics, radius);\n}\n\nstd::vector<torch::Tensor> se3_build_backward(\n    torch::Tensor attention,\n    torch::Tensor transforms,\n    torch::Tensor points,\n    torch::Tensor targets,\n    torch::Tensor weights,\n    torch::Tensor intrinsics,\n    torch::Tensor H_grad,\n    torch::Tensor b_grad,\n    int radius) {\n\n  CHECK_INPUT(transforms);\n  CHECK_INPUT(attention);\n  CHECK_INPUT(points);\n  CHECK_INPUT(targets);\n  CHECK_INPUT(weights);\n  CHECK_INPUT(intrinsics);\n\n  CHECK_INPUT(H_grad);\n  CHECK_INPUT(b_grad);\n\n  return se3_build_backward_cuda(attention, transforms, points, \n    targets, weights, intrinsics, H_grad, b_grad, radius);\n}\n\nstd::vector<torch::Tensor> se3_build_inplace(\n    torch::Tensor transforms,\n    torch::Tensor embeddings,\n    torch::Tensor points,\n    torch::Tensor targets,\n    torch::Tensor weights,\n    torch::Tensor intrinsics,\n    int radius) {\n\n  CHECK_INPUT(transforms);\n  CHECK_INPUT(embeddings);\n  CHECK_INPUT(points);\n  CHECK_INPUT(targets);\n  CHECK_INPUT(weights);\n  CHECK_INPUT(intrinsics);\n\n  return dense_se3_forward_cuda(transforms, embeddings, \n    points, targets, weights, intrinsics, radius);\n}\n\nstd::vector<torch::Tensor> se3_build_inplace_backward(\n    torch::Tensor transforms,\n    torch::Tensor embeddings,\n    torch::Tensor points,\n    torch::Tensor targets,\n    torch::Tensor weights,\n    torch::Tensor intrinsics,\n    torch::Tensor H_grad,\n    torch::Tensor b_grad,\n    int radius) {\n\n  CHECK_INPUT(transforms);\n  CHECK_INPUT(embeddings);\n  CHECK_INPUT(points);\n  CHECK_INPUT(targets);\n  CHECK_INPUT(weights);\n  CHECK_INPUT(intrinsics);\n\n  CHECK_INPUT(H_grad);\n  CHECK_INPUT(b_grad);\n\n  return dense_se3_backward_cuda(transforms, embeddings, points, \n    targets, weights, intrinsics, H_grad, b_grad, radius);\n}\n\n\nstd::vector<torch::Tensor> cholesky6x6_forward(\n    torch::Tensor H,\n    torch::Tensor b) {\n  CHECK_INPUT(H);\n  CHECK_INPUT(b);\n  \n  return cholesky_solve6x6_forward_cuda(H, b);\n}\n\nstd::vector<torch::Tensor> cholesky6x6_backward(\n    torch::Tensor H,\n    torch::Tensor b,\n    torch::Tensor dx) {\n\n  CHECK_INPUT(H);\n  CHECK_INPUT(b);\n  CHECK_INPUT(dx);\n\n  return cholesky_solve6x6_backward_cuda(H, b, dx);\n}\n\nPYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {\n  m.def(\"altcorr_forward\", &altcorr_forward, \"ALTCORR forward\");\n  m.def(\"altcorr_backward\", &altcorr_backward, \"ALTCORR backward\");\n  m.def(\"corr_index_forward\", &corr_index_forward, \"INDEX forward\");\n  m.def(\"corr_index_backward\", &corr_index_backward, \"INDEX backward\");\n\n  // RAFT-3D functions\n  m.def(\"se3_build\", &se3_build, \"build forward\");\n  m.def(\"se3_build_backward\", &se3_build_backward, \"build backward\");\n  \n  m.def(\"se3_build_inplace\", &se3_build_inplace, \"build forward\");\n  m.def(\"se3_build_inplace_backward\", &se3_build_inplace_backward, \"build backward\");\n\n  m.def(\"cholesky6x6_forward\", &cholesky6x6_forward, \"solve forward\");\n  m.def(\"cholesky6x6_backward\", &cholesky6x6_backward, \"solve backward\");\n}\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/extras/se3_builder.cu",
    "content": "#include <torch/extension.h>\n#include <cuda.h>\n#include <cuda_runtime.h>\n#include <vector>\n#include <iostream>\n\n#define NUM_THREADS 64\n// #define RADIUS 32\n\n\n__global__ void se3_build_forward_kernel(\n  const torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> attention,\n  const torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> transforms,\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> points,\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> targets,\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> weights,\n  const torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> intrinsics,\n  torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> Hx,\n  torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> bx,\n  int radius)\n{\n    /* Dense transform layer aggregation step\n        Inputs:\n            attention:      [B, H, W, H, W]\n            transforms:     [B, H, W, 4, 4]\n            points:         [B, 3, H, W]\n            targets:        [B, 2, H, W]\n            weights:        [B, 2, H, W]\n            intrinsics:     [B, 4]\n\n        Outputs:\n            Hx:             [B, H, W, 6, 6]\n            bx:             [B, H, W, 6, 1]\n    */\n    \n  int batch_id = blockIdx.x; // batch_index\n  int tx = threadIdx.x;\n  int ix = blockIdx.y * NUM_THREADS + tx; // image_index\n\n  int ht = attention.size(1);\n  int wd = attention.size(2);\n  int dim = ht * wd;\n\n  int h1 = ix / wd;\n  int w1 = ix % wd;\n\n  const float* Gdata = transforms[batch_id].data();\n  const float* Xdata = points[batch_id].data();\n  const float* rdata = targets[batch_id].data();\n  const float* wdata = weights[batch_id].data();\n\n  __shared__ float fx, fy, cx, cy;\n  if (tx == 0) {\n    fx = intrinsics[batch_id][0];\n    fy = intrinsics[batch_id][1];\n    cx = intrinsics[batch_id][2];\n    cy = intrinsics[batch_id][3];\n  }\n\n  float G[12];\n  if (ix < dim) {\n    for (int k=0; k<12; k++)\n      G[k] = Gdata[ix + k*dim];\n  }\n\n  // linear system\n  float H[6][6];\n  float b[6];\n\n  for (int ii=0; ii<6; ii++) {\n    b[ii] = 0.0f;\n    for (int jj=0; jj<6; jj++) {\n      H[ii][jj] = 0.0f;\n    }\n  }\n\n  // jacobians\n  float Ju[6];\n  float Jv[6];\n  float Jz[6];\n\n  __shared__ float X0[3][NUM_THREADS];\n  __shared__ float rvec[3][NUM_THREADS];\n  __shared__ float wvec[3][NUM_THREADS];\n\n  __syncthreads();\n\n  for (int i=0; i<dim; i+=NUM_THREADS) {\n    // load in data\n    int jx = i + tx;\n    if (jx < dim) {\n      X0[0][tx] = Xdata[jx+0*dim];\n      X0[1][tx] = Xdata[jx+1*dim];\n      X0[2][tx] = Xdata[jx+2*dim];\n\n      rvec[0][tx] = rdata[jx+0*dim];\n      rvec[1][tx] = rdata[jx+1*dim];\n      rvec[2][tx] = rdata[jx+2*dim];\n\n      wvec[0][tx] = wdata[jx+0*dim];\n      wvec[1][tx] = wdata[jx+1*dim];\n      wvec[2][tx] = wdata[jx+2*dim];\n    }\n\n    __syncthreads();\n\n    for (int j=0; j<NUM_THREADS; j++) {\n      jx = i + j;\n      if (ix<dim && jx<dim) {\n        int h2 = jx / wd;\n        int w2 = jx % wd;\n\n        int r = max(abs(h1-h2), abs(w1-w2));\n        if (r > radius) \n          continue;\n\n        float w = attention[batch_id][h1][w1][h2][w2];\n        float wu = w * wvec[0][j];\n        float wv = w * wvec[1][j];\n        float wz = w * wvec[2][j];\n\n        float X1, Y1, Z1;\n        X1 = G[0]*X0[0][j] + G[1]*X0[1][j] + G[2]*X0[2][j] + G[3];\n        Y1 = G[4]*X0[0][j] + G[5]*X0[1][j] + G[6]*X0[2][j] + G[7];\n        Z1 = G[8]*X0[0][j] + G[9]*X0[1][j] + G[10]*X0[2][j] + G[11];\n\n        if (Z1 < 0.1) Z1 = 0.001;\n\n        // residual vectors\n        float ru = rvec[0][j] - (fx * (X1 / Z1) + cx);\n        float rv = rvec[1][j] - (fy * (Y1 / Z1) + cy);\n        float rz = rvec[2][j] - (1.0 / Z1);\n\n        if (abs(ru) > 250 || abs(rv) > 250 || Z1 < 0.1) {\n          continue;\n        }\n\n        float d = 1.f/Z1; \n        float d2 = d*d;\n\n        // x-jacobians\n        Ju[0] = fx * d;\n        Ju[1] = fx * 0.0;\n        Ju[2] = fx * (-X1*d2);\n        Ju[3] = fx * (-X1*Y1*d2);\n        Ju[4] = fx * (1 + X1*X1*d2);\n        Ju[5] = fx * (-Y1*d);\n\n        // y-jacobians\n        Jv[0] = fy * 0.0;\n        Jv[1] = fy * d;\n        Jv[2] = fy * (-Y1*d2);\n        Jv[3] = fy * -1 * (1+Y1*Y1*d2);\n        Jv[4] = fy * X1*Y1*d2;\n        Jv[5] = fy * X1*d;\n\n        // z-jacobians\n        Jz[0] = 0.0;\n        Jz[1] = 0.0;\n        Jz[2] = -d2;\n        Jz[3] = d * Y1;\n        Jz[4] = -d * X1;\n        Jz[5] = 0.0;\n\n        for (int ii=0; ii<6; ii++) {\n          b[ii] += wu*ru*Ju[ii] + wv*rv*Jv[ii] + wz*rz*Jz[ii];\n          for (int jj=0; jj<6; jj++) {\n            H[ii][jj] += wu*Ju[ii]*Ju[jj] + wv*Jv[ii]*Jv[jj] + wz*Jz[ii]*Jz[jj];\n          }\n        }\n\n      }\n    }\n    __syncthreads();\n  }\n\n  if (ix < dim) {\n    for (int ii=0; ii<6; ii++) {\n      bx[batch_id][ii][0][h1][w1] = b[ii];\n      for (int jj=0; jj<6; jj++) {\n        Hx[batch_id][ii][jj][h1][w1] = H[ii][jj];\n      }\n    }\n  }\n}\n\n\n__global__ void se3_build_backward_kernel(\n  const torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> attention,\n  const torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> transforms,\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> points,\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> targets,\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> weights,\n  const torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> intrinsics,\n  const torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> Hx_grad,\n  const torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> bx_grad,\n  torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> attention_grad,\n  torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> targets_grad,\n  torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> weights_grad,\n  int radius)\n{\n\n  int batch_id = blockIdx.x; // batch_index\n  int tx = threadIdx.x;\n  int ix = blockIdx.y * NUM_THREADS + tx; // image_index\n\n  int ht = attention.size(1);\n  int wd = attention.size(2);\n  int dim = ht * wd;\n\n  int h2 = ix / wd;\n  int w2 = ix % wd;\n\n  const float* Gdata = transforms[batch_id].data();\n  const float* Hdata = Hx_grad[batch_id].data();\n  const float* bdata = bx_grad[batch_id].data();\n\n  __shared__ float fx, fy, cx, cy;\n  if (tx == 0) {\n    fx = intrinsics[batch_id][0];\n    fy = intrinsics[batch_id][1];\n    cx = intrinsics[batch_id][2];\n    cy = intrinsics[batch_id][3];\n  }\n\n  float X0[3];\n  X0[0] = points[batch_id][0][h2][w2];\n  X0[1] = points[batch_id][1][h2][w2];\n  X0[2] = points[batch_id][2][h2][w2];\n\n  float target_u = targets[batch_id][0][h2][w2];\n  float target_v = targets[batch_id][1][h2][w2];\n  float target_z = targets[batch_id][2][h2][w2];\n\n  float wu = weights[batch_id][0][h2][w2];\n  float wv = weights[batch_id][1][h2][w2];\n  float wz = weights[batch_id][2][h2][w2];\n\n  // jacobians\n  float Ju[6], Jv[6], Jz[6];\n  float diff_ru = 0.0f;\n  float diff_rv = 0.0f;\n  float diff_rz = 0.0f;\n  float diff_wu = 0.0f;\n  float diff_wv = 0.0f;\n  float diff_wz = 0.0f;\n\n  __shared__ float Gs[12][NUM_THREADS];\n  __shared__ float H_grad[36][NUM_THREADS];\n  __shared__ float b_grad[6][NUM_THREADS];\n  \n  __syncthreads();\n\n  for (int i=0; i<dim; i+=NUM_THREADS) {\n    int jx = i + tx;\n    if (jx < dim) {\n      for (int k=0; k<12; k++)\n        Gs[k][tx] = Gdata[jx + k*dim];\n\n      for (int k=0; k<36; k++)\n        H_grad[k][tx] = Hdata[jx + k*dim];\n\n      for (int k=0; k<6; k++)\n        b_grad[k][tx] = bdata[jx + k*dim];\n    }\n\n    __syncthreads();\n\n    for (int j=0; j<NUM_THREADS; j++) {\n      jx = i + j;\n      if (ix<dim && jx<dim) {\n        int h1 = jx / wd;\n        int w1 = jx % wd;\n\n        int r = max(abs(h1-h2), abs(w1-w2));\n        if (r > radius) \n          continue;\n\n        float w = attention[batch_id][h1][w1][h2][w2];\n        float diff_w = 0.0f;\n\n        float X1, Y1, Z1;\n        X1 = Gs[0][j]*X0[0] + Gs[1][j]*X0[1] + Gs[2][j]*X0[2] + Gs[3][j];\n        Y1 = Gs[4][j]*X0[0] + Gs[5][j]*X0[1] + Gs[6][j]*X0[2] + Gs[7][j];\n        Z1 = Gs[8][j]*X0[0] + Gs[9][j]*X0[1] + Gs[10][j]*X0[2] + Gs[11][j];\n\n        if (Z1 < 0.1) Z1 = 0.001;\n\n        // residual vectors\n        float ru = target_u - (fx * (X1 / Z1) + cx);\n        float rv = target_v - (fy * (Y1 / Z1) + cy);\n        float rz = target_z - (1.0 / Z1);\n\n        if (abs(ru) > 50 || abs(rv) > 50 || Z1 < 0.1) {\n          continue;\n        }\n\n        float d = 1.f/Z1; \n        float d2 = d*d;\n\n        // x-jacobians\n        Ju[0] = fx * d;\n        Ju[1] = fx * 0.0;\n        Ju[2] = fx * (-X1*d2);\n        Ju[3] = fx * (-X1*Y1*d2);\n        Ju[4] = fx * (1 + X1*X1*d2);\n        Ju[5] = fx * (-Y1*d);\n\n        // y-jacobians\n        Jv[0] = fy * 0.0;\n        Jv[1] = fy * d;\n        Jv[2] = fy * (-Y1*d2);\n        Jv[3] = fy * -1 * (1+Y1*Y1*d2);\n        Jv[4] = fy * X1*Y1*d2;\n        Jv[5] = fy * X1*d;\n\n        // z-jacobians\n        Jz[0] = 0.0;\n        Jz[1] = 0.0;\n        Jz[2] = -d2;\n        Jz[3] = d * Y1;\n        Jz[4] = -d * X1;\n        Jz[5] = 0.0;\n\n        for (int ii=0; ii<6; ii++) {\n          // residual gradients\n          diff_ru += w*wu*Ju[ii]*b_grad[ii][j];\n          diff_rv += w*wv*Jv[ii]*b_grad[ii][j];\n          diff_rz += w*wz*Jz[ii]*b_grad[ii][j];\n\n          // weights gradients\n          diff_wu += w*ru*Ju[ii]*b_grad[ii][j];\n          diff_wv += w*rv*Jv[ii]*b_grad[ii][j];\n          diff_wz += w*rz*Jz[ii]*b_grad[ii][j];\n\n          // embedding weight\n          diff_w += (wu*ru*Ju[ii] + wv*rv*Jv[ii] + wz*rz*Jz[ii]) * b_grad[ii][j];\n\n          for (int jj=0; jj<6; jj++) {\n            diff_wu += w*Ju[ii]*Ju[jj]*H_grad[6*ii+jj][j];\n            diff_wv += w*Jv[ii]*Jv[jj]*H_grad[6*ii+jj][j];\n            diff_wz += w*Jz[ii]*Jz[jj]*H_grad[6*ii+jj][j];\n            diff_w += (wu*Ju[ii]*Ju[jj] + wv*Jv[ii]*Jv[jj] + wz*Jz[ii]*Jz[jj])*H_grad[6*ii+jj][j];\n          }\n        }\n\n        attention_grad[batch_id][h1][w1][h2][w2] = diff_w;\n      }\n    }\n    __syncthreads();\n  }\n\n  targets_grad[batch_id][0][h2][w2] = diff_ru;\n  targets_grad[batch_id][1][h2][w2] = diff_rv;\n  targets_grad[batch_id][2][h2][w2] = diff_rz;\n\n  weights_grad[batch_id][0][h2][w2] = diff_wu;\n  weights_grad[batch_id][1][h2][w2] = diff_wv;\n  weights_grad[batch_id][2][h2][w2] = diff_wz;\n}\n\n\nstd::vector<torch::Tensor> se3_build_cuda(\n  torch::Tensor attention,\n  torch::Tensor transforms,\n  torch::Tensor points,\n  torch::Tensor targets,\n  torch::Tensor weights,\n  torch::Tensor intrinsics,\n  int radius)\n{\n\n  int batch_size = attention.size(0);\n  int ht = attention.size(1);\n  int wd = attention.size(2);\n\n  dim3 grid = dim3(batch_size, (ht*wd + NUM_THREADS-1) / NUM_THREADS);\n\n  auto opts = attention.options();\n  torch::Tensor H = torch::zeros({batch_size, 6, 6, ht, wd}, opts);\n  torch::Tensor b = torch::zeros({batch_size, 6, 1, ht, wd}, opts);\n\n  se3_build_forward_kernel<<<grid, NUM_THREADS>>>(\n    attention.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    transforms.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    points.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    targets.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    weights.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    intrinsics.packed_accessor32<float,2,torch::RestrictPtrTraits>(),\n    H.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    b.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    radius);\n\n  return {H, b};\n}\n\n\nstd::vector<torch::Tensor> se3_build_backward_cuda(\n  torch::Tensor attention,\n  torch::Tensor transforms,\n  torch::Tensor points,\n  torch::Tensor targets,\n  torch::Tensor weights,\n  torch::Tensor intrinsics,\n  torch::Tensor H_grad,\n  torch::Tensor b_grad,\n  int radius)\n{\n\n  int batch_size = attention.size(0);\n  int ht = attention.size(1);\n  int wd = attention.size(2);\n\n  dim3 grid = dim3(batch_size, (ht*wd + NUM_THREADS-1) / NUM_THREADS);\n  torch::Tensor attention_grad = torch::zeros_like(attention);\n  torch::Tensor targets_grad = torch::zeros_like(targets);\n  torch::Tensor weights_grad = torch::zeros_like(weights);\n\n  se3_build_backward_kernel<<<grid, NUM_THREADS>>>(\n    attention.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    transforms.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    points.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    targets.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    weights.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    intrinsics.packed_accessor32<float,2,torch::RestrictPtrTraits>(),\n    H_grad.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    b_grad.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    attention_grad.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    targets_grad.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    weights_grad.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    radius);\n\n  return {attention_grad, targets_grad, weights_grad};\n}"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/extras/se3_inplace_builder.cu",
    "content": "#include <torch/extension.h>\n#include <cuda.h>\n#include <cuda_runtime.h>\n#include <vector>\n#include <iostream>\n\n#define NUM_THREADS 64\n#define AE_DIM 32\n\n__device__ __forceinline__ float sigmoid(float x) {\n  return exp(x) / (exp(x) + 1.0);\n}\n\n__device__ __forceinline__ void\nse3_transform_point_inplace(const float T[7], float X[3]) {\n  const float tx=T[0], ty=T[1], tz=T[2];\n  const float qx=T[3], qy=T[4], qz=T[5], qw=T[6];  \n  \n  float uv[3];\n  uv[0] = 2.0 * (qy*X[2] - qz*X[1]);\n  uv[1] = 2.0 * (qz*X[0] - qx*X[2]);\n  uv[2] = 2.0 * (qx*X[1] - qy*X[0]);\n\n  X[0] += qw*uv[0] + (qy*uv[2] - qz*uv[1]) + tx;\n  X[1] += qw*uv[1] + (qz*uv[0] - qx*uv[2]) + ty;\n  X[2] += qw*uv[2] + (qx*uv[1] - qy*uv[0]) + tz;\n}\n\n__device__ __forceinline__ void\npinhole_jacobians(const float p[3], const float fx, const float fy, float Ju[6], float Jv[6], float Jz[6]) {\n  const float X1=p[0], Y1=p[1], Z1=p[2];\n  const float d = 1.0 / Z1; \n  const float d2 = d * d;\n\n  // x-jacobians\n  Ju[0] = fx * d;\n  Ju[1] = fx * 0.0;\n  Ju[2] = fx * (-X1*d2);\n  Ju[3] = fx * (-X1*Y1*d2);\n  Ju[4] = fx * (1 + X1*X1*d2);\n  Ju[5] = fx * (-Y1*d);\n\n  // y-jacobians\n  Jv[0] = fy * 0.0;\n  Jv[1] = fy * d;\n  Jv[2] = fy * (-Y1*d2);\n  Jv[3] = fy * -1 * (1+Y1*Y1*d2);\n  Jv[4] = fy * X1*Y1*d2;\n  Jv[5] = fy * X1*d;\n\n  // z-jacobians\n  Jz[0] = 0.0;\n  Jz[1] = 0.0;\n  Jz[2] = -d2;\n  Jz[3] = d * Y1;\n  Jz[4] = -d * X1;\n  Jz[5] = 0.0;\n}\n\n\n__global__ void dense_se3_forward_kernel(\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> transforms,\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> embeddings,\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> points,\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> targets,\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> weights,\n  const torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> intrinsics,\n  torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> Hx,\n  torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> bx,\n  int radius)\n{\n\n  int batch_id = blockIdx.x; // batch_index\n  int tx = threadIdx.x;\n  int ix = blockIdx.y * NUM_THREADS + tx; // image_index\n\n  const int ht = transforms.size(2);\n  const int wd = transforms.size(3);\n  const int ae_dim = embeddings.size(1);\n\n  const int dim = ht * wd;\n  const int h1 = ix / wd;\n  const int w1 = ix % wd;\n\n  const float* Xdata = points[batch_id].data();\n  const float* rdata = targets[batch_id].data();\n  const float* wdata = weights[batch_id].data();\n  const float* ae_data = embeddings[batch_id].data();\n\n  __shared__ float fx, fy, cx, cy;\n  if (tx == 0) {\n    fx = intrinsics[batch_id][0];\n    fy = intrinsics[batch_id][1];\n    cx = intrinsics[batch_id][2];\n    cy = intrinsics[batch_id][3];\n  }\n\n  // transformation\n  float G[7];\n  float ae1[AE_DIM];\n\n  // linear system\n  float H[6][6], b[6];\n\n  if (ix < dim) {\n    G[0] = transforms[batch_id][0][h1][w1]; // tx\n    G[1] = transforms[batch_id][1][h1][w1]; // ty\n    G[2] = transforms[batch_id][2][h1][w1]; // tz\n    G[3] = transforms[batch_id][3][h1][w1]; // qx\n    G[4] = transforms[batch_id][4][h1][w1]; // qy\n    G[5] = transforms[batch_id][5][h1][w1]; // qz\n    G[6] = transforms[batch_id][6][h1][w1]; // qw\n\n    for (int ii=0; ii<ae_dim; ii++) {\n      ae1[ii] = embeddings[batch_id][ii][h1][w1];\n    }\n  }\n\n  for (int ii=0; ii<6; ii++) {\n    b[ii] = 0;\n  }\n\n  for (int ii=0; ii<6; ii++) {\n    for (int jj=0; jj<6; jj++) {\n      H[ii][jj] = 0;\n    }\n  }\n\n  // jacobians\n  float Ju[6], Jv[6], Jz[6];\n\n  __shared__ float X0[3][NUM_THREADS];\n  __shared__ float ae2[AE_DIM][NUM_THREADS];\n  __shared__ float rvec[3][NUM_THREADS];\n  __shared__ float wvec[3][NUM_THREADS];\n\n  __syncthreads();\n\n  for (int i=0; i<dim; i+=NUM_THREADS) {\n    // load in data\n    int jx = i + tx;\n    if (jx < dim) {\n      X0[0][tx] = Xdata[jx+0*dim];\n      X0[1][tx] = Xdata[jx+1*dim];\n      X0[2][tx] = Xdata[jx+2*dim];\n\n      rvec[0][tx] = rdata[jx+0*dim];\n      rvec[1][tx] = rdata[jx+1*dim];\n      rvec[2][tx] = rdata[jx+2*dim];\n\n      wvec[0][tx] = wdata[jx+0*dim];\n      wvec[1][tx] = wdata[jx+1*dim];\n      wvec[2][tx] = wdata[jx+2*dim];\n\n      for (int k=0; k<ae_dim; k++)\n        ae2[k][tx] = ae_data[jx + k*dim];\n    }\n\n    __syncthreads();\n\n    for (int j=0; j<NUM_THREADS; j++) {\n      jx = i + j;\n      if (ix<dim && jx<dim) {\n        int h2 = jx / wd;\n        int w2 = jx % wd;\n\n        int r = max(abs(h1-h2), abs(w1-w2));        \n        if (r > radius) \n          continue;\n\n        float p[3] = { X0[0][j], X0[1][j], X0[2][j] };        \n        se3_transform_point_inplace(G, p);\n        \n        // residual vectors\n        const float X1=p[0], Y1=p[1], Z1=p[2];\n\n\n        const float u = fx * (X1 / Z1) + cx;\n        const float v = fy * (Y1 / Z1) + cy;\n        const float ru = rvec[0][j] - u;\n        const float rv = rvec[1][j] - v;\n        const float rz = rvec[2][j] - 1.0 / Z1;\n\n        // exclude pixels too close or errors too big\n        if (Z1 < 0.1 || abs(ru) > 128 || abs(rv) > 128) \n          continue;\n      \n        float s=0.0;\n        for (int k=0; k<ae_dim; k++) {\n          s += (ae1[k] - ae2[k][j]) * (ae1[k] - ae2[k][j]);\n        }\n        \n        const float w = sigmoid(-s);\n        const float wu = w * wvec[0][j];\n        const float wv = w * wvec[1][j];\n        const float wz = w * wvec[2][j];\n\n        pinhole_jacobians(p, fx, fy, Ju, Jv, Jz);\n\n        for (int ii=0; ii<6; ii++) {\n          b[ii] += wu*ru*Ju[ii] + wv*rv*Jv[ii] + wz*rz*Jz[ii];\n        }\n\n        for (int ii=0; ii<6; ii++) {\n          for (int jj=0; jj<6; jj++) {\n            H[ii][jj] += wu*Ju[ii]*Ju[jj] + wv*Jv[ii]*Jv[jj] + wz*Jz[ii]*Jz[jj];\n          }\n        }\n      }\n    }\n    __syncthreads();\n  }\n\n  if (ix < dim) {\n\n    for (int ii=0; ii<6; ii++) {\n      bx[batch_id][ii][0][h1][w1] = b[ii];\n    }\n\n    for (int ii=0; ii<6; ii++) {\n      for (int jj=0; jj<6; jj++) {\n        Hx[batch_id][ii][jj][h1][w1] = H[ii][jj];\n      }\n    }\n\n  }\n}\n\n\n__global__ void dense_se3_backward_kernel1(\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> transforms,\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> embeddings,\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> points,\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> targets,\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> weights,\n  const torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> intrinsics,\n  const torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> Hx_grad,\n  const torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> bx_grad,\n  torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> embedding_grad,\n  torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> targets_grad,\n  torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> weights_grad,\n  int radius)\n{\n\n  int batch_id = blockIdx.x; // batch_index\n  int tx = threadIdx.x;\n  int ix = blockIdx.y * NUM_THREADS + tx; // image_index\n\n  const int ht = transforms.size(2);\n  const int wd = transforms.size(3);\n  const int dim = ht * wd;\n  const int ae_dim = embeddings.size(1);\n\n  int h2 = ix / wd;\n  int w2 = ix % wd;\n\n  const float* transform_data = transforms[batch_id].data();\n  const float* ae_data = embeddings[batch_id].data();\n  const float* diffH_data = Hx_grad[batch_id].data();\n  const float* diffb_data = bx_grad[batch_id].data();\n\n  __shared__ float fx, fy, cx, cy;\n  if (tx == 0) {\n    fx = intrinsics[batch_id][0];\n    fy = intrinsics[batch_id][1];\n    cx = intrinsics[batch_id][2];\n    cy = intrinsics[batch_id][3];\n  }\n\n  float X0[3];\n  float target_u, target_v, target_z;\n  float wu, wv, wz;\n\n  float ae2[AE_DIM];\n  float diff_ae2[AE_DIM];\n\n  if (ix < dim) {\n    X0[0] = points[batch_id][0][h2][w2];\n    X0[1] = points[batch_id][1][h2][w2];\n    X0[2] = points[batch_id][2][h2][w2];\n\n    target_u = targets[batch_id][0][h2][w2];\n    target_v = targets[batch_id][1][h2][w2];\n    target_z = targets[batch_id][2][h2][w2];\n\n    wu = weights[batch_id][0][h2][w2];\n    wv = weights[batch_id][1][h2][w2];\n    wz = weights[batch_id][2][h2][w2];\n    \n    for (int ii=0; ii<ae_dim; ii++) {\n      ae2[ii] = ae_data[ix + ii*dim];\n      diff_ae2[ii] = 0;\n    }\n  }\n\n  // jacobians\n  float Ju[6], Jv[6], Jz[6];\n  float diff_ru = 0;\n  float diff_rv = 0;\n  float diff_rz = 0;\n  float diff_wu = 0;\n  float diff_wv = 0;\n  float diff_wz = 0;\n\n  __shared__ float Gs[NUM_THREADS][7];\n  __shared__ float dH[6][6][NUM_THREADS];\n  __shared__ float db[6][NUM_THREADS];\n  __shared__ float ae1[AE_DIM][NUM_THREADS];\n  \n  __syncthreads();\n\n  for (int i=0; i<dim; i+=NUM_THREADS) {\n    int jx = i + tx;\n\n    // read from global\n    if (jx < dim) {\n      Gs[tx][0] = transform_data[jx + 0*dim];\n      Gs[tx][1] = transform_data[jx + 1*dim];\n      Gs[tx][2] = transform_data[jx + 2*dim];\n      Gs[tx][3] = transform_data[jx + 3*dim];\n      Gs[tx][4] = transform_data[jx + 4*dim];\n      Gs[tx][5] = transform_data[jx + 5*dim];\n      Gs[tx][6] = transform_data[jx + 6*dim];\n\n      for (int ii=0; ii<ae_dim; ii++) {\n        ae1[ii][tx] = ae_data[jx + ii*dim];\n      }\n\n      for (int ii=0; ii<6; ii++) {\n        for (int jj=0; jj<6; jj++) {\n          dH[ii][jj][tx] = diffH_data[jx + (ii*6+jj)*dim];\n        }\n      }\n\n      for (int ii=0; ii<6; ii++) {\n        db[ii][tx] = diffb_data[jx + ii*dim];\n      }\n    }\n\n    __syncthreads();\n\n    for (int j=0; j<NUM_THREADS; j++) {\n      jx = i + j;\n      if (ix<dim && jx<dim) {\n        int h1 = jx / wd;\n        int w1 = jx % wd;\n\n        int r = max(abs(h1-h2), abs(w1-w2));\n        if (r > radius) continue;\n  \n        float p[3] = { X0[0], X0[1], X0[2] };\n        se3_transform_point_inplace(&Gs[j][0], p);\n        \n        // residual vectors\n        const float X1=p[0], Y1=p[1], Z1=p[2];\n        const float u = fx * (X1 / Z1) + cx;\n        const float v = fy * (Y1 / Z1) + cy;\n        const float ru = target_u - u;\n        const float rv = target_v - v;\n        const float rz = target_z - 1.0 / Z1;\n\n        float s=0.0;\n        for (int k=0; k<ae_dim; k++) {\n          s += (ae1[k][j] - ae2[k]) * (ae1[k][j] - ae2[k]);\n        }\n        \n        float diff_w = 0.0f;\n        const float w = sigmoid(-s);\n\n        // exclude pixels too close or errors too big\n        if (Z1 < 0.1 || abs(ru) > 128 || abs(rv) > 128) \n          continue;\n\n        pinhole_jacobians(p, fx, fy, Ju, Jv, Jz);\n\n        for (int ii=0; ii<6; ii++) {\n\n          const float db_i = db[ii][j];\n          // residual gradients\n          diff_ru += w*wu*Ju[ii] * db_i;\n          diff_rv += w*wv*Jv[ii] * db_i;\n          diff_rz += w*wz*Jz[ii] * db_i;\n\n          // weights gradients\n          diff_wu += w*ru*Ju[ii] * db_i;\n          diff_wv += w*rv*Jv[ii] * db_i;\n          diff_wz += w*rz*Jz[ii] * db_i;\n\n          // embedding weight\n          diff_w += (wu*ru*Ju[ii] + wv*rv*Jv[ii] + wz*rz*Jz[ii]) * db_i;\n\n          for (int jj=0; jj<6; jj++) {\n            const float dH_ij = dH[ii][jj][j];\n            diff_wu += w*Ju[ii]*Ju[jj] * dH_ij;\n            diff_wv += w*Jv[ii]*Jv[jj] * dH_ij;\n            diff_wz += w*Jz[ii]*Jz[jj] * dH_ij;\n            diff_w += (wu*Ju[ii]*Ju[jj] + wv*Jv[ii]*Jv[jj] + wz*Jz[ii]*Jz[jj]) * dH_ij;\n          }\n        }\n\n        float diff_s = -diff_w * sigmoid(-s) * (1.0f - sigmoid(-s));\n        for (int k=0; k<ae_dim; k++) {\n          diff_ae2[k] += -2 * diff_s * (ae1[k][j] - ae2[k]);\n        }\n      }\n    }\n    __syncthreads();\n  }\n\n  if (ix < dim) {\n    targets_grad[batch_id][0][h2][w2] = diff_ru;\n    targets_grad[batch_id][1][h2][w2] = diff_rv;\n    targets_grad[batch_id][2][h2][w2] = diff_rz;\n\n    weights_grad[batch_id][0][h2][w2] = diff_wu;\n    weights_grad[batch_id][1][h2][w2] = diff_wv;\n    weights_grad[batch_id][2][h2][w2] = diff_wz;\n\n    for (int k=0; k<ae_dim; k++)\n      embedding_grad[batch_id][k][h2][w2] += diff_ae2[k];\n  }\n}\n\n\n__global__ void dense_se3_backward_kernel2(\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> transforms,\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> embeddings,\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> points,\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> targets,\n  const torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> weights,\n  const torch::PackedTensorAccessor32<float,2,torch::RestrictPtrTraits> intrinsics,\n  const torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> Hx_grad,\n  const torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> bx_grad,\n  torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> embedding_grad,\n  torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> targets_grad,\n  torch::PackedTensorAccessor32<float,4,torch::RestrictPtrTraits> weights_grad,\n  int radius) {\n\n  int batch_id = blockIdx.x; // batch_index\n  int tx = threadIdx.x;\n  int ix = blockIdx.y * NUM_THREADS + tx; // image_index\n\n  const int ht = transforms.size(2);\n  const int wd = transforms.size(3);\n  const int ae_dim = embeddings.size(1);\n\n  const int dim = ht * wd;\n  const int h1 = ix / wd;\n  const int w1 = ix % wd;\n\n  const float* transform_data = transforms[batch_id].data();\n  const float* Xdata = points[batch_id].data();\n  const float* rdata = targets[batch_id].data();\n  const float* wdata = weights[batch_id].data();\n  const float* ae_data = embeddings[batch_id].data();\n\n  __shared__ float fx, fy, cx, cy;\n  if (tx == 0) {\n    fx = intrinsics[batch_id][0];\n    fy = intrinsics[batch_id][1];\n    cx = intrinsics[batch_id][2];\n    cy = intrinsics[batch_id][3];\n  }\n\n  // transformation\n  float G[7];\n  float ae1[AE_DIM];\n  float diff_ae1[AE_DIM];\n\n  float db[6], dH[6][6];\n  if (ix < dim) {\n    G[0] = transform_data[ix + 0*dim]; // tx\n    G[1] = transform_data[ix + 1*dim]; // ty\n    G[2] = transform_data[ix + 2*dim]; // tz\n    G[3] = transform_data[ix + 3*dim]; // qx\n    G[4] = transform_data[ix + 4*dim]; // qy\n    G[5] = transform_data[ix + 5*dim]; // qz\n    G[6] = transform_data[ix + 6*dim]; // qw\n\n    for (int ii=0; ii<ae_dim; ii++) {\n      ae1[ii] = embeddings[batch_id][ii][h1][w1];\n      diff_ae1[ii] = 0;\n    }\n    \n    for (int ii=0; ii<6; ii++) {\n      db[ii] = bx_grad[batch_id][ii][0][h1][w1];\n    }\n\n    for (int ii=0; ii<6; ii++) {\n      for (int jj=0; jj<6; jj++) {\n        dH[ii][jj] = Hx_grad[batch_id][ii][jj][h1][w1];\n      }\n    }\n  }\n\n\n  // jacobians\n  float Ju[6], Jv[6], Jz[6];\n\n  __shared__ float X0[3][NUM_THREADS];\n  __shared__ float ae2[AE_DIM][NUM_THREADS];\n  __shared__ float rvec[3][NUM_THREADS];\n  __shared__ float wvec[3][NUM_THREADS];\n\n  __syncthreads();\n\n  for (int i=0; i<dim; i+=NUM_THREADS) {\n    // load in data\n    int jx = i + tx;\n    if (jx < dim) {\n      X0[0][tx] = Xdata[jx+0*dim];\n      X0[1][tx] = Xdata[jx+1*dim];\n      X0[2][tx] = Xdata[jx+2*dim];\n\n      rvec[0][tx] = rdata[jx+0*dim];\n      rvec[1][tx] = rdata[jx+1*dim];\n      rvec[2][tx] = rdata[jx+2*dim];\n\n      wvec[0][tx] = wdata[jx+0*dim];\n      wvec[1][tx] = wdata[jx+1*dim];\n      wvec[2][tx] = wdata[jx+2*dim];\n\n      for (int k=0; k<ae_dim; k++)\n        ae2[k][tx] = ae_data[jx + k*dim];\n    }\n\n    __syncthreads();\n\n    for (int j=0; j<NUM_THREADS; j++) {\n      jx = i + j;\n      if (ix<dim && jx<dim) {\n        int h2 = jx / wd;\n        int w2 = jx % wd;\n\n        int r = max(abs(h1-h2), abs(w1-w2));        \n        if (r > radius) continue;\n\n        float p[3] = { X0[0][j], X0[1][j], X0[2][j] };        \n        se3_transform_point_inplace(G, p);\n        \n        // residual vectors\n        const float X1=p[0], Y1=p[1], Z1=p[2];\n        const float u = fx * (X1 / Z1) + cx;\n        const float v = fy * (Y1 / Z1) + cy;\n        \n        const float ru = rvec[0][j] - u;\n        const float rv = rvec[1][j] - v;\n        const float rz = rvec[2][j] - 1.0 / Z1;\n\n        float s=0.0;\n        for (int k=0; k<ae_dim; k++) {\n          s += (ae1[k] - ae2[k][j]) * (ae1[k] - ae2[k][j]);\n        }\n        \n        const float w = sigmoid(-s);\n        float diff_w = 0;\n\n        const float wu = wvec[0][j];\n        const float wv = wvec[1][j];\n        const float wz = wvec[2][j];\n\n        // exclude pixels too close or errors too big\n        if (Z1 < 0.1 || abs(ru) > 128 || abs(rv) > 128) \n          continue;\n\n        pinhole_jacobians(p, fx, fy, Ju, Jv, Jz);\n\n        for (int ii=0; ii<6; ii++) {\n          diff_w += (wu*ru*Ju[ii] + wv*rv*Jv[ii] + wz*rz*Jz[ii]) * db[ii];\n          for (int jj=0; jj<6; jj++) {\n            diff_w += (wu*Ju[ii]*Ju[jj] + wv*Jv[ii]*Jv[jj] + wz*Jz[ii]*Jz[jj]) * dH[ii][jj];\n          }\n        }\n\n\n        float diff_s = -diff_w * sigmoid(-s) * (1.0f - sigmoid(-s));\n\n        for (int k=0; k<ae_dim; k++) {\n          diff_ae1[k] += 2 * diff_s * (ae1[k] - ae2[k][j]);\n        }\n      }\n    }\n    __syncthreads();\n  }\n\n  if (ix < dim) {\n    for (int k=0; k<ae_dim; k++)\n      embedding_grad[batch_id][k][h1][w1] += diff_ae1[k];\n  }\n}\n\n\n\nstd::vector<torch::Tensor> dense_se3_forward_cuda(\n  torch::Tensor transforms,\n  torch::Tensor embeddings,\n  torch::Tensor points,\n  torch::Tensor targets,\n  torch::Tensor weights,\n  torch::Tensor intrinsics,\n  int radius)\n{\n\n  int batch_size = transforms.size(0);\n  int ht = transforms.size(2);\n  int wd = transforms.size(3);\n\n  dim3 grid = dim3(batch_size, (ht*wd + NUM_THREADS-1) / NUM_THREADS);\n\n  auto opts = targets.options();\n  torch::Tensor H = torch::zeros({batch_size, 6, 6, ht, wd}, opts);\n  torch::Tensor b = torch::zeros({batch_size, 6, 1, ht, wd}, opts);\n\n  dense_se3_forward_kernel<<<grid, NUM_THREADS>>>(\n    transforms.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    embeddings.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    points.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    targets.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    weights.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    intrinsics.packed_accessor32<float,2,torch::RestrictPtrTraits>(),\n    H.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    b.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    radius);\n\n  return {H, b};\n}\n\n\nstd::vector<torch::Tensor> dense_se3_backward_cuda(\n  torch::Tensor transforms,\n  torch::Tensor embeddings,\n  torch::Tensor points,\n  torch::Tensor targets,\n  torch::Tensor weights,\n  torch::Tensor intrinsics,\n  torch::Tensor H_grad,\n  torch::Tensor b_grad,\n  int radius)\n{\n\n  int batch_size = transforms.size(0);\n  int ht = transforms.size(2);\n  int wd = transforms.size(3);\n\n  dim3 grid = dim3(batch_size, (ht*wd + NUM_THREADS-1) / NUM_THREADS);\n  torch::Tensor embedding_grad = torch::zeros_like(embeddings);\n  torch::Tensor targets_grad = torch::zeros_like(targets);\n  torch::Tensor weights_grad = torch::zeros_like(weights);\n\n  // backward pass split into two kernels to avoid atomics\n\n  dense_se3_backward_kernel1<<<grid, NUM_THREADS>>>(\n    transforms.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    embeddings.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    points.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    targets.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    weights.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    intrinsics.packed_accessor32<float,2,torch::RestrictPtrTraits>(),\n    H_grad.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    b_grad.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    embedding_grad.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    targets_grad.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    weights_grad.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    radius);\n\n  dense_se3_backward_kernel2<<<grid, NUM_THREADS>>>(\n    transforms.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    embeddings.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    points.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    targets.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    weights.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    intrinsics.packed_accessor32<float,2,torch::RestrictPtrTraits>(),\n    H_grad.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    b_grad.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    embedding_grad.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    targets_grad.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    weights_grad.packed_accessor32<float,4,torch::RestrictPtrTraits>(),\n    radius);\n\n  return {embedding_grad, targets_grad, weights_grad};\n}"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/extras/se3_solver.cu",
    "content": "#include <torch/extension.h>\n#include <vector>\n\n\n#define NUM_THREADS 64\n#define EPS 1e-8\n\n\ntemplate <int N>\n__device__ __forceinline__ void llt(const float A[N][N], float L[N][N])\n{\n\n  for (int i=0; i<N; i++) {\n    for (int j=0; j<N; j++) {\n      L[i][j] = 0;\n    }\n  }\n\n  float s;\n  for (int i=0; i<N; i++) {\n    for (int j=0; j<(i+1); j++) {\n      s = 0.0;\n      for (int k=0; k<j; k++)\n        s += L[i][k] * L[j][k];\n\n      if (i==j) {\n        s = s > A[i][i] ? A[i][i] + EPS : s;\n        L[i][j] = sqrtf(A[i][i]-s);\n      }\n\n      else\n        L[i][j] = (A[i][j] - s) / L[j][j];\n    }\n  }\n}\n\ntemplate <int N> \n__device__ __forceinline__ void llt_solve(const float L[N][N], float x[N])\n{\n  float s;\n  for (int i=0; i<N; i++) {\n    s = 0.0;\n    for (int j=0; j<i; j++)\n      s += L[i][j] * x[j];\n\n    x[i] = (x[i] - s) / L[i][i];\n  }\n\n  for (int i=N-1; i>=0; i--) {\n    s = 0.0;\n    for (int j=i+1; j<N; j++)\n      s += L[j][i] * x[j];\n\n    x[i] = (x[i] - s) / L[i][i];\n  }\n}\n\n\n__global__ void cholesky_solve6x6_forward_kernel(\n    const torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> H_tensor,\n    const torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> b_tensor,\n    torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> x_tensor) {\n\n  /*Inputs: H [batch,6,6,ht,wd], b [batch,6,1,ht,wd]\n    Outputs: x [batch,6,1,ht,wd]; Hx = b\n  */\n\n  int batch_id = blockIdx.x;\n  const int dim = H_tensor.size(3) * H_tensor.size(4);\n  int m = blockIdx.y * NUM_THREADS + threadIdx.x;\n\n  const float* H_ptr = H_tensor[batch_id].data();\n  const float* b_ptr = b_tensor[batch_id].data();\n  float* x_ptr = x_tensor[batch_id].data();\n\n  if (m < dim) {\n    float H[6][6], L[6][6], x[6];\n\n    for (int i=0; i<6; i++) {\n      for (int j=0; j<6; j++) {\n        H[i][j] = H_ptr[m + (6*i+j)*dim];\n      }\n    }\n\n    for (int i=0; i<6; i++) {\n      x[i] = b_ptr[m + i*dim];\n    }\n\n    llt<6>(H, L);\n    llt_solve<6>(L, x);\n\n    for (int i=0; i<6; i++) {\n      x_ptr[m + i*dim] = x[i];\n    }\n  }\n}\n  \n\n__global__ void cholesky_solve6x6_backward_kernel(\n    const torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> H_tensor,\n    const torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> b_tensor,\n    const torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> dx_tensor,\n    torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> dH_tensor,\n    torch::PackedTensorAccessor32<float,5,torch::RestrictPtrTraits> db_tensor) {\n\n\n  int batch_id = blockIdx.x;\n  const int dim = H_tensor.size(3) * H_tensor.size(4);\n  int m = blockIdx.y * NUM_THREADS + threadIdx.x;\n\n  const float* H_ptr = H_tensor[batch_id].data();\n  const float* b_ptr = b_tensor[batch_id].data();\n  \n  const float* dx_ptr = dx_tensor[batch_id].data();\n  float* dH_ptr = dH_tensor[batch_id].data();\n  float* db_ptr = db_tensor[batch_id].data();\n\n  if (m < dim) {\n    float H[6][6], L[6][6], x[6], dz[6];\n\n    for (int i=0; i<6; i++) {\n      for (int j=0; j<6; j++) {\n        H[i][j] = H_ptr[m + (6*i+j)*dim];\n      }\n    }\n\n    for (int i=0; i<6; i++) {\n      x[i] = b_ptr[m + i*dim];\n    }\n\n    for (int i=0; i<6; i++) {\n      dz[i] = dx_ptr[m + i*dim];\n    }\n\n    // cholesky factorization\n    llt<6>(H, L);\n\n    llt_solve<6>(L, x);\n    llt_solve<6>(L, dz);\n\n    for (int i=0; i<6; i++) {\n      for (int j=0; j<6; j++) {\n        dH_ptr[m + (6*i+j)*dim] = -dz[i] * x[j];\n      }\n    }\n\n    for (int i=0; i<6; i++) {\n      db_ptr[m + i*dim] = dz[i];\n    }\n  }\n}\n\n\nstd::vector<torch::Tensor> cholesky_solve6x6_forward_cuda(torch::Tensor H, torch::Tensor b) {\n\n  const int batch_size = H.size(0);\n  const int ht = H.size(3);\n  const int wd = H.size(4);\n\n  torch::Tensor x = torch::zeros_like(b);\n  dim3 grid = dim3(batch_size, (ht*wd + NUM_THREADS-1) / NUM_THREADS);\n\n  cholesky_solve6x6_forward_kernel<<<grid, NUM_THREADS>>>(\n    H.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    b.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    x.packed_accessor32<float,5,torch::RestrictPtrTraits>());\n\n  return {x};\n}\n\n\nstd::vector<torch::Tensor> cholesky_solve6x6_backward_cuda(torch::Tensor H, torch::Tensor b, torch::Tensor dx) {\n  const int batch_size = H.size(0);\n  const int ht = H.size(3);\n  const int wd = H.size(4);\n\n  torch::Tensor dH = torch::zeros_like(H);\n  torch::Tensor db = torch::zeros_like(b);\n  dim3 grid = dim3(batch_size, (ht*wd + NUM_THREADS-1) / NUM_THREADS);\n\n  cholesky_solve6x6_backward_kernel<<<grid, NUM_THREADS>>>(\n    H.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    b.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    dx.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    dH.packed_accessor32<float,5,torch::RestrictPtrTraits>(),\n    db.packed_accessor32<float,5,torch::RestrictPtrTraits>());\n\n  return {dH, db};\n}"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/gradcheck.py",
    "content": "import torch\n\nTORCH_MAJOR = int(torch.__version__.split('.')[0])\nTORCH_MINOR = int(torch.__version__.split('.')[1])\n\nfrom torch.types import _TensorOrTensors\nif TORCH_MAJOR == 1 and TORCH_MINOR < 8:\n    from torch._six import container_abcs, istuple\nelse:\n    import collections.abc as container_abcs\n\nimport torch.testing\nfrom torch.overrides import is_tensor_like\nfrom itertools import product\nimport warnings\nfrom typing import Callable, Union, Optional, Iterable, List\n\ndef zero_gradients(x):\n    if isinstance(x, torch.Tensor):\n        if x.grad is not None:\n            x.grad.detach_()\n            x.grad.zero_()\n    elif isinstance(x, container_abcs.Iterable):\n        for elem in x:\n            zero_gradients(elem)\n\n\ndef make_jacobian(input, num_out):\n    if is_tensor_like(input):\n        if not input.is_floating_point() and not input.is_complex():\n            return None\n        if not input.requires_grad:\n            return None\n        return input.new_zeros((input.nelement(), num_out), dtype=input.dtype, layout=torch.strided)\n    elif isinstance(input, container_abcs.Iterable) and not isinstance(input, str):\n        jacobians = list(filter(\n            lambda x: x is not None, (make_jacobian(elem, num_out) for elem in input)))\n        if not jacobians:\n            return None\n        return type(input)(jacobians)  # type: ignore\n    else:\n        return None\n\n\ndef iter_tensors(x: Union[torch.Tensor, Iterable[torch.Tensor]], only_requiring_grad: bool = False) -> Iterable[torch.Tensor]:\n    if is_tensor_like(x):\n        # mypy doesn't narrow type of `x` to torch.Tensor\n        if x.requires_grad or not only_requiring_grad:  # type: ignore\n            yield x  # type: ignore\n    elif isinstance(x, container_abcs.Iterable) and not isinstance(x, str):\n        for elem in x:\n            for result in iter_tensors(elem, only_requiring_grad):\n                yield result\n\ndef get_numerical_jacobian(fn, input, target=None, eps=1e-3, grad_out=1.0):\n    \"\"\"\n    input: input to `fn`\n    target: the Tensors wrt whom Jacobians are calculated (default=`input`)\n    grad_out: grad output value used to calculate gradients.\n\n    Note that `target` may not even be part of `input` to `fn`, so please be\n    **very careful** in this to not clone `target`.\n    \"\"\"\n    if target is None:\n        target = input\n    output_size = fn(input).numel()\n    jacobian = make_jacobian(target, output_size)\n\n    # It's much easier to iterate over flattened lists of tensors.\n    # These are reference to the same objects in jacobian, so any changes\n    # will be reflected in it as well.\n    x_tensors = iter_tensors(target, True)\n    j_tensors = iter_tensors(jacobian)\n\n    def update_jacobians(x, idx, d, d_idx, is_mkldnn=False):\n\n        # compute_jacobian only works for pure real\n        # or pure imaginary delta\n        def compute_gradient(delta):\n            # we currently assume that the norm of delta equals eps\n            assert(delta == eps or delta == (eps * 1j))\n\n            def fn_out():\n                if not is_mkldnn:\n                    # x is a view into input and so this works\n                    return fn(input).clone()\n                else:\n                    # convert the dense tensor back to have mkldnn layout\n                    return fn([x.to_mkldnn()])\n\n            orig = x[idx].item()\n            x[idx] = orig - delta\n            outa = fn_out()\n            x[idx] = orig + delta\n            outb = fn_out()\n            x[idx] = orig\n            r = (outb - outa) / (2 * eps)\n            return r.detach().reshape(-1)\n\n        # for details on the algorithm used here, refer:\n        # Section 3.5.3 https://arxiv.org/pdf/1701.00392.pdf\n        # s = fn(z) where z = x for real valued input\n        # and z = x + yj for complex valued input\n        ds_dx = compute_gradient(eps)\n        if x.is_complex():  # C -> C, C -> R\n            ds_dy = compute_gradient(eps * 1j)\n            # conjugate wirtinger derivative\n            conj_w_d = 0.5 * (ds_dx + ds_dy * 1j)\n            # wirtinger derivative\n            w_d = 0.5 * (ds_dx - ds_dy * 1j)\n            d[d_idx] = grad_out.conjugate() * conj_w_d + grad_out * w_d.conj()\n        elif ds_dx.is_complex():  # R -> C\n            # w_d = conj_w_d = 0.5 * ds_dx\n            # dL_dz_conj = 0.5 * [grad_out.conj() * ds_dx + grad_out * ds_dx.conj()]\n            #            = 0.5 * [grad_out.conj() * ds_dx + (grad_out.conj() * ds_dx).conj()]\n            #            = 0.5 * 2 * real(grad_out.conj() * ds_dx)\n            #            = real(grad_out.conj() * ds_dx)\n            d[d_idx] = torch.real(grad_out.conjugate() * ds_dx)\n        else:   # R -> R\n            d[d_idx] = ds_dx * grad_out\n\n    # TODO: compare structure\n    for x_tensor, d_tensor in zip(x_tensors, j_tensors):\n        if x_tensor.is_sparse:\n            def get_stride(size):\n                dim = len(size)\n                tmp = 1\n                stride = [0] * dim\n                for i in reversed(range(dim)):\n                    stride[i] = tmp\n                    tmp *= size[i]\n                return stride\n\n            x_nnz = x_tensor._nnz()\n            x_size = list(x_tensor.size())\n            x_indices = x_tensor._indices().t()\n            x_values = x_tensor._values()\n            x_stride = get_stride(x_size)\n\n            # Use .data here to get around the version check\n            x_values = x_values.data\n\n            for i in range(x_nnz):\n                x_value = x_values[i]\n                for x_idx in product(*[range(m) for m in x_values.size()[1:]]):\n                    indices = x_indices[i].tolist() + list(x_idx)\n                    d_idx = sum(indices[k] * x_stride[k] for k in range(len(x_size)))\n                    update_jacobians(x_value, x_idx, d_tensor, d_idx)\n        elif x_tensor.layout == torch._mkldnn:  # type: ignore\n            # Use .data here to get around the version check\n            x_tensor = x_tensor.data\n            if len(input) != 1:\n                raise ValueError('gradcheck currently only supports functions with 1 input, but got: ',\n                                 len(input))\n            for d_idx, x_idx in enumerate(product(*[range(m) for m in x_tensor.size()])):\n                # this is really inefficient, but without indexing implemented, there's\n                # not really a better way than converting back and forth\n                x_tensor_dense = x_tensor.to_dense()\n                update_jacobians(x_tensor_dense, x_idx, d_tensor, d_idx, is_mkldnn=True)\n        else:\n            # Use .data here to get around the version check\n            x_tensor = x_tensor.data\n            for d_idx, x_idx in enumerate(product(*[range(m) for m in x_tensor.size()])):\n                update_jacobians(x_tensor, x_idx, d_tensor, d_idx)\n\n    return jacobian\n\n\ndef get_analytical_jacobian(input, output, nondet_tol=0.0, grad_out=1.0):\n    # it is easier to call to_dense() on the sparse output than\n    # to modify analytical jacobian\n    if output.is_sparse:\n        raise ValueError('Sparse output is not supported at gradcheck yet. '\n                         'Please call to_dense() on the output of fn for gradcheck.')\n    if output.layout == torch._mkldnn:  # type: ignore\n        raise ValueError('MKLDNN output is not supported at gradcheck yet. '\n                         'Please call to_dense() on the output of fn for gradcheck.')\n    diff_input_list = list(iter_tensors(input, True))\n    jacobian = make_jacobian(input, output.numel())\n    jacobian_reentrant = make_jacobian(input, output.numel())\n    grad_output = torch.zeros_like(output, memory_format=torch.legacy_contiguous_format)\n    flat_grad_output = grad_output.view(-1)\n    reentrant = True\n    correct_grad_sizes = True\n    correct_grad_types = True\n\n    for i in range(flat_grad_output.numel()):\n        flat_grad_output.zero_()\n        flat_grad_output[i] = grad_out\n        for jacobian_c in (jacobian, jacobian_reentrant):\n            grads_input = torch.autograd.grad(output, diff_input_list, grad_output,\n                                              retain_graph=True, allow_unused=True)\n            for jacobian_x, d_x, x in zip(jacobian_c, grads_input, diff_input_list):\n                if d_x is not None and d_x.size() != x.size():\n                    correct_grad_sizes = False\n                elif d_x is not None and d_x.dtype != x.dtype:\n                    correct_grad_types = False\n                elif jacobian_x.numel() != 0:\n                    if d_x is None:\n                        jacobian_x[:, i].zero_()\n                    else:\n                        d_x_dense = d_x.to_dense() if not d_x.layout == torch.strided else d_x\n                        assert jacobian_x[:, i].numel() == d_x_dense.numel()\n                        jacobian_x[:, i] = d_x_dense.contiguous().view(-1)\n\n    for jacobian_x, jacobian_reentrant_x in zip(jacobian, jacobian_reentrant):\n        if jacobian_x.numel() != 0 and (jacobian_x - jacobian_reentrant_x).abs().max() > nondet_tol:\n            reentrant = False\n\n    return jacobian, reentrant, correct_grad_sizes, correct_grad_types\n\n\ndef _as_tuple(x):\n    if TORCH_MAJOR == 1 and TORCH_MINOR < 8:\n        b_tuple = istuple(x)  \n    else:\n        b_tuple = isinstance(x, tuple)\n    \n    if b_tuple:\n        return x\n    elif isinstance(x, list):\n        return tuple(x)\n    else:\n        return x,\n    \n\n\ndef _differentiable_outputs(x):\n    return tuple(o for o in _as_tuple(x) if o.requires_grad)\n\n\n# Note [VarArg of Tensors]\n# ~~~~~~~~~~~~~~~~~~~~~~~~\n# 'func' accepts a vararg of tensors, which isn't expressable in the type system at the moment.\n# If https://mypy.readthedocs.io/en/latest/additional_features.html?highlight=callable#extended-callable-types is accepted,\n# the '...' first argument of Callable can be replaced with VarArg(Tensor).\n# For now, we permit any input.\n# the '...' first argument of Callable can be replaced with VarArg(Tensor).\n# For now, we permit any input.\n\ndef gradcheck(\n    func: Callable[..., Union[_TensorOrTensors]],  # See Note [VarArg of Tensors]\n    inputs: _TensorOrTensors,\n    eps: float = 1e-6,\n    atol: float = 1e-5,\n    rtol: float = 1e-3,\n    raise_exception: bool = True,\n    check_sparse_nnz: bool = False,\n    nondet_tol: float = 0.0,\n    check_undefined_grad: bool = True,\n    check_grad_dtypes: bool = False\n) -> bool:\n    r\"\"\"Check gradients computed via small finite differences against analytical\n    gradients w.r.t. tensors in :attr:`inputs` that are of floating point or complex type\n    and with ``requires_grad=True``.\n\n    The check between numerical and analytical gradients uses :func:`~torch.allclose`.\n\n    For complex functions, no notion of Jacobian exists. Gradcheck verifies if the numerical and\n    analytical values of Wirtinger and Conjugate Wirtinger derivative are consistent. The gradient\n    computation is done under the assumption that the overall function has a real valued output.\n    For functions with complex output, gradcheck compares the numerical and analytical gradients\n    for two values of :attr:`grad_output`: 1 and 1j. For more details, check out\n    :ref:`complex_autograd-doc`.\n\n    .. note::\n        The default values are designed for :attr:`input` of double precision.\n        This check will likely fail if :attr:`input` is of less precision, e.g.,\n        ``FloatTensor``.\n\n    .. warning::\n       If any checked tensor in :attr:`input` has overlapping memory, i.e.,\n       different indices pointing to the same memory address (e.g., from\n       :func:`torch.expand`), this check will likely fail because the numerical\n       gradients computed by point perturbation at such indices will change\n       values at all other indices that share the same memory address.\n\n    Args:\n        func (function): a Python function that takes Tensor inputs and returns\n            a Tensor or a tuple of Tensors\n        inputs (tuple of Tensor or Tensor): inputs to the function\n        eps (float, optional): perturbation for finite differences\n        atol (float, optional): absolute tolerance\n        rtol (float, optional): relative tolerance\n        raise_exception (bool, optional): indicating whether to raise an exception if\n            the check fails. The exception gives more information about the\n            exact nature of the failure. This is helpful when debugging gradchecks.\n        check_sparse_nnz (bool, optional): if True, gradcheck allows for SparseTensor input,\n            and for any SparseTensor at input, gradcheck will perform check at nnz positions only.\n        nondet_tol (float, optional): tolerance for non-determinism. When running\n            identical inputs through the differentiation, the results must either match\n            exactly (default, 0.0) or be within this tolerance.\n        check_undefined_grad (bool, options): if True, check if undefined output grads\n            are supported and treated as zeros, for ``Tensor`` outputs.\n\n    Returns:\n        True if all differences satisfy allclose condition\n    \"\"\"\n    def fail_test(msg):\n        if raise_exception:\n            raise RuntimeError(msg)\n        return False\n\n    tupled_inputs = _as_tuple(inputs)\n    if not check_sparse_nnz and any(t.is_sparse for t in tupled_inputs if isinstance(t, torch.Tensor)):\n        return fail_test('gradcheck expects all tensor inputs are dense when check_sparse_nnz is set to False.')\n\n    # Make sure that gradients are saved for at least one input\n    any_input_requiring_grad = False\n    for idx, inp in enumerate(tupled_inputs):\n        if is_tensor_like(inp) and inp.requires_grad:\n            if not (inp.dtype == torch.float64 or inp.dtype == torch.complex128):\n                warnings.warn(\n                    f'Input #{idx} requires gradient and '\n                    'is not a double precision floating point or complex. '\n                    'This check will likely fail if all the inputs are '\n                    'not of double precision floating point or complex. ')\n            content = inp._values() if inp.is_sparse else inp\n            # TODO: To cover more problematic cases, replace stride = 0 check with\n            # \"any overlap in memory\" once we have a proper function to check it.\n            if content.layout is not torch._mkldnn:  # type: ignore\n                if not all(st > 0 or sz <= 1 for st, sz in zip(content.stride(), content.size())):\n                    raise RuntimeError(\n                        'The {}th input has a dimension with stride 0. gradcheck only '\n                        'supports inputs that are non-overlapping to be able to '\n                        'compute the numerical gradients correctly. You should call '\n                        '.contiguous on the input before passing it to gradcheck.')\n            any_input_requiring_grad = True\n            inp.retain_grad()\n    if not any_input_requiring_grad:\n        raise ValueError(\n            'gradcheck expects at least one input tensor to require gradient, '\n            'but none of the them have requires_grad=True.')\n\n    func_out = func(*tupled_inputs)\n    output = _differentiable_outputs(func_out)\n\n    if not output:\n        for i, o in enumerate(func_out):\n            def fn(input):\n                return _as_tuple(func(*input))[i]\n            numerical = get_numerical_jacobian(fn, tupled_inputs, eps=eps)\n            for n in numerical:\n                if torch.ne(n, 0).sum() > 0:\n                    return fail_test('Numerical gradient for function expected to be zero')\n        return True\n\n    for i, o in enumerate(output):\n        if not o.requires_grad:\n            continue\n\n        def fn(input):\n            return _as_tuple(func(*input))[i]\n\n        analytical, reentrant, correct_grad_sizes, correct_grad_types = get_analytical_jacobian(tupled_inputs,\n                                                                                                o,\n                                                                                                nondet_tol=nondet_tol)\n        numerical = get_numerical_jacobian(fn, tupled_inputs, eps=eps)\n\n        return analytical, numerical\n\n        out_is_complex = o.is_complex()\n\n        if out_is_complex:\n            # analytical vjp with grad_out = 1.0j\n            analytical_with_imag_grad_out, reentrant_with_imag_grad_out, \\\n                correct_grad_sizes_with_imag_grad_out, correct_grad_types_with_imag_grad_out \\\n                = get_analytical_jacobian(tupled_inputs, o, nondet_tol=nondet_tol, grad_out=1j)\n            numerical_with_imag_grad_out = get_numerical_jacobian(fn, tupled_inputs, eps=eps, grad_out=1j)\n\n        if not correct_grad_types and check_grad_dtypes:\n            return fail_test('Gradient has dtype mismatch')\n\n        if out_is_complex and not correct_grad_types_with_imag_grad_out and check_grad_dtypes:\n            return fail_test('Gradient (calculated using complex valued grad output) has dtype mismatch')\n\n        if not correct_grad_sizes:\n            return fail_test('Analytical gradient has incorrect size')\n\n        if out_is_complex and not correct_grad_sizes_with_imag_grad_out:\n            return fail_test('Analytical gradient (calculated using complex valued grad output) has incorrect size')\n\n        def checkIfNumericalAnalyticAreClose(a, n, j, error_str=''):\n            if not torch.allclose(a, n, rtol, atol):\n                return fail_test(error_str + 'Jacobian mismatch for output %d with respect to input %d,\\n'\n                                 'numerical:%s\\nanalytical:%s\\n' % (i, j, n, a))\n\n        inp_tensors = iter_tensors(tupled_inputs, True)\n\n        for j, (a, n, inp) in enumerate(zip(analytical, numerical, inp_tensors)):\n            if a.numel() != 0 or n.numel() != 0:\n                if o.is_complex():\n                    # C -> C, R -> C\n                    a_with_imag_grad_out = analytical_with_imag_grad_out[j]\n                    n_with_imag_grad_out = numerical_with_imag_grad_out[j]\n                    checkIfNumericalAnalyticAreClose(a_with_imag_grad_out, n_with_imag_grad_out, j,\n                                                     \"Gradients failed to compare equal for grad output = 1j. \")\n                if inp.is_complex():\n                    # C -> R, C -> C\n                    checkIfNumericalAnalyticAreClose(a, n, j,\n                                                     \"Gradients failed to compare equal for grad output = 1. \")\n                else:\n                    # R -> R, R -> C\n                    checkIfNumericalAnalyticAreClose(a, n, j)\n\n\n        def not_reentrant_error(error_str=''):\n            error_msg = \"Backward\" + error_str + \" is not reentrant, i.e., running backward with same \\\n                        input and grad_output multiple times gives different values, \\\n                        although analytical gradient matches numerical gradient. \\\n                        The tolerance for nondeterminism was {}.\".format(nondet_tol)\n            return fail_test(error_msg)\n\n        if not reentrant:\n            return not_reentrant_error()\n\n        if out_is_complex and not reentrant_with_imag_grad_out:\n            return not_reentrant_error(' (calculated using complex valued grad output)')\n\n    # check if the backward multiplies by grad_output\n    output = _differentiable_outputs(func(*tupled_inputs))\n    if any([o.requires_grad for o in output]):\n        diff_input_list: List[torch.Tensor] = list(iter_tensors(tupled_inputs, True))\n        if not diff_input_list:\n            raise RuntimeError(\"no Tensors requiring grad found in input\")\n        grads_input = torch.autograd.grad(output, diff_input_list,\n                                          [torch.zeros_like(o, memory_format=torch.legacy_contiguous_format) for o in output],\n                                          allow_unused=True)\n        for gi, di in zip(grads_input, diff_input_list):\n            if gi is None:\n                continue\n            if isinstance(gi, torch.Tensor) and gi.layout != torch.strided:\n                if gi.layout != di.layout:\n                    return fail_test('grad is incorrect layout (' + str(gi.layout) + ' is not ' + str(di.layout) + ')')\n                if gi.layout == torch.sparse_coo:\n                    if gi.sparse_dim() != di.sparse_dim():\n                        return fail_test('grad is sparse tensor, but has incorrect sparse_dim')\n                    if gi.dense_dim() != di.dense_dim():\n                        return fail_test('grad is sparse tensor, but has incorrect dense_dim')\n                gi = gi.to_dense()\n                di = di.to_dense()\n            if not gi.eq(0).all():\n                return fail_test('backward not multiplied by grad_output')\n            if gi.dtype != di.dtype or gi.device != di.device or gi.is_sparse != di.is_sparse:\n                return fail_test(\"grad is incorrect type\")\n            if gi.size() != di.size():\n                return fail_test('grad is incorrect size')\n\n        if check_undefined_grad:\n            def warn_bc_breaking():\n                warnings.warn((\n                    'Backwards compatibility: New undefined gradient support checking '\n                    'feature is enabled by default, but it may break existing callers '\n                    'of this function. If this is true for you, you can call this '\n                    'function with \"check_undefined_grad=False\" to disable the feature'))\n\n            def check_undefined_grad_support(output_to_check):\n                grads_output = [torch.zeros_like(o, memory_format=torch.legacy_contiguous_format) for o in output_to_check]\n                try:\n                    grads_input = torch.autograd.grad(output_to_check,\n                                                      diff_input_list,\n                                                      grads_output,\n                                                      allow_unused=True)\n                except RuntimeError:\n                    warn_bc_breaking()\n                    return fail_test((\n                        'Expected backward function to handle undefined output grads. '\n                        'Please look at \"Notes about undefined output gradients\" in '\n                        '\"tools/autograd/derivatives.yaml\"'))\n\n                for gi, i in zip(grads_input, diff_input_list):\n                    if (gi is not None) and (not gi.eq(0).all()):\n                        warn_bc_breaking()\n                        return fail_test((\n                            'Expected all input grads to be undefined or zero when all output grads are undefined '\n                            'or zero. Please look at \"Notes about undefined output gradients\" in '\n                            '\"tools/autograd/derivatives.yaml\"'))\n                return True\n\n            # All backward functions must work properly if all output grads are undefined\n            outputs_to_check = [[\n                torch._C._functions.UndefinedGrad()(o) for o in _differentiable_outputs(func(*tupled_inputs))\n                # This check filters out Tensor-likes that aren't instances of Tensor.\n                if isinstance(o, torch.Tensor)\n            ]]\n\n            # If there are multiple output grads, we should be able to undef one at a time without error\n            if len(outputs_to_check[0]) > 1:\n                for undef_grad_idx in range(len(output)):\n                    output_to_check = _differentiable_outputs(func(*tupled_inputs))\n                    outputs_to_check.append([\n                        torch._C._functions.UndefinedGrad()(o) if idx == undef_grad_idx else o\n                        for idx, o in enumerate(output_to_check)])\n\n            for output_to_check in outputs_to_check:\n                if not check_undefined_grad_support(output_to_check):\n                    return False\n\n    return True\n\n\ndef gradgradcheck(\n    func: Callable[..., _TensorOrTensors],  # See Note [VarArg of Tensors]\n    inputs: _TensorOrTensors,\n    grad_outputs: Optional[_TensorOrTensors] = None,\n    eps: float = 1e-6,\n    atol: float = 1e-5,\n    rtol: float = 1e-3,\n    gen_non_contig_grad_outputs: bool = False,\n    raise_exception: bool = True,\n    nondet_tol: float = 0.0,\n    check_undefined_grad: bool = True,\n    check_grad_dtypes: bool = False\n) -> bool:\n    r\"\"\"Check gradients of gradients computed via small finite differences\n    against analytical gradients w.r.t. tensors in :attr:`inputs` and\n    :attr:`grad_outputs` that are of floating point or complex type and with\n    ``requires_grad=True``.\n\n    This function checks that backpropagating through the gradients computed\n    to the given :attr:`grad_outputs` are correct.\n\n    The check between numerical and analytical gradients uses :func:`~torch.allclose`.\n\n    .. note::\n        The default values are designed for :attr:`input` and\n        :attr:`grad_outputs` of double precision. This check will likely fail if\n        they are of less precision, e.g., ``FloatTensor``.\n\n    .. warning::\n       If any checked tensor in :attr:`input` and :attr:`grad_outputs` has\n       overlapping memory, i.e., different indices pointing to the same memory\n       address (e.g., from :func:`torch.expand`), this check will likely fail\n       because the numerical gradients computed by point perturbation at such\n       indices will change values at all other indices that share the same\n       memory address.\n\n    Args:\n        func (function): a Python function that takes Tensor inputs and returns\n            a Tensor or a tuple of Tensors\n        inputs (tuple of Tensor or Tensor): inputs to the function\n        grad_outputs (tuple of Tensor or Tensor, optional): The gradients with\n            respect to the function's outputs.\n        eps (float, optional): perturbation for finite differences\n        atol (float, optional): absolute tolerance\n        rtol (float, optional): relative tolerance\n        gen_non_contig_grad_outputs (bool, optional): if :attr:`grad_outputs` is\n            ``None`` and :attr:`gen_non_contig_grad_outputs` is ``True``, the\n            randomly generated gradient outputs are made to be noncontiguous\n        raise_exception (bool, optional): indicating whether to raise an exception if\n            the check fails. The exception gives more information about the\n            exact nature of the failure. This is helpful when debugging gradchecks.\n        nondet_tol (float, optional): tolerance for non-determinism. When running\n            identical inputs through the differentiation, the results must either match\n            exactly (default, 0.0) or be within this tolerance. Note that a small amount\n            of nondeterminism in the gradient will lead to larger inaccuracies in\n            the second derivative.\n        check_undefined_grad (bool, options): if True, check if undefined output grads\n            are supported and treated as zeros\n\n    Returns:\n        True if all differences satisfy allclose condition\n    \"\"\"\n    tupled_inputs = _as_tuple(inputs)\n\n    if grad_outputs is None:\n        # If grad_outputs is not specified, create random Tensors of the same\n        # shape, type, and device as the outputs\n        def randn_like(x):\n            y = torch.testing.randn_like(\n                x if (x.is_floating_point() or x.is_complex()) else x.double(), memory_format=torch.legacy_contiguous_format)\n            if gen_non_contig_grad_outputs:\n                y = torch.testing.make_non_contiguous(y)\n            return y.requires_grad_()\n        outputs = _as_tuple(func(*tupled_inputs))\n        tupled_grad_outputs = tuple(randn_like(x) for x in outputs)\n    else:\n        tupled_grad_outputs = _as_tuple(grad_outputs)\n\n    num_outputs = len(tupled_grad_outputs)\n\n    def new_func(*args):\n        input_args = args[:-num_outputs]\n        grad_outputs = args[-num_outputs:]\n        outputs = _differentiable_outputs(func(*input_args))\n        input_args = tuple(x for x in input_args if isinstance(x, torch.Tensor) and x.requires_grad)\n        grad_inputs = torch.autograd.grad(outputs, input_args, grad_outputs, create_graph=True)\n        return grad_inputs\n\n    return gradcheck(new_func, tupled_inputs + tupled_grad_outputs, eps, atol, rtol, raise_exception,\n                     nondet_tol=nondet_tol, check_undefined_grad=check_undefined_grad,\n                     check_grad_dtypes=check_grad_dtypes)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/group_ops.py",
    "content": "import lietorch_backends\nimport torch\nimport torch.nn.functional as F\n\n\n\nclass GroupOp(torch.autograd.Function):\n    \"\"\" group operation base class \"\"\"\n\n    @classmethod\n    def forward(cls, ctx, group_id, *inputs):\n        ctx.group_id = group_id\n        ctx.save_for_backward(*inputs)\n        out = cls.forward_op(ctx.group_id, *inputs)\n        return out\n\n    @classmethod\n    def backward(cls, ctx, grad):\n        error_str = \"Backward operation not implemented for {}\".format(cls)\n        assert cls.backward_op is not None, error_str\n\n        inputs = ctx.saved_tensors\n        grad = grad.contiguous()\n        grad_inputs = cls.backward_op(ctx.group_id, grad, *inputs)\n        return (None, ) + tuple(grad_inputs)\n        \n\nclass Exp(GroupOp):\n    \"\"\" exponential map \"\"\"\n    forward_op, backward_op = lietorch_backends.expm, lietorch_backends.expm_backward\n\nclass Log(GroupOp):\n    \"\"\" logarithm map \"\"\"\n    forward_op, backward_op = lietorch_backends.logm, lietorch_backends.logm_backward\n\nclass Inv(GroupOp):\n    \"\"\" group inverse \"\"\"\n    forward_op, backward_op = lietorch_backends.inv, lietorch_backends.inv_backward\n\nclass Mul(GroupOp):\n    \"\"\" group multiplication \"\"\"\n    forward_op, backward_op = lietorch_backends.mul, lietorch_backends.mul_backward\n\nclass Adj(GroupOp):\n    \"\"\" adjoint operator \"\"\"\n    forward_op, backward_op = lietorch_backends.adj, lietorch_backends.adj_backward\n\nclass AdjT(GroupOp):\n    \"\"\" adjoint operator \"\"\"\n    forward_op, backward_op = lietorch_backends.adjT, lietorch_backends.adjT_backward\n\nclass Act3(GroupOp):\n    \"\"\" action on point \"\"\"\n    forward_op, backward_op = lietorch_backends.act, lietorch_backends.act_backward\n\nclass Act4(GroupOp):\n    \"\"\" action on point \"\"\"\n    forward_op, backward_op = lietorch_backends.act4, lietorch_backends.act4_backward\n\nclass Jinv(GroupOp):\n    \"\"\" adjoint operator \"\"\"\n    forward_op, backward_op = lietorch_backends.Jinv, None\n\nclass ToMatrix(GroupOp):\n    \"\"\" convert to matrix representation \"\"\"\n    forward_op, backward_op = lietorch_backends.as_matrix, None\n\n\n\n\n### conversion operations to/from Euclidean embeddings ###\n\nclass FromVec(torch.autograd.Function):\n    \"\"\" convert vector into group object \"\"\"\n\n    @classmethod\n    def forward(cls, ctx, group_id, *inputs):\n        ctx.group_id = group_id\n        ctx.save_for_backward(*inputs)\n        return inputs[0]\n\n    @classmethod\n    def backward(cls, ctx, grad):\n        inputs = ctx.saved_tensors\n        J = lietorch_backends.projector(ctx.group_id, *inputs)\n        return None, torch.matmul(grad.unsqueeze(-2), torch.linalg.pinv(J)).squeeze(-2)\n\nclass ToVec(torch.autograd.Function):\n    \"\"\" convert group object to vector \"\"\"\n\n    @classmethod\n    def forward(cls, ctx, group_id, *inputs):\n        ctx.group_id = group_id\n        ctx.save_for_backward(*inputs)\n        return inputs[0]\n\n    @classmethod\n    def backward(cls, ctx, grad):\n        inputs = ctx.saved_tensors\n        J = lietorch_backends.projector(ctx.group_id, *inputs)\n        return None, torch.matmul(grad.unsqueeze(-2), J).squeeze(-2)\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/groups.py",
    "content": "import torch\nimport numpy as np\n\n# group operations implemented in cuda\nfrom .group_ops import Exp, Log, Inv, Mul, Adj, AdjT, Jinv, Act3, Act4, ToMatrix, ToVec, FromVec\nfrom .broadcasting import broadcast_inputs\n\n\nclass LieGroupParameter(torch.Tensor):\n    \"\"\" Wrapper class for LieGroup \"\"\"\n\n    from torch._C import _disabled_torch_function_impl\n    __torch_function__ = _disabled_torch_function_impl\n\n    def __new__(cls, group, requires_grad=True):\n        data = torch.zeros(group.tangent_shape, \n                           device=group.data.device, \n                           dtype=group.data.dtype, \n                           requires_grad=True)\n\n        return torch.Tensor._make_subclass(cls, data, requires_grad)\n\n    def __init__(self, group):\n        self.group = group\n\n    def retr(self):\n        return self.group.retr(self)\n\n    def log(self):\n        return self.retr().log()\n\n    def inv(self):\n        return self.retr().inv()\n\n    def adj(self, a):\n        return self.retr().adj(a)\n\n    def __mul__(self, other):\n        if isinstance(other, LieGroupParameter):\n            return self.retr() * other.retr()\n        else:\n            return self.retr() * other\n\n    def add_(self, update, alpha):\n        self.group = self.group.exp(alpha*update) * self.group\n\n    def __getitem__(self, index):\n        return self.retr().__getitem__(index)\n\n\nclass LieGroup:\n    \"\"\" Base class for Lie Group \"\"\"\n\n    def __init__(self, data):\n        self.data = data\n\n    def __repr__(self):\n        return \"{}: size={}, device={}, dtype={}\".format(\n            self.group_name, self.shape, self.device, self.dtype)\n\n    @property\n    def shape(self):\n        return self.data.shape[:-1]\n\n    @property\n    def device(self):\n        return self.data.device\n\n    @property\n    def dtype(self):\n        return self.data.dtype\n\n    def vec(self):\n        return self.apply_op(ToVec, self.data)\n\n    @property\n    def tangent_shape(self):\n        return self.data.shape[:-1] + (self.manifold_dim,)\n\n    @classmethod\n    def Identity(cls, *batch_shape, **kwargs):\n        \"\"\" Construct identity element with batch shape \"\"\"\n        \n        if isinstance(batch_shape[0], tuple):\n            batch_shape = batch_shape[0]\n        \n        elif isinstance(batch_shape[0], list):\n            batch_shape = tuple(batch_shape[0])\n\n        numel = np.prod(batch_shape)\n        data = cls.id_elem.reshape(1,-1)\n\n        if 'device' in kwargs:\n            data = data.to(kwargs['device'])\n\n        if 'dtype' in kwargs:\n            data = data.type(kwargs['dtype'])\n\n        data = data.repeat(numel, 1)\n        return cls(data).view(batch_shape)\n\n    @classmethod\n    def IdentityLike(cls, G):\n        return cls.Identity(G.shape, device=G.data.device, dtype=G.data.dtype)\n\n    @classmethod\n    def InitFromVec(cls, data):\n        return cls(cls.apply_op(FromVec, data))\n\n    @classmethod\n    def Random(cls, *batch_shape, sigma=1.0, **kwargs):\n        \"\"\" Construct random element with batch_shape by random sampling in tangent space\"\"\"\n\n        if isinstance(batch_shape[0], tuple):\n            batch_shape = batch_shape[0]\n        \n        elif isinstance(batch_shape[0], list):\n            batch_shape = tuple(batch_shape[0])\n        \n        tangent_shape = batch_shape + (cls.manifold_dim,)\n        xi = torch.randn(tangent_shape, **kwargs)\n        return cls.exp(sigma * xi)\n\n    @classmethod\n    def apply_op(cls, op, x, y=None):\n        \"\"\" Apply group operator \"\"\"\n        inputs, out_shape = broadcast_inputs(x, y)\n\n        data = op.apply(cls.group_id, *inputs)\n        return data.view(out_shape + (-1,))\n\n    @classmethod\n    def exp(cls, x):\n        \"\"\" exponential map: x -> X \"\"\"\n        return cls(cls.apply_op(Exp, x))\n\n    def quaternion(self):\n        \"\"\" extract quaternion \"\"\"\n        return self.apply_op(Quat, self.data)\n\n    def log(self):\n        \"\"\" logarithm map \"\"\"\n        return self.apply_op(Log, self.data)\n\n    def inv(self):\n        \"\"\" group inverse \"\"\"\n        return self.__class__(self.apply_op(Inv, self.data))\n\n    def mul(self, other):\n        \"\"\" group multiplication \"\"\"\n        return self.__class__(self.apply_op(Mul, self.data, other.data))\n\n    def retr(self, a):\n        \"\"\" retraction: Exp(a) * X \"\"\"\n        dX = self.__class__.apply_op(Exp, a)\n        return self.__class__(self.apply_op(Mul, dX, self.data))\n\n    def adj(self, a):\n        \"\"\" adjoint operator: b = A(X) * a \"\"\"\n        return self.apply_op(Adj, self.data, a)\n\n    def adjT(self, a):\n        \"\"\" transposed adjoint operator: b = a * A(X) \"\"\"\n        return self.apply_op(AdjT, self.data, a)\n\n    def Jinv(self, a):\n        return self.apply_op(Jinv, self.data, a)\n\n    def act(self, p):\n        \"\"\" action on a point cloud \"\"\"\n        \n        # action on point\n        if p.shape[-1] == 3:\n            return self.apply_op(Act3, self.data, p)\n        \n        # action on homogeneous point\n        elif p.shape[-1] == 4:\n            return self.apply_op(Act4, self.data, p)\n\n    def matrix(self):\n        \"\"\" convert element to 4x4 matrix \"\"\"\n        I = torch.eye(4, dtype=self.dtype, device=self.device)\n        I = I.view([1] * (len(self.data.shape) - 1) + [4, 4])\n        return self.__class__(self.data[...,None,:]).act(I).transpose(-1,-2)\n\n    def translation(self):\n        \"\"\" extract translation component \"\"\"\n        p = torch.as_tensor([0.0, 0.0, 0.0, 1.0], dtype=self.dtype, device=self.device)\n        p = p.view([1] * (len(self.data.shape) - 1) + [4,])\n        return self.apply_op(Act4, self.data, p)\n\n    def detach(self):\n        return self.__class__(self.data.detach())\n\n    def view(self, dims):\n        data_reshaped = self.data.view(dims + (self.embedded_dim,))\n        return self.__class__(data_reshaped)\n\n    def __mul__(self, other):\n        # group multiplication\n        if isinstance(other, LieGroup):\n            return self.mul(other)\n\n        # action on point\n        elif isinstance(other, torch.Tensor):\n            return self.act(other)\n\n    def __getitem__(self, index):\n        return self.__class__(self.data[index])\n\n    def __setitem__(self, index, item):\n        self.data[index] = item.data\n\n    def to(self, *args, **kwargs):\n        return self.__class__(self.data.to(*args, **kwargs))\n\n    def cpu(self):\n        return self.__class__(self.data.cpu())\n\n    def cuda(self):\n        return self.__class__(self.data.cuda())\n\n    def float(self, device):\n        return self.__class__(self.data.float())\n\n    def double(self, device):\n        return self.__class__(self.data.double())\n\n    def unbind(self, dim=0):\n        return [self.__class__(x) for x in self.data.unbind(dim=dim)]\n        \n\nclass SO3(LieGroup):\n    group_name = 'SO3'\n    group_id = 1\n    manifold_dim = 3\n    embedded_dim = 4\n    \n    # unit quaternion\n    id_elem = torch.as_tensor([0.0, 0.0, 0.0, 1.0])\n\n    def __init__(self, data):\n        if isinstance(data, SE3):\n            data = data.data[..., 3:7]\n\n        super(SO3, self).__init__(data)\n\n\nclass RxSO3(LieGroup):\n    group_name = 'RxSO3'\n    group_id = 2\n    manifold_dim = 4\n    embedded_dim = 5\n    \n    # unit quaternion\n    id_elem = torch.as_tensor([0.0, 0.0, 0.0, 1.0, 1.0])\n\n    def __init__(self, data):\n        if isinstance(data, Sim3):\n            data = data.data[..., 3:8]\n\n        super(RxSO3, self).__init__(data)\n\n\nclass SE3(LieGroup):\n    group_name = 'SE3'\n    group_id = 3\n    manifold_dim = 6\n    embedded_dim = 7\n\n    # translation, unit quaternion\n    id_elem = torch.as_tensor([0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0])\n\n    def __init__(self, data):\n        if isinstance(data, SO3):\n            translation = torch.zeros_like(data.data[...,:3])\n            data = torch.cat([translation, data.data], -1)\n\n        super(SE3, self).__init__(data)\n\n    def scale(self, s):\n        t, q = self.data.split([3,4], -1)\n        t = t * s.unsqueeze(-1)\n        return SE3(torch.cat([t, q], dim=-1))\n\n\nclass Sim3(LieGroup):\n    group_name = 'Sim3'\n    group_id = 4\n    manifold_dim = 7\n    embedded_dim = 8\n\n    # translation, unit quaternion, scale\n    id_elem = torch.as_tensor([0.0, 0.0, 0.0, 0.0, 0.0, 0.0, 1.0, 1.0])\n\n    def __init__(self, data):\n\n        if isinstance(data, SO3):\n            scale = torch.ones_like(SO3.data[...,:1])\n            translation = torch.zeros_like(SO3.data[...,:3])\n            data = torch.cat([translation, SO3.data, scale], -1)\n\n        elif isinstance(data, SE3):\n            scale = torch.ones_like(data.data[...,:1])\n            data = torch.cat([data.data, scale], -1)\n\n        elif isinstance(data, Sim3):\n            data = data.data\n\n        super(Sim3, self).__init__(data)\n\n\ndef cat(group_list, dim):\n    \"\"\" Concatenate groups along dimension \"\"\"\n    data = torch.cat([X.data for X in group_list], dim=dim)\n    return group_list[0].__class__(data)\n\ndef stack(group_list, dim):\n    \"\"\" Concatenate groups along dimension \"\"\"\n    data = torch.stack([X.data for X in group_list], dim=dim)\n    return group_list[0].__class__(data)\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/include/common.h",
    "content": "#ifndef COMMON_H\n#define COMMON_H\n\n#define EIGEN_DEFAULT_DENSE_INDEX_TYPE int\n#define EIGEN_RUNTIME_NO_MALLOC\n\n#define EPS 1e-6\n#define PI 3.14159265358979323846\n\n\n#endif\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/include/dispatch.h",
    "content": "#ifndef DISPATCH_H\n#define DISPATCH_H\n\n#include <torch/extension.h>\n\n#include \"so3.h\"\n#include \"rxso3.h\"\n#include \"se3.h\"\n#include \"sim3.h\"\n\n\n#define PRIVATE_CASE_TYPE(group_index, enum_type, type, ...)    \\\n  case enum_type: {                                             \\\n    using scalar_t = type;                                      \\\n    switch (group_index) {                                      \\\n      case 1: {                                                 \\\n        using group_t = SO3<type>;                              \\\n        return __VA_ARGS__();                                   \\\n      }                                                         \\\n      case 2: {                                                 \\\n        using group_t = RxSO3<type>;                            \\\n        return __VA_ARGS__();                                   \\\n      }                                                         \\\n      case 3: {                                                 \\\n        using group_t = SE3<type>;                              \\\n        return __VA_ARGS__();                                   \\\n      }                                                         \\\n      case 4: {                                                 \\\n        using group_t = Sim3<type>;                             \\\n        return __VA_ARGS__();                                   \\\n      }                                                         \\\n    }                                                           \\\n  }                                                             \\\n\n#define DISPATCH_GROUP_AND_FLOATING_TYPES(GROUP_INDEX, TYPE, NAME, ...)              \\\n  [&] {                                                                              \\\n    const auto& the_type = TYPE;                                                     \\\n    /* don't use TYPE again in case it is an expensive or side-effect op */          \\\n    at::ScalarType _st = ::detail::scalar_type(the_type);                            \\\n    switch (_st) {                                                                   \\\n      PRIVATE_CASE_TYPE(GROUP_INDEX, at::ScalarType::Double, double, __VA_ARGS__)    \\\n      PRIVATE_CASE_TYPE(GROUP_INDEX, at::ScalarType::Float, float, __VA_ARGS__)      \\\n      default: break;                                                                \\\n    }                                                                                \\\n  }()\n\n#endif\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/include/lietorch_cpu.h",
    "content": "\n#ifndef LIETORCH_CPU_H_\n#define LIETORCH_CPU_H_\n\n#include <vector>\n#include <torch/extension.h>\n\n\n// unary operations\ntorch::Tensor exp_forward_cpu(int, torch::Tensor);\nstd::vector<torch::Tensor> exp_backward_cpu(int, torch::Tensor, torch::Tensor);\n\ntorch::Tensor log_forward_cpu(int, torch::Tensor);\nstd::vector<torch::Tensor> log_backward_cpu(int, torch::Tensor, torch::Tensor);\n\ntorch::Tensor inv_forward_cpu(int, torch::Tensor);\nstd::vector<torch::Tensor> inv_backward_cpu(int, torch::Tensor, torch::Tensor);\n\n// binary operations\ntorch::Tensor mul_forward_cpu(int, torch::Tensor, torch::Tensor);\nstd::vector<torch::Tensor> mul_backward_cpu(int, torch::Tensor, torch::Tensor, torch::Tensor);\n\ntorch::Tensor adj_forward_cpu(int, torch::Tensor, torch::Tensor);\nstd::vector<torch::Tensor> adj_backward_cpu(int, torch::Tensor, torch::Tensor, torch::Tensor);\n\ntorch::Tensor adjT_forward_cpu(int, torch::Tensor, torch::Tensor);\nstd::vector<torch::Tensor> adjT_backward_cpu(int, torch::Tensor, torch::Tensor, torch::Tensor);\n\ntorch::Tensor act_forward_cpu(int, torch::Tensor, torch::Tensor);\nstd::vector<torch::Tensor> act_backward_cpu(int, torch::Tensor, torch::Tensor, torch::Tensor);\n\ntorch::Tensor act4_forward_cpu(int, torch::Tensor, torch::Tensor);\nstd::vector<torch::Tensor> act4_backward_cpu(int, torch::Tensor, torch::Tensor, torch::Tensor);\n\n\n// conversion operations\n// std::vector<torch::Tensor> to_vec_backward_cpu(int, torch::Tensor, torch::Tensor);\n// std::vector<torch::Tensor> from_vec_backward_cpu(int, torch::Tensor, torch::Tensor);\n\n// utility operations\ntorch::Tensor orthogonal_projector_cpu(int, torch::Tensor);\n\ntorch::Tensor as_matrix_forward_cpu(int, torch::Tensor);\n\ntorch::Tensor jleft_forward_cpu(int, torch::Tensor, torch::Tensor);\n\n\n#endif\n\n\n  "
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/include/lietorch_gpu.h",
    "content": "\n#ifndef LIETORCH_GPU_H_\n#define LIETORCH_GPU_H_\n\n#include <vector>\n#include <torch/extension.h>\n#include <cuda.h>\n#include <cuda_runtime.h>\n\n\n// unary operations\ntorch::Tensor exp_forward_gpu(int, torch::Tensor);\nstd::vector<torch::Tensor> exp_backward_gpu(int, torch::Tensor, torch::Tensor);\n\ntorch::Tensor log_forward_gpu(int, torch::Tensor);\nstd::vector<torch::Tensor> log_backward_gpu(int, torch::Tensor, torch::Tensor);\n\ntorch::Tensor inv_forward_gpu(int, torch::Tensor);\nstd::vector<torch::Tensor> inv_backward_gpu(int, torch::Tensor, torch::Tensor);\n\n// binary operations\ntorch::Tensor mul_forward_gpu(int, torch::Tensor, torch::Tensor);\nstd::vector<torch::Tensor> mul_backward_gpu(int, torch::Tensor, torch::Tensor, torch::Tensor);\n\ntorch::Tensor adj_forward_gpu(int, torch::Tensor, torch::Tensor);\nstd::vector<torch::Tensor> adj_backward_gpu(int, torch::Tensor, torch::Tensor, torch::Tensor);\n\ntorch::Tensor adjT_forward_gpu(int, torch::Tensor, torch::Tensor);\nstd::vector<torch::Tensor> adjT_backward_gpu(int, torch::Tensor, torch::Tensor, torch::Tensor);\n\ntorch::Tensor act_forward_gpu(int, torch::Tensor, torch::Tensor);\nstd::vector<torch::Tensor> act_backward_gpu(int, torch::Tensor, torch::Tensor, torch::Tensor);\n\ntorch::Tensor act4_forward_gpu(int, torch::Tensor, torch::Tensor);\nstd::vector<torch::Tensor> act4_backward_gpu(int, torch::Tensor, torch::Tensor, torch::Tensor);\n\n// conversion operations\n// std::vector<torch::Tensor> to_vec_backward_gpu(int, torch::Tensor, torch::Tensor);\n// std::vector<torch::Tensor> from_vec_backward_gpu(int, torch::Tensor, torch::Tensor);\n\n// utility operators\ntorch::Tensor orthogonal_projector_gpu(int, torch::Tensor);\n\ntorch::Tensor as_matrix_forward_gpu(int, torch::Tensor);\n\ntorch::Tensor jleft_forward_gpu(int, torch::Tensor, torch::Tensor);\n\n#endif\n\n\n  "
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/include/rxso3.h",
    "content": "\n#ifndef RxSO3_HEADER\n#define RxSO3_HEADER\n\n#include <stdio.h>\n#include <Eigen/Dense>\n#include <Eigen/Geometry> \n\n#include \"common.h\"\n\ntemplate <typename Scalar>\nclass RxSO3 {\n  public:\n    const static int constexpr K = 4; // manifold dimension\n    const static int constexpr N = 5; // embedding dimension\n\n    using Vector3 = Eigen::Matrix<Scalar,3,1>;\n    using Vector4 = Eigen::Matrix<Scalar,4,1>;\n    using Matrix3 = Eigen::Matrix<Scalar,3,3>;\n\n    using Tangent = Eigen::Matrix<Scalar,K,1>;\n    using Data = Eigen::Matrix<Scalar,N,1>;\n\n    using Point = Eigen::Matrix<Scalar,3,1>;\n    using Point4 = Eigen::Matrix<Scalar,4,1>;\n\n    using Quaternion = Eigen::Quaternion<Scalar>;\n    using Transformation = Eigen::Matrix<Scalar,3,3>;\n    using Adjoint = Eigen::Matrix<Scalar,4,4>;\n\n\n    EIGEN_DEVICE_FUNC RxSO3(Quaternion const& q, Scalar const s) \n        : unit_quaternion(q), scale(s) {\n      unit_quaternion.normalize();\n    };\n\n    EIGEN_DEVICE_FUNC RxSO3(const Scalar *data) : unit_quaternion(data), scale(data[4]) {\n      unit_quaternion.normalize();\n    };\n\n    EIGEN_DEVICE_FUNC RxSO3() {\n      unit_quaternion = Quaternion::Identity();\n      scale = Scalar(1.0);\n    }\n\n    EIGEN_DEVICE_FUNC RxSO3<Scalar> inv() {\n      return RxSO3<Scalar>(unit_quaternion.conjugate(), 1.0/scale);\n    }\n\n    EIGEN_DEVICE_FUNC Data data() const {\n      Data data_vec; data_vec << unit_quaternion.coeffs(), scale;\n      return data_vec;\n    }\n\n    EIGEN_DEVICE_FUNC RxSO3<Scalar> operator*(RxSO3<Scalar> const& other) {\n      return RxSO3<Scalar>(unit_quaternion * other.unit_quaternion, scale * other.scale);\n    }\n\n    EIGEN_DEVICE_FUNC Point operator*(Point const& p) const {\n      const Quaternion& q = unit_quaternion;\n      Point uv = q.vec().cross(p); uv += uv;\n      return scale * (p + q.w()*uv + q.vec().cross(uv));\n    }\n\n    EIGEN_DEVICE_FUNC Point4 act4(Point4 const& p) const {\n      Point4 p1; p1 << this->operator*(p.template segment<3>(0)), p(3);\n      return p1;\n    }\n\n    EIGEN_DEVICE_FUNC Adjoint Adj() const {\n      Adjoint Ad = Adjoint::Identity();\n      Ad.template block<3,3>(0,0) = unit_quaternion.toRotationMatrix();\n      return Ad;\n    }\n\n    EIGEN_DEVICE_FUNC Transformation Matrix() const {\n      return scale * unit_quaternion.toRotationMatrix();\n    }\n\n    EIGEN_DEVICE_FUNC Eigen::Matrix<Scalar,4,4> Matrix4x4() const {\n      Eigen::Matrix<Scalar,4,4> T;\n      T = Eigen::Matrix<Scalar,4,4>::Identity();\n      T.template block<3,3>(0,0) = Matrix();\n      return T;\n    }\n\n    EIGEN_DEVICE_FUNC Eigen::Matrix<Scalar,5,5> orthogonal_projector() const {\n      // jacobian action on a point\n      Eigen::Matrix<Scalar,5,5> J = Eigen::Matrix<Scalar,5,5>::Zero();\n      \n      J.template block<3,3>(0,0) = 0.5 * (\n        unit_quaternion.w() * Matrix3::Identity() + \n        SO3<Scalar>::hat(-unit_quaternion.vec())\n      );\n      \n      J.template block<1,3>(3,0) = 0.5 * (-unit_quaternion.vec());\n\n      // scale\n      J(4,3) = scale;\n\n      return J;\n    }\n\n    EIGEN_DEVICE_FUNC Transformation Rotation() const {\n      return unit_quaternion.toRotationMatrix();\n    }\n\n    EIGEN_DEVICE_FUNC Tangent Adj(Tangent const& a) const {\n      return Adj() * a;\n    }\n\n    EIGEN_DEVICE_FUNC Tangent AdjT(Tangent const& a) const {\n      return Adj().transpose() * a;\n    }\n\n    EIGEN_DEVICE_FUNC static Transformation hat(Tangent const& phi_sigma) {\n      Vector3 const phi = phi_sigma.template segment<3>(0);\n      return SO3<Scalar>::hat(phi) + phi(3) * Transformation::Identity();\n    }\n\n    EIGEN_DEVICE_FUNC static Adjoint adj(Tangent const& phi_sigma) {\n      Vector3 const phi = phi_sigma.template segment<3>(0);\n      Matrix3 const Phi = SO3<Scalar>::hat(phi);\n\n      Adjoint ad = Adjoint::Zero();\n      ad.template block<3,3>(0,0) = Phi;\n\n      return ad;\n    }\n\n    EIGEN_DEVICE_FUNC Tangent Log() const {\n      using std::abs;\n      using std::atan;\n      using std::sqrt;\n\n      Scalar squared_n = unit_quaternion.vec().squaredNorm();\n      Scalar w = unit_quaternion.w();\n      Scalar two_atan_nbyw_by_n;\n\n      /// Atan-based log thanks to\n      ///\n      /// C. Hertzberg et al.:\n      /// \"Integrating Generic Sensor Fusion Algorithms with Sound State\n      /// Representation through Encapsulation of Manifolds\"\n      /// Information Fusion, 2011\n\n      if (squared_n < EPS * EPS) {\n        two_atan_nbyw_by_n = Scalar(2) / w - Scalar(2.0/3.0) * (squared_n) / (w * w * w);\n      } else {\n        Scalar n = sqrt(squared_n);\n        if (abs(w) < EPS) {\n          if (w > Scalar(0)) {\n            two_atan_nbyw_by_n = PI / n;\n          } else {\n            two_atan_nbyw_by_n = -PI / n;\n          }\n        } else {\n          two_atan_nbyw_by_n = Scalar(2) * atan(n / w) / n;\n        }\n      }\n\n      Tangent phi_sigma;\n      phi_sigma << two_atan_nbyw_by_n * unit_quaternion.vec(), log(scale);\n\n      return phi_sigma;\n    }\n\n    EIGEN_DEVICE_FUNC static RxSO3<Scalar> Exp(Tangent const& phi_sigma) {\n      Vector3 phi = phi_sigma.template segment<3>(0);\n      Scalar scale = exp(phi_sigma(3));\n\n      Scalar theta2 = phi.squaredNorm();\n      Scalar theta = sqrt(theta2);\n      Scalar imag_factor;\n      Scalar real_factor;\n\n      if (theta < EPS) {\n        Scalar theta4 = theta2 * theta2;\n        imag_factor = Scalar(0.5) - Scalar(1.0/48.0) * theta2 + Scalar(1.0/3840.0) * theta4;\n        real_factor = Scalar(1) - Scalar(1.0/8.0) * theta2 + Scalar(1.0/384.0) * theta4;\n      } else {\n        imag_factor = sin(.5 * theta) / theta;\n        real_factor = cos(.5 * theta);\n      }\n\n      Quaternion q(real_factor, imag_factor*phi.x(), imag_factor*phi.y(), imag_factor*phi.z());\n      return RxSO3<Scalar>(q, scale);\n    }\n    \n    EIGEN_DEVICE_FUNC static Matrix3 calcW(Tangent const& phi_sigma) {\n      // left jacobian\n      using std::abs;\n      Matrix3 const I = Matrix3::Identity();\n      Scalar const one(1);\n      Scalar const half(0.5);\n      \n      Vector3 const phi = phi_sigma.template segment<3>(0);\n      Scalar const sigma = phi_sigma(3);\n      Scalar const theta = phi.norm();\n\n      Matrix3 const Phi = SO3<Scalar>::hat(phi);\n      Matrix3 const Phi2 = Phi * Phi;\n      Scalar const scale = exp(sigma);\n\n      Scalar A, B, C;\n      if (abs(sigma) < EPS) {\n        C = one;\n        if (abs(theta) < EPS) {\n          A = half;\n          B = Scalar(1. / 6.);\n        } else {\n          Scalar theta_sq = theta * theta;\n          A = (one - cos(theta)) / theta_sq;\n          B = (theta - sin(theta)) / (theta_sq * theta);\n        }\n      } else {\n        C = (scale - one) / sigma;\n        if (abs(theta) < EPS) {\n          Scalar sigma_sq = sigma * sigma;\n          A = ((sigma - one) * scale + one) / sigma_sq;\n          B = (scale * half * sigma_sq + scale - one - sigma * scale) /\n              (sigma_sq * sigma);\n        } else {\n          Scalar theta_sq = theta * theta;\n          Scalar a = scale * sin(theta);\n          Scalar b = scale * cos(theta);\n          Scalar c = theta_sq + sigma * sigma;\n          A = (a * sigma + (one - b) * theta) / (theta * c);\n          B = (C - ((b - one) * sigma + a * theta) / (c)) * one / (theta_sq);\n        }\n      }\n      return A * Phi + B * Phi2 + C * I;\n    }\n\n    EIGEN_DEVICE_FUNC static Matrix3 calcWInv(Tangent const& phi_sigma) {\n      // left jacobian inverse\n      Matrix3 const I = Matrix3::Identity();\n      Scalar const half(0.5);\n      Scalar const one(1);\n      Scalar const two(2);\n      \n      Vector3 const phi = phi_sigma.template segment<3>(0);\n      Scalar const sigma = phi_sigma(3);\n      Scalar const theta = phi.norm();\n      Scalar const scale = exp(sigma);\n\n      Matrix3 const Phi = SO3<Scalar>::hat(phi);\n      Matrix3 const Phi2 = Phi * Phi;\n      Scalar const scale_sq = scale * scale;\n      Scalar const theta_sq = theta * theta;\n      Scalar const sin_theta = sin(theta);\n      Scalar const cos_theta = cos(theta);\n\n      Scalar a, b, c;\n      if (abs(sigma * sigma) < EPS) {\n        c = one - half * sigma;\n        a = -half;\n        if (abs(theta_sq) < EPS) {\n          b = Scalar(1. / 12.);\n        } else {\n          b = (theta * sin_theta + two * cos_theta - two) /\n              (two * theta_sq * (cos_theta - one));\n        }\n      } else {\n        Scalar const scale_cu = scale_sq * scale;\n        c = sigma / (scale - one);\n        if (abs(theta_sq) < EPS) {\n          a = (-sigma * scale + scale - one) / ((scale - one) * (scale - one));\n          b = (scale_sq * sigma - two * scale_sq + scale * sigma + two * scale) /\n              (two * scale_cu - Scalar(6) * scale_sq + Scalar(6) * scale - two);\n        } else {\n          Scalar const s_sin_theta = scale * sin_theta;\n          Scalar const s_cos_theta = scale * cos_theta;\n          a = (theta * s_cos_theta - theta - sigma * s_sin_theta) /\n              (theta * (scale_sq - two * s_cos_theta + one));\n          b = -scale *\n              (theta * s_sin_theta - theta * sin_theta + sigma * s_cos_theta -\n              scale * sigma + sigma * cos_theta - sigma) /\n              (theta_sq * (scale_cu - two * scale * s_cos_theta - scale_sq +\n                          two * s_cos_theta + scale - one));\n        }\n      }\n      return a * Phi + b * Phi2 + c * I;\n    }\n\n    EIGEN_DEVICE_FUNC static Adjoint left_jacobian(Tangent const& phi_sigma) {\n      // left jacobian\n      Adjoint J = Adjoint::Identity();\n      Vector3 phi = phi_sigma.template segment<3>(0);\n      J.template block<3,3>(0,0) = SO3<Scalar>::left_jacobian(phi);\n      return J;\n    }\n\n  EIGEN_DEVICE_FUNC static Adjoint left_jacobian_inverse(Tangent const& phi_sigma) {\n      // left jacobian inverse\n      Adjoint Jinv = Adjoint::Identity();\n      Vector3 phi = phi_sigma.template segment<3>(0);\n      Jinv.template block<3,3>(0,0) = SO3<Scalar>::left_jacobian_inverse(phi);\n      return Jinv;\n    }\n\n    EIGEN_DEVICE_FUNC static Eigen::Matrix<Scalar,3,4> act_jacobian(Point const& p) {\n      // jacobian action on a point\n      Eigen::Matrix<Scalar,3,4> Ja; \n      Ja << SO3<Scalar>::hat(-p), p;\n      return Ja;\n    }\n\n    EIGEN_DEVICE_FUNC static Eigen::Matrix<Scalar,4,4> act4_jacobian(Point4 const& p) {\n      // jacobian action on a point\n      Eigen::Matrix<Scalar,4,4> J = Eigen::Matrix<Scalar,4,4>::Zero();\n      J.template block<3,3>(0,0) = SO3<Scalar>::hat(-p.template segment<3>(0));\n      J.template block<3,1>(0,3) = p.template segment<3>(0); \n      return J;\n    }\n\n  private:\n    Quaternion unit_quaternion;\n    Scalar scale;\n};\n\n#endif\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/include/se3.h",
    "content": "\n#ifndef SE3_HEADER\n#define SE3_HEADER\n\n#include <stdio.h>\n#include <Eigen/Dense>\n#include <Eigen/Geometry> \n\n#include \"common.h\"\n#include \"so3.h\"\n\n\ntemplate <typename Scalar>\nclass SE3 {\n  public:\n    const static int constexpr K = 6; // manifold dimension\n    const static int constexpr N = 7; // embedding dimension\n\n    using Vector3 = Eigen::Matrix<Scalar,3,1>;\n    using Vector4 = Eigen::Matrix<Scalar,4,1>;\n    using Matrix3 = Eigen::Matrix<Scalar,3,3>;\n\n    using Tangent = Eigen::Matrix<Scalar,K,1>;\n    using Point = Eigen::Matrix<Scalar,3,1>;\n    using Point4 = Eigen::Matrix<Scalar,4,1>;\n    using Data = Eigen::Matrix<Scalar,N,1>;\n    using Transformation = Eigen::Matrix<Scalar,4,4>;\n    using Adjoint = Eigen::Matrix<Scalar,K,K>;\n\n    EIGEN_DEVICE_FUNC SE3() { translation = Vector3::Zero(); }\n\n    EIGEN_DEVICE_FUNC SE3(SO3<Scalar> const& so3, Vector3 const& t) : so3(so3), translation(t) {};\n\n    EIGEN_DEVICE_FUNC SE3(const Scalar *data) :  translation(data), so3(data+3) {};\n\n    EIGEN_DEVICE_FUNC SE3<Scalar> inv() {\n      return SE3(so3.inv(), -(so3.inv()*translation));\n    }\n\n    EIGEN_DEVICE_FUNC Data data() const {\n      Data data_vec; data_vec << translation, so3.data();\n      return data_vec;\n    }\n\n    EIGEN_DEVICE_FUNC SE3<Scalar> operator*(SE3<Scalar> const& other) {\n      return SE3(so3 * other.so3, translation + so3 * other.translation);\n    }\n\n    EIGEN_DEVICE_FUNC Point operator*(Point const& p) const {\n      return so3 * p + translation;\n    }\n\n    EIGEN_DEVICE_FUNC Point4 act4(Point4 const& p) const {\n      Point4 p1; p1 << so3 * p.template segment<3>(0) + translation * p(3), p(3);\n      return p1;\n    }\n\n    EIGEN_DEVICE_FUNC Adjoint Adj() const {\n      Matrix3 R = so3.Matrix();\n      Matrix3 tx = SO3<Scalar>::hat(translation);\n      Matrix3 Zer = Matrix3::Zero();\n\n      Adjoint Ad;\n      Ad << R, tx*R, Zer, R;\n\n      return Ad;\n    }\n\n    EIGEN_DEVICE_FUNC Transformation Matrix() const {\n      Transformation T = Transformation::Identity();\n      T.template block<3,3>(0,0) = so3.Matrix();\n      T.template block<3,1>(0,3) = translation;\n      return T;\n    }\n\n    EIGEN_DEVICE_FUNC Transformation Matrix4x4() const {\n      return Matrix();\n    }\n\n    EIGEN_DEVICE_FUNC Tangent Adj(Tangent const& a) const {\n      return Adj() * a;\n    }\n\n    EIGEN_DEVICE_FUNC Tangent AdjT(Tangent const& a) const {\n      return Adj().transpose() * a;\n    }\n\n\n    EIGEN_DEVICE_FUNC static Transformation hat(Tangent const& tau_phi) {\n      Vector3 tau = tau_phi.template segment<3>(0);\n      Vector3 phi = tau_phi.template segment<3>(3);\n\n      Transformation TauPhi = Transformation::Zero();\n      TauPhi.template block<3,3>(0,0) = SO3<Scalar>::hat(phi);\n      TauPhi.template block<3,1>(0,3) = tau;\n      \n      return TauPhi;\n    }\n\n    EIGEN_DEVICE_FUNC static Adjoint adj(Tangent const& tau_phi) {\n      Vector3 tau = tau_phi.template segment<3>(0);\n      Vector3 phi = tau_phi.template segment<3>(3);\n\n      Matrix3 Tau = SO3<Scalar>::hat(tau);\n      Matrix3 Phi = SO3<Scalar>::hat(phi);\n      Matrix3 Zer = Matrix3::Zero();\n\n      Adjoint ad;\n      ad << Phi, Tau, Zer, Phi;\n\n      return ad;\n    }\n\n    EIGEN_DEVICE_FUNC Eigen::Matrix<Scalar,7,7> orthogonal_projector() const {\n      // jacobian action on a point\n      Eigen::Matrix<Scalar,7,7> J = Eigen::Matrix<Scalar,7,7>::Zero();\n      J.template block<3,3>(0,0) = Matrix3::Identity();\n      J.template block<3,3>(0,3) = SO3<Scalar>::hat(-translation);\n      J.template block<4,4>(3,3) = so3.orthogonal_projector();\n\n      return J;\n    }\n\n    EIGEN_DEVICE_FUNC Tangent Log() const {\n      Vector3 phi = so3.Log();      \n      Matrix3 Vinv = SO3<Scalar>::left_jacobian_inverse(phi);\n\n      Tangent tau_phi; \n      tau_phi << Vinv * translation, phi;\n\n      return tau_phi;\n    }\n\n    EIGEN_DEVICE_FUNC static SE3<Scalar> Exp(Tangent const& tau_phi) {\n      Vector3 tau = tau_phi.template segment<3>(0);\n      Vector3 phi = tau_phi.template segment<3>(3);\n\n      SO3<Scalar> so3 = SO3<Scalar>::Exp(phi);\n      Vector3 t = SO3<Scalar>::left_jacobian(phi) * tau;\n\n      return SE3<Scalar>(so3, t);\n    }\n\n    EIGEN_DEVICE_FUNC static Matrix3 calcQ(Tangent const& tau_phi) {\n      // Q matrix\n      Vector3 tau = tau_phi.template segment<3>(0);\n      Vector3 phi = tau_phi.template segment<3>(3);\n      Matrix3 Tau = SO3<Scalar>::hat(tau);\n      Matrix3 Phi = SO3<Scalar>::hat(phi);\n\n      Scalar theta = phi.norm();\n      Scalar theta_pow2 = theta * theta;\n      Scalar theta_pow4 = theta_pow2 * theta_pow2;\n\n      Scalar coef1 = (theta < EPS) ?\n        Scalar(1.0/6.0) - Scalar(1.0/120.0) * theta_pow2 : \n        (theta - sin(theta)) / (theta_pow2 * theta);\n\n      Scalar coef2 = (theta < EPS) ?\n        Scalar(1.0/24.0) - Scalar(1.0/720.0) * theta_pow2 : \n        (theta_pow2 + 2*cos(theta) - 2) / (2 * theta_pow4);\n\n      Scalar coef3 = (theta < EPS) ?\n        Scalar(1.0/120.0) - Scalar(1.0/2520.0) * theta_pow2 : \n        (2*theta - 3*sin(theta) + theta*cos(theta)) / (2 * theta_pow4 * theta);\n\n      Matrix3 Q = Scalar(0.5) * Tau + \n        coef1 * (Phi*Tau + Tau*Phi + Phi*Tau*Phi) +\n        coef2 * (Phi*Phi*Tau + Tau*Phi*Phi - 3*Phi*Tau*Phi) + \n        coef3 * (Phi*Tau*Phi*Phi + Phi*Phi*Tau*Phi);\n\n      return Q;\n    }\n    \n    EIGEN_DEVICE_FUNC static Adjoint left_jacobian(Tangent const& tau_phi) {\n      // left jacobian\n      Vector3 phi = tau_phi.template segment<3>(3);\n      Matrix3 J = SO3<Scalar>::left_jacobian(phi);\n      Matrix3 Q = SE3<Scalar>::calcQ(tau_phi);\n      Matrix3 Zer = Matrix3::Zero();\n\n      Adjoint J6x6;\n      J6x6 << J, Q, Zer, J;\n\n      return J6x6;\n    }\n\n    EIGEN_DEVICE_FUNC static Adjoint left_jacobian_inverse(Tangent const& tau_phi) {\n      // left jacobian inverse\n      Vector3 tau = tau_phi.template segment<3>(0);\n      Vector3 phi = tau_phi.template segment<3>(3);\n      Matrix3 Jinv = SO3<Scalar>::left_jacobian_inverse(phi);\n      Matrix3 Q = SE3<Scalar>::calcQ(tau_phi);\n      Matrix3 Zer = Matrix3::Zero();\n\n      Adjoint J6x6;\n      J6x6 << Jinv, -Jinv * Q * Jinv, Zer, Jinv;\n\n      return J6x6;\n\n    }\n\n    EIGEN_DEVICE_FUNC static Eigen::Matrix<Scalar,3,6> act_jacobian(Point const& p) {\n      // jacobian action on a point\n      Eigen::Matrix<Scalar,3,6> J;\n      J.template block<3,3>(0,0) = Matrix3::Identity();\n      J.template block<3,3>(0,3) = SO3<Scalar>::hat(-p);\n      return J;\n    }\n\n    EIGEN_DEVICE_FUNC static Eigen::Matrix<Scalar,4,6> act4_jacobian(Point4 const& p) {\n      // jacobian action on a point\n      Eigen::Matrix<Scalar,4,6> J = Eigen::Matrix<Scalar,4,6>::Zero();\n      J.template block<3,3>(0,0) = p(3) * Matrix3::Identity();\n      J.template block<3,3>(0,3) = SO3<Scalar>::hat(-p.template segment<3>(0));\n      return J;\n    }\n\n\n\n\n  private:\n    SO3<Scalar> so3;\n    Vector3 translation;\n\n};\n\n#endif\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/include/sim3.h",
    "content": "\n#ifndef Sim3_HEADER\n#define Sim3_HEADER\n\n#include <stdio.h>\n#include <iostream>\n\n#include <Eigen/Dense>\n#include <Eigen/Geometry> \n\n#include \"common.h\"\n#include \"so3.h\"\n#include \"rxso3.h\"\n\n\ntemplate <typename Scalar>\nclass Sim3 {\n  public:\n    const static int constexpr K = 7; // manifold dimension\n    const static int constexpr N = 8; // embedding dimension\n\n    using Vector3 = Eigen::Matrix<Scalar,3,1>;\n    using Vector4 = Eigen::Matrix<Scalar,4,1>;\n    using Matrix3 = Eigen::Matrix<Scalar,3,3>;\n\n    using Tangent = Eigen::Matrix<Scalar,K,1>;\n    using Point = Eigen::Matrix<Scalar,3,1>;\n    using Point4 = Eigen::Matrix<Scalar,4,1>;\n    using Data = Eigen::Matrix<Scalar,N,1>;\n    using Transformation = Eigen::Matrix<Scalar,4,4>;\n    using Adjoint = Eigen::Matrix<Scalar,K,K>;\n\n    EIGEN_DEVICE_FUNC Sim3() {\n      translation = Vector3::Zero();\n    }\n\n    EIGEN_DEVICE_FUNC Sim3(RxSO3<Scalar> const& rxso3, Vector3 const& t)\n      : rxso3(rxso3), translation(t) {};\n\n    EIGEN_DEVICE_FUNC Sim3(const Scalar *data) \n      : translation(data), rxso3(data+3)  {};\n\n    EIGEN_DEVICE_FUNC Sim3<Scalar> inv() {\n      return Sim3<Scalar>(rxso3.inv(), -(rxso3.inv() * translation));\n    }\n\n    EIGEN_DEVICE_FUNC Data data() const {\n      Data data_vec; data_vec << translation, rxso3.data();\n      return data_vec;\n    }\n\n    EIGEN_DEVICE_FUNC Sim3<Scalar> operator*(Sim3<Scalar> const& other) {\n      return Sim3(rxso3 * other.rxso3, translation + rxso3 * other.translation);\n    }\n\n    EIGEN_DEVICE_FUNC Point operator*(Point const& p) const {\n      return (rxso3 * p) + translation;\n    }\n    \n    EIGEN_DEVICE_FUNC Point4 act4(Point4 const& p) const {\n      Point4 p1; p1 << rxso3 * p.template segment<3>(0) + p(3) * translation , p(3);\n      return p1;\n    }\n\n    EIGEN_DEVICE_FUNC Transformation Matrix() const {\n      Transformation T = Transformation::Identity();\n      T.template block<3,3>(0,0) = rxso3.Matrix();\n      T.template block<3,1>(0,3) = translation;\n      return T;\n    }\n\n    EIGEN_DEVICE_FUNC Transformation Matrix4x4() const {\n      Transformation T = Transformation::Identity();\n      T.template block<3,3>(0,0) = rxso3.Matrix();\n      T.template block<3,1>(0,3) = translation;\n      return T;\n    }\n\n    EIGEN_DEVICE_FUNC Eigen::Matrix<Scalar,8,8> orthogonal_projector() const {\n      // jacobian action on a point\n      Eigen::Matrix<Scalar,8,8> J = Eigen::Matrix<Scalar,8,8>::Zero();\n      J.template block<3,3>(0,0) = Matrix3::Identity();\n      J.template block<3,3>(0,3) = SO3<Scalar>::hat(-translation);\n      J.template block<3,1>(0,6) = translation;\n      J.template block<5,5>(3,3) = rxso3.orthogonal_projector();\n      return J;\n    }\n\n    EIGEN_DEVICE_FUNC Adjoint Adj() const {\n      Adjoint Ad = Adjoint::Identity();\n      Matrix3 sR = rxso3.Matrix();\n      Matrix3 tx = SO3<Scalar>::hat(translation);\n      Matrix3 R = rxso3.Rotation();\n\n      Ad.template block<3,3>(0,0) = sR;\n      Ad.template block<3,3>(0,3) = tx * R;\n      Ad.template block<3,1>(0,6) = -translation;\n      Ad.template block<3,3>(3,3) = R;\n\n      return Ad;\n    }\n\n    EIGEN_DEVICE_FUNC Tangent Adj(Tangent const& a) const {\n      return Adj() * a;\n    }\n\n    EIGEN_DEVICE_FUNC Tangent AdjT(Tangent const& a) const {\n      return Adj().transpose() * a;\n    }\n\n    EIGEN_DEVICE_FUNC static Transformation hat(Tangent const& tau_phi_sigma) {\n      Vector3 tau = tau_phi_sigma.template segment<3>(0);\n      Vector3 phi = tau_phi_sigma.template segment<3>(3);\n      Scalar sigma = tau_phi_sigma(6);\n\n      Matrix3 Phi = SO3<Scalar>::hat(phi);\n      Matrix3 I = Matrix3::Identity();\n      \n      Transformation Omega = Transformation::Zero();\n      Omega.template block<3,3>(0,0) = Phi + sigma * I;\n      Omega.template block<3,1>(0,3) = tau;\n      \n      return Omega;\n    }\n\n    EIGEN_DEVICE_FUNC  static Adjoint adj(Tangent const& tau_phi_sigma) {\n      Adjoint ad = Adjoint::Zero();\n      Vector3 tau = tau_phi_sigma.template segment<3>(0);\n      Vector3 phi = tau_phi_sigma.template segment<3>(3);\n      Scalar sigma = tau_phi_sigma(6);\n\n      Matrix3 Tau = SO3<Scalar>::hat(tau);\n      Matrix3 Phi = SO3<Scalar>::hat(phi);\n      Matrix3 I = Matrix3::Identity();\n\n      ad.template block<3,3>(0,0) = Phi + sigma * I;\n      ad.template block<3,3>(0,3) = Tau;\n      ad.template block<3,1>(0,6) = -tau;\n      ad.template block<3,3>(3,3) = Phi;\n\n      return ad;\n    }\n    \n\n    EIGEN_DEVICE_FUNC Tangent Log() const {\n      // logarithm map\n      Vector4 phi_sigma = rxso3.Log();      \n      Matrix3 W = RxSO3<Scalar>::calcW(phi_sigma);\n      \n      Tangent tau_phi_sigma; \n      tau_phi_sigma << W.inverse() * translation, phi_sigma;\n\n      return tau_phi_sigma;\n    }\n\n    EIGEN_DEVICE_FUNC static Sim3<Scalar> Exp(Tangent const& tau_phi_sigma) {\n      // exponential map\n      Vector3 tau = tau_phi_sigma.template segment<3>(0);\n      Vector4 phi_sigma = tau_phi_sigma.template segment<4>(3);\n      \n      RxSO3<Scalar> rxso3 = RxSO3<Scalar>::Exp(phi_sigma);\n      Matrix3 W = RxSO3<Scalar>::calcW(phi_sigma);\n\n      return Sim3<Scalar>(rxso3, W*tau);\n    }\n\n    EIGEN_DEVICE_FUNC static Adjoint left_jacobian(Tangent const& tau_phi_sigma) {\n      // left jacobian\n      Adjoint const Xi = adj(tau_phi_sigma);\n      Adjoint const Xi2 = Xi * Xi;\n      Adjoint const Xi4 = Xi2 * Xi2;\n\n      return Adjoint::Identity() \n        + Scalar(1.0/2.0)*Xi\n        + Scalar(1.0/6.0)*Xi2\n        + Scalar(1.0/24.0)*Xi*Xi2\n        + Scalar(1.0/120.0)*Xi4;\n        + Scalar(1.0/720.0)*Xi*Xi4;\n    }\n\n    EIGEN_DEVICE_FUNC static Adjoint left_jacobian_inverse(Tangent const& tau_phi_sigma) {\n      // left jacobian inverse\n      Adjoint const Xi = adj(tau_phi_sigma);\n      Adjoint const Xi2 = Xi * Xi;\n      Adjoint const Xi4 = Xi2 * Xi2;\n\n      return Adjoint::Identity() \n        - Scalar(1.0/2.0)*Xi\n        + Scalar(1.0/12.0)*Xi2\n        - Scalar(1.0/720.0)*Xi4;\n    }\n\n    EIGEN_DEVICE_FUNC static Eigen::Matrix<Scalar,3,7> act_jacobian(Point const& p) {\n      // jacobian action on a point\n      Eigen::Matrix<Scalar,3,7> J;\n      J.template block<3,3>(0,0) = Matrix3::Identity();\n      J.template block<3,3>(0,3) = SO3<Scalar>::hat(-p);\n      J.template block<3,1>(0,6) = p;\n      return J;\n    }\n\n    EIGEN_DEVICE_FUNC static Eigen::Matrix<Scalar,4,7> act4_jacobian(Point4 const& p) {\n      // jacobian action on a point\n      Eigen::Matrix<Scalar,4,7> J = Eigen::Matrix<Scalar,4,7>::Zero();\n      J.template block<3,3>(0,0) = p(3) * Matrix3::Identity();\n      J.template block<3,3>(0,3) = SO3<Scalar>::hat(-p.template segment<3>(0));\n      J.template block<3,1>(0,6) = p.template segment<3>(0);\n      return J;\n    }\n\n  private:\n    Vector3 translation;\n    RxSO3<Scalar> rxso3;\n};\n\n#endif\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/include/so3.h",
    "content": "\n#ifndef SO3_HEADER\n#define SO3_HEADER\n\n#include <cuda.h>\n#include <stdio.h>\n#include <Eigen/Dense>\n#include <Eigen/Geometry> \n\n#include \"common.h\"\n\ntemplate <typename Scalar>\nclass SO3 {\n  public:\n    const static int constexpr K = 3; // manifold dimension\n    const static int constexpr N = 4; // embedding dimension\n\n    using Vector3 = Eigen::Matrix<Scalar,3,1>;\n    using Vector4 = Eigen::Matrix<Scalar,4,1>;\n    using Matrix3 = Eigen::Matrix<Scalar,3,3>;\n\n    using Tangent = Eigen::Matrix<Scalar,K,1>;\n    using Data = Eigen::Matrix<Scalar,N,1>;\n\n    using Point = Eigen::Matrix<Scalar,3,1>;\n    using Point4 = Eigen::Matrix<Scalar,4,1>;\n    using Transformation = Eigen::Matrix<Scalar,3,3>;\n    using Adjoint = Eigen::Matrix<Scalar,K,K>;\n    using Quaternion = Eigen::Quaternion<Scalar>;\n\n    EIGEN_DEVICE_FUNC SO3(Quaternion const& q) : unit_quaternion(q) {\n      unit_quaternion.normalize();\n    };\n\n    EIGEN_DEVICE_FUNC SO3(const Scalar *data) : unit_quaternion(data) {\n      unit_quaternion.normalize();\n    };\n\n    EIGEN_DEVICE_FUNC SO3() {\n      unit_quaternion = Quaternion::Identity();\n    }\n\n    EIGEN_DEVICE_FUNC SO3<Scalar> inv() {\n      return SO3<Scalar>(unit_quaternion.conjugate());\n    }\n\n    EIGEN_DEVICE_FUNC Data data() const {\n      return unit_quaternion.coeffs();\n    }\n\n    EIGEN_DEVICE_FUNC SO3<Scalar> operator*(SO3<Scalar> const& other) {\n      return SO3(unit_quaternion * other.unit_quaternion);\n    }\n\n    EIGEN_DEVICE_FUNC Point operator*(Point const& p) const {\n      const Quaternion& q = unit_quaternion;\n      Point uv = q.vec().cross(p);\n      uv += uv;\n      return p + q.w()*uv + q.vec().cross(uv);\n    }\n\n    EIGEN_DEVICE_FUNC Point4 act4(Point4 const& p) const {\n      Point4 p1; p1 << this->operator*(p.template segment<3>(0)), p(3);\n      return p1;\n    }\n    \n    EIGEN_DEVICE_FUNC Adjoint Adj() const {\n      return unit_quaternion.toRotationMatrix();\n    }\n\n    EIGEN_DEVICE_FUNC Transformation Matrix() const {\n      return unit_quaternion.toRotationMatrix();\n    }\n\n    EIGEN_DEVICE_FUNC Eigen::Matrix<Scalar,4,4> Matrix4x4() const {\n      Eigen::Matrix<Scalar,4,4> T = Eigen::Matrix<Scalar,4,4>::Identity();\n      T.template block<3,3>(0,0) = Matrix();\n      return T;\n    }\n\n    EIGEN_DEVICE_FUNC Eigen::Matrix<Scalar,4,4> orthogonal_projector() const {\n      // jacobian action on a point\n      Eigen::Matrix<Scalar,4,4> J = Eigen::Matrix<Scalar,4,4>::Zero();\n      J.template block<3,3>(0,0) = 0.5 * (\n        unit_quaternion.w() * Matrix3::Identity() + \n        SO3<Scalar>::hat(-unit_quaternion.vec())\n      );\n      \n      J.template block<1,3>(3,0) = 0.5 * (-unit_quaternion.vec());\n      return J;\n    }\n\n    EIGEN_DEVICE_FUNC Tangent Adj(Tangent const& a) const {\n      return Adj() * a;\n    }\n\n    EIGEN_DEVICE_FUNC Tangent AdjT(Tangent const& a) const {\n      return Adj().transpose() * a;\n    }\n\n    EIGEN_DEVICE_FUNC static Transformation hat(Tangent const& phi) {\n      Transformation Phi;\n      Phi << \n        0.0, -phi(2), phi(1), \n        phi(2), 0.0, -phi(0), \n        -phi(1), phi(0), 0.0;\n\n      return Phi;\n    }\n\n    EIGEN_DEVICE_FUNC static Adjoint adj(Tangent const& phi) {\n      return SO3<Scalar>::hat(phi);\n    }\n\n    EIGEN_DEVICE_FUNC Tangent Log() const {\n      using std::abs;\n      using std::atan;\n      using std::sqrt;\n      Scalar squared_n = unit_quaternion.vec().squaredNorm();\n      Scalar w = unit_quaternion.w();\n\n      Scalar two_atan_nbyw_by_n;\n\n      /// Atan-based log thanks to\n      ///\n      /// C. Hertzberg et al.:\n      /// \"Integrating Generic Sensor Fusion Algorithms with Sound State\n      /// Representation through Encapsulation of Manifolds\"\n      /// Information Fusion, 2011\n\n      if (squared_n < EPS * EPS) {\n        // If quaternion is normalized and n=0, then w should be 1;\n        // w=0 should never happen here!\n        Scalar squared_w = w * w;\n        two_atan_nbyw_by_n =\n            Scalar(2) / w - Scalar(2.0/3.0) * (squared_n) / (w * squared_w);\n      } else {\n        Scalar n = sqrt(squared_n);\n        if (abs(w) < EPS) {\n          if (w > Scalar(0)) {\n            two_atan_nbyw_by_n = Scalar(PI) / n;\n          } else {\n            two_atan_nbyw_by_n = -Scalar(PI) / n;\n          }\n        } else {\n          two_atan_nbyw_by_n = Scalar(2) * atan(n / w) / n;\n        }\n      }\n\n      return two_atan_nbyw_by_n * unit_quaternion.vec();\n    }\n\n    EIGEN_DEVICE_FUNC static SO3<Scalar> Exp(Tangent const& phi) {\n      Scalar theta2 = phi.squaredNorm();\n      Scalar theta = sqrt(theta2);\n      Scalar imag_factor;\n      Scalar real_factor;\n\n      if (theta < EPS) {\n        Scalar theta4 = theta2 * theta2;\n        imag_factor = Scalar(0.5) - Scalar(1.0/48.0) * theta2 + Scalar(1.0/3840.0) * theta4;\n        real_factor = Scalar(1) - Scalar(1.0/8.0) * theta2 + Scalar(1.0/384.0) * theta4;\n      } else {\n        imag_factor = sin(.5 * theta) / theta;\n        real_factor = cos(.5 * theta);\n      }\n\n      Quaternion q(real_factor, imag_factor*phi.x(), imag_factor*phi.y(), imag_factor*phi.z());\n      return SO3<Scalar>(q);\n    }\n    \n    EIGEN_DEVICE_FUNC static Adjoint left_jacobian(Tangent const& phi) {\n      // left jacobian\n      Matrix3 I = Matrix3::Identity();\n      Matrix3 Phi = SO3<Scalar>::hat(phi);\n      Matrix3 Phi2 = Phi * Phi;\n\n      Scalar theta2 = phi.squaredNorm();\n      Scalar theta = sqrt(theta2);\n\n      Scalar coef1 = (theta < EPS) ? \n        Scalar(1.0/2.0) - Scalar(1.0/24.0) * theta2 : \n        (1.0 - cos(theta)) / theta2;\n      \n      Scalar coef2 = (theta < EPS) ? \n        Scalar(1.0/6.0) - Scalar(1.0/120.0) * theta2 : \n        (theta - sin(theta)) / (theta2 * theta); \n\n      return I + coef1 * Phi + coef2 * Phi2;\n    }\n\n    EIGEN_DEVICE_FUNC static Adjoint left_jacobian_inverse(Tangent const& phi) {\n      // left jacobian inverse\n      Matrix3 I = Matrix3::Identity();\n      Matrix3 Phi = SO3<Scalar>::hat(phi);\n      Matrix3 Phi2 = Phi * Phi;\n\n      Scalar theta2 = phi.squaredNorm();\n      Scalar theta = sqrt(theta2);\n      Scalar half_theta = Scalar(.5) * theta ;\n\n      Scalar coef2 = (theta < EPS) ? Scalar(1.0/12.0) : \n           (Scalar(1) -\n            theta * cos(half_theta) / (Scalar(2) * sin(half_theta))) /\n               (theta * theta);\n\n      return I + Scalar(-0.5) * Phi + coef2 * Phi2;\n    }\n\n    EIGEN_DEVICE_FUNC static Eigen::Matrix<Scalar,3,3> act_jacobian(Point const& p) {\n      // jacobian action on a point\n      return SO3<Scalar>::hat(-p);\n    }\n\n    EIGEN_DEVICE_FUNC static Eigen::Matrix<Scalar,4,3> act4_jacobian(Point4 const& p) {\n      // jacobian action on a point\n      Eigen::Matrix<Scalar,4,3> J = Eigen::Matrix<Scalar,4,3>::Zero();\n      J.template block<3,3>(0,0) = SO3<Scalar>::hat(-p.template segment<3>(0));\n      return J;\n    }\n\n  private:\n    Quaternion unit_quaternion;\n\n};\n\n#endif\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/run_tests.py",
    "content": "import torch\nimport lietorch\n\nfrom lietorch import SO3, RxSO3, SE3, Sim3\nfrom gradcheck import gradcheck, get_analytical_jacobian\n\n\n### forward tests ###\n\ndef make_homogeneous(p):\n    return torch.cat([p, torch.ones_like(p[...,:1])], dim=-1)\n\ndef matv(A, b):\n    return torch.matmul(A, b[...,None])[..., 0]\n\ndef test_exp_log(Group, device='cuda'):\n    \"\"\" check Log(Exp(x)) == x \"\"\"\n    a = .2*torch.randn(2,3,4,5,6,7,Group.manifold_dim, device=device).double()\n    b = Group.exp(a).log()\n    assert torch.allclose(a,b,atol=1e-8), \"should be identity\"\n    print(\"\\t-\", Group, \"Passed exp-log test\")\n    \ndef test_inv(Group, device='cuda'):\n    \"\"\" check X * X^{-1} == 0 \"\"\"\n    X = Group.exp(.1*torch.randn(2,3,4,5,Group.manifold_dim, device=device).double())\n    a = (X * X.inv()).log()\n    assert torch.allclose(a, torch.zeros_like(a), atol=1e-8), \"should be 0\"\n    print(\"\\t-\", Group, \"Passed inv test\")\n\ndef test_adj(Group, device='cuda'):\n    \"\"\" check X * Exp(a) == Exp(Adj(X,a)) * X 0 \"\"\"\n    X = Group.exp(torch.randn(2,3,4,5, Group.manifold_dim, device=device).double())\n    a = torch.randn(2,3,4,5, Group.manifold_dim, device=device).double()\n\n    b = X.adj(a)\n    Y1 = X * Group.exp(a)\n    Y2 = Group.exp(b) * X\n\n    c = (Y1 * Y2.inv()).log()\n    assert torch.allclose(c, torch.zeros_like(c), atol=1e-8), \"should be 0\"\n    print(\"\\t-\", Group, \"Passed adj test\")\n    \n\ndef test_act(Group, device='cuda'):\n    X = Group.exp(torch.randn(1, Group.manifold_dim, device=device).double())\n    p = torch.randn(1,3,device=device).double()\n\n    p1 = X.act(p)\n    p2 = matv(X.matrix(), make_homogeneous(p))\n\n    assert torch.allclose(p1, p2[...,:3], atol=1e-8), \"should be 0\"\n    print(\"\\t-\", Group, \"Passed act test\")\n\n\n### backward tests ###\ndef test_exp_log_grad(Group, device='cuda', tol=1e-8):\n    \n    D = Group.manifold_dim\n\n    def fn(a):\n        return Group.exp(a).log()\n\n    a = torch.zeros(1, Group.manifold_dim, requires_grad=True, device=device).double()\n    analytical, reentrant, correct_grad_sizes, correct_grad_types = \\\n        get_analytical_jacobian((a,), fn(a))\n\n    assert torch.allclose(analytical[0], torch.eye(D, device=device).double(), atol=tol)\n\n    a = .2 * torch.randn(1, Group.manifold_dim, requires_grad=True, device=device).double()\n    analytical, reentrant, correct_grad_sizes, correct_grad_types = \\\n        get_analytical_jacobian((a,), fn(a))\n\n    assert torch.allclose(analytical[0], torch.eye(D, device=device).double(), atol=tol)\n\n    print(\"\\t-\", Group, \"Passed eye-grad test\")\n\n\ndef test_inv_log_grad(Group, device='cuda', tol=1e-8):\n\n    D = Group.manifold_dim\n    X = Group.exp(.2*torch.randn(1,D,device=device).double())\n\n    def fn(a):\n        return (Group.exp(a) * X).inv().log()\n\n    a = torch.zeros(1, D, requires_grad=True, device=device).double()\n    analytical, numerical = gradcheck(fn, [a], eps=1e-4)\n\n    # assert torch.allclose(analytical[0], numerical[0], atol=tol)\n    if not torch.allclose(analytical[0], numerical[0], atol=tol):\n        print(analytical[0])\n        print(numerical[0])\n\n    print(\"\\t-\", Group, \"Passed inv-grad test\")\n\n\ndef test_adj_grad(Group, device='cuda'):\n    D = Group.manifold_dim\n    X = Group.exp(.5*torch.randn(1,Group.manifold_dim, device=device).double())\n    \n    def fn(a, b):\n        return (Group.exp(a) * X).adj(b)\n\n    a = torch.zeros(1, D, requires_grad=True, device=device).double()\n    b = torch.randn(1, D, requires_grad=True, device=device).double()\n\n    analytical, numerical = gradcheck(fn, [a, b], eps=1e-4)\n    assert torch.allclose(analytical[0], numerical[0], atol=1e-8)\n    assert torch.allclose(analytical[1], numerical[1], atol=1e-8)\n\n    print(\"\\t-\", Group, \"Passed adj-grad test\")\n\n\ndef test_adjT_grad(Group, device='cuda'):\n    D = Group.manifold_dim\n    X = Group.exp(.5*torch.randn(1,Group.manifold_dim, device=device).double())\n    \n    def fn(a, b):\n        return (Group.exp(a) * X).adjT(b)\n\n    a = torch.zeros(1, D, requires_grad=True, device=device).double()\n    b = torch.randn(1, D, requires_grad=True, device=device).double()\n\n    analytical, numerical = gradcheck(fn, [a, b], eps=1e-4)\n\n    assert torch.allclose(analytical[0], numerical[0], atol=1e-8)\n    assert torch.allclose(analytical[1], numerical[1], atol=1e-8)\n\n    print(\"\\t-\", Group, \"Passed adjT-grad test\")\n\n\ndef test_act_grad(Group, device='cuda'):\n    D = Group.manifold_dim\n    X = Group.exp(5*torch.randn(1,D, device=device).double())\n    \n    def fn(a, b):\n        return (X*Group.exp(a)).act(b)\n\n    a = torch.zeros(1, D, requires_grad=True, device=device).double()\n    b = torch.randn(1, 3, requires_grad=True, device=device).double()\n\n    analytical, numerical = gradcheck(fn, [a, b], eps=1e-4)\n\n    assert torch.allclose(analytical[0], numerical[0], atol=1e-8)\n    assert torch.allclose(analytical[1], numerical[1], atol=1e-8)\n\n    print(\"\\t-\", Group, \"Passed act-grad test\")\n\n\ndef test_matrix_grad(Group, device='cuda'):\n    D = Group.manifold_dim\n    X = Group.exp(torch.randn(1, D, device=device).double())\n    \n    def fn(a):\n        return (Group.exp(a) * X).matrix()\n\n    a = torch.zeros(1, D, requires_grad=True, device=device).double()\n    analytical, numerical = gradcheck(fn, [a], eps=1e-4)\n    assert torch.allclose(analytical[0], numerical[0], atol=1e-6)\n\n    print(\"\\t-\", Group, \"Passed matrix-grad test\")\n\n\ndef extract_translation_grad(Group, device='cuda'):\n    \"\"\" prototype function \"\"\"\n\n    D = Group.manifold_dim\n    X = Group.exp(5*torch.randn(1,D, device=device).double())\n    \n    def fn(a):\n        return (Group.exp(a)*X).translation()\n\n    a = torch.zeros(1, D, requires_grad=True, device=device).double()\n\n    analytical, numerical = gradcheck(fn, [a], eps=1e-4)\n\n    assert torch.allclose(analytical[0], numerical[0], atol=1e-8)\n    print(\"\\t-\", Group, \"Passed translation grad test\")\n\n\ndef test_vec_grad(Group, device='cuda', tol=1e-6):\n\n    D = Group.manifold_dim\n    X = Group.exp(5*torch.randn(1,D, device=device).double())\n    \n    def fn(a):\n        return (Group.exp(a)*X).vec()\n\n    a = torch.zeros(1, D, requires_grad=True, device=device).double()\n\n    analytical, numerical = gradcheck(fn, [a], eps=1e-4)\n\n    assert torch.allclose(analytical[0], numerical[0], atol=tol)\n    print(\"\\t-\", Group, \"Passed tovec grad test\")\n\n\ndef test_fromvec_grad(Group, device='cuda', tol=1e-6):\n\n    def fn(a):\n        if Group == SO3:\n            a = a / a.norm(dim=-1, keepdim=True)\n\n        elif Group == RxSO3:\n            q, s = a.split([4, 1], dim=-1)\n            q = q / q.norm(dim=-1, keepdim=True)\n            a = torch.cat([q, s.exp()], dim=-1)\n\n        elif Group == SE3:\n            t, q = a.split([3, 4], dim=-1)\n            q = q / q.norm(dim=-1, keepdim=True)\n            a = torch.cat([t, q], dim=-1)\n\n        elif Group == Sim3:\n            t, q, s = a.split([3, 4, 1], dim=-1)\n            q = q / q.norm(dim=-1, keepdim=True)\n            a = torch.cat([t, q, s.exp()], dim=-1)\n\n        return Group.InitFromVec(a).vec()\n\n    D = Group.embedded_dim\n    a = torch.randn(1, 2, D, requires_grad=True, device=device).double()\n\n    analytical, numerical = gradcheck(fn, [a], eps=1e-4)\n\n    assert torch.allclose(analytical[0], numerical[0], atol=tol)\n    print(\"\\t-\", Group, \"Passed fromvec grad test\")\n\n\n\ndef scale(device='cuda'):\n    \n    def fn(a, s):\n        X = SE3.exp(a)\n        X.scale(s)\n        return X.log()\n\n    s = torch.rand(1, requires_grad=True, device=device).double()\n    a = torch.randn(1, 6, requires_grad=True, device=device).double()\n    \n    analytical, numerical = gradcheck(fn, [a, s], eps=1e-3)\n    print(analytical[1])\n    print(numerical[1])\n\n\n    assert torch.allclose(analytical[0], numerical[0], atol=1e-8)\n    assert torch.allclose(analytical[1], numerical[1], atol=1e-8)\n\n    print(\"\\t-\", \"Passed se3-to-sim3 test\")\n\n    \nif __name__ == '__main__':\n\n\n    print(\"Testing lietorch forward pass (CPU) ...\")\n    for Group in [SO3, RxSO3, SE3, Sim3]:\n        test_exp_log(Group, device='cpu')\n        test_inv(Group, device='cpu')\n        test_adj(Group, device='cpu')\n        test_act(Group, device='cpu')\n\n    print(\"Testing lietorch backward pass (CPU)...\")\n    for Group in [SO3, RxSO3, SE3, Sim3]:\n        if Group == Sim3:\n            tol = 1e-3\n        else:\n            tol = 1e-8\n\n        test_exp_log_grad(Group, device='cpu', tol=tol)\n        test_inv_log_grad(Group, device='cpu', tol=tol)\n        test_adj_grad(Group, device='cpu')\n        test_adjT_grad(Group, device='cpu')\n        test_act_grad(Group, device='cpu')\n        test_matrix_grad(Group, device='cpu')\n        extract_translation_grad(Group, device='cpu')\n        test_vec_grad(Group, device='cpu')\n        test_fromvec_grad(Group, device='cpu')\n\n    print(\"Testing lietorch forward pass (GPU) ...\")\n    for Group in [SO3, RxSO3, SE3, Sim3]:\n        test_exp_log(Group, device='cuda')\n        test_inv(Group, device='cuda')\n        test_adj(Group, device='cuda')\n        test_act(Group, device='cuda')\n\n    print(\"Testing lietorch backward pass (GPU)...\")\n    for Group in [SO3, RxSO3, SE3, Sim3]:\n        if Group == Sim3:\n            tol = 1e-3\n        else:\n            tol = 1e-8\n\n        test_exp_log_grad(Group, device='cuda', tol=tol)\n        test_inv_log_grad(Group, device='cuda', tol=tol)\n        test_adj_grad(Group, device='cuda')\n        test_adjT_grad(Group, device='cuda')\n        test_act_grad(Group, device='cuda')\n        test_matrix_grad(Group, device='cuda')\n        extract_translation_grad(Group, device='cuda')\n        test_vec_grad(Group, device='cuda')\n        test_fromvec_grad(Group, device='cuda')\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/src/lietorch.cpp",
    "content": "#include <torch/extension.h>\n#include <vector>\n#include \"lietorch_gpu.h\"\n#include \"lietorch_cpu.h\"\n\n\n#define CHECK_CONTIGUOUS(x) TORCH_CHECK(x.is_contiguous(), #x \" must be contiguous\")\n\n\n/* Interface for cuda and c++ group operations\n\n    enum group_t { SO3=1, SE3=2, Sim3=3 };\n    X, Y, Z: (uppercase) Lie Group Elements\n    a, b, c: (lowercase) Lie Algebra Elements\n*/\n\n// Unary operations\ntorch::Tensor expm(int group_index, torch::Tensor a) {\n    CHECK_CONTIGUOUS(a);\n    if (a.device().type() == torch::DeviceType::CPU) {\n        return exp_forward_cpu(group_index, a);\n\n    } else if (a.device().type() == torch::DeviceType::CUDA) {\n        return exp_forward_gpu(group_index, a);\n    }\n\n    return a;\n}\n\nstd::vector<torch::Tensor> expm_backward(int group_index, torch::Tensor grad, torch::Tensor a) {\n    CHECK_CONTIGUOUS(a);\n    CHECK_CONTIGUOUS(grad);\n    if (a.device().type() == torch::DeviceType::CPU) {\n        return exp_backward_cpu(group_index, grad, a);\n\n    } else if (a.device().type() == torch::DeviceType::CUDA) {\n        return exp_backward_gpu(group_index, grad, a);\n    }\n\n    return {};\n}\n\ntorch::Tensor logm(int group_index, torch::Tensor X) {\n    CHECK_CONTIGUOUS(X);\n    if (X.device().type() == torch::DeviceType::CPU) {\n        return log_forward_cpu(group_index, X);\n\n    } else if (X.device().type() == torch::DeviceType::CUDA) {\n        return log_forward_gpu(group_index, X);\n    }\n\n    return X;\n}\n\nstd::vector<torch::Tensor> logm_backward(int group_index, torch::Tensor grad, torch::Tensor X) {\n    CHECK_CONTIGUOUS(X);\n    CHECK_CONTIGUOUS(grad);\n\n    if (X.device().type() == torch::DeviceType::CPU) {\n        return log_backward_cpu(group_index, grad, X);\n\n    } else if (X.device().type() == torch::DeviceType::CUDA) {\n        return log_backward_gpu(group_index, grad, X);\n    }\n\n    return {};\n}\n\ntorch::Tensor inv(int group_index, torch::Tensor X) {\n    CHECK_CONTIGUOUS(X);\n\n    if (X.device().type() == torch::DeviceType::CPU) {\n        return inv_forward_cpu(group_index, X);\n    } else if (X.device().type() == torch::DeviceType::CUDA) {\n        return inv_forward_gpu(group_index, X);\n    }\n\n    return X;\n}\n\nstd::vector<torch::Tensor> inv_backward(int group_index, torch::Tensor grad, torch::Tensor X) {\n    CHECK_CONTIGUOUS(X);\n    CHECK_CONTIGUOUS(grad);\n\n    if (X.device().type() == torch::DeviceType::CPU) {\n        return inv_backward_cpu(group_index, grad, X);\n\n    } else if (X.device().type() == torch::DeviceType::CUDA) {\n        return inv_backward_gpu(group_index, grad, X);\n    }\n\n    return {};\n}\n\n// Binary operations\n\ntorch::Tensor mul(int group_index, torch::Tensor X, torch::Tensor Y) {\n    CHECK_CONTIGUOUS(X);\n    CHECK_CONTIGUOUS(Y);\n\n    if (X.device().type() == torch::DeviceType::CPU) {\n        return mul_forward_cpu(group_index, X, Y);\n\n    } else if (X.device().type() == torch::DeviceType::CUDA) {\n        return mul_forward_gpu(group_index, X, Y);\n    }\n\n    return X;\n}\n\nstd::vector<torch::Tensor> mul_backward(int group_index, torch::Tensor grad, torch::Tensor X, torch::Tensor Y) {\n    CHECK_CONTIGUOUS(X);\n    CHECK_CONTIGUOUS(Y);\n    CHECK_CONTIGUOUS(grad);\n\n    if (X.device().type() == torch::DeviceType::CPU) {\n        return mul_backward_cpu(group_index, grad, X, Y);\n\n    } else if (X.device().type() == torch::DeviceType::CUDA) {\n        return mul_backward_gpu(group_index, grad, X, Y);\n    }\n\n    return {};\n}\n\ntorch::Tensor adj(int group_index, torch::Tensor X, torch::Tensor a) {\n    CHECK_CONTIGUOUS(X);\n    CHECK_CONTIGUOUS(a);\n\n    if (X.device().type() == torch::DeviceType::CPU) {\n        return adj_forward_cpu(group_index, X, a);\n\n    } else if (X.device().type() == torch::DeviceType::CUDA) {\n        return adj_forward_gpu(group_index, X, a);\n    }\n\n    return X;\n}\n\nstd::vector<torch::Tensor> adj_backward(int group_index, torch::Tensor grad, torch::Tensor X, torch::Tensor a) {\n    CHECK_CONTIGUOUS(X);\n    CHECK_CONTIGUOUS(a);\n    CHECK_CONTIGUOUS(grad);\n\n    if (X.device().type() == torch::DeviceType::CPU) {\n        return adj_backward_cpu(group_index, grad, X, a);\n\n    } else if (X.device().type() == torch::DeviceType::CUDA) {\n        return adj_backward_gpu(group_index, grad, X, a);\n    }\n\n    return {};\n}\n\ntorch::Tensor adjT(int group_index, torch::Tensor X, torch::Tensor a) {\n    CHECK_CONTIGUOUS(X);\n    CHECK_CONTIGUOUS(a);\n    \n    if (X.device().type() == torch::DeviceType::CPU) {\n        return adjT_forward_cpu(group_index, X, a);\n\n    } else if (X.device().type() == torch::DeviceType::CUDA) {\n        return adjT_forward_gpu(group_index, X, a);\n    }\n\n    return X;\n}\n\nstd::vector<torch::Tensor> adjT_backward(int group_index, torch::Tensor grad, torch::Tensor X, torch::Tensor a) {\n    CHECK_CONTIGUOUS(X);\n    CHECK_CONTIGUOUS(a);\n    CHECK_CONTIGUOUS(grad);\n    \n    if (X.device().type() == torch::DeviceType::CPU) {\n        return adjT_backward_cpu(group_index, grad, X, a);\n\n    } else if (X.device().type() == torch::DeviceType::CUDA) {\n        return adjT_backward_gpu(group_index, grad, X, a);\n    }\n\n    return {};\n}\n\n\ntorch::Tensor act(int group_index, torch::Tensor X, torch::Tensor p) {\n    CHECK_CONTIGUOUS(X);\n    CHECK_CONTIGUOUS(p);\n\n    if (X.device().type() == torch::DeviceType::CPU) {\n        return act_forward_cpu(group_index, X, p);\n\n    } else if (X.device().type() == torch::DeviceType::CUDA) {\n        return act_forward_gpu(group_index, X, p);\n    }\n\n    return X;\n}\n\nstd::vector<torch::Tensor> act_backward(int group_index, torch::Tensor grad, torch::Tensor X, torch::Tensor p) {\n    CHECK_CONTIGUOUS(X);\n    CHECK_CONTIGUOUS(p);\n    CHECK_CONTIGUOUS(grad);\n\n    if (X.device().type() == torch::DeviceType::CPU) {\n        return act_backward_cpu(group_index, grad, X, p);\n\n    } else if (X.device().type() == torch::DeviceType::CUDA) {\n        return act_backward_gpu(group_index, grad, X, p);\n    }\n\n    return {};\n}\n\ntorch::Tensor act4(int group_index, torch::Tensor X, torch::Tensor p) {\n    CHECK_CONTIGUOUS(X);\n    CHECK_CONTIGUOUS(p);\n    \n    if (X.device().type() == torch::DeviceType::CPU) {\n        return act4_forward_cpu(group_index, X, p);\n\n    } else if (X.device().type() == torch::DeviceType::CUDA) {\n        return act4_forward_gpu(group_index, X, p);\n    }\n\n    return X;\n}\n\nstd::vector<torch::Tensor> act4_backward(int group_index, torch::Tensor grad, torch::Tensor X, torch::Tensor p) {\n    CHECK_CONTIGUOUS(X);\n    CHECK_CONTIGUOUS(p);\n    CHECK_CONTIGUOUS(grad);\n\n    if (X.device().type() == torch::DeviceType::CPU) {\n        return act4_backward_cpu(group_index, grad, X, p);\n\n    } else if (X.device().type() == torch::DeviceType::CUDA) {\n        return act4_backward_gpu(group_index, grad, X, p);\n    }\n\n    return {};\n}\n\n\ntorch::Tensor projector(int group_index, torch::Tensor X) {\n    CHECK_CONTIGUOUS(X);\n    \n    if (X.device().type() == torch::DeviceType::CPU) {\n        return orthogonal_projector_cpu(group_index, X);\n\n    } else if (X.device().type() == torch::DeviceType::CUDA) {\n        return orthogonal_projector_gpu(group_index, X);\n    }\n\n    return X;\n}\n\n\ntorch::Tensor as_matrix(int group_index, torch::Tensor X) {\n    CHECK_CONTIGUOUS(X);\n    \n    if (X.device().type() == torch::DeviceType::CPU) {\n        return as_matrix_forward_cpu(group_index, X);\n\n    } else if (X.device().type() == torch::DeviceType::CUDA) {\n        return as_matrix_forward_gpu(group_index, X);\n    }\n\n    return X;\n}\n\ntorch::Tensor Jinv(int group_index, torch::Tensor X, torch::Tensor a) {\n    CHECK_CONTIGUOUS(X);\n    CHECK_CONTIGUOUS(a);\n\n    if (X.device().type() == torch::DeviceType::CPU) {\n        return jleft_forward_cpu(group_index, X, a);\n\n    } else if (X.device().type() == torch::DeviceType::CUDA) {\n        return jleft_forward_gpu(group_index, X, a);\n    }\n\n    return a;\n}\n\n// {exp, log, inv, mul, adj, adjT, act, act4} forward/backward bindings\nPYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {\n  m.def(\"expm\", &expm, \"exp map forward\");\n  m.def(\"expm_backward\", &expm_backward, \"exp map backward\");\n\n  m.def(\"logm\", &logm, \"log map forward\");\n  m.def(\"logm_backward\", &logm_backward, \"log map backward\");\n\n  m.def(\"inv\", &inv, \"inverse operator\");\n  m.def(\"inv_backward\", &inv_backward, \"inverse operator backward\");\n\n  m.def(\"mul\", &mul, \"group operator\");\n  m.def(\"mul_backward\", &mul_backward, \"group operator backward\");\n\n  m.def(\"adj\", &adj, \"adjoint operator\");\n  m.def(\"adj_backward\", &adj_backward, \"adjoint operator backward\");\n\n  m.def(\"adjT\", &adjT, \"transposed adjoint operator\");\n  m.def(\"adjT_backward\", &adjT_backward, \"transposed adjoint operator backward\");\n\n  m.def(\"act\", &act, \"action on point\");\n  m.def(\"act_backward\", &act_backward, \"action on point backward\");\n\n  m.def(\"act4\", &act4, \"action on homogeneous point\");\n  m.def(\"act4_backward\", &act4_backward, \"action on homogeneous point backward\");\n\n  // functions with no gradient\n  m.def(\"as_matrix\", &as_matrix, \"convert to matrix\");\n  m.def(\"projector\", &projector, \"orthogonal projection matrix\");\n  m.def(\"Jinv\", &Jinv, \"left inverse jacobian operator\");\n\n};\n\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/src/lietorch_cpu.cpp",
    "content": "\n#include \"lietorch_cpu.h\"\n#include <Eigen/Dense>\n\n#include <iostream>\n#include \"common.h\"\n#include \"dispatch.h\"\n\n#include \"so3.h\"\n#include \"rxso3.h\"\n#include \"se3.h\"\n#include \"sim3.h\"\n\n\ntemplate <typename Group, typename scalar_t>\nvoid exp_forward_kernel(const scalar_t* a_ptr, scalar_t* X_ptr, int batch_size) {\n    // exponential map forward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n    \n    at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n        for (int64_t i=start; i<end; i++) {\n            Tangent a(a_ptr + i*Group::K);\n            Eigen::Map<Data>(X_ptr + i*Group::N) = Group::Exp(a).data();\n        }\n    });\n}\n\ntemplate <typename Group, typename scalar_t>\nvoid exp_backward_kernel(const scalar_t* grad, const scalar_t* a_ptr, scalar_t* da, int batch_size) {\n    // exponential map backward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Grad = Eigen::Matrix<scalar_t,1,Group::K>;\n\n    at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n        for (int64_t i=start; i<end; i++) {\n            Tangent a(a_ptr + i*Group::K);\n            Grad dX(grad + i*Group::N);\n            Eigen::Map<Grad>(da + i*Group::K) = dX * Group::left_jacobian(a);\n        }\n    });\n}\n\ntemplate <typename Group, typename scalar_t>\nvoid log_forward_kernel(const scalar_t* X_ptr, scalar_t* a_ptr, int batch_size) {\n    // logarithm map forward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n\n    at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n        for (int64_t i=start; i<end; i++) {\n            Tangent a = Group(X_ptr + i*Group::N).Log();\n            Eigen::Map<Tangent>(a_ptr + i*Group::K) = a;\n        }\n    });\n}\n\ntemplate <typename Group, typename scalar_t>\nvoid log_backward_kernel(const scalar_t* grad, const scalar_t* X_ptr, scalar_t* dX, int batch_size) {\n    // logarithm map backward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Grad = Eigen::Matrix<scalar_t,1,Group::K>;\n\n    at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n        for (int64_t i=start; i<end; i++) {\n            Tangent a = Group(X_ptr + i*Group::N).Log();\n            Grad da(grad + i*Group::K);\n            Eigen::Map<Grad>(dX + i*Group::N) = da * Group::left_jacobian_inverse(a);\n        }\n    });\n}\n\ntemplate <typename Group, typename scalar_t>\nvoid inv_forward_kernel(const scalar_t* X_ptr, scalar_t* Y_ptr, int batch_size) {\n    // group inverse forward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n\n    at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n        for (int64_t i=start; i<end; i++) {\n            Group X(X_ptr + i*Group::N);\n            Eigen::Map<Data>(Y_ptr + i*Group::N) = X.inv().data();\n        }\n    });\n}\n\ntemplate <typename Group, typename scalar_t>\nvoid inv_backward_kernel(const scalar_t* grad, const scalar_t* X_ptr, scalar_t *dX, int batch_size) {\n    // group inverse backward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Grad = Eigen::Matrix<scalar_t,1,Group::K>;\n\n    at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n        for (int64_t i=start; i<end; i++) {\n            Group Y = Group(X_ptr + i*Group::N).inv();\n            Grad dY(grad + i*Group::N);\n            Eigen::Map<Grad>(dX + i*Group::N) = -dY * Y.Adj();\n        }\n    });\n}\n\ntemplate <typename Group, typename scalar_t>\nvoid mul_forward_kernel(const scalar_t* X_ptr, const scalar_t* Y_ptr, scalar_t* Z_ptr, int batch_size) {\n    // group multiplication forward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n\n    at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n        for (int64_t i=start; i<end; i++) {\n            Group Z = Group(X_ptr + i*Group::N) * Group(Y_ptr + i*Group::N);\n            Eigen::Map<Data>(Z_ptr + i*Group::N) = Z.data();\n        }\n    });\n}\n\ntemplate <class Group, typename scalar_t>\nvoid mul_backward_kernel(const scalar_t* grad, const scalar_t* X_ptr, const scalar_t* Y_ptr, scalar_t* dX, scalar_t* dY, int batch_size) {\n    // group multiplication backward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Grad = Eigen::Matrix<scalar_t,1,Group::K>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n\n    at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n        for (int64_t i=start; i<end; i++) {\n            Grad dZ(grad + i*Group::N);\n            Group X(X_ptr + i*Group::N);        \n            Eigen::Map<Grad>(dX + i*Group::N) = dZ;\n            Eigen::Map<Grad>(dY + i*Group::N) = dZ * X.Adj();\n        }\n    });\n}\n\ntemplate <typename Group, typename scalar_t>\nvoid adj_forward_kernel(const scalar_t* X_ptr, const scalar_t* a_ptr, scalar_t* b_ptr, int batch_size) {\n    // adjoint forward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n\n    at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n        for (int64_t i=start; i<end; i++) {\n            Group X(X_ptr + i*Group::N);\n            Tangent a(a_ptr + i*Group::K);\n            Eigen::Map<Tangent>(b_ptr + i*Group::K) = X.Adj(a);\n        }\n    });\n}\n\ntemplate <typename Group, typename scalar_t>\nvoid adj_backward_kernel(const scalar_t* grad, const scalar_t* X_ptr, const scalar_t* a_ptr, scalar_t* dX, scalar_t* da, int batch_size) {\n    // adjoint backward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Grad = Eigen::Matrix<scalar_t,1,Group::K>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n\n    at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n        for (int64_t i=start; i<end; i++) {\n            Group X(X_ptr + i*Group::N);\n            Grad db(grad + i*Group::K);\n\n            Tangent a(a_ptr + i*Group::K);\n            Tangent b = X.Adj() * a;\n\n            Eigen::Map<Grad>(da + i*Group::K) = db * X.Adj();\n            Eigen::Map<Grad>(dX + i*Group::N) = -db * Group::adj(b);\n        }\n    });\n}\n\ntemplate <typename Group, typename scalar_t>\nvoid adjT_forward_kernel(const scalar_t* X_ptr, const scalar_t* a_ptr, scalar_t* b_ptr, int batch_size) {\n    // adjoint forward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n\n    at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n        for (int64_t i=start; i<end; i++) {\n            Group X(X_ptr + i*Group::N);\n            Tangent a(a_ptr + i*Group::K);\n            Eigen::Map<Tangent>(b_ptr + i*Group::K) = X.AdjT(a);\n        }\n    });\n}\n\ntemplate <typename Group, typename scalar_t>\nvoid adjT_backward_kernel(const scalar_t* grad, const scalar_t* X_ptr, const scalar_t* a_ptr, scalar_t* dX, scalar_t* da, int batch_size) {\n    // adjoint backward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Grad = Eigen::Matrix<scalar_t,1,Group::K>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n\n    at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n        for (int64_t i=start; i<end; i++) {\n            Group X(X_ptr + i*Group::N);        \n            Tangent db(grad + i*Group::K);\n            Grad a(a_ptr + i*Group::K);\n\n            Eigen::Map<Tangent>(da + i*Group::K) = X.Adj(db);\n            Eigen::Map<Grad>(dX + i*Group::N) = -a * Group::adj(X.Adj(db));\n        }\n    });\n}\n\n\ntemplate <typename Group, typename scalar_t>\nvoid act_forward_kernel(const scalar_t* X_ptr, const scalar_t* p_ptr, scalar_t* q_ptr, int batch_size) {\n    // action on point forward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n    using Point = Eigen::Matrix<scalar_t,3,1>;\n\n    at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n        for (int64_t i=start; i<end; i++) {\n            Group X(X_ptr + i*Group::N);\n            Point p(p_ptr + i*3);\n            Eigen::Map<Point>(q_ptr + i*3) = X * p;\n        }\n    });\n}\n\ntemplate <typename Group, typename scalar_t>\nvoid act_backward_kernel(const scalar_t* grad, const scalar_t* X_ptr, const scalar_t* p_ptr, scalar_t* dX, scalar_t* dp, int batch_size) {\n    // adjoint backward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Grad = Eigen::Matrix<scalar_t,1,Group::K>;\n    using Point = Eigen::Matrix<scalar_t,3,1>;\n    using PointGrad = Eigen::Matrix<scalar_t,1,3>;\n    using Transformation = Eigen::Matrix<scalar_t,4,4>;\n\n    at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n        for (int64_t i=start; i<end; i++) {\n            Group X(X_ptr + i*Group::N);\n            Point p(p_ptr + i*3);\n            PointGrad dq(grad + i*3);\n\n            Eigen::Map<PointGrad>(dp + i*3) = dq * X.Matrix().template block<3,3>(0,0);\n            Eigen::Map<Grad>(dX + i*Group::N) = dq * Group::act_jacobian(X*p);\n        }\n    });\n}\n\n\n// template <typename Group, typename scalar_t>\n// void tovec_backward_kernel(const scalar_t* grad, const scalar_t* X_ptr, scalar_t* dX, int batch_size) {\n//     // group inverse forward kernel\n//     using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n//     using Grad = Eigen::Matrix<scalar_t,1,Group::N>;\n\n//     at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n//         for (int64_t i=start; i<end; i++) {\n//             Group X(X_ptr + i*Group::N);\n//             Grad g(grad + i*Group::N);\n//             Eigen::Map<Grad>(dX + i*Group::N) = g * X.vec_jacobian();\n//         }\n//     });\n// }\n\n// template <typename Group, typename scalar_t>\n// void fromvec_backward_kernel(const scalar_t* grad, const scalar_t* X_ptr, scalar_t* dX, int batch_size) {\n//     // group inverse forward kernel\n//     using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n//     using Grad = Eigen::Matrix<scalar_t,1,Group::N>;\n\n//     at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n//         for (int64_t i=start; i<end; i++) {\n//             Group X(X_ptr + i*Group::N);\n//             Grad g(grad + i*Group::N);\n//             Eigen::Map<Grad>(dX + i*Group::N) = g * X.vec_jacobian();\n//         }\n//     });\n// }\n\n\ntemplate <typename Group, typename scalar_t>\nvoid act4_forward_kernel(const scalar_t* X_ptr, const scalar_t* p_ptr, scalar_t* q_ptr, int batch_size) {\n    // action on homogeneous point forward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n    using Point = Eigen::Matrix<scalar_t,4,1>;\n\n    at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n        for (int64_t i=start; i<end; i++) {\n            Group X(X_ptr + i*Group::N);\n            Point p(p_ptr + i*4);\n            Eigen::Map<Point>(q_ptr + i*4) = X.act4(p);\n        }\n    });\n}\n\ntemplate <typename Group, typename scalar_t>\nvoid act4_backward_kernel(const scalar_t* grad, const scalar_t* X_ptr, const scalar_t* p_ptr, scalar_t* dX, scalar_t* dp, int batch_size) {\n    // action on homogeneous point backward kernel\n\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Grad = Eigen::Matrix<scalar_t,1,Group::K>;\n    using Point = Eigen::Matrix<scalar_t,4,1>;\n    using PointGrad = Eigen::Matrix<scalar_t,1,4>;\n    using Transformation = Eigen::Matrix<scalar_t,4,4>;\n\n    at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n        for (int64_t i=start; i<end; i++) {\n            Group X(X_ptr + i*Group::N);\n            Point p(p_ptr + i*4);\n            PointGrad dq(grad + i*4);\n\n            Eigen::Map<PointGrad>(dp + i*4) = dq * X.Matrix4x4();\n            const Point q = X.act4(p);\n            Eigen::Map<Grad>(dX + i*Group::N) = dq * Group::act4_jacobian(q);\n        }\n    });\n}\n\ntemplate <typename Group, typename scalar_t>\nvoid as_matrix_forward_kernel(const scalar_t* X_ptr, scalar_t* T_ptr, int batch_size) {\n    // group inverse forward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n    using Matrix4 = Eigen::Matrix<scalar_t,4,4,Eigen::RowMajor>;\n\n    at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n        for (int64_t i=start; i<end; i++) {\n            Group X(X_ptr + i*Group::N);\n            Eigen::Map<Matrix4>(T_ptr + i*16) = X.Matrix4x4();\n        }\n    });\n}\n\ntemplate <typename Group, typename scalar_t>\nvoid orthogonal_projector_kernel(const scalar_t* X_ptr, scalar_t* P_ptr, int batch_size) {\n    // group inverse forward kernel\n    using Proj = Eigen::Matrix<scalar_t,Group::N,Group::N,Eigen::RowMajor>;\n    at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n        for (int64_t i=start; i<end; i++) {\n            Group X(X_ptr + i*Group::N);\n            Eigen::Map<Proj>(P_ptr + i*Group::N*Group::N) = X.orthogonal_projector();\n        }\n    });\n}\n\ntemplate <typename Group, typename scalar_t>\nvoid jleft_forward_kernel(const scalar_t* X_ptr, const scalar_t* a_ptr, scalar_t* b_ptr, int batch_size) {\n    // left-jacobian inverse action\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n\n    at::parallel_for(0, batch_size, 1, [&](int64_t start, int64_t end) {\n        for (int64_t i=start; i<end; i++) {\n            Group X(X_ptr + i*Group::N);\n            Tangent a(a_ptr + i*Group::K);\n            Tangent b = Group::left_jacobian_inverse(X.Log()) * a;\n            Eigen::Map<Tangent>(b_ptr + i*Group::K) = b;\n        }\n    });\n}\n\n// unary operations\n\ntorch::Tensor exp_forward_cpu(int group_id, torch::Tensor a) {\n    int batch_size = a.size(0);\n    torch::Tensor X;\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, a.type(), \"exp_forward_kernel\", ([&] {\n        X = torch::zeros({batch_size, group_t::N}, a.options());\n        exp_forward_kernel<group_t, scalar_t>(\n            a.data_ptr<scalar_t>(), \n            X.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return X;\n}\n\nstd::vector<torch::Tensor> exp_backward_cpu(int group_id, torch::Tensor grad, torch::Tensor a) {\n    int batch_size = a.size(0);\n    torch::Tensor da = torch::zeros(a.sizes(), grad.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, a.type(), \"exp_backward_kernel\", ([&] {\n        exp_backward_kernel<group_t, scalar_t>(\n            grad.data_ptr<scalar_t>(), \n            a.data_ptr<scalar_t>(), \n            da.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return {da};\n}\n\ntorch::Tensor log_forward_cpu(int group_id, torch::Tensor X) {\n    int batch_size = X.size(0);\n    torch::Tensor a;\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"log_forward_kernel\", ([&] {\n        a = torch::zeros({batch_size, group_t::K}, X.options());\n        log_forward_kernel<group_t, scalar_t>(\n            X.data_ptr<scalar_t>(), \n            a.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return a;\n}\n\nstd::vector<torch::Tensor> log_backward_cpu(int group_id, torch::Tensor grad, torch::Tensor X) {\n    int batch_size = X.size(0);\n    torch::Tensor dX = torch::zeros(X.sizes(), grad.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"log_backward_kernel\", ([&] {\n        log_backward_kernel<group_t, scalar_t>(\n            grad.data_ptr<scalar_t>(), \n            X.data_ptr<scalar_t>(), \n            dX.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return {dX};\n}\n\ntorch::Tensor inv_forward_cpu(int group_id, torch::Tensor X) {\n    int batch_size = X.size(0);\n    torch::Tensor Y = torch::zeros_like(X);\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"inv_forward_kernel\", ([&] {\n        inv_forward_kernel<group_t, scalar_t>(\n            X.data_ptr<scalar_t>(), \n            Y.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return Y;\n}\n\nstd::vector<torch::Tensor> inv_backward_cpu(int group_id, torch::Tensor grad, torch::Tensor X) {\n    int batch_size = X.size(0);\n    torch::Tensor dX = torch::zeros(X.sizes(), grad.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"inv_backward_kernel\", ([&] {\n        inv_backward_kernel<group_t, scalar_t>(\n            grad.data_ptr<scalar_t>(), \n            X.data_ptr<scalar_t>(), \n            dX.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return {dX};\n}\n\n// binary operations\ntorch::Tensor mul_forward_cpu(int group_id, torch::Tensor X, torch::Tensor Y) {\n    int batch_size = X.size(0);\n    torch::Tensor Z = torch::zeros_like(X);\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"mul_forward_kernel\", ([&] {\n        mul_forward_kernel<group_t, scalar_t>(\n            X.data_ptr<scalar_t>(), \n            Y.data_ptr<scalar_t>(), \n            Z.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return Z;\n}\n\nstd::vector<torch::Tensor> mul_backward_cpu(int group_id, torch::Tensor grad, torch::Tensor X, torch::Tensor Y) {\n    int batch_size = X.size(0);\n    torch::Tensor dX = torch::zeros(X.sizes(), grad.options());\n    torch::Tensor dY = torch::zeros(Y.sizes(), grad.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"mul_backward_kernel\", ([&] {\n        mul_backward_kernel<group_t, scalar_t>(\n            grad.data_ptr<scalar_t>(), \n            X.data_ptr<scalar_t>(), \n            Y.data_ptr<scalar_t>(), \n            dX.data_ptr<scalar_t>(), \n            dY.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return {dX, dY};\n}\n\ntorch::Tensor adj_forward_cpu(int group_id, torch::Tensor X, torch::Tensor a) {\n    int batch_size = X.size(0);\n    torch::Tensor b = torch::zeros(a.sizes(), a.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"adj_forward_kernel\", ([&] {\n        adj_forward_kernel<group_t, scalar_t>(\n            X.data_ptr<scalar_t>(), \n            a.data_ptr<scalar_t>(), \n            b.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return b;\n}\n\nstd::vector<torch::Tensor> adj_backward_cpu(int group_id, torch::Tensor grad, torch::Tensor X, torch::Tensor a) {\n    int batch_size = X.size(0);\n    torch::Tensor dX = torch::zeros(X.sizes(), grad.options());\n    torch::Tensor da = torch::zeros(a.sizes(), grad.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"adj_backward_kernel\", ([&] {\n        adj_backward_kernel<group_t, scalar_t>(\n            grad.data_ptr<scalar_t>(), \n            X.data_ptr<scalar_t>(), \n            a.data_ptr<scalar_t>(), \n            dX.data_ptr<scalar_t>(), \n            da.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return {dX, da};\n}\n\n\ntorch::Tensor adjT_forward_cpu(int group_id, torch::Tensor X, torch::Tensor a) {\n    int batch_size = X.size(0);\n    torch::Tensor b = torch::zeros(a.sizes(), a.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"adjT_forward_kernel\", ([&] {\n        adjT_forward_kernel<group_t, scalar_t>(\n            X.data_ptr<scalar_t>(), \n            a.data_ptr<scalar_t>(), \n            b.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return b;\n}\n\nstd::vector<torch::Tensor> adjT_backward_cpu(int group_id, torch::Tensor grad, torch::Tensor X, torch::Tensor a) {\n    int batch_size = X.size(0);\n    torch::Tensor dX = torch::zeros(X.sizes(), grad.options());\n    torch::Tensor da = torch::zeros(a.sizes(), grad.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"adjT_backward_kernel\", ([&] {\n        adjT_backward_kernel<group_t, scalar_t>(\n            grad.data_ptr<scalar_t>(), \n            X.data_ptr<scalar_t>(), \n            a.data_ptr<scalar_t>(), \n            dX.data_ptr<scalar_t>(), \n            da.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return {dX, da};\n}\n\n\ntorch::Tensor act_forward_cpu(int group_id, torch::Tensor X, torch::Tensor p) {\n    int batch_size = X.size(0);\n    torch::Tensor q = torch::zeros(p.sizes(), p.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"act_forward_kernel\", ([&] {\n        act_forward_kernel<group_t, scalar_t>(\n            X.data_ptr<scalar_t>(), \n            p.data_ptr<scalar_t>(), \n            q.data_ptr<scalar_t>(),\n            batch_size);\n    }));\n\n    return q;\n}\n\nstd::vector<torch::Tensor> act_backward_cpu(int group_id, torch::Tensor grad, torch::Tensor X, torch::Tensor p) {\n    int batch_size = X.size(0);\n    torch::Tensor dX = torch::zeros(X.sizes(), grad.options());\n    torch::Tensor dp = torch::zeros(p.sizes(), grad.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"act_backward_kernel\", ([&] {\n        act_backward_kernel<group_t, scalar_t>(\n            grad.data_ptr<scalar_t>(), \n            X.data_ptr<scalar_t>(), \n            p.data_ptr<scalar_t>(), \n            dX.data_ptr<scalar_t>(), \n            dp.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return {dX, dp};\n}\n\n\ntorch::Tensor act4_forward_cpu(int group_id, torch::Tensor X, torch::Tensor p) {\n    int batch_size = X.size(0);\n    torch::Tensor q = torch::zeros(p.sizes(), p.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"act4_forward_kernel\", ([&] {\n        act4_forward_kernel<group_t, scalar_t>(\n            X.data_ptr<scalar_t>(), \n            p.data_ptr<scalar_t>(), \n            q.data_ptr<scalar_t>(),\n            batch_size);\n    }));\n\n    return q;\n}\n\nstd::vector<torch::Tensor> act4_backward_cpu(int group_id, torch::Tensor grad, torch::Tensor X, torch::Tensor p) {\n    int batch_size = X.size(0);\n    torch::Tensor dX = torch::zeros(X.sizes(), grad.options());\n    torch::Tensor dp = torch::zeros(p.sizes(), grad.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"act4_backward_kernel\", ([&] {\n        act4_backward_kernel<group_t, scalar_t>(\n            grad.data_ptr<scalar_t>(), \n            X.data_ptr<scalar_t>(), \n            p.data_ptr<scalar_t>(), \n            dX.data_ptr<scalar_t>(), \n            dp.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return {dX, dp};\n}\n\n\ntorch::Tensor as_matrix_forward_cpu(int group_id, torch::Tensor X) {\n    int batch_size = X.size(0);\n    torch::Tensor T4x4 = torch::zeros({X.size(0), 4, 4}, X.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"as_matrix_forward_kernel\", ([&] {\n        as_matrix_forward_kernel<group_t, scalar_t>(\n            X.data_ptr<scalar_t>(), \n            T4x4.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return T4x4;\n}\n\n\ntorch::Tensor orthogonal_projector_cpu(int group_id, torch::Tensor X) {\n    int batch_size = X.size(0);\n    torch::Tensor P;\n    \n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"orthogonal_projector_kernel\", ([&] {\n        P = torch::zeros({X.size(0), group_t::N, group_t::N}, X.options());\n        orthogonal_projector_kernel<group_t, scalar_t>(X.data_ptr<scalar_t>(), P.data_ptr<scalar_t>(), batch_size);\n    }));\n\n    return P;\n}\n\n\n\ntorch::Tensor jleft_forward_cpu(int group_id, torch::Tensor X, torch::Tensor a) {\n    int batch_size = X.size(0);\n    torch::Tensor b = torch::zeros(a.sizes(), a.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"jleft_forward_kernel\", ([&] {\n        jleft_forward_kernel<group_t, scalar_t>(\n            X.data_ptr<scalar_t>(), \n            a.data_ptr<scalar_t>(), \n            b.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return b;\n}"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/lietorch/src/lietorch_gpu.cu",
    "content": "\n#include \"lietorch_gpu.h\"\n#include <Eigen/Dense>\n\n#include \"common.h\"\n#include \"dispatch.h\"\n\n#include \"so3.h\"\n#include \"rxso3.h\"\n#include \"se3.h\"\n#include \"sim3.h\"\n\n#define GPU_1D_KERNEL_LOOP(i, n) \\\n  for (size_t i = blockIdx.x * blockDim.x + threadIdx.x; i<n; i += blockDim.x * gridDim.x)\n\n#define NUM_THREADS 256\n#define NUM_BLOCKS(batch_size) ((batch_size + NUM_THREADS - 1) / NUM_THREADS)\n\n\ntemplate <typename Group, typename scalar_t>\n__global__ void exp_forward_kernel(const scalar_t* a_ptr, scalar_t* X_ptr, int num_threads) {\n    // exponential map forward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n    \n    GPU_1D_KERNEL_LOOP(i, num_threads) {\n        Tangent a(a_ptr + i*Group::K);\n        Eigen::Map<Data>(X_ptr + i*Group::N) = Group::Exp(a).data();\n    }\n}\n\ntemplate <typename Group, typename scalar_t>\n__global__ void exp_backward_kernel(const scalar_t* grad, const scalar_t* a_ptr, scalar_t* da, int num_threads) {\n    // exponential map backward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Grad = Eigen::Matrix<scalar_t,1,Group::K>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n\n    GPU_1D_KERNEL_LOOP(i, num_threads) {\n        Tangent a(a_ptr + i*Group::K);\n        Grad dX(grad + i*Group::N);\n        Eigen::Map<Grad>(da + i*Group::K) = dX * Group::left_jacobian(a);\n    }\n}\n\ntemplate <typename Group, typename scalar_t>\n__global__ void log_forward_kernel(const scalar_t* X_ptr, scalar_t* a_ptr, int num_threads) {\n    // logarithm map forward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n\n    GPU_1D_KERNEL_LOOP(i, num_threads) {\n        Tangent a = Group(X_ptr + i*Group::N).Log();\n        Eigen::Map<Tangent>(a_ptr + i*Group::K) = a;\n    }\n}\n\ntemplate <typename Group, typename scalar_t>\n__global__ void log_backward_kernel(const scalar_t* grad, const scalar_t* X_ptr, scalar_t* dX, int num_threads) {\n    // logarithm map backward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Grad = Eigen::Matrix<scalar_t,1,Group::K>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n\n    GPU_1D_KERNEL_LOOP(i, num_threads) {\n        Tangent a = Group(X_ptr + i*Group::N).Log();\n        Grad da(grad + i*Group::K);\n        Eigen::Map<Grad>(dX + i*Group::N) = da * Group::left_jacobian_inverse(a);\n    }\n}\n\ntemplate <typename Group, typename scalar_t>\n__global__ void inv_forward_kernel(const scalar_t* X_ptr, scalar_t* Y_ptr, int num_threads) {\n    // group inverse forward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n\n    GPU_1D_KERNEL_LOOP(i, num_threads) {\n        Group X(X_ptr + i*Group::N);\n        Eigen::Map<Data>(Y_ptr + i*Group::N) = X.inv().data();\n    }\n}\n\n\ntemplate <typename Group, typename scalar_t>\n__global__ void inv_backward_kernel(const scalar_t* grad, const scalar_t* X_ptr, scalar_t *dX, int num_threads) {\n    // group inverse backward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Grad = Eigen::Matrix<scalar_t,1,Group::K>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n\n    GPU_1D_KERNEL_LOOP(i, num_threads) {\n        Group Y = Group(X_ptr + i*Group::N).inv();\n        Grad dY(grad + i*Group::N);\n        Eigen::Map<Grad>(dX + i*Group::N) = -dY * Y.Adj();\n    }\n}\n\n\ntemplate <typename Group, typename scalar_t>\n__global__ void mul_forward_kernel(const scalar_t* X_ptr, const scalar_t* Y_ptr, scalar_t* Z_ptr, int num_threads) {\n    // group multiplication forward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n\n    GPU_1D_KERNEL_LOOP(i, num_threads) {\n        Group Z = Group(X_ptr + i*Group::N) * Group(Y_ptr + i*Group::N);\n        Eigen::Map<Data>(Z_ptr + i*Group::N) = Z.data();\n    }\n}\n\ntemplate <class Group, typename scalar_t>\n__global__ void mul_backward_kernel(const scalar_t* grad, const scalar_t* X_ptr, const scalar_t* Y_ptr, scalar_t* dX, scalar_t* dY, int num_threads) {\n    // group multiplication backward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Grad = Eigen::Matrix<scalar_t,1,Group::K>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n\n    GPU_1D_KERNEL_LOOP(i, num_threads) {\n        Grad dZ(grad + i*Group::N);\n        Group X(X_ptr + i*Group::N);        \n        Eigen::Map<Grad>(dX + i*Group::N) = dZ;\n        Eigen::Map<Grad>(dY + i*Group::N) = dZ * X.Adj();\n    }\n}\n\ntemplate <typename Group, typename scalar_t>\n__global__ void adj_forward_kernel(const scalar_t* X_ptr, const scalar_t* a_ptr, scalar_t* b_ptr, int num_threads) {\n    // adjoint forward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n\n    GPU_1D_KERNEL_LOOP(i, num_threads) {\n        Group X(X_ptr + i*Group::N);\n        Tangent a(a_ptr + i*Group::K);\n        Eigen::Map<Tangent>(b_ptr + i*Group::K) = X.Adj(a);\n    }\n}\n\ntemplate <typename Group, typename scalar_t>\n__global__ void adj_backward_kernel(const scalar_t* grad, const scalar_t* X_ptr, const scalar_t* a_ptr, scalar_t* dX, scalar_t* da, int num_threads) {\n    // adjoint backward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Grad = Eigen::Matrix<scalar_t,1,Group::K>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n\n    GPU_1D_KERNEL_LOOP(i, num_threads) {\n        Group X(X_ptr + i*Group::N);\n        Grad db(grad + i*Group::K);\n\n        Tangent a(a_ptr + i*Group::K);\n        Tangent b = X.Adj() * a;\n\n        Eigen::Map<Grad>(da + i*Group::K) = db * X.Adj();\n        Eigen::Map<Grad>(dX + i*Group::N) = -db * Group::adj(b);\n    }\n}\n\n\ntemplate <typename Group, typename scalar_t>\n__global__ void adjT_forward_kernel(const scalar_t* X_ptr, const scalar_t* a_ptr, scalar_t* b_ptr, int num_threads) {\n    // adjoint forward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n\n    GPU_1D_KERNEL_LOOP(i, num_threads) {\n        Group X(X_ptr + i*Group::N);\n        Tangent a(a_ptr + i*Group::K);\n        Eigen::Map<Tangent>(b_ptr + i*Group::K) = X.AdjT(a);\n    }\n}\n\ntemplate <typename Group, typename scalar_t>\n__global__ void adjT_backward_kernel(const scalar_t* grad, const scalar_t* X_ptr, const scalar_t* a_ptr, scalar_t* dX, scalar_t* da, int num_threads) {\n    // adjoint backward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Grad = Eigen::Matrix<scalar_t,1,Group::K>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n\n    GPU_1D_KERNEL_LOOP(i, num_threads) {\n        Group X(X_ptr + i*Group::N);        \n        Tangent db(grad + i*Group::K);\n        Grad a(a_ptr + i*Group::K);\n\n        Eigen::Map<Tangent>(da + i*Group::K) = X.Adj(db);\n        Eigen::Map<Grad>(dX + i*Group::N) = -a * Group::adj(X.Adj(db));\n    }\n}\n\ntemplate <typename Group, typename scalar_t>\n__global__ void act_forward_kernel(const scalar_t* X_ptr, const scalar_t* p_ptr, scalar_t* q_ptr, int num_threads) {\n    // action on point forward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n    using Point = Eigen::Matrix<scalar_t,3,1>;\n\n    GPU_1D_KERNEL_LOOP(i, num_threads) {\n        Group X(X_ptr + i*Group::N);\n        Point p(p_ptr + i*3);\n        Eigen::Map<Point>(q_ptr + i*3) = X * p;\n    }\n}\n\ntemplate <typename Group, typename scalar_t>\n__global__ void act_backward_kernel(const scalar_t* grad, const scalar_t* X_ptr, const scalar_t* p_ptr, scalar_t* dX, scalar_t* dp, int num_threads) {\n    // adjoint backward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Grad = Eigen::Matrix<scalar_t,1,Group::K>;\n    using Point = Eigen::Matrix<scalar_t,3,1>;\n    using PointGrad = Eigen::Matrix<scalar_t,1,3>;\n    using Transformation = Eigen::Matrix<scalar_t,4,4>;\n\n    GPU_1D_KERNEL_LOOP(i, num_threads) {\n        Group X(X_ptr + i*Group::N);\n        Point p(p_ptr + i*3);\n        PointGrad dq(grad + i*3);\n\n        Eigen::Map<PointGrad>(dp + i*3) = dq * X.Matrix4x4().block<3,3>(0,0);\n        Eigen::Map<Grad>(dX + i*Group::N) = dq * Group::act_jacobian(X*p);\n    }\n}\n\n\ntemplate <typename Group, typename scalar_t>\n__global__ void act4_forward_kernel(const scalar_t* X_ptr, const scalar_t* p_ptr, scalar_t* q_ptr, int num_threads) {\n    // action on point forward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n    using Point = Eigen::Matrix<scalar_t,4,1>;\n\n    GPU_1D_KERNEL_LOOP(i, num_threads) {\n        Group X(X_ptr + i*Group::N);\n        Point p(p_ptr + i*4);\n        Eigen::Map<Point>(q_ptr + i*4) = X.act4(p);\n    }\n}\n\ntemplate <typename Group, typename scalar_t>\n__global__ void act4_backward_kernel(const scalar_t* grad, const scalar_t* X_ptr, const scalar_t* p_ptr, scalar_t* dX, scalar_t* dp, int num_threads) {\n    // adjoint backward kernel\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Grad = Eigen::Matrix<scalar_t,1,Group::K>;\n    using Point = Eigen::Matrix<scalar_t,4,1>;\n    using PointGrad = Eigen::Matrix<scalar_t,1,4>;\n    using Transformation = Eigen::Matrix<scalar_t,4,4>;\n\n    GPU_1D_KERNEL_LOOP(i, num_threads) {\n        Group X(X_ptr + i*Group::N);\n        Point p(p_ptr + i*4);\n        PointGrad dq(grad + i*4);\n\n        Eigen::Map<PointGrad>(dp + i*4) = dq * X.Matrix4x4();\n        const Point q = X.act4(p);\n        Eigen::Map<Grad>(dX + i*Group::N) = dq * Group::act4_jacobian(q);\n    }\n}\n\ntemplate <typename Group, typename scalar_t>\n__global__ void as_matrix_forward_kernel(const scalar_t* X_ptr, scalar_t* T_ptr, int num_threads) {\n    // convert to 4x4 matrix representation\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n    using Matrix4 = Eigen::Matrix<scalar_t,4,4,Eigen::RowMajor>;\n\n    GPU_1D_KERNEL_LOOP(i, num_threads) {\n        Group X(X_ptr + i*Group::N);\n        Eigen::Map<Matrix4>(T_ptr + i*16) = X.Matrix4x4();\n    }\n}\n\ntemplate <typename Group, typename scalar_t>\n__global__ void orthogonal_projector_kernel(const scalar_t* X_ptr, scalar_t* P_ptr, int num_threads) {\n    // orthogonal projection matrix\n    using Proj = Eigen::Matrix<scalar_t,Group::N,Group::N,Eigen::RowMajor>;\n\n    GPU_1D_KERNEL_LOOP(i, num_threads) {\n        Group X(X_ptr + i*Group::N);\n        Eigen::Map<Proj>(P_ptr + i*Group::N*Group::N) = X.orthogonal_projector();\n    }\n}\n\ntemplate <typename Group, typename scalar_t>\n__global__ void jleft_forward_kernel(const scalar_t* X_ptr, const scalar_t* a_ptr, scalar_t* b_ptr, int num_threads) {\n    // left jacobian inverse action\n    using Tangent = Eigen::Matrix<scalar_t,Group::K,1>;\n    using Data = Eigen::Matrix<scalar_t,Group::N,1>;\n\n    GPU_1D_KERNEL_LOOP(i, num_threads) {\n        Group X(X_ptr + i*Group::N);\n        Tangent a(a_ptr + i*Group::K);\n        Tangent b = Group::left_jacobian_inverse(X.Log()) * a;\n        Eigen::Map<Tangent>(b_ptr + i*Group::K) = b;\n    }\n}\n\n// unary operations\n\ntorch::Tensor exp_forward_gpu(int group_id, torch::Tensor a) {\n    int batch_size = a.size(0);\n    torch::Tensor X;\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, a.type(), \"exp_forward_kernel\", ([&] {\n        X = torch::zeros({batch_size, group_t::N}, a.options());\n        exp_forward_kernel<group_t, scalar_t><<<NUM_BLOCKS(batch_size), NUM_THREADS>>>(\n            a.data_ptr<scalar_t>(), \n            X.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return X;\n}\n\nstd::vector<torch::Tensor> exp_backward_gpu(int group_id, torch::Tensor grad, torch::Tensor a) {\n    int batch_size = a.size(0);\n    torch::Tensor da = torch::zeros(a.sizes(), grad.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, a.type(), \"exp_backward_kernel\", ([&] {\n        exp_backward_kernel<group_t, scalar_t><<<NUM_BLOCKS(batch_size), NUM_THREADS>>>(\n            grad.data_ptr<scalar_t>(), \n            a.data_ptr<scalar_t>(), \n            da.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return {da};\n}\n\ntorch::Tensor log_forward_gpu(int group_id, torch::Tensor X) {\n    int batch_size = X.size(0);\n    torch::Tensor a;\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"log_forward_kernel\", ([&] {\n        a = torch::zeros({batch_size, group_t::K}, X.options());\n        log_forward_kernel<group_t, scalar_t><<<NUM_BLOCKS(batch_size), NUM_THREADS>>>(\n            X.data_ptr<scalar_t>(), \n            a.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return a;\n}\n\nstd::vector<torch::Tensor> log_backward_gpu(int group_id, torch::Tensor grad, torch::Tensor X) {\n    int batch_size = X.size(0);\n    torch::Tensor dX = torch::zeros(X.sizes(), grad.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"log_backward_kernel\", ([&] {\n        log_backward_kernel<group_t, scalar_t><<<NUM_BLOCKS(batch_size), NUM_THREADS>>>(\n            grad.data_ptr<scalar_t>(), \n            X.data_ptr<scalar_t>(), \n            dX.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return {dX};\n}\n\ntorch::Tensor inv_forward_gpu(int group_id, torch::Tensor X) {\n    int batch_size = X.size(0);\n    torch::Tensor Y = torch::zeros_like(X);\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"inv_forward_kernel\", ([&] {\n        inv_forward_kernel<group_t, scalar_t><<<NUM_BLOCKS(batch_size), NUM_THREADS>>>(\n            X.data_ptr<scalar_t>(), \n            Y.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return Y;\n}\n\nstd::vector<torch::Tensor> inv_backward_gpu(int group_id, torch::Tensor grad, torch::Tensor X) {\n    int batch_size = X.size(0);\n    torch::Tensor dX = torch::zeros(X.sizes(), grad.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"inv_backward_kernel\", ([&] {\n        inv_backward_kernel<group_t, scalar_t><<<NUM_BLOCKS(batch_size), NUM_THREADS>>>(\n            grad.data_ptr<scalar_t>(), \n            X.data_ptr<scalar_t>(), \n            dX.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return {dX};\n}\n\n// binary operations\ntorch::Tensor mul_forward_gpu(int group_id, torch::Tensor X, torch::Tensor Y) {\n    int batch_size = X.size(0);\n    torch::Tensor Z = torch::zeros_like(X);\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"mul_forward_kernel\", ([&] {\n        mul_forward_kernel<group_t, scalar_t><<<NUM_BLOCKS(batch_size), NUM_THREADS>>>(\n            X.data_ptr<scalar_t>(), \n            Y.data_ptr<scalar_t>(), \n            Z.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return Z;\n}\n\nstd::vector<torch::Tensor> mul_backward_gpu(int group_id, torch::Tensor grad, torch::Tensor X, torch::Tensor Y) {\n    int batch_size = X.size(0);\n    torch::Tensor dX = torch::zeros(X.sizes(), grad.options());\n    torch::Tensor dY = torch::zeros(Y.sizes(), grad.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"mul_backward_kernel\", ([&] {\n        mul_backward_kernel<group_t, scalar_t><<<NUM_BLOCKS(batch_size), NUM_THREADS>>>(\n            grad.data_ptr<scalar_t>(), \n            X.data_ptr<scalar_t>(), \n            Y.data_ptr<scalar_t>(), \n            dX.data_ptr<scalar_t>(), \n            dY.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return {dX, dY};\n}\n\ntorch::Tensor adj_forward_gpu(int group_id, torch::Tensor X, torch::Tensor a) {\n    int batch_size = X.size(0);\n    torch::Tensor b = torch::zeros(a.sizes(), a.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"adj_forward_kernel\", ([&] {\n        adj_forward_kernel<group_t, scalar_t><<<NUM_BLOCKS(batch_size), NUM_THREADS>>>(\n            X.data_ptr<scalar_t>(), \n            a.data_ptr<scalar_t>(), \n            b.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return b;\n}\n\nstd::vector<torch::Tensor> adj_backward_gpu(int group_id, torch::Tensor grad, torch::Tensor X, torch::Tensor a) {\n    int batch_size = X.size(0);\n    torch::Tensor dX = torch::zeros(X.sizes(), grad.options());\n    torch::Tensor da = torch::zeros(a.sizes(), grad.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"adj_backward_kernel\", ([&] {\n        adj_backward_kernel<group_t, scalar_t><<<NUM_BLOCKS(batch_size), NUM_THREADS>>>(\n            grad.data_ptr<scalar_t>(), \n            X.data_ptr<scalar_t>(), \n            a.data_ptr<scalar_t>(), \n            dX.data_ptr<scalar_t>(), \n            da.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return {dX, da};\n}\n\n\ntorch::Tensor adjT_forward_gpu(int group_id, torch::Tensor X, torch::Tensor a) {\n    int batch_size = X.size(0);\n    torch::Tensor b = torch::zeros(a.sizes(), a.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"adjT_forward_kernel\", ([&] {\n        adjT_forward_kernel<group_t, scalar_t><<<NUM_BLOCKS(batch_size), NUM_THREADS>>>(\n            X.data_ptr<scalar_t>(), \n            a.data_ptr<scalar_t>(), \n            b.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return b;\n}\n\nstd::vector<torch::Tensor> adjT_backward_gpu(int group_id, torch::Tensor grad, torch::Tensor X, torch::Tensor a) {\n    int batch_size = X.size(0);\n    torch::Tensor dX = torch::zeros(X.sizes(), grad.options());\n    torch::Tensor da = torch::zeros(a.sizes(), grad.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"adjT_backward_kernel\", ([&] {\n        adjT_backward_kernel<group_t, scalar_t><<<NUM_BLOCKS(batch_size), NUM_THREADS>>>(\n            grad.data_ptr<scalar_t>(), \n            X.data_ptr<scalar_t>(), \n            a.data_ptr<scalar_t>(), \n            dX.data_ptr<scalar_t>(), \n            da.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return {dX, da};\n}\n\n\n\ntorch::Tensor act_forward_gpu(int group_id, torch::Tensor X, torch::Tensor p) {\n    int batch_size = X.size(0);\n    torch::Tensor q = torch::zeros(p.sizes(), p.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"act_forward_kernel\", ([&] {\n        act_forward_kernel<group_t, scalar_t><<<NUM_BLOCKS(batch_size), NUM_THREADS>>>(\n            X.data_ptr<scalar_t>(), \n            p.data_ptr<scalar_t>(), \n            q.data_ptr<scalar_t>(),\n            batch_size);\n    }));\n\n    return q;\n}\n\nstd::vector<torch::Tensor> act_backward_gpu(int group_id, torch::Tensor grad, torch::Tensor X, torch::Tensor p) {\n    int batch_size = X.size(0);\n    torch::Tensor dX = torch::zeros(X.sizes(), grad.options());\n    torch::Tensor dp = torch::zeros(p.sizes(), grad.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"act_backward_kernel\", ([&] {\n        act_backward_kernel<group_t, scalar_t><<<NUM_BLOCKS(batch_size), NUM_THREADS>>>(\n            grad.data_ptr<scalar_t>(), \n            X.data_ptr<scalar_t>(), \n            p.data_ptr<scalar_t>(), \n            dX.data_ptr<scalar_t>(), \n            dp.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return {dX, dp};\n}\n\ntorch::Tensor act4_forward_gpu(int group_id, torch::Tensor X, torch::Tensor p) {\n    int batch_size = X.size(0);\n    torch::Tensor q = torch::zeros(p.sizes(), p.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"act4_forward_kernel\", ([&] {\n        act4_forward_kernel<group_t, scalar_t><<<NUM_BLOCKS(batch_size), NUM_THREADS>>>(\n            X.data_ptr<scalar_t>(), \n            p.data_ptr<scalar_t>(), \n            q.data_ptr<scalar_t>(),\n            batch_size);\n    }));\n\n    return q;\n}\n\nstd::vector<torch::Tensor> act4_backward_gpu(int group_id, torch::Tensor grad, torch::Tensor X, torch::Tensor p) {\n    int batch_size = X.size(0);\n    torch::Tensor dX = torch::zeros(X.sizes(), grad.options());\n    torch::Tensor dp = torch::zeros(p.sizes(), grad.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"act4_backward_kernel\", ([&] {\n        act4_backward_kernel<group_t, scalar_t><<<NUM_BLOCKS(batch_size), NUM_THREADS>>>(\n            grad.data_ptr<scalar_t>(), \n            X.data_ptr<scalar_t>(), \n            p.data_ptr<scalar_t>(), \n            dX.data_ptr<scalar_t>(), \n            dp.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return {dX, dp};\n}\n\n\ntorch::Tensor as_matrix_forward_gpu(int group_id, torch::Tensor X) {\n    int batch_size = X.size(0);\n    torch::Tensor T4x4 = torch::zeros({X.size(0), 4, 4}, X.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"as_matrix_forward_kernel\", ([&] {\n        as_matrix_forward_kernel<group_t, scalar_t><<<NUM_BLOCKS(batch_size), NUM_THREADS>>>(\n            X.data_ptr<scalar_t>(), \n            T4x4.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return T4x4;\n}\n\n\ntorch::Tensor orthogonal_projector_gpu(int group_id, torch::Tensor X) {\n    int batch_size = X.size(0);\n    torch::Tensor P;\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"orthogonal_projector_kernel\", ([&] {\n        P = torch::zeros({X.size(0), group_t::N, group_t::N}, X.options());\n        orthogonal_projector_kernel<group_t, scalar_t><<<NUM_BLOCKS(batch_size), NUM_THREADS>>>(\n            X.data_ptr<scalar_t>(), \n            P.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return P;\n}\n\n\ntorch::Tensor jleft_forward_gpu(int group_id, torch::Tensor X, torch::Tensor a) {\n    int batch_size = X.size(0);\n    torch::Tensor b = torch::zeros(a.sizes(), a.options());\n\n    DISPATCH_GROUP_AND_FLOATING_TYPES(group_id, X.type(), \"jleft_forward_kernel\", ([&] {\n        jleft_forward_kernel<group_t, scalar_t><<<NUM_BLOCKS(batch_size), NUM_THREADS>>>(\n            X.data_ptr<scalar_t>(), \n            a.data_ptr<scalar_t>(), \n            b.data_ptr<scalar_t>(), \n            batch_size);\n    }));\n\n    return b;\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/run_tests.sh",
    "content": "#!/bin/bash\n\npython lietorch/run_tests.py\n"
  },
  {
    "path": "VO_Module/thirdparty/lietorch/setup.py",
    "content": "from setuptools import setup\nfrom torch.utils.cpp_extension import BuildExtension, CUDAExtension\n\nimport os.path as osp\n\n\nROOT = osp.dirname(osp.abspath(__file__))\n\nsetup(\n    name='lietorch',\n    version='0.2',\n    description='Lie Groups for PyTorch',\n    author='teedrz',\n    packages=['lietorch'],\n    ext_modules=[\n        CUDAExtension('lietorch_backends', \n            include_dirs=[\n                osp.join(ROOT, 'lietorch/include'), \n                osp.join(ROOT, 'eigen')],\n            sources=[\n                'lietorch/src/lietorch.cpp', \n                'lietorch/src/lietorch_gpu.cu',\n                'lietorch/src/lietorch_cpu.cpp'],\n            extra_compile_args={\n                'cxx': ['-O2'], \n                'nvcc': ['-O2',\n                    '-gencode=arch=compute_60,code=sm_60', \n                    '-gencode=arch=compute_61,code=sm_61', \n                    '-gencode=arch=compute_70,code=sm_70', \n                    '-gencode=arch=compute_75,code=sm_75',\n                    '-gencode=arch=compute_75,code=compute_75',\n                    \n                ]\n            }),\n\n        CUDAExtension('lietorch_extras', \n            sources=[\n                'lietorch/extras/altcorr_kernel.cu',\n                'lietorch/extras/corr_index_kernel.cu',\n                'lietorch/extras/se3_builder.cu',\n                'lietorch/extras/se3_inplace_builder.cu',\n                'lietorch/extras/se3_solver.cu',\n                'lietorch/extras/extras.cpp',\n            ],\n            extra_compile_args={\n                'cxx': ['-O2'], \n                'nvcc': ['-O2',\n                    '-gencode=arch=compute_60,code=sm_60', \n                    '-gencode=arch=compute_61,code=sm_61', \n                    '-gencode=arch=compute_70,code=sm_70', \n                    '-gencode=arch=compute_75,code=sm_75',\n                    '-gencode=arch=compute_75,code=compute_75',\n                    \n                ]\n            }),\n    ],\n    cmdclass={ 'build_ext': BuildExtension }\n)\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/tartanair_tools/LICENSE",
    "content": "Copyright (c) 2020, Carnegie Mellon University\nAll rights reserved.\n\nRedistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:\n\n1. Redistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.\n\n2. Redistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.\n\n3. Neither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.\n\nTHIS 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 THE COPYRIGHT HOLDER OR 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."
  },
  {
    "path": "VO_Module/thirdparty/tartanair_tools/README.md",
    "content": "# TartanAir dataset: AirSim Simulation Dataset for Simultaneous Localization and Mapping\nThis repository provides sample code and scripts for accessing the training and testing data, as well as evaluation tools. Please refer to [TartanAir](http://theairlab.org/tartanair-dataset) for more information about the dataset. \nYou can also reach out to contributors on the associated [AirSim GitHub](https://github.com/microsoft/AirSim).\n\nThis dataset was used to train the first generalizable learning-based visual odometry [TartanVO](http://theairlab.org/tartanvo/), which achieved better performance than geometry-based VO methods in challenging cases. Please check out the [paper](https://arxiv.org/pdf/2011.00359.pdf) and published [TartanVO code](https://github.com/castacks/tartanvo). \n\n## Download the training data\n\nThe data is divided into two levels (Easy and Hard) in terms of the motion patterns. It is organized in trajectory folders. You can download data from different cameras (left or right), with different data types (RGB, depth, segmentation, camera pose, and flow). Please see [data type](data_type.md) page for the camera intrinsics, extrinsics and other information. \n\n\n<p style=\"color:red\"> <b> !! NOTE: The size of all the data is up to 3TB! It could take days to download. We also added the option to use the dataset directly on Azure without requiring a download. Please select the data type you really need before download. You can also go to \n<a href=http://theairlab.org/tartanair-dataset>TartanAir</a> \nto download the sample files for a better understanding of the data types. </b> </p>\n\n###  Data directory structure\n\n```\nROOT\n|\n--- ENV_NAME_0                             # environment folder\n|       |\n|       ---- Easy                          # difficulty level\n|       |      |\n|       |      ---- P000                   # trajectory folder\n|       |      |      |\n|       |      |      +--- depth_left      # 000000_left_depth.npy - 000xxx_left_depth.npy\n|       |      |      +--- depth_right     # 000000_right_depth.npy - 000xxx_right_depth.npy\n|       |      |      +--- flow            # 000000_000001_flow/mask.npy - 000xxx_000xxx_flow/mask.npy\n|       |      |      +--- image_left      # 000000_left.png - 000xxx_left.png \n|       |      |      +--- image_right     # 000000_right.png - 000xxx_right.png \n|       |      |      +--- seg_left        # 000000_left_seg.npy - 000xxx_left_seg.npy\n|       |      |      +--- seg_right       # 000000_right_seg.npy - 000xxx_right_seg.npy\n|       |      |      ---- pose_left.txt \n|       |      |      ---- pose_right.txt\n|       |      |  \n|       |      +--- P001\n|       |      .\n|       |      .\n|       |      |\n|       |      +--- P00K\n|       |\n|       +--- Hard\n|\n+-- ENV_NAME_1\n.\n.\n|\n+-- ENV_NAME_N\n```\n\n### Download data to your local machine\n\nWe provide a python script `download_training.py` for the data downloading. You can also take look at the [URL list](download_training_zipfiles.txt) to download the spesific files you want. \n\n* Specify an output directory\n\n  --output-dir OUTPUTDIR\n\n* Select file type:\n\n  --rgb\n\n  --depth\n\n  --seg\n\n  --flow\n\n* Select difficulty level:\n  \n  --only-hard\n\n  --only-easy\n\n  [NO TAG]: both 'hard' and 'easy' levels\n\n* Select camera:\n  \n  --only-left\n\n  --only-right\n\n  [NO TAG]: both 'left' and 'right' cameras\n\n* Select flow type when --flow is set:\n  \n  --only-flow\n\n  --only-mask\n\n  [NO TAG]: both 'flow' and 'mask' files\n\nFor example, download all the RGB images from the left camera:\n\n```\npython download_training.py --output-dir OUTPUTDIR --rgb --only-left\n```\n\nDownload all the depth data from both cameras in hard level: \n\n```\npython download_training.py --output-dir OUTPUTDIR --depth --only-hard\n```\n\nDownload all optical flow data without flow-mask:\n\n```\npython download_training.py --output-dir OUTPUTDIR --flow --only-flow\n```\n\nDownload all the files in the dataset (could be very slow due to the large size):\n\n```\npython download_training.py --output-dir OUTPUTDIR --rgb --depth --seg --flow\n```\n\n---\n**NOTE**\n\nWe found that using AzCopy, which is a tool provided by MicroSoft, is much faster than directly downloading by the URLs. Please try the following steps if you want to accelerate the downloading process. \n\n1. Download the [AzCopy](https://docs.microsoft.com/en-us/azure/storage/common/storage-use-azcopy-v10) and put the executable to your system path. \n\n2. Run the above commands with a --azcopy tag. \n\n---\n\n### Access the data using Azure virtual machine\n\nYet another way to access the data is to use an Azure virtual machine. In this way, you don't have to download the data to your local machine. You can use [Azure SDKs](https://github.com/Azure/azure-sdk-for-python) to access the data on the cloud. [Here](TartanAir_Sample.ipynb) is a sample notebook for accessing and visualizing the data. **NOTE: This sample notebook can only be used on Azure. To download the data to your local machine, please refer to the download instructions [here](https://github.com/castacks/tartanair_tools#download-data-to-your-local-machine) or the [dataset website](http://theairlab.org/tartanair-dataset) for the sample data.**\n\n## Download the testing data for the CVPR Visual SLAM challenge\n\nYou can click the download links below. In Linux system, you can also run the following command to download all the files: \n```\nwget -r -i download_cvpr_slam_test.txt\n``` \n\n* [Monocular track](https://tartanair.blob.core.windows.net/tartanair-testing1/tartanair-test-mono-release.tar.gz) (Size: 7.65 GB)\n  \n  MD5 hash: 009b52e7d7b224ffb8a203db294ac9fb\n\n```\nmono\n|\n--- ME000                             # monocular easy trajectory 0 \n|       |\n|       ---- 000000.png               # RGB image 000000\n|       ---- 000001.png               # RGB image 000001\n|       .\n|       .\n|       ---- 000xxx.png               # RGB image 000xxx\n|\n+-- ME001                             # monocular easy trajectory 1 \n.\n.\n+-- ME007                             # monocular easy trajectory 7 \n|\n+-- MH000                             # monocular hard trajectory 0 \n.\n.\n|\n+-- MH007                             # monocular hard trajectory 7 \n```\n\n* [Stereo track](https://tartanair.blob.core.windows.net/tartanair-testing1/tartanair-test-stereo-release.tar.gz) (Size: 17.51 GB)\n\n  MD5 hash: 8a3363ff2013f147c9495d5bb161c48e\n\n```\nstereo\n|\n--- SE000                                 # stereo easy trajectory 0 \n|       |\n|       ---- image_left                   # left image folder\n|       |       |\n|       |       ---- 000000_left.png      # RGB left image 000000\n|       |       ---- 000001_left.png      # RGB left image 000001\n|       |       .\n|       |       .\n|       |       ---- 000xxx_left.png      # RGB left image 000xxx\n|       |\n|       ---- image_right                  # right image folder\n|               |\n|               ---- 000000_right.png     # RGB right image 000000\n|               ---- 000001_right.png     # RGB right image 000001\n|               .\n|               .\n|               ---- 000xxx_right.png     # RGB right image 000xxx\n|\n+-- SE001                                 # stereo easy trajectory 1 \n.\n.\n+-- SE007                                 # stereo easy trajectory 7 \n|\n+-- SH000                                 # stereo hard trajectory 0 \n.\n.\n|\n+-- SH007                                 # stereo hard trajectory 7 \n```\n\n* [Both monocular and stereo tracks](https://tartanair.blob.core.windows.net/tartanair-testing1/tartanair-test-release.tar.gz) (Size: 25.16 GB)\n\n  MD5 hash: ea176ca274135622cbf897c8fa462012 \n\nMore information about the [CVPR Visual SLAM challenge](https://sites.google.com/view/vislocslamcvpr2020/slam-challenge)\n\n* The [monocular track](https://www.aicrowd.com/challenges/tartanair-visual-slam-mono-track)\n\n* The [stereo track](https://www.aicrowd.com/challenges/tartanair-visual-slam-stereo-track)\n\nNow the CVPR challenge has completed, if you need the <b> ground truth poses </b> for the above testing trajectories, please send an email to [tartanair@hotmail.com](tartanair@hotmail.com). \n\n## Evaluation tools\n\nFollowing the [TUM dataset](https://vision.in.tum.de/data/datasets/rgbd-dataset) and the [KITTI dataset](http://www.cvlibs.net/datasets/kitti/eval_odometry.php), we adopt three metrics: absolute trajectory error (ATE), the relative pose error (RPE), a modified version of KITTI VO metric. \n\n[More details](https://vision.in.tum.de/data/datasets/rgbd-dataset/tools#evaluation)\n\nCheck out the sample code: \n```\ncd evaluation\npython tartanair_evaluator.py\n```\n\nNote that our camera poses are defined in the NED frame. That is to say, the x-axis is pointing to the camera's forward, the y-axis is pointing to the camera's right, the z-axis is pointing to the camera's downward. You can use the `cam2ned` function in the `evaluation/trajectory_transform.py` to transform the trajectory from the camera frame to the NED frame. \n\n## Paper\nMore technical details are available in the [TartanAir paper](https://arxiv.org/abs/2003.14338). Please cite this as: \n```\n@article{tartanair2020iros,\n  title =   {TartanAir: A Dataset to Push the Limits of Visual SLAM},\n  author =  {Wang, Wenshan and Zhu, Delong and Wang, Xiangwei and Hu, Yaoyu and Qiu, Yuheng and Wang, Chen and Hu, Yafei and Kapoor, Ashish and Scherer, Sebastian},\n  booktitle = {2020 IEEE/RSJ International Conference on Intelligent Robots and Systems (IROS)},\n  year =    {2020}\n}\n```\n\n## Contact \nEmail tartanair@hotmail.com if you have any questions about the data source. To post problems in the Github issue is also welcome. You can also reach out to contributors on the associated [GitHub](https://github.com/microsoft/AirSim).\n\n## License\n[This software is BSD licensed.](https://opensource.org/licenses/BSD-3-Clause)\n\nCopyright (c) 2020, Carnegie Mellon University All rights reserved.\n\nRedistribution and use in source and binary forms, with or without modification, are permitted provided that the following conditions are met:\n\nRedistributions of source code must retain the above copyright notice, this list of conditions and the following disclaimer.\n\nRedistributions in binary form must reproduce the above copyright notice, this list of conditions and the following disclaimer in the documentation and/or other materials provided with the distribution.\n\nNeither the name of the copyright holder nor the names of its contributors may be used to endorse or promote products derived from this software without specific prior written permission.\n\nTHIS 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 THE COPYRIGHT HOLDER OR 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.\n"
  },
  {
    "path": "VO_Module/thirdparty/tartanair_tools/TartanAir_Sample.ipynb",
    "content": "{\n \"cells\": [\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"## Demo notebook for accessing TartanAir data on Azure\\n\",\n    \"\\n\",\n    \"<p style=\\\"color:red\\\"> <b> !! NOTE: This sample file should only be used on Azure. To download the data to your local machine, please refer to the download instructions <a href=https://github.com/castacks/tartanair_tools#download-data>here</a> or the <a href=http://theairlab.org/tartanair-dataset>dataset website</a> for the sample data. </b> </p>\\n\",\n    \"\\n\",\n    \"This notebook provides an example of accessing TartanAir data from blobl storage on Azure, including: \\n\",\n    \"\\n\",\n    \"1) navigate the directories of different environments and trajectories. \\n\",\n    \"\\n\",\n    \"2) load the data into memory, and \\n\",\n    \"\\n\",\n    \"3) visualize the data. \\n\",\n    \"\\n\",\n    \"## Data directory structure\\n\",\n    \"```\\n\",\n    \"ROOT\\n\",\n    \"|\\n\",\n    \"--- ENV_NAME_0                             # environment folder\\n\",\n    \"|       |\\n\",\n    \"|       ---- Easy                          # difficulty level\\n\",\n    \"|       |      |\\n\",\n    \"|       |      ---- P000                   # trajectory folder\\n\",\n    \"|       |      |      |\\n\",\n    \"|       |      |      +--- depth_left      # 000000_left_depth.npy - 000xxx_left_depth.npy\\n\",\n    \"|       |      |      +--- depth_right     # 000000_right_depth.npy - 000xxx_right_depth.npy\\n\",\n    \"|       |      |      +--- flow            # 000000_000001_flow/mask.npy - 000xxx_000xxx_flow/mask.npy\\n\",\n    \"|       |      |      +--- image_left      # 000000_left.png - 000xxx_left.png \\n\",\n    \"|       |      |      +--- image_right     # 000000_right.png - 000xxx_right.png \\n\",\n    \"|       |      |      +--- seg_left        # 000000_left_seg.npy - 000xxx_left_seg.npy\\n\",\n    \"|       |      |      +--- seg_right       # 000000_right_seg.npy - 000xxx_right_seg.npy\\n\",\n    \"|       |      |      ---- pose_left.txt \\n\",\n    \"|       |      |      ---- pose_right.txt\\n\",\n    \"|       |      |  \\n\",\n    \"|       |      +--- P001\\n\",\n    \"|       |      .\\n\",\n    \"|       |      .\\n\",\n    \"|       |      |\\n\",\n    \"|       |      +--- P00K\\n\",\n    \"|       |\\n\",\n    \"|       +--- Hard\\n\",\n    \"|\\n\",\n    \"+-- ENV_NAME_1\\n\",\n    \".\\n\",\n    \".\\n\",\n    \"|\\n\",\n    \"+-- ENV_NAME_N\\n\",\n    \" ```\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"## Notebook dependencies\\n\",\n    \"`pip install numpy`\\n\",\n    \"\\n\",\n    \"`pip install azure-storage-blob`\\n\",\n    \"\\n\",\n    \"`pip install opencv-python`\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"## Imports and contrainer_client\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": 1,\n   \"metadata\": {},\n   \"outputs\": [],\n   \"source\": [\n    \"from azure.storage.blob import ContainerClient\\n\",\n    \"import numpy as np\\n\",\n    \"import io\\n\",\n    \"import cv2\\n\",\n    \"import time\\n\",\n    \"import matplotlib.pyplot as plt\\n\",\n    \"%matplotlib inline\\n\",\n    \"\\n\",\n    \"# Dataset website: http://theairlab.org/tartanair-dataset/\\n\",\n    \"account_url = 'https://tartanair.blob.core.windows.net/'\\n\",\n    \"container_name = 'tartanair-release1'\\n\",\n    \"\\n\",\n    \"container_client = ContainerClient(account_url=account_url, \\n\",\n    \"                                 container_name=container_name,\\n\",\n    \"                                 credential=None)\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"## List the environments and trajectories\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": 2,\n   \"metadata\": {},\n   \"outputs\": [],\n   \"source\": [\n    \"def get_environment_list():\\n\",\n    \"    '''\\n\",\n    \"    List all the environments shown in the root directory\\n\",\n    \"    '''\\n\",\n    \"    env_gen = container_client.walk_blobs()\\n\",\n    \"    envlist = []\\n\",\n    \"    for env in env_gen:\\n\",\n    \"        envlist.append(env.name)\\n\",\n    \"    return envlist\\n\",\n    \"\\n\",\n    \"def get_trajectory_list(envname, easy_hard = 'Easy'):\\n\",\n    \"    '''\\n\",\n    \"    List all the trajectory folders, which is named as 'P0XX'\\n\",\n    \"    '''\\n\",\n    \"    assert(easy_hard=='Easy' or easy_hard=='Hard')\\n\",\n    \"    traj_gen = container_client.walk_blobs(name_starts_with=envname + '/' + easy_hard+'/')\\n\",\n    \"    trajlist = []\\n\",\n    \"    for traj in traj_gen:\\n\",\n    \"        trajname = traj.name\\n\",\n    \"        trajname_split = trajname.split('/')\\n\",\n    \"        trajname_split = [tt for tt in trajname_split if len(tt)>0]\\n\",\n    \"        if trajname_split[-1][0] == 'P':\\n\",\n    \"            trajlist.append(trajname)\\n\",\n    \"    return trajlist\\n\",\n    \"\\n\",\n    \"def _list_blobs_in_folder(folder_name):\\n\",\n    \"    \\\"\\\"\\\"\\n\",\n    \"    List all blobs in a virtual folder in an Azure blob container\\n\",\n    \"    \\\"\\\"\\\"\\n\",\n    \"    \\n\",\n    \"    files = []\\n\",\n    \"    generator = container_client.list_blobs(name_starts_with=folder_name)\\n\",\n    \"    for blob in generator:\\n\",\n    \"        files.append(blob.name)\\n\",\n    \"    return files\\n\",\n    \"\\n\",\n    \"def get_image_list(trajdir, left_right = 'left'):\\n\",\n    \"    assert(left_right == 'left' or left_right == 'right')\\n\",\n    \"    files = _list_blobs_in_folder(trajdir + '/image_' + left_right + '/')\\n\",\n    \"    files = [fn for fn in files if fn.endswith('.png')]\\n\",\n    \"    return files\\n\",\n    \"\\n\",\n    \"def get_depth_list(trajdir, left_right = 'left'):\\n\",\n    \"    assert(left_right == 'left' or left_right == 'right')\\n\",\n    \"    files = _list_blobs_in_folder(trajdir + '/depth_' + left_right + '/')\\n\",\n    \"    files = [fn for fn in files if fn.endswith('.npy')]\\n\",\n    \"    return files\\n\",\n    \"\\n\",\n    \"def get_flow_list(trajdir, ):\\n\",\n    \"    files = _list_blobs_in_folder(trajdir + '/flow/')\\n\",\n    \"    files = [fn for fn in files if fn.endswith('flow.npy')]\\n\",\n    \"    return files\\n\",\n    \"\\n\",\n    \"def get_flow_mask_list(trajdir, ):\\n\",\n    \"    files = _list_blobs_in_folder(trajdir + '/flow/')\\n\",\n    \"    files = [fn for fn in files if fn.endswith('mask.npy')]\\n\",\n    \"    return files\\n\",\n    \"\\n\",\n    \"def get_posefile(trajdir, left_right = 'left'):\\n\",\n    \"    assert(left_right == 'left' or left_right == 'right')\\n\",\n    \"    return trajdir + '/pose_' + left_right + '.txt'\\n\",\n    \"\\n\",\n    \"def get_seg_list(trajdir, left_right = 'left'):\\n\",\n    \"    assert(left_right == 'left' or left_right == 'right')\\n\",\n    \"    files = _list_blobs_in_folder(trajdir + '/seg_' + left_right + '/')\\n\",\n    \"    files = [fn for fn in files if fn.endswith('.npy')]\\n\",\n    \"    return files\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"### List all the environments \"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": 3,\n   \"metadata\": {},\n   \"outputs\": [\n    {\n     \"name\": \"stdout\",\n     \"output_type\": \"stream\",\n     \"text\": [\n      \"Find 18 environments..\\n\",\n      \"['abandonedfactory/', 'abandonedfactory_night/', 'amusement/', 'carwelding/', 'endofworld/', 'gascola/', 'hospital/', 'japanesealley/', 'neighborhood/', 'ocean/', 'office/', 'office2/', 'oldtown/', 'seasidetown/', 'seasonsforest/', 'seasonsforest_winter/', 'soulcity/', 'westerndesert/']\\n\"\n     ]\n    }\n   ],\n   \"source\": [\n    \"envlist = get_environment_list()\\n\",\n    \"print('Find {} environments..'.format(len(envlist)))\\n\",\n    \"print(envlist)\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"### List all the 'Easy' trajectories in the first environment \"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": 4,\n   \"metadata\": {},\n   \"outputs\": [\n    {\n     \"name\": \"stdout\",\n     \"output_type\": \"stream\",\n     \"text\": [\n      \"Find 10 trajectories in abandonedfactory/Easy\\n\",\n      \"['abandonedfactory/Easy/P000/', 'abandonedfactory/Easy/P001/', 'abandonedfactory/Easy/P002/', 'abandonedfactory/Easy/P004/', 'abandonedfactory/Easy/P005/', 'abandonedfactory/Easy/P006/', 'abandonedfactory/Easy/P008/', 'abandonedfactory/Easy/P009/', 'abandonedfactory/Easy/P010/', 'abandonedfactory/Easy/P011/']\\n\"\n     ]\n    }\n   ],\n   \"source\": [\n    \"diff_level = 'Easy'\\n\",\n    \"env_ind = 0\\n\",\n    \"trajlist = get_trajectory_list(envlist[env_ind], easy_hard = diff_level)\\n\",\n    \"print('Find {} trajectories in {}'.format(len(trajlist), envlist[env_ind]+diff_level))\\n\",\n    \"print(trajlist)\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"### List all the data files in one trajectory\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": 5,\n   \"metadata\": {},\n   \"outputs\": [\n    {\n     \"name\": \"stdout\",\n     \"output_type\": \"stream\",\n     \"text\": [\n      \"Find 434 left images in abandonedfactory/Easy/P001/\\n\",\n      \"Find 434 right images in abandonedfactory/Easy/P001/\\n\",\n      \"Find 434 left depth files in abandonedfactory/Easy/P001/\\n\",\n      \"Find 434 right depth files in abandonedfactory/Easy/P001/\\n\",\n      \"Find 434 left segmentation files in abandonedfactory/Easy/P001/\\n\",\n      \"Find 434 right segmentation files in abandonedfactory/Easy/P001/\\n\",\n      \"Find 433 flow files in abandonedfactory/Easy/P001/\\n\",\n      \"Find 433 flow mask files in abandonedfactory/Easy/P001/\\n\",\n      \"Left pose file: abandonedfactory/Easy/P001//pose_left.txt\\n\",\n      \"Right pose file: abandonedfactory/Easy/P001//pose_right.txt\\n\"\n     ]\n    }\n   ],\n   \"source\": [\n    \"traj_ind = 1\\n\",\n    \"traj_dir = trajlist[traj_ind]\\n\",\n    \"\\n\",\n    \"left_img_list = get_image_list(traj_dir, left_right = 'left')\\n\",\n    \"print('Find {} left images in {}'.format(len(left_img_list), traj_dir))  \\n\",\n    \"\\n\",\n    \"right_img_list = get_image_list(traj_dir, left_right = 'right')\\n\",\n    \"print('Find {} right images in {}'.format(len(right_img_list), traj_dir))\\n\",\n    \"\\n\",\n    \"left_depth_list = get_depth_list(traj_dir, left_right = 'left')\\n\",\n    \"print('Find {} left depth files in {}'.format(len(left_depth_list), traj_dir))\\n\",\n    \"\\n\",\n    \"right_depth_list = get_depth_list(traj_dir, left_right = 'right')\\n\",\n    \"print('Find {} right depth files in {}'.format(len(right_depth_list), traj_dir))\\n\",\n    \"\\n\",\n    \"left_seg_list = get_seg_list(traj_dir, left_right = 'left')\\n\",\n    \"print('Find {} left segmentation files in {}'.format(len(left_seg_list), traj_dir))\\n\",\n    \"\\n\",\n    \"right_seg_list = get_seg_list(traj_dir, left_right = 'left')\\n\",\n    \"print('Find {} right segmentation files in {}'.format(len(right_seg_list), traj_dir))\\n\",\n    \"\\n\",\n    \"flow_list = get_flow_list(traj_dir)\\n\",\n    \"print('Find {} flow files in {}'.format(len(flow_list), traj_dir)) \\n\",\n    \"\\n\",\n    \"flow_mask_list = get_flow_mask_list(traj_dir)\\n\",\n    \"print('Find {} flow mask files in {}'.format(len(flow_mask_list), traj_dir)) \\n\",\n    \"\\n\",\n    \"left_pose_file = get_posefile(traj_dir, left_right = 'left')\\n\",\n    \"print('Left pose file: {}'.format(left_pose_file))\\n\",\n    \"\\n\",\n    \"right_pose_file = get_posefile(traj_dir, left_right = 'right')\\n\",\n    \"print('Right pose file: {}'.format(right_pose_file))\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"## Functions for data downloading\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": 6,\n   \"metadata\": {},\n   \"outputs\": [],\n   \"source\": [\n    \"def read_numpy_file(numpy_file,):\\n\",\n    \"    '''\\n\",\n    \"    return a numpy array given the file path\\n\",\n    \"    '''\\n\",\n    \"    bc = container_client.get_blob_client(blob=numpy_file)\\n\",\n    \"    data = bc.download_blob()\\n\",\n    \"    ee = io.BytesIO(data.content_as_bytes())\\n\",\n    \"    ff = np.load(ee)\\n\",\n    \"    return ff\\n\",\n    \"\\n\",\n    \"\\n\",\n    \"def read_image_file(image_file,):\\n\",\n    \"    '''\\n\",\n    \"    return a uint8 numpy array given the file path  \\n\",\n    \"    '''\\n\",\n    \"    bc = container_client.get_blob_client(blob=image_file)\\n\",\n    \"    data = bc.download_blob()\\n\",\n    \"    ee = io.BytesIO(data.content_as_bytes())\\n\",\n    \"    img=cv2.imdecode(np.asarray(bytearray(ee.read()),dtype=np.uint8), cv2.IMREAD_COLOR)\\n\",\n    \"    im_rgb = img[:, :, [2, 1, 0]] # BGR2RGB\\n\",\n    \"    return im_rgb\\n\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"## Functions for data visualization\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": 7,\n   \"metadata\": {},\n   \"outputs\": [],\n   \"source\": [\n    \"def depth2vis(depth, maxthresh = 50):\\n\",\n    \"    depthvis = np.clip(depth,0,maxthresh)\\n\",\n    \"    depthvis = depthvis/maxthresh*255\\n\",\n    \"    depthvis = depthvis.astype(np.uint8)\\n\",\n    \"    depthvis = np.tile(depthvis.reshape(depthvis.shape+(1,)), (1,1,3))\\n\",\n    \"\\n\",\n    \"    return depthvis\\n\",\n    \"\\n\",\n    \"def seg2vis(segnp):\\n\",\n    \"    colors = np.loadtxt('seg_rgbs.txt')\\n\",\n    \"    segvis = np.zeros(segnp.shape+(3,), dtype=np.uint8)\\n\",\n    \"\\n\",\n    \"    for k in range(256):\\n\",\n    \"        mask = segnp==k\\n\",\n    \"        colorind = k % len(colors)\\n\",\n    \"        if np.sum(mask)>0:\\n\",\n    \"            segvis[mask,:] = colors[colorind]\\n\",\n    \"\\n\",\n    \"    return segvis\\n\",\n    \"\\n\",\n    \"def _calculate_angle_distance_from_du_dv(du, dv, flagDegree=False):\\n\",\n    \"    a = np.arctan2( dv, du )\\n\",\n    \"\\n\",\n    \"    angleShift = np.pi\\n\",\n    \"\\n\",\n    \"    if ( True == flagDegree ):\\n\",\n    \"        a = a / np.pi * 180\\n\",\n    \"        angleShift = 180\\n\",\n    \"        # print(\\\"Convert angle from radian to degree as demanded by the input file.\\\")\\n\",\n    \"\\n\",\n    \"    d = np.sqrt( du * du + dv * dv )\\n\",\n    \"\\n\",\n    \"    return a, d, angleShift\\n\",\n    \"\\n\",\n    \"def flow2vis(flownp, maxF=500.0, n=8, mask=None, hueMax=179, angShift=0.0): \\n\",\n    \"    \\\"\\\"\\\"\\n\",\n    \"    Show a optical flow field as the KITTI dataset does.\\n\",\n    \"    Some parts of this function is the transform of the original MATLAB code flow_to_color.m.\\n\",\n    \"    \\\"\\\"\\\"\\n\",\n    \"\\n\",\n    \"    ang, mag, _ = _calculate_angle_distance_from_du_dv( flownp[:, :, 0], flownp[:, :, 1], flagDegree=False )\\n\",\n    \"\\n\",\n    \"    # Use Hue, Saturation, Value colour model \\n\",\n    \"    hsv = np.zeros( ( ang.shape[0], ang.shape[1], 3 ) , dtype=np.float32)\\n\",\n    \"\\n\",\n    \"    am = ang < 0\\n\",\n    \"    ang[am] = ang[am] + np.pi * 2\\n\",\n    \"\\n\",\n    \"    hsv[ :, :, 0 ] = np.remainder( ( ang + angShift ) / (2*np.pi), 1 )\\n\",\n    \"    hsv[ :, :, 1 ] = mag / maxF * n\\n\",\n    \"    hsv[ :, :, 2 ] = (n - hsv[:, :, 1])/n\\n\",\n    \"\\n\",\n    \"    hsv[:, :, 0] = np.clip( hsv[:, :, 0], 0, 1 ) * hueMax\\n\",\n    \"    hsv[:, :, 1:3] = np.clip( hsv[:, :, 1:3], 0, 1 ) * 255\\n\",\n    \"    hsv = hsv.astype(np.uint8)\\n\",\n    \"\\n\",\n    \"    rgb = cv2.cvtColor(hsv, cv2.COLOR_HSV2RGB)\\n\",\n    \"\\n\",\n    \"    if ( mask is not None ):\\n\",\n    \"        mask = mask > 0\\n\",\n    \"        rgb[mask] = np.array([0, 0 ,0], dtype=np.uint8)\\n\",\n    \"\\n\",\n    \"    return rgb\\n\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"### Download and visualize the data\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": 8,\n   \"metadata\": {},\n   \"outputs\": [],\n   \"source\": [\n    \"data_ind = 173 # randomly select one frame (data_ind < TRAJ_LEN)\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"#### Visualize the left and right RGB images\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": 9,\n   \"metadata\": {},\n   \"outputs\": [\n    {\n     \"data\": {\n      \"image/png\": \"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\\n\",\n      \"text/plain\": [\n       \"<Figure size 864x360 with 2 Axes>\"\n      ]\n     },\n     \"metadata\": {\n      \"needs_background\": \"light\"\n     },\n     \"output_type\": \"display_data\"\n    }\n   ],\n   \"source\": [\n    \"left_img = read_image_file(left_img_list[data_ind])\\n\",\n    \"right_img = read_image_file(right_img_list[data_ind])\\n\",\n    \"\\n\",\n    \"plt.figure(figsize=(12, 5))\\n\",\n    \"plt.subplot(121)\\n\",\n    \"plt.imshow(left_img)\\n\",\n    \"plt.title('Left Image')\\n\",\n    \"plt.subplot(122)\\n\",\n    \"plt.imshow(right_img)\\n\",\n    \"plt.title('Right Image')\\n\",\n    \"plt.show()\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"#### Visualize the left and right depth files\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": 10,\n   \"metadata\": {},\n   \"outputs\": [\n    {\n     \"data\": {\n      \"image/png\": \"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\\n\",\n      \"text/plain\": [\n       \"<Figure size 864x360 with 2 Axes>\"\n      ]\n     },\n     \"metadata\": {\n      \"needs_background\": \"light\"\n     },\n     \"output_type\": \"display_data\"\n    }\n   ],\n   \"source\": [\n    \"left_depth = read_numpy_file(left_depth_list[data_ind])\\n\",\n    \"left_depth_vis = depth2vis(left_depth)\\n\",\n    \"\\n\",\n    \"right_depth = read_numpy_file(right_depth_list[data_ind])\\n\",\n    \"right_depth_vis = depth2vis(right_depth)\\n\",\n    \"\\n\",\n    \"plt.figure(figsize=(12, 5))\\n\",\n    \"plt.subplot(121)\\n\",\n    \"plt.imshow(left_depth_vis)\\n\",\n    \"plt.title('Left Depth')\\n\",\n    \"plt.subplot(122)\\n\",\n    \"plt.imshow(right_depth_vis)\\n\",\n    \"plt.title('Right Depth')\\n\",\n    \"plt.show()\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"#### Visualize the left and right segmentation files\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": 11,\n   \"metadata\": {},\n   \"outputs\": [\n    {\n     \"data\": {\n      \"image/png\": \"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\\n\",\n      \"text/plain\": [\n       \"<Figure size 864x360 with 2 Axes>\"\n      ]\n     },\n     \"metadata\": {\n      \"needs_background\": \"light\"\n     },\n     \"output_type\": \"display_data\"\n    }\n   ],\n   \"source\": [\n    \"left_seg = read_numpy_file(left_seg_list[data_ind])\\n\",\n    \"left_seg_vis = seg2vis(left_seg)\\n\",\n    \"\\n\",\n    \"right_seg = read_numpy_file(right_seg_list[data_ind])\\n\",\n    \"right_seg_vis = seg2vis(right_seg)\\n\",\n    \"\\n\",\n    \"plt.figure(figsize=(12, 5))\\n\",\n    \"plt.subplot(121)\\n\",\n    \"plt.imshow(left_seg_vis)\\n\",\n    \"plt.title('Left Segmentation')\\n\",\n    \"plt.subplot(122)\\n\",\n    \"plt.imshow(right_seg_vis)\\n\",\n    \"plt.title('Right Segmentation')\\n\",\n    \"plt.show()\"\n   ]\n  },\n  {\n   \"cell_type\": \"markdown\",\n   \"metadata\": {},\n   \"source\": [\n    \"#### Visualize the flow and mask files\"\n   ]\n  },\n  {\n   \"cell_type\": \"code\",\n   \"execution_count\": 12,\n   \"metadata\": {\n    \"scrolled\": true\n   },\n   \"outputs\": [\n    {\n     \"data\": {\n      \"image/png\": \"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\\n\",\n      \"text/plain\": [\n       \"<Figure size 864x360 with 2 Axes>\"\n      ]\n     },\n     \"metadata\": {\n      \"needs_background\": \"light\"\n     },\n     \"output_type\": \"display_data\"\n    }\n   ],\n   \"source\": [\n    \"flow = read_numpy_file(flow_list[data_ind])\\n\",\n    \"flow_vis = flow2vis(flow)\\n\",\n    \"\\n\",\n    \"flow_mask = read_numpy_file(flow_mask_list[data_ind])\\n\",\n    \"flow_vis_w_mask = flow2vis(flow, mask = flow_mask)\\n\",\n    \"\\n\",\n    \"plt.figure(figsize=(12, 5))\\n\",\n    \"plt.subplot(121)\\n\",\n    \"plt.imshow(flow_vis)\\n\",\n    \"plt.title('Optical Flow')\\n\",\n    \"plt.subplot(122)\\n\",\n    \"plt.imshow(flow_vis_w_mask)\\n\",\n    \"plt.title('Optical Flow w/ Mask')\\n\",\n    \"plt.show()\"\n   ]\n  }\n ],\n \"metadata\": {\n  \"kernelspec\": {\n   \"display_name\": \"Python 2\",\n   \"language\": \"python\",\n   \"name\": \"python2\"\n  },\n  \"language_info\": {\n   \"codemirror_mode\": {\n    \"name\": \"ipython\",\n    \"version\": 2\n   },\n   \"file_extension\": \".py\",\n   \"mimetype\": \"text/x-python\",\n   \"name\": \"python\",\n   \"nbconvert_exporter\": \"python\",\n   \"pygments_lexer\": \"ipython2\",\n   \"version\": \"2.7.17\"\n  }\n },\n \"nbformat\": 4,\n \"nbformat_minor\": 2\n}\n"
  },
  {
    "path": "VO_Module/thirdparty/tartanair_tools/data_type.md",
    "content": "### GRB Image\n\nThe color images are stored as 640x480 8-bit RGB images in PNG format.\n\n* Load the image using OpenCV: \n```\nimport cv2\nimg = cv2.imread(FILENAME)\ncv2.imshow('img', img)\ncv2.waitKey(0)\n```\n\n* Load the image using Pillow:\n```\nfrom PIL import Image\nimg = Image.open(FILENAME)\nimg.show()\n```\n\n### Camera intrinsics \n```\nfx = 320.0  # focal length x\nfy = 320.0  # focal length y\ncx = 320.0  # optical center x\ncy = 240.0  # optical center y\n\nfov = 90 deg # field of view\n\nwidth = 640\nheight = 480\n```\n\n### Depth image\n\nThe depth maps are stored as 640x480 16-bit numpy array in NPY format. In the Unreal Engine, the environment usually has a sky sphere at a large distance. So the infinite distant object such as the sky has a large depth value (e.g. 10000) instead of an infinite number. \n\nThe unit of the depth value is meter. The baseline between the left and right cameras is 0.25m. \n\n* Load the depth image:\n```\nimport numpy as np\ndepth = np.load(FILENAME)\n\n# change to disparity image\ndisparity = 80.0 / depth\n```\n\n### Segmentation image\n\nThe segmentation images are saved as a uint8 numpy array. AirSim assigns value 0 to 255 to each mesh available in the environment. \n\n[More details](https://github.com/microsoft/AirSim/blob/master/docs/image_apis.md#segmentation)\n\n* Load the segmentation image\n```\nimport numpy as np\ndepth = np.load(FILENAME)\n```\n\n### Optical flow\n\nThe optical flow maps are saved as a float32 numpy array, which is calculated based on the ground truth depth and ground truth camera motion, using [this](https://github.com/huyaoyu/ImageFlow) code. Dynamic objects and occlusions are masked by the mask file, which is a uint8 numpy array. We currently provide the optical flow for the left camera. \n\n* Load the optical flow\n```\nimport numpy as np\nflow = np.load(FILENAME)\n\n# load the mask\nmask = np.load(MASKFILENAME)\n```\n\n### Pose file\n\nThe camera pose file is a text file containing the translation and orientation of the camera in a fixed coordinate frame. Note that our automatic evaluation tool expects both the ground truth trajectory and the estimated trajectory to be in this format. \n\n* Each line in the text file contains a single pose.\n\n* The number of lines/poses is the same as the number of image frames in that trajectory. \n\n* The format of each line is '**tx ty tz qx qy qz qw**'. \n\n* **tx ty tz** (3 floats) give the position of the optical center of the color camera with respect to the world origin in the world frame.\n\n* **qx qy qz qw** (4 floats) give the orientation of the optical center of the color camera in the form of a unit quaternion with respect to the world frame. \n\n* The camera motion is defined in the NED frame. That is to say, the x-axis is pointing to the camera's forward, the y-axis is pointing to the camera's right, the z-axis is pointing to the camera's downward. \n\n* Load the pose file:\n```\nimport numpy as np\nflow = np.loadtxt(FILENAME)\n```\n"
  },
  {
    "path": "VO_Module/thirdparty/tartanair_tools/download_cvpr_slam_test.txt",
    "content": "https://tartanair.blob.core.windows.net/tartanair-testing1/tartanair-test-mono-release.tar.gz\nhttps://tartanair.blob.core.windows.net/tartanair-testing1/tartanair-test-stereo-release.tar.gz\nhttps://tartanair.blob.core.windows.net/tartanair-testing1/tartanair-test-release.tar.gz"
  },
  {
    "path": "VO_Module/thirdparty/tartanair_tools/download_training.py",
    "content": "from os import system, mkdir\nimport argparse\nfrom os.path import isdir, isfile\n\ndef get_args():\n    parser = argparse.ArgumentParser(description='TartanAir')\n\n    parser.add_argument('--output-dir', default='./',\n                        help='root directory for downloaded files')\n\n    parser.add_argument('--rgb', action='store_true', default=False,\n                        help='download rgb image')\n\n    parser.add_argument('--depth', action='store_true', default=False,\n                        help='download depth image')\n\n    parser.add_argument('--flow', action='store_true', default=False,\n                        help='download optical flow')\n\n    parser.add_argument('--seg', action='store_true', default=False,\n                        help='download segmentation image')\n\n    parser.add_argument('--only-easy', action='store_true', default=False,\n                        help='download only easy trajectories')\n\n    parser.add_argument('--only-hard', action='store_true', default=False,\n                        help='download only hard trajectories')\n\n    parser.add_argument('--only-left', action='store_true', default=False,\n                        help='download only left camera')\n\n    parser.add_argument('--only-right', action='store_true', default=False,\n                        help='download only right camera')\n\n    parser.add_argument('--only-flow', action='store_true', default=False,\n                        help='download only optical flow wo/ mask')\n\n    parser.add_argument('--only-mask', action='store_true', default=False,\n                        help='download only mask wo/ flow')\n\n    parser.add_argument('--azcopy', action='store_true', default=False,\n                        help='download the data with AzCopy, which is 10x faster in our test')\n\n    args = parser.parse_args()\n\n    return args\n\ndef _help():\n    print ''\n\nif __name__ == '__main__':\n    args = get_args()\n\n    # output directory\n    outdir = args.output_dir\n    if not isdir(outdir):\n        print('Output dir {} does not exists!'.format(outdir))\n        exit()\n\n    # difficulty level\n    levellist = ['Easy', 'Hard']\n    if args.only_easy:\n        levellist = ['Easy']\n    if args.only_hard:\n        levellist = ['Hard']\n    if args.only_easy and args.only_hard:\n        print('--only-eazy and --only-hard tags can not be set at the same time!')\n        exit()\n\n\n    # filetype\n    typelist = []\n    if args.rgb:\n        typelist.append('image')\n    if args.depth:\n        typelist.append('depth')\n    if args.seg:\n        typelist.append('seg')\n    if args.flow:\n        typelist.append('flow')\n    if len(typelist)==0:\n        print('Specify the type of data you want to download by --rgb/depth/seg/flow')\n        exit()\n\n    # camera \n    cameralist = ['left', 'right', 'flow', 'mask']\n    if args.only_left:\n        cameralist.remove('right')\n    if args.only_right:\n        cameralist.remove('left')\n    if args.only_flow:\n        cameralist.remove('mask')\n    if args.only_mask:\n        cameralist.remove('flow')\n    if args.only_left and args.only_right:\n        print('--only-left and --only-right tags can not be set at the same time!')\n        exit()\n    if args.only_flow and args.only_mask:\n        print('--only-flow and --only-mask tags can not be set at the same time!')\n        exit()\n\n    # read all the zip file urls\n    with open('download_training_zipfiles.txt') as f:\n        lines = f.readlines()\n    ziplist = [ll.strip() for ll in lines if ll.strip().endswith('.zip')]\n\n    downloadlist = []\n    for zipfile in ziplist:\n        zf = zipfile.split('/')\n        filename = zf[-1]\n        difflevel = zf[-2]\n\n        # image/depth/seg/flow\n        filetype = filename.split('_')[0] \n        # left/right/flow/mask\n        cameratype = filename.split('.')[0].split('_')[-1]\n        \n        if (difflevel in levellist) and (filetype in typelist) and (cameratype in cameralist):\n            downloadlist.append(zipfile) \n\n    if len(downloadlist)==0:\n        print('No file meets the condition!')\n        exit()\n\n    print('{} files are going to be downloaded...'.format(len(downloadlist)))\n    for fileurl in downloadlist:\n        print fileurl\n\n    for fileurl in downloadlist:\n        zf = fileurl.split('/')\n        filename = zf[-1]\n        difflevel = zf[-2]\n        envname = zf[-3]\n\n        envfolder = outdir + '/' + envname\n        if not isdir(envfolder):\n            mkdir(envfolder)\n            print('Created a new env folder {}..'.format(envfolder))\n        # else: \n        #     print('Env folder {} already exists..'.format(envfolder))\n\n        levelfolder = envfolder + '/' + difflevel\n        if not isdir(levelfolder):\n            mkdir(levelfolder)\n            print('  Created a new level folder {}..'.format(levelfolder))\n        # else: \n        #     print('Level folder {} already exists..'.format(levelfolder))\n\n        targetfile = levelfolder + '/' + filename\n        if isfile(targetfile):\n            print('Target file {} already exists..'.format(targetfile))\n            exit()\n\n        if args.azcopy:\n            cmd = 'azcopy copy ' + fileurl + ' ' + targetfile \n        else:\n            cmd = 'wget -r -O ' + targetfile + ' ' + fileurl\n        print cmd\n        system(cmd)"
  },
  {
    "path": "VO_Module/thirdparty/tartanair_tools/download_training_zipfiles.txt",
    "content": "https://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Easy/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Easy/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Easy/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Easy/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Easy/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Easy/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Easy/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Easy/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Hard/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Hard/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Hard/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Hard/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Hard/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Hard/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Hard/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory/Hard/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Easy/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Easy/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Easy/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Easy/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Easy/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Easy/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Easy/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Easy/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Hard/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Hard/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Hard/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Hard/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Hard/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Hard/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Hard/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/abandonedfactory_night/Hard/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/amusement/Easy/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/amusement/Easy/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/amusement/Easy/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/amusement/Easy/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/amusement/Easy/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/amusement/Easy/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/amusement/Easy/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/amusement/Easy/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/amusement/Hard/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/amusement/Hard/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/amusement/Hard/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/amusement/Hard/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/amusement/Hard/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/amusement/Hard/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/amusement/Hard/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/amusement/Hard/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Easy/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Easy/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Easy/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Easy/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Easy/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Easy/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Easy/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Easy/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Hard/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Hard/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Hard/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Hard/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Hard/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Hard/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Hard/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/carwelding/Hard/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Easy/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Easy/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Easy/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Easy/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Easy/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Easy/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Easy/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Easy/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Hard/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Hard/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Hard/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Hard/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Hard/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Hard/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Hard/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/endofworld/Hard/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/gascola/Easy/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/gascola/Easy/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/gascola/Easy/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/gascola/Easy/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/gascola/Easy/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/gascola/Easy/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/gascola/Easy/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/gascola/Easy/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/gascola/Hard/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/gascola/Hard/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/gascola/Hard/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/gascola/Hard/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/gascola/Hard/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/gascola/Hard/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/gascola/Hard/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/gascola/Hard/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/hospital/Easy/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/hospital/Easy/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/hospital/Easy/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/hospital/Easy/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/hospital/Easy/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/hospital/Easy/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/hospital/Easy/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/hospital/Easy/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/hospital/Hard/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/hospital/Hard/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/hospital/Hard/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/hospital/Hard/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/hospital/Hard/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/hospital/Hard/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/hospital/Hard/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/hospital/Hard/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Easy/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Easy/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Easy/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Easy/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Easy/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Easy/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Easy/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Easy/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Hard/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Hard/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Hard/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Hard/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Hard/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Hard/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Hard/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/japanesealley/Hard/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Easy/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Easy/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Easy/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Easy/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Easy/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Easy/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Easy/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Easy/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Hard/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Hard/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Hard/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Hard/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Hard/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Hard/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Hard/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/neighborhood/Hard/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/ocean/Easy/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/ocean/Easy/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/ocean/Easy/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/ocean/Easy/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/ocean/Easy/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/ocean/Easy/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/ocean/Easy/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/ocean/Easy/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/ocean/Hard/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/ocean/Hard/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/ocean/Hard/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/ocean/Hard/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/ocean/Hard/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/ocean/Hard/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/ocean/Hard/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/ocean/Hard/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office/Easy/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office/Easy/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office/Easy/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office/Easy/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office/Easy/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office/Easy/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office/Easy/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office/Easy/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office/Hard/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office/Hard/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office/Hard/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office/Hard/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office/Hard/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office/Hard/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office/Hard/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office/Hard/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office2/Easy/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office2/Easy/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office2/Easy/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office2/Easy/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office2/Easy/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office2/Easy/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office2/Easy/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office2/Easy/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office2/Hard/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office2/Hard/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office2/Hard/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office2/Hard/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office2/Hard/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office2/Hard/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office2/Hard/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/office2/Hard/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Easy/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Easy/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Easy/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Easy/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Easy/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Easy/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Easy/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Easy/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Hard/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Hard/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Hard/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Hard/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Hard/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Hard/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Hard/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/oldtown/Hard/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Easy/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Easy/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Easy/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Easy/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Easy/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Easy/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Easy/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Easy/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Hard/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Hard/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Hard/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Hard/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Hard/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Hard/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Hard/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasidetown/Hard/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Easy/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Easy/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Easy/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Easy/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Easy/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Easy/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Easy/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Easy/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Hard/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Hard/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Hard/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Hard/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Hard/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Hard/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Hard/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest/Hard/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Easy/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Easy/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Easy/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Easy/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Easy/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Easy/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Easy/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Easy/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Hard/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Hard/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Hard/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Hard/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Hard/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Hard/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Hard/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/seasonsforest_winter/Hard/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Easy/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Easy/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Easy/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Easy/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Easy/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Easy/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Easy/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Easy/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Hard/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Hard/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Hard/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Hard/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Hard/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Hard/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Hard/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/soulcity/Hard/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Easy/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Easy/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Easy/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Easy/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Easy/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Easy/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Easy/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Easy/seg_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Hard/depth_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Hard/depth_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Hard/flow_flow.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Hard/flow_mask.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Hard/image_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Hard/image_right.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Hard/seg_left.zip\nhttps://tartanair.blob.core.windows.net/tartanair-release1/westerndesert/Hard/seg_right.zip\n"
  },
  {
    "path": "VO_Module/thirdparty/tartanair_tools/evaluation/__init__.py",
    "content": ""
  },
  {
    "path": "VO_Module/thirdparty/tartanair_tools/evaluation/evaluate_ate_scale.py",
    "content": "#!/usr/bin/python\n\n# Modified by Wenshan Wang\n# Modified by Raul Mur-Artal\n# Automatically compute the optimal scale factor for monocular VO/SLAM.\n\n# Software License Agreement (BSD License)\n#\n# Copyright (c) 2013, Juergen Sturm, TUM\n# All rights reserved.\n#\n# Redistribution and use in source and binary forms, with or without\n# modification, are permitted provided that the following conditions\n# are met:\n#\n#  * Redistributions of source code must retain the above copyright\n#    notice, this list of conditions and the following disclaimer.\n#  * Redistributions in binary form must reproduce the above\n#    copyright notice, this list of conditions and the following\n#    disclaimer in the documentation and/or other materials provided\n#    with the distribution.\n#  * Neither the name of TUM nor the names of its\n#    contributors may be used to endorse or promote products derived\n#    from this software without specific prior written permission.\n#\n# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n# \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n# POSSIBILITY OF SUCH DAMAGE.\n#\n# Requirements: \n# sudo apt-get install python-argparse\n\n\"\"\"\nThis script computes the absolute trajectory error from the ground truth\ntrajectory and the estimated trajectory.\n\"\"\"\n\nimport numpy\n\ndef align(model,data,calc_scale=False):\n    \"\"\"Align two trajectories using the method of Horn (closed-form).\n    \n    Input:\n    model -- first trajectory (3xn)\n    data -- second trajectory (3xn)\n    \n    Output:\n    rot -- rotation matrix (3x3)\n    trans -- translation vector (3x1)\n    trans_error -- translational error per point (1xn)\n    \n    \"\"\"\n    numpy.set_printoptions(precision=3,suppress=True)\n    model_zerocentered = model - model.mean(1)\n    data_zerocentered = data - data.mean(1)\n    \n    W = numpy.zeros( (3,3) )\n    for column in range(model.shape[1]):\n        W += numpy.outer(model_zerocentered[:,column],data_zerocentered[:,column])\n    U,d,Vh = numpy.linalg.linalg.svd(W.transpose())\n    S = numpy.matrix(numpy.identity( 3 ))\n    if(numpy.linalg.det(U) * numpy.linalg.det(Vh)<0):\n        S[2,2] = -1\n    rot = U*S*Vh\n\n    if calc_scale:\n        rotmodel = rot*model_zerocentered\n        dots = 0.0\n        norms = 0.0\n        for column in range(data_zerocentered.shape[1]):\n            dots += numpy.dot(data_zerocentered[:,column].transpose(),rotmodel[:,column])\n            normi = numpy.linalg.norm(model_zerocentered[:,column])\n            norms += normi*normi\n        # s = float(dots/norms)  \n        s = float(norms/dots)\n    else:\n        s = 1.0  \n\n    # trans = data.mean(1) - s*rot * model.mean(1)\n    # model_aligned = s*rot * model + trans\n    # alignment_error = model_aligned - data\n\n    # scale the est to the gt, otherwise the ATE could be very small if the est scale is small\n    trans = s*data.mean(1) - rot * model.mean(1)\n    model_aligned = rot * model + trans\n    data_alingned = s * data\n    alignment_error = model_aligned - data_alingned\n    \n    trans_error = numpy.sqrt(numpy.sum(numpy.multiply(alignment_error,alignment_error),0)).A[0]\n        \n    return rot,trans,trans_error, s\n\ndef plot_traj(ax,stamps,traj,style,color,label):\n    \"\"\"\n    Plot a trajectory using matplotlib. \n    \n    Input:\n    ax -- the plot\n    stamps -- time stamps (1xn)\n    traj -- trajectory (3xn)\n    style -- line style\n    color -- line color\n    label -- plot legend\n    \n    \"\"\"\n    stamps.sort()\n    interval = numpy.median([s-t for s,t in zip(stamps[1:],stamps[:-1])])\n    x = []\n    y = []\n    last = stamps[0]\n    for i in range(len(stamps)):\n        if stamps[i]-last < 2*interval:\n            x.append(traj[i][0])\n            y.append(traj[i][1])\n        elif len(x)>0:\n            ax.plot(x,y,style,color=color,label=label)\n            label=\"\"\n            x=[]\n            y=[]\n        last= stamps[i]\n    if len(x)>0:\n        ax.plot(x,y,style,color=color,label=label)\n            \n\n"
  },
  {
    "path": "VO_Module/thirdparty/tartanair_tools/evaluation/evaluate_kitti.py",
    "content": "# Copyright (c) 2020 Carnegie Mellon University, Wenshan Wang <wenshanw@andrew.cmu.edu>\n# For License information please see the LICENSE file in the root directory.\n# This is a python reinplementation of the KITTI metric: http://www.cvlibs.net/datasets/kitti/eval_odometry.php\n# Cridit: Xiangwei Wang https://github.com/TimingSpace\n\nimport numpy as np\nimport sys\n\ndef trajectory_distances(poses):\n    distances = []\n    distances.append(0)\n    for i in range(1,len(poses)):\n        p1 = poses[i-1]\n        p2 = poses[i]\n        delta = p1[0:3,3] - p2[0:3,3]\n        distances.append(distances[i-1]+np.linalg.norm(delta))\n    return distances\n\ndef last_frame_from_segment_length(dist,first_frame,length):\n    for i in range(first_frame,len(dist)):\n        if dist[i]>dist[first_frame]+length:\n            return i\n    return -1\n\ndef rotation_error(pose_error):\n    a = pose_error[0,0]\n    b = pose_error[1,1]\n    c = pose_error[2,2]\n    d = 0.5*(a+b+c-1)\n    rot_error = np.arccos(max(min(d,1.0),-1.0))\n    return rot_error\n\ndef translation_error(pose_error):\n    dx = pose_error[0,3]\n    dy = pose_error[1,3]\n    dz = pose_error[2,3]\n    return np.sqrt(dx*dx+dy*dy+dz*dz)\n\n# def line2matrix(pose_line):\n#     pose_line = np.array(pose_line)\n#     pose_m = np.matrix(np.eye(4))\n#     pose_m[0:3,:] = pose_line.reshape(3,4)\n#     return pose_m\n    \ndef calculate_sequence_error(poses_gt,poses_result,lengths=[10,20,30,40,50,60,70,80]):\n    # error_vetor\n    errors = []\n\n    # paramet\n    step_size = 1 #10; # every second\n    num_lengths = len(lengths)\n\n    # import ipdb;ipdb.set_trace()\n    # pre-compute distances (from ground truth as reference)\n    dist = trajectory_distances(poses_gt)\n    # for all start positions do\n    for  first_frame in range(0, len(poses_gt), step_size):\n    # for all segment lengths do\n        for i in range(0,num_lengths):\n            #  current length\n            length = lengths[i];\n\n            # compute last frame\n            last_frame = last_frame_from_segment_length(dist,first_frame,length);\n            # continue, if sequence not long enough\n            if (last_frame==-1):\n                continue;\n\n            # compute rotational and translational errors\n            pose_delta_gt     = np.linalg.inv(poses_gt[first_frame]).dot(poses_gt[last_frame])\n            pose_delta_result = np.linalg.inv(poses_result[first_frame]).dot(poses_result[last_frame])\n            pose_error        = np.linalg.inv(pose_delta_result).dot(pose_delta_gt)\n            r_err = rotation_error(pose_error);\n            t_err = translation_error(pose_error);\n\n            # compute speed\n            num_frames = (float)(last_frame-first_frame+1);\n            speed = length/(0.1*num_frames);\n\n            # write to file\n            error = [first_frame,r_err/length,t_err/length,length,speed]\n            errors.append(error)\n            # return error vector\n    return errors\n\ndef calculate_ave_errors(errors,lengths=[10,20,30,40,50,60,70,80]):\n    rot_errors=[]\n    tra_errors=[]\n    for length in lengths:\n        rot_error_each_length =[]\n        tra_error_each_length =[]\n        for error in errors:\n            if abs(error[3]-length)<0.1:\n                rot_error_each_length.append(error[1])\n                tra_error_each_length.append(error[2])\n\n        if len(rot_error_each_length)==0:\n            # import ipdb;ipdb.set_trace()\n            continue\n        else:\n            rot_errors.append(sum(rot_error_each_length)/len(rot_error_each_length))\n            tra_errors.append(sum(tra_error_each_length)/len(tra_error_each_length))\n    return np.array(rot_errors)*180/np.pi, tra_errors\n\ndef evaluate(gt, data,rescale_=False):\n    lens =  [5,10,15,20,25,30,35,40] #[1,2,3,4,5,6] # \n    errors = calculate_sequence_error(gt, data, lengths=lens)\n    rot,tra = calculate_ave_errors(errors, lengths=lens)\n    return np.mean(rot), np.mean(tra)\n\ndef  main():\n    # usage: python main.py path_to_ground_truth path_to_predict_pose\n    # load and preprocess data\n    ground_truth_data  = np.loadtxt(sys.argv[1])\n    predict_pose__data = np.loadtxt(sys.argv[2])\n    errors = calculate_sequence_error(ground_truth_data,predict_pose__data)\n    rot,tra = calculate_ave_errors(errors)\n    print(rot,'\\n',tra)\n    #print(error)\n    # evaluate the vo result\n    # save and visualization the evaluatation result\n\nif __name__ == \"__main__\":\n    main()\n\n\n"
  },
  {
    "path": "VO_Module/thirdparty/tartanair_tools/evaluation/evaluate_rpe.py",
    "content": "#!/usr/bin/python\n# Software License Agreement (BSD License)\n#\n# Modified by Wenshan Wang\n# Copyright (c) 2013, Juergen Sturm, TUM\n# All rights reserved.\n#\n# Redistribution and use in source and binary forms, with or without\n# modification, are permitted provided that the following conditions\n# are met:\n#\n#  * Redistributions of source code must retain the above copyright\n#    notice, this list of conditions and the following disclaimer.\n#  * Redistributions in binary form must reproduce the above\n#    copyright notice, this list of conditions and the following\n#    disclaimer in the documentation and/or other materials provided\n#    with the distribution.\n#  * Neither the name of TUM nor the names of its\n#    contributors may be used to endorse or promote products derived\n#    from this software without specific prior written permission.\n#\n# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS\n# \"AS IS\" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT\n# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS\n# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE\n# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,\n# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,\n# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;\n# LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n# CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT\n# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN\n# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE\n# POSSIBILITY OF SUCH DAMAGE.\n\n\"\"\"\nThis script computes the relative pose error from the ground truth trajectory\nand the estimated trajectory.\n\"\"\"\n\nimport random\nimport numpy as np\nimport sys\n\ndef ominus(a,b):\n    \"\"\"\n    Compute the relative 3D transformation between a and b.\n    \n    Input:\n    a -- first pose (homogeneous 4x4 matrix)\n    b -- second pose (homogeneous 4x4 matrix)\n    \n    Output:\n    Relative 3D transformation from a to b.\n    \"\"\"\n    return np.dot(np.linalg.inv(a),b)\n\ndef compute_distance(transform):\n    \"\"\"\n    Compute the distance of the translational component of a 4x4 homogeneous matrix.\n    \"\"\"\n    return np.linalg.norm(transform[0:3,3])\n\ndef compute_angle(transform):\n    \"\"\"\n    Compute the rotation angle from a 4x4 homogeneous matrix.\n    \"\"\"\n    # an invitation to 3-d vision, p 27\n    return np.arccos( min(1,max(-1, (np.trace(transform[0:3,0:3]) - 1)/2) ))\n\ndef distances_along_trajectory(traj):\n    \"\"\"\n    Compute the translational distances along a trajectory. \n    \"\"\"\n    motion = [ominus(traj[i+1],traj[i]) for i in range(len(traj)-1)]\n    distances = [0]\n    sum = 0\n    for t in motion:\n        sum += compute_distance(t)\n        distances.append(sum)\n    return distances\n    \n\ndef evaluate_trajectory(traj_gt, traj_est, param_max_pairs=10000, param_fixed_delta=False,\n                        param_delta=1.00):\n    \"\"\"\n    Compute the relative pose error between two trajectories.\n    \n    Input:\n    traj_gt -- the first trajectory (ground truth)\n    traj_est -- the second trajectory (estimated trajectory)\n    param_max_pairs -- number of relative poses to be evaluated\n    param_fixed_delta -- false: evaluate over all possible pairs\n                         true: only evaluate over pairs with a given distance (delta)\n    param_delta -- distance between the evaluated pairs\n    param_delta_unit -- unit for comparison:\n                        \"s\": seconds\n                        \"m\": meters\n                        \"rad\": radians\n                        \"deg\": degrees\n                        \"f\": frames\n    param_offset -- time offset between two trajectories (to model the delay)\n    param_scale -- scale to be applied to the second trajectory\n    \n    Output:\n    list of compared poses and the resulting translation and rotation error\n    \"\"\"\n    \n    if not param_fixed_delta:\n        if(param_max_pairs==0 or len(traj_est)<np.sqrt(param_max_pairs)):\n            pairs = [(i,j) for i in range(len(traj_est)) for j in range(len(traj_est))]\n        else:\n            pairs = [(random.randint(0,len(traj_est)-1),random.randint(0,len(traj_est)-1)) for i in range(param_max_pairs)]\n    else:\n        pairs = []\n        for i in range(len(traj_est)):\n            j = i + param_delta\n            if j < len(traj_est): \n                pairs.append((i,j))\n        if(param_max_pairs!=0 and len(pairs)>param_max_pairs):\n            pairs = random.sample(pairs,param_max_pairs)\n        \n    result = []\n    for i,j in pairs:\n        \n        error44 = ominus(  ominus( traj_est[j], traj_est[i] ),\n                           ominus( traj_gt[j], traj_gt[i] ) )\n        \n        trans = compute_distance(error44)\n        rot = compute_angle(error44)\n        \n        result.append([i,j,trans,rot])\n        \n    if len(result)<2:\n        raise Exception(\"Couldn't find pairs between groundtruth and estimated trajectory!\")\n        \n    return result\n\n# import argparse\n# if __name__ == '__main__':\n#     random.seed(0)\n\n#     parser = argparse.ArgumentParser(description='''\n#     This script computes the relative pose error from the ground truth trajectory and the estimated trajectory. \n#     ''')\n#     parser.add_argument('groundtruth_file', help='ground-truth trajectory file (format: \"timestamp tx ty tz qx qy qz qw\")')\n#     parser.add_argument('estimated_file', help='estimated trajectory file (format: \"timestamp tx ty tz qx qy qz qw\")')\n#     parser.add_argument('--max_pairs', help='maximum number of pose comparisons (default: 10000, set to zero to disable downsampling)', default=10000)\n#     parser.add_argument('--fixed_delta', help='only consider pose pairs that have a distance of delta delta_unit (e.g., for evaluating the drift per second/meter/radian)', action='store_true')\n#     parser.add_argument('--delta', help='delta for evaluation (default: 1.0)',default=1.0)\n#     parser.add_argument('--delta_unit', help='unit of delta (options: \\'s\\' for seconds, \\'m\\' for meters, \\'rad\\' for radians, \\'f\\' for frames; default: \\'s\\')',default='s')\n#     parser.add_argument('--offset', help='time offset between ground-truth and estimated trajectory (default: 0.0)',default=0.0)\n#     parser.add_argument('--scale', help='scaling factor for the estimated trajectory (default: 1.0)',default=1.0)\n#     parser.add_argument('--save', help='text file to which the evaluation will be saved (format: stamp_est0 stamp_est1 stamp_gt0 stamp_gt1 trans_error rot_error)')\n#     parser.add_argument('--plot', help='plot the result to a file (requires --fixed_delta, output format: png)')\n#     parser.add_argument('--verbose', help='print all evaluation data (otherwise, only the mean translational error measured in meters will be printed)', action='store_true')\n#     args = parser.parse_args()\n    \n#     if args.plot and not args.fixed_delta:\n#         sys.exit(\"The '--plot' option can only be used in combination with '--fixed_delta'\")\n    \n#     traj_gt = np.loadtxt(args.groundtruth_file)\n#     traj_est = np.loadtxt(args.estimated_file)\n    \n#     from trajectory_transform import trajectory_transform\n#     traj_gt, traj_est = trajectory_transform(traj_gt, traj_est)\n\n#     traj_gt = tf.pos_quats2SE_matrices(traj_gt)\n#     traj_est = tf.pos_quats2SE_matrices(traj_est)\n\n#     result = evaluate_trajectory(traj_gt,\n#                                  traj_est,\n#                                  int(args.max_pairs),\n#                                  args.fixed_delta,\n#                                  float(args.delta),\n#                                  args.delta_unit)\n    \n#     trans_error = np.array(result)[:,2]\n#     rot_error = np.array(result)[:,3]\n    \n#     if args.save:\n#         f = open(args.save,\"w\")\n#         f.write(\"\\n\".join([\" \".join([\"%f\"%v for v in line]) for line in result]))\n#         f.close()\n    \n#     if args.verbose:\n#         print \"compared_pose_pairs %d pairs\"%(len(trans_error))\n\n#         print \"translational_error.rmse %f m\"%np.sqrt(np.dot(trans_error,trans_error) / len(trans_error))\n#         print \"translational_error.mean %f m\"%np.mean(trans_error)\n#         print \"translational_error.median %f m\"%np.median(trans_error)\n#         print \"translational_error.std %f m\"%np.std(trans_error)\n#         print \"translational_error.min %f m\"%np.min(trans_error)\n#         print \"translational_error.max %f m\"%np.max(trans_error)\n\n#         print \"rotational_error.rmse %f deg\"%(np.sqrt(np.dot(rot_error,rot_error) / len(rot_error)) * 180.0 / np.pi)\n#         print \"rotational_error.mean %f deg\"%(np.mean(rot_error) * 180.0 / np.pi)\n#         print \"rotational_error.median %f deg\"%(np.median(rot_error) * 180.0 / np.pi)\n#         print \"rotational_error.std %f deg\"%(np.std(rot_error) * 180.0 / np.pi)\n#         print \"rotational_error.min %f deg\"%(np.min(rot_error) * 180.0 / np.pi)\n#         print \"rotational_error.max %f deg\"%(np.max(rot_error) * 180.0 / np.pi)\n#     else:\n#         print np.mean(trans_error)\n\n#     import ipdb;ipdb.set_trace()\n\n#     if args.plot:    \n#         import matplotlib\n#         matplotlib.use('Agg')\n#         import matplotlib.pyplot as plt\n#         import matplotlib.pylab as pylab\n#         fig = plt.figure()\n#         ax = fig.add_subplot(111)        \n#         ax.plot(stamps - stamps[0],trans_error,'-',color=\"blue\")\n#         #ax.plot([t for t,e in err_rot],[e for t,e in err_rot],'-',color=\"red\")\n#         ax.set_xlabel('time [s]')\n#         ax.set_ylabel('translational error [m]')\n#         plt.savefig(args.plot,dpi=300)\n        \n\n"
  },
  {
    "path": "VO_Module/thirdparty/tartanair_tools/evaluation/evaluator_base.py",
    "content": "# Copyright (c) 2020 Carnegie Mellon University, Wenshan Wang <wenshanw@andrew.cmu.edu>\n# For License information please see the LICENSE file in the root directory.\n\nimport numpy as np\nfrom .trajectory_transform import trajectory_transform, rescale\nfrom .transformation import pos_quats2SE_matrices, SE2pos_quat\n\n\nnp.set_printoptions(suppress=True, precision=2, threshold=100000)\n\ndef transform_trajs(gt_traj, est_traj, cal_scale):\n    gt_traj, est_traj = trajectory_transform(gt_traj, est_traj)\n    if cal_scale :\n        est_traj, s = rescale(gt_traj, est_traj)\n        print('  Scale, {}'.format(s))\n    else:\n        s = 1.0\n    return gt_traj, est_traj, s\n\ndef quats2SEs(gt_traj, est_traj):\n    gt_SEs = pos_quats2SE_matrices(gt_traj)\n    est_SEs = pos_quats2SE_matrices(est_traj)\n    return gt_SEs, est_SEs\n\nfrom .evaluate_ate_scale import align, plot_traj\n\n\nclass ATEEvaluator(object):\n    def __init__(self):\n        super(ATEEvaluator, self).__init__()\n\n\n    def evaluate(self, gt_traj, est_traj, scale):\n        gt_xyz = np.matrix(gt_traj[:,0:3].transpose())\n        est_xyz = np.matrix(est_traj[:, 0:3].transpose())\n\n        rot, trans, trans_error, s = align(gt_xyz, est_xyz, scale)\n        print('  ATE scale: {}'.format(s))\n        error = np.sqrt(np.dot(trans_error,trans_error) / len(trans_error))\n\n        # align two trajs \n        est_SEs = pos_quats2SE_matrices(est_traj)\n        T = np.eye(4) \n        T[:3,:3] = rot\n        T[:3,3:] = trans \n        T = np.linalg.inv(T)\n        est_traj_aligned = []\n        for se in est_SEs:\n            se[:3,3] = se[:3,3] * s\n            se_new = T.dot(se)\n            se_new = SE2pos_quat(se_new)\n            est_traj_aligned.append(se_new)\n\n\n        return error, gt_traj, est_traj_aligned\n\n# =======================\n\nfrom .evaluate_rpe import evaluate_trajectory\n\nclass RPEEvaluator(object):\n    def __init__(self):\n        super(RPEEvaluator, self).__init__()\n\n\n    def evaluate(self, gt_SEs, est_SEs):\n        result = evaluate_trajectory(gt_SEs, est_SEs)\n        \n        trans_error = np.array(result)[:,2]\n        rot_error = np.array(result)[:,3]\n\n        trans_error_mean = np.mean(trans_error)\n        rot_error_mean = np.mean(rot_error)\n\n        # import ipdb;ipdb.set_trace()\n\n        return (rot_error_mean, trans_error_mean)\n\n# =======================\n\nfrom .evaluate_kitti import evaluate as kittievaluate\n\nclass KittiEvaluator(object):\n    def __init__(self):\n        super(KittiEvaluator, self).__init__()\n\n    # return rot_error, tra_error\n    def evaluate(self, gt_SEs, est_SEs):\n        # trajectory_scale(est_SEs, 0.831984631412)\n        error = kittievaluate(gt_SEs, est_SEs)\n        return error\n"
  },
  {
    "path": "VO_Module/thirdparty/tartanair_tools/evaluation/pose_est.txt",
    "content": "0.000000000000000000e+00 0.000000000000000000e+00 0.000000000000000000e+00 0.000000000000000000e+00 0.000000000000000000e+00 0.000000000000000000e+00 1.000000000000000000e+00\n-7.763581722974777222e-02 8.129438757896423340e-02 8.294846117496490479e-02 1.040334086665092687e-02 1.041169190809397287e-05 2.011712313020339732e-02 9.997435032193935367e-01\n-1.614615394973635265e-01 1.753936329237417158e-01 1.824119399153587007e-01 2.189289735848180471e-02 3.260965583645257884e-04 4.095062368656528229e-02 9.989212336112042179e-01\n-2.483997135085643793e-01 2.510054263822752985e-01 2.833032081283895498e-01 3.369437576438091830e-02 8.340466259779691837e-04 6.266394019408838556e-02 9.974653986514492310e-01\n-3.529906697922169379e-01 3.595898575063656288e-01 3.870853431034880776e-01 4.637325208655862507e-02 1.227550561596514080e-03 8.501253099674151159e-02 9.952993929278292073e-01\n-4.535691853102751248e-01 4.568637710855560918e-01 4.845526710044738561e-01 5.965438091144881216e-02 1.521359706053023028e-03 1.078180747714191229e-01 9.923781052491449373e-01\n-5.581615826024445282e-01 5.510385940212652045e-01 5.734740478287805310e-01 7.331615232253894943e-02 1.618413853996865165e-03 1.308376388366791765e-01 9.886878357407519191e-01\n-6.897704174794190290e-01 6.581356249561387539e-01 6.748434631430831887e-01 8.658215377582006989e-02 1.708541625585218663e-03 1.538210618132044571e-01 9.842965445244924449e-01\n-8.455515829656050641e-01 7.827321154762114652e-01 7.665332346157245347e-01 9.995978770471897201e-02 1.513542442906467460e-03 1.765521462832924382e-01 9.792012504960488917e-01\n-1.005513256527982735e+00 9.027695237376163195e-01 8.540858013618440880e-01 1.130726715079791306e-01 1.288185412497112490e-03 1.989259590578820736e-01 9.734687286525551819e-01\n-1.185129075147004274e+00 1.021053229676384566e+00 9.391665916590067331e-01 1.257653451526082322e-01 1.150079331193483694e-03 2.206728462822609149e-01 9.672048514541641273e-01\n-1.374462012916290554e+00 1.141221578215573240e+00 1.015970865367560094e+00 1.376554687585733461e-01 1.061026809043993544e-03 2.417534712645754424e-01 9.605233365418593960e-01\n-1.588499030350069452e+00 1.266209135639860373e+00 1.086002959009900071e+00 1.485755038267222716e-01 9.605313046758917573e-04 2.622085642178698661e-01 9.535046055003959520e-01\n-1.818806502634098043e+00 1.383276731247666813e+00 1.140712190299622009e+00 1.584588407539465338e-01 8.681071444247497352e-04 2.817861214627339073e-01 9.463015368426513918e-01\n-2.045776265470826250e+00 1.492418481673508657e+00 1.184797250600713614e+00 1.670675346700424002e-01 8.257189692240109700e-04 3.001841140278199149e-01 9.391364327290262493e-01\n-2.276180491460872535e+00 1.596256008567038975e+00 1.221639715698451978e+00 1.742704915296339196e-01 9.591303608554155227e-04 3.170547184699983312e-01 9.322580994966139789e-01\n-2.506512307163954123e+00 1.697691124429126175e+00 1.253975000882568303e+00 1.801102943798766620e-01 1.308365573539137326e-03 3.320161931722179216e-01 9.259178078324850070e-01\n-2.730647291904825469e+00 1.791590510575493456e+00 1.278466289637631537e+00 1.840968232324677878e-01 1.578886214964081739e-03 3.451396192693618192e-01 9.203175983449257691e-01\n-2.923433144178567922e+00 1.870891735631864616e+00 1.292601088431287737e+00 1.849707697653387994e-01 1.386025599471512292e-03 3.562485413351011987e-01 9.158989209312665691e-01\n-3.077175452596739635e+00 1.933593849915830720e+00 1.299696969678707736e+00 1.854755639593988203e-01 1.868600603979128421e-03 3.650181587589055865e-01 9.123360260273387645e-01\n-3.193939947754621311e+00 1.981891317735233304e+00 1.303578995604927293e+00 1.855183673014065560e-01 3.083188543593773021e-03 3.715047670010525604e-01 9.097019288038555862e-01\n-3.315409474942201840e+00 2.030990137869406187e+00 1.311135170562608199e+00 1.812982113234903048e-01 3.879075462185585434e-03 3.754939783009084153e-01 9.089115129713721819e-01\n-3.457097195304501103e+00 2.079057742802964626e+00 1.323314158036400512e+00 1.751551006930524568e-01 4.849743914728919456e-03 3.771605153527103349e-01 9.094212882393348796e-01\n-3.607751299212842433e+00 2.125597561155946114e+00 1.328744742853992244e+00 1.669760035300219270e-01 5.862731875882476289e-03 3.762797830799659016e-01 9.113167052387843858e-01\n-3.741661109607048896e+00 2.166749128476885389e+00 1.330438836879045406e+00 1.569512452791514689e-01 6.669659372063521142e-03 3.735049313371923141e-01 9.142296515067259710e-01\n-3.860063450797174944e+00 2.199894961373179303e+00 1.333838814317130472e+00 1.454407120026545708e-01 7.241853549464966934e-03 3.691224647884061572e-01 9.179014869378113728e-01\n-3.965440417418732100e+00 2.226800631160249289e+00 1.343206933663203984e+00 1.325379926970463584e-01 7.844176604592478091e-03 3.633626870690228605e-01 9.221386473454279420e-01\n-4.066402862077570290e+00 2.255844838276743314e+00 1.355485145997750829e+00 1.183286632454299964e-01 8.219612003103273987e-03 3.562999831573637755e-01 9.268123073828324898e-01\n-4.169311459254840813e+00 2.289886648958757487e+00 1.371346518212128496e+00 1.032299517681223161e-01 8.406974670792977805e-03 3.479357009271835111e-01 9.317798054429122789e-01\n-4.274304728659573449e+00 2.326110416854968665e+00 1.388732450883825464e+00 8.741415828963333690e-02 8.379913478480226913e-03 3.384163034407642878e-01 9.368900192068824184e-01\n-4.371023610733479003e+00 2.361730196758660583e+00 1.403553973261158161e+00 7.102109638379625056e-02 8.057980014233599719e-03 3.279150071870076122e-01 9.419993613653473430e-01\n-4.459560418429068918e+00 2.395030322184842575e+00 1.416461243442338258e+00 5.420612473697292849e-02 7.365064650816518024e-03 3.164921687723831201e-01 9.470164409778689674e-01\n-4.540001823203836828e+00 2.425599654086818990e+00 1.426464306582395425e+00 3.715621844980641908e-02 6.231494058011067053e-03 3.043837172282954362e-01 9.518041337804227231e-01\n-4.612358115392317437e+00 2.452776723440271756e+00 1.433268633649291468e+00 2.011834412594883451e-02 4.716985069882587492e-03 2.919181785674783702e-01 9.562200316515701015e-01\n-4.676197707866614373e+00 2.476170399256655941e+00 1.437578832081728653e+00 3.272165197888430091e-03 2.840839541992785672e-03 2.793353264558116611e-01 9.601838140965953672e-01\n-4.729394004887086389e+00 2.494799783342323884e+00 1.440516646926108590e+00 -1.318569206037614912e-02 7.089819845754987337e-04 2.668435421441125444e-01 9.636493737582385588e-01\n-4.773843758590919251e+00 2.507891700440353144e+00 1.442752113368175770e+00 -2.903920539287624045e-02 -1.910930719998760402e-03 2.545928327167661376e-01 9.666103197388770107e-01\n-4.810216717409360854e+00 2.516280950884616008e+00 1.445033489495043622e+00 -4.413449361689851524e-02 -5.156598890310192841e-03 2.426934570333589558e-01 9.690848176630005861e-01\n-4.842444961040081708e+00 2.521851936853974241e+00 1.448018661613891700e+00 -5.830208152581990710e-02 -9.081029144956875507e-03 2.314251854411013276e-01 9.710616495485874244e-01\n-4.866759795781309350e+00 2.525786235783391565e+00 1.452406291993692200e+00 -7.126999092386157586e-02 -1.369779941037953253e-02 2.210570242580389144e-01 9.725567772416677803e-01\n-4.884401443052239777e+00 2.527892111796247843e+00 1.457189468992783343e+00 -8.289824316857601072e-02 -1.915495834478810055e-02 2.119194481674736563e-01 9.735764284800602075e-01\n-4.892039541818142823e+00 2.529953841039938478e+00 1.458850563230165820e+00 -9.301414318055745145e-02 -2.547372208527273404e-02 2.043313470160121326e-01 9.741396701707516481e-01\n-4.899106108043921104e+00 2.532639924374405549e+00 1.459694477163018700e+00 -1.016629322170821970e-01 -3.248648335372286700e-02 1.980939191208750672e-01 9.743551761291968649e-01\n-4.913951589168281231e+00 2.534521876501546256e+00 1.461731588944155558e+00 -1.089088070086514509e-01 -4.010769518544383266e-02 1.929507514486798747e-01 9.743203648503796499e-01\n-4.933610942602353333e+00 2.538586854819794958e+00 1.464692314854086463e+00 -1.147749002202129304e-01 -4.828628938072188070e-02 1.886497650383399949e-01 9.741182319926873223e-01\n-4.958440654878941700e+00 2.543277612007893929e+00 1.468203406428834512e+00 -1.194863089348542767e-01 -5.696299705392537938e-02 1.853303060451857998e-01 9.737200862826957959e-01\n-4.990954677322402944e+00 2.549407909844580988e+00 1.471203394844951884e+00 -1.231642486268289260e-01 -6.604007246099961870e-02 1.828656214855920725e-01 9.731543130891747717e-01\n-5.025047938541398196e+00 2.558715939396833505e+00 1.473825988547360355e+00 -1.259017917447793344e-01 -7.542633386954311625e-02 1.811794706028058144e-01 9.724368823910578552e-01\n-5.056480018462073289e+00 2.564807758629558343e+00 1.475891196155413532e+00 -1.278915055890489927e-01 -8.509363100646011313e-02 1.800907271765929685e-01 9.715812114247180942e-01\n-5.086104798580855402e+00 2.569691283527485659e+00 1.477163312790321648e+00 -1.292293462264915427e-01 -9.496559244675582823e-02 1.794984267144049683e-01 9.705985276768369641e-01\n-5.112606255918975329e+00 2.573412687699331514e+00 1.477477854537477153e+00 -1.299627604284677995e-01 -1.049854785309249916e-01 1.792703541166686954e-01 9.695100505118784406e-01\n-5.134905255077595321e+00 2.576288036269610782e+00 1.477239630484135979e+00 -1.302426546338418811e-01 -1.150711451979672811e-01 1.792885473078411618e-01 9.683237916200010398e-01\n-5.153893624298311771e+00 2.578483882124743776e+00 1.476620330702864026e+00 -1.302009236249876412e-01 -1.251474567794172432e-01 1.794546117522611839e-01 9.670479499330235651e-01\n-5.170387700900536565e+00 2.580064156137910292e+00 1.475659244919312441e+00 -1.299670410286786204e-01 -1.351584452176034790e-01 1.796414632746508588e-01 9.656964250670172500e-01\n-5.184181027452599899e+00 2.581160090942109075e+00 1.474565384211478536e+00 -1.296418604936777075e-01 -1.450448905082182272e-01 1.797323884557865681e-01 9.642878788901542153e-01\n-5.193670199816169841e+00 2.581753477051173640e+00 1.473764585350773926e+00 -1.293351330843586777e-01 -1.547441736237192833e-01 1.795981723139647712e-01 9.628452851806021950e-01\n-5.199333265867458032e+00 2.582035217643015024e+00 1.473379856620376183e+00 -1.291569717635498993e-01 -1.641813293619758807e-01 1.791096871363017651e-01 9.613961617381699964e-01\n-5.202331774675752030e+00 2.581664544006828432e+00 1.473864297841081417e+00 -1.292272888139313625e-01 -1.732843541244645513e-01 1.782025435959828374e-01 9.599565502006950357e-01\n-5.206241793394302597e+00 2.582221202370767354e+00 1.474536803626558035e+00 -1.297041040826846792e-01 -1.820029342402989803e-01 1.766310062204095588e-01 9.585682842352059030e-01\n-5.210985438789853319e+00 2.583094789759607490e+00 1.474966989504564285e+00 -1.307007029242959195e-01 -1.902369471614826779e-01 1.743631391815418374e-01 9.572484572619643917e-01\n-5.216251160117276520e+00 2.583977407180919617e+00 1.475366210935058264e+00 -1.323205068189602929e-01 -1.979592096899689679e-01 1.712833846211577193e-01 9.560153302771712269e-01\n-5.222946233934185223e+00 2.586808942321393801e+00 1.472278643001111886e+00 -1.310237157238480776e-01 -2.045421318352779183e-01 1.680589194756306470e-01 9.553802323633658888e-01\n-5.231628991463434630e+00 2.589857794226577248e+00 1.469924268626294328e+00 -1.299914791537154501e-01 -2.105017348685536416e-01 1.642104059553242124e-01 9.548958446152637780e-01\n-5.242168825144799982e+00 2.592841460080200999e+00 1.468451453680363228e+00 -1.292111837068332103e-01 -2.159394456534998452e-01 1.599379638273054072e-01 9.545126345911275623e-01\n-5.253286415437917078e+00 2.595970513784641387e+00 1.467826428868046262e+00 -1.286807950362075514e-01 -2.209464468219945743e-01 1.552757326655797021e-01 9.542081801217947579e-01\n-5.265486490643125350e+00 2.599432535416068557e+00 1.467152445892538015e+00 -1.283580449028720871e-01 -2.256078437309221862e-01 1.503256341714759581e-01 9.539535620795475124e-01\n-5.278931683231727234e+00 2.602917166318048814e+00 1.466546231382643173e+00 -1.282128746978846989e-01 -2.299556577100002053e-01 1.452586887261335946e-01 9.537198972899648686e-01\n-5.294180719114427447e+00 2.606445447497604206e+00 1.466469015635006201e+00 -1.281738649061152646e-01 -2.340465156471444597e-01 1.402375308412729671e-01 9.534815137992896927e-01\n-5.312463140471031409e+00 2.609762618928178846e+00 1.467229721920807917e+00 -1.281673290126850717e-01 -2.379196270513008749e-01 1.354483648227918224e-01 9.532161404201969779e-01\n-5.335824573770256762e+00 2.613782928396423788e+00 1.469043526066431404e+00 -1.281189173127078307e-01 -2.416006561296493993e-01 1.310745825024880462e-01 9.529081867508989445e-01\n-5.363259463899353818e+00 2.617851172109413760e+00 1.471131569469693146e+00 -1.280001689701116829e-01 -2.451563298382018197e-01 1.272199112235238294e-01 9.525383605911197371e-01\n-5.395411344443875379e+00 2.623212074403216576e+00 1.472248485541352014e+00 -1.277061673877437353e-01 -2.486749857660476848e-01 1.239774978389931309e-01 9.520931477990380865e-01\n-5.426128985633432933e+00 2.629509303787030738e+00 1.472886535222979631e+00 -1.272485630563925385e-01 -2.522551300913905559e-01 1.214382283999674711e-01 9.515396978379735415e-01\n-5.452652039613852253e+00 2.636104068030554970e+00 1.473580777471113379e+00 -1.265948281006319676e-01 -2.558473110227643121e-01 1.197640264486956596e-01 9.508797857273025844e-01\n-5.472306931796175888e+00 2.641829902721481105e+00 1.473873320383656482e+00 -1.256680327166950772e-01 -2.594724547148206106e-01 1.191192015543088567e-01 9.501010974737226222e-01\n-5.492777734979259918e+00 2.648747575407238042e+00 1.473959231064704500e+00 -1.244619490961244718e-01 -2.631815118648019314e-01 1.198660794814391944e-01 9.491452656899548312e-01\n-5.517309030986859320e+00 2.656660512910526073e+00 1.473909882633906099e+00 -1.229588360211476133e-01 -2.670171479008756621e-01 1.220429262392918324e-01 9.479917596835117921e-01\n-5.548501007034063015e+00 2.665854748006321273e+00 1.473972335360250963e+00 -1.210092705313811912e-01 -2.710428319108487139e-01 1.256652081050372294e-01 9.466259477090569474e-01\n-5.582659995289544597e+00 2.676549627306799017e+00 1.473410706142274762e+00 -1.184397636966367240e-01 -2.754753876080917596e-01 1.309016614379956145e-01 9.449603036347121732e-01\n-5.618542000812452919e+00 2.688346823076197545e+00 1.473815846312817035e+00 -1.152002555259703243e-01 -2.803413333399834562e-01 1.378292494260122403e-01 9.429425343495222434e-01\n-5.658800331255713800e+00 2.701072122771759787e+00 1.476535456259537193e+00 -1.111809696889956428e-01 -2.856535347335066866e-01 1.466344650116992443e-01 9.404993667055564499e-01\n-5.723162393434017226e+00 2.711850001969680513e+00 1.472010511799559440e+00 -9.645960069527406699e-02 -2.899736214586458583e-01 1.603600069216811475e-01 9.385602750540950057e-01\n-5.789886399037957432e+00 2.724914339993221191e+00 1.467559068109455245e+00 -7.961234498813223037e-02 -2.944040355605375137e-01 1.761043348999501434e-01 9.359355020986513951e-01\n-5.857801027110975056e+00 2.744695431095274696e+00 1.463945204565434421e+00 -6.075934553055403753e-02 -2.988044004969594991e-01 1.932606735103165330e-01 9.325633481775772449e-01\n-5.928718842828847535e+00 2.767996982110530357e+00 1.460667842684073348e+00 -4.041363023151172545e-02 -3.030217965527199353e-01 2.116615388665777919e-01 9.283015556563347648e-01\n-6.002894602593839224e+00 2.792273267216474952e+00 1.458903479340398990e+00 -1.906988129351004299e-02 -3.068992941963777921e-01 2.311642366215765632e-01 9.230450172788735586e-01\n-6.080423592056320103e+00 2.816755985211592872e+00 1.457840699040749088e+00 2.989901128715029190e-03 -3.103978479901604026e-01 2.515253384808229797e-01 9.167219268166566515e-01\n-6.159821503433136058e+00 2.842283901774936172e+00 1.456838883270557883e+00 2.555327984341005526e-02 -3.134828696451882335e-01 2.725158317531349850e-01 9.092911994515439078e-01\n-6.242220272728821406e+00 2.869195785452348435e+00 1.457031532612975910e+00 4.835426017865434439e-02 -3.160287452290629906e-01 2.938780975588026201e-01 9.007903192073739573e-01\n-6.328228979922918107e+00 2.897916089429688480e+00 1.459431885899282078e+00 7.112281369337754289e-02 -3.179164658780405661e-01 3.153813211739048272e-01 8.912940786818626115e-01\n-6.418319400752959147e+00 2.929363133766030192e+00 1.463556676178051852e+00 9.361902027674687266e-02 -3.191164931957644613e-01 3.367341951773196729e-01 8.809143376209914722e-01\n-6.512459485064193032e+00 2.961652060875547221e+00 1.469992759476173250e+00 1.154273123828760544e-01 -3.196110203343623946e-01 3.576625340537895603e-01 8.698291177469383850e-01\n-6.608705668912721265e+00 2.993374042313872163e+00 1.477422440200679254e+00 1.362564011417555232e-01 -3.194120827828730858e-01 3.779349820944927774e-01 8.582395397556208394e-01\n-6.708860129414741635e+00 3.029684950161678270e+00 1.483726567384882733e+00 1.557847355957741042e-01 -3.186315622378103063e-01 3.972704498662247841e-01 8.463929817961677315e-01\n-6.819298594650499368e+00 3.074051487095454505e+00 1.490085988826882257e+00 1.736994998816114855e-01 -3.172153833985199012e-01 4.153375084553274088e-01 8.346840542764281112e-01\n-6.937727501343463388e+00 3.123999412892846994e+00 1.495942713530356682e+00 1.897426385614484623e-01 -3.152290908872911745e-01 4.316833056047169603e-01 8.235761676614492544e-01\n-7.053690389257425863e+00 3.175431624220932392e+00 1.500371635520052482e+00 2.035718323494609405e-01 -3.128428333350659618e-01 4.460332176324769415e-01 8.134753052567540443e-01\n-7.160507266271090465e+00 3.219836099753031089e+00 1.503678186645701187e+00 2.147192789143497760e-01 -3.101588794608615141e-01 4.586560715210674100e-01 8.045691677036902467e-01\n-7.263857222743489217e+00 3.259420686638322184e+00 1.507104829137044577e+00 2.230030551458123678e-01 -3.071117296537569374e-01 4.694030734605031951e-01 7.972531801455003952e-01\n-7.379427554787534760e+00 3.303978953117806316e+00 1.512684161807263727e+00 2.285458026868785741e-01 -3.033655638342385719e-01 4.783511397594756853e-01 7.917803892531537491e-01\n-7.513956051602586506e+00 3.354457427853559270e+00 1.517813172094303109e+00 2.313569936374561264e-01 -2.988858572686310944e-01 4.853137690080703837e-01 7.884234824257249086e-01\n-7.647871124811962851e+00 3.403524157911047343e+00 1.519694781159322883e+00 2.307807859810244722e-01 -2.941287420864104329e-01 4.897210142813168132e-01 7.876558226717300659e-01\n-7.783024520160962467e+00 3.454887356183196978e+00 1.531881838661782735e+00 2.270182624484105294e-01 -2.889180509553187504e-01 4.918595901670846371e-01 7.893434444840518038e-01\n-7.932927031712694088e+00 3.515541344819415048e+00 1.544813960111571349e+00 2.209137782161527952e-01 -2.832097413707863054e-01 4.918438846262578878e-01 7.931448797570244125e-01\n-8.066793397270458854e+00 3.569413410737276582e+00 1.559274798339227663e+00 2.119618830049600222e-01 -2.773903912958500806e-01 4.906034406410121340e-01 7.983951694859114934e-01\n-8.192223267129946862e+00 3.619156454846514492e+00 1.574389835259532466e+00 2.007164604924963069e-01 -2.714268003444554322e-01 4.875667565567802231e-01 8.051825387388809041e-01\n-8.320078886071526014e+00 3.669773930832634701e+00 1.589713284153562167e+00 1.873456602548720096e-01 -2.654088840600973831e-01 4.830340534420075049e-01 8.131037354177889087e-01\n-8.445641803750774557e+00 3.718161069698102228e+00 1.602382435863983989e+00 1.722686950193424715e-01 -2.592978863788403254e-01 4.770453874402176830e-01 8.218976054209284898e-01\n-8.585898597663639720e+00 3.763842337255594028e+00 1.612724215029670782e+00 1.559540902868197521e-01 -2.529943279552718249e-01 4.697196254227078427e-01 8.312854751181643076e-01\n-8.744284886021782555e+00 3.810431377428940003e+00 1.623718323368587235e+00 1.385303921116263770e-01 -2.465440258096578408e-01 4.612076909196240471e-01 8.410188561040446986e-01\n-8.917256787043321253e+00 3.857984143852772885e+00 1.635529520697025729e+00 1.200997614827219034e-01 -2.400285635394314998e-01 4.518427327995526710e-01 8.507645647184876037e-01\n-9.104064759810293950e+00 3.909468736568438185e+00 1.647792240600521207e+00 1.010256813838104617e-01 -2.334802681253919932e-01 4.416485369603997957e-01 8.603645783314409767e-01\n-9.301241223158305260e+00 3.966133280590436350e+00 1.659879276563957395e+00 8.162298523277151940e-02 -2.270393438443374656e-01 4.308338925838269828e-01 8.695819940915584523e-01\n-9.506898456077562898e+00 4.033050506019718817e+00 1.671615796186202152e+00 6.232921915732245188e-02 -2.207809463892332902e-01 4.195279425445178068e-01 8.782750198852098400e-01\n-9.719084547238489691e+00 4.107758244306594975e+00 1.683041549236502066e+00 4.339485462197354565e-02 -2.147223909901595229e-01 4.081630697574083477e-01 8.862358301817121475e-01\n-9.937901626828326229e+00 4.184882732919266601e+00 1.691597128612665424e+00 2.514333870120135858e-02 -2.090149953532211835e-01 3.970576489093294303e-01 8.933228028578739099e-01\n-1.016759103732679392e+01 4.263001199913111883e+00 1.695061943809942129e+00 7.951056979035085390e-03 -2.037524638280196476e-01 3.863944356921051870e-01 8.995114907978111196e-01\n-1.040311776555026668e+01 4.342138223454597323e+00 1.694155376650493539e+00 -7.860991495868187989e-03 -1.991039859389698297e-01 3.761993446063320312e-01 9.048589492432858039e-01\n-1.062897301257094007e+01 4.421929781002599036e+00 1.690288951959063590e+00 -2.214107243025818447e-02 -1.953405400448643969e-01 3.664771572666042365e-01 9.094207967402290205e-01\n-1.083888411301165178e+01 4.502998187798571195e+00 1.686517435052399483e+00 -3.432563094326723102e-02 -1.924284141359653699e-01 3.578962584641444677e-01 9.130734760142072970e-01\n-1.102600989759129213e+01 4.574895040257780821e+00 1.683943445938448136e+00 -4.432764650310910826e-02 -1.905976866897620137e-01 3.511897429252484604e-01 9.156272141432794109e-01\n-1.119162909577845610e+01 4.637566012598074217e+00 1.683328669899319951e+00 -5.190637318312452120e-02 -1.897319204890198785e-01 3.464870459511551481e-01 9.171990500328939255e-01\n-1.138509586620138769e+01 4.700995911950154316e+00 1.682164000735672182e+00 -5.716773658474903069e-02 -1.900562658324461418e-01 3.437203900201822315e-01 9.178597923492943789e-01\n-1.158554687652896398e+01 4.773839985834662514e+00 1.684945256451874096e+00 -5.996103732729100855e-02 -1.911621616282371816e-01 3.424860699307142875e-01 9.179133040169402680e-01\n-1.177760597264674303e+01 4.855169503782111207e+00 1.688083280889883353e+00 -6.048066505920299957e-02 -1.931844251355316622e-01 3.427646024985401829e-01 9.173517037762234372e-01\n-1.196887591957389496e+01 4.947745171815075338e+00 1.686750522816761855e+00 -5.925859327901381729e-02 -1.960387045525514016e-01 3.442936519395072281e-01 9.162526822346890309e-01\n-1.216992391604054902e+01 5.054905297112563645e+00 1.685436264709414989e+00 -5.622420424806187644e-02 -1.994930407666681560e-01 3.469751204847852932e-01 9.146854551281152768e-01\n-1.236532759982683061e+01 5.162857071153237776e+00 1.682019361756213582e+00 -5.158909614579330200e-02 -2.035015282505595879e-01 3.506607040282821997e-01 9.126678623466392137e-01\n-1.256170608523899901e+01 5.273156950802071030e+00 1.679515879409670953e+00 -4.537404264791386477e-02 -2.079235185402558694e-01 3.553344735306013802e-01 9.101902459545322399e-01\n-1.276708765983067906e+01 5.389368126411258508e+00 1.681734725436552669e+00 -3.773606152303884964e-02 -2.125714885631528328e-01 3.607183884419826736e-01 9.073430853038946253e-01\n-1.297045639587896915e+01 5.502656323061654753e+00 1.684277003464522693e+00 -2.895915841600426449e-02 -2.175540603194260902e-01 3.667778982942412891e-01 9.040494676300264709e-01\n-1.316619284720094640e+01 5.616050585154817476e+00 1.685634018354128516e+00 -1.912370531618038869e-02 -2.226372597372509310e-01 3.730394864934088450e-01 9.005044928755971956e-01\n-1.337143560244176044e+01 5.735008513802350549e+00 1.690148906924720640e+00 -8.392904909194753849e-03 -2.277444471868876330e-01 3.796126924332511310e-01 8.966359897929240264e-01\n-1.356737765708902188e+01 5.849611986405886199e+00 1.694239201507259596e+00 3.188069272633895900e-03 -2.328242933347296761e-01 3.861322106115112618e-01 8.925718311500835389e-01\n-1.377000282528432784e+01 5.965616664818147896e+00 1.699851328706560638e+00 1.545742103295346184e-02 -2.377059136115166060e-01 3.925069498358597642e-01 8.883665491224195243e-01\n-1.398212489561399607e+01 6.084928747493433043e+00 1.708285859510020321e+00 2.820644182687547311e-02 -2.423252529499348162e-01 3.987638062806674322e-01 8.840080159246346270e-01\n-1.420648560532310078e+01 6.210423501976889860e+00 1.718109657231867038e+00 4.128077843900963134e-02 -2.466187100076117078e-01 4.048654964394661215e-01 8.795219754325778183e-01\n-1.443425241573653572e+01 6.334786491546755549e+00 1.725589570138854167e+00 5.455567918078327305e-02 -2.505771213294181732e-01 4.106165240693651630e-01 8.750021179724133402e-01\n-1.466078662471714722e+01 6.456107463720189621e+00 1.731439103688600323e+00 6.788851507020579601e-02 -2.541798207114213670e-01 4.158866153694868451e-01 8.705296904758311749e-01\n-1.488285297923898121e+01 6.573529320482816907e+00 1.737718214085419266e+00 8.109585000858207660e-02 -2.573371237995916716e-01 4.204963649265053838e-01 8.662469212230400339e-01\n-1.509735422230190238e+01 6.686039798413209390e+00 1.743139241988748367e+00 9.393535441045894330e-02 -2.599591505149226878e-01 4.243821918820579464e-01 8.622627143897424462e-01\n-1.530865095285013311e+01 6.796819388747013413e+00 1.746061735856029085e+00 1.063152694493233186e-01 -2.619316692924129608e-01 4.275231495756733335e-01 8.586691296852853039e-01\n-1.551262471361659934e+01 6.907480535836007185e+00 1.748239987247944383e+00 1.182349415536220888e-01 -2.632263886307654177e-01 4.300142524946435896e-01 8.554647568458139117e-01\n-1.570625846627583577e+01 7.013312466228680542e+00 1.750445888451903187e+00 1.298043062854738749e-01 -2.639090550059828288e-01 4.318805497222688583e-01 8.526323214820138441e-01\n-1.589019998778768716e+01 7.112664845566693650e+00 1.752781886349465967e+00 1.409289133858263876e-01 -2.641656477315370011e-01 4.330758048961919071e-01 8.501768791463034658e-01\n-1.606792120950874647e+01 7.208294803460730371e+00 1.754591869893346701e+00 1.517765163723192312e-01 -2.638692742451970163e-01 4.336451467018893058e-01 8.481088428129829326e-01\n-1.624434227101607320e+01 7.303142846534119492e+00 1.753898109638208691e+00 1.623957051178717692e-01 -2.630526253297322259e-01 4.335576118085632813e-01 8.464387588780707405e-01\n-1.641625602811456019e+01 7.395043159563359225e+00 1.751152354780340259e+00 1.726525697619735733e-01 -2.619629885775675571e-01 4.328739764729817585e-01 8.450955121849976770e-01\n-1.658587085178702480e+01 7.485826733257320953e+00 1.748231259560814044e+00 1.826036761368338701e-01 -2.606393656664650615e-01 4.315508758716597448e-01 8.440892646836253288e-01\n-1.675089644930930177e+01 7.575510349925608011e+00 1.745856667694209330e+00 1.922807357009022056e-01 -2.591184385917666422e-01 4.297045137176721541e-01 8.433502304484872258e-01\n-1.691506089922895484e+01 7.665309506093168856e+00 1.743384547774412763e+00 2.017770353694364749e-01 -2.575116521304156580e-01 4.273549743327898498e-01 8.428174999857650507e-01\n-1.708644637763754659e+01 7.758788866789966043e+00 1.742004140810507806e+00 2.111321666661664098e-01 -2.558397527854995857e-01 4.245088266948168765e-01 8.424733385149421050e-01\n-1.726784494652930135e+01 7.856822001082897522e+00 1.742654404360780562e+00 2.202197341042913814e-01 -2.541798948408322545e-01 4.211774153635236551e-01 8.423213530536949323e-01\n-1.746024801472902865e+01 7.960010265021137954e+00 1.745074856908168881e+00 2.289213759479810650e-01 -2.526004026647560297e-01 4.175357519182459343e-01 8.422895932772127559e-01\n-1.766654731231349373e+01 8.070327666174712533e+00 1.749793661338604478e+00 2.372063226794104418e-01 -2.511936926804049786e-01 4.136414953630123126e-01 8.423392565676695032e-01\n-1.787788669118211615e+01 8.183003558841669189e+00 1.755478918113403175e+00 2.450457413536536733e-01 -2.501033031262356321e-01 4.096916862187967578e-01 8.423499753459694483e-01\n-1.809178068879210954e+01 8.297254115051348577e+00 1.760518962209867366e+00 2.524429972134340505e-01 -2.493763715999471331e-01 4.056703627689585701e-01 8.423273410439073849e-01\n-1.829889634534535148e+01 8.414415868617682648e+00 1.763164725088491425e+00 2.592251936228366360e-01 -2.490581846075268502e-01 4.017012901080917464e-01 8.422637539869913814e-01\n-1.851064610958139767e+01 8.534587540429054542e+00 1.764080181755627086e+00 2.655126382578260613e-01 -2.491929627978202721e-01 3.976523144453786296e-01 8.421866733400295013e-01\n-1.872454699617393103e+01 8.657280115236002160e+00 1.765527871483244526e+00 2.713811710415635625e-01 -2.498018764759534494e-01 3.935295657386952417e-01 8.420722093215934345e-01\n-1.894476973094467809e+01 8.784598810057248741e+00 1.768893760754383537e+00 2.767423065037515340e-01 -2.509284107718010581e-01 3.893340918734590206e-01 8.419426592142716936e-01\n-1.916930753403601884e+01 8.909285765942943414e+00 1.783316449746438659e+00 2.754078127414572585e-01 -2.555650128083557515e-01 3.828539219274156302e-01 8.439548559210982015e-01\n-1.939833876380693667e+01 9.043023693463442925e+00 1.795814343152166925e+00 2.741002434342232896e-01 -2.604431742157352625e-01 3.764380432859956715e-01 8.457734172403018613e-01\n-1.963030247248972771e+01 9.185783372552252857e+00 1.806329673449146300e+00 2.727671470290222167e-01 -2.654510008092491047e-01 3.701835801397498904e-01 8.474065255370455407e-01\n-1.985929403658107972e+01 9.327231473640164694e+00 1.814036488740335740e+00 2.714815194294271095e-01 -2.705141545889362398e-01 3.640393622045553501e-01 8.488787256893001176e-01\n-2.008724920614000098e+01 9.470197801790330772e+00 1.819776077373240097e+00 2.702972236686065344e-01 -2.755438478847290207e-01 3.581381006992591653e-01 8.501481949323179688e-01\n-2.032193039518956112e+01 9.621574230777977021e+00 1.825137553906702736e+00 2.692228019766066960e-01 -2.804239749088110467e-01 3.526741685036900997e-01 8.511769884460007596e-01\n-2.055983410568753911e+01 9.794256163438852525e+00 1.827306526060864522e+00 2.682162956675854248e-01 -2.850021063575245428e-01 3.477638855419329378e-01 8.519941087514807387e-01\n-2.080293224004554631e+01 9.972464334757884075e+00 1.829046400636300307e+00 2.672929664477728950e-01 -2.892413510317480285e-01 3.434828989686284917e-01 8.525920906990737125e-01\n-2.104319455191703980e+01 1.015193624681640117e+01 1.830505407648819860e+00 2.665293772039856735e-01 -2.930953321927718958e-01 3.398652204467554339e-01 8.529646562564245915e-01\n-2.127315204145920546e+01 1.034196338290001549e+01 1.829235382877234306e+00 2.661559915932656395e-01 -2.962545926634149174e-01 3.368958021106880918e-01 8.531677962679651284e-01\n-2.149062860136037401e+01 1.053373496479204618e+01 1.827213082327507676e+00 2.661038993072872283e-01 -2.986506387292243714e-01 3.347622233780889744e-01 8.531885073889062809e-01\n-2.171292379071395828e+01 1.072679453505857339e+01 1.826920523683371211e+00 2.661970591574436273e-01 -3.001603278758976923e-01 3.337948908485642852e-01 8.530086441499495908e-01\n-2.189600021112985573e+01 1.091582039776040247e+01 1.831307815889416490e+00 2.661770342769272935e-01 -3.005621832023218087e-01 3.342485374222869399e-01 8.526957074314620577e-01\n-2.206506251410940322e+01 1.109854080964264256e+01 1.836749905245590231e+00 2.663409260383603483e-01 -2.999053713265300014e-01 3.355388451102992997e-01 8.523689739125704934e-01\n-2.221763032385653958e+01 1.127820034525780635e+01 1.843343858713348604e+00 2.667725878069750478e-01 -2.981830404836873227e-01 3.379075340574845820e-01 8.519023768153046738e-01\n-2.234894315407058230e+01 1.147270415594502246e+01 1.843866628129394725e+00 2.676971524061693697e-01 -2.950622061617062530e-01 3.413938183935630866e-01 8.513088127639103497e-01\n-2.247386418036266420e+01 1.168154878226672722e+01 1.838370263703727359e+00 2.688546026644202946e-01 -2.906278576088964782e-01 3.454956517088636492e-01 8.508144985039610697e-01\n-2.259389337586892665e+01 1.190418644415488103e+01 1.838890700189365734e+00 2.593184761901075053e-01 -2.888925775979807042e-01 3.457696129264617446e-01 8.542471993748459447e-01\n-2.267702201622588731e+01 1.216089715596706355e+01 1.843454210563671092e+00 2.478898442015371739e-01 -2.860717404439759859e-01 3.474433750659513542e-01 8.579024277992634007e-01\n-2.274279138435072767e+01 1.244641240095573664e+01 1.844891758709419571e+00 2.350113954258568061e-01 -2.820010737368858766e-01 3.503205816576961951e-01 8.616962368834414354e-01\n-2.278776095047748029e+01 1.274748733955873803e+01 1.835676297077167174e+00 2.202462408517593673e-01 -2.770604558117971128e-01 3.543508626105592030e-01 8.655428624579093455e-01\n-2.279386004297854740e+01 1.306813583639917020e+01 1.834061530233466852e+00 2.036987851021139495e-01 -2.712513536126683333e-01 3.588190722062826188e-01 8.695851084366361672e-01\n-2.278229110269767332e+01 1.337783685125774547e+01 1.836618388344035457e+00 1.856512666883281815e-01 -2.643068830537648739e-01 3.638748649299665128e-01 8.736535110686377559e-01\n-2.277482624181896043e+01 1.367788348151518818e+01 1.843272471041611071e+00 1.662779501905558566e-01 -2.563450872855653762e-01 3.691014452839521676e-01 8.777259605980322066e-01\n-2.277517771992877016e+01 1.396731596792628061e+01 1.848943435838783289e+00 1.459242359544663803e-01 -2.476261045319048115e-01 3.742100104701540642e-01 8.816769275250099236e-01\n-2.277891014895916655e+01 1.424863148173696814e+01 1.855507995309751523e+00 1.248368063514628812e-01 -2.381565662526234917e-01 3.797117746949031369e-01 8.851644458579459585e-01\n-2.278123831349811113e+01 1.452426181633606639e+01 1.868045646144445682e+00 1.032021173666537867e-01 -2.278694164594527172e-01 3.852498782419169210e-01 8.882608259442732468e-01\n-2.279374700624046923e+01 1.481405841726335737e+01 1.886702130759408291e+00 8.099637708244554479e-02 -2.170287580511503500e-01 3.911035793876907474e-01 8.907165682039777099e-01\n-2.281929122668881504e+01 1.511389860255536099e+01 1.909525084692540009e+00 5.810858941600706429e-02 -2.058242624457075065e-01 3.971769791025749341e-01 8.924741634270476620e-01\n-2.286619277585237953e+01 1.543078205055002883e+01 1.936867770270033873e+00 3.522591846294927803e-02 -1.941157524976541426e-01 4.032522840365893591e-01 8.935690979229948816e-01\n-2.292728992030420443e+01 1.575137801941480475e+01 1.967793013318889006e+00 1.274691221836536832e-02 -1.820988605748549427e-01 4.089524268852030020e-01 8.941114926427708998e-01\n-2.299970283838371543e+01 1.607013826214909002e+01 2.003532377978304080e+00 -9.192614801675663347e-03 -1.696025980915364106e-01 4.142256496517094932e-01 8.941853775339785315e-01\n-2.308401849355340474e+01 1.639451031089354416e+01 2.044617845076738050e+00 -3.079224063408317683e-02 -1.570274799098854701e-01 4.190687514791211488e-01 8.937424258576105451e-01\n-2.317791519790469579e+01 1.671692564319279484e+01 2.086556150440285418e+00 -5.170548063332913724e-02 -1.445299529190750831e-01 4.234558570874848993e-01 8.928172885769531941e-01\n-2.328381015351661532e+01 1.704096193805269266e+01 2.128948609238156653e+00 -7.189672916997863483e-02 -1.323312869182792229e-01 4.270045605427215119e-01 8.916200578594382087e-01\n-2.340427795004438138e+01 1.735701626761366967e+01 2.171373466696040477e+00 -9.112431622345168458e-02 -1.205138629086791729e-01 4.296235839130483902e-01 8.902787695180095495e-01\n-2.353721495216070636e+01 1.764163672899979218e+01 2.210276193991378424e+00 -1.088210540981210811e-01 -1.092261746711385290e-01 4.313071902192137652e-01 8.889328804280178797e-01\n-2.368482889535566827e+01 1.788736550815216830e+01 2.241025979305187654e+00 -1.249783686403358601e-01 -9.859504380821511316e-02 4.321472169235637262e-01 8.876418983541274343e-01\n-2.384607928896862816e+01 1.811242521096227520e+01 2.266084136725431186e+00 -1.394825025042187583e-01 -8.852640207265864702e-02 4.321040839500001618e-01 8.865628536497245360e-01\n-2.401887021275577538e+01 1.831890565421714356e+01 2.279919748837222038e+00 -1.522484236699693239e-01 -7.954755114421421802e-02 4.316803821504608396e-01 8.855193733080354290e-01\n-2.417563814101417563e+01 1.849465333577828829e+01 2.280101357735958345e+00 -1.568609837457968781e-01 -6.905650246495133315e-02 4.320591088014251735e-01 8.854098853287528659e-01\n-2.435465239258103409e+01 1.866788034911684591e+01 2.278833551147209313e+00 -1.607272140386094283e-01 -6.017316194805825968e-02 4.319610751780899593e-01 8.854126046456390897e-01\n-2.456409566518592769e+01 1.884827946901418727e+01 2.269796614147971958e+00 -1.636609697667866792e-01 -5.291919348364309411e-02 4.311929497177032777e-01 8.857128064040995508e-01\n-2.479778785919083361e+01 1.903629896227497653e+01 2.257981623479938804e+00 -1.659125060591743195e-01 -4.713767011932128853e-02 4.300026166831247831e-01 8.861990328509232739e-01\n-2.505276016903864189e+01 1.922914089322856057e+01 2.243173278804790449e+00 -1.677053219712714149e-01 -4.237869624486044484e-02 4.284738455514192079e-01 8.868421699997788288e-01\n-2.531606684592797407e+01 1.942574769930528333e+01 2.229085231275929058e+00 -1.691240220535058791e-01 -3.869162175143402160e-02 4.265967679199939577e-01 8.876458319017992427e-01\n-2.557257251407279952e+01 1.962250513150229736e+01 2.216540469105335198e+00 -1.700231185885573981e-01 -3.605937356402070387e-02 4.245757510827790626e-01 8.885534334973053117e-01\n-2.580221087760002874e+01 1.982022611720514860e+01 2.213541204118973926e+00 -1.706118174258889064e-01 -3.421548493935728380e-02 4.221743612690299075e-01 8.896570216912565998e-01\n-2.601146817578661441e+01 2.002178072754179183e+01 2.220440591652892426e+00 -1.708795840907891550e-01 -3.305780614654894867e-02 4.195332938165493575e-01 8.908979080478455215e-01\n-2.620146402382770745e+01 2.022263752058559660e+01 2.232834173233681163e+00 -1.707515192904049961e-01 -3.259258493898324616e-02 4.166296946298410631e-01 8.923011074035356316e-01\n-2.637627819712720978e+01 2.042627191949194554e+01 2.246709810052124556e+00 -1.704933168163576263e-01 -3.283554693023437582e-02 4.135249830121538461e-01 8.937845782005444661e-01\n-2.654141434367915409e+01 2.064312858172237952e+01 2.261016826810119174e+00 -1.699567631640833132e-01 -3.375044009679307316e-02 4.102752691268951035e-01 8.953489432173035167e-01\n-2.669147582367332916e+01 2.090214578367661247e+01 2.266700491683564245e+00 -1.690759921526795440e-01 -3.505602877705428499e-02 4.072087389723742512e-01 8.968641789317577384e-01\n-2.680711447038204653e+01 2.118769864213084730e+01 2.259189892130341271e+00 -1.681949656527562675e-01 -3.650877260619080772e-02 4.037426557047869569e-01 8.985373429708651827e-01\n-2.691264022015269930e+01 2.147122141299361786e+01 2.251254662706501097e+00 -1.673685360070890360e-01 -3.799697171692978381e-02 4.002503107457208720e-01 9.001908829296069170e-01\n-2.701700745394519387e+01 2.175605453038072312e+01 2.244111561578600700e+00 -1.666208604647388680e-01 -3.938839449346565741e-02 3.967915708431682953e-01 9.017995479560309002e-01\n-2.711597343636304203e+01 2.203754618878080151e+01 2.239399721771621277e+00 -1.660184516917547204e-01 -4.057493926753620583e-02 3.935196243600725396e-01 9.032905269722538710e-01\n-2.721313862380371518e+01 2.231502709860468059e+01 2.233579569352742045e+00 -1.655366737945723477e-01 -4.146849096221055797e-02 3.903769855378326770e-01 9.047008969436354242e-01\n-2.730451173334633808e+01 2.258723126943073822e+01 2.232524467267274826e+00 -1.652420270226250820e-01 -4.183748958383041311e-02 3.873398158884339693e-01 9.060422117107009843e-01\n-2.739618781129729186e+01 2.285659210566472765e+01 2.229679291440306965e+00 -1.651158750932687769e-01 -4.190338686780778477e-02 3.845494507040361776e-01 9.072499716299705641e-01\n-2.747385408025323983e+01 2.309855032345035397e+01 2.227974427794786827e+00 -1.632434010926707146e-01 -4.056829921507414810e-02 3.822183543045849508e-01 9.086335181036162556e-01\n-2.750097978566391532e+01 2.334479347695600993e+01 2.221391878575035950e+00 -1.621176179697699782e-01 -3.882819126368952656e-02 3.796792465634049041e-01 9.099746408228959194e-01\n-2.726825350965150818e+01 2.325151116060946777e+01 2.175983573215688693e+00 -1.613709937062294542e-01 -3.628260994147344126e-02 3.772982732247785465e-01 9.112019044525625500e-01\n-2.702456224413602115e+01 2.309912761978292295e+01 2.139766417121252040e+00 -1.613481927529301363e-01 -3.349904736413328310e-02 3.751107976647562459e-01 9.122151078617489750e-01\n-2.679101439840390597e+01 2.293399738099144969e+01 2.103119306761279450e+00 -1.616097877716584919e-01 -3.051899457695839493e-02 3.729867941334186754e-01 9.131438330849267482e-01\n-2.657740017191866500e+01 2.277437930122923149e+01 2.078001530922096940e+00 -1.620419907806670556e-01 -2.735605387094369040e-02 3.708395914350989253e-01 9.140415652853018935e-01\n-2.637159897173790313e+01 2.262100277940090010e+01 2.066049215829654173e+00 -1.627234156896967820e-01 -2.407343051419220947e-02 3.688004373214123222e-01 9.148375486076620877e-01\n-2.615837650587571872e+01 2.247488982876452113e+01 2.071833704459263625e+00 -1.635572428108897081e-01 -2.066514976553302310e-02 3.666721118914089139e-01 9.156273725873216307e-01\n-2.594072159916872522e+01 2.231161067952020360e+01 2.083107860750283979e+00 -1.646165804832455115e-01 -1.722983316112723304e-02 3.645091161472031605e-01 9.163719516309467572e-01\n-2.574886541918168348e+01 2.215301706047239350e+01 2.091090146796715121e+00 -1.658629634766780880e-01 -1.383545216156034825e-02 3.623977673111308251e-01 9.170419007802971256e-01\n-2.556440423704056997e+01 2.198430157723035450e+01 2.098127451992665815e+00 -1.672358011107535902e-01 -1.058012178033332536e-02 3.600494200502910580e-01 9.177606457015089481e-01\n-2.538037160207138498e+01 2.181392663014435840e+01 2.108677686882134417e+00 -1.686931897332309416e-01 -7.448179926461856101e-03 3.575327469053996565e-01 9.185082539839041216e-01\n-2.520276902143701037e+01 2.165310427306733487e+01 2.120402607732097877e+00 -1.703342537738301854e-01 -4.561949277056037005e-03 3.549010508834821720e-01 9.192445919532085119e-01\n-2.502419845774825191e+01 2.148206206072395119e+01 2.130397958085426868e+00 -1.720280497022145250e-01 -2.082080681697975888e-03 3.520872298862169902e-01 9.200198588567216618e-01\n-2.486219346498838689e+01 2.132068850602420795e+01 2.134670903847158741e+00 -1.734560119174085036e-01 -8.512613343039085239e-05 3.491701646239731005e-01 9.208654370189738314e-01\n-2.471280762926851438e+01 2.118007644514408483e+01 2.144139937175970179e+00 -1.750086373768262038e-01 1.603936758375859323e-03 3.463092364640772969e-01 9.216503036123622206e-01\n-2.456835475227538268e+01 2.103812656267921000e+01 2.152434445001956576e+00 -1.763108370000965319e-01 2.732061531323511702e-03 3.431077662199614187e-01 9.225963561061628626e-01\n-2.442264628234016399e+01 2.089420069466747876e+01 2.161781400049501922e+00 -1.774873368601994905e-01 3.238134741228041770e-03 3.396101015079875940e-01 9.236626433839272288e-01\n-2.427355990026089927e+01 2.073994110416465730e+01 2.170807444422401478e+00 -1.783772892155512380e-01 3.164213493379939256e-03 3.356419573651723276e-01 9.249410412238524559e-01\n-2.411143338788069457e+01 2.058005725822879839e+01 2.181711413896941121e+00 -1.789011116774514576e-01 2.533429513252270782e-03 3.312247041750007170e-01 9.264329941860981465e-01\n-2.395358374681939395e+01 2.043156042038951981e+01 2.193466375655354295e+00 -1.781820297642631445e-01 1.518440338007657478e-03 3.265133176735959819e-01 9.282444887438395797e-01\n-2.378137291698228850e+01 2.027731198521926004e+01 2.202544851885130051e+00 -1.772231022939589340e-01 -1.142698712680511951e-04 3.213388908752234374e-01 9.302328688441559024e-01\n-2.360820039485843225e+01 2.012826763343965908e+01 2.210462999475496293e+00 -1.760922286042515550e-01 -2.334194068303546785e-03 3.158412220681679483e-01 9.323252258603759168e-01\n-2.343254729893018506e+01 1.998287346412564602e+01 2.220826320731257297e+00 -1.747725618769842004e-01 -5.082887453721562400e-03 3.100518298367477832e-01 9.345033420507886657e-01\n-2.326255796617168414e+01 1.983837668300360235e+01 2.229804523609773437e+00 -1.733364359478628547e-01 -8.348776079163816588e-03 3.038379501885040690e-01 9.367855656332416681e-01\n-2.310235838765634142e+01 1.970584173074448131e+01 2.241947866511607490e+00 -1.717849912618561181e-01 -1.199786572547334104e-02 2.973837773282887453e-01 9.390999819259777670e-01\n-2.295028196114595787e+01 1.958286525374220943e+01 2.255424051517243456e+00 -1.701818409947707111e-01 -1.595036499586073228e-02 2.905897082064004544e-01 9.414569948030672153e-01\n-2.280736594859218513e+01 1.946862924924761273e+01 2.267797479466579169e+00 -1.685447598422293580e-01 -2.013834440397856140e-02 2.835267542321208145e-01 9.438218124474053727e-01\n-2.267118424034019597e+01 1.935690750043622543e+01 2.280219219544293185e+00 -1.669499012363294399e-01 -2.445635087061915486e-02 2.760323207101295639e-01 9.462217993880225331e-01\n-2.254359611888131099e+01 1.924570146442235341e+01 2.290289369338574854e+00 -1.653825843482539248e-01 -2.890006054022439819e-02 2.681149157090276236e-01 9.486451883395159435e-01\n-2.242508383706413611e+01 1.913420649682531760e+01 2.298669420917671236e+00 -1.638814594322881013e-01 -3.334227193822694724e-02 2.600662318870630707e-01 9.509977030939973375e-01\n-2.231183483397288114e+01 1.902501793763106264e+01 2.308454712118715335e+00 -1.625786648799470435e-01 -3.758926290786378938e-02 2.517783702289140835e-01 9.532905131090511075e-01\n-2.220400006045826657e+01 1.891547836354818202e+01 2.318149300855755879e+00 -1.613833449136288234e-01 -4.173159024063542027e-02 2.433500179162118027e-01 9.555075035627831337e-01\n-2.209845338351153643e+01 1.880975098162064896e+01 2.329158518475625161e+00 -1.603213535040028948e-01 -4.556253125266216536e-02 2.346356194645030369e-01 9.576884541883025070e-01\n-2.199799084197544730e+01 1.870655874788373296e+01 2.340223438454463789e+00 -1.594738115004466772e-01 -4.897948336942856834e-02 2.258455659957382677e-01 9.597722787657028132e-01\n-2.190095719256446216e+01 1.859784303157948671e+01 2.351705863539985231e+00 -1.587822881713953915e-01 -5.191858353588252317e-02 2.169134396992903335e-01 9.617905909233496198e-01\n-2.180016806990845168e+01 1.847877138637376504e+01 2.364258134753425278e+00 -1.583307346781289426e-01 -5.435581923632944873e-02 2.077876944491077460e-01 9.637432388082685097e-01\n-2.169832459632621635e+01 1.834041881565324061e+01 2.371908520050601155e+00 -1.580906530827755618e-01 -5.627824353758310166e-02 1.985031164445777430e-01 9.656275424787137407e-01\n-2.161548383546879748e+01 1.821752885545812362e+01 2.373340289822982285e+00 -1.580645006030164668e-01 -5.749209138725010215e-02 1.891466165768861118e-01 9.674367010008695367e-01\n-2.153422843287851407e+01 1.810552516173234494e+01 2.377717464229693878e+00 -1.582610487034898650e-01 -5.781615261480226725e-02 1.797060467473474143e-01 9.691833749751642690e-01\n-2.145644821540220448e+01 1.800209728838094847e+01 2.381849807874012903e+00 -1.587154231477732047e-01 -5.729026022789755757e-02 1.700788142442150874e-01 9.708760857212688222e-01\n-2.138004282181617910e+01 1.789385514207005556e+01 2.382619277185873408e+00 -1.592238091682391388e-01 -5.593437977958651275e-02 1.603099744843234087e-01 9.725326580684515720e-01\n-2.131597834516782441e+01 1.779451138764849105e+01 2.380707270552539612e+00 -1.597441991719376064e-01 -5.398242832653989132e-02 1.506953849547642277e-01 9.740936845584099446e-01\n-2.126265806665829672e+01 1.770139245316920551e+01 2.377305864217933884e+00 -1.602471603559134095e-01 -5.139311720526714561e-02 1.412382715028596691e-01 9.755671451721739107e-01\n-2.121685694350008689e+01 1.761415606179631865e+01 2.373554570508440431e+00 -1.607831530752041049e-01 -4.823766780015736194e-02 1.320171000100557046e-01 9.769305603099242008e-01\n-2.117367240235097370e+01 1.752188071591168139e+01 2.367590729108215442e+00 -1.612903379465737419e-01 -4.463757036160696801e-02 1.230275604278528445e-01 9.781907060963731526e-01\n-2.113100143682661169e+01 1.742278791756978151e+01 2.362691670404515332e+00 -1.618331352219359032e-01 -4.061698168306866752e-02 1.142921155128258093e-01 9.793352532705437152e-01\n-2.109492570797476318e+01 1.733146658600596979e+01 2.358713281992010025e+00 -1.623646253406837714e-01 -3.634335667160287081e-02 1.059958855915424519e-01 9.803477332634522590e-01\n-2.106526439786156502e+01 1.724624616177715808e+01 2.355980308482712449e+00 -1.628528046406527985e-01 -3.176630233078926724e-02 9.806486672466814547e-02 9.812507632677880398e-01\n-2.103936426292183626e+01 1.716172325856282654e+01 2.353005008951581267e+00 -1.632545499615026263e-01 -2.699483486846433744e-02 9.055017290930690577e-02 9.820487892613617431e-01\n-2.101316994183832421e+01 1.707674261872273291e+01 2.353074067198606567e+00 -1.636490478128985460e-01 -2.195947066909571810e-02 8.355952919697588743e-02 9.827280953470782787e-01\n-2.098479064496500612e+01 1.699431492942678545e+01 2.358596145165361868e+00 -1.639983383793207072e-01 -1.668269947733160008e-02 7.701321204686938093e-02 9.833082601240621390e-01\n-2.096163967115072779e+01 1.692453467350348362e+01 2.361175419977556977e+00 -1.642102349878315215e-01 -1.137705240406010516e-02 7.111908588094235928e-02 9.837924535274802373e-01\n-2.094336156452694908e+01 1.685937661067343285e+01 2.360740008996073946e+00 -1.644046833924985573e-01 -6.180734840807129878e-03 6.576125912326838407e-02 9.841790107169632318e-01\n-2.091996040243015997e+01 1.679113249666621854e+01 2.358775558375123094e+00 -1.645912914975021790e-01 -1.145647390666358926e-03 6.090789961009554498e-02 9.844788459438268413e-01\n-2.089543578595064233e+01 1.672696514289351555e+01 2.357740460916899483e+00 -1.648569860265175491e-01 3.843779565520111068e-03 5.679655997310179699e-02 9.846733111862938648e-01\n-2.087405016091337373e+01 1.666244969984196800e+01 2.352794701593329929e+00 -1.651557222290719329e-01 8.705447299667892769e-03 5.350871175046966605e-02 9.847764234466773736e-01\n-2.084682301696283702e+01 1.659373989436810604e+01 2.347284577116218962e+00 -1.653984696066861937e-01 1.343221752683440400e-02 5.098368829005908709e-02 9.848165100232305624e-01\n-2.082007325794588581e+01 1.651314920667093133e+01 2.338474942774067866e+00 -1.656639873016375331e-01 1.789091360014482060e-02 4.940161429136621929e-02 9.847816052548349353e-01\n-2.080010771656053237e+01 1.643467478336274468e+01 2.327420048648610518e+00 -1.658959161410687166e-01 2.207375510463954749e-02 4.874050405911737466e-02 9.846906230381583525e-01\n-2.077628596253444471e+01 1.633766415659650306e+01 2.311139872091339420e+00 -1.632495460536843579e-01 2.578267823255039892e-02 4.885143635650564947e-02 9.850372287332536114e-01\n-2.074269164923461872e+01 1.624306984938383636e+01 2.298012188524479971e+00 -1.599678110252953922e-01 2.918402575743999500e-02 4.992603871806279570e-02 9.854267835299000966e-01\n-2.071488868840863873e+01 1.616813284508246085e+01 2.287606128844659636e+00 -1.561182751816872494e-01 3.226338163908769319e-02 5.183087125454018812e-02 9.858497283236083986e-01\n-2.069429637576661563e+01 1.611479893213525827e+01 2.281165493657008714e+00 -1.517945123779943506e-01 3.510028329535292563e-02 5.447281094409707480e-02 9.862854932444228284e-01\n-2.067553701424431623e+01 1.606311297660372617e+01 2.278231674796024286e+00 -1.470623601140047809e-01 3.762818768044523532e-02 5.780810384592470486e-02 9.867192945718008534e-01\n-2.066005838233551373e+01 1.601730414076842379e+01 2.273252518070416617e+00 -1.419792709351021809e-01 3.989278958783632617e-02 6.172065692333886938e-02 9.871377693749885385e-01\n-2.064257134839859731e+01 1.597737853305197220e+01 2.269208534476636174e+00 -1.366602495681482621e-01 4.195775416104875061e-02 6.614564021603631938e-02 9.875162004661860449e-01\n-2.061997488949099022e+01 1.594087837935035168e+01 2.267951612735017886e+00 -1.312409524567876851e-01 4.379814446672567613e-02 7.104242182550495055e-02 9.878311914263957494e-01\n-2.059128170228992616e+01 1.589691802007559573e+01 2.268632761416656596e+00 -1.258040767870452492e-01 4.544670677981129531e-02 7.643959187395041321e-02 9.880611720875707160e-01\n-2.056995440351705540e+01 1.586070097046617988e+01 2.269894712831388439e+00 -1.203359303490808413e-01 4.699870185379919491e-02 8.214074553465268436e-02 9.882121447876437426e-01\n-2.055072368872220423e+01 1.582903563376351919e+01 2.271289033989540407e+00 -1.148204424327542300e-01 4.844133874280111274e-02 8.821176639260819297e-02 9.882754465886016693e-01\n-2.053411520233666110e+01 1.580249573892884030e+01 2.271322097049400579e+00 -1.092922895106014647e-01 4.977367090376329933e-02 9.463243089736995961e-02 9.882420982243942387e-01\n-2.052063436617159908e+01 1.578139047222228086e+01 2.269965081994594236e+00 -1.037949162151052540e-01 5.102594258875241262e-02 1.012866999303133758e-01 9.881112975901364948e-01\n-2.051109816762516047e+01 1.576614547502966701e+01 2.267769777918209773e+00 -9.840104008533895330e-02 5.227638024267977634e-02 1.081710706902907354e-01 9.878681065840148046e-01\n-2.050568321714575859e+01 1.575574744993795129e+01 2.265118931868119301e+00 -9.318094791277606315e-02 5.357389269048426494e-02 1.152212324396054838e-01 9.875075575476254253e-01\n-2.050166382423019229e+01 1.574690267938842325e+01 2.263077717368975339e+00 -8.821430977653496597e-02 5.492012921237273554e-02 1.223792101330696547e-01 9.870285202846668104e-01\n-2.049881720857412049e+01 1.574049373021817644e+01 2.261503709674841378e+00 -8.356314648832394165e-02 5.630909305222969730e-02 1.294914206530896894e-01 9.864473735640079122e-01\n-2.049634004631608164e+01 1.573664397208897192e+01 2.260506344301061787e+00 -7.936371613926523905e-02 5.776690852868199971e-02 1.364776028964898302e-01 9.857678233796330902e-01\n-2.049218710833437740e+01 1.572331693234137262e+01 2.258134984051995975e+00 -7.554488226594657796e-02 5.917387585839132408e-02 1.434541500898740829e-01 9.849935446105722026e-01\n-2.048657437881676557e+01 1.569756930055372379e+01 2.255590004990317254e+00 -7.234952555513138317e-02 6.067932273964941892e-02 1.500437064990849667e-01 9.841597448593090158e-01\n-2.047843582579944410e+01 1.566225449672118231e+01 2.252243725286425136e+00 -6.971624011045358948e-02 6.231747739621338461e-02 1.563830270621933693e-01 9.832601318403235702e-01\n-2.046442239506922434e+01 1.561154057414355201e+01 2.247412752498196831e+00 -6.753753647134667915e-02 6.408830427774044047e-02 1.625061682465696600e-01 9.823049831204545557e-01\n-2.044462728535043183e+01 1.553935775085130544e+01 2.239074167287379513e+00 -6.574968329266300815e-02 6.597160830403327181e-02 1.684161561215151981e-01 9.813056078961603923e-01\n-2.041817639042516319e+01 1.544780975665219280e+01 2.225232816334454355e+00 -6.428081985558835310e-02 6.796958880377335088e-02 1.743106238010578568e-01 9.802366497841802362e-01\n-2.037827970100034491e+01 1.535655819445656256e+01 2.215730549141833094e+00 -6.314394592599967271e-02 7.012749691860384327e-02 1.802301429577914393e-01 9.790873554259137412e-01\n-2.034304301221650135e+01 1.525750656497740110e+01 2.208270842005666257e+00 -6.228750850023884178e-02 7.234470415608308669e-02 1.860913730315238990e-01 9.778836844129077388e-01\n-2.030496317045575339e+01 1.515266078113735482e+01 2.201351717315796819e+00 -6.176481948095294966e-02 7.464613919449145096e-02 1.919754907470901106e-01 9.766055802156206056e-01\n-2.026302311912285603e+01 1.502794260271870108e+01 2.194500827666788556e+00 -6.150353105975184254e-02 7.689509711329897690e-02 1.977486174561704779e-01 9.752947917744485551e-01\n-2.020849726341433339e+01 1.490013804558936172e+01 2.179868191048701220e+00 -6.134829259082300729e-02 7.915527343069228561e-02 2.037013814230680120e-01 9.738976099600501479e-01\n-2.015865252051629852e+01 1.478943384765494073e+01 2.172600629379263903e+00 -6.130733305315389653e-02 8.150632296801041399e-02 2.099363517575650873e-01 9.723810155697343305e-01\n-2.010697506542285140e+01 1.469454277800677389e+01 2.169887108051629099e+00 -6.122343169573608856e-02 8.385772232222171718e-02 2.160867110524038737e-01 9.708378266261108447e-01\n-2.004333324686132300e+01 1.459155794196276901e+01 2.168254593386185203e+00 -6.121813631254290067e-02 8.620945953303266185e-02 2.221014920901688283e-01 9.692735309063055249e-01\n-1.995536522431518733e+01 1.449161916155743590e+01 2.176704636767818002e+00 -6.121831844503336506e-02 8.849909393654395440e-02 2.282178498163161540e-01 9.676449822251577126e-01\n-1.986852694734326619e+01 1.442672928122935261e+01 2.184905732446394300e+00 -6.079935440944351371e-02 9.076774558049814645e-02 2.348681532696405838e-01 9.658682934572044854e-01\n-1.977248391560454621e+01 1.435172719976702815e+01 2.195254625368472823e+00 -5.995056471532162617e-02 9.312418594182914067e-02 2.418719696773432015e-01 9.639666560933002337e-01\n-1.969067993194185107e+01 1.426944732331360122e+01 2.199145282308047289e+00 -5.868241001951993857e-02 9.537467557572931742e-02 2.493537768367389829e-01 9.619161504109252636e-01\n-1.960956707831019941e+01 1.417168327337953571e+01 2.203751693175549420e+00 -5.704751587468308988e-02 9.750129778798000135e-02 2.568054443738436721e-01 9.598385176861311541e-01\n-1.955079876767694813e+01 1.409388215135465394e+01 2.206114221758293858e+00 -5.500135549751854203e-02 9.950490433384594213e-02 2.647950310287480735e-01 9.575787960004964461e-01\n-1.949116912884880648e+01 1.402973278451732142e+01 2.205298159181333872e+00 -5.209322678538553381e-02 1.017655153258788803e-01 2.732479988458092479e-01 9.551259315684987872e-01\n-1.942543732676718093e+01 1.397021949839072974e+01 2.204714454798081924e+00 -4.870392115491865848e-02 1.040523361421392540e-01 2.825111603538412730e-01 9.523594029970722241e-01\n-1.929821494239357804e+01 1.378497043399655553e+01 2.205750938714737153e+00 -4.492083545822482538e-02 1.061211487241495860e-01 2.917518127459385879e-01 9.495268583346441194e-01\n-1.912665396715104649e+01 1.353795928427117978e+01 2.205938936536770090e+00 -4.050387523008284335e-02 1.083404317492605851e-01 3.015274564377538047e-01 9.464158367774282432e-01\n-1.890935921934523023e+01 1.327559809124179502e+01 2.224901666802643785e+00 -3.551371582259577053e-02 1.104073315128968891e-01 3.113157326726145313e-01 9.432027635009208044e-01\n-1.871895692483319706e+01 1.304034078023417109e+01 2.240376825580436826e+00 -3.059565958570060334e-02 1.122690636555179616e-01 3.210416825095556703e-01 9.398892217118648418e-01\n-1.858533960095937232e+01 1.285581032850718053e+01 2.239556104990208851e+00 -2.533638816897254217e-02 1.134705182592263134e-01 3.306192625627465409e-01 9.365753419114675182e-01\n-1.846637934944839188e+01 1.267245711276296838e+01 2.232190393417010199e+00 -1.996472408195707968e-02 1.142426246977342186e-01 3.400037153505683363e-01 9.332456640499179334e-01\n-1.834424743626685128e+01 1.248542095186074086e+01 2.224726272720475517e+00 -1.461782668039461608e-02 1.147569380941151490e-01 3.490302168913915204e-01 9.299435636087323154e-01\n-1.821656758056435876e+01 1.228891383911369317e+01 2.218094745620765806e+00 -9.473427686408660356e-03 1.150921517709838637e-01 3.575202265649736200e-01 9.267379901628109984e-01\n-1.808473947371998847e+01 1.208766941031786146e+01 2.211148295661107710e+00 -4.591869651937877973e-03 1.152099924134651621e-01 3.652709483137638879e-01 9.237330117737343471e-01\n-1.796212633515017743e+01 1.190028077422488195e+01 2.202906659710205606e+00 -2.268098271442152251e-04 1.150432754928166768e-01 3.721879461725837723e-01 9.210000560270295011e-01\n-1.785453028213330029e+01 1.173500074493014900e+01 2.196422447926726473e+00 3.584831690984122479e-03 1.146186967401746082e-01 3.781439587308655925e-01 9.186167999001022544e-01\n-1.776411908157643182e+01 1.159193336663456186e+01 2.188055005070835168e+00 6.860951809147601901e-03 1.138170436653504064e-01 3.829512423719652614e-01 9.167043907533920510e-01\n-1.769734221398674023e+01 1.147952232355739000e+01 2.179243348434104721e+00 9.447360004739294159e-03 1.127334212492174664e-01 3.865639640853909542e-01 9.152978760535983582e-01\n-1.763255751500428303e+01 1.137085906132285018e+01 2.171910293257880653e+00 1.110555655371989886e-02 1.114242542141882925e-01 3.885893432651385537e-01 9.145816551065322209e-01\n-1.757316524267253399e+01 1.127964602695488061e+01 2.166473754292252529e+00 1.185933542491708452e-02 1.098771284046711066e-01 3.892181435789570099e-01 9.144919826590290901e-01\n-1.752693756265603753e+01 1.120474242156642752e+01 2.162020643769047012e+00 1.173225842753999187e-02 1.079556522185817213e-01 3.881986992109021650e-01 9.151555493068490588e-01\n-1.749635054128563993e+01 1.114842258175177214e+01 2.159801109387699203e+00 1.068457498525992276e-02 1.054529732056452701e-01 3.853574005046796480e-01 9.166597900985391512e-01\n-1.746987484039617655e+01 1.109833512739065675e+01 2.160562514213641094e+00 8.361420198932255701e-03 1.023366124301905711e-01 3.807866783946503575e-01 9.189443942600107329e-01\n-1.743961018697540410e+01 1.103295869616226099e+01 2.160514159081406760e+00 4.759838570044848741e-03 9.862923242753426911e-02 3.740671675138654284e-01 9.221297941097912343e-01\n-1.738209358789312020e+01 1.092662162694817951e+01 2.159551026333672574e+00 -4.267478026647154540e-04 9.451641194703352955e-02 3.648909327282914838e-01 9.262402779090995741e-01\n-1.728429936725947869e+01 1.078156544320308186e+01 2.161188781995482699e+00 -7.344681234861672250e-03 8.979843880021999569e-02 3.532146170640036997e-01 9.311937065706878958e-01\n-1.717129514951847469e+01 1.060954244656145207e+01 2.161881636377004146e+00 -1.558728871856538897e-02 8.459577425049155663e-02 3.393465364544549501e-01 9.367200835681316340e-01\n-1.706168993742090123e+01 1.044539723171767776e+01 2.164013818496068442e+00 -2.499361266717898752e-02 7.909483822218456306e-02 3.234376213958564672e-01 9.426067187801692171e-01\n-1.696109414029760387e+01 1.029391974573971957e+01 2.167050192972648226e+00 -3.532126478746205889e-02 7.333142691594213280e-02 3.056241350394299783e-01 9.486668460192403396e-01\n-1.687467613593777571e+01 1.016347404306224256e+01 2.168212206345208504e+00 -4.622486579764858300e-02 6.725972925270648495e-02 2.862841285846667305e-01 9.546626484609582741e-01\n-1.679382067074978124e+01 1.004178731367571586e+01 2.169404071549860369e+00 -5.744366751608519228e-02 6.090054550451711596e-02 2.656675949095181899e-01 9.604228510589920553e-01\n-1.671502872125901007e+01 9.928769784441687563e+00 2.172637553329854754e+00 -6.892427977923976101e-02 5.424888258536680885e-02 2.438624215285866981e-01 9.658351854806833670e-01\n-1.663799007586359480e+01 9.817469086452909721e+00 2.178387655751162555e+00 -8.060115121284738837e-02 4.751327452176265509e-02 2.213335174097662561e-01 9.706994426515963559e-01\n-1.656408488197978457e+01 9.712851673770579453e+00 2.188949668821842831e+00 -9.216847508597671157e-02 4.077806440951327327e-02 1.983061332690445600e-01 9.749445003683047117e-01\n-1.649973487856637533e+01 9.614714016748605374e+00 2.200081186862143046e+00 -1.034956853282595624e-01 3.406593713696950271e-02 1.751033563911676694e-01 9.785024007734179907e-01\n-1.644145189377235994e+01 9.518645326628329073e+00 2.211673619938637980e+00 -1.143697992967085963e-01 2.747856742179980924e-02 1.520167501308666569e-01 9.813538443386329302e-01\n-1.639295111415408002e+01 9.438464491340159412e+00 2.223216243399236181e+00 -1.246647215866305419e-01 2.102622803237862506e-02 1.291460620602334630e-01 9.835333673742464589e-01\n-1.635229191864688758e+01 9.368127702486257036e+00 2.233562520519563499e+00 -1.342134310043322509e-01 1.479586287658969657e-02 1.068738640728450623e-01 9.850613124757330308e-01\n-1.631830051074468457e+01 9.307242259240959825e+00 2.244426700517038853e+00 -1.428014414319911107e-01 8.879592283973461453e-03 8.562554733092427039e-02 9.860005750991928108e-01\n-1.628619582107893038e+01 9.255500505683029289e+00 2.258414306512610548e+00 -1.503244219381807412e-01 3.270482471886472942e-03 6.561739121335170843e-02 9.864513117733360037e-01\n-1.625537509089395627e+01 9.209283319931946821e+00 2.273578104608310557e+00 -1.566462438607570395e-01 -2.030606906476295839e-03 4.723166892274411471e-02 9.865226583743368360e-01\n-1.622515917466837010e+01 9.168472316023480673e+00 2.287756380059410954e+00 -1.615980304750979923e-01 -6.849638316913116316e-03 3.080643644438940676e-02 9.863519073006619120e-01\n-1.619263194700837261e+01 9.132351626603893990e+00 2.302137466604272209e+00 -1.648971126317285152e-01 -1.098738770568819141e-02 1.663825802873680412e-02 9.861091961530722427e-01\n-1.615948541636274527e+01 9.105472748325324162e+00 2.317080591805684708e+00 -1.655842833399760461e-01 -1.447054216107828729e-02 5.040399209603840455e-03 9.860765656444495653e-01\n-1.613543561889148137e+01 9.089246719148793119e+00 2.330073713023355531e+00 -1.656461391315860177e-01 -1.718069026848557598e-02 -3.816953218732600274e-03 9.860281758057878321e-01\n-1.611969485803400559e+01 9.080030284385308903e+00 2.333121595778725244e+00 -1.630190628763794614e-01 -1.919318291760680265e-02 -9.716719758919092897e-03 9.863883371728771055e-01\n-1.611101792298105551e+01 9.077893633231999715e+00 2.332891359582450086e+00 -1.585215352822811896e-01 -2.029516156287563405e-02 -1.268769550646510827e-02 9.870653532020081666e-01\n-1.610786570749139557e+01 9.074754689125031248e+00 2.332373661696823586e+00 -1.522359735163119898e-01 -2.072530759265489228e-02 -1.317284282213836144e-02 9.880390140301673618e-01\n-1.610707111008888148e+01 9.074273188830556336e+00 2.330908070778615393e+00 -1.444230926660645953e-01 -2.059467730056086660e-02 -1.135002870264241633e-02 9.892365560008224978e-01\n-1.610051076023561123e+01 9.067454666629032545e+00 2.329856523599523221e+00 -1.354194888253757445e-01 -2.003183825100954274e-02 -7.444247601461353135e-03 9.905578304610710427e-01\n-1.608561065131056012e+01 9.055431567141054572e+00 2.333570903625997950e+00 -1.253950029047078696e-01 -1.897163984724062682e-02 -1.641236612165737933e-03 9.919241008659176462e-01\n-1.604942488873723505e+01 9.047208141752495436e+00 2.347260763556520580e+00 -1.144697698682805159e-01 -1.762930797492083534e-02 5.740325714956262711e-03 9.932536784984982159e-01\n-1.599780400830240801e+01 9.036078121086683623e+00 2.365797423118996434e+00 -1.028793770958119497e-01 -1.601182389409760293e-02 1.438189170857957951e-02 9.944609331068434699e-01\n-1.597493526484967674e+01 9.054104035289602948e+00 2.375230004990104948e+00 -9.116612313425521974e-02 -1.402592871805455159e-02 2.404947248203979926e-02 9.954464178891656578e-01\n-1.596623212574137796e+01 9.088837732746416265e+00 2.379756223421016781e+00 -7.920706450329700887e-02 -1.186981575955644609e-02 3.411035148029154668e-02 9.962036791399401237e-01\n-1.596954706205692354e+01 9.145630681692750841e+00 2.378335418541498658e+00 -6.713151095836895899e-02 -9.939073942417494395e-03 4.453442322185163782e-02 9.967001579566676650e-01\n-1.597713426819272442e+01 9.209867560630165428e+00 2.375847369721776126e+00 -5.513994028047861096e-02 -8.117924896497836357e-03 5.531919823089394977e-02 9.969119332950577839e-01\n-1.599726395083548702e+01 9.286978546016371183e+00 2.368917688079634765e+00 -4.346590881166189496e-02 -6.423142916541952317e-03 6.621660902030318541e-02 9.968373749311695287e-01\n-1.602325280615994174e+01 9.384730327165568653e+00 2.360474174448691898e+00 -3.231471166577935122e-02 -4.952948608179501104e-03 7.695102274079493321e-02 9.964987172343905408e-01\n-1.606731305965451639e+01 9.504301408337655133e+00 2.347623184502842797e+00 -2.189820861151870954e-02 -3.729460773636685943e-03 8.743663417366816237e-02 9.959223462074408006e-01\n-1.612083081086907654e+01 9.644930870353693564e+00 2.335521445274497676e+00 -1.240500041987740651e-02 -2.751275237990671516e-03 9.731352131216068624e-02 9.951726225457058206e-01\n-1.618099947206566469e+01 9.795013133979924902e+00 2.324490477150014112e+00 -4.103948224691608693e-03 -2.038100836592279547e-03 1.062099577466320416e-01 9.943331278112087501e-01\n-1.624217904165843152e+01 9.942615724029280955e+00 2.313414108981703077e+00 2.671543113858131438e-03 -1.817275572975684834e-03 1.139050986658751985e-01 9.934863396660439383e-01\n-1.629124780354753099e+01 1.006938740591245995e+01 2.303920311212641181e+00 7.578488459806609866e-03 -2.268273374107130595e-03 1.198967946776430676e-01 9.927548071932547069e-01\n-1.633472385079273792e+01 1.017595524124036643e+01 2.290903076987572895e+00 1.049449308106667478e-02 -3.410735886430148710e-03 1.241520308463849587e-01 9.922018096698036471e-01\n-1.637793268302061378e+01 1.028165325764400073e+01 2.274641803603773660e+00 1.135478531300459365e-02 -5.504453293259703277e-03 1.267870953564638192e-01 9.918496433009207358e-01\n-1.642822846916649837e+01 1.040742890945908350e+01 2.257948914225482273e+00 1.029881112775398767e-02 -8.313216204557929631e-03 1.277369548604467553e-01 9.917197144658432828e-01\n-1.647931254011575319e+01 1.052246117433054451e+01 2.243167421829907582e+00 7.634594890201421881e-03 -1.166218571425032755e-02 1.268715450056190353e-01 9.918211601256338161e-01\n-1.653516030257644331e+01 1.065070388833428439e+01 2.229596635922036718e+00 3.412057472295177384e-03 -1.565310569281696748e-02 1.246696696394519049e-01 9.920689093088246313e-01\n-1.659536502724029816e+01 1.079629368550196133e+01 2.219560690459061458e+00 -2.277955605083687059e-03 -2.008936474288094270e-02 1.213646936867543435e-01 9.924020086246534422e-01\n-1.666574160083146339e+01 1.095804922228458267e+01 2.206575003680418590e+00 -9.232634428867562970e-03 -2.485068396863391454e-02 1.169590881075668609e-01 9.927827994400153511e-01\n-1.674190989691862796e+01 1.113371931954566918e+01 2.190580694345738877e+00 -1.729123396301393556e-02 -2.983821393142610523e-02 1.116249497908161081e-01 9.931517888250256387e-01\n-1.682084807372992330e+01 1.131155062160362057e+01 2.171354591314961446e+00 -2.627781006345874734e-02 -3.505250642584061688e-02 1.055596444750812601e-01 9.934474642225414875e-01\n-1.690339518644142913e+01 1.149827905820425400e+01 2.151008411228464645e+00 -3.600895897540373758e-02 -4.038228984364392038e-02 9.883217843337271935e-02 9.936320924692395584e-01\n-1.699017092537654250e+01 1.169579789143146975e+01 2.131659798115800530e+00 -4.632514640753965934e-02 -4.565426019546325875e-02 9.170207545078250255e-02 9.936600517883820149e-01\n-1.709386783254561593e+01 1.190758659631958771e+01 2.114919487083909200e+00 -5.697037751959511953e-02 -5.086295538998143045e-02 8.444393908915696911e-02 9.934970847992861120e-01\n-1.721252576975277293e+01 1.212821192215514188e+01 2.102066421114354267e+00 -6.762684478981473291e-02 -5.597921324432133389e-02 7.717879162941922166e-02 9.931446415325295707e-01\n-1.734414723779302037e+01 1.234817916102151791e+01 2.094966851470915437e+00 -7.811016813160526207e-02 -6.091964018158538274e-02 7.004974020309484573e-02 9.926129889366381853e-01\n-1.749466391275494104e+01 1.255966252000725802e+01 2.090670235722457804e+00 -8.825476276087608485e-02 -6.557760250153599202e-02 6.300433027933761976e-02 9.919380279893152963e-01\n-1.766160084761688864e+01 1.275175773625625197e+01 2.088632206476979558e+00 -9.801771896044846055e-02 -6.981677485633164260e-02 5.643833537049062349e-02 9.911270216109892006e-01\n-1.784674088814451665e+01 1.293479071192559005e+01 2.084145789414349359e+00 -1.072340540274417386e-01 -7.358196782590170626e-02 5.072332308422956154e-02 9.902088707269739443e-01\n-1.804303659319181818e+01 1.312350271965192761e+01 2.086779122422094623e+00 -1.156308791144170789e-01 -7.684132591609062202e-02 4.584309259977438489e-02 9.892538760014278898e-01\n-1.823680545551879106e+01 1.330054306159428457e+01 2.100665654473128807e+00 -1.231424855552845504e-01 -7.936709817534590150e-02 4.193402412085699832e-02 9.883209154678385122e-01\n-1.841567601464123882e+01 1.346193909844716075e+01 2.134129752566813476e+00 -1.293208643605408825e-01 -8.103128912829450636e-02 3.909683664104095929e-02 9.875127227309660194e-01\n-1.858253985886641146e+01 1.360433933777828486e+01 2.168064371091896980e+00 -1.341300029799911697e-01 -8.204923167606985313e-02 3.767319669960150774e-02 9.868422817252924251e-01\n-1.872528555110619308e+01 1.371417458432784997e+01 2.190000764840207115e+00 -1.374762638688906968e-01 -8.210701065406829369e-02 3.764342635540047360e-02 9.863780127125750807e-01\n-1.886174992968339836e+01 1.381813799764337958e+01 2.202999472521771196e+00 -1.395160263736313910e-01 -8.129732852998228232e-02 3.901140679525193222e-02 9.861054839331668820e-01\n-1.900846804434779713e+01 1.392831097412183361e+01 2.206856974323029519e+00 -1.403293273126852980e-01 -7.988191194438465370e-02 4.150051939448869132e-02 9.860041399728640688e-01\n-1.916571367673935811e+01 1.403579048606478530e+01 2.207071381292480261e+00 -1.400379638015649963e-01 -7.790403469512195700e-02 4.501333120722775250e-02 9.860497042400393486e-01\n-1.932336268452755590e+01 1.413904396895380522e+01 2.204120642705144295e+00 -1.388513136416683336e-01 -7.536944635375898704e-02 4.938366621938568984e-02 9.862053041473500814e-01\n-1.948019051283263892e+01 1.423741841155265675e+01 2.200146855982614724e+00 -1.367630726654870954e-01 -7.234988442363499139e-02 5.469348488684781101e-02 9.864430411568382295e-01\n-1.964875955572989952e+01 1.433830687080092581e+01 2.194627629322277063e+00 -1.337558056365891479e-01 -6.896716357587492907e-02 6.103991920834043322e-02 9.867253612628513748e-01\n-1.982736775656775308e+01 1.443923626581344166e+01 2.187412016870568632e+00 -1.299336473950004622e-01 -6.540464313115372519e-02 6.827843064796437766e-02 9.870042669290723936e-01\n-2.003310344387709208e+01 1.455450267049625701e+01 2.188406739971098691e+00 -1.251762827996395766e-01 -6.150402563108019194e-02 7.655005314683840933e-02 9.872629464605172656e-01\n-2.020370104676618084e+01 1.463269892318620791e+01 2.183445481404470812e+00 -1.201726246628413569e-01 -5.755515563868281170e-02 8.478117842600900456e-02 9.874502375473758198e-01\n-2.039944575523385950e+01 1.473814869357466328e+01 2.171863244999892029e+00 -1.150452482359691914e-01 -5.377802125628649427e-02 9.345944491593065340e-02 9.874906169596617822e-01\n-2.058323154692209656e+01 1.482187808651007543e+01 2.162320377892114731e+00 -1.095851340567848969e-01 -5.021388268546568556e-02 1.027892628893974369e-01 9.873722237646116451e-01\n-2.077850243723293033e+01 1.491262548729414306e+01 2.155145278297261324e+00 -1.039155139600953515e-01 -4.681374706100800004e-02 1.126103102700283937e-01 9.870809676505636343e-01\n-2.097268377603544209e+01 1.499967083972508064e+01 2.144085471811068899e+00 -9.854660583477990732e-02 -4.354060165108766811e-02 1.221308656917521052e-01 9.866492309360290758e-01\n-2.117992613839238203e+01 1.510366820591486459e+01 2.131473250414687381e+00 -9.318340102928472646e-02 -4.053285809127053774e-02 1.316266821970481227e-01 9.860771868811744056e-01\n-2.134511741496542925e+01 1.527708983157364031e+01 2.103044743210867207e+00 -8.748968684153357600e-02 -3.735379189054816723e-02 1.413872393545844153e-01 9.853728963266293883e-01\n-2.111324512817924770e+01 1.530666291996512385e+01 2.083534390417496773e+00 -8.253825544210410814e-02 -3.501602564173068866e-02 1.505422105512969067e-01 9.845294345390187551e-01\n-2.087389369854814447e+01 1.529357879033045009e+01 2.075755340018088368e+00 -7.785113952916211666e-02 -3.342901890145941191e-02 1.591765119103717985e-01 9.836078446930101027e-01\n-2.064248619497521631e+01 1.526955410168450200e+01 2.074871614817053622e+00 -7.357602023898533738e-02 -3.232203097506882589e-02 1.671843552861336235e-01 9.826449531754252176e-01\n-2.043162307627387975e+01 1.524231419457743542e+01 2.074558946751290822e+00 -7.006468207152179162e-02 -3.194303482292529944e-02 1.745368820176589897e-01 9.816350169486763866e-01\n-2.023100473798250221e+01 1.520814818070421737e+01 2.068743045828157268e+00 -6.718428342995476366e-02 -3.238310953251236773e-02 1.810233746475911343e-01 9.806467197504810107e-01\n-2.003008189925847660e+01 1.517409903606462507e+01 2.070659101001316671e+00 -6.525167378786993211e-02 -3.344579123601653520e-02 1.870358849538260870e-01 9.796126902291274474e-01\n-1.982494515732422968e+01 1.513063637487507229e+01 2.074430086483830316e+00 -6.416746726491839858e-02 -3.519578605880979011e-02 1.918981645418474380e-01 9.786821423416809385e-01\n-1.965384943012049135e+01 1.508698024869777399e+01 2.076389137955708009e+00 -6.378019514722951810e-02 -3.763855786655878610e-02 1.957479091285511952e-01 9.778537888697909075e-01\n-1.948961096498404544e+01 1.505179097379046205e+01 2.072284817075018992e+00 -6.389437410566929654e-02 -4.044202187162802831e-02 1.987253473825571493e-01 9.771335832118609455e-01\n-1.933258911723182294e+01 1.502003635824399730e+01 2.070368887616188314e+00 -6.470998510553505056e-02 -4.345444887374317472e-02 2.009126418589243790e-01 9.765030957275405710e-01\n-1.917320681512573799e+01 1.499041699506302194e+01 2.072088841608691112e+00 -6.618339888423839523e-02 -4.693590890032925400e-02 2.019804236340539960e-01 9.760228275395445019e-01\n-1.902034381543474240e+01 1.496555965102183450e+01 2.075386078124768829e+00 -6.810809804166763348e-02 -5.054610197927305454e-02 2.020383533922505970e-01 9.756980827019108293e-01\n-1.887027065573176543e+01 1.494518788345334670e+01 2.078513958520793903e+00 -7.050182936655541299e-02 -5.418052228721418478e-02 2.010213896943786327e-01 9.755430435144810675e-01\n-1.874056917559722280e+01 1.492958187260158986e+01 2.082164290731034928e+00 -7.336861876315663167e-02 -5.773025156134082431e-02 1.988567967143820836e-01 9.755716779770967628e-01\n-1.863255263101379811e+01 1.491530607359389649e+01 2.085717404095332572e+00 -7.655764968775266577e-02 -6.113532483107075866e-02 1.956919154001892924e-01 9.757591584624414338e-01\n-1.853528160626419918e+01 1.490112845445516321e+01 2.088775495282948036e+00 -8.005915433033353179e-02 -6.435110930606666169e-02 1.914672314884831583e-01 9.761094407317428834e-01\n-1.844534103986456230e+01 1.488481591228454626e+01 2.092963753052159426e+00 -8.382208454099877859e-02 -6.742247592598546446e-02 1.861089373675393344e-01 9.766224457108689805e-01\n-1.836223704409640689e+01 1.486653652516606883e+01 2.096376783761374263e+00 -8.766101706523214687e-02 -7.022268758169866731e-02 1.796967982783925499e-01 9.772887180412758168e-01\n-1.828559200289143760e+01 1.484661298079097413e+01 2.097336750536834327e+00 -9.162121050648702747e-02 -7.262208661281341349e-02 1.722005733861409760e-01 9.780993763408689645e-01\n-1.821208011980237984e+01 1.482685568067020832e+01 2.095806705510431911e+00 -9.574690372886669743e-02 -7.452372176215169008e-02 1.634387164022577388e-01 9.790640306001334725e-01\n-1.813626085198079707e+01 1.480494398657802613e+01 2.095515815191007380e+00 -9.993557997899722711e-02 -7.582870961633583762e-02 1.535873062232560315e-01 9.801396184984921822e-01\n-1.806150641619427688e+01 1.478309008123216906e+01 2.096079684485329331e+00 -1.040516534877436727e-01 -7.641651660915249611e-02 1.425483410307718801e-01 9.813325570462070324e-01\n-1.798716727284493189e+01 1.476309320501279920e+01 2.097857943105324363e+00 -1.079974499821066969e-01 -7.626260043230576047e-02 1.302367427375733522e-01 9.826285163278722923e-01\n-1.792035828452866042e+01 1.474847287771143378e+01 2.099481093561671674e+00 -1.118371981574265428e-01 -7.520129091147600975e-02 1.168578180182255205e-01 9.839620417255634521e-01\n-1.786896633246229271e+01 1.473883459295010745e+01 2.100079897133919182e+00 -1.155498340418688458e-01 -7.296937675020730152e-02 1.024256137683263873e-01 9.853083491927672188e-01\n-1.782955813724623795e+01 1.473018792611420480e+01 2.101394596507172086e+00 -1.191334854201221288e-01 -6.976046563237510434e-02 8.680260521505843430e-02 9.866133172349799141e-01\n-1.780025780684731629e+01 1.472016275391155737e+01 2.106005668767443328e+00 -1.227530299644173234e-01 -6.568173737006395563e-02 7.021006128590007167e-02 9.877692035547255278e-01\n-1.778024323699494857e+01 1.471179777764218244e+01 2.111474266157935542e+00 -1.263361315597076040e-01 -6.082715310475720477e-02 5.267126556216187444e-02 9.887187798754073498e-01\n-1.776688363602180232e+01 1.470608652646782666e+01 2.114623548761825234e+00 -1.298361307518257068e-01 -5.531859876520795610e-02 3.432665932972633893e-02 9.893957596410226651e-01\n-1.776180378205032184e+01 1.470420970695452212e+01 2.115301687685079202e+00 -1.332139316602710677e-01 -4.932799815798065424e-02 1.516235116415115894e-02 9.897427758281290844e-01\n-1.776083762602299743e+01 1.470488575887673122e+01 2.115395313544910838e+00 -1.364343403737725557e-01 -4.288589963293847063e-02 -4.614807795886593025e-03 9.897095679667489154e-01\n-1.776346128225869947e+01 1.470799042157793757e+01 2.115089730487588859e+00 -1.394610445813741495e-01 -3.610019484816001656e-02 -2.484307627542065369e-02 9.892573303291761766e-01\n-1.776381347894344742e+01 1.471083074267056467e+01 2.115187686400317180e+00 -1.423418346008326618e-01 -2.899275916591693286e-02 -4.518123988528639778e-02 9.883606354666614191e-01\n-1.776124323303142205e+01 1.471304403810461281e+01 2.115470615317164960e+00 -1.450500884313442873e-01 -2.167426971983349437e-02 -6.550171346812502793e-02 9.870157493613137545e-01\n-1.775576822200288873e+01 1.471449152830182072e+01 2.116163165305680938e+00 -1.475710839897600157e-01 -1.423157851761065913e-02 -8.564796990829237622e-02 9.852332354915237511e-01\n-1.774671665487562322e+01 1.471525345178032396e+01 2.117798358331107966e+00 -1.498742727731608437e-01 -6.744801397174555319e-03 -1.054758811063421786e-01 9.830396339459467336e-01\n-1.773425008782144374e+01 1.471524935046138793e+01 2.120497156016112772e+00 -1.519542430216485329e-01 6.908105285363304055e-04 -1.248346645081095108e-01 9.804721340744722013e-01\n-1.771933772421600040e+01 1.471452123882868968e+01 2.124018873593796375e+00 -1.538148544917070648e-01 7.945132713633333565e-03 -1.435659849898861251e-01 9.775819838768001757e-01\n-1.770158892031110298e+01 1.471332367211089220e+01 2.128353228040870793e+00 -1.554512998809085833e-01 1.487580230637751237e-02 -1.615518430521011850e-01 9.744303333156587588e-01\n-1.768070659655806054e+01 1.471178483285920890e+01 2.133486153904172511e+00 -1.568672270639969446e-01 2.137023449095604155e-02 -1.786748408674451449e-01 9.710876148719804757e-01\n-1.765520583790828368e+01 1.470953312904325827e+01 2.139785298003943126e+00 -1.580715135408298500e-01 2.735972551992696747e-02 -1.948075342638374841e-01 9.676335654745908954e-01\n-1.763257909878102581e+01 1.470792589631183667e+01 2.145768696274809262e+00 -1.591307992913066627e-01 3.274421947091263330e-02 -2.098386170646575899e-01 9.641435573131417192e-01\n-1.761154506912698992e+01 1.470756849560478763e+01 2.150759440345031859e+00 -1.600752148866937674e-01 3.748578752557860799e-02 -2.237643708399396081e-01 9.606768854753626741e-01\n-1.759346871674128110e+01 1.470832716101988602e+01 2.153318594371060435e+00 -1.609509316239397247e-01 4.145880040599969618e-02 -2.363738737888267105e-01 9.573417213092957345e-01\n-1.757715898289109191e+01 1.470985754540407342e+01 2.156877113365502474e+00 -1.602667494947415394e-01 4.430118789341638830e-02 -2.476207932373343801e-01 9.544819165735920485e-01\n-1.756470525599414501e+01 1.471083080869373916e+01 2.160252285466500055e+00 -1.596877662244635121e-01 4.645445504920311941e-02 -2.575108597271836275e-01 9.518559635896126636e-01\n-1.755430864807247460e+01 1.471272029587783514e+01 2.164736519679076654e+00 -1.592736919425307984e-01 4.799229735555288201e-02 -2.661396745097128758e-01 9.494725491621541780e-01\n-1.754858573576068537e+01 1.471440250282627815e+01 2.166458189873719853e+00 -1.590557544306516191e-01 4.882832573250100311e-02 -2.734190187995648724e-01 9.473958580849505262e-01\n-1.754552770370608528e+01 1.471451448183227662e+01 2.167897316934680241e+00 -1.589529114605628402e-01 4.913746779228266720e-02 -2.794246577992133274e-01 9.456432448388171208e-01\n-1.754428721701840033e+01 1.471336620128529304e+01 2.168646122790431008e+00 -1.589759204067289211e-01 4.899210478298784976e-02 -2.843120574432076442e-01 9.441890061790466637e-01\n-1.754390638424300519e+01 1.471321537899052601e+01 2.168568871272051002e+00 -1.591757036192298358e-01 4.847914298886440293e-02 -2.882517089297858548e-01 9.429865401738088959e-01\n-1.753290603074790610e+01 1.471363162880962250e+01 2.169377446536030707e+00 -1.594643028330341994e-01 4.763583741186019904e-02 -2.911380238452138114e-01 9.420936299997494379e-01\n-1.751853244776126672e+01 1.471280485397276472e+01 2.169986494430891089e+00 -1.597935945782330835e-01 4.660807173512841045e-02 -2.931362906841420979e-01 9.414693874770819759e-01\n-1.749360712046400579e+01 1.470823595765781810e+01 2.168300470524465950e+00 -1.602048833166648811e-01 4.531525870765994862e-02 -2.941799139575875244e-01 9.411370248698095464e-01\n-1.745801525471232907e+01 1.470027967859899221e+01 2.166110862214427168e+00 -1.607828737305490308e-01 4.380865285503965367e-02 -2.943071296303092499e-01 9.410700126972115775e-01\n-1.741882322495211710e+01 1.469317200249942168e+01 2.163938381328017080e+00 -1.613279033958738840e-01 4.226787651504165105e-02 -2.936509542937228434e-01 9.412521680717634842e-01\n-1.737896885794033963e+01 1.468541492320332864e+01 2.164267197864405468e+00 -1.619048546725881388e-01 4.080061870030021742e-02 -2.923728871494927772e-01 9.416156437917089228e-01\n-1.732517095217490066e+01 1.467056184203279656e+01 2.166301326430514429e+00 -1.624501422565838293e-01 3.924979473063118507e-02 -2.905188307762270328e-01 9.421613522439444832e-01\n-1.726126185485400200e+01 1.465085560410666332e+01 2.171132953640088736e+00 -1.628620259007576287e-01 3.778866383611321350e-02 -2.880354133628819646e-01 9.429121825691334502e-01\n-1.719660886337743122e+01 1.463240272352795657e+01 2.175043059578144256e+00 -1.631772076012331096e-01 3.651314370467392822e-02 -2.850262011098593229e-01 9.438219432046217605e-01\n-1.712681734994837868e+01 1.461326579475347565e+01 2.179298359770279525e+00 -1.633524409900261043e-01 3.540889622928487107e-02 -2.816128215824896253e-01 9.448577738285589556e-01\n-1.704915580289160459e+01 1.459310383259100341e+01 2.183854887157135050e+00 -1.634045079515848709e-01 3.457048599237469433e-02 -2.778413567799292161e-01 9.459956815391612484e-01\n-1.696043605798555021e+01 1.457022790767244835e+01 2.188178644843842946e+00 -1.633968358729152026e-01 3.400307237291030210e-02 -2.737401073632363402e-01 9.472124447289032023e-01\n-1.686445452943246082e+01 1.454556340935098113e+01 2.192252050279553721e+00 -1.633193504788871819e-01 3.373760357456163234e-02 -2.693973164946810162e-01 9.484795406941164408e-01\n-1.676247652571894164e+01 1.451863900828790932e+01 2.195668851689526857e+00 -1.627230258886791237e-01 3.363081066303381245e-02 -2.648764450952924565e-01 9.498581159229988469e-01\n-1.665414071784867289e+01 1.448945165759921316e+01 2.199309790274477816e+00 -1.620861716074133430e-01 3.386812534102041222e-02 -2.601942143283090259e-01 9.512516870670147950e-01\n-1.654096545727008305e+01 1.445813648103237803e+01 2.201809227910159095e+00 -1.614146099625347330e-01 3.438326190478429439e-02 -2.554701948352409158e-01 9.526268243938107450e-01\n-1.642521524600244476e+01 1.442424229103463773e+01 2.204874207459998292e+00 -1.607356232978392752e-01 3.514888531803071064e-02 -2.508221460753407017e-01 9.539479241986402736e-01\n-1.630276064959747018e+01 1.438910735164141386e+01 2.207111311065022452e+00 -1.600734291322964964e-01 3.610716151405037738e-02 -2.463145030052167894e-01 9.551972140610355266e-01\n-1.617531324703833562e+01 1.435379086875449950e+01 2.208392404173166401e+00 -1.594634551745424123e-01 3.718634443121759947e-02 -2.420772117923132294e-01 9.563404116826896839e-01\n-1.604214904655785645e+01 1.431703333398411360e+01 2.210212697699383000e+00 -1.588795560143457797e-01 3.834523471075730605e-02 -2.382154889010023868e-01 9.573609992253030443e-01\n-1.590417679979208465e+01 1.427947412300661867e+01 2.210313007287423748e+00 -1.583865263573699944e-01 3.944165915495820990e-02 -2.348361943610171310e-01 9.582326377184082755e-01\n-1.576631978958427638e+01 1.424097358560167592e+01 2.207741055732447499e+00 -1.580269097823363833e-01 4.041997628330624287e-02 -2.320227947900415644e-01 9.589363356533610050e-01\n-1.562145330482072936e+01 1.420406578287582988e+01 2.203849486508297595e+00 -1.576936287658199654e-01 4.130167230877271334e-02 -2.297510513434703472e-01 9.595004439268123297e-01\n-1.546460777698472633e+01 1.416602655418754253e+01 2.202303482841406090e+00 -1.573713487654057608e-01 4.207713230364828333e-02 -2.282462273944179942e-01 9.598787356885335464e-01\n-1.530606226785305068e+01 1.413256628063003717e+01 2.199627038052340389e+00 -1.571426035282546818e-01 4.259567267890640441e-02 -2.278114988057656221e-01 9.599966085586523201e-01\n-1.514087565949761860e+01 1.409378848750856150e+01 2.199873242883951807e+00 -1.570254715378673060e-01 4.286541684680277020e-02 -2.283332991658232058e-01 9.598797937163758842e-01\n-1.498034452942751749e+01 1.405489914660284789e+01 2.200973272957193583e+00 -1.571775213891299372e-01 4.280269431575939310e-02 -2.299371452910466684e-01 9.594747592803697378e-01\n-1.482121006184025980e+01 1.401708694435837543e+01 2.197753955363283218e+00 -1.576473983988297967e-01 4.214352245069670488e-02 -2.325262432191075035e-01 9.588026482315483712e-01\n-1.466983996292526271e+01 1.397496022545172778e+01 2.194572255859627674e+00 -1.582920265446358388e-01 4.094213490888980872e-02 -2.361841713341422955e-01 9.578539371333814056e-01\n-1.453352887369791446e+01 1.393358679012593271e+01 2.190418074615139599e+00 -1.592016359939976422e-01 3.915596996180333716e-02 -2.409854874862833729e-01 9.565810926802701397e-01\n-1.439827424546816204e+01 1.388542956385763638e+01 2.183351167213614108e+00 -1.604243221444694723e-01 3.654193201848164596e-02 -2.472768717811687222e-01 9.548730884675132868e-01\n-1.425669761309909767e+01 1.383277627131903920e+01 2.173425473550271381e+00 -1.620682001990153831e-01 3.307854631736246998e-02 -2.551892415462925778e-01 9.526373409199061504e-01\n-1.412590162618181289e+01 1.377712114185407088e+01 2.167234427590452928e+00 -1.639446513721360132e-01 2.899553668503442386e-02 -2.648674162229788243e-01 9.498033491687686292e-01\n-1.399604943682839142e+01 1.372158914898174764e+01 2.163970265701970597e+00 -1.657858129734203489e-01 2.406582795187409488e-02 -2.762822044488303930e-01 9.463634454060370071e-01\n-1.384661139511829120e+01 1.365143058518259167e+01 2.161904520263594698e+00 -1.678233245218127556e-01 1.828506504258629178e-02 -2.893916232965937363e-01 9.422065621608289865e-01\n-1.368006921888726701e+01 1.356123087789077530e+01 2.166096155544508850e+00 -1.701283568415986325e-01 1.191197093043556629e-02 -3.039668466991156670e-01 9.372930924319964330e-01\n-1.350985440111793068e+01 1.345763383471481056e+01 2.175242283285886202e+00 -1.725710839785354611e-01 5.075239848615055449e-03 -3.194541419225832568e-01 9.317415178968395661e-01\n-1.333697703434933857e+01 1.334215600679860358e+01 2.185838791556650396e+00 -1.750679068924898552e-01 -2.337291607788242933e-03 -3.355921660815493479e-01 9.255935483312971446e-01\n-1.316622061469933058e+01 1.322387309937271560e+01 2.197136583342674587e+00 -1.775351457546254785e-01 -1.014724224601772258e-02 -3.520047064885605259e-01 9.189508931296438421e-01\n-1.299703565313839526e+01 1.310376719126060507e+01 2.215860596135141858e+00 -1.799735251964539040e-01 -1.806386358304223894e-02 -3.686207810301289078e-01 9.118123200612366919e-01\n-1.283168503003983929e+01 1.298131717868560742e+01 2.235696275939695443e+00 -1.824075464885830389e-01 -2.615885946035455267e-02 -3.851350973103248032e-01 9.042753526796357688e-01\n-1.267741113485115889e+01 1.286063583119418219e+01 2.260013652335474799e+00 -1.848076219677117216e-01 -3.410309760761479764e-02 -4.011888836470370312e-01 8.965100939703536387e-01\n-1.253201695949777950e+01 1.273853756466149889e+01 2.289854396520654589e+00 -1.871327884395841412e-01 -4.181670002319468060e-02 -4.167913561875874473e-01 8.885479215972782452e-01\n-1.239863978088368057e+01 1.262283651605162049e+01 2.320628911511395387e+00 -1.892500114284657031e-01 -4.925487165030190823e-02 -4.318127606038639765e-01 8.805088769975960572e-01\n-1.227396043270233683e+01 1.251183608098020805e+01 2.351509364719013728e+00 -1.912744275848471676e-01 -5.635579653835351421e-02 -4.460962716794354965e-01 8.724883850854173728e-01\n-1.216051823961005240e+01 1.240915076818466822e+01 2.382139946864808344e+00 -1.932260904940433788e-01 -6.292957144351564447e-02 -4.594119531511073329e-01 8.646640758342634125e-01\n-1.205266159099152823e+01 1.230780791279903319e+01 2.416061604298839871e+00 -1.949856614867817584e-01 -6.886831191208621361e-02 -4.715655968278623100e-01 8.572417331603260360e-01\n-1.194514238363695569e+01 1.220397806549690145e+01 2.455611748650547099e+00 -1.966094868358854442e-01 -7.416589001951345850e-02 -4.823695417288748066e-01 8.503902129255297426e-01\n-1.183827173554612244e+01 1.208747529584322855e+01 2.510145093144891426e+00 -1.982654813135747707e-01 -7.852441961796580161e-02 -4.916076360240347887e-01 8.443023175323814966e-01\n-1.173756014225560662e+01 1.196418221569341789e+01 2.581550381106281655e+00 -1.998543923968104929e-01 -8.183923493788647363e-02 -4.989418827405184831e-01 8.392957352908562152e-01\n-1.163732329880508054e+01 1.182568728239220590e+01 2.672790209931520167e+00 -2.011187590883487530e-01 -8.439271952813923172e-02 -5.044072222011399820e-01 8.354652951616321488e-01\n-1.153635173778608802e+01 1.166349977492017231e+01 2.788874222994223384e+00 -2.023787857096887022e-01 -8.622784410876796479e-02 -5.079827912772086895e-01 8.328030155242747146e-01\n-1.143950013689890000e+01 1.149166655351469402e+01 2.928524681772375349e+00 -2.035215056948520007e-01 -8.740878554344684581e-02 -5.095161711255729031e-01 8.314636210992372156e-01\n-1.135773304335328859e+01 1.133922297177344163e+01 3.075193507733003262e+00 -2.041824177583614619e-01 -8.757948540178962793e-02 -5.088236989862157111e-01 8.317076320332140726e-01\n-1.128699032941793767e+01 1.120075420766714025e+01 3.230513953070606181e+00 -2.047516830280953493e-01 -8.649289447884173088e-02 -5.060204106363749288e-01 8.333899617835321960e-01\n-1.122313447529674590e+01 1.107289294214347919e+01 3.385157011413508776e+00 -2.053711844052330260e-01 -8.408611022249672107e-02 -5.012543003408139741e-01 8.363588315347345592e-01\n-1.115248117688900820e+01 1.094133733651713491e+01 3.555691288090234714e+00 -2.056462033375179854e-01 -8.075730723813241696e-02 -4.951674025132455914e-01 8.402362303435323421e-01\n-1.108732048213619414e+01 1.081456404053830234e+01 3.717121101071051648e+00 -2.059910685309201961e-01 -7.650109225546963820e-02 -4.874224662550116771e-01 8.450647273734225307e-01\n-1.101494070912414713e+01 1.068284157588535521e+01 3.886119635478032297e+00 -2.061466384733158519e-01 -7.127643491142374166e-02 -4.784386800959306019e-01 8.505994696215272155e-01\n-1.093524173425383594e+01 1.054803923807605948e+01 4.058019727573429769e+00 -2.061099341383379191e-01 -6.507997307295336487e-02 -4.681790076260793354e-01 8.567914006080686873e-01\n-1.084763447487299537e+01 1.041268831336648404e+01 4.229629705735738376e+00 -2.057315387040039856e-01 -5.772430254235429853e-02 -4.568317663531050177e-01 8.635085207620848413e-01\n-1.074511561564592022e+01 1.027247535588492511e+01 4.400687582912439666e+00 -2.046454030423378867e-01 -4.918420410341037274e-02 -4.446273787415646606e-01 8.706362310051629638e-01\n-1.062932761967035589e+01 1.012820442647781150e+01 4.553728133787957155e+00 -2.029565690760325170e-01 -3.949167088139289572e-02 -4.311415380845254330e-01 8.782743283105247656e-01\n-1.049700918522519721e+01 9.987838589611772733e+00 4.669379209295867028e+00 -2.008189702976947155e-01 -2.903101795731325221e-02 -4.166969991530746209e-01 8.861107850649578843e-01\n-1.035518267560249939e+01 9.861969085908372179e+00 4.751070819784137811e+00 -1.958454252688869301e-01 -1.868715204652300274e-02 -4.016501144514015298e-01 8.944117098230366381e-01\n-1.020832808150564475e+01 9.749660002455138752e+00 4.807984829444467145e+00 -1.903070630035642863e-01 -7.593968791745912307e-03 -3.861295325734883654e-01 9.025681642910160507e-01\n-1.006462358990678396e+01 9.652235384479599389e+00 4.846173601572889567e+00 -1.847445601796558479e-01 4.365578917755052676e-03 -3.701214127740822257e-01 9.104176421348203485e-01\n-9.928657381585725972e+00 9.568888013689392125e+00 4.867075191618293495e+00 -1.792362421215590584e-01 1.718675473453972966e-02 -3.538081418758112218e-01 9.178227182108023019e-01\n-9.795577920659157556e+00 9.494090355712675233e+00 4.878113693445429888e+00 -1.737343257625819093e-01 3.081909256437668707e-02 -3.375861476186318155e-01 9.246090618534862360e-01\n-9.661176967701988971e+00 9.423962946457072221e+00 4.882171328813533329e+00 -1.681756565410551796e-01 4.502750568400982339e-02 -3.216238190481252035e-01 9.307240917155382709e-01\n-9.526235813569117639e+00 9.358046157154838340e+00 4.879546246116782449e+00 -1.627319079534192414e-01 5.965657446638202022e-02 -3.062229051444254613e-01 9.360484561081945376e-01\n-9.390715066920950704e+00 9.294511340234727470e+00 4.872074737937317046e+00 -1.575600456324180998e-01 7.452147882480016083e-02 -2.916078133009603612e-01 9.405243241610005134e-01\n-9.255741124676109877e+00 9.233168477068076641e+00 4.862719929474887515e+00 -1.526083636231672647e-01 8.970028692292388028e-02 -2.779558671478457588e-01 9.441423766854085686e-01\n-9.110115748703927707e+00 9.160656321856599504e+00 4.853119718596683008e+00 -1.448805444527668240e-01 1.042704447501368176e-01 -2.654940920189678422e-01 9.474438960705133805e-01\n-8.960508298635936342e+00 9.086392725294514250e+00 4.844143091669125489e+00 -1.368322183912593359e-01 1.191111185464089617e-01 -2.543805445511533869e-01 9.499367212115463754e-01\n-8.802053506879710554e+00 9.010855401599721759e+00 4.832301039463605896e+00 -1.284837162166377333e-01 1.338807568014935556e-01 -2.445762298229477716e-01 9.517090363254917529e-01\n-8.636209778905397982e+00 8.932626204285671889e+00 4.818409796669749667e+00 -1.199414029479377447e-01 1.484064460215570591e-01 -2.359549264073556307e-01 9.528455386988187170e-01\n-8.464140448895715707e+00 8.850351050039439116e+00 4.803352734674167124e+00 -1.112792292450228149e-01 1.626455393506967828e-01 -2.284682760107906996e-01 9.533967514881616090e-01\n-8.285842459073196054e+00 8.773383956707331066e+00 4.782369279912356497e+00 -1.025146313610508786e-01 1.764788996614772842e-01 -2.221124353490130932e-01 9.534210932004744121e-01\n-8.114133289484326994e+00 8.705543691922068561e+00 4.757856858937089761e+00 -9.388423022029269982e-02 1.897102117440097879e-01 -2.167248350967028725e-01 9.530088667976455152e-01\n-7.966413532293470823e+00 8.649262174225476940e+00 4.732697675124038383e+00 -8.546786416506156614e-02 2.021958267635559636e-01 -2.122202162550722582e-01 9.522470547132205754e-01\n-7.838296370121983436e+00 8.602142342702320477e+00 4.706681049907486702e+00 -7.722082121429661716e-02 2.138807004510542842e-01 -2.086132058058942085e-01 9.511951941279739309e-01\n-7.722460607913379960e+00 8.555961850315631168e+00 4.682140683149526694e+00 -6.926594664978155680e-02 2.246589746999888837e-01 -2.057724656928235640e-01 9.499410831019948764e-01\n-7.623831137275054459e+00 8.512771062322395110e+00 4.657138786462549085e+00 -6.168996695748747705e-02 2.343784833952097801e-01 -2.037189628972736477e-01 9.485565157627455779e-01\n-7.546843188356539223e+00 8.472208031328831268e+00 4.633192190619449313e+00 -5.450375163225126135e-02 2.430585373033365970e-01 -2.024227503969243946e-01 9.470885500355606945e-01\n-7.486476728816337634e+00 8.440815148072747576e+00 4.610710309118721817e+00 -4.770571378634198140e-02 2.506317554601256714e-01 -2.020770809235940546e-01 9.455540866581557680e-01\n-7.440299964705224589e+00 8.416958122596488678e+00 4.593164121767197905e+00 -4.140588616186403198e-02 2.570514082178247950e-01 -2.025012668505896951e-01 9.440355657182665228e-01\n-7.396345226618334046e+00 8.397243593556252605e+00 4.580928575928226998e+00 -3.559464193890889833e-02 2.619480351332992840e-01 -2.040529019416751078e-01 9.425913457587361544e-01\n-7.359082997625071343e+00 8.384106685373392764e+00 4.568838528947360977e+00 -3.082171805157595326e-02 2.643322252904545810e-01 -2.069175931235628374e-01 9.414687456203280069e-01\n-7.302026356289392339e+00 8.357480387139352374e+00 4.544941278909785609e+00 -2.705147037784246672e-02 2.635474766097758992e-01 -2.108188989966877647e-01 9.409389584548618624e-01\n-7.249194796845570998e+00 8.332448662081926472e+00 4.522177037968137192e+00 -2.348931618740522642e-02 2.629461495568421459e-01 -2.151934143954868928e-01 9.402122886374607580e-01\n-7.192574988222773413e+00 8.304052243351245366e+00 4.498606689260705949e+00 -2.019453168423964579e-02 2.624139011815839195e-01 -2.200437222374501678e-01 9.393144602230939499e-01\n-7.134046519940341113e+00 8.271338824996039563e+00 4.475103494481515121e+00 -1.720243089105051582e-02 2.619425976925379151e-01 -2.252009680059845753e-01 9.382827111412271881e-01\n-7.101496752580978011e+00 8.256352049370411450e+00 4.464792718273583816e+00 -1.608926579076124311e-02 2.563946365376729153e-01 -2.316767545295572439e-01 9.382582764825715405e-01\n-7.066311361565515980e+00 8.229456314921264948e+00 4.452957677367096245e+00 -1.588172072373412666e-02 2.486992594060363493e-01 -2.384370209333511736e-01 9.386394576744967466e-01\n-7.023231946952388505e+00 8.189605347353088760e+00 4.440963527834605351e+00 -1.649931232245117549e-02 2.391868458650006912e-01 -2.455518537738545781e-01 9.392664750276934482e-01\n-6.979041839034425543e+00 8.143272453791784216e+00 4.430181111014941386e+00 -1.786565177166500942e-02 2.279937541361085895e-01 -2.529972316317633529e-01 9.400488617876656683e-01\n-6.935183589108718571e+00 8.089564188639213782e+00 4.422930206766563899e+00 -1.998480485305475368e-02 2.154290072454379257e-01 -2.606377633159859819e-01 9.408818707293717942e-01\n-6.888868303451047836e+00 8.030702240266915481e+00 4.417015406419602996e+00 -2.287103566259705151e-02 2.016401886372044816e-01 -2.684141293202135237e-01 9.416856130777121470e-01\n-6.840674241225232599e+00 7.967394404473957081e+00 4.412340650852007329e+00 -2.640110625360386071e-02 1.867330320427368351e-01 -2.761348269065626027e-01 9.424346671394686625e-01\n-6.783646706868969645e+00 7.893077095892037320e+00 4.406745275081826563e+00 -3.049310860789122488e-02 1.707747820104351943e-01 -2.838466760501241470e-01 9.430466609513866727e-01\n-6.706675553581081139e+00 7.805858116523429757e+00 4.399698552885772607e+00 -3.517078950191957626e-02 1.539407376304821329e-01 -2.915211517472718339e-01 9.434407566295304193e-01\n-6.608358311218235137e+00 7.714939868202249862e+00 4.390607292666790507e+00 -4.032984107040732402e-02 1.362637847355430420e-01 -2.991954937832328465e-01 9.435504829919811876e-01\n-6.496344793411751084e+00 7.635577509875125735e+00 4.374959519035974687e+00 -4.606334997161197486e-02 1.176713080147281237e-01 -3.069104571995260322e-01 9.433119127938537352e-01\n-6.377487104502294279e+00 7.559796599687431673e+00 4.357834903699150608e+00 -5.216803244863016387e-02 9.851820270137630342e-02 -3.145480621841146851e-01 9.426727619600988595e-01\n-6.253332481168209611e+00 7.486272953676961883e+00 4.337973343863350983e+00 -5.869621212591501908e-02 7.896475123581589428e-02 -3.220200705284214648e-01 9.416061618763930108e-01\n-6.125955660049786644e+00 7.416734456754976890e+00 4.318464720724177752e+00 -6.561700398737782547e-02 5.905604672987263548e-02 -3.295377877320313509e-01 9.400060645074467258e-01\n-6.003543153951099498e+00 7.348223801923311704e+00 4.300963972352018772e+00 -7.299305252052640247e-02 3.916334266508965378e-02 -3.366025357079139857e-01 9.379961291790802624e-01\n-5.880512867404823041e+00 7.277274617380643740e+00 4.282508140535700392e+00 -8.085000752411357350e-02 1.931657739625739292e-02 -3.431589170379617526e-01 9.355917188810530805e-01\n-5.752199727943890117e+00 7.205898979355740863e+00 4.264124981893480104e+00 -8.880612838383861174e-02 -1.839939236060274318e-04 -3.490965591188769923e-01 9.328691180592872945e-01\n-5.620867968844497575e+00 7.133680648589026951e+00 4.248143531305163201e+00 -9.684880036799936587e-02 -1.922477257833903747e-02 -3.542156685044489661e-01 9.299364131219416407e-01\n-5.487357874667395663e+00 7.063942181732535630e+00 4.235131167686096987e+00 -1.048774302590843588e-01 -3.769935494056864816e-02 -3.586219151837029551e-01 9.268061084962051499e-01\n-5.351468054219385984e+00 7.001415512029576682e+00 4.221427222353877795e+00 -1.129437658115804433e-01 -5.559397401524718285e-02 -3.623312765097851940e-01 9.235089714721697041e-01\n-5.215343083461586815e+00 6.942455538290364991e+00 4.209360461916056728e+00 -1.210502069832659344e-01 -7.255572553426346827e-02 -3.652346965790361222e-01 9.201553656388268276e-01\n-5.077978219438366914e+00 6.884623083408889066e+00 4.199271436486815112e+00 -1.293062233471359845e-01 -8.853527020957462079e-02 -3.674283988327597394e-01 9.167538155023878810e-01\n-4.936981366718767639e+00 6.825944957851960204e+00 4.184431251317998424e+00 -1.377268663162275475e-01 -1.038090277746670370e-01 -3.689458283477936029e-01 9.133092345837549031e-01\n-4.799067951959267830e+00 6.767530718028485381e+00 4.167587916588884056e+00 -1.462227977877073315e-01 -1.183681824697107587e-01 -3.697480938739740042e-01 9.098868043232711811e-01\n-4.659851106914774554e+00 6.708264457925801061e+00 4.146864561326532694e+00 -1.546790427632031839e-01 -1.322488951593409623e-01 -3.700943353112481904e-01 9.064295818552727813e-01\n-4.522188911375335962e+00 6.649766699923481461e+00 4.125261756970721727e+00 -1.630881252217175059e-01 -1.453561096703797351e-01 -3.699021021501966988e-01 9.030205405840713295e-01\n-4.384336257272807735e+00 6.592750756864155015e+00 4.104585628073848191e+00 -1.713861896820074171e-01 -1.577184267005262430e-01 -3.692641992798849082e-01 8.996640653209384553e-01\n-4.250973995207671052e+00 6.537395187942486530e+00 4.087722524472261476e+00 -1.795708065933855901e-01 -1.692032476285243170e-01 -3.683439904464128056e-01 8.963521108677855453e-01\n-4.119881159089879397e+00 6.483124114210427891e+00 4.074099790579315261e+00 -1.875247269533678318e-01 -1.798487727683729109e-01 -3.671948340929857002e-01 8.931162726885953917e-01\n-3.986719846703399739e+00 6.430081682505231377e+00 4.063457033507956950e+00 -1.950501282673557935e-01 -1.897321176069262927e-01 -3.657920878694423394e-01 8.900298624484728194e-01\n-3.857806398098146961e+00 6.376368202825703158e+00 4.050154850419703578e+00 -2.025033880086890281e-01 -1.989905774586621656e-01 -3.640499842730823832e-01 8.870527416890000572e-01\n-3.733261705384908868e+00 6.323539375167103849e+00 4.034584292157113339e+00 -2.097529231168790420e-01 -2.076064800471262295e-01 -3.621125463825130009e-01 8.841818827288916438e-01\n-3.608895954391719840e+00 6.268594256964607148e+00 4.018608938499705019e+00 -2.167298606279331741e-01 -2.157054293662292455e-01 -3.599471943344783043e-01 8.814404110978438789e-01\n-3.484578877128846841e+00 6.211247339903801290e+00 4.002878100488556967e+00 -2.233355575556960071e-01 -2.232795469326028792e-01 -3.575758573962185549e-01 8.788667835228113345e-01\n-3.361961781382274861e+00 6.152604211490512398e+00 3.987491560176556593e+00 -2.296326114300094590e-01 -2.303731593773752084e-01 -3.550985408290596168e-01 8.764142549027159612e-01\n-3.232963224561080207e+00 6.092362024818040567e+00 3.971946792803201731e+00 -2.355387531475781060e-01 -2.370476390156331381e-01 -3.525263185246546027e-01 8.741023728411995153e-01\n-3.096806288696448473e+00 6.032428544600991316e+00 3.957059679993236934e+00 -2.409063130901048233e-01 -2.432742862646420090e-01 -3.499663749929467493e-01 8.719547870850730131e-01\n-2.947835898989248804e+00 5.971301466077779452e+00 3.941377327530580121e+00 -2.457396268570619657e-01 -2.491844071049651721e-01 -3.474969933653390686e-01 8.699223264919266896e-01\n-2.785655452816519606e+00 5.908597375916054162e+00 3.925311168851185695e+00 -2.499514306323248614e-01 -2.546738318261297929e-01 -3.451455502244761275e-01 8.680667693277970276e-01\n-2.612704489809447139e+00 5.843342742627270603e+00 3.908542328851709158e+00 -2.535515842518141771e-01 -2.598313598438937166e-01 -3.429015539914031518e-01 8.663819208033343156e-01\n-2.455399236820277942e+00 5.785151754944600100e+00 3.892242304149701848e+00 -2.539072761237607390e-01 -2.659010252763311377e-01 -3.403582355159561201e-01 8.654385333501263267e-01\n-2.293190962984199999e+00 5.723915231927273695e+00 3.876423312901263962e+00 -2.542894226008700631e-01 -2.714890557432704798e-01 -3.381377392628824308e-01 8.644612780053019252e-01\n-2.132373455540924390e+00 5.660935038304082845e+00 3.860920394488562835e+00 -2.547217607893528246e-01 -2.766660536020267291e-01 -3.362315999067881922e-01 8.634355157012689741e-01\n-1.971021436458088694e+00 5.595174079862699656e+00 3.846183329849794941e+00 -2.551964250719007121e-01 -2.814446574914436505e-01 -3.345882303122783008e-01 8.623887001362717797e-01\n-1.807598528662877957e+00 5.524880524458068543e+00 3.830543208442553027e+00 -2.557911745855398489e-01 -2.858331761697825990e-01 -3.331920886003421067e-01 8.613089869330943227e-01\n-1.636396750634920849e+00 5.449308591653828415e+00 3.814179987336483002e+00 -2.564356646716348109e-01 -2.898095296325224335e-01 -3.320076105548865342e-01 8.602453154731618534e-01\n-1.462849563296797939e+00 5.371808452666209099e+00 3.797672266084052506e+00 -2.570846326308839913e-01 -2.934042790718436877e-01 -3.310843152500332343e-01 8.591882670241032249e-01\n-1.288959287414961796e+00 5.292917677155276834e+00 3.781545168563773984e+00 -2.577150435771182191e-01 -2.966579214383787133e-01 -3.303889811051302083e-01 8.581491827892056001e-01\n-1.110384294059284738e+00 5.211388943277480479e+00 3.765021413855301535e+00 -2.582909199352131369e-01 -2.996411462888850519e-01 -3.299194320397960123e-01 8.571196094334919691e-01\n-9.306947922898101133e-01 5.129943480558734947e+00 3.748700907305206886e+00 -2.588553676685850791e-01 -3.023829077184999603e-01 -3.296466100733500548e-01 8.560908006544866167e-01\n-7.494490685971613164e-01 5.049509158624354122e+00 3.732439212189940125e+00 -2.593950529272124883e-01 -3.049098097719332712e-01 -3.295787314463892170e-01 8.550566825203730348e-01\n-5.667012248128854290e-01 4.970188515249279071e+00 3.716356193768302063e+00 -2.599189540195596115e-01 -3.071948295083041791e-01 -3.296747320403945469e-01 8.540421010068511842e-01\n-3.860252854679036005e-01 4.892396188679936309e+00 3.700342768031741336e+00 -2.604240794617456167e-01 -3.092307619911773275e-01 -3.299333368873552663e-01 8.530530468325369098e-01\n-2.072054335978287809e-01 4.816065056247569309e+00 3.683928818633339208e+00 -2.608932064002745799e-01 -3.110089615292314091e-01 -3.303045370677028525e-01 8.521190897992432234e-01\n-2.447975579075292729e-02 4.740467106325708890e+00 3.665415456885624312e+00 -2.613135702090207402e-01 -3.126000364908323448e-01 -3.308125963372271494e-01 8.512105144502563059e-01\n1.595740249002560729e-01 4.665596905702058095e+00 3.644972489376070879e+00 -2.616471515267254078e-01 -3.140208114602017209e-01 -3.314132164393753244e-01 8.503510167153639498e-01\n3.471288447045393077e-01 4.592472284345312517e+00 3.621866047608115924e+00 -2.619265891786012879e-01 -3.153883736017398798e-01 -3.320535384187794925e-01 8.495086451738068645e-01\n5.396921092991235902e-01 4.519869961037433548e+00 3.596445246442431909e+00 -2.621150676509559907e-01 -3.167384979479005991e-01 -3.326630847997775198e-01 8.487093440523550969e-01\n7.346148540931147775e-01 4.446154606730820191e+00 3.569251401890256137e+00 -2.622470510724456694e-01 -3.180828556285650865e-01 -3.331491282575469448e-01 8.479748298607119317e-01\n9.277145905395938197e-01 4.371409091765972477e+00 3.540091949644653901e+00 -2.626230253190023900e-01 -3.193624715034126260e-01 -3.335856134824063957e-01 8.472055639799496163e-01\n1.147408349023798069e+00 4.281853873535411026e+00 3.511632800095275897e+00 -2.628203931086945389e-01 -3.193106846024571510e-01 -3.337710710169577433e-01 8.470908282256689459e-01\n1.371228197384347425e+00 4.190689634470587954e+00 3.482504849926784107e+00 -2.630578164411414566e-01 -3.193105176189386385e-01 -3.338745359760006415e-01 8.469764171327285318e-01\n1.602631115346870860e+00 4.097610571536848489e+00 3.453718898542426530e+00 -2.632061328141644396e-01 -3.193060045923379331e-01 -3.339019271168552905e-01 8.469212385752546979e-01\n1.842365399673236093e+00 4.002317572365756249e+00 3.425523951207936957e+00 -2.633080283766072172e-01 -3.192899564009949454e-01 -3.338950352034970037e-01 8.468983398369697158e-01\n2.094720218907040632e+00 3.903878329413128512e+00 3.398803037233063318e+00 -2.633433159475628282e-01 -3.192180823322913752e-01 -3.338741291112674592e-01 8.469227088957377303e-01\n2.354262591754949341e+00 3.802152009202809158e+00 3.371593096554410085e+00 -2.633424979717358116e-01 -3.191920957378263646e-01 -3.337663848244893927e-01 8.469752245128163715e-01\n2.604197411746636881e+00 3.703220435939146959e+00 3.344303562073439817e+00 -2.633523283509775492e-01 -3.191927118787689643e-01 -3.336429326564991360e-01 8.470205656605683808e-01\n2.849775638970309721e+00 3.605343351638679028e+00 3.316527186966311547e+00 -2.633916373959189206e-01 -3.191995139476732080e-01 -3.334907466265020770e-01 8.470657089718527377e-01\n3.097269574732867792e+00 3.506807682250299152e+00 3.289455236294969609e+00 -2.634189178173160228e-01 -3.191981926378932299e-01 -3.333384052945241316e-01 8.471176831536757490e-01\n3.342667446625483318e+00 3.406404482585304372e+00 3.262533902487871007e+00 -2.635555257933511752e-01 -3.191790282508754628e-01 -3.331869385297593911e-01 8.471420100346495063e-01\n3.593692424357135540e+00 3.301117941430975478e+00 3.236380047578341745e+00 -2.637593801182107622e-01 -3.191393166883175203e-01 -3.330730963503033548e-01 8.471382904737906339e-01\n3.852259093578912719e+00 3.192793752004558172e+00 3.213368726070757742e+00 -2.640442641389767475e-01 -3.189400741266654737e-01 -3.330624427466959414e-01 8.471287691376589990e-01\n4.113682057355155131e+00 3.082963511105495158e+00 3.191243107632094844e+00 -2.643981242925143027e-01 -3.187506099625990741e-01 -3.331401395710793523e-01 8.470591522750866575e-01\n4.370650574498331942e+00 2.977905077017091617e+00 3.169436135804180488e+00 -2.645646206709125758e-01 -3.185704737972833156e-01 -3.334163189360682122e-01 8.469662612022570425e-01\n4.620010054486803242e+00 2.871391553607040237e+00 3.146975411462293870e+00 -2.647681049364830619e-01 -3.183207930799472063e-01 -3.337982696995875909e-01 8.468461048975165495e-01\n4.863105136758973934e+00 2.762516502334317892e+00 3.123525705996005097e+00 -2.651349630960089243e-01 -3.180136252111560591e-01 -3.342822003727763946e-01 8.466558281521140428e-01\n5.106965073624266438e+00 2.652677746937647907e+00 3.098733993142643417e+00 -2.655768091290671706e-01 -3.176437851507328269e-01 -3.348761857328731439e-01 8.464214163404696345e-01\n5.354525067790735449e+00 2.541683752404830798e+00 3.074547760560428333e+00 -2.659806296365726519e-01 -3.173161632991127190e-01 -3.356035998930727571e-01 8.461293501372315617e-01\n5.597027485204747244e+00 2.429894493447691151e+00 3.050253510475960272e+00 -2.664232896895293301e-01 -3.169067121365465312e-01 -3.365219601688203555e-01 8.457787065808948235e-01\n5.836457741611654981e+00 2.315672829549108691e+00 3.025680323846295483e+00 -2.668654645992337149e-01 -3.164087699659623443e-01 -3.375767531686643674e-01 8.454053050542151837e-01\n6.117179288033596229e+00 2.190876188079310172e+00 3.010688665963426658e+00 -2.625925915965534596e-01 -3.144352311098035924e-01 -3.373157174925847657e-01 8.475810285781371078e-01\n6.392460556058090049e+00 2.067228880174349470e+00 2.996010438678178733e+00 -2.575668981622772358e-01 -3.123728920230591788e-01 -3.369449988173235377e-01 8.500296443946259162e-01\n6.658490381244710044e+00 1.939125647571039002e+00 2.981245968920347877e+00 -2.517209370236194732e-01 -3.102719220936205891e-01 -3.366281794051740883e-01 8.526718178173181562e-01\n6.912966313485639169e+00 1.809531368391803952e+00 2.966588253924220098e+00 -2.453541443386767218e-01 -3.081337647487315534e-01 -3.361372045666425334e-01 8.554919993791344490e-01\n7.166081066372939290e+00 1.678144150695186188e+00 2.953539738913553148e+00 -2.383598649625162380e-01 -3.059262103830030499e-01 -3.355485534593488084e-01 8.584874814499373619e-01\n7.407934894783917201e+00 1.540454532724790937e+00 2.940250316007217535e+00 -2.308189700194129834e-01 -3.039631380850821296e-01 -3.349167410328621752e-01 8.614868743738993695e-01\n7.645869190725107956e+00 1.402894482678236576e+00 2.927984272082231776e+00 -2.226982507458010185e-01 -3.019744150717587616e-01 -3.342011298824619780e-01 8.645960845077699242e-01\n7.879217222833892365e+00 1.263399767335893875e+00 2.916618247588234958e+00 -2.140442592818645184e-01 -3.000658136006504884e-01 -3.333421032048318744e-01 8.677721226945004362e-01\n8.101334182756193769e+00 1.114780728356713269e+00 2.903659326891121051e+00 -2.054042949094037063e-01 -2.983662472546353972e-01 -3.324355015884601916e-01 8.707888081023515969e-01\n8.316225389912437649e+00 9.739550368439301442e-01 2.890432379311826061e+00 -1.964004584317672053e-01 -2.967803379525187912e-01 -3.314081403746222954e-01 8.737944784908888707e-01\n8.518734735201679342e+00 8.313422478980142527e-01 2.874659751083602721e+00 -1.873391067637601437e-01 -2.954759115789979962e-01 -3.305242338919597844e-01 8.765566865973857258e-01\n8.714223449303062807e+00 6.901135551082709929e-01 2.853743022883866498e+00 -1.783814212996334136e-01 -2.947715811138956754e-01 -3.296676214527598514e-01 8.789817337026891719e-01\n8.901441703891322277e+00 5.477546585134192014e-01 2.829696535221562392e+00 -1.695609075824687784e-01 -2.944237726621946050e-01 -3.287275382093225451e-01 8.811933876497437534e-01\n9.078252217730501172e+00 4.047536081228386706e-01 2.802179636631398463e+00 -1.607081968684333506e-01 -2.945056761842785309e-01 -3.277574482865859284e-01 8.831841102795328080e-01\n9.256796672624741262e+00 2.524054102349223561e-01 2.773384531365481021e+00 -1.521706827702955511e-01 -2.949674485666893275e-01 -3.268486962327947776e-01 8.848774271648428558e-01\n9.437211480952583997e+00 1.019943370345930134e-01 2.740277687602983736e+00 -1.435440180017515943e-01 -2.962383808567644605e-01 -3.259722865758864496e-01 8.862165957787457859e-01\n9.614766413691938851e+00 -4.729431208288253918e-02 2.704138251970213069e+00 -1.351058412327545422e-01 -2.977652060887240881e-01 -3.255769416052359810e-01 8.871763062267944422e-01\n9.770680202075253007e+00 -2.137748156193516880e-01 2.660377981225994670e+00 -1.277980964958311261e-01 -2.994357142642493641e-01 -3.253508338443577008e-01 8.877795700325497030e-01\n9.895132899960527695e+00 -3.858343836036971508e-01 2.598976673030808371e+00 -1.209923776176651394e-01 -3.012916446279859106e-01 -3.253564029833109772e-01 8.881031691856229315e-01\n1.000784447976543312e+01 -5.542553917153727472e-01 2.539350212476968682e+00 -1.150348663748838318e-01 -3.041427652656003011e-01 -3.249411924668446083e-01 8.880750053336999850e-01\n1.011265858691146668e+01 -7.179240050332311718e-01 2.470303229771022568e+00 -1.093006246538966303e-01 -3.081398019909077357e-01 -3.242624791160269027e-01 8.876693710704502971e-01\n1.022179692454391642e+01 -8.938462439381638092e-01 2.398513353490872024e+00 -1.035879986039058426e-01 -3.130950296430229929e-01 -3.240235413764137040e-01 8.867071670131574379e-01\n1.031148418984229131e+01 -1.040490301961203068e+00 2.307379810975608070e+00 -9.895497979985456993e-02 -3.183025159083416877e-01 -3.241619410384071198e-01 8.853305944841912689e-01\n1.037458622336226632e+01 -1.199648378737218524e+00 2.155572717082807621e+00 -9.703088203751170093e-02 -3.235862015959237725e-01 -3.236099439488839824e-01 8.838288200747589363e-01\n1.033318031932382652e+01 -1.293788436612981485e+00 1.905604072331350318e+00 -9.583695922994829586e-02 -3.271036389910402797e-01 -3.223569286728097949e-01 8.831218936305078593e-01\n1.023160183727370587e+01 -1.297948238006191302e+00 1.686275207041092905e+00 -9.387844954349483517e-02 -3.285142537315361988e-01 -3.222070139403097611e-01 8.828633200513485990e-01\n1.013119133191871235e+01 -1.261453794927615002e+00 1.542548847588035343e+00 -9.191333695847365981e-02 -3.317726228408854894e-01 -3.209426832334480451e-01 8.823119792264556560e-01\n9.993068328826669955e+00 -1.199750050880664665e+00 1.419193056000999986e+00 -8.955600720068797316e-02 -3.350458152737550988e-01 -3.208571001218437635e-01 8.813481293069412859e-01\n9.839563844464670694e+00 -1.128046972397543257e+00 1.338773818802253768e+00 -8.716823732184753037e-02 -3.382973192498133219e-01 -3.202054633799073513e-01 8.805821249443431809e-01\n9.728775802832204889e+00 -1.067105695522975850e+00 1.317468721063768111e+00 -8.511297273402342045e-02 -3.411115703857309223e-01 -3.203872894876689248e-01 8.796308638173925276e-01\n9.592023064321383075e+00 -9.725138047100572170e-01 1.308323457140910140e+00 -8.324578925318551481e-02 -3.431697891317079252e-01 -3.206000584852718993e-01 8.789311876194231266e-01\n9.442514675688185477e+00 -8.865337403329596189e-01 1.309883048538571071e+00 -8.166234106319285313e-02 -3.443225012511207939e-01 -3.203618421632400404e-01 8.787157501268997306e-01\n9.243589006673698094e+00 -7.912641982220930403e-01 1.325250630842437660e+00 -8.058690716438521306e-02 -3.443962014632983015e-01 -3.198974240769477673e-01 8.789553095603842570e-01\n9.018713194484710982e+00 -6.973293621360053818e-01 1.349168903506297035e+00 -7.925052868461171518e-02 -3.430578774573275203e-01 -3.191651674739566236e-01 8.798659243559093790e-01\n8.794012934437590800e+00 -6.187998979776567765e-01 1.382093492347846064e+00 -7.754037262700048949e-02 -3.400949725598375606e-01 -3.182367278169105362e-01 8.815033030004451042e-01\n8.581093571463386027e+00 -5.678327707402348601e-01 1.432173235376540177e+00 -7.591787169801128554e-02 -3.351992479099216160e-01 -3.175150776307634204e-01 8.837770662728448023e-01\n8.356264859884369400e+00 -5.286084301729339074e-01 1.484533567428590217e+00 -7.475072075718444675e-02 -3.282424444301498823e-01 -3.172419918661169014e-01 8.865813747828040770e-01\n8.118141635712989412e+00 -4.533118041249175612e-01 1.546988785181073300e+00 -7.313787077684372195e-02 -3.184073158508980428e-01 -3.174481306661658953e-01 8.902213780012463440e-01\n7.885570979441841821e+00 -3.983022579506699801e-01 1.601614041429946012e+00 -7.222139811872199666e-02 -3.061747143521878489e-01 -3.167312789249355776e-01 8.948308206659270070e-01\n7.682280939427666766e+00 -3.426629948067420051e-01 1.660634392982965668e+00 -7.179067418860048122e-02 -2.919527620693291858e-01 -3.160240699340598480e-01 8.998545718211709010e-01\n7.483608420427465546e+00 -2.961222204354244103e-01 1.719483263801687478e+00 -7.238493429684997316e-02 -2.753927756205827304e-01 -3.125801758836983524e-01 9.062078343684074611e-01\n7.309593075800011164e+00 -2.491927950743856868e-01 1.762921616388872792e+00 -7.432672740303010450e-02 -2.591273842264239513e-01 -3.102336817168699912e-01 9.116377394746917329e-01\n7.186201407452266210e+00 -1.870181783399862685e-01 1.766995228434814047e+00 -7.570759026599568897e-02 -2.432403940302289014e-01 -3.089772647673496020e-01 9.163161567725046641e-01\n7.040016477131526784e+00 -1.254953908139266883e-01 1.774089566325022238e+00 -7.670085028303229302e-02 -2.236201011955259443e-01 -3.070589235930023531e-01 9.218598784147321590e-01\n6.883667222996407986e+00 -6.709789548504513368e-02 1.768740016452765795e+00 -7.695912179331232394e-02 -2.017136002352660218e-01 -3.033548059118340579e-01 9.280972875644398767e-01\n6.722489697222223448e+00 -7.132980592086404781e-03 1.773727667361867155e+00 -7.704205922201358414e-02 -1.771477949789016793e-01 -2.990543712304484791e-01 9.344781770924713848e-01\n6.553664031184613492e+00 4.363647910078472664e-02 1.788075056764896420e+00 -7.705471421229488638e-02 -1.507743054792893000e-01 -2.944771267846891249e-01 9.405385123347719256e-01\n6.399744872508970950e+00 9.213386090419793673e-02 1.804570210033077604e+00 -7.626469955704046066e-02 -1.232300052429474158e-01 -2.889706227736842936e-01 9.463053576260282984e-01\n6.283577945003052889e+00 1.409379348652331776e-01 1.817695696466347099e+00 -7.497477266826389763e-02 -9.556048504081869621e-02 -2.839805537480736830e-01 9.511055689135718971e-01\n6.165654234236661146e+00 1.886136316691612858e-01 1.828152981630380758e+00 -7.364911608445168234e-02 -6.751080611787575736e-02 -2.786812776149009130e-01 9.551725629693529340e-01\n6.006019668023494518e+00 2.544104705378745779e-01 1.826357011983414491e+00 -7.209285452247593540e-02 -3.768186370331205043e-02 -2.730092473174886014e-01 9.585658163086976380e-01\n5.851285669886095775e+00 3.135814254923192101e-01 1.831344793058397036e+00 -7.008086715476420647e-02 -7.712049288828025199e-03 -2.676113689847374744e-01 9.609438667054630567e-01\n5.687481187047801257e+00 3.753294979574372525e-01 1.826613185591021926e+00 -6.757506981026646653e-02 2.210565334137030991e-02 -2.620294546172630690e-01 9.624371524220843854e-01\n5.572482549207586899e+00 4.318711072780065385e-01 1.824131582377623184e+00 -6.455514472084453170e-02 5.101699181857401871e-02 -2.566402477532203075e-01 9.629981458207059752e-01\n5.463498683954522761e+00 4.789541105287173361e-01 1.817043558246825841e+00 -6.089649783964248136e-02 7.818583888336987087e-02 -2.515926628039379387e-01 9.627457985270306828e-01\n5.373660904996192755e+00 5.170222625909541847e-01 1.821363672678161016e+00 -5.648860974444370325e-02 1.046954015972235003e-01 -2.467684888537582666e-01 9.617447518947903617e-01\n5.292031383098232844e+00 5.478507349686534411e-01 1.826529350585744726e+00 -5.207748258217679421e-02 1.296791723418434794e-01 -2.422735039362444998e-01 9.600908974973291210e-01\n5.195276546738191392e+00 5.905541172720901733e-01 1.826909895560539621e+00 -4.731428839170495615e-02 1.533120260154208769e-01 -2.386195653872892619e-01 9.577667865653205492e-01\n5.092197376701467881e+00 6.452614676134084126e-01 1.829453752892473695e+00 -4.220872745835693024e-02 1.750102993576923560e-01 -2.355782546923148313e-01 9.550353076768015592e-01\n4.999395722764114147e+00 6.867274119595971893e-01 1.829890949949061207e+00 -3.705983355028762138e-02 1.937000885286660201e-01 -2.327405117138519886e-01 9.523331489764216284e-01\n4.904188612785413071e+00 7.230854418774752546e-01 1.825964567083782963e+00 -3.180907193893355023e-02 2.089741586944637297e-01 -2.299984308363392516e-01 9.499570750882178061e-01\n4.836359910417331598e+00 7.418748113249656884e-01 1.821516767781382384e+00 -2.630853752681055688e-02 2.213746912648067722e-01 -2.275513831475613480e-01 9.479035899050954894e-01\n4.774702623194593265e+00 7.594512672561393174e-01 1.823385491238055156e+00 -2.038097436678299595e-02 2.317929447355764339e-01 -2.254099005143083423e-01 9.460691130506385660e-01\n4.711944631315355458e+00 7.833726412195742839e-01 1.833813714964690034e+00 -1.423762970859515295e-02 2.407079291359719986e-01 -2.235820730232180864e-01 9.443875096112156475e-01\n4.657523108621798080e+00 8.003853495378130400e-01 1.840671087893041236e+00 -8.219002226126889341e-03 2.476918705681500910e-01 -2.220298698167657014e-01 9.430183694484783885e-01\n4.596358931879579224e+00 8.077105411340720353e-01 1.840197358001297578e+00 -2.252653806068338673e-03 2.528540218873879253e-01 -2.201001484410734788e-01 9.421334441070958743e-01\n4.513729575748419265e+00 8.234347702564530636e-01 1.845918812490166871e+00 2.441912602580241422e-03 2.517728788032461140e-01 -2.181656276710544906e-01 9.428721816207311646e-01\n4.446834005879682472e+00 8.332576422366795299e-01 1.848173300475050240e+00 7.337880936797516913e-03 2.507708835141969073e-01 -2.157774837802976520e-01 9.436630473104179462e-01\n4.367832664500934214e+00 8.495117597821696398e-01 1.847862784825574423e+00 1.255189815650801198e-02 2.498591285665464901e-01 -2.130857943807204780e-01 9.444612557364822081e-01\n4.278047546831988512e+00 8.726757823392047309e-01 1.852963461240989318e+00 1.783265084550779075e-02 2.490205004779956488e-01 -2.100835157820606092e-01 9.452700485000359309e-01\n4.187759666223808352e+00 8.966909365192722303e-01 1.861003620416938009e+00 2.304002229000207819e-02 2.483107479673281881e-01 -2.064868752841157451e-01 9.461362815581543240e-01\n4.100515627667462581e+00 9.191911665850622803e-01 1.871205763894083107e+00 2.811443648596686357e-02 2.476812695549159282e-01 -2.021626360448621762e-01 9.470974643019459682e-01\n4.017590127056370974e+00 9.457163438563104263e-01 1.882360796148873749e+00 3.310663952318108894e-02 2.472080442372935616e-01 -1.971543544096434342e-01 9.481150086226399765e-01\n3.935537952426522601e+00 9.747118430788668242e-01 1.888131497135645986e+00 3.778238227017630124e-02 2.469453856496486299e-01 -1.913063301364711921e-01 9.492060512382806126e-01\n3.844863648313443072e+00 1.006040667570216041e+00 1.891954198035363133e+00 4.200956620979449940e-02 2.469007605187059640e-01 -1.846575290367432620e-01 9.503560332466997052e-01\n3.752119776379838623e+00 1.030921014336568131e+00 1.895160540559985618e+00 4.572982454506694522e-02 2.471328095683613391e-01 -1.767601364033251354e-01 9.516248252162111676e-01\n3.655449276242216605e+00 1.047527968549495148e+00 1.896577398359254651e+00 4.889846738913333768e-02 2.476125954583918709e-01 -1.673065434560853382e-01 9.530505022535807891e-01\n3.551634402061322415e+00 1.052695227407163925e+00 1.897153145950726927e+00 5.158017875574462396e-02 2.484179267617634135e-01 -1.563113387765038831e-01 9.545651179835072941e-01\n3.433367344687048295e+00 1.057388574327681185e+00 1.893019431761171711e+00 5.351107157230604316e-02 2.495089121239796870e-01 -1.437991192074766500e-01 9.561398703838684954e-01\n3.304394071475590611e+00 1.063090447397548655e+00 1.885639777352333457e+00 5.468254737695817103e-02 2.508713596432330384e-01 -1.297737954647030512e-01 9.577222524999897679e-01\n3.174884511557202860e+00 1.057595977742291415e+00 1.871923674892396861e+00 5.512959625100254807e-02 2.515747685992416049e-01 -1.138548032405743704e-01 9.595351525592590303e-01\n3.042828940095391399e+00 1.054878158578969272e+00 1.859796949775027519e+00 5.502964306928410931e-02 2.531697064694624077e-01 -9.643531647962980125e-02 9.610290470209132963e-01\n2.886904068324312789e+00 1.051820898911627999e+00 1.850082813414826610e+00 5.445278744204544441e-02 2.554650968723521931e-01 -7.775334808345839288e-02 9.621468976568758880e-01\n2.737246884887406750e+00 1.044871013432058682e+00 1.843313201603032025e+00 5.342934757180003297e-02 2.584251323516172372e-01 -5.798309113619418143e-02 9.628081215938619764e-01\n2.595539215649875331e+00 1.036570209460514702e+00 1.838660812688639901e+00 5.194429891562304946e-02 2.619595488542477146e-01 -3.706639850511356943e-02 9.629666748603040727e-01\n2.471655378637240386e+00 1.020278307185802591e+00 1.832890396937285393e+00 5.025958364461263067e-02 2.659871585894769686e-01 -1.512084190171237956e-02 9.625465771267009973e-01\n2.361805375437458387e+00 9.946352421541702071e-01 1.819262243611750929e+00 4.831907901680129042e-02 2.703590516105336405e-01 7.970878288176675916e-03 9.615131114867041529e-01\n2.254798573921629412e+00 9.657731475642721275e-01 1.801584821853835949e+00 4.607461141922492703e-02 2.744682041790506011e-01 3.195523318727293283e-02 9.599598623523349916e-01\n2.156331200628903044e+00 9.354610770299200961e-01 1.785182304753967220e+00 4.349284820289647802e-02 2.783964684725468985e-01 5.682084500715660347e-02 9.577969054901966928e-01\n2.081093664573391511e+00 9.146482249127811937e-01 1.775003960629129685e+00 4.067061785910941474e-02 2.825575148398388192e-01 8.211915980762943268e-02 9.548629899942776555e-01\n2.003133753503066661e+00 8.867706236324429669e-01 1.756695982983064619e+00 3.802693536825232229e-02 2.864982988596169178e-01 1.078791048614142212e-01 9.512278924864361329e-01\n1.947019822678452305e+00 8.674125084140920094e-01 1.743373598653120915e+00 3.509895256714958695e-02 2.906579821852781631e-01 1.337572597115262718e-01 9.467812376610010849e-01\n1.927366560612738144e+00 8.604708776888644328e-01 1.735590456236154155e+00 3.182196997947735889e-02 2.946261339476313190e-01 1.595424884228644480e-01 9.416627401571485700e-01\n"
  },
  {
    "path": "VO_Module/thirdparty/tartanair_tools/evaluation/pose_gt.txt",
    "content": "8.257375717163085938e+00 -2.730143547058105469e+01 -3.229445695877075195e+00 -0.000000000000000000e+00 -0.000000000000000000e+00 1.324519515037536621e-01 9.911894202232360840e-01\n8.150029182434082031e+00 -2.726499938964843750e+01 -3.124113798141479492e+00 1.005725376307964325e-02 1.408183714374899864e-03 1.519933491945266724e-01 9.883292913436889648e-01\n8.035955429077148438e+00 -2.722590827941894531e+01 -3.013025999069213867e+00 2.116696164011955261e-02 2.910247072577476501e-03 1.725988239049911499e-01 9.847604036331176758e-01\n7.914939880371093750e+00 -2.718400382995605469e+01 -2.896314620971679688e+00 3.313439339399337769e-02 4.488728940486907959e-03 1.940394788980484009e-01 9.804237484931945801e-01\n7.786039829254150391e+00 -2.713848495483398438e+01 -2.775121927261352539e+00 4.576298221945762634e-02 6.125640124082565308e-03 2.160865813493728638e-01 9.752818942070007324e-01\n7.648814678192138672e+00 -2.708902359008789062e+01 -2.649977922439575195e+00 5.885510146617889404e-02 7.802580017596483231e-03 2.385131120681762695e-01 9.693228006362915039e-01\n7.502609729766845703e+00 -2.703505706787109375e+01 -2.521782159805297852e+00 7.221274077892303467e-02 9.501649998128414154e-03 2.610951364040374756e-01 9.625613689422607422e-01\n7.346512317657470703e+00 -2.697579002380371094e+01 -2.391965389251708984e+00 8.563899993896484375e-02 1.120452024042606354e-02 2.836139798164367676e-01 9.550411701202392578e-01\n7.179455280303955078e+00 -2.691020011901855469e+01 -2.262508392333984375e+00 9.893891215324401855e-02 1.289336383342742920e-02 3.058579564094543457e-01 9.468346238136291504e-01\n7.000294685363769531e+00 -2.683707046508789062e+01 -2.136049747467041016e+00 1.119204610586166382e-01 1.455131731927394867e-02 3.276241421699523926e-01 9.380428791046142578e-01\n6.807950973510742188e+00 -2.675503349304199219e+01 -2.016015529632568359e+00 1.243962049484252930e-01 1.616092585027217865e-02 3.487199246883392334e-01 9.287942051887512207e-01\n6.599474906921386719e+00 -2.666633796691894531e+01 -1.908085942268371582e+00 1.361834555864334106e-01 1.770585030317306519e-02 3.689627945423126221e-01 9.192425608634948730e-01\n6.370777606964111328e+00 -2.657961273193359375e+01 -1.817972421646118164e+00 1.471050679683685303e-01 1.917048171162605286e-02 3.881823122501373291e-01 9.095642566680908203e-01\n6.139701843261718750e+00 -2.650517082214355469e+01 -1.749771714210510254e+00 1.569896787405014038e-01 2.053925022482872009e-02 4.062187373638153076e-01 8.999547958374023438e-01\n5.910547256469726562e+00 -2.644154167175292969e+01 -1.696130275726318359e+00 1.656711250543594360e-01 2.179830893874168396e-02 4.229246973991394043e-01 8.906247615814208984e-01\n5.684411525726318359e+00 -2.639022445678710938e+01 -1.656192541122436523e+00 1.729882657527923584e-01 2.293346077203750610e-02 4.381606578826904297e-01 8.817959427833557129e-01\n5.464765071868896484e+00 -2.634597015380859375e+01 -1.622294902801513672e+00 1.787836253643035889e-01 2.393117547035217285e-02 4.517953991889953613e-01 8.736959099769592285e-01\n5.251664161682128906e+00 -2.630884170532226562e+01 -1.594280958175659180e+00 1.825749278068542480e-01 2.460363134741783142e-02 4.637119174003601074e-01 8.666211366653442383e-01\n5.046442508697509766e+00 -2.627592277526855469e+01 -1.568546056747436523e+00 1.834198236465454102e-01 2.448996528983116150e-02 4.738091528415679932e-01 8.609658479690551758e-01\n4.848206520080566406e+00 -2.625026321411132812e+01 -1.548382520675659180e+00 1.838009655475616455e-01 2.502397820353507996e-02 4.818847477436065674e-01 8.563749194145202637e-01\n4.658301830291748047e+00 -2.622618103027343750e+01 -1.529111266136169434e+00 1.836267709732055664e-01 2.628898248076438904e-02 4.877998232841491699e-01 8.530189990997314453e-01\n4.476706981658935547e+00 -2.620547866821289062e+01 -1.510836124420166016e+00 1.795126795768737793e-01 2.640318125486373901e-02 4.915642440319061279e-01 8.517292737960815430e-01\n4.302931308746337891e+00 -2.619043922424316406e+01 -1.495709180831909180e+00 1.732770353555679321e-01 2.629615366458892822e-02 4.932430088520050049e-01 8.520532846450805664e-01\n4.137679100036621094e+00 -2.617677116394042969e+01 -1.480880141258239746e+00 1.651134490966796875e-01 2.594937756657600403e-02 4.929910898208618164e-01 8.538290262222290039e-01\n3.980953931808471680e+00 -2.616441345214843750e+01 -1.466370820999145508e+00 1.552121192216873169e-01 2.534341439604759216e-02 4.909519553184509277e-01 8.568739891052246094e-01\n3.832751274108886719e+00 -2.615327072143554688e+01 -1.452200889587402344e+00 1.437613666057586670e-01 2.445927262306213379e-02 4.872626960277557373e-01 8.609933257102966309e-01\n3.692717790603637695e+00 -2.614628410339355469e+01 -1.440113544464111328e+00 1.309500336647033691e-01 2.327736094594001770e-02 4.820578396320343018e-01 8.659853339195251465e-01\n3.561160087585449219e+00 -2.614063453674316406e+01 -1.428563237190246582e+00 1.169686764478683472e-01 2.177853137254714966e-02 4.754727780818939209e-01 8.716476559638977051e-01\n3.438129901885986328e+00 -2.613575172424316406e+01 -1.417299747467041016e+00 1.020105704665184021e-01 1.994415000081062317e-02 4.676474928855895996e-01 8.777823448181152344e-01\n3.323622465133666992e+00 -2.613155174255371094e+01 -1.406351327896118164e+00 8.627232909202575684e-02 1.775621995329856873e-02 4.587280750274658203e-01 8.842004537582397461e-01\n3.217639923095703125e+00 -2.612795257568359375e+01 -1.395756840705871582e+00 6.995402276515960693e-02 1.519817486405372620e-02 4.488692879676818848e-01 8.907254338264465332e-01\n3.120190143585205078e+00 -2.612490653991699219e+01 -1.385557889938354492e+00 5.325971171259880066e-02 1.225320342928171158e-02 4.382355511188507080e-01 8.971971869468688965e-01\n3.031288385391235352e+00 -2.612232780456542969e+01 -1.375803232192993164e+00 3.639610856771469116e-02 8.906225673854351044e-03 4.270016551017761230e-01 9.034742116928100586e-01\n2.950957059860229492e+00 -2.612017059326171875e+01 -1.366545438766479492e+00 1.957202330231666565e-02 5.143407732248306274e-03 4.153527021408081055e-01 9.094352722167968750e-01\n2.879151344299316406e+00 -2.611909103393554688e+01 -1.358444809913635254e+00 2.997935982421040535e-03 9.512035176157951355e-04 4.034842848777770996e-01 9.149811863899230957e-01\n2.815986633300781250e+00 -2.611833000183105469e+01 -1.350934982299804688e+00 -1.311498880386352539e-02 -3.683640155941247940e-03 3.916012048721313477e-01 9.200341701507568359e-01\n2.761515855789184570e+00 -2.611777305603027344e+01 -1.344009995460510254e+00 -2.855683118104934692e-02 -8.773547597229480743e-03 3.799151778221130371e-01 9.245388507843017578e-01\n2.715790271759033203e+00 -2.611742591857910156e+01 -1.337728261947631836e+00 -4.311827197670936584e-02 -1.433096732944250107e-02 3.686465024948120117e-01 9.284585118293762207e-01\n2.678865909576416016e+00 -2.611726570129394531e+01 -1.332148432731628418e+00 -5.659235641360282898e-02 -2.036875113844871521e-02 3.580188453197479248e-01 9.317751526832580566e-01\n2.650802850723266602e+00 -2.611730003356933594e+01 -1.327322959899902344e+00 -6.877423077821731567e-02 -2.690066583454608917e-02 3.482596874237060547e-01 9.344847798347473145e-01\n2.631665229797363281e+00 -2.611752891540527344e+01 -1.323305606842041016e+00 -7.946231216192245483e-02 -3.394139930605888367e-02 3.395984470844268799e-01 9.365930557250976562e-01\n2.621506929397583008e+00 -2.611796760559082031e+01 -1.320130586624145508e+00 -8.851067721843719482e-02 -4.149623960256576538e-02 3.322108387947082520e-01 9.381257891654968262e-01\n2.604746103286743164e+00 -2.611786651611328125e+01 -1.316929936408996582e+00 -9.599139541387557983e-02 -4.952628165483474731e-02 3.260566592216491699e-01 9.391590952873229980e-01\n2.581374406814575195e+00 -2.611726570129394531e+01 -1.313673019409179688e+00 -1.020307838916778564e-01 -5.798066779971122742e-02 3.210361599922180176e-01 9.397679567337036133e-01\n2.551380872726440430e+00 -2.611620140075683594e+01 -1.310332059860229492e+00 -1.067542657256126404e-01 -6.680898368358612061e-02 3.170435726642608643e-01 9.400123953819274902e-01\n2.514750719070434570e+00 -2.611468696594238281e+01 -1.306879878044128418e+00 -1.102860048413276672e-01 -7.595979422330856323e-02 3.139690458774566650e-01 9.399418234825134277e-01\n2.471467494964599609e+00 -2.611276245117187500e+01 -1.303287267684936523e+00 -1.127503067255020142e-01 -8.538196235895156860e-02 3.116994798183441162e-01 9.395960569381713867e-01\n2.421512603759765625e+00 -2.611042404174804688e+01 -1.299526333808898926e+00 -1.142703592777252197e-01 -9.502364695072174072e-02 3.101196289062500000e-01 9.390093684196472168e-01\n2.376385927200317383e+00 -2.610828590393066406e+01 -1.296202421188354492e+00 -1.149689331650733948e-01 -1.048334240913391113e-01 3.091127574443817139e-01 9.382117986679077148e-01\n2.336065053939819336e+00 -2.610634613037109375e+01 -1.293288588523864746e+00 -1.149692237377166748e-01 -1.147588342428207397e-01 3.085614442825317383e-01 9.372311830520629883e-01\n2.300527811050415039e+00 -2.610463714599609375e+01 -1.290760517120361328e+00 -1.143935322761535645e-01 -1.247479841113090515e-01 3.083480596542358398e-01 9.360948801040649414e-01\n2.269750118255615234e+00 -2.610315322875976562e+01 -1.288591265678405762e+00 -1.133648008108139038e-01 -1.347490549087524414e-01 3.083551526069641113e-01 9.348304867744445801e-01\n2.243707180023193359e+00 -2.610190773010253906e+01 -1.286761403083801270e+00 -1.120056807994842529e-01 -1.447095274925231934e-01 3.084664642810821533e-01 9.334679245948791504e-01\n2.222373247146606445e+00 -2.610091781616210938e+01 -1.285245299339294434e+00 -1.104394048452377319e-01 -1.545778214931488037e-01 3.085660040378570557e-01 9.320386052131652832e-01\n2.205722808837890625e+00 -2.610018539428710938e+01 -1.284022212028503418e+00 -1.087885349988937378e-01 -1.643026769161224365e-01 3.085390627384185791e-01 9.305768609046936035e-01\n2.193727970123291016e+00 -2.609972190856933594e+01 -1.283072471618652344e+00 -1.071762964129447937e-01 -1.738324314355850220e-01 3.082725405693054199e-01 9.291197657585144043e-01\n2.186362266540527344e+00 -2.609954452514648438e+01 -1.282379150390625000e+00 -1.057260483503341675e-01 -1.831168383359909058e-01 3.076536953449249268e-01 9.277065396308898926e-01\n2.183596372604370117e+00 -2.609965705871582031e+01 -1.281921386718750000e+00 -1.045607924461364746e-01 -1.921051144599914551e-01 3.065711855888366699e-01 9.263783693313598633e-01\n2.178739786148071289e+00 -2.609973526000976562e+01 -1.281318306922912598e+00 -1.038029193878173828e-01 -2.007473111152648926e-01 3.049142658710479736e-01 9.251772165298461914e-01\n2.171762704849243164e+00 -2.609978866577148438e+01 -1.280552983283996582e+00 -1.035755872726440430e-01 -2.089937329292297363e-01 3.025719523429870605e-01 9.241449236869812012e-01\n2.162633657455444336e+00 -2.609983253479003906e+01 -1.279610514640808105e+00 -1.040007025003433228e-01 -2.167947590351104736e-01 2.994336187839508057e-01 9.233219027519226074e-01\n2.151756286621093750e+00 -2.609991073608398438e+01 -1.279266357421875000e+00 -1.018563807010650635e-01 -2.230551093816757202e-01 2.962332963943481445e-01 9.231020808219909668e-01\n2.138787031173706055e+00 -2.609995079040527344e+01 -1.278807401657104492e+00 -1.000821962952613831e-01 -2.287934869527816772e-01 2.924018502235412598e-01 9.231132864952087402e-01\n2.123752832412719727e+00 -2.609994125366210938e+01 -1.278233647346496582e+00 -9.863399714231491089e-02 -2.340759038925170898e-01 2.880798876285552979e-01 9.233037829399108887e-01\n2.106680870056152344e+00 -2.609985733032226562e+01 -1.277545094490051270e+00 -9.746373444795608521e-02 -2.389639019966125488e-01 2.834067344665527344e-01 9.236220121383666992e-01\n2.087599992752075195e+00 -2.609968185424804688e+01 -1.276743173599243164e+00 -9.652115404605865479e-02 -2.435137331485748291e-01 2.785216569900512695e-01 9.240186214447021484e-01\n2.066539525985717773e+00 -2.609939956665039062e+01 -1.275826334953308105e+00 -9.575416892766952515e-02 -2.477771490812301636e-01 2.735641896724700928e-01 9.244459271430969238e-01\n2.043530464172363281e+00 -2.609897804260253906e+01 -1.274796128273010254e+00 -9.510961920022964478e-02 -2.518011033535003662e-01 2.686747014522552490e-01 9.248589873313903809e-01\n2.018604755401611328e+00 -2.609842681884765625e+01 -1.273653507232666016e+00 -9.453330934047698975e-02 -2.556293010711669922e-01 2.639941573143005371e-01 9.252157807350158691e-01\n1.991794824600219727e+00 -2.609771347045898438e+01 -1.272398710250854492e+00 -9.397020936012268066e-02 -2.593019306659698486e-01 2.596642374992370605e-01 9.254763126373291016e-01\n1.963134527206420898e+00 -2.609683036804199219e+01 -1.271032691001892090e+00 -9.336430579423904419e-02 -2.628570795059204102e-01 2.558271884918212891e-01 9.256033897399902344e-01\n1.932657837867736816e+00 -2.609576606750488281e+01 -1.269554376602172852e+00 -9.265825897455215454e-02 -2.663317620754241943e-01 2.526248395442962646e-01 9.255605936050415039e-01\n1.900395274162292480e+00 -2.609452629089355469e+01 -1.268021225929260254e+00 -9.179296344518661499e-02 -2.697627544403076172e-01 2.501989006996154785e-01 9.253121614456176758e-01\n1.866372346878051758e+00 -2.609314346313476562e+01 -1.266556382179260254e+00 -9.070674329996109009e-02 -2.731886208057403564e-01 2.486893981695175171e-01 9.248208999633789062e-01\n1.830633640289306641e+00 -2.609154319763183594e+01 -1.264996290206909180e+00 -8.933471143245697021e-02 -2.766507267951965332e-01 2.482342422008514404e-01 9.240472912788391113e-01\n1.790276765823364258e+00 -2.608957481384277344e+01 -1.263203144073486328e+00 -8.760775625705718994e-02 -2.801944017410278320e-01 2.489677965641021729e-01 9.229469299316406250e-01\n1.745332121849060059e+00 -2.608722686767578125e+01 -1.261175513267517090e+00 -8.545089513063430786e-02 -2.838713824748992920e-01 2.510198652744293213e-01 9.214685559272766113e-01\n1.695828557014465332e+00 -2.608447265625000000e+01 -1.258919596672058105e+00 -8.278183639049530029e-02 -2.877405583858489990e-01 2.545136511325836182e-01 9.195516109466552734e-01\n1.641791701316833496e+00 -2.608129310607910156e+01 -1.256438016891479492e+00 -7.950858026742935181e-02 -2.918704450130462646e-01 2.595636546611785889e-01 9.171241521835327148e-01\n1.583243012428283691e+00 -2.607766532897949219e+01 -1.253734111785888672e+00 -7.552697509527206421e-02 -2.963385283946990967e-01 2.662736177444458008e-01 9.140993356704711914e-01\n1.520200014114379883e+00 -2.607355880737304688e+01 -1.250813007354736328e+00 -7.071685791015625000e-02 -3.012339174747467041e-01 2.747328281402587891e-01 9.103729724884033203e-01\n1.454235196113586426e+00 -2.606877899169921875e+01 -1.249844908714294434e+00 -5.525906383991241455e-02 -3.035594820976257324e-01 2.882252037525177002e-01 9.064901471138000488e-01\n1.383903503417968750e+00 -2.606328582763671875e+01 -1.248920917510986328e+00 -3.777214884757995605e-02 -3.056705296039581299e-01 3.037523031234741211e-01 9.015948772430419922e-01\n1.309079766273498535e+00 -2.605702018737792969e+01 -1.247990727424621582e+00 -1.855715364217758179e-02 -3.074791133403778076e-01 3.209738135337829590e-01 8.955936431884765625e-01\n1.229634761810302734e+00 -2.604996109008789062e+01 -1.246994614601135254e+00 2.079017460346221924e-03 -3.089032173156738281e-01 3.395516574382781982e-01 8.884138464927673340e-01\n1.145437955856323242e+00 -2.604207992553710938e+01 -1.245875239372253418e+00 2.382044494152069092e-02 -3.098701834678649902e-01 3.591489195823669434e-01 8.800143003463745117e-01\n1.056360840797424316e+00 -2.603338813781738281e+01 -1.244570255279541016e+00 4.634601622819900513e-02 -3.103204071521759033e-01 3.794378042221069336e-01 8.703909516334533691e-01\n9.622811079025268555e-01 -2.602390480041503906e+01 -1.243022441864013672e+00 6.933062523603439331e-02 -3.102084100246429443e-01 4.001006484031677246e-01 8.595832586288452148e-01\n8.630869388580322266e-01 -2.601369476318359375e+01 -1.241176724433898926e+00 9.244732558727264404e-02 -3.095055222511291504e-01 4.208358526229858398e-01 8.476773500442504883e-01\n7.586755752563476562e-01 -2.600251388549804688e+01 -1.239426255226135254e+00 1.153714805841445923e-01 -3.082002401351928711e-01 4.413614571094512939e-01 8.348065614700317383e-01\n6.489708423614501953e-01 -2.599065780639648438e+01 -1.237429141998291016e+00 1.377833187580108643e-01 -3.062991797924041748e-01 4.614176154136657715e-01 8.211518526077270508e-01\n5.339149236679077148e-01 -2.597833442687988281e+01 -1.235021948814392090e+00 1.593710333108901978e-01 -3.038252592086791992e-01 4.807699918746948242e-01 8.069394826889038086e-01\n4.134708344936370850e-01 -2.596566772460937500e+01 -1.232172846794128418e+00 1.798333376646041870e-01 -3.008187711238861084e-01 4.992105662822723389e-01 7.924372553825378418e-01\n2.876244187355041504e-01 -2.595279312133789062e+01 -1.228863477706909180e+00 1.988817751407623291e-01 -2.973341047763824463e-01 5.165591239929199219e-01 7.779493331909179688e-01\n1.563831120729446411e-01 -2.593984222412109375e+01 -1.225079298019409180e+00 2.162414491176605225e-01 -2.934379577636718750e-01 5.326616168022155762e-01 7.638098597526550293e-01\n1.977386511862277985e-02 -2.592696762084960938e+01 -1.220815420150756836e+00 2.316501736640930176e-01 -2.892060577869415283e-01 5.473881959915161133e-01 7.503760457038879395e-01\n-1.221602037549018860e-01 -2.591429710388183594e+01 -1.216070532798767090e+00 2.448578178882598877e-01 -2.847204804420471191e-01 5.606288909912109375e-01 7.380204200744628906e-01\n-2.693642973899841309e-01 -2.590196228027343750e+01 -1.210849523544311523e+00 2.556236982345581055e-01 -2.800659835338592529e-01 5.722882151603698730e-01 7.271215915679931641e-01\n-4.217575490474700928e-01 -2.588953018188476562e+01 -1.205434560775756836e+00 2.637114226818084717e-01 -2.753245532512664795e-01 5.822781920433044434e-01 7.180562615394592285e-01\n-5.792719125747680664e-01 -2.587693214416503906e+01 -1.199920654296875000e+00 2.688854634761810303e-01 -2.705728113651275635e-01 5.905099511146545410e-01 7.111884951591491699e-01\n-7.418780326843261719e-01 -2.586498069763183594e+01 -1.193951368331909180e+00 2.709034085273742676e-01 -2.658755183219909668e-01 5.968830585479736328e-01 7.068607807159423828e-01\n-9.095315337181091309e-01 -2.585373878479003906e+01 -1.187517046928405762e+00 2.696073949337005615e-01 -2.612811923027038574e-01 6.013295054435729980e-01 7.052990794181823730e-01\n-1.082196712493896484e+00 -2.584315872192382812e+01 -1.180628657341003418e+00 2.652037143707275391e-01 -2.568131983280181885e-01 6.039624810218811035e-01 7.063591480255126953e-01\n-1.259857892990112305e+00 -2.583313941955566406e+01 -1.173294663429260254e+00 2.579801678657531738e-01 -2.524796426296234131e-01 6.049149036407470703e-01 7.097733616828918457e-01\n-1.442517638206481934e+00 -2.582359313964843750e+01 -1.165510177612304688e+00 2.482134401798248291e-01 -2.482767254114151001e-01 6.042959094047546387e-01 7.152449488639831543e-01\n-1.630190968513488770e+00 -2.581442260742187500e+01 -1.157275319099426270e+00 2.361755520105361938e-01 -2.441955357789993286e-01 6.021990776062011719e-01 7.224583029747009277e-01\n-1.822792649269104004e+00 -2.580361747741699219e+01 -1.149105191230773926e+00 2.221380621194839478e-01 -2.402243912220001221e-01 5.987128615379333496e-01 7.310880422592163086e-01\n-2.020425319671630859e+00 -2.579247474670410156e+01 -1.140615224838256836e+00 2.063753902912139893e-01 -2.363522201776504517e-01 5.939273834228515625e-01 7.408083677291870117e-01\n-2.223135709762573242e+00 -2.578133201599121094e+01 -1.131688237190246582e+00 1.891683191061019897e-01 -2.325716316699981689e-01 5.879410505294799805e-01 7.512996196746826172e-01\n-2.430940866470336914e+00 -2.577008819580078125e+01 -1.122332692146301270e+00 1.708054840564727783e-01 -2.288807183504104614e-01 5.808661580085754395e-01 7.622555494308471680e-01\n-2.643848896026611328e+00 -2.575863647460937500e+01 -1.112574458122253418e+00 1.515839397907257080e-01 -2.252849787473678589e-01 5.728331804275512695e-01 7.733894586563110352e-01\n-2.861857891082763672e+00 -2.574687385559082031e+01 -1.102440118789672852e+00 1.318101584911346436e-01 -2.217981219291687012e-01 5.639927983283996582e-01 7.844384908676147461e-01\n-3.084932088851928711e+00 -2.573441886901855469e+01 -1.092018961906433105e+00 1.117970794439315796e-01 -2.184428274631500244e-01 5.545181632041931152e-01 7.951689958572387695e-01\n-3.312824249267578125e+00 -2.571818351745605469e+01 -1.081887125968933105e+00 9.186533093452453613e-02 -2.152512967586517334e-01 5.446047186851501465e-01 8.053777217864990234e-01\n-3.545735597610473633e+00 -2.570132827758789062e+01 -1.071532011032104492e+00 7.233910262584686279e-02 -2.122652828693389893e-01 5.344696044921875000e-01 8.148942589759826660e-01\n-3.783617496490478516e+00 -2.568376922607421875e+01 -1.061015605926513672e+00 5.354552716016769409e-02 -2.095348089933395386e-01 5.243495106697082520e-01 8.235809803009033203e-01\n-4.026412487030029297e+00 -2.566546249389648438e+01 -1.050401568412780762e+00 3.581195324659347534e-02 -2.071186453104019165e-01 5.144988298416137695e-01 8.313304185867309570e-01\n-4.274055004119873047e+00 -2.564637565612792969e+01 -1.039759516716003418e+00 1.946479082107543945e-02 -2.050815224647521973e-01 5.051854252815246582e-01 8.380634784698486328e-01\n-4.526473522186279297e+00 -2.562646865844726562e+01 -1.029154062271118164e+00 4.827596247196197510e-03 -2.034938782453536987e-01 4.966876506805419922e-01 8.437229394912719727e-01\n-4.783144950866699219e+00 -2.560096168518066406e+01 -1.019245624542236328e+00 -7.779009640216827393e-03 -2.024299055337905884e-01 4.892896711826324463e-01 8.482671976089477539e-01\n-5.044416904449462891e+00 -2.557433128356933594e+01 -1.009541034698486328e+00 -1.803756505250930786e-02 -2.019653618335723877e-01 4.832766652107238770e-01 8.516620397567749023e-01\n-5.302582263946533203e+00 -2.554758262634277344e+01 -1.000302672386169434e+00 -2.571143954992294312e-02 -2.021553814411163330e-01 4.788711369037628174e-01 8.539054393768310547e-01\n-5.557634353637695312e+00 -2.552076148986816406e+01 -9.915307164192199707e-01 -3.087937086820602417e-02 -2.029705345630645752e-01 4.760487377643585205e-01 8.551180958747863770e-01\n-5.809582233428955078e+00 -2.549390983581542969e+01 -9.832091927528381348e-01 -3.369780629873275757e-02 -2.043549120426177979e-01 4.747093617916107178e-01 8.554264307022094727e-01\n-6.058428287506103516e+00 -2.546691322326660156e+01 -9.753307700157165527e-01 -3.432291001081466675e-02 -2.062465548515319824e-01 4.747377634048461914e-01 8.549318313598632812e-01\n-6.303567409515380859e+00 -2.543446159362792969e+01 -9.683629870414733887e-01 -3.290986269712448120e-02 -2.085783779621124268e-01 4.760079979896545410e-01 8.537144064903259277e-01\n-6.557874202728271484e+00 -2.540054130554199219e+01 -9.614318609237670898e-01 -2.961410582065582275e-02 -2.112799137830734253e-01 4.783855676651000977e-01 8.518398404121398926e-01\n-6.821374893188476562e+00 -2.536515998840332031e+01 -9.545104503631591797e-01 -2.458949387073516846e-02 -2.142781317234039307e-01 4.817292094230651855e-01 8.493627309799194336e-01\n-7.094101905822753906e+00 -2.532833862304687500e+01 -9.475768804550170898e-01 -1.799146831035614014e-02 -2.174982428550720215e-01 4.858947098255157471e-01 8.463315367698669434e-01\n-7.376088142395019531e+00 -2.529010200500488281e+01 -9.406054615974426270e-01 -9.974963963031768799e-03 -2.208639681339263916e-01 4.907353818416595459e-01 8.427920341491699219e-01\n-7.667158603668212891e+00 -2.524897003173828125e+01 -9.337072372436523438e-01 -6.955191493034362793e-04 -2.242999076843261719e-01 4.961045384407043457e-01 8.387904167175292969e-01\n-7.959429264068603516e+00 -2.520267486572265625e+01 -9.273742437362670898e-01 9.689696133136749268e-03 -2.277305126190185547e-01 5.018569231033325195e-01 8.343767523765563965e-01\n-8.253588676452636719e+00 -2.515594100952148438e+01 -9.211474657058715820e-01 2.102287113666534424e-02 -2.310820966958999634e-01 5.078500509262084961e-01 8.296068310737609863e-01\n-8.541360855102539062e+00 -2.511005783081054688e+01 -9.152233600616455078e-01 3.314618766307830811e-02 -2.342820912599563599e-01 5.139456987380981445e-01 8.245441317558288574e-01\n-8.822777748107910156e+00 -2.506504249572753906e+01 -9.095849394798278809e-01 4.589994251728057861e-02 -2.372606992721557617e-01 5.200105309486389160e-01 8.192616105079650879e-01\n-9.097865104675292969e+00 -2.502093696594238281e+01 -9.042126536369323730e-01 5.912540107965469360e-02 -2.399505525827407837e-01 5.259176492691040039e-01 8.138417601585388184e-01\n-9.365920066833496094e+00 -2.497324180603027344e+01 -8.995105028152465820e-01 7.266320288181304932e-02 -2.422876656055450439e-01 5.315462946891784668e-01 8.083781599998474121e-01\n-9.627545356750488281e+00 -2.492558479309082031e+01 -8.951293826103210449e-01 8.635501563549041748e-02 -2.442109286785125732e-01 5.367828607559204102e-01 8.029744625091552734e-01\n-9.882925987243652344e+00 -2.487905693054199219e+01 -8.909606933593750000e-01 1.000431627035140991e-01 -2.456623315811157227e-01 5.415208935737609863e-01 7.977446317672729492e-01\n-1.013208103179931641e+01 -2.483370018005371094e+01 -8.869934082031250000e-01 1.135715693235397339e-01 -2.465868890285491943e-01 5.456603169441223145e-01 7.928122282028198242e-01\n-1.037502384185791016e+01 -2.478955459594726562e+01 -8.832201957702636719e-01 1.267857998609542847e-01 -2.469325810670852661e-01 5.491075515747070312e-01 7.883086204528808594e-01\n-1.061176395416259766e+01 -2.474665451049804688e+01 -8.796362280845642090e-01 1.395600289106369019e-01 -2.466690540313720703e-01 5.517964959144592285e-01 7.843455076217651367e-01\n-1.084166145324707031e+01 -2.470154762268066406e+01 -8.765624761581420898e-01 1.518780887126922607e-01 -2.458456903696060181e-01 5.537524223327636719e-01 7.809297442436218262e-01\n-1.106510353088378906e+01 -2.465637207031250000e+01 -8.737902641296386719e-01 1.637502014636993408e-01 -2.445301562547683716e-01 5.550203323364257812e-01 7.780380845069885254e-01\n-1.128235054016113281e+01 -2.461257743835449219e+01 -8.711816072463989258e-01 1.751865893602371216e-01 -2.427901923656463623e-01 5.556436181068420410e-01 7.756434082984924316e-01\n-1.149339485168457031e+01 -2.457016563415527344e+01 -8.687292337417602539e-01 1.861974149942398071e-01 -2.406913191080093384e-01 5.556635260581970215e-01 7.737158536911010742e-01\n-1.169823074340820312e+01 -2.452912521362304688e+01 -8.664233088493347168e-01 1.967928707599639893e-01 -2.382993102073669434e-01 5.551197528839111328e-01 7.722227573394775391e-01\n-1.189685535430908203e+01 -2.448945236206054688e+01 -8.642578125000000000e-01 2.069828212261199951e-01 -2.356788516044616699e-01 5.540509819984436035e-01 7.711297273635864258e-01\n-1.208925914764404297e+01 -2.445113754272460938e+01 -8.622229099273681641e-01 2.167773693799972534e-01 -2.328945249319076538e-01 5.524944663047790527e-01 7.704008221626281738e-01\n-1.227489948272705078e+01 -2.441156768798828125e+01 -8.605554103851318359e-01 2.261860370635986328e-01 -2.300098091363906860e-01 5.504872798919677734e-01 7.699993848800659180e-01\n-1.245398521423339844e+01 -2.437176132202148438e+01 -8.591491580009460449e-01 2.352190017700195312e-01 -2.270886003971099854e-01 5.480658411979675293e-01 7.698873877525329590e-01\n-1.262686634063720703e+01 -2.433344650268554688e+01 -8.578307628631591797e-01 2.438857853412628174e-01 -2.241941392421722412e-01 5.452659130096435547e-01 7.700272202491760254e-01\n-1.280683422088623047e+01 -2.429367637634277344e+01 -8.563159108161926270e-01 2.521966099739074707e-01 -2.213897407054901123e-01 5.421235561370849609e-01 7.703801989555358887e-01\n-1.299388980865478516e+01 -2.425245094299316406e+01 -8.545935153961181641e-01 2.601614594459533691e-01 -2.187384665012359619e-01 5.386744737625122070e-01 7.709079980850219727e-01\n-1.318802261352539062e+01 -2.420975112915039062e+01 -8.526562452316284180e-01 2.677903175354003906e-01 -2.163032144308090210e-01 5.349546074867248535e-01 7.715730667114257812e-01\n-1.338922119140625000e+01 -2.416558074951171875e+01 -8.504919409751892090e-01 2.750933170318603516e-01 -2.141466438770294189e-01 5.309993624687194824e-01 7.723371386528015137e-01\n-1.359730148315429688e+01 -2.411916542053222656e+01 -8.481615781784057617e-01 2.820808291435241699e-01 -2.123317122459411621e-01 5.268448591232299805e-01 7.731623649597167969e-01\n-1.381124687194824219e+01 -2.406614685058593750e+01 -8.460729718208312988e-01 2.887633442878723145e-01 -2.109213173389434814e-01 5.225268006324768066e-01 7.740113139152526855e-01\n-1.403218841552734375e+01 -2.401143455505371094e+01 -8.437451124191284180e-01 2.951512634754180908e-01 -2.099776864051818848e-01 5.180809497833251953e-01 7.748466134071350098e-01\n-1.426011848449707031e+01 -2.395502471923828125e+01 -8.411706089973449707e-01 3.012549281120300293e-01 -2.095633149147033691e-01 5.135427117347717285e-01 7.756304144859313965e-01\n-1.449502277374267578e+01 -2.389689826965332031e+01 -8.383386135101318359e-01 3.070848882198333740e-01 -2.097403109073638916e-01 5.089473724365234375e-01 7.763249278068542480e-01\n-1.473693466186523438e+01 -2.383842658996582031e+01 -8.338268995285034180e-01 3.065032660961151123e-01 -2.145159691572189331e-01 5.026563405990600586e-01 7.793427705764770508e-01\n-1.498472881317138672e+01 -2.377401351928710938e+01 -8.295714855194091797e-01 3.060118556022644043e-01 -2.194902896881103516e-01 4.964650571346282959e-01 7.821146249771118164e-01\n-1.523827362060546875e+01 -2.370317268371582031e+01 -8.256250023841857910e-01 3.055872321128845215e-01 -2.245676517486572266e-01 4.904325902462005615e-01 7.846412062644958496e-01\n-1.549872779846191406e+01 -2.363027381896972656e+01 -8.215686082839965820e-01 3.052128553390502930e-01 -2.296506762504577637e-01 4.846248924732208252e-01 7.869207262992858887e-01\n-1.576608371734619141e+01 -2.355529212951660156e+01 -8.174071907997131348e-01 3.048793077468872070e-01 -2.346402853727340698e-01 4.791148006916046143e-01 7.889497280120849609e-01\n-1.604001426696777344e+01 -2.347719192504882812e+01 -8.132445812225341797e-01 3.045835494995117188e-01 -2.394354343414306641e-01 4.739812910556793213e-01 7.907220125198364258e-01\n-1.631705474853515625e+01 -2.338483428955078125e+01 -8.101818561553955078e-01 3.043285310268402100e-01 -2.439338266849517822e-01 4.693088233470916748e-01 7.922308444976806641e-01\n-1.660086822509765625e+01 -2.329003334045410156e+01 -8.070617318153381348e-01 3.041211366653442383e-01 -2.480305284261703491e-01 4.651857912540435791e-01 7.934691309928894043e-01\n-1.688272476196289062e+01 -2.319570350646972656e+01 -8.039770126342773438e-01 3.039715886116027832e-01 -2.516188025474548340e-01 4.617031812667846680e-01 7.944301962852478027e-01\n-1.715821075439453125e+01 -2.309016036987304688e+01 -8.021142482757568359e-01 3.038906455039978027e-01 -2.545894980430603027e-01 4.589523375034332275e-01 7.951083183288574219e-01\n-1.742863082885742188e+01 -2.297690391540527344e+01 -8.011242747306823730e-01 3.038873672485351562e-01 -2.568305432796478271e-01 4.570226073265075684e-01 7.955004572868347168e-01\n-1.769711875915527344e+01 -2.286419296264648438e+01 -8.001745343208312988e-01 3.039654791355133057e-01 -2.582265436649322510e-01 4.559979438781738281e-01 7.956066131591796875e-01\n-1.795545768737792969e+01 -2.273483276367187500e+01 -8.009973168373107910e-01 3.041208386421203613e-01 -2.586601376533508301e-01 4.559538066387176514e-01 7.954316139221191406e-01\n-1.820840263366699219e+01 -2.259877395629882812e+01 -8.026000857353210449e-01 3.043361306190490723e-01 -2.580100297927856445e-01 4.569530785083770752e-01 7.949869632720947266e-01\n-1.845356178283691406e+01 -2.245384216308593750e+01 -8.052062988281250000e-01 3.045781552791595459e-01 -2.561534345149993896e-01 4.590417444705963135e-01 7.942910790443420410e-01\n-1.868462753295898438e+01 -2.228983306884765625e+01 -8.098449707031250000e-01 3.047925829887390137e-01 -2.529663443565368652e-01 4.622446596622467041e-01 7.933721542358398438e-01\n-1.890363311767578125e+01 -2.211425209045410156e+01 -8.157787919044494629e-01 3.049005568027496338e-01 -2.483250051736831665e-01 4.665615260601043701e-01 7.922693490982055664e-01\n-1.910454940795898438e+01 -2.192168426513671875e+01 -8.215343952178955078e-01 2.945684194564819336e-01 -2.481755763292312622e-01 4.688011407852172852e-01 7.948985695838928223e-01\n-1.927557182312011719e+01 -2.170585823059082031e+01 -8.294323682785034180e-01 2.825427353382110596e-01 -2.472493946552276611e-01 4.717763364315032959e-01 7.977871894836425781e-01\n-1.942508697509765625e+01 -2.146347045898437500e+01 -8.392358422279357910e-01 2.687639594078063965e-01 -2.454302906990051270e-01 4.755074381828308105e-01 8.008886575698852539e-01\n-1.954216575622558594e+01 -2.119265556335449219e+01 -8.509130477905273438e-01 2.531774640083312988e-01 -2.426455467939376831e-01 4.799710512161254883e-01 8.041468262672424316e-01\n-1.962533950805664062e+01 -2.090949630737304688e+01 -8.627063035964965820e-01 2.359070032835006714e-01 -2.389250248670578003e-01 4.850493669509887695e-01 8.074588775634765625e-01\n-1.969269943237304688e+01 -2.062216758728027344e+01 -8.727245926856994629e-01 2.171254158020019531e-01 -2.343276143074035645e-01 4.906017482280731201e-01 8.107138276100158691e-01\n-1.976142501831054688e+01 -2.033530235290527344e+01 -8.793127536773681641e-01 1.970101296901702881e-01 -2.289136946201324463e-01 4.964909851551055908e-01 8.138071894645690918e-01\n-1.983432769775390625e+01 -2.004959869384765625e+01 -8.815551400184631348e-01 1.757451593875885010e-01 -2.227488011121749878e-01 5.025841593742370605e-01 8.166429996490478516e-01\n-1.991426658630371094e+01 -1.976594161987304688e+01 -8.786755204200744629e-01 1.535205245018005371e-01 -2.159026265144348145e-01 5.087547302246093750e-01 8.191374540328979492e-01\n-2.000371360778808594e+01 -1.948537635803222656e+01 -8.701708912849426270e-01 1.305329352617263794e-01 -2.084505409002304077e-01 5.148843526840209961e-01 8.212208151817321777e-01\n-2.010437202453613281e+01 -1.920896911621093750e+01 -8.559069633483886719e-01 1.069843769073486328e-01 -2.004730701446533203e-01 5.208641290664672852e-01 8.228398561477661133e-01\n-2.021696090698242188e+01 -1.893766021728515625e+01 -8.361364603042602539e-01 8.308219909667968750e-02 -1.920559257268905640e-01 5.265967249870300293e-01 8.239585757255554199e-01\n-2.034121322631835938e+01 -1.867202568054199219e+01 -8.114489316940307617e-01 5.903753638267517090e-02 -1.832901090383529663e-01 5.319957137107849121e-01 8.245604038238525391e-01\n-2.047609901428222656e+01 -1.841223526000976562e+01 -7.826293706893920898e-01 3.506408631801605225e-02 -1.742717623710632324e-01 5.369876623153686523e-01 8.246477842330932617e-01\n-2.062051963806152344e+01 -1.815816879272460938e+01 -7.515124082565307617e-01 1.137626916170120239e-02 -1.651008129119873047e-01 5.415123105049133301e-01 8.242430686950683594e-01\n-2.077400016784667969e+01 -1.790994644165039062e+01 -7.193176150321960449e-01 -1.181076467037200928e-02 -1.558807641267776489e-01 5.455222725868225098e-01 8.233875632286071777e-01\n-2.093643760681152344e+01 -1.766792488098144531e+01 -6.869445443153381348e-01 -3.428380936384201050e-02 -1.467182040214538574e-01 5.489829778671264648e-01 8.221411108970642090e-01\n-2.110804367065429688e+01 -1.743272018432617188e+01 -6.551440358161926270e-01 -5.583245679736137390e-02 -1.377217173576354980e-01 5.518721938133239746e-01 8.205806016921997070e-01\n-2.128930091857910156e+01 -1.720520401000976562e+01 -6.246276497840881348e-01 -7.624924182891845703e-02 -1.290009617805480957e-01 5.541790723800659180e-01 8.187981843948364258e-01\n-2.148101425170898438e+01 -1.698668479919433594e+01 -5.961560010910034180e-01 -9.533132612705230713e-02 -1.206667348742485046e-01 5.559023618698120117e-01 8.168990612030029297e-01\n-2.168679428100585938e+01 -1.678162574768066406e+01 -5.714086890220642090e-01 -1.128805875778198242e-01 -1.128291189670562744e-01 5.570487380027770996e-01 8.149995803833007812e-01\n-2.190575408935546875e+01 -1.659123039245605469e+01 -5.512145757675170898e-01 -1.287030577659606934e-01 -1.055976971983909607e-01 5.576310157775878906e-01 8.132233619689941406e-01\n-2.213914299011230469e+01 -1.641951560974121094e+01 -5.370470881462097168e-01 -1.426087766885757446e-01 -9.908163547515869141e-02 5.576655268669128418e-01 8.116985559463500977e-01\n-2.238475036621093750e+01 -1.626752853393554688e+01 -5.304577350616455078e-01 -1.490601301193237305e-01 -8.964521437883377075e-02 5.577902197837829590e-01 8.115508556365966797e-01\n-2.264039993286132812e+01 -1.613380813598632812e+01 -5.288525223731994629e-01 -1.544735133647918701e-01 -8.161737024784088135e-02 5.572797656059265137e-01 8.117362856864929199e-01\n-2.290334701538085938e+01 -1.601597213745117188e+01 -5.312219262123107910e-01 -1.589248329401016235e-01 -7.490587979555130005e-02 5.562464594841003418e-01 8.122325539588928223e-01\n-2.317114639282226562e+01 -1.591066360473632812e+01 -5.363464355468750000e-01 -1.624944806098937988e-01 -6.941533088684082031e-02 5.547821521759033203e-01 8.130152821540832520e-01\n-2.344164657592773438e+01 -1.581360816955566406e+01 -5.427783131599426270e-01 -1.652654111385345459e-01 -6.504709273576736450e-02 5.529615283012390137e-01 8.140575289726257324e-01\n-2.371278762817382812e+01 -1.571944808959960938e+01 -5.487646460533142090e-01 -1.673214584589004517e-01 -6.169995665550231934e-02 5.508458018302917480e-01 8.153315186500549316e-01\n-2.398210716247558594e+01 -1.562127399444580078e+01 -5.520458817481994629e-01 -1.687461286783218384e-01 -5.927060544490814209e-02 5.484846234321594238e-01 8.168085813522338867e-01\n-2.424491691589355469e+01 -1.550804615020751953e+01 -5.487365722656250000e-01 -1.696220040321350098e-01 -5.765402317047119141e-02 5.459191203117370605e-01 8.184599280357360840e-01\n-2.449951553344726562e+01 -1.537872505187988281e+01 -5.386352539062500000e-01 -1.700302809476852417e-01 -5.674361437559127808e-02 5.431839823722839355e-01 8.202565908432006836e-01\n-2.474444007873535156e+01 -1.523342704772949219e+01 -5.220702886581420898e-01 -1.700503081083297729e-01 -5.643201619386672974e-02 5.403098464012145996e-01 8.221699595451354980e-01\n-2.497766494750976562e+01 -1.507148361206054688e+01 -4.995800554752349854e-01 -1.697595268487930298e-01 -5.661123991012573242e-02 5.373245477676391602e-01 8.241718411445617676e-01\n-2.519788742065429688e+01 -1.489331054687500000e+01 -4.744763076305389404e-01 -1.692334264516830444e-01 -5.717277154326438904e-02 5.342547893524169922e-01 8.262342810630798340e-01\n-2.539336204528808594e+01 -1.468873500823974609e+01 -4.596862792968750000e-01 -1.685453206300735474e-01 -5.800805985927581787e-02 5.311273932456970215e-01 8.283303380012512207e-01\n-2.555798339843750000e+01 -1.445811462402343750e+01 -4.592394828796386719e-01 -1.677662283182144165e-01 -5.900888144969940186e-02 5.279706120491027832e-01 8.304332494735717773e-01\n-2.571812248229980469e+01 -1.422478961944580078e+01 -4.612707495689392090e-01 -1.669649779796600342e-01 -6.006729975342750549e-02 5.248143672943115234e-01 8.325169086456298828e-01\n-2.587863731384277344e+01 -1.399217700958251953e+01 -4.633276164531707764e-01 -1.662081480026245117e-01 -6.107582896947860718e-02 5.216907262802124023e-01 8.345557451248168945e-01\n-2.603939819335937500e+01 -1.376019477844238281e+01 -4.652734398841857910e-01 -1.655599474906921387e-01 -6.192769110202789307e-02 5.186341404914855957e-01 8.365246057510375977e-01\n-2.620061683654785156e+01 -1.352896499633789062e+01 -4.669726490974426270e-01 -1.650823801755905151e-01 -6.251683831214904785e-02 5.156816840171813965e-01 8.383983969688415527e-01\n-2.636240959167480469e+01 -1.329857921600341797e+01 -4.683166444301605225e-01 -1.648352891206741333e-01 -6.273782253265380859e-02 5.128720402717590332e-01 8.401520252227783203e-01\n-2.652549934387207031e+01 -1.306953620910644531e+01 -4.689233303070068359e-01 -1.648764610290527344e-01 -6.248602271080017090e-02 5.102450251579284668e-01 8.417608141899108887e-01\n-2.668920898437500000e+01 -1.284157180786132812e+01 -4.689306616783142090e-01 -1.635180413722991943e-01 -6.064473092555999756e-02 5.079550147056579590e-01 8.435435891151428223e-01\n-2.678941345214843750e+01 -1.259829521179199219e+01 -4.772912561893463135e-01 -1.627251207828521729e-01 -5.846070125699043274e-02 5.058341622352600098e-01 8.451240658760070801e-01\n-2.651661872863769531e+01 -1.259877395629882812e+01 -5.171887278556823730e-01 -1.624446660280227661e-01 -5.598696693778038025e-02 5.038542747497558594e-01 8.465270996093750000e-01\n-2.624497032165527344e+01 -1.265571308135986328e+01 -5.533349514007568359e-01 -1.626231074333190918e-01 -5.327646434307098389e-02 5.019860267639160156e-01 8.477767109870910645e-01\n-2.597594642639160156e+01 -1.272301197052001953e+01 -5.885253548622131348e-01 -1.632073819637298584e-01 -5.038213729858398438e-02 5.001997947692871094e-01 8.488964438438415527e-01\n-2.570717620849609375e+01 -1.279211902618408203e+01 -6.183996200561523438e-01 -1.641437411308288574e-01 -4.735671356320381165e-02 4.984661638736724854e-01 8.499091863632202148e-01\n-2.543681907653808594e+01 -1.285688400268554688e+01 -6.373022198677062988e-01 -1.653789579868316650e-01 -4.425322264432907104e-02 4.967552125453948975e-01 8.508382439613342285e-01\n-2.515522003173828125e+01 -1.291918945312500000e+01 -6.406725645065307617e-01 -1.668590009212493896e-01 -4.112435504794120789e-02 4.950375556945800781e-01 8.517069220542907715e-01\n-2.486792182922363281e+01 -1.299890136718750000e+01 -6.366809010505676270e-01 -1.685309559106826782e-01 -3.802309930324554443e-02 4.932837784290313721e-01 8.525389432907104492e-01\n-2.459251213073730469e+01 -1.309572219848632812e+01 -6.340332031250000000e-01 -1.703415215015411377e-01 -3.500250354409217834e-02 4.914650619029998779e-01 8.533584475517272949e-01\n-2.432781219482421875e+01 -1.320330047607421875e+01 -6.343395709991455078e-01 -1.722373217344284058e-01 -3.211538866162300110e-02 4.895527064800262451e-01 8.541902303695678711e-01\n-2.407213020324707031e+01 -1.331618118286132812e+01 -6.366015672683715820e-01 -1.741653680801391602e-01 -2.941481396555900574e-02 4.875183403491973877e-01 8.550596237182617188e-01\n-2.382385635375976562e+01 -1.343023872375488281e+01 -6.396130323410034180e-01 -1.760728061199188232e-01 -2.695365622639656067e-02 4.853337705135345459e-01 8.559924364089965820e-01\n-2.358245468139648438e+01 -1.354421329498291016e+01 -6.429601907730102539e-01 -1.779067516326904297e-01 -2.478495612740516663e-02 4.829712510108947754e-01 8.570144176483154297e-01\n-2.334757423400878906e+01 -1.365731906890869141e+01 -6.463440060615539551e-01 -1.796139925718307495e-01 -2.296158671379089355e-02 4.804029166698455811e-01 8.581519126892089844e-01\n-2.311899566650390625e+01 -1.376906681060791016e+01 -6.494702100753784180e-01 -1.811420321464538574e-01 -2.153661847114562988e-02 4.776009321212768555e-01 8.594307899475097656e-01\n-2.289647483825683594e+01 -1.387895011901855469e+01 -6.519653201103210449e-01 -1.824380159378051758e-01 -2.056293934583663940e-02 4.745368361473083496e-01 8.608764410018920898e-01\n-2.267963409423828125e+01 -1.398621082305908203e+01 -6.532312035560607910e-01 -1.834485381841659546e-01 -2.009310945868492126e-02 4.711823761463165283e-01 8.625138401985168457e-01\n-2.246773719787597656e+01 -1.408929157257080078e+01 -6.521801352500915527e-01 -1.841205060482025146e-01 -2.018003538250923157e-02 4.675078690052032471e-01 8.643661141395568848e-01\n-2.226006698608398438e+01 -1.418655204772949219e+01 -6.480712890625000000e-01 -1.844001263380050659e-01 -2.087630331516265869e-02 4.634829461574554443e-01 8.664549589157104492e-01\n-2.205663490295410156e+01 -1.427795410156250000e+01 -6.416552662849426270e-01 -1.835716813802719116e-01 -2.185546979308128357e-02 4.591004848480224609e-01 8.689364194869995117e-01\n-2.185772132873535156e+01 -1.436379337310791016e+01 -6.333520412445068359e-01 -1.824225485324859619e-01 -2.347820624709129333e-02 4.543474614620208740e-01 8.716301321983337402e-01\n-2.166368293762207031e+01 -1.444483852386474609e+01 -6.238781809806823730e-01 -1.810006201267242432e-01 -2.567527443170547485e-02 4.492349326610565186e-01 8.745098710060119629e-01\n-2.147487449645996094e+01 -1.452191352844238281e+01 -6.138256788253784180e-01 -1.793531924486160278e-01 -2.837654948234558105e-02 4.437734782695770264e-01 8.775489926338195801e-01\n-2.129187965393066406e+01 -1.459654712677001953e+01 -6.037365794181823730e-01 -1.775269359350204468e-01 -3.151117265224456787e-02 4.379730820655822754e-01 8.807217478752136230e-01\n-2.111501884460449219e+01 -1.466954517364501953e+01 -5.938305258750915527e-01 -1.755676269531250000e-01 -3.500741720199584961e-02 4.318441450595855713e-01 8.840028047561645508e-01\n-2.094495010375976562e+01 -1.474252891540527344e+01 -5.844531059265136719e-01 -1.735200583934783936e-01 -3.879258409142494202e-02 4.253970980644226074e-01 8.873687386512756348e-01\n-2.078098678588867188e+01 -1.481380367279052734e+01 -5.754565596580505371e-01 -1.714278608560562134e-01 -4.279293864965438843e-02 4.186428785324096680e-01 8.907969594001770020e-01\n-2.062461853027343750e+01 -1.488681602478027344e+01 -5.673596262931823730e-01 -1.693332791328430176e-01 -4.693398624658584595e-02 4.115937650203704834e-01 8.942673206329345703e-01\n-2.047404289245605469e+01 -1.495735359191894531e+01 -5.595715045928955078e-01 -1.672767847776412964e-01 -5.114042758941650391e-02 4.042624533176422119e-01 8.977610468864440918e-01\n-2.033163452148437500e+01 -1.503049278259277344e+01 -5.529308915138244629e-01 -1.652971953153610229e-01 -5.533592775464057922e-02 3.966634571552276611e-01 9.012618064880371094e-01\n-2.019488525390625000e+01 -1.510086917877197266e+01 -5.465551614761352539e-01 -1.634310036897659302e-01 -5.944371595978736877e-02 3.888122439384460449e-01 9.047551155090332031e-01\n-2.006615447998046875e+01 -1.517303657531738281e+01 -5.412658452987670898e-01 -1.617124378681182861e-01 -6.338612735271453857e-02 3.807254731655120850e-01 9.082287549972534180e-01\n-1.994371604919433594e+01 -1.524365234375000000e+01 -5.364623665809631348e-01 -1.601731330156326294e-01 -6.708491593599319458e-02 3.724210858345031738e-01 9.116724133491516113e-01\n-1.982761192321777344e+01 -1.531261730194091797e+01 -5.321472287178039551e-01 -1.588416397571563721e-01 -7.046176493167877197e-02 3.639198243618011475e-01 9.150775074958801270e-01\n-1.971994972229003906e+01 -1.538352966308593750e+01 -5.290173292160034180e-01 -1.577431112527847290e-01 -7.343824952840805054e-02 3.552419245243072510e-01 9.184372425079345703e-01\n-1.961760330200195312e+01 -1.545106887817382812e+01 -5.260412693023681641e-01 -1.568995416164398193e-01 -7.593537867069244385e-02 3.464096486568450928e-01 9.217464923858642578e-01\n-1.952189826965332031e+01 -1.551718235015869141e+01 -5.236254930496215820e-01 -1.563290804624557495e-01 -7.787409424781799316e-02 3.374458253383636475e-01 9.250012040138244629e-01\n-1.943454551696777344e+01 -1.558438968658447266e+01 -5.222949385643005371e-01 -1.560456752777099609e-01 -7.917611300945281982e-02 3.283739984035491943e-01 9.281979203224182129e-01\n-1.934015464782714844e+01 -1.565674781799316406e+01 -5.208557248115539551e-01 -1.560593098402023315e-01 -7.976308465003967285e-02 3.192176818847656250e-01 9.313342571258544922e-01\n-1.924914169311523438e+01 -1.572825622558593750e+01 -5.196911692619323730e-01 -1.563673317432403564e-01 -7.958032190799713135e-02 3.100039660930633545e-01 9.344055056571960449e-01\n-1.916583824157714844e+01 -1.580432605743408203e+01 -5.200195312500000000e-01 -1.569329351186752319e-01 -7.866371423006057739e-02 3.007761240005493164e-01 9.373994469642639160e-01\n-1.908487319946289062e+01 -1.587828063964843750e+01 -5.203344821929931641e-01 -1.577120125293731689e-01 -7.707326114177703857e-02 2.915808260440826416e-01 9.403016567230224609e-01\n-1.900623321533203125e+01 -1.595010185241699219e+01 -5.206396579742431641e-01 -1.586629748344421387e-01 -7.486814260482788086e-02 2.824644148349761963e-01 9.430984258651733398e-01\n-1.893425178527832031e+01 -1.602438926696777344e+01 -5.220336914062500000e-01 -1.597469151020050049e-01 -7.210765033960342407e-02 2.734732627868652344e-01 9.457767605781555176e-01\n-1.886517524719238281e+01 -1.609718704223632812e+01 -5.235705375671386719e-01 -1.609278172254562378e-01 -6.885146349668502808e-02 2.646539509296417236e-01 9.483247995376586914e-01\n-1.879824447631835938e+01 -1.616769027709960938e+01 -5.250585675239562988e-01 -1.621732115745544434e-01 -6.515870243310928345e-02 2.560534775257110596e-01 9.507316946983337402e-01\n-1.873452568054199219e+01 -1.623689460754394531e+01 -5.267516970634460449e-01 -1.634541451930999756e-01 -6.108817085623741150e-02 2.477196604013442993e-01 9.529878497123718262e-01\n-1.867581558227539062e+01 -1.630647850036621094e+01 -5.290759205818176270e-01 -1.647452563047409058e-01 -5.669882893562316895e-02 2.397010773420333862e-01 9.550851583480834961e-01\n-1.861907958984375000e+01 -1.637364196777343750e+01 -5.313208103179931641e-01 -1.660249382257461548e-01 -5.204921215772628784e-02 2.320473194122314453e-01 9.570164680480957031e-01\n-1.856431198120117188e+01 -1.643838310241699219e+01 -5.334875583648681641e-01 -1.672755330801010132e-01 -4.719660058617591858e-02 2.248092293739318848e-01 9.587763547897338867e-01\n-1.851239585876464844e+01 -1.650145912170410156e+01 -5.357751250267028809e-01 -1.684827357530593872e-01 -4.219894483685493469e-02 2.180386632680892944e-01 9.603602290153503418e-01\n-1.846445465087890625e+01 -1.656378936767578125e+01 -5.384314060211181641e-01 -1.696358472108840942e-01 -3.711352124810218811e-02 2.117889374494552612e-01 9.617648720741271973e-01\n-1.841833114624023438e+01 -1.662360763549804688e+01 -5.409862995147705078e-01 -1.707274615764617920e-01 -3.199715912342071533e-02 2.061144709587097168e-01 9.629875421524047852e-01\n-1.837400627136230469e+01 -1.668091773986816406e+01 -5.434387326240539551e-01 -1.717531234025955200e-01 -2.690691873431205750e-02 2.010709494352340698e-01 9.640266299247741699e-01\n-1.833147239685058594e+01 -1.673570823669433594e+01 -5.457910299301147461e-01 -1.727110296487808228e-01 -2.190021425485610962e-02 1.967148929834365845e-01 9.648805260658264160e-01\n-1.829236221313476562e+01 -1.678922843933105469e+01 -5.483788847923278809e-01 -1.736016720533370972e-01 -1.703507639467716217e-02 1.931038051843643188e-01 9.655480384826660156e-01\n-1.825531387329101562e+01 -1.684044837951660156e+01 -5.509252548217773438e-01 -1.744272559881210327e-01 -1.237064786255359650e-02 1.902956515550613403e-01 9.660277962684631348e-01\n-1.821992683410644531e+01 -1.688907623291015625e+01 -5.533496141433715820e-01 -1.751911938190460205e-01 -7.967818528413772583e-03 1.883485168218612671e-01 9.663174152374267578e-01\n-1.818618583679199219e+01 -1.693511199951171875e+01 -5.556518435478210449e-01 -1.758974492549896240e-01 -3.889763727784156799e-03 1.873202025890350342e-01 9.664139747619628906e-01\n-1.815403366088867188e+01 -1.697879791259765625e+01 -5.585265755653381348e-01 -1.736778020858764648e-01 3.683120012283325195e-04 1.872485131025314331e-01 9.668369889259338379e-01\n-1.812410545349121094e+01 -1.702033615112304688e+01 -5.615234375000000000e-01 -1.708639562129974365e-01 4.365487024188041687e-03 1.880719512701034546e-01 9.671686887741088867e-01\n-1.809640502929687500e+01 -1.705971717834472656e+01 -5.646276473999023438e-01 -1.675173193216323853e-01 8.118055760860443115e-03 1.897289156913757324e-01 9.674062728881835938e-01\n-1.807031250000000000e+01 -1.709648895263671875e+01 -5.677074790000915527e-01 -1.636992692947387695e-01 1.164237223565578461e-02 1.921575218439102173e-01 9.675445556640625000e-01\n-1.804584503173828125e+01 -1.713065338134765625e+01 -5.707470774650573730e-01 -1.594703197479248047e-01 1.495485939085483551e-02 1.952953934669494629e-01 9.675769805908203125e-01\n-1.802301406860351562e+01 -1.716219711303710938e+01 -5.737353563308715820e-01 -1.548913419246673584e-01 1.807173900306224823e-02 1.990799605846405029e-01 9.674964547157287598e-01\n-1.800183868408203125e+01 -1.719112205505371094e+01 -5.766589045524597168e-01 -1.500232070684432983e-01 2.100928872823715210e-02 2.034485489130020142e-01 9.672953486442565918e-01\n-1.798233222961425781e+01 -1.721742630004882812e+01 -5.795056223869323730e-01 -1.449269354343414307e-01 2.378391660749912262e-02 2.083385735750198364e-01 9.669671654701232910e-01\n-1.796454048156738281e+01 -1.724111747741699219e+01 -5.822631716728210449e-01 -1.396637409925460815e-01 2.641172707080841064e-02 2.136875092983245850e-01 9.665061235427856445e-01\n-1.794881820678710938e+01 -1.726243591308593750e+01 -5.849756002426147461e-01 -1.342951357364654541e-01 2.890913002192974091e-02 2.194330692291259766e-01 9.659079313278198242e-01\n-1.793476104736328125e+01 -1.728108406066894531e+01 -5.875573754310607910e-01 -1.288829147815704346e-01 3.129223734140396118e-02 2.255132198333740234e-01 9.651703834533691406e-01\n-1.792238235473632812e+01 -1.729707527160644531e+01 -5.899950861930847168e-01 -1.234894543886184692e-01 3.357748687267303467e-02 2.318663746118545532e-01 9.642929434776306152e-01\n-1.791169548034667969e+01 -1.731039047241210938e+01 -5.922704935073852539e-01 -1.181771308183670044e-01 3.578108549118041992e-02 2.384315133094787598e-01 9.632779359817504883e-01\n-1.790271568298339844e+01 -1.732105445861816406e+01 -5.943713188171386719e-01 -1.130089387297630310e-01 3.791945800185203552e-02 2.451479583978652954e-01 9.621296525001525879e-01\n-1.789545440673828125e+01 -1.732906150817871094e+01 -5.962817072868347168e-01 -1.080475375056266785e-01 4.000906646251678467e-02 2.519558668136596680e-01 9.608554244041442871e-01\n-1.788992500305175781e+01 -1.733441925048828125e+01 -5.979833602905273438e-01 -1.033566072583198547e-01 4.206611216068267822e-02 2.587959468364715576e-01 9.594647884368896484e-01\n-1.788613891601562500e+01 -1.733712768554687500e+01 -5.994641184806823730e-01 -9.899981319904327393e-02 4.410721734166145325e-02 2.656095325946807861e-01 9.579692482948303223e-01\n-1.788411140441894531e+01 -1.733719635009765625e+01 -6.007080078125000000e-01 -9.504061937332153320e-02 4.614873975515365601e-02 2.723386883735656738e-01 9.563834071159362793e-01\n-1.787696456909179688e+01 -1.734501457214355469e+01 -6.022863388061523438e-01 -9.154327213764190674e-02 4.820729792118072510e-02 2.789262533187866211e-01 9.547230601310729980e-01\n-1.786470603942871094e+01 -1.736057662963867188e+01 -6.041833162307739258e-01 -8.857118338346481323e-02 5.029954761266708374e-02 2.853153944015502930e-01 9.530058503150939941e-01\n-1.784735107421875000e+01 -1.738390541076660156e+01 -6.063903570175170898e-01 -8.616801351308822632e-02 5.243882536888122559e-02 2.914660573005676270e-01 9.512479901313781738e-01\n-1.782488632202148438e+01 -1.741499900817871094e+01 -6.089184284210205078e-01 -8.429352939128875732e-02 5.462608486413955688e-02 2.974020540714263916e-01 9.494538903236389160e-01\n-1.779734039306640625e+01 -1.745387077331542969e+01 -6.117821931838989258e-01 -8.288758993148803711e-02 5.685858055949211121e-02 3.031627237796783447e-01 9.476228952407836914e-01\n-1.776491355895996094e+01 -1.750066947937011719e+01 -6.150036454200744629e-01 -8.188873529434204102e-02 5.913389846682548523e-02 3.087868690490722656e-01 9.457526803016662598e-01\n-1.772739982604980469e+01 -1.755525779724121094e+01 -6.185900568962097168e-01 -8.123598992824554443e-02 6.144924834370613098e-02 3.143127262592315674e-01 9.438390731811523438e-01\n-1.768478775024414062e+01 -1.761763572692871094e+01 -6.225597858428955078e-01 -8.086805045604705811e-02 6.380198150873184204e-02 3.197781145572662354e-01 9.418767094612121582e-01\n-1.763625717163085938e+01 -1.768726539611816406e+01 -6.266626119613647461e-01 -8.072343468666076660e-02 6.618919223546981812e-02 3.252205848693847656e-01 9.398586750030517578e-01\n-1.758230400085449219e+01 -1.776447677612304688e+01 -6.310778856277465820e-01 -8.074045926332473755e-02 6.860806047916412354e-02 3.306772112846374512e-01 9.377774000167846680e-01\n-1.752128601074218750e+01 -1.784814834594726562e+01 -6.353161334991455078e-01 -8.085796236991882324e-02 7.105553895235061646e-02 3.361848294734954834e-01 9.356243014335632324e-01\n-1.745257949829101562e+01 -1.793774414062500000e+01 -6.392089724540710449e-01 -8.101430535316467285e-02 7.352856546640396118e-02 3.417798578739166260e-01 9.333900213241577148e-01\n-1.737313652038574219e+01 -1.803073692321777344e+01 -6.418249607086181641e-01 -8.114737272262573242e-02 7.602420449256896973e-02 3.474985361099243164e-01 9.310639500617980957e-01\n-1.727821540832519531e+01 -1.812207412719726562e+01 -6.416015625000000000e-01 -8.119583874940872192e-02 7.853914797306060791e-02 3.533766865730285645e-01 9.286354780197143555e-01\n-1.716444396972656250e+01 -1.820580101013183594e+01 -6.372119188308715820e-01 -8.109773695468902588e-02 8.107020705938339233e-02 3.594494760036468506e-01 9.260922670364379883e-01\n-1.703792572021484375e+01 -1.828765106201171875e+01 -6.308032274246215820e-01 -8.079120516777038574e-02 8.361406624317169189e-02 3.657518625259399414e-01 9.234213232994079590e-01\n-1.690320205688476562e+01 -1.837402725219726562e+01 -6.242114305496215820e-01 -8.021453022956848145e-02 8.616720885038375854e-02 3.723181784152984619e-01 9.206085205078125000e-01\n-1.676093673706054688e+01 -1.846594619750976562e+01 -6.178197860717773438e-01 -7.930594682693481445e-02 8.872600644826889038e-02 3.791821002960205078e-01 9.176378250122070312e-01\n-1.661141777038574219e+01 -1.856386184692382812e+01 -6.118798851966857910e-01 -7.800345122814178467e-02 9.128685295581817627e-02 3.863770961761474609e-01 9.144915938377380371e-01\n-1.645495605468750000e+01 -1.866820716857910156e+01 -6.066784262657165527e-01 -7.624515146017074585e-02 9.384562075138092041e-02 3.939341008663177490e-01 9.111507534980773926e-01\n-1.629194259643554688e+01 -1.877953529357910156e+01 -6.025720238685607910e-01 -7.396907359361648560e-02 9.639839082956314087e-02 4.018841981887817383e-01 9.075930118560791016e-01\n-1.612274742126464844e+01 -1.889830017089843750e+01 -5.998827815055847168e-01 -7.111330330371856689e-02 9.894046932458877563e-02 4.102570116519927979e-01 9.037936329841613770e-01\n-1.594792461395263672e+01 -1.902517127990722656e+01 -5.990747213363647461e-01 -6.764376163482666016e-02 1.014612764120101929e-01 4.190501570701599121e-01 8.997371196746826172e-01\n-1.576822853088378906e+01 -1.916101074218750000e+01 -6.007885336875915527e-01 -6.363680213689804077e-02 1.039256975054740906e-01 4.281411468982696533e-01 8.954579234123229980e-01\n-1.558430385589599609e+01 -1.930643463134765625e+01 -6.056188941001892090e-01 -5.919722840189933777e-02 1.062933802604675293e-01 4.373798668384552002e-01 8.910086154937744141e-01\n-1.539637660980224609e+01 -1.946148300170898438e+01 -6.137255430221557617e-01 -5.443003028631210327e-02 1.085248515009880066e-01 4.466195404529571533e-01 8.864483833312988281e-01\n-1.520430183410644531e+01 -1.962582397460937500e+01 -6.249060034751892090e-01 -4.944133758544921875e-02 1.105812788009643555e-01 4.557167887687683105e-01 8.818444013595581055e-01\n-1.500771331787109375e+01 -1.979891586303710938e+01 -6.387646198272705078e-01 -4.433740675449371338e-02 1.124248802661895752e-01 4.645321965217590332e-01 8.772711157798767090e-01\n-1.480619621276855469e+01 -1.998026275634765625e+01 -6.548547148704528809e-01 -3.922503814101219177e-02 1.140190213918685913e-01 4.729304611682891846e-01 8.728103041648864746e-01\n-1.459937191009521484e+01 -2.016944694519042969e+01 -6.727819442749023438e-01 -3.421109169721603394e-02 1.153278648853302002e-01 4.807797670364379883e-01 8.685504198074340820e-01\n-1.438695049285888672e+01 -2.036620521545410156e+01 -6.922289729118347168e-01 -2.940253913402557373e-02 1.163163855671882629e-01 4.879520535469055176e-01 8.645858764648437500e-01\n-1.416900730133056641e+01 -2.057060050964355469e+01 -7.132446169853210449e-01 -2.490628883242607117e-02 1.169503927230834961e-01 4.943219423294067383e-01 8.610157370567321777e-01\n-1.395810794830322266e+01 -2.076930618286132812e+01 -7.336339950561523438e-01 -2.082914486527442932e-02 1.171961426734924316e-01 4.997668564319610596e-01 8.579419851303100586e-01\n-1.375402069091796875e+01 -2.096210861206054688e+01 -7.532275319099426270e-01 -1.727757975459098816e-02 1.170200556516647339e-01 5.041647553443908691e-01 8.554680943489074707e-01\n-1.355647563934326172e+01 -2.114881706237792969e+01 -7.714196443557739258e-01 -1.435786113142967224e-02 1.163884699344635010e-01 5.073940157890319824e-01 8.536972403526306152e-01\n-1.336550045013427734e+01 -2.132947158813476562e+01 -7.884838581085205078e-01 -1.217595487833023071e-02 1.152671799063682556e-01 5.093313455581665039e-01 8.527289628982543945e-01\n-1.318074798583984375e+01 -2.150379371643066406e+01 -8.037194609642028809e-01 -1.083766296505928040e-02 1.136212199926376343e-01 5.098505020141601562e-01 8.526577949523925781e-01\n-1.300255870819091797e+01 -2.167208480834960938e+01 -8.177490234375000000e-01 -1.044839248061180115e-02 1.114140003919601440e-01 5.088196992874145508e-01 8.535690903663635254e-01\n-1.283029842376708984e+01 -2.183377456665039062e+01 -8.294262290000915527e-01 -1.111348345875740051e-02 1.086074858903884888e-01 5.061002373695373535e-01 8.555368781089782715e-01\n-1.266489505767822266e+01 -2.198973655700683594e+01 -8.402550816535949707e-01 -1.293786615133285522e-02 1.051610410213470459e-01 5.015448331832885742e-01 8.586189746856689453e-01\n-1.250496673583984375e+01 -2.213861274719238281e+01 -8.478466868400573730e-01 -1.602597907185554504e-02 1.010316461324691772e-01 4.949942231178283691e-01 8.628536462783813477e-01\n-1.235201644897460938e+01 -2.228182601928710938e+01 -8.545812964439392090e-01 -2.048139087855815887e-02 9.617313742637634277e-02 4.862766563892364502e-01 8.682547211647033691e-01\n-1.220498275756835938e+01 -2.241820335388183594e+01 -8.585851788520812988e-01 -2.635845541954040527e-02 9.055834263563156128e-02 4.752687513828277588e-01 8.747708797454833984e-01\n-1.206440067291259766e+01 -2.254821205139160156e+01 -8.607397079467773438e-01 -3.351867198944091797e-02 8.424679934978485107e-02 4.620925784111022949e-01 8.821844458580017090e-01\n-1.193075942993164062e+01 -2.267219161987304688e+01 -8.618810772895812988e-01 -4.177390038967132568e-02 7.732103765010833740e-02 4.469355344772338867e-01 8.902387619018554688e-01\n-1.180233383178710938e+01 -2.278814315795898438e+01 -8.590893149375915527e-01 -5.093406885862350464e-02 6.986640393733978271e-02 4.299928843975067139e-01 8.986826539039611816e-01\n-1.168124580383300781e+01 -2.289830017089843750e+01 -8.560631871223449707e-01 -6.080749630928039551e-02 6.197084113955497742e-02 4.114713370800018311e-01 9.072780609130859375e-01\n-1.156612873077392578e+01 -2.300089836120605469e+01 -8.504064679145812988e-01 -7.120185345411300659e-02 5.372554808855056763e-02 3.915930092334747314e-01 9.158050417900085449e-01\n-1.145700263977050781e+01 -2.309589767456054688e+01 -8.422644138336181641e-01 -8.192436397075653076e-02 4.522506892681121826e-02 3.705942034721374512e-01 9.240686893463134766e-01\n-1.135530757904052734e+01 -2.318506240844726562e+01 -8.344018459320068359e-01 -9.278335422277450562e-02 3.656715154647827148e-02 3.487282693386077881e-01 9.319027662277221680e-01\n-1.125894165039062500e+01 -2.326542854309082031e+01 -8.236218094825744629e-01 -1.035891473293304443e-01 2.785192057490348816e-02 3.262639045715332031e-01 9.391727447509765625e-01\n-1.116942977905273438e+01 -2.333920860290527344e+01 -8.125329613685607910e-01 -1.141555085778236389e-01 1.918116211891174316e-02 3.034849464893341064e-01 9.457788467407226562e-01\n-1.108734512329101562e+01 -2.340727424621582031e+01 -8.022240996360778809e-01 -1.243009939789772034e-01 1.065819710493087769e-02 2.806864678859710693e-01 9.516568779945373535e-01\n-1.101012325286865234e+01 -2.346564865112304688e+01 -7.894347906112670898e-01 -1.338488608598709106e-01 2.386640757322311401e-03 2.581741809844970703e-01 9.567784667015075684e-01\n-1.094018077850341797e+01 -2.351834869384765625e+01 -7.775878906250000000e-01 -1.426293998956680298e-01 -5.530703812837600708e-03 2.362618595361709595e-01 9.611486196517944336e-01\n-1.087761116027832031e+01 -2.356570243835449219e+01 -7.669897079467773438e-01 -1.504779756069183350e-01 -1.299132406711578369e-02 2.152677923440933228e-01 9.648043513298034668e-01\n-1.081989383697509766e+01 -2.360318374633789062e+01 -7.549633383750915527e-01 -1.572377234697341919e-01 -1.989493519067764282e-02 1.955124735832214355e-01 9.678095579147338867e-01\n-1.076939964294433594e+01 -2.363549232482910156e+01 -7.443163990974426270e-01 -1.627555489540100098e-01 -2.614275738596916199e-02 1.773162335157394409e-01 9.702506065368652344e-01\n-1.072629261016845703e+01 -2.366316795349121094e+01 -7.353747487068176270e-01 -1.668835878372192383e-01 -3.163781389594078064e-02 1.609973907470703125e-01 9.722288250923156738e-01\n-1.068942451477050781e+01 -2.368360710144042969e+01 -7.270935177803039551e-01 -1.694756001234054565e-01 -3.628516569733619690e-02 1.468703299760818481e-01 9.738534092903137207e-01\n-1.065877342224121094e+01 -2.369713401794433594e+01 -7.197473049163818359e-01 -1.697092056274414062e-01 -3.989725559949874878e-02 1.352724879980087280e-01 9.753503203392028809e-01\n-1.063575077056884766e+01 -2.370730972290039062e+01 -7.143371701240539551e-01 -1.694652587175369263e-01 -4.266242682933807373e-02 1.264244019985198975e-01 9.764621257781982422e-01\n-1.062023162841796875e+01 -2.371432495117187500e+01 -7.113623023033142090e-01 -1.666205227375030518e-01 -4.424036294221878052e-02 1.206160113215446472e-01 9.776155352592468262e-01\n-1.061051654815673828e+01 -2.371881866455078125e+01 -7.102355957031250000e-01 -1.619942039251327515e-01 -4.480173811316490173e-02 1.176587045192718506e-01 9.787273406982421875e-01\n-1.060666942596435547e+01 -2.372078132629394531e+01 -7.109069824218750000e-01 -1.557830721139907837e-01 -4.445625096559524536e-02 1.172960177063941956e-01 9.797943234443664551e-01\n-1.060481262207031250e+01 -2.372170448303222656e+01 -7.124841213226318359e-01 -1.481798291206359863e-01 -4.331202805042266846e-02 1.192679628729820251e-01 9.807863831520080566e-01\n-1.059402942657470703e+01 -2.372573280334472656e+01 -7.125634551048278809e-01 -1.393745392560958862e-01 -4.147681593894958496e-02 1.233121752738952637e-01 9.816560149192810059e-01\n-1.057428169250488281e+01 -2.373179626464843750e+01 -7.108715772628784180e-01 -1.295560449361801147e-01 -3.905843943357467651e-02 1.291646510362625122e-01 9.823472499847412109e-01\n-1.054468154907226562e+01 -2.373078536987304688e+01 -7.053527832031250000e-01 -1.189149618148803711e-01 -3.616411983966827393e-02 1.365606486797332764e-01 9.828034639358520508e-01\n-1.050600719451904297e+01 -2.372926712036132812e+01 -6.974206566810607910e-01 -1.076428443193435669e-01 -3.290275484323501587e-02 1.452350765466690063e-01 9.829736351966857910e-01\n-1.047626781463623047e+01 -2.370073127746582031e+01 -6.884130835533142090e-01 -9.593401104211807251e-02 -2.938275039196014404e-02 1.549237966537475586e-01 9.828183650970458984e-01\n-1.046522426605224609e+01 -2.364887619018554688e+01 -6.820385456085205078e-01 -8.398548513650894165e-02 -2.571449242532253265e-02 1.653640419244766235e-01 9.823135137557983398e-01\n-1.048062133789062500e+01 -2.358564949035644531e+01 -6.827343702316284180e-01 -7.199695706367492676e-02 -2.200762741267681122e-02 1.762954741716384888e-01 9.814540743827819824e-01\n-1.050563335418701172e+01 -2.351642608642578125e+01 -6.861621141433715820e-01 -6.017067655920982361e-02 -1.837365329265594482e-02 1.874611973762512207e-01 9.802551865577697754e-01\n-1.054297256469726562e+01 -2.344232940673828125e+01 -6.934130787849426270e-01 -4.871069639921188354e-02 -1.492377743124961853e-02 1.986082196235656738e-01 9.787539839744567871e-01\n-1.058514404296875000e+01 -2.336031723022460938e+01 -7.011474370956420898e-01 -3.782265260815620422e-02 -1.176953222602605820e-02 2.094882875680923462e-01 9.770084619522094727e-01\n-1.063856792449951172e+01 -2.327448272705078125e+01 -7.121984958648681641e-01 -2.771227434277534485e-02 -9.021600708365440369e-03 2.198581695556640625e-01 9.750964045524597168e-01\n-1.069721889495849609e+01 -2.318099975585937500e+01 -7.237438559532165527e-01 -1.858626678586006165e-02 -6.791889201849699020e-03 2.294794023036956787e-01 9.731123447418212891e-01\n-1.076325702667236328e+01 -2.308148384094238281e+01 -7.366576790809631348e-01 -1.065042708069086075e-02 -5.190695635974407196e-03 2.381179630756378174e-01 9.711639881134033203e-01\n-1.083692359924316406e+01 -2.297613716125488281e+01 -7.509692311286926270e-01 -4.110292997211217880e-03 -4.328842274844646454e-03 2.455432265996932983e-01 9.693673253059387207e-01\n-1.091626167297363281e+01 -2.286353874206542969e+01 -7.657372951507568359e-01 8.294742438010871410e-04 -4.317172802984714508e-03 2.515261769294738770e-01 9.678404927253723145e-01\n-1.100432872772216797e+01 -2.274613761901855469e+01 -7.821130156517028809e-01 3.964609466493129730e-03 -5.266502965241670609e-03 2.558379769325256348e-01 9.666971564292907715e-01\n-1.109833145141601562e+01 -2.262172889709472656e+01 -7.989257574081420898e-01 5.153934471309185028e-03 -7.251162547618150711e-03 2.583153545856475830e-01 9.660197496414184570e-01\n-1.119967460632324219e+01 -2.249148941040039062e+01 -8.166686892509460449e-01 4.504605196416378021e-03 -1.019955892115831375e-02 2.590637207031250000e-01 9.657959342002868652e-01\n-1.130787372589111328e+01 -2.235502433776855469e+01 -8.352453708648681641e-01 2.185793127864599228e-03 -1.400303561240434647e-02 2.582513689994812012e-01 9.659738540649414062e-01\n-1.142283821105957031e+01 -2.221224975585937500e+01 -8.545776009559631348e-01 -1.633108127862215042e-03 -1.855275034904479980e-02 2.560428678989410400e-01 9.664859771728515625e-01\n-1.154491806030273438e+01 -2.206347084045410156e+01 -8.747839331626892090e-01 -6.783263292163610458e-03 -2.373933419585227966e-02 2.526000142097473145e-01 9.672556519508361816e-01\n-1.167372322082519531e+01 -2.190831565856933594e+01 -8.956835865974426270e-01 -1.309422217309474945e-02 -2.945379167795181274e-02 2.480840981006622314e-01 9.682021141052246094e-01\n-1.180952262878417969e+01 -2.174700164794921875e+01 -9.173119664192199707e-01 -2.039594948291778564e-02 -3.558594360947608948e-02 2.426568120718002319e-01 9.692447185516357422e-01\n-1.195242786407470703e+01 -2.157956504821777344e+01 -9.393078684806823730e-01 -2.851795963943004608e-02 -4.202570021152496338e-02 2.364814728498458862e-01 9.703077077865600586e-01\n-1.210221576690673828e+01 -2.140580940246582031e+01 -9.616162180900573730e-01 -3.728902339935302734e-02 -4.866314306855201721e-02 2.297237962484359741e-01 9.713229537010192871e-01\n-1.225943660736083984e+01 -2.122608375549316406e+01 -9.834057688713073730e-01 -4.653758928179740906e-02 -5.538772046566009521e-02 2.225524336099624634e-01 9.722328782081604004e-01\n-1.242544555664062500e+01 -2.104152297973632812e+01 -1.003858566284179688e+00 -5.609222501516342163e-02 -6.208969652652740479e-02 2.151391804218292236e-01 9.729921221733093262e-01\n-1.259703445434570312e+01 -2.086024856567382812e+01 -1.021265864372253418e+00 -6.578211486339569092e-02 -6.865978240966796875e-02 2.076589465141296387e-01 9.735688567161560059e-01\n-1.277709674835205078e+01 -2.068539428710937500e+01 -1.034840106964111328e+00 -7.543698698282241821e-02 -7.498934864997863770e-02 2.002898007631301880e-01 9.739454984664916992e-01\n-1.297280883789062500e+01 -2.052606964111328125e+01 -1.043343424797058105e+00 -8.488766103982925415e-02 -8.097057044506072998e-02 1.932124793529510498e-01 9.741185307502746582e-01\n-1.318554782867431641e+01 -2.038809967041015625e+01 -1.050672531127929688e+00 -9.396622329950332642e-02 -8.649715036153793335e-02 1.866097748279571533e-01 9.740972518920898438e-01\n-1.340810298919677734e+01 -2.026439857482910156e+01 -1.056845664978027344e+00 -1.025063842535018921e-01 -9.146361798048019409e-02 1.806665956974029541e-01 9.739026427268981934e-01\n-1.363603401184082031e+01 -2.014865112304687500e+01 -1.056191325187683105e+00 -1.103432998061180115e-01 -9.576536715030670166e-02 1.755688339471817017e-01 9.735651016235351562e-01\n-1.386581039428710938e+01 -2.003540420532226562e+01 -1.043540000915527344e+00 -1.173135638236999512e-01 -9.929943084716796875e-02 1.715029180049896240e-01 9.731207489967346191e-01\n-1.409475421905517578e+01 -1.992141151428222656e+01 -1.015662789344787598e+00 -1.232542917132377625e-01 -1.019623205065727234e-01 1.686556339263916016e-01 9.726085066795349121e-01\n-1.432707595825195312e+01 -1.981404304504394531e+01 -9.837145805358886719e-01 -1.280037760734558105e-01 -1.036513596773147583e-01 1.672129184007644653e-01 9.720654487609863281e-01\n-1.456527996063232422e+01 -1.971718215942382812e+01 -9.577209353446960449e-01 -1.314439326524734497e-01 -1.042973548173904419e-01 1.673095226287841797e-01 9.715204834938049316e-01\n-1.480920982360839844e+01 -1.963162612915039062e+01 -9.416223168373107910e-01 -1.336328685283660889e-01 -1.039666831493377686e-01 1.688769906759262085e-01 9.709860086441040039e-01\n-1.505674266815185547e+01 -1.955385780334472656e+01 -9.336132407188415527e-01 -1.346721351146697998e-01 -1.027587950229644775e-01 1.717943102121353149e-01 9.704590439796447754e-01\n-1.530693912506103516e+01 -1.948230361938476562e+01 -9.326086044311523438e-01 -1.346603780984878540e-01 -1.007723584771156311e-01 1.759385019540786743e-01 9.699262976646423340e-01\n-1.555902957916259766e+01 -1.941506385803222656e+01 -9.368615746498107910e-01 -1.336965858936309814e-01 -9.810473024845123291e-02 1.811851710081100464e-01 9.693671464920043945e-01\n-1.581249237060546875e+01 -1.935045433044433594e+01 -9.446935653686523438e-01 -1.318787783384323120e-01 -9.485309571027755737e-02 1.874091774225234985e-01 9.687562584877014160e-01\n-1.606719398498535156e+01 -1.928809928894042969e+01 -9.559924006462097168e-01 -1.293048858642578125e-01 -9.111483395099639893e-02 1.944845765829086304e-01 9.680672287940979004e-01\n-1.632287406921386719e+01 -1.922676658630371094e+01 -9.694970250129699707e-01 -1.260729134082794189e-01 -8.698722720146179199e-02 2.022854983806610107e-01 9.672741889953613281e-01\n-1.657949256896972656e+01 -1.916606903076171875e+01 -9.848546981811523438e-01 -1.222814619541168213e-01 -8.256836235523223877e-02 2.106860280036926270e-01 9.663545489311218262e-01\n-1.683703422546386719e+01 -1.910580062866210938e+01 -1.001964092254638672e+00 -1.180305927991867065e-01 -7.795666903257369995e-02 2.195609360933303833e-01 9.652899503707885742e-01\n-1.709544563293457031e+01 -1.904576110839843750e+01 -1.021319508552551270e+00 -1.134206950664520264e-01 -7.325114309787750244e-02 2.287859469652175903e-01 9.640679359436035156e-01\n-1.735464859008789062e+01 -1.898541450500488281e+01 -1.042510986328125000e+00 -1.085525155067443848e-01 -6.855186820030212402e-02 2.382379472255706787e-01 9.626835584640502930e-01\n-1.761455535888671875e+01 -1.892434120178222656e+01 -1.065726280212402344e+00 -1.035291403532028198e-01 -6.395925581455230713e-02 2.477953881025314331e-01 9.611391425132751465e-01\n-1.787494087219238281e+01 -1.886177253723144531e+01 -1.091593027114868164e+00 -9.845310449600219727e-02 -5.957423523068428040e-02 2.573384940624237061e-01 9.594449996948242188e-01\n-1.813428115844726562e+01 -1.879277229309082031e+01 -1.122253417968750000e+00 -9.342893958091735840e-02 -5.549824237823486328e-02 2.667495608329772949e-01 9.576197862625122070e-01\n-1.833241462707519531e+01 -1.866669464111328125e+01 -1.176586866378784180e+00 -8.856072276830673218e-02 -5.183271691203117371e-02 2.759130597114562988e-01 9.556894898414611816e-01\n-1.808251571655273438e+01 -1.856697273254394531e+01 -1.208829283714294434e+00 -8.395332098007202148e-02 -4.868030920624732971e-02 2.847153842449188232e-01 9.536872506141662598e-01\n-1.782111358642578125e+01 -1.851432037353515625e+01 -1.220994830131530762e+00 -7.971203327178955078e-02 -4.614233970642089844e-02 2.930452525615692139e-01 9.516519308090209961e-01\n-1.756674957275390625e+01 -1.847419929504394531e+01 -1.227602481842041016e+00 -7.594230771064758301e-02 -4.432166740298271179e-02 3.007927834987640381e-01 9.496273398399353027e-01\n-1.732123565673828125e+01 -1.843797302246093750e+01 -1.232556104660034180e+00 -7.274919003248214722e-02 -4.332016408443450928e-02 3.078496754169464111e-01 9.476599693298339844e-01\n-1.708448410034179688e+01 -1.840636253356933594e+01 -1.235462665557861328e+00 -7.021540403366088867e-02 -4.320727288722991943e-02 3.141236603260040283e-01 9.457956552505493164e-01\n-1.685700225830078125e+01 -1.837602424621582031e+01 -1.238062739372253418e+00 -6.833245605230331421e-02 -4.392163828015327454e-02 3.195825815200805664e-01 9.440701603889465332e-01\n-1.663839530944824219e+01 -1.835005760192871094e+01 -1.238934278488159180e+00 -6.706956028938293457e-02 -4.536860436201095581e-02 3.242086470127105713e-01 9.425137042999267578e-01\n-1.642906761169433594e+01 -1.832528686523437500e+01 -1.239571452140808105e+00 -6.639516353607177734e-02 -4.745297878980636597e-02 3.279826641082763672e-01 9.411520957946777344e-01\n-1.622902488708496094e+01 -1.830168914794921875e+01 -1.240007281303405762e+00 -6.627741456031799316e-02 -5.008045583963394165e-02 3.308842480182647705e-01 9.400079250335693359e-01\n-1.603810691833496094e+01 -1.828070259094238281e+01 -1.239680171012878418e+00 -6.668455898761749268e-02 -5.315614491701126099e-02 3.328922688961029053e-01 9.391008615493774414e-01\n-1.585641098022460938e+01 -1.826147842407226562e+01 -1.238952636718750000e+00 -6.758426874876022339e-02 -5.658433213829994202e-02 3.339850008487701416e-01 9.384479522705078125e-01\n-1.568401622772216797e+01 -1.824333953857421875e+01 -1.238115191459655762e+00 -6.894429028034210205e-02 -6.027023121714591980e-02 3.341394960880279541e-01 9.380645155906677246e-01\n-1.552092266082763672e+01 -1.822630310058593750e+01 -1.237186193466186523e+00 -7.073239982128143311e-02 -6.411853432655334473e-02 3.333325684070587158e-01 9.379633069038391113e-01\n-1.536710643768310547e+01 -1.821068763732910156e+01 -1.236071705818176270e+00 -7.291604578495025635e-02 -6.803405284881591797e-02 3.315400183200836182e-01 9.381555318832397461e-01\n-1.522249126434326172e+01 -1.819730377197265625e+01 -1.234512925148010254e+00 -7.546215504407882690e-02 -7.192133367061614990e-02 3.287371993064880371e-01 9.386504292488098145e-01\n-1.508719921112060547e+01 -1.818493080139160156e+01 -1.232949137687683105e+00 -7.833813130855560303e-02 -7.568459212779998779e-02 3.248988687992095947e-01 9.394549727439880371e-01\n-1.496123886108398438e+01 -1.817356491088867188e+01 -1.231396436691284180e+00 -8.151099085807800293e-02 -7.922795414924621582e-02 3.199989199638366699e-01 9.405741095542907715e-01\n-1.484461498260498047e+01 -1.816320228576660156e+01 -1.229871749877929688e+00 -8.494706451892852783e-02 -8.245579898357391357e-02 3.140104711055755615e-01 9.420098066329956055e-01\n-1.473733615875244141e+01 -1.815383720397949219e+01 -1.228391051292419434e+00 -8.861301839351654053e-02 -8.527182042598724365e-02 3.069058656692504883e-01 9.437612295150756836e-01\n-1.463940525054931641e+01 -1.814546394348144531e+01 -1.226967692375183105e+00 -9.247442334890365601e-02 -8.757954835891723633e-02 2.986566722393035889e-01 9.458237290382385254e-01\n-1.455079936981201172e+01 -1.813845634460449219e+01 -1.225509047508239746e+00 -9.649711102247238159e-02 -8.928236365318298340e-02 2.892331182956695557e-01 9.481883049011230469e-01\n-1.447151565551757812e+01 -1.813287544250488281e+01 -1.224000215530395508e+00 -1.006453931331634521e-01 -9.028363227844238281e-02 2.786045968532562256e-01 9.508411288261413574e-01\n-1.440161228179931641e+01 -1.812816429138183594e+01 -1.222614765167236328e+00 -1.048841774463653564e-01 -9.048581123352050781e-02 2.667394876480102539e-01 9.537618160247802734e-01\n-1.434109973907470703e+01 -1.812429237365722656e+01 -1.221358656883239746e+00 -1.091762632131576538e-01 -8.979181945323944092e-02 2.536047101020812988e-01 9.569235444068908691e-01\n-1.428998184204101562e+01 -1.812124443054199219e+01 -1.220239281654357910e+00 -1.134869679808616638e-01 -8.813484013080596924e-02 2.391924560070037842e-01 9.602811336517333984e-01\n-1.424823951721191406e+01 -1.811898422241210938e+01 -1.219243168830871582e+00 -1.177903041243553162e-01 -8.556693792343139648e-02 2.236001640558242798e-01 9.637461304664611816e-01\n-1.421585559844970703e+01 -1.811746978759765625e+01 -1.218361735343933105e+00 -1.220636069774627686e-01 -8.217258751392364502e-02 2.069532722234725952e-01 9.672220349311828613e-01\n-1.419280338287353516e+01 -1.811666488647460938e+01 -1.217582941055297852e+00 -1.262835711240768433e-01 -7.803602516651153564e-02 1.893805265426635742e-01 9.706172347068786621e-01\n-1.417905616760253906e+01 -1.811654281616210938e+01 -1.216898202896118164e+00 -1.304282695055007935e-01 -7.324372977018356323e-02 1.710139065980911255e-01 9.738470911979675293e-01\n-1.417458438873291016e+01 -1.811705970764160156e+01 -1.216296315193176270e+00 -1.344764232635498047e-01 -6.788312643766403198e-02 1.519887447357177734e-01 9.768354892730712891e-01\n-1.417400646209716797e+01 -1.811774826049804688e+01 -1.215728759765625000e+00 -1.384075284004211426e-01 -6.204353272914886475e-02 1.324436813592910767e-01 9.795166254043579102e-01\n-1.417728614807128906e+01 -1.811858940124511719e+01 -1.215190410614013672e+00 -1.422036290168762207e-01 -5.581462383270263672e-02 1.125206649303436279e-01 9.818360805511474609e-01\n-1.417791461944580078e+01 -1.811901283264160156e+01 -1.214627623558044434e+00 -1.458467990159988403e-01 -4.928795993328094482e-02 9.236415475606918335e-02 9.837521910667419434e-01\n-1.417585754394531250e+01 -1.811901855468750000e+01 -1.214035630226135254e+00 -1.493225842714309692e-01 -4.255578666925430298e-02 7.212089747190475464e-02 9.852362275123596191e-01\n-1.417107486724853516e+01 -1.811859321594238281e+01 -1.213415503501892090e+00 -1.526171863079071045e-01 -3.571120649576187134e-02 5.193909257650375366e-02 9.862733483314514160e-01\n-1.416352653503417969e+01 -1.811774444580078125e+01 -1.212767362594604492e+00 -1.557197868824005127e-01 -2.884677797555923462e-02 3.196797147393226624e-02 9.868622422218322754e-01\n-1.415317249298095703e+01 -1.811647415161132812e+01 -1.212092280387878418e+00 -1.586212366819381714e-01 -2.205622941255569458e-02 1.235679350793361664e-02 9.870157241821289062e-01\n-1.413997554779052734e+01 -1.811479949951171875e+01 -1.211398839950561523e+00 -1.613143682479858398e-01 -1.543178688734769821e-02 -6.745595484972000122e-03 9.867593050003051758e-01\n-1.412389755249023438e+01 -1.811273384094238281e+01 -1.210687279701232910e+00 -1.637944579124450684e-01 -9.066479280591011047e-03 -2.519115246832370758e-02 9.861310720443725586e-01\n-1.410490608215332031e+01 -1.811030197143554688e+01 -1.209967017173767090e+00 -1.660586595535278320e-01 -3.051096573472023010e-03 -4.283371195197105408e-02 9.851804375648498535e-01\n-1.408296585083007812e+01 -1.810753822326660156e+01 -1.209245562553405762e+00 -1.681053489446640015e-01 2.523428294807672501e-03 -5.952922254800796509e-02 9.839667081832885742e-01\n-1.406326961517333984e+01 -1.810489273071289062e+01 -1.208572983741760254e+00 -1.699351519346237183e-01 7.567468099296092987e-03 -7.513505220413208008e-02 9.825576543807983398e-01\n-1.404578781127929688e+01 -1.810241699218750000e+01 -1.207955241203308105e+00 -1.715495586395263672e-01 1.199221983551979065e-02 -8.951156586408615112e-02 9.810273051261901855e-01\n-1.403049373626708984e+01 -1.810012626647949219e+01 -1.207407236099243164e+00 -1.729509383440017700e-01 1.571034267544746399e-02 -1.025211811065673828e-01 9.794542193412780762e-01\n-1.401740169525146484e+01 -1.809819793701171875e+01 -1.207285165786743164e+00 -1.726683527231216431e-01 1.848724856972694397e-02 -1.140902489423751831e-01 9.781754612922668457e-01\n-1.400649261474609375e+01 -1.809649848937988281e+01 -1.207183837890625000e+00 -1.724350452423095703e-01 2.053248509764671326e-02 -1.242277249693870544e-01 9.769400954246520996e-01\n-1.399778175354003906e+01 -1.809504318237304688e+01 -1.207100749015808105e+00 -1.722651720046997070e-01 2.192180231213569641e-02 -1.329989433288574219e-01 9.757844805717468262e-01\n-1.399128532409667969e+01 -1.809384727478027344e+01 -1.207037329673767090e+00 -1.721656471490859985e-01 2.272762730717658997e-02 -1.404699087142944336e-01 9.747360944747924805e-01\n-1.398701858520507812e+01 -1.809292030334472656e+01 -1.206994652748107910e+00 -1.721377372741699219e-01 2.301858924329280853e-02 -1.467078775167465210e-01 9.738149046897888184e-01\n-1.398499679565429688e+01 -1.809226608276367188e+01 -1.206970214843750000e+00 -1.721778661012649536e-01 2.286203764379024506e-02 -1.517801433801651001e-01 9.730338454246520996e-01\n-1.398523807525634766e+01 -1.809188461303710938e+01 -1.206966519355773926e+00 -1.722793132066726685e-01 2.232120744884014130e-02 -1.557542830705642700e-01 9.724001884460449219e-01\n-1.397761917114257812e+01 -1.809093666076660156e+01 -1.206903100013732910e+00 -1.724327653646469116e-01 2.145808935165405273e-02 -1.586971580982208252e-01 9.719166159629821777e-01\n-1.396215820312500000e+01 -1.808941841125488281e+01 -1.206783413887023926e+00 -1.726271212100982666e-01 2.033315971493721008e-02 -1.606758087873458862e-01 9.715810418128967285e-01\n-1.393886661529541016e+01 -1.808732795715332031e+01 -1.206604003906250000e+00 -1.728504449129104614e-01 1.900516077876091003e-02 -1.617571413516998291e-01 9.713887572288513184e-01\n-1.390776252746582031e+01 -1.808465385437011719e+01 -1.206368327140808105e+00 -1.730903536081314087e-01 1.753239706158638000e-02 -1.620070487260818481e-01 9.713321328163146973e-01\n-1.386885452270507812e+01 -1.808140182495117188e+01 -1.206072926521301270e+00 -1.733345538377761841e-01 1.597235724329948425e-02 -1.614910960197448730e-01 9.714013934135437012e-01\n-1.382213211059570312e+01 -1.807789993286132812e+01 -1.205638408660888672e+00 -1.735712736845016479e-01 1.438270509243011475e-02 -1.602747738361358643e-01 9.715853929519653320e-01\n-1.376761054992675781e+01 -1.807411575317382812e+01 -1.205068349838256836e+00 -1.737896353006362915e-01 1.282062474638223648e-02 -1.584229916334152222e-01 9.718718528747558594e-01\n-1.370531749725341797e+01 -1.806981468200683594e+01 -1.204416513442993164e+00 -1.739798337221145630e-01 1.134419813752174377e-02 -1.559999138116836548e-01 9.722481369972229004e-01\n-1.363526439666748047e+01 -1.806501007080078125e+01 -1.203685283660888672e+00 -1.741333454847335815e-01 1.001187786459922791e-02 -1.530704051256179810e-01 9.727007746696472168e-01\n-1.355746555328369141e+01 -1.805967712402343750e+01 -1.202871084213256836e+00 -1.742431223392486572e-01 8.882367983460426331e-03 -1.496979445219039917e-01 9.732167720794677734e-01\n-1.347193241119384766e+01 -1.805382728576660156e+01 -1.201976299285888672e+00 -1.743036210536956787e-01 8.014990016818046570e-03 -1.459468007087707520e-01 9.737830758094787598e-01\n-1.337867641448974609e+01 -1.804744148254394531e+01 -1.200998544692993164e+00 -1.743105649948120117e-01 7.470415905117988586e-03 -1.418801993131637573e-01 9.743869900703430176e-01\n-1.327770996093750000e+01 -1.804051780700683594e+01 -1.199940204620361328e+00 -1.742613017559051514e-01 7.308905944228172302e-03 -1.375627517700195312e-01 9.750158786773681641e-01\n-1.316905403137207031e+01 -1.803308486938476562e+01 -1.198902606964111328e+00 -1.737243086099624634e-01 7.511528208851814270e-03 -1.330658644437789917e-01 9.757340550422668457e-01\n-1.305272388458251953e+01 -1.802510261535644531e+01 -1.197773456573486328e+00 -1.731890290975570679e-01 8.101944811642169952e-03 -1.284751296043395996e-01 9.764395356178283691e-01\n-1.292867183685302734e+01 -1.801776313781738281e+01 -1.196290254592895508e+00 -1.726641356945037842e-01 9.012149646878242493e-03 -1.238846331834793091e-01 9.771173596382141113e-01\n-1.279695129394531250e+01 -1.801057624816894531e+01 -1.194560527801513672e+00 -1.721579730510711670e-01 1.017384883016347885e-02 -1.193878725171089172e-01 9.777548909187316895e-01\n-1.265762901306152344e+01 -1.800292396545410156e+01 -1.192717313766479492e+00 -1.716792434453964233e-01 1.151873078197240829e-02 -1.150800734758377075e-01 9.783405065536499023e-01\n-1.251072597503662109e+01 -1.799479866027832031e+01 -1.190762877464294434e+00 -1.712377369403839111e-01 1.297887600958347321e-02 -1.110554561018943787e-01 9.788646101951599121e-01\n-1.235627460479736328e+01 -1.798620986938476562e+01 -1.188693761825561523e+00 -1.708422154188156128e-01 1.448602043092250824e-02 -1.074089184403419495e-01 9.793193936347961426e-01\n-1.219427490234375000e+01 -1.797763061523437500e+01 -1.186416029930114746e+00 -1.705030798912048340e-01 1.597205176949501038e-02 -1.042353734374046326e-01 9.796981811523437500e-01\n-1.202464580535888672e+01 -1.797151756286621094e+01 -1.183442354202270508e+00 -1.702296584844589233e-01 1.736923307180404663e-02 -1.016294136643409729e-01 9.799957871437072754e-01\n-1.184753894805908203e+01 -1.796508789062500000e+01 -1.180319786071777344e+00 -1.700322329998016357e-01 1.860933378338813782e-02 -9.968673437833786011e-02 9.802067875862121582e-01\n-1.166297626495361328e+01 -1.795832443237304688e+01 -1.177045822143554688e+00 -1.699207425117492676e-01 1.962437480688095093e-02 -9.850159287452697754e-02 9.803261756896972656e-01\n-1.147096920013427734e+01 -1.795227050781250000e+01 -1.173431396484375000e+00 -1.699048429727554321e-01 2.034642919898033142e-02 -9.816955029964447021e-02 9.803473353385925293e-01\n-1.127146911621093750e+01 -1.795106887817382812e+01 -1.168714523315429688e+00 -1.699938774108886719e-01 2.070740051567554474e-02 -9.878458082675933838e-02 9.802626967430114746e-01\n-1.106458854675292969e+01 -1.794975471496582031e+01 -1.163802504539489746e+00 -1.701969504356384277e-01 2.063925191760063171e-02 -1.004416123032569885e-01 9.800604581832885742e-01\n-1.085038566589355469e+01 -1.795021438598632812e+01 -1.158355712890625000e+00 -1.705220788717269897e-01 2.007384411990642548e-02 -1.032341718673706055e-01 9.797254204750061035e-01\n-1.062896347045898438e+01 -1.795693778991699219e+01 -1.151569843292236328e+00 -1.709766089916229248e-01 1.894273981451988220e-02 -1.072558686137199402e-01 9.792366027832031250e-01\n-1.040914535522460938e+01 -1.796353530883789062e+01 -1.144811987876892090e+00 -1.715665906667709351e-01 1.717771589756011963e-02 -1.125989109277725220e-01 9.785659313201904297e-01\n-1.019149208068847656e+01 -1.797900390625000000e+01 -1.136512398719787598e+00 -1.722959578037261963e-01 1.471004076302051544e-02 -1.193545386195182800e-01 9.776769280433654785e-01\n-9.975522041320800781e+00 -1.799488258361816406e+01 -1.128155469894409180e+00 -1.731677055358886719e-01 1.147142145782709122e-02 -1.276125013828277588e-01 9.765226840972900391e-01\n-9.762405395507812500e+00 -1.802145957946777344e+01 -1.118013858795166016e+00 -1.741821318864822388e-01 7.393093779683113098e-03 -1.374605298042297363e-01 9.750438332557678223e-01\n-9.551672935485839844e+00 -1.805210876464843750e+01 -1.107297301292419434e+00 -1.751508414745330811e-01 2.409156411886215210e-03 -1.489315479993820190e-01 9.732089638710021973e-01\n-9.343825340270996094e+00 -1.809015655517578125e+01 -1.095410108566284180e+00 -1.763336509466171265e-01 -3.357563167810440063e-03 -1.618455797433853149e-01 9.709279537200927734e-01\n-9.140208244323730469e+00 -1.813973617553710938e+01 -1.081787109375000000e+00 -1.778234690427780151e-01 -9.767286479473114014e-03 -1.759740561246871948e-01 9.681510329246520996e-01\n-8.940580368041992188e+00 -1.819780158996582031e+01 -1.067119121551513672e+00 -1.793223172426223755e-01 -1.674799993634223938e-02 -1.910861283540725708e-01 9.649089574813842773e-01\n-8.744725227355957031e+00 -1.826290512084960938e+01 -1.051865220069885254e+00 -1.807363778352737427e-01 -2.420132979750633240e-02 -2.069481462240219116e-01 9.612082242965698242e-01\n-8.550765037536621094e+00 -1.832936477661132812e+01 -1.037139892578125000e+00 -1.821496188640594482e-01 -3.199212625622749329e-02 -2.233315557241439819e-01 9.570375680923461914e-01\n-8.358754158020019531e+00 -1.839709854125976562e+01 -1.021613717079162598e+00 -1.835409551858901978e-01 -4.000447690486907959e-02 -2.400090098381042480e-01 9.524222612380981445e-01\n-8.169313430786132812e+00 -1.846738243103027344e+01 -1.003211617469787598e+00 -1.848921775817871094e-01 -4.812299087643623352e-02 -2.567564845085144043e-01 9.474044442176818848e-01\n-7.983161926269531250e+00 -1.854133224487304688e+01 -9.799682497978210449e-01 -1.861882060766220093e-01 -5.623311549425125122e-02 -2.733535170555114746e-01 9.420455098152160645e-01\n-7.801586627960205078e+00 -1.862045860290527344e+01 -9.491564631462097168e-01 -1.874181628227233887e-01 -6.422104686498641968e-02 -2.895855307579040527e-01 9.364241957664489746e-01\n-7.624364376068115234e+00 -1.870360755920410156e+01 -9.116979837417602539e-01 -1.885739862918853760e-01 -7.197412848472595215e-02 -3.052431046962738037e-01 9.306375980377197266e-01\n-7.451340675354003906e+00 -1.879007339477539062e+01 -8.682433962821960449e-01 -1.896513700485229492e-01 -7.938150316476821899e-02 -3.201229274272918701e-01 9.247984290122985840e-01\n-7.282464981079101562e+00 -1.887909126281738281e+01 -8.187023997306823730e-01 -1.906493306159973145e-01 -8.633489906787872314e-02 -3.340278267860412598e-01 9.190346002578735352e-01\n-7.118041038513183594e+00 -1.897014999389648438e+01 -7.621923685073852539e-01 -1.915690600872039795e-01 -9.272623807191848755e-02 -3.467673957347869873e-01 9.134853482246398926e-01\n-6.958520412445068359e+00 -1.906286621093750000e+01 -6.979882717132568359e-01 -1.924146562814712524e-01 -9.845100343227386475e-02 -3.581552803516387939e-01 9.083000421524047852e-01\n-6.804482936859130859e+00 -1.915691375732421875e+01 -6.254442930221557617e-01 -1.931910961866378784e-01 -1.034047901630401611e-01 -3.680100739002227783e-01 9.036333560943603516e-01\n-6.656631469726562500e+00 -1.925200653076171875e+01 -5.439599752426147461e-01 -1.939039826393127441e-01 -1.074857339262962341e-01 -3.761520385742187500e-01 8.996430635452270508e-01\n-6.515871524810791016e+00 -1.934782600402832031e+01 -4.528369009494781494e-01 -1.945595145225524902e-01 -1.105909198522567749e-01 -3.824028372764587402e-01 8.964843153953552246e-01\n-6.385496616363525391e+00 -1.944392967224121094e+01 -3.488501012325286865e-01 -1.951622217893600464e-01 -1.126182675361633301e-01 -3.865822553634643555e-01 8.943058252334594727e-01\n-6.265444755554199219e+00 -1.953947257995605469e+01 -2.338836640119552612e-01 -1.957140564918518066e-01 -1.134633868932723999e-01 -3.885057568550109863e-01 8.932442069053649902e-01\n-6.157030582427978516e+00 -1.963372993469238281e+01 -1.080126911401748657e-01 -1.962120831012725830e-01 -1.130470186471939087e-01 -3.880454897880554199e-01 8.933877944946289062e-01\n-6.059088706970214844e+00 -1.972624015808105469e+01 2.670959383249282837e-02 -1.966399848461151123e-01 -1.113923639059066772e-01 -3.853203356266021729e-01 8.946801424026489258e-01\n-5.969214439392089844e+00 -1.981676292419433594e+01 1.674096584320068359e-01 -1.969755291938781738e-01 -1.085469126701354980e-01 -3.805048465728759766e-01 8.970141410827636719e-01\n-5.885583877563476562e+00 -1.990472602844238281e+01 3.124322295188903809e-01 -1.971935629844665527e-01 -1.045555323362350464e-01 -3.737675249576568604e-01 9.002670049667358398e-01\n-5.803256034851074219e+00 -1.999086380004882812e+01 4.581799209117889404e-01 -1.972658038139343262e-01 -9.946345537900924683e-02 -3.652730286121368408e-01 9.043057560920715332e-01\n-5.719892024993896484e+00 -2.007541465759277344e+01 6.031121611595153809e-01 -1.971632838249206543e-01 -9.331437945365905762e-02 -3.551842272281646729e-01 9.089902639389038086e-01\n-5.633288860321044922e+00 -2.015843200683593750e+01 7.457769513130187988e-01 -1.968562752008438110e-01 -8.615399897098541260e-02 -3.436643779277801514e-01 9.141771793365478516e-01\n-5.540076732635498047e+00 -2.023985862731933594e+01 8.839520215988159180e-01 -1.963153928518295288e-01 -7.802811264991760254e-02 -3.308785259723663330e-01 9.197234511375427246e-01\n-5.434156894683837891e+00 -2.031917953491210938e+01 1.012612223625183105e+00 -1.955126374959945679e-01 -6.898463517427444458e-02 -3.169950842857360840e-01 9.254890680313110352e-01\n-5.314202308654785156e+00 -2.039573287963867188e+01 1.128260493278503418e+00 -1.944207549095153809e-01 -5.907347053289413452e-02 -3.021857738494873047e-01 9.313402175903320312e-01\n-5.178050518035888672e+00 -2.046792030334472656e+01 1.225153803825378418e+00 -1.930157095193862915e-01 -4.834614321589469910e-02 -2.866281270980834961e-01 9.371509552001953125e-01\n-5.027757644653320312e+00 -2.053473663330078125e+01 1.300881981849670410e+00 -1.893039792776107788e-01 -3.742266073822975159e-02 -2.704261243343353271e-01 9.432036876678466797e-01\n-4.867827892303466797e+00 -2.059556579589843750e+01 1.357622623443603516e+00 -1.852363497018814087e-01 -2.571909502148628235e-02 -2.538959681987762451e-01 9.489797949790954590e-01\n-4.701978206634521484e+00 -2.065056037902832031e+01 1.398209810256958008e+00 -1.813626885414123535e-01 -1.315394416451454163e-02 -2.372401058673858643e-01 9.542806744575500488e-01\n-4.532223224639892578e+00 -2.069898414611816406e+01 1.422392487525939941e+00 -1.777279376983642578e-01 1.920461654663085938e-04 -2.206349968910217285e-01 9.590271115303039551e-01\n-4.361598491668701172e+00 -2.074292373657226562e+01 1.436777949333190918e+00 -1.743630915880203247e-01 1.422951556742191315e-02 -2.042547166347503662e-01 9.631588459014892578e-01\n-4.190948486328125000e+00 -2.078312873840332031e+01 1.443652868270874023e+00 -1.712842732667922974e-01 2.886412292718887329e-02 -1.882722675800323486e-01 9.666343331336975098e-01\n-4.020798206329345703e+00 -2.082008171081542969e+01 1.444533705711364746e+00 -1.684927195310592651e-01 4.399876669049263000e-02 -1.728609502315521240e-01 9.694294333457946777e-01\n-3.851472377777099609e+00 -2.085371017456054688e+01 1.439882755279541016e+00 -1.659740358591079712e-01 5.953872203826904297e-02 -1.581941694021224976e-01 9.715360999107360840e-01\n-3.683309555053710938e+00 -2.088486862182617188e+01 1.432135581970214844e+00 -1.636987477540969849e-01 7.539305090904235840e-02 -1.444470286369323730e-01 9.729613065719604492e-01\n-3.516623497009277344e+00 -2.091453170776367188e+01 1.422302246093750000e+00 -1.584810763597488403e-01 9.103906154632568359e-02 -1.320538371801376343e-01 9.742470979690551758e-01\n-3.351352214813232422e+00 -2.094268989562988281e+01 1.411395192146301270e+00 -1.529230773448944092e-01 1.067758351564407349e-01 -1.208692938089370728e-01 9.749891757965087891e-01\n-3.186737537384033203e+00 -2.096947669982910156e+01 1.399062514305114746e+00 -1.470785140991210938e-01 1.224749907851219177e-01 -1.108664870262145996e-01 9.752315282821655273e-01\n-3.022862434387207031e+00 -2.099501991271972656e+01 1.384777188301086426e+00 -1.410022526979446411e-01 1.380095779895782471e-01 -1.020165681838989258e-01 9.750201702117919922e-01\n-2.859816312789916992e+00 -2.101975059509277344e+01 1.368644952774047852e+00 -1.347483843564987183e-01 1.532539427280426025e-01 -9.429048746824264526e-02 9.744052290916442871e-01\n-2.697672605514526367e+00 -2.104387092590332031e+01 1.350438237190246582e+00 -1.283714473247528076e-01 1.680841445922851562e-01 -8.765873312950134277e-02 9.734395146369934082e-01\n-2.536515951156616211e+00 -2.106760787963867188e+01 1.329924345016479492e+00 -1.219269409775733948e-01 1.823779642581939697e-01 -8.209069073200225830e-02 9.721795916557312012e-01\n-2.376441240310668945e+00 -2.109122467041015625e+01 1.306878685951232910e+00 -1.154689937829971313e-01 1.960151493549346924e-01 -7.755572348833084106e-02 9.706854224205017090e-01\n-2.217573881149291992e+00 -2.111502838134765625e+01 1.280995488166809082e+00 -1.090524122118949890e-01 2.088771462440490723e-01 -7.402298599481582642e-02 9.690194129943847656e-01\n-2.060139656066894531e+00 -2.113944244384765625e+01 1.251676559448242188e+00 -1.027315035462379456e-01 2.208474874496459961e-01 -7.146216928958892822e-02 9.672465920448303223e-01\n-1.904189229011535645e+00 -2.116470146179199219e+01 1.219267606735229492e+00 -9.656047075986862183e-02 2.318109124898910522e-01 -6.984190642833709717e-02 9.654335379600524902e-01\n-1.749730229377746582e+00 -2.119121551513671875e+01 1.184332847595214844e+00 -9.059253334999084473e-02 2.416539192199707031e-01 -6.913200020790100098e-02 9.636478424072265625e-01\n-1.596755623817443848e+00 -2.121939849853515625e+01 1.147445678710937500e+00 -8.488062024116516113e-02 2.502637505531311035e-01 -6.930173933506011963e-02 9.619567394256591797e-01\n-1.445254445075988770e+00 -2.124968147277832031e+01 1.109163761138916016e+00 -7.947713881731033325e-02 2.575280368328094482e-01 -7.032090425491333008e-02 9.604257345199584961e-01\n-1.295220732688903809e+00 -2.128248977661132812e+01 1.070039033889770508e+00 -7.443322986364364624e-02 2.633346617221832275e-01 -7.215952128171920776e-02 9.591181874275207520e-01\n-1.146725416183471680e+00 -2.131830596923828125e+01 1.030656099319458008e+00 -6.996620446443557739e-02 2.663185894489288330e-01 -7.495104521512985229e-02 9.584161043167114258e-01\n-9.999613165855407715e-01 -2.135830497741699219e+01 9.917449951171875000e-01 -6.614603102207183838e-02 2.662808001041412354e-01 -7.866744697093963623e-02 9.584000706672668457e-01\n-8.547224998474121094e-01 -2.140241241455078125e+01 9.539013504981994629e-01 -6.259322166442871094e-02 2.662970125675201416e-01 -8.287088572978973389e-02 9.582799673080444336e-01\n-7.111460566520690918e-01 -2.145109748840332031e+01 9.177319407463073730e-01 -5.932302400469779968e-02 2.663649320602416992e-01 -8.752603083848953247e-02 9.580551385879516602e-01\n-5.694254040718078613e-01 -2.150481796264648438e+01 8.838702440261840820e-01 -5.633988976478576660e-02 2.664817869663238525e-01 -9.259188920259475708e-02 9.577264785766601562e-01\n-4.298233687877655029e-01 -2.156326675415039062e+01 8.526470661163330078e-01 -5.446594208478927612e-02 2.611390650272369385e-01 -9.870256483554840088e-02 9.586958885192871094e-01\n-2.920832037925720215e-01 -2.162565803527832031e+01 8.238085508346557617e-01 -5.321475118398666382e-02 2.537637054920196533e-01 -1.053738519549369812e-01 9.600356817245483398e-01\n-1.560231447219848633e-01 -2.169121932983398438e+01 7.971881031990051270e-01 -5.256302654743194580e-02 2.444927394390106201e-01 -1.125296354293823242e-01 9.616639018058776855e-01\n-2.139944955706596375e-02 -2.175920295715332031e+01 7.726220488548278809e-01 -5.248617380857467651e-02 2.334626466035842896e-01 -1.200938150286674500e-01 9.634925127029418945e-01\n1.120875328779220581e-01 -2.182886123657226562e+01 7.500683665275573730e-01 -5.295992642641067505e-02 2.208105325698852539e-01 -1.279888451099395752e-01 9.654309749603271484e-01\n2.449163943529129028e-01 -2.189912986755371094e+01 7.292101979255676270e-01 -5.395935475826263428e-02 2.066756784915924072e-01 -1.361361443996429443e-01 9.673885107040405273e-01\n3.775641918182373047e-01 -2.196906280517578125e+01 7.098785042762756348e-01 -5.545983836054801941e-02 1.911994516849517822e-01 -1.444572955369949341e-01 9.692776799201965332e-01\n5.106136798858642578e-01 -2.203748512268066406e+01 6.919341683387756348e-01 -5.743588507175445557e-02 1.745266765356063843e-01 -1.528737545013427734e-01 9.710155129432678223e-01\n6.447994709014892578e-01 -2.210284042358398438e+01 6.752325296401977539e-01 -5.986256152391433716e-02 1.568054258823394775e-01 -1.613068580627441406e-01 9.725269079208374023e-01\n7.830833792686462402e-01 -2.215785598754882812e+01 6.589977741241455078e-01 -6.271472573280334473e-02 1.381875276565551758e-01 -1.696794927120208740e-01 9.737452864646911621e-01\n9.247810244560241699e-01 -2.220174217224121094e+01 6.425030231475830078e-01 -6.596759706735610962e-02 1.188281029462814331e-01 -1.779153048992156982e-01 9.746149182319641113e-01\n1.067692518234252930e+00 -2.223961830139160156e+01 6.257092356681823730e-01 -6.959612667560577393e-02 9.888577461242675781e-02 -1.859395205974578857e-01 9.750919938087463379e-01\n1.211504101753234863e+00 -2.227413940429687500e+01 6.087017655372619629e-01 -7.357654720544815063e-02 7.852183282375335693e-02 -1.936799436807632446e-01 9.751455783843994141e-01\n1.356289744377136230e+00 -2.230418968200683594e+01 5.912957787513732910e-01 -7.788492739200592041e-02 5.789966508746147156e-02 -2.010660767555236816e-01 9.747585058212280273e-01\n1.501374959945678711e+00 -2.233302116394042969e+01 5.737719535827636719e-01 -8.249861747026443481e-02 3.718444705009460449e-02 -2.080305963754653931e-01 9.739274382591247559e-01\n1.646695852279663086e+00 -2.236085891723632812e+01 5.561267137527465820e-01 -8.739582449197769165e-02 1.654189079999923706e-02 -2.145096361637115479e-01 9.726633429527282715e-01\n1.792532801628112793e+00 -2.238619613647460938e+01 5.381982326507568359e-01 -9.255601465702056885e-02 -3.862014040350914001e-03 -2.204417586326599121e-01 9.709911942481994629e-01\n1.938458919525146484e+00 -2.241155624389648438e+01 5.202868580818176270e-01 -9.795944392681121826e-02 -2.386232092976570129e-02 -2.257693856954574585e-01 9.689492583274841309e-01\n2.084487915039062500e+00 -2.243694686889648438e+01 5.024065971374511719e-01 -1.035886555910110474e-01 -4.329508915543556213e-02 -2.304384112358093262e-01 9.665883779525756836e-01\n2.230934143066406250e+00 -2.246038055419921875e+01 4.842815995216369629e-01 -1.094269901514053345e-01 -6.199895590543746948e-02 -2.343970835208892822e-01 9.639708995819091797e-01\n2.377528190612792969e+00 -2.248369598388671875e+01 4.661981165409088135e-01 -1.154559776186943054e-01 -7.984423637390136719e-02 -2.376135885715484619e-01 9.611631035804748535e-01\n2.524234294891357422e+00 -2.250704956054687500e+01 4.481854140758514404e-01 -1.216437593102455139e-01 -9.682249277830123901e-02 -2.401245534420013428e-01 9.582110643386840820e-01\n2.671039104461669922e+00 -2.253044891357421875e+01 4.302423000335693359e-01 -1.279535591602325439e-01 -1.129571571946144104e-01 -2.419821918010711670e-01 9.551507830619812012e-01\n2.818022966384887695e+00 -2.255319786071777344e+01 4.122344851493835449e-01 -1.343493461608886719e-01 -1.282716542482376099e-01 -2.432388663291931152e-01 9.520144462585449219e-01\n2.965167999267578125e+00 -2.257532119750976562e+01 3.941674828529357910e-01 -1.407942622900009155e-01 -1.427913308143615723e-01 -2.439457178115844727e-01 9.488298296928405762e-01\n3.112375974655151367e+00 -2.259748077392578125e+01 3.761584460735321045e-01 -1.472518146038055420e-01 -1.565414667129516602e-01 -2.441536337137222290e-01 9.456219077110290527e-01\n3.259636163711547852e+00 -2.261967277526855469e+01 3.582000732421875000e-01 -1.536853909492492676e-01 -1.695484369993209839e-01 -2.439132332801818848e-01 9.424121379852294922e-01\n3.406939029693603516e+00 -2.264188385009765625e+01 3.402874767780303955e-01 -1.600580364465713501e-01 -1.818387359380722046e-01 -2.432737946510314941e-01 9.392198324203491211e-01\n3.554276466369628906e+00 -2.266412544250488281e+01 3.224102854728698730e-01 -1.663337945938110352e-01 -1.934393793344497681e-01 -2.422850728034973145e-01 9.360620379447937012e-01\n3.701730251312255859e+00 -2.268562889099121094e+01 3.043792545795440674e-01 -1.724757254123687744e-01 -2.043778002262115479e-01 -2.409955710172653198e-01 9.329538941383361816e-01\n3.849213838577270508e+00 -2.270705032348632812e+01 2.863415479660034180e-01 -1.784478276968002319e-01 -2.146816551685333252e-01 -2.394533157348632812e-01 9.299087524414062500e-01\n3.996708631515502930e+00 -2.272849464416503906e+01 2.683117687702178955e-01 -1.842135637998580933e-01 -2.243779599666595459e-01 -2.377061247825622559e-01 9.269389510154724121e-01\n4.144206523895263672e+00 -2.274995613098144531e+01 2.502771019935607910e-01 -1.897367388010025024e-01 -2.334952950477600098e-01 -2.358017265796661377e-01 9.240548610687255859e-01\n4.291700839996337891e+00 -2.277143096923828125e+01 2.322283834218978882e-01 -1.949817240238189697e-01 -2.420607805252075195e-01 -2.337866723537445068e-01 9.212667942047119141e-01\n4.439185619354248047e+00 -2.279292488098144531e+01 2.141534388065338135e-01 -1.999120414257049561e-01 -2.501026988029479980e-01 -2.317075878381729126e-01 9.185833930969238281e-01\n4.586654663085937500e+00 -2.281444358825683594e+01 1.960394233465194702e-01 -2.044924050569534302e-01 -2.576487660408020020e-01 -2.296108454465866089e-01 9.160124063491821289e-01\n4.734113693237304688e+00 -2.283577537536621094e+01 1.777484118938446045e-01 -2.086867988109588623e-01 -2.647267580032348633e-01 -2.275423109531402588e-01 9.135611653327941895e-01\n4.881546497344970703e+00 -2.285709953308105469e+01 1.593688875436782837e-01 -2.124596685171127319e-01 -2.713642418384552002e-01 -2.255471348762512207e-01 9.112358093261718750e-01\n5.028945446014404297e+00 -2.287844276428222656e+01 1.409149169921875000e-01 -2.157747149467468262e-01 -2.775894701480865479e-01 -2.236704975366592407e-01 9.090417027473449707e-01\n5.176304817199707031e+00 -2.289980506896972656e+01 1.223730444908142090e-01 -2.185968756675720215e-01 -2.834294438362121582e-01 -2.219573408365249634e-01 9.069829583168029785e-01\n5.323926448822021484e+00 -2.292157745361328125e+01 1.032061725854873657e-01 -2.183007597923278809e-01 -2.895419895648956299e-01 -2.196118384599685669e-01 9.056935310363769531e-01\n5.471455097198486328e+00 -2.294329071044921875e+01 8.406127989292144775e-02 -2.180402576923370361e-01 -2.951793372631072998e-01 -2.176025211811065674e-01 9.044205546379089355e-01\n5.618889808654785156e+00 -2.296496009826660156e+01 6.493835151195526123e-02 -2.178272604942321777e-01 -3.003686070442199707e-01 -2.159234732389450073e-01 9.031649827957153320e-01\n5.766230106353759766e+00 -2.298657608032226562e+01 4.583679139614105225e-02 -2.176707684993743896e-01 -3.051361739635467529e-01 -2.145657837390899658e-01 9.019272923469543457e-01\n5.916031837463378906e+00 -2.300862312316894531e+01 2.632995508611202240e-02 -2.175770252943038940e-01 -3.095074892044067383e-01 -2.135170549154281616e-01 9.007084369659423828e-01\n6.068310260772705078e+00 -2.303104972839355469e+01 6.466064136475324631e-03 -2.175496369600296021e-01 -3.135075569152832031e-01 -2.127615511417388916e-01 8.995097279548645020e-01\n6.223081111907958984e+00 -2.305381202697753906e+01 -1.371154747903347015e-02 -2.175899446010589600e-01 -3.171609640121459961e-01 -2.122813165187835693e-01 8.983318805694580078e-01\n6.380347251892089844e+00 -2.307691383361816406e+01 -3.420227020978927612e-02 -2.176974266767501831e-01 -3.204920291900634766e-01 -2.120563983917236328e-01 8.971759676933288574e-01\n6.540111064910888672e+00 -2.310035514831542969e+01 -5.500915274024009705e-02 -2.178691923618316650e-01 -3.235246837139129639e-01 -2.120636552572250366e-01 8.960434198379516602e-01\n6.702379703521728516e+00 -2.312413978576660156e+01 -7.613097876310348511e-02 -2.181010395288467407e-01 -3.262832164764404297e-01 -2.122789770364761353e-01 8.949350714683532715e-01\n6.867156982421875000e+00 -2.314827537536621094e+01 -9.756835550069808960e-02 -2.183872163295745850e-01 -3.287917077541351318e-01 -2.126764357089996338e-01 8.938522338867187500e-01\n7.034446716308593750e+00 -2.317276382446289062e+01 -1.193243414163589478e-01 -2.187206745147705078e-01 -3.310744464397430420e-01 -2.132287174463272095e-01 8.927958011627197266e-01\n7.204215526580810547e+00 -2.319782638549804688e+01 -1.414691060781478882e-01 -2.190932780504226685e-01 -3.331558704376220703e-01 -2.139072418212890625e-01 8.917673230171203613e-01\n7.376455307006835938e+00 -2.322353553771972656e+01 -1.640246510505676270e-01 -2.194961309432983398e-01 -3.350614905357360840e-01 -2.146829664707183838e-01 8.907672762870788574e-01\n7.558326244354248047e+00 -2.325066757202148438e+01 -1.878265291452407837e-01 -2.199192792177200317e-01 -3.368162810802459717e-01 -2.155251652002334595e-01 8.897972106933593750e-01\n7.749835491180419922e+00 -2.327924728393554688e+01 -2.128747552633285522e-01 -2.203524261713027954e-01 -3.384456932544708252e-01 -2.164032459259033203e-01 8.888582587242126465e-01\n7.950988769531250000e+00 -2.330927276611328125e+01 -2.391711324453353882e-01 -2.207848131656646729e-01 -3.399763405323028564e-01 -2.172861248254776001e-01 8.879509568214416504e-01\n8.161792755126953125e+00 -2.334073638916015625e+01 -2.667163014411926270e-01 -2.212050259113311768e-01 -3.414342701435089111e-01 -2.181417942047119141e-01 8.870766758918762207e-01\n8.382266998291015625e+00 -2.337367630004882812e+01 -2.955285608768463135e-01 -2.215003967285156250e-01 -3.428717851638793945e-01 -2.188988626003265381e-01 8.862617015838623047e-01\n8.612287521362304688e+00 -2.340854835510253906e+01 -3.256640434265136719e-01 -2.219618260860443115e-01 -3.442403376102447510e-01 -2.196419537067413330e-01 8.854314684867858887e-01\n8.851962089538574219e+00 -2.344560432434082031e+01 -3.571130335330963135e-01 -2.221293747425079346e-01 -3.441322743892669678e-01 -2.200729548931121826e-01 8.853244185447692871e-01\n9.101294517517089844e+00 -2.348416900634765625e+01 -3.898266553878784180e-01 -2.222552895545959473e-01 -3.440509736537933350e-01 -2.203968763351440430e-01 8.852438330650329590e-01\n9.360280036926269531e+00 -2.352424240112304688e+01 -4.238024950027465820e-01 -2.223452627658843994e-01 -3.439927995204925537e-01 -2.206283807754516602e-01 8.851861357688903809e-01\n9.628916740417480469e+00 -2.356582069396972656e+01 -4.590429663658142090e-01 -2.224056422710418701e-01 -3.439537882804870605e-01 -2.207837700843811035e-01 8.851474523544311523e-01\n9.907197952270507812e+00 -2.360889053344726562e+01 -4.955468773841857910e-01 -2.224431037902832031e-01 -3.439295589923858643e-01 -2.208801507949829102e-01 8.851233720779418945e-01\n1.019474601745605469e+01 -2.365554618835449219e+01 -5.336694121360778809e-01 -2.224644124507904053e-01 -3.439157605171203613e-01 -2.209350764751434326e-01 8.851096630096435547e-01\n1.048197364807128906e+01 -2.370218658447265625e+01 -5.717553496360778809e-01 -2.224770784378051758e-01 -3.439075946807861328e-01 -2.209676057100296021e-01 8.851014971733093262e-01\n1.076888275146484375e+01 -2.374876976013183594e+01 -6.097985506057739258e-01 -2.224884331226348877e-01 -3.439002335071563721e-01 -2.209968268871307373e-01 8.850942254066467285e-01\n1.105547142028808594e+01 -2.379530143737792969e+01 -6.477990746498107910e-01 -2.225062996149063110e-01 -3.438886702060699463e-01 -2.210428118705749512e-01 8.850827813148498535e-01\n1.134161949157714844e+01 -2.384237670898437500e+01 -6.858483552932739258e-01 -2.225385308265686035e-01 -3.438678085803985596e-01 -2.211257815361022949e-01 8.850619792938232422e-01\n1.162697315216064453e+01 -2.389184570312500000e+01 -7.242211699485778809e-01 -2.225930988788604736e-01 -3.438324630260467529e-01 -2.212662696838378906e-01 8.850269317626953125e-01\n1.191199398040771484e+01 -2.394124984741210938e+01 -7.625512480735778809e-01 -2.226775139570236206e-01 -3.437778353691101074e-01 -2.214835584163665771e-01 8.849725723266601562e-01\n1.219667434692382812e+01 -2.399057579040527344e+01 -8.008385896682739258e-01 -2.227995544672012329e-01 -3.436987400054931641e-01 -2.217977046966552734e-01 8.848938941955566406e-01\n1.248101043701171875e+01 -2.403982925415039062e+01 -8.390832543373107910e-01 -2.229660153388977051e-01 -3.435907959938049316e-01 -2.222263514995574951e-01 8.847863674163818359e-01\n1.276442241668701172e+01 -2.409189414978027344e+01 -8.776794075965881348e-01 -2.231833934783935547e-01 -3.434496223926544189e-01 -2.227861881256103516e-01 8.846454620361328125e-01\n1.304715538024902344e+01 -2.414550781250000000e+01 -9.164562821388244629e-01 -2.234573364257812500e-01 -3.432714343070983887e-01 -2.234919369220733643e-01 8.844674825668334961e-01\n1.332954025268554688e+01 -2.419902801513671875e+01 -9.551879763603210449e-01 -2.237923741340637207e-01 -3.430531024932861328e-01 -2.243553698062896729e-01 8.842488527297973633e-01\n1.361156749725341797e+01 -2.425247001647949219e+01 -9.938769340515136719e-01 -2.241918444633483887e-01 -3.427921831607818604e-01 -2.253852337598800659e-01 8.839869499206542969e-01\n1.389249801635742188e+01 -2.430917930603027344e+01 -1.032952904701232910e+00 -2.246578484773635864e-01 -3.424869775772094727e-01 -2.265873253345489502e-01 8.836795687675476074e-01\n1.417225646972656250e+01 -2.436950111389160156e+01 -1.072458505630493164e+00 -2.251906096935272217e-01 -3.421368896961212158e-01 -2.279623448848724365e-01 8.833258748054504395e-01\n1.445251178741455078e+01 -2.443052101135253906e+01 -1.112601280212402344e+00 -2.207838743925094604e-01 -3.398961424827575684e-01 -2.274083197116851807e-01 8.854436874389648438e-01\n1.473253631591796875e+01 -2.449156761169433594e+01 -1.152830839157104492e+00 -2.156427800655364990e-01 -3.374349474906921387e-01 -2.267166227102279663e-01 8.878262639045715332e-01\n1.501059627532958984e+01 -2.455951690673828125e+01 -1.194051504135131836e+00 -2.098293602466583252e-01 -3.348003625869750977e-01 -2.259006351232528687e-01 8.904207348823547363e-01\n1.528816604614257812e+01 -2.462841796875000000e+01 -1.235473632812500000e+00 -2.034060060977935791e-01 -3.320398628711700439e-01 -2.249738425016403198e-01 8.931754231452941895e-01\n1.556547927856445312e+01 -2.469728469848632812e+01 -1.276966571807861328e+00 -1.964354664087295532e-01 -3.292009234428405762e-01 -2.239504456520080566e-01 8.960390686988830566e-01\n1.584055137634277344e+01 -2.477307510375976562e+01 -1.319479942321777344e+00 -1.889812648296356201e-01 -3.263326883316040039e-01 -2.228447943925857544e-01 8.989622592926025391e-01\n1.611485099792480469e+01 -2.485056114196777344e+01 -1.362290024757385254e+00 -1.811068356037139893e-01 -3.234843015670776367e-01 -2.216712534427642822e-01 9.018979668617248535e-01\n1.638828277587890625e+01 -2.492979431152343750e+01 -1.405413746833801270e+00 -1.728771626949310303e-01 -3.207059502601623535e-01 -2.204457521438598633e-01 9.048009514808654785e-01\n1.665892982482910156e+01 -2.501667404174804688e+01 -1.449704527854919434e+00 -1.643574535846710205e-01 -3.180485963821411133e-01 -2.191843688488006592e-01 9.076287150382995605e-01\n1.692925453186035156e+01 -2.510351562500000000e+01 -1.494035601615905762e+00 -1.556134819984436035e-01 -3.155647218227386475e-01 -2.179037779569625854e-01 9.103413224220275879e-01\n1.719555282592773438e+01 -2.520039939880371094e+01 -1.539997577667236328e+00 -1.467118263244628906e-01 -3.133070170879364014e-01 -2.166214287281036377e-01 9.129017591476440430e-01\n1.746067047119140625e+01 -2.529924201965332031e+01 -1.586348891258239746e+00 -1.377195268869400024e-01 -3.113292455673217773e-01 -2.153556346893310547e-01 9.152755737304687500e-01\n1.772199058532714844e+01 -2.540629768371582031e+01 -1.634212613105773926e+00 -1.287038028240203857e-01 -3.096866011619567871e-01 -2.141248285770416260e-01 9.174311757087707520e-01\n1.797966957092285156e+01 -2.552020454406738281e+01 -1.683673024177551270e+00 -1.197323352098464966e-01 -3.084343373775482178e-01 -2.129480689764022827e-01 9.193396568298339844e-01\n1.823372077941894531e+01 -2.564036560058593750e+01 -1.735097646713256836e+00 -1.108731925487518311e-01 -3.076283633708953857e-01 -2.118457108736038208e-01 9.209740757942199707e-01\n1.848494148254394531e+01 -2.576435089111328125e+01 -1.789418935775756836e+00 -1.021941900253295898e-01 -3.073254525661468506e-01 -2.108376473188400269e-01 9.223095774650573730e-01\n1.873287773132324219e+01 -2.589137077331542969e+01 -1.849500656127929688e+00 -9.376326948404312134e-02 -3.075828254222869873e-01 -2.099442481994628906e-01 9.233225584030151367e-01\n1.897032737731933594e+01 -2.602990150451660156e+01 -1.922786831855773926e+00 -8.564832061529159546e-02 -3.084577918052673340e-01 -2.091858983039855957e-01 9.239910244941711426e-01\n1.918661117553710938e+01 -2.619185066223144531e+01 -2.010993719100952148e+00 -7.791706919670104980e-02 -3.100074231624603271e-01 -2.085837125778198242e-01 9.242928028106689453e-01\n1.939688873291015625e+01 -2.636192321777343750e+01 -2.097397327423095703e+00 -7.063672691583633423e-02 -3.122891485691070557e-01 -2.081581056118011475e-01 9.242056608200073242e-01\n1.960333633422851562e+01 -2.653208923339843750e+01 -2.191108465194702148e+00 -6.386113911867141724e-02 -3.153225779533386230e-01 -2.079208791255950928e-01 9.237220287322998047e-01\n1.980067253112792969e+01 -2.670052719116210938e+01 -2.304293155670166016e+00 -5.759227648377418518e-02 -3.189783096313476562e-01 -2.078484743833541870e-01 9.228949546813964844e-01\n1.997805976867675781e+01 -2.686252403259277344e+01 -2.452465772628784180e+00 -5.181930959224700928e-02 -3.230887651443481445e-01 -2.079097777605056763e-01 9.217927455902099609e-01\n2.010663986206054688e+01 -2.700180625915527344e+01 -2.658095598220825195e+00 -4.653124511241912842e-02 -3.274874389171600342e-01 -2.080729454755783081e-01 9.204848408699035645e-01\n2.013336563110351562e+01 -2.708231353759765625e+01 -2.923445940017700195e+00 -4.171708226203918457e-02 -3.320077657699584961e-01 -2.083068042993545532e-01 9.190422892570495605e-01\n2.006044387817382812e+01 -2.710072135925292969e+01 -3.192740440368652344e+00 -3.736594691872596741e-02 -3.364843428134918213e-01 -2.085808515548706055e-01 9.175381064414978027e-01\n1.991547203063964844e+01 -2.707538032531738281e+01 -3.430675029754638672e+00 -3.346715122461318970e-02 -3.407529592514038086e-01 -2.088648378849029541e-01 9.160473942756652832e-01\n1.971638298034667969e+01 -2.702067375183105469e+01 -3.618968486785888672e+00 -3.000989928841590881e-02 -3.446498513221740723e-01 -2.091291546821594238e-01 9.146478772163391113e-01\n1.947625732421875000e+01 -2.694724464416503906e+01 -3.741216897964477539e+00 -2.698357030749320984e-02 -3.480124771595001221e-01 -2.093446254730224609e-01 9.134188890457153320e-01\n1.921686553955078125e+01 -2.686842155456542969e+01 -3.807093381881713867e+00 -2.437749505043029785e-02 -3.506780266761779785e-01 -2.094826698303222656e-01 9.124405384063720703e-01\n1.895020866394042969e+01 -2.679267120361328125e+01 -3.836425781250000000e+00 -2.218068391084671021e-02 -3.524843454360961914e-01 -2.095136344432830811e-01 9.117931723594665527e-01\n1.867999649047851562e+01 -2.672515487670898438e+01 -3.840672492980957031e+00 -2.038262039422988892e-02 -3.532688617706298828e-01 -2.094088792800903320e-01 9.115555882453918457e-01\n1.840722465515136719e+01 -2.667154693603515625e+01 -3.829312562942504883e+00 -1.897224783897399902e-02 -3.528676629066467285e-01 -2.091383486986160278e-01 9.118034839630126953e-01\n1.813268661499023438e+01 -2.663323211669921875e+01 -3.809109926223754883e+00 -1.793826371431350708e-02 -3.511150181293487549e-01 -2.086706757545471191e-01 9.126078486442565918e-01\n1.785753250122070312e+01 -2.660956573486328125e+01 -3.780355215072631836e+00 -1.726895570755004883e-02 -3.478419482707977295e-01 -2.079730629920959473e-01 9.140322804450988770e-01\n1.758689117431640625e+01 -2.659740638732910156e+01 -3.744694709777832031e+00 -1.695244759321212769e-02 -3.428765535354614258e-01 -2.070108056068420410e-01 9.161303043365478516e-01\n1.732136154174804688e+01 -2.659372901916503906e+01 -3.702745199203491211e+00 -1.697567105293273926e-02 -3.360415697097778320e-01 -2.057455033063888550e-01 9.189432263374328613e-01\n1.706144523620605469e+01 -2.659532737731933594e+01 -3.654067277908325195e+00 -1.732514798641204834e-02 -3.271546661853790283e-01 -2.041360139846801758e-01 9.224956631660461426e-01\n1.680853652954101562e+01 -2.660082435607910156e+01 -3.593966007232666016e+00 -1.798589155077934265e-02 -3.160273730754852295e-01 -2.021358907222747803e-01 9.267923831939697266e-01\n1.656593704223632812e+01 -2.660934448242187500e+01 -3.513918399810791016e+00 -1.894154399633407593e-02 -3.024637699127197266e-01 -1.996945291757583618e-01 9.318148493766784668e-01\n1.633611869812011719e+01 -2.661814308166503906e+01 -3.412678241729736328e+00 -2.016894891858100891e-02 -2.863315939903259277e-01 -1.967687010765075684e-01 9.374909400939941406e-01\n1.611628913879394531e+01 -2.662369537353515625e+01 -3.300189018249511719e+00 -2.162275835871696472e-02 -2.677738666534423828e-01 -1.933650076389312744e-01 9.436310529708862305e-01\n1.589969062805175781e+01 -2.662261199951171875e+01 -3.191188812255859375e+00 -2.325204573571681976e-02 -2.470081895589828491e-01 -1.895039975643157959e-01 9.500181674957275391e-01\n1.568132400512695312e+01 -2.661123466491699219e+01 -3.097897768020629883e+00 -2.500555105507373810e-02 -2.242593169212341309e-01 -1.852087676525115967e-01 9.564414024353027344e-01\n1.545940303802490234e+01 -2.658679199218750000e+01 -3.031638145446777344e+00 -2.683191560208797455e-02 -1.997609585523605347e-01 -1.805061548948287964e-01 9.627009630203247070e-01\n1.523797893524169922e+01 -2.655461883544921875e+01 -2.986737012863159180e+00 -2.867994084954261780e-02 -1.737575680017471313e-01 -1.754268705844879150e-01 9.686130285263061523e-01\n1.501963710784912109e+01 -2.652018547058105469e+01 -2.953201770782470703e+00 -3.049903176724910736e-02 -1.465035229921340942e-01 -1.700080633163452148e-01 9.740142822265625000e-01\n1.480522632598876953e+01 -2.648631858825683594e+01 -2.924599647521972656e+00 -3.223899379372596741e-02 -1.182626336812973022e-01 -1.642913967370986938e-01 9.787660837173461914e-01\n1.459505081176757812e+01 -2.645399284362792969e+01 -2.897641420364379883e+00 -3.385071828961372375e-02 -8.930751681327819824e-02 -1.583246886730194092e-01 9.827570915222167969e-01\n1.438920879364013672e+01 -2.642324638366699219e+01 -2.871393918991088867e+00 -3.528673201799392700e-02 -5.991753563284873962e-02 -1.521615684032440186e-01 9.859064817428588867e-01\n1.418772411346435547e+01 -2.639378929138183594e+01 -2.845865488052368164e+00 -3.650032728910446167e-02 -3.037654981017112732e-02 -1.458611339330673218e-01 9.881647229194641113e-01\n1.399059867858886719e+01 -2.636548233032226562e+01 -2.821068048477172852e+00 -3.744756802916526794e-02 -9.714961051940917969e-04 -1.394872367382049561e-01 9.895150661468505859e-01\n1.379781436920166016e+01 -2.633822631835937500e+01 -2.797016620635986328e+00 -3.808545321226119995e-02 2.801096439361572266e-02 -1.331087201833724976e-01 9.899731874465942383e-01\n1.360933780670166016e+01 -2.631202507019042969e+01 -2.773726701736450195e+00 -3.837392851710319519e-02 5.628693476319313049e-02 -1.267978847026824951e-01 9.895865917205810547e-01\n1.342513370513916016e+01 -2.628688812255859375e+01 -2.751210927963256836e+00 -3.827369213104248047e-02 8.357636630535125732e-02 -1.206306293606758118e-01 9.884322285652160645e-01\n1.324517345428466797e+01 -2.626273918151855469e+01 -2.729470252990722656e+00 -3.774780780076980591e-02 1.096056178212165833e-01 -1.146849542856216431e-01 9.866149425506591797e-01\n1.306941986083984375e+01 -2.623960304260253906e+01 -2.708507061004638672e+00 -3.676097095012664795e-02 1.341087967157363892e-01 -1.090409010648727417e-01 9.842630028724670410e-01\n1.289782524108886719e+01 -2.621754837036132812e+01 -2.688323974609375000e+00 -3.527792543172836304e-02 1.568278819322586060e-01 -1.037788391113281250e-01 9.815245866775512695e-01\n1.273034286499023438e+01 -2.619669914245605469e+01 -2.668940305709838867e+00 -3.326483443379402161e-02 1.775135546922683716e-01 -9.898018091917037964e-02 9.785629510879516602e-01\n1.256687068939208984e+01 -2.617734336853027344e+01 -2.650635957717895508e+00 -3.068697638809680939e-02 1.959243118762969971e-01 -9.472550451755523682e-02 9.755507111549377441e-01\n1.240734195709228516e+01 -2.615968132019042969e+01 -2.633720636367797852e+00 -2.752725780010223389e-02 2.118933647871017456e-01 -9.106374531984329224e-02 9.726514816284179688e-01\n1.225172710418701172e+01 -2.614393424987792969e+01 -2.618526458740234375e+00 -2.384060062468051910e-02 2.255300134420394897e-01 -8.791892975568771362e-02 9.699681401252746582e-01\n1.210001945495605469e+01 -2.613039398193359375e+01 -2.605453968048095703e+00 -1.969877257943153381e-02 2.370096743106842041e-01 -8.518087863922119141e-02 9.675652384757995605e-01\n1.195223331451416016e+01 -2.611929702758789062e+01 -2.594952344894409180e+00 -1.517291553318500519e-02 2.465046793222427368e-01 -8.273734152317047119e-02 9.654842019081115723e-01\n1.180842876434326172e+01 -2.611089324951171875e+01 -2.587496280670166016e+00 -1.033360138535499573e-02 2.541842758655548096e-01 -8.047319948673248291e-02 9.637466669082641602e-01\n1.166873264312744141e+01 -2.610503768920898438e+01 -2.583181142807006836e+00 -5.250874906778335571e-03 2.602048218250274658e-01 -7.827369868755340576e-02 9.623612165451049805e-01\n1.153323745727539062e+01 -2.610152244567871094e+01 -2.581868886947631836e+00 -4.532914608716964722e-04 2.597315609455108643e-01 -7.625352591276168823e-02 9.626653790473937988e-01\n1.140217590332031250e+01 -2.609998512268066406e+01 -2.583013772964477539e+00 4.624022170901298523e-03 2.592605948448181152e-01 -7.393597811460494995e-02 9.629621505737304688e-01\n1.127563953399658203e+01 -2.610012054443359375e+01 -2.586120605468750000e+00 9.884547442197799683e-03 2.588075399398803711e-01 -7.123043388128280640e-02 9.632481932640075684e-01\n1.115369224548339844e+01 -2.610171318054199219e+01 -2.590780019760131836e+00 1.523126568645238876e-02 2.583893537521362305e-01 -6.804589182138442993e-02 9.635209441184997559e-01\n1.103638744354248047e+01 -2.610457420349121094e+01 -2.596641778945922852e+00 2.056868188083171844e-02 2.580237686634063721e-01 -6.429013609886169434e-02 9.637777209281921387e-01\n1.092376804351806641e+01 -2.610856437683105469e+01 -2.603400707244873047e+00 2.580112963914871216e-02 2.577296495437622070e-01 -5.986779555678367615e-02 9.640153646469116211e-01\n1.081586933135986328e+01 -2.611361312866210938e+01 -2.610776424407958984e+00 3.083451092243194580e-02 2.575255334377288818e-01 -5.467998981475830078e-02 9.642302393913269043e-01\n1.070365047454833984e+01 -2.612030220031738281e+01 -2.619052648544311523e+00 3.557673841714859009e-02 2.574303746223449707e-01 -4.862414672970771790e-02 9.644167423248291016e-01\n1.058720302581787109e+01 -2.612927246093750000e+01 -2.628027200698852539e+00 3.993793204426765442e-02 2.574616968631744385e-01 -4.159193113446235657e-02 9.645665287971496582e-01\n1.046674633026123047e+01 -2.614217758178710938e+01 -2.637519359588623047e+00 4.383187368512153625e-02 2.576360106468200684e-01 -3.347089886665344238e-02 9.646668434143066406e-01\n1.034272193908691406e+01 -2.616141510009765625e+01 -2.647081136703491211e+00 4.717654734849929810e-02 2.579675316810607910e-01 -2.414281293749809265e-02 9.646990299224853516e-01\n1.021537590026855469e+01 -2.618688964843750000e+01 -2.656219482421875000e+00 4.989557713270187378e-02 2.584675848484039307e-01 -1.348417624831199646e-02 9.646362066268920898e-01\n1.008484077453613281e+01 -2.621813964843750000e+01 -2.664593458175659180e+00 5.191991105675697327e-02 2.591438591480255127e-01 -1.366918906569480896e-03 9.644412398338317871e-01\n9.950877189636230469e+00 -2.625335884094238281e+01 -2.672272920608520508e+00 5.318967998027801514e-02 2.599999010562896729e-01 1.234182342886924744e-02 9.640635251998901367e-01\n9.813652038574218750e+00 -2.629250335693359375e+01 -2.680364847183227539e+00 5.374157801270484924e-02 2.600106000900268555e-01 2.781768701970577240e-02 9.637076854705810547e-01\n9.673460960388183594e+00 -2.633624458312988281e+01 -2.690360069274902344e+00 5.356618016958236694e-02 2.605955302715301514e-01 4.487821832299232483e-02 9.629156589508056641e-01\n9.531424522399902344e+00 -2.638529205322265625e+01 -2.703675508499145508e+00 5.271744728088378906e-02 2.616814076900482178e-01 6.338652223348617554e-02 9.616267085075378418e-01\n9.388124465942382812e+00 -2.644035530090332031e+01 -2.721546649932861328e+00 5.124986916780471802e-02 2.631950974464416504e-01 8.320283889770507812e-02 9.597807526588439941e-01\n9.244585037231445312e+00 -2.650260734558105469e+01 -2.745594501495361328e+00 4.921869561076164246e-02 2.650635242462158203e-01 1.041846200823783875e-01 9.573215246200561523e-01\n9.102452278137207031e+00 -2.657352447509765625e+01 -2.777873516082763672e+00 4.668008908629417419e-02 2.672145068645477295e-01 1.261866539716720581e-01 9.541982412338256836e-01\n8.964381217956542969e+00 -2.665489768981933594e+01 -2.820977687835693359e+00 4.369113594293594360e-02 2.695775926113128662e-01 1.490615159273147583e-01 9.503681659698486328e-01\n8.832632064819335938e+00 -2.674715232849121094e+01 -2.876063108444213867e+00 4.040694609284400940e-02 2.716771364212036133e-01 1.727234572172164917e-01 9.458992481231689453e-01\n8.707996368408203125e+00 -2.684913444519042969e+01 -2.942261934280395508e+00 3.691590949892997742e-02 2.734744250774383545e-01 1.970320641994476318e-01 9.407589435577392578e-01\n8.590589523315429688e+00 -2.695952033996582031e+01 -3.018403291702270508e+00 3.319668024778366089e-02 2.753017246723175049e-01 2.217792868614196777e-01 9.348374009132385254e-01\n8.477613449096679688e+00 -2.707590675354003906e+01 -3.101557493209838867e+00 2.929470688104629517e-02 2.771500647068023682e-01 2.468045502901077271e-01 9.281256198883056641e-01\n8.368250846862792969e+00 -2.719570159912109375e+01 -3.189133167266845703e+00 2.524992823600769043e-02 2.790117561817169189e-01 2.719464898109436035e-01 9.206302165985107422e-01\n8.290827751159667969e+00 -2.728365135192871094e+01 -3.255115985870361328e+00 2.109719812870025635e-02 2.808790802955627441e-01 2.970450520515441895e-01 9.123739004135131836e-01\n"
  },
  {
    "path": "VO_Module/thirdparty/tartanair_tools/evaluation/tartanair_evaluator.py",
    "content": "# Copyright (c) 2020 Carnegie Mellon University, Wenshan Wang <wenshanw@andrew.cmu.edu>\n# For License information please see the LICENSE file in the root directory.\n\nimport numpy as np\nfrom os.path import isdir, isfile\n\nfrom .evaluator_base import ATEEvaluator, RPEEvaluator, KittiEvaluator, transform_trajs, quats2SEs\n\n# from trajectory_transform import timestamp_associate\n\n\ndef plot_traj(gtposes, estposes, vis=False, savefigname=None, title=''):\n    import matplotlib.pyplot as plt\n    fig = plt.figure(figsize=(4,4))\n\n\n    cm = plt.cm.get_cmap('Spectral')\n\n    plt.subplot(111)\n    plt.plot(gtposes[:,2],gtposes[:,0], linestyle='dashed',c='k')\n    plt.plot(estposes[:, 2], estposes[:, 0],c='#ff7f0e')\n    plt.xlabel('x (m)')\n    plt.ylabel('y (m)')\n    plt.legend(['Ground Truth','Ours'])\n    plt.title(title)\n\n    plt.axis('equal')    \n\n    if savefigname is not None:\n        plt.savefig(savefigname)\n    \n    if vis:\n        plt.show()\n    \n    plt.close(fig)\n\n\n# \n\nclass TartanAirEvaluator:\n    def __init__(self, scale = False, round=1):\n        self.ate_eval = ATEEvaluator()\n        self.rpe_eval = RPEEvaluator()\n        self.kitti_eval = KittiEvaluator()\n        \n    def evaluate_one_trajectory(self, gt_traj, est_traj, scale=False, title=''):\n        \"\"\"\n        scale = True: calculate a global scale\n        \"\"\"\n\n        if gt_traj.shape[0] != est_traj.shape[0]:\n            raise Exception(\"POSEFILE_LENGTH_ILLEGAL\")\n            \n        if gt_traj.shape[1] != 7 or est_traj.shape[1] != 7:\n            raise Exception(\"POSEFILE_FORMAT_ILLEGAL\")\n\n        gt_traj = gt_traj.astype(np.float64)\n        est_traj = est_traj.astype(np.float64)\n\n        ate_score, gt_ate_aligned, est_ate_aligned = self.ate_eval.evaluate(gt_traj, est_traj, scale)\n\n        plot_traj(np.matrix(gt_ate_aligned), np.matrix(est_ate_aligned), vis=False, savefigname=\"figures/%s.pdf\"%title, title=title)\n\n        est_ate_aligned = np.array(est_ate_aligned)\n        gt_SEs, est_SEs = quats2SEs(gt_ate_aligned, est_ate_aligned)\n\n\n\n        rpe_score = self.rpe_eval.evaluate(gt_SEs, est_SEs)\n        kitti_score = self.kitti_eval.evaluate(gt_SEs, est_SEs)\n\n        return {'ate_score': ate_score, 'rpe_score': rpe_score, 'kitti_score': kitti_score}\n\n\nif __name__ == \"__main__\":\n    \n    # scale = True for monocular track, scale = False for stereo track\n    aicrowd_evaluator = TartanAirEvaluator()\n    result = aicrowd_evaluator.evaluate_one_trajectory('pose_gt.txt', 'pose_est.txt', scale=True)\n    print(result)\n"
  },
  {
    "path": "VO_Module/thirdparty/tartanair_tools/evaluation/trajectory_transform.py",
    "content": "# Copyright (c) 2020 Carnegie Mellon University, Wenshan Wang <wenshanw@andrew.cmu.edu>\n# For License information please see the LICENSE file in the root directory.\n\nimport numpy as np\nfrom . import transformation as tf\n\ndef shift0(traj): \n    '''\n    Traj: a list of [t + quat]\n    Return: translate and rotate the traj\n    '''\n    traj_ses = tf.pos_quats2SE_matrices(np.array(traj))\n    traj_init = traj_ses[0]\n    traj_init_inv = np.linalg.inv(traj_init)\n    new_traj = []\n    for tt in traj_ses:\n        ttt=traj_init_inv.dot(tt)\n        new_traj.append(tf.SE2pos_quat(ttt))\n    return np.array(new_traj)\n\ndef ned2cam(traj):\n    '''\n    transfer a ned traj to camera frame traj\n    '''\n    T = np.array([[0,1,0,0],\n                  [0,0,1,0],\n                  [1,0,0,0],\n                  [0,0,0,1]], dtype=np.float32) \n    T_inv = np.linalg.inv(T)\n    new_traj = []\n    traj_ses = tf.pos_quats2SE_matrices(np.array(traj))\n\n    for tt in traj_ses:\n        ttt=T.dot(tt).dot(T_inv)\n        new_traj.append(tf.SE2pos_quat(ttt))\n        \n    return np.array(new_traj)\n\ndef cam2ned(traj):\n    '''\n    transfer a camera traj to ned frame traj\n    '''\n    T = np.array([[0,0,1,0],\n                  [1,0,0,0],\n                  [0,1,0,0],\n                  [0,0,0,1]], dtype=np.float32) \n    T_inv = np.linalg.inv(T)\n    new_traj = []\n    traj_ses = tf.pos_quats2SE_matrices(np.array(traj))\n\n    for tt in traj_ses:\n        ttt=T.dot(tt).dot(T_inv)\n        new_traj.append(tf.SE2pos_quat(ttt))\n        \n    return np.array(new_traj)\n\n\ndef trajectory_transform(gt_traj, est_traj):\n    '''\n    1. center the start frame to the axis origin\n    2. align the GT frame (NED) with estimation frame (camera)\n    '''\n    gt_traj_trans = shift0(gt_traj)\n    est_traj_trans = shift0(est_traj)\n\n    # gt_traj_trans = ned2cam(gt_traj_trans)\n    # est_traj_trans = cam2ned(est_traj_trans)\n\n    return gt_traj_trans, est_traj_trans\n\ndef rescale_bk(poses_gt, poses):\n    motion_gt = tf.pose2motion(poses_gt)\n    motion    = tf.pose2motion(poses)\n    \n    speed_square_gt = np.sum(motion_gt[:,0:3,3]*motion_gt[:,0:3,3],1)\n    speed_gt = np.sqrt(speed_square_gt)\n    speed_square    = np.sum(motion[:,0:3,3]*motion[:,0:3,3],1)\n    speed = np.sqrt(speed_square)\n    # when the speed is small, the scale could become very large\n    # import ipdb;ipdb.set_trace()\n    mask = (speed_gt>0.0001) # * (speed>0.00001)\n    scale = np.mean((speed[mask])/speed_gt[mask])\n    scale = 1.0/scale\n    motion[:,0:3,3] = motion[:,0:3,3]*scale\n    pose_update = tf.motion2pose(motion)\n    return  pose_update, scale\n\ndef pose2trans(pose_data):\n    data_size = len(pose_data)\n    trans = []\n    for i in range(0,data_size-1):\n        tran = np.array(pose_data[i+1][:3]) - np.array(pose_data[i][:3]) # np.linalg.inv(data[i]).dot(data[i+1])\n        trans.append(tran)\n\n    return np.array(trans) # N x 3\n\n\ndef rescale(poses_gt, poses):\n    '''\n    similar to rescale\n    poses_gt/poses: N x 7 poselist in quaternion format\n    '''\n    trans_gt = pose2trans(poses_gt)\n    trans    = pose2trans(poses)\n    \n    speed_square_gt = np.sum(trans_gt*trans_gt,1)\n    speed_gt = np.sqrt(speed_square_gt)\n    speed_square    = np.sum(trans*trans,1)\n    speed = np.sqrt(speed_square)\n    # when the speed is small, the scale could become very large\n    # import ipdb;ipdb.set_trace()\n    mask = (speed_gt>0.0001) # * (speed>0.00001)\n    scale = np.mean((speed[mask])/speed_gt[mask])\n    scale = 1.0/scale\n    poses[:,0:3] = poses[:,0:3]*scale\n    return  poses, scale\n\ndef trajectory_scale(traj, scale):\n    for ttt in traj:\n        ttt[0:3,3] = ttt[0:3,3]*scale\n    return traj\n \ndef timestamp_associate(first_list, second_list, max_difference):\n    \"\"\"\n    Associate two trajectory of [stamp,data]. As the time stamps never match exactly, we aim \n    to find the closest match for every input tuple.\n    \n    Input:\n    first_list -- first list of (stamp,data)\n    second_list -- second list of (stamp,data)\n    max_difference -- search radius for candidate generation\n\n    Output:\n    first_res: matched data from the first list\n    second_res: matched data from the second list\n    \n    \"\"\"\n    first_dict = dict([(l[0],l[1:]) for l in first_list if len(l)>1])\n    second_dict = dict([(l[0],l[1:]) for l in second_list if len(l)>1])\n\n    first_keys = first_dict.keys()\n    second_keys = second_dict.keys()\n    potential_matches = [(abs(a - b ), a, b) \n                         for a in first_keys \n                         for b in second_keys \n                         if abs(a - b) < max_difference]\n    potential_matches.sort()\n    matches = []\n    for diff, a, b in potential_matches:\n        if a in first_keys and b in second_keys:\n            first_keys.remove(a)\n            second_keys.remove(b)\n            matches.append((a, b))\n    \n    matches.sort()\n\n    first_res = []\n    second_res = []\n    for t1, t2 in matches:\n        first_res.append(first_dict[t1])\n        second_res.append(second_dict[t2])\n    return np.array(first_res), np.array(second_res)\n"
  },
  {
    "path": "VO_Module/thirdparty/tartanair_tools/evaluation/transformation.py",
    "content": "# Copyright (c) 2020 Carnegie Mellon University, Wenshan Wang <wenshanw@andrew.cmu.edu>\n# For License information please see the LICENSE file in the root directory.\n# Cridit: Xiangwei Wang https://github.com/TimingSpace\n\nimport numpy as np\nfrom scipy.spatial.transform import Rotation as R\n\ndef line2mat(line_data):\n    mat = np.eye(4)\n    mat[0:3,:] = line_data.reshape(3,4)\n    return np.matrix(mat)\n\ndef motion2pose(data):\n    data_size = len(data)\n    all_pose = [] # np.zeros((data_size+1, 4, 4))\n    all_pose.append(np.eye(4,4)) #[0,:] = np.eye(4,4)\n    pose = np.eye(4,4)\n    for i in range(0,data_size):\n        pose = pose.dot(data[i])\n        all_pose.append(pose)\n    return all_pose\n\ndef pose2motion(data):\n    data_size = len(data)\n    all_motion = []\n    for i in range(0,data_size-1):\n        motion = np.linalg.inv(data[i]).dot(data[i+1])\n        all_motion.append(motion)\n\n    return np.array(all_motion) # N x 4 x 4\n\ndef SE2se(SE_data):\n    result = np.zeros((6))\n    result[0:3] = np.array(SE_data[0:3,3].T)\n    result[3:6] = SO2so(SE_data[0:3,0:3]).T\n    return result\n    \ndef SO2so(SO_data):\n    return R.from_matrix(SO_data).as_rotvec()\n\ndef so2SO(so_data):\n    return R.from_rotvec(so_data).as_matrix()\n\ndef se2SE(se_data):\n    result_mat = np.matrix(np.eye(4))\n    result_mat[0:3,0:3] = so2SO(se_data[3:6])\n    result_mat[0:3,3]   = np.matrix(se_data[0:3]).T\n    return result_mat\n### can get wrong result\ndef se_mean(se_datas):\n    all_SE = np.matrix(np.eye(4))\n    for i in range(se_datas.shape[0]):\n        se = se_datas[i,:]\n        SE = se2SE(se)\n        all_SE = all_SE*SE\n    all_se = SE2se(all_SE)\n    mean_se = all_se/se_datas.shape[0]\n    return mean_se\n\ndef ses_mean(se_datas):\n    se_datas = np.array(se_datas)\n    se_datas = np.transpose(se_datas.reshape(se_datas.shape[0],se_datas.shape[1],se_datas.shape[2]*se_datas.shape[3]),(0,2,1))\n    se_result = np.zeros((se_datas.shape[0],se_datas.shape[2]))\n    for i in range(0,se_datas.shape[0]):\n        mean_se = se_mean(se_datas[i,:,:])\n        se_result[i,:] = mean_se\n    return se_result\n\ndef ses2poses(data):\n    data_size = data.shape[0]\n    all_pose = np.zeros((data_size+1,12))\n    temp = np.eye(4,4).reshape(1,16)\n    all_pose[0,:] = temp[0,0:12]\n    pose = np.matrix(np.eye(4,4))\n    for i in range(0,data_size):\n        data_mat = se2SE(data[i,:])\n        pose = pose*data_mat\n        pose_line = np.array(pose[0:3,:]).reshape(1,12)\n        all_pose[i+1,:] = pose_line\n    return all_pose\n\ndef SEs2ses(motion_data):\n    data_size = motion_data.shape[0]\n    ses = np.zeros((data_size,6))\n    for i in range(0,data_size):\n        SE = np.matrix(np.eye(4))\n        SE[0:3,:] = motion_data[i,:].reshape(3,4)\n        ses[i,:] = SE2se(SE)\n    return ses\n\ndef so2quat(so_data):\n    so_data = np.array(so_data)\n    theta = np.sqrt(np.sum(so_data*so_data))\n    axis = so_data/theta\n    quat=np.zeros(4)\n    quat[0:3] = np.sin(theta/2)*axis\n    quat[3] = np.cos(theta/2)\n    return quat\n\ndef quat2so(quat_data):\n    quat_data = np.array(quat_data)\n    sin_half_theta = np.sqrt(np.sum(quat_data[0:3]*quat_data[0:3]))\n    axis = quat_data[0:3]/sin_half_theta\n    cos_half_theta = quat_data[3]\n    theta = 2*np.arctan2(sin_half_theta,cos_half_theta)\n    so = theta*axis\n    return so\n\n# input so_datas batch*channel*height*width\n# return quat_datas batch*numner*channel\ndef sos2quats(so_datas,mean_std=[[1],[1]]):\n    so_datas = np.array(so_datas)\n    so_datas = so_datas.reshape(so_datas.shape[0],so_datas.shape[1],so_datas.shape[2]*so_datas.shape[3])\n    so_datas = np.transpose(so_datas,(0,2,1))\n    quat_datas = np.zeros((so_datas.shape[0],so_datas.shape[1],4))\n    for i_b in range(0,so_datas.shape[0]):\n        for i_p in range(0,so_datas.shape[1]):\n            so_data = so_datas[i_b,i_p,:]\n            quat_data = so2quat(so_data)\n            quat_datas[i_b,i_p,:] = quat_data\n    return quat_datas\n\ndef SO2quat(SO_data):\n    rr = R.from_matrix(SO_data)\n    return rr.as_quat()\n\ndef quat2SO(quat_data):\n    return R.from_quat(quat_data).as_matrix()\n\n\ndef pos_quat2SE(quat_data):\n    SO = R.from_quat(quat_data[3:7]).as_matrix()\n    SE = np.matrix(np.eye(4))\n    SE[0:3,0:3] = np.matrix(SO)\n    SE[0:3,3]   = np.matrix(quat_data[0:3]).T\n    SE = np.array(SE[0:3,:]).reshape(1,12)\n    return SE\n\n\ndef pos_quats2SEs(quat_datas):\n    data_len = quat_datas.shape[0]\n    SEs = np.zeros((data_len,12))\n    for i_data in range(0,data_len):\n        SE = pos_quat2SE(quat_datas[i_data,:])\n        SEs[i_data,:] = SE\n    return SEs\n\n\ndef pos_quats2SE_matrices(quat_datas):\n    data_len = quat_datas.shape[0]\n    SEs = []\n    for quat in quat_datas:\n        SO = R.from_quat(quat[3:7]).as_matrix()\n        SE = np.eye(4)\n        SE[0:3,0:3] = SO\n        SE[0:3,3]   = quat[0:3]\n        SEs.append(SE)\n    return SEs\n\ndef SE2pos_quat(SE_data):\n    pos_quat = np.zeros(7)\n    pos_quat[3:] = SO2quat(SE_data[0:3,0:3])\n    pos_quat[:3] = SE_data[0:3,3].T\n    return pos_quat"
  },
  {
    "path": "VO_Module/thirdparty/tartanair_tools/seg_rgbs.txt",
    "content": "0 0 0\n153 108 6\n112 105 191\n89 121 72\n190 225 64\n206 190 59\n81 13 36\n115 176 195\n161 171 27\n135 169 180\n29 26 199\n102 16 239\n242 107 146\n156 198 23\n49 89 160\n68 218 116\n11 236 9\n196 30 8\n121 67 28\n0 53 65\n146 52 70\n226 149 143\n151 126 171\n194 39 7\n205 120 161\n212 51 60\n211 80 208\n189 135 188\n54 72 205\n103 252 157\n124 21 123\n19 132 69\n195 237 132\n94 253 175\n182 251 87\n90 162 242\n199 29 1\n254 12 229\n35 196 244\n220 163 49\n86 254 214\n152 3 129\n92 31 106\n207 229 90\n125 75 48\n98 55 74\n126 129 238\n222 153 109\n85 152 34\n173 69 31\n37 128 125\n58 19 33\n134 57 119\n218 124 115\n120 0 200\n225 131 92\n246 90 16\n51 155 241\n202 97 155\n184 145 182\n96 232 44\n133 244 133\n180 191 29\n1 222 192\n99 242 104\n91 168 219\n65 54 217\n148 66 130\n203 102 204\n216 78 75\n234 20 250\n109 206 24\n164 194 17\n157 23 236\n158 114 88\n245 22 110\n67 17 35\n181 213 93\n170 179 42\n52 187 148\n247 200 111\n25 62 174\n100 25 240\n191 195 144\n252 36 67\n241 77 149\n237 33 141\n119 230 85\n28 34 108\n78 98 254\n114 161 30\n75 50 243\n66 226 253\n46 104 76\n8 234 216\n15 241 102\n93 14 71\n192 255 193\n253 41 164\n24 175 120\n185 243 231\n169 233 97\n243 215 145\n72 137 21\n160 113 101\n214 92 13\n167 140 147\n101 109 181\n53 118 126\n3 177 32\n40 63 99\n186 139 153\n88 207 100\n71 146 227\n236 38 187\n215 4 215\n18 211 66\n113 49 134\n47 42 63\n219 103 127\n57 240 137\n227 133 211\n145 71 201\n217 173 183\n250 40 113\n208 125 68\n224 186 249\n69 148 46\n239 85 20\n108 116 224\n56 214 26\n179 147 43\n48 188 172\n221 83 47\n155 166 218\n62 217 189\n198 180 122\n201 144 169\n132 2 14\n128 189 114\n163 227 112\n45 157 177\n64 86 142\n118 193 163\n14 32 79\n200 45 170\n74 81 2\n59 37 212\n73 35 225\n95 224 39\n84 170 220\n159 58 173\n17 91 237\n31 95 84\n34 201 248\n63 73 209\n129 235 107\n231 115 40\n36 74 95\n238 228 154\n61 212 54\n13 94 165\n141 174 0\n140 167 255\n117 93 91\n183 10 186\n165 28 61\n144 238 194\n12 158 41\n76 110 234\n150 9 121\n142 1 246\n230 136 198\n5 60 233\n232 250 80\n143 112 56\n187 70 156\n2 185 62\n138 223 226\n122 183 222\n166 245 3\n175 6 140\n240 59 210\n248 44 10\n83 82 52\n223 248 167\n87 15 150\n111 178 117\n197 84 22\n235 208 124\n9 76 45\n176 24 50\n154 159 251\n149 111 207\n168 231 15\n209 247 202\n80 205 152\n178 221 213\n27 8 38\n244 117 51\n107 68 190\n23 199 139\n171 88 168\n136 202 58\n6 46 86\n105 127 176\n174 249 197\n172 172 138\n228 142 81\n7 204 185\n22 61 247\n233 100 78\n127 65 105\n33 87 158\n139 156 252\n42 7 136\n20 99 179\n79 150 223\n131 182 184\n110 123 37\n60 138 96\n210 96 94\n123 48 18\n137 197 162\n188 18 5\n39 219 151\n204 143 135\n249 79 73\n77 64 178\n41 246 77\n16 154 4\n116 134 19\n4 122 235\n177 106 230\n21 119 12\n104 5 98\n50 130 53\n30 192 25\n26 165 166\n10 160 82\n106 43 131\n44 216 103\n255 101 221\n32 151 196\n213 220 89\n70 209 228\n97 184 83\n82 239 232\n251 164 128\n193 11 245\n38 27 159\n229 141 203\n130 56 55\n147 210 11\n162 203 118\n255 255 255"
  },
  {
    "path": "VO_Module/tools/generate_demo.py",
    "content": "import PIL.Image as Image\nimport os\nimport numpy as np\nimport cv2\nimport imageio\n\npred_dir = 'tools/edit-demo/results/Scene02/warp_img'\nfilelist = os.listdir(pred_dir)\nfilelist.sort()\n\n# img_dir = \"../datasets/cityscapes_vps/val/img_all\"\n# img_dir = \"../datasets/viper/val/img\"\n# imagelist = os.listdir(img_dir)\n# imagelist.sort()\n\nout_folder = \"tools/edit-demo/video\"\nif not os.path.isdir(out_folder):\n    os.makedirs(out_folder)\n\ncnt = 0\nfourcc = cv2.VideoWriter_fourcc(*'XVID')\nvideo = cv2.VideoWriter(\"3.avi\", fourcc, 8, (1240,368))\nfor img_file in filelist:\n    save_path = os.path.join(out_folder, img_file)\n\n    img = cv2.imread(os.path.join(pred_dir, img_file))\n    # background = cv2.imread(os.path.join(img_dir, img_file))\n\n    # added_image = cv2.addWeighted(background,0.5,overlay,0.5, 0)\n\n    \n    # cv2.imwrite(save_path, added_image)\n    # img = cv2.imread(save_path)\n    video.write(img)\n\nvideo.release()\n"
  },
  {
    "path": "VO_Module/tools/vis.py",
    "content": "import sys\nsys.path.append('droid_slam')\n\n'''\n用于生成轨迹\n'''\n\nimport torch\nfrom torch.utils.data import DataLoader\nimport glob\nimport os\nimport os.path as osp\nimport cv2\nimport numpy as np\nimport pandas as pd\nimport torch.nn.functional as F\nfrom scipy.spatial.transform import Rotation as R\nfrom collections import OrderedDict\nfrom lietorch import SE3\nfrom geom.projective_ops import projective_transform, coords_grid\nfrom geom.graph_utils import graph_to_edge_list\nfrom droid_net import DroidNet, upsample_inter\nfrom data_readers.factory import dataset_factory\nimport data_readers.vkitti2\nfrom panopticapi.utils import id2rgb, rgb2id\nimport PIL.Image as Image\n\n\ndef load_weights(weights, device):\n    \"\"\" load trained model weights \"\"\"\n    net = DroidNet()\n    state_dict = OrderedDict([\n        (k.replace(\"module.\", \"\"), v) for (k, v) in torch.load(weights, device).items()])\n    net.load_state_dict(state_dict)\n    return net.to(device).eval()\n\n\ndef resize(mask, size, need_permute):\n    if need_permute:\n        mask = mask.permute(0, 1, 4, 2, 3).contiguous()\n    batch, num, dim, ht, wd = mask.shape\n    mask = mask.view(batch*num, dim, ht, wd)\n    mask = F.interpolate(mask, size=size, mode='bilinear', align_corners=True)\n    if need_permute:\n        mask = mask.permute(0, 2, 3, 1).contiguous()\n        return mask.view(batch, num, size[0], size[1], dim)\n    else:\n        return mask.view(batch, num, dim, size[0], size[1])\n\n\ndef resize_flow(flow, size):\n    flow = flow.permute(0, 1, 4, 2, 3).contiguous()\n    batch, num, dim, ht, wd = flow.shape\n    flow = flow.view(batch*num, dim, ht, wd)\n    flow[:, 0, ...] /= wd\n    flow[:, 1, ...] /= ht\n    flow = F.interpolate(flow, size=size, mode='bilinear', align_corners=True)\n    flow[:, 0, ...] *= size[1]\n    flow[:, 1, ...] *= size[0]\n    flow = flow.permute(0, 2, 3, 1).contiguous()\n    return flow.view(batch, num, size[0], size[1], dim)\n\n\ndef occ_warp_img_(u0, v0, flow1, dep_uv, ref_img, fix_img, dy_mask):\n\n    flow1 = flow1.detach().cpu().numpy()\n    ref_img = ref_img.permute(1, 2, 0).cpu().numpy()\n    fix_img = fix_img.permute(1, 2, 0).cpu().numpy()\n    dy_mask = dy_mask.detach().cpu().numpy()\n\n    rows, cols = flow1.shape[:2]\n    u1 = (u0 + flow1[:, :, 0])\n    v1 = (v0 + flow1[:, :, 1])\n\n    u0 = u0.flatten()\n    v0 = v0.flatten()\n    u1 = u1.flatten()\n    v1 = v1.flatten()\n\n    mm = (0 <= u1).__and__(u1 < cols).__and__(0 <= v1).__and__(v1 < rows)\n    u1, v1 = u1[mm], v1[mm]\n    u0, v0 = u0[mm], v0[mm]\n    dep_uv = dep_uv[mm]\n\n    encode_uvu1v1 = np.stack([u0, v0, u1, v1], axis=-1)\n    df = pd.DataFrame(encode_uvu1v1, index=dep_uv).sort_index(ascending=False)\n    new_encode_uvu1v1 = df.to_numpy()\n\n    u0, v0 = new_encode_uvu1v1[:, 0], new_encode_uvu1v1[:, 1]\n    u1, v1 = new_encode_uvu1v1[:, 2], new_encode_uvu1v1[:, 3]\n\n    u1 = np.clip(np.around(u1), 0, cols-1).astype(np.int32)\n    v1 = np.clip(np.around(v1), 0, rows-1).astype(np.int32)\n    warp_img = np.ones([rows, cols, 3])*255\n    warp_img[v1, u1] = ref_img[v0.astype(np.int32), u0.astype(np.int32)]\n\n    fix_index = (warp_img.mean(axis=-1, keepdims=True)\n                 >= 255).__and__(dy_mask < 1)\n    fix_index[:rows//3, :, :] = True\n    fix_index = np.concatenate([fix_index, fix_index, fix_index], axis=-1)\n    warp_img[fix_index] = fix_img[fix_index]\n\n    return warp_img\n\ndef occ_warp_img(u0, v0, flow1, dep_uv, ref_img, fix_img, dy_mask, segments, use_blende=True, idx=0):\n\n    flow1 = flow1.detach().cpu().numpy()\n    ref_img = ref_img.permute(1, 2, 0).cpu().numpy()\n    fix_img = fix_img.permute(1, 2, 0).cpu().numpy()\n    dy_mask = dy_mask.detach().cpu().numpy()\n\n    # segm filter\n   \n    segments = F.interpolate(segments.unsqueeze(0).unsqueeze(0),size=img_size).squeeze(0).squeeze(0).int()\n    segments = segments.detach().cpu().numpy() # 368x1240\n\n    big_car_mask = (segments == 12009) * 1\n    Image.fromarray(big_car_mask.astype(np.uint8)*255).save(str(idx) + '.png')\n    speed_u = flow1[:,:,0]*big_car_mask\n    speed_v = flow1[:,:,1]*big_car_mask\n    Image.fromarray(speed_u.astype(np.uint8)*255).save(str(idx) + '_u.png')\n    u_m = np.mean(speed_u[(abs(speed_u) < 100)])\n    u_v = np.mean(speed_v[(abs(speed_v) < 100)])\n    \n    speed_u[big_car_mask] = u_m\n    speed_v[big_car_mask] = u_v\n    Image.fromarray(speed_u.astype(np.uint8)*255).save(str(idx) + '_f.png')\n    print(np.unique(speed_u[big_car_mask]))\n    print(np.unique(speed_u[1-big_car_mask]))\n\n    rows, cols = flow1.shape[:2]\n    u1 = (u0 + speed_u)\n    v1 = (v0 + speed_v)\n\n    u0 = u0.flatten()\n    v0 = v0.flatten()\n    u1 = u1.flatten()\n    v1 = v1.flatten()\n\n    mm = (0 <= u1).__and__(u1 < cols).__and__(0 <= v1).__and__(v1 < rows)\n    u1, v1 = u1[mm], v1[mm]\n    u0, v0 = u0[mm], v0[mm]\n    dep_uv = dep_uv[mm]\n\n    encode_uvu1v1 = np.stack([u0, v0, u1, v1], axis=-1)\n    df = pd.DataFrame(encode_uvu1v1, index=dep_uv).sort_index(ascending=False)\n    new_encode_uvu1v1 = df.to_numpy()\n\n    u0, v0 = new_encode_uvu1v1[:, 0], new_encode_uvu1v1[:, 1]\n    u1, v1 = new_encode_uvu1v1[:, 2], new_encode_uvu1v1[:, 3]\n\n    # u1 = np.clip(np.around(u1), 0, cols-1).astype(np.int32)\n    # v1 = np.clip(np.around(v1), 0, rows-1).astype(np.int32)\n    if use_blende:\n        u1, v1 = u1.astype(np.int32), v1.astype(np.int32)\n        u0, v0 = u0.astype(np.int32), v0.astype(np.int32)\n    else:\n        up_u1 = np.clip(np.ceil(u1), 0, cols-1).astype(np.int32)\n        up_v1 = np.clip(np.ceil(v1), 0, rows-1).astype(np.int32)\n        down_u1 = np.floor(u1).astype(np.int32)\n        down_v1 = np.floor(v1).astype(np.int32)\n        u1 = np.concatenate([up_u1, down_u1, up_u1, down_u1], 0)\n        v1 = np.concatenate([up_v1, down_v1, down_v1, up_v1], 0)\n        u0 = np.concatenate([u0, u0, u0, u0], 0).astype(np.int32)\n        v0 = np.concatenate([v0, v0, v0, v0], 0).astype(np.int32)\n\n    warp_img = np.ones([rows, cols, 3])*255\n\n    if use_blende:\n        direc = [[1, 0], [0, 1], [-1, 0], [0, -1],\n                [1, 1], [-1, -1], [1, -1], [-1, 1]]\n        for i in range(len(v1)):\n            i_v1, i_u1, i_v0, i_u0 = v1[i], u1[i], v0[i], u0[i]\n            warp_img[i_v1, i_u1] = ref_img[i_v0, i_u0]\n            if i_v1 == i_v0 and i_u1 == i_u0:\n                continue\n            for d in direc:\n                t_v, t_u = i_v1+d[0], i_u1+d[1]\n                if t_v < rows and t_v >= 0 and t_u < cols and t_u >= 0:\n                    warp_img[t_v, t_u] = ref_img[i_v0, i_u0]\n    else:\n        warp_img[v1, u1] = ref_img[v0, u0]\n\n    warp_img[v1, u1] = ref_img[v0.astype(np.int32), u0.astype(np.int32)]\n\n    \n    # dy_mask[:,:,0] = dy_mask[:,:,0]*(1-big_car_mask*1)\n    # fix_index = (warp_img.mean(axis=-1, keepdims=True)>= 255).__and__(dy_mask < 1) # 0 dongtai\n    # fix_index[:rows//3, :, :] = True\n    # fix_index = np.concatenate([fix_index, fix_index, fix_index], axis=-1)\n    # warp_img[fix_index] = fix_img[fix_index]\n\n    # fix_index = (warp_img.mean(axis=-1, keepdims=True) >= 255)\n    # fix_index = np.concatenate([fix_index, fix_index, fix_index], axis=-1)\n    # warp_img[fix_index] = fix_img[fix_index]\n\n    return warp_img\n\n\nscene_id = 'Scene02'\nimg_size = [368, 1240]\n\nmax_fac = 5\nspeed_fac = []\nfor f in np.linspace(1, max_fac, 10):\n    speed_fac.append(f)\nfor f in np.linspace(1, max_fac, 10)[::-1]:\n    speed_fac.append(f)\nspeed_fac.append(0)\nfor f in np.linspace(1, max_fac, 10):\n    speed_fac.append(-f)\nfor f in np.linspace(1, max_fac, 10)[::-1]:\n    speed_fac.append(-f)\nspeed_fac.append(0)\n\ni_start = 158\ni_end = i_start+1\ntest_file = 'droid_slam/data_readers/vkitti2_test.txt'\nflow_label = True\n\nf = open(test_file)\ndata_readers.vkitti2.test_split = f.read().split()\nf.close()\n\nori_img_dir = osp.join('tools/edit-demo/results', scene_id, 'ori_img')\nwarp_img_dir = osp.join('tools/edit-demo/results', scene_id, 'warp_img')\nif not osp.exists(ori_img_dir):\n    os.makedirs(ori_img_dir)\nif not osp.exists(warp_img_dir):\n    os.makedirs(warp_img_dir)\n\ndb = dataset_factory(['vkitti2'], datapath='datasets/Virtual_KITTI2', do_aug=False,\n                     n_frames=2, flow_label=flow_label, aug_graph=False, split_mode='val',\n                     need_inv=False, build_mask=False, crop_size=img_size, mode='semisup', rebuild=False)\ntrain_loader = DataLoader(db, batch_size=1, num_workers=2)\n\nweights_file = \"/mnt/nas_8/group/yuxingyuan/Neural-iMAP/checkpoints/vkitti2_dy_train_semiv4_080000.pth\"\ndevice = 'cuda:0'\ntorch.cuda.set_device(int(device.split(':')[-1]))\n\nsegment_dir = \"/mnt/nas_55/datasets/virtual_kitti2/vkitti/Scene02/15-deg-left/panoptic_gt_id\"\nseg_list = os.listdir(segment_dir)\nseg_list.sort()\n\ngraph = OrderedDict()\ngraph[0] = [1]\ngraph[1] = [0]\nii, jj, _ = graph_to_edge_list(graph)\n\nmodel = load_weights(weights_file, device)\ncoords0 = coords_grid(img_size[0], img_size[1], device=device)\n\nv = np.arange(img_size[0])\nv = v.reshape(img_size[0], 1)\nv = np.repeat(v, img_size[1], axis=1)\nu = np.arange(img_size[1])\nu = np.tile(u, (img_size[0], 1))\n\nv1, u1 = v.copy(), u.copy()\nv0, u0 = v.copy(), u.copy()\n\nfor i_batch, item in enumerate(train_loader):\n    if i_batch < i_start and i_batch >= i_start-20:\n        images, _, _, _, _, _,segments = [x.to('cuda') for x in item]\n        images = resize(images, img_size, False)\n        ori_img = images[0, 0].permute(1, 2, 0).cpu().numpy().astype(np.uint8)\n        cv2.imwrite(osp.join(ori_img_dir, str(i_batch)+'.png'), ori_img)\n        continue\n    elif i_batch < i_start-20:\n        continue\n    elif i_batch == i_end:\n        break\n\n    if flow_label:\n        images, poses, disps, intrinsics, fo_flows, _, segments = [ x.to('cuda') for x in item]\n        fo_flows = resize_flow(fo_flows, img_size)\n    else:\n        images, poses, disps, intrinsics, _, _ = [x.to('cuda') for x in item]\n\n    hr, wr = img_size[0]/images.shape[3], img_size[1]/images.shape[4]\n    intrinsics[:, :, 0] *= wr\n    intrinsics[:, :, 2] *= wr\n    intrinsics[:, :, 1] *= hr\n    intrinsics[:, :, 3] *= hr\n    images = resize(images, img_size, False)\n    disps = resize(disps.unsqueeze(2), img_size, False).squeeze(2)\n     \n    Gs = SE3(poses)\n    disp0 = disps[:, :, 3::8, 3::8]\n\n    for _ in range(1):\n        poses_est, disps_est, residuals, full_flows, masks = \\\n                model(Gs, images, disp0, intrinsics/8,\n                         graph, num_steps=15, fixedp=2,\n                        ret_flow=True, downsample=True)\n\n    coords1, val0 = projective_transform(Gs, disps, intrinsics, ii, jj)\n\n    cam_flow = (coords1-coords0)[0, 0]\n    if flow_label:\n        full_flow = fo_flows[0, 0]\n    else:\n        full_flow = (upsample_inter(full_flows[-1]*8))[0, 0]\n\n    dy_flow = full_flow-cam_flow\n    dy_mask = (masks[-1][0, 0].mean(-1, keepdim=True) < 0.5).float()\n\n    ref_depth = disps[0, 0]\n    ref_depth = torch.clamp(1/ref_depth, 1e-3, 80)\n    ref_depth = ref_depth.detach().cpu().numpy()\n    dep_uv = ref_depth.flatten()\n    ref_img = images[0, 0]\n\n    for i, fac in enumerate(speed_fac):\n        segments = rgb2id(np.array(Image.open(\\\n                            os.path.join(segment_dir, seg_list[i_batch+i]) ))).astype(np.float32) # 375x1242x3\n        segments = torch.from_numpy(segments)\n\n        warp_img = occ_warp_img(u0, v0, dy_flow*fac, dep_uv, \\\n                        ref_img, images[0, 0], dy_mask, segments, idx=i)\n        warp_img = warp_img.astype(np.uint8)\n        cv2.imwrite(osp.join(warp_img_dir, str(i_batch)+'_%03d.png' % i), warp_img)\n        print('Finished warping %d img in speed factor %f' % (i_batch, fac))\n\n    ori_img = images[0, 0].permute(1, 2, 0).cpu().numpy().astype(np.uint8)\n    cv2.imwrite(osp.join(ori_img_dir, str(i_batch)+'.png'), ori_img)\n"
  },
  {
    "path": "VO_Module/tools/vis_2.py",
    "content": "import sys\nsys.path.append('droid_slam')\n\nimport torch\nfrom torch.utils.data import DataLoader\nimport glob\nimport os\nimport os.path as osp\nimport cv2\nimport numpy as np\nimport pandas as pd\nimport torch.nn.functional as F\nfrom scipy.spatial.transform import Rotation as R\nfrom collections import OrderedDict\nfrom lietorch import SE3\nfrom geom.projective_ops import projective_transform, coords_grid\nfrom geom.graph_utils import graph_to_edge_list\nfrom droid_net import DroidNet, upsample_inter\nfrom data_readers.factory import dataset_factory\nimport data_readers.vkitti2\n\n\ndef load_weights(weights, device):\n    \"\"\" load trained model weights \"\"\"\n    net = DroidNet()\n    state_dict = OrderedDict([\n        (k.replace(\"module.\", \"\"), v) for (k, v) in torch.load(weights, device).items()])\n    net.load_state_dict(state_dict)\n    return net.to(device).eval()\n\n\ndef resize(mask, size, need_permute):\n    if need_permute:\n        mask = mask.permute(0, 1, 4, 2, 3).contiguous()\n    batch, num, dim, ht, wd = mask.shape\n    mask = mask.view(batch*num, dim, ht, wd)\n    mask = F.interpolate(mask, size=size, mode='bilinear', align_corners=True)\n    if need_permute:\n        mask = mask.permute(0, 2, 3, 1).contiguous()\n        return mask.view(batch, num, size[0], size[1], dim)\n    else:\n        return mask.view(batch, num, dim, size[0], size[1])\n\n\ndef resize_flow(flow, size):\n    flow = flow.permute(0, 1, 4, 2, 3).contiguous()\n    batch, num, dim, ht, wd = flow.shape\n    flow = flow.view(batch*num, dim, ht, wd)\n    flow[:, 0, ...] /= wd\n    flow[:, 1, ...] /= ht\n    flow = F.interpolate(flow, size=size, mode='bilinear', align_corners=True)\n    flow[:, 0, ...] *= size[1]\n    flow[:, 1, ...] *= size[0]\n    flow = flow.permute(0, 2, 3, 1).contiguous()\n    return flow.view(batch, num, size[0], size[1], dim)\n\n\ndef occ_warp_img(u0, v0, flow1, dep_uv, ref_img, fix_img=None, dy_mask=None,use_blende=False):\n    \"\"\"\n    flow: 无变速\n    flow1: 变速\n    \"\"\"\n    print(flow1.shape)\n    print(dep_uv.shape)\n    print(ref_img.shape)\n    # print(fix_img.shape)\n    # flow = flow.detach().cpu()\n    flow1 = flow1.detach().cpu().numpy()\n    ref_img = ref_img.permute(1, 2, 0).cpu().numpy()\n    # fix_img = fix_img.permute(1, 2, 0).cpu().numpy()\n    if dy_mask != None:\n        print(dy_mask.shape)\n        dy_mask = dy_mask.detach().cpu().numpy()\n    print(\"--------------------\")\n\n    rows, cols = flow1.shape[:2]\n\n    # grid_uv=torch.from_numpy(np.concatenate([u0/(cols-1),v0/(rows-1)],axis=-1)).view(1,1,-1,2)\n    # grid_uv=grid_uv*2-1\n    # # sm_flow=F.grid_sample(flow,grid_uv,padding_mode=\"border\", align_corners=True).view(-1,2).numpy()\n    # sm_flow1=F.grid_sample(flow1,grid_uv,padding_mode=\"border\", align_corners=True).view(-1,2).numpy()\n    # # u,v=u+sm_flow[:,0],v+sm_flow[:,1]\n    # u1,v1=u0+sm_flow1[:,0],v0+sm_flow1[:,1]\n\n    u1 = (u0 + flow1[:, :, 0])\n    v1 = (v0 + flow1[:, :, 1])\n\n    u0 = u0.flatten()\n    v0 = v0.flatten()\n    u1 = u1.flatten()\n    v1 = v1.flatten()\n\n    # tu = (u + flow[v, u, 0]).astype(np.int32)\n    # tv = (v + flow[v, u, 1]).astype(np.int32)\n    # u, v = tu, tv\n\n    mm = (0 <= u1).__and__(u1 < cols).__and__(0 <= v1).__and__(v1 < rows)\n    # mm2 = (0 <= u).__and__(u < cols).__and__(0 <= v).__and__(v < rows)\n    # mm = mm1.__and__(mm2)\n    # u, v = u[mm], v[mm]\n    u1, v1 = u1[mm], v1[mm]\n    u0, v0 = u0[mm], v0[mm]\n    dep_uv = dep_uv[mm]\n\n    # encode_uvu1v1 = u0 * 1e14 + v0 * 1e10 + u1 * 1e6 + v1 * 1e2\n    encode_uvu1v1 = np.stack([u0, v0, u1, v1], axis=-1)\n    df = pd.DataFrame(encode_uvu1v1, index=dep_uv).sort_index(ascending=False)\n    new_encode_uvu1v1 = df.to_numpy()\n\n    # dic = dict(zip(encode_uvu1v1, dep_uv))\n    # ndic = np.array(\n    #     sorted(dic.items(), key=lambda item: item[1], reverse=True))\n    # new_encode_uvu1v1 = ndic[:, 0]\n\n    # u0 = (new_encode_uvu1v1 // 1e14).astype(np.int32)\n    # v0 = (new_encode_uvu1v1 % 1e14 // 1e10).astype(np.int32)\n    # u1 = (new_encode_uvu1v1 % 1e10 // 1e6).astype(np.int32)\n    # v1 = (new_encode_uvu1v1 % 1e6 // 1e2).astype(np.int32)\n\n    u0, v0 = new_encode_uvu1v1[:, 0], new_encode_uvu1v1[:, 1]\n    u1, v1 = new_encode_uvu1v1[:, 2], new_encode_uvu1v1[:, 3]\n\n    if use_blende:\n        u1, v1 = u1.astype(np.int32), v1.astype(np.int32)\n        u0, v0 = u0.astype(np.int32), v0.astype(np.int32)\n    else:\n        up_u1 = np.clip(np.ceil(u1), 0, cols-1).astype(np.int32)\n        up_v1 = np.clip(np.ceil(v1), 0, rows-1).astype(np.int32)\n        down_u1 = np.floor(u1).astype(np.int32)\n        down_v1 = np.floor(v1).astype(np.int32)\n        u1 = np.concatenate([up_u1, down_u1, up_u1, down_u1], 0)\n        v1 = np.concatenate([up_v1, down_v1, down_v1, up_v1], 0)\n        u0 = np.concatenate([u0, u0, u0, u0], 0).astype(np.int32)\n        v0 = np.concatenate([v0, v0, v0, v0], 0).astype(np.int32)\n\n    warp_img = np.ones([rows, cols, 3])*255\n    \n    if use_blende:\n        print(ref_img.shape, warp_img.shape)\n        direc = [[1, 0], [0, 1], [-1, 0], [0, -1],\n                [1, 1], [-1, -1], [1, -1], [-1, 1]]\n        for i in range(len(v1)):\n            i_v1, i_u1, i_v0, i_u0 = v1[i], u1[i], v0[i], u0[i]\n            warp_img[i_v1, i_u1] = ref_img[i_v0, i_u0]\n            if i_v1 == i_v0 and i_u1 == i_u0:\n                continue\n            for d in direc:\n                t_v, t_u = i_v1+d[0], i_u1+d[1]\n                if t_v < rows and t_v >= 0 and t_u < cols and t_u >= 0:\n                    warp_img[t_v, t_u] = ref_img[i_v0, i_u0]\n    else:\n        warp_img[v1, u1] = ref_img[v0, u0]\n\n    if fix_img is not None:\n        fix_index = (warp_img.mean(axis=-1, keepdims=True)\n                     >= 255).__and__(dy_mask < 1)\n        fix_index[:rows//3, :, :] = True\n        fix_index = np.concatenate([fix_index, fix_index, fix_index], axis=-1)\n        warp_img[fix_index] = ref_img[fix_index]\n\n        fix_index = (warp_img.mean(axis=-1, keepdims=True) >= 255)\n        fix_index = np.concatenate([fix_index, fix_index, fix_index], axis=-1)\n        warp_img[fix_index] = fix_img[fix_index]\n\n    return warp_img\n\n\ndef occ_warp_img_seg(ori_u0, ori_v0, flow1, ori_dep_uv, ref_img, \\\n                    fix_img=None, dy_mask=None, use_blende=False, segments=None, idx=0):\n    \"\"\"\n    flow: 无变速\n    flow1: 变速\n    \"\"\"\n    # flow = flow.detach().cpu()\n    flow1 = flow1.detach().cpu().numpy()\n    ref_img = ref_img.permute(1, 2, 0).cpu().numpy()\n    # fix_img = fix_img.permute(1, 2, 0).cpu().numpy()\n    if dy_mask != None:\n        dy_mask = dy_mask.detach().cpu().numpy()\n\n    # segm filter\n    segments = F.interpolate(segments,size=img_size).squeeze(0).squeeze(0).int()\n    segments = segments.detach().cpu().numpy()\n    # print(np.unique(segments))\n    # big_car_mask = segments > 1000\n    # cv2.imwrite(str(idx) + '.png', big_car_mask*255)\n    # flow1[:,:,0] = flow1[:,:,0] * big_car_mask\n    # flow1[:,:,1] = flow1[:,:,1] * big_car_mask\n\n    # ----------------------------------------------------------------\n    rows, cols = flow1.shape[:2]\n    u1 = (ori_u0 + flow1[:, :, 0])\n    v1 = (ori_v0 + flow1[:, :, 1])\n\n    u0 = ori_u0.flatten()\n    v0 = ori_v0.flatten()\n    u1 = u1.flatten()\n    v1 = v1.flatten()\n\n    mm = (0 <= u1).__and__(u1 < cols).__and__(0 <= v1).__and__(v1 < rows)\n    u1, v1 = u1[mm], v1[mm]\n    u0, v0 = u0[mm], v0[mm]\n    dep_uv = ori_dep_uv[mm]\n\n    encode_uvu1v1 = np.stack([u0, v0, u1, v1], axis=-1)\n    df = pd.DataFrame(encode_uvu1v1, index=dep_uv).sort_index(ascending=False)\n    new_encode_uvu1v1 = df.to_numpy()\n\n    u0, v0 = new_encode_uvu1v1[:, 0], new_encode_uvu1v1[:, 1]\n    u1, v1 = new_encode_uvu1v1[:, 2], new_encode_uvu1v1[:, 3]\n\n    if use_blende:\n        u1, v1 = u1.astype(np.int32), v1.astype(np.int32)\n        u0, v0 = u0.astype(np.int32), v0.astype(np.int32)\n    else:\n        up_u1 = np.clip(np.ceil(u1), 0, cols-1).astype(np.int32)\n        up_v1 = np.clip(np.ceil(v1), 0, rows-1).astype(np.int32)\n        down_u1 = np.floor(u1).astype(np.int32)\n        down_v1 = np.floor(v1).astype(np.int32)\n        u1 = np.concatenate([up_u1, down_u1, up_u1, down_u1], 0)\n        v1 = np.concatenate([up_v1, down_v1, down_v1, up_v1], 0)\n        u0 = np.concatenate([u0, u0, u0, u0], 0).astype(np.int32)\n        v0 = np.concatenate([v0, v0, v0, v0], 0).astype(np.int32)\n\n    warp_segm = np.ones([rows, cols])\n    if use_blende:\n        direc = [[1, 0], [0, 1], [-1, 0], [0, -1],\n                [1, 1], [-1, -1], [1, -1], [-1, 1]]\n        for i in range(len(v1)):\n            i_v1, i_u1, i_v0, i_u0 = v1[i], u1[i], v0[i], u0[i]\n            warp_segm[i_v1, i_u1] = segments[i_v0, i_u0]\n            if i_v1 == i_v0 and i_u1 == i_u0:\n                continue\n            for d in direc:\n                t_v, t_u = i_v1+d[0], i_u1+d[1]\n                if t_v < rows and t_v >= 0 and t_u < cols and t_u >= 0:\n                    warp_segm[t_v, t_u] = segments[i_v0, i_u0]\n    else:\n        warp_segm[v1, u1] = segments[v0, u0]\n\n    # -------------------------------------\n    big_car_mask = warp_segm > 1000\n    cv2.imwrite(str(idx) + '.png', big_car_mask*255)\n    flow1[:,:,0] = flow1[:,:,0] * big_car_mask\n    flow1[:,:,1] = flow1[:,:,1] * big_car_mask\n\n    rows, cols = flow1.shape[:2]\n    u1 = (ori_u0 + flow1[:, :, 0])\n    v1 = (ori_v0 + flow1[:, :, 1])\n\n    u0 = ori_u0.flatten()\n    v0 = ori_v0.flatten()\n    u1 = u1.flatten()\n    v1 = v1.flatten()\n\n    mm = (0 <= u1).__and__(u1 < cols).__and__(0 <= v1).__and__(v1 < rows)\n    u1, v1 = u1[mm], v1[mm]\n    u0, v0 = u0[mm], v0[mm]\n    dep_uv = ori_dep_uv[mm]\n\n    encode_uvu1v1 = np.stack([u0, v0, u1, v1], axis=-1)\n    df = pd.DataFrame(encode_uvu1v1, index=dep_uv).sort_index(ascending=False)\n    new_encode_uvu1v1 = df.to_numpy()\n\n    u0, v0 = new_encode_uvu1v1[:, 0], new_encode_uvu1v1[:, 1]\n    u1, v1 = new_encode_uvu1v1[:, 2], new_encode_uvu1v1[:, 3]\n\n    if use_blende:\n        u1, v1 = u1.astype(np.int32), v1.astype(np.int32)\n        u0, v0 = u0.astype(np.int32), v0.astype(np.int32)\n    else:\n        up_u1 = np.clip(np.ceil(u1), 0, cols-1).astype(np.int32)\n        up_v1 = np.clip(np.ceil(v1), 0, rows-1).astype(np.int32)\n        down_u1 = np.floor(u1).astype(np.int32)\n        down_v1 = np.floor(v1).astype(np.int32)\n        u1 = np.concatenate([up_u1, down_u1, up_u1, down_u1], 0)\n        v1 = np.concatenate([up_v1, down_v1, down_v1, up_v1], 0)\n        u0 = np.concatenate([u0, u0, u0, u0], 0).astype(np.int32)\n        v0 = np.concatenate([v0, v0, v0, v0], 0).astype(np.int32)\n\n    #=====================================\n    \n    warp_img = np.ones([rows, cols, 3])*255\n    if use_blende:\n        direc = [[1, 0], [0, 1], [-1, 0], [0, -1],\n                [1, 1], [-1, -1], [1, -1], [-1, 1]]\n        for i in range(len(v1)):\n            i_v1, i_u1, i_v0, i_u0 = v1[i], u1[i], v0[i], u0[i]\n            warp_img[i_v1, i_u1] = ref_img[i_v0, i_u0]\n            if i_v1 == i_v0 and i_u1 == i_u0:\n                continue\n            for d in direc:\n                t_v, t_u = i_v1+d[0], i_u1+d[1]\n                if t_v < rows and t_v >= 0 and t_u < cols and t_u >= 0:\n                    warp_img[t_v, t_u] = ref_img[i_v0, i_u0]\n    else:\n        warp_img[v1, u1] = ref_img[v0, u0]\n\n\n    if fix_img is not None:\n        fix_index = (warp_img.mean(axis=-1, keepdims=True)\n                     >= 255).__and__(dy_mask < 1)\n        fix_index[:rows//3, :, :] = True\n        fix_index = np.concatenate([fix_index, fix_index, fix_index], axis=-1)\n        warp_img[fix_index] = ref_img[fix_index]\n\n        fix_index = (warp_img.mean(axis=-1, keepdims=True) >= 255)\n        fix_index = np.concatenate([fix_index, fix_index, fix_index], axis=-1)\n        warp_img[fix_index] = fix_img[fix_index]\n\n    return warp_img\n\n\ndef occ_warp_img_seg1(u0, v0, flow1, dep_uv, ref_img, fix_img=None, dy_mask=None,use_blende=False):\n    \"\"\"\n    flow: 无变速\n    flow1: 变速\n    \"\"\"\n    flow1 = flow1.detach().cpu().numpy()\n    ref_img = ref_img.permute(1, 2, 0).cpu().numpy()\n    if dy_mask != None:\n        dy_mask = dy_mask.detach().cpu().numpy()\n\n    rows, cols = flow1.shape[:2]\n\n    u1 = (u0 + flow1[:, :, 0])\n    v1 = (v0 + flow1[:, :, 1])\n\n    u0 = u0.flatten()\n    v0 = v0.flatten()\n    u1 = u1.flatten()\n    v1 = v1.flatten()\n\n    mm = (0 <= u1).__and__(u1 < cols).__and__(0 <= v1).__and__(v1 < rows)\n\n    u1, v1 = u1[mm], v1[mm]\n    u0, v0 = u0[mm], v0[mm]\n    dep_uv = dep_uv[mm]\n\n    encode_uvu1v1 = np.stack([u0, v0, u1, v1], axis=-1)\n    df = pd.DataFrame(encode_uvu1v1, index=dep_uv).sort_index(ascending=False)\n    new_encode_uvu1v1 = df.to_numpy()\n\n    u0, v0 = new_encode_uvu1v1[:, 0], new_encode_uvu1v1[:, 1]\n    u1, v1 = new_encode_uvu1v1[:, 2], new_encode_uvu1v1[:, 3]\n\n    if use_blende:\n        u1, v1 = u1.astype(np.int32), v1.astype(np.int32)\n        u0, v0 = u0.astype(np.int32), v0.astype(np.int32)\n    else:\n        up_u1 = np.clip(np.ceil(u1), 0, cols-1).astype(np.int32)\n        up_v1 = np.clip(np.ceil(v1), 0, rows-1).astype(np.int32)\n        down_u1 = np.floor(u1).astype(np.int32)\n        down_v1 = np.floor(v1).astype(np.int32)\n        u1 = np.concatenate([up_u1, down_u1, up_u1, down_u1], 0)\n        v1 = np.concatenate([up_v1, down_v1, down_v1, up_v1], 0)\n        u0 = np.concatenate([u0, u0, u0, u0], 0).astype(np.int32)\n        v0 = np.concatenate([v0, v0, v0, v0], 0).astype(np.int32)\n\n    warp_img = np.ones([rows, cols, 3])*255\n    \n    if use_blende:\n        direc = [[1, 0], [0, 1], [-1, 0], [0, -1],\n                [1, 1], [-1, -1], [1, -1], [-1, 1]]\n        for i in range(len(v1)):\n            i_v1, i_u1, i_v0, i_u0 = v1[i], u1[i], v0[i], u0[i]\n            warp_img[i_v1, i_u1] = ref_img[i_v0, i_u0]\n            if i_v1 == i_v0 and i_u1 == i_u0:\n                continue\n            for d in direc:\n                t_v, t_u = i_v1+d[0], i_u1+d[1]\n                if t_v < rows and t_v >= 0 and t_u < cols and t_u >= 0:\n                    warp_img[t_v, t_u] = ref_img[i_v0, i_u0]\n    else:\n        warp_img[v1, u1] = ref_img[v0, u0]\n\n    if fix_img is not None:\n        fix_index = (warp_img.mean(axis=-1, keepdims=True)\n                     >= 255).__and__(dy_mask < 1)\n        fix_index[:rows//3, :, :] = True\n        fix_index = np.concatenate([fix_index, fix_index, fix_index], axis=-1)\n        warp_img[fix_index] = ref_img[fix_index]\n\n        fix_index = (warp_img.mean(axis=-1, keepdims=True) >= 255)\n        fix_index = np.concatenate([fix_index, fix_index, fix_index], axis=-1)\n        warp_img[fix_index] = fix_img[fix_index]\n\n    return warp_img\n\nscene_id = 'Scene02'\nimg_size = [368, 1240]\n\nmax_fac = 5\nspeed_fac = []\nfor f in np.linspace(1, max_fac, 10):\n    speed_fac.append(f)\nfor f in np.linspace(1, max_fac, 10)[::-1]:\n    speed_fac.append(f)\nspeed_fac.append(0)\nfor f in np.linspace(1, max_fac, 10):\n    speed_fac.append(-f)\nfor f in np.linspace(1, max_fac, 10)[::-1]:\n    speed_fac.append(-f)\nspeed_fac.append(0)\n\ni_target = 158\ni_fix = 171\n# i_fix = 164\ntest_file = 'droid_slam/data_readers/vkitti2_test.txt'\nflow_label = True\ndirect_fix = True\nuse_blende = True\nuse_seg = True\n\nf = open(test_file)\ndata_readers.vkitti2.test_split = f.read().split()\nf.close()\n\nori_img_dir = osp.join('tools/edit-demo/results', scene_id, 'ori_img')\nwarp_img_dir = osp.join('tools/edit-demo/results', scene_id, 'warp_img')\nfix_img_dir = osp.join('tools/edit-demo/results', scene_id, 'fix_img')\nif not osp.exists(ori_img_dir):\n    os.makedirs(ori_img_dir)\nif not osp.exists(warp_img_dir):\n    os.makedirs(warp_img_dir)\nif not osp.exists(fix_img_dir):\n    os.makedirs(fix_img_dir)\n\ndb = dataset_factory(['vkitti2'], datapath='datasets/Virtual_KITTI2', do_aug=False,\n                     n_frames=2, flow_label=flow_label, aug_graph=False, split_mode='val',\n                     need_inv=False, build_mask=False, crop_size=img_size, mode='semisup', rebuild=False)\ntrain_loader = DataLoader(db, batch_size=1, num_workers=2)\n\nweights_file = \"/mnt/nas_8/group/yuxingyuan/Neural-iMAP/checkpoints/vkitti2_dy_train_semiv4_080000.pth\"\ndevice = 'cuda:0'\ntorch.cuda.set_device(int(device.split(':')[-1]))\n\ngraph = OrderedDict()\ngraph[0] = [1]\ngraph[1] = [0]\nii, jj, _ = graph_to_edge_list(graph)\n\nmodel = load_weights(weights_file, device)\ncoords0 = coords_grid(img_size[0], img_size[1], device=device)\n\nv = np.arange(img_size[0])\nv = v.reshape(img_size[0], 1)\nv = np.repeat(v, img_size[1], axis=1)\nu = np.arange(img_size[1])\nu = np.tile(u, (img_size[0], 1))\n\nv1, u1 = v.copy(), u.copy()\nv0, u0 = v.copy(), u.copy()\n\nfor i_batch, item in enumerate(train_loader):\n\n    if i_batch < i_target and i_batch >= i_target-20:  # 视频前半段，静止部分\n        images, _, _, _, _, _, _ = [x.to('cuda') for x in item]\n        images = resize(images, img_size, False)\n        ori_img = images[0, 0].permute(1, 2, 0).cpu().numpy().astype(np.uint8)\n        cv2.imwrite(osp.join(ori_img_dir, str(i_batch)+'.png'), ori_img)\n        print(\"1-----\",i_batch)\n        continue\n    elif i_batch < i_target-20:  # 删除过早的\n        continue\n    elif i_batch > i_target and i_batch < i_fix:\n        print(\"3-----\",i_batch)\n        continue\n    elif i_batch > i_fix:\n        break\n\n    if flow_label:\n        images, poses, disps, intrinsics, fo_flows, _, segments = [x.to('cuda') for x in item]\n        fo_flows = resize_flow(fo_flows, img_size)\n    else:\n        images, poses, disps, intrinsics, _, _ = [ x.to('cuda') for x in item]\n\n    hr, wr = img_size[0]/images.shape[3], img_size[1]/images.shape[4]\n    intrinsics[:, :, 0] *= wr\n    intrinsics[:, :, 2] *= wr\n    intrinsics[:, :, 1] *= hr\n    intrinsics[:, :, 3] *= hr\n    images = resize(images, img_size, False)\n    disps = resize(disps.unsqueeze(2), img_size, False).squeeze(2)\n\n    Gs = SE3(poses)\n    disp0 = disps[:, :, 3::8, 3::8]\n\n    if i_batch == i_target:\n\n        for _ in range(1):\n            poses_est, disps_est, residuals, full_flows, masks = \\\n                model(Gs, images, disp0, intrinsics/8,\n                      graph, num_steps=15, fixedp=2,\n                      ret_flow=True, downsample=True)\n\n        coords1, val0 = projective_transform(Gs, disps, intrinsics, ii, jj)\n\n        cam_flow = (coords1-coords0)[0, 0]\n        if flow_label:\n            full_flow = fo_flows[0, 0]\n        else:\n            full_flow = (upsample_inter(full_flows[-1]*8))[0, 0]\n\n        dy_flow = full_flow-cam_flow\n        dy_mask = (masks[-1][0, 0].mean(-1, keepdim=True) < 0.5).float()\n\n        # dynamic_flow = dy_flow.detach().cpu().numpy()\n        # dynamic_flow = cv2.resize(dynamic_flow, (375, 1242))\n        # np.save(('dy.npy'), dynamic_flow)\n\n        # dynamic_mask = dy_mask.detach().cpu().numpy()\n        # dynamic_mask = cv2.resize(dynamic_mask, (375, 1242))\n        # np.save(('dy_mask.npy'), dynamic_mask)\n\n        ref_disps_tar = disps[0, 0]\n        ref_depth_tar = torch.clamp(1/ref_disps_tar, 1e-3, 80)\n        ref_depth_tar = ref_depth_tar.detach().cpu().numpy()\n        dep_uv_tar = ref_depth_tar.flatten()\n        ref_img_tar = images[0, 0]\n        tar_poses = Gs\n\n    else:\n        print(\"begin cal motion\")\n        Gs.data[:, 1] = tar_poses.data[:, 0]\n        coords1, val0 = projective_transform( Gs, disps, intrinsics, ii, jj)\n\n        fix_flow = (coords1-coords0)[0, 0]\n        if direct_fix:\n            fix_flow = torch.zeros_like(fix_flow)\n\n        ref_disps_fix = disps[0, 0]\n        ref_depth_fix = torch.clamp(1/ref_disps_fix, 1e-3, 80)\n        ref_depth_fix = ref_depth_fix.detach().cpu().numpy()\n        dep_uv_fix = ref_depth_fix.flatten()\n        ref_img_fix = images[0, 0]\n\n        fix_img = occ_warp_img(u0, v0, fix_flow, dep_uv_fix, ref_img_fix)\n        cv2.imwrite(osp.join(fix_img_dir, '%d_%d.png' % (i_fix, i_target)), fix_img)\n\n        for i, fac in enumerate(speed_fac):\n            if use_seg:\n                warp_img = occ_warp_img_seg(u0, v0, dy_flow*fac,dep_uv_tar, ref_img_tar, \\\n                                    fix_img, dy_mask, use_blende=use_blende, segments=segments, idx=i)\n            else:\n                warp_img = occ_warp_img(u0, v0, dy_flow*fac,dep_uv_tar, ref_img_tar, \n                                    fix_img, dy_mask, use_blende=use_blende)\n            warp_img = warp_img.astype(np.uint8)\n            cv2.imwrite(osp.join(warp_img_dir, str(i_target)+'_%03d.png' % i), warp_img)\n            print('Finished warping %d img in speed factor %f' % (i_target, fac))\n\n        ori_img = ref_img_tar.permute(1, 2, 0).cpu().numpy().astype(np.uint8)\n        cv2.imwrite(osp.join(ori_img_dir, str(i_target)+'.png'), ori_img)\n"
  },
  {
    "path": "VO_Module/tools/vis_ori.py",
    "content": "import sys\nsys.path.append('droid_slam')\n\nimport torch\nfrom torch.utils.data import DataLoader\nimport glob\nimport os\nimport os.path as osp\nimport cv2\nimport numpy as np\nimport pandas as pd\nimport torch.nn.functional as F\nfrom scipy.spatial.transform import Rotation as R\nfrom collections import OrderedDict\nfrom lietorch import SE3\nfrom geom.projective_ops import projective_transform, coords_grid\nfrom geom.graph_utils import graph_to_edge_list\nfrom droid_net import DroidNet, upsample_inter\nfrom data_readers.factory import dataset_factory\nimport data_readers.vkitti2\n\n\ndef load_weights(weights, device):\n    \"\"\" load trained model weights \"\"\"\n    net = DroidNet()\n    state_dict = OrderedDict([\n        (k.replace(\"module.\", \"\"), v) for (k, v) in torch.load(weights, device).items()])\n    net.load_state_dict(state_dict)\n    return net.to(device).eval()\n\n\ndef resize(mask, size, need_permute):\n    if need_permute:\n        mask = mask.permute(0, 1, 4, 2, 3).contiguous()\n    batch, num, dim, ht, wd = mask.shape\n    mask = mask.view(batch*num, dim, ht, wd)\n    mask = F.interpolate(mask, size=size, mode='bilinear', align_corners=True)\n    if need_permute:\n        mask = mask.permute(0, 2, 3, 1).contiguous()\n        return mask.view(batch, num, size[0], size[1], dim)\n    else:\n        return mask.view(batch, num, dim, size[0], size[1])\n\n\ndef resize_flow(flow, size):\n    flow = flow.permute(0, 1, 4, 2, 3).contiguous()\n    batch, num, dim, ht, wd = flow.shape\n    flow = flow.view(batch*num, dim, ht, wd)\n    flow[:, 0, ...] /= wd\n    flow[:, 1, ...] /= ht\n    flow = F.interpolate(flow, size=size, mode='bilinear', align_corners=True)\n    flow[:, 0, ...] *= size[1]\n    flow[:, 1, ...] *= size[0]\n    flow = flow.permute(0, 2, 3, 1).contiguous()\n    return flow.view(batch, num, size[0], size[1], dim)\n\n\ndef occ_warp_img(u0, v0, flow1, dep_uv, ref_img, fix_img, dy_mask):\n\n    # flow = flow.detach().cpu()\n    flow1 = flow1.detach().cpu().numpy()\n    ref_img = ref_img.permute(1, 2, 0).cpu().numpy()\n    fix_img = fix_img.permute(1, 2, 0).cpu().numpy()\n    dy_mask = dy_mask.detach().cpu().numpy()\n\n    rows, cols = flow1.shape[:2]\n\n    # grid_uv=torch.from_numpy(np.concatenate([u0/(cols-1),v0/(rows-1)],axis=-1)).view(1,1,-1,2)\n    # grid_uv=grid_uv*2-1\n    # # sm_flow=F.grid_sample(flow,grid_uv,padding_mode=\"border\", align_corners=True).view(-1,2).numpy()\n    # sm_flow1=F.grid_sample(flow1,grid_uv,padding_mode=\"border\", align_corners=True).view(-1,2).numpy()\n    # # u,v=u+sm_flow[:,0],v+sm_flow[:,1]\n    # u1,v1=u0+sm_flow1[:,0],v0+sm_flow1[:,1]\n\n    u1 = (u0 + flow1[:, :, 0])\n    v1 = (v0 + flow1[:, :, 1])\n\n    u0 = u0.flatten()\n    v0 = v0.flatten()\n    u1 = u1.flatten()\n    v1 = v1.flatten()\n\n    # tu = (u + flow[v, u, 0]).astype(np.int32)\n    # tv = (v + flow[v, u, 1]).astype(np.int32)\n    # u, v = tu, tv\n\n    mm = (0 <= u1).__and__(u1 < cols).__and__(0 <= v1).__and__(v1 < rows)\n    # mm2 = (0 <= u).__and__(u < cols).__and__(0 <= v).__and__(v < rows)\n    # mm = mm1.__and__(mm2)\n    # u, v = u[mm], v[mm]\n    u1, v1 = u1[mm], v1[mm]\n    u0, v0 = u0[mm], v0[mm]\n    dep_uv = dep_uv[mm]\n\n    # encode_uvu1v1 = u0 * 1e14 + v0 * 1e10 + u1 * 1e6 + v1 * 1e2\n    encode_uvu1v1 = np.stack([u0, v0, u1, v1], axis=-1)\n    df = pd.DataFrame(encode_uvu1v1, index=dep_uv).sort_index(ascending=False)\n    new_encode_uvu1v1 = df.to_numpy()\n\n    # dic = dict(zip(encode_uvu1v1, dep_uv))\n    # ndic = np.array(\n    #     sorted(dic.items(), key=lambda item: item[1], reverse=True))\n    # new_encode_uvu1v1 = ndic[:, 0]\n\n    # u0 = (new_encode_uvu1v1 // 1e14).astype(np.int32)\n    # v0 = (new_encode_uvu1v1 % 1e14 // 1e10).astype(np.int32)\n    # u1 = (new_encode_uvu1v1 % 1e10 // 1e6).astype(np.int32)\n    # v1 = (new_encode_uvu1v1 % 1e6 // 1e2).astype(np.int32)\n\n    u0, v0 = new_encode_uvu1v1[:, 0], new_encode_uvu1v1[:, 1]\n    u1, v1 = new_encode_uvu1v1[:, 2], new_encode_uvu1v1[:, 3]\n\n    # grid_uv0 = torch.from_numpy(np.concatenate(\n    #     [u0/(cols-1), v0/(rows-1)], axis=-1)).view(1, 1, -1, 2)\n    # grid_uv0 = grid_uv0*2-1\n    # ref_pixs = F.grid_sample(ref_img.unsqueeze(\n    #     0).double(), grid_uv0, padding_mode=\"border\", align_corners=True).view(-1, 3).numpy()\n\n    u1 = np.clip(np.around(u1), 0, cols-1).astype(np.int32)\n    v1 = np.clip(np.around(v1), 0, rows-1).astype(np.int32)\n    warp_img = np.ones([rows, cols, 3])*255\n    # warp_img[v1, u1] = ref_pixs\n    warp_img[v1, u1] = ref_img[v0.astype(np.int32), u0.astype(np.int32)]\n\n    fix_index = (warp_img.mean(axis=-1, keepdims=True)\n                 >= 255).__and__(dy_mask < 1)\n    fix_index[:rows//3, :, :] = True\n    fix_index = np.concatenate([fix_index, fix_index, fix_index], axis=-1)\n    warp_img[fix_index] = fix_img[fix_index]\n\n    return warp_img\n\n\nscene_id = 'Scene02'\nimg_size = [368, 1240]\n\nmax_fac = 5\nspeed_fac = []\nfor f in np.linspace(1, max_fac, 10):\n    speed_fac.append(f)\nfor f in np.linspace(1, max_fac, 10)[::-1]:\n    speed_fac.append(f)\nspeed_fac.append(0)\nfor f in np.linspace(1, max_fac, 10):\n    speed_fac.append(-f)\nfor f in np.linspace(1, max_fac, 10)[::-1]:\n    speed_fac.append(-f)\nspeed_fac.append(0)\n\ni_start = 158\ni_end = i_start+1\ntest_file = 'droid_slam/data_readers/vkitti2_test.txt'\nflow_label = True\n\nf = open(test_file)\ndata_readers.vkitti2.test_split = f.read().split()\nf.close()\n\nori_img_dir = osp.join('tools/edit-demo/results', scene_id, 'ori_img')\nwarp_img_dir = osp.join('tools/edit-demo/results', scene_id, 'warp_img')\nif not osp.exists(ori_img_dir):\n    os.makedirs(ori_img_dir)\nif not osp.exists(warp_img_dir):\n    os.makedirs(warp_img_dir)\n\ndb = dataset_factory(['vkitti2'], datapath='datasets/Virtual_KITTI2', do_aug=False,\n                     n_frames=2, flow_label=flow_label, aug_graph=False, split_mode='val',\n                     need_inv=False, build_mask=False, crop_size=img_size, mode='semisup', rebuild=True)\ntrain_loader = DataLoader(db, batch_size=1, num_workers=2)\n\nweights_file = \"/mnt/nas_8/group/yuxingyuan/Neural-iMAP/checkpoints/vkitti2_dy_train_semiv4_080000.pth\"\ndevice = 'cuda:0'\ntorch.cuda.set_device(int(device.split(':')[-1]))\n\ngraph = OrderedDict()\ngraph[0] = [1]\ngraph[1] = [0]\nii, jj, _ = graph_to_edge_list(graph)\n\nmodel = load_weights(weights_file, device)\ncoords0 = coords_grid(img_size[0], img_size[1], device=device)\n\nv = np.arange(img_size[0])\nv = v.reshape(img_size[0], 1)\nv = np.repeat(v, img_size[1], axis=1)\nu = np.arange(img_size[1])\nu = np.tile(u, (img_size[0], 1))\n\nv1, u1 = v.copy(), u.copy()\nv0, u0 = v.copy(), u.copy()\n\nfor i_batch, item in enumerate(train_loader):\n    if i_batch < i_start and i_batch >= i_start-20:\n        images, _, _, _, _, _ = [x.to('cuda') for x in item]\n        images = resize(images, img_size, False)\n        ori_img = images[0, 0].permute(1, 2, 0).cpu().numpy().astype(np.uint8)\n        cv2.imwrite(osp.join(ori_img_dir, str(i_batch)+'.png'), ori_img)\n        continue\n    elif i_batch < i_start-20:\n        continue\n    elif i_batch == i_end:\n        break\n\n    if flow_label:\n        images, poses, disps, intrinsics, fo_flows, _ = [ x.to('cuda') for x in item]\n        fo_flows = resize_flow(fo_flows, img_size)\n    else:\n        images, poses, disps, intrinsics, _, _ = [x.to('cuda') for x in item]\n\n    hr, wr = img_size[0]/images.shape[3], img_size[1]/images.shape[4]\n    intrinsics[:, :, 0] *= wr\n    intrinsics[:, :, 2] *= wr\n    intrinsics[:, :, 1] *= hr\n    intrinsics[:, :, 3] *= hr\n    images = resize(images, img_size, False)\n    disps = resize(disps.unsqueeze(2), img_size, False).squeeze(2)\n\n    Gs = SE3(poses)\n    disp0 = disps[:, :, 3::8, 3::8]\n\n    for _ in range(1):\n        poses_est, disps_est, residuals, full_flows, masks = \\\n                model(Gs, images, disp0, intrinsics/8,\n                         graph, num_steps=15, fixedp=2,\n                        ret_flow=True, downsample=True)\n        # Gs = poses_est[-1]\n        # disp0 = disps_est[-1][:, :, 3::8, 3::8]\n\n    # coords1, val0 = projective_transform(\n    #     poses_est[-1], disps_est[-1], intrinsics, ii, jj)\n    coords1, val0 = projective_transform(Gs, disps, intrinsics, ii, jj)\n\n    cam_flow = (coords1-coords0)[0, 0]\n    if flow_label:\n        full_flow = fo_flows[0, 0]\n    else:\n        full_flow = (upsample_inter(full_flows[-1]*8))[0, 0]\n\n    dy_flow = full_flow-cam_flow\n    dy_mask = (masks[-1][0, 0].mean(-1, keepdim=True) < 0.5).float()\n\n    ref_depth = disps[0, 0]\n    ref_depth = torch.clamp(1/ref_depth, 1e-3, 80)\n    ref_depth = ref_depth.detach().cpu().numpy()\n    dep_uv = ref_depth.flatten()\n    ref_img = images[0, 0]\n\n    for i, fac in enumerate(speed_fac):\n        warp_img = occ_warp_img(u0, v0, dy_flow*fac, dep_uv, ref_img, images[0, 0], dy_mask)\n        warp_img = warp_img.astype(np.uint8)\n        cv2.imwrite(osp.join(warp_img_dir, str(i_batch)+'_%03d.png' % i), warp_img)\n        print('Finished warping %d img in speed factor %f' % (i_batch, fac))\n\n    ori_img = images[0, 0].permute(1, 2, 0).cpu().numpy().astype(np.uint8)\n    cv2.imwrite(osp.join(ori_img_dir, str(i_batch)+'.png'), ori_img)\n"
  },
  {
    "path": "VO_Module/train.py",
    "content": "import os\nos.environ[\"KMP_DUPLICATE_LIB_OK\"] = \"TRUE\"\n# os.environ[\"OMP_NUM_THREADS\"] = \"2\"\n# os.environ[\"MKL_NUM_THREADS\"] = \"2\"\n\nimport sys\nsys.path.append('VO_Module/droid_slam')\n\nimport cv2\nimport numpy as np\nfrom collections import OrderedDict\n\nimport torch\nimport torch.optim as optim\nimport torch.nn as nn\nfrom torch.utils.data import DataLoader\nfrom data_readers.factory import dataset_factory\n\nfrom lietorch import SO3, SE3, Sim3\nfrom geom import losses\nfrom geom.graph_utils import build_frame_graph\n\n# Network\nfrom droid_net import DroidNet\nfrom logger import Logger\n\n# DDP training\nfrom torch.nn.parallel import DistributedDataParallel as DDP\nimport torch.distributed as dist\nimport torch.multiprocessing as mp\n\n\ndef setup_ddp(index, gpu, args):\n    dist.init_process_group(\n        backend='nccl',\n        init_method='env://',\n        world_size=args.world_size,\n        rank=index)\n\n    torch.manual_seed(0)\n    torch.cuda.set_device(gpu)\n\n\ndef show_image(image):\n    image = image.permute(1, 2, 0).cpu().numpy()\n    cv2.imshow('image', image / 255.0)\n    cv2.waitKey()\n\n\ndef train(index, args):\n    \"\"\" Test to make sure project transform correctly maps points \"\"\"\n    # torch.autograd.set_detect_anomaly(True)\n    gpu = int(args.gpus.split(',')[index])\n\n    # coordinate multiple GPUs\n    setup_ddp(index, gpu, args)\n    rng = np.random.default_rng(12345)\n\n    N = args.n_frames\n    model = DroidNet(args.use_aff_bri)\n    model.cuda()\n    model.train()\n\n    model = DDP(model, device_ids=[gpu], find_unused_parameters=False)\n    ssim = losses.SSIM().to('cuda') if args.ssim is True else None\n\n    if args.ckpt is not None:\n        model.load_state_dict(torch.load(\n            args.ckpt, map_location='cuda:'+str(gpu)))\n\n    # fetch dataloader\n    # vkitti2\n    # sup 240, 808\n    # semisup 216, 720(ssim in ph_cam), 240, 808(no ssim)\n    # unsup 216, 720\n    # tartan\n    # ori 384, 512\n    # semisup 344, 464\n    print('loading datasets -----------------------')\n    db = dataset_factory(['vkitti2'], datapath=args.datapath,\n                         n_frames=args.n_frames, fmin=args.fmin, fmax=args.fmax,\n                        #  crop_size=[216, 720], flow_label=args.flow_label,\n                         crop_size=[200, 400], flow_label=args.flow_label,\n                         aug_graph=args.aug_graph, need_inv=args.need_inv,\n                         mode=args.mode)\n\n    train_sampler = torch.utils.data.distributed.DistributedSampler(\n        db, shuffle=True, num_replicas=args.world_size, rank=index)\n\n    train_loader = DataLoader(\n        db, batch_size=args.batch, sampler=train_sampler, num_workers=2)\n\n    # fetch optimizer\n    # args.lr = args.lr / args.gpu_num\n    optimizer = torch.optim.Adam(\n        model.parameters(), lr=args.lr, weight_decay=1e-5)\n    scheduler = torch.optim.lr_scheduler.OneCycleLR(optimizer,\n                                                    args.lr, args.steps, pct_start=0.01, cycle_momentum=False)\n\n    logger = Logger(args.name, scheduler)\n    should_keep_training = True\n    total_steps = 0\n\n    while should_keep_training:\n        for i_batch, item in enumerate(train_loader):\n            optimizer.zero_grad()\n\n            if args.flow_label:\n                images, poses, disps, intrinsics, \\\n                    fo_flows, ba_flows, \\\n                    fo_masks, ba_masks = [x.to('cuda') for x in item]\n            elif args.mode == 'sup':\n                images, poses, disps, intrinsics,\\\n                    gt_masks, gt_vals = [x.to('cuda') for x in item]\n            elif args.mode == 'semisup':\n                images, poses, disps, intrinsics,\\\n                    gt_masks, gt_vals, segments = [x.to('cuda') for x in item]\n            elif args.mode == 'unsup':\n                images, poses, disps, intrinsics = [x.to('cuda') for x in item]\n\n            # convert poses w2c -> c2w\n            # use w2c for vkitti2, which don't have to inv\n            if args.need_inv:\n                Ps = SE3(poses).inv()\n            else: # False\n                Ps = SE3(poses)\n            Gs = SE3.IdentityLike(Ps)\n\n            if args.aug_graph: # True\n                if np.random.rand() < 0.5:\n                    graph = build_frame_graph(\n                        poses, disps, intrinsics, num=args.edges,\n                        need_inv=args.need_inv)\n                else:\n                    graph = OrderedDict()\n                    for i in range(N):\n                        graph[i] = [j for j in range(\n                            N) if i != j and abs(i-j) <= 2]\n            else:\n                graph = OrderedDict()\n                for i in range(N):\n                    graph[i] = [j for j in range(N) if abs(i-j) == 1]\n\n            # fix first to camera poses\n            Gs.data[:, 0] = Ps.data[:, 0].clone()\n            Gs.data[:, 1:] = Ps.data[:, [1]].clone()\n            disp0 = torch.ones_like(disps[:, :, 3::8, 3::8])\n\n            # perform random restarts\n            r = 0\n            while r < args.restart_prob:\n                r = rng.random()\n\n                intrinsics0 = intrinsics / 8.0\n                if args.flow_label or args.ph_loss: # True\n                    if args.use_aff_bri:\n                        poses_est, disps_est, residuals, full_flows, masks, aff_params = \\\n                            model(Gs, images, disp0, intrinsics0,\n                                  graph, num_steps=args.iters, fixedp=2,\n                                  ret_flow=True, downsample=args.downsample)\n                    else: # False\n                        poses_est, disps_est, residuals, full_flows, masks = \\\n                            model(Gs, images, disp0, intrinsics0,\n                                  graph, num_steps=args.iters, fixedp=2,\n                                  ret_flow=True, downsample=args.downsample, segments=segments)\n                        aff_params = None\n                else:\n                    poses_est, disps_est, residuals, masks = \\\n                        model(Gs, images, disp0, intrinsics0,\n                              graph, num_steps=args.iters, fixedp=2, ret_flow=False)\n\n                geo_loss, cam_f_loss = 0, 0\n                gt_l_loss = 0\n                flo_loss = 0\n                cam_ph_loss = 0\n                al_loss = 0\n\n                if args.mode == 'sup':\n                    geo_loss, geo_metrics = losses.geodesic_loss(\n                        Ps, poses_est, graph, do_scale=False)\n                    cam_f_loss, cam_f_metrics = losses.cam_flow_loss(\n                        Ps, disps, poses_est, disps_est, intrinsics, graph)\n                    gt_l_loss, gt_l_metrics = losses.gt_label_loss(\n                        gt_masks, gt_vals, masks, graph)\n                    if args.flow_label:\n                        flo_loss, flo_metrics = losses.flow_loss(\n                            fo_flows, ba_flows, full_flows, graph)\n\n                elif args.mode == 'semisup':\n                    cam_ph_loss, cam_ph_metrics = losses.photo_loss_cam(\n                        images, poses_est, disps_est, intrinsics, graph, args.mode, gt_masks, ssim=ssim)\n                    gt_l_loss, gt_l_metrics = losses.gt_label_loss(\n                        gt_masks, gt_vals, masks, graph)\n\n                elif args.mode == 'unsup':\n                    art_masks = losses.unsup_art_label(\n                        poses_est, disps_est, intrinsics, full_flows, graph, downsample=args.downsample)\n\n                    use_one = False if i_batch > args.steps * \\\n                        (3/4) and args.occ_ph else True\n                    ph_vals = losses.unsup_occ_vals(\n                        poses_est, disps_est, intrinsics, args.downsample, graph,\n                        'ph_loss', use_one=use_one)\n                    cam_ph_vals = losses.unsup_occ_vals(\n                        poses_est, disps_est, intrinsics, False, None,\n                        'cam_ph_loss', use_one=use_one)\n\n                    cam_ph_loss, cam_ph_metrics = losses.photo_loss_cam(\n                        images, poses_est, disps_est, intrinsics, graph, args.mode, cam_ph_vals, ssim=ssim)\n                    al_loss, al_metric = losses.art_label_loss(\n                        art_masks, masks, downsample=args.downsample)\n\n                else:\n                    raise Exception('ERROR: Unknown mode!')\n\n                ph_loss = 0\n                if args.ph_loss: # True\n                    if args.mode == 'sup':\n                        ph_loss, ph_metrics = losses.photo_loss(\n                            images, full_flows, gt_vals, graph, args.mode, ssim=None,\n                            aff_params=aff_params, downsample=args.downsample)\n                    elif args.mode == 'semisup':\n                        if args.occ_ph and i_batch > args.steps*(3/4):\n                            ph_vals = losses.unsup_occ_vals(\n                                poses_est, disps_est, intrinsics, args.downsample, graph, 'ph_loss')\n                            ph_vals = losses.unsup_dy_vals(\n                                ph_vals, gt_masks, graph)\n                            ph_loss, ph_metrics = losses.photo_loss(\n                                images, full_flows, ph_vals, graph, 'unsup', ssim=None,\n                                aff_params=aff_params, downsample=args.downsample)\n                        else:\n                            ph_loss, ph_metrics = losses.photo_loss(\n                                images, full_flows, gt_vals, graph, args.mode, ssim=None,\n                                aff_params=aff_params, downsample=args.downsample)\n                    else:\n                        if use_one:\n                            ph_loss, ph_metrics = losses.photo_loss(\n                                images, full_flows, ph_vals, graph, args.mode, ssim=None,\n                                aff_params=aff_params, downsample=args.downsample)\n                        else:\n                            ph_vals = losses.unsup_dy_vals(\n                                ph_vals, art_masks, graph)\n                            ph_loss, ph_metrics = losses.photo_loss(\n                                images, full_flows, ph_vals, graph, args.mode, ssim=None,\n                                aff_params=aff_params, downsample=args.downsample)\n\n                res_loss, res_metrics = losses.residual_loss(residuals)\n\n                ce_loss = 0\n                if args.ce_reg: # False\n                    ce_loss, ce_metric = losses.ce_reg_loss(masks)\n                con_loss = 0\n                if args.con_loss: # Falses\n                    con_loss, con_metric = losses.consistency_loss(\n                        masks, args.n_frames, graph)\n\n                loss = args.w1 * geo_loss + args.w2 * res_loss + \\\n                    args.w3 * cam_f_loss + args.w4 * ph_loss + \\\n                    args.w5 * ce_loss + args.w6 * al_loss + \\\n                    args.w10 * cam_ph_loss + args.w7 * con_loss + \\\n                    args.w8 * flo_loss + args.w9 * gt_l_loss\n                loss.backward()\n\n                Gs = poses_est[-1].detach()\n                disp0 = disps_est[-1][:, :, 3::8, 3::8].detach()\n\n            metrics = {}\n            metrics.update(res_metrics)\n            if args.ph_loss: # True\n                metrics.update(ph_metrics)\n\n            if args.mode == 'sup':\n                metrics.update(geo_metrics)\n                metrics.update(cam_f_metrics)\n                metrics.update(gt_l_metrics)\n                if args.flow_label:\n                    metrics.update(flo_metrics)\n\n            elif args.mode == 'semisup':\n                metrics.update(cam_ph_metrics)\n                metrics.update(gt_l_metrics)\n\n            elif args.mode == 'unsup':\n                metrics.update(cam_ph_metrics)\n                metrics.update(al_metric)\n\n            if args.ce_reg:\n                metrics.update(ce_metric)\n            if args.con_loss:\n                metrics.update(con_metric)\n\n            torch.nn.utils.clip_grad_norm_(model.parameters(), args.clip)\n            optimizer.step()\n            scheduler.step()\n\n            total_steps += 1\n\n            if gpu == int(args.gpus.split(',')[0]):\n                logger.push(metrics)\n\n            if total_steps % 2000 == 0 and gpu == int(args.gpus.split(',')[0]):\n                PATH = 'checkpoints/%s_%06d.pth' % (args.name, total_steps)\n                torch.save(model.state_dict(), PATH)\n\n            if total_steps >= args.steps:\n                should_keep_training = False\n                break\n\n    if gpu == int(args.gpus.split(',')[0]):\n        final_path = 'checkpoints/%s_final.pth' % (args.name)\n        torch.save(model.state_dict(), final_path)\n\n    dist.destroy_process_group()\n\n\nif __name__ == '__main__':\n    import argparse\n    parser = argparse.ArgumentParser()\n    parser.add_argument('--name', default='vkitti2_dy_train',\n                        help='name your experiment')\n    parser.add_argument('--datapath', default='datasets/Virtual_KITTI2',\n                        help=\"path to dataset directory\")\n    parser.add_argument('--need_inv', type=bool, default=False,\n                        help='vkitti2 doesn\\'t need inv poses, tartanair needs it')\n    parser.add_argument('--gpus', type=str, default='0,1')\n    parser.add_argument('--mode', type=str, default='semisup',\n                        help='mode in sup,semisup,unsup')\n    # 0.00025 when 4 gpus, total 0.001\n    # also depend on steps\n    parser.add_argument('--lr', type=float, default=0.0005)\n    parser.add_argument('--steps', type=int, default=20000)\n    parser.add_argument('--occ_ph', type=bool, default=False,\n                        help='use occ detection in semisup ph_loss')\n\n    parser.add_argument('--ckpt', help='checkpoint to restore')\n    parser.add_argument('--datasets', nargs='+',\n                        help='lists of datasets for training')\n    parser.add_argument('--flow_label', type=bool, default=False,\n                        help='use gt flow data when training')\n    parser.add_argument('--aug_graph', type=bool, default=True,\n                        help='use droid method to get training graph')\n    parser.add_argument('--use_aff_bri', type=bool, default=False,\n                        help='brightness transformation parameters')\n    parser.add_argument('--downsample', type=bool, default=True,\n                        help='use not upsampled flows in ph_loss')\n    parser.add_argument('--ssim', type=bool, default=True,\n                        help='use ssim metric in ph_loss')\n\n    parser.add_argument('--ce_reg', type=bool, default=False,\n                        help='use ce regularization in masks')\n    parser.add_argument('--con_loss', type=bool, default=False,\n                        help='use consistency loss for dynamic masks')\n    parser.add_argument('--ph_loss', type=bool, default=True )\n    parser.add_argument('--batch', type=int, default=1)\n    parser.add_argument('--iters', type=int, default=15)\n    parser.add_argument('--clip', type=float, default=2.5)\n    # 7\n    parser.add_argument('--n_frames', type=int, default=6)\n\n    # sup w\n    # 10\n    parser.add_argument('--w1', type=float, default=40.0, help='geo_loss')\n    # 0.05\n    parser.add_argument('--w3', type=float, default=0.20, help='cam_f_loss')\n    # TODO: 0.01->0.05\n    parser.add_argument('--w9', type=float, default=0.01, help='gt_l_loss')\n    # semisup w\n    # TODO: 10->5\n    parser.add_argument('--w10', type=float, default=100.0, help='cam_ph_loss')\n    # unsup w\n    parser.add_argument('--w6', type=float, default=0.05, help='al_loss')\n\n    parser.add_argument('--w4', type=float, default=5.0, help='ph_loss')\n    parser.add_argument('--w2', type=float, default=0.01, help='res_loss')\n\n    parser.add_argument('--w5', type=float, default=0.001, help='ce_loss')\n    parser.add_argument('--w7', type=float, default=0.01, help='con_loss')\n    parser.add_argument('--w8', type=float, default=0.05, help='flo_loss')\n\n    parser.add_argument('--fmin', type=float, default=8.0)\n    # 96\n    parser.add_argument('--fmax', type=float, default=96.0)\n    parser.add_argument('--noise', action='store_true')\n    parser.add_argument('--scale', action='store_true')\n    # 24\n    parser.add_argument('--edges', type=int, default=20)\n    parser.add_argument('--restart_prob', type=float, default=0.2)\n\n    import os\n    if not os.path.isdir('checkpoints'):\n        os.mkdir('checkpoints')\n\n    args = parser.parse_args()\n    args.world_size = len(args.gpus.split(','))\n    args.gpu_num = len(args.gpus.split(','))\n    print(args)\n\n    os.environ['MASTER_ADDR'] = 'localhost'\n    os.environ['MASTER_PORT'] = '12356'\n    mp.spawn(train, nprocs=args.gpu_num, args=(args,))\n"
  },
  {
    "path": "VPS_Module/.circleci/config.yml",
    "content": "version: 2.1\n\n# -------------------------------------------------------------------------------------\n# Environments to run the jobs in\n# -------------------------------------------------------------------------------------\ncpu: &cpu\n  machine:\n    image: ubuntu-2004:202107-02\n  resource_class: medium\n\ngpu: &gpu\n  machine:\n    # NOTE: use a cuda vesion that's supported by all our pytorch versions\n    image: ubuntu-1604-cuda-11.1:202012-01\n  resource_class: gpu.nvidia.small\n\nwindows-cpu: &windows_cpu\n  machine:\n    resource_class: windows.medium\n    image: windows-server-2019-vs2019:stable\n    shell: powershell.exe\n\n# windows-gpu: &windows_gpu\n#     machine:\n#       resource_class: windows.gpu.nvidia.medium\n#       image: windows-server-2019-nvidia:stable\n\nversion_parameters: &version_parameters\n  parameters:\n    pytorch_version:\n      type: string\n    torchvision_version:\n      type: string\n    pytorch_index:\n      type: string\n      # use test wheels index to have access to RC wheels\n      # https://download.pytorch.org/whl/test/torch_test.html\n      default: \"https://download.pytorch.org/whl/torch_stable.html\"\n    python_version:  # NOTE: only affect linux\n      type: string\n      default: '3.6.8'\n\n  environment:\n    PYTORCH_VERSION: << parameters.pytorch_version >>\n    TORCHVISION_VERSION: << parameters.torchvision_version >>\n    PYTORCH_INDEX: << parameters.pytorch_index >>\n    PYTHON_VERSION: << parameters.python_version>>\n    # point datasets to ~/.torch so it's cached in CI\n    DETECTRON2_DATASETS: ~/.torch/datasets\n\n# -------------------------------------------------------------------------------------\n# Re-usable commands\n# -------------------------------------------------------------------------------------\n# install_nvidia_driver: &install_nvidia_driver\n#   - run:\n#       name: Install nvidia driver\n#       working_directory: ~/\n#       command: |\n#         wget -q 'https://s3.amazonaws.com/ossci-linux/nvidia_driver/NVIDIA-Linux-x86_64-430.40.run'\n#         sudo /bin/bash ./NVIDIA-Linux-x86_64-430.40.run -s --no-drm\n#         nvidia-smi\n\nadd_ssh_keys: &add_ssh_keys\n  # https://circleci.com/docs/2.0/add-ssh-key/\n  - add_ssh_keys:\n      fingerprints:\n        - \"e4:13:f2:22:d4:49:e8:e4:57:5a:ac:20:2f:3f:1f:ca\"\n\ninstall_python: &install_python\n  - run:\n      name: Install Python\n      working_directory: ~/\n      command: |\n        # upgrade pyenv\n        cd /opt/circleci/.pyenv/plugins/python-build/../.. && git pull && cd -\n        pyenv install -s $PYTHON_VERSION\n        pyenv global $PYTHON_VERSION\n        python --version\n        which python\n        pip install --upgrade pip\n\nsetup_venv: &setup_venv\n  - run:\n      name: Setup Virtual Env\n      working_directory: ~/\n      command: |\n        python -m venv ~/venv\n        echo \". ~/venv/bin/activate\" >> $BASH_ENV\n        . ~/venv/bin/activate\n        python --version\n        which python\n        which pip\n        pip install --upgrade pip\n\nsetup_venv_win: &setup_venv_win\n  - run:\n      name: Setup Virutal Env for Windows\n      command: |\n        pip install virtualenv\n        python -m virtualenv env\n        .\\env\\Scripts\\activate\n        python --version\n        which python\n        which pip\n\ninstall_linux_dep: &install_linux_dep\n  - run:\n      name: Install Dependencies\n      command: |\n        # disable crash coredump, so unittests fail fast\n        sudo systemctl stop apport.service\n        # install from github to get latest; install iopath first since fvcore depends on it\n        pip install --progress-bar off -U 'git+https://github.com/facebookresearch/iopath'\n        pip install --progress-bar off -U 'git+https://github.com/facebookresearch/fvcore'\n        # Don't use pytest-xdist: cuda tests are unstable under multi-process workers.\n        pip install --progress-bar off ninja opencv-python-headless pytest tensorboard pycocotools\n        pip install --progress-bar off torch==$PYTORCH_VERSION -f $PYTORCH_INDEX\n        if [[ \"$TORCHVISION_VERSION\" == \"master\" ]]; then\n          pip install git+https://github.com/pytorch/vision.git\n        else\n          pip install --progress-bar off torchvision==$TORCHVISION_VERSION -f $PYTORCH_INDEX\n        fi\n\n        python -c 'import torch; print(\"CUDA:\", torch.cuda.is_available())'\n        gcc --version\n\ninstall_detectron2: &install_detectron2\n  - run:\n      name: Install Detectron2\n      command: |\n        # Remove first, in case it's in the CI cache\n        pip uninstall -y detectron2\n        pip install --progress-bar off -e .[all]\n        python -m detectron2.utils.collect_env\n        ./datasets/prepare_for_tests.sh\n\nrun_unittests: &run_unittests\n  - run:\n      name: Run Unit Tests\n      command: |\n        pytest -v --durations=15 tests  # parallel causes some random failures\n\n# -------------------------------------------------------------------------------------\n# Jobs to run\n# -------------------------------------------------------------------------------------\njobs:\n  linux_cpu_tests:\n    <<: *cpu\n    <<: *version_parameters\n\n    working_directory: ~/detectron2\n\n    steps:\n      - checkout\n\n      # Cache the venv directory that contains python, dependencies, and checkpoints\n      # Refresh the key when dependencies should be updated (e.g. when pytorch releases)\n      - restore_cache:\n          keys:\n            - cache-{{ arch }}-<< parameters.pytorch_version >>-{{ .Branch }}-20210827\n\n      - <<: *install_python\n      - <<: *install_linux_dep\n      - <<: *install_detectron2\n      - <<: *run_unittests\n\n      - save_cache:\n          paths:\n            - /opt/circleci/.pyenv\n            - ~/.torch\n          key: cache-{{ arch }}-<< parameters.pytorch_version >>-{{ .Branch }}-20210827\n\n\n  linux_gpu_tests:\n    <<: *gpu\n    <<: *version_parameters\n\n    working_directory: ~/detectron2\n\n    steps:\n      - checkout\n\n      - restore_cache:\n          keys:\n            - cache-{{ arch }}-<< parameters.pytorch_version >>-{{ .Branch }}-20210827\n\n      - <<: *install_python\n      - <<: *install_linux_dep\n      - <<: *install_detectron2\n      - <<: *run_unittests\n\n      - save_cache:\n          paths:\n            - /opt/circleci/.pyenv\n            - ~/.torch\n          key: cache-{{ arch }}-<< parameters.pytorch_version >>-{{ .Branch }}-20210827\n\n  windows_cpu_build:\n    <<: *windows_cpu\n    <<: *version_parameters\n    steps:\n      - <<: *add_ssh_keys\n      - checkout\n      - <<: *setup_venv_win\n\n      # Cache the env directory that contains dependencies\n      - restore_cache:\n          keys:\n            - cache-{{ arch }}-<< parameters.pytorch_version >>-{{ .Branch }}-20210404\n\n      - run:\n          name: Install Dependencies\n          command: |\n            pip install certifi --ignore-installed  # required on windows to workaround some cert issue\n            pip install numpy cython  # required on windows before pycocotools\n            pip install opencv-python-headless pytest-xdist pycocotools tensorboard\n            pip install -U git+https://github.com/facebookresearch/iopath\n            pip install -U git+https://github.com/facebookresearch/fvcore\n            pip install torch==$env:PYTORCH_VERSION torchvision==$env:TORCHVISION_VERSION -f $env:PYTORCH_INDEX\n\n      - save_cache:\n          paths:\n            - env\n          key: cache-{{ arch }}-<< parameters.pytorch_version >>-{{ .Branch }}-20210404\n\n      - <<: *install_detectron2\n      # TODO: unittest fails for now\n\nworkflows:\n  version: 2\n  regular_test:\n    jobs:\n      - linux_cpu_tests:\n          name: linux_cpu_tests_pytorch1.10\n          pytorch_version: '1.10.0+cpu'\n          torchvision_version: '0.11.1+cpu'\n      - linux_gpu_tests:\n          name: linux_gpu_tests_pytorch1.8\n          pytorch_version: '1.8.1+cu111'\n          torchvision_version: '0.9.1+cu111'\n      - linux_gpu_tests:\n          name: linux_gpu_tests_pytorch1.9\n          pytorch_version: '1.9+cu111'\n          torchvision_version: '0.10+cu111'\n      - linux_gpu_tests:\n          name: linux_gpu_tests_pytorch1.10\n          pytorch_version: '1.10+cu111'\n          torchvision_version: '0.11.1+cu111'\n      - linux_gpu_tests:\n          name: linux_gpu_tests_pytorch1.10_python39\n          pytorch_version: '1.10+cu111'\n          torchvision_version: '0.11.1+cu111'\n          python_version: '3.9.6'\n      - windows_cpu_build:\n          pytorch_version: '1.10+cpu'\n          torchvision_version: '0.11.1+cpu'\n"
  },
  {
    "path": "VPS_Module/.clang-format",
    "content": "AccessModifierOffset: -1\nAlignAfterOpenBracket: AlwaysBreak\nAlignConsecutiveAssignments: false\nAlignConsecutiveDeclarations: false\nAlignEscapedNewlinesLeft: true\nAlignOperands:   false\nAlignTrailingComments: false\nAllowAllParametersOfDeclarationOnNextLine: false\nAllowShortBlocksOnASingleLine: false\nAllowShortCaseLabelsOnASingleLine: false\nAllowShortFunctionsOnASingleLine: Empty\nAllowShortIfStatementsOnASingleLine: false\nAllowShortLoopsOnASingleLine: false\nAlwaysBreakAfterReturnType: None\nAlwaysBreakBeforeMultilineStrings: true\nAlwaysBreakTemplateDeclarations: true\nBinPackArguments: false\nBinPackParameters: false\nBraceWrapping:\n  AfterClass:      false\n  AfterControlStatement: false\n  AfterEnum:       false\n  AfterFunction:   false\n  AfterNamespace:  false\n  AfterObjCDeclaration: false\n  AfterStruct:     false\n  AfterUnion:      false\n  BeforeCatch:     false\n  BeforeElse:      false\n  IndentBraces:    false\nBreakBeforeBinaryOperators: None\nBreakBeforeBraces: Attach\nBreakBeforeTernaryOperators: true\nBreakConstructorInitializersBeforeComma: false\nBreakAfterJavaFieldAnnotations: false\nBreakStringLiterals: false\nColumnLimit:     80\nCommentPragmas:  '^ IWYU pragma:'\nConstructorInitializerAllOnOneLineOrOnePerLine: true\nConstructorInitializerIndentWidth: 4\nContinuationIndentWidth: 4\nCpp11BracedListStyle: true\nDerivePointerAlignment: false\nDisableFormat:   false\nForEachMacros:   [ FOR_EACH, FOR_EACH_R, FOR_EACH_RANGE, ]\nIncludeCategories:\n  - Regex:           '^<.*\\.h(pp)?>'\n    Priority:        1\n  - Regex:           '^<.*'\n    Priority:        2\n  - Regex:           '.*'\n    Priority:        3\nIndentCaseLabels: true\nIndentWidth:     2\nIndentWrappedFunctionNames: false\nKeepEmptyLinesAtTheStartOfBlocks: false\nMacroBlockBegin: ''\nMacroBlockEnd:   ''\nMaxEmptyLinesToKeep: 1\nNamespaceIndentation: None\nObjCBlockIndentWidth: 2\nObjCSpaceAfterProperty: false\nObjCSpaceBeforeProtocolList: false\nPenaltyBreakBeforeFirstCallParameter: 1\nPenaltyBreakComment: 300\nPenaltyBreakFirstLessLess: 120\nPenaltyBreakString: 1000\nPenaltyExcessCharacter: 1000000\nPenaltyReturnTypeOnItsOwnLine: 200\nPointerAlignment: Left\nReflowComments:  true\nSortIncludes:    true\nSpaceAfterCStyleCast: false\nSpaceBeforeAssignmentOperators: true\nSpaceBeforeParens: ControlStatements\nSpaceInEmptyParentheses: false\nSpacesBeforeTrailingComments: 1\nSpacesInAngles:  false\nSpacesInContainerLiterals: true\nSpacesInCStyleCastParentheses: false\nSpacesInParentheses: false\nSpacesInSquareBrackets: false\nStandard:        Cpp11\nTabWidth:        8\nUseTab:          Never\n"
  },
  {
    "path": "VPS_Module/.flake8",
    "content": "# This is an example .flake8 config, used when developing *Black* itself.\n# Keep in sync with setup.cfg which is used for source packages.\n\n[flake8]\nignore = W503, E203, E221, C901, C408, E741, C407, B017\nmax-line-length = 100\nmax-complexity = 18\nselect = B,C,E,F,W,T4,B9\nexclude = build\nper-file-ignores =\n  **/__init__.py:F401,F403,E402\n  **/configs/**.py:F401,E402\n  configs/**.py:F401,E402\n  **/tests/config/**.py:F401,E402\n  tests/config/**.py:F401,E402\n"
  },
  {
    "path": "VPS_Module/README.md",
    "content": "# Use Builtin Datasets\n\nA dataset can be used by accessing [DatasetCatalog](https://detectron2.readthedocs.io/modules/data.html#detectron2.data.DatasetCatalog)\nfor its data, or [MetadataCatalog](https://detectron2.readthedocs.io/modules/data.html#detectron2.data.MetadataCatalog) for its metadata (class names, etc).\nThis document explains how to setup the builtin datasets so they can be used by the above APIs.\n[Use Custom Datasets](https://detectron2.readthedocs.io/tutorials/datasets.html) gives a deeper dive on how to use `DatasetCatalog` and `MetadataCatalog`,\nand how to add new datasets to them.\n\nDetectron2 has builtin support for a few datasets.\nThe datasets are assumed to exist in a directory specified by the environment variable\n`DETECTRON2_DATASETS`.\nUnder this directory, detectron2 will look for datasets in the structure described below, if needed.\n```\n$DETECTRON2_DATASETS/\n  coco/\n  lvis/\n  cityscapes/\n  VOC20{07,12}/\n```\n\nYou can set the location for builtin datasets by `export DETECTRON2_DATASETS=/path/to/datasets`.\nIf left unset, the default is `./datasets` relative to your current working directory.\n\nThe [model zoo](https://github.com/facebookresearch/detectron2/blob/master/MODEL_ZOO.md)\ncontains configs and models that use these builtin datasets.\n\n## Expected dataset structure for [COCO instance/keypoint detection](https://cocodataset.org/#download):\n\n```\ncoco/\n  annotations/\n    instances_{train,val}2017.json\n    person_keypoints_{train,val}2017.json\n  {train,val}2017/\n    # image files that are mentioned in the corresponding json\n```\n\nYou can use the 2014 version of the dataset as well.\n\nSome of the builtin tests (`dev/run_*_tests.sh`) uses a tiny version of the COCO dataset,\nwhich you can download with `./datasets/prepare_for_tests.sh`.\n\n## Expected dataset structure for PanopticFPN:\n\nExtract panoptic annotations from [COCO website](https://cocodataset.org/#download)\ninto the following structure:\n```\ncoco/\n  annotations/\n    panoptic_{train,val}2017.json\n  panoptic_{train,val}2017/  # png annotations\n  panoptic_stuff_{train,val}2017/  # generated by the script mentioned below\n```\n\nInstall panopticapi by:\n```\npip install git+https://github.com/cocodataset/panopticapi.git\n```\nThen, run `python datasets/prepare_panoptic_fpn.py`, to extract semantic annotations from panoptic annotations.\n\n## Expected dataset structure for [LVIS instance segmentation](https://www.lvisdataset.org/dataset):\n```\ncoco/\n  {train,val,test}2017/\nlvis/\n  lvis_v0.5_{train,val}.json\n  lvis_v0.5_image_info_test.json\n  lvis_v1_{train,val}.json\n  lvis_v1_image_info_test{,_challenge}.json\n```\n\nInstall lvis-api by:\n```\npip install git+https://github.com/lvis-dataset/lvis-api.git\n```\n\nTo evaluate models trained on the COCO dataset using LVIS annotations,\nrun `python datasets/prepare_cocofied_lvis.py` to prepare \"cocofied\" LVIS annotations.\n\n## Expected dataset structure for [cityscapes](https://www.cityscapes-dataset.com/downloads/):\n```\ncityscapes/\n  gtFine/\n    train/\n      aachen/\n        color.png, instanceIds.png, labelIds.png, polygons.json,\n        labelTrainIds.png\n      ...\n    val/\n    test/\n    # below are generated Cityscapes panoptic annotation\n    cityscapes_panoptic_train.json\n    cityscapes_panoptic_train/\n    cityscapes_panoptic_val.json\n    cityscapes_panoptic_val/\n    cityscapes_panoptic_test.json\n    cityscapes_panoptic_test/\n  leftImg8bit/\n    train/\n    val/\n    test/\n```\nInstall cityscapes scripts by:\n```\npip install git+https://github.com/mcordts/cityscapesScripts.git\n```\n\nNote: to create labelTrainIds.png, first prepare the above structure, then run cityscapesescript with:\n```\nCITYSCAPES_DATASET=/path/to/abovementioned/cityscapes python cityscapesscripts/preparation/createTrainIdLabelImgs.py\n```\nThese files are not needed for instance segmentation.\n\nNote: to generate Cityscapes panoptic dataset, run cityscapesescript with:\n```\nCITYSCAPES_DATASET=/path/to/abovementioned/cityscapes python cityscapesscripts/preparation/createPanopticImgs.py\n```\nThese files are not needed for semantic and instance segmentation.\n\n## Expected dataset structure for [Pascal VOC](http://host.robots.ox.ac.uk/pascal/VOC/index.html):\n```\nVOC20{07,12}/\n  Annotations/\n  ImageSets/\n    Main/\n      trainval.txt\n      test.txt\n      # train.txt or val.txt, if you use these splits\n  JPEGImages/\n```\n\n## Expected dataset structure for [ADE20k Scene Parsing](http://sceneparsing.csail.mit.edu/):\n```\nADEChallengeData2016/\n  annotations/\n  annotations_detectron2/\n  images/\n  objectInfo150.txt\n```\nThe directory `annotations_detectron2` is generated by running `python datasets/prepare_ade20k_sem_seg.py`.\n"
  },
  {
    "path": "VPS_Module/configs/Base-RCNN-C4.yaml",
    "content": "MODEL:\n  META_ARCHITECTURE: \"GeneralizedRCNN\"\n  RPN:\n    PRE_NMS_TOPK_TEST: 6000\n    POST_NMS_TOPK_TEST: 1000\n  ROI_HEADS:\n    NAME: \"Res5ROIHeads\"\nDATASETS:\n  TRAIN: (\"coco_2017_train\",)\n  TEST: (\"coco_2017_val\",)\nSOLVER:\n  IMS_PER_BATCH: 16\n  BASE_LR: 0.02\n  STEPS: (60000, 80000)\n  MAX_ITER: 90000\nINPUT:\n  MIN_SIZE_TRAIN: (640, 672, 704, 736, 768, 800)\nVERSION: 2\n"
  },
  {
    "path": "VPS_Module/configs/Base-RCNN-DilatedC5.yaml",
    "content": "MODEL:\n  META_ARCHITECTURE: \"GeneralizedRCNN\"\n  RESNETS:\n    OUT_FEATURES: [\"res5\"]\n    RES5_DILATION: 2\n  RPN:\n    IN_FEATURES: [\"res5\"]\n    PRE_NMS_TOPK_TEST: 6000\n    POST_NMS_TOPK_TEST: 1000\n  ROI_HEADS:\n    NAME: \"StandardROIHeads\"\n    IN_FEATURES: [\"res5\"]\n  ROI_BOX_HEAD:\n    NAME: \"FastRCNNConvFCHead\"\n    NUM_FC: 2\n    POOLER_RESOLUTION: 7\n  ROI_MASK_HEAD:\n    NAME: \"MaskRCNNConvUpsampleHead\"\n    NUM_CONV: 4\n    POOLER_RESOLUTION: 14\nDATASETS:\n  TRAIN: (\"coco_2017_train\",)\n  TEST: (\"coco_2017_val\",)\nSOLVER:\n  IMS_PER_BATCH: 16\n  BASE_LR: 0.02\n  STEPS: (60000, 80000)\n  MAX_ITER: 90000\nINPUT:\n  MIN_SIZE_TRAIN: (640, 672, 704, 736, 768, 800)\nVERSION: 2\n"
  },
  {
    "path": "VPS_Module/configs/Base-RCNN-FPN.yaml",
    "content": "MODEL:\n  META_ARCHITECTURE: \"GeneralizedRCNN\"\n  BACKBONE:\n    NAME: \"build_resnet_fpn_backbone\"\n  RESNETS:\n    OUT_FEATURES: [\"res2\", \"res3\", \"res4\", \"res5\"]\n  FPN:\n    IN_FEATURES: [\"res2\", \"res3\", \"res4\", \"res5\"]\n  ANCHOR_GENERATOR:\n    SIZES: [[32], [64], [128], [256], [512]]  # One size for each in feature map\n    ASPECT_RATIOS: [[0.5, 1.0, 2.0]]  # Three aspect ratios (same for all in feature maps)\n  RPN:\n    IN_FEATURES: [\"p2\", \"p3\", \"p4\", \"p5\", \"p6\"]\n    PRE_NMS_TOPK_TRAIN: 2000  # Per FPN level\n    PRE_NMS_TOPK_TEST: 1000  # Per FPN level\n    # Detectron1 uses 2000 proposals per-batch,\n    # (See \"modeling/rpn/rpn_outputs.py\" for details of this legacy issue)\n    # which is approximately 1000 proposals per-image since the default batch size for FPN is 2.\n    POST_NMS_TOPK_TRAIN: 1000\n    POST_NMS_TOPK_TEST: 1000\n  ROI_HEADS:\n    NAME: \"StandardROIHeads\"\n    IN_FEATURES: [\"p2\", \"p3\", \"p4\", \"p5\"]\n  ROI_BOX_HEAD:\n    NAME: \"FastRCNNConvFCHead\"\n    NUM_FC: 2\n    POOLER_RESOLUTION: 7\n  ROI_MASK_HEAD:\n    NAME: \"MaskRCNNConvUpsampleHead\"\n    NUM_CONV: 4\n    POOLER_RESOLUTION: 14\nDATASETS:\n  TRAIN: (\"coco_2017_train\",)\n  TEST: (\"coco_2017_val\",)\nSOLVER:\n  IMS_PER_BATCH: 1\n  BASE_LR: 0.02\n  STEPS: (60000, 80000)\n  MAX_ITER: 90000\nINPUT:\n  MIN_SIZE_TRAIN: (640, 672, 704, 736, 768, 800)\nVERSION: 2\n"
  },
  {
    "path": "VPS_Module/configs/Base-RetinaNet.yaml",
    "content": "MODEL:\n  META_ARCHITECTURE: \"RetinaNet\"\n  BACKBONE:\n    NAME: \"build_retinanet_resnet_fpn_backbone\"\n  RESNETS:\n    OUT_FEATURES: [\"res3\", \"res4\", \"res5\"]\n  ANCHOR_GENERATOR:\n    SIZES: !!python/object/apply:eval [\"[[x, x * 2**(1.0/3), x * 2**(2.0/3) ] for x in [32, 64, 128, 256, 512 ]]\"]\n  FPN:\n    IN_FEATURES: [\"res3\", \"res4\", \"res5\"]\n  RETINANET:\n    IOU_THRESHOLDS: [0.4, 0.5]\n    IOU_LABELS: [0, -1, 1]\n    SMOOTH_L1_LOSS_BETA: 0.0\nDATASETS:\n  TRAIN: (\"coco_2017_train\",)\n  TEST: (\"coco_2017_val\",)\nSOLVER:\n  IMS_PER_BATCH: 16\n  BASE_LR: 0.01  # Note that RetinaNet uses a different default learning rate\n  STEPS: (60000, 80000)\n  MAX_ITER: 90000\nINPUT:\n  MIN_SIZE_TRAIN: (640, 672, 704, 736, 768, 800)\nVERSION: 2\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Detection/fast_rcnn_R_50_FPN_1x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: False\n  LOAD_PROPOSALS: True\n  RESNETS:\n    DEPTH: 50\n  PROPOSAL_GENERATOR:\n    NAME: \"PrecomputedProposals\"\nDATASETS:\n  TRAIN: (\"coco_2017_train\",)\n  PROPOSAL_FILES_TRAIN: (\"detectron2://COCO-Detection/rpn_R_50_FPN_1x/137258492/coco_2017_train_box_proposals_21bc3a.pkl\", )\n  TEST: (\"coco_2017_val\",)\n  PROPOSAL_FILES_TEST: (\"detectron2://COCO-Detection/rpn_R_50_FPN_1x/137258492/coco_2017_val_box_proposals_ee0dad.pkl\", )\nDATALOADER:\n  # proposals are part of the dataset_dicts, and take a lot of RAM\n  NUM_WORKERS: 2\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Detection/faster_rcnn_R_101_C4_3x.yaml",
    "content": "_BASE_: \"../Base-RCNN-C4.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  MASK_ON: False\n  RESNETS:\n    DEPTH: 101\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Detection/faster_rcnn_R_101_DC5_3x.yaml",
    "content": "_BASE_: \"../Base-RCNN-DilatedC5.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  MASK_ON: False\n  RESNETS:\n    DEPTH: 101\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Detection/faster_rcnn_R_101_FPN_3x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  MASK_ON: False\n  RESNETS:\n    DEPTH: 101\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Detection/faster_rcnn_R_50_C4_1x.yaml",
    "content": "_BASE_: \"../Base-RCNN-C4.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: False\n  RESNETS:\n    DEPTH: 50\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Detection/faster_rcnn_R_50_C4_3x.yaml",
    "content": "_BASE_: \"../Base-RCNN-C4.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: False\n  RESNETS:\n    DEPTH: 50\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Detection/faster_rcnn_R_50_DC5_1x.yaml",
    "content": "_BASE_: \"../Base-RCNN-DilatedC5.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: False\n  RESNETS:\n    DEPTH: 50\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Detection/faster_rcnn_R_50_DC5_3x.yaml",
    "content": "_BASE_: \"../Base-RCNN-DilatedC5.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: False\n  RESNETS:\n    DEPTH: 50\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Detection/faster_rcnn_R_50_FPN_1x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: False\n  RESNETS:\n    DEPTH: 50\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Detection/faster_rcnn_R_50_FPN_3x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: False\n  RESNETS:\n    DEPTH: 50\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Detection/faster_rcnn_X_101_32x8d_FPN_3x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  MASK_ON: False\n  WEIGHTS: \"detectron2://ImageNetPretrained/FAIR/X-101-32x8d.pkl\"\n  PIXEL_STD: [57.375, 57.120, 58.395]\n  RESNETS:\n    STRIDE_IN_1X1: False  # this is a C2 model\n    NUM_GROUPS: 32\n    WIDTH_PER_GROUP: 8\n    DEPTH: 101\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Detection/fcos_R_50_FPN_1x.py",
    "content": "from ..common.optim import SGD as optimizer\nfrom ..common.coco_schedule import lr_multiplier_1x as lr_multiplier\nfrom ..common.data.coco import dataloader\nfrom ..common.models.fcos import model\nfrom ..common.train import train\n\ndataloader.train.mapper.use_instance_mask = False\noptimizer.lr = 0.01\n\nmodel.backbone.bottom_up.freeze_at = 2\ntrain.init_checkpoint = \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Detection/retinanet_R_101_FPN_3x.yaml",
    "content": "_BASE_: \"../Base-RetinaNet.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  RESNETS:\n    DEPTH: 101\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Detection/retinanet_R_50_FPN_1x.py",
    "content": "from ..common.optim import SGD as optimizer\nfrom ..common.coco_schedule import lr_multiplier_1x as lr_multiplier\nfrom ..common.data.coco import dataloader\nfrom ..common.models.retinanet import model\nfrom ..common.train import train\n\ndataloader.train.mapper.use_instance_mask = False\nmodel.backbone.bottom_up.freeze_at = 2\noptimizer.lr = 0.01\n\ntrain.init_checkpoint = \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Detection/retinanet_R_50_FPN_1x.yaml",
    "content": "_BASE_: \"../Base-RetinaNet.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Detection/retinanet_R_50_FPN_3x.yaml",
    "content": "_BASE_: \"../Base-RetinaNet.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Detection/rpn_R_50_C4_1x.yaml",
    "content": "_BASE_: \"../Base-RCNN-C4.yaml\"\nMODEL:\n  META_ARCHITECTURE: \"ProposalNetwork\"\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: False\n  RESNETS:\n    DEPTH: 50\n  RPN:\n    PRE_NMS_TOPK_TEST: 12000\n    POST_NMS_TOPK_TEST: 2000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Detection/rpn_R_50_FPN_1x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  META_ARCHITECTURE: \"ProposalNetwork\"\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: False\n  RESNETS:\n    DEPTH: 50\n  RPN:\n    POST_NMS_TOPK_TEST: 2000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-InstanceSegmentation/mask_rcnn_R_101_C4_3x.yaml",
    "content": "_BASE_: \"../Base-RCNN-C4.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 101\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-InstanceSegmentation/mask_rcnn_R_101_DC5_3x.yaml",
    "content": "_BASE_: \"../Base-RCNN-DilatedC5.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 101\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-InstanceSegmentation/mask_rcnn_R_101_FPN_3x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 101\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-InstanceSegmentation/mask_rcnn_R_50_C4_1x.py",
    "content": "from ..common.train import train\nfrom ..common.optim import SGD as optimizer\nfrom ..common.coco_schedule import lr_multiplier_1x as lr_multiplier\nfrom ..common.data.coco import dataloader\nfrom ..common.models.mask_rcnn_c4 import model\n\nmodel.backbone.freeze_at = 2\ntrain.init_checkpoint = \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n"
  },
  {
    "path": "VPS_Module/configs/COCO-InstanceSegmentation/mask_rcnn_R_50_C4_1x.yaml",
    "content": "_BASE_: \"../Base-RCNN-C4.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 50\n"
  },
  {
    "path": "VPS_Module/configs/COCO-InstanceSegmentation/mask_rcnn_R_50_C4_3x.yaml",
    "content": "_BASE_: \"../Base-RCNN-C4.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 50\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-InstanceSegmentation/mask_rcnn_R_50_DC5_1x.yaml",
    "content": "_BASE_: \"../Base-RCNN-DilatedC5.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 50\n"
  },
  {
    "path": "VPS_Module/configs/COCO-InstanceSegmentation/mask_rcnn_R_50_DC5_3x.yaml",
    "content": "_BASE_: \"../Base-RCNN-DilatedC5.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 50\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_1x.py",
    "content": "from ..common.optim import SGD as optimizer\nfrom ..common.coco_schedule import lr_multiplier_1x as lr_multiplier\nfrom ..common.data.coco import dataloader\nfrom ..common.models.mask_rcnn_fpn import model\nfrom ..common.train import train\n\nmodel.backbone.bottom_up.freeze_at = 2\ntrain.init_checkpoint = \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n"
  },
  {
    "path": "VPS_Module/configs/COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_1x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 50\n"
  },
  {
    "path": "VPS_Module/configs/COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_1x_giou.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 50\n  RPN:\n    BBOX_REG_LOSS_TYPE: \"giou\"\n    BBOX_REG_LOSS_WEIGHT: 2.0\n  ROI_BOX_HEAD:\n    BBOX_REG_LOSS_TYPE: \"giou\"\n    BBOX_REG_LOSS_WEIGHT: 10.0\n"
  },
  {
    "path": "VPS_Module/configs/COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_3x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 50\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-InstanceSegmentation/mask_rcnn_X_101_32x8d_FPN_3x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  MASK_ON: True\n  WEIGHTS: \"detectron2://ImageNetPretrained/FAIR/X-101-32x8d.pkl\"\n  PIXEL_STD: [57.375, 57.120, 58.395]\n  RESNETS:\n    STRIDE_IN_1X1: False  # this is a C2 model\n    NUM_GROUPS: 32\n    WIDTH_PER_GROUP: 8\n    DEPTH: 101\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-InstanceSegmentation/mask_rcnn_regnetx_4gf_dds_fpn_1x.py",
    "content": "from ..common.optim import SGD as optimizer\nfrom ..common.coco_schedule import lr_multiplier_1x as lr_multiplier\nfrom ..common.data.coco import dataloader\nfrom ..common.models.mask_rcnn_fpn import model\nfrom ..common.train import train\n\nfrom detectron2.config import LazyCall as L\nfrom detectron2.modeling.backbone import RegNet\nfrom detectron2.modeling.backbone.regnet import SimpleStem, ResBottleneckBlock\n\n\n# Replace default ResNet with RegNetX-4GF from the DDS paper. Config source:\n# https://github.com/facebookresearch/pycls/blob/2c152a6e5d913e898cca4f0a758f41e6b976714d/configs/dds_baselines/regnetx/RegNetX-4.0GF_dds_8gpu.yaml#L4-L9  # noqa\nmodel.backbone.bottom_up = L(RegNet)(\n    stem_class=SimpleStem,\n    stem_width=32,\n    block_class=ResBottleneckBlock,\n    depth=23,\n    w_a=38.65,\n    w_0=96,\n    w_m=2.43,\n    group_width=40,\n    freeze_at=2,\n    norm=\"FrozenBN\",\n    out_features=[\"s1\", \"s2\", \"s3\", \"s4\"],\n)\nmodel.pixel_std = [57.375, 57.120, 58.395]\n\noptimizer.weight_decay = 5e-5\ntrain.init_checkpoint = (\n    \"https://dl.fbaipublicfiles.com/pycls/dds_baselines/160906383/RegNetX-4.0GF_dds_8gpu.pyth\"\n)\n# RegNets benefit from enabling cudnn benchmark mode\ntrain.cudnn_benchmark = True\n"
  },
  {
    "path": "VPS_Module/configs/COCO-InstanceSegmentation/mask_rcnn_regnety_4gf_dds_fpn_1x.py",
    "content": "from ..common.optim import SGD as optimizer\nfrom ..common.coco_schedule import lr_multiplier_1x as lr_multiplier\nfrom ..common.data.coco import dataloader\nfrom ..common.models.mask_rcnn_fpn import model\nfrom ..common.train import train\n\nfrom detectron2.config import LazyCall as L\nfrom detectron2.modeling.backbone import RegNet\nfrom detectron2.modeling.backbone.regnet import SimpleStem, ResBottleneckBlock\n\n\n# Replace default ResNet with RegNetY-4GF from the DDS paper. Config source:\n# https://github.com/facebookresearch/pycls/blob/2c152a6e5d913e898cca4f0a758f41e6b976714d/configs/dds_baselines/regnety/RegNetY-4.0GF_dds_8gpu.yaml#L4-L10  # noqa\nmodel.backbone.bottom_up = L(RegNet)(\n    stem_class=SimpleStem,\n    stem_width=32,\n    block_class=ResBottleneckBlock,\n    depth=22,\n    w_a=31.41,\n    w_0=96,\n    w_m=2.24,\n    group_width=64,\n    se_ratio=0.25,\n    freeze_at=2,\n    norm=\"FrozenBN\",\n    out_features=[\"s1\", \"s2\", \"s3\", \"s4\"],\n)\nmodel.pixel_std = [57.375, 57.120, 58.395]\n\noptimizer.weight_decay = 5e-5\ntrain.init_checkpoint = (\n    \"https://dl.fbaipublicfiles.com/pycls/dds_baselines/160906838/RegNetY-4.0GF_dds_8gpu.pyth\"\n)\n# RegNets benefit from enabling cudnn benchmark mode\ntrain.cudnn_benchmark = True\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Keypoints/Base-Keypoint-RCNN-FPN.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  KEYPOINT_ON: True\n  ROI_HEADS:\n    NUM_CLASSES: 1\n  ROI_BOX_HEAD:\n    SMOOTH_L1_BETA: 0.5  # Keypoint AP degrades (though box AP improves) when using plain L1 loss\n  RPN:\n    # Detectron1 uses 2000 proposals per-batch, but this option is per-image in detectron2.\n    # 1000 proposals per-image is found to hurt box AP.\n    # Therefore we increase it to 1500 per-image.\n    POST_NMS_TOPK_TRAIN: 1500\nDATASETS:\n  TRAIN: (\"keypoints_coco_2017_train\",)\n  TEST: (\"keypoints_coco_2017_val\",)\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Keypoints/keypoint_rcnn_R_101_FPN_3x.yaml",
    "content": "_BASE_: \"Base-Keypoint-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  RESNETS:\n    DEPTH: 101\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Keypoints/keypoint_rcnn_R_50_FPN_1x.py",
    "content": "from ..common.optim import SGD as optimizer\nfrom ..common.coco_schedule import lr_multiplier_1x as lr_multiplier\nfrom ..common.data.coco_keypoint import dataloader\nfrom ..common.models.keypoint_rcnn_fpn import model\nfrom ..common.train import train\n\nmodel.backbone.bottom_up.freeze_at = 2\ntrain.init_checkpoint = \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Keypoints/keypoint_rcnn_R_50_FPN_1x.yaml",
    "content": "_BASE_: \"Base-Keypoint-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Keypoints/keypoint_rcnn_R_50_FPN_3x.yaml",
    "content": "_BASE_: \"Base-Keypoint-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-Keypoints/keypoint_rcnn_X_101_32x8d_FPN_3x.yaml",
    "content": "_BASE_: \"Base-Keypoint-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/FAIR/X-101-32x8d.pkl\"\n  PIXEL_STD: [57.375, 57.120, 58.395]\n  RESNETS:\n    STRIDE_IN_1X1: False  # this is a C2 model\n    NUM_GROUPS: 32\n    WIDTH_PER_GROUP: 8\n    DEPTH: 101\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-PanopticSegmentation/Base-Panoptic-FPN.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  META_ARCHITECTURE: \"PanopticFPN\"\n  MASK_ON: True\n  SEM_SEG_HEAD:\n    LOSS_WEIGHT: 0.5\nDATASETS:\n  TRAIN: (\"coco_2017_train_panoptic_separated\",)\n  TEST: (\"coco_2017_val_panoptic_separated\",)\nDATALOADER:\n  FILTER_EMPTY_ANNOTATIONS: False\n"
  },
  {
    "path": "VPS_Module/configs/COCO-PanopticSegmentation/panoptic_fpn_R_101_3x.yaml",
    "content": "_BASE_: \"Base-Panoptic-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  RESNETS:\n    DEPTH: 101\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-PanopticSegmentation/panoptic_fpn_R_50_1x.py",
    "content": "from ..common.optim import SGD as optimizer\nfrom ..common.coco_schedule import lr_multiplier_1x as lr_multiplier\nfrom ..common.data.coco_panoptic_separated import dataloader\nfrom ..common.models.panoptic_fpn import model\nfrom ..common.train import train\n\nmodel.backbone.bottom_up.freeze_at = 2\ntrain.init_checkpoint = \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n"
  },
  {
    "path": "VPS_Module/configs/COCO-PanopticSegmentation/panoptic_fpn_R_50_1x.yaml",
    "content": "_BASE_: \"Base-Panoptic-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n"
  },
  {
    "path": "VPS_Module/configs/COCO-PanopticSegmentation/panoptic_fpn_R_50_3x.yaml",
    "content": "_BASE_: \"Base-Panoptic-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/COCO-PanopticSegmentation/panoptic_fpn_R_50_3x_vkitti_511.yaml",
    "content": "_BASE_: \"Base-Panoptic-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    NUM_CLASSES: 3 # thing\n  SEM_SEG_HEAD:\n    NUM_CLASSES: 12 # stuff\n  PANOPTIC_FPN:\n    FUSION: True\nDATASETS:\n  TRAIN: (\"vkitti_511_train\",)\n  TEST: (\"vkitti_511_val\",)\nSOLVER:\n  IMS_PER_BATCH: 16\n  BASE_LR: 1e-5 \n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n  CHECKPOINT_PERIOD: 10\nINPUT:\n  MASK_FORMAT: \"bitmask\"\n  MIN_SIZE_TRAIN: (375,)\n  MAX_SIZE_TRAIN: 1242\n  MIN_SIZE_TEST: 375 \n  MAX_SIZE_TEST: 1242 \nDATALOADER:\n  NUM_WORKERS: 2\n\n\n"
  },
  {
    "path": "VPS_Module/configs/COCO-PanopticSegmentation/panoptic_fpn_R_50_3x_vkitti_init_clone.yaml",
    "content": "_BASE_: \"Base-Panoptic-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    NUM_CLASSES: 3 # thing\n  SEM_SEG_HEAD:\n    NUM_CLASSES: 12 # stuff\n  PANOPTIC_FPN:\n    FUSION: False\nDATASETS:\n  TRAIN: (\"vkitti_train\",)\n  TEST: (\"vkitti_clone\",)\nSOLVER:\n  IMS_PER_BATCH: 16\n  BASE_LR: 1e-5 \n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n  CHECKPOINT_PERIOD: 10\nINPUT:\n  MASK_FORMAT: \"bitmask\"\n  MIN_SIZE_TRAIN: (375,)\n  MAX_SIZE_TRAIN: 1242\n  MIN_SIZE_TEST: 375 \n  MAX_SIZE_TEST: 1242 \n\nDATALOADER:\n  NUM_WORKERS: 2\n\n  \n\n"
  },
  {
    "path": "VPS_Module/configs/COCO-PanopticSegmentation/panoptic_fpn_R_50_3x_vkitti_init_test.yaml",
    "content": "_BASE_: \"Base-Panoptic-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    NUM_CLASSES: 3 # thing\n  SEM_SEG_HEAD:\n    NUM_CLASSES: 12 # stuff\n  PANOPTIC_FPN:\n    FUSION: False\nDATASETS:\n  TRAIN: (\"vkitti_train\",)\n  TEST: (\"vkitti_test\",)\nSOLVER:\n  IMS_PER_BATCH: 16\n  BASE_LR: 1e-5 \n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n  CHECKPOINT_PERIOD: 10\nINPUT:\n  MASK_FORMAT: \"bitmask\"\n  MIN_SIZE_TRAIN: (375,)\n  MAX_SIZE_TRAIN: 1242\n  MIN_SIZE_TEST: 375 \n  MAX_SIZE_TEST: 1242 \n\nDATALOADER:\n  NUM_WORKERS: 2\n\n  \n\n"
  },
  {
    "path": "VPS_Module/configs/Cityscapes/mask_rcnn_R_50_FPN.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  # WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  # For better, more stable performance initialize from COCO\n  WEIGHTS: \"detectron2://COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_3x/137849600/model_final_f10217.pkl\"\n  MASK_ON: True\n  ROI_HEADS:\n    NUM_CLASSES: 8\n# This is similar to the setting used in Mask R-CNN paper, Appendix A\n# But there are some differences, e.g., we did not initialize the output\n# layer using the corresponding classes from COCO\nINPUT:\n  MIN_SIZE_TRAIN: (800, 832, 864, 896, 928, 960, 992, 1024)\n  MIN_SIZE_TRAIN_SAMPLING: \"choice\"\n  MIN_SIZE_TEST: 1024\n  MAX_SIZE_TRAIN: 2048\n  MAX_SIZE_TEST: 2048\nDATASETS:\n  TRAIN: (\"cityscapes_fine_instance_seg_train\",)\n  TEST: (\"cityscapes_fine_instance_seg_val\",)\nSOLVER:\n  BASE_LR: 0.01\n  STEPS: (18000,)\n  MAX_ITER: 24000\n  IMS_PER_BATCH: 8\nTEST:\n  EVAL_PERIOD: 8000\n"
  },
  {
    "path": "VPS_Module/configs/Detectron1-Comparisons/README.md",
    "content": "\nDetectron2 model zoo's experimental settings and a few implementation details are different from Detectron.\n\nThe differences in implementation details are shared in\n[Compatibility with Other Libraries](../../docs/notes/compatibility.md).\n\nThe differences in model zoo's experimental settings include:\n* Use scale augmentation during training. This improves AP with lower training cost.\n* Use L1 loss instead of smooth L1 loss for simplicity. This sometimes improves box AP but may\n  affect other AP.\n* Use `POOLER_SAMPLING_RATIO=0` instead of 2. This does not significantly affect AP.\n* Use `ROIAlignV2`. This does not significantly affect AP.\n\nIn this directory, we provide a few configs that __do not__ have the above changes.\nThey mimic Detectron's behavior as close as possible,\nand provide a fair comparison of accuracy and speed against Detectron.\n\n<!--\n./gen_html_table.py --config 'Detectron1-Comparisons/*.yaml' --name \"Faster R-CNN\" \"Keypoint R-CNN\" \"Mask R-CNN\" --fields lr_sched train_speed inference_speed mem box_AP mask_AP keypoint_AP --base-dir ../../../configs/Detectron1-Comparisons\n-->\n\n\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Name</th>\n<th valign=\"bottom\">lr<br/>sched</th>\n<th valign=\"bottom\">train<br/>time<br/>(s/iter)</th>\n<th valign=\"bottom\">inference<br/>time<br/>(s/im)</th>\n<th valign=\"bottom\">train<br/>mem<br/>(GB)</th>\n<th valign=\"bottom\">box<br/>AP</th>\n<th valign=\"bottom\">mask<br/>AP</th>\n<th valign=\"bottom\">kp.<br/>AP</th>\n<th valign=\"bottom\">model id</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n<!-- ROW: faster_rcnn_R_50_FPN_noaug_1x -->\n <tr><td align=\"left\"><a href=\"faster_rcnn_R_50_FPN_noaug_1x.yaml\">Faster R-CNN</a></td>\n<td align=\"center\">1x</td>\n<td align=\"center\">0.219</td>\n<td align=\"center\">0.038</td>\n<td align=\"center\">3.1</td>\n<td align=\"center\">36.9</td>\n<td align=\"center\"></td>\n<td align=\"center\"></td>\n<td align=\"center\">137781054</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/detectron2/Detectron1-Comparisons/faster_rcnn_R_50_FPN_noaug_1x/137781054/model_final_7ab50c.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/Detectron1-Comparisons/faster_rcnn_R_50_FPN_noaug_1x/137781054/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: keypoint_rcnn_R_50_FPN_1x -->\n <tr><td align=\"left\"><a href=\"keypoint_rcnn_R_50_FPN_1x.yaml\">Keypoint R-CNN</a></td>\n<td align=\"center\">1x</td>\n<td align=\"center\">0.313</td>\n<td align=\"center\">0.071</td>\n<td align=\"center\">5.0</td>\n<td align=\"center\">53.1</td>\n<td align=\"center\"></td>\n<td align=\"center\">64.2</td>\n<td align=\"center\">137781195</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/detectron2/Detectron1-Comparisons/keypoint_rcnn_R_50_FPN_1x/137781195/model_final_cce136.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/Detectron1-Comparisons/keypoint_rcnn_R_50_FPN_1x/137781195/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: mask_rcnn_R_50_FPN_noaug_1x -->\n <tr><td align=\"left\"><a href=\"mask_rcnn_R_50_FPN_noaug_1x.yaml\">Mask R-CNN</a></td>\n<td align=\"center\">1x</td>\n<td align=\"center\">0.273</td>\n<td align=\"center\">0.043</td>\n<td align=\"center\">3.4</td>\n<td align=\"center\">37.8</td>\n<td align=\"center\">34.9</td>\n<td align=\"center\"></td>\n<td align=\"center\">137781281</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/detectron2/Detectron1-Comparisons/mask_rcnn_R_50_FPN_noaug_1x/137781281/model_final_62ca52.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/Detectron1-Comparisons/mask_rcnn_R_50_FPN_noaug_1x/137781281/metrics.json\">metrics</a></td>\n</tr>\n</tbody></table>\n\n## Comparisons:\n\n* Faster R-CNN: Detectron's AP is 36.7, similar to ours.\n* Keypoint R-CNN: Detectron's AP is box 53.6, keypoint 64.2. Fixing a Detectron's\n  [bug](https://github.com/facebookresearch/Detectron/issues/459) lead to a drop in box AP, and can be\n\tcompensated back by some parameter tuning.\n* Mask R-CNN: Detectron's AP is box 37.7, mask 33.9. We're 1 AP better in mask AP, due to more correct implementation.\n  See [this article](https://ppwwyyxx.com/blog/2021/Where-are-Pixels/) for details.\n\nFor speed comparison, see [benchmarks](https://detectron2.readthedocs.io/notes/benchmarks.html).\n"
  },
  {
    "path": "VPS_Module/configs/Detectron1-Comparisons/faster_rcnn_R_50_FPN_noaug_1x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: False\n  RESNETS:\n    DEPTH: 50\n  # Detectron1 uses smooth L1 loss with some magic beta values.\n  # The defaults are changed to L1 loss in Detectron2.\n  RPN:\n    SMOOTH_L1_BETA: 0.1111\n  ROI_BOX_HEAD:\n    SMOOTH_L1_BETA: 1.0\n    POOLER_SAMPLING_RATIO: 2\n    POOLER_TYPE: \"ROIAlign\"\nINPUT:\n  # no scale augmentation\n  MIN_SIZE_TRAIN: (800, )\n"
  },
  {
    "path": "VPS_Module/configs/Detectron1-Comparisons/keypoint_rcnn_R_50_FPN_1x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  KEYPOINT_ON: True\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    NUM_CLASSES: 1\n  ROI_KEYPOINT_HEAD:\n    POOLER_RESOLUTION: 14\n    POOLER_SAMPLING_RATIO: 2\n    POOLER_TYPE: \"ROIAlign\"\n  # Detectron1 uses smooth L1 loss with some magic beta values.\n  # The defaults are changed to L1 loss in Detectron2.\n  ROI_BOX_HEAD:\n    SMOOTH_L1_BETA: 1.0\n    POOLER_SAMPLING_RATIO: 2\n    POOLER_TYPE: \"ROIAlign\"\n  RPN:\n    SMOOTH_L1_BETA: 0.1111\n    # Detectron1 uses 2000 proposals per-batch, but this option is per-image in detectron2\n    # 1000 proposals per-image is found to hurt box AP.\n    # Therefore we increase it to 1500 per-image.\n    POST_NMS_TOPK_TRAIN: 1500\nDATASETS:\n  TRAIN: (\"keypoints_coco_2017_train\",)\n  TEST: (\"keypoints_coco_2017_val\",)\n"
  },
  {
    "path": "VPS_Module/configs/Detectron1-Comparisons/mask_rcnn_R_50_FPN_noaug_1x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 50\n  # Detectron1 uses smooth L1 loss with some magic beta values.\n  # The defaults are changed to L1 loss in Detectron2.\n  RPN:\n    SMOOTH_L1_BETA: 0.1111\n  ROI_BOX_HEAD:\n    SMOOTH_L1_BETA: 1.0\n    POOLER_SAMPLING_RATIO: 2\n    POOLER_TYPE: \"ROIAlign\"\n  ROI_MASK_HEAD:\n    POOLER_SAMPLING_RATIO: 2\n    POOLER_TYPE: \"ROIAlign\"\nINPUT:\n  # no scale augmentation\n  MIN_SIZE_TRAIN: (800, )\n"
  },
  {
    "path": "VPS_Module/configs/LVISv0.5-InstanceSegmentation/mask_rcnn_R_101_FPN_1x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 101\n  ROI_HEADS:\n    NUM_CLASSES: 1230\n    SCORE_THRESH_TEST: 0.0001\nINPUT:\n  MIN_SIZE_TRAIN: (640, 672, 704, 736, 768, 800)\nDATASETS:\n  TRAIN: (\"lvis_v0.5_train\",)\n  TEST: (\"lvis_v0.5_val\",)\nTEST:\n  DETECTIONS_PER_IMAGE: 300  # LVIS allows up to 300\nDATALOADER:\n  SAMPLER_TRAIN: \"RepeatFactorTrainingSampler\"\n  REPEAT_THRESHOLD: 0.001\n"
  },
  {
    "path": "VPS_Module/configs/LVISv0.5-InstanceSegmentation/mask_rcnn_R_50_FPN_1x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    NUM_CLASSES: 1230\n    SCORE_THRESH_TEST: 0.0001\nINPUT:\n  MIN_SIZE_TRAIN: (640, 672, 704, 736, 768, 800)\nDATASETS:\n  TRAIN: (\"lvis_v0.5_train\",)\n  TEST: (\"lvis_v0.5_val\",)\nTEST:\n  DETECTIONS_PER_IMAGE: 300  # LVIS allows up to 300\nDATALOADER:\n  SAMPLER_TRAIN: \"RepeatFactorTrainingSampler\"\n  REPEAT_THRESHOLD: 0.001\n"
  },
  {
    "path": "VPS_Module/configs/LVISv0.5-InstanceSegmentation/mask_rcnn_X_101_32x8d_FPN_1x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/FAIR/X-101-32x8d.pkl\"\n  PIXEL_STD: [57.375, 57.120, 58.395]\n  MASK_ON: True\n  RESNETS:\n    STRIDE_IN_1X1: False  # this is a C2 model\n    NUM_GROUPS: 32\n    WIDTH_PER_GROUP: 8\n    DEPTH: 101\n  ROI_HEADS:\n    NUM_CLASSES: 1230\n    SCORE_THRESH_TEST: 0.0001\nINPUT:\n  MIN_SIZE_TRAIN: (640, 672, 704, 736, 768, 800)\nDATASETS:\n  TRAIN: (\"lvis_v0.5_train\",)\n  TEST: (\"lvis_v0.5_val\",)\nTEST:\n  DETECTIONS_PER_IMAGE: 300  # LVIS allows up to 300\nDATALOADER:\n  SAMPLER_TRAIN: \"RepeatFactorTrainingSampler\"\n  REPEAT_THRESHOLD: 0.001\n"
  },
  {
    "path": "VPS_Module/configs/LVISv1-InstanceSegmentation/mask_rcnn_R_101_FPN_1x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 101\n  ROI_HEADS:\n    NUM_CLASSES: 1203\n    SCORE_THRESH_TEST: 0.0001\nINPUT:\n  MIN_SIZE_TRAIN: (640, 672, 704, 736, 768, 800)\nDATASETS:\n  TRAIN: (\"lvis_v1_train\",)\n  TEST: (\"lvis_v1_val\",)\nTEST:\n  DETECTIONS_PER_IMAGE: 300  # LVIS allows up to 300\nSOLVER:\n  STEPS: (120000, 160000)\n  MAX_ITER: 180000  # 180000 * 16 / 100000 ~ 28.8 epochs\nDATALOADER:\n  SAMPLER_TRAIN: \"RepeatFactorTrainingSampler\"\n  REPEAT_THRESHOLD: 0.001\n"
  },
  {
    "path": "VPS_Module/configs/LVISv1-InstanceSegmentation/mask_rcnn_R_50_FPN_1x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    NUM_CLASSES: 1203\n    SCORE_THRESH_TEST: 0.0001\nINPUT:\n  MIN_SIZE_TRAIN: (640, 672, 704, 736, 768, 800)\nDATASETS:\n  TRAIN: (\"lvis_v1_train\",)\n  TEST: (\"lvis_v1_val\",)\nTEST:\n  DETECTIONS_PER_IMAGE: 300  # LVIS allows up to 300\nSOLVER:\n  STEPS: (120000, 160000)\n  MAX_ITER: 180000  # 180000 * 16 / 100000 ~ 28.8 epochs\nDATALOADER:\n  SAMPLER_TRAIN: \"RepeatFactorTrainingSampler\"\n  REPEAT_THRESHOLD: 0.001\n"
  },
  {
    "path": "VPS_Module/configs/LVISv1-InstanceSegmentation/mask_rcnn_X_101_32x8d_FPN_1x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/FAIR/X-101-32x8d.pkl\"\n  PIXEL_STD: [57.375, 57.120, 58.395]\n  MASK_ON: True\n  RESNETS:\n    STRIDE_IN_1X1: False  # this is a C2 model\n    NUM_GROUPS: 32\n    WIDTH_PER_GROUP: 8\n    DEPTH: 101\n  ROI_HEADS:\n    NUM_CLASSES: 1203\n    SCORE_THRESH_TEST: 0.0001\nINPUT:\n  MIN_SIZE_TRAIN: (640, 672, 704, 736, 768, 800)\nDATASETS:\n  TRAIN: (\"lvis_v1_train\",)\n  TEST: (\"lvis_v1_val\",)\nSOLVER:\n  STEPS: (120000, 160000)\n  MAX_ITER: 180000  # 180000 * 16 / 100000 ~ 28.8 epochs\nTEST:\n  DETECTIONS_PER_IMAGE: 300  # LVIS allows up to 300\nDATALOADER:\n  SAMPLER_TRAIN: \"RepeatFactorTrainingSampler\"\n  REPEAT_THRESHOLD: 0.001\n"
  },
  {
    "path": "VPS_Module/configs/Misc/cascade_mask_rcnn_R_50_FPN_1x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    NAME: CascadeROIHeads\n  ROI_BOX_HEAD:\n    CLS_AGNOSTIC_BBOX_REG: True\n  RPN:\n    POST_NMS_TOPK_TRAIN: 2000\n"
  },
  {
    "path": "VPS_Module/configs/Misc/cascade_mask_rcnn_R_50_FPN_3x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    NAME: CascadeROIHeads\n  ROI_BOX_HEAD:\n    CLS_AGNOSTIC_BBOX_REG: True\n  RPN:\n    POST_NMS_TOPK_TRAIN: 2000\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/Misc/cascade_mask_rcnn_X_152_32x8d_FPN_IN5k_gn_dconv.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  MASK_ON: True\n  WEIGHTS: \"catalog://ImageNetPretrained/FAIR/X-152-32x8d-IN5k\"\n  RESNETS:\n    STRIDE_IN_1X1: False  # this is a C2 model\n    NUM_GROUPS: 32\n    WIDTH_PER_GROUP: 8\n    DEPTH: 152\n    DEFORM_ON_PER_STAGE: [False, True, True, True]\n  ROI_HEADS:\n    NAME: \"CascadeROIHeads\"\n  ROI_BOX_HEAD:\n    NAME: \"FastRCNNConvFCHead\"\n    NUM_CONV: 4\n    NUM_FC: 1\n    NORM: \"GN\"\n    CLS_AGNOSTIC_BBOX_REG: True\n  ROI_MASK_HEAD:\n    NUM_CONV: 8\n    NORM: \"GN\"\n  RPN:\n    POST_NMS_TOPK_TRAIN: 2000\nSOLVER:\n  IMS_PER_BATCH: 128\n  STEPS: (35000, 45000)\n  MAX_ITER: 50000\n  BASE_LR: 0.16\nINPUT:\n  MIN_SIZE_TRAIN: (640, 864)\n  MIN_SIZE_TRAIN_SAMPLING: \"range\"\n  MAX_SIZE_TRAIN: 1440\n  CROP:\n    ENABLED: True\nTEST:\n  EVAL_PERIOD: 2500\n"
  },
  {
    "path": "VPS_Module/configs/Misc/mask_rcnn_R_50_FPN_1x_cls_agnostic.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 50\n  ROI_BOX_HEAD:\n    CLS_AGNOSTIC_BBOX_REG: True\n  ROI_MASK_HEAD:\n    CLS_AGNOSTIC_MASK: True\n"
  },
  {
    "path": "VPS_Module/configs/Misc/mask_rcnn_R_50_FPN_1x_dconv_c3-c5.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 50\n    DEFORM_ON_PER_STAGE: [False, True, True, True] # on Res3,Res4,Res5\n    DEFORM_MODULATED: False\n"
  },
  {
    "path": "VPS_Module/configs/Misc/mask_rcnn_R_50_FPN_3x_dconv_c3-c5.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 50\n    DEFORM_ON_PER_STAGE: [False, True, True, True] # on Res3,Res4,Res5\n    DEFORM_MODULATED: False\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/Misc/mask_rcnn_R_50_FPN_3x_gn.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"catalog://ImageNetPretrained/FAIR/R-50-GN\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 50\n    NORM: \"GN\"\n    STRIDE_IN_1X1: False\n  FPN:\n    NORM: \"GN\"\n  ROI_BOX_HEAD:\n    NAME: \"FastRCNNConvFCHead\"\n    NUM_CONV: 4\n    NUM_FC: 1\n    NORM: \"GN\"\n  ROI_MASK_HEAD:\n    NORM: \"GN\"\nSOLVER:\n  # 3x schedule\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/configs/Misc/mask_rcnn_R_50_FPN_3x_syncbn.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 50\n    NORM: \"SyncBN\"\n    STRIDE_IN_1X1: True\n  FPN:\n    NORM: \"SyncBN\"\n  ROI_BOX_HEAD:\n    NAME: \"FastRCNNConvFCHead\"\n    NUM_CONV: 4\n    NUM_FC: 1\n    NORM: \"SyncBN\"\n  ROI_MASK_HEAD:\n    NORM: \"SyncBN\"\nSOLVER:\n  # 3x schedule\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\nTEST:\n  PRECISE_BN:\n    ENABLED: True\n"
  },
  {
    "path": "VPS_Module/configs/Misc/mmdet_mask_rcnn_R_50_FPN_1x.py",
    "content": "# An example config to train a mmdetection model using detectron2.\n\nfrom ..common.data.coco import dataloader\nfrom ..common.coco_schedule import lr_multiplier_1x as lr_multiplier\nfrom ..common.optim import SGD as optimizer\nfrom ..common.train import train\n\nfrom detectron2.modeling.mmdet_wrapper import MMDetDetector\nfrom detectron2.config import LazyCall as L\n\nmodel = L(MMDetDetector)(\n    detector=dict(\n        type=\"MaskRCNN\",\n        pretrained=\"torchvision://resnet50\",\n        backbone=dict(\n            type=\"ResNet\",\n            depth=50,\n            num_stages=4,\n            out_indices=(0, 1, 2, 3),\n            frozen_stages=1,\n            norm_cfg=dict(type=\"BN\", requires_grad=True),\n            norm_eval=True,\n            style=\"pytorch\",\n        ),\n        neck=dict(type=\"FPN\", in_channels=[256, 512, 1024, 2048], out_channels=256, num_outs=5),\n        rpn_head=dict(\n            type=\"RPNHead\",\n            in_channels=256,\n            feat_channels=256,\n            anchor_generator=dict(\n                type=\"AnchorGenerator\",\n                scales=[8],\n                ratios=[0.5, 1.0, 2.0],\n                strides=[4, 8, 16, 32, 64],\n            ),\n            bbox_coder=dict(\n                type=\"DeltaXYWHBBoxCoder\",\n                target_means=[0.0, 0.0, 0.0, 0.0],\n                target_stds=[1.0, 1.0, 1.0, 1.0],\n            ),\n            loss_cls=dict(type=\"CrossEntropyLoss\", use_sigmoid=True, loss_weight=1.0),\n            loss_bbox=dict(type=\"L1Loss\", loss_weight=1.0),\n        ),\n        roi_head=dict(\n            type=\"StandardRoIHead\",\n            bbox_roi_extractor=dict(\n                type=\"SingleRoIExtractor\",\n                roi_layer=dict(type=\"RoIAlign\", output_size=7, sampling_ratio=0),\n                out_channels=256,\n                featmap_strides=[4, 8, 16, 32],\n            ),\n            bbox_head=dict(\n                type=\"Shared2FCBBoxHead\",\n                in_channels=256,\n                fc_out_channels=1024,\n                roi_feat_size=7,\n                num_classes=80,\n                bbox_coder=dict(\n                    type=\"DeltaXYWHBBoxCoder\",\n                    target_means=[0.0, 0.0, 0.0, 0.0],\n                    target_stds=[0.1, 0.1, 0.2, 0.2],\n                ),\n                reg_class_agnostic=False,\n                loss_cls=dict(type=\"CrossEntropyLoss\", use_sigmoid=False, loss_weight=1.0),\n                loss_bbox=dict(type=\"L1Loss\", loss_weight=1.0),\n            ),\n            mask_roi_extractor=dict(\n                type=\"SingleRoIExtractor\",\n                roi_layer=dict(type=\"RoIAlign\", output_size=14, sampling_ratio=0),\n                out_channels=256,\n                featmap_strides=[4, 8, 16, 32],\n            ),\n            mask_head=dict(\n                type=\"FCNMaskHead\",\n                num_convs=4,\n                in_channels=256,\n                conv_out_channels=256,\n                num_classes=80,\n                loss_mask=dict(type=\"CrossEntropyLoss\", use_mask=True, loss_weight=1.0),\n            ),\n        ),\n        # model training and testing settings\n        train_cfg=dict(\n            rpn=dict(\n                assigner=dict(\n                    type=\"MaxIoUAssigner\",\n                    pos_iou_thr=0.7,\n                    neg_iou_thr=0.3,\n                    min_pos_iou=0.3,\n                    match_low_quality=True,\n                    ignore_iof_thr=-1,\n                ),\n                sampler=dict(\n                    type=\"RandomSampler\",\n                    num=256,\n                    pos_fraction=0.5,\n                    neg_pos_ub=-1,\n                    add_gt_as_proposals=False,\n                ),\n                allowed_border=-1,\n                pos_weight=-1,\n                debug=False,\n            ),\n            rpn_proposal=dict(\n                nms_pre=2000,\n                max_per_img=1000,\n                nms=dict(type=\"nms\", iou_threshold=0.7),\n                min_bbox_size=0,\n            ),\n            rcnn=dict(\n                assigner=dict(\n                    type=\"MaxIoUAssigner\",\n                    pos_iou_thr=0.5,\n                    neg_iou_thr=0.5,\n                    min_pos_iou=0.5,\n                    match_low_quality=True,\n                    ignore_iof_thr=-1,\n                ),\n                sampler=dict(\n                    type=\"RandomSampler\",\n                    num=512,\n                    pos_fraction=0.25,\n                    neg_pos_ub=-1,\n                    add_gt_as_proposals=True,\n                ),\n                mask_size=28,\n                pos_weight=-1,\n                debug=False,\n            ),\n        ),\n        test_cfg=dict(\n            rpn=dict(\n                nms_pre=1000,\n                max_per_img=1000,\n                nms=dict(type=\"nms\", iou_threshold=0.7),\n                min_bbox_size=0,\n            ),\n            rcnn=dict(\n                score_thr=0.05,\n                nms=dict(type=\"nms\", iou_threshold=0.5),\n                max_per_img=100,\n                mask_thr_binary=0.5,\n            ),\n        ),\n    ),\n    pixel_mean=[123.675, 116.280, 103.530],\n    pixel_std=[58.395, 57.120, 57.375],\n)\n\ndataloader.train.mapper.image_format = \"RGB\"  # torchvision pretrained model\ntrain.init_checkpoint = None  # pretrained model is loaded inside backbone\n"
  },
  {
    "path": "VPS_Module/configs/Misc/panoptic_fpn_R_101_dconv_cascade_gn_3x.yaml",
    "content": "# A large PanopticFPN for demo purposes.\n# Use GN on backbone to support semantic seg.\n# Use Cascade + Deform Conv to improve localization.\n_BASE_: \"../COCO-PanopticSegmentation/Base-Panoptic-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"catalog://ImageNetPretrained/FAIR/R-101-GN\"\n  RESNETS:\n    DEPTH: 101\n    NORM: \"GN\"\n    DEFORM_ON_PER_STAGE: [False, True, True, True]\n    STRIDE_IN_1X1: False\n  FPN:\n    NORM: \"GN\"\n  ROI_HEADS:\n    NAME: CascadeROIHeads\n  ROI_BOX_HEAD:\n    CLS_AGNOSTIC_BBOX_REG: True\n  ROI_MASK_HEAD:\n    NORM: \"GN\"\n  RPN:\n    POST_NMS_TOPK_TRAIN: 2000\nSOLVER:\n  STEPS: (105000, 125000)\n  MAX_ITER: 135000\n  IMS_PER_BATCH: 32\n  BASE_LR: 0.04\n"
  },
  {
    "path": "VPS_Module/configs/Misc/scratch_mask_rcnn_R_50_FPN_3x_gn.yaml",
    "content": "_BASE_: \"mask_rcnn_R_50_FPN_3x_gn.yaml\"\nMODEL:\n  # Train from random initialization.\n  WEIGHTS: \"\"\n  # It makes sense to divide by STD when training from scratch\n  # But it seems to make no difference on the results and C2's models didn't do this.\n  # So we keep things consistent with C2.\n  # PIXEL_STD: [57.375, 57.12, 58.395]\n  MASK_ON: True\n  BACKBONE:\n    FREEZE_AT: 0\n# NOTE: Please refer to Rethinking ImageNet Pre-training https://arxiv.org/abs/1811.08883\n# to learn what you need for training from scratch.\n"
  },
  {
    "path": "VPS_Module/configs/Misc/scratch_mask_rcnn_R_50_FPN_9x_gn.yaml",
    "content": "_BASE_: \"mask_rcnn_R_50_FPN_3x_gn.yaml\"\nMODEL:\n  PIXEL_STD: [57.375, 57.12, 58.395]\n  WEIGHTS: \"\"\n  MASK_ON: True\n  RESNETS:\n    STRIDE_IN_1X1: False\n  BACKBONE:\n    FREEZE_AT: 0\nSOLVER:\n  # 9x schedule\n  IMS_PER_BATCH: 64  # 4x the standard\n  STEPS: (187500, 197500)  # last 60/4==15k and last 20/4==5k\n  MAX_ITER: 202500   # 90k * 9 / 4\n  BASE_LR: 0.08\nTEST:\n  EVAL_PERIOD: 2500\n# NOTE: Please refer to Rethinking ImageNet Pre-training https://arxiv.org/abs/1811.08883\n# to learn what you need for training from scratch.\n"
  },
  {
    "path": "VPS_Module/configs/Misc/scratch_mask_rcnn_R_50_FPN_9x_syncbn.yaml",
    "content": "_BASE_: \"mask_rcnn_R_50_FPN_3x_syncbn.yaml\"\nMODEL:\n  PIXEL_STD: [57.375, 57.12, 58.395]\n  WEIGHTS: \"\"\n  MASK_ON: True\n  RESNETS:\n    STRIDE_IN_1X1: False\n  BACKBONE:\n    FREEZE_AT: 0\nSOLVER:\n  # 9x schedule\n  IMS_PER_BATCH: 64  # 4x the standard\n  STEPS: (187500, 197500)  # last 60/4==15k and last 20/4==5k\n  MAX_ITER: 202500   # 90k * 9 / 4\n  BASE_LR: 0.08\nTEST:\n  EVAL_PERIOD: 2500\n# NOTE: Please refer to Rethinking ImageNet Pre-training https://arxiv.org/abs/1811.08883\n# to learn what you need for training from scratch.\n"
  },
  {
    "path": "VPS_Module/configs/Misc/semantic_R_50_FPN_1x.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  META_ARCHITECTURE: \"SemanticSegmentor\"\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\nDATASETS:\n  TRAIN: (\"coco_2017_train_panoptic_stuffonly\",)\n  TEST: (\"coco_2017_val_panoptic_stuffonly\",)\nINPUT:\n  MIN_SIZE_TRAIN: (640, 672, 704, 736, 768, 800)\n"
  },
  {
    "path": "VPS_Module/configs/Misc/torchvision_imagenet_R_50.py",
    "content": "\"\"\"\nAn example config file to train a ImageNet classifier with detectron2.\nModel and dataloader both come from torchvision.\nThis shows how to use detectron2 as a general engine for any new models and tasks.\n\nTo run, use the following command:\n\npython tools/lazyconfig_train_net.py --config-file configs/Misc/torchvision_imagenet_R_50.py \\\n    --num-gpus 8 dataloader.train.dataset.root=/path/to/imagenet/\n\n\"\"\"\n\n\nimport torch\nfrom torch import nn\nfrom torch.nn import functional as F\nfrom omegaconf import OmegaConf\nimport torchvision\nfrom torchvision.transforms import transforms as T\nfrom torchvision.models.resnet import ResNet, Bottleneck\nfrom fvcore.common.param_scheduler import MultiStepParamScheduler\n\nfrom detectron2.solver import WarmupParamScheduler\nfrom detectron2.solver.build import get_default_optimizer_params\nfrom detectron2.config import LazyCall as L\nfrom detectron2.model_zoo import get_config\nfrom detectron2.data.samplers import TrainingSampler, InferenceSampler\nfrom detectron2.evaluation import DatasetEvaluator\nfrom detectron2.utils import comm\n\n\n\"\"\"\nNote: Here we put reusable code (models, evaluation, data) together with configs just as a\nproof-of-concept, to easily demonstrate what's needed to train a ImageNet classifier in detectron2.\nWriting code in configs offers extreme flexibility but is often not a good engineering practice.\nIn practice, you might want to put code in your project and import them instead.\n\"\"\"\n\n\ndef build_data_loader(dataset, batch_size, num_workers, training=True):\n    return torch.utils.data.DataLoader(\n        dataset,\n        sampler=(TrainingSampler if training else InferenceSampler)(len(dataset)),\n        batch_size=batch_size,\n        num_workers=num_workers,\n        pin_memory=True,\n    )\n\n\nclass ClassificationNet(nn.Module):\n    def __init__(self, model: nn.Module):\n        super().__init__()\n        self.model = model\n\n    @property\n    def device(self):\n        return list(self.model.parameters())[0].device\n\n    def forward(self, inputs):\n        image, label = inputs\n        pred = self.model(image.to(self.device))\n        if self.training:\n            label = label.to(self.device)\n            return F.cross_entropy(pred, label)\n        else:\n            return pred\n\n\nclass ClassificationAcc(DatasetEvaluator):\n    def reset(self):\n        self.corr = self.total = 0\n\n    def process(self, inputs, outputs):\n        image, label = inputs\n        self.corr += (outputs.argmax(dim=1).cpu() == label.cpu()).sum().item()\n        self.total += len(label)\n\n    def evaluate(self):\n        all_corr_total = comm.all_gather([self.corr, self.total])\n        corr = sum(x[0] for x in all_corr_total)\n        total = sum(x[1] for x in all_corr_total)\n        return {\"accuracy\": corr / total}\n\n\n# --- End of code that could be in a project and be imported\n\n\ndataloader = OmegaConf.create()\ndataloader.train = L(build_data_loader)(\n    dataset=L(torchvision.datasets.ImageNet)(\n        root=\"/path/to/imagenet\",\n        split=\"train\",\n        transform=L(T.Compose)(\n            transforms=[\n                L(T.RandomResizedCrop)(size=224),\n                L(T.RandomHorizontalFlip)(),\n                T.ToTensor(),\n                L(T.Normalize)(mean=(0.485, 0.456, 0.406), std=(0.229, 0.224, 0.225)),\n            ]\n        ),\n    ),\n    batch_size=256 // 8,\n    num_workers=4,\n    training=True,\n)\n\ndataloader.test = L(build_data_loader)(\n    dataset=L(torchvision.datasets.ImageNet)(\n        root=\"${...train.dataset.root}\",\n        split=\"val\",\n        transform=L(T.Compose)(\n            transforms=[\n                L(T.Resize)(size=256),\n                L(T.CenterCrop)(size=224),\n                T.ToTensor(),\n                L(T.Normalize)(mean=(0.485, 0.456, 0.406), std=(0.229, 0.224, 0.225)),\n            ]\n        ),\n    ),\n    batch_size=256 // 8,\n    num_workers=4,\n    training=False,\n)\n\ndataloader.evaluator = L(ClassificationAcc)()\n\nmodel = L(ClassificationNet)(\n    model=(ResNet)(block=Bottleneck, layers=[3, 4, 6, 3], zero_init_residual=True)\n)\n\n\noptimizer = L(torch.optim.SGD)(\n    params=L(get_default_optimizer_params)(),\n    lr=0.1,\n    momentum=0.9,\n    weight_decay=1e-4,\n)\n\nlr_multiplier = L(WarmupParamScheduler)(\n    scheduler=L(MultiStepParamScheduler)(\n        values=[1.0, 0.1, 0.01, 0.001], milestones=[30, 60, 90, 100]\n    ),\n    warmup_length=1 / 100,\n    warmup_factor=0.1,\n)\n\n\ntrain = get_config(\"common/train.py\").train\ntrain.init_checkpoint = None\ntrain.max_iter = 100 * 1281167 // 256\n"
  },
  {
    "path": "VPS_Module/configs/PascalVOC-Detection/faster_rcnn_R_50_C4.yaml",
    "content": "_BASE_: \"../Base-RCNN-C4.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: False\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    NUM_CLASSES: 20\nINPUT:\n  MIN_SIZE_TRAIN: (480, 512, 544, 576, 608, 640, 672, 704, 736, 768, 800)\n  MIN_SIZE_TEST: 800\nDATASETS:\n  TRAIN: ('voc_2007_trainval', 'voc_2012_trainval')\n  TEST: ('voc_2007_test',)\nSOLVER:\n  STEPS: (12000, 16000)\n  MAX_ITER: 18000  # 17.4 epochs\n  WARMUP_ITERS: 100\n"
  },
  {
    "path": "VPS_Module/configs/PascalVOC-Detection/faster_rcnn_R_50_FPN.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: False\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    NUM_CLASSES: 20\nINPUT:\n  MIN_SIZE_TRAIN: (480, 512, 544, 576, 608, 640, 672, 704, 736, 768, 800)\n  MIN_SIZE_TEST: 800\nDATASETS:\n  TRAIN: ('voc_2007_trainval', 'voc_2012_trainval')\n  TEST: ('voc_2007_test',)\nSOLVER:\n  STEPS: (12000, 16000)\n  MAX_ITER: 18000  # 17.4 epochs\n  WARMUP_ITERS: 100\n"
  },
  {
    "path": "VPS_Module/configs/common/README.md",
    "content": "This directory provides definitions for a few common models, dataloaders, scheduler,\nand optimizers that are often used in training.\nThe definition of these objects are provided in the form of lazy instantiation:\ntheir arguments can be edited by users before constructing the objects.\n\nThey can be imported, or loaded by `model_zoo.get_config` API in users' own configs.\n"
  },
  {
    "path": "VPS_Module/configs/common/coco_schedule.py",
    "content": "from fvcore.common.param_scheduler import MultiStepParamScheduler\n\nfrom detectron2.config import LazyCall as L\nfrom detectron2.solver import WarmupParamScheduler\n\n\ndef default_X_scheduler(num_X):\n    \"\"\"\n    Returns the config for a default multi-step LR scheduler such as \"1x\", \"3x\",\n    commonly referred to in papers, where every 1x has the total length of 1440k\n    training images (~12 COCO epochs). LR is decayed twice at the end of training\n    following the strategy defined in \"Rethinking ImageNet Pretraining\", Sec 4.\n\n    Args:\n        num_X: a positive real number\n\n    Returns:\n        DictConfig: configs that define the multiplier for LR during training\n    \"\"\"\n    # total number of iterations assuming 16 batch size, using 1440000/16=90000\n    total_steps_16bs = num_X * 90000\n\n    if num_X <= 2:\n        scheduler = L(MultiStepParamScheduler)(\n            values=[1.0, 0.1, 0.01],\n            # note that scheduler is scale-invariant. This is equivalent to\n            # milestones=[6, 8, 9]\n            milestones=[60000, 80000, 90000],\n        )\n    else:\n        scheduler = L(MultiStepParamScheduler)(\n            values=[1.0, 0.1, 0.01],\n            milestones=[total_steps_16bs - 60000, total_steps_16bs - 20000, total_steps_16bs],\n        )\n    return L(WarmupParamScheduler)(\n        scheduler=scheduler,\n        warmup_length=1000 / total_steps_16bs,\n        warmup_method=\"linear\",\n        warmup_factor=0.001,\n    )\n\n\nlr_multiplier_1x = default_X_scheduler(1)\nlr_multiplier_2x = default_X_scheduler(2)\nlr_multiplier_3x = default_X_scheduler(3)\nlr_multiplier_6x = default_X_scheduler(6)\nlr_multiplier_9x = default_X_scheduler(9)\n"
  },
  {
    "path": "VPS_Module/configs/common/models/cascade_rcnn.py",
    "content": "from detectron2.config import LazyCall as L\nfrom detectron2.layers import ShapeSpec\nfrom detectron2.modeling.box_regression import Box2BoxTransform\nfrom detectron2.modeling.matcher import Matcher\nfrom detectron2.modeling.roi_heads import FastRCNNOutputLayers, FastRCNNConvFCHead, CascadeROIHeads\n\nfrom .mask_rcnn_fpn import model\n\n# arguments that don't exist for Cascade R-CNN\n[model.roi_heads.pop(k) for k in [\"box_head\", \"box_predictor\", \"proposal_matcher\"]]\n\nmodel.roi_heads.update(\n    _target_=CascadeROIHeads,\n    box_heads=[\n        L(FastRCNNConvFCHead)(\n            input_shape=ShapeSpec(channels=256, height=7, width=7),\n            conv_dims=[],\n            fc_dims=[1024, 1024],\n        )\n        for k in range(3)\n    ],\n    box_predictors=[\n        L(FastRCNNOutputLayers)(\n            input_shape=ShapeSpec(channels=1024),\n            test_score_thresh=0.05,\n            box2box_transform=L(Box2BoxTransform)(weights=(w1, w1, w2, w2)),\n            cls_agnostic_bbox_reg=True,\n            num_classes=\"${...num_classes}\",\n        )\n        for (w1, w2) in [(10, 5), (20, 10), (30, 15)]\n    ],\n    proposal_matchers=[\n        L(Matcher)(thresholds=[th], labels=[0, 1], allow_low_quality_matches=False)\n        for th in [0.5, 0.6, 0.7]\n    ],\n)\n"
  },
  {
    "path": "VPS_Module/configs/common/models/fcos.py",
    "content": "from detectron2.modeling.meta_arch.fcos import FCOS, FCOSHead\n\nfrom .retinanet import model\n\nmodel._target_ = FCOS\n\ndel model.anchor_generator\ndel model.box2box_transform\ndel model.anchor_matcher\ndel model.input_format\n\n# Use P5 instead of C5 to compute P6/P7\n# (Sec 2.2 of https://arxiv.org/abs/2006.09214)\nmodel.backbone.top_block.in_feature = \"p5\"\nmodel.backbone.top_block.in_channels = 256\n\n# New score threshold determined based on sqrt(cls_score * centerness)\nmodel.test_score_thresh = 0.2\nmodel.test_nms_thresh = 0.6\n\nmodel.head._target_ = FCOSHead\ndel model.head.num_anchors\nmodel.head.norm = \"GN\"\n"
  },
  {
    "path": "VPS_Module/configs/common/models/keypoint_rcnn_fpn.py",
    "content": "from detectron2.config import LazyCall as L\nfrom detectron2.layers import ShapeSpec\nfrom detectron2.modeling.poolers import ROIPooler\nfrom detectron2.modeling.roi_heads import KRCNNConvDeconvUpsampleHead\n\nfrom .mask_rcnn_fpn import model\n\n[model.roi_heads.pop(x) for x in [\"mask_in_features\", \"mask_pooler\", \"mask_head\"]]\n\nmodel.roi_heads.update(\n    num_classes=1,\n    keypoint_in_features=[\"p2\", \"p3\", \"p4\", \"p5\"],\n    keypoint_pooler=L(ROIPooler)(\n        output_size=14,\n        scales=(1.0 / 4, 1.0 / 8, 1.0 / 16, 1.0 / 32),\n        sampling_ratio=0,\n        pooler_type=\"ROIAlignV2\",\n    ),\n    keypoint_head=L(KRCNNConvDeconvUpsampleHead)(\n        input_shape=ShapeSpec(channels=256, width=14, height=14),\n        num_keypoints=17,\n        conv_dims=[512] * 8,\n        loss_normalizer=\"visible\",\n    ),\n)\n\n# Detectron1 uses 2000 proposals per-batch, but this option is per-image in detectron2.\n# 1000 proposals per-image is found to hurt box AP.\n# Therefore we increase it to 1500 per-image.\nmodel.proposal_generator.post_nms_topk = (1500, 1000)\n\n# Keypoint AP degrades (though box AP improves) when using plain L1 loss\nmodel.roi_heads.box_predictor.smooth_l1_beta = 0.5\n"
  },
  {
    "path": "VPS_Module/configs/common/models/mask_rcnn_c4.py",
    "content": "from detectron2.config import LazyCall as L\nfrom detectron2.layers import ShapeSpec\nfrom detectron2.modeling.meta_arch import GeneralizedRCNN\nfrom detectron2.modeling.anchor_generator import DefaultAnchorGenerator\nfrom detectron2.modeling.backbone import BasicStem, BottleneckBlock, ResNet\nfrom detectron2.modeling.box_regression import Box2BoxTransform\nfrom detectron2.modeling.matcher import Matcher\nfrom detectron2.modeling.poolers import ROIPooler\nfrom detectron2.modeling.proposal_generator import RPN, StandardRPNHead\nfrom detectron2.modeling.roi_heads import (\n    FastRCNNOutputLayers,\n    MaskRCNNConvUpsampleHead,\n    Res5ROIHeads,\n)\n\nmodel = L(GeneralizedRCNN)(\n    backbone=L(ResNet)(\n        stem=L(BasicStem)(in_channels=3, out_channels=64, norm=\"FrozenBN\"),\n        stages=L(ResNet.make_default_stages)(\n            depth=50,\n            stride_in_1x1=True,\n            norm=\"FrozenBN\",\n        ),\n        out_features=[\"res4\"],\n    ),\n    proposal_generator=L(RPN)(\n        in_features=[\"res4\"],\n        head=L(StandardRPNHead)(in_channels=1024, num_anchors=15),\n        anchor_generator=L(DefaultAnchorGenerator)(\n            sizes=[[32, 64, 128, 256, 512]],\n            aspect_ratios=[0.5, 1.0, 2.0],\n            strides=[16],\n            offset=0.0,\n        ),\n        anchor_matcher=L(Matcher)(\n            thresholds=[0.3, 0.7], labels=[0, -1, 1], allow_low_quality_matches=True\n        ),\n        box2box_transform=L(Box2BoxTransform)(weights=[1.0, 1.0, 1.0, 1.0]),\n        batch_size_per_image=256,\n        positive_fraction=0.5,\n        pre_nms_topk=(12000, 6000),\n        post_nms_topk=(2000, 1000),\n        nms_thresh=0.7,\n    ),\n    roi_heads=L(Res5ROIHeads)(\n        num_classes=80,\n        batch_size_per_image=512,\n        positive_fraction=0.25,\n        proposal_matcher=L(Matcher)(\n            thresholds=[0.5], labels=[0, 1], allow_low_quality_matches=False\n        ),\n        in_features=[\"res4\"],\n        pooler=L(ROIPooler)(\n            output_size=14,\n            scales=(1.0 / 16,),\n            sampling_ratio=0,\n            pooler_type=\"ROIAlignV2\",\n        ),\n        res5=L(ResNet.make_stage)(\n            block_class=BottleneckBlock,\n            num_blocks=3,\n            stride_per_block=[2, 1, 1],\n            in_channels=1024,\n            bottleneck_channels=512,\n            out_channels=2048,\n            norm=\"FrozenBN\",\n            stride_in_1x1=True,\n        ),\n        box_predictor=L(FastRCNNOutputLayers)(\n            input_shape=L(ShapeSpec)(channels=\"${...res5.out_channels}\", height=1, width=1),\n            test_score_thresh=0.05,\n            box2box_transform=L(Box2BoxTransform)(weights=(10, 10, 5, 5)),\n            num_classes=\"${..num_classes}\",\n        ),\n        mask_head=L(MaskRCNNConvUpsampleHead)(\n            input_shape=L(ShapeSpec)(\n                channels=\"${...res5.out_channels}\",\n                width=\"${...pooler.output_size}\",\n                height=\"${...pooler.output_size}\",\n            ),\n            num_classes=\"${..num_classes}\",\n            conv_dims=[256],\n        ),\n    ),\n    pixel_mean=[103.530, 116.280, 123.675],\n    pixel_std=[1.0, 1.0, 1.0],\n    input_format=\"BGR\",\n)\n"
  },
  {
    "path": "VPS_Module/configs/common/models/mask_rcnn_fpn.py",
    "content": "from detectron2.config import LazyCall as L\nfrom detectron2.layers import ShapeSpec\nfrom detectron2.modeling.meta_arch import GeneralizedRCNN\nfrom detectron2.modeling.anchor_generator import DefaultAnchorGenerator\nfrom detectron2.modeling.backbone.fpn import LastLevelMaxPool\nfrom detectron2.modeling.backbone import BasicStem, FPN, ResNet\nfrom detectron2.modeling.box_regression import Box2BoxTransform\nfrom detectron2.modeling.matcher import Matcher\nfrom detectron2.modeling.poolers import ROIPooler\nfrom detectron2.modeling.proposal_generator import RPN, StandardRPNHead\nfrom detectron2.modeling.roi_heads import (\n    StandardROIHeads,\n    FastRCNNOutputLayers,\n    MaskRCNNConvUpsampleHead,\n    FastRCNNConvFCHead,\n)\n\nmodel = L(GeneralizedRCNN)(\n    backbone=L(FPN)(\n        bottom_up=L(ResNet)(\n            stem=L(BasicStem)(in_channels=3, out_channels=64, norm=\"FrozenBN\"),\n            stages=L(ResNet.make_default_stages)(\n                depth=50,\n                stride_in_1x1=True,\n                norm=\"FrozenBN\",\n            ),\n            out_features=[\"res2\", \"res3\", \"res4\", \"res5\"],\n        ),\n        in_features=\"${.bottom_up.out_features}\",\n        out_channels=256,\n        top_block=L(LastLevelMaxPool)(),\n    ),\n    proposal_generator=L(RPN)(\n        in_features=[\"p2\", \"p3\", \"p4\", \"p5\", \"p6\"],\n        head=L(StandardRPNHead)(in_channels=256, num_anchors=3),\n        anchor_generator=L(DefaultAnchorGenerator)(\n            sizes=[[32], [64], [128], [256], [512]],\n            aspect_ratios=[0.5, 1.0, 2.0],\n            strides=[4, 8, 16, 32, 64],\n            offset=0.0,\n        ),\n        anchor_matcher=L(Matcher)(\n            thresholds=[0.3, 0.7], labels=[0, -1, 1], allow_low_quality_matches=True\n        ),\n        box2box_transform=L(Box2BoxTransform)(weights=[1.0, 1.0, 1.0, 1.0]),\n        batch_size_per_image=256,\n        positive_fraction=0.5,\n        pre_nms_topk=(2000, 1000),\n        post_nms_topk=(1000, 1000),\n        nms_thresh=0.7,\n    ),\n    roi_heads=L(StandardROIHeads)(\n        num_classes=80,\n        batch_size_per_image=512,\n        positive_fraction=0.25,\n        proposal_matcher=L(Matcher)(\n            thresholds=[0.5], labels=[0, 1], allow_low_quality_matches=False\n        ),\n        box_in_features=[\"p2\", \"p3\", \"p4\", \"p5\"],\n        box_pooler=L(ROIPooler)(\n            output_size=7,\n            scales=(1.0 / 4, 1.0 / 8, 1.0 / 16, 1.0 / 32),\n            sampling_ratio=0,\n            pooler_type=\"ROIAlignV2\",\n        ),\n        box_head=L(FastRCNNConvFCHead)(\n            input_shape=ShapeSpec(channels=256, height=7, width=7),\n            conv_dims=[],\n            fc_dims=[1024, 1024],\n        ),\n        box_predictor=L(FastRCNNOutputLayers)(\n            input_shape=ShapeSpec(channels=1024),\n            test_score_thresh=0.05,\n            box2box_transform=L(Box2BoxTransform)(weights=(10, 10, 5, 5)),\n            num_classes=\"${..num_classes}\",\n        ),\n        mask_in_features=[\"p2\", \"p3\", \"p4\", \"p5\"],\n        mask_pooler=L(ROIPooler)(\n            output_size=14,\n            scales=(1.0 / 4, 1.0 / 8, 1.0 / 16, 1.0 / 32),\n            sampling_ratio=0,\n            pooler_type=\"ROIAlignV2\",\n        ),\n        mask_head=L(MaskRCNNConvUpsampleHead)(\n            input_shape=ShapeSpec(channels=256, width=14, height=14),\n            num_classes=\"${..num_classes}\",\n            conv_dims=[256, 256, 256, 256, 256],\n        ),\n    ),\n    pixel_mean=[103.530, 116.280, 123.675],\n    pixel_std=[1.0, 1.0, 1.0],\n    input_format=\"BGR\",\n)\n"
  },
  {
    "path": "VPS_Module/configs/common/models/panoptic_fpn.py",
    "content": "from detectron2.config import LazyCall as L\nfrom detectron2.layers import ShapeSpec\nfrom detectron2.modeling import PanopticFPN\nfrom detectron2.modeling.meta_arch.semantic_seg import SemSegFPNHead\n\nfrom .mask_rcnn_fpn import model\n\nmodel._target_ = PanopticFPN\nmodel.sem_seg_head = L(SemSegFPNHead)(\n    input_shape={\n        f: L(ShapeSpec)(stride=s, channels=\"${....backbone.out_channels}\")\n        for f, s in zip([\"p2\", \"p3\", \"p4\", \"p5\"], [4, 8, 16, 32])\n    },\n    ignore_value=255,\n    num_classes= 54,  # COCO stuff + 1\n    conv_dims=128,\n    common_stride=4,\n    loss_weight=0.5,\n    norm=\"GN\",\n)\n"
  },
  {
    "path": "VPS_Module/configs/common/models/retinanet.py",
    "content": "# -*- coding: utf-8 -*-\n\nfrom detectron2.config import LazyCall as L\nfrom detectron2.layers import ShapeSpec\nfrom detectron2.modeling.meta_arch import RetinaNet\nfrom detectron2.modeling.anchor_generator import DefaultAnchorGenerator\nfrom detectron2.modeling.backbone.fpn import LastLevelP6P7\nfrom detectron2.modeling.backbone import BasicStem, FPN, ResNet\nfrom detectron2.modeling.box_regression import Box2BoxTransform\nfrom detectron2.modeling.matcher import Matcher\nfrom detectron2.modeling.meta_arch.retinanet import RetinaNetHead\n\nmodel = L(RetinaNet)(\n    backbone=L(FPN)(\n        bottom_up=L(ResNet)(\n            stem=L(BasicStem)(in_channels=3, out_channels=64, norm=\"FrozenBN\"),\n            stages=L(ResNet.make_default_stages)(\n                depth=50,\n                stride_in_1x1=True,\n                norm=\"FrozenBN\",\n            ),\n            out_features=[\"res3\", \"res4\", \"res5\"],\n        ),\n        in_features=[\"res3\", \"res4\", \"res5\"],\n        out_channels=256,\n        top_block=L(LastLevelP6P7)(in_channels=2048, out_channels=\"${..out_channels}\"),\n    ),\n    head=L(RetinaNetHead)(\n        # Shape for each input feature map\n        input_shape=[ShapeSpec(channels=256)] * 5,\n        num_classes=\"${..num_classes}\",\n        conv_dims=[256, 256, 256, 256],\n        prior_prob=0.01,\n        num_anchors=9,\n    ),\n    anchor_generator=L(DefaultAnchorGenerator)(\n        sizes=[[x, x * 2 ** (1.0 / 3), x * 2 ** (2.0 / 3)] for x in [32, 64, 128, 256, 512]],\n        aspect_ratios=[0.5, 1.0, 2.0],\n        strides=[8, 16, 32, 64, 128],\n        offset=0.0,\n    ),\n    box2box_transform=L(Box2BoxTransform)(weights=[1.0, 1.0, 1.0, 1.0]),\n    anchor_matcher=L(Matcher)(\n        thresholds=[0.4, 0.5], labels=[0, -1, 1], allow_low_quality_matches=True\n    ),\n    num_classes=80,\n    head_in_features=[\"p3\", \"p4\", \"p5\", \"p6\", \"p7\"],\n    focal_loss_alpha=0.25,\n    focal_loss_gamma=2.0,\n    pixel_mean=[103.530, 116.280, 123.675],\n    pixel_std=[1.0, 1.0, 1.0],\n    input_format=\"BGR\",\n)\n"
  },
  {
    "path": "VPS_Module/configs/common/optim.py",
    "content": "import torch\n\nfrom detectron2.config import LazyCall as L\nfrom detectron2.solver.build import get_default_optimizer_params\n\nSGD = L(torch.optim.SGD)(\n    params=L(get_default_optimizer_params)(\n        # params.model is meant to be set to the model object, before instantiating\n        # the optimizer.\n        weight_decay_norm=0.0\n    ),\n    lr=0.02,\n    momentum=0.9,\n    weight_decay=1e-4,\n)\n"
  },
  {
    "path": "VPS_Module/configs/common/train.py",
    "content": "# Common training-related configs that are designed for \"tools/lazyconfig_train_net.py\"\n# You can use your own instead, together with your own train_net.py\ntrain = dict(\n    output_dir=\"./output\",\n    init_checkpoint=\"\",\n    max_iter=90000,\n    amp=dict(enabled=False),  # options for Automatic Mixed Precision\n    ddp=dict(  # options for DistributedDataParallel\n        broadcast_buffers=False,\n        find_unused_parameters=False,\n        fp16_compression=False,\n    ),\n    checkpointer=dict(period=5000, max_to_keep=100),  # options for PeriodicCheckpointer\n    eval_period=5000,\n    log_period=20,\n    device=\"cuda\"\n    # ...\n)\n"
  },
  {
    "path": "VPS_Module/configs/new_baselines/mask_rcnn_R_101_FPN_100ep_LSJ.py",
    "content": "from .mask_rcnn_R_50_FPN_100ep_LSJ import (\n    dataloader,\n    lr_multiplier,\n    model,\n    optimizer,\n    train,\n)\n\nmodel.backbone.bottom_up.stages.depth = 101\n"
  },
  {
    "path": "VPS_Module/configs/new_baselines/mask_rcnn_R_101_FPN_200ep_LSJ.py",
    "content": "from .mask_rcnn_R_101_FPN_100ep_LSJ import (\n    dataloader,\n    lr_multiplier,\n    model,\n    optimizer,\n    train,\n)\n\ntrain.max_iter *= 2  # 100ep -> 200ep\n\nlr_multiplier.scheduler.milestones = [\n    milestone * 2 for milestone in lr_multiplier.scheduler.milestones\n]\nlr_multiplier.scheduler.num_updates = train.max_iter\n"
  },
  {
    "path": "VPS_Module/configs/new_baselines/mask_rcnn_R_101_FPN_400ep_LSJ.py",
    "content": "from .mask_rcnn_R_101_FPN_100ep_LSJ import (\n    dataloader,\n    lr_multiplier,\n    model,\n    optimizer,\n    train,\n)\n\ntrain.max_iter *= 4  # 100ep -> 400ep\n\nlr_multiplier.scheduler.milestones = [\n    milestone * 4 for milestone in lr_multiplier.scheduler.milestones\n]\nlr_multiplier.scheduler.num_updates = train.max_iter\n"
  },
  {
    "path": "VPS_Module/configs/new_baselines/mask_rcnn_R_50_FPN_100ep_LSJ.py",
    "content": "import detectron2.data.transforms as T\nfrom detectron2.config.lazy import LazyCall as L\nfrom detectron2.layers.batch_norm import NaiveSyncBatchNorm\nfrom detectron2.solver import WarmupParamScheduler\nfrom fvcore.common.param_scheduler import MultiStepParamScheduler\n\nfrom ..common.data.coco import dataloader\nfrom ..common.models.mask_rcnn_fpn import model\nfrom ..common.optim import SGD as optimizer\nfrom ..common.train import train\n\n# train from scratch\ntrain.init_checkpoint = \"\"\ntrain.amp.enabled = True\ntrain.ddp.fp16_compression = True\nmodel.backbone.bottom_up.freeze_at = 0\n\n# SyncBN\n# fmt: off\nmodel.backbone.bottom_up.stem.norm = \\\n    model.backbone.bottom_up.stages.norm = \\\n    model.backbone.norm = \"SyncBN\"\n\n# Using NaiveSyncBatchNorm becase heads may have empty input. That is not supported by\n# torch.nn.SyncBatchNorm. We can remove this after\n# https://github.com/pytorch/pytorch/issues/36530 is fixed.\nmodel.roi_heads.box_head.conv_norm = \\\n    model.roi_heads.mask_head.conv_norm = lambda c: NaiveSyncBatchNorm(c,\n                                                                       stats_mode=\"N\")\n# fmt: on\n\n# 2conv in RPN:\n# https://github.com/tensorflow/tpu/blob/b24729de804fdb751b06467d3dce0637fa652060/models/official/detection/modeling/architecture/heads.py#L95-L97  # noqa: E501, B950\nmodel.proposal_generator.head.conv_dims = [-1, -1]\n\n# 4conv1fc box head\nmodel.roi_heads.box_head.conv_dims = [256, 256, 256, 256]\nmodel.roi_heads.box_head.fc_dims = [1024]\n\n# resize_and_crop_image in:\n# https://github.com/tensorflow/tpu/blob/b24729de804fdb751b06467d3dce0637fa652060/models/official/detection/utils/input_utils.py#L127  # noqa: E501, B950\nimage_size = 1024\ndataloader.train.mapper.augmentations = [\n    L(T.ResizeScale)(\n        min_scale=0.1, max_scale=2.0, target_height=image_size, target_width=image_size\n    ),\n    L(T.FixedSizeCrop)(crop_size=(image_size, image_size)),\n    L(T.RandomFlip)(horizontal=True),\n]\n\n# recompute boxes due to cropping\ndataloader.train.mapper.recompute_boxes = True\n\n# larger batch-size.\ndataloader.train.total_batch_size = 64\n\n# Equivalent to 100 epochs.\n# 100 ep = 184375 iters * 64 images/iter / 118000 images/ep\ntrain.max_iter = 184375\n\nlr_multiplier = L(WarmupParamScheduler)(\n    scheduler=L(MultiStepParamScheduler)(\n        values=[1.0, 0.1, 0.01],\n        milestones=[163889, 177546],\n        num_updates=train.max_iter,\n    ),\n    warmup_length=500 / train.max_iter,\n    warmup_factor=0.067,\n)\n\noptimizer.lr = 0.1\noptimizer.weight_decay = 4e-5\n"
  },
  {
    "path": "VPS_Module/configs/new_baselines/mask_rcnn_R_50_FPN_200ep_LSJ.py",
    "content": "from .mask_rcnn_R_50_FPN_100ep_LSJ import (\n    dataloader,\n    lr_multiplier,\n    model,\n    optimizer,\n    train,\n)\n\ntrain.max_iter *= 2  # 100ep -> 200ep\n\nlr_multiplier.scheduler.milestones = [\n    milestone * 2 for milestone in lr_multiplier.scheduler.milestones\n]\nlr_multiplier.scheduler.num_updates = train.max_iter\n"
  },
  {
    "path": "VPS_Module/configs/new_baselines/mask_rcnn_R_50_FPN_400ep_LSJ.py",
    "content": "from .mask_rcnn_R_50_FPN_100ep_LSJ import (\n    dataloader,\n    lr_multiplier,\n    model,\n    optimizer,\n    train,\n)\n\ntrain.max_iter *= 4  # 100ep -> 400ep\n\nlr_multiplier.scheduler.milestones = [\n    milestone * 4 for milestone in lr_multiplier.scheduler.milestones\n]\nlr_multiplier.scheduler.num_updates = train.max_iter\n"
  },
  {
    "path": "VPS_Module/configs/new_baselines/mask_rcnn_R_50_FPN_50ep_LSJ.py",
    "content": "from .mask_rcnn_R_50_FPN_100ep_LSJ import (\n    dataloader,\n    lr_multiplier,\n    model,\n    optimizer,\n    train,\n)\n\ntrain.max_iter //= 2  # 100ep -> 50ep\n\nlr_multiplier.scheduler.milestones = [\n    milestone // 2 for milestone in lr_multiplier.scheduler.milestones\n]\nlr_multiplier.scheduler.num_updates = train.max_iter\n"
  },
  {
    "path": "VPS_Module/configs/new_baselines/mask_rcnn_regnetx_4gf_dds_FPN_100ep_LSJ.py",
    "content": "from .mask_rcnn_R_50_FPN_100ep_LSJ import (\n    dataloader,\n    lr_multiplier,\n    model,\n    optimizer,\n    train,\n)\nfrom detectron2.config import LazyCall as L\nfrom detectron2.modeling.backbone import RegNet\nfrom detectron2.modeling.backbone.regnet import SimpleStem, ResBottleneckBlock\n\n# Config source:\n# https://github.com/facebookresearch/detectron2/blob/main/configs/COCO-InstanceSegmentation/mask_rcnn_regnetx_4gf_dds_fpn_1x.py  # noqa\nmodel.backbone.bottom_up = L(RegNet)(\n    stem_class=SimpleStem,\n    stem_width=32,\n    block_class=ResBottleneckBlock,\n    depth=23,\n    w_a=38.65,\n    w_0=96,\n    w_m=2.43,\n    group_width=40,\n    norm=\"SyncBN\",\n    out_features=[\"s1\", \"s2\", \"s3\", \"s4\"],\n)\nmodel.pixel_std = [57.375, 57.120, 58.395]\n\n# RegNets benefit from enabling cudnn benchmark mode\ntrain.cudnn_benchmark = True\n"
  },
  {
    "path": "VPS_Module/configs/new_baselines/mask_rcnn_regnetx_4gf_dds_FPN_200ep_LSJ.py",
    "content": "from .mask_rcnn_regnetx_4gf_dds_FPN_100ep_LSJ import (\n    dataloader,\n    lr_multiplier,\n    model,\n    optimizer,\n    train,\n)\n\ntrain.max_iter *= 2  # 100ep -> 200ep\n\nlr_multiplier.scheduler.milestones = [\n    milestone * 2 for milestone in lr_multiplier.scheduler.milestones\n]\nlr_multiplier.scheduler.num_updates = train.max_iter\n"
  },
  {
    "path": "VPS_Module/configs/new_baselines/mask_rcnn_regnetx_4gf_dds_FPN_400ep_LSJ.py",
    "content": "from .mask_rcnn_regnetx_4gf_dds_FPN_100ep_LSJ import (\n    dataloader,\n    lr_multiplier,\n    model,\n    optimizer,\n    train,\n)\n\ntrain.max_iter *= 4  # 100ep -> 400ep\n\nlr_multiplier.scheduler.milestones = [\n    milestone * 4 for milestone in lr_multiplier.scheduler.milestones\n]\nlr_multiplier.scheduler.num_updates = train.max_iter\n"
  },
  {
    "path": "VPS_Module/configs/new_baselines/mask_rcnn_regnety_4gf_dds_FPN_100ep_LSJ.py",
    "content": "from .mask_rcnn_R_50_FPN_100ep_LSJ import (\n    dataloader,\n    lr_multiplier,\n    model,\n    optimizer,\n    train,\n)\nfrom detectron2.config import LazyCall as L\nfrom detectron2.modeling.backbone import RegNet\nfrom detectron2.modeling.backbone.regnet import SimpleStem, ResBottleneckBlock\n\n# Config source:\n# https://github.com/facebookresearch/detectron2/blob/main/configs/COCO-InstanceSegmentation/mask_rcnn_regnety_4gf_dds_fpn_1x.py  # noqa\nmodel.backbone.bottom_up = L(RegNet)(\n    stem_class=SimpleStem,\n    stem_width=32,\n    block_class=ResBottleneckBlock,\n    depth=22,\n    w_a=31.41,\n    w_0=96,\n    w_m=2.24,\n    group_width=64,\n    se_ratio=0.25,\n    norm=\"SyncBN\",\n    out_features=[\"s1\", \"s2\", \"s3\", \"s4\"],\n)\nmodel.pixel_std = [57.375, 57.120, 58.395]\n\n# RegNets benefit from enabling cudnn benchmark mode\ntrain.cudnn_benchmark = True\n"
  },
  {
    "path": "VPS_Module/configs/new_baselines/mask_rcnn_regnety_4gf_dds_FPN_200ep_LSJ.py",
    "content": "from .mask_rcnn_regnety_4gf_dds_FPN_100ep_LSJ import (\n    dataloader,\n    lr_multiplier,\n    model,\n    optimizer,\n    train,\n)\n\ntrain.max_iter *= 2  # 100ep -> 200ep\n\nlr_multiplier.scheduler.milestones = [\n    milestone * 2 for milestone in lr_multiplier.scheduler.milestones\n]\nlr_multiplier.scheduler.num_updates = train.max_iter\n"
  },
  {
    "path": "VPS_Module/configs/new_baselines/mask_rcnn_regnety_4gf_dds_FPN_400ep_LSJ.py",
    "content": "from .mask_rcnn_regnety_4gf_dds_FPN_100ep_LSJ import (\n    dataloader,\n    lr_multiplier,\n    model,\n    optimizer,\n    train,\n)\n\ntrain.max_iter *= 4  # 100ep -> 400ep\n\nlr_multiplier.scheduler.milestones = [\n    milestone * 4 for milestone in lr_multiplier.scheduler.milestones\n]\nlr_multiplier.scheduler.num_updates = train.max_iter\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/README.md",
    "content": "These are quick configs for performance or accuracy regression tracking purposes.\n\n* `*instance_test.yaml`: can train on 2 GPUs. They are used to test whether the training can\n  successfully finish. They are not expected to produce reasonable training results.\n* `*inference_acc_test.yaml`: They should be run using `--eval-only`. They run inference using pre-trained models and verify\n  the results are as expected.\n* `*training_acc_test.yaml`: They should be trained on 8 GPUs. They finish in about an hour and verify the training accuracy\n  is within the normal range.\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/cascade_mask_rcnn_R_50_FPN_inference_acc_test.yaml",
    "content": "_BASE_: \"../Misc/cascade_mask_rcnn_R_50_FPN_3x.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://Misc/cascade_mask_rcnn_R_50_FPN_3x/144998488/model_final_480dd8.pkl\"\nDATASETS:\n  TEST: (\"coco_2017_val_100\",)\nTEST:\n  EXPECTED_RESULTS: [[\"bbox\", \"AP\", 50.18, 0.02], [\"segm\", \"AP\",  43.87, 0.02]]\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/cascade_mask_rcnn_R_50_FPN_instant_test.yaml",
    "content": "_BASE_: \"../Misc/cascade_mask_rcnn_R_50_FPN_3x.yaml\"\nDATASETS:\n  TRAIN: (\"coco_2017_val_100\",)\n  TEST: (\"coco_2017_val_100\",)\nSOLVER:\n  BASE_LR: 0.005\n  STEPS: (30,)\n  MAX_ITER: 40\n  IMS_PER_BATCH: 4\nDATALOADER:\n  NUM_WORKERS: 2\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/fast_rcnn_R_50_FPN_inference_acc_test.yaml",
    "content": "_BASE_: \"../COCO-Detection/fast_rcnn_R_50_FPN_1x.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://COCO-Detection/fast_rcnn_R_50_FPN_1x/137635226/model_final_e5f7ce.pkl\"\nDATASETS:\n  TEST: (\"coco_2017_val_100\",)\nTEST:\n  EXPECTED_RESULTS: [[\"bbox\", \"AP\", 45.70, 0.02]]\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/fast_rcnn_R_50_FPN_instant_test.yaml",
    "content": "_BASE_: \"../COCO-Detection/fast_rcnn_R_50_FPN_1x.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\nDATASETS:\n  TRAIN: (\"coco_2017_val_100\",)\n  PROPOSAL_FILES_TRAIN: (\"detectron2://COCO-Detection/rpn_R_50_FPN_1x/137258492/coco_2017_val_box_proposals_ee0dad.pkl\", )\n  TEST: (\"coco_2017_val_100\",)\n  PROPOSAL_FILES_TEST: (\"detectron2://COCO-Detection/rpn_R_50_FPN_1x/137258492/coco_2017_val_box_proposals_ee0dad.pkl\", )\nSOLVER:\n  BASE_LR: 0.005\n  STEPS: (30,)\n  MAX_ITER: 40\n  IMS_PER_BATCH: 4\nDATALOADER:\n  NUM_WORKERS: 2\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/keypoint_rcnn_R_50_FPN_inference_acc_test.yaml",
    "content": "_BASE_: \"../COCO-Keypoints/keypoint_rcnn_R_50_FPN_3x.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://COCO-Keypoints/keypoint_rcnn_R_50_FPN_3x/137849621/model_final_a6e10b.pkl\"\nDATASETS:\n  TEST: (\"keypoints_coco_2017_val_100\",)\nTEST:\n  EXPECTED_RESULTS: [[\"bbox\", \"AP\", 52.47, 0.02], [\"keypoints\", \"AP\", 67.36, 0.02]]\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/keypoint_rcnn_R_50_FPN_instant_test.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  KEYPOINT_ON: True\n  ROI_HEADS:\n    NUM_CLASSES: 1\nDATASETS:\n  TRAIN: (\"keypoints_coco_2017_val_100\",)\n  TEST: (\"keypoints_coco_2017_val_100\",)\nSOLVER:\n  BASE_LR: 0.005\n  STEPS: (30,)\n  MAX_ITER: 40\n  IMS_PER_BATCH: 4\nDATALOADER:\n  NUM_WORKERS: 2\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/keypoint_rcnn_R_50_FPN_normalized_training_acc_test.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  KEYPOINT_ON: True\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    BATCH_SIZE_PER_IMAGE: 256\n    NUM_CLASSES: 1\n  ROI_KEYPOINT_HEAD:\n    POOLER_RESOLUTION: 14\n    POOLER_SAMPLING_RATIO: 2\n    NORMALIZE_LOSS_BY_VISIBLE_KEYPOINTS: False\n    LOSS_WEIGHT: 4.0\n  ROI_BOX_HEAD:\n    SMOOTH_L1_BETA: 1.0  # Keypoint AP degrades when using plain L1 loss\n  RPN:\n    SMOOTH_L1_BETA: 0.2  # Keypoint AP degrades when using plain L1 loss\nDATASETS:\n  TRAIN: (\"keypoints_coco_2017_val\",)\n  TEST: (\"keypoints_coco_2017_val\",)\nINPUT:\n  MIN_SIZE_TRAIN: (640, 672, 704, 736, 768, 800)\nSOLVER:\n  WARMUP_FACTOR: 0.33333333\n  WARMUP_ITERS: 100\n  STEPS: (5500, 5800)\n  MAX_ITER: 6000\nTEST:\n  EXPECTED_RESULTS: [[\"bbox\", \"AP\", 55.35, 1.0], [\"keypoints\", \"AP\", 76.91, 1.0]]\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/keypoint_rcnn_R_50_FPN_training_acc_test.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  KEYPOINT_ON: True\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    BATCH_SIZE_PER_IMAGE: 256\n    NUM_CLASSES: 1\n  ROI_KEYPOINT_HEAD:\n    POOLER_RESOLUTION: 14\n    POOLER_SAMPLING_RATIO: 2\n  ROI_BOX_HEAD:\n    SMOOTH_L1_BETA: 1.0  # Keypoint AP degrades when using plain L1 loss\n  RPN:\n    SMOOTH_L1_BETA: 0.2  # Keypoint AP degrades when using plain L1 loss\nDATASETS:\n  TRAIN: (\"keypoints_coco_2017_val\",)\n  TEST: (\"keypoints_coco_2017_val\",)\nINPUT:\n  MIN_SIZE_TRAIN: (640, 672, 704, 736, 768, 800)\nSOLVER:\n  WARMUP_FACTOR: 0.33333333\n  WARMUP_ITERS: 100\n  STEPS: (5500, 5800)\n  MAX_ITER: 6000\nTEST:\n  EXPECTED_RESULTS: [[\"bbox\", \"AP\", 53.5, 1.0], [\"keypoints\", \"AP\", 72.4, 1.0]]\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/mask_rcnn_R_50_C4_GCV_instant_test.yaml",
    "content": "_BASE_: \"../Base-RCNN-C4.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\nDATASETS:\n  TRAIN: (\"coco_2017_val_100\",)\n  TEST: (\"coco_2017_val_100\",)\nSOLVER:\n  BASE_LR: 0.001\n  STEPS: (30,)\n  MAX_ITER: 40\n  IMS_PER_BATCH: 4\n  CLIP_GRADIENTS:\n    ENABLED: True\n    CLIP_TYPE: \"value\"\n    CLIP_VALUE: 1.0\nDATALOADER:\n  NUM_WORKERS: 2\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/mask_rcnn_R_50_C4_inference_acc_test.yaml",
    "content": "_BASE_: \"../COCO-InstanceSegmentation/mask_rcnn_R_50_C4_3x.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://COCO-InstanceSegmentation/mask_rcnn_R_50_C4_3x/137849525/model_final_4ce675.pkl\"\nDATASETS:\n  TEST: (\"coco_2017_val_100\",)\nTEST:\n  EXPECTED_RESULTS: [[\"bbox\", \"AP\", 47.37, 0.02], [\"segm\", \"AP\", 40.99, 0.02]]\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/mask_rcnn_R_50_C4_instant_test.yaml",
    "content": "_BASE_: \"../Base-RCNN-C4.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\nDATASETS:\n  TRAIN: (\"coco_2017_val_100\",)\n  TEST: (\"coco_2017_val_100\",)\nSOLVER:\n  BASE_LR: 0.001\n  STEPS: (30,)\n  MAX_ITER: 40\n  IMS_PER_BATCH: 4\nDATALOADER:\n  NUM_WORKERS: 2\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/mask_rcnn_R_50_C4_training_acc_test.yaml",
    "content": "_BASE_: \"../Base-RCNN-C4.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  ROI_HEADS:\n    BATCH_SIZE_PER_IMAGE: 256\n  MASK_ON: True\nDATASETS:\n  TRAIN: (\"coco_2017_val\",)\n  TEST: (\"coco_2017_val\",)\nINPUT:\n  MIN_SIZE_TRAIN: (600,)\n  MAX_SIZE_TRAIN: 1000\n  MIN_SIZE_TEST: 800\n  MAX_SIZE_TEST: 1000\nSOLVER:\n  IMS_PER_BATCH: 8  # base uses 16\n  WARMUP_FACTOR: 0.33333\n  WARMUP_ITERS: 100\n  STEPS: (11000, 11600)\n  MAX_ITER: 12000\nTEST:\n  EXPECTED_RESULTS: [[\"bbox\", \"AP\", 41.88, 0.7], [\"segm\", \"AP\", 33.79, 0.5]]\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/mask_rcnn_R_50_DC5_inference_acc_test.yaml",
    "content": "_BASE_: \"../COCO-InstanceSegmentation/mask_rcnn_R_50_DC5_3x.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://COCO-InstanceSegmentation/mask_rcnn_R_50_DC5_3x/137849551/model_final_84107b.pkl\"\nDATASETS:\n  TEST: (\"coco_2017_val_100\",)\nTEST:\n  EXPECTED_RESULTS: [[\"bbox\", \"AP\", 47.44, 0.02], [\"segm\", \"AP\", 42.94, 0.02]]\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/mask_rcnn_R_50_FPN_inference_acc_test.yaml",
    "content": "_BASE_: \"../COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_3x.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_3x/137849600/model_final_f10217.pkl\"\nDATASETS:\n  TEST: (\"coco_2017_val_100\",)\nTEST:\n  EXPECTED_RESULTS: [[\"bbox\", \"AP\", 47.34, 0.02], [\"segm\", \"AP\",  42.67, 0.02], [\"bbox_TTA\", \"AP\", 49.11, 0.02], [\"segm_TTA\", \"AP\", 45.04, 0.02]]\n  AUG:\n    ENABLED: True\n    MIN_SIZES: (700, 800)  # to save some time\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/mask_rcnn_R_50_FPN_instant_test.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\nDATASETS:\n  TRAIN: (\"coco_2017_val_100\",)\n  TEST: (\"coco_2017_val_100\",)\nSOLVER:\n  BASE_LR: 0.005\n  STEPS: (30,)\n  MAX_ITER: 40\n  IMS_PER_BATCH: 4\nDATALOADER:\n  NUM_WORKERS: 2\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/mask_rcnn_R_50_FPN_pred_boxes_training_acc_test.yaml",
    "content": "_BASE_: \"./mask_rcnn_R_50_FPN_training_acc_test.yaml\"\nMODEL:\n  ROI_BOX_HEAD:\n    TRAIN_ON_PRED_BOXES: True\nTEST:\n  EXPECTED_RESULTS: [[\"bbox\", \"AP\", 42.6, 1.0], [\"segm\", \"AP\", 35.8, 0.8]]\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/mask_rcnn_R_50_FPN_training_acc_test.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  ROI_HEADS:\n    BATCH_SIZE_PER_IMAGE: 256\n  MASK_ON: True\nDATASETS:\n  TRAIN: (\"coco_2017_val\",)\n  TEST: (\"coco_2017_val\",)\nINPUT:\n  MIN_SIZE_TRAIN: (600,)\n  MAX_SIZE_TRAIN: 1000\n  MIN_SIZE_TEST: 800\n  MAX_SIZE_TEST: 1000\nSOLVER:\n  WARMUP_FACTOR: 0.3333333\n  WARMUP_ITERS: 100\n  STEPS: (5500, 5800)\n  MAX_ITER: 6000\nTEST:\n  EXPECTED_RESULTS: [[\"bbox\", \"AP\", 42.5, 1.0], [\"segm\", \"AP\", 35.8, 0.8]]\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/panoptic_fpn_R_50_inference_acc_test.yaml",
    "content": "_BASE_: \"../COCO-PanopticSegmentation/panoptic_fpn_R_50_3x.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://COCO-PanopticSegmentation/panoptic_fpn_R_50_3x/139514569/model_final_c10459.pkl\"\nDATASETS:\n  TEST: (\"coco_2017_val_100_panoptic_separated\",)\nTEST:\n  EXPECTED_RESULTS: [[\"bbox\", \"AP\", 46.47, 0.02], [\"segm\", \"AP\", 43.39, 0.02], [\"sem_seg\", \"mIoU\", 42.55, 0.02], [\"panoptic_seg\", \"PQ\", 38.99, 0.02]]\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/panoptic_fpn_R_50_instant_test.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  META_ARCHITECTURE: \"PanopticFPN\"\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 50\n  SEM_SEG_HEAD:\n    LOSS_WEIGHT: 0.5\nDATASETS:\n  TRAIN: (\"coco_2017_val_100_panoptic_separated\",)\n  TEST: (\"coco_2017_val_100_panoptic_separated\",)\nSOLVER:\n  BASE_LR: 0.005\n  STEPS: (30,)\n  MAX_ITER: 40\n  IMS_PER_BATCH: 4\nDATALOADER:\n  NUM_WORKERS: 1\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/panoptic_fpn_R_50_training_acc_test.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  META_ARCHITECTURE: \"PanopticFPN\"\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 50\n  SEM_SEG_HEAD:\n    LOSS_WEIGHT: 0.5\nDATASETS:\n  TRAIN: (\"coco_2017_val_panoptic_separated\",)\n  TEST: (\"coco_2017_val_panoptic_separated\",)\nSOLVER:\n  BASE_LR: 0.01\n  WARMUP_FACTOR: 0.001\n  WARMUP_ITERS: 500\n  STEPS: (5500,)\n  MAX_ITER: 7000\nTEST:\n  EXPECTED_RESULTS: [[\"bbox\", \"AP\", 46.70, 1.1], [\"segm\", \"AP\", 39.0, 0.7], [\"sem_seg\", \"mIoU\", 64.73, 1.3], [\"panoptic_seg\", \"PQ\", 48.13, 0.8]]\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/retinanet_R_50_FPN_inference_acc_test.yaml",
    "content": "_BASE_: \"../COCO-Detection/retinanet_R_50_FPN_3x.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://COCO-Detection/retinanet_R_50_FPN_3x/190397829/model_final_5bd44e.pkl\"\nDATASETS:\n  TEST: (\"coco_2017_val_100\",)\nTEST:\n  EXPECTED_RESULTS: [[\"bbox\", \"AP\", 44.45, 0.02]]\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/retinanet_R_50_FPN_instant_test.yaml",
    "content": "_BASE_: \"../COCO-Detection/retinanet_R_50_FPN_1x.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\nDATASETS:\n  TRAIN: (\"coco_2017_val_100\",)\n  TEST: (\"coco_2017_val_100\",)\nSOLVER:\n  BASE_LR: 0.005\n  STEPS: (30,)\n  MAX_ITER: 40\n  IMS_PER_BATCH: 4\nDATALOADER:\n  NUM_WORKERS: 2\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/rpn_R_50_FPN_inference_acc_test.yaml",
    "content": "_BASE_: \"../COCO-Detection/rpn_R_50_FPN_1x.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://COCO-Detection/rpn_R_50_FPN_1x/137258492/model_final_02ce48.pkl\"\nDATASETS:\n  TEST: (\"coco_2017_val_100\",)\nTEST:\n  EXPECTED_RESULTS: [[\"box_proposals\", \"AR@1000\", 58.16, 0.02]]\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/rpn_R_50_FPN_instant_test.yaml",
    "content": "_BASE_: \"../COCO-Detection/rpn_R_50_FPN_1x.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\nDATASETS:\n  TRAIN: (\"coco_2017_val_100\",)\n  TEST: (\"coco_2017_val_100\",)\nSOLVER:\n  STEPS: (30,)\n  MAX_ITER: 40\n  BASE_LR: 0.005\n  IMS_PER_BATCH: 4\nDATALOADER:\n  NUM_WORKERS: 2\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/semantic_R_50_FPN_inference_acc_test.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  META_ARCHITECTURE: \"SemanticSegmentor\"\n  WEIGHTS: \"detectron2://semantic_R_50_FPN_1x/111802073/model_final_c18079783c55a94968edc28b7101c5f0.pkl\"\n  RESNETS:\n    DEPTH: 50\nDATASETS:\n  TEST: (\"coco_2017_val_100_panoptic_stuffonly\",)\nTEST:\n  EXPECTED_RESULTS: [[\"sem_seg\", \"mIoU\", 39.53, 0.02], [\"sem_seg\", \"mACC\", 51.50, 0.02]]\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/semantic_R_50_FPN_instant_test.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  META_ARCHITECTURE: \"SemanticSegmentor\"\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\nDATASETS:\n  TRAIN: (\"coco_2017_val_100_panoptic_stuffonly\",)\n  TEST: (\"coco_2017_val_100_panoptic_stuffonly\",)\nINPUT:\n  MIN_SIZE_TRAIN: (640, 672, 704, 736, 768, 800)\nSOLVER:\n  BASE_LR: 0.005\n  STEPS: (30,)\n  MAX_ITER: 40\n  IMS_PER_BATCH: 4\nDATALOADER:\n  NUM_WORKERS: 2\n"
  },
  {
    "path": "VPS_Module/configs/quick_schedules/semantic_R_50_FPN_training_acc_test.yaml",
    "content": "_BASE_: \"../Base-RCNN-FPN.yaml\"\nMODEL:\n  META_ARCHITECTURE: \"SemanticSegmentor\"\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\nDATASETS:\n  TRAIN: (\"coco_2017_val_panoptic_stuffonly\",)\n  TEST: (\"coco_2017_val_panoptic_stuffonly\",)\nSOLVER:\n  BASE_LR: 0.01\n  WARMUP_FACTOR: 0.001\n  WARMUP_ITERS: 300\n  STEPS: (5500,)\n  MAX_ITER: 7000\nTEST:\n  EXPECTED_RESULTS: [[\"sem_seg\", \"mIoU\", 76.51, 1.0], [\"sem_seg\", \"mACC\", 83.25, 1.0]]\nINPUT:\n  # no scale augmentation\n  MIN_SIZE_TRAIN: (800, )\n"
  },
  {
    "path": "VPS_Module/demo/README.md",
    "content": "<img src=\".github/Detectron2-Logo-Horz.svg\" width=\"300\" >\n\nDetectron2 is Facebook AI Research's next generation library\nthat provides state-of-the-art detection and segmentation algorithms.\nIt is the successor of\n[Detectron](https://github.com/facebookresearch/Detectron/)\nand [maskrcnn-benchmark](https://github.com/facebookresearch/maskrcnn-benchmark/).\nIt supports a number of computer vision research projects and production applications in Facebook.\n\n<div align=\"center\">\n  <img src=\"https://user-images.githubusercontent.com/1381301/66535560-d3422200-eace-11e9-9123-5535d469db19.png\"/>\n</div>\n\n### What's New\n* Includes new capabilities such as panoptic segmentation, Densepose, Cascade R-CNN, rotated bounding boxes, PointRend,\n  DeepLab, etc.\n* Used as a library to support building [research projects](projects/) on top of it.\n* Models can be exported to TorchScript format or Caffe2 format for deployment.\n* It [trains much faster](https://detectron2.readthedocs.io/notes/benchmarks.html).\n\nSee our [blog post](https://ai.facebook.com/blog/-detectron2-a-pytorch-based-modular-object-detection-library-/)\nto see more demos and learn about detectron2.\n\n## Installation\n\nSee [installation instructions](https://detectron2.readthedocs.io/tutorials/install.html).\n\n## Getting Started\n\nSee [Getting Started with Detectron2](https://detectron2.readthedocs.io/tutorials/getting_started.html),\nand the [Colab Notebook](https://colab.research.google.com/drive/16jcaJoc6bCFAQ96jDe2HwtXj7BMD_-m5)\nto learn about basic usage.\n\nLearn more at our [documentation](https://detectron2.readthedocs.org).\nAnd see [projects/](projects/) for some projects that are built on top of detectron2.\n\n## Model Zoo and Baselines\n\nWe provide a large set of baseline results and trained models available for download in the [Detectron2 Model Zoo](MODEL_ZOO.md).\n\n## License\n\nDetectron2 is released under the [Apache 2.0 license](LICENSE).\n\n## Citing Detectron2\n\nIf you use Detectron2 in your research or wish to refer to the baseline results published in the [Model Zoo](MODEL_ZOO.md), please use the following BibTeX entry.\n\n```BibTeX\n@misc{wu2019detectron2,\n  author =       {Yuxin Wu and Alexander Kirillov and Francisco Massa and\n                  Wan-Yen Lo and Ross Girshick},\n  title =        {Detectron2},\n  howpublished = {\\url{https://github.com/facebookresearch/detectron2}},\n  year =         {2019}\n}\n```\n\n## Detectron2 Demo\n\nWe provide a command line tool to run a simple demo of builtin configs.\nThe usage is explained in [GETTING_STARTED.md](../GETTING_STARTED.md).\n\nSee our [blog post](https://ai.facebook.com/blog/-detectron2-a-pytorch-based-modular-object-detection-library-)\nfor a high-quality demo generated with this tool.\n"
  },
  {
    "path": "VPS_Module/demo/demo.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport argparse\nimport glob\nimport multiprocessing as mp\nimport numpy as np\nimport os\nimport tempfile\nimport time\nimport warnings\nimport cv2\nimport tqdm\n\nfrom detectron2.config import get_cfg\nfrom detectron2.data.detection_utils import read_image\nfrom detectron2.utils.logger import setup_logger\n\nfrom predictor import VisualizationDemo\n\n# constants\nWINDOW_NAME = \"COCO detections\"\n\n\ndef setup_cfg(args):\n    # load config from file and command-line arguments\n    cfg = get_cfg()\n    # To use demo for Panoptic-DeepLab, please uncomment the following two lines.\n    # from detectron2.projects.panoptic_deeplab import add_panoptic_deeplab_config  # noqa\n    # add_panoptic_deeplab_config(cfg)\n    cfg.merge_from_file(args.config_file)\n    cfg.merge_from_list(args.opts)\n    # Set score_threshold for builtin models\n    cfg.MODEL.RETINANET.SCORE_THRESH_TEST = args.confidence_threshold\n    cfg.MODEL.ROI_HEADS.SCORE_THRESH_TEST = args.confidence_threshold\n    cfg.MODEL.PANOPTIC_FPN.COMBINE.INSTANCES_CONFIDENCE_THRESH = args.confidence_threshold\n    cfg.freeze()\n    return cfg\n\n\ndef get_parser():\n    parser = argparse.ArgumentParser(description=\"Detectron2 demo for builtin configs\")\n    parser.add_argument(\n        \"--config-file\",\n        default=\"configs/quick_schedules/mask_rcnn_R_50_FPN_inference_acc_test.yaml\",\n        metavar=\"FILE\",\n        help=\"path to config file\",\n    )\n    parser.add_argument(\"--webcam\", action=\"store_true\", help=\"Take inputs from webcam.\")\n    parser.add_argument(\"--video-input\", help=\"Path to video file.\")\n    parser.add_argument(\n        \"--input\",\n        nargs=\"+\",\n        help=\"A list of space separated input images; \"\n        \"or a single glob pattern such as 'directory/*.jpg'\",\n    )\n    parser.add_argument(\n        \"--output\",\n        help=\"A file or directory to save output visualizations. \"\n        \"If not given, will show output in an OpenCV window.\",\n    )\n\n    parser.add_argument(\n        \"--confidence-threshold\",\n        type=float,\n        default=0.5,\n        help=\"Minimum score for instance predictions to be shown\",\n    )\n    parser.add_argument(\n        \"--opts\",\n        help=\"Modify config options using the command-line 'KEY VALUE' pairs\",\n        default=[],\n        nargs=argparse.REMAINDER,\n    )\n    return parser\n\n\ndef test_opencv_video_format(codec, file_ext):\n    with tempfile.TemporaryDirectory(prefix=\"video_format_test\") as dir:\n        filename = os.path.join(dir, \"test_file\" + file_ext)\n        writer = cv2.VideoWriter(\n            filename=filename,\n            fourcc=cv2.VideoWriter_fourcc(*codec),\n            fps=float(30),\n            frameSize=(10, 10),\n            isColor=True,\n        )\n        [writer.write(np.zeros((10, 10, 3), np.uint8)) for _ in range(30)]\n        writer.release()\n        if os.path.isfile(filename):\n            return True\n        return False\n\n\nif __name__ == \"__main__\":\n    mp.set_start_method(\"spawn\", force=True)\n    args = get_parser().parse_args()\n    setup_logger(name=\"fvcore\")\n    logger = setup_logger()\n    logger.info(\"Arguments: \" + str(args))\n\n    cfg = setup_cfg(args)\n\n    demo = VisualizationDemo(cfg)\n\n    if args.input:\n        if len(args.input) == 1:\n            args.input = glob.glob(os.path.expanduser(args.input[0]))\n            assert args.input, \"The input path(s) was not found\"\n        for path in tqdm.tqdm(args.input, disable=not args.output):\n            # use PIL, to be consistent with evaluation\n            img = read_image(path, format=\"BGR\")\n            start_time = time.time()\n            predictions, visualized_output = demo.run_on_image(img)\n            logger.info(\n                \"{}: {} in {:.2f}s\".format(\n                    path,\n                    \"detected {} instances\".format(len(predictions[\"instances\"]))\n                    if \"instances\" in predictions\n                    else \"finished\",\n                    time.time() - start_time,\n                )\n            )\n\n            if args.output:\n                if os.path.isdir(args.output):\n                    assert os.path.isdir(args.output), args.output\n                    out_filename = os.path.join(args.output, os.path.basename(path))\n                else:\n                    assert len(args.input) == 1, \"Please specify a directory with args.output\"\n                    out_filename = args.output\n                visualized_output.save(out_filename)\n            else:\n                cv2.namedWindow(WINDOW_NAME, cv2.WINDOW_NORMAL)\n                cv2.imshow(WINDOW_NAME, visualized_output.get_image()[:, :, ::-1])\n                if cv2.waitKey(0) == 27:\n                    break  # esc to quit\n    elif args.webcam:\n        assert args.input is None, \"Cannot have both --input and --webcam!\"\n        assert args.output is None, \"output not yet supported with --webcam!\"\n        cam = cv2.VideoCapture(0)\n        for vis in tqdm.tqdm(demo.run_on_video(cam)):\n            cv2.namedWindow(WINDOW_NAME, cv2.WINDOW_NORMAL)\n            cv2.imshow(WINDOW_NAME, vis)\n            if cv2.waitKey(1) == 27:\n                break  # esc to quit\n        cam.release()\n        cv2.destroyAllWindows()\n    elif args.video_input:\n        video = cv2.VideoCapture(args.video_input)\n        width = int(video.get(cv2.CAP_PROP_FRAME_WIDTH))\n        height = int(video.get(cv2.CAP_PROP_FRAME_HEIGHT))\n        frames_per_second = video.get(cv2.CAP_PROP_FPS)\n        num_frames = int(video.get(cv2.CAP_PROP_FRAME_COUNT))\n        basename = os.path.basename(args.video_input)\n        codec, file_ext = (\n            (\"x264\", \".mkv\") if test_opencv_video_format(\"x264\", \".mkv\") else (\"mp4v\", \".mp4\")\n        )\n        if codec == \".mp4v\":\n            warnings.warn(\"x264 codec not available, switching to mp4v\")\n        if args.output:\n            if os.path.isdir(args.output):\n                output_fname = os.path.join(args.output, basename)\n                output_fname = os.path.splitext(output_fname)[0] + file_ext\n            else:\n                output_fname = args.output\n            assert not os.path.isfile(output_fname), output_fname\n            output_file = cv2.VideoWriter(\n                filename=output_fname,\n                # some installation of opencv may not support x264 (due to its license),\n                # you can try other format (e.g. MPEG)\n                fourcc=cv2.VideoWriter_fourcc(*codec),\n                fps=float(frames_per_second),\n                frameSize=(width, height),\n                isColor=True,\n            )\n        assert os.path.isfile(args.video_input)\n        for vis_frame in tqdm.tqdm(demo.run_on_video(video), total=num_frames):\n            if args.output:\n                output_file.write(vis_frame)\n            else:\n                cv2.namedWindow(basename, cv2.WINDOW_NORMAL)\n                cv2.imshow(basename, vis_frame)\n                if cv2.waitKey(1) == 27:\n                    break  # esc to quit\n        video.release()\n        if args.output:\n            output_file.release()\n        else:\n            cv2.destroyAllWindows()\n"
  },
  {
    "path": "VPS_Module/demo/predictor.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport atexit\nimport bisect\nimport multiprocessing as mp\nfrom collections import deque\nimport cv2\nimport torch\n\nfrom detectron2.data import MetadataCatalog\nfrom detectron2.engine.defaults import DefaultPredictor\nfrom detectron2.utils.video_visualizer import VideoVisualizer\nfrom detectron2.utils.visualizer import ColorMode, Visualizer\n\n\nclass VisualizationDemo(object):\n    def __init__(self, cfg, instance_mode=ColorMode.IMAGE, parallel=False):\n        \"\"\"\n        Args:\n            cfg (CfgNode):\n            instance_mode (ColorMode):\n            parallel (bool): whether to run the model in different processes from visualization.\n                Useful since the visualization logic can be slow.\n        \"\"\"\n        self.metadata = MetadataCatalog.get(\n            cfg.DATASETS.TEST[0] if len(cfg.DATASETS.TEST) else \"__unused\"\n        )\n        self.cpu_device = torch.device(\"cpu\")\n        self.instance_mode = instance_mode\n\n        self.parallel = parallel\n        if parallel:\n            num_gpu = torch.cuda.device_count()\n            self.predictor = AsyncPredictor(cfg, num_gpus=num_gpu)\n        else:\n            self.predictor = DefaultPredictor(cfg)\n\n    def run_on_image(self, image):\n        \"\"\"\n        Args:\n            image (np.ndarray): an image of shape (H, W, C) (in BGR order).\n                This is the format used by OpenCV.\n\n        Returns:\n            predictions (dict): the output of the model.\n            vis_output (VisImage): the visualized image output.\n        \"\"\"\n        vis_output = None\n        predictions = self.predictor(image)\n        # Convert image from OpenCV BGR format to Matplotlib RGB format.\n        image = image[:, :, ::-1]\n        visualizer = Visualizer(image, self.metadata, instance_mode=self.instance_mode)\n        if \"panoptic_seg\" in predictions:\n            panoptic_seg, segments_info = predictions[\"panoptic_seg\"]\n            vis_output = visualizer.draw_panoptic_seg_predictions(\n                panoptic_seg.to(self.cpu_device), segments_info\n            )\n        else:\n            if \"sem_seg\" in predictions:\n                vis_output = visualizer.draw_sem_seg(\n                    predictions[\"sem_seg\"].argmax(dim=0).to(self.cpu_device)\n                )\n            if \"instances\" in predictions:\n                instances = predictions[\"instances\"].to(self.cpu_device)\n                vis_output = visualizer.draw_instance_predictions(predictions=instances)\n\n        return predictions, vis_output\n\n    def _frame_from_video(self, video):\n        while video.isOpened():\n            success, frame = video.read()\n            if success:\n                yield frame\n            else:\n                break\n\n    def run_on_video(self, video):\n        \"\"\"\n        Visualizes predictions on frames of the input video.\n\n        Args:\n            video (cv2.VideoCapture): a :class:`VideoCapture` object, whose source can be\n                either a webcam or a video file.\n\n        Yields:\n            ndarray: BGR visualizations of each video frame.\n        \"\"\"\n        video_visualizer = VideoVisualizer(self.metadata, self.instance_mode)\n\n        def process_predictions(frame, predictions):\n            frame = cv2.cvtColor(frame, cv2.COLOR_BGR2RGB)\n            if \"panoptic_seg\" in predictions:\n                panoptic_seg, segments_info = predictions[\"panoptic_seg\"]\n                vis_frame = video_visualizer.draw_panoptic_seg_predictions(\n                    frame, panoptic_seg.to(self.cpu_device), segments_info\n                )\n            elif \"instances\" in predictions:\n                predictions = predictions[\"instances\"].to(self.cpu_device)\n                vis_frame = video_visualizer.draw_instance_predictions(frame, predictions)\n            elif \"sem_seg\" in predictions:\n                vis_frame = video_visualizer.draw_sem_seg(\n                    frame, predictions[\"sem_seg\"].argmax(dim=0).to(self.cpu_device)\n                )\n\n            # Converts Matplotlib RGB format to OpenCV BGR format\n            vis_frame = cv2.cvtColor(vis_frame.get_image(), cv2.COLOR_RGB2BGR)\n            return vis_frame\n\n        frame_gen = self._frame_from_video(video)\n        if self.parallel:\n            buffer_size = self.predictor.default_buffer_size\n\n            frame_data = deque()\n\n            for cnt, frame in enumerate(frame_gen):\n                frame_data.append(frame)\n                self.predictor.put(frame)\n\n                if cnt >= buffer_size:\n                    frame = frame_data.popleft()\n                    predictions = self.predictor.get()\n                    yield process_predictions(frame, predictions)\n\n            while len(frame_data):\n                frame = frame_data.popleft()\n                predictions = self.predictor.get()\n                yield process_predictions(frame, predictions)\n        else:\n            for frame in frame_gen:\n                yield process_predictions(frame, self.predictor(frame))\n\n\nclass AsyncPredictor:\n    \"\"\"\n    A predictor that runs the model asynchronously, possibly on >1 GPUs.\n    Because rendering the visualization takes considerably amount of time,\n    this helps improve throughput a little bit when rendering videos.\n    \"\"\"\n\n    class _StopToken:\n        pass\n\n    class _PredictWorker(mp.Process):\n        def __init__(self, cfg, task_queue, result_queue):\n            self.cfg = cfg\n            self.task_queue = task_queue\n            self.result_queue = result_queue\n            super().__init__()\n\n        def run(self):\n            predictor = DefaultPredictor(self.cfg)\n\n            while True:\n                task = self.task_queue.get()\n                if isinstance(task, AsyncPredictor._StopToken):\n                    break\n                idx, data = task\n                result = predictor(data)\n                self.result_queue.put((idx, result))\n\n    def __init__(self, cfg, num_gpus: int = 1):\n        \"\"\"\n        Args:\n            cfg (CfgNode):\n            num_gpus (int): if 0, will run on CPU\n        \"\"\"\n        num_workers = max(num_gpus, 1)\n        self.task_queue = mp.Queue(maxsize=num_workers * 3)\n        self.result_queue = mp.Queue(maxsize=num_workers * 3)\n        self.procs = []\n        for gpuid in range(max(num_gpus, 1)):\n            cfg = cfg.clone()\n            cfg.defrost()\n            cfg.MODEL.DEVICE = \"cuda:{}\".format(gpuid) if num_gpus > 0 else \"cpu\"\n            self.procs.append(\n                AsyncPredictor._PredictWorker(cfg, self.task_queue, self.result_queue)\n            )\n\n        self.put_idx = 0\n        self.get_idx = 0\n        self.result_rank = []\n        self.result_data = []\n\n        for p in self.procs:\n            p.start()\n        atexit.register(self.shutdown)\n\n    def put(self, image):\n        self.put_idx += 1\n        self.task_queue.put((self.put_idx, image))\n\n    def get(self):\n        self.get_idx += 1  # the index needed for this request\n        if len(self.result_rank) and self.result_rank[0] == self.get_idx:\n            res = self.result_data[0]\n            del self.result_data[0], self.result_rank[0]\n            return res\n\n        while True:\n            # make sure the results are returned in the correct order\n            idx, res = self.result_queue.get()\n            if idx == self.get_idx:\n                return res\n            insert = bisect.bisect(self.result_rank, idx)\n            self.result_rank.insert(insert, idx)\n            self.result_data.insert(insert, res)\n\n    def __len__(self):\n        return self.put_idx - self.get_idx\n\n    def __call__(self, image):\n        self.put(image)\n        return self.get()\n\n    def shutdown(self):\n        for _ in self.procs:\n            self.task_queue.put(AsyncPredictor._StopToken())\n\n    @property\n    def default_buffer_size(self):\n        return len(self.procs) * 5\n"
  },
  {
    "path": "VPS_Module/detectron2/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom .utils.env import setup_environment\n\nsetup_environment()\n\n\n# This line will be programatically read/write by setup.py.\n# Leave them at the bottom of this file and don't touch them.\n__version__ = \"0.6\"\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/__init__.py",
    "content": "from .engines import build_engine\nfrom .models import build_vos_model\nfrom .aot_config import AOTConfig\n\n\n__all__ = [\"build_vos_model\", \"build_engine\", \"AOTConfig\"]\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/aot_config.py",
    "content": "import os\nimport importlib\n\n\nclass AOTConfig():\n    def __init__(self, exp_name='default', model='AOTT'):\n\n        self.STAGE_NAME = 'default'\n        self.MODEL_VOS = 'aot'\n        self.MODEL_ENGINE = 'aotengine'\n        self.MODEL_ALIGN_CORNERS = True\n        self.MODEL_ENCODER = 'resnet50'\n        self.MODEL_ENCODER_PRETRAIN = './pretrain_models/resnet50-0676ba61.pth'  # https://download.pytorch.org/models/resnet50-0676ba61.pth\n        \n        self.MODEL_DECODER_INTERMEDIATE_LSTT = True\n        self.MODEL_FREEZE_BN = True\n        self.MODEL_FREEZE_BACKBONE = True\n        self.MODEL_SELF_HEADS = 8\n        self.MODEL_ATT_HEADS = 8\n        self.MODEL_EPSILON = 1e-5\n        self.MODEL_USE_PREV_PROB = False\n\n        self.MODEL_NAME = 'R50_AOTL'\n        # self.EXP_NAME = exp_name + '_' + self.MODEL_NAME\n\n        self.MODEL_MAX_OBJ_NUM = 10\n\n        self.MODEL_ENCODER_EMBEDDING_DIM = 256\n        self.MODEL_ENCODER_DIM = [256, 512, 1024, 1024]  # 4x, 8x, 16x, 16x\n        self.MODEL_LSTT_NUM = 3\n\n        self.TRAIN_LONG_TERM_MEM_GAP = 2\n        self.TEST_LONG_TERM_MEM_GAP = 5\n\n        # self.DATASETS = ['youtubevos']\n        # self.DATA_WORKERS = 8\n        # self.DATA_RANDOMCROP = (465,\n        #                         465) if self.MODEL_ALIGN_CORNERS else (464,\n        #                                                                464)\n        # self.DATA_RANDOMFLIP = 0.5\n        # self.DATA_MAX_CROP_STEPS = 10\n        # self.DATA_SHORT_EDGE_LEN = 480\n        # self.DATA_MIN_SCALE_FACTOR = 0.7\n        # self.DATA_MAX_SCALE_FACTOR = 1.3\n        # self.DATA_RANDOM_REVERSE_SEQ = True\n        # self.DATA_SEQ_LEN = 5\n        # self.DATA_DAVIS_REPEAT = 5\n        # self.DATA_RANDOM_GAP_DAVIS = 12  # max frame interval between two sampled frames for DAVIS (24fps)\n        # self.DATA_RANDOM_GAP_YTB = 3  # max frame interval between two sampled frames for YouTube-VOS (6fps)\n        # self.DATA_DYNAMIC_MERGE_PROB = 0.3\n\n        self.TRAIN_TOTAL_STEPS = 100000\n        self.TRAIN_START_STEP = 0\n        self.TRAIN_WEIGHT_DECAY = 0.07\n        self.TRAIN_WEIGHT_DECAY_EXCLUSIVE = {\n            # 'encoder.': 0.01\n        }\n        self.TRAIN_WEIGHT_DECAY_EXEMPTION = [\n            'absolute_pos_embed', 'relative_position_bias_table',\n            'relative_emb_v', 'conv_out'\n        ]\n        self.TRAIN_LR = 2e-4\n        self.TRAIN_LR_MIN = 2e-5 if 'mobilenetv2' in self.MODEL_ENCODER else 1e-5\n        self.TRAIN_LR_POWER = 0.9\n        self.TRAIN_LR_ENCODER_RATIO = 0.1\n        self.TRAIN_LR_WARM_UP_RATIO = 0.05\n        self.TRAIN_LR_COSINE_DECAY = False\n        self.TRAIN_LR_RESTART = 1\n        self.TRAIN_LR_UPDATE_STEP = 1\n        self.TRAIN_AUX_LOSS_WEIGHT = 1.0\n        self.TRAIN_AUX_LOSS_RATIO = 1.0\n        self.TRAIN_OPT = 'adamw'\n        self.TRAIN_SGD_MOMENTUM = 0.9\n        self.TRAIN_GPUS = 4\n        self.TRAIN_BATCH_SIZE = 16\n        self.TRAIN_TBLOG = False\n        self.TRAIN_TBLOG_STEP = 50\n        self.TRAIN_LOG_STEP = 20\n        self.TRAIN_IMG_LOG = True\n        self.TRAIN_TOP_K_PERCENT_PIXELS = 0.15\n        self.TRAIN_SEQ_TRAINING_FREEZE_PARAMS = ['patch_wise_id_bank']\n        self.TRAIN_SEQ_TRAINING_START_RATIO = 0.5\n        self.TRAIN_HARD_MINING_RATIO = 0.5\n        self.TRAIN_EMA_RATIO = 0.1\n        self.TRAIN_CLIP_GRAD_NORM = 5.\n        self.TRAIN_SAVE_STEP = 1000\n        self.TRAIN_MAX_KEEP_CKPT = 8\n        self.TRAIN_RESUME = False\n        self.TRAIN_RESUME_CKPT = None\n        self.TRAIN_RESUME_STEP = 0\n        self.TRAIN_AUTO_RESUME = True\n        self.TRAIN_DATASET_FULL_RESOLUTION = False\n        self.TRAIN_ENABLE_PREV_FRAME = False\n        self.TRAIN_ENCODER_FREEZE_AT = 2\n        self.TRAIN_LSTT_EMB_DROPOUT = 0.\n        self.TRAIN_LSTT_ID_DROPOUT = 0.\n        self.TRAIN_LSTT_DROPPATH = 0.1\n        self.TRAIN_LSTT_DROPPATH_SCALING = False\n        self.TRAIN_LSTT_DROPPATH_LST = False\n        self.TRAIN_LSTT_LT_DROPOUT = 0.\n        self.TRAIN_LSTT_ST_DROPOUT = 0.\n\n        self.TEST_GPU_ID = 0\n        self.TEST_GPU_NUM = 1\n        self.TEST_FRAME_LOG = False\n        self.TEST_DATASET = 'youtubevos'\n        self.TEST_DATASET_FULL_RESOLUTION = False\n        self.TEST_DATASET_SPLIT = 'val'\n        self.TEST_CKPT_PATH = None\n        # if \"None\", evaluate the latest checkpoint.\n        self.TEST_CKPT_STEP = None\n        self.TEST_FLIP = False\n        self.TEST_MULTISCALE = [1]\n        self.TEST_MIN_SIZE = None\n        self.TEST_MAX_SIZE = 800 * 1.3\n        self.TEST_WORKERS = 4\n\n        # GPU distribution\n        # self.DIST_ENABLE = True\n        # self.DIST_BACKEND = \"nccl\"  # \"gloo\"\n        # self.DIST_URL = \"tcp://127.0.0.1:13241\"\n        # self.DIST_START_GPU = 0\n\n        self.PRETRAIN = True\n        self.PRETRAIN_FULL = True  # if False, load encoder only\n        self.PRETRAIN_MODEL = \"data/aot_r50_checkpoint/R50_AOTL_PRE_YTB_DAV.pth\"\n\n    '''\n    def init_dir(self):\n        self.DIR_DATA = './datasets'\n        self.DIR_DAVIS = os.path.join(self.DIR_DATA, 'DAVIS')\n        self.DIR_YTB = os.path.join(self.DIR_DATA, 'YTB')\n        self.DIR_STATIC = os.path.join(self.DIR_DATA, 'Static')\n\n        self.DIR_ROOT = './results'\n\n        self.DIR_RESULT = os.path.join(self.DIR_ROOT, 'result', self.EXP_NAME,\n                                       self.STAGE_NAME)\n        self.DIR_CKPT = os.path.join(self.DIR_RESULT, 'ckpt')\n        self.DIR_EMA_CKPT = os.path.join(self.DIR_RESULT, 'ema_ckpt')\n        self.DIR_LOG = os.path.join(self.DIR_RESULT, 'log')\n        self.DIR_TB_LOG = os.path.join(self.DIR_RESULT, 'log', 'tensorboard')\n        self.DIR_IMG_LOG = os.path.join(self.DIR_RESULT, 'log', 'img')\n        self.DIR_EVALUATION = os.path.join(self.DIR_RESULT, 'eval')\n\n        for path in [\n                self.DIR_RESULT, self.DIR_CKPT, self.DIR_EMA_CKPT,\n                self.DIR_LOG, self.DIR_EVALUATION, self.DIR_IMG_LOG,\n                self.DIR_TB_LOG\n        ]:\n            if not os.path.isdir(path):\n                try:\n                    os.makedirs(path)\n                except Exception as inst:\n                    print(inst)\n                    print('Failed to make dir: {}.'.format(path))\n    '''"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/decoders/__init__.py",
    "content": "from detectron2.aot_modules.decoders.fpn import FPNSegmentationHead\n\n\ndef build_decoder(name, **kwargs):\n\n    if name == 'fpn':\n        return FPNSegmentationHead(**kwargs)\n    else:\n        raise NotImplementedError\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/decoders/fpn.py",
    "content": "import torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom detectron2.aot_modules.layers.basic import ConvGN\n\n\nclass FPNSegmentationHead(nn.Module):\n    def __init__(self,\n                 in_dim,\n                 out_dim,\n                 decode_intermediate_input=True,\n                 hidden_dim=256,\n                 shortcut_dims=[24, 32, 96, 1280],\n                 align_corners=True):\n        super().__init__()\n        self.align_corners = align_corners\n\n        self.decode_intermediate_input = decode_intermediate_input\n\n        self.conv_in = ConvGN(in_dim, hidden_dim, 1)\n\n        self.conv_16x = ConvGN(hidden_dim, hidden_dim, 3)\n        self.conv_8x = ConvGN(hidden_dim, hidden_dim // 2, 3)\n        self.conv_4x = ConvGN(hidden_dim // 2, hidden_dim // 2, 3)\n\n        self.adapter_16x = nn.Conv2d(shortcut_dims[-2], hidden_dim, 1)\n        self.adapter_8x = nn.Conv2d(shortcut_dims[-3], hidden_dim, 1)\n        self.adapter_4x = nn.Conv2d(shortcut_dims[-4], hidden_dim // 2, 1)\n\n        self.conv_out = nn.Conv2d(hidden_dim // 2, out_dim, 1)\n\n        self._init_weight()\n\n    def forward(self, inputs, shortcuts):\n\n        if self.decode_intermediate_input:\n            x = torch.cat(inputs, dim=1)\n        else:\n            x = inputs[-1]\n\n        x = F.relu_(self.conv_in(x))\n        x = F.relu_(self.conv_16x(self.adapter_16x(shortcuts[-2]) + x))\n\n        x = F.interpolate(x,\n                          size=shortcuts[-3].size()[-2:],\n                          mode=\"bilinear\",\n                          align_corners=self.align_corners)\n        x = F.relu_(self.conv_8x(self.adapter_8x(shortcuts[-3]) + x))\n\n        x = F.interpolate(x,\n                          size=shortcuts[-4].size()[-2:],\n                          mode=\"bilinear\",\n                          align_corners=self.align_corners)\n        x = F.relu_(self.conv_4x(self.adapter_4x(shortcuts[-4]) + x))\n\n        x = self.conv_out(x)\n\n        return x\n\n    def _init_weight(self):\n        for p in self.parameters():\n            if p.dim() > 1:\n                nn.init.xavier_uniform_(p)\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/encoders/__init__.py",
    "content": "from detectron2.aot_modules.encoders.mobilenetv2 import MobileNetV2\nfrom detectron2.aot_modules.encoders.mobilenetv3 import MobileNetV3Large\nfrom detectron2.aot_modules.encoders.resnet import ResNet101, ResNet50\nfrom detectron2.aot_modules.encoders.resnest import resnest\nfrom detectron2.aot_modules.encoders.swin import build_swin_model\nfrom detectron2.aot_modules.layers.normalization import FrozenBatchNorm2d\nfrom torch import nn\n\n\ndef build_encoder(name, frozen_bn=True, freeze_at=-1):\n    if frozen_bn:\n        BatchNorm = FrozenBatchNorm2d\n    else:\n        BatchNorm = nn.BatchNorm2d\n\n    if name == 'mobilenetv2':\n        return MobileNetV2(16, BatchNorm, freeze_at=freeze_at)\n    elif name == 'mobilenetv3':\n        return MobileNetV3Large(16, BatchNorm, freeze_at=freeze_at)\n    elif name == 'resnet50':\n        return ResNet50(16, BatchNorm, freeze_at=freeze_at)\n    elif name == 'resnet101':\n        return ResNet101(16, BatchNorm, freeze_at=freeze_at)\n    elif name == 'resnest50':\n        return resnest.resnest50(norm_layer=BatchNorm,\n                                 dilation=2,\n                                 freeze_at=freeze_at)\n    elif name == 'resnest101':\n        return resnest.resnest101(norm_layer=BatchNorm,\n                                  dilation=2,\n                                  freeze_at=freeze_at)\n    elif 'swin' in name:\n        return build_swin_model(name, freeze_at=freeze_at)\n    else:\n        raise NotImplementedError\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/encoders/mobilenetv2.py",
    "content": "from torch import nn\nfrom torch import Tensor\nfrom typing import Callable, Optional, List\nfrom detectron2.aot_modules.utils.learning import freeze_params\n\n__all__ = ['MobileNetV2']\n\n\ndef _make_divisible(v: float,\n                    divisor: int,\n                    min_value: Optional[int] = None) -> int:\n    \"\"\"\n    This function is taken from the original tf repo.\n    It ensures that all layers have a channel number that is divisible by 8\n    It can be seen here:\n    https://github.com/tensorflow/models/blob/master/research/slim/nets/mobilenet/mobilenet.py\n    \"\"\"\n    if min_value is None:\n        min_value = divisor\n    new_v = max(min_value, int(v + divisor / 2) // divisor * divisor)\n    # Make sure that round down does not go down by more than 10%.\n    if new_v < 0.9 * v:\n        new_v += divisor\n    return new_v\n\n\nclass ConvBNActivation(nn.Sequential):\n    def __init__(\n        self,\n        in_planes: int,\n        out_planes: int,\n        kernel_size: int = 3,\n        stride: int = 1,\n        groups: int = 1,\n        padding: int = -1,\n        norm_layer: Optional[Callable[..., nn.Module]] = None,\n        activation_layer: Optional[Callable[..., nn.Module]] = None,\n        dilation: int = 1,\n    ) -> None:\n        if padding == -1:\n            padding = (kernel_size - 1) // 2 * dilation\n        if norm_layer is None:\n            norm_layer = nn.BatchNorm2d\n        if activation_layer is None:\n            activation_layer = nn.ReLU6\n        super().__init__(\n            nn.Conv2d(in_planes,\n                      out_planes,\n                      kernel_size,\n                      stride,\n                      padding,\n                      dilation=dilation,\n                      groups=groups,\n                      bias=False), norm_layer(out_planes),\n            activation_layer(inplace=True))\n        self.out_channels = out_planes\n\n\n# necessary for backwards compatibility\nConvBNReLU = ConvBNActivation\n\n\nclass InvertedResidual(nn.Module):\n    def __init__(\n            self,\n            inp: int,\n            oup: int,\n            stride: int,\n            dilation: int,\n            expand_ratio: int,\n            norm_layer: Optional[Callable[..., nn.Module]] = None) -> None:\n        super(InvertedResidual, self).__init__()\n        self.stride = stride\n        assert stride in [1, 2]\n\n        if norm_layer is None:\n            norm_layer = nn.BatchNorm2d\n\n        self.kernel_size = 3\n        self.dilation = dilation\n\n        hidden_dim = int(round(inp * expand_ratio))\n        self.use_res_connect = self.stride == 1 and inp == oup\n\n        layers: List[nn.Module] = []\n        if expand_ratio != 1:\n            # pw\n            layers.append(\n                ConvBNReLU(inp,\n                           hidden_dim,\n                           kernel_size=1,\n                           norm_layer=norm_layer))\n        layers.extend([\n            # dw\n            ConvBNReLU(hidden_dim,\n                       hidden_dim,\n                       stride=stride,\n                       dilation=dilation,\n                       groups=hidden_dim,\n                       norm_layer=norm_layer),\n            # pw-linear\n            nn.Conv2d(hidden_dim, oup, 1, 1, 0, bias=False),\n            norm_layer(oup),\n        ])\n        self.conv = nn.Sequential(*layers)\n        self.out_channels = oup\n        self._is_cn = stride > 1\n\n    def forward(self, x: Tensor) -> Tensor:\n        if self.use_res_connect:\n            return x + self.conv(x)\n        else:\n            return self.conv(x)\n\n\nclass MobileNetV2(nn.Module):\n    def __init__(self,\n                 output_stride=8,\n                 norm_layer: Optional[Callable[..., nn.Module]] = None,\n                 width_mult: float = 1.0,\n                 inverted_residual_setting: Optional[List[List[int]]] = None,\n                 round_nearest: int = 8,\n                 block: Optional[Callable[..., nn.Module]] = None,\n                 freeze_at=0) -> None:\n        \"\"\"\n        MobileNet V2 main class\n        Args:\n            num_classes (int): Number of classes\n            width_mult (float): Width multiplier - adjusts number of channels in each layer by this amount\n            inverted_residual_setting: Network structure\n            round_nearest (int): Round the number of channels in each layer to be a multiple of this number\n            Set to 1 to turn off rounding\n            block: Module specifying inverted residual building block for mobilenet\n            norm_layer: Module specifying the normalization layer to use\n        \"\"\"\n        super(MobileNetV2, self).__init__()\n\n        if block is None:\n            block = InvertedResidual\n\n        if norm_layer is None:\n            norm_layer = nn.BatchNorm2d\n\n        last_channel = 1280\n        input_channel = 32\n        current_stride = 1\n        rate = 1\n\n        if inverted_residual_setting is None:\n            inverted_residual_setting = [\n                # t, c, n, s\n                [1, 16, 1, 1],\n                [6, 24, 2, 2],\n                [6, 32, 3, 2],\n                [6, 64, 4, 2],\n                [6, 96, 3, 1],\n                [6, 160, 3, 2],\n                [6, 320, 1, 1],\n            ]\n\n        # only check the first element, assuming user knows t,c,n,s are required\n        if len(inverted_residual_setting) == 0 or len(\n                inverted_residual_setting[0]) != 4:\n            raise ValueError(\"inverted_residual_setting should be non-empty \"\n                             \"or a 4-element list, got {}\".format(\n                                 inverted_residual_setting))\n\n        # building first layer\n        input_channel = _make_divisible(input_channel * width_mult,\n                                        round_nearest)\n        self.last_channel = _make_divisible(\n            last_channel * max(1.0, width_mult), round_nearest)\n        features: List[nn.Module] = [\n            ConvBNReLU(3, input_channel, stride=2, norm_layer=norm_layer)\n        ]\n        current_stride *= 2\n        # building inverted residual blocks\n        for t, c, n, s in inverted_residual_setting:\n            if current_stride == output_stride:\n                stride = 1\n                dilation = rate\n                rate *= s\n            else:\n                stride = s\n                dilation = 1\n                current_stride *= s\n            output_channel = _make_divisible(c * width_mult, round_nearest)\n            for i in range(n):\n                if i == 0:\n                    features.append(\n                        block(input_channel, output_channel, stride, dilation,\n                              t, norm_layer))\n                else:\n                    features.append(\n                        block(input_channel, output_channel, 1, rate, t,\n                              norm_layer))\n                input_channel = output_channel\n\n        # building last several layers\n        features.append(\n            ConvBNReLU(input_channel,\n                       self.last_channel,\n                       kernel_size=1,\n                       norm_layer=norm_layer))\n        # make it nn.Sequential\n        self.features = nn.Sequential(*features)\n\n        self._initialize_weights()\n\n        feature_4x = self.features[0:4]\n        feautre_8x = self.features[4:7]\n        feature_16x = self.features[7:14]\n        feature_32x = self.features[14:]\n\n        self.stages = [feature_4x, feautre_8x, feature_16x, feature_32x]\n\n        self.freeze(freeze_at)\n\n    def forward(self, x):\n        xs = []\n        for stage in self.stages:\n            x = stage(x)\n            xs.append(x)\n        return xs\n\n    def _initialize_weights(self):\n        # weight initialization\n        for m in self.modules():\n            if isinstance(m, nn.Conv2d):\n                nn.init.kaiming_normal_(m.weight, mode='fan_out')\n                if m.bias is not None:\n                    nn.init.zeros_(m.bias)\n            elif isinstance(m, (nn.BatchNorm2d, nn.GroupNorm)):\n                nn.init.ones_(m.weight)\n                nn.init.zeros_(m.bias)\n            elif isinstance(m, nn.Linear):\n                nn.init.normal_(m.weight, 0, 0.01)\n                nn.init.zeros_(m.bias)\n\n    def freeze(self, freeze_at):\n        if freeze_at >= 1:\n            for m in self.stages[0][0]:\n                freeze_params(m)\n\n        for idx, stage in enumerate(self.stages, start=2):\n            if freeze_at >= idx:\n                freeze_params(stage)\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/encoders/mobilenetv3.py",
    "content": "\"\"\"\nCreates a MobileNetV3 Model as defined in:\nAndrew Howard, Mark Sandler, Grace Chu, Liang-Chieh Chen, Bo Chen, Mingxing Tan, Weijun Wang, Yukun Zhu, Ruoming Pang, Vijay Vasudevan, Quoc V. Le, Hartwig Adam. (2019).\nSearching for MobileNetV3\narXiv preprint arXiv:1905.02244.\n\"\"\"\n\nimport torch.nn as nn\nimport math\nfrom detectron2.aot_modules.utils.learning import freeze_params\n\n\ndef _make_divisible(v, divisor, min_value=None):\n    \"\"\"\n    This function is taken from the original tf repo.\n    It ensures that all layers have a channel number that is divisible by 8\n    It can be seen here:\n    https://github.com/tensorflow/models/blob/master/research/slim/nets/mobilenet/mobilenet.py\n    :param v:\n    :param divisor:\n    :param min_value:\n    :return:\n    \"\"\"\n    if min_value is None:\n        min_value = divisor\n    new_v = max(min_value, int(v + divisor / 2) // divisor * divisor)\n    # Make sure that round down does not go down by more than 10%.\n    if new_v < 0.9 * v:\n        new_v += divisor\n    return new_v\n\n\nclass h_sigmoid(nn.Module):\n    def __init__(self, inplace=True):\n        super(h_sigmoid, self).__init__()\n        self.relu = nn.ReLU6(inplace=inplace)\n\n    def forward(self, x):\n        return self.relu(x + 3) / 6\n\n\nclass h_swish(nn.Module):\n    def __init__(self, inplace=True):\n        super(h_swish, self).__init__()\n        self.sigmoid = h_sigmoid(inplace=inplace)\n\n    def forward(self, x):\n        return x * self.sigmoid(x)\n\n\nclass SELayer(nn.Module):\n    def __init__(self, channel, reduction=4):\n        super(SELayer, self).__init__()\n        self.avg_pool = nn.AdaptiveAvgPool2d(1)\n        self.fc = nn.Sequential(\n            nn.Linear(channel, _make_divisible(channel // reduction, 8)),\n            nn.ReLU(inplace=True),\n            nn.Linear(_make_divisible(channel // reduction, 8), channel),\n            h_sigmoid())\n\n    def forward(self, x):\n        b, c, _, _ = x.size()\n        y = self.avg_pool(x).view(b, c)\n        y = self.fc(y).view(b, c, 1, 1)\n        return x * y\n\n\ndef conv_3x3_bn(inp, oup, stride, norm_layer=nn.BatchNorm2d):\n    return nn.Sequential(nn.Conv2d(inp, oup, 3, stride, 1, bias=False),\n                         norm_layer(oup), h_swish())\n\n\ndef conv_1x1_bn(inp, oup, norm_layer=nn.BatchNorm2d):\n    return nn.Sequential(nn.Conv2d(inp, oup, 1, 1, 0, bias=False),\n                         norm_layer(oup), h_swish())\n\n\nclass InvertedResidual(nn.Module):\n    def __init__(self,\n                 inp,\n                 hidden_dim,\n                 oup,\n                 kernel_size,\n                 stride,\n                 use_se,\n                 use_hs,\n                 dilation=1,\n                 norm_layer=nn.BatchNorm2d):\n        super(InvertedResidual, self).__init__()\n        assert stride in [1, 2]\n\n        self.identity = stride == 1 and inp == oup\n\n        if inp == hidden_dim:\n            self.conv = nn.Sequential(\n                # dw\n                nn.Conv2d(hidden_dim,\n                          hidden_dim,\n                          kernel_size,\n                          stride, (kernel_size - 1) // 2 * dilation,\n                          dilation=dilation,\n                          groups=hidden_dim,\n                          bias=False),\n                norm_layer(hidden_dim),\n                h_swish() if use_hs else nn.ReLU(inplace=True),\n                # Squeeze-and-Excite\n                SELayer(hidden_dim) if use_se else nn.Identity(),\n                # pw-linear\n                nn.Conv2d(hidden_dim, oup, 1, 1, 0, bias=False),\n                norm_layer(oup),\n            )\n        else:\n            self.conv = nn.Sequential(\n                # pw\n                nn.Conv2d(inp, hidden_dim, 1, 1, 0, bias=False),\n                norm_layer(hidden_dim),\n                h_swish() if use_hs else nn.ReLU(inplace=True),\n                # dw\n                nn.Conv2d(hidden_dim,\n                          hidden_dim,\n                          kernel_size,\n                          stride, (kernel_size - 1) // 2 * dilation,\n                          dilation=dilation,\n                          groups=hidden_dim,\n                          bias=False),\n                norm_layer(hidden_dim),\n                # Squeeze-and-Excite\n                SELayer(hidden_dim) if use_se else nn.Identity(),\n                h_swish() if use_hs else nn.ReLU(inplace=True),\n                # pw-linear\n                nn.Conv2d(hidden_dim, oup, 1, 1, 0, bias=False),\n                norm_layer(oup),\n            )\n\n    def forward(self, x):\n        if self.identity:\n            return x + self.conv(x)\n        else:\n            return self.conv(x)\n\n\nclass MobileNetV3Large(nn.Module):\n    def __init__(self,\n                 output_stride=16,\n                 norm_layer=nn.BatchNorm2d,\n                 width_mult=1.,\n                 freeze_at=0):\n        super(MobileNetV3Large, self).__init__()\n        \"\"\"\n        Constructs a MobileNetV3-Large model\n        \"\"\"\n        cfgs = [\n            # k, t, c, SE, HS, s\n            [3, 1, 16, 0, 0, 1],\n            [3, 4, 24, 0, 0, 2],\n            [3, 3, 24, 0, 0, 1],\n            [5, 3, 40, 1, 0, 2],\n            [5, 3, 40, 1, 0, 1],\n            [5, 3, 40, 1, 0, 1],\n            [3, 6, 80, 0, 1, 2],\n            [3, 2.5, 80, 0, 1, 1],\n            [3, 2.3, 80, 0, 1, 1],\n            [3, 2.3, 80, 0, 1, 1],\n            [3, 6, 112, 1, 1, 1],\n            [3, 6, 112, 1, 1, 1],\n            [5, 6, 160, 1, 1, 2],\n            [5, 6, 160, 1, 1, 1],\n            [5, 6, 160, 1, 1, 1]\n        ]\n        self.cfgs = cfgs\n\n        # building first layer\n        input_channel = _make_divisible(16 * width_mult, 8)\n        layers = [conv_3x3_bn(3, input_channel, 2, norm_layer)]\n        # building inverted residual blocks\n        block = InvertedResidual\n        now_stride = 2\n        rate = 1\n        for k, t, c, use_se, use_hs, s in self.cfgs:\n            if now_stride == output_stride:\n                dilation = rate\n                rate *= s\n                s = 1\n            else:\n                dilation = 1\n                now_stride *= s\n            output_channel = _make_divisible(c * width_mult, 8)\n            exp_size = _make_divisible(input_channel * t, 8)\n            layers.append(\n                block(input_channel, exp_size, output_channel, k, s, use_se,\n                      use_hs, dilation, norm_layer))\n            input_channel = output_channel\n\n        self.features = nn.Sequential(*layers)\n        self.conv = conv_1x1_bn(input_channel, exp_size, norm_layer)\n        # building last several layers\n\n        self._initialize_weights()\n\n        feature_4x = self.features[0:4]\n        feautre_8x = self.features[4:7]\n        feature_16x = self.features[7:13]\n        feature_32x = self.features[13:]\n\n        self.stages = [feature_4x, feautre_8x, feature_16x, feature_32x]\n\n        self.freeze(freeze_at)\n\n    def forward(self, x):\n        xs = []\n        for stage in self.stages:\n            x = stage(x)\n            xs.append(x)\n        xs[-1] = self.conv(xs[-1])\n        return xs\n\n    def _initialize_weights(self):\n        for m in self.modules():\n            if isinstance(m, nn.Conv2d):\n                n = m.kernel_size[0] * m.kernel_size[1] * m.out_channels\n                m.weight.data.normal_(0, math.sqrt(2. / n))\n                if m.bias is not None:\n                    m.bias.data.zero_()\n            elif isinstance(m, nn.BatchNorm2d):\n                m.weight.data.fill_(1)\n                m.bias.data.zero_()\n            elif isinstance(m, nn.Linear):\n                n = m.weight.size(1)\n                m.weight.data.normal_(0, 0.01)\n                m.bias.data.zero_()\n\n    def freeze(self, freeze_at):\n        if freeze_at >= 1:\n            for m in self.stages[0][0]:\n                freeze_params(m)\n\n        for idx, stage in enumerate(self.stages, start=2):\n            if freeze_at >= idx:\n                freeze_params(stage)\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/encoders/resnest/__init__.py",
    "content": "from .resnest import *\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/encoders/resnest/resnest.py",
    "content": "import torch\nfrom .resnet import ResNet, Bottleneck\n\n__all__ = ['resnest50', 'resnest101', 'resnest200', 'resnest269']\n\n_url_format = 'https://s3.us-west-1.wasabisys.com/resnest/torch/{}-{}.pth'\n\n_model_sha256 = {\n    name: checksum\n    for checksum, name in [\n        ('528c19ca', 'resnest50'),\n        ('22405ba7', 'resnest101'),\n        ('75117900', 'resnest200'),\n        ('0cc87c48', 'resnest269'),\n    ]\n}\n\n\ndef short_hash(name):\n    if name not in _model_sha256:\n        raise ValueError(\n            'Pretrained model for {name} is not available.'.format(name=name))\n    return _model_sha256[name][:8]\n\n\nresnest_model_urls = {\n    name: _url_format.format(name, short_hash(name))\n    for name in _model_sha256.keys()\n}\n\n\ndef resnest50(pretrained=False, root='~/.encoding/models', **kwargs):\n    model = ResNet(Bottleneck, [3, 4, 6, 3],\n                   radix=2,\n                   groups=1,\n                   bottleneck_width=64,\n                   deep_stem=True,\n                   stem_width=32,\n                   avg_down=True,\n                   avd=True,\n                   avd_first=False,\n                   **kwargs)\n    if pretrained:\n        model.load_state_dict(\n            torch.hub.load_state_dict_from_url(resnest_model_urls['resnest50'],\n                                               progress=True,\n                                               check_hash=True))\n    return model\n\n\ndef resnest101(pretrained=False, root='~/.encoding/models', **kwargs):\n    model = ResNet(Bottleneck, [3, 4, 23, 3],\n                   radix=2,\n                   groups=1,\n                   bottleneck_width=64,\n                   deep_stem=True,\n                   stem_width=64,\n                   avg_down=True,\n                   avd=True,\n                   avd_first=False,\n                   **kwargs)\n    if pretrained:\n        model.load_state_dict(\n            torch.hub.load_state_dict_from_url(\n                resnest_model_urls['resnest101'],\n                progress=True,\n                check_hash=True))\n    return model\n\n\ndef resnest200(pretrained=False, root='~/.encoding/models', **kwargs):\n    model = ResNet(Bottleneck, [3, 24, 36, 3],\n                   radix=2,\n                   groups=1,\n                   bottleneck_width=64,\n                   deep_stem=True,\n                   stem_width=64,\n                   avg_down=True,\n                   avd=True,\n                   avd_first=False,\n                   **kwargs)\n    if pretrained:\n        model.load_state_dict(\n            torch.hub.load_state_dict_from_url(\n                resnest_model_urls['resnest200'],\n                progress=True,\n                check_hash=True))\n    return model\n\n\ndef resnest269(pretrained=False, root='~/.encoding/models', **kwargs):\n    model = ResNet(Bottleneck, [3, 30, 48, 8],\n                   radix=2,\n                   groups=1,\n                   bottleneck_width=64,\n                   deep_stem=True,\n                   stem_width=64,\n                   avg_down=True,\n                   avd=True,\n                   avd_first=False,\n                   **kwargs)\n    if pretrained:\n        model.load_state_dict(\n            torch.hub.load_state_dict_from_url(\n                resnest_model_urls['resnest269'],\n                progress=True,\n                check_hash=True))\n    return model\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/encoders/resnest/resnet.py",
    "content": "import math\nimport torch.nn as nn\n\nfrom .splat import SplAtConv2d, DropBlock2D\nfrom detectron2.aot_modules.utils.learning import freeze_params\n\n__all__ = ['ResNet', 'Bottleneck']\n\n_url_format = 'https://s3.us-west-1.wasabisys.com/resnest/torch/{}-{}.pth'\n\n_model_sha256 = {name: checksum for checksum, name in []}\n\n\ndef short_hash(name):\n    if name not in _model_sha256:\n        raise ValueError(\n            'Pretrained model for {name} is not available.'.format(name=name))\n    return _model_sha256[name][:8]\n\n\nresnest_model_urls = {\n    name: _url_format.format(name, short_hash(name))\n    for name in _model_sha256.keys()\n}\n\n\nclass GlobalAvgPool2d(nn.Module):\n    def __init__(self):\n        \"\"\"Global average pooling over the input's spatial dimensions\"\"\"\n        super(GlobalAvgPool2d, self).__init__()\n\n    def forward(self, inputs):\n        return nn.functional.adaptive_avg_pool2d(inputs,\n                                                 1).view(inputs.size(0), -1)\n\n\nclass Bottleneck(nn.Module):\n    \"\"\"ResNet Bottleneck\n    \"\"\"\n    # pylint: disable=unused-argument\n    expansion = 4\n\n    def __init__(self,\n                 inplanes,\n                 planes,\n                 stride=1,\n                 downsample=None,\n                 radix=1,\n                 cardinality=1,\n                 bottleneck_width=64,\n                 avd=False,\n                 avd_first=False,\n                 dilation=1,\n                 is_first=False,\n                 rectified_conv=False,\n                 rectify_avg=False,\n                 norm_layer=None,\n                 dropblock_prob=0.0,\n                 last_gamma=False):\n        super(Bottleneck, self).__init__()\n        group_width = int(planes * (bottleneck_width / 64.)) * cardinality\n        self.conv1 = nn.Conv2d(inplanes,\n                               group_width,\n                               kernel_size=1,\n                               bias=False)\n        self.bn1 = norm_layer(group_width)\n        self.dropblock_prob = dropblock_prob\n        self.radix = radix\n        self.avd = avd and (stride > 1 or is_first)\n        self.avd_first = avd_first\n\n        if self.avd:\n            self.avd_layer = nn.AvgPool2d(3, stride, padding=1)\n            stride = 1\n\n        if dropblock_prob > 0.0:\n            self.dropblock1 = DropBlock2D(dropblock_prob, 3)\n            if radix == 1:\n                self.dropblock2 = DropBlock2D(dropblock_prob, 3)\n            self.dropblock3 = DropBlock2D(dropblock_prob, 3)\n\n        if radix >= 1:\n            self.conv2 = SplAtConv2d(group_width,\n                                     group_width,\n                                     kernel_size=3,\n                                     stride=stride,\n                                     padding=dilation,\n                                     dilation=dilation,\n                                     groups=cardinality,\n                                     bias=False,\n                                     radix=radix,\n                                     rectify=rectified_conv,\n                                     rectify_avg=rectify_avg,\n                                     norm_layer=norm_layer,\n                                     dropblock_prob=dropblock_prob)\n        elif rectified_conv:\n            from rfconv import RFConv2d\n            self.conv2 = RFConv2d(group_width,\n                                  group_width,\n                                  kernel_size=3,\n                                  stride=stride,\n                                  padding=dilation,\n                                  dilation=dilation,\n                                  groups=cardinality,\n                                  bias=False,\n                                  average_mode=rectify_avg)\n            self.bn2 = norm_layer(group_width)\n        else:\n            self.conv2 = nn.Conv2d(group_width,\n                                   group_width,\n                                   kernel_size=3,\n                                   stride=stride,\n                                   padding=dilation,\n                                   dilation=dilation,\n                                   groups=cardinality,\n                                   bias=False)\n            self.bn2 = norm_layer(group_width)\n\n        self.conv3 = nn.Conv2d(group_width,\n                               planes * 4,\n                               kernel_size=1,\n                               bias=False)\n        self.bn3 = norm_layer(planes * 4)\n\n        if last_gamma:\n            from torch.nn.init import zeros_\n            zeros_(self.bn3.weight)\n        self.relu = nn.ReLU(inplace=True)\n        self.downsample = downsample\n        self.dilation = dilation\n        self.stride = stride\n\n    def forward(self, x):\n        residual = x\n\n        out = self.conv1(x)\n        out = self.bn1(out)\n        if self.dropblock_prob > 0.0:\n            out = self.dropblock1(out)\n        out = self.relu(out)\n\n        if self.avd and self.avd_first:\n            out = self.avd_layer(out)\n\n        out = self.conv2(out)\n        if self.radix == 0:\n            out = self.bn2(out)\n            if self.dropblock_prob > 0.0:\n                out = self.dropblock2(out)\n            out = self.relu(out)\n\n        if self.avd and not self.avd_first:\n            out = self.avd_layer(out)\n\n        out = self.conv3(out)\n        out = self.bn3(out)\n        if self.dropblock_prob > 0.0:\n            out = self.dropblock3(out)\n\n        if self.downsample is not None:\n            residual = self.downsample(x)\n\n        out += residual\n        out = self.relu(out)\n\n        return out\n\n\nclass ResNet(nn.Module):\n    \"\"\"ResNet Variants\n    Parameters\n    ----------\n    block : Block\n        Class for the residual block. Options are BasicBlockV1, BottleneckV1.\n    layers : list of int\n        Numbers of layers in each block\n    classes : int, default 1000\n        Number of classification classes.\n    dilated : bool, default False\n        Applying dilation strategy to pretrained ResNet yielding a stride-8 model,\n        typically used in Semantic Segmentation.\n    norm_layer : object\n        Normalization layer used in backbone network (default: :class:`mxnet.gluon.nn.BatchNorm`;\n        for Synchronized Cross-GPU BachNormalization).\n    Reference:\n        - He, Kaiming, et al. \"Deep residual learning for image recognition.\" Proceedings of the IEEE conference on computer vision and pattern recognition. 2016.\n        - Yu, Fisher, and Vladlen Koltun. \"Multi-scale context aggregation by dilated convolutions.\"\n    \"\"\"\n\n    # pylint: disable=unused-variable\n    def __init__(self,\n                 block,\n                 layers,\n                 radix=1,\n                 groups=1,\n                 bottleneck_width=64,\n                 num_classes=1000,\n                 dilated=False,\n                 dilation=1,\n                 deep_stem=False,\n                 stem_width=64,\n                 avg_down=False,\n                 rectified_conv=False,\n                 rectify_avg=False,\n                 avd=False,\n                 avd_first=False,\n                 final_drop=0.0,\n                 dropblock_prob=0,\n                 last_gamma=False,\n                 norm_layer=nn.BatchNorm2d,\n                 freeze_at=0):\n        self.cardinality = groups\n        self.bottleneck_width = bottleneck_width\n        # ResNet-D params\n        self.inplanes = stem_width * 2 if deep_stem else 64\n        self.avg_down = avg_down\n        self.last_gamma = last_gamma\n        # ResNeSt params\n        self.radix = radix\n        self.avd = avd\n        self.avd_first = avd_first\n\n        super(ResNet, self).__init__()\n        self.rectified_conv = rectified_conv\n        self.rectify_avg = rectify_avg\n        if rectified_conv:\n            from rfconv import RFConv2d\n            conv_layer = RFConv2d\n        else:\n            conv_layer = nn.Conv2d\n        conv_kwargs = {'average_mode': rectify_avg} if rectified_conv else {}\n        if deep_stem:\n            self.conv1 = nn.Sequential(\n                conv_layer(3,\n                           stem_width,\n                           kernel_size=3,\n                           stride=2,\n                           padding=1,\n                           bias=False,\n                           **conv_kwargs),\n                norm_layer(stem_width),\n                nn.ReLU(inplace=True),\n                conv_layer(stem_width,\n                           stem_width,\n                           kernel_size=3,\n                           stride=1,\n                           padding=1,\n                           bias=False,\n                           **conv_kwargs),\n                norm_layer(stem_width),\n                nn.ReLU(inplace=True),\n                conv_layer(stem_width,\n                           stem_width * 2,\n                           kernel_size=3,\n                           stride=1,\n                           padding=1,\n                           bias=False,\n                           **conv_kwargs),\n            )\n        else:\n            self.conv1 = conv_layer(3,\n                                    64,\n                                    kernel_size=7,\n                                    stride=2,\n                                    padding=3,\n                                    bias=False,\n                                    **conv_kwargs)\n        self.bn1 = norm_layer(self.inplanes)\n        self.relu = nn.ReLU(inplace=True)\n        self.maxpool = nn.MaxPool2d(kernel_size=3, stride=2, padding=1)\n        self.layer1 = self._make_layer(block,\n                                       64,\n                                       layers[0],\n                                       norm_layer=norm_layer,\n                                       is_first=False)\n        self.layer2 = self._make_layer(block,\n                                       128,\n                                       layers[1],\n                                       stride=2,\n                                       norm_layer=norm_layer)\n        if dilated or dilation == 4:\n            self.layer3 = self._make_layer(block,\n                                           256,\n                                           layers[2],\n                                           stride=1,\n                                           dilation=2,\n                                           norm_layer=norm_layer,\n                                           dropblock_prob=dropblock_prob)\n        elif dilation == 2:\n            self.layer3 = self._make_layer(block,\n                                           256,\n                                           layers[2],\n                                           stride=2,\n                                           dilation=1,\n                                           norm_layer=norm_layer,\n                                           dropblock_prob=dropblock_prob)\n        else:\n            self.layer3 = self._make_layer(block,\n                                           256,\n                                           layers[2],\n                                           stride=2,\n                                           norm_layer=norm_layer,\n                                           dropblock_prob=dropblock_prob)\n\n        self.stem = [self.conv1, self.bn1]\n        self.stages = [self.layer1, self.layer2, self.layer3]\n\n        for m in self.modules():\n            if isinstance(m, nn.Conv2d):\n                n = m.kernel_size[0] * m.kernel_size[1] * m.out_channels\n                m.weight.data.normal_(0, math.sqrt(2. / n))\n            elif isinstance(m, norm_layer):\n                m.weight.data.fill_(1)\n                m.bias.data.zero_()\n\n        self.freeze(freeze_at)\n\n    def _make_layer(self,\n                    block,\n                    planes,\n                    blocks,\n                    stride=1,\n                    dilation=1,\n                    norm_layer=None,\n                    dropblock_prob=0.0,\n                    is_first=True):\n        downsample = None\n        if stride != 1 or self.inplanes != planes * block.expansion:\n            down_layers = []\n            if self.avg_down:\n                if dilation == 1:\n                    down_layers.append(\n                        nn.AvgPool2d(kernel_size=stride,\n                                     stride=stride,\n                                     ceil_mode=True,\n                                     count_include_pad=False))\n                else:\n                    down_layers.append(\n                        nn.AvgPool2d(kernel_size=1,\n                                     stride=1,\n                                     ceil_mode=True,\n                                     count_include_pad=False))\n                down_layers.append(\n                    nn.Conv2d(self.inplanes,\n                              planes * block.expansion,\n                              kernel_size=1,\n                              stride=1,\n                              bias=False))\n            else:\n                down_layers.append(\n                    nn.Conv2d(self.inplanes,\n                              planes * block.expansion,\n                              kernel_size=1,\n                              stride=stride,\n                              bias=False))\n            down_layers.append(norm_layer(planes * block.expansion))\n            downsample = nn.Sequential(*down_layers)\n\n        layers = []\n        if dilation == 1 or dilation == 2:\n            layers.append(\n                block(self.inplanes,\n                      planes,\n                      stride,\n                      downsample=downsample,\n                      radix=self.radix,\n                      cardinality=self.cardinality,\n                      bottleneck_width=self.bottleneck_width,\n                      avd=self.avd,\n                      avd_first=self.avd_first,\n                      dilation=1,\n                      is_first=is_first,\n                      rectified_conv=self.rectified_conv,\n                      rectify_avg=self.rectify_avg,\n                      norm_layer=norm_layer,\n                      dropblock_prob=dropblock_prob,\n                      last_gamma=self.last_gamma))\n        elif dilation == 4:\n            layers.append(\n                block(self.inplanes,\n                      planes,\n                      stride,\n                      downsample=downsample,\n                      radix=self.radix,\n                      cardinality=self.cardinality,\n                      bottleneck_width=self.bottleneck_width,\n                      avd=self.avd,\n                      avd_first=self.avd_first,\n                      dilation=2,\n                      is_first=is_first,\n                      rectified_conv=self.rectified_conv,\n                      rectify_avg=self.rectify_avg,\n                      norm_layer=norm_layer,\n                      dropblock_prob=dropblock_prob,\n                      last_gamma=self.last_gamma))\n        else:\n            raise RuntimeError(\"=> unknown dilation size: {}\".format(dilation))\n\n        self.inplanes = planes * block.expansion\n        for i in range(1, blocks):\n            layers.append(\n                block(self.inplanes,\n                      planes,\n                      radix=self.radix,\n                      cardinality=self.cardinality,\n                      bottleneck_width=self.bottleneck_width,\n                      avd=self.avd,\n                      avd_first=self.avd_first,\n                      dilation=dilation,\n                      rectified_conv=self.rectified_conv,\n                      rectify_avg=self.rectify_avg,\n                      norm_layer=norm_layer,\n                      dropblock_prob=dropblock_prob,\n                      last_gamma=self.last_gamma))\n\n        return nn.Sequential(*layers)\n\n    def forward(self, x):\n        x = self.conv1(x)\n        x = self.bn1(x)\n        x = self.relu(x)\n        x = self.maxpool(x)\n\n        xs = []\n\n        x = self.layer1(x)\n        xs.append(x)  # 4X\n        x = self.layer2(x)\n        xs.append(x)  # 8X\n        x = self.layer3(x)\n        xs.append(x)  # 16X\n        # Following STMVOS, we drop stage 5.\n        xs.append(x)  # 16X\n\n        return xs\n\n    def freeze(self, freeze_at):\n        if freeze_at >= 1:\n            for m in self.stem:\n                freeze_params(m)\n\n        for idx, stage in enumerate(self.stages, start=2):\n            if freeze_at >= idx:\n                freeze_params(stage)\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/encoders/resnest/splat.py",
    "content": "import torch\nfrom torch import nn\nimport torch.nn.functional as F\nfrom torch.nn import Conv2d, Module, ReLU\nfrom torch.nn.modules.utils import _pair\n\n__all__ = ['SplAtConv2d', 'DropBlock2D']\n\n\nclass DropBlock2D(object):\n    def __init__(self, *args, **kwargs):\n        raise NotImplementedError\n\n\nclass SplAtConv2d(Module):\n    \"\"\"Split-Attention Conv2d\n    \"\"\"\n    def __init__(self,\n                 in_channels,\n                 channels,\n                 kernel_size,\n                 stride=(1, 1),\n                 padding=(0, 0),\n                 dilation=(1, 1),\n                 groups=1,\n                 bias=True,\n                 radix=2,\n                 reduction_factor=4,\n                 rectify=False,\n                 rectify_avg=False,\n                 norm_layer=None,\n                 dropblock_prob=0.0,\n                 **kwargs):\n        super(SplAtConv2d, self).__init__()\n        padding = _pair(padding)\n        self.rectify = rectify and (padding[0] > 0 or padding[1] > 0)\n        self.rectify_avg = rectify_avg\n        inter_channels = max(in_channels * radix // reduction_factor, 32)\n        self.radix = radix\n        self.cardinality = groups\n        self.channels = channels\n        self.dropblock_prob = dropblock_prob\n        if self.rectify:\n            from rfconv import RFConv2d\n            self.conv = RFConv2d(in_channels,\n                                 channels * radix,\n                                 kernel_size,\n                                 stride,\n                                 padding,\n                                 dilation,\n                                 groups=groups * radix,\n                                 bias=bias,\n                                 average_mode=rectify_avg,\n                                 **kwargs)\n        else:\n            self.conv = Conv2d(in_channels,\n                               channels * radix,\n                               kernel_size,\n                               stride,\n                               padding,\n                               dilation,\n                               groups=groups * radix,\n                               bias=bias,\n                               **kwargs)\n        self.use_bn = norm_layer is not None\n        if self.use_bn:\n            self.bn0 = norm_layer(channels * radix)\n        self.relu = ReLU(inplace=True)\n        self.fc1 = Conv2d(channels, inter_channels, 1, groups=self.cardinality)\n        if self.use_bn:\n            self.bn1 = norm_layer(inter_channels)\n        self.fc2 = Conv2d(inter_channels,\n                          channels * radix,\n                          1,\n                          groups=self.cardinality)\n        if dropblock_prob > 0.0:\n            self.dropblock = DropBlock2D(dropblock_prob, 3)\n        self.rsoftmax = rSoftMax(radix, groups)\n\n    def forward(self, x):\n        x = self.conv(x)\n        if self.use_bn:\n            x = self.bn0(x)\n        if self.dropblock_prob > 0.0:\n            x = self.dropblock(x)\n        x = self.relu(x)\n\n        batch, rchannel = x.shape[:2]\n        if self.radix > 1:\n            if torch.__version__ < '1.5':\n                splited = torch.split(x, int(rchannel // self.radix), dim=1)\n            else:\n                splited = torch.split(x, rchannel // self.radix, dim=1)\n            gap = sum(splited)\n        else:\n            gap = x\n        gap = F.adaptive_avg_pool2d(gap, 1)\n        gap = self.fc1(gap)\n\n        if self.use_bn:\n            gap = self.bn1(gap)\n        gap = self.relu(gap)\n\n        atten = self.fc2(gap)\n        atten = self.rsoftmax(atten).view(batch, -1, 1, 1)\n\n        if self.radix > 1:\n            if torch.__version__ < '1.5':\n                attens = torch.split(atten, int(rchannel // self.radix), dim=1)\n            else:\n                attens = torch.split(atten, rchannel // self.radix, dim=1)\n            out = sum([att * split for (att, split) in zip(attens, splited)])\n        else:\n            out = atten * x\n        return out.contiguous()\n\n\nclass rSoftMax(nn.Module):\n    def __init__(self, radix, cardinality):\n        super().__init__()\n        self.radix = radix\n        self.cardinality = cardinality\n\n    def forward(self, x):\n        batch = x.size(0)\n        if self.radix > 1:\n            x = x.view(batch, self.cardinality, self.radix, -1).transpose(1, 2)\n            x = F.softmax(x, dim=1)\n            x = x.reshape(batch, -1)\n        else:\n            x = torch.sigmoid(x)\n        return x\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/encoders/resnet.py",
    "content": "import math\nimport torch.nn as nn\nfrom detectron2.aot_modules.utils.learning import freeze_params\n\n\nclass Bottleneck(nn.Module):\n    expansion = 4\n\n    def __init__(self,\n                 inplanes,\n                 planes,\n                 stride=1,\n                 dilation=1,\n                 downsample=None,\n                 BatchNorm=None):\n        super(Bottleneck, self).__init__()\n        self.conv1 = nn.Conv2d(inplanes, planes, kernel_size=1, bias=False)\n        self.bn1 = BatchNorm(planes)\n        self.conv2 = nn.Conv2d(planes,\n                               planes,\n                               kernel_size=3,\n                               stride=stride,\n                               dilation=dilation,\n                               padding=dilation,\n                               bias=False)\n        self.bn2 = BatchNorm(planes)\n        self.conv3 = nn.Conv2d(planes, planes * 4, kernel_size=1, bias=False)\n        self.bn3 = BatchNorm(planes * 4)\n        self.relu = nn.ReLU(inplace=True)\n        self.downsample = downsample\n        self.stride = stride\n        self.dilation = dilation\n\n    def forward(self, x):\n        residual = x\n\n        out = self.conv1(x)\n        out = self.bn1(out)\n        out = self.relu(out)\n\n        out = self.conv2(out)\n        out = self.bn2(out)\n        out = self.relu(out)\n\n        out = self.conv3(out)\n        out = self.bn3(out)\n\n        if self.downsample is not None:\n            residual = self.downsample(x)\n\n        out += residual\n        out = self.relu(out)\n\n        return out\n\n\nclass ResNet(nn.Module):\n    def __init__(self, block, layers, output_stride, BatchNorm, freeze_at=0):\n        self.inplanes = 64\n        super(ResNet, self).__init__()\n\n        if output_stride == 16:\n            strides = [1, 2, 2, 1]\n            dilations = [1, 1, 1, 2]\n        elif output_stride == 8:\n            strides = [1, 2, 1, 1]\n            dilations = [1, 1, 2, 4]\n        else:\n            raise NotImplementedError\n\n        # Modules\n        self.conv1 = nn.Conv2d(3,\n                               64,\n                               kernel_size=7,\n                               stride=2,\n                               padding=3,\n                               bias=False)\n        self.bn1 = BatchNorm(64)\n        self.relu = nn.ReLU(inplace=True)\n        self.maxpool = nn.MaxPool2d(kernel_size=3, stride=2, padding=1)\n\n        self.layer1 = self._make_layer(block,\n                                       64,\n                                       layers[0],\n                                       stride=strides[0],\n                                       dilation=dilations[0],\n                                       BatchNorm=BatchNorm)\n        self.layer2 = self._make_layer(block,\n                                       128,\n                                       layers[1],\n                                       stride=strides[1],\n                                       dilation=dilations[1],\n                                       BatchNorm=BatchNorm)\n        self.layer3 = self._make_layer(block,\n                                       256,\n                                       layers[2],\n                                       stride=strides[2],\n                                       dilation=dilations[2],\n                                       BatchNorm=BatchNorm)\n        # self.layer4 = self._make_layer(block, 512, layers[3], stride=strides[3], dilation=dilations[3], BatchNorm=BatchNorm)\n\n        self.stem = [self.conv1, self.bn1]\n        self.stages = [self.layer1, self.layer2, self.layer3]\n\n        self._init_weight()\n        self.freeze(freeze_at)\n\n    def _make_layer(self,\n                    block,\n                    planes,\n                    blocks,\n                    stride=1,\n                    dilation=1,\n                    BatchNorm=None):\n        downsample = None\n        if stride != 1 or self.inplanes != planes * block.expansion:\n            downsample = nn.Sequential(\n                nn.Conv2d(self.inplanes,\n                          planes * block.expansion,\n                          kernel_size=1,\n                          stride=stride,\n                          bias=False),\n                BatchNorm(planes * block.expansion),\n            )\n\n        layers = []\n        layers.append(\n            block(self.inplanes, planes, stride, max(dilation // 2, 1),\n                  downsample, BatchNorm))\n        self.inplanes = planes * block.expansion\n        for i in range(1, blocks):\n            layers.append(\n                block(self.inplanes,\n                      planes,\n                      dilation=dilation,\n                      BatchNorm=BatchNorm))\n\n        return nn.Sequential(*layers)\n\n    def forward(self, input):\n        x = self.conv1(input)\n        x = self.bn1(x)\n        x = self.relu(x)\n        x = self.maxpool(x)\n\n        xs = []\n\n        x = self.layer1(x)\n        xs.append(x)  # 4X\n        x = self.layer2(x)\n        xs.append(x)  # 8X\n        x = self.layer3(x)\n        xs.append(x)  # 16X\n        # Following STMVOS, we drop stage 5.\n        xs.append(x)  # 16X\n\n        return xs\n\n    def _init_weight(self):\n        for m in self.modules():\n            if isinstance(m, nn.Conv2d):\n                n = m.kernel_size[0] * m.kernel_size[1] * m.out_channels\n                m.weight.data.normal_(0, math.sqrt(2. / n))\n            elif isinstance(m, nn.BatchNorm2d):\n                m.weight.data.fill_(1)\n                m.bias.data.zero_()\n\n    def freeze(self, freeze_at):\n        if freeze_at >= 1:\n            for m in self.stem:\n                freeze_params(m)\n\n        for idx, stage in enumerate(self.stages, start=2):\n            if freeze_at >= idx:\n                freeze_params(stage)\n\n\ndef ResNet50(output_stride, BatchNorm, freeze_at=0):\n    \"\"\"Constructs a ResNet-50 model.\n    Args:\n        pretrained (bool): If True, returns a model pre-trained on ImageNet\n    \"\"\"\n    model = ResNet(Bottleneck, [3, 4, 6, 3],\n                   output_stride,\n                   BatchNorm,\n                   freeze_at=freeze_at)\n    return model\n\n\ndef ResNet101(output_stride, BatchNorm, freeze_at=0):\n    \"\"\"Constructs a ResNet-101 model.\n    Args:\n        pretrained (bool): If True, returns a model pre-trained on ImageNet\n    \"\"\"\n    model = ResNet(Bottleneck, [3, 4, 23, 3],\n                   output_stride,\n                   BatchNorm,\n                   freeze_at=freeze_at)\n    return model\n\n\nif __name__ == \"__main__\":\n    import torch\n    model = ResNet101(BatchNorm=nn.BatchNorm2d, output_stride=8)\n    input = torch.rand(1, 3, 512, 512)\n    output, low_level_feat = model(input)\n    print(output.size())\n    print(low_level_feat.size())\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/encoders/swin/__init__.py",
    "content": "from .build import build_swin_model"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/encoders/swin/build.py",
    "content": "# --------------------------------------------------------\n# Swin Transformer\n# Copyright (c) 2021 Microsoft\n# Licensed under The MIT License [see LICENSE for details]\n# Written by Ze Liu\n# --------------------------------------------------------\n\nfrom .swin_transformer import SwinTransformer\n\n\ndef build_swin_model(model_type, freeze_at=0):\n    if model_type == 'swin_base':\n        model = SwinTransformer(embed_dim=128,\n                                depths=[2, 2, 18, 2],\n                                num_heads=[4, 8, 16, 32],\n                                window_size=7,\n                                drop_path_rate=0.3,\n                                out_indices=(0, 1, 2),\n                                ape=False,\n                                patch_norm=True,\n                                frozen_stages=freeze_at,\n                                use_checkpoint=False)\n\n    else:\n        raise NotImplementedError(f\"Unkown model: {model_type}\")\n\n    return model\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/encoders/swin/swin_transformer.py",
    "content": "# --------------------------------------------------------\n# Swin Transformer\n# Copyright (c) 2021 Microsoft\n# Licensed under The MIT License [see LICENSE for details]\n# Written by Ze Liu\n# --------------------------------------------------------\nfrom itertools import repeat\nimport collections.abc\n\nimport numpy as np\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nimport torch.utils.checkpoint as checkpoint\n\nfrom detectron2.aot_modules.layers.basic import DropPath\n\n\ndef _ntuple(n):\n    def parse(x):\n        if isinstance(x, collections.abc.Iterable):\n            return x\n        return tuple(repeat(x, n))\n\n    return parse\n\n\nto_2tuple = _ntuple(2)\n\n\ndef trunc_normal_(tensor, mean=0, std=1):\n    size = tensor.shape\n    tmp = tensor.new_empty(size + (4, )).normal_()\n    valid = (tmp < 2) & (tmp > -2)\n    ind = valid.max(-1, keepdim=True)[1]\n    tensor.data.copy_(tmp.gather(-1, ind).squeeze(-1))\n    tensor.data.mul_(std).add_(mean)\n    return tensor\n\n\nclass Mlp(nn.Module):\n    \"\"\" Multilayer perceptron.\"\"\"\n    def __init__(self,\n                 in_features,\n                 hidden_features=None,\n                 out_features=None,\n                 act_layer=nn.GELU,\n                 drop=0.):\n        super().__init__()\n        out_features = out_features or in_features\n        hidden_features = hidden_features or in_features\n        self.fc1 = nn.Linear(in_features, hidden_features)\n        self.act = act_layer()\n        self.fc2 = nn.Linear(hidden_features, out_features)\n        self.drop = nn.Dropout(drop)\n\n    def forward(self, x):\n        x = self.fc1(x)\n        x = self.act(x)\n        x = self.drop(x)\n        x = self.fc2(x)\n        x = self.drop(x)\n        return x\n\n\ndef window_partition(x, window_size):\n    \"\"\"\n    Args:\n        x: (B, H, W, C)\n        window_size (int): window size\n    Returns:\n        windows: (num_windows*B, window_size, window_size, C)\n    \"\"\"\n    B, H, W, C = x.shape\n    x = x.view(B, H // window_size, window_size, W // window_size, window_size,\n               C)\n    windows = x.permute(0, 1, 3, 2, 4,\n                        5).contiguous().view(-1, window_size, window_size, C)\n    return windows\n\n\ndef window_reverse(windows, window_size, H, W):\n    \"\"\"\n    Args:\n        windows: (num_windows*B, window_size, window_size, C)\n        window_size (int): Window size\n        H (int): Height of image\n        W (int): Width of image\n    Returns:\n        x: (B, H, W, C)\n    \"\"\"\n    B = int(windows.shape[0] / (H * W / window_size / window_size))\n    x = windows.view(B, H // window_size, W // window_size, window_size,\n                     window_size, -1)\n    x = x.permute(0, 1, 3, 2, 4, 5).contiguous().view(B, H, W, -1)\n    return x\n\n\nclass WindowAttention(nn.Module):\n    \"\"\" Window based multi-head self attention (W-MSA) module with relative position bias.\n    It supports both of shifted and non-shifted window.\n    Args:\n        dim (int): Number of input channels.\n        window_size (tuple[int]): The height and width of the window.\n        num_heads (int): Number of attention heads.\n        qkv_bias (bool, optional):  If True, add a learnable bias to query, key, value. Default: True\n        qk_scale (float | None, optional): Override default qk scale of head_dim ** -0.5 if set\n        attn_drop (float, optional): Dropout ratio of attention weight. Default: 0.0\n        proj_drop (float, optional): Dropout ratio of output. Default: 0.0\n    \"\"\"\n    def __init__(self,\n                 dim,\n                 window_size,\n                 num_heads,\n                 qkv_bias=True,\n                 qk_scale=None,\n                 attn_drop=0.,\n                 proj_drop=0.):\n\n        super().__init__()\n        self.dim = dim\n        self.window_size = window_size  # Wh, Ww\n        self.num_heads = num_heads\n        head_dim = dim // num_heads\n        self.scale = qk_scale or head_dim**-0.5\n\n        # define a parameter table of relative position bias\n        self.relative_position_bias_table = nn.Parameter(\n            torch.zeros((2 * window_size[0] - 1) * (2 * window_size[1] - 1),\n                        num_heads))  # 2*Wh-1 * 2*Ww-1, nH\n\n        # get pair-wise relative position index for each token inside the window\n        coords_h = torch.arange(self.window_size[0])\n        coords_w = torch.arange(self.window_size[1])\n        coords = torch.stack(torch.meshgrid([coords_h, coords_w]))  # 2, Wh, Ww\n        coords_flatten = torch.flatten(coords, 1)  # 2, Wh*Ww\n        relative_coords = coords_flatten[:, :,\n                                         None] - coords_flatten[:,\n                                                                None, :]  # 2, Wh*Ww, Wh*Ww\n        relative_coords = relative_coords.permute(\n            1, 2, 0).contiguous()  # Wh*Ww, Wh*Ww, 2\n        relative_coords[:, :,\n                        0] += self.window_size[0] - 1  # shift to start from 0\n        relative_coords[:, :, 1] += self.window_size[1] - 1\n        relative_coords[:, :, 0] *= 2 * self.window_size[1] - 1\n        relative_position_index = relative_coords.sum(-1)  # Wh*Ww, Wh*Ww\n        self.register_buffer(\"relative_position_index\",\n                             relative_position_index)\n\n        self.qkv = nn.Linear(dim, dim * 3, bias=qkv_bias)\n        self.attn_drop = nn.Dropout(attn_drop)\n        self.proj = nn.Linear(dim, dim)\n        self.proj_drop = nn.Dropout(proj_drop)\n\n        trunc_normal_(self.relative_position_bias_table, std=.02)\n        self.softmax = nn.Softmax(dim=-1)\n\n    def forward(self, x, mask=None):\n        \"\"\" Forward function.\n        Args:\n            x: input features with shape of (num_windows*B, N, C)\n            mask: (0/-inf) mask with shape of (num_windows, Wh*Ww, Wh*Ww) or None\n        \"\"\"\n        B_, N, C = x.shape\n        qkv = self.qkv(x).reshape(B_, N, 3, self.num_heads,\n                                  C // self.num_heads).permute(2, 0, 3, 1, 4)\n        q, k, v = qkv[0], qkv[1], qkv[\n            2]  # make torchscript happy (cannot use tensor as tuple)\n\n        q = q * self.scale\n        attn = (q @ k.transpose(-2, -1))\n\n        relative_position_bias = self.relative_position_bias_table[\n            self.relative_position_index.view(-1)].view(\n                self.window_size[0] * self.window_size[1],\n                self.window_size[0] * self.window_size[1],\n                -1)  # Wh*Ww,Wh*Ww,nH\n        relative_position_bias = relative_position_bias.permute(\n            2, 0, 1).contiguous()  # nH, Wh*Ww, Wh*Ww\n        attn = attn + relative_position_bias.unsqueeze(0)\n\n        if mask is not None:\n            nW = mask.shape[0]\n            attn = attn.view(B_ // nW, nW, self.num_heads, N,\n                             N) + mask.unsqueeze(1).unsqueeze(0)\n            attn = attn.view(-1, self.num_heads, N, N)\n            attn = self.softmax(attn)\n        else:\n            attn = self.softmax(attn)\n\n        attn = self.attn_drop(attn)\n\n        x = (attn @ v).transpose(1, 2).reshape(B_, N, C)\n        x = self.proj(x)\n        x = self.proj_drop(x)\n        return x\n\n\nclass SwinTransformerBlock(nn.Module):\n    \"\"\" Swin Transformer Block.\n    Args:\n        dim (int): Number of input channels.\n        num_heads (int): Number of attention heads.\n        window_size (int): Window size.\n        shift_size (int): Shift size for SW-MSA.\n        mlp_ratio (float): Ratio of mlp hidden dim to embedding dim.\n        qkv_bias (bool, optional): If True, add a learnable bias to query, key, value. Default: True\n        qk_scale (float | None, optional): Override default qk scale of head_dim ** -0.5 if set.\n        drop (float, optional): Dropout rate. Default: 0.0\n        attn_drop (float, optional): Attention dropout rate. Default: 0.0\n        drop_path (float, optional): Stochastic depth rate. Default: 0.0\n        act_layer (nn.Module, optional): Activation layer. Default: nn.GELU\n        norm_layer (nn.Module, optional): Normalization layer.  Default: nn.LayerNorm\n    \"\"\"\n    def __init__(self,\n                 dim,\n                 num_heads,\n                 window_size=7,\n                 shift_size=0,\n                 mlp_ratio=4.,\n                 qkv_bias=True,\n                 qk_scale=None,\n                 drop=0.,\n                 attn_drop=0.,\n                 drop_path=0.,\n                 act_layer=nn.GELU,\n                 norm_layer=nn.LayerNorm):\n        super().__init__()\n        self.dim = dim\n        self.num_heads = num_heads\n        self.window_size = window_size\n        self.shift_size = shift_size\n        self.mlp_ratio = mlp_ratio\n        assert 0 <= self.shift_size < self.window_size, \"shift_size must in 0-window_size\"\n\n        self.norm1 = norm_layer(dim)\n        self.attn = WindowAttention(dim,\n                                    window_size=to_2tuple(self.window_size),\n                                    num_heads=num_heads,\n                                    qkv_bias=qkv_bias,\n                                    qk_scale=qk_scale,\n                                    attn_drop=attn_drop,\n                                    proj_drop=drop)\n\n        self.drop_path = DropPath(\n            drop_path) if drop_path > 0. else nn.Identity()\n        self.norm2 = norm_layer(dim)\n        mlp_hidden_dim = int(dim * mlp_ratio)\n        self.mlp = Mlp(in_features=dim,\n                       hidden_features=mlp_hidden_dim,\n                       act_layer=act_layer,\n                       drop=drop)\n\n        self.H = None\n        self.W = None\n\n    def forward(self, x, mask_matrix):\n        \"\"\" Forward function.\n        Args:\n            x: Input feature, tensor size (B, H*W, C).\n            H, W: Spatial resolution of the input feature.\n            mask_matrix: Attention mask for cyclic shift.\n        \"\"\"\n        B, L, C = x.shape\n        H, W = self.H, self.W\n        assert L == H * W, \"input feature has wrong size\"\n\n        shortcut = x\n        x = self.norm1(x)\n        x = x.view(B, H, W, C)\n\n        # pad feature maps to multiples of window size\n        pad_l = pad_t = 0\n        pad_r = (self.window_size - W % self.window_size) % self.window_size\n        pad_b = (self.window_size - H % self.window_size) % self.window_size\n        x = F.pad(x, (0, 0, pad_l, pad_r, pad_t, pad_b))\n        _, Hp, Wp, _ = x.shape\n\n        # cyclic shift\n        if self.shift_size > 0:\n            shifted_x = torch.roll(x,\n                                   shifts=(-self.shift_size, -self.shift_size),\n                                   dims=(1, 2))\n            attn_mask = mask_matrix\n        else:\n            shifted_x = x\n            attn_mask = None\n\n        # partition windows\n        x_windows = window_partition(\n            shifted_x, self.window_size)  # nW*B, window_size, window_size, C\n        x_windows = x_windows.view(-1, self.window_size * self.window_size,\n                                   C)  # nW*B, window_size*window_size, C\n\n        # W-MSA/SW-MSA\n        attn_windows = self.attn(\n            x_windows, mask=attn_mask)  # nW*B, window_size*window_size, C\n\n        # merge windows\n        attn_windows = attn_windows.view(-1, self.window_size,\n                                         self.window_size, C)\n        shifted_x = window_reverse(attn_windows, self.window_size, Hp,\n                                   Wp)  # B H' W' C\n\n        # reverse cyclic shift\n        if self.shift_size > 0:\n            x = torch.roll(shifted_x,\n                           shifts=(self.shift_size, self.shift_size),\n                           dims=(1, 2))\n        else:\n            x = shifted_x\n\n        if pad_r > 0 or pad_b > 0:\n            x = x[:, :H, :W, :].contiguous()\n\n        x = x.view(B, H * W, C)\n\n        # FFN\n        x = shortcut + self.drop_path(x)\n        x = x + self.drop_path(self.mlp(self.norm2(x)))\n\n        return x\n\n\nclass PatchMerging(nn.Module):\n    \"\"\" Patch Merging Layer\n    Args:\n        dim (int): Number of input channels.\n        norm_layer (nn.Module, optional): Normalization layer.  Default: nn.LayerNorm\n    \"\"\"\n    def __init__(self, dim, norm_layer=nn.LayerNorm):\n        super().__init__()\n        self.dim = dim\n        self.reduction = nn.Linear(4 * dim, 2 * dim, bias=False)\n        self.norm = norm_layer(4 * dim)\n\n    def forward(self, x, H, W):\n        \"\"\" Forward function.\n        Args:\n            x: Input feature, tensor size (B, H*W, C).\n            H, W: Spatial resolution of the input feature.\n        \"\"\"\n        B, L, C = x.shape\n        assert L == H * W, \"input feature has wrong size\"\n\n        x = x.view(B, H, W, C)\n\n        # padding\n        pad_input = (H % 2 == 1) or (W % 2 == 1)\n        if pad_input:\n            x = F.pad(x, (0, 0, 0, W % 2, 0, H % 2))\n\n        x0 = x[:, 0::2, 0::2, :]  # B H/2 W/2 C\n        x1 = x[:, 1::2, 0::2, :]  # B H/2 W/2 C\n        x2 = x[:, 0::2, 1::2, :]  # B H/2 W/2 C\n        x3 = x[:, 1::2, 1::2, :]  # B H/2 W/2 C\n        x = torch.cat([x0, x1, x2, x3], -1)  # B H/2 W/2 4*C\n        x = x.view(B, -1, 4 * C)  # B H/2*W/2 4*C\n\n        x = self.norm(x)\n        x = self.reduction(x)\n\n        return x\n\n\nclass BasicLayer(nn.Module):\n    \"\"\" A basic Swin Transformer layer for one stage.\n    Args:\n        dim (int): Number of feature channels\n        depth (int): Depths of this stage.\n        num_heads (int): Number of attention head.\n        window_size (int): Local window size. Default: 7.\n        mlp_ratio (float): Ratio of mlp hidden dim to embedding dim. Default: 4.\n        qkv_bias (bool, optional): If True, add a learnable bias to query, key, value. Default: True\n        qk_scale (float | None, optional): Override default qk scale of head_dim ** -0.5 if set.\n        drop (float, optional): Dropout rate. Default: 0.0\n        attn_drop (float, optional): Attention dropout rate. Default: 0.0\n        drop_path (float | tuple[float], optional): Stochastic depth rate. Default: 0.0\n        norm_layer (nn.Module, optional): Normalization layer. Default: nn.LayerNorm\n        downsample (nn.Module | None, optional): Downsample layer at the end of the layer. Default: None\n        use_checkpoint (bool): Whether to use checkpointing to save memory. Default: False.\n    \"\"\"\n    def __init__(self,\n                 dim,\n                 depth,\n                 num_heads,\n                 window_size=7,\n                 mlp_ratio=4.,\n                 qkv_bias=True,\n                 qk_scale=None,\n                 drop=0.,\n                 attn_drop=0.,\n                 drop_path=0.,\n                 norm_layer=nn.LayerNorm,\n                 downsample=None,\n                 use_checkpoint=False):\n        super().__init__()\n        self.window_size = window_size\n        self.shift_size = window_size // 2\n        self.depth = depth\n        self.use_checkpoint = use_checkpoint\n\n        # build blocks\n        self.blocks = nn.ModuleList([\n            SwinTransformerBlock(dim=dim,\n                                 num_heads=num_heads,\n                                 window_size=window_size,\n                                 shift_size=0 if\n                                 (i % 2 == 0) else window_size // 2,\n                                 mlp_ratio=mlp_ratio,\n                                 qkv_bias=qkv_bias,\n                                 qk_scale=qk_scale,\n                                 drop=drop,\n                                 attn_drop=attn_drop,\n                                 drop_path=drop_path[i] if isinstance(\n                                     drop_path, list) else drop_path,\n                                 norm_layer=norm_layer) for i in range(depth)\n        ])\n\n        # patch merging layer\n        if downsample is not None:\n            self.downsample = downsample(dim=dim, norm_layer=norm_layer)\n        else:\n            self.downsample = None\n\n    def forward(self, x, H, W):\n        \"\"\" Forward function.\n        Args:\n            x: Input feature, tensor size (B, H*W, C).\n            H, W: Spatial resolution of the input feature.\n        \"\"\"\n\n        # calculate attention mask for SW-MSA\n        Hp = int(np.ceil(H / self.window_size)) * self.window_size\n        Wp = int(np.ceil(W / self.window_size)) * self.window_size\n        img_mask = torch.zeros((1, Hp, Wp, 1), device=x.device)  # 1 Hp Wp 1\n        h_slices = (slice(0, -self.window_size),\n                    slice(-self.window_size,\n                          -self.shift_size), slice(-self.shift_size, None))\n        w_slices = (slice(0, -self.window_size),\n                    slice(-self.window_size,\n                          -self.shift_size), slice(-self.shift_size, None))\n        cnt = 0\n        for h in h_slices:\n            for w in w_slices:\n                img_mask[:, h, w, :] = cnt\n                cnt += 1\n\n        mask_windows = window_partition(\n            img_mask, self.window_size)  # nW, window_size, window_size, 1\n        mask_windows = mask_windows.view(-1,\n                                         self.window_size * self.window_size)\n        attn_mask = mask_windows.unsqueeze(1) - mask_windows.unsqueeze(2)\n        attn_mask = attn_mask.masked_fill(attn_mask != 0,\n                                          float(-100.0)).masked_fill(\n                                              attn_mask == 0, float(0.0))\n\n        for blk in self.blocks:\n            blk.H, blk.W = H, W\n            if self.use_checkpoint:\n                x = checkpoint.checkpoint(blk, x, attn_mask)\n            else:\n                x = blk(x, attn_mask)\n        if self.downsample is not None:\n            x_down = self.downsample(x, H, W)\n            Wh, Ww = (H + 1) // 2, (W + 1) // 2\n            return x, H, W, x_down, Wh, Ww\n        else:\n            return x, H, W, x, H, W\n\n\nclass PatchEmbed(nn.Module):\n    \"\"\" Image to Patch Embedding\n    Args:\n        patch_size (int): Patch token size. Default: 4.\n        in_chans (int): Number of input image channels. Default: 3.\n        embed_dim (int): Number of linear projection output channels. Default: 96.\n        norm_layer (nn.Module, optional): Normalization layer. Default: None\n    \"\"\"\n    def __init__(self,\n                 patch_size=4,\n                 in_chans=3,\n                 embed_dim=96,\n                 norm_layer=None):\n        super().__init__()\n        patch_size = to_2tuple(patch_size)\n        self.patch_size = patch_size\n\n        self.in_chans = in_chans\n        self.embed_dim = embed_dim\n\n        self.proj = nn.Conv2d(in_chans,\n                              embed_dim,\n                              kernel_size=patch_size,\n                              stride=patch_size)\n        if norm_layer is not None:\n            self.norm = norm_layer(embed_dim)\n        else:\n            self.norm = None\n\n    def forward(self, x):\n        \"\"\"Forward function.\"\"\"\n        # padding\n        _, _, H, W = x.size()\n        if W % self.patch_size[1] != 0:\n            x = F.pad(x, (0, self.patch_size[1] - W % self.patch_size[1]))\n        if H % self.patch_size[0] != 0:\n            x = F.pad(x,\n                      (0, 0, 0, self.patch_size[0] - H % self.patch_size[0]))\n\n        x = self.proj(x)  # B C Wh Ww\n        if self.norm is not None:\n            Wh, Ww = x.size(2), x.size(3)\n            x = x.flatten(2).transpose(1, 2)\n            x = self.norm(x)\n            x = x.transpose(1, 2).view(-1, self.embed_dim, Wh, Ww)\n\n        return x\n\n\nclass SwinTransformer(nn.Module):\n    \"\"\" Swin Transformer backbone.\n        A PyTorch impl of : `Swin Transformer: Hierarchical Vision Transformer using Shifted Windows`  -\n          https://arxiv.org/pdf/2103.14030\n    Args:\n        pretrain_img_size (int): Input image size for training the pretrained model,\n            used in absolute postion embedding. Default 224.\n        patch_size (int | tuple(int)): Patch size. Default: 4.\n        in_chans (int): Number of input image channels. Default: 3.\n        embed_dim (int): Number of linear projection output channels. Default: 96.\n        depths (tuple[int]): Depths of each Swin Transformer stage.\n        num_heads (tuple[int]): Number of attention head of each stage.\n        window_size (int): Window size. Default: 7.\n        mlp_ratio (float): Ratio of mlp hidden dim to embedding dim. Default: 4.\n        qkv_bias (bool): If True, add a learnable bias to query, key, value. Default: True\n        qk_scale (float): Override default qk scale of head_dim ** -0.5 if set.\n        drop_rate (float): Dropout rate.\n        attn_drop_rate (float): Attention dropout rate. Default: 0.\n        drop_path_rate (float): Stochastic depth rate. Default: 0.2.\n        norm_layer (nn.Module): Normalization layer. Default: nn.LayerNorm.\n        ape (bool): If True, add absolute position embedding to the patch embedding. Default: False.\n        patch_norm (bool): If True, add normalization after patch embedding. Default: True.\n        out_indices (Sequence[int]): Output from which stages.\n        frozen_stages (int): Stages to be frozen (stop grad and set eval mode).\n            -1 means not freezing any parameters.\n        use_checkpoint (bool): Whether to use checkpointing to save memory. Default: False.\n    \"\"\"\n    def __init__(self,\n                 pretrain_img_size=224,\n                 patch_size=4,\n                 in_chans=3,\n                 embed_dim=96,\n                 depths=[2, 2, 6, 2],\n                 num_heads=[3, 6, 12, 24],\n                 window_size=7,\n                 mlp_ratio=4.,\n                 qkv_bias=True,\n                 qk_scale=None,\n                 drop_rate=0.,\n                 attn_drop_rate=0.,\n                 drop_path_rate=0.2,\n                 norm_layer=nn.LayerNorm,\n                 ape=False,\n                 patch_norm=True,\n                 out_indices=(0, 1, 2),\n                 frozen_stages=-1,\n                 use_checkpoint=False):\n        super().__init__()\n\n        self.pretrain_img_size = pretrain_img_size\n        self.num_layers = len(depths) - 1  # remove the last stage\n        self.embed_dim = embed_dim\n        self.ape = ape\n        self.patch_norm = patch_norm\n        self.out_indices = out_indices\n        self.frozen_stages = frozen_stages\n\n        # split image into non-overlapping patches\n        self.patch_embed = PatchEmbed(\n            patch_size=patch_size,\n            in_chans=in_chans,\n            embed_dim=embed_dim,\n            norm_layer=norm_layer if self.patch_norm else None)\n\n        # absolute position embedding\n        if self.ape:\n            pretrain_img_size = to_2tuple(pretrain_img_size)\n            patch_size = to_2tuple(patch_size)\n            patches_resolution = [\n                pretrain_img_size[0] // patch_size[0],\n                pretrain_img_size[1] // patch_size[1]\n            ]\n\n            self.absolute_pos_embed = nn.Parameter(\n                torch.zeros(1, embed_dim, patches_resolution[0],\n                            patches_resolution[1]))\n            trunc_normal_(self.absolute_pos_embed, std=.02)\n\n        self.pos_drop = nn.Dropout(p=drop_rate)\n\n        # stochastic depth\n        dpr = [\n            x.item() for x in torch.linspace(0, drop_path_rate, sum(depths))\n        ]  # stochastic depth decay rule\n\n        # build layers\n        self.layers = nn.ModuleList()\n        for i_layer in range(self.num_layers):\n            layer = BasicLayer(\n                dim=int(embed_dim * 2**i_layer),\n                depth=depths[i_layer],\n                num_heads=num_heads[i_layer],\n                window_size=window_size,\n                mlp_ratio=mlp_ratio,\n                qkv_bias=qkv_bias,\n                qk_scale=qk_scale,\n                drop=drop_rate,\n                attn_drop=attn_drop_rate,\n                drop_path=dpr[sum(depths[:i_layer]):sum(depths[:i_layer + 1])],\n                norm_layer=norm_layer,\n                downsample=PatchMerging if\n                (i_layer < self.num_layers - 1) else None,\n                use_checkpoint=use_checkpoint)\n            self.layers.append(layer)\n\n        num_features = [int(embed_dim * 2**i) for i in range(self.num_layers)]\n        self.num_features = num_features\n\n        # add a norm layer for each output\n        for i_layer in out_indices:\n            layer = norm_layer(num_features[i_layer])\n            layer_name = f'norm{i_layer}'\n            self.add_module(layer_name, layer)\n\n        self._freeze_stages()\n\n    def _freeze_stages(self):\n        if self.frozen_stages >= 0:\n            self.patch_embed.eval()\n            for param in self.patch_embed.parameters():\n                param.requires_grad = False\n\n        if self.frozen_stages >= 1 and self.ape:\n            self.absolute_pos_embed.requires_grad = False\n\n        if self.frozen_stages >= 2:\n            self.pos_drop = nn.Identity()\n            for i in range(0, self.frozen_stages - 1):\n                m = self.layers[i]\n                for block in m.blocks:\n                    block.drop_path = nn.Identity()\n                    block.attn.attn_drop = nn.Identity()\n                    block.attn.proj_drop = nn.Identity()\n                for param in m.parameters():\n                    param.requires_grad = False\n            if m.downsample is not None:\n                for param in m.downsample.parameters():\n                    param.requires_grad = True\n\n    def init_weights(self, pretrained=None):\n        \"\"\"Initialize the weights in backbone.\n        Args:\n            pretrained (str, optional): Path to pre-trained weights.\n                Defaults to None.\n        \"\"\"\n        def _init_weights(m):\n            if isinstance(m, nn.Linear):\n                trunc_normal_(m.weight, std=.02)\n                if isinstance(m, nn.Linear) and m.bias is not None:\n                    nn.init.constant_(m.bias, 0)\n            elif isinstance(m, nn.LayerNorm):\n                nn.init.constant_(m.bias, 0)\n                nn.init.constant_(m.weight, 1.0)\n\n        if isinstance(pretrained, str):\n            self.apply(_init_weights)\n            # logger = get_root_logger()\n            # load_checkpoint(self, pretrained, strict=False, logger=logger)\n        elif pretrained is None:\n            self.apply(_init_weights)\n        else:\n            raise TypeError('pretrained must be a str or None')\n\n    def forward(self, x):\n        \"\"\"Forward function.\"\"\"\n        x = self.patch_embed(x)\n\n        Wh, Ww = x.size(2), x.size(3)\n        if self.ape:\n            # interpolate the position embedding to the corresponding size\n            absolute_pos_embed = F.interpolate(self.absolute_pos_embed,\n                                               size=(Wh, Ww),\n                                               mode='bicubic')\n            x = (x + absolute_pos_embed).flatten(2).transpose(1,\n                                                              2)  # B Wh*Ww C\n        else:\n            x = x.flatten(2).transpose(1, 2)\n        x = self.pos_drop(x)\n\n        outs = []\n        for i in range(self.num_layers):\n            layer = self.layers[i]\n            x_out, H, W, x, Wh, Ww = layer(x, Wh, Ww)\n\n            if i in self.out_indices:\n                norm_layer = getattr(self, f'norm{i}')\n                x_out = norm_layer(x_out)\n\n                out = x_out.view(-1, H, W,\n                                 self.num_features[i]).permute(0, 3, 1,\n                                                               2).contiguous()\n                outs.append(out)\n\n        outs.append(outs[-1])\n\n        return outs\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/engines/__init__.py",
    "content": "from detectron2.aot_modules.engines.aot_engine import AOTEngine, AOTInferEngine\n\n\ndef build_engine(name, phase='train', **kwargs):\n    if name == 'aotengine':\n        if phase == 'train':\n            return AOTEngine(**kwargs)\n        elif phase == 'eval':\n            return AOTInferEngine(**kwargs)\n        else:\n            raise NotImplementedError\n    else:\n        raise NotImplementedError\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/engines/aot_engine.py",
    "content": "import torch\nimport torch.nn as nn\nimport torch.nn.functional as F\n\nimport numpy as np\nfrom typing import Dict,List\n\nfrom detectron2.aot_modules.utils.math import generate_permute_matrix\nfrom detectron2.aot_modules.utils.image import one_hot_mask\n\nfrom detectron2.aot_modules.layers.basic import seq_to_2d\n\n\nclass AOTEngine(nn.Module):\n    def __init__(self,\n                 aot_model,\n                 gpu_id=0,\n                 long_term_mem_gap=9999,\n                 short_term_mem_skip=1):\n        super().__init__()\n\n        self.cfg = aot_model.cfg\n        self.align_corners = aot_model.cfg.MODEL_ALIGN_CORNERS\n        self.AOT = aot_model\n\n        self.max_obj_num = aot_model.max_obj_num\n        self.gpu_id = gpu_id\n        self.long_term_mem_gap = long_term_mem_gap\n        self.short_term_mem_skip = short_term_mem_skip\n        self.losses = None\n\n        self.restart_engine()\n\n    def forward(self,\n                all_frames,\n                all_masks,\n                batch_size,\n                obj_nums,\n                step=0,\n                tf_board=False,\n                use_prev_pred=False,\n                enable_prev_frame=False,\n                use_prev_prob=False):  # only used for training\n        if self.losses is None:\n            self._init_losses()\n\n        self.freeze_id = True if use_prev_pred else False\n        aux_weight = self.aux_weight * max(self.aux_step - step,\n                                           0.) / self.aux_step\n\n        self.offline_encoder(all_frames, all_masks)\n\n        self.add_reference_frame(frame_step=0, obj_nums=obj_nums)\n\n        grad_state = torch.no_grad if aux_weight == 0 else torch.enable_grad\n        with grad_state():\n            ref_aux_loss, ref_aux_mask = self.generate_loss_mask(\n                self.offline_masks[self.frame_step], step)\n\n        aux_losses = [ref_aux_loss]\n        aux_masks = [ref_aux_mask]\n\n        curr_losses, curr_masks = [], []\n        if enable_prev_frame:\n            self.set_prev_frame(frame_step=1)\n            with grad_state():\n                prev_aux_loss, prev_aux_mask = self.generate_loss_mask(\n                    self.offline_masks[self.frame_step], step)\n            aux_losses.append(prev_aux_loss)\n            aux_masks.append(prev_aux_mask)\n        else:\n            self.match_propogate_one_frame()\n            curr_loss, curr_mask, curr_prob = self.generate_loss_mask(\n                self.offline_masks[self.frame_step], step, return_prob=True)\n            self.update_short_term_memory(\n                curr_mask if not use_prev_prob else curr_prob,\n                None if use_prev_pred else self.assign_identity(\n                    self.offline_one_hot_masks[self.frame_step]))\n            curr_losses.append(curr_loss)\n            curr_masks.append(curr_mask)\n\n        self.match_propogate_one_frame()\n        curr_loss, curr_mask, curr_prob = self.generate_loss_mask(\n            self.offline_masks[self.frame_step], step, return_prob=True)\n        curr_losses.append(curr_loss)\n        curr_masks.append(curr_mask)\n        for _ in range(self.total_offline_frame_num - 3):\n            self.update_short_term_memory(\n                curr_mask if not use_prev_prob else curr_prob,\n                None if use_prev_pred else self.assign_identity(\n                    self.offline_one_hot_masks[self.frame_step]))\n            self.match_propogate_one_frame()\n            curr_loss, curr_mask, curr_prob = self.generate_loss_mask(\n                self.offline_masks[self.frame_step], step, return_prob=True)\n            curr_losses.append(curr_loss)\n            curr_masks.append(curr_mask)\n\n        aux_loss = torch.cat(aux_losses, dim=0).mean(dim=0)\n        pred_loss = torch.cat(curr_losses, dim=0).mean(dim=0)\n\n        loss = aux_weight * aux_loss + pred_loss\n\n        all_pred_mask = aux_masks + curr_masks\n\n        all_frame_loss = aux_losses + curr_losses\n\n        boards = {'image': {}, 'scalar': {}} # type:Dict[str,Dict[str,List]]\n\n        return loss, all_pred_mask, all_frame_loss, boards\n\n    def _init_losses(self):\n        cfg = self.cfg\n\n        from networks.layers.loss import CrossEntropyLoss, SoftJaccordLoss\n        bce_loss = CrossEntropyLoss(\n            cfg.TRAIN_TOP_K_PERCENT_PIXELS,\n            cfg.TRAIN_HARD_MINING_RATIO * cfg.TRAIN_TOTAL_STEPS)\n        iou_loss = SoftJaccordLoss()\n\n        losses = [bce_loss, iou_loss]\n        loss_weights = [0.5, 0.5]\n\n        self.losses = nn.ModuleList(losses)\n        self.loss_weights = loss_weights\n        self.aux_weight = cfg.TRAIN_AUX_LOSS_WEIGHT\n        self.aux_step = cfg.TRAIN_TOTAL_STEPS * cfg.TRAIN_AUX_LOSS_RATIO + 1e-5\n\n    def encode_one_img_mask(self, img=None, mask=None, frame_step=-1):\n        if frame_step == -1:\n            frame_step = self.frame_step\n\n        if self.enable_offline_enc:\n            curr_enc_embs = self.offline_enc_embs[frame_step]\n        elif img is None:\n            curr_enc_embs = None\n        else:\n            curr_enc_embs = self.AOT.encode_image(img)\n\n        if mask is not None:\n            curr_one_hot_mask = one_hot_mask(mask, self.max_obj_num)\n        elif self.enable_offline_enc:\n            curr_one_hot_mask = self.offline_one_hot_masks[frame_step]\n        else:\n            curr_one_hot_mask = None\n\n        return curr_enc_embs, curr_one_hot_mask\n\n    def offline_encoder(self, all_frames, all_masks=None):\n        self.enable_offline_enc = True\n        self.offline_frames = all_frames.size(0) // self.batch_size\n\n        # extract backbone features\n        self.offline_enc_embs = self.split_frames(\n            self.AOT.encode_image(all_frames), self.batch_size)\n        self.total_offline_frame_num = len(self.offline_enc_embs)\n\n        if all_masks is not None:\n            # extract mask embeddings\n            offline_one_hot_masks = one_hot_mask(all_masks, self.max_obj_num)\n            self.offline_masks = list(\n                torch.split(all_masks, self.batch_size, dim=0))\n            self.offline_one_hot_masks = list(\n                torch.split(offline_one_hot_masks, self.batch_size, dim=0))\n\n        if self.input_size_2d is None:\n            self.update_size(all_frames.size()[2:],\n                             self.offline_enc_embs[0][-1].size()[2:])\n\n    def assign_identity(self, one_hot_mask):\n        if self.enable_id_shuffle:\n            one_hot_mask = torch.einsum('bohw,bot->bthw', one_hot_mask,\n                                        self.id_shuffle_matrix)\n\n        id_emb = self.AOT.get_id_emb(one_hot_mask).view(\n            self.batch_size, -1, self.enc_hw).permute(2, 0, 1)\n\n        if self.training and self.freeze_id:\n            id_emb = id_emb.detach()\n\n        return id_emb\n\n    def split_frames(self, xs, chunk_size):\n        new_xs = []\n        for x in xs:\n            all_x = list(torch.split(x, chunk_size, dim=0))\n            new_xs.append(all_x)\n        return list(zip(*new_xs))\n    # ---------------------------------------\n    def add_reference_frame(self,\n                            img=None,\n                            mask=None,\n                            frame_step=-1,\n                            obj_nums=None,\n                            img_embs=None):\n        if self.obj_nums is None and obj_nums is None:\n            print('No objects for reference frame!')\n            exit()\n        elif obj_nums is not None:\n            self.obj_nums = obj_nums # 该序列中有多少 obj 44\n\n        if frame_step == -1:\n            frame_step = self.frame_step # 0\n\n        if img_embs is None: # 将第一帧 img 和 mask进行编码\n            curr_enc_embs, curr_one_hot_mask = self.encode_one_img_mask(\n                img, mask, frame_step)\n        else:\n            _, curr_one_hot_mask = self.encode_one_img_mask(\n                None, mask, frame_step)\n            curr_enc_embs = img_embs\n\n        if curr_enc_embs is None:\n            print('No image for reference frame!')\n            exit()\n\n        if curr_one_hot_mask is None:\n            print('No mask for reference frame!')\n            exit()\n\n        if self.input_size_2d is None:\n            self.update_size(img.size()[2:], curr_enc_embs[-1].size()[2:])\n\n        self.curr_enc_embs = curr_enc_embs  # r50, 4个 1/4，1/8，1/16，1/16\n        self.curr_one_hot_mask = curr_one_hot_mask # 1x11x321x1041\n\n        if self.pos_emb is None:\n            self.pos_emb = self.AOT.get_pos_emb(curr_enc_embs[-1]).expand(\n                self.batch_size, -1, -1,\n                -1).view(self.batch_size, -1, self.enc_hw).permute(2, 0, 1)\n\n        curr_id_emb = self.assign_identity(curr_one_hot_mask)\n        self.curr_id_embs = curr_id_emb\n\n        # print(curr_enc_embs[0].shape, img.shape) # 1x256x81x261, 1x3x321x1041\n        # print(curr_one_hot_mask.shape) # 1x11x321x1041, (一个engin 10张图)\n        # print(curr_id_emb.shape) # 1386x1x256\n        # print(self.pos_emb.shape) # 1386x1x256\n        # print(\"----------------------------------\")\n\n        # self matching and propagation\n        self.curr_lstt_output = self.AOT.LSTT_forward(curr_enc_embs,\n                                                      None,\n                                                      None,\n                                                      curr_id_emb,\n                                                      pos_emb=self.pos_emb,\n                                                      size_2d=self.enc_size_2d)\n\n        lstt_embs, lstt_curr_memories, lstt_long_memories, lstt_short_memories = self.curr_lstt_output\n\n        if self.long_term_memories is None:\n            self.long_term_memories = lstt_long_memories\n        else:\n            self.update_long_term_memory(lstt_long_memories)\n        self.last_mem_step = frame_step\n\n        self.short_term_memories_list = [lstt_short_memories]\n        self.short_term_memories = lstt_short_memories\n\n    def set_prev_frame(self, img=None, mask=None, frame_step=1):\n        self.frame_step = frame_step\n        curr_enc_embs, curr_one_hot_mask = self.encode_one_img_mask(\n            img, mask, frame_step)\n\n        if curr_enc_embs is None:\n            print('No image for previous frame!')\n            exit()\n\n        if curr_one_hot_mask is None:\n            print('No mask for previous frame!')\n            exit()\n\n        self.curr_enc_embs = curr_enc_embs\n        self.curr_one_hot_mask = curr_one_hot_mask\n\n        curr_id_emb = self.assign_identity(curr_one_hot_mask)\n        self.curr_id_embs = curr_id_emb\n\n        # self matching and propagation\n        self.curr_lstt_output = self.AOT.LSTT_forward(curr_enc_embs,\n                                                      None,\n                                                      None,\n                                                      curr_id_emb,\n                                                      pos_emb=self.pos_emb,\n                                                      size_2d=self.enc_size_2d)\n\n        lstt_embs, lstt_curr_memories, lstt_long_memories, lstt_short_memories = self.curr_lstt_output\n\n        if self.long_term_memories is None:\n            self.long_term_memories = lstt_long_memories\n        else:\n            self.update_long_term_memory(lstt_long_memories)\n        self.last_mem_step = frame_step\n\n        self.short_term_memories_list = [lstt_short_memories]\n        self.short_term_memories = lstt_short_memories\n\n    def update_long_term_memory(self, new_long_term_memories):\n        updated_long_term_memories = []\n        for new_long_term_memory, last_long_term_memory in zip(\n                new_long_term_memories, self.long_term_memories):\n            updated_e = []\n            for new_e, last_e in zip(new_long_term_memory,\n                                     last_long_term_memory):\n                updated_e.append(torch.cat([new_e, last_e], dim=0))\n            updated_long_term_memories.append(updated_e)\n        self.long_term_memories = updated_long_term_memories\n\n    def update_short_term_memory(self, curr_mask, curr_id_emb=None):\n        if curr_id_emb is None:\n            if len(curr_mask.size()) == 3 or curr_mask.size()[0] == 1:\n                curr_one_hot_mask = one_hot_mask(curr_mask, self.max_obj_num)\n            else:\n                curr_one_hot_mask = curr_mask\n            curr_id_emb = self.assign_identity(curr_one_hot_mask)\n\n        lstt_curr_memories = self.curr_lstt_output[1]\n        lstt_curr_memories_2d = []\n        for layer_idx in range(len(lstt_curr_memories)):\n            curr_v = lstt_curr_memories[layer_idx][1]\n            curr_v = self.AOT.LSTT.layers[layer_idx].linear_V(curr_v +\n                                                              curr_id_emb)\n            lstt_curr_memories[layer_idx][1] = curr_v\n            lstt_curr_memories_2d.append([\n                seq_to_2d(lstt_curr_memories[layer_idx][0], self.enc_size_2d),\n                seq_to_2d(lstt_curr_memories[layer_idx][1], self.enc_size_2d)\n            ])\n\n        self.short_term_memories_list.append(lstt_curr_memories_2d)\n        self.short_term_memories_list = self.short_term_memories_list[\n            -self.short_term_mem_skip:]\n        self.short_term_memories = self.short_term_memories_list[0]\n\n        if self.frame_step - self.last_mem_step >= self.long_term_mem_gap:\n            self.update_long_term_memory(lstt_curr_memories)\n            self.last_mem_step = self.frame_step\n        print(len(self.short_term_memories), len(self.long_term_memories)) #3 , 3\n\n    # ---------------------------------------\n    def match_propogate_one_frame(self, img=None, img_embs=None):\n        self.frame_step += 1 # 控制当前进行到第几帧\n        if img_embs is None:\n            curr_enc_embs, _ = self.encode_one_img_mask(\n                img, None, self.frame_step)\n        else:\n            curr_enc_embs = img_embs\n        self.curr_enc_embs = curr_enc_embs\n\n        self.curr_lstt_output = self.AOT.LSTT_forward(curr_enc_embs,\n                                                      self.long_term_memories,\n                                                      self.short_term_memories,\n                                                      None,\n                                                      pos_emb=self.pos_emb,\n                                                      size_2d=self.enc_size_2d)\n\n    def decode_current_logits(self, output_size=None):\n        curr_enc_embs = self.curr_enc_embs # 4 fpn\n        curr_lstt_embs = self.curr_lstt_output[0]\n\n        # print(curr_enc_embs[0].shape, curr_enc_embs[1].shape, curr_enc_embs[2].shape, curr_enc_embs[3].shape) \n        # # 1x256x81x261 1x512x41x131, 1x1024x21x66, 1x256x21x66\n        # print(curr_lstt_embs[0].shape) # 1386x1x256\n        pred_id_logits = self.AOT.decode_id_logits(curr_lstt_embs,\n                                                   curr_enc_embs)\n        # print(\"pred id logits:\", pred_id_logits.shape) # 1x11x81x261\n        if self.enable_id_shuffle:  # reverse shuffle\n            pred_id_logits = torch.einsum('bohw,bto->bthw', pred_id_logits,\n                                          self.id_shuffle_matrix)\n\n        # remove unused identities\n        for batch_idx, obj_num in enumerate(self.obj_nums):\n            pred_id_logits[batch_idx, (obj_num+1):] = - \\\n                1e+10 if pred_id_logits.dtype == torch.float32 else -1e+4\n\n        self.pred_id_logits = pred_id_logits\n\n        if output_size is not None:\n            pred_id_logits = F.interpolate(pred_id_logits,\n                                           size=output_size,\n                                           mode=\"bilinear\",\n                                           align_corners=self.align_corners)\n\n        return pred_id_logits\n\n    def predict_current_mask(self, output_size=None, return_prob=False):\n        if output_size is None:\n            output_size = self.input_size_2d\n\n        pred_id_logits = F.interpolate(self.pred_id_logits,\n                                       size=output_size,\n                                       mode=\"bilinear\",\n                                       align_corners=self.align_corners)\n        pred_mask = torch.argmax(pred_id_logits, dim=1)\n\n        if not return_prob:\n            return pred_mask\n        else:\n            pred_prob = torch.softmax(pred_id_logits, dim=1)\n            return pred_mask, pred_prob\n\n    def calculate_current_loss(self, gt_mask, step):\n        pred_id_logits = self.pred_id_logits\n\n        pred_id_logits = F.interpolate(pred_id_logits,\n                                       size=gt_mask.size()[-2:],\n                                       mode=\"bilinear\",\n                                       align_corners=self.align_corners)\n\n        label_list = []\n        logit_list = []\n        for batch_idx, obj_num in enumerate(self.obj_nums):\n            now_label = gt_mask[batch_idx].long()\n            now_logit = pred_id_logits[batch_idx, :(obj_num + 1)].unsqueeze(0)\n            label_list.append(now_label.long())\n            logit_list.append(now_logit)\n\n        total_loss = 0\n        for loss, loss_weight in zip(self.losses, self.loss_weights):\n            total_loss = total_loss + loss_weight * \\\n                loss(logit_list, label_list, step)\n\n        return total_loss\n\n    def generate_loss_mask(self, gt_mask, step, return_prob=False):\n        self.decode_current_logits()\n        loss = self.calculate_current_loss(gt_mask, step)\n        if return_prob:\n            mask, prob = self.predict_current_mask(return_prob=True)\n            return loss, mask, prob\n        else:\n            mask = self.predict_current_mask()\n            return loss, mask\n\n    def keep_gt_mask(self, pred_mask, keep_prob=0.2):\n        pred_mask = pred_mask.float()\n        gt_mask = self.offline_masks[self.frame_step].float().squeeze(1)\n\n        shape = [1 for _ in range(pred_mask.ndim)]\n        shape[0] = self.batch_size\n        random_tensor = keep_prob + torch.rand(\n            shape, dtype=pred_mask.dtype, device=pred_mask.device)\n        random_tensor.floor_()  # binarize\n\n        pred_mask = pred_mask * (1 - random_tensor) + gt_mask * random_tensor\n\n        return pred_mask\n\n    def restart_engine(self, batch_size=1, enable_id_shuffle=False):\n\n        self.batch_size = batch_size\n        self.frame_step = 0\n        self.last_mem_step = -1\n        self.enable_id_shuffle = enable_id_shuffle\n        self.freeze_id = False\n\n        self.obj_nums = None\n        self.pos_emb = None\n        self.enc_size_2d = None\n        self.enc_hw = None\n        self.input_size_2d = None\n\n        self.long_term_memories = None\n        self.short_term_memories_list = []\n        self.short_term_memories = None\n\n        self.enable_offline_enc = False\n        self.offline_enc_embs = None\n        self.offline_one_hot_masks = None\n        self.offline_frames = -1\n        self.total_offline_frame_num = 0\n\n        self.curr_enc_embs = None\n        self.curr_memories = None\n        self.curr_id_embs = None\n\n        if enable_id_shuffle:\n            self.id_shuffle_matrix = generate_permute_matrix(\n                self.max_obj_num + 1, batch_size, gpu_id=self.gpu_id)\n        else:\n            self.id_shuffle_matrix = None\n\n    def update_size(self, input_size, enc_size):\n        self.input_size_2d = input_size\n        self.enc_size_2d = enc_size\n        self.enc_hw = self.enc_size_2d[0] * self.enc_size_2d[1]\n\n\nclass AOTInferEngine(nn.Module):\n    def __init__(self,\n                 aot_model,\n                 gpu_id=0,\n                 long_term_mem_gap=9999,\n                 short_term_mem_skip=1,\n                 max_aot_obj_num=None):\n        super().__init__()\n\n        self.cfg = aot_model.cfg\n        self.AOT = aot_model\n\n        if max_aot_obj_num is None or max_aot_obj_num > aot_model.max_obj_num: # aot_model.max_obj_num:10\n            self.max_aot_obj_num = aot_model.max_obj_num\n        else:\n            self.max_aot_obj_num = max_aot_obj_num\n\n        self.gpu_id = gpu_id\n        self.long_term_mem_gap = long_term_mem_gap\n        self.short_term_mem_skip = short_term_mem_skip\n\n        self.aot_engines = []\n\n        self.restart_engine()\n\n    def restart_engine(self):\n        self.aot_engines = []\n        self.obj_nums = None\n\n    def separate_mask(self, mask):\n        if mask is None:\n            return [None] * len(self.aot_engines)\n        if len(self.aot_engines) == 1:\n            return [mask]\n\n        if len(mask.size()) == 3 or mask.size()[0] == 1:\n            separated_masks = []\n            for idx in range(len(self.aot_engines)):\n                start_id = idx * self.max_aot_obj_num + 1\n                end_id = (idx + 1) * self.max_aot_obj_num\n                fg_mask = ((mask >= start_id) & (mask <= end_id)).float()\n                separated_mask = (fg_mask * mask - start_id + 1) * fg_mask\n                separated_masks.append(separated_mask)\n            return separated_masks\n        else:\n            prob = mask\n            separated_probs = []\n            for idx in range(len(self.aot_engines)):\n                start_id = idx * self.max_aot_obj_num + 1\n                end_id = (idx + 1) * self.max_aot_obj_num\n                fg_prob = prob[start_id:(end_id + 1)]\n                bg_prob = 1. - torch.sum(fg_prob, dim=1, keepdim=True)\n                separated_probs.append(torch.cat([bg_prob, fg_prob], dim=1))\n            return separated_probs\n\n    def min_logit_aggregation(self, all_logits):\n        if len(all_logits) == 1:\n            return all_logits[0]\n\n        fg_logits = []\n        bg_logits = []\n\n        for logit in all_logits:\n            bg_logits.append(logit[:, 0:1])\n            fg_logits.append(logit[:, 1:1 + self.max_aot_obj_num])\n\n        bg_logit, _ = torch.min(torch.cat(bg_logits, dim=1),\n                                dim=1,\n                                keepdim=True)\n        merged_logit = torch.cat([bg_logit] + fg_logits, dim=1)\n\n        return merged_logit\n\n    def soft_logit_aggregation(self, all_logits):\n        if len(all_logits) == 1:\n            return all_logits[0]\n\n        fg_probs = []\n        bg_probs = []\n\n        for logit in all_logits:\n            prob = torch.softmax(logit, dim=1)\n            bg_probs.append(prob[:, 0:1])\n            fg_probs.append(prob[:, 1:1 + self.max_aot_obj_num])\n\n        bg_prob = torch.prod(torch.cat(bg_probs, dim=1), dim=1, keepdim=True)\n        merged_prob = torch.cat([bg_prob] + fg_probs,\n                                dim=1).clamp(1e-5, 1 - 1e-5)\n        merged_logit = torch.logit(merged_prob)\n\n        return merged_logit\n\n    def add_reference_frame(self, img, mask, obj_nums, frame_step=-1):\n        if isinstance(obj_nums, list):\n            obj_nums = obj_nums[0]\n        aot_num = max(np.ceil(obj_nums / self.max_aot_obj_num), 1) # 分成多个 engine 并行加快速度\n        # print(obj_nums, self.max_aot_obj_num, aot_num) # 44,10,5\n        while (aot_num > len(self.aot_engines)):\n            new_engine = AOTEngine(self.AOT, self.gpu_id,\n                                   self.long_term_mem_gap,\n                                   self.short_term_mem_skip)\n            new_engine.eval()\n            self.aot_engines.append(new_engine)\n\n        separated_masks = self.separate_mask(mask)\n        img_embs = None\n        for aot_engine, separated_mask in zip(self.aot_engines,\n                                              separated_masks):\n            aot_engine.add_reference_frame(img,\n                                           separated_mask,\n                                           obj_nums=[self.max_aot_obj_num],\n                                           frame_step=frame_step,\n                                           img_embs=img_embs)\n            if img_embs is None:  # reuse image embeddings\n                img_embs = aot_engine.curr_enc_embs\n\n        self.update_size()\n\n    def match_propogate_one_frame(self, img=None):\n        img_embs = None\n        for aot_engine in self.aot_engines:\n            aot_engine.match_propogate_one_frame(img, img_embs=img_embs)\n            if img_embs is None:  # reuse image embeddings\n                img_embs = aot_engine.curr_enc_embs\n\n    def decode_current_logits(self, output_size=None):\n        all_logits = []\n        for aot_engine in self.aot_engines:\n            all_logits.append(aot_engine.decode_current_logits(output_size))\n        pred_id_logits = self.soft_logit_aggregation(all_logits)\n        return pred_id_logits\n\n    def update_memory(self, curr_mask):\n        separated_masks = self.separate_mask(curr_mask)\n        for aot_engine, separated_mask in zip(self.aot_engines,\n                                              separated_masks):\n            aot_engine.update_short_term_memory(separated_mask)\n\n    def update_size(self):\n        self.input_size_2d = self.aot_engines[0].input_size_2d\n        self.enc_size_2d = self.aot_engines[0].enc_size_2d\n        self.enc_hw = self.aot_engines[0].enc_hw\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/layers/__init__.py",
    "content": ""
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/layers/attention.py",
    "content": "import torch\nimport torch.nn as nn\nimport torch.nn.functional as F\nfrom detectron2.aot_modules.layers.basic import DropOutLogit\n\n\n# Long-term attention\nclass MultiheadAttention(nn.Module):\n    def __init__(self, d_model, num_head=8, dropout=0., use_linear=True):\n        super().__init__()\n        self.d_model = d_model\n        self.num_head = num_head\n\n        self.hidden_dim = d_model // num_head\n        self.T = (d_model / num_head)**0.5\n        self.use_linear = use_linear\n\n        if use_linear:\n            self.linear_Q = nn.Linear(d_model, d_model)\n            self.linear_K = nn.Linear(d_model, d_model)\n            self.linear_V = nn.Linear(d_model, d_model)\n\n        self.dropout = nn.Dropout(dropout)\n        self.drop_prob = dropout\n        self.projection = nn.Linear(d_model, d_model)\n        self._init_weight()\n\n    def forward(self, Q, K, V):\n        \"\"\"\n        :param Q: A 3d tensor with shape of [T_q, bs, C_q]\n        :param K: A 3d tensor with shape of [T_k, bs, C_k]\n        :param V: A 3d tensor with shape of [T_v, bs, C_v]\n        \"\"\"\n        num_head = self.num_head\n        hidden_dim = self.hidden_dim\n\n        bs = Q.size()[1]\n\n        # Linear projections\n        if self.use_linear:\n            Q = self.linear_Q(Q)\n            K = self.linear_K(K)\n            V = self.linear_V(V)\n\n        # Scale\n        Q = Q / self.T\n\n        # Multi-head\n        Q = Q.view(-1, bs, num_head, hidden_dim).permute(1, 2, 0, 3)\n        K = K.view(-1, bs, num_head, hidden_dim).permute(1, 2, 3, 0)\n        V = V.view(-1, bs, num_head, hidden_dim).permute(1, 2, 0, 3)\n\n        # Multiplication\n        QK = Q @ K\n\n        # Activation\n        attn = torch.softmax(QK, dim=-1)\n\n        # Dropouts\n        attn = self.dropout(attn)\n\n        # Weighted sum\n        outputs = (attn @ V).permute(2, 0, 1, 3)\n\n        # Restore shape\n        outputs = outputs.reshape(-1, bs, self.d_model)\n\n        outputs = self.projection(outputs)\n\n        return outputs, attn\n\n    def _init_weight(self):\n        for p in self.parameters():\n            if p.dim() > 1:\n                nn.init.xavier_uniform_(p)\n\n\n# Short-term attention\nclass MultiheadLocalAttentionV1(nn.Module):\n    def __init__(self,\n                 d_model,\n                 num_head,\n                 dropout=0.,\n                 max_dis=7,\n                 dilation=1,\n                 use_linear=True,\n                 enable_corr=True):\n        super().__init__()\n        self.dilation = dilation\n        self.window_size = 2 * max_dis + 1\n        self.max_dis = max_dis\n        self.num_head = num_head\n        self.T = ((d_model / num_head)**0.5)\n\n        self.use_linear = use_linear\n        if use_linear:\n            self.linear_Q = nn.Conv2d(d_model, d_model, kernel_size=1)\n            self.linear_K = nn.Conv2d(d_model, d_model, kernel_size=1)\n            self.linear_V = nn.Conv2d(d_model, d_model, kernel_size=1)\n\n        self.relative_emb_k = nn.Conv2d(d_model,\n                                        num_head * self.window_size *\n                                        self.window_size,\n                                        kernel_size=1,\n                                        groups=num_head)\n        self.relative_emb_v = nn.Parameter(\n            torch.zeros([\n                self.num_head, d_model // self.num_head,\n                self.window_size * self.window_size\n            ]))\n\n        self.enable_corr = enable_corr\n\n        if enable_corr:\n            from spatial_correlation_sampler import SpatialCorrelationSampler\n            self.correlation_sampler = SpatialCorrelationSampler(\n                kernel_size=1,\n                patch_size=self.window_size,\n                stride=1,\n                padding=0,\n                dilation=1,\n                dilation_patch=self.dilation)\n\n        self.projection = nn.Linear(d_model, d_model)\n\n        self.dropout = nn.Dropout(dropout)\n        self.drop_prob = dropout\n\n    def forward(self, q, k, v):\n        n, c, h, w = v.size()\n\n        if self.use_linear:\n            q = self.linear_Q(q)\n            k = self.linear_K(k)\n            v = self.linear_V(v)\n\n        hidden_dim = c // self.num_head\n\n        relative_emb = self.relative_emb_k(q)\n        memory_mask = torch.ones((1, 1, h, w), device=v.device).float()\n\n        # Scale\n        q = q / self.T\n\n        q = q.view(-1, hidden_dim, h, w)\n        k = k.reshape(-1, hidden_dim, h, w).contiguous()\n        unfolded_v = self.pad_and_unfold(v).view(\n            n, self.num_head, hidden_dim, self.window_size * self.window_size,\n            h * w) + self.relative_emb_v.unsqueeze(0).unsqueeze(-1)\n\n        relative_emb = relative_emb.view(n, self.num_head,\n                                         self.window_size * self.window_size,\n                                         h * w)\n        unfolded_k_mask = self.pad_and_unfold(memory_mask).bool().view(\n            1, 1, self.window_size * self.window_size,\n            h * w).expand(n, self.num_head, -1, -1)\n\n        if self.enable_corr:\n            qk = self.correlation_sampler(q, k).view(\n                n, self.num_head, self.window_size * self.window_size,\n                h * w) + relative_emb\n        else:\n            unfolded_k = self.pad_and_unfold(k).view(\n                n * self.num_head, hidden_dim,\n                self.window_size * self.window_size, h, w)\n            qk = (q.unsqueeze(2) * unfolded_k).sum(dim=1).view(\n                n, self.num_head, self.window_size * self.window_size,\n                h * w) + relative_emb\n\n        qk_mask = 1 - unfolded_k_mask\n\n        qk -= qk_mask * 1e+8 if qk.dtype == torch.float32 else qk_mask * 1e+4\n\n        local_attn = torch.softmax(qk, dim=2)\n\n        local_attn = self.dropout(local_attn)\n\n        output = (local_attn.unsqueeze(2) * unfolded_v).sum(dim=3).permute(\n            3, 0, 1, 2).view(h * w, n, c)\n\n        output = self.projection(output)\n\n        return output, local_attn\n\n    def pad_and_unfold(self, x):\n        pad_pixel = self.max_dis * self.dilation\n        x = F.pad(x, (pad_pixel, pad_pixel, pad_pixel, pad_pixel),\n                  mode='constant',\n                  value=0)\n        x = F.unfold(x,\n                     kernel_size=(self.window_size, self.window_size),\n                     stride=(1, 1),\n                     dilation=self.dilation)\n        return x\n\n\nclass MultiheadLocalAttentionV2(nn.Module):\n    def __init__(self,\n                 d_model,\n                 num_head,\n                 dropout=0.,\n                 max_dis=7,\n                 dilation=1,\n                 use_linear=True,\n                 enable_corr=True):\n        super().__init__()\n        self.dilation = dilation\n        self.window_size = 2 * max_dis + 1\n        self.max_dis = max_dis\n        self.num_head = num_head\n        self.T = (d_model / num_head)**0.5\n\n        self.use_linear = use_linear\n        if use_linear:\n            self.linear_Q = nn.Conv2d(d_model, d_model, kernel_size=1)\n            self.linear_K = nn.Conv2d(d_model, d_model, kernel_size=1)\n            self.linear_V = nn.Conv2d(d_model, d_model, kernel_size=1)\n\n        self.relative_emb_k = nn.Conv2d(d_model,\n                                        num_head * self.window_size *\n                                        self.window_size,\n                                        kernel_size=1,\n                                        groups=num_head)\n        self.relative_emb_v = nn.Parameter(\n            torch.zeros([\n                self.num_head, d_model // self.num_head,\n                self.window_size * self.window_size\n            ]))\n\n        self.enable_corr = enable_corr\n\n        if enable_corr:\n            from spatial_correlation_sampler import SpatialCorrelationSampler\n            self.correlation_sampler = SpatialCorrelationSampler(\n                kernel_size=1,\n                patch_size=self.window_size,\n                stride=1,\n                padding=0,\n                dilation=1,\n                dilation_patch=self.dilation)\n\n        self.projection = nn.Linear(d_model, d_model)\n\n        self.dropout = nn.Dropout(dropout)\n\n        self.drop_prob = dropout\n\n        self.local_mask = None\n        self.last_size_2d = None\n        self.qk_mask = None\n\n    def forward(self, q, k, v):\n        n, c, h, w = v.size()\n\n        if self.use_linear:\n            q = self.linear_Q(q)\n            k = self.linear_K(k)\n            v = self.linear_V(v)\n\n        hidden_dim = c // self.num_head\n\n        if self.qk_mask is not None and (h, w) == self.last_size_2d:\n            qk_mask = self.qk_mask\n        else:\n            memory_mask = torch.ones((1, 1, h, w), device=v.device).float()\n            unfolded_k_mask = self.pad_and_unfold(memory_mask).view(\n                1, 1, self.window_size * self.window_size, h * w)\n            qk_mask = 1 - unfolded_k_mask\n            self.qk_mask = qk_mask\n\n        relative_emb = self.relative_emb_k(q)\n\n        # Scale\n        q = q / self.T\n\n        q = q.view(-1, hidden_dim, h, w)\n        k = k.view(-1, hidden_dim, h, w)\n        v = v.view(-1, self.num_head, hidden_dim, h * w)\n\n        relative_emb = relative_emb.view(n, self.num_head,\n                                         self.window_size * self.window_size,\n                                         h * w)\n\n        if self.enable_corr:\n            qk = self.correlation_sampler(q, k).view(\n                n, self.num_head, self.window_size * self.window_size,\n                h * w) + relative_emb\n        else:\n            unfolded_k = self.pad_and_unfold(k).view(\n                n * self.num_head, hidden_dim,\n                self.window_size * self.window_size, h, w)\n            qk = (q.unsqueeze(2) * unfolded_k).sum(dim=1).view(\n                n, self.num_head, self.window_size * self.window_size,\n                h * w) + relative_emb\n\n        qk -= qk_mask * 1e+8 if qk.dtype == torch.float32 else qk_mask * 1e+4\n\n        local_attn = torch.softmax(qk, dim=2)\n\n        local_attn = self.dropout(local_attn)\n\n        agg_bias = torch.einsum('bhwn,hcw->bhnc', local_attn,\n                                self.relative_emb_v)\n\n        global_attn = self.local2global(local_attn, h, w)\n\n        agg_value = (global_attn @ v.transpose(-2, -1))\n\n        output = (agg_value + agg_bias).permute(2, 0, 1,\n                                                3).reshape(h * w, n, c)\n\n        output = self.projection(output)\n\n        self.last_size_2d = (h, w)\n        return output, local_attn\n\n    def local2global(self, local_attn, height, width):\n        batch_size = local_attn.size()[0]\n\n        pad_height = height + 2 * self.max_dis\n        pad_width = width + 2 * self.max_dis\n\n        if self.local_mask is not None and (height,\n                                            width) == self.last_size_2d:\n            local_mask = self.local_mask\n        else:\n            ky, kx = torch.meshgrid([\n                torch.arange(0, pad_height, device=local_attn.device),\n                torch.arange(0, pad_width, device=local_attn.device)\n            ])\n            qy, qx = torch.meshgrid([\n                torch.arange(0, height, device=local_attn.device),\n                torch.arange(0, width, device=local_attn.device)\n            ])\n\n            offset_y = qy.reshape(-1, 1) - ky.reshape(1, -1) + self.max_dis\n            offset_x = qx.reshape(-1, 1) - kx.reshape(1, -1) + self.max_dis\n\n            local_mask = (offset_y.abs() <= self.max_dis) & (offset_x.abs() <=\n                                                             self.max_dis)\n            local_mask = local_mask.view(1, 1, height * width, pad_height,\n                                         pad_width)\n            self.local_mask = local_mask\n\n        global_attn = torch.zeros(\n            (batch_size, self.num_head, height * width, pad_height, pad_width),\n            device=local_attn.device)\n        global_attn[local_mask.expand(batch_size, self.num_head,\n                                      -1, -1, -1)] = local_attn.transpose(\n                                          -1, -2).reshape(-1)\n        global_attn = global_attn[:, :, :, self.max_dis:-self.max_dis,\n                                  self.max_dis:-self.max_dis].reshape(\n                                      batch_size, self.num_head,\n                                      height * width, height * width)\n\n        return global_attn\n\n    def pad_and_unfold(self, x):\n        pad_pixel = self.max_dis * self.dilation\n        x = F.pad(x, (pad_pixel, pad_pixel, pad_pixel, pad_pixel),\n                  mode='constant',\n                  value=0)\n        x = F.unfold(x,\n                     kernel_size=(self.window_size, self.window_size),\n                     stride=(1, 1),\n                     dilation=self.dilation)\n        return x\n\n\nclass MultiheadLocalAttentionV3(nn.Module):\n    def __init__(self,\n                 d_model,\n                 num_head,\n                 dropout=0.,\n                 max_dis=7,\n                 dilation=1,\n                 use_linear=True):\n        super().__init__()\n        self.dilation = dilation\n        self.window_size = 2 * max_dis + 1\n        self.max_dis = max_dis\n        self.num_head = num_head\n        self.T = ((d_model / num_head)**0.5)\n\n        self.use_linear = use_linear\n        if use_linear:\n            self.linear_Q = nn.Conv2d(d_model, d_model, kernel_size=1)\n            self.linear_K = nn.Conv2d(d_model, d_model, kernel_size=1)\n            self.linear_V = nn.Conv2d(d_model, d_model, kernel_size=1)\n\n        self.relative_emb_k = nn.Conv2d(d_model,\n                                        num_head * self.window_size *\n                                        self.window_size,\n                                        kernel_size=1,\n                                        groups=num_head)\n        self.relative_emb_v = nn.Parameter(\n            torch.zeros([\n                self.num_head, d_model // self.num_head,\n                self.window_size * self.window_size\n            ]))\n\n        self.projection = nn.Linear(d_model, d_model)\n        self.dropout = DropOutLogit(dropout)\n\n        self.padded_local_mask = None\n        self.local_mask = None\n        self.last_size_2d = None\n        self.qk_mask = None\n\n    def forward(self, q, k, v):\n        n, c, h, w = q.size()\n\n        if self.use_linear:\n            q = self.linear_Q(q)\n            k = self.linear_K(k)\n            v = self.linear_V(v)\n\n        hidden_dim = c // self.num_head\n\n        relative_emb = self.relative_emb_k(q)\n        relative_emb = relative_emb.view(n, self.num_head,\n                                         self.window_size * self.window_size,\n                                         h * w)\n        padded_local_mask, local_mask = self.compute_mask(h,\n                                                          w,\n                                                          device=q.device)\n        qk_mask = (~padded_local_mask).float()\n\n        # Scale\n        q = q / self.T\n\n        q = q.view(-1, self.num_head, hidden_dim, h * w)\n        k = k.view(-1, self.num_head, hidden_dim, h * w)\n        v = v.view(-1, self.num_head, hidden_dim, h * w)\n\n        qk = q.transpose(-1, -2) @ k  # [B, nH, kL, qL]\n\n        pad_pixel = self.max_dis * self.dilation\n\n        padded_qk = F.pad(qk.view(-1, self.num_head, h * w, h, w),\n                          (pad_pixel, pad_pixel, pad_pixel, pad_pixel),\n                          mode='constant',\n                          value=-1e+8 if qk.dtype == torch.float32 else -1e+4)\n\n        qk_mask = qk_mask * 1e+8 if (padded_qk.dtype\n                                     == torch.float32) else qk_mask * 1e+4\n        padded_qk = padded_qk - qk_mask\n\n        padded_qk[padded_local_mask.expand(n, self.num_head, -1, -1,\n                                           -1)] += relative_emb.transpose(\n                                               -1, -2).reshape(-1)\n        padded_qk = self.dropout(padded_qk)\n\n        local_qk = padded_qk[padded_local_mask.expand(n, self.num_head, -1, -1,\n                                                      -1)]\n\n        global_qk = padded_qk[:, :, :, self.max_dis:-self.max_dis,\n                              self.max_dis:-self.max_dis].reshape(\n                                  n, self.num_head, h * w, h * w)\n\n        local_attn = torch.softmax(local_qk.reshape(\n            n, self.num_head, h * w, self.window_size * self.window_size),\n                                   dim=3)\n        global_attn = torch.softmax(global_qk, dim=3)\n\n        agg_bias = torch.einsum('bhnw,hcw->bhnc', local_attn,\n                                self.relative_emb_v)\n\n        agg_value = (global_attn @ v.transpose(-2, -1))\n\n        output = (agg_value + agg_bias).permute(2, 0, 1,\n                                                3).reshape(h * w, n, c)\n\n        output = self.projection(output)\n\n        self.last_size_2d = (h, w)\n        return output, local_attn\n\n    def compute_mask(self, height, width, device=None):\n        pad_height = height + 2 * self.max_dis\n        pad_width = width + 2 * self.max_dis\n\n        if self.padded_local_mask is not None and (height,\n                                                   width) == self.last_size_2d:\n            padded_local_mask = self.padded_local_mask\n            local_mask = self.local_mask\n\n        else:\n            ky, kx = torch.meshgrid([\n                torch.arange(0, pad_height, device=device),\n                torch.arange(0, pad_width, device=device)\n            ])\n            qy, qx = torch.meshgrid([\n                torch.arange(0, height, device=device),\n                torch.arange(0, width, device=device)\n            ])\n\n            qy = qy.reshape(-1, 1)\n            qx = qx.reshape(-1, 1)\n            offset_y = qy - ky.reshape(1, -1) + self.max_dis\n            offset_x = qx - kx.reshape(1, -1) + self.max_dis\n            padded_local_mask = (offset_y.abs() <= self.max_dis) & (\n                offset_x.abs() <= self.max_dis)\n            padded_local_mask = padded_local_mask.view(1, 1, height * width,\n                                                       pad_height, pad_width)\n            local_mask = padded_local_mask[:, :, :, self.max_dis:-self.max_dis,\n                                           self.max_dis:-self.max_dis]\n            pad_pixel = self.max_dis * self.dilation\n            local_mask = F.pad(local_mask.float(),\n                               (pad_pixel, pad_pixel, pad_pixel, pad_pixel),\n                               mode='constant',\n                               value=0).view(1, 1, height * width, pad_height,\n                                             pad_width)\n            self.padded_local_mask = padded_local_mask\n            self.local_mask = local_mask\n\n        return padded_local_mask, local_mask\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/layers/basic.py",
    "content": "import torch\nimport torch.nn.functional as F\nfrom torch import nn\n\n\nclass GroupNorm1D(nn.Module):\n    def __init__(self, indim, groups=8):\n        super().__init__()\n        self.gn = nn.GroupNorm(groups, indim)\n\n    def forward(self, x):\n        return self.gn(x.permute(1, 2, 0)).permute(2, 0, 1)\n\n\nclass GNActDWConv2d(nn.Module):\n    def __init__(self, indim, gn_groups=32):\n        super().__init__()\n        self.gn = nn.GroupNorm(gn_groups, indim)\n        self.conv = nn.Conv2d(indim,\n                              indim,\n                              5,\n                              dilation=1,\n                              padding=2,\n                              groups=indim,\n                              bias=False)\n\n    def forward(self, x, size_2d):\n        h, w = size_2d\n        _, bs, c = x.size()\n        x = x.view(h, w, bs, c).permute(2, 3, 0, 1)\n        x = self.gn(x)\n        x = F.gelu(x)\n        x = self.conv(x)\n        x = x.view(bs, c, h * w).permute(2, 0, 1)\n        return x\n\n\nclass ConvGN(nn.Module):\n    def __init__(self, indim, outdim, kernel_size, gn_groups=8):\n        super().__init__()\n        self.conv = nn.Conv2d(indim,\n                              outdim,\n                              kernel_size,\n                              padding=kernel_size // 2)\n        self.gn = nn.GroupNorm(gn_groups, outdim)\n\n    def forward(self, x):\n        return self.gn(self.conv(x))\n\n\ndef seq_to_2d(tensor, size_2d):\n    h, w = size_2d\n    _, n, c = tensor.size()\n    tensor = tensor.view(h, w, n, c).permute(2, 3, 0, 1).contiguous()\n    return tensor\n\n\ndef drop_path(x, drop_prob: float = 0., training: bool = False):\n    if drop_prob == 0. or not training:\n        return x\n    keep_prob = 1 - drop_prob\n    shape = (x.shape[0], ) + (1, ) * (\n        x.ndim - 1)  # work with diff dim tensors, not just 2D ConvNets\n    random_tensor = keep_prob + torch.rand(\n        shape, dtype=x.dtype, device=x.device)\n    random_tensor.floor_()  # binarize\n    output = x.div(keep_prob) * random_tensor\n    return output\n\n\nclass DropPath(nn.Module):\n    def __init__(self, drop_prob=None, batch_dim=0):\n        super(DropPath, self).__init__()\n        self.drop_prob = drop_prob\n        self.batch_dim = batch_dim\n\n    def forward(self, x):\n        return self.drop_path(x, self.drop_prob)\n\n    def drop_path(self, x, drop_prob):\n        if drop_prob == 0. or not self.training:\n            return x\n        keep_prob = 1 - drop_prob\n        shape = [1 for _ in range(x.ndim)]\n        shape[self.batch_dim] = x.shape[self.batch_dim]\n        random_tensor = keep_prob + torch.rand(\n            shape, dtype=x.dtype, device=x.device)\n        random_tensor.floor_()  # binarize\n        output = x.div(keep_prob) * random_tensor\n        return output\n\n\nclass DropOutLogit(nn.Module):\n    def __init__(self, drop_prob=None):\n        super(DropOutLogit, self).__init__()\n        self.drop_prob = drop_prob\n\n    def forward(self, x):\n        return self.drop_logit(x, self.drop_prob)\n\n    def drop_logit(self, x, drop_prob):\n        if drop_prob == 0. or not self.training:\n            return x\n        random_tensor = drop_prob + torch.rand(\n            x.shape, dtype=x.dtype, device=x.device)\n        random_tensor.floor_()  # binarize\n        mask = random_tensor * 1e+8 if (\n            x.dtype == torch.float32) else random_tensor * 1e+4\n        output = x - mask\n        return output\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/layers/loss.py",
    "content": "import torch\nimport torch.nn as nn\nimport torch.nn.functional as F\n\ntry:\n    from itertools import ifilterfalse\nexcept ImportError:  # py3k\n    from itertools import filterfalse as ifilterfalse\n\n\ndef dice_loss(probas, labels, smooth=1):\n\n    C = probas.size(1)\n    losses = []\n    for c in list(range(C)):\n        fg = (labels == c).float()\n        if fg.sum() == 0:\n            continue\n        class_pred = probas[:, c]\n        p0 = class_pred\n        g0 = fg\n        numerator = 2 * torch.sum(p0 * g0) + smooth\n        denominator = torch.sum(p0) + torch.sum(g0) + smooth\n        losses.append(1 - ((numerator) / (denominator)))\n    return mean(losses)\n\n\ndef tversky_loss(probas, labels, alpha=0.5, beta=0.5, epsilon=1e-6):\n    '''\n    Tversky loss function.\n        probas: [P, C] Variable, class probabilities at each prediction (between 0 and 1)\n        labels: [P] Tensor, ground truth labels (between 0 and C - 1)\n\n    Same as soft dice loss when alpha=beta=0.5.\n    Same as Jaccord loss when alpha=beta=1.0.\n    See `Tversky loss function for image segmentation using 3D fully convolutional deep networks`\n    https://arxiv.org/pdf/1706.05721.pdf\n    '''\n    C = probas.size(1)\n    losses = []\n    for c in list(range(C)):\n        fg = (labels == c).float()\n        if fg.sum() == 0:\n            continue\n        class_pred = probas[:, c]\n        p0 = class_pred\n        p1 = 1 - class_pred\n        g0 = fg\n        g1 = 1 - fg\n        numerator = torch.sum(p0 * g0)\n        denominator = numerator + alpha * \\\n            torch.sum(p0*g1) + beta*torch.sum(p1*g0)\n        losses.append(1 - ((numerator) / (denominator + epsilon)))\n    return mean(losses)\n\n\ndef flatten_probas(probas, labels, ignore=255):\n    \"\"\"\n    Flattens predictions in the batch\n    \"\"\"\n    B, C, H, W = probas.size()\n    probas = probas.permute(0, 2, 3,\n                            1).contiguous().view(-1, C)  # B * H * W, C = P, C\n    labels = labels.view(-1)\n    if ignore is None:\n        return probas, labels\n    valid = (labels != ignore)\n    vprobas = probas[valid.view(-1, 1).expand(-1, C)].reshape(-1, C)\n    # vprobas = probas[torch.nonzero(valid).squeeze()]\n    vlabels = labels[valid]\n    return vprobas, vlabels\n\n\ndef isnan(x):\n    return x != x\n\n\ndef mean(l, ignore_nan=False, empty=0):\n    \"\"\"\n    nanmean compatible with generators.\n    \"\"\"\n    l = iter(l)\n    if ignore_nan:\n        l = ifilterfalse(isnan, l)\n    try:\n        n = 1\n        acc = next(l)\n    except StopIteration:\n        if empty == 'raise':\n            raise ValueError('Empty mean')\n        return empty\n    for n, v in enumerate(l, 2):\n        acc += v\n    if n == 1:\n        return acc\n    return acc / n\n\n\nclass DiceLoss(nn.Module):\n    def __init__(self, ignore_index=255):\n        super(DiceLoss, self).__init__()\n        self.ignore_index = ignore_index\n\n    def forward(self, tmp_dic, label_dic, step=None):\n        total_loss = []\n        for idx in range(len(tmp_dic)):\n            pred = tmp_dic[idx]\n            label = label_dic[idx]\n            pred = F.softmax(pred, dim=1)\n            label = label.view(1, 1, pred.size()[2], pred.size()[3])\n            loss = dice_loss(\n                *flatten_probas(pred, label, ignore=self.ignore_index))\n            total_loss.append(loss.unsqueeze(0))\n        total_loss = torch.cat(total_loss, dim=0)\n        return total_loss\n\n\nclass SoftJaccordLoss(nn.Module):\n    def __init__(self, ignore_index=255):\n        super(SoftJaccordLoss, self).__init__()\n        self.ignore_index = ignore_index\n\n    def forward(self, tmp_dic, label_dic, step=None):\n        total_loss = []\n        for idx in range(len(tmp_dic)):\n            pred = tmp_dic[idx]\n            label = label_dic[idx]\n            pred = F.softmax(pred, dim=1)\n            label = label.view(1, 1, pred.size()[2], pred.size()[3])\n            loss = tversky_loss(*flatten_probas(pred,\n                                                label,\n                                                ignore=self.ignore_index),\n                                alpha=1.0,\n                                beta=1.0)\n            total_loss.append(loss.unsqueeze(0))\n        total_loss = torch.cat(total_loss, dim=0)\n        return total_loss\n\n\nclass CrossEntropyLoss(nn.Module):\n    def __init__(self,\n                 top_k_percent_pixels=None,\n                 hard_example_mining_step=100000):\n        super(CrossEntropyLoss, self).__init__()\n        self.top_k_percent_pixels = top_k_percent_pixels\n        if top_k_percent_pixels is not None:\n            assert (top_k_percent_pixels > 0 and top_k_percent_pixels < 1)\n        self.hard_example_mining_step = hard_example_mining_step + 1e-5\n        if self.top_k_percent_pixels is None:\n            self.celoss = nn.CrossEntropyLoss(ignore_index=255,\n                                              reduction='mean')\n        else:\n            self.celoss = nn.CrossEntropyLoss(ignore_index=255,\n                                              reduction='none')\n\n    def forward(self, dic_tmp, y, step):\n        total_loss = []\n        for i in range(len(dic_tmp)):\n            pred_logits = dic_tmp[i]\n            gts = y[i]\n            if self.top_k_percent_pixels is None:\n                final_loss = self.celoss(pred_logits, gts)\n            else:\n                # Only compute the loss for top k percent pixels.\n                # First, compute the loss for all pixels. Note we do not put the loss\n                # to loss_collection and set reduction = None to keep the shape.\n                num_pixels = float(pred_logits.size(2) * pred_logits.size(3))\n                pred_logits = pred_logits.view(\n                    -1, pred_logits.size(1),\n                    pred_logits.size(2) * pred_logits.size(3))\n                gts = gts.view(-1, gts.size(1) * gts.size(2))\n                pixel_losses = self.celoss(pred_logits, gts)\n                if self.hard_example_mining_step == 0:\n                    top_k_pixels = int(self.top_k_percent_pixels * num_pixels)\n                else:\n                    ratio = min(1.0,\n                                step / float(self.hard_example_mining_step))\n                    top_k_pixels = int((ratio * self.top_k_percent_pixels +\n                                        (1.0 - ratio)) * num_pixels)\n                top_k_loss, top_k_indices = torch.topk(pixel_losses,\n                                                       k=top_k_pixels,\n                                                       dim=1)\n\n                final_loss = torch.mean(top_k_loss)\n            final_loss = final_loss.unsqueeze(0)\n            total_loss.append(final_loss)\n        total_loss = torch.cat(total_loss, dim=0)\n        return total_loss\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/layers/normalization.py",
    "content": "import torch\nimport torch.nn as nn\nimport torch.nn.functional as F\n\n\nclass FrozenBatchNorm2d(nn.Module):\n    \"\"\"\n    BatchNorm2d where the batch statistics and the affine parameters\n    are fixed\n    \"\"\"\n    def __init__(self, n, epsilon=1e-5):\n        super(FrozenBatchNorm2d, self).__init__()\n        self.register_buffer(\"weight\", torch.ones(n))\n        self.register_buffer(\"bias\", torch.zeros(n))\n        self.register_buffer(\"running_mean\", torch.zeros(n))\n        self.register_buffer(\"running_var\", torch.ones(n) - epsilon)\n        self.epsilon = epsilon\n\n    def forward(self, x):\n        \"\"\"\n        Refer to Detectron2 (https://github.com/facebookresearch/detectron2/blob/cbbc1ce26473cb2a5cc8f58e8ada9ae14cb41052/detectron2/layers/batch_norm.py)\n        \"\"\"\n        if x.requires_grad:\n            # When gradients are needed, F.batch_norm will use extra memory\n            # because its backward op computes gradients for weight/bias as well.\n            scale = self.weight * (self.running_var + self.epsilon).rsqrt()\n            bias = self.bias - self.running_mean * scale\n            scale = scale.reshape(1, -1, 1, 1)\n            bias = bias.reshape(1, -1, 1, 1)\n            out_dtype = x.dtype  # may be half\n            return x * scale.to(out_dtype) + bias.to(out_dtype)\n        else:\n            # When gradients are not needed, F.batch_norm is a single fused op\n            # and provide more optimization opportunities.\n            return F.batch_norm(\n                x,\n                self.running_mean,\n                self.running_var,\n                self.weight,\n                self.bias,\n                training=False,\n                eps=self.epsilon,\n            )\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/layers/position.py",
    "content": "import math\n\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\n\nfrom detectron2.aot_modules.utils.math import truncated_normal_\n\n\nclass Downsample2D(nn.Module):\n    def __init__(self, mode='nearest', scale=4):\n        super().__init__()\n        self.mode = mode\n        self.scale = scale\n\n    def forward(self, x):\n        n, c, h, w = x.size()\n        x = F.interpolate(x,\n                          size=(h // self.scale + 1, w // self.scale + 1),\n                          mode=self.mode)\n        return x\n\n\ndef generate_coord(x):\n    _, _, h, w = x.size()\n    device = x.device\n    col = torch.arange(0, h, device=device)\n    row = torch.arange(0, w, device=device)\n    grid_h, grid_w = torch.meshgrid(col, row)\n    return grid_h, grid_w\n\n\nclass PositionEmbeddingSine(nn.Module):\n    def __init__(self,\n                 num_pos_feats=64,\n                 temperature=10000,\n                 normalize=False,\n                 scale=None):\n        super().__init__()\n        self.num_pos_feats = num_pos_feats\n        self.temperature = temperature\n        self.normalize = normalize\n        if scale is not None and normalize is False:\n            raise ValueError(\"normalize should be True if scale is passed\")\n        if scale is None:\n            scale = 2 * math.pi\n        self.scale = scale\n\n    def forward(self, x):\n        grid_y, grid_x = generate_coord(x)\n\n        y_embed = grid_y.unsqueeze(0).float()\n        x_embed = grid_x.unsqueeze(0).float()\n\n        if self.normalize:\n            eps = 1e-6\n            y_embed = y_embed / (y_embed[:, -1:, :] + eps) * self.scale\n            x_embed = x_embed / (x_embed[:, :, -1:] + eps) * self.scale\n\n        dim_t = torch.arange(self.num_pos_feats,\n                             dtype=torch.float32,\n                             device=x.device)\n        dim_t = self.temperature**(2 * (dim_t // 2) / self.num_pos_feats)\n\n        pos_x = x_embed[:, :, :, None] / dim_t\n        pos_y = y_embed[:, :, :, None] / dim_t\n        pos_x = torch.stack(\n            (pos_x[:, :, :, 0::2].sin(), pos_x[:, :, :, 1::2].cos()),\n            dim=4).flatten(3)\n        pos_y = torch.stack(\n            (pos_y[:, :, :, 0::2].sin(), pos_y[:, :, :, 1::2].cos()),\n            dim=4).flatten(3)\n        pos = torch.cat((pos_y, pos_x), dim=3).permute(0, 3, 1, 2)\n        return pos\n\n\nclass PositionEmbeddingLearned(nn.Module):\n    def __init__(self, num_pos_feats=64, H=30, W=30):\n        super().__init__()\n        self.H = H\n        self.W = W\n        self.pos_emb = nn.Parameter(\n            truncated_normal_(torch.zeros(1, num_pos_feats, H, W)))\n\n    def forward(self, x):\n        bs, _, h, w = x.size()\n        pos_emb = self.pos_emb\n        if h != self.H or w != self.W:\n            pos_emb = F.interpolate(pos_emb, size=(h, w), mode=\"bilinear\")\n        return pos_emb\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/layers/transformer.py",
    "content": "import torch.nn.functional as F\nfrom torch import nn\n\nfrom detectron2.aot_modules.layers.basic import DropPath, GroupNorm1D, GNActDWConv2d, seq_to_2d\nfrom detectron2.aot_modules.layers.attention import MultiheadAttention, MultiheadLocalAttentionV2, MultiheadLocalAttentionV3\n\n\ndef _get_norm(indim, type='ln', groups=8):\n    if type == 'gn':\n        return GroupNorm1D(indim, groups)\n    else:\n        return nn.LayerNorm(indim)\n\n\ndef _get_activation_fn(activation):\n    \"\"\"Return an activation function given a string\"\"\"\n    if activation == \"relu\":\n        return F.relu\n    if activation == \"gelu\":\n        return F.gelu\n    if activation == \"glu\":\n        return F.glu\n    raise RuntimeError(\n        F\"activation should be relu/gele/glu, not {activation}.\")\n\n\nclass LongShortTermTransformer(nn.Module):\n    def __init__(self,\n                 num_layers=2,\n                 d_model=256,\n                 self_nhead=8,\n                 att_nhead=8,\n                 dim_feedforward=1024,\n                 emb_dropout=0.,\n                 droppath=0.1,\n                 lt_dropout=0.,\n                 st_dropout=0.,\n                 droppath_lst=False,\n                 droppath_scaling=False,\n                 activation=\"gelu\",\n                 return_intermediate=False,\n                 intermediate_norm=True,\n                 final_norm=True):\n\n        super().__init__()\n        self.intermediate_norm = intermediate_norm\n        self.final_norm = final_norm\n        self.num_layers = num_layers\n        self.return_intermediate = return_intermediate\n\n        self.emb_dropout = nn.Dropout(emb_dropout, True)\n\n        layers = []\n        for idx in range(num_layers):\n            if droppath_scaling:\n                if num_layers == 1:\n                    droppath_rate = 0\n                else:\n                    droppath_rate = droppath * idx / (num_layers - 1)\n            else:\n                droppath_rate = droppath\n            layers.append(\n                LongShortTermTransformerBlock(d_model, self_nhead, att_nhead,\n                                              dim_feedforward, droppath_rate,\n                                              lt_dropout, st_dropout,\n                                              droppath_lst, activation))\n        self.layers = nn.ModuleList(layers)\n\n        num_norms = num_layers - 1 if intermediate_norm else 0\n        if final_norm:\n            num_norms += 1\n        self.decoder_norms = [\n            _get_norm(d_model, type='ln') for _ in range(num_norms)\n        ] if num_norms > 0 else None\n\n        if self.decoder_norms is not None:\n            self.decoder_norms = nn.ModuleList(self.decoder_norms)\n\n    def forward(self,\n                tgt,\n                long_term_memories,\n                short_term_memories,\n                curr_id_emb=None,\n                self_pos=None,\n                size_2d=None):\n\n        output = self.emb_dropout(tgt)\n\n        intermediate = []\n        intermediate_memories = []\n\n        for idx, layer in enumerate(self.layers):\n            output, memories = layer(output,\n                                     long_term_memories[idx] if\n                                     long_term_memories is not None else None,\n                                     short_term_memories[idx] if\n                                     short_term_memories is not None else None,\n                                     curr_id_emb=curr_id_emb,\n                                     self_pos=self_pos,\n                                     size_2d=size_2d) # tgt, [[cur_k, cur_v],[global_k, global_v],[local_k, local_v]]\n            # print(output.shape, memories[0][0].shape) \n\n            if self.return_intermediate:\n                intermediate.append(output)\n                intermediate_memories.append(memories)\n\n        if self.decoder_norms is not None:\n            if self.final_norm:\n                output = self.decoder_norms[-1](output)\n\n            if self.return_intermediate:\n                intermediate.pop()\n                intermediate.append(output)\n\n                if self.intermediate_norm:\n                    for idx in range(len(intermediate) - 1):\n                        intermediate[idx] = self.decoder_norms[idx](\n                            intermediate[idx])\n\n        if self.return_intermediate:\n            return intermediate, intermediate_memories # list len = 3, memories = list [[ck,cv], [gk,gv], [lk,lv]]\n\n        return output, memories\n\n\nclass LongShortTermTransformerBlock(nn.Module):\n    def __init__(self,\n                 d_model,\n                 self_nhead,\n                 att_nhead,\n                 dim_feedforward=1024,\n                 droppath=0.1,\n                 lt_dropout=0.,\n                 st_dropout=0.,\n                 droppath_lst=False,\n                 activation=\"gelu\",\n                 local_dilation=1,\n                 enable_corr=True):\n        super().__init__()\n\n        # Self-attention\n        self.norm1 = _get_norm(d_model)\n        self.self_attn = MultiheadAttention(d_model, self_nhead)\n\n        # Long Short-Term Attention\n        self.norm2 = _get_norm(d_model)\n        self.linear_Q = nn.Linear(d_model, d_model)\n        self.linear_V = nn.Linear(d_model, d_model)\n\n        self.long_term_attn = MultiheadAttention(d_model,\n                                                 att_nhead,\n                                                 use_linear=False,\n                                                 dropout=lt_dropout)\n        if enable_corr:\n            try:\n                import spatial_correlation_sampler\n                MultiheadLocalAttention = MultiheadLocalAttentionV2\n            except Exception as inst:\n                print(inst)\n                print(\n                    \"Failed to import PyTorch Correlation. For better efficiency, please install it.\"\n                )\n                MultiheadLocalAttention = MultiheadLocalAttentionV3\n        else:\n            MultiheadLocalAttention = MultiheadLocalAttentionV3\n        self.short_term_attn = MultiheadLocalAttention(d_model,\n                                                       att_nhead,\n                                                       dilation=local_dilation,\n                                                       use_linear=False,\n                                                       dropout=st_dropout)\n\n        self.droppath_lst = droppath_lst\n\n        # Feed-forward\n        self.norm3 = _get_norm(d_model)\n        self.linear1 = nn.Linear(d_model, dim_feedforward)\n        self.activation = GNActDWConv2d(dim_feedforward)\n        self.linear2 = nn.Linear(dim_feedforward, d_model)\n\n        self.droppath = DropPath(droppath, batch_dim=1)\n        self._init_weight()\n\n    def with_pos_embed(self, tensor, pos=None):\n        size = tensor.size()\n        if len(size) == 4 and pos is not None:\n            n, c, h, w = size\n            pos = pos.view(h, w, n, c).permute(2, 3, 0, 1)\n        return tensor if pos is None else tensor + pos\n\n    def forward(self,\n                tgt,\n                long_term_memory=None,\n                short_term_memory=None,\n                curr_id_emb=None,\n                self_pos=None,\n                size_2d=(30, 30)):\n\n        # Self-attention\n        _tgt = self.norm1(tgt)\n        q = k = self.with_pos_embed(_tgt, self_pos)\n        v = _tgt\n        tgt2 = self.self_attn(q, k, v)[0]\n\n        tgt = tgt + self.droppath(tgt2)\n\n        # Long Short-Term Attention\n        _tgt = self.norm2(tgt)\n\n        curr_Q = self.linear_Q(_tgt)\n        curr_K = curr_Q\n        curr_V = _tgt\n\n        local_Q = seq_to_2d(curr_Q, size_2d)\n\n        if curr_id_emb is not None:\n            global_K = curr_K\n            global_V = self.linear_V(curr_V + curr_id_emb)\n            local_K = seq_to_2d(global_K, size_2d)\n            local_V = seq_to_2d(global_V, size_2d)\n        else:\n            global_K, global_V = long_term_memory\n            local_K, local_V = short_term_memory\n\n        tgt2 = self.long_term_attn(curr_Q, global_K, global_V)[0]\n        tgt3 = self.short_term_attn(local_Q, local_K, local_V)[0]\n\n        if self.droppath_lst:\n            tgt = tgt + self.droppath(tgt2 + tgt3)\n        else:\n            tgt = tgt + tgt2 + tgt3\n\n        # Feed-forward\n        _tgt = self.norm3(tgt)\n\n        tgt2 = self.linear2(self.activation(self.linear1(_tgt), size_2d))\n\n        tgt = tgt + self.droppath(tgt2)\n\n        return tgt, [[curr_K, curr_V], [global_K, global_V],\n                     [local_K, local_V]]\n\n    def _init_weight(self):\n        for p in self.parameters():\n            if p.dim() > 1:\n                nn.init.xavier_uniform_(p)\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/models/__init__.py",
    "content": "from detectron2.aot_modules.models.aot import AOT\n\n\n\ndef build_vos_model(name, cfg, **kwargs):\n\n    if name == 'aot':\n        return AOT(cfg, encoder=cfg.MODEL_ENCODER, **kwargs)\n    else:\n        raise NotImplementedError\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/models/aot.py",
    "content": "import torch.nn as nn\n\nfrom detectron2.aot_modules.encoders import build_encoder\nfrom detectron2.aot_modules.layers.transformer import LongShortTermTransformer\nfrom detectron2.aot_modules.decoders import build_decoder\nfrom detectron2.aot_modules.layers.position import PositionEmbeddingSine\n\n\nclass AOT(nn.Module):\n    def __init__(self, cfg, encoder='mobilenetv2', decoder='fpn'):\n        super().__init__()\n        self.cfg = cfg\n        self.max_obj_num = cfg.MODEL_MAX_OBJ_NUM\n        self.epsilon = cfg.MODEL_EPSILON\n\n        self.encoder = build_encoder(encoder,\n                                     frozen_bn=cfg.MODEL_FREEZE_BN,\n                                     freeze_at=cfg.TRAIN_ENCODER_FREEZE_AT)\n        self.encoder_projector = nn.Conv2d(cfg.MODEL_ENCODER_DIM[-1],\n                                           cfg.MODEL_ENCODER_EMBEDDING_DIM,\n                                           kernel_size=1)\n\n        self.LSTT = LongShortTermTransformer(\n            cfg.MODEL_LSTT_NUM,\n            cfg.MODEL_ENCODER_EMBEDDING_DIM,\n            cfg.MODEL_SELF_HEADS,\n            cfg.MODEL_ATT_HEADS,\n            emb_dropout=cfg.TRAIN_LSTT_EMB_DROPOUT,\n            droppath=cfg.TRAIN_LSTT_DROPPATH,\n            lt_dropout=cfg.TRAIN_LSTT_LT_DROPOUT,\n            st_dropout=cfg.TRAIN_LSTT_ST_DROPOUT,\n            droppath_lst=cfg.TRAIN_LSTT_DROPPATH_LST,\n            droppath_scaling=cfg.TRAIN_LSTT_DROPPATH_SCALING,\n            intermediate_norm=cfg.MODEL_DECODER_INTERMEDIATE_LSTT,\n            return_intermediate=True)\n\n        decoder_indim = cfg.MODEL_ENCODER_EMBEDDING_DIM * \\\n            (cfg.MODEL_LSTT_NUM +\n             1) if cfg.MODEL_DECODER_INTERMEDIATE_LSTT else cfg.MODEL_ENCODER_EMBEDDING_DIM\n\n        self.decoder = build_decoder(\n            decoder,\n            in_dim=decoder_indim,\n            out_dim=cfg.MODEL_MAX_OBJ_NUM + 1, # 10+1\n            decode_intermediate_input=cfg.MODEL_DECODER_INTERMEDIATE_LSTT,\n            hidden_dim=cfg.MODEL_ENCODER_EMBEDDING_DIM,\n            shortcut_dims=cfg.MODEL_ENCODER_DIM,\n            align_corners=cfg.MODEL_ALIGN_CORNERS)\n\n        if cfg.MODEL_ALIGN_CORNERS:\n            self.patch_wise_id_bank = nn.Conv2d(\n                cfg.MODEL_MAX_OBJ_NUM + 1, # 10+1\n                cfg.MODEL_ENCODER_EMBEDDING_DIM, # 256\n                kernel_size=17,\n                stride=16,\n                padding=8)\n        else:\n            self.patch_wise_id_bank = nn.Conv2d(\n                cfg.MODEL_MAX_OBJ_NUM + 1,\n                cfg.MODEL_ENCODER_EMBEDDING_DIM,\n                kernel_size=16,\n                stride=16,\n                padding=0)\n\n        self.id_dropout = nn.Dropout(cfg.TRAIN_LSTT_ID_DROPOUT, True)\n\n        self.pos_generator = PositionEmbeddingSine(\n            cfg.MODEL_ENCODER_EMBEDDING_DIM // 2, normalize=True)\n\n        self._init_weight()\n\n    def get_pos_emb(self, x):\n        pos_emb = self.pos_generator(x)\n        return pos_emb\n\n    def get_id_emb(self, x):\n        # print(\"get id emb: \", x.shape) # 1x11x321x1041 1x151x374x1240\n        id_emb = self.patch_wise_id_bank(x) \n        # print(id_emb.shape) # 1x256x21x66  1x256x24x78\n        id_emb = self.id_dropout(id_emb)\n        # print(id_emb.shape) # 1x256x21x66\n        return id_emb\n\n    def encode_image(self, img):\n        xs = self.encoder(img) # r50, 256x1/4, 512x1/8, 1024x1/16, 1024x1/16\n        xs[-1] = self.encoder_projector(xs[-1]) # r50, 256x1/4, 512x1/8, 1024x1/16, 256x1/16\n        # print(\"encoder:\", xs[0].shape, xs[1].shape, xs[2].shape, xs[3].shape)\n        return xs\n\n    def decode_id_logits(self, lstt_emb, shortcuts):\n        n, c, h, w = shortcuts[-1].size()\n        decoder_inputs = [shortcuts[-1]]\n        for emb in lstt_emb:\n            decoder_inputs.append(emb.view(h, w, n, c).permute(2, 3, 0, 1))\n        pred_logit = self.decoder(decoder_inputs, shortcuts)\n        return pred_logit\n\n    def LSTT_forward(self,\n                     curr_embs,\n                     long_term_memories,\n                     short_term_memories,\n                     curr_id_emb=None,\n                     pos_emb=None,\n                     size_2d=(30, 30)):\n        n, c, h, w = curr_embs[-1].size() # 1x256x21x66\n        curr_emb = curr_embs[-1].view(n, c, h * w).permute(2, 0, 1) # 1386x1x256\n        lstt_embs, lstt_memories = self.LSTT(curr_emb, long_term_memories,\n                                             short_term_memories, curr_id_emb,\n                                             pos_emb, size_2d) # list = 3\n        # print(lstt_embs[0].shape, lstt_embs[1].shape, lstt_embs[2].shape) # 1386x1x256\n        # print(lstt_memories[0][0][0].shape, lstt_memories[0][0][1].shape) # 1386x1x256, 1386x1x256\n        # lstt_memories[0]:  [[cur_K, cur_v], [global_k, global_v], [local_k, local_v]]\n        lstt_curr_memories, lstt_long_memories, lstt_short_memories = zip(*lstt_memories) \n        return lstt_embs, lstt_curr_memories, lstt_long_memories, lstt_short_memories\n\n    def _init_weight(self):\n        nn.init.xavier_uniform_(self.encoder_projector.weight)\n        nn.init.orthogonal_(\n            self.patch_wise_id_bank.weight.view(\n                self.cfg.MODEL_ENCODER_EMBEDDING_DIM, -1).permute(0, 1),\n            gain=17**-2 if self.cfg.MODEL_ALIGN_CORNERS else 16**-2)\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/utils/__init__.py",
    "content": ""
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/utils/checkpoint.py",
    "content": "import torch\nimport os\nimport numpy as np\n\n\ndef load_network_and_optimizer(net, opt, pretrained_dir, gpu, scaler=None):\n    pretrained = torch.load(pretrained_dir,\n                            map_location=torch.device(\"cuda:\" + str(gpu)))\n    pretrained_dict = pretrained['state_dict']\n    model_dict = net.state_dict()\n    pretrained_dict_update = {}\n    pretrained_dict_remove = []\n    for k, v in pretrained_dict.items():\n        if k in model_dict:\n            pretrained_dict_update[k] = v\n        elif k[:7] == 'module.':\n            if k[7:] in model_dict:\n                pretrained_dict_update[k[7:]] = v\n        else:\n            pretrained_dict_remove.append(k)\n    model_dict.update(pretrained_dict_update)\n    net.load_state_dict(model_dict)\n    opt.load_state_dict(pretrained['optimizer'])\n    if scaler is not None and 'scaler' in pretrained.keys():\n        scaler.load_state_dict(pretrained['scaler'])\n    del (pretrained)\n    return net.cuda(gpu), opt, pretrained_dict_remove\n\n\ndef load_network_and_optimizer_v2(net, opt, pretrained_dir, gpu, scaler=None):\n    pretrained = torch.load(pretrained_dir,\n                            map_location=torch.device(\"cuda:\" + str(gpu)))\n    # load model\n    pretrained_dict = pretrained['state_dict']\n    model_dict = net.state_dict()\n    pretrained_dict_update = {}\n    pretrained_dict_remove = []\n    for k, v in pretrained_dict.items():\n        if k in model_dict:\n            pretrained_dict_update[k] = v\n        elif k[:7] == 'module.':\n            if k[7:] in model_dict:\n                pretrained_dict_update[k[7:]] = v\n        else:\n            pretrained_dict_remove.append(k)\n    model_dict.update(pretrained_dict_update)\n    net.load_state_dict(model_dict)\n\n    # load optimizer\n    opt_dict = opt.state_dict()\n    all_params = {\n        param_group['name']: param_group['params'][0]\n        for param_group in opt_dict['param_groups']\n    }\n    pretrained_opt_dict = {'state': {}, 'param_groups': []}\n    for idx in range(len(pretrained['optimizer']['param_groups'])):\n        param_group = pretrained['optimizer']['param_groups'][idx]\n        if param_group['name'] in all_params.keys():\n            pretrained_opt_dict['state'][all_params[\n                param_group['name']]] = pretrained['optimizer']['state'][\n                    param_group['params'][0]]\n            param_group['params'][0] = all_params[param_group['name']]\n            pretrained_opt_dict['param_groups'].append(param_group)\n\n    opt_dict.update(pretrained_opt_dict)\n    opt.load_state_dict(opt_dict)\n\n    # load scaler\n    if scaler is not None and 'scaler' in pretrained.keys():\n        scaler.load_state_dict(pretrained['scaler'])\n    del (pretrained)\n    return net.cuda(gpu), opt, pretrained_dict_remove\n\n\ndef load_network(net, pretrained_dir, gpu):\n    pretrained = torch.load(pretrained_dir,\n                            map_location=torch.device(\"cuda:\" + str(gpu)))\n    if 'state_dict' in pretrained.keys():\n        pretrained_dict = pretrained['state_dict']\n    elif 'model' in pretrained.keys():\n        pretrained_dict = pretrained['model']\n    else:\n        pretrained_dict = pretrained\n    model_dict = net.state_dict()\n    pretrained_dict_update = {}\n    pretrained_dict_remove = []\n    for k, v in pretrained_dict.items():\n        if k in model_dict:\n            pretrained_dict_update[k] = v\n        elif k[:7] == 'module.':\n            if k[7:] in model_dict:\n                pretrained_dict_update[k[7:]] = v\n        else:\n            pretrained_dict_remove.append(k)\n    model_dict.update(pretrained_dict_update)\n    net.load_state_dict(model_dict)\n    del (pretrained)\n    return net.cuda(gpu), pretrained_dict_remove\n\n\ndef save_network(net,\n                 opt,\n                 step,\n                 save_path,\n                 max_keep=8,\n                 backup_dir='./saved_models',\n                 scaler=None):\n    ckpt = {'state_dict': net.state_dict(), 'optimizer': opt.state_dict()}\n    if scaler is not None:\n        ckpt['scaler'] = scaler.state_dict()\n\n    try:\n        if not os.path.exists(save_path):\n            os.makedirs(save_path)\n        save_file = 'save_step_%s.pth' % (step)\n        save_dir = os.path.join(save_path, save_file)\n        torch.save(ckpt, save_dir)\n    except:\n        save_path = backup_dir\n        if not os.path.exists(save_path):\n            os.makedirs(save_path)\n        save_file = 'save_step_%s.pth' % (step)\n        save_dir = os.path.join(save_path, save_file)\n        torch.save(ckpt, save_dir)\n\n    all_ckpt = os.listdir(save_path)\n    if len(all_ckpt) > max_keep:\n        all_step = []\n        for ckpt_name in all_ckpt:\n            step = int(ckpt_name.split('_')[-1].split('.')[0])\n            all_step.append(step)\n        all_step = list(np.sort(all_step))[:-max_keep]\n        for step in all_step:\n            ckpt_path = os.path.join(save_path, 'save_step_%s.pth' % (step))\n            os.system('rm {}'.format(ckpt_path))\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/utils/ema.py",
    "content": "from __future__ import division\nfrom __future__ import unicode_literals\n\nimport torch\n\n\ndef get_param_buffer_for_ema(model,\n                             update_buffer=False,\n                             required_buffers=['running_mean', 'running_var']):\n    params = model.parameters()\n    all_param_buffer = [p for p in params if p.requires_grad]\n    if update_buffer:\n        named_buffers = model.named_buffers()\n        for key, value in named_buffers:\n            for buffer_name in required_buffers:\n                if buffer_name in key:\n                    all_param_buffer.append(value)\n                    break\n    return all_param_buffer\n\n\nclass ExponentialMovingAverage:\n    \"\"\"\n    Maintains (exponential) moving average of a set of parameters.\n    \"\"\"\n    def __init__(self, parameters, decay, use_num_updates=True):\n        \"\"\"\n        Args:\n          parameters: Iterable of `torch.nn.Parameter`; usually the result of\n            `model.parameters()`.\n          decay: The exponential decay.\n          use_num_updates: Whether to use number of updates when computing\n            averages.\n        \"\"\"\n        if decay < 0.0 or decay > 1.0:\n            raise ValueError('Decay must be between 0 and 1')\n        self.decay = decay\n        self.num_updates = 0 if use_num_updates else None\n        self.shadow_params = [p.clone().detach() for p in parameters]\n        self.collected_params = []\n\n    def update(self, parameters):\n        \"\"\"\n        Update currently maintained parameters.\n        Call this every time the parameters are updated, such as the result of\n        the `optimizer.step()` call.\n        Args:\n          parameters: Iterable of `torch.nn.Parameter`; usually the same set of\n            parameters used to initialize this object.\n        \"\"\"\n        decay = self.decay\n        if self.num_updates is not None:\n            self.num_updates += 1\n            decay = min(decay,\n                        (1 + self.num_updates) / (10 + self.num_updates))\n        one_minus_decay = 1.0 - decay\n        with torch.no_grad():\n            for s_param, param in zip(self.shadow_params, parameters):\n                s_param.sub_(one_minus_decay * (s_param - param))\n\n    def copy_to(self, parameters):\n        \"\"\"\n        Copy current parameters into given collection of parameters.\n        Args:\n          parameters: Iterable of `torch.nn.Parameter`; the parameters to be\n            updated with the stored moving averages.\n        \"\"\"\n        for s_param, param in zip(self.shadow_params, parameters):\n            param.data.copy_(s_param.data)\n\n    def store(self, parameters):\n        \"\"\"\n        Save the current parameters for restoring later.\n        Args:\n          parameters: Iterable of `torch.nn.Parameter`; the parameters to be\n            temporarily stored.\n        \"\"\"\n        self.collected_params = [param.clone() for param in parameters]\n\n    def restore(self, parameters):\n        \"\"\"\n        Restore the parameters stored with the `store` method.\n        Useful to validate the model with EMA parameters without affecting the\n        original optimization process. Store the parameters before the\n        `copy_to` method. After validation (or model saving), use this to\n        restore the former parameters.\n        Args:\n          parameters: Iterable of `torch.nn.Parameter`; the parameters to be\n            updated with the stored parameters.\n        \"\"\"\n        for c_param, param in zip(self.collected_params, parameters):\n            param.data.copy_(c_param.data)\n        del (self.collected_params)\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/utils/eval.py",
    "content": "import zipfile\nimport os\n\n\ndef zip_folder(source_folder, zip_dir):\n    f = zipfile.ZipFile(zip_dir, 'w', zipfile.ZIP_DEFLATED)\n    pre_len = len(os.path.dirname(source_folder))\n    for dirpath, dirnames, filenames in os.walk(source_folder):\n        for filename in filenames:\n            pathfile = os.path.join(dirpath, filename)\n            arcname = pathfile[pre_len:].strip(os.path.sep)\n            f.write(pathfile, arcname)\n    f.close()"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/utils/image.py",
    "content": "import numpy as np\nfrom PIL import Image\nimport torch\nimport threading\n\n_palette = [\n    0, 0, 0, 128, 0, 0, 0, 128, 0, 128, 128, 0, 0, 0, 128, 128, 0, 128, 0, 128,\n    128, 128, 128, 128, 64, 0, 0, 191, 0, 0, 64, 128, 0, 191, 128, 0, 64, 0,\n    128, 191, 0, 128, 64, 128, 128, 191, 128, 128, 0, 64, 0, 128, 64, 0, 0,\n    191, 0, 128, 191, 0, 0, 64, 128, 128, 64, 128, 22, 22, 22, 23, 23, 23, 24,\n    24, 24, 25, 25, 25, 26, 26, 26, 27, 27, 27, 28, 28, 28, 29, 29, 29, 30, 30,\n    30, 31, 31, 31, 32, 32, 32, 33, 33, 33, 34, 34, 34, 35, 35, 35, 36, 36, 36,\n    37, 37, 37, 38, 38, 38, 39, 39, 39, 40, 40, 40, 41, 41, 41, 42, 42, 42, 43,\n    43, 43, 44, 44, 44, 45, 45, 45, 46, 46, 46, 47, 47, 47, 48, 48, 48, 49, 49,\n    49, 50, 50, 50, 51, 51, 51, 52, 52, 52, 53, 53, 53, 54, 54, 54, 55, 55, 55,\n    56, 56, 56, 57, 57, 57, 58, 58, 58, 59, 59, 59, 60, 60, 60, 61, 61, 61, 62,\n    62, 62, 63, 63, 63, 64, 64, 64, 65, 65, 65, 66, 66, 66, 67, 67, 67, 68, 68,\n    68, 69, 69, 69, 70, 70, 70, 71, 71, 71, 72, 72, 72, 73, 73, 73, 74, 74, 74,\n    75, 75, 75, 76, 76, 76, 77, 77, 77, 78, 78, 78, 79, 79, 79, 80, 80, 80, 81,\n    81, 81, 82, 82, 82, 83, 83, 83, 84, 84, 84, 85, 85, 85, 86, 86, 86, 87, 87,\n    87, 88, 88, 88, 89, 89, 89, 90, 90, 90, 91, 91, 91, 92, 92, 92, 93, 93, 93,\n    94, 94, 94, 95, 95, 95, 96, 96, 96, 97, 97, 97, 98, 98, 98, 99, 99, 99,\n    100, 100, 100, 101, 101, 101, 102, 102, 102, 103, 103, 103, 104, 104, 104,\n    105, 105, 105, 106, 106, 106, 107, 107, 107, 108, 108, 108, 109, 109, 109,\n    110, 110, 110, 111, 111, 111, 112, 112, 112, 113, 113, 113, 114, 114, 114,\n    115, 115, 115, 116, 116, 116, 117, 117, 117, 118, 118, 118, 119, 119, 119,\n    120, 120, 120, 121, 121, 121, 122, 122, 122, 123, 123, 123, 124, 124, 124,\n    125, 125, 125, 126, 126, 126, 127, 127, 127, 128, 128, 128, 129, 129, 129,\n    130, 130, 130, 131, 131, 131, 132, 132, 132, 133, 133, 133, 134, 134, 134,\n    135, 135, 135, 136, 136, 136, 137, 137, 137, 138, 138, 138, 139, 139, 139,\n    140, 140, 140, 141, 141, 141, 142, 142, 142, 143, 143, 143, 144, 144, 144,\n    145, 145, 145, 146, 146, 146, 147, 147, 147, 148, 148, 148, 149, 149, 149,\n    150, 150, 150, 151, 151, 151, 152, 152, 152, 153, 153, 153, 154, 154, 154,\n    155, 155, 155, 156, 156, 156, 157, 157, 157, 158, 158, 158, 159, 159, 159,\n    160, 160, 160, 161, 161, 161, 162, 162, 162, 163, 163, 163, 164, 164, 164,\n    165, 165, 165, 166, 166, 166, 167, 167, 167, 168, 168, 168, 169, 169, 169,\n    170, 170, 170, 171, 171, 171, 172, 172, 172, 173, 173, 173, 174, 174, 174,\n    175, 175, 175, 176, 176, 176, 177, 177, 177, 178, 178, 178, 179, 179, 179,\n    180, 180, 180, 181, 181, 181, 182, 182, 182, 183, 183, 183, 184, 184, 184,\n    185, 185, 185, 186, 186, 186, 187, 187, 187, 188, 188, 188, 189, 189, 189,\n    190, 190, 190, 191, 191, 191, 192, 192, 192, 193, 193, 193, 194, 194, 194,\n    195, 195, 195, 196, 196, 196, 197, 197, 197, 198, 198, 198, 199, 199, 199,\n    200, 200, 200, 201, 201, 201, 202, 202, 202, 203, 203, 203, 204, 204, 204,\n    205, 205, 205, 206, 206, 206, 207, 207, 207, 208, 208, 208, 209, 209, 209,\n    210, 210, 210, 211, 211, 211, 212, 212, 212, 213, 213, 213, 214, 214, 214,\n    215, 215, 215, 216, 216, 216, 217, 217, 217, 218, 218, 218, 219, 219, 219,\n    220, 220, 220, 221, 221, 221, 222, 222, 222, 223, 223, 223, 224, 224, 224,\n    225, 225, 225, 226, 226, 226, 227, 227, 227, 228, 228, 228, 229, 229, 229,\n    230, 230, 230, 231, 231, 231, 232, 232, 232, 233, 233, 233, 234, 234, 234,\n    235, 235, 235, 236, 236, 236, 237, 237, 237, 238, 238, 238, 239, 239, 239,\n    240, 240, 240, 241, 241, 241, 242, 242, 242, 243, 243, 243, 244, 244, 244,\n    245, 245, 245, 246, 246, 246, 247, 247, 247, 248, 248, 248, 249, 249, 249,\n    250, 250, 250, 251, 251, 251, 252, 252, 252, 253, 253, 253, 254, 254, 254,\n    255, 255, 255\n]\n\n\ndef label2colormap(label):\n\n    m = label.astype(np.uint8)\n    r, c = m.shape\n    cmap = np.zeros((r, c, 3), dtype=np.uint8)\n    cmap[:, :, 0] = (m & 1) << 7 | (m & 8) << 3 | (m & 64) >> 1\n    cmap[:, :, 1] = (m & 2) << 6 | (m & 16) << 2 | (m & 128) >> 2\n    cmap[:, :, 2] = (m & 4) << 5 | (m & 32) << 1\n    return cmap\n\n\ndef one_hot_mask(mask, cls_num):\n    if len(mask.size()) == 3:\n        mask = mask.unsqueeze(1)\n    indices = torch.arange(0, cls_num + 1,\n                           device=mask.device).view(1, -1, 1, 1)\n    return (mask == indices).float()\n\n\ndef masked_image(image, colored_mask, mask, alpha=0.7):\n    mask = np.expand_dims(mask > 0, axis=0)\n    mask = np.repeat(mask, 3, axis=0)\n    show_img = (image * alpha + colored_mask *\n                (1 - alpha)) * mask + image * (1 - mask)\n    return show_img\n\n\ndef save_image(image, path):\n    im = Image.fromarray(np.uint8(image * 255.).transpose((1, 2, 0)))\n    im.save(path)\n\n\ndef _save_mask(mask, path, squeeze_idx=None):\n    if squeeze_idx is not None:\n        unsqueezed_mask = mask * 0\n        for idx in range(1, len(squeeze_idx)):\n            obj_id = squeeze_idx[idx]\n            mask_i = mask == idx\n            unsqueezed_mask += (mask_i * obj_id).astype(np.uint8)\n        mask = unsqueezed_mask\n    mask = Image.fromarray(mask).convert('P')\n    mask.putpalette(_palette)\n    mask.save(path)\n\n\ndef save_mask(mask_tensor, path, squeeze_idx=None):\n    mask = mask_tensor.cpu().numpy().astype('uint8')\n    threading.Thread(target=_save_mask, args=[mask, path, squeeze_idx]).start()\n\n\ndef flip_tensor(tensor, dim=0):\n    inv_idx = torch.arange(tensor.size(dim) - 1, -1, -1,\n                           device=tensor.device).long()\n    tensor = tensor.index_select(dim, inv_idx)\n    return tensor\n\n\ndef shuffle_obj_mask(mask):\n\n    bs, obj_num, _, _ = mask.size()\n    new_masks = []\n    for idx in range(bs):\n        now_mask = mask[idx]\n        random_matrix = torch.eye(obj_num, device=mask.device)\n        fg = random_matrix[1:][torch.randperm(obj_num - 1)]\n        random_matrix = torch.cat([random_matrix[0:1], fg], dim=0)\n        now_mask = torch.einsum('nm,nhw->mhw', random_matrix, now_mask)\n        new_masks.append(now_mask)\n\n    return torch.stack(new_masks, dim=0)\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/utils/learning.py",
    "content": "import math\n\n\ndef adjust_learning_rate(optimizer,\n                         base_lr,\n                         p,\n                         itr,\n                         max_itr,\n                         restart=1,\n                         warm_up_steps=1000,\n                         is_cosine_decay=False,\n                         min_lr=1e-5,\n                         encoder_lr_ratio=1.0,\n                         freeze_params=[]):\n\n    if restart > 1:\n        each_max_itr = int(math.ceil(float(max_itr) / restart))\n        itr = itr % each_max_itr\n        warm_up_steps /= restart\n        max_itr = each_max_itr\n\n    if itr < warm_up_steps:\n        now_lr = min_lr + (base_lr - min_lr) * itr / warm_up_steps\n    else:\n        itr = itr - warm_up_steps\n        max_itr = max_itr - warm_up_steps\n        if is_cosine_decay:\n            now_lr = min_lr + (base_lr - min_lr) * (math.cos(math.pi * itr /\n                                                             (max_itr + 1)) +\n                                                    1.) * 0.5\n        else:\n            now_lr = min_lr + (base_lr - min_lr) * (1 - itr / (max_itr + 1))**p\n\n    for param_group in optimizer.param_groups:\n        if encoder_lr_ratio != 1.0 and \"encoder.\" in param_group[\"name\"]:\n            param_group['lr'] = (now_lr - min_lr) * encoder_lr_ratio + min_lr\n        else:\n            param_group['lr'] = now_lr\n\n        for freeze_param in freeze_params:\n            if freeze_param in param_group[\"name\"]:\n                param_group['lr'] = 0\n                param_group['weight_decay'] = 0\n                break\n\n    return now_lr\n\n\ndef get_trainable_params(model,\n                         base_lr,\n                         weight_decay,\n                         use_frozen_bn=False,\n                         exclusive_wd_dict={},\n                         no_wd_keys=[]):\n    params = []\n    memo = set()\n    total_param = 0\n    for key, value in model.named_parameters():\n        if value in memo:\n            continue\n        total_param += value.numel()\n        if not value.requires_grad:\n            continue\n        memo.add(value)\n        wd = weight_decay\n        for exclusive_key in exclusive_wd_dict.keys():\n            if exclusive_key in key:\n                wd = exclusive_wd_dict[exclusive_key]\n                break\n        if len(value.shape) == 1:  # normalization layers\n            if 'bias' in key:  # bias requires no weight decay\n                wd = 0.\n            elif not use_frozen_bn:  # if not use frozen BN, apply zero weight decay\n                wd = 0.\n            elif 'encoder.' not in key:  # if use frozen BN, apply weight decay to all frozen BNs in the encoder\n                wd = 0.\n        else:\n            for no_wd_key in no_wd_keys:\n                if no_wd_key in key:\n                    wd = 0.\n                    break\n        params += [{\n            \"params\": [value],\n            \"lr\": base_lr,\n            \"weight_decay\": wd,\n            \"name\": key\n        }]\n\n    print('Total Param: {:.2f}M'.format(total_param / 1e6))\n    return params\n\n\ndef freeze_params(module):\n    for p in module.parameters():\n        p.requires_grad = False\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/utils/math.py",
    "content": "import torch\n\n\ndef generate_permute_matrix(dim, num, keep_first=True, gpu_id=0):\n    all_matrix = []\n    for idx in range(num):\n        random_matrix = torch.eye(dim, device=torch.device('cuda', gpu_id))\n        if keep_first:\n            fg = random_matrix[1:][torch.randperm(dim - 1)]\n            random_matrix = torch.cat([random_matrix[0:1], fg], dim=0)\n        else:\n            random_matrix = random_matrix[torch.randperm(dim)]\n        all_matrix.append(random_matrix)\n    return torch.stack(all_matrix, dim=0)\n\n\ndef truncated_normal_(tensor, mean=0, std=.02):\n    size = tensor.shape\n    tmp = tensor.new_empty(size + (4, )).normal_()\n    valid = (tmp < 2) & (tmp > -2)\n    ind = valid.max(-1, keepdim=True)[1]\n    tensor.data.copy_(tmp.gather(-1, ind).squeeze(-1))\n    tensor.data.mul_(std).add_(mean)\n    return tensor\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/utils/meters.py",
    "content": "from __future__ import absolute_import\n\n\nclass AverageMeter(object):\n    \"\"\"Computes and stores the average and current value\"\"\"\n    def __init__(self, momentum=0.999):\n        self.val = 0\n        self.avg = 0\n        self.sum = 0\n        self.count = 0\n        self.long_count = 0\n        self.momentum = momentum\n        self.moving_avg = 0\n\n    def reset(self):\n        self.val = 0\n        self.avg = 0\n        self.sum = 0\n        self.count = 0\n\n    def update(self, val, n=1):\n        if self.long_count == 0:\n            self.moving_avg = val\n        else:\n            momentum = min(self.momentum, 1. - 1. / self.long_count)\n            self.moving_avg = self.moving_avg * momentum + val * (1 - momentum)\n        self.val = val\n        self.sum += val * n\n        self.count += n\n        self.long_count += n\n        self.avg = self.sum / self.count\n"
  },
  {
    "path": "VPS_Module/detectron2/aot_modules/utils/metric.py",
    "content": "import torch\n\n\ndef pytorch_iou(pred, target, obj_num, epsilon=1e-6):\n    '''\n    pred: [bs, h, w]\n    target: [bs, h, w]\n    obj_num: [bs]\n    '''\n    bs = pred.size(0)\n    all_iou = []\n    for idx in range(bs):\n        now_pred = pred[idx].unsqueeze(0)\n        now_target = target[idx].unsqueeze(0)\n        now_obj_num = obj_num[idx]\n\n        obj_ids = torch.arange(0, now_obj_num + 1,\n                               device=now_pred.device).int().view(-1, 1, 1)\n        if obj_ids.size(0) == 1:  # only contain background\n            continue\n        else:\n            obj_ids = obj_ids[1:]\n            now_pred = (now_pred == obj_ids).float()\n            now_target = (now_target == obj_ids).float()\n\n            intersection = (now_pred * now_target).sum((1, 2))\n            union = ((now_pred + now_target) > 0).float().sum((1, 2))\n\n            now_iou = (intersection + epsilon) / (union + epsilon)\n\n            all_iou.append(now_iou.mean())\n    if len(all_iou) > 0:\n        all_iou = torch.stack(all_iou).mean()\n    else:\n        all_iou = torch.ones((1), device=pred.device)\n    return all_iou\n"
  },
  {
    "path": "VPS_Module/detectron2/checkpoint/__init__.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n# File:\n\n\nfrom . import catalog as _UNUSED  # register the handler\nfrom .detection_checkpoint import DetectionCheckpointer\nfrom fvcore.common.checkpoint import Checkpointer, PeriodicCheckpointer\n\n__all__ = [\"Checkpointer\", \"PeriodicCheckpointer\", \"DetectionCheckpointer\"]\n"
  },
  {
    "path": "VPS_Module/detectron2/checkpoint/c2_model_loading.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport copy\nimport logging\nimport re\nfrom typing import Dict, List\nimport torch\nfrom tabulate import tabulate\n\n\ndef convert_basic_c2_names(original_keys):\n    \"\"\"\n    Apply some basic name conversion to names in C2 weights.\n    It only deals with typical backbone models.\n\n    Args:\n        original_keys (list[str]):\n    Returns:\n        list[str]: The same number of strings matching those in original_keys.\n    \"\"\"\n    layer_keys = copy.deepcopy(original_keys)\n    layer_keys = [\n        {\"pred_b\": \"linear_b\", \"pred_w\": \"linear_w\"}.get(k, k) for k in layer_keys\n    ]  # some hard-coded mappings\n\n    layer_keys = [k.replace(\"_\", \".\") for k in layer_keys]\n    layer_keys = [re.sub(\"\\\\.b$\", \".bias\", k) for k in layer_keys]\n    layer_keys = [re.sub(\"\\\\.w$\", \".weight\", k) for k in layer_keys]\n    # Uniform both bn and gn names to \"norm\"\n    layer_keys = [re.sub(\"bn\\\\.s$\", \"norm.weight\", k) for k in layer_keys]\n    layer_keys = [re.sub(\"bn\\\\.bias$\", \"norm.bias\", k) for k in layer_keys]\n    layer_keys = [re.sub(\"bn\\\\.rm\", \"norm.running_mean\", k) for k in layer_keys]\n    layer_keys = [re.sub(\"bn\\\\.running.mean$\", \"norm.running_mean\", k) for k in layer_keys]\n    layer_keys = [re.sub(\"bn\\\\.riv$\", \"norm.running_var\", k) for k in layer_keys]\n    layer_keys = [re.sub(\"bn\\\\.running.var$\", \"norm.running_var\", k) for k in layer_keys]\n    layer_keys = [re.sub(\"bn\\\\.gamma$\", \"norm.weight\", k) for k in layer_keys]\n    layer_keys = [re.sub(\"bn\\\\.beta$\", \"norm.bias\", k) for k in layer_keys]\n    layer_keys = [re.sub(\"gn\\\\.s$\", \"norm.weight\", k) for k in layer_keys]\n    layer_keys = [re.sub(\"gn\\\\.bias$\", \"norm.bias\", k) for k in layer_keys]\n\n    # stem\n    layer_keys = [re.sub(\"^res\\\\.conv1\\\\.norm\\\\.\", \"conv1.norm.\", k) for k in layer_keys]\n    # to avoid mis-matching with \"conv1\" in other components (e.g. detection head)\n    layer_keys = [re.sub(\"^conv1\\\\.\", \"stem.conv1.\", k) for k in layer_keys]\n\n    # layer1-4 is used by torchvision, however we follow the C2 naming strategy (res2-5)\n    # layer_keys = [re.sub(\"^res2.\", \"layer1.\", k) for k in layer_keys]\n    # layer_keys = [re.sub(\"^res3.\", \"layer2.\", k) for k in layer_keys]\n    # layer_keys = [re.sub(\"^res4.\", \"layer3.\", k) for k in layer_keys]\n    # layer_keys = [re.sub(\"^res5.\", \"layer4.\", k) for k in layer_keys]\n\n    # blocks\n    layer_keys = [k.replace(\".branch1.\", \".shortcut.\") for k in layer_keys]\n    layer_keys = [k.replace(\".branch2a.\", \".conv1.\") for k in layer_keys]\n    layer_keys = [k.replace(\".branch2b.\", \".conv2.\") for k in layer_keys]\n    layer_keys = [k.replace(\".branch2c.\", \".conv3.\") for k in layer_keys]\n\n    # DensePose substitutions\n    layer_keys = [re.sub(\"^body.conv.fcn\", \"body_conv_fcn\", k) for k in layer_keys]\n    layer_keys = [k.replace(\"AnnIndex.lowres\", \"ann_index_lowres\") for k in layer_keys]\n    layer_keys = [k.replace(\"Index.UV.lowres\", \"index_uv_lowres\") for k in layer_keys]\n    layer_keys = [k.replace(\"U.lowres\", \"u_lowres\") for k in layer_keys]\n    layer_keys = [k.replace(\"V.lowres\", \"v_lowres\") for k in layer_keys]\n    return layer_keys\n\n\ndef convert_c2_detectron_names(weights):\n    \"\"\"\n    Map Caffe2 Detectron weight names to Detectron2 names.\n\n    Args:\n        weights (dict): name -> tensor\n\n    Returns:\n        dict: detectron2 names -> tensor\n        dict: detectron2 names -> C2 names\n    \"\"\"\n    logger = logging.getLogger(__name__)\n    logger.info(\"Renaming Caffe2 weights ......\")\n    original_keys = sorted(weights.keys())\n    layer_keys = copy.deepcopy(original_keys)\n\n    layer_keys = convert_basic_c2_names(layer_keys)\n\n    # --------------------------------------------------------------------------\n    # RPN hidden representation conv\n    # --------------------------------------------------------------------------\n    # FPN case\n    # In the C2 model, the RPN hidden layer conv is defined for FPN level 2 and then\n    # shared for all other levels, hence the appearance of \"fpn2\"\n    layer_keys = [\n        k.replace(\"conv.rpn.fpn2\", \"proposal_generator.rpn_head.conv\") for k in layer_keys\n    ]\n    # Non-FPN case\n    layer_keys = [k.replace(\"conv.rpn\", \"proposal_generator.rpn_head.conv\") for k in layer_keys]\n\n    # --------------------------------------------------------------------------\n    # RPN box transformation conv\n    # --------------------------------------------------------------------------\n    # FPN case (see note above about \"fpn2\")\n    layer_keys = [\n        k.replace(\"rpn.bbox.pred.fpn2\", \"proposal_generator.rpn_head.anchor_deltas\")\n        for k in layer_keys\n    ]\n    layer_keys = [\n        k.replace(\"rpn.cls.logits.fpn2\", \"proposal_generator.rpn_head.objectness_logits\")\n        for k in layer_keys\n    ]\n    # Non-FPN case\n    layer_keys = [\n        k.replace(\"rpn.bbox.pred\", \"proposal_generator.rpn_head.anchor_deltas\") for k in layer_keys\n    ]\n    layer_keys = [\n        k.replace(\"rpn.cls.logits\", \"proposal_generator.rpn_head.objectness_logits\")\n        for k in layer_keys\n    ]\n\n    # --------------------------------------------------------------------------\n    # Fast R-CNN box head\n    # --------------------------------------------------------------------------\n    layer_keys = [re.sub(\"^bbox\\\\.pred\", \"bbox_pred\", k) for k in layer_keys]\n    layer_keys = [re.sub(\"^cls\\\\.score\", \"cls_score\", k) for k in layer_keys]\n    layer_keys = [re.sub(\"^fc6\\\\.\", \"box_head.fc1.\", k) for k in layer_keys]\n    layer_keys = [re.sub(\"^fc7\\\\.\", \"box_head.fc2.\", k) for k in layer_keys]\n    # 4conv1fc head tensor names: head_conv1_w, head_conv1_gn_s\n    layer_keys = [re.sub(\"^head\\\\.conv\", \"box_head.conv\", k) for k in layer_keys]\n\n    # --------------------------------------------------------------------------\n    # FPN lateral and output convolutions\n    # --------------------------------------------------------------------------\n    def fpn_map(name):\n        \"\"\"\n        Look for keys with the following patterns:\n        1) Starts with \"fpn.inner.\"\n           Example: \"fpn.inner.res2.2.sum.lateral.weight\"\n           Meaning: These are lateral pathway convolutions\n        2) Starts with \"fpn.res\"\n           Example: \"fpn.res2.2.sum.weight\"\n           Meaning: These are FPN output convolutions\n        \"\"\"\n        splits = name.split(\".\")\n        norm = \".norm\" if \"norm\" in splits else \"\"\n        if name.startswith(\"fpn.inner.\"):\n            # splits example: ['fpn', 'inner', 'res2', '2', 'sum', 'lateral', 'weight']\n            stage = int(splits[2][len(\"res\") :])\n            return \"fpn_lateral{}{}.{}\".format(stage, norm, splits[-1])\n        elif name.startswith(\"fpn.res\"):\n            # splits example: ['fpn', 'res2', '2', 'sum', 'weight']\n            stage = int(splits[1][len(\"res\") :])\n            return \"fpn_output{}{}.{}\".format(stage, norm, splits[-1])\n        return name\n\n    layer_keys = [fpn_map(k) for k in layer_keys]\n\n    # --------------------------------------------------------------------------\n    # Mask R-CNN mask head\n    # --------------------------------------------------------------------------\n    # roi_heads.StandardROIHeads case\n    layer_keys = [k.replace(\".[mask].fcn\", \"mask_head.mask_fcn\") for k in layer_keys]\n    layer_keys = [re.sub(\"^\\\\.mask\\\\.fcn\", \"mask_head.mask_fcn\", k) for k in layer_keys]\n    layer_keys = [k.replace(\"mask.fcn.logits\", \"mask_head.predictor\") for k in layer_keys]\n    # roi_heads.Res5ROIHeads case\n    layer_keys = [k.replace(\"conv5.mask\", \"mask_head.deconv\") for k in layer_keys]\n\n    # --------------------------------------------------------------------------\n    # Keypoint R-CNN head\n    # --------------------------------------------------------------------------\n    # interestingly, the keypoint head convs have blob names that are simply \"conv_fcnX\"\n    layer_keys = [k.replace(\"conv.fcn\", \"roi_heads.keypoint_head.conv_fcn\") for k in layer_keys]\n    layer_keys = [\n        k.replace(\"kps.score.lowres\", \"roi_heads.keypoint_head.score_lowres\") for k in layer_keys\n    ]\n    layer_keys = [k.replace(\"kps.score.\", \"roi_heads.keypoint_head.score.\") for k in layer_keys]\n\n    # --------------------------------------------------------------------------\n    # Done with replacements\n    # --------------------------------------------------------------------------\n    assert len(set(layer_keys)) == len(layer_keys)\n    assert len(original_keys) == len(layer_keys)\n\n    new_weights = {}\n    new_keys_to_original_keys = {}\n    for orig, renamed in zip(original_keys, layer_keys):\n        new_keys_to_original_keys[renamed] = orig\n        if renamed.startswith(\"bbox_pred.\") or renamed.startswith(\"mask_head.predictor.\"):\n            # remove the meaningless prediction weight for background class\n            new_start_idx = 4 if renamed.startswith(\"bbox_pred.\") else 1\n            new_weights[renamed] = weights[orig][new_start_idx:]\n            logger.info(\n                \"Remove prediction weight for background class in {}. The shape changes from \"\n                \"{} to {}.\".format(\n                    renamed, tuple(weights[orig].shape), tuple(new_weights[renamed].shape)\n                )\n            )\n        elif renamed.startswith(\"cls_score.\"):\n            # move weights of bg class from original index 0 to last index\n            logger.info(\n                \"Move classification weights for background class in {} from index 0 to \"\n                \"index {}.\".format(renamed, weights[orig].shape[0] - 1)\n            )\n            new_weights[renamed] = torch.cat([weights[orig][1:], weights[orig][:1]])\n        else:\n            new_weights[renamed] = weights[orig]\n\n    return new_weights, new_keys_to_original_keys\n\n\n# Note the current matching is not symmetric.\n# it assumes model_state_dict will have longer names.\ndef align_and_update_state_dicts(model_state_dict, ckpt_state_dict, c2_conversion=True):\n    \"\"\"\n    Match names between the two state-dict, and returns a new chkpt_state_dict with names\n    converted to match model_state_dict with heuristics. The returned dict can be later\n    loaded with fvcore checkpointer.\n    If `c2_conversion==True`, `ckpt_state_dict` is assumed to be a Caffe2\n    model and will be renamed at first.\n\n    Strategy: suppose that the models that we will create will have prefixes appended\n    to each of its keys, for example due to an extra level of nesting that the original\n    pre-trained weights from ImageNet won't contain. For example, model.state_dict()\n    might return backbone[0].body.res2.conv1.weight, while the pre-trained model contains\n    res2.conv1.weight. We thus want to match both parameters together.\n    For that, we look for each model weight, look among all loaded keys if there is one\n    that is a suffix of the current weight name, and use it if that's the case.\n    If multiple matches exist, take the one with longest size\n    of the corresponding name. For example, for the same model as before, the pretrained\n    weight file can contain both res2.conv1.weight, as well as conv1.weight. In this case,\n    we want to match backbone[0].body.conv1.weight to conv1.weight, and\n    backbone[0].body.res2.conv1.weight to res2.conv1.weight.\n    \"\"\"\n    model_keys = sorted(model_state_dict.keys())\n    if c2_conversion:\n        ckpt_state_dict, original_keys = convert_c2_detectron_names(ckpt_state_dict)\n        # original_keys: the name in the original dict (before renaming)\n    else:\n        original_keys = {x: x for x in ckpt_state_dict.keys()}\n    ckpt_keys = sorted(ckpt_state_dict.keys())\n\n    def match(a, b):\n        # Matched ckpt_key should be a complete (starts with '.') suffix.\n        # For example, roi_heads.mesh_head.whatever_conv1 does not match conv1,\n        # but matches whatever_conv1 or mesh_head.whatever_conv1.\n        return a == b or a.endswith(\".\" + b)\n\n    # get a matrix of string matches, where each (i, j) entry correspond to the size of the\n    # ckpt_key string, if it matches\n    match_matrix = [len(j) if match(i, j) else 0 for i in model_keys for j in ckpt_keys]\n    match_matrix = torch.as_tensor(match_matrix).view(len(model_keys), len(ckpt_keys))\n    # use the matched one with longest size in case of multiple matches\n    max_match_size, idxs = match_matrix.max(1)\n    # remove indices that correspond to no-match\n    idxs[max_match_size == 0] = -1\n\n    logger = logging.getLogger(__name__)\n    # matched_pairs (matched checkpoint key --> matched model key)\n    matched_keys = {}\n    result_state_dict = {}\n    for idx_model, idx_ckpt in enumerate(idxs.tolist()):\n        if idx_ckpt == -1:\n            continue\n        key_model = model_keys[idx_model]\n        key_ckpt = ckpt_keys[idx_ckpt]\n        value_ckpt = ckpt_state_dict[key_ckpt]\n        shape_in_model = model_state_dict[key_model].shape\n\n        if shape_in_model != value_ckpt.shape:\n            logger.warning(\n                \"Shape of {} in checkpoint is {}, while shape of {} in model is {}.\".format(\n                    key_ckpt, value_ckpt.shape, key_model, shape_in_model\n                )\n            )\n            logger.warning(\n                \"{} will not be loaded. Please double check and see if this is desired.\".format(\n                    key_ckpt\n                )\n            )\n            continue\n\n        assert key_model not in result_state_dict\n        result_state_dict[key_model] = value_ckpt\n        if key_ckpt in matched_keys:  # already added to matched_keys\n            logger.error(\n                \"Ambiguity found for {} in checkpoint!\"\n                \"It matches at least two keys in the model ({} and {}).\".format(\n                    key_ckpt, key_model, matched_keys[key_ckpt]\n                )\n            )\n            raise ValueError(\"Cannot match one checkpoint key to multiple keys in the model.\")\n\n        matched_keys[key_ckpt] = key_model\n\n    # logging:\n    matched_model_keys = sorted(matched_keys.values())\n    if len(matched_model_keys) == 0:\n        logger.warning(\"No weights in checkpoint matched with model.\")\n        return ckpt_state_dict\n    common_prefix = _longest_common_prefix(matched_model_keys)\n    rev_matched_keys = {v: k for k, v in matched_keys.items()}\n    original_keys = {k: original_keys[rev_matched_keys[k]] for k in matched_model_keys}\n\n    model_key_groups = _group_keys_by_module(matched_model_keys, original_keys)\n    table = []\n    memo = set()\n    for key_model in matched_model_keys:\n        if key_model in memo:\n            continue\n        if key_model in model_key_groups:\n            group = model_key_groups[key_model]\n            memo |= set(group)\n            shapes = [tuple(model_state_dict[k].shape) for k in group]\n            table.append(\n                (\n                    _longest_common_prefix([k[len(common_prefix) :] for k in group]) + \"*\",\n                    _group_str([original_keys[k] for k in group]),\n                    \" \".join([str(x).replace(\" \", \"\") for x in shapes]),\n                )\n            )\n        else:\n            key_checkpoint = original_keys[key_model]\n            shape = str(tuple(model_state_dict[key_model].shape))\n            table.append((key_model[len(common_prefix) :], key_checkpoint, shape))\n    table_str = tabulate(\n        table, tablefmt=\"pipe\", headers=[\"Names in Model\", \"Names in Checkpoint\", \"Shapes\"]\n    )\n    logger.info(\n        \"Following weights matched with \"\n        + (f\"submodule {common_prefix[:-1]}\" if common_prefix else \"model\")\n        + \":\\n\"\n        + table_str\n    )\n\n    unmatched_ckpt_keys = [k for k in ckpt_keys if k not in set(matched_keys.keys())]\n    for k in unmatched_ckpt_keys:\n        result_state_dict[k] = ckpt_state_dict[k]\n    return result_state_dict\n\n\ndef _group_keys_by_module(keys: List[str], original_names: Dict[str, str]):\n    \"\"\"\n    Params in the same submodule are grouped together.\n\n    Args:\n        keys: names of all parameters\n        original_names: mapping from parameter name to their name in the checkpoint\n\n    Returns:\n        dict[name -> all other names in the same group]\n    \"\"\"\n\n    def _submodule_name(key):\n        pos = key.rfind(\".\")\n        if pos < 0:\n            return None\n        prefix = key[: pos + 1]\n        return prefix\n\n    all_submodules = [_submodule_name(k) for k in keys]\n    all_submodules = [x for x in all_submodules if x]\n    all_submodules = sorted(all_submodules, key=len)\n\n    ret = {}\n    for prefix in all_submodules:\n        group = [k for k in keys if k.startswith(prefix)]\n        if len(group) <= 1:\n            continue\n        original_name_lcp = _longest_common_prefix_str([original_names[k] for k in group])\n        if len(original_name_lcp) == 0:\n            # don't group weights if original names don't share prefix\n            continue\n\n        for k in group:\n            if k in ret:\n                continue\n            ret[k] = group\n    return ret\n\n\ndef _longest_common_prefix(names: List[str]) -> str:\n    \"\"\"\n    [\"abc.zfg\", \"abc.zef\"] -> \"abc.\"\n    \"\"\"\n    names = [n.split(\".\") for n in names]\n    m1, m2 = min(names), max(names)\n    ret = [a for a, b in zip(m1, m2) if a == b]\n    ret = \".\".join(ret) + \".\" if len(ret) else \"\"\n    return ret\n\n\ndef _longest_common_prefix_str(names: List[str]) -> str:\n    m1, m2 = min(names), max(names)\n    lcp = [a for a, b in zip(m1, m2) if a == b]\n    lcp = \"\".join(lcp)\n    return lcp\n\n\ndef _group_str(names: List[str]) -> str:\n    \"\"\"\n    Turn \"common1\", \"common2\", \"common3\" into \"common{1,2,3}\"\n    \"\"\"\n    lcp = _longest_common_prefix_str(names)\n    rest = [x[len(lcp) :] for x in names]\n    rest = \"{\" + \",\".join(rest) + \"}\"\n    ret = lcp + rest\n\n    # add some simplification for BN specifically\n    ret = ret.replace(\"bn_{beta,running_mean,running_var,gamma}\", \"bn_*\")\n    ret = ret.replace(\"bn_beta,bn_running_mean,bn_running_var,bn_gamma\", \"bn_*\")\n    return ret\n"
  },
  {
    "path": "VPS_Module/detectron2/checkpoint/catalog.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport logging\n\nfrom detectron2.utils.file_io import PathHandler, PathManager\n\n\nclass ModelCatalog(object):\n    \"\"\"\n    Store mappings from names to third-party models.\n    \"\"\"\n\n    S3_C2_DETECTRON_PREFIX = \"https://dl.fbaipublicfiles.com/detectron\"\n\n    # MSRA models have STRIDE_IN_1X1=True. False otherwise.\n    # NOTE: all BN models here have fused BN into an affine layer.\n    # As a result, you should only load them to a model with \"FrozenBN\".\n    # Loading them to a model with regular BN or SyncBN is wrong.\n    # Even when loaded to FrozenBN, it is still different from affine by an epsilon,\n    # which should be negligible for training.\n    # NOTE: all models here uses PIXEL_STD=[1,1,1]\n    # NOTE: Most of the BN models here are no longer used. We use the\n    # re-converted pre-trained models under detectron2 model zoo instead.\n    C2_IMAGENET_MODELS = {\n        \"MSRA/R-50\": \"ImageNetPretrained/MSRA/R-50.pkl\",\n        \"MSRA/R-101\": \"ImageNetPretrained/MSRA/R-101.pkl\",\n        \"FAIR/R-50-GN\": \"ImageNetPretrained/47261647/R-50-GN.pkl\",\n        \"FAIR/R-101-GN\": \"ImageNetPretrained/47592356/R-101-GN.pkl\",\n        \"FAIR/X-101-32x8d\": \"ImageNetPretrained/20171220/X-101-32x8d.pkl\",\n        \"FAIR/X-101-64x4d\": \"ImageNetPretrained/FBResNeXt/X-101-64x4d.pkl\",\n        \"FAIR/X-152-32x8d-IN5k\": \"ImageNetPretrained/25093814/X-152-32x8d-IN5k.pkl\",\n    }\n\n    C2_DETECTRON_PATH_FORMAT = (\n        \"{prefix}/{url}/output/train/{dataset}/{type}/model_final.pkl\"  # noqa B950\n    )\n\n    C2_DATASET_COCO = \"coco_2014_train%3Acoco_2014_valminusminival\"\n    C2_DATASET_COCO_KEYPOINTS = \"keypoints_coco_2014_train%3Akeypoints_coco_2014_valminusminival\"\n\n    # format: {model_name} -> part of the url\n    C2_DETECTRON_MODELS = {\n        \"35857197/e2e_faster_rcnn_R-50-C4_1x\": \"35857197/12_2017_baselines/e2e_faster_rcnn_R-50-C4_1x.yaml.01_33_49.iAX0mXvW\",  # noqa B950\n        \"35857345/e2e_faster_rcnn_R-50-FPN_1x\": \"35857345/12_2017_baselines/e2e_faster_rcnn_R-50-FPN_1x.yaml.01_36_30.cUF7QR7I\",  # noqa B950\n        \"35857890/e2e_faster_rcnn_R-101-FPN_1x\": \"35857890/12_2017_baselines/e2e_faster_rcnn_R-101-FPN_1x.yaml.01_38_50.sNxI7sX7\",  # noqa B950\n        \"36761737/e2e_faster_rcnn_X-101-32x8d-FPN_1x\": \"36761737/12_2017_baselines/e2e_faster_rcnn_X-101-32x8d-FPN_1x.yaml.06_31_39.5MIHi1fZ\",  # noqa B950\n        \"35858791/e2e_mask_rcnn_R-50-C4_1x\": \"35858791/12_2017_baselines/e2e_mask_rcnn_R-50-C4_1x.yaml.01_45_57.ZgkA7hPB\",  # noqa B950\n        \"35858933/e2e_mask_rcnn_R-50-FPN_1x\": \"35858933/12_2017_baselines/e2e_mask_rcnn_R-50-FPN_1x.yaml.01_48_14.DzEQe4wC\",  # noqa B950\n        \"35861795/e2e_mask_rcnn_R-101-FPN_1x\": \"35861795/12_2017_baselines/e2e_mask_rcnn_R-101-FPN_1x.yaml.02_31_37.KqyEK4tT\",  # noqa B950\n        \"36761843/e2e_mask_rcnn_X-101-32x8d-FPN_1x\": \"36761843/12_2017_baselines/e2e_mask_rcnn_X-101-32x8d-FPN_1x.yaml.06_35_59.RZotkLKI\",  # noqa B950\n        \"48616381/e2e_mask_rcnn_R-50-FPN_2x_gn\": \"GN/48616381/04_2018_gn_baselines/e2e_mask_rcnn_R-50-FPN_2x_gn_0416.13_23_38.bTlTI97Q\",  # noqa B950\n        \"37697547/e2e_keypoint_rcnn_R-50-FPN_1x\": \"37697547/12_2017_baselines/e2e_keypoint_rcnn_R-50-FPN_1x.yaml.08_42_54.kdzV35ao\",  # noqa B950\n        \"35998355/rpn_R-50-C4_1x\": \"35998355/12_2017_baselines/rpn_R-50-C4_1x.yaml.08_00_43.njH5oD9L\",  # noqa B950\n        \"35998814/rpn_R-50-FPN_1x\": \"35998814/12_2017_baselines/rpn_R-50-FPN_1x.yaml.08_06_03.Axg0r179\",  # noqa B950\n        \"36225147/fast_R-50-FPN_1x\": \"36225147/12_2017_baselines/fast_rcnn_R-50-FPN_1x.yaml.08_39_09.L3obSdQ2\",  # noqa B950\n    }\n\n    @staticmethod\n    def get(name):\n        if name.startswith(\"Caffe2Detectron/COCO\"):\n            return ModelCatalog._get_c2_detectron_baseline(name)\n        if name.startswith(\"ImageNetPretrained/\"):\n            return ModelCatalog._get_c2_imagenet_pretrained(name)\n        raise RuntimeError(\"model not present in the catalog: {}\".format(name))\n\n    @staticmethod\n    def _get_c2_imagenet_pretrained(name):\n        prefix = ModelCatalog.S3_C2_DETECTRON_PREFIX\n        name = name[len(\"ImageNetPretrained/\") :]\n        name = ModelCatalog.C2_IMAGENET_MODELS[name]\n        url = \"/\".join([prefix, name])\n        return url\n\n    @staticmethod\n    def _get_c2_detectron_baseline(name):\n        name = name[len(\"Caffe2Detectron/COCO/\") :]\n        url = ModelCatalog.C2_DETECTRON_MODELS[name]\n        if \"keypoint_rcnn\" in name:\n            dataset = ModelCatalog.C2_DATASET_COCO_KEYPOINTS\n        else:\n            dataset = ModelCatalog.C2_DATASET_COCO\n\n        if \"35998355/rpn_R-50-C4_1x\" in name:\n            # this one model is somehow different from others ..\n            type = \"rpn\"\n        else:\n            type = \"generalized_rcnn\"\n\n        # Detectron C2 models are stored in the structure defined in `C2_DETECTRON_PATH_FORMAT`.\n        url = ModelCatalog.C2_DETECTRON_PATH_FORMAT.format(\n            prefix=ModelCatalog.S3_C2_DETECTRON_PREFIX, url=url, type=type, dataset=dataset\n        )\n        return url\n\n\nclass ModelCatalogHandler(PathHandler):\n    \"\"\"\n    Resolve URL like catalog://.\n    \"\"\"\n\n    PREFIX = \"catalog://\"\n\n    def _get_supported_prefixes(self):\n        return [self.PREFIX]\n\n    def _get_local_path(self, path, **kwargs):\n        logger = logging.getLogger(__name__)\n        catalog_path = ModelCatalog.get(path[len(self.PREFIX) :])\n        logger.info(\"Catalog entry {} points to {}\".format(path, catalog_path))\n        return PathManager.get_local_path(catalog_path, **kwargs)\n\n    def _open(self, path, mode=\"r\", **kwargs):\n        return PathManager.open(self._get_local_path(path), mode, **kwargs)\n\n\nPathManager.register_handler(ModelCatalogHandler())\n"
  },
  {
    "path": "VPS_Module/detectron2/checkpoint/detection_checkpoint.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport logging\nimport os\nimport pickle\nimport torch\nfrom fvcore.common.checkpoint import Checkpointer\nfrom torch.nn.parallel import DistributedDataParallel\n\nimport detectron2.utils.comm as comm\nfrom detectron2.utils.file_io import PathManager\n\nfrom .c2_model_loading import align_and_update_state_dicts\n\n\nclass DetectionCheckpointer(Checkpointer):\n    \"\"\"\n    Same as :class:`Checkpointer`, but is able to:\n    1. handle models in detectron & detectron2 model zoo, and apply conversions for legacy models.\n    2. correctly load checkpoints that are only available on the master worker\n    \"\"\"\n\n    def __init__(self, model, save_dir=\"\", *, save_to_disk=None, **checkpointables):\n        is_main_process = comm.is_main_process()\n        super().__init__(\n            model,\n            save_dir,\n            save_to_disk=is_main_process if save_to_disk is None else save_to_disk,\n            **checkpointables,\n        )\n        self.path_manager = PathManager\n\n    def load(self, path, *args, **kwargs):\n        need_sync = False\n\n        if path and isinstance(self.model, DistributedDataParallel):\n            logger = logging.getLogger(__name__)\n            path = self.path_manager.get_local_path(path)\n            has_file = os.path.isfile(path)\n            all_has_file = comm.all_gather(has_file)\n            if not all_has_file[0]:\n                raise OSError(f\"File {path} not found on main worker.\")\n            if not all(all_has_file):\n                logger.warning(\n                    f\"Not all workers can read checkpoint {path}. \"\n                    \"Training may fail to fully resume.\"\n                )\n                # TODO: broadcast the checkpoint file contents from main\n                # worker, and load from it instead.\n                need_sync = True\n            if not has_file:\n                path = None  # don't load if not readable\n        ret = super().load(path, *args, **kwargs)\n\n        if need_sync:\n            logger.info(\"Broadcasting model states from main worker ...\")\n            self.model._sync_params_and_buffers()\n        return ret\n\n    def _load_file(self, filename):\n        if filename.endswith(\".pkl\"):\n            with PathManager.open(filename, \"rb\") as f:\n                data = pickle.load(f, encoding=\"latin1\")\n            if \"model\" in data and \"__author__\" in data:\n                # file is in Detectron2 model zoo format\n                self.logger.info(\"Reading a file from '{}'\".format(data[\"__author__\"]))\n                return data\n            else:\n                # assume file is from Caffe2 / Detectron1 model zoo\n                if \"blobs\" in data:\n                    # Detection models have \"blobs\", but ImageNet models don't\n                    data = data[\"blobs\"]\n                data = {k: v for k, v in data.items() if not k.endswith(\"_momentum\")}\n                return {\"model\": data, \"__author__\": \"Caffe2\", \"matching_heuristics\": True}\n        elif filename.endswith(\".pyth\"):\n            # assume file is from pycls; no one else seems to use the \".pyth\" extension\n            with PathManager.open(filename, \"rb\") as f:\n                data = torch.load(f)\n            assert (\n                \"model_state\" in data\n            ), f\"Cannot load .pyth file {filename}; pycls checkpoints must contain 'model_state'.\"\n            model_state = {\n                k: v\n                for k, v in data[\"model_state\"].items()\n                if not k.endswith(\"num_batches_tracked\")\n            }\n            return {\"model\": model_state, \"__author__\": \"pycls\", \"matching_heuristics\": True}\n\n        loaded = super()._load_file(filename)  # load native pth checkpoint\n        if \"model\" not in loaded:\n            loaded = {\"model\": loaded}\n        return loaded\n\n    def _load_model(self, checkpoint):\n        if checkpoint.get(\"matching_heuristics\", False):\n            self._convert_ndarray_to_tensor(checkpoint[\"model\"])\n            # convert weights by name-matching heuristics\n            checkpoint[\"model\"] = align_and_update_state_dicts(\n                self.model.state_dict(),\n                checkpoint[\"model\"],\n                c2_conversion=checkpoint.get(\"__author__\", None) == \"Caffe2\",\n            )\n        # for non-caffe2 models, use standard ways to load it\n        incompatible = super()._load_model(checkpoint)\n\n        model_buffers = dict(self.model.named_buffers(recurse=False))\n        for k in [\"pixel_mean\", \"pixel_std\"]:\n            # Ignore missing key message about pixel_mean/std.\n            # Though they may be missing in old checkpoints, they will be correctly\n            # initialized from config anyway.\n            if k in model_buffers:\n                try:\n                    incompatible.missing_keys.remove(k)\n                except ValueError:\n                    pass\n        for k in incompatible.unexpected_keys[:]:\n            # Ignore unexpected keys about cell anchors. They exist in old checkpoints\n            # but now they are non-persistent buffers and will not be in new checkpoints.\n            if \"anchor_generator.cell_anchors\" in k:\n                incompatible.unexpected_keys.remove(k)\n        return incompatible\n"
  },
  {
    "path": "VPS_Module/detectron2/config/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom .compat import downgrade_config, upgrade_config\nfrom .config import CfgNode, get_cfg, global_cfg, set_global_cfg, configurable\nfrom .instantiate import instantiate\nfrom .lazy import LazyCall, LazyConfig\n\n__all__ = [\n    \"CfgNode\",\n    \"get_cfg\",\n    \"global_cfg\",\n    \"set_global_cfg\",\n    \"downgrade_config\",\n    \"upgrade_config\",\n    \"configurable\",\n    \"instantiate\",\n    \"LazyCall\",\n    \"LazyConfig\",\n]\n\n\nfrom detectron2.utils.env import fixup_module_metadata\n\nfixup_module_metadata(__name__, globals(), __all__)\ndel fixup_module_metadata\n"
  },
  {
    "path": "VPS_Module/detectron2/config/compat.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\"\"\"\nBackward compatibility of configs.\n\nInstructions to bump version:\n+ It's not needed to bump version if new keys are added.\n  It's only needed when backward-incompatible changes happen\n  (i.e., some existing keys disappear, or the meaning of a key changes)\n+ To bump version, do the following:\n    1. Increment _C.VERSION in defaults.py\n    2. Add a converter in this file.\n\n      Each ConverterVX has a function \"upgrade\" which in-place upgrades config from X-1 to X,\n      and a function \"downgrade\" which in-place downgrades config from X to X-1\n\n      In each function, VERSION is left unchanged.\n\n      Each converter assumes that its input has the relevant keys\n      (i.e., the input is not a partial config).\n    3. Run the tests (test_config.py) to make sure the upgrade & downgrade\n       functions are consistent.\n\"\"\"\n\nimport logging\nfrom typing import List, Optional, Tuple\n\nfrom .config import CfgNode as CN\nfrom .defaults import _C\n\n__all__ = [\"upgrade_config\", \"downgrade_config\"]\n\n\ndef upgrade_config(cfg: CN, to_version: Optional[int] = None) -> CN:\n    \"\"\"\n    Upgrade a config from its current version to a newer version.\n\n    Args:\n        cfg (CfgNode):\n        to_version (int): defaults to the latest version.\n    \"\"\"\n    cfg = cfg.clone()\n    if to_version is None:\n        to_version = _C.VERSION\n\n    assert cfg.VERSION <= to_version, \"Cannot upgrade from v{} to v{}!\".format(\n        cfg.VERSION, to_version\n    )\n    for k in range(cfg.VERSION, to_version):\n        converter = globals()[\"ConverterV\" + str(k + 1)]\n        converter.upgrade(cfg)\n        cfg.VERSION = k + 1\n    return cfg\n\n\ndef downgrade_config(cfg: CN, to_version: int) -> CN:\n    \"\"\"\n    Downgrade a config from its current version to an older version.\n\n    Args:\n        cfg (CfgNode):\n        to_version (int):\n\n    Note:\n        A general downgrade of arbitrary configs is not always possible due to the\n        different functionalities in different versions.\n        The purpose of downgrade is only to recover the defaults in old versions,\n        allowing it to load an old partial yaml config.\n        Therefore, the implementation only needs to fill in the default values\n        in the old version when a general downgrade is not possible.\n    \"\"\"\n    cfg = cfg.clone()\n    assert cfg.VERSION >= to_version, \"Cannot downgrade from v{} to v{}!\".format(\n        cfg.VERSION, to_version\n    )\n    for k in range(cfg.VERSION, to_version, -1):\n        converter = globals()[\"ConverterV\" + str(k)]\n        converter.downgrade(cfg)\n        cfg.VERSION = k - 1\n    return cfg\n\n\ndef guess_version(cfg: CN, filename: str) -> int:\n    \"\"\"\n    Guess the version of a partial config where the VERSION field is not specified.\n    Returns the version, or the latest if cannot make a guess.\n\n    This makes it easier for users to migrate.\n    \"\"\"\n    logger = logging.getLogger(__name__)\n\n    def _has(name: str) -> bool:\n        cur = cfg\n        for n in name.split(\".\"):\n            if n not in cur:\n                return False\n            cur = cur[n]\n        return True\n\n    # Most users' partial configs have \"MODEL.WEIGHT\", so guess on it\n    ret = None\n    if _has(\"MODEL.WEIGHT\") or _has(\"TEST.AUG_ON\"):\n        ret = 1\n\n    if ret is not None:\n        logger.warning(\"Config '{}' has no VERSION. Assuming it to be v{}.\".format(filename, ret))\n    else:\n        ret = _C.VERSION\n        logger.warning(\n            \"Config '{}' has no VERSION. Assuming it to be compatible with latest v{}.\".format(\n                filename, ret\n            )\n        )\n    return ret\n\n\ndef _rename(cfg: CN, old: str, new: str) -> None:\n    old_keys = old.split(\".\")\n    new_keys = new.split(\".\")\n\n    def _set(key_seq: List[str], val: str) -> None:\n        cur = cfg\n        for k in key_seq[:-1]:\n            if k not in cur:\n                cur[k] = CN()\n            cur = cur[k]\n        cur[key_seq[-1]] = val\n\n    def _get(key_seq: List[str]) -> CN:\n        cur = cfg\n        for k in key_seq:\n            cur = cur[k]\n        return cur\n\n    def _del(key_seq: List[str]) -> None:\n        cur = cfg\n        for k in key_seq[:-1]:\n            cur = cur[k]\n        del cur[key_seq[-1]]\n        if len(cur) == 0 and len(key_seq) > 1:\n            _del(key_seq[:-1])\n\n    _set(new_keys, _get(old_keys))\n    _del(old_keys)\n\n\nclass _RenameConverter:\n    \"\"\"\n    A converter that handles simple rename.\n    \"\"\"\n\n    RENAME: List[Tuple[str, str]] = []  # list of tuples of (old name, new name)\n\n    @classmethod\n    def upgrade(cls, cfg: CN) -> None:\n        for old, new in cls.RENAME:\n            _rename(cfg, old, new)\n\n    @classmethod\n    def downgrade(cls, cfg: CN) -> None:\n        for old, new in cls.RENAME[::-1]:\n            _rename(cfg, new, old)\n\n\nclass ConverterV1(_RenameConverter):\n    RENAME = [(\"MODEL.RPN_HEAD.NAME\", \"MODEL.RPN.HEAD_NAME\")]\n\n\nclass ConverterV2(_RenameConverter):\n    \"\"\"\n    A large bulk of rename, before public release.\n    \"\"\"\n\n    RENAME = [\n        (\"MODEL.WEIGHT\", \"MODEL.WEIGHTS\"),\n        (\"MODEL.PANOPTIC_FPN.SEMANTIC_LOSS_SCALE\", \"MODEL.SEM_SEG_HEAD.LOSS_WEIGHT\"),\n        (\"MODEL.PANOPTIC_FPN.RPN_LOSS_SCALE\", \"MODEL.RPN.LOSS_WEIGHT\"),\n        (\"MODEL.PANOPTIC_FPN.INSTANCE_LOSS_SCALE\", \"MODEL.PANOPTIC_FPN.INSTANCE_LOSS_WEIGHT\"),\n        (\"MODEL.PANOPTIC_FPN.COMBINE_ON\", \"MODEL.PANOPTIC_FPN.COMBINE.ENABLED\"),\n        (\n            \"MODEL.PANOPTIC_FPN.COMBINE_OVERLAP_THRESHOLD\",\n            \"MODEL.PANOPTIC_FPN.COMBINE.OVERLAP_THRESH\",\n        ),\n        (\n            \"MODEL.PANOPTIC_FPN.COMBINE_STUFF_AREA_LIMIT\",\n            \"MODEL.PANOPTIC_FPN.COMBINE.STUFF_AREA_LIMIT\",\n        ),\n        (\n            \"MODEL.PANOPTIC_FPN.COMBINE_INSTANCES_CONFIDENCE_THRESHOLD\",\n            \"MODEL.PANOPTIC_FPN.COMBINE.INSTANCES_CONFIDENCE_THRESH\",\n        ),\n        (\"MODEL.ROI_HEADS.SCORE_THRESH\", \"MODEL.ROI_HEADS.SCORE_THRESH_TEST\"),\n        (\"MODEL.ROI_HEADS.NMS\", \"MODEL.ROI_HEADS.NMS_THRESH_TEST\"),\n        (\"MODEL.RETINANET.INFERENCE_SCORE_THRESHOLD\", \"MODEL.RETINANET.SCORE_THRESH_TEST\"),\n        (\"MODEL.RETINANET.INFERENCE_TOPK_CANDIDATES\", \"MODEL.RETINANET.TOPK_CANDIDATES_TEST\"),\n        (\"MODEL.RETINANET.INFERENCE_NMS_THRESHOLD\", \"MODEL.RETINANET.NMS_THRESH_TEST\"),\n        (\"TEST.DETECTIONS_PER_IMG\", \"TEST.DETECTIONS_PER_IMAGE\"),\n        (\"TEST.AUG_ON\", \"TEST.AUG.ENABLED\"),\n        (\"TEST.AUG_MIN_SIZES\", \"TEST.AUG.MIN_SIZES\"),\n        (\"TEST.AUG_MAX_SIZE\", \"TEST.AUG.MAX_SIZE\"),\n        (\"TEST.AUG_FLIP\", \"TEST.AUG.FLIP\"),\n    ]\n\n    @classmethod\n    def upgrade(cls, cfg: CN) -> None:\n        super().upgrade(cfg)\n\n        if cfg.MODEL.META_ARCHITECTURE == \"RetinaNet\":\n            _rename(\n                cfg, \"MODEL.RETINANET.ANCHOR_ASPECT_RATIOS\", \"MODEL.ANCHOR_GENERATOR.ASPECT_RATIOS\"\n            )\n            _rename(cfg, \"MODEL.RETINANET.ANCHOR_SIZES\", \"MODEL.ANCHOR_GENERATOR.SIZES\")\n            del cfg[\"MODEL\"][\"RPN\"][\"ANCHOR_SIZES\"]\n            del cfg[\"MODEL\"][\"RPN\"][\"ANCHOR_ASPECT_RATIOS\"]\n        else:\n            _rename(cfg, \"MODEL.RPN.ANCHOR_ASPECT_RATIOS\", \"MODEL.ANCHOR_GENERATOR.ASPECT_RATIOS\")\n            _rename(cfg, \"MODEL.RPN.ANCHOR_SIZES\", \"MODEL.ANCHOR_GENERATOR.SIZES\")\n            del cfg[\"MODEL\"][\"RETINANET\"][\"ANCHOR_SIZES\"]\n            del cfg[\"MODEL\"][\"RETINANET\"][\"ANCHOR_ASPECT_RATIOS\"]\n        del cfg[\"MODEL\"][\"RETINANET\"][\"ANCHOR_STRIDES\"]\n\n    @classmethod\n    def downgrade(cls, cfg: CN) -> None:\n        super().downgrade(cfg)\n\n        _rename(cfg, \"MODEL.ANCHOR_GENERATOR.ASPECT_RATIOS\", \"MODEL.RPN.ANCHOR_ASPECT_RATIOS\")\n        _rename(cfg, \"MODEL.ANCHOR_GENERATOR.SIZES\", \"MODEL.RPN.ANCHOR_SIZES\")\n        cfg.MODEL.RETINANET.ANCHOR_ASPECT_RATIOS = cfg.MODEL.RPN.ANCHOR_ASPECT_RATIOS\n        cfg.MODEL.RETINANET.ANCHOR_SIZES = cfg.MODEL.RPN.ANCHOR_SIZES\n        cfg.MODEL.RETINANET.ANCHOR_STRIDES = []  # this is not used anywhere in any version\n"
  },
  {
    "path": "VPS_Module/detectron2/config/config.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport functools\nimport inspect\nimport logging\nfrom fvcore.common.config import CfgNode as _CfgNode\n\nfrom detectron2.utils.file_io import PathManager\n\n\nclass CfgNode(_CfgNode):\n    \"\"\"\n    The same as `fvcore.common.config.CfgNode`, but different in:\n\n    1. Use unsafe yaml loading by default.\n       Note that this may lead to arbitrary code execution: you must not\n       load a config file from untrusted sources before manually inspecting\n       the content of the file.\n    2. Support config versioning.\n       When attempting to merge an old config, it will convert the old config automatically.\n\n    .. automethod:: clone\n    .. automethod:: freeze\n    .. automethod:: defrost\n    .. automethod:: is_frozen\n    .. automethod:: load_yaml_with_base\n    .. automethod:: merge_from_list\n    .. automethod:: merge_from_other_cfg\n    \"\"\"\n\n    @classmethod\n    def _open_cfg(cls, filename):\n        return PathManager.open(filename, \"r\")\n\n    # Note that the default value of allow_unsafe is changed to True\n    def merge_from_file(self, cfg_filename: str, allow_unsafe: bool = True) -> None:\n        \"\"\"\n        Load content from the given config file and merge it into self.\n\n        Args:\n            cfg_filename: config filename\n            allow_unsafe: allow unsafe yaml syntax\n        \"\"\"\n        assert PathManager.isfile(cfg_filename), f\"Config file '{cfg_filename}' does not exist!\"\n        loaded_cfg = self.load_yaml_with_base(cfg_filename, allow_unsafe=allow_unsafe)\n        loaded_cfg = type(self)(loaded_cfg)\n\n        # defaults.py needs to import CfgNode\n        from .defaults import _C\n\n        latest_ver = _C.VERSION\n        assert (\n            latest_ver == self.VERSION\n        ), \"CfgNode.merge_from_file is only allowed on a config object of latest version!\"\n\n        logger = logging.getLogger(__name__)\n\n        loaded_ver = loaded_cfg.get(\"VERSION\", None)\n        if loaded_ver is None:\n            from .compat import guess_version\n\n            loaded_ver = guess_version(loaded_cfg, cfg_filename)\n        assert loaded_ver <= self.VERSION, \"Cannot merge a v{} config into a v{} config.\".format(\n            loaded_ver, self.VERSION\n        )\n\n        if loaded_ver == self.VERSION:\n            self.merge_from_other_cfg(loaded_cfg)\n        else:\n            # compat.py needs to import CfgNode\n            from .compat import upgrade_config, downgrade_config\n\n            logger.warning(\n                \"Loading an old v{} config file '{}' by automatically upgrading to v{}. \"\n                \"See docs/CHANGELOG.md for instructions to update your files.\".format(\n                    loaded_ver, cfg_filename, self.VERSION\n                )\n            )\n            # To convert, first obtain a full config at an old version\n            old_self = downgrade_config(self, to_version=loaded_ver)\n            old_self.merge_from_other_cfg(loaded_cfg)\n            new_config = upgrade_config(old_self)\n            self.clear()\n            self.update(new_config)\n\n    def dump(self, *args, **kwargs):\n        \"\"\"\n        Returns:\n            str: a yaml string representation of the config\n        \"\"\"\n        # to make it show up in docs\n        return super().dump(*args, **kwargs)\n\n\nglobal_cfg = CfgNode()\n\n\ndef get_cfg() -> CfgNode:\n    \"\"\"\n    Get a copy of the default config.\n\n    Returns:\n        a detectron2 CfgNode instance.\n    \"\"\"\n    from .defaults import _C\n\n    return _C.clone()\n\n\ndef set_global_cfg(cfg: CfgNode) -> None:\n    \"\"\"\n    Let the global config point to the given cfg.\n\n    Assume that the given \"cfg\" has the key \"KEY\", after calling\n    `set_global_cfg(cfg)`, the key can be accessed by:\n    ::\n        from detectron2.config import global_cfg\n        print(global_cfg.KEY)\n\n    By using a hacky global config, you can access these configs anywhere,\n    without having to pass the config object or the values deep into the code.\n    This is a hacky feature introduced for quick prototyping / research exploration.\n    \"\"\"\n    global global_cfg\n    global_cfg.clear()\n    global_cfg.update(cfg)\n\n\ndef configurable(init_func=None, *, from_config=None):\n    \"\"\"\n    Decorate a function or a class's __init__ method so that it can be called\n    with a :class:`CfgNode` object using a :func:`from_config` function that translates\n    :class:`CfgNode` to arguments.\n\n    Examples:\n    ::\n        # Usage 1: Decorator on __init__:\n        class A:\n            @configurable\n            def __init__(self, a, b=2, c=3):\n                pass\n\n            @classmethod\n            def from_config(cls, cfg):   # 'cfg' must be the first argument\n                # Returns kwargs to be passed to __init__\n                return {\"a\": cfg.A, \"b\": cfg.B}\n\n        a1 = A(a=1, b=2)  # regular construction\n        a2 = A(cfg)       # construct with a cfg\n        a3 = A(cfg, b=3, c=4)  # construct with extra overwrite\n\n        # Usage 2: Decorator on any function. Needs an extra from_config argument:\n        @configurable(from_config=lambda cfg: {\"a: cfg.A, \"b\": cfg.B})\n        def a_func(a, b=2, c=3):\n            pass\n\n        a1 = a_func(a=1, b=2)  # regular call\n        a2 = a_func(cfg)       # call with a cfg\n        a3 = a_func(cfg, b=3, c=4)  # call with extra overwrite\n\n    Args:\n        init_func (callable): a class's ``__init__`` method in usage 1. The\n            class must have a ``from_config`` classmethod which takes `cfg` as\n            the first argument.\n        from_config (callable): the from_config function in usage 2. It must take `cfg`\n            as its first argument.\n    \"\"\"\n\n    if init_func is not None:\n        assert (\n            inspect.isfunction(init_func)\n            and from_config is None\n            and init_func.__name__ == \"__init__\"\n        ), \"Incorrect use of @configurable. Check API documentation for examples.\"\n\n        @functools.wraps(init_func)\n        def wrapped(self, *args, **kwargs):\n            try:\n                from_config_func = type(self).from_config\n            except AttributeError as e:\n                raise AttributeError(\n                    \"Class with @configurable must have a 'from_config' classmethod.\"\n                ) from e\n            if not inspect.ismethod(from_config_func):\n                raise TypeError(\"Class with @configurable must have a 'from_config' classmethod.\")\n\n            if _called_with_cfg(*args, **kwargs):\n                explicit_args = _get_args_from_config(from_config_func, *args, **kwargs)\n                init_func(self, **explicit_args)\n            else:\n                init_func(self, *args, **kwargs)\n\n        return wrapped\n\n    else:\n        if from_config is None:\n            return configurable  # @configurable() is made equivalent to @configurable\n        assert inspect.isfunction(\n            from_config\n        ), \"from_config argument of configurable must be a function!\"\n\n        def wrapper(orig_func):\n            @functools.wraps(orig_func)\n            def wrapped(*args, **kwargs):\n                if _called_with_cfg(*args, **kwargs):\n                    explicit_args = _get_args_from_config(from_config, *args, **kwargs)\n                    return orig_func(**explicit_args)\n                else:\n                    return orig_func(*args, **kwargs)\n\n            wrapped.from_config = from_config\n            return wrapped\n\n        return wrapper\n\n\ndef _get_args_from_config(from_config_func, *args, **kwargs):\n    \"\"\"\n    Use `from_config` to obtain explicit arguments.\n\n    Returns:\n        dict: arguments to be used for cls.__init__\n    \"\"\"\n    signature = inspect.signature(from_config_func)\n    if list(signature.parameters.keys())[0] != \"cfg\":\n        if inspect.isfunction(from_config_func):\n            name = from_config_func.__name__\n        else:\n            name = f\"{from_config_func.__self__}.from_config\"\n        raise TypeError(f\"{name} must take 'cfg' as the first argument!\")\n    support_var_arg = any(\n        param.kind in [param.VAR_POSITIONAL, param.VAR_KEYWORD]\n        for param in signature.parameters.values()\n    )\n    if support_var_arg:  # forward all arguments to from_config, if from_config accepts them\n        ret = from_config_func(*args, **kwargs)\n    else:\n        # forward supported arguments to from_config\n        supported_arg_names = set(signature.parameters.keys())\n        extra_kwargs = {}\n        for name in list(kwargs.keys()):\n            if name not in supported_arg_names:\n                extra_kwargs[name] = kwargs.pop(name)\n        ret = from_config_func(*args, **kwargs)\n        # forward the other arguments to __init__\n        ret.update(extra_kwargs)\n    return ret\n\n\ndef _called_with_cfg(*args, **kwargs):\n    \"\"\"\n    Returns:\n        bool: whether the arguments contain CfgNode and should be considered\n            forwarded to from_config.\n    \"\"\"\n    from omegaconf import DictConfig\n\n    if len(args) and isinstance(args[0], (_CfgNode, DictConfig)):\n        return True\n    if isinstance(kwargs.pop(\"cfg\", None), (_CfgNode, DictConfig)):\n        return True\n    # `from_config`'s first argument is forced to be \"cfg\".\n    # So the above check covers all cases.\n    return False\n"
  },
  {
    "path": "VPS_Module/detectron2/config/defaults.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom .config import CfgNode as CN\n\n# NOTE: given the new config system\n# (https://detectron2.readthedocs.io/en/latest/tutorials/lazyconfigs.html),\n# we will stop adding new functionalities to default CfgNode.\n\n# -----------------------------------------------------------------------------\n# Convention about Training / Test specific parameters\n# -----------------------------------------------------------------------------\n# Whenever an argument can be either used for training or for testing, the\n# corresponding name will be post-fixed by a _TRAIN for a training parameter,\n# or _TEST for a test-specific parameter.\n# For example, the number of images during training will be\n# IMAGES_PER_BATCH_TRAIN, while the number of images for testing will be\n# IMAGES_PER_BATCH_TEST\n\n# -----------------------------------------------------------------------------\n# Config definition\n# -----------------------------------------------------------------------------\n\n_C = CN()\n\n# The version number, to upgrade from old configs to new ones if any\n# changes happen. It's recommended to keep a VERSION in your config file.\n_C.VERSION = 2\n\n_C.MODEL = CN()\n_C.MODEL.LOAD_PROPOSALS = False\n_C.MODEL.MASK_ON = False\n_C.MODEL.KEYPOINT_ON = False\n_C.MODEL.DEVICE = \"cuda\"\n_C.MODEL.META_ARCHITECTURE = \"GeneralizedRCNN\"\n\n# Path (a file path, or URL like detectron2://.., https://..) to a checkpoint file\n# to be loaded to the model. You can find available models in the model zoo.\n_C.MODEL.WEIGHTS = \"\"\n\n# Values to be used for image normalization (BGR order, since INPUT.FORMAT defaults to BGR).\n# To train on images of different number of channels, just set different mean & std.\n# Default values are the mean pixel value from ImageNet: [103.53, 116.28, 123.675]\n_C.MODEL.PIXEL_MEAN = [103.530, 116.280, 123.675]\n# When using pre-trained models in Detectron1 or any MSRA models,\n# std has been absorbed into its conv1 weights, so the std needs to be set 1.\n# Otherwise, you can use [57.375, 57.120, 58.395] (ImageNet std)\n_C.MODEL.PIXEL_STD = [1.0, 1.0, 1.0]\n\n\n# -----------------------------------------------------------------------------\n# INPUT\n# -----------------------------------------------------------------------------\n_C.INPUT = CN()\n# By default, {MIN,MAX}_SIZE options are used in transforms.ResizeShortestEdge.\n# Please refer to ResizeShortestEdge for detailed definition.\n# Size of the smallest side of the image during training\n_C.INPUT.MIN_SIZE_TRAIN = (800,)\n# Sample size of smallest side by choice or random selection from range give by\n# INPUT.MIN_SIZE_TRAIN\n_C.INPUT.MIN_SIZE_TRAIN_SAMPLING = \"choice\"\n# Maximum size of the side of the image during training\n_C.INPUT.MAX_SIZE_TRAIN = 1333\n# Size of the smallest side of the image during testing. Set to zero to disable resize in testing.\n_C.INPUT.MIN_SIZE_TEST = 800\n# Maximum size of the side of the image during testing\n_C.INPUT.MAX_SIZE_TEST = 1333\n# Mode for flipping images used in data augmentation during training\n# choose one of [\"horizontal, \"vertical\", \"none\"]\n_C.INPUT.RANDOM_FLIP = \"horizontal\"\n\n# `True` if cropping is used for data augmentation during training\n_C.INPUT.CROP = CN({\"ENABLED\": False})\n# Cropping type. See documentation of `detectron2.data.transforms.RandomCrop` for explanation.\n_C.INPUT.CROP.TYPE = \"relative_range\"\n# Size of crop in range (0, 1] if CROP.TYPE is \"relative\" or \"relative_range\" and in number of\n# pixels if CROP.TYPE is \"absolute\"\n_C.INPUT.CROP.SIZE = [0.9, 0.9]\n\n\n# Whether the model needs RGB, YUV, HSV etc.\n# Should be one of the modes defined here, as we use PIL to read the image:\n# https://pillow.readthedocs.io/en/stable/handbook/concepts.html#concept-modes\n# with BGR being the one exception. One can set image format to BGR, we will\n# internally use RGB for conversion and flip the channels over\n_C.INPUT.FORMAT = \"BGR\"\n# The ground truth mask format that the model will use.\n# Mask R-CNN supports either \"polygon\" or \"bitmask\" as ground truth.\n_C.INPUT.MASK_FORMAT = \"polygon\"  # alternative: \"bitmask\"\n\n\n# -----------------------------------------------------------------------------\n# Dataset\n# -----------------------------------------------------------------------------\n_C.DATASETS = CN()\n# List of the dataset names for training. Must be registered in DatasetCatalog\n# Samples from these datasets will be merged and used as one dataset.\n_C.DATASETS.TRAIN = ()\n# List of the pre-computed proposal files for training, which must be consistent\n# with datasets listed in DATASETS.TRAIN.\n_C.DATASETS.PROPOSAL_FILES_TRAIN = ()\n# Number of top scoring precomputed proposals to keep for training\n_C.DATASETS.PRECOMPUTED_PROPOSAL_TOPK_TRAIN = 2000\n# List of the dataset names for testing. Must be registered in DatasetCatalog\n_C.DATASETS.TEST = ()\n# List of the pre-computed proposal files for test, which must be consistent\n# with datasets listed in DATASETS.TEST.\n_C.DATASETS.PROPOSAL_FILES_TEST = ()\n# Number of top scoring precomputed proposals to keep for test\n_C.DATASETS.PRECOMPUTED_PROPOSAL_TOPK_TEST = 1000\n\n# -----------------------------------------------------------------------------\n# DataLoader\n# -----------------------------------------------------------------------------\n_C.DATALOADER = CN()\n# Number of data loading threads\n_C.DATALOADER.NUM_WORKERS = 4\n# If True, each batch should contain only images for which the aspect ratio\n# is compatible. This groups portrait images together, and landscape images\n# are not batched with portrait images.\n_C.DATALOADER.ASPECT_RATIO_GROUPING = True\n# Options: TrainingSampler, RepeatFactorTrainingSampler\n_C.DATALOADER.SAMPLER_TRAIN = \"TrainingSampler\"\n# Repeat threshold for RepeatFactorTrainingSampler\n_C.DATALOADER.REPEAT_THRESHOLD = 0.0\n# Tf True, when working on datasets that have instance annotations, the\n# training dataloader will filter out images without associated annotations\n_C.DATALOADER.FILTER_EMPTY_ANNOTATIONS = True\n\n# ---------------------------------------------------------------------------- #\n# Backbone options\n# ---------------------------------------------------------------------------- #\n_C.MODEL.BACKBONE = CN()\n\n_C.MODEL.BACKBONE.NAME = \"build_resnet_backbone\"\n# Freeze the first several stages so they are not trained.\n# There are 5 stages in ResNet. The first is a convolution, and the following\n# stages are each group of residual blocks.\n_C.MODEL.BACKBONE.FREEZE_AT = 2\n\n\n# ---------------------------------------------------------------------------- #\n# FPN options\n# ---------------------------------------------------------------------------- #\n_C.MODEL.FPN = CN()\n# Names of the input feature maps to be used by FPN\n# They must have contiguous power of 2 strides\n# e.g., [\"res2\", \"res3\", \"res4\", \"res5\"]\n_C.MODEL.FPN.IN_FEATURES = []\n_C.MODEL.FPN.OUT_CHANNELS = 256\n\n# Options: \"\" (no norm), \"GN\"\n_C.MODEL.FPN.NORM = \"\"\n\n# Types for fusing the FPN top-down and lateral features. Can be either \"sum\" or \"avg\"\n_C.MODEL.FPN.FUSE_TYPE = \"sum\"\n\n\n# ---------------------------------------------------------------------------- #\n# Proposal generator options\n# ---------------------------------------------------------------------------- #\n_C.MODEL.PROPOSAL_GENERATOR = CN()\n# Current proposal generators include \"RPN\", \"RRPN\" and \"PrecomputedProposals\"\n_C.MODEL.PROPOSAL_GENERATOR.NAME = \"RPN\"\n# Proposal height and width both need to be greater than MIN_SIZE\n# (a the scale used during training or inference)\n_C.MODEL.PROPOSAL_GENERATOR.MIN_SIZE = 0\n\n\n# ---------------------------------------------------------------------------- #\n# Anchor generator options\n# ---------------------------------------------------------------------------- #\n_C.MODEL.ANCHOR_GENERATOR = CN()\n# The generator can be any name in the ANCHOR_GENERATOR registry\n_C.MODEL.ANCHOR_GENERATOR.NAME = \"DefaultAnchorGenerator\"\n# Anchor sizes (i.e. sqrt of area) in absolute pixels w.r.t. the network input.\n# Format: list[list[float]]. SIZES[i] specifies the list of sizes to use for\n# IN_FEATURES[i]; len(SIZES) must be equal to len(IN_FEATURES) or 1.\n# When len(SIZES) == 1, SIZES[0] is used for all IN_FEATURES.\n_C.MODEL.ANCHOR_GENERATOR.SIZES = [[32, 64, 128, 256, 512]]\n# Anchor aspect ratios. For each area given in `SIZES`, anchors with different aspect\n# ratios are generated by an anchor generator.\n# Format: list[list[float]]. ASPECT_RATIOS[i] specifies the list of aspect ratios (H/W)\n# to use for IN_FEATURES[i]; len(ASPECT_RATIOS) == len(IN_FEATURES) must be true,\n# or len(ASPECT_RATIOS) == 1 is true and aspect ratio list ASPECT_RATIOS[0] is used\n# for all IN_FEATURES.\n_C.MODEL.ANCHOR_GENERATOR.ASPECT_RATIOS = [[0.5, 1.0, 2.0]]\n# Anchor angles.\n# list[list[float]], the angle in degrees, for each input feature map.\n# ANGLES[i] specifies the list of angles for IN_FEATURES[i].\n_C.MODEL.ANCHOR_GENERATOR.ANGLES = [[-90, 0, 90]]\n# Relative offset between the center of the first anchor and the top-left corner of the image\n# Value has to be in [0, 1). Recommend to use 0.5, which means half stride.\n# The value is not expected to affect model accuracy.\n_C.MODEL.ANCHOR_GENERATOR.OFFSET = 0.0\n\n# ---------------------------------------------------------------------------- #\n# RPN options\n# ---------------------------------------------------------------------------- #\n_C.MODEL.RPN = CN()\n_C.MODEL.RPN.HEAD_NAME = \"StandardRPNHead\"  # used by RPN_HEAD_REGISTRY\n\n# Names of the input feature maps to be used by RPN\n# e.g., [\"p2\", \"p3\", \"p4\", \"p5\", \"p6\"] for FPN\n_C.MODEL.RPN.IN_FEATURES = [\"res4\"]\n# Remove RPN anchors that go outside the image by BOUNDARY_THRESH pixels\n# Set to -1 or a large value, e.g. 100000, to disable pruning anchors\n_C.MODEL.RPN.BOUNDARY_THRESH = -1\n# IOU overlap ratios [BG_IOU_THRESHOLD, FG_IOU_THRESHOLD]\n# Minimum overlap required between an anchor and ground-truth box for the\n# (anchor, gt box) pair to be a positive example (IoU >= FG_IOU_THRESHOLD\n# ==> positive RPN example: 1)\n# Maximum overlap allowed between an anchor and ground-truth box for the\n# (anchor, gt box) pair to be a negative examples (IoU < BG_IOU_THRESHOLD\n# ==> negative RPN example: 0)\n# Anchors with overlap in between (BG_IOU_THRESHOLD <= IoU < FG_IOU_THRESHOLD)\n# are ignored (-1)\n_C.MODEL.RPN.IOU_THRESHOLDS = [0.3, 0.7]\n_C.MODEL.RPN.IOU_LABELS = [0, -1, 1]\n# Number of regions per image used to train RPN\n_C.MODEL.RPN.BATCH_SIZE_PER_IMAGE = 256\n# Target fraction of foreground (positive) examples per RPN minibatch\n_C.MODEL.RPN.POSITIVE_FRACTION = 0.5\n# Options are: \"smooth_l1\", \"giou\", \"diou\", \"ciou\"\n_C.MODEL.RPN.BBOX_REG_LOSS_TYPE = \"smooth_l1\"\n_C.MODEL.RPN.BBOX_REG_LOSS_WEIGHT = 1.0\n# Weights on (dx, dy, dw, dh) for normalizing RPN anchor regression targets\n_C.MODEL.RPN.BBOX_REG_WEIGHTS = (1.0, 1.0, 1.0, 1.0)\n# The transition point from L1 to L2 loss. Set to 0.0 to make the loss simply L1.\n_C.MODEL.RPN.SMOOTH_L1_BETA = 0.0\n_C.MODEL.RPN.LOSS_WEIGHT = 1.0\n# Number of top scoring RPN proposals to keep before applying NMS\n# When FPN is used, this is *per FPN level* (not total)\n_C.MODEL.RPN.PRE_NMS_TOPK_TRAIN = 12000\n_C.MODEL.RPN.PRE_NMS_TOPK_TEST = 6000\n# Number of top scoring RPN proposals to keep after applying NMS\n# When FPN is used, this limit is applied per level and then again to the union\n# of proposals from all levels\n# NOTE: When FPN is used, the meaning of this config is different from Detectron1.\n# It means per-batch topk in Detectron1, but per-image topk here.\n# See the \"find_top_rpn_proposals\" function for details.\n_C.MODEL.RPN.POST_NMS_TOPK_TRAIN = 2000\n_C.MODEL.RPN.POST_NMS_TOPK_TEST = 1000\n# NMS threshold used on RPN proposals\n_C.MODEL.RPN.NMS_THRESH = 0.7\n# Set this to -1 to use the same number of output channels as input channels.\n_C.MODEL.RPN.CONV_DIMS = [-1]\n\n# ---------------------------------------------------------------------------- #\n# ROI HEADS options\n# ---------------------------------------------------------------------------- #\n_C.MODEL.ROI_HEADS = CN()\n_C.MODEL.ROI_HEADS.NAME = \"Res5ROIHeads\"\n# Number of foreground classes\n_C.MODEL.ROI_HEADS.NUM_CLASSES = 80\n# Names of the input feature maps to be used by ROI heads\n# Currently all heads (box, mask, ...) use the same input feature map list\n# e.g., [\"p2\", \"p3\", \"p4\", \"p5\"] is commonly used for FPN\n_C.MODEL.ROI_HEADS.IN_FEATURES = [\"res4\"]\n# IOU overlap ratios [IOU_THRESHOLD]\n# Overlap threshold for an RoI to be considered background (if < IOU_THRESHOLD)\n# Overlap threshold for an RoI to be considered foreground (if >= IOU_THRESHOLD)\n_C.MODEL.ROI_HEADS.IOU_THRESHOLDS = [0.5]\n_C.MODEL.ROI_HEADS.IOU_LABELS = [0, 1]\n# RoI minibatch size *per image* (number of regions of interest [ROIs]) during training\n# Total number of RoIs per training minibatch =\n#   ROI_HEADS.BATCH_SIZE_PER_IMAGE * SOLVER.IMS_PER_BATCH\n# E.g., a common configuration is: 512 * 16 = 8192\n_C.MODEL.ROI_HEADS.BATCH_SIZE_PER_IMAGE = 512\n# Target fraction of RoI minibatch that is labeled foreground (i.e. class > 0)\n_C.MODEL.ROI_HEADS.POSITIVE_FRACTION = 0.25\n\n# Only used on test mode\n\n# Minimum score threshold (assuming scores in a [0, 1] range); a value chosen to\n# balance obtaining high recall with not having too many low precision\n# detections that will slow down inference post processing steps (like NMS)\n# A default threshold of 0.0 increases AP by ~0.2-0.3 but significantly slows down\n# inference.\n_C.MODEL.ROI_HEADS.SCORE_THRESH_TEST = 0.05\n# Overlap threshold used for non-maximum suppression (suppress boxes with\n# IoU >= this threshold)\n_C.MODEL.ROI_HEADS.NMS_THRESH_TEST = 0.5\n# If True, augment proposals with ground-truth boxes before sampling proposals to\n# train ROI heads.\n_C.MODEL.ROI_HEADS.PROPOSAL_APPEND_GT = True\n\n# ---------------------------------------------------------------------------- #\n# Box Head\n# ---------------------------------------------------------------------------- #\n_C.MODEL.ROI_BOX_HEAD = CN()\n# C4 don't use head name option\n# Options for non-C4 models: FastRCNNConvFCHead,\n_C.MODEL.ROI_BOX_HEAD.NAME = \"\"\n# Options are: \"smooth_l1\", \"giou\", \"diou\", \"ciou\"\n_C.MODEL.ROI_BOX_HEAD.BBOX_REG_LOSS_TYPE = \"smooth_l1\"\n# The final scaling coefficient on the box regression loss, used to balance the magnitude of its\n# gradients with other losses in the model. See also `MODEL.ROI_KEYPOINT_HEAD.LOSS_WEIGHT`.\n_C.MODEL.ROI_BOX_HEAD.BBOX_REG_LOSS_WEIGHT = 1.0\n# Default weights on (dx, dy, dw, dh) for normalizing bbox regression targets\n# These are empirically chosen to approximately lead to unit variance targets\n_C.MODEL.ROI_BOX_HEAD.BBOX_REG_WEIGHTS = (10.0, 10.0, 5.0, 5.0)\n# The transition point from L1 to L2 loss. Set to 0.0 to make the loss simply L1.\n_C.MODEL.ROI_BOX_HEAD.SMOOTH_L1_BETA = 0.0\n_C.MODEL.ROI_BOX_HEAD.POOLER_RESOLUTION = 14\n_C.MODEL.ROI_BOX_HEAD.POOLER_SAMPLING_RATIO = 0\n# Type of pooling operation applied to the incoming feature map for each RoI\n_C.MODEL.ROI_BOX_HEAD.POOLER_TYPE = \"ROIAlignV2\"\n\n_C.MODEL.ROI_BOX_HEAD.NUM_FC = 0\n# Hidden layer dimension for FC layers in the RoI box head\n_C.MODEL.ROI_BOX_HEAD.FC_DIM = 1024\n_C.MODEL.ROI_BOX_HEAD.NUM_CONV = 0\n# Channel dimension for Conv layers in the RoI box head\n_C.MODEL.ROI_BOX_HEAD.CONV_DIM = 256\n# Normalization method for the convolution layers.\n# Options: \"\" (no norm), \"GN\", \"SyncBN\".\n_C.MODEL.ROI_BOX_HEAD.NORM = \"\"\n# Whether to use class agnostic for bbox regression\n_C.MODEL.ROI_BOX_HEAD.CLS_AGNOSTIC_BBOX_REG = False\n# If true, RoI heads use bounding boxes predicted by the box head rather than proposal boxes.\n_C.MODEL.ROI_BOX_HEAD.TRAIN_ON_PRED_BOXES = False\n\n# ---------------------------------------------------------------------------- #\n# Cascaded Box Head\n# ---------------------------------------------------------------------------- #\n_C.MODEL.ROI_BOX_CASCADE_HEAD = CN()\n# The number of cascade stages is implicitly defined by the length of the following two configs.\n_C.MODEL.ROI_BOX_CASCADE_HEAD.BBOX_REG_WEIGHTS = (\n    (10.0, 10.0, 5.0, 5.0),\n    (20.0, 20.0, 10.0, 10.0),\n    (30.0, 30.0, 15.0, 15.0),\n)\n_C.MODEL.ROI_BOX_CASCADE_HEAD.IOUS = (0.5, 0.6, 0.7)\n\n\n# ---------------------------------------------------------------------------- #\n# Mask Head\n# ---------------------------------------------------------------------------- #\n_C.MODEL.ROI_MASK_HEAD = CN()\n_C.MODEL.ROI_MASK_HEAD.NAME = \"MaskRCNNConvUpsampleHead\"\n_C.MODEL.ROI_MASK_HEAD.POOLER_RESOLUTION = 14\n_C.MODEL.ROI_MASK_HEAD.POOLER_SAMPLING_RATIO = 0\n_C.MODEL.ROI_MASK_HEAD.NUM_CONV = 0  # The number of convs in the mask head\n_C.MODEL.ROI_MASK_HEAD.CONV_DIM = 256\n# Normalization method for the convolution layers.\n# Options: \"\" (no norm), \"GN\", \"SyncBN\".\n_C.MODEL.ROI_MASK_HEAD.NORM = \"\"\n# Whether to use class agnostic for mask prediction\n_C.MODEL.ROI_MASK_HEAD.CLS_AGNOSTIC_MASK = False\n# Type of pooling operation applied to the incoming feature map for each RoI\n_C.MODEL.ROI_MASK_HEAD.POOLER_TYPE = \"ROIAlignV2\"\n\n\n# ---------------------------------------------------------------------------- #\n# Keypoint Head\n# ---------------------------------------------------------------------------- #\n_C.MODEL.ROI_KEYPOINT_HEAD = CN()\n_C.MODEL.ROI_KEYPOINT_HEAD.NAME = \"KRCNNConvDeconvUpsampleHead\"\n_C.MODEL.ROI_KEYPOINT_HEAD.POOLER_RESOLUTION = 14\n_C.MODEL.ROI_KEYPOINT_HEAD.POOLER_SAMPLING_RATIO = 0\n_C.MODEL.ROI_KEYPOINT_HEAD.CONV_DIMS = tuple(512 for _ in range(8))\n_C.MODEL.ROI_KEYPOINT_HEAD.NUM_KEYPOINTS = 17  # 17 is the number of keypoints in COCO.\n\n# Images with too few (or no) keypoints are excluded from training.\n_C.MODEL.ROI_KEYPOINT_HEAD.MIN_KEYPOINTS_PER_IMAGE = 1\n# Normalize by the total number of visible keypoints in the minibatch if True.\n# Otherwise, normalize by the total number of keypoints that could ever exist\n# in the minibatch.\n# The keypoint softmax loss is only calculated on visible keypoints.\n# Since the number of visible keypoints can vary significantly between\n# minibatches, this has the effect of up-weighting the importance of\n# minibatches with few visible keypoints. (Imagine the extreme case of\n# only one visible keypoint versus N: in the case of N, each one\n# contributes 1/N to the gradient compared to the single keypoint\n# determining the gradient direction). Instead, we can normalize the\n# loss by the total number of keypoints, if it were the case that all\n# keypoints were visible in a full minibatch. (Returning to the example,\n# this means that the one visible keypoint contributes as much as each\n# of the N keypoints.)\n_C.MODEL.ROI_KEYPOINT_HEAD.NORMALIZE_LOSS_BY_VISIBLE_KEYPOINTS = True\n# Multi-task loss weight to use for keypoints\n# Recommended values:\n#   - use 1.0 if NORMALIZE_LOSS_BY_VISIBLE_KEYPOINTS is True\n#   - use 4.0 if NORMALIZE_LOSS_BY_VISIBLE_KEYPOINTS is False\n_C.MODEL.ROI_KEYPOINT_HEAD.LOSS_WEIGHT = 1.0\n# Type of pooling operation applied to the incoming feature map for each RoI\n_C.MODEL.ROI_KEYPOINT_HEAD.POOLER_TYPE = \"ROIAlignV2\"\n\n# ---------------------------------------------------------------------------- #\n# Semantic Segmentation Head\n# ---------------------------------------------------------------------------- #\n_C.MODEL.SEM_SEG_HEAD = CN()\n_C.MODEL.SEM_SEG_HEAD.NAME = \"SemSegFPNHead\"\n_C.MODEL.SEM_SEG_HEAD.IN_FEATURES = [\"p2\", \"p3\", \"p4\", \"p5\"]\n# Label in the semantic segmentation ground truth that is ignored, i.e., no loss is calculated for\n# the correposnding pixel.\n_C.MODEL.SEM_SEG_HEAD.IGNORE_VALUE = 255\n# Number of classes in the semantic segmentation head\n_C.MODEL.SEM_SEG_HEAD.NUM_CLASSES = 54\n# Number of channels in the 3x3 convs inside semantic-FPN heads.\n_C.MODEL.SEM_SEG_HEAD.CONVS_DIM = 128\n# Outputs from semantic-FPN heads are up-scaled to the COMMON_STRIDE stride.\n_C.MODEL.SEM_SEG_HEAD.COMMON_STRIDE = 4\n# Normalization method for the convolution layers. Options: \"\" (no norm), \"GN\".\n_C.MODEL.SEM_SEG_HEAD.NORM = \"GN\"\n_C.MODEL.SEM_SEG_HEAD.LOSS_WEIGHT = 1.0\n\n_C.MODEL.PANOPTIC_FPN = CN()\n# Scaling of all losses from instance detection / segmentation head.\n_C.MODEL.PANOPTIC_FPN.INSTANCE_LOSS_WEIGHT = 1.0\n_C.MODEL.PANOPTIC_FPN.FUSION = False\n\n# options when combining instance & semantic segmentation outputs\n_C.MODEL.PANOPTIC_FPN.COMBINE = CN({\"ENABLED\": True})  # \"COMBINE.ENABLED\" is deprecated & not used\n_C.MODEL.PANOPTIC_FPN.COMBINE.OVERLAP_THRESH = 0.5\n_C.MODEL.PANOPTIC_FPN.COMBINE.STUFF_AREA_LIMIT = 4096\n_C.MODEL.PANOPTIC_FPN.COMBINE.INSTANCES_CONFIDENCE_THRESH = 0.5\n\n\n# ---------------------------------------------------------------------------- #\n# RetinaNet Head\n# ---------------------------------------------------------------------------- #\n_C.MODEL.RETINANET = CN()\n\n# This is the number of foreground classes.\n_C.MODEL.RETINANET.NUM_CLASSES = 80\n\n_C.MODEL.RETINANET.IN_FEATURES = [\"p3\", \"p4\", \"p5\", \"p6\", \"p7\"]\n\n# Convolutions to use in the cls and bbox tower\n# NOTE: this doesn't include the last conv for logits\n_C.MODEL.RETINANET.NUM_CONVS = 4\n\n# IoU overlap ratio [bg, fg] for labeling anchors.\n# Anchors with < bg are labeled negative (0)\n# Anchors  with >= bg and < fg are ignored (-1)\n# Anchors with >= fg are labeled positive (1)\n_C.MODEL.RETINANET.IOU_THRESHOLDS = [0.4, 0.5]\n_C.MODEL.RETINANET.IOU_LABELS = [0, -1, 1]\n\n# Prior prob for rare case (i.e. foreground) at the beginning of training.\n# This is used to set the bias for the logits layer of the classifier subnet.\n# This improves training stability in the case of heavy class imbalance.\n_C.MODEL.RETINANET.PRIOR_PROB = 0.01\n\n# Inference cls score threshold, only anchors with score > INFERENCE_TH are\n# considered for inference (to improve speed)\n_C.MODEL.RETINANET.SCORE_THRESH_TEST = 0.05\n# Select topk candidates before NMS\n_C.MODEL.RETINANET.TOPK_CANDIDATES_TEST = 1000\n_C.MODEL.RETINANET.NMS_THRESH_TEST = 0.5\n\n# Weights on (dx, dy, dw, dh) for normalizing Retinanet anchor regression targets\n_C.MODEL.RETINANET.BBOX_REG_WEIGHTS = (1.0, 1.0, 1.0, 1.0)\n\n# Loss parameters\n_C.MODEL.RETINANET.FOCAL_LOSS_GAMMA = 2.0\n_C.MODEL.RETINANET.FOCAL_LOSS_ALPHA = 0.25\n_C.MODEL.RETINANET.SMOOTH_L1_LOSS_BETA = 0.1\n# Options are: \"smooth_l1\", \"giou\", \"diou\", \"ciou\"\n_C.MODEL.RETINANET.BBOX_REG_LOSS_TYPE = \"smooth_l1\"\n\n# One of BN, SyncBN, FrozenBN, GN\n# Only supports GN until unshared norm is implemented\n_C.MODEL.RETINANET.NORM = \"\"\n\n\n# ---------------------------------------------------------------------------- #\n# ResNe[X]t options (ResNets = {ResNet, ResNeXt}\n# Note that parts of a resnet may be used for both the backbone and the head\n# These options apply to both\n# ---------------------------------------------------------------------------- #\n_C.MODEL.RESNETS = CN()\n\n_C.MODEL.RESNETS.DEPTH = 50\n_C.MODEL.RESNETS.OUT_FEATURES = [\"res4\"]  # res4 for C4 backbone, res2..5 for FPN backbone\n\n# Number of groups to use; 1 ==> ResNet; > 1 ==> ResNeXt\n_C.MODEL.RESNETS.NUM_GROUPS = 1\n\n# Options: FrozenBN, GN, \"SyncBN\", \"BN\"\n_C.MODEL.RESNETS.NORM = \"FrozenBN\"\n\n# Baseline width of each group.\n# Scaling this parameters will scale the width of all bottleneck layers.\n_C.MODEL.RESNETS.WIDTH_PER_GROUP = 64\n\n# Place the stride 2 conv on the 1x1 filter\n# Use True only for the original MSRA ResNet; use False for C2 and Torch models\n_C.MODEL.RESNETS.STRIDE_IN_1X1 = True\n\n# Apply dilation in stage \"res5\"\n_C.MODEL.RESNETS.RES5_DILATION = 1\n\n# Output width of res2. Scaling this parameters will scale the width of all 1x1 convs in ResNet\n# For R18 and R34, this needs to be set to 64\n_C.MODEL.RESNETS.RES2_OUT_CHANNELS = 256\n_C.MODEL.RESNETS.STEM_OUT_CHANNELS = 64\n\n# Apply Deformable Convolution in stages\n# Specify if apply deform_conv on Res2, Res3, Res4, Res5\n_C.MODEL.RESNETS.DEFORM_ON_PER_STAGE = [False, False, False, False]\n# Use True to use modulated deform_conv (DeformableV2, https://arxiv.org/abs/1811.11168);\n# Use False for DeformableV1.\n_C.MODEL.RESNETS.DEFORM_MODULATED = False\n# Number of groups in deformable conv.\n_C.MODEL.RESNETS.DEFORM_NUM_GROUPS = 1\n\n\n# ---------------------------------------------------------------------------- #\n# Solver\n# ---------------------------------------------------------------------------- #\n_C.SOLVER = CN()\n\n# Options: WarmupMultiStepLR, WarmupCosineLR.\n# See detectron2/solver/build.py for definition.\n_C.SOLVER.LR_SCHEDULER_NAME = \"WarmupMultiStepLR\"\n\n_C.SOLVER.MAX_ITER = 40000\n\n_C.SOLVER.BASE_LR = 0.001\n\n_C.SOLVER.MOMENTUM = 0.9\n\n_C.SOLVER.NESTEROV = False\n\n_C.SOLVER.WEIGHT_DECAY = 0.0001\n# The weight decay that's applied to parameters of normalization layers\n# (typically the affine transformation)\n_C.SOLVER.WEIGHT_DECAY_NORM = 0.0\n\n_C.SOLVER.GAMMA = 0.1\n# The iteration number to decrease learning rate by GAMMA.\n_C.SOLVER.STEPS = (30000,)\n\n_C.SOLVER.WARMUP_FACTOR = 1.0 / 1000\n_C.SOLVER.WARMUP_ITERS = 1000\n_C.SOLVER.WARMUP_METHOD = \"linear\"\n\n# Save a checkpoint after every this number of iterations\n_C.SOLVER.CHECKPOINT_PERIOD = 5000\n\n# Number of images per batch across all machines. This is also the number\n# of training images per step (i.e. per iteration). If we use 16 GPUs\n# and IMS_PER_BATCH = 32, each GPU will see 2 images per batch.\n# May be adjusted automatically if REFERENCE_WORLD_SIZE is set.\n_C.SOLVER.IMS_PER_BATCH = 16\n\n# The reference number of workers (GPUs) this config is meant to train with.\n# It takes no effect when set to 0.\n# With a non-zero value, it will be used by DefaultTrainer to compute a desired\n# per-worker batch size, and then scale the other related configs (total batch size,\n# learning rate, etc) to match the per-worker batch size.\n# See documentation of `DefaultTrainer.auto_scale_workers` for details:\n_C.SOLVER.REFERENCE_WORLD_SIZE = 0\n\n# Detectron v1 (and previous detection code) used a 2x higher LR and 0 WD for\n# biases. This is not useful (at least for recent models). You should avoid\n# changing these and they exist only to reproduce Detectron v1 training if\n# desired.\n_C.SOLVER.BIAS_LR_FACTOR = 1.0\n_C.SOLVER.WEIGHT_DECAY_BIAS = None  # None means following WEIGHT_DECAY\n\n# Gradient clipping\n_C.SOLVER.CLIP_GRADIENTS = CN({\"ENABLED\": False})\n# Type of gradient clipping, currently 2 values are supported:\n# - \"value\": the absolute values of elements of each gradients are clipped\n# - \"norm\": the norm of the gradient for each parameter is clipped thus\n#   affecting all elements in the parameter\n_C.SOLVER.CLIP_GRADIENTS.CLIP_TYPE = \"value\"\n# Maximum absolute value used for clipping gradients\n_C.SOLVER.CLIP_GRADIENTS.CLIP_VALUE = 1.0\n# Floating point number p for L-p norm to be used with the \"norm\"\n# gradient clipping type; for L-inf, please specify .inf\n_C.SOLVER.CLIP_GRADIENTS.NORM_TYPE = 2.0\n\n# Enable automatic mixed precision for training\n# Note that this does not change model's inference behavior.\n# To use AMP in inference, run inference under autocast()\n_C.SOLVER.AMP = CN({\"ENABLED\": False})\n\n# ---------------------------------------------------------------------------- #\n# Specific test options\n# ---------------------------------------------------------------------------- #\n_C.TEST = CN()\n# For end-to-end tests to verify the expected accuracy.\n# Each item is [task, metric, value, tolerance]\n# e.g.: [['bbox', 'AP', 38.5, 0.2]]\n_C.TEST.EXPECTED_RESULTS = []\n# The period (in terms of steps) to evaluate the model during training.\n# Set to 0 to disable.\n_C.TEST.EVAL_PERIOD = 0\n# The sigmas used to calculate keypoint OKS. See http://cocodataset.org/#keypoints-eval\n# When empty, it will use the defaults in COCO.\n# Otherwise it should be a list[float] with the same length as ROI_KEYPOINT_HEAD.NUM_KEYPOINTS.\n_C.TEST.KEYPOINT_OKS_SIGMAS = []\n# Maximum number of detections to return per image during inference (100 is\n# based on the limit established for the COCO dataset).\n_C.TEST.DETECTIONS_PER_IMAGE = 100\n\n_C.TEST.AUG = CN({\"ENABLED\": False})\n_C.TEST.AUG.MIN_SIZES = (400, 500, 600, 700, 800, 900, 1000, 1100, 1200)\n_C.TEST.AUG.MAX_SIZE = 4000\n_C.TEST.AUG.FLIP = True\n\n_C.TEST.PRECISE_BN = CN({\"ENABLED\": False})\n_C.TEST.PRECISE_BN.NUM_ITER = 200\n\n# ---------------------------------------------------------------------------- #\n# Misc options\n# ---------------------------------------------------------------------------- #\n# Directory where output files are written\n_C.OUTPUT_DIR = \"./output\"\n# Set seed to negative to fully randomize everything.\n# Set seed to positive to use a fixed seed. Note that a fixed seed increases\n# reproducibility but does not guarantee fully deterministic behavior.\n# Disabling all parallelism further increases reproducibility.\n_C.SEED = -1\n# Benchmark different cudnn algorithms.\n# If input images have very different sizes, this option will have large overhead\n# for about 10k iterations. It usually hurts total time, but can benefit for certain models.\n# If input images have the same or similar sizes, benchmark is often helpful.\n_C.CUDNN_BENCHMARK = False\n# The period (in terms of steps) for minibatch visualization at train time.\n# Set to 0 to disable.\n_C.VIS_PERIOD = 0\n\n# global config is for quick hack purposes.\n# You can set them in command line or config files,\n# and access it with:\n#\n# from detectron2.config import global_cfg\n# print(global_cfg.HACK)\n#\n# Do not commit any configs into it.\n_C.GLOBAL = CN()\n_C.GLOBAL.HACK = 1.0\n"
  },
  {
    "path": "VPS_Module/detectron2/config/instantiate.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport dataclasses\nimport logging\nfrom collections import abc\nfrom typing import Any\n\nfrom detectron2.utils.registry import _convert_target_to_string, locate\n\n__all__ = [\"dump_dataclass\", \"instantiate\"]\n\n\ndef dump_dataclass(obj: Any):\n    \"\"\"\n    Dump a dataclass recursively into a dict that can be later instantiated.\n\n    Args:\n        obj: a dataclass object\n\n    Returns:\n        dict\n    \"\"\"\n    assert dataclasses.is_dataclass(obj) and not isinstance(\n        obj, type\n    ), \"dump_dataclass() requires an instance of a dataclass.\"\n    ret = {\"_target_\": _convert_target_to_string(type(obj))}\n    for f in dataclasses.fields(obj):\n        v = getattr(obj, f.name)\n        if dataclasses.is_dataclass(v):\n            v = dump_dataclass(v)\n        if isinstance(v, (list, tuple)):\n            v = [dump_dataclass(x) if dataclasses.is_dataclass(x) else x for x in v]\n        ret[f.name] = v\n    return ret\n\n\ndef instantiate(cfg):\n    \"\"\"\n    Recursively instantiate objects defined in dictionaries by\n    \"_target_\" and arguments.\n\n    Args:\n        cfg: a dict-like object with \"_target_\" that defines the caller, and\n            other keys that define the arguments\n\n    Returns:\n        object instantiated by cfg\n    \"\"\"\n    from omegaconf import ListConfig\n\n    if isinstance(cfg, ListConfig):\n        lst = [instantiate(x) for x in cfg]\n        return ListConfig(lst, flags={\"allow_objects\": True})\n    if isinstance(cfg, list):\n        # Specialize for list, because many classes take\n        # list[objects] as arguments, such as ResNet, DatasetMapper\n        return [instantiate(x) for x in cfg]\n\n    if isinstance(cfg, abc.Mapping) and \"_target_\" in cfg:\n        # conceptually equivalent to hydra.utils.instantiate(cfg) with _convert_=all,\n        # but faster: https://github.com/facebookresearch/hydra/issues/1200\n        cfg = {k: instantiate(v) for k, v in cfg.items()}\n        cls = cfg.pop(\"_target_\")\n        cls = instantiate(cls)\n\n        if isinstance(cls, str):\n            cls_name = cls\n            cls = locate(cls_name)\n            assert cls is not None, cls_name\n        else:\n            try:\n                cls_name = cls.__module__ + \".\" + cls.__qualname__\n            except Exception:\n                # target could be anything, so the above could fail\n                cls_name = str(cls)\n        assert callable(cls), f\"_target_ {cls} does not define a callable object\"\n        try:\n            return cls(**cfg)\n        except TypeError:\n            logger = logging.getLogger(__name__)\n            logger.error(f\"Error when instantiating {cls_name}!\")\n            raise\n    return cfg  # return as-is if don't know what to do\n"
  },
  {
    "path": "VPS_Module/detectron2/config/lazy.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport ast\nimport builtins\nimport importlib\nimport inspect\nimport logging\nimport os\nimport uuid\nfrom collections import abc\nfrom contextlib import contextmanager\nfrom copy import deepcopy\nfrom dataclasses import is_dataclass\nfrom typing import List, Tuple, Union\nimport cloudpickle\nimport yaml\nfrom omegaconf import DictConfig, ListConfig, OmegaConf\n\nfrom detectron2.utils.file_io import PathManager\nfrom detectron2.utils.registry import _convert_target_to_string\n\n__all__ = [\"LazyCall\", \"LazyConfig\"]\n\n\nclass LazyCall:\n    \"\"\"\n    Wrap a callable so that when it's called, the call will not be executed,\n    but returns a dict that describes the call.\n\n    LazyCall object has to be called with only keyword arguments. Positional\n    arguments are not yet supported.\n\n    Examples:\n    ::\n        from detectron2.config import instantiate, LazyCall\n\n        layer_cfg = LazyCall(nn.Conv2d)(in_channels=32, out_channels=32)\n        layer_cfg.out_channels = 64   # can edit it afterwards\n        layer = instantiate(layer_cfg)\n    \"\"\"\n\n    def __init__(self, target):\n        if not (callable(target) or isinstance(target, (str, abc.Mapping))):\n            raise TypeError(\n                f\"target of LazyCall must be a callable or defines a callable! Got {target}\"\n            )\n        self._target = target\n\n    def __call__(self, **kwargs):\n        if is_dataclass(self._target):\n            # omegaconf object cannot hold dataclass type\n            # https://github.com/omry/omegaconf/issues/784\n            target = _convert_target_to_string(self._target)\n        else:\n            target = self._target\n        kwargs[\"_target_\"] = target\n\n        return DictConfig(content=kwargs, flags={\"allow_objects\": True})\n\n\ndef _visit_dict_config(cfg, func):\n    \"\"\"\n    Apply func recursively to all DictConfig in cfg.\n    \"\"\"\n    if isinstance(cfg, DictConfig):\n        func(cfg)\n        for v in cfg.values():\n            _visit_dict_config(v, func)\n    elif isinstance(cfg, ListConfig):\n        for v in cfg:\n            _visit_dict_config(v, func)\n\n\ndef _validate_py_syntax(filename):\n    # see also https://github.com/open-mmlab/mmcv/blob/master/mmcv/utils/config.py\n    with PathManager.open(filename, \"r\") as f:\n        content = f.read()\n    try:\n        ast.parse(content)\n    except SyntaxError as e:\n        raise SyntaxError(f\"Config file {filename} has syntax error!\") from e\n\n\ndef _cast_to_config(obj):\n    # if given a dict, return DictConfig instead\n    if isinstance(obj, dict):\n        return DictConfig(obj, flags={\"allow_objects\": True})\n    return obj\n\n\n_CFG_PACKAGE_NAME = \"detectron2._cfg_loader\"\n\"\"\"\nA namespace to put all imported config into.\n\"\"\"\n\n\ndef _random_package_name(filename):\n    # generate a random package name when loading config files\n    return _CFG_PACKAGE_NAME + str(uuid.uuid4())[:4] + \".\" + os.path.basename(filename)\n\n\n@contextmanager\ndef _patch_import():\n    \"\"\"\n    Enhance relative import statements in config files, so that they:\n    1. locate files purely based on relative location, regardless of packages.\n       e.g. you can import file without having __init__\n    2. do not cache modules globally; modifications of module states has no side effect\n    3. support other storage system through PathManager\n    4. imported dict are turned into omegaconf.DictConfig automatically\n    \"\"\"\n    old_import = builtins.__import__\n\n    def find_relative_file(original_file, relative_import_path, level):\n        cur_file = os.path.dirname(original_file)\n        for _ in range(level - 1):\n            cur_file = os.path.dirname(cur_file)\n        cur_name = relative_import_path.lstrip(\".\")\n        for part in cur_name.split(\".\"):\n            cur_file = os.path.join(cur_file, part)\n        # NOTE: directory import is not handled. Because then it's unclear\n        # if such import should produce python module or DictConfig. This can\n        # be discussed further if needed.\n        if not cur_file.endswith(\".py\"):\n            cur_file += \".py\"\n        if not PathManager.isfile(cur_file):\n            raise ImportError(\n                f\"Cannot import name {relative_import_path} from \"\n                f\"{original_file}: {cur_file} has to exist.\"\n            )\n        return cur_file\n\n    def new_import(name, globals=None, locals=None, fromlist=(), level=0):\n        if (\n            # Only deal with relative imports inside config files\n            level != 0\n            and globals is not None\n            and (globals.get(\"__package__\", \"\") or \"\").startswith(_CFG_PACKAGE_NAME)\n        ):\n            cur_file = find_relative_file(globals[\"__file__\"], name, level)\n            _validate_py_syntax(cur_file)\n            spec = importlib.machinery.ModuleSpec(\n                _random_package_name(cur_file), None, origin=cur_file\n            )\n            module = importlib.util.module_from_spec(spec)\n            module.__file__ = cur_file\n            with PathManager.open(cur_file) as f:\n                content = f.read()\n            exec(compile(content, cur_file, \"exec\"), module.__dict__)\n            for name in fromlist:  # turn imported dict into DictConfig automatically\n                val = _cast_to_config(module.__dict__[name])\n                module.__dict__[name] = val\n            return module\n        return old_import(name, globals, locals, fromlist=fromlist, level=level)\n\n    builtins.__import__ = new_import\n    yield new_import\n    builtins.__import__ = old_import\n\n\nclass LazyConfig:\n    \"\"\"\n    Provide methods to save, load, and overrides an omegaconf config object\n    which may contain definition of lazily-constructed objects.\n    \"\"\"\n\n    @staticmethod\n    def load_rel(filename: str, keys: Union[None, str, Tuple[str, ...]] = None):\n        \"\"\"\n        Similar to :meth:`load()`, but load path relative to the caller's\n        source file.\n\n        This has the same functionality as a relative import, except that this method\n        accepts filename as a string, so more characters are allowed in the filename.\n        \"\"\"\n        caller_frame = inspect.stack()[1]\n        caller_fname = caller_frame[0].f_code.co_filename\n        assert caller_fname != \"<string>\", \"load_rel Unable to find caller\"\n        caller_dir = os.path.dirname(caller_fname)\n        filename = os.path.join(caller_dir, filename)\n        return LazyConfig.load(filename, keys)\n\n    @staticmethod\n    def load(filename: str, keys: Union[None, str, Tuple[str, ...]] = None):\n        \"\"\"\n        Load a config file.\n\n        Args:\n            filename: absolute path or relative path w.r.t. the current working directory\n            keys: keys to load and return. If not given, return all keys\n                (whose values are config objects) in a dict.\n        \"\"\"\n        has_keys = keys is not None\n        filename = filename.replace(\"/./\", \"/\")  # redundant\n        if os.path.splitext(filename)[1] not in [\".py\", \".yaml\", \".yml\"]:\n            raise ValueError(f\"Config file {filename} has to be a python or yaml file.\")\n        if filename.endswith(\".py\"):\n            _validate_py_syntax(filename)\n\n            with _patch_import():\n                # Record the filename\n                module_namespace = {\n                    \"__file__\": filename,\n                    \"__package__\": _random_package_name(filename),\n                }\n                with PathManager.open(filename) as f:\n                    content = f.read()\n                # Compile first with filename to:\n                # 1. make filename appears in stacktrace\n                # 2. make load_rel able to find its parent's (possibly remote) location\n                exec(compile(content, filename, \"exec\"), module_namespace)\n\n            ret = module_namespace\n        else:\n            with PathManager.open(filename) as f:\n                obj = yaml.unsafe_load(f)\n            ret = OmegaConf.create(obj, flags={\"allow_objects\": True})\n\n        if has_keys:\n            if isinstance(keys, str):\n                return _cast_to_config(ret[keys])\n            else:\n                return tuple(_cast_to_config(ret[a]) for a in keys)\n        else:\n            if filename.endswith(\".py\"):\n                # when not specified, only load those that are config objects\n                ret = DictConfig(\n                    {\n                        name: _cast_to_config(value)\n                        for name, value in ret.items()\n                        if isinstance(value, (DictConfig, ListConfig, dict))\n                        and not name.startswith(\"_\")\n                    },\n                    flags={\"allow_objects\": True},\n                )\n            return ret\n\n    @staticmethod\n    def save(cfg, filename: str):\n        \"\"\"\n        Save a config object to a yaml file.\n        Note that when the config dictionary contains complex objects (e.g. lambda),\n        it can't be saved to yaml. In that case we will print an error and\n        attempt to save to a pkl file instead.\n\n        Args:\n            cfg: an omegaconf config object\n            filename: yaml file name to save the config file\n        \"\"\"\n        logger = logging.getLogger(__name__)\n        try:\n            cfg = deepcopy(cfg)\n        except Exception:\n            pass\n        else:\n            # if it's deep-copyable, then...\n            def _replace_type_by_name(x):\n                if \"_target_\" in x and callable(x._target_):\n                    try:\n                        x._target_ = _convert_target_to_string(x._target_)\n                    except AttributeError:\n                        pass\n\n            # not necessary, but makes yaml looks nicer\n            _visit_dict_config(cfg, _replace_type_by_name)\n\n        save_pkl = False\n        try:\n            dict = OmegaConf.to_container(cfg, resolve=False)\n            dumped = yaml.dump(dict, default_flow_style=None, allow_unicode=True, width=9999)\n            with PathManager.open(filename, \"w\") as f:\n                f.write(dumped)\n\n            try:\n                _ = yaml.unsafe_load(dumped)  # test that it is loadable\n            except Exception:\n                logger.warning(\n                    \"The config contains objects that cannot serialize to a valid yaml. \"\n                    f\"{filename} is human-readable but cannot be loaded.\"\n                )\n                save_pkl = True\n        except Exception:\n            logger.exception(\"Unable to serialize the config to yaml. Error:\")\n            save_pkl = True\n\n        if save_pkl:\n            new_filename = filename + \".pkl\"\n            try:\n                # retry by pickle\n                with PathManager.open(new_filename, \"wb\") as f:\n                    cloudpickle.dump(cfg, f)\n                logger.warning(f\"Config is saved using cloudpickle at {new_filename}.\")\n            except Exception:\n                pass\n\n    @staticmethod\n    def apply_overrides(cfg, overrides: List[str]):\n        \"\"\"\n        In-place override contents of cfg.\n\n        Args:\n            cfg: an omegaconf config object\n            overrides: list of strings in the format of \"a=b\" to override configs.\n                See https://hydra.cc/docs/next/advanced/override_grammar/basic/\n                for syntax.\n\n        Returns:\n            the cfg object\n        \"\"\"\n\n        def safe_update(cfg, key, value):\n            parts = key.split(\".\")\n            for idx in range(1, len(parts)):\n                prefix = \".\".join(parts[:idx])\n                v = OmegaConf.select(cfg, prefix, default=None)\n                if v is None:\n                    break\n                if not OmegaConf.is_config(v):\n                    raise KeyError(\n                        f\"Trying to update key {key}, but {prefix} \"\n                        f\"is not a config, but has type {type(v)}.\"\n                    )\n            OmegaConf.update(cfg, key, value, merge=True)\n\n        from hydra.core.override_parser.overrides_parser import OverridesParser\n\n        parser = OverridesParser.create()\n        overrides = parser.parse_overrides(overrides)\n        for o in overrides:\n            key = o.key_or_group\n            value = o.value()\n            if o.is_delete():\n                # TODO support this\n                raise NotImplementedError(\"deletion is not yet a supported override\")\n            safe_update(cfg, key, value)\n        return cfg\n\n    @staticmethod\n    def to_py(cfg, prefix: str = \"cfg.\"):\n        \"\"\"\n        Try to convert a config object into Python-like psuedo code.\n\n        Note that perfect conversion is not always possible. So the returned\n        results are mainly meant to be human-readable, and not meant to be executed.\n\n        Args:\n            cfg: an omegaconf config object\n            prefix: root name for the resulting code (default: \"cfg.\")\n\n\n        Returns:\n            str of formatted Python code\n        \"\"\"\n        import black\n\n        cfg = OmegaConf.to_container(cfg, resolve=True)\n\n        def _to_str(obj, prefix=None, inside_call=False):\n            if prefix is None:\n                prefix = []\n            if isinstance(obj, abc.Mapping) and \"_target_\" in obj:\n                # Dict representing a function call\n                target = _convert_target_to_string(obj.pop(\"_target_\"))\n                args = []\n                for k, v in sorted(obj.items()):\n                    args.append(f\"{k}={_to_str(v, inside_call=True)}\")\n                args = \", \".join(args)\n                call = f\"{target}({args})\"\n                return \"\".join(prefix) + call\n            elif isinstance(obj, abc.Mapping) and not inside_call:\n                # Dict that is not inside a call is a list of top-level config objects that we\n                # render as one object per line with dot separated prefixes\n                key_list = []\n                for k, v in sorted(obj.items()):\n                    if isinstance(v, abc.Mapping) and \"_target_\" not in v:\n                        key_list.append(_to_str(v, prefix=prefix + [k + \".\"]))\n                    else:\n                        key = \"\".join(prefix) + k\n                        key_list.append(f\"{key}={_to_str(v)}\")\n                return \"\\n\".join(key_list)\n            elif isinstance(obj, abc.Mapping):\n                # Dict that is inside a call is rendered as a regular dict\n                return (\n                    \"{\"\n                    + \",\".join(\n                        f\"{repr(k)}: {_to_str(v, inside_call=inside_call)}\"\n                        for k, v in sorted(obj.items())\n                    )\n                    + \"}\"\n                )\n            elif isinstance(obj, list):\n                return \"[\" + \",\".join(_to_str(x, inside_call=inside_call) for x in obj) + \"]\"\n            else:\n                return repr(obj)\n\n        py_str = _to_str(cfg, prefix=[prefix])\n        try:\n            return black.format_str(py_str, mode=black.Mode())\n        except black.InvalidInput:\n            return py_str\n"
  },
  {
    "path": "VPS_Module/detectron2/engine/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom .launch import *\nfrom .train_loop import *\n\n__all__ = [k for k in globals().keys() if not k.startswith(\"_\")]\n\n\n# prefer to let hooks and defaults live in separate namespaces (therefore not in __all__)\n# but still make them available here\nfrom .hooks import *\nfrom .defaults import *\n"
  },
  {
    "path": "VPS_Module/detectron2/engine/defaults.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n\n\"\"\"\nThis file contains components with some default boilerplate logic user may need\nin training / testing. They will not work for everyone, but many users may find them useful.\n\nThe behavior of functions/classes in this file is subject to change,\nsince they are meant to represent the \"common default behavior\" people need in their projects.\n\"\"\"\n\nimport argparse\nimport logging\nimport os\nimport sys\nimport weakref\nfrom collections import OrderedDict\nfrom typing import Optional\nimport torch\nfrom fvcore.nn.precise_bn import get_bn_modules\nfrom omegaconf import OmegaConf\nfrom torch.nn.parallel import DistributedDataParallel\n\nimport detectron2.data.transforms as T\nfrom detectron2.checkpoint import DetectionCheckpointer\nfrom detectron2.config import CfgNode, LazyConfig\nfrom detectron2.data import (\n    MetadataCatalog,\n    build_detection_test_loader,\n    build_detection_train_loader,\n)\nfrom detectron2.evaluation import (\n    DatasetEvaluator,\n    inference_on_dataset,\n    print_csv_format,\n    verify_results,\n)\nfrom detectron2.modeling import build_model\nfrom detectron2.solver import build_lr_scheduler, build_optimizer\nfrom detectron2.utils import comm\nfrom detectron2.utils.collect_env import collect_env_info\nfrom detectron2.utils.env import seed_all_rng\nfrom detectron2.utils.events import CommonMetricPrinter, JSONWriter, TensorboardXWriter\nfrom detectron2.utils.file_io import PathManager\nfrom detectron2.utils.logger import setup_logger\n\nfrom . import hooks\nfrom .train_loop import AMPTrainer, SimpleTrainer, TrainerBase\n\n__all__ = [\n    \"create_ddp_model\",\n    \"default_argument_parser\",\n    \"default_setup\",\n    \"default_writers\",\n    \"DefaultPredictor\",\n    \"DefaultTrainer\",\n]\n\n\ndef create_ddp_model(model, *, fp16_compression=False, **kwargs):\n    \"\"\"\n    Create a DistributedDataParallel model if there are >1 processes.\n\n    Args:\n        model: a torch.nn.Module\n        fp16_compression: add fp16 compression hooks to the ddp object.\n            See more at https://pytorch.org/docs/stable/ddp_comm_hooks.html#torch.distributed.algorithms.ddp_comm_hooks.default_hooks.fp16_compress_hook\n        kwargs: other arguments of :module:`torch.nn.parallel.DistributedDataParallel`.\n    \"\"\"  # noqa\n    if comm.get_world_size() == 1:\n        return model\n    if \"device_ids\" not in kwargs:\n        kwargs[\"device_ids\"] = [comm.get_local_rank()]\n    ddp = DistributedDataParallel(model, **kwargs)\n    if fp16_compression:\n        from torch.distributed.algorithms.ddp_comm_hooks import default as comm_hooks\n\n        ddp.register_comm_hook(state=None, hook=comm_hooks.fp16_compress_hook)\n    return ddp\n\n\ndef default_argument_parser(epilog=None):\n    \"\"\"\n    Create a parser with some common arguments used by detectron2 users.\n\n    Args:\n        epilog (str): epilog passed to ArgumentParser describing the usage.\n\n    Returns:\n        argparse.ArgumentParser:\n    \"\"\"\n    parser = argparse.ArgumentParser(\n        epilog=epilog\n        or f\"\"\"\nExamples:\n\nRun on single machine:\n    $ {sys.argv[0]} --num-gpus 8 --config-file cfg.yaml\n\nChange some config options:\n    $ {sys.argv[0]} --config-file cfg.yaml MODEL.WEIGHTS /path/to/weight.pth SOLVER.BASE_LR 0.001\n\nRun on multiple machines:\n    (machine0)$ {sys.argv[0]} --machine-rank 0 --num-machines 2 --dist-url <URL> [--other-flags]\n    (machine1)$ {sys.argv[0]} --machine-rank 1 --num-machines 2 --dist-url <URL> [--other-flags]\n\"\"\",\n        formatter_class=argparse.RawDescriptionHelpFormatter,\n    )\n    parser.add_argument(\"--config-file\", default=\"\", metavar=\"FILE\", help=\"path to config file\")\n    parser.add_argument(\n        \"--resume\",\n        action=\"store_true\",\n        help=\"Whether to attempt to resume from the checkpoint directory. \"\n        \"See documentation of `DefaultTrainer.resume_or_load()` for what it means.\",\n    )\n    parser.add_argument(\"--eval-only\", action=\"store_true\", help=\"perform evaluation only\")\n    parser.add_argument(\"--best_weight\", action=\"store_true\", help=\"among weights find one with best pq\")\n    parser.add_argument(\"--num-gpus\", type=int, default=1, help=\"number of gpus *per machine*\")\n    parser.add_argument(\"--num-machines\", type=int, default=1, help=\"total number of machines\")\n    parser.add_argument(\n        \"--machine-rank\", type=int, default=0, help=\"the rank of this machine (unique per machine)\"\n    )\n\n    # PyTorch still may leave orphan processes in multi-gpu training.\n    # Therefore we use a deterministic way to obtain port,\n    # so that users are aware of orphan processes by seeing the port occupied.\n    port = 2 ** 15 + 2 ** 14 + hash(os.getuid() if sys.platform != \"win32\" else 1) % 2 ** 14\n    parser.add_argument(\n        \"--dist-url\",\n        default=\"tcp://127.0.0.1:{}\".format(port),\n        help=\"initialization URL for pytorch distributed backend. See \"\n        \"https://pytorch.org/docs/stable/distributed.html for details.\",\n    )\n    parser.add_argument(\n        \"opts\",\n        help=\"\"\"\nModify config options at the end of the command. For Yacs configs, use\nspace-separated \"PATH.KEY VALUE\" pairs.\nFor python-based LazyConfig, use \"path.key=value\".\n        \"\"\".strip(),\n        default=None,\n        nargs=argparse.REMAINDER,\n    )\n    return parser\n\n\ndef _try_get_key(cfg, *keys, default=None):\n    \"\"\"\n    Try select keys from cfg until the first key that exists. Otherwise return default.\n    \"\"\"\n    if isinstance(cfg, CfgNode):\n        cfg = OmegaConf.create(cfg.dump())\n    for k in keys:\n        none = object()\n        p = OmegaConf.select(cfg, k, default=none)\n        if p is not none:\n            return p\n    return default\n\n\ndef _highlight(code, filename):\n    try:\n        import pygments\n    except ImportError:\n        return code\n\n    from pygments.lexers import Python3Lexer, YamlLexer\n    from pygments.formatters import Terminal256Formatter\n\n    lexer = Python3Lexer() if filename.endswith(\".py\") else YamlLexer()\n    code = pygments.highlight(code, lexer, Terminal256Formatter(style=\"monokai\"))\n    return code\n\n\ndef default_setup(cfg, args):\n    \"\"\"\n    Perform some basic common setups at the beginning of a job, including:\n\n    1. Set up the detectron2 logger\n    2. Log basic information about environment, cmdline arguments, and config\n    3. Backup the config to the output directory\n\n    Args:\n        cfg (CfgNode or omegaconf.DictConfig): the full config to be used\n        args (argparse.NameSpace): the command line arguments to be logged\n    \"\"\"\n    output_dir = _try_get_key(cfg, \"OUTPUT_DIR\", \"output_dir\", \"train.output_dir\")\n    if comm.is_main_process() and output_dir:\n        PathManager.mkdirs(output_dir)\n\n    rank = comm.get_rank()\n    setup_logger(output_dir, distributed_rank=rank, name=\"fvcore\")\n    logger = setup_logger(output_dir, distributed_rank=rank)\n\n    logger.info(\"Rank of current process: {}. World size: {}\".format(rank, comm.get_world_size()))\n    logger.info(\"Environment info:\\n\" + collect_env_info())\n\n    logger.info(\"Command line arguments: \" + str(args))\n    if hasattr(args, \"config_file\") and args.config_file != \"\":\n        logger.info(\n            \"Contents of args.config_file={}:\\n{}\".format(\n                args.config_file,\n                _highlight(PathManager.open(args.config_file, \"r\").read(), args.config_file),\n            )\n        )\n\n    if comm.is_main_process() and output_dir:\n        # Note: some of our scripts may expect the existence of\n        # config.yaml in output directory\n        path = os.path.join(output_dir, \"config.yaml\")\n        if isinstance(cfg, CfgNode):\n            logger.info(\"Running with full config:\\n{}\".format(_highlight(cfg.dump(), \".yaml\")))\n            with PathManager.open(path, \"w\") as f:\n                f.write(cfg.dump())\n        else:\n            LazyConfig.save(cfg, path)\n        logger.info(\"Full config saved to {}\".format(path))\n\n    # make sure each worker has a different, yet deterministic seed if specified\n    seed = _try_get_key(cfg, \"SEED\", \"train.seed\", default=-1)\n    seed_all_rng(None if seed < 0 else seed + rank)\n\n    # cudnn benchmark has large overhead. It shouldn't be used considering the small size of\n    # typical validation set.\n    if not (hasattr(args, \"eval_only\") and args.eval_only):\n        torch.backends.cudnn.benchmark = _try_get_key(\n            cfg, \"CUDNN_BENCHMARK\", \"train.cudnn_benchmark\", default=False\n        )\n\n\ndef default_writers(output_dir: str, max_iter: Optional[int] = None):\n    \"\"\"\n    Build a list of :class:`EventWriter` to be used.\n    It now consists of a :class:`CommonMetricPrinter`,\n    :class:`TensorboardXWriter` and :class:`JSONWriter`.\n\n    Args:\n        output_dir: directory to store JSON metrics and tensorboard events\n        max_iter: the total number of iterations\n\n    Returns:\n        list[EventWriter]: a list of :class:`EventWriter` objects.\n    \"\"\"\n    PathManager.mkdirs(output_dir)\n    return [\n        # It may not always print what you want to see, since it prints \"common\" metrics only.\n        CommonMetricPrinter(max_iter),\n        JSONWriter(os.path.join(output_dir, \"metrics.json\")),\n        TensorboardXWriter(output_dir),\n    ]\n\n\nclass DefaultPredictor:\n    \"\"\"\n    Create a simple end-to-end predictor with the given config that runs on\n    single device for a single input image.\n\n    Compared to using the model directly, this class does the following additions:\n\n    1. Load checkpoint from `cfg.MODEL.WEIGHTS`.\n    2. Always take BGR image as the input and apply conversion defined by `cfg.INPUT.FORMAT`.\n    3. Apply resizing defined by `cfg.INPUT.{MIN,MAX}_SIZE_TEST`.\n    4. Take one input image and produce a single output, instead of a batch.\n\n    This is meant for simple demo purposes, so it does the above steps automatically.\n    This is not meant for benchmarks or running complicated inference logic.\n    If you'd like to do anything more complicated, please refer to its source code as\n    examples to build and use the model manually.\n\n    Attributes:\n        metadata (Metadata): the metadata of the underlying dataset, obtained from\n            cfg.DATASETS.TEST.\n\n    Examples:\n    ::\n        pred = DefaultPredictor(cfg)\n        inputs = cv2.imread(\"input.jpg\")\n        outputs = pred(inputs)\n    \"\"\"\n\n    def __init__(self, cfg):\n        self.cfg = cfg.clone()  # cfg can be modified by model\n        self.model = build_model(self.cfg)\n        self.model.eval()\n        if len(cfg.DATASETS.TEST):\n            self.metadata = MetadataCatalog.get(cfg.DATASETS.TEST[0])\n\n        checkpointer = DetectionCheckpointer(self.model)\n        checkpointer.load(cfg.MODEL.WEIGHTS)\n\n        self.aug = T.ResizeShortestEdge(\n            [cfg.INPUT.MIN_SIZE_TEST, cfg.INPUT.MIN_SIZE_TEST], cfg.INPUT.MAX_SIZE_TEST\n        )\n\n        self.input_format = cfg.INPUT.FORMAT\n        assert self.input_format in [\"RGB\", \"BGR\"], self.input_format\n\n    def __call__(self, original_image):\n        \"\"\"\n        Args:\n            original_image (np.ndarray): an image of shape (H, W, C) (in BGR order).\n\n        Returns:\n            predictions (dict):\n                the output of the model for one image only.\n                See :doc:`/tutorials/models` for details about the format.\n        \"\"\"\n        with torch.no_grad():  # https://github.com/sphinx-doc/sphinx/issues/4258\n            # Apply pre-processing to image.\n            if self.input_format == \"RGB\":\n                # whether the model expects BGR inputs or RGB\n                original_image = original_image[:, :, ::-1]\n            height, width = original_image.shape[:2]\n            image = self.aug.get_transform(original_image).apply_image(original_image)\n            image = torch.as_tensor(image.astype(\"float32\").transpose(2, 0, 1))\n\n            inputs = {\"image\": image, \"height\": height, \"width\": width}\n            predictions = self.model([inputs])[0]\n            return predictions\n\n\nclass DefaultTrainer(TrainerBase):\n    \"\"\"\n    A trainer with default training logic. It does the following:\n\n    1. Create a :class:`SimpleTrainer` using model, optimizer, dataloader\n       defined by the given config. Create a LR scheduler defined by the config.\n    2. Load the last checkpoint or `cfg.MODEL.WEIGHTS`, if exists, when\n       `resume_or_load` is called.\n    3. Register a few common hooks defined by the config.\n\n    It is created to simplify the **standard model training workflow** and reduce code boilerplate\n    for users who only need the standard training workflow, with standard features.\n    It means this class makes *many assumptions* about your training logic that\n    may easily become invalid in a new research. In fact, any assumptions beyond those made in the\n    :class:`SimpleTrainer` are too much for research.\n\n    The code of this class has been annotated about restrictive assumptions it makes.\n    When they do not work for you, you're encouraged to:\n\n    1. Overwrite methods of this class, OR:\n    2. Use :class:`SimpleTrainer`, which only does minimal SGD training and\n       nothing else. You can then add your own hooks if needed. OR:\n    3. Write your own training loop similar to `tools/plain_train_net.py`.\n\n    See the :doc:`/tutorials/training` tutorials for more details.\n\n    Note that the behavior of this class, like other functions/classes in\n    this file, is not stable, since it is meant to represent the \"common default behavior\".\n    It is only guaranteed to work well with the standard models and training workflow in detectron2.\n    To obtain more stable behavior, write your own training logic with other public APIs.\n\n    Examples:\n    ::\n        trainer = DefaultTrainer(cfg)\n        trainer.resume_or_load()  # load last checkpoint or MODEL.WEIGHTS\n        trainer.train()\n\n    Attributes:\n        scheduler:\n        checkpointer (DetectionCheckpointer):\n        cfg (CfgNode):\n    \"\"\"\n\n    def __init__(self, cfg):\n        \"\"\"\n        Args:\n            cfg (CfgNode):\n        \"\"\"\n        super().__init__()\n        logger = logging.getLogger(\"detectron2\")\n        if not logger.isEnabledFor(logging.INFO):  # setup_logger is not called for d2\n            setup_logger()\n        cfg = DefaultTrainer.auto_scale_workers(cfg, comm.get_world_size())\n\n        # Assume these objects must be constructed in this order.\n        model = self.build_model(cfg)\n        optimizer = self.build_optimizer(cfg, model)\n        data_loader = self.build_train_loader(cfg)\n\n        model = create_ddp_model(model, broadcast_buffers=False)\n        self._trainer = (AMPTrainer if cfg.SOLVER.AMP.ENABLED else SimpleTrainer)(\n            model, data_loader, optimizer\n        )\n\n        self.scheduler = self.build_lr_scheduler(cfg, optimizer)\n        self.checkpointer = DetectionCheckpointer(\n            # Assume you want to save checkpoints together with logs/statistics\n            model,\n            cfg.OUTPUT_DIR,\n            trainer=weakref.proxy(self),\n        )\n        self.start_iter = 0\n        self.max_iter = cfg.SOLVER.MAX_ITER\n        self.cfg = cfg\n\n        self.register_hooks(self.build_hooks())\n\n    def resume_or_load(self, resume=True):\n        \"\"\"\n        If `resume==True` and `cfg.OUTPUT_DIR` contains the last checkpoint (defined by\n        a `last_checkpoint` file), resume from the file. Resuming means loading all\n        available states (eg. optimizer and scheduler) and update iteration counter\n        from the checkpoint. ``cfg.MODEL.WEIGHTS`` will not be used.\n\n        Otherwise, this is considered as an independent training. The method will load model\n        weights from the file `cfg.MODEL.WEIGHTS` (but will not load other states) and start\n        from iteration 0.\n\n        Args:\n            resume (bool): whether to do resume or not\n        \"\"\"\n        self.checkpointer.resume_or_load(self.cfg.MODEL.WEIGHTS, resume=resume)\n        if resume and self.checkpointer.has_checkpoint():\n            # The checkpoint stores the training iteration that just finished, thus we start\n            # at the next iteration\n            self.start_iter = self.iter + 1\n\n    def build_hooks(self):\n        \"\"\"\n        Build a list of default hooks, including timing, evaluation,\n        checkpointing, lr scheduling, precise BN, writing events.\n\n        Returns:\n            list[HookBase]:\n        \"\"\"\n        cfg = self.cfg.clone()\n        cfg.defrost()\n        cfg.DATALOADER.NUM_WORKERS = 0  # save some memory and time for PreciseBN\n\n        ret = [\n            hooks.IterationTimer(),\n            hooks.LRScheduler(),\n            hooks.PreciseBN(\n                # Run at the same freq as (but before) evaluation.\n                cfg.TEST.EVAL_PERIOD,\n                self.model,\n                # Build a new data loader to not affect training\n                self.build_train_loader(cfg),\n                cfg.TEST.PRECISE_BN.NUM_ITER,\n            )\n            if cfg.TEST.PRECISE_BN.ENABLED and get_bn_modules(self.model)\n            else None,\n        ]\n\n        # Do PreciseBN before checkpointer, because it updates the model and need to\n        # be saved by checkpointer.\n        # This is not always the best: if checkpointing has a different frequency,\n        # some checkpoints may have more precise statistics than others.\n        if comm.is_main_process():\n            ret.append(hooks.PeriodicCheckpointer(self.checkpointer, cfg.SOLVER.CHECKPOINT_PERIOD))\n\n        def test_and_save_results():\n            self._last_eval_results = self.test(self.cfg, self.model)\n            return self._last_eval_results\n\n        # Do evaluation after checkpointer, because then if it fails,\n        # we can use the saved checkpoint to debug.\n        ret.append(hooks.EvalHook(cfg.TEST.EVAL_PERIOD, test_and_save_results))\n\n        if comm.is_main_process():\n            # Here the default print/log frequency of each writer is used.\n            # run writers in the end, so that evaluation metrics are written\n            ret.append(hooks.PeriodicWriter(self.build_writers(), period=20))\n        return ret\n\n    def build_writers(self):\n        \"\"\"\n        Build a list of writers to be used using :func:`default_writers()`.\n        If you'd like a different list of writers, you can overwrite it in\n        your trainer.\n\n        Returns:\n            list[EventWriter]: a list of :class:`EventWriter` objects.\n        \"\"\"\n        return default_writers(self.cfg.OUTPUT_DIR, self.max_iter)\n\n    def train(self):\n        \"\"\"\n        Run training.\n\n        Returns:\n            OrderedDict of results, if evaluation is enabled. Otherwise None.\n        \"\"\"\n        super().train(self.start_iter, self.max_iter)\n        if len(self.cfg.TEST.EXPECTED_RESULTS) and comm.is_main_process():\n            assert hasattr(\n                self, \"_last_eval_results\"\n            ), \"No evaluation results obtained during training!\"\n            verify_results(self.cfg, self._last_eval_results)\n            return self._last_eval_results\n\n    def run_step(self):\n        self._trainer.iter = self.iter\n        self._trainer.run_step()\n\n    def state_dict(self):\n        ret = super().state_dict()\n        ret[\"_trainer\"] = self._trainer.state_dict()\n        return ret\n\n    def load_state_dict(self, state_dict):\n        super().load_state_dict(state_dict)\n        self._trainer.load_state_dict(state_dict[\"_trainer\"])\n\n    @classmethod\n    def build_model(cls, cfg):\n        \"\"\"\n        Returns:\n            torch.nn.Module:\n\n        It now calls :func:`detectron2.modeling.build_model`.\n        Overwrite it if you'd like a different model.\n        \"\"\"\n        model = build_model(cfg)\n        logger = logging.getLogger(__name__)\n        logger.info(\"Model:\\n{}\".format(model))\n        return model\n\n    @classmethod\n    def build_optimizer(cls, cfg, model):\n        \"\"\"\n        Returns:\n            torch.optim.Optimizer:\n\n        It now calls :func:`detectron2.solver.build_optimizer`.\n        Overwrite it if you'd like a different optimizer.\n        \"\"\"\n        return build_optimizer(cfg, model)\n\n    @classmethod\n    def build_lr_scheduler(cls, cfg, optimizer):\n        \"\"\"\n        It now calls :func:`detectron2.solver.build_lr_scheduler`.\n        Overwrite it if you'd like a different scheduler.\n        \"\"\"\n        return build_lr_scheduler(cfg, optimizer)\n\n    @classmethod\n    def build_train_loader(cls, cfg):\n        \"\"\"\n        Returns:\n            iterable\n\n        It now calls :func:`detectron2.data.build_detection_train_loader`.\n        Overwrite it if you'd like a different data loader.\n        \"\"\"\n        return build_detection_train_loader(cfg)\n\n    @classmethod\n    def build_test_loader(cls, cfg, dataset_name):\n        \"\"\"\n        Returns:\n            iterable\n\n        It now calls :func:`detectron2.data.build_detection_test_loader`.\n        Overwrite it if you'd like a different data loader.\n        \"\"\"\n        return build_detection_test_loader(cfg, dataset_name)\n\n    @classmethod\n    def build_evaluator(cls, cfg, dataset_name):\n        \"\"\"\n        Returns:\n            DatasetEvaluator or None\n\n        It is not implemented by default.\n        \"\"\"\n        raise NotImplementedError(\n            \"\"\"\nIf you want DefaultTrainer to automatically run evaluation,\nplease implement `build_evaluator()` in subclasses (see train_net.py for example).\nAlternatively, you can call evaluation functions yourself (see Colab balloon tutorial for example).\n\"\"\"\n        )\n\n    @classmethod\n    def test(cls, cfg, model, evaluators=None):\n        \"\"\"\n        Evaluate the given model. The given model is expected to already contain\n        weights to evaluate.\n\n        Args:\n            cfg (CfgNode):\n            model (nn.Module):\n            evaluators (list[DatasetEvaluator] or None): if None, will call\n                :meth:`build_evaluator`. Otherwise, must have the same length as\n                ``cfg.DATASETS.TEST``.\n\n        Returns:\n            dict: a dict of result metrics\n        \"\"\"\n        logger = logging.getLogger(__name__)\n        if isinstance(evaluators, DatasetEvaluator):\n            evaluators = [evaluators]\n        if evaluators is not None:\n            assert len(cfg.DATASETS.TEST) == len(evaluators), \"{} != {}\".format(\n                len(cfg.DATASETS.TEST), len(evaluators)\n            )\n\n        results = OrderedDict()\n        for idx, dataset_name in enumerate(cfg.DATASETS.TEST):\n            data_loader = cls.build_test_loader(cfg, dataset_name)\n            # When evaluators are passed in as arguments,\n            # implicitly assume that evaluators can be created before data_loader.\n            if evaluators is not None:\n                evaluator = evaluators[idx]\n            else:\n                try:\n                    evaluator = cls.build_evaluator(cfg, dataset_name)\n                except NotImplementedError:\n                    logger.warn(\n                        \"No evaluator found. Use `DefaultTrainer.test(evaluators=)`, \"\n                        \"or implement its `build_evaluator` method.\"\n                    )\n                    results[dataset_name] = {}\n                    continue\n            results_i = inference_on_dataset(model, data_loader, evaluator)\n            results[dataset_name] = results_i\n            if comm.is_main_process():\n                assert isinstance(\n                    results_i, dict\n                ), \"Evaluator must return a dict on the main process. Got {} instead.\".format(\n                    results_i\n                )\n                logger.info(\"Evaluation results for {} in csv format:\".format(dataset_name))\n                print_csv_format(results_i)\n\n        if len(results) == 1:\n            results = list(results.values())[0]\n        return results\n\n    @staticmethod\n    def auto_scale_workers(cfg, num_workers: int):\n        \"\"\"\n        When the config is defined for certain number of workers (according to\n        ``cfg.SOLVER.REFERENCE_WORLD_SIZE``) that's different from the number of\n        workers currently in use, returns a new cfg where the total batch size\n        is scaled so that the per-GPU batch size stays the same as the\n        original ``IMS_PER_BATCH // REFERENCE_WORLD_SIZE``.\n\n        Other config options are also scaled accordingly:\n        * training steps and warmup steps are scaled inverse proportionally.\n        * learning rate are scaled proportionally, following :paper:`ImageNet in 1h`.\n\n        For example, with the original config like the following:\n\n        .. code-block:: yaml\n\n            IMS_PER_BATCH: 16\n            BASE_LR: 0.1\n            REFERENCE_WORLD_SIZE: 8\n            MAX_ITER: 5000\n            STEPS: (4000,)\n            CHECKPOINT_PERIOD: 1000\n\n        When this config is used on 16 GPUs instead of the reference number 8,\n        calling this method will return a new config with:\n\n        .. code-block:: yaml\n\n            IMS_PER_BATCH: 32\n            BASE_LR: 0.2\n            REFERENCE_WORLD_SIZE: 16\n            MAX_ITER: 2500\n            STEPS: (2000,)\n            CHECKPOINT_PERIOD: 500\n\n        Note that both the original config and this new config can be trained on 16 GPUs.\n        It's up to user whether to enable this feature (by setting ``REFERENCE_WORLD_SIZE``).\n\n        Returns:\n            CfgNode: a new config. Same as original if ``cfg.SOLVER.REFERENCE_WORLD_SIZE==0``.\n        \"\"\"\n        old_world_size = cfg.SOLVER.REFERENCE_WORLD_SIZE\n        if old_world_size == 0 or old_world_size == num_workers:\n            return cfg\n        cfg = cfg.clone()\n        frozen = cfg.is_frozen()\n        cfg.defrost()\n\n        assert (\n            cfg.SOLVER.IMS_PER_BATCH % old_world_size == 0\n        ), \"Invalid REFERENCE_WORLD_SIZE in config!\"\n        scale = num_workers / old_world_size\n        bs = cfg.SOLVER.IMS_PER_BATCH = int(round(cfg.SOLVER.IMS_PER_BATCH * scale))\n        lr = cfg.SOLVER.BASE_LR = cfg.SOLVER.BASE_LR * scale\n        max_iter = cfg.SOLVER.MAX_ITER = int(round(cfg.SOLVER.MAX_ITER / scale))\n        warmup_iter = cfg.SOLVER.WARMUP_ITERS = int(round(cfg.SOLVER.WARMUP_ITERS / scale))\n        cfg.SOLVER.STEPS = tuple(int(round(s / scale)) for s in cfg.SOLVER.STEPS)\n        cfg.TEST.EVAL_PERIOD = int(round(cfg.TEST.EVAL_PERIOD / scale))\n        cfg.SOLVER.CHECKPOINT_PERIOD = int(round(cfg.SOLVER.CHECKPOINT_PERIOD / scale))\n        cfg.SOLVER.REFERENCE_WORLD_SIZE = num_workers  # maintain invariant\n        logger = logging.getLogger(__name__)\n        logger.info(\n            f\"Auto-scaling the config to batch_size={bs}, learning_rate={lr}, \"\n            f\"max_iter={max_iter}, warmup={warmup_iter}.\"\n        )\n\n        if frozen:\n            cfg.freeze()\n        return cfg\n\n\n# Access basic attributes from the underlying trainer\nfor _attr in [\"model\", \"data_loader\", \"optimizer\"]:\n    setattr(\n        DefaultTrainer,\n        _attr,\n        property(\n            # getter\n            lambda self, x=_attr: getattr(self._trainer, x),\n            # setter\n            lambda self, value, x=_attr: setattr(self._trainer, x, value),\n        ),\n    )\n"
  },
  {
    "path": "VPS_Module/detectron2/engine/hooks.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport datetime\nimport itertools\nimport logging\nimport math\nimport operator\nimport os\nimport tempfile\nimport time\nimport warnings\nfrom collections import Counter\nimport torch\nfrom fvcore.common.checkpoint import Checkpointer\nfrom fvcore.common.checkpoint import PeriodicCheckpointer as _PeriodicCheckpointer\nfrom fvcore.common.param_scheduler import ParamScheduler\nfrom fvcore.common.timer import Timer\nfrom fvcore.nn.precise_bn import get_bn_modules, update_bn_stats\n\nimport detectron2.utils.comm as comm\nfrom detectron2.evaluation.testing import flatten_results_dict\nfrom detectron2.solver import LRMultiplier\nfrom detectron2.utils.events import EventStorage, EventWriter\nfrom detectron2.utils.file_io import PathManager\n\nfrom .train_loop import HookBase\n\n__all__ = [\n    \"CallbackHook\",\n    \"IterationTimer\",\n    \"PeriodicWriter\",\n    \"PeriodicCheckpointer\",\n    \"BestCheckpointer\",\n    \"LRScheduler\",\n    \"AutogradProfiler\",\n    \"EvalHook\",\n    \"PreciseBN\",\n    \"TorchProfiler\",\n    \"TorchMemoryStats\",\n]\n\n\n\"\"\"\nImplement some common hooks.\n\"\"\"\n\n\nclass CallbackHook(HookBase):\n    \"\"\"\n    Create a hook using callback functions provided by the user.\n    \"\"\"\n\n    def __init__(self, *, before_train=None, after_train=None, before_step=None, after_step=None):\n        \"\"\"\n        Each argument is a function that takes one argument: the trainer.\n        \"\"\"\n        self._before_train = before_train\n        self._before_step = before_step\n        self._after_step = after_step\n        self._after_train = after_train\n\n    def before_train(self):\n        if self._before_train:\n            self._before_train(self.trainer)\n\n    def after_train(self):\n        if self._after_train:\n            self._after_train(self.trainer)\n        # The functions may be closures that hold reference to the trainer\n        # Therefore, delete them to avoid circular reference.\n        del self._before_train, self._after_train\n        del self._before_step, self._after_step\n\n    def before_step(self):\n        if self._before_step:\n            self._before_step(self.trainer)\n\n    def after_step(self):\n        if self._after_step:\n            self._after_step(self.trainer)\n\n\nclass IterationTimer(HookBase):\n    \"\"\"\n    Track the time spent for each iteration (each run_step call in the trainer).\n    Print a summary in the end of training.\n\n    This hook uses the time between the call to its :meth:`before_step`\n    and :meth:`after_step` methods.\n    Under the convention that :meth:`before_step` of all hooks should only\n    take negligible amount of time, the :class:`IterationTimer` hook should be\n    placed at the beginning of the list of hooks to obtain accurate timing.\n    \"\"\"\n\n    def __init__(self, warmup_iter=3):\n        \"\"\"\n        Args:\n            warmup_iter (int): the number of iterations at the beginning to exclude\n                from timing.\n        \"\"\"\n        self._warmup_iter = warmup_iter\n        self._step_timer = Timer()\n        self._start_time = time.perf_counter()\n        self._total_timer = Timer()\n\n    def before_train(self):\n        self._start_time = time.perf_counter()\n        self._total_timer.reset()\n        self._total_timer.pause()\n\n    def after_train(self):\n        logger = logging.getLogger(__name__)\n        total_time = time.perf_counter() - self._start_time\n        total_time_minus_hooks = self._total_timer.seconds()\n        hook_time = total_time - total_time_minus_hooks\n\n        num_iter = self.trainer.storage.iter + 1 - self.trainer.start_iter - self._warmup_iter\n\n        if num_iter > 0 and total_time_minus_hooks > 0:\n            # Speed is meaningful only after warmup\n            # NOTE this format is parsed by grep in some scripts\n            logger.info(\n                \"Overall training speed: {} iterations in {} ({:.4f} s / it)\".format(\n                    num_iter,\n                    str(datetime.timedelta(seconds=int(total_time_minus_hooks))),\n                    total_time_minus_hooks / num_iter,\n                )\n            )\n\n        logger.info(\n            \"Total training time: {} ({} on hooks)\".format(\n                str(datetime.timedelta(seconds=int(total_time))),\n                str(datetime.timedelta(seconds=int(hook_time))),\n            )\n        )\n\n    def before_step(self):\n        self._step_timer.reset()\n        self._total_timer.resume()\n\n    def after_step(self):\n        # +1 because we're in after_step, the current step is done\n        # but not yet counted\n        iter_done = self.trainer.storage.iter - self.trainer.start_iter + 1\n        if iter_done >= self._warmup_iter:\n            sec = self._step_timer.seconds()\n            self.trainer.storage.put_scalars(time=sec)\n        else:\n            self._start_time = time.perf_counter()\n            self._total_timer.reset()\n\n        self._total_timer.pause()\n\n\nclass PeriodicWriter(HookBase):\n    \"\"\"\n    Write events to EventStorage (by calling ``writer.write()``) periodically.\n\n    It is executed every ``period`` iterations and after the last iteration.\n    Note that ``period`` does not affect how data is smoothed by each writer.\n    \"\"\"\n\n    def __init__(self, writers, period=20):\n        \"\"\"\n        Args:\n            writers (list[EventWriter]): a list of EventWriter objects\n            period (int):\n        \"\"\"\n        self._writers = writers\n        for w in writers:\n            assert isinstance(w, EventWriter), w\n        self._period = period\n\n    def after_step(self):\n        if (self.trainer.iter + 1) % self._period == 0 or (\n            self.trainer.iter == self.trainer.max_iter - 1\n        ):\n            for writer in self._writers:\n                writer.write()\n\n    def after_train(self):\n        for writer in self._writers:\n            # If any new data is found (e.g. produced by other after_train),\n            # write them before closing\n            writer.write()\n            writer.close()\n\n\nclass PeriodicCheckpointer(_PeriodicCheckpointer, HookBase):\n    \"\"\"\n    Same as :class:`detectron2.checkpoint.PeriodicCheckpointer`, but as a hook.\n\n    Note that when used as a hook,\n    it is unable to save additional data other than what's defined\n    by the given `checkpointer`.\n\n    It is executed every ``period`` iterations and after the last iteration.\n    \"\"\"\n\n    def before_train(self):\n        self.max_iter = self.trainer.max_iter\n\n    def after_step(self):\n        # No way to use **kwargs\n        self.step(self.trainer.iter)\n\n\nclass BestCheckpointer(HookBase):\n    \"\"\"\n    Checkpoints best weights based off given metric.\n\n    This hook should be used in conjunction to and executed after the hook\n    that produces the metric, e.g. `EvalHook`.\n    \"\"\"\n\n    def __init__(\n        self,\n        eval_period: int,\n        checkpointer: Checkpointer,\n        val_metric: str,\n        mode: str = \"max\",\n        file_prefix: str = \"model_best\",\n    ) -> None:\n        \"\"\"\n        Args:\n            eval_period (int): the period `EvalHook` is set to run.\n            checkpointer: the checkpointer object used to save checkpoints.\n            val_metric (str): validation metric to track for best checkpoint, e.g. \"bbox/AP50\"\n            mode (str): one of {'max', 'min'}. controls whether the chosen val metric should be\n                maximized or minimized, e.g. for \"bbox/AP50\" it should be \"max\"\n            file_prefix (str): the prefix of checkpoint's filename, defaults to \"model_best\"\n        \"\"\"\n        self._logger = logging.getLogger(__name__)\n        self._period = eval_period\n        self._val_metric = val_metric\n        assert mode in [\n            \"max\",\n            \"min\",\n        ], f'Mode \"{mode}\" to `BestCheckpointer` is unknown. It should be one of {\"max\", \"min\"}.'\n        if mode == \"max\":\n            self._compare = operator.gt\n        else:\n            self._compare = operator.lt\n        self._checkpointer = checkpointer\n        self._file_prefix = file_prefix\n        self.best_metric = None\n        self.best_iter = None\n\n    def _update_best(self, val, iteration):\n        if math.isnan(val) or math.isinf(val):\n            return False\n        self.best_metric = val\n        self.best_iter = iteration\n        return True\n\n    def _best_checking(self):\n        metric_tuple = self.trainer.storage.latest().get(self._val_metric)\n        if metric_tuple is None:\n            self._logger.warning(\n                f\"Given val metric {self._val_metric} does not seem to be computed/stored.\"\n                \"Will not be checkpointing based on it.\"\n            )\n            return\n        else:\n            latest_metric, metric_iter = metric_tuple\n\n        if self.best_metric is None:\n            if self._update_best(latest_metric, metric_iter):\n                additional_state = {\"iteration\": metric_iter}\n                self._checkpointer.save(f\"{self._file_prefix}\", **additional_state)\n                self._logger.info(\n                    f\"Saved first model at {self.best_metric:0.5f} @ {self.best_iter} steps\"\n                )\n        elif self._compare(latest_metric, self.best_metric):\n            additional_state = {\"iteration\": metric_iter}\n            self._checkpointer.save(f\"{self._file_prefix}\", **additional_state)\n            self._logger.info(\n                f\"Saved best model as latest eval score for {self._val_metric} is \"\n                f\"{latest_metric:0.5f}, better than last best score \"\n                f\"{self.best_metric:0.5f} @ iteration {self.best_iter}.\"\n            )\n            self._update_best(latest_metric, metric_iter)\n        else:\n            self._logger.info(\n                f\"Not saving as latest eval score for {self._val_metric} is {latest_metric:0.5f}, \"\n                f\"not better than best score {self.best_metric:0.5f} @ iteration {self.best_iter}.\"\n            )\n\n    def after_step(self):\n        # same conditions as `EvalHook`\n        next_iter = self.trainer.iter + 1\n        if (\n            self._period > 0\n            and next_iter % self._period == 0\n            and next_iter != self.trainer.max_iter\n        ):\n            self._best_checking()\n\n    def after_train(self):\n        # same conditions as `EvalHook`\n        if self.trainer.iter + 1 >= self.trainer.max_iter:\n            self._best_checking()\n\n\nclass LRScheduler(HookBase):\n    \"\"\"\n    A hook which executes a torch builtin LR scheduler and summarizes the LR.\n    It is executed after every iteration.\n    \"\"\"\n\n    def __init__(self, optimizer=None, scheduler=None):\n        \"\"\"\n        Args:\n            optimizer (torch.optim.Optimizer):\n            scheduler (torch.optim.LRScheduler or fvcore.common.param_scheduler.ParamScheduler):\n                if a :class:`ParamScheduler` object, it defines the multiplier over the base LR\n                in the optimizer.\n\n        If any argument is not given, will try to obtain it from the trainer.\n        \"\"\"\n        self._optimizer = optimizer\n        self._scheduler = scheduler\n\n    def before_train(self):\n        self._optimizer = self._optimizer or self.trainer.optimizer\n        if isinstance(self.scheduler, ParamScheduler):\n            self._scheduler = LRMultiplier(\n                self._optimizer,\n                self.scheduler,\n                self.trainer.max_iter,\n                last_iter=self.trainer.iter - 1,\n            )\n        self._best_param_group_id = LRScheduler.get_best_param_group_id(self._optimizer)\n\n    @staticmethod\n    def get_best_param_group_id(optimizer):\n        # NOTE: some heuristics on what LR to summarize\n        # summarize the param group with most parameters\n        largest_group = max(len(g[\"params\"]) for g in optimizer.param_groups)\n\n        if largest_group == 1:\n            # If all groups have one parameter,\n            # then find the most common initial LR, and use it for summary\n            lr_count = Counter([g[\"lr\"] for g in optimizer.param_groups])\n            lr = lr_count.most_common()[0][0]\n            for i, g in enumerate(optimizer.param_groups):\n                if g[\"lr\"] == lr:\n                    return i\n        else:\n            for i, g in enumerate(optimizer.param_groups):\n                if len(g[\"params\"]) == largest_group:\n                    return i\n\n    def after_step(self):\n        lr = self._optimizer.param_groups[self._best_param_group_id][\"lr\"]\n        self.trainer.storage.put_scalar(\"lr\", lr, smoothing_hint=False)\n        self.scheduler.step()\n\n    @property\n    def scheduler(self):\n        return self._scheduler or self.trainer.scheduler\n\n    def state_dict(self):\n        if isinstance(self.scheduler, torch.optim.lr_scheduler._LRScheduler):\n            return self.scheduler.state_dict()\n        return {}\n\n    def load_state_dict(self, state_dict):\n        if isinstance(self.scheduler, torch.optim.lr_scheduler._LRScheduler):\n            logger = logging.getLogger(__name__)\n            logger.info(\"Loading scheduler from state_dict ...\")\n            self.scheduler.load_state_dict(state_dict)\n\n\nclass TorchProfiler(HookBase):\n    \"\"\"\n    A hook which runs `torch.profiler.profile`.\n\n    Examples:\n    ::\n        hooks.TorchProfiler(\n             lambda trainer: 10 < trainer.iter < 20, self.cfg.OUTPUT_DIR\n        )\n\n    The above example will run the profiler for iteration 10~20 and dump\n    results to ``OUTPUT_DIR``. We did not profile the first few iterations\n    because they are typically slower than the rest.\n    The result files can be loaded in the ``chrome://tracing`` page in chrome browser,\n    and the tensorboard visualizations can be visualized using\n    ``tensorboard --logdir OUTPUT_DIR/log``\n    \"\"\"\n\n    def __init__(self, enable_predicate, output_dir, *, activities=None, save_tensorboard=True):\n        \"\"\"\n        Args:\n            enable_predicate (callable[trainer -> bool]): a function which takes a trainer,\n                and returns whether to enable the profiler.\n                It will be called once every step, and can be used to select which steps to profile.\n            output_dir (str): the output directory to dump tracing files.\n            activities (iterable): same as in `torch.profiler.profile`.\n            save_tensorboard (bool): whether to save tensorboard visualizations at (output_dir)/log/\n        \"\"\"\n        self._enable_predicate = enable_predicate\n        self._activities = activities\n        self._output_dir = output_dir\n        self._save_tensorboard = save_tensorboard\n\n    def before_step(self):\n        if self._enable_predicate(self.trainer):\n            if self._save_tensorboard:\n                on_trace_ready = torch.profiler.tensorboard_trace_handler(\n                    os.path.join(\n                        self._output_dir,\n                        \"log\",\n                        \"profiler-tensorboard-iter{}\".format(self.trainer.iter),\n                    ),\n                    f\"worker{comm.get_rank()}\",\n                )\n            else:\n                on_trace_ready = None\n            self._profiler = torch.profiler.profile(\n                activities=self._activities,\n                on_trace_ready=on_trace_ready,\n                record_shapes=True,\n                profile_memory=True,\n                with_stack=True,\n                with_flops=True,\n            )\n            self._profiler.__enter__()\n        else:\n            self._profiler = None\n\n    def after_step(self):\n        if self._profiler is None:\n            return\n        self._profiler.__exit__(None, None, None)\n        if not self._save_tensorboard:\n            PathManager.mkdirs(self._output_dir)\n            out_file = os.path.join(\n                self._output_dir, \"profiler-trace-iter{}.json\".format(self.trainer.iter)\n            )\n            if \"://\" not in out_file:\n                self._profiler.export_chrome_trace(out_file)\n            else:\n                # Support non-posix filesystems\n                with tempfile.TemporaryDirectory(prefix=\"detectron2_profiler\") as d:\n                    tmp_file = os.path.join(d, \"tmp.json\")\n                    self._profiler.export_chrome_trace(tmp_file)\n                    with open(tmp_file) as f:\n                        content = f.read()\n                with PathManager.open(out_file, \"w\") as f:\n                    f.write(content)\n\n\nclass AutogradProfiler(TorchProfiler):\n    \"\"\"\n    A hook which runs `torch.autograd.profiler.profile`.\n\n    Examples:\n    ::\n        hooks.AutogradProfiler(\n             lambda trainer: 10 < trainer.iter < 20, self.cfg.OUTPUT_DIR\n        )\n\n    The above example will run the profiler for iteration 10~20 and dump\n    results to ``OUTPUT_DIR``. We did not profile the first few iterations\n    because they are typically slower than the rest.\n    The result files can be loaded in the ``chrome://tracing`` page in chrome browser.\n\n    Note:\n        When used together with NCCL on older version of GPUs,\n        autograd profiler may cause deadlock because it unnecessarily allocates\n        memory on every device it sees. The memory management calls, if\n        interleaved with NCCL calls, lead to deadlock on GPUs that do not\n        support ``cudaLaunchCooperativeKernelMultiDevice``.\n    \"\"\"\n\n    def __init__(self, enable_predicate, output_dir, *, use_cuda=True):\n        \"\"\"\n        Args:\n            enable_predicate (callable[trainer -> bool]): a function which takes a trainer,\n                and returns whether to enable the profiler.\n                It will be called once every step, and can be used to select which steps to profile.\n            output_dir (str): the output directory to dump tracing files.\n            use_cuda (bool): same as in `torch.autograd.profiler.profile`.\n        \"\"\"\n        warnings.warn(\"AutogradProfiler has been deprecated in favor of TorchProfiler.\")\n        self._enable_predicate = enable_predicate\n        self._use_cuda = use_cuda\n        self._output_dir = output_dir\n\n    def before_step(self):\n        if self._enable_predicate(self.trainer):\n            self._profiler = torch.autograd.profiler.profile(use_cuda=self._use_cuda)\n            self._profiler.__enter__()\n        else:\n            self._profiler = None\n\n\nclass EvalHook(HookBase):\n    \"\"\"\n    Run an evaluation function periodically, and at the end of training.\n\n    It is executed every ``eval_period`` iterations and after the last iteration.\n    \"\"\"\n\n    def __init__(self, eval_period, eval_function):\n        \"\"\"\n        Args:\n            eval_period (int): the period to run `eval_function`. Set to 0 to\n                not evaluate periodically (but still after the last iteration).\n            eval_function (callable): a function which takes no arguments, and\n                returns a nested dict of evaluation metrics.\n\n        Note:\n            This hook must be enabled in all or none workers.\n            If you would like only certain workers to perform evaluation,\n            give other workers a no-op function (`eval_function=lambda: None`).\n        \"\"\"\n        self._period = eval_period\n        self._func = eval_function\n\n    def _do_eval(self):\n        results = self._func()\n\n        if results:\n            assert isinstance(\n                results, dict\n            ), \"Eval function must return a dict. Got {} instead.\".format(results)\n\n            flattened_results = flatten_results_dict(results)\n            for k, v in flattened_results.items():\n                try:\n                    v = float(v)\n                except Exception as e:\n                    raise ValueError(\n                        \"[EvalHook] eval_function should return a nested dict of float. \"\n                        \"Got '{}: {}' instead.\".format(k, v)\n                    ) from e\n            self.trainer.storage.put_scalars(**flattened_results, smoothing_hint=False)\n\n        # Evaluation may take different time among workers.\n        # A barrier make them start the next iteration together.\n        comm.synchronize()\n\n    def after_step(self):\n        next_iter = self.trainer.iter + 1\n        if self._period > 0 and next_iter % self._period == 0:\n            # do the last eval in after_train\n            if next_iter != self.trainer.max_iter:\n                self._do_eval()\n\n    def after_train(self):\n        # This condition is to prevent the eval from running after a failed training\n        if self.trainer.iter + 1 >= self.trainer.max_iter:\n            self._do_eval()\n        # func is likely a closure that holds reference to the trainer\n        # therefore we clean it to avoid circular reference in the end\n        del self._func\n\n\nclass PreciseBN(HookBase):\n    \"\"\"\n    The standard implementation of BatchNorm uses EMA in inference, which is\n    sometimes suboptimal.\n    This class computes the true average of statistics rather than the moving average,\n    and put true averages to every BN layer in the given model.\n\n    It is executed every ``period`` iterations and after the last iteration.\n    \"\"\"\n\n    def __init__(self, period, model, data_loader, num_iter):\n        \"\"\"\n        Args:\n            period (int): the period this hook is run, or 0 to not run during training.\n                The hook will always run in the end of training.\n            model (nn.Module): a module whose all BN layers in training mode will be\n                updated by precise BN.\n                Note that user is responsible for ensuring the BN layers to be\n                updated are in training mode when this hook is triggered.\n            data_loader (iterable): it will produce data to be run by `model(data)`.\n            num_iter (int): number of iterations used to compute the precise\n                statistics.\n        \"\"\"\n        self._logger = logging.getLogger(__name__)\n        if len(get_bn_modules(model)) == 0:\n            self._logger.info(\n                \"PreciseBN is disabled because model does not contain BN layers in training mode.\"\n            )\n            self._disabled = True\n            return\n\n        self._model = model\n        self._data_loader = data_loader\n        self._num_iter = num_iter\n        self._period = period\n        self._disabled = False\n\n        self._data_iter = None\n\n    def after_step(self):\n        next_iter = self.trainer.iter + 1\n        is_final = next_iter == self.trainer.max_iter\n        if is_final or (self._period > 0 and next_iter % self._period == 0):\n            self.update_stats()\n\n    def update_stats(self):\n        \"\"\"\n        Update the model with precise statistics. Users can manually call this method.\n        \"\"\"\n        if self._disabled:\n            return\n\n        if self._data_iter is None:\n            self._data_iter = iter(self._data_loader)\n\n        def data_loader():\n            for num_iter in itertools.count(1):\n                if num_iter % 100 == 0:\n                    self._logger.info(\n                        \"Running precise-BN ... {}/{} iterations.\".format(num_iter, self._num_iter)\n                    )\n                # This way we can reuse the same iterator\n                yield next(self._data_iter)\n\n        with EventStorage():  # capture events in a new storage to discard them\n            self._logger.info(\n                \"Running precise-BN for {} iterations...  \".format(self._num_iter)\n                + \"Note that this could produce different statistics every time.\"\n            )\n            update_bn_stats(self._model, data_loader(), self._num_iter)\n\n\nclass TorchMemoryStats(HookBase):\n    \"\"\"\n    Writes pytorch's cuda memory statistics periodically.\n    \"\"\"\n\n    def __init__(self, period=20, max_runs=10):\n        \"\"\"\n        Args:\n            period (int): Output stats each 'period' iterations\n            max_runs (int): Stop the logging after 'max_runs'\n        \"\"\"\n\n        self._logger = logging.getLogger(__name__)\n        self._period = period\n        self._max_runs = max_runs\n        self._runs = 0\n\n    def after_step(self):\n        if self._runs > self._max_runs:\n            return\n\n        if (self.trainer.iter + 1) % self._period == 0 or (\n            self.trainer.iter == self.trainer.max_iter - 1\n        ):\n            if torch.cuda.is_available():\n                max_reserved_mb = torch.cuda.max_memory_reserved() / 1024.0 / 1024.0\n                reserved_mb = torch.cuda.memory_reserved() / 1024.0 / 1024.0\n                max_allocated_mb = torch.cuda.max_memory_allocated() / 1024.0 / 1024.0\n                allocated_mb = torch.cuda.memory_allocated() / 1024.0 / 1024.0\n\n                self._logger.info(\n                    (\n                        \" iter: {} \"\n                        \" max_reserved_mem: {:.0f}MB \"\n                        \" reserved_mem: {:.0f}MB \"\n                        \" max_allocated_mem: {:.0f}MB \"\n                        \" allocated_mem: {:.0f}MB \"\n                    ).format(\n                        self.trainer.iter,\n                        max_reserved_mb,\n                        reserved_mb,\n                        max_allocated_mb,\n                        allocated_mb,\n                    )\n                )\n\n                self._runs += 1\n                if self._runs == self._max_runs:\n                    mem_summary = torch.cuda.memory_summary()\n                    self._logger.info(\"\\n\" + mem_summary)\n\n                torch.cuda.reset_peak_memory_stats()\n"
  },
  {
    "path": "VPS_Module/detectron2/engine/launch.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport logging\nfrom datetime import timedelta\nimport torch\nimport torch.distributed as dist\nimport torch.multiprocessing as mp\n\nfrom detectron2.utils import comm\n\n__all__ = [\"DEFAULT_TIMEOUT\", \"launch\"]\n\nDEFAULT_TIMEOUT = timedelta(minutes=30)\n\n\ndef _find_free_port():\n    import socket\n\n    sock = socket.socket(socket.AF_INET, socket.SOCK_STREAM)\n    # Binding to port 0 will cause the OS to find an available port for us\n    sock.bind((\"\", 0))\n    port = sock.getsockname()[1]\n    sock.close()\n    # NOTE: there is still a chance the port could be taken by other processes.\n    return port\n\n\ndef launch(\n    main_func,\n    num_gpus_per_machine,\n    num_machines=1,\n    machine_rank=0,\n    dist_url=None,\n    args=(),\n    timeout=DEFAULT_TIMEOUT,\n):\n    \"\"\"\n    Launch multi-gpu or distributed training.\n    This function must be called on all machines involved in the training.\n    It will spawn child processes (defined by ``num_gpus_per_machine``) on each machine.\n\n    Args:\n        main_func: a function that will be called by `main_func(*args)`\n        num_gpus_per_machine (int): number of GPUs per machine\n        num_machines (int): the total number of machines\n        machine_rank (int): the rank of this machine\n        dist_url (str): url to connect to for distributed jobs, including protocol\n                       e.g. \"tcp://127.0.0.1:8686\".\n                       Can be set to \"auto\" to automatically select a free port on localhost\n        timeout (timedelta): timeout of the distributed workers\n        args (tuple): arguments passed to main_func\n    \"\"\"\n    world_size = num_machines * num_gpus_per_machine\n    if world_size > 1:\n        # https://github.com/pytorch/pytorch/pull/14391\n        # TODO prctl in spawned processes\n\n        if dist_url == \"auto\":\n            assert num_machines == 1, \"dist_url=auto not supported in multi-machine jobs.\"\n            port = _find_free_port()\n            dist_url = f\"tcp://127.0.0.1:{port}\"\n        if num_machines > 1 and dist_url.startswith(\"file://\"):\n            logger = logging.getLogger(__name__)\n            logger.warning(\n                \"file:// is not a reliable init_method in multi-machine jobs. Prefer tcp://\"\n            )\n\n        mp.spawn(\n            _distributed_worker,\n            nprocs=num_gpus_per_machine,\n            args=(\n                main_func,\n                world_size,\n                num_gpus_per_machine,\n                machine_rank,\n                dist_url,\n                args,\n                timeout,\n            ),\n            daemon=False,\n        )\n    else:\n        main_func(*args)\n\n\ndef _distributed_worker(\n    local_rank,\n    main_func,\n    world_size,\n    num_gpus_per_machine,\n    machine_rank,\n    dist_url,\n    args,\n    timeout=DEFAULT_TIMEOUT,\n):\n    assert torch.cuda.is_available(), \"cuda is not available. Please check your installation.\"\n    global_rank = machine_rank * num_gpus_per_machine + local_rank\n    try:\n        dist.init_process_group(\n            backend=\"NCCL\",\n            init_method=dist_url,\n            world_size=world_size,\n            rank=global_rank,\n            timeout=timeout,\n        )\n    except Exception as e:\n        logger = logging.getLogger(__name__)\n        logger.error(\"Process group URL: {}\".format(dist_url))\n        raise e\n\n    # Setup the local process group (which contains ranks within the same machine)\n    assert comm._LOCAL_PROCESS_GROUP is None\n    num_machines = world_size // num_gpus_per_machine\n    for i in range(num_machines):\n        ranks_on_i = list(range(i * num_gpus_per_machine, (i + 1) * num_gpus_per_machine))\n        pg = dist.new_group(ranks_on_i)\n        if i == machine_rank:\n            comm._LOCAL_PROCESS_GROUP = pg\n\n    assert num_gpus_per_machine <= torch.cuda.device_count()\n    torch.cuda.set_device(local_rank)\n\n    # synchronize is needed here to prevent a possible timeout after calling init_process_group\n    # See: https://github.com/facebookresearch/maskrcnn-benchmark/issues/172\n    comm.synchronize()\n\n    main_func(*args)\n"
  },
  {
    "path": "VPS_Module/detectron2/engine/train_loop.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport logging\nimport numpy as np\nimport time\nimport weakref\nfrom typing import List, Mapping, Optional\nimport torch\nfrom torch.nn.parallel import DataParallel, DistributedDataParallel\n\nimport detectron2.utils.comm as comm\nfrom detectron2.utils.events import EventStorage, get_event_storage\nfrom detectron2.utils.logger import _log_api_usage\n\n__all__ = [\"HookBase\", \"TrainerBase\", \"SimpleTrainer\", \"AMPTrainer\"]\n\n\nclass HookBase:\n    \"\"\"\n    Base class for hooks that can be registered with :class:`TrainerBase`.\n\n    Each hook can implement 4 methods. The way they are called is demonstrated\n    in the following snippet:\n    ::\n        hook.before_train()\n        for iter in range(start_iter, max_iter):\n            hook.before_step()\n            trainer.run_step()\n            hook.after_step()\n        iter += 1\n        hook.after_train()\n\n    Notes:\n        1. In the hook method, users can access ``self.trainer`` to access more\n           properties about the context (e.g., model, current iteration, or config\n           if using :class:`DefaultTrainer`).\n\n        2. A hook that does something in :meth:`before_step` can often be\n           implemented equivalently in :meth:`after_step`.\n           If the hook takes non-trivial time, it is strongly recommended to\n           implement the hook in :meth:`after_step` instead of :meth:`before_step`.\n           The convention is that :meth:`before_step` should only take negligible time.\n\n           Following this convention will allow hooks that do care about the difference\n           between :meth:`before_step` and :meth:`after_step` (e.g., timer) to\n           function properly.\n\n    \"\"\"\n\n    trainer: \"TrainerBase\" = None\n    \"\"\"\n    A weak reference to the trainer object. Set by the trainer when the hook is registered.\n    \"\"\"\n\n    def before_train(self):\n        \"\"\"\n        Called before the first iteration.\n        \"\"\"\n        pass\n\n    def after_train(self):\n        \"\"\"\n        Called after the last iteration.\n        \"\"\"\n        pass\n\n    def before_step(self):\n        \"\"\"\n        Called before each iteration.\n        \"\"\"\n        pass\n\n    def after_step(self):\n        \"\"\"\n        Called after each iteration.\n        \"\"\"\n        pass\n\n    def state_dict(self):\n        \"\"\"\n        Hooks are stateless by default, but can be made checkpointable by\n        implementing `state_dict` and `load_state_dict`.\n        \"\"\"\n        return {}\n\n\nclass TrainerBase:\n    \"\"\"\n    Base class for iterative trainer with hooks.\n\n    The only assumption we made here is: the training runs in a loop.\n    A subclass can implement what the loop is.\n    We made no assumptions about the existence of dataloader, optimizer, model, etc.\n\n    Attributes:\n        iter(int): the current iteration.\n\n        start_iter(int): The iteration to start with.\n            By convention the minimum possible value is 0.\n\n        max_iter(int): The iteration to end training.\n\n        storage(EventStorage): An EventStorage that's opened during the course of training.\n    \"\"\"\n\n    def __init__(self) -> None:\n        self._hooks: List[HookBase] = []\n        self.iter: int = 0\n        self.start_iter: int = 0\n        self.max_iter: int\n        self.storage: EventStorage\n        _log_api_usage(\"trainer.\" + self.__class__.__name__)\n\n    def register_hooks(self, hooks: List[Optional[HookBase]]) -> None:\n        \"\"\"\n        Register hooks to the trainer. The hooks are executed in the order\n        they are registered.\n\n        Args:\n            hooks (list[Optional[HookBase]]): list of hooks\n        \"\"\"\n        hooks = [h for h in hooks if h is not None]\n        for h in hooks:\n            assert isinstance(h, HookBase)\n            # To avoid circular reference, hooks and trainer cannot own each other.\n            # This normally does not matter, but will cause memory leak if the\n            # involved objects contain __del__:\n            # See http://engineering.hearsaysocial.com/2013/06/16/circular-references-in-python/\n            h.trainer = weakref.proxy(self)\n        self._hooks.extend(hooks)\n\n    def train(self, start_iter: int, max_iter: int):\n        \"\"\"\n        Args:\n            start_iter, max_iter (int): See docs above\n        \"\"\"\n        logger = logging.getLogger(__name__)\n        logger.info(\"Starting training from iteration {}\".format(start_iter))\n\n        self.iter = self.start_iter = start_iter\n        self.max_iter = max_iter\n\n        with EventStorage(start_iter) as self.storage:\n            try:\n                self.before_train()\n                for self.iter in range(start_iter, max_iter):\n                    self.before_step()\n                    self.run_step()\n                    self.after_step()\n                # self.iter == max_iter can be used by `after_train` to\n                # tell whether the training successfully finished or failed\n                # due to exceptions.\n                self.iter += 1\n            except Exception:\n                logger.exception(\"Exception during training:\")\n                raise\n            finally:\n                self.after_train()\n\n    def before_train(self):\n        for h in self._hooks:\n            h.before_train()\n\n    def after_train(self):\n        self.storage.iter = self.iter\n        for h in self._hooks:\n            h.after_train()\n\n    def before_step(self):\n        # Maintain the invariant that storage.iter == trainer.iter\n        # for the entire execution of each step\n        self.storage.iter = self.iter\n\n        for h in self._hooks:\n            h.before_step()\n\n    def after_step(self):\n        for h in self._hooks:\n            h.after_step()\n\n    def run_step(self):\n        raise NotImplementedError\n\n    def state_dict(self):\n        ret = {\"iteration\": self.iter}\n        hooks_state = {}\n        for h in self._hooks:\n            sd = h.state_dict()\n            if sd:\n                name = type(h).__qualname__\n                if name in hooks_state:\n                    # TODO handle repetitive stateful hooks\n                    continue\n                hooks_state[name] = sd\n        if hooks_state:\n            ret[\"hooks\"] = hooks_state\n        return ret\n\n    def load_state_dict(self, state_dict):\n        logger = logging.getLogger(__name__)\n        self.iter = state_dict[\"iteration\"]\n        for key, value in state_dict.get(\"hooks\", {}).items():\n            for h in self._hooks:\n                try:\n                    name = type(h).__qualname__\n                except AttributeError:\n                    continue\n                if name == key:\n                    h.load_state_dict(value)\n                    break\n            else:\n                logger.warning(f\"Cannot find the hook '{key}', its state_dict is ignored.\")\n\n\nclass SimpleTrainer(TrainerBase):\n    \"\"\"\n    A simple trainer for the most common type of task:\n    single-cost single-optimizer single-data-source iterative optimization,\n    optionally using data-parallelism.\n    It assumes that every step, you:\n\n    1. Compute the loss with a data from the data_loader.\n    2. Compute the gradients with the above loss.\n    3. Update the model with the optimizer.\n\n    All other tasks during training (checkpointing, logging, evaluation, LR schedule)\n    are maintained by hooks, which can be registered by :meth:`TrainerBase.register_hooks`.\n\n    If you want to do anything fancier than this,\n    either subclass TrainerBase and implement your own `run_step`,\n    or write your own training loop.\n    \"\"\"\n\n    def __init__(self, model, data_loader, optimizer):\n        \"\"\"\n        Args:\n            model: a torch Module. Takes a data from data_loader and returns a\n                dict of losses.\n            data_loader: an iterable. Contains data to be used to call model.\n            optimizer: a torch optimizer.\n        \"\"\"\n        super().__init__()\n\n        \"\"\"\n        We set the model to training mode in the trainer.\n        However it's valid to train a model that's in eval mode.\n        If you want your model (or a submodule of it) to behave\n        like evaluation during training, you can overwrite its train() method.\n        \"\"\"\n        model.train()\n\n        self.model = model\n        self.data_loader = data_loader\n        self._data_loader_iter = iter(data_loader)\n        self.optimizer = optimizer\n\n    def run_step(self):\n        \"\"\"\n        Implement the standard training logic described above.\n        \"\"\"\n        assert self.model.training, \"[SimpleTrainer] model was changed to eval mode!\"\n        start = time.perf_counter()\n        \"\"\"\n        If you want to do something with the data, you can wrap the dataloader.\n        \"\"\"\n        data = next(self._data_loader_iter)\n        data_time = time.perf_counter() - start\n\n        \"\"\"\n        If you want to do something with the losses, you can wrap the model.\n        \"\"\"\n        loss_dict = self.model(data)\n        if isinstance(loss_dict, torch.Tensor):\n            losses = loss_dict\n            loss_dict = {\"total_loss\": loss_dict}\n        else:\n            losses = sum(loss_dict.values())\n\n        \"\"\"\n        If you need to accumulate gradients or do something similar, you can\n        wrap the optimizer with your custom `zero_grad()` method.\n        \"\"\"\n        self.optimizer.zero_grad()\n        losses.backward()\n\n        self._write_metrics(loss_dict, data_time)\n\n        \"\"\"\n        If you need gradient clipping/scaling or other processing, you can\n        wrap the optimizer with your custom `step()` method. But it is\n        suboptimal as explained in https://arxiv.org/abs/2006.15704 Sec 3.2.4\n        \"\"\"\n        self.optimizer.step()\n\n    def _write_metrics(\n        self,\n        loss_dict: Mapping[str, torch.Tensor],\n        data_time: float,\n        prefix: str = \"\",\n    ) -> None:\n        SimpleTrainer.write_metrics(loss_dict, data_time, prefix)\n\n    @staticmethod\n    def write_metrics(\n        loss_dict: Mapping[str, torch.Tensor],\n        data_time: float,\n        prefix: str = \"\",\n    ) -> None:\n        \"\"\"\n        Args:\n            loss_dict (dict): dict of scalar losses\n            data_time (float): time taken by the dataloader iteration\n            prefix (str): prefix for logging keys\n        \"\"\"\n        metrics_dict = {k: v.detach().cpu().item() for k, v in loss_dict.items()}\n        metrics_dict[\"data_time\"] = data_time\n\n        # Gather metrics among all workers for logging\n        # This assumes we do DDP-style training, which is currently the only\n        # supported method in detectron2.\n        all_metrics_dict = comm.gather(metrics_dict)\n\n        if comm.is_main_process():\n            storage = get_event_storage()\n\n            # data_time among workers can have high variance. The actual latency\n            # caused by data_time is the maximum among workers.\n            data_time = np.max([x.pop(\"data_time\") for x in all_metrics_dict])\n            storage.put_scalar(\"data_time\", data_time)\n\n            # average the rest metrics\n            metrics_dict = {\n                k: np.mean([x[k] for x in all_metrics_dict]) for k in all_metrics_dict[0].keys()\n            }\n            total_losses_reduced = sum(metrics_dict.values())\n            if not np.isfinite(total_losses_reduced):\n                raise FloatingPointError(\n                    f\"Loss became infinite or NaN at iteration={storage.iter}!\\n\"\n                    f\"loss_dict = {metrics_dict}\"\n                )\n\n            storage.put_scalar(\"{}total_loss\".format(prefix), total_losses_reduced)\n            if len(metrics_dict) > 1:\n                storage.put_scalars(**metrics_dict)\n\n    def state_dict(self):\n        ret = super().state_dict()\n        ret[\"optimizer\"] = self.optimizer.state_dict()\n        return ret\n\n    def load_state_dict(self, state_dict):\n        super().load_state_dict(state_dict)\n        self.optimizer.load_state_dict(state_dict[\"optimizer\"])\n\n\nclass AMPTrainer(SimpleTrainer):\n    \"\"\"\n    Like :class:`SimpleTrainer`, but uses PyTorch's native automatic mixed precision\n    in the training loop.\n    \"\"\"\n\n    def __init__(self, model, data_loader, optimizer, grad_scaler=None):\n        \"\"\"\n        Args:\n            model, data_loader, optimizer: same as in :class:`SimpleTrainer`.\n            grad_scaler: torch GradScaler to automatically scale gradients.\n        \"\"\"\n        unsupported = \"AMPTrainer does not support single-process multi-device training!\"\n        if isinstance(model, DistributedDataParallel):\n            assert not (model.device_ids and len(model.device_ids) > 1), unsupported\n        assert not isinstance(model, DataParallel), unsupported\n\n        super().__init__(model, data_loader, optimizer)\n\n        if grad_scaler is None:\n            from torch.cuda.amp import GradScaler\n\n            grad_scaler = GradScaler()\n        self.grad_scaler = grad_scaler\n\n    def run_step(self):\n        \"\"\"\n        Implement the AMP training logic.\n        \"\"\"\n        assert self.model.training, \"[AMPTrainer] model was changed to eval mode!\"\n        assert torch.cuda.is_available(), \"[AMPTrainer] CUDA is required for AMP training!\"\n        from torch.cuda.amp import autocast\n\n        start = time.perf_counter()\n        data = next(self._data_loader_iter)\n        data_time = time.perf_counter() - start\n\n        with autocast():\n            loss_dict = self.model(data)\n            if isinstance(loss_dict, torch.Tensor):\n                losses = loss_dict\n                loss_dict = {\"total_loss\": loss_dict}\n            else:\n                losses = sum(loss_dict.values())\n\n        self.optimizer.zero_grad()\n        self.grad_scaler.scale(losses).backward()\n\n        self._write_metrics(loss_dict, data_time)\n\n        self.grad_scaler.step(self.optimizer)\n        self.grad_scaler.update()\n\n    def state_dict(self):\n        ret = super().state_dict()\n        ret[\"grad_scaler\"] = self.grad_scaler.state_dict()\n        return ret\n\n    def load_state_dict(self, state_dict):\n        super().load_state_dict(state_dict)\n        self.grad_scaler.load_state_dict(state_dict[\"grad_scaler\"])\n"
  },
  {
    "path": "VPS_Module/detectron2/evaluation/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom .cityscapes_evaluation import CityscapesInstanceEvaluator, CityscapesSemSegEvaluator\nfrom .coco_evaluation import COCOEvaluator\nfrom .rotated_coco_evaluation import RotatedCOCOEvaluator\nfrom .evaluator import DatasetEvaluator, DatasetEvaluators, inference_context, inference_on_dataset\nfrom .lvis_evaluation import LVISEvaluator\nfrom .panoptic_evaluation import COCOPanopticEvaluator\nfrom .pascal_voc_evaluation import PascalVOCDetectionEvaluator\nfrom .sem_seg_evaluation import SemSegEvaluator\nfrom .testing import print_csv_format, verify_results\n\n__all__ = [k for k in globals().keys() if not k.startswith(\"_\")]\n"
  },
  {
    "path": "VPS_Module/detectron2/evaluation/cityscapes_evaluation.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport glob\nimport logging\nimport numpy as np\nimport os\nimport tempfile\nfrom collections import OrderedDict\nimport torch\nfrom PIL import Image\n\nfrom detectron2.data import MetadataCatalog\nfrom detectron2.utils import comm\nfrom detectron2.utils.file_io import PathManager\n\nfrom .evaluator import DatasetEvaluator\n\n\nclass CityscapesEvaluator(DatasetEvaluator):\n    \"\"\"\n    Base class for evaluation using cityscapes API.\n    \"\"\"\n\n    def __init__(self, dataset_name):\n        \"\"\"\n        Args:\n            dataset_name (str): the name of the dataset.\n                It must have the following metadata associated with it:\n                \"thing_classes\", \"gt_dir\".\n        \"\"\"\n        self._metadata = MetadataCatalog.get(dataset_name)\n        self._cpu_device = torch.device(\"cpu\")\n        self._logger = logging.getLogger(__name__)\n\n    def reset(self):\n        self._working_dir = tempfile.TemporaryDirectory(prefix=\"cityscapes_eval_\")\n        self._temp_dir = self._working_dir.name\n        # All workers will write to the same results directory\n        # TODO this does not work in distributed training\n        self._temp_dir = comm.all_gather(self._temp_dir)[0]\n        if self._temp_dir != self._working_dir.name:\n            self._working_dir.cleanup()\n        self._logger.info(\n            \"Writing cityscapes results to temporary directory {} ...\".format(self._temp_dir)\n        )\n\n\nclass CityscapesInstanceEvaluator(CityscapesEvaluator):\n    \"\"\"\n    Evaluate instance segmentation results on cityscapes dataset using cityscapes API.\n\n    Note:\n        * It does not work in multi-machine distributed training.\n        * It contains a synchronization, therefore has to be used on all ranks.\n        * Only the main process runs evaluation.\n    \"\"\"\n\n    def process(self, inputs, outputs):\n        from cityscapesscripts.helpers.labels import name2label\n\n        for input, output in zip(inputs, outputs):\n            file_name = input[\"file_name\"]\n            basename = os.path.splitext(os.path.basename(file_name))[0]\n            pred_txt = os.path.join(self._temp_dir, basename + \"_pred.txt\")\n\n            if \"instances\" in output:\n                output = output[\"instances\"].to(self._cpu_device)\n                num_instances = len(output)\n                with open(pred_txt, \"w\") as fout:\n                    for i in range(num_instances):\n                        pred_class = output.pred_classes[i]\n                        classes = self._metadata.thing_classes[pred_class]\n                        class_id = name2label[classes].id\n                        score = output.scores[i]\n                        mask = output.pred_masks[i].numpy().astype(\"uint8\")\n                        png_filename = os.path.join(\n                            self._temp_dir, basename + \"_{}_{}.png\".format(i, classes)\n                        )\n\n                        Image.fromarray(mask * 255).save(png_filename)\n                        fout.write(\n                            \"{} {} {}\\n\".format(os.path.basename(png_filename), class_id, score)\n                        )\n            else:\n                # Cityscapes requires a prediction file for every ground truth image.\n                with open(pred_txt, \"w\") as fout:\n                    pass\n\n    def evaluate(self):\n        \"\"\"\n        Returns:\n            dict: has a key \"segm\", whose value is a dict of \"AP\" and \"AP50\".\n        \"\"\"\n        comm.synchronize()\n        if comm.get_rank() > 0:\n            return\n        import cityscapesscripts.evaluation.evalInstanceLevelSemanticLabeling as cityscapes_eval\n\n        self._logger.info(\"Evaluating results under {} ...\".format(self._temp_dir))\n\n        # set some global states in cityscapes evaluation API, before evaluating\n        cityscapes_eval.args.predictionPath = os.path.abspath(self._temp_dir)\n        cityscapes_eval.args.predictionWalk = None\n        cityscapes_eval.args.JSONOutput = False\n        cityscapes_eval.args.colorized = False\n        cityscapes_eval.args.gtInstancesFile = os.path.join(self._temp_dir, \"gtInstances.json\")\n\n        # These lines are adopted from\n        # https://github.com/mcordts/cityscapesScripts/blob/master/cityscapesscripts/evaluation/evalInstanceLevelSemanticLabeling.py # noqa\n        gt_dir = PathManager.get_local_path(self._metadata.gt_dir)\n        groundTruthImgList = glob.glob(os.path.join(gt_dir, \"*\", \"*_gtFine_instanceIds.png\"))\n        assert len(\n            groundTruthImgList\n        ), \"Cannot find any ground truth images to use for evaluation. Searched for: {}\".format(\n            cityscapes_eval.args.groundTruthSearch\n        )\n        predictionImgList = []\n        for gt in groundTruthImgList:\n            predictionImgList.append(cityscapes_eval.getPrediction(gt, cityscapes_eval.args))\n        results = cityscapes_eval.evaluateImgLists(\n            predictionImgList, groundTruthImgList, cityscapes_eval.args\n        )[\"averages\"]\n\n        ret = OrderedDict()\n        ret[\"segm\"] = {\"AP\": results[\"allAp\"] * 100, \"AP50\": results[\"allAp50%\"] * 100}\n        self._working_dir.cleanup()\n        return ret\n\n\nclass CityscapesSemSegEvaluator(CityscapesEvaluator):\n    \"\"\"\n    Evaluate semantic segmentation results on cityscapes dataset using cityscapes API.\n\n    Note:\n        * It does not work in multi-machine distributed training.\n        * It contains a synchronization, therefore has to be used on all ranks.\n        * Only the main process runs evaluation.\n    \"\"\"\n\n    def process(self, inputs, outputs):\n        from cityscapesscripts.helpers.labels import trainId2label\n\n        for input, output in zip(inputs, outputs):\n            file_name = input[\"file_name\"]\n            basename = os.path.splitext(os.path.basename(file_name))[0]\n            pred_filename = os.path.join(self._temp_dir, basename + \"_pred.png\")\n\n            output = output[\"sem_seg\"].argmax(dim=0).to(self._cpu_device).numpy()\n            pred = 255 * np.ones(output.shape, dtype=np.uint8)\n            for train_id, label in trainId2label.items():\n                if label.ignoreInEval:\n                    continue\n                pred[output == train_id] = label.id\n            Image.fromarray(pred).save(pred_filename)\n\n    def evaluate(self):\n        comm.synchronize()\n        if comm.get_rank() > 0:\n            return\n        # Load the Cityscapes eval script *after* setting the required env var,\n        # since the script reads CITYSCAPES_DATASET into global variables at load time.\n        import cityscapesscripts.evaluation.evalPixelLevelSemanticLabeling as cityscapes_eval\n\n        self._logger.info(\"Evaluating results under {} ...\".format(self._temp_dir))\n\n        # set some global states in cityscapes evaluation API, before evaluating\n        cityscapes_eval.args.predictionPath = os.path.abspath(self._temp_dir)\n        cityscapes_eval.args.predictionWalk = None\n        cityscapes_eval.args.JSONOutput = False\n        cityscapes_eval.args.colorized = False\n\n        # These lines are adopted from\n        # https://github.com/mcordts/cityscapesScripts/blob/master/cityscapesscripts/evaluation/evalPixelLevelSemanticLabeling.py # noqa\n        gt_dir = PathManager.get_local_path(self._metadata.gt_dir)\n        groundTruthImgList = glob.glob(os.path.join(gt_dir, \"*\", \"*_gtFine_labelIds.png\"))\n        assert len(\n            groundTruthImgList\n        ), \"Cannot find any ground truth images to use for evaluation. Searched for: {}\".format(\n            cityscapes_eval.args.groundTruthSearch\n        )\n        predictionImgList = []\n        for gt in groundTruthImgList:\n            predictionImgList.append(cityscapes_eval.getPrediction(cityscapes_eval.args, gt))\n        results = cityscapes_eval.evaluateImgLists(\n            predictionImgList, groundTruthImgList, cityscapes_eval.args\n        )\n        ret = OrderedDict()\n        ret[\"sem_seg\"] = {\n            \"IoU\": 100.0 * results[\"averageScoreClasses\"],\n            \"iIoU\": 100.0 * results[\"averageScoreInstClasses\"],\n            \"IoU_sup\": 100.0 * results[\"averageScoreCategories\"],\n            \"iIoU_sup\": 100.0 * results[\"averageScoreInstCategories\"],\n        }\n        self._working_dir.cleanup()\n        return ret\n"
  },
  {
    "path": "VPS_Module/detectron2/evaluation/coco_evaluation.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport contextlib\nimport copy\nimport io\nimport itertools\nimport json\nimport logging\nimport numpy as np\nimport os\nimport pickle\nfrom collections import OrderedDict\nimport pycocotools.mask as mask_util\nimport torch\nfrom pycocotools.coco import COCO\nfrom pycocotools.cocoeval import COCOeval\nfrom tabulate import tabulate\n\nimport detectron2.utils.comm as comm\nfrom detectron2.config import CfgNode\nfrom detectron2.data import MetadataCatalog\nfrom detectron2.data.datasets.coco import convert_to_coco_json\nfrom detectron2.evaluation.fast_eval_api import COCOeval_opt\nfrom detectron2.structures import Boxes, BoxMode, pairwise_iou\nfrom detectron2.utils.file_io import PathManager\nfrom detectron2.utils.logger import create_small_table\n\nfrom .evaluator import DatasetEvaluator\n\n\nclass COCOEvaluator(DatasetEvaluator):\n    \"\"\"\n    Evaluate AR for object proposals, AP for instance detection/segmentation, AP\n    for keypoint detection outputs using COCO's metrics.\n    See http://cocodataset.org/#detection-eval and\n    http://cocodataset.org/#keypoints-eval to understand its metrics.\n    The metrics range from 0 to 100 (instead of 0 to 1), where a -1 or NaN means\n    the metric cannot be computed (e.g. due to no predictions made).\n\n    In addition to COCO, this evaluator is able to support any bounding box detection,\n    instance segmentation, or keypoint detection dataset.\n    \"\"\"\n\n    def __init__(\n        self,\n        dataset_name,\n        tasks=None,\n        distributed=True,\n        output_dir=None,\n        *,\n        max_dets_per_image=None,\n        use_fast_impl=True,\n        kpt_oks_sigmas=(),\n    ):\n        \"\"\"\n        Args:\n            dataset_name (str): name of the dataset to be evaluated.\n                It must have either the following corresponding metadata:\n\n                    \"json_file\": the path to the COCO format annotation\n\n                Or it must be in detectron2's standard dataset format\n                so it can be converted to COCO format automatically.\n            tasks (tuple[str]): tasks that can be evaluated under the given\n                configuration. A task is one of \"bbox\", \"segm\", \"keypoints\".\n                By default, will infer this automatically from predictions.\n            distributed (True): if True, will collect results from all ranks and run evaluation\n                in the main process.\n                Otherwise, will only evaluate the results in the current process.\n            output_dir (str): optional, an output directory to dump all\n                results predicted on the dataset. The dump contains two files:\n\n                1. \"instances_predictions.pth\" a file that can be loaded with `torch.load` and\n                   contains all the results in the format they are produced by the model.\n                2. \"coco_instances_results.json\" a json file in COCO's result format.\n            max_dets_per_image (int): limit on the maximum number of detections per image.\n                By default in COCO, this limit is to 100, but this can be customized\n                to be greater, as is needed in evaluation metrics AP fixed and AP pool\n                (see https://arxiv.org/pdf/2102.01066.pdf)\n                This doesn't affect keypoint evaluation.\n            use_fast_impl (bool): use a fast but **unofficial** implementation to compute AP.\n                Although the results should be very close to the official implementation in COCO\n                API, it is still recommended to compute results with the official API for use in\n                papers. The faster implementation also uses more RAM.\n            kpt_oks_sigmas (list[float]): The sigmas used to calculate keypoint OKS.\n                See http://cocodataset.org/#keypoints-eval\n                When empty, it will use the defaults in COCO.\n                Otherwise it should be the same length as ROI_KEYPOINT_HEAD.NUM_KEYPOINTS.\n        \"\"\"\n        self._logger = logging.getLogger(__name__)\n        self._distributed = distributed\n        self._output_dir = output_dir\n        self._use_fast_impl = use_fast_impl\n\n        # COCOeval requires the limit on the number of detections per image (maxDets) to be a list\n        # with at least 3 elements. The default maxDets in COCOeval is [1, 10, 100], in which the\n        # 3rd element (100) is used as the limit on the number of detections per image when\n        # evaluating AP. COCOEvaluator expects an integer for max_dets_per_image, so for COCOeval,\n        # we reformat max_dets_per_image into [1, 10, max_dets_per_image], based on the defaults.\n        if max_dets_per_image is None:\n            max_dets_per_image = [1, 10, 100]\n        else:\n            max_dets_per_image = [1, 10, max_dets_per_image]\n        self._max_dets_per_image = max_dets_per_image\n\n        if tasks is not None and isinstance(tasks, CfgNode):\n            kpt_oks_sigmas = (\n                tasks.TEST.KEYPOINT_OKS_SIGMAS if not kpt_oks_sigmas else kpt_oks_sigmas\n            )\n            self._logger.warn(\n                \"COCO Evaluator instantiated using config, this is deprecated behavior.\"\n                \" Please pass in explicit arguments instead.\"\n            )\n            self._tasks = None  # Infering it from predictions should be better\n        else:\n            self._tasks = tasks\n\n        self._cpu_device = torch.device(\"cpu\")\n\n        self._metadata = MetadataCatalog.get(dataset_name)\n        if not hasattr(self._metadata, \"json_file\"):\n            if output_dir is None:\n                raise ValueError(\n                    \"output_dir must be provided to COCOEvaluator \"\n                    \"for datasets not in COCO format.\"\n                )\n            self._logger.info(f\"Trying to convert '{dataset_name}' to COCO format ...\")\n\n            cache_path = os.path.join(output_dir, f\"{dataset_name}_coco_format.json\")\n            self._metadata.json_file = cache_path\n            convert_to_coco_json(dataset_name, cache_path)\n\n        json_file = PathManager.get_local_path(self._metadata.json_file)\n        with contextlib.redirect_stdout(io.StringIO()):\n            self._coco_api = COCO(json_file)\n\n        # Test set json files do not contain annotations (evaluation must be\n        # performed using the COCO evaluation server).\n        self._do_evaluation = \"annotations\" in self._coco_api.dataset\n        if self._do_evaluation:\n            self._kpt_oks_sigmas = kpt_oks_sigmas\n\n    def reset(self):\n        self._predictions = []\n\n    def process(self, inputs, outputs):\n        \"\"\"\n        Args:\n            inputs: the inputs to a COCO model (e.g., GeneralizedRCNN).\n                It is a list of dict. Each dict corresponds to an image and\n                contains keys like \"height\", \"width\", \"file_name\", \"image_id\".\n            outputs: the outputs of a COCO model. It is a list of dicts with key\n                \"instances\" that contains :class:`Instances`.\n        \"\"\"\n        for input, output in zip(inputs, outputs):\n            prediction = {\"image_id\": input[\"image_id\"]}\n\n            if \"instances\" in output:\n                instances = output[\"instances\"].to(self._cpu_device)\n                prediction[\"instances\"] = instances_to_coco_json(instances, input[\"image_id\"])\n            if \"proposals\" in output:\n                prediction[\"proposals\"] = output[\"proposals\"].to(self._cpu_device)\n            if len(prediction) > 1:\n                self._predictions.append(prediction)\n\n    def evaluate(self, img_ids=None):\n        \"\"\"\n        Args:\n            img_ids: a list of image IDs to evaluate on. Default to None for the whole dataset\n        \"\"\"\n        if self._distributed:\n            comm.synchronize()\n            predictions = comm.gather(self._predictions, dst=0)\n            predictions = list(itertools.chain(*predictions))\n\n            if not comm.is_main_process():\n                return {}\n        else:\n            predictions = self._predictions\n\n        if len(predictions) == 0:\n            self._logger.warning(\"[COCOEvaluator] Did not receive valid predictions.\")\n            return {}\n\n        if self._output_dir:\n            PathManager.mkdirs(self._output_dir)\n            file_path = os.path.join(self._output_dir, \"instances_predictions.pth\")\n            with PathManager.open(file_path, \"wb\") as f:\n                torch.save(predictions, f)\n\n        self._results = OrderedDict()\n        if \"proposals\" in predictions[0]:\n            self._eval_box_proposals(predictions)\n        if \"instances\" in predictions[0]:\n            self._eval_predictions(predictions, img_ids=img_ids)\n        # Copy so the caller can do whatever with results\n        return copy.deepcopy(self._results)\n\n    def _tasks_from_predictions(self, predictions):\n        \"\"\"\n        Get COCO API \"tasks\" (i.e. iou_type) from COCO-format predictions.\n        \"\"\"\n        tasks = {\"bbox\"}\n        for pred in predictions:\n            if \"segmentation\" in pred:\n                tasks.add(\"segm\")\n            if \"keypoints\" in pred:\n                tasks.add(\"keypoints\")\n        return sorted(tasks)\n\n    def _eval_predictions(self, predictions, img_ids=None):\n        \"\"\"\n        Evaluate predictions. Fill self._results with the metrics of the tasks.\n        \"\"\"\n        self._logger.info(\"Preparing results for COCO format ...\")\n        coco_results = list(itertools.chain(*[x[\"instances\"] for x in predictions]))\n        tasks = self._tasks or self._tasks_from_predictions(coco_results)\n\n        # unmap the category ids for COCO\n        if hasattr(self._metadata, \"thing_dataset_id_to_contiguous_id\"):\n            dataset_id_to_contiguous_id = self._metadata.thing_dataset_id_to_contiguous_id\n            all_contiguous_ids = list(dataset_id_to_contiguous_id.values())\n            num_classes = len(all_contiguous_ids)\n            assert min(all_contiguous_ids) == 0 and max(all_contiguous_ids) == num_classes - 1\n\n            reverse_id_mapping = {v: k for k, v in dataset_id_to_contiguous_id.items()}\n            for result in coco_results:\n                category_id = result[\"category_id\"]\n                assert category_id < num_classes, (\n                    f\"A prediction has class={category_id}, \"\n                    f\"but the dataset only has {num_classes} classes and \"\n                    f\"predicted class id should be in [0, {num_classes - 1}].\"\n                )\n                result[\"category_id\"] = reverse_id_mapping[category_id]\n\n        if self._output_dir:\n            file_path = os.path.join(self._output_dir, \"coco_instances_results.json\")\n            self._logger.info(\"Saving results to {}\".format(file_path))\n            with PathManager.open(file_path, \"w\") as f:\n                f.write(json.dumps(coco_results))\n                f.flush()\n\n        if not self._do_evaluation:\n            self._logger.info(\"Annotations are not available for evaluation.\")\n            return\n\n        self._logger.info(\n            \"Evaluating predictions with {} COCO API...\".format(\n                \"unofficial\" if self._use_fast_impl else \"official\"\n            )\n        )\n        for task in sorted(tasks):\n            assert task in {\"bbox\", \"segm\", \"keypoints\"}, f\"Got unknown task: {task}!\"\n            coco_eval = (\n                _evaluate_predictions_on_coco(\n                    self._coco_api,\n                    coco_results,\n                    task,\n                    kpt_oks_sigmas=self._kpt_oks_sigmas,\n                    use_fast_impl=self._use_fast_impl,\n                    img_ids=img_ids,\n                    max_dets_per_image=self._max_dets_per_image,\n                )\n                if len(coco_results) > 0\n                else None  # cocoapi does not handle empty results very well\n            )\n\n            res = self._derive_coco_results(\n                coco_eval, task, class_names=self._metadata.get(\"thing_classes\")\n            )\n            self._results[task] = res\n\n    def _eval_box_proposals(self, predictions):\n        \"\"\"\n        Evaluate the box proposals in predictions.\n        Fill self._results with the metrics for \"box_proposals\" task.\n        \"\"\"\n        if self._output_dir:\n            # Saving generated box proposals to file.\n            # Predicted box_proposals are in XYXY_ABS mode.\n            bbox_mode = BoxMode.XYXY_ABS.value\n            ids, boxes, objectness_logits = [], [], []\n            for prediction in predictions:\n                ids.append(prediction[\"image_id\"])\n                boxes.append(prediction[\"proposals\"].proposal_boxes.tensor.numpy())\n                objectness_logits.append(prediction[\"proposals\"].objectness_logits.numpy())\n\n            proposal_data = {\n                \"boxes\": boxes,\n                \"objectness_logits\": objectness_logits,\n                \"ids\": ids,\n                \"bbox_mode\": bbox_mode,\n            }\n            with PathManager.open(os.path.join(self._output_dir, \"box_proposals.pkl\"), \"wb\") as f:\n                pickle.dump(proposal_data, f)\n\n        if not self._do_evaluation:\n            self._logger.info(\"Annotations are not available for evaluation.\")\n            return\n\n        self._logger.info(\"Evaluating bbox proposals ...\")\n        res = {}\n        areas = {\"all\": \"\", \"small\": \"s\", \"medium\": \"m\", \"large\": \"l\"}\n        for limit in [100, 1000]:\n            for area, suffix in areas.items():\n                stats = _evaluate_box_proposals(predictions, self._coco_api, area=area, limit=limit)\n                key = \"AR{}@{:d}\".format(suffix, limit)\n                res[key] = float(stats[\"ar\"].item() * 100)\n        self._logger.info(\"Proposal metrics: \\n\" + create_small_table(res))\n        self._results[\"box_proposals\"] = res\n\n    def _derive_coco_results(self, coco_eval, iou_type, class_names=None):\n        \"\"\"\n        Derive the desired score numbers from summarized COCOeval.\n\n        Args:\n            coco_eval (None or COCOEval): None represents no predictions from model.\n            iou_type (str):\n            class_names (None or list[str]): if provided, will use it to predict\n                per-category AP.\n\n        Returns:\n            a dict of {metric name: score}\n        \"\"\"\n\n        metrics = {\n            \"bbox\": [\"AP\", \"AP50\", \"AP75\", \"APs\", \"APm\", \"APl\"],\n            \"segm\": [\"AP\", \"AP50\", \"AP75\", \"APs\", \"APm\", \"APl\"],\n            \"keypoints\": [\"AP\", \"AP50\", \"AP75\", \"APm\", \"APl\"],\n        }[iou_type]\n\n        if coco_eval is None:\n            self._logger.warn(\"No predictions from the model!\")\n            return {metric: float(\"nan\") for metric in metrics}\n\n        # the standard metrics\n        results = {\n            metric: float(coco_eval.stats[idx] * 100 if coco_eval.stats[idx] >= 0 else \"nan\")\n            for idx, metric in enumerate(metrics)\n        }\n        self._logger.info(\n            \"Evaluation results for {}: \\n\".format(iou_type) + create_small_table(results)\n        )\n        if not np.isfinite(sum(results.values())):\n            self._logger.info(\"Some metrics cannot be computed and is shown as NaN.\")\n\n        if class_names is None or len(class_names) <= 1:\n            return results\n        # Compute per-category AP\n        # from https://github.com/facebookresearch/Detectron/blob/a6a835f5b8208c45d0dce217ce9bbda915f44df7/detectron/datasets/json_dataset_evaluator.py#L222-L252 # noqa\n        precisions = coco_eval.eval[\"precision\"]\n        # precision has dims (iou, recall, cls, area range, max dets)\n        assert len(class_names) == precisions.shape[2]\n\n        results_per_category = []\n        for idx, name in enumerate(class_names):\n            # area range index 0: all area ranges\n            # max dets index -1: typically 100 per image\n            precision = precisions[:, :, idx, 0, -1]\n            precision = precision[precision > -1]\n            ap = np.mean(precision) if precision.size else float(\"nan\")\n            results_per_category.append((\"{}\".format(name), float(ap * 100)))\n\n        # tabulate it\n        N_COLS = min(6, len(results_per_category) * 2)\n        results_flatten = list(itertools.chain(*results_per_category))\n        results_2d = itertools.zip_longest(*[results_flatten[i::N_COLS] for i in range(N_COLS)])\n        table = tabulate(\n            results_2d,\n            tablefmt=\"pipe\",\n            floatfmt=\".3f\",\n            headers=[\"category\", \"AP\"] * (N_COLS // 2),\n            numalign=\"left\",\n        )\n        self._logger.info(\"Per-category {} AP: \\n\".format(iou_type) + table)\n\n        results.update({\"AP-\" + name: ap for name, ap in results_per_category})\n        return results\n\n\ndef instances_to_coco_json(instances, img_id):\n    \"\"\"\n    Dump an \"Instances\" object to a COCO-format json that's used for evaluation.\n\n    Args:\n        instances (Instances):\n        img_id (int): the image id\n\n    Returns:\n        list[dict]: list of json annotations in COCO format.\n    \"\"\"\n    num_instance = len(instances)\n    if num_instance == 0:\n        return []\n\n    boxes = instances.pred_boxes.tensor.numpy()\n    boxes = BoxMode.convert(boxes, BoxMode.XYXY_ABS, BoxMode.XYWH_ABS)\n    boxes = boxes.tolist()\n    scores = instances.scores.tolist()\n    classes = instances.pred_classes.tolist()\n\n    has_mask = instances.has(\"pred_masks\")\n    if has_mask:\n        # use RLE to encode the masks, because they are too large and takes memory\n        # since this evaluator stores outputs of the entire dataset\n        rles = [\n            mask_util.encode(np.array(mask[:, :, None], order=\"F\", dtype=\"uint8\"))[0]\n            for mask in instances.pred_masks\n        ]\n        for rle in rles:\n            # \"counts\" is an array encoded by mask_util as a byte-stream. Python3's\n            # json writer which always produces strings cannot serialize a bytestream\n            # unless you decode it. Thankfully, utf-8 works out (which is also what\n            # the pycocotools/_mask.pyx does).\n            rle[\"counts\"] = rle[\"counts\"].decode(\"utf-8\")\n\n    has_keypoints = instances.has(\"pred_keypoints\")\n    if has_keypoints:\n        keypoints = instances.pred_keypoints\n\n    results = []\n    for k in range(num_instance):\n        result = {\n            \"image_id\": img_id,\n            \"category_id\": classes[k],\n            \"bbox\": boxes[k],\n            \"score\": scores[k],\n        }\n        if has_mask:\n            result[\"segmentation\"] = rles[k]\n        if has_keypoints:\n            # In COCO annotations,\n            # keypoints coordinates are pixel indices.\n            # However our predictions are floating point coordinates.\n            # Therefore we subtract 0.5 to be consistent with the annotation format.\n            # This is the inverse of data loading logic in `datasets/coco.py`.\n            keypoints[k][:, :2] -= 0.5\n            result[\"keypoints\"] = keypoints[k].flatten().tolist()\n        results.append(result)\n    return results\n\n\n# inspired from Detectron:\n# https://github.com/facebookresearch/Detectron/blob/a6a835f5b8208c45d0dce217ce9bbda915f44df7/detectron/datasets/json_dataset_evaluator.py#L255 # noqa\ndef _evaluate_box_proposals(dataset_predictions, coco_api, thresholds=None, area=\"all\", limit=None):\n    \"\"\"\n    Evaluate detection proposal recall metrics. This function is a much\n    faster alternative to the official COCO API recall evaluation code. However,\n    it produces slightly different results.\n    \"\"\"\n    # Record max overlap value for each gt box\n    # Return vector of overlap values\n    areas = {\n        \"all\": 0,\n        \"small\": 1,\n        \"medium\": 2,\n        \"large\": 3,\n        \"96-128\": 4,\n        \"128-256\": 5,\n        \"256-512\": 6,\n        \"512-inf\": 7,\n    }\n    area_ranges = [\n        [0 ** 2, 1e5 ** 2],  # all\n        [0 ** 2, 32 ** 2],  # small\n        [32 ** 2, 96 ** 2],  # medium\n        [96 ** 2, 1e5 ** 2],  # large\n        [96 ** 2, 128 ** 2],  # 96-128\n        [128 ** 2, 256 ** 2],  # 128-256\n        [256 ** 2, 512 ** 2],  # 256-512\n        [512 ** 2, 1e5 ** 2],\n    ]  # 512-inf\n    assert area in areas, \"Unknown area range: {}\".format(area)\n    area_range = area_ranges[areas[area]]\n    gt_overlaps = []\n    num_pos = 0\n\n    for prediction_dict in dataset_predictions:\n        predictions = prediction_dict[\"proposals\"]\n\n        # sort predictions in descending order\n        # TODO maybe remove this and make it explicit in the documentation\n        inds = predictions.objectness_logits.sort(descending=True)[1]\n        predictions = predictions[inds]\n\n        ann_ids = coco_api.getAnnIds(imgIds=prediction_dict[\"image_id\"])\n        anno = coco_api.loadAnns(ann_ids)\n        gt_boxes = [\n            BoxMode.convert(obj[\"bbox\"], BoxMode.XYWH_ABS, BoxMode.XYXY_ABS)\n            for obj in anno\n            if obj[\"iscrowd\"] == 0\n        ]\n        gt_boxes = torch.as_tensor(gt_boxes).reshape(-1, 4)  # guard against no boxes\n        gt_boxes = Boxes(gt_boxes)\n        gt_areas = torch.as_tensor([obj[\"area\"] for obj in anno if obj[\"iscrowd\"] == 0])\n\n        if len(gt_boxes) == 0 or len(predictions) == 0:\n            continue\n\n        valid_gt_inds = (gt_areas >= area_range[0]) & (gt_areas <= area_range[1])\n        gt_boxes = gt_boxes[valid_gt_inds]\n\n        num_pos += len(gt_boxes)\n\n        if len(gt_boxes) == 0:\n            continue\n\n        if limit is not None and len(predictions) > limit:\n            predictions = predictions[:limit]\n\n        overlaps = pairwise_iou(predictions.proposal_boxes, gt_boxes)\n\n        _gt_overlaps = torch.zeros(len(gt_boxes))\n        for j in range(min(len(predictions), len(gt_boxes))):\n            # find which proposal box maximally covers each gt box\n            # and get the iou amount of coverage for each gt box\n            max_overlaps, argmax_overlaps = overlaps.max(dim=0)\n\n            # find which gt box is 'best' covered (i.e. 'best' = most iou)\n            gt_ovr, gt_ind = max_overlaps.max(dim=0)\n            assert gt_ovr >= 0\n            # find the proposal box that covers the best covered gt box\n            box_ind = argmax_overlaps[gt_ind]\n            # record the iou coverage of this gt box\n            _gt_overlaps[j] = overlaps[box_ind, gt_ind]\n            assert _gt_overlaps[j] == gt_ovr\n            # mark the proposal box and the gt box as used\n            overlaps[box_ind, :] = -1\n            overlaps[:, gt_ind] = -1\n\n        # append recorded iou coverage level\n        gt_overlaps.append(_gt_overlaps)\n    gt_overlaps = (\n        torch.cat(gt_overlaps, dim=0) if len(gt_overlaps) else torch.zeros(0, dtype=torch.float32)\n    )\n    gt_overlaps, _ = torch.sort(gt_overlaps)\n\n    if thresholds is None:\n        step = 0.05\n        thresholds = torch.arange(0.5, 0.95 + 1e-5, step, dtype=torch.float32)\n    recalls = torch.zeros_like(thresholds)\n    # compute recall for each iou threshold\n    for i, t in enumerate(thresholds):\n        recalls[i] = (gt_overlaps >= t).float().sum() / float(num_pos)\n    # ar = 2 * np.trapz(recalls, thresholds)\n    ar = recalls.mean()\n    return {\n        \"ar\": ar,\n        \"recalls\": recalls,\n        \"thresholds\": thresholds,\n        \"gt_overlaps\": gt_overlaps,\n        \"num_pos\": num_pos,\n    }\n\n\ndef _evaluate_predictions_on_coco(\n    coco_gt,\n    coco_results,\n    iou_type,\n    kpt_oks_sigmas=None,\n    use_fast_impl=True,\n    img_ids=None,\n    max_dets_per_image=None,\n):\n    \"\"\"\n    Evaluate the coco results using COCOEval API.\n    \"\"\"\n    assert len(coco_results) > 0\n\n    if iou_type == \"segm\":\n        coco_results = copy.deepcopy(coco_results)\n        # When evaluating mask AP, if the results contain bbox, cocoapi will\n        # use the box area as the area of the instance, instead of the mask area.\n        # This leads to a different definition of small/medium/large.\n        # We remove the bbox field to let mask AP use mask area.\n        for c in coco_results:\n            c.pop(\"bbox\", None)\n\n    coco_dt = coco_gt.loadRes(coco_results)\n    coco_eval = (COCOeval_opt if use_fast_impl else COCOeval)(coco_gt, coco_dt, iou_type)\n    # For COCO, the default max_dets_per_image is [1, 10, 100].\n    if max_dets_per_image is None:\n        max_dets_per_image = [1, 10, 100]  # Default from COCOEval\n    else:\n        assert (\n            len(max_dets_per_image) >= 3\n        ), \"COCOeval requires maxDets (and max_dets_per_image) to have length at least 3\"\n        # In the case that user supplies a custom input for max_dets_per_image,\n        # apply COCOevalMaxDets to evaluate AP with the custom input.\n        if max_dets_per_image[2] != 100:\n            coco_eval = COCOevalMaxDets(coco_gt, coco_dt, iou_type)\n    if iou_type != \"keypoints\":\n        coco_eval.params.maxDets = max_dets_per_image\n\n    if img_ids is not None:\n        coco_eval.params.imgIds = img_ids\n\n    if iou_type == \"keypoints\":\n        # Use the COCO default keypoint OKS sigmas unless overrides are specified\n        if kpt_oks_sigmas:\n            assert hasattr(coco_eval.params, \"kpt_oks_sigmas\"), \"pycocotools is too old!\"\n            coco_eval.params.kpt_oks_sigmas = np.array(kpt_oks_sigmas)\n        # COCOAPI requires every detection and every gt to have keypoints, so\n        # we just take the first entry from both\n        num_keypoints_dt = len(coco_results[0][\"keypoints\"]) // 3\n        num_keypoints_gt = len(next(iter(coco_gt.anns.values()))[\"keypoints\"]) // 3\n        num_keypoints_oks = len(coco_eval.params.kpt_oks_sigmas)\n        assert num_keypoints_oks == num_keypoints_dt == num_keypoints_gt, (\n            f\"[COCOEvaluator] Prediction contain {num_keypoints_dt} keypoints. \"\n            f\"Ground truth contains {num_keypoints_gt} keypoints. \"\n            f\"The length of cfg.TEST.KEYPOINT_OKS_SIGMAS is {num_keypoints_oks}. \"\n            \"They have to agree with each other. For meaning of OKS, please refer to \"\n            \"http://cocodataset.org/#keypoints-eval.\"\n        )\n\n    coco_eval.evaluate()\n    coco_eval.accumulate()\n    coco_eval.summarize()\n\n    return coco_eval\n\n\nclass COCOevalMaxDets(COCOeval):\n    \"\"\"\n    Modified version of COCOeval for evaluating AP with a custom\n    maxDets (by default for COCO, maxDets is 100)\n    \"\"\"\n\n    def summarize(self):\n        \"\"\"\n        Compute and display summary metrics for evaluation results given\n        a custom value for  max_dets_per_image\n        \"\"\"\n\n        def _summarize(ap=1, iouThr=None, areaRng=\"all\", maxDets=100):\n            p = self.params\n            iStr = \" {:<18} {} @[ IoU={:<9} | area={:>6s} | maxDets={:>3d} ] = {:0.3f}\"\n            titleStr = \"Average Precision\" if ap == 1 else \"Average Recall\"\n            typeStr = \"(AP)\" if ap == 1 else \"(AR)\"\n            iouStr = (\n                \"{:0.2f}:{:0.2f}\".format(p.iouThrs[0], p.iouThrs[-1])\n                if iouThr is None\n                else \"{:0.2f}\".format(iouThr)\n            )\n\n            aind = [i for i, aRng in enumerate(p.areaRngLbl) if aRng == areaRng]\n            mind = [i for i, mDet in enumerate(p.maxDets) if mDet == maxDets]\n            if ap == 1:\n                # dimension of precision: [TxRxKxAxM]\n                s = self.eval[\"precision\"]\n                # IoU\n                if iouThr is not None:\n                    t = np.where(iouThr == p.iouThrs)[0]\n                    s = s[t]\n                s = s[:, :, :, aind, mind]\n            else:\n                # dimension of recall: [TxKxAxM]\n                s = self.eval[\"recall\"]\n                if iouThr is not None:\n                    t = np.where(iouThr == p.iouThrs)[0]\n                    s = s[t]\n                s = s[:, :, aind, mind]\n            if len(s[s > -1]) == 0:\n                mean_s = -1\n            else:\n                mean_s = np.mean(s[s > -1])\n            print(iStr.format(titleStr, typeStr, iouStr, areaRng, maxDets, mean_s))\n            return mean_s\n\n        def _summarizeDets():\n            stats = np.zeros((12,))\n            # Evaluate AP using the custom limit on maximum detections per image\n            stats[0] = _summarize(1, maxDets=self.params.maxDets[2])\n            stats[1] = _summarize(1, iouThr=0.5, maxDets=self.params.maxDets[2])\n            stats[2] = _summarize(1, iouThr=0.75, maxDets=self.params.maxDets[2])\n            stats[3] = _summarize(1, areaRng=\"small\", maxDets=self.params.maxDets[2])\n            stats[4] = _summarize(1, areaRng=\"medium\", maxDets=self.params.maxDets[2])\n            stats[5] = _summarize(1, areaRng=\"large\", maxDets=self.params.maxDets[2])\n            stats[6] = _summarize(0, maxDets=self.params.maxDets[0])\n            stats[7] = _summarize(0, maxDets=self.params.maxDets[1])\n            stats[8] = _summarize(0, maxDets=self.params.maxDets[2])\n            stats[9] = _summarize(0, areaRng=\"small\", maxDets=self.params.maxDets[2])\n            stats[10] = _summarize(0, areaRng=\"medium\", maxDets=self.params.maxDets[2])\n            stats[11] = _summarize(0, areaRng=\"large\", maxDets=self.params.maxDets[2])\n            return stats\n\n        def _summarizeKps():\n            stats = np.zeros((10,))\n            stats[0] = _summarize(1, maxDets=20)\n            stats[1] = _summarize(1, maxDets=20, iouThr=0.5)\n            stats[2] = _summarize(1, maxDets=20, iouThr=0.75)\n            stats[3] = _summarize(1, maxDets=20, areaRng=\"medium\")\n            stats[4] = _summarize(1, maxDets=20, areaRng=\"large\")\n            stats[5] = _summarize(0, maxDets=20)\n            stats[6] = _summarize(0, maxDets=20, iouThr=0.5)\n            stats[7] = _summarize(0, maxDets=20, iouThr=0.75)\n            stats[8] = _summarize(0, maxDets=20, areaRng=\"medium\")\n            stats[9] = _summarize(0, maxDets=20, areaRng=\"large\")\n            return stats\n\n        if not self.eval:\n            raise Exception(\"Please run accumulate() first\")\n        iouType = self.params.iouType\n        if iouType == \"segm\" or iouType == \"bbox\":\n            summarize = _summarizeDets\n        elif iouType == \"keypoints\":\n            summarize = _summarizeKps\n        self.stats = summarize()\n\n    def __str__(self):\n        self.summarize()\n"
  },
  {
    "path": "VPS_Module/detectron2/evaluation/evaluator.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport datetime\nimport logging\nimport time\nfrom collections import OrderedDict, abc\nfrom contextlib import ExitStack, contextmanager\nfrom typing import List, Union\nimport torch\nfrom torch import nn\n\nfrom detectron2.utils.comm import get_world_size, is_main_process\nfrom detectron2.utils.logger import log_every_n_seconds\n\n\nclass DatasetEvaluator:\n    \"\"\"\n    Base class for a dataset evaluator.\n\n    The function :func:`inference_on_dataset` runs the model over\n    all samples in the dataset, and have a DatasetEvaluator to process the inputs/outputs.\n\n    This class will accumulate information of the inputs/outputs (by :meth:`process`),\n    and produce evaluation results in the end (by :meth:`evaluate`).\n    \"\"\"\n\n    def reset(self):\n        \"\"\"\n        Preparation for a new round of evaluation.\n        Should be called before starting a round of evaluation.\n        \"\"\"\n        pass\n\n    def process(self, inputs, outputs):\n        \"\"\"\n        Process the pair of inputs and outputs.\n        If they contain batches, the pairs can be consumed one-by-one using `zip`:\n\n        .. code-block:: python\n\n            for input_, output in zip(inputs, outputs):\n                # do evaluation on single input/output pair\n                ...\n\n        Args:\n            inputs (list): the inputs that's used to call the model.\n            outputs (list): the return value of `model(inputs)`\n        \"\"\"\n        pass\n\n    def evaluate(self):\n        \"\"\"\n        Evaluate/summarize the performance, after processing all input/output pairs.\n\n        Returns:\n            dict:\n                A new evaluator class can return a dict of arbitrary format\n                as long as the user can process the results.\n                In our train_net.py, we expect the following format:\n\n                * key: the name of the task (e.g., bbox)\n                * value: a dict of {metric name: score}, e.g.: {\"AP50\": 80}\n        \"\"\"\n        pass\n\n\nclass DatasetEvaluators(DatasetEvaluator):\n    \"\"\"\n    Wrapper class to combine multiple :class:`DatasetEvaluator` instances.\n\n    This class dispatches every evaluation call to\n    all of its :class:`DatasetEvaluator`.\n    \"\"\"\n\n    def __init__(self, evaluators):\n        \"\"\"\n        Args:\n            evaluators (list): the evaluators to combine.\n        \"\"\"\n        super().__init__()\n        self._evaluators = evaluators\n\n    def reset(self):\n        for evaluator in self._evaluators:\n            evaluator.reset()\n\n    def process(self, inputs, outputs):\n        for evaluator in self._evaluators:\n            evaluator.process(inputs, outputs)\n\n    def evaluate(self):\n        results = OrderedDict()\n        for evaluator in self._evaluators:\n            result = evaluator.evaluate()\n            if is_main_process() and result is not None:\n                for k, v in result.items():\n                    assert (\n                        k not in results\n                    ), \"Different evaluators produce results with the same key {}\".format(k)\n                    results[k] = v\n        return results\n\n\ndef inference_on_dataset(\n    model, data_loader, evaluator: Union[DatasetEvaluator, List[DatasetEvaluator], None]\n):\n    \"\"\"\n    Run model on the data_loader and evaluate the metrics with evaluator.\n    Also benchmark the inference speed of `model.__call__` accurately.\n    The model will be used in eval mode.\n\n    Args:\n        model (callable): a callable which takes an object from\n            `data_loader` and returns some outputs.\n\n            If it's an nn.Module, it will be temporarily set to `eval` mode.\n            If you wish to evaluate a model in `training` mode instead, you can\n            wrap the given model and override its behavior of `.eval()` and `.train()`.\n        data_loader: an iterable object with a length.\n            The elements it generates will be the inputs to the model.\n        evaluator: the evaluator(s) to run. Use `None` if you only want to benchmark,\n            but don't want to do any evaluation.\n\n    Returns:\n        The return value of `evaluator.evaluate()`\n    \"\"\"\n    num_devices = get_world_size()\n    logger = logging.getLogger(__name__)\n    logger.info(\"Start inference on {} batches\".format(len(data_loader)))\n\n    total = len(data_loader)  # inference data loader must have a fixed length\n    if evaluator is None:\n        # create a no-op evaluator\n        evaluator = DatasetEvaluators([])\n    if isinstance(evaluator, abc.MutableSequence):\n        evaluator = DatasetEvaluators(evaluator)\n    evaluator.reset()\n\n    num_warmup = min(5, total - 1)\n    start_time = time.perf_counter()\n    total_data_time = 0\n    total_compute_time = 0\n    total_eval_time = 0\n    with ExitStack() as stack:\n        if isinstance(model, nn.Module):\n            stack.enter_context(inference_context(model))\n        stack.enter_context(torch.no_grad())\n\n        start_data_time = time.perf_counter()\n        for idx, inputs in enumerate(data_loader):\n            total_data_time += time.perf_counter() - start_data_time\n            if idx == num_warmup:\n                start_time = time.perf_counter()\n                total_data_time = 0\n                total_compute_time = 0\n                total_eval_time = 0\n\n            start_compute_time = time.perf_counter()\n            outputs = model(inputs)\n            if torch.cuda.is_available():\n                torch.cuda.synchronize()\n            total_compute_time += time.perf_counter() - start_compute_time\n\n            start_eval_time = time.perf_counter()\n            evaluator.process(inputs, outputs)\n            total_eval_time += time.perf_counter() - start_eval_time\n\n            iters_after_start = idx + 1 - num_warmup * int(idx >= num_warmup)\n            data_seconds_per_iter = total_data_time / iters_after_start\n            compute_seconds_per_iter = total_compute_time / iters_after_start\n            eval_seconds_per_iter = total_eval_time / iters_after_start\n            total_seconds_per_iter = (time.perf_counter() - start_time) / iters_after_start\n            if idx >= num_warmup * 2 or compute_seconds_per_iter > 5:\n                eta = datetime.timedelta(seconds=int(total_seconds_per_iter * (total - idx - 1)))\n                log_every_n_seconds(\n                    logging.INFO,\n                    (\n                        f\"Inference done {idx + 1}/{total}. \"\n                        f\"Dataloading: {data_seconds_per_iter:.4f} s/iter. \"\n                        f\"Inference: {compute_seconds_per_iter:.4f} s/iter. \"\n                        f\"Eval: {eval_seconds_per_iter:.4f} s/iter. \"\n                        f\"Total: {total_seconds_per_iter:.4f} s/iter. \"\n                        f\"ETA={eta}\"\n                    ),\n                    n=5,\n                )\n            start_data_time = time.perf_counter()\n\n    # Measure the time only for this worker (before the synchronization barrier)\n    total_time = time.perf_counter() - start_time\n    total_time_str = str(datetime.timedelta(seconds=total_time))\n    # NOTE this format is parsed by grep\n    logger.info(\n        \"Total inference time: {} ({:.6f} s / iter per device, on {} devices)\".format(\n            total_time_str, total_time / (total - num_warmup), num_devices\n        )\n    )\n    total_compute_time_str = str(datetime.timedelta(seconds=int(total_compute_time)))\n    logger.info(\n        \"Total inference pure compute time: {} ({:.6f} s / iter per device, on {} devices)\".format(\n            total_compute_time_str, total_compute_time / (total - num_warmup), num_devices\n        )\n    )\n\n    results = evaluator.evaluate()\n    # An evaluator may return None when not in main process.\n    # Replace it by an empty dict instead to make it easier for downstream code to handle\n    if results is None:\n        results = {}\n    return results\n\n\n@contextmanager\ndef inference_context(model):\n    \"\"\"\n    A context where the model is temporarily changed to eval mode,\n    and restored to previous mode afterwards.\n\n    Args:\n        model: a torch Module\n    \"\"\"\n    training_mode = model.training\n    model.eval()\n    yield\n    model.train(training_mode)\n"
  },
  {
    "path": "VPS_Module/detectron2/evaluation/fast_eval_api.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport copy\nimport logging\nimport numpy as np\nimport time\nfrom pycocotools.cocoeval import COCOeval\n\nfrom detectron2 import _C\n\nlogger = logging.getLogger(__name__)\n\n\nclass COCOeval_opt(COCOeval):\n    \"\"\"\n    This is a slightly modified version of the original COCO API, where the functions evaluateImg()\n    and accumulate() are implemented in C++ to speedup evaluation\n    \"\"\"\n\n    def evaluate(self):\n        \"\"\"\n        Run per image evaluation on given images and store results in self.evalImgs_cpp, a\n        datastructure that isn't readable from Python but is used by a c++ implementation of\n        accumulate().  Unlike the original COCO PythonAPI, we don't populate the datastructure\n        self.evalImgs because this datastructure is a computational bottleneck.\n        :return: None\n        \"\"\"\n        tic = time.time()\n\n        p = self.params\n        # add backward compatibility if useSegm is specified in params\n        if p.useSegm is not None:\n            p.iouType = \"segm\" if p.useSegm == 1 else \"bbox\"\n        logger.info(\"Evaluate annotation type *{}*\".format(p.iouType))\n        p.imgIds = list(np.unique(p.imgIds))\n        if p.useCats:\n            p.catIds = list(np.unique(p.catIds))\n        p.maxDets = sorted(p.maxDets)\n        self.params = p\n\n        self._prepare()  # bottleneck\n\n        # loop through images, area range, max detection number\n        catIds = p.catIds if p.useCats else [-1]\n\n        if p.iouType == \"segm\" or p.iouType == \"bbox\":\n            computeIoU = self.computeIoU\n        elif p.iouType == \"keypoints\":\n            computeIoU = self.computeOks\n        self.ious = {\n            (imgId, catId): computeIoU(imgId, catId) for imgId in p.imgIds for catId in catIds\n        }  # bottleneck\n\n        maxDet = p.maxDets[-1]\n\n        # <<<< Beginning of code differences with original COCO API\n        def convert_instances_to_cpp(instances, is_det=False):\n            # Convert annotations for a list of instances in an image to a format that's fast\n            # to access in C++\n            instances_cpp = []\n            for instance in instances:\n                instance_cpp = _C.InstanceAnnotation(\n                    int(instance[\"id\"]),\n                    instance[\"score\"] if is_det else instance.get(\"score\", 0.0),\n                    instance[\"area\"],\n                    bool(instance.get(\"iscrowd\", 0)),\n                    bool(instance.get(\"ignore\", 0)),\n                )\n                instances_cpp.append(instance_cpp)\n            return instances_cpp\n\n        # Convert GT annotations, detections, and IOUs to a format that's fast to access in C++\n        ground_truth_instances = [\n            [convert_instances_to_cpp(self._gts[imgId, catId]) for catId in p.catIds]\n            for imgId in p.imgIds\n        ]\n        detected_instances = [\n            [convert_instances_to_cpp(self._dts[imgId, catId], is_det=True) for catId in p.catIds]\n            for imgId in p.imgIds\n        ]\n        ious = [[self.ious[imgId, catId] for catId in catIds] for imgId in p.imgIds]\n\n        if not p.useCats:\n            # For each image, flatten per-category lists into a single list\n            ground_truth_instances = [[[o for c in i for o in c]] for i in ground_truth_instances]\n            detected_instances = [[[o for c in i for o in c]] for i in detected_instances]\n\n        # Call C++ implementation of self.evaluateImgs()\n        self._evalImgs_cpp = _C.COCOevalEvaluateImages(\n            p.areaRng, maxDet, p.iouThrs, ious, ground_truth_instances, detected_instances\n        )\n        self._evalImgs = None\n\n        self._paramsEval = copy.deepcopy(self.params)\n        toc = time.time()\n        logger.info(\"COCOeval_opt.evaluate() finished in {:0.2f} seconds.\".format(toc - tic))\n        # >>>> End of code differences with original COCO API\n\n    def accumulate(self):\n        \"\"\"\n        Accumulate per image evaluation results and store the result in self.eval.  Does not\n        support changing parameter settings from those used by self.evaluate()\n        \"\"\"\n        logger.info(\"Accumulating evaluation results...\")\n        tic = time.time()\n        assert hasattr(\n            self, \"_evalImgs_cpp\"\n        ), \"evaluate() must be called before accmulate() is called.\"\n\n        self.eval = _C.COCOevalAccumulate(self._paramsEval, self._evalImgs_cpp)\n\n        # recall is num_iou_thresholds X num_categories X num_area_ranges X num_max_detections\n        self.eval[\"recall\"] = np.array(self.eval[\"recall\"]).reshape(\n            self.eval[\"counts\"][:1] + self.eval[\"counts\"][2:]\n        )\n\n        # precision and scores are num_iou_thresholds X num_recall_thresholds X num_categories X\n        # num_area_ranges X num_max_detections\n        self.eval[\"precision\"] = np.array(self.eval[\"precision\"]).reshape(self.eval[\"counts\"])\n        self.eval[\"scores\"] = np.array(self.eval[\"scores\"]).reshape(self.eval[\"counts\"])\n        toc = time.time()\n        logger.info(\"COCOeval_opt.accumulate() finished in {:0.2f} seconds.\".format(toc - tic))\n"
  },
  {
    "path": "VPS_Module/detectron2/evaluation/lvis_evaluation.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport copy\nimport itertools\nimport json\nimport logging\nimport os\nimport pickle\nfrom collections import OrderedDict\nimport torch\n\nimport detectron2.utils.comm as comm\nfrom detectron2.config import CfgNode\nfrom detectron2.data import MetadataCatalog\nfrom detectron2.structures import Boxes, BoxMode, pairwise_iou\nfrom detectron2.utils.file_io import PathManager\nfrom detectron2.utils.logger import create_small_table\n\nfrom .coco_evaluation import instances_to_coco_json\nfrom .evaluator import DatasetEvaluator\n\n\nclass LVISEvaluator(DatasetEvaluator):\n    \"\"\"\n    Evaluate object proposal and instance detection/segmentation outputs using\n    LVIS's metrics and evaluation API.\n    \"\"\"\n\n    def __init__(\n        self,\n        dataset_name,\n        tasks=None,\n        distributed=True,\n        output_dir=None,\n        *,\n        max_dets_per_image=None,\n    ):\n        \"\"\"\n        Args:\n            dataset_name (str): name of the dataset to be evaluated.\n                It must have the following corresponding metadata:\n                \"json_file\": the path to the LVIS format annotation\n            tasks (tuple[str]): tasks that can be evaluated under the given\n                configuration. A task is one of \"bbox\", \"segm\".\n                By default, will infer this automatically from predictions.\n            distributed (True): if True, will collect results from all ranks for evaluation.\n                Otherwise, will evaluate the results in the current process.\n            output_dir (str): optional, an output directory to dump results.\n            max_dets_per_image (None or int): limit on maximum detections per image in evaluating AP\n                This limit, by default of the LVIS dataset, is 300.\n        \"\"\"\n        from lvis import LVIS\n\n        self._logger = logging.getLogger(__name__)\n\n        if tasks is not None and isinstance(tasks, CfgNode):\n            self._logger.warn(\n                \"COCO Evaluator instantiated using config, this is deprecated behavior.\"\n                \" Please pass in explicit arguments instead.\"\n            )\n            self._tasks = None  # Infering it from predictions should be better\n        else:\n            self._tasks = tasks\n\n        self._distributed = distributed\n        self._output_dir = output_dir\n        self._max_dets_per_image = max_dets_per_image\n\n        self._cpu_device = torch.device(\"cpu\")\n\n        self._metadata = MetadataCatalog.get(dataset_name)\n        json_file = PathManager.get_local_path(self._metadata.json_file)\n        self._lvis_api = LVIS(json_file)\n        # Test set json files do not contain annotations (evaluation must be\n        # performed using the LVIS evaluation server).\n        self._do_evaluation = len(self._lvis_api.get_ann_ids()) > 0\n\n    def reset(self):\n        self._predictions = []\n\n    def process(self, inputs, outputs):\n        \"\"\"\n        Args:\n            inputs: the inputs to a LVIS model (e.g., GeneralizedRCNN).\n                It is a list of dict. Each dict corresponds to an image and\n                contains keys like \"height\", \"width\", \"file_name\", \"image_id\".\n            outputs: the outputs of a LVIS model. It is a list of dicts with key\n                \"instances\" that contains :class:`Instances`.\n        \"\"\"\n        for input, output in zip(inputs, outputs):\n            prediction = {\"image_id\": input[\"image_id\"]}\n\n            if \"instances\" in output:\n                instances = output[\"instances\"].to(self._cpu_device)\n                prediction[\"instances\"] = instances_to_coco_json(instances, input[\"image_id\"])\n            if \"proposals\" in output:\n                prediction[\"proposals\"] = output[\"proposals\"].to(self._cpu_device)\n            self._predictions.append(prediction)\n\n    def evaluate(self):\n        if self._distributed:\n            comm.synchronize()\n            predictions = comm.gather(self._predictions, dst=0)\n            predictions = list(itertools.chain(*predictions))\n\n            if not comm.is_main_process():\n                return\n        else:\n            predictions = self._predictions\n\n        if len(predictions) == 0:\n            self._logger.warning(\"[LVISEvaluator] Did not receive valid predictions.\")\n            return {}\n\n        if self._output_dir:\n            PathManager.mkdirs(self._output_dir)\n            file_path = os.path.join(self._output_dir, \"instances_predictions.pth\")\n            with PathManager.open(file_path, \"wb\") as f:\n                torch.save(predictions, f)\n\n        self._results = OrderedDict()\n        if \"proposals\" in predictions[0]:\n            self._eval_box_proposals(predictions)\n        if \"instances\" in predictions[0]:\n            self._eval_predictions(predictions)\n        # Copy so the caller can do whatever with results\n        return copy.deepcopy(self._results)\n\n    def _tasks_from_predictions(self, predictions):\n        for pred in predictions:\n            if \"segmentation\" in pred:\n                return (\"bbox\", \"segm\")\n        return (\"bbox\",)\n\n    def _eval_predictions(self, predictions):\n        \"\"\"\n        Evaluate predictions. Fill self._results with the metrics of the tasks.\n\n        Args:\n            predictions (list[dict]): list of outputs from the model\n        \"\"\"\n        self._logger.info(\"Preparing results in the LVIS format ...\")\n        lvis_results = list(itertools.chain(*[x[\"instances\"] for x in predictions]))\n        tasks = self._tasks or self._tasks_from_predictions(lvis_results)\n\n        # LVIS evaluator can be used to evaluate results for COCO dataset categories.\n        # In this case `_metadata` variable will have a field with COCO-specific category mapping.\n        if hasattr(self._metadata, \"thing_dataset_id_to_contiguous_id\"):\n            reverse_id_mapping = {\n                v: k for k, v in self._metadata.thing_dataset_id_to_contiguous_id.items()\n            }\n            for result in lvis_results:\n                result[\"category_id\"] = reverse_id_mapping[result[\"category_id\"]]\n        else:\n            # unmap the category ids for LVIS (from 0-indexed to 1-indexed)\n            for result in lvis_results:\n                result[\"category_id\"] += 1\n\n        if self._output_dir:\n            file_path = os.path.join(self._output_dir, \"lvis_instances_results.json\")\n            self._logger.info(\"Saving results to {}\".format(file_path))\n            with PathManager.open(file_path, \"w\") as f:\n                f.write(json.dumps(lvis_results))\n                f.flush()\n\n        if not self._do_evaluation:\n            self._logger.info(\"Annotations are not available for evaluation.\")\n            return\n\n        self._logger.info(\"Evaluating predictions ...\")\n        for task in sorted(tasks):\n            res = _evaluate_predictions_on_lvis(\n                self._lvis_api,\n                lvis_results,\n                task,\n                max_dets_per_image=self._max_dets_per_image,\n                class_names=self._metadata.get(\"thing_classes\"),\n            )\n            self._results[task] = res\n\n    def _eval_box_proposals(self, predictions):\n        \"\"\"\n        Evaluate the box proposals in predictions.\n        Fill self._results with the metrics for \"box_proposals\" task.\n        \"\"\"\n        if self._output_dir:\n            # Saving generated box proposals to file.\n            # Predicted box_proposals are in XYXY_ABS mode.\n            bbox_mode = BoxMode.XYXY_ABS.value\n            ids, boxes, objectness_logits = [], [], []\n            for prediction in predictions:\n                ids.append(prediction[\"image_id\"])\n                boxes.append(prediction[\"proposals\"].proposal_boxes.tensor.numpy())\n                objectness_logits.append(prediction[\"proposals\"].objectness_logits.numpy())\n\n            proposal_data = {\n                \"boxes\": boxes,\n                \"objectness_logits\": objectness_logits,\n                \"ids\": ids,\n                \"bbox_mode\": bbox_mode,\n            }\n            with PathManager.open(os.path.join(self._output_dir, \"box_proposals.pkl\"), \"wb\") as f:\n                pickle.dump(proposal_data, f)\n\n        if not self._do_evaluation:\n            self._logger.info(\"Annotations are not available for evaluation.\")\n            return\n\n        self._logger.info(\"Evaluating bbox proposals ...\")\n        res = {}\n        areas = {\"all\": \"\", \"small\": \"s\", \"medium\": \"m\", \"large\": \"l\"}\n        for limit in [100, 1000]:\n            for area, suffix in areas.items():\n                stats = _evaluate_box_proposals(predictions, self._lvis_api, area=area, limit=limit)\n                key = \"AR{}@{:d}\".format(suffix, limit)\n                res[key] = float(stats[\"ar\"].item() * 100)\n        self._logger.info(\"Proposal metrics: \\n\" + create_small_table(res))\n        self._results[\"box_proposals\"] = res\n\n\n# inspired from Detectron:\n# https://github.com/facebookresearch/Detectron/blob/a6a835f5b8208c45d0dce217ce9bbda915f44df7/detectron/datasets/json_dataset_evaluator.py#L255 # noqa\ndef _evaluate_box_proposals(dataset_predictions, lvis_api, thresholds=None, area=\"all\", limit=None):\n    \"\"\"\n    Evaluate detection proposal recall metrics. This function is a much\n    faster alternative to the official LVIS API recall evaluation code. However,\n    it produces slightly different results.\n    \"\"\"\n    # Record max overlap value for each gt box\n    # Return vector of overlap values\n    areas = {\n        \"all\": 0,\n        \"small\": 1,\n        \"medium\": 2,\n        \"large\": 3,\n        \"96-128\": 4,\n        \"128-256\": 5,\n        \"256-512\": 6,\n        \"512-inf\": 7,\n    }\n    area_ranges = [\n        [0 ** 2, 1e5 ** 2],  # all\n        [0 ** 2, 32 ** 2],  # small\n        [32 ** 2, 96 ** 2],  # medium\n        [96 ** 2, 1e5 ** 2],  # large\n        [96 ** 2, 128 ** 2],  # 96-128\n        [128 ** 2, 256 ** 2],  # 128-256\n        [256 ** 2, 512 ** 2],  # 256-512\n        [512 ** 2, 1e5 ** 2],\n    ]  # 512-inf\n    assert area in areas, \"Unknown area range: {}\".format(area)\n    area_range = area_ranges[areas[area]]\n    gt_overlaps = []\n    num_pos = 0\n\n    for prediction_dict in dataset_predictions:\n        predictions = prediction_dict[\"proposals\"]\n\n        # sort predictions in descending order\n        # TODO maybe remove this and make it explicit in the documentation\n        inds = predictions.objectness_logits.sort(descending=True)[1]\n        predictions = predictions[inds]\n\n        ann_ids = lvis_api.get_ann_ids(img_ids=[prediction_dict[\"image_id\"]])\n        anno = lvis_api.load_anns(ann_ids)\n        gt_boxes = [\n            BoxMode.convert(obj[\"bbox\"], BoxMode.XYWH_ABS, BoxMode.XYXY_ABS) for obj in anno\n        ]\n        gt_boxes = torch.as_tensor(gt_boxes).reshape(-1, 4)  # guard against no boxes\n        gt_boxes = Boxes(gt_boxes)\n        gt_areas = torch.as_tensor([obj[\"area\"] for obj in anno])\n\n        if len(gt_boxes) == 0 or len(predictions) == 0:\n            continue\n\n        valid_gt_inds = (gt_areas >= area_range[0]) & (gt_areas <= area_range[1])\n        gt_boxes = gt_boxes[valid_gt_inds]\n\n        num_pos += len(gt_boxes)\n\n        if len(gt_boxes) == 0:\n            continue\n\n        if limit is not None and len(predictions) > limit:\n            predictions = predictions[:limit]\n\n        overlaps = pairwise_iou(predictions.proposal_boxes, gt_boxes)\n\n        _gt_overlaps = torch.zeros(len(gt_boxes))\n        for j in range(min(len(predictions), len(gt_boxes))):\n            # find which proposal box maximally covers each gt box\n            # and get the iou amount of coverage for each gt box\n            max_overlaps, argmax_overlaps = overlaps.max(dim=0)\n\n            # find which gt box is 'best' covered (i.e. 'best' = most iou)\n            gt_ovr, gt_ind = max_overlaps.max(dim=0)\n            assert gt_ovr >= 0\n            # find the proposal box that covers the best covered gt box\n            box_ind = argmax_overlaps[gt_ind]\n            # record the iou coverage of this gt box\n            _gt_overlaps[j] = overlaps[box_ind, gt_ind]\n            assert _gt_overlaps[j] == gt_ovr\n            # mark the proposal box and the gt box as used\n            overlaps[box_ind, :] = -1\n            overlaps[:, gt_ind] = -1\n\n        # append recorded iou coverage level\n        gt_overlaps.append(_gt_overlaps)\n    gt_overlaps = (\n        torch.cat(gt_overlaps, dim=0) if len(gt_overlaps) else torch.zeros(0, dtype=torch.float32)\n    )\n    gt_overlaps, _ = torch.sort(gt_overlaps)\n\n    if thresholds is None:\n        step = 0.05\n        thresholds = torch.arange(0.5, 0.95 + 1e-5, step, dtype=torch.float32)\n    recalls = torch.zeros_like(thresholds)\n    # compute recall for each iou threshold\n    for i, t in enumerate(thresholds):\n        recalls[i] = (gt_overlaps >= t).float().sum() / float(num_pos)\n    # ar = 2 * np.trapz(recalls, thresholds)\n    ar = recalls.mean()\n    return {\n        \"ar\": ar,\n        \"recalls\": recalls,\n        \"thresholds\": thresholds,\n        \"gt_overlaps\": gt_overlaps,\n        \"num_pos\": num_pos,\n    }\n\n\ndef _evaluate_predictions_on_lvis(\n    lvis_gt, lvis_results, iou_type, max_dets_per_image=None, class_names=None\n):\n    \"\"\"\n    Args:\n        iou_type (str):\n        max_dets_per_image (None or int): limit on maximum detections per image in evaluating AP\n            This limit, by default of the LVIS dataset, is 300.\n        class_names (None or list[str]): if provided, will use it to predict\n            per-category AP.\n\n    Returns:\n        a dict of {metric name: score}\n    \"\"\"\n    metrics = {\n        \"bbox\": [\"AP\", \"AP50\", \"AP75\", \"APs\", \"APm\", \"APl\", \"APr\", \"APc\", \"APf\"],\n        \"segm\": [\"AP\", \"AP50\", \"AP75\", \"APs\", \"APm\", \"APl\", \"APr\", \"APc\", \"APf\"],\n    }[iou_type]\n\n    logger = logging.getLogger(__name__)\n\n    if len(lvis_results) == 0:  # TODO: check if needed\n        logger.warn(\"No predictions from the model!\")\n        return {metric: float(\"nan\") for metric in metrics}\n\n    if iou_type == \"segm\":\n        lvis_results = copy.deepcopy(lvis_results)\n        # When evaluating mask AP, if the results contain bbox, LVIS API will\n        # use the box area as the area of the instance, instead of the mask area.\n        # This leads to a different definition of small/medium/large.\n        # We remove the bbox field to let mask AP use mask area.\n        for c in lvis_results:\n            c.pop(\"bbox\", None)\n\n    if max_dets_per_image is None:\n        max_dets_per_image = 300  # Default for LVIS dataset\n\n    from lvis import LVISEval, LVISResults\n\n    logger.info(f\"Evaluating with max detections per image = {max_dets_per_image}\")\n    lvis_results = LVISResults(lvis_gt, lvis_results, max_dets=max_dets_per_image)\n    lvis_eval = LVISEval(lvis_gt, lvis_results, iou_type)\n    lvis_eval.run()\n    lvis_eval.print_results()\n\n    # Pull the standard metrics from the LVIS results\n    results = lvis_eval.get_results()\n    results = {metric: float(results[metric] * 100) for metric in metrics}\n    logger.info(\"Evaluation results for {}: \\n\".format(iou_type) + create_small_table(results))\n    return results\n"
  },
  {
    "path": "VPS_Module/detectron2/evaluation/panoptic_evaluation.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport contextlib\nimport io\nimport itertools\nimport json\nimport logging\nimport numpy as np\nimport os\nimport tempfile\nfrom collections import OrderedDict\nfrom typing import Optional\nfrom PIL import Image\nfrom tabulate import tabulate\n\nfrom detectron2.data import MetadataCatalog\nfrom detectron2.utils import comm\nfrom detectron2.utils.file_io import PathManager\nfrom .pq_compute import pq_compute\n\nfrom .evaluator import DatasetEvaluator\n\nlogger = logging.getLogger(__name__)\n\n\nclass COCOPanopticEvaluator(DatasetEvaluator):\n    \"\"\"\n    Evaluate Panoptic Quality metrics on COCO using PanopticAPI.\n    It saves panoptic segmentation prediction in `output_dir`\n\n    It contains a synchronize call and has to be called from all workers.\n    \"\"\"\n\n    def __init__(self, dataset_name: str, output_dir: Optional[str] = None):\n        \"\"\"\n        Args:\n            dataset_name: name of the dataset\n            output_dir: output directory to save results for evaluation.\n        \"\"\"\n        self._metadata = MetadataCatalog.get(dataset_name)\n        self._thing_contiguous_id_to_dataset_id = {\n            v: k for k, v in self._metadata.thing_dataset_id_to_contiguous_id.items()\n        }\n        self._stuff_contiguous_id_to_dataset_id = {\n            v: k for k, v in self._metadata.stuff_dataset_id_to_contiguous_id.items()\n        }\n\n        self.dataset_name = dataset_name\n        self._output_dir = output_dir\n        if self._output_dir is not None:\n            PathManager.mkdirs(self._output_dir)\n\n    def reset(self):\n        self._predictions = []\n\n    def _convert_category_id(self, segment_info):\n        isthing = segment_info.pop(\"isthing\", None)\n        if isthing is None:\n            # the model produces panoptic category id directly. No more conversion needed\n            return segment_info\n        if isthing is True:\n            segment_info[\"category_id\"] = self._thing_contiguous_id_to_dataset_id[\n                segment_info[\"category_id\"]\n            ]\n        else:\n            segment_info[\"category_id\"] = self._stuff_contiguous_id_to_dataset_id[\n                segment_info[\"category_id\"]\n            ]\n        return segment_info\n\n    def process(self, inputs, outputs):\n        from panopticapi.utils import id2rgb\n\n        for input, output in zip(inputs, outputs):\n            panoptic_img, segments_info = output[\"panoptic_seg\"]\n            panoptic_img = panoptic_img.cpu().numpy()\n            if segments_info is None:\n                # If \"segments_info\" is None, we assume \"panoptic_img\" is a\n                # H*W int32 image storing the panoptic_id in the format of\n                # category_id * label_divisor + instance_id. We reserve -1 for\n                # VOID label, and add 1 to panoptic_img since the official\n                # evaluation script uses 0 for VOID label.\n                label_divisor = self._metadata.label_divisor\n                segments_info = []\n                for panoptic_label in np.unique(panoptic_img):\n                    if panoptic_label == -1:\n                        # VOID region.\n                        continue\n                    pred_class = panoptic_label // label_divisor\n                    isthing = (\n                        pred_class in self._metadata.thing_dataset_id_to_contiguous_id.values()\n                    )\n                    segments_info.append(\n                        {\n                            \"id\": int(panoptic_label) + 1,\n                            \"category_id\": int(pred_class),\n                            \"isthing\": bool(isthing),\n                        }\n                    )\n                # Official evaluation script uses 0 for VOID label.\n                panoptic_img += 1\n\n            file_name = os.path.basename(input[\"file_name\"])\n            file_name_png = os.path.splitext(file_name)[0] + \".png\"\n            with io.BytesIO() as out:\n                Image.fromarray(id2rgb(panoptic_img)).save(out, format=\"PNG\")\n                # ---------------- vkitti, cityscapes jump this --------------------------------------------------------------\n                # segments_info = [self._convert_category_id(x) for x in segments_info]\n                self._predictions.append(\n                    {\n                        \"image_id\": input[\"image_id\"],\n                        \"file_name\": file_name_png,\n                        \"png_string\": out.getvalue(),\n                        \"segments_info\": segments_info,\n                    }\n                )\n\n    def evaluate(self):\n        comm.synchronize()\n\n        self._predictions = comm.gather(self._predictions)\n        self._predictions = list(itertools.chain(*self._predictions))\n        if not comm.is_main_process():\n            return\n\n        # PanopticApi requires local files\n        gt_json = PathManager.get_local_path(self._metadata.panoptic_json)\n        gt_folder = PathManager.get_local_path(self._metadata.panoptic_root)\n\n        pred_dir = os.path.join(self._output_dir,'pan_seg')\n        if not os.path.isdir(pred_dir):\n            os.makedirs(pred_dir)\n        # with tempfile.TemporaryDirectory(prefix=\"panoptic_eval\") as pred_dir:\n        logger.info(\"Writing all panoptic predictions to {} ...\".format(pred_dir))\n        for p in self._predictions:\n            with open(os.path.join(pred_dir, p[\"file_name\"]), \"wb\") as f:\n                f.write(p.pop(\"png_string\"))\n\n        with open(gt_json, \"r\") as f:\n            json_data = json.load(f)\n        json_data[\"annotations\"] = self._predictions\n\n        output_dir = self._output_dir or pred_dir\n        predictions_json = os.path.join(output_dir, \"predictions.json\")\n        with PathManager.open(predictions_json, \"w\") as f:\n            f.write(json.dumps(json_data))\n\n            # with contextlib.redirect_stdout(io.StringIO()):\n        pq_res = pq_compute(\n                    gt_json,\n                    PathManager.get_local_path(predictions_json),\n                    gt_folder=gt_folder,\n                    pred_folder=pred_dir,\n                )\n\n        res = {}\n        res[\"PQ\"] = 100 * pq_res[\"All\"][\"pq\"]\n        res[\"SQ\"] = 100 * pq_res[\"All\"][\"sq\"]\n        res[\"RQ\"] = 100 * pq_res[\"All\"][\"rq\"]\n        res[\"PQ_th\"] = 100 * pq_res[\"Things\"][\"pq\"]\n        res[\"SQ_th\"] = 100 * pq_res[\"Things\"][\"sq\"]\n        res[\"RQ_th\"] = 100 * pq_res[\"Things\"][\"rq\"]\n        res[\"PQ_st\"] = 100 * pq_res[\"Stuff\"][\"pq\"]\n        res[\"SQ_st\"] = 100 * pq_res[\"Stuff\"][\"sq\"]\n        res[\"RQ_st\"] = 100 * pq_res[\"Stuff\"][\"rq\"]\n\n        results = OrderedDict({\"panoptic_seg\": res})\n        _print_panoptic_results(pq_res)\n\n        return results\n\n\ndef _print_panoptic_results(pq_res):\n    headers = [\"\", \"PQ\", \"SQ\", \"RQ\", \"#categories\"]\n    data = []\n    for name in [\"All\", \"Things\", \"Stuff\"]:\n        row = [name] + [pq_res[name][k] * 100 for k in [\"pq\", \"sq\", \"rq\"]] + [pq_res[name][\"n\"]]\n        data.append(row)\n    table = tabulate(\n        data, headers=headers, tablefmt=\"pipe\", floatfmt=\".3f\", stralign=\"center\", numalign=\"center\"\n    )\n    logger.info(\"Panoptic Evaluation Results:\\n\" + table)\n\n\nif __name__ == \"__main__\":\n    from detectron2.utils.logger import setup_logger\n\n    logger = setup_logger()\n    import argparse\n\n    parser = argparse.ArgumentParser()\n    parser.add_argument(\"--gt-json\")\n    parser.add_argument(\"--gt-dir\")\n    parser.add_argument(\"--pred-json\")\n    parser.add_argument(\"--pred-dir\")\n    args = parser.parse_args()\n\n    from panopticapi.evaluation import pq_compute\n\n    with contextlib.redirect_stdout(io.StringIO()):\n        pq_res = pq_compute(\n            args.gt_json, args.pred_json, gt_folder=args.gt_dir, pred_folder=args.pred_dir\n        )\n        _print_panoptic_results(pq_res)\n"
  },
  {
    "path": "VPS_Module/detectron2/evaluation/pascal_voc_evaluation.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport logging\nimport numpy as np\nimport os\nimport tempfile\nimport xml.etree.ElementTree as ET\nfrom collections import OrderedDict, defaultdict\nfrom functools import lru_cache\nimport torch\n\nfrom detectron2.data import MetadataCatalog\nfrom detectron2.utils import comm\nfrom detectron2.utils.file_io import PathManager\n\nfrom .evaluator import DatasetEvaluator\n\n\nclass PascalVOCDetectionEvaluator(DatasetEvaluator):\n    \"\"\"\n    Evaluate Pascal VOC style AP for Pascal VOC dataset.\n    It contains a synchronization, therefore has to be called from all ranks.\n\n    Note that the concept of AP can be implemented in different ways and may not\n    produce identical results. This class mimics the implementation of the official\n    Pascal VOC Matlab API, and should produce similar but not identical results to the\n    official API.\n    \"\"\"\n\n    def __init__(self, dataset_name):\n        \"\"\"\n        Args:\n            dataset_name (str): name of the dataset, e.g., \"voc_2007_test\"\n        \"\"\"\n        self._dataset_name = dataset_name\n        meta = MetadataCatalog.get(dataset_name)\n\n        # Too many tiny files, download all to local for speed.\n        annotation_dir_local = PathManager.get_local_path(\n            os.path.join(meta.dirname, \"Annotations/\")\n        )\n        self._anno_file_template = os.path.join(annotation_dir_local, \"{}.xml\")\n        self._image_set_path = os.path.join(meta.dirname, \"ImageSets\", \"Main\", meta.split + \".txt\")\n        self._class_names = meta.thing_classes\n        assert meta.year in [2007, 2012], meta.year\n        self._is_2007 = meta.year == 2007\n        self._cpu_device = torch.device(\"cpu\")\n        self._logger = logging.getLogger(__name__)\n\n    def reset(self):\n        self._predictions = defaultdict(list)  # class name -> list of prediction strings\n\n    def process(self, inputs, outputs):\n        for input, output in zip(inputs, outputs):\n            image_id = input[\"image_id\"]\n            instances = output[\"instances\"].to(self._cpu_device)\n            boxes = instances.pred_boxes.tensor.numpy()\n            scores = instances.scores.tolist()\n            classes = instances.pred_classes.tolist()\n            for box, score, cls in zip(boxes, scores, classes):\n                xmin, ymin, xmax, ymax = box\n                # The inverse of data loading logic in `datasets/pascal_voc.py`\n                xmin += 1\n                ymin += 1\n                self._predictions[cls].append(\n                    f\"{image_id} {score:.3f} {xmin:.1f} {ymin:.1f} {xmax:.1f} {ymax:.1f}\"\n                )\n\n    def evaluate(self):\n        \"\"\"\n        Returns:\n            dict: has a key \"segm\", whose value is a dict of \"AP\", \"AP50\", and \"AP75\".\n        \"\"\"\n        all_predictions = comm.gather(self._predictions, dst=0)\n        if not comm.is_main_process():\n            return\n        predictions = defaultdict(list)\n        for predictions_per_rank in all_predictions:\n            for clsid, lines in predictions_per_rank.items():\n                predictions[clsid].extend(lines)\n        del all_predictions\n\n        self._logger.info(\n            \"Evaluating {} using {} metric. \"\n            \"Note that results do not use the official Matlab API.\".format(\n                self._dataset_name, 2007 if self._is_2007 else 2012\n            )\n        )\n\n        with tempfile.TemporaryDirectory(prefix=\"pascal_voc_eval_\") as dirname:\n            res_file_template = os.path.join(dirname, \"{}.txt\")\n\n            aps = defaultdict(list)  # iou -> ap per class\n            for cls_id, cls_name in enumerate(self._class_names):\n                lines = predictions.get(cls_id, [\"\"])\n\n                with open(res_file_template.format(cls_name), \"w\") as f:\n                    f.write(\"\\n\".join(lines))\n\n                for thresh in range(50, 100, 5):\n                    rec, prec, ap = voc_eval(\n                        res_file_template,\n                        self._anno_file_template,\n                        self._image_set_path,\n                        cls_name,\n                        ovthresh=thresh / 100.0,\n                        use_07_metric=self._is_2007,\n                    )\n                    aps[thresh].append(ap * 100)\n\n        ret = OrderedDict()\n        mAP = {iou: np.mean(x) for iou, x in aps.items()}\n        ret[\"bbox\"] = {\"AP\": np.mean(list(mAP.values())), \"AP50\": mAP[50], \"AP75\": mAP[75]}\n        return ret\n\n\n##############################################################################\n#\n# Below code is modified from\n# https://github.com/rbgirshick/py-faster-rcnn/blob/master/lib/datasets/voc_eval.py\n# --------------------------------------------------------\n# Fast/er R-CNN\n# Licensed under The MIT License [see LICENSE for details]\n# Written by Bharath Hariharan\n# --------------------------------------------------------\n\n\"\"\"Python implementation of the PASCAL VOC devkit's AP evaluation code.\"\"\"\n\n\n@lru_cache(maxsize=None)\ndef parse_rec(filename):\n    \"\"\"Parse a PASCAL VOC xml file.\"\"\"\n    with PathManager.open(filename) as f:\n        tree = ET.parse(f)\n    objects = []\n    for obj in tree.findall(\"object\"):\n        obj_struct = {}\n        obj_struct[\"name\"] = obj.find(\"name\").text\n        obj_struct[\"pose\"] = obj.find(\"pose\").text\n        obj_struct[\"truncated\"] = int(obj.find(\"truncated\").text)\n        obj_struct[\"difficult\"] = int(obj.find(\"difficult\").text)\n        bbox = obj.find(\"bndbox\")\n        obj_struct[\"bbox\"] = [\n            int(bbox.find(\"xmin\").text),\n            int(bbox.find(\"ymin\").text),\n            int(bbox.find(\"xmax\").text),\n            int(bbox.find(\"ymax\").text),\n        ]\n        objects.append(obj_struct)\n\n    return objects\n\n\ndef voc_ap(rec, prec, use_07_metric=False):\n    \"\"\"Compute VOC AP given precision and recall. If use_07_metric is true, uses\n    the VOC 07 11-point method (default:False).\n    \"\"\"\n    if use_07_metric:\n        # 11 point metric\n        ap = 0.0\n        for t in np.arange(0.0, 1.1, 0.1):\n            if np.sum(rec >= t) == 0:\n                p = 0\n            else:\n                p = np.max(prec[rec >= t])\n            ap = ap + p / 11.0\n    else:\n        # correct AP calculation\n        # first append sentinel values at the end\n        mrec = np.concatenate(([0.0], rec, [1.0]))\n        mpre = np.concatenate(([0.0], prec, [0.0]))\n\n        # compute the precision envelope\n        for i in range(mpre.size - 1, 0, -1):\n            mpre[i - 1] = np.maximum(mpre[i - 1], mpre[i])\n\n        # to calculate area under PR curve, look for points\n        # where X axis (recall) changes value\n        i = np.where(mrec[1:] != mrec[:-1])[0]\n\n        # and sum (\\Delta recall) * prec\n        ap = np.sum((mrec[i + 1] - mrec[i]) * mpre[i + 1])\n    return ap\n\n\ndef voc_eval(detpath, annopath, imagesetfile, classname, ovthresh=0.5, use_07_metric=False):\n    \"\"\"rec, prec, ap = voc_eval(detpath,\n                                annopath,\n                                imagesetfile,\n                                classname,\n                                [ovthresh],\n                                [use_07_metric])\n\n    Top level function that does the PASCAL VOC evaluation.\n\n    detpath: Path to detections\n        detpath.format(classname) should produce the detection results file.\n    annopath: Path to annotations\n        annopath.format(imagename) should be the xml annotations file.\n    imagesetfile: Text file containing the list of images, one image per line.\n    classname: Category name (duh)\n    [ovthresh]: Overlap threshold (default = 0.5)\n    [use_07_metric]: Whether to use VOC07's 11 point AP computation\n        (default False)\n    \"\"\"\n    # assumes detections are in detpath.format(classname)\n    # assumes annotations are in annopath.format(imagename)\n    # assumes imagesetfile is a text file with each line an image name\n\n    # first load gt\n    # read list of images\n    with PathManager.open(imagesetfile, \"r\") as f:\n        lines = f.readlines()\n    imagenames = [x.strip() for x in lines]\n\n    # load annots\n    recs = {}\n    for imagename in imagenames:\n        recs[imagename] = parse_rec(annopath.format(imagename))\n\n    # extract gt objects for this class\n    class_recs = {}\n    npos = 0\n    for imagename in imagenames:\n        R = [obj for obj in recs[imagename] if obj[\"name\"] == classname]\n        bbox = np.array([x[\"bbox\"] for x in R])\n        difficult = np.array([x[\"difficult\"] for x in R]).astype(np.bool)\n        # difficult = np.array([False for x in R]).astype(np.bool)  # treat all \"difficult\" as GT\n        det = [False] * len(R)\n        npos = npos + sum(~difficult)\n        class_recs[imagename] = {\"bbox\": bbox, \"difficult\": difficult, \"det\": det}\n\n    # read dets\n    detfile = detpath.format(classname)\n    with open(detfile, \"r\") as f:\n        lines = f.readlines()\n\n    splitlines = [x.strip().split(\" \") for x in lines]\n    image_ids = [x[0] for x in splitlines]\n    confidence = np.array([float(x[1]) for x in splitlines])\n    BB = np.array([[float(z) for z in x[2:]] for x in splitlines]).reshape(-1, 4)\n\n    # sort by confidence\n    sorted_ind = np.argsort(-confidence)\n    BB = BB[sorted_ind, :]\n    image_ids = [image_ids[x] for x in sorted_ind]\n\n    # go down dets and mark TPs and FPs\n    nd = len(image_ids)\n    tp = np.zeros(nd)\n    fp = np.zeros(nd)\n    for d in range(nd):\n        R = class_recs[image_ids[d]]\n        bb = BB[d, :].astype(float)\n        ovmax = -np.inf\n        BBGT = R[\"bbox\"].astype(float)\n\n        if BBGT.size > 0:\n            # compute overlaps\n            # intersection\n            ixmin = np.maximum(BBGT[:, 0], bb[0])\n            iymin = np.maximum(BBGT[:, 1], bb[1])\n            ixmax = np.minimum(BBGT[:, 2], bb[2])\n            iymax = np.minimum(BBGT[:, 3], bb[3])\n            iw = np.maximum(ixmax - ixmin + 1.0, 0.0)\n            ih = np.maximum(iymax - iymin + 1.0, 0.0)\n            inters = iw * ih\n\n            # union\n            uni = (\n                (bb[2] - bb[0] + 1.0) * (bb[3] - bb[1] + 1.0)\n                + (BBGT[:, 2] - BBGT[:, 0] + 1.0) * (BBGT[:, 3] - BBGT[:, 1] + 1.0)\n                - inters\n            )\n\n            overlaps = inters / uni\n            ovmax = np.max(overlaps)\n            jmax = np.argmax(overlaps)\n\n        if ovmax > ovthresh:\n            if not R[\"difficult\"][jmax]:\n                if not R[\"det\"][jmax]:\n                    tp[d] = 1.0\n                    R[\"det\"][jmax] = 1\n                else:\n                    fp[d] = 1.0\n        else:\n            fp[d] = 1.0\n\n    # compute precision recall\n    fp = np.cumsum(fp)\n    tp = np.cumsum(tp)\n    rec = tp / float(npos)\n    # avoid divide by zero in case the first detection matches a difficult\n    # ground truth\n    prec = tp / np.maximum(tp + fp, np.finfo(np.float64).eps)\n    ap = voc_ap(rec, prec, use_07_metric)\n\n    return rec, prec, ap\n"
  },
  {
    "path": "VPS_Module/detectron2/evaluation/pq_compute.py",
    "content": "import os, sys\nimport numpy as np\nimport json\nimport time\nfrom datetime import timedelta\nfrom collections import defaultdict\nimport argparse\nimport multiprocessing\n\nimport PIL.Image as Image\n\nfrom panopticapi.utils import get_traceback, rgb2id\n\nOFFSET = 256 * 256 * 256\nVOID = 0\n\nclass PQStatCat():\n        def __init__(self):\n            self.iou = 0.0\n            self.tp = 0\n            self.fp = 0\n            self.fn = 0\n\n        def __iadd__(self, pq_stat_cat):\n            self.iou += pq_stat_cat.iou\n            self.tp += pq_stat_cat.tp\n            self.fp += pq_stat_cat.fp\n            self.fn += pq_stat_cat.fn\n            return self\n\n\nclass PQStat():\n    def __init__(self):\n        self.pq_per_cat = defaultdict(PQStatCat)\n\n    def __getitem__(self, i):\n        return self.pq_per_cat[i]\n\n    def __iadd__(self, pq_stat):\n        for label, pq_stat_cat in pq_stat.pq_per_cat.items():\n            self.pq_per_cat[label] += pq_stat_cat\n        return self\n\n    def pq_average(self, categories, isthing):\n        pq, sq, rq, n = 0, 0, 0, 0\n        per_class_results = {}\n        \n        for label, label_info in categories.items():\n            if isthing is not None:\n                cat_isthing = label_info['isthing'] == 1\n                if isthing != cat_isthing:\n                    continue\n            iou = self.pq_per_cat[label].iou\n            tp = self.pq_per_cat[label].tp\n            fp = self.pq_per_cat[label].fp\n            fn = self.pq_per_cat[label].fn\n            if tp + fp + fn == 0:\n                per_class_results[label] = {'pq': 0.0, 'sq': 0.0, 'rq': 0.0}\n                continue\n            n += 1\n            pq_class = iou / (tp + 0.5 * fp + 0.5 * fn)\n            sq_class = iou / tp if tp != 0 else 0\n            rq_class = tp / (tp + 0.5 * fp + 0.5 * fn)\n            per_class_results[label] = {'pq': pq_class, 'sq': sq_class, 'rq': rq_class, 'iou':iou, \n                                        'tp': tp, 'fp': fp, 'fn': fn}\n            pq += pq_class\n            sq += sq_class\n            rq += rq_class\n        \n        return {'pq': pq / n, 'sq': sq / n, 'rq': rq / n, 'n': n}, per_class_results\n\n\n@get_traceback\ndef pq_compute_single_core(proc_id, annotation_set, gt_folder, pred_folder, categories):\n    pq_stat = PQStat()\n\n    idx = 0\n    for gt_ann, pred_ann in annotation_set:\n        if idx % 100 == 0:\n            print('Core: {}, {} from {} images processed'.format(proc_id, idx, len(annotation_set)))\n        idx += 1\n\n        pan_gt = np.array(Image.open(os.path.join(gt_folder, gt_ann['file_name'])), dtype=np.uint32)\n        pan_gt = rgb2id(pan_gt)\n        pan_pred = np.array(Image.open(os.path.join(pred_folder, pred_ann['file_name'])), dtype=np.uint32)\n        pan_pred = rgb2id(pan_pred)\n\n        gt_segms = {el['id']: el for el in gt_ann['segments_info']}\n        pred_segms = {el['id']: el for el in pred_ann['segments_info']}\n\n        # predicted segments area calculation + prediction sanity checks\n        pred_labels_set = set(el['id'] for el in pred_ann['segments_info'])\n        labels, labels_cnt = np.unique(pan_pred, return_counts=True) # 返回预测的segm_map上存在的label数，和每个label的个数（即masks的大小）\n        # print('pan_pred_label: ',labels)\n        for label, label_cnt in zip(labels, labels_cnt):\n            if label not in pred_segms:\n                if label == VOID:\n                    continue\n                raise KeyError('In the image with ID {} segment with ID {} is presented in PNG and not presented in JSON.'.format(gt_ann['image_id'], label))\n            pred_segms[label]['area'] = label_cnt\n            pred_labels_set.remove(label)\n            if pred_segms[label]['category_id'] not in categories:\n                raise KeyError('In the image with ID {} segment with ID {} has unknown category_id {}.'.format(gt_ann['image_id'], label, pred_segms[label]['category_id']))\n        if len(pred_labels_set) != 0:\n            raise KeyError('In the image with ID {} the following segment IDs {} are presented in JSON and not presented in PNG.'.format(gt_ann['image_id'], list(pred_labels_set)))\n\n        # confusion matrix calculation\n        pan_gt_pred = pan_gt.astype(np.uint64) * OFFSET + pan_pred.astype(np.uint64)\n        gt_pred_map = {}\n        labels, labels_cnt = np.unique(pan_gt_pred, return_counts=True)\n        for label, intersection in zip(labels, labels_cnt):\n            gt_id = label // OFFSET\n            pred_id = label % OFFSET\n            gt_pred_map[(gt_id, pred_id)] = intersection # 一个例子:(15213556.0, 31.0): 48\n        # count all matched pairs  === TP ===\n        gt_matched = set()\n        pred_matched = set()\n        for label_tuple, intersection in gt_pred_map.items():\n            gt_label, pred_label = label_tuple\n            if gt_label not in gt_segms:\n                continue\n            if pred_label not in pred_segms:\n                continue\n            if gt_segms[gt_label]['iscrowd'] == 1:\n                continue\n            if gt_segms[gt_label]['category_id'] != pred_segms[pred_label]['category_id']:\n                continue\n\n            union = pred_segms[pred_label]['area'] + gt_segms[gt_label]['area'] \\\n                        - intersection - gt_pred_map.get((VOID, pred_label), 0)\n            iou = intersection / union\n            if iou > 0.5:\n                pq_stat[gt_segms[gt_label]['category_id']].tp += 1\n                pq_stat[gt_segms[gt_label]['category_id']].iou += iou\n                gt_matched.add(gt_label)\n                pred_matched.add(pred_label)\n\n        # count false positives  === FP ===\n        crowd_labels_dict = {}\n        for gt_label, gt_info in gt_segms.items():\n            if gt_label in gt_matched:\n                continue\n            # crowd segments are ignored\n            if gt_info['iscrowd'] == 1:\n                crowd_labels_dict[gt_info['category_id']] = gt_label\n                continue\n            pq_stat[gt_info['category_id']].fn += 1\n\n        # count false positives   === FP ===\n        for pred_label, pred_info in pred_segms.items():\n            if pred_label in pred_matched:\n                continue\n            # intersection of the segment with VOID\n            intersection = gt_pred_map.get((VOID, pred_label), 0)\n            # plus intersection with corresponding CROWD region if it exists\n            if pred_info['category_id'] in crowd_labels_dict:\n                intersection += gt_pred_map.get((crowd_labels_dict[pred_info['category_id']], pred_label), 0)\n            # predicted segment is ignored if more than half of the segment correspond to VOID and CROWD regions\n            if intersection / pred_info['area'] > 0.5:\n                continue\n            pq_stat[pred_info['category_id']].fp += 1\n\n    print('Core: {}, all {} images processed'.format(proc_id, len(annotation_set)))\n    return pq_stat\n\n\ndef pq_compute_multi_core(matched_annotations_list, gt_folder, pred_folder, categories):\n    cpu_num = int(multiprocessing.cpu_count() // 2)\n    annotations_split = np.array_split(matched_annotations_list, cpu_num)\n    print(\"Number of cores: {}, images per core: {}\\n\".format(cpu_num, len(annotations_split[0])))\n    workers = multiprocessing.Pool(processes=cpu_num)\n    processes = []\n    for proc_id, annotation_set in enumerate(annotations_split):\n        p = workers.apply_async(pq_compute_single_core,\n                                (proc_id, annotation_set, gt_folder, pred_folder, categories))\n        processes.append(p)\n    pq_stat = PQStat()\n    for p in processes:\n        pq_stat += p.get()\n    workers.terminate()\n    workers.join()\n    return pq_stat\n\n\ndef pq_compute(gt_json_file, pred_json_file, gt_folder=None, pred_folder=None):\n\n    start_time = time.time()\n    with open(gt_json_file, 'r') as f:\n        gt_json = json.load(f)\n    with open(pred_json_file, 'r') as f:\n        pred_json = json.load(f)\n\n    if gt_folder is None:\n        gt_folder = gt_json_file.replace('.json', '')\n    if pred_folder is None:\n        pred_folder = pred_json_file.replace('.json', '')\n    if 'kitti_panoptic' in gt_json_file:\n        categories = {el['trainId']: el for el in gt_json['categories']}\n    else:\n        categories = {el['id']: el for el in gt_json['categories']}\n    print(\"---------------------------------\",len(categories))\n\n    print(\"Evaluation panoptic segmentation metrics:\")\n    print(\"Ground truth:\")\n    print(\"\\tSegmentation folder: {}\".format(gt_folder))\n    print(\"\\tJSON file: {}\".format(gt_json_file))\n    print(\"Prediction:\")\n    print(\"\\tSegmentation folder: {}\".format(pred_folder))\n    print(\"\\tJSON file: {}\".format(pred_json_file))\n\n    if not os.path.isdir(gt_folder):\n        raise Exception(\"Folder {} with ground truth segmentations doesn't exist\".format(gt_folder))\n    if not os.path.isdir(pred_folder):\n        raise Exception(\"Folder {} with predicted segmentations doesn't exist\".format(pred_folder))\n\n    pred_annotations = {el['image_id']: el for el in pred_json['annotations']}\n    matched_annotations_list = []\n    for gt_ann in gt_json['annotations']:\n        image_id = gt_ann['image_id']\n        if image_id not in pred_annotations:\n            raise Exception('no prediction for the image with id: {}'.format(image_id))\n        matched_annotations_list.append((gt_ann, pred_annotations[image_id]))\n\n    pq_stat = pq_compute_multi_core(matched_annotations_list, gt_folder, pred_folder, categories)\n    metrics = [(\"All\", None), (\"Things\", True), (\"Stuff\", False)]\n    results = {}\n    print(\"------------------------------------------------\")\n    for name, isthing in metrics:\n        results[name], per_class_results = pq_stat.pq_average(categories, isthing=isthing)\n        if name != 'All':\n            for k,v in per_class_results.items():\n                print(k,\"-\",categories[k]['name'],\" : \",v)\n            print(\"------------------------------------------------\")\n        if name == 'All':\n            results['per_class'] = per_class_results\n    print(\"{:10s}| {:>5s}  {:>5s}  {:>5s} {:>5s}\".format(\"\", \"PQ\", \"SQ\", \"RQ\", \"N\"))\n    print(\"-\" * (10 + 7 * 4))\n\n    for name, _isthing in metrics:\n        print(\"{:10s}| {:5.1f}  {:5.1f}  {:5.1f} {:5d}\".format(\n            name,\n            100 * results[name]['pq'],\n            100 * results[name]['sq'],\n            100 * results[name]['rq'],\n            results[name]['n'])\n        )\n\n    t_delta = time.time() - start_time\n    print(\"Time elapsed: {:0.2f} seconds\".format(t_delta))\n\n    return results\n\n\ndef vpq_compute_single_core(gt_pred_set, categories, nframes=2):\n    OFFSET = 256 * 256 * 256\n    VOID = 255\n    vpq_stat = PQStat()\n\n    # Iterate over the video frames 0::T-λ\n    for idx in range(0, len(gt_pred_set)-nframes+1): \n        vid_pan_gt, vid_pan_pred = [], []\n        gt_segms_list, pred_segms_list = [], []\n\n        # Matching nframes-long tubes.\n        # Collect tube IoU, TP, FP, FN\n        for i, (gt_json, pred_json, gt_pan, pred_pan, gt_image_json) in enumerate(gt_pred_set[idx:idx+nframes]):\n            #### Step1. Collect frame-level pan_gt, pan_pred, etc.\n            gt_pan, pred_pan = np.uint32(gt_pan), np.uint32(pred_pan)\n            pan_gt = gt_pan[:, :, 0] + gt_pan[:, :, 1] * 256 + gt_pan[:, :, 2] * 256 * 256\n            pan_pred = pred_pan[:, :, 0] + pred_pan[:, :, 1] * 256 + pred_pan[:, :, 2] * 256 * 256\n            gt_segms = {}\n            for el in gt_json['segments_info']:\n                if el['id'] in gt_segms:\n                    gt_segms[el['id']]['area'] += el['area']\n                else:\n                    gt_segms[el['id']] = copy.deepcopy(el)\n            pred_segms = {}\n            for el in pred_json['segments_info']:\n                if el['id'] in pred_segms:\n                    pred_segms[el['id']]['area'] += el['area']\n                else:\n                    pred_segms[el['id']] = copy.deepcopy(el)\n            # predicted segments area calculation + prediction sanity checks\n            pred_labels_set = set(el['id'] for el in pred_json['segments_info'])\n            labels, labels_cnt = np.unique(pan_pred, return_counts=True)\n            for label, label_cnt in zip(labels, labels_cnt):\n                if label not in pred_segms:\n                    if label == VOID:\n                        continue\n                    raise KeyError('Segment with ID {} is presented in PNG and not presented in JSON.'.format(label))\n                pred_segms[label]['area'] = label_cnt\n                pred_labels_set.remove(label)\n                if pred_segms[label]['category_id'] not in categories:\n                    raise KeyError('Segment with ID {} has unknown category_id {}.'.format(label, pred_segms[label]['category_id']))\n            if len(pred_labels_set) != 0:\n                raise KeyError(\n                    'The following segment IDs {} are presented in JSON and not presented in PNG.'.format(list(pred_labels_set)))\n\n            vid_pan_gt.append(pan_gt)\n            vid_pan_pred.append(pan_pred)\n            gt_segms_list.append(gt_segms)\n            pred_segms_list.append(pred_segms)\n\n        #### Step 2. Concatenate the collected items -> tube-level. \n        vid_pan_gt = np.stack(vid_pan_gt) # [nf,H,W]\n        vid_pan_pred = np.stack(vid_pan_pred) # [nf,H,W]\n        vid_gt_segms, vid_pred_segms = {}, {}\n        for gt_segms, pred_segms in zip(gt_segms_list, pred_segms_list):\n            # aggregate into tube 'area'\n            for k in gt_segms.keys():\n                if not k in vid_gt_segms:\n                    vid_gt_segms[k] = gt_segms[k]\n                else:\n                    vid_gt_segms[k]['area'] += gt_segms[k]['area']\n            for k in pred_segms.keys():\n                if not k in vid_pred_segms:\n                    vid_pred_segms[k] = pred_segms[k]\n                else:\n                    vid_pred_segms[k]['area'] += pred_segms[k]['area']\n\n        #### Step3. Confusion matrix calculation\n        vid_pan_gt_pred = vid_pan_gt.astype(np.uint64) * OFFSET + vid_pan_pred.astype(np.uint64)\n        gt_pred_map = {}\n        labels, labels_cnt = np.unique(vid_pan_gt_pred, return_counts=True)\n        for label, intersection in zip(labels, labels_cnt):\n            gt_id = label // OFFSET\n            pred_id = label % OFFSET\n            gt_pred_map[(gt_id, pred_id)] = intersection\n\n        # count all matched pairs\n        gt_matched = set()\n        pred_matched = set()\n        tp = 0\n        fp = 0\n        fn = 0\n\n        #### Step4. Tube matching\n        for label_tuple, intersection in gt_pred_map.items():\n            gt_label, pred_label = label_tuple\n\n            if gt_label not in vid_gt_segms:\n                continue\n            if pred_label not in vid_pred_segms:\n                continue\n            if vid_gt_segms[gt_label]['iscrowd'] == 1:\n                continue\n            if vid_gt_segms[gt_label]['category_id'] != \\\n                    vid_pred_segms[pred_label]['category_id']:\n                continue\n\n            union = vid_pred_segms[pred_label]['area'] + vid_gt_segms[gt_label]['area'] - intersection - gt_pred_map.get(\n                (VOID, pred_label), 0)\n            iou = intersection / union\n            assert iou <= 1.0, 'INVALID IOU VALUE : %d'%(gt_label)\n            # count true positives\n            if iou > 0.5:\n                vpq_stat[vid_gt_segms[gt_label]['category_id']].tp += 1\n                vpq_stat[vid_gt_segms[gt_label]['category_id']].iou += iou\n                gt_matched.add(gt_label)\n                pred_matched.add(pred_label)\n                tp += 1\n\n        # count false negatives\n        crowd_labels_dict = {}\n        for gt_label, gt_info in vid_gt_segms.items():\n            if gt_label in gt_matched:\n                continue\n            # crowd segments are ignored\n            if gt_info['iscrowd'] == 1:\n                crowd_labels_dict[gt_info['category_id']] = gt_label\n                continue\n            vpq_stat[gt_info['category_id']].fn += 1\n            fn += 1\n\n        # count false positives\n        for pred_label, pred_info in vid_pred_segms.items():\n            if pred_label in pred_matched:\n                continue\n            # intersection of the segment with VOID\n            intersection = gt_pred_map.get((VOID, pred_label), 0)\n            # plus intersection with corresponding CROWD region if it exists\n            if pred_info['category_id'] in crowd_labels_dict:\n                intersection += gt_pred_map.get((crowd_labels_dict[pred_info['category_id']], pred_label), 0)\n            # predicted segment is ignored if more than half of the segment correspond to VOID and CROWD regions\n            if intersection / pred_info['area'] > 0.5:\n                continue\n            vpq_stat[pred_info['category_id']].fp += 1\n            fp += 1\n\n    return vpq_stat\n\ndef vpq_compute(gt_pred_split, categories, nframes, output_dir):\n    start_time = time.time()\n    vpq_stat = PQStat()\n    for idx, gt_pred_set in enumerate(gt_pred_split):\n        tmp = vpq_compute_single_core(gt_pred_set, categories, nframes=nframes)\n        vpq_stat += tmp\n\n    # hyperparameter: window size k\n    k = (nframes-1)*5\n    print('==> %d-frame vpq_stat:'%(k), time.time()-start_time, 'sec')\n    metrics = [(\"All\", None), (\"Things\", True), (\"Stuff\", False)]\n    results = {}\n    for name, isthing in metrics:\n        results[name], per_class_results = vpq_stat.pq_average(categories, isthing=isthing)\n        if name == 'All':\n            results['per_class'] = per_class_results\n\n    vpq_all = 100 * results['All']['pq']\n    vpq_thing = 100 * results['Things']['pq']\n    vpq_stuff = 100 * results['Stuff']['pq']\n\n    save_name = os.path.join(output_dir, 'vpq-%d.txt'%(k))\n    f = open(save_name, 'w') if save_name else None\n    f.write(\"================================================\\n\")\n    f.write(\"{:10s}| {:>5s}  {:>5s}  {:>5s} {:>5s}\".format(\"\", \"PQ\", \"SQ\", \"RQ\", \"N\\n\"))\n    f.write(\"-\" * (10 + 7 * 4)+'\\n')\n    for name, _isthing in metrics:\n        f.write(\"{:10s}| {:5.1f}  {:5.1f}  {:5.1f} {:5d}\\n\".format(name, 100 * results[name]['pq'], 100 * results[name]['sq'], 100 * results[name]['rq'], results[name]['n']))\n    f.write(\"{:4s}| {:>5s} {:>5s} {:>5s} {:>6s} {:>7s} {:>7s} {:>7s}\\n\".format(\"IDX\", \"PQ\", \"SQ\", \"RQ\", \"IoU\", \"TP\", \"FP\", \"FN\"))\n    for idx, result in results['per_class'].items():\n        f.write(\"{:4d} | {:5.1f} {:5.1f} {:5.1f} {:6.1f} {:7d} {:7d} {:7d}\\n\".format(idx, 100 * result['pq'], 100 * result['sq'], 100 * result['rq'], result['iou'], result['tp'], result['fp'], result['fn']))\n    if save_name:\n        f.close()\n\n    return vpq_all, vpq_thing, vpq_stuff\n\nif __name__ == \"__main__\":\n    parser = argparse.ArgumentParser()\n    parser.add_argument('--gt_json_file', type=str,\n                        help=\"JSON file with ground truth data\")\n    parser.add_argument('--pred_json_file', type=str,\n                        help=\"JSON file with predictions data\")\n    parser.add_argument('--gt_folder', type=str, default=None,\n                        help=\"Folder with ground turth COCO format segmentations. \\\n                              Default: X if the corresponding json file is X.json\")\n    parser.add_argument('--pred_folder', type=str, default=None,\n                        help=\"Folder with prediction COCO format segmentations. \\\n                              Default: X if the corresponding json file is X.json\")\n    args = parser.parse_args()\n    pq_compute(args.gt_json_file, args.pred_json_file, args.gt_folder, args.pred_folder)\n"
  },
  {
    "path": "VPS_Module/detectron2/evaluation/rotated_coco_evaluation.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport itertools\nimport json\nimport numpy as np\nimport os\nimport torch\nfrom pycocotools.cocoeval import COCOeval, maskUtils\n\nfrom detectron2.structures import BoxMode, RotatedBoxes, pairwise_iou_rotated\nfrom detectron2.utils.file_io import PathManager\n\nfrom .coco_evaluation import COCOEvaluator\n\n\nclass RotatedCOCOeval(COCOeval):\n    @staticmethod\n    def is_rotated(box_list):\n        if type(box_list) == np.ndarray:\n            return box_list.shape[1] == 5\n        elif type(box_list) == list:\n            if box_list == []:  # cannot decide the box_dim\n                return False\n            return np.all(\n                np.array(\n                    [\n                        (len(obj) == 5) and ((type(obj) == list) or (type(obj) == np.ndarray))\n                        for obj in box_list\n                    ]\n                )\n            )\n        return False\n\n    @staticmethod\n    def boxlist_to_tensor(boxlist, output_box_dim):\n        if type(boxlist) == np.ndarray:\n            box_tensor = torch.from_numpy(boxlist)\n        elif type(boxlist) == list:\n            if boxlist == []:\n                return torch.zeros((0, output_box_dim), dtype=torch.float32)\n            else:\n                box_tensor = torch.FloatTensor(boxlist)\n        else:\n            raise Exception(\"Unrecognized boxlist type\")\n\n        input_box_dim = box_tensor.shape[1]\n        if input_box_dim != output_box_dim:\n            if input_box_dim == 4 and output_box_dim == 5:\n                box_tensor = BoxMode.convert(box_tensor, BoxMode.XYWH_ABS, BoxMode.XYWHA_ABS)\n            else:\n                raise Exception(\n                    \"Unable to convert from {}-dim box to {}-dim box\".format(\n                        input_box_dim, output_box_dim\n                    )\n                )\n        return box_tensor\n\n    def compute_iou_dt_gt(self, dt, gt, is_crowd):\n        if self.is_rotated(dt) or self.is_rotated(gt):\n            # TODO: take is_crowd into consideration\n            assert all(c == 0 for c in is_crowd)\n            dt = RotatedBoxes(self.boxlist_to_tensor(dt, output_box_dim=5))\n            gt = RotatedBoxes(self.boxlist_to_tensor(gt, output_box_dim=5))\n            return pairwise_iou_rotated(dt, gt)\n        else:\n            # This is the same as the classical COCO evaluation\n            return maskUtils.iou(dt, gt, is_crowd)\n\n    def computeIoU(self, imgId, catId):\n        p = self.params\n        if p.useCats:\n            gt = self._gts[imgId, catId]\n            dt = self._dts[imgId, catId]\n        else:\n            gt = [_ for cId in p.catIds for _ in self._gts[imgId, cId]]\n            dt = [_ for cId in p.catIds for _ in self._dts[imgId, cId]]\n        if len(gt) == 0 and len(dt) == 0:\n            return []\n        inds = np.argsort([-d[\"score\"] for d in dt], kind=\"mergesort\")\n        dt = [dt[i] for i in inds]\n        if len(dt) > p.maxDets[-1]:\n            dt = dt[0 : p.maxDets[-1]]\n\n        assert p.iouType == \"bbox\", \"unsupported iouType for iou computation\"\n\n        g = [g[\"bbox\"] for g in gt]\n        d = [d[\"bbox\"] for d in dt]\n\n        # compute iou between each dt and gt region\n        iscrowd = [int(o[\"iscrowd\"]) for o in gt]\n\n        # Note: this function is copied from cocoeval.py in cocoapi\n        # and the major difference is here.\n        ious = self.compute_iou_dt_gt(d, g, iscrowd)\n        return ious\n\n\nclass RotatedCOCOEvaluator(COCOEvaluator):\n    \"\"\"\n    Evaluate object proposal/instance detection outputs using COCO-like metrics and APIs,\n    with rotated boxes support.\n    Note: this uses IOU only and does not consider angle differences.\n    \"\"\"\n\n    def process(self, inputs, outputs):\n        \"\"\"\n        Args:\n            inputs: the inputs to a COCO model (e.g., GeneralizedRCNN).\n                It is a list of dict. Each dict corresponds to an image and\n                contains keys like \"height\", \"width\", \"file_name\", \"image_id\".\n            outputs: the outputs of a COCO model. It is a list of dicts with key\n                \"instances\" that contains :class:`Instances`.\n        \"\"\"\n        for input, output in zip(inputs, outputs):\n            prediction = {\"image_id\": input[\"image_id\"]}\n\n            if \"instances\" in output:\n                instances = output[\"instances\"].to(self._cpu_device)\n\n                prediction[\"instances\"] = self.instances_to_json(instances, input[\"image_id\"])\n            if \"proposals\" in output:\n                prediction[\"proposals\"] = output[\"proposals\"].to(self._cpu_device)\n            self._predictions.append(prediction)\n\n    def instances_to_json(self, instances, img_id):\n        num_instance = len(instances)\n        if num_instance == 0:\n            return []\n\n        boxes = instances.pred_boxes.tensor.numpy()\n        if boxes.shape[1] == 4:\n            boxes = BoxMode.convert(boxes, BoxMode.XYXY_ABS, BoxMode.XYWH_ABS)\n        boxes = boxes.tolist()\n        scores = instances.scores.tolist()\n        classes = instances.pred_classes.tolist()\n\n        results = []\n        for k in range(num_instance):\n            result = {\n                \"image_id\": img_id,\n                \"category_id\": classes[k],\n                \"bbox\": boxes[k],\n                \"score\": scores[k],\n            }\n\n            results.append(result)\n        return results\n\n    def _eval_predictions(self, predictions, img_ids=None):  # img_ids: unused\n        \"\"\"\n        Evaluate predictions on the given tasks.\n        Fill self._results with the metrics of the tasks.\n        \"\"\"\n        self._logger.info(\"Preparing results for COCO format ...\")\n        coco_results = list(itertools.chain(*[x[\"instances\"] for x in predictions]))\n\n        # unmap the category ids for COCO\n        if hasattr(self._metadata, \"thing_dataset_id_to_contiguous_id\"):\n            reverse_id_mapping = {\n                v: k for k, v in self._metadata.thing_dataset_id_to_contiguous_id.items()\n            }\n            for result in coco_results:\n                result[\"category_id\"] = reverse_id_mapping[result[\"category_id\"]]\n\n        if self._output_dir:\n            file_path = os.path.join(self._output_dir, \"coco_instances_results.json\")\n            self._logger.info(\"Saving results to {}\".format(file_path))\n            with PathManager.open(file_path, \"w\") as f:\n                f.write(json.dumps(coco_results))\n                f.flush()\n\n        if not self._do_evaluation:\n            self._logger.info(\"Annotations are not available for evaluation.\")\n            return\n\n        self._logger.info(\"Evaluating predictions ...\")\n\n        assert self._tasks is None or set(self._tasks) == {\n            \"bbox\"\n        }, \"[RotatedCOCOEvaluator] Only bbox evaluation is supported\"\n        coco_eval = (\n            self._evaluate_predictions_on_coco(self._coco_api, coco_results)\n            if len(coco_results) > 0\n            else None  # cocoapi does not handle empty results very well\n        )\n\n        task = \"bbox\"\n        res = self._derive_coco_results(\n            coco_eval, task, class_names=self._metadata.get(\"thing_classes\")\n        )\n        self._results[task] = res\n\n    def _evaluate_predictions_on_coco(self, coco_gt, coco_results):\n        \"\"\"\n        Evaluate the coco results using COCOEval API.\n        \"\"\"\n        assert len(coco_results) > 0\n\n        coco_dt = coco_gt.loadRes(coco_results)\n\n        # Only bbox is supported for now\n        coco_eval = RotatedCOCOeval(coco_gt, coco_dt, iouType=\"bbox\")\n\n        coco_eval.evaluate()\n        coco_eval.accumulate()\n        coco_eval.summarize()\n\n        return coco_eval\n"
  },
  {
    "path": "VPS_Module/detectron2/evaluation/sem_seg_evaluation.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport itertools\nimport json\nimport logging\nimport numpy as np\nimport os\nfrom collections import OrderedDict\nimport PIL.Image as Image\nimport pycocotools.mask as mask_util\nimport torch\n\nfrom detectron2.data import DatasetCatalog, MetadataCatalog\nfrom detectron2.utils.comm import all_gather, is_main_process, synchronize\nfrom detectron2.utils.file_io import PathManager\n\nfrom .evaluator import DatasetEvaluator\n\n\nclass SemSegEvaluator(DatasetEvaluator):\n    \"\"\"\n    Evaluate semantic segmentation metrics.\n    \"\"\"\n\n    def __init__(\n        self,\n        dataset_name,\n        distributed=True,\n        output_dir=None,\n        *,\n        num_classes=None,\n        ignore_label=None,\n    ):\n        \"\"\"\n        Args:\n            dataset_name (str): name of the dataset to be evaluated.\n            distributed (bool): if True, will collect results from all ranks for evaluation.\n                Otherwise, will evaluate the results in the current process.\n            output_dir (str): an output directory to dump results.\n            num_classes, ignore_label: deprecated argument\n        \"\"\"\n        self._logger = logging.getLogger(__name__)\n        if num_classes is not None:\n            self._logger.warn(\n                \"SemSegEvaluator(num_classes) is deprecated! It should be obtained from metadata.\"\n            )\n        if ignore_label is not None:\n            self._logger.warn(\n                \"SemSegEvaluator(ignore_label) is deprecated! It should be obtained from metadata.\"\n            )\n        self._dataset_name = dataset_name\n        self._distributed = distributed\n        self._output_dir = output_dir\n\n        self._cpu_device = torch.device(\"cpu\")\n\n        self.input_file_to_gt_file = {\n            dataset_record[\"file_name\"]: dataset_record[\"sem_seg_file_name\"]\n            for dataset_record in DatasetCatalog.get(dataset_name)\n        }\n\n        meta = MetadataCatalog.get(dataset_name)\n        # Dict that maps contiguous training ids to COCO category ids\n        try:\n            c2d = meta.stuff_dataset_id_to_contiguous_id\n            self._contiguous_id_to_dataset_id = {v: k for k, v in c2d.items()}\n        except AttributeError:\n            self._contiguous_id_to_dataset_id = None\n        self._class_names = meta.stuff_classes\n        self._num_classes = len(meta.stuff_classes)\n        if num_classes is not None:\n            assert self._num_classes == num_classes, f\"{self._num_classes} != {num_classes}\"\n        self._ignore_label = ignore_label if ignore_label is not None else meta.ignore_label\n\n    def reset(self):\n        self._conf_matrix = np.zeros((self._num_classes + 1, self._num_classes + 1), dtype=np.int64)\n        self._predictions = []\n\n    def process(self, inputs, outputs):\n        \"\"\"\n        Args:\n            inputs: the inputs to a model.\n                It is a list of dicts. Each dict corresponds to an image and\n                contains keys like \"height\", \"width\", \"file_name\".\n            outputs: the outputs of a model. It is either list of semantic segmentation predictions\n                (Tensor [H, W]) or list of dicts with key \"sem_seg\" that contains semantic\n                segmentation prediction in the same format.\n        \"\"\"\n        for input, output in zip(inputs, outputs):\n            output = output[\"sem_seg\"].argmax(dim=0).to(self._cpu_device)\n            pred = np.array(output, dtype=np.int)\n            with PathManager.open(self.input_file_to_gt_file[input[\"file_name\"]], \"rb\") as f:\n                gt = np.array(Image.open(f), dtype=np.int)\n\n            gt[gt == self._ignore_label] = self._num_classes\n\n            self._conf_matrix += np.bincount(\n                (self._num_classes + 1) * pred.reshape(-1) + gt.reshape(-1),\n                minlength=self._conf_matrix.size,\n            ).reshape(self._conf_matrix.shape)\n\n            self._predictions.extend(self.encode_json_sem_seg(pred, input[\"file_name\"]))\n\n    def evaluate(self):\n        \"\"\"\n        Evaluates standard semantic segmentation metrics (http://cocodataset.org/#stuff-eval):\n\n        * Mean intersection-over-union averaged across classes (mIoU)\n        * Frequency Weighted IoU (fwIoU)\n        * Mean pixel accuracy averaged across classes (mACC)\n        * Pixel Accuracy (pACC)\n        \"\"\"\n        if self._distributed:\n            synchronize()\n            conf_matrix_list = all_gather(self._conf_matrix)\n            self._predictions = all_gather(self._predictions)\n            self._predictions = list(itertools.chain(*self._predictions))\n            if not is_main_process():\n                return\n\n            self._conf_matrix = np.zeros_like(self._conf_matrix)\n            for conf_matrix in conf_matrix_list:\n                self._conf_matrix += conf_matrix\n\n        if self._output_dir:\n            PathManager.mkdirs(self._output_dir)\n            file_path = os.path.join(self._output_dir, \"sem_seg_predictions.json\")\n            with PathManager.open(file_path, \"w\") as f:\n                f.write(json.dumps(self._predictions))\n\n        acc = np.full(self._num_classes, np.nan, dtype=np.float)\n        iou = np.full(self._num_classes, np.nan, dtype=np.float)\n        tp = self._conf_matrix.diagonal()[:-1].astype(np.float)\n        pos_gt = np.sum(self._conf_matrix[:-1, :-1], axis=0).astype(np.float)\n        class_weights = pos_gt / np.sum(pos_gt)\n        pos_pred = np.sum(self._conf_matrix[:-1, :-1], axis=1).astype(np.float)\n        acc_valid = pos_gt > 0\n        acc[acc_valid] = tp[acc_valid] / pos_gt[acc_valid]\n        iou_valid = (pos_gt + pos_pred) > 0\n        union = pos_gt + pos_pred - tp\n        iou[acc_valid] = tp[acc_valid] / union[acc_valid]\n        macc = np.sum(acc[acc_valid]) / np.sum(acc_valid)\n        miou = np.sum(iou[acc_valid]) / np.sum(iou_valid)\n        fiou = np.sum(iou[acc_valid] * class_weights[acc_valid])\n        pacc = np.sum(tp) / np.sum(pos_gt)\n\n        res = {}\n        res[\"mIoU\"] = 100 * miou\n        res[\"fwIoU\"] = 100 * fiou\n        for i, name in enumerate(self._class_names):\n            res[\"IoU-{}\".format(name)] = 100 * iou[i]\n        res[\"mACC\"] = 100 * macc\n        res[\"pACC\"] = 100 * pacc\n        for i, name in enumerate(self._class_names):\n            res[\"ACC-{}\".format(name)] = 100 * acc[i]\n\n        if self._output_dir:\n            file_path = os.path.join(self._output_dir, \"sem_seg_evaluation.pth\")\n            with PathManager.open(file_path, \"wb\") as f:\n                torch.save(res, f)\n        results = OrderedDict({\"sem_seg\": res})\n        self._logger.info(results)\n        return results\n\n    def encode_json_sem_seg(self, sem_seg, input_file_name):\n        \"\"\"\n        Convert semantic segmentation to COCO stuff format with segments encoded as RLEs.\n        See http://cocodataset.org/#format-results\n        \"\"\"\n        json_list = []\n        for label in np.unique(sem_seg):\n            if self._contiguous_id_to_dataset_id is not None:\n                assert (\n                    label in self._contiguous_id_to_dataset_id\n                ), \"Label {} is not in the metadata info for {}\".format(label, self._dataset_name)\n                dataset_id = self._contiguous_id_to_dataset_id[label]\n            else:\n                dataset_id = int(label)\n            mask = (sem_seg == label).astype(np.uint8)\n            mask_rle = mask_util.encode(np.array(mask[:, :, None], order=\"F\"))[0]\n            mask_rle[\"counts\"] = mask_rle[\"counts\"].decode(\"utf-8\")\n            json_list.append(\n                {\"file_name\": input_file_name, \"category_id\": dataset_id, \"segmentation\": mask_rle}\n            )\n        return json_list\n"
  },
  {
    "path": "VPS_Module/detectron2/evaluation/testing.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport logging\nimport numpy as np\nimport pprint\nimport sys\nfrom collections.abc import Mapping\n\n\ndef print_csv_format(results):\n    \"\"\"\n    Print main metrics in a format similar to Detectron,\n    so that they are easy to copypaste into a spreadsheet.\n\n    Args:\n        results (OrderedDict[dict]): task_name -> {metric -> score}\n            unordered dict can also be printed, but in arbitrary order\n    \"\"\"\n    assert isinstance(results, Mapping) or not len(results), results\n    logger = logging.getLogger(__name__)\n    for task, res in results.items():\n        if isinstance(res, Mapping):\n            # Don't print \"AP-category\" metrics since they are usually not tracked.\n            important_res = [(k, v) for k, v in res.items() if \"-\" not in k]\n            logger.info(\"copypaste: Task: {}\".format(task))\n            logger.info(\"copypaste: \" + \",\".join([k[0] for k in important_res]))\n            logger.info(\"copypaste: \" + \",\".join([\"{0:.4f}\".format(k[1]) for k in important_res]))\n        else:\n            logger.info(f\"copypaste: {task}={res}\")\n\n\ndef verify_results(cfg, results):\n    \"\"\"\n    Args:\n        results (OrderedDict[dict]): task_name -> {metric -> score}\n\n    Returns:\n        bool: whether the verification succeeds or not\n    \"\"\"\n    expected_results = cfg.TEST.EXPECTED_RESULTS\n    if not len(expected_results):\n        return True\n\n    ok = True\n    for task, metric, expected, tolerance in expected_results:\n        actual = results[task].get(metric, None)\n        if actual is None:\n            ok = False\n            continue\n        if not np.isfinite(actual):\n            ok = False\n            continue\n        diff = abs(actual - expected)\n        if diff > tolerance:\n            ok = False\n\n    logger = logging.getLogger(__name__)\n    if not ok:\n        logger.error(\"Result verification failed!\")\n        logger.error(\"Expected Results: \" + str(expected_results))\n        logger.error(\"Actual Results: \" + pprint.pformat(results))\n\n        sys.exit(1)\n    else:\n        logger.info(\"Results verification passed.\")\n    return ok\n\n\ndef flatten_results_dict(results):\n    \"\"\"\n    Expand a hierarchical dict of scalars into a flat dict of scalars.\n    If results[k1][k2][k3] = v, the returned dict will have the entry\n    {\"k1/k2/k3\": v}.\n\n    Args:\n        results (dict):\n    \"\"\"\n    r = {}\n    for k, v in results.items():\n        if isinstance(v, Mapping):\n            v = flatten_results_dict(v)\n            for kk, vv in v.items():\n                r[k + \"/\" + kk] = vv\n        else:\n            r[k] = v\n    return r\n"
  },
  {
    "path": "VPS_Module/detectron2/export/README.md",
    "content": "\nThis directory contains code to prepare a detectron2 model for deployment.\nCurrently it supports exporting a detectron2 model to Caffe2 format through ONNX.\n\nPlease see [documentation](https://detectron2.readthedocs.io/tutorials/deployment.html) for its usage.\n\n\n### Acknowledgements\n\nThanks to Mobile Vision team at Facebook for developing the Caffe2 conversion tools.\n\nThanks to Computing Platform Department - PAI team at Alibaba Group (@bddpqq, @chenbohua3) who\nhelp export Detectron2 models to TorchScript.\n"
  },
  {
    "path": "VPS_Module/detectron2/export/__init__.py",
    "content": "# -*- coding: utf-8 -*-\n\ntry:\n    from caffe2.proto import caffe2_pb2 as _tmp\n\n    # caffe2 is optional\nexcept ImportError:\n    pass\nelse:\n    from .api import *\n\nfrom .flatten import TracingAdapter\nfrom .torchscript import scripting_with_instances, dump_torchscript_IR\n\n__all__ = [k for k in globals().keys() if not k.startswith(\"_\")]\n"
  },
  {
    "path": "VPS_Module/detectron2/export/api.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport copy\nimport logging\nimport os\nimport torch\nfrom caffe2.proto import caffe2_pb2\nfrom torch import nn\n\nfrom detectron2.config import CfgNode\nfrom detectron2.utils.file_io import PathManager\n\nfrom .caffe2_inference import ProtobufDetectionModel\nfrom .caffe2_modeling import META_ARCH_CAFFE2_EXPORT_TYPE_MAP, convert_batched_inputs_to_c2_format\nfrom .shared import get_pb_arg_vali, get_pb_arg_vals, save_graph\n\n__all__ = [\n    \"add_export_config\",\n    \"Caffe2Model\",\n    \"Caffe2Tracer\",\n]\n\n\ndef add_export_config(cfg):\n    return cfg\n\n\nclass Caffe2Tracer:\n    \"\"\"\n    Make a detectron2 model traceable with Caffe2 operators.\n    This class creates a traceable version of a detectron2 model which:\n\n    1. Rewrite parts of the model using ops in Caffe2. Note that some ops do\n       not have GPU implementation in Caffe2.\n    2. Remove post-processing and only produce raw layer outputs\n\n    After making a traceable model, the class provide methods to export such a\n    model to different deployment formats.\n    Exported graph produced by this class take two input tensors:\n\n    1. (1, C, H, W) float \"data\" which is an image (usually in [0, 255]).\n       (H, W) often has to be padded to multiple of 32 (depend on the model\n       architecture).\n    2. 1x3 float \"im_info\", each row of which is (height, width, 1.0).\n       Height and width are true image shapes before padding.\n\n    The class currently only supports models using builtin meta architectures.\n    Batch inference is not supported, and contributions are welcome.\n    \"\"\"\n\n    def __init__(self, cfg: CfgNode, model: nn.Module, inputs):\n        \"\"\"\n        Args:\n            cfg (CfgNode): a detectron2 config used to construct caffe2-compatible model.\n            model (nn.Module): An original pytorch model. Must be among a few official models\n                in detectron2 that can be converted to become caffe2-compatible automatically.\n                Weights have to be already loaded to this model.\n            inputs: sample inputs that the given model takes for inference.\n                Will be used to trace the model. For most models, random inputs with\n                no detected objects will not work as they lead to wrong traces.\n        \"\"\"\n        assert isinstance(cfg, CfgNode), cfg\n        assert isinstance(model, torch.nn.Module), type(model)\n\n        # TODO make it support custom models, by passing in c2 model directly\n        C2MetaArch = META_ARCH_CAFFE2_EXPORT_TYPE_MAP[cfg.MODEL.META_ARCHITECTURE]\n        self.traceable_model = C2MetaArch(cfg, copy.deepcopy(model))\n        self.inputs = inputs\n        self.traceable_inputs = self.traceable_model.get_caffe2_inputs(inputs)\n\n    def export_caffe2(self):\n        \"\"\"\n        Export the model to Caffe2's protobuf format.\n        The returned object can be saved with its :meth:`.save_protobuf()` method.\n        The result can be loaded and executed using Caffe2 runtime.\n\n        Returns:\n            :class:`Caffe2Model`\n        \"\"\"\n        from .caffe2_export import export_caffe2_detection_model\n\n        predict_net, init_net = export_caffe2_detection_model(\n            self.traceable_model, self.traceable_inputs\n        )\n        return Caffe2Model(predict_net, init_net)\n\n    def export_onnx(self):\n        \"\"\"\n        Export the model to ONNX format.\n        Note that the exported model contains custom ops only available in caffe2, therefore it\n        cannot be directly executed by other runtime (such as onnxruntime or TensorRT).\n        Post-processing or transformation passes may be applied on the model to accommodate\n        different runtimes, but we currently do not provide support for them.\n\n        Returns:\n            onnx.ModelProto: an onnx model.\n        \"\"\"\n        from .caffe2_export import export_onnx_model as export_onnx_model_impl\n\n        return export_onnx_model_impl(self.traceable_model, (self.traceable_inputs,))\n\n    def export_torchscript(self):\n        \"\"\"\n        Export the model to a ``torch.jit.TracedModule`` by tracing.\n        The returned object can be saved to a file by ``.save()``.\n\n        Returns:\n            torch.jit.TracedModule: a torch TracedModule\n        \"\"\"\n        logger = logging.getLogger(__name__)\n        logger.info(\"Tracing the model with torch.jit.trace ...\")\n        with torch.no_grad():\n            return torch.jit.trace(self.traceable_model, (self.traceable_inputs,))\n\n\nclass Caffe2Model(nn.Module):\n    \"\"\"\n    A wrapper around the traced model in Caffe2's protobuf format.\n    The exported graph has different inputs/outputs from the original Pytorch\n    model, as explained in :class:`Caffe2Tracer`. This class wraps around the\n    exported graph to simulate the same interface as the original Pytorch model.\n    It also provides functions to save/load models in Caffe2's format.'\n\n    Examples:\n    ::\n        c2_model = Caffe2Tracer(cfg, torch_model, inputs).export_caffe2()\n        inputs = [{\"image\": img_tensor_CHW}]\n        outputs = c2_model(inputs)\n        orig_outputs = torch_model(inputs)\n    \"\"\"\n\n    def __init__(self, predict_net, init_net):\n        super().__init__()\n        self.eval()  # always in eval mode\n        self._predict_net = predict_net\n        self._init_net = init_net\n        self._predictor = None\n\n    __init__.__HIDE_SPHINX_DOC__ = True\n\n    @property\n    def predict_net(self):\n        \"\"\"\n        caffe2.core.Net: the underlying caffe2 predict net\n        \"\"\"\n        return self._predict_net\n\n    @property\n    def init_net(self):\n        \"\"\"\n        caffe2.core.Net: the underlying caffe2 init net\n        \"\"\"\n        return self._init_net\n\n    def save_protobuf(self, output_dir):\n        \"\"\"\n        Save the model as caffe2's protobuf format.\n        It saves the following files:\n\n            * \"model.pb\": definition of the graph. Can be visualized with\n              tools like `netron <https://github.com/lutzroeder/netron>`_.\n            * \"model_init.pb\": model parameters\n            * \"model.pbtxt\": human-readable definition of the graph. Not\n              needed for deployment.\n\n        Args:\n            output_dir (str): the output directory to save protobuf files.\n        \"\"\"\n        logger = logging.getLogger(__name__)\n        logger.info(\"Saving model to {} ...\".format(output_dir))\n        if not PathManager.exists(output_dir):\n            PathManager.mkdirs(output_dir)\n\n        with PathManager.open(os.path.join(output_dir, \"model.pb\"), \"wb\") as f:\n            f.write(self._predict_net.SerializeToString())\n        with PathManager.open(os.path.join(output_dir, \"model.pbtxt\"), \"w\") as f:\n            f.write(str(self._predict_net))\n        with PathManager.open(os.path.join(output_dir, \"model_init.pb\"), \"wb\") as f:\n            f.write(self._init_net.SerializeToString())\n\n    def save_graph(self, output_file, inputs=None):\n        \"\"\"\n        Save the graph as SVG format.\n\n        Args:\n            output_file (str): a SVG file\n            inputs: optional inputs given to the model.\n                If given, the inputs will be used to run the graph to record\n                shape of every tensor. The shape information will be\n                saved together with the graph.\n        \"\"\"\n        from .caffe2_export import run_and_save_graph\n\n        if inputs is None:\n            save_graph(self._predict_net, output_file, op_only=False)\n        else:\n            size_divisibility = get_pb_arg_vali(self._predict_net, \"size_divisibility\", 0)\n            device = get_pb_arg_vals(self._predict_net, \"device\", b\"cpu\").decode(\"ascii\")\n            inputs = convert_batched_inputs_to_c2_format(inputs, size_divisibility, device)\n            inputs = [x.cpu().numpy() for x in inputs]\n            run_and_save_graph(self._predict_net, self._init_net, inputs, output_file)\n\n    @staticmethod\n    def load_protobuf(dir):\n        \"\"\"\n        Args:\n            dir (str): a directory used to save Caffe2Model with\n                :meth:`save_protobuf`.\n                The files \"model.pb\" and \"model_init.pb\" are needed.\n\n        Returns:\n            Caffe2Model: the caffe2 model loaded from this directory.\n        \"\"\"\n        predict_net = caffe2_pb2.NetDef()\n        with PathManager.open(os.path.join(dir, \"model.pb\"), \"rb\") as f:\n            predict_net.ParseFromString(f.read())\n\n        init_net = caffe2_pb2.NetDef()\n        with PathManager.open(os.path.join(dir, \"model_init.pb\"), \"rb\") as f:\n            init_net.ParseFromString(f.read())\n\n        return Caffe2Model(predict_net, init_net)\n\n    def __call__(self, inputs):\n        \"\"\"\n        An interface that wraps around a Caffe2 model and mimics detectron2's models'\n        input/output format. See details about the format at :doc:`/tutorials/models`.\n        This is used to compare the outputs of caffe2 model with its original torch model.\n\n        Due to the extra conversion between Pytorch/Caffe2, this method is not meant for\n        benchmark. Because of the conversion, this method also has dependency\n        on detectron2 in order to convert to detectron2's output format.\n        \"\"\"\n        if self._predictor is None:\n            self._predictor = ProtobufDetectionModel(self._predict_net, self._init_net)\n        return self._predictor(inputs)\n"
  },
  {
    "path": "VPS_Module/detectron2/export/c10.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport math\nimport torch\nimport torch.nn.functional as F\n\nfrom detectron2.layers import cat\nfrom detectron2.layers.roi_align_rotated import ROIAlignRotated\nfrom detectron2.modeling import poolers\nfrom detectron2.modeling.proposal_generator import rpn\nfrom detectron2.modeling.roi_heads.mask_head import mask_rcnn_inference\nfrom detectron2.structures import Boxes, ImageList, Instances, Keypoints\n\nfrom .shared import alias, to_device\n\n\n\"\"\"\nThis file contains caffe2-compatible implementation of several detectron2 components.\n\"\"\"\n\n\nclass Caffe2Boxes(Boxes):\n    \"\"\"\n    Representing a list of detectron2.structures.Boxes from minibatch, each box\n    is represented by a 5d vector (batch index + 4 coordinates), or a 6d vector\n    (batch index + 5 coordinates) for RotatedBoxes.\n    \"\"\"\n\n    def __init__(self, tensor):\n        assert isinstance(tensor, torch.Tensor)\n        assert tensor.dim() == 2 and tensor.size(-1) in [4, 5, 6], tensor.size()\n        # TODO: make tensor immutable when dim is Nx5 for Boxes,\n        # and Nx6 for RotatedBoxes?\n        self.tensor = tensor\n\n\n# TODO clean up this class, maybe just extend Instances\nclass InstancesList(object):\n    \"\"\"\n    Tensor representation of a list of Instances object for a batch of images.\n\n    When dealing with a batch of images with Caffe2 ops, a list of bboxes\n    (instances) are usually represented by single Tensor with size\n    (sigma(Ni), 5) or (sigma(Ni), 4) plus a batch split Tensor. This class is\n    for providing common functions to convert between these two representations.\n    \"\"\"\n\n    def __init__(self, im_info, indices, extra_fields=None):\n        # [N, 3] -> (H, W, Scale)\n        self.im_info = im_info\n        # [N,] -> indice of batch to which the instance belongs\n        self.indices = indices\n        # [N, ...]\n        self.batch_extra_fields = extra_fields or {}\n\n        self.image_size = self.im_info\n\n    def get_fields(self):\n        \"\"\"like `get_fields` in the Instances object,\n        but return each field in tensor representations\"\"\"\n        ret = {}\n        for k, v in self.batch_extra_fields.items():\n            # if isinstance(v, torch.Tensor):\n            #     tensor_rep = v\n            # elif isinstance(v, (Boxes, Keypoints)):\n            #     tensor_rep = v.tensor\n            # else:\n            #     raise ValueError(\"Can't find tensor representation for: {}\".format())\n            ret[k] = v\n        return ret\n\n    def has(self, name):\n        return name in self.batch_extra_fields\n\n    def set(self, name, value):\n        data_len = len(value)\n        if len(self.batch_extra_fields):\n            assert (\n                len(self) == data_len\n            ), \"Adding a field of length {} to a Instances of length {}\".format(data_len, len(self))\n        self.batch_extra_fields[name] = value\n\n    def __setattr__(self, name, val):\n        if name in [\"im_info\", \"indices\", \"batch_extra_fields\", \"image_size\"]:\n            super().__setattr__(name, val)\n        else:\n            self.set(name, val)\n\n    def __getattr__(self, name):\n        if name not in self.batch_extra_fields:\n            raise AttributeError(\"Cannot find field '{}' in the given Instances!\".format(name))\n        return self.batch_extra_fields[name]\n\n    def __len__(self):\n        return len(self.indices)\n\n    def flatten(self):\n        ret = []\n        for _, v in self.batch_extra_fields.items():\n            if isinstance(v, (Boxes, Keypoints)):\n                ret.append(v.tensor)\n            else:\n                ret.append(v)\n        return ret\n\n    @staticmethod\n    def to_d2_instances_list(instances_list):\n        \"\"\"\n        Convert InstancesList to List[Instances]. The input `instances_list` can\n        also be a List[Instances], in this case this method is a non-op.\n        \"\"\"\n        if not isinstance(instances_list, InstancesList):\n            assert all(isinstance(x, Instances) for x in instances_list)\n            return instances_list\n\n        ret = []\n        for i, info in enumerate(instances_list.im_info):\n            instances = Instances(torch.Size([int(info[0].item()), int(info[1].item())]))\n\n            ids = instances_list.indices == i\n            for k, v in instances_list.batch_extra_fields.items():\n                if isinstance(v, torch.Tensor):\n                    instances.set(k, v[ids])\n                    continue\n                elif isinstance(v, Boxes):\n                    instances.set(k, v[ids, -4:])\n                    continue\n\n                target_type, tensor_source = v\n                assert isinstance(tensor_source, torch.Tensor)\n                assert tensor_source.shape[0] == instances_list.indices.shape[0]\n                tensor_source = tensor_source[ids]\n\n                if issubclass(target_type, Boxes):\n                    instances.set(k, Boxes(tensor_source[:, -4:]))\n                elif issubclass(target_type, Keypoints):\n                    instances.set(k, Keypoints(tensor_source))\n                elif issubclass(target_type, torch.Tensor):\n                    instances.set(k, tensor_source)\n                else:\n                    raise ValueError(\"Can't handle targe type: {}\".format(target_type))\n\n            ret.append(instances)\n        return ret\n\n\nclass Caffe2Compatible(object):\n    \"\"\"\n    A model can inherit this class to indicate that it can be traced and deployed with caffe2.\n    \"\"\"\n\n    def _get_tensor_mode(self):\n        return self._tensor_mode\n\n    def _set_tensor_mode(self, v):\n        self._tensor_mode = v\n\n    tensor_mode = property(_get_tensor_mode, _set_tensor_mode)\n    \"\"\"\n    If true, the model expects C2-style tensor only inputs/outputs format.\n    \"\"\"\n\n\nclass Caffe2RPN(Caffe2Compatible, rpn.RPN):\n    def _generate_proposals(\n        self, images, objectness_logits_pred, anchor_deltas_pred, gt_instances=None\n    ):\n        assert isinstance(images, ImageList)\n        if self.tensor_mode:\n            im_info = images.image_sizes\n        else:\n            im_info = torch.tensor([[im_sz[0], im_sz[1], 1.0] for im_sz in images.image_sizes]).to(\n                images.tensor.device\n            )\n        assert isinstance(im_info, torch.Tensor)\n\n        rpn_rois_list = []\n        rpn_roi_probs_list = []\n        for scores, bbox_deltas, cell_anchors_tensor, feat_stride in zip(\n            objectness_logits_pred,\n            anchor_deltas_pred,\n            iter(self.anchor_generator.cell_anchors),\n            self.anchor_generator.strides,\n        ):\n            scores = scores.detach()\n            bbox_deltas = bbox_deltas.detach()\n\n            rpn_rois, rpn_roi_probs = torch.ops._caffe2.GenerateProposals(\n                scores,\n                bbox_deltas,\n                im_info,\n                cell_anchors_tensor,\n                spatial_scale=1.0 / feat_stride,\n                pre_nms_topN=self.pre_nms_topk[self.training],\n                post_nms_topN=self.post_nms_topk[self.training],\n                nms_thresh=self.nms_thresh,\n                min_size=self.min_box_size,\n                # correct_transform_coords=True,  # deprecated argument\n                angle_bound_on=True,  # Default\n                angle_bound_lo=-180,\n                angle_bound_hi=180,\n                clip_angle_thresh=1.0,  # Default\n                legacy_plus_one=False,\n            )\n            rpn_rois_list.append(rpn_rois)\n            rpn_roi_probs_list.append(rpn_roi_probs)\n\n        # For FPN in D2, in RPN all proposals from different levels are concated\n        # together, ranked and picked by top post_nms_topk. Then in ROIPooler\n        # it calculates level_assignments and calls the RoIAlign from\n        # the corresponding level.\n\n        if len(objectness_logits_pred) == 1:\n            rpn_rois = rpn_rois_list[0]\n            rpn_roi_probs = rpn_roi_probs_list[0]\n        else:\n            assert len(rpn_rois_list) == len(rpn_roi_probs_list)\n            rpn_post_nms_topN = self.post_nms_topk[self.training]\n\n            device = rpn_rois_list[0].device\n            input_list = [to_device(x, \"cpu\") for x in (rpn_rois_list + rpn_roi_probs_list)]\n\n            # TODO remove this after confirming rpn_max_level/rpn_min_level\n            # is not needed in CollectRpnProposals.\n            feature_strides = list(self.anchor_generator.strides)\n            rpn_min_level = int(math.log2(feature_strides[0]))\n            rpn_max_level = int(math.log2(feature_strides[-1]))\n            assert (rpn_max_level - rpn_min_level + 1) == len(\n                rpn_rois_list\n            ), \"CollectRpnProposals requires continuous levels\"\n\n            rpn_rois = torch.ops._caffe2.CollectRpnProposals(\n                input_list,\n                # NOTE: in current implementation, rpn_max_level and rpn_min_level\n                # are not needed, only the subtraction of two matters and it\n                # can be infer from the number of inputs. Keep them now for\n                # consistency.\n                rpn_max_level=2 + len(rpn_rois_list) - 1,\n                rpn_min_level=2,\n                rpn_post_nms_topN=rpn_post_nms_topN,\n            )\n            rpn_rois = to_device(rpn_rois, device)\n            rpn_roi_probs = []\n\n        proposals = self.c2_postprocess(im_info, rpn_rois, rpn_roi_probs, self.tensor_mode)\n        return proposals, {}\n\n    def forward(self, images, features, gt_instances=None):\n        assert not self.training\n        features = [features[f] for f in self.in_features]\n        objectness_logits_pred, anchor_deltas_pred = self.rpn_head(features)\n        return self._generate_proposals(\n            images,\n            objectness_logits_pred,\n            anchor_deltas_pred,\n            gt_instances,\n        )\n\n    @staticmethod\n    def c2_postprocess(im_info, rpn_rois, rpn_roi_probs, tensor_mode):\n        proposals = InstancesList(\n            im_info=im_info,\n            indices=rpn_rois[:, 0],\n            extra_fields={\n                \"proposal_boxes\": Caffe2Boxes(rpn_rois),\n                \"objectness_logits\": (torch.Tensor, rpn_roi_probs),\n            },\n        )\n        if not tensor_mode:\n            proposals = InstancesList.to_d2_instances_list(proposals)\n        else:\n            proposals = [proposals]\n        return proposals\n\n\nclass Caffe2ROIPooler(Caffe2Compatible, poolers.ROIPooler):\n    @staticmethod\n    def c2_preprocess(box_lists):\n        assert all(isinstance(x, Boxes) for x in box_lists)\n        if all(isinstance(x, Caffe2Boxes) for x in box_lists):\n            # input is pure-tensor based\n            assert len(box_lists) == 1\n            pooler_fmt_boxes = box_lists[0].tensor\n        else:\n            pooler_fmt_boxes = poolers.convert_boxes_to_pooler_format(box_lists)\n        return pooler_fmt_boxes\n\n    def forward(self, x, box_lists):\n        assert not self.training\n\n        pooler_fmt_boxes = self.c2_preprocess(box_lists)\n        num_level_assignments = len(self.level_poolers)\n\n        if num_level_assignments == 1:\n            if isinstance(self.level_poolers[0], ROIAlignRotated):\n                c2_roi_align = torch.ops._caffe2.RoIAlignRotated\n                aligned = True\n            else:\n                c2_roi_align = torch.ops._caffe2.RoIAlign\n                aligned = self.level_poolers[0].aligned\n\n            x0 = x[0]\n            if x0.is_quantized:\n                x0 = x0.dequantize()\n\n            out = c2_roi_align(\n                x0,\n                pooler_fmt_boxes,\n                order=\"NCHW\",\n                spatial_scale=float(self.level_poolers[0].spatial_scale),\n                pooled_h=int(self.output_size[0]),\n                pooled_w=int(self.output_size[1]),\n                sampling_ratio=int(self.level_poolers[0].sampling_ratio),\n                aligned=aligned,\n            )\n            return out\n\n        device = pooler_fmt_boxes.device\n        assert (\n            self.max_level - self.min_level + 1 == 4\n        ), \"Currently DistributeFpnProposals only support 4 levels\"\n        fpn_outputs = torch.ops._caffe2.DistributeFpnProposals(\n            to_device(pooler_fmt_boxes, \"cpu\"),\n            roi_canonical_scale=self.canonical_box_size,\n            roi_canonical_level=self.canonical_level,\n            roi_max_level=self.max_level,\n            roi_min_level=self.min_level,\n            legacy_plus_one=False,\n        )\n        fpn_outputs = [to_device(x, device) for x in fpn_outputs]\n\n        rois_fpn_list = fpn_outputs[:-1]\n        rois_idx_restore_int32 = fpn_outputs[-1]\n\n        roi_feat_fpn_list = []\n        for roi_fpn, x_level, pooler in zip(rois_fpn_list, x, self.level_poolers):\n            if isinstance(pooler, ROIAlignRotated):\n                c2_roi_align = torch.ops._caffe2.RoIAlignRotated\n                aligned = True\n            else:\n                c2_roi_align = torch.ops._caffe2.RoIAlign\n                aligned = bool(pooler.aligned)\n\n            if x_level.is_quantized:\n                x_level = x_level.dequantize()\n\n            roi_feat_fpn = c2_roi_align(\n                x_level,\n                roi_fpn,\n                order=\"NCHW\",\n                spatial_scale=float(pooler.spatial_scale),\n                pooled_h=int(self.output_size[0]),\n                pooled_w=int(self.output_size[1]),\n                sampling_ratio=int(pooler.sampling_ratio),\n                aligned=aligned,\n            )\n            roi_feat_fpn_list.append(roi_feat_fpn)\n\n        roi_feat_shuffled = cat(roi_feat_fpn_list, dim=0)\n        assert roi_feat_shuffled.numel() > 0 and rois_idx_restore_int32.numel() > 0, (\n            \"Caffe2 export requires tracing with a model checkpoint + input that can produce valid\"\n            \" detections. But no detections were obtained with the given checkpoint and input!\"\n        )\n        roi_feat = torch.ops._caffe2.BatchPermutation(roi_feat_shuffled, rois_idx_restore_int32)\n        return roi_feat\n\n\nclass Caffe2FastRCNNOutputsInference:\n    def __init__(self, tensor_mode):\n        self.tensor_mode = tensor_mode  # whether the output is caffe2 tensor mode\n\n    def __call__(self, box_predictor, predictions, proposals):\n        \"\"\"equivalent to FastRCNNOutputLayers.inference\"\"\"\n        num_classes = box_predictor.num_classes\n        score_thresh = box_predictor.test_score_thresh\n        nms_thresh = box_predictor.test_nms_thresh\n        topk_per_image = box_predictor.test_topk_per_image\n        is_rotated = len(box_predictor.box2box_transform.weights) == 5\n\n        if is_rotated:\n            box_dim = 5\n            assert box_predictor.box2box_transform.weights[4] == 1, (\n                \"The weights for Rotated BBoxTransform in C2 have only 4 dimensions,\"\n                + \" thus enforcing the angle weight to be 1 for now\"\n            )\n            box2box_transform_weights = box_predictor.box2box_transform.weights[:4]\n        else:\n            box_dim = 4\n            box2box_transform_weights = box_predictor.box2box_transform.weights\n\n        class_logits, box_regression = predictions\n        if num_classes + 1 == class_logits.shape[1]:\n            class_prob = F.softmax(class_logits, -1)\n        else:\n            assert num_classes == class_logits.shape[1]\n            class_prob = F.sigmoid(class_logits)\n            # BoxWithNMSLimit will infer num_classes from the shape of the class_prob\n            # So append a zero column as placeholder for the background class\n            class_prob = torch.cat((class_prob, torch.zeros(class_prob.shape[0], 1)), dim=1)\n\n        assert box_regression.shape[1] % box_dim == 0\n        cls_agnostic_bbox_reg = box_regression.shape[1] // box_dim == 1\n\n        input_tensor_mode = proposals[0].proposal_boxes.tensor.shape[1] == box_dim + 1\n\n        rois = type(proposals[0].proposal_boxes).cat([p.proposal_boxes for p in proposals])\n        device, dtype = rois.tensor.device, rois.tensor.dtype\n        if input_tensor_mode:\n            im_info = proposals[0].image_size\n            rois = rois.tensor\n        else:\n            im_info = torch.tensor(\n                [[sz[0], sz[1], 1.0] for sz in [x.image_size for x in proposals]]\n            )\n            batch_ids = cat(\n                [\n                    torch.full((b, 1), i, dtype=dtype, device=device)\n                    for i, b in enumerate(len(p) for p in proposals)\n                ],\n                dim=0,\n            )\n            rois = torch.cat([batch_ids, rois.tensor], dim=1)\n\n        roi_pred_bbox, roi_batch_splits = torch.ops._caffe2.BBoxTransform(\n            to_device(rois, \"cpu\"),\n            to_device(box_regression, \"cpu\"),\n            to_device(im_info, \"cpu\"),\n            weights=box2box_transform_weights,\n            apply_scale=True,\n            rotated=is_rotated,\n            angle_bound_on=True,\n            angle_bound_lo=-180,\n            angle_bound_hi=180,\n            clip_angle_thresh=1.0,\n            legacy_plus_one=False,\n        )\n        roi_pred_bbox = to_device(roi_pred_bbox, device)\n        roi_batch_splits = to_device(roi_batch_splits, device)\n\n        nms_outputs = torch.ops._caffe2.BoxWithNMSLimit(\n            to_device(class_prob, \"cpu\"),\n            to_device(roi_pred_bbox, \"cpu\"),\n            to_device(roi_batch_splits, \"cpu\"),\n            score_thresh=float(score_thresh),\n            nms=float(nms_thresh),\n            detections_per_im=int(topk_per_image),\n            soft_nms_enabled=False,\n            soft_nms_method=\"linear\",\n            soft_nms_sigma=0.5,\n            soft_nms_min_score_thres=0.001,\n            rotated=is_rotated,\n            cls_agnostic_bbox_reg=cls_agnostic_bbox_reg,\n            input_boxes_include_bg_cls=False,\n            output_classes_include_bg_cls=False,\n            legacy_plus_one=False,\n        )\n        roi_score_nms = to_device(nms_outputs[0], device)\n        roi_bbox_nms = to_device(nms_outputs[1], device)\n        roi_class_nms = to_device(nms_outputs[2], device)\n        roi_batch_splits_nms = to_device(nms_outputs[3], device)\n        roi_keeps_nms = to_device(nms_outputs[4], device)\n        roi_keeps_size_nms = to_device(nms_outputs[5], device)\n        if not self.tensor_mode:\n            roi_class_nms = roi_class_nms.to(torch.int64)\n\n        roi_batch_ids = cat(\n            [\n                torch.full((b, 1), i, dtype=dtype, device=device)\n                for i, b in enumerate(int(x.item()) for x in roi_batch_splits_nms)\n            ],\n            dim=0,\n        )\n\n        roi_class_nms = alias(roi_class_nms, \"class_nms\")\n        roi_score_nms = alias(roi_score_nms, \"score_nms\")\n        roi_bbox_nms = alias(roi_bbox_nms, \"bbox_nms\")\n        roi_batch_splits_nms = alias(roi_batch_splits_nms, \"batch_splits_nms\")\n        roi_keeps_nms = alias(roi_keeps_nms, \"keeps_nms\")\n        roi_keeps_size_nms = alias(roi_keeps_size_nms, \"keeps_size_nms\")\n\n        results = InstancesList(\n            im_info=im_info,\n            indices=roi_batch_ids[:, 0],\n            extra_fields={\n                \"pred_boxes\": Caffe2Boxes(roi_bbox_nms),\n                \"scores\": roi_score_nms,\n                \"pred_classes\": roi_class_nms,\n            },\n        )\n\n        if not self.tensor_mode:\n            results = InstancesList.to_d2_instances_list(results)\n            batch_splits = roi_batch_splits_nms.int().tolist()\n            kept_indices = list(roi_keeps_nms.to(torch.int64).split(batch_splits))\n        else:\n            results = [results]\n            kept_indices = [roi_keeps_nms]\n\n        return results, kept_indices\n\n\nclass Caffe2MaskRCNNInference:\n    def __call__(self, pred_mask_logits, pred_instances):\n        \"\"\"equivalent to mask_head.mask_rcnn_inference\"\"\"\n        if all(isinstance(x, InstancesList) for x in pred_instances):\n            assert len(pred_instances) == 1\n            mask_probs_pred = pred_mask_logits.sigmoid()\n            mask_probs_pred = alias(mask_probs_pred, \"mask_fcn_probs\")\n            pred_instances[0].pred_masks = mask_probs_pred\n        else:\n            mask_rcnn_inference(pred_mask_logits, pred_instances)\n\n\nclass Caffe2KeypointRCNNInference:\n    def __init__(self, use_heatmap_max_keypoint):\n        self.use_heatmap_max_keypoint = use_heatmap_max_keypoint\n\n    def __call__(self, pred_keypoint_logits, pred_instances):\n        # just return the keypoint heatmap for now,\n        # there will be option to call HeatmapMaxKeypointOp\n        output = alias(pred_keypoint_logits, \"kps_score\")\n        if all(isinstance(x, InstancesList) for x in pred_instances):\n            assert len(pred_instances) == 1\n            if self.use_heatmap_max_keypoint:\n                device = output.device\n                output = torch.ops._caffe2.HeatmapMaxKeypoint(\n                    to_device(output, \"cpu\"),\n                    pred_instances[0].pred_boxes.tensor,\n                    should_output_softmax=True,  # worth make it configerable?\n                )\n                output = to_device(output, device)\n                output = alias(output, \"keypoints_out\")\n            pred_instances[0].pred_keypoints = output\n        return pred_keypoint_logits\n"
  },
  {
    "path": "VPS_Module/detectron2/export/caffe2_export.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport copy\nimport io\nimport logging\nimport numpy as np\nfrom typing import List\nimport onnx\nimport torch\nfrom caffe2.proto import caffe2_pb2\nfrom caffe2.python import core\nfrom caffe2.python.onnx.backend import Caffe2Backend\nfrom tabulate import tabulate\nfrom termcolor import colored\nfrom torch.onnx import OperatorExportTypes\n\nfrom .shared import (\n    ScopedWS,\n    construct_init_net_from_params,\n    fuse_alias_placeholder,\n    fuse_copy_between_cpu_and_gpu,\n    get_params_from_init_net,\n    group_norm_replace_aten_with_caffe2,\n    infer_device_type,\n    remove_dead_end_ops,\n    remove_reshape_for_fc,\n    save_graph,\n)\n\nlogger = logging.getLogger(__name__)\n\n\ndef export_onnx_model(model, inputs):\n    \"\"\"\n    Trace and export a model to onnx format.\n\n    Args:\n        model (nn.Module):\n        inputs (tuple[args]): the model will be called by `model(*inputs)`\n\n    Returns:\n        an onnx model\n    \"\"\"\n    assert isinstance(model, torch.nn.Module)\n\n    # make sure all modules are in eval mode, onnx may change the training state\n    # of the module if the states are not consistent\n    def _check_eval(module):\n        assert not module.training\n\n    model.apply(_check_eval)\n\n    # Export the model to ONNX\n    with torch.no_grad():\n        with io.BytesIO() as f:\n            torch.onnx.export(\n                model,\n                inputs,\n                f,\n                operator_export_type=OperatorExportTypes.ONNX_ATEN_FALLBACK,\n                # verbose=True,  # NOTE: uncomment this for debugging\n                # export_params=True,\n            )\n            onnx_model = onnx.load_from_string(f.getvalue())\n\n    # Apply ONNX's Optimization\n    all_passes = onnx.optimizer.get_available_passes()\n    passes = [\"fuse_bn_into_conv\"]\n    assert all(p in all_passes for p in passes)\n    onnx_model = onnx.optimizer.optimize(onnx_model, passes)\n    return onnx_model\n\n\ndef _op_stats(net_def):\n    type_count = {}\n    for t in [op.type for op in net_def.op]:\n        type_count[t] = type_count.get(t, 0) + 1\n    type_count_list = sorted(type_count.items(), key=lambda kv: kv[0])  # alphabet\n    type_count_list = sorted(type_count_list, key=lambda kv: -kv[1])  # count\n    return \"\\n\".join(\"{:>4}x {}\".format(count, name) for name, count in type_count_list)\n\n\ndef _assign_device_option(\n    predict_net: caffe2_pb2.NetDef, init_net: caffe2_pb2.NetDef, tensor_inputs: List[torch.Tensor]\n):\n    \"\"\"\n    ONNX exported network doesn't have concept of device, assign necessary\n    device option for each op in order to make it runable on GPU runtime.\n    \"\"\"\n\n    def _get_device_type(torch_tensor):\n        assert torch_tensor.device.type in [\"cpu\", \"cuda\"]\n        assert torch_tensor.device.index == 0\n        return torch_tensor.device.type\n\n    def _assign_op_device_option(net_proto, net_ssa, blob_device_types):\n        for op, ssa_i in zip(net_proto.op, net_ssa):\n            if op.type in [\"CopyCPUToGPU\", \"CopyGPUToCPU\"]:\n                op.device_option.CopyFrom(core.DeviceOption(caffe2_pb2.CUDA, 0))\n            else:\n                devices = [blob_device_types[b] for b in ssa_i[0] + ssa_i[1]]\n                assert all(d == devices[0] for d in devices)\n                if devices[0] == \"cuda\":\n                    op.device_option.CopyFrom(core.DeviceOption(caffe2_pb2.CUDA, 0))\n\n    # update ops in predict_net\n    predict_net_input_device_types = {\n        (name, 0): _get_device_type(tensor)\n        for name, tensor in zip(predict_net.external_input, tensor_inputs)\n    }\n    predict_net_device_types = infer_device_type(\n        predict_net, known_status=predict_net_input_device_types, device_name_style=\"pytorch\"\n    )\n    predict_net_ssa, _ = core.get_ssa(predict_net)\n    _assign_op_device_option(predict_net, predict_net_ssa, predict_net_device_types)\n\n    # update ops in init_net\n    init_net_ssa, versions = core.get_ssa(init_net)\n    init_net_output_device_types = {\n        (name, versions[name]): predict_net_device_types[(name, 0)]\n        for name in init_net.external_output\n    }\n    init_net_device_types = infer_device_type(\n        init_net, known_status=init_net_output_device_types, device_name_style=\"pytorch\"\n    )\n    _assign_op_device_option(init_net, init_net_ssa, init_net_device_types)\n\n\ndef export_caffe2_detection_model(model: torch.nn.Module, tensor_inputs: List[torch.Tensor]):\n    \"\"\"\n    Export a caffe2-compatible Detectron2 model to caffe2 format via ONNX.\n\n    Arg:\n        model: a caffe2-compatible version of detectron2 model, defined in caffe2_modeling.py\n        tensor_inputs: a list of tensors that caffe2 model takes as input.\n    \"\"\"\n    model = copy.deepcopy(model)\n    assert isinstance(model, torch.nn.Module)\n    assert hasattr(model, \"encode_additional_info\")\n\n    # Export via ONNX\n    logger.info(\n        \"Exporting a {} model via ONNX ...\".format(type(model).__name__)\n        + \" Some warnings from ONNX are expected and are usually not to worry about.\"\n    )\n    onnx_model = export_onnx_model(model, (tensor_inputs,))\n    # Convert ONNX model to Caffe2 protobuf\n    init_net, predict_net = Caffe2Backend.onnx_graph_to_caffe2_net(onnx_model)\n    ops_table = [[op.type, op.input, op.output] for op in predict_net.op]\n    table = tabulate(ops_table, headers=[\"type\", \"input\", \"output\"], tablefmt=\"pipe\")\n    logger.info(\n        \"ONNX export Done. Exported predict_net (before optimizations):\\n\" + colored(table, \"cyan\")\n    )\n\n    # Apply protobuf optimization\n    fuse_alias_placeholder(predict_net, init_net)\n    if any(t.device.type != \"cpu\" for t in tensor_inputs):\n        fuse_copy_between_cpu_and_gpu(predict_net)\n        remove_dead_end_ops(init_net)\n        _assign_device_option(predict_net, init_net, tensor_inputs)\n    params, device_options = get_params_from_init_net(init_net)\n    predict_net, params = remove_reshape_for_fc(predict_net, params)\n    init_net = construct_init_net_from_params(params, device_options)\n    group_norm_replace_aten_with_caffe2(predict_net)\n\n    # Record necessary information for running the pb model in Detectron2 system.\n    model.encode_additional_info(predict_net, init_net)\n\n    logger.info(\"Operators used in predict_net: \\n{}\".format(_op_stats(predict_net)))\n    logger.info(\"Operators used in init_net: \\n{}\".format(_op_stats(init_net)))\n\n    return predict_net, init_net\n\n\ndef run_and_save_graph(predict_net, init_net, tensor_inputs, graph_save_path):\n    \"\"\"\n    Run the caffe2 model on given inputs, recording the shape and draw the graph.\n\n    predict_net/init_net: caffe2 model.\n    tensor_inputs: a list of tensors that caffe2 model takes as input.\n    graph_save_path: path for saving graph of exported model.\n    \"\"\"\n\n    logger.info(\"Saving graph of ONNX exported model to {} ...\".format(graph_save_path))\n    save_graph(predict_net, graph_save_path, op_only=False)\n\n    # Run the exported Caffe2 net\n    logger.info(\"Running ONNX exported model ...\")\n    with ScopedWS(\"__ws_tmp__\", True) as ws:\n        ws.RunNetOnce(init_net)\n        initialized_blobs = set(ws.Blobs())\n        uninitialized = [inp for inp in predict_net.external_input if inp not in initialized_blobs]\n        for name, blob in zip(uninitialized, tensor_inputs):\n            ws.FeedBlob(name, blob)\n\n        try:\n            ws.RunNetOnce(predict_net)\n        except RuntimeError as e:\n            logger.warning(\"Encountered RuntimeError: \\n{}\".format(str(e)))\n\n        ws_blobs = {b: ws.FetchBlob(b) for b in ws.Blobs()}\n        blob_sizes = {b: ws_blobs[b].shape for b in ws_blobs if isinstance(ws_blobs[b], np.ndarray)}\n\n        logger.info(\"Saving graph with blob shapes to {} ...\".format(graph_save_path))\n        save_graph(predict_net, graph_save_path, op_only=False, blob_sizes=blob_sizes)\n\n        return ws_blobs\n"
  },
  {
    "path": "VPS_Module/detectron2/export/caffe2_inference.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport logging\nimport numpy as np\nfrom itertools import count\nimport torch\nfrom caffe2.proto import caffe2_pb2\nfrom caffe2.python import core\n\nfrom .caffe2_modeling import META_ARCH_CAFFE2_EXPORT_TYPE_MAP, convert_batched_inputs_to_c2_format\nfrom .shared import ScopedWS, get_pb_arg_vali, get_pb_arg_vals, infer_device_type\n\nlogger = logging.getLogger(__name__)\n\n\n# ===== ref: mobile-vision predictor's 'Caffe2Wrapper' class ======\nclass ProtobufModel(torch.nn.Module):\n    \"\"\"\n    Wrapper of a caffe2's protobuf model.\n    It works just like nn.Module, but running caffe2 under the hood.\n    Input/Output are tuple[tensor] that match the caffe2 net's external_input/output.\n    \"\"\"\n\n    _ids = count(0)\n\n    def __init__(self, predict_net, init_net):\n        logger.info(f\"Initializing ProtobufModel for: {predict_net.name} ...\")\n        super().__init__()\n        assert isinstance(predict_net, caffe2_pb2.NetDef)\n        assert isinstance(init_net, caffe2_pb2.NetDef)\n        # create unique temporary workspace for each instance\n        self.ws_name = \"__tmp_ProtobufModel_{}__\".format(next(self._ids))\n        self.net = core.Net(predict_net)\n\n        logger.info(\"Running init_net once to fill the parameters ...\")\n        with ScopedWS(self.ws_name, is_reset=True, is_cleanup=False) as ws:\n            ws.RunNetOnce(init_net)\n            uninitialized_external_input = []\n            for blob in self.net.Proto().external_input:\n                if blob not in ws.Blobs():\n                    uninitialized_external_input.append(blob)\n                    ws.CreateBlob(blob)\n            ws.CreateNet(self.net)\n\n        self._error_msgs = set()\n        self._input_blobs = uninitialized_external_input\n\n    def _infer_output_devices(self, inputs):\n        \"\"\"\n        Returns:\n            list[str]: list of device for each external output\n        \"\"\"\n\n        def _get_device_type(torch_tensor):\n            assert torch_tensor.device.type in [\"cpu\", \"cuda\"]\n            assert torch_tensor.device.index == 0\n            return torch_tensor.device.type\n\n        predict_net = self.net.Proto()\n        input_device_types = {\n            (name, 0): _get_device_type(tensor) for name, tensor in zip(self._input_blobs, inputs)\n        }\n        device_type_map = infer_device_type(\n            predict_net, known_status=input_device_types, device_name_style=\"pytorch\"\n        )\n        ssa, versions = core.get_ssa(predict_net)\n        versioned_outputs = [(name, versions[name]) for name in predict_net.external_output]\n        output_devices = [device_type_map[outp] for outp in versioned_outputs]\n        return output_devices\n\n    def forward(self, inputs):\n        \"\"\"\n        Args:\n            inputs (tuple[torch.Tensor])\n\n        Returns:\n            tuple[torch.Tensor]\n        \"\"\"\n        assert len(inputs) == len(self._input_blobs), (\n            f\"Length of inputs ({len(inputs)}) \"\n            f\"doesn't match the required input blobs: {self._input_blobs}\"\n        )\n\n        with ScopedWS(self.ws_name, is_reset=False, is_cleanup=False) as ws:\n            for b, tensor in zip(self._input_blobs, inputs):\n                ws.FeedBlob(b, tensor)\n\n            try:\n                ws.RunNet(self.net.Proto().name)\n            except RuntimeError as e:\n                if not str(e) in self._error_msgs:\n                    self._error_msgs.add(str(e))\n                    logger.warning(\"Encountered new RuntimeError: \\n{}\".format(str(e)))\n                logger.warning(\"Catch the error and use partial results.\")\n\n            c2_outputs = [ws.FetchBlob(b) for b in self.net.Proto().external_output]\n            # Remove outputs of current run, this is necessary in order to\n            # prevent fetching the result from previous run if the model fails\n            # in the middle.\n            for b in self.net.Proto().external_output:\n                # Needs to create uninitialized blob to make the net runable.\n                # This is \"equivalent\" to: ws.RemoveBlob(b) then ws.CreateBlob(b),\n                # but there'no such API.\n                ws.FeedBlob(b, f\"{b}, a C++ native class of type nullptr (uninitialized).\")\n\n        # Cast output to torch.Tensor on the desired device\n        output_devices = (\n            self._infer_output_devices(inputs)\n            if any(t.device.type != \"cpu\" for t in inputs)\n            else [\"cpu\" for _ in self.net.Proto().external_output]\n        )\n\n        outputs = []\n        for name, c2_output, device in zip(\n            self.net.Proto().external_output, c2_outputs, output_devices\n        ):\n            if not isinstance(c2_output, np.ndarray):\n                raise RuntimeError(\n                    \"Invalid output for blob {}, received: {}\".format(name, c2_output)\n                )\n            outputs.append(torch.tensor(c2_output).to(device=device))\n        return tuple(outputs)\n\n\nclass ProtobufDetectionModel(torch.nn.Module):\n    \"\"\"\n    A class works just like a pytorch meta arch in terms of inference, but running\n    caffe2 model under the hood.\n    \"\"\"\n\n    def __init__(self, predict_net, init_net, *, convert_outputs=None):\n        \"\"\"\n        Args:\n            predict_net, init_net (core.Net): caffe2 nets\n            convert_outptus (callable): a function that converts caffe2\n                outputs to the same format of the original pytorch model.\n                By default, use the one defined in the caffe2 meta_arch.\n        \"\"\"\n        super().__init__()\n        self.protobuf_model = ProtobufModel(predict_net, init_net)\n        self.size_divisibility = get_pb_arg_vali(predict_net, \"size_divisibility\", 0)\n        self.device = get_pb_arg_vals(predict_net, \"device\", b\"cpu\").decode(\"ascii\")\n\n        if convert_outputs is None:\n            meta_arch = get_pb_arg_vals(predict_net, \"meta_architecture\", b\"GeneralizedRCNN\")\n            meta_arch = META_ARCH_CAFFE2_EXPORT_TYPE_MAP[meta_arch.decode(\"ascii\")]\n            self._convert_outputs = meta_arch.get_outputs_converter(predict_net, init_net)\n        else:\n            self._convert_outputs = convert_outputs\n\n    def _convert_inputs(self, batched_inputs):\n        # currently all models convert inputs in the same way\n        return convert_batched_inputs_to_c2_format(\n            batched_inputs, self.size_divisibility, self.device\n        )\n\n    def forward(self, batched_inputs):\n        c2_inputs = self._convert_inputs(batched_inputs)\n        c2_results = self.protobuf_model(c2_inputs)\n        c2_results = dict(zip(self.protobuf_model.net.Proto().external_output, c2_results))\n        return self._convert_outputs(batched_inputs, c2_inputs, c2_results)\n"
  },
  {
    "path": "VPS_Module/detectron2/export/caffe2_modeling.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport functools\nimport io\nimport struct\nimport types\nimport torch\n\nfrom detectron2.modeling import meta_arch\nfrom detectron2.modeling.box_regression import Box2BoxTransform\nfrom detectron2.modeling.roi_heads import keypoint_head\nfrom detectron2.structures import Boxes, ImageList, Instances, RotatedBoxes\n\nfrom .c10 import Caffe2Compatible\nfrom .caffe2_patch import ROIHeadsPatcher, patch_generalized_rcnn\nfrom .shared import (\n    alias,\n    check_set_pb_arg,\n    get_pb_arg_floats,\n    get_pb_arg_valf,\n    get_pb_arg_vali,\n    get_pb_arg_vals,\n    mock_torch_nn_functional_interpolate,\n)\n\n\ndef assemble_rcnn_outputs_by_name(image_sizes, tensor_outputs, force_mask_on=False):\n    \"\"\"\n    A function to assemble caffe2 model's outputs (i.e. Dict[str, Tensor])\n    to detectron2's format (i.e. list of Instances instance).\n    This only works when the model follows the Caffe2 detectron's naming convention.\n\n    Args:\n        image_sizes (List[List[int, int]]): [H, W] of every image.\n        tensor_outputs (Dict[str, Tensor]): external_output to its tensor.\n\n        force_mask_on (Bool): if true, the it make sure there'll be pred_masks even\n            if the mask is not found from tensor_outputs (usually due to model crash)\n    \"\"\"\n\n    results = [Instances(image_size) for image_size in image_sizes]\n\n    batch_splits = tensor_outputs.get(\"batch_splits\", None)\n    if batch_splits:\n        raise NotImplementedError()\n    assert len(image_sizes) == 1\n    result = results[0]\n\n    bbox_nms = tensor_outputs[\"bbox_nms\"]\n    score_nms = tensor_outputs[\"score_nms\"]\n    class_nms = tensor_outputs[\"class_nms\"]\n    # Detection will always success because Conv support 0-batch\n    assert bbox_nms is not None\n    assert score_nms is not None\n    assert class_nms is not None\n    if bbox_nms.shape[1] == 5:\n        result.pred_boxes = RotatedBoxes(bbox_nms)\n    else:\n        result.pred_boxes = Boxes(bbox_nms)\n    result.scores = score_nms\n    result.pred_classes = class_nms.to(torch.int64)\n\n    mask_fcn_probs = tensor_outputs.get(\"mask_fcn_probs\", None)\n    if mask_fcn_probs is not None:\n        # finish the mask pred\n        mask_probs_pred = mask_fcn_probs\n        num_masks = mask_probs_pred.shape[0]\n        class_pred = result.pred_classes\n        indices = torch.arange(num_masks, device=class_pred.device)\n        mask_probs_pred = mask_probs_pred[indices, class_pred][:, None]\n        result.pred_masks = mask_probs_pred\n    elif force_mask_on:\n        # NOTE: there's no way to know the height/width of mask here, it won't be\n        # used anyway when batch size is 0, so just set them to 0.\n        result.pred_masks = torch.zeros([0, 1, 0, 0], dtype=torch.uint8)\n\n    keypoints_out = tensor_outputs.get(\"keypoints_out\", None)\n    kps_score = tensor_outputs.get(\"kps_score\", None)\n    if keypoints_out is not None:\n        # keypoints_out: [N, 4, #kypoints], where 4 is in order of (x, y, score, prob)\n        keypoints_tensor = keypoints_out\n        # NOTE: it's possible that prob is not calculated if \"should_output_softmax\"\n        # is set to False in HeatmapMaxKeypoint, so just using raw score, seems\n        # it doesn't affect mAP. TODO: check more carefully.\n        keypoint_xyp = keypoints_tensor.transpose(1, 2)[:, :, [0, 1, 2]]\n        result.pred_keypoints = keypoint_xyp\n    elif kps_score is not None:\n        # keypoint heatmap to sparse data structure\n        pred_keypoint_logits = kps_score\n        keypoint_head.keypoint_rcnn_inference(pred_keypoint_logits, [result])\n\n    return results\n\n\ndef _cast_to_f32(f64):\n    return struct.unpack(\"f\", struct.pack(\"f\", f64))[0]\n\n\ndef set_caffe2_compatible_tensor_mode(model, enable=True):\n    def _fn(m):\n        if isinstance(m, Caffe2Compatible):\n            m.tensor_mode = enable\n\n    model.apply(_fn)\n\n\ndef convert_batched_inputs_to_c2_format(batched_inputs, size_divisibility, device):\n    \"\"\"\n    See get_caffe2_inputs() below.\n    \"\"\"\n    assert all(isinstance(x, dict) for x in batched_inputs)\n    assert all(x[\"image\"].dim() == 3 for x in batched_inputs)\n\n    images = [x[\"image\"] for x in batched_inputs]\n    images = ImageList.from_tensors(images, size_divisibility)\n\n    im_info = []\n    for input_per_image, image_size in zip(batched_inputs, images.image_sizes):\n        target_height = input_per_image.get(\"height\", image_size[0])\n        target_width = input_per_image.get(\"width\", image_size[1])  # noqa\n        # NOTE: The scale inside im_info is kept as convention and for providing\n        # post-processing information if further processing is needed. For\n        # current Caffe2 model definitions that don't include post-processing inside\n        # the model, this number is not used.\n        # NOTE: There can be a slight difference between width and height\n        # scales, using a single number can results in numerical difference\n        # compared with D2's post-processing.\n        scale = target_height / image_size[0]\n        im_info.append([image_size[0], image_size[1], scale])\n    im_info = torch.Tensor(im_info)\n\n    return images.tensor.to(device), im_info.to(device)\n\n\nclass Caffe2MetaArch(Caffe2Compatible, torch.nn.Module):\n    \"\"\"\n    Base class for caffe2-compatible implementation of a meta architecture.\n    The forward is traceable and its traced graph can be converted to caffe2\n    graph through ONNX.\n    \"\"\"\n\n    def __init__(self, cfg, torch_model):\n        \"\"\"\n        Args:\n            cfg (CfgNode):\n            torch_model (nn.Module): the detectron2 model (meta_arch) to be\n                converted.\n        \"\"\"\n        super().__init__()\n        self._wrapped_model = torch_model\n        self.eval()\n        set_caffe2_compatible_tensor_mode(self, True)\n\n    def get_caffe2_inputs(self, batched_inputs):\n        \"\"\"\n        Convert pytorch-style structured inputs to caffe2-style inputs that\n        are tuples of tensors.\n\n        Args:\n            batched_inputs (list[dict]): inputs to a detectron2 model\n                in its standard format. Each dict has \"image\" (CHW tensor), and optionally\n                \"height\" and \"width\".\n\n        Returns:\n            tuple[Tensor]:\n                tuple of tensors that will be the inputs to the\n                :meth:`forward` method. For existing models, the first\n                is an NCHW tensor (padded and batched); the second is\n                a im_info Nx3 tensor, where the rows are\n                (height, width, unused legacy parameter)\n        \"\"\"\n        return convert_batched_inputs_to_c2_format(\n            batched_inputs,\n            self._wrapped_model.backbone.size_divisibility,\n            self._wrapped_model.device,\n        )\n\n    def encode_additional_info(self, predict_net, init_net):\n        \"\"\"\n        Save extra metadata that will be used by inference in the output protobuf.\n        \"\"\"\n        pass\n\n    def forward(self, inputs):\n        \"\"\"\n        Run the forward in caffe2-style. It has to use caffe2-compatible ops\n        and the method will be used for tracing.\n\n        Args:\n            inputs (tuple[Tensor]): inputs defined by :meth:`get_caffe2_input`.\n                They will be the inputs of the converted caffe2 graph.\n\n        Returns:\n            tuple[Tensor]: output tensors. They will be the outputs of the\n                converted caffe2 graph.\n        \"\"\"\n        raise NotImplementedError\n\n    def _caffe2_preprocess_image(self, inputs):\n        \"\"\"\n        Caffe2 implementation of preprocess_image, which is called inside each MetaArch's forward.\n        It normalizes the input images, and the final caffe2 graph assumes the\n        inputs have been batched already.\n        \"\"\"\n        data, im_info = inputs\n        data = alias(data, \"data\")\n        im_info = alias(im_info, \"im_info\")\n        mean, std = self._wrapped_model.pixel_mean, self._wrapped_model.pixel_std\n        normalized_data = (data - mean) / std\n        normalized_data = alias(normalized_data, \"normalized_data\")\n\n        # Pack (data, im_info) into ImageList which is recognized by self.inference.\n        images = ImageList(tensor=normalized_data, image_sizes=im_info)\n        return images\n\n    @staticmethod\n    def get_outputs_converter(predict_net, init_net):\n        \"\"\"\n        Creates a function that converts outputs of the caffe2 model to\n        detectron2's standard format.\n        The function uses information in `predict_net` and `init_net` that are\n        available at inferene time. Therefore the function logic can be used in inference.\n\n        The returned function has the following signature:\n\n            def convert(batched_inputs, c2_inputs, c2_results) -> detectron2_outputs\n\n        Where\n\n            * batched_inputs (list[dict]): the original input format of the meta arch\n            * c2_inputs (tuple[Tensor]): the caffe2 inputs.\n            * c2_results (dict[str, Tensor]): the caffe2 output format,\n                corresponding to the outputs of the :meth:`forward` function.\n            * detectron2_outputs: the original output format of the meta arch.\n\n        This function can be used to compare the outputs of the original meta arch and\n        the converted caffe2 graph.\n\n        Returns:\n            callable: a callable of the above signature.\n        \"\"\"\n        raise NotImplementedError\n\n\nclass Caffe2GeneralizedRCNN(Caffe2MetaArch):\n    def __init__(self, cfg, torch_model):\n        assert isinstance(torch_model, meta_arch.GeneralizedRCNN)\n        torch_model = patch_generalized_rcnn(torch_model)\n        super().__init__(cfg, torch_model)\n\n        try:\n            use_heatmap_max_keypoint = cfg.EXPORT_CAFFE2.USE_HEATMAP_MAX_KEYPOINT\n        except AttributeError:\n            use_heatmap_max_keypoint = False\n        self.roi_heads_patcher = ROIHeadsPatcher(\n            self._wrapped_model.roi_heads, use_heatmap_max_keypoint\n        )\n\n    def encode_additional_info(self, predict_net, init_net):\n        size_divisibility = self._wrapped_model.backbone.size_divisibility\n        check_set_pb_arg(predict_net, \"size_divisibility\", \"i\", size_divisibility)\n        check_set_pb_arg(\n            predict_net, \"device\", \"s\", str.encode(str(self._wrapped_model.device), \"ascii\")\n        )\n        check_set_pb_arg(predict_net, \"meta_architecture\", \"s\", b\"GeneralizedRCNN\")\n\n    @mock_torch_nn_functional_interpolate()\n    def forward(self, inputs):\n        if not self.tensor_mode:\n            return self._wrapped_model.inference(inputs)\n        images = self._caffe2_preprocess_image(inputs)\n        features = self._wrapped_model.backbone(images.tensor)\n        proposals, _ = self._wrapped_model.proposal_generator(images, features)\n        with self.roi_heads_patcher.mock_roi_heads():\n            detector_results, _ = self._wrapped_model.roi_heads(images, features, proposals)\n        return tuple(detector_results[0].flatten())\n\n    @staticmethod\n    def get_outputs_converter(predict_net, init_net):\n        def f(batched_inputs, c2_inputs, c2_results):\n            _, im_info = c2_inputs\n            image_sizes = [[int(im[0]), int(im[1])] for im in im_info]\n            results = assemble_rcnn_outputs_by_name(image_sizes, c2_results)\n            return meta_arch.GeneralizedRCNN._postprocess(results, batched_inputs, image_sizes)\n\n        return f\n\n\nclass Caffe2RetinaNet(Caffe2MetaArch):\n    def __init__(self, cfg, torch_model):\n        assert isinstance(torch_model, meta_arch.RetinaNet)\n        super().__init__(cfg, torch_model)\n\n    @mock_torch_nn_functional_interpolate()\n    def forward(self, inputs):\n        assert self.tensor_mode\n        images = self._caffe2_preprocess_image(inputs)\n\n        # explicitly return the images sizes to avoid removing \"im_info\" by ONNX\n        # since it's not used in the forward path\n        return_tensors = [images.image_sizes]\n\n        features = self._wrapped_model.backbone(images.tensor)\n        features = [features[f] for f in self._wrapped_model.head_in_features]\n        for i, feature_i in enumerate(features):\n            features[i] = alias(feature_i, \"feature_{}\".format(i), is_backward=True)\n            return_tensors.append(features[i])\n\n        pred_logits, pred_anchor_deltas = self._wrapped_model.head(features)\n        for i, (box_cls_i, box_delta_i) in enumerate(zip(pred_logits, pred_anchor_deltas)):\n            return_tensors.append(alias(box_cls_i, \"box_cls_{}\".format(i)))\n            return_tensors.append(alias(box_delta_i, \"box_delta_{}\".format(i)))\n\n        return tuple(return_tensors)\n\n    def encode_additional_info(self, predict_net, init_net):\n        size_divisibility = self._wrapped_model.backbone.size_divisibility\n        check_set_pb_arg(predict_net, \"size_divisibility\", \"i\", size_divisibility)\n        check_set_pb_arg(\n            predict_net, \"device\", \"s\", str.encode(str(self._wrapped_model.device), \"ascii\")\n        )\n        check_set_pb_arg(predict_net, \"meta_architecture\", \"s\", b\"RetinaNet\")\n\n        # Inference parameters:\n        check_set_pb_arg(\n            predict_net, \"score_threshold\", \"f\", _cast_to_f32(self._wrapped_model.test_score_thresh)\n        )\n        check_set_pb_arg(\n            predict_net, \"topk_candidates\", \"i\", self._wrapped_model.test_topk_candidates\n        )\n        check_set_pb_arg(\n            predict_net, \"nms_threshold\", \"f\", _cast_to_f32(self._wrapped_model.test_nms_thresh)\n        )\n        check_set_pb_arg(\n            predict_net,\n            \"max_detections_per_image\",\n            \"i\",\n            self._wrapped_model.max_detections_per_image,\n        )\n\n        check_set_pb_arg(\n            predict_net,\n            \"bbox_reg_weights\",\n            \"floats\",\n            [_cast_to_f32(w) for w in self._wrapped_model.box2box_transform.weights],\n        )\n        self._encode_anchor_generator_cfg(predict_net)\n\n    def _encode_anchor_generator_cfg(self, predict_net):\n        # serialize anchor_generator for future use\n        serialized_anchor_generator = io.BytesIO()\n        torch.save(self._wrapped_model.anchor_generator, serialized_anchor_generator)\n        # Ideally we can put anchor generating inside the model, then we don't\n        # need to store this information.\n        bytes = serialized_anchor_generator.getvalue()\n        check_set_pb_arg(predict_net, \"serialized_anchor_generator\", \"s\", bytes)\n\n    @staticmethod\n    def get_outputs_converter(predict_net, init_net):\n        self = types.SimpleNamespace()\n        serialized_anchor_generator = io.BytesIO(\n            get_pb_arg_vals(predict_net, \"serialized_anchor_generator\", None)\n        )\n        self.anchor_generator = torch.load(serialized_anchor_generator)\n        bbox_reg_weights = get_pb_arg_floats(predict_net, \"bbox_reg_weights\", None)\n        self.box2box_transform = Box2BoxTransform(weights=tuple(bbox_reg_weights))\n        self.test_score_thresh = get_pb_arg_valf(predict_net, \"score_threshold\", None)\n        self.test_topk_candidates = get_pb_arg_vali(predict_net, \"topk_candidates\", None)\n        self.test_nms_thresh = get_pb_arg_valf(predict_net, \"nms_threshold\", None)\n        self.max_detections_per_image = get_pb_arg_vali(\n            predict_net, \"max_detections_per_image\", None\n        )\n\n        # hack to reuse inference code from RetinaNet\n        for meth in [\n            \"forward_inference\",\n            \"inference_single_image\",\n            \"_transpose_dense_predictions\",\n            \"_decode_multi_level_predictions\",\n            \"_decode_per_level_predictions\",\n        ]:\n            setattr(self, meth, functools.partial(getattr(meta_arch.RetinaNet, meth), self))\n\n        def f(batched_inputs, c2_inputs, c2_results):\n            _, im_info = c2_inputs\n            image_sizes = [[int(im[0]), int(im[1])] for im in im_info]\n            dummy_images = ImageList(\n                torch.randn(\n                    (\n                        len(im_info),\n                        3,\n                    )\n                    + tuple(image_sizes[0])\n                ),\n                image_sizes,\n            )\n\n            num_features = len([x for x in c2_results.keys() if x.startswith(\"box_cls_\")])\n            pred_logits = [c2_results[\"box_cls_{}\".format(i)] for i in range(num_features)]\n            pred_anchor_deltas = [c2_results[\"box_delta_{}\".format(i)] for i in range(num_features)]\n\n            # For each feature level, feature should have the same batch size and\n            # spatial dimension as the box_cls and box_delta.\n            dummy_features = [x.clone()[:, 0:0, :, :] for x in pred_logits]\n            # self.num_classess can be inferred\n            self.num_classes = pred_logits[0].shape[1] // (pred_anchor_deltas[0].shape[1] // 4)\n\n            results = self.forward_inference(\n                dummy_images, dummy_features, [pred_logits, pred_anchor_deltas]\n            )\n            return meta_arch.GeneralizedRCNN._postprocess(results, batched_inputs, image_sizes)\n\n        return f\n\n\nMETA_ARCH_CAFFE2_EXPORT_TYPE_MAP = {\n    \"GeneralizedRCNN\": Caffe2GeneralizedRCNN,\n    \"RetinaNet\": Caffe2RetinaNet,\n}\n"
  },
  {
    "path": "VPS_Module/detectron2/export/caffe2_patch.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport contextlib\nfrom unittest import mock\nimport torch\n\nfrom detectron2.modeling import poolers\nfrom detectron2.modeling.proposal_generator import rpn\nfrom detectron2.modeling.roi_heads import keypoint_head, mask_head\nfrom detectron2.modeling.roi_heads.fast_rcnn import FastRCNNOutputLayers\n\nfrom .c10 import (\n    Caffe2Compatible,\n    Caffe2FastRCNNOutputsInference,\n    Caffe2KeypointRCNNInference,\n    Caffe2MaskRCNNInference,\n    Caffe2ROIPooler,\n    Caffe2RPN,\n)\n\n\nclass GenericMixin(object):\n    pass\n\n\nclass Caffe2CompatibleConverter(object):\n    \"\"\"\n    A GenericUpdater which implements the `create_from` interface, by modifying\n    module object and assign it with another class replaceCls.\n    \"\"\"\n\n    def __init__(self, replaceCls):\n        self.replaceCls = replaceCls\n\n    def create_from(self, module):\n        # update module's class to the new class\n        assert isinstance(module, torch.nn.Module)\n        if issubclass(self.replaceCls, GenericMixin):\n            # replaceCls should act as mixin, create a new class on-the-fly\n            new_class = type(\n                \"{}MixedWith{}\".format(self.replaceCls.__name__, module.__class__.__name__),\n                (self.replaceCls, module.__class__),\n                {},  # {\"new_method\": lambda self: ...},\n            )\n            module.__class__ = new_class\n        else:\n            # replaceCls is complete class, this allow arbitrary class swap\n            module.__class__ = self.replaceCls\n\n        # initialize Caffe2Compatible\n        if isinstance(module, Caffe2Compatible):\n            module.tensor_mode = False\n\n        return module\n\n\ndef patch(model, target, updater, *args, **kwargs):\n    \"\"\"\n    recursively (post-order) update all modules with the target type and its\n    subclasses, make a initialization/composition/inheritance/... via the\n    updater.create_from.\n    \"\"\"\n    for name, module in model.named_children():\n        model._modules[name] = patch(module, target, updater, *args, **kwargs)\n    if isinstance(model, target):\n        return updater.create_from(model, *args, **kwargs)\n    return model\n\n\ndef patch_generalized_rcnn(model):\n    ccc = Caffe2CompatibleConverter\n    model = patch(model, rpn.RPN, ccc(Caffe2RPN))\n    model = patch(model, poolers.ROIPooler, ccc(Caffe2ROIPooler))\n\n    return model\n\n\n@contextlib.contextmanager\ndef mock_fastrcnn_outputs_inference(\n    tensor_mode, check=True, box_predictor_type=FastRCNNOutputLayers\n):\n    with mock.patch.object(\n        box_predictor_type,\n        \"inference\",\n        autospec=True,\n        side_effect=Caffe2FastRCNNOutputsInference(tensor_mode),\n    ) as mocked_func:\n        yield\n    if check:\n        assert mocked_func.call_count > 0\n\n\n@contextlib.contextmanager\ndef mock_mask_rcnn_inference(tensor_mode, patched_module, check=True):\n    with mock.patch(\n        \"{}.mask_rcnn_inference\".format(patched_module), side_effect=Caffe2MaskRCNNInference()\n    ) as mocked_func:\n        yield\n    if check:\n        assert mocked_func.call_count > 0\n\n\n@contextlib.contextmanager\ndef mock_keypoint_rcnn_inference(tensor_mode, patched_module, use_heatmap_max_keypoint, check=True):\n    with mock.patch(\n        \"{}.keypoint_rcnn_inference\".format(patched_module),\n        side_effect=Caffe2KeypointRCNNInference(use_heatmap_max_keypoint),\n    ) as mocked_func:\n        yield\n    if check:\n        assert mocked_func.call_count > 0\n\n\nclass ROIHeadsPatcher:\n    def __init__(self, heads, use_heatmap_max_keypoint):\n        self.heads = heads\n        self.use_heatmap_max_keypoint = use_heatmap_max_keypoint\n\n    @contextlib.contextmanager\n    def mock_roi_heads(self, tensor_mode=True):\n        \"\"\"\n        Patching several inference functions inside ROIHeads and its subclasses\n\n        Args:\n            tensor_mode (bool): whether the inputs/outputs are caffe2's tensor\n                format or not. Default to True.\n        \"\"\"\n        # NOTE: this requries the `keypoint_rcnn_inference` and `mask_rcnn_inference`\n        # are called inside the same file as BaseXxxHead due to using mock.patch.\n        kpt_heads_mod = keypoint_head.BaseKeypointRCNNHead.__module__\n        mask_head_mod = mask_head.BaseMaskRCNNHead.__module__\n\n        mock_ctx_managers = [\n            mock_fastrcnn_outputs_inference(\n                tensor_mode=tensor_mode,\n                check=True,\n                box_predictor_type=type(self.heads.box_predictor),\n            )\n        ]\n        if getattr(self.heads, \"keypoint_on\", False):\n            mock_ctx_managers += [\n                mock_keypoint_rcnn_inference(\n                    tensor_mode, kpt_heads_mod, self.use_heatmap_max_keypoint\n                )\n            ]\n        if getattr(self.heads, \"mask_on\", False):\n            mock_ctx_managers += [mock_mask_rcnn_inference(tensor_mode, mask_head_mod)]\n\n        with contextlib.ExitStack() as stack:  # python 3.3+\n            for mgr in mock_ctx_managers:\n                stack.enter_context(mgr)\n            yield\n"
  },
  {
    "path": "VPS_Module/detectron2/export/flatten.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport collections\nfrom dataclasses import dataclass\nfrom typing import Callable, List, Optional, Tuple\nimport torch\nfrom torch import nn\n\nfrom detectron2.structures import Boxes, Instances, ROIMasks\nfrom detectron2.utils.registry import _convert_target_to_string, locate\n\nfrom .torchscript_patch import patch_builtin_len\n\n\n@dataclass\nclass Schema:\n    \"\"\"\n    A Schema defines how to flatten a possibly hierarchical object into tuple of\n    primitive objects, so it can be used as inputs/outputs of PyTorch's tracing.\n\n    PyTorch does not support tracing a function that produces rich output\n    structures (e.g. dict, Instances, Boxes). To trace such a function, we\n    flatten the rich object into tuple of tensors, and return this tuple of tensors\n    instead. Meanwhile, we also need to know how to \"rebuild\" the original object\n    from the flattened results, so we can evaluate the flattened results.\n    A Schema defines how to flatten an object, and while flattening it, it records\n    necessary schemas so that the object can be rebuilt using the flattened outputs.\n\n    The flattened object and the schema object is returned by ``.flatten`` classmethod.\n    Then the original object can be rebuilt with the ``__call__`` method of schema.\n\n    A Schema is a dataclass that can be serialized easily.\n    \"\"\"\n\n    # inspired by FetchMapper in tensorflow/python/client/session.py\n\n    @classmethod\n    def flatten(cls, obj):\n        raise NotImplementedError\n\n    def __call__(self, values):\n        raise NotImplementedError\n\n    @staticmethod\n    def _concat(values):\n        ret = ()\n        sizes = []\n        for v in values:\n            assert isinstance(v, tuple), \"Flattened results must be a tuple\"\n            ret = ret + v\n            sizes.append(len(v))\n        return ret, sizes\n\n    @staticmethod\n    def _split(values, sizes):\n        if len(sizes):\n            expected_len = sum(sizes)\n            assert (\n                len(values) == expected_len\n            ), f\"Values has length {len(values)} but expect length {expected_len}.\"\n        ret = []\n        for k in range(len(sizes)):\n            begin, end = sum(sizes[:k]), sum(sizes[: k + 1])\n            ret.append(values[begin:end])\n        return ret\n\n\n@dataclass\nclass ListSchema(Schema):\n    schemas: List[Schema]  # the schemas that define how to flatten each element in the list\n    sizes: List[int]  # the flattened length of each element\n\n    def __call__(self, values):\n        values = self._split(values, self.sizes)\n        if len(values) != len(self.schemas):\n            raise ValueError(\n                f\"Values has length {len(values)} but schemas \" f\"has length {len(self.schemas)}!\"\n            )\n        values = [m(v) for m, v in zip(self.schemas, values)]\n        return list(values)\n\n    @classmethod\n    def flatten(cls, obj):\n        res = [flatten_to_tuple(k) for k in obj]\n        values, sizes = cls._concat([k[0] for k in res])\n        return values, cls([k[1] for k in res], sizes)\n\n\n@dataclass\nclass TupleSchema(ListSchema):\n    def __call__(self, values):\n        return tuple(super().__call__(values))\n\n\n@dataclass\nclass IdentitySchema(Schema):\n    def __call__(self, values):\n        return values[0]\n\n    @classmethod\n    def flatten(cls, obj):\n        return (obj,), cls()\n\n\n@dataclass\nclass DictSchema(ListSchema):\n    keys: List[str]\n\n    def __call__(self, values):\n        values = super().__call__(values)\n        return dict(zip(self.keys, values))\n\n    @classmethod\n    def flatten(cls, obj):\n        for k in obj.keys():\n            if not isinstance(k, str):\n                raise KeyError(\"Only support flattening dictionaries if keys are str.\")\n        keys = sorted(obj.keys())\n        values = [obj[k] for k in keys]\n        ret, schema = ListSchema.flatten(values)\n        return ret, cls(schema.schemas, schema.sizes, keys)\n\n\n@dataclass\nclass InstancesSchema(DictSchema):\n    def __call__(self, values):\n        image_size, fields = values[-1], values[:-1]\n        fields = super().__call__(fields)\n        return Instances(image_size, **fields)\n\n    @classmethod\n    def flatten(cls, obj):\n        ret, schema = super().flatten(obj.get_fields())\n        size = obj.image_size\n        if not isinstance(size, torch.Tensor):\n            size = torch.tensor(size)\n        return ret + (size,), schema\n\n\n@dataclass\nclass TensorWrapSchema(Schema):\n    \"\"\"\n    For classes that are simple wrapper of tensors, e.g.\n    Boxes, RotatedBoxes, BitMasks\n    \"\"\"\n\n    class_name: str\n\n    def __call__(self, values):\n        return locate(self.class_name)(values[0])\n\n    @classmethod\n    def flatten(cls, obj):\n        return (obj.tensor,), cls(_convert_target_to_string(type(obj)))\n\n\n# if more custom structures needed in the future, can allow\n# passing in extra schemas for custom types\ndef flatten_to_tuple(obj):\n    \"\"\"\n    Flatten an object so it can be used for PyTorch tracing.\n    Also returns how to rebuild the original object from the flattened outputs.\n\n    Returns:\n        res (tuple): the flattened results that can be used as tracing outputs\n        schema: an object with a ``__call__`` method such that ``schema(res) == obj``.\n             It is a pure dataclass that can be serialized.\n    \"\"\"\n    schemas = [\n        ((str, bytes), IdentitySchema),\n        (list, ListSchema),\n        (tuple, TupleSchema),\n        (collections.abc.Mapping, DictSchema),\n        (Instances, InstancesSchema),\n        ((Boxes, ROIMasks), TensorWrapSchema),\n    ]\n    for klass, schema in schemas:\n        if isinstance(obj, klass):\n            F = schema\n            break\n    else:\n        F = IdentitySchema\n\n    return F.flatten(obj)\n\n\nclass TracingAdapter(nn.Module):\n    \"\"\"\n    A model may take rich input/output format (e.g. dict or custom classes),\n    but `torch.jit.trace` requires tuple of tensors as input/output.\n    This adapter flattens input/output format of a model so it becomes traceable.\n\n    It also records the necessary schema to rebuild model's inputs/outputs from flattened\n    inputs/outputs.\n\n    Example:\n    ::\n        outputs = model(inputs)   # inputs/outputs may be rich structure\n        adapter = TracingAdapter(model, inputs)\n\n        # can now trace the model, with adapter.flattened_inputs, or another\n        # tuple of tensors with the same length and meaning\n        traced = torch.jit.trace(adapter, adapter.flattened_inputs)\n\n        # traced model can only produce flattened outputs (tuple of tensors)\n        flattened_outputs = traced(*adapter.flattened_inputs)\n        # adapter knows the schema to convert it back (new_outputs == outputs)\n        new_outputs = adapter.outputs_schema(flattened_outputs)\n    \"\"\"\n\n    flattened_inputs: Tuple[torch.Tensor] = None\n    \"\"\"\n    Flattened version of inputs given to this class's constructor.\n    \"\"\"\n\n    inputs_schema: Schema = None\n    \"\"\"\n    Schema of the inputs given to this class's constructor.\n    \"\"\"\n\n    outputs_schema: Schema = None\n    \"\"\"\n    Schema of the output produced by calling the given model with inputs.\n    \"\"\"\n\n    def __init__(\n        self,\n        model: nn.Module,\n        inputs,\n        inference_func: Optional[Callable] = None,\n        allow_non_tensor: bool = False,\n    ):\n        \"\"\"\n        Args:\n            model: an nn.Module\n            inputs: An input argument or a tuple of input arguments used to call model.\n                After flattening, it has to only consist of tensors.\n            inference_func: a callable that takes (model, *inputs), calls the\n                model with inputs, and return outputs. By default it\n                is ``lambda model, *inputs: model(*inputs)``. Can be override\n                if you need to call the model differently.\n            allow_non_tensor: allow inputs/outputs to contain non-tensor objects.\n                This option will filter out non-tensor objects to make the\n                model traceable, but ``inputs_schema``/``outputs_schema`` cannot be\n                used anymore because inputs/outputs cannot be rebuilt from pure tensors.\n                This is useful when you're only interested in the single trace of\n                execution (e.g. for flop count), but not interested in\n                generalizing the traced graph to new inputs.\n        \"\"\"\n        super().__init__()\n        if isinstance(model, (nn.parallel.distributed.DistributedDataParallel, nn.DataParallel)):\n            model = model.module\n        self.model = model\n        if not isinstance(inputs, tuple):\n            inputs = (inputs,)\n        self.inputs = inputs\n        self.allow_non_tensor = allow_non_tensor\n\n        if inference_func is None:\n            inference_func = lambda model, *inputs: model(*inputs)  # noqa\n        self.inference_func = inference_func\n\n        self.flattened_inputs, self.inputs_schema = flatten_to_tuple(inputs)\n\n        if all(isinstance(x, torch.Tensor) for x in self.flattened_inputs):\n            return\n        if self.allow_non_tensor:\n            self.flattened_inputs = tuple(\n                [x for x in self.flattened_inputs if isinstance(x, torch.Tensor)]\n            )\n            self.inputs_schema = None\n        else:\n            for input in self.flattened_inputs:\n                if not isinstance(input, torch.Tensor):\n                    raise ValueError(\n                        \"Inputs for tracing must only contain tensors. \"\n                        f\"Got a {type(input)} instead.\"\n                    )\n\n    def forward(self, *args: torch.Tensor):\n        with torch.no_grad(), patch_builtin_len():\n            if self.inputs_schema is not None:\n                inputs_orig_format = self.inputs_schema(args)\n            else:\n                if len(args) != len(self.flattened_inputs) or any(\n                    x is not y for x, y in zip(args, self.flattened_inputs)\n                ):\n                    raise ValueError(\n                        \"TracingAdapter does not contain valid inputs_schema.\"\n                        \" So it cannot generalize to other inputs and must be\"\n                        \" traced with `.flattened_inputs`.\"\n                    )\n                inputs_orig_format = self.inputs\n\n            outputs = self.inference_func(self.model, *inputs_orig_format)\n            flattened_outputs, schema = flatten_to_tuple(outputs)\n\n            flattened_output_tensors = tuple(\n                [x for x in flattened_outputs if isinstance(x, torch.Tensor)]\n            )\n            if len(flattened_output_tensors) < len(flattened_outputs):\n                if self.allow_non_tensor:\n                    flattened_outputs = flattened_output_tensors\n                    self.outputs_schema = None\n                else:\n                    raise ValueError(\n                        \"Model cannot be traced because some model outputs \"\n                        \"cannot flatten to tensors.\"\n                    )\n            else:  # schema is valid\n                if self.outputs_schema is None:\n                    self.outputs_schema = schema\n                else:\n                    assert self.outputs_schema == schema, (\n                        \"Model should always return outputs with the same \"\n                        \"structure so it can be traced!\"\n                    )\n            return flattened_outputs\n\n    def _create_wrapper(self, traced_model):\n        \"\"\"\n        Return a function that has an input/output interface the same as the\n        original model, but it calls the given traced model under the hood.\n        \"\"\"\n\n        def forward(*args):\n            flattened_inputs, _ = flatten_to_tuple(args)\n            flattened_outputs = traced_model(*flattened_inputs)\n            return self.outputs_schema(flattened_outputs)\n\n        return forward\n"
  },
  {
    "path": "VPS_Module/detectron2/export/shared.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport collections\nimport contextlib\nimport copy\nimport functools\nimport logging\nimport numpy as np\nimport os\nfrom typing import Any, Callable, Dict, List, Optional, Tuple, Union\nfrom unittest import mock\nimport caffe2.python.utils as putils\nimport torch\nimport torch.nn.functional as F\nfrom caffe2.proto import caffe2_pb2\nfrom caffe2.python import core, net_drawer, workspace\nfrom torch.nn.functional import interpolate as interp\n\nlogger = logging.getLogger(__name__)\n\n\n# ==== torch/utils_toffee/cast.py =======================================\n\n\ndef to_device(t, device_str):\n    \"\"\"\n    This function is a replacement of .to(another_device) such that it allows the\n    casting to be traced properly by explicitly calling the underlying copy ops.\n    It also avoids introducing unncessary op when casting to the same device.\n    \"\"\"\n    src = t.device\n    dst = torch.device(device_str)\n\n    if src == dst:\n        return t\n    elif src.type == \"cuda\" and dst.type == \"cpu\":\n        return torch.ops._caffe2.CopyGPUToCPU(t)\n    elif src.type == \"cpu\" and dst.type == \"cuda\":\n        return torch.ops._caffe2.CopyCPUToGPU(t)\n    else:\n        raise RuntimeError(\"Can't cast tensor from device {} to device {}\".format(src, dst))\n\n\n# ==== torch/utils_toffee/interpolate.py =======================================\n\n\n# Note: borrowed from vision/detection/fair/detectron/detectron/modeling/detector.py\ndef BilinearInterpolation(tensor_in, up_scale):\n    assert up_scale % 2 == 0, \"Scale should be even\"\n\n    def upsample_filt(size):\n        factor = (size + 1) // 2\n        if size % 2 == 1:\n            center = factor - 1\n        else:\n            center = factor - 0.5\n\n        og = np.ogrid[:size, :size]\n        return (1 - abs(og[0] - center) / factor) * (1 - abs(og[1] - center) / factor)\n\n    kernel_size = int(up_scale) * 2\n    bil_filt = upsample_filt(kernel_size)\n\n    dim = int(tensor_in.shape[1])\n    kernel = np.zeros((dim, dim, kernel_size, kernel_size), dtype=np.float32)\n    kernel[range(dim), range(dim), :, :] = bil_filt\n\n    tensor_out = F.conv_transpose2d(\n        tensor_in,\n        weight=to_device(torch.Tensor(kernel), tensor_in.device),\n        bias=None,\n        stride=int(up_scale),\n        padding=int(up_scale / 2),\n    )\n\n    return tensor_out\n\n\n# NOTE: ONNX is incompatible with traced torch.nn.functional.interpolate if\n# using dynamic `scale_factor` rather than static `size`. (T43166860)\n# NOTE: Caffe2 Int8 conversion might not be able to quantize `size` properly.\ndef onnx_compatibale_interpolate(\n    input, size=None, scale_factor=None, mode=\"nearest\", align_corners=None\n):\n    # NOTE: The input dimensions are interpreted in the form:\n    # `mini-batch x channels x [optional depth] x [optional height] x width`.\n    if size is None and scale_factor is not None:\n        if input.dim() == 4:\n            if isinstance(scale_factor, (int, float)):\n                height_scale, width_scale = (scale_factor, scale_factor)\n            else:\n                assert isinstance(scale_factor, (tuple, list))\n                assert len(scale_factor) == 2\n                height_scale, width_scale = scale_factor\n\n            assert not align_corners, \"No matching C2 op for align_corners == True\"\n            if mode == \"nearest\":\n                return torch.ops._caffe2.ResizeNearest(\n                    input, order=\"NCHW\", width_scale=width_scale, height_scale=height_scale\n                )\n            elif mode == \"bilinear\":\n                logger.warning(\n                    \"Use F.conv_transpose2d for bilinear interpolate\"\n                    \" because there's no such C2 op, this may cause significant\"\n                    \" slowdown and the boundary pixels won't be as same as\"\n                    \" using F.interpolate due to padding.\"\n                )\n                assert height_scale == width_scale\n                return BilinearInterpolation(input, up_scale=height_scale)\n        logger.warning(\"Output size is not static, it might cause ONNX conversion issue\")\n\n    return interp(input, size, scale_factor, mode, align_corners)\n\n\n@contextlib.contextmanager\ndef mock_torch_nn_functional_interpolate():\n    if torch.onnx.is_in_onnx_export():\n        with mock.patch(\n            \"torch.nn.functional.interpolate\", side_effect=onnx_compatibale_interpolate\n        ):\n            yield\n    else:\n        yield\n\n\n# ==== torch/utils_caffe2/ws_utils.py ==========================================\n\n\nclass ScopedWS(object):\n    def __init__(self, ws_name, is_reset, is_cleanup=False):\n        self.ws_name = ws_name\n        self.is_reset = is_reset\n        self.is_cleanup = is_cleanup\n        self.org_ws = \"\"\n\n    def __enter__(self):\n        self.org_ws = workspace.CurrentWorkspace()\n        if self.ws_name is not None:\n            workspace.SwitchWorkspace(self.ws_name, True)\n        if self.is_reset:\n            workspace.ResetWorkspace()\n\n        return workspace\n\n    def __exit__(self, *args):\n        if self.is_cleanup:\n            workspace.ResetWorkspace()\n        if self.ws_name is not None:\n            workspace.SwitchWorkspace(self.org_ws)\n\n\ndef fetch_any_blob(name):\n    bb = None\n    try:\n        bb = workspace.FetchBlob(name)\n    except TypeError:\n        bb = workspace.FetchInt8Blob(name)\n    except Exception as e:\n        logger.error(\"Get blob {} error: {}\".format(name, e))\n\n    return bb\n\n\n# ==== torch/utils_caffe2/protobuf.py ==========================================\n\n\ndef get_pb_arg(pb, arg_name):\n    for x in pb.arg:\n        if x.name == arg_name:\n            return x\n    return None\n\n\ndef get_pb_arg_valf(pb, arg_name, default_val):\n    arg = get_pb_arg(pb, arg_name)\n    return arg.f if arg is not None else default_val\n\n\ndef get_pb_arg_floats(pb, arg_name, default_val):\n    arg = get_pb_arg(pb, arg_name)\n    return list(map(float, arg.floats)) if arg is not None else default_val\n\n\ndef get_pb_arg_ints(pb, arg_name, default_val):\n    arg = get_pb_arg(pb, arg_name)\n    return list(map(int, arg.ints)) if arg is not None else default_val\n\n\ndef get_pb_arg_vali(pb, arg_name, default_val):\n    arg = get_pb_arg(pb, arg_name)\n    return arg.i if arg is not None else default_val\n\n\ndef get_pb_arg_vals(pb, arg_name, default_val):\n    arg = get_pb_arg(pb, arg_name)\n    return arg.s if arg is not None else default_val\n\n\ndef get_pb_arg_valstrings(pb, arg_name, default_val):\n    arg = get_pb_arg(pb, arg_name)\n    return list(arg.strings) if arg is not None else default_val\n\n\ndef check_set_pb_arg(pb, arg_name, arg_attr, arg_value, allow_override=False):\n    arg = get_pb_arg(pb, arg_name)\n    if arg is None:\n        arg = putils.MakeArgument(arg_name, arg_value)\n        assert hasattr(arg, arg_attr)\n        pb.arg.extend([arg])\n    if allow_override and getattr(arg, arg_attr) != arg_value:\n        logger.warning(\n            \"Override argument {}: {} -> {}\".format(arg_name, getattr(arg, arg_attr), arg_value)\n        )\n        setattr(arg, arg_attr, arg_value)\n    else:\n        assert arg is not None\n        assert getattr(arg, arg_attr) == arg_value, \"Existing value {}, new value {}\".format(\n            getattr(arg, arg_attr), arg_value\n        )\n\n\ndef _create_const_fill_op_from_numpy(name, tensor, device_option=None):\n    assert type(tensor) == np.ndarray\n    kTypeNameMapper = {\n        np.dtype(\"float32\"): \"GivenTensorFill\",\n        np.dtype(\"int32\"): \"GivenTensorIntFill\",\n        np.dtype(\"int64\"): \"GivenTensorInt64Fill\",\n        np.dtype(\"uint8\"): \"GivenTensorStringFill\",\n    }\n\n    args_dict = {}\n    if tensor.dtype == np.dtype(\"uint8\"):\n        args_dict.update({\"values\": [str(tensor.data)], \"shape\": [1]})\n    else:\n        args_dict.update({\"values\": tensor, \"shape\": tensor.shape})\n\n    if device_option is not None:\n        args_dict[\"device_option\"] = device_option\n\n    return core.CreateOperator(kTypeNameMapper[tensor.dtype], [], [name], **args_dict)\n\n\ndef _create_const_fill_op_from_c2_int8_tensor(name, int8_tensor):\n    assert type(int8_tensor) == workspace.Int8Tensor\n    kTypeNameMapper = {\n        np.dtype(\"int32\"): \"Int8GivenIntTensorFill\",\n        np.dtype(\"uint8\"): \"Int8GivenTensorFill\",\n    }\n\n    tensor = int8_tensor.data\n    assert tensor.dtype in [np.dtype(\"uint8\"), np.dtype(\"int32\")]\n    values = tensor.tobytes() if tensor.dtype == np.dtype(\"uint8\") else tensor\n\n    return core.CreateOperator(\n        kTypeNameMapper[tensor.dtype],\n        [],\n        [name],\n        values=values,\n        shape=tensor.shape,\n        Y_scale=int8_tensor.scale,\n        Y_zero_point=int8_tensor.zero_point,\n    )\n\n\ndef create_const_fill_op(\n    name: str,\n    blob: Union[np.ndarray, workspace.Int8Tensor],\n    device_option: Optional[caffe2_pb2.DeviceOption] = None,\n) -> caffe2_pb2.OperatorDef:\n    \"\"\"\n    Given a blob object, return the Caffe2 operator that creates this blob\n    as constant. Currently support NumPy tensor and Caffe2 Int8Tensor.\n    \"\"\"\n\n    tensor_type = type(blob)\n    assert tensor_type in [\n        np.ndarray,\n        workspace.Int8Tensor,\n    ], 'Error when creating const fill op for \"{}\", unsupported blob type: {}'.format(\n        name, type(blob)\n    )\n\n    if tensor_type == np.ndarray:\n        return _create_const_fill_op_from_numpy(name, blob, device_option)\n    elif tensor_type == workspace.Int8Tensor:\n        assert device_option is None\n        return _create_const_fill_op_from_c2_int8_tensor(name, blob)\n\n\ndef construct_init_net_from_params(\n    params: Dict[str, Any], device_options: Optional[Dict[str, caffe2_pb2.DeviceOption]] = None\n) -> caffe2_pb2.NetDef:\n    \"\"\"\n    Construct the init_net from params dictionary\n    \"\"\"\n    init_net = caffe2_pb2.NetDef()\n    device_options = device_options or {}\n    for name, blob in params.items():\n        if isinstance(blob, str):\n            logger.warning(\n                (\n                    \"Blob {} with type {} is not supported in generating init net,\"\n                    \" skipped.\".format(name, type(blob))\n                )\n            )\n            continue\n        init_net.op.extend(\n            [create_const_fill_op(name, blob, device_option=device_options.get(name, None))]\n        )\n        init_net.external_output.append(name)\n    return init_net\n\n\ndef get_producer_map(ssa):\n    \"\"\"\n    Return dict from versioned blob to (i, j),\n        where i is index of producer op, j is the index of output of that op.\n    \"\"\"\n    producer_map = {}\n    for i in range(len(ssa)):\n        outputs = ssa[i][1]\n        for j, outp in enumerate(outputs):\n            producer_map[outp] = (i, j)\n    return producer_map\n\n\ndef get_consumer_map(ssa):\n    \"\"\"\n    Return dict from versioned blob to list of (i, j),\n        where i is index of consumer op, j is the index of input of that op.\n    \"\"\"\n    consumer_map = collections.defaultdict(list)\n    for i in range(len(ssa)):\n        inputs = ssa[i][0]\n        for j, inp in enumerate(inputs):\n            consumer_map[inp].append((i, j))\n    return consumer_map\n\n\ndef get_params_from_init_net(\n    init_net: caffe2_pb2.NetDef,\n) -> [Dict[str, Any], Dict[str, caffe2_pb2.DeviceOption]]:\n    \"\"\"\n    Take the output blobs from init_net by running it.\n    Outputs:\n        params: dict from blob name to numpy array\n        device_options: dict from blob name to the device option of its creating op\n    \"\"\"\n    # NOTE: this assumes that the params is determined by producer op with the\n    # only exception be CopyGPUToCPU which is CUDA op but returns CPU tensor.\n    def _get_device_option(producer_op):\n        if producer_op.type == \"CopyGPUToCPU\":\n            return caffe2_pb2.DeviceOption()\n        else:\n            return producer_op.device_option\n\n    with ScopedWS(\"__get_params_from_init_net__\", is_reset=True, is_cleanup=True) as ws:\n        ws.RunNetOnce(init_net)\n        params = {b: fetch_any_blob(b) for b in init_net.external_output}\n    ssa, versions = core.get_ssa(init_net)\n    producer_map = get_producer_map(ssa)\n    device_options = {\n        b: _get_device_option(init_net.op[producer_map[(b, versions[b])][0]])\n        for b in init_net.external_output\n    }\n    return params, device_options\n\n\ndef _updater_raise(op, input_types, output_types):\n    raise RuntimeError(\n        \"Failed to apply updater for op {} given input_types {} and\"\n        \" output_types {}\".format(op, input_types, output_types)\n    )\n\n\ndef _generic_status_identifier(\n    predict_net: caffe2_pb2.NetDef,\n    status_updater: Callable,\n    known_status: Dict[Tuple[str, int], Any],\n) -> Dict[Tuple[str, int], Any]:\n    \"\"\"\n    Statically infer the status of each blob, the status can be such as device type\n        (CPU/GPU), layout (NCHW/NHWC), data type (float32/int8), etc. \"Blob\" here\n        is versioned blob (Tuple[str, int]) in the format compatible with ssa.\n    Inputs:\n        predict_net: the caffe2 network\n        status_updater: a callable, given an op and the status of its input/output,\n            it returns the updated status of input/output. `None` is used for\n            representing unknown status.\n        known_status: a dict containing known status, used as initialization.\n    Outputs:\n        A dict mapping from versioned blob to its status\n    \"\"\"\n    ssa, versions = core.get_ssa(predict_net)\n    versioned_ext_input = [(b, 0) for b in predict_net.external_input]\n    versioned_ext_output = [(b, versions[b]) for b in predict_net.external_output]\n    all_versioned_blobs = set().union(*[set(x[0] + x[1]) for x in ssa])\n\n    allowed_vbs = all_versioned_blobs.union(versioned_ext_input).union(versioned_ext_output)\n    assert all(k in allowed_vbs for k in known_status)\n    assert all(v is not None for v in known_status.values())\n    _known_status = copy.deepcopy(known_status)\n\n    def _check_and_update(key, value):\n        assert value is not None\n        if key in _known_status:\n            if not _known_status[key] == value:\n                raise RuntimeError(\n                    \"Confilict status for {}, existing status {}, new status {}\".format(\n                        key, _known_status[key], value\n                    )\n                )\n        _known_status[key] = value\n\n    def _update_i(op, ssa_i):\n        versioned_inputs = ssa_i[0]\n        versioned_outputs = ssa_i[1]\n\n        inputs_status = [_known_status.get(b, None) for b in versioned_inputs]\n        outputs_status = [_known_status.get(b, None) for b in versioned_outputs]\n\n        new_inputs_status, new_outputs_status = status_updater(op, inputs_status, outputs_status)\n\n        for versioned_blob, status in zip(\n            versioned_inputs + versioned_outputs, new_inputs_status + new_outputs_status\n        ):\n            if status is not None:\n                _check_and_update(versioned_blob, status)\n\n    for op, ssa_i in zip(predict_net.op, ssa):\n        _update_i(op, ssa_i)\n    for op, ssa_i in zip(reversed(predict_net.op), reversed(ssa)):\n        _update_i(op, ssa_i)\n\n    # NOTE: This strictly checks all the blob from predict_net must be assgined\n    # a known status. However sometimes it's impossible (eg. having deadend op),\n    # we may relax this constraint if\n    for k in all_versioned_blobs:\n        if k not in _known_status:\n            raise NotImplementedError(\n                \"Can not infer the status for {}. Currently only support the case where\"\n                \" a single forward and backward pass can identify status for all blobs.\".format(k)\n            )\n\n    return _known_status\n\n\ndef infer_device_type(\n    predict_net: caffe2_pb2.NetDef,\n    known_status: Dict[Tuple[str, int], Any],\n    device_name_style: str = \"caffe2\",\n) -> Dict[Tuple[str, int], str]:\n    \"\"\"Return the device type (\"cpu\" or \"gpu\"/\"cuda\") of each (versioned) blob\"\"\"\n\n    assert device_name_style in [\"caffe2\", \"pytorch\"]\n    _CPU_STR = \"cpu\"\n    _GPU_STR = \"gpu\" if device_name_style == \"caffe2\" else \"cuda\"\n\n    def _copy_cpu_to_gpu_updater(op, input_types, output_types):\n        if input_types[0] == _GPU_STR or output_types[0] == _CPU_STR:\n            _updater_raise(op, input_types, output_types)\n        return ([_CPU_STR], [_GPU_STR])\n\n    def _copy_gpu_to_cpu_updater(op, input_types, output_types):\n        if input_types[0] == _CPU_STR or output_types[0] == _GPU_STR:\n            _updater_raise(op, input_types, output_types)\n        return ([_GPU_STR], [_CPU_STR])\n\n    def _other_ops_updater(op, input_types, output_types):\n        non_none_types = [x for x in input_types + output_types if x is not None]\n        if len(non_none_types) > 0:\n            the_type = non_none_types[0]\n            if not all(x == the_type for x in non_none_types):\n                _updater_raise(op, input_types, output_types)\n        else:\n            the_type = None\n        return ([the_type for _ in op.input], [the_type for _ in op.output])\n\n    def _device_updater(op, *args, **kwargs):\n        return {\n            \"CopyCPUToGPU\": _copy_cpu_to_gpu_updater,\n            \"CopyGPUToCPU\": _copy_gpu_to_cpu_updater,\n        }.get(op.type, _other_ops_updater)(op, *args, **kwargs)\n\n    return _generic_status_identifier(predict_net, _device_updater, known_status)\n\n\n# ==== torch/utils_caffe2/vis.py ===============================================\n\n\ndef _modify_blob_names(ops, blob_rename_f):\n    ret = []\n\n    def _replace_list(blob_list, replaced_list):\n        del blob_list[:]\n        blob_list.extend(replaced_list)\n\n    for x in ops:\n        cur = copy.deepcopy(x)\n        _replace_list(cur.input, list(map(blob_rename_f, cur.input)))\n        _replace_list(cur.output, list(map(blob_rename_f, cur.output)))\n        ret.append(cur)\n\n    return ret\n\n\ndef _rename_blob(name, blob_sizes, blob_ranges):\n    def _list_to_str(bsize):\n        ret = \", \".join([str(x) for x in bsize])\n        ret = \"[\" + ret + \"]\"\n        return ret\n\n    ret = name\n    if blob_sizes is not None and name in blob_sizes:\n        ret += \"\\n\" + _list_to_str(blob_sizes[name])\n    if blob_ranges is not None and name in blob_ranges:\n        ret += \"\\n\" + _list_to_str(blob_ranges[name])\n\n    return ret\n\n\n# graph_name could not contain word 'graph'\ndef save_graph(net, file_name, graph_name=\"net\", op_only=True, blob_sizes=None, blob_ranges=None):\n    blob_rename_f = functools.partial(_rename_blob, blob_sizes=blob_sizes, blob_ranges=blob_ranges)\n    return save_graph_base(net, file_name, graph_name, op_only, blob_rename_f)\n\n\ndef save_graph_base(net, file_name, graph_name=\"net\", op_only=True, blob_rename_func=None):\n    graph = None\n    ops = net.op\n    if blob_rename_func is not None:\n        ops = _modify_blob_names(ops, blob_rename_func)\n    if not op_only:\n        graph = net_drawer.GetPydotGraph(ops, graph_name, rankdir=\"TB\")\n    else:\n        graph = net_drawer.GetPydotGraphMinimal(\n            ops, graph_name, rankdir=\"TB\", minimal_dependency=True\n        )\n\n    try:\n        par_dir = os.path.dirname(file_name)\n        if not os.path.exists(par_dir):\n            os.makedirs(par_dir)\n\n        format = os.path.splitext(os.path.basename(file_name))[-1]\n        if format == \".png\":\n            graph.write_png(file_name)\n        elif format == \".pdf\":\n            graph.write_pdf(file_name)\n        elif format == \".svg\":\n            graph.write_svg(file_name)\n        else:\n            print(\"Incorrect format {}\".format(format))\n    except Exception as e:\n        print(\"Error when writing graph to image {}\".format(e))\n\n    return graph\n\n\n# ==== torch/utils_toffee/aten_to_caffe2.py ====================================\n\n\ndef group_norm_replace_aten_with_caffe2(predict_net: caffe2_pb2.NetDef):\n    \"\"\"\n    For ONNX exported model, GroupNorm will be represented as ATen op,\n        this can be a drop in replacement from ATen to GroupNorm\n    \"\"\"\n    count = 0\n    for op in predict_net.op:\n        if op.type == \"ATen\":\n            op_name = get_pb_arg_vals(op, \"operator\", None)  # return byte in py3\n            if op_name and op_name.decode() == \"group_norm\":\n                op.arg.remove(get_pb_arg(op, \"operator\"))\n\n                if get_pb_arg_vali(op, \"cudnn_enabled\", None):\n                    op.arg.remove(get_pb_arg(op, \"cudnn_enabled\"))\n\n                num_groups = get_pb_arg_vali(op, \"num_groups\", None)\n                if num_groups is not None:\n                    op.arg.remove(get_pb_arg(op, \"num_groups\"))\n                    check_set_pb_arg(op, \"group\", \"i\", num_groups)\n\n                op.type = \"GroupNorm\"\n                count += 1\n    if count > 1:\n        logger.info(\"Replaced {} ATen operator to GroupNormOp\".format(count))\n\n\n# ==== torch/utils_toffee/alias.py =============================================\n\n\ndef alias(x, name, is_backward=False):\n    if not torch.onnx.is_in_onnx_export():\n        return x\n    assert isinstance(x, torch.Tensor)\n    return torch.ops._caffe2.AliasWithName(x, name, is_backward=is_backward)\n\n\ndef fuse_alias_placeholder(predict_net, init_net):\n    \"\"\"Remove AliasWithName placeholder and rename the input/output of it\"\"\"\n    # First we finish all the re-naming\n    for i, op in enumerate(predict_net.op):\n        if op.type == \"AliasWithName\":\n            assert len(op.input) == 1\n            assert len(op.output) == 1\n            name = get_pb_arg_vals(op, \"name\", None).decode()\n            is_backward = bool(get_pb_arg_vali(op, \"is_backward\", 0))\n            rename_op_input(predict_net, init_net, i, 0, name, from_producer=is_backward)\n            rename_op_output(predict_net, i, 0, name)\n\n    # Remove AliasWithName, should be very safe since it's a non-op\n    new_ops = []\n    for op in predict_net.op:\n        if op.type != \"AliasWithName\":\n            new_ops.append(op)\n        else:\n            # safety check\n            assert op.input == op.output\n            assert op.input[0] == op.arg[0].s.decode()\n    del predict_net.op[:]\n    predict_net.op.extend(new_ops)\n\n\n# ==== torch/utils_caffe2/graph_transform.py ===================================\n\n\nclass IllegalGraphTransformError(ValueError):\n    \"\"\"When a graph transform function call can't be executed.\"\"\"\n\n\ndef _rename_versioned_blob_in_proto(\n    proto: caffe2_pb2.NetDef,\n    old_name: str,\n    new_name: str,\n    version: int,\n    ssa: List[Tuple[List[Tuple[str, int]], List[Tuple[str, int]]]],\n    start_versions: Dict[str, int],\n    end_versions: Dict[str, int],\n):\n    \"\"\"In given proto, rename all blobs with matched version\"\"\"\n    # Operater list\n    for op, i_th_ssa in zip(proto.op, ssa):\n        versioned_inputs, versioned_outputs = i_th_ssa\n        for i in range(len(op.input)):\n            if versioned_inputs[i] == (old_name, version):\n                op.input[i] = new_name\n        for i in range(len(op.output)):\n            if versioned_outputs[i] == (old_name, version):\n                op.output[i] = new_name\n    # external_input\n    if start_versions.get(old_name, 0) == version:\n        for i in range(len(proto.external_input)):\n            if proto.external_input[i] == old_name:\n                proto.external_input[i] = new_name\n    # external_output\n    if end_versions.get(old_name, 0) == version:\n        for i in range(len(proto.external_output)):\n            if proto.external_output[i] == old_name:\n                proto.external_output[i] = new_name\n\n\ndef rename_op_input(\n    predict_net: caffe2_pb2.NetDef,\n    init_net: caffe2_pb2.NetDef,\n    op_id: int,\n    input_id: int,\n    new_name: str,\n    from_producer: bool = False,\n):\n    \"\"\"\n    Rename the op_id-th operator in predict_net, change it's input_id-th input's\n        name to the new_name. It also does automatic re-route and change\n        external_input and init_net if necessary.\n    - It requires the input is only consumed by this op.\n    - This function modifies predict_net and init_net in-place.\n    - When from_producer is enable, this also updates other operators that consumes\n        the same input. Be cautious because may trigger unintended behavior.\n    \"\"\"\n    assert isinstance(predict_net, caffe2_pb2.NetDef)\n    assert isinstance(init_net, caffe2_pb2.NetDef)\n\n    init_net_ssa, init_net_versions = core.get_ssa(init_net)\n    predict_net_ssa, predict_net_versions = core.get_ssa(\n        predict_net, copy.deepcopy(init_net_versions)\n    )\n\n    versioned_inputs, versioned_outputs = predict_net_ssa[op_id]\n    old_name, version = versioned_inputs[input_id]\n\n    if from_producer:\n        producer_map = get_producer_map(predict_net_ssa)\n        if not (old_name, version) in producer_map:\n            raise NotImplementedError(\n                \"Can't find producer, the input {} is probably from\"\n                \" init_net, this is not supported yet.\".format(old_name)\n            )\n        producer = producer_map[(old_name, version)]\n        rename_op_output(predict_net, producer[0], producer[1], new_name)\n        return\n\n    def contain_targets(op_ssa):\n        return (old_name, version) in op_ssa[0]\n\n    is_consumer = [contain_targets(op_ssa) for op_ssa in predict_net_ssa]\n    if sum(is_consumer) > 1:\n        raise IllegalGraphTransformError(\n            (\n                \"Input '{}' of operator(#{}) are consumed by other ops, please use\"\n                + \" rename_op_output on the producer instead. Offending op: \\n{}\"\n            ).format(old_name, op_id, predict_net.op[op_id])\n        )\n\n    # update init_net\n    _rename_versioned_blob_in_proto(\n        init_net, old_name, new_name, version, init_net_ssa, {}, init_net_versions\n    )\n    # update predict_net\n    _rename_versioned_blob_in_proto(\n        predict_net,\n        old_name,\n        new_name,\n        version,\n        predict_net_ssa,\n        init_net_versions,\n        predict_net_versions,\n    )\n\n\ndef rename_op_output(predict_net: caffe2_pb2.NetDef, op_id: int, output_id: int, new_name: str):\n    \"\"\"\n    Rename the op_id-th operator in predict_net, change it's output_id-th input's\n        name to the new_name. It also does automatic re-route and change\n        external_output and if necessary.\n    - It allows multiple consumers of its output.\n    - This function modifies predict_net in-place, doesn't need init_net.\n    \"\"\"\n    assert isinstance(predict_net, caffe2_pb2.NetDef)\n\n    ssa, blob_versions = core.get_ssa(predict_net)\n\n    versioned_inputs, versioned_outputs = ssa[op_id]\n    old_name, version = versioned_outputs[output_id]\n\n    # update predict_net\n    _rename_versioned_blob_in_proto(\n        predict_net, old_name, new_name, version, ssa, {}, blob_versions\n    )\n\n\ndef get_sub_graph_external_input_output(\n    predict_net: caffe2_pb2.NetDef, sub_graph_op_indices: List[int]\n) -> Tuple[List[Tuple[str, int]], List[Tuple[str, int]]]:\n    \"\"\"\n    Return the list of external input/output of sub-graph,\n    each element is tuple of the name and corresponding version in predict_net.\n\n    external input/output is defined the same way as caffe2 NetDef.\n    \"\"\"\n    ssa, versions = core.get_ssa(predict_net)\n\n    all_inputs = []\n    all_outputs = []\n    for op_id in sub_graph_op_indices:\n        all_inputs += [inp for inp in ssa[op_id][0] if inp not in all_inputs]\n        all_outputs += list(ssa[op_id][1])  # ssa output won't repeat\n\n    # for versioned blobs, external inputs are just those blob in all_inputs\n    # but not in all_outputs\n    ext_inputs = [inp for inp in all_inputs if inp not in all_outputs]\n\n    # external outputs are essentially outputs of this subgraph that are used\n    # outside of this sub-graph (including predict_net.external_output)\n    all_other_inputs = sum(\n        (ssa[i][0] for i in range(len(ssa)) if i not in sub_graph_op_indices),\n        [(outp, versions[outp]) for outp in predict_net.external_output],\n    )\n    ext_outputs = [outp for outp in all_outputs if outp in set(all_other_inputs)]\n\n    return ext_inputs, ext_outputs\n\n\nclass DiGraph:\n    \"\"\"A DAG representation of caffe2 graph, each vertice is a versioned blob.\"\"\"\n\n    def __init__(self):\n        self.vertices = set()\n        self.graph = collections.defaultdict(list)\n\n    def add_edge(self, u, v):\n        self.graph[u].append(v)\n        self.vertices.add(u)\n        self.vertices.add(v)\n\n    # grab from https://www.geeksforgeeks.org/find-paths-given-source-destination/\n    def get_all_paths(self, s, d):\n        visited = {k: False for k in self.vertices}\n        path = []\n        all_paths = []\n\n        def _get_all_paths_util(graph, u, d, visited, path):\n            visited[u] = True\n            path.append(u)\n            if u == d:\n                all_paths.append(copy.deepcopy(path))\n            else:\n                for i in graph[u]:\n                    if not visited[i]:\n                        _get_all_paths_util(graph, i, d, visited, path)\n            path.pop()\n            visited[u] = False\n\n        _get_all_paths_util(self.graph, s, d, visited, path)\n        return all_paths\n\n    @staticmethod\n    def from_ssa(ssa):\n        graph = DiGraph()\n        for op_id in range(len(ssa)):\n            for inp in ssa[op_id][0]:\n                for outp in ssa[op_id][1]:\n                    graph.add_edge(inp, outp)\n        return graph\n\n\ndef _get_dependency_chain(ssa, versioned_target, versioned_source):\n    \"\"\"\n    Return the index list of relevant operator to produce target blob from source blob,\n        if there's no dependency, return empty list.\n    \"\"\"\n\n    # finding all paths between nodes can be O(N!), thus we can only search\n    # in the subgraph using the op starting from the first consumer of source blob\n    # to the producer of the target blob.\n    consumer_map = get_consumer_map(ssa)\n    producer_map = get_producer_map(ssa)\n    start_op = min(x[0] for x in consumer_map[versioned_source]) - 15\n    end_op = (\n        producer_map[versioned_target][0] + 15 if versioned_target in producer_map else start_op\n    )\n    sub_graph_ssa = ssa[start_op : end_op + 1]\n    if len(sub_graph_ssa) > 30:\n        logger.warning(\n            \"Subgraph bebetween {} and {} is large (from op#{} to op#{}), it\"\n            \" might take non-trival time to find all paths between them.\".format(\n                versioned_source, versioned_target, start_op, end_op\n            )\n        )\n\n    dag = DiGraph.from_ssa(sub_graph_ssa)\n    paths = dag.get_all_paths(versioned_source, versioned_target)  # include two ends\n    ops_in_paths = [[producer_map[blob][0] for blob in path[1:]] for path in paths]\n    return sorted(set().union(*[set(ops) for ops in ops_in_paths]))\n\n\ndef identify_reshape_sub_graph(predict_net: caffe2_pb2.NetDef) -> List[List[int]]:\n    \"\"\"\n    Idenfity the reshape sub-graph in a protobuf.\n    The reshape sub-graph is defined as matching the following pattern:\n\n    (input_blob) -> Op_1 -> ... -> Op_N -> (new_shape) -─┐\n        └-------------------------------------------> Reshape -> (output_blob)\n\n    Return:\n        List of sub-graphs, each sub-graph is represented as a list of indices\n        of the relavent ops, [Op_1, Op_2, ..., Op_N, Reshape]\n    \"\"\"\n\n    ssa, _ = core.get_ssa(predict_net)\n\n    ret = []\n    for i, op in enumerate(predict_net.op):\n        if op.type == \"Reshape\":\n            assert len(op.input) == 2\n            input_ssa = ssa[i][0]\n            data_source = input_ssa[0]\n            shape_source = input_ssa[1]\n            op_indices = _get_dependency_chain(ssa, shape_source, data_source)\n            ret.append(op_indices + [i])\n    return ret\n\n\ndef remove_reshape_for_fc(predict_net, params):\n    \"\"\"\n    In PyTorch nn.Linear has to take 2D tensor, this often leads to reshape\n        a 4D tensor to 2D by calling .view(). However this (dynamic) reshaping\n        doesn't work well with ONNX and Int8 tools, and cause using extra\n        ops (eg. ExpandDims) that might not be available on mobile.\n    Luckily Caffe2 supports 4D tensor for FC, so we can remove those reshape\n        after exporting ONNX model.\n    \"\"\"\n    from caffe2.python import core\n\n    # find all reshape sub-graph that can be removed, which is now all Reshape\n    # sub-graph whose output is only consumed by FC.\n    # TODO: to make it safer, we may need the actually value to better determine\n    # if a Reshape before FC is removable.\n    reshape_sub_graphs = identify_reshape_sub_graph(predict_net)\n    sub_graphs_to_remove = []\n    for reshape_sub_graph in reshape_sub_graphs:\n        reshape_op_id = reshape_sub_graph[-1]\n        assert predict_net.op[reshape_op_id].type == \"Reshape\"\n        ssa, _ = core.get_ssa(predict_net)\n        reshape_output = ssa[reshape_op_id][1][0]\n        consumers = [i for i in range(len(ssa)) if reshape_output in ssa[i][0]]\n        if all(predict_net.op[consumer].type == \"FC\" for consumer in consumers):\n            # safety check if the sub-graph is isolated, for this reshape sub-graph,\n            # it means it has one non-param external input and one external output.\n            ext_inputs, ext_outputs = get_sub_graph_external_input_output(\n                predict_net, reshape_sub_graph\n            )\n            non_params_ext_inputs = [inp for inp in ext_inputs if inp[1] != 0]\n            if len(non_params_ext_inputs) == 1 and len(ext_outputs) == 1:\n                sub_graphs_to_remove.append(reshape_sub_graph)\n\n    # perform removing subgraph by:\n    # 1: rename the Reshape's output to its input, then the graph can be\n    #   seen as in-place itentify, meaning whose external input/output are the same.\n    # 2: simply remove those ops.\n    remove_op_ids = []\n    params_to_remove = []\n    for sub_graph in sub_graphs_to_remove:\n        logger.info(\n            \"Remove Reshape sub-graph:\\n{}\".format(\n                \"\".join([\"(#{:>4})\\n{}\".format(i, predict_net.op[i]) for i in sub_graph])\n            )\n        )\n        reshape_op_id = sub_graph[-1]\n        new_reshap_output = predict_net.op[reshape_op_id].input[0]\n        rename_op_output(predict_net, reshape_op_id, 0, new_reshap_output)\n        ext_inputs, ext_outputs = get_sub_graph_external_input_output(predict_net, sub_graph)\n        non_params_ext_inputs = [inp for inp in ext_inputs if inp[1] != 0]\n        params_ext_inputs = [inp for inp in ext_inputs if inp[1] == 0]\n        assert len(non_params_ext_inputs) == 1 and len(ext_outputs) == 1\n        assert ext_outputs[0][0] == non_params_ext_inputs[0][0]\n        assert ext_outputs[0][1] == non_params_ext_inputs[0][1] + 1\n        remove_op_ids.extend(sub_graph)\n        params_to_remove.extend(params_ext_inputs)\n\n    predict_net = copy.deepcopy(predict_net)\n    new_ops = [op for i, op in enumerate(predict_net.op) if i not in remove_op_ids]\n    del predict_net.op[:]\n    predict_net.op.extend(new_ops)\n    for versioned_params in params_to_remove:\n        name = versioned_params[0]\n        logger.info(\"Remove params: {} from init_net and predict_net.external_input\".format(name))\n        del params[name]\n        predict_net.external_input.remove(name)\n\n    return predict_net, params\n\n\ndef fuse_copy_between_cpu_and_gpu(predict_net: caffe2_pb2.NetDef):\n    \"\"\"\n    In-place fuse extra copy ops between cpu/gpu for the following case:\n        a -CopyAToB-> b -CopyBToA> c1 -NextOp1-> d1\n                        -CopyBToA> c2 -NextOp2-> d2\n    The fused network will look like:\n        a -NextOp1-> d1\n          -NextOp2-> d2\n    \"\"\"\n\n    _COPY_OPS = [\"CopyCPUToGPU\", \"CopyGPUToCPU\"]\n\n    def _fuse_once(predict_net):\n        ssa, blob_versions = core.get_ssa(predict_net)\n        consumer_map = get_consumer_map(ssa)\n        versioned_external_output = [\n            (name, blob_versions[name]) for name in predict_net.external_output\n        ]\n\n        for op_id, op in enumerate(predict_net.op):\n            if op.type in _COPY_OPS:\n                fw_copy_versioned_output = ssa[op_id][1][0]\n                consumer_ids = [x[0] for x in consumer_map[fw_copy_versioned_output]]\n                reverse_op_type = _COPY_OPS[1 - _COPY_OPS.index(op.type)]\n\n                is_fusable = (\n                    len(consumer_ids) > 0\n                    and fw_copy_versioned_output not in versioned_external_output\n                    and all(\n                        predict_net.op[_op_id].type == reverse_op_type\n                        and ssa[_op_id][1][0] not in versioned_external_output\n                        for _op_id in consumer_ids\n                    )\n                )\n\n                if is_fusable:\n                    for rv_copy_op_id in consumer_ids:\n                        # making each NextOp uses \"a\" directly and removing Copy ops\n                        rs_copy_versioned_output = ssa[rv_copy_op_id][1][0]\n                        next_op_id, inp_id = consumer_map[rs_copy_versioned_output][0]\n                        predict_net.op[next_op_id].input[inp_id] = op.input[0]\n                    # remove CopyOps\n                    new_ops = [\n                        op\n                        for i, op in enumerate(predict_net.op)\n                        if i != op_id and i not in consumer_ids\n                    ]\n                    del predict_net.op[:]\n                    predict_net.op.extend(new_ops)\n                    return True\n\n        return False\n\n    # _fuse_once returns False is nothing can be fused\n    while _fuse_once(predict_net):\n        pass\n\n\ndef remove_dead_end_ops(net_def: caffe2_pb2.NetDef):\n    \"\"\"remove ops if its output is not used or not in external_output\"\"\"\n    ssa, versions = core.get_ssa(net_def)\n    versioned_external_output = [(name, versions[name]) for name in net_def.external_output]\n    consumer_map = get_consumer_map(ssa)\n    removed_op_ids = set()\n\n    def _is_dead_end(versioned_blob):\n        return not (\n            versioned_blob in versioned_external_output\n            or (\n                len(consumer_map[versioned_blob]) > 0\n                and all(x[0] not in removed_op_ids for x in consumer_map[versioned_blob])\n            )\n        )\n\n    for i, ssa_i in reversed(list(enumerate(ssa))):\n        versioned_outputs = ssa_i[1]\n        if all(_is_dead_end(outp) for outp in versioned_outputs):\n            removed_op_ids.add(i)\n\n    # simply removing those deadend ops should have no effect to external_output\n    new_ops = [op for i, op in enumerate(net_def.op) if i not in removed_op_ids]\n    del net_def.op[:]\n    net_def.op.extend(new_ops)\n"
  },
  {
    "path": "VPS_Module/detectron2/export/torchscript.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport os\nimport torch\n\nfrom detectron2.utils.file_io import PathManager\n\nfrom .torchscript_patch import freeze_training_mode, patch_instances\n\n__all__ = [\"scripting_with_instances\", \"dump_torchscript_IR\"]\n\n\ndef scripting_with_instances(model, fields):\n    \"\"\"\n    Run :func:`torch.jit.script` on a model that uses the :class:`Instances` class. Since\n    attributes of :class:`Instances` are \"dynamically\" added in eager mode，it is difficult\n    for scripting to support it out of the box. This function is made to support scripting\n    a model that uses :class:`Instances`. It does the following:\n\n    1. Create a scriptable ``new_Instances`` class which behaves similarly to ``Instances``,\n       but with all attributes been \"static\".\n       The attributes need to be statically declared in the ``fields`` argument.\n    2. Register ``new_Instances``, and force scripting compiler to\n       use it when trying to compile ``Instances``.\n\n    After this function, the process will be reverted. User should be able to script another model\n    using different fields.\n\n    Example:\n        Assume that ``Instances`` in the model consist of two attributes named\n        ``proposal_boxes`` and ``objectness_logits`` with type :class:`Boxes` and\n        :class:`Tensor` respectively during inference. You can call this function like:\n        ::\n            fields = {\"proposal_boxes\": Boxes, \"objectness_logits\": torch.Tensor}\n            torchscipt_model =  scripting_with_instances(model, fields)\n\n    Note:\n        It only support models in evaluation mode.\n\n    Args:\n        model (nn.Module): The input model to be exported by scripting.\n        fields (Dict[str, type]): Attribute names and corresponding type that\n            ``Instances`` will use in the model. Note that all attributes used in ``Instances``\n            need to be added, regardless of whether they are inputs/outputs of the model.\n            Data type not defined in detectron2 is not supported for now.\n\n    Returns:\n        torch.jit.ScriptModule: the model in torchscript format\n    \"\"\"\n    assert (\n        not model.training\n    ), \"Currently we only support exporting models in evaluation mode to torchscript\"\n\n    with freeze_training_mode(model), patch_instances(fields):\n        scripted_model = torch.jit.script(model)\n        return scripted_model\n\n\n# alias for old name\nexport_torchscript_with_instances = scripting_with_instances\n\n\ndef dump_torchscript_IR(model, dir):\n    \"\"\"\n    Dump IR of a TracedModule/ScriptModule/Function in various format (code, graph,\n    inlined graph). Useful for debugging.\n\n    Args:\n        model (TracedModule/ScriptModule/ScriptFUnction): traced or scripted module\n        dir (str): output directory to dump files.\n    \"\"\"\n    dir = os.path.expanduser(dir)\n    PathManager.mkdirs(dir)\n\n    def _get_script_mod(mod):\n        if isinstance(mod, torch.jit.TracedModule):\n            return mod._actual_script_module\n        return mod\n\n    # Dump pretty-printed code: https://pytorch.org/docs/stable/jit.html#inspecting-code\n    with PathManager.open(os.path.join(dir, \"model_ts_code.txt\"), \"w\") as f:\n\n        def get_code(mod):\n            # Try a few ways to get code using private attributes.\n            try:\n                # This contains more information than just `mod.code`\n                return _get_script_mod(mod)._c.code\n            except AttributeError:\n                pass\n            try:\n                return mod.code\n            except AttributeError:\n                return None\n\n        def dump_code(prefix, mod):\n            code = get_code(mod)\n            name = prefix or \"root model\"\n            if code is None:\n                f.write(f\"Could not found code for {name} (type={mod.original_name})\\n\")\n                f.write(\"\\n\")\n            else:\n                f.write(f\"\\nCode for {name}, type={mod.original_name}:\\n\")\n                f.write(code)\n                f.write(\"\\n\")\n                f.write(\"-\" * 80)\n\n            for name, m in mod.named_children():\n                dump_code(prefix + \".\" + name, m)\n\n        if isinstance(model, torch.jit.ScriptFunction):\n            f.write(get_code(model))\n        else:\n            dump_code(\"\", model)\n\n    def _get_graph(model):\n        try:\n            # Recursively dump IR of all modules\n            return _get_script_mod(model)._c.dump_to_str(True, False, False)\n        except AttributeError:\n            return model.graph.str()\n\n    with PathManager.open(os.path.join(dir, \"model_ts_IR.txt\"), \"w\") as f:\n        f.write(_get_graph(model))\n\n    # Dump IR of the entire graph (all submodules inlined)\n    with PathManager.open(os.path.join(dir, \"model_ts_IR_inlined.txt\"), \"w\") as f:\n        f.write(str(model.inlined_graph))\n\n    if not isinstance(model, torch.jit.ScriptFunction):\n        # Dump the model structure in pytorch style\n        with PathManager.open(os.path.join(dir, \"model.txt\"), \"w\") as f:\n            f.write(str(model))\n"
  },
  {
    "path": "VPS_Module/detectron2/export/torchscript_patch.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport os\nimport sys\nimport tempfile\nfrom contextlib import ExitStack, contextmanager\nfrom copy import deepcopy\nfrom unittest import mock\nimport torch\nfrom torch import nn\n\n# need some explicit imports due to https://github.com/pytorch/pytorch/issues/38964\nimport detectron2  # noqa F401\nfrom detectron2.structures import Boxes, Instances\nfrom detectron2.utils.env import _import_file\n\n_counter = 0\n\n\ndef _clear_jit_cache():\n    from torch.jit._recursive import concrete_type_store\n    from torch.jit._state import _jit_caching_layer\n\n    concrete_type_store.type_store.clear()  # for modules\n    _jit_caching_layer.clear()  # for free functions\n\n\ndef _add_instances_conversion_methods(newInstances):\n    \"\"\"\n    Add from_instances methods to the scripted Instances class.\n    \"\"\"\n    cls_name = newInstances.__name__\n\n    @torch.jit.unused\n    def from_instances(instances: Instances):\n        \"\"\"\n        Create scripted Instances from original Instances\n        \"\"\"\n        fields = instances.get_fields()\n        image_size = instances.image_size\n        ret = newInstances(image_size)\n        for name, val in fields.items():\n            assert hasattr(ret, f\"_{name}\"), f\"No attribute named {name} in {cls_name}\"\n            setattr(ret, name, deepcopy(val))\n        return ret\n\n    newInstances.from_instances = from_instances\n\n\n@contextmanager\ndef patch_instances(fields):\n    \"\"\"\n    A contextmanager, under which the Instances class in detectron2 is replaced\n    by a statically-typed scriptable class, defined by `fields`.\n    See more in `scripting_with_instances`.\n    \"\"\"\n\n    with tempfile.TemporaryDirectory(prefix=\"detectron2\") as dir, tempfile.NamedTemporaryFile(\n        mode=\"w\", encoding=\"utf-8\", suffix=\".py\", dir=dir, delete=False\n    ) as f:\n        try:\n            # Objects that use Instances should not reuse previously-compiled\n            # results in cache, because `Instances` could be a new class each time.\n            _clear_jit_cache()\n\n            cls_name, s = _gen_instance_module(fields)\n            f.write(s)\n            f.flush()\n            f.close()\n\n            module = _import(f.name)\n            new_instances = getattr(module, cls_name)\n            _ = torch.jit.script(new_instances)\n            # let torchscript think Instances was scripted already\n            Instances.__torch_script_class__ = True\n            # let torchscript find new_instances when looking for the jit type of Instances\n            Instances._jit_override_qualname = torch._jit_internal._qualified_name(new_instances)\n\n            _add_instances_conversion_methods(new_instances)\n            yield new_instances\n        finally:\n            try:\n                del Instances.__torch_script_class__\n                del Instances._jit_override_qualname\n            except AttributeError:\n                pass\n            sys.modules.pop(module.__name__)\n\n\ndef _gen_instance_class(fields):\n    \"\"\"\n    Args:\n        fields (dict[name: type])\n    \"\"\"\n\n    class _FieldType:\n        def __init__(self, name, type_):\n            assert isinstance(name, str), f\"Field name must be str, got {name}\"\n            self.name = name\n            self.type_ = type_\n            self.annotation = f\"{type_.__module__}.{type_.__name__}\"\n\n    fields = [_FieldType(k, v) for k, v in fields.items()]\n\n    def indent(level, s):\n        return \" \" * 4 * level + s\n\n    lines = []\n\n    global _counter\n    _counter += 1\n\n    cls_name = \"ScriptedInstances{}\".format(_counter)\n\n    field_names = tuple(x.name for x in fields)\n    extra_args = \", \".join([f\"{f.name}: Optional[{f.annotation}] = None\" for f in fields])\n    lines.append(\n        f\"\"\"\nclass {cls_name}:\n    def __init__(self, image_size: Tuple[int, int], {extra_args}):\n        self.image_size = image_size\n        self._field_names = {field_names}\n\"\"\"\n    )\n\n    for f in fields:\n        lines.append(\n            indent(2, f\"self._{f.name} = torch.jit.annotate(Optional[{f.annotation}], {f.name})\")\n        )\n\n    for f in fields:\n        lines.append(\n            f\"\"\"\n    @property\n    def {f.name}(self) -> {f.annotation}:\n        # has to use a local for type refinement\n        # https://pytorch.org/docs/stable/jit_language_reference.html#optional-type-refinement\n        t = self._{f.name}\n        assert t is not None, \"{f.name} is None and cannot be accessed!\"\n        return t\n\n    @{f.name}.setter\n    def {f.name}(self, value: {f.annotation}) -> None:\n        self._{f.name} = value\n\"\"\"\n        )\n\n    # support method `__len__`\n    lines.append(\n        \"\"\"\n    def __len__(self) -> int:\n\"\"\"\n    )\n    for f in fields:\n        lines.append(\n            f\"\"\"\n        t = self._{f.name}\n        if t is not None:\n            return len(t)\n\"\"\"\n        )\n    lines.append(\n        \"\"\"\n        raise NotImplementedError(\"Empty Instances does not support __len__!\")\n\"\"\"\n    )\n\n    # support method `has`\n    lines.append(\n        \"\"\"\n    def has(self, name: str) -> bool:\n\"\"\"\n    )\n    for f in fields:\n        lines.append(\n            f\"\"\"\n        if name == \"{f.name}\":\n            return self._{f.name} is not None\n\"\"\"\n        )\n    lines.append(\n        \"\"\"\n        return False\n\"\"\"\n    )\n\n    # support method `to`\n    none_args = \", None\" * len(fields)\n    lines.append(\n        f\"\"\"\n    def to(self, device: torch.device) -> \"{cls_name}\":\n        ret = {cls_name}(self.image_size{none_args})\n\"\"\"\n    )\n    for f in fields:\n        if hasattr(f.type_, \"to\"):\n            lines.append(\n                f\"\"\"\n        t = self._{f.name}\n        if t is not None:\n            ret._{f.name} = t.to(device)\n\"\"\"\n            )\n        else:\n            # For now, ignore fields that cannot be moved to devices.\n            # Maybe can support other tensor-like classes (e.g. __torch_function__)\n            pass\n    lines.append(\n        \"\"\"\n        return ret\n\"\"\"\n    )\n\n    # support method `getitem`\n    none_args = \", None\" * len(fields)\n    lines.append(\n        f\"\"\"\n    def __getitem__(self, item) -> \"{cls_name}\":\n        ret = {cls_name}(self.image_size{none_args})\n\"\"\"\n    )\n    for f in fields:\n        lines.append(\n            f\"\"\"\n        t = self._{f.name}\n        if t is not None:\n            ret._{f.name} = t[item]\n\"\"\"\n        )\n    lines.append(\n        \"\"\"\n        return ret\n\"\"\"\n    )\n\n    # support method `cat`\n    # this version does not contain checks that all instances have same size and fields\n    none_args = \", None\" * len(fields)\n    lines.append(\n        f\"\"\"\n    def cat(self, instances: List[\"{cls_name}\"]) -> \"{cls_name}\":\n        ret = {cls_name}(self.image_size{none_args})\n\"\"\"\n    )\n    for f in fields:\n        lines.append(\n            f\"\"\"\n        t = self._{f.name}\n        if t is not None:\n            values: List[{f.annotation}] = [x.{f.name} for x in instances]\n            if torch.jit.isinstance(t, torch.Tensor):\n                ret._{f.name} = torch.cat(values, dim=0)\n            else:\n                ret._{f.name} = t.cat(values)\n\"\"\"\n        )\n    lines.append(\n        \"\"\"\n        return ret\"\"\"\n    )\n\n    # support method `get_fields()`\n    lines.append(\n        \"\"\"\n    def get_fields(self) -> Dict[str, Tensor]:\n        ret = {}\n    \"\"\"\n    )\n    for f in fields:\n        if f.type_ == Boxes:\n            stmt = \"t.tensor\"\n        elif f.type_ == torch.Tensor:\n            stmt = \"t\"\n        else:\n            stmt = f'assert False, \"unsupported type {str(f.type_)}\"'\n        lines.append(\n            f\"\"\"\n        t = self._{f.name}\n        if t is not None:\n            ret[\"{f.name}\"] = {stmt}\n        \"\"\"\n        )\n    lines.append(\n        \"\"\"\n        return ret\"\"\"\n    )\n    return cls_name, os.linesep.join(lines)\n\n\ndef _gen_instance_module(fields):\n    # TODO: find a more automatic way to enable import of other classes\n    s = \"\"\"\nfrom copy import deepcopy\nimport torch\nfrom torch import Tensor\nimport typing\nfrom typing import *\n\nimport detectron2\nfrom detectron2.structures import Boxes, Instances\n\n\"\"\"\n\n    cls_name, cls_def = _gen_instance_class(fields)\n    s += cls_def\n    return cls_name, s\n\n\ndef _import(path):\n    return _import_file(\n        \"{}{}\".format(sys.modules[__name__].__name__, _counter), path, make_importable=True\n    )\n\n\n@contextmanager\ndef patch_builtin_len(modules=()):\n    \"\"\"\n    Patch the builtin len() function of a few detectron2 modules\n    to use __len__ instead, because __len__ does not convert values to\n    integers and therefore is friendly to tracing.\n\n    Args:\n        modules (list[stsr]): names of extra modules to patch len(), in\n            addition to those in detectron2.\n    \"\"\"\n\n    def _new_len(obj):\n        return obj.__len__()\n\n    with ExitStack() as stack:\n        MODULES = [\n            \"detectron2.modeling.roi_heads.fast_rcnn\",\n            \"detectron2.modeling.roi_heads.mask_head\",\n            \"detectron2.modeling.roi_heads.keypoint_head\",\n        ] + list(modules)\n        ctxs = [stack.enter_context(mock.patch(mod + \".len\")) for mod in MODULES]\n        for m in ctxs:\n            m.side_effect = _new_len\n        yield\n\n\ndef patch_nonscriptable_classes():\n    \"\"\"\n    Apply patches on a few nonscriptable detectron2 classes.\n    Should not have side-effects on eager usage.\n    \"\"\"\n    # __prepare_scriptable__ can also be added to models for easier maintenance.\n    # But it complicates the clean model code.\n\n    from detectron2.modeling.backbone import ResNet, FPN\n\n    # Due to https://github.com/pytorch/pytorch/issues/36061,\n    # we change backbone to use ModuleList for scripting.\n    # (note: this changes param names in state_dict)\n\n    def prepare_resnet(self):\n        ret = deepcopy(self)\n        ret.stages = nn.ModuleList(ret.stages)\n        for k in self.stage_names:\n            delattr(ret, k)\n        return ret\n\n    ResNet.__prepare_scriptable__ = prepare_resnet\n\n    def prepare_fpn(self):\n        ret = deepcopy(self)\n        ret.lateral_convs = nn.ModuleList(ret.lateral_convs)\n        ret.output_convs = nn.ModuleList(ret.output_convs)\n        for name, _ in self.named_children():\n            if name.startswith(\"fpn_\"):\n                delattr(ret, name)\n        return ret\n\n    FPN.__prepare_scriptable__ = prepare_fpn\n\n    # Annotate some attributes to be constants for the purpose of scripting,\n    # even though they are not constants in eager mode.\n    from detectron2.modeling.roi_heads import StandardROIHeads\n\n    if hasattr(StandardROIHeads, \"__annotations__\"):\n        # copy first to avoid editing annotations of base class\n        StandardROIHeads.__annotations__ = deepcopy(StandardROIHeads.__annotations__)\n        StandardROIHeads.__annotations__[\"mask_on\"] = torch.jit.Final[bool]\n        StandardROIHeads.__annotations__[\"keypoint_on\"] = torch.jit.Final[bool]\n\n\n# These patches are not supposed to have side-effects.\npatch_nonscriptable_classes()\n\n\n@contextmanager\ndef freeze_training_mode(model):\n    \"\"\"\n    A context manager that annotates the \"training\" attribute of every submodule\n    to constant, so that the training codepath in these modules can be\n    meta-compiled away. Upon exiting, the annotations are reverted.\n    \"\"\"\n    classes = {type(x) for x in model.modules()}\n    # __constants__ is the old way to annotate constants and not compatible\n    # with __annotations__ .\n    classes = {x for x in classes if not hasattr(x, \"__constants__\")}\n    for cls in classes:\n        cls.__annotations__[\"training\"] = torch.jit.Final[bool]\n    yield\n    for cls in classes:\n        cls.__annotations__[\"training\"] = bool\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom .batch_norm import FrozenBatchNorm2d, get_norm, NaiveSyncBatchNorm, CycleBatchNormList\nfrom .deform_conv import DeformConv, ModulatedDeformConv\nfrom .mask_ops import paste_masks_in_image\nfrom .nms import batched_nms, batched_nms_rotated, nms, nms_rotated\nfrom .roi_align import ROIAlign, roi_align\nfrom .roi_align_rotated import ROIAlignRotated, roi_align_rotated\nfrom .shape_spec import ShapeSpec\nfrom .wrappers import (\n    BatchNorm2d,\n    Conv2d,\n    ConvTranspose2d,\n    cat,\n    interpolate,\n    Linear,\n    nonzero_tuple,\n    cross_entropy,\n    shapes_to_tensor,\n)\nfrom .blocks import CNNBlockBase, DepthwiseSeparableConv2d\nfrom .aspp import ASPP\nfrom .losses import ciou_loss, diou_loss\n\n__all__ = [k for k in globals().keys() if not k.startswith(\"_\")]\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/aspp.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom copy import deepcopy\nimport fvcore.nn.weight_init as weight_init\nimport torch\nfrom torch import nn\nfrom torch.nn import functional as F\n\nfrom .batch_norm import get_norm\nfrom .blocks import DepthwiseSeparableConv2d\nfrom .wrappers import Conv2d\n\n\nclass ASPP(nn.Module):\n    \"\"\"\n    Atrous Spatial Pyramid Pooling (ASPP).\n    \"\"\"\n\n    def __init__(\n        self,\n        in_channels,\n        out_channels,\n        dilations,\n        *,\n        norm,\n        activation,\n        pool_kernel_size=None,\n        dropout: float = 0.0,\n        use_depthwise_separable_conv=False,\n    ):\n        \"\"\"\n        Args:\n            in_channels (int): number of input channels for ASPP.\n            out_channels (int): number of output channels.\n            dilations (list): a list of 3 dilations in ASPP.\n            norm (str or callable): normalization for all conv layers.\n                See :func:`layers.get_norm` for supported format. norm is\n                applied to all conv layers except the conv following\n                global average pooling.\n            activation (callable): activation function.\n            pool_kernel_size (tuple, list): the average pooling size (kh, kw)\n                for image pooling layer in ASPP. If set to None, it always\n                performs global average pooling. If not None, it must be\n                divisible by the shape of inputs in forward(). It is recommended\n                to use a fixed input feature size in training, and set this\n                option to match this size, so that it performs global average\n                pooling in training, and the size of the pooling window stays\n                consistent in inference.\n            dropout (float): apply dropout on the output of ASPP. It is used in\n                the official DeepLab implementation with a rate of 0.1:\n                https://github.com/tensorflow/models/blob/21b73d22f3ed05b650e85ac50849408dd36de32e/research/deeplab/model.py#L532  # noqa\n            use_depthwise_separable_conv (bool): use DepthwiseSeparableConv2d\n                for 3x3 convs in ASPP, proposed in :paper:`DeepLabV3+`.\n        \"\"\"\n        super(ASPP, self).__init__()\n        assert len(dilations) == 3, \"ASPP expects 3 dilations, got {}\".format(len(dilations))\n        self.pool_kernel_size = pool_kernel_size\n        self.dropout = dropout\n        use_bias = norm == \"\"\n        self.convs = nn.ModuleList()\n        # conv 1x1\n        self.convs.append(\n            Conv2d(\n                in_channels,\n                out_channels,\n                kernel_size=1,\n                bias=use_bias,\n                norm=get_norm(norm, out_channels),\n                activation=deepcopy(activation),\n            )\n        )\n        weight_init.c2_xavier_fill(self.convs[-1])\n        # atrous convs\n        for dilation in dilations:\n            if use_depthwise_separable_conv:\n                self.convs.append(\n                    DepthwiseSeparableConv2d(\n                        in_channels,\n                        out_channels,\n                        kernel_size=3,\n                        padding=dilation,\n                        dilation=dilation,\n                        norm1=norm,\n                        activation1=deepcopy(activation),\n                        norm2=norm,\n                        activation2=deepcopy(activation),\n                    )\n                )\n            else:\n                self.convs.append(\n                    Conv2d(\n                        in_channels,\n                        out_channels,\n                        kernel_size=3,\n                        padding=dilation,\n                        dilation=dilation,\n                        bias=use_bias,\n                        norm=get_norm(norm, out_channels),\n                        activation=deepcopy(activation),\n                    )\n                )\n                weight_init.c2_xavier_fill(self.convs[-1])\n        # image pooling\n        # We do not add BatchNorm because the spatial resolution is 1x1,\n        # the original TF implementation has BatchNorm.\n        if pool_kernel_size is None:\n            image_pooling = nn.Sequential(\n                nn.AdaptiveAvgPool2d(1),\n                Conv2d(in_channels, out_channels, 1, bias=True, activation=deepcopy(activation)),\n            )\n        else:\n            image_pooling = nn.Sequential(\n                nn.AvgPool2d(kernel_size=pool_kernel_size, stride=1),\n                Conv2d(in_channels, out_channels, 1, bias=True, activation=deepcopy(activation)),\n            )\n        weight_init.c2_xavier_fill(image_pooling[1])\n        self.convs.append(image_pooling)\n\n        self.project = Conv2d(\n            5 * out_channels,\n            out_channels,\n            kernel_size=1,\n            bias=use_bias,\n            norm=get_norm(norm, out_channels),\n            activation=deepcopy(activation),\n        )\n        weight_init.c2_xavier_fill(self.project)\n\n    def forward(self, x):\n        size = x.shape[-2:]\n        if self.pool_kernel_size is not None:\n            if size[0] % self.pool_kernel_size[0] or size[1] % self.pool_kernel_size[1]:\n                raise ValueError(\n                    \"`pool_kernel_size` must be divisible by the shape of inputs. \"\n                    \"Input size: {} `pool_kernel_size`: {}\".format(size, self.pool_kernel_size)\n                )\n        res = []\n        for conv in self.convs:\n            res.append(conv(x))\n        res[-1] = F.interpolate(res[-1], size=size, mode=\"bilinear\", align_corners=False)\n        res = torch.cat(res, dim=1)\n        res = self.project(res)\n        res = F.dropout(res, self.dropout, training=self.training) if self.dropout > 0 else res\n        return res\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/batch_norm.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport torch\nimport torch.distributed as dist\nfrom fvcore.nn.distributed import differentiable_all_reduce\nfrom torch import nn\nfrom torch.nn import functional as F\n\nfrom detectron2.utils import comm, env\n\nfrom .wrappers import BatchNorm2d\n\n\nclass FrozenBatchNorm2d(nn.Module):\n    \"\"\"\n    BatchNorm2d where the batch statistics and the affine parameters are fixed.\n\n    It contains non-trainable buffers called\n    \"weight\" and \"bias\", \"running_mean\", \"running_var\",\n    initialized to perform identity transformation.\n\n    The pre-trained backbone models from Caffe2 only contain \"weight\" and \"bias\",\n    which are computed from the original four parameters of BN.\n    The affine transform `x * weight + bias` will perform the equivalent\n    computation of `(x - running_mean) / sqrt(running_var) * weight + bias`.\n    When loading a backbone model from Caffe2, \"running_mean\" and \"running_var\"\n    will be left unchanged as identity transformation.\n\n    Other pre-trained backbone models may contain all 4 parameters.\n\n    The forward is implemented by `F.batch_norm(..., training=False)`.\n    \"\"\"\n\n    _version = 3\n\n    def __init__(self, num_features, eps=1e-5):\n        super().__init__()\n        self.num_features = num_features\n        self.eps = eps\n        self.register_buffer(\"weight\", torch.ones(num_features))\n        self.register_buffer(\"bias\", torch.zeros(num_features))\n        self.register_buffer(\"running_mean\", torch.zeros(num_features))\n        self.register_buffer(\"running_var\", torch.ones(num_features) - eps)\n\n    def forward(self, x):\n        if x.requires_grad:\n            # When gradients are needed, F.batch_norm will use extra memory\n            # because its backward op computes gradients for weight/bias as well.\n            scale = self.weight * (self.running_var + self.eps).rsqrt()\n            bias = self.bias - self.running_mean * scale\n            scale = scale.reshape(1, -1, 1, 1)\n            bias = bias.reshape(1, -1, 1, 1)\n            out_dtype = x.dtype  # may be half\n            return x * scale.to(out_dtype) + bias.to(out_dtype)\n        else:\n            # When gradients are not needed, F.batch_norm is a single fused op\n            # and provide more optimization opportunities.\n            return F.batch_norm(\n                x,\n                self.running_mean,\n                self.running_var,\n                self.weight,\n                self.bias,\n                training=False,\n                eps=self.eps,\n            )\n\n    def _load_from_state_dict(\n        self, state_dict, prefix, local_metadata, strict, missing_keys, unexpected_keys, error_msgs\n    ):\n        version = local_metadata.get(\"version\", None)\n\n        if version is None or version < 2:\n            # No running_mean/var in early versions\n            # This will silent the warnings\n            if prefix + \"running_mean\" not in state_dict:\n                state_dict[prefix + \"running_mean\"] = torch.zeros_like(self.running_mean)\n            if prefix + \"running_var\" not in state_dict:\n                state_dict[prefix + \"running_var\"] = torch.ones_like(self.running_var)\n\n        super()._load_from_state_dict(\n            state_dict, prefix, local_metadata, strict, missing_keys, unexpected_keys, error_msgs\n        )\n\n    def __repr__(self):\n        return \"FrozenBatchNorm2d(num_features={}, eps={})\".format(self.num_features, self.eps)\n\n    @classmethod\n    def convert_frozen_batchnorm(cls, module):\n        \"\"\"\n        Convert all BatchNorm/SyncBatchNorm in module into FrozenBatchNorm.\n\n        Args:\n            module (torch.nn.Module):\n\n        Returns:\n            If module is BatchNorm/SyncBatchNorm, returns a new module.\n            Otherwise, in-place convert module and return it.\n\n        Similar to convert_sync_batchnorm in\n        https://github.com/pytorch/pytorch/blob/master/torch/nn/modules/batchnorm.py\n        \"\"\"\n        bn_module = nn.modules.batchnorm\n        bn_module = (bn_module.BatchNorm2d, bn_module.SyncBatchNorm)\n        res = module\n        if isinstance(module, bn_module):\n            res = cls(module.num_features)\n            if module.affine:\n                res.weight.data = module.weight.data.clone().detach()\n                res.bias.data = module.bias.data.clone().detach()\n            res.running_mean.data = module.running_mean.data\n            res.running_var.data = module.running_var.data\n            res.eps = module.eps\n        else:\n            for name, child in module.named_children():\n                new_child = cls.convert_frozen_batchnorm(child)\n                if new_child is not child:\n                    res.add_module(name, new_child)\n        return res\n\n\ndef get_norm(norm, out_channels):\n    \"\"\"\n    Args:\n        norm (str or callable): either one of BN, SyncBN, FrozenBN, GN;\n            or a callable that takes a channel number and returns\n            the normalization layer as a nn.Module.\n\n    Returns:\n        nn.Module or None: the normalization layer\n    \"\"\"\n    if norm is None:\n        return None\n    if isinstance(norm, str):\n        if len(norm) == 0:\n            return None\n        norm = {\n            \"BN\": BatchNorm2d,\n            # Fixed in https://github.com/pytorch/pytorch/pull/36382\n            \"SyncBN\": NaiveSyncBatchNorm if env.TORCH_VERSION <= (1, 5) else nn.SyncBatchNorm,\n            \"FrozenBN\": FrozenBatchNorm2d,\n            \"GN\": lambda channels: nn.GroupNorm(32, channels),\n            # for debugging:\n            \"nnSyncBN\": nn.SyncBatchNorm,\n            \"naiveSyncBN\": NaiveSyncBatchNorm,\n            # expose stats_mode N as an option to caller, required for zero-len inputs\n            \"naiveSyncBN_N\": lambda channels: NaiveSyncBatchNorm(channels, stats_mode=\"N\"),\n        }[norm]\n    return norm(out_channels)\n\n\nclass NaiveSyncBatchNorm(BatchNorm2d):\n    \"\"\"\n    In PyTorch<=1.5, ``nn.SyncBatchNorm`` has incorrect gradient\n    when the batch size on each worker is different.\n    (e.g., when scale augmentation is used, or when it is applied to mask head).\n\n    This is a slower but correct alternative to `nn.SyncBatchNorm`.\n\n    Note:\n        There isn't a single definition of Sync BatchNorm.\n\n        When ``stats_mode==\"\"``, this module computes overall statistics by using\n        statistics of each worker with equal weight.  The result is true statistics\n        of all samples (as if they are all on one worker) only when all workers\n        have the same (N, H, W). This mode does not support inputs with zero batch size.\n\n        When ``stats_mode==\"N\"``, this module computes overall statistics by weighting\n        the statistics of each worker by their ``N``. The result is true statistics\n        of all samples (as if they are all on one worker) only when all workers\n        have the same (H, W). It is slower than ``stats_mode==\"\"``.\n\n        Even though the result of this module may not be the true statistics of all samples,\n        it may still be reasonable because it might be preferrable to assign equal weights\n        to all workers, regardless of their (H, W) dimension, instead of putting larger weight\n        on larger images. From preliminary experiments, little difference is found between such\n        a simplified implementation and an accurate computation of overall mean & variance.\n    \"\"\"\n\n    def __init__(self, *args, stats_mode=\"\", **kwargs):\n        super().__init__(*args, **kwargs)\n        assert stats_mode in [\"\", \"N\"]\n        self._stats_mode = stats_mode\n\n    def forward(self, input):\n        if comm.get_world_size() == 1 or not self.training:\n            return super().forward(input)\n\n        B, C = input.shape[0], input.shape[1]\n\n        half_input = input.dtype == torch.float16\n        if half_input:\n            # fp16 does not have good enough numerics for the reduction here\n            input = input.float()\n        mean = torch.mean(input, dim=[0, 2, 3])\n        meansqr = torch.mean(input * input, dim=[0, 2, 3])\n\n        if self._stats_mode == \"\":\n            assert B > 0, 'SyncBatchNorm(stats_mode=\"\") does not support zero batch size.'\n            vec = torch.cat([mean, meansqr], dim=0)\n            vec = differentiable_all_reduce(vec) * (1.0 / dist.get_world_size())\n            mean, meansqr = torch.split(vec, C)\n            momentum = self.momentum\n        else:\n            if B == 0:\n                vec = torch.zeros([2 * C + 1], device=mean.device, dtype=mean.dtype)\n                vec = vec + input.sum()  # make sure there is gradient w.r.t input\n            else:\n                vec = torch.cat(\n                    [mean, meansqr, torch.ones([1], device=mean.device, dtype=mean.dtype)], dim=0\n                )\n            vec = differentiable_all_reduce(vec * B)\n\n            total_batch = vec[-1].detach()\n            momentum = total_batch.clamp(max=1) * self.momentum  # no update if total_batch is 0\n            mean, meansqr, _ = torch.split(vec / total_batch.clamp(min=1), C)  # avoid div-by-zero\n\n        var = meansqr - mean * mean\n        invstd = torch.rsqrt(var + self.eps)\n        scale = self.weight * invstd\n        bias = self.bias - mean * scale\n        scale = scale.reshape(1, -1, 1, 1)\n        bias = bias.reshape(1, -1, 1, 1)\n\n        self.running_mean += momentum * (mean.detach() - self.running_mean)\n        self.running_var += momentum * (var.detach() - self.running_var)\n        ret = input * scale + bias\n        if half_input:\n            ret = ret.half()\n        return ret\n\n\nclass CycleBatchNormList(nn.ModuleList):\n    \"\"\"\n    Implement domain-specific BatchNorm by cycling.\n\n    When a BatchNorm layer is used for multiple input domains or input\n    features, it might need to maintain a separate test-time statistics\n    for each domain. See Sec 5.2 in :paper:`rethinking-batchnorm`.\n\n    This module implements it by using N separate BN layers\n    and it cycles through them every time a forward() is called.\n\n    NOTE: The caller of this module MUST guarantee to always call\n    this module by multiple of N times. Otherwise its test-time statistics\n    will be incorrect.\n    \"\"\"\n\n    def __init__(self, length: int, bn_class=nn.BatchNorm2d, **kwargs):\n        \"\"\"\n        Args:\n            length: number of BatchNorm layers to cycle.\n            bn_class: the BatchNorm class to use\n            kwargs: arguments of the BatchNorm class, such as num_features.\n        \"\"\"\n        self._affine = kwargs.pop(\"affine\", True)\n        super().__init__([bn_class(**kwargs, affine=False) for k in range(length)])\n        if self._affine:\n            # shared affine, domain-specific BN\n            channels = self[0].num_features\n            self.weight = nn.Parameter(torch.ones(channels))\n            self.bias = nn.Parameter(torch.zeros(channels))\n        self._pos = 0\n\n    def forward(self, x):\n        ret = self[self._pos](x)\n        self._pos = (self._pos + 1) % len(self)\n\n        if self._affine:\n            w = self.weight.reshape(1, -1, 1, 1)\n            b = self.bias.reshape(1, -1, 1, 1)\n            return ret * w + b\n        else:\n            return ret\n\n    def extra_repr(self):\n        return f\"affine={self._affine}\"\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/blocks.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport fvcore.nn.weight_init as weight_init\nfrom torch import nn\n\nfrom .batch_norm import FrozenBatchNorm2d, get_norm\nfrom .wrappers import Conv2d\n\n\n\"\"\"\nCNN building blocks.\n\"\"\"\n\n\nclass CNNBlockBase(nn.Module):\n    \"\"\"\n    A CNN block is assumed to have input channels, output channels and a stride.\n    The input and output of `forward()` method must be NCHW tensors.\n    The method can perform arbitrary computation but must match the given\n    channels and stride specification.\n\n    Attribute:\n        in_channels (int):\n        out_channels (int):\n        stride (int):\n    \"\"\"\n\n    def __init__(self, in_channels, out_channels, stride):\n        \"\"\"\n        The `__init__` method of any subclass should also contain these arguments.\n\n        Args:\n            in_channels (int):\n            out_channels (int):\n            stride (int):\n        \"\"\"\n        super().__init__()\n        self.in_channels = in_channels\n        self.out_channels = out_channels\n        self.stride = stride\n\n    def freeze(self):\n        \"\"\"\n        Make this block not trainable.\n        This method sets all parameters to `requires_grad=False`,\n        and convert all BatchNorm layers to FrozenBatchNorm\n\n        Returns:\n            the block itself\n        \"\"\"\n        for p in self.parameters():\n            p.requires_grad = False\n        FrozenBatchNorm2d.convert_frozen_batchnorm(self)\n        return self\n\n\nclass DepthwiseSeparableConv2d(nn.Module):\n    \"\"\"\n    A kxk depthwise convolution + a 1x1 convolution.\n\n    In :paper:`xception`, norm & activation are applied on the second conv.\n    :paper:`mobilenet` uses norm & activation on both convs.\n    \"\"\"\n\n    def __init__(\n        self,\n        in_channels,\n        out_channels,\n        kernel_size=3,\n        padding=1,\n        dilation=1,\n        *,\n        norm1=None,\n        activation1=None,\n        norm2=None,\n        activation2=None,\n    ):\n        \"\"\"\n        Args:\n            norm1, norm2 (str or callable): normalization for the two conv layers.\n            activation1, activation2 (callable(Tensor) -> Tensor): activation\n                function for the two conv layers.\n        \"\"\"\n        super().__init__()\n        self.depthwise = Conv2d(\n            in_channels,\n            in_channels,\n            kernel_size=kernel_size,\n            padding=padding,\n            dilation=dilation,\n            groups=in_channels,\n            bias=not norm1,\n            norm=get_norm(norm1, in_channels),\n            activation=activation1,\n        )\n        self.pointwise = Conv2d(\n            in_channels,\n            out_channels,\n            kernel_size=1,\n            bias=not norm2,\n            norm=get_norm(norm2, out_channels),\n            activation=activation2,\n        )\n\n        # default initialization\n        weight_init.c2_msra_fill(self.depthwise)\n        weight_init.c2_msra_fill(self.pointwise)\n\n    def forward(self, x):\n        return self.pointwise(self.depthwise(x))\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/csrc/README.md",
    "content": "\n\nTo add a new Op:\n\n1. Create a new directory\n2. Implement new ops there\n3. Delcare its Python interface in `vision.cpp`.\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/csrc/ROIAlignRotated/ROIAlignRotated.h",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#pragma once\n#include <torch/types.h>\n\nnamespace detectron2 {\n\nat::Tensor ROIAlignRotated_forward_cpu(\n    const at::Tensor& input,\n    const at::Tensor& rois,\n    const float spatial_scale,\n    const int pooled_height,\n    const int pooled_width,\n    const int sampling_ratio);\n\nat::Tensor ROIAlignRotated_backward_cpu(\n    const at::Tensor& grad,\n    const at::Tensor& rois,\n    const float spatial_scale,\n    const int pooled_height,\n    const int pooled_width,\n    const int batch_size,\n    const int channels,\n    const int height,\n    const int width,\n    const int sampling_ratio);\n\n#if defined(WITH_CUDA) || defined(WITH_HIP)\nat::Tensor ROIAlignRotated_forward_cuda(\n    const at::Tensor& input,\n    const at::Tensor& rois,\n    const float spatial_scale,\n    const int pooled_height,\n    const int pooled_width,\n    const int sampling_ratio);\n\nat::Tensor ROIAlignRotated_backward_cuda(\n    const at::Tensor& grad,\n    const at::Tensor& rois,\n    const float spatial_scale,\n    const int pooled_height,\n    const int pooled_width,\n    const int batch_size,\n    const int channels,\n    const int height,\n    const int width,\n    const int sampling_ratio);\n#endif\n\n// Interface for Python\ninline at::Tensor ROIAlignRotated_forward(\n    const at::Tensor& input,\n    const at::Tensor& rois,\n    const double spatial_scale,\n    const int64_t pooled_height,\n    const int64_t pooled_width,\n    const int64_t sampling_ratio) {\n  if (input.is_cuda()) {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n    return ROIAlignRotated_forward_cuda(\n        input,\n        rois,\n        spatial_scale,\n        pooled_height,\n        pooled_width,\n        sampling_ratio);\n#else\n    AT_ERROR(\"Detectron2 is not compiled with GPU support!\");\n#endif\n  }\n  return ROIAlignRotated_forward_cpu(\n      input, rois, spatial_scale, pooled_height, pooled_width, sampling_ratio);\n}\n\ninline at::Tensor ROIAlignRotated_backward(\n    const at::Tensor& grad,\n    const at::Tensor& rois,\n    const double spatial_scale,\n    const int64_t pooled_height,\n    const int64_t pooled_width,\n    const int64_t batch_size,\n    const int64_t channels,\n    const int64_t height,\n    const int64_t width,\n    const int64_t sampling_ratio) {\n  if (grad.is_cuda()) {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n    return ROIAlignRotated_backward_cuda(\n        grad,\n        rois,\n        spatial_scale,\n        pooled_height,\n        pooled_width,\n        batch_size,\n        channels,\n        height,\n        width,\n        sampling_ratio);\n#else\n    AT_ERROR(\"Detectron2 is not compiled with GPU support!\");\n#endif\n  }\n  return ROIAlignRotated_backward_cpu(\n      grad,\n      rois,\n      spatial_scale,\n      pooled_height,\n      pooled_width,\n      batch_size,\n      channels,\n      height,\n      width,\n      sampling_ratio);\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/csrc/ROIAlignRotated/ROIAlignRotated_cpu.cpp",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#include <ATen/TensorUtils.h>\n#include \"ROIAlignRotated.h\"\n\n// Note: this implementation originates from the Caffe2 ROIAlignRotated Op\n// and PyTorch ROIAlign (non-rotated) Op implementations.\n// The key difference between this implementation and those ones is\n// we don't do \"legacy offset\" in this version, as there aren't many previous\n// works, if any, using the \"legacy\" ROIAlignRotated Op.\n// This would make the interface a bit cleaner.\n\nnamespace detectron2 {\n\nnamespace {\ntemplate <typename T>\nstruct PreCalc {\n  int pos1;\n  int pos2;\n  int pos3;\n  int pos4;\n  T w1;\n  T w2;\n  T w3;\n  T w4;\n};\n\ntemplate <typename T>\nvoid pre_calc_for_bilinear_interpolate(\n    const int height,\n    const int width,\n    const int pooled_height,\n    const int pooled_width,\n    const int iy_upper,\n    const int ix_upper,\n    T roi_start_h,\n    T roi_start_w,\n    T bin_size_h,\n    T bin_size_w,\n    int roi_bin_grid_h,\n    int roi_bin_grid_w,\n    T roi_center_h,\n    T roi_center_w,\n    T cos_theta,\n    T sin_theta,\n    std::vector<PreCalc<T>>& pre_calc) {\n  int pre_calc_index = 0;\n  for (int ph = 0; ph < pooled_height; ph++) {\n    for (int pw = 0; pw < pooled_width; pw++) {\n      for (int iy = 0; iy < iy_upper; iy++) {\n        const T yy = roi_start_h + ph * bin_size_h +\n            static_cast<T>(iy + .5f) * bin_size_h /\n                static_cast<T>(roi_bin_grid_h); // e.g., 0.5, 1.5\n        for (int ix = 0; ix < ix_upper; ix++) {\n          const T xx = roi_start_w + pw * bin_size_w +\n              static_cast<T>(ix + .5f) * bin_size_w /\n                  static_cast<T>(roi_bin_grid_w);\n\n          // Rotate by theta around the center and translate\n          // In image space, (y, x) is the order for Right Handed System,\n          // and this is essentially multiplying the point by a rotation matrix\n          // to rotate it counterclockwise through angle theta.\n          T y = yy * cos_theta - xx * sin_theta + roi_center_h;\n          T x = yy * sin_theta + xx * cos_theta + roi_center_w;\n          // deal with: inverse elements are out of feature map boundary\n          if (y < -1.0 || y > height || x < -1.0 || x > width) {\n            // empty\n            PreCalc<T> pc;\n            pc.pos1 = 0;\n            pc.pos2 = 0;\n            pc.pos3 = 0;\n            pc.pos4 = 0;\n            pc.w1 = 0;\n            pc.w2 = 0;\n            pc.w3 = 0;\n            pc.w4 = 0;\n            pre_calc[pre_calc_index] = pc;\n            pre_calc_index += 1;\n            continue;\n          }\n\n          if (y < 0) {\n            y = 0;\n          }\n          if (x < 0) {\n            x = 0;\n          }\n\n          int y_low = (int)y;\n          int x_low = (int)x;\n          int y_high;\n          int x_high;\n\n          if (y_low >= height - 1) {\n            y_high = y_low = height - 1;\n            y = (T)y_low;\n          } else {\n            y_high = y_low + 1;\n          }\n\n          if (x_low >= width - 1) {\n            x_high = x_low = width - 1;\n            x = (T)x_low;\n          } else {\n            x_high = x_low + 1;\n          }\n\n          T ly = y - y_low;\n          T lx = x - x_low;\n          T hy = 1. - ly, hx = 1. - lx;\n          T w1 = hy * hx, w2 = hy * lx, w3 = ly * hx, w4 = ly * lx;\n\n          // save weights and indices\n          PreCalc<T> pc;\n          pc.pos1 = y_low * width + x_low;\n          pc.pos2 = y_low * width + x_high;\n          pc.pos3 = y_high * width + x_low;\n          pc.pos4 = y_high * width + x_high;\n          pc.w1 = w1;\n          pc.w2 = w2;\n          pc.w3 = w3;\n          pc.w4 = w4;\n          pre_calc[pre_calc_index] = pc;\n\n          pre_calc_index += 1;\n        }\n      }\n    }\n  }\n}\n\ntemplate <typename T>\nvoid bilinear_interpolate_gradient(\n    const int height,\n    const int width,\n    T y,\n    T x,\n    T& w1,\n    T& w2,\n    T& w3,\n    T& w4,\n    int& x_low,\n    int& x_high,\n    int& y_low,\n    int& y_high) {\n  // deal with cases that inverse elements are out of feature map boundary\n  if (y < -1.0 || y > height || x < -1.0 || x > width) {\n    // empty\n    w1 = w2 = w3 = w4 = 0.;\n    x_low = x_high = y_low = y_high = -1;\n    return;\n  }\n\n  if (y < 0) {\n    y = 0;\n  }\n\n  if (x < 0) {\n    x = 0;\n  }\n\n  y_low = (int)y;\n  x_low = (int)x;\n\n  if (y_low >= height - 1) {\n    y_high = y_low = height - 1;\n    y = (T)y_low;\n  } else {\n    y_high = y_low + 1;\n  }\n\n  if (x_low >= width - 1) {\n    x_high = x_low = width - 1;\n    x = (T)x_low;\n  } else {\n    x_high = x_low + 1;\n  }\n\n  T ly = y - y_low;\n  T lx = x - x_low;\n  T hy = 1. - ly, hx = 1. - lx;\n\n  // reference in forward\n  // T v1 = input[y_low * width + x_low];\n  // T v2 = input[y_low * width + x_high];\n  // T v3 = input[y_high * width + x_low];\n  // T v4 = input[y_high * width + x_high];\n  // T val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n\n  w1 = hy * hx, w2 = hy * lx, w3 = ly * hx, w4 = ly * lx;\n\n  return;\n}\n\ntemplate <class T>\ninline void add(T* address, const T& val) {\n  *address += val;\n}\n\n} // namespace\n\ntemplate <typename T>\nvoid ROIAlignRotatedForward(\n    const int nthreads,\n    const T* input,\n    const T& spatial_scale,\n    const int channels,\n    const int height,\n    const int width,\n    const int pooled_height,\n    const int pooled_width,\n    const int sampling_ratio,\n    const T* rois,\n    T* output) {\n  int n_rois = nthreads / channels / pooled_width / pooled_height;\n  // (n, c, ph, pw) is an element in the pooled output\n  // can be parallelized using omp\n  // #pragma omp parallel for num_threads(32)\n  for (int n = 0; n < n_rois; n++) {\n    int index_n = n * channels * pooled_width * pooled_height;\n\n    const T* current_roi = rois + n * 6;\n    int roi_batch_ind = current_roi[0];\n\n    // Do not use rounding; this implementation detail is critical\n    // ROIAlignRotated supports align == true, i.e., continuous coordinate\n    // by default, thus the 0.5 offset\n    T offset = (T)0.5;\n    T roi_center_w = current_roi[1] * spatial_scale - offset;\n    T roi_center_h = current_roi[2] * spatial_scale - offset;\n    T roi_width = current_roi[3] * spatial_scale;\n    T roi_height = current_roi[4] * spatial_scale;\n    T theta = current_roi[5] * M_PI / 180.0;\n    T cos_theta = cos(theta);\n    T sin_theta = sin(theta);\n\n    AT_ASSERTM(\n        roi_width >= 0 && roi_height >= 0,\n        \"ROIs in ROIAlignRotated do not have non-negative size!\");\n\n    T bin_size_h = static_cast<T>(roi_height) / static_cast<T>(pooled_height);\n    T bin_size_w = static_cast<T>(roi_width) / static_cast<T>(pooled_width);\n\n    // We use roi_bin_grid to sample the grid and mimic integral\n    int roi_bin_grid_h = (sampling_ratio > 0)\n        ? sampling_ratio\n        : ceil(roi_height / pooled_height); // e.g., = 2\n    int roi_bin_grid_w =\n        (sampling_ratio > 0) ? sampling_ratio : ceil(roi_width / pooled_width);\n\n    // We do average (integral) pooling inside a bin\n    const T count = std::max(roi_bin_grid_h * roi_bin_grid_w, 1); // e.g. = 4\n\n    // we want to precalculate indices and weights shared by all channels,\n    // this is the key point of optimization\n    std::vector<PreCalc<T>> pre_calc(\n        roi_bin_grid_h * roi_bin_grid_w * pooled_width * pooled_height);\n\n    // roi_start_h and roi_start_w are computed wrt the center of RoI (x, y).\n    // Appropriate translation needs to be applied after.\n    T roi_start_h = -roi_height / 2.0;\n    T roi_start_w = -roi_width / 2.0;\n\n    pre_calc_for_bilinear_interpolate(\n        height,\n        width,\n        pooled_height,\n        pooled_width,\n        roi_bin_grid_h,\n        roi_bin_grid_w,\n        roi_start_h,\n        roi_start_w,\n        bin_size_h,\n        bin_size_w,\n        roi_bin_grid_h,\n        roi_bin_grid_w,\n        roi_center_h,\n        roi_center_w,\n        cos_theta,\n        sin_theta,\n        pre_calc);\n\n    for (int c = 0; c < channels; c++) {\n      int index_n_c = index_n + c * pooled_width * pooled_height;\n      const T* offset_input =\n          input + (roi_batch_ind * channels + c) * height * width;\n      int pre_calc_index = 0;\n\n      for (int ph = 0; ph < pooled_height; ph++) {\n        for (int pw = 0; pw < pooled_width; pw++) {\n          int index = index_n_c + ph * pooled_width + pw;\n\n          T output_val = 0.;\n          for (int iy = 0; iy < roi_bin_grid_h; iy++) {\n            for (int ix = 0; ix < roi_bin_grid_w; ix++) {\n              PreCalc<T> pc = pre_calc[pre_calc_index];\n              output_val += pc.w1 * offset_input[pc.pos1] +\n                  pc.w2 * offset_input[pc.pos2] +\n                  pc.w3 * offset_input[pc.pos3] + pc.w4 * offset_input[pc.pos4];\n\n              pre_calc_index += 1;\n            }\n          }\n          output_val /= count;\n\n          output[index] = output_val;\n        } // for pw\n      } // for ph\n    } // for c\n  } // for n\n}\n\ntemplate <typename T>\nvoid ROIAlignRotatedBackward(\n    const int nthreads,\n    // may not be contiguous. should index using n_stride, etc\n    const T* grad_output,\n    const T& spatial_scale,\n    const int channels,\n    const int height,\n    const int width,\n    const int pooled_height,\n    const int pooled_width,\n    const int sampling_ratio,\n    T* grad_input,\n    const T* rois,\n    const int n_stride,\n    const int c_stride,\n    const int h_stride,\n    const int w_stride) {\n  for (int index = 0; index < nthreads; index++) {\n    // (n, c, ph, pw) is an element in the pooled output\n    int pw = index % pooled_width;\n    int ph = (index / pooled_width) % pooled_height;\n    int c = (index / pooled_width / pooled_height) % channels;\n    int n = index / pooled_width / pooled_height / channels;\n\n    const T* current_roi = rois + n * 6;\n    int roi_batch_ind = current_roi[0];\n\n    // Do not use rounding; this implementation detail is critical\n    // ROIAlignRotated supports align == true, i.e., continuous coordinate\n    // by default, thus the 0.5 offset\n    T offset = (T)0.5;\n    T roi_center_w = current_roi[1] * spatial_scale - offset;\n    T roi_center_h = current_roi[2] * spatial_scale - offset;\n    T roi_width = current_roi[3] * spatial_scale;\n    T roi_height = current_roi[4] * spatial_scale;\n    T theta = current_roi[5] * M_PI / 180.0;\n    T cos_theta = cos(theta);\n    T sin_theta = sin(theta);\n\n    AT_ASSERTM(\n        roi_width >= 0 && roi_height >= 0,\n        \"ROIs in ROIAlignRotated do not have non-negative size!\");\n\n    T bin_size_h = static_cast<T>(roi_height) / static_cast<T>(pooled_height);\n    T bin_size_w = static_cast<T>(roi_width) / static_cast<T>(pooled_width);\n\n    T* offset_grad_input =\n        grad_input + ((roi_batch_ind * channels + c) * height * width);\n\n    int output_offset = n * n_stride + c * c_stride;\n    const T* offset_grad_output = grad_output + output_offset;\n    const T grad_output_this_bin =\n        offset_grad_output[ph * h_stride + pw * w_stride];\n\n    // We use roi_bin_grid to sample the grid and mimic integral\n    int roi_bin_grid_h = (sampling_ratio > 0)\n        ? sampling_ratio\n        : ceil(roi_height / pooled_height); // e.g., = 2\n    int roi_bin_grid_w =\n        (sampling_ratio > 0) ? sampling_ratio : ceil(roi_width / pooled_width);\n\n    // roi_start_h and roi_start_w are computed wrt the center of RoI (x, y).\n    // Appropriate translation needs to be applied after.\n    T roi_start_h = -roi_height / 2.0;\n    T roi_start_w = -roi_width / 2.0;\n\n    // We do average (integral) pooling inside a bin\n    const T count = roi_bin_grid_h * roi_bin_grid_w; // e.g. = 4\n\n    for (int iy = 0; iy < roi_bin_grid_h; iy++) {\n      const T yy = roi_start_h + ph * bin_size_h +\n          static_cast<T>(iy + .5f) * bin_size_h /\n              static_cast<T>(roi_bin_grid_h); // e.g., 0.5, 1.5\n      for (int ix = 0; ix < roi_bin_grid_w; ix++) {\n        const T xx = roi_start_w + pw * bin_size_w +\n            static_cast<T>(ix + .5f) * bin_size_w /\n                static_cast<T>(roi_bin_grid_w);\n\n        // Rotate by theta around the center and translate\n        T y = yy * cos_theta - xx * sin_theta + roi_center_h;\n        T x = yy * sin_theta + xx * cos_theta + roi_center_w;\n\n        T w1, w2, w3, w4;\n        int x_low, x_high, y_low, y_high;\n\n        bilinear_interpolate_gradient(\n            height, width, y, x, w1, w2, w3, w4, x_low, x_high, y_low, y_high);\n\n        T g1 = grad_output_this_bin * w1 / count;\n        T g2 = grad_output_this_bin * w2 / count;\n        T g3 = grad_output_this_bin * w3 / count;\n        T g4 = grad_output_this_bin * w4 / count;\n\n        if (x_low >= 0 && x_high >= 0 && y_low >= 0 && y_high >= 0) {\n          // atomic add is not needed for now since it is single threaded\n          add(offset_grad_input + y_low * width + x_low, static_cast<T>(g1));\n          add(offset_grad_input + y_low * width + x_high, static_cast<T>(g2));\n          add(offset_grad_input + y_high * width + x_low, static_cast<T>(g3));\n          add(offset_grad_input + y_high * width + x_high, static_cast<T>(g4));\n        } // if\n      } // ix\n    } // iy\n  } // for\n} // ROIAlignRotatedBackward\n\nat::Tensor ROIAlignRotated_forward_cpu(\n    const at::Tensor& input,\n    const at::Tensor& rois,\n    const float spatial_scale,\n    const int pooled_height,\n    const int pooled_width,\n    const int sampling_ratio) {\n  AT_ASSERTM(input.device().is_cpu(), \"input must be a CPU tensor\");\n  AT_ASSERTM(rois.device().is_cpu(), \"rois must be a CPU tensor\");\n\n  at::TensorArg input_t{input, \"input\", 1}, rois_t{rois, \"rois\", 2};\n\n  at::CheckedFrom c = \"ROIAlign_forward_cpu\";\n  at::checkAllSameType(c, {input_t, rois_t});\n\n  auto num_rois = rois.size(0);\n  auto channels = input.size(1);\n  auto height = input.size(2);\n  auto width = input.size(3);\n\n  at::Tensor output = at::zeros(\n      {num_rois, channels, pooled_height, pooled_width}, input.options());\n\n  auto output_size = num_rois * pooled_height * pooled_width * channels;\n\n  if (output.numel() == 0) {\n    return output;\n  }\n\n  auto input_ = input.contiguous(), rois_ = rois.contiguous();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      input.scalar_type(), \"ROIAlignRotated_forward\", [&] {\n        ROIAlignRotatedForward<scalar_t>(\n            output_size,\n            input_.data_ptr<scalar_t>(),\n            spatial_scale,\n            channels,\n            height,\n            width,\n            pooled_height,\n            pooled_width,\n            sampling_ratio,\n            rois_.data_ptr<scalar_t>(),\n            output.data_ptr<scalar_t>());\n      });\n  return output;\n}\n\nat::Tensor ROIAlignRotated_backward_cpu(\n    const at::Tensor& grad,\n    const at::Tensor& rois,\n    const float spatial_scale,\n    const int pooled_height,\n    const int pooled_width,\n    const int batch_size,\n    const int channels,\n    const int height,\n    const int width,\n    const int sampling_ratio) {\n  AT_ASSERTM(grad.device().is_cpu(), \"grad must be a CPU tensor\");\n  AT_ASSERTM(rois.device().is_cpu(), \"rois must be a CPU tensor\");\n\n  at::TensorArg grad_t{grad, \"grad\", 1}, rois_t{rois, \"rois\", 2};\n\n  at::CheckedFrom c = \"ROIAlignRotated_backward_cpu\";\n  at::checkAllSameType(c, {grad_t, rois_t});\n\n  at::Tensor grad_input =\n      at::zeros({batch_size, channels, height, width}, grad.options());\n\n  // handle possibly empty gradients\n  if (grad.numel() == 0) {\n    return grad_input;\n  }\n\n  // get stride values to ensure indexing into gradients is correct.\n  int n_stride = grad.stride(0);\n  int c_stride = grad.stride(1);\n  int h_stride = grad.stride(2);\n  int w_stride = grad.stride(3);\n\n  auto rois_ = rois.contiguous();\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      grad.scalar_type(), \"ROIAlignRotated_forward\", [&] {\n        ROIAlignRotatedBackward<scalar_t>(\n            grad.numel(),\n            grad.data_ptr<scalar_t>(),\n            spatial_scale,\n            channels,\n            height,\n            width,\n            pooled_height,\n            pooled_width,\n            sampling_ratio,\n            grad_input.data_ptr<scalar_t>(),\n            rois_.data_ptr<scalar_t>(),\n            n_stride,\n            c_stride,\n            h_stride,\n            w_stride);\n      });\n  return grad_input;\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/csrc/ROIAlignRotated/ROIAlignRotated_cuda.cu",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#include <ATen/ATen.h>\n#include <ATen/cuda/CUDAContext.h>\n#include <c10/cuda/CUDAGuard.h>\n#include <ATen/cuda/CUDAApplyUtils.cuh>\n\n// TODO make it in a common file\n#define CUDA_1D_KERNEL_LOOP(i, n)                            \\\n  for (int i = blockIdx.x * blockDim.x + threadIdx.x; i < n; \\\n       i += blockDim.x * gridDim.x)\n\n// Note: this implementation originates from the Caffe2 ROIAlignRotated Op\n// and PyTorch ROIAlign (non-rotated) Op implementations.\n// The key difference between this implementation and those ones is\n// we don't do \"legacy offset\" in this version, as there aren't many previous\n// works, if any, using the \"legacy\" ROIAlignRotated Op.\n// This would make the interface a bit cleaner.\n\nnamespace detectron2 {\n\nnamespace {\n\ntemplate <typename T>\n__device__ T bilinear_interpolate(\n    const T* input,\n    const int height,\n    const int width,\n    T y,\n    T x) {\n  // deal with cases that inverse elements are out of feature map boundary\n  if (y < -1.0 || y > height || x < -1.0 || x > width) {\n    // empty\n    return 0;\n  }\n\n  if (y < 0) {\n    y = 0;\n  }\n\n  if (x < 0) {\n    x = 0;\n  }\n\n  int y_low = (int)y;\n  int x_low = (int)x;\n  int y_high;\n  int x_high;\n\n  if (y_low >= height - 1) {\n    y_high = y_low = height - 1;\n    y = (T)y_low;\n  } else {\n    y_high = y_low + 1;\n  }\n\n  if (x_low >= width - 1) {\n    x_high = x_low = width - 1;\n    x = (T)x_low;\n  } else {\n    x_high = x_low + 1;\n  }\n\n  T ly = y - y_low;\n  T lx = x - x_low;\n  T hy = 1. - ly, hx = 1. - lx;\n  // do bilinear interpolation\n  T v1 = input[y_low * width + x_low];\n  T v2 = input[y_low * width + x_high];\n  T v3 = input[y_high * width + x_low];\n  T v4 = input[y_high * width + x_high];\n  T w1 = hy * hx, w2 = hy * lx, w3 = ly * hx, w4 = ly * lx;\n\n  T val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n\n  return val;\n}\n\ntemplate <typename T>\n__device__ void bilinear_interpolate_gradient(\n    const int height,\n    const int width,\n    T y,\n    T x,\n    T& w1,\n    T& w2,\n    T& w3,\n    T& w4,\n    int& x_low,\n    int& x_high,\n    int& y_low,\n    int& y_high) {\n  // deal with cases that inverse elements are out of feature map boundary\n  if (y < -1.0 || y > height || x < -1.0 || x > width) {\n    // empty\n    w1 = w2 = w3 = w4 = 0.;\n    x_low = x_high = y_low = y_high = -1;\n    return;\n  }\n\n  if (y < 0) {\n    y = 0;\n  }\n\n  if (x < 0) {\n    x = 0;\n  }\n\n  y_low = (int)y;\n  x_low = (int)x;\n\n  if (y_low >= height - 1) {\n    y_high = y_low = height - 1;\n    y = (T)y_low;\n  } else {\n    y_high = y_low + 1;\n  }\n\n  if (x_low >= width - 1) {\n    x_high = x_low = width - 1;\n    x = (T)x_low;\n  } else {\n    x_high = x_low + 1;\n  }\n\n  T ly = y - y_low;\n  T lx = x - x_low;\n  T hy = 1. - ly, hx = 1. - lx;\n\n  // reference in forward\n  // T v1 = input[y_low * width + x_low];\n  // T v2 = input[y_low * width + x_high];\n  // T v3 = input[y_high * width + x_low];\n  // T v4 = input[y_high * width + x_high];\n  // T val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n\n  w1 = hy * hx, w2 = hy * lx, w3 = ly * hx, w4 = ly * lx;\n\n  return;\n}\n\n} // namespace\n\ntemplate <typename T>\n__global__ void RoIAlignRotatedForward(\n    const int nthreads,\n    const T* input,\n    const T spatial_scale,\n    const int channels,\n    const int height,\n    const int width,\n    const int pooled_height,\n    const int pooled_width,\n    const int sampling_ratio,\n    const T* rois,\n    T* top_data) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    // (n, c, ph, pw) is an element in the pooled output\n    int pw = index % pooled_width;\n    int ph = (index / pooled_width) % pooled_height;\n    int c = (index / pooled_width / pooled_height) % channels;\n    int n = index / pooled_width / pooled_height / channels;\n\n    const T* current_roi = rois + n * 6;\n    int roi_batch_ind = current_roi[0];\n\n    // Do not use rounding; this implementation detail is critical\n    // ROIAlignRotated supports align == true, i.e., continuous coordinate\n    // by default, thus the 0.5 offset\n    T offset = (T)0.5;\n    T roi_center_w = current_roi[1] * spatial_scale - offset;\n    T roi_center_h = current_roi[2] * spatial_scale - offset;\n    T roi_width = current_roi[3] * spatial_scale;\n    T roi_height = current_roi[4] * spatial_scale;\n    T theta = current_roi[5] * M_PI / 180.0;\n    T cos_theta = cos(theta);\n    T sin_theta = sin(theta);\n\n    T bin_size_h = static_cast<T>(roi_height) / static_cast<T>(pooled_height);\n    T bin_size_w = static_cast<T>(roi_width) / static_cast<T>(pooled_width);\n\n    const T* offset_input =\n        input + (roi_batch_ind * channels + c) * height * width;\n\n    // We use roi_bin_grid to sample the grid and mimic integral\n    int roi_bin_grid_h = (sampling_ratio > 0)\n        ? sampling_ratio\n        : ceil(roi_height / pooled_height); // e.g., = 2\n    int roi_bin_grid_w =\n        (sampling_ratio > 0) ? sampling_ratio : ceil(roi_width / pooled_width);\n\n    // roi_start_h and roi_start_w are computed wrt the center of RoI (x, y).\n    // Appropriate translation needs to be applied after.\n    T roi_start_h = -roi_height / 2.0;\n    T roi_start_w = -roi_width / 2.0;\n\n    // We do average (inte  gral) pooling inside a bin\n    const T count = max(roi_bin_grid_h * roi_bin_grid_w, 1); // e.g. = 4\n\n    T output_val = 0.;\n    for (int iy = 0; iy < roi_bin_grid_h; iy++) // e.g., iy = 0, 1\n    {\n      const T yy = roi_start_h + ph * bin_size_h +\n          static_cast<T>(iy + .5f) * bin_size_h /\n              static_cast<T>(roi_bin_grid_h); // e.g., 0.5, 1.5\n      for (int ix = 0; ix < roi_bin_grid_w; ix++) {\n        const T xx = roi_start_w + pw * bin_size_w +\n            static_cast<T>(ix + .5f) * bin_size_w /\n                static_cast<T>(roi_bin_grid_w);\n\n        // Rotate by theta around the center and translate\n        T y = yy * cos_theta - xx * sin_theta + roi_center_h;\n        T x = yy * sin_theta + xx * cos_theta + roi_center_w;\n\n        T val = bilinear_interpolate(offset_input, height, width, y, x);\n        output_val += val;\n      }\n    }\n    output_val /= count;\n\n    top_data[index] = output_val;\n  }\n}\n\ntemplate <typename T>\n__global__ void RoIAlignRotatedBackwardFeature(\n    const int nthreads,\n    const T* top_diff,\n    const int num_rois,\n    const T spatial_scale,\n    const int channels,\n    const int height,\n    const int width,\n    const int pooled_height,\n    const int pooled_width,\n    const int sampling_ratio,\n    T* bottom_diff,\n    const T* rois) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    // (n, c, ph, pw) is an element in the pooled output\n    int pw = index % pooled_width;\n    int ph = (index / pooled_width) % pooled_height;\n    int c = (index / pooled_width / pooled_height) % channels;\n    int n = index / pooled_width / pooled_height / channels;\n\n    const T* current_roi = rois + n * 6;\n    int roi_batch_ind = current_roi[0];\n\n    // Do not use rounding; this implementation detail is critical\n    // ROIAlignRotated supports align == true, i.e., continuous coordinate\n    // by default, thus the 0.5 offset\n    T offset = (T)0.5;\n    T roi_center_w = current_roi[1] * spatial_scale - offset;\n    T roi_center_h = current_roi[2] * spatial_scale - offset;\n    T roi_width = current_roi[3] * spatial_scale;\n    T roi_height = current_roi[4] * spatial_scale;\n    T theta = current_roi[5] * M_PI / 180.0;\n    T cos_theta = cos(theta);\n    T sin_theta = sin(theta);\n\n    T bin_size_h = static_cast<T>(roi_height) / static_cast<T>(pooled_height);\n    T bin_size_w = static_cast<T>(roi_width) / static_cast<T>(pooled_width);\n\n    T* offset_bottom_diff =\n        bottom_diff + (roi_batch_ind * channels + c) * height * width;\n\n    int top_offset = (n * channels + c) * pooled_height * pooled_width;\n    const T* offset_top_diff = top_diff + top_offset;\n    const T top_diff_this_bin = offset_top_diff[ph * pooled_width + pw];\n\n    // We use roi_bin_grid to sample the grid and mimic integral\n    int roi_bin_grid_h = (sampling_ratio > 0)\n        ? sampling_ratio\n        : ceil(roi_height / pooled_height); // e.g., = 2\n    int roi_bin_grid_w =\n        (sampling_ratio > 0) ? sampling_ratio : ceil(roi_width / pooled_width);\n\n    // roi_start_h and roi_start_w are computed wrt the center of RoI (x, y).\n    // Appropriate translation needs to be applied after.\n    T roi_start_h = -roi_height / 2.0;\n    T roi_start_w = -roi_width / 2.0;\n\n    // We do average (integral) pooling inside a bin\n    const T count = roi_bin_grid_h * roi_bin_grid_w; // e.g. = 4\n\n    for (int iy = 0; iy < roi_bin_grid_h; iy++) // e.g., iy = 0, 1\n    {\n      const T yy = roi_start_h + ph * bin_size_h +\n          static_cast<T>(iy + .5f) * bin_size_h /\n              static_cast<T>(roi_bin_grid_h); // e.g., 0.5, 1.5\n      for (int ix = 0; ix < roi_bin_grid_w; ix++) {\n        const T xx = roi_start_w + pw * bin_size_w +\n            static_cast<T>(ix + .5f) * bin_size_w /\n                static_cast<T>(roi_bin_grid_w);\n\n        // Rotate by theta around the center and translate\n        T y = yy * cos_theta - xx * sin_theta + roi_center_h;\n        T x = yy * sin_theta + xx * cos_theta + roi_center_w;\n\n        T w1, w2, w3, w4;\n        int x_low, x_high, y_low, y_high;\n\n        bilinear_interpolate_gradient(\n            height, width, y, x, w1, w2, w3, w4, x_low, x_high, y_low, y_high);\n\n        T g1 = top_diff_this_bin * w1 / count;\n        T g2 = top_diff_this_bin * w2 / count;\n        T g3 = top_diff_this_bin * w3 / count;\n        T g4 = top_diff_this_bin * w4 / count;\n\n        if (x_low >= 0 && x_high >= 0 && y_low >= 0 && y_high >= 0) {\n          atomicAdd(\n              offset_bottom_diff + y_low * width + x_low, static_cast<T>(g1));\n          atomicAdd(\n              offset_bottom_diff + y_low * width + x_high, static_cast<T>(g2));\n          atomicAdd(\n              offset_bottom_diff + y_high * width + x_low, static_cast<T>(g3));\n          atomicAdd(\n              offset_bottom_diff + y_high * width + x_high, static_cast<T>(g4));\n        } // if\n      } // ix\n    } // iy\n  } // CUDA_1D_KERNEL_LOOP\n} // RoIAlignRotatedBackward\n\nat::Tensor ROIAlignRotated_forward_cuda(\n    const at::Tensor& input,\n    const at::Tensor& rois,\n    const float spatial_scale,\n    const int pooled_height,\n    const int pooled_width,\n    const int sampling_ratio) {\n  AT_ASSERTM(input.device().is_cuda(), \"input must be a CUDA tensor\");\n  AT_ASSERTM(rois.device().is_cuda(), \"rois must be a CUDA tensor\");\n  at::TensorArg input_t{input, \"input\", 1}, rois_t{rois, \"rois\", 2};\n\n  at::CheckedFrom c = \"ROIAlignRotated_forward_cuda\";\n  at::checkAllSameGPU(c, {input_t, rois_t});\n  at::checkAllSameType(c, {input_t, rois_t});\n  at::cuda::CUDAGuard device_guard(input.device());\n\n  auto num_rois = rois.size(0);\n  auto channels = input.size(1);\n  auto height = input.size(2);\n  auto width = input.size(3);\n\n  auto output = at::empty(\n      {num_rois, channels, pooled_height, pooled_width}, input.options());\n  auto output_size = num_rois * pooled_height * pooled_width * channels;\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  dim3 grid(std::min(\n      at::cuda::ATenCeilDiv(\n          static_cast<int64_t>(output_size), static_cast<int64_t>(512)),\n      static_cast<int64_t>(4096)));\n  dim3 block(512);\n\n  if (output.numel() == 0) {\n    AT_CUDA_CHECK(cudaGetLastError());\n    return output;\n  }\n\n  auto input_ = input.contiguous(), rois_ = rois.contiguous();\n  AT_DISPATCH_FLOATING_TYPES(\n      input.scalar_type(), \"ROIAlignRotated_forward\", [&] {\n        RoIAlignRotatedForward<scalar_t><<<grid, block, 0, stream>>>(\n            output_size,\n            input_.data_ptr<scalar_t>(),\n            spatial_scale,\n            channels,\n            height,\n            width,\n            pooled_height,\n            pooled_width,\n            sampling_ratio,\n            rois_.data_ptr<scalar_t>(),\n            output.data_ptr<scalar_t>());\n      });\n  cudaDeviceSynchronize();\n  AT_CUDA_CHECK(cudaGetLastError());\n  return output;\n}\n\n// TODO remove the dependency on input and use instead its sizes -> save memory\nat::Tensor ROIAlignRotated_backward_cuda(\n    const at::Tensor& grad,\n    const at::Tensor& rois,\n    const float spatial_scale,\n    const int pooled_height,\n    const int pooled_width,\n    const int batch_size,\n    const int channels,\n    const int height,\n    const int width,\n    const int sampling_ratio) {\n  AT_ASSERTM(grad.device().is_cuda(), \"grad must be a CUDA tensor\");\n  AT_ASSERTM(rois.device().is_cuda(), \"rois must be a CUDA tensor\");\n\n  at::TensorArg grad_t{grad, \"grad\", 1}, rois_t{rois, \"rois\", 2};\n  at::CheckedFrom c = \"ROIAlign_backward_cuda\";\n  at::checkAllSameGPU(c, {grad_t, rois_t});\n  at::checkAllSameType(c, {grad_t, rois_t});\n  at::cuda::CUDAGuard device_guard(grad.device());\n\n  auto num_rois = rois.size(0);\n  auto grad_input =\n      at::zeros({batch_size, channels, height, width}, grad.options());\n\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  dim3 grid(std::min(\n      at::cuda::ATenCeilDiv(\n          static_cast<int64_t>(grad.numel()), static_cast<int64_t>(512)),\n      static_cast<int64_t>(4096)));\n  dim3 block(512);\n\n  // handle possibly empty gradients\n  if (grad.numel() == 0) {\n    AT_CUDA_CHECK(cudaGetLastError());\n    return grad_input;\n  }\n\n  auto grad_ = grad.contiguous(), rois_ = rois.contiguous();\n  AT_DISPATCH_FLOATING_TYPES(\n      grad.scalar_type(), \"ROIAlignRotated_backward\", [&] {\n        RoIAlignRotatedBackwardFeature<scalar_t><<<grid, block, 0, stream>>>(\n            grad.numel(),\n            grad_.data_ptr<scalar_t>(),\n            num_rois,\n            spatial_scale,\n            channels,\n            height,\n            width,\n            pooled_height,\n            pooled_width,\n            sampling_ratio,\n            grad_input.data_ptr<scalar_t>(),\n            rois_.data_ptr<scalar_t>());\n      });\n  AT_CUDA_CHECK(cudaGetLastError());\n  return grad_input;\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/csrc/box_iou_rotated/box_iou_rotated.h",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#pragma once\n#include <torch/types.h>\n\nnamespace detectron2 {\n\nat::Tensor box_iou_rotated_cpu(\n    const at::Tensor& boxes1,\n    const at::Tensor& boxes2);\n\n#if defined(WITH_CUDA) || defined(WITH_HIP)\nat::Tensor box_iou_rotated_cuda(\n    const at::Tensor& boxes1,\n    const at::Tensor& boxes2);\n#endif\n\n// Interface for Python\n// inline is needed to prevent multiple function definitions when this header is\n// included by different cpps\ninline at::Tensor box_iou_rotated(\n    const at::Tensor& boxes1,\n    const at::Tensor& boxes2) {\n  assert(boxes1.device().is_cuda() == boxes2.device().is_cuda());\n  if (boxes1.device().is_cuda()) {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n    return box_iou_rotated_cuda(boxes1.contiguous(), boxes2.contiguous());\n#else\n    AT_ERROR(\"Detectron2 is not compiled with GPU support!\");\n#endif\n  }\n\n  return box_iou_rotated_cpu(boxes1.contiguous(), boxes2.contiguous());\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/csrc/box_iou_rotated/box_iou_rotated_cpu.cpp",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#include \"box_iou_rotated.h\"\n#include \"box_iou_rotated_utils.h\"\n\nnamespace detectron2 {\n\ntemplate <typename T>\nvoid box_iou_rotated_cpu_kernel(\n    const at::Tensor& boxes1,\n    const at::Tensor& boxes2,\n    at::Tensor& ious) {\n  auto num_boxes1 = boxes1.size(0);\n  auto num_boxes2 = boxes2.size(0);\n\n  for (int i = 0; i < num_boxes1; i++) {\n    for (int j = 0; j < num_boxes2; j++) {\n      ious[i * num_boxes2 + j] = single_box_iou_rotated<T>(\n          boxes1[i].data_ptr<T>(), boxes2[j].data_ptr<T>());\n    }\n  }\n}\n\nat::Tensor box_iou_rotated_cpu(\n    // input must be contiguous:\n    const at::Tensor& boxes1,\n    const at::Tensor& boxes2) {\n  auto num_boxes1 = boxes1.size(0);\n  auto num_boxes2 = boxes2.size(0);\n  at::Tensor ious =\n      at::empty({num_boxes1 * num_boxes2}, boxes1.options().dtype(at::kFloat));\n\n  box_iou_rotated_cpu_kernel<float>(boxes1, boxes2, ious);\n\n  // reshape from 1d array to 2d array\n  auto shape = std::vector<int64_t>{num_boxes1, num_boxes2};\n  return ious.reshape(shape);\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/csrc/box_iou_rotated/box_iou_rotated_cuda.cu",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#include <ATen/ATen.h>\n#include <ATen/cuda/CUDAContext.h>\n#include <c10/cuda/CUDAGuard.h>\n#include <ATen/cuda/CUDAApplyUtils.cuh>\n#include \"box_iou_rotated_utils.h\"\n\nnamespace detectron2 {\n\n// 2D block with 32 * 16 = 512 threads per block\nconst int BLOCK_DIM_X = 32;\nconst int BLOCK_DIM_Y = 16;\n\ntemplate <typename T>\n__global__ void box_iou_rotated_cuda_kernel(\n    const int n_boxes1,\n    const int n_boxes2,\n    const T* dev_boxes1,\n    const T* dev_boxes2,\n    T* dev_ious) {\n  const int row_start = blockIdx.x * blockDim.x;\n  const int col_start = blockIdx.y * blockDim.y;\n\n  const int row_size = min(n_boxes1 - row_start, blockDim.x);\n  const int col_size = min(n_boxes2 - col_start, blockDim.y);\n\n  __shared__ float block_boxes1[BLOCK_DIM_X * 5];\n  __shared__ float block_boxes2[BLOCK_DIM_Y * 5];\n\n  // It's safe to copy using threadIdx.x since BLOCK_DIM_X >= BLOCK_DIM_Y\n  if (threadIdx.x < row_size && threadIdx.y == 0) {\n    block_boxes1[threadIdx.x * 5 + 0] =\n        dev_boxes1[(row_start + threadIdx.x) * 5 + 0];\n    block_boxes1[threadIdx.x * 5 + 1] =\n        dev_boxes1[(row_start + threadIdx.x) * 5 + 1];\n    block_boxes1[threadIdx.x * 5 + 2] =\n        dev_boxes1[(row_start + threadIdx.x) * 5 + 2];\n    block_boxes1[threadIdx.x * 5 + 3] =\n        dev_boxes1[(row_start + threadIdx.x) * 5 + 3];\n    block_boxes1[threadIdx.x * 5 + 4] =\n        dev_boxes1[(row_start + threadIdx.x) * 5 + 4];\n  }\n\n  if (threadIdx.x < col_size && threadIdx.y == 0) {\n    block_boxes2[threadIdx.x * 5 + 0] =\n        dev_boxes2[(col_start + threadIdx.x) * 5 + 0];\n    block_boxes2[threadIdx.x * 5 + 1] =\n        dev_boxes2[(col_start + threadIdx.x) * 5 + 1];\n    block_boxes2[threadIdx.x * 5 + 2] =\n        dev_boxes2[(col_start + threadIdx.x) * 5 + 2];\n    block_boxes2[threadIdx.x * 5 + 3] =\n        dev_boxes2[(col_start + threadIdx.x) * 5 + 3];\n    block_boxes2[threadIdx.x * 5 + 4] =\n        dev_boxes2[(col_start + threadIdx.x) * 5 + 4];\n  }\n  __syncthreads();\n\n  if (threadIdx.x < row_size && threadIdx.y < col_size) {\n    int offset = (row_start + threadIdx.x) * n_boxes2 + col_start + threadIdx.y;\n    dev_ious[offset] = single_box_iou_rotated<T>(\n        block_boxes1 + threadIdx.x * 5, block_boxes2 + threadIdx.y * 5);\n  }\n}\n\nat::Tensor box_iou_rotated_cuda(\n    // input must be contiguous\n    const at::Tensor& boxes1,\n    const at::Tensor& boxes2) {\n  using scalar_t = float;\n  AT_ASSERTM(\n      boxes1.scalar_type() == at::kFloat, \"boxes1 must be a float tensor\");\n  AT_ASSERTM(\n      boxes2.scalar_type() == at::kFloat, \"boxes2 must be a float tensor\");\n  AT_ASSERTM(boxes1.is_cuda(), \"boxes1 must be a CUDA tensor\");\n  AT_ASSERTM(boxes2.is_cuda(), \"boxes2 must be a CUDA tensor\");\n  at::cuda::CUDAGuard device_guard(boxes1.device());\n\n  auto num_boxes1 = boxes1.size(0);\n  auto num_boxes2 = boxes2.size(0);\n\n  at::Tensor ious =\n      at::empty({num_boxes1 * num_boxes2}, boxes1.options().dtype(at::kFloat));\n\n  bool transpose = false;\n  if (num_boxes1 > 0 && num_boxes2 > 0) {\n    scalar_t *data1 = boxes1.data_ptr<scalar_t>(),\n             *data2 = boxes2.data_ptr<scalar_t>();\n\n    if (num_boxes2 > 65535 * BLOCK_DIM_Y) {\n      AT_ASSERTM(\n          num_boxes1 <= 65535 * BLOCK_DIM_Y,\n          \"Too many boxes for box_iou_rotated_cuda!\");\n      // x dim is allowed to be large, but y dim cannot,\n      // so we transpose the two to avoid \"invalid configuration argument\"\n      // error. We assume one of them is small. Otherwise the result is hard to\n      // fit in memory anyway.\n      std::swap(num_boxes1, num_boxes2);\n      std::swap(data1, data2);\n      transpose = true;\n    }\n\n    const int blocks_x =\n        at::cuda::ATenCeilDiv(static_cast<int>(num_boxes1), BLOCK_DIM_X);\n    const int blocks_y =\n        at::cuda::ATenCeilDiv(static_cast<int>(num_boxes2), BLOCK_DIM_Y);\n\n    dim3 blocks(blocks_x, blocks_y);\n    dim3 threads(BLOCK_DIM_X, BLOCK_DIM_Y);\n    cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n    box_iou_rotated_cuda_kernel<scalar_t><<<blocks, threads, 0, stream>>>(\n        num_boxes1,\n        num_boxes2,\n        data1,\n        data2,\n        (scalar_t*)ious.data_ptr<scalar_t>());\n\n    AT_CUDA_CHECK(cudaGetLastError());\n  }\n\n  // reshape from 1d array to 2d array\n  auto shape = std::vector<int64_t>{num_boxes1, num_boxes2};\n  if (transpose) {\n    return ious.view(shape).t();\n  } else {\n    return ious.view(shape);\n  }\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/csrc/box_iou_rotated/box_iou_rotated_utils.h",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#pragma once\n\n#include <cassert>\n#include <cmath>\n\n#if defined(__CUDACC__) || __HCC__ == 1 || __HIP__ == 1\n// Designates functions callable from the host (CPU) and the device (GPU)\n#define HOST_DEVICE __host__ __device__\n#define HOST_DEVICE_INLINE HOST_DEVICE __forceinline__\n#else\n#include <algorithm>\n#define HOST_DEVICE\n#define HOST_DEVICE_INLINE HOST_DEVICE inline\n#endif\n\nnamespace detectron2 {\n\nnamespace {\n\ntemplate <typename T>\nstruct RotatedBox {\n  T x_ctr, y_ctr, w, h, a;\n};\n\ntemplate <typename T>\nstruct Point {\n  T x, y;\n  HOST_DEVICE_INLINE Point(const T& px = 0, const T& py = 0) : x(px), y(py) {}\n  HOST_DEVICE_INLINE Point operator+(const Point& p) const {\n    return Point(x + p.x, y + p.y);\n  }\n  HOST_DEVICE_INLINE Point& operator+=(const Point& p) {\n    x += p.x;\n    y += p.y;\n    return *this;\n  }\n  HOST_DEVICE_INLINE Point operator-(const Point& p) const {\n    return Point(x - p.x, y - p.y);\n  }\n  HOST_DEVICE_INLINE Point operator*(const T coeff) const {\n    return Point(x * coeff, y * coeff);\n  }\n};\n\ntemplate <typename T>\nHOST_DEVICE_INLINE T dot_2d(const Point<T>& A, const Point<T>& B) {\n  return A.x * B.x + A.y * B.y;\n}\n\n// R: result type. can be different from input type\ntemplate <typename T, typename R = T>\nHOST_DEVICE_INLINE R cross_2d(const Point<T>& A, const Point<T>& B) {\n  return static_cast<R>(A.x) * static_cast<R>(B.y) -\n      static_cast<R>(B.x) * static_cast<R>(A.y);\n}\n\ntemplate <typename T>\nHOST_DEVICE_INLINE void get_rotated_vertices(\n    const RotatedBox<T>& box,\n    Point<T> (&pts)[4]) {\n  // M_PI / 180. == 0.01745329251\n  double theta = box.a * 0.01745329251;\n  T cosTheta2 = (T)cos(theta) * 0.5f;\n  T sinTheta2 = (T)sin(theta) * 0.5f;\n\n  // y: top --> down; x: left --> right\n  pts[0].x = box.x_ctr + sinTheta2 * box.h + cosTheta2 * box.w;\n  pts[0].y = box.y_ctr + cosTheta2 * box.h - sinTheta2 * box.w;\n  pts[1].x = box.x_ctr - sinTheta2 * box.h + cosTheta2 * box.w;\n  pts[1].y = box.y_ctr - cosTheta2 * box.h - sinTheta2 * box.w;\n  pts[2].x = 2 * box.x_ctr - pts[0].x;\n  pts[2].y = 2 * box.y_ctr - pts[0].y;\n  pts[3].x = 2 * box.x_ctr - pts[1].x;\n  pts[3].y = 2 * box.y_ctr - pts[1].y;\n}\n\ntemplate <typename T>\nHOST_DEVICE_INLINE int get_intersection_points(\n    const Point<T> (&pts1)[4],\n    const Point<T> (&pts2)[4],\n    Point<T> (&intersections)[24]) {\n  // Line vector\n  // A line from p1 to p2 is: p1 + (p2-p1)*t, t=[0,1]\n  Point<T> vec1[4], vec2[4];\n  for (int i = 0; i < 4; i++) {\n    vec1[i] = pts1[(i + 1) % 4] - pts1[i];\n    vec2[i] = pts2[(i + 1) % 4] - pts2[i];\n  }\n\n  // When computing the intersection area, it doesn't hurt if we have\n  // more (duplicated/approximate) intersections/vertices than needed,\n  // while it can cause drastic difference if we miss an intersection/vertex.\n  // Therefore, we add an epsilon to relax the comparisons between\n  // the float point numbers that decide the intersection points.\n  double EPS = 1e-5;\n\n  // Line test - test all line combos for intersection\n  int num = 0; // number of intersections\n  for (int i = 0; i < 4; i++) {\n    for (int j = 0; j < 4; j++) {\n      // Solve for 2x2 Ax=b\n      T det = cross_2d<T>(vec2[j], vec1[i]);\n\n      // This takes care of parallel lines\n      if (fabs(det) <= 1e-14) {\n        continue;\n      }\n\n      auto vec12 = pts2[j] - pts1[i];\n\n      T t1 = cross_2d<T>(vec2[j], vec12) / det;\n      T t2 = cross_2d<T>(vec1[i], vec12) / det;\n\n      if (t1 > -EPS && t1 < 1.0f + EPS && t2 > -EPS && t2 < 1.0f + EPS) {\n        intersections[num++] = pts1[i] + vec1[i] * t1;\n      }\n    }\n  }\n\n  // Check for vertices of rect1 inside rect2\n  {\n    const auto& AB = vec2[0];\n    const auto& DA = vec2[3];\n    auto ABdotAB = dot_2d<T>(AB, AB);\n    auto ADdotAD = dot_2d<T>(DA, DA);\n    for (int i = 0; i < 4; i++) {\n      // assume ABCD is the rectangle, and P is the point to be judged\n      // P is inside ABCD iff. P's projection on AB lies within AB\n      // and P's projection on AD lies within AD\n\n      auto AP = pts1[i] - pts2[0];\n\n      auto APdotAB = dot_2d<T>(AP, AB);\n      auto APdotAD = -dot_2d<T>(AP, DA);\n\n      if ((APdotAB > -EPS) && (APdotAD > -EPS) && (APdotAB < ABdotAB + EPS) &&\n          (APdotAD < ADdotAD + EPS)) {\n        intersections[num++] = pts1[i];\n      }\n    }\n  }\n\n  // Reverse the check - check for vertices of rect2 inside rect1\n  {\n    const auto& AB = vec1[0];\n    const auto& DA = vec1[3];\n    auto ABdotAB = dot_2d<T>(AB, AB);\n    auto ADdotAD = dot_2d<T>(DA, DA);\n    for (int i = 0; i < 4; i++) {\n      auto AP = pts2[i] - pts1[0];\n\n      auto APdotAB = dot_2d<T>(AP, AB);\n      auto APdotAD = -dot_2d<T>(AP, DA);\n\n      if ((APdotAB > -EPS) && (APdotAD > -EPS) && (APdotAB < ABdotAB + EPS) &&\n          (APdotAD < ADdotAD + EPS)) {\n        intersections[num++] = pts2[i];\n      }\n    }\n  }\n\n  return num;\n}\n\ntemplate <typename T>\nHOST_DEVICE_INLINE int convex_hull_graham(\n    const Point<T> (&p)[24],\n    const int& num_in,\n    Point<T> (&q)[24],\n    bool shift_to_zero = false) {\n  assert(num_in >= 2);\n\n  // Step 1:\n  // Find point with minimum y\n  // if more than 1 points have the same minimum y,\n  // pick the one with the minimum x.\n  int t = 0;\n  for (int i = 1; i < num_in; i++) {\n    if (p[i].y < p[t].y || (p[i].y == p[t].y && p[i].x < p[t].x)) {\n      t = i;\n    }\n  }\n  auto& start = p[t]; // starting point\n\n  // Step 2:\n  // Subtract starting point from every points (for sorting in the next step)\n  for (int i = 0; i < num_in; i++) {\n    q[i] = p[i] - start;\n  }\n\n  // Swap the starting point to position 0\n  auto tmp = q[0];\n  q[0] = q[t];\n  q[t] = tmp;\n\n  // Step 3:\n  // Sort point 1 ~ num_in according to their relative cross-product values\n  // (essentially sorting according to angles)\n  // If the angles are the same, sort according to their distance to origin\n  T dist[24];\n#if defined(__CUDACC__) || __HCC__ == 1 || __HIP__ == 1\n  // compute distance to origin before sort, and sort them together with the\n  // points\n  for (int i = 0; i < num_in; i++) {\n    dist[i] = dot_2d<T>(q[i], q[i]);\n  }\n\n  // CUDA version\n  // In the future, we can potentially use thrust\n  // for sorting here to improve speed (though not guaranteed)\n  for (int i = 1; i < num_in - 1; i++) {\n    for (int j = i + 1; j < num_in; j++) {\n      T crossProduct = cross_2d<T>(q[i], q[j]);\n      if ((crossProduct < -1e-6) ||\n          (fabs(crossProduct) < 1e-6 && dist[i] > dist[j])) {\n        auto q_tmp = q[i];\n        q[i] = q[j];\n        q[j] = q_tmp;\n        auto dist_tmp = dist[i];\n        dist[i] = dist[j];\n        dist[j] = dist_tmp;\n      }\n    }\n  }\n#else\n  // CPU version\n  std::sort(\n      q + 1, q + num_in, [](const Point<T>& A, const Point<T>& B) -> bool {\n        T temp = cross_2d<T>(A, B);\n        if (fabs(temp) < 1e-6) {\n          return dot_2d<T>(A, A) < dot_2d<T>(B, B);\n        } else {\n          return temp > 0;\n        }\n      });\n  // compute distance to origin after sort, since the points are now different.\n  for (int i = 0; i < num_in; i++) {\n    dist[i] = dot_2d<T>(q[i], q[i]);\n  }\n#endif\n\n  // Step 4:\n  // Make sure there are at least 2 points (that don't overlap with each other)\n  // in the stack\n  int k; // index of the non-overlapped second point\n  for (k = 1; k < num_in; k++) {\n    if (dist[k] > 1e-8) {\n      break;\n    }\n  }\n  if (k == num_in) {\n    // We reach the end, which means the convex hull is just one point\n    q[0] = p[t];\n    return 1;\n  }\n  q[1] = q[k];\n  int m = 2; // 2 points in the stack\n  // Step 5:\n  // Finally we can start the scanning process.\n  // When a non-convex relationship between the 3 points is found\n  // (either concave shape or duplicated points),\n  // we pop the previous point from the stack\n  // until the 3-point relationship is convex again, or\n  // until the stack only contains two points\n  for (int i = k + 1; i < num_in; i++) {\n    while (m > 1) {\n      auto q1 = q[i] - q[m - 2], q2 = q[m - 1] - q[m - 2];\n      // cross_2d() uses FMA and therefore computes round(round(q1.x*q2.y) -\n      // q2.x*q1.y) So it may not return 0 even when q1==q2. Therefore we\n      // compare round(q1.x*q2.y) and round(q2.x*q1.y) directly. (round means\n      // round to nearest floating point).\n      if (q1.x * q2.y >= q2.x * q1.y)\n        m--;\n      else\n        break;\n    }\n    // Using double also helps, but float can solve the issue for now.\n    // while (m > 1 && cross_2d<T, double>(q[i] - q[m - 2], q[m - 1] - q[m - 2])\n    // >= 0) {\n    //     m--;\n    // }\n    q[m++] = q[i];\n  }\n\n  // Step 6 (Optional):\n  // In general sense we need the original coordinates, so we\n  // need to shift the points back (reverting Step 2)\n  // But if we're only interested in getting the area/perimeter of the shape\n  // We can simply return.\n  if (!shift_to_zero) {\n    for (int i = 0; i < m; i++) {\n      q[i] += start;\n    }\n  }\n\n  return m;\n}\n\ntemplate <typename T>\nHOST_DEVICE_INLINE T polygon_area(const Point<T> (&q)[24], const int& m) {\n  if (m <= 2) {\n    return 0;\n  }\n\n  T area = 0;\n  for (int i = 1; i < m - 1; i++) {\n    area += fabs(cross_2d<T>(q[i] - q[0], q[i + 1] - q[0]));\n  }\n\n  return area / 2.0;\n}\n\ntemplate <typename T>\nHOST_DEVICE_INLINE T rotated_boxes_intersection(\n    const RotatedBox<T>& box1,\n    const RotatedBox<T>& box2) {\n  // There are up to 4 x 4 + 4 + 4 = 24 intersections (including dups) returned\n  // from rotated_rect_intersection_pts\n  Point<T> intersectPts[24], orderedPts[24];\n\n  Point<T> pts1[4];\n  Point<T> pts2[4];\n  get_rotated_vertices<T>(box1, pts1);\n  get_rotated_vertices<T>(box2, pts2);\n\n  int num = get_intersection_points<T>(pts1, pts2, intersectPts);\n\n  if (num <= 2) {\n    return 0.0;\n  }\n\n  // Convex Hull to order the intersection points in clockwise order and find\n  // the contour area.\n  int num_convex = convex_hull_graham<T>(intersectPts, num, orderedPts, true);\n  return polygon_area<T>(orderedPts, num_convex);\n}\n\n} // namespace\n\ntemplate <typename T>\nHOST_DEVICE_INLINE T\nsingle_box_iou_rotated(T const* const box1_raw, T const* const box2_raw) {\n  // shift center to the middle point to achieve higher precision in result\n  RotatedBox<T> box1, box2;\n  auto center_shift_x = (box1_raw[0] + box2_raw[0]) / 2.0;\n  auto center_shift_y = (box1_raw[1] + box2_raw[1]) / 2.0;\n  box1.x_ctr = box1_raw[0] - center_shift_x;\n  box1.y_ctr = box1_raw[1] - center_shift_y;\n  box1.w = box1_raw[2];\n  box1.h = box1_raw[3];\n  box1.a = box1_raw[4];\n  box2.x_ctr = box2_raw[0] - center_shift_x;\n  box2.y_ctr = box2_raw[1] - center_shift_y;\n  box2.w = box2_raw[2];\n  box2.h = box2_raw[3];\n  box2.a = box2_raw[4];\n\n  T area1 = box1.w * box1.h;\n  T area2 = box2.w * box2.h;\n  if (area1 < 1e-14 || area2 < 1e-14) {\n    return 0.f;\n  }\n\n  T intersection = rotated_boxes_intersection<T>(box1, box2);\n  T iou = intersection / (area1 + area2 - intersection);\n  return iou;\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/csrc/cocoeval/cocoeval.cpp",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#include \"cocoeval.h\"\n#include <time.h>\n#include <algorithm>\n#include <cstdint>\n#include <numeric>\n\nusing namespace pybind11::literals;\n\nnamespace detectron2 {\n\nnamespace COCOeval {\n\n// Sort detections from highest score to lowest, such that\n// detection_instances[detection_sorted_indices[t]] >=\n// detection_instances[detection_sorted_indices[t+1]].  Use stable_sort to match\n// original COCO API\nvoid SortInstancesByDetectionScore(\n    const std::vector<InstanceAnnotation>& detection_instances,\n    std::vector<uint64_t>* detection_sorted_indices) {\n  detection_sorted_indices->resize(detection_instances.size());\n  std::iota(\n      detection_sorted_indices->begin(), detection_sorted_indices->end(), 0);\n  std::stable_sort(\n      detection_sorted_indices->begin(),\n      detection_sorted_indices->end(),\n      [&detection_instances](size_t j1, size_t j2) {\n        return detection_instances[j1].score > detection_instances[j2].score;\n      });\n}\n\n// Partition the ground truth objects based on whether or not to ignore them\n// based on area\nvoid SortInstancesByIgnore(\n    const std::array<double, 2>& area_range,\n    const std::vector<InstanceAnnotation>& ground_truth_instances,\n    std::vector<uint64_t>* ground_truth_sorted_indices,\n    std::vector<bool>* ignores) {\n  ignores->clear();\n  ignores->reserve(ground_truth_instances.size());\n  for (auto o : ground_truth_instances) {\n    ignores->push_back(\n        o.ignore || o.area < area_range[0] || o.area > area_range[1]);\n  }\n\n  ground_truth_sorted_indices->resize(ground_truth_instances.size());\n  std::iota(\n      ground_truth_sorted_indices->begin(),\n      ground_truth_sorted_indices->end(),\n      0);\n  std::stable_sort(\n      ground_truth_sorted_indices->begin(),\n      ground_truth_sorted_indices->end(),\n      [&ignores](size_t j1, size_t j2) {\n        return (int)(*ignores)[j1] < (int)(*ignores)[j2];\n      });\n}\n\n// For each IOU threshold, greedily match each detected instance to a ground\n// truth instance (if possible) and store the results\nvoid MatchDetectionsToGroundTruth(\n    const std::vector<InstanceAnnotation>& detection_instances,\n    const std::vector<uint64_t>& detection_sorted_indices,\n    const std::vector<InstanceAnnotation>& ground_truth_instances,\n    const std::vector<uint64_t>& ground_truth_sorted_indices,\n    const std::vector<bool>& ignores,\n    const std::vector<std::vector<double>>& ious,\n    const std::vector<double>& iou_thresholds,\n    const std::array<double, 2>& area_range,\n    ImageEvaluation* results) {\n  // Initialize memory to store return data matches and ignore\n  const int num_iou_thresholds = iou_thresholds.size();\n  const int num_ground_truth = ground_truth_sorted_indices.size();\n  const int num_detections = detection_sorted_indices.size();\n  std::vector<uint64_t> ground_truth_matches(\n      num_iou_thresholds * num_ground_truth, 0);\n  std::vector<uint64_t>& detection_matches = results->detection_matches;\n  std::vector<bool>& detection_ignores = results->detection_ignores;\n  std::vector<bool>& ground_truth_ignores = results->ground_truth_ignores;\n  detection_matches.resize(num_iou_thresholds * num_detections, 0);\n  detection_ignores.resize(num_iou_thresholds * num_detections, false);\n  ground_truth_ignores.resize(num_ground_truth);\n  for (auto g = 0; g < num_ground_truth; ++g) {\n    ground_truth_ignores[g] = ignores[ground_truth_sorted_indices[g]];\n  }\n\n  for (auto t = 0; t < num_iou_thresholds; ++t) {\n    for (auto d = 0; d < num_detections; ++d) {\n      // information about best match so far (match=-1 -> unmatched)\n      double best_iou = std::min(iou_thresholds[t], 1 - 1e-10);\n      int match = -1;\n      for (auto g = 0; g < num_ground_truth; ++g) {\n        // if this ground truth instance is already matched and not a\n        // crowd, it cannot be matched to another detection\n        if (ground_truth_matches[t * num_ground_truth + g] > 0 &&\n            !ground_truth_instances[ground_truth_sorted_indices[g]].is_crowd) {\n          continue;\n        }\n\n        // if detected instance matched to a regular ground truth\n        // instance, we can break on the first ground truth instance\n        // tagged as ignore (because they are sorted by the ignore tag)\n        if (match >= 0 && !ground_truth_ignores[match] &&\n            ground_truth_ignores[g]) {\n          break;\n        }\n\n        // if IOU overlap is the best so far, store the match appropriately\n        if (ious[d][ground_truth_sorted_indices[g]] >= best_iou) {\n          best_iou = ious[d][ground_truth_sorted_indices[g]];\n          match = g;\n        }\n      }\n      // if match was made, store id of match for both detection and\n      // ground truth\n      if (match >= 0) {\n        detection_ignores[t * num_detections + d] = ground_truth_ignores[match];\n        detection_matches[t * num_detections + d] =\n            ground_truth_instances[ground_truth_sorted_indices[match]].id;\n        ground_truth_matches[t * num_ground_truth + match] =\n            detection_instances[detection_sorted_indices[d]].id;\n      }\n\n      // set unmatched detections outside of area range to ignore\n      const InstanceAnnotation& detection =\n          detection_instances[detection_sorted_indices[d]];\n      detection_ignores[t * num_detections + d] =\n          detection_ignores[t * num_detections + d] ||\n          (detection_matches[t * num_detections + d] == 0 &&\n           (detection.area < area_range[0] || detection.area > area_range[1]));\n    }\n  }\n\n  // store detection score results\n  results->detection_scores.resize(detection_sorted_indices.size());\n  for (size_t d = 0; d < detection_sorted_indices.size(); ++d) {\n    results->detection_scores[d] =\n        detection_instances[detection_sorted_indices[d]].score;\n  }\n}\n\nstd::vector<ImageEvaluation> EvaluateImages(\n    const std::vector<std::array<double, 2>>& area_ranges,\n    int max_detections,\n    const std::vector<double>& iou_thresholds,\n    const ImageCategoryInstances<std::vector<double>>& image_category_ious,\n    const ImageCategoryInstances<InstanceAnnotation>&\n        image_category_ground_truth_instances,\n    const ImageCategoryInstances<InstanceAnnotation>&\n        image_category_detection_instances) {\n  const int num_area_ranges = area_ranges.size();\n  const int num_images = image_category_ground_truth_instances.size();\n  const int num_categories =\n      image_category_ious.size() > 0 ? image_category_ious[0].size() : 0;\n  std::vector<uint64_t> detection_sorted_indices;\n  std::vector<uint64_t> ground_truth_sorted_indices;\n  std::vector<bool> ignores;\n  std::vector<ImageEvaluation> results_all(\n      num_images * num_area_ranges * num_categories);\n\n  // Store results for each image, category, and area range combination. Results\n  // for each IOU threshold are packed into the same ImageEvaluation object\n  for (auto i = 0; i < num_images; ++i) {\n    for (auto c = 0; c < num_categories; ++c) {\n      const std::vector<InstanceAnnotation>& ground_truth_instances =\n          image_category_ground_truth_instances[i][c];\n      const std::vector<InstanceAnnotation>& detection_instances =\n          image_category_detection_instances[i][c];\n\n      SortInstancesByDetectionScore(\n          detection_instances, &detection_sorted_indices);\n      if ((int)detection_sorted_indices.size() > max_detections) {\n        detection_sorted_indices.resize(max_detections);\n      }\n\n      for (size_t a = 0; a < area_ranges.size(); ++a) {\n        SortInstancesByIgnore(\n            area_ranges[a],\n            ground_truth_instances,\n            &ground_truth_sorted_indices,\n            &ignores);\n\n        MatchDetectionsToGroundTruth(\n            detection_instances,\n            detection_sorted_indices,\n            ground_truth_instances,\n            ground_truth_sorted_indices,\n            ignores,\n            image_category_ious[i][c],\n            iou_thresholds,\n            area_ranges[a],\n            &results_all\n                [c * num_area_ranges * num_images + a * num_images + i]);\n      }\n    }\n  }\n\n  return results_all;\n}\n\n// Convert a python list to a vector\ntemplate <typename T>\nstd::vector<T> list_to_vec(const py::list& l) {\n  std::vector<T> v(py::len(l));\n  for (int i = 0; i < (int)py::len(l); ++i) {\n    v[i] = l[i].cast<T>();\n  }\n  return v;\n}\n\n// Helper function to Accumulate()\n// Considers the evaluation results applicable to a particular category, area\n// range, and max_detections parameter setting, which begin at\n// evaluations[evaluation_index].  Extracts a sorted list of length n of all\n// applicable detection instances concatenated across all images in the dataset,\n// which are represented by the outputs evaluation_indices, detection_scores,\n// image_detection_indices, and detection_sorted_indices--all of which are\n// length n. evaluation_indices[i] stores the applicable index into\n// evaluations[] for instance i, which has detection score detection_score[i],\n// and is the image_detection_indices[i]'th of the list of detections\n// for the image containing i.  detection_sorted_indices[] defines a sorted\n// permutation of the 3 other outputs\nint BuildSortedDetectionList(\n    const std::vector<ImageEvaluation>& evaluations,\n    const int64_t evaluation_index,\n    const int64_t num_images,\n    const int max_detections,\n    std::vector<uint64_t>* evaluation_indices,\n    std::vector<double>* detection_scores,\n    std::vector<uint64_t>* detection_sorted_indices,\n    std::vector<uint64_t>* image_detection_indices) {\n  assert(evaluations.size() >= evaluation_index + num_images);\n\n  // Extract a list of object instances of the applicable category, area\n  // range, and max detections requirements such that they can be sorted\n  image_detection_indices->clear();\n  evaluation_indices->clear();\n  detection_scores->clear();\n  image_detection_indices->reserve(num_images * max_detections);\n  evaluation_indices->reserve(num_images * max_detections);\n  detection_scores->reserve(num_images * max_detections);\n  int num_valid_ground_truth = 0;\n  for (auto i = 0; i < num_images; ++i) {\n    const ImageEvaluation& evaluation = evaluations[evaluation_index + i];\n\n    for (int d = 0;\n         d < (int)evaluation.detection_scores.size() && d < max_detections;\n         ++d) { // detected instances\n      evaluation_indices->push_back(evaluation_index + i);\n      image_detection_indices->push_back(d);\n      detection_scores->push_back(evaluation.detection_scores[d]);\n    }\n    for (auto ground_truth_ignore : evaluation.ground_truth_ignores) {\n      if (!ground_truth_ignore) {\n        ++num_valid_ground_truth;\n      }\n    }\n  }\n\n  // Sort detections by decreasing score, using stable sort to match\n  // python implementation\n  detection_sorted_indices->resize(detection_scores->size());\n  std::iota(\n      detection_sorted_indices->begin(), detection_sorted_indices->end(), 0);\n  std::stable_sort(\n      detection_sorted_indices->begin(),\n      detection_sorted_indices->end(),\n      [&detection_scores](size_t j1, size_t j2) {\n        return (*detection_scores)[j1] > (*detection_scores)[j2];\n      });\n\n  return num_valid_ground_truth;\n}\n\n// Helper function to Accumulate()\n// Compute a precision recall curve given a sorted list of detected instances\n// encoded in evaluations, evaluation_indices, detection_scores,\n// detection_sorted_indices, image_detection_indices (see\n// BuildSortedDetectionList()). Using vectors precisions and recalls\n// and temporary storage, output the results into precisions_out, recalls_out,\n// and scores_out, which are large buffers containing many precion/recall curves\n// for all possible parameter settings, with precisions_out_index and\n// recalls_out_index defining the applicable indices to store results.\nvoid ComputePrecisionRecallCurve(\n    const int64_t precisions_out_index,\n    const int64_t precisions_out_stride,\n    const int64_t recalls_out_index,\n    const std::vector<double>& recall_thresholds,\n    const int iou_threshold_index,\n    const int num_iou_thresholds,\n    const int num_valid_ground_truth,\n    const std::vector<ImageEvaluation>& evaluations,\n    const std::vector<uint64_t>& evaluation_indices,\n    const std::vector<double>& detection_scores,\n    const std::vector<uint64_t>& detection_sorted_indices,\n    const std::vector<uint64_t>& image_detection_indices,\n    std::vector<double>* precisions,\n    std::vector<double>* recalls,\n    std::vector<double>* precisions_out,\n    std::vector<double>* scores_out,\n    std::vector<double>* recalls_out) {\n  assert(recalls_out->size() > recalls_out_index);\n\n  // Compute precision/recall for each instance in the sorted list of detections\n  int64_t true_positives_sum = 0, false_positives_sum = 0;\n  precisions->clear();\n  recalls->clear();\n  precisions->reserve(detection_sorted_indices.size());\n  recalls->reserve(detection_sorted_indices.size());\n  assert(!evaluations.empty() || detection_sorted_indices.empty());\n  for (auto detection_sorted_index : detection_sorted_indices) {\n    const ImageEvaluation& evaluation =\n        evaluations[evaluation_indices[detection_sorted_index]];\n    const auto num_detections =\n        evaluation.detection_matches.size() / num_iou_thresholds;\n    const auto detection_index = iou_threshold_index * num_detections +\n        image_detection_indices[detection_sorted_index];\n    assert(evaluation.detection_matches.size() > detection_index);\n    assert(evaluation.detection_ignores.size() > detection_index);\n    const int64_t detection_match =\n        evaluation.detection_matches[detection_index];\n    const bool detection_ignores =\n        evaluation.detection_ignores[detection_index];\n    const auto true_positive = detection_match > 0 && !detection_ignores;\n    const auto false_positive = detection_match == 0 && !detection_ignores;\n    if (true_positive) {\n      ++true_positives_sum;\n    }\n    if (false_positive) {\n      ++false_positives_sum;\n    }\n\n    const double recall =\n        static_cast<double>(true_positives_sum) / num_valid_ground_truth;\n    recalls->push_back(recall);\n    const int64_t num_valid_detections =\n        true_positives_sum + false_positives_sum;\n    const double precision = num_valid_detections > 0\n        ? static_cast<double>(true_positives_sum) / num_valid_detections\n        : 0.0;\n    precisions->push_back(precision);\n  }\n\n  (*recalls_out)[recalls_out_index] = !recalls->empty() ? recalls->back() : 0;\n\n  for (int64_t i = static_cast<int64_t>(precisions->size()) - 1; i > 0; --i) {\n    if ((*precisions)[i] > (*precisions)[i - 1]) {\n      (*precisions)[i - 1] = (*precisions)[i];\n    }\n  }\n\n  // Sample the per instance precision/recall list at each recall threshold\n  for (size_t r = 0; r < recall_thresholds.size(); ++r) {\n    // first index in recalls >= recall_thresholds[r]\n    std::vector<double>::iterator low = std::lower_bound(\n        recalls->begin(), recalls->end(), recall_thresholds[r]);\n    size_t precisions_index = low - recalls->begin();\n\n    const auto results_ind = precisions_out_index + r * precisions_out_stride;\n    assert(results_ind < precisions_out->size());\n    assert(results_ind < scores_out->size());\n    if (precisions_index < precisions->size()) {\n      (*precisions_out)[results_ind] = (*precisions)[precisions_index];\n      (*scores_out)[results_ind] =\n          detection_scores[detection_sorted_indices[precisions_index]];\n    } else {\n      (*precisions_out)[results_ind] = 0;\n      (*scores_out)[results_ind] = 0;\n    }\n  }\n}\npy::dict Accumulate(\n    const py::object& params,\n    const std::vector<ImageEvaluation>& evaluations) {\n  const std::vector<double> recall_thresholds =\n      list_to_vec<double>(params.attr(\"recThrs\"));\n  const std::vector<int> max_detections =\n      list_to_vec<int>(params.attr(\"maxDets\"));\n  const int num_iou_thresholds = py::len(params.attr(\"iouThrs\"));\n  const int num_recall_thresholds = py::len(params.attr(\"recThrs\"));\n  const int num_categories = params.attr(\"useCats\").cast<int>() == 1\n      ? py::len(params.attr(\"catIds\"))\n      : 1;\n  const int num_area_ranges = py::len(params.attr(\"areaRng\"));\n  const int num_max_detections = py::len(params.attr(\"maxDets\"));\n  const int num_images = py::len(params.attr(\"imgIds\"));\n\n  std::vector<double> precisions_out(\n      num_iou_thresholds * num_recall_thresholds * num_categories *\n          num_area_ranges * num_max_detections,\n      -1);\n  std::vector<double> recalls_out(\n      num_iou_thresholds * num_categories * num_area_ranges *\n          num_max_detections,\n      -1);\n  std::vector<double> scores_out(\n      num_iou_thresholds * num_recall_thresholds * num_categories *\n          num_area_ranges * num_max_detections,\n      -1);\n\n  // Consider the list of all detected instances in the entire dataset in one\n  // large list.  evaluation_indices, detection_scores,\n  // image_detection_indices, and detection_sorted_indices all have the same\n  // length as this list, such that each entry corresponds to one detected\n  // instance\n  std::vector<uint64_t> evaluation_indices; // indices into evaluations[]\n  std::vector<double> detection_scores; // detection scores of each instance\n  std::vector<uint64_t> detection_sorted_indices; // sorted indices of all\n                                                  // instances in the dataset\n  std::vector<uint64_t>\n      image_detection_indices; // indices into the list of detected instances in\n                               // the same image as each instance\n  std::vector<double> precisions, recalls;\n\n  for (auto c = 0; c < num_categories; ++c) {\n    for (auto a = 0; a < num_area_ranges; ++a) {\n      for (auto m = 0; m < num_max_detections; ++m) {\n        // The COCO PythonAPI assumes evaluations[] (the return value of\n        // COCOeval::EvaluateImages() is one long list storing results for each\n        // combination of category, area range, and image id, with categories in\n        // the outermost loop and images in the innermost loop.\n        const int64_t evaluations_index =\n            c * num_area_ranges * num_images + a * num_images;\n        int num_valid_ground_truth = BuildSortedDetectionList(\n            evaluations,\n            evaluations_index,\n            num_images,\n            max_detections[m],\n            &evaluation_indices,\n            &detection_scores,\n            &detection_sorted_indices,\n            &image_detection_indices);\n\n        if (num_valid_ground_truth == 0) {\n          continue;\n        }\n\n        for (auto t = 0; t < num_iou_thresholds; ++t) {\n          // recalls_out is a flattened vectors representing a\n          // num_iou_thresholds X num_categories X num_area_ranges X\n          // num_max_detections matrix\n          const int64_t recalls_out_index =\n              t * num_categories * num_area_ranges * num_max_detections +\n              c * num_area_ranges * num_max_detections +\n              a * num_max_detections + m;\n\n          // precisions_out and scores_out are flattened vectors\n          // representing a num_iou_thresholds X num_recall_thresholds X\n          // num_categories X num_area_ranges X num_max_detections matrix\n          const int64_t precisions_out_stride =\n              num_categories * num_area_ranges * num_max_detections;\n          const int64_t precisions_out_index = t * num_recall_thresholds *\n                  num_categories * num_area_ranges * num_max_detections +\n              c * num_area_ranges * num_max_detections +\n              a * num_max_detections + m;\n\n          ComputePrecisionRecallCurve(\n              precisions_out_index,\n              precisions_out_stride,\n              recalls_out_index,\n              recall_thresholds,\n              t,\n              num_iou_thresholds,\n              num_valid_ground_truth,\n              evaluations,\n              evaluation_indices,\n              detection_scores,\n              detection_sorted_indices,\n              image_detection_indices,\n              &precisions,\n              &recalls,\n              &precisions_out,\n              &scores_out,\n              &recalls_out);\n        }\n      }\n    }\n  }\n\n  time_t rawtime;\n  struct tm local_time;\n  std::array<char, 200> buffer;\n  time(&rawtime);\n#ifdef _WIN32\n  localtime_s(&local_time, &rawtime);\n#else\n  localtime_r(&rawtime, &local_time);\n#endif\n  strftime(\n      buffer.data(), 200, \"%Y-%m-%d %H:%num_max_detections:%S\", &local_time);\n  return py::dict(\n      \"params\"_a = params,\n      \"counts\"_a = std::vector<int64_t>(\n          {num_iou_thresholds,\n           num_recall_thresholds,\n           num_categories,\n           num_area_ranges,\n           num_max_detections}),\n      \"date\"_a = buffer,\n      \"precision\"_a = precisions_out,\n      \"recall\"_a = recalls_out,\n      \"scores\"_a = scores_out);\n}\n\n} // namespace COCOeval\n\n} // namespace detectron2\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/csrc/cocoeval/cocoeval.h",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#pragma once\n\n#include <pybind11/numpy.h>\n#include <pybind11/pybind11.h>\n#include <pybind11/stl.h>\n#include <pybind11/stl_bind.h>\n#include <vector>\n\nnamespace py = pybind11;\n\nnamespace detectron2 {\n\nnamespace COCOeval {\n\n// Annotation data for a single object instance in an image\nstruct InstanceAnnotation {\n  InstanceAnnotation(\n      uint64_t id,\n      double score,\n      double area,\n      bool is_crowd,\n      bool ignore)\n      : id{id}, score{score}, area{area}, is_crowd{is_crowd}, ignore{ignore} {}\n  uint64_t id;\n  double score = 0.;\n  double area = 0.;\n  bool is_crowd = false;\n  bool ignore = false;\n};\n\n// Stores intermediate results for evaluating detection results for a single\n// image that has D detected instances and G ground truth instances. This stores\n// matches between detected and ground truth instances\nstruct ImageEvaluation {\n  // For each of the D detected instances, the id of the matched ground truth\n  // instance, or 0 if unmatched\n  std::vector<uint64_t> detection_matches;\n\n  // The detection score of each of the D detected instances\n  std::vector<double> detection_scores;\n\n  // Marks whether or not each of G instances was ignored from evaluation (e.g.,\n  // because it's outside area_range)\n  std::vector<bool> ground_truth_ignores;\n\n  // Marks whether or not each of D instances was ignored from evaluation (e.g.,\n  // because it's outside aRng)\n  std::vector<bool> detection_ignores;\n};\n\ntemplate <class T>\nusing ImageCategoryInstances = std::vector<std::vector<std::vector<T>>>;\n\n// C++ implementation of COCO API cocoeval.py::COCOeval.evaluateImg().  For each\n// combination of image, category, area range settings, and IOU thresholds to\n// evaluate, it matches detected instances to ground truth instances and stores\n// the results into a vector of ImageEvaluation results, which will be\n// interpreted by the COCOeval::Accumulate() function to produce precion-recall\n// curves.  The parameters of nested vectors have the following semantics:\n//   image_category_ious[i][c][d][g] is the intersection over union of the d'th\n//     detected instance and g'th ground truth instance of\n//     category category_ids[c] in image image_ids[i]\n//   image_category_ground_truth_instances[i][c] is a vector of ground truth\n//     instances in image image_ids[i] of category category_ids[c]\n//   image_category_detection_instances[i][c] is a vector of detected\n//     instances in image image_ids[i] of category category_ids[c]\nstd::vector<ImageEvaluation> EvaluateImages(\n    const std::vector<std::array<double, 2>>& area_ranges, // vector of 2-tuples\n    int max_detections,\n    const std::vector<double>& iou_thresholds,\n    const ImageCategoryInstances<std::vector<double>>& image_category_ious,\n    const ImageCategoryInstances<InstanceAnnotation>&\n        image_category_ground_truth_instances,\n    const ImageCategoryInstances<InstanceAnnotation>&\n        image_category_detection_instances);\n\n// C++ implementation of COCOeval.accumulate(), which generates precision\n// recall curves for each set of category, IOU threshold, detection area range,\n// and max number of detections parameters.  It is assumed that the parameter\n// evaluations is the return value of the functon COCOeval::EvaluateImages(),\n// which was called with the same parameter settings params\npy::dict Accumulate(\n    const py::object& params,\n    const std::vector<ImageEvaluation>& evalutations);\n\n} // namespace COCOeval\n} // namespace detectron2\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/csrc/cuda_version.cu",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n\n#include <cuda_runtime_api.h>\n\nnamespace detectron2 {\nint get_cudart_version() {\n// Not a ROCM platform: Either HIP is not used, or\n// it is used, but platform is not ROCM (i.e. it is CUDA)\n#if !defined(__HIP_PLATFORM_HCC__)\n  return CUDART_VERSION;\n#else\n  int version = 0;\n\n#if HIP_VERSION_MAJOR != 0\n  // Create a convention similar to that of CUDA, as assumed by other\n  // parts of the code.\n\n  version = HIP_VERSION_MINOR;\n  version += (HIP_VERSION_MAJOR * 100);\n#else\n  hipRuntimeGetVersion(&version);\n#endif\n  return version;\n#endif\n}\n} // namespace detectron2\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/csrc/deformable/deform_conv.h",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#pragma once\n#include <torch/types.h>\n\nnamespace detectron2 {\n\n#if defined(WITH_CUDA) || defined(WITH_HIP)\nint deform_conv_forward_cuda(\n    at::Tensor input,\n    at::Tensor weight,\n    at::Tensor offset,\n    at::Tensor output,\n    at::Tensor columns,\n    at::Tensor ones,\n    int kW,\n    int kH,\n    int dW,\n    int dH,\n    int padW,\n    int padH,\n    int dilationW,\n    int dilationH,\n    int group,\n    int deformable_group,\n    int im2col_step);\n\nint deform_conv_backward_input_cuda(\n    at::Tensor input,\n    at::Tensor offset,\n    at::Tensor gradOutput,\n    at::Tensor gradInput,\n    at::Tensor gradOffset,\n    at::Tensor weight,\n    at::Tensor columns,\n    int kW,\n    int kH,\n    int dW,\n    int dH,\n    int padW,\n    int padH,\n    int dilationW,\n    int dilationH,\n    int group,\n    int deformable_group,\n    int im2col_step);\n\nint deform_conv_backward_parameters_cuda(\n    at::Tensor input,\n    at::Tensor offset,\n    at::Tensor gradOutput,\n    at::Tensor gradWeight, // at::Tensor gradBias,\n    at::Tensor columns,\n    at::Tensor ones,\n    int kW,\n    int kH,\n    int dW,\n    int dH,\n    int padW,\n    int padH,\n    int dilationW,\n    int dilationH,\n    int group,\n    int deformable_group,\n    float scale,\n    int im2col_step);\n\nvoid modulated_deform_conv_cuda_forward(\n    at::Tensor input,\n    at::Tensor weight,\n    at::Tensor bias,\n    at::Tensor ones,\n    at::Tensor offset,\n    at::Tensor mask,\n    at::Tensor output,\n    at::Tensor columns,\n    int kernel_h,\n    int kernel_w,\n    const int stride_h,\n    const int stride_w,\n    const int pad_h,\n    const int pad_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int group,\n    const int deformable_group,\n    const bool with_bias);\n\nvoid modulated_deform_conv_cuda_backward(\n    at::Tensor input,\n    at::Tensor weight,\n    at::Tensor bias,\n    at::Tensor ones,\n    at::Tensor offset,\n    at::Tensor mask,\n    at::Tensor columns,\n    at::Tensor grad_input,\n    at::Tensor grad_weight,\n    at::Tensor grad_bias,\n    at::Tensor grad_offset,\n    at::Tensor grad_mask,\n    at::Tensor grad_output,\n    int kernel_h,\n    int kernel_w,\n    int stride_h,\n    int stride_w,\n    int pad_h,\n    int pad_w,\n    int dilation_h,\n    int dilation_w,\n    int group,\n    int deformable_group,\n    const bool with_bias);\n\n#endif\n\ninline int deform_conv_forward(\n    at::Tensor input,\n    at::Tensor weight,\n    at::Tensor offset,\n    at::Tensor output,\n    at::Tensor columns,\n    at::Tensor ones,\n    int kW,\n    int kH,\n    int dW,\n    int dH,\n    int padW,\n    int padH,\n    int dilationW,\n    int dilationH,\n    int group,\n    int deformable_group,\n    int im2col_step) {\n  if (input.is_cuda()) {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n    TORCH_CHECK(weight.is_cuda(), \"weight tensor is not on GPU!\");\n    TORCH_CHECK(offset.is_cuda(), \"offset tensor is not on GPU!\");\n    return deform_conv_forward_cuda(\n        input,\n        weight,\n        offset,\n        output,\n        columns,\n        ones,\n        kW,\n        kH,\n        dW,\n        dH,\n        padW,\n        padH,\n        dilationW,\n        dilationH,\n        group,\n        deformable_group,\n        im2col_step);\n#else\n    AT_ERROR(\"Detectron2 is not compiled with GPU support!\");\n#endif\n  }\n  AT_ERROR(\"This operator is not implemented on CPU\");\n}\n\ninline int deform_conv_backward_input(\n    at::Tensor input,\n    at::Tensor offset,\n    at::Tensor gradOutput,\n    at::Tensor gradInput,\n    at::Tensor gradOffset,\n    at::Tensor weight,\n    at::Tensor columns,\n    int kW,\n    int kH,\n    int dW,\n    int dH,\n    int padW,\n    int padH,\n    int dilationW,\n    int dilationH,\n    int group,\n    int deformable_group,\n    int im2col_step) {\n  if (gradOutput.is_cuda()) {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n    TORCH_CHECK(input.is_cuda(), \"input tensor is not on GPU!\");\n    TORCH_CHECK(weight.is_cuda(), \"weight tensor is not on GPU!\");\n    TORCH_CHECK(offset.is_cuda(), \"offset tensor is not on GPU!\");\n    return deform_conv_backward_input_cuda(\n        input,\n        offset,\n        gradOutput,\n        gradInput,\n        gradOffset,\n        weight,\n        columns,\n        kW,\n        kH,\n        dW,\n        dH,\n        padW,\n        padH,\n        dilationW,\n        dilationH,\n        group,\n        deformable_group,\n        im2col_step);\n#else\n    AT_ERROR(\"Detectron2 is not compiled with GPU support!\");\n#endif\n  }\n  AT_ERROR(\"This operator is not implemented on CPU\");\n}\n\ninline int deform_conv_backward_filter(\n    at::Tensor input,\n    at::Tensor offset,\n    at::Tensor gradOutput,\n    at::Tensor gradWeight, // at::Tensor gradBias,\n    at::Tensor columns,\n    at::Tensor ones,\n    int kW,\n    int kH,\n    int dW,\n    int dH,\n    int padW,\n    int padH,\n    int dilationW,\n    int dilationH,\n    int group,\n    int deformable_group,\n    float scale,\n    int im2col_step) {\n  if (gradOutput.is_cuda()) {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n    TORCH_CHECK(input.is_cuda(), \"input tensor is not on GPU!\");\n    TORCH_CHECK(offset.is_cuda(), \"offset tensor is not on GPU!\");\n    return deform_conv_backward_parameters_cuda(\n        input,\n        offset,\n        gradOutput,\n        gradWeight,\n        columns,\n        ones,\n        kW,\n        kH,\n        dW,\n        dH,\n        padW,\n        padH,\n        dilationW,\n        dilationH,\n        group,\n        deformable_group,\n        scale,\n        im2col_step);\n#else\n    AT_ERROR(\"Detectron2 is not compiled with GPU support!\");\n#endif\n  }\n  AT_ERROR(\"This operator is not implemented on CPU\");\n}\n\ninline void modulated_deform_conv_forward(\n    at::Tensor input,\n    at::Tensor weight,\n    at::Tensor bias,\n    at::Tensor ones,\n    at::Tensor offset,\n    at::Tensor mask,\n    at::Tensor output,\n    at::Tensor columns,\n    int kernel_h,\n    int kernel_w,\n    const int stride_h,\n    const int stride_w,\n    const int pad_h,\n    const int pad_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int group,\n    const int deformable_group,\n    const bool with_bias) {\n  if (input.is_cuda()) {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n    TORCH_CHECK(weight.is_cuda(), \"weight tensor is not on GPU!\");\n    TORCH_CHECK(bias.is_cuda(), \"bias tensor is not on GPU!\");\n    TORCH_CHECK(offset.is_cuda(), \"offset tensor is not on GPU!\");\n    return modulated_deform_conv_cuda_forward(\n        input,\n        weight,\n        bias,\n        ones,\n        offset,\n        mask,\n        output,\n        columns,\n        kernel_h,\n        kernel_w,\n        stride_h,\n        stride_w,\n        pad_h,\n        pad_w,\n        dilation_h,\n        dilation_w,\n        group,\n        deformable_group,\n        with_bias);\n#else\n    AT_ERROR(\"Detectron2 is not compiled with GPU support!\");\n#endif\n  }\n  AT_ERROR(\"This operator is not implemented on CPU\");\n}\n\ninline void modulated_deform_conv_backward(\n    at::Tensor input,\n    at::Tensor weight,\n    at::Tensor bias,\n    at::Tensor ones,\n    at::Tensor offset,\n    at::Tensor mask,\n    at::Tensor columns,\n    at::Tensor grad_input,\n    at::Tensor grad_weight,\n    at::Tensor grad_bias,\n    at::Tensor grad_offset,\n    at::Tensor grad_mask,\n    at::Tensor grad_output,\n    int kernel_h,\n    int kernel_w,\n    int stride_h,\n    int stride_w,\n    int pad_h,\n    int pad_w,\n    int dilation_h,\n    int dilation_w,\n    int group,\n    int deformable_group,\n    const bool with_bias) {\n  if (grad_output.is_cuda()) {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n    TORCH_CHECK(input.is_cuda(), \"input tensor is not on GPU!\");\n    TORCH_CHECK(weight.is_cuda(), \"weight tensor is not on GPU!\");\n    TORCH_CHECK(bias.is_cuda(), \"bias tensor is not on GPU!\");\n    TORCH_CHECK(offset.is_cuda(), \"offset tensor is not on GPU!\");\n    return modulated_deform_conv_cuda_backward(\n        input,\n        weight,\n        bias,\n        ones,\n        offset,\n        mask,\n        columns,\n        grad_input,\n        grad_weight,\n        grad_bias,\n        grad_offset,\n        grad_mask,\n        grad_output,\n        kernel_h,\n        kernel_w,\n        stride_h,\n        stride_w,\n        pad_h,\n        pad_w,\n        dilation_h,\n        dilation_w,\n        group,\n        deformable_group,\n        with_bias);\n#else\n    AT_ERROR(\"Detectron2 is not compiled with GPU support!\");\n#endif\n  }\n  AT_ERROR(\"This operator is not implemented on CPU\");\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/csrc/deformable/deform_conv_cuda.cu",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n\n// modified from\n// https://github.com/open-mmlab/mmdetection/blob/master/mmdet/ops/dcn/src/deform_conv_cuda.cpp\n// Original license: Apache 2.0\n\n// modify from\n// https://github.com/chengdazhi/Deformable-Convolution-V2-PyTorch/blob/mmdetection/mmdet/ops/dcn/src/deform_conv_cuda.c\n// Original license: Apache 2.0\n\n#include <torch/types.h>\n\n#include \"deform_conv.h\"\n\n#include <cmath>\n#include <vector>\n\nnamespace detectron2 {\n\nvoid deformable_im2col(\n    const at::Tensor data_im,\n    const at::Tensor data_offset,\n    const int channels,\n    const int height,\n    const int width,\n    const int ksize_h,\n    const int ksize_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int parallel_imgs,\n    const int deformable_group,\n    at::Tensor data_col);\n\nvoid deformable_col2im(\n    const at::Tensor data_col,\n    const at::Tensor data_offset,\n    const int channels,\n    const int height,\n    const int width,\n    const int ksize_h,\n    const int ksize_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int parallel_imgs,\n    const int deformable_group,\n    at::Tensor grad_im);\n\nvoid deformable_col2im_coord(\n    const at::Tensor data_col,\n    const at::Tensor data_im,\n    const at::Tensor data_offset,\n    const int channels,\n    const int height,\n    const int width,\n    const int ksize_h,\n    const int ksize_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int parallel_imgs,\n    const int deformable_group,\n    at::Tensor grad_offset);\n\nvoid modulated_deformable_im2col_cuda(\n    const at::Tensor data_im,\n    const at::Tensor data_offset,\n    const at::Tensor data_mask,\n    const int batch_size,\n    const int channels,\n    const int height_im,\n    const int width_im,\n    const int height_col,\n    const int width_col,\n    const int kernel_h,\n    const int kenerl_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int deformable_group,\n    at::Tensor data_col);\n\nvoid modulated_deformable_col2im_cuda(\n    const at::Tensor data_col,\n    const at::Tensor data_offset,\n    const at::Tensor data_mask,\n    const int batch_size,\n    const int channels,\n    const int height_im,\n    const int width_im,\n    const int height_col,\n    const int width_col,\n    const int kernel_h,\n    const int kenerl_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int deformable_group,\n    at::Tensor grad_im);\n\nvoid modulated_deformable_col2im_coord_cuda(\n    const at::Tensor data_col,\n    const at::Tensor data_im,\n    const at::Tensor data_offset,\n    const at::Tensor data_mask,\n    const int batch_size,\n    const int channels,\n    const int height_im,\n    const int width_im,\n    const int height_col,\n    const int width_col,\n    const int kernel_h,\n    const int kenerl_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int deformable_group,\n    at::Tensor grad_offset,\n    at::Tensor grad_mask);\n\nvoid shape_check(\n    at::Tensor input,\n    at::Tensor offset,\n    at::Tensor* gradOutput,\n    at::Tensor weight,\n    int kH,\n    int kW,\n    int dH,\n    int dW,\n    int padH,\n    int padW,\n    int dilationH,\n    int dilationW,\n    int group,\n    int deformable_group) {\n  TORCH_CHECK(\n      weight.ndimension() == 4,\n      \"4D weight tensor (nOutputPlane,nInputPlane,kH,kW) expected, \"\n      \"but got: %s\",\n      weight.ndimension());\n\n  TORCH_CHECK(weight.is_contiguous(), \"weight tensor has to be contiguous\");\n\n  TORCH_CHECK(\n      kW > 0 && kH > 0,\n      \"kernel size should be greater than zero, but got kH: %d kW: %d\",\n      kH,\n      kW);\n\n  TORCH_CHECK(\n      (weight.size(2) == kH && weight.size(3) == kW),\n      \"kernel size should be consistent with weight, \",\n      \"but got kH: %d kW: %d weight.size(2): %d, weight.size(3): %d\",\n      kH,\n      kW,\n      weight.size(2),\n      weight.size(3));\n\n  TORCH_CHECK(\n      dW > 0 && dH > 0,\n      \"stride should be greater than zero, but got dH: %d dW: %d\",\n      dH,\n      dW);\n\n  TORCH_CHECK(\n      dilationW > 0 && dilationH > 0,\n      \"dilation should be greater than 0, but got dilationH: %d dilationW: %d\",\n      dilationH,\n      dilationW);\n\n  int ndim = input.ndimension();\n  int dimf = 0;\n  int dimh = 1;\n  int dimw = 2;\n\n  if (ndim == 4) {\n    dimf++;\n    dimh++;\n    dimw++;\n  }\n\n  TORCH_CHECK(\n      ndim == 3 || ndim == 4,\n      \"3D or 4D input tensor expected but got: %s\",\n      ndim);\n\n  long nInputPlane = weight.size(1) * group;\n  long inputHeight = input.size(dimh);\n  long inputWidth = input.size(dimw);\n  long nOutputPlane = weight.size(0);\n  long outputHeight =\n      (inputHeight + 2 * padH - (dilationH * (kH - 1) + 1)) / dH + 1;\n  long outputWidth =\n      (inputWidth + 2 * padW - (dilationW * (kW - 1) + 1)) / dW + 1;\n\n  TORCH_CHECK(\n      nInputPlane % deformable_group == 0,\n      \"input channels must divide deformable group size\");\n\n  if (outputWidth < 1 || outputHeight < 1)\n    AT_ERROR(\n        \"Given input size: (%ld x %ld x %ld). \"\n        \"Calculated output size: (%ld x %ld x %ld). Output size is too small\",\n        nInputPlane,\n        inputHeight,\n        inputWidth,\n        nOutputPlane,\n        outputHeight,\n        outputWidth);\n\n  TORCH_CHECK(\n      input.size(1) == nInputPlane,\n      \"invalid number of input planes, expected: %d, but got: %d\",\n      nInputPlane,\n      input.size(1));\n\n  TORCH_CHECK(\n      (inputHeight + 2 * padH >= kH && inputWidth + 2 * padW >= kW),\n      \"input image is smaller than kernel\");\n\n  TORCH_CHECK(\n      (offset.size(2) == outputHeight && offset.size(3) == outputWidth),\n      \"invalid spatial size of offset, expected height: %d width: %d, but \"\n      \"got height: %d width: %d\",\n      outputHeight,\n      outputWidth,\n      offset.size(2),\n      offset.size(3));\n\n  TORCH_CHECK(\n      (offset.size(1) == deformable_group * 2 * kH * kW),\n      \"invalid number of channels of offset\");\n\n  if (gradOutput != NULL) {\n    TORCH_CHECK(\n        gradOutput->size(dimf) == nOutputPlane,\n        \"invalid number of gradOutput planes, expected: %d, but got: %d\",\n        nOutputPlane,\n        gradOutput->size(dimf));\n\n    TORCH_CHECK(\n        (gradOutput->size(dimh) == outputHeight &&\n         gradOutput->size(dimw) == outputWidth),\n        \"invalid size of gradOutput, expected height: %d width: %d , but \"\n        \"got height: %d width: %d\",\n        outputHeight,\n        outputWidth,\n        gradOutput->size(dimh),\n        gradOutput->size(dimw));\n  }\n}\n\nint deform_conv_forward_cuda(\n    at::Tensor input,\n    at::Tensor weight,\n    at::Tensor offset,\n    at::Tensor output,\n    at::Tensor columns,\n    at::Tensor ones,\n    int kW,\n    int kH,\n    int dW,\n    int dH,\n    int padW,\n    int padH,\n    int dilationW,\n    int dilationH,\n    int group,\n    int deformable_group,\n    int im2col_step) {\n  // todo: resize columns to include im2col: done\n  // todo: add im2col_step as input\n  // todo: add new output buffer and transpose it to output (or directly\n  // transpose output) todo: possibly change data indexing because of\n  // parallel_imgs\n\n  shape_check(\n      input,\n      offset,\n      NULL,\n      weight,\n      kH,\n      kW,\n      dH,\n      dW,\n      padH,\n      padW,\n      dilationH,\n      dilationW,\n      group,\n      deformable_group);\n\n  input = input.contiguous();\n  offset = offset.contiguous();\n  weight = weight.contiguous();\n\n  int batch = 1;\n  if (input.ndimension() == 3) {\n    // Force batch\n    batch = 0;\n    input.unsqueeze_(0);\n    offset.unsqueeze_(0);\n  }\n\n  // todo: assert batchsize dividable by im2col_step\n\n  long batchSize = input.size(0);\n  long nInputPlane = input.size(1);\n  long inputHeight = input.size(2);\n  long inputWidth = input.size(3);\n\n  long nOutputPlane = weight.size(0);\n\n  long outputWidth =\n      (inputWidth + 2 * padW - (dilationW * (kW - 1) + 1)) / dW + 1;\n  long outputHeight =\n      (inputHeight + 2 * padH - (dilationH * (kH - 1) + 1)) / dH + 1;\n\n  TORCH_CHECK((offset.size(0) == batchSize), \"invalid batch size of offset\");\n\n  output = output.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       nOutputPlane,\n       outputHeight,\n       outputWidth});\n  columns = at::zeros(\n      {nInputPlane * kW * kH, im2col_step * outputHeight * outputWidth},\n      input.options());\n\n  if (ones.ndimension() != 2 ||\n      ones.size(0) * ones.size(1) < outputHeight * outputWidth) {\n    ones = at::ones({outputHeight, outputWidth}, input.options());\n  }\n\n  input = input.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       nInputPlane,\n       inputHeight,\n       inputWidth});\n  offset = offset.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       deformable_group * 2 * kH * kW,\n       outputHeight,\n       outputWidth});\n\n  at::Tensor output_buffer = at::zeros(\n      {batchSize / im2col_step,\n       nOutputPlane,\n       im2col_step * outputHeight,\n       outputWidth},\n      output.options());\n\n  output_buffer = output_buffer.view(\n      {output_buffer.size(0),\n       group,\n       output_buffer.size(1) / group,\n       output_buffer.size(2),\n       output_buffer.size(3)});\n\n  for (int elt = 0; elt < batchSize / im2col_step; elt++) {\n    deformable_im2col(\n        input[elt],\n        offset[elt],\n        nInputPlane,\n        inputHeight,\n        inputWidth,\n        kH,\n        kW,\n        padH,\n        padW,\n        dH,\n        dW,\n        dilationH,\n        dilationW,\n        im2col_step,\n        deformable_group,\n        columns);\n\n    columns = columns.view({group, columns.size(0) / group, columns.size(1)});\n    weight = weight.view(\n        {group,\n         weight.size(0) / group,\n         weight.size(1),\n         weight.size(2),\n         weight.size(3)});\n\n    for (int g = 0; g < group; g++) {\n      output_buffer[elt][g] = output_buffer[elt][g]\n                                  .flatten(1)\n                                  .addmm_(weight[g].flatten(1), columns[g])\n                                  .view_as(output_buffer[elt][g]);\n    }\n  }\n\n  output_buffer = output_buffer.view(\n      {output_buffer.size(0),\n       output_buffer.size(1) * output_buffer.size(2),\n       output_buffer.size(3),\n       output_buffer.size(4)});\n\n  output_buffer = output_buffer.view(\n      {batchSize / im2col_step,\n       nOutputPlane,\n       im2col_step,\n       outputHeight,\n       outputWidth});\n  output_buffer.transpose_(1, 2);\n  output.copy_(output_buffer);\n  output = output.view({batchSize, nOutputPlane, outputHeight, outputWidth});\n\n  input = input.view({batchSize, nInputPlane, inputHeight, inputWidth});\n  offset = offset.view(\n      {batchSize, deformable_group * 2 * kH * kW, outputHeight, outputWidth});\n\n  if (batch == 0) {\n    output = output.view({nOutputPlane, outputHeight, outputWidth});\n    input = input.view({nInputPlane, inputHeight, inputWidth});\n    offset = offset.view({offset.size(1), offset.size(2), offset.size(3)});\n  }\n\n  return 1;\n}\n\nint deform_conv_backward_input_cuda(\n    at::Tensor input,\n    at::Tensor offset,\n    at::Tensor gradOutput,\n    at::Tensor gradInput,\n    at::Tensor gradOffset,\n    at::Tensor weight,\n    at::Tensor columns,\n    int kW,\n    int kH,\n    int dW,\n    int dH,\n    int padW,\n    int padH,\n    int dilationW,\n    int dilationH,\n    int group,\n    int deformable_group,\n    int im2col_step) {\n  shape_check(\n      input,\n      offset,\n      &gradOutput,\n      weight,\n      kH,\n      kW,\n      dH,\n      dW,\n      padH,\n      padW,\n      dilationH,\n      dilationW,\n      group,\n      deformable_group);\n\n  input = input.contiguous();\n  offset = offset.contiguous();\n  gradOutput = gradOutput.contiguous();\n  weight = weight.contiguous();\n\n  int batch = 1;\n\n  if (input.ndimension() == 3) {\n    // Force batch\n    batch = 0;\n    input = input.view({1, input.size(0), input.size(1), input.size(2)});\n    offset = offset.view({1, offset.size(0), offset.size(1), offset.size(2)});\n    gradOutput = gradOutput.view(\n        {1, gradOutput.size(0), gradOutput.size(1), gradOutput.size(2)});\n  }\n\n  long batchSize = input.size(0);\n  long nInputPlane = input.size(1);\n  long inputHeight = input.size(2);\n  long inputWidth = input.size(3);\n\n  long nOutputPlane = weight.size(0);\n\n  long outputWidth =\n      (inputWidth + 2 * padW - (dilationW * (kW - 1) + 1)) / dW + 1;\n  long outputHeight =\n      (inputHeight + 2 * padH - (dilationH * (kH - 1) + 1)) / dH + 1;\n\n  TORCH_CHECK((offset.size(0) == batchSize), 3, \"invalid batch size of offset\");\n  gradInput = gradInput.view({batchSize, nInputPlane, inputHeight, inputWidth});\n  columns = at::zeros(\n      {nInputPlane * kW * kH, im2col_step * outputHeight * outputWidth},\n      input.options());\n\n  // change order of grad output\n  gradOutput = gradOutput.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       nOutputPlane,\n       outputHeight,\n       outputWidth});\n  gradOutput.transpose_(1, 2);\n\n  gradInput = gradInput.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       nInputPlane,\n       inputHeight,\n       inputWidth});\n  input = input.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       nInputPlane,\n       inputHeight,\n       inputWidth});\n  gradOffset = gradOffset.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       deformable_group * 2 * kH * kW,\n       outputHeight,\n       outputWidth});\n  offset = offset.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       deformable_group * 2 * kH * kW,\n       outputHeight,\n       outputWidth});\n\n  for (int elt = 0; elt < batchSize / im2col_step; elt++) {\n    // divide into groups\n    columns = columns.view({group, columns.size(0) / group, columns.size(1)});\n    weight = weight.view(\n        {group,\n         weight.size(0) / group,\n         weight.size(1),\n         weight.size(2),\n         weight.size(3)});\n    gradOutput = gradOutput.view(\n        {gradOutput.size(0),\n         group,\n         gradOutput.size(1) / group,\n         gradOutput.size(2),\n         gradOutput.size(3),\n         gradOutput.size(4)});\n\n    for (int g = 0; g < group; g++) {\n      columns[g] = columns[g].addmm_(\n          weight[g].flatten(1).transpose(0, 1),\n          gradOutput[elt][g].flatten(1),\n          0.0f,\n          1.0f);\n    }\n\n    columns =\n        columns.view({columns.size(0) * columns.size(1), columns.size(2)});\n    gradOutput = gradOutput.view(\n        {gradOutput.size(0),\n         gradOutput.size(1) * gradOutput.size(2),\n         gradOutput.size(3),\n         gradOutput.size(4),\n         gradOutput.size(5)});\n\n    deformable_col2im_coord(\n        columns,\n        input[elt],\n        offset[elt],\n        nInputPlane,\n        inputHeight,\n        inputWidth,\n        kH,\n        kW,\n        padH,\n        padW,\n        dH,\n        dW,\n        dilationH,\n        dilationW,\n        im2col_step,\n        deformable_group,\n        gradOffset[elt]);\n\n    deformable_col2im(\n        columns,\n        offset[elt],\n        nInputPlane,\n        inputHeight,\n        inputWidth,\n        kH,\n        kW,\n        padH,\n        padW,\n        dH,\n        dW,\n        dilationH,\n        dilationW,\n        im2col_step,\n        deformable_group,\n        gradInput[elt]);\n  }\n\n  gradOutput.transpose_(1, 2);\n  gradOutput =\n      gradOutput.view({batchSize, nOutputPlane, outputHeight, outputWidth});\n\n  gradInput = gradInput.view({batchSize, nInputPlane, inputHeight, inputWidth});\n  input = input.view({batchSize, nInputPlane, inputHeight, inputWidth});\n  gradOffset = gradOffset.view(\n      {batchSize, deformable_group * 2 * kH * kW, outputHeight, outputWidth});\n  offset = offset.view(\n      {batchSize, deformable_group * 2 * kH * kW, outputHeight, outputWidth});\n\n  if (batch == 0) {\n    gradOutput = gradOutput.view({nOutputPlane, outputHeight, outputWidth});\n    input = input.view({nInputPlane, inputHeight, inputWidth});\n    gradInput = gradInput.view({nInputPlane, inputHeight, inputWidth});\n    offset = offset.view({offset.size(1), offset.size(2), offset.size(3)});\n    gradOffset =\n        gradOffset.view({offset.size(1), offset.size(2), offset.size(3)});\n  }\n\n  return 1;\n}\n\nint deform_conv_backward_parameters_cuda(\n    at::Tensor input,\n    at::Tensor offset,\n    at::Tensor gradOutput,\n    at::Tensor gradWeight, // at::Tensor gradBias,\n    at::Tensor columns,\n    at::Tensor ones,\n    int kW,\n    int kH,\n    int dW,\n    int dH,\n    int padW,\n    int padH,\n    int dilationW,\n    int dilationH,\n    int group,\n    int deformable_group,\n    float scale,\n    int im2col_step) {\n  // todo: transpose and reshape outGrad\n  // todo: reshape columns\n  // todo: add im2col_step as input\n\n  shape_check(\n      input,\n      offset,\n      &gradOutput,\n      gradWeight,\n      kH,\n      kW,\n      dH,\n      dW,\n      padH,\n      padW,\n      dilationH,\n      dilationW,\n      group,\n      deformable_group);\n\n  input = input.contiguous();\n  offset = offset.contiguous();\n  gradOutput = gradOutput.contiguous();\n\n  int batch = 1;\n\n  if (input.ndimension() == 3) {\n    // Force batch\n    batch = 0;\n    input = input.view(\n        at::IntList({1, input.size(0), input.size(1), input.size(2)}));\n    gradOutput = gradOutput.view(\n        {1, gradOutput.size(0), gradOutput.size(1), gradOutput.size(2)});\n  }\n\n  long batchSize = input.size(0);\n  long nInputPlane = input.size(1);\n  long inputHeight = input.size(2);\n  long inputWidth = input.size(3);\n\n  long nOutputPlane = gradWeight.size(0);\n\n  long outputWidth =\n      (inputWidth + 2 * padW - (dilationW * (kW - 1) + 1)) / dW + 1;\n  long outputHeight =\n      (inputHeight + 2 * padH - (dilationH * (kH - 1) + 1)) / dH + 1;\n\n  TORCH_CHECK((offset.size(0) == batchSize), \"invalid batch size of offset\");\n\n  columns = at::zeros(\n      {nInputPlane * kW * kH, im2col_step * outputHeight * outputWidth},\n      input.options());\n\n  gradOutput = gradOutput.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       nOutputPlane,\n       outputHeight,\n       outputWidth});\n  gradOutput.transpose_(1, 2);\n\n  at::Tensor gradOutputBuffer = at::zeros_like(gradOutput);\n  gradOutputBuffer = gradOutputBuffer.view(\n      {batchSize / im2col_step,\n       nOutputPlane,\n       im2col_step,\n       outputHeight,\n       outputWidth});\n  gradOutputBuffer.copy_(gradOutput);\n  // gradOutput is not contiguous, so we do reshape (instead of view) next\n  gradOutputBuffer = gradOutputBuffer.reshape(\n      {batchSize / im2col_step,\n       nOutputPlane,\n       im2col_step * outputHeight,\n       outputWidth});\n\n  gradOutput.transpose_(1, 2);\n  gradOutput =\n      gradOutput.view({batchSize, nOutputPlane, outputHeight, outputWidth});\n\n  input = input.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       nInputPlane,\n       inputHeight,\n       inputWidth});\n  offset = offset.view(\n      {batchSize / im2col_step,\n       im2col_step,\n       deformable_group * 2 * kH * kW,\n       outputHeight,\n       outputWidth});\n\n  for (int elt = 0; elt < batchSize / im2col_step; elt++) {\n    deformable_im2col(\n        input[elt],\n        offset[elt],\n        nInputPlane,\n        inputHeight,\n        inputWidth,\n        kH,\n        kW,\n        padH,\n        padW,\n        dH,\n        dW,\n        dilationH,\n        dilationW,\n        im2col_step,\n        deformable_group,\n        columns);\n\n    // divide into group\n    gradOutputBuffer = gradOutputBuffer.view(\n        {gradOutputBuffer.size(0),\n         group,\n         gradOutputBuffer.size(1) / group,\n         gradOutputBuffer.size(2),\n         gradOutputBuffer.size(3)});\n    columns = columns.view({group, columns.size(0) / group, columns.size(1)});\n    gradWeight = gradWeight.view(\n        {group,\n         gradWeight.size(0) / group,\n         gradWeight.size(1),\n         gradWeight.size(2),\n         gradWeight.size(3)});\n\n    for (int g = 0; g < group; g++) {\n      gradWeight[g] = gradWeight[g]\n                          .flatten(1)\n                          .addmm_(\n                              gradOutputBuffer[elt][g].flatten(1),\n                              columns[g].transpose(1, 0),\n                              1.0,\n                              scale)\n                          .view_as(gradWeight[g]);\n    }\n    gradOutputBuffer = gradOutputBuffer.view(\n        {gradOutputBuffer.size(0),\n         gradOutputBuffer.size(1) * gradOutputBuffer.size(2),\n         gradOutputBuffer.size(3),\n         gradOutputBuffer.size(4)});\n    columns =\n        columns.view({columns.size(0) * columns.size(1), columns.size(2)});\n    gradWeight = gradWeight.view(\n        {gradWeight.size(0) * gradWeight.size(1),\n         gradWeight.size(2),\n         gradWeight.size(3),\n         gradWeight.size(4)});\n  }\n\n  input = input.view({batchSize, nInputPlane, inputHeight, inputWidth});\n  offset = offset.view(\n      {batchSize, deformable_group * 2 * kH * kW, outputHeight, outputWidth});\n\n  if (batch == 0) {\n    gradOutput = gradOutput.view({nOutputPlane, outputHeight, outputWidth});\n    input = input.view({nInputPlane, inputHeight, inputWidth});\n  }\n\n  return 1;\n}\n\nvoid modulated_deform_conv_cuda_forward(\n    at::Tensor input,\n    at::Tensor weight,\n    at::Tensor bias,\n    at::Tensor ones,\n    at::Tensor offset,\n    at::Tensor mask,\n    at::Tensor output,\n    at::Tensor columns,\n    int kernel_h,\n    int kernel_w,\n    const int stride_h,\n    const int stride_w,\n    const int pad_h,\n    const int pad_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int group,\n    const int deformable_group,\n    const bool with_bias) {\n  shape_check(\n      input,\n      offset,\n      NULL,\n      weight,\n      kernel_h,\n      kernel_w,\n      stride_h,\n      stride_w,\n      pad_h,\n      pad_w,\n      dilation_h,\n      dilation_w,\n      group,\n      deformable_group);\n\n  TORCH_CHECK(input.is_contiguous(), \"input tensor has to be contiguous\");\n  TORCH_CHECK(weight.is_contiguous(), \"weight tensor has to be contiguous\");\n\n  const int batch = input.size(0);\n  const int channels = input.size(1);\n  const int height = input.size(2);\n  const int width = input.size(3);\n\n  const int channels_out = weight.size(0);\n  const int channels_kernel = weight.size(1);\n  const int kernel_h_ = weight.size(2);\n  const int kernel_w_ = weight.size(3);\n\n  if (kernel_h_ != kernel_h || kernel_w_ != kernel_w)\n    AT_ERROR(\n        \"Input shape and kernel shape wont match: (%d x %d vs %d x %d).\",\n        kernel_h_,\n        kernel_w,\n        kernel_h_,\n        kernel_w_);\n  if (channels != channels_kernel * group)\n    AT_ERROR(\n        \"Input shape and kernel channels wont match: (%d vs %d).\",\n        channels,\n        channels_kernel * group);\n\n  const int height_out =\n      (height + 2 * pad_h - (dilation_h * (kernel_h - 1) + 1)) / stride_h + 1;\n  const int width_out =\n      (width + 2 * pad_w - (dilation_w * (kernel_w - 1) + 1)) / stride_w + 1;\n\n  // mask shape check\n  TORCH_CHECK(\n      (mask.size(2) == height_out && mask.size(3) == width_out),\n      \"invalid spatial size of mask, expected height: %d width: %d, but \"\n      \"got height: %d width: %d\",\n      height_out,\n      width_out,\n      mask.size(2),\n      mask.size(3));\n\n  TORCH_CHECK(\n      (mask.size(1) == deformable_group * kernel_h * kernel_w),\n      \"invalid number of channels of mask\");\n\n  if (ones.ndimension() != 2 ||\n      ones.size(0) * ones.size(1) < height_out * width_out) {\n    // Resize plane and fill with ones...\n    ones = at::ones({height_out, width_out}, input.options());\n  }\n\n  // resize output\n  output = output.view({batch, channels_out, height_out, width_out}).zero_();\n  // resize temporary columns\n  columns = at::zeros(\n      {channels * kernel_h * kernel_w, 1 * height_out * width_out},\n      input.options());\n\n  output = output.view(\n      {output.size(0),\n       group,\n       output.size(1) / group,\n       output.size(2),\n       output.size(3)});\n\n  for (int b = 0; b < batch; b++) {\n    modulated_deformable_im2col_cuda(\n        input[b],\n        offset[b],\n        mask[b],\n        1,\n        channels,\n        height,\n        width,\n        height_out,\n        width_out,\n        kernel_h,\n        kernel_w,\n        pad_h,\n        pad_w,\n        stride_h,\n        stride_w,\n        dilation_h,\n        dilation_w,\n        deformable_group,\n        columns);\n\n    // divide into group\n    weight = weight.view(\n        {group,\n         weight.size(0) / group,\n         weight.size(1),\n         weight.size(2),\n         weight.size(3)});\n    columns = columns.view({group, columns.size(0) / group, columns.size(1)});\n\n    for (int g = 0; g < group; g++) {\n      output[b][g] = output[b][g]\n                         .flatten(1)\n                         .addmm_(weight[g].flatten(1), columns[g])\n                         .view_as(output[b][g]);\n    }\n\n    weight = weight.view(\n        {weight.size(0) * weight.size(1),\n         weight.size(2),\n         weight.size(3),\n         weight.size(4)});\n    columns =\n        columns.view({columns.size(0) * columns.size(1), columns.size(2)});\n  }\n\n  output = output.view(\n      {output.size(0),\n       output.size(1) * output.size(2),\n       output.size(3),\n       output.size(4)});\n\n  if (with_bias) {\n    output += bias.view({1, bias.size(0), 1, 1});\n  }\n}\n\nvoid modulated_deform_conv_cuda_backward(\n    at::Tensor input,\n    at::Tensor weight,\n    at::Tensor bias,\n    at::Tensor ones,\n    at::Tensor offset,\n    at::Tensor mask,\n    at::Tensor columns,\n    at::Tensor grad_input,\n    at::Tensor grad_weight,\n    at::Tensor grad_bias,\n    at::Tensor grad_offset,\n    at::Tensor grad_mask,\n    at::Tensor grad_output,\n    int kernel_h,\n    int kernel_w,\n    int stride_h,\n    int stride_w,\n    int pad_h,\n    int pad_w,\n    int dilation_h,\n    int dilation_w,\n    int group,\n    int deformable_group,\n    const bool with_bias) {\n  shape_check(\n      input,\n      offset,\n      &grad_output,\n      weight,\n      kernel_h,\n      kernel_w,\n      stride_h,\n      stride_w,\n      pad_h,\n      pad_w,\n      dilation_h,\n      dilation_w,\n      group,\n      deformable_group);\n\n  TORCH_CHECK(input.is_contiguous(), \"input tensor has to be contiguous\");\n  TORCH_CHECK(weight.is_contiguous(), \"weight tensor has to be contiguous\");\n\n  const int batch = input.size(0);\n  const int channels = input.size(1);\n  const int height = input.size(2);\n  const int width = input.size(3);\n\n  const int channels_kernel = weight.size(1);\n  const int kernel_h_ = weight.size(2);\n  const int kernel_w_ = weight.size(3);\n  if (kernel_h_ != kernel_h || kernel_w_ != kernel_w)\n    AT_ERROR(\n        \"Input shape and kernel shape wont match: (%d x %d vs %d x %d).\",\n        kernel_h_,\n        kernel_w,\n        kernel_h_,\n        kernel_w_);\n  if (channels != channels_kernel * group)\n    AT_ERROR(\n        \"Input shape and kernel channels wont match: (%d vs %d).\",\n        channels,\n        channels_kernel * group);\n\n  const int height_out =\n      (height + 2 * pad_h - (dilation_h * (kernel_h - 1) + 1)) / stride_h + 1;\n  const int width_out =\n      (width + 2 * pad_w - (dilation_w * (kernel_w - 1) + 1)) / stride_w + 1;\n\n  // mask shape check\n  TORCH_CHECK(\n      (mask.size(2) == height_out && mask.size(3) == width_out),\n      \"invalid spatial size of mask, expected height: %d width: %d, but \"\n      \"got height: %d width: %d\",\n      height_out,\n      width_out,\n      mask.size(2),\n      mask.size(3));\n\n  TORCH_CHECK(\n      (mask.size(1) == deformable_group * kernel_h * kernel_w),\n      \"invalid number of channels of mask\");\n\n  if (ones.ndimension() != 2 ||\n      ones.size(0) * ones.size(1) < height_out * width_out) {\n    // Resize plane and fill with ones...\n    ones = at::ones({height_out, width_out}, input.options());\n  }\n\n  grad_input = grad_input.view({batch, channels, height, width});\n  columns = at::zeros(\n      {channels * kernel_h * kernel_w, height_out * width_out},\n      input.options());\n\n  grad_output = grad_output.view(\n      {grad_output.size(0),\n       group,\n       grad_output.size(1) / group,\n       grad_output.size(2),\n       grad_output.size(3)});\n\n  for (int b = 0; b < batch; b++) {\n    // divide int group\n    columns = columns.view({group, columns.size(0) / group, columns.size(1)});\n    weight = weight.view(\n        {group,\n         weight.size(0) / group,\n         weight.size(1),\n         weight.size(2),\n         weight.size(3)});\n\n    for (int g = 0; g < group; g++) {\n      columns[g].addmm_(\n          weight[g].flatten(1).transpose(0, 1),\n          grad_output[b][g].flatten(1),\n          0.0f,\n          1.0f);\n    }\n\n    columns =\n        columns.view({columns.size(0) * columns.size(1), columns.size(2)});\n    weight = weight.view(\n        {weight.size(0) * weight.size(1),\n         weight.size(2),\n         weight.size(3),\n         weight.size(4)});\n\n    // gradient w.r.t. input coordinate data\n    modulated_deformable_col2im_coord_cuda(\n        columns,\n        input[b],\n        offset[b],\n        mask[b],\n        1,\n        channels,\n        height,\n        width,\n        height_out,\n        width_out,\n        kernel_h,\n        kernel_w,\n        pad_h,\n        pad_w,\n        stride_h,\n        stride_w,\n        dilation_h,\n        dilation_w,\n        deformable_group,\n        grad_offset[b],\n        grad_mask[b]);\n    // gradient w.r.t. input data\n    modulated_deformable_col2im_cuda(\n        columns,\n        offset[b],\n        mask[b],\n        1,\n        channels,\n        height,\n        width,\n        height_out,\n        width_out,\n        kernel_h,\n        kernel_w,\n        pad_h,\n        pad_w,\n        stride_h,\n        stride_w,\n        dilation_h,\n        dilation_w,\n        deformable_group,\n        grad_input[b]);\n\n    // gradient w.r.t. weight, dWeight should accumulate across the batch and\n    // group\n    modulated_deformable_im2col_cuda(\n        input[b],\n        offset[b],\n        mask[b],\n        1,\n        channels,\n        height,\n        width,\n        height_out,\n        width_out,\n        kernel_h,\n        kernel_w,\n        pad_h,\n        pad_w,\n        stride_h,\n        stride_w,\n        dilation_h,\n        dilation_w,\n        deformable_group,\n        columns);\n\n    columns = columns.view({group, columns.size(0) / group, columns.size(1)});\n    grad_weight = grad_weight.view(\n        {group,\n         grad_weight.size(0) / group,\n         grad_weight.size(1),\n         grad_weight.size(2),\n         grad_weight.size(3)});\n    if (with_bias)\n      grad_bias = grad_bias.view({group, grad_bias.size(0) / group});\n\n    for (int g = 0; g < group; g++) {\n      grad_weight[g] =\n          grad_weight[g]\n              .flatten(1)\n              .addmm_(grad_output[b][g].flatten(1), columns[g].transpose(0, 1))\n              .view_as(grad_weight[g]);\n      if (with_bias) {\n        grad_bias[g] =\n            grad_bias[g]\n                .view({-1, 1})\n                .addmm_(grad_output[b][g].flatten(1), ones.view({-1, 1}))\n                .view(-1);\n      }\n    }\n\n    columns =\n        columns.view({columns.size(0) * columns.size(1), columns.size(2)});\n    grad_weight = grad_weight.view(\n        {grad_weight.size(0) * grad_weight.size(1),\n         grad_weight.size(2),\n         grad_weight.size(3),\n         grad_weight.size(4)});\n    if (with_bias)\n      grad_bias = grad_bias.view({grad_bias.size(0) * grad_bias.size(1)});\n  }\n  grad_output = grad_output.view(\n      {grad_output.size(0) * grad_output.size(1),\n       grad_output.size(2),\n       grad_output.size(3),\n       grad_output.size(4)});\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/csrc/deformable/deform_conv_cuda_kernel.cu",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n\n// modified from\n// https://github.com/open-mmlab/mmdetection/blob/master/mmdet/ops/dcn/src/deform_conv_cuda_kernel.cu\n// Original license: Apache 2.0\n// clang-format off\n\n// modify from\n// https://github.com/chengdazhi/Deformable-Convolution-V2-PyTorch/blob/mmdetection/mmdet/ops/dcn/src/deform_conv_cuda_kernel.cu\n\n/*!\n ******************* BEGIN Caffe Copyright Notice and Disclaimer *****************\n *\n * COPYRIGHT\n *\n * All contributions by the University of California:\n * Copyright (c) 2014-2017 The Regents of the University of California (Regents)\n * All rights reserved.\n *\n * All other contributions:\n * Copyright (c) 2014-2017, the respective contributors\n * All rights reserved.\n *\n * Caffe uses a shared copyright model: each contributor holds copyright over\n * their contributions to Caffe. The project versioning records all such\n * contribution and copyright details. If a contributor wants to further mark\n * their specific copyright on a particular contribution, they should indicate\n * their copyright solely in the commit message of the change when it is\n * committed.\n *\n * LICENSE\n *\n * Redistribution and use in source and binary forms, with or without\n * modification, are permitted provided that the following conditions are met:\n *\n * 1. Redistributions of source code must retain the above copyright notice, this\n * list of conditions and the following disclaimer.\n * 2. Redistributions in binary form must reproduce the above copyright notice,\n * this list of conditions and the following disclaimer in the documentation\n * and/or other materials provided with the distribution.\n *\n * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS \"AS IS\"\n *AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE\n *IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE\n * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE\n *FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL\n *DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR\n *SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER\n *CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,\n *OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE\n *OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.\n *\n * CONTRIBUTION AGREEMENT\n *\n * By contributing to the BVLC/caffe repository through pull-request, comment,\n * or otherwise, the contributor releases their content to the\n * license and copyright terms herein.\n *\n ***************** END Caffe Copyright Notice and Disclaimer *********************\n *\n * Copyright (c) 2018 Microsoft\n * Licensed under The MIT License [see LICENSE for details]\n * \\file modulated_deformable_im2col.cuh\n * \\brief Function definitions of converting an image to\n * column matrix based on kernel, padding, dilation, and offset.\n * These functions are mainly used in deformable convolution operators.\n * \\ref: https://arxiv.org/abs/1703.06211\n * \\author Yuwen Xiong, Haozhi Qi, Jifeng Dai, Xizhou Zhu, Han Hu, Dazhi Cheng\n */\n\n#include <ATen/ATen.h>\n#include <c10/cuda/CUDAGuard.h>\n#include <float.h>\n#include <math.h>\n#include <stdio.h>\n#include <THC/THCAtomics.cuh>\n\nusing namespace at;\n\n#define CUDA_KERNEL_LOOP(i, n)                                 \\\n  for (int i = blockIdx.x * blockDim.x + threadIdx.x; i < (n); \\\n       i += blockDim.x * gridDim.x)\n\n\nnamespace {\n\nconst int CUDA_NUM_THREADS = 1024;\nconst int kMaxGridNum = 65535;\n\ninline int GET_BLOCKS(const int N) {\n  return std::min(kMaxGridNum, (N + CUDA_NUM_THREADS - 1) / CUDA_NUM_THREADS);\n}\n\n}\n\ntemplate <typename scalar_t>\n__device__ scalar_t deformable_im2col_bilinear(\n    const scalar_t* bottom_data,\n    const int data_width,\n    const int height,\n    const int width,\n    scalar_t h,\n    scalar_t w) {\n  int h_low = floor(h);\n  int w_low = floor(w);\n  int h_high = h_low + 1;\n  int w_high = w_low + 1;\n\n  scalar_t lh = h - h_low;\n  scalar_t lw = w - w_low;\n  scalar_t hh = 1 - lh, hw = 1 - lw;\n\n  scalar_t v1 = 0;\n  if (h_low >= 0 && w_low >= 0)\n    v1 = bottom_data[h_low * data_width + w_low];\n  scalar_t v2 = 0;\n  if (h_low >= 0 && w_high <= width - 1)\n    v2 = bottom_data[h_low * data_width + w_high];\n  scalar_t v3 = 0;\n  if (h_high <= height - 1 && w_low >= 0)\n    v3 = bottom_data[h_high * data_width + w_low];\n  scalar_t v4 = 0;\n  if (h_high <= height - 1 && w_high <= width - 1)\n    v4 = bottom_data[h_high * data_width + w_high];\n\n  scalar_t w1 = hh * hw, w2 = hh * lw, w3 = lh * hw, w4 = lh * lw;\n\n  scalar_t val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n  return val;\n}\n\ntemplate <typename scalar_t>\n__device__ scalar_t get_gradient_weight(\n    scalar_t argmax_h,\n    scalar_t argmax_w,\n    const int h,\n    const int w,\n    const int height,\n    const int width) {\n  if (argmax_h <= -1 || argmax_h >= height || argmax_w <= -1 ||\n      argmax_w >= width) {\n    // empty\n    return 0;\n  }\n\n  int argmax_h_low = floor(argmax_h);\n  int argmax_w_low = floor(argmax_w);\n  int argmax_h_high = argmax_h_low + 1;\n  int argmax_w_high = argmax_w_low + 1;\n\n  scalar_t weight = 0;\n  if (h == argmax_h_low && w == argmax_w_low)\n    weight = (h + 1 - argmax_h) * (w + 1 - argmax_w);\n  if (h == argmax_h_low && w == argmax_w_high)\n    weight = (h + 1 - argmax_h) * (argmax_w + 1 - w);\n  if (h == argmax_h_high && w == argmax_w_low)\n    weight = (argmax_h + 1 - h) * (w + 1 - argmax_w);\n  if (h == argmax_h_high && w == argmax_w_high)\n    weight = (argmax_h + 1 - h) * (argmax_w + 1 - w);\n  return weight;\n}\n\ntemplate <typename scalar_t>\n__device__ scalar_t get_coordinate_weight(\n    scalar_t argmax_h,\n    scalar_t argmax_w,\n    const int height,\n    const int width,\n    const scalar_t* im_data,\n    const int data_width,\n    const int bp_dir) {\n  if (argmax_h <= -1 || argmax_h >= height || argmax_w <= -1 ||\n      argmax_w >= width) {\n    // empty\n    return 0;\n  }\n\n  int argmax_h_low = floor(argmax_h);\n  int argmax_w_low = floor(argmax_w);\n  int argmax_h_high = argmax_h_low + 1;\n  int argmax_w_high = argmax_w_low + 1;\n\n  scalar_t weight = 0;\n\n  if (bp_dir == 0) {\n    if (argmax_h_low >= 0 && argmax_w_low >= 0)\n      weight += -1 * (argmax_w_low + 1 - argmax_w) *\n          im_data[argmax_h_low * data_width + argmax_w_low];\n    if (argmax_h_low >= 0 && argmax_w_high <= width - 1)\n      weight += -1 * (argmax_w - argmax_w_low) *\n          im_data[argmax_h_low * data_width + argmax_w_high];\n    if (argmax_h_high <= height - 1 && argmax_w_low >= 0)\n      weight += (argmax_w_low + 1 - argmax_w) *\n          im_data[argmax_h_high * data_width + argmax_w_low];\n    if (argmax_h_high <= height - 1 && argmax_w_high <= width - 1)\n      weight += (argmax_w - argmax_w_low) *\n          im_data[argmax_h_high * data_width + argmax_w_high];\n  } else if (bp_dir == 1) {\n    if (argmax_h_low >= 0 && argmax_w_low >= 0)\n      weight += -1 * (argmax_h_low + 1 - argmax_h) *\n          im_data[argmax_h_low * data_width + argmax_w_low];\n    if (argmax_h_low >= 0 && argmax_w_high <= width - 1)\n      weight += (argmax_h_low + 1 - argmax_h) *\n          im_data[argmax_h_low * data_width + argmax_w_high];\n    if (argmax_h_high <= height - 1 && argmax_w_low >= 0)\n      weight += -1 * (argmax_h - argmax_h_low) *\n          im_data[argmax_h_high * data_width + argmax_w_low];\n    if (argmax_h_high <= height - 1 && argmax_w_high <= width - 1)\n      weight += (argmax_h - argmax_h_low) *\n          im_data[argmax_h_high * data_width + argmax_w_high];\n  }\n\n  return weight;\n}\n\ntemplate <typename scalar_t>\n__global__ void deformable_im2col_gpu_kernel(\n    const int n,\n    const scalar_t* data_im,\n    const scalar_t* data_offset,\n    const int height,\n    const int width,\n    const int kernel_h,\n    const int kernel_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int channel_per_deformable_group,\n    const int batch_size,\n    const int num_channels,\n    const int deformable_group,\n    const int height_col,\n    const int width_col,\n    scalar_t* data_col) {\n  CUDA_KERNEL_LOOP(index, n) {\n    // index index of output matrix\n    const int w_col = index % width_col;\n    const int h_col = (index / width_col) % height_col;\n    const int b_col = (index / width_col / height_col) % batch_size;\n    const int c_im = (index / width_col / height_col) / batch_size;\n    const int c_col = c_im * kernel_h * kernel_w;\n\n    // compute deformable group index\n    const int deformable_group_index = c_im / channel_per_deformable_group;\n\n    const int h_in = h_col * stride_h - pad_h;\n    const int w_in = w_col * stride_w - pad_w;\n    scalar_t* data_col_ptr = data_col +\n        ((c_col * batch_size + b_col) * height_col + h_col) * width_col + w_col;\n    // const scalar_t* data_im_ptr = data_im + ((b_col * num_channels + c_im) *\n    // height + h_in) * width + w_in;\n    const scalar_t* data_im_ptr =\n        data_im + (b_col * num_channels + c_im) * height * width;\n    const scalar_t* data_offset_ptr = data_offset +\n        (b_col * deformable_group + deformable_group_index) * 2 * kernel_h *\n            kernel_w * height_col * width_col;\n\n    for (int i = 0; i < kernel_h; ++i) {\n      for (int j = 0; j < kernel_w; ++j) {\n        const int data_offset_h_ptr =\n            ((2 * (i * kernel_w + j)) * height_col + h_col) * width_col + w_col;\n        const int data_offset_w_ptr =\n            ((2 * (i * kernel_w + j) + 1) * height_col + h_col) * width_col +\n            w_col;\n        const scalar_t offset_h = data_offset_ptr[data_offset_h_ptr];\n        const scalar_t offset_w = data_offset_ptr[data_offset_w_ptr];\n        scalar_t val = static_cast<scalar_t>(0);\n        const scalar_t h_im = h_in + i * dilation_h + offset_h;\n        const scalar_t w_im = w_in + j * dilation_w + offset_w;\n        if (h_im > -1 && w_im > -1 && h_im < height && w_im < width) {\n          // const scalar_t map_h = i * dilation_h + offset_h;\n          // const scalar_t map_w = j * dilation_w + offset_w;\n          // const int cur_height = height - h_in;\n          // const int cur_width = width - w_in;\n          // val = deformable_im2col_bilinear(data_im_ptr, width, cur_height,\n          // cur_width, map_h, map_w);\n          val = deformable_im2col_bilinear(\n              data_im_ptr, width, height, width, h_im, w_im);\n        }\n        *data_col_ptr = val;\n        data_col_ptr += batch_size * height_col * width_col;\n      }\n    }\n  }\n}\n\n\ntemplate <typename scalar_t>\n__global__ void deformable_col2im_gpu_kernel(\n    const int n,\n    const scalar_t* data_col,\n    const scalar_t* data_offset,\n    const int channels,\n    const int height,\n    const int width,\n    const int kernel_h,\n    const int kernel_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int channel_per_deformable_group,\n    const int batch_size,\n    const int deformable_group,\n    const int height_col,\n    const int width_col,\n    scalar_t* grad_im) {\n  CUDA_KERNEL_LOOP(index, n) {\n    const int j = (index / width_col / height_col / batch_size) % kernel_w;\n    const int i =\n        (index / width_col / height_col / batch_size / kernel_w) % kernel_h;\n    const int c =\n        index / width_col / height_col / batch_size / kernel_w / kernel_h;\n    // compute the start and end of the output\n\n    const int deformable_group_index = c / channel_per_deformable_group;\n\n    int w_out = index % width_col;\n    int h_out = (index / width_col) % height_col;\n    int b = (index / width_col / height_col) % batch_size;\n    int w_in = w_out * stride_w - pad_w;\n    int h_in = h_out * stride_h - pad_h;\n\n    const scalar_t* data_offset_ptr = data_offset +\n        (b * deformable_group + deformable_group_index) * 2 * kernel_h *\n            kernel_w * height_col * width_col;\n    const int data_offset_h_ptr =\n        ((2 * (i * kernel_w + j)) * height_col + h_out) * width_col + w_out;\n    const int data_offset_w_ptr =\n        ((2 * (i * kernel_w + j) + 1) * height_col + h_out) * width_col + w_out;\n    const scalar_t offset_h = data_offset_ptr[data_offset_h_ptr];\n    const scalar_t offset_w = data_offset_ptr[data_offset_w_ptr];\n    const scalar_t cur_inv_h_data = h_in + i * dilation_h + offset_h;\n    const scalar_t cur_inv_w_data = w_in + j * dilation_w + offset_w;\n\n    const scalar_t cur_top_grad = data_col[index];\n    const int cur_h = (int)cur_inv_h_data;\n    const int cur_w = (int)cur_inv_w_data;\n    for (int dy = -2; dy <= 2; dy++) {\n      for (int dx = -2; dx <= 2; dx++) {\n        if (cur_h + dy >= 0 && cur_h + dy < height && cur_w + dx >= 0 &&\n            cur_w + dx < width && abs(cur_inv_h_data - (cur_h + dy)) < 1 &&\n            abs(cur_inv_w_data - (cur_w + dx)) < 1) {\n          int cur_bottom_grad_pos =\n              ((b * channels + c) * height + cur_h + dy) * width + cur_w + dx;\n          scalar_t weight = get_gradient_weight(\n              cur_inv_h_data,\n              cur_inv_w_data,\n              cur_h + dy,\n              cur_w + dx,\n              height,\n              width);\n          atomicAdd(grad_im + cur_bottom_grad_pos, weight * cur_top_grad);\n        }\n      }\n    }\n  }\n}\n\n\ntemplate <typename scalar_t>\n__global__ void deformable_col2im_coord_gpu_kernel(\n    const int n,\n    const scalar_t* data_col,\n    const scalar_t* data_im,\n    const scalar_t* data_offset,\n    const int channels,\n    const int height,\n    const int width,\n    const int kernel_h,\n    const int kernel_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int channel_per_deformable_group,\n    const int batch_size,\n    const int offset_channels,\n    const int deformable_group,\n    const int height_col,\n    const int width_col,\n    scalar_t* grad_offset) {\n  CUDA_KERNEL_LOOP(index, n) {\n    scalar_t val = 0;\n    int w = index % width_col;\n    int h = (index / width_col) % height_col;\n    int c = (index / width_col / height_col) % offset_channels;\n    int b = (index / width_col / height_col) / offset_channels;\n    // compute the start and end of the output\n\n    const int deformable_group_index = c / (2 * kernel_h * kernel_w);\n    const int col_step = kernel_h * kernel_w;\n    int cnt = 0;\n    const scalar_t* data_col_ptr = data_col +\n        deformable_group_index * channel_per_deformable_group * batch_size *\n            width_col * height_col;\n    const scalar_t* data_im_ptr = data_im +\n        (b * deformable_group + deformable_group_index) *\n            channel_per_deformable_group / kernel_h / kernel_w * height * width;\n    const scalar_t* data_offset_ptr = data_offset +\n        (b * deformable_group + deformable_group_index) * 2 * kernel_h *\n            kernel_w * height_col * width_col;\n\n    const int offset_c = c - deformable_group_index * 2 * kernel_h * kernel_w;\n\n    for (int col_c = (offset_c / 2); col_c < channel_per_deformable_group;\n         col_c += col_step) {\n      const int col_pos =\n          (((col_c * batch_size + b) * height_col) + h) * width_col + w;\n      const int bp_dir = offset_c % 2;\n\n      int j = (col_pos / width_col / height_col / batch_size) % kernel_w;\n      int i =\n          (col_pos / width_col / height_col / batch_size / kernel_w) % kernel_h;\n      int w_out = col_pos % width_col;\n      int h_out = (col_pos / width_col) % height_col;\n      int w_in = w_out * stride_w - pad_w;\n      int h_in = h_out * stride_h - pad_h;\n      const int data_offset_h_ptr =\n          (((2 * (i * kernel_w + j)) * height_col + h_out) * width_col + w_out);\n      const int data_offset_w_ptr =\n          (((2 * (i * kernel_w + j) + 1) * height_col + h_out) * width_col +\n           w_out);\n      const scalar_t offset_h = data_offset_ptr[data_offset_h_ptr];\n      const scalar_t offset_w = data_offset_ptr[data_offset_w_ptr];\n      scalar_t inv_h = h_in + i * dilation_h + offset_h;\n      scalar_t inv_w = w_in + j * dilation_w + offset_w;\n      if (inv_h <= -1 || inv_w <= -1 || inv_h >= height || inv_w >= width) {\n        inv_h = inv_w = -2;\n      }\n      const scalar_t weight = get_coordinate_weight(\n          inv_h,\n          inv_w,\n          height,\n          width,\n          data_im_ptr + cnt * height * width,\n          width,\n          bp_dir);\n      val += weight * data_col_ptr[col_pos];\n      cnt += 1;\n    }\n\n    grad_offset[index] = val;\n  }\n}\n\n\nnamespace detectron2 {\n\nvoid deformable_im2col(\n    const at::Tensor data_im,\n    const at::Tensor data_offset,\n    const int channels,\n    const int height,\n    const int width,\n    const int ksize_h,\n    const int ksize_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int parallel_imgs,\n    const int deformable_group,\n    at::Tensor data_col) {\n  // num_axes should be smaller than block size\n  // todo: check parallel_imgs is correctly passed in\n  int height_col =\n      (height + 2 * pad_h - (dilation_h * (ksize_h - 1) + 1)) / stride_h + 1;\n  int width_col =\n      (width + 2 * pad_w - (dilation_w * (ksize_w - 1) + 1)) / stride_w + 1;\n  int num_kernels = channels * height_col * width_col * parallel_imgs;\n  int channel_per_deformable_group = channels / deformable_group;\n\n  at::cuda::CUDAGuard device_guard(data_im.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_im.scalar_type(), \"deformable_im2col_gpu\", ([&] {\n        const scalar_t* data_im_ = data_im.data_ptr<scalar_t>();\n        const scalar_t* data_offset_ = data_offset.data_ptr<scalar_t>();\n        scalar_t* data_col_ = data_col.data_ptr<scalar_t>();\n\n        deformable_im2col_gpu_kernel<<<\n            GET_BLOCKS(num_kernels),\n            CUDA_NUM_THREADS,\n            0,\n            stream>>>(\n            num_kernels,\n            data_im_,\n            data_offset_,\n            height,\n            width,\n            ksize_h,\n            ksize_w,\n            pad_h,\n            pad_w,\n            stride_h,\n            stride_w,\n            dilation_h,\n            dilation_w,\n            channel_per_deformable_group,\n            parallel_imgs,\n            channels,\n            deformable_group,\n            height_col,\n            width_col,\n            data_col_);\n      }));\n\n  cudaError_t err = cudaGetLastError();\n  if (err != cudaSuccess) {\n    printf(\"error in deformable_im2col: %s\\n\", cudaGetErrorString(err));\n  }\n}\n\n\nvoid deformable_col2im(\n    const at::Tensor data_col,\n    const at::Tensor data_offset,\n    const int channels,\n    const int height,\n    const int width,\n    const int ksize_h,\n    const int ksize_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int parallel_imgs,\n    const int deformable_group,\n    at::Tensor grad_im) {\n  // todo: make sure parallel_imgs is passed in correctly\n  int height_col =\n      (height + 2 * pad_h - (dilation_h * (ksize_h - 1) + 1)) / stride_h + 1;\n  int width_col =\n      (width + 2 * pad_w - (dilation_w * (ksize_w - 1) + 1)) / stride_w + 1;\n  int num_kernels =\n      channels * ksize_h * ksize_w * height_col * width_col * parallel_imgs;\n  int channel_per_deformable_group = channels / deformable_group;\n\n  at::cuda::CUDAGuard device_guard(data_col.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_col.scalar_type(), \"deformable_col2im_gpu\", ([&] {\n        const scalar_t* data_col_ = data_col.data_ptr<scalar_t>();\n        const scalar_t* data_offset_ = data_offset.data_ptr<scalar_t>();\n        scalar_t* grad_im_ = grad_im.data_ptr<scalar_t>();\n\n        deformable_col2im_gpu_kernel<<<\n            GET_BLOCKS(num_kernels),\n            CUDA_NUM_THREADS,\n            0,\n            stream>>>(\n            num_kernels,\n            data_col_,\n            data_offset_,\n            channels,\n            height,\n            width,\n            ksize_h,\n            ksize_w,\n            pad_h,\n            pad_w,\n            stride_h,\n            stride_w,\n            dilation_h,\n            dilation_w,\n            channel_per_deformable_group,\n            parallel_imgs,\n            deformable_group,\n            height_col,\n            width_col,\n            grad_im_);\n      }));\n\n  cudaError_t err = cudaGetLastError();\n  if (err != cudaSuccess) {\n    printf(\"error in deformable_col2im: %s\\n\", cudaGetErrorString(err));\n  }\n}\n\n\nvoid deformable_col2im_coord(\n    const at::Tensor data_col,\n    const at::Tensor data_im,\n    const at::Tensor data_offset,\n    const int channels,\n    const int height,\n    const int width,\n    const int ksize_h,\n    const int ksize_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int parallel_imgs,\n    const int deformable_group,\n    at::Tensor grad_offset) {\n  int height_col =\n      (height + 2 * pad_h - (dilation_h * (ksize_h - 1) + 1)) / stride_h + 1;\n  int width_col =\n      (width + 2 * pad_w - (dilation_w * (ksize_w - 1) + 1)) / stride_w + 1;\n  int num_kernels = height_col * width_col * 2 * ksize_h * ksize_w *\n      deformable_group * parallel_imgs;\n  int channel_per_deformable_group =\n      channels * ksize_h * ksize_w / deformable_group;\n\n  at::cuda::CUDAGuard device_guard(data_col.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_col.scalar_type(), \"deformable_col2im_coord_gpu\", ([&] {\n        const scalar_t* data_col_ = data_col.data_ptr<scalar_t>();\n        const scalar_t* data_im_ = data_im.data_ptr<scalar_t>();\n        const scalar_t* data_offset_ = data_offset.data_ptr<scalar_t>();\n        scalar_t* grad_offset_ = grad_offset.data_ptr<scalar_t>();\n\n        deformable_col2im_coord_gpu_kernel<<<\n            GET_BLOCKS(num_kernels),\n            CUDA_NUM_THREADS,\n            0,\n            stream>>>(\n            num_kernels,\n            data_col_,\n            data_im_,\n            data_offset_,\n            channels,\n            height,\n            width,\n            ksize_h,\n            ksize_w,\n            pad_h,\n            pad_w,\n            stride_h,\n            stride_w,\n            dilation_h,\n            dilation_w,\n            channel_per_deformable_group,\n            parallel_imgs,\n            2 * ksize_h * ksize_w * deformable_group,\n            deformable_group,\n            height_col,\n            width_col,\n            grad_offset_);\n      }));\n}\n\n} // namespace detectron2\n\n\ntemplate <typename scalar_t>\n__device__ scalar_t dmcn_im2col_bilinear(\n    const scalar_t* bottom_data,\n    const int data_width,\n    const int height,\n    const int width,\n    scalar_t h,\n    scalar_t w) {\n  int h_low = floor(h);\n  int w_low = floor(w);\n  int h_high = h_low + 1;\n  int w_high = w_low + 1;\n\n  scalar_t lh = h - h_low;\n  scalar_t lw = w - w_low;\n  scalar_t hh = 1 - lh, hw = 1 - lw;\n\n  scalar_t v1 = 0;\n  if (h_low >= 0 && w_low >= 0)\n    v1 = bottom_data[h_low * data_width + w_low];\n  scalar_t v2 = 0;\n  if (h_low >= 0 && w_high <= width - 1)\n    v2 = bottom_data[h_low * data_width + w_high];\n  scalar_t v3 = 0;\n  if (h_high <= height - 1 && w_low >= 0)\n    v3 = bottom_data[h_high * data_width + w_low];\n  scalar_t v4 = 0;\n  if (h_high <= height - 1 && w_high <= width - 1)\n    v4 = bottom_data[h_high * data_width + w_high];\n\n  scalar_t w1 = hh * hw, w2 = hh * lw, w3 = lh * hw, w4 = lh * lw;\n\n  scalar_t val = (w1 * v1 + w2 * v2 + w3 * v3 + w4 * v4);\n  return val;\n}\n\ntemplate <typename scalar_t>\n__device__ scalar_t dmcn_get_gradient_weight(\n    scalar_t argmax_h,\n    scalar_t argmax_w,\n    const int h,\n    const int w,\n    const int height,\n    const int width) {\n  if (argmax_h <= -1 || argmax_h >= height || argmax_w <= -1 ||\n      argmax_w >= width) {\n    // empty\n    return 0;\n  }\n\n  int argmax_h_low = floor(argmax_h);\n  int argmax_w_low = floor(argmax_w);\n  int argmax_h_high = argmax_h_low + 1;\n  int argmax_w_high = argmax_w_low + 1;\n\n  scalar_t weight = 0;\n  if (h == argmax_h_low && w == argmax_w_low)\n    weight = (h + 1 - argmax_h) * (w + 1 - argmax_w);\n  if (h == argmax_h_low && w == argmax_w_high)\n    weight = (h + 1 - argmax_h) * (argmax_w + 1 - w);\n  if (h == argmax_h_high && w == argmax_w_low)\n    weight = (argmax_h + 1 - h) * (w + 1 - argmax_w);\n  if (h == argmax_h_high && w == argmax_w_high)\n    weight = (argmax_h + 1 - h) * (argmax_w + 1 - w);\n  return weight;\n}\n\ntemplate <typename scalar_t>\n__device__ scalar_t dmcn_get_coordinate_weight(\n    scalar_t argmax_h,\n    scalar_t argmax_w,\n    const int height,\n    const int width,\n    const scalar_t* im_data,\n    const int data_width,\n    const int bp_dir) {\n  if (argmax_h <= -1 || argmax_h >= height || argmax_w <= -1 ||\n      argmax_w >= width) {\n    // empty\n    return 0;\n  }\n\n  int argmax_h_low = floor(argmax_h);\n  int argmax_w_low = floor(argmax_w);\n  int argmax_h_high = argmax_h_low + 1;\n  int argmax_w_high = argmax_w_low + 1;\n\n  scalar_t weight = 0;\n\n  if (bp_dir == 0) {\n    if (argmax_h_low >= 0 && argmax_w_low >= 0)\n      weight += -1 * (argmax_w_low + 1 - argmax_w) *\n          im_data[argmax_h_low * data_width + argmax_w_low];\n    if (argmax_h_low >= 0 && argmax_w_high <= width - 1)\n      weight += -1 * (argmax_w - argmax_w_low) *\n          im_data[argmax_h_low * data_width + argmax_w_high];\n    if (argmax_h_high <= height - 1 && argmax_w_low >= 0)\n      weight += (argmax_w_low + 1 - argmax_w) *\n          im_data[argmax_h_high * data_width + argmax_w_low];\n    if (argmax_h_high <= height - 1 && argmax_w_high <= width - 1)\n      weight += (argmax_w - argmax_w_low) *\n          im_data[argmax_h_high * data_width + argmax_w_high];\n  } else if (bp_dir == 1) {\n    if (argmax_h_low >= 0 && argmax_w_low >= 0)\n      weight += -1 * (argmax_h_low + 1 - argmax_h) *\n          im_data[argmax_h_low * data_width + argmax_w_low];\n    if (argmax_h_low >= 0 && argmax_w_high <= width - 1)\n      weight += (argmax_h_low + 1 - argmax_h) *\n          im_data[argmax_h_low * data_width + argmax_w_high];\n    if (argmax_h_high <= height - 1 && argmax_w_low >= 0)\n      weight += -1 * (argmax_h - argmax_h_low) *\n          im_data[argmax_h_high * data_width + argmax_w_low];\n    if (argmax_h_high <= height - 1 && argmax_w_high <= width - 1)\n      weight += (argmax_h - argmax_h_low) *\n          im_data[argmax_h_high * data_width + argmax_w_high];\n  }\n\n  return weight;\n}\n\ntemplate <typename scalar_t>\n__global__ void modulated_deformable_im2col_gpu_kernel(\n    const int n,\n    const scalar_t* data_im,\n    const scalar_t* data_offset,\n    const scalar_t* data_mask,\n    const int height,\n    const int width,\n    const int kernel_h,\n    const int kernel_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int channel_per_deformable_group,\n    const int batch_size,\n    const int num_channels,\n    const int deformable_group,\n    const int height_col,\n    const int width_col,\n    scalar_t* data_col) {\n  CUDA_KERNEL_LOOP(index, n) {\n    // index index of output matrix\n    const int w_col = index % width_col;\n    const int h_col = (index / width_col) % height_col;\n    const int b_col = (index / width_col / height_col) % batch_size;\n    const int c_im = (index / width_col / height_col) / batch_size;\n    const int c_col = c_im * kernel_h * kernel_w;\n\n    // compute deformable group index\n    const int deformable_group_index = c_im / channel_per_deformable_group;\n\n    const int h_in = h_col * stride_h - pad_h;\n    const int w_in = w_col * stride_w - pad_w;\n\n    scalar_t* data_col_ptr = data_col +\n        ((c_col * batch_size + b_col) * height_col + h_col) * width_col + w_col;\n    // const float* data_im_ptr = data_im + ((b_col * num_channels + c_im) *\n    // height + h_in) * width + w_in;\n    const scalar_t* data_im_ptr =\n        data_im + (b_col * num_channels + c_im) * height * width;\n    const scalar_t* data_offset_ptr = data_offset +\n        (b_col * deformable_group + deformable_group_index) * 2 * kernel_h *\n            kernel_w * height_col * width_col;\n\n    const scalar_t* data_mask_ptr = data_mask +\n        (b_col * deformable_group + deformable_group_index) * kernel_h *\n            kernel_w * height_col * width_col;\n\n    for (int i = 0; i < kernel_h; ++i) {\n      for (int j = 0; j < kernel_w; ++j) {\n        const int data_offset_h_ptr =\n            ((2 * (i * kernel_w + j)) * height_col + h_col) * width_col + w_col;\n        const int data_offset_w_ptr =\n            ((2 * (i * kernel_w + j) + 1) * height_col + h_col) * width_col +\n            w_col;\n        const int data_mask_hw_ptr =\n            ((i * kernel_w + j) * height_col + h_col) * width_col + w_col;\n        const scalar_t offset_h = data_offset_ptr[data_offset_h_ptr];\n        const scalar_t offset_w = data_offset_ptr[data_offset_w_ptr];\n        const scalar_t mask = data_mask_ptr[data_mask_hw_ptr];\n        scalar_t val = static_cast<scalar_t>(0);\n        const scalar_t h_im = h_in + i * dilation_h + offset_h;\n        const scalar_t w_im = w_in + j * dilation_w + offset_w;\n        // if (h_im >= 0 && w_im >= 0 && h_im < height && w_im < width) {\n        if (h_im > -1 && w_im > -1 && h_im < height && w_im < width) {\n          // const float map_h = i * dilation_h + offset_h;\n          // const float map_w = j * dilation_w + offset_w;\n          // const int cur_height = height - h_in;\n          // const int cur_width = width - w_in;\n          // val = dmcn_im2col_bilinear(data_im_ptr, width, cur_height,\n          // cur_width, map_h, map_w);\n          val = dmcn_im2col_bilinear(\n              data_im_ptr, width, height, width, h_im, w_im);\n        }\n        *data_col_ptr = val * mask;\n        data_col_ptr += batch_size * height_col * width_col;\n        // data_col_ptr += height_col * width_col;\n      }\n    }\n  }\n}\n\ntemplate <typename scalar_t>\n__global__ void modulated_deformable_col2im_gpu_kernel(\n    const int n,\n    const scalar_t* data_col,\n    const scalar_t* data_offset,\n    const scalar_t* data_mask,\n    const int channels,\n    const int height,\n    const int width,\n    const int kernel_h,\n    const int kernel_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int channel_per_deformable_group,\n    const int batch_size,\n    const int deformable_group,\n    const int height_col,\n    const int width_col,\n    scalar_t* grad_im) {\n  CUDA_KERNEL_LOOP(index, n) {\n    const int j = (index / width_col / height_col / batch_size) % kernel_w;\n    const int i =\n        (index / width_col / height_col / batch_size / kernel_w) % kernel_h;\n    const int c =\n        index / width_col / height_col / batch_size / kernel_w / kernel_h;\n    // compute the start and end of the output\n\n    const int deformable_group_index = c / channel_per_deformable_group;\n\n    int w_out = index % width_col;\n    int h_out = (index / width_col) % height_col;\n    int b = (index / width_col / height_col) % batch_size;\n    int w_in = w_out * stride_w - pad_w;\n    int h_in = h_out * stride_h - pad_h;\n\n    const scalar_t* data_offset_ptr = data_offset +\n        (b * deformable_group + deformable_group_index) * 2 * kernel_h *\n            kernel_w * height_col * width_col;\n    const scalar_t* data_mask_ptr = data_mask +\n        (b * deformable_group + deformable_group_index) * kernel_h * kernel_w *\n            height_col * width_col;\n    const int data_offset_h_ptr =\n        ((2 * (i * kernel_w + j)) * height_col + h_out) * width_col + w_out;\n    const int data_offset_w_ptr =\n        ((2 * (i * kernel_w + j) + 1) * height_col + h_out) * width_col + w_out;\n    const int data_mask_hw_ptr =\n        ((i * kernel_w + j) * height_col + h_out) * width_col + w_out;\n    const scalar_t offset_h = data_offset_ptr[data_offset_h_ptr];\n    const scalar_t offset_w = data_offset_ptr[data_offset_w_ptr];\n    const scalar_t mask = data_mask_ptr[data_mask_hw_ptr];\n    const scalar_t cur_inv_h_data = h_in + i * dilation_h + offset_h;\n    const scalar_t cur_inv_w_data = w_in + j * dilation_w + offset_w;\n\n    const scalar_t cur_top_grad = data_col[index] * mask;\n    const int cur_h = (int)cur_inv_h_data;\n    const int cur_w = (int)cur_inv_w_data;\n    for (int dy = -2; dy <= 2; dy++) {\n      for (int dx = -2; dx <= 2; dx++) {\n        if (cur_h + dy >= 0 && cur_h + dy < height && cur_w + dx >= 0 &&\n            cur_w + dx < width && abs(cur_inv_h_data - (cur_h + dy)) < 1 &&\n            abs(cur_inv_w_data - (cur_w + dx)) < 1) {\n          int cur_bottom_grad_pos =\n              ((b * channels + c) * height + cur_h + dy) * width + cur_w + dx;\n          scalar_t weight = dmcn_get_gradient_weight(\n              cur_inv_h_data,\n              cur_inv_w_data,\n              cur_h + dy,\n              cur_w + dx,\n              height,\n              width);\n          atomicAdd(grad_im + cur_bottom_grad_pos, weight * cur_top_grad);\n        }\n      }\n    }\n  }\n}\n\ntemplate <typename scalar_t>\n__global__ void modulated_deformable_col2im_coord_gpu_kernel(\n    const int n,\n    const scalar_t* data_col,\n    const scalar_t* data_im,\n    const scalar_t* data_offset,\n    const scalar_t* data_mask,\n    const int channels,\n    const int height,\n    const int width,\n    const int kernel_h,\n    const int kernel_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int channel_per_deformable_group,\n    const int batch_size,\n    const int offset_channels,\n    const int deformable_group,\n    const int height_col,\n    const int width_col,\n    scalar_t* grad_offset,\n    scalar_t* grad_mask) {\n  CUDA_KERNEL_LOOP(index, n) {\n    scalar_t val = 0, mval = 0;\n    int w = index % width_col;\n    int h = (index / width_col) % height_col;\n    int c = (index / width_col / height_col) % offset_channels;\n    int b = (index / width_col / height_col) / offset_channels;\n    // compute the start and end of the output\n\n    const int deformable_group_index = c / (2 * kernel_h * kernel_w);\n    const int col_step = kernel_h * kernel_w;\n    int cnt = 0;\n    const scalar_t* data_col_ptr = data_col +\n        deformable_group_index * channel_per_deformable_group * batch_size *\n            width_col * height_col;\n    const scalar_t* data_im_ptr = data_im +\n        (b * deformable_group + deformable_group_index) *\n            channel_per_deformable_group / kernel_h / kernel_w * height * width;\n    const scalar_t* data_offset_ptr = data_offset +\n        (b * deformable_group + deformable_group_index) * 2 * kernel_h *\n            kernel_w * height_col * width_col;\n    const scalar_t* data_mask_ptr = data_mask +\n        (b * deformable_group + deformable_group_index) * kernel_h * kernel_w *\n            height_col * width_col;\n\n    const int offset_c = c - deformable_group_index * 2 * kernel_h * kernel_w;\n\n    for (int col_c = (offset_c / 2); col_c < channel_per_deformable_group;\n         col_c += col_step) {\n      const int col_pos =\n          (((col_c * batch_size + b) * height_col) + h) * width_col + w;\n      const int bp_dir = offset_c % 2;\n\n      int j = (col_pos / width_col / height_col / batch_size) % kernel_w;\n      int i =\n          (col_pos / width_col / height_col / batch_size / kernel_w) % kernel_h;\n      int w_out = col_pos % width_col;\n      int h_out = (col_pos / width_col) % height_col;\n      int w_in = w_out * stride_w - pad_w;\n      int h_in = h_out * stride_h - pad_h;\n      const int data_offset_h_ptr =\n          (((2 * (i * kernel_w + j)) * height_col + h_out) * width_col + w_out);\n      const int data_offset_w_ptr =\n          (((2 * (i * kernel_w + j) + 1) * height_col + h_out) * width_col +\n           w_out);\n      const int data_mask_hw_ptr =\n          (((i * kernel_w + j) * height_col + h_out) * width_col + w_out);\n      const scalar_t offset_h = data_offset_ptr[data_offset_h_ptr];\n      const scalar_t offset_w = data_offset_ptr[data_offset_w_ptr];\n      const scalar_t mask = data_mask_ptr[data_mask_hw_ptr];\n      scalar_t inv_h = h_in + i * dilation_h + offset_h;\n      scalar_t inv_w = w_in + j * dilation_w + offset_w;\n      if (inv_h <= -1 || inv_w <= -1 || inv_h >= height || inv_w >= width) {\n        inv_h = inv_w = -2;\n      } else {\n        mval += data_col_ptr[col_pos] *\n            dmcn_im2col_bilinear(\n                    data_im_ptr + cnt * height * width,\n                    width,\n                    height,\n                    width,\n                    inv_h,\n                    inv_w);\n      }\n      const scalar_t weight = dmcn_get_coordinate_weight(\n          inv_h,\n          inv_w,\n          height,\n          width,\n          data_im_ptr + cnt * height * width,\n          width,\n          bp_dir);\n      val += weight * data_col_ptr[col_pos] * mask;\n      cnt += 1;\n    }\n    // KERNEL_ASSIGN(grad_offset[index], offset_req, val);\n    grad_offset[index] = val;\n    if (offset_c % 2 == 0)\n      // KERNEL_ASSIGN(grad_mask[(((b * deformable_group +\n      // deformable_group_index) * kernel_h * kernel_w + offset_c / 2) *\n      // height_col + h) * width_col + w], mask_req, mval);\n      grad_mask\n          [(((b * deformable_group + deformable_group_index) * kernel_h *\n                 kernel_w +\n             offset_c / 2) *\n                height_col +\n            h) *\n               width_col +\n           w] = mval;\n  }\n}\n\n\nnamespace detectron2 {\n\nvoid modulated_deformable_im2col_cuda(\n    const at::Tensor data_im,\n    const at::Tensor data_offset,\n    const at::Tensor data_mask,\n    const int batch_size,\n    const int channels,\n    const int height_im,\n    const int width_im,\n    const int height_col,\n    const int width_col,\n    const int kernel_h,\n    const int kenerl_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int deformable_group,\n    at::Tensor data_col) {\n  // num_axes should be smaller than block size\n  const int channel_per_deformable_group = channels / deformable_group;\n  const int num_kernels = channels * batch_size * height_col * width_col;\n\n  at::cuda::CUDAGuard device_guard(data_im.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_im.scalar_type(), \"modulated_deformable_im2col_gpu\", ([&] {\n        const scalar_t* data_im_ = data_im.data_ptr<scalar_t>();\n        const scalar_t* data_offset_ = data_offset.data_ptr<scalar_t>();\n        const scalar_t* data_mask_ = data_mask.data_ptr<scalar_t>();\n        scalar_t* data_col_ = data_col.data_ptr<scalar_t>();\n\n        modulated_deformable_im2col_gpu_kernel<<<\n            GET_BLOCKS(num_kernels),\n            CUDA_NUM_THREADS,\n            0,\n            stream>>>(\n            num_kernels,\n            data_im_,\n            data_offset_,\n            data_mask_,\n            height_im,\n            width_im,\n            kernel_h,\n            kenerl_w,\n            pad_h,\n            pad_w,\n            stride_h,\n            stride_w,\n            dilation_h,\n            dilation_w,\n            channel_per_deformable_group,\n            batch_size,\n            channels,\n            deformable_group,\n            height_col,\n            width_col,\n            data_col_);\n      }));\n\n  cudaError_t err = cudaGetLastError();\n  if (err != cudaSuccess) {\n    printf(\n        \"error in modulated_deformable_im2col_cuda: %s\\n\",\n        cudaGetErrorString(err));\n  }\n}\n\nvoid modulated_deformable_col2im_cuda(\n    const at::Tensor data_col,\n    const at::Tensor data_offset,\n    const at::Tensor data_mask,\n    const int batch_size,\n    const int channels,\n    const int height_im,\n    const int width_im,\n    const int height_col,\n    const int width_col,\n    const int kernel_h,\n    const int kernel_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int deformable_group,\n    at::Tensor grad_im) {\n  const int channel_per_deformable_group = channels / deformable_group;\n  const int num_kernels =\n      channels * kernel_h * kernel_w * batch_size * height_col * width_col;\n\n  at::cuda::CUDAGuard device_guard(data_col.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_col.scalar_type(), \"modulated_deformable_col2im_gpu\", ([&] {\n        const scalar_t* data_col_ = data_col.data_ptr<scalar_t>();\n        const scalar_t* data_offset_ = data_offset.data_ptr<scalar_t>();\n        const scalar_t* data_mask_ = data_mask.data_ptr<scalar_t>();\n        scalar_t* grad_im_ = grad_im.data_ptr<scalar_t>();\n\n        modulated_deformable_col2im_gpu_kernel<<<\n            GET_BLOCKS(num_kernels),\n            CUDA_NUM_THREADS,\n            0,\n            stream>>>(\n            num_kernels,\n            data_col_,\n            data_offset_,\n            data_mask_,\n            channels,\n            height_im,\n            width_im,\n            kernel_h,\n            kernel_w,\n            pad_h,\n            pad_w,\n            stride_h,\n            stride_w,\n            dilation_h,\n            dilation_w,\n            channel_per_deformable_group,\n            batch_size,\n            deformable_group,\n            height_col,\n            width_col,\n            grad_im_);\n      }));\n\n  cudaError_t err = cudaGetLastError();\n  if (err != cudaSuccess) {\n    printf(\n        \"error in modulated_deformable_col2im_cuda: %s\\n\",\n        cudaGetErrorString(err));\n  }\n}\n\nvoid modulated_deformable_col2im_coord_cuda(\n    const at::Tensor data_col,\n    const at::Tensor data_im,\n    const at::Tensor data_offset,\n    const at::Tensor data_mask,\n    const int batch_size,\n    const int channels,\n    const int height_im,\n    const int width_im,\n    const int height_col,\n    const int width_col,\n    const int kernel_h,\n    const int kernel_w,\n    const int pad_h,\n    const int pad_w,\n    const int stride_h,\n    const int stride_w,\n    const int dilation_h,\n    const int dilation_w,\n    const int deformable_group,\n    at::Tensor grad_offset,\n    at::Tensor grad_mask) {\n  const int num_kernels = batch_size * height_col * width_col * 2 * kernel_h *\n      kernel_w * deformable_group;\n  const int channel_per_deformable_group =\n      channels * kernel_h * kernel_w / deformable_group;\n\n  at::cuda::CUDAGuard device_guard(data_col.device());\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  AT_DISPATCH_FLOATING_TYPES_AND_HALF(\n      data_col.scalar_type(), \"modulated_deformable_col2im_coord_gpu\", ([&] {\n        const scalar_t* data_col_ = data_col.data_ptr<scalar_t>();\n        const scalar_t* data_im_ = data_im.data_ptr<scalar_t>();\n        const scalar_t* data_offset_ = data_offset.data_ptr<scalar_t>();\n        const scalar_t* data_mask_ = data_mask.data_ptr<scalar_t>();\n        scalar_t* grad_offset_ = grad_offset.data_ptr<scalar_t>();\n        scalar_t* grad_mask_ = grad_mask.data_ptr<scalar_t>();\n\n        modulated_deformable_col2im_coord_gpu_kernel<<<\n            GET_BLOCKS(num_kernels),\n            CUDA_NUM_THREADS,\n            0,\n            stream>>>(\n            num_kernels,\n            data_col_,\n            data_im_,\n            data_offset_,\n            data_mask_,\n            channels,\n            height_im,\n            width_im,\n            kernel_h,\n            kernel_w,\n            pad_h,\n            pad_w,\n            stride_h,\n            stride_w,\n            dilation_h,\n            dilation_w,\n            channel_per_deformable_group,\n            batch_size,\n            2 * kernel_h * kernel_w * deformable_group,\n            deformable_group,\n            height_col,\n            width_col,\n            grad_offset_,\n            grad_mask_);\n      }));\n  cudaError_t err = cudaGetLastError();\n  if (err != cudaSuccess) {\n    printf(\n        \"error in modulated_deformable_col2im_coord_cuda: %s\\n\",\n        cudaGetErrorString(err));\n  }\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/csrc/nms_rotated/nms_rotated.h",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#pragma once\n#include <torch/types.h>\n\nnamespace detectron2 {\n\nat::Tensor nms_rotated_cpu(\n    const at::Tensor& dets,\n    const at::Tensor& scores,\n    const double iou_threshold);\n\n#if defined(WITH_CUDA) || defined(WITH_HIP)\nat::Tensor nms_rotated_cuda(\n    const at::Tensor& dets,\n    const at::Tensor& scores,\n    const double iou_threshold);\n#endif\n\n// Interface for Python\n// inline is needed to prevent multiple function definitions when this header is\n// included by different cpps\ninline at::Tensor nms_rotated(\n    const at::Tensor& dets,\n    const at::Tensor& scores,\n    const double iou_threshold) {\n  assert(dets.device().is_cuda() == scores.device().is_cuda());\n  if (dets.device().is_cuda()) {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n    return nms_rotated_cuda(\n        dets.contiguous(), scores.contiguous(), iou_threshold);\n#else\n    AT_ERROR(\"Detectron2 is not compiled with GPU support!\");\n#endif\n  }\n\n  return nms_rotated_cpu(dets.contiguous(), scores.contiguous(), iou_threshold);\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/csrc/nms_rotated/nms_rotated_cpu.cpp",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#include \"../box_iou_rotated/box_iou_rotated_utils.h\"\n#include \"nms_rotated.h\"\n\nnamespace detectron2 {\n\ntemplate <typename scalar_t>\nat::Tensor nms_rotated_cpu_kernel(\n    const at::Tensor& dets,\n    const at::Tensor& scores,\n    const double iou_threshold) {\n  // nms_rotated_cpu_kernel is modified from torchvision's nms_cpu_kernel,\n  // however, the code in this function is much shorter because\n  // we delegate the IoU computation for rotated boxes to\n  // the single_box_iou_rotated function in box_iou_rotated_utils.h\n  AT_ASSERTM(dets.device().is_cpu(), \"dets must be a CPU tensor\");\n  AT_ASSERTM(scores.device().is_cpu(), \"scores must be a CPU tensor\");\n  AT_ASSERTM(\n      dets.scalar_type() == scores.scalar_type(),\n      \"dets should have the same type as scores\");\n\n  if (dets.numel() == 0) {\n    return at::empty({0}, dets.options().dtype(at::kLong));\n  }\n\n  auto order_t = std::get<1>(scores.sort(0, /* descending=*/true));\n\n  auto ndets = dets.size(0);\n  at::Tensor suppressed_t = at::zeros({ndets}, dets.options().dtype(at::kByte));\n  at::Tensor keep_t = at::zeros({ndets}, dets.options().dtype(at::kLong));\n\n  auto suppressed = suppressed_t.data_ptr<uint8_t>();\n  auto keep = keep_t.data_ptr<int64_t>();\n  auto order = order_t.data_ptr<int64_t>();\n\n  int64_t num_to_keep = 0;\n\n  for (int64_t _i = 0; _i < ndets; _i++) {\n    auto i = order[_i];\n    if (suppressed[i] == 1) {\n      continue;\n    }\n\n    keep[num_to_keep++] = i;\n\n    for (int64_t _j = _i + 1; _j < ndets; _j++) {\n      auto j = order[_j];\n      if (suppressed[j] == 1) {\n        continue;\n      }\n\n      auto ovr = single_box_iou_rotated<scalar_t>(\n          dets[i].data_ptr<scalar_t>(), dets[j].data_ptr<scalar_t>());\n      if (ovr >= iou_threshold) {\n        suppressed[j] = 1;\n      }\n    }\n  }\n  return keep_t.narrow(/*dim=*/0, /*start=*/0, /*length=*/num_to_keep);\n}\n\nat::Tensor nms_rotated_cpu(\n    // input must be contiguous\n    const at::Tensor& dets,\n    const at::Tensor& scores,\n    const double iou_threshold) {\n  auto result = at::empty({0}, dets.options());\n\n  AT_DISPATCH_FLOATING_TYPES(dets.scalar_type(), \"nms_rotated\", [&] {\n    result = nms_rotated_cpu_kernel<scalar_t>(dets, scores, iou_threshold);\n  });\n  return result;\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/csrc/nms_rotated/nms_rotated_cuda.cu",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#include <ATen/ATen.h>\n#include <ATen/cuda/CUDAContext.h>\n#include <c10/cuda/CUDAGuard.h>\n#include <ATen/cuda/CUDAApplyUtils.cuh>\n#ifdef WITH_CUDA\n#include \"../box_iou_rotated/box_iou_rotated_utils.h\"\n#endif\n// TODO avoid this when pytorch supports \"same directory\" hipification\n#ifdef WITH_HIP\n#include \"box_iou_rotated/box_iou_rotated_utils.h\"\n#endif\n\nusing namespace detectron2;\n\nnamespace {\nint const threadsPerBlock = sizeof(unsigned long long) * 8;\n}\n\ntemplate <typename T>\n__global__ void nms_rotated_cuda_kernel(\n    const int n_boxes,\n    const double iou_threshold,\n    const T* dev_boxes,\n    unsigned long long* dev_mask) {\n  // nms_rotated_cuda_kernel is modified from torchvision's nms_cuda_kernel\n\n  const int row_start = blockIdx.y;\n  const int col_start = blockIdx.x;\n\n  // if (row_start > col_start) return;\n\n  const int row_size =\n      min(n_boxes - row_start * threadsPerBlock, threadsPerBlock);\n  const int col_size =\n      min(n_boxes - col_start * threadsPerBlock, threadsPerBlock);\n\n  // Compared to nms_cuda_kernel, where each box is represented with 4 values\n  // (x1, y1, x2, y2), each rotated box is represented with 5 values\n  // (x_center, y_center, width, height, angle_degrees) here.\n  __shared__ T block_boxes[threadsPerBlock * 5];\n  if (threadIdx.x < col_size) {\n    block_boxes[threadIdx.x * 5 + 0] =\n        dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 5 + 0];\n    block_boxes[threadIdx.x * 5 + 1] =\n        dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 5 + 1];\n    block_boxes[threadIdx.x * 5 + 2] =\n        dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 5 + 2];\n    block_boxes[threadIdx.x * 5 + 3] =\n        dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 5 + 3];\n    block_boxes[threadIdx.x * 5 + 4] =\n        dev_boxes[(threadsPerBlock * col_start + threadIdx.x) * 5 + 4];\n  }\n  __syncthreads();\n\n  if (threadIdx.x < row_size) {\n    const int cur_box_idx = threadsPerBlock * row_start + threadIdx.x;\n    const T* cur_box = dev_boxes + cur_box_idx * 5;\n    int i = 0;\n    unsigned long long t = 0;\n    int start = 0;\n    if (row_start == col_start) {\n      start = threadIdx.x + 1;\n    }\n    for (i = start; i < col_size; i++) {\n      // Instead of devIoU used by original horizontal nms, here\n      // we use the single_box_iou_rotated function from box_iou_rotated_utils.h\n      if (single_box_iou_rotated<T>(cur_box, block_boxes + i * 5) >\n          iou_threshold) {\n        t |= 1ULL << i;\n      }\n    }\n    const int col_blocks = at::cuda::ATenCeilDiv(n_boxes, threadsPerBlock);\n    dev_mask[cur_box_idx * col_blocks + col_start] = t;\n  }\n}\n\nnamespace detectron2 {\n\nat::Tensor nms_rotated_cuda(\n    // input must be contiguous\n    const at::Tensor& dets,\n    const at::Tensor& scores,\n    double iou_threshold) {\n  // using scalar_t = float;\n  AT_ASSERTM(dets.is_cuda(), \"dets must be a CUDA tensor\");\n  AT_ASSERTM(scores.is_cuda(), \"scores must be a CUDA tensor\");\n  at::cuda::CUDAGuard device_guard(dets.device());\n\n  auto order_t = std::get<1>(scores.sort(0, /* descending=*/true));\n  auto dets_sorted = dets.index_select(0, order_t);\n\n  auto dets_num = dets.size(0);\n\n  const int col_blocks =\n      at::cuda::ATenCeilDiv(static_cast<int>(dets_num), threadsPerBlock);\n\n  at::Tensor mask =\n      at::empty({dets_num * col_blocks}, dets.options().dtype(at::kLong));\n\n  dim3 blocks(col_blocks, col_blocks);\n  dim3 threads(threadsPerBlock);\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  AT_DISPATCH_FLOATING_TYPES(\n      dets_sorted.scalar_type(), \"nms_rotated_kernel_cuda\", [&] {\n        nms_rotated_cuda_kernel<scalar_t><<<blocks, threads, 0, stream>>>(\n            dets_num,\n            iou_threshold,\n            dets_sorted.data_ptr<scalar_t>(),\n            (unsigned long long*)mask.data_ptr<int64_t>());\n      });\n\n  at::Tensor mask_cpu = mask.to(at::kCPU);\n  unsigned long long* mask_host =\n      (unsigned long long*)mask_cpu.data_ptr<int64_t>();\n\n  std::vector<unsigned long long> remv(col_blocks);\n  memset(&remv[0], 0, sizeof(unsigned long long) * col_blocks);\n\n  at::Tensor keep =\n      at::empty({dets_num}, dets.options().dtype(at::kLong).device(at::kCPU));\n  int64_t* keep_out = keep.data_ptr<int64_t>();\n\n  int num_to_keep = 0;\n  for (int i = 0; i < dets_num; i++) {\n    int nblock = i / threadsPerBlock;\n    int inblock = i % threadsPerBlock;\n\n    if (!(remv[nblock] & (1ULL << inblock))) {\n      keep_out[num_to_keep++] = i;\n      unsigned long long* p = mask_host + i * col_blocks;\n      for (int j = nblock; j < col_blocks; j++) {\n        remv[j] |= p[j];\n      }\n    }\n  }\n\n  AT_CUDA_CHECK(cudaGetLastError());\n  return order_t.index(\n      {keep.narrow(/*dim=*/0, /*start=*/0, /*length=*/num_to_keep)\n           .to(order_t.device(), keep.scalar_type())});\n}\n\n} // namespace detectron2\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/csrc/vision.cpp",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n\n#include <torch/extension.h>\n#include \"ROIAlignRotated/ROIAlignRotated.h\"\n#include \"box_iou_rotated/box_iou_rotated.h\"\n#include \"cocoeval/cocoeval.h\"\n#include \"deformable/deform_conv.h\"\n#include \"nms_rotated/nms_rotated.h\"\n\nnamespace detectron2 {\n\n#if defined(WITH_CUDA) || defined(WITH_HIP)\nextern int get_cudart_version();\n#endif\n\nstd::string get_cuda_version() {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n  std::ostringstream oss;\n\n#if defined(WITH_CUDA)\n  oss << \"CUDA \";\n#else\n  oss << \"HIP \";\n#endif\n\n  // copied from\n  // https://github.com/pytorch/pytorch/blob/master/aten/src/ATen/cuda/detail/CUDAHooks.cpp#L231\n  auto printCudaStyleVersion = [&](int v) {\n    oss << (v / 1000) << \".\" << (v / 10 % 100);\n    if (v % 10 != 0) {\n      oss << \".\" << (v % 10);\n    }\n  };\n  printCudaStyleVersion(get_cudart_version());\n  return oss.str();\n#else // neither CUDA nor HIP\n  return std::string(\"not available\");\n#endif\n}\n\nbool has_cuda() {\n#if defined(WITH_CUDA)\n  return true;\n#else\n  return false;\n#endif\n}\n\n// similar to\n// https://github.com/pytorch/pytorch/blob/master/aten/src/ATen/Version.cpp\nstd::string get_compiler_version() {\n  std::ostringstream ss;\n#if defined(__GNUC__)\n#ifndef __clang__\n\n#if ((__GNUC__ <= 4) && (__GNUC_MINOR__ <= 8))\n#error \"GCC >= 4.9 is required!\"\n#endif\n\n  { ss << \"GCC \" << __GNUC__ << \".\" << __GNUC_MINOR__; }\n#endif\n#endif\n\n#if defined(__clang_major__)\n  {\n    ss << \"clang \" << __clang_major__ << \".\" << __clang_minor__ << \".\"\n       << __clang_patchlevel__;\n  }\n#endif\n\n#if defined(_MSC_VER)\n  { ss << \"MSVC \" << _MSC_FULL_VER; }\n#endif\n  return ss.str();\n}\n\nPYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {\n  m.def(\"get_compiler_version\", &get_compiler_version, \"get_compiler_version\");\n  m.def(\"get_cuda_version\", &get_cuda_version, \"get_cuda_version\");\n  m.def(\"has_cuda\", &has_cuda, \"has_cuda\");\n\n  m.def(\"deform_conv_forward\", &deform_conv_forward, \"deform_conv_forward\");\n  m.def(\n      \"deform_conv_backward_input\",\n      &deform_conv_backward_input,\n      \"deform_conv_backward_input\");\n  m.def(\n      \"deform_conv_backward_filter\",\n      &deform_conv_backward_filter,\n      \"deform_conv_backward_filter\");\n  m.def(\n      \"modulated_deform_conv_forward\",\n      &modulated_deform_conv_forward,\n      \"modulated_deform_conv_forward\");\n  m.def(\n      \"modulated_deform_conv_backward\",\n      &modulated_deform_conv_backward,\n      \"modulated_deform_conv_backward\");\n\n  m.def(\"COCOevalAccumulate\", &COCOeval::Accumulate, \"COCOeval::Accumulate\");\n  m.def(\n      \"COCOevalEvaluateImages\",\n      &COCOeval::EvaluateImages,\n      \"COCOeval::EvaluateImages\");\n  pybind11::class_<COCOeval::InstanceAnnotation>(m, \"InstanceAnnotation\")\n      .def(pybind11::init<uint64_t, double, double, bool, bool>());\n  pybind11::class_<COCOeval::ImageEvaluation>(m, \"ImageEvaluation\")\n      .def(pybind11::init<>());\n}\n\nTORCH_LIBRARY(detectron2, m) {\n  m.def(\"nms_rotated\", &nms_rotated);\n  m.def(\"box_iou_rotated\", &box_iou_rotated);\n  m.def(\"roi_align_rotated_forward\", &ROIAlignRotated_forward);\n  m.def(\"roi_align_rotated_backward\", &ROIAlignRotated_backward);\n}\n} // namespace detectron2\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/deform_conv.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport math\nfrom functools import lru_cache\nimport torch\nfrom torch import nn\nfrom torch.autograd import Function\nfrom torch.autograd.function import once_differentiable\nfrom torch.nn.modules.utils import _pair\nfrom torchvision.ops import deform_conv2d\n\nfrom detectron2 import _C\n\nfrom .wrappers import _NewEmptyTensorOp\n\n\nclass _DeformConv(Function):\n    @staticmethod\n    def forward(\n        ctx,\n        input,\n        offset,\n        weight,\n        stride=1,\n        padding=0,\n        dilation=1,\n        groups=1,\n        deformable_groups=1,\n        im2col_step=64,\n    ):\n        if input is not None and input.dim() != 4:\n            raise ValueError(\n                \"Expected 4D tensor as input, got {}D tensor instead.\".format(input.dim())\n            )\n        ctx.stride = _pair(stride)\n        ctx.padding = _pair(padding)\n        ctx.dilation = _pair(dilation)\n        ctx.groups = groups\n        ctx.deformable_groups = deformable_groups\n        ctx.im2col_step = im2col_step\n\n        ctx.save_for_backward(input, offset, weight)\n\n        output = input.new_empty(\n            _DeformConv._output_size(input, weight, ctx.padding, ctx.dilation, ctx.stride)\n        )\n\n        ctx.bufs_ = [input.new_empty(0), input.new_empty(0)]  # columns, ones\n\n        if not input.is_cuda:\n            if deformable_groups != 1:\n                raise NotImplementedError(\n                    \"Deformable Conv with deformable_groups != 1 is not supported on CPUs!\"\n                )\n            return deform_conv2d(\n                input, offset, weight, stride=stride, padding=padding, dilation=dilation\n            )\n        else:\n            cur_im2col_step = _DeformConv._cal_im2col_step(input.shape[0], ctx.im2col_step)\n            assert (input.shape[0] % cur_im2col_step) == 0, \"im2col step must divide batchsize\"\n\n            _C.deform_conv_forward(\n                input,\n                weight,\n                offset,\n                output,\n                ctx.bufs_[0],\n                ctx.bufs_[1],\n                weight.size(3),\n                weight.size(2),\n                ctx.stride[1],\n                ctx.stride[0],\n                ctx.padding[1],\n                ctx.padding[0],\n                ctx.dilation[1],\n                ctx.dilation[0],\n                ctx.groups,\n                ctx.deformable_groups,\n                cur_im2col_step,\n            )\n        return output\n\n    @staticmethod\n    @once_differentiable\n    def backward(ctx, grad_output):\n        input, offset, weight = ctx.saved_tensors\n\n        grad_input = grad_offset = grad_weight = None\n\n        if not grad_output.is_cuda:\n            raise NotImplementedError(\"Deformable Conv is not supported on CPUs!\")\n        else:\n            cur_im2col_step = _DeformConv._cal_im2col_step(input.shape[0], ctx.im2col_step)\n            assert (input.shape[0] % cur_im2col_step) == 0, \"im2col step must divide batchsize\"\n\n            if ctx.needs_input_grad[0] or ctx.needs_input_grad[1]:\n                grad_input = torch.zeros_like(input)\n                grad_offset = torch.zeros_like(offset)\n                _C.deform_conv_backward_input(\n                    input,\n                    offset,\n                    grad_output,\n                    grad_input,\n                    grad_offset,\n                    weight,\n                    ctx.bufs_[0],\n                    weight.size(3),\n                    weight.size(2),\n                    ctx.stride[1],\n                    ctx.stride[0],\n                    ctx.padding[1],\n                    ctx.padding[0],\n                    ctx.dilation[1],\n                    ctx.dilation[0],\n                    ctx.groups,\n                    ctx.deformable_groups,\n                    cur_im2col_step,\n                )\n\n            if ctx.needs_input_grad[2]:\n                grad_weight = torch.zeros_like(weight)\n                _C.deform_conv_backward_filter(\n                    input,\n                    offset,\n                    grad_output,\n                    grad_weight,\n                    ctx.bufs_[0],\n                    ctx.bufs_[1],\n                    weight.size(3),\n                    weight.size(2),\n                    ctx.stride[1],\n                    ctx.stride[0],\n                    ctx.padding[1],\n                    ctx.padding[0],\n                    ctx.dilation[1],\n                    ctx.dilation[0],\n                    ctx.groups,\n                    ctx.deformable_groups,\n                    1,\n                    cur_im2col_step,\n                )\n\n        return grad_input, grad_offset, grad_weight, None, None, None, None, None, None\n\n    @staticmethod\n    def _output_size(input, weight, padding, dilation, stride):\n        channels = weight.size(0)\n        output_size = (input.size(0), channels)\n        for d in range(input.dim() - 2):\n            in_size = input.size(d + 2)\n            pad = padding[d]\n            kernel = dilation[d] * (weight.size(d + 2) - 1) + 1\n            stride_ = stride[d]\n            output_size += ((in_size + (2 * pad) - kernel) // stride_ + 1,)\n        if not all(map(lambda s: s > 0, output_size)):\n            raise ValueError(\n                \"convolution input is too small (output would be {})\".format(\n                    \"x\".join(map(str, output_size))\n                )\n            )\n        return output_size\n\n    @staticmethod\n    @lru_cache(maxsize=128)\n    def _cal_im2col_step(input_size, default_size):\n        \"\"\"\n        Calculate proper im2col step size, which should be divisible by input_size and not larger\n        than prefer_size. Meanwhile the step size should be as large as possible to be more\n        efficient. So we choose the largest one among all divisors of input_size which are smaller\n        than prefer_size.\n        :param input_size: input batch size .\n        :param default_size: default preferred im2col step size.\n        :return: the largest proper step size.\n        \"\"\"\n        if input_size <= default_size:\n            return input_size\n        best_step = 1\n        for step in range(2, min(int(math.sqrt(input_size)) + 1, default_size)):\n            if input_size % step == 0:\n                if input_size // step <= default_size:\n                    return input_size // step\n                best_step = step\n\n        return best_step\n\n\nclass _ModulatedDeformConv(Function):\n    @staticmethod\n    def forward(\n        ctx,\n        input,\n        offset,\n        mask,\n        weight,\n        bias=None,\n        stride=1,\n        padding=0,\n        dilation=1,\n        groups=1,\n        deformable_groups=1,\n    ):\n        ctx.stride = stride\n        ctx.padding = padding\n        ctx.dilation = dilation\n        ctx.groups = groups\n        ctx.deformable_groups = deformable_groups\n        ctx.with_bias = bias is not None\n        if not ctx.with_bias:\n            bias = input.new_empty(1)  # fake tensor\n        if not input.is_cuda:\n            raise NotImplementedError(\"Deformable Conv is not supported on CPUs!\")\n        if (\n            weight.requires_grad\n            or mask.requires_grad\n            or offset.requires_grad\n            or input.requires_grad\n        ):\n            ctx.save_for_backward(input, offset, mask, weight, bias)\n        output = input.new_empty(_ModulatedDeformConv._infer_shape(ctx, input, weight))\n        ctx._bufs = [input.new_empty(0), input.new_empty(0)]\n        _C.modulated_deform_conv_forward(\n            input,\n            weight,\n            bias,\n            ctx._bufs[0],\n            offset,\n            mask,\n            output,\n            ctx._bufs[1],\n            weight.shape[2],\n            weight.shape[3],\n            ctx.stride,\n            ctx.stride,\n            ctx.padding,\n            ctx.padding,\n            ctx.dilation,\n            ctx.dilation,\n            ctx.groups,\n            ctx.deformable_groups,\n            ctx.with_bias,\n        )\n        return output\n\n    @staticmethod\n    @once_differentiable\n    def backward(ctx, grad_output):\n        if not grad_output.is_cuda:\n            raise NotImplementedError(\"Deformable Conv is not supported on CPUs!\")\n        input, offset, mask, weight, bias = ctx.saved_tensors\n        grad_input = torch.zeros_like(input)\n        grad_offset = torch.zeros_like(offset)\n        grad_mask = torch.zeros_like(mask)\n        grad_weight = torch.zeros_like(weight)\n        grad_bias = torch.zeros_like(bias)\n        _C.modulated_deform_conv_backward(\n            input,\n            weight,\n            bias,\n            ctx._bufs[0],\n            offset,\n            mask,\n            ctx._bufs[1],\n            grad_input,\n            grad_weight,\n            grad_bias,\n            grad_offset,\n            grad_mask,\n            grad_output,\n            weight.shape[2],\n            weight.shape[3],\n            ctx.stride,\n            ctx.stride,\n            ctx.padding,\n            ctx.padding,\n            ctx.dilation,\n            ctx.dilation,\n            ctx.groups,\n            ctx.deformable_groups,\n            ctx.with_bias,\n        )\n        if not ctx.with_bias:\n            grad_bias = None\n\n        return (\n            grad_input,\n            grad_offset,\n            grad_mask,\n            grad_weight,\n            grad_bias,\n            None,\n            None,\n            None,\n            None,\n            None,\n        )\n\n    @staticmethod\n    def _infer_shape(ctx, input, weight):\n        n = input.size(0)\n        channels_out = weight.size(0)\n        height, width = input.shape[2:4]\n        kernel_h, kernel_w = weight.shape[2:4]\n        height_out = (\n            height + 2 * ctx.padding - (ctx.dilation * (kernel_h - 1) + 1)\n        ) // ctx.stride + 1\n        width_out = (\n            width + 2 * ctx.padding - (ctx.dilation * (kernel_w - 1) + 1)\n        ) // ctx.stride + 1\n        return n, channels_out, height_out, width_out\n\n\ndeform_conv = _DeformConv.apply\nmodulated_deform_conv = _ModulatedDeformConv.apply\n\n\nclass DeformConv(nn.Module):\n    def __init__(\n        self,\n        in_channels,\n        out_channels,\n        kernel_size,\n        stride=1,\n        padding=0,\n        dilation=1,\n        groups=1,\n        deformable_groups=1,\n        bias=False,\n        norm=None,\n        activation=None,\n    ):\n        \"\"\"\n        Deformable convolution from :paper:`deformconv`.\n\n        Arguments are similar to :class:`Conv2D`. Extra arguments:\n\n        Args:\n            deformable_groups (int): number of groups used in deformable convolution.\n            norm (nn.Module, optional): a normalization layer\n            activation (callable(Tensor) -> Tensor): a callable activation function\n        \"\"\"\n        super(DeformConv, self).__init__()\n\n        assert not bias\n        assert in_channels % groups == 0, \"in_channels {} cannot be divisible by groups {}\".format(\n            in_channels, groups\n        )\n        assert (\n            out_channels % groups == 0\n        ), \"out_channels {} cannot be divisible by groups {}\".format(out_channels, groups)\n\n        self.in_channels = in_channels\n        self.out_channels = out_channels\n        self.kernel_size = _pair(kernel_size)\n        self.stride = _pair(stride)\n        self.padding = _pair(padding)\n        self.dilation = _pair(dilation)\n        self.groups = groups\n        self.deformable_groups = deformable_groups\n        self.norm = norm\n        self.activation = activation\n\n        self.weight = nn.Parameter(\n            torch.Tensor(out_channels, in_channels // self.groups, *self.kernel_size)\n        )\n        self.bias = None\n\n        nn.init.kaiming_uniform_(self.weight, nonlinearity=\"relu\")\n\n    def forward(self, x, offset):\n        if x.numel() == 0:\n            # When input is empty, we want to return a empty tensor with \"correct\" shape,\n            # So that the following operations will not panic\n            # if they check for the shape of the tensor.\n            # This computes the height and width of the output tensor\n            output_shape = [\n                (i + 2 * p - (di * (k - 1) + 1)) // s + 1\n                for i, p, di, k, s in zip(\n                    x.shape[-2:], self.padding, self.dilation, self.kernel_size, self.stride\n                )\n            ]\n            output_shape = [x.shape[0], self.weight.shape[0]] + output_shape\n            return _NewEmptyTensorOp.apply(x, output_shape)\n\n        x = deform_conv(\n            x,\n            offset,\n            self.weight,\n            self.stride,\n            self.padding,\n            self.dilation,\n            self.groups,\n            self.deformable_groups,\n        )\n        if self.norm is not None:\n            x = self.norm(x)\n        if self.activation is not None:\n            x = self.activation(x)\n        return x\n\n    def extra_repr(self):\n        tmpstr = \"in_channels=\" + str(self.in_channels)\n        tmpstr += \", out_channels=\" + str(self.out_channels)\n        tmpstr += \", kernel_size=\" + str(self.kernel_size)\n        tmpstr += \", stride=\" + str(self.stride)\n        tmpstr += \", padding=\" + str(self.padding)\n        tmpstr += \", dilation=\" + str(self.dilation)\n        tmpstr += \", groups=\" + str(self.groups)\n        tmpstr += \", deformable_groups=\" + str(self.deformable_groups)\n        tmpstr += \", bias=False\"\n        return tmpstr\n\n\nclass ModulatedDeformConv(nn.Module):\n    def __init__(\n        self,\n        in_channels,\n        out_channels,\n        kernel_size,\n        stride=1,\n        padding=0,\n        dilation=1,\n        groups=1,\n        deformable_groups=1,\n        bias=True,\n        norm=None,\n        activation=None,\n    ):\n        \"\"\"\n        Modulated deformable convolution from :paper:`deformconv2`.\n\n        Arguments are similar to :class:`Conv2D`. Extra arguments:\n\n        Args:\n            deformable_groups (int): number of groups used in deformable convolution.\n            norm (nn.Module, optional): a normalization layer\n            activation (callable(Tensor) -> Tensor): a callable activation function\n        \"\"\"\n        super(ModulatedDeformConv, self).__init__()\n        self.in_channels = in_channels\n        self.out_channels = out_channels\n        self.kernel_size = _pair(kernel_size)\n        self.stride = stride\n        self.padding = padding\n        self.dilation = dilation\n        self.groups = groups\n        self.deformable_groups = deformable_groups\n        self.with_bias = bias\n        self.norm = norm\n        self.activation = activation\n\n        self.weight = nn.Parameter(\n            torch.Tensor(out_channels, in_channels // groups, *self.kernel_size)\n        )\n        if bias:\n            self.bias = nn.Parameter(torch.Tensor(out_channels))\n        else:\n            self.bias = None\n\n        nn.init.kaiming_uniform_(self.weight, nonlinearity=\"relu\")\n        if self.bias is not None:\n            nn.init.constant_(self.bias, 0)\n\n    def forward(self, x, offset, mask):\n        if x.numel() == 0:\n            output_shape = [\n                (i + 2 * p - (di * (k - 1) + 1)) // s + 1\n                for i, p, di, k, s in zip(\n                    x.shape[-2:], self.padding, self.dilation, self.kernel_size, self.stride\n                )\n            ]\n            output_shape = [x.shape[0], self.weight.shape[0]] + output_shape\n            return _NewEmptyTensorOp.apply(x, output_shape)\n\n        x = modulated_deform_conv(\n            x,\n            offset,\n            mask,\n            self.weight,\n            self.bias,\n            self.stride,\n            self.padding,\n            self.dilation,\n            self.groups,\n            self.deformable_groups,\n        )\n        if self.norm is not None:\n            x = self.norm(x)\n        if self.activation is not None:\n            x = self.activation(x)\n        return x\n\n    def extra_repr(self):\n        tmpstr = \"in_channels=\" + str(self.in_channels)\n        tmpstr += \", out_channels=\" + str(self.out_channels)\n        tmpstr += \", kernel_size=\" + str(self.kernel_size)\n        tmpstr += \", stride=\" + str(self.stride)\n        tmpstr += \", padding=\" + str(self.padding)\n        tmpstr += \", dilation=\" + str(self.dilation)\n        tmpstr += \", groups=\" + str(self.groups)\n        tmpstr += \", deformable_groups=\" + str(self.deformable_groups)\n        tmpstr += \", bias=\" + str(self.with_bias)\n        return tmpstr\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/losses.py",
    "content": "import math\nimport torch\n\n\ndef diou_loss(\n    boxes1: torch.Tensor,\n    boxes2: torch.Tensor,\n    reduction: str = \"none\",\n    eps: float = 1e-7,\n) -> torch.Tensor:\n    \"\"\"\n    Distance Intersection over Union Loss (Zhaohui Zheng et. al)\n    https://arxiv.org/abs/1911.08287\n    Args:\n        boxes1, boxes2 (Tensor): box locations in XYXY format, shape (N, 4) or (4,).\n        reduction: 'none' | 'mean' | 'sum'\n                 'none': No reduction will be applied to the output.\n                 'mean': The output will be averaged.\n                 'sum': The output will be summed.\n        eps (float): small number to prevent division by zero\n    \"\"\"\n\n    x1, y1, x2, y2 = boxes1.unbind(dim=-1)\n    x1g, y1g, x2g, y2g = boxes2.unbind(dim=-1)\n\n    # TODO: use torch._assert_async() when pytorch 1.8 support is dropped\n    assert (x2 >= x1).all(), \"bad box: x1 larger than x2\"\n    assert (y2 >= y1).all(), \"bad box: y1 larger than y2\"\n\n    # Intersection keypoints\n    xkis1 = torch.max(x1, x1g)\n    ykis1 = torch.max(y1, y1g)\n    xkis2 = torch.min(x2, x2g)\n    ykis2 = torch.min(y2, y2g)\n\n    intsct = torch.zeros_like(x1)\n    mask = (ykis2 > ykis1) & (xkis2 > xkis1)\n    intsct[mask] = (xkis2[mask] - xkis1[mask]) * (ykis2[mask] - ykis1[mask])\n    union = (x2 - x1) * (y2 - y1) + (x2g - x1g) * (y2g - y1g) - intsct + eps\n    iou = intsct / union\n\n    # smallest enclosing box\n    xc1 = torch.min(x1, x1g)\n    yc1 = torch.min(y1, y1g)\n    xc2 = torch.max(x2, x2g)\n    yc2 = torch.max(y2, y2g)\n    diag_len = ((xc2 - xc1) ** 2) + ((yc2 - yc1) ** 2) + eps\n\n    # centers of boxes\n    x_p = (x2 + x1) / 2\n    y_p = (y2 + y1) / 2\n    x_g = (x1g + x2g) / 2\n    y_g = (y1g + y2g) / 2\n    distance = ((x_p - x_g) ** 2) + ((y_p - y_g) ** 2)\n\n    # Eqn. (7)\n    loss = 1 - iou + (distance / diag_len)\n    if reduction == \"mean\":\n        loss = loss.mean() if loss.numel() > 0 else 0.0 * loss.sum()\n    elif reduction == \"sum\":\n        loss = loss.sum()\n\n    return loss\n\n\ndef ciou_loss(\n    boxes1: torch.Tensor,\n    boxes2: torch.Tensor,\n    reduction: str = \"none\",\n    eps: float = 1e-7,\n) -> torch.Tensor:\n    \"\"\"\n    Complete Intersection over Union Loss (Zhaohui Zheng et. al)\n    https://arxiv.org/abs/1911.08287\n    Args:\n        boxes1, boxes2 (Tensor): box locations in XYXY format, shape (N, 4) or (4,).\n        reduction: 'none' | 'mean' | 'sum'\n                 'none': No reduction will be applied to the output.\n                 'mean': The output will be averaged.\n                 'sum': The output will be summed.\n        eps (float): small number to prevent division by zero\n    \"\"\"\n\n    x1, y1, x2, y2 = boxes1.unbind(dim=-1)\n    x1g, y1g, x2g, y2g = boxes2.unbind(dim=-1)\n\n    # TODO: use torch._assert_async() when pytorch 1.8 support is dropped\n    assert (x2 >= x1).all(), \"bad box: x1 larger than x2\"\n    assert (y2 >= y1).all(), \"bad box: y1 larger than y2\"\n\n    # Intersection keypoints\n    xkis1 = torch.max(x1, x1g)\n    ykis1 = torch.max(y1, y1g)\n    xkis2 = torch.min(x2, x2g)\n    ykis2 = torch.min(y2, y2g)\n\n    intsct = torch.zeros_like(x1)\n    mask = (ykis2 > ykis1) & (xkis2 > xkis1)\n    intsct[mask] = (xkis2[mask] - xkis1[mask]) * (ykis2[mask] - ykis1[mask])\n    union = (x2 - x1) * (y2 - y1) + (x2g - x1g) * (y2g - y1g) - intsct + eps\n    iou = intsct / union\n\n    # smallest enclosing box\n    xc1 = torch.min(x1, x1g)\n    yc1 = torch.min(y1, y1g)\n    xc2 = torch.max(x2, x2g)\n    yc2 = torch.max(y2, y2g)\n    diag_len = ((xc2 - xc1) ** 2) + ((yc2 - yc1) ** 2) + eps\n\n    # centers of boxes\n    x_p = (x2 + x1) / 2\n    y_p = (y2 + y1) / 2\n    x_g = (x1g + x2g) / 2\n    y_g = (y1g + y2g) / 2\n    distance = ((x_p - x_g) ** 2) + ((y_p - y_g) ** 2)\n\n    # width and height of boxes\n    w_pred = x2 - x1\n    h_pred = y2 - y1\n    w_gt = x2g - x1g\n    h_gt = y2g - y1g\n    v = (4 / (math.pi ** 2)) * torch.pow((torch.atan(w_gt / h_gt) - torch.atan(w_pred / h_pred)), 2)\n    with torch.no_grad():\n        alpha = v / (1 - iou + v + eps)\n\n    # Eqn. (10)\n    loss = 1 - iou + (distance / diag_len) + alpha * v\n    if reduction == \"mean\":\n        loss = loss.mean() if loss.numel() > 0 else 0.0 * loss.sum()\n    elif reduction == \"sum\":\n        loss = loss.sum()\n\n    return loss\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/mask_ops.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport numpy as np\nfrom typing import Tuple\nimport torch\nfrom PIL import Image\nfrom torch.nn import functional as F\n\n__all__ = [\"paste_masks_in_image\"]\n\n\nBYTES_PER_FLOAT = 4\n# TODO: This memory limit may be too much or too little. It would be better to\n# determine it based on available resources.\nGPU_MEM_LIMIT = 1024 ** 3  # 1 GB memory limit\n\n\ndef _do_paste_mask(masks, boxes, img_h: int, img_w: int, skip_empty: bool = True):\n    \"\"\"\n    Args:\n        masks: N, 1, H, W\n        boxes: N, 4\n        img_h, img_w (int):\n        skip_empty (bool): only paste masks within the region that\n            tightly bound all boxes, and returns the results this region only.\n            An important optimization for CPU.\n\n    Returns:\n        if skip_empty == False, a mask of shape (N, img_h, img_w)\n        if skip_empty == True, a mask of shape (N, h', w'), and the slice\n            object for the corresponding region.\n    \"\"\"\n    # On GPU, paste all masks together (up to chunk size)\n    # by using the entire image to sample the masks\n    # Compared to pasting them one by one,\n    # this has more operations but is faster on COCO-scale dataset.\n    device = masks.device\n\n    if skip_empty and not torch.jit.is_scripting():\n        x0_int, y0_int = torch.clamp(boxes.min(dim=0).values.floor()[:2] - 1, min=0).to(\n            dtype=torch.int32\n        )\n        x1_int = torch.clamp(boxes[:, 2].max().ceil() + 1, max=img_w).to(dtype=torch.int32)\n        y1_int = torch.clamp(boxes[:, 3].max().ceil() + 1, max=img_h).to(dtype=torch.int32)\n    else:\n        x0_int, y0_int = 0, 0\n        x1_int, y1_int = img_w, img_h\n    x0, y0, x1, y1 = torch.split(boxes, 1, dim=1)  # each is Nx1\n\n    N = masks.shape[0]\n\n    img_y = torch.arange(y0_int, y1_int, device=device, dtype=torch.float32) + 0.5\n    img_x = torch.arange(x0_int, x1_int, device=device, dtype=torch.float32) + 0.5\n    img_y = (img_y - y0) / (y1 - y0) * 2 - 1\n    img_x = (img_x - x0) / (x1 - x0) * 2 - 1\n    # img_x, img_y have shapes (N, w), (N, h)\n\n    gx = img_x[:, None, :].expand(N, img_y.size(1), img_x.size(1))\n    gy = img_y[:, :, None].expand(N, img_y.size(1), img_x.size(1))\n    grid = torch.stack([gx, gy], dim=3)\n\n    if not torch.jit.is_scripting():\n        if not masks.dtype.is_floating_point:\n            masks = masks.float()\n    img_masks = F.grid_sample(masks, grid.to(masks.dtype), align_corners=False)\n\n    if skip_empty and not torch.jit.is_scripting():\n        return img_masks[:, 0], (slice(y0_int, y1_int), slice(x0_int, x1_int))\n    else:\n        return img_masks[:, 0], ()\n\n\n# Annotate boxes as Tensor (but not Boxes) in order to use scripting\n@torch.jit.script_if_tracing\ndef paste_masks_in_image(\n    masks: torch.Tensor, boxes: torch.Tensor, image_shape: Tuple[int, int], threshold: float = 0.5\n):\n    \"\"\"\n    Paste a set of masks that are of a fixed resolution (e.g., 28 x 28) into an image.\n    The location, height, and width for pasting each mask is determined by their\n    corresponding bounding boxes in boxes.\n\n    Note:\n        This is a complicated but more accurate implementation. In actual deployment, it is\n        often enough to use a faster but less accurate implementation.\n        See :func:`paste_mask_in_image_old` in this file for an alternative implementation.\n\n    Args:\n        masks (tensor): Tensor of shape (Bimg, Hmask, Wmask), where Bimg is the number of\n            detected object instances in the image and Hmask, Wmask are the mask width and mask\n            height of the predicted mask (e.g., Hmask = Wmask = 28). Values are in [0, 1].\n        boxes (Boxes or Tensor): A Boxes of length Bimg or Tensor of shape (Bimg, 4).\n            boxes[i] and masks[i] correspond to the same object instance.\n        image_shape (tuple): height, width\n        threshold (float): A threshold in [0, 1] for converting the (soft) masks to\n            binary masks.\n\n    Returns:\n        img_masks (Tensor): A tensor of shape (Bimg, Himage, Wimage), where Bimg is the\n        number of detected object instances and Himage, Wimage are the image width\n        and height. img_masks[i] is a binary mask for object instance i.\n    \"\"\"\n\n    assert masks.shape[-1] == masks.shape[-2], \"Only square mask predictions are supported\"\n    N = len(masks)\n    if N == 0:\n        return masks.new_empty((0,) + image_shape, dtype=torch.uint8)\n    if not isinstance(boxes, torch.Tensor):\n        boxes = boxes.tensor\n    device = boxes.device\n    assert len(boxes) == N, boxes.shape\n\n    img_h, img_w = image_shape\n\n    # The actual implementation split the input into chunks,\n    # and paste them chunk by chunk.\n    if device.type == \"cpu\" or torch.jit.is_scripting():\n        # CPU is most efficient when they are pasted one by one with skip_empty=True\n        # so that it performs minimal number of operations.\n        num_chunks = N\n    else:\n        # GPU benefits from parallelism for larger chunks, but may have memory issue\n        # int(img_h) because shape may be tensors in tracing\n        num_chunks = int(np.ceil(N * int(img_h) * int(img_w) * BYTES_PER_FLOAT / GPU_MEM_LIMIT))\n        assert (\n            num_chunks <= N\n        ), \"Default GPU_MEM_LIMIT in mask_ops.py is too small; try increasing it\"\n    chunks = torch.chunk(torch.arange(N, device=device), num_chunks)\n\n    img_masks = torch.zeros(\n        N, img_h, img_w, device=device, dtype=torch.bool if threshold >= 0 else torch.uint8\n    )\n    for inds in chunks:\n        masks_chunk, spatial_inds = _do_paste_mask(\n            masks[inds, None, :, :], boxes[inds], img_h, img_w, skip_empty=device.type == \"cpu\"\n        )\n\n        if threshold >= 0:\n            masks_chunk = (masks_chunk >= threshold).to(dtype=torch.bool)\n        else:\n            # for visualization and debugging\n            masks_chunk = (masks_chunk * 255).to(dtype=torch.uint8)\n\n        if torch.jit.is_scripting():  # Scripting does not use the optimized codepath\n            img_masks[inds] = masks_chunk\n        else:\n            img_masks[(inds,) + spatial_inds] = masks_chunk\n    return img_masks\n\n\n# The below are the original paste function (from Detectron1) which has\n# larger quantization error.\n# It is faster on CPU, while the aligned one is faster on GPU thanks to grid_sample.\n\n\ndef paste_mask_in_image_old(mask, box, img_h, img_w, threshold):\n    \"\"\"\n    Paste a single mask in an image.\n    This is a per-box implementation of :func:`paste_masks_in_image`.\n    This function has larger quantization error due to incorrect pixel\n    modeling and is not used any more.\n\n    Args:\n        mask (Tensor): A tensor of shape (Hmask, Wmask) storing the mask of a single\n            object instance. Values are in [0, 1].\n        box (Tensor): A tensor of shape (4, ) storing the x0, y0, x1, y1 box corners\n            of the object instance.\n        img_h, img_w (int): Image height and width.\n        threshold (float): Mask binarization threshold in [0, 1].\n\n    Returns:\n        im_mask (Tensor):\n            The resized and binarized object mask pasted into the original\n            image plane (a tensor of shape (img_h, img_w)).\n    \"\"\"\n    # Conversion from continuous box coordinates to discrete pixel coordinates\n    # via truncation (cast to int32). This determines which pixels to paste the\n    # mask onto.\n    box = box.to(dtype=torch.int32)  # Continuous to discrete coordinate conversion\n    # An example (1D) box with continuous coordinates (x0=0.7, x1=4.3) will map to\n    # a discrete coordinates (x0=0, x1=4). Note that box is mapped to 5 = x1 - x0 + 1\n    # pixels (not x1 - x0 pixels).\n    samples_w = box[2] - box[0] + 1  # Number of pixel samples, *not* geometric width\n    samples_h = box[3] - box[1] + 1  # Number of pixel samples, *not* geometric height\n\n    # Resample the mask from it's original grid to the new samples_w x samples_h grid\n    mask = Image.fromarray(mask.cpu().numpy())\n    mask = mask.resize((samples_w, samples_h), resample=Image.BILINEAR)\n    mask = np.array(mask, copy=False)\n\n    if threshold >= 0:\n        mask = np.array(mask > threshold, dtype=np.uint8)\n        mask = torch.from_numpy(mask)\n    else:\n        # for visualization and debugging, we also\n        # allow it to return an unmodified mask\n        mask = torch.from_numpy(mask * 255).to(torch.uint8)\n\n    im_mask = torch.zeros((img_h, img_w), dtype=torch.uint8)\n    x_0 = max(box[0], 0)\n    x_1 = min(box[2] + 1, img_w)\n    y_0 = max(box[1], 0)\n    y_1 = min(box[3] + 1, img_h)\n\n    im_mask[y_0:y_1, x_0:x_1] = mask[\n        (y_0 - box[1]) : (y_1 - box[1]), (x_0 - box[0]) : (x_1 - box[0])\n    ]\n    return im_mask\n\n\n# Our pixel modeling requires extrapolation for any continuous\n# coordinate < 0.5 or > length - 0.5. When sampling pixels on the masks,\n# we would like this extrapolation to be an interpolation between boundary values and zero,\n# instead of using absolute zero or boundary values.\n# Therefore `paste_mask_in_image_old` is often used with zero padding around the masks like this:\n# masks, scale = pad_masks(masks[:, 0, :, :], 1)\n# boxes = scale_boxes(boxes.tensor, scale)\n\n\ndef pad_masks(masks, padding):\n    \"\"\"\n    Args:\n        masks (tensor): A tensor of shape (B, M, M) representing B masks.\n        padding (int): Number of cells to pad on all sides.\n\n    Returns:\n        The padded masks and the scale factor of the padding size / original size.\n    \"\"\"\n    B = masks.shape[0]\n    M = masks.shape[-1]\n    pad2 = 2 * padding\n    scale = float(M + pad2) / M\n    padded_masks = masks.new_zeros((B, M + pad2, M + pad2))\n    padded_masks[:, padding:-padding, padding:-padding] = masks\n    return padded_masks, scale\n\n\ndef scale_boxes(boxes, scale):\n    \"\"\"\n    Args:\n        boxes (tensor): A tensor of shape (B, 4) representing B boxes with 4\n            coords representing the corners x0, y0, x1, y1,\n        scale (float): The box scaling factor.\n\n    Returns:\n        Scaled boxes.\n    \"\"\"\n    w_half = (boxes[:, 2] - boxes[:, 0]) * 0.5\n    h_half = (boxes[:, 3] - boxes[:, 1]) * 0.5\n    x_c = (boxes[:, 2] + boxes[:, 0]) * 0.5\n    y_c = (boxes[:, 3] + boxes[:, 1]) * 0.5\n\n    w_half *= scale\n    h_half *= scale\n\n    scaled_boxes = torch.zeros_like(boxes)\n    scaled_boxes[:, 0] = x_c - w_half\n    scaled_boxes[:, 2] = x_c + w_half\n    scaled_boxes[:, 1] = y_c - h_half\n    scaled_boxes[:, 3] = y_c + h_half\n    return scaled_boxes\n\n\n@torch.jit.script_if_tracing\ndef _paste_masks_tensor_shape(\n    masks: torch.Tensor,\n    boxes: torch.Tensor,\n    image_shape: Tuple[torch.Tensor, torch.Tensor],\n    threshold: float = 0.5,\n):\n    \"\"\"\n    A wrapper of paste_masks_in_image where image_shape is Tensor.\n    During tracing, shapes might be tensors instead of ints. The Tensor->int\n    conversion should be scripted rather than traced.\n    \"\"\"\n    return paste_masks_in_image(masks, boxes, (int(image_shape[0]), int(image_shape[1])), threshold)\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/nms.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport torch\nfrom torchvision.ops import boxes as box_ops\nfrom torchvision.ops import nms  # noqa . for compatibility\n\n\ndef batched_nms(\n    boxes: torch.Tensor, scores: torch.Tensor, idxs: torch.Tensor, iou_threshold: float\n):\n    \"\"\"\n    Same as torchvision.ops.boxes.batched_nms, but with float().\n    \"\"\"\n    assert boxes.shape[-1] == 4\n    # Note: Torchvision already has a strategy (https://github.com/pytorch/vision/issues/1311)\n    # to decide whether to use coordinate trick or for loop to implement batched_nms. So we\n    # just call it directly.\n    # Fp16 does not have enough range for batched NMS, so adding float().\n    return box_ops.batched_nms(boxes.float(), scores, idxs, iou_threshold)\n\n\n# Note: this function (nms_rotated) might be moved into\n# torchvision/ops/boxes.py in the future\ndef nms_rotated(boxes, scores, iou_threshold):\n    \"\"\"\n    Performs non-maximum suppression (NMS) on the rotated boxes according\n    to their intersection-over-union (IoU).\n\n    Rotated NMS iteratively removes lower scoring rotated boxes which have an\n    IoU greater than iou_threshold with another (higher scoring) rotated box.\n\n    Note that RotatedBox (5, 3, 4, 2, -90) covers exactly the same region as\n    RotatedBox (5, 3, 4, 2, 90) does, and their IoU will be 1. However, they\n    can be representing completely different objects in certain tasks, e.g., OCR.\n\n    As for the question of whether rotated-NMS should treat them as faraway boxes\n    even though their IOU is 1, it depends on the application and/or ground truth annotation.\n\n    As an extreme example, consider a single character v and the square box around it.\n\n    If the angle is 0 degree, the object (text) would be read as 'v';\n\n    If the angle is 90 degrees, the object (text) would become '>';\n\n    If the angle is 180 degrees, the object (text) would become '^';\n\n    If the angle is 270/-90 degrees, the object (text) would become '<'\n\n    All of these cases have IoU of 1 to each other, and rotated NMS that only\n    uses IoU as criterion would only keep one of them with the highest score -\n    which, practically, still makes sense in most cases because typically\n    only one of theses orientations is the correct one. Also, it does not matter\n    as much if the box is only used to classify the object (instead of transcribing\n    them with a sequential OCR recognition model) later.\n\n    On the other hand, when we use IoU to filter proposals that are close to the\n    ground truth during training, we should definitely take the angle into account if\n    we know the ground truth is labeled with the strictly correct orientation (as in,\n    upside-down words are annotated with -180 degrees even though they can be covered\n    with a 0/90/-90 degree box, etc.)\n\n    The way the original dataset is annotated also matters. For example, if the dataset\n    is a 4-point polygon dataset that does not enforce ordering of vertices/orientation,\n    we can estimate a minimum rotated bounding box to this polygon, but there's no way\n    we can tell the correct angle with 100% confidence (as shown above, there could be 4 different\n    rotated boxes, with angles differed by 90 degrees to each other, covering the exactly\n    same region). In that case we have to just use IoU to determine the box\n    proximity (as many detection benchmarks (even for text) do) unless there're other\n    assumptions we can make (like width is always larger than height, or the object is not\n    rotated by more than 90 degrees CCW/CW, etc.)\n\n    In summary, not considering angles in rotated NMS seems to be a good option for now,\n    but we should be aware of its implications.\n\n    Args:\n        boxes (Tensor[N, 5]): Rotated boxes to perform NMS on. They are expected to be in\n           (x_center, y_center, width, height, angle_degrees) format.\n        scores (Tensor[N]): Scores for each one of the rotated boxes\n        iou_threshold (float): Discards all overlapping rotated boxes with IoU < iou_threshold\n\n    Returns:\n        keep (Tensor): int64 tensor with the indices of the elements that have been kept\n        by Rotated NMS, sorted in decreasing order of scores\n    \"\"\"\n    return torch.ops.detectron2.nms_rotated(boxes, scores, iou_threshold)\n\n\n# Note: this function (batched_nms_rotated) might be moved into\n# torchvision/ops/boxes.py in the future\ndef batched_nms_rotated(boxes, scores, idxs, iou_threshold):\n    \"\"\"\n    Performs non-maximum suppression in a batched fashion.\n\n    Each index value correspond to a category, and NMS\n    will not be applied between elements of different categories.\n\n    Args:\n        boxes (Tensor[N, 5]):\n           boxes where NMS will be performed. They\n           are expected to be in (x_ctr, y_ctr, width, height, angle_degrees) format\n        scores (Tensor[N]):\n           scores for each one of the boxes\n        idxs (Tensor[N]):\n           indices of the categories for each one of the boxes.\n        iou_threshold (float):\n           discards all overlapping boxes\n           with IoU < iou_threshold\n\n    Returns:\n        Tensor:\n            int64 tensor with the indices of the elements that have been kept\n            by NMS, sorted in decreasing order of scores\n    \"\"\"\n    assert boxes.shape[-1] == 5\n\n    if boxes.numel() == 0:\n        return torch.empty((0,), dtype=torch.int64, device=boxes.device)\n    boxes = boxes.float()  # fp16 does not have enough range for batched NMS\n    # Strategy: in order to perform NMS independently per class,\n    # we add an offset to all the boxes. The offset is dependent\n    # only on the class idx, and is large enough so that boxes\n    # from different classes do not overlap\n\n    # Note that batched_nms in torchvision/ops/boxes.py only uses max_coordinate,\n    # which won't handle negative coordinates correctly.\n    # Here by using min_coordinate we can make sure the negative coordinates are\n    # correctly handled.\n    max_coordinate = (\n        torch.max(boxes[:, 0], boxes[:, 1]) + torch.max(boxes[:, 2], boxes[:, 3]) / 2\n    ).max()\n    min_coordinate = (\n        torch.min(boxes[:, 0], boxes[:, 1]) - torch.max(boxes[:, 2], boxes[:, 3]) / 2\n    ).min()\n    offsets = idxs.to(boxes) * (max_coordinate - min_coordinate + 1)\n    boxes_for_nms = boxes.clone()  # avoid modifying the original values in boxes\n    boxes_for_nms[:, :2] += offsets[:, None]\n    keep = nms_rotated(boxes_for_nms, scores, iou_threshold)\n    return keep\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/roi_align.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom torch import nn\nfrom torchvision.ops import roi_align\n\n\n# NOTE: torchvision's RoIAlign has a different default aligned=False\nclass ROIAlign(nn.Module):\n    def __init__(self, output_size, spatial_scale, sampling_ratio, aligned=True):\n        \"\"\"\n        Args:\n            output_size (tuple): h, w\n            spatial_scale (float): scale the input boxes by this number\n            sampling_ratio (int): number of inputs samples to take for each output\n                sample. 0 to take samples densely.\n            aligned (bool): if False, use the legacy implementation in\n                Detectron. If True, align the results more perfectly.\n\n        Note:\n            The meaning of aligned=True:\n\n            Given a continuous coordinate c, its two neighboring pixel indices (in our\n            pixel model) are computed by floor(c - 0.5) and ceil(c - 0.5). For example,\n            c=1.3 has pixel neighbors with discrete indices [0] and [1] (which are sampled\n            from the underlying signal at continuous coordinates 0.5 and 1.5). But the original\n            roi_align (aligned=False) does not subtract the 0.5 when computing neighboring\n            pixel indices and therefore it uses pixels with a slightly incorrect alignment\n            (relative to our pixel model) when performing bilinear interpolation.\n\n            With `aligned=True`,\n            we first appropriately scale the ROI and then shift it by -0.5\n            prior to calling roi_align. This produces the correct neighbors; see\n            detectron2/tests/test_roi_align.py for verification.\n\n            The difference does not make a difference to the model's performance if\n            ROIAlign is used together with conv layers.\n        \"\"\"\n        super().__init__()\n        self.output_size = output_size\n        self.spatial_scale = spatial_scale\n        self.sampling_ratio = sampling_ratio\n        self.aligned = aligned\n\n        from torchvision import __version__\n\n        version = tuple(int(x) for x in __version__.split(\".\")[:2])\n        # https://github.com/pytorch/vision/pull/2438\n        assert version >= (0, 7), \"Require torchvision >= 0.7\"\n\n    def forward(self, input, rois):\n        \"\"\"\n        Args:\n            input: NCHW images\n            rois: Bx5 boxes. First column is the index into N. The other 4 columns are xyxy.\n        \"\"\"\n        assert rois.dim() == 2 and rois.size(1) == 5\n        if input.is_quantized:\n            input = input.dequantize()\n        return roi_align(\n            input,\n            rois.to(dtype=input.dtype),\n            self.output_size,\n            self.spatial_scale,\n            self.sampling_ratio,\n            self.aligned,\n        )\n\n    def __repr__(self):\n        tmpstr = self.__class__.__name__ + \"(\"\n        tmpstr += \"output_size=\" + str(self.output_size)\n        tmpstr += \", spatial_scale=\" + str(self.spatial_scale)\n        tmpstr += \", sampling_ratio=\" + str(self.sampling_ratio)\n        tmpstr += \", aligned=\" + str(self.aligned)\n        tmpstr += \")\"\n        return tmpstr\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/roi_align_rotated.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport torch\nfrom torch import nn\nfrom torch.autograd import Function\nfrom torch.autograd.function import once_differentiable\nfrom torch.nn.modules.utils import _pair\n\n\nclass _ROIAlignRotated(Function):\n    @staticmethod\n    def forward(ctx, input, roi, output_size, spatial_scale, sampling_ratio):\n        ctx.save_for_backward(roi)\n        ctx.output_size = _pair(output_size)\n        ctx.spatial_scale = spatial_scale\n        ctx.sampling_ratio = sampling_ratio\n        ctx.input_shape = input.size()\n        output = torch.ops.detectron2.roi_align_rotated_forward(\n            input, roi, spatial_scale, output_size[0], output_size[1], sampling_ratio\n        )\n        return output\n\n    @staticmethod\n    @once_differentiable\n    def backward(ctx, grad_output):\n        (rois,) = ctx.saved_tensors\n        output_size = ctx.output_size\n        spatial_scale = ctx.spatial_scale\n        sampling_ratio = ctx.sampling_ratio\n        bs, ch, h, w = ctx.input_shape\n        grad_input = torch.ops.detectron2.roi_align_rotated_backward(\n            grad_output,\n            rois,\n            spatial_scale,\n            output_size[0],\n            output_size[1],\n            bs,\n            ch,\n            h,\n            w,\n            sampling_ratio,\n        )\n        return grad_input, None, None, None, None, None\n\n\nroi_align_rotated = _ROIAlignRotated.apply\n\n\nclass ROIAlignRotated(nn.Module):\n    def __init__(self, output_size, spatial_scale, sampling_ratio):\n        \"\"\"\n        Args:\n            output_size (tuple): h, w\n            spatial_scale (float): scale the input boxes by this number\n            sampling_ratio (int): number of inputs samples to take for each output\n                sample. 0 to take samples densely.\n\n        Note:\n            ROIAlignRotated supports continuous coordinate by default:\n            Given a continuous coordinate c, its two neighboring pixel indices (in our\n            pixel model) are computed by floor(c - 0.5) and ceil(c - 0.5). For example,\n            c=1.3 has pixel neighbors with discrete indices [0] and [1] (which are sampled\n            from the underlying signal at continuous coordinates 0.5 and 1.5).\n        \"\"\"\n        super(ROIAlignRotated, self).__init__()\n        self.output_size = output_size\n        self.spatial_scale = spatial_scale\n        self.sampling_ratio = sampling_ratio\n\n    def forward(self, input, rois):\n        \"\"\"\n        Args:\n            input: NCHW images\n            rois: Bx6 boxes. First column is the index into N.\n                The other 5 columns are (x_ctr, y_ctr, width, height, angle_degrees).\n        \"\"\"\n        assert rois.dim() == 2 and rois.size(1) == 6\n        orig_dtype = input.dtype\n        if orig_dtype == torch.float16:\n            input = input.float()\n            rois = rois.float()\n        return roi_align_rotated(\n            input, rois, self.output_size, self.spatial_scale, self.sampling_ratio\n        ).to(dtype=orig_dtype)\n\n    def __repr__(self):\n        tmpstr = self.__class__.__name__ + \"(\"\n        tmpstr += \"output_size=\" + str(self.output_size)\n        tmpstr += \", spatial_scale=\" + str(self.spatial_scale)\n        tmpstr += \", sampling_ratio=\" + str(self.sampling_ratio)\n        tmpstr += \")\"\n        return tmpstr\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/rotated_boxes.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom __future__ import absolute_import, division, print_function, unicode_literals\nimport torch\n\n\ndef pairwise_iou_rotated(boxes1, boxes2):\n    \"\"\"\n    Return intersection-over-union (Jaccard index) of boxes.\n\n    Both sets of boxes are expected to be in\n    (x_center, y_center, width, height, angle) format.\n\n    Arguments:\n        boxes1 (Tensor[N, 5])\n        boxes2 (Tensor[M, 5])\n\n    Returns:\n        iou (Tensor[N, M]): the NxM matrix containing the pairwise\n            IoU values for every element in boxes1 and boxes2\n    \"\"\"\n    return torch.ops.detectron2.box_iou_rotated(boxes1, boxes2)\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/shape_spec.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\nfrom collections import namedtuple\n\n\nclass ShapeSpec(namedtuple(\"_ShapeSpec\", [\"channels\", \"height\", \"width\", \"stride\"])):\n    \"\"\"\n    A simple structure that contains basic shape specification about a tensor.\n    It is often used as the auxiliary inputs/outputs of models,\n    to complement the lack of shape inference ability among pytorch modules.\n\n    Attributes:\n        channels:\n        height:\n        width:\n        stride:\n    \"\"\"\n\n    def __new__(cls, channels=None, height=None, width=None, stride=None):\n        return super().__new__(cls, channels, height, width, stride)\n"
  },
  {
    "path": "VPS_Module/detectron2/layers/wrappers.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\"\"\"\nWrappers around on some nn functions, mainly to support empty tensors.\n\nIdeally, add support directly in PyTorch to empty tensors in those functions.\n\nThese can be removed once https://github.com/pytorch/pytorch/issues/12013\nis implemented\n\"\"\"\n\nfrom typing import List, Optional\nimport torch\nfrom torch.nn import functional as F\n\n\ndef shapes_to_tensor(x: List[int], device: Optional[torch.device] = None) -> torch.Tensor:\n    \"\"\"\n    Turn a list of integer scalars or integer Tensor scalars into a vector,\n    in a way that's both traceable and scriptable.\n\n    In tracing, `x` should be a list of scalar Tensor, so the output can trace to the inputs.\n    In scripting or eager, `x` should be a list of int.\n    \"\"\"\n    if torch.jit.is_scripting():\n        return torch.as_tensor(x, device=device)\n    if torch.jit.is_tracing():\n        assert all(\n            [isinstance(t, torch.Tensor) for t in x]\n        ), \"Shape should be tensor during tracing!\"\n        # as_tensor should not be used in tracing because it records a constant\n        ret = torch.stack(x)\n        if ret.device != device:  # avoid recording a hard-coded device if not necessary\n            ret = ret.to(device=device)\n        return ret\n    return torch.as_tensor(x, device=device)\n\n\ndef cat(tensors: List[torch.Tensor], dim: int = 0):\n    \"\"\"\n    Efficient version of torch.cat that avoids a copy if there is only a single element in a list\n    \"\"\"\n    assert isinstance(tensors, (list, tuple))\n    if len(tensors) == 1:\n        return tensors[0]\n    return torch.cat(tensors, dim)\n\n\ndef cross_entropy(input, target, *, reduction=\"mean\", **kwargs):\n    \"\"\"\n    Same as `torch.nn.functional.cross_entropy`, but returns 0 (instead of nan)\n    for empty inputs.\n    \"\"\"\n    if target.numel() == 0 and reduction == \"mean\":\n        return input.sum() * 0.0  # connect the gradient\n    return F.cross_entropy(input, target, reduction=reduction, **kwargs)\n\n\nclass _NewEmptyTensorOp(torch.autograd.Function):\n    @staticmethod\n    def forward(ctx, x, new_shape):\n        ctx.shape = x.shape\n        return x.new_empty(new_shape)\n\n    @staticmethod\n    def backward(ctx, grad):\n        shape = ctx.shape\n        return _NewEmptyTensorOp.apply(grad, shape), None\n\n\nclass Conv2d(torch.nn.Conv2d):\n    \"\"\"\n    A wrapper around :class:`torch.nn.Conv2d` to support empty inputs and more features.\n    \"\"\"\n\n    def __init__(self, *args, **kwargs):\n        \"\"\"\n        Extra keyword arguments supported in addition to those in `torch.nn.Conv2d`:\n\n        Args:\n            norm (nn.Module, optional): a normalization layer\n            activation (callable(Tensor) -> Tensor): a callable activation function\n\n        It assumes that norm layer is used before activation.\n        \"\"\"\n        norm = kwargs.pop(\"norm\", None)\n        activation = kwargs.pop(\"activation\", None)\n        super().__init__(*args, **kwargs)\n\n        self.norm = norm\n        self.activation = activation\n\n    def forward(self, x):\n        # torchscript does not support SyncBatchNorm yet\n        # https://github.com/pytorch/pytorch/issues/40507\n        # and we skip these codes in torchscript since:\n        # 1. currently we only support torchscript in evaluation mode\n        # 2. features needed by exporting module to torchscript are added in PyTorch 1.6 or\n        # later version, `Conv2d` in these PyTorch versions has already supported empty inputs.\n        if not torch.jit.is_scripting():\n            if x.numel() == 0 and self.training:\n                # https://github.com/pytorch/pytorch/issues/12013\n                assert not isinstance(\n                    self.norm, torch.nn.SyncBatchNorm\n                ), \"SyncBatchNorm does not support empty inputs!\"\n\n        x = F.conv2d(\n            x, self.weight, self.bias, self.stride, self.padding, self.dilation, self.groups\n        )\n        if self.norm is not None:\n            x = self.norm(x)\n        if self.activation is not None:\n            x = self.activation(x)\n        return x\n\n\nConvTranspose2d = torch.nn.ConvTranspose2d\nBatchNorm2d = torch.nn.BatchNorm2d\ninterpolate = F.interpolate\nLinear = torch.nn.Linear\n\n\ndef nonzero_tuple(x):\n    \"\"\"\n    A 'as_tuple=True' version of torch.nonzero to support torchscript.\n    because of https://github.com/pytorch/pytorch/issues/38718\n    \"\"\"\n    if torch.jit.is_scripting():\n        if x.dim() == 0:\n            return x.unsqueeze(0).nonzero().unbind(1)\n        return x.nonzero().unbind(1)\n    else:\n        return x.nonzero(as_tuple=True)\n"
  },
  {
    "path": "VPS_Module/detectron2/model_zoo/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\"\"\"\nModel Zoo API for Detectron2: a collection of functions to create common model architectures\nlisted in `MODEL_ZOO.md <https://github.com/facebookresearch/detectron2/blob/main/MODEL_ZOO.md>`_,\nand optionally load their pre-trained weights.\n\"\"\"\n\nfrom .model_zoo import get, get_config_file, get_checkpoint_url, get_config\n\n__all__ = [\"get_checkpoint_url\", \"get\", \"get_config_file\", \"get_config\"]\n"
  },
  {
    "path": "VPS_Module/detectron2/model_zoo/configs",
    "content": "/mnt/nas_8/group/lanxinyue/work/project_pvo/detectron2/configs"
  },
  {
    "path": "VPS_Module/detectron2/model_zoo/model_zoo.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport os\nfrom typing import Optional\nimport pkg_resources\nimport torch\n\nfrom detectron2.checkpoint import DetectionCheckpointer\nfrom detectron2.config import CfgNode, LazyConfig, get_cfg, instantiate\nfrom detectron2.modeling import build_model\n\n\nclass _ModelZooUrls(object):\n    \"\"\"\n    Mapping from names to officially released Detectron2 pre-trained models.\n    \"\"\"\n\n    S3_PREFIX = \"https://dl.fbaipublicfiles.com/detectron2/\"\n\n    # format: {config_path.yaml} -> model_id/model_final_{commit}.pkl\n    CONFIG_PATH_TO_URL_SUFFIX = {\n        # COCO Detection with Faster R-CNN\n        \"COCO-Detection/faster_rcnn_R_50_C4_1x\": \"137257644/model_final_721ade.pkl\",\n        \"COCO-Detection/faster_rcnn_R_50_DC5_1x\": \"137847829/model_final_51d356.pkl\",\n        \"COCO-Detection/faster_rcnn_R_50_FPN_1x\": \"137257794/model_final_b275ba.pkl\",\n        \"COCO-Detection/faster_rcnn_R_50_C4_3x\": \"137849393/model_final_f97cb7.pkl\",\n        \"COCO-Detection/faster_rcnn_R_50_DC5_3x\": \"137849425/model_final_68d202.pkl\",\n        \"COCO-Detection/faster_rcnn_R_50_FPN_3x\": \"137849458/model_final_280758.pkl\",\n        \"COCO-Detection/faster_rcnn_R_101_C4_3x\": \"138204752/model_final_298dad.pkl\",\n        \"COCO-Detection/faster_rcnn_R_101_DC5_3x\": \"138204841/model_final_3e0943.pkl\",\n        \"COCO-Detection/faster_rcnn_R_101_FPN_3x\": \"137851257/model_final_f6e8b1.pkl\",\n        \"COCO-Detection/faster_rcnn_X_101_32x8d_FPN_3x\": \"139173657/model_final_68b088.pkl\",\n        # COCO Detection with RetinaNet\n        \"COCO-Detection/retinanet_R_50_FPN_1x\": \"190397773/model_final_bfca0b.pkl\",\n        \"COCO-Detection/retinanet_R_50_FPN_3x\": \"190397829/model_final_5bd44e.pkl\",\n        \"COCO-Detection/retinanet_R_101_FPN_3x\": \"190397697/model_final_971ab9.pkl\",\n        # COCO Detection with RPN and Fast R-CNN\n        \"COCO-Detection/rpn_R_50_C4_1x\": \"137258005/model_final_450694.pkl\",\n        \"COCO-Detection/rpn_R_50_FPN_1x\": \"137258492/model_final_02ce48.pkl\",\n        \"COCO-Detection/fast_rcnn_R_50_FPN_1x\": \"137635226/model_final_e5f7ce.pkl\",\n        # COCO Instance Segmentation Baselines with Mask R-CNN\n        \"COCO-InstanceSegmentation/mask_rcnn_R_50_C4_1x\": \"137259246/model_final_9243eb.pkl\",\n        \"COCO-InstanceSegmentation/mask_rcnn_R_50_DC5_1x\": \"137260150/model_final_4f86c3.pkl\",\n        \"COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_1x\": \"137260431/model_final_a54504.pkl\",\n        \"COCO-InstanceSegmentation/mask_rcnn_R_50_C4_3x\": \"137849525/model_final_4ce675.pkl\",\n        \"COCO-InstanceSegmentation/mask_rcnn_R_50_DC5_3x\": \"137849551/model_final_84107b.pkl\",\n        \"COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_3x\": \"137849600/model_final_f10217.pkl\",\n        \"COCO-InstanceSegmentation/mask_rcnn_R_101_C4_3x\": \"138363239/model_final_a2914c.pkl\",\n        \"COCO-InstanceSegmentation/mask_rcnn_R_101_DC5_3x\": \"138363294/model_final_0464b7.pkl\",\n        \"COCO-InstanceSegmentation/mask_rcnn_R_101_FPN_3x\": \"138205316/model_final_a3ec72.pkl\",\n        \"COCO-InstanceSegmentation/mask_rcnn_X_101_32x8d_FPN_3x\": \"139653917/model_final_2d9806.pkl\",  # noqa\n        # New baselines using Large-Scale Jitter and Longer Training Schedule\n        \"new_baselines/mask_rcnn_R_50_FPN_100ep_LSJ\": \"42047764/model_final_bb69de.pkl\",\n        \"new_baselines/mask_rcnn_R_50_FPN_200ep_LSJ\": \"42047638/model_final_89a8d3.pkl\",\n        \"new_baselines/mask_rcnn_R_50_FPN_400ep_LSJ\": \"42019571/model_final_14d201.pkl\",\n        \"new_baselines/mask_rcnn_R_101_FPN_100ep_LSJ\": \"42025812/model_final_4f7b58.pkl\",\n        \"new_baselines/mask_rcnn_R_101_FPN_200ep_LSJ\": \"42131867/model_final_0bb7ae.pkl\",\n        \"new_baselines/mask_rcnn_R_101_FPN_400ep_LSJ\": \"42073830/model_final_f96b26.pkl\",\n        \"new_baselines/mask_rcnn_regnetx_4gf_dds_FPN_100ep_LSJ\": \"42047771/model_final_b7fbab.pkl\",  # noqa\n        \"new_baselines/mask_rcnn_regnetx_4gf_dds_FPN_200ep_LSJ\": \"42132721/model_final_5d87c1.pkl\",  # noqa\n        \"new_baselines/mask_rcnn_regnetx_4gf_dds_FPN_400ep_LSJ\": \"42025447/model_final_f1362d.pkl\",  # noqa\n        \"new_baselines/mask_rcnn_regnety_4gf_dds_FPN_100ep_LSJ\": \"42047784/model_final_6ba57e.pkl\",  # noqa\n        \"new_baselines/mask_rcnn_regnety_4gf_dds_FPN_200ep_LSJ\": \"42047642/model_final_27b9c1.pkl\",  # noqa\n        \"new_baselines/mask_rcnn_regnety_4gf_dds_FPN_400ep_LSJ\": \"42045954/model_final_ef3a80.pkl\",  # noqa\n        # COCO Person Keypoint Detection Baselines with Keypoint R-CNN\n        \"COCO-Keypoints/keypoint_rcnn_R_50_FPN_1x\": \"137261548/model_final_04e291.pkl\",\n        \"COCO-Keypoints/keypoint_rcnn_R_50_FPN_3x\": \"137849621/model_final_a6e10b.pkl\",\n        \"COCO-Keypoints/keypoint_rcnn_R_101_FPN_3x\": \"138363331/model_final_997cc7.pkl\",\n        \"COCO-Keypoints/keypoint_rcnn_X_101_32x8d_FPN_3x\": \"139686956/model_final_5ad38f.pkl\",\n        # COCO Panoptic Segmentation Baselines with Panoptic FPN\n        \"COCO-PanopticSegmentation/panoptic_fpn_R_50_1x\": \"139514544/model_final_dbfeb4.pkl\",\n        \"COCO-PanopticSegmentation/panoptic_fpn_R_50_3x\": \"139514569/model_final_c10459.pkl\",\n        \"COCO-PanopticSegmentation/panoptic_fpn_R_101_3x\": \"139514519/model_final_cafdb1.pkl\",\n        # LVIS Instance Segmentation Baselines with Mask R-CNN\n        \"LVISv0.5-InstanceSegmentation/mask_rcnn_R_50_FPN_1x\": \"144219072/model_final_571f7c.pkl\",  # noqa\n        \"LVISv0.5-InstanceSegmentation/mask_rcnn_R_101_FPN_1x\": \"144219035/model_final_824ab5.pkl\",  # noqa\n        \"LVISv0.5-InstanceSegmentation/mask_rcnn_X_101_32x8d_FPN_1x\": \"144219108/model_final_5e3439.pkl\",  # noqa\n        # Cityscapes & Pascal VOC Baselines\n        \"Cityscapes/mask_rcnn_R_50_FPN\": \"142423278/model_final_af9cf5.pkl\",\n        \"PascalVOC-Detection/faster_rcnn_R_50_C4\": \"142202221/model_final_b1acc2.pkl\",\n        # Other Settings\n        \"Misc/mask_rcnn_R_50_FPN_1x_dconv_c3-c5\": \"138602867/model_final_65c703.pkl\",\n        \"Misc/mask_rcnn_R_50_FPN_3x_dconv_c3-c5\": \"144998336/model_final_821d0b.pkl\",\n        \"Misc/cascade_mask_rcnn_R_50_FPN_1x\": \"138602847/model_final_e9d89b.pkl\",\n        \"Misc/cascade_mask_rcnn_R_50_FPN_3x\": \"144998488/model_final_480dd8.pkl\",\n        \"Misc/mask_rcnn_R_50_FPN_3x_syncbn\": \"169527823/model_final_3b3c51.pkl\",\n        \"Misc/mask_rcnn_R_50_FPN_3x_gn\": \"138602888/model_final_dc5d9e.pkl\",\n        \"Misc/scratch_mask_rcnn_R_50_FPN_3x_gn\": \"138602908/model_final_01ca85.pkl\",\n        \"Misc/scratch_mask_rcnn_R_50_FPN_9x_gn\": \"183808979/model_final_da7b4c.pkl\",\n        \"Misc/scratch_mask_rcnn_R_50_FPN_9x_syncbn\": \"184226666/model_final_5ce33e.pkl\",\n        \"Misc/panoptic_fpn_R_101_dconv_cascade_gn_3x\": \"139797668/model_final_be35db.pkl\",\n        \"Misc/cascade_mask_rcnn_X_152_32x8d_FPN_IN5k_gn_dconv\": \"18131413/model_0039999_e76410.pkl\",  # noqa\n        # D1 Comparisons\n        \"Detectron1-Comparisons/faster_rcnn_R_50_FPN_noaug_1x\": \"137781054/model_final_7ab50c.pkl\",  # noqa\n        \"Detectron1-Comparisons/mask_rcnn_R_50_FPN_noaug_1x\": \"137781281/model_final_62ca52.pkl\",  # noqa\n        \"Detectron1-Comparisons/keypoint_rcnn_R_50_FPN_1x\": \"137781195/model_final_cce136.pkl\",\n    }\n\n    @staticmethod\n    def query(config_path: str) -> Optional[str]:\n        \"\"\"\n        Args:\n            config_path: relative config filename\n        \"\"\"\n        name = config_path.replace(\".yaml\", \"\").replace(\".py\", \"\")\n        if name in _ModelZooUrls.CONFIG_PATH_TO_URL_SUFFIX:\n            suffix = _ModelZooUrls.CONFIG_PATH_TO_URL_SUFFIX[name]\n            return _ModelZooUrls.S3_PREFIX + name + \"/\" + suffix\n        return None\n\n\ndef get_checkpoint_url(config_path):\n    \"\"\"\n    Returns the URL to the model trained using the given config\n\n    Args:\n        config_path (str): config file name relative to detectron2's \"configs/\"\n            directory, e.g., \"COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_1x.yaml\"\n\n    Returns:\n        str: a URL to the model\n    \"\"\"\n    url = _ModelZooUrls.query(config_path)\n    if url is None:\n        raise RuntimeError(\"Pretrained model for {} is not available!\".format(config_path))\n    return url\n\n\ndef get_config_file(config_path):\n    \"\"\"\n    Returns path to a builtin config file.\n\n    Args:\n        config_path (str): config file name relative to detectron2's \"configs/\"\n            directory, e.g., \"COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_1x.yaml\"\n\n    Returns:\n        str: the real path to the config file.\n    \"\"\"\n    cfg_file = pkg_resources.resource_filename(\n        \"detectron2.model_zoo\", os.path.join(\"configs\", config_path)\n    )\n    if not os.path.exists(cfg_file):\n        raise RuntimeError(\"{} not available in Model Zoo!\".format(config_path))\n    return cfg_file\n\n\ndef get_config(config_path, trained: bool = False):\n    \"\"\"\n    Returns a config object for a model in model zoo.\n\n    Args:\n        config_path (str): config file name relative to detectron2's \"configs/\"\n            directory, e.g., \"COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_1x.yaml\"\n        trained (bool): If True, will set ``MODEL.WEIGHTS`` to trained model zoo weights.\n            If False, the checkpoint specified in the config file's ``MODEL.WEIGHTS`` is used\n            instead; this will typically (though not always) initialize a subset of weights using\n            an ImageNet pre-trained model, while randomly initializing the other weights.\n\n    Returns:\n        CfgNode or omegaconf.DictConfig: a config object\n    \"\"\"\n    cfg_file = get_config_file(config_path)\n    if cfg_file.endswith(\".yaml\"):\n        cfg = get_cfg()\n        cfg.merge_from_file(cfg_file)\n        if trained:\n            cfg.MODEL.WEIGHTS = get_checkpoint_url(config_path)\n        return cfg\n    elif cfg_file.endswith(\".py\"):\n        cfg = LazyConfig.load(cfg_file)\n        if trained:\n            url = get_checkpoint_url(config_path)\n            if \"train\" in cfg and \"init_checkpoint\" in cfg.train:\n                cfg.train.init_checkpoint = url\n            else:\n                raise NotImplementedError\n        return cfg\n\n\ndef get(config_path, trained: bool = False, device: Optional[str] = None):\n    \"\"\"\n    Get a model specified by relative path under Detectron2's official ``configs/`` directory.\n\n    Args:\n        config_path (str): config file name relative to detectron2's \"configs/\"\n            directory, e.g., \"COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_1x.yaml\"\n        trained (bool): see :func:`get_config`.\n        device (str or None): overwrite the device in config, if given.\n\n    Returns:\n        nn.Module: a detectron2 model. Will be in training mode.\n\n    Example:\n    ::\n        from detectron2 import model_zoo\n        model = model_zoo.get(\"COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_1x.yaml\", trained=True)\n    \"\"\"\n    cfg = get_config(config_path, trained)\n    if device is None and not torch.cuda.is_available():\n        device = \"cpu\"\n    if device is not None and isinstance(cfg, CfgNode):\n        cfg.MODEL.DEVICE = device\n\n    if isinstance(cfg, CfgNode):\n        model = build_model(cfg)\n        DetectionCheckpointer(model).load(cfg.MODEL.WEIGHTS)\n    else:\n        model = instantiate(cfg.model)\n        if device is not None:\n            model = model.to(device)\n        if \"train\" in cfg and \"init_checkpoint\" in cfg.train:\n            DetectionCheckpointer(model).load(cfg.train.init_checkpoint)\n    return model\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom detectron2.layers import ShapeSpec\n\nfrom .anchor_generator import build_anchor_generator, ANCHOR_GENERATOR_REGISTRY\nfrom .backbone import (\n    BACKBONE_REGISTRY,\n    FPN,\n    Backbone,\n    ResNet,\n    ResNetBlockBase,\n    build_backbone,\n    build_resnet_backbone,\n    make_stage,\n)\nfrom .meta_arch import (\n    META_ARCH_REGISTRY,\n    SEM_SEG_HEADS_REGISTRY,\n    GeneralizedRCNN,\n    PanopticFPN,\n    ProposalNetwork,\n    RetinaNet,\n    SemanticSegmentor,\n    build_model,\n    build_sem_seg_head,\n    FCOS,\n)\nfrom .postprocessing import detector_postprocess\nfrom .proposal_generator import (\n    PROPOSAL_GENERATOR_REGISTRY,\n    build_proposal_generator,\n    RPN_HEAD_REGISTRY,\n    build_rpn_head,\n)\nfrom .roi_heads import (\n    ROI_BOX_HEAD_REGISTRY,\n    ROI_HEADS_REGISTRY,\n    ROI_KEYPOINT_HEAD_REGISTRY,\n    ROI_MASK_HEAD_REGISTRY,\n    ROIHeads,\n    StandardROIHeads,\n    BaseMaskRCNNHead,\n    BaseKeypointRCNNHead,\n    FastRCNNOutputLayers,\n    build_box_head,\n    build_keypoint_head,\n    build_mask_head,\n    build_roi_heads,\n)\nfrom .test_time_augmentation import DatasetMapperTTA, GeneralizedRCNNWithTTA\nfrom .mmdet_wrapper import MMDetBackbone, MMDetDetector\n\n_EXCLUDE = {\"ShapeSpec\"}\n__all__ = [k for k in globals().keys() if k not in _EXCLUDE and not k.startswith(\"_\")]\n\n\nfrom detectron2.utils.env import fixup_module_metadata\n\nfixup_module_metadata(__name__, globals(), __all__)\ndel fixup_module_metadata\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/anchor_generator.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport collections\nimport math\nfrom typing import List\nimport torch\nfrom torch import nn\n\nfrom detectron2.config import configurable\nfrom detectron2.layers import ShapeSpec\nfrom detectron2.structures import Boxes, RotatedBoxes\nfrom detectron2.utils.registry import Registry\n\nANCHOR_GENERATOR_REGISTRY = Registry(\"ANCHOR_GENERATOR\")\nANCHOR_GENERATOR_REGISTRY.__doc__ = \"\"\"\nRegistry for modules that creates object detection anchors for feature maps.\n\nThe registered object will be called with `obj(cfg, input_shape)`.\n\"\"\"\n\n\nclass BufferList(nn.Module):\n    \"\"\"\n    Similar to nn.ParameterList, but for buffers\n    \"\"\"\n\n    def __init__(self, buffers):\n        super().__init__()\n        for i, buffer in enumerate(buffers):\n            # Use non-persistent buffer so the values are not saved in checkpoint\n            self.register_buffer(str(i), buffer, persistent=False)\n\n    def __len__(self):\n        return len(self._buffers)\n\n    def __iter__(self):\n        return iter(self._buffers.values())\n\n\ndef _create_grid_offsets(size: List[int], stride: int, offset: float, device: torch.device):\n    grid_height, grid_width = size\n    shifts_x = torch.arange(\n        offset * stride, grid_width * stride, step=stride, dtype=torch.float32, device=device\n    )\n    shifts_y = torch.arange(\n        offset * stride, grid_height * stride, step=stride, dtype=torch.float32, device=device\n    )\n\n    shift_y, shift_x = torch.meshgrid(shifts_y, shifts_x)\n    shift_x = shift_x.reshape(-1)\n    shift_y = shift_y.reshape(-1)\n    return shift_x, shift_y\n\n\ndef _broadcast_params(params, num_features, name):\n    \"\"\"\n    If one size (or aspect ratio) is specified and there are multiple feature\n    maps, we \"broadcast\" anchors of that single size (or aspect ratio)\n    over all feature maps.\n\n    If params is list[float], or list[list[float]] with len(params) == 1, repeat\n    it num_features time.\n\n    Returns:\n        list[list[float]]: param for each feature\n    \"\"\"\n    assert isinstance(\n        params, collections.abc.Sequence\n    ), f\"{name} in anchor generator has to be a list! Got {params}.\"\n    assert len(params), f\"{name} in anchor generator cannot be empty!\"\n    if not isinstance(params[0], collections.abc.Sequence):  # params is list[float]\n        return [params] * num_features\n    if len(params) == 1:\n        return list(params) * num_features\n    assert len(params) == num_features, (\n        f\"Got {name} of length {len(params)} in anchor generator, \"\n        f\"but the number of input features is {num_features}!\"\n    )\n    return params\n\n\n@ANCHOR_GENERATOR_REGISTRY.register()\nclass DefaultAnchorGenerator(nn.Module):\n    \"\"\"\n    Compute anchors in the standard ways described in\n    \"Faster R-CNN: Towards Real-Time Object Detection with Region Proposal Networks\".\n    \"\"\"\n\n    box_dim: torch.jit.Final[int] = 4\n    \"\"\"\n    the dimension of each anchor box.\n    \"\"\"\n\n    @configurable\n    def __init__(self, *, sizes, aspect_ratios, strides, offset=0.5):\n        \"\"\"\n        This interface is experimental.\n\n        Args:\n            sizes (list[list[float]] or list[float]):\n                If ``sizes`` is list[list[float]], ``sizes[i]`` is the list of anchor sizes\n                (i.e. sqrt of anchor area) to use for the i-th feature map.\n                If ``sizes`` is list[float], ``sizes`` is used for all feature maps.\n                Anchor sizes are given in absolute lengths in units of\n                the input image; they do not dynamically scale if the input image size changes.\n            aspect_ratios (list[list[float]] or list[float]): list of aspect ratios\n                (i.e. height / width) to use for anchors. Same \"broadcast\" rule for `sizes` applies.\n            strides (list[int]): stride of each input feature.\n            offset (float): Relative offset between the center of the first anchor and the top-left\n                corner of the image. Value has to be in [0, 1).\n                Recommend to use 0.5, which means half stride.\n        \"\"\"\n        super().__init__()\n\n        self.strides = strides\n        self.num_features = len(self.strides)\n        sizes = _broadcast_params(sizes, self.num_features, \"sizes\")\n        aspect_ratios = _broadcast_params(aspect_ratios, self.num_features, \"aspect_ratios\")\n        self.cell_anchors = self._calculate_anchors(sizes, aspect_ratios)\n\n        self.offset = offset\n        assert 0.0 <= self.offset < 1.0, self.offset\n\n    @classmethod\n    def from_config(cls, cfg, input_shape: List[ShapeSpec]):\n        return {\n            \"sizes\": cfg.MODEL.ANCHOR_GENERATOR.SIZES,\n            \"aspect_ratios\": cfg.MODEL.ANCHOR_GENERATOR.ASPECT_RATIOS,\n            \"strides\": [x.stride for x in input_shape],\n            \"offset\": cfg.MODEL.ANCHOR_GENERATOR.OFFSET,\n        }\n\n    def _calculate_anchors(self, sizes, aspect_ratios):\n        cell_anchors = [\n            self.generate_cell_anchors(s, a).float() for s, a in zip(sizes, aspect_ratios)\n        ]\n        return BufferList(cell_anchors)\n\n    @property\n    @torch.jit.unused\n    def num_cell_anchors(self):\n        \"\"\"\n        Alias of `num_anchors`.\n        \"\"\"\n        return self.num_anchors\n\n    @property\n    @torch.jit.unused\n    def num_anchors(self):\n        \"\"\"\n        Returns:\n            list[int]: Each int is the number of anchors at every pixel\n                location, on that feature map.\n                For example, if at every pixel we use anchors of 3 aspect\n                ratios and 5 sizes, the number of anchors is 15.\n                (See also ANCHOR_GENERATOR.SIZES and ANCHOR_GENERATOR.ASPECT_RATIOS in config)\n\n                In standard RPN models, `num_anchors` on every feature map is the same.\n        \"\"\"\n        return [len(cell_anchors) for cell_anchors in self.cell_anchors]\n\n    def _grid_anchors(self, grid_sizes: List[List[int]]):\n        \"\"\"\n        Returns:\n            list[Tensor]: #featuremap tensors, each is (#locations x #cell_anchors) x 4\n        \"\"\"\n        anchors = []\n        # buffers() not supported by torchscript. use named_buffers() instead\n        buffers: List[torch.Tensor] = [x[1] for x in self.cell_anchors.named_buffers()]\n        for size, stride, base_anchors in zip(grid_sizes, self.strides, buffers):\n            shift_x, shift_y = _create_grid_offsets(size, stride, self.offset, base_anchors.device)\n            shifts = torch.stack((shift_x, shift_y, shift_x, shift_y), dim=1)\n\n            anchors.append((shifts.view(-1, 1, 4) + base_anchors.view(1, -1, 4)).reshape(-1, 4))\n\n        return anchors\n\n    def generate_cell_anchors(self, sizes=(32, 64, 128, 256, 512), aspect_ratios=(0.5, 1, 2)):\n        \"\"\"\n        Generate a tensor storing canonical anchor boxes, which are all anchor\n        boxes of different sizes and aspect_ratios centered at (0, 0).\n        We can later build the set of anchors for a full feature map by\n        shifting and tiling these tensors (see `meth:_grid_anchors`).\n\n        Args:\n            sizes (tuple[float]):\n            aspect_ratios (tuple[float]]):\n\n        Returns:\n            Tensor of shape (len(sizes) * len(aspect_ratios), 4) storing anchor boxes\n                in XYXY format.\n        \"\"\"\n\n        # This is different from the anchor generator defined in the original Faster R-CNN\n        # code or Detectron. They yield the same AP, however the old version defines cell\n        # anchors in a less natural way with a shift relative to the feature grid and\n        # quantization that results in slightly different sizes for different aspect ratios.\n        # See also https://github.com/facebookresearch/Detectron/issues/227\n\n        anchors = []\n        for size in sizes:\n            area = size ** 2.0\n            for aspect_ratio in aspect_ratios:\n                # s * s = w * h\n                # a = h / w\n                # ... some algebra ...\n                # w = sqrt(s * s / a)\n                # h = a * w\n                w = math.sqrt(area / aspect_ratio)\n                h = aspect_ratio * w\n                x0, y0, x1, y1 = -w / 2.0, -h / 2.0, w / 2.0, h / 2.0\n                anchors.append([x0, y0, x1, y1])\n        return torch.tensor(anchors)\n\n    def forward(self, features: List[torch.Tensor]):\n        \"\"\"\n        Args:\n            features (list[Tensor]): list of backbone feature maps on which to generate anchors.\n\n        Returns:\n            list[Boxes]: a list of Boxes containing all the anchors for each feature map\n                (i.e. the cell anchors repeated over all locations in the feature map).\n                The number of anchors of each feature map is Hi x Wi x num_cell_anchors,\n                where Hi, Wi are resolution of the feature map divided by anchor stride.\n        \"\"\"\n        grid_sizes = [feature_map.shape[-2:] for feature_map in features]\n        anchors_over_all_feature_maps = self._grid_anchors(grid_sizes)\n        return [Boxes(x) for x in anchors_over_all_feature_maps]\n\n\n@ANCHOR_GENERATOR_REGISTRY.register()\nclass RotatedAnchorGenerator(nn.Module):\n    \"\"\"\n    Compute rotated anchors used by Rotated RPN (RRPN), described in\n    \"Arbitrary-Oriented Scene Text Detection via Rotation Proposals\".\n    \"\"\"\n\n    box_dim: int = 5\n    \"\"\"\n    the dimension of each anchor box.\n    \"\"\"\n\n    @configurable\n    def __init__(self, *, sizes, aspect_ratios, strides, angles, offset=0.5):\n        \"\"\"\n        This interface is experimental.\n\n        Args:\n            sizes (list[list[float]] or list[float]):\n                If sizes is list[list[float]], sizes[i] is the list of anchor sizes\n                (i.e. sqrt of anchor area) to use for the i-th feature map.\n                If sizes is list[float], the sizes are used for all feature maps.\n                Anchor sizes are given in absolute lengths in units of\n                the input image; they do not dynamically scale if the input image size changes.\n            aspect_ratios (list[list[float]] or list[float]): list of aspect ratios\n                (i.e. height / width) to use for anchors. Same \"broadcast\" rule for `sizes` applies.\n            strides (list[int]): stride of each input feature.\n            angles (list[list[float]] or list[float]): list of angles (in degrees CCW)\n                to use for anchors. Same \"broadcast\" rule for `sizes` applies.\n            offset (float): Relative offset between the center of the first anchor and the top-left\n                corner of the image. Value has to be in [0, 1).\n                Recommend to use 0.5, which means half stride.\n        \"\"\"\n        super().__init__()\n\n        self.strides = strides\n        self.num_features = len(self.strides)\n        sizes = _broadcast_params(sizes, self.num_features, \"sizes\")\n        aspect_ratios = _broadcast_params(aspect_ratios, self.num_features, \"aspect_ratios\")\n        angles = _broadcast_params(angles, self.num_features, \"angles\")\n        self.cell_anchors = self._calculate_anchors(sizes, aspect_ratios, angles)\n\n        self.offset = offset\n        assert 0.0 <= self.offset < 1.0, self.offset\n\n    @classmethod\n    def from_config(cls, cfg, input_shape: List[ShapeSpec]):\n        return {\n            \"sizes\": cfg.MODEL.ANCHOR_GENERATOR.SIZES,\n            \"aspect_ratios\": cfg.MODEL.ANCHOR_GENERATOR.ASPECT_RATIOS,\n            \"strides\": [x.stride for x in input_shape],\n            \"offset\": cfg.MODEL.ANCHOR_GENERATOR.OFFSET,\n            \"angles\": cfg.MODEL.ANCHOR_GENERATOR.ANGLES,\n        }\n\n    def _calculate_anchors(self, sizes, aspect_ratios, angles):\n        cell_anchors = [\n            self.generate_cell_anchors(size, aspect_ratio, angle).float()\n            for size, aspect_ratio, angle in zip(sizes, aspect_ratios, angles)\n        ]\n        return BufferList(cell_anchors)\n\n    @property\n    def num_cell_anchors(self):\n        \"\"\"\n        Alias of `num_anchors`.\n        \"\"\"\n        return self.num_anchors\n\n    @property\n    def num_anchors(self):\n        \"\"\"\n        Returns:\n            list[int]: Each int is the number of anchors at every pixel\n                location, on that feature map.\n                For example, if at every pixel we use anchors of 3 aspect\n                ratios, 2 sizes and 5 angles, the number of anchors is 30.\n                (See also ANCHOR_GENERATOR.SIZES, ANCHOR_GENERATOR.ASPECT_RATIOS\n                and ANCHOR_GENERATOR.ANGLES in config)\n\n                In standard RRPN models, `num_anchors` on every feature map is the same.\n        \"\"\"\n        return [len(cell_anchors) for cell_anchors in self.cell_anchors]\n\n    def _grid_anchors(self, grid_sizes):\n        anchors = []\n        for size, stride, base_anchors in zip(grid_sizes, self.strides, self.cell_anchors):\n            shift_x, shift_y = _create_grid_offsets(size, stride, self.offset, base_anchors.device)\n            zeros = torch.zeros_like(shift_x)\n            shifts = torch.stack((shift_x, shift_y, zeros, zeros, zeros), dim=1)\n\n            anchors.append((shifts.view(-1, 1, 5) + base_anchors.view(1, -1, 5)).reshape(-1, 5))\n\n        return anchors\n\n    def generate_cell_anchors(\n        self,\n        sizes=(32, 64, 128, 256, 512),\n        aspect_ratios=(0.5, 1, 2),\n        angles=(-90, -60, -30, 0, 30, 60, 90),\n    ):\n        \"\"\"\n        Generate a tensor storing canonical anchor boxes, which are all anchor\n        boxes of different sizes, aspect_ratios, angles centered at (0, 0).\n        We can later build the set of anchors for a full feature map by\n        shifting and tiling these tensors (see `meth:_grid_anchors`).\n\n        Args:\n            sizes (tuple[float]):\n            aspect_ratios (tuple[float]]):\n            angles (tuple[float]]):\n\n        Returns:\n            Tensor of shape (len(sizes) * len(aspect_ratios) * len(angles), 5)\n                storing anchor boxes in (x_ctr, y_ctr, w, h, angle) format.\n        \"\"\"\n        anchors = []\n        for size in sizes:\n            area = size ** 2.0\n            for aspect_ratio in aspect_ratios:\n                # s * s = w * h\n                # a = h / w\n                # ... some algebra ...\n                # w = sqrt(s * s / a)\n                # h = a * w\n                w = math.sqrt(area / aspect_ratio)\n                h = aspect_ratio * w\n                anchors.extend([0, 0, w, h, a] for a in angles)\n\n        return torch.tensor(anchors)\n\n    def forward(self, features):\n        \"\"\"\n        Args:\n            features (list[Tensor]): list of backbone feature maps on which to generate anchors.\n\n        Returns:\n            list[RotatedBoxes]: a list of Boxes containing all the anchors for each feature map\n                (i.e. the cell anchors repeated over all locations in the feature map).\n                The number of anchors of each feature map is Hi x Wi x num_cell_anchors,\n                where Hi, Wi are resolution of the feature map divided by anchor stride.\n        \"\"\"\n        grid_sizes = [feature_map.shape[-2:] for feature_map in features]\n        anchors_over_all_feature_maps = self._grid_anchors(grid_sizes)\n        return [RotatedBoxes(x) for x in anchors_over_all_feature_maps]\n\n\ndef build_anchor_generator(cfg, input_shape):\n    \"\"\"\n    Built an anchor generator from `cfg.MODEL.ANCHOR_GENERATOR.NAME`.\n    \"\"\"\n    anchor_generator = cfg.MODEL.ANCHOR_GENERATOR.NAME\n    return ANCHOR_GENERATOR_REGISTRY.get(anchor_generator)(cfg, input_shape)\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/backbone/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom .build import build_backbone, BACKBONE_REGISTRY  # noqa F401 isort:skip\n\nfrom .backbone import Backbone\nfrom .fpn import FPN\nfrom .regnet import RegNet\nfrom .resnet import (\n    BasicStem,\n    ResNet,\n    ResNetBlockBase,\n    build_resnet_backbone,\n    make_stage,\n    BottleneckBlock,\n)\n\n__all__ = [k for k in globals().keys() if not k.startswith(\"_\")]\n# TODO can expose more resnet blocks after careful consideration\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/backbone/backbone.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom abc import ABCMeta, abstractmethod\nimport torch.nn as nn\n\nfrom detectron2.layers import ShapeSpec\n\n__all__ = [\"Backbone\"]\n\n\nclass Backbone(nn.Module, metaclass=ABCMeta):\n    \"\"\"\n    Abstract base class for network backbones.\n    \"\"\"\n\n    def __init__(self):\n        \"\"\"\n        The `__init__` method of any subclass can specify its own set of arguments.\n        \"\"\"\n        super().__init__()\n\n    @abstractmethod\n    def forward(self):\n        \"\"\"\n        Subclasses must override this method, but adhere to the same return type.\n\n        Returns:\n            dict[str->Tensor]: mapping from feature name (e.g., \"res2\") to tensor\n        \"\"\"\n        pass\n\n    @property\n    def size_divisibility(self) -> int:\n        \"\"\"\n        Some backbones require the input height and width to be divisible by a\n        specific integer. This is typically true for encoder / decoder type networks\n        with lateral connection (e.g., FPN) for which feature maps need to match\n        dimension in the \"bottom up\" and \"top down\" paths. Set to 0 if no specific\n        input size divisibility is required.\n        \"\"\"\n        return 0\n\n    def output_shape(self):\n        \"\"\"\n        Returns:\n            dict[str->ShapeSpec]\n        \"\"\"\n        # this is a backward-compatible default\n        return {\n            name: ShapeSpec(\n                channels=self._out_feature_channels[name], stride=self._out_feature_strides[name]\n            )\n            for name in self._out_features\n        }\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/backbone/build.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom detectron2.layers import ShapeSpec\nfrom detectron2.utils.registry import Registry\n\nfrom .backbone import Backbone\n\nBACKBONE_REGISTRY = Registry(\"BACKBONE\")\nBACKBONE_REGISTRY.__doc__ = \"\"\"\nRegistry for backbones, which extract feature maps from images\n\nThe registered object must be a callable that accepts two arguments:\n\n1. A :class:`detectron2.config.CfgNode`\n2. A :class:`detectron2.layers.ShapeSpec`, which contains the input shape specification.\n\nRegistered object must return instance of :class:`Backbone`.\n\"\"\"\n\n\ndef build_backbone(cfg, input_shape=None):\n    \"\"\"\n    Build a backbone from `cfg.MODEL.BACKBONE.NAME`.\n\n    Returns:\n        an instance of :class:`Backbone`\n    \"\"\"\n    if input_shape is None:\n        input_shape = ShapeSpec(channels=len(cfg.MODEL.PIXEL_MEAN))\n\n    backbone_name = cfg.MODEL.BACKBONE.NAME\n    backbone = BACKBONE_REGISTRY.get(backbone_name)(cfg, input_shape)\n    assert isinstance(backbone, Backbone)\n    return backbone\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/backbone/fpn.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport math\nimport fvcore.nn.weight_init as weight_init\nimport torch\nimport torch.nn.functional as F\nfrom torch import nn\n\nfrom detectron2.layers import Conv2d, ShapeSpec, get_norm\n\nfrom .backbone import Backbone\nfrom .build import BACKBONE_REGISTRY\nfrom .resnet import build_resnet_backbone\n\n__all__ = [\"build_resnet_fpn_backbone\", \"build_retinanet_resnet_fpn_backbone\", \"FPN\"]\n\n\nclass FPN(Backbone):\n    \"\"\"\n    This module implements :paper:`FPN`.\n    It creates pyramid features built on top of some input feature maps.\n    \"\"\"\n\n    _fuse_type: torch.jit.Final[str]\n\n    def __init__(\n        self, bottom_up, in_features, out_channels, norm=\"\", top_block=None, fuse_type=\"sum\"\n    ):\n        \"\"\"\n        Args:\n            bottom_up (Backbone): module representing the bottom up subnetwork.\n                Must be a subclass of :class:`Backbone`. The multi-scale feature\n                maps generated by the bottom up network, and listed in `in_features`,\n                are used to generate FPN levels.\n            in_features (list[str]): names of the input feature maps coming\n                from the backbone to which FPN is attached. For example, if the\n                backbone produces [\"res2\", \"res3\", \"res4\"], any *contiguous* sublist\n                of these may be used; order must be from high to low resolution.\n            out_channels (int): number of channels in the output feature maps.\n            norm (str): the normalization to use.\n            top_block (nn.Module or None): if provided, an extra operation will\n                be performed on the output of the last (smallest resolution)\n                FPN output, and the result will extend the result list. The top_block\n                further downsamples the feature map. It must have an attribute\n                \"num_levels\", meaning the number of extra FPN levels added by\n                this block, and \"in_feature\", which is a string representing\n                its input feature (e.g., p5).\n            fuse_type (str): types for fusing the top down features and the lateral\n                ones. It can be \"sum\" (default), which sums up element-wise; or \"avg\",\n                which takes the element-wise mean of the two.\n        \"\"\"\n        super(FPN, self).__init__()\n        assert isinstance(bottom_up, Backbone)\n        assert in_features, in_features\n\n        # Feature map strides and channels from the bottom up network (e.g. ResNet)\n        input_shapes = bottom_up.output_shape()\n        strides = [input_shapes[f].stride for f in in_features]\n        in_channels_per_feature = [input_shapes[f].channels for f in in_features]\n\n        _assert_strides_are_log2_contiguous(strides)\n        lateral_convs = []\n        output_convs = []\n\n        use_bias = norm == \"\"\n        for idx, in_channels in enumerate(in_channels_per_feature):\n            lateral_norm = get_norm(norm, out_channels)\n            output_norm = get_norm(norm, out_channels)\n\n            lateral_conv = Conv2d(\n                in_channels, out_channels, kernel_size=1, bias=use_bias, norm=lateral_norm\n            )\n            output_conv = Conv2d(\n                out_channels,\n                out_channels,\n                kernel_size=3,\n                stride=1,\n                padding=1,\n                bias=use_bias,\n                norm=output_norm,\n            )\n            weight_init.c2_xavier_fill(lateral_conv)\n            weight_init.c2_xavier_fill(output_conv)\n            stage = int(math.log2(strides[idx]))\n            self.add_module(\"fpn_lateral{}\".format(stage), lateral_conv)\n            self.add_module(\"fpn_output{}\".format(stage), output_conv)\n\n            lateral_convs.append(lateral_conv)\n            output_convs.append(output_conv)\n        # Place convs into top-down order (from low to high resolution)\n        # to make the top-down computation in forward clearer.\n        self.lateral_convs = lateral_convs[::-1]\n        self.output_convs = output_convs[::-1]\n        self.top_block = top_block\n        self.in_features = tuple(in_features)\n        self.bottom_up = bottom_up\n        # Return feature names are \"p<stage>\", like [\"p2\", \"p3\", ..., \"p6\"]\n        self._out_feature_strides = {\"p{}\".format(int(math.log2(s))): s for s in strides}\n        # top block output feature maps.\n        if self.top_block is not None:\n            for s in range(stage, stage + self.top_block.num_levels):\n                self._out_feature_strides[\"p{}\".format(s + 1)] = 2 ** (s + 1)\n\n        self._out_features = list(self._out_feature_strides.keys())\n        self._out_feature_channels = {k: out_channels for k in self._out_features}\n        self._size_divisibility = strides[-1]\n        assert fuse_type in {\"avg\", \"sum\"}\n        self._fuse_type = fuse_type\n\n    @property\n    def size_divisibility(self):\n        return self._size_divisibility\n\n    def forward(self, x):\n        \"\"\"\n        Args:\n            input (dict[str->Tensor]): mapping feature map name (e.g., \"res5\") to\n                feature map tensor for each feature level in high to low resolution order.\n\n        Returns:\n            dict[str->Tensor]:\n                mapping from feature map name to FPN feature map tensor\n                in high to low resolution order. Returned feature names follow the FPN\n                paper convention: \"p<stage>\", where stage has stride = 2 ** stage e.g.,\n                [\"p2\", \"p3\", ..., \"p6\"].\n        \"\"\"\n        bottom_up_features = self.bottom_up(x)\n        results = []\n        prev_features = self.lateral_convs[0](bottom_up_features[self.in_features[-1]])\n        results.append(self.output_convs[0](prev_features))\n\n        # Reverse feature maps into top-down order (from low to high resolution)\n        for idx, (lateral_conv, output_conv) in enumerate(\n            zip(self.lateral_convs, self.output_convs)\n        ):\n            # Slicing of ModuleList is not supported https://github.com/pytorch/pytorch/issues/47336\n            # Therefore we loop over all modules but skip the first one\n            if idx > 0:\n                features = self.in_features[-idx - 1]\n                features = bottom_up_features[features]\n                top_down_features = F.interpolate(prev_features, scale_factor=2.0, mode=\"nearest\")\n                lateral_features = lateral_conv(features)\n                prev_features = lateral_features + top_down_features\n                if self._fuse_type == \"avg\":\n                    prev_features /= 2\n                results.insert(0, output_conv(prev_features))\n\n        if self.top_block is not None:\n            if self.top_block.in_feature in bottom_up_features:\n                top_block_in_feature = bottom_up_features[self.top_block.in_feature]\n            else:\n                top_block_in_feature = results[self._out_features.index(self.top_block.in_feature)]\n            results.extend(self.top_block(top_block_in_feature))\n        assert len(self._out_features) == len(results)\n        return {f: res for f, res in zip(self._out_features, results)}\n\n    def output_shape(self):\n        return {\n            name: ShapeSpec(\n                channels=self._out_feature_channels[name], stride=self._out_feature_strides[name]\n            )\n            for name in self._out_features\n        }\n\n\ndef _assert_strides_are_log2_contiguous(strides):\n    \"\"\"\n    Assert that each stride is 2x times its preceding stride, i.e. \"contiguous in log2\".\n    \"\"\"\n    for i, stride in enumerate(strides[1:], 1):\n        assert stride == 2 * strides[i - 1], \"Strides {} {} are not log2 contiguous\".format(\n            stride, strides[i - 1]\n        )\n\n\nclass LastLevelMaxPool(nn.Module):\n    \"\"\"\n    This module is used in the original FPN to generate a downsampled\n    P6 feature from P5.\n    \"\"\"\n\n    def __init__(self):\n        super().__init__()\n        self.num_levels = 1\n        self.in_feature = \"p5\"\n\n    def forward(self, x):\n        return [F.max_pool2d(x, kernel_size=1, stride=2, padding=0)]\n\n\nclass LastLevelP6P7(nn.Module):\n    \"\"\"\n    This module is used in RetinaNet to generate extra layers, P6 and P7 from\n    C5 feature.\n    \"\"\"\n\n    def __init__(self, in_channels, out_channels, in_feature=\"res5\"):\n        super().__init__()\n        self.num_levels = 2\n        self.in_feature = in_feature\n        self.p6 = nn.Conv2d(in_channels, out_channels, 3, 2, 1)\n        self.p7 = nn.Conv2d(out_channels, out_channels, 3, 2, 1)\n        for module in [self.p6, self.p7]:\n            weight_init.c2_xavier_fill(module)\n\n    def forward(self, c5):\n        p6 = self.p6(c5)\n        p7 = self.p7(F.relu(p6))\n        return [p6, p7]\n\n\n@BACKBONE_REGISTRY.register()\ndef build_resnet_fpn_backbone(cfg, input_shape: ShapeSpec):\n    \"\"\"\n    Args:\n        cfg: a detectron2 CfgNode\n\n    Returns:\n        backbone (Backbone): backbone module, must be a subclass of :class:`Backbone`.\n    \"\"\"\n    bottom_up = build_resnet_backbone(cfg, input_shape)\n    in_features = cfg.MODEL.FPN.IN_FEATURES\n    out_channels = cfg.MODEL.FPN.OUT_CHANNELS\n    backbone = FPN(\n        bottom_up=bottom_up,\n        in_features=in_features,\n        out_channels=out_channels,\n        norm=cfg.MODEL.FPN.NORM,\n        top_block=LastLevelMaxPool(),\n        fuse_type=cfg.MODEL.FPN.FUSE_TYPE,\n    )\n    return backbone\n\n\n@BACKBONE_REGISTRY.register()\ndef build_retinanet_resnet_fpn_backbone(cfg, input_shape: ShapeSpec):\n    \"\"\"\n    Args:\n        cfg: a detectron2 CfgNode\n\n    Returns:\n        backbone (Backbone): backbone module, must be a subclass of :class:`Backbone`.\n    \"\"\"\n    bottom_up = build_resnet_backbone(cfg, input_shape)\n    in_features = cfg.MODEL.FPN.IN_FEATURES\n    out_channels = cfg.MODEL.FPN.OUT_CHANNELS\n    in_channels_p6p7 = bottom_up.output_shape()[\"res5\"].channels\n    backbone = FPN(\n        bottom_up=bottom_up,\n        in_features=in_features,\n        out_channels=out_channels,\n        norm=cfg.MODEL.FPN.NORM,\n        top_block=LastLevelP6P7(in_channels_p6p7, out_channels),\n        fuse_type=cfg.MODEL.FPN.FUSE_TYPE,\n    )\n    return backbone\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/backbone/regnet.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\"\"\"\nImplementation of RegNet models from :paper:`dds` and :paper:`scaling`.\n\nThis code is adapted from https://github.com/facebookresearch/pycls with minimal modifications.\nSome code duplication exists between RegNet and ResNets (e.g., ResStem) in order to simplify\nmodel loading.\n\"\"\"\n\nimport numpy as np\nfrom torch import nn\n\nfrom detectron2.layers import CNNBlockBase, ShapeSpec, get_norm\n\nfrom .backbone import Backbone\n\n__all__ = [\n    \"AnyNet\",\n    \"RegNet\",\n    \"ResStem\",\n    \"SimpleStem\",\n    \"VanillaBlock\",\n    \"ResBasicBlock\",\n    \"ResBottleneckBlock\",\n]\n\n\ndef conv2d(w_in, w_out, k, *, stride=1, groups=1, bias=False):\n    \"\"\"Helper for building a conv2d layer.\"\"\"\n    assert k % 2 == 1, \"Only odd size kernels supported to avoid padding issues.\"\n    s, p, g, b = stride, (k - 1) // 2, groups, bias\n    return nn.Conv2d(w_in, w_out, k, stride=s, padding=p, groups=g, bias=b)\n\n\ndef gap2d():\n    \"\"\"Helper for building a global average pooling layer.\"\"\"\n    return nn.AdaptiveAvgPool2d((1, 1))\n\n\ndef pool2d(k, *, stride=1):\n    \"\"\"Helper for building a pool2d layer.\"\"\"\n    assert k % 2 == 1, \"Only odd size kernels supported to avoid padding issues.\"\n    return nn.MaxPool2d(k, stride=stride, padding=(k - 1) // 2)\n\n\ndef init_weights(m):\n    \"\"\"Performs ResNet-style weight initialization.\"\"\"\n    if isinstance(m, nn.Conv2d):\n        # Note that there is no bias due to BN\n        fan_out = m.kernel_size[0] * m.kernel_size[1] * m.out_channels\n        m.weight.data.normal_(mean=0.0, std=np.sqrt(2.0 / fan_out))\n    elif isinstance(m, nn.BatchNorm2d):\n        m.weight.data.fill_(1.0)\n        m.bias.data.zero_()\n    elif isinstance(m, nn.Linear):\n        m.weight.data.normal_(mean=0.0, std=0.01)\n        m.bias.data.zero_()\n\n\nclass ResStem(CNNBlockBase):\n    \"\"\"ResNet stem for ImageNet: 7x7, BN, AF, MaxPool.\"\"\"\n\n    def __init__(self, w_in, w_out, norm, activation_class):\n        super().__init__(w_in, w_out, 4)\n        self.conv = conv2d(w_in, w_out, 7, stride=2)\n        self.bn = get_norm(norm, w_out)\n        self.af = activation_class()\n        self.pool = pool2d(3, stride=2)\n\n    def forward(self, x):\n        for layer in self.children():\n            x = layer(x)\n        return x\n\n\nclass SimpleStem(CNNBlockBase):\n    \"\"\"Simple stem for ImageNet: 3x3, BN, AF.\"\"\"\n\n    def __init__(self, w_in, w_out, norm, activation_class):\n        super().__init__(w_in, w_out, 2)\n        self.conv = conv2d(w_in, w_out, 3, stride=2)\n        self.bn = get_norm(norm, w_out)\n        self.af = activation_class()\n\n    def forward(self, x):\n        for layer in self.children():\n            x = layer(x)\n        return x\n\n\nclass SE(nn.Module):\n    \"\"\"Squeeze-and-Excitation (SE) block: AvgPool, FC, Act, FC, Sigmoid.\"\"\"\n\n    def __init__(self, w_in, w_se, activation_class):\n        super().__init__()\n        self.avg_pool = gap2d()\n        self.f_ex = nn.Sequential(\n            conv2d(w_in, w_se, 1, bias=True),\n            activation_class(),\n            conv2d(w_se, w_in, 1, bias=True),\n            nn.Sigmoid(),\n        )\n\n    def forward(self, x):\n        return x * self.f_ex(self.avg_pool(x))\n\n\nclass VanillaBlock(CNNBlockBase):\n    \"\"\"Vanilla block: [3x3 conv, BN, Relu] x2.\"\"\"\n\n    def __init__(self, w_in, w_out, stride, norm, activation_class, _params):\n        super().__init__(w_in, w_out, stride)\n        self.a = conv2d(w_in, w_out, 3, stride=stride)\n        self.a_bn = get_norm(norm, w_out)\n        self.a_af = activation_class()\n        self.b = conv2d(w_out, w_out, 3)\n        self.b_bn = get_norm(norm, w_out)\n        self.b_af = activation_class()\n\n    def forward(self, x):\n        for layer in self.children():\n            x = layer(x)\n        return x\n\n\nclass BasicTransform(nn.Module):\n    \"\"\"Basic transformation: [3x3 conv, BN, Relu] x2.\"\"\"\n\n    def __init__(self, w_in, w_out, stride, norm, activation_class, _params):\n        super().__init__()\n        self.a = conv2d(w_in, w_out, 3, stride=stride)\n        self.a_bn = get_norm(norm, w_out)\n        self.a_af = activation_class()\n        self.b = conv2d(w_out, w_out, 3)\n        self.b_bn = get_norm(norm, w_out)\n        self.b_bn.final_bn = True\n\n    def forward(self, x):\n        for layer in self.children():\n            x = layer(x)\n        return x\n\n\nclass ResBasicBlock(CNNBlockBase):\n    \"\"\"Residual basic block: x + f(x), f = basic transform.\"\"\"\n\n    def __init__(self, w_in, w_out, stride, norm, activation_class, params):\n        super().__init__(w_in, w_out, stride)\n        self.proj, self.bn = None, None\n        if (w_in != w_out) or (stride != 1):\n            self.proj = conv2d(w_in, w_out, 1, stride=stride)\n            self.bn = get_norm(norm, w_out)\n        self.f = BasicTransform(w_in, w_out, stride, norm, activation_class, params)\n        self.af = activation_class()\n\n    def forward(self, x):\n        x_p = self.bn(self.proj(x)) if self.proj else x\n        return self.af(x_p + self.f(x))\n\n\nclass BottleneckTransform(nn.Module):\n    \"\"\"Bottleneck transformation: 1x1, 3x3 [+SE], 1x1.\"\"\"\n\n    def __init__(self, w_in, w_out, stride, norm, activation_class, params):\n        super().__init__()\n        w_b = int(round(w_out * params[\"bot_mul\"]))\n        w_se = int(round(w_in * params[\"se_r\"]))\n        groups = w_b // params[\"group_w\"]\n        self.a = conv2d(w_in, w_b, 1)\n        self.a_bn = get_norm(norm, w_b)\n        self.a_af = activation_class()\n        self.b = conv2d(w_b, w_b, 3, stride=stride, groups=groups)\n        self.b_bn = get_norm(norm, w_b)\n        self.b_af = activation_class()\n        self.se = SE(w_b, w_se, activation_class) if w_se else None\n        self.c = conv2d(w_b, w_out, 1)\n        self.c_bn = get_norm(norm, w_out)\n        self.c_bn.final_bn = True\n\n    def forward(self, x):\n        for layer in self.children():\n            x = layer(x)\n        return x\n\n\nclass ResBottleneckBlock(CNNBlockBase):\n    \"\"\"Residual bottleneck block: x + f(x), f = bottleneck transform.\"\"\"\n\n    def __init__(self, w_in, w_out, stride, norm, activation_class, params):\n        super().__init__(w_in, w_out, stride)\n        self.proj, self.bn = None, None\n        if (w_in != w_out) or (stride != 1):\n            self.proj = conv2d(w_in, w_out, 1, stride=stride)\n            self.bn = get_norm(norm, w_out)\n        self.f = BottleneckTransform(w_in, w_out, stride, norm, activation_class, params)\n        self.af = activation_class()\n\n    def forward(self, x):\n        x_p = self.bn(self.proj(x)) if self.proj else x\n        return self.af(x_p + self.f(x))\n\n\nclass AnyStage(nn.Module):\n    \"\"\"AnyNet stage (sequence of blocks w/ the same output shape).\"\"\"\n\n    def __init__(self, w_in, w_out, stride, d, block_class, norm, activation_class, params):\n        super().__init__()\n        for i in range(d):\n            block = block_class(w_in, w_out, stride, norm, activation_class, params)\n            self.add_module(\"b{}\".format(i + 1), block)\n            stride, w_in = 1, w_out\n\n    def forward(self, x):\n        for block in self.children():\n            x = block(x)\n        return x\n\n\nclass AnyNet(Backbone):\n    \"\"\"AnyNet model. See :paper:`dds`.\"\"\"\n\n    def __init__(\n        self,\n        *,\n        stem_class,\n        stem_width,\n        block_class,\n        depths,\n        widths,\n        group_widths,\n        strides,\n        bottleneck_ratios,\n        se_ratio,\n        activation_class,\n        freeze_at=0,\n        norm=\"BN\",\n        out_features=None,\n    ):\n        \"\"\"\n        Args:\n            stem_class (callable): A callable taking 4 arguments (channels in, channels out,\n                normalization, callable returning an activation function) that returns another\n                callable implementing the stem module.\n            stem_width (int): The number of output channels that the stem produces.\n            block_class (callable): A callable taking 6 arguments (channels in, channels out,\n                stride, normalization, callable returning an activation function, a dict of\n                block-specific parameters) that returns another callable implementing the repeated\n                block module.\n            depths (list[int]): Number of blocks in each stage.\n            widths (list[int]): For each stage, the number of output channels of each block.\n            group_widths (list[int]): For each stage, the number of channels per group in group\n                convolution, if the block uses group convolution.\n            strides (list[int]): The stride that each network stage applies to its input.\n            bottleneck_ratios (list[float]): For each stage, the ratio of the number of bottleneck\n                channels to the number of block input channels (or, equivalently, output channels),\n                if the block uses a bottleneck.\n            se_ratio (float): The ratio of the number of channels used inside the squeeze-excitation\n                (SE) module to it number of input channels, if SE the block uses SE.\n            activation_class (callable): A callable taking no arguments that returns another\n                callable implementing an activation function.\n            freeze_at (int): The number of stages at the beginning to freeze.\n                see :meth:`freeze` for detailed explanation.\n            norm (str or callable): normalization for all conv layers.\n                See :func:`layers.get_norm` for supported format.\n            out_features (list[str]): name of the layers whose outputs should\n                be returned in forward. RegNet's use \"stem\" and \"s1\", \"s2\", etc for the stages after\n                the stem. If None, will return the output of the last layer.\n        \"\"\"\n        super().__init__()\n        self.stem = stem_class(3, stem_width, norm, activation_class)\n\n        current_stride = self.stem.stride\n        self._out_feature_strides = {\"stem\": current_stride}\n        self._out_feature_channels = {\"stem\": self.stem.out_channels}\n        self.stages_and_names = []\n        prev_w = stem_width\n\n        for i, (d, w, s, b, g) in enumerate(\n            zip(depths, widths, strides, bottleneck_ratios, group_widths)\n        ):\n            params = {\"bot_mul\": b, \"group_w\": g, \"se_r\": se_ratio}\n            stage = AnyStage(prev_w, w, s, d, block_class, norm, activation_class, params)\n            name = \"s{}\".format(i + 1)\n            self.add_module(name, stage)\n            self.stages_and_names.append((stage, name))\n            self._out_feature_strides[name] = current_stride = int(\n                current_stride * np.prod([k.stride for k in stage.children()])\n            )\n            self._out_feature_channels[name] = list(stage.children())[-1].out_channels\n            prev_w = w\n\n        self.apply(init_weights)\n\n        if out_features is None:\n            out_features = [name]\n        self._out_features = out_features\n        assert len(self._out_features)\n        children = [x[0] for x in self.named_children()]\n        for out_feature in self._out_features:\n            assert out_feature in children, \"Available children: {} does not include {}\".format(\n                \", \".join(children), out_feature\n            )\n        self.freeze(freeze_at)\n\n    def forward(self, x):\n        \"\"\"\n        Args:\n            x: Tensor of shape (N,C,H,W). H, W must be a multiple of ``self.size_divisibility``.\n\n        Returns:\n            dict[str->Tensor]: names and the corresponding features\n        \"\"\"\n        assert x.dim() == 4, f\"Model takes an input of shape (N, C, H, W). Got {x.shape} instead!\"\n        outputs = {}\n        x = self.stem(x)\n        if \"stem\" in self._out_features:\n            outputs[\"stem\"] = x\n        for stage, name in self.stages_and_names:\n            x = stage(x)\n            if name in self._out_features:\n                outputs[name] = x\n        return outputs\n\n    def output_shape(self):\n        return {\n            name: ShapeSpec(\n                channels=self._out_feature_channels[name], stride=self._out_feature_strides[name]\n            )\n            for name in self._out_features\n        }\n\n    def freeze(self, freeze_at=0):\n        \"\"\"\n        Freeze the first several stages of the model. Commonly used in fine-tuning.\n\n        Layers that produce the same feature map spatial size are defined as one\n        \"stage\" by :paper:`FPN`.\n\n        Args:\n            freeze_at (int): number of stages to freeze.\n                `1` means freezing the stem. `2` means freezing the stem and\n                one residual stage, etc.\n\n        Returns:\n            nn.Module: this model itself\n        \"\"\"\n        if freeze_at >= 1:\n            self.stem.freeze()\n        for idx, (stage, _) in enumerate(self.stages_and_names, start=2):\n            if freeze_at >= idx:\n                for block in stage.children():\n                    block.freeze()\n        return self\n\n\ndef adjust_block_compatibility(ws, bs, gs):\n    \"\"\"Adjusts the compatibility of widths, bottlenecks, and groups.\"\"\"\n    assert len(ws) == len(bs) == len(gs)\n    assert all(w > 0 and b > 0 and g > 0 for w, b, g in zip(ws, bs, gs))\n    vs = [int(max(1, w * b)) for w, b in zip(ws, bs)]\n    gs = [int(min(g, v)) for g, v in zip(gs, vs)]\n    ms = [np.lcm(g, b) if b > 1 else g for g, b in zip(gs, bs)]\n    vs = [max(m, int(round(v / m) * m)) for v, m in zip(vs, ms)]\n    ws = [int(v / b) for v, b in zip(vs, bs)]\n    assert all(w * b % g == 0 for w, b, g in zip(ws, bs, gs))\n    return ws, bs, gs\n\n\ndef generate_regnet_parameters(w_a, w_0, w_m, d, q=8):\n    \"\"\"Generates per stage widths and depths from RegNet parameters.\"\"\"\n    assert w_a >= 0 and w_0 > 0 and w_m > 1 and w_0 % q == 0\n    # Generate continuous per-block ws\n    ws_cont = np.arange(d) * w_a + w_0\n    # Generate quantized per-block ws\n    ks = np.round(np.log(ws_cont / w_0) / np.log(w_m))\n    ws_all = w_0 * np.power(w_m, ks)\n    ws_all = np.round(np.divide(ws_all, q)).astype(int) * q\n    # Generate per stage ws and ds (assumes ws_all are sorted)\n    ws, ds = np.unique(ws_all, return_counts=True)\n    # Compute number of actual stages and total possible stages\n    num_stages, total_stages = len(ws), ks.max() + 1\n    # Convert numpy arrays to lists and return\n    ws, ds, ws_all, ws_cont = (x.tolist() for x in (ws, ds, ws_all, ws_cont))\n    return ws, ds, num_stages, total_stages, ws_all, ws_cont\n\n\nclass RegNet(AnyNet):\n    \"\"\"RegNet model. See :paper:`dds`.\"\"\"\n\n    def __init__(\n        self,\n        *,\n        stem_class,\n        stem_width,\n        block_class,\n        depth,\n        w_a,\n        w_0,\n        w_m,\n        group_width,\n        stride=2,\n        bottleneck_ratio=1.0,\n        se_ratio=0.0,\n        activation_class=None,\n        freeze_at=0,\n        norm=\"BN\",\n        out_features=None,\n    ):\n        \"\"\"\n        Build a RegNet from the parameterization described in :paper:`dds` Section 3.3.\n\n        Args:\n            See :class:`AnyNet` for arguments that are not listed here.\n            depth (int): Total number of blocks in the RegNet.\n            w_a (float): Factor by which block width would increase prior to quantizing block widths\n                by stage. See :paper:`dds` Section 3.3.\n            w_0 (int): Initial block width. See :paper:`dds` Section 3.3.\n            w_m (float): Parameter controlling block width quantization.\n                See :paper:`dds` Section 3.3.\n            group_width (int): Number of channels per group in group convolution, if the block uses\n                group convolution.\n            bottleneck_ratio (float): The ratio of the number of bottleneck channels to the number\n                of block input channels (or, equivalently, output channels), if the block uses a\n                bottleneck.\n            stride (int): The stride that each network stage applies to its input.\n        \"\"\"\n        ws, ds = generate_regnet_parameters(w_a, w_0, w_m, depth)[0:2]\n        ss = [stride for _ in ws]\n        bs = [bottleneck_ratio for _ in ws]\n        gs = [group_width for _ in ws]\n        ws, bs, gs = adjust_block_compatibility(ws, bs, gs)\n\n        def default_activation_class():\n            return nn.ReLU(inplace=True)\n\n        super().__init__(\n            stem_class=stem_class,\n            stem_width=stem_width,\n            block_class=block_class,\n            depths=ds,\n            widths=ws,\n            strides=ss,\n            group_widths=gs,\n            bottleneck_ratios=bs,\n            se_ratio=se_ratio,\n            activation_class=default_activation_class\n            if activation_class is None\n            else activation_class,\n            freeze_at=freeze_at,\n            norm=norm,\n            out_features=out_features,\n        )\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/backbone/resnet.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport numpy as np\nimport fvcore.nn.weight_init as weight_init\nimport torch\nimport torch.nn.functional as F\nfrom torch import nn\n\nfrom detectron2.layers import (\n    CNNBlockBase,\n    Conv2d,\n    DeformConv,\n    ModulatedDeformConv,\n    ShapeSpec,\n    get_norm,\n)\n\nfrom .backbone import Backbone\nfrom .build import BACKBONE_REGISTRY\n\n__all__ = [\n    \"ResNetBlockBase\",\n    \"BasicBlock\",\n    \"BottleneckBlock\",\n    \"DeformBottleneckBlock\",\n    \"BasicStem\",\n    \"ResNet\",\n    \"make_stage\",\n    \"build_resnet_backbone\",\n]\n\n\nclass BasicBlock(CNNBlockBase):\n    \"\"\"\n    The basic residual block for ResNet-18 and ResNet-34 defined in :paper:`ResNet`,\n    with two 3x3 conv layers and a projection shortcut if needed.\n    \"\"\"\n\n    def __init__(self, in_channels, out_channels, *, stride=1, norm=\"BN\"):\n        \"\"\"\n        Args:\n            in_channels (int): Number of input channels.\n            out_channels (int): Number of output channels.\n            stride (int): Stride for the first conv.\n            norm (str or callable): normalization for all conv layers.\n                See :func:`layers.get_norm` for supported format.\n        \"\"\"\n        super().__init__(in_channels, out_channels, stride)\n\n        if in_channels != out_channels:\n            self.shortcut = Conv2d(\n                in_channels,\n                out_channels,\n                kernel_size=1,\n                stride=stride,\n                bias=False,\n                norm=get_norm(norm, out_channels),\n            )\n        else:\n            self.shortcut = None\n\n        self.conv1 = Conv2d(\n            in_channels,\n            out_channels,\n            kernel_size=3,\n            stride=stride,\n            padding=1,\n            bias=False,\n            norm=get_norm(norm, out_channels),\n        )\n\n        self.conv2 = Conv2d(\n            out_channels,\n            out_channels,\n            kernel_size=3,\n            stride=1,\n            padding=1,\n            bias=False,\n            norm=get_norm(norm, out_channels),\n        )\n\n        for layer in [self.conv1, self.conv2, self.shortcut]:\n            if layer is not None:  # shortcut can be None\n                weight_init.c2_msra_fill(layer)\n\n    def forward(self, x):\n        out = self.conv1(x)\n        out = F.relu_(out)\n        out = self.conv2(out)\n\n        if self.shortcut is not None:\n            shortcut = self.shortcut(x)\n        else:\n            shortcut = x\n\n        out += shortcut\n        out = F.relu_(out)\n        return out\n\n\nclass BottleneckBlock(CNNBlockBase):\n    \"\"\"\n    The standard bottleneck residual block used by ResNet-50, 101 and 152\n    defined in :paper:`ResNet`.  It contains 3 conv layers with kernels\n    1x1, 3x3, 1x1, and a projection shortcut if needed.\n    \"\"\"\n\n    def __init__(\n        self,\n        in_channels,\n        out_channels,\n        *,\n        bottleneck_channels,\n        stride=1,\n        num_groups=1,\n        norm=\"BN\",\n        stride_in_1x1=False,\n        dilation=1,\n    ):\n        \"\"\"\n        Args:\n            bottleneck_channels (int): number of output channels for the 3x3\n                \"bottleneck\" conv layers.\n            num_groups (int): number of groups for the 3x3 conv layer.\n            norm (str or callable): normalization for all conv layers.\n                See :func:`layers.get_norm` for supported format.\n            stride_in_1x1 (bool): when stride>1, whether to put stride in the\n                first 1x1 convolution or the bottleneck 3x3 convolution.\n            dilation (int): the dilation rate of the 3x3 conv layer.\n        \"\"\"\n        super().__init__(in_channels, out_channels, stride)\n\n        if in_channels != out_channels:\n            self.shortcut = Conv2d(\n                in_channels,\n                out_channels,\n                kernel_size=1,\n                stride=stride,\n                bias=False,\n                norm=get_norm(norm, out_channels),\n            )\n        else:\n            self.shortcut = None\n\n        # The original MSRA ResNet models have stride in the first 1x1 conv\n        # The subsequent fb.torch.resnet and Caffe2 ResNe[X]t implementations have\n        # stride in the 3x3 conv\n        stride_1x1, stride_3x3 = (stride, 1) if stride_in_1x1 else (1, stride)\n\n        self.conv1 = Conv2d(\n            in_channels,\n            bottleneck_channels,\n            kernel_size=1,\n            stride=stride_1x1,\n            bias=False,\n            norm=get_norm(norm, bottleneck_channels),\n        )\n\n        self.conv2 = Conv2d(\n            bottleneck_channels,\n            bottleneck_channels,\n            kernel_size=3,\n            stride=stride_3x3,\n            padding=1 * dilation,\n            bias=False,\n            groups=num_groups,\n            dilation=dilation,\n            norm=get_norm(norm, bottleneck_channels),\n        )\n\n        self.conv3 = Conv2d(\n            bottleneck_channels,\n            out_channels,\n            kernel_size=1,\n            bias=False,\n            norm=get_norm(norm, out_channels),\n        )\n\n        for layer in [self.conv1, self.conv2, self.conv3, self.shortcut]:\n            if layer is not None:  # shortcut can be None\n                weight_init.c2_msra_fill(layer)\n\n        # Zero-initialize the last normalization in each residual branch,\n        # so that at the beginning, the residual branch starts with zeros,\n        # and each residual block behaves like an identity.\n        # See Sec 5.1 in \"Accurate, Large Minibatch SGD: Training ImageNet in 1 Hour\":\n        # \"For BN layers, the learnable scaling coefficient γ is initialized\n        # to be 1, except for each residual block's last BN\n        # where γ is initialized to be 0.\"\n\n        # nn.init.constant_(self.conv3.norm.weight, 0)\n        # TODO this somehow hurts performance when training GN models from scratch.\n        # Add it as an option when we need to use this code to train a backbone.\n\n    def forward(self, x):\n        out = self.conv1(x)\n        out = F.relu_(out)\n\n        out = self.conv2(out)\n        out = F.relu_(out)\n\n        out = self.conv3(out)\n\n        if self.shortcut is not None:\n            shortcut = self.shortcut(x)\n        else:\n            shortcut = x\n\n        out += shortcut\n        out = F.relu_(out)\n        return out\n\n\nclass DeformBottleneckBlock(CNNBlockBase):\n    \"\"\"\n    Similar to :class:`BottleneckBlock`, but with :paper:`deformable conv <deformconv>`\n    in the 3x3 convolution.\n    \"\"\"\n\n    def __init__(\n        self,\n        in_channels,\n        out_channels,\n        *,\n        bottleneck_channels,\n        stride=1,\n        num_groups=1,\n        norm=\"BN\",\n        stride_in_1x1=False,\n        dilation=1,\n        deform_modulated=False,\n        deform_num_groups=1,\n    ):\n        super().__init__(in_channels, out_channels, stride)\n        self.deform_modulated = deform_modulated\n\n        if in_channels != out_channels:\n            self.shortcut = Conv2d(\n                in_channels,\n                out_channels,\n                kernel_size=1,\n                stride=stride,\n                bias=False,\n                norm=get_norm(norm, out_channels),\n            )\n        else:\n            self.shortcut = None\n\n        stride_1x1, stride_3x3 = (stride, 1) if stride_in_1x1 else (1, stride)\n\n        self.conv1 = Conv2d(\n            in_channels,\n            bottleneck_channels,\n            kernel_size=1,\n            stride=stride_1x1,\n            bias=False,\n            norm=get_norm(norm, bottleneck_channels),\n        )\n\n        if deform_modulated:\n            deform_conv_op = ModulatedDeformConv\n            # offset channels are 2 or 3 (if with modulated) * kernel_size * kernel_size\n            offset_channels = 27\n        else:\n            deform_conv_op = DeformConv\n            offset_channels = 18\n\n        self.conv2_offset = Conv2d(\n            bottleneck_channels,\n            offset_channels * deform_num_groups,\n            kernel_size=3,\n            stride=stride_3x3,\n            padding=1 * dilation,\n            dilation=dilation,\n        )\n        self.conv2 = deform_conv_op(\n            bottleneck_channels,\n            bottleneck_channels,\n            kernel_size=3,\n            stride=stride_3x3,\n            padding=1 * dilation,\n            bias=False,\n            groups=num_groups,\n            dilation=dilation,\n            deformable_groups=deform_num_groups,\n            norm=get_norm(norm, bottleneck_channels),\n        )\n\n        self.conv3 = Conv2d(\n            bottleneck_channels,\n            out_channels,\n            kernel_size=1,\n            bias=False,\n            norm=get_norm(norm, out_channels),\n        )\n\n        for layer in [self.conv1, self.conv2, self.conv3, self.shortcut]:\n            if layer is not None:  # shortcut can be None\n                weight_init.c2_msra_fill(layer)\n\n        nn.init.constant_(self.conv2_offset.weight, 0)\n        nn.init.constant_(self.conv2_offset.bias, 0)\n\n    def forward(self, x):\n        out = self.conv1(x)\n        out = F.relu_(out)\n\n        if self.deform_modulated:\n            offset_mask = self.conv2_offset(out)\n            offset_x, offset_y, mask = torch.chunk(offset_mask, 3, dim=1)\n            offset = torch.cat((offset_x, offset_y), dim=1)\n            mask = mask.sigmoid()\n            out = self.conv2(out, offset, mask)\n        else:\n            offset = self.conv2_offset(out)\n            out = self.conv2(out, offset)\n        out = F.relu_(out)\n\n        out = self.conv3(out)\n\n        if self.shortcut is not None:\n            shortcut = self.shortcut(x)\n        else:\n            shortcut = x\n\n        out += shortcut\n        out = F.relu_(out)\n        return out\n\n\nclass BasicStem(CNNBlockBase):\n    \"\"\"\n    The standard ResNet stem (layers before the first residual block),\n    with a conv, relu and max_pool.\n    \"\"\"\n\n    def __init__(self, in_channels=3, out_channels=64, norm=\"BN\"):\n        \"\"\"\n        Args:\n            norm (str or callable): norm after the first conv layer.\n                See :func:`layers.get_norm` for supported format.\n        \"\"\"\n        super().__init__(in_channels, out_channels, 4)\n        self.in_channels = in_channels\n        self.conv1 = Conv2d(\n            in_channels,\n            out_channels,\n            kernel_size=7,\n            stride=2,\n            padding=3,\n            bias=False,\n            norm=get_norm(norm, out_channels),\n        )\n        weight_init.c2_msra_fill(self.conv1)\n\n    def forward(self, x):\n        x = self.conv1(x)\n        x = F.relu_(x)\n        x = F.max_pool2d(x, kernel_size=3, stride=2, padding=1)\n        return x\n\n\nclass ResNet(Backbone):\n    \"\"\"\n    Implement :paper:`ResNet`.\n    \"\"\"\n\n    def __init__(self, stem, stages, num_classes=None, out_features=None, freeze_at=0):\n        \"\"\"\n        Args:\n            stem (nn.Module): a stem module\n            stages (list[list[CNNBlockBase]]): several (typically 4) stages,\n                each contains multiple :class:`CNNBlockBase`.\n            num_classes (None or int): if None, will not perform classification.\n                Otherwise, will create a linear layer.\n            out_features (list[str]): name of the layers whose outputs should\n                be returned in forward. Can be anything in \"stem\", \"linear\", or \"res2\" ...\n                If None, will return the output of the last layer.\n            freeze_at (int): The number of stages at the beginning to freeze.\n                see :meth:`freeze` for detailed explanation.\n        \"\"\"\n        super().__init__()\n        self.stem = stem\n        self.num_classes = num_classes\n\n        current_stride = self.stem.stride\n        self._out_feature_strides = {\"stem\": current_stride}\n        self._out_feature_channels = {\"stem\": self.stem.out_channels}\n\n        self.stage_names, self.stages = [], []\n\n        if out_features is not None:\n            # Avoid keeping unused layers in this module. They consume extra memory\n            # and may cause allreduce to fail\n            num_stages = max(\n                [{\"res2\": 1, \"res3\": 2, \"res4\": 3, \"res5\": 4}.get(f, 0) for f in out_features]\n            )\n            stages = stages[:num_stages]\n        for i, blocks in enumerate(stages):\n            assert len(blocks) > 0, len(blocks)\n            for block in blocks:\n                assert isinstance(block, CNNBlockBase), block\n\n            name = \"res\" + str(i + 2)\n            stage = nn.Sequential(*blocks)\n\n            self.add_module(name, stage)\n            self.stage_names.append(name)\n            self.stages.append(stage)\n\n            self._out_feature_strides[name] = current_stride = int(\n                current_stride * np.prod([k.stride for k in blocks])\n            )\n            self._out_feature_channels[name] = curr_channels = blocks[-1].out_channels\n        self.stage_names = tuple(self.stage_names)  # Make it static for scripting\n\n        if num_classes is not None:\n            self.avgpool = nn.AdaptiveAvgPool2d((1, 1))\n            self.linear = nn.Linear(curr_channels, num_classes)\n\n            # Sec 5.1 in \"Accurate, Large Minibatch SGD: Training ImageNet in 1 Hour\":\n            # \"The 1000-way fully-connected layer is initialized by\n            # drawing weights from a zero-mean Gaussian with standard deviation of 0.01.\"\n            nn.init.normal_(self.linear.weight, std=0.01)\n            name = \"linear\"\n\n        if out_features is None:\n            out_features = [name]\n        self._out_features = out_features\n        assert len(self._out_features)\n        children = [x[0] for x in self.named_children()]\n        for out_feature in self._out_features:\n            assert out_feature in children, \"Available children: {}\".format(\", \".join(children))\n        self.freeze(freeze_at)\n\n    def forward(self, x):\n        \"\"\"\n        Args:\n            x: Tensor of shape (N,C,H,W). H, W must be a multiple of ``self.size_divisibility``.\n\n        Returns:\n            dict[str->Tensor]: names and the corresponding features\n        \"\"\"\n        assert x.dim() == 4, f\"ResNet takes an input of shape (N, C, H, W). Got {x.shape} instead!\"\n        outputs = {}\n        x = self.stem(x)\n        # print(x.shape)\n        if \"stem\" in self._out_features:\n            outputs[\"stem\"] = x\n        for name, stage in zip(self.stage_names, self.stages):\n            x = stage(x)\n            # print(x.shape)\n            if name in self._out_features:\n                outputs[name] = x\n        if self.num_classes is not None:\n            x = self.avgpool(x)\n            x = torch.flatten(x, 1)\n            x = self.linear(x)\n            if \"linear\" in self._out_features:\n                outputs[\"linear\"] = x\n        return outputs\n\n    def output_shape(self):\n        return {\n            name: ShapeSpec(\n                channels=self._out_feature_channels[name], stride=self._out_feature_strides[name]\n            )\n            for name in self._out_features\n        }\n\n    def freeze(self, freeze_at=0):\n        \"\"\"\n        Freeze the first several stages of the ResNet. Commonly used in\n        fine-tuning.\n\n        Layers that produce the same feature map spatial size are defined as one\n        \"stage\" by :paper:`FPN`.\n\n        Args:\n            freeze_at (int): number of stages to freeze.\n                `1` means freezing the stem. `2` means freezing the stem and\n                one residual stage, etc.\n\n        Returns:\n            nn.Module: this ResNet itself\n        \"\"\"\n        if freeze_at >= 1:\n            self.stem.freeze()\n        for idx, stage in enumerate(self.stages, start=2):\n            if freeze_at >= idx:\n                for block in stage.children():\n                    block.freeze()\n        return self\n\n    @staticmethod\n    def make_stage(block_class, num_blocks, *, in_channels, out_channels, **kwargs):\n        \"\"\"\n        Create a list of blocks of the same type that forms one ResNet stage.\n\n        Args:\n            block_class (type): a subclass of CNNBlockBase that's used to create all blocks in this\n                stage. A module of this type must not change spatial resolution of inputs unless its\n                stride != 1.\n            num_blocks (int): number of blocks in this stage\n            in_channels (int): input channels of the entire stage.\n            out_channels (int): output channels of **every block** in the stage.\n            kwargs: other arguments passed to the constructor of\n                `block_class`. If the argument name is \"xx_per_block\", the\n                argument is a list of values to be passed to each block in the\n                stage. Otherwise, the same argument is passed to every block\n                in the stage.\n\n        Returns:\n            list[CNNBlockBase]: a list of block module.\n\n        Examples:\n        ::\n            stage = ResNet.make_stage(\n                BottleneckBlock, 3, in_channels=16, out_channels=64,\n                bottleneck_channels=16, num_groups=1,\n                stride_per_block=[2, 1, 1],\n                dilations_per_block=[1, 1, 2]\n            )\n\n        Usually, layers that produce the same feature map spatial size are defined as one\n        \"stage\" (in :paper:`FPN`). Under such definition, ``stride_per_block[1:]`` should\n        all be 1.\n        \"\"\"\n        blocks = []\n        for i in range(num_blocks):\n            curr_kwargs = {}\n            for k, v in kwargs.items():\n                if k.endswith(\"_per_block\"):\n                    assert len(v) == num_blocks, (\n                        f\"Argument '{k}' of make_stage should have the \"\n                        f\"same length as num_blocks={num_blocks}.\"\n                    )\n                    newk = k[: -len(\"_per_block\")]\n                    assert newk not in kwargs, f\"Cannot call make_stage with both {k} and {newk}!\"\n                    curr_kwargs[newk] = v[i]\n                else:\n                    curr_kwargs[k] = v\n\n            blocks.append(\n                block_class(in_channels=in_channels, out_channels=out_channels, **curr_kwargs)\n            )\n            in_channels = out_channels\n        return blocks\n\n    @staticmethod\n    def make_default_stages(depth, block_class=None, **kwargs):\n        \"\"\"\n        Created list of ResNet stages from pre-defined depth (one of 18, 34, 50, 101, 152).\n        If it doesn't create the ResNet variant you need, please use :meth:`make_stage`\n        instead for fine-grained customization.\n\n        Args:\n            depth (int): depth of ResNet\n            block_class (type): the CNN block class. Has to accept\n                `bottleneck_channels` argument for depth > 50.\n                By default it is BasicBlock or BottleneckBlock, based on the\n                depth.\n            kwargs:\n                other arguments to pass to `make_stage`. Should not contain\n                stride and channels, as they are predefined for each depth.\n\n        Returns:\n            list[list[CNNBlockBase]]: modules in all stages; see arguments of\n                :class:`ResNet.__init__`.\n        \"\"\"\n        num_blocks_per_stage = {\n            18: [2, 2, 2, 2],\n            34: [3, 4, 6, 3],\n            50: [3, 4, 6, 3],\n            101: [3, 4, 23, 3],\n            152: [3, 8, 36, 3],\n        }[depth]\n        if block_class is None:\n            block_class = BasicBlock if depth < 50 else BottleneckBlock\n        if depth < 50:\n            in_channels = [64, 64, 128, 256]\n            out_channels = [64, 128, 256, 512]\n        else:\n            in_channels = [64, 256, 512, 1024]\n            out_channels = [256, 512, 1024, 2048]\n        ret = []\n        for (n, s, i, o) in zip(num_blocks_per_stage, [1, 2, 2, 2], in_channels, out_channels):\n            if depth >= 50:\n                kwargs[\"bottleneck_channels\"] = o // 4\n            ret.append(\n                ResNet.make_stage(\n                    block_class=block_class,\n                    num_blocks=n,\n                    stride_per_block=[s] + [1] * (n - 1),\n                    in_channels=i,\n                    out_channels=o,\n                    **kwargs,\n                )\n            )\n        return ret\n\n\nResNetBlockBase = CNNBlockBase\n\"\"\"\nAlias for backward compatibiltiy.\n\"\"\"\n\n\ndef make_stage(*args, **kwargs):\n    \"\"\"\n    Deprecated alias for backward compatibiltiy.\n    \"\"\"\n    return ResNet.make_stage(*args, **kwargs)\n\n\n@BACKBONE_REGISTRY.register()\ndef build_resnet_backbone(cfg, input_shape):\n    \"\"\"\n    Create a ResNet instance from config.\n\n    Returns:\n        ResNet: a :class:`ResNet` instance.\n    \"\"\"\n    # need registration of new blocks/stems?\n    norm = cfg.MODEL.RESNETS.NORM\n    stem = BasicStem(\n        in_channels=input_shape.channels,\n        out_channels=cfg.MODEL.RESNETS.STEM_OUT_CHANNELS,\n        norm=norm,\n    )\n\n    # fmt: off\n    freeze_at           = cfg.MODEL.BACKBONE.FREEZE_AT\n    out_features        = cfg.MODEL.RESNETS.OUT_FEATURES\n    depth               = cfg.MODEL.RESNETS.DEPTH\n    num_groups          = cfg.MODEL.RESNETS.NUM_GROUPS\n    width_per_group     = cfg.MODEL.RESNETS.WIDTH_PER_GROUP\n    bottleneck_channels = num_groups * width_per_group\n    in_channels         = cfg.MODEL.RESNETS.STEM_OUT_CHANNELS\n    out_channels        = cfg.MODEL.RESNETS.RES2_OUT_CHANNELS\n    stride_in_1x1       = cfg.MODEL.RESNETS.STRIDE_IN_1X1\n    res5_dilation       = cfg.MODEL.RESNETS.RES5_DILATION\n    deform_on_per_stage = cfg.MODEL.RESNETS.DEFORM_ON_PER_STAGE\n    deform_modulated    = cfg.MODEL.RESNETS.DEFORM_MODULATED\n    deform_num_groups   = cfg.MODEL.RESNETS.DEFORM_NUM_GROUPS\n    # fmt: on\n    assert res5_dilation in {1, 2}, \"res5_dilation cannot be {}.\".format(res5_dilation)\n\n    num_blocks_per_stage = {\n        18: [2, 2, 2, 2],\n        34: [3, 4, 6, 3],\n        50: [3, 4, 6, 3],\n        101: [3, 4, 23, 3],\n        152: [3, 8, 36, 3],\n    }[depth]\n\n    if depth in [18, 34]:\n        assert out_channels == 64, \"Must set MODEL.RESNETS.RES2_OUT_CHANNELS = 64 for R18/R34\"\n        assert not any(\n            deform_on_per_stage\n        ), \"MODEL.RESNETS.DEFORM_ON_PER_STAGE unsupported for R18/R34\"\n        assert res5_dilation == 1, \"Must set MODEL.RESNETS.RES5_DILATION = 1 for R18/R34\"\n        assert num_groups == 1, \"Must set MODEL.RESNETS.NUM_GROUPS = 1 for R18/R34\"\n\n    stages = []\n\n    for idx, stage_idx in enumerate(range(2, 6)):\n        # res5_dilation is used this way as a convention in R-FCN & Deformable Conv paper\n        dilation = res5_dilation if stage_idx == 5 else 1\n        first_stride = 1 if idx == 0 or (stage_idx == 5 and dilation == 2) else 2\n        stage_kargs = {\n            \"num_blocks\": num_blocks_per_stage[idx],\n            \"stride_per_block\": [first_stride] + [1] * (num_blocks_per_stage[idx] - 1),\n            \"in_channels\": in_channels,\n            \"out_channels\": out_channels,\n            \"norm\": norm,\n        }\n        # Use BasicBlock for R18 and R34.\n        if depth in [18, 34]:\n            stage_kargs[\"block_class\"] = BasicBlock\n        else:\n            stage_kargs[\"bottleneck_channels\"] = bottleneck_channels\n            stage_kargs[\"stride_in_1x1\"] = stride_in_1x1\n            stage_kargs[\"dilation\"] = dilation\n            stage_kargs[\"num_groups\"] = num_groups\n            if deform_on_per_stage[idx]:\n                stage_kargs[\"block_class\"] = DeformBottleneckBlock\n                stage_kargs[\"deform_modulated\"] = deform_modulated\n                stage_kargs[\"deform_num_groups\"] = deform_num_groups\n            else:\n                stage_kargs[\"block_class\"] = BottleneckBlock\n        blocks = ResNet.make_stage(**stage_kargs)\n        in_channels = out_channels\n        out_channels *= 2\n        bottleneck_channels *= 2\n        stages.append(blocks)\n    return ResNet(stem, stages, out_features=out_features, freeze_at=freeze_at)\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/box_regression.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport math\nfrom typing import List, Tuple, Union\nimport torch\nfrom fvcore.nn import giou_loss, smooth_l1_loss\nfrom torch.nn import functional as F\n\nfrom detectron2.layers import cat, ciou_loss, diou_loss\nfrom detectron2.structures import Boxes\n\n# Value for clamping large dw and dh predictions. The heuristic is that we clamp\n# such that dw and dh are no larger than what would transform a 16px box into a\n# 1000px box (based on a small anchor, 16px, and a typical image size, 1000px).\n_DEFAULT_SCALE_CLAMP = math.log(1000.0 / 16)\n\n\n__all__ = [\"Box2BoxTransform\", \"Box2BoxTransformRotated\", \"Box2BoxTransformLinear\"]\n\n\n@torch.jit.script\nclass Box2BoxTransform(object):\n    \"\"\"\n    The box-to-box transform defined in R-CNN. The transformation is parameterized\n    by 4 deltas: (dx, dy, dw, dh). The transformation scales the box's width and height\n    by exp(dw), exp(dh) and shifts a box's center by the offset (dx * width, dy * height).\n    \"\"\"\n\n    def __init__(\n        self, weights: Tuple[float, float, float, float], scale_clamp: float = _DEFAULT_SCALE_CLAMP\n    ):\n        \"\"\"\n        Args:\n            weights (4-element tuple): Scaling factors that are applied to the\n                (dx, dy, dw, dh) deltas. In Fast R-CNN, these were originally set\n                such that the deltas have unit variance; now they are treated as\n                hyperparameters of the system.\n            scale_clamp (float): When predicting deltas, the predicted box scaling\n                factors (dw and dh) are clamped such that they are <= scale_clamp.\n        \"\"\"\n        self.weights = weights\n        self.scale_clamp = scale_clamp\n\n    def get_deltas(self, src_boxes, target_boxes):\n        \"\"\"\n        Get box regression transformation deltas (dx, dy, dw, dh) that can be used\n        to transform the `src_boxes` into the `target_boxes`. That is, the relation\n        ``target_boxes == self.apply_deltas(deltas, src_boxes)`` is true (unless\n        any delta is too large and is clamped).\n\n        Args:\n            src_boxes (Tensor): source boxes, e.g., object proposals\n            target_boxes (Tensor): target of the transformation, e.g., ground-truth\n                boxes.\n        \"\"\"\n        assert isinstance(src_boxes, torch.Tensor), type(src_boxes)\n        assert isinstance(target_boxes, torch.Tensor), type(target_boxes)\n\n        src_widths = src_boxes[:, 2] - src_boxes[:, 0]\n        src_heights = src_boxes[:, 3] - src_boxes[:, 1]\n        src_ctr_x = src_boxes[:, 0] + 0.5 * src_widths\n        src_ctr_y = src_boxes[:, 1] + 0.5 * src_heights\n\n        target_widths = target_boxes[:, 2] - target_boxes[:, 0]\n        target_heights = target_boxes[:, 3] - target_boxes[:, 1]\n        target_ctr_x = target_boxes[:, 0] + 0.5 * target_widths\n        target_ctr_y = target_boxes[:, 1] + 0.5 * target_heights\n\n        wx, wy, ww, wh = self.weights\n        dx = wx * (target_ctr_x - src_ctr_x) / src_widths\n        dy = wy * (target_ctr_y - src_ctr_y) / src_heights\n        dw = ww * torch.log(target_widths / src_widths)\n        dh = wh * torch.log(target_heights / src_heights)\n\n        deltas = torch.stack((dx, dy, dw, dh), dim=1)\n        assert (src_widths > 0).all().item(), \"Input boxes to Box2BoxTransform are not valid!\"\n        return deltas\n\n    def apply_deltas(self, deltas, boxes):\n        \"\"\"\n        Apply transformation `deltas` (dx, dy, dw, dh) to `boxes`.\n\n        Args:\n            deltas (Tensor): transformation deltas of shape (N, k*4), where k >= 1.\n                deltas[i] represents k potentially different class-specific\n                box transformations for the single box boxes[i].\n            boxes (Tensor): boxes to transform, of shape (N, 4)\n        \"\"\"\n        deltas = deltas.float()  # ensure fp32 for decoding precision\n        boxes = boxes.to(deltas.dtype)\n\n        widths = boxes[:, 2] - boxes[:, 0]\n        heights = boxes[:, 3] - boxes[:, 1]\n        ctr_x = boxes[:, 0] + 0.5 * widths\n        ctr_y = boxes[:, 1] + 0.5 * heights\n\n        wx, wy, ww, wh = self.weights\n        dx = deltas[:, 0::4] / wx\n        dy = deltas[:, 1::4] / wy\n        dw = deltas[:, 2::4] / ww\n        dh = deltas[:, 3::4] / wh\n\n        # Prevent sending too large values into torch.exp()\n        dw = torch.clamp(dw, max=self.scale_clamp)\n        dh = torch.clamp(dh, max=self.scale_clamp)\n\n        pred_ctr_x = dx * widths[:, None] + ctr_x[:, None]\n        pred_ctr_y = dy * heights[:, None] + ctr_y[:, None]\n        pred_w = torch.exp(dw) * widths[:, None]\n        pred_h = torch.exp(dh) * heights[:, None]\n\n        x1 = pred_ctr_x - 0.5 * pred_w\n        y1 = pred_ctr_y - 0.5 * pred_h\n        x2 = pred_ctr_x + 0.5 * pred_w\n        y2 = pred_ctr_y + 0.5 * pred_h\n        pred_boxes = torch.stack((x1, y1, x2, y2), dim=-1)\n        return pred_boxes.reshape(deltas.shape)\n\n\n@torch.jit.script\nclass Box2BoxTransformRotated(object):\n    \"\"\"\n    The box-to-box transform defined in Rotated R-CNN. The transformation is parameterized\n    by 5 deltas: (dx, dy, dw, dh, da). The transformation scales the box's width and height\n    by exp(dw), exp(dh), shifts a box's center by the offset (dx * width, dy * height),\n    and rotate a box's angle by da (radians).\n    Note: angles of deltas are in radians while angles of boxes are in degrees.\n    \"\"\"\n\n    def __init__(\n        self,\n        weights: Tuple[float, float, float, float, float],\n        scale_clamp: float = _DEFAULT_SCALE_CLAMP,\n    ):\n        \"\"\"\n        Args:\n            weights (5-element tuple): Scaling factors that are applied to the\n                (dx, dy, dw, dh, da) deltas. These are treated as\n                hyperparameters of the system.\n            scale_clamp (float): When predicting deltas, the predicted box scaling\n                factors (dw and dh) are clamped such that they are <= scale_clamp.\n        \"\"\"\n        self.weights = weights\n        self.scale_clamp = scale_clamp\n\n    def get_deltas(self, src_boxes, target_boxes):\n        \"\"\"\n        Get box regression transformation deltas (dx, dy, dw, dh, da) that can be used\n        to transform the `src_boxes` into the `target_boxes`. That is, the relation\n        ``target_boxes == self.apply_deltas(deltas, src_boxes)`` is true (unless\n        any delta is too large and is clamped).\n\n        Args:\n            src_boxes (Tensor): Nx5 source boxes, e.g., object proposals\n            target_boxes (Tensor): Nx5 target of the transformation, e.g., ground-truth\n                boxes.\n        \"\"\"\n        assert isinstance(src_boxes, torch.Tensor), type(src_boxes)\n        assert isinstance(target_boxes, torch.Tensor), type(target_boxes)\n\n        src_ctr_x, src_ctr_y, src_widths, src_heights, src_angles = torch.unbind(src_boxes, dim=1)\n\n        target_ctr_x, target_ctr_y, target_widths, target_heights, target_angles = torch.unbind(\n            target_boxes, dim=1\n        )\n\n        wx, wy, ww, wh, wa = self.weights\n        dx = wx * (target_ctr_x - src_ctr_x) / src_widths\n        dy = wy * (target_ctr_y - src_ctr_y) / src_heights\n        dw = ww * torch.log(target_widths / src_widths)\n        dh = wh * torch.log(target_heights / src_heights)\n        # Angles of deltas are in radians while angles of boxes are in degrees.\n        # the conversion to radians serve as a way to normalize the values\n        da = target_angles - src_angles\n        da = (da + 180.0) % 360.0 - 180.0  # make it in [-180, 180)\n        da *= wa * math.pi / 180.0\n\n        deltas = torch.stack((dx, dy, dw, dh, da), dim=1)\n        assert (\n            (src_widths > 0).all().item()\n        ), \"Input boxes to Box2BoxTransformRotated are not valid!\"\n        return deltas\n\n    def apply_deltas(self, deltas, boxes):\n        \"\"\"\n        Apply transformation `deltas` (dx, dy, dw, dh, da) to `boxes`.\n\n        Args:\n            deltas (Tensor): transformation deltas of shape (N, k*5).\n                deltas[i] represents box transformation for the single box boxes[i].\n            boxes (Tensor): boxes to transform, of shape (N, 5)\n        \"\"\"\n        assert deltas.shape[1] % 5 == 0 and boxes.shape[1] == 5\n\n        boxes = boxes.to(deltas.dtype).unsqueeze(2)\n\n        ctr_x = boxes[:, 0]\n        ctr_y = boxes[:, 1]\n        widths = boxes[:, 2]\n        heights = boxes[:, 3]\n        angles = boxes[:, 4]\n\n        wx, wy, ww, wh, wa = self.weights\n\n        dx = deltas[:, 0::5] / wx\n        dy = deltas[:, 1::5] / wy\n        dw = deltas[:, 2::5] / ww\n        dh = deltas[:, 3::5] / wh\n        da = deltas[:, 4::5] / wa\n\n        # Prevent sending too large values into torch.exp()\n        dw = torch.clamp(dw, max=self.scale_clamp)\n        dh = torch.clamp(dh, max=self.scale_clamp)\n\n        pred_boxes = torch.zeros_like(deltas)\n        pred_boxes[:, 0::5] = dx * widths + ctr_x  # x_ctr\n        pred_boxes[:, 1::5] = dy * heights + ctr_y  # y_ctr\n        pred_boxes[:, 2::5] = torch.exp(dw) * widths  # width\n        pred_boxes[:, 3::5] = torch.exp(dh) * heights  # height\n\n        # Following original RRPN implementation,\n        # angles of deltas are in radians while angles of boxes are in degrees.\n        pred_angle = da * 180.0 / math.pi + angles\n        pred_angle = (pred_angle + 180.0) % 360.0 - 180.0  # make it in [-180, 180)\n\n        pred_boxes[:, 4::5] = pred_angle\n\n        return pred_boxes\n\n\nclass Box2BoxTransformLinear(object):\n    \"\"\"\n    The linear box-to-box transform defined in FCOS. The transformation is parameterized\n    by the distance from the center of (square) src box to 4 edges of the target box.\n    \"\"\"\n\n    def __init__(self, normalize_by_size=True):\n        \"\"\"\n        Args:\n            normalize_by_size: normalize deltas by the size of src (anchor) boxes.\n        \"\"\"\n        self.normalize_by_size = normalize_by_size\n\n    def get_deltas(self, src_boxes, target_boxes):\n        \"\"\"\n        Get box regression transformation deltas (dx1, dy1, dx2, dy2) that can be used\n        to transform the `src_boxes` into the `target_boxes`. That is, the relation\n        ``target_boxes == self.apply_deltas(deltas, src_boxes)`` is true.\n        The center of src must be inside target boxes.\n\n        Args:\n            src_boxes (Tensor): square source boxes, e.g., anchors\n            target_boxes (Tensor): target of the transformation, e.g., ground-truth\n                boxes.\n        \"\"\"\n        assert isinstance(src_boxes, torch.Tensor), type(src_boxes)\n        assert isinstance(target_boxes, torch.Tensor), type(target_boxes)\n\n        src_ctr_x = 0.5 * (src_boxes[:, 0] + src_boxes[:, 2])\n        src_ctr_y = 0.5 * (src_boxes[:, 1] + src_boxes[:, 3])\n\n        target_l = src_ctr_x - target_boxes[:, 0]\n        target_t = src_ctr_y - target_boxes[:, 1]\n        target_r = target_boxes[:, 2] - src_ctr_x\n        target_b = target_boxes[:, 3] - src_ctr_y\n\n        deltas = torch.stack((target_l, target_t, target_r, target_b), dim=1)\n        if self.normalize_by_size:\n            stride_w = src_boxes[:, 2] - src_boxes[:, 0]\n            stride_h = src_boxes[:, 3] - src_boxes[:, 1]\n            strides = torch.stack([stride_w, stride_h, stride_w, stride_h], axis=1)\n            deltas = deltas / strides\n\n        return deltas\n\n    def apply_deltas(self, deltas, boxes):\n        \"\"\"\n        Apply transformation `deltas` (dx1, dy1, dx2, dy2) to `boxes`.\n\n        Args:\n            deltas (Tensor): transformation deltas of shape (N, k*4), where k >= 1.\n                deltas[i] represents k potentially different class-specific\n                box transformations for the single box boxes[i].\n            boxes (Tensor): boxes to transform, of shape (N, 4)\n        \"\"\"\n        # Ensure the output is a valid box. See Sec 2.1 of https://arxiv.org/abs/2006.09214\n        deltas = F.relu(deltas)\n        boxes = boxes.to(deltas.dtype)\n\n        ctr_x = 0.5 * (boxes[:, 0] + boxes[:, 2])\n        ctr_y = 0.5 * (boxes[:, 1] + boxes[:, 3])\n        if self.normalize_by_size:\n            stride_w = boxes[:, 2] - boxes[:, 0]\n            stride_h = boxes[:, 3] - boxes[:, 1]\n            strides = torch.stack([stride_w, stride_h, stride_w, stride_h], axis=1)\n            deltas = deltas * strides\n\n        l = deltas[:, 0::4]\n        t = deltas[:, 1::4]\n        r = deltas[:, 2::4]\n        b = deltas[:, 3::4]\n\n        pred_boxes = torch.zeros_like(deltas)\n        pred_boxes[:, 0::4] = ctr_x[:, None] - l  # x1\n        pred_boxes[:, 1::4] = ctr_y[:, None] - t  # y1\n        pred_boxes[:, 2::4] = ctr_x[:, None] + r  # x2\n        pred_boxes[:, 3::4] = ctr_y[:, None] + b  # y2\n        return pred_boxes\n\n\ndef _dense_box_regression_loss(\n    anchors: List[Union[Boxes, torch.Tensor]],\n    box2box_transform: Box2BoxTransform,\n    pred_anchor_deltas: List[torch.Tensor],\n    gt_boxes: List[torch.Tensor],\n    fg_mask: torch.Tensor,\n    box_reg_loss_type=\"smooth_l1\",\n    smooth_l1_beta=0.0,\n):\n    \"\"\"\n    Compute loss for dense multi-level box regression.\n    Loss is accumulated over ``fg_mask``.\n\n    Args:\n        anchors: #lvl anchor boxes, each is (HixWixA, 4)\n        pred_anchor_deltas: #lvl predictions, each is (N, HixWixA, 4)\n        gt_boxes: N ground truth boxes, each has shape (R, 4) (R = sum(Hi * Wi * A))\n        fg_mask: the foreground boolean mask of shape (N, R) to compute loss on\n        box_reg_loss_type (str): Loss type to use. Supported losses: \"smooth_l1\", \"giou\",\n            \"diou\", \"ciou\".\n        smooth_l1_beta (float): beta parameter for the smooth L1 regression loss. Default to\n            use L1 loss. Only used when `box_reg_loss_type` is \"smooth_l1\"\n    \"\"\"\n    if isinstance(anchors[0], Boxes):\n        anchors = type(anchors[0]).cat(anchors).tensor  # (R, 4)\n    else:\n        anchors = cat(anchors)\n    if box_reg_loss_type == \"smooth_l1\":\n        gt_anchor_deltas = [box2box_transform.get_deltas(anchors, k) for k in gt_boxes]\n        gt_anchor_deltas = torch.stack(gt_anchor_deltas)  # (N, R, 4)\n        loss_box_reg = smooth_l1_loss(\n            cat(pred_anchor_deltas, dim=1)[fg_mask],\n            gt_anchor_deltas[fg_mask],\n            beta=smooth_l1_beta,\n            reduction=\"sum\",\n        )\n    elif box_reg_loss_type == \"giou\":\n        pred_boxes = [\n            box2box_transform.apply_deltas(k, anchors) for k in cat(pred_anchor_deltas, dim=1)\n        ]\n        loss_box_reg = giou_loss(\n            torch.stack(pred_boxes)[fg_mask], torch.stack(gt_boxes)[fg_mask], reduction=\"sum\"\n        )\n    elif box_reg_loss_type == \"diou\":\n        pred_boxes = [\n            box2box_transform.apply_deltas(k, anchors) for k in cat(pred_anchor_deltas, dim=1)\n        ]\n        loss_box_reg = diou_loss(\n            torch.stack(pred_boxes)[fg_mask], torch.stack(gt_boxes)[fg_mask], reduction=\"sum\"\n        )\n    elif box_reg_loss_type == \"ciou\":\n        pred_boxes = [\n            box2box_transform.apply_deltas(k, anchors) for k in cat(pred_anchor_deltas, dim=1)\n        ]\n        loss_box_reg = ciou_loss(\n            torch.stack(pred_boxes)[fg_mask], torch.stack(gt_boxes)[fg_mask], reduction=\"sum\"\n        )\n    else:\n        raise ValueError(f\"Invalid dense box regression loss type '{box_reg_loss_type}'\")\n    return loss_box_reg\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/matcher.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom typing import List\nimport torch\n\nfrom detectron2.layers import nonzero_tuple\n\n\n# TODO: the name is too general\nclass Matcher(object):\n    \"\"\"\n    This class assigns to each predicted \"element\" (e.g., a box) a ground-truth\n    element. Each predicted element will have exactly zero or one matches; each\n    ground-truth element may be matched to zero or more predicted elements.\n\n    The matching is determined by the MxN match_quality_matrix, that characterizes\n    how well each (ground-truth, prediction)-pair match each other. For example,\n    if the elements are boxes, this matrix may contain box intersection-over-union\n    overlap values.\n\n    The matcher returns (a) a vector of length N containing the index of the\n    ground-truth element m in [0, M) that matches to prediction n in [0, N).\n    (b) a vector of length N containing the labels for each prediction.\n    \"\"\"\n\n    def __init__(\n        self, thresholds: List[float], labels: List[int], allow_low_quality_matches: bool = False\n    ):\n        \"\"\"\n        Args:\n            thresholds (list): a list of thresholds used to stratify predictions\n                into levels.\n            labels (list): a list of values to label predictions belonging at\n                each level. A label can be one of {-1, 0, 1} signifying\n                {ignore, negative class, positive class}, respectively.\n            allow_low_quality_matches (bool): if True, produce additional matches\n                for predictions with maximum match quality lower than high_threshold.\n                See set_low_quality_matches_ for more details.\n\n            For example,\n                thresholds = [0.3, 0.5]\n                labels = [0, -1, 1]\n                All predictions with iou < 0.3 will be marked with 0 and\n                thus will be considered as false positives while training.\n                All predictions with 0.3 <= iou < 0.5 will be marked with -1 and\n                thus will be ignored.\n                All predictions with 0.5 <= iou will be marked with 1 and\n                thus will be considered as true positives.\n        \"\"\"\n        # Add -inf and +inf to first and last position in thresholds\n        thresholds = thresholds[:]\n        assert thresholds[0] > 0\n        thresholds.insert(0, -float(\"inf\"))\n        thresholds.append(float(\"inf\"))\n        # Currently torchscript does not support all + generator\n        assert all([low <= high for (low, high) in zip(thresholds[:-1], thresholds[1:])])\n        assert all([l in [-1, 0, 1] for l in labels])\n        assert len(labels) == len(thresholds) - 1\n        self.thresholds = thresholds\n        self.labels = labels\n        self.allow_low_quality_matches = allow_low_quality_matches\n\n    def __call__(self, match_quality_matrix):\n        \"\"\"\n        Args:\n            match_quality_matrix (Tensor[float]): an MxN tensor, containing the\n                pairwise quality between M ground-truth elements and N predicted\n                elements. All elements must be >= 0 (due to the us of `torch.nonzero`\n                for selecting indices in :meth:`set_low_quality_matches_`).\n\n        Returns:\n            matches (Tensor[int64]): a vector of length N, where matches[i] is a matched\n                ground-truth index in [0, M)\n            match_labels (Tensor[int8]): a vector of length N, where pred_labels[i] indicates\n                whether a prediction is a true or false positive or ignored\n        \"\"\"\n        assert match_quality_matrix.dim() == 2\n        if match_quality_matrix.numel() == 0:\n            default_matches = match_quality_matrix.new_full(\n                (match_quality_matrix.size(1),), 0, dtype=torch.int64\n            )\n            # When no gt boxes exist, we define IOU = 0 and therefore set labels\n            # to `self.labels[0]`, which usually defaults to background class 0\n            # To choose to ignore instead, can make labels=[-1,0,-1,1] + set appropriate thresholds\n            default_match_labels = match_quality_matrix.new_full(\n                (match_quality_matrix.size(1),), self.labels[0], dtype=torch.int8\n            )\n            return default_matches, default_match_labels\n\n        assert torch.all(match_quality_matrix >= 0)\n\n        # match_quality_matrix is M (gt) x N (predicted)\n        # Max over gt elements (dim 0) to find best gt candidate for each prediction\n        matched_vals, matches = match_quality_matrix.max(dim=0)\n\n        match_labels = matches.new_full(matches.size(), 1, dtype=torch.int8)\n\n        for (l, low, high) in zip(self.labels, self.thresholds[:-1], self.thresholds[1:]):\n            low_high = (matched_vals >= low) & (matched_vals < high)\n            match_labels[low_high] = l\n\n        if self.allow_low_quality_matches:\n            self.set_low_quality_matches_(match_labels, match_quality_matrix)\n\n        return matches, match_labels\n\n    def set_low_quality_matches_(self, match_labels, match_quality_matrix):\n        \"\"\"\n        Produce additional matches for predictions that have only low-quality matches.\n        Specifically, for each ground-truth G find the set of predictions that have\n        maximum overlap with it (including ties); for each prediction in that set, if\n        it is unmatched, then match it to the ground-truth G.\n\n        This function implements the RPN assignment case (i) in Sec. 3.1.2 of\n        :paper:`Faster R-CNN`.\n        \"\"\"\n        # For each gt, find the prediction with which it has highest quality\n        highest_quality_foreach_gt, _ = match_quality_matrix.max(dim=1)\n        # Find the highest quality match available, even if it is low, including ties.\n        # Note that the matches qualities must be positive due to the use of\n        # `torch.nonzero`.\n        _, pred_inds_with_highest_quality = nonzero_tuple(\n            match_quality_matrix == highest_quality_foreach_gt[:, None]\n        )\n        # If an anchor was labeled positive only due to a low-quality match\n        # with gt_A, but it has larger overlap with gt_B, it's matched index will still be gt_B.\n        # This follows the implementation in Detectron, and is found to have no significant impact.\n        match_labels[pred_inds_with_highest_quality] = 1\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/meta_arch/__init__.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom .build import META_ARCH_REGISTRY, build_model  # isort:skip\n\nfrom .panoptic_fpn import PanopticFPN\n\n# import all the meta_arch, so they will be registered\nfrom .rcnn import GeneralizedRCNN, ProposalNetwork\nfrom .dense_detector import DenseDetector\nfrom .retinanet import RetinaNet\nfrom .fcos import FCOS\nfrom .semantic_seg import SEM_SEG_HEADS_REGISTRY, SemanticSegmentor, build_sem_seg_head\n\n\n__all__ = list(globals().keys())\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/meta_arch/build.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport torch\n\nfrom detectron2.utils.logger import _log_api_usage\nfrom detectron2.utils.registry import Registry\n\nMETA_ARCH_REGISTRY = Registry(\"META_ARCH\")  # noqa F401 isort:skip\nMETA_ARCH_REGISTRY.__doc__ = \"\"\"\nRegistry for meta-architectures, i.e. the whole model.\n\nThe registered object will be called with `obj(cfg)`\nand expected to return a `nn.Module` object.\n\"\"\"\n\n\ndef build_model(cfg):\n    \"\"\"\n    Build the whole model architecture, defined by ``cfg.MODEL.META_ARCHITECTURE``.\n    Note that it does not load any weights from ``cfg``.\n    \"\"\"\n    meta_arch = cfg.MODEL.META_ARCHITECTURE\n    model = META_ARCH_REGISTRY.get(meta_arch)(cfg)\n    model.to(torch.device(cfg.MODEL.DEVICE))\n    _log_api_usage(\"modeling.meta_arch.\" + meta_arch)\n    return model\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/meta_arch/dense_detector.py",
    "content": "import numpy as np\nfrom typing import Dict, List, Optional, Tuple\nimport torch\nfrom torch import Tensor, nn\n\nfrom detectron2.data.detection_utils import convert_image_to_rgb\nfrom detectron2.modeling import Backbone\nfrom detectron2.structures import Boxes, ImageList, Instances\nfrom detectron2.utils.events import get_event_storage\n\nfrom ..postprocessing import detector_postprocess\n\n\ndef permute_to_N_HWA_K(tensor, K: int):\n    \"\"\"\n    Transpose/reshape a tensor from (N, (Ai x K), H, W) to (N, (HxWxAi), K)\n    \"\"\"\n    assert tensor.dim() == 4, tensor.shape\n    N, _, H, W = tensor.shape\n    tensor = tensor.view(N, -1, K, H, W)\n    tensor = tensor.permute(0, 3, 4, 1, 2)\n    tensor = tensor.reshape(N, -1, K)  # Size=(N,HWA,K)\n    return tensor\n\n\nclass DenseDetector(nn.Module):\n    \"\"\"\n    Base class for dense detector. We define a dense detector as a fully-convolutional model that\n    makes per-pixel (i.e. dense) predictions.\n    \"\"\"\n\n    def __init__(\n        self,\n        backbone: Backbone,\n        head: nn.Module,\n        head_in_features: Optional[List[str]] = None,\n        *,\n        pixel_mean,\n        pixel_std,\n    ):\n        \"\"\"\n        Args:\n            backbone: backbone module\n            head: head module\n            head_in_features: backbone features to use in head. Default to all backbone features.\n            pixel_mean (Tuple[float]):\n                Values to be used for image normalization (BGR order).\n                To train on images of different number of channels, set different mean & std.\n                Default values are the mean pixel value from ImageNet: [103.53, 116.28, 123.675]\n            pixel_std (Tuple[float]):\n                When using pre-trained models in Detectron1 or any MSRA models,\n                std has been absorbed into its conv1 weights, so the std needs to be set 1.\n                Otherwise, you can use [57.375, 57.120, 58.395] (ImageNet std)\n        \"\"\"\n        super().__init__()\n\n        self.backbone = backbone\n        self.head = head\n        if head_in_features is None:\n            shapes = self.backbone.output_shape()\n            self.head_in_features = sorted(shapes.keys(), key=lambda x: shapes[x].stride)\n        else:\n            self.head_in_features = head_in_features\n\n        self.register_buffer(\"pixel_mean\", torch.tensor(pixel_mean).view(-1, 1, 1), False)\n        self.register_buffer(\"pixel_std\", torch.tensor(pixel_std).view(-1, 1, 1), False)\n\n    @property\n    def device(self):\n        return self.pixel_mean.device\n\n    def forward(self, batched_inputs: List[Dict[str, Tensor]]):\n        \"\"\"\n        Args:\n            batched_inputs: a list, batched outputs of :class:`DatasetMapper` .\n                Each item in the list contains the inputs for one image.\n                For now, each item in the list is a dict that contains:\n\n                * image: Tensor, image in (C, H, W) format.\n                * instances: Instances\n\n                Other information that's included in the original dicts, such as:\n\n                * \"height\", \"width\" (int): the output resolution of the model, used in inference.\n                  See :meth:`postprocess` for details.\n\n        Returns:\n            In training, dict[str, Tensor]: mapping from a named loss to a tensor storing the\n            loss. Used during training only. In inference, the standard output format, described\n            in :doc:`/tutorials/models`.\n        \"\"\"\n        images = self.preprocess_image(batched_inputs)\n        features = self.backbone(images.tensor)\n        features = [features[f] for f in self.head_in_features]\n        predictions = self.head(features)\n\n        if self.training:\n            assert not torch.jit.is_scripting(), \"Not supported\"\n            assert \"instances\" in batched_inputs[0], \"Instance annotations are missing in training!\"\n            gt_instances = [x[\"instances\"].to(self.device) for x in batched_inputs]\n            return self.forward_training(images, features, predictions, gt_instances)\n        else:\n            results = self.forward_inference(images, features, predictions)\n            if torch.jit.is_scripting():\n                return results\n\n            processed_results = []\n            for results_per_image, input_per_image, image_size in zip(\n                results, batched_inputs, images.image_sizes\n            ):\n                height = input_per_image.get(\"height\", image_size[0])\n                width = input_per_image.get(\"width\", image_size[1])\n                r = detector_postprocess(results_per_image, height, width)\n                processed_results.append({\"instances\": r})\n            return processed_results\n\n    def forward_training(self, images, features, predictions, gt_instances):\n        raise NotImplementedError()\n\n    def preprocess_image(self, batched_inputs: List[Dict[str, Tensor]]):\n        \"\"\"\n        Normalize, pad and batch the input images.\n        \"\"\"\n        images = [x[\"image\"].to(self.device) for x in batched_inputs]\n        images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n        images = ImageList.from_tensors(images, self.backbone.size_divisibility)\n        return images\n\n    def _transpose_dense_predictions(\n        self, predictions: List[List[Tensor]], dims_per_anchor: List[int]\n    ) -> List[List[Tensor]]:\n        \"\"\"\n        Transpose the dense per-level predictions.\n\n        Args:\n            predictions: a list of outputs, each is a list of per-level\n                predictions with shape (N, Ai x K, Hi, Wi), where N is the\n                number of images, Ai is the number of anchors per location on\n                level i, K is the dimension of predictions per anchor.\n            dims_per_anchor: the value of K for each predictions. e.g. 4 for\n                box prediction, #classes for classification prediction.\n\n        Returns:\n            List[List[Tensor]]: each prediction is transposed to (N, Hi x Wi x Ai, K).\n        \"\"\"\n        assert len(predictions) == len(dims_per_anchor)\n        res: List[List[Tensor]] = []\n        for pred, dim_per_anchor in zip(predictions, dims_per_anchor):\n            pred = [permute_to_N_HWA_K(x, dim_per_anchor) for x in pred]\n            res.append(pred)\n        return res\n\n    def _ema_update(self, name: str, value: float, initial_value: float, momentum: float = 0.9):\n        \"\"\"\n        Apply EMA update to `self.name` using `value`.\n\n        This is mainly used for loss normalizer. In Detectron1, loss is normalized by number\n        of foreground samples in the batch. When batch size is 1 per GPU, #foreground has a\n        large variance and using it lead to lower performance. Therefore we maintain an EMA of\n        #foreground to stabilize the normalizer.\n\n        Args:\n            name: name of the normalizer\n            value: the new value to update\n            initial_value: the initial value to start with\n            momentum: momentum of EMA\n\n        Returns:\n            float: the updated EMA value\n        \"\"\"\n        if hasattr(self, name):\n            old = getattr(self, name)\n        else:\n            old = initial_value\n        new = old * momentum + value * (1 - momentum)\n        setattr(self, name, new)\n        return new\n\n    def _decode_per_level_predictions(\n        self,\n        anchors: Boxes,\n        pred_scores: Tensor,\n        pred_deltas: Tensor,\n        score_thresh: float,\n        topk_candidates: int,\n        image_size: Tuple[int, int],\n    ) -> Instances:\n        \"\"\"\n        Decode boxes and classification predictions of one featuer level, by\n        the following steps:\n        1. filter the predictions based on score threshold and top K scores.\n        2. transform the box regression outputs\n        3. return the predicted scores, classes and boxes\n\n        Args:\n            anchors: Boxes, anchor for this feature level\n            pred_scores: HxWxA,K\n            pred_deltas: HxWxA,4\n\n        Returns:\n            Instances: with field \"scores\", \"pred_boxes\", \"pred_classes\".\n        \"\"\"\n        # Apply two filtering to make NMS faster.\n        # 1. Keep boxes with confidence score higher than threshold\n        keep_idxs = pred_scores > score_thresh\n        pred_scores = pred_scores[keep_idxs]\n        topk_idxs = torch.nonzero(keep_idxs)  # Kx2\n\n        # 2. Keep top k top scoring boxes only\n        num_topk = min(topk_candidates, topk_idxs.size(0))\n        pred_scores, idxs = pred_scores.topk(num_topk)\n        topk_idxs = topk_idxs[idxs]\n\n        anchor_idxs, classes_idxs = topk_idxs.unbind(dim=1)\n\n        pred_boxes = self.box2box_transform.apply_deltas(\n            pred_deltas[anchor_idxs], anchors.tensor[anchor_idxs]\n        )\n        return Instances(\n            image_size, pred_boxes=Boxes(pred_boxes), scores=pred_scores, pred_classes=classes_idxs\n        )\n\n    def _decode_multi_level_predictions(\n        self,\n        anchors: List[Boxes],\n        pred_scores: List[Tensor],\n        pred_deltas: List[Tensor],\n        score_thresh: float,\n        topk_candidates: int,\n        image_size: Tuple[int, int],\n    ) -> Instances:\n        \"\"\"\n        Run `_decode_per_level_predictions` for all feature levels and concat the results.\n        \"\"\"\n        predictions = [\n            self._decode_per_level_predictions(\n                anchors_i,\n                box_cls_i,\n                box_reg_i,\n                self.test_score_thresh,\n                self.test_topk_candidates,\n                image_size,\n            )\n            # Iterate over every feature level\n            for box_cls_i, box_reg_i, anchors_i in zip(pred_scores, pred_deltas, anchors)\n        ]\n        return predictions[0].cat(predictions)  # 'Instances.cat' is not scriptale but this is\n\n    def visualize_training(self, batched_inputs, results):\n        \"\"\"\n        A function used to visualize ground truth images and final network predictions.\n        It shows ground truth bounding boxes on the original image and up to 20\n        predicted object bounding boxes on the original image.\n\n        Args:\n            batched_inputs (list): a list that contains input to the model.\n            results (List[Instances]): a list of #images elements returned by forward_inference().\n        \"\"\"\n        from detectron2.utils.visualizer import Visualizer\n\n        assert len(batched_inputs) == len(\n            results\n        ), \"Cannot visualize inputs and results of different sizes\"\n        storage = get_event_storage()\n        max_boxes = 20\n\n        image_index = 0  # only visualize a single image\n        img = batched_inputs[image_index][\"image\"]\n        img = convert_image_to_rgb(img.permute(1, 2, 0), self.input_format)\n        v_gt = Visualizer(img, None)\n        v_gt = v_gt.overlay_instances(boxes=batched_inputs[image_index][\"instances\"].gt_boxes)\n        anno_img = v_gt.get_image()\n        processed_results = detector_postprocess(results[image_index], img.shape[0], img.shape[1])\n        predicted_boxes = processed_results.pred_boxes.tensor.detach().cpu().numpy()\n\n        v_pred = Visualizer(img, None)\n        v_pred = v_pred.overlay_instances(boxes=predicted_boxes[0:max_boxes])\n        prop_img = v_pred.get_image()\n        vis_img = np.vstack((anno_img, prop_img))\n        vis_img = vis_img.transpose(2, 0, 1)\n        vis_name = f\"Top: GT bounding boxes; Bottom: {max_boxes} Highest Scoring Results\"\n        storage.put_image(vis_name, vis_img)\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/meta_arch/fcos.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport logging\nfrom typing import List, Optional, Tuple\nimport torch\nfrom fvcore.nn import sigmoid_focal_loss_jit\nfrom torch import Tensor, nn\nfrom torch.nn import functional as F\n\nfrom detectron2.layers import ShapeSpec, batched_nms\nfrom detectron2.structures import Boxes, ImageList, Instances, pairwise_point_box_distance\nfrom detectron2.utils.events import get_event_storage\n\nfrom ..anchor_generator import DefaultAnchorGenerator\nfrom ..backbone import Backbone\nfrom ..box_regression import Box2BoxTransformLinear, _dense_box_regression_loss\nfrom .dense_detector import DenseDetector\nfrom .retinanet import RetinaNetHead\n\n__all__ = [\"FCOS\"]\n\n\nlogger = logging.getLogger(__name__)\n\n\nclass FCOS(DenseDetector):\n    \"\"\"\n    Implement FCOS in :paper:`fcos`.\n    \"\"\"\n\n    def __init__(\n        self,\n        *,\n        backbone: Backbone,\n        head: nn.Module,\n        head_in_features: Optional[List[str]] = None,\n        box2box_transform=None,\n        num_classes,\n        center_sampling_radius: float = 1.5,\n        focal_loss_alpha=0.25,\n        focal_loss_gamma=2.0,\n        test_score_thresh=0.2,\n        test_topk_candidates=1000,\n        test_nms_thresh=0.6,\n        max_detections_per_image=100,\n        pixel_mean,\n        pixel_std,\n    ):\n        \"\"\"\n        Args:\n            center_sampling_radius: radius of the \"center\" of a groundtruth box,\n                within which all anchor points are labeled positive.\n            Other arguments mean the same as in :class:`RetinaNet`.\n        \"\"\"\n        super().__init__(\n            backbone, head, head_in_features, pixel_mean=pixel_mean, pixel_std=pixel_std\n        )\n\n        self.num_classes = num_classes\n\n        # FCOS uses one anchor point per location.\n        # We represent the anchor point by a box whose size equals the anchor stride.\n        feature_shapes = backbone.output_shape()\n        fpn_strides = [feature_shapes[k].stride for k in self.head_in_features]\n        self.anchor_generator = DefaultAnchorGenerator(\n            sizes=[[k] for k in fpn_strides], aspect_ratios=[1.0], strides=fpn_strides\n        )\n\n        # FCOS parameterizes box regression by a linear transform,\n        # where predictions are normalized by anchor stride (equal to anchor size).\n        if box2box_transform is None:\n            box2box_transform = Box2BoxTransformLinear(normalize_by_size=True)\n        self.box2box_transform = box2box_transform\n\n        self.center_sampling_radius = float(center_sampling_radius)\n\n        # Loss parameters:\n        self.focal_loss_alpha = focal_loss_alpha\n        self.focal_loss_gamma = focal_loss_gamma\n\n        # Inference parameters:\n        self.test_score_thresh = test_score_thresh\n        self.test_topk_candidates = test_topk_candidates\n        self.test_nms_thresh = test_nms_thresh\n        self.max_detections_per_image = max_detections_per_image\n\n    def forward_training(self, images, features, predictions, gt_instances):\n        # Transpose the Hi*Wi*A dimension to the middle:\n        pred_logits, pred_anchor_deltas, pred_centerness = self._transpose_dense_predictions(\n            predictions, [self.num_classes, 4, 1]\n        )\n        anchors = self.anchor_generator(features)\n        gt_labels, gt_boxes = self.label_anchors(anchors, gt_instances)\n        return self.losses(\n            anchors, pred_logits, gt_labels, pred_anchor_deltas, gt_boxes, pred_centerness\n        )\n\n    @torch.no_grad()\n    def match_anchors(self, anchors: List[Boxes], gt_instances: List[Instances]):\n        \"\"\"\n        Match anchors with ground truth boxes.\n\n        Args:\n            anchors: #level boxes, from the highest resolution to lower resolution\n            gt_instances: ground truth instances per image\n\n        Returns:\n            List[Tensor]:\n                #image tensors, each is a vector of matched gt\n                indices (or -1 for unmatched anchors) for all anchors.\n        \"\"\"\n        num_anchors_per_level = [len(x) for x in anchors]\n        anchors = Boxes.cat(anchors)  # Rx4\n        anchor_centers = anchors.get_centers()  # Rx2\n        anchor_sizes = anchors.tensor[:, 2] - anchors.tensor[:, 0]  # R\n\n        lower_bound = anchor_sizes * 4\n        lower_bound[: num_anchors_per_level[0]] = 0\n        upper_bound = anchor_sizes * 8\n        upper_bound[-num_anchors_per_level[-1] :] = float(\"inf\")\n\n        matched_indices = []\n        for gt_per_image in gt_instances:\n            gt_centers = gt_per_image.gt_boxes.get_centers()  # Nx2\n            # FCOS with center sampling: anchor point must be close enough to gt center.\n            pairwise_match = (anchor_centers[:, None, :] - gt_centers[None, :, :]).abs_().max(\n                dim=2\n            ).values < self.center_sampling_radius * anchor_sizes[:, None]\n            pairwise_dist = pairwise_point_box_distance(anchor_centers, gt_per_image.gt_boxes)\n\n            # The original FCOS anchor matching rule: anchor point must be inside gt\n            pairwise_match &= pairwise_dist.min(dim=2).values > 0\n\n            # Multilevel anchor matching in FCOS: each anchor is only responsible\n            # for certain scale range.\n            pairwise_dist = pairwise_dist.max(dim=2).values\n            pairwise_match &= (pairwise_dist > lower_bound[:, None]) & (\n                pairwise_dist < upper_bound[:, None]\n            )\n\n            # Match the GT box with minimum area, if there are multiple GT matches\n            gt_areas = gt_per_image.gt_boxes.area()  # N\n            pairwise_match = pairwise_match.to(torch.float32) * (1e8 - gt_areas[None, :])\n            min_values, matched_idx = pairwise_match.max(dim=1)  # R, per-anchor match\n            matched_idx[min_values < 1e-5] = -1  # Unmatched anchors are assigned -1\n\n            matched_indices.append(matched_idx)\n        return matched_indices\n\n    @torch.no_grad()\n    def label_anchors(self, anchors, gt_instances):\n        \"\"\"\n        Same interface as :meth:`RetinaNet.label_anchors`, but implemented with FCOS\n        anchor matching rule.\n\n        Unlike RetinaNet, there are no ignored anchors.\n        \"\"\"\n        matched_indices = self.match_anchors(anchors, gt_instances)\n\n        matched_labels, matched_boxes = [], []\n        for gt_index, gt_per_image in zip(matched_indices, gt_instances):\n            label = gt_per_image.gt_classes[gt_index.clip(min=0)]\n            label[gt_index < 0] = self.num_classes  # background\n\n            matched_gt_boxes = gt_per_image.gt_boxes[gt_index.clip(min=0)]\n\n            matched_labels.append(label)\n            matched_boxes.append(matched_gt_boxes)\n        return matched_labels, matched_boxes\n\n    def losses(\n        self, anchors, pred_logits, gt_labels, pred_anchor_deltas, gt_boxes, pred_centerness\n    ):\n        \"\"\"\n        This method is almost identical to :meth:`RetinaNet.losses`, with an extra\n        \"loss_centerness\" in the returned dict.\n        \"\"\"\n        num_images = len(gt_labels)\n        gt_labels = torch.stack(gt_labels)  # (N, R)\n\n        pos_mask = (gt_labels >= 0) & (gt_labels != self.num_classes)\n        num_pos_anchors = pos_mask.sum().item()\n        get_event_storage().put_scalar(\"num_pos_anchors\", num_pos_anchors / num_images)\n        normalizer = self._ema_update(\"loss_normalizer\", max(num_pos_anchors, 1), 300)\n\n        # classification and regression loss\n        gt_labels_target = F.one_hot(gt_labels, num_classes=self.num_classes + 1)[\n            :, :, :-1\n        ]  # no loss for the last (background) class\n        loss_cls = sigmoid_focal_loss_jit(\n            torch.cat(pred_logits, dim=1),\n            gt_labels_target.to(pred_logits[0].dtype),\n            alpha=self.focal_loss_alpha,\n            gamma=self.focal_loss_gamma,\n            reduction=\"sum\",\n        )\n\n        loss_box_reg = _dense_box_regression_loss(\n            anchors,\n            self.box2box_transform,\n            pred_anchor_deltas,\n            [x.tensor for x in gt_boxes],\n            pos_mask,\n            box_reg_loss_type=\"giou\",\n        )\n\n        ctrness_targets = self.compute_ctrness_targets(anchors, gt_boxes)  # NxR\n        pred_centerness = torch.cat(pred_centerness, dim=1).squeeze(dim=2)  # NxR\n        ctrness_loss = F.binary_cross_entropy_with_logits(\n            pred_centerness[pos_mask], ctrness_targets[pos_mask], reduction=\"sum\"\n        )\n        return {\n            \"loss_fcos_cls\": loss_cls / normalizer,\n            \"loss_fcos_loc\": loss_box_reg / normalizer,\n            \"loss_fcos_ctr\": ctrness_loss / normalizer,\n        }\n\n    def compute_ctrness_targets(self, anchors, gt_boxes):  # NxR\n        anchors = Boxes.cat(anchors).tensor  # Rx4\n        reg_targets = [self.box2box_transform.get_deltas(anchors, m.tensor) for m in gt_boxes]\n        reg_targets = torch.stack(reg_targets, dim=0)  # NxRx4\n        if len(reg_targets) == 0:\n            return reg_targets.new_zeros(len(reg_targets))\n        left_right = reg_targets[:, :, [0, 2]]\n        top_bottom = reg_targets[:, :, [1, 3]]\n        ctrness = (left_right.min(dim=-1)[0] / left_right.max(dim=-1)[0]) * (\n            top_bottom.min(dim=-1)[0] / top_bottom.max(dim=-1)[0]\n        )\n        return torch.sqrt(ctrness)\n\n    def forward_inference(\n        self, images: ImageList, features: List[Tensor], predictions: List[List[Tensor]]\n    ):\n        pred_logits, pred_anchor_deltas, pred_centerness = self._transpose_dense_predictions(\n            predictions, [self.num_classes, 4, 1]\n        )\n        anchors = self.anchor_generator(features)\n\n        results: List[Instances] = []\n        for img_idx, image_size in enumerate(images.image_sizes):\n            scores_per_image = [\n                # Multiply and sqrt centerness & classification scores\n                # (See eqn. 4 in https://arxiv.org/abs/2006.09214)\n                torch.sqrt(x[img_idx].sigmoid_() * y[img_idx].sigmoid_())\n                for x, y in zip(pred_logits, pred_centerness)\n            ]\n            deltas_per_image = [x[img_idx] for x in pred_anchor_deltas]\n            results_per_image = self.inference_single_image(\n                anchors, scores_per_image, deltas_per_image, image_size\n            )\n            results.append(results_per_image)\n        return results\n\n    def inference_single_image(\n        self,\n        anchors: List[Boxes],\n        box_cls: List[Tensor],\n        box_delta: List[Tensor],\n        image_size: Tuple[int, int],\n    ):\n        \"\"\"\n        Identical to :meth:`RetinaNet.inference_single_image.\n        \"\"\"\n        pred = self._decode_multi_level_predictions(\n            anchors,\n            box_cls,\n            box_delta,\n            self.test_score_thresh,\n            self.test_topk_candidates,\n            image_size,\n        )\n        keep = batched_nms(\n            pred.pred_boxes.tensor, pred.scores, pred.pred_classes, self.test_nms_thresh\n        )\n        return pred[keep[: self.max_detections_per_image]]\n\n\nclass FCOSHead(RetinaNetHead):\n    \"\"\"\n    The head used in :paper:`fcos`. It adds an additional centerness\n    prediction branch on top of :class:`RetinaNetHead`.\n    \"\"\"\n\n    def __init__(self, *, input_shape: List[ShapeSpec], conv_dims: List[int], **kwargs):\n        super().__init__(input_shape=input_shape, conv_dims=conv_dims, num_anchors=1, **kwargs)\n        # Unlike original FCOS, we do not add an additional learnable scale layer\n        # because it's found to have no benefits after normalizing regression targets by stride.\n        self._num_features = len(input_shape)\n        self.ctrness = nn.Conv2d(conv_dims[-1], 1, kernel_size=3, stride=1, padding=1)\n        torch.nn.init.normal_(self.ctrness.weight, std=0.01)\n        torch.nn.init.constant_(self.ctrness.bias, 0)\n\n    def forward(self, features):\n        assert len(features) == self._num_features\n        logits = []\n        bbox_reg = []\n        ctrness = []\n        for feature in features:\n            logits.append(self.cls_score(self.cls_subnet(feature)))\n            bbox_feature = self.bbox_subnet(feature)\n            bbox_reg.append(self.bbox_pred(bbox_feature))\n            ctrness.append(self.ctrness(bbox_feature))\n        return logits, bbox_reg, ctrness\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/meta_arch/panoptic_fpn.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport logging\nfrom typing import Dict, List\nimport torch\nfrom torch import nn\nimport torch.nn.functional as F\nimport numpy as np\n\nfrom detectron2.config import configurable\nfrom detectron2.structures import ImageList\nfrom detectron2.data.datasets.builtin_meta import CITYSCAPES_CATEGORIES, KITTI_STEP_CATEGORIES, VKITTI_CATEGORIES\n\nfrom ..postprocessing import detector_postprocess, sem_seg_postprocess\nfrom .build import META_ARCH_REGISTRY\nfrom .rcnn import GeneralizedRCNN\nfrom .semantic_seg import build_sem_seg_head\n\nimport importlib\nfrom detectron2.aot_modules.layers.loss import CrossEntropyLoss, SoftJaccordLoss\nimport PIL.Image as Image\nimport copy\nimport cv2  \nfrom collections import OrderedDict\n\n__all__ = [\"PanopticFPN\"]\n\nthing_ids = [k[\"trainId\"] for k in VKITTI_CATEGORIES if k[\"isthing\"] == 1]\nthing_id2cat = {i: k for i,k in enumerate(thing_ids)}\nstuff_ids = [k[\"trainId\"] for k in VKITTI_CATEGORIES if k[\"isthing\"] == 0]\nstuff_id2cat = {i+1: k for  i,k in enumerate(stuff_ids)}\n\n\n@META_ARCH_REGISTRY.register()\nclass PanopticFPN(GeneralizedRCNN):\n    \"\"\"\n    Implement the paper :paper:`PanopticFPN`.\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self,\n        *,\n        sem_seg_head: nn.Module,\n        combine_overlap_thresh: float = 0.5,\n        combine_stuff_area_thresh: float = 4096,\n        combine_instances_score_thresh: float = 0.5,\n        fusion,\n        **kwargs,\n    ):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            sem_seg_head: a module for the semantic segmentation head.\n            combine_overlap_thresh: combine masks into one instances if\n                they have enough overlap\n            combine_stuff_area_thresh: ignore stuff areas smaller than this threshold\n            combine_instances_score_thresh: ignore instances whose score is\n                smaller than this threshold\n\n        Other arguments are the same as :class:`GeneralizedRCNN`.\n        \"\"\"\n        super().__init__(**kwargs)\n        self.sem_seg_head = sem_seg_head\n        # options when combining instance & semantic outputs\n        self.combine_overlap_thresh = combine_overlap_thresh\n        self.combine_stuff_area_thresh = combine_stuff_area_thresh\n        self.combine_instances_score_thresh = combine_instances_score_thresh\n        \n        self.flow_is_npy = True\n        self.fusion = fusion \n        self.alpha = 1.0\n        if self.fusion:\n            for param in self.parameters(): \n                param.requires_grad = False\n\n            self.flow_transport = True\n            self.flow_depth_transport = False  \n            self.depth_proj_op = False\n\n            self.fusion_conv1 = nn.Conv2d(512, 256, kernel_size=3, stride=1, padding=1) \n\n            self.fx = 725.0087\n            self.fy = 725.0087\n            self.cx = 620.5\n            self.cy = 187\n            \n            self.vid = None\n            self.ref_flow = None\n            self.ref_image = None\n            self.ref_id = None\n\n            n_parameters = sum(p.numel() for p in self.parameters() if p.requires_grad)\n            print('ACTIVE number of params:', n_parameters)     \n        else:\n            self.fusion_conv1 = nn.Conv2d(512, 256, kernel_size=3, stride=1, padding=1) \n            for p in self.fusion_conv1.parameters():\n                p.requires_grad = False\n\n    @classmethod\n    def from_config(cls, cfg):\n        ret = super().from_config(cfg)\n        ret.update(\n            {\n                \"combine_overlap_thresh\": cfg.MODEL.PANOPTIC_FPN.COMBINE.OVERLAP_THRESH,\n                \"combine_stuff_area_thresh\": cfg.MODEL.PANOPTIC_FPN.COMBINE.STUFF_AREA_LIMIT,\n                \"combine_instances_score_thresh\": cfg.MODEL.PANOPTIC_FPN.COMBINE.INSTANCES_CONFIDENCE_THRESH,  # noqa\n                \"fusion\" : cfg.MODEL.PANOPTIC_FPN.FUSION,\n            }\n        )\n        ret[\"sem_seg_head\"] = build_sem_seg_head(cfg, ret[\"backbone\"].output_shape())\n        logger = logging.getLogger(__name__)\n        if not cfg.MODEL.PANOPTIC_FPN.COMBINE.ENABLED:\n            logger.warning(\n                \"PANOPTIC_FPN.COMBINED.ENABLED is no longer used. \"\n                \" model.inference(do_postprocess=) should be used to toggle postprocessing.\"\n            )\n        if cfg.MODEL.PANOPTIC_FPN.INSTANCE_LOSS_WEIGHT != 1.0:\n            w = cfg.MODEL.PANOPTIC_FPN.INSTANCE_LOSS_WEIGHT\n            logger.warning(\n                \"PANOPTIC_FPN.INSTANCE_LOSS_WEIGHT should be replaced by weights on each ROI head.\"\n            )\n\n            def update_weight(x):\n                if isinstance(x, dict):\n                    return {k: v * w for k, v in x.items()}\n                else:\n                    return x * w\n\n            roi_heads = ret[\"roi_heads\"]\n            roi_heads.box_predictor.loss_weight = update_weight(roi_heads.box_predictor.loss_weight)\n            roi_heads.mask_head.loss_weight = update_weight(roi_heads.mask_head.loss_weight)\n        return ret\n\n    def forward(self, batched_inputs):\n        \"\"\"\n        Args:\n            batched_inputs: a list, batched outputs of :class:`DatasetMapper`.\n                Each item in the list contains the inputs for one image.\n\n                For now, each item in the list is a dict that contains:\n\n                * \"image\": Tensor, image in (C, H, W) format.\n                * \"instances\": Instances\n                * \"sem_seg\": semantic segmentation ground truth.\n                * Other information that's included in the original dicts, such as:\n                  \"height\", \"width\" (int): the output resolution of the model, used in inference.\n                  See :meth:`postprocess` for details.\n\n        Returns:\n            list[dict]:\n                each dict has the results for one image. The dict contains the following keys:\n\n                * \"instances\": see :meth:`GeneralizedRCNN.forward` for its format.\n                * \"sem_seg\": see :meth:`SemanticSegmentor.forward` for its format.\n                * \"panoptic_seg\": See the return value of\n                  :func:`combine_semantic_and_instance_outputs` for its format.\n        \"\"\"\n        self.batch_size = len(batched_inputs)\n        if self.fusion :\n            if self.training:  \n                return self.train_fusion(batched_inputs)\n            else:\n                return self.inference_fusion(batched_inputs)\n\n        if not self.training:\n            return self.inference(batched_inputs)\n        \n        images = self.preprocess_image(batched_inputs)\n        features = self.backbone(images.tensor)\n\n        assert \"sem_seg\" in batched_inputs[0]\n        gt_sem_seg = [x[\"sem_seg\"].to(self.device) for x in batched_inputs]\n        gt_sem_seg = ImageList.from_tensors(\n            gt_sem_seg, self.backbone.size_divisibility, self.sem_seg_head.ignore_value\n        ).tensor\n        sem_seg_results, sem_seg_losses = self.sem_seg_head(features, gt_sem_seg)\n\n        gt_instances = [x[\"instances\"].to(self.device) for x in batched_inputs]\n        proposals, proposal_losses = self.proposal_generator(images, features, gt_instances)\n        detector_results, detector_losses = self.roi_heads(\n            images, features, proposals, gt_instances\n        )\n\n        losses = sem_seg_losses\n        losses.update(proposal_losses)\n        losses.update(detector_losses)\n        return losses\n    \n    # feature \n    def wrap_in_stage2(self, seq):\n        images = [v[\"image\"].to(self.device) for k,v in seq.items()] \n        images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n        images = ImageList.from_tensors(images, self.backbone.size_divisibility)\n        features = self.backbone(images.tensor)\n\n        if self.flow_transport:\n            flow = seq['ref']['flow']\n            features = self.flow_transport_feature(features, flow)\n        elif self.flow_depth_transport:\n            flow = seq['ref']['flow']\n            depth = seq['ref']['depth']\n            if self.depth_proj_op:\n                pose = [v[\"pose_extrinsic\"] for k,v in seq.items()]\n                depth = self.pose_transport_depth(depth, pose)\n            features = self.flow_transport_feature_with_depth(features, flow, depth)\n\n        features = self.fusion_module(features)\n\n        if self.training:\n            # gt_sem_seg = [v[\"sem_seg\"].to(self.device) for k,v in seq.items()] \n            gt_sem_seg = [seq['cur']['sem_seg'].to(self.device)]\n            gt_sem_seg = ImageList.from_tensors(gt_sem_seg, self.backbone.size_divisibility, self.sem_seg_head.ignore_value).tensor\n            sem_seg_results, sem_seg_losses = self.sem_seg_head(features, gt_sem_seg)\n        else:\n            sem_seg_results, _ = self.sem_seg_head(features, None)\n            \n\n        if self.training:\n            # gt_instances = [v[\"instances\"].to(self.device) for k,v in seq.items()]\n            gt_instances = [seq['cur']['instances'].to(self.device)]\n            images = [seq['cur'][\"image\"].to(self.device)] \n            images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n            images = ImageList.from_tensors(images, self.backbone.size_divisibility)\n            proposals, proposal_losses = self.proposal_generator(images, features, gt_instances)\n            detector_results, detector_losses = self.roi_heads(images, features, proposals, gt_instances)\n        else:\n            images = [seq['cur'][\"image\"].to(self.device)] \n            images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n            images = ImageList.from_tensors(images, self.backbone.size_divisibility)\n            proposals, _ = self.proposal_generator(images, features, None)\n            detector_results, _ = self.roi_heads(images, features, proposals, None)\n        \n\n        if self.training:\n            return features, sem_seg_results, detector_results[0], sem_seg_losses, detector_losses, proposal_losses,proposals[0]\n        else:\n            return sem_seg_results, detector_results, images\n\n    def train_fusion(self, batched_inputs):\n        for seq in batched_inputs: # ref, cur\n            wfeat2, sem2, inst2, sem_loss2, inst_loss2, pro_loss2, pro2 = self.wrap_in_stage2(seq)\n            losses = {\n                        'loss_sem_seg': sem_loss2['loss_sem_seg']\n                    }\n            for k in inst_loss2.keys():\n                losses.update({k: inst_loss2[k]})  \n            for k in pro_loss2.keys():\n                losses.update({k: pro_loss2[k]}) \n        return losses\n    \n    def inference_fusion(self, batched_inputs, do_postprocess=True):\n        cur_vid = batched_inputs[0]['image_id'][:4]\n        if cur_vid != self.vid: \n            self.vid = cur_vid\n            images = [batched_inputs[0][\"image\"].to(self.device)] \n            images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n            images = ImageList.from_tensors(images, self.backbone.size_divisibility)\n            features = self.backbone(images.tensor)\n            sem_seg_results, sem_seg_losses = self.sem_seg_head(features, None)\n            proposals, _ = self.proposal_generator(images, features, None)\n            detector_results, _ = self.roi_heads(images, features, proposals, None)\n        else:\n            seq = {'ref': {}, 'cur':{}}\n            seq['ref']['flow'] = self.ref_flow\n            seq['ref']['image'] = self.ref_image\n            seq['ref']['image_id'] = self.ref_id\n            seq['cur'] = batched_inputs[0]\n            if self.flow_depth_transport:\n                seq['ref']['depth'] = self.ref_depth\n            if self.depth_proj_op :\n                seq['ref']['pose_extrinsic'] = self.ref_pose\n            sem_seg_results, detector_results, images = self.wrap_in_stage2(seq)\n\n        if 'flow' in batched_inputs[0]:\n            self.ref_flow = batched_inputs[0]['flow']\n            self.ref_image = batched_inputs[0]['image']\n            self.ref_id = batched_inputs[0]['image_id']\n        if 'depth' in batched_inputs[0]:\n            self.ref_depth = batched_inputs[0]['depth']\n        if self.depth_proj_op:\n            self.ref_pose = batched_inputs[0]['pose_extrinsic']\n                \n        if do_postprocess:\n            processed_results = []\n            for sem_seg_result, detector_result, input_per_image, image_size in zip(\n                sem_seg_results, detector_results, batched_inputs, images.image_sizes\n            ):\n                height = input_per_image.get(\"height\", image_size[0])\n                width = input_per_image.get(\"width\", image_size[1])\n                sem_seg_r = sem_seg_postprocess(sem_seg_result, image_size, height, width)\n                detector_r = detector_postprocess(detector_result, height, width)\n\n                processed_results.append({\"sem_seg\": sem_seg_r, \"instances\": detector_r})\n\n                panoptic_r = combine_semantic_and_instance_outputs(\n                    detector_r,\n                    sem_seg_r.argmax(dim=0),\n                    self.combine_overlap_thresh,\n                    self.combine_stuff_area_thresh,\n                    self.combine_instances_score_thresh,\n                )\n                processed_results[-1][\"panoptic_seg\"] = panoptic_r\n            return processed_results\n        else:\n            return detector_results, sem_seg_results\n\n    def flow_transport_feature(self, features, ori_flow): \n        for k,feat in features.items():   \n            ref_flow = self.resize(ori_flow.unsqueeze(0), feat.shape[-2:]).squeeze(0).permute(1,2,0)\n            if self.flow_is_npy:\n                ref_flow = ref_flow.detach().cpu().numpy().astype(np.uint16)\n            else:\n                ref_flow = self.read_vkitti_png_flow(ref_flow.detach().cpu().numpy().astype(np.uint16), ori_flow.shape)          \n            [rows, cols] = feat.shape[-2:]\n    \n            mask = torch.zeros(feat.shape[-3:]).to(self.device) \n            v = np.arange(rows)\n            v = v.reshape(rows, 1)\n            v = np.repeat(v, cols, axis=1)\n            u = np.arange(cols)\n            u = np.tile(u, (rows, 1))\n\n            u1 = (u + ref_flow[:,:,0]).astype(np.int32) \n            v1 = (v + ref_flow[:,:,1]).astype(np.int32) \n\n            u = u.flatten()\n            v = v.flatten()\n            u1 = u1.flatten()\n            v1 = v1.flatten()\n\n            mm = (0 <= u1).__and__(u1 < cols).__and__(0 <= v1).__and__(v1 < rows)\n            u1 = u1[mm]\n            v1 = v1[mm]\n            u = u[mm]\n            v = v[mm]\n\n            mask[:,v1,u1] = feat[0][:,v,u]\n            query_mask = torch.as_tensor(mask) \n            features[k] = torch.cat((feat[1],  self.alpha * query_mask), dim=0).unsqueeze(0)\n\n        return features\n\n    def flow_transport_feature_with_depth(self, features, ori_flow, ori_depth):\n        for k,feat in features.items():\n            ref_flow = self.resize(ori_flow.unsqueeze(0), feat.shape[-2:]).squeeze(0).permute(1,2,0)\n            if self.flow_is_npy:\n                ref_flow = ref_flow.detach().cpu().numpy().astype(np.uint16)\n            else:\n                ref_flow = self.read_vkitti_png_flow(ref_flow.detach().cpu().numpy().astype(np.uint16), ori_flow.shape)            \n            ref_depth = self.resize(ori_depth.unsqueeze(0).unsqueeze(0), feat.shape[-2:]).squeeze(0).squeeze(0).cpu().numpy()\n\n            [rows, cols] = feat.shape[-2:]\n    \n            mask = torch.zeros(feat.shape[-3:]).to(self.device) \n            v = np.arange(rows)\n            v = v.reshape(rows, 1)\n            v = np.repeat(v, cols, axis=1)\n            u = np.arange(cols)\n            u = np.tile(u, (rows, 1))\n\n            u1 = (u + ref_flow[:,:,0]).astype(np.int32) \n            v1 = (v + ref_flow[:,:,1]).astype(np.int32) \n\n            u = u.flatten()\n            v = v.flatten()\n            u1 = u1.flatten()\n            v1 = v1.flatten()\n            dep_uv = ref_depth.flatten()\n\n            mm = (0 <= u1).__and__(u1 < cols).__and__(0 <= v1).__and__(v1 < rows)\n            u1 = u1[mm]\n            v1 = v1[mm]\n            u = u[mm]\n            v = v[mm]\n            dep_uv = dep_uv[mm]\n\n            u1,v1,u,v = self.depth_filter(u1, v1, u, v, dep_uv)\n\n            mask[:,v1,u1] = feat[0][:,v,u]\n            query_mask = torch.as_tensor(mask)\n            features[k] = torch.cat((feat[1],  self.alpha * query_mask), dim=0).unsqueeze(0)\n\n        return features\n\n    def pose_transport_depth(self, ori_depth, pose):\n        [rows, cols] = ori_depth.shape[-2:]\n        v = np.repeat(np.arange(rows).reshape(rows, 1), cols, axis=1)\n        u = np.tile(np.arange(cols), (rows, 1))\n\n        Zc0 = ori_depth.detach().cpu().numpy()\n        Xc0 = (u[:,:] - self.cx) / self.fx * Zc0[:,:]\n        Yc0 = (v[:,:] - self.cy) / self.fy * Zc0[:,:]\n        Ones = np.ones((rows, cols))\n        point_camera_0 = np.array([Xc0, Yc0, Zc0 ,Ones]).reshape(4, -1)  \n\n        extrinsics_inv_0 = np.array(pose[0]).reshape((4, 4))\n        extrinsics_0 = np.linalg.inv(extrinsics_inv_0) # cam2wold\n        extrinsics_inv_1 = np.array(pose[1]).reshape((4, 4)) # world2cam  # extrinsics_inv Twc: camera to world\n           \n        relative_pose = np.matmul(extrinsics_inv_1, extrinsics_0)\n        point_camera_1 = np.matmul(relative_pose, point_camera_0)\n\n        Xc1, Yc1, Zc1 = point_camera_1[:3, :] \n        depth = torch.as_tensor(Zc1.reshape(rows, cols)).to(self.device)\n        return depth\n\n    def fusion_module(self, features):\n        for k,v in features.items():\n            x = self.fusion_conv1(v)\n            features[k] = x\n        return features\n\n    def depth_filter(self, u1, v1, u, v, dep_uv):\n        encode_uvu1v1 = u * 1e14 + v * 1e10 + u1 * 1e6 + v1 * 1e2\n        dic = dict(zip(encode_uvu1v1, dep_uv))\n        ndic = np.array(sorted(dic.items(), key=lambda item:item[1], reverse=True))\n\n        if ndic.shape[0] != 0:\n            new_encode_uvu1v1 = ndic[:,0]\n        else:\n            new_encode_uvu1v1 = encode_uvu1v1\n\n        u = (new_encode_uvu1v1 // 1e14).astype(np.int32)\n        v = (new_encode_uvu1v1 % 1e14 // 1e10).astype(np.int32)\n        u1 = (new_encode_uvu1v1 % 1e10 // 1e6).astype(np.int32)\n        v1 = (new_encode_uvu1v1 % 1e6 // 1e2).astype(np.int32)\n\n        return u1, v1, u, v\n\n    def resize(self, mask, output_size):\n        mask = F.interpolate(mask,\n                            size=output_size,\n                            mode=\"bilinear\",\n                            align_corners=True)\n        return mask\n\n    def read_vkitti_png_flow(self, bgr, ori_shape):\n        # bgr = cv2.imread(flow_fn, cv2.IMREAD_ANYCOLOR | cv2.IMREAD_ANYDEPTH)\n        _c, h, w = ori_shape\n        assert bgr.dtype == np.uint16 and _c == 3\n        # b == invalid flow flag == 0 for sky or other invalid flow\n        invalid = bgr[:,:,0] == 0\n        # g,r == flow_y,x normalized by height,width and scaled to [0;2**16 – 1]\n        out_flow = 2.0 / (2**16 - 1.0) * bgr[:,:,2:0:-1].astype('f4') -1\n        out_flow[:,:, 0] *= w - 1\n        out_flow[:,:, 1] *= h - 1\n        out_flow[invalid] = 0  # or another value (e.g., np.nan)\n        return out_flow\n\n    def inference(self, batched_inputs: List[Dict[str, torch.Tensor]], do_postprocess: bool = True):\n        \"\"\"\n        Run inference on the given inputs.\n\n        Args:\n            batched_inputs (list[dict]): same as in :meth:`forward`\n            do_postprocess (bool): whether to apply post-processing on the outputs.\n\n        Returns:\n            When do_postprocess=True, see docs in :meth:`forward`.\n            Otherwise, returns a (list[Instances], list[Tensor]) that contains\n            the raw detector outputs, and raw semantic segmentation outputs.\n        \"\"\"\n        images = self.preprocess_image(batched_inputs)\n        features = self.backbone(images.tensor)\n        sem_seg_results, sem_seg_losses = self.sem_seg_head(features, None)\n        proposals, _ = self.proposal_generator(images, features, None)\n        detector_results, _ = self.roi_heads(images, features, proposals, None)\n\n        if do_postprocess:\n            processed_results = []\n            for sem_seg_result, detector_result, input_per_image, image_size in zip(\n                sem_seg_results, detector_results, batched_inputs, images.image_sizes\n            ):\n                height = input_per_image.get(\"height\", image_size[0])\n                width = input_per_image.get(\"width\", image_size[1])\n                sem_seg_r = sem_seg_postprocess(sem_seg_result, image_size, height, width)\n                detector_r = detector_postprocess(detector_result, height, width)\n\n                processed_results.append({\"sem_seg\": sem_seg_r, \"instances\": detector_r})\n\n                panoptic_r = combine_semantic_and_instance_outputs(\n                    detector_r,\n                    sem_seg_r.argmax(dim=0),\n                    self.combine_overlap_thresh,\n                    self.combine_stuff_area_thresh,\n                    self.combine_instances_score_thresh,\n                )\n                processed_results[-1][\"panoptic_seg\"] = panoptic_r\n            return processed_results\n        else:\n            return detector_results, sem_seg_results\n\n\ndef combine_semantic_and_instance_outputs(\n    instance_results,\n    semantic_results,\n    overlap_threshold,\n    stuff_area_thresh,\n    instances_score_thresh,\n):\n    \"\"\"\n    Implement a simple combining logic following\n    \"combine_semantic_and_instance_predictions.py\" in panopticapi\n    to produce panoptic segmentation outputs.\n\n    Args:\n        instance_results: output of :func:`detector_postprocess`.\n        semantic_results: an (H, W) tensor, each element is the contiguous semantic\n            category id\n\n    Returns:\n        panoptic_seg (Tensor): of shape (height, width) where the values are ids for each segment.\n        segments_info (list[dict]): Describe each segment in `panoptic_seg`.\n            Each dict contains keys \"id\", \"category_id\", \"isthing\".\n    \"\"\"\n    panoptic_seg = torch.zeros_like(semantic_results, dtype=torch.int32)\n\n    # sort instance outputs by scores\n    sorted_inds = torch.argsort(-instance_results.scores)\n\n    current_segment_id = 0\n    segments_info = []\n\n    instance_masks = instance_results.pred_masks.to(dtype=torch.bool, device=panoptic_seg.device)\n\n    # Add instances one-by-one, check for overlaps with existing ones\n    for inst_id in sorted_inds:\n        score = instance_results.scores[inst_id].item()\n        if score < instances_score_thresh:\n            break\n        mask = instance_masks[inst_id]  # H,W\n        mask_area = mask.sum().item()\n\n        if mask_area == 0:\n            continue\n\n        intersect = (mask > 0) & (panoptic_seg > 0)\n        intersect_area = intersect.sum().item()\n\n        if intersect_area * 1.0 / mask_area > overlap_threshold:\n            continue\n\n        if intersect_area > 0:\n            mask = mask & (panoptic_seg == 0)\n\n        current_segment_id += 1\n        cat = instance_results.pred_classes[inst_id].item()\n        cat = thing_id2cat[cat]\n        instance_id = cat * 10000 + current_segment_id\n        panoptic_seg[mask] = instance_id\n        segments_info.append(\n            {\n                \"id\": instance_id,\n                \"isthing\": True,\n                \"score\": score,\n                \"category_id\": cat,\n                \"instance_id\": inst_id.item(),\n            }\n        )\n\n    # Add semantic results to remaining empty areas\n    semantic_labels = torch.unique(semantic_results).cpu().tolist()\n    for semantic_label in semantic_labels:\n        if semantic_label == 0:  # 0 is a special \"thing\" class\n            continue\n        mask = (semantic_results == semantic_label) & (panoptic_seg == 0)\n        mask_area = mask.sum().item()\n        if mask_area < stuff_area_thresh:\n            continue\n\n        current_segment_id += 1\n        # cat = semantic_label\n        cat = stuff_id2cat[semantic_label]\n        stuff_id = cat * 10000\n        panoptic_seg[mask] = stuff_id\n        segments_info.append(\n            {\n                \"id\": stuff_id,\n                \"isthing\": False,\n                \"category_id\": cat,\n                \"area\": mask_area,\n            }\n        )\n\n    return panoptic_seg, segments_info\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/meta_arch/panoptic_fpn_train.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport logging\nfrom typing import Dict, List\nimport torch\nfrom torch import nn\nimport torch.nn.functional as F\nimport numpy as np\n\nfrom detectron2.config import configurable\nfrom detectron2.structures import ImageList\nfrom detectron2.data.datasets.builtin_meta import CITYSCAPES_CATEGORIES, KITTI_STEP_CATEGORIES, VKITTI_CATEGORIES\n\nfrom ..postprocessing import detector_postprocess, sem_seg_postprocess\nfrom .build import META_ARCH_REGISTRY\nfrom .rcnn import GeneralizedRCNN\nfrom .semantic_seg import build_sem_seg_head\n\n# from detectron2.aot_modules import build_vos_model, build_engine, AOTConfig\nimport importlib\nfrom detectron2.aot_modules.layers.loss import CrossEntropyLoss, SoftJaccordLoss\nimport PIL.Image as Image\nimport copy\nimport cv2  \nfrom collections import OrderedDict\n\n__all__ = [\"PanopticFPN\"]\n\nthing_ids = [k[\"trainId\"] for k in VKITTI_CATEGORIES if k[\"isthing\"] == 1]\nthing_id2cat = {i: k for i,k in enumerate(thing_ids)}\nstuff_ids = [k[\"trainId\"] for k in VKITTI_CATEGORIES if k[\"isthing\"] == 0]\nstuff_id2cat = {i+1: k for  i,k in enumerate(stuff_ids)}\n\n# thing_ids = [k[\"id\"] for k in CITYSCAPES_CATEGORIES if k[\"isthing\"] == 1]\n# thing_id2cat = {i: k for i,k in enumerate(thing_ids)}\n# stuff_ids = [k[\"id\"] for k in CITYSCAPES_CATEGORIES if k[\"isthing\"] == 0]\n# stuff_id2cat = {i+1: k for  i,k in enumerate(stuff_ids)}\n\n\n@META_ARCH_REGISTRY.register()\nclass PanopticFPN(GeneralizedRCNN):\n    \"\"\"\n    Implement the paper :paper:`PanopticFPN`.\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self,\n        *,\n        sem_seg_head: nn.Module,\n        combine_overlap_thresh: float = 0.5,\n        combine_stuff_area_thresh: float = 4096,\n        combine_instances_score_thresh: float = 0.5,\n        **kwargs,\n    ):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            sem_seg_head: a module for the semantic segmentation head.\n            combine_overlap_thresh: combine masks into one instances if\n                they have enough overlap\n            combine_stuff_area_thresh: ignore stuff areas smaller than this threshold\n            combine_instances_score_thresh: ignore instances whose score is\n                smaller than this threshold\n\n        Other arguments are the same as :class:`GeneralizedRCNN`.\n        \"\"\"\n        super().__init__(**kwargs)\n        self.sem_seg_head = sem_seg_head\n        # options when combining instance & semantic outputs\n        self.combine_overlap_thresh = combine_overlap_thresh\n        self.combine_stuff_area_thresh = combine_stuff_area_thresh\n        self.combine_instances_score_thresh = combine_instances_score_thresh\n        \n        self.city = False\n        self.flow_is_npy = True # ******************************* !!!\n        self.read_fea_conv = False\n        self.fusion = True # ************* !!!\n        self.alpha = 1.0\n        if self.fusion:\n            # 分割部分 freeze, 只训练 fusion 部分 \n            for param in self.parameters(): \n                param.requires_grad = False\n            \n            print(\"---------------------\")\n            print('parameters:', sum(param.numel() for param in self.parameters()))\n            n_parameters = sum(p.numel() for p in self.parameters() if p.requires_grad)\n            print('ACTIVE number of params:', n_parameters)\n\n            self.pose_transport = False \n            self.flow_transport = True\n            self.flow_depth_transport = False  # ***************** !!!\n            self.depth_proj_op = self.flow_depth_transport\n\n            self.fusion_conv1 = nn.Conv2d(512, 256, kernel_size=3, stride=1, padding=1) \n            if self.read_fea_conv:\n                model_path = 'output/panFPN_vkitti_511_fea_conv1/model_0071599.pth'\n                state_dict = torch.load(model_path)\n                self.new_state_dict = OrderedDict()\n               \n                self.fusion_conv1.weight = torch.nn.Parameter(state_dict['model']['fusion_conv1.weight'])\n                self.fusion_conv1.bias = torch.nn.Parameter(state_dict['model']['fusion_conv1.bias'])\n\n            self.stage1 = False\n            self.l1loss = nn.L1Loss()\n\n            self.fx = 725.0087\n            self.fy = 725.0087\n            self.cx = 620.5\n            self.cy = 187\n\n            self.vid = None\n            self.ref_flow = None\n            self.ref_image = None\n            self.ref_id = None\n\n            n_parameters = sum(p.numel() for p in self.parameters() if p.requires_grad)\n            print('ACTIVE number of params:', n_parameters)     \n        else:\n            self.fusion_conv1 = nn.Conv2d(512, 256, kernel_size=3, stride=1, padding=1) \n            for p in self.fusion_conv1.parameters():\n                p.requires_grad = False\n            print(\"---------------------------------------\")\n            print('parameters:', sum(param.numel() for param in self.parameters()))\n            n_parameters = sum(p.numel() for p in self.parameters() if p.requires_grad)\n            print('ACTIVE number of params:', n_parameters)\n\n    @classmethod\n    def from_config(cls, cfg):\n        ret = super().from_config(cfg)\n        ret.update(\n            {\n                \"combine_overlap_thresh\": cfg.MODEL.PANOPTIC_FPN.COMBINE.OVERLAP_THRESH,\n                \"combine_stuff_area_thresh\": cfg.MODEL.PANOPTIC_FPN.COMBINE.STUFF_AREA_LIMIT,\n                \"combine_instances_score_thresh\": cfg.MODEL.PANOPTIC_FPN.COMBINE.INSTANCES_CONFIDENCE_THRESH,  # noqa\n            }\n        )\n        ret[\"sem_seg_head\"] = build_sem_seg_head(cfg, ret[\"backbone\"].output_shape())\n        logger = logging.getLogger(__name__)\n        if not cfg.MODEL.PANOPTIC_FPN.COMBINE.ENABLED:\n            logger.warning(\n                \"PANOPTIC_FPN.COMBINED.ENABLED is no longer used. \"\n                \" model.inference(do_postprocess=) should be used to toggle postprocessing.\"\n            )\n        if cfg.MODEL.PANOPTIC_FPN.INSTANCE_LOSS_WEIGHT != 1.0:\n            w = cfg.MODEL.PANOPTIC_FPN.INSTANCE_LOSS_WEIGHT\n            logger.warning(\n                \"PANOPTIC_FPN.INSTANCE_LOSS_WEIGHT should be replaced by weights on each ROI head.\"\n            )\n\n            def update_weight(x):\n                if isinstance(x, dict):\n                    return {k: v * w for k, v in x.items()}\n                else:\n                    return x * w\n\n            roi_heads = ret[\"roi_heads\"]\n            roi_heads.box_predictor.loss_weight = update_weight(roi_heads.box_predictor.loss_weight)\n            roi_heads.mask_head.loss_weight = update_weight(roi_heads.mask_head.loss_weight)\n        return ret\n\n    def forward(self, batched_inputs):\n        \"\"\"\n        Args:\n            batched_inputs: a list, batched outputs of :class:`DatasetMapper`.\n                Each item in the list contains the inputs for one image.\n\n                For now, each item in the list is a dict that contains:\n\n                * \"image\": Tensor, image in (C, H, W) format.\n                * \"instances\": Instances\n                * \"sem_seg\": semantic segmentation ground truth.\n                * Other information that's included in the original dicts, such as:\n                  \"height\", \"width\" (int): the output resolution of the model, used in inference.\n                  See :meth:`postprocess` for details.\n\n        Returns:\n            list[dict]:\n                each dict has the results for one image. The dict contains the following keys:\n\n                * \"instances\": see :meth:`GeneralizedRCNN.forward` for its format.\n                * \"sem_seg\": see :meth:`SemanticSegmentor.forward` for its format.\n                * \"panoptic_seg\": See the return value of\n                  :func:`combine_semantic_and_instance_outputs` for its format.\n        \"\"\"\n        self.batch_size = len(batched_inputs)\n        if self.fusion :\n            if self.training:  \n                return self.train_fusion(batched_inputs)\n            else:\n                return self.inference_fusion(batched_inputs)\n\n        if not self.training:\n            return self.inference(batched_inputs)\n        \n        images = self.preprocess_image(batched_inputs)\n        features = self.backbone(images.tensor)\n\n        assert \"sem_seg\" in batched_inputs[0]\n        gt_sem_seg = [x[\"sem_seg\"].to(self.device) for x in batched_inputs]\n        gt_sem_seg = ImageList.from_tensors(\n            gt_sem_seg, self.backbone.size_divisibility, self.sem_seg_head.ignore_value\n        ).tensor\n        sem_seg_results, sem_seg_losses = self.sem_seg_head(features, gt_sem_seg)\n\n        gt_instances = [x[\"instances\"].to(self.device) for x in batched_inputs]\n        proposals, proposal_losses = self.proposal_generator(images, features, gt_instances)\n        detector_results, detector_losses = self.roi_heads(\n            images, features, proposals, gt_instances\n        )\n\n        losses = sem_seg_losses\n        losses.update(proposal_losses)\n        losses.update(detector_losses)\n        return losses\n    \n    # feature   ------- STAGE 2 -------\n    def wrap_in_stage2(self, seq):\n        images = [v[\"image\"].to(self.device) for k,v in seq.items()] \n        images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n        images = ImageList.from_tensors(images, self.backbone.size_divisibility)\n        features = self.backbone(images.tensor)\n        # print(images.image_sizes) # [(374, 1240), (374, 1240)]\n        # for k,v in features.items(): \n        #     # p2 2x256x96x312, p3 2x256x48x156, p4 2x256x24x78, p5 2x256x12x39, p6 2x256x6x20\n        #     # 1/4               1/8               1/16             1/32            1/64\n        #     print(k,v.shape)\n\n        if self.pose_transport:\n            depth = seq['ref']['depth'].to(self.device)\n            pose =  [v[\"pose_extrinsic\"] for k,v in seq.items()]\n            features = self.pose_transport_feature(features, depth, pose)\n        elif self.flow_transport:\n            flow = seq['ref']['flow']\n            features = self.flow_transport_feature(features, flow)\n        elif self.flow_depth_transport:\n            flow = seq['ref']['flow']\n            depth = seq['ref']['depth']\n            if self.depth_proj_op:\n                pose = [v[\"pose_extrinsic\"] for k,v in seq.items()]\n                depth = self.pose_transport_depth(depth, pose)\n            features = self.flow_transport_feature_with_depth(features, flow, depth)\n\n        # 组织好的 p2 1x512x96x312, p3 1x512x48x156, p4, p5\n        features = self.fusion_module(features)\n        # 组织好的 p2 1x256x96x312, p3 1x256x48x156, p4, p5\n\n        if self.training:\n            # gt_sem_seg = [v[\"sem_seg\"].to(self.device) for k,v in seq.items()] \n            gt_sem_seg = [seq['cur']['sem_seg'].to(self.device)]\n            gt_sem_seg = ImageList.from_tensors(gt_sem_seg, self.backbone.size_divisibility, self.sem_seg_head.ignore_value).tensor\n            sem_seg_results, sem_seg_losses = self.sem_seg_head(features, gt_sem_seg)\n        else:\n            sem_seg_results, _ = self.sem_seg_head(features, None)\n            \n\n        if self.training:\n            # gt_instances = [v[\"instances\"].to(self.device) for k,v in seq.items()]\n            gt_instances = [seq['cur']['instances'].to(self.device)]\n            images = [seq['cur'][\"image\"].to(self.device)] \n            images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n            images = ImageList.from_tensors(images, self.backbone.size_divisibility)\n            proposals, proposal_losses = self.proposal_generator(images, features, gt_instances)\n            detector_results, detector_losses = self.roi_heads(images, features, proposals, gt_instances)\n        else:\n            images = [seq['cur'][\"image\"].to(self.device)] \n            images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n            images = ImageList.from_tensors(images, self.backbone.size_divisibility)\n            proposals, _ = self.proposal_generator(images, features, None)\n            detector_results, _ = self.roi_heads(images, features, proposals, None)\n        \n\n        if self.training:\n            return features, sem_seg_results, detector_results[0], sem_seg_losses, detector_losses, proposal_losses,proposals[0]\n        else:\n            return sem_seg_results, detector_results, images\n\n    # img space ------- STAGE 1 -------\n    def wrap_in_stage1(self, seq):\n        images = [v[\"image\"].to(self.device) for k,v in seq.items()] \n        images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n        images = ImageList.from_tensors(images, self.backbone.size_divisibility)\n\n        if self.flow_transport:\n            flow = seq['ref']['flow']\n            query_img = self.flow_transport_img(images.tensor[0:1], flow) # 1x3xHxW\n        elif self.flow_depth_transport:\n            flow = seq['ref']['flow']\n            depth = seq['ref']['depth']\n            if self.depth_proj_op:\n                pose = [v[\"pose_extrinsic\"] for k,v in seq.items()]\n                depth = self.pose_transport_depth(depth, pose)\n            query_img = self.flow_transport_img_with_depth(images.tensor[0:1], flow, depth)\n\n        # Image.fromarray(np.uint8(images.tensor[0].detach().cpu().permute(1,2,0).numpy())).save(\"ref.png\")\n        # Image.fromarray(np.uint8(images.tensor[1].detach().cpu().permute(1,2,0).numpy())).save(\"cur.png\")\n        images.tensor[0:1] = query_img\n        # Image.fromarray(np.uint8(images.tensor[0].detach().cpu().permute(1,2,0).numpy())).save(\"ref_flow.png\")\n        # a=p\n\n        features = self.backbone(images.tensor)\n        \n        for k,feat in features.items():\n            features[k] = torch.cat((feat[1],  self.alpha * feat[0]), dim=0).unsqueeze(0)\n        # p2 1x512x96x312, p3 1x512x48x156, p4, p5\n        features = self.fusion_module(features)\n        # p2 1x256x96x312, p3 1x256x48x156, p4, p5\n\n        return features\n\n        '''\n        if self.training:\n            gt_sem_seg = [seq['cur']['sem_seg'].to(self.device)]\n            gt_sem_seg = ImageList.from_tensors(gt_sem_seg, self.backbone.size_divisibility, self.sem_seg_head.ignore_value).tensor\n            sem_seg_results, sem_seg_losses = self.sem_seg_head(features, gt_sem_seg)\n        else:\n            sem_seg_results, _ = self.sem_seg_head(features, None)\n\n        if self.training:\n            gt_instances = [seq['cur']['instances'].to(self.device)]\n            images = [seq['cur'][\"image\"].to(self.device)] \n            images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n            images = ImageList.from_tensors(images, self.backbone.size_divisibility)\n            proposals, proposal_losses = self.proposal_generator(images, features, gt_instances)\n            detector_results, detector_losses = self.roi_heads(images, features, proposals, gt_instances)\n        else:\n            images = [seq['cur'][\"image\"].to(self.device)] \n            images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n            images = ImageList.from_tensors(images, self.backbone.size_divisibility)\n            proposals, proposal_losses = self.proposal_generator(images, features, None)\n            detector_results, detector_losses = self.roi_heads(images, features, proposals, None)\n\n        if self.training:\n            return features, sem_seg_results, detector_results[0], sem_seg_losses, detector_losses, proposal_losses, proposals[0]\n        else:\n            return sem_seg_results, detector_results, images \n        '''\n    \n    def wrap_in_stage1_2(self, seq):\n        images = [v[\"image\"].to(self.device) for k,v in seq.items()] \n        Image.fromarray(np.uint8(images[0].squeeze(0).permute(1,2,0).detach().cpu().numpy())).save(\"img0.png\")\n        Image.fromarray(np.uint8(images[1].squeeze(0).permute(1,2,0).detach().cpu().numpy())).save(\"img1.png\")\n\n        images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n        images = ImageList.from_tensors(images, self.backbone.size_divisibility)\n        Image.fromarray(np.uint8(images[0].squeeze(0).permute(1,2,0).detach().cpu().numpy())).save(\"img2.png\")\n        Image.fromarray(np.uint8(images[1].squeeze(0).permute(1,2,0).detach().cpu().numpy())).save(\"img3.png\")\n\n        features = self.backbone(images.tensor)\n\n        flow = seq['ref']['flow']\n        features = self.flow_transport_feature(features, flow)\n        # p2 1x512x96x312, p3 1x512x48x156, p4, p5\n        \n        print(seq['ref']['file_name'], seq['cur']['file_name'])\n       \n        query_img = self.flow_transport_img(images.tensor[0:1], flow) # 1x3xHxW\n        Image.fromarray(np.uint8(query_img.squeeze(0).permute(1,2,0).detach().cpu().numpy())).save(\"img.png\")\n        a=p\n        images.tensor[0:1] = query_img\n        wrap_img_features = self.backbone(images.tensor)\n        # p2 2x256x96x312, p3 2x256x48x156, p4, p5\n\n        for k,feat in wrap_img_features.items():\n            features[k] = torch.cat((feat[0:1], features[k]), dim=1)\n            # p2 1x768x96x312, p3 1x768x48x156, p4, p5\n\n        features = self.fusion_module(features)\n\n        if self.training:\n            gt_sem_seg = [seq['cur']['sem_seg'].to(self.device)]\n            gt_sem_seg = ImageList.from_tensors(gt_sem_seg, self.backbone.size_divisibility, self.sem_seg_head.ignore_value).tensor\n            sem_seg_results, sem_seg_losses = self.sem_seg_head(features, gt_sem_seg)\n        else:\n            sem_seg_results, _ = self.sem_seg_head(features, None)\n\n        if self.training:\n            gt_instances = [seq['cur']['instances'].to(self.device)]\n            images = [seq['cur'][\"image\"].to(self.device)] \n            images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n            images = ImageList.from_tensors(images, self.backbone.size_divisibility)\n            proposals, proposal_losses = self.proposal_generator(images, features, gt_instances)\n            detector_results, detector_losses = self.roi_heads(images, features, proposals, gt_instances)\n        else:\n            images = [seq['cur'][\"image\"].to(self.device)] \n            images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n            images = ImageList.from_tensors(images, self.backbone.size_divisibility)\n            proposals, proposal_losses = self.proposal_generator(images, features, None)\n            detector_results, detector_losses = self.roi_heads(images, features, proposals, None)\n\n        if self.training:\n            return features, sem_seg_results, detector_results[0], sem_seg_losses, detector_losses, proposal_losses, proposals[0]\n        else:\n            return sem_seg_results, detector_results, images \n\n    def train_fusion(self, batched_inputs): # batch_size = 1\n        for seq in batched_inputs: # ref, cur\n            # seq 有2张图 ref, cur\n            wfeat2, sem2, inst2, sem_loss2, inst_loss2, pro_loss2, pro2 = self.wrap_in_stage2(seq)\n            # wfeat1 = self.wrap_in_stage1(seq)\n            \n            # L_fea = self.l1loss(wfeat2['p2'],  wfeat1['p2']) + \\\n            #         self.l1loss(wfeat2['p3'],  wfeat1['p3']) + \\\n            #         self.l1loss(wfeat2['p4'],  wfeat1['p4']) + \\\n            #         self.l1loss(wfeat2['p5'],  wfeat1['p5'])\n\n            # L_rec = self.l1loss(sem2, sem1) + \\\n            #         self.l1loss(pro2.objectness_logits, pro1.objectness_logits) + \\\n            #         self.l1loss(inst2.objectness_logits, inst1.objectness_logits)\n\n            losses = {\n                        # \"loss_fea\": L_fea, \n                        # \"loss_rec\": L_rec,\n                        'loss_sem_seg': sem_loss2['loss_sem_seg']\n                    }\n            for k in inst_loss2.keys():\n                losses.update({k: inst_loss2[k]}) #  \n            for k in pro_loss2.keys():\n                losses.update({k: pro_loss2[k]}) #  + pro_loss1[k]\n        \n        return losses\n    \n    def inference_fusion(self, batched_inputs, do_postprocess=True):\n        if self.city:\n            cur_vid = batched_inputs[0]['file_name'].rsplit('/')[-1][:4]\n        else:\n            cur_vid = batched_inputs[0]['image_id'][:4]\n        # print(batched_inputs)\n        if cur_vid != self.vid: # 第一帧\n            self.vid = cur_vid\n            images = [batched_inputs[0][\"image\"].to(self.device)] \n            images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n            images = ImageList.from_tensors(images, self.backbone.size_divisibility)\n            features = self.backbone(images.tensor)\n            sem_seg_results, sem_seg_losses = self.sem_seg_head(features, None)\n            proposals, _ = self.proposal_generator(images, features, None)\n            detector_results, _ = self.roi_heads(images, features, proposals, None)\n        else:\n            seq = {'ref': {}, 'cur':{}}\n            seq['ref']['flow'] = self.ref_flow\n            seq['ref']['image'] = self.ref_image\n            seq['ref']['image_id'] = self.ref_id\n            seq['cur'] = batched_inputs[0]\n            if self.flow_depth_transport or self.pose_transport:\n                seq['ref']['depth'] = self.ref_depth\n            if self.depth_proj_op or self.pose_transport:\n                seq['ref']['pose_extrinsic'] = self.ref_pose\n            if self.stage1:\n                sem_seg_results, detector_results, images = self.wrap_in_stage1(seq)\n            else:\n                sem_seg_results, detector_results, images = self.wrap_in_stage2(seq)\n\n        if 'flow' in batched_inputs[0]:\n            self.ref_flow = batched_inputs[0]['flow']\n            self.ref_image = batched_inputs[0]['image']\n            self.ref_id = batched_inputs[0]['image_id']\n        if 'depth' in batched_inputs[0]:\n            self.ref_depth = batched_inputs[0]['depth']\n        if self.depth_proj_op or self.pose_transport:\n            self.ref_pose = batched_inputs[0]['pose_extrinsic']\n                \n\n        if do_postprocess:\n            processed_results = []\n            for sem_seg_result, detector_result, input_per_image, image_size in zip(\n                sem_seg_results, detector_results, batched_inputs, images.image_sizes\n            ):\n                height = input_per_image.get(\"height\", image_size[0])\n                width = input_per_image.get(\"width\", image_size[1])\n                sem_seg_r = sem_seg_postprocess(sem_seg_result, image_size, height, width)\n                detector_r = detector_postprocess(detector_result, height, width)\n\n                processed_results.append({\"sem_seg\": sem_seg_r, \"instances\": detector_r})\n\n                panoptic_r = combine_semantic_and_instance_outputs(\n                    detector_r,\n                    sem_seg_r.argmax(dim=0),\n                    self.combine_overlap_thresh,\n                    self.combine_stuff_area_thresh,\n                    self.combine_instances_score_thresh,\n                )\n                processed_results[-1][\"panoptic_seg\"] = panoptic_r\n            return processed_results\n        else:\n            return detector_results, sem_seg_results\n\n    # -------------------flow ----------\n    def flow_transport_feature(self, features, ori_flow): # 3xHxW\n        # Image.fromarray(np.uint8(ori_flow.permute(1,2,0).detach().cpu().numpy())).save(\"p0.png\") \n        for k,feat in features.items():\n            # p2 2x256x96x312, p3 2x256x48x156, p4 2x256x24x78, p5 2x256x12x39, p6 2x256x6x20\n            #     # 1/4               1/8               1/16             1/32            1/64\n            \n            ref_flow = self.resize(ori_flow.unsqueeze(0), feat.shape[-2:]).squeeze(0).permute(1,2,0)\n            if self.flow_is_npy:\n                ref_flow = ref_flow.detach().cpu().numpy().astype(np.uint16)\n            else:\n                ref_flow = self.read_vkitti_png_flow(ref_flow.detach().cpu().numpy().astype(np.uint16), ori_flow.shape)          \n            [rows, cols] = feat.shape[-2:]\n    \n            mask = torch.zeros(feat.shape[-3:]).to(self.device) # 256x96x312\n            v = np.arange(rows)\n            v = v.reshape(rows, 1)\n            v = np.repeat(v, cols, axis=1)\n            u = np.arange(cols)\n            u = np.tile(u, (rows, 1))\n\n            u1 = (u + ref_flow[:,:,0]).astype(np.int32) # 1247\n            v1 = (v + ref_flow[:,:,1]).astype(np.int32) # 374\n\n            u = u.flatten()\n            v = v.flatten()\n            u1 = u1.flatten()\n            v1 = v1.flatten()\n\n            mm = (0 <= u1).__and__(u1 < cols).__and__(0 <= v1).__and__(v1 < rows)\n            u1 = u1[mm]\n            v1 = v1[mm]\n            u = u[mm]\n            v = v[mm]\n\n            mask[:,v1,u1] = feat[0][:,v,u]\n            query_mask = torch.as_tensor(mask) # 256xHxW\n            features[k] = torch.cat((feat[1],  self.alpha * query_mask), dim=0).unsqueeze(0)\n\n        return features\n\n    def flow_transport_img(self, image, ori_flow):\n        ref_flow = self.resize(ori_flow.unsqueeze(0), image.shape[-2:]).squeeze(0).permute(1,2,0)\n        ref_flow = self.read_vkitti_png_flow(ref_flow.detach().cpu().numpy().astype(np.uint16), ori_flow.shape)          \n        [rows, cols] = image.shape[-2:]\n    \n        mask = torch.zeros(image.shape).to(self.device) # 256x96x312\n\n        v = np.arange(rows)\n        v = v.reshape(rows, 1)\n        v = np.repeat(v, cols, axis=1)\n        u = np.arange(cols)\n        u = np.tile(u, (rows, 1))\n\n        u1 = (u + ref_flow[:,:,0]).astype(np.int32) # 1247\n        v1 = (v + ref_flow[:,:,1]).astype(np.int32) # 374\n\n        u = u.flatten()\n        v = v.flatten()\n        u1 = u1.flatten()\n        v1 = v1.flatten()\n\n        mm = (0 <= u1).__and__(u1 < cols).__and__(0 <= v1).__and__(v1 < rows)\n        u1 = u1[mm]\n        v1 = v1[mm]\n        u = u[mm]\n        v = v[mm]\n\n        mask[:,:,v1,u1] = image[:,:,v,u]\n\n        return mask\n    \n    # =================  depth ==============\n    def depth_filter(self, u1, v1, u, v, dep_uv):\n        encode_uvu1v1 = u * 1e14 + v * 1e10 + u1 * 1e6 + v1 * 1e2\n        dic = dict(zip(encode_uvu1v1, dep_uv))\n        ndic = np.array(sorted(dic.items(), key=lambda item:item[1], reverse=True))\n        # print(ndic.shape)\n        if ndic.shape[0] != 0:\n            new_encode_uvu1v1 = ndic[:,0]\n        else:\n            new_encode_uvu1v1 = encode_uvu1v1\n\n        u = (new_encode_uvu1v1 // 1e14).astype(np.int32)\n        v = (new_encode_uvu1v1 % 1e14 // 1e10).astype(np.int32)\n        u1 = (new_encode_uvu1v1 % 1e10 // 1e6).astype(np.int32)\n        v1 = (new_encode_uvu1v1 % 1e6 // 1e2).astype(np.int32)\n\n        return u1, v1, u, v\n\n    def flow_transport_feature_with_depth(self, features, ori_flow, ori_depth): # 3xHxW\n        # Image.fromarray(np.uint8(ori_flow.permute(1,2,0).detach().cpu().numpy())).save(\"p0.png\") \n        for k,feat in features.items():\n            # p2 2x256x96x312, p3 2x256x48x156, p4 2x256x24x78, p5 2x256x12x39, p6 2x256x6x20\n            #     # 1/4               1/8               1/16             1/32            1/64\n            ref_flow = self.resize(ori_flow.unsqueeze(0), feat.shape[-2:]).squeeze(0).permute(1,2,0)\n            if self.flow_is_npy:\n                ref_flow = ref_flow.detach().cpu().numpy().astype(np.uint16)\n            else:\n                ref_flow = self.read_vkitti_png_flow(ref_flow.detach().cpu().numpy().astype(np.uint16), ori_flow.shape)            \n            ref_depth = self.resize(ori_depth.unsqueeze(0).unsqueeze(0), feat.shape[-2:]).squeeze(0).squeeze(0).cpu().numpy()\n\n            [rows, cols] = feat.shape[-2:]\n    \n            mask = torch.zeros(feat.shape[-3:]).to(self.device) # 256x96x312\n            v = np.arange(rows)\n            v = v.reshape(rows, 1)\n            v = np.repeat(v, cols, axis=1)\n            u = np.arange(cols)\n            u = np.tile(u, (rows, 1))\n\n            u1 = (u + ref_flow[:,:,0]).astype(np.int32) # 1247\n            v1 = (v + ref_flow[:,:,1]).astype(np.int32) # 374\n\n            u = u.flatten()\n            v = v.flatten()\n            u1 = u1.flatten()\n            v1 = v1.flatten()\n            dep_uv = ref_depth.flatten()\n\n            mm = (0 <= u1).__and__(u1 < cols).__and__(0 <= v1).__and__(v1 < rows)\n            u1 = u1[mm]\n            v1 = v1[mm]\n            u = u[mm]\n            v = v[mm]\n            dep_uv = dep_uv[mm]\n\n            u1,v1,u,v = self.depth_filter(u1, v1, u, v, dep_uv)\n\n            mask[:,v1,u1] = feat[0][:,v,u]\n            query_mask = torch.as_tensor(mask) # 256xHxW\n            features[k] = torch.cat((feat[1],  self.alpha * query_mask), dim=0).unsqueeze(0)\n\n        return features\n\n    def flow_transport_img_with_depth(self, image, ori_flow, ori_depth): # 3xHxW\n        ref_flow = self.resize(ori_flow.unsqueeze(0), image.shape[-2:]).squeeze(0).permute(1,2,0)\n        ref_flow = self.read_vkitti_png_flow(ref_flow.detach().cpu().numpy().astype(np.uint16), ori_flow.shape)          \n        ref_depth = self.resize(ori_depth.unsqueeze(0).unsqueeze(0), image.shape[-2:]).squeeze(0).squeeze(0).cpu().numpy()\n        [rows, cols] = image.shape[-2:]\n    \n        mask = torch.zeros(image.shape).to(self.device) # 256x96x312\n        v = np.arange(rows)\n        v = v.reshape(rows, 1)\n        v = np.repeat(v, cols, axis=1)\n        u = np.arange(cols)\n        u = np.tile(u, (rows, 1))\n\n        u1 = (u + ref_flow[:,:,0]).astype(np.int32) # 1247\n        v1 = (v + ref_flow[:,:,1]).astype(np.int32) # 374\n\n        u = u.flatten()\n        v = v.flatten()\n        u1 = u1.flatten()\n        v1 = v1.flatten()\n        dep_uv = ref_depth.flatten()\n\n        mm = (0 <= u1).__and__(u1 < cols).__and__(0 <= v1).__and__(v1 < rows)\n        u1 = u1[mm]\n        v1 = v1[mm]\n        u = u[mm]\n        v = v[mm]\n        dep_uv = dep_uv[mm]\n\n        u1,v1,u,v = self.depth_filter(u1, v1, u, v, dep_uv)\n        mask[:,:,v1,u1] = image[:,:,v,u]\n\n        return mask\n\n    # ********************************\n    def pose_transport_feature(self, features, ori_depth, pose):\n        # Image.fromarray(np.uint8(ori_depth.detach().cpu().numpy())).save(\"p0.png\")\n        for k,feat in features.items():\n            # p2 2x256x96x312, p3 2x256x48x156, p4 2x256x24x78, p5 2x256x12x39, p6 2x256x6x20\n            #     # 1/4               1/8               1/16             1/32            1/64\n            depth = self.resize(ori_depth.unsqueeze(0).unsqueeze(0), feat.shape[-2:]).squeeze(0).squeeze(0)\n            # d = depth.detach().cpu().numpy()\n            # Image.fromarray(np.uint8(d)).save(k + \".png\") \n            [rows, cols] = feat.shape[-2:]\n    \n            mask = torch.zeros(feat.shape[-3:]).to(self.device) # 256x96x312\n            v = np.arange(rows)\n            v = v.reshape(rows, 1)\n            v = np.repeat(v, cols, axis=1)\n            u = np.arange(cols)\n            u = np.tile(u, (rows, 1))\n\n            Zc0 = depth.detach().cpu().numpy()\n            Xc0 = (u[:,:] - self.cx) / self.fx * Zc0[:,:]\n            Yc0 = (v[:,:] - self.cy) / self.fy * Zc0[:,:]\n            Ones = np.ones((rows, cols))\n            point_camera_0 = np.array([Xc0, Yc0, Zc0 ,Ones])   \n            point_camera_0 = point_camera_0.reshape(4, -1)\n            # -----------------------------------------------------\n            extrinsics_inv_0 = np.array(pose[0]).reshape((4, 4))\n            extrinsics_0 = np.linalg.inv(extrinsics_inv_0)\n\n            extrinsics_inv_1 = np.array(pose[1]).reshape((4, 4)) # world2cam  # extrinsics_inv Twc: camera to world\n            extrinsics_1 = np.linalg.inv(extrinsics_inv_1)  # cam2wold # extrinsics Tcw: world to camera\n            # -----------------------------------------------------\n            relative_pose = np.matmul(extrinsics_inv_1, extrinsics_0) # 2 ---------------------------\n            point_camera_1 = np.matmul(relative_pose, point_camera_0)\n\n            Xc1, Yc1, Zc1 = point_camera_1[:3, :]\n            eps = 1e-4\n            eps = np.tile(eps, (rows * cols))\n            Zc1 = np.maximum(Zc1, eps)\n            u1 = (self.fx * Xc1 / Zc1 + self.cx).astype(np.int32) # 1247\n            v1 = (self.fy * Yc1 / Zc1 + self.cy).astype(np.int32) # 374\n\n            u = u.flatten()\n            v = v.flatten()\n\n            mm = (0 <= u1).__and__(u1 < cols).__and__(0 <= v1).__and__(v1 < rows)\n            u1 = u1[mm]\n            v1 = v1[mm]\n            u = u[mm]\n            v = v[mm]\n            # print(u,v) # [ 15  37  38 ... 309 310 311] [ 0  0  0 ... 95 95 95]\n            mask[:,v1,u1] = feat[0][:,v,u]\n            # features[k] = copy.deepcopy(mask)\n            query_mask = torch.as_tensor(mask) # 256xHxW\n            features[k] = torch.cat((feat[1],  self.alpha * query_mask), dim=0).unsqueeze(0)\n\n        return features\n\n    def pose_transport_depth(self, ori_depth, pose):\n        [rows, cols] = ori_depth.shape[-2:]\n        v = np.repeat(np.arange(rows).reshape(rows, 1), cols, axis=1)\n        u = np.tile(np.arange(cols), (rows, 1))\n\n        Zc0 = ori_depth.detach().cpu().numpy()\n        Xc0 = (u[:,:] - self.cx) / self.fx * Zc0[:,:]\n        Yc0 = (v[:,:] - self.cy) / self.fy * Zc0[:,:]\n        Ones = np.ones((rows, cols))\n        point_camera_0 = np.array([Xc0, Yc0, Zc0 ,Ones]).reshape(4, -1)  \n\n        extrinsics_inv_0 = np.array(pose[0]).reshape((4, 4))\n        extrinsics_0 = np.linalg.inv(extrinsics_inv_0) # cam2wold\n        extrinsics_inv_1 = np.array(pose[1]).reshape((4, 4)) # world2cam  # extrinsics_inv Twc: camera to world\n           \n        relative_pose = np.matmul(extrinsics_inv_1, extrinsics_0)\n        point_camera_1 = np.matmul(relative_pose, point_camera_0)\n\n        Xc1, Yc1, Zc1 = point_camera_1[:3, :] \n        depth = torch.as_tensor(Zc1.reshape(rows, cols)).to(self.device)\n        return depth\n\n    def fusion_module(self, features):\n        for k,v in features.items():\n            x = self.fusion_conv1(v)\n            # x = self.fusion_conv2(self.activation(x))\n            features[k] = x\n        return features\n    \n    def resize(self, mask, output_size):\n        mask = F.interpolate(mask,\n                            size=output_size,\n                            mode=\"bilinear\",\n                            align_corners=True)\n        return mask\n\n    def read_vkitti_png_flow(self, bgr, ori_shape):\n        # bgr = cv2.imread(flow_fn, cv2.IMREAD_ANYCOLOR | cv2.IMREAD_ANYDEPTH)\n        _c, h, w = ori_shape\n        assert bgr.dtype == np.uint16 and _c == 3\n        # b == invalid flow flag == 0 for sky or other invalid flow\n        invalid = bgr[:,:,0] == 0\n        # g,r == flow_y,x normalized by height,width and scaled to [0;2**16 – 1]\n        out_flow = 2.0 / (2**16 - 1.0) * bgr[:,:,2:0:-1].astype('f4') -1\n        out_flow[:,:, 0] *= w - 1\n        out_flow[:,:, 1] *= h - 1\n        out_flow[invalid] = 0  # or another value (e.g., np.nan)\n        return out_flow\n\n    def inference(self, batched_inputs: List[Dict[str, torch.Tensor]], do_postprocess: bool = True):\n        \"\"\"\n        Run inference on the given inputs.\n\n        Args:\n            batched_inputs (list[dict]): same as in :meth:`forward`\n            do_postprocess (bool): whether to apply post-processing on the outputs.\n\n        Returns:\n            When do_postprocess=True, see docs in :meth:`forward`.\n            Otherwise, returns a (list[Instances], list[Tensor]) that contains\n            the raw detector outputs, and raw semantic segmentation outputs.\n        \"\"\"\n        images = self.preprocess_image(batched_inputs)\n        features = self.backbone(images.tensor)\n        sem_seg_results, sem_seg_losses = self.sem_seg_head(features, None)\n        proposals, _ = self.proposal_generator(images, features, None)\n        detector_results, _ = self.roi_heads(images, features, proposals, None)\n\n        if do_postprocess:\n            processed_results = []\n            for sem_seg_result, detector_result, input_per_image, image_size in zip(\n                sem_seg_results, detector_results, batched_inputs, images.image_sizes\n            ):\n                height = input_per_image.get(\"height\", image_size[0])\n                width = input_per_image.get(\"width\", image_size[1])\n                sem_seg_r = sem_seg_postprocess(sem_seg_result, image_size, height, width)\n                detector_r = detector_postprocess(detector_result, height, width)\n\n                processed_results.append({\"sem_seg\": sem_seg_r, \"instances\": detector_r})\n\n                panoptic_r = combine_semantic_and_instance_outputs(\n                    detector_r,\n                    sem_seg_r.argmax(dim=0),\n                    self.combine_overlap_thresh,\n                    self.combine_stuff_area_thresh,\n                    self.combine_instances_score_thresh,\n                )\n                processed_results[-1][\"panoptic_seg\"] = panoptic_r\n            return processed_results\n        else:\n            return detector_results, sem_seg_results\n\n\ndef combine_semantic_and_instance_outputs(\n    instance_results,\n    semantic_results,\n    overlap_threshold,\n    stuff_area_thresh,\n    instances_score_thresh,\n):\n    \"\"\"\n    Implement a simple combining logic following\n    \"combine_semantic_and_instance_predictions.py\" in panopticapi\n    to produce panoptic segmentation outputs.\n\n    Args:\n        instance_results: output of :func:`detector_postprocess`.\n        semantic_results: an (H, W) tensor, each element is the contiguous semantic\n            category id\n\n    Returns:\n        panoptic_seg (Tensor): of shape (height, width) where the values are ids for each segment.\n        segments_info (list[dict]): Describe each segment in `panoptic_seg`.\n            Each dict contains keys \"id\", \"category_id\", \"isthing\".\n    \"\"\"\n    panoptic_seg = torch.zeros_like(semantic_results, dtype=torch.int32)\n\n    # sort instance outputs by scores\n    sorted_inds = torch.argsort(-instance_results.scores)\n\n    current_segment_id = 0\n    segments_info = []\n\n    instance_masks = instance_results.pred_masks.to(dtype=torch.bool, device=panoptic_seg.device)\n\n    # Add instances one-by-one, check for overlaps with existing ones\n    for inst_id in sorted_inds:\n        score = instance_results.scores[inst_id].item()\n        if score < instances_score_thresh:\n            break\n        mask = instance_masks[inst_id]  # H,W\n        mask_area = mask.sum().item()\n\n        if mask_area == 0:\n            continue\n\n        intersect = (mask > 0) & (panoptic_seg > 0)\n        intersect_area = intersect.sum().item()\n\n        if intersect_area * 1.0 / mask_area > overlap_threshold:\n            continue\n\n        if intersect_area > 0:\n            mask = mask & (panoptic_seg == 0)\n\n        current_segment_id += 1\n        cat = instance_results.pred_classes[inst_id].item()\n        cat = thing_id2cat[cat]\n        instance_id = cat * 10000 + current_segment_id\n        panoptic_seg[mask] = instance_id\n        segments_info.append(\n            {\n                \"id\": instance_id,\n                \"isthing\": True,\n                \"score\": score,\n                \"category_id\": cat,\n                \"instance_id\": inst_id.item(),\n            }\n        )\n\n    # Add semantic results to remaining empty areas\n    semantic_labels = torch.unique(semantic_results).cpu().tolist()\n    for semantic_label in semantic_labels:\n        if semantic_label == 0:  # 0 is a special \"thing\" class\n            continue\n        mask = (semantic_results == semantic_label) & (panoptic_seg == 0)\n        mask_area = mask.sum().item()\n        if mask_area < stuff_area_thresh:\n            continue\n\n        current_segment_id += 1\n        # cat = semantic_label\n        cat = stuff_id2cat[semantic_label]\n        stuff_id = cat * 10000\n        panoptic_seg[mask] = stuff_id\n        segments_info.append(\n            {\n                \"id\": stuff_id,\n                \"isthing\": False,\n                \"category_id\": cat,\n                \"area\": mask_area,\n            }\n        )\n\n    return panoptic_seg, segments_info"
  },
  {
    "path": "VPS_Module/detectron2/modeling/meta_arch/rcnn.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport logging\nimport numpy as np\nfrom typing import Dict, List, Optional, Tuple\nimport torch\nfrom torch import nn\n\nfrom detectron2.config import configurable\nfrom detectron2.data.detection_utils import convert_image_to_rgb\nfrom detectron2.structures import ImageList, Instances\nfrom detectron2.utils.events import get_event_storage\nfrom detectron2.utils.logger import log_first_n\n\nfrom ..backbone import Backbone, build_backbone\nfrom ..postprocessing import detector_postprocess\nfrom ..proposal_generator import build_proposal_generator\nfrom ..roi_heads import build_roi_heads\nfrom .build import META_ARCH_REGISTRY\n\n__all__ = [\"GeneralizedRCNN\", \"ProposalNetwork\"]\n\n\n@META_ARCH_REGISTRY.register()\nclass GeneralizedRCNN(nn.Module):\n    \"\"\"\n    Generalized R-CNN. Any models that contains the following three components:\n    1. Per-image feature extraction (aka backbone)\n    2. Region proposal generation\n    3. Per-region feature extraction and prediction\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self,\n        *,\n        backbone: Backbone,\n        proposal_generator: nn.Module,\n        roi_heads: nn.Module,\n        pixel_mean: Tuple[float],\n        pixel_std: Tuple[float],\n        input_format: Optional[str] = None,\n        vis_period: int = 0,\n    ):\n        \"\"\"\n        Args:\n            backbone: a backbone module, must follow detectron2's backbone interface\n            proposal_generator: a module that generates proposals using backbone features\n            roi_heads: a ROI head that performs per-region computation\n            pixel_mean, pixel_std: list or tuple with #channels element, representing\n                the per-channel mean and std to be used to normalize the input image\n            input_format: describe the meaning of channels of input. Needed by visualization\n            vis_period: the period to run visualization. Set to 0 to disable.\n        \"\"\"\n        super().__init__()\n        self.backbone = backbone\n\n        # for param in self.parameters(): \n        #     param.requires_grad = False\n            \n        self.proposal_generator = proposal_generator\n        self.roi_heads = roi_heads\n\n        self.input_format = input_format\n        self.vis_period = vis_period\n        if vis_period > 0:\n            assert input_format is not None, \"input_format is required for visualization!\"\n\n        self.register_buffer(\"pixel_mean\", torch.tensor(pixel_mean).view(-1, 1, 1), False)\n        self.register_buffer(\"pixel_std\", torch.tensor(pixel_std).view(-1, 1, 1), False)\n        assert (\n            self.pixel_mean.shape == self.pixel_std.shape\n        ), f\"{self.pixel_mean} and {self.pixel_std} have different shapes!\"\n\n    @classmethod\n    def from_config(cls, cfg):\n        backbone = build_backbone(cfg)\n        return {\n            \"backbone\": backbone,\n            \"proposal_generator\": build_proposal_generator(cfg, backbone.output_shape()),\n            \"roi_heads\": build_roi_heads(cfg, backbone.output_shape()),\n            \"input_format\": cfg.INPUT.FORMAT,\n            \"vis_period\": cfg.VIS_PERIOD,\n            \"pixel_mean\": cfg.MODEL.PIXEL_MEAN,\n            \"pixel_std\": cfg.MODEL.PIXEL_STD,\n        }\n\n    @property\n    def device(self):\n        return self.pixel_mean.device\n\n    def visualize_training(self, batched_inputs, proposals):\n        \"\"\"\n        A function used to visualize images and proposals. It shows ground truth\n        bounding boxes on the original image and up to 20 top-scoring predicted\n        object proposals on the original image. Users can implement different\n        visualization functions for different models.\n\n        Args:\n            batched_inputs (list): a list that contains input to the model.\n            proposals (list): a list that contains predicted proposals. Both\n                batched_inputs and proposals should have the same length.\n        \"\"\"\n        from detectron2.utils.visualizer import Visualizer\n\n        storage = get_event_storage()\n        max_vis_prop = 20\n\n        for input, prop in zip(batched_inputs, proposals):\n            img = input[\"image\"]\n            img = convert_image_to_rgb(img.permute(1, 2, 0), self.input_format)\n            v_gt = Visualizer(img, None)\n            v_gt = v_gt.overlay_instances(boxes=input[\"instances\"].gt_boxes)\n            anno_img = v_gt.get_image()\n            box_size = min(len(prop.proposal_boxes), max_vis_prop)\n            v_pred = Visualizer(img, None)\n            v_pred = v_pred.overlay_instances(\n                boxes=prop.proposal_boxes[0:box_size].tensor.cpu().numpy()\n            )\n            prop_img = v_pred.get_image()\n            vis_img = np.concatenate((anno_img, prop_img), axis=1)\n            vis_img = vis_img.transpose(2, 0, 1)\n            vis_name = \"Left: GT bounding boxes;  Right: Predicted proposals\"\n            storage.put_image(vis_name, vis_img)\n            break  # only visualize one image in a batch\n\n    def forward(self, batched_inputs: List[Dict[str, torch.Tensor]]):\n        \"\"\"\n        Args:\n            batched_inputs: a list, batched outputs of :class:`DatasetMapper` .\n                Each item in the list contains the inputs for one image.\n                For now, each item in the list is a dict that contains:\n\n                * image: Tensor, image in (C, H, W) format.\n                * instances (optional): groundtruth :class:`Instances`\n                * proposals (optional): :class:`Instances`, precomputed proposals.\n\n                Other information that's included in the original dicts, such as:\n\n                * \"height\", \"width\" (int): the output resolution of the model, used in inference.\n                  See :meth:`postprocess` for details.\n\n        Returns:\n            list[dict]:\n                Each dict is the output for one input image.\n                The dict contains one key \"instances\" whose value is a :class:`Instances`.\n                The :class:`Instances` object has the following keys:\n                \"pred_boxes\", \"pred_classes\", \"scores\", \"pred_masks\", \"pred_keypoints\"\n        \"\"\"\n        if not self.training:\n            return self.inference(batched_inputs)\n\n        images = self.preprocess_image(batched_inputs)\n        if \"instances\" in batched_inputs[0]:\n            gt_instances = [x[\"instances\"].to(self.device) for x in batched_inputs]\n        else:\n            gt_instances = None\n\n        features = self.backbone(images.tensor)\n\n        if self.proposal_generator is not None:\n            proposals, proposal_losses = self.proposal_generator(images, features, gt_instances)\n        else:\n            assert \"proposals\" in batched_inputs[0]\n            proposals = [x[\"proposals\"].to(self.device) for x in batched_inputs]\n            proposal_losses = {}\n\n        _, detector_losses = self.roi_heads(images, features, proposals, gt_instances)\n        if self.vis_period > 0:\n            storage = get_event_storage()\n            if storage.iter % self.vis_period == 0:\n                self.visualize_training(batched_inputs, proposals)\n\n        losses = {}\n        losses.update(detector_losses)\n        losses.update(proposal_losses)\n        return losses\n\n    def inference(\n        self,\n        batched_inputs: List[Dict[str, torch.Tensor]],\n        detected_instances: Optional[List[Instances]] = None,\n        do_postprocess: bool = True,\n    ):\n        \"\"\"\n        Run inference on the given inputs.\n\n        Args:\n            batched_inputs (list[dict]): same as in :meth:`forward`\n            detected_instances (None or list[Instances]): if not None, it\n                contains an `Instances` object per image. The `Instances`\n                object contains \"pred_boxes\" and \"pred_classes\" which are\n                known boxes in the image.\n                The inference will then skip the detection of bounding boxes,\n                and only predict other per-ROI outputs.\n            do_postprocess (bool): whether to apply post-processing on the outputs.\n\n        Returns:\n            When do_postprocess=True, same as in :meth:`forward`.\n            Otherwise, a list[Instances] containing raw network outputs.\n        \"\"\"\n        assert not self.training\n\n        images = self.preprocess_image(batched_inputs)\n        features = self.backbone(images.tensor)\n\n        if detected_instances is None:\n            if self.proposal_generator is not None:\n                proposals, _ = self.proposal_generator(images, features, None)\n            else:\n                assert \"proposals\" in batched_inputs[0]\n                proposals = [x[\"proposals\"].to(self.device) for x in batched_inputs]\n\n            results, _ = self.roi_heads(images, features, proposals, None)\n        else:\n            detected_instances = [x.to(self.device) for x in detected_instances]\n            results = self.roi_heads.forward_with_given_boxes(features, detected_instances)\n\n        if do_postprocess:\n            assert not torch.jit.is_scripting(), \"Scripting is not supported for postprocess.\"\n            return GeneralizedRCNN._postprocess(results, batched_inputs, images.image_sizes)\n        else:\n            return results\n\n    def preprocess_image(self, batched_inputs: List[Dict[str, torch.Tensor]]):\n        \"\"\"\n        Normalize, pad and batch the input images.\n        \"\"\"\n        images = [x[\"image\"].to(self.device) for x in batched_inputs]\n        images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n        images = ImageList.from_tensors(images, self.backbone.size_divisibility)\n        return images\n\n    @staticmethod\n    def _postprocess(instances, batched_inputs: List[Dict[str, torch.Tensor]], image_sizes):\n        \"\"\"\n        Rescale the output instances to the target size.\n        \"\"\"\n        # note: private function; subject to changes\n        processed_results = []\n        for results_per_image, input_per_image, image_size in zip(\n            instances, batched_inputs, image_sizes\n        ):\n            height = input_per_image.get(\"height\", image_size[0])\n            width = input_per_image.get(\"width\", image_size[1])\n            r = detector_postprocess(results_per_image, height, width)\n            processed_results.append({\"instances\": r})\n        return processed_results\n\n\n@META_ARCH_REGISTRY.register()\nclass ProposalNetwork(nn.Module):\n    \"\"\"\n    A meta architecture that only predicts object proposals.\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self,\n        *,\n        backbone: Backbone,\n        proposal_generator: nn.Module,\n        pixel_mean: Tuple[float],\n        pixel_std: Tuple[float],\n    ):\n        \"\"\"\n        Args:\n            backbone: a backbone module, must follow detectron2's backbone interface\n            proposal_generator: a module that generates proposals using backbone features\n            pixel_mean, pixel_std: list or tuple with #channels element, representing\n                the per-channel mean and std to be used to normalize the input image\n        \"\"\"\n        super().__init__()\n        self.backbone = backbone\n        self.proposal_generator = proposal_generator\n        self.register_buffer(\"pixel_mean\", torch.tensor(pixel_mean).view(-1, 1, 1), False)\n        self.register_buffer(\"pixel_std\", torch.tensor(pixel_std).view(-1, 1, 1), False)\n\n    @classmethod\n    def from_config(cls, cfg):\n        backbone = build_backbone(cfg)\n        return {\n            \"backbone\": backbone,\n            \"proposal_generator\": build_proposal_generator(cfg, backbone.output_shape()),\n            \"pixel_mean\": cfg.MODEL.PIXEL_MEAN,\n            \"pixel_std\": cfg.MODEL.PIXEL_STD,\n        }\n\n    @property\n    def device(self):\n        return self.pixel_mean.device\n\n    def forward(self, batched_inputs):\n        \"\"\"\n        Args:\n            Same as in :class:`GeneralizedRCNN.forward`\n\n        Returns:\n            list[dict]:\n                Each dict is the output for one input image.\n                The dict contains one key \"proposals\" whose value is a\n                :class:`Instances` with keys \"proposal_boxes\" and \"objectness_logits\".\n        \"\"\"\n        images = [x[\"image\"].to(self.device) for x in batched_inputs]\n        images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n        images = ImageList.from_tensors(images, self.backbone.size_divisibility)\n        features = self.backbone(images.tensor)\n\n        if \"instances\" in batched_inputs[0]:\n            gt_instances = [x[\"instances\"].to(self.device) for x in batched_inputs]\n        elif \"targets\" in batched_inputs[0]:\n            log_first_n(\n                logging.WARN, \"'targets' in the model inputs is now renamed to 'instances'!\", n=10\n            )\n            gt_instances = [x[\"targets\"].to(self.device) for x in batched_inputs]\n        else:\n            gt_instances = None\n        proposals, proposal_losses = self.proposal_generator(images, features, gt_instances)\n        # In training, the proposals are not useful at all but we generate them anyway.\n        # This makes RPN-only models about 5% slower.\n        if self.training:\n            return proposal_losses\n\n        processed_results = []\n        for results_per_image, input_per_image, image_size in zip(\n            proposals, batched_inputs, images.image_sizes\n        ):\n            height = input_per_image.get(\"height\", image_size[0])\n            width = input_per_image.get(\"width\", image_size[1])\n            r = detector_postprocess(results_per_image, height, width)\n            processed_results.append({\"proposals\": r})\n        return processed_results\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/meta_arch/retinanet.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport logging\nimport math\nfrom typing import List, Tuple\nimport torch\nfrom fvcore.nn import sigmoid_focal_loss_jit\nfrom torch import Tensor, nn\nfrom torch.nn import functional as F\n\nfrom detectron2.config import configurable\nfrom detectron2.layers import CycleBatchNormList, ShapeSpec, batched_nms, cat, get_norm\nfrom detectron2.structures import Boxes, ImageList, Instances, pairwise_iou\nfrom detectron2.utils.events import get_event_storage\n\nfrom ..anchor_generator import build_anchor_generator\nfrom ..backbone import Backbone, build_backbone\nfrom ..box_regression import Box2BoxTransform, _dense_box_regression_loss\nfrom ..matcher import Matcher\nfrom .build import META_ARCH_REGISTRY\nfrom .dense_detector import DenseDetector, permute_to_N_HWA_K  # noqa\n\n__all__ = [\"RetinaNet\"]\n\n\nlogger = logging.getLogger(__name__)\n\n\n@META_ARCH_REGISTRY.register()\nclass RetinaNet(DenseDetector):\n    \"\"\"\n    Implement RetinaNet in :paper:`RetinaNet`.\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self,\n        *,\n        backbone: Backbone,\n        head: nn.Module,\n        head_in_features,\n        anchor_generator,\n        box2box_transform,\n        anchor_matcher,\n        num_classes,\n        focal_loss_alpha=0.25,\n        focal_loss_gamma=2.0,\n        smooth_l1_beta=0.0,\n        box_reg_loss_type=\"smooth_l1\",\n        test_score_thresh=0.05,\n        test_topk_candidates=1000,\n        test_nms_thresh=0.5,\n        max_detections_per_image=100,\n        pixel_mean,\n        pixel_std,\n        vis_period=0,\n        input_format=\"BGR\",\n    ):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            backbone: a backbone module, must follow detectron2's backbone interface\n            head (nn.Module): a module that predicts logits and regression deltas\n                for each level from a list of per-level features\n            head_in_features (Tuple[str]): Names of the input feature maps to be used in head\n            anchor_generator (nn.Module): a module that creates anchors from a\n                list of features. Usually an instance of :class:`AnchorGenerator`\n            box2box_transform (Box2BoxTransform): defines the transform from anchors boxes to\n                instance boxes\n            anchor_matcher (Matcher): label the anchors by matching them with ground truth.\n            num_classes (int): number of classes. Used to label background proposals.\n\n            # Loss parameters:\n            focal_loss_alpha (float): focal_loss_alpha\n            focal_loss_gamma (float): focal_loss_gamma\n            smooth_l1_beta (float): smooth_l1_beta\n            box_reg_loss_type (str): Options are \"smooth_l1\", \"giou\", \"diou\", \"ciou\"\n\n            # Inference parameters:\n            test_score_thresh (float): Inference cls score threshold, only anchors with\n                score > INFERENCE_TH are considered for inference (to improve speed)\n            test_topk_candidates (int): Select topk candidates before NMS\n            test_nms_thresh (float): Overlap threshold used for non-maximum suppression\n                (suppress boxes with IoU >= this threshold)\n            max_detections_per_image (int):\n                Maximum number of detections to return per image during inference\n                (100 is based on the limit established for the COCO dataset).\n\n            pixel_mean, pixel_std: see :class:`DenseDetector`.\n        \"\"\"\n        super().__init__(\n            backbone, head, head_in_features, pixel_mean=pixel_mean, pixel_std=pixel_std\n        )\n        self.num_classes = num_classes\n\n        # Anchors\n        self.anchor_generator = anchor_generator\n        self.box2box_transform = box2box_transform\n        self.anchor_matcher = anchor_matcher\n\n        # Loss parameters:\n        self.focal_loss_alpha = focal_loss_alpha\n        self.focal_loss_gamma = focal_loss_gamma\n        self.smooth_l1_beta = smooth_l1_beta\n        self.box_reg_loss_type = box_reg_loss_type\n        # Inference parameters:\n        self.test_score_thresh = test_score_thresh\n        self.test_topk_candidates = test_topk_candidates\n        self.test_nms_thresh = test_nms_thresh\n        self.max_detections_per_image = max_detections_per_image\n        # Vis parameters\n        self.vis_period = vis_period\n        self.input_format = input_format\n\n    @classmethod\n    def from_config(cls, cfg):\n        backbone = build_backbone(cfg)\n        backbone_shape = backbone.output_shape()\n        feature_shapes = [backbone_shape[f] for f in cfg.MODEL.RETINANET.IN_FEATURES]\n        head = RetinaNetHead(cfg, feature_shapes)\n        anchor_generator = build_anchor_generator(cfg, feature_shapes)\n        return {\n            \"backbone\": backbone,\n            \"head\": head,\n            \"anchor_generator\": anchor_generator,\n            \"box2box_transform\": Box2BoxTransform(weights=cfg.MODEL.RETINANET.BBOX_REG_WEIGHTS),\n            \"anchor_matcher\": Matcher(\n                cfg.MODEL.RETINANET.IOU_THRESHOLDS,\n                cfg.MODEL.RETINANET.IOU_LABELS,\n                allow_low_quality_matches=True,\n            ),\n            \"pixel_mean\": cfg.MODEL.PIXEL_MEAN,\n            \"pixel_std\": cfg.MODEL.PIXEL_STD,\n            \"num_classes\": cfg.MODEL.RETINANET.NUM_CLASSES,\n            \"head_in_features\": cfg.MODEL.RETINANET.IN_FEATURES,\n            # Loss parameters:\n            \"focal_loss_alpha\": cfg.MODEL.RETINANET.FOCAL_LOSS_ALPHA,\n            \"focal_loss_gamma\": cfg.MODEL.RETINANET.FOCAL_LOSS_GAMMA,\n            \"smooth_l1_beta\": cfg.MODEL.RETINANET.SMOOTH_L1_LOSS_BETA,\n            \"box_reg_loss_type\": cfg.MODEL.RETINANET.BBOX_REG_LOSS_TYPE,\n            # Inference parameters:\n            \"test_score_thresh\": cfg.MODEL.RETINANET.SCORE_THRESH_TEST,\n            \"test_topk_candidates\": cfg.MODEL.RETINANET.TOPK_CANDIDATES_TEST,\n            \"test_nms_thresh\": cfg.MODEL.RETINANET.NMS_THRESH_TEST,\n            \"max_detections_per_image\": cfg.TEST.DETECTIONS_PER_IMAGE,\n            # Vis parameters\n            \"vis_period\": cfg.VIS_PERIOD,\n            \"input_format\": cfg.INPUT.FORMAT,\n        }\n\n    def forward_training(self, images, features, predictions, gt_instances):\n        # Transpose the Hi*Wi*A dimension to the middle:\n        pred_logits, pred_anchor_deltas = self._transpose_dense_predictions(\n            predictions, [self.num_classes, 4]\n        )\n        anchors = self.anchor_generator(features)\n        gt_labels, gt_boxes = self.label_anchors(anchors, gt_instances)\n        return self.losses(anchors, pred_logits, gt_labels, pred_anchor_deltas, gt_boxes)\n\n    def losses(self, anchors, pred_logits, gt_labels, pred_anchor_deltas, gt_boxes):\n        \"\"\"\n        Args:\n            anchors (list[Boxes]): a list of #feature level Boxes\n            gt_labels, gt_boxes: see output of :meth:`RetinaNet.label_anchors`.\n                Their shapes are (N, R) and (N, R, 4), respectively, where R is\n                the total number of anchors across levels, i.e. sum(Hi x Wi x Ai)\n            pred_logits, pred_anchor_deltas: both are list[Tensor]. Each element in the\n                list corresponds to one level and has shape (N, Hi * Wi * Ai, K or 4).\n                Where K is the number of classes used in `pred_logits`.\n\n        Returns:\n            dict[str, Tensor]:\n                mapping from a named loss to a scalar tensor storing the loss.\n                Used during training only. The dict keys are: \"loss_cls\" and \"loss_box_reg\"\n        \"\"\"\n        num_images = len(gt_labels)\n        gt_labels = torch.stack(gt_labels)  # (N, R)\n\n        valid_mask = gt_labels >= 0\n        pos_mask = (gt_labels >= 0) & (gt_labels != self.num_classes)\n        num_pos_anchors = pos_mask.sum().item()\n        get_event_storage().put_scalar(\"num_pos_anchors\", num_pos_anchors / num_images)\n        normalizer = self._ema_update(\"loss_normalizer\", max(num_pos_anchors, 1), 100)\n\n        # classification and regression loss\n        gt_labels_target = F.one_hot(gt_labels[valid_mask], num_classes=self.num_classes + 1)[\n            :, :-1\n        ]  # no loss for the last (background) class\n        loss_cls = sigmoid_focal_loss_jit(\n            cat(pred_logits, dim=1)[valid_mask],\n            gt_labels_target.to(pred_logits[0].dtype),\n            alpha=self.focal_loss_alpha,\n            gamma=self.focal_loss_gamma,\n            reduction=\"sum\",\n        )\n\n        loss_box_reg = _dense_box_regression_loss(\n            anchors,\n            self.box2box_transform,\n            pred_anchor_deltas,\n            gt_boxes,\n            pos_mask,\n            box_reg_loss_type=self.box_reg_loss_type,\n            smooth_l1_beta=self.smooth_l1_beta,\n        )\n\n        return {\n            \"loss_cls\": loss_cls / normalizer,\n            \"loss_box_reg\": loss_box_reg / normalizer,\n        }\n\n    @torch.no_grad()\n    def label_anchors(self, anchors, gt_instances):\n        \"\"\"\n        Args:\n            anchors (list[Boxes]): A list of #feature level Boxes.\n                The Boxes contains anchors of this image on the specific feature level.\n            gt_instances (list[Instances]): a list of N `Instances`s. The i-th\n                `Instances` contains the ground-truth per-instance annotations\n                for the i-th input image.\n\n        Returns:\n            list[Tensor]: List of #img tensors. i-th element is a vector of labels whose length is\n            the total number of anchors across all feature maps (sum(Hi * Wi * A)).\n            Label values are in {-1, 0, ..., K}, with -1 means ignore, and K means background.\n\n            list[Tensor]: i-th element is a Rx4 tensor, where R is the total number of anchors\n            across feature maps. The values are the matched gt boxes for each anchor.\n            Values are undefined for those anchors not labeled as foreground.\n        \"\"\"\n        anchors = Boxes.cat(anchors)  # Rx4\n\n        gt_labels = []\n        matched_gt_boxes = []\n        for gt_per_image in gt_instances:\n            match_quality_matrix = pairwise_iou(gt_per_image.gt_boxes, anchors)\n            matched_idxs, anchor_labels = self.anchor_matcher(match_quality_matrix)\n            del match_quality_matrix\n\n            if len(gt_per_image) > 0:\n                matched_gt_boxes_i = gt_per_image.gt_boxes.tensor[matched_idxs]\n\n                gt_labels_i = gt_per_image.gt_classes[matched_idxs]\n                # Anchors with label 0 are treated as background.\n                gt_labels_i[anchor_labels == 0] = self.num_classes\n                # Anchors with label -1 are ignored.\n                gt_labels_i[anchor_labels == -1] = -1\n            else:\n                matched_gt_boxes_i = torch.zeros_like(anchors.tensor)\n                gt_labels_i = torch.zeros_like(matched_idxs) + self.num_classes\n\n            gt_labels.append(gt_labels_i)\n            matched_gt_boxes.append(matched_gt_boxes_i)\n\n        return gt_labels, matched_gt_boxes\n\n    def forward_inference(\n        self, images: ImageList, features: List[Tensor], predictions: List[List[Tensor]]\n    ):\n        pred_logits, pred_anchor_deltas = self._transpose_dense_predictions(\n            predictions, [self.num_classes, 4]\n        )\n        anchors = self.anchor_generator(features)\n\n        results: List[Instances] = []\n        for img_idx, image_size in enumerate(images.image_sizes):\n            scores_per_image = [x[img_idx].sigmoid_() for x in pred_logits]\n            deltas_per_image = [x[img_idx] for x in pred_anchor_deltas]\n            results_per_image = self.inference_single_image(\n                anchors, scores_per_image, deltas_per_image, image_size\n            )\n            results.append(results_per_image)\n        return results\n\n    def inference_single_image(\n        self,\n        anchors: List[Boxes],\n        box_cls: List[Tensor],\n        box_delta: List[Tensor],\n        image_size: Tuple[int, int],\n    ):\n        \"\"\"\n        Single-image inference. Return bounding-box detection results by thresholding\n        on scores and applying non-maximum suppression (NMS).\n\n        Arguments:\n            anchors (list[Boxes]): list of #feature levels. Each entry contains\n                a Boxes object, which contains all the anchors in that feature level.\n            box_cls (list[Tensor]): list of #feature levels. Each entry contains\n                tensor of size (H x W x A, K)\n            box_delta (list[Tensor]): Same shape as 'box_cls' except that K becomes 4.\n            image_size (tuple(H, W)): a tuple of the image height and width.\n\n        Returns:\n            Same as `inference`, but for only one image.\n        \"\"\"\n        pred = self._decode_multi_level_predictions(\n            anchors,\n            box_cls,\n            box_delta,\n            self.test_score_thresh,\n            self.test_topk_candidates,\n            image_size,\n        )\n        keep = batched_nms(  # per-class NMS\n            pred.pred_boxes.tensor, pred.scores, pred.pred_classes, self.test_nms_thresh\n        )\n        return pred[keep[: self.max_detections_per_image]]\n\n\nclass RetinaNetHead(nn.Module):\n    \"\"\"\n    The head used in RetinaNet for object classification and box regression.\n    It has two subnets for the two tasks, with a common structure but separate parameters.\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self,\n        *,\n        input_shape: List[ShapeSpec],\n        num_classes,\n        num_anchors,\n        conv_dims: List[int],\n        norm=\"\",\n        prior_prob=0.01,\n    ):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            input_shape (List[ShapeSpec]): input shape\n            num_classes (int): number of classes. Used to label background proposals.\n            num_anchors (int): number of generated anchors\n            conv_dims (List[int]): dimensions for each convolution layer\n            norm (str or callable):\n                Normalization for conv layers except for the two output layers.\n                See :func:`detectron2.layers.get_norm` for supported types.\n            prior_prob (float): Prior weight for computing bias\n        \"\"\"\n        super().__init__()\n\n        self._num_features = len(input_shape)\n        if norm == \"BN\" or norm == \"SyncBN\":\n            logger.info(\n                f\"Using domain-specific {norm} in RetinaNetHead with len={self._num_features}.\"\n            )\n            bn_class = nn.BatchNorm2d if norm == \"BN\" else nn.SyncBatchNorm\n\n            def norm(c):\n                return CycleBatchNormList(\n                    length=self._num_features, bn_class=bn_class, num_features=c\n                )\n\n        else:\n            norm_name = str(type(get_norm(norm, 1)))\n            if \"BN\" in norm_name:\n                logger.warning(\n                    f\"Shared BatchNorm (type={norm_name}) may not work well in RetinaNetHead.\"\n                )\n\n        cls_subnet = []\n        bbox_subnet = []\n        for in_channels, out_channels in zip(\n            [input_shape[0].channels] + list(conv_dims), conv_dims\n        ):\n            cls_subnet.append(\n                nn.Conv2d(in_channels, out_channels, kernel_size=3, stride=1, padding=1)\n            )\n            if norm:\n                cls_subnet.append(get_norm(norm, out_channels))\n            cls_subnet.append(nn.ReLU())\n            bbox_subnet.append(\n                nn.Conv2d(in_channels, out_channels, kernel_size=3, stride=1, padding=1)\n            )\n            if norm:\n                bbox_subnet.append(get_norm(norm, out_channels))\n            bbox_subnet.append(nn.ReLU())\n\n        self.cls_subnet = nn.Sequential(*cls_subnet)\n        self.bbox_subnet = nn.Sequential(*bbox_subnet)\n        self.cls_score = nn.Conv2d(\n            conv_dims[-1], num_anchors * num_classes, kernel_size=3, stride=1, padding=1\n        )\n        self.bbox_pred = nn.Conv2d(\n            conv_dims[-1], num_anchors * 4, kernel_size=3, stride=1, padding=1\n        )\n\n        # Initialization\n        for modules in [self.cls_subnet, self.bbox_subnet, self.cls_score, self.bbox_pred]:\n            for layer in modules.modules():\n                if isinstance(layer, nn.Conv2d):\n                    torch.nn.init.normal_(layer.weight, mean=0, std=0.01)\n                    torch.nn.init.constant_(layer.bias, 0)\n\n        # Use prior in model initialization to improve stability\n        bias_value = -(math.log((1 - prior_prob) / prior_prob))\n        torch.nn.init.constant_(self.cls_score.bias, bias_value)\n\n    @classmethod\n    def from_config(cls, cfg, input_shape: List[ShapeSpec]):\n        num_anchors = build_anchor_generator(cfg, input_shape).num_cell_anchors\n        assert (\n            len(set(num_anchors)) == 1\n        ), \"Using different number of anchors between levels is not currently supported!\"\n        num_anchors = num_anchors[0]\n\n        return {\n            \"input_shape\": input_shape,\n            \"num_classes\": cfg.MODEL.RETINANET.NUM_CLASSES,\n            \"conv_dims\": [input_shape[0].channels] * cfg.MODEL.RETINANET.NUM_CONVS,\n            \"prior_prob\": cfg.MODEL.RETINANET.PRIOR_PROB,\n            \"norm\": cfg.MODEL.RETINANET.NORM,\n            \"num_anchors\": num_anchors,\n        }\n\n    def forward(self, features: List[Tensor]):\n        \"\"\"\n        Arguments:\n            features (list[Tensor]): FPN feature map tensors in high to low resolution.\n                Each tensor in the list correspond to different feature levels.\n\n        Returns:\n            logits (list[Tensor]): #lvl tensors, each has shape (N, AxK, Hi, Wi).\n                The tensor predicts the classification probability\n                at each spatial position for each of the A anchors and K object\n                classes.\n            bbox_reg (list[Tensor]): #lvl tensors, each has shape (N, Ax4, Hi, Wi).\n                The tensor predicts 4-vector (dx,dy,dw,dh) box\n                regression values for every anchor. These values are the\n                relative offset between the anchor and the ground truth box.\n        \"\"\"\n        assert len(features) == self._num_features\n        logits = []\n        bbox_reg = []\n        for feature in features:\n            logits.append(self.cls_score(self.cls_subnet(feature)))\n            bbox_reg.append(self.bbox_pred(self.bbox_subnet(feature)))\n        return logits, bbox_reg\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/meta_arch/semantic_seg.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport numpy as np\nfrom typing import Callable, Dict, Optional, Tuple, Union\nimport fvcore.nn.weight_init as weight_init\nimport torch\nfrom torch import nn\nfrom torch.nn import functional as F\n\nfrom detectron2.config import configurable\nfrom detectron2.layers import Conv2d, ShapeSpec, get_norm\nfrom detectron2.structures import ImageList\nfrom detectron2.utils.registry import Registry\n\nfrom ..backbone import Backbone, build_backbone\nfrom ..postprocessing import sem_seg_postprocess\nfrom .build import META_ARCH_REGISTRY\n\n__all__ = [\n    \"SemanticSegmentor\",\n    \"SEM_SEG_HEADS_REGISTRY\",\n    \"SemSegFPNHead\",\n    \"build_sem_seg_head\",\n]\n\n\nSEM_SEG_HEADS_REGISTRY = Registry(\"SEM_SEG_HEADS\")\nSEM_SEG_HEADS_REGISTRY.__doc__ = \"\"\"\nRegistry for semantic segmentation heads, which make semantic segmentation predictions\nfrom feature maps.\n\"\"\"\n\n\n@META_ARCH_REGISTRY.register()\nclass SemanticSegmentor(nn.Module):\n    \"\"\"\n    Main class for semantic segmentation architectures.\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self,\n        *,\n        backbone: Backbone,\n        sem_seg_head: nn.Module,\n        pixel_mean: Tuple[float],\n        pixel_std: Tuple[float],\n    ):\n        \"\"\"\n        Args:\n            backbone: a backbone module, must follow detectron2's backbone interface\n            sem_seg_head: a module that predicts semantic segmentation from backbone features\n            pixel_mean, pixel_std: list or tuple with #channels element, representing\n                the per-channel mean and std to be used to normalize the input image\n        \"\"\"\n        super().__init__()\n        self.backbone = backbone\n        self.sem_seg_head = sem_seg_head\n        self.register_buffer(\"pixel_mean\", torch.tensor(pixel_mean).view(-1, 1, 1), False)\n        self.register_buffer(\"pixel_std\", torch.tensor(pixel_std).view(-1, 1, 1), False)\n\n    @classmethod\n    def from_config(cls, cfg):\n        backbone = build_backbone(cfg)\n        sem_seg_head = build_sem_seg_head(cfg, backbone.output_shape())\n        return {\n            \"backbone\": backbone,\n            \"sem_seg_head\": sem_seg_head,\n            \"pixel_mean\": cfg.MODEL.PIXEL_MEAN,\n            \"pixel_std\": cfg.MODEL.PIXEL_STD,\n        }\n\n    @property\n    def device(self):\n        return self.pixel_mean.device\n\n    def forward(self, batched_inputs):\n        \"\"\"\n        Args:\n            batched_inputs: a list, batched outputs of :class:`DatasetMapper`.\n                Each item in the list contains the inputs for one image.\n\n                For now, each item in the list is a dict that contains:\n\n                   * \"image\": Tensor, image in (C, H, W) format.\n                   * \"sem_seg\": semantic segmentation ground truth\n                   * Other information that's included in the original dicts, such as:\n                     \"height\", \"width\" (int): the output resolution of the model (may be different\n                     from input resolution), used in inference.\n\n\n        Returns:\n            list[dict]:\n              Each dict is the output for one input image.\n              The dict contains one key \"sem_seg\" whose value is a\n              Tensor that represents the\n              per-pixel segmentation prediced by the head.\n              The prediction has shape KxHxW that represents the logits of\n              each class for each pixel.\n        \"\"\"\n        images = [x[\"image\"].to(self.device) for x in batched_inputs]\n        images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n        images = ImageList.from_tensors(images, self.backbone.size_divisibility)\n\n        features = self.backbone(images.tensor)\n\n        if \"sem_seg\" in batched_inputs[0]:\n            targets = [x[\"sem_seg\"].to(self.device) for x in batched_inputs]\n            targets = ImageList.from_tensors(\n                targets, self.backbone.size_divisibility, self.sem_seg_head.ignore_value\n            ).tensor\n        else:\n            targets = None\n        results, losses = self.sem_seg_head(features, targets)\n\n        if self.training:\n            return losses\n\n        processed_results = []\n        for result, input_per_image, image_size in zip(results, batched_inputs, images.image_sizes):\n            height = input_per_image.get(\"height\", image_size[0])\n            width = input_per_image.get(\"width\", image_size[1])\n            r = sem_seg_postprocess(result, image_size, height, width)\n            processed_results.append({\"sem_seg\": r})\n        return processed_results\n\n\ndef build_sem_seg_head(cfg, input_shape):\n    \"\"\"\n    Build a semantic segmentation head from `cfg.MODEL.SEM_SEG_HEAD.NAME`.\n    \"\"\"\n    name = cfg.MODEL.SEM_SEG_HEAD.NAME\n    return SEM_SEG_HEADS_REGISTRY.get(name)(cfg, input_shape)\n\n\n@SEM_SEG_HEADS_REGISTRY.register()\nclass SemSegFPNHead(nn.Module):\n    \"\"\"\n    A semantic segmentation head described in :paper:`PanopticFPN`.\n    It takes a list of FPN features as input, and applies a sequence of\n    3x3 convs and upsampling to scale all of them to the stride defined by\n    ``common_stride``. Then these features are added and used to make final\n    predictions by another 1x1 conv layer.\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self,\n        input_shape: Dict[str, ShapeSpec],\n        *,\n        num_classes: int,\n        conv_dims: int,\n        common_stride: int,\n        loss_weight: float = 1.0,\n        norm: Optional[Union[str, Callable]] = None,\n        ignore_value: int = -1,\n    ):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            input_shape: shapes (channels and stride) of the input features\n            num_classes: number of classes to predict\n            conv_dims: number of output channels for the intermediate conv layers.\n            common_stride: the common stride that all features will be upscaled to\n            loss_weight: loss weight\n            norm (str or callable): normalization for all conv layers\n            ignore_value: category id to be ignored during training.\n        \"\"\"\n        super().__init__()\n        input_shape = sorted(input_shape.items(), key=lambda x: x[1].stride)\n        if not len(input_shape):\n            raise ValueError(\"SemSegFPNHead(input_shape=) cannot be empty!\")\n        self.in_features = [k for k, v in input_shape]\n        feature_strides = [v.stride for k, v in input_shape]\n        feature_channels = [v.channels for k, v in input_shape]\n\n        self.ignore_value = ignore_value\n        self.common_stride = common_stride\n        self.loss_weight = loss_weight\n\n        self.scale_heads = []\n        for in_feature, stride, channels in zip(\n            self.in_features, feature_strides, feature_channels\n        ):\n            head_ops = []\n            head_length = max(1, int(np.log2(stride) - np.log2(self.common_stride)))\n            for k in range(head_length):\n                norm_module = get_norm(norm, conv_dims)\n                conv = Conv2d(\n                    channels if k == 0 else conv_dims,\n                    conv_dims,\n                    kernel_size=3,\n                    stride=1,\n                    padding=1,\n                    bias=not norm,\n                    norm=norm_module,\n                    activation=F.relu,\n                )\n                weight_init.c2_msra_fill(conv)\n                head_ops.append(conv)\n                if stride != self.common_stride:\n                    head_ops.append(\n                        nn.Upsample(scale_factor=2, mode=\"bilinear\", align_corners=False)\n                    )\n            self.scale_heads.append(nn.Sequential(*head_ops))\n            self.add_module(in_feature, self.scale_heads[-1])\n        self.predictor = Conv2d(conv_dims, num_classes, kernel_size=1, stride=1, padding=0)\n        weight_init.c2_msra_fill(self.predictor)\n\n    @classmethod\n    def from_config(cls, cfg, input_shape: Dict[str, ShapeSpec]):\n        return {\n            \"input_shape\": {\n                k: v for k, v in input_shape.items() if k in cfg.MODEL.SEM_SEG_HEAD.IN_FEATURES\n            },\n            \"ignore_value\": cfg.MODEL.SEM_SEG_HEAD.IGNORE_VALUE,\n            \"num_classes\": cfg.MODEL.SEM_SEG_HEAD.NUM_CLASSES,\n            \"conv_dims\": cfg.MODEL.SEM_SEG_HEAD.CONVS_DIM,\n            \"common_stride\": cfg.MODEL.SEM_SEG_HEAD.COMMON_STRIDE,\n            \"norm\": cfg.MODEL.SEM_SEG_HEAD.NORM,\n            \"loss_weight\": cfg.MODEL.SEM_SEG_HEAD.LOSS_WEIGHT,\n        }\n\n    def forward(self, features, targets=None):\n        \"\"\"\n        Returns:\n            In training, returns (None, dict of losses)\n            In inference, returns (CxHxW logits, {})\n        \"\"\"\n        x = self.layers(features)\n        if self.training:\n            # return None, self.losses(x, targets)\n            seg = F.interpolate(\n                x, scale_factor=self.common_stride, mode=\"bilinear\", align_corners=False\n            )\n            return seg, self.losses(x, targets)\n        else:\n            x = F.interpolate(\n                x, scale_factor=self.common_stride, mode=\"bilinear\", align_corners=False\n            )\n            return x, {}\n\n    def layers(self, features):\n        for i, f in enumerate(self.in_features):\n            if i == 0:\n                x = self.scale_heads[i](features[f])\n            else:\n                x = x + self.scale_heads[i](features[f])\n        # print(x.shape) # 3x128x96x312\n        x = self.predictor(x) # 3x12x96x312 (batch x num_cls x 1/4)\n        return x\n\n    def losses(self, predictions, targets):\n        predictions = predictions.float()  # https://github.com/pytorch/pytorch/issues/48163\n        predictions = F.interpolate(\n            predictions,\n            scale_factor=self.common_stride,\n            mode=\"bilinear\",\n            align_corners=False,\n        )\n        loss = F.cross_entropy(\n            predictions, targets, reduction=\"mean\", ignore_index=self.ignore_value\n        )\n        losses = {\"loss_sem_seg\": loss * self.loss_weight}\n        return losses\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/mmdet_wrapper.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport itertools\nimport logging\nimport numpy as np\nfrom collections import OrderedDict\nfrom collections.abc import Mapping\nfrom typing import Dict, List, Optional, Tuple, Union\nimport torch\nfrom omegaconf import DictConfig, OmegaConf\nfrom torch import Tensor, nn\n\nfrom detectron2.layers import ShapeSpec\nfrom detectron2.structures import BitMasks, Boxes, ImageList, Instances\nfrom detectron2.utils.events import get_event_storage\n\nfrom .backbone import Backbone\n\nlogger = logging.getLogger(__name__)\n\n\ndef _to_container(cfg):\n    \"\"\"\n    mmdet will assert the type of dict/list.\n    So convert omegaconf objects to dict/list.\n    \"\"\"\n    if isinstance(cfg, DictConfig):\n        cfg = OmegaConf.to_container(cfg, resolve=True)\n    from mmcv.utils import ConfigDict\n\n    return ConfigDict(cfg)\n\n\nclass MMDetBackbone(Backbone):\n    \"\"\"\n    Wrapper of mmdetection backbones to use in detectron2.\n\n    mmdet backbones produce list/tuple of tensors, while detectron2 backbones\n    produce a dict of tensors. This class wraps the given backbone to produce\n    output in detectron2's convention, so it can be used in place of detectron2\n    backbones.\n    \"\"\"\n\n    def __init__(\n        self,\n        backbone: Union[nn.Module, Mapping],\n        neck: Union[nn.Module, Mapping, None] = None,\n        *,\n        output_shapes: List[ShapeSpec],\n        output_names: Optional[List[str]] = None,\n    ):\n        \"\"\"\n        Args:\n            backbone: either a backbone module or a mmdet config dict that defines a\n                backbone. The backbone takes a 4D image tensor and returns a\n                sequence of tensors.\n            neck: either a backbone module or a mmdet config dict that defines a\n                neck. The neck takes outputs of backbone and returns a\n                sequence of tensors. If None, no neck is used.\n            pretrained_backbone: defines the backbone weights that can be loaded by\n                mmdet, such as \"torchvision://resnet50\".\n            output_shapes: shape for every output of the backbone (or neck, if given).\n                stride and channels are often needed.\n            output_names: names for every output of the backbone (or neck, if given).\n                By default, will use \"out0\", \"out1\", ...\n        \"\"\"\n        super().__init__()\n        if isinstance(backbone, Mapping):\n            from mmdet.models import build_backbone\n\n            backbone = build_backbone(_to_container(backbone))\n        self.backbone = backbone\n\n        if isinstance(neck, Mapping):\n            from mmdet.models import build_neck\n\n            neck = build_neck(_to_container(neck))\n        self.neck = neck\n\n        # \"Neck\" weights, if any, are part of neck itself. This is the interface\n        # of mmdet so we follow it. Reference:\n        # https://github.com/open-mmlab/mmdetection/blob/master/mmdet/models/detectors/two_stage.py\n        logger.info(\"Initializing mmdet backbone weights...\")\n        self.backbone.init_weights()\n        # train() in mmdet modules is non-trivial, and has to be explicitly\n        # called. Reference:\n        # https://github.com/open-mmlab/mmdetection/blob/master/mmdet/models/backbones/resnet.py\n        self.backbone.train()\n        if self.neck is not None:\n            logger.info(\"Initializing mmdet neck weights ...\")\n            if isinstance(self.neck, nn.Sequential):\n                for m in self.neck:\n                    m.init_weights()\n            else:\n                self.neck.init_weights()\n            self.neck.train()\n\n        self._output_shapes = output_shapes\n        if not output_names:\n            output_names = [f\"out{i}\" for i in range(len(output_shapes))]\n        self._output_names = output_names\n\n    def forward(self, x) -> Dict[str, Tensor]:\n        outs = self.backbone(x)\n        if self.neck is not None:\n            outs = self.neck(outs)\n        assert isinstance(\n            outs, (list, tuple)\n        ), \"mmdet backbone should return a list/tuple of tensors!\"\n        if len(outs) != len(self._output_shapes):\n            raise ValueError(\n                \"Length of output_shapes does not match outputs from the mmdet backbone: \"\n                f\"{len(outs)} != {len(self._output_shapes)}\"\n            )\n        return {k: v for k, v in zip(self._output_names, outs)}\n\n    def output_shape(self) -> Dict[str, ShapeSpec]:\n        return {k: v for k, v in zip(self._output_names, self._output_shapes)}\n\n\nclass MMDetDetector(nn.Module):\n    \"\"\"\n    Wrapper of a mmdetection detector model, for detection and instance segmentation.\n    Input/output formats of this class follow detectron2's convention, so a\n    mmdetection model can be trained and evaluated in detectron2.\n    \"\"\"\n\n    def __init__(\n        self,\n        detector: Union[nn.Module, Mapping],\n        *,\n        # Default is 32 regardless of model:\n        # https://github.com/open-mmlab/mmdetection/tree/master/configs/_base_/datasets\n        size_divisibility=32,\n        pixel_mean: Tuple[float],\n        pixel_std: Tuple[float],\n    ):\n        \"\"\"\n        Args:\n            detector: a mmdet detector, or a mmdet config dict that defines a detector.\n            size_divisibility: pad input images to multiple of this number\n            pixel_mean: per-channel mean to normalize input image\n            pixel_std: per-channel stddev to normalize input image\n        \"\"\"\n        super().__init__()\n        if isinstance(detector, Mapping):\n            from mmdet.models import build_detector\n\n            detector = build_detector(_to_container(detector))\n        self.detector = detector\n        self.size_divisibility = size_divisibility\n\n        self.register_buffer(\"pixel_mean\", torch.tensor(pixel_mean).view(-1, 1, 1), False)\n        self.register_buffer(\"pixel_std\", torch.tensor(pixel_std).view(-1, 1, 1), False)\n        assert (\n            self.pixel_mean.shape == self.pixel_std.shape\n        ), f\"{self.pixel_mean} and {self.pixel_std} have different shapes!\"\n\n    def forward(self, batched_inputs: List[Dict[str, torch.Tensor]]):\n        images = [x[\"image\"].to(self.device) for x in batched_inputs]\n        images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n        images = ImageList.from_tensors(images, size_divisibility=self.size_divisibility).tensor\n        metas = []\n        rescale = {\"height\" in x for x in batched_inputs}\n        if len(rescale) != 1:\n            raise ValueError(\"Some inputs have original height/width, but some don't!\")\n        rescale = list(rescale)[0]\n        output_shapes = []\n        for input in batched_inputs:\n            meta = {}\n            c, h, w = input[\"image\"].shape\n            meta[\"img_shape\"] = meta[\"ori_shape\"] = (h, w, c)\n            if rescale:\n                scale_factor = np.array(\n                    [w / input[\"width\"], h / input[\"height\"]] * 2, dtype=\"float32\"\n                )\n                ori_shape = (input[\"height\"], input[\"width\"])\n                output_shapes.append(ori_shape)\n                meta[\"ori_shape\"] = ori_shape + (c,)\n            else:\n                scale_factor = 1.0\n                output_shapes.append((h, w))\n            meta[\"scale_factor\"] = scale_factor\n            meta[\"flip\"] = False\n            padh, padw = images.shape[-2:]\n            meta[\"pad_shape\"] = (padh, padw, c)\n            metas.append(meta)\n\n        if self.training:\n            gt_instances = [x[\"instances\"].to(self.device) for x in batched_inputs]\n            if gt_instances[0].has(\"gt_masks\"):\n                from mmdet.core import PolygonMasks as mm_PolygonMasks, BitmapMasks as mm_BitMasks\n\n                def convert_mask(m, shape):\n                    # mmdet mask format\n                    if isinstance(m, BitMasks):\n                        return mm_BitMasks(m.tensor.cpu().numpy(), shape[0], shape[1])\n                    else:\n                        return mm_PolygonMasks(m.polygons, shape[0], shape[1])\n\n                gt_masks = [convert_mask(x.gt_masks, x.image_size) for x in gt_instances]\n                losses_and_metrics = self.detector.forward_train(\n                    images,\n                    metas,\n                    [x.gt_boxes.tensor for x in gt_instances],\n                    [x.gt_classes for x in gt_instances],\n                    gt_masks=gt_masks,\n                )\n            else:\n                losses_and_metrics = self.detector.forward_train(\n                    images,\n                    metas,\n                    [x.gt_boxes.tensor for x in gt_instances],\n                    [x.gt_classes for x in gt_instances],\n                )\n            return _parse_losses(losses_and_metrics)\n        else:\n            results = self.detector.simple_test(images, metas, rescale=rescale)\n            results = [\n                {\"instances\": _convert_mmdet_result(r, shape)}\n                for r, shape in zip(results, output_shapes)\n            ]\n            return results\n\n    @property\n    def device(self):\n        return self.pixel_mean.device\n\n\n# Reference: show_result() in\n# https://github.com/open-mmlab/mmdetection/blob/master/mmdet/models/detectors/base.py\ndef _convert_mmdet_result(result, shape: Tuple[int, int]) -> Instances:\n    if isinstance(result, tuple):\n        bbox_result, segm_result = result\n        if isinstance(segm_result, tuple):\n            segm_result = segm_result[0]\n    else:\n        bbox_result, segm_result = result, None\n\n    bboxes = torch.from_numpy(np.vstack(bbox_result))  # Nx5\n    bboxes, scores = bboxes[:, :4], bboxes[:, -1]\n    labels = [\n        torch.full((bbox.shape[0],), i, dtype=torch.int32) for i, bbox in enumerate(bbox_result)\n    ]\n    labels = torch.cat(labels)\n    inst = Instances(shape)\n    inst.pred_boxes = Boxes(bboxes)\n    inst.scores = scores\n    inst.pred_classes = labels\n\n    if segm_result is not None and len(labels) > 0:\n        segm_result = list(itertools.chain(*segm_result))\n        segm_result = [torch.from_numpy(x) if isinstance(x, np.ndarray) else x for x in segm_result]\n        segm_result = torch.stack(segm_result, dim=0)\n        inst.pred_masks = segm_result\n    return inst\n\n\n# reference: https://github.com/open-mmlab/mmdetection/blob/master/mmdet/models/detectors/base.py\ndef _parse_losses(losses: Dict[str, Tensor]) -> Dict[str, Tensor]:\n    log_vars = OrderedDict()\n    for loss_name, loss_value in losses.items():\n        if isinstance(loss_value, torch.Tensor):\n            log_vars[loss_name] = loss_value.mean()\n        elif isinstance(loss_value, list):\n            log_vars[loss_name] = sum(_loss.mean() for _loss in loss_value)\n        else:\n            raise TypeError(f\"{loss_name} is not a tensor or list of tensors\")\n\n        if \"loss\" not in loss_name:\n            # put metrics to storage; don't return them\n            storage = get_event_storage()\n            value = log_vars.pop(loss_name).cpu().item()\n            storage.put_scalar(loss_name, value)\n    return log_vars\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/poolers.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport math\nfrom typing import List\nimport torch\nfrom torch import nn\nfrom torchvision.ops import RoIPool\n\nfrom detectron2.layers import ROIAlign, ROIAlignRotated, cat, nonzero_tuple, shapes_to_tensor\nfrom detectron2.structures import Boxes\n\n\"\"\"\nTo export ROIPooler to torchscript, in this file, variables that should be annotated with\n`Union[List[Boxes], List[RotatedBoxes]]` are only annotated with `List[Boxes]`.\n\nTODO: Correct these annotations when torchscript support `Union`.\nhttps://github.com/pytorch/pytorch/issues/41412\n\"\"\"\n\n__all__ = [\"ROIPooler\"]\n\n\ndef assign_boxes_to_levels(\n    box_lists: List[Boxes],\n    min_level: int,\n    max_level: int,\n    canonical_box_size: int,\n    canonical_level: int,\n):\n    \"\"\"\n    Map each box in `box_lists` to a feature map level index and return the assignment\n    vector.\n\n    Args:\n        box_lists (list[Boxes] | list[RotatedBoxes]): A list of N Boxes or N RotatedBoxes,\n            where N is the number of images in the batch.\n        min_level (int): Smallest feature map level index. The input is considered index 0,\n            the output of stage 1 is index 1, and so.\n        max_level (int): Largest feature map level index.\n        canonical_box_size (int): A canonical box size in pixels (sqrt(box area)).\n        canonical_level (int): The feature map level index on which a canonically-sized box\n            should be placed.\n\n    Returns:\n        A tensor of length M, where M is the total number of boxes aggregated over all\n            N batch images. The memory layout corresponds to the concatenation of boxes\n            from all images. Each element is the feature map index, as an offset from\n            `self.min_level`, for the corresponding box (so value i means the box is at\n            `self.min_level + i`).\n    \"\"\"\n    box_sizes = torch.sqrt(cat([boxes.area() for boxes in box_lists]))\n    # Eqn.(1) in FPN paper\n    level_assignments = torch.floor(\n        canonical_level + torch.log2(box_sizes / canonical_box_size + 1e-8)\n    )\n    # clamp level to (min, max), in case the box size is too large or too small\n    # for the available feature maps\n    level_assignments = torch.clamp(level_assignments, min=min_level, max=max_level)\n    return level_assignments.to(torch.int64) - min_level\n\n\ndef convert_boxes_to_pooler_format(box_lists: List[Boxes]):\n    \"\"\"\n    Convert all boxes in `box_lists` to the low-level format used by ROI pooling ops\n    (see description under Returns).\n\n    Args:\n        box_lists (list[Boxes] | list[RotatedBoxes]):\n            A list of N Boxes or N RotatedBoxes, where N is the number of images in the batch.\n\n    Returns:\n        When input is list[Boxes]:\n            A tensor of shape (M, 5), where M is the total number of boxes aggregated over all\n            N batch images.\n            The 5 columns are (batch index, x0, y0, x1, y1), where batch index\n            is the index in [0, N) identifying which batch image the box with corners at\n            (x0, y0, x1, y1) comes from.\n        When input is list[RotatedBoxes]:\n            A tensor of shape (M, 6), where M is the total number of boxes aggregated over all\n            N batch images.\n            The 6 columns are (batch index, x_ctr, y_ctr, width, height, angle_degrees),\n            where batch index is the index in [0, N) identifying which batch image the\n            rotated box (x_ctr, y_ctr, width, height, angle_degrees) comes from.\n    \"\"\"\n    boxes = torch.cat([x.tensor for x in box_lists], dim=0)\n    # __len__ returns Tensor in tracing.\n    sizes = shapes_to_tensor([x.__len__() for x in box_lists], device=boxes.device)\n    indices = torch.repeat_interleave(\n        torch.arange(len(box_lists), dtype=boxes.dtype, device=boxes.device), sizes\n    )\n    return cat([indices[:, None], boxes], dim=1)\n\n\nclass ROIPooler(nn.Module):\n    \"\"\"\n    Region of interest feature map pooler that supports pooling from one or more\n    feature maps.\n    \"\"\"\n\n    def __init__(\n        self,\n        output_size,\n        scales,\n        sampling_ratio,\n        pooler_type,\n        canonical_box_size=224,\n        canonical_level=4,\n    ):\n        \"\"\"\n        Args:\n            output_size (int, tuple[int] or list[int]): output size of the pooled region,\n                e.g., 14 x 14. If tuple or list is given, the length must be 2.\n            scales (list[float]): The scale for each low-level pooling op relative to\n                the input image. For a feature map with stride s relative to the input\n                image, scale is defined as 1/s. The stride must be power of 2.\n                When there are multiple scales, they must form a pyramid, i.e. they must be\n                a monotically decreasing geometric sequence with a factor of 1/2.\n            sampling_ratio (int): The `sampling_ratio` parameter for the ROIAlign op.\n            pooler_type (string): Name of the type of pooling operation that should be applied.\n                For instance, \"ROIPool\" or \"ROIAlignV2\".\n            canonical_box_size (int): A canonical box size in pixels (sqrt(box area)). The default\n                is heuristically defined as 224 pixels in the FPN paper (based on ImageNet\n                pre-training).\n            canonical_level (int): The feature map level index from which a canonically-sized box\n                should be placed. The default is defined as level 4 (stride=16) in the FPN paper,\n                i.e., a box of size 224x224 will be placed on the feature with stride=16.\n                The box placement for all boxes will be determined from their sizes w.r.t\n                canonical_box_size. For example, a box whose area is 4x that of a canonical box\n                should be used to pool features from feature level ``canonical_level+1``.\n\n                Note that the actual input feature maps given to this module may not have\n                sufficiently many levels for the input boxes. If the boxes are too large or too\n                small for the input feature maps, the closest level will be used.\n        \"\"\"\n        super().__init__()\n\n        if isinstance(output_size, int):\n            output_size = (output_size, output_size)\n        assert len(output_size) == 2\n        assert isinstance(output_size[0], int) and isinstance(output_size[1], int)\n        self.output_size = output_size\n\n        if pooler_type == \"ROIAlign\":\n            self.level_poolers = nn.ModuleList(\n                ROIAlign(\n                    output_size, spatial_scale=scale, sampling_ratio=sampling_ratio, aligned=False\n                )\n                for scale in scales\n            )\n        elif pooler_type == \"ROIAlignV2\":\n            self.level_poolers = nn.ModuleList(\n                ROIAlign(\n                    output_size, spatial_scale=scale, sampling_ratio=sampling_ratio, aligned=True\n                )\n                for scale in scales\n            )\n        elif pooler_type == \"ROIPool\":\n            self.level_poolers = nn.ModuleList(\n                RoIPool(output_size, spatial_scale=scale) for scale in scales\n            )\n        elif pooler_type == \"ROIAlignRotated\":\n            self.level_poolers = nn.ModuleList(\n                ROIAlignRotated(output_size, spatial_scale=scale, sampling_ratio=sampling_ratio)\n                for scale in scales\n            )\n        else:\n            raise ValueError(\"Unknown pooler type: {}\".format(pooler_type))\n\n        # Map scale (defined as 1 / stride) to its feature map level under the\n        # assumption that stride is a power of 2.\n        min_level = -(math.log2(scales[0]))\n        max_level = -(math.log2(scales[-1]))\n        assert math.isclose(min_level, int(min_level)) and math.isclose(\n            max_level, int(max_level)\n        ), \"Featuremap stride is not power of 2!\"\n        self.min_level = int(min_level)\n        self.max_level = int(max_level)\n        assert (\n            len(scales) == self.max_level - self.min_level + 1\n        ), \"[ROIPooler] Sizes of input featuremaps do not form a pyramid!\"\n        assert 0 <= self.min_level and self.min_level <= self.max_level\n        self.canonical_level = canonical_level\n        assert canonical_box_size > 0\n        self.canonical_box_size = canonical_box_size\n\n    def forward(self, x: List[torch.Tensor], box_lists: List[Boxes]):\n        \"\"\"\n        Args:\n            x (list[Tensor]): A list of feature maps of NCHW shape, with scales matching those\n                used to construct this module.\n            box_lists (list[Boxes] | list[RotatedBoxes]):\n                A list of N Boxes or N RotatedBoxes, where N is the number of images in the batch.\n                The box coordinates are defined on the original image and\n                will be scaled by the `scales` argument of :class:`ROIPooler`.\n\n        Returns:\n            Tensor:\n                A tensor of shape (M, C, output_size, output_size) where M is the total number of\n                boxes aggregated over all N batch images and C is the number of channels in `x`.\n        \"\"\"\n        num_level_assignments = len(self.level_poolers)\n\n        assert isinstance(x, list) and isinstance(\n            box_lists, list\n        ), \"Arguments to pooler must be lists\"\n        assert (\n            len(x) == num_level_assignments\n        ), \"unequal value, num_level_assignments={}, but x is list of {} Tensors\".format(\n            num_level_assignments, len(x)\n        )\n\n        assert len(box_lists) == x[0].size(\n            0\n        ), \"unequal value, x[0] batch dim 0 is {}, but box_list has length {}\".format(\n            x[0].size(0), len(box_lists)\n        )\n        if len(box_lists) == 0:\n            return torch.zeros(\n                (0, x[0].shape[1]) + self.output_size, device=x[0].device, dtype=x[0].dtype\n            )\n\n        pooler_fmt_boxes = convert_boxes_to_pooler_format(box_lists)\n\n        if num_level_assignments == 1:\n            return self.level_poolers[0](x[0], pooler_fmt_boxes)\n\n        level_assignments = assign_boxes_to_levels(\n            box_lists, self.min_level, self.max_level, self.canonical_box_size, self.canonical_level\n        )\n\n        num_boxes = pooler_fmt_boxes.size(0)\n        num_channels = x[0].shape[1]\n        output_size = self.output_size[0]\n\n        dtype, device = x[0].dtype, x[0].device\n        output = torch.zeros(\n            (num_boxes, num_channels, output_size, output_size), dtype=dtype, device=device\n        )\n\n        for level, pooler in enumerate(self.level_poolers):\n            inds = nonzero_tuple(level_assignments == level)[0]\n            pooler_fmt_boxes_level = pooler_fmt_boxes[inds]\n            # Use index_put_ instead of advance indexing, to avoid pytorch/issues/49852\n            output.index_put_((inds,), pooler(x[level], pooler_fmt_boxes_level))\n\n        return output\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/postprocessing.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport torch\nfrom torch.nn import functional as F\n\nfrom detectron2.structures import Instances, ROIMasks\n\n\n# perhaps should rename to \"resize_instance\"\ndef detector_postprocess(\n    results: Instances, output_height: int, output_width: int, mask_threshold: float = 0.5\n):\n    \"\"\"\n    Resize the output instances.\n    The input images are often resized when entering an object detector.\n    As a result, we often need the outputs of the detector in a different\n    resolution from its inputs.\n\n    This function will resize the raw outputs of an R-CNN detector\n    to produce outputs according to the desired output resolution.\n\n    Args:\n        results (Instances): the raw outputs from the detector.\n            `results.image_size` contains the input image resolution the detector sees.\n            This object might be modified in-place.\n        output_height, output_width: the desired output resolution.\n\n    Returns:\n        Instances: the resized output from the model, based on the output resolution\n    \"\"\"\n    if isinstance(output_width, torch.Tensor):\n        # This shape might (but not necessarily) be tensors during tracing.\n        # Converts integer tensors to float temporaries to ensure true\n        # division is performed when computing scale_x and scale_y.\n        output_width_tmp = output_width.float()\n        output_height_tmp = output_height.float()\n        new_size = torch.stack([output_height, output_width])\n    else:\n        new_size = (output_height, output_width)\n        output_width_tmp = output_width\n        output_height_tmp = output_height\n\n    scale_x, scale_y = (\n        output_width_tmp / results.image_size[1],\n        output_height_tmp / results.image_size[0],\n    )\n    results = Instances(new_size, **results.get_fields())\n\n    if results.has(\"pred_boxes\"):\n        output_boxes = results.pred_boxes\n    elif results.has(\"proposal_boxes\"):\n        output_boxes = results.proposal_boxes\n    else:\n        output_boxes = None\n    assert output_boxes is not None, \"Predictions must contain boxes!\"\n\n    output_boxes.scale(scale_x, scale_y)\n    output_boxes.clip(results.image_size)\n\n    results = results[output_boxes.nonempty()]\n\n    if results.has(\"pred_masks\"):\n        if isinstance(results.pred_masks, ROIMasks):\n            roi_masks = results.pred_masks\n        else:\n            # pred_masks is a tensor of shape (N, 1, M, M)\n            roi_masks = ROIMasks(results.pred_masks[:, 0, :, :])\n        results.pred_masks = roi_masks.to_bitmasks(\n            results.pred_boxes, output_height, output_width, mask_threshold\n        ).tensor  # TODO return ROIMasks/BitMask object in the future\n\n    if results.has(\"pred_keypoints\"):\n        results.pred_keypoints[:, :, 0] *= scale_x\n        results.pred_keypoints[:, :, 1] *= scale_y\n\n    return results\n\n\ndef sem_seg_postprocess(result, img_size, output_height, output_width):\n    \"\"\"\n    Return semantic segmentation predictions in the original resolution.\n\n    The input images are often resized when entering semantic segmentor. Moreover, in same\n    cases, they also padded inside segmentor to be divisible by maximum network stride.\n    As a result, we often need the predictions of the segmentor in a different\n    resolution from its inputs.\n\n    Args:\n        result (Tensor): semantic segmentation prediction logits. A tensor of shape (C, H, W),\n            where C is the number of classes, and H, W are the height and width of the prediction.\n        img_size (tuple): image size that segmentor is taking as input.\n        output_height, output_width: the desired output resolution.\n\n    Returns:\n        semantic segmentation prediction (Tensor): A tensor of the shape\n            (C, output_height, output_width) that contains per-pixel soft predictions.\n    \"\"\"\n    result = result[:, : img_size[0], : img_size[1]].expand(1, -1, -1, -1)\n    result = F.interpolate(\n        result, size=(output_height, output_width), mode=\"bilinear\", align_corners=False\n    )[0]\n    return result\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/proposal_generator/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom .build import PROPOSAL_GENERATOR_REGISTRY, build_proposal_generator\nfrom .rpn import RPN_HEAD_REGISTRY, build_rpn_head, RPN, StandardRPNHead\n\n__all__ = list(globals().keys())\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/proposal_generator/build.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom detectron2.utils.registry import Registry\n\nPROPOSAL_GENERATOR_REGISTRY = Registry(\"PROPOSAL_GENERATOR\")\nPROPOSAL_GENERATOR_REGISTRY.__doc__ = \"\"\"\nRegistry for proposal generator, which produces object proposals from feature maps.\n\nThe registered object will be called with `obj(cfg, input_shape)`.\nThe call should return a `nn.Module` object.\n\"\"\"\n\nfrom . import rpn, rrpn  # noqa F401 isort:skip\n\n\ndef build_proposal_generator(cfg, input_shape):\n    \"\"\"\n    Build a proposal generator from `cfg.MODEL.PROPOSAL_GENERATOR.NAME`.\n    The name can be \"PrecomputedProposals\" to use no proposal generator.\n    \"\"\"\n    name = cfg.MODEL.PROPOSAL_GENERATOR.NAME\n    if name == \"PrecomputedProposals\":\n        return None\n\n    return PROPOSAL_GENERATOR_REGISTRY.get(name)(cfg, input_shape)\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/proposal_generator/proposal_utils.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport logging\nimport math\nfrom typing import List, Tuple, Union\nimport torch\n\nfrom detectron2.layers import batched_nms, cat\nfrom detectron2.structures import Boxes, Instances\n\nlogger = logging.getLogger(__name__)\n\n\ndef _is_tracing():\n    # (fixed in TORCH_VERSION >= 1.9)\n    if torch.jit.is_scripting():\n        # https://github.com/pytorch/pytorch/issues/47379\n        return False\n    else:\n        return torch.jit.is_tracing()\n\n\ndef find_top_rpn_proposals(\n    proposals: List[torch.Tensor],\n    pred_objectness_logits: List[torch.Tensor],\n    image_sizes: List[Tuple[int, int]],\n    nms_thresh: float,\n    pre_nms_topk: int,\n    post_nms_topk: int,\n    min_box_size: float,\n    training: bool,\n):\n    \"\"\"\n    For each feature map, select the `pre_nms_topk` highest scoring proposals,\n    apply NMS, clip proposals, and remove small boxes. Return the `post_nms_topk`\n    highest scoring proposals among all the feature maps for each image.\n\n    Args:\n        proposals (list[Tensor]): A list of L tensors. Tensor i has shape (N, Hi*Wi*A, 4).\n            All proposal predictions on the feature maps.\n        pred_objectness_logits (list[Tensor]): A list of L tensors. Tensor i has shape (N, Hi*Wi*A).\n        image_sizes (list[tuple]): sizes (h, w) for each image\n        nms_thresh (float): IoU threshold to use for NMS\n        pre_nms_topk (int): number of top k scoring proposals to keep before applying NMS.\n            When RPN is run on multiple feature maps (as in FPN) this number is per\n            feature map.\n        post_nms_topk (int): number of top k scoring proposals to keep after applying NMS.\n            When RPN is run on multiple feature maps (as in FPN) this number is total,\n            over all feature maps.\n        min_box_size (float): minimum proposal box side length in pixels (absolute units\n            wrt input images).\n        training (bool): True if proposals are to be used in training, otherwise False.\n            This arg exists only to support a legacy bug; look for the \"NB: Legacy bug ...\"\n            comment.\n\n    Returns:\n        list[Instances]: list of N Instances. The i-th Instances\n            stores post_nms_topk object proposals for image i, sorted by their\n            objectness score in descending order.\n    \"\"\"\n    num_images = len(image_sizes)\n    device = proposals[0].device\n\n    # 1. Select top-k anchor for every level and every image\n    topk_scores = []  # #lvl Tensor, each of shape N x topk\n    topk_proposals = []\n    level_ids = []  # #lvl Tensor, each of shape (topk,)\n    batch_idx = torch.arange(num_images, device=device)\n    for level_id, (proposals_i, logits_i) in enumerate(zip(proposals, pred_objectness_logits)):\n        Hi_Wi_A = logits_i.shape[1]\n        if isinstance(Hi_Wi_A, torch.Tensor):  # it's a tensor in tracing\n            num_proposals_i = torch.clamp(Hi_Wi_A, max=pre_nms_topk)\n        else:\n            num_proposals_i = min(Hi_Wi_A, pre_nms_topk)\n\n        topk_scores_i, topk_idx = logits_i.topk(num_proposals_i, dim=1)\n\n        # each is N x topk\n        topk_proposals_i = proposals_i[batch_idx[:, None], topk_idx]  # N x topk x 4\n\n        topk_proposals.append(topk_proposals_i)\n        topk_scores.append(topk_scores_i)\n        level_ids.append(torch.full((num_proposals_i,), level_id, dtype=torch.int64, device=device))\n\n    # 2. Concat all levels together\n    topk_scores = cat(topk_scores, dim=1)\n    topk_proposals = cat(topk_proposals, dim=1)\n    level_ids = cat(level_ids, dim=0)\n\n    # 3. For each image, run a per-level NMS, and choose topk results.\n    results: List[Instances] = []\n    for n, image_size in enumerate(image_sizes):\n        boxes = Boxes(topk_proposals[n])\n        scores_per_img = topk_scores[n]\n        lvl = level_ids\n\n        valid_mask = torch.isfinite(boxes.tensor).all(dim=1) & torch.isfinite(scores_per_img)\n        if not valid_mask.all():\n            if training:\n                raise FloatingPointError(\n                    \"Predicted boxes or scores contain Inf/NaN. Training has diverged.\"\n                )\n            boxes = boxes[valid_mask]\n            scores_per_img = scores_per_img[valid_mask]\n            lvl = lvl[valid_mask]\n        boxes.clip(image_size)\n\n        # filter empty boxes\n        keep = boxes.nonempty(threshold=min_box_size)\n        if _is_tracing() or keep.sum().item() != len(boxes):\n            boxes, scores_per_img, lvl = boxes[keep], scores_per_img[keep], lvl[keep]\n\n        keep = batched_nms(boxes.tensor, scores_per_img, lvl, nms_thresh)\n        # In Detectron1, there was different behavior during training vs. testing.\n        # (https://github.com/facebookresearch/Detectron/issues/459)\n        # During training, topk is over the proposals from *all* images in the training batch.\n        # During testing, it is over the proposals for each image separately.\n        # As a result, the training behavior becomes batch-dependent,\n        # and the configuration \"POST_NMS_TOPK_TRAIN\" end up relying on the batch size.\n        # This bug is addressed in Detectron2 to make the behavior independent of batch size.\n        keep = keep[:post_nms_topk]  # keep is already sorted\n\n        res = Instances(image_size)\n        res.proposal_boxes = boxes[keep]\n        res.objectness_logits = scores_per_img[keep]\n        results.append(res)\n    return results\n\n\ndef add_ground_truth_to_proposals(\n    gt: Union[List[Instances], List[Boxes]], proposals: List[Instances]\n) -> List[Instances]:\n    \"\"\"\n    Call `add_ground_truth_to_proposals_single_image` for all images.\n\n    Args:\n        gt(Union[List[Instances], List[Boxes]): list of N elements. Element i is a Instances\n            representing the ground-truth for image i.\n        proposals (list[Instances]): list of N elements. Element i is a Instances\n            representing the proposals for image i.\n\n    Returns:\n        list[Instances]: list of N Instances. Each is the proposals for the image,\n            with field \"proposal_boxes\" and \"objectness_logits\".\n    \"\"\"\n    assert gt is not None\n\n    if len(proposals) != len(gt):\n        raise ValueError(\"proposals and gt should have the same length as the number of images!\")\n    if len(proposals) == 0:\n        return proposals\n\n    return [\n        add_ground_truth_to_proposals_single_image(gt_i, proposals_i)\n        for gt_i, proposals_i in zip(gt, proposals)\n    ]\n\n\ndef add_ground_truth_to_proposals_single_image(\n    gt: Union[Instances, Boxes], proposals: Instances\n) -> Instances:\n    \"\"\"\n    Augment `proposals` with `gt`.\n\n    Args:\n        Same as `add_ground_truth_to_proposals`, but with gt and proposals\n        per image.\n\n    Returns:\n        Same as `add_ground_truth_to_proposals`, but for only one image.\n    \"\"\"\n    if isinstance(gt, Boxes):\n        # convert Boxes to Instances\n        gt = Instances(proposals.image_size, gt_boxes=gt)\n\n    gt_boxes = gt.gt_boxes\n    device = proposals.objectness_logits.device\n    # Assign all ground-truth boxes an objectness logit corresponding to\n    # P(object) = sigmoid(logit) =~ 1.\n    gt_logit_value = math.log((1.0 - 1e-10) / (1 - (1.0 - 1e-10)))\n    gt_logits = gt_logit_value * torch.ones(len(gt_boxes), device=device)\n\n    # Concatenating gt_boxes with proposals requires them to have the same fields\n    gt_proposal = Instances(proposals.image_size, **gt.get_fields())\n    gt_proposal.proposal_boxes = gt_boxes\n    gt_proposal.objectness_logits = gt_logits\n\n    for key in proposals.get_fields().keys():\n        assert gt_proposal.has(\n            key\n        ), \"The attribute '{}' in `proposals` does not exist in `gt`\".format(key)\n\n    # NOTE: Instances.cat only use fields from the first item. Extra fields in latter items\n    # will be thrown away.\n    new_proposals = Instances.cat([proposals, gt_proposal])\n\n    return new_proposals\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/proposal_generator/rpn.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom typing import Dict, List, Optional, Tuple, Union\nimport torch\nimport torch.nn.functional as F\nfrom torch import nn\n\nfrom detectron2.config import configurable\nfrom detectron2.layers import Conv2d, ShapeSpec, cat\nfrom detectron2.structures import Boxes, ImageList, Instances, pairwise_iou\nfrom detectron2.utils.events import get_event_storage\nfrom detectron2.utils.memory import retry_if_cuda_oom\nfrom detectron2.utils.registry import Registry\n\nfrom ..anchor_generator import build_anchor_generator\nfrom ..box_regression import Box2BoxTransform, _dense_box_regression_loss\nfrom ..matcher import Matcher\nfrom ..sampling import subsample_labels\nfrom .build import PROPOSAL_GENERATOR_REGISTRY\nfrom .proposal_utils import find_top_rpn_proposals\n\nRPN_HEAD_REGISTRY = Registry(\"RPN_HEAD\")\nRPN_HEAD_REGISTRY.__doc__ = \"\"\"\nRegistry for RPN heads, which take feature maps and perform\nobjectness classification and bounding box regression for anchors.\n\nThe registered object will be called with `obj(cfg, input_shape)`.\nThe call should return a `nn.Module` object.\n\"\"\"\n\n\n\"\"\"\nShape shorthand in this module:\n\n    N: number of images in the minibatch\n    L: number of feature maps per image on which RPN is run\n    A: number of cell anchors (must be the same for all feature maps)\n    Hi, Wi: height and width of the i-th feature map\n    B: size of the box parameterization\n\nNaming convention:\n\n    objectness: refers to the binary classification of an anchor as object vs. not object.\n\n    deltas: refers to the 4-d (dx, dy, dw, dh) deltas that parameterize the box2box\n    transform (see :class:`box_regression.Box2BoxTransform`), or 5d for rotated boxes.\n\n    pred_objectness_logits: predicted objectness scores in [-inf, +inf]; use\n        sigmoid(pred_objectness_logits) to estimate P(object).\n\n    gt_labels: ground-truth binary classification labels for objectness\n\n    pred_anchor_deltas: predicted box2box transform deltas\n\n    gt_anchor_deltas: ground-truth box2box transform deltas\n\"\"\"\n\n\ndef build_rpn_head(cfg, input_shape):\n    \"\"\"\n    Build an RPN head defined by `cfg.MODEL.RPN.HEAD_NAME`.\n    \"\"\"\n    name = cfg.MODEL.RPN.HEAD_NAME\n    return RPN_HEAD_REGISTRY.get(name)(cfg, input_shape)\n\n\n@RPN_HEAD_REGISTRY.register()\nclass StandardRPNHead(nn.Module):\n    \"\"\"\n    Standard RPN classification and regression heads described in :paper:`Faster R-CNN`.\n    Uses a 3x3 conv to produce a shared hidden state from which one 1x1 conv predicts\n    objectness logits for each anchor and a second 1x1 conv predicts bounding-box deltas\n    specifying how to deform each anchor into an object proposal.\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self, *, in_channels: int, num_anchors: int, box_dim: int = 4, conv_dims: List[int] = (-1,)\n    ):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            in_channels (int): number of input feature channels. When using multiple\n                input features, they must have the same number of channels.\n            num_anchors (int): number of anchors to predict for *each spatial position*\n                on the feature map. The total number of anchors for each\n                feature map will be `num_anchors * H * W`.\n            box_dim (int): dimension of a box, which is also the number of box regression\n                predictions to make for each anchor. An axis aligned box has\n                box_dim=4, while a rotated box has box_dim=5.\n            conv_dims (list[int]): a list of integers representing the output channels\n                of N conv layers. Set it to -1 to use the same number of output channels\n                as input channels.\n        \"\"\"\n        super().__init__()\n        cur_channels = in_channels\n        # Keeping the old variable names and structure for backwards compatiblity.\n        # Otherwise the old checkpoints will fail to load.\n        if len(conv_dims) == 1:\n            out_channels = cur_channels if conv_dims[0] == -1 else conv_dims[0]\n            # 3x3 conv for the hidden representation\n            self.conv = self._get_rpn_conv(cur_channels, out_channels)\n            cur_channels = out_channels\n        else:\n            self.conv = nn.Sequential()\n            for k, conv_dim in enumerate(conv_dims):\n                out_channels = cur_channels if conv_dim == -1 else conv_dim\n                if out_channels <= 0:\n                    raise ValueError(\n                        f\"Conv output channels should be greater than 0. Got {out_channels}\"\n                    )\n                conv = self._get_rpn_conv(cur_channels, out_channels)\n                self.conv.add_module(f\"conv{k}\", conv)\n                cur_channels = out_channels\n        # 1x1 conv for predicting objectness logits\n        self.objectness_logits = nn.Conv2d(cur_channels, num_anchors, kernel_size=1, stride=1)\n        # 1x1 conv for predicting box2box transform deltas\n        self.anchor_deltas = nn.Conv2d(cur_channels, num_anchors * box_dim, kernel_size=1, stride=1)\n\n        # Keeping the order of weights initialization same for backwards compatiblility.\n        for layer in self.modules():\n            if isinstance(layer, nn.Conv2d):\n                nn.init.normal_(layer.weight, std=0.01)\n                nn.init.constant_(layer.bias, 0)\n\n    def _get_rpn_conv(self, in_channels, out_channels):\n        return Conv2d(\n            in_channels,\n            out_channels,\n            kernel_size=3,\n            stride=1,\n            padding=1,\n            activation=nn.ReLU(),\n        )\n\n    @classmethod\n    def from_config(cls, cfg, input_shape):\n        # Standard RPN is shared across levels:\n        in_channels = [s.channels for s in input_shape]\n        assert len(set(in_channels)) == 1, \"Each level must have the same channel!\"\n        in_channels = in_channels[0]\n\n        # RPNHead should take the same input as anchor generator\n        # NOTE: it assumes that creating an anchor generator does not have unwanted side effect.\n        anchor_generator = build_anchor_generator(cfg, input_shape)\n        num_anchors = anchor_generator.num_anchors\n        box_dim = anchor_generator.box_dim\n        assert (\n            len(set(num_anchors)) == 1\n        ), \"Each level must have the same number of anchors per spatial position\"\n        return {\n            \"in_channels\": in_channels,\n            \"num_anchors\": num_anchors[0],\n            \"box_dim\": box_dim,\n            \"conv_dims\": cfg.MODEL.RPN.CONV_DIMS,\n        }\n\n    def forward(self, features: List[torch.Tensor]):\n        \"\"\"\n        Args:\n            features (list[Tensor]): list of feature maps\n\n        Returns:\n            list[Tensor]: A list of L elements.\n                Element i is a tensor of shape (N, A, Hi, Wi) representing\n                the predicted objectness logits for all anchors. A is the number of cell anchors.\n            list[Tensor]: A list of L elements. Element i is a tensor of shape\n                (N, A*box_dim, Hi, Wi) representing the predicted \"deltas\" used to transform anchors\n                to proposals.\n        \"\"\"\n        pred_objectness_logits = []\n        pred_anchor_deltas = []\n        for x in features:\n            t = self.conv(x)\n            pred_objectness_logits.append(self.objectness_logits(t))\n            pred_anchor_deltas.append(self.anchor_deltas(t))\n        return pred_objectness_logits, pred_anchor_deltas\n\n\n@PROPOSAL_GENERATOR_REGISTRY.register()\nclass RPN(nn.Module):\n    \"\"\"\n    Region Proposal Network, introduced by :paper:`Faster R-CNN`.\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self,\n        *,\n        in_features: List[str],\n        head: nn.Module,\n        anchor_generator: nn.Module,\n        anchor_matcher: Matcher,\n        box2box_transform: Box2BoxTransform,\n        batch_size_per_image: int,\n        positive_fraction: float,\n        pre_nms_topk: Tuple[float, float],\n        post_nms_topk: Tuple[float, float],\n        nms_thresh: float = 0.7,\n        min_box_size: float = 0.0,\n        anchor_boundary_thresh: float = -1.0,\n        loss_weight: Union[float, Dict[str, float]] = 1.0,\n        box_reg_loss_type: str = \"smooth_l1\",\n        smooth_l1_beta: float = 0.0,\n    ):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            in_features (list[str]): list of names of input features to use\n            head (nn.Module): a module that predicts logits and regression deltas\n                for each level from a list of per-level features\n            anchor_generator (nn.Module): a module that creates anchors from a\n                list of features. Usually an instance of :class:`AnchorGenerator`\n            anchor_matcher (Matcher): label the anchors by matching them with ground truth.\n            box2box_transform (Box2BoxTransform): defines the transform from anchors boxes to\n                instance boxes\n            batch_size_per_image (int): number of anchors per image to sample for training\n            positive_fraction (float): fraction of foreground anchors to sample for training\n            pre_nms_topk (tuple[float]): (train, test) that represents the\n                number of top k proposals to select before NMS, in\n                training and testing.\n            post_nms_topk (tuple[float]): (train, test) that represents the\n                number of top k proposals to select after NMS, in\n                training and testing.\n            nms_thresh (float): NMS threshold used to de-duplicate the predicted proposals\n            min_box_size (float): remove proposal boxes with any side smaller than this threshold,\n                in the unit of input image pixels\n            anchor_boundary_thresh (float): legacy option\n            loss_weight (float|dict): weights to use for losses. Can be single float for weighting\n                all rpn losses together, or a dict of individual weightings. Valid dict keys are:\n                    \"loss_rpn_cls\" - applied to classification loss\n                    \"loss_rpn_loc\" - applied to box regression loss\n            box_reg_loss_type (str): Loss type to use. Supported losses: \"smooth_l1\", \"giou\".\n            smooth_l1_beta (float): beta parameter for the smooth L1 regression loss. Default to\n                use L1 loss. Only used when `box_reg_loss_type` is \"smooth_l1\"\n        \"\"\"\n        super().__init__()\n        self.in_features = in_features\n        self.rpn_head = head\n        self.anchor_generator = anchor_generator\n        self.anchor_matcher = anchor_matcher\n        self.box2box_transform = box2box_transform\n        self.batch_size_per_image = batch_size_per_image\n        self.positive_fraction = positive_fraction\n        # Map from self.training state to train/test settings\n        self.pre_nms_topk = {True: pre_nms_topk[0], False: pre_nms_topk[1]}\n        self.post_nms_topk = {True: post_nms_topk[0], False: post_nms_topk[1]}\n        self.nms_thresh = nms_thresh\n        self.min_box_size = float(min_box_size)\n        self.anchor_boundary_thresh = anchor_boundary_thresh\n        if isinstance(loss_weight, float):\n            loss_weight = {\"loss_rpn_cls\": loss_weight, \"loss_rpn_loc\": loss_weight}\n        self.loss_weight = loss_weight\n        self.box_reg_loss_type = box_reg_loss_type\n        self.smooth_l1_beta = smooth_l1_beta\n\n    @classmethod\n    def from_config(cls, cfg, input_shape: Dict[str, ShapeSpec]):\n        in_features = cfg.MODEL.RPN.IN_FEATURES\n        ret = {\n            \"in_features\": in_features,\n            \"min_box_size\": cfg.MODEL.PROPOSAL_GENERATOR.MIN_SIZE,\n            \"nms_thresh\": cfg.MODEL.RPN.NMS_THRESH,\n            \"batch_size_per_image\": cfg.MODEL.RPN.BATCH_SIZE_PER_IMAGE,\n            \"positive_fraction\": cfg.MODEL.RPN.POSITIVE_FRACTION,\n            \"loss_weight\": {\n                \"loss_rpn_cls\": cfg.MODEL.RPN.LOSS_WEIGHT,\n                \"loss_rpn_loc\": cfg.MODEL.RPN.BBOX_REG_LOSS_WEIGHT * cfg.MODEL.RPN.LOSS_WEIGHT,\n            },\n            \"anchor_boundary_thresh\": cfg.MODEL.RPN.BOUNDARY_THRESH,\n            \"box2box_transform\": Box2BoxTransform(weights=cfg.MODEL.RPN.BBOX_REG_WEIGHTS),\n            \"box_reg_loss_type\": cfg.MODEL.RPN.BBOX_REG_LOSS_TYPE,\n            \"smooth_l1_beta\": cfg.MODEL.RPN.SMOOTH_L1_BETA,\n        }\n\n        ret[\"pre_nms_topk\"] = (cfg.MODEL.RPN.PRE_NMS_TOPK_TRAIN, cfg.MODEL.RPN.PRE_NMS_TOPK_TEST)\n        ret[\"post_nms_topk\"] = (cfg.MODEL.RPN.POST_NMS_TOPK_TRAIN, cfg.MODEL.RPN.POST_NMS_TOPK_TEST)\n\n        ret[\"anchor_generator\"] = build_anchor_generator(cfg, [input_shape[f] for f in in_features])\n        ret[\"anchor_matcher\"] = Matcher(\n            cfg.MODEL.RPN.IOU_THRESHOLDS, cfg.MODEL.RPN.IOU_LABELS, allow_low_quality_matches=True\n        )\n        ret[\"head\"] = build_rpn_head(cfg, [input_shape[f] for f in in_features])\n        return ret\n\n    def _subsample_labels(self, label):\n        \"\"\"\n        Randomly sample a subset of positive and negative examples, and overwrite\n        the label vector to the ignore value (-1) for all elements that are not\n        included in the sample.\n\n        Args:\n            labels (Tensor): a vector of -1, 0, 1. Will be modified in-place and returned.\n        \"\"\"\n        pos_idx, neg_idx = subsample_labels(\n            label, self.batch_size_per_image, self.positive_fraction, 0\n        )\n        # Fill with the ignore label (-1), then set positive and negative labels\n        label.fill_(-1)\n        label.scatter_(0, pos_idx, 1)\n        label.scatter_(0, neg_idx, 0)\n        return label\n\n    @torch.jit.unused\n    @torch.no_grad()\n    def label_and_sample_anchors(\n        self, anchors: List[Boxes], gt_instances: List[Instances]\n    ) -> Tuple[List[torch.Tensor], List[torch.Tensor]]:\n        \"\"\"\n        Args:\n            anchors (list[Boxes]): anchors for each feature map.\n            gt_instances: the ground-truth instances for each image.\n\n        Returns:\n            list[Tensor]:\n                List of #img tensors. i-th element is a vector of labels whose length is\n                the total number of anchors across all feature maps R = sum(Hi * Wi * A).\n                Label values are in {-1, 0, 1}, with meanings: -1 = ignore; 0 = negative\n                class; 1 = positive class.\n            list[Tensor]:\n                i-th element is a Rx4 tensor. The values are the matched gt boxes for each\n                anchor. Values are undefined for those anchors not labeled as 1.\n        \"\"\"\n        anchors = Boxes.cat(anchors)\n\n        gt_boxes = [x.gt_boxes for x in gt_instances]\n        image_sizes = [x.image_size for x in gt_instances]\n        del gt_instances\n\n        gt_labels = []\n        matched_gt_boxes = []\n        for image_size_i, gt_boxes_i in zip(image_sizes, gt_boxes):\n            \"\"\"\n            image_size_i: (h, w) for the i-th image\n            gt_boxes_i: ground-truth boxes for i-th image\n            \"\"\"\n\n            match_quality_matrix = retry_if_cuda_oom(pairwise_iou)(gt_boxes_i, anchors)\n            matched_idxs, gt_labels_i = retry_if_cuda_oom(self.anchor_matcher)(match_quality_matrix)\n            # Matching is memory-expensive and may result in CPU tensors. But the result is small\n            gt_labels_i = gt_labels_i.to(device=gt_boxes_i.device)\n            del match_quality_matrix\n\n            if self.anchor_boundary_thresh >= 0:\n                # Discard anchors that go out of the boundaries of the image\n                # NOTE: This is legacy functionality that is turned off by default in Detectron2\n                anchors_inside_image = anchors.inside_box(image_size_i, self.anchor_boundary_thresh)\n                gt_labels_i[~anchors_inside_image] = -1\n\n            # A vector of labels (-1, 0, 1) for each anchor\n            gt_labels_i = self._subsample_labels(gt_labels_i)\n\n            if len(gt_boxes_i) == 0:\n                # These values won't be used anyway since the anchor is labeled as background\n                matched_gt_boxes_i = torch.zeros_like(anchors.tensor)\n            else:\n                # TODO wasted indexing computation for ignored boxes\n                matched_gt_boxes_i = gt_boxes_i[matched_idxs].tensor\n\n            gt_labels.append(gt_labels_i)  # N,AHW\n            matched_gt_boxes.append(matched_gt_boxes_i)\n        return gt_labels, matched_gt_boxes\n\n    @torch.jit.unused\n    def losses(\n        self,\n        anchors: List[Boxes],\n        pred_objectness_logits: List[torch.Tensor],\n        gt_labels: List[torch.Tensor],\n        pred_anchor_deltas: List[torch.Tensor],\n        gt_boxes: List[torch.Tensor],\n    ) -> Dict[str, torch.Tensor]:\n        \"\"\"\n        Return the losses from a set of RPN predictions and their associated ground-truth.\n\n        Args:\n            anchors (list[Boxes or RotatedBoxes]): anchors for each feature map, each\n                has shape (Hi*Wi*A, B), where B is box dimension (4 or 5).\n            pred_objectness_logits (list[Tensor]): A list of L elements.\n                Element i is a tensor of shape (N, Hi*Wi*A) representing\n                the predicted objectness logits for all anchors.\n            gt_labels (list[Tensor]): Output of :meth:`label_and_sample_anchors`.\n            pred_anchor_deltas (list[Tensor]): A list of L elements. Element i is a tensor of shape\n                (N, Hi*Wi*A, 4 or 5) representing the predicted \"deltas\" used to transform anchors\n                to proposals.\n            gt_boxes (list[Tensor]): Output of :meth:`label_and_sample_anchors`.\n\n        Returns:\n            dict[loss name -> loss value]: A dict mapping from loss name to loss value.\n                Loss names are: `loss_rpn_cls` for objectness classification and\n                `loss_rpn_loc` for proposal localization.\n        \"\"\"\n        num_images = len(gt_labels)\n        gt_labels = torch.stack(gt_labels)  # (N, sum(Hi*Wi*Ai))\n\n        # Log the number of positive/negative anchors per-image that's used in training\n        pos_mask = gt_labels == 1\n        num_pos_anchors = pos_mask.sum().item()\n        num_neg_anchors = (gt_labels == 0).sum().item()\n        storage = get_event_storage()\n        storage.put_scalar(\"rpn/num_pos_anchors\", num_pos_anchors / num_images)\n        storage.put_scalar(\"rpn/num_neg_anchors\", num_neg_anchors / num_images)\n\n        localization_loss = _dense_box_regression_loss(\n            anchors,\n            self.box2box_transform,\n            pred_anchor_deltas,\n            gt_boxes,\n            pos_mask,\n            box_reg_loss_type=self.box_reg_loss_type,\n            smooth_l1_beta=self.smooth_l1_beta,\n        )\n\n        valid_mask = gt_labels >= 0\n        objectness_loss = F.binary_cross_entropy_with_logits(\n            cat(pred_objectness_logits, dim=1)[valid_mask],\n            gt_labels[valid_mask].to(torch.float32),\n            reduction=\"sum\",\n        )\n        normalizer = self.batch_size_per_image * num_images\n        losses = {\n            \"loss_rpn_cls\": objectness_loss / normalizer,\n            # The original Faster R-CNN paper uses a slightly different normalizer\n            # for loc loss. But it doesn't matter in practice\n            \"loss_rpn_loc\": localization_loss / normalizer,\n        }\n        losses = {k: v * self.loss_weight.get(k, 1.0) for k, v in losses.items()}\n        return losses\n\n    def forward(\n        self,\n        images: ImageList,\n        features: Dict[str, torch.Tensor],\n        gt_instances: Optional[List[Instances]] = None,\n    ):\n        \"\"\"\n        Args:\n            images (ImageList): input images of length `N`\n            features (dict[str, Tensor]): input data as a mapping from feature\n                map name to tensor. Axis 0 represents the number of images `N` in\n                the input data; axes 1-3 are channels, height, and width, which may\n                vary between feature maps (e.g., if a feature pyramid is used).\n            gt_instances (list[Instances], optional): a length `N` list of `Instances`s.\n                Each `Instances` stores ground-truth instances for the corresponding image.\n\n        Returns:\n            proposals: list[Instances]: contains fields \"proposal_boxes\", \"objectness_logits\"\n            loss: dict[Tensor] or None\n        \"\"\"\n        features = [features[f] for f in self.in_features]\n        anchors = self.anchor_generator(features)\n\n        pred_objectness_logits, pred_anchor_deltas = self.rpn_head(features)\n        # Transpose the Hi*Wi*A dimension to the middle:\n        pred_objectness_logits = [\n            # (N, A, Hi, Wi) -> (N, Hi, Wi, A) -> (N, Hi*Wi*A)\n            score.permute(0, 2, 3, 1).flatten(1)\n            for score in pred_objectness_logits\n        ]\n        pred_anchor_deltas = [\n            # (N, A*B, Hi, Wi) -> (N, A, B, Hi, Wi) -> (N, Hi, Wi, A, B) -> (N, Hi*Wi*A, B)\n            x.view(x.shape[0], -1, self.anchor_generator.box_dim, x.shape[-2], x.shape[-1])\n            .permute(0, 3, 4, 1, 2)\n            .flatten(1, -2)\n            for x in pred_anchor_deltas\n        ]\n\n        if self.training:\n            assert gt_instances is not None, \"RPN requires gt_instances in training!\"\n            gt_labels, gt_boxes = self.label_and_sample_anchors(anchors, gt_instances)\n            losses = self.losses(\n                anchors, pred_objectness_logits, gt_labels, pred_anchor_deltas, gt_boxes\n            )\n        else:\n            losses = {}\n        proposals = self.predict_proposals(\n            anchors, pred_objectness_logits, pred_anchor_deltas, images.image_sizes\n        )\n        return proposals, losses\n\n    def predict_proposals(\n        self,\n        anchors: List[Boxes],\n        pred_objectness_logits: List[torch.Tensor],\n        pred_anchor_deltas: List[torch.Tensor],\n        image_sizes: List[Tuple[int, int]],\n    ):\n        \"\"\"\n        Decode all the predicted box regression deltas to proposals. Find the top proposals\n        by applying NMS and removing boxes that are too small.\n\n        Returns:\n            proposals (list[Instances]): list of N Instances. The i-th Instances\n                stores post_nms_topk object proposals for image i, sorted by their\n                objectness score in descending order.\n        \"\"\"\n        # The proposals are treated as fixed for joint training with roi heads.\n        # This approach ignores the derivative w.r.t. the proposal boxes’ coordinates that\n        # are also network responses.\n        with torch.no_grad():\n            pred_proposals = self._decode_proposals(anchors, pred_anchor_deltas)\n            return find_top_rpn_proposals(\n                pred_proposals,\n                pred_objectness_logits,\n                image_sizes,\n                self.nms_thresh,\n                self.pre_nms_topk[self.training],\n                self.post_nms_topk[self.training],\n                self.min_box_size,\n                self.training,\n            )\n\n    def _decode_proposals(self, anchors: List[Boxes], pred_anchor_deltas: List[torch.Tensor]):\n        \"\"\"\n        Transform anchors into proposals by applying the predicted anchor deltas.\n\n        Returns:\n            proposals (list[Tensor]): A list of L tensors. Tensor i has shape\n                (N, Hi*Wi*A, B)\n        \"\"\"\n        N = pred_anchor_deltas[0].shape[0]\n        proposals = []\n        # For each feature map\n        for anchors_i, pred_anchor_deltas_i in zip(anchors, pred_anchor_deltas):\n            B = anchors_i.tensor.size(1)\n            pred_anchor_deltas_i = pred_anchor_deltas_i.reshape(-1, B)\n            # Expand anchors to shape (N*Hi*Wi*A, B)\n            anchors_i = anchors_i.tensor.unsqueeze(0).expand(N, -1, -1).reshape(-1, B)\n            proposals_i = self.box2box_transform.apply_deltas(pred_anchor_deltas_i, anchors_i)\n            # Append feature map proposals with shape (N, Hi*Wi*A, B)\n            proposals.append(proposals_i.view(N, -1, B))\n        return proposals\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/proposal_generator/rrpn.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport itertools\nimport logging\nfrom typing import Dict, List\nimport torch\n\nfrom detectron2.config import configurable\nfrom detectron2.layers import ShapeSpec, batched_nms_rotated, cat\nfrom detectron2.structures import Instances, RotatedBoxes, pairwise_iou_rotated\nfrom detectron2.utils.memory import retry_if_cuda_oom\n\nfrom ..box_regression import Box2BoxTransformRotated\nfrom .build import PROPOSAL_GENERATOR_REGISTRY\nfrom .proposal_utils import _is_tracing\nfrom .rpn import RPN\n\nlogger = logging.getLogger(__name__)\n\n\ndef find_top_rrpn_proposals(\n    proposals,\n    pred_objectness_logits,\n    image_sizes,\n    nms_thresh,\n    pre_nms_topk,\n    post_nms_topk,\n    min_box_size,\n    training,\n):\n    \"\"\"\n    For each feature map, select the `pre_nms_topk` highest scoring proposals,\n    apply NMS, clip proposals, and remove small boxes. Return the `post_nms_topk`\n    highest scoring proposals among all the feature maps if `training` is True,\n    otherwise, returns the highest `post_nms_topk` scoring proposals for each\n    feature map.\n\n    Args:\n        proposals (list[Tensor]): A list of L tensors. Tensor i has shape (N, Hi*Wi*A, 5).\n            All proposal predictions on the feature maps.\n        pred_objectness_logits (list[Tensor]): A list of L tensors. Tensor i has shape (N, Hi*Wi*A).\n        image_sizes (list[tuple]): sizes (h, w) for each image\n        nms_thresh (float): IoU threshold to use for NMS\n        pre_nms_topk (int): number of top k scoring proposals to keep before applying NMS.\n            When RRPN is run on multiple feature maps (as in FPN) this number is per\n            feature map.\n        post_nms_topk (int): number of top k scoring proposals to keep after applying NMS.\n            When RRPN is run on multiple feature maps (as in FPN) this number is total,\n            over all feature maps.\n        min_box_size(float): minimum proposal box side length in pixels (absolute units wrt\n            input images).\n        training (bool): True if proposals are to be used in training, otherwise False.\n            This arg exists only to support a legacy bug; look for the \"NB: Legacy bug ...\"\n            comment.\n\n    Returns:\n        proposals (list[Instances]): list of N Instances. The i-th Instances\n            stores post_nms_topk object proposals for image i.\n    \"\"\"\n    num_images = len(image_sizes)\n    device = proposals[0].device\n\n    # 1. Select top-k anchor for every level and every image\n    topk_scores = []  # #lvl Tensor, each of shape N x topk\n    topk_proposals = []\n    level_ids = []  # #lvl Tensor, each of shape (topk,)\n    batch_idx = torch.arange(num_images, device=device)\n    for level_id, proposals_i, logits_i in zip(\n        itertools.count(), proposals, pred_objectness_logits\n    ):\n        Hi_Wi_A = logits_i.shape[1]\n        if isinstance(Hi_Wi_A, torch.Tensor):  # it's a tensor in tracing\n            num_proposals_i = torch.clamp(Hi_Wi_A, max=pre_nms_topk)\n        else:\n            num_proposals_i = min(Hi_Wi_A, pre_nms_topk)\n\n        topk_scores_i, topk_idx = logits_i.topk(num_proposals_i, dim=1)\n\n        # each is N x topk\n        topk_proposals_i = proposals_i[batch_idx[:, None], topk_idx]  # N x topk x 5\n\n        topk_proposals.append(topk_proposals_i)\n        topk_scores.append(topk_scores_i)\n        level_ids.append(torch.full((num_proposals_i,), level_id, dtype=torch.int64, device=device))\n\n    # 2. Concat all levels together\n    topk_scores = cat(topk_scores, dim=1)\n    topk_proposals = cat(topk_proposals, dim=1)\n    level_ids = cat(level_ids, dim=0)\n\n    # 3. For each image, run a per-level NMS, and choose topk results.\n    results = []\n    for n, image_size in enumerate(image_sizes):\n        boxes = RotatedBoxes(topk_proposals[n])\n        scores_per_img = topk_scores[n]\n        valid_mask = torch.isfinite(boxes.tensor).all(dim=1) & torch.isfinite(scores_per_img)\n        if not valid_mask.all():\n            boxes = boxes[valid_mask]\n            scores_per_img = scores_per_img[valid_mask]\n        boxes.clip(image_size)\n\n        # filter empty boxes\n        keep = boxes.nonempty(threshold=min_box_size)\n        lvl = level_ids\n        if _is_tracing() or keep.sum().item() != len(boxes):\n            boxes, scores_per_img, lvl = (boxes[keep], scores_per_img[keep], level_ids[keep])\n\n        keep = batched_nms_rotated(boxes.tensor, scores_per_img, lvl, nms_thresh)\n        # In Detectron1, there was different behavior during training vs. testing.\n        # (https://github.com/facebookresearch/Detectron/issues/459)\n        # During training, topk is over the proposals from *all* images in the training batch.\n        # During testing, it is over the proposals for each image separately.\n        # As a result, the training behavior becomes batch-dependent,\n        # and the configuration \"POST_NMS_TOPK_TRAIN\" end up relying on the batch size.\n        # This bug is addressed in Detectron2 to make the behavior independent of batch size.\n        keep = keep[:post_nms_topk]\n\n        res = Instances(image_size)\n        res.proposal_boxes = boxes[keep]\n        res.objectness_logits = scores_per_img[keep]\n        results.append(res)\n    return results\n\n\n@PROPOSAL_GENERATOR_REGISTRY.register()\nclass RRPN(RPN):\n    \"\"\"\n    Rotated Region Proposal Network described in :paper:`RRPN`.\n    \"\"\"\n\n    @configurable\n    def __init__(self, *args, **kwargs):\n        super().__init__(*args, **kwargs)\n        if self.anchor_boundary_thresh >= 0:\n            raise NotImplementedError(\n                \"anchor_boundary_thresh is a legacy option not implemented for RRPN.\"\n            )\n\n    @classmethod\n    def from_config(cls, cfg, input_shape: Dict[str, ShapeSpec]):\n        ret = super().from_config(cfg, input_shape)\n        ret[\"box2box_transform\"] = Box2BoxTransformRotated(weights=cfg.MODEL.RPN.BBOX_REG_WEIGHTS)\n        return ret\n\n    @torch.no_grad()\n    def label_and_sample_anchors(self, anchors: List[RotatedBoxes], gt_instances: List[Instances]):\n        \"\"\"\n        Args:\n            anchors (list[RotatedBoxes]): anchors for each feature map.\n            gt_instances: the ground-truth instances for each image.\n\n        Returns:\n            list[Tensor]:\n                List of #img tensors. i-th element is a vector of labels whose length is\n                the total number of anchors across feature maps. Label values are in {-1, 0, 1},\n                with meanings: -1 = ignore; 0 = negative class; 1 = positive class.\n            list[Tensor]:\n                i-th element is a Nx5 tensor, where N is the total number of anchors across\n                feature maps.  The values are the matched gt boxes for each anchor.\n                Values are undefined for those anchors not labeled as 1.\n        \"\"\"\n        anchors = RotatedBoxes.cat(anchors)\n\n        gt_boxes = [x.gt_boxes for x in gt_instances]\n        del gt_instances\n\n        gt_labels = []\n        matched_gt_boxes = []\n        for gt_boxes_i in gt_boxes:\n            \"\"\"\n            gt_boxes_i: ground-truth boxes for i-th image\n            \"\"\"\n            match_quality_matrix = retry_if_cuda_oom(pairwise_iou_rotated)(gt_boxes_i, anchors)\n            matched_idxs, gt_labels_i = retry_if_cuda_oom(self.anchor_matcher)(match_quality_matrix)\n            # Matching is memory-expensive and may result in CPU tensors. But the result is small\n            gt_labels_i = gt_labels_i.to(device=gt_boxes_i.device)\n\n            # A vector of labels (-1, 0, 1) for each anchor\n            gt_labels_i = self._subsample_labels(gt_labels_i)\n\n            if len(gt_boxes_i) == 0:\n                # These values won't be used anyway since the anchor is labeled as background\n                matched_gt_boxes_i = torch.zeros_like(anchors.tensor)\n            else:\n                # TODO wasted indexing computation for ignored boxes\n                matched_gt_boxes_i = gt_boxes_i[matched_idxs].tensor\n\n            gt_labels.append(gt_labels_i)  # N,AHW\n            matched_gt_boxes.append(matched_gt_boxes_i)\n        return gt_labels, matched_gt_boxes\n\n    @torch.no_grad()\n    def predict_proposals(self, anchors, pred_objectness_logits, pred_anchor_deltas, image_sizes):\n        pred_proposals = self._decode_proposals(anchors, pred_anchor_deltas)\n        return find_top_rrpn_proposals(\n            pred_proposals,\n            pred_objectness_logits,\n            image_sizes,\n            self.nms_thresh,\n            self.pre_nms_topk[self.training],\n            self.post_nms_topk[self.training],\n            self.min_box_size,\n            self.training,\n        )\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/roi_heads/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom .box_head import ROI_BOX_HEAD_REGISTRY, build_box_head, FastRCNNConvFCHead\nfrom .keypoint_head import (\n    ROI_KEYPOINT_HEAD_REGISTRY,\n    build_keypoint_head,\n    BaseKeypointRCNNHead,\n    KRCNNConvDeconvUpsampleHead,\n)\nfrom .mask_head import (\n    ROI_MASK_HEAD_REGISTRY,\n    build_mask_head,\n    BaseMaskRCNNHead,\n    MaskRCNNConvUpsampleHead,\n)\nfrom .roi_heads import (\n    ROI_HEADS_REGISTRY,\n    ROIHeads,\n    Res5ROIHeads,\n    StandardROIHeads,\n    build_roi_heads,\n    select_foreground_proposals,\n)\nfrom .cascade_rcnn import CascadeROIHeads\nfrom .rotated_fast_rcnn import RROIHeads\nfrom .fast_rcnn import FastRCNNOutputLayers\n\nfrom . import cascade_rcnn  # isort:skip\n\n__all__ = list(globals().keys())\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/roi_heads/box_head.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport numpy as np\nfrom typing import List\nimport fvcore.nn.weight_init as weight_init\nimport torch\nfrom torch import nn\n\nfrom detectron2.config import configurable\nfrom detectron2.layers import Conv2d, ShapeSpec, get_norm\nfrom detectron2.utils.registry import Registry\n\n__all__ = [\"FastRCNNConvFCHead\", \"build_box_head\", \"ROI_BOX_HEAD_REGISTRY\"]\n\nROI_BOX_HEAD_REGISTRY = Registry(\"ROI_BOX_HEAD\")\nROI_BOX_HEAD_REGISTRY.__doc__ = \"\"\"\nRegistry for box heads, which make box predictions from per-region features.\n\nThe registered object will be called with `obj(cfg, input_shape)`.\n\"\"\"\n\n\n# To get torchscript support, we make the head a subclass of `nn.Sequential`.\n# Therefore, to add new layers in this head class, please make sure they are\n# added in the order they will be used in forward().\n@ROI_BOX_HEAD_REGISTRY.register()\nclass FastRCNNConvFCHead(nn.Sequential):\n    \"\"\"\n    A head with several 3x3 conv layers (each followed by norm & relu) and then\n    several fc layers (each followed by relu).\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self, input_shape: ShapeSpec, *, conv_dims: List[int], fc_dims: List[int], conv_norm=\"\"\n    ):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            input_shape (ShapeSpec): shape of the input feature.\n            conv_dims (list[int]): the output dimensions of the conv layers\n            fc_dims (list[int]): the output dimensions of the fc layers\n            conv_norm (str or callable): normalization for the conv layers.\n                See :func:`detectron2.layers.get_norm` for supported types.\n        \"\"\"\n        super().__init__()\n        assert len(conv_dims) + len(fc_dims) > 0\n\n        self._output_size = (input_shape.channels, input_shape.height, input_shape.width)\n\n        self.conv_norm_relus = []\n        for k, conv_dim in enumerate(conv_dims):\n            conv = Conv2d(\n                self._output_size[0],\n                conv_dim,\n                kernel_size=3,\n                padding=1,\n                bias=not conv_norm,\n                norm=get_norm(conv_norm, conv_dim),\n                activation=nn.ReLU(),\n            )\n            self.add_module(\"conv{}\".format(k + 1), conv)\n            self.conv_norm_relus.append(conv)\n            self._output_size = (conv_dim, self._output_size[1], self._output_size[2])\n\n        self.fcs = []\n        for k, fc_dim in enumerate(fc_dims):\n            if k == 0:\n                self.add_module(\"flatten\", nn.Flatten())\n            fc = nn.Linear(int(np.prod(self._output_size)), fc_dim)\n            self.add_module(\"fc{}\".format(k + 1), fc)\n            self.add_module(\"fc_relu{}\".format(k + 1), nn.ReLU())\n            self.fcs.append(fc)\n            self._output_size = fc_dim\n\n        for layer in self.conv_norm_relus:\n            weight_init.c2_msra_fill(layer)\n        for layer in self.fcs:\n            weight_init.c2_xavier_fill(layer)\n\n    @classmethod\n    def from_config(cls, cfg, input_shape):\n        num_conv = cfg.MODEL.ROI_BOX_HEAD.NUM_CONV\n        conv_dim = cfg.MODEL.ROI_BOX_HEAD.CONV_DIM\n        num_fc = cfg.MODEL.ROI_BOX_HEAD.NUM_FC\n        fc_dim = cfg.MODEL.ROI_BOX_HEAD.FC_DIM\n        return {\n            \"input_shape\": input_shape,\n            \"conv_dims\": [conv_dim] * num_conv,\n            \"fc_dims\": [fc_dim] * num_fc,\n            \"conv_norm\": cfg.MODEL.ROI_BOX_HEAD.NORM,\n        }\n\n    def forward(self, x):\n        for layer in self:\n            x = layer(x)\n        return x\n\n    @property\n    @torch.jit.unused\n    def output_shape(self):\n        \"\"\"\n        Returns:\n            ShapeSpec: the output feature shape\n        \"\"\"\n        o = self._output_size\n        if isinstance(o, int):\n            return ShapeSpec(channels=o)\n        else:\n            return ShapeSpec(channels=o[0], height=o[1], width=o[2])\n\n\ndef build_box_head(cfg, input_shape):\n    \"\"\"\n    Build a box head defined by `cfg.MODEL.ROI_BOX_HEAD.NAME`.\n    \"\"\"\n    name = cfg.MODEL.ROI_BOX_HEAD.NAME\n    return ROI_BOX_HEAD_REGISTRY.get(name)(cfg, input_shape)\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/roi_heads/cascade_rcnn.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom typing import List\nimport torch\nfrom torch import nn\nfrom torch.autograd.function import Function\n\nfrom detectron2.config import configurable\nfrom detectron2.layers import ShapeSpec\nfrom detectron2.structures import Boxes, Instances, pairwise_iou\nfrom detectron2.utils.events import get_event_storage\n\nfrom ..box_regression import Box2BoxTransform\nfrom ..matcher import Matcher\nfrom ..poolers import ROIPooler\nfrom .box_head import build_box_head\nfrom .fast_rcnn import FastRCNNOutputLayers, fast_rcnn_inference\nfrom .roi_heads import ROI_HEADS_REGISTRY, StandardROIHeads\n\n\nclass _ScaleGradient(Function):\n    @staticmethod\n    def forward(ctx, input, scale):\n        ctx.scale = scale\n        return input\n\n    @staticmethod\n    def backward(ctx, grad_output):\n        return grad_output * ctx.scale, None\n\n\n@ROI_HEADS_REGISTRY.register()\nclass CascadeROIHeads(StandardROIHeads):\n    \"\"\"\n    The ROI heads that implement :paper:`Cascade R-CNN`.\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self,\n        *,\n        box_in_features: List[str],\n        box_pooler: ROIPooler,\n        box_heads: List[nn.Module],\n        box_predictors: List[nn.Module],\n        proposal_matchers: List[Matcher],\n        **kwargs,\n    ):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            box_pooler (ROIPooler): pooler that extracts region features from given boxes\n            box_heads (list[nn.Module]): box head for each cascade stage\n            box_predictors (list[nn.Module]): box predictor for each cascade stage\n            proposal_matchers (list[Matcher]): matcher with different IoU thresholds to\n                match boxes with ground truth for each stage. The first matcher matches\n                RPN proposals with ground truth, the other matchers use boxes predicted\n                by the previous stage as proposals and match them with ground truth.\n        \"\"\"\n        assert \"proposal_matcher\" not in kwargs, (\n            \"CascadeROIHeads takes 'proposal_matchers=' for each stage instead \"\n            \"of one 'proposal_matcher='.\"\n        )\n        # The first matcher matches RPN proposals with ground truth, done in the base class\n        kwargs[\"proposal_matcher\"] = proposal_matchers[0]\n        num_stages = self.num_cascade_stages = len(box_heads)\n        box_heads = nn.ModuleList(box_heads)\n        box_predictors = nn.ModuleList(box_predictors)\n        assert len(box_predictors) == num_stages, f\"{len(box_predictors)} != {num_stages}!\"\n        assert len(proposal_matchers) == num_stages, f\"{len(proposal_matchers)} != {num_stages}!\"\n        super().__init__(\n            box_in_features=box_in_features,\n            box_pooler=box_pooler,\n            box_head=box_heads,\n            box_predictor=box_predictors,\n            **kwargs,\n        )\n        self.proposal_matchers = proposal_matchers\n\n    @classmethod\n    def from_config(cls, cfg, input_shape):\n        ret = super().from_config(cfg, input_shape)\n        ret.pop(\"proposal_matcher\")\n        return ret\n\n    @classmethod\n    def _init_box_head(cls, cfg, input_shape):\n        # fmt: off\n        in_features              = cfg.MODEL.ROI_HEADS.IN_FEATURES\n        pooler_resolution        = cfg.MODEL.ROI_BOX_HEAD.POOLER_RESOLUTION\n        pooler_scales            = tuple(1.0 / input_shape[k].stride for k in in_features)\n        sampling_ratio           = cfg.MODEL.ROI_BOX_HEAD.POOLER_SAMPLING_RATIO\n        pooler_type              = cfg.MODEL.ROI_BOX_HEAD.POOLER_TYPE\n        cascade_bbox_reg_weights = cfg.MODEL.ROI_BOX_CASCADE_HEAD.BBOX_REG_WEIGHTS\n        cascade_ious             = cfg.MODEL.ROI_BOX_CASCADE_HEAD.IOUS\n        assert len(cascade_bbox_reg_weights) == len(cascade_ious)\n        assert cfg.MODEL.ROI_BOX_HEAD.CLS_AGNOSTIC_BBOX_REG,  \\\n            \"CascadeROIHeads only support class-agnostic regression now!\"\n        assert cascade_ious[0] == cfg.MODEL.ROI_HEADS.IOU_THRESHOLDS[0]\n        # fmt: on\n\n        in_channels = [input_shape[f].channels for f in in_features]\n        # Check all channel counts are equal\n        assert len(set(in_channels)) == 1, in_channels\n        in_channels = in_channels[0]\n\n        box_pooler = ROIPooler(\n            output_size=pooler_resolution,\n            scales=pooler_scales,\n            sampling_ratio=sampling_ratio,\n            pooler_type=pooler_type,\n        )\n        pooled_shape = ShapeSpec(\n            channels=in_channels, width=pooler_resolution, height=pooler_resolution\n        )\n\n        box_heads, box_predictors, proposal_matchers = [], [], []\n        for match_iou, bbox_reg_weights in zip(cascade_ious, cascade_bbox_reg_weights):\n            box_head = build_box_head(cfg, pooled_shape)\n            box_heads.append(box_head)\n            box_predictors.append(\n                FastRCNNOutputLayers(\n                    cfg,\n                    box_head.output_shape,\n                    box2box_transform=Box2BoxTransform(weights=bbox_reg_weights),\n                )\n            )\n            proposal_matchers.append(Matcher([match_iou], [0, 1], allow_low_quality_matches=False))\n        return {\n            \"box_in_features\": in_features,\n            \"box_pooler\": box_pooler,\n            \"box_heads\": box_heads,\n            \"box_predictors\": box_predictors,\n            \"proposal_matchers\": proposal_matchers,\n        }\n\n    def forward(self, images, features, proposals, targets=None):\n        del images\n        if self.training:\n            proposals = self.label_and_sample_proposals(proposals, targets)\n\n        if self.training:\n            # Need targets to box head\n            losses = self._forward_box(features, proposals, targets)\n            losses.update(self._forward_mask(features, proposals))\n            losses.update(self._forward_keypoint(features, proposals))\n            return proposals, losses\n        else:\n            pred_instances = self._forward_box(features, proposals)\n            pred_instances = self.forward_with_given_boxes(features, pred_instances)\n            return pred_instances, {}\n\n    def _forward_box(self, features, proposals, targets=None):\n        \"\"\"\n        Args:\n            features, targets: the same as in\n                Same as in :meth:`ROIHeads.forward`.\n            proposals (list[Instances]): the per-image object proposals with\n                their matching ground truth.\n                Each has fields \"proposal_boxes\", and \"objectness_logits\",\n                \"gt_classes\", \"gt_boxes\".\n        \"\"\"\n        features = [features[f] for f in self.box_in_features]\n        head_outputs = []  # (predictor, predictions, proposals)\n        prev_pred_boxes = None\n        image_sizes = [x.image_size for x in proposals]\n        for k in range(self.num_cascade_stages):\n            if k > 0:\n                # The output boxes of the previous stage are used to create the input\n                # proposals of the next stage.\n                proposals = self._create_proposals_from_boxes(prev_pred_boxes, image_sizes)\n                if self.training:\n                    proposals = self._match_and_label_boxes(proposals, k, targets)\n            predictions = self._run_stage(features, proposals, k)\n            prev_pred_boxes = self.box_predictor[k].predict_boxes(predictions, proposals)\n            head_outputs.append((self.box_predictor[k], predictions, proposals))\n\n        if self.training:\n            losses = {}\n            storage = get_event_storage()\n            for stage, (predictor, predictions, proposals) in enumerate(head_outputs):\n                with storage.name_scope(\"stage{}\".format(stage)):\n                    stage_losses = predictor.losses(predictions, proposals)\n                losses.update({k + \"_stage{}\".format(stage): v for k, v in stage_losses.items()})\n            return losses\n        else:\n            # Each is a list[Tensor] of length #image. Each tensor is Ri x (K+1)\n            scores_per_stage = [h[0].predict_probs(h[1], h[2]) for h in head_outputs]\n\n            # Average the scores across heads\n            scores = [\n                sum(list(scores_per_image)) * (1.0 / self.num_cascade_stages)\n                for scores_per_image in zip(*scores_per_stage)\n            ]\n            # Use the boxes of the last head\n            predictor, predictions, proposals = head_outputs[-1]\n            boxes = predictor.predict_boxes(predictions, proposals)\n            pred_instances, _ = fast_rcnn_inference(\n                boxes,\n                scores,\n                image_sizes,\n                predictor.test_score_thresh,\n                predictor.test_nms_thresh,\n                predictor.test_topk_per_image,\n            )\n            return pred_instances\n\n    @torch.no_grad()\n    def _match_and_label_boxes(self, proposals, stage, targets):\n        \"\"\"\n        Match proposals with groundtruth using the matcher at the given stage.\n        Label the proposals as foreground or background based on the match.\n\n        Args:\n            proposals (list[Instances]): One Instances for each image, with\n                the field \"proposal_boxes\".\n            stage (int): the current stage\n            targets (list[Instances]): the ground truth instances\n\n        Returns:\n            list[Instances]: the same proposals, but with fields \"gt_classes\" and \"gt_boxes\"\n        \"\"\"\n        num_fg_samples, num_bg_samples = [], []\n        for proposals_per_image, targets_per_image in zip(proposals, targets):\n            match_quality_matrix = pairwise_iou(\n                targets_per_image.gt_boxes, proposals_per_image.proposal_boxes\n            )\n            # proposal_labels are 0 or 1\n            matched_idxs, proposal_labels = self.proposal_matchers[stage](match_quality_matrix)\n            if len(targets_per_image) > 0:\n                gt_classes = targets_per_image.gt_classes[matched_idxs]\n                # Label unmatched proposals (0 label from matcher) as background (label=num_classes)\n                gt_classes[proposal_labels == 0] = self.num_classes\n                gt_boxes = targets_per_image.gt_boxes[matched_idxs]\n            else:\n                gt_classes = torch.zeros_like(matched_idxs) + self.num_classes\n                gt_boxes = Boxes(\n                    targets_per_image.gt_boxes.tensor.new_zeros((len(proposals_per_image), 4))\n                )\n            proposals_per_image.gt_classes = gt_classes\n            proposals_per_image.gt_boxes = gt_boxes\n\n            num_fg_samples.append((proposal_labels == 1).sum().item())\n            num_bg_samples.append(proposal_labels.numel() - num_fg_samples[-1])\n\n        # Log the number of fg/bg samples in each stage\n        storage = get_event_storage()\n        storage.put_scalar(\n            \"stage{}/roi_head/num_fg_samples\".format(stage),\n            sum(num_fg_samples) / len(num_fg_samples),\n        )\n        storage.put_scalar(\n            \"stage{}/roi_head/num_bg_samples\".format(stage),\n            sum(num_bg_samples) / len(num_bg_samples),\n        )\n        return proposals\n\n    def _run_stage(self, features, proposals, stage):\n        \"\"\"\n        Args:\n            features (list[Tensor]): #lvl input features to ROIHeads\n            proposals (list[Instances]): #image Instances, with the field \"proposal_boxes\"\n            stage (int): the current stage\n\n        Returns:\n            Same output as `FastRCNNOutputLayers.forward()`.\n        \"\"\"\n        box_features = self.box_pooler(features, [x.proposal_boxes for x in proposals])\n        # The original implementation averages the losses among heads,\n        # but scale up the parameter gradients of the heads.\n        # This is equivalent to adding the losses among heads,\n        # but scale down the gradients on features.\n        if self.training:\n            box_features = _ScaleGradient.apply(box_features, 1.0 / self.num_cascade_stages)\n        box_features = self.box_head[stage](box_features)\n        return self.box_predictor[stage](box_features)\n\n    def _create_proposals_from_boxes(self, boxes, image_sizes):\n        \"\"\"\n        Args:\n            boxes (list[Tensor]): per-image predicted boxes, each of shape Ri x 4\n            image_sizes (list[tuple]): list of image shapes in (h, w)\n\n        Returns:\n            list[Instances]: per-image proposals with the given boxes.\n        \"\"\"\n        # Just like RPN, the proposals should not have gradients\n        boxes = [Boxes(b.detach()) for b in boxes]\n        proposals = []\n        for boxes_per_image, image_size in zip(boxes, image_sizes):\n            boxes_per_image.clip(image_size)\n            if self.training:\n                # do not filter empty boxes at inference time,\n                # because the scores from each stage need to be aligned and added later\n                boxes_per_image = boxes_per_image[boxes_per_image.nonempty()]\n            prop = Instances(image_size)\n            prop.proposal_boxes = boxes_per_image\n            proposals.append(prop)\n        return proposals\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/roi_heads/fast_rcnn.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport logging\nfrom typing import Dict, List, Tuple, Union\nimport torch\nfrom torch import nn\nfrom torch.nn import functional as F\n\nfrom detectron2.config import configurable\nfrom detectron2.layers import ShapeSpec, batched_nms, cat, cross_entropy, nonzero_tuple\nfrom detectron2.modeling.box_regression import Box2BoxTransform, _dense_box_regression_loss\nfrom detectron2.structures import Boxes, Instances\nfrom detectron2.utils.events import get_event_storage\n\n__all__ = [\"fast_rcnn_inference\", \"FastRCNNOutputLayers\"]\n\n\nlogger = logging.getLogger(__name__)\n\n\"\"\"\nShape shorthand in this module:\n\n    N: number of images in the minibatch\n    R: number of ROIs, combined over all images, in the minibatch\n    Ri: number of ROIs in image i\n    K: number of foreground classes. E.g.,there are 80 foreground classes in COCO.\n\nNaming convention:\n\n    deltas: refers to the 4-d (dx, dy, dw, dh) deltas that parameterize the box2box\n    transform (see :class:`box_regression.Box2BoxTransform`).\n\n    pred_class_logits: predicted class scores in [-inf, +inf]; use\n        softmax(pred_class_logits) to estimate P(class).\n\n    gt_classes: ground-truth classification labels in [0, K], where [0, K) represent\n        foreground object classes and K represents the background class.\n\n    pred_proposal_deltas: predicted box2box transform deltas for transforming proposals\n        to detection box predictions.\n\n    gt_proposal_deltas: ground-truth box2box transform deltas\n\"\"\"\n\n\ndef fast_rcnn_inference(\n    boxes: List[torch.Tensor],\n    scores: List[torch.Tensor],\n    image_shapes: List[Tuple[int, int]],\n    score_thresh: float,\n    nms_thresh: float,\n    topk_per_image: int,\n):\n    \"\"\"\n    Call `fast_rcnn_inference_single_image` for all images.\n\n    Args:\n        boxes (list[Tensor]): A list of Tensors of predicted class-specific or class-agnostic\n            boxes for each image. Element i has shape (Ri, K * 4) if doing\n            class-specific regression, or (Ri, 4) if doing class-agnostic\n            regression, where Ri is the number of predicted objects for image i.\n            This is compatible with the output of :meth:`FastRCNNOutputLayers.predict_boxes`.\n        scores (list[Tensor]): A list of Tensors of predicted class scores for each image.\n            Element i has shape (Ri, K + 1), where Ri is the number of predicted objects\n            for image i. Compatible with the output of :meth:`FastRCNNOutputLayers.predict_probs`.\n        image_shapes (list[tuple]): A list of (width, height) tuples for each image in the batch.\n        score_thresh (float): Only return detections with a confidence score exceeding this\n            threshold.\n        nms_thresh (float):  The threshold to use for box non-maximum suppression. Value in [0, 1].\n        topk_per_image (int): The number of top scoring detections to return. Set < 0 to return\n            all detections.\n\n    Returns:\n        instances: (list[Instances]): A list of N instances, one for each image in the batch,\n            that stores the topk most confidence detections.\n        kept_indices: (list[Tensor]): A list of 1D tensor of length of N, each element indicates\n            the corresponding boxes/scores index in [0, Ri) from the input, for image i.\n    \"\"\"\n    result_per_image = [\n        fast_rcnn_inference_single_image(\n            boxes_per_image, scores_per_image, image_shape, score_thresh, nms_thresh, topk_per_image\n        )\n        for scores_per_image, boxes_per_image, image_shape in zip(scores, boxes, image_shapes)\n    ]\n    return [x[0] for x in result_per_image], [x[1] for x in result_per_image]\n\n\ndef _log_classification_stats(pred_logits, gt_classes, prefix=\"fast_rcnn\"):\n    \"\"\"\n    Log the classification metrics to EventStorage.\n\n    Args:\n        pred_logits: Rx(K+1) logits. The last column is for background class.\n        gt_classes: R labels\n    \"\"\"\n    num_instances = gt_classes.numel()\n    if num_instances == 0:\n        return\n    pred_classes = pred_logits.argmax(dim=1)\n    bg_class_ind = pred_logits.shape[1] - 1\n\n    fg_inds = (gt_classes >= 0) & (gt_classes < bg_class_ind)\n    num_fg = fg_inds.nonzero().numel()\n    fg_gt_classes = gt_classes[fg_inds]\n    fg_pred_classes = pred_classes[fg_inds]\n\n    num_false_negative = (fg_pred_classes == bg_class_ind).nonzero().numel()\n    num_accurate = (pred_classes == gt_classes).nonzero().numel()\n    fg_num_accurate = (fg_pred_classes == fg_gt_classes).nonzero().numel()\n\n    storage = get_event_storage()\n    storage.put_scalar(f\"{prefix}/cls_accuracy\", num_accurate / num_instances)\n    if num_fg > 0:\n        storage.put_scalar(f\"{prefix}/fg_cls_accuracy\", fg_num_accurate / num_fg)\n        storage.put_scalar(f\"{prefix}/false_negative\", num_false_negative / num_fg)\n\n\ndef fast_rcnn_inference_single_image(\n    boxes,\n    scores,\n    image_shape: Tuple[int, int],\n    score_thresh: float,\n    nms_thresh: float,\n    topk_per_image: int,\n):\n    \"\"\"\n    Single-image inference. Return bounding-box detection results by thresholding\n    on scores and applying non-maximum suppression (NMS).\n\n    Args:\n        Same as `fast_rcnn_inference`, but with boxes, scores, and image shapes\n        per image.\n\n    Returns:\n        Same as `fast_rcnn_inference`, but for only one image.\n    \"\"\"\n    valid_mask = torch.isfinite(boxes).all(dim=1) & torch.isfinite(scores).all(dim=1)\n    if not valid_mask.all():\n        boxes = boxes[valid_mask]\n        scores = scores[valid_mask]\n\n    scores = scores[:, :-1]\n    num_bbox_reg_classes = boxes.shape[1] // 4\n    # Convert to Boxes to use the `clip` function ...\n    boxes = Boxes(boxes.reshape(-1, 4))\n    boxes.clip(image_shape)\n    boxes = boxes.tensor.view(-1, num_bbox_reg_classes, 4)  # R x C x 4\n\n    # 1. Filter results based on detection scores. It can make NMS more efficient\n    #    by filtering out low-confidence detections.\n    filter_mask = scores > score_thresh  # R x K\n    # R' x 2. First column contains indices of the R predictions;\n    # Second column contains indices of classes.\n    filter_inds = filter_mask.nonzero()\n    if num_bbox_reg_classes == 1:\n        boxes = boxes[filter_inds[:, 0], 0]\n    else:\n        boxes = boxes[filter_mask]\n    scores = scores[filter_mask]\n\n    # 2. Apply NMS for each class independently.\n    keep = batched_nms(boxes, scores, filter_inds[:, 1], nms_thresh)\n    if topk_per_image >= 0:\n        keep = keep[:topk_per_image]\n    boxes, scores, filter_inds = boxes[keep], scores[keep], filter_inds[keep]\n\n    result = Instances(image_shape)\n    result.pred_boxes = Boxes(boxes)\n    result.scores = scores\n    result.pred_classes = filter_inds[:, 1]\n    return result, filter_inds[:, 0]\n\n\nclass FastRCNNOutputLayers(nn.Module):\n    \"\"\"\n    Two linear layers for predicting Fast R-CNN outputs:\n\n    1. proposal-to-detection box regression deltas\n    2. classification scores\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self,\n        input_shape: ShapeSpec,\n        *,\n        box2box_transform,\n        num_classes: int,\n        test_score_thresh: float = 0.0,\n        test_nms_thresh: float = 0.5,\n        test_topk_per_image: int = 100,\n        cls_agnostic_bbox_reg: bool = False,\n        smooth_l1_beta: float = 0.0,\n        box_reg_loss_type: str = \"smooth_l1\",\n        loss_weight: Union[float, Dict[str, float]] = 1.0,\n    ):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            input_shape (ShapeSpec): shape of the input feature to this module\n            box2box_transform (Box2BoxTransform or Box2BoxTransformRotated):\n            num_classes (int): number of foreground classes\n            test_score_thresh (float): threshold to filter predictions results.\n            test_nms_thresh (float): NMS threshold for prediction results.\n            test_topk_per_image (int): number of top predictions to produce per image.\n            cls_agnostic_bbox_reg (bool): whether to use class agnostic for bbox regression\n            smooth_l1_beta (float): transition point from L1 to L2 loss. Only used if\n                `box_reg_loss_type` is \"smooth_l1\"\n            box_reg_loss_type (str): Box regression loss type. One of: \"smooth_l1\", \"giou\",\n                \"diou\", \"ciou\"\n            loss_weight (float|dict): weights to use for losses. Can be single float for weighting\n                all losses, or a dict of individual weightings. Valid dict keys are:\n                    * \"loss_cls\": applied to classification loss\n                    * \"loss_box_reg\": applied to box regression loss\n        \"\"\"\n        super().__init__()\n        if isinstance(input_shape, int):  # some backward compatibility\n            input_shape = ShapeSpec(channels=input_shape)\n        self.num_classes = num_classes\n        input_size = input_shape.channels * (input_shape.width or 1) * (input_shape.height or 1)\n        # prediction layer for num_classes foreground classes and one background class (hence + 1)\n        self.cls_score = nn.Linear(input_size, num_classes + 1)\n        num_bbox_reg_classes = 1 if cls_agnostic_bbox_reg else num_classes\n        box_dim = len(box2box_transform.weights)\n        self.bbox_pred = nn.Linear(input_size, num_bbox_reg_classes * box_dim)\n\n        nn.init.normal_(self.cls_score.weight, std=0.01)\n        nn.init.normal_(self.bbox_pred.weight, std=0.001)\n        for l in [self.cls_score, self.bbox_pred]:\n            nn.init.constant_(l.bias, 0)\n\n        self.box2box_transform = box2box_transform\n        self.smooth_l1_beta = smooth_l1_beta\n        self.test_score_thresh = test_score_thresh\n        self.test_nms_thresh = test_nms_thresh\n        self.test_topk_per_image = test_topk_per_image\n        self.box_reg_loss_type = box_reg_loss_type\n        if isinstance(loss_weight, float):\n            loss_weight = {\"loss_cls\": loss_weight, \"loss_box_reg\": loss_weight}\n        self.loss_weight = loss_weight\n\n    @classmethod\n    def from_config(cls, cfg, input_shape):\n        return {\n            \"input_shape\": input_shape,\n            \"box2box_transform\": Box2BoxTransform(weights=cfg.MODEL.ROI_BOX_HEAD.BBOX_REG_WEIGHTS),\n            # fmt: off\n            \"num_classes\"           : cfg.MODEL.ROI_HEADS.NUM_CLASSES,\n            \"cls_agnostic_bbox_reg\" : cfg.MODEL.ROI_BOX_HEAD.CLS_AGNOSTIC_BBOX_REG,\n            \"smooth_l1_beta\"        : cfg.MODEL.ROI_BOX_HEAD.SMOOTH_L1_BETA,\n            \"test_score_thresh\"     : cfg.MODEL.ROI_HEADS.SCORE_THRESH_TEST,\n            \"test_nms_thresh\"       : cfg.MODEL.ROI_HEADS.NMS_THRESH_TEST,\n            \"test_topk_per_image\"   : cfg.TEST.DETECTIONS_PER_IMAGE,\n            \"box_reg_loss_type\"     : cfg.MODEL.ROI_BOX_HEAD.BBOX_REG_LOSS_TYPE,\n            \"loss_weight\"           : {\"loss_box_reg\": cfg.MODEL.ROI_BOX_HEAD.BBOX_REG_LOSS_WEIGHT},\n            # fmt: on\n        }\n\n    def forward(self, x):\n        \"\"\"\n        Args:\n            x: per-region features of shape (N, ...) for N bounding boxes to predict.\n\n        Returns:\n            (Tensor, Tensor):\n            First tensor: shape (N,K+1), scores for each of the N box. Each row contains the\n            scores for K object categories and 1 background class.\n\n            Second tensor: bounding box regression deltas for each box. Shape is shape (N,Kx4),\n            or (N,4) for class-agnostic regression.\n        \"\"\"\n        if x.dim() > 2:\n            x = torch.flatten(x, start_dim=1)\n        scores = self.cls_score(x)\n        proposal_deltas = self.bbox_pred(x)\n        return scores, proposal_deltas\n\n    def losses(self, predictions, proposals):\n        \"\"\"\n        Args:\n            predictions: return values of :meth:`forward()`.\n            proposals (list[Instances]): proposals that match the features that were used\n                to compute predictions. The fields ``proposal_boxes``, ``gt_boxes``,\n                ``gt_classes`` are expected.\n\n        Returns:\n            Dict[str, Tensor]: dict of losses\n        \"\"\"\n        scores, proposal_deltas = predictions\n\n        # parse classification outputs\n        gt_classes = (\n            cat([p.gt_classes for p in proposals], dim=0) if len(proposals) else torch.empty(0)\n        )\n        _log_classification_stats(scores, gt_classes)\n\n        # parse box regression outputs\n        if len(proposals):\n            proposal_boxes = cat([p.proposal_boxes.tensor for p in proposals], dim=0)  # Nx4\n            assert not proposal_boxes.requires_grad, \"Proposals should not require gradients!\"\n            # If \"gt_boxes\" does not exist, the proposals must be all negative and\n            # should not be included in regression loss computation.\n            # Here we just use proposal_boxes as an arbitrary placeholder because its\n            # value won't be used in self.box_reg_loss().\n            gt_boxes = cat(\n                [(p.gt_boxes if p.has(\"gt_boxes\") else p.proposal_boxes).tensor for p in proposals],\n                dim=0,\n            )\n        else:\n            proposal_boxes = gt_boxes = torch.empty((0, 4), device=proposal_deltas.device)\n\n        losses = {\n            \"loss_cls\": cross_entropy(scores, gt_classes, reduction=\"mean\"),\n            \"loss_box_reg\": self.box_reg_loss(\n                proposal_boxes, gt_boxes, proposal_deltas, gt_classes\n            ),\n        }\n        return {k: v * self.loss_weight.get(k, 1.0) for k, v in losses.items()}\n\n    def box_reg_loss(self, proposal_boxes, gt_boxes, pred_deltas, gt_classes):\n        \"\"\"\n        Args:\n            proposal_boxes/gt_boxes are tensors with the same shape (R, 4 or 5).\n            pred_deltas has shape (R, 4 or 5), or (R, num_classes * (4 or 5)).\n            gt_classes is a long tensor of shape R, the gt class label of each proposal.\n            R shall be the number of proposals.\n        \"\"\"\n        box_dim = proposal_boxes.shape[1]  # 4 or 5\n        # Regression loss is only computed for foreground proposals (those matched to a GT)\n        fg_inds = nonzero_tuple((gt_classes >= 0) & (gt_classes < self.num_classes))[0]\n        if pred_deltas.shape[1] == box_dim:  # cls-agnostic regression\n            fg_pred_deltas = pred_deltas[fg_inds]\n        else:\n            fg_pred_deltas = pred_deltas.view(-1, self.num_classes, box_dim)[\n                fg_inds, gt_classes[fg_inds]\n            ]\n\n        loss_box_reg = _dense_box_regression_loss(\n            [proposal_boxes[fg_inds]],\n            self.box2box_transform,\n            [fg_pred_deltas.unsqueeze(0)],\n            [gt_boxes[fg_inds]],\n            ...,\n            self.box_reg_loss_type,\n            self.smooth_l1_beta,\n        )\n\n        # The reg loss is normalized using the total number of regions (R), not the number\n        # of foreground regions even though the box regression loss is only defined on\n        # foreground regions. Why? Because doing so gives equal training influence to\n        # each foreground example. To see how, consider two different minibatches:\n        #  (1) Contains a single foreground region\n        #  (2) Contains 100 foreground regions\n        # If we normalize by the number of foreground regions, the single example in\n        # minibatch (1) will be given 100 times as much influence as each foreground\n        # example in minibatch (2). Normalizing by the total number of regions, R,\n        # means that the single example in minibatch (1) and each of the 100 examples\n        # in minibatch (2) are given equal influence.\n        return loss_box_reg / max(gt_classes.numel(), 1.0)  # return 0 if empty\n\n    def inference(self, predictions: Tuple[torch.Tensor, torch.Tensor], proposals: List[Instances]):\n        \"\"\"\n        Args:\n            predictions: return values of :meth:`forward()`.\n            proposals (list[Instances]): proposals that match the features that were\n                used to compute predictions. The ``proposal_boxes`` field is expected.\n\n        Returns:\n            list[Instances]: same as `fast_rcnn_inference`.\n            list[Tensor]: same as `fast_rcnn_inference`.\n        \"\"\"\n        boxes = self.predict_boxes(predictions, proposals)\n        scores = self.predict_probs(predictions, proposals)\n        image_shapes = [x.image_size for x in proposals]\n        return fast_rcnn_inference(\n            boxes,\n            scores,\n            image_shapes,\n            self.test_score_thresh,\n            self.test_nms_thresh,\n            self.test_topk_per_image,\n        )\n\n    def predict_boxes_for_gt_classes(self, predictions, proposals):\n        \"\"\"\n        Args:\n            predictions: return values of :meth:`forward()`.\n            proposals (list[Instances]): proposals that match the features that were used\n                to compute predictions. The fields ``proposal_boxes``, ``gt_classes`` are expected.\n\n        Returns:\n            list[Tensor]:\n                A list of Tensors of predicted boxes for GT classes in case of\n                class-specific box head. Element i of the list has shape (Ri, B), where Ri is\n                the number of proposals for image i and B is the box dimension (4 or 5)\n        \"\"\"\n        if not len(proposals):\n            return []\n        scores, proposal_deltas = predictions\n        proposal_boxes = cat([p.proposal_boxes.tensor for p in proposals], dim=0)\n        N, B = proposal_boxes.shape\n        predict_boxes = self.box2box_transform.apply_deltas(\n            proposal_deltas, proposal_boxes\n        )  # Nx(KxB)\n\n        K = predict_boxes.shape[1] // B\n        if K > 1:\n            gt_classes = torch.cat([p.gt_classes for p in proposals], dim=0)\n            # Some proposals are ignored or have a background class. Their gt_classes\n            # cannot be used as index.\n            gt_classes = gt_classes.clamp_(0, K - 1)\n\n            predict_boxes = predict_boxes.view(N, K, B)[\n                torch.arange(N, dtype=torch.long, device=predict_boxes.device), gt_classes\n            ]\n        num_prop_per_image = [len(p) for p in proposals]\n        return predict_boxes.split(num_prop_per_image)\n\n    def predict_boxes(\n        self, predictions: Tuple[torch.Tensor, torch.Tensor], proposals: List[Instances]\n    ):\n        \"\"\"\n        Args:\n            predictions: return values of :meth:`forward()`.\n            proposals (list[Instances]): proposals that match the features that were\n                used to compute predictions. The ``proposal_boxes`` field is expected.\n\n        Returns:\n            list[Tensor]:\n                A list of Tensors of predicted class-specific or class-agnostic boxes\n                for each image. Element i has shape (Ri, K * B) or (Ri, B), where Ri is\n                the number of proposals for image i and B is the box dimension (4 or 5)\n        \"\"\"\n        if not len(proposals):\n            return []\n        _, proposal_deltas = predictions\n        num_prop_per_image = [len(p) for p in proposals]\n        proposal_boxes = cat([p.proposal_boxes.tensor for p in proposals], dim=0)\n        predict_boxes = self.box2box_transform.apply_deltas(\n            proposal_deltas,\n            proposal_boxes,\n        )  # Nx(KxB)\n        return predict_boxes.split(num_prop_per_image)\n\n    def predict_probs(\n        self, predictions: Tuple[torch.Tensor, torch.Tensor], proposals: List[Instances]\n    ):\n        \"\"\"\n        Args:\n            predictions: return values of :meth:`forward()`.\n            proposals (list[Instances]): proposals that match the features that were\n                used to compute predictions.\n\n        Returns:\n            list[Tensor]:\n                A list of Tensors of predicted class probabilities for each image.\n                Element i has shape (Ri, K + 1), where Ri is the number of proposals for image i.\n        \"\"\"\n        scores, _ = predictions\n        num_inst_per_image = [len(p) for p in proposals]\n        probs = F.softmax(scores, dim=-1)\n        return probs.split(num_inst_per_image, dim=0)\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/roi_heads/keypoint_head.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom typing import List\nimport torch\nfrom torch import nn\nfrom torch.nn import functional as F\n\nfrom detectron2.config import configurable\nfrom detectron2.layers import Conv2d, ConvTranspose2d, cat, interpolate\nfrom detectron2.structures import Instances, heatmaps_to_keypoints\nfrom detectron2.utils.events import get_event_storage\nfrom detectron2.utils.registry import Registry\n\n_TOTAL_SKIPPED = 0\n\n\n__all__ = [\n    \"ROI_KEYPOINT_HEAD_REGISTRY\",\n    \"build_keypoint_head\",\n    \"BaseKeypointRCNNHead\",\n    \"KRCNNConvDeconvUpsampleHead\",\n]\n\n\nROI_KEYPOINT_HEAD_REGISTRY = Registry(\"ROI_KEYPOINT_HEAD\")\nROI_KEYPOINT_HEAD_REGISTRY.__doc__ = \"\"\"\nRegistry for keypoint heads, which make keypoint predictions from per-region features.\n\nThe registered object will be called with `obj(cfg, input_shape)`.\n\"\"\"\n\n\ndef build_keypoint_head(cfg, input_shape):\n    \"\"\"\n    Build a keypoint head from `cfg.MODEL.ROI_KEYPOINT_HEAD.NAME`.\n    \"\"\"\n    name = cfg.MODEL.ROI_KEYPOINT_HEAD.NAME\n    return ROI_KEYPOINT_HEAD_REGISTRY.get(name)(cfg, input_shape)\n\n\ndef keypoint_rcnn_loss(pred_keypoint_logits, instances, normalizer):\n    \"\"\"\n    Arguments:\n        pred_keypoint_logits (Tensor): A tensor of shape (N, K, S, S) where N is the total number\n            of instances in the batch, K is the number of keypoints, and S is the side length\n            of the keypoint heatmap. The values are spatial logits.\n        instances (list[Instances]): A list of M Instances, where M is the batch size.\n            These instances are predictions from the model\n            that are in 1:1 correspondence with pred_keypoint_logits.\n            Each Instances should contain a `gt_keypoints` field containing a `structures.Keypoint`\n            instance.\n        normalizer (float): Normalize the loss by this amount.\n            If not specified, we normalize by the number of visible keypoints in the minibatch.\n\n    Returns a scalar tensor containing the loss.\n    \"\"\"\n    heatmaps = []\n    valid = []\n\n    keypoint_side_len = pred_keypoint_logits.shape[2]\n    for instances_per_image in instances:\n        if len(instances_per_image) == 0:\n            continue\n        keypoints = instances_per_image.gt_keypoints\n        heatmaps_per_image, valid_per_image = keypoints.to_heatmap(\n            instances_per_image.proposal_boxes.tensor, keypoint_side_len\n        )\n        heatmaps.append(heatmaps_per_image.view(-1))\n        valid.append(valid_per_image.view(-1))\n\n    if len(heatmaps):\n        keypoint_targets = cat(heatmaps, dim=0)\n        valid = cat(valid, dim=0).to(dtype=torch.uint8)\n        valid = torch.nonzero(valid).squeeze(1)\n\n    # torch.mean (in binary_cross_entropy_with_logits) doesn't\n    # accept empty tensors, so handle it separately\n    if len(heatmaps) == 0 or valid.numel() == 0:\n        global _TOTAL_SKIPPED\n        _TOTAL_SKIPPED += 1\n        storage = get_event_storage()\n        storage.put_scalar(\"kpts_num_skipped_batches\", _TOTAL_SKIPPED, smoothing_hint=False)\n        return pred_keypoint_logits.sum() * 0\n\n    N, K, H, W = pred_keypoint_logits.shape\n    pred_keypoint_logits = pred_keypoint_logits.view(N * K, H * W)\n\n    keypoint_loss = F.cross_entropy(\n        pred_keypoint_logits[valid], keypoint_targets[valid], reduction=\"sum\"\n    )\n\n    # If a normalizer isn't specified, normalize by the number of visible keypoints in the minibatch\n    if normalizer is None:\n        normalizer = valid.numel()\n    keypoint_loss /= normalizer\n\n    return keypoint_loss\n\n\ndef keypoint_rcnn_inference(pred_keypoint_logits: torch.Tensor, pred_instances: List[Instances]):\n    \"\"\"\n    Post process each predicted keypoint heatmap in `pred_keypoint_logits` into (x, y, score)\n        and add it to the `pred_instances` as a `pred_keypoints` field.\n\n    Args:\n        pred_keypoint_logits (Tensor): A tensor of shape (R, K, S, S) where R is the total number\n           of instances in the batch, K is the number of keypoints, and S is the side length of\n           the keypoint heatmap. The values are spatial logits.\n        pred_instances (list[Instances]): A list of N Instances, where N is the number of images.\n\n    Returns:\n        None. Each element in pred_instances will contain extra \"pred_keypoints\" and\n            \"pred_keypoint_heatmaps\" fields. \"pred_keypoints\" is a tensor of shape\n            (#instance, K, 3) where the last dimension corresponds to (x, y, score).\n            The scores are larger than 0. \"pred_keypoint_heatmaps\" contains the raw\n            keypoint logits as passed to this function.\n    \"\"\"\n    # flatten all bboxes from all images together (list[Boxes] -> Rx4 tensor)\n    bboxes_flat = cat([b.pred_boxes.tensor for b in pred_instances], dim=0)\n\n    pred_keypoint_logits = pred_keypoint_logits.detach()\n    keypoint_results = heatmaps_to_keypoints(pred_keypoint_logits, bboxes_flat.detach())\n    num_instances_per_image = [len(i) for i in pred_instances]\n    keypoint_results = keypoint_results[:, :, [0, 1, 3]].split(num_instances_per_image, dim=0)\n    heatmap_results = pred_keypoint_logits.split(num_instances_per_image, dim=0)\n\n    for keypoint_results_per_image, heatmap_results_per_image, instances_per_image in zip(\n        keypoint_results, heatmap_results, pred_instances\n    ):\n        # keypoint_results_per_image is (num instances)x(num keypoints)x(x, y, score)\n        # heatmap_results_per_image is (num instances)x(num keypoints)x(side)x(side)\n        instances_per_image.pred_keypoints = keypoint_results_per_image\n        instances_per_image.pred_keypoint_heatmaps = heatmap_results_per_image\n\n\nclass BaseKeypointRCNNHead(nn.Module):\n    \"\"\"\n    Implement the basic Keypoint R-CNN losses and inference logic described in\n    Sec. 5 of :paper:`Mask R-CNN`.\n    \"\"\"\n\n    @configurable\n    def __init__(self, *, num_keypoints, loss_weight=1.0, loss_normalizer=1.0):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            num_keypoints (int): number of keypoints to predict\n            loss_weight (float): weight to multiple on the keypoint loss\n            loss_normalizer (float or str):\n                If float, divide the loss by `loss_normalizer * #images`.\n                If 'visible', the loss is normalized by the total number of\n                visible keypoints across images.\n        \"\"\"\n        super().__init__()\n        self.num_keypoints = num_keypoints\n        self.loss_weight = loss_weight\n        assert loss_normalizer == \"visible\" or isinstance(loss_normalizer, float), loss_normalizer\n        self.loss_normalizer = loss_normalizer\n\n    @classmethod\n    def from_config(cls, cfg, input_shape):\n        ret = {\n            \"loss_weight\": cfg.MODEL.ROI_KEYPOINT_HEAD.LOSS_WEIGHT,\n            \"num_keypoints\": cfg.MODEL.ROI_KEYPOINT_HEAD.NUM_KEYPOINTS,\n        }\n        normalize_by_visible = (\n            cfg.MODEL.ROI_KEYPOINT_HEAD.NORMALIZE_LOSS_BY_VISIBLE_KEYPOINTS\n        )  # noqa\n        if not normalize_by_visible:\n            batch_size_per_image = cfg.MODEL.ROI_HEADS.BATCH_SIZE_PER_IMAGE\n            positive_sample_fraction = cfg.MODEL.ROI_HEADS.POSITIVE_FRACTION\n            ret[\"loss_normalizer\"] = (\n                ret[\"num_keypoints\"] * batch_size_per_image * positive_sample_fraction\n            )\n        else:\n            ret[\"loss_normalizer\"] = \"visible\"\n        return ret\n\n    def forward(self, x, instances: List[Instances]):\n        \"\"\"\n        Args:\n            x: input 4D region feature(s) provided by :class:`ROIHeads`.\n            instances (list[Instances]): contains the boxes & labels corresponding\n                to the input features.\n                Exact format is up to its caller to decide.\n                Typically, this is the foreground instances in training, with\n                \"proposal_boxes\" field and other gt annotations.\n                In inference, it contains boxes that are already predicted.\n\n        Returns:\n            A dict of losses if in training. The predicted \"instances\" if in inference.\n        \"\"\"\n        x = self.layers(x)\n        if self.training:\n            num_images = len(instances)\n            normalizer = (\n                None if self.loss_normalizer == \"visible\" else num_images * self.loss_normalizer\n            )\n            return {\n                \"loss_keypoint\": keypoint_rcnn_loss(x, instances, normalizer=normalizer)\n                * self.loss_weight\n            }\n        else:\n            keypoint_rcnn_inference(x, instances)\n            return instances\n\n    def layers(self, x):\n        \"\"\"\n        Neural network layers that makes predictions from regional input features.\n        \"\"\"\n        raise NotImplementedError\n\n\n# To get torchscript support, we make the head a subclass of `nn.Sequential`.\n# Therefore, to add new layers in this head class, please make sure they are\n# added in the order they will be used in forward().\n@ROI_KEYPOINT_HEAD_REGISTRY.register()\nclass KRCNNConvDeconvUpsampleHead(BaseKeypointRCNNHead, nn.Sequential):\n    \"\"\"\n    A standard keypoint head containing a series of 3x3 convs, followed by\n    a transpose convolution and bilinear interpolation for upsampling.\n    It is described in Sec. 5 of :paper:`Mask R-CNN`.\n    \"\"\"\n\n    @configurable\n    def __init__(self, input_shape, *, num_keypoints, conv_dims, **kwargs):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            input_shape (ShapeSpec): shape of the input feature\n            conv_dims: an iterable of output channel counts for each conv in the head\n                         e.g. (512, 512, 512) for three convs outputting 512 channels.\n        \"\"\"\n        super().__init__(num_keypoints=num_keypoints, **kwargs)\n\n        # default up_scale to 2.0 (this can be made an option)\n        up_scale = 2.0\n        in_channels = input_shape.channels\n\n        for idx, layer_channels in enumerate(conv_dims, 1):\n            module = Conv2d(in_channels, layer_channels, 3, stride=1, padding=1)\n            self.add_module(\"conv_fcn{}\".format(idx), module)\n            self.add_module(\"conv_fcn_relu{}\".format(idx), nn.ReLU())\n            in_channels = layer_channels\n\n        deconv_kernel = 4\n        self.score_lowres = ConvTranspose2d(\n            in_channels, num_keypoints, deconv_kernel, stride=2, padding=deconv_kernel // 2 - 1\n        )\n        self.up_scale = up_scale\n\n        for name, param in self.named_parameters():\n            if \"bias\" in name:\n                nn.init.constant_(param, 0)\n            elif \"weight\" in name:\n                # Caffe2 implementation uses MSRAFill, which in fact\n                # corresponds to kaiming_normal_ in PyTorch\n                nn.init.kaiming_normal_(param, mode=\"fan_out\", nonlinearity=\"relu\")\n\n    @classmethod\n    def from_config(cls, cfg, input_shape):\n        ret = super().from_config(cfg, input_shape)\n        ret[\"input_shape\"] = input_shape\n        ret[\"conv_dims\"] = cfg.MODEL.ROI_KEYPOINT_HEAD.CONV_DIMS\n        return ret\n\n    def layers(self, x):\n        for layer in self:\n            x = layer(x)\n        x = interpolate(x, scale_factor=self.up_scale, mode=\"bilinear\", align_corners=False)\n        return x\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/roi_heads/mask_head.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom typing import List\nimport fvcore.nn.weight_init as weight_init\nimport torch\nfrom torch import nn\nfrom torch.nn import functional as F\n\nfrom detectron2.config import configurable\nfrom detectron2.layers import Conv2d, ConvTranspose2d, ShapeSpec, cat, get_norm\nfrom detectron2.structures import Instances\nfrom detectron2.utils.events import get_event_storage\nfrom detectron2.utils.registry import Registry\n\n__all__ = [\n    \"BaseMaskRCNNHead\",\n    \"MaskRCNNConvUpsampleHead\",\n    \"build_mask_head\",\n    \"ROI_MASK_HEAD_REGISTRY\",\n]\n\n\nROI_MASK_HEAD_REGISTRY = Registry(\"ROI_MASK_HEAD\")\nROI_MASK_HEAD_REGISTRY.__doc__ = \"\"\"\nRegistry for mask heads, which predicts instance masks given\nper-region features.\n\nThe registered object will be called with `obj(cfg, input_shape)`.\n\"\"\"\n\n\n@torch.jit.unused\ndef mask_rcnn_loss(pred_mask_logits: torch.Tensor, instances: List[Instances], vis_period: int = 0):\n    \"\"\"\n    Compute the mask prediction loss defined in the Mask R-CNN paper.\n\n    Args:\n        pred_mask_logits (Tensor): A tensor of shape (B, C, Hmask, Wmask) or (B, 1, Hmask, Wmask)\n            for class-specific or class-agnostic, where B is the total number of predicted masks\n            in all images, C is the number of foreground classes, and Hmask, Wmask are the height\n            and width of the mask predictions. The values are logits.\n        instances (list[Instances]): A list of N Instances, where N is the number of images\n            in the batch. These instances are in 1:1\n            correspondence with the pred_mask_logits. The ground-truth labels (class, box, mask,\n            ...) associated with each instance are stored in fields.\n        vis_period (int): the period (in steps) to dump visualization.\n\n    Returns:\n        mask_loss (Tensor): A scalar tensor containing the loss.\n    \"\"\"\n    cls_agnostic_mask = pred_mask_logits.size(1) == 1\n    total_num_masks = pred_mask_logits.size(0)\n    mask_side_len = pred_mask_logits.size(2)\n    assert pred_mask_logits.size(2) == pred_mask_logits.size(3), \"Mask prediction must be square!\"\n\n    gt_classes = []\n    gt_masks = []\n    for instances_per_image in instances:\n        if len(instances_per_image) == 0:\n            continue\n        if not cls_agnostic_mask:\n            gt_classes_per_image = instances_per_image.gt_classes.to(dtype=torch.int64)\n            gt_classes.append(gt_classes_per_image)\n\n        gt_masks_per_image = instances_per_image.gt_masks.crop_and_resize(\n            instances_per_image.proposal_boxes.tensor, mask_side_len\n        ).to(device=pred_mask_logits.device)\n        # A tensor of shape (N, M, M), N=#instances in the image; M=mask_side_len\n        gt_masks.append(gt_masks_per_image)\n\n    if len(gt_masks) == 0:\n        return pred_mask_logits.sum() * 0\n\n    gt_masks = cat(gt_masks, dim=0)\n\n    if cls_agnostic_mask:\n        pred_mask_logits = pred_mask_logits[:, 0]\n    else:\n        indices = torch.arange(total_num_masks)\n        gt_classes = cat(gt_classes, dim=0)\n        pred_mask_logits = pred_mask_logits[indices, gt_classes]\n\n    if gt_masks.dtype == torch.bool:\n        gt_masks_bool = gt_masks\n    else:\n        # Here we allow gt_masks to be float as well (depend on the implementation of rasterize())\n        gt_masks_bool = gt_masks > 0.5\n    gt_masks = gt_masks.to(dtype=torch.float32)\n\n    # Log the training accuracy (using gt classes and 0.5 threshold)\n    mask_incorrect = (pred_mask_logits > 0.0) != gt_masks_bool\n    mask_accuracy = 1 - (mask_incorrect.sum().item() / max(mask_incorrect.numel(), 1.0))\n    num_positive = gt_masks_bool.sum().item()\n    false_positive = (mask_incorrect & ~gt_masks_bool).sum().item() / max(\n        gt_masks_bool.numel() - num_positive, 1.0\n    )\n    false_negative = (mask_incorrect & gt_masks_bool).sum().item() / max(num_positive, 1.0)\n\n    storage = get_event_storage()\n    storage.put_scalar(\"mask_rcnn/accuracy\", mask_accuracy)\n    storage.put_scalar(\"mask_rcnn/false_positive\", false_positive)\n    storage.put_scalar(\"mask_rcnn/false_negative\", false_negative)\n    if vis_period > 0 and storage.iter % vis_period == 0:\n        pred_masks = pred_mask_logits.sigmoid()\n        vis_masks = torch.cat([pred_masks, gt_masks], axis=2)\n        name = \"Left: mask prediction;   Right: mask GT\"\n        for idx, vis_mask in enumerate(vis_masks):\n            vis_mask = torch.stack([vis_mask] * 3, axis=0)\n            storage.put_image(name + f\" ({idx})\", vis_mask)\n\n    mask_loss = F.binary_cross_entropy_with_logits(pred_mask_logits, gt_masks, reduction=\"mean\")\n    return mask_loss\n\n\ndef mask_rcnn_inference(pred_mask_logits: torch.Tensor, pred_instances: List[Instances]):\n    \"\"\"\n    Convert pred_mask_logits to estimated foreground probability masks while also\n    extracting only the masks for the predicted classes in pred_instances. For each\n    predicted box, the mask of the same class is attached to the instance by adding a\n    new \"pred_masks\" field to pred_instances.\n\n    Args:\n        pred_mask_logits (Tensor): A tensor of shape (B, C, Hmask, Wmask) or (B, 1, Hmask, Wmask)\n            for class-specific or class-agnostic, where B is the total number of predicted masks\n            in all images, C is the number of foreground classes, and Hmask, Wmask are the height\n            and width of the mask predictions. The values are logits.\n        pred_instances (list[Instances]): A list of N Instances, where N is the number of images\n            in the batch. Each Instances must have field \"pred_classes\".\n\n    Returns:\n        None. pred_instances will contain an extra \"pred_masks\" field storing a mask of size (Hmask,\n            Wmask) for predicted class. Note that the masks are returned as a soft (non-quantized)\n            masks the resolution predicted by the network; post-processing steps, such as resizing\n            the predicted masks to the original image resolution and/or binarizing them, is left\n            to the caller.\n    \"\"\"\n    cls_agnostic_mask = pred_mask_logits.size(1) == 1\n\n    if cls_agnostic_mask:\n        mask_probs_pred = pred_mask_logits.sigmoid()\n    else:\n        # Select masks corresponding to the predicted classes\n        num_masks = pred_mask_logits.shape[0]\n        class_pred = cat([i.pred_classes for i in pred_instances])\n        indices = torch.arange(num_masks, device=class_pred.device)\n        mask_probs_pred = pred_mask_logits[indices, class_pred][:, None].sigmoid()\n    # mask_probs_pred.shape: (B, 1, Hmask, Wmask)\n\n    num_boxes_per_image = [len(i) for i in pred_instances]\n    mask_probs_pred = mask_probs_pred.split(num_boxes_per_image, dim=0)\n\n    for prob, instances in zip(mask_probs_pred, pred_instances):\n        instances.pred_masks = prob  # (1, Hmask, Wmask)\n\n\nclass BaseMaskRCNNHead(nn.Module):\n    \"\"\"\n    Implement the basic Mask R-CNN losses and inference logic described in :paper:`Mask R-CNN`\n    \"\"\"\n\n    @configurable\n    def __init__(self, *, loss_weight: float = 1.0, vis_period: int = 0):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            loss_weight (float): multiplier of the loss\n            vis_period (int): visualization period\n        \"\"\"\n        super().__init__()\n        self.vis_period = vis_period\n        self.loss_weight = loss_weight\n\n    @classmethod\n    def from_config(cls, cfg, input_shape):\n        return {\"vis_period\": cfg.VIS_PERIOD}\n\n    def forward(self, x, instances: List[Instances]):\n        \"\"\"\n        Args:\n            x: input region feature(s) provided by :class:`ROIHeads`.\n            instances (list[Instances]): contains the boxes & labels corresponding\n                to the input features.\n                Exact format is up to its caller to decide.\n                Typically, this is the foreground instances in training, with\n                \"proposal_boxes\" field and other gt annotations.\n                In inference, it contains boxes that are already predicted.\n\n        Returns:\n            A dict of losses in training. The predicted \"instances\" in inference.\n        \"\"\"\n        x = self.layers(x)\n        if self.training:\n            return {\"loss_mask\": mask_rcnn_loss(x, instances, self.vis_period) * self.loss_weight}\n        else:\n            mask_rcnn_inference(x, instances)\n            return instances\n\n    def layers(self, x):\n        \"\"\"\n        Neural network layers that makes predictions from input features.\n        \"\"\"\n        raise NotImplementedError\n\n\n# To get torchscript support, we make the head a subclass of `nn.Sequential`.\n# Therefore, to add new layers in this head class, please make sure they are\n# added in the order they will be used in forward().\n@ROI_MASK_HEAD_REGISTRY.register()\nclass MaskRCNNConvUpsampleHead(BaseMaskRCNNHead, nn.Sequential):\n    \"\"\"\n    A mask head with several conv layers, plus an upsample layer (with `ConvTranspose2d`).\n    Predictions are made with a final 1x1 conv layer.\n    \"\"\"\n\n    @configurable\n    def __init__(self, input_shape: ShapeSpec, *, num_classes, conv_dims, conv_norm=\"\", **kwargs):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            input_shape (ShapeSpec): shape of the input feature\n            num_classes (int): the number of foreground classes (i.e. background is not\n                included). 1 if using class agnostic prediction.\n            conv_dims (list[int]): a list of N>0 integers representing the output dimensions\n                of N-1 conv layers and the last upsample layer.\n            conv_norm (str or callable): normalization for the conv layers.\n                See :func:`detectron2.layers.get_norm` for supported types.\n        \"\"\"\n        super().__init__(**kwargs)\n        assert len(conv_dims) >= 1, \"conv_dims have to be non-empty!\"\n\n        self.conv_norm_relus = []\n\n        cur_channels = input_shape.channels\n        for k, conv_dim in enumerate(conv_dims[:-1]):\n            conv = Conv2d(\n                cur_channels,\n                conv_dim,\n                kernel_size=3,\n                stride=1,\n                padding=1,\n                bias=not conv_norm,\n                norm=get_norm(conv_norm, conv_dim),\n                activation=nn.ReLU(),\n            )\n            self.add_module(\"mask_fcn{}\".format(k + 1), conv)\n            self.conv_norm_relus.append(conv)\n            cur_channels = conv_dim\n\n        self.deconv = ConvTranspose2d(\n            cur_channels, conv_dims[-1], kernel_size=2, stride=2, padding=0\n        )\n        self.add_module(\"deconv_relu\", nn.ReLU())\n        cur_channels = conv_dims[-1]\n\n        self.predictor = Conv2d(cur_channels, num_classes, kernel_size=1, stride=1, padding=0)\n\n        for layer in self.conv_norm_relus + [self.deconv]:\n            weight_init.c2_msra_fill(layer)\n        # use normal distribution initialization for mask prediction layer\n        nn.init.normal_(self.predictor.weight, std=0.001)\n        if self.predictor.bias is not None:\n            nn.init.constant_(self.predictor.bias, 0)\n\n    @classmethod\n    def from_config(cls, cfg, input_shape):\n        ret = super().from_config(cfg, input_shape)\n        conv_dim = cfg.MODEL.ROI_MASK_HEAD.CONV_DIM\n        num_conv = cfg.MODEL.ROI_MASK_HEAD.NUM_CONV\n        ret.update(\n            conv_dims=[conv_dim] * (num_conv + 1),  # +1 for ConvTranspose\n            conv_norm=cfg.MODEL.ROI_MASK_HEAD.NORM,\n            input_shape=input_shape,\n        )\n        if cfg.MODEL.ROI_MASK_HEAD.CLS_AGNOSTIC_MASK:\n            ret[\"num_classes\"] = 1\n        else:\n            ret[\"num_classes\"] = cfg.MODEL.ROI_HEADS.NUM_CLASSES\n        return ret\n\n    def layers(self, x):\n        for layer in self:\n            x = layer(x)\n        return x\n\n\ndef build_mask_head(cfg, input_shape):\n    \"\"\"\n    Build a mask head defined by `cfg.MODEL.ROI_MASK_HEAD.NAME`.\n    \"\"\"\n    name = cfg.MODEL.ROI_MASK_HEAD.NAME\n    return ROI_MASK_HEAD_REGISTRY.get(name)(cfg, input_shape)\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/roi_heads/roi_heads.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport inspect\nimport logging\nimport numpy as np\nfrom typing import Dict, List, Optional, Tuple\nimport torch\nfrom torch import nn\n\nfrom detectron2.config import configurable\nfrom detectron2.layers import ShapeSpec, nonzero_tuple\nfrom detectron2.structures import Boxes, ImageList, Instances, pairwise_iou\nfrom detectron2.utils.events import get_event_storage\nfrom detectron2.utils.registry import Registry\n\nfrom ..backbone.resnet import BottleneckBlock, ResNet\nfrom ..matcher import Matcher\nfrom ..poolers import ROIPooler\nfrom ..proposal_generator.proposal_utils import add_ground_truth_to_proposals\nfrom ..sampling import subsample_labels\nfrom .box_head import build_box_head\nfrom .fast_rcnn import FastRCNNOutputLayers\nfrom .keypoint_head import build_keypoint_head\nfrom .mask_head import build_mask_head\n\nROI_HEADS_REGISTRY = Registry(\"ROI_HEADS\")\nROI_HEADS_REGISTRY.__doc__ = \"\"\"\nRegistry for ROI heads in a generalized R-CNN model.\nROIHeads take feature maps and region proposals, and\nperform per-region computation.\n\nThe registered object will be called with `obj(cfg, input_shape)`.\nThe call is expected to return an :class:`ROIHeads`.\n\"\"\"\n\nlogger = logging.getLogger(__name__)\n\n\ndef build_roi_heads(cfg, input_shape):\n    \"\"\"\n    Build ROIHeads defined by `cfg.MODEL.ROI_HEADS.NAME`.\n    \"\"\"\n    name = cfg.MODEL.ROI_HEADS.NAME\n    return ROI_HEADS_REGISTRY.get(name)(cfg, input_shape)\n\n\ndef select_foreground_proposals(\n    proposals: List[Instances], bg_label: int\n) -> Tuple[List[Instances], List[torch.Tensor]]:\n    \"\"\"\n    Given a list of N Instances (for N images), each containing a `gt_classes` field,\n    return a list of Instances that contain only instances with `gt_classes != -1 &&\n    gt_classes != bg_label`.\n\n    Args:\n        proposals (list[Instances]): A list of N Instances, where N is the number of\n            images in the batch.\n        bg_label: label index of background class.\n\n    Returns:\n        list[Instances]: N Instances, each contains only the selected foreground instances.\n        list[Tensor]: N boolean vector, correspond to the selection mask of\n            each Instances object. True for selected instances.\n    \"\"\"\n    assert isinstance(proposals, (list, tuple))\n    assert isinstance(proposals[0], Instances)\n    assert proposals[0].has(\"gt_classes\")\n    fg_proposals = []\n    fg_selection_masks = []\n    for proposals_per_image in proposals:\n        gt_classes = proposals_per_image.gt_classes\n        fg_selection_mask = (gt_classes != -1) & (gt_classes != bg_label)\n        fg_idxs = fg_selection_mask.nonzero().squeeze(1)\n        fg_proposals.append(proposals_per_image[fg_idxs])\n        fg_selection_masks.append(fg_selection_mask)\n    return fg_proposals, fg_selection_masks\n\n\ndef select_proposals_with_visible_keypoints(proposals: List[Instances]) -> List[Instances]:\n    \"\"\"\n    Args:\n        proposals (list[Instances]): a list of N Instances, where N is the\n            number of images.\n\n    Returns:\n        proposals: only contains proposals with at least one visible keypoint.\n\n    Note that this is still slightly different from Detectron.\n    In Detectron, proposals for training keypoint head are re-sampled from\n    all the proposals with IOU>threshold & >=1 visible keypoint.\n\n    Here, the proposals are first sampled from all proposals with\n    IOU>threshold, then proposals with no visible keypoint are filtered out.\n    This strategy seems to make no difference on Detectron and is easier to implement.\n    \"\"\"\n    ret = []\n    all_num_fg = []\n    for proposals_per_image in proposals:\n        # If empty/unannotated image (hard negatives), skip filtering for train\n        if len(proposals_per_image) == 0:\n            ret.append(proposals_per_image)\n            continue\n        gt_keypoints = proposals_per_image.gt_keypoints.tensor\n        # #fg x K x 3\n        vis_mask = gt_keypoints[:, :, 2] >= 1\n        xs, ys = gt_keypoints[:, :, 0], gt_keypoints[:, :, 1]\n        proposal_boxes = proposals_per_image.proposal_boxes.tensor.unsqueeze(dim=1)  # #fg x 1 x 4\n        kp_in_box = (\n            (xs >= proposal_boxes[:, :, 0])\n            & (xs <= proposal_boxes[:, :, 2])\n            & (ys >= proposal_boxes[:, :, 1])\n            & (ys <= proposal_boxes[:, :, 3])\n        )\n        selection = (kp_in_box & vis_mask).any(dim=1)\n        selection_idxs = nonzero_tuple(selection)[0]\n        all_num_fg.append(selection_idxs.numel())\n        ret.append(proposals_per_image[selection_idxs])\n\n    storage = get_event_storage()\n    storage.put_scalar(\"keypoint_head/num_fg_samples\", np.mean(all_num_fg))\n    return ret\n\n\nclass ROIHeads(torch.nn.Module):\n    \"\"\"\n    ROIHeads perform all per-region computation in an R-CNN.\n\n    It typically contains logic to\n\n    1. (in training only) match proposals with ground truth and sample them\n    2. crop the regions and extract per-region features using proposals\n    3. make per-region predictions with different heads\n\n    It can have many variants, implemented as subclasses of this class.\n    This base class contains the logic to match/sample proposals.\n    But it is not necessary to inherit this class if the sampling logic is not needed.\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self,\n        *,\n        num_classes,\n        batch_size_per_image,\n        positive_fraction,\n        proposal_matcher,\n        proposal_append_gt=True,\n    ):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            num_classes (int): number of foreground classes (i.e. background is not included)\n            batch_size_per_image (int): number of proposals to sample for training\n            positive_fraction (float): fraction of positive (foreground) proposals\n                to sample for training.\n            proposal_matcher (Matcher): matcher that matches proposals and ground truth\n            proposal_append_gt (bool): whether to include ground truth as proposals as well\n        \"\"\"\n        super().__init__()\n        self.batch_size_per_image = batch_size_per_image\n        self.positive_fraction = positive_fraction\n        self.num_classes = num_classes\n        self.proposal_matcher = proposal_matcher\n        self.proposal_append_gt = proposal_append_gt\n\n    @classmethod\n    def from_config(cls, cfg):\n        return {\n            \"batch_size_per_image\": cfg.MODEL.ROI_HEADS.BATCH_SIZE_PER_IMAGE,\n            \"positive_fraction\": cfg.MODEL.ROI_HEADS.POSITIVE_FRACTION,\n            \"num_classes\": cfg.MODEL.ROI_HEADS.NUM_CLASSES,\n            \"proposal_append_gt\": cfg.MODEL.ROI_HEADS.PROPOSAL_APPEND_GT,\n            # Matcher to assign box proposals to gt boxes\n            \"proposal_matcher\": Matcher(\n                cfg.MODEL.ROI_HEADS.IOU_THRESHOLDS,\n                cfg.MODEL.ROI_HEADS.IOU_LABELS,\n                allow_low_quality_matches=False,\n            ),\n        }\n\n    def _sample_proposals(\n        self, matched_idxs: torch.Tensor, matched_labels: torch.Tensor, gt_classes: torch.Tensor\n    ) -> Tuple[torch.Tensor, torch.Tensor]:\n        \"\"\"\n        Based on the matching between N proposals and M groundtruth,\n        sample the proposals and set their classification labels.\n\n        Args:\n            matched_idxs (Tensor): a vector of length N, each is the best-matched\n                gt index in [0, M) for each proposal.\n            matched_labels (Tensor): a vector of length N, the matcher's label\n                (one of cfg.MODEL.ROI_HEADS.IOU_LABELS) for each proposal.\n            gt_classes (Tensor): a vector of length M.\n\n        Returns:\n            Tensor: a vector of indices of sampled proposals. Each is in [0, N).\n            Tensor: a vector of the same length, the classification label for\n                each sampled proposal. Each sample is labeled as either a category in\n                [0, num_classes) or the background (num_classes).\n        \"\"\"\n        has_gt = gt_classes.numel() > 0\n        # Get the corresponding GT for each proposal\n        if has_gt:\n            gt_classes = gt_classes[matched_idxs]\n            # Label unmatched proposals (0 label from matcher) as background (label=num_classes)\n            gt_classes[matched_labels == 0] = self.num_classes\n            # Label ignore proposals (-1 label)\n            gt_classes[matched_labels == -1] = -1\n        else:\n            gt_classes = torch.zeros_like(matched_idxs) + self.num_classes\n\n        sampled_fg_idxs, sampled_bg_idxs = subsample_labels(\n            gt_classes, self.batch_size_per_image, self.positive_fraction, self.num_classes\n        )\n\n        sampled_idxs = torch.cat([sampled_fg_idxs, sampled_bg_idxs], dim=0)\n        return sampled_idxs, gt_classes[sampled_idxs]\n\n    @torch.no_grad()\n    def label_and_sample_proposals(\n        self, proposals: List[Instances], targets: List[Instances]\n    ) -> List[Instances]:\n        \"\"\"\n        Prepare some proposals to be used to train the ROI heads.\n        It performs box matching between `proposals` and `targets`, and assigns\n        training labels to the proposals.\n        It returns ``self.batch_size_per_image`` random samples from proposals and groundtruth\n        boxes, with a fraction of positives that is no larger than\n        ``self.positive_fraction``.\n\n        Args:\n            See :meth:`ROIHeads.forward`\n\n        Returns:\n            list[Instances]:\n                length `N` list of `Instances`s containing the proposals\n                sampled for training. Each `Instances` has the following fields:\n\n                - proposal_boxes: the proposal boxes\n                - gt_boxes: the ground-truth box that the proposal is assigned to\n                  (this is only meaningful if the proposal has a label > 0; if label = 0\n                  then the ground-truth box is random)\n\n                Other fields such as \"gt_classes\", \"gt_masks\", that's included in `targets`.\n        \"\"\"\n        # Augment proposals with ground-truth boxes.\n        # In the case of learned proposals (e.g., RPN), when training starts\n        # the proposals will be low quality due to random initialization.\n        # It's possible that none of these initial\n        # proposals have high enough overlap with the gt objects to be used\n        # as positive examples for the second stage components (box head,\n        # cls head, mask head). Adding the gt boxes to the set of proposals\n        # ensures that the second stage components will have some positive\n        # examples from the start of training. For RPN, this augmentation improves\n        # convergence and empirically improves box AP on COCO by about 0.5\n        # points (under one tested configuration).\n        if self.proposal_append_gt:\n            proposals = add_ground_truth_to_proposals(targets, proposals)\n\n        proposals_with_gt = []\n\n        num_fg_samples = []\n        num_bg_samples = []\n        for proposals_per_image, targets_per_image in zip(proposals, targets):\n            has_gt = len(targets_per_image) > 0\n            match_quality_matrix = pairwise_iou(\n                targets_per_image.gt_boxes, proposals_per_image.proposal_boxes\n            )\n            matched_idxs, matched_labels = self.proposal_matcher(match_quality_matrix)\n            sampled_idxs, gt_classes = self._sample_proposals(\n                matched_idxs, matched_labels, targets_per_image.gt_classes\n            )\n\n            # Set target attributes of the sampled proposals:\n            proposals_per_image = proposals_per_image[sampled_idxs]\n            proposals_per_image.gt_classes = gt_classes\n\n            if has_gt:\n                sampled_targets = matched_idxs[sampled_idxs]\n                # We index all the attributes of targets that start with \"gt_\"\n                # and have not been added to proposals yet (=\"gt_classes\").\n                # NOTE: here the indexing waste some compute, because heads\n                # like masks, keypoints, etc, will filter the proposals again,\n                # (by foreground/background, or number of keypoints in the image, etc)\n                # so we essentially index the data twice.\n                for (trg_name, trg_value) in targets_per_image.get_fields().items():\n                    if trg_name.startswith(\"gt_\") and not proposals_per_image.has(trg_name):\n                        proposals_per_image.set(trg_name, trg_value[sampled_targets])\n            # If no GT is given in the image, we don't know what a dummy gt value can be.\n            # Therefore the returned proposals won't have any gt_* fields, except for a\n            # gt_classes full of background label.\n\n            num_bg_samples.append((gt_classes == self.num_classes).sum().item())\n            num_fg_samples.append(gt_classes.numel() - num_bg_samples[-1])\n            proposals_with_gt.append(proposals_per_image)\n\n        # Log the number of fg/bg samples that are selected for training ROI heads\n        storage = get_event_storage()\n        storage.put_scalar(\"roi_head/num_fg_samples\", np.mean(num_fg_samples))\n        storage.put_scalar(\"roi_head/num_bg_samples\", np.mean(num_bg_samples))\n\n        return proposals_with_gt\n\n    def forward(\n        self,\n        images: ImageList,\n        features: Dict[str, torch.Tensor],\n        proposals: List[Instances],\n        targets: Optional[List[Instances]] = None,\n    ) -> Tuple[List[Instances], Dict[str, torch.Tensor]]:\n        \"\"\"\n        Args:\n            images (ImageList):\n            features (dict[str,Tensor]): input data as a mapping from feature\n                map name to tensor. Axis 0 represents the number of images `N` in\n                the input data; axes 1-3 are channels, height, and width, which may\n                vary between feature maps (e.g., if a feature pyramid is used).\n            proposals (list[Instances]): length `N` list of `Instances`. The i-th\n                `Instances` contains object proposals for the i-th input image,\n                with fields \"proposal_boxes\" and \"objectness_logits\".\n            targets (list[Instances], optional): length `N` list of `Instances`. The i-th\n                `Instances` contains the ground-truth per-instance annotations\n                for the i-th input image.  Specify `targets` during training only.\n                It may have the following fields:\n\n                - gt_boxes: the bounding box of each instance.\n                - gt_classes: the label for each instance with a category ranging in [0, #class].\n                - gt_masks: PolygonMasks or BitMasks, the ground-truth masks of each instance.\n                - gt_keypoints: NxKx3, the groud-truth keypoints for each instance.\n\n        Returns:\n            list[Instances]: length `N` list of `Instances` containing the\n            detected instances. Returned during inference only; may be [] during training.\n\n            dict[str->Tensor]:\n            mapping from a named loss to a tensor storing the loss. Used during training only.\n        \"\"\"\n        raise NotImplementedError()\n\n\n@ROI_HEADS_REGISTRY.register()\nclass Res5ROIHeads(ROIHeads):\n    \"\"\"\n    The ROIHeads in a typical \"C4\" R-CNN model, where\n    the box and mask head share the cropping and\n    the per-region feature computation by a Res5 block.\n    See :paper:`ResNet` Appendix A.\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self,\n        *,\n        in_features: List[str],\n        pooler: ROIPooler,\n        res5: nn.Module,\n        box_predictor: nn.Module,\n        mask_head: Optional[nn.Module] = None,\n        **kwargs,\n    ):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            in_features (list[str]): list of backbone feature map names to use for\n                feature extraction\n            pooler (ROIPooler): pooler to extra region features from backbone\n            res5 (nn.Sequential): a CNN to compute per-region features, to be used by\n                ``box_predictor`` and ``mask_head``. Typically this is a \"res5\"\n                block from a ResNet.\n            box_predictor (nn.Module): make box predictions from the feature.\n                Should have the same interface as :class:`FastRCNNOutputLayers`.\n            mask_head (nn.Module): transform features to make mask predictions\n        \"\"\"\n        super().__init__(**kwargs)\n        self.in_features = in_features\n        self.pooler = pooler\n        if isinstance(res5, (list, tuple)):\n            res5 = nn.Sequential(*res5)\n        self.res5 = res5\n        self.box_predictor = box_predictor\n        self.mask_on = mask_head is not None\n        if self.mask_on:\n            self.mask_head = mask_head\n\n    @classmethod\n    def from_config(cls, cfg, input_shape):\n        # fmt: off\n        ret = super().from_config(cfg)\n        in_features = ret[\"in_features\"] = cfg.MODEL.ROI_HEADS.IN_FEATURES\n        pooler_resolution = cfg.MODEL.ROI_BOX_HEAD.POOLER_RESOLUTION\n        pooler_type       = cfg.MODEL.ROI_BOX_HEAD.POOLER_TYPE\n        pooler_scales     = (1.0 / input_shape[in_features[0]].stride, )\n        sampling_ratio    = cfg.MODEL.ROI_BOX_HEAD.POOLER_SAMPLING_RATIO\n        mask_on           = cfg.MODEL.MASK_ON\n        # fmt: on\n        assert not cfg.MODEL.KEYPOINT_ON\n        assert len(in_features) == 1\n\n        ret[\"pooler\"] = ROIPooler(\n            output_size=pooler_resolution,\n            scales=pooler_scales,\n            sampling_ratio=sampling_ratio,\n            pooler_type=pooler_type,\n        )\n\n        # Compatbility with old moco code. Might be useful.\n        # See notes in StandardROIHeads.from_config\n        if not inspect.ismethod(cls._build_res5_block):\n            logger.warning(\n                \"The behavior of _build_res5_block may change. \"\n                \"Please do not depend on private methods.\"\n            )\n            cls._build_res5_block = classmethod(cls._build_res5_block)\n\n        ret[\"res5\"], out_channels = cls._build_res5_block(cfg)\n        ret[\"box_predictor\"] = FastRCNNOutputLayers(\n            cfg, ShapeSpec(channels=out_channels, height=1, width=1)\n        )\n\n        if mask_on:\n            ret[\"mask_head\"] = build_mask_head(\n                cfg,\n                ShapeSpec(channels=out_channels, width=pooler_resolution, height=pooler_resolution),\n            )\n        return ret\n\n    @classmethod\n    def _build_res5_block(cls, cfg):\n        # fmt: off\n        stage_channel_factor = 2 ** 3  # res5 is 8x res2\n        num_groups           = cfg.MODEL.RESNETS.NUM_GROUPS\n        width_per_group      = cfg.MODEL.RESNETS.WIDTH_PER_GROUP\n        bottleneck_channels  = num_groups * width_per_group * stage_channel_factor\n        out_channels         = cfg.MODEL.RESNETS.RES2_OUT_CHANNELS * stage_channel_factor\n        stride_in_1x1        = cfg.MODEL.RESNETS.STRIDE_IN_1X1\n        norm                 = cfg.MODEL.RESNETS.NORM\n        assert not cfg.MODEL.RESNETS.DEFORM_ON_PER_STAGE[-1], \\\n            \"Deformable conv is not yet supported in res5 head.\"\n        # fmt: on\n\n        blocks = ResNet.make_stage(\n            BottleneckBlock,\n            3,\n            stride_per_block=[2, 1, 1],\n            in_channels=out_channels // 2,\n            bottleneck_channels=bottleneck_channels,\n            out_channels=out_channels,\n            num_groups=num_groups,\n            norm=norm,\n            stride_in_1x1=stride_in_1x1,\n        )\n        return nn.Sequential(*blocks), out_channels\n\n    def _shared_roi_transform(self, features: List[torch.Tensor], boxes: List[Boxes]):\n        x = self.pooler(features, boxes)\n        return self.res5(x)\n\n    def forward(\n        self,\n        images: ImageList,\n        features: Dict[str, torch.Tensor],\n        proposals: List[Instances],\n        targets: Optional[List[Instances]] = None,\n    ):\n        \"\"\"\n        See :meth:`ROIHeads.forward`.\n        \"\"\"\n        del images\n\n        if self.training:\n            assert targets\n            proposals = self.label_and_sample_proposals(proposals, targets)\n        del targets\n\n        proposal_boxes = [x.proposal_boxes for x in proposals]\n        box_features = self._shared_roi_transform(\n            [features[f] for f in self.in_features], proposal_boxes\n        )\n        predictions = self.box_predictor(box_features.mean(dim=[2, 3]))\n\n        if self.training:\n            del features\n            losses = self.box_predictor.losses(predictions, proposals)\n            if self.mask_on:\n                proposals, fg_selection_masks = select_foreground_proposals(\n                    proposals, self.num_classes\n                )\n                # Since the ROI feature transform is shared between boxes and masks,\n                # we don't need to recompute features. The mask loss is only defined\n                # on foreground proposals, so we need to select out the foreground\n                # features.\n                mask_features = box_features[torch.cat(fg_selection_masks, dim=0)]\n                del box_features\n                losses.update(self.mask_head(mask_features, proposals))\n            return [], losses\n        else:\n            pred_instances, _ = self.box_predictor.inference(predictions, proposals)\n            pred_instances = self.forward_with_given_boxes(features, pred_instances)\n            return pred_instances, {}\n\n    def forward_with_given_boxes(\n        self, features: Dict[str, torch.Tensor], instances: List[Instances]\n    ) -> List[Instances]:\n        \"\"\"\n        Use the given boxes in `instances` to produce other (non-box) per-ROI outputs.\n\n        Args:\n            features: same as in `forward()`\n            instances (list[Instances]): instances to predict other outputs. Expect the keys\n                \"pred_boxes\" and \"pred_classes\" to exist.\n\n        Returns:\n            instances (Instances):\n                the same `Instances` object, with extra\n                fields such as `pred_masks` or `pred_keypoints`.\n        \"\"\"\n        assert not self.training\n        assert instances[0].has(\"pred_boxes\") and instances[0].has(\"pred_classes\")\n\n        if self.mask_on:\n            feature_list = [features[f] for f in self.in_features]\n            x = self._shared_roi_transform(feature_list, [x.pred_boxes for x in instances])\n            return self.mask_head(x, instances)\n        else:\n            return instances\n\n\n@ROI_HEADS_REGISTRY.register()\nclass StandardROIHeads(ROIHeads):\n    \"\"\"\n    It's \"standard\" in a sense that there is no ROI transform sharing\n    or feature sharing between tasks.\n    Each head independently processes the input features by each head's\n    own pooler and head.\n\n    This class is used by most models, such as FPN and C5.\n    To implement more models, you can subclass it and implement a different\n    :meth:`forward()` or a head.\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self,\n        *,\n        box_in_features: List[str],\n        box_pooler: ROIPooler,\n        box_head: nn.Module,\n        box_predictor: nn.Module,\n        mask_in_features: Optional[List[str]] = None,\n        mask_pooler: Optional[ROIPooler] = None,\n        mask_head: Optional[nn.Module] = None,\n        keypoint_in_features: Optional[List[str]] = None,\n        keypoint_pooler: Optional[ROIPooler] = None,\n        keypoint_head: Optional[nn.Module] = None,\n        train_on_pred_boxes: bool = False,\n        **kwargs,\n    ):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            box_in_features (list[str]): list of feature names to use for the box head.\n            box_pooler (ROIPooler): pooler to extra region features for box head\n            box_head (nn.Module): transform features to make box predictions\n            box_predictor (nn.Module): make box predictions from the feature.\n                Should have the same interface as :class:`FastRCNNOutputLayers`.\n            mask_in_features (list[str]): list of feature names to use for the mask\n                pooler or mask head. None if not using mask head.\n            mask_pooler (ROIPooler): pooler to extract region features from image features.\n                The mask head will then take region features to make predictions.\n                If None, the mask head will directly take the dict of image features\n                defined by `mask_in_features`\n            mask_head (nn.Module): transform features to make mask predictions\n            keypoint_in_features, keypoint_pooler, keypoint_head: similar to ``mask_*``.\n            train_on_pred_boxes (bool): whether to use proposal boxes or\n                predicted boxes from the box head to train other heads.\n        \"\"\"\n        super().__init__(**kwargs)\n        # keep self.in_features for backward compatibility\n        self.in_features = self.box_in_features = box_in_features\n        self.box_pooler = box_pooler\n        self.box_head = box_head\n        self.box_predictor = box_predictor\n\n        self.mask_on = mask_in_features is not None\n        if self.mask_on:\n            self.mask_in_features = mask_in_features\n            self.mask_pooler = mask_pooler\n            self.mask_head = mask_head\n\n        self.keypoint_on = keypoint_in_features is not None\n        if self.keypoint_on:\n            self.keypoint_in_features = keypoint_in_features\n            self.keypoint_pooler = keypoint_pooler\n            self.keypoint_head = keypoint_head\n\n        self.train_on_pred_boxes = train_on_pred_boxes\n\n    @classmethod\n    def from_config(cls, cfg, input_shape):\n        ret = super().from_config(cfg)\n        ret[\"train_on_pred_boxes\"] = cfg.MODEL.ROI_BOX_HEAD.TRAIN_ON_PRED_BOXES\n        # Subclasses that have not been updated to use from_config style construction\n        # may have overridden _init_*_head methods. In this case, those overridden methods\n        # will not be classmethods and we need to avoid trying to call them here.\n        # We test for this with ismethod which only returns True for bound methods of cls.\n        # Such subclasses will need to handle calling their overridden _init_*_head methods.\n        if inspect.ismethod(cls._init_box_head):\n            ret.update(cls._init_box_head(cfg, input_shape))\n        if inspect.ismethod(cls._init_mask_head):\n            ret.update(cls._init_mask_head(cfg, input_shape))\n        if inspect.ismethod(cls._init_keypoint_head):\n            ret.update(cls._init_keypoint_head(cfg, input_shape))\n        return ret\n\n    @classmethod\n    def _init_box_head(cls, cfg, input_shape):\n        # fmt: off\n        in_features       = cfg.MODEL.ROI_HEADS.IN_FEATURES\n        pooler_resolution = cfg.MODEL.ROI_BOX_HEAD.POOLER_RESOLUTION\n        pooler_scales     = tuple(1.0 / input_shape[k].stride for k in in_features)\n        sampling_ratio    = cfg.MODEL.ROI_BOX_HEAD.POOLER_SAMPLING_RATIO\n        pooler_type       = cfg.MODEL.ROI_BOX_HEAD.POOLER_TYPE\n        # fmt: on\n\n        # If StandardROIHeads is applied on multiple feature maps (as in FPN),\n        # then we share the same predictors and therefore the channel counts must be the same\n        in_channels = [input_shape[f].channels for f in in_features]\n        # Check all channel counts are equal\n        assert len(set(in_channels)) == 1, in_channels\n        in_channels = in_channels[0]\n\n        box_pooler = ROIPooler(\n            output_size=pooler_resolution,\n            scales=pooler_scales,\n            sampling_ratio=sampling_ratio,\n            pooler_type=pooler_type,\n        )\n        # Here we split \"box head\" and \"box predictor\", which is mainly due to historical reasons.\n        # They are used together so the \"box predictor\" layers should be part of the \"box head\".\n        # New subclasses of ROIHeads do not need \"box predictor\"s.\n        box_head = build_box_head(\n            cfg, ShapeSpec(channels=in_channels, height=pooler_resolution, width=pooler_resolution)\n        )\n        box_predictor = FastRCNNOutputLayers(cfg, box_head.output_shape)\n        return {\n            \"box_in_features\": in_features,\n            \"box_pooler\": box_pooler,\n            \"box_head\": box_head,\n            \"box_predictor\": box_predictor,\n        }\n\n    @classmethod\n    def _init_mask_head(cls, cfg, input_shape):\n        if not cfg.MODEL.MASK_ON:\n            return {}\n        # fmt: off\n        in_features       = cfg.MODEL.ROI_HEADS.IN_FEATURES\n        pooler_resolution = cfg.MODEL.ROI_MASK_HEAD.POOLER_RESOLUTION\n        pooler_scales     = tuple(1.0 / input_shape[k].stride for k in in_features)\n        sampling_ratio    = cfg.MODEL.ROI_MASK_HEAD.POOLER_SAMPLING_RATIO\n        pooler_type       = cfg.MODEL.ROI_MASK_HEAD.POOLER_TYPE\n        # fmt: on\n\n        in_channels = [input_shape[f].channels for f in in_features][0]\n\n        ret = {\"mask_in_features\": in_features}\n        ret[\"mask_pooler\"] = (\n            ROIPooler(\n                output_size=pooler_resolution,\n                scales=pooler_scales,\n                sampling_ratio=sampling_ratio,\n                pooler_type=pooler_type,\n            )\n            if pooler_type\n            else None\n        )\n        if pooler_type:\n            shape = ShapeSpec(\n                channels=in_channels, width=pooler_resolution, height=pooler_resolution\n            )\n        else:\n            shape = {f: input_shape[f] for f in in_features}\n        ret[\"mask_head\"] = build_mask_head(cfg, shape)\n        return ret\n\n    @classmethod\n    def _init_keypoint_head(cls, cfg, input_shape):\n        if not cfg.MODEL.KEYPOINT_ON:\n            return {}\n        # fmt: off\n        in_features       = cfg.MODEL.ROI_HEADS.IN_FEATURES\n        pooler_resolution = cfg.MODEL.ROI_KEYPOINT_HEAD.POOLER_RESOLUTION\n        pooler_scales     = tuple(1.0 / input_shape[k].stride for k in in_features)  # noqa\n        sampling_ratio    = cfg.MODEL.ROI_KEYPOINT_HEAD.POOLER_SAMPLING_RATIO\n        pooler_type       = cfg.MODEL.ROI_KEYPOINT_HEAD.POOLER_TYPE\n        # fmt: on\n\n        in_channels = [input_shape[f].channels for f in in_features][0]\n\n        ret = {\"keypoint_in_features\": in_features}\n        ret[\"keypoint_pooler\"] = (\n            ROIPooler(\n                output_size=pooler_resolution,\n                scales=pooler_scales,\n                sampling_ratio=sampling_ratio,\n                pooler_type=pooler_type,\n            )\n            if pooler_type\n            else None\n        )\n        if pooler_type:\n            shape = ShapeSpec(\n                channels=in_channels, width=pooler_resolution, height=pooler_resolution\n            )\n        else:\n            shape = {f: input_shape[f] for f in in_features}\n        ret[\"keypoint_head\"] = build_keypoint_head(cfg, shape)\n        return ret\n\n    def forward(\n        self,\n        images: ImageList,\n        features: Dict[str, torch.Tensor],\n        proposals: List[Instances],\n        targets: Optional[List[Instances]] = None,\n    ) -> Tuple[List[Instances], Dict[str, torch.Tensor]]:\n        \"\"\"\n        See :class:`ROIHeads.forward`.\n        \"\"\"\n        del images\n        if self.training:\n            assert targets, \"'targets' argument is required during training\"\n            proposals = self.label_and_sample_proposals(proposals, targets)\n        del targets\n\n        if self.training:\n            losses = self._forward_box(features, proposals)\n            # Usually the original proposals used by the box head are used by the mask, keypoint\n            # heads. But when `self.train_on_pred_boxes is True`, proposals will contain boxes\n            # predicted by the box head.\n            losses.update(self._forward_mask(features, proposals))\n            losses.update(self._forward_keypoint(features, proposals))\n            return proposals, losses\n        else:\n            pred_instances = self._forward_box(features, proposals)\n            # During inference cascaded prediction is used: the mask and keypoints heads are only\n            # applied to the top scoring box detections.\n            pred_instances = self.forward_with_given_boxes(features, pred_instances)\n            return pred_instances, {}\n\n    def forward_with_given_boxes(\n        self, features: Dict[str, torch.Tensor], instances: List[Instances]\n    ) -> List[Instances]:\n        \"\"\"\n        Use the given boxes in `instances` to produce other (non-box) per-ROI outputs.\n\n        This is useful for downstream tasks where a box is known, but need to obtain\n        other attributes (outputs of other heads).\n        Test-time augmentation also uses this.\n\n        Args:\n            features: same as in `forward()`\n            instances (list[Instances]): instances to predict other outputs. Expect the keys\n                \"pred_boxes\" and \"pred_classes\" to exist.\n\n        Returns:\n            list[Instances]:\n                the same `Instances` objects, with extra\n                fields such as `pred_masks` or `pred_keypoints`.\n        \"\"\"\n        assert not self.training\n        assert instances[0].has(\"pred_boxes\") and instances[0].has(\"pred_classes\")\n\n        instances = self._forward_mask(features, instances)\n        instances = self._forward_keypoint(features, instances)\n        return instances\n\n    def _forward_box(self, features: Dict[str, torch.Tensor], proposals: List[Instances]):\n        \"\"\"\n        Forward logic of the box prediction branch. If `self.train_on_pred_boxes is True`,\n            the function puts predicted boxes in the `proposal_boxes` field of `proposals` argument.\n\n        Args:\n            features (dict[str, Tensor]): mapping from feature map names to tensor.\n                Same as in :meth:`ROIHeads.forward`.\n            proposals (list[Instances]): the per-image object proposals with\n                their matching ground truth.\n                Each has fields \"proposal_boxes\", and \"objectness_logits\",\n                \"gt_classes\", \"gt_boxes\".\n\n        Returns:\n            In training, a dict of losses.\n            In inference, a list of `Instances`, the predicted instances.\n        \"\"\"\n        features = [features[f] for f in self.box_in_features]\n        box_features = self.box_pooler(features, [x.proposal_boxes for x in proposals])\n        box_features = self.box_head(box_features)\n        predictions = self.box_predictor(box_features)\n        del box_features\n\n        if self.training:\n            losses = self.box_predictor.losses(predictions, proposals)\n            # proposals is modified in-place below, so losses must be computed first.\n            if self.train_on_pred_boxes:\n                with torch.no_grad():\n                    pred_boxes = self.box_predictor.predict_boxes_for_gt_classes(\n                        predictions, proposals\n                    )\n                    for proposals_per_image, pred_boxes_per_image in zip(proposals, pred_boxes):\n                        proposals_per_image.proposal_boxes = Boxes(pred_boxes_per_image)\n            return losses\n        else:\n            pred_instances, _ = self.box_predictor.inference(predictions, proposals)\n            return pred_instances\n\n    def _forward_mask(self, features: Dict[str, torch.Tensor], instances: List[Instances]):\n        \"\"\"\n        Forward logic of the mask prediction branch.\n\n        Args:\n            features (dict[str, Tensor]): mapping from feature map names to tensor.\n                Same as in :meth:`ROIHeads.forward`.\n            instances (list[Instances]): the per-image instances to train/predict masks.\n                In training, they can be the proposals.\n                In inference, they can be the boxes predicted by R-CNN box head.\n\n        Returns:\n            In training, a dict of losses.\n            In inference, update `instances` with new fields \"pred_masks\" and return it.\n        \"\"\"\n        if not self.mask_on:\n            return {} if self.training else instances\n\n        if self.training:\n            # head is only trained on positive proposals.\n            instances, _ = select_foreground_proposals(instances, self.num_classes)\n\n        if self.mask_pooler is not None:\n            features = [features[f] for f in self.mask_in_features]\n            boxes = [x.proposal_boxes if self.training else x.pred_boxes for x in instances]\n            features = self.mask_pooler(features, boxes)\n        else:\n            features = {f: features[f] for f in self.mask_in_features}\n        return self.mask_head(features, instances)\n\n    def _forward_keypoint(self, features: Dict[str, torch.Tensor], instances: List[Instances]):\n        \"\"\"\n        Forward logic of the keypoint prediction branch.\n\n        Args:\n            features (dict[str, Tensor]): mapping from feature map names to tensor.\n                Same as in :meth:`ROIHeads.forward`.\n            instances (list[Instances]): the per-image instances to train/predict keypoints.\n                In training, they can be the proposals.\n                In inference, they can be the boxes predicted by R-CNN box head.\n\n        Returns:\n            In training, a dict of losses.\n            In inference, update `instances` with new fields \"pred_keypoints\" and return it.\n        \"\"\"\n        if not self.keypoint_on:\n            return {} if self.training else instances\n\n        if self.training:\n            # head is only trained on positive proposals with >=1 visible keypoints.\n            instances, _ = select_foreground_proposals(instances, self.num_classes)\n            instances = select_proposals_with_visible_keypoints(instances)\n\n        if self.keypoint_pooler is not None:\n            features = [features[f] for f in self.keypoint_in_features]\n            boxes = [x.proposal_boxes if self.training else x.pred_boxes for x in instances]\n            features = self.keypoint_pooler(features, boxes)\n        else:\n            features = {f: features[f] for f in self.keypoint_in_features}\n        return self.keypoint_head(features, instances)\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/roi_heads/rotated_fast_rcnn.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport logging\nimport numpy as np\nimport torch\n\nfrom detectron2.config import configurable\nfrom detectron2.layers import ShapeSpec, batched_nms_rotated\nfrom detectron2.structures import Instances, RotatedBoxes, pairwise_iou_rotated\nfrom detectron2.utils.events import get_event_storage\n\nfrom ..box_regression import Box2BoxTransformRotated\nfrom ..poolers import ROIPooler\nfrom ..proposal_generator.proposal_utils import add_ground_truth_to_proposals\nfrom .box_head import build_box_head\nfrom .fast_rcnn import FastRCNNOutputLayers\nfrom .roi_heads import ROI_HEADS_REGISTRY, StandardROIHeads\n\nlogger = logging.getLogger(__name__)\n\n\"\"\"\nShape shorthand in this module:\n\n    N: number of images in the minibatch\n    R: number of ROIs, combined over all images, in the minibatch\n    Ri: number of ROIs in image i\n    K: number of foreground classes. E.g.,there are 80 foreground classes in COCO.\n\nNaming convention:\n\n    deltas: refers to the 5-d (dx, dy, dw, dh, da) deltas that parameterize the box2box\n    transform (see :class:`box_regression.Box2BoxTransformRotated`).\n\n    pred_class_logits: predicted class scores in [-inf, +inf]; use\n        softmax(pred_class_logits) to estimate P(class).\n\n    gt_classes: ground-truth classification labels in [0, K], where [0, K) represent\n        foreground object classes and K represents the background class.\n\n    pred_proposal_deltas: predicted rotated box2box transform deltas for transforming proposals\n        to detection box predictions.\n\n    gt_proposal_deltas: ground-truth rotated box2box transform deltas\n\"\"\"\n\n\ndef fast_rcnn_inference_rotated(\n    boxes, scores, image_shapes, score_thresh, nms_thresh, topk_per_image\n):\n    \"\"\"\n    Call `fast_rcnn_inference_single_image_rotated` for all images.\n\n    Args:\n        boxes (list[Tensor]): A list of Tensors of predicted class-specific or class-agnostic\n            boxes for each image. Element i has shape (Ri, K * 5) if doing\n            class-specific regression, or (Ri, 5) if doing class-agnostic\n            regression, where Ri is the number of predicted objects for image i.\n            This is compatible with the output of :meth:`FastRCNNOutputLayers.predict_boxes`.\n        scores (list[Tensor]): A list of Tensors of predicted class scores for each image.\n            Element i has shape (Ri, K + 1), where Ri is the number of predicted objects\n            for image i. Compatible with the output of :meth:`FastRCNNOutputLayers.predict_probs`.\n        image_shapes (list[tuple]): A list of (width, height) tuples for each image in the batch.\n        score_thresh (float): Only return detections with a confidence score exceeding this\n            threshold.\n        nms_thresh (float):  The threshold to use for box non-maximum suppression. Value in [0, 1].\n        topk_per_image (int): The number of top scoring detections to return. Set < 0 to return\n            all detections.\n\n    Returns:\n        instances: (list[Instances]): A list of N instances, one for each image in the batch,\n            that stores the topk most confidence detections.\n        kept_indices: (list[Tensor]): A list of 1D tensor of length of N, each element indicates\n            the corresponding boxes/scores index in [0, Ri) from the input, for image i.\n    \"\"\"\n    result_per_image = [\n        fast_rcnn_inference_single_image_rotated(\n            boxes_per_image, scores_per_image, image_shape, score_thresh, nms_thresh, topk_per_image\n        )\n        for scores_per_image, boxes_per_image, image_shape in zip(scores, boxes, image_shapes)\n    ]\n    return [x[0] for x in result_per_image], [x[1] for x in result_per_image]\n\n\ndef fast_rcnn_inference_single_image_rotated(\n    boxes, scores, image_shape, score_thresh, nms_thresh, topk_per_image\n):\n    \"\"\"\n    Single-image inference. Return rotated bounding-box detection results by thresholding\n    on scores and applying rotated non-maximum suppression (Rotated NMS).\n\n    Args:\n        Same as `fast_rcnn_inference_rotated`, but with rotated boxes, scores, and image shapes\n        per image.\n\n    Returns:\n        Same as `fast_rcnn_inference_rotated`, but for only one image.\n    \"\"\"\n    valid_mask = torch.isfinite(boxes).all(dim=1) & torch.isfinite(scores).all(dim=1)\n    if not valid_mask.all():\n        boxes = boxes[valid_mask]\n        scores = scores[valid_mask]\n\n    B = 5  # box dimension\n    scores = scores[:, :-1]\n    num_bbox_reg_classes = boxes.shape[1] // B\n    # Convert to Boxes to use the `clip` function ...\n    boxes = RotatedBoxes(boxes.reshape(-1, B))\n    boxes.clip(image_shape)\n    boxes = boxes.tensor.view(-1, num_bbox_reg_classes, B)  # R x C x B\n    # Filter results based on detection scores\n    filter_mask = scores > score_thresh  # R x K\n    # R' x 2. First column contains indices of the R predictions;\n    # Second column contains indices of classes.\n    filter_inds = filter_mask.nonzero()\n    if num_bbox_reg_classes == 1:\n        boxes = boxes[filter_inds[:, 0], 0]\n    else:\n        boxes = boxes[filter_mask]\n    scores = scores[filter_mask]\n\n    # Apply per-class Rotated NMS\n    keep = batched_nms_rotated(boxes, scores, filter_inds[:, 1], nms_thresh)\n    if topk_per_image >= 0:\n        keep = keep[:topk_per_image]\n    boxes, scores, filter_inds = boxes[keep], scores[keep], filter_inds[keep]\n\n    result = Instances(image_shape)\n    result.pred_boxes = RotatedBoxes(boxes)\n    result.scores = scores\n    result.pred_classes = filter_inds[:, 1]\n\n    return result, filter_inds[:, 0]\n\n\nclass RotatedFastRCNNOutputLayers(FastRCNNOutputLayers):\n    \"\"\"\n    Two linear layers for predicting Rotated Fast R-CNN outputs.\n    \"\"\"\n\n    @classmethod\n    def from_config(cls, cfg, input_shape):\n        args = super().from_config(cfg, input_shape)\n        args[\"box2box_transform\"] = Box2BoxTransformRotated(\n            weights=cfg.MODEL.ROI_BOX_HEAD.BBOX_REG_WEIGHTS\n        )\n        return args\n\n    def inference(self, predictions, proposals):\n        \"\"\"\n        Returns:\n            list[Instances]: same as `fast_rcnn_inference_rotated`.\n            list[Tensor]: same as `fast_rcnn_inference_rotated`.\n        \"\"\"\n        boxes = self.predict_boxes(predictions, proposals)\n        scores = self.predict_probs(predictions, proposals)\n        image_shapes = [x.image_size for x in proposals]\n\n        return fast_rcnn_inference_rotated(\n            boxes,\n            scores,\n            image_shapes,\n            self.test_score_thresh,\n            self.test_nms_thresh,\n            self.test_topk_per_image,\n        )\n\n\n@ROI_HEADS_REGISTRY.register()\nclass RROIHeads(StandardROIHeads):\n    \"\"\"\n    This class is used by Rotated Fast R-CNN to detect rotated boxes.\n    For now, it only supports box predictions but not mask or keypoints.\n    \"\"\"\n\n    @configurable\n    def __init__(self, **kwargs):\n        \"\"\"\n        NOTE: this interface is experimental.\n        \"\"\"\n        super().__init__(**kwargs)\n        assert (\n            not self.mask_on and not self.keypoint_on\n        ), \"Mask/Keypoints not supported in Rotated ROIHeads.\"\n        assert not self.train_on_pred_boxes, \"train_on_pred_boxes not implemented for RROIHeads!\"\n\n    @classmethod\n    def _init_box_head(cls, cfg, input_shape):\n        # fmt: off\n        in_features       = cfg.MODEL.ROI_HEADS.IN_FEATURES\n        pooler_resolution = cfg.MODEL.ROI_BOX_HEAD.POOLER_RESOLUTION\n        pooler_scales     = tuple(1.0 / input_shape[k].stride for k in in_features)\n        sampling_ratio    = cfg.MODEL.ROI_BOX_HEAD.POOLER_SAMPLING_RATIO\n        pooler_type       = cfg.MODEL.ROI_BOX_HEAD.POOLER_TYPE\n        # fmt: on\n        assert pooler_type in [\"ROIAlignRotated\"], pooler_type\n        # assume all channel counts are equal\n        in_channels = [input_shape[f].channels for f in in_features][0]\n\n        box_pooler = ROIPooler(\n            output_size=pooler_resolution,\n            scales=pooler_scales,\n            sampling_ratio=sampling_ratio,\n            pooler_type=pooler_type,\n        )\n        box_head = build_box_head(\n            cfg, ShapeSpec(channels=in_channels, height=pooler_resolution, width=pooler_resolution)\n        )\n        # This line is the only difference v.s. StandardROIHeads\n        box_predictor = RotatedFastRCNNOutputLayers(cfg, box_head.output_shape)\n        return {\n            \"box_in_features\": in_features,\n            \"box_pooler\": box_pooler,\n            \"box_head\": box_head,\n            \"box_predictor\": box_predictor,\n        }\n\n    @torch.no_grad()\n    def label_and_sample_proposals(self, proposals, targets):\n        \"\"\"\n        Prepare some proposals to be used to train the RROI heads.\n        It performs box matching between `proposals` and `targets`, and assigns\n        training labels to the proposals.\n        It returns `self.batch_size_per_image` random samples from proposals and groundtruth boxes,\n        with a fraction of positives that is no larger than `self.positive_sample_fraction.\n\n        Args:\n            See :meth:`StandardROIHeads.forward`\n\n        Returns:\n            list[Instances]: length `N` list of `Instances`s containing the proposals\n                sampled for training. Each `Instances` has the following fields:\n                - proposal_boxes: the rotated proposal boxes\n                - gt_boxes: the ground-truth rotated boxes that the proposal is assigned to\n                  (this is only meaningful if the proposal has a label > 0; if label = 0\n                   then the ground-truth box is random)\n                - gt_classes: the ground-truth classification lable for each proposal\n        \"\"\"\n        if self.proposal_append_gt:\n            proposals = add_ground_truth_to_proposals(targets, proposals)\n\n        proposals_with_gt = []\n\n        num_fg_samples = []\n        num_bg_samples = []\n        for proposals_per_image, targets_per_image in zip(proposals, targets):\n            has_gt = len(targets_per_image) > 0\n            match_quality_matrix = pairwise_iou_rotated(\n                targets_per_image.gt_boxes, proposals_per_image.proposal_boxes\n            )\n            matched_idxs, matched_labels = self.proposal_matcher(match_quality_matrix)\n            sampled_idxs, gt_classes = self._sample_proposals(\n                matched_idxs, matched_labels, targets_per_image.gt_classes\n            )\n\n            proposals_per_image = proposals_per_image[sampled_idxs]\n            proposals_per_image.gt_classes = gt_classes\n\n            if has_gt:\n                sampled_targets = matched_idxs[sampled_idxs]\n                proposals_per_image.gt_boxes = targets_per_image.gt_boxes[sampled_targets]\n\n            num_bg_samples.append((gt_classes == self.num_classes).sum().item())\n            num_fg_samples.append(gt_classes.numel() - num_bg_samples[-1])\n            proposals_with_gt.append(proposals_per_image)\n\n        # Log the number of fg/bg samples that are selected for training ROI heads\n        storage = get_event_storage()\n        storage.put_scalar(\"roi_head/num_fg_samples\", np.mean(num_fg_samples))\n        storage.put_scalar(\"roi_head/num_bg_samples\", np.mean(num_bg_samples))\n\n        return proposals_with_gt\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/sampling.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport torch\n\nfrom detectron2.layers import nonzero_tuple\n\n__all__ = [\"subsample_labels\"]\n\n\ndef subsample_labels(\n    labels: torch.Tensor, num_samples: int, positive_fraction: float, bg_label: int\n):\n    \"\"\"\n    Return `num_samples` (or fewer, if not enough found)\n    random samples from `labels` which is a mixture of positives & negatives.\n    It will try to return as many positives as possible without\n    exceeding `positive_fraction * num_samples`, and then try to\n    fill the remaining slots with negatives.\n\n    Args:\n        labels (Tensor): (N, ) label vector with values:\n            * -1: ignore\n            * bg_label: background (\"negative\") class\n            * otherwise: one or more foreground (\"positive\") classes\n        num_samples (int): The total number of labels with value >= 0 to return.\n            Values that are not sampled will be filled with -1 (ignore).\n        positive_fraction (float): The number of subsampled labels with values > 0\n            is `min(num_positives, int(positive_fraction * num_samples))`. The number\n            of negatives sampled is `min(num_negatives, num_samples - num_positives_sampled)`.\n            In order words, if there are not enough positives, the sample is filled with\n            negatives. If there are also not enough negatives, then as many elements are\n            sampled as is possible.\n        bg_label (int): label index of background (\"negative\") class.\n\n    Returns:\n        pos_idx, neg_idx (Tensor):\n            1D vector of indices. The total length of both is `num_samples` or fewer.\n    \"\"\"\n    positive = nonzero_tuple((labels != -1) & (labels != bg_label))[0]\n    negative = nonzero_tuple(labels == bg_label)[0]\n\n    num_pos = int(num_samples * positive_fraction)\n    # protect against not enough positive examples\n    num_pos = min(positive.numel(), num_pos)\n    num_neg = num_samples - num_pos\n    # protect against not enough negative examples\n    num_neg = min(negative.numel(), num_neg)\n\n    # randomly select positive and negative examples\n    perm1 = torch.randperm(positive.numel(), device=positive.device)[:num_pos]\n    perm2 = torch.randperm(negative.numel(), device=negative.device)[:num_neg]\n\n    pos_idx = positive[perm1]\n    neg_idx = negative[perm2]\n    return pos_idx, neg_idx\n"
  },
  {
    "path": "VPS_Module/detectron2/modeling/test_time_augmentation.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport copy\nimport numpy as np\nfrom contextlib import contextmanager\nfrom itertools import count\nfrom typing import List\nimport torch\nfrom fvcore.transforms import HFlipTransform, NoOpTransform\nfrom torch import nn\nfrom torch.nn.parallel import DistributedDataParallel\n\nfrom detectron2.config import configurable\nfrom detectron2.data.detection_utils import read_image\nfrom detectron2.data.transforms import (\n    RandomFlip,\n    ResizeShortestEdge,\n    ResizeTransform,\n    apply_augmentations,\n)\nfrom detectron2.structures import Boxes, Instances\n\nfrom .meta_arch import GeneralizedRCNN\nfrom .postprocessing import detector_postprocess\nfrom .roi_heads.fast_rcnn import fast_rcnn_inference_single_image\n\n__all__ = [\"DatasetMapperTTA\", \"GeneralizedRCNNWithTTA\"]\n\n\nclass DatasetMapperTTA:\n    \"\"\"\n    Implement test-time augmentation for detection data.\n    It is a callable which takes a dataset dict from a detection dataset,\n    and returns a list of dataset dicts where the images\n    are augmented from the input image by the transformations defined in the config.\n    This is used for test-time augmentation.\n    \"\"\"\n\n    @configurable\n    def __init__(self, min_sizes: List[int], max_size: int, flip: bool):\n        \"\"\"\n        Args:\n            min_sizes: list of short-edge size to resize the image to\n            max_size: maximum height or width of resized images\n            flip: whether to apply flipping augmentation\n        \"\"\"\n        self.min_sizes = min_sizes\n        self.max_size = max_size\n        self.flip = flip\n\n    @classmethod\n    def from_config(cls, cfg):\n        return {\n            \"min_sizes\": cfg.TEST.AUG.MIN_SIZES,\n            \"max_size\": cfg.TEST.AUG.MAX_SIZE,\n            \"flip\": cfg.TEST.AUG.FLIP,\n        }\n\n    def __call__(self, dataset_dict):\n        \"\"\"\n        Args:\n            dict: a dict in standard model input format. See tutorials for details.\n\n        Returns:\n            list[dict]:\n                a list of dicts, which contain augmented version of the input image.\n                The total number of dicts is ``len(min_sizes) * (2 if flip else 1)``.\n                Each dict has field \"transforms\" which is a TransformList,\n                containing the transforms that are used to generate this image.\n        \"\"\"\n        numpy_image = dataset_dict[\"image\"].permute(1, 2, 0).numpy()\n        shape = numpy_image.shape\n        orig_shape = (dataset_dict[\"height\"], dataset_dict[\"width\"])\n        if shape[:2] != orig_shape:\n            # It transforms the \"original\" image in the dataset to the input image\n            pre_tfm = ResizeTransform(orig_shape[0], orig_shape[1], shape[0], shape[1])\n        else:\n            pre_tfm = NoOpTransform()\n\n        # Create all combinations of augmentations to use\n        aug_candidates = []  # each element is a list[Augmentation]\n        for min_size in self.min_sizes:\n            resize = ResizeShortestEdge(min_size, self.max_size)\n            aug_candidates.append([resize])  # resize only\n            if self.flip:\n                flip = RandomFlip(prob=1.0)\n                aug_candidates.append([resize, flip])  # resize + flip\n\n        # Apply all the augmentations\n        ret = []\n        for aug in aug_candidates:\n            new_image, tfms = apply_augmentations(aug, np.copy(numpy_image))\n            torch_image = torch.from_numpy(np.ascontiguousarray(new_image.transpose(2, 0, 1)))\n\n            dic = copy.deepcopy(dataset_dict)\n            dic[\"transforms\"] = pre_tfm + tfms\n            dic[\"image\"] = torch_image\n            ret.append(dic)\n        return ret\n\n\nclass GeneralizedRCNNWithTTA(nn.Module):\n    \"\"\"\n    A GeneralizedRCNN with test-time augmentation enabled.\n    Its :meth:`__call__` method has the same interface as :meth:`GeneralizedRCNN.forward`.\n    \"\"\"\n\n    def __init__(self, cfg, model, tta_mapper=None, batch_size=3):\n        \"\"\"\n        Args:\n            cfg (CfgNode):\n            model (GeneralizedRCNN): a GeneralizedRCNN to apply TTA on.\n            tta_mapper (callable): takes a dataset dict and returns a list of\n                augmented versions of the dataset dict. Defaults to\n                `DatasetMapperTTA(cfg)`.\n            batch_size (int): batch the augmented images into this batch size for inference.\n        \"\"\"\n        super().__init__()\n        if isinstance(model, DistributedDataParallel):\n            model = model.module\n        assert isinstance(\n            model, GeneralizedRCNN\n        ), \"TTA is only supported on GeneralizedRCNN. Got a model of type {}\".format(type(model))\n        self.cfg = cfg.clone()\n        assert not self.cfg.MODEL.KEYPOINT_ON, \"TTA for keypoint is not supported yet\"\n        assert (\n            not self.cfg.MODEL.LOAD_PROPOSALS\n        ), \"TTA for pre-computed proposals is not supported yet\"\n\n        self.model = model\n\n        if tta_mapper is None:\n            tta_mapper = DatasetMapperTTA(cfg)\n        self.tta_mapper = tta_mapper\n        self.batch_size = batch_size\n\n    @contextmanager\n    def _turn_off_roi_heads(self, attrs):\n        \"\"\"\n        Open a context where some heads in `model.roi_heads` are temporarily turned off.\n        Args:\n            attr (list[str]): the attribute in `model.roi_heads` which can be used\n                to turn off a specific head, e.g., \"mask_on\", \"keypoint_on\".\n        \"\"\"\n        roi_heads = self.model.roi_heads\n        old = {}\n        for attr in attrs:\n            try:\n                old[attr] = getattr(roi_heads, attr)\n            except AttributeError:\n                # The head may not be implemented in certain ROIHeads\n                pass\n\n        if len(old.keys()) == 0:\n            yield\n        else:\n            for attr in old.keys():\n                setattr(roi_heads, attr, False)\n            yield\n            for attr in old.keys():\n                setattr(roi_heads, attr, old[attr])\n\n    def _batch_inference(self, batched_inputs, detected_instances=None):\n        \"\"\"\n        Execute inference on a list of inputs,\n        using batch size = self.batch_size, instead of the length of the list.\n\n        Inputs & outputs have the same format as :meth:`GeneralizedRCNN.inference`\n        \"\"\"\n        if detected_instances is None:\n            detected_instances = [None] * len(batched_inputs)\n\n        outputs = []\n        inputs, instances = [], []\n        for idx, input, instance in zip(count(), batched_inputs, detected_instances):\n            inputs.append(input)\n            instances.append(instance)\n            if len(inputs) == self.batch_size or idx == len(batched_inputs) - 1:\n                outputs.extend(\n                    self.model.inference(\n                        inputs,\n                        instances if instances[0] is not None else None,\n                        do_postprocess=False,\n                    )\n                )\n                inputs, instances = [], []\n        return outputs\n\n    def __call__(self, batched_inputs):\n        \"\"\"\n        Same input/output format as :meth:`GeneralizedRCNN.forward`\n        \"\"\"\n\n        def _maybe_read_image(dataset_dict):\n            ret = copy.copy(dataset_dict)\n            if \"image\" not in ret:\n                image = read_image(ret.pop(\"file_name\"), self.model.input_format)\n                image = torch.from_numpy(np.ascontiguousarray(image.transpose(2, 0, 1)))  # CHW\n                ret[\"image\"] = image\n            if \"height\" not in ret and \"width\" not in ret:\n                ret[\"height\"] = image.shape[1]\n                ret[\"width\"] = image.shape[2]\n            return ret\n\n        return [self._inference_one_image(_maybe_read_image(x)) for x in batched_inputs]\n\n    def _inference_one_image(self, input):\n        \"\"\"\n        Args:\n            input (dict): one dataset dict with \"image\" field being a CHW tensor\n\n        Returns:\n            dict: one output dict\n        \"\"\"\n        orig_shape = (input[\"height\"], input[\"width\"])\n        augmented_inputs, tfms = self._get_augmented_inputs(input)\n        # Detect boxes from all augmented versions\n        with self._turn_off_roi_heads([\"mask_on\", \"keypoint_on\"]):\n            # temporarily disable roi heads\n            all_boxes, all_scores, all_classes = self._get_augmented_boxes(augmented_inputs, tfms)\n        # merge all detected boxes to obtain final predictions for boxes\n        merged_instances = self._merge_detections(all_boxes, all_scores, all_classes, orig_shape)\n\n        if self.cfg.MODEL.MASK_ON:\n            # Use the detected boxes to obtain masks\n            augmented_instances = self._rescale_detected_boxes(\n                augmented_inputs, merged_instances, tfms\n            )\n            # run forward on the detected boxes\n            outputs = self._batch_inference(augmented_inputs, augmented_instances)\n            # Delete now useless variables to avoid being out of memory\n            del augmented_inputs, augmented_instances\n            # average the predictions\n            merged_instances.pred_masks = self._reduce_pred_masks(outputs, tfms)\n            merged_instances = detector_postprocess(merged_instances, *orig_shape)\n            return {\"instances\": merged_instances}\n        else:\n            return {\"instances\": merged_instances}\n\n    def _get_augmented_inputs(self, input):\n        augmented_inputs = self.tta_mapper(input)\n        tfms = [x.pop(\"transforms\") for x in augmented_inputs]\n        return augmented_inputs, tfms\n\n    def _get_augmented_boxes(self, augmented_inputs, tfms):\n        # 1: forward with all augmented images\n        outputs = self._batch_inference(augmented_inputs)\n        # 2: union the results\n        all_boxes = []\n        all_scores = []\n        all_classes = []\n        for output, tfm in zip(outputs, tfms):\n            # Need to inverse the transforms on boxes, to obtain results on original image\n            pred_boxes = output.pred_boxes.tensor\n            original_pred_boxes = tfm.inverse().apply_box(pred_boxes.cpu().numpy())\n            all_boxes.append(torch.from_numpy(original_pred_boxes).to(pred_boxes.device))\n\n            all_scores.extend(output.scores)\n            all_classes.extend(output.pred_classes)\n        all_boxes = torch.cat(all_boxes, dim=0)\n        return all_boxes, all_scores, all_classes\n\n    def _merge_detections(self, all_boxes, all_scores, all_classes, shape_hw):\n        # select from the union of all results\n        num_boxes = len(all_boxes)\n        num_classes = self.cfg.MODEL.ROI_HEADS.NUM_CLASSES\n        # +1 because fast_rcnn_inference expects background scores as well\n        all_scores_2d = torch.zeros(num_boxes, num_classes + 1, device=all_boxes.device)\n        for idx, cls, score in zip(count(), all_classes, all_scores):\n            all_scores_2d[idx, cls] = score\n\n        merged_instances, _ = fast_rcnn_inference_single_image(\n            all_boxes,\n            all_scores_2d,\n            shape_hw,\n            1e-8,\n            self.cfg.MODEL.ROI_HEADS.NMS_THRESH_TEST,\n            self.cfg.TEST.DETECTIONS_PER_IMAGE,\n        )\n\n        return merged_instances\n\n    def _rescale_detected_boxes(self, augmented_inputs, merged_instances, tfms):\n        augmented_instances = []\n        for input, tfm in zip(augmented_inputs, tfms):\n            # Transform the target box to the augmented image's coordinate space\n            pred_boxes = merged_instances.pred_boxes.tensor.cpu().numpy()\n            pred_boxes = torch.from_numpy(tfm.apply_box(pred_boxes))\n\n            aug_instances = Instances(\n                image_size=input[\"image\"].shape[1:3],\n                pred_boxes=Boxes(pred_boxes),\n                pred_classes=merged_instances.pred_classes,\n                scores=merged_instances.scores,\n            )\n            augmented_instances.append(aug_instances)\n        return augmented_instances\n\n    def _reduce_pred_masks(self, outputs, tfms):\n        # Should apply inverse transforms on masks.\n        # We assume only resize & flip are used. pred_masks is a scale-invariant\n        # representation, so we handle flip specially\n        for output, tfm in zip(outputs, tfms):\n            if any(isinstance(t, HFlipTransform) for t in tfm.transforms):\n                output.pred_masks = output.pred_masks.flip(dims=[3])\n        all_pred_masks = torch.stack([o.pred_masks for o in outputs], dim=0)\n        avg_pred_masks = torch.mean(all_pred_masks, dim=0)\n        return avg_pred_masks\n"
  },
  {
    "path": "VPS_Module/detectron2/projects/README.md",
    "content": "\nProjects live in the [`projects` directory](../../projects) under the root of this repository, but not here.\n"
  },
  {
    "path": "VPS_Module/detectron2/projects/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport importlib\nfrom pathlib import Path\n\n_PROJECTS = {\n    \"point_rend\": \"PointRend\",\n    \"deeplab\": \"DeepLab\",\n    \"panoptic_deeplab\": \"Panoptic-DeepLab\",\n}\n_PROJECT_ROOT = Path(__file__).resolve().parent.parent.parent / \"projects\"\n\nif _PROJECT_ROOT.is_dir():\n    # This is true only for in-place installation (pip install -e, setup.py develop),\n    # where setup(package_dir=) does not work: https://github.com/pypa/setuptools/issues/230\n\n    class _D2ProjectsFinder(importlib.abc.MetaPathFinder):\n        def find_spec(self, name, path, target=None):\n            if not name.startswith(\"detectron2.projects.\"):\n                return\n            project_name = name.split(\".\")[-1]\n            project_dir = _PROJECTS.get(project_name)\n            if not project_dir:\n                return\n            target_file = _PROJECT_ROOT / f\"{project_dir}/{project_name}/__init__.py\"\n            if not target_file.is_file():\n                return\n            return importlib.util.spec_from_file_location(name, target_file)\n\n    import sys\n\n    sys.meta_path.append(_D2ProjectsFinder())\n"
  },
  {
    "path": "VPS_Module/detectron2/solver/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom .build import build_lr_scheduler, build_optimizer, get_default_optimizer_params\nfrom .lr_scheduler import WarmupCosineLR, WarmupMultiStepLR, LRMultiplier, WarmupParamScheduler\n\n__all__ = [k for k in globals().keys() if not k.startswith(\"_\")]\n"
  },
  {
    "path": "VPS_Module/detectron2/solver/build.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport copy\nimport itertools\nimport logging\nfrom collections import defaultdict\nfrom enum import Enum\nfrom typing import Any, Callable, Dict, Iterable, List, Optional, Set, Type, Union\nimport torch\nfrom fvcore.common.param_scheduler import CosineParamScheduler, MultiStepParamScheduler\n\nfrom detectron2.config import CfgNode\n\nfrom .lr_scheduler import LRMultiplier, WarmupParamScheduler\n\n_GradientClipperInput = Union[torch.Tensor, Iterable[torch.Tensor]]\n_GradientClipper = Callable[[_GradientClipperInput], None]\n\n\nclass GradientClipType(Enum):\n    VALUE = \"value\"\n    NORM = \"norm\"\n\n\ndef _create_gradient_clipper(cfg: CfgNode) -> _GradientClipper:\n    \"\"\"\n    Creates gradient clipping closure to clip by value or by norm,\n    according to the provided config.\n    \"\"\"\n    cfg = copy.deepcopy(cfg)\n\n    def clip_grad_norm(p: _GradientClipperInput):\n        torch.nn.utils.clip_grad_norm_(p, cfg.CLIP_VALUE, cfg.NORM_TYPE)\n\n    def clip_grad_value(p: _GradientClipperInput):\n        torch.nn.utils.clip_grad_value_(p, cfg.CLIP_VALUE)\n\n    _GRADIENT_CLIP_TYPE_TO_CLIPPER = {\n        GradientClipType.VALUE: clip_grad_value,\n        GradientClipType.NORM: clip_grad_norm,\n    }\n    return _GRADIENT_CLIP_TYPE_TO_CLIPPER[GradientClipType(cfg.CLIP_TYPE)]\n\n\ndef _generate_optimizer_class_with_gradient_clipping(\n    optimizer: Type[torch.optim.Optimizer],\n    *,\n    per_param_clipper: Optional[_GradientClipper] = None,\n    global_clipper: Optional[_GradientClipper] = None,\n) -> Type[torch.optim.Optimizer]:\n    \"\"\"\n    Dynamically creates a new type that inherits the type of a given instance\n    and overrides the `step` method to add gradient clipping\n    \"\"\"\n    assert (\n        per_param_clipper is None or global_clipper is None\n    ), \"Not allowed to use both per-parameter clipping and global clipping\"\n\n    def optimizer_wgc_step(self, closure=None):\n        if per_param_clipper is not None:\n            for group in self.param_groups:\n                for p in group[\"params\"]:\n                    per_param_clipper(p)\n        else:\n            # global clipper for future use with detr\n            # (https://github.com/facebookresearch/detr/pull/287)\n            all_params = itertools.chain(*[g[\"params\"] for g in self.param_groups])\n            global_clipper(all_params)\n        super(type(self), self).step(closure)\n\n    OptimizerWithGradientClip = type(\n        optimizer.__name__ + \"WithGradientClip\",\n        (optimizer,),\n        {\"step\": optimizer_wgc_step},\n    )\n    return OptimizerWithGradientClip\n\n\ndef maybe_add_gradient_clipping(\n    cfg: CfgNode, optimizer: Type[torch.optim.Optimizer]\n) -> Type[torch.optim.Optimizer]:\n    \"\"\"\n    If gradient clipping is enabled through config options, wraps the existing\n    optimizer type to become a new dynamically created class OptimizerWithGradientClip\n    that inherits the given optimizer and overrides the `step` method to\n    include gradient clipping.\n\n    Args:\n        cfg: CfgNode, configuration options\n        optimizer: type. A subclass of torch.optim.Optimizer\n\n    Return:\n        type: either the input `optimizer` (if gradient clipping is disabled), or\n            a subclass of it with gradient clipping included in the `step` method.\n    \"\"\"\n    if not cfg.SOLVER.CLIP_GRADIENTS.ENABLED:\n        return optimizer\n    if isinstance(optimizer, torch.optim.Optimizer):\n        optimizer_type = type(optimizer)\n    else:\n        assert issubclass(optimizer, torch.optim.Optimizer), optimizer\n        optimizer_type = optimizer\n\n    grad_clipper = _create_gradient_clipper(cfg.SOLVER.CLIP_GRADIENTS)\n    OptimizerWithGradientClip = _generate_optimizer_class_with_gradient_clipping(\n        optimizer_type, per_param_clipper=grad_clipper\n    )\n    if isinstance(optimizer, torch.optim.Optimizer):\n        optimizer.__class__ = OptimizerWithGradientClip  # a bit hacky, not recommended\n        return optimizer\n    else:\n        return OptimizerWithGradientClip\n\n\ndef build_optimizer(cfg: CfgNode, model: torch.nn.Module) -> torch.optim.Optimizer:\n    \"\"\"\n    Build an optimizer from config.\n    \"\"\"\n    params = get_default_optimizer_params(\n        model,\n        base_lr=cfg.SOLVER.BASE_LR,\n        weight_decay_norm=cfg.SOLVER.WEIGHT_DECAY_NORM,\n        bias_lr_factor=cfg.SOLVER.BIAS_LR_FACTOR,\n        weight_decay_bias=cfg.SOLVER.WEIGHT_DECAY_BIAS,\n    )\n    return maybe_add_gradient_clipping(cfg, torch.optim.SGD)(\n        params,\n        lr=cfg.SOLVER.BASE_LR,\n        momentum=cfg.SOLVER.MOMENTUM,\n        nesterov=cfg.SOLVER.NESTEROV,\n        weight_decay=cfg.SOLVER.WEIGHT_DECAY,\n    )\n\n\ndef get_default_optimizer_params(\n    model: torch.nn.Module,\n    base_lr: Optional[float] = None,\n    weight_decay: Optional[float] = None,\n    weight_decay_norm: Optional[float] = None,\n    bias_lr_factor: Optional[float] = 1.0,\n    weight_decay_bias: Optional[float] = None,\n    overrides: Optional[Dict[str, Dict[str, float]]] = None,\n) -> List[Dict[str, Any]]:\n    \"\"\"\n    Get default param list for optimizer, with support for a few types of\n    overrides. If no overrides needed, this is equivalent to `model.parameters()`.\n\n    Args:\n        base_lr: lr for every group by default. Can be omitted to use the one in optimizer.\n        weight_decay: weight decay for every group by default. Can be omitted to use the one\n            in optimizer.\n        weight_decay_norm: override weight decay for params in normalization layers\n        bias_lr_factor: multiplier of lr for bias parameters.\n        weight_decay_bias: override weight decay for bias parameters\n        overrides: if not `None`, provides values for optimizer hyperparameters\n            (LR, weight decay) for module parameters with a given name; e.g.\n            ``{\"embedding\": {\"lr\": 0.01, \"weight_decay\": 0.1}}`` will set the LR and\n            weight decay values for all module parameters named `embedding`.\n\n    For common detection models, ``weight_decay_norm`` is the only option\n    needed to be set. ``bias_lr_factor,weight_decay_bias`` are legacy settings\n    from Detectron1 that are not found useful.\n\n    Example:\n    ::\n        torch.optim.SGD(get_default_optimizer_params(model, weight_decay_norm=0),\n                       lr=0.01, weight_decay=1e-4, momentum=0.9)\n    \"\"\"\n    if overrides is None:\n        overrides = {}\n    defaults = {}\n    if base_lr is not None:\n        defaults[\"lr\"] = base_lr\n    if weight_decay is not None:\n        defaults[\"weight_decay\"] = weight_decay\n    bias_overrides = {}\n    if bias_lr_factor is not None and bias_lr_factor != 1.0:\n        # NOTE: unlike Detectron v1, we now by default make bias hyperparameters\n        # exactly the same as regular weights.\n        if base_lr is None:\n            raise ValueError(\"bias_lr_factor requires base_lr\")\n        bias_overrides[\"lr\"] = base_lr * bias_lr_factor\n    if weight_decay_bias is not None:\n        bias_overrides[\"weight_decay\"] = weight_decay_bias\n    if len(bias_overrides):\n        if \"bias\" in overrides:\n            raise ValueError(\"Conflicting overrides for 'bias'\")\n        overrides[\"bias\"] = bias_overrides\n\n    norm_module_types = (\n        torch.nn.BatchNorm1d,\n        torch.nn.BatchNorm2d,\n        torch.nn.BatchNorm3d,\n        torch.nn.SyncBatchNorm,\n        # NaiveSyncBatchNorm inherits from BatchNorm2d\n        torch.nn.GroupNorm,\n        torch.nn.InstanceNorm1d,\n        torch.nn.InstanceNorm2d,\n        torch.nn.InstanceNorm3d,\n        torch.nn.LayerNorm,\n        torch.nn.LocalResponseNorm,\n    )\n    params: List[Dict[str, Any]] = []\n    memo: Set[torch.nn.parameter.Parameter] = set()\n    for module in model.modules():\n        for module_param_name, value in module.named_parameters(recurse=False):\n            if not value.requires_grad:\n                continue\n            # Avoid duplicating parameters\n            if value in memo:\n                continue\n            memo.add(value)\n\n            hyperparams = copy.copy(defaults)\n            if isinstance(module, norm_module_types) and weight_decay_norm is not None:\n                hyperparams[\"weight_decay\"] = weight_decay_norm\n            hyperparams.update(overrides.get(module_param_name, {}))\n            params.append({\"params\": [value], **hyperparams})\n    return reduce_param_groups(params)\n\n\ndef _expand_param_groups(params: List[Dict[str, Any]]) -> List[Dict[str, Any]]:\n    # Transform parameter groups into per-parameter structure.\n    # Later items in `params` can overwrite parameters set in previous items.\n    ret = defaultdict(dict)\n    for item in params:\n        assert \"params\" in item\n        cur_params = {x: y for x, y in item.items() if x != \"params\"}\n        for param in item[\"params\"]:\n            ret[param].update({\"params\": [param], **cur_params})\n    return list(ret.values())\n\n\ndef reduce_param_groups(params: List[Dict[str, Any]]) -> List[Dict[str, Any]]:\n    # Reorganize the parameter groups and merge duplicated groups.\n    # The number of parameter groups needs to be as small as possible in order\n    # to efficiently use the PyTorch multi-tensor optimizer. Therefore instead\n    # of using a parameter_group per single parameter, we reorganize the\n    # parameter groups and merge duplicated groups. This approach speeds\n    # up multi-tensor optimizer significantly.\n    params = _expand_param_groups(params)\n    groups = defaultdict(list)  # re-group all parameter groups by their hyperparams\n    for item in params:\n        cur_params = tuple((x, y) for x, y in item.items() if x != \"params\")\n        groups[cur_params].extend(item[\"params\"])\n    ret = []\n    for param_keys, param_values in groups.items():\n        cur = {kv[0]: kv[1] for kv in param_keys}\n        cur[\"params\"] = param_values\n        ret.append(cur)\n    return ret\n\n\ndef build_lr_scheduler(\n    cfg: CfgNode, optimizer: torch.optim.Optimizer\n) -> torch.optim.lr_scheduler._LRScheduler:\n    \"\"\"\n    Build a LR scheduler from config.\n    \"\"\"\n    name = cfg.SOLVER.LR_SCHEDULER_NAME\n\n    if name == \"WarmupMultiStepLR\":\n        steps = [x for x in cfg.SOLVER.STEPS if x <= cfg.SOLVER.MAX_ITER]\n        if len(steps) != len(cfg.SOLVER.STEPS):\n            logger = logging.getLogger(__name__)\n            logger.warning(\n                \"SOLVER.STEPS contains values larger than SOLVER.MAX_ITER. \"\n                \"These values will be ignored.\"\n            )\n        sched = MultiStepParamScheduler(\n            values=[cfg.SOLVER.GAMMA ** k for k in range(len(steps) + 1)],\n            milestones=steps,\n            num_updates=cfg.SOLVER.MAX_ITER,\n        )\n    elif name == \"WarmupCosineLR\":\n        sched = CosineParamScheduler(1, 0)\n    else:\n        raise ValueError(\"Unknown LR scheduler: {}\".format(name))\n\n    sched = WarmupParamScheduler(\n        sched,\n        cfg.SOLVER.WARMUP_FACTOR,\n        min(cfg.SOLVER.WARMUP_ITERS / cfg.SOLVER.MAX_ITER, 1.0),\n        cfg.SOLVER.WARMUP_METHOD,\n    )\n    return LRMultiplier(optimizer, multiplier=sched, max_iter=cfg.SOLVER.MAX_ITER)\n"
  },
  {
    "path": "VPS_Module/detectron2/solver/lr_scheduler.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport logging\nimport math\nfrom bisect import bisect_right\nfrom typing import List\nimport torch\nfrom fvcore.common.param_scheduler import (\n    CompositeParamScheduler,\n    ConstantParamScheduler,\n    LinearParamScheduler,\n    ParamScheduler,\n)\n\nlogger = logging.getLogger(__name__)\n\n\nclass WarmupParamScheduler(CompositeParamScheduler):\n    \"\"\"\n    Add an initial warmup stage to another scheduler.\n    \"\"\"\n\n    def __init__(\n        self,\n        scheduler: ParamScheduler,\n        warmup_factor: float,\n        warmup_length: float,\n        warmup_method: str = \"linear\",\n    ):\n        \"\"\"\n        Args:\n            scheduler: warmup will be added at the beginning of this scheduler\n            warmup_factor: the factor w.r.t the initial value of ``scheduler``, e.g. 0.001\n            warmup_length: the relative length (in [0, 1]) of warmup steps w.r.t the entire\n                training, e.g. 0.01\n            warmup_method: one of \"linear\" or \"constant\"\n        \"\"\"\n        end_value = scheduler(warmup_length)  # the value to reach when warmup ends\n        start_value = warmup_factor * scheduler(0.0)\n        if warmup_method == \"constant\":\n            warmup = ConstantParamScheduler(start_value)\n        elif warmup_method == \"linear\":\n            warmup = LinearParamScheduler(start_value, end_value)\n        else:\n            raise ValueError(\"Unknown warmup method: {}\".format(warmup_method))\n        super().__init__(\n            [warmup, scheduler],\n            interval_scaling=[\"rescaled\", \"fixed\"],\n            lengths=[warmup_length, 1 - warmup_length],\n        )\n\n\nclass LRMultiplier(torch.optim.lr_scheduler._LRScheduler):\n    \"\"\"\n    A LRScheduler which uses fvcore :class:`ParamScheduler` to multiply the\n    learning rate of each param in the optimizer.\n    Every step, the learning rate of each parameter becomes its initial value\n    multiplied by the output of the given :class:`ParamScheduler`.\n\n    The absolute learning rate value of each parameter can be different.\n    This scheduler can be used as long as the relative scale among them do\n    not change during training.\n\n    Examples:\n    ::\n        LRMultiplier(\n            opt,\n            WarmupParamScheduler(\n                MultiStepParamScheduler(\n                    [1, 0.1, 0.01],\n                    milestones=[60000, 80000],\n                    num_updates=90000,\n                ), 0.001, 100 / 90000\n            ),\n            max_iter=90000\n        )\n    \"\"\"\n\n    # NOTES: in the most general case, every LR can use its own scheduler.\n    # Supporting this requires interaction with the optimizer when its parameter\n    # group is initialized. For example, classyvision implements its own optimizer\n    # that allows different schedulers for every parameter group.\n    # To avoid this complexity, we use this class to support the most common cases\n    # where the relative scale among all LRs stay unchanged during training.  In this\n    # case we only need a total of one scheduler that defines the relative LR multiplier.\n\n    def __init__(\n        self,\n        optimizer: torch.optim.Optimizer,\n        multiplier: ParamScheduler,\n        max_iter: int,\n        last_iter: int = -1,\n    ):\n        \"\"\"\n        Args:\n            optimizer, last_iter: See ``torch.optim.lr_scheduler._LRScheduler``.\n                ``last_iter`` is the same as ``last_epoch``.\n            multiplier: a fvcore ParamScheduler that defines the multiplier on\n                every LR of the optimizer\n            max_iter: the total number of training iterations\n        \"\"\"\n        if not isinstance(multiplier, ParamScheduler):\n            raise ValueError(\n                \"_LRMultiplier(multiplier=) must be an instance of fvcore \"\n                f\"ParamScheduler. Got {multiplier} instead.\"\n            )\n        self._multiplier = multiplier\n        self._max_iter = max_iter\n        super().__init__(optimizer, last_epoch=last_iter)\n\n    def state_dict(self):\n        # fvcore schedulers are stateless. Only keep pytorch scheduler states\n        return {\"base_lrs\": self.base_lrs, \"last_epoch\": self.last_epoch}\n\n    def get_lr(self) -> List[float]:\n        multiplier = self._multiplier(self.last_epoch / self._max_iter)\n        return [base_lr * multiplier for base_lr in self.base_lrs]\n\n\n\"\"\"\nContent below is no longer needed!\n\"\"\"\n\n# NOTE: PyTorch's LR scheduler interface uses names that assume the LR changes\n# only on epoch boundaries. We typically use iteration based schedules instead.\n# As a result, \"epoch\" (e.g., as in self.last_epoch) should be understood to mean\n# \"iteration\" instead.\n\n# FIXME: ideally this would be achieved with a CombinedLRScheduler, separating\n# MultiStepLR with WarmupLR but the current LRScheduler design doesn't allow it.\n\n\nclass WarmupMultiStepLR(torch.optim.lr_scheduler._LRScheduler):\n    def __init__(\n        self,\n        optimizer: torch.optim.Optimizer,\n        milestones: List[int],\n        gamma: float = 0.1,\n        warmup_factor: float = 0.001,\n        warmup_iters: int = 1000,\n        warmup_method: str = \"linear\",\n        last_epoch: int = -1,\n    ):\n        logger.warning(\n            \"WarmupMultiStepLR is deprecated! Use LRMultipilier with fvcore ParamScheduler instead!\"\n        )\n        if not list(milestones) == sorted(milestones):\n            raise ValueError(\n                \"Milestones should be a list of\" \" increasing integers. Got {}\", milestones\n            )\n        self.milestones = milestones\n        self.gamma = gamma\n        self.warmup_factor = warmup_factor\n        self.warmup_iters = warmup_iters\n        self.warmup_method = warmup_method\n        super().__init__(optimizer, last_epoch)\n\n    def get_lr(self) -> List[float]:\n        warmup_factor = _get_warmup_factor_at_iter(\n            self.warmup_method, self.last_epoch, self.warmup_iters, self.warmup_factor\n        )\n        return [\n            base_lr * warmup_factor * self.gamma ** bisect_right(self.milestones, self.last_epoch)\n            for base_lr in self.base_lrs\n        ]\n\n    def _compute_values(self) -> List[float]:\n        # The new interface\n        return self.get_lr()\n\n\nclass WarmupCosineLR(torch.optim.lr_scheduler._LRScheduler):\n    def __init__(\n        self,\n        optimizer: torch.optim.Optimizer,\n        max_iters: int,\n        warmup_factor: float = 0.001,\n        warmup_iters: int = 1000,\n        warmup_method: str = \"linear\",\n        last_epoch: int = -1,\n    ):\n        logger.warning(\n            \"WarmupCosineLR is deprecated! Use LRMultipilier with fvcore ParamScheduler instead!\"\n        )\n        self.max_iters = max_iters\n        self.warmup_factor = warmup_factor\n        self.warmup_iters = warmup_iters\n        self.warmup_method = warmup_method\n        super().__init__(optimizer, last_epoch)\n\n    def get_lr(self) -> List[float]:\n        warmup_factor = _get_warmup_factor_at_iter(\n            self.warmup_method, self.last_epoch, self.warmup_iters, self.warmup_factor\n        )\n        # Different definitions of half-cosine with warmup are possible. For\n        # simplicity we multiply the standard half-cosine schedule by the warmup\n        # factor. An alternative is to start the period of the cosine at warmup_iters\n        # instead of at 0. In the case that warmup_iters << max_iters the two are\n        # very close to each other.\n        return [\n            base_lr\n            * warmup_factor\n            * 0.5\n            * (1.0 + math.cos(math.pi * self.last_epoch / self.max_iters))\n            for base_lr in self.base_lrs\n        ]\n\n    def _compute_values(self) -> List[float]:\n        # The new interface\n        return self.get_lr()\n\n\ndef _get_warmup_factor_at_iter(\n    method: str, iter: int, warmup_iters: int, warmup_factor: float\n) -> float:\n    \"\"\"\n    Return the learning rate warmup factor at a specific iteration.\n    See :paper:`ImageNet in 1h` for more details.\n\n    Args:\n        method (str): warmup method; either \"constant\" or \"linear\".\n        iter (int): iteration at which to calculate the warmup factor.\n        warmup_iters (int): the number of warmup iterations.\n        warmup_factor (float): the base warmup factor (the meaning changes according\n            to the method used).\n\n    Returns:\n        float: the effective warmup factor at the given iteration.\n    \"\"\"\n    if iter >= warmup_iters:\n        return 1.0\n\n    if method == \"constant\":\n        return warmup_factor\n    elif method == \"linear\":\n        alpha = iter / warmup_iters\n        return warmup_factor * (1 - alpha) + alpha\n    else:\n        raise ValueError(\"Unknown warmup method: {}\".format(method))\n"
  },
  {
    "path": "VPS_Module/detectron2/structures/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom .boxes import Boxes, BoxMode, pairwise_iou, pairwise_ioa, pairwise_point_box_distance\nfrom .image_list import ImageList\n\nfrom .instances import Instances\nfrom .keypoints import Keypoints, heatmaps_to_keypoints\nfrom .masks import BitMasks, PolygonMasks, polygons_to_bitmask, ROIMasks\nfrom .rotated_boxes import RotatedBoxes\nfrom .rotated_boxes import pairwise_iou as pairwise_iou_rotated\n\n__all__ = [k for k in globals().keys() if not k.startswith(\"_\")]\n\n\nfrom detectron2.utils.env import fixup_module_metadata\n\nfixup_module_metadata(__name__, globals(), __all__)\ndel fixup_module_metadata\n"
  },
  {
    "path": "VPS_Module/detectron2/structures/boxes.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport math\nimport numpy as np\nfrom enum import IntEnum, unique\nfrom typing import List, Tuple, Union\nimport torch\nfrom torch import device\n\n_RawBoxType = Union[List[float], Tuple[float, ...], torch.Tensor, np.ndarray]\n\n\n@unique\nclass BoxMode(IntEnum):\n    \"\"\"\n    Enum of different ways to represent a box.\n    \"\"\"\n\n    XYXY_ABS = 0\n    \"\"\"\n    (x0, y0, x1, y1) in absolute floating points coordinates.\n    The coordinates in range [0, width or height].\n    \"\"\"\n    XYWH_ABS = 1\n    \"\"\"\n    (x0, y0, w, h) in absolute floating points coordinates.\n    \"\"\"\n    XYXY_REL = 2\n    \"\"\"\n    Not yet supported!\n    (x0, y0, x1, y1) in range [0, 1]. They are relative to the size of the image.\n    \"\"\"\n    XYWH_REL = 3\n    \"\"\"\n    Not yet supported!\n    (x0, y0, w, h) in range [0, 1]. They are relative to the size of the image.\n    \"\"\"\n    XYWHA_ABS = 4\n    \"\"\"\n    (xc, yc, w, h, a) in absolute floating points coordinates.\n    (xc, yc) is the center of the rotated box, and the angle a is in degrees ccw.\n    \"\"\"\n\n    @staticmethod\n    def convert(box: _RawBoxType, from_mode: \"BoxMode\", to_mode: \"BoxMode\") -> _RawBoxType:\n        \"\"\"\n        Args:\n            box: can be a k-tuple, k-list or an Nxk array/tensor, where k = 4 or 5\n            from_mode, to_mode (BoxMode)\n\n        Returns:\n            The converted box of the same type.\n        \"\"\"\n        if from_mode == to_mode:\n            return box\n\n        original_type = type(box)\n        is_numpy = isinstance(box, np.ndarray)\n        single_box = isinstance(box, (list, tuple))\n        if single_box:\n            assert len(box) == 4 or len(box) == 5, (\n                \"BoxMode.convert takes either a k-tuple/list or an Nxk array/tensor,\"\n                \" where k == 4 or 5\"\n            )\n            arr = torch.tensor(box)[None, :]\n        else:\n            # avoid modifying the input box\n            if is_numpy:\n                arr = torch.from_numpy(np.asarray(box)).clone()\n            else:\n                arr = box.clone()\n\n        assert to_mode not in [BoxMode.XYXY_REL, BoxMode.XYWH_REL] and from_mode not in [\n            BoxMode.XYXY_REL,\n            BoxMode.XYWH_REL,\n        ], \"Relative mode not yet supported!\"\n\n        if from_mode == BoxMode.XYWHA_ABS and to_mode == BoxMode.XYXY_ABS:\n            assert (\n                arr.shape[-1] == 5\n            ), \"The last dimension of input shape must be 5 for XYWHA format\"\n            original_dtype = arr.dtype\n            arr = arr.double()\n\n            w = arr[:, 2]\n            h = arr[:, 3]\n            a = arr[:, 4]\n            c = torch.abs(torch.cos(a * math.pi / 180.0))\n            s = torch.abs(torch.sin(a * math.pi / 180.0))\n            # This basically computes the horizontal bounding rectangle of the rotated box\n            new_w = c * w + s * h\n            new_h = c * h + s * w\n\n            # convert center to top-left corner\n            arr[:, 0] -= new_w / 2.0\n            arr[:, 1] -= new_h / 2.0\n            # bottom-right corner\n            arr[:, 2] = arr[:, 0] + new_w\n            arr[:, 3] = arr[:, 1] + new_h\n\n            arr = arr[:, :4].to(dtype=original_dtype)\n        elif from_mode == BoxMode.XYWH_ABS and to_mode == BoxMode.XYWHA_ABS:\n            original_dtype = arr.dtype\n            arr = arr.double()\n            arr[:, 0] += arr[:, 2] / 2.0\n            arr[:, 1] += arr[:, 3] / 2.0\n            angles = torch.zeros((arr.shape[0], 1), dtype=arr.dtype)\n            arr = torch.cat((arr, angles), axis=1).to(dtype=original_dtype)\n        else:\n            if to_mode == BoxMode.XYXY_ABS and from_mode == BoxMode.XYWH_ABS:\n                arr[:, 2] += arr[:, 0]\n                arr[:, 3] += arr[:, 1]\n            elif from_mode == BoxMode.XYXY_ABS and to_mode == BoxMode.XYWH_ABS:\n                arr[:, 2] -= arr[:, 0]\n                arr[:, 3] -= arr[:, 1]\n            else:\n                raise NotImplementedError(\n                    \"Conversion from BoxMode {} to {} is not supported yet\".format(\n                        from_mode, to_mode\n                    )\n                )\n\n        if single_box:\n            return original_type(arr.flatten().tolist())\n        if is_numpy:\n            return arr.numpy()\n        else:\n            return arr\n\n\nclass Boxes:\n    \"\"\"\n    This structure stores a list of boxes as a Nx4 torch.Tensor.\n    It supports some common methods about boxes\n    (`area`, `clip`, `nonempty`, etc),\n    and also behaves like a Tensor\n    (support indexing, `to(device)`, `.device`, and iteration over all boxes)\n\n    Attributes:\n        tensor (torch.Tensor): float matrix of Nx4. Each row is (x1, y1, x2, y2).\n    \"\"\"\n\n    def __init__(self, tensor: torch.Tensor):\n        \"\"\"\n        Args:\n            tensor (Tensor[float]): a Nx4 matrix.  Each row is (x1, y1, x2, y2).\n        \"\"\"\n        device = tensor.device if isinstance(tensor, torch.Tensor) else torch.device(\"cpu\")\n        tensor = torch.as_tensor(tensor, dtype=torch.float32, device=device)\n        if tensor.numel() == 0:\n            # Use reshape, so we don't end up creating a new tensor that does not depend on\n            # the inputs (and consequently confuses jit)\n            tensor = tensor.reshape((-1, 4)).to(dtype=torch.float32, device=device)\n        assert tensor.dim() == 2 and tensor.size(-1) == 4, tensor.size()\n\n        self.tensor = tensor\n\n    def clone(self) -> \"Boxes\":\n        \"\"\"\n        Clone the Boxes.\n\n        Returns:\n            Boxes\n        \"\"\"\n        return Boxes(self.tensor.clone())\n\n    def to(self, device: torch.device):\n        # Boxes are assumed float32 and does not support to(dtype)\n        return Boxes(self.tensor.to(device=device))\n\n    def area(self) -> torch.Tensor:\n        \"\"\"\n        Computes the area of all the boxes.\n\n        Returns:\n            torch.Tensor: a vector with areas of each box.\n        \"\"\"\n        box = self.tensor\n        area = (box[:, 2] - box[:, 0]) * (box[:, 3] - box[:, 1])\n        return area\n\n    def clip(self, box_size: Tuple[int, int]) -> None:\n        \"\"\"\n        Clip (in place) the boxes by limiting x coordinates to the range [0, width]\n        and y coordinates to the range [0, height].\n\n        Args:\n            box_size (height, width): The clipping box's size.\n        \"\"\"\n        assert torch.isfinite(self.tensor).all(), \"Box tensor contains infinite or NaN!\"\n        h, w = box_size\n        x1 = self.tensor[:, 0].clamp(min=0, max=w)\n        y1 = self.tensor[:, 1].clamp(min=0, max=h)\n        x2 = self.tensor[:, 2].clamp(min=0, max=w)\n        y2 = self.tensor[:, 3].clamp(min=0, max=h)\n        self.tensor = torch.stack((x1, y1, x2, y2), dim=-1)\n\n    def nonempty(self, threshold: float = 0.0) -> torch.Tensor:\n        \"\"\"\n        Find boxes that are non-empty.\n        A box is considered empty, if either of its side is no larger than threshold.\n\n        Returns:\n            Tensor:\n                a binary vector which represents whether each box is empty\n                (False) or non-empty (True).\n        \"\"\"\n        box = self.tensor\n        widths = box[:, 2] - box[:, 0]\n        heights = box[:, 3] - box[:, 1]\n        keep = (widths > threshold) & (heights > threshold)\n        return keep\n\n    def __getitem__(self, item) -> \"Boxes\":\n        \"\"\"\n        Args:\n            item: int, slice, or a BoolTensor\n\n        Returns:\n            Boxes: Create a new :class:`Boxes` by indexing.\n\n        The following usage are allowed:\n\n        1. `new_boxes = boxes[3]`: return a `Boxes` which contains only one box.\n        2. `new_boxes = boxes[2:10]`: return a slice of boxes.\n        3. `new_boxes = boxes[vector]`, where vector is a torch.BoolTensor\n           with `length = len(boxes)`. Nonzero elements in the vector will be selected.\n\n        Note that the returned Boxes might share storage with this Boxes,\n        subject to Pytorch's indexing semantics.\n        \"\"\"\n        if isinstance(item, int):\n            return Boxes(self.tensor[item].view(1, -1))\n        b = self.tensor[item]\n        assert b.dim() == 2, \"Indexing on Boxes with {} failed to return a matrix!\".format(item)\n        return Boxes(b)\n\n    def __len__(self) -> int:\n        return self.tensor.shape[0]\n\n    def __repr__(self) -> str:\n        return \"Boxes(\" + str(self.tensor) + \")\"\n\n    def inside_box(self, box_size: Tuple[int, int], boundary_threshold: int = 0) -> torch.Tensor:\n        \"\"\"\n        Args:\n            box_size (height, width): Size of the reference box.\n            boundary_threshold (int): Boxes that extend beyond the reference box\n                boundary by more than boundary_threshold are considered \"outside\".\n\n        Returns:\n            a binary vector, indicating whether each box is inside the reference box.\n        \"\"\"\n        height, width = box_size\n        inds_inside = (\n            (self.tensor[..., 0] >= -boundary_threshold)\n            & (self.tensor[..., 1] >= -boundary_threshold)\n            & (self.tensor[..., 2] < width + boundary_threshold)\n            & (self.tensor[..., 3] < height + boundary_threshold)\n        )\n        return inds_inside\n\n    def get_centers(self) -> torch.Tensor:\n        \"\"\"\n        Returns:\n            The box centers in a Nx2 array of (x, y).\n        \"\"\"\n        return (self.tensor[:, :2] + self.tensor[:, 2:]) / 2\n\n    def scale(self, scale_x: float, scale_y: float) -> None:\n        \"\"\"\n        Scale the box with horizontal and vertical scaling factors\n        \"\"\"\n        self.tensor[:, 0::2] *= scale_x\n        self.tensor[:, 1::2] *= scale_y\n\n    @classmethod\n    def cat(cls, boxes_list: List[\"Boxes\"]) -> \"Boxes\":\n        \"\"\"\n        Concatenates a list of Boxes into a single Boxes\n\n        Arguments:\n            boxes_list (list[Boxes])\n\n        Returns:\n            Boxes: the concatenated Boxes\n        \"\"\"\n        assert isinstance(boxes_list, (list, tuple))\n        if len(boxes_list) == 0:\n            return cls(torch.empty(0))\n        assert all([isinstance(box, Boxes) for box in boxes_list])\n\n        # use torch.cat (v.s. layers.cat) so the returned boxes never share storage with input\n        cat_boxes = cls(torch.cat([b.tensor for b in boxes_list], dim=0))\n        return cat_boxes\n\n    @property\n    def device(self) -> device:\n        return self.tensor.device\n\n    # type \"Iterator[torch.Tensor]\", yield, and iter() not supported by torchscript\n    # https://github.com/pytorch/pytorch/issues/18627\n    @torch.jit.unused\n    def __iter__(self):\n        \"\"\"\n        Yield a box as a Tensor of shape (4,) at a time.\n        \"\"\"\n        yield from self.tensor\n\n\ndef pairwise_intersection(boxes1: Boxes, boxes2: Boxes) -> torch.Tensor:\n    \"\"\"\n    Given two lists of boxes of size N and M,\n    compute the intersection area between __all__ N x M pairs of boxes.\n    The box order must be (xmin, ymin, xmax, ymax)\n\n    Args:\n        boxes1,boxes2 (Boxes): two `Boxes`. Contains N & M boxes, respectively.\n\n    Returns:\n        Tensor: intersection, sized [N,M].\n    \"\"\"\n    boxes1, boxes2 = boxes1.tensor, boxes2.tensor\n    width_height = torch.min(boxes1[:, None, 2:], boxes2[:, 2:]) - torch.max(\n        boxes1[:, None, :2], boxes2[:, :2]\n    )  # [N,M,2]\n\n    width_height.clamp_(min=0)  # [N,M,2]\n    intersection = width_height.prod(dim=2)  # [N,M]\n    return intersection\n\n\n# implementation from https://github.com/kuangliu/torchcv/blob/master/torchcv/utils/box.py\n# with slight modifications\ndef pairwise_iou(boxes1: Boxes, boxes2: Boxes) -> torch.Tensor:\n    \"\"\"\n    Given two lists of boxes of size N and M, compute the IoU\n    (intersection over union) between **all** N x M pairs of boxes.\n    The box order must be (xmin, ymin, xmax, ymax).\n\n    Args:\n        boxes1,boxes2 (Boxes): two `Boxes`. Contains N & M boxes, respectively.\n\n    Returns:\n        Tensor: IoU, sized [N,M].\n    \"\"\"\n    area1 = boxes1.area()  # [N]\n    area2 = boxes2.area()  # [M]\n    inter = pairwise_intersection(boxes1, boxes2)\n\n    # handle empty boxes\n    iou = torch.where(\n        inter > 0,\n        inter / (area1[:, None] + area2 - inter),\n        torch.zeros(1, dtype=inter.dtype, device=inter.device),\n    )\n    return iou\n\n\ndef pairwise_ioa(boxes1: Boxes, boxes2: Boxes) -> torch.Tensor:\n    \"\"\"\n    Similar to :func:`pariwise_iou` but compute the IoA (intersection over boxes2 area).\n\n    Args:\n        boxes1,boxes2 (Boxes): two `Boxes`. Contains N & M boxes, respectively.\n\n    Returns:\n        Tensor: IoA, sized [N,M].\n    \"\"\"\n    area2 = boxes2.area()  # [M]\n    inter = pairwise_intersection(boxes1, boxes2)\n\n    # handle empty boxes\n    ioa = torch.where(\n        inter > 0, inter / area2, torch.zeros(1, dtype=inter.dtype, device=inter.device)\n    )\n    return ioa\n\n\ndef pairwise_point_box_distance(points: torch.Tensor, boxes: Boxes):\n    \"\"\"\n    Pairwise distance between N points and M boxes. The distance between a\n    point and a box is represented by the distance from the point to 4 edges\n    of the box. Distances are all positive when the point is inside the box.\n\n    Args:\n        points: Nx2 coordinates. Each row is (x, y)\n        boxes: M boxes\n\n    Returns:\n        Tensor: distances of size (N, M, 4). The 4 values are distances from\n            the point to the left, top, right, bottom of the box.\n    \"\"\"\n    x, y = points.unsqueeze(dim=2).unbind(dim=1)  # (N, 1)\n    x0, y0, x1, y1 = boxes.tensor.unsqueeze(dim=0).unbind(dim=2)  # (1, M)\n    return torch.stack([x - x0, y - y0, x1 - x, y1 - y], dim=2)\n\n\ndef matched_pairwise_iou(boxes1: Boxes, boxes2: Boxes) -> torch.Tensor:\n    \"\"\"\n    Compute pairwise intersection over union (IOU) of two sets of matched\n    boxes that have the same number of boxes.\n    Similar to :func:`pairwise_iou`, but computes only diagonal elements of the matrix.\n\n    Args:\n        boxes1 (Boxes): bounding boxes, sized [N,4].\n        boxes2 (Boxes): same length as boxes1\n    Returns:\n        Tensor: iou, sized [N].\n    \"\"\"\n    assert len(boxes1) == len(\n        boxes2\n    ), \"boxlists should have the same\" \"number of entries, got {}, {}\".format(\n        len(boxes1), len(boxes2)\n    )\n    area1 = boxes1.area()  # [N]\n    area2 = boxes2.area()  # [N]\n    box1, box2 = boxes1.tensor, boxes2.tensor\n    lt = torch.max(box1[:, :2], box2[:, :2])  # [N,2]\n    rb = torch.min(box1[:, 2:], box2[:, 2:])  # [N,2]\n    wh = (rb - lt).clamp(min=0)  # [N,2]\n    inter = wh[:, 0] * wh[:, 1]  # [N]\n    iou = inter / (area1 + area2 - inter)  # [N]\n    return iou\n"
  },
  {
    "path": "VPS_Module/detectron2/structures/image_list.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom __future__ import division\nfrom typing import Any, List, Tuple\nimport torch\nfrom torch import device\nfrom torch.nn import functional as F\n\nfrom detectron2.layers.wrappers import shapes_to_tensor\n\n\nclass ImageList(object):\n    \"\"\"\n    Structure that holds a list of images (of possibly\n    varying sizes) as a single tensor.\n    This works by padding the images to the same size.\n    The original sizes of each image is stored in `image_sizes`.\n\n    Attributes:\n        image_sizes (list[tuple[int, int]]): each tuple is (h, w).\n            During tracing, it becomes list[Tensor] instead.\n    \"\"\"\n\n    def __init__(self, tensor: torch.Tensor, image_sizes: List[Tuple[int, int]]):\n        \"\"\"\n        Arguments:\n            tensor (Tensor): of shape (N, H, W) or (N, C_1, ..., C_K, H, W) where K >= 1\n            image_sizes (list[tuple[int, int]]): Each tuple is (h, w). It can\n                be smaller than (H, W) due to padding.\n        \"\"\"\n        self.tensor = tensor\n        self.image_sizes = image_sizes\n\n    def __len__(self) -> int:\n        return len(self.image_sizes)\n\n    def __getitem__(self, idx) -> torch.Tensor:\n        \"\"\"\n        Access the individual image in its original size.\n\n        Args:\n            idx: int or slice\n\n        Returns:\n            Tensor: an image of shape (H, W) or (C_1, ..., C_K, H, W) where K >= 1\n        \"\"\"\n        size = self.image_sizes[idx]\n        return self.tensor[idx, ..., : size[0], : size[1]]\n\n    @torch.jit.unused\n    def to(self, *args: Any, **kwargs: Any) -> \"ImageList\":\n        cast_tensor = self.tensor.to(*args, **kwargs)\n        return ImageList(cast_tensor, self.image_sizes)\n\n    @property\n    def device(self) -> device:\n        return self.tensor.device\n\n    @staticmethod\n    def from_tensors(\n        tensors: List[torch.Tensor], size_divisibility: int = 0, pad_value: float = 0.0\n    ) -> \"ImageList\":\n        \"\"\"\n        Args:\n            tensors: a tuple or list of `torch.Tensor`, each of shape (Hi, Wi) or\n                (C_1, ..., C_K, Hi, Wi) where K >= 1. The Tensors will be padded\n                to the same shape with `pad_value`.\n            size_divisibility (int): If `size_divisibility > 0`, add padding to ensure\n                the common height and width is divisible by `size_divisibility`.\n                This depends on the model and many models need a divisibility of 32.\n            pad_value (float): value to pad\n\n        Returns:\n            an `ImageList`.\n        \"\"\"\n        assert len(tensors) > 0\n        assert isinstance(tensors, (tuple, list))\n        for t in tensors:\n            assert isinstance(t, torch.Tensor), type(t)\n            assert t.shape[:-2] == tensors[0].shape[:-2], t.shape\n\n        image_sizes = [(im.shape[-2], im.shape[-1]) for im in tensors]\n        image_sizes_tensor = [shapes_to_tensor(x) for x in image_sizes]\n        max_size = torch.stack(image_sizes_tensor).max(0).values\n\n        if size_divisibility > 1:\n            stride = size_divisibility\n            # the last two dims are H,W, both subject to divisibility requirement\n            max_size = (max_size + (stride - 1)).div(stride, rounding_mode=\"floor\") * stride\n\n        # handle weirdness of scripting and tracing ...\n        if torch.jit.is_scripting():\n            max_size: List[int] = max_size.to(dtype=torch.long).tolist()\n        else:\n            if torch.jit.is_tracing():\n                image_sizes = image_sizes_tensor\n\n        if len(tensors) == 1:\n            # This seems slightly (2%) faster.\n            # TODO: check whether it's faster for multiple images as well\n            image_size = image_sizes[0]\n            padding_size = [0, max_size[-1] - image_size[1], 0, max_size[-2] - image_size[0]]\n            batched_imgs = F.pad(tensors[0], padding_size, value=pad_value).unsqueeze_(0)\n        else:\n            # max_size can be a tensor in tracing mode, therefore convert to list\n            batch_shape = [len(tensors)] + list(tensors[0].shape[:-2]) + list(max_size)\n            batched_imgs = tensors[0].new_full(batch_shape, pad_value)\n            for img, pad_img in zip(tensors, batched_imgs):\n                pad_img[..., : img.shape[-2], : img.shape[-1]].copy_(img)\n\n        return ImageList(batched_imgs.contiguous(), image_sizes)\n"
  },
  {
    "path": "VPS_Module/detectron2/structures/instances.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport itertools\nfrom typing import Any, Dict, List, Tuple, Union\nimport torch\n\n\nclass Instances:\n    \"\"\"\n    This class represents a list of instances in an image.\n    It stores the attributes of instances (e.g., boxes, masks, labels, scores) as \"fields\".\n    All fields must have the same ``__len__`` which is the number of instances.\n\n    All other (non-field) attributes of this class are considered private:\n    they must start with '_' and are not modifiable by a user.\n\n    Some basic usage:\n\n    1. Set/get/check a field:\n\n       .. code-block:: python\n\n          instances.gt_boxes = Boxes(...)\n          print(instances.pred_masks)  # a tensor of shape (N, H, W)\n          print('gt_masks' in instances)\n\n    2. ``len(instances)`` returns the number of instances\n    3. Indexing: ``instances[indices]`` will apply the indexing on all the fields\n       and returns a new :class:`Instances`.\n       Typically, ``indices`` is a integer vector of indices,\n       or a binary mask of length ``num_instances``\n\n       .. code-block:: python\n\n          category_3_detections = instances[instances.pred_classes == 3]\n          confident_detections = instances[instances.scores > 0.9]\n    \"\"\"\n\n    def __init__(self, image_size: Tuple[int, int], **kwargs: Any):\n        \"\"\"\n        Args:\n            image_size (height, width): the spatial size of the image.\n            kwargs: fields to add to this `Instances`.\n        \"\"\"\n        self._image_size = image_size\n        self._fields: Dict[str, Any] = {}\n        for k, v in kwargs.items():\n            self.set(k, v)\n\n    @property\n    def image_size(self) -> Tuple[int, int]:\n        \"\"\"\n        Returns:\n            tuple: height, width\n        \"\"\"\n        return self._image_size\n\n    def __setattr__(self, name: str, val: Any) -> None:\n        if name.startswith(\"_\"):\n            super().__setattr__(name, val)\n        else:\n            self.set(name, val)\n\n    def __getattr__(self, name: str) -> Any:\n        if name == \"_fields\" or name not in self._fields:\n            raise AttributeError(\"Cannot find field '{}' in the given Instances!\".format(name))\n        return self._fields[name]\n\n    def set(self, name: str, value: Any) -> None:\n        \"\"\"\n        Set the field named `name` to `value`.\n        The length of `value` must be the number of instances,\n        and must agree with other existing fields in this object.\n        \"\"\"\n        data_len = len(value)\n        if len(self._fields):\n            assert (\n                len(self) == data_len\n            ), \"Adding a field of length {} to a Instances of length {}\".format(data_len, len(self))\n        self._fields[name] = value\n\n    def has(self, name: str) -> bool:\n        \"\"\"\n        Returns:\n            bool: whether the field called `name` exists.\n        \"\"\"\n        return name in self._fields\n\n    def remove(self, name: str) -> None:\n        \"\"\"\n        Remove the field called `name`.\n        \"\"\"\n        del self._fields[name]\n\n    def get(self, name: str) -> Any:\n        \"\"\"\n        Returns the field called `name`.\n        \"\"\"\n        return self._fields[name]\n\n    def get_fields(self) -> Dict[str, Any]:\n        \"\"\"\n        Returns:\n            dict: a dict which maps names (str) to data of the fields\n\n        Modifying the returned dict will modify this instance.\n        \"\"\"\n        return self._fields\n\n    # Tensor-like methods\n    def to(self, *args: Any, **kwargs: Any) -> \"Instances\":\n        \"\"\"\n        Returns:\n            Instances: all fields are called with a `to(device)`, if the field has this method.\n        \"\"\"\n        ret = Instances(self._image_size)\n        for k, v in self._fields.items():\n            if hasattr(v, \"to\"):\n                v = v.to(*args, **kwargs)\n            ret.set(k, v)\n        return ret\n\n    def __getitem__(self, item: Union[int, slice, torch.BoolTensor]) -> \"Instances\":\n        \"\"\"\n        Args:\n            item: an index-like object and will be used to index all the fields.\n\n        Returns:\n            If `item` is a string, return the data in the corresponding field.\n            Otherwise, returns an `Instances` where all fields are indexed by `item`.\n        \"\"\"\n        if type(item) == int:\n            if item >= len(self) or item < -len(self):\n                raise IndexError(\"Instances index out of range!\")\n            else:\n                item = slice(item, None, len(self))\n\n        ret = Instances(self._image_size)\n        for k, v in self._fields.items():\n            ret.set(k, v[item])\n        return ret\n\n    def __len__(self) -> int:\n        for v in self._fields.values():\n            # use __len__ because len() has to be int and is not friendly to tracing\n            return v.__len__()\n        raise NotImplementedError(\"Empty Instances does not support __len__!\")\n\n    def __iter__(self):\n        raise NotImplementedError(\"`Instances` object is not iterable!\")\n\n    @staticmethod\n    def cat(instance_lists: List[\"Instances\"]) -> \"Instances\":\n        \"\"\"\n        Args:\n            instance_lists (list[Instances])\n\n        Returns:\n            Instances\n        \"\"\"\n        assert all(isinstance(i, Instances) for i in instance_lists)\n        assert len(instance_lists) > 0\n        if len(instance_lists) == 1:\n            return instance_lists[0]\n\n        image_size = instance_lists[0].image_size\n        if not isinstance(image_size, torch.Tensor):  # could be a tensor in tracing\n            for i in instance_lists[1:]:\n                assert i.image_size == image_size\n        ret = Instances(image_size)\n        for k in instance_lists[0]._fields.keys():\n            values = [i.get(k) for i in instance_lists]\n            v0 = values[0]\n            if isinstance(v0, torch.Tensor):\n                values = torch.cat(values, dim=0)\n            elif isinstance(v0, list):\n                values = list(itertools.chain(*values))\n            elif hasattr(type(v0), \"cat\"):\n                values = type(v0).cat(values)\n            else:\n                raise ValueError(\"Unsupported type {} for concatenation\".format(type(v0)))\n            ret.set(k, values)\n        return ret\n\n    def __str__(self) -> str:\n        s = self.__class__.__name__ + \"(\"\n        s += \"num_instances={}, \".format(len(self))\n        s += \"image_height={}, \".format(self._image_size[0])\n        s += \"image_width={}, \".format(self._image_size[1])\n        s += \"fields=[{}])\".format(\", \".join((f\"{k}: {v}\" for k, v in self._fields.items())))\n        return s\n\n    __repr__ = __str__\n"
  },
  {
    "path": "VPS_Module/detectron2/structures/keypoints.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport numpy as np\nfrom typing import Any, List, Tuple, Union\nimport torch\nfrom torch.nn import functional as F\n\n\nclass Keypoints:\n    \"\"\"\n    Stores keypoint **annotation** data. GT Instances have a `gt_keypoints` property\n    containing the x,y location and visibility flag of each keypoint. This tensor has shape\n    (N, K, 3) where N is the number of instances and K is the number of keypoints per instance.\n\n    The visibility flag follows the COCO format and must be one of three integers:\n\n    * v=0: not labeled (in which case x=y=0)\n    * v=1: labeled but not visible\n    * v=2: labeled and visible\n    \"\"\"\n\n    def __init__(self, keypoints: Union[torch.Tensor, np.ndarray, List[List[float]]]):\n        \"\"\"\n        Arguments:\n            keypoints: A Tensor, numpy array, or list of the x, y, and visibility of each keypoint.\n                The shape should be (N, K, 3) where N is the number of\n                instances, and K is the number of keypoints per instance.\n        \"\"\"\n        device = keypoints.device if isinstance(keypoints, torch.Tensor) else torch.device(\"cpu\")\n        keypoints = torch.as_tensor(keypoints, dtype=torch.float32, device=device)\n        assert keypoints.dim() == 3 and keypoints.shape[2] == 3, keypoints.shape\n        self.tensor = keypoints\n\n    def __len__(self) -> int:\n        return self.tensor.size(0)\n\n    def to(self, *args: Any, **kwargs: Any) -> \"Keypoints\":\n        return type(self)(self.tensor.to(*args, **kwargs))\n\n    @property\n    def device(self) -> torch.device:\n        return self.tensor.device\n\n    def to_heatmap(self, boxes: torch.Tensor, heatmap_size: int) -> torch.Tensor:\n        \"\"\"\n        Convert keypoint annotations to a heatmap of one-hot labels for training,\n        as described in :paper:`Mask R-CNN`.\n\n        Arguments:\n            boxes: Nx4 tensor, the boxes to draw the keypoints to\n\n        Returns:\n            heatmaps:\n                A tensor of shape (N, K), each element is integer spatial label\n                in the range [0, heatmap_size**2 - 1] for each keypoint in the input.\n            valid:\n                A tensor of shape (N, K) containing whether each keypoint is in the roi or not.\n        \"\"\"\n        return _keypoints_to_heatmap(self.tensor, boxes, heatmap_size)\n\n    def __getitem__(self, item: Union[int, slice, torch.BoolTensor]) -> \"Keypoints\":\n        \"\"\"\n        Create a new `Keypoints` by indexing on this `Keypoints`.\n\n        The following usage are allowed:\n\n        1. `new_kpts = kpts[3]`: return a `Keypoints` which contains only one instance.\n        2. `new_kpts = kpts[2:10]`: return a slice of key points.\n        3. `new_kpts = kpts[vector]`, where vector is a torch.ByteTensor\n           with `length = len(kpts)`. Nonzero elements in the vector will be selected.\n\n        Note that the returned Keypoints might share storage with this Keypoints,\n        subject to Pytorch's indexing semantics.\n        \"\"\"\n        if isinstance(item, int):\n            return Keypoints([self.tensor[item]])\n        return Keypoints(self.tensor[item])\n\n    def __repr__(self) -> str:\n        s = self.__class__.__name__ + \"(\"\n        s += \"num_instances={})\".format(len(self.tensor))\n        return s\n\n    @staticmethod\n    def cat(keypoints_list: List[\"Keypoints\"]) -> \"Keypoints\":\n        \"\"\"\n        Concatenates a list of Keypoints into a single Keypoints\n\n        Arguments:\n            keypoints_list (list[Keypoints])\n\n        Returns:\n            Keypoints: the concatenated Keypoints\n        \"\"\"\n        assert isinstance(keypoints_list, (list, tuple))\n        assert len(keypoints_list) > 0\n        assert all(isinstance(keypoints, Keypoints) for keypoints in keypoints_list)\n\n        cat_kpts = type(keypoints_list[0])(\n            torch.cat([kpts.tensor for kpts in keypoints_list], dim=0)\n        )\n        return cat_kpts\n\n\n# TODO make this nicer, this is a direct translation from C2 (but removing the inner loop)\ndef _keypoints_to_heatmap(\n    keypoints: torch.Tensor, rois: torch.Tensor, heatmap_size: int\n) -> Tuple[torch.Tensor, torch.Tensor]:\n    \"\"\"\n    Encode keypoint locations into a target heatmap for use in SoftmaxWithLoss across space.\n\n    Maps keypoints from the half-open interval [x1, x2) on continuous image coordinates to the\n    closed interval [0, heatmap_size - 1] on discrete image coordinates. We use the\n    continuous-discrete conversion from Heckbert 1990 (\"What is the coordinate of a pixel?\"):\n    d = floor(c) and c = d + 0.5, where d is a discrete coordinate and c is a continuous coordinate.\n\n    Arguments:\n        keypoints: tensor of keypoint locations in of shape (N, K, 3).\n        rois: Nx4 tensor of rois in xyxy format\n        heatmap_size: integer side length of square heatmap.\n\n    Returns:\n        heatmaps: A tensor of shape (N, K) containing an integer spatial label\n            in the range [0, heatmap_size**2 - 1] for each keypoint in the input.\n        valid: A tensor of shape (N, K) containing whether each keypoint is in\n            the roi or not.\n    \"\"\"\n\n    if rois.numel() == 0:\n        return rois.new().long(), rois.new().long()\n    offset_x = rois[:, 0]\n    offset_y = rois[:, 1]\n    scale_x = heatmap_size / (rois[:, 2] - rois[:, 0])\n    scale_y = heatmap_size / (rois[:, 3] - rois[:, 1])\n\n    offset_x = offset_x[:, None]\n    offset_y = offset_y[:, None]\n    scale_x = scale_x[:, None]\n    scale_y = scale_y[:, None]\n\n    x = keypoints[..., 0]\n    y = keypoints[..., 1]\n\n    x_boundary_inds = x == rois[:, 2][:, None]\n    y_boundary_inds = y == rois[:, 3][:, None]\n\n    x = (x - offset_x) * scale_x\n    x = x.floor().long()\n    y = (y - offset_y) * scale_y\n    y = y.floor().long()\n\n    x[x_boundary_inds] = heatmap_size - 1\n    y[y_boundary_inds] = heatmap_size - 1\n\n    valid_loc = (x >= 0) & (y >= 0) & (x < heatmap_size) & (y < heatmap_size)\n    vis = keypoints[..., 2] > 0\n    valid = (valid_loc & vis).long()\n\n    lin_ind = y * heatmap_size + x\n    heatmaps = lin_ind * valid\n\n    return heatmaps, valid\n\n\n@torch.jit.script_if_tracing\ndef heatmaps_to_keypoints(maps: torch.Tensor, rois: torch.Tensor) -> torch.Tensor:\n    \"\"\"\n    Extract predicted keypoint locations from heatmaps.\n\n    Args:\n        maps (Tensor): (#ROIs, #keypoints, POOL_H, POOL_W). The predicted heatmap of logits for\n            each ROI and each keypoint.\n        rois (Tensor): (#ROIs, 4). The box of each ROI.\n\n    Returns:\n        Tensor of shape (#ROIs, #keypoints, 4) with the last dimension corresponding to\n        (x, y, logit, score) for each keypoint.\n\n    When converting discrete pixel indices in an NxN image to a continuous keypoint coordinate,\n    we maintain consistency with :meth:`Keypoints.to_heatmap` by using the conversion from\n    Heckbert 1990: c = d + 0.5, where d is a discrete coordinate and c is a continuous coordinate.\n    \"\"\"\n    # The decorator use of torch.no_grad() was not supported by torchscript.\n    # https://github.com/pytorch/pytorch/issues/44768\n    maps = maps.detach()\n    rois = rois.detach()\n\n    offset_x = rois[:, 0]\n    offset_y = rois[:, 1]\n\n    widths = (rois[:, 2] - rois[:, 0]).clamp(min=1)\n    heights = (rois[:, 3] - rois[:, 1]).clamp(min=1)\n    widths_ceil = widths.ceil()\n    heights_ceil = heights.ceil()\n\n    num_rois, num_keypoints = maps.shape[:2]\n    xy_preds = maps.new_zeros(rois.shape[0], num_keypoints, 4)\n\n    width_corrections = widths / widths_ceil\n    height_corrections = heights / heights_ceil\n\n    keypoints_idx = torch.arange(num_keypoints, device=maps.device)\n\n    for i in range(num_rois):\n        outsize = (int(heights_ceil[i]), int(widths_ceil[i]))\n        roi_map = F.interpolate(\n            maps[[i]], size=outsize, mode=\"bicubic\", align_corners=False\n        ).squeeze(\n            0\n        )  # #keypoints x H x W\n\n        # softmax over the spatial region\n        max_score, _ = roi_map.view(num_keypoints, -1).max(1)\n        max_score = max_score.view(num_keypoints, 1, 1)\n        tmp_full_resolution = (roi_map - max_score).exp_()\n        tmp_pool_resolution = (maps[i] - max_score).exp_()\n        # Produce scores over the region H x W, but normalize with POOL_H x POOL_W,\n        # so that the scores of objects of different absolute sizes will be more comparable\n        roi_map_scores = tmp_full_resolution / tmp_pool_resolution.sum((1, 2), keepdim=True)\n\n        w = roi_map.shape[2]\n        pos = roi_map.view(num_keypoints, -1).argmax(1)\n\n        x_int = pos % w\n        y_int = (pos - x_int) // w\n\n        assert (\n            roi_map_scores[keypoints_idx, y_int, x_int]\n            == roi_map_scores.view(num_keypoints, -1).max(1)[0]\n        ).all()\n\n        x = (x_int.float() + 0.5) * width_corrections[i]\n        y = (y_int.float() + 0.5) * height_corrections[i]\n\n        xy_preds[i, :, 0] = x + offset_x[i]\n        xy_preds[i, :, 1] = y + offset_y[i]\n        xy_preds[i, :, 2] = roi_map[keypoints_idx, y_int, x_int]\n        xy_preds[i, :, 3] = roi_map_scores[keypoints_idx, y_int, x_int]\n\n    return xy_preds\n"
  },
  {
    "path": "VPS_Module/detectron2/structures/masks.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport copy\nimport itertools\nimport numpy as np\nfrom typing import Any, Iterator, List, Union\nimport pycocotools.mask as mask_util\nimport torch\nfrom torch import device\n\nfrom detectron2.layers.roi_align import ROIAlign\nfrom detectron2.utils.memory import retry_if_cuda_oom\n\nfrom .boxes import Boxes\n\n\ndef polygon_area(x, y):\n    # Using the shoelace formula\n    # https://stackoverflow.com/questions/24467972/calculate-area-of-polygon-given-x-y-coordinates\n    return 0.5 * np.abs(np.dot(x, np.roll(y, 1)) - np.dot(y, np.roll(x, 1)))\n\n\ndef polygons_to_bitmask(polygons: List[np.ndarray], height: int, width: int) -> np.ndarray:\n    \"\"\"\n    Args:\n        polygons (list[ndarray]): each array has shape (Nx2,)\n        height, width (int)\n\n    Returns:\n        ndarray: a bool mask of shape (height, width)\n    \"\"\"\n    if len(polygons) == 0:\n        # COCOAPI does not support empty polygons\n        return np.zeros((height, width)).astype(np.bool)\n    rles = mask_util.frPyObjects(polygons, height, width)\n    rle = mask_util.merge(rles)\n    return mask_util.decode(rle).astype(np.bool)\n\n\ndef rasterize_polygons_within_box(\n    polygons: List[np.ndarray], box: np.ndarray, mask_size: int\n) -> torch.Tensor:\n    \"\"\"\n    Rasterize the polygons into a mask image and\n    crop the mask content in the given box.\n    The cropped mask is resized to (mask_size, mask_size).\n\n    This function is used when generating training targets for mask head in Mask R-CNN.\n    Given original ground-truth masks for an image, new ground-truth mask\n    training targets in the size of `mask_size x mask_size`\n    must be provided for each predicted box. This function will be called to\n    produce such targets.\n\n    Args:\n        polygons (list[ndarray[float]]): a list of polygons, which represents an instance.\n        box: 4-element numpy array\n        mask_size (int):\n\n    Returns:\n        Tensor: BoolTensor of shape (mask_size, mask_size)\n    \"\"\"\n    # 1. Shift the polygons w.r.t the boxes\n    w, h = box[2] - box[0], box[3] - box[1]\n\n    polygons = copy.deepcopy(polygons)\n    for p in polygons:\n        p[0::2] = p[0::2] - box[0]\n        p[1::2] = p[1::2] - box[1]\n\n    # 2. Rescale the polygons to the new box size\n    # max() to avoid division by small number\n    ratio_h = mask_size / max(h, 0.1)\n    ratio_w = mask_size / max(w, 0.1)\n\n    if ratio_h == ratio_w:\n        for p in polygons:\n            p *= ratio_h\n    else:\n        for p in polygons:\n            p[0::2] *= ratio_w\n            p[1::2] *= ratio_h\n\n    # 3. Rasterize the polygons with coco api\n    mask = polygons_to_bitmask(polygons, mask_size, mask_size)\n    mask = torch.from_numpy(mask)\n    return mask\n\n\nclass BitMasks:\n    \"\"\"\n    This class stores the segmentation masks for all objects in one image, in\n    the form of bitmaps.\n\n    Attributes:\n        tensor: bool Tensor of N,H,W, representing N instances in the image.\n    \"\"\"\n\n    def __init__(self, tensor: Union[torch.Tensor, np.ndarray]):\n        \"\"\"\n        Args:\n            tensor: bool Tensor of N,H,W, representing N instances in the image.\n        \"\"\"\n        device = tensor.device if isinstance(tensor, torch.Tensor) else torch.device(\"cpu\")\n        tensor = torch.as_tensor(tensor, dtype=torch.bool, device=device)\n        assert tensor.dim() == 3, tensor.size()\n        self.image_size = tensor.shape[1:]\n        self.tensor = tensor\n\n    @torch.jit.unused\n    def to(self, *args: Any, **kwargs: Any) -> \"BitMasks\":\n        return BitMasks(self.tensor.to(*args, **kwargs))\n\n    @property\n    def device(self) -> torch.device:\n        return self.tensor.device\n\n    @torch.jit.unused\n    def __getitem__(self, item: Union[int, slice, torch.BoolTensor]) -> \"BitMasks\":\n        \"\"\"\n        Returns:\n            BitMasks: Create a new :class:`BitMasks` by indexing.\n\n        The following usage are allowed:\n\n        1. `new_masks = masks[3]`: return a `BitMasks` which contains only one mask.\n        2. `new_masks = masks[2:10]`: return a slice of masks.\n        3. `new_masks = masks[vector]`, where vector is a torch.BoolTensor\n           with `length = len(masks)`. Nonzero elements in the vector will be selected.\n\n        Note that the returned object might share storage with this object,\n        subject to Pytorch's indexing semantics.\n        \"\"\"\n        if isinstance(item, int):\n            return BitMasks(self.tensor[item].unsqueeze(0))\n        m = self.tensor[item]\n        assert m.dim() == 3, \"Indexing on BitMasks with {} returns a tensor with shape {}!\".format(\n            item, m.shape\n        )\n        return BitMasks(m)\n\n    @torch.jit.unused\n    def __iter__(self) -> torch.Tensor:\n        yield from self.tensor\n\n    @torch.jit.unused\n    def __repr__(self) -> str:\n        s = self.__class__.__name__ + \"(\"\n        s += \"num_instances={})\".format(len(self.tensor))\n        return s\n\n    def __len__(self) -> int:\n        return self.tensor.shape[0]\n\n    def nonempty(self) -> torch.Tensor:\n        \"\"\"\n        Find masks that are non-empty.\n\n        Returns:\n            Tensor: a BoolTensor which represents\n                whether each mask is empty (False) or non-empty (True).\n        \"\"\"\n        return self.tensor.flatten(1).any(dim=1)\n\n    @staticmethod\n    def from_polygon_masks(\n        polygon_masks: Union[\"PolygonMasks\", List[List[np.ndarray]]], height: int, width: int\n    ) -> \"BitMasks\":\n        \"\"\"\n        Args:\n            polygon_masks (list[list[ndarray]] or PolygonMasks)\n            height, width (int)\n        \"\"\"\n        if isinstance(polygon_masks, PolygonMasks):\n            polygon_masks = polygon_masks.polygons\n        masks = [polygons_to_bitmask(p, height, width) for p in polygon_masks]\n        if len(masks):\n            return BitMasks(torch.stack([torch.from_numpy(x) for x in masks]))\n        else:\n            return BitMasks(torch.empty(0, height, width, dtype=torch.bool))\n\n    @staticmethod\n    def from_roi_masks(roi_masks: \"ROIMasks\", height: int, width: int) -> \"BitMasks\":\n        \"\"\"\n        Args:\n            roi_masks:\n            height, width (int):\n        \"\"\"\n        return roi_masks.to_bitmasks(height, width)\n\n    def crop_and_resize(self, boxes: torch.Tensor, mask_size: int) -> torch.Tensor:\n        \"\"\"\n        Crop each bitmask by the given box, and resize results to (mask_size, mask_size).\n        This can be used to prepare training targets for Mask R-CNN.\n        It has less reconstruction error compared to rasterization with polygons.\n        However we observe no difference in accuracy,\n        but BitMasks requires more memory to store all the masks.\n\n        Args:\n            boxes (Tensor): Nx4 tensor storing the boxes for each mask\n            mask_size (int): the size of the rasterized mask.\n\n        Returns:\n            Tensor:\n                A bool tensor of shape (N, mask_size, mask_size), where\n                N is the number of predicted boxes for this image.\n        \"\"\"\n        assert len(boxes) == len(self), \"{} != {}\".format(len(boxes), len(self))\n        device = self.tensor.device\n\n        batch_inds = torch.arange(len(boxes), device=device).to(dtype=boxes.dtype)[:, None]\n        rois = torch.cat([batch_inds, boxes], dim=1)  # Nx5\n\n        bit_masks = self.tensor.to(dtype=torch.float32)\n        rois = rois.to(device=device)\n        output = (\n            ROIAlign((mask_size, mask_size), 1.0, 0, aligned=True)\n            .forward(bit_masks[:, None, :, :], rois)\n            .squeeze(1)\n        )\n        output = output >= 0.5\n        return output\n\n    def get_bounding_boxes(self) -> Boxes:\n        \"\"\"\n        Returns:\n            Boxes: tight bounding boxes around bitmasks.\n            If a mask is empty, it's bounding box will be all zero.\n        \"\"\"\n        boxes = torch.zeros(self.tensor.shape[0], 4, dtype=torch.float32)\n        x_any = torch.any(self.tensor, dim=1)\n        y_any = torch.any(self.tensor, dim=2)\n        for idx in range(self.tensor.shape[0]):\n            x = torch.where(x_any[idx, :])[0]\n            y = torch.where(y_any[idx, :])[0]\n            if len(x) > 0 and len(y) > 0:\n                boxes[idx, :] = torch.as_tensor(\n                    [x[0], y[0], x[-1] + 1, y[-1] + 1], dtype=torch.float32\n                )\n        return Boxes(boxes)\n\n    @staticmethod\n    def cat(bitmasks_list: List[\"BitMasks\"]) -> \"BitMasks\":\n        \"\"\"\n        Concatenates a list of BitMasks into a single BitMasks\n\n        Arguments:\n            bitmasks_list (list[BitMasks])\n\n        Returns:\n            BitMasks: the concatenated BitMasks\n        \"\"\"\n        assert isinstance(bitmasks_list, (list, tuple))\n        assert len(bitmasks_list) > 0\n        assert all(isinstance(bitmask, BitMasks) for bitmask in bitmasks_list)\n\n        cat_bitmasks = type(bitmasks_list[0])(torch.cat([bm.tensor for bm in bitmasks_list], dim=0))\n        return cat_bitmasks\n\n\nclass PolygonMasks:\n    \"\"\"\n    This class stores the segmentation masks for all objects in one image, in the form of polygons.\n\n    Attributes:\n        polygons: list[list[ndarray]]. Each ndarray is a float64 vector representing a polygon.\n    \"\"\"\n\n    def __init__(self, polygons: List[List[Union[torch.Tensor, np.ndarray]]]):\n        \"\"\"\n        Arguments:\n            polygons (list[list[np.ndarray]]): The first\n                level of the list correspond to individual instances,\n                the second level to all the polygons that compose the\n                instance, and the third level to the polygon coordinates.\n                The third level array should have the format of\n                [x0, y0, x1, y1, ..., xn, yn] (n >= 3).\n        \"\"\"\n        if not isinstance(polygons, list):\n            raise ValueError(\n                \"Cannot create PolygonMasks: Expect a list of list of polygons per image. \"\n                \"Got '{}' instead.\".format(type(polygons))\n            )\n\n        def _make_array(t: Union[torch.Tensor, np.ndarray]) -> np.ndarray:\n            # Use float64 for higher precision, because why not?\n            # Always put polygons on CPU (self.to is a no-op) since they\n            # are supposed to be small tensors.\n            # May need to change this assumption if GPU placement becomes useful\n            if isinstance(t, torch.Tensor):\n                t = t.cpu().numpy()\n            return np.asarray(t).astype(\"float64\")\n\n        def process_polygons(\n            polygons_per_instance: List[Union[torch.Tensor, np.ndarray]]\n        ) -> List[np.ndarray]:\n            if not isinstance(polygons_per_instance, list):\n                raise ValueError(\n                    \"Cannot create polygons: Expect a list of polygons per instance. \"\n                    \"Got '{}' instead.\".format(type(polygons_per_instance))\n                )\n            # transform each polygon to a numpy array\n            polygons_per_instance = [_make_array(p) for p in polygons_per_instance]\n            for polygon in polygons_per_instance:\n                if len(polygon) % 2 != 0 or len(polygon) < 6:\n                    raise ValueError(f\"Cannot create a polygon from {len(polygon)} coordinates.\")\n            return polygons_per_instance\n\n        self.polygons: List[List[np.ndarray]] = [\n            process_polygons(polygons_per_instance) for polygons_per_instance in polygons\n        ]\n\n    def to(self, *args: Any, **kwargs: Any) -> \"PolygonMasks\":\n        return self\n\n    @property\n    def device(self) -> torch.device:\n        return torch.device(\"cpu\")\n\n    def get_bounding_boxes(self) -> Boxes:\n        \"\"\"\n        Returns:\n            Boxes: tight bounding boxes around polygon masks.\n        \"\"\"\n        boxes = torch.zeros(len(self.polygons), 4, dtype=torch.float32)\n        for idx, polygons_per_instance in enumerate(self.polygons):\n            minxy = torch.as_tensor([float(\"inf\"), float(\"inf\")], dtype=torch.float32)\n            maxxy = torch.zeros(2, dtype=torch.float32)\n            for polygon in polygons_per_instance:\n                coords = torch.from_numpy(polygon).view(-1, 2).to(dtype=torch.float32)\n                minxy = torch.min(minxy, torch.min(coords, dim=0).values)\n                maxxy = torch.max(maxxy, torch.max(coords, dim=0).values)\n            boxes[idx, :2] = minxy\n            boxes[idx, 2:] = maxxy\n        return Boxes(boxes)\n\n    def nonempty(self) -> torch.Tensor:\n        \"\"\"\n        Find masks that are non-empty.\n\n        Returns:\n            Tensor:\n                a BoolTensor which represents whether each mask is empty (False) or not (True).\n        \"\"\"\n        keep = [1 if len(polygon) > 0 else 0 for polygon in self.polygons]\n        return torch.from_numpy(np.asarray(keep, dtype=np.bool))\n\n    def __getitem__(self, item: Union[int, slice, List[int], torch.BoolTensor]) -> \"PolygonMasks\":\n        \"\"\"\n        Support indexing over the instances and return a `PolygonMasks` object.\n        `item` can be:\n\n        1. An integer. It will return an object with only one instance.\n        2. A slice. It will return an object with the selected instances.\n        3. A list[int]. It will return an object with the selected instances,\n           correpsonding to the indices in the list.\n        4. A vector mask of type BoolTensor, whose length is num_instances.\n           It will return an object with the instances whose mask is nonzero.\n        \"\"\"\n        if isinstance(item, int):\n            selected_polygons = [self.polygons[item]]\n        elif isinstance(item, slice):\n            selected_polygons = self.polygons[item]\n        elif isinstance(item, list):\n            selected_polygons = [self.polygons[i] for i in item]\n        elif isinstance(item, torch.Tensor):\n            # Polygons is a list, so we have to move the indices back to CPU.\n            if item.dtype == torch.bool:\n                assert item.dim() == 1, item.shape\n                item = item.nonzero().squeeze(1).cpu().numpy().tolist()\n            elif item.dtype in [torch.int32, torch.int64]:\n                item = item.cpu().numpy().tolist()\n            else:\n                raise ValueError(\"Unsupported tensor dtype={} for indexing!\".format(item.dtype))\n            selected_polygons = [self.polygons[i] for i in item]\n        return PolygonMasks(selected_polygons)\n\n    def __iter__(self) -> Iterator[List[np.ndarray]]:\n        \"\"\"\n        Yields:\n            list[ndarray]: the polygons for one instance.\n            Each Tensor is a float64 vector representing a polygon.\n        \"\"\"\n        return iter(self.polygons)\n\n    def __repr__(self) -> str:\n        s = self.__class__.__name__ + \"(\"\n        s += \"num_instances={})\".format(len(self.polygons))\n        return s\n\n    def __len__(self) -> int:\n        return len(self.polygons)\n\n    def crop_and_resize(self, boxes: torch.Tensor, mask_size: int) -> torch.Tensor:\n        \"\"\"\n        Crop each mask by the given box, and resize results to (mask_size, mask_size).\n        This can be used to prepare training targets for Mask R-CNN.\n\n        Args:\n            boxes (Tensor): Nx4 tensor storing the boxes for each mask\n            mask_size (int): the size of the rasterized mask.\n\n        Returns:\n            Tensor: A bool tensor of shape (N, mask_size, mask_size), where\n            N is the number of predicted boxes for this image.\n        \"\"\"\n        assert len(boxes) == len(self), \"{} != {}\".format(len(boxes), len(self))\n\n        device = boxes.device\n        # Put boxes on the CPU, as the polygon representation is not efficient GPU-wise\n        # (several small tensors for representing a single instance mask)\n        boxes = boxes.to(torch.device(\"cpu\"))\n\n        results = [\n            rasterize_polygons_within_box(poly, box.numpy(), mask_size)\n            for poly, box in zip(self.polygons, boxes)\n        ]\n        \"\"\"\n        poly: list[list[float]], the polygons for one instance\n        box: a tensor of shape (4,)\n        \"\"\"\n        if len(results) == 0:\n            return torch.empty(0, mask_size, mask_size, dtype=torch.bool, device=device)\n        return torch.stack(results, dim=0).to(device=device)\n\n    def area(self):\n        \"\"\"\n        Computes area of the mask.\n        Only works with Polygons, using the shoelace formula:\n        https://stackoverflow.com/questions/24467972/calculate-area-of-polygon-given-x-y-coordinates\n\n        Returns:\n            Tensor: a vector, area for each instance\n        \"\"\"\n\n        area = []\n        for polygons_per_instance in self.polygons:\n            area_per_instance = 0\n            for p in polygons_per_instance:\n                area_per_instance += polygon_area(p[0::2], p[1::2])\n            area.append(area_per_instance)\n\n        return torch.tensor(area)\n\n    @staticmethod\n    def cat(polymasks_list: List[\"PolygonMasks\"]) -> \"PolygonMasks\":\n        \"\"\"\n        Concatenates a list of PolygonMasks into a single PolygonMasks\n\n        Arguments:\n            polymasks_list (list[PolygonMasks])\n\n        Returns:\n            PolygonMasks: the concatenated PolygonMasks\n        \"\"\"\n        assert isinstance(polymasks_list, (list, tuple))\n        assert len(polymasks_list) > 0\n        assert all(isinstance(polymask, PolygonMasks) for polymask in polymasks_list)\n\n        cat_polymasks = type(polymasks_list[0])(\n            list(itertools.chain.from_iterable(pm.polygons for pm in polymasks_list))\n        )\n        return cat_polymasks\n\n\nclass ROIMasks:\n    \"\"\"\n    Represent masks by N smaller masks defined in some ROIs. Once ROI boxes are given,\n    full-image bitmask can be obtained by \"pasting\" the mask on the region defined\n    by the corresponding ROI box.\n    \"\"\"\n\n    def __init__(self, tensor: torch.Tensor):\n        \"\"\"\n        Args:\n            tensor: (N, M, M) mask tensor that defines the mask within each ROI.\n        \"\"\"\n        if tensor.dim() != 3:\n            raise ValueError(\"ROIMasks must take a masks of 3 dimension.\")\n        self.tensor = tensor\n\n    def to(self, device: torch.device) -> \"ROIMasks\":\n        return ROIMasks(self.tensor.to(device))\n\n    @property\n    def device(self) -> device:\n        return self.tensor.device\n\n    def __len__(self):\n        return self.tensor.shape[0]\n\n    def __getitem__(self, item) -> \"ROIMasks\":\n        \"\"\"\n        Returns:\n            ROIMasks: Create a new :class:`ROIMasks` by indexing.\n\n        The following usage are allowed:\n\n        1. `new_masks = masks[2:10]`: return a slice of masks.\n        2. `new_masks = masks[vector]`, where vector is a torch.BoolTensor\n           with `length = len(masks)`. Nonzero elements in the vector will be selected.\n\n        Note that the returned object might share storage with this object,\n        subject to Pytorch's indexing semantics.\n        \"\"\"\n        t = self.tensor[item]\n        if t.dim() != 3:\n            raise ValueError(\n                f\"Indexing on ROIMasks with {item} returns a tensor with shape {t.shape}!\"\n            )\n        return ROIMasks(t)\n\n    @torch.jit.unused\n    def __repr__(self) -> str:\n        s = self.__class__.__name__ + \"(\"\n        s += \"num_instances={})\".format(len(self.tensor))\n        return s\n\n    @torch.jit.unused\n    def to_bitmasks(self, boxes: torch.Tensor, height, width, threshold=0.5):\n        \"\"\"\n        Args: see documentation of :func:`paste_masks_in_image`.\n        \"\"\"\n        from detectron2.layers.mask_ops import paste_masks_in_image, _paste_masks_tensor_shape\n\n        if torch.jit.is_tracing():\n            if isinstance(height, torch.Tensor):\n                paste_func = _paste_masks_tensor_shape\n            else:\n                paste_func = paste_masks_in_image\n        else:\n            paste_func = retry_if_cuda_oom(paste_masks_in_image)\n        bitmasks = paste_func(self.tensor, boxes.tensor, (height, width), threshold=threshold)\n        return BitMasks(bitmasks)\n"
  },
  {
    "path": "VPS_Module/detectron2/structures/rotated_boxes.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport math\nfrom typing import List, Tuple\nimport torch\n\nfrom detectron2.layers.rotated_boxes import pairwise_iou_rotated\n\nfrom .boxes import Boxes\n\n\nclass RotatedBoxes(Boxes):\n    \"\"\"\n    This structure stores a list of rotated boxes as a Nx5 torch.Tensor.\n    It supports some common methods about boxes\n    (`area`, `clip`, `nonempty`, etc),\n    and also behaves like a Tensor\n    (support indexing, `to(device)`, `.device`, and iteration over all boxes)\n    \"\"\"\n\n    def __init__(self, tensor: torch.Tensor):\n        \"\"\"\n        Args:\n            tensor (Tensor[float]): a Nx5 matrix.  Each row is\n                (x_center, y_center, width, height, angle),\n                in which angle is represented in degrees.\n                While there's no strict range restriction for it,\n                the recommended principal range is between [-180, 180) degrees.\n\n        Assume we have a horizontal box B = (x_center, y_center, width, height),\n        where width is along the x-axis and height is along the y-axis.\n        The rotated box B_rot (x_center, y_center, width, height, angle)\n        can be seen as:\n\n        1. When angle == 0:\n           B_rot == B\n        2. When angle > 0:\n           B_rot is obtained by rotating B w.r.t its center by :math:`|angle|` degrees CCW;\n        3. When angle < 0:\n           B_rot is obtained by rotating B w.r.t its center by :math:`|angle|` degrees CW.\n\n        Mathematically, since the right-handed coordinate system for image space\n        is (y, x), where y is top->down and x is left->right, the 4 vertices of the\n        rotated rectangle :math:`(yr_i, xr_i)` (i = 1, 2, 3, 4) can be obtained from\n        the vertices of the horizontal rectangle :math:`(y_i, x_i)` (i = 1, 2, 3, 4)\n        in the following way (:math:`\\\\theta = angle*\\\\pi/180` is the angle in radians,\n        :math:`(y_c, x_c)` is the center of the rectangle):\n\n        .. math::\n\n            yr_i = \\\\cos(\\\\theta) (y_i - y_c) - \\\\sin(\\\\theta) (x_i - x_c) + y_c,\n\n            xr_i = \\\\sin(\\\\theta) (y_i - y_c) + \\\\cos(\\\\theta) (x_i - x_c) + x_c,\n\n        which is the standard rigid-body rotation transformation.\n\n        Intuitively, the angle is\n        (1) the rotation angle from y-axis in image space\n        to the height vector (top->down in the box's local coordinate system)\n        of the box in CCW, and\n        (2) the rotation angle from x-axis in image space\n        to the width vector (left->right in the box's local coordinate system)\n        of the box in CCW.\n\n        More intuitively, consider the following horizontal box ABCD represented\n        in (x1, y1, x2, y2): (3, 2, 7, 4),\n        covering the [3, 7] x [2, 4] region of the continuous coordinate system\n        which looks like this:\n\n        .. code:: none\n\n            O--------> x\n            |\n            |  A---B\n            |  |   |\n            |  D---C\n            |\n            v y\n\n        Note that each capital letter represents one 0-dimensional geometric point\n        instead of a 'square pixel' here.\n\n        In the example above, using (x, y) to represent a point we have:\n\n        .. math::\n\n            O = (0, 0), A = (3, 2), B = (7, 2), C = (7, 4), D = (3, 4)\n\n        We name vector AB = vector DC as the width vector in box's local coordinate system, and\n        vector AD = vector BC as the height vector in box's local coordinate system. Initially,\n        when angle = 0 degree, they're aligned with the positive directions of x-axis and y-axis\n        in the image space, respectively.\n\n        For better illustration, we denote the center of the box as E,\n\n        .. code:: none\n\n            O--------> x\n            |\n            |  A---B\n            |  | E |\n            |  D---C\n            |\n            v y\n\n        where the center E = ((3+7)/2, (2+4)/2) = (5, 3).\n\n        Also,\n\n        .. math::\n\n            width = |AB| = |CD| = 7 - 3 = 4,\n            height = |AD| = |BC| = 4 - 2 = 2.\n\n        Therefore, the corresponding representation for the same shape in rotated box in\n        (x_center, y_center, width, height, angle) format is:\n\n        (5, 3, 4, 2, 0),\n\n        Now, let's consider (5, 3, 4, 2, 90), which is rotated by 90 degrees\n        CCW (counter-clockwise) by definition. It looks like this:\n\n        .. code:: none\n\n            O--------> x\n            |   B-C\n            |   | |\n            |   |E|\n            |   | |\n            |   A-D\n            v y\n\n        The center E is still located at the same point (5, 3), while the vertices\n        ABCD are rotated by 90 degrees CCW with regard to E:\n        A = (4, 5), B = (4, 1), C = (6, 1), D = (6, 5)\n\n        Here, 90 degrees can be seen as the CCW angle to rotate from y-axis to\n        vector AD or vector BC (the top->down height vector in box's local coordinate system),\n        or the CCW angle to rotate from x-axis to vector AB or vector DC (the left->right\n        width vector in box's local coordinate system).\n\n        .. math::\n\n            width = |AB| = |CD| = 5 - 1 = 4,\n            height = |AD| = |BC| = 6 - 4 = 2.\n\n        Next, how about (5, 3, 4, 2, -90), which is rotated by 90 degrees CW (clockwise)\n        by definition? It looks like this:\n\n        .. code:: none\n\n            O--------> x\n            |   D-A\n            |   | |\n            |   |E|\n            |   | |\n            |   C-B\n            v y\n\n        The center E is still located at the same point (5, 3), while the vertices\n        ABCD are rotated by 90 degrees CW with regard to E:\n        A = (6, 1), B = (6, 5), C = (4, 5), D = (4, 1)\n\n        .. math::\n\n            width = |AB| = |CD| = 5 - 1 = 4,\n            height = |AD| = |BC| = 6 - 4 = 2.\n\n        This covers exactly the same region as (5, 3, 4, 2, 90) does, and their IoU\n        will be 1. However, these two will generate different RoI Pooling results and\n        should not be treated as an identical box.\n\n        On the other hand, it's easy to see that (X, Y, W, H, A) is identical to\n        (X, Y, W, H, A+360N), for any integer N. For example (5, 3, 4, 2, 270) would be\n        identical to (5, 3, 4, 2, -90), because rotating the shape 270 degrees CCW is\n        equivalent to rotating the same shape 90 degrees CW.\n\n        We could rotate further to get (5, 3, 4, 2, 180), or (5, 3, 4, 2, -180):\n\n        .. code:: none\n\n            O--------> x\n            |\n            |  C---D\n            |  | E |\n            |  B---A\n            |\n            v y\n\n        .. math::\n\n            A = (7, 4), B = (3, 4), C = (3, 2), D = (7, 2),\n\n            width = |AB| = |CD| = 7 - 3 = 4,\n            height = |AD| = |BC| = 4 - 2 = 2.\n\n        Finally, this is a very inaccurate (heavily quantized) illustration of\n        how (5, 3, 4, 2, 60) looks like in case anyone wonders:\n\n        .. code:: none\n\n            O--------> x\n            |     B\\\n            |    /  C\n            |   /E /\n            |  A  /\n            |   `D\n            v y\n\n        It's still a rectangle with center of (5, 3), width of 4 and height of 2,\n        but its angle (and thus orientation) is somewhere between\n        (5, 3, 4, 2, 0) and (5, 3, 4, 2, 90).\n        \"\"\"\n        device = tensor.device if isinstance(tensor, torch.Tensor) else torch.device(\"cpu\")\n        tensor = torch.as_tensor(tensor, dtype=torch.float32, device=device)\n        if tensor.numel() == 0:\n            # Use reshape, so we don't end up creating a new tensor that does not depend on\n            # the inputs (and consequently confuses jit)\n            tensor = tensor.reshape((0, 5)).to(dtype=torch.float32, device=device)\n        assert tensor.dim() == 2 and tensor.size(-1) == 5, tensor.size()\n\n        self.tensor = tensor\n\n    def clone(self) -> \"RotatedBoxes\":\n        \"\"\"\n        Clone the RotatedBoxes.\n\n        Returns:\n            RotatedBoxes\n        \"\"\"\n        return RotatedBoxes(self.tensor.clone())\n\n    def to(self, device: torch.device):\n        # Boxes are assumed float32 and does not support to(dtype)\n        return RotatedBoxes(self.tensor.to(device=device))\n\n    def area(self) -> torch.Tensor:\n        \"\"\"\n        Computes the area of all the boxes.\n\n        Returns:\n            torch.Tensor: a vector with areas of each box.\n        \"\"\"\n        box = self.tensor\n        area = box[:, 2] * box[:, 3]\n        return area\n\n    def normalize_angles(self) -> None:\n        \"\"\"\n        Restrict angles to the range of [-180, 180) degrees\n        \"\"\"\n        self.tensor[:, 4] = (self.tensor[:, 4] + 180.0) % 360.0 - 180.0\n\n    def clip(self, box_size: Tuple[int, int], clip_angle_threshold: float = 1.0) -> None:\n        \"\"\"\n        Clip (in place) the boxes by limiting x coordinates to the range [0, width]\n        and y coordinates to the range [0, height].\n\n        For RRPN:\n        Only clip boxes that are almost horizontal with a tolerance of\n        clip_angle_threshold to maintain backward compatibility.\n\n        Rotated boxes beyond this threshold are not clipped for two reasons:\n\n        1. There are potentially multiple ways to clip a rotated box to make it\n           fit within the image.\n        2. It's tricky to make the entire rectangular box fit within the image\n           and still be able to not leave out pixels of interest.\n\n        Therefore we rely on ops like RoIAlignRotated to safely handle this.\n\n        Args:\n            box_size (height, width): The clipping box's size.\n            clip_angle_threshold:\n                Iff. abs(normalized(angle)) <= clip_angle_threshold (in degrees),\n                we do the clipping as horizontal boxes.\n        \"\"\"\n        h, w = box_size\n\n        # normalize angles to be within (-180, 180] degrees\n        self.normalize_angles()\n\n        idx = torch.where(torch.abs(self.tensor[:, 4]) <= clip_angle_threshold)[0]\n\n        # convert to (x1, y1, x2, y2)\n        x1 = self.tensor[idx, 0] - self.tensor[idx, 2] / 2.0\n        y1 = self.tensor[idx, 1] - self.tensor[idx, 3] / 2.0\n        x2 = self.tensor[idx, 0] + self.tensor[idx, 2] / 2.0\n        y2 = self.tensor[idx, 1] + self.tensor[idx, 3] / 2.0\n\n        # clip\n        x1.clamp_(min=0, max=w)\n        y1.clamp_(min=0, max=h)\n        x2.clamp_(min=0, max=w)\n        y2.clamp_(min=0, max=h)\n\n        # convert back to (xc, yc, w, h)\n        self.tensor[idx, 0] = (x1 + x2) / 2.0\n        self.tensor[idx, 1] = (y1 + y2) / 2.0\n        # make sure widths and heights do not increase due to numerical errors\n        self.tensor[idx, 2] = torch.min(self.tensor[idx, 2], x2 - x1)\n        self.tensor[idx, 3] = torch.min(self.tensor[idx, 3], y2 - y1)\n\n    def nonempty(self, threshold: float = 0.0) -> torch.Tensor:\n        \"\"\"\n        Find boxes that are non-empty.\n        A box is considered empty, if either of its side is no larger than threshold.\n\n        Returns:\n            Tensor: a binary vector which represents\n            whether each box is empty (False) or non-empty (True).\n        \"\"\"\n        box = self.tensor\n        widths = box[:, 2]\n        heights = box[:, 3]\n        keep = (widths > threshold) & (heights > threshold)\n        return keep\n\n    def __getitem__(self, item) -> \"RotatedBoxes\":\n        \"\"\"\n        Returns:\n            RotatedBoxes: Create a new :class:`RotatedBoxes` by indexing.\n\n        The following usage are allowed:\n\n        1. `new_boxes = boxes[3]`: return a `RotatedBoxes` which contains only one box.\n        2. `new_boxes = boxes[2:10]`: return a slice of boxes.\n        3. `new_boxes = boxes[vector]`, where vector is a torch.ByteTensor\n           with `length = len(boxes)`. Nonzero elements in the vector will be selected.\n\n        Note that the returned RotatedBoxes might share storage with this RotatedBoxes,\n        subject to Pytorch's indexing semantics.\n        \"\"\"\n        if isinstance(item, int):\n            return RotatedBoxes(self.tensor[item].view(1, -1))\n        b = self.tensor[item]\n        assert b.dim() == 2, \"Indexing on RotatedBoxes with {} failed to return a matrix!\".format(\n            item\n        )\n        return RotatedBoxes(b)\n\n    def __len__(self) -> int:\n        return self.tensor.shape[0]\n\n    def __repr__(self) -> str:\n        return \"RotatedBoxes(\" + str(self.tensor) + \")\"\n\n    def inside_box(self, box_size: Tuple[int, int], boundary_threshold: int = 0) -> torch.Tensor:\n        \"\"\"\n        Args:\n            box_size (height, width): Size of the reference box covering\n                [0, width] x [0, height]\n            boundary_threshold (int): Boxes that extend beyond the reference box\n                boundary by more than boundary_threshold are considered \"outside\".\n\n        For RRPN, it might not be necessary to call this function since it's common\n        for rotated box to extend to outside of the image boundaries\n        (the clip function only clips the near-horizontal boxes)\n\n        Returns:\n            a binary vector, indicating whether each box is inside the reference box.\n        \"\"\"\n        height, width = box_size\n\n        cnt_x = self.tensor[..., 0]\n        cnt_y = self.tensor[..., 1]\n        half_w = self.tensor[..., 2] / 2.0\n        half_h = self.tensor[..., 3] / 2.0\n        a = self.tensor[..., 4]\n        c = torch.abs(torch.cos(a * math.pi / 180.0))\n        s = torch.abs(torch.sin(a * math.pi / 180.0))\n        # This basically computes the horizontal bounding rectangle of the rotated box\n        max_rect_dx = c * half_w + s * half_h\n        max_rect_dy = c * half_h + s * half_w\n\n        inds_inside = (\n            (cnt_x - max_rect_dx >= -boundary_threshold)\n            & (cnt_y - max_rect_dy >= -boundary_threshold)\n            & (cnt_x + max_rect_dx < width + boundary_threshold)\n            & (cnt_y + max_rect_dy < height + boundary_threshold)\n        )\n\n        return inds_inside\n\n    def get_centers(self) -> torch.Tensor:\n        \"\"\"\n        Returns:\n            The box centers in a Nx2 array of (x, y).\n        \"\"\"\n        return self.tensor[:, :2]\n\n    def scale(self, scale_x: float, scale_y: float) -> None:\n        \"\"\"\n        Scale the rotated box with horizontal and vertical scaling factors\n        Note: when scale_factor_x != scale_factor_y,\n        the rotated box does not preserve the rectangular shape when the angle\n        is not a multiple of 90 degrees under resize transformation.\n        Instead, the shape is a parallelogram (that has skew)\n        Here we make an approximation by fitting a rotated rectangle to the parallelogram.\n        \"\"\"\n        self.tensor[:, 0] *= scale_x\n        self.tensor[:, 1] *= scale_y\n        theta = self.tensor[:, 4] * math.pi / 180.0\n        c = torch.cos(theta)\n        s = torch.sin(theta)\n\n        # In image space, y is top->down and x is left->right\n        # Consider the local coordintate system for the rotated box,\n        # where the box center is located at (0, 0), and the four vertices ABCD are\n        # A(-w / 2, -h / 2), B(w / 2, -h / 2), C(w / 2, h / 2), D(-w / 2, h / 2)\n        # the midpoint of the left edge AD of the rotated box E is:\n        # E = (A+D)/2 = (-w / 2, 0)\n        # the midpoint of the top edge AB of the rotated box F is:\n        # F(0, -h / 2)\n        # To get the old coordinates in the global system, apply the rotation transformation\n        # (Note: the right-handed coordinate system for image space is yOx):\n        # (old_x, old_y) = (s * y + c * x, c * y - s * x)\n        # E(old) = (s * 0 + c * (-w/2), c * 0 - s * (-w/2)) = (-c * w / 2, s * w / 2)\n        # F(old) = (s * (-h / 2) + c * 0, c * (-h / 2) - s * 0) = (-s * h / 2, -c * h / 2)\n        # After applying the scaling factor (sfx, sfy):\n        # E(new) = (-sfx * c * w / 2, sfy * s * w / 2)\n        # F(new) = (-sfx * s * h / 2, -sfy * c * h / 2)\n        # The new width after scaling tranformation becomes:\n\n        # w(new) = |E(new) - O| * 2\n        #        = sqrt[(sfx * c * w / 2)^2 + (sfy * s * w / 2)^2] * 2\n        #        = sqrt[(sfx * c)^2 + (sfy * s)^2] * w\n        # i.e., scale_factor_w = sqrt[(sfx * c)^2 + (sfy * s)^2]\n        #\n        # For example,\n        # when angle = 0 or 180, |c| = 1, s = 0, scale_factor_w == scale_factor_x;\n        # when |angle| = 90, c = 0, |s| = 1, scale_factor_w == scale_factor_y\n        self.tensor[:, 2] *= torch.sqrt((scale_x * c) ** 2 + (scale_y * s) ** 2)\n\n        # h(new) = |F(new) - O| * 2\n        #        = sqrt[(sfx * s * h / 2)^2 + (sfy * c * h / 2)^2] * 2\n        #        = sqrt[(sfx * s)^2 + (sfy * c)^2] * h\n        # i.e., scale_factor_h = sqrt[(sfx * s)^2 + (sfy * c)^2]\n        #\n        # For example,\n        # when angle = 0 or 180, |c| = 1, s = 0, scale_factor_h == scale_factor_y;\n        # when |angle| = 90, c = 0, |s| = 1, scale_factor_h == scale_factor_x\n        self.tensor[:, 3] *= torch.sqrt((scale_x * s) ** 2 + (scale_y * c) ** 2)\n\n        # The angle is the rotation angle from y-axis in image space to the height\n        # vector (top->down in the box's local coordinate system) of the box in CCW.\n        #\n        # angle(new) = angle_yOx(O - F(new))\n        #            = angle_yOx( (sfx * s * h / 2, sfy * c * h / 2) )\n        #            = atan2(sfx * s * h / 2, sfy * c * h / 2)\n        #            = atan2(sfx * s, sfy * c)\n        #\n        # For example,\n        # when sfx == sfy, angle(new) == atan2(s, c) == angle(old)\n        self.tensor[:, 4] = torch.atan2(scale_x * s, scale_y * c) * 180 / math.pi\n\n    @classmethod\n    def cat(cls, boxes_list: List[\"RotatedBoxes\"]) -> \"RotatedBoxes\":\n        \"\"\"\n        Concatenates a list of RotatedBoxes into a single RotatedBoxes\n\n        Arguments:\n            boxes_list (list[RotatedBoxes])\n\n        Returns:\n            RotatedBoxes: the concatenated RotatedBoxes\n        \"\"\"\n        assert isinstance(boxes_list, (list, tuple))\n        if len(boxes_list) == 0:\n            return cls(torch.empty(0))\n        assert all([isinstance(box, RotatedBoxes) for box in boxes_list])\n\n        # use torch.cat (v.s. layers.cat) so the returned boxes never share storage with input\n        cat_boxes = cls(torch.cat([b.tensor for b in boxes_list], dim=0))\n        return cat_boxes\n\n    @property\n    def device(self) -> torch.device:\n        return self.tensor.device\n\n    @torch.jit.unused\n    def __iter__(self):\n        \"\"\"\n        Yield a box as a Tensor of shape (5,) at a time.\n        \"\"\"\n        yield from self.tensor\n\n\ndef pairwise_iou(boxes1: RotatedBoxes, boxes2: RotatedBoxes) -> None:\n    \"\"\"\n    Given two lists of rotated boxes of size N and M,\n    compute the IoU (intersection over union)\n    between **all** N x M pairs of boxes.\n    The box order must be (x_center, y_center, width, height, angle).\n\n    Args:\n        boxes1, boxes2 (RotatedBoxes):\n            two `RotatedBoxes`. Contains N & M rotated boxes, respectively.\n\n    Returns:\n        Tensor: IoU, sized [N,M].\n    \"\"\"\n\n    return pairwise_iou_rotated(boxes1.tensor, boxes2.tensor)\n"
  },
  {
    "path": "VPS_Module/detectron2/utils/README.md",
    "content": "# Utility functions\n\nThis folder contain utility functions that are not used in the\ncore library, but are useful for building models or training\ncode using the config system.\n"
  },
  {
    "path": "VPS_Module/detectron2/utils/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n"
  },
  {
    "path": "VPS_Module/detectron2/utils/analysis.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n# -*- coding: utf-8 -*-\n\nimport typing\nfrom typing import Any, List\nimport fvcore\nfrom fvcore.nn import activation_count, flop_count, parameter_count, parameter_count_table\nfrom torch import nn\n\nfrom detectron2.export import TracingAdapter\n\n__all__ = [\n    \"activation_count_operators\",\n    \"flop_count_operators\",\n    \"parameter_count_table\",\n    \"parameter_count\",\n    \"FlopCountAnalysis\",\n]\n\nFLOPS_MODE = \"flops\"\nACTIVATIONS_MODE = \"activations\"\n\n\n# Some extra ops to ignore from counting, including elementwise and reduction ops\n_IGNORED_OPS = {\n    \"aten::add\",\n    \"aten::add_\",\n    \"aten::argmax\",\n    \"aten::argsort\",\n    \"aten::batch_norm\",\n    \"aten::constant_pad_nd\",\n    \"aten::div\",\n    \"aten::div_\",\n    \"aten::exp\",\n    \"aten::log2\",\n    \"aten::max_pool2d\",\n    \"aten::meshgrid\",\n    \"aten::mul\",\n    \"aten::mul_\",\n    \"aten::neg\",\n    \"aten::nonzero_numpy\",\n    \"aten::reciprocal\",\n    \"aten::repeat_interleave\",\n    \"aten::rsub\",\n    \"aten::sigmoid\",\n    \"aten::sigmoid_\",\n    \"aten::softmax\",\n    \"aten::sort\",\n    \"aten::sqrt\",\n    \"aten::sub\",\n    \"torchvision::nms\",  # TODO estimate flop for nms\n}\n\n\nclass FlopCountAnalysis(fvcore.nn.FlopCountAnalysis):\n    \"\"\"\n    Same as :class:`fvcore.nn.FlopCountAnalysis`, but supports detectron2 models.\n    \"\"\"\n\n    def __init__(self, model, inputs):\n        \"\"\"\n        Args:\n            model (nn.Module):\n            inputs (Any): inputs of the given model. Does not have to be tuple of tensors.\n        \"\"\"\n        wrapper = TracingAdapter(model, inputs, allow_non_tensor=True)\n        super().__init__(wrapper, wrapper.flattened_inputs)\n        self.set_op_handle(**{k: None for k in _IGNORED_OPS})\n\n\ndef flop_count_operators(model: nn.Module, inputs: list) -> typing.DefaultDict[str, float]:\n    \"\"\"\n    Implement operator-level flops counting using jit.\n    This is a wrapper of :func:`fvcore.nn.flop_count` and adds supports for standard\n    detection models in detectron2.\n    Please use :class:`FlopCountAnalysis` for more advanced functionalities.\n\n    Note:\n        The function runs the input through the model to compute flops.\n        The flops of a detection model is often input-dependent, for example,\n        the flops of box & mask head depends on the number of proposals &\n        the number of detected objects.\n        Therefore, the flops counting using a single input may not accurately\n        reflect the computation cost of a model. It's recommended to average\n        across a number of inputs.\n\n    Args:\n        model: a detectron2 model that takes `list[dict]` as input.\n        inputs (list[dict]): inputs to model, in detectron2's standard format.\n            Only \"image\" key will be used.\n        supported_ops (dict[str, Handle]): see documentation of :func:`fvcore.nn.flop_count`\n\n    Returns:\n        Counter: Gflop count per operator\n    \"\"\"\n    old_train = model.training\n    model.eval()\n    ret = FlopCountAnalysis(model, inputs).by_operator()\n    model.train(old_train)\n    return {k: v / 1e9 for k, v in ret.items()}\n\n\ndef activation_count_operators(\n    model: nn.Module, inputs: list, **kwargs\n) -> typing.DefaultDict[str, float]:\n    \"\"\"\n    Implement operator-level activations counting using jit.\n    This is a wrapper of fvcore.nn.activation_count, that supports standard detection models\n    in detectron2.\n\n    Note:\n        The function runs the input through the model to compute activations.\n        The activations of a detection model is often input-dependent, for example,\n        the activations of box & mask head depends on the number of proposals &\n        the number of detected objects.\n\n    Args:\n        model: a detectron2 model that takes `list[dict]` as input.\n        inputs (list[dict]): inputs to model, in detectron2's standard format.\n            Only \"image\" key will be used.\n\n    Returns:\n        Counter: activation count per operator\n    \"\"\"\n    return _wrapper_count_operators(model=model, inputs=inputs, mode=ACTIVATIONS_MODE, **kwargs)\n\n\ndef _wrapper_count_operators(\n    model: nn.Module, inputs: list, mode: str, **kwargs\n) -> typing.DefaultDict[str, float]:\n    # ignore some ops\n    supported_ops = {k: lambda *args, **kwargs: {} for k in _IGNORED_OPS}\n    supported_ops.update(kwargs.pop(\"supported_ops\", {}))\n    kwargs[\"supported_ops\"] = supported_ops\n\n    assert len(inputs) == 1, \"Please use batch size=1\"\n    tensor_input = inputs[0][\"image\"]\n    inputs = [{\"image\": tensor_input}]  # remove other keys, in case there are any\n\n    old_train = model.training\n    if isinstance(model, (nn.parallel.distributed.DistributedDataParallel, nn.DataParallel)):\n        model = model.module\n    wrapper = TracingAdapter(model, inputs)\n    wrapper.eval()\n    if mode == FLOPS_MODE:\n        ret = flop_count(wrapper, (tensor_input,), **kwargs)\n    elif mode == ACTIVATIONS_MODE:\n        ret = activation_count(wrapper, (tensor_input,), **kwargs)\n    else:\n        raise NotImplementedError(\"Count for mode {} is not supported yet.\".format(mode))\n    # compatible with change in fvcore\n    if isinstance(ret, tuple):\n        ret = ret[0]\n    model.train(old_train)\n    return ret\n\n\ndef find_unused_parameters(model: nn.Module, inputs: Any) -> List[str]:\n    \"\"\"\n    Given a model, find parameters that do not contribute\n    to the loss.\n\n    Args:\n        model: a model in training mode that returns losses\n        inputs: argument or a tuple of arguments. Inputs of the model\n\n    Returns:\n        list[str]: the name of unused parameters\n    \"\"\"\n    assert model.training\n    for _, prm in model.named_parameters():\n        prm.grad = None\n\n    if isinstance(inputs, tuple):\n        losses = model(*inputs)\n    else:\n        losses = model(inputs)\n\n    if isinstance(losses, dict):\n        losses = sum(losses.values())\n    losses.backward()\n\n    unused: List[str] = []\n    for name, prm in model.named_parameters():\n        if prm.grad is None:\n            unused.append(name)\n        prm.grad = None\n    return unused\n"
  },
  {
    "path": "VPS_Module/detectron2/utils/collect_env.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport importlib\nimport numpy as np\nimport os\nimport re\nimport subprocess\nimport sys\nfrom collections import defaultdict\nimport PIL\nimport torch\nimport torchvision\nfrom tabulate import tabulate\n\n__all__ = [\"collect_env_info\"]\n\n\ndef collect_torch_env():\n    try:\n        import torch.__config__\n\n        return torch.__config__.show()\n    except ImportError:\n        # compatible with older versions of pytorch\n        from torch.utils.collect_env import get_pretty_env_info\n\n        return get_pretty_env_info()\n\n\ndef get_env_module():\n    var_name = \"DETECTRON2_ENV_MODULE\"\n    return var_name, os.environ.get(var_name, \"<not set>\")\n\n\ndef detect_compute_compatibility(CUDA_HOME, so_file):\n    try:\n        cuobjdump = os.path.join(CUDA_HOME, \"bin\", \"cuobjdump\")\n        if os.path.isfile(cuobjdump):\n            output = subprocess.check_output(\n                \"'{}' --list-elf '{}'\".format(cuobjdump, so_file), shell=True\n            )\n            output = output.decode(\"utf-8\").strip().split(\"\\n\")\n            arch = []\n            for line in output:\n                line = re.findall(r\"\\.sm_([0-9]*)\\.\", line)[0]\n                arch.append(\".\".join(line))\n            arch = sorted(set(arch))\n            return \", \".join(arch)\n        else:\n            return so_file + \"; cannot find cuobjdump\"\n    except Exception:\n        # unhandled failure\n        return so_file\n\n\ndef collect_env_info():\n    has_gpu = torch.cuda.is_available()  # true for both CUDA & ROCM\n    torch_version = torch.__version__\n\n    # NOTE that CUDA_HOME/ROCM_HOME could be None even when CUDA runtime libs are functional\n    from torch.utils.cpp_extension import CUDA_HOME, ROCM_HOME\n\n    has_rocm = False\n    if (getattr(torch.version, \"hip\", None) is not None) and (ROCM_HOME is not None):\n        has_rocm = True\n    has_cuda = has_gpu and (not has_rocm)\n\n    data = []\n    data.append((\"sys.platform\", sys.platform))  # check-template.yml depends on it\n    data.append((\"Python\", sys.version.replace(\"\\n\", \"\")))\n    data.append((\"numpy\", np.__version__))\n\n    try:\n        import detectron2  # noqa\n\n        data.append(\n            (\"detectron2\", detectron2.__version__ + \" @\" + os.path.dirname(detectron2.__file__))\n        )\n    except ImportError:\n        data.append((\"detectron2\", \"failed to import\"))\n    except AttributeError:\n        data.append((\"detectron2\", \"imported a wrong installation\"))\n\n    try:\n        import detectron2._C as _C\n    except ImportError as e:\n        data.append((\"detectron2._C\", f\"not built correctly: {e}\"))\n\n        # print system compilers when extension fails to build\n        if sys.platform != \"win32\":  # don't know what to do for windows\n            try:\n                # this is how torch/utils/cpp_extensions.py choose compiler\n                cxx = os.environ.get(\"CXX\", \"c++\")\n                cxx = subprocess.check_output(\"'{}' --version\".format(cxx), shell=True)\n                cxx = cxx.decode(\"utf-8\").strip().split(\"\\n\")[0]\n            except subprocess.SubprocessError:\n                cxx = \"Not found\"\n            data.append((\"Compiler ($CXX)\", cxx))\n\n            if has_cuda and CUDA_HOME is not None:\n                try:\n                    nvcc = os.path.join(CUDA_HOME, \"bin\", \"nvcc\")\n                    nvcc = subprocess.check_output(\"'{}' -V\".format(nvcc), shell=True)\n                    nvcc = nvcc.decode(\"utf-8\").strip().split(\"\\n\")[-1]\n                except subprocess.SubprocessError:\n                    nvcc = \"Not found\"\n                data.append((\"CUDA compiler\", nvcc))\n        if has_cuda and sys.platform != \"win32\":\n            try:\n                so_file = importlib.util.find_spec(\"detectron2._C\").origin\n            except (ImportError, AttributeError):\n                pass\n            else:\n                data.append(\n                    (\"detectron2 arch flags\", detect_compute_compatibility(CUDA_HOME, so_file))\n                )\n    else:\n        # print compilers that are used to build extension\n        data.append((\"Compiler\", _C.get_compiler_version()))\n        data.append((\"CUDA compiler\", _C.get_cuda_version()))  # cuda or hip\n        if has_cuda and getattr(_C, \"has_cuda\", lambda: True)():\n            data.append(\n                (\"detectron2 arch flags\", detect_compute_compatibility(CUDA_HOME, _C.__file__))\n            )\n\n    data.append(get_env_module())\n    data.append((\"PyTorch\", torch_version + \" @\" + os.path.dirname(torch.__file__)))\n    data.append((\"PyTorch debug build\", torch.version.debug))\n\n    if not has_gpu:\n        has_gpu_text = \"No: torch.cuda.is_available() == False\"\n    else:\n        has_gpu_text = \"Yes\"\n    data.append((\"GPU available\", has_gpu_text))\n    if has_gpu:\n        devices = defaultdict(list)\n        for k in range(torch.cuda.device_count()):\n            cap = \".\".join((str(x) for x in torch.cuda.get_device_capability(k)))\n            name = torch.cuda.get_device_name(k) + f\" (arch={cap})\"\n            devices[name].append(str(k))\n        for name, devids in devices.items():\n            data.append((\"GPU \" + \",\".join(devids), name))\n\n        if has_rocm:\n            msg = \" - invalid!\" if not (ROCM_HOME and os.path.isdir(ROCM_HOME)) else \"\"\n            data.append((\"ROCM_HOME\", str(ROCM_HOME) + msg))\n        else:\n            try:\n                from torch.utils.collect_env import get_nvidia_driver_version, run as _run\n\n                data.append((\"Driver version\", get_nvidia_driver_version(_run)))\n            except Exception:\n                pass\n            msg = \" - invalid!\" if not (CUDA_HOME and os.path.isdir(CUDA_HOME)) else \"\"\n            data.append((\"CUDA_HOME\", str(CUDA_HOME) + msg))\n\n            cuda_arch_list = os.environ.get(\"TORCH_CUDA_ARCH_LIST\", None)\n            if cuda_arch_list:\n                data.append((\"TORCH_CUDA_ARCH_LIST\", cuda_arch_list))\n    data.append((\"Pillow\", PIL.__version__))\n\n    try:\n        data.append(\n            (\n                \"torchvision\",\n                str(torchvision.__version__) + \" @\" + os.path.dirname(torchvision.__file__),\n            )\n        )\n        if has_cuda:\n            try:\n                torchvision_C = importlib.util.find_spec(\"torchvision._C\").origin\n                msg = detect_compute_compatibility(CUDA_HOME, torchvision_C)\n                data.append((\"torchvision arch flags\", msg))\n            except (ImportError, AttributeError):\n                data.append((\"torchvision._C\", \"Not found\"))\n    except AttributeError:\n        data.append((\"torchvision\", \"unknown\"))\n\n    try:\n        import fvcore\n\n        data.append((\"fvcore\", fvcore.__version__))\n    except (ImportError, AttributeError):\n        pass\n\n    try:\n        import iopath\n\n        data.append((\"iopath\", iopath.__version__))\n    except (ImportError, AttributeError):\n        pass\n\n    try:\n        import cv2\n\n        data.append((\"cv2\", cv2.__version__))\n    except (ImportError, AttributeError):\n        data.append((\"cv2\", \"Not found\"))\n    env_str = tabulate(data) + \"\\n\"\n    env_str += collect_torch_env()\n    return env_str\n\n\ndef test_nccl_ops():\n    num_gpu = torch.cuda.device_count()\n    if os.access(\"/tmp\", os.W_OK):\n        import torch.multiprocessing as mp\n\n        dist_url = \"file:///tmp/nccl_tmp_file\"\n        print(\"Testing NCCL connectivity ... this should not hang.\")\n        mp.spawn(_test_nccl_worker, nprocs=num_gpu, args=(num_gpu, dist_url), daemon=False)\n        print(\"NCCL succeeded.\")\n\n\ndef _test_nccl_worker(rank, num_gpu, dist_url):\n    import torch.distributed as dist\n\n    dist.init_process_group(backend=\"NCCL\", init_method=dist_url, rank=rank, world_size=num_gpu)\n    dist.barrier(device_ids=[rank])\n\n\nif __name__ == \"__main__\":\n    try:\n        from detectron2.utils.collect_env import collect_env_info as f\n\n        print(f())\n    except ImportError:\n        print(collect_env_info())\n\n    if torch.cuda.is_available():\n        num_gpu = torch.cuda.device_count()\n        for k in range(num_gpu):\n            device = f\"cuda:{k}\"\n            try:\n                x = torch.tensor([1, 2.0], dtype=torch.float32)\n                x = x.to(device)\n            except Exception as e:\n                print(\n                    f\"Unable to copy tensor to device={device}: {e}. \"\n                    \"Your CUDA environment is broken.\"\n                )\n        if num_gpu > 1:\n            test_nccl_ops()\n"
  },
  {
    "path": "VPS_Module/detectron2/utils/colormap.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\n\"\"\"\nAn awesome colormap for really neat visualizations.\nCopied from Detectron, and removed gray colors.\n\"\"\"\n\nimport numpy as np\n\n__all__ = [\"colormap\", \"random_color\"]\n\n# fmt: off\n# RGB:\n_COLORS = np.array(\n    [\n        0.000, 0.447, 0.741,\n        0.850, 0.325, 0.098,\n        0.929, 0.694, 0.125,\n        0.494, 0.184, 0.556,\n        0.466, 0.674, 0.188,\n        0.301, 0.745, 0.933,\n        0.635, 0.078, 0.184,\n        0.300, 0.300, 0.300,\n        0.600, 0.600, 0.600,\n        1.000, 0.000, 0.000,\n        1.000, 0.500, 0.000,\n        0.749, 0.749, 0.000,\n        0.000, 1.000, 0.000,\n        0.000, 0.000, 1.000,\n        0.667, 0.000, 1.000,\n        0.333, 0.333, 0.000,\n        0.333, 0.667, 0.000,\n        0.333, 1.000, 0.000,\n        0.667, 0.333, 0.000,\n        0.667, 0.667, 0.000,\n        0.667, 1.000, 0.000,\n        1.000, 0.333, 0.000,\n        1.000, 0.667, 0.000,\n        1.000, 1.000, 0.000,\n        0.000, 0.333, 0.500,\n        0.000, 0.667, 0.500,\n        0.000, 1.000, 0.500,\n        0.333, 0.000, 0.500,\n        0.333, 0.333, 0.500,\n        0.333, 0.667, 0.500,\n        0.333, 1.000, 0.500,\n        0.667, 0.000, 0.500,\n        0.667, 0.333, 0.500,\n        0.667, 0.667, 0.500,\n        0.667, 1.000, 0.500,\n        1.000, 0.000, 0.500,\n        1.000, 0.333, 0.500,\n        1.000, 0.667, 0.500,\n        1.000, 1.000, 0.500,\n        0.000, 0.333, 1.000,\n        0.000, 0.667, 1.000,\n        0.000, 1.000, 1.000,\n        0.333, 0.000, 1.000,\n        0.333, 0.333, 1.000,\n        0.333, 0.667, 1.000,\n        0.333, 1.000, 1.000,\n        0.667, 0.000, 1.000,\n        0.667, 0.333, 1.000,\n        0.667, 0.667, 1.000,\n        0.667, 1.000, 1.000,\n        1.000, 0.000, 1.000,\n        1.000, 0.333, 1.000,\n        1.000, 0.667, 1.000,\n        0.333, 0.000, 0.000,\n        0.500, 0.000, 0.000,\n        0.667, 0.000, 0.000,\n        0.833, 0.000, 0.000,\n        1.000, 0.000, 0.000,\n        0.000, 0.167, 0.000,\n        0.000, 0.333, 0.000,\n        0.000, 0.500, 0.000,\n        0.000, 0.667, 0.000,\n        0.000, 0.833, 0.000,\n        0.000, 1.000, 0.000,\n        0.000, 0.000, 0.167,\n        0.000, 0.000, 0.333,\n        0.000, 0.000, 0.500,\n        0.000, 0.000, 0.667,\n        0.000, 0.000, 0.833,\n        0.000, 0.000, 1.000,\n        0.000, 0.000, 0.000,\n        0.143, 0.143, 0.143,\n        0.857, 0.857, 0.857,\n        1.000, 1.000, 1.000\n    ]\n).astype(np.float32).reshape(-1, 3)\n# fmt: on\n\n\ndef colormap(rgb=False, maximum=255):\n    \"\"\"\n    Args:\n        rgb (bool): whether to return RGB colors or BGR colors.\n        maximum (int): either 255 or 1\n\n    Returns:\n        ndarray: a float32 array of Nx3 colors, in range [0, 255] or [0, 1]\n    \"\"\"\n    assert maximum in [255, 1], maximum\n    c = _COLORS * maximum\n    if not rgb:\n        c = c[:, ::-1]\n    return c\n\n\ndef random_color(rgb=False, maximum=255):\n    \"\"\"\n    Args:\n        rgb (bool): whether to return RGB colors or BGR colors.\n        maximum (int): either 255 or 1\n\n    Returns:\n        ndarray: a vector of 3 numbers\n    \"\"\"\n    idx = np.random.randint(0, len(_COLORS))\n    ret = _COLORS[idx] * maximum\n    if not rgb:\n        ret = ret[::-1]\n    return ret\n\n\nif __name__ == \"__main__\":\n    import cv2\n\n    size = 100\n    H, W = 10, 10\n    canvas = np.random.rand(H * size, W * size, 3).astype(\"float32\")\n    for h in range(H):\n        for w in range(W):\n            idx = h * W + w\n            if idx >= len(_COLORS):\n                break\n            canvas[h * size : (h + 1) * size, w * size : (w + 1) * size] = _COLORS[idx]\n    cv2.imshow(\"a\", canvas)\n    cv2.waitKey(0)\n"
  },
  {
    "path": "VPS_Module/detectron2/utils/comm.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\"\"\"\nThis file contains primitives for multi-gpu communication.\nThis is useful when doing distributed training.\n\"\"\"\n\nimport functools\nimport numpy as np\nimport torch\nimport torch.distributed as dist\n\n_LOCAL_PROCESS_GROUP = None\n\"\"\"\nA torch process group which only includes processes that on the same machine as the current process.\nThis variable is set when processes are spawned by `launch()` in \"engine/launch.py\".\n\"\"\"\n\n\ndef get_world_size() -> int:\n    if not dist.is_available():\n        return 1\n    if not dist.is_initialized():\n        return 1\n    return dist.get_world_size()\n\n\ndef get_rank() -> int:\n    if not dist.is_available():\n        return 0\n    if not dist.is_initialized():\n        return 0\n    return dist.get_rank()\n\n\ndef get_local_rank() -> int:\n    \"\"\"\n    Returns:\n        The rank of the current process within the local (per-machine) process group.\n    \"\"\"\n    if not dist.is_available():\n        return 0\n    if not dist.is_initialized():\n        return 0\n    assert (\n        _LOCAL_PROCESS_GROUP is not None\n    ), \"Local process group is not created! Please use launch() to spawn processes!\"\n    return dist.get_rank(group=_LOCAL_PROCESS_GROUP)\n\n\ndef get_local_size() -> int:\n    \"\"\"\n    Returns:\n        The size of the per-machine process group,\n        i.e. the number of processes per machine.\n    \"\"\"\n    if not dist.is_available():\n        return 1\n    if not dist.is_initialized():\n        return 1\n    return dist.get_world_size(group=_LOCAL_PROCESS_GROUP)\n\n\ndef is_main_process() -> bool:\n    return get_rank() == 0\n\n\ndef synchronize():\n    \"\"\"\n    Helper function to synchronize (barrier) among all processes when\n    using distributed training\n    \"\"\"\n    if not dist.is_available():\n        return\n    if not dist.is_initialized():\n        return\n    world_size = dist.get_world_size()\n    if world_size == 1:\n        return\n    if dist.get_backend() == dist.Backend.NCCL:\n        # This argument is needed to avoid warnings.\n        # It's valid only for NCCL backend.\n        dist.barrier(device_ids=[torch.cuda.current_device()])\n    else:\n        dist.barrier()\n\n\n@functools.lru_cache()\ndef _get_global_gloo_group():\n    \"\"\"\n    Return a process group based on gloo backend, containing all the ranks\n    The result is cached.\n    \"\"\"\n    if dist.get_backend() == \"nccl\":\n        return dist.new_group(backend=\"gloo\")\n    else:\n        return dist.group.WORLD\n\n\ndef all_gather(data, group=None):\n    \"\"\"\n    Run all_gather on arbitrary picklable data (not necessarily tensors).\n\n    Args:\n        data: any picklable object\n        group: a torch process group. By default, will use a group which\n            contains all ranks on gloo backend.\n\n    Returns:\n        list[data]: list of data gathered from each rank\n    \"\"\"\n    if get_world_size() == 1:\n        return [data]\n    if group is None:\n        group = _get_global_gloo_group()  # use CPU group by default, to reduce GPU RAM usage.\n    world_size = dist.get_world_size(group)\n    if world_size == 1:\n        return [data]\n\n    output = [None for _ in range(world_size)]\n    dist.all_gather_object(output, data, group=group)\n    return output\n\n\ndef gather(data, dst=0, group=None):\n    \"\"\"\n    Run gather on arbitrary picklable data (not necessarily tensors).\n\n    Args:\n        data: any picklable object\n        dst (int): destination rank\n        group: a torch process group. By default, will use a group which\n            contains all ranks on gloo backend.\n\n    Returns:\n        list[data]: on dst, a list of data gathered from each rank. Otherwise,\n            an empty list.\n    \"\"\"\n    if get_world_size() == 1:\n        return [data]\n    if group is None:\n        group = _get_global_gloo_group()\n    world_size = dist.get_world_size(group=group)\n    if world_size == 1:\n        return [data]\n    rank = dist.get_rank(group=group)\n\n    if rank == dst:\n        output = [None for _ in range(world_size)]\n        dist.gather_object(data, output, dst=dst, group=group)\n        return output\n    else:\n        dist.gather_object(data, None, dst=dst, group=group)\n        return []\n\n\ndef shared_random_seed():\n    \"\"\"\n    Returns:\n        int: a random number that is the same across all workers.\n        If workers need a shared RNG, they can use this shared seed to\n        create one.\n\n    All workers must call this function, otherwise it will deadlock.\n    \"\"\"\n    ints = np.random.randint(2 ** 31)\n    all_ints = all_gather(ints)\n    return all_ints[0]\n\n\ndef reduce_dict(input_dict, average=True):\n    \"\"\"\n    Reduce the values in the dictionary from all processes so that process with rank\n    0 has the reduced results.\n\n    Args:\n        input_dict (dict): inputs to be reduced. All the values must be scalar CUDA Tensor.\n        average (bool): whether to do average or sum\n\n    Returns:\n        a dict with the same keys as input_dict, after reduction.\n    \"\"\"\n    world_size = get_world_size()\n    if world_size < 2:\n        return input_dict\n    with torch.no_grad():\n        names = []\n        values = []\n        # sort the keys so that they are consistent across processes\n        for k in sorted(input_dict.keys()):\n            names.append(k)\n            values.append(input_dict[k])\n        values = torch.stack(values, dim=0)\n        dist.reduce(values, dst=0)\n        if dist.get_rank() == 0 and average:\n            # only main process gets accumulated, so only divide by\n            # world_size in this case\n            values /= world_size\n        reduced_dict = {k: v for k, v in zip(names, values)}\n    return reduced_dict\n"
  },
  {
    "path": "VPS_Module/detectron2/utils/env.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport importlib\nimport importlib.util\nimport logging\nimport numpy as np\nimport os\nimport random\nimport sys\nfrom datetime import datetime\nimport torch\n\n__all__ = [\"seed_all_rng\"]\n\n\nTORCH_VERSION = tuple(int(x) for x in torch.__version__.split(\".\")[:2])\n\"\"\"\nPyTorch version as a tuple of 2 ints. Useful for comparison.\n\"\"\"\n\n\nDOC_BUILDING = os.getenv(\"_DOC_BUILDING\", False)  # set in docs/conf.py\n\"\"\"\nWhether we're building documentation.\n\"\"\"\n\n\ndef seed_all_rng(seed=None):\n    \"\"\"\n    Set the random seed for the RNG in torch, numpy and python.\n\n    Args:\n        seed (int): if None, will use a strong random seed.\n    \"\"\"\n    if seed is None:\n        seed = (\n            os.getpid()\n            + int(datetime.now().strftime(\"%S%f\"))\n            + int.from_bytes(os.urandom(2), \"big\")\n        )\n        logger = logging.getLogger(__name__)\n        logger.info(\"Using a generated random seed {}\".format(seed))\n    np.random.seed(seed)\n    torch.manual_seed(seed)\n    random.seed(seed)\n    os.environ[\"PYTHONHASHSEED\"] = str(seed)\n\n\n# from https://stackoverflow.com/questions/67631/how-to-import-a-module-given-the-full-path\ndef _import_file(module_name, file_path, make_importable=False):\n    spec = importlib.util.spec_from_file_location(module_name, file_path)\n    module = importlib.util.module_from_spec(spec)\n    spec.loader.exec_module(module)\n    if make_importable:\n        sys.modules[module_name] = module\n    return module\n\n\ndef _configure_libraries():\n    \"\"\"\n    Configurations for some libraries.\n    \"\"\"\n    # An environment option to disable `import cv2` globally,\n    # in case it leads to negative performance impact\n    disable_cv2 = int(os.environ.get(\"DETECTRON2_DISABLE_CV2\", False))\n    if disable_cv2:\n        sys.modules[\"cv2\"] = None\n    else:\n        # Disable opencl in opencv since its interaction with cuda often has negative effects\n        # This envvar is supported after OpenCV 3.4.0\n        os.environ[\"OPENCV_OPENCL_RUNTIME\"] = \"disabled\"\n        try:\n            import cv2\n\n            if int(cv2.__version__.split(\".\")[0]) >= 3:\n                cv2.ocl.setUseOpenCL(False)\n        except ModuleNotFoundError:\n            # Other types of ImportError, if happened, should not be ignored.\n            # Because a failed opencv import could mess up address space\n            # https://github.com/skvark/opencv-python/issues/381\n            pass\n\n    def get_version(module, digit=2):\n        return tuple(map(int, module.__version__.split(\".\")[:digit]))\n\n    # fmt: off\n    assert get_version(torch) >= (1, 4), \"Requires torch>=1.4\"\n    import fvcore\n    assert get_version(fvcore, 3) >= (0, 1, 2), \"Requires fvcore>=0.1.2\"\n    import yaml\n    assert get_version(yaml) >= (5, 1), \"Requires pyyaml>=5.1\"\n    # fmt: on\n\n\n_ENV_SETUP_DONE = False\n\n\ndef setup_environment():\n    \"\"\"Perform environment setup work. The default setup is a no-op, but this\n    function allows the user to specify a Python source file or a module in\n    the $DETECTRON2_ENV_MODULE environment variable, that performs\n    custom setup work that may be necessary to their computing environment.\n    \"\"\"\n    global _ENV_SETUP_DONE\n    if _ENV_SETUP_DONE:\n        return\n    _ENV_SETUP_DONE = True\n\n    _configure_libraries()\n\n    custom_module_path = os.environ.get(\"DETECTRON2_ENV_MODULE\")\n\n    if custom_module_path:\n        setup_custom_environment(custom_module_path)\n    else:\n        # The default setup is a no-op\n        pass\n\n\ndef setup_custom_environment(custom_module):\n    \"\"\"\n    Load custom environment setup by importing a Python source file or a\n    module, and run the setup function.\n    \"\"\"\n    if custom_module.endswith(\".py\"):\n        module = _import_file(\"detectron2.utils.env.custom_module\", custom_module)\n    else:\n        module = importlib.import_module(custom_module)\n    assert hasattr(module, \"setup_environment\") and callable(module.setup_environment), (\n        \"Custom environment module defined in {} does not have the \"\n        \"required callable attribute 'setup_environment'.\"\n    ).format(custom_module)\n    module.setup_environment()\n\n\ndef fixup_module_metadata(module_name, namespace, keys=None):\n    \"\"\"\n    Fix the __qualname__ of module members to be their exported api name, so\n    when they are referenced in docs, sphinx can find them. Reference:\n    https://github.com/python-trio/trio/blob/6754c74eacfad9cc5c92d5c24727a2f3b620624e/trio/_util.py#L216-L241\n    \"\"\"\n    if not DOC_BUILDING:\n        return\n    seen_ids = set()\n\n    def fix_one(qualname, name, obj):\n        # avoid infinite recursion (relevant when using\n        # typing.Generic, for example)\n        if id(obj) in seen_ids:\n            return\n        seen_ids.add(id(obj))\n\n        mod = getattr(obj, \"__module__\", None)\n        if mod is not None and (mod.startswith(module_name) or mod.startswith(\"fvcore.\")):\n            obj.__module__ = module_name\n            # Modules, unlike everything else in Python, put fully-qualitied\n            # names into their __name__ attribute. We check for \".\" to avoid\n            # rewriting these.\n            if hasattr(obj, \"__name__\") and \".\" not in obj.__name__:\n                obj.__name__ = name\n                obj.__qualname__ = qualname\n            if isinstance(obj, type):\n                for attr_name, attr_value in obj.__dict__.items():\n                    fix_one(objname + \".\" + attr_name, attr_name, attr_value)\n\n    if keys is None:\n        keys = namespace.keys()\n    for objname in keys:\n        if not objname.startswith(\"_\"):\n            obj = namespace[objname]\n            fix_one(objname, objname, obj)\n"
  },
  {
    "path": "VPS_Module/detectron2/utils/events.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport datetime\nimport json\nimport logging\nimport os\nimport time\nfrom collections import defaultdict\nfrom contextlib import contextmanager\nfrom typing import Optional\nimport torch\nfrom fvcore.common.history_buffer import HistoryBuffer\n\nfrom detectron2.utils.file_io import PathManager\n\n__all__ = [\n    \"get_event_storage\",\n    \"JSONWriter\",\n    \"TensorboardXWriter\",\n    \"CommonMetricPrinter\",\n    \"EventStorage\",\n]\n\n_CURRENT_STORAGE_STACK = []\n\n\ndef get_event_storage():\n    \"\"\"\n    Returns:\n        The :class:`EventStorage` object that's currently being used.\n        Throws an error if no :class:`EventStorage` is currently enabled.\n    \"\"\"\n    assert len(\n        _CURRENT_STORAGE_STACK\n    ), \"get_event_storage() has to be called inside a 'with EventStorage(...)' context!\"\n    return _CURRENT_STORAGE_STACK[-1]\n\n\nclass EventWriter:\n    \"\"\"\n    Base class for writers that obtain events from :class:`EventStorage` and process them.\n    \"\"\"\n\n    def write(self):\n        raise NotImplementedError\n\n    def close(self):\n        pass\n\n\nclass JSONWriter(EventWriter):\n    \"\"\"\n    Write scalars to a json file.\n\n    It saves scalars as one json per line (instead of a big json) for easy parsing.\n\n    Examples parsing such a json file:\n    ::\n        $ cat metrics.json | jq -s '.[0:2]'\n        [\n          {\n            \"data_time\": 0.008433341979980469,\n            \"iteration\": 19,\n            \"loss\": 1.9228371381759644,\n            \"loss_box_reg\": 0.050025828182697296,\n            \"loss_classifier\": 0.5316952466964722,\n            \"loss_mask\": 0.7236229181289673,\n            \"loss_rpn_box\": 0.0856662318110466,\n            \"loss_rpn_cls\": 0.48198649287223816,\n            \"lr\": 0.007173333333333333,\n            \"time\": 0.25401854515075684\n          },\n          {\n            \"data_time\": 0.007216215133666992,\n            \"iteration\": 39,\n            \"loss\": 1.282649278640747,\n            \"loss_box_reg\": 0.06222952902317047,\n            \"loss_classifier\": 0.30682939291000366,\n            \"loss_mask\": 0.6970193982124329,\n            \"loss_rpn_box\": 0.038663312792778015,\n            \"loss_rpn_cls\": 0.1471673548221588,\n            \"lr\": 0.007706666666666667,\n            \"time\": 0.2490077018737793\n          }\n        ]\n\n        $ cat metrics.json | jq '.loss_mask'\n        0.7126231789588928\n        0.689423680305481\n        0.6776131987571716\n        ...\n\n    \"\"\"\n\n    def __init__(self, json_file, window_size=20):\n        \"\"\"\n        Args:\n            json_file (str): path to the json file. New data will be appended if the file exists.\n            window_size (int): the window size of median smoothing for the scalars whose\n                `smoothing_hint` are True.\n        \"\"\"\n        self._file_handle = PathManager.open(json_file, \"a\")\n        self._window_size = window_size\n        self._last_write = -1\n\n    def write(self):\n        storage = get_event_storage()\n        to_save = defaultdict(dict)\n\n        for k, (v, iter) in storage.latest_with_smoothing_hint(self._window_size).items():\n            # keep scalars that have not been written\n            if iter <= self._last_write:\n                continue\n            to_save[iter][k] = v\n        if len(to_save):\n            all_iters = sorted(to_save.keys())\n            self._last_write = max(all_iters)\n\n        for itr, scalars_per_iter in to_save.items():\n            scalars_per_iter[\"iteration\"] = itr\n            self._file_handle.write(json.dumps(scalars_per_iter, sort_keys=True) + \"\\n\")\n        self._file_handle.flush()\n        try:\n            os.fsync(self._file_handle.fileno())\n        except AttributeError:\n            pass\n\n    def close(self):\n        self._file_handle.close()\n\n\nclass TensorboardXWriter(EventWriter):\n    \"\"\"\n    Write all scalars to a tensorboard file.\n    \"\"\"\n\n    def __init__(self, log_dir: str, window_size: int = 20, **kwargs):\n        \"\"\"\n        Args:\n            log_dir (str): the directory to save the output events\n            window_size (int): the scalars will be median-smoothed by this window size\n\n            kwargs: other arguments passed to `torch.utils.tensorboard.SummaryWriter(...)`\n        \"\"\"\n        self._window_size = window_size\n        from torch.utils.tensorboard import SummaryWriter\n\n        self._writer = SummaryWriter(log_dir, **kwargs)\n        self._last_write = -1\n\n    def write(self):\n        storage = get_event_storage()\n        new_last_write = self._last_write\n        for k, (v, iter) in storage.latest_with_smoothing_hint(self._window_size).items():\n            if iter > self._last_write:\n                self._writer.add_scalar(k, v, iter)\n                new_last_write = max(new_last_write, iter)\n        self._last_write = new_last_write\n\n        # storage.put_{image,histogram} is only meant to be used by\n        # tensorboard writer. So we access its internal fields directly from here.\n        if len(storage._vis_data) >= 1:\n            for img_name, img, step_num in storage._vis_data:\n                self._writer.add_image(img_name, img, step_num)\n            # Storage stores all image data and rely on this writer to clear them.\n            # As a result it assumes only one writer will use its image data.\n            # An alternative design is to let storage store limited recent\n            # data (e.g. only the most recent image) that all writers can access.\n            # In that case a writer may not see all image data if its period is long.\n            storage.clear_images()\n\n        if len(storage._histograms) >= 1:\n            for params in storage._histograms:\n                self._writer.add_histogram_raw(**params)\n            storage.clear_histograms()\n\n    def close(self):\n        if hasattr(self, \"_writer\"):  # doesn't exist when the code fails at import\n            self._writer.close()\n\n\nclass CommonMetricPrinter(EventWriter):\n    \"\"\"\n    Print **common** metrics to the terminal, including\n    iteration time, ETA, memory, all losses, and the learning rate.\n    It also applies smoothing using a window of 20 elements.\n\n    It's meant to print common metrics in common ways.\n    To print something in more customized ways, please implement a similar printer by yourself.\n    \"\"\"\n\n    def __init__(self, max_iter: Optional[int] = None, window_size: int = 20):\n        \"\"\"\n        Args:\n            max_iter: the maximum number of iterations to train.\n                Used to compute ETA. If not given, ETA will not be printed.\n            window_size (int): the losses will be median-smoothed by this window size\n        \"\"\"\n        self.logger = logging.getLogger(__name__)\n        self._max_iter = max_iter\n        self._window_size = window_size\n        self._last_write = None  # (step, time) of last call to write(). Used to compute ETA\n\n    def _get_eta(self, storage) -> Optional[str]:\n        if self._max_iter is None:\n            return \"\"\n        iteration = storage.iter\n        try:\n            eta_seconds = storage.history(\"time\").median(1000) * (self._max_iter - iteration - 1)\n            storage.put_scalar(\"eta_seconds\", eta_seconds, smoothing_hint=False)\n            return str(datetime.timedelta(seconds=int(eta_seconds)))\n        except KeyError:\n            # estimate eta on our own - more noisy\n            eta_string = None\n            if self._last_write is not None:\n                estimate_iter_time = (time.perf_counter() - self._last_write[1]) / (\n                    iteration - self._last_write[0]\n                )\n                eta_seconds = estimate_iter_time * (self._max_iter - iteration - 1)\n                eta_string = str(datetime.timedelta(seconds=int(eta_seconds)))\n            self._last_write = (iteration, time.perf_counter())\n            return eta_string\n\n    def write(self):\n        storage = get_event_storage()\n        iteration = storage.iter\n        if iteration == self._max_iter:\n            # This hook only reports training progress (loss, ETA, etc) but not other data,\n            # therefore do not write anything after training succeeds, even if this method\n            # is called.\n            return\n\n        try:\n            data_time = storage.history(\"data_time\").avg(20)\n        except KeyError:\n            # they may not exist in the first few iterations (due to warmup)\n            # or when SimpleTrainer is not used\n            data_time = None\n        try:\n            iter_time = storage.history(\"time\").global_avg()\n        except KeyError:\n            iter_time = None\n        try:\n            lr = \"{:.5g}\".format(storage.history(\"lr\").latest())\n        except KeyError:\n            lr = \"N/A\"\n\n        eta_string = self._get_eta(storage)\n\n        if torch.cuda.is_available():\n            max_mem_mb = torch.cuda.max_memory_allocated() / 1024.0 / 1024.0\n        else:\n            max_mem_mb = None\n\n        # NOTE: max_mem is parsed by grep in \"dev/parse_results.sh\"\n        self.logger.info(\n            \" {eta}iter: {iter}  {losses}  {time}{data_time}lr: {lr}  {memory}\".format(\n                eta=f\"eta: {eta_string}  \" if eta_string else \"\",\n                iter=iteration,\n                losses=\"  \".join(\n                    [\n                        \"{}: {:.4g}\".format(k, v.median(self._window_size))\n                        for k, v in storage.histories().items()\n                        if \"loss\" in k\n                    ]\n                ),\n                time=\"time: {:.4f}  \".format(iter_time) if iter_time is not None else \"\",\n                data_time=\"data_time: {:.4f}  \".format(data_time) if data_time is not None else \"\",\n                lr=lr,\n                memory=\"max_mem: {:.0f}M\".format(max_mem_mb) if max_mem_mb is not None else \"\",\n            )\n        )\n\n\nclass EventStorage:\n    \"\"\"\n    The user-facing class that provides metric storage functionalities.\n\n    In the future we may add support for storing / logging other types of data if needed.\n    \"\"\"\n\n    def __init__(self, start_iter=0):\n        \"\"\"\n        Args:\n            start_iter (int): the iteration number to start with\n        \"\"\"\n        self._history = defaultdict(HistoryBuffer)\n        self._smoothing_hints = {}\n        self._latest_scalars = {}\n        self._iter = start_iter\n        self._current_prefix = \"\"\n        self._vis_data = []\n        self._histograms = []\n\n    def put_image(self, img_name, img_tensor):\n        \"\"\"\n        Add an `img_tensor` associated with `img_name`, to be shown on\n        tensorboard.\n\n        Args:\n            img_name (str): The name of the image to put into tensorboard.\n            img_tensor (torch.Tensor or numpy.array): An `uint8` or `float`\n                Tensor of shape `[channel, height, width]` where `channel` is\n                3. The image format should be RGB. The elements in img_tensor\n                can either have values in [0, 1] (float32) or [0, 255] (uint8).\n                The `img_tensor` will be visualized in tensorboard.\n        \"\"\"\n        self._vis_data.append((img_name, img_tensor, self._iter))\n\n    def put_scalar(self, name, value, smoothing_hint=True):\n        \"\"\"\n        Add a scalar `value` to the `HistoryBuffer` associated with `name`.\n\n        Args:\n            smoothing_hint (bool): a 'hint' on whether this scalar is noisy and should be\n                smoothed when logged. The hint will be accessible through\n                :meth:`EventStorage.smoothing_hints`.  A writer may ignore the hint\n                and apply custom smoothing rule.\n\n                It defaults to True because most scalars we save need to be smoothed to\n                provide any useful signal.\n        \"\"\"\n        name = self._current_prefix + name\n        history = self._history[name]\n        value = float(value)\n        history.update(value, self._iter)\n        self._latest_scalars[name] = (value, self._iter)\n\n        existing_hint = self._smoothing_hints.get(name)\n        if existing_hint is not None:\n            assert (\n                existing_hint == smoothing_hint\n            ), \"Scalar {} was put with a different smoothing_hint!\".format(name)\n        else:\n            self._smoothing_hints[name] = smoothing_hint\n\n    def put_scalars(self, *, smoothing_hint=True, **kwargs):\n        \"\"\"\n        Put multiple scalars from keyword arguments.\n\n        Examples:\n\n            storage.put_scalars(loss=my_loss, accuracy=my_accuracy, smoothing_hint=True)\n        \"\"\"\n        for k, v in kwargs.items():\n            self.put_scalar(k, v, smoothing_hint=smoothing_hint)\n\n    def put_histogram(self, hist_name, hist_tensor, bins=1000):\n        \"\"\"\n        Create a histogram from a tensor.\n\n        Args:\n            hist_name (str): The name of the histogram to put into tensorboard.\n            hist_tensor (torch.Tensor): A Tensor of arbitrary shape to be converted\n                into a histogram.\n            bins (int): Number of histogram bins.\n        \"\"\"\n        ht_min, ht_max = hist_tensor.min().item(), hist_tensor.max().item()\n\n        # Create a histogram with PyTorch\n        hist_counts = torch.histc(hist_tensor, bins=bins)\n        hist_edges = torch.linspace(start=ht_min, end=ht_max, steps=bins + 1, dtype=torch.float32)\n\n        # Parameter for the add_histogram_raw function of SummaryWriter\n        hist_params = dict(\n            tag=hist_name,\n            min=ht_min,\n            max=ht_max,\n            num=len(hist_tensor),\n            sum=float(hist_tensor.sum()),\n            sum_squares=float(torch.sum(hist_tensor ** 2)),\n            bucket_limits=hist_edges[1:].tolist(),\n            bucket_counts=hist_counts.tolist(),\n            global_step=self._iter,\n        )\n        self._histograms.append(hist_params)\n\n    def history(self, name):\n        \"\"\"\n        Returns:\n            HistoryBuffer: the scalar history for name\n        \"\"\"\n        ret = self._history.get(name, None)\n        if ret is None:\n            raise KeyError(\"No history metric available for {}!\".format(name))\n        return ret\n\n    def histories(self):\n        \"\"\"\n        Returns:\n            dict[name -> HistoryBuffer]: the HistoryBuffer for all scalars\n        \"\"\"\n        return self._history\n\n    def latest(self):\n        \"\"\"\n        Returns:\n            dict[str -> (float, int)]: mapping from the name of each scalar to the most\n                recent value and the iteration number its added.\n        \"\"\"\n        return self._latest_scalars\n\n    def latest_with_smoothing_hint(self, window_size=20):\n        \"\"\"\n        Similar to :meth:`latest`, but the returned values\n        are either the un-smoothed original latest value,\n        or a median of the given window_size,\n        depend on whether the smoothing_hint is True.\n\n        This provides a default behavior that other writers can use.\n        \"\"\"\n        result = {}\n        for k, (v, itr) in self._latest_scalars.items():\n            result[k] = (\n                self._history[k].median(window_size) if self._smoothing_hints[k] else v,\n                itr,\n            )\n        return result\n\n    def smoothing_hints(self):\n        \"\"\"\n        Returns:\n            dict[name -> bool]: the user-provided hint on whether the scalar\n                is noisy and needs smoothing.\n        \"\"\"\n        return self._smoothing_hints\n\n    def step(self):\n        \"\"\"\n        User should either: (1) Call this function to increment storage.iter when needed. Or\n        (2) Set `storage.iter` to the correct iteration number before each iteration.\n\n        The storage will then be able to associate the new data with an iteration number.\n        \"\"\"\n        self._iter += 1\n\n    @property\n    def iter(self):\n        \"\"\"\n        Returns:\n            int: The current iteration number. When used together with a trainer,\n                this is ensured to be the same as trainer.iter.\n        \"\"\"\n        return self._iter\n\n    @iter.setter\n    def iter(self, val):\n        self._iter = int(val)\n\n    @property\n    def iteration(self):\n        # for backward compatibility\n        return self._iter\n\n    def __enter__(self):\n        _CURRENT_STORAGE_STACK.append(self)\n        return self\n\n    def __exit__(self, exc_type, exc_val, exc_tb):\n        assert _CURRENT_STORAGE_STACK[-1] == self\n        _CURRENT_STORAGE_STACK.pop()\n\n    @contextmanager\n    def name_scope(self, name):\n        \"\"\"\n        Yields:\n            A context within which all the events added to this storage\n            will be prefixed by the name scope.\n        \"\"\"\n        old_prefix = self._current_prefix\n        self._current_prefix = name.rstrip(\"/\") + \"/\"\n        yield\n        self._current_prefix = old_prefix\n\n    def clear_images(self):\n        \"\"\"\n        Delete all the stored images for visualization. This should be called\n        after images are written to tensorboard.\n        \"\"\"\n        self._vis_data = []\n\n    def clear_histograms(self):\n        \"\"\"\n        Delete all the stored histograms for visualization.\n        This should be called after histograms are written to tensorboard.\n        \"\"\"\n        self._histograms = []\n"
  },
  {
    "path": "VPS_Module/detectron2/utils/file_io.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom iopath.common.file_io import HTTPURLHandler, OneDrivePathHandler, PathHandler\nfrom iopath.common.file_io import PathManager as PathManagerBase\n\n__all__ = [\"PathManager\", \"PathHandler\"]\n\n\nPathManager = PathManagerBase()\n\"\"\"\nThis is a detectron2 project-specific PathManager.\nWe try to stay away from global PathManager in fvcore as it\nintroduces potential conflicts among other libraries.\n\"\"\"\n\n\nclass Detectron2Handler(PathHandler):\n    \"\"\"\n    Resolve anything that's hosted under detectron2's namespace.\n    \"\"\"\n\n    PREFIX = \"detectron2://\"\n    S3_DETECTRON2_PREFIX = \"https://dl.fbaipublicfiles.com/detectron2/\"\n\n    def _get_supported_prefixes(self):\n        return [self.PREFIX]\n\n    def _get_local_path(self, path, **kwargs):\n        name = path[len(self.PREFIX) :]\n        return PathManager.get_local_path(self.S3_DETECTRON2_PREFIX + name, **kwargs)\n\n    def _open(self, path, mode=\"r\", **kwargs):\n        return PathManager.open(self._get_local_path(path), mode, **kwargs)\n\n\nPathManager.register_handler(HTTPURLHandler())\nPathManager.register_handler(OneDrivePathHandler())\nPathManager.register_handler(Detectron2Handler())\n"
  },
  {
    "path": "VPS_Module/detectron2/utils/logger.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport atexit\nimport functools\nimport logging\nimport os\nimport sys\nimport time\nfrom collections import Counter\nimport torch\nfrom tabulate import tabulate\nfrom termcolor import colored\n\nfrom detectron2.utils.file_io import PathManager\n\n__all__ = [\"setup_logger\", \"log_first_n\", \"log_every_n\", \"log_every_n_seconds\"]\n\n\nclass _ColorfulFormatter(logging.Formatter):\n    def __init__(self, *args, **kwargs):\n        self._root_name = kwargs.pop(\"root_name\") + \".\"\n        self._abbrev_name = kwargs.pop(\"abbrev_name\", \"\")\n        if len(self._abbrev_name):\n            self._abbrev_name = self._abbrev_name + \".\"\n        super(_ColorfulFormatter, self).__init__(*args, **kwargs)\n\n    def formatMessage(self, record):\n        record.name = record.name.replace(self._root_name, self._abbrev_name)\n        log = super(_ColorfulFormatter, self).formatMessage(record)\n        if record.levelno == logging.WARNING:\n            prefix = colored(\"WARNING\", \"red\", attrs=[\"blink\"])\n        elif record.levelno == logging.ERROR or record.levelno == logging.CRITICAL:\n            prefix = colored(\"ERROR\", \"red\", attrs=[\"blink\", \"underline\"])\n        else:\n            return log\n        return prefix + \" \" + log\n\n\n@functools.lru_cache()  # so that calling setup_logger multiple times won't add many handlers\ndef setup_logger(\n    output=None, distributed_rank=0, *, color=True, name=\"detectron2\", abbrev_name=None\n):\n    \"\"\"\n    Initialize the detectron2 logger and set its verbosity level to \"DEBUG\".\n\n    Args:\n        output (str): a file name or a directory to save log. If None, will not save log file.\n            If ends with \".txt\" or \".log\", assumed to be a file name.\n            Otherwise, logs will be saved to `output/log.txt`.\n        name (str): the root module name of this logger\n        abbrev_name (str): an abbreviation of the module, to avoid long names in logs.\n            Set to \"\" to not log the root module in logs.\n            By default, will abbreviate \"detectron2\" to \"d2\" and leave other\n            modules unchanged.\n\n    Returns:\n        logging.Logger: a logger\n    \"\"\"\n    logger = logging.getLogger(name)\n    logger.setLevel(logging.DEBUG)\n    logger.propagate = False\n\n    if abbrev_name is None:\n        abbrev_name = \"d2\" if name == \"detectron2\" else name\n\n    plain_formatter = logging.Formatter(\n        \"[%(asctime)s] %(name)s %(levelname)s: %(message)s\", datefmt=\"%m/%d %H:%M:%S\"\n    )\n    # stdout logging: master only\n    if distributed_rank == 0:\n        ch = logging.StreamHandler(stream=sys.stdout)\n        ch.setLevel(logging.DEBUG)\n        if color:\n            formatter = _ColorfulFormatter(\n                colored(\"[%(asctime)s %(name)s]: \", \"green\") + \"%(message)s\",\n                datefmt=\"%m/%d %H:%M:%S\",\n                root_name=name,\n                abbrev_name=str(abbrev_name),\n            )\n        else:\n            formatter = plain_formatter\n        ch.setFormatter(formatter)\n        logger.addHandler(ch)\n\n    # file logging: all workers\n    if output is not None:\n        if output.endswith(\".txt\") or output.endswith(\".log\"):\n            filename = output\n        else:\n            filename = os.path.join(output, \"log.txt\")\n        if distributed_rank > 0:\n            filename = filename + \".rank{}\".format(distributed_rank)\n        PathManager.mkdirs(os.path.dirname(filename))\n\n        fh = logging.StreamHandler(_cached_log_stream(filename))\n        fh.setLevel(logging.DEBUG)\n        fh.setFormatter(plain_formatter)\n        logger.addHandler(fh)\n\n    return logger\n\n\n# cache the opened file object, so that different calls to `setup_logger`\n# with the same file name can safely write to the same file.\n@functools.lru_cache(maxsize=None)\ndef _cached_log_stream(filename):\n    # use 1K buffer if writing to cloud storage\n    io = PathManager.open(filename, \"a\", buffering=1024 if \"://\" in filename else -1)\n    atexit.register(io.close)\n    return io\n\n\n\"\"\"\nBelow are some other convenient logging methods.\nThey are mainly adopted from\nhttps://github.com/abseil/abseil-py/blob/master/absl/logging/__init__.py\n\"\"\"\n\n\ndef _find_caller():\n    \"\"\"\n    Returns:\n        str: module name of the caller\n        tuple: a hashable key to be used to identify different callers\n    \"\"\"\n    frame = sys._getframe(2)\n    while frame:\n        code = frame.f_code\n        if os.path.join(\"utils\", \"logger.\") not in code.co_filename:\n            mod_name = frame.f_globals[\"__name__\"]\n            if mod_name == \"__main__\":\n                mod_name = \"detectron2\"\n            return mod_name, (code.co_filename, frame.f_lineno, code.co_name)\n        frame = frame.f_back\n\n\n_LOG_COUNTER = Counter()\n_LOG_TIMER = {}\n\n\ndef log_first_n(lvl, msg, n=1, *, name=None, key=\"caller\"):\n    \"\"\"\n    Log only for the first n times.\n\n    Args:\n        lvl (int): the logging level\n        msg (str):\n        n (int):\n        name (str): name of the logger to use. Will use the caller's module by default.\n        key (str or tuple[str]): the string(s) can be one of \"caller\" or\n            \"message\", which defines how to identify duplicated logs.\n            For example, if called with `n=1, key=\"caller\"`, this function\n            will only log the first call from the same caller, regardless of\n            the message content.\n            If called with `n=1, key=\"message\"`, this function will log the\n            same content only once, even if they are called from different places.\n            If called with `n=1, key=(\"caller\", \"message\")`, this function\n            will not log only if the same caller has logged the same message before.\n    \"\"\"\n    if isinstance(key, str):\n        key = (key,)\n    assert len(key) > 0\n\n    caller_module, caller_key = _find_caller()\n    hash_key = ()\n    if \"caller\" in key:\n        hash_key = hash_key + caller_key\n    if \"message\" in key:\n        hash_key = hash_key + (msg,)\n\n    _LOG_COUNTER[hash_key] += 1\n    if _LOG_COUNTER[hash_key] <= n:\n        logging.getLogger(name or caller_module).log(lvl, msg)\n\n\ndef log_every_n(lvl, msg, n=1, *, name=None):\n    \"\"\"\n    Log once per n times.\n\n    Args:\n        lvl (int): the logging level\n        msg (str):\n        n (int):\n        name (str): name of the logger to use. Will use the caller's module by default.\n    \"\"\"\n    caller_module, key = _find_caller()\n    _LOG_COUNTER[key] += 1\n    if n == 1 or _LOG_COUNTER[key] % n == 1:\n        logging.getLogger(name or caller_module).log(lvl, msg)\n\n\ndef log_every_n_seconds(lvl, msg, n=1, *, name=None):\n    \"\"\"\n    Log no more than once per n seconds.\n\n    Args:\n        lvl (int): the logging level\n        msg (str):\n        n (int):\n        name (str): name of the logger to use. Will use the caller's module by default.\n    \"\"\"\n    caller_module, key = _find_caller()\n    last_logged = _LOG_TIMER.get(key, None)\n    current_time = time.time()\n    if last_logged is None or current_time - last_logged >= n:\n        logging.getLogger(name or caller_module).log(lvl, msg)\n        _LOG_TIMER[key] = current_time\n\n\ndef create_small_table(small_dict):\n    \"\"\"\n    Create a small table using the keys of small_dict as headers. This is only\n    suitable for small dictionaries.\n\n    Args:\n        small_dict (dict): a result dictionary of only a few items.\n\n    Returns:\n        str: the table as a string.\n    \"\"\"\n    keys, values = tuple(zip(*small_dict.items()))\n    table = tabulate(\n        [values],\n        headers=keys,\n        tablefmt=\"pipe\",\n        floatfmt=\".3f\",\n        stralign=\"center\",\n        numalign=\"center\",\n    )\n    return table\n\n\ndef _log_api_usage(identifier: str):\n    \"\"\"\n    Internal function used to log the usage of different detectron2 components\n    inside facebook's infra.\n    \"\"\"\n    torch._C._log_api_usage_once(\"detectron2.\" + identifier)\n"
  },
  {
    "path": "VPS_Module/detectron2/utils/memory.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport logging\nfrom contextlib import contextmanager\nfrom functools import wraps\nimport torch\n\n__all__ = [\"retry_if_cuda_oom\"]\n\n\n@contextmanager\ndef _ignore_torch_cuda_oom():\n    \"\"\"\n    A context which ignores CUDA OOM exception from pytorch.\n    \"\"\"\n    try:\n        yield\n    except RuntimeError as e:\n        # NOTE: the string may change?\n        if \"CUDA out of memory. \" in str(e):\n            pass\n        else:\n            raise\n\n\ndef retry_if_cuda_oom(func):\n    \"\"\"\n    Makes a function retry itself after encountering\n    pytorch's CUDA OOM error.\n    It will first retry after calling `torch.cuda.empty_cache()`.\n\n    If that still fails, it will then retry by trying to convert inputs to CPUs.\n    In this case, it expects the function to dispatch to CPU implementation.\n    The return values may become CPU tensors as well and it's user's\n    responsibility to convert it back to CUDA tensor if needed.\n\n    Args:\n        func: a stateless callable that takes tensor-like objects as arguments\n\n    Returns:\n        a callable which retries `func` if OOM is encountered.\n\n    Examples:\n    ::\n        output = retry_if_cuda_oom(some_torch_function)(input1, input2)\n        # output may be on CPU even if inputs are on GPU\n\n    Note:\n        1. When converting inputs to CPU, it will only look at each argument and check\n           if it has `.device` and `.to` for conversion. Nested structures of tensors\n           are not supported.\n\n        2. Since the function might be called more than once, it has to be\n           stateless.\n    \"\"\"\n\n    def maybe_to_cpu(x):\n        try:\n            like_gpu_tensor = x.device.type == \"cuda\" and hasattr(x, \"to\")\n        except AttributeError:\n            like_gpu_tensor = False\n        if like_gpu_tensor:\n            return x.to(device=\"cpu\")\n        else:\n            return x\n\n    @wraps(func)\n    def wrapped(*args, **kwargs):\n        with _ignore_torch_cuda_oom():\n            return func(*args, **kwargs)\n\n        # Clear cache and retry\n        torch.cuda.empty_cache()\n        with _ignore_torch_cuda_oom():\n            return func(*args, **kwargs)\n\n        # Try on CPU. This slows down the code significantly, therefore print a notice.\n        logger = logging.getLogger(__name__)\n        logger.info(\"Attempting to copy inputs of {} to CPU due to CUDA OOM\".format(str(func)))\n        new_args = (maybe_to_cpu(x) for x in args)\n        new_kwargs = {k: maybe_to_cpu(v) for k, v in kwargs.items()}\n        return func(*new_args, **new_kwargs)\n\n    return wrapped\n"
  },
  {
    "path": "VPS_Module/detectron2/utils/registry.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom typing import Any\nimport pydoc\nfrom fvcore.common.registry import Registry  # for backward compatibility.\n\n\"\"\"\n``Registry`` and `locate` provide ways to map a string (typically found\nin config files) to callable objects.\n\"\"\"\n\n__all__ = [\"Registry\", \"locate\"]\n\n\ndef _convert_target_to_string(t: Any) -> str:\n    \"\"\"\n    Inverse of ``locate()``.\n\n    Args:\n        t: any object with ``__module__`` and ``__qualname__``\n    \"\"\"\n    module, qualname = t.__module__, t.__qualname__\n\n    # Compress the path to this object, e.g. ``module.submodule._impl.class``\n    # may become ``module.submodule.class``, if the later also resolves to the same\n    # object. This simplifies the string, and also is less affected by moving the\n    # class implementation.\n    module_parts = module.split(\".\")\n    for k in range(1, len(module_parts)):\n        prefix = \".\".join(module_parts[:k])\n        candidate = f\"{prefix}.{qualname}\"\n        try:\n            if locate(candidate) is t:\n                return candidate\n        except ImportError:\n            pass\n    return f\"{module}.{qualname}\"\n\n\ndef locate(name: str) -> Any:\n    \"\"\"\n    Locate and return an object ``x`` using an input string ``{x.__module__}.{x.__qualname__}``,\n    such as \"module.submodule.class_name\".\n\n    Raise Exception if it cannot be found.\n    \"\"\"\n    obj = pydoc.locate(name)\n\n    # Some cases (e.g. torch.optim.sgd.SGD) not handled correctly\n    # by pydoc.locate. Try a private function from hydra.\n    if obj is None:\n        try:\n            # from hydra.utils import get_method - will print many errors\n            from hydra.utils import _locate\n        except ImportError as e:\n            raise ImportError(f\"Cannot dynamically locate object {name}!\") from e\n        else:\n            obj = _locate(name)  # it raises if fails\n\n    return obj\n"
  },
  {
    "path": "VPS_Module/detectron2/utils/serialize.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport cloudpickle\n\n\nclass PicklableWrapper(object):\n    \"\"\"\n    Wrap an object to make it more picklable, note that it uses\n    heavy weight serialization libraries that are slower than pickle.\n    It's best to use it only on closures (which are usually not picklable).\n\n    This is a simplified version of\n    https://github.com/joblib/joblib/blob/master/joblib/externals/loky/cloudpickle_wrapper.py\n    \"\"\"\n\n    def __init__(self, obj):\n        while isinstance(obj, PicklableWrapper):\n            # Wrapping an object twice is no-op\n            obj = obj._obj\n        self._obj = obj\n\n    def __reduce__(self):\n        s = cloudpickle.dumps(self._obj)\n        return cloudpickle.loads, (s,)\n\n    def __call__(self, *args, **kwargs):\n        return self._obj(*args, **kwargs)\n\n    def __getattr__(self, attr):\n        # Ensure that the wrapped object can be used seamlessly as the previous object.\n        if attr not in [\"_obj\"]:\n            return getattr(self._obj, attr)\n        return getattr(self, attr)\n"
  },
  {
    "path": "VPS_Module/detectron2/utils/testing.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport io\nimport numpy as np\nimport torch\n\nfrom detectron2 import model_zoo\nfrom detectron2.data import DatasetCatalog\nfrom detectron2.data.detection_utils import read_image\nfrom detectron2.modeling import build_model\nfrom detectron2.structures import Boxes, Instances, ROIMasks\nfrom detectron2.utils.file_io import PathManager\n\n\n\"\"\"\nInternal utilities for tests. Don't use except for writing tests.\n\"\"\"\n\n\ndef get_model_no_weights(config_path):\n    \"\"\"\n    Like model_zoo.get, but do not load any weights (even pretrained)\n    \"\"\"\n    cfg = model_zoo.get_config(config_path)\n    if not torch.cuda.is_available():\n        cfg.MODEL.DEVICE = \"cpu\"\n    return build_model(cfg)\n\n\ndef random_boxes(num_boxes, max_coord=100, device=\"cpu\"):\n    \"\"\"\n    Create a random Nx4 boxes tensor, with coordinates < max_coord.\n    \"\"\"\n    boxes = torch.rand(num_boxes, 4, device=device) * (max_coord * 0.5)\n    boxes.clamp_(min=1.0)  # tiny boxes cause numerical instability in box regression\n    # Note: the implementation of this function in torchvision is:\n    # boxes[:, 2:] += torch.rand(N, 2) * 100\n    # but it does not guarantee non-negative widths/heights constraints:\n    # boxes[:, 2] >= boxes[:, 0] and boxes[:, 3] >= boxes[:, 1]:\n    boxes[:, 2:] += boxes[:, :2]\n    return boxes\n\n\ndef get_sample_coco_image(tensor=True):\n    \"\"\"\n    Args:\n        tensor (bool): if True, returns 3xHxW tensor.\n            else, returns a HxWx3 numpy array.\n\n    Returns:\n        an image, in BGR color.\n    \"\"\"\n    try:\n        file_name = DatasetCatalog.get(\"coco_2017_val_100\")[0][\"file_name\"]\n        if not PathManager.exists(file_name):\n            raise FileNotFoundError()\n    except IOError:\n        # for public CI to run\n        file_name = PathManager.get_local_path(\n            \"http://images.cocodataset.org/train2017/000000000009.jpg\"\n        )\n    ret = read_image(file_name, format=\"BGR\")\n    if tensor:\n        ret = torch.from_numpy(np.ascontiguousarray(ret.transpose(2, 0, 1)))\n    return ret\n\n\ndef convert_scripted_instances(instances):\n    \"\"\"\n    Convert a scripted Instances object to a regular :class:`Instances` object\n    \"\"\"\n    assert hasattr(\n        instances, \"image_size\"\n    ), f\"Expect an Instances object, but got {type(instances)}!\"\n    ret = Instances(instances.image_size)\n    for name in instances._field_names:\n        val = getattr(instances, \"_\" + name, None)\n        if val is not None:\n            ret.set(name, val)\n    return ret\n\n\ndef assert_instances_allclose(input, other, *, rtol=1e-5, msg=\"\", size_as_tensor=False):\n    \"\"\"\n    Args:\n        input, other (Instances):\n        size_as_tensor: compare image_size of the Instances as tensors (instead of tuples).\n             Useful for comparing outputs of tracing.\n    \"\"\"\n    if not isinstance(input, Instances):\n        input = convert_scripted_instances(input)\n    if not isinstance(other, Instances):\n        other = convert_scripted_instances(other)\n\n    if not msg:\n        msg = \"Two Instances are different! \"\n    else:\n        msg = msg.rstrip() + \" \"\n\n    size_error_msg = msg + f\"image_size is {input.image_size} vs. {other.image_size}!\"\n    if size_as_tensor:\n        assert torch.equal(\n            torch.tensor(input.image_size), torch.tensor(other.image_size)\n        ), size_error_msg\n    else:\n        assert input.image_size == other.image_size, size_error_msg\n    fields = sorted(input.get_fields().keys())\n    fields_other = sorted(other.get_fields().keys())\n    assert fields == fields_other, msg + f\"Fields are {fields} vs {fields_other}!\"\n\n    for f in fields:\n        val1, val2 = input.get(f), other.get(f)\n        if isinstance(val1, (Boxes, ROIMasks)):\n            # boxes in the range of O(100) and can have a larger tolerance\n            assert torch.allclose(val1.tensor, val2.tensor, atol=100 * rtol), (\n                msg + f\"Field {f} differs too much!\"\n            )\n        elif isinstance(val1, torch.Tensor):\n            if val1.dtype.is_floating_point:\n                mag = torch.abs(val1).max().cpu().item()\n                assert torch.allclose(val1, val2, atol=mag * rtol), (\n                    msg + f\"Field {f} differs too much!\"\n                )\n            else:\n                assert torch.equal(val1, val2), msg + f\"Field {f} is different!\"\n        else:\n            raise ValueError(f\"Don't know how to compare type {type(val1)}\")\n\n\ndef reload_script_model(module):\n    \"\"\"\n    Save a jit module and load it back.\n    Similar to the `getExportImportCopy` function in torch/testing/\n    \"\"\"\n    buffer = io.BytesIO()\n    torch.jit.save(module, buffer)\n    buffer.seek(0)\n    return torch.jit.load(buffer)\n"
  },
  {
    "path": "VPS_Module/detectron2/utils/video_visualizer.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport numpy as np\nimport pycocotools.mask as mask_util\n\nfrom detectron2.utils.visualizer import (\n    ColorMode,\n    Visualizer,\n    _create_text_labels,\n    _PanopticPrediction,\n)\n\nfrom .colormap import random_color\n\n\nclass _DetectedInstance:\n    \"\"\"\n    Used to store data about detected objects in video frame,\n    in order to transfer color to objects in the future frames.\n\n    Attributes:\n        label (int):\n        bbox (tuple[float]):\n        mask_rle (dict):\n        color (tuple[float]): RGB colors in range (0, 1)\n        ttl (int): time-to-live for the instance. For example, if ttl=2,\n            the instance color can be transferred to objects in the next two frames.\n    \"\"\"\n\n    __slots__ = [\"label\", \"bbox\", \"mask_rle\", \"color\", \"ttl\"]\n\n    def __init__(self, label, bbox, mask_rle, color, ttl):\n        self.label = label\n        self.bbox = bbox\n        self.mask_rle = mask_rle\n        self.color = color\n        self.ttl = ttl\n\n\nclass VideoVisualizer:\n    def __init__(self, metadata, instance_mode=ColorMode.IMAGE):\n        \"\"\"\n        Args:\n            metadata (MetadataCatalog): image metadata.\n        \"\"\"\n        self.metadata = metadata\n        self._old_instances = []\n        assert instance_mode in [\n            ColorMode.IMAGE,\n            ColorMode.IMAGE_BW,\n        ], \"Other mode not supported yet.\"\n        self._instance_mode = instance_mode\n\n    def draw_instance_predictions(self, frame, predictions):\n        \"\"\"\n        Draw instance-level prediction results on an image.\n\n        Args:\n            frame (ndarray): an RGB image of shape (H, W, C), in the range [0, 255].\n            predictions (Instances): the output of an instance detection/segmentation\n                model. Following fields will be used to draw:\n                \"pred_boxes\", \"pred_classes\", \"scores\", \"pred_masks\" (or \"pred_masks_rle\").\n\n        Returns:\n            output (VisImage): image object with visualizations.\n        \"\"\"\n        frame_visualizer = Visualizer(frame, self.metadata)\n        num_instances = len(predictions)\n        if num_instances == 0:\n            return frame_visualizer.output\n\n        boxes = predictions.pred_boxes.tensor.numpy() if predictions.has(\"pred_boxes\") else None\n        scores = predictions.scores if predictions.has(\"scores\") else None\n        classes = predictions.pred_classes.numpy() if predictions.has(\"pred_classes\") else None\n        keypoints = predictions.pred_keypoints if predictions.has(\"pred_keypoints\") else None\n        colors = predictions.COLOR if predictions.has(\"COLOR\") else [None] * len(predictions)\n        durations = predictions.ID_duration if predictions.has(\"ID_duration\") else None\n        duration_threshold = self.metadata.get(\"duration_threshold\", 0)\n        visibilities = None if durations is None else [x > duration_threshold for x in durations]\n\n        if predictions.has(\"pred_masks\"):\n            masks = predictions.pred_masks\n            # mask IOU is not yet enabled\n            # masks_rles = mask_util.encode(np.asarray(masks.permute(1, 2, 0), order=\"F\"))\n            # assert len(masks_rles) == num_instances\n        else:\n            masks = None\n\n        detected = [\n            _DetectedInstance(classes[i], boxes[i], mask_rle=None, color=colors[i], ttl=8)\n            for i in range(num_instances)\n        ]\n        if not predictions.has(\"COLOR\"):\n            colors = self._assign_colors(detected)\n\n        labels = _create_text_labels(classes, scores, self.metadata.get(\"thing_classes\", None))\n\n        if self._instance_mode == ColorMode.IMAGE_BW:\n            # any() returns uint8 tensor\n            frame_visualizer.output.reset_image(\n                frame_visualizer._create_grayscale_image(\n                    (masks.any(dim=0) > 0).numpy() if masks is not None else None\n                )\n            )\n            alpha = 0.3\n        else:\n            alpha = 0.5\n\n        labels = (\n            None\n            if labels is None\n            else [y[0] for y in filter(lambda x: x[1], zip(labels, visibilities))]\n        )  # noqa\n        assigned_colors = (\n            None\n            if colors is None\n            else [y[0] for y in filter(lambda x: x[1], zip(colors, visibilities))]\n        )  # noqa\n        frame_visualizer.overlay_instances(\n            boxes=None if masks is not None else boxes[visibilities],  # boxes are a bit distracting\n            masks=None if masks is None else masks[visibilities],\n            labels=labels,\n            keypoints=None if keypoints is None else keypoints[visibilities],\n            assigned_colors=assigned_colors,\n            alpha=alpha,\n        )\n\n        return frame_visualizer.output\n\n    def draw_sem_seg(self, frame, sem_seg, area_threshold=None):\n        \"\"\"\n        Args:\n            sem_seg (ndarray or Tensor): semantic segmentation of shape (H, W),\n                each value is the integer label.\n            area_threshold (Optional[int]): only draw segmentations larger than the threshold\n        \"\"\"\n        # don't need to do anything special\n        frame_visualizer = Visualizer(frame, self.metadata)\n        frame_visualizer.draw_sem_seg(sem_seg, area_threshold=None)\n        return frame_visualizer.output\n\n    def draw_panoptic_seg_predictions(\n        self, frame, panoptic_seg, segments_info, area_threshold=None, alpha=0.5\n    ):\n        frame_visualizer = Visualizer(frame, self.metadata)\n        pred = _PanopticPrediction(panoptic_seg, segments_info, self.metadata)\n\n        if self._instance_mode == ColorMode.IMAGE_BW:\n            frame_visualizer.output.reset_image(\n                frame_visualizer._create_grayscale_image(pred.non_empty_mask())\n            )\n\n        # draw mask for all semantic segments first i.e. \"stuff\"\n        for mask, sinfo in pred.semantic_masks():\n            category_idx = sinfo[\"category_id\"]\n            try:\n                mask_color = [x / 255 for x in self.metadata.stuff_colors[category_idx]]\n            except AttributeError:\n                mask_color = None\n\n            frame_visualizer.draw_binary_mask(\n                mask,\n                color=mask_color,\n                text=self.metadata.stuff_classes[category_idx],\n                alpha=alpha,\n                area_threshold=area_threshold,\n            )\n\n        all_instances = list(pred.instance_masks())\n        if len(all_instances) == 0:\n            return frame_visualizer.output\n        # draw mask for all instances second\n        masks, sinfo = list(zip(*all_instances))\n        num_instances = len(masks)\n        masks_rles = mask_util.encode(\n            np.asarray(np.asarray(masks).transpose(1, 2, 0), dtype=np.uint8, order=\"F\")\n        )\n        assert len(masks_rles) == num_instances\n\n        category_ids = [x[\"category_id\"] for x in sinfo]\n        detected = [\n            _DetectedInstance(category_ids[i], bbox=None, mask_rle=masks_rles[i], color=None, ttl=8)\n            for i in range(num_instances)\n        ]\n        colors = self._assign_colors(detected)\n        labels = [self.metadata.thing_classes[k] for k in category_ids]\n\n        frame_visualizer.overlay_instances(\n            boxes=None,\n            masks=masks,\n            labels=labels,\n            keypoints=None,\n            assigned_colors=colors,\n            alpha=alpha,\n        )\n        return frame_visualizer.output\n\n    def _assign_colors(self, instances):\n        \"\"\"\n        Naive tracking heuristics to assign same color to the same instance,\n        will update the internal state of tracked instances.\n\n        Returns:\n            list[tuple[float]]: list of colors.\n        \"\"\"\n\n        # Compute iou with either boxes or masks:\n        is_crowd = np.zeros((len(instances),), dtype=np.bool)\n        if instances[0].bbox is None:\n            assert instances[0].mask_rle is not None\n            # use mask iou only when box iou is None\n            # because box seems good enough\n            rles_old = [x.mask_rle for x in self._old_instances]\n            rles_new = [x.mask_rle for x in instances]\n            ious = mask_util.iou(rles_old, rles_new, is_crowd)\n            threshold = 0.5\n        else:\n            boxes_old = [x.bbox for x in self._old_instances]\n            boxes_new = [x.bbox for x in instances]\n            ious = mask_util.iou(boxes_old, boxes_new, is_crowd)\n            threshold = 0.6\n        if len(ious) == 0:\n            ious = np.zeros((len(self._old_instances), len(instances)), dtype=\"float32\")\n\n        # Only allow matching instances of the same label:\n        for old_idx, old in enumerate(self._old_instances):\n            for new_idx, new in enumerate(instances):\n                if old.label != new.label:\n                    ious[old_idx, new_idx] = 0\n\n        matched_new_per_old = np.asarray(ious).argmax(axis=1)\n        max_iou_per_old = np.asarray(ious).max(axis=1)\n\n        # Try to find match for each old instance:\n        extra_instances = []\n        for idx, inst in enumerate(self._old_instances):\n            if max_iou_per_old[idx] > threshold:\n                newidx = matched_new_per_old[idx]\n                if instances[newidx].color is None:\n                    instances[newidx].color = inst.color\n                    continue\n            # If an old instance does not match any new instances,\n            # keep it for the next frame in case it is just missed by the detector\n            inst.ttl -= 1\n            if inst.ttl > 0:\n                extra_instances.append(inst)\n\n        # Assign random color to newly-detected instances:\n        for inst in instances:\n            if inst.color is None:\n                inst.color = random_color(rgb=True, maximum=1)\n        self._old_instances = instances[:] + extra_instances\n        return [d.color for d in instances]\n"
  },
  {
    "path": "VPS_Module/detectron2/utils/visualizer.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport colorsys\nimport logging\nimport math\nimport numpy as np\nfrom enum import Enum, unique\nimport cv2\nimport matplotlib as mpl\nimport matplotlib.colors as mplc\nimport matplotlib.figure as mplfigure\nimport pycocotools.mask as mask_util\nimport torch\nfrom matplotlib.backends.backend_agg import FigureCanvasAgg\nfrom PIL import Image\n\nfrom detectron2.data import MetadataCatalog\nfrom detectron2.structures import BitMasks, Boxes, BoxMode, Keypoints, PolygonMasks, RotatedBoxes\nfrom detectron2.utils.file_io import PathManager\n\nfrom .colormap import random_color\n\nlogger = logging.getLogger(__name__)\n\n__all__ = [\"ColorMode\", \"VisImage\", \"Visualizer\"]\n\n\n_SMALL_OBJECT_AREA_THRESH = 1000\n_LARGE_MASK_AREA_THRESH = 120000\n_OFF_WHITE = (1.0, 1.0, 240.0 / 255)\n_BLACK = (0, 0, 0)\n_RED = (1.0, 0, 0)\n\n_KEYPOINT_THRESHOLD = 0.05\n\n\n@unique\nclass ColorMode(Enum):\n    \"\"\"\n    Enum of different color modes to use for instance visualizations.\n    \"\"\"\n\n    IMAGE = 0\n    \"\"\"\n    Picks a random color for every instance and overlay segmentations with low opacity.\n    \"\"\"\n    SEGMENTATION = 1\n    \"\"\"\n    Let instances of the same category have similar colors\n    (from metadata.thing_colors), and overlay them with\n    high opacity. This provides more attention on the quality of segmentation.\n    \"\"\"\n    IMAGE_BW = 2\n    \"\"\"\n    Same as IMAGE, but convert all areas without masks to gray-scale.\n    Only available for drawing per-instance mask predictions.\n    \"\"\"\n\n\nclass GenericMask:\n    \"\"\"\n    Attribute:\n        polygons (list[ndarray]): list[ndarray]: polygons for this mask.\n            Each ndarray has format [x, y, x, y, ...]\n        mask (ndarray): a binary mask\n    \"\"\"\n\n    def __init__(self, mask_or_polygons, height, width):\n        self._mask = self._polygons = self._has_holes = None\n        self.height = height\n        self.width = width\n\n        m = mask_or_polygons\n        if isinstance(m, dict):\n            # RLEs\n            assert \"counts\" in m and \"size\" in m\n            if isinstance(m[\"counts\"], list):  # uncompressed RLEs\n                h, w = m[\"size\"]\n                assert h == height and w == width\n                m = mask_util.frPyObjects(m, h, w)\n            self._mask = mask_util.decode(m)[:, :]\n            return\n\n        if isinstance(m, list):  # list[ndarray]\n            self._polygons = [np.asarray(x).reshape(-1) for x in m]\n            return\n\n        if isinstance(m, np.ndarray):  # assumed to be a binary mask\n            assert m.shape[1] != 2, m.shape\n            assert m.shape == (\n                height,\n                width,\n            ), f\"mask shape: {m.shape}, target dims: {height}, {width}\"\n            self._mask = m.astype(\"uint8\")\n            return\n\n        raise ValueError(\"GenericMask cannot handle object {} of type '{}'\".format(m, type(m)))\n\n    @property\n    def mask(self):\n        if self._mask is None:\n            self._mask = self.polygons_to_mask(self._polygons)\n        return self._mask\n\n    @property\n    def polygons(self):\n        if self._polygons is None:\n            self._polygons, self._has_holes = self.mask_to_polygons(self._mask)\n        return self._polygons\n\n    @property\n    def has_holes(self):\n        if self._has_holes is None:\n            if self._mask is not None:\n                self._polygons, self._has_holes = self.mask_to_polygons(self._mask)\n            else:\n                self._has_holes = False  # if original format is polygon, does not have holes\n        return self._has_holes\n\n    def mask_to_polygons(self, mask):\n        # cv2.RETR_CCOMP flag retrieves all the contours and arranges them to a 2-level\n        # hierarchy. External contours (boundary) of the object are placed in hierarchy-1.\n        # Internal contours (holes) are placed in hierarchy-2.\n        # cv2.CHAIN_APPROX_NONE flag gets vertices of polygons from contours.\n        mask = np.ascontiguousarray(mask)  # some versions of cv2 does not support incontiguous arr\n        res = cv2.findContours(mask.astype(\"uint8\"), cv2.RETR_CCOMP, cv2.CHAIN_APPROX_NONE)\n        hierarchy = res[-1]\n        if hierarchy is None:  # empty mask\n            return [], False\n        has_holes = (hierarchy.reshape(-1, 4)[:, 3] >= 0).sum() > 0\n        res = res[-2]\n        res = [x.flatten() for x in res]\n        # These coordinates from OpenCV are integers in range [0, W-1 or H-1].\n        # We add 0.5 to turn them into real-value coordinate space. A better solution\n        # would be to first +0.5 and then dilate the returned polygon by 0.5.\n        res = [x + 0.5 for x in res if len(x) >= 6]\n        return res, has_holes\n\n    def polygons_to_mask(self, polygons):\n        rle = mask_util.frPyObjects(polygons, self.height, self.width)\n        rle = mask_util.merge(rle)\n        return mask_util.decode(rle)[:, :]\n\n    def area(self):\n        return self.mask.sum()\n\n    def bbox(self):\n        p = mask_util.frPyObjects(self.polygons, self.height, self.width)\n        p = mask_util.merge(p)\n        bbox = mask_util.toBbox(p)\n        bbox[2] += bbox[0]\n        bbox[3] += bbox[1]\n        return bbox\n\n\nclass _PanopticPrediction:\n    \"\"\"\n    Unify different panoptic annotation/prediction formats\n    \"\"\"\n\n    def __init__(self, panoptic_seg, segments_info, metadata=None):\n        if segments_info is None:\n            assert metadata is not None\n            # If \"segments_info\" is None, we assume \"panoptic_img\" is a\n            # H*W int32 image storing the panoptic_id in the format of\n            # category_id * label_divisor + instance_id. We reserve -1 for\n            # VOID label.\n            label_divisor = metadata.label_divisor\n            segments_info = []\n            for panoptic_label in np.unique(panoptic_seg.numpy()):\n                if panoptic_label == -1:\n                    # VOID region.\n                    continue\n                pred_class = panoptic_label // label_divisor\n                isthing = pred_class in metadata.thing_dataset_id_to_contiguous_id.values()\n                segments_info.append(\n                    {\n                        \"id\": int(panoptic_label),\n                        \"category_id\": int(pred_class),\n                        \"isthing\": bool(isthing),\n                    }\n                )\n        del metadata\n\n        self._seg = panoptic_seg\n\n        self._sinfo = {s[\"id\"]: s for s in segments_info}  # seg id -> seg info\n        segment_ids, areas = torch.unique(panoptic_seg, sorted=True, return_counts=True)\n        areas = areas.numpy()\n        sorted_idxs = np.argsort(-areas)\n        self._seg_ids, self._seg_areas = segment_ids[sorted_idxs], areas[sorted_idxs]\n        self._seg_ids = self._seg_ids.tolist()\n        for sid, area in zip(self._seg_ids, self._seg_areas):\n            if sid in self._sinfo:\n                self._sinfo[sid][\"area\"] = float(area)\n\n    def non_empty_mask(self):\n        \"\"\"\n        Returns:\n            (H, W) array, a mask for all pixels that have a prediction\n        \"\"\"\n        empty_ids = []\n        for id in self._seg_ids:\n            if id not in self._sinfo:\n                empty_ids.append(id)\n        if len(empty_ids) == 0:\n            return np.zeros(self._seg.shape, dtype=np.uint8)\n        assert (\n            len(empty_ids) == 1\n        ), \">1 ids corresponds to no labels. This is currently not supported\"\n        return (self._seg != empty_ids[0]).numpy().astype(np.bool)\n\n    def semantic_masks(self):\n        for sid in self._seg_ids:\n            sinfo = self._sinfo.get(sid)\n            if sinfo is None or sinfo[\"isthing\"]:\n                # Some pixels (e.g. id 0 in PanopticFPN) have no instance or semantic predictions.\n                continue\n            yield (self._seg == sid).numpy().astype(np.bool), sinfo\n\n    def instance_masks(self):\n        for sid in self._seg_ids:\n            sinfo = self._sinfo.get(sid)\n            if sinfo is None or not sinfo[\"isthing\"]:\n                continue\n            mask = (self._seg == sid).numpy().astype(np.bool)\n            if mask.sum() > 0:\n                yield mask, sinfo\n\n\ndef _create_text_labels(classes, scores, class_names, is_crowd=None):\n    \"\"\"\n    Args:\n        classes (list[int] or None):\n        scores (list[float] or None):\n        class_names (list[str] or None):\n        is_crowd (list[bool] or None):\n\n    Returns:\n        list[str] or None\n    \"\"\"\n    labels = None\n    if classes is not None:\n        if class_names is not None and len(class_names) > 0:\n            labels = [class_names[i] for i in classes]\n        else:\n            labels = [str(i) for i in classes]\n    if scores is not None:\n        if labels is None:\n            labels = [\"{:.0f}%\".format(s * 100) for s in scores]\n        else:\n            labels = [\"{} {:.0f}%\".format(l, s * 100) for l, s in zip(labels, scores)]\n    if labels is not None and is_crowd is not None:\n        labels = [l + (\"|crowd\" if crowd else \"\") for l, crowd in zip(labels, is_crowd)]\n    return labels\n\n\nclass VisImage:\n    def __init__(self, img, scale=1.0):\n        \"\"\"\n        Args:\n            img (ndarray): an RGB image of shape (H, W, 3) in range [0, 255].\n            scale (float): scale the input image\n        \"\"\"\n        self.img = img\n        self.scale = scale\n        self.width, self.height = img.shape[1], img.shape[0]\n        self._setup_figure(img)\n\n    def _setup_figure(self, img):\n        \"\"\"\n        Args:\n            Same as in :meth:`__init__()`.\n\n        Returns:\n            fig (matplotlib.pyplot.figure): top level container for all the image plot elements.\n            ax (matplotlib.pyplot.Axes): contains figure elements and sets the coordinate system.\n        \"\"\"\n        fig = mplfigure.Figure(frameon=False)\n        self.dpi = fig.get_dpi()\n        # add a small 1e-2 to avoid precision lost due to matplotlib's truncation\n        # (https://github.com/matplotlib/matplotlib/issues/15363)\n        fig.set_size_inches(\n            (self.width * self.scale + 1e-2) / self.dpi,\n            (self.height * self.scale + 1e-2) / self.dpi,\n        )\n        self.canvas = FigureCanvasAgg(fig)\n        # self.canvas = mpl.backends.backend_cairo.FigureCanvasCairo(fig)\n        ax = fig.add_axes([0.0, 0.0, 1.0, 1.0])\n        ax.axis(\"off\")\n        self.fig = fig\n        self.ax = ax\n        self.reset_image(img)\n\n    def reset_image(self, img):\n        \"\"\"\n        Args:\n            img: same as in __init__\n        \"\"\"\n        img = img.astype(\"uint8\")\n        self.ax.imshow(img, extent=(0, self.width, self.height, 0), interpolation=\"nearest\")\n\n    def save(self, filepath):\n        \"\"\"\n        Args:\n            filepath (str): a string that contains the absolute path, including the file name, where\n                the visualized image will be saved.\n        \"\"\"\n        self.fig.savefig(filepath)\n\n    def get_image(self):\n        \"\"\"\n        Returns:\n            ndarray:\n                the visualized image of shape (H, W, 3) (RGB) in uint8 type.\n                The shape is scaled w.r.t the input image using the given `scale` argument.\n        \"\"\"\n        canvas = self.canvas\n        s, (width, height) = canvas.print_to_buffer()\n        # buf = io.BytesIO()  # works for cairo backend\n        # canvas.print_rgba(buf)\n        # width, height = self.width, self.height\n        # s = buf.getvalue()\n\n        buffer = np.frombuffer(s, dtype=\"uint8\")\n\n        img_rgba = buffer.reshape(height, width, 4)\n        rgb, alpha = np.split(img_rgba, [3], axis=2)\n        return rgb.astype(\"uint8\")\n\n\nclass Visualizer:\n    \"\"\"\n    Visualizer that draws data about detection/segmentation on images.\n\n    It contains methods like `draw_{text,box,circle,line,binary_mask,polygon}`\n    that draw primitive objects to images, as well as high-level wrappers like\n    `draw_{instance_predictions,sem_seg,panoptic_seg_predictions,dataset_dict}`\n    that draw composite data in some pre-defined style.\n\n    Note that the exact visualization style for the high-level wrappers are subject to change.\n    Style such as color, opacity, label contents, visibility of labels, or even the visibility\n    of objects themselves (e.g. when the object is too small) may change according\n    to different heuristics, as long as the results still look visually reasonable.\n\n    To obtain a consistent style, you can implement custom drawing functions with the\n    abovementioned primitive methods instead. If you need more customized visualization\n    styles, you can process the data yourself following their format documented in\n    tutorials (:doc:`/tutorials/models`, :doc:`/tutorials/datasets`). This class does not\n    intend to satisfy everyone's preference on drawing styles.\n\n    This visualizer focuses on high rendering quality rather than performance. It is not\n    designed to be used for real-time applications.\n    \"\"\"\n\n    # TODO implement a fast, rasterized version using OpenCV\n\n    def __init__(self, img_rgb, metadata=None, scale=1.0, instance_mode=ColorMode.IMAGE):\n        \"\"\"\n        Args:\n            img_rgb: a numpy array of shape (H, W, C), where H and W correspond to\n                the height and width of the image respectively. C is the number of\n                color channels. The image is required to be in RGB format since that\n                is a requirement of the Matplotlib library. The image is also expected\n                to be in the range [0, 255].\n            metadata (Metadata): dataset metadata (e.g. class names and colors)\n            instance_mode (ColorMode): defines one of the pre-defined style for drawing\n                instances on an image.\n        \"\"\"\n        self.img = np.asarray(img_rgb).clip(0, 255).astype(np.uint8)\n        if metadata is None:\n            metadata = MetadataCatalog.get(\"__nonexist__\")\n        self.metadata = metadata\n        self.output = VisImage(self.img, scale=scale)\n        self.cpu_device = torch.device(\"cpu\")\n\n        # too small texts are useless, therefore clamp to 9\n        self._default_font_size = max(\n            np.sqrt(self.output.height * self.output.width) // 90, 10 // scale\n        )\n        self._instance_mode = instance_mode\n        self.keypoint_threshold = _KEYPOINT_THRESHOLD\n\n    def draw_instance_predictions(self, predictions):\n        \"\"\"\n        Draw instance-level prediction results on an image.\n\n        Args:\n            predictions (Instances): the output of an instance detection/segmentation\n                model. Following fields will be used to draw:\n                \"pred_boxes\", \"pred_classes\", \"scores\", \"pred_masks\" (or \"pred_masks_rle\").\n\n        Returns:\n            output (VisImage): image object with visualizations.\n        \"\"\"\n        boxes = predictions.pred_boxes if predictions.has(\"pred_boxes\") else None\n        scores = predictions.scores if predictions.has(\"scores\") else None\n        classes = predictions.pred_classes.tolist() if predictions.has(\"pred_classes\") else None\n        labels = _create_text_labels(classes, scores, self.metadata.get(\"thing_classes\", None))\n        keypoints = predictions.pred_keypoints if predictions.has(\"pred_keypoints\") else None\n\n        if predictions.has(\"pred_masks\"):\n            masks = np.asarray(predictions.pred_masks)\n            masks = [GenericMask(x, self.output.height, self.output.width) for x in masks]\n        else:\n            masks = None\n\n        if self._instance_mode == ColorMode.SEGMENTATION and self.metadata.get(\"thing_colors\"):\n            colors = [\n                self._jitter([x / 255 for x in self.metadata.thing_colors[c]]) for c in classes\n            ]\n            alpha = 0.8\n        else:\n            colors = None\n            alpha = 0.5\n\n        if self._instance_mode == ColorMode.IMAGE_BW:\n            self.output.reset_image(\n                self._create_grayscale_image(\n                    (predictions.pred_masks.any(dim=0) > 0).numpy()\n                    if predictions.has(\"pred_masks\")\n                    else None\n                )\n            )\n            alpha = 0.3\n\n        self.overlay_instances(\n            masks=masks,\n            boxes=boxes,\n            labels=labels,\n            keypoints=keypoints,\n            assigned_colors=colors,\n            alpha=alpha,\n        )\n        return self.output\n\n    def draw_sem_seg(self, sem_seg, area_threshold=None, alpha=0.8):\n        \"\"\"\n        Draw semantic segmentation predictions/labels.\n\n        Args:\n            sem_seg (Tensor or ndarray): the segmentation of shape (H, W).\n                Each value is the integer label of the pixel.\n            area_threshold (int): segments with less than `area_threshold` are not drawn.\n            alpha (float): the larger it is, the more opaque the segmentations are.\n\n        Returns:\n            output (VisImage): image object with visualizations.\n        \"\"\"\n        if isinstance(sem_seg, torch.Tensor):\n            sem_seg = sem_seg.numpy()\n        labels, areas = np.unique(sem_seg, return_counts=True)\n        sorted_idxs = np.argsort(-areas).tolist()\n        labels = labels[sorted_idxs]\n        for label in filter(lambda l: l < len(self.metadata.stuff_classes), labels):\n            try:\n                mask_color = [x / 255 for x in self.metadata.stuff_colors[label]]\n            except (AttributeError, IndexError):\n                mask_color = None\n\n            binary_mask = (sem_seg == label).astype(np.uint8)\n            text = self.metadata.stuff_classes[label]\n            self.draw_binary_mask(\n                binary_mask,\n                color=mask_color,\n                edge_color=_OFF_WHITE,\n                text=text,\n                alpha=alpha,\n                area_threshold=area_threshold,\n            )\n        return self.output\n\n    def draw_panoptic_seg(self, panoptic_seg, segments_info, area_threshold=None, alpha=0.7):\n        \"\"\"\n        Draw panoptic prediction annotations or results.\n\n        Args:\n            panoptic_seg (Tensor): of shape (height, width) where the values are ids for each\n                segment.\n            segments_info (list[dict] or None): Describe each segment in `panoptic_seg`.\n                If it is a ``list[dict]``, each dict contains keys \"id\", \"category_id\".\n                If None, category id of each pixel is computed by\n                ``pixel // metadata.label_divisor``.\n            area_threshold (int): stuff segments with less than `area_threshold` are not drawn.\n\n        Returns:\n            output (VisImage): image object with visualizations.\n        \"\"\"\n        pred = _PanopticPrediction(panoptic_seg, segments_info, self.metadata)\n\n        if self._instance_mode == ColorMode.IMAGE_BW:\n            self.output.reset_image(self._create_grayscale_image(pred.non_empty_mask()))\n\n        # draw mask for all semantic segments first i.e. \"stuff\"\n        for mask, sinfo in pred.semantic_masks():\n            category_idx = sinfo[\"category_id\"]\n            try:\n                mask_color = [x / 255 for x in self.metadata.stuff_colors[category_idx]]\n            except AttributeError:\n                mask_color = None\n\n            text = self.metadata.stuff_classes[category_idx]\n            self.draw_binary_mask(\n                mask,\n                color=mask_color,\n                edge_color=_OFF_WHITE,\n                text=text,\n                alpha=alpha,\n                area_threshold=area_threshold,\n            )\n\n        # draw mask for all instances second\n        all_instances = list(pred.instance_masks())\n        if len(all_instances) == 0:\n            return self.output\n        masks, sinfo = list(zip(*all_instances))\n        category_ids = [x[\"category_id\"] for x in sinfo]\n\n        try:\n            scores = [x[\"score\"] for x in sinfo]\n        except KeyError:\n            scores = None\n        labels = _create_text_labels(\n            category_ids, scores, self.metadata.thing_classes, [x.get(\"iscrowd\", 0) for x in sinfo]\n        )\n\n        try:\n            colors = [\n                self._jitter([x / 255 for x in self.metadata.thing_colors[c]]) for c in category_ids\n            ]\n        except AttributeError:\n            colors = None\n        self.overlay_instances(masks=masks, labels=labels, assigned_colors=colors, alpha=alpha)\n\n        return self.output\n\n    draw_panoptic_seg_predictions = draw_panoptic_seg  # backward compatibility\n\n    def draw_dataset_dict(self, dic):\n        \"\"\"\n        Draw annotations/segmentaions in Detectron2 Dataset format.\n\n        Args:\n            dic (dict): annotation/segmentation data of one image, in Detectron2 Dataset format.\n\n        Returns:\n            output (VisImage): image object with visualizations.\n        \"\"\"\n        annos = dic.get(\"annotations\", None)\n        if annos:\n            if \"segmentation\" in annos[0]:\n                masks = [x[\"segmentation\"] for x in annos]\n            else:\n                masks = None\n            if \"keypoints\" in annos[0]:\n                keypts = [x[\"keypoints\"] for x in annos]\n                keypts = np.array(keypts).reshape(len(annos), -1, 3)\n            else:\n                keypts = None\n\n            boxes = [\n                BoxMode.convert(x[\"bbox\"], x[\"bbox_mode\"], BoxMode.XYXY_ABS)\n                if len(x[\"bbox\"]) == 4\n                else x[\"bbox\"]\n                for x in annos\n            ]\n\n            colors = None\n            category_ids = [x[\"category_id\"] for x in annos]\n            if self._instance_mode == ColorMode.SEGMENTATION and self.metadata.get(\"thing_colors\"):\n                colors = [\n                    self._jitter([x / 255 for x in self.metadata.thing_colors[c]])\n                    for c in category_ids\n                ]\n            names = self.metadata.get(\"thing_classes\", None)\n            labels = _create_text_labels(\n                category_ids,\n                scores=None,\n                class_names=names,\n                is_crowd=[x.get(\"iscrowd\", 0) for x in annos],\n            )\n            self.overlay_instances(\n                labels=labels, boxes=boxes, masks=masks, keypoints=keypts, assigned_colors=colors\n            )\n\n        sem_seg = dic.get(\"sem_seg\", None)\n        if sem_seg is None and \"sem_seg_file_name\" in dic:\n            with PathManager.open(dic[\"sem_seg_file_name\"], \"rb\") as f:\n                sem_seg = Image.open(f)\n                sem_seg = np.asarray(sem_seg, dtype=\"uint8\")\n        if sem_seg is not None:\n            self.draw_sem_seg(sem_seg, area_threshold=0, alpha=0.5)\n\n        pan_seg = dic.get(\"pan_seg\", None)\n        if pan_seg is None and \"pan_seg_file_name\" in dic:\n            with PathManager.open(dic[\"pan_seg_file_name\"], \"rb\") as f:\n                pan_seg = Image.open(f)\n                pan_seg = np.asarray(pan_seg)\n                from panopticapi.utils import rgb2id\n\n                pan_seg = rgb2id(pan_seg)\n        if pan_seg is not None:\n            segments_info = dic[\"segments_info\"]\n            pan_seg = torch.tensor(pan_seg)\n            self.draw_panoptic_seg(pan_seg, segments_info, area_threshold=0, alpha=0.5)\n        return self.output\n\n    def overlay_instances(\n        self,\n        *,\n        boxes=None,\n        labels=None,\n        masks=None,\n        keypoints=None,\n        assigned_colors=None,\n        alpha=0.5,\n    ):\n        \"\"\"\n        Args:\n            boxes (Boxes, RotatedBoxes or ndarray): either a :class:`Boxes`,\n                or an Nx4 numpy array of XYXY_ABS format for the N objects in a single image,\n                or a :class:`RotatedBoxes`,\n                or an Nx5 numpy array of (x_center, y_center, width, height, angle_degrees) format\n                for the N objects in a single image,\n            labels (list[str]): the text to be displayed for each instance.\n            masks (masks-like object): Supported types are:\n\n                * :class:`detectron2.structures.PolygonMasks`,\n                  :class:`detectron2.structures.BitMasks`.\n                * list[list[ndarray]]: contains the segmentation masks for all objects in one image.\n                  The first level of the list corresponds to individual instances. The second\n                  level to all the polygon that compose the instance, and the third level\n                  to the polygon coordinates. The third level should have the format of\n                  [x0, y0, x1, y1, ..., xn, yn] (n >= 3).\n                * list[ndarray]: each ndarray is a binary mask of shape (H, W).\n                * list[dict]: each dict is a COCO-style RLE.\n            keypoints (Keypoint or array like): an array-like object of shape (N, K, 3),\n                where the N is the number of instances and K is the number of keypoints.\n                The last dimension corresponds to (x, y, visibility or score).\n            assigned_colors (list[matplotlib.colors]): a list of colors, where each color\n                corresponds to each mask or box in the image. Refer to 'matplotlib.colors'\n                for full list of formats that the colors are accepted in.\n        Returns:\n            output (VisImage): image object with visualizations.\n        \"\"\"\n        num_instances = 0\n        if boxes is not None:\n            boxes = self._convert_boxes(boxes)\n            num_instances = len(boxes)\n        if masks is not None:\n            masks = self._convert_masks(masks)\n            if num_instances:\n                assert len(masks) == num_instances\n            else:\n                num_instances = len(masks)\n        if keypoints is not None:\n            if num_instances:\n                assert len(keypoints) == num_instances\n            else:\n                num_instances = len(keypoints)\n            keypoints = self._convert_keypoints(keypoints)\n        if labels is not None:\n            assert len(labels) == num_instances\n        if assigned_colors is None:\n            assigned_colors = [random_color(rgb=True, maximum=1) for _ in range(num_instances)]\n        if num_instances == 0:\n            return self.output\n        if boxes is not None and boxes.shape[1] == 5:\n            return self.overlay_rotated_instances(\n                boxes=boxes, labels=labels, assigned_colors=assigned_colors\n            )\n\n        # Display in largest to smallest order to reduce occlusion.\n        areas = None\n        if boxes is not None:\n            areas = np.prod(boxes[:, 2:] - boxes[:, :2], axis=1)\n        elif masks is not None:\n            areas = np.asarray([x.area() for x in masks])\n\n        if areas is not None:\n            sorted_idxs = np.argsort(-areas).tolist()\n            # Re-order overlapped instances in descending order.\n            boxes = boxes[sorted_idxs] if boxes is not None else None\n            labels = [labels[k] for k in sorted_idxs] if labels is not None else None\n            masks = [masks[idx] for idx in sorted_idxs] if masks is not None else None\n            assigned_colors = [assigned_colors[idx] for idx in sorted_idxs]\n            keypoints = keypoints[sorted_idxs] if keypoints is not None else None\n\n        for i in range(num_instances):\n            color = assigned_colors[i]\n            if boxes is not None:\n                self.draw_box(boxes[i], edge_color=color)\n\n            if masks is not None:\n                for segment in masks[i].polygons:\n                    self.draw_polygon(segment.reshape(-1, 2), color, alpha=alpha)\n\n            if labels is not None:\n                # first get a box\n                if boxes is not None:\n                    x0, y0, x1, y1 = boxes[i]\n                    text_pos = (x0, y0)  # if drawing boxes, put text on the box corner.\n                    horiz_align = \"left\"\n                elif masks is not None:\n                    # skip small mask without polygon\n                    if len(masks[i].polygons) == 0:\n                        continue\n\n                    x0, y0, x1, y1 = masks[i].bbox()\n\n                    # draw text in the center (defined by median) when box is not drawn\n                    # median is less sensitive to outliers.\n                    text_pos = np.median(masks[i].mask.nonzero(), axis=1)[::-1]\n                    horiz_align = \"center\"\n                else:\n                    continue  # drawing the box confidence for keypoints isn't very useful.\n                # for small objects, draw text at the side to avoid occlusion\n                instance_area = (y1 - y0) * (x1 - x0)\n                if (\n                    instance_area < _SMALL_OBJECT_AREA_THRESH * self.output.scale\n                    or y1 - y0 < 40 * self.output.scale\n                ):\n                    if y1 >= self.output.height - 5:\n                        text_pos = (x1, y0)\n                    else:\n                        text_pos = (x0, y1)\n\n                height_ratio = (y1 - y0) / np.sqrt(self.output.height * self.output.width)\n                lighter_color = self._change_color_brightness(color, brightness_factor=0.7)\n                font_size = (\n                    np.clip((height_ratio - 0.02) / 0.08 + 1, 1.2, 2)\n                    * 0.5\n                    * self._default_font_size\n                )\n                self.draw_text(\n                    labels[i],\n                    text_pos,\n                    color=lighter_color,\n                    horizontal_alignment=horiz_align,\n                    font_size=font_size,\n                )\n\n        # draw keypoints\n        if keypoints is not None:\n            for keypoints_per_instance in keypoints:\n                self.draw_and_connect_keypoints(keypoints_per_instance)\n\n        return self.output\n\n    def overlay_rotated_instances(self, boxes=None, labels=None, assigned_colors=None):\n        \"\"\"\n        Args:\n            boxes (ndarray): an Nx5 numpy array of\n                (x_center, y_center, width, height, angle_degrees) format\n                for the N objects in a single image.\n            labels (list[str]): the text to be displayed for each instance.\n            assigned_colors (list[matplotlib.colors]): a list of colors, where each color\n                corresponds to each mask or box in the image. Refer to 'matplotlib.colors'\n                for full list of formats that the colors are accepted in.\n\n        Returns:\n            output (VisImage): image object with visualizations.\n        \"\"\"\n        num_instances = len(boxes)\n\n        if assigned_colors is None:\n            assigned_colors = [random_color(rgb=True, maximum=1) for _ in range(num_instances)]\n        if num_instances == 0:\n            return self.output\n\n        # Display in largest to smallest order to reduce occlusion.\n        if boxes is not None:\n            areas = boxes[:, 2] * boxes[:, 3]\n\n        sorted_idxs = np.argsort(-areas).tolist()\n        # Re-order overlapped instances in descending order.\n        boxes = boxes[sorted_idxs]\n        labels = [labels[k] for k in sorted_idxs] if labels is not None else None\n        colors = [assigned_colors[idx] for idx in sorted_idxs]\n\n        for i in range(num_instances):\n            self.draw_rotated_box_with_label(\n                boxes[i], edge_color=colors[i], label=labels[i] if labels is not None else None\n            )\n\n        return self.output\n\n    def draw_and_connect_keypoints(self, keypoints):\n        \"\"\"\n        Draws keypoints of an instance and follows the rules for keypoint connections\n        to draw lines between appropriate keypoints. This follows color heuristics for\n        line color.\n\n        Args:\n            keypoints (Tensor): a tensor of shape (K, 3), where K is the number of keypoints\n                and the last dimension corresponds to (x, y, probability).\n\n        Returns:\n            output (VisImage): image object with visualizations.\n        \"\"\"\n        visible = {}\n        keypoint_names = self.metadata.get(\"keypoint_names\")\n        for idx, keypoint in enumerate(keypoints):\n            # draw keypoint\n            x, y, prob = keypoint\n            if prob > self.keypoint_threshold:\n                self.draw_circle((x, y), color=_RED)\n                if keypoint_names:\n                    keypoint_name = keypoint_names[idx]\n                    visible[keypoint_name] = (x, y)\n\n        if self.metadata.get(\"keypoint_connection_rules\"):\n            for kp0, kp1, color in self.metadata.keypoint_connection_rules:\n                if kp0 in visible and kp1 in visible:\n                    x0, y0 = visible[kp0]\n                    x1, y1 = visible[kp1]\n                    color = tuple(x / 255.0 for x in color)\n                    self.draw_line([x0, x1], [y0, y1], color=color)\n\n        # draw lines from nose to mid-shoulder and mid-shoulder to mid-hip\n        # Note that this strategy is specific to person keypoints.\n        # For other keypoints, it should just do nothing\n        try:\n            ls_x, ls_y = visible[\"left_shoulder\"]\n            rs_x, rs_y = visible[\"right_shoulder\"]\n            mid_shoulder_x, mid_shoulder_y = (ls_x + rs_x) / 2, (ls_y + rs_y) / 2\n        except KeyError:\n            pass\n        else:\n            # draw line from nose to mid-shoulder\n            nose_x, nose_y = visible.get(\"nose\", (None, None))\n            if nose_x is not None:\n                self.draw_line([nose_x, mid_shoulder_x], [nose_y, mid_shoulder_y], color=_RED)\n\n            try:\n                # draw line from mid-shoulder to mid-hip\n                lh_x, lh_y = visible[\"left_hip\"]\n                rh_x, rh_y = visible[\"right_hip\"]\n            except KeyError:\n                pass\n            else:\n                mid_hip_x, mid_hip_y = (lh_x + rh_x) / 2, (lh_y + rh_y) / 2\n                self.draw_line([mid_hip_x, mid_shoulder_x], [mid_hip_y, mid_shoulder_y], color=_RED)\n        return self.output\n\n    \"\"\"\n    Primitive drawing functions:\n    \"\"\"\n\n    def draw_text(\n        self,\n        text,\n        position,\n        *,\n        font_size=None,\n        color=\"g\",\n        horizontal_alignment=\"center\",\n        rotation=0,\n    ):\n        \"\"\"\n        Args:\n            text (str): class label\n            position (tuple): a tuple of the x and y coordinates to place text on image.\n            font_size (int, optional): font of the text. If not provided, a font size\n                proportional to the image width is calculated and used.\n            color: color of the text. Refer to `matplotlib.colors` for full list\n                of formats that are accepted.\n            horizontal_alignment (str): see `matplotlib.text.Text`\n            rotation: rotation angle in degrees CCW\n\n        Returns:\n            output (VisImage): image object with text drawn.\n        \"\"\"\n        if not font_size:\n            font_size = self._default_font_size\n\n        # since the text background is dark, we don't want the text to be dark\n        color = np.maximum(list(mplc.to_rgb(color)), 0.2)\n        color[np.argmax(color)] = max(0.8, np.max(color))\n\n        x, y = position\n        self.output.ax.text(\n            x,\n            y,\n            text,\n            size=font_size * self.output.scale,\n            family=\"sans-serif\",\n            bbox={\"facecolor\": \"black\", \"alpha\": 0.8, \"pad\": 0.7, \"edgecolor\": \"none\"},\n            verticalalignment=\"top\",\n            horizontalalignment=horizontal_alignment,\n            color=color,\n            zorder=10,\n            rotation=rotation,\n        )\n        return self.output\n\n    def draw_box(self, box_coord, alpha=0.5, edge_color=\"g\", line_style=\"-\"):\n        \"\"\"\n        Args:\n            box_coord (tuple): a tuple containing x0, y0, x1, y1 coordinates, where x0 and y0\n                are the coordinates of the image's top left corner. x1 and y1 are the\n                coordinates of the image's bottom right corner.\n            alpha (float): blending efficient. Smaller values lead to more transparent masks.\n            edge_color: color of the outline of the box. Refer to `matplotlib.colors`\n                for full list of formats that are accepted.\n            line_style (string): the string to use to create the outline of the boxes.\n\n        Returns:\n            output (VisImage): image object with box drawn.\n        \"\"\"\n        x0, y0, x1, y1 = box_coord\n        width = x1 - x0\n        height = y1 - y0\n\n        linewidth = max(self._default_font_size / 4, 1)\n\n        self.output.ax.add_patch(\n            mpl.patches.Rectangle(\n                (x0, y0),\n                width,\n                height,\n                fill=False,\n                edgecolor=edge_color,\n                linewidth=linewidth * self.output.scale,\n                alpha=alpha,\n                linestyle=line_style,\n            )\n        )\n        return self.output\n\n    def draw_rotated_box_with_label(\n        self, rotated_box, alpha=0.5, edge_color=\"g\", line_style=\"-\", label=None\n    ):\n        \"\"\"\n        Draw a rotated box with label on its top-left corner.\n\n        Args:\n            rotated_box (tuple): a tuple containing (cnt_x, cnt_y, w, h, angle),\n                where cnt_x and cnt_y are the center coordinates of the box.\n                w and h are the width and height of the box. angle represents how\n                many degrees the box is rotated CCW with regard to the 0-degree box.\n            alpha (float): blending efficient. Smaller values lead to more transparent masks.\n            edge_color: color of the outline of the box. Refer to `matplotlib.colors`\n                for full list of formats that are accepted.\n            line_style (string): the string to use to create the outline of the boxes.\n            label (string): label for rotated box. It will not be rendered when set to None.\n\n        Returns:\n            output (VisImage): image object with box drawn.\n        \"\"\"\n        cnt_x, cnt_y, w, h, angle = rotated_box\n        area = w * h\n        # use thinner lines when the box is small\n        linewidth = self._default_font_size / (\n            6 if area < _SMALL_OBJECT_AREA_THRESH * self.output.scale else 3\n        )\n\n        theta = angle * math.pi / 180.0\n        c = math.cos(theta)\n        s = math.sin(theta)\n        rect = [(-w / 2, h / 2), (-w / 2, -h / 2), (w / 2, -h / 2), (w / 2, h / 2)]\n        # x: left->right ; y: top->down\n        rotated_rect = [(s * yy + c * xx + cnt_x, c * yy - s * xx + cnt_y) for (xx, yy) in rect]\n        for k in range(4):\n            j = (k + 1) % 4\n            self.draw_line(\n                [rotated_rect[k][0], rotated_rect[j][0]],\n                [rotated_rect[k][1], rotated_rect[j][1]],\n                color=edge_color,\n                linestyle=\"--\" if k == 1 else line_style,\n                linewidth=linewidth,\n            )\n\n        if label is not None:\n            text_pos = rotated_rect[1]  # topleft corner\n\n            height_ratio = h / np.sqrt(self.output.height * self.output.width)\n            label_color = self._change_color_brightness(edge_color, brightness_factor=0.7)\n            font_size = (\n                np.clip((height_ratio - 0.02) / 0.08 + 1, 1.2, 2) * 0.5 * self._default_font_size\n            )\n            self.draw_text(label, text_pos, color=label_color, font_size=font_size, rotation=angle)\n\n        return self.output\n\n    def draw_circle(self, circle_coord, color, radius=3):\n        \"\"\"\n        Args:\n            circle_coord (list(int) or tuple(int)): contains the x and y coordinates\n                of the center of the circle.\n            color: color of the polygon. Refer to `matplotlib.colors` for a full list of\n                formats that are accepted.\n            radius (int): radius of the circle.\n\n        Returns:\n            output (VisImage): image object with box drawn.\n        \"\"\"\n        x, y = circle_coord\n        self.output.ax.add_patch(\n            mpl.patches.Circle(circle_coord, radius=radius, fill=True, color=color)\n        )\n        return self.output\n\n    def draw_line(self, x_data, y_data, color, linestyle=\"-\", linewidth=None):\n        \"\"\"\n        Args:\n            x_data (list[int]): a list containing x values of all the points being drawn.\n                Length of list should match the length of y_data.\n            y_data (list[int]): a list containing y values of all the points being drawn.\n                Length of list should match the length of x_data.\n            color: color of the line. Refer to `matplotlib.colors` for a full list of\n                formats that are accepted.\n            linestyle: style of the line. Refer to `matplotlib.lines.Line2D`\n                for a full list of formats that are accepted.\n            linewidth (float or None): width of the line. When it's None,\n                a default value will be computed and used.\n\n        Returns:\n            output (VisImage): image object with line drawn.\n        \"\"\"\n        if linewidth is None:\n            linewidth = self._default_font_size / 3\n        linewidth = max(linewidth, 1)\n        self.output.ax.add_line(\n            mpl.lines.Line2D(\n                x_data,\n                y_data,\n                linewidth=linewidth * self.output.scale,\n                color=color,\n                linestyle=linestyle,\n            )\n        )\n        return self.output\n\n    def draw_binary_mask(\n        self, binary_mask, color=None, *, edge_color=None, text=None, alpha=0.5, area_threshold=10\n    ):\n        \"\"\"\n        Args:\n            binary_mask (ndarray): numpy array of shape (H, W), where H is the image height and\n                W is the image width. Each value in the array is either a 0 or 1 value of uint8\n                type.\n            color: color of the mask. Refer to `matplotlib.colors` for a full list of\n                formats that are accepted. If None, will pick a random color.\n            edge_color: color of the polygon edges. Refer to `matplotlib.colors` for a\n                full list of formats that are accepted.\n            text (str): if None, will be drawn on the object\n            alpha (float): blending efficient. Smaller values lead to more transparent masks.\n            area_threshold (float): a connected component smaller than this area will not be shown.\n\n        Returns:\n            output (VisImage): image object with mask drawn.\n        \"\"\"\n        if color is None:\n            color = random_color(rgb=True, maximum=1)\n        color = mplc.to_rgb(color)\n\n        has_valid_segment = False\n        binary_mask = binary_mask.astype(\"uint8\")  # opencv needs uint8\n        mask = GenericMask(binary_mask, self.output.height, self.output.width)\n        shape2d = (binary_mask.shape[0], binary_mask.shape[1])\n\n        if not mask.has_holes:\n            # draw polygons for regular masks\n            for segment in mask.polygons:\n                area = mask_util.area(mask_util.frPyObjects([segment], shape2d[0], shape2d[1]))\n                if area < (area_threshold or 0):\n                    continue\n                has_valid_segment = True\n                segment = segment.reshape(-1, 2)\n                self.draw_polygon(segment, color=color, edge_color=edge_color, alpha=alpha)\n        else:\n            # TODO: Use Path/PathPatch to draw vector graphics:\n            # https://stackoverflow.com/questions/8919719/how-to-plot-a-complex-polygon\n            rgba = np.zeros(shape2d + (4,), dtype=\"float32\")\n            rgba[:, :, :3] = color\n            rgba[:, :, 3] = (mask.mask == 1).astype(\"float32\") * alpha\n            has_valid_segment = True\n            self.output.ax.imshow(rgba, extent=(0, self.output.width, self.output.height, 0))\n\n        if text is not None and has_valid_segment:\n            lighter_color = self._change_color_brightness(color, brightness_factor=0.7)\n            self._draw_text_in_mask(binary_mask, text, lighter_color)\n        return self.output\n\n    def draw_soft_mask(self, soft_mask, color=None, *, text=None, alpha=0.5):\n        \"\"\"\n        Args:\n            soft_mask (ndarray): float array of shape (H, W), each value in [0, 1].\n            color: color of the mask. Refer to `matplotlib.colors` for a full list of\n                formats that are accepted. If None, will pick a random color.\n            text (str): if None, will be drawn on the object\n            alpha (float): blending efficient. Smaller values lead to more transparent masks.\n\n        Returns:\n            output (VisImage): image object with mask drawn.\n        \"\"\"\n        if color is None:\n            color = random_color(rgb=True, maximum=1)\n        color = mplc.to_rgb(color)\n\n        shape2d = (soft_mask.shape[0], soft_mask.shape[1])\n        rgba = np.zeros(shape2d + (4,), dtype=\"float32\")\n        rgba[:, :, :3] = color\n        rgba[:, :, 3] = soft_mask * alpha\n        self.output.ax.imshow(rgba, extent=(0, self.output.width, self.output.height, 0))\n\n        if text is not None:\n            lighter_color = self._change_color_brightness(color, brightness_factor=0.7)\n            binary_mask = (soft_mask > 0.5).astype(\"uint8\")\n            self._draw_text_in_mask(binary_mask, text, lighter_color)\n        return self.output\n\n    def draw_polygon(self, segment, color, edge_color=None, alpha=0.5):\n        \"\"\"\n        Args:\n            segment: numpy array of shape Nx2, containing all the points in the polygon.\n            color: color of the polygon. Refer to `matplotlib.colors` for a full list of\n                formats that are accepted.\n            edge_color: color of the polygon edges. Refer to `matplotlib.colors` for a\n                full list of formats that are accepted. If not provided, a darker shade\n                of the polygon color will be used instead.\n            alpha (float): blending efficient. Smaller values lead to more transparent masks.\n\n        Returns:\n            output (VisImage): image object with polygon drawn.\n        \"\"\"\n        if edge_color is None:\n            # make edge color darker than the polygon color\n            if alpha > 0.8:\n                edge_color = self._change_color_brightness(color, brightness_factor=-0.7)\n            else:\n                edge_color = color\n        edge_color = mplc.to_rgb(edge_color) + (1,)\n\n        polygon = mpl.patches.Polygon(\n            segment,\n            fill=True,\n            facecolor=mplc.to_rgb(color) + (alpha,),\n            edgecolor=edge_color,\n            linewidth=max(self._default_font_size // 15 * self.output.scale, 1),\n        )\n        self.output.ax.add_patch(polygon)\n        return self.output\n\n    \"\"\"\n    Internal methods:\n    \"\"\"\n\n    def _jitter(self, color):\n        \"\"\"\n        Randomly modifies given color to produce a slightly different color than the color given.\n\n        Args:\n            color (tuple[double]): a tuple of 3 elements, containing the RGB values of the color\n                picked. The values in the list are in the [0.0, 1.0] range.\n\n        Returns:\n            jittered_color (tuple[double]): a tuple of 3 elements, containing the RGB values of the\n                color after being jittered. The values in the list are in the [0.0, 1.0] range.\n        \"\"\"\n        color = mplc.to_rgb(color)\n        vec = np.random.rand(3)\n        # better to do it in another color space\n        vec = vec / np.linalg.norm(vec) * 0.5\n        res = np.clip(vec + color, 0, 1)\n        return tuple(res)\n\n    def _create_grayscale_image(self, mask=None):\n        \"\"\"\n        Create a grayscale version of the original image.\n        The colors in masked area, if given, will be kept.\n        \"\"\"\n        img_bw = self.img.astype(\"f4\").mean(axis=2)\n        img_bw = np.stack([img_bw] * 3, axis=2)\n        if mask is not None:\n            img_bw[mask] = self.img[mask]\n        return img_bw\n\n    def _change_color_brightness(self, color, brightness_factor):\n        \"\"\"\n        Depending on the brightness_factor, gives a lighter or darker color i.e. a color with\n        less or more saturation than the original color.\n\n        Args:\n            color: color of the polygon. Refer to `matplotlib.colors` for a full list of\n                formats that are accepted.\n            brightness_factor (float): a value in [-1.0, 1.0] range. A lightness factor of\n                0 will correspond to no change, a factor in [-1.0, 0) range will result in\n                a darker color and a factor in (0, 1.0] range will result in a lighter color.\n\n        Returns:\n            modified_color (tuple[double]): a tuple containing the RGB values of the\n                modified color. Each value in the tuple is in the [0.0, 1.0] range.\n        \"\"\"\n        assert brightness_factor >= -1.0 and brightness_factor <= 1.0\n        color = mplc.to_rgb(color)\n        polygon_color = colorsys.rgb_to_hls(*mplc.to_rgb(color))\n        modified_lightness = polygon_color[1] + (brightness_factor * polygon_color[1])\n        modified_lightness = 0.0 if modified_lightness < 0.0 else modified_lightness\n        modified_lightness = 1.0 if modified_lightness > 1.0 else modified_lightness\n        modified_color = colorsys.hls_to_rgb(polygon_color[0], modified_lightness, polygon_color[2])\n        return modified_color\n\n    def _convert_boxes(self, boxes):\n        \"\"\"\n        Convert different format of boxes to an NxB array, where B = 4 or 5 is the box dimension.\n        \"\"\"\n        if isinstance(boxes, Boxes) or isinstance(boxes, RotatedBoxes):\n            return boxes.tensor.detach().numpy()\n        else:\n            return np.asarray(boxes)\n\n    def _convert_masks(self, masks_or_polygons):\n        \"\"\"\n        Convert different format of masks or polygons to a tuple of masks and polygons.\n\n        Returns:\n            list[GenericMask]:\n        \"\"\"\n\n        m = masks_or_polygons\n        if isinstance(m, PolygonMasks):\n            m = m.polygons\n        if isinstance(m, BitMasks):\n            m = m.tensor.numpy()\n        if isinstance(m, torch.Tensor):\n            m = m.numpy()\n        ret = []\n        for x in m:\n            if isinstance(x, GenericMask):\n                ret.append(x)\n            else:\n                ret.append(GenericMask(x, self.output.height, self.output.width))\n        return ret\n\n    def _draw_text_in_mask(self, binary_mask, text, color):\n        \"\"\"\n        Find proper places to draw text given a binary mask.\n        \"\"\"\n        # TODO sometimes drawn on wrong objects. the heuristics here can improve.\n        _num_cc, cc_labels, stats, centroids = cv2.connectedComponentsWithStats(binary_mask, 8)\n        if stats[1:, -1].size == 0:\n            return\n        largest_component_id = np.argmax(stats[1:, -1]) + 1\n\n        # draw text on the largest component, as well as other very large components.\n        for cid in range(1, _num_cc):\n            if cid == largest_component_id or stats[cid, -1] > _LARGE_MASK_AREA_THRESH:\n                # median is more stable than centroid\n                # center = centroids[largest_component_id]\n                center = np.median((cc_labels == cid).nonzero(), axis=1)[::-1]\n                self.draw_text(text, center, color=color)\n\n    def _convert_keypoints(self, keypoints):\n        if isinstance(keypoints, Keypoints):\n            keypoints = keypoints.tensor\n        keypoints = np.asarray(keypoints)\n        return keypoints\n\n    def get_output(self):\n        \"\"\"\n        Returns:\n            output (VisImage): the image output containing the visualizations added\n            to the image.\n        \"\"\"\n        return self.output\n"
  },
  {
    "path": "VPS_Module/dev/README.md",
    "content": "\n## Some scripts for developers to use, include:\n\n- `linter.sh`: lint the codebase before commit.\n- `run_{inference,instant}_tests.sh`: run inference/training for a few iterations.\n   Note that these tests require 2 GPUs.\n- `parse_results.sh`: parse results from a log file.\n"
  },
  {
    "path": "VPS_Module/dev/linter.sh",
    "content": "#!/bin/bash -e\n# Copyright (c) Facebook, Inc. and its affiliates.\n\n# cd to detectron2 project root\ncd \"$(dirname \"${BASH_SOURCE[0]}\")/..\"\n\n{\n  black --version | grep -E \"21\\.\" > /dev/null\n} || {\n  echo \"Linter requires 'black==21.*' !\"\n  exit 1\n}\n\nISORT_VERSION=$(isort --version-number)\nif [[ \"$ISORT_VERSION\" != 4.3* ]]; then\n  echo \"Linter requires isort==4.3.21 !\"\n  exit 1\nfi\n\nset -v\n\necho \"Running isort ...\"\nisort -y -sp . --atomic\n\necho \"Running black ...\"\nblack -l 100 .\n\necho \"Running flake8 ...\"\nif [ -x \"$(command -v flake8-3)\" ]; then\n  flake8-3 .\nelse\n  python3 -m flake8 .\nfi\n\n# echo \"Running mypy ...\"\n# Pytorch does not have enough type annotations\n# mypy detectron2/solver detectron2/structures detectron2/config\n\necho \"Running clang-format ...\"\nfind . -regex \".*\\.\\(cpp\\|c\\|cc\\|cu\\|cxx\\|h\\|hh\\|hpp\\|hxx\\|tcc\\|mm\\|m\\)\" -print0 | xargs -0 clang-format -i\n\ncommand -v arc > /dev/null && arc lint\n"
  },
  {
    "path": "VPS_Module/dev/packaging/README.md",
    "content": "\n## To build a cu101 wheel for release:\n\n```\n$ nvidia-docker run -it --storage-opt \"size=20GB\" --name pt  pytorch/manylinux-cuda101\n# inside the container:\n# git clone https://github.com/facebookresearch/detectron2/\n# cd detectron2\n# export CU_VERSION=cu101 D2_VERSION_SUFFIX= PYTHON_VERSION=3.7 PYTORCH_VERSION=1.8\n# ./dev/packaging/build_wheel.sh\n```\n\n## To build all wheels for combinations of CUDA and Python\n```\n./dev/packaging/build_all_wheels.sh\n./dev/packaging/gen_wheel_index.sh /path/to/wheels\n```\n"
  },
  {
    "path": "VPS_Module/dev/packaging/build_all_wheels.sh",
    "content": "#!/bin/bash -e\n# Copyright (c) Facebook, Inc. and its affiliates.\n\n[[ -d \"dev/packaging\" ]] || {\n  echo \"Please run this script at detectron2 root!\"\n  exit 1\n}\n\nbuild_one() {\n  cu=$1\n  pytorch_ver=$2\n\n  case \"$cu\" in\n    cu*)\n      container_name=manylinux-cuda${cu/cu/}\n      ;;\n    cpu)\n      container_name=manylinux-cuda101\n      ;;\n    *)\n      echo \"Unrecognized cu=$cu\"\n      exit 1\n      ;;\n  esac\n\n  echo \"Launching container $container_name ...\"\n  container_id=\"$container_name\"_\"$cu\"_\"$pytorch_ver\"\n\n  py_versions=(3.6 3.7 3.8 3.9)\n\n  for py in \"${py_versions[@]}\"; do\n    docker run -itd \\\n      --name \"$container_id\" \\\n      --mount type=bind,source=\"$(pwd)\",target=/detectron2 \\\n      pytorch/$container_name\n\n    cat <<EOF | docker exec -i $container_id sh\n      export CU_VERSION=$cu D2_VERSION_SUFFIX=+$cu PYTHON_VERSION=$py\n      export PYTORCH_VERSION=$pytorch_ver\n      cd /detectron2 && ./dev/packaging/build_wheel.sh\nEOF\n\n    docker container stop $container_id\n    docker container rm $container_id\n  done\n}\n\n\nif [[ -n \"$1\" ]] && [[ -n \"$2\" ]]; then\n  build_one \"$1\" \"$2\"\nelse\n  build_one cu113 1.10\n  build_one cu111 1.10\n  build_one cu102 1.10\n  build_one cpu 1.10\n\n  build_one cu111 1.9\n  build_one cu102 1.9\n  build_one cpu 1.9\n\n  build_one cu111 1.8\n  build_one cu102 1.8\n  build_one cu101 1.8\n  build_one cpu 1.8\nfi\n"
  },
  {
    "path": "VPS_Module/dev/packaging/build_wheel.sh",
    "content": "#!/bin/bash\n# Copyright (c) Facebook, Inc. and its affiliates.\nset -ex\n\nldconfig  # https://github.com/NVIDIA/nvidia-docker/issues/854\n\nscript_dir=\"$( cd \"$( dirname \"${BASH_SOURCE[0]}\" )\" >/dev/null 2>&1 && pwd )\"\n. \"$script_dir/pkg_helpers.bash\"\n\necho \"Build Settings:\"\necho \"CU_VERSION: $CU_VERSION\"                 # e.g. cu101\necho \"D2_VERSION_SUFFIX: $D2_VERSION_SUFFIX\"   # e.g. +cu101 or \"\"\necho \"PYTHON_VERSION: $PYTHON_VERSION\"         # e.g. 3.6\necho \"PYTORCH_VERSION: $PYTORCH_VERSION\"       # e.g. 1.4\n\nsetup_cuda\nsetup_wheel_python\n\nyum install ninja-build -y\nln -sv /usr/bin/ninja-build /usr/bin/ninja || true\n\npip_install pip numpy -U\npip_install \"torch==$PYTORCH_VERSION\" \\\n\t-f https://download.pytorch.org/whl/\"$CU_VERSION\"/torch_stable.html\n\n# use separate directories to allow parallel build\nBASE_BUILD_DIR=build/$CU_VERSION-py$PYTHON_VERSION-pt$PYTORCH_VERSION\npython setup.py \\\n  build -b \"$BASE_BUILD_DIR\" \\\n  bdist_wheel -b \"$BASE_BUILD_DIR/build_dist\" -d \"wheels/$CU_VERSION/torch$PYTORCH_VERSION\"\nrm -rf \"$BASE_BUILD_DIR\"\n"
  },
  {
    "path": "VPS_Module/dev/packaging/gen_install_table.py",
    "content": "#!/usr/bin/env python\n# Copyright (c) Facebook, Inc. and its affiliates.\n# -*- coding: utf-8 -*-\n\nimport argparse\n\ntemplate = \"\"\"<details><summary> install </summary><pre><code>\\\npython -m pip install detectron2{d2_version} -f \\\\\n  https://dl.fbaipublicfiles.com/detectron2/wheels/{cuda}/torch{torch}/index.html\n</code></pre> </details>\"\"\"\nCUDA_SUFFIX = {\n    \"11.3\": \"cu113\",\n    \"11.1\": \"cu111\",\n    \"11.0\": \"cu110\",\n    \"10.2\": \"cu102\",\n    \"10.1\": \"cu101\",\n    \"10.0\": \"cu100\",\n    \"9.2\": \"cu92\",\n    \"cpu\": \"cpu\",\n}\n\n\ndef gen_header(torch_versions):\n    return '<table class=\"docutils\"><tbody><th width=\"80\"> CUDA </th>' + \"\".join(\n        [\n            '<th valign=\"bottom\" align=\"left\" width=\"100\">torch {}</th>'.format(t)\n            for t in torch_versions\n        ]\n    )\n\n\nif __name__ == \"__main__\":\n    parser = argparse.ArgumentParser()\n    parser.add_argument(\"--d2-version\", help=\"detectron2 version number, default to empty\")\n    args = parser.parse_args()\n    d2_version = f\"=={args.d2_version}\" if args.d2_version else \"\"\n\n    all_versions = (\n        [(\"1.8\", k) for k in [\"11.1\", \"10.2\", \"10.1\", \"cpu\"]]\n        + [(\"1.9\", k) for k in [\"11.1\", \"10.2\", \"cpu\"]]\n        + [(\"1.10\", k) for k in [\"11.3\", \"11.1\", \"10.2\", \"cpu\"]]\n    )\n\n    torch_versions = sorted(\n        {k[0] for k in all_versions}, key=lambda x: int(x.split(\".\")[1]), reverse=True\n    )\n    cuda_versions = sorted(\n        {k[1] for k in all_versions}, key=lambda x: float(x) if x != \"cpu\" else 0, reverse=True\n    )\n\n    table = gen_header(torch_versions)\n    for cu in cuda_versions:\n        table += f\"\"\" <tr><td align=\"left\">{cu}</td>\"\"\"\n        cu_suffix = CUDA_SUFFIX[cu]\n        for torch in torch_versions:\n            if (torch, cu) in all_versions:\n                cell = template.format(d2_version=d2_version, cuda=cu_suffix, torch=torch)\n            else:\n                cell = \"\"\n            table += f\"\"\"<td align=\"left\">{cell} </td> \"\"\"\n        table += \"</tr>\"\n    table += \"</tbody></table>\"\n    print(table)\n"
  },
  {
    "path": "VPS_Module/dev/packaging/gen_wheel_index.sh",
    "content": "#!/bin/bash -e\n# Copyright (c) Facebook, Inc. and its affiliates.\n\n\nroot=$(readlink -f $1)\nif [[ -z \"$root\" ]]; then\n  echo \"Usage: ./gen_wheel_index.sh /absolute/path/to/wheels\"\n  exit\nfi\n\nexport LC_ALL=C  # reproducible sort\n# NOTE: all sort in this script might not work when xx.10 is released\n\nindex=$root/index.html\n\ncd \"$root\"\nfor cu in cpu cu92 cu100 cu101 cu102 cu110 cu111 cu113; do\n  mkdir -p \"$root/$cu\"\n  cd \"$root/$cu\"\n  echo \"Creating $PWD/index.html ...\"\n  # First sort by torch version, then stable sort by d2 version with unique.\n  # As a result, the latest torch version for each d2 version is kept.\n  for whl in $(find -type f -name '*.whl' -printf '%P\\n' \\\n    | sort -k 1 -r  | sort -t '/' -k 2 --stable -r --unique); do\n    echo \"<a href=\\\"${whl/+/%2B}\\\">$whl</a><br>\"\n  done > index.html\n\n\n  for torch in torch*; do\n    cd \"$root/$cu/$torch\"\n\n    # list all whl for each cuda,torch version\n    echo \"Creating $PWD/index.html ...\"\n    for whl in $(find . -type f -name '*.whl' -printf '%P\\n' | sort -r); do\n      echo \"<a href=\\\"${whl/+/%2B}\\\">$whl</a><br>\"\n    done > index.html\n  done\ndone\n\ncd \"$root\"\n# Just list everything:\necho \"Creating $index ...\"\nfor whl in $(find . -type f -name '*.whl' -printf '%P\\n' | sort -r); do\n  echo \"<a href=\\\"${whl/+/%2B}\\\">$whl</a><br>\"\ndone > \"$index\"\n\n"
  },
  {
    "path": "VPS_Module/dev/packaging/pkg_helpers.bash",
    "content": "#!/bin/bash -e\n# Copyright (c) Facebook, Inc. and its affiliates.\n\n# Function to retry functions that sometimes timeout or have flaky failures\nretry () {\n    $*  || (sleep 1 && $*) || (sleep 2 && $*) || (sleep 4 && $*) || (sleep 8 && $*)\n}\n# Install with pip a bit more robustly than the default\npip_install() {\n  retry pip install --progress-bar off \"$@\"\n}\n\n\nsetup_cuda() {\n  # Now work out the CUDA settings\n  # Like other torch domain libraries, we choose common GPU architectures only.\n  # See https://github.com/pytorch/pytorch/blob/master/torch/utils/cpp_extension.py\n  # and https://github.com/pytorch/vision/blob/main/packaging/pkg_helpers.bash for reference.\n  export FORCE_CUDA=1\n  case \"$CU_VERSION\" in\n    cu113)\n      export CUDA_HOME=/usr/local/cuda-11.3/\n      export TORCH_CUDA_ARCH_LIST=\"3.7;5.0;5.2;6.0;6.1+PTX;7.0;7.5+PTX;8.0;8.6+PTX\"\n      ;;\n    cu112)\n      export CUDA_HOME=/usr/local/cuda-11.2/\n      export TORCH_CUDA_ARCH_LIST=\"3.7;5.0;5.2;6.0;6.1+PTX;7.0;7.5+PTX;8.0;8.6+PTX\"\n      ;;\n    cu111)\n      export CUDA_HOME=/usr/local/cuda-11.1/\n      export TORCH_CUDA_ARCH_LIST=\"3.7;5.0;5.2;6.0;6.1+PTX;7.0;7.5+PTX;8.0;8.6+PTX\"\n      ;;\n    cu110)\n      export CUDA_HOME=/usr/local/cuda-11.0/\n      export TORCH_CUDA_ARCH_LIST=\"3.7;5.0;5.2;6.0;6.1+PTX;7.0;7.5+PTX;8.0+PTX\"\n      ;;\n    cu102)\n      export CUDA_HOME=/usr/local/cuda-10.2/\n      export TORCH_CUDA_ARCH_LIST=\"3.7;5.0;5.2;6.0;6.1+PTX;7.0;7.5+PTX\"\n      ;;\n    cu101)\n      export CUDA_HOME=/usr/local/cuda-10.1/\n      export TORCH_CUDA_ARCH_LIST=\"3.7;5.0;5.2;6.0;6.1+PTX;7.0;7.5+PTX\"\n      ;;\n    cu100)\n      export CUDA_HOME=/usr/local/cuda-10.0/\n      export TORCH_CUDA_ARCH_LIST=\"3.7;5.0;5.2;6.0;6.1+PTX;7.0;7.5+PTX\"\n      ;;\n    cu92)\n      export CUDA_HOME=/usr/local/cuda-9.2/\n      export TORCH_CUDA_ARCH_LIST=\"3.7;5.0;5.2;6.0;6.1+PTX;7.0+PTX\"\n      ;;\n    cpu)\n      unset FORCE_CUDA\n      export CUDA_VISIBLE_DEVICES=\n      ;;\n    *)\n      echo \"Unrecognized CU_VERSION=$CU_VERSION\"\n      exit 1\n      ;;\n  esac\n}\n\nsetup_wheel_python() {\n  case \"$PYTHON_VERSION\" in\n    3.6) python_abi=cp36-cp36m ;;\n    3.7) python_abi=cp37-cp37m ;;\n    3.8) python_abi=cp38-cp38 ;;\n    3.9) python_abi=cp39-cp39 ;;\n    *)\n      echo \"Unrecognized PYTHON_VERSION=$PYTHON_VERSION\"\n      exit 1\n      ;;\n  esac\n  export PATH=\"/opt/python/$python_abi/bin:$PATH\"\n}\n"
  },
  {
    "path": "VPS_Module/dev/parse_results.sh",
    "content": "#!/bin/bash\n# Copyright (c) Facebook, Inc. and its affiliates.\n\n# A shell script that parses metrics from the log file.\n# Make it easier for developers to track performance of models.\n\nLOG=\"$1\"\n\nif [[ -z \"$LOG\" ]]; then\n\techo \"Usage: $0 /path/to/log/file\"\n\texit 1\nfi\n\n# [12/15 11:47:32] trainer INFO: Total training time: 12:15:04.446477 (0.4900 s / it)\n# [12/15 11:49:03] inference INFO: Total inference time: 0:01:25.326167 (0.13652186737060548 s / img per device, on 8 devices)\n# [12/15 11:49:03] inference INFO: Total inference pure compute time: .....\n\n# training time\ntrainspeed=$(grep -o 'Overall training.*' \"$LOG\" | grep -Eo '\\(.*\\)' | grep -o '[0-9\\.]*')\necho \"Training speed: $trainspeed s/it\"\n\n# inference time: there could be multiple inference during training\ninferencespeed=$(grep -o 'Total inference pure.*' \"$LOG\" | tail -n1 | grep -Eo '\\(.*\\)' | grep -o '[0-9\\.]*' | head -n1)\necho \"Inference speed: $inferencespeed s/it\"\n\n# [12/15 11:47:18] trainer INFO: eta: 0:00:00  iter: 90000  loss: 0.5407 (0.7256)  loss_classifier: 0.1744 (0.2446)  loss_box_reg: 0.0838 (0.1160)  loss_mask: 0.2159 (0.2722)  loss_objectness: 0.0244 (0.0429)  loss_rpn_box_reg: 0.0279 (0.0500)  time: 0.4487 (0.4899)  data: 0.0076 (0.0975) lr: 0.000200  max mem: 4161\nmemory=$(grep -o 'max[_ ]mem: [0-9]*' \"$LOG\" | tail -n1 | grep -o '[0-9]*')\necho \"Training memory: $memory MB\"\n\necho \"Easy to copypaste:\"\necho \"$trainspeed\",\"$inferencespeed\",\"$memory\"\n\necho \"------------------------------\"\n\n# [12/26 17:26:32] engine.coco_evaluation: copypaste: Task: bbox\n# [12/26 17:26:32] engine.coco_evaluation: copypaste: AP,AP50,AP75,APs,APm,APl\n# [12/26 17:26:32] engine.coco_evaluation: copypaste: 0.0017,0.0024,0.0017,0.0005,0.0019,0.0011\n# [12/26 17:26:32] engine.coco_evaluation: copypaste: Task: segm\n# [12/26 17:26:32] engine.coco_evaluation: copypaste: AP,AP50,AP75,APs,APm,APl\n# [12/26 17:26:32] engine.coco_evaluation: copypaste: 0.0014,0.0021,0.0016,0.0005,0.0016,0.0011\n\necho \"COCO Results:\"\nnum_tasks=$(grep -o 'copypaste:.*Task.*' \"$LOG\" | sort -u | wc -l)\n# each task has 3 lines\ngrep -o 'copypaste:.*' \"$LOG\" | cut -d ' ' -f 2- | tail -n $((num_tasks * 3))\n"
  },
  {
    "path": "VPS_Module/dev/run_inference_tests.sh",
    "content": "#!/bin/bash -e\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nBIN=\"python tools/train_net.py\"\nOUTPUT=\"inference_test_output\"\nNUM_GPUS=2\n\nCFG_LIST=( \"${@:1}\" )\n\nif [ ${#CFG_LIST[@]} -eq 0 ]; then\n  CFG_LIST=( ./configs/quick_schedules/*inference_acc_test.yaml )\nfi\n\necho \"========================================================================\"\necho \"Configs to run:\"\necho \"${CFG_LIST[@]}\"\necho \"========================================================================\"\n\n\nfor cfg in \"${CFG_LIST[@]}\"; do\n    echo \"========================================================================\"\n    echo \"Running $cfg ...\"\n    echo \"========================================================================\"\n    $BIN \\\n      --eval-only \\\n      --num-gpus $NUM_GPUS \\\n      --config-file \"$cfg\" \\\n      OUTPUT_DIR $OUTPUT\n      rm -rf $OUTPUT\ndone\n\n\necho \"========================================================================\"\necho \"Running demo.py ...\"\necho \"========================================================================\"\nDEMO_BIN=\"python demo/demo.py\"\nCOCO_DIR=datasets/coco/val2014\nmkdir -pv $OUTPUT\n\nset -v\n\n$DEMO_BIN --config-file ./configs/quick_schedules/panoptic_fpn_R_50_inference_acc_test.yaml \\\n  --input $COCO_DIR/COCO_val2014_0000001933* --output $OUTPUT\nrm -rf $OUTPUT\n"
  },
  {
    "path": "VPS_Module/dev/run_instant_tests.sh",
    "content": "#!/bin/bash -e\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nBIN=\"python tools/train_net.py\"\nOUTPUT=\"instant_test_output\"\nNUM_GPUS=2\n\nCFG_LIST=( \"${@:1}\" )\nif [ ${#CFG_LIST[@]} -eq 0 ]; then\n  CFG_LIST=( ./configs/quick_schedules/*instant_test.yaml )\nfi\n\necho \"========================================================================\"\necho \"Configs to run:\"\necho \"${CFG_LIST[@]}\"\necho \"========================================================================\"\n\nfor cfg in \"${CFG_LIST[@]}\"; do\n    echo \"========================================================================\"\n    echo \"Running $cfg ...\"\n    echo \"========================================================================\"\n    $BIN --num-gpus $NUM_GPUS --config-file \"$cfg\" \\\n      SOLVER.IMS_PER_BATCH $(($NUM_GPUS * 2)) \\\n      OUTPUT_DIR \"$OUTPUT\"\n    rm -rf \"$OUTPUT\"\ndone\n\n"
  },
  {
    "path": "VPS_Module/docker/Dockerfile",
    "content": "FROM nvidia/cuda:11.1.1-cudnn8-devel-ubuntu18.04\n# use an older system (18.04) to avoid opencv incompatibility (issue#3524)\n\nENV DEBIAN_FRONTEND noninteractive\nRUN apt-get update && apt-get install -y \\\n\tpython3-opencv ca-certificates python3-dev git wget sudo ninja-build\nRUN ln -sv /usr/bin/python3 /usr/bin/python\n\n# create a non-root user\nARG USER_ID=1000\nRUN useradd -m --no-log-init --system  --uid ${USER_ID} appuser -g sudo\nRUN echo '%sudo ALL=(ALL) NOPASSWD:ALL' >> /etc/sudoers\nUSER appuser\nWORKDIR /home/appuser\n\nENV PATH=\"/home/appuser/.local/bin:${PATH}\"\nRUN wget https://bootstrap.pypa.io/get-pip.py && \\\n\tpython3 get-pip.py --user && \\\n\trm get-pip.py\n\n# install dependencies\n# See https://pytorch.org/ for other options if you use a different version of CUDA\nRUN pip install --user tensorboard cmake   # cmake from apt-get is too old\nRUN pip install --user torch==1.10 torchvision==0.11.1 -f https://download.pytorch.org/whl/cu111/torch_stable.html\n\nRUN pip install --user 'git+https://github.com/facebookresearch/fvcore'\n# install detectron2\nRUN git clone https://github.com/facebookresearch/detectron2 detectron2_repo\n# set FORCE_CUDA because during `docker build` cuda is not accessible\nENV FORCE_CUDA=\"1\"\n# This will by default build detectron2 for all common cuda architectures and take a lot more time,\n# because inside `docker build`, there is no way to tell which architecture will be used.\nARG TORCH_CUDA_ARCH_LIST=\"Kepler;Kepler+Tesla;Maxwell;Maxwell+Tegra;Pascal;Volta;Turing\"\nENV TORCH_CUDA_ARCH_LIST=\"${TORCH_CUDA_ARCH_LIST}\"\n\nRUN pip install --user -e detectron2_repo\n\n# Set a fixed model cache directory.\nENV FVCORE_CACHE=\"/tmp\"\nWORKDIR /home/appuser/detectron2_repo\n\n# run detectron2 under user \"appuser\":\n# wget http://images.cocodataset.org/val2017/000000439715.jpg -O input.jpg\n# python3 demo/demo.py  \\\n\t#--config-file configs/COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_3x.yaml \\\n\t#--input input.jpg --output outputs/ \\\n\t#--opts MODEL.WEIGHTS detectron2://COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_3x/137849600/model_final_f10217.pkl\n"
  },
  {
    "path": "VPS_Module/docker/README.md",
    "content": "\n## Use the container (with docker ≥ 19.03)\n\n```\ncd docker/\n# Build:\ndocker build --build-arg USER_ID=$UID -t detectron2:v0 .\n# Launch (require GPUs):\ndocker run --gpus all -it \\\n  --shm-size=8gb --env=\"DISPLAY\" --volume=\"/tmp/.X11-unix:/tmp/.X11-unix:rw\" \\\n  --name=detectron2 detectron2:v0\n\n# Grant docker access to host X server to show images\nxhost +local:`docker inspect --format='{{ .Config.Hostname }}' detectron2`\n```\n\n## Use the container (with docker-compose ≥ 1.28.0)\n\nInstall docker-compose and nvidia-docker-toolkit, then run:\n```\ncd docker && USER_ID=$UID docker-compose run detectron2\n```\n\n## Use the deployment container (to test C++ examples)\nAfter building the base detectron2 container as above, do:\n```\n# Build:\ndocker build -t detectron2-deploy:v0 -f deploy.Dockerfile .\n# Launch:\ndocker run --gpus all -it detectron2-deploy:v0\n```\n\n#### Using a persistent cache directory\n\nYou can prevent models from being re-downloaded on every run,\nby storing them in a cache directory.\n\nTo do this, add `--volume=$HOME/.torch/fvcore_cache:/tmp:rw` in the run command.\n\n## Install new dependencies\nAdd the following to `Dockerfile` to make persistent changes.\n```\nRUN sudo apt-get update && sudo apt-get install -y vim\n```\nOr run them in the container to make temporary changes.\n"
  },
  {
    "path": "VPS_Module/docker/deploy.Dockerfile",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n# This file defines a container that compiles the C++ examples of detectron2.\n# See docker/README.md for usage.\n\n# Depends on the image produced by \"./Dockerfile\"\nFROM detectron2:v0\n\nUSER appuser\nENV HOME=/home/appuser\nWORKDIR $HOME\n\n# Let torchvision find libtorch\nENV CMAKE_PREFIX_PATH=$HOME/.local/lib/python3.6/site-packages/torch/\n\nRUN sudo apt-get update && sudo apt-get install libopencv-dev --yes\n\n# install libtorchvision\nRUN git clone --branch v0.11.1 https://github.com/pytorch/vision/\nRUN mkdir vision/build && cd vision/build && \\\n\tcmake .. -DCMAKE_INSTALL_PREFIX=$HOME/.local -DCMAKE_BUILD_TYPE=Release -DWITH_CUDA=on -DTORCH_CUDA_ARCH_LIST=$TORCH_CUDA_ARCH_LIST && \\\n\tmake -j && make install\n\n# make our installation take effect\nENV CPATH=$HOME/.local/include \\\n\t  LIBRARY_PATH=$HOME/.local/lib \\\n\t  LD_LIBRARY_PATH=$HOME/.local/lib\n\n\n# build C++ examples of detectron2\nRUN cd detectron2_repo/tools/deploy && mkdir build && cd build && \\\n\t cmake -DTORCH_CUDA_ARCH_LIST=$TORCH_CUDA_ARCH_LIST .. && make\n# binaries will be available under tools/deploy/build\n"
  },
  {
    "path": "VPS_Module/docker/docker-compose.yml",
    "content": "version: \"2.3\"\nservices:\n  detectron2:\n    build:\n      context: .\n      dockerfile: Dockerfile\n      args:\n        USER_ID: ${USER_ID:-1000}\n    deploy:\n      resources:\n        reservations:\n          devices:\n            - capabilities:\n              - gpu\n    shm_size: \"8gb\"\n    ulimits:\n      memlock: -1\n      stack: 67108864\n    volumes:\n      - /tmp/.X11-unix:/tmp/.X11-unix:ro\n    environment:\n      - DISPLAY=$DISPLAY\n      - NVIDIA_VISIBLE_DEVICES=all\n    # Uncomment with proper source to access webcam from docker\n    # devices: \n    #   - /dev/video0:/dev/video0\n"
  },
  {
    "path": "VPS_Module/docs/.gitignore",
    "content": "_build\n"
  },
  {
    "path": "VPS_Module/docs/Makefile",
    "content": "# Minimal makefile for Sphinx documentation\n# Copyright (c) Facebook, Inc. and its affiliates.\n\n# You can set these variables from the command line.\nSPHINXOPTS    =\nSPHINXBUILD   = sphinx-build\nSOURCEDIR     = .\nBUILDDIR      = _build\n\n# Put it first so that \"make\" without argument is like \"make help\".\nhelp:\n\t@$(SPHINXBUILD) -M help \"$(SOURCEDIR)\" \"$(BUILDDIR)\" $(SPHINXOPTS) $(O)\n\n.PHONY: help Makefile\n\n# Catch-all target: route all unknown targets to Sphinx using the new\n# \"make mode\" option.  $(O) is meant as a shortcut for $(SPHINXOPTS).\n%: Makefile\n\t@$(SPHINXBUILD) -M $@ \"$(SOURCEDIR)\" \"$(BUILDDIR)\" $(SPHINXOPTS) $(O)\n"
  },
  {
    "path": "VPS_Module/docs/README.md",
    "content": "# Read the docs:\n\nThe latest documentation built from this directory is available at [detectron2.readthedocs.io](https://detectron2.readthedocs.io/).\nDocuments in this directory are not meant to be read on github.\n\n# Build the docs:\n\n1. Install detectron2 according to [INSTALL.md](../INSTALL.md).\n2. Install additional libraries required to build docs:\n  - docutils==0.16\n  - Sphinx==3.2.0\n  - recommonmark==0.6.0\n  - sphinx_rtd_theme\n\n3. Run `make html` from this directory.\n"
  },
  {
    "path": "VPS_Module/docs/_static/css/custom.css",
    "content": "/*\n * Copyright (c) Facebook, Inc. and its affiliates.\n * some extra css to make markdown look similar between github/sphinx\n */\n\n/*\n * Below is for install.md:\n */\n.rst-content code {\n  white-space: pre;\n  border: 0px;\n}\n\n.rst-content th {\n  border: 1px solid #e1e4e5;\n}\n\n.rst-content th p {\n  /* otherwise will be default 24px for regular paragraph */\n  margin-bottom: 0px;\n}\n\n.rst-content .line-block {\n  /* otherwise will be 24px */\n  margin-bottom: 0px;\n}\n\ndiv.section > details {\n  padding-bottom: 1em;\n}\n"
  },
  {
    "path": "VPS_Module/docs/conf.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n\n# flake8: noqa\n\n# Configuration file for the Sphinx documentation builder.\n#\n# This file does only contain a selection of the most common options. For a\n# full list see the documentation:\n# http://www.sphinx-doc.org/en/master/config\n\n# -- Path setup --------------------------------------------------------------\n\n# If extensions (or modules to document with autodoc) are in another directory,\n# add these directories to sys.path here. If the directory is relative to the\n# documentation root, use os.path.abspath to make it absolute, like shown here.\n#\nimport os\nimport sys\nfrom unittest import mock\nfrom sphinx.domains import Domain\nfrom typing import Dict, List, Tuple\n\n# The theme to use for HTML and HTML Help pages.  See the documentation for\n# a list of builtin themes.\n#\nimport sphinx_rtd_theme\n\n\nclass GithubURLDomain(Domain):\n    \"\"\"\n    Resolve certain links in markdown files to github source.\n    \"\"\"\n\n    name = \"githuburl\"\n    ROOT = \"https://github.com/facebookresearch/detectron2/blob/main/\"\n    LINKED_DOC = [\"tutorials/install\", \"tutorials/getting_started\"]\n\n    def resolve_any_xref(self, env, fromdocname, builder, target, node, contnode):\n        github_url = None\n        if not target.endswith(\"html\") and target.startswith(\"../../\"):\n            url = target.replace(\"../\", \"\")\n            github_url = url\n        if fromdocname in self.LINKED_DOC:\n            # unresolved links in these docs are all github links\n            github_url = target\n\n        if github_url is not None:\n            if github_url.endswith(\"MODEL_ZOO\") or github_url.endswith(\"README\"):\n                # bug of recommonmark.\n                # https://github.com/readthedocs/recommonmark/blob/ddd56e7717e9745f11300059e4268e204138a6b1/recommonmark/parser.py#L152-L155\n                github_url += \".md\"\n            print(\"Ref {} resolved to github:{}\".format(target, github_url))\n            contnode[\"refuri\"] = self.ROOT + github_url\n            return [(\"githuburl:any\", contnode)]\n        else:\n            return []\n\n\n# to support markdown\nfrom recommonmark.parser import CommonMarkParser\n\nsys.path.insert(0, os.path.abspath(\"../\"))\nos.environ[\"_DOC_BUILDING\"] = \"True\"\nDEPLOY = os.environ.get(\"READTHEDOCS\") == \"True\"\n\n\n# -- Project information -----------------------------------------------------\n\n# fmt: off\ntry:\n    import torch  # noqa\nexcept ImportError:\n    for m in [\n        \"torch\", \"torchvision\", \"torch.nn\", \"torch.nn.parallel\", \"torch.distributed\", \"torch.multiprocessing\", \"torch.autograd\",\n        \"torch.autograd.function\", \"torch.nn.modules\", \"torch.nn.modules.utils\", \"torch.utils\", \"torch.utils.data\", \"torch.onnx\",\n        \"torchvision\", \"torchvision.ops\",\n    ]:\n        sys.modules[m] = mock.Mock(name=m)\n    sys.modules['torch'].__version__ = \"1.7\"  # fake version\n    HAS_TORCH = False\nelse:\n    try:\n        torch.ops.detectron2 = mock.Mock(name=\"torch.ops.detectron2\")\n    except:\n        pass\n    HAS_TORCH = True\n\nfor m in [\n    \"cv2\", \"scipy\", \"portalocker\", \"detectron2._C\",\n    \"pycocotools\", \"pycocotools.mask\", \"pycocotools.coco\", \"pycocotools.cocoeval\",\n    \"google\", \"google.protobuf\", \"google.protobuf.internal\", \"onnx\",\n    \"caffe2\", \"caffe2.proto\", \"caffe2.python\", \"caffe2.python.utils\", \"caffe2.python.onnx\", \"caffe2.python.onnx.backend\",\n]:\n    sys.modules[m] = mock.Mock(name=m)\n# fmt: on\nsys.modules[\"cv2\"].__version__ = \"3.4\"\n\nimport detectron2  # isort: skip\n\nif HAS_TORCH:\n    from detectron2.utils.env import fixup_module_metadata\n\n    fixup_module_metadata(\"torch.nn\", torch.nn.__dict__)\n    fixup_module_metadata(\"torch.utils.data\", torch.utils.data.__dict__)\n\n\nproject = \"detectron2\"\ncopyright = \"2019-2020, detectron2 contributors\"\nauthor = \"detectron2 contributors\"\n\n# The short X.Y version\nversion = detectron2.__version__\n# The full version, including alpha/beta/rc tags\nrelease = version\n\n\n# -- General configuration ---------------------------------------------------\n\n# If your documentation needs a minimal Sphinx version, state it here.\n#\nneeds_sphinx = \"3.0\"\n\n# Add any Sphinx extension module names here, as strings. They can be\n# extensions coming with Sphinx (named 'sphinx.ext.*') or your custom\n# ones.\nextensions = [\n    \"recommonmark\",\n    \"sphinx.ext.autodoc\",\n    \"sphinx.ext.napoleon\",\n    \"sphinx.ext.intersphinx\",\n    \"sphinx.ext.todo\",\n    \"sphinx.ext.coverage\",\n    \"sphinx.ext.mathjax\",\n    \"sphinx.ext.viewcode\",\n    \"sphinx.ext.githubpages\",\n]\n\n# -- Configurations for plugins ------------\nnapoleon_google_docstring = True\nnapoleon_include_init_with_doc = True\nnapoleon_include_special_with_doc = True\nnapoleon_numpy_docstring = False\nnapoleon_use_rtype = False\nautodoc_inherit_docstrings = False\nautodoc_member_order = \"bysource\"\n\nif DEPLOY:\n    intersphinx_timeout = 10\nelse:\n    # skip this when building locally\n    intersphinx_timeout = 0.5\nintersphinx_mapping = {\n    \"python\": (\"https://docs.python.org/3.6\", None),\n    \"numpy\": (\"https://docs.scipy.org/doc/numpy/\", None),\n    \"torch\": (\"https://pytorch.org/docs/master/\", None),\n}\n# -------------------------\n\n\n# Add any paths that contain templates here, relative to this directory.\ntemplates_path = [\"_templates\"]\n\nsource_suffix = [\".rst\", \".md\"]\n\n# The master toctree document.\nmaster_doc = \"index\"\n\n# The language for content autogenerated by Sphinx. Refer to documentation\n# for a list of supported languages.\n#\n# This is also used if you do content translation via gettext catalogs.\n# Usually you set \"language\" from the command line for these cases.\nlanguage = None\n\n# List of patterns, relative to source directory, that match files and\n# directories to ignore when looking for source files.\n# This pattern also affects html_static_path and html_extra_path.\nexclude_patterns = [\"_build\", \"Thumbs.db\", \".DS_Store\", \"build\", \"README.md\", \"tutorials/README.md\"]\n\n# The name of the Pygments (syntax highlighting) style to use.\npygments_style = \"sphinx\"\n\n\n# -- Options for HTML output -------------------------------------------------\n\nhtml_theme = \"sphinx_rtd_theme\"\nhtml_theme_path = [sphinx_rtd_theme.get_html_theme_path()]\n\n# Theme options are theme-specific and customize the look and feel of a theme\n# further.  For a list of options available for each theme, see the\n# documentation.\n#\n# html_theme_options = {}\n\n# Add any paths that contain custom static files (such as style sheets) here,\n# relative to this directory. They are copied after the builtin static files,\n# so a file named \"default.css\" will overwrite the builtin \"default.css\".\nhtml_static_path = [\"_static\"]\nhtml_css_files = [\"css/custom.css\"]\n\n# Custom sidebar templates, must be a dictionary that maps document names\n# to template names.\n#\n# The default sidebars (for documents that don't match any pattern) are\n# defined by theme itself.  Builtin themes are using these templates by\n# default: ``['localtoc.html', 'relations.html', 'sourcelink.html',\n# 'searchbox.html']``.\n#\n# html_sidebars = {}\n\n\n# -- Options for HTMLHelp output ---------------------------------------------\n\n# Output file base name for HTML help builder.\nhtmlhelp_basename = \"detectron2doc\"\n\n\n# -- Options for LaTeX output ------------------------------------------------\n\nlatex_elements = {\n    # The paper size ('letterpaper' or 'a4paper').\n    #\n    # 'papersize': 'letterpaper',\n    # The font size ('10pt', '11pt' or '12pt').\n    #\n    # 'pointsize': '10pt',\n    # Additional stuff for the LaTeX preamble.\n    #\n    # 'preamble': '',\n    # Latex figure (float) alignment\n    #\n    # 'figure_align': 'htbp',\n}\n\n# Grouping the document tree into LaTeX files. List of tuples\n# (source start file, target name, title,\n#  author, documentclass [howto, manual, or own class]).\nlatex_documents = [\n    (master_doc, \"detectron2.tex\", \"detectron2 Documentation\", \"detectron2 contributors\", \"manual\")\n]\n\n\n# -- Options for manual page output ------------------------------------------\n\n# One entry per manual page. List of tuples\n# (source start file, name, description, authors, manual section).\nman_pages = [(master_doc, \"detectron2\", \"detectron2 Documentation\", [author], 1)]\n\n\n# -- Options for Texinfo output ----------------------------------------------\n\n# Grouping the document tree into Texinfo files. List of tuples\n# (source start file, target name, title, author,\n#  dir menu entry, description, category)\ntexinfo_documents = [\n    (\n        master_doc,\n        \"detectron2\",\n        \"detectron2 Documentation\",\n        author,\n        \"detectron2\",\n        \"One line description of project.\",\n        \"Miscellaneous\",\n    )\n]\n\n\n# -- Options for todo extension ----------------------------------------------\n\n# If true, `todo` and `todoList` produce output, else they produce nothing.\ntodo_include_todos = True\n\n\ndef autodoc_skip_member(app, what, name, obj, skip, options):\n    # we hide something deliberately\n    if getattr(obj, \"__HIDE_SPHINX_DOC__\", False):\n        return True\n\n    # Hide some that are deprecated or not intended to be used\n    HIDDEN = {\n        \"ResNetBlockBase\",\n        \"GroupedBatchSampler\",\n        \"build_transform_gen\",\n        \"apply_transform_gens\",\n        \"TransformGen\",\n        \"apply_augmentations\",\n        \"StandardAugInput\",\n        \"build_batch_data_loader\",\n        \"draw_panoptic_seg_predictions\",\n        \"WarmupCosineLR\",\n        \"WarmupMultiStepLR\",\n        \"downgrade_config\",\n        \"upgrade_config\",\n        \"add_export_config\",\n    }\n    try:\n        if name in HIDDEN or (\n            hasattr(obj, \"__doc__\") and obj.__doc__.lower().strip().startswith(\"deprecated\")\n        ):\n            print(\"Skipping deprecated object: {}\".format(name))\n            return True\n    except:\n        pass\n    return skip\n\n\n_PAPER_DATA = {\n    \"resnet\": (\"1512.03385\", \"Deep Residual Learning for Image Recognition\"),\n    \"fpn\": (\"1612.03144\", \"Feature Pyramid Networks for Object Detection\"),\n    \"mask r-cnn\": (\"1703.06870\", \"Mask R-CNN\"),\n    \"faster r-cnn\": (\n        \"1506.01497\",\n        \"Faster R-CNN: Towards Real-Time Object Detection with Region Proposal Networks\",\n    ),\n    \"deformconv\": (\"1703.06211\", \"Deformable Convolutional Networks\"),\n    \"deformconv2\": (\"1811.11168\", \"Deformable ConvNets v2: More Deformable, Better Results\"),\n    \"panopticfpn\": (\"1901.02446\", \"Panoptic Feature Pyramid Networks\"),\n    \"retinanet\": (\"1708.02002\", \"Focal Loss for Dense Object Detection\"),\n    \"cascade r-cnn\": (\"1712.00726\", \"Cascade R-CNN: Delving into High Quality Object Detection\"),\n    \"lvis\": (\"1908.03195\", \"LVIS: A Dataset for Large Vocabulary Instance Segmentation\"),\n    \"rrpn\": (\"1703.01086\", \"Arbitrary-Oriented Scene Text Detection via Rotation Proposals\"),\n    \"imagenet in 1h\": (\"1706.02677\", \"Accurate, Large Minibatch SGD: Training ImageNet in 1 Hour\"),\n    \"xception\": (\"1610.02357\", \"Xception: Deep Learning with Depthwise Separable Convolutions\"),\n    \"mobilenet\": (\n        \"1704.04861\",\n        \"MobileNets: Efficient Convolutional Neural Networks for Mobile Vision Applications\",\n    ),\n    \"deeplabv3+\": (\n        \"1802.02611\",\n        \"Encoder-Decoder with Atrous Separable Convolution for Semantic Image Segmentation\",\n    ),\n    \"dds\": (\"2003.13678\", \"Designing Network Design Spaces\"),\n    \"scaling\": (\"2103.06877\", \"Fast and Accurate Model Scaling\"),\n    \"fcos\": (\"2006.09214\", \"FCOS: A Simple and Strong Anchor-free Object Detector\"),\n    \"rethinking-batchnorm\": (\"2105.07576\", 'Rethinking \"Batch\" in BatchNorm'),\n}\n\n\ndef paper_ref_role(\n    typ: str,\n    rawtext: str,\n    text: str,\n    lineno: int,\n    inliner,\n    options: Dict = {},\n    content: List[str] = [],\n):\n    \"\"\"\n    Parse :paper:`xxx`. Similar to the \"extlinks\" sphinx extension.\n    \"\"\"\n    from docutils import nodes, utils\n    from sphinx.util.nodes import split_explicit_title\n\n    text = utils.unescape(text)\n    has_explicit_title, title, link = split_explicit_title(text)\n    link = link.lower()\n    if link not in _PAPER_DATA:\n        inliner.reporter.warning(\"Cannot find paper \" + link)\n        paper_url, paper_title = \"#\", link\n    else:\n        paper_url, paper_title = _PAPER_DATA[link]\n        if \"/\" not in paper_url:\n            paper_url = \"https://arxiv.org/abs/\" + paper_url\n    if not has_explicit_title:\n        title = paper_title\n    pnode = nodes.reference(title, title, internal=False, refuri=paper_url)\n    return [pnode], []\n\n\ndef setup(app):\n    from recommonmark.transform import AutoStructify\n\n    app.add_domain(GithubURLDomain)\n    app.connect(\"autodoc-skip-member\", autodoc_skip_member)\n    app.add_role(\"paper\", paper_ref_role)\n    app.add_config_value(\n        \"recommonmark_config\",\n        {\"enable_math\": True, \"enable_inline_math\": True, \"enable_eval_rst\": True},\n        True,\n    )\n    app.add_transform(AutoStructify)\n"
  },
  {
    "path": "VPS_Module/docs/index.rst",
    "content": ".. detectron2 documentation master file, created by\n   sphinx-quickstart on Sat Sep 21 13:46:45 2019.\n   You can adapt this file completely to your liking, but it should at least\n   contain the root `toctree` directive.\n\nWelcome to detectron2's documentation!\n======================================\n\n.. toctree::\n   :maxdepth: 2\n\n   tutorials/index\n   notes/index\n   modules/index\n"
  },
  {
    "path": "VPS_Module/docs/modules/checkpoint.rst",
    "content": "detectron2.checkpoint \n=============================\n\n.. automodule:: detectron2.checkpoint\n    :members:\n    :undoc-members:\n    :show-inheritance:\n"
  },
  {
    "path": "VPS_Module/docs/modules/config.rst",
    "content": "detectron2.config\n=========================\n\nRelated tutorials: :doc:`../tutorials/configs`, :doc:`../tutorials/extend`.\n\n.. automodule:: detectron2.config\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\n\nYaml Config References\n-----------------\n\n.. literalinclude:: ../../detectron2/config/defaults.py\n  :language: python\n  :linenos:\n  :lines: 7-\n"
  },
  {
    "path": "VPS_Module/docs/modules/data.rst",
    "content": "detectron2.data\n=======================\n\n.. autodata:: detectron2.data.DatasetCatalog(dict)\n    :annotation:\n\n.. autodata:: detectron2.data.MetadataCatalog(dict)\n    :annotation:\n\n.. automodule:: detectron2.data\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\ndetectron2.data.detection\\_utils module\n---------------------------------------\n\n.. automodule:: detectron2.data.detection_utils\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\ndetectron2.data.datasets module\n---------------------------------------\n\n.. automodule:: detectron2.data.datasets\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\ndetectron2.data.samplers module\n---------------------------------------\n\n.. automodule:: detectron2.data.samplers\n    :members:\n    :undoc-members:\n    :show-inheritance:\n"
  },
  {
    "path": "VPS_Module/docs/modules/data_transforms.rst",
    "content": "detectron2.data.transforms \n====================================\n\nRelated tutorial: :doc:`../tutorials/augmentation`.\n\n.. automodule:: detectron2.data.transforms\n    :members:\n    :undoc-members:\n    :show-inheritance:\n    :imported-members:\n"
  },
  {
    "path": "VPS_Module/docs/modules/engine.rst",
    "content": "detectron2.engine \n=========================\n\nRelated tutorial: :doc:`../tutorials/training`.\n\n.. automodule:: detectron2.engine\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\n\ndetectron2.engine.defaults module\n---------------------------------\n\n.. automodule:: detectron2.engine.defaults\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\ndetectron2.engine.hooks module\n---------------------------------\n\n.. automodule:: detectron2.engine.hooks\n    :members:\n    :undoc-members:\n    :show-inheritance:\n"
  },
  {
    "path": "VPS_Module/docs/modules/evaluation.rst",
    "content": "detectron2.evaluation \n=============================\n\n.. automodule:: detectron2.evaluation\n    :members:\n    :undoc-members:\n    :show-inheritance:\n"
  },
  {
    "path": "VPS_Module/docs/modules/export.rst",
    "content": "detectron2.export \n=========================\n\nRelated tutorial: :doc:`../tutorials/deployment`.\n\n.. automodule:: detectron2.export\n    :members:\n    :undoc-members:\n    :show-inheritance:\n"
  },
  {
    "path": "VPS_Module/docs/modules/fvcore.rst",
    "content": "fvcore documentation\n====================\n\nDetectron2 depends on utilities in\n`fvcore <https://github.com/facebookresearch/fvcore/>`_.\nWe include part of fvcore documentation here for easier reference.\n\nfvcore.nn\n-----------------\n\n.. automodule:: fvcore.nn\n    :members:\n    :inherited-members:\n    :undoc-members:\n    :show-inheritance:\n\nfvcore.common\n---------------------\n\n.. automodule:: fvcore.common.checkpoint\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\n.. automodule:: fvcore.common.config\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\n.. automodule:: fvcore.common.history_buffer\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\n.. automodule:: fvcore.common.param_scheduler\n    :members:\n    :inherited-members:\n    :undoc-members:\n    :show-inheritance:\n\n.. automodule:: fvcore.common.registry\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\n.. automodule:: fvcore.common.timer\n    :members:\n    :undoc-members:\n    :show-inheritance:\n"
  },
  {
    "path": "VPS_Module/docs/modules/index.rst",
    "content": "API Documentation\n==================\n\n.. toctree::\n\n    checkpoint\n    config\n    data\n    data_transforms\n    engine\n    evaluation\n    layers\n    model_zoo\n    modeling\n    solver\n    structures\n    utils\n    export\n    fvcore\n"
  },
  {
    "path": "VPS_Module/docs/modules/layers.rst",
    "content": "detectron2.layers \n=========================\n\n.. automodule:: detectron2.layers\n    :members:\n    :undoc-members:\n    :show-inheritance:\n"
  },
  {
    "path": "VPS_Module/docs/modules/model_zoo.rst",
    "content": "detectron2.model_zoo \n============================\n\n.. automodule:: detectron2.model_zoo\n    :members:\n    :undoc-members:\n    :show-inheritance:\n"
  },
  {
    "path": "VPS_Module/docs/modules/modeling.rst",
    "content": "detectron2.modeling \n===========================\n\n.. automodule:: detectron2.modeling\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\n\ndetectron2.modeling.poolers module\n---------------------------------------\n\n.. automodule:: detectron2.modeling.poolers\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\n\ndetectron2.modeling.sampling module\n------------------------------------\n\n.. automodule:: detectron2.modeling.sampling\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\n\ndetectron2.modeling.box_regression module\n------------------------------------------\n\n.. automodule:: detectron2.modeling.box_regression\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\n\nModel Registries\n-----------------\n\nThese are different registries provided in modeling.\nEach registry provide you the ability to replace it with your customized component,\nwithout having to modify detectron2's code.\n\nNote that it is impossible to allow users to customize any line of code directly.\nEven just to add one line at some place,\nyou'll likely need to find out the smallest registry which contains that line,\nand register your component to that registry.\n\n\n.. autodata:: detectron2.modeling.META_ARCH_REGISTRY\n.. autodata:: detectron2.modeling.BACKBONE_REGISTRY\n.. autodata:: detectron2.modeling.PROPOSAL_GENERATOR_REGISTRY\n.. autodata:: detectron2.modeling.RPN_HEAD_REGISTRY\n.. autodata:: detectron2.modeling.ANCHOR_GENERATOR_REGISTRY\n.. autodata:: detectron2.modeling.ROI_HEADS_REGISTRY\n.. autodata:: detectron2.modeling.ROI_BOX_HEAD_REGISTRY\n.. autodata:: detectron2.modeling.ROI_MASK_HEAD_REGISTRY\n.. autodata:: detectron2.modeling.ROI_KEYPOINT_HEAD_REGISTRY\n"
  },
  {
    "path": "VPS_Module/docs/modules/solver.rst",
    "content": "detectron2.solver \n=========================\n\n.. automodule:: detectron2.solver\n    :members:\n    :undoc-members:\n    :show-inheritance:\n"
  },
  {
    "path": "VPS_Module/docs/modules/structures.rst",
    "content": "detectron2.structures \n=============================\n\n.. automodule:: detectron2.structures\n    :members:\n    :undoc-members:\n    :show-inheritance:\n"
  },
  {
    "path": "VPS_Module/docs/modules/utils.rst",
    "content": "detectron2.utils \n========================\n\ndetectron2.utils.colormap module\n--------------------------------\n\n.. automodule:: detectron2.utils.colormap\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\ndetectron2.utils.comm module\n----------------------------\n\n.. automodule:: detectron2.utils.comm\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\n\ndetectron2.utils.events module\n------------------------------\n\n.. automodule:: detectron2.utils.events\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\n\ndetectron2.utils.logger module\n------------------------------\n\n.. automodule:: detectron2.utils.logger\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\n\ndetectron2.utils.registry module\n--------------------------------\n\n.. automodule:: detectron2.utils.registry\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\ndetectron2.utils.memory module\n----------------------------------\n\n.. automodule:: detectron2.utils.memory\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\n\ndetectron2.utils.analysis module\n----------------------------------\n\n.. automodule:: detectron2.utils.analysis\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\n\ndetectron2.utils.visualizer module\n----------------------------------\n\n.. automodule:: detectron2.utils.visualizer\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\ndetectron2.utils.video\\_visualizer module\n-----------------------------------------\n\n.. automodule:: detectron2.utils.video_visualizer\n    :members:\n    :undoc-members:\n    :show-inheritance:\n\n"
  },
  {
    "path": "VPS_Module/docs/notes/benchmarks.md",
    "content": "\n# Benchmarks\n\nHere we benchmark the training speed of a Mask R-CNN in detectron2,\nwith some other popular open source Mask R-CNN implementations.\n\n\n### Settings\n\n* Hardware: 8 NVIDIA V100s with NVLink.\n* Software: Python 3.7, CUDA 10.1, cuDNN 7.6.5, PyTorch 1.5,\n  TensorFlow 1.15.0rc2, Keras 2.2.5, MxNet 1.6.0b20190820.\n* Model: an end-to-end R-50-FPN Mask-RCNN model, using the same hyperparameter as the\n  [Detectron baseline config](https://github.com/facebookresearch/Detectron/blob/master/configs/12_2017_baselines/e2e_mask_rcnn_R-50-FPN_1x.yaml)\n  (it does not have scale augmentation).\n* Metrics: We use the average throughput in iterations 100-500 to skip GPU warmup time.\n  Note that for R-CNN-style models, the throughput of a model typically changes during training, because\n  it depends on the predictions of the model. Therefore this metric is not directly comparable with\n  \"train speed\" in model zoo, which is the average speed of the entire training run.\n\n\n### Main Results\n\n```eval_rst\n+-------------------------------+--------------------+\n| Implementation                | Throughput (img/s) |\n+===============================+====================+\n| |D2| |PT|                     | 62                 |\n+-------------------------------+--------------------+\n| mmdetection_  |PT|            | 53                 |\n+-------------------------------+--------------------+\n| maskrcnn-benchmark_  |PT|     | 53                 |\n+-------------------------------+--------------------+\n| tensorpack_ |TF|              | 50                 |\n+-------------------------------+--------------------+\n| simpledet_ |mxnet|            | 39                 |\n+-------------------------------+--------------------+\n| Detectron_  |C2|              | 19                 |\n+-------------------------------+--------------------+\n| `matterport/Mask_RCNN`__ |TF| | 14                 |\n+-------------------------------+--------------------+\n\n.. _maskrcnn-benchmark: https://github.com/facebookresearch/maskrcnn-benchmark/\n.. _tensorpack: https://github.com/tensorpack/tensorpack/tree/master/examples/FasterRCNN\n.. _mmdetection: https://github.com/open-mmlab/mmdetection/\n.. _simpledet: https://github.com/TuSimple/simpledet/\n.. _Detectron: https://github.com/facebookresearch/Detectron\n__ https://github.com/matterport/Mask_RCNN/\n\n.. |D2| image:: https://github.com/facebookresearch/detectron2/raw/main/.github/Detectron2-Logo-Horz.svg?sanitize=true\n   :height: 15pt\n   :target: https://github.com/facebookresearch/detectron2/\n.. |PT| image:: https://pytorch.org/assets/images/logo-icon.svg\n   :width: 15pt\n   :height: 15pt\n   :target: https://pytorch.org\n.. |TF| image:: https://static.nvidiagrid.net/ngc/containers/tensorflow.png\n   :width: 15pt\n   :height: 15pt\n   :target: https://tensorflow.org\n.. |mxnet| image:: https://github.com/dmlc/web-data/raw/master/mxnet/image/mxnet_favicon.png\n   :width: 15pt\n   :height: 15pt\n   :target: https://mxnet.apache.org/\n.. |C2| image:: https://caffe2.ai/static/logo.svg\n   :width: 15pt\n   :height: 15pt\n   :target: https://caffe2.ai\n```\n\n\nDetails for each implementation:\n\n* __Detectron2__: with release v0.1.2, run:\n  ```\n  python tools/train_net.py  --config-file configs/Detectron1-Comparisons/mask_rcnn_R_50_FPN_noaug_1x.yaml --num-gpus 8\n  ```\n\n* __mmdetection__: at commit `b0d845f`, run\n  ```\n  ./tools/dist_train.sh configs/mask_rcnn/mask_rcnn_r50_caffe_fpn_1x_coco.py 8\n  ```\n\n* __maskrcnn-benchmark__: use commit `0ce8f6f` with `sed -i 's/torch.uint8/torch.bool/g' **/*.py; sed -i 's/AT_CHECK/TORCH_CHECK/g' **/*.cu`\n  to make it compatible with PyTorch 1.5. Then, run training with\n  ```\n  python -m torch.distributed.launch --nproc_per_node=8 tools/train_net.py --config-file configs/e2e_mask_rcnn_R_50_FPN_1x.yaml\n  ```\n  The speed we observed is faster than its model zoo, likely due to different software versions.\n\n* __tensorpack__: at commit `caafda`, `export TF_CUDNN_USE_AUTOTUNE=0`, then run\n  ```\n  mpirun -np 8 ./train.py --config DATA.BASEDIR=/data/coco TRAINER=horovod BACKBONE.STRIDE_1X1=True TRAIN.STEPS_PER_EPOCH=50 --load ImageNet-R50-AlignPadding.npz\n  ```\n\n* __SimpleDet__: at commit `9187a1`, run\n  ```\n  python detection_train.py --config config/mask_r50v1_fpn_1x.py\n  ```\n\n* __Detectron__: run\n  ```\n  python tools/train_net.py --cfg configs/12_2017_baselines/e2e_mask_rcnn_R-50-FPN_1x.yaml\n  ```\n  Note that many of its ops run on CPUs, therefore the performance is limited.\n\n* __matterport/Mask_RCNN__: at commit `3deaec`, apply the following diff, `export TF_CUDNN_USE_AUTOTUNE=0`, then run\n  ```\n  python coco.py train --dataset=/data/coco/ --model=imagenet\n  ```\n  Note that many small details in this implementation might be different\n  from Detectron's standards.\n\n  <details>\n  <summary>\n  (diff to make it use the same hyperparameters - click to expand)\n  </summary>\n\n  ```diff\n  diff --git i/mrcnn/model.py w/mrcnn/model.py\n  index 62cb2b0..61d7779 100644\n  --- i/mrcnn/model.py\n  +++ w/mrcnn/model.py\n  @@ -2367,8 +2367,8 @@ class MaskRCNN():\n        epochs=epochs,\n        steps_per_epoch=self.config.STEPS_PER_EPOCH,\n        callbacks=callbacks,\n  -            validation_data=val_generator,\n  -            validation_steps=self.config.VALIDATION_STEPS,\n  +            #validation_data=val_generator,\n  +            #validation_steps=self.config.VALIDATION_STEPS,\n        max_queue_size=100,\n        workers=workers,\n        use_multiprocessing=True,\n  diff --git i/mrcnn/parallel_model.py w/mrcnn/parallel_model.py\n  index d2bf53b..060172a 100644\n  --- i/mrcnn/parallel_model.py\n  +++ w/mrcnn/parallel_model.py\n  @@ -32,6 +32,7 @@ class ParallelModel(KM.Model):\n      keras_model: The Keras model to parallelize\n      gpu_count: Number of GPUs. Must be > 1\n      \"\"\"\n  +        super().__init__()\n      self.inner_model = keras_model\n      self.gpu_count = gpu_count\n      merged_outputs = self.make_parallel()\n  diff --git i/samples/coco/coco.py w/samples/coco/coco.py\n  index 5d172b5..239ed75 100644\n  --- i/samples/coco/coco.py\n  +++ w/samples/coco/coco.py\n  @@ -81,7 +81,10 @@ class CocoConfig(Config):\n    IMAGES_PER_GPU = 2\n\n    # Uncomment to train on 8 GPUs (default is 1)\n  -    # GPU_COUNT = 8\n  +    GPU_COUNT = 8\n  +    BACKBONE = \"resnet50\"\n  +    STEPS_PER_EPOCH = 50\n  +    TRAIN_ROIS_PER_IMAGE = 512\n\n    # Number of classes (including background)\n    NUM_CLASSES = 1 + 80  # COCO has 80 classes\n  @@ -496,29 +499,10 @@ if __name__ == '__main__':\n      # *** This training schedule is an example. Update to your needs ***\n\n      # Training - Stage 1\n  -        print(\"Training network heads\")\n      model.train(dataset_train, dataset_val,\n            learning_rate=config.LEARNING_RATE,\n            epochs=40,\n  -                    layers='heads',\n  -                    augmentation=augmentation)\n  -\n  -        # Training - Stage 2\n  -        # Finetune layers from ResNet stage 4 and up\n  -        print(\"Fine tune Resnet stage 4 and up\")\n  -        model.train(dataset_train, dataset_val,\n  -                    learning_rate=config.LEARNING_RATE,\n  -                    epochs=120,\n  -                    layers='4+',\n  -                    augmentation=augmentation)\n  -\n  -        # Training - Stage 3\n  -        # Fine tune all layers\n  -        print(\"Fine tune all layers\")\n  -        model.train(dataset_train, dataset_val,\n  -                    learning_rate=config.LEARNING_RATE / 10,\n  -                    epochs=160,\n  -                    layers='all',\n  +                    layers='3+',\n            augmentation=augmentation)\n\n    elif args.command == \"evaluate\":\n  ```\n\n  </details>\n"
  },
  {
    "path": "VPS_Module/docs/notes/changelog.md",
    "content": "# Change Log and Backward Compatibility\n\n### Releases\nSee release logs at\n[https://github.com/facebookresearch/detectron2/releases](https://github.com/facebookresearch/detectron2/releases)\nfor new updates.\n\n### Backward Compatibility\n\nDue to the research nature of what the library does, there might be backward incompatible changes.\nBut we try to reduce users' disruption by the following ways:\n* APIs listed in [API documentation](https://detectron2.readthedocs.io/modules/index.html), including\n  function/class names, their arguments, and documented class attributes, are considered *stable* unless\n  otherwise noted in the documentation.\n  They are less likely to be broken, but if needed, will trigger a deprecation warning for a reasonable period\n  before getting broken, and will be documented in release logs.\n* Others functions/classses/attributes are considered internal, and are more likely to change.\n  However, we're aware that some of them may be already used by other projects, and in particular we may\n  use them for convenience among projects under `detectron2/projects`.\n  For such APIs, we may treat them as stable APIs and also apply the above strategies.\n  They may be promoted to stable when we're ready.\n* Projects under \"detectron2/projects\" or imported with \"detectron2.projects\" are research projects\n  and are all considered experimental.\n* Classes/functions that contain the word \"default\" or are explicitly documented to produce\n  \"default behavior\" may change their behaviors when new features are added.\n\nDespite of the possible breakage, if a third-party project would like to keep up with the latest updates\nin detectron2, using it as a library will still be less disruptive than forking, because\nthe frequency and scope of API changes will be much smaller than code changes.\n\nTo see such changes, search for \"incompatible changes\" in [release logs](https://github.com/facebookresearch/detectron2/releases).\n\n### Config Version Change Log\n\nDetectron2's config version has not been changed since open source.\nThere is no need for an open source user to worry about this.\n\n* v1: Rename `RPN_HEAD.NAME` to `RPN.HEAD_NAME`.\n* v2: A batch of rename of many configurations before release.\n\n### Silent Regressions in Historical Versions:\n\nWe list a few silent regressions, since they may silently produce incorrect results and will be hard to debug.\n\n* 04/01/2020 - 05/11/2020: Bad accuracy if `TRAIN_ON_PRED_BOXES` is set to True.\n* 03/30/2020 - 04/01/2020: ResNets are not correctly built.\n* 12/19/2019 - 12/26/2019: Using aspect ratio grouping causes a drop in accuracy.\n* - 11/9/2019: Test time augmentation does not predict the last category.\n"
  },
  {
    "path": "VPS_Module/docs/notes/compatibility.md",
    "content": "# Compatibility with Other Libraries\n\n## Compatibility with Detectron (and maskrcnn-benchmark)\n\nDetectron2 addresses some legacy issues left in Detectron. As a result, their models\nare not compatible:\nrunning inference with the same model weights will produce different results in the two code bases.\n\nThe major differences regarding inference are:\n\n- The height and width of a box with corners (x1, y1) and (x2, y2) is now computed more naturally as\n  width = x2 - x1 and height = y2 - y1;\n  In Detectron, a \"+ 1\" was added both height and width.\n\n  Note that the relevant ops in Caffe2 have [adopted this change of convention](https://github.com/pytorch/pytorch/pull/20550)\n  with an extra option.\n  So it is still possible to run inference with a Detectron2-trained model in Caffe2.\n\n  The change in height/width calculations most notably changes:\n  - encoding/decoding in bounding box regression.\n  - non-maximum suppression. The effect here is very negligible, though.\n\n- RPN now uses simpler anchors with fewer quantization artifacts.\n\n  In Detectron, the anchors were quantized and\n  [do not have accurate areas](https://github.com/facebookresearch/Detectron/issues/227).\n  In Detectron2, the anchors are center-aligned to feature grid points and not quantized.\n\n- Classification layers have a different ordering of class labels.\n\n  This involves any trainable parameter with shape (..., num_categories + 1, ...).\n  In Detectron2, integer labels [0, K-1] correspond to the K = num_categories object categories\n  and the label \"K\" corresponds to the special \"background\" category.\n  In Detectron, label \"0\" means background, and labels [1, K] correspond to the K categories.\n\n- ROIAlign is implemented differently. The new implementation is [available in Caffe2](https://github.com/pytorch/pytorch/pull/23706).\n\n  1. All the ROIs are shifted by half a pixel compared to Detectron in order to create better image-feature-map alignment.\n     See `layers/roi_align.py` for details.\n     To enable the old behavior, use `ROIAlign(aligned=False)`, or `POOLER_TYPE=ROIAlign` instead of\n     `ROIAlignV2` (the default).\n\n  1. The ROIs are not required to have a minimum size of 1.\n     This will lead to tiny differences in the output, but should be negligible.\n\n- Mask inference function is different.\n\n  In Detectron2, the \"paste_mask\" function is different and should be more accurate than in Detectron. This change\n  can improve mask AP on COCO by ~0.5% absolute.\n\nThere are some other differences in training as well, but they won't affect\nmodel-level compatibility. The major ones are:\n\n- We fixed a [bug](https://github.com/facebookresearch/Detectron/issues/459) in\n  Detectron, by making `RPN.POST_NMS_TOPK_TRAIN` per-image, rather than per-batch.\n  The fix may lead to a small accuracy drop for a few models (e.g. keypoint\n  detection) and will require some parameter tuning to match the Detectron results.\n- For simplicity, we change the default loss in bounding box regression to L1 loss, instead of smooth L1 loss.\n  We have observed that this tends to slightly decrease box AP50 while improving box AP for higher\n  overlap thresholds (and leading to a slight overall improvement in box AP).\n- We interpret the coordinates in COCO bounding box and segmentation annotations\n  as coordinates in range `[0, width]` or `[0, height]`. The coordinates in\n  COCO keypoint annotations are interpreted as pixel indices in range `[0, width - 1]` or `[0, height - 1]`.\n  Note that this affects how flip augmentation is implemented.\n\n\n[This article](https://ppwwyyxx.com/blog/2021/Where-are-Pixels/)\nexplains more details on the above mentioned issues\nabout pixels, coordinates, and \"+1\"s.\n\n\n## Compatibility with Caffe2\n\nAs mentioned above, despite the incompatibilities with Detectron, the relevant\nops have been implemented in Caffe2.\nTherefore, models trained with detectron2 can be converted in Caffe2.\nSee [Deployment](../tutorials/deployment.md) for the tutorial.\n\n## Compatibility with TensorFlow\n\nMost ops are available in TensorFlow, although some tiny differences in\nthe implementation of resize / ROIAlign / padding need to be addressed.\nA working conversion script is provided by [tensorpack Faster R-CNN](https://github.com/tensorpack/tensorpack/tree/master/examples/FasterRCNN/convert_d2)\nto run a standard detectron2 model in TensorFlow.\n"
  },
  {
    "path": "VPS_Module/docs/notes/contributing.md",
    "content": "../../.github/CONTRIBUTING.md"
  },
  {
    "path": "VPS_Module/docs/notes/index.rst",
    "content": "Notes\n======================================\n\n.. toctree::\n   :maxdepth: 2\n\n   benchmarks\n   compatibility\n   contributing\n   changelog\n"
  },
  {
    "path": "VPS_Module/docs/requirements.txt",
    "content": "docutils==0.16\n# https://github.com/sphinx-doc/sphinx/commit/7acd3ada3f38076af7b2b5c9f3b60bb9c2587a3d\nsphinx==3.2.0\nrecommonmark==0.6.0\nsphinx_rtd_theme\n# Dependencies here are only those required by import\ntermcolor\nnumpy\ntqdm\nmatplotlib\ntermcolor\nyacs\ntabulate\ncloudpickle\nPillow\nfuture\ngit+git://github.com/facebookresearch/fvcore.git\nhttps://download.pytorch.org/whl/cpu/torch-1.8.1%2Bcpu-cp37-cp37m-linux_x86_64.whl\nhttps://download.pytorch.org/whl/cpu/torchvision-0.9.1%2Bcpu-cp37-cp37m-linux_x86_64.whl\nomegaconf>=2.1.0.dev24\nhydra-core>=1.1.0.dev5\n"
  },
  {
    "path": "VPS_Module/docs/tutorials/README.md",
    "content": "# Read the docs:\n\nThe latest documentation built from this directory is available at [detectron2.readthedocs.io](https://detectron2.readthedocs.io/).\nDocuments in this directory are not meant to be read on github.\n"
  },
  {
    "path": "VPS_Module/docs/tutorials/augmentation.md",
    "content": "\n# Data Augmentation\n\nAugmentation is an important part of training.\nDetectron2's data augmentation system aims at addressing the following goals:\n\n1. Allow augmenting multiple data types together\n   (e.g., images together with their bounding boxes and masks)\n2. Allow applying a sequence of statically-declared augmentation\n3. Allow adding custom new data types to augment (rotated bounding boxes, video clips, etc.)\n4. Process and manipulate the __operations__ that are applied by augmentations\n\nThe first two features cover most of the common use cases, and is also\navailable in other libraries such as [albumentations](https://medium.com/pytorch/multi-target-in-albumentations-16a777e9006e).\nSupporting other features adds some overhead to detectron2's augmentation API,\nwhich we'll explain in this tutorial.\n\nThis tutorial focuses on how to use augmentations when writing new data loaders,\nand how to write new augmentations.\nIf you use the default data loader in detectron2, it already supports taking a user-provided list of custom augmentations,\nas explained in the [Dataloader tutorial](data_loading).\n\n## Basic Usage\n\nThe basic usage of feature (1) and (2) is like the following:\n```python\nfrom detectron2.data import transforms as T\n# Define a sequence of augmentations:\naugs = T.AugmentationList([\n    T.RandomBrightness(0.9, 1.1),\n    T.RandomFlip(prob=0.5),\n    T.RandomCrop(\"absolute\", (640, 640))\n])  # type: T.Augmentation\n\n# Define the augmentation input (\"image\" required, others optional):\ninput = T.AugInput(image, boxes=boxes, sem_seg=sem_seg)\n# Apply the augmentation:\ntransform = augs(input)  # type: T.Transform\nimage_transformed = input.image  # new image\nsem_seg_transformed = input.sem_seg  # new semantic segmentation\n\n# For any extra data that needs to be augmented together, use transform, e.g.:\nimage2_transformed = transform.apply_image(image2)\npolygons_transformed = transform.apply_polygons(polygons)\n```\n\nThree basic concepts are involved here. They are:\n* [T.Augmentation](../modules/data_transforms.html#detectron2.data.transforms.Augmentation) defines the __\"policy\"__ to modify inputs.\n  * its `__call__(AugInput) -> Transform` method augments the inputs in-place, and returns the operation that is applied\n* [T.Transform](../modules/data_transforms.html#detectron2.data.transforms.Transform)\n  implements the actual __operations__ to transform data\n  * it has methods such as `apply_image`, `apply_coords` that define how to transform each data type\n* [T.AugInput](../modules/data_transforms.html#detectron2.data.transforms.AugInput)\n  stores inputs needed by `T.Augmentation` and how they should be transformed.\n  This concept is needed for some advanced usage.\n  Using this class directly should be sufficient for all common use cases,\n  since extra data not in `T.AugInput` can be augmented using the returned\n  `transform`, as shown in the above example.\n\n## Write New Augmentations\n\nMost 2D augmentations only need to know about the input image. Such augmentation can be implemented easily like this:\n\n```python\nclass MyColorAugmentation(T.Augmentation):\n    def get_transform(self, image):\n        r = np.random.rand(2)\n        return T.ColorTransform(lambda x: x * r[0] + r[1] * 10)\n\nclass MyCustomResize(T.Augmentation):\n    def get_transform(self, image):\n        old_h, old_w = image.shape[:2]\n        new_h, new_w = int(old_h * np.random.rand()), int(old_w * 1.5)\n        return T.ResizeTransform(old_h, old_w, new_h, new_w)\n\naugs = MyCustomResize()\ntransform = augs(input)\n```\n\nIn addition to image, any attributes of the given `AugInput` can be used as long\nas they are part of the function signature, e.g.:\n\n```python\nclass MyCustomCrop(T.Augmentation):\n    def get_transform(self, image, sem_seg):\n        # decide where to crop using both image and sem_seg\n        return T.CropTransform(...)\n\naugs = MyCustomCrop()\nassert hasattr(input, \"image\") and hasattr(input, \"sem_seg\")\ntransform = augs(input)\n```\n\nNew transform operation can also be added by subclassing\n[T.Transform](../modules/data_transforms.html#detectron2.data.transforms.Transform).\n\n## Advanced Usage\n\nWe give a few examples of advanced usages that\nare enabled by our system.\nThese options can be interesting to new research,\nalthough changing them is often not needed\nfor standard use cases.\n\n### Custom transform strategy\n\nInstead of only returning the augmented data, detectron2's `Augmentation` returns the __operations__ as `T.Transform`.\nThis allows users to apply custom transform strategy on their data.\nWe use keypoints data as an example.\n\nKeypoints are (x, y) coordinates, but they are not so trivial to augment due to the semantic meaning they carry.\nSuch meaning is only known to the users, therefore users may want to augment them manually\nby looking at the returned `transform`.\nFor example, when an image is horizontally flipped, we'd like to swap the keypoint annotations for \"left eye\" and \"right eye\".\nThis can be done like this (included by default in detectron2's default data loader):\n```python\n# augs, input are defined as in previous examples\ntransform = augs(input)  # type: T.Transform\nkeypoints_xy = transform.apply_coords(keypoints_xy)   # transform the coordinates\n\n# get a list of all transforms that were applied\ntransforms = T.TransformList([transform]).transforms\n# check if it is flipped for odd number of times\ndo_hflip = sum(isinstance(t, T.HFlipTransform) for t in transforms) % 2 == 1\nif do_hflip:\n    keypoints_xy = keypoints_xy[flip_indices_mapping]\n```\n\nAs another example, keypoints annotations often have a \"visibility\" field.\nA sequence of augmentations might augment a visible keypoint out of the image boundary (e.g. with cropping),\nbut then bring it back within the boundary afterwards (e.g. with image padding).\nIf users decide to label such keypoints \"invisible\",\nthen the visibility check has to happen after every transform step.\nThis can be achieved by:\n\n```python\ntransform = augs(input)  # type: T.TransformList\nassert isinstance(transform, T.TransformList)\nfor t in transform.transforms:\n    keypoints_xy = t.apply_coords(keypoints_xy)\n    visibility &= (keypoints_xy >= [0, 0] & keypoints_xy <= [W, H]).all(axis=1)\n\n# btw, detectron2's `transform_keypoint_annotations` function chooses to label such keypoints \"visible\":\n# keypoints_xy = transform.apply_coords(keypoints_xy)\n# visibility &= (keypoints_xy >= [0, 0] & keypoints_xy <= [W, H]).all(axis=1)\n```\n\n\n### Geometrically invert the transform\nIf images are pre-processed by augmentations before inference, the predicted results\nsuch as segmentation masks are localized on the augmented image.\nWe'd like to invert the applied augmentation with the [inverse()](../modules/data_transforms.html#detectron2.data.transforms.Transform.inverse)\nAPI, to obtain results on the original image:\n```python\ntransform = augs(input)\npred_mask = make_prediction(input.image)\ninv_transform = transform.inverse()\npred_mask_orig = inv_transform.apply_segmentation(pred_mask)\n```\n\n### Add new data types\n\n[T.Transform](../modules/data_transforms.html#detectron2.data.transforms.Transform)\nsupports a few common data types to transform, including images, coordinates, masks, boxes, polygons.\nIt allows registering new data types, e.g.:\n```python\n@T.HFlipTransform.register_type(\"rotated_boxes\")\ndef func(flip_transform: T.HFlipTransform, rotated_boxes: Any):\n    # do the work\n    return flipped_rotated_boxes\n\nt = HFlipTransform(width=800)\ntransformed_rotated_boxes = t.apply_rotated_boxes(rotated_boxes)  # func will be called\n```\n\n### Extend T.AugInput\n\nAn augmentation can only access attributes available in the given input.\n[T.AugInput](../modules/data_transforms.html#detectron2.data.transforms.StandardAugInput) defines \"image\", \"boxes\", \"sem_seg\",\nwhich are sufficient for common augmentation strategies to decide how to augment.\nIf not, a custom implementation is needed.\n\nBy re-implement the \"transform()\" method in AugInput, it is also possible to\naugment different fields in ways that are dependent on each other.\nSuch use case is uncommon (e.g. post-process bounding box based on augmented masks), but allowed by the system.\n\n"
  },
  {
    "path": "VPS_Module/docs/tutorials/builtin_datasets.md",
    "content": "../../datasets/README.md"
  },
  {
    "path": "VPS_Module/docs/tutorials/configs.md",
    "content": "# Yacs Configs\n\nDetectron2 provides a key-value based config system that can be\nused to obtain standard, common behaviors.\n\nThis system uses YAML and [yacs](https://github.com/rbgirshick/yacs).\nYaml is a very limited language,\nso we do not expect all features in detectron2 to be available through configs.\nIf you need something that's not available in the config space,\nplease write code using detectron2's API.\n\nWith the introduction of a more powerful [LazyConfig system](lazyconfigs.md),\nwe no longer add functionality / new keys to the Yacs/Yaml-based config system.\n\n### Basic Usage\n\nSome basic usage of the `CfgNode` object is shown here. See more in [documentation](../modules/config.html#detectron2.config.CfgNode).\n```python\nfrom detectron2.config import get_cfg\ncfg = get_cfg()    # obtain detectron2's default config\ncfg.xxx = yyy      # add new configs for your own custom components\ncfg.merge_from_file(\"my_cfg.yaml\")   # load values from a file\n\ncfg.merge_from_list([\"MODEL.WEIGHTS\", \"weights.pth\"])   # can also load values from a list of str\nprint(cfg.dump())  # print formatted configs\nwith open(\"output.yaml\", \"w\") as f:\n  f.write(cfg.dump())   # save config to file\n```\n\nIn addition to the basic Yaml syntax, the config file can\ndefine a `_BASE_: base.yaml` field, which will load a base config file first.\nValues in the base config will be overwritten in sub-configs, if there are any conflicts.\nWe provided several base configs for standard model architectures.\n\nMany builtin tools in detectron2 accept command line config overwrite:\nKey-value pairs provided in the command line will overwrite the existing values in the config file.\nFor example, [demo.py](../../demo/demo.py) can be used with\n```\n./demo.py --config-file config.yaml [--other-options] \\\n  --opts MODEL.WEIGHTS /path/to/weights INPUT.MIN_SIZE_TEST 1000\n```\n\nTo see a list of available configs in detectron2 and what they mean,\ncheck [Config References](../modules/config.html#config-references)\n\n### Configs in Projects\n\nA project that lives outside the detectron2 library may define its own configs, which will need to be added\nfor the project to be functional, e.g.:\n```python\nfrom detectron2.projects.point_rend import add_pointrend_config\ncfg = get_cfg()    # obtain detectron2's default config\nadd_pointrend_config(cfg)  # add pointrend's default config\n# ... ...\n```\n\n### Best Practice with Configs\n\n1. Treat the configs you write as \"code\": avoid copying them or duplicating them; use `_BASE_`\n   to share common parts between configs.\n\n2. Keep the configs you write simple: don't include keys that do not affect the experimental setting.\n"
  },
  {
    "path": "VPS_Module/docs/tutorials/data_loading.md",
    "content": "\n# Dataloader\n\nDataloader is the component that provides data to models.\nA dataloader usually (but not necessarily) takes raw information from [datasets](./datasets.md),\nand process them into a format needed by the model.\n\n## How the Existing Dataloader Works\n\nDetectron2 contains a builtin data loading pipeline.\nIt's good to understand how it works, in case you need to write a custom one.\n\nDetectron2 provides two functions\n[build_detection_{train,test}_loader](../modules/data.html#detectron2.data.build_detection_train_loader)\nthat create a default data loader from a given config.\nHere is how `build_detection_{train,test}_loader` work:\n\n1. It takes the name of a registered dataset (e.g., \"coco_2017_train\") and loads a `list[dict]` representing the dataset items\n   in a lightweight format. These dataset items are not yet ready to be used by the model (e.g., images are\n   not loaded into memory, random augmentations have not been applied, etc.).\n   Details about the dataset format and dataset registration can be found in\n   [datasets](./datasets.md).\n2. Each dict in this list is mapped by a function (\"mapper\"):\n   * Users can customize this mapping function by specifying the \"mapper\" argument in\n        `build_detection_{train,test}_loader`. The default mapper is [DatasetMapper](../modules/data.html#detectron2.data.DatasetMapper).\n   * The output format of the mapper can be arbitrary, as long as it is accepted by the consumer of this data loader (usually the model).\n     The outputs of the default mapper, after batching, follow the default model input format documented in\n     [Use Models](./models.html#model-input-format).\n   * The role of the mapper is to transform the lightweight representation of a dataset item into a format\n     that is ready for the model to consume (including, e.g., read images, perform random data augmentation and convert to torch Tensors).\n     If you would like to perform custom transformations to data, you often want a custom mapper.\n3. The outputs of the mapper are batched (simply into a list).\n4. This batched data is the output of the data loader. Typically, it's also the input of\n   `model.forward()`.\n\n\n## Write a Custom Dataloader\n\nUsing a different \"mapper\" with `build_detection_{train,test}_loader(mapper=)` works for most use cases\nof custom data loading.\nFor example, if you want to resize all images to a fixed size for training, use:\n\n```python\nimport detectron2.data.transforms as T\nfrom detectron2.data import DatasetMapper   # the default mapper\ndataloader = build_detection_train_loader(cfg,\n   mapper=DatasetMapper(cfg, is_train=True, augmentations=[\n      T.Resize((800, 800))\n   ]))\n# use this dataloader instead of the default\n```\nIf the arguments of the default [DatasetMapper](../modules/data.html#detectron2.data.DatasetMapper)\ndoes not provide what you need, you may write a custom mapper function and use it instead, e.g.:\n\n```python\nfrom detectron2.data import detection_utils as utils\n # Show how to implement a minimal mapper, similar to the default DatasetMapper\ndef mapper(dataset_dict):\n    dataset_dict = copy.deepcopy(dataset_dict)  # it will be modified by code below\n    # can use other ways to read image\n    image = utils.read_image(dataset_dict[\"file_name\"], format=\"BGR\")\n    # See \"Data Augmentation\" tutorial for details usage\n    auginput = T.AugInput(image)\n    transform = T.Resize((800, 800))(auginput)\n    image = torch.from_numpy(auginput.image.transpose(2, 0, 1))\n    annos = [\n        utils.transform_instance_annotations(annotation, [transform], image.shape[1:])\n        for annotation in dataset_dict.pop(\"annotations\")\n    ]\n    return {\n       # create the format that the model expects\n       \"image\": image,\n       \"instances\": utils.annotations_to_instances(annos, image.shape[1:])\n    }\ndataloader = build_detection_train_loader(cfg, mapper=mapper)\n```\n\nIf you want to change not only the mapper (e.g., in order to implement different sampling or batching logic),\n`build_detection_train_loader` won't work and you will need to write a different data loader.\nThe data loader is simply a\npython iterator that produces [the format](./models.md) that the model accepts.\nYou can implement it using any tools you like.\n\nNo matter what to implement, it's recommended to\ncheck out [API documentation of detectron2.data](../modules/data) to learn more about the APIs of\nthese functions.\n\n## Use a Custom Dataloader\n\nIf you use [DefaultTrainer](../modules/engine.html#detectron2.engine.defaults.DefaultTrainer),\nyou can overwrite its `build_{train,test}_loader` method to use your own dataloader.\nSee the [deeplab dataloader](../../projects/DeepLab/train_net.py)\nfor an example.\n\nIf you write your own training loop, you can plug in your data loader easily.\n"
  },
  {
    "path": "VPS_Module/docs/tutorials/datasets.md",
    "content": "# Use Custom Datasets\n\nThis document explains how the dataset APIs\n([DatasetCatalog](../modules/data.html#detectron2.data.DatasetCatalog), [MetadataCatalog](../modules/data.html#detectron2.data.MetadataCatalog))\nwork, and how to use them to add custom datasets.\n\nDatasets that have builtin support in detectron2 are listed in [builtin datasets](builtin_datasets.md).\nIf you want to use a custom dataset while also reusing detectron2's data loaders,\nyou will need to:\n\n1. __Register__ your dataset (i.e., tell detectron2 how to obtain your dataset).\n2. Optionally, __register metadata__ for your dataset.\n\nNext, we explain the above two concepts in detail.\n\nThe [Colab tutorial](https://colab.research.google.com/drive/16jcaJoc6bCFAQ96jDe2HwtXj7BMD_-m5)\nhas a live example of how to register and train on a dataset of custom formats.\n\n### Register a Dataset\n\nTo let detectron2 know how to obtain a dataset named \"my_dataset\", users need to implement\na function that returns the items in your dataset and then tell detectron2 about this\nfunction:\n```python\ndef my_dataset_function():\n  ...\n  return list[dict] in the following format\n\nfrom detectron2.data import DatasetCatalog\nDatasetCatalog.register(\"my_dataset\", my_dataset_function)\n# later, to access the data:\ndata: List[Dict] = DatasetCatalog.get(\"my_dataset\")\n```\n\nHere, the snippet associates a dataset named \"my_dataset\" with a function that returns the data.\nThe function must return the same data (with same order) if called multiple times.\nThe registration stays effective until the process exits.\n\nThe function can do arbitrary things and should return the data in `list[dict]`, each dict in either\nof the following formats:\n1. Detectron2's standard dataset dict, described below. This will make it work with many other builtin\n   features in detectron2, so it's recommended to use it when it's sufficient.\n2. Any custom format. You can also return arbitrary dicts in your own format,\n   such as adding extra keys for new tasks.\n   Then you will need to handle them properly downstream as well.\n   See below for more details.\n\n#### Standard Dataset Dicts\n\nFor standard tasks\n(instance detection, instance/semantic/panoptic segmentation, keypoint detection),\nwe load the original dataset into `list[dict]` with a specification similar to COCO's annotations.\nThis is our standard representation for a dataset.\n\nEach dict contains information about one image.\nThe dict may have the following fields,\nand the required fields vary based on what the dataloader or the task needs (see more below).\n\n```eval_rst\n.. list-table::\n  :header-rows: 1\n\n  * - Task\n    - Fields\n  * - Common\n    - file_name, height, width, image_id\n\n  * - Instance detection/segmentation\n    - annotations\n\n  * - Semantic segmentation\n    - sem_seg_file_name\n\n  * - Panoptic segmentation\n    - pan_seg_file_name, segments_info\n```\n\n+ `file_name`: the full path to the image file.\n+ `height`, `width`: integer. The shape of the image.\n+ `image_id` (str or int): a unique id that identifies this image. Required by many\n  evaluators to identify the images, but a dataset may use it for different purposes.\n+ `annotations` (list[dict]): Required by __instance detection/segmentation or keypoint detection__ tasks.\n  Each dict corresponds to annotations of one instance in this image, and\n  may contain the following keys:\n  + `bbox` (list[float], required): list of 4 numbers representing the bounding box of the instance.\n  + `bbox_mode` (int, required): the format of bbox.  It must be a member of\n    [structures.BoxMode](../modules/structures.html#detectron2.structures.BoxMode).\n    Currently supports: `BoxMode.XYXY_ABS`, `BoxMode.XYWH_ABS`.\n  + `category_id` (int, required): an integer in the range [0, num_categories-1] representing the category label.\n    The value num_categories is reserved to represent the \"background\" category, if applicable.\n  + `segmentation` (list[list[float]] or dict): the segmentation mask of the instance.\n    + If `list[list[float]]`, it represents a list of polygons, one for each connected component\n      of the object. Each `list[float]` is one simple polygon in the format of `[x1, y1, ..., xn, yn]` (n≥3).\n      The Xs and Ys are absolute coordinates in unit of pixels.\n    + If `dict`, it represents the per-pixel segmentation mask in COCO's compressed RLE format.\n      The dict should have keys \"size\" and \"counts\". You can convert a uint8 segmentation mask of 0s and\n      1s into such dict by `pycocotools.mask.encode(np.asarray(mask, order=\"F\"))`.\n      `cfg.INPUT.MASK_FORMAT` must be set to `bitmask` if using the default data loader with such format.\n  + `keypoints` (list[float]): in the format of [x1, y1, v1,..., xn, yn, vn].\n    v[i] means the [visibility](http://cocodataset.org/#format-data) of this keypoint.\n    `n` must be equal to the number of keypoint categories.\n    The Xs and Ys are absolute real-value coordinates in range [0, W or H].\n\n    (Note that the keypoint coordinates in COCO format are integers in range [0, W-1 or H-1], which is different\n    from our standard format. Detectron2 adds 0.5 to COCO keypoint coordinates to convert them from discrete\n    pixel indices to floating point coordinates.)\n  + `iscrowd`: 0 (default) or 1. Whether this instance is labeled as COCO's \"crowd\n    region\". Don't include this field if you don't know what it means.\n\n  If `annotations` is an empty list, it means the image is labeled to have no objects.\n  Such images will by default be removed from training,\n  but can be included using `DATALOADER.FILTER_EMPTY_ANNOTATIONS`.\n\n+ `sem_seg_file_name` (str):\n  The full path to the semantic segmentation ground truth file.\n  It should be a grayscale image whose pixel values are integer labels.\n+ `pan_seg_file_name` (str):\n  The full path to panoptic segmentation ground truth file.\n  It should be an RGB image whose pixel values are integer ids encoded using the\n  [panopticapi.utils.id2rgb](https://github.com/cocodataset/panopticapi/) function.\n  The ids are defined by `segments_info`.\n  If an id does not appear in `segments_info`, the pixel is considered unlabeled\n  and is usually ignored in training & evaluation.\n+ `segments_info` (list[dict]): defines the meaning of each id in panoptic segmentation ground truth.\n  Each dict has the following keys:\n  + `id` (int): integer that appears in the ground truth image.\n  + `category_id` (int): an integer in the range [0, num_categories-1] representing the category label.\n  + `iscrowd`: 0 (default) or 1. Whether this instance is labeled as COCO's \"crowd region\".\n\n\n```eval_rst\n\n.. note::\n\n   The PanopticFPN model does not use the panoptic segmentation\n   format defined here, but a combination of both instance segmentation and semantic segmentation data\n   format. See :doc:`builtin_datasets` for instructions on COCO.\n\n```\n\nFast R-CNN (with pre-computed proposals) models are rarely used today.\nTo train a Fast R-CNN, the following extra keys are needed:\n\n+ `proposal_boxes` (array): 2D numpy array with shape (K, 4) representing K precomputed proposal boxes for this image.\n+ `proposal_objectness_logits` (array): numpy array with shape (K, ), which corresponds to the objectness\n logits of proposals in 'proposal_boxes'.\n+ `proposal_bbox_mode` (int): the format of the precomputed proposal bbox.\n It must be a member of\n [structures.BoxMode](../modules/structures.html#detectron2.structures.BoxMode).\n Default is `BoxMode.XYXY_ABS`.\n\n\n\n#### Custom Dataset Dicts for New Tasks\n\nIn the `list[dict]` that your dataset function returns, the dictionary can also have __arbitrary custom data__.\nThis will be useful for a new task that needs extra information not covered\nby the standard dataset dicts. In this case, you need to make sure the downstream code can handle your data\ncorrectly. Usually this requires writing a new `mapper` for the dataloader (see [Use Custom Dataloaders](./data_loading.md)).\n\nWhen designing a custom format, note that all dicts are stored in memory\n(sometimes serialized and with multiple copies).\nTo save memory, each dict is meant to contain __small__ but sufficient information\nabout each sample, such as file names and annotations.\nLoading full samples typically happens in the data loader.\n\nFor attributes shared among the entire dataset, use `Metadata` (see below).\nTo avoid extra memory, do not save such information inside each sample.\n\n### \"Metadata\" for Datasets\n\nEach dataset is associated with some metadata, accessible through\n`MetadataCatalog.get(dataset_name).some_metadata`.\nMetadata is a key-value mapping that contains information that's shared among\nthe entire dataset, and usually is used to interpret what's in the dataset, e.g.,\nnames of classes, colors of classes, root of files, etc.\nThis information will be useful for augmentation, evaluation, visualization, logging, etc.\nThe structure of metadata depends on what is needed from the corresponding downstream code.\n\nIf you register a new dataset through `DatasetCatalog.register`,\nyou may also want to add its corresponding metadata through\n`MetadataCatalog.get(dataset_name).some_key = some_value`, to enable any features that need the metadata.\nYou can do it like this (using the metadata key \"thing_classes\" as an example):\n\n```python\nfrom detectron2.data import MetadataCatalog\nMetadataCatalog.get(\"my_dataset\").thing_classes = [\"person\", \"dog\"]\n```\n\nHere is a list of metadata keys that are used by builtin features in detectron2.\nIf you add your own dataset without these metadata, some features may be\nunavailable to you:\n\n* `thing_classes` (list[str]): Used by all instance detection/segmentation tasks.\n  A list of names for each instance/thing category.\n  If you load a COCO format dataset, it will be automatically set by the function `load_coco_json`.\n\n* `thing_colors` (list[tuple(r, g, b)]): Pre-defined color (in [0, 255]) for each thing category.\n  Used for visualization. If not given, random colors will be used.\n\n* `stuff_classes` (list[str]): Used by semantic and panoptic segmentation tasks.\n  A list of names for each stuff category.\n\n* `stuff_colors` (list[tuple(r, g, b)]): Pre-defined color (in [0, 255]) for each stuff category.\n  Used for visualization. If not given, random colors are used.\n\n* `ignore_label` (int): Used by semantic and panoptic segmentation tasks. Pixels in ground-truth\n  annotations with this category label should be ignored in evaluation. Typically these are \"unlabeled\"\n  pixels.\n\n* `keypoint_names` (list[str]): Used by keypoint detection. A list of names for each keypoint.\n\n* `keypoint_flip_map` (list[tuple[str]]): Used by keypoint detection. A list of pairs of names,\n  where each pair are the two keypoints that should be flipped if the image is\n  flipped horizontally during augmentation.\n* `keypoint_connection_rules`: list[tuple(str, str, (r, g, b))]. Each tuple specifies a pair of keypoints\n  that are connected and the color (in [0, 255]) to use for the line between them when visualized.\n\nSome additional metadata that are specific to the evaluation of certain datasets (e.g. COCO):\n\n* `thing_dataset_id_to_contiguous_id` (dict[int->int]): Used by all instance detection/segmentation tasks in the COCO format.\n  A mapping from instance class ids in the dataset to contiguous ids in range [0, #class).\n  Will be automatically set by the function `load_coco_json`.\n\n* `stuff_dataset_id_to_contiguous_id` (dict[int->int]): Used when generating prediction json files for\n  semantic/panoptic segmentation.\n  A mapping from semantic segmentation class ids in the dataset\n  to contiguous ids in [0, num_categories). It is useful for evaluation only.\n\n* `json_file`: The COCO annotation json file. Used by COCO evaluation for COCO-format datasets.\n* `panoptic_root`, `panoptic_json`: Used by COCO-format panoptic evaluation.\n* `evaluator_type`: Used by the builtin main training script to select\n   evaluator. Don't use it in a new training script.\n   You can just provide the [DatasetEvaluator](../modules/evaluation.html#detectron2.evaluation.DatasetEvaluator)\n   for your dataset directly in your main script.\n\n```eval_rst\n.. note::\n\n   In recognition, sometimes we use the term \"thing\" for instance-level tasks,\n   and \"stuff\" for semantic segmentation tasks.\n   Both are used in panoptic segmentation tasks.\n   For background on the concept of \"thing\" and \"stuff\", see\n   `On Seeing Stuff: The Perception of Materials by Humans and Machines\n   <http://persci.mit.edu/pub_pdfs/adelson_spie_01.pdf>`_.\n```\n\n### Register a COCO Format Dataset\n\nIf your instance-level (detection, segmentation, keypoint) dataset is already a json file in the COCO format,\nthe dataset and its associated metadata can be registered easily with:\n```python\nfrom detectron2.data.datasets import register_coco_instances\nregister_coco_instances(\"my_dataset\", {}, \"json_annotation.json\", \"path/to/image/dir\")\n```\n\nIf your dataset is in COCO format but need to be further processed, or has extra custom per-instance annotations,\nthe [load_coco_json](../modules/data.html#detectron2.data.datasets.load_coco_json)\nfunction might be useful.\n\n### Update the Config for New Datasets\n\nOnce you've registered the dataset, you can use the name of the dataset (e.g., \"my_dataset\" in\nexample above) in `cfg.DATASETS.{TRAIN,TEST}`.\nThere are other configs you might want to change to train or evaluate on new datasets:\n\n* `MODEL.ROI_HEADS.NUM_CLASSES` and `MODEL.RETINANET.NUM_CLASSES` are the number of thing classes\n  for R-CNN and RetinaNet models, respectively.\n* `MODEL.ROI_KEYPOINT_HEAD.NUM_KEYPOINTS` sets the number of keypoints for Keypoint R-CNN.\n  You'll also need to set [Keypoint OKS](http://cocodataset.org/#keypoints-eval)\n  with `TEST.KEYPOINT_OKS_SIGMAS` for evaluation.\n* `MODEL.SEM_SEG_HEAD.NUM_CLASSES` sets the number of stuff classes for Semantic FPN & Panoptic FPN.\n* `TEST.DETECTIONS_PER_IMAGE` controls the maximum number of objects to be detected.\n  Set it to a larger number if test images may contain >100 objects.\n* If you're training Fast R-CNN (with precomputed proposals), `DATASETS.PROPOSAL_FILES_{TRAIN,TEST}`\n  need to match the datasets. The format of proposal files are documented\n  [here](../modules/data.html#detectron2.data.load_proposals_into_dataset).\n\nNew models\n(e.g. [TensorMask](../../projects/TensorMask),\n[PointRend](../../projects/PointRend))\noften have similar configs of their own that need to be changed as well.\n\n```eval_rst\n.. tip::\n\n   After changing the number of classes, certain layers in a pre-trained model will become incompatible\n   and therefore cannot be loaded to the new model.\n   This is expected, and loading such pre-trained models will produce warnings about such layers.\n```\n"
  },
  {
    "path": "VPS_Module/docs/tutorials/deployment.md",
    "content": "# Deployment\n\nModels written in Python need to go through an export process to become a deployable artifact.\nA few basic concepts about this process:\n\n__\"Export method\"__ is how a Python model is fully serialized to a deployable format.\nWe support the following export methods:\n\n* `tracing`: see [pytorch documentation](https://pytorch.org/tutorials/beginner/Intro_to_TorchScript_tutorial.html) to learn about it\n* `scripting`: see [pytorch documentation](https://pytorch.org/tutorials/beginner/Intro_to_TorchScript_tutorial.html) to learn about it\n* `caffe2_tracing`: replace parts of the model by caffe2 operators, then use tracing.\n\n__\"Format\"__ is how a serialized model is described in a file, e.g.\nTorchScript, Caffe2 protobuf, ONNX format.\n__\"Runtime\"__ is an engine that loads a serialized model and executes it,\ne.g., PyTorch, Caffe2, TensorFlow, onnxruntime, TensorRT, etc.\nA runtime is often tied to a specific format\n(e.g. PyTorch needs TorchScript format, Caffe2 needs protobuf format).\nWe currently support the following combination and each has some limitations:\n\n```eval_rst\n+----------------------------+-------------+-------------+-----------------------------+\n|       Export Method        |   tracing   |  scripting  |       caffe2_tracing        |\n+============================+=============+=============+=============================+\n| **Formats**                | TorchScript | TorchScript | Caffe2, TorchScript, ONNX   |\n+----------------------------+-------------+-------------+-----------------------------+\n| **Runtime**                | PyTorch     | PyTorch     | Caffe2, PyTorch             |\n+----------------------------+-------------+-------------+-----------------------------+\n| C++/Python inference       | ✅          | ✅          | ✅                          |\n+----------------------------+-------------+-------------+-----------------------------+\n| Dynamic resolution         | ✅          | ✅          | ✅                          |\n+----------------------------+-------------+-------------+-----------------------------+\n| Batch size requirement     | Constant    | Dynamic     | Batch inference unsupported |\n+----------------------------+-------------+-------------+-----------------------------+\n| Extra runtime deps         | torchvision | torchvision | Caffe2 ops (usually already |\n|                            |             |             |                             |\n|                            |             |             | included in PyTorch)        |\n+----------------------------+-------------+-------------+-----------------------------+\n| Faster/Mask/Keypoint R-CNN | ✅          | ✅          | ✅                          |\n+----------------------------+-------------+-------------+-----------------------------+\n| RetinaNet                  | ✅          | ✅          | ✅                          |\n+----------------------------+-------------+-------------+-----------------------------+\n| PointRend R-CNN            | ✅          | ❌          | ❌                          |\n+----------------------------+-------------+-------------+-----------------------------+\n| Cascade R-CNN              | ✅          | ❌          | ❌                          |\n+----------------------------+-------------+-------------+-----------------------------+\n\n```\n\n`caffe2_tracing` is going to be deprecated.\nWe don't plan to work on additional support for other formats/runtime, but contributions are welcome.\n\n\n## Deployment with Tracing or Scripting\n\nModels can be exported to TorchScript format, by either\n[tracing or scripting](https://pytorch.org/tutorials/beginner/Intro_to_TorchScript_tutorial.html).\nThe output model file can be loaded without detectron2 dependency in either Python or C++.\nThe exported model often requires torchvision (or its C++ library) dependency for some custom ops.\n\nThis feature requires PyTorch ≥ 1.8.\n\n### Coverage\nMost official models under the meta architectures `GeneralizedRCNN` and `RetinaNet`\nare supported in both tracing and scripting mode.\nCascade R-CNN and PointRend are currently supported in tracing.\nUsers' custom extensions are supported if they are also scriptable or traceable.\n\nFor models exported with tracing, dynamic input resolution is allowed, but batch size\n(number of input images) must be fixed.\nScripting can support dynamic batch size.\n\n### Usage\n\nThe main export APIs for tracing and scripting are [TracingAdapter](../modules/export.html#detectron2.export.TracingAdapter)\nand [scripting_with_instances](../modules/export.html#detectron2.export.scripting_with_instances).\nTheir usage is currently demonstrated in [test_export_torchscript.py](../../tests/test_export_torchscript.py)\n(see `TestScripting` and `TestTracing`)\nas well as the [deployment example](../../tools/deploy).\nPlease check that these examples can run, and then modify for your use cases.\nThe usage now requires some user effort and necessary knowledge for each model to workaround the limitation of scripting and tracing.\nIn the future we plan to wrap these under simpler APIs to lower the bar to use them.\n\n## Deployment with Caffe2-tracing\nWe provide [Caffe2Tracer](../modules/export.html#detectron2.export.Caffe2Tracer)\nthat performs the export logic.\nIt replaces parts of the model with Caffe2 operators,\nand then export the model into Caffe2, TorchScript or ONNX format.\n\nThe converted model is able to run in either Python or C++ without detectron2/torchvision dependency, on CPU or GPUs.\nIt has a runtime optimized for CPU & mobile inference, but not optimized for GPU inference.\n\nThis feature requires 1.9 > ONNX ≥ 1.6.\n\n### Coverage\n\nMost official models under these 3 common meta architectures: `GeneralizedRCNN`, `RetinaNet`, `PanopticFPN`\nare supported. Cascade R-CNN is not supported. Batch inference is not supported.\n\nUsers' custom extensions under these architectures (added through registration) are supported\nas long as they do not contain control flow or operators not available in Caffe2 (e.g. deformable convolution).\nFor example, custom backbones and heads are often supported out of the box.\n\n### Usage\n\nThe APIs are listed at [the API documentation](../modules/export).\nWe provide [export_model.py](../../tools/deploy/) as an example that uses\nthese APIs to convert a standard model. For custom models/datasets, you can add them to this script.\n\n### Use the model in C++/Python\n\nThe model can be loaded in C++ and deployed with\neither Caffe2 or Pytorch runtime.. [C++ examples](../../tools/deploy/) for Mask R-CNN\nare given as a reference. Note that:\n\n* Models exported with `caffe2_tracing` method take a special input format\n  described in [documentation](../modules/export.html#detectron2.export.Caffe2Tracer).\n  This was taken care of in the C++ example.\n\n* The converted models do not contain post-processing operations that\n  transform raw layer outputs into formatted predictions.\n  For example, the C++ examples only produce raw outputs (28x28 masks) from the final\n  layers that are not post-processed, because in actual deployment, an application often needs\n  its custom lightweight post-processing, so this step is left for users.\n\nTo help use the Caffe2-format model in python,\nwe provide a python wrapper around the converted model, in the\n[Caffe2Model.\\_\\_call\\_\\_](../modules/export.html#detectron2.export.Caffe2Model.__call__) method.\nThis method has an interface that's identical to the [pytorch versions of models](./models.md),\nand it internally applies pre/post-processing code to match the formats.\nThis wrapper can serve as a reference for how to use Caffe2's python API,\nor for how to implement pre/post-processing in actual deployment.\n\n## Conversion to TensorFlow\n[tensorpack Faster R-CNN](https://github.com/tensorpack/tensorpack/tree/master/examples/FasterRCNN/convert_d2)\nprovides scripts to convert a few standard detectron2 R-CNN models to TensorFlow's pb format.\nIt works by translating configs and weights, therefore only support a few models.\n"
  },
  {
    "path": "VPS_Module/docs/tutorials/evaluation.md",
    "content": "\n# Evaluation\n\nEvaluation is a process that takes a number of inputs/outputs pairs and aggregate them.\nYou can always [use the model](./models.md) directly and just parse its inputs/outputs manually to perform\nevaluation.\nAlternatively, evaluation is implemented in detectron2 using the [DatasetEvaluator](../modules/evaluation.html#detectron2.evaluation.DatasetEvaluator)\ninterface.\n\nDetectron2 includes a few `DatasetEvaluator` that computes metrics using standard dataset-specific\nAPIs (e.g., COCO, LVIS).\nYou can also implement your own `DatasetEvaluator` that performs some other jobs\nusing the inputs/outputs pairs.\nFor example, to count how many instances are detected on the validation set:\n\n```\nclass Counter(DatasetEvaluator):\n  def reset(self):\n    self.count = 0\n  def process(self, inputs, outputs):\n    for output in outputs:\n      self.count += len(output[\"instances\"])\n  def evaluate(self):\n    # save self.count somewhere, or print it, or return it.\n    return {\"count\": self.count}\n```\n\n## Use evaluators\n\nTo evaluate using the methods of evaluators manually:\n```\ndef get_all_inputs_outputs():\n  for data in data_loader:\n    yield data, model(data)\n\nevaluator.reset()\nfor inputs, outputs in get_all_inputs_outputs():\n  evaluator.process(inputs, outputs)\neval_results = evaluator.evaluate()\n```\n\nEvaluators can also be used with [inference_on_dataset](../modules/evaluation.html#detectron2.evaluation.inference_on_dataset).\nFor example,\n\n```python\neval_results = inference_on_dataset(\n    model,\n    data_loader,\n    DatasetEvaluators([COCOEvaluator(...), Counter()]))\n```\nThis will execute `model` on all inputs from `data_loader`, and call evaluator to process them.\n\nCompared to running the evaluation manually using the model, the benefit of this function is that\nevaluators can be merged together using [DatasetEvaluators](../modules/evaluation.html#detectron2.evaluation.DatasetEvaluators),\nand all the evaluation can finish in one forward pass over the dataset.\nThis function also provides accurate speed benchmarks for the given model and dataset.\n\n## Evaluators for custom dataset\n\nMany evaluators in detectron2 are made for specific datasets,\nin order to obtain scores using each dataset's official API.\nIn addition to that, two evaluators are able to evaluate any generic dataset\nthat follows detectron2's [standard dataset format](./datasets.md), so they\ncan be used to evaluate custom datasets:\n\n* [COCOEvaluator](../modules/evaluation.html#detectron2.evaluation.COCOEvaluator) is able to evaluate AP (Average Precision) for box detection,\n  instance segmentation, keypoint detection on any custom dataset.\n* [SemSegEvaluator](../modules/evaluation.html#detectron2.evaluation.SemSegEvaluator) is able to evaluate semantic segmentation metrics on any custom dataset.\n"
  },
  {
    "path": "VPS_Module/docs/tutorials/extend.md",
    "content": "# Extend Detectron2's Defaults\n\n__Research is about doing things in new ways__.\nThis brings a tension in how to create abstractions in code,\nwhich is a challenge for any research engineering project of a significant size:\n\n1. On one hand, it needs to have very thin abstractions to allow for the possibility of doing\n   everything in new ways. It should be reasonably easy to break existing\n   abstractions and replace them with new ones.\n\n2. On the other hand, such a project also needs reasonably high-level\n   abstractions, so that users can easily do things in standard ways,\n   without worrying too much about the details that only certain researchers care about.\n\nIn detectron2, there are two types of interfaces that address this tension together:\n\n1. Functions and classes that take a config (`cfg`) argument\n   created from a yaml file\n   (sometimes with few extra arguments).\n\n   Such functions and classes implement\n   the \"standard default\" behavior: it will read what it needs from a given\n   config and do the \"standard\" thing.\n   Users only need to load an expert-made config and pass it around, without having to worry about\n   which arguments are used and what they all mean.\n\n   See [Yacs Configs](configs.md) for a detailed tutorial.\n\n2. Functions and classes that have well-defined explicit arguments.\n\n   Each of these is a small building block of the entire system.\n   They require users' expertise to understand what each argument should be,\n   and require more effort to stitch together to a larger system.\n   But they can be stitched together in more flexible ways.\n\n   When you need to implement something not supported by the \"standard defaults\"\n   included in detectron2, these well-defined components can be reused.\n\n   The [LazyConfig system](lazyconfigs.md) relies on such functions and classes.\n\n3. A few functions and classes are implemented with the\n   [@configurable](../modules/config.html#detectron2.config.configurable)\n   decorator - they can be called with either a config, or with explicit arguments, or a mixture of both.\n   Their explicit argument interfaces are currently experimental.\n\n   As an example, a Mask R-CNN model can be built in the following ways:\n\n   1. Config-only:\n      ```python\n      # load proper yaml config file, then\n      model = build_model(cfg)\n      ```\n\n   2. Mixture of config and additional argument overrides:\n      ```python\n      model = GeneralizedRCNN(\n        cfg,\n        roi_heads=StandardROIHeads(cfg, batch_size_per_image=666),\n        pixel_std=[57.0, 57.0, 57.0])\n      ```\n\n   3. Full explicit arguments:\n   <details>\n   <summary>\n   (click to expand)\n   </summary>\n\n   ```python\n   model = GeneralizedRCNN(\n       backbone=FPN(\n           ResNet(\n               BasicStem(3, 64, norm=\"FrozenBN\"),\n               ResNet.make_default_stages(50, stride_in_1x1=True, norm=\"FrozenBN\"),\n               out_features=[\"res2\", \"res3\", \"res4\", \"res5\"],\n           ).freeze(2),\n           [\"res2\", \"res3\", \"res4\", \"res5\"],\n           256,\n           top_block=LastLevelMaxPool(),\n       ),\n       proposal_generator=RPN(\n           in_features=[\"p2\", \"p3\", \"p4\", \"p5\", \"p6\"],\n           head=StandardRPNHead(in_channels=256, num_anchors=3),\n           anchor_generator=DefaultAnchorGenerator(\n               sizes=[[32], [64], [128], [256], [512]],\n               aspect_ratios=[0.5, 1.0, 2.0],\n               strides=[4, 8, 16, 32, 64],\n               offset=0.0,\n           ),\n           anchor_matcher=Matcher([0.3, 0.7], [0, -1, 1], allow_low_quality_matches=True),\n           box2box_transform=Box2BoxTransform([1.0, 1.0, 1.0, 1.0]),\n           batch_size_per_image=256,\n           positive_fraction=0.5,\n           pre_nms_topk=(2000, 1000),\n           post_nms_topk=(1000, 1000),\n           nms_thresh=0.7,\n       ),\n       roi_heads=StandardROIHeads(\n           num_classes=80,\n           batch_size_per_image=512,\n           positive_fraction=0.25,\n           proposal_matcher=Matcher([0.5], [0, 1], allow_low_quality_matches=False),\n           box_in_features=[\"p2\", \"p3\", \"p4\", \"p5\"],\n           box_pooler=ROIPooler(7, (1.0 / 4, 1.0 / 8, 1.0 / 16, 1.0 / 32), 0, \"ROIAlignV2\"),\n           box_head=FastRCNNConvFCHead(\n               ShapeSpec(channels=256, height=7, width=7), conv_dims=[], fc_dims=[1024, 1024]\n           ),\n           box_predictor=FastRCNNOutputLayers(\n               ShapeSpec(channels=1024),\n               test_score_thresh=0.05,\n               box2box_transform=Box2BoxTransform((10, 10, 5, 5)),\n               num_classes=80,\n           ),\n           mask_in_features=[\"p2\", \"p3\", \"p4\", \"p5\"],\n           mask_pooler=ROIPooler(14, (1.0 / 4, 1.0 / 8, 1.0 / 16, 1.0 / 32), 0, \"ROIAlignV2\"),\n           mask_head=MaskRCNNConvUpsampleHead(\n               ShapeSpec(channels=256, width=14, height=14),\n               num_classes=80,\n               conv_dims=[256, 256, 256, 256, 256],\n           ),\n       ),\n       pixel_mean=[103.530, 116.280, 123.675],\n       pixel_std=[1.0, 1.0, 1.0],\n       input_format=\"BGR\",\n   )\n   ```\n\n   </details>\n\n\nIf you only need the standard behavior, the [Beginner's Tutorial](./getting_started.md)\nshould suffice. If you need to extend detectron2 to your own needs,\nsee the following tutorials for more details:\n\n* Detectron2 includes a few standard datasets. To use custom ones, see\n  [Use Custom Datasets](./datasets.md).\n* Detectron2 contains the standard logic that creates a data loader for training/testing from a\n  dataset, but you can write your own as well. See [Use Custom Data Loaders](./data_loading.md).\n* Detectron2 implements many standard detection models, and provide ways for you\n  to overwrite their behaviors. See [Use Models](./models.md) and [Write Models](./write-models.md).\n* Detectron2 provides a default training loop that is good for common training tasks.\n  You can customize it with hooks, or write your own loop instead. See [training](./training.md).\n"
  },
  {
    "path": "VPS_Module/docs/tutorials/getting_started.md",
    "content": "../../GETTING_STARTED.md"
  },
  {
    "path": "VPS_Module/docs/tutorials/index.rst",
    "content": "Tutorials\n======================================\n\n.. toctree::\n   :maxdepth: 2\n\n   install\n   getting_started\n   builtin_datasets\n   extend\n   datasets\n   data_loading\n   augmentation\n   models\n   write-models\n   training\n   evaluation\n   configs\n   lazyconfigs\n   deployment\n"
  },
  {
    "path": "VPS_Module/docs/tutorials/install.md",
    "content": "../../INSTALL.md"
  },
  {
    "path": "VPS_Module/docs/tutorials/lazyconfigs.md",
    "content": "# Lazy Configs\n\nThe traditional yacs-based config system provides basic, standard functionalities.\nHowever, it does not offer enough flexibility for many new projects.\nWe develop an alternative, non-intrusive config system that can be used with\ndetectron2 or potentially any other complex projects.\n\n## Python Syntax\n\nOur config objects are still dictionaries. Instead of using Yaml to define dictionaries,\nwe create dictionaries in Python directly. This gives users the following power that\ndoesn't exist in Yaml:\n\n* Easily manipulate the dictionary (addition & deletion) using Python.\n* Write simple arithmetics or call simple functions.\n* Use more data types / objects.\n* Import / compose other config files, using the familiar Python import syntax.\n\nA Python config file can be loaded like this:\n```python\n# config.py:\na = dict(x=1, y=2, z=dict(xx=1))\nb = dict(x=3, y=4)\n\n# my_code.py:\nfrom detectron2.config import LazyConfig\ncfg = LazyConfig.load(\"path/to/config.py\")  # an omegaconf dictionary\nassert cfg.a.z.xx == 1\n```\n\nAfter [LazyConfig.load](../modules/config.html#detectron2.config.LazyConfig.load), `cfg` will be a dictionary that contains all dictionaries\ndefined in the global scope of the config file. Note that:\n* All dictionaries are turned to an [omegaconf](https://omegaconf.readthedocs.io/)\n  config object during loading. This enables access to omegaconf features,\n  such as its [access syntax](https://omegaconf.readthedocs.io/en/2.1_branch/usage.html#access-and-manipulation)\n  and [interpolation](https://omegaconf.readthedocs.io/en/2.1_branch/usage.html#variable-interpolation).\n* Absolute imports in `config.py` works the same as in regular Python.\n* Relative imports can only import dictionaries from config files.\n  They are simply a syntax sugar for [LazyConfig.load_rel](../modules/config.html#detectron2.config.LazyConfig.load_rel).\n  They can load Python files at relative path without requiring `__init__.py`.\n\n[LazyConfig.save](../modules/config.html#detectron2.config.LazyConfig.save) can save a config object to yaml.\nNote that this is not always successful if non-serializable objects appear in the config file (e.g. lambdas).\nIt is up to users whether to sacrifice the ability to save in exchange for flexibility.\n\n## Recursive Instantiation\n\nThe LazyConfig system heavily uses recursive instantiation, which is a pattern that\nuses a dictionary to describe a\ncall to a function/class. The dictionary consists of:\n\n1. A \"\\_target\\_\" key which contains path to the callable, such as \"module.submodule.class_name\".\n2. Other keys that represent arguments to pass to the callable. Arguments themselves can be defined\n   using recursive instantiation.\n\nWe provide a helper function [LazyCall](../modules/config.html#detectron2.config.LazyCall) that helps create such dictionaries.\nThe following code using `LazyCall`\n```python\nfrom detectron2.config import LazyCall as L\nfrom my_app import Trainer, Optimizer\ncfg = L(Trainer)(\n  optimizer=L(Optimizer)(\n    lr=0.01,\n    algo=\"SGD\"\n  )\n)\n```\ncreates a dictionary like this:\n```\ncfg = {\n  \"_target_\": \"my_app.Trainer\",\n  \"optimizer\": {\n    \"_target_\": \"my_app.Optimizer\",\n    \"lr\": 0.01, \"algo\": \"SGD\"\n  }\n}\n```\n\nBy representing objects using such dictionaries, a general\n[instantiate](../modules/config.html#detectron2.config.instantiate)\nfunction can turn them into actual objects, i.e.:\n```python\nfrom detectron2.config import instantiate\ntrainer = instantiate(cfg)\n# equivalent to:\n# from my_app import Trainer, Optimizer\n# trainer = Trainer(optimizer=Optimizer(lr=0.01, algo=\"SGD\"))\n```\n\nThis pattern is powerful enough to describe very complex objects, e.g.:\n\n <details>\n <summary>\nA Full Mask R-CNN described in recursive instantiation (click to expand)\n </summary>\n\n```eval_rst\n.. literalinclude:: ../../configs/common/models/mask_rcnn_fpn.py\n  :language: python\n  :linenos:\n```\n\n </details>\n\nThere are also objects or logic that cannot be described simply by a dictionary,\nsuch as reused objects or method calls. They may require some refactoring\nto work with recursive instantiation.\n\n## Using Model Zoo LazyConfigs\n\nWe provide some configs in the model zoo using the LazyConfig system, for example:\n\n* [common baselines](../../configs/common/).\n* [new Mask R-CNN baselines](../../configs/new_baselines/)\n\nAfter installing detectron2, they can be loaded by the model zoo API\n[model_zoo.get_config](../modules/model_zoo.html#detectron2.model_zoo.get_config).\n\nUsing these as references, you're free to define custom config structure / fields for your own\nproject, as long as your training script can understand them.\nDespite of this, our model zoo configs still follow some simple conventions for consistency, e.g.\n`cfg.model` defines a model object, `cfg.dataloader.{train,test}` defines dataloader objects,\nand `cfg.train` contains training options in key-value form.\nIn addition to `print()`, a better way to view the structure of a config is like this:\n```\nfrom detectron2.model_zoo import get_config\nfrom detectron2.config import LazyConfig\nprint(LazyConfig.to_py(get_config(\"COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_1x.py\")))\n```\nFrom the output it's easier to find relevant options to change, e.g.\n`dataloader.train.total_batch_size` for the batch size, or `optimizer.lr` for base learning rate.\n\nWe provide a reference training script\n[tools/lazyconfig_train_net.py](../../tools/lazyconfig_train_net.py),\nthat can train/eval our model zoo configs.\nIt also shows how to support command line value overrides.\n\nTo demonstrate the power and flexibility of the new system, we show that\n[a simple config file](../../configs/Misc/torchvision_imagenet_R_50.py)\ncan let detectron2 train an ImageNet classification model from torchvision, even though\ndetectron2 contains no features about ImageNet classification.\nThis can serve as a reference for using detectron2 in other deep learning tasks.\n\n## Summary\n\nBy using recursive instantiation to create objects,\nwe avoid passing a giant config to many places, because `cfg` is only passed to `instantiate`.\nThis has the following benefits:\n\n* It's __non-intrusive__: objects to be constructed are config-agnostic, regular Python\n  functions/classes.\n  They can even live in other libraries. For example,\n  `{\"_target_\": \"torch.nn.Conv2d\", \"in_channels\": 10, \"out_channels\": 10, \"kernel_size\": 1}`\n  defines a conv layer.\n* __Clarity__ of what function/classes will be called, and what arguments they use.\n* `cfg` doesn't need pre-defined keys and structures. It's valid as long as it translates to valid\n  code. This gives a lot more __flexibility__.\n* You can still pass huge dictionaries as arguments, just like the old way.\n\nRecursive instantiation and Python syntax are orthogonal: you can use one without the other.\nBut by putting them together, the config file looks a lot like the code that will be executed:\n\n![img](./lazyconfig.jpg)\n\nHowever, the config file just defines dictionaries, which can be easily manipulated further\nby composition or overrides.\nThe corresponding code will only be executed\nlater when `instantiate` is called. In some way,\nin config files we're writing \"editable code\" that will be \"lazily executed\" later when needed.\nThat's why we call this system \"LazyConfig\".\n"
  },
  {
    "path": "VPS_Module/docs/tutorials/models.md",
    "content": "# Use Models\n\n## Build Models from Yacs Config\nFrom a yacs config object,\nmodels (and their sub-models) can be built by\nfunctions such as `build_model`, `build_backbone`, `build_roi_heads`:\n```python\nfrom detectron2.modeling import build_model\nmodel = build_model(cfg)  # returns a torch.nn.Module\n```\n\n`build_model` only builds the model structure and fills it with random parameters.\nSee below for how to load an existing checkpoint to the model and how to use the `model` object.\n\n### Load/Save a Checkpoint\n```python\nfrom detectron2.checkpoint import DetectionCheckpointer\nDetectionCheckpointer(model).load(file_path_or_url)  # load a file, usually from cfg.MODEL.WEIGHTS\n\ncheckpointer = DetectionCheckpointer(model, save_dir=\"output\")\ncheckpointer.save(\"model_999\")  # save to output/model_999.pth\n```\n\nDetectron2's checkpointer recognizes models in pytorch's `.pth` format, as well as the `.pkl` files\nin our model zoo.\nSee [API doc](../modules/checkpoint.html#detectron2.checkpoint.DetectionCheckpointer)\nfor more details about its usage.\n\nThe model files can be arbitrarily manipulated using `torch.{load,save}` for `.pth` files or\n`pickle.{dump,load}` for `.pkl` files.\n\n### Use a Model\n\nA model can be called by `outputs = model(inputs)`, where `inputs` is a `list[dict]`.\nEach dict corresponds to one image and the required keys\ndepend on the type of model, and whether the model is in training or evaluation mode.\nFor example, in order to do inference,\nall existing models expect the \"image\" key, and optionally \"height\" and \"width\".\nThe detailed format of inputs and outputs of existing models are explained below.\n\n__Training__: When in training mode, all models are required to be used under an `EventStorage`.\nThe training statistics will be put into the storage:\n```python\nfrom detectron2.utils.events import EventStorage\nwith EventStorage() as storage:\n  losses = model(inputs)\n```\n\n__Inference__: If you only want to do simple inference using an existing model,\n[DefaultPredictor](../modules/engine.html#detectron2.engine.defaults.DefaultPredictor)\nis a wrapper around model that provides such basic functionality.\nIt includes default behavior including model loading, preprocessing,\nand operates on single image rather than batches. See its documentation for usage.\n\nYou can also run inference directly like this:\n```\nmodel.eval()\nwith torch.no_grad():\n  outputs = model(inputs)\n```\n\n### Model Input Format\n\nUsers can implement custom models that support any arbitrary input format.\nHere we describe the standard input format that all builtin models support in detectron2.\nThey all take a `list[dict]` as the inputs. Each dict\ncorresponds to information about one image.\n\nThe dict may contain the following keys:\n\n* \"image\": `Tensor` in (C, H, W) format. The meaning of channels are defined by `cfg.INPUT.FORMAT`.\n  Image normalization, if any, will be performed inside the model using\n  `cfg.MODEL.PIXEL_{MEAN,STD}`.\n* \"height\", \"width\": the **desired** output height and width **in inference**, which is not necessarily the same\n  as the height or width of the `image` field.\n  For example, the `image` field contains the resized image, if resize is used as a preprocessing step.\n  But you may want the outputs to be in **original** resolution.\n  If provided, the model will produce output in this resolution,\n  rather than in the resolution of the `image` as input into the model. This is more efficient and accurate.\n* \"instances\": an [Instances](../modules/structures.html#detectron2.structures.Instances)\n  object for training, with the following fields:\n  + \"gt_boxes\": a [Boxes](../modules/structures.html#detectron2.structures.Boxes) object storing N boxes, one for each instance.\n  + \"gt_classes\": `Tensor` of long type, a vector of N labels, in range [0, num_categories).\n  + \"gt_masks\": a [PolygonMasks](../modules/structures.html#detectron2.structures.PolygonMasks)\n    or [BitMasks](../modules/structures.html#detectron2.structures.BitMasks) object storing N masks, one for each instance.\n  + \"gt_keypoints\": a [Keypoints](../modules/structures.html#detectron2.structures.Keypoints)\n    object storing N keypoint sets, one for each instance.\n* \"sem_seg\": `Tensor[int]` in (H, W) format. The semantic segmentation ground truth for training.\n  Values represent category labels starting from 0.\n* \"proposals\": an [Instances](../modules/structures.html#detectron2.structures.Instances)\n  object used only in Fast R-CNN style models, with the following fields:\n  + \"proposal_boxes\": a [Boxes](../modules/structures.html#detectron2.structures.Boxes) object storing P proposal boxes.\n  + \"objectness_logits\": `Tensor`, a vector of P scores, one for each proposal.\n\nFor inference of builtin models, only \"image\" key is required, and \"width/height\" are optional.\n\nWe currently don't define standard input format for panoptic segmentation training,\nbecause models now use custom formats produced by custom data loaders.\n\n#### How it connects to data loader:\n\nThe output of the default [DatasetMapper]( ../modules/data.html#detectron2.data.DatasetMapper) is a dict\nthat follows the above format.\nAfter the data loader performs batching, it becomes `list[dict]` which the builtin models support.\n\n\n### Model Output Format\n\nWhen in training mode, the builtin models output a `dict[str->ScalarTensor]` with all the losses.\n\nWhen in inference mode, the builtin models output a `list[dict]`, one dict for each image.\nBased on the tasks the model is doing, each dict may contain the following fields:\n\n* \"instances\": [Instances](../modules/structures.html#detectron2.structures.Instances)\n  object with the following fields:\n  * \"pred_boxes\": [Boxes](../modules/structures.html#detectron2.structures.Boxes) object storing N boxes, one for each detected instance.\n  * \"scores\": `Tensor`, a vector of N confidence scores.\n  * \"pred_classes\": `Tensor`, a vector of N labels in range [0, num_categories).\n  + \"pred_masks\": a `Tensor` of shape (N, H, W), masks for each detected instance.\n  + \"pred_keypoints\": a `Tensor` of shape (N, num_keypoint, 3).\n    Each row in the last dimension is (x, y, score). Confidence scores are larger than 0.\n* \"sem_seg\": `Tensor` of (num_categories, H, W), the semantic segmentation prediction.\n* \"proposals\": [Instances](../modules/structures.html#detectron2.structures.Instances)\n  object with the following fields:\n  * \"proposal_boxes\": [Boxes](../modules/structures.html#detectron2.structures.Boxes)\n    object storing N boxes.\n  * \"objectness_logits\": a torch vector of N confidence scores.\n* \"panoptic_seg\": A tuple of `(pred: Tensor, segments_info: Optional[list[dict]])`.\n  The `pred` tensor has shape (H, W), containing the segment id of each pixel.\n\n  * If `segments_info` exists, each dict describes one segment id in `pred` and has the following fields:\n\n    * \"id\": the segment id\n    * \"isthing\": whether the segment is a thing or stuff\n    * \"category_id\": the category id of this segment.\n\n    If a pixel's id does not exist in `segments_info`, it is considered to be void label\n    defined in [Panoptic Segmentation](https://arxiv.org/abs/1801.00868).\n\n  * If `segments_info` is None, all pixel values in `pred` must be ≥ -1.\n    Pixels with value -1 are assigned void labels.\n    Otherwise, the category id of each pixel is obtained by\n    `category_id = pixel // metadata.label_divisor`.\n\n\n### Partially execute a model:\n\nSometimes you may want to obtain an intermediate tensor inside a model,\nsuch as the input of certain layer, the output before post-processing.\nSince there are typically hundreds of intermediate tensors, there isn't an API that provides you\nthe intermediate result you need.\nYou have the following options:\n\n1. Write a (sub)model. Following the [tutorial](./write-models.md), you can\n   rewrite a model component (e.g. a head of a model), such that it\n   does the same thing as the existing component, but returns the output\n   you need.\n2. Partially execute a model. You can create the model as usual,\n   but use custom code to execute it instead of its `forward()`. For example,\n   the following code obtains mask features before mask head.\n\n   ```python\n   images = ImageList.from_tensors(...)  # preprocessed input tensor\n   model = build_model(cfg)\n   model.eval()\n   features = model.backbone(images.tensor)\n   proposals, _ = model.proposal_generator(images, features)\n   instances, _ = model.roi_heads(images, features, proposals)\n   mask_features = [features[f] for f in model.roi_heads.in_features]\n   mask_features = model.roi_heads.mask_pooler(mask_features, [x.pred_boxes for x in instances])\n   ```\n\n3. Use [forward hooks](https://pytorch.org/tutorials/beginner/former_torchies/nnft_tutorial.html#forward-and-backward-function-hooks).\n   Forward hooks can help you obtain inputs or outputs of a certain module.\n   If they are not exactly what you want, they can at least be used together with partial execution\n   to obtain other tensors.\n\nAll options require you to read documentation and sometimes code\nof the existing models to understand the internal logic,\nin order to write code to obtain the internal tensors.\n"
  },
  {
    "path": "VPS_Module/docs/tutorials/training.md",
    "content": "# Training\n\nFrom the previous tutorials, you may now have a custom model and a data loader.\nTo run training, users typically have a preference in one of the following two styles:\n\n### Custom Training Loop\n\nWith a model and a data loader ready, everything else needed to write a training loop can\nbe found in PyTorch, and you are free to write the training loop yourself.\nThis style allows researchers to manage the entire training logic more clearly and have full control.\nOne such example is provided in [tools/plain_train_net.py](../../tools/plain_train_net.py).\n\nAny customization on the training logic is then easily controlled by the user.\n\n### Trainer Abstraction\n\nWe also provide a standardized \"trainer\" abstraction with a\nhook system that helps simplify the standard training behavior.\nIt includes the following two instantiations:\n\n* [SimpleTrainer](../modules/engine.html#detectron2.engine.SimpleTrainer)\n  provides a minimal training loop for single-cost single-optimizer single-data-source training, with nothing else.\n  Other tasks (checkpointing, logging, etc) can be implemented using\n  [the hook system](../modules/engine.html#detectron2.engine.HookBase).\n* [DefaultTrainer](../modules/engine.html#detectron2.engine.defaults.DefaultTrainer) is a `SimpleTrainer` initialized from a\n  yacs config, used by\n  [tools/train_net.py](../../tools/train_net.py) and many scripts.\n  It includes more standard default behaviors that one might want to opt in,\n  including default configurations for optimizer, learning rate schedule,\n  logging, evaluation, checkpointing etc.\n\nTo customize a `DefaultTrainer`:\n\n1. For simple customizations (e.g. change optimizer, evaluator, LR scheduler, data loader, etc.), overwrite [its methods](../modules/engine.html#detectron2.engine.defaults.DefaultTrainer) in a subclass, just like [tools/train_net.py](../../tools/train_net.py).\n2. For extra tasks during training, check the\n   [hook system](../modules/engine.html#detectron2.engine.HookBase) to see if it's supported.\n\n   As an example, to print hello during training:\n   ```python\n   class HelloHook(HookBase):\n     def after_step(self):\n       if self.trainer.iter % 100 == 0:\n         print(f\"Hello at iteration {self.trainer.iter}!\")\n   ```\n3. Using a trainer+hook system means there will always be some non-standard behaviors that cannot be supported, especially in research.\n   For this reason, we intentionally keep the trainer & hook system minimal, rather than powerful.\n   If anything cannot be achieved by such a system, it's easier to start from [tools/plain_train_net.py](../../tools/plain_train_net.py) to implement custom training logic manually.\n\n### Logging of Metrics\n\nDuring training, detectron2 models and trainer put metrics to a centralized [EventStorage](../modules/utils.html#detectron2.utils.events.EventStorage).\nYou can use the following code to access it and log metrics to it:\n```\nfrom detectron2.utils.events import get_event_storage\n\n# inside the model:\nif self.training:\n  value = # compute the value from inputs\n  storage = get_event_storage()\n  storage.put_scalar(\"some_accuracy\", value)\n```\n\nRefer to its documentation for more details.\n\nMetrics are then written to various destinations with [EventWriter](../modules/utils.html#module-detectron2.utils.events).\nDefaultTrainer enables a few `EventWriter` with default configurations.\nSee above for how to customize them.\n"
  },
  {
    "path": "VPS_Module/docs/tutorials/write-models.md",
    "content": "# Write Models\n\nIf you are trying to do something completely new, you may wish to implement\na model entirely from scratch. However, in many situations you may\nbe interested in modifying or extending some components of an existing model.\nTherefore, we also provide mechanisms that let users override the\nbehavior of certain internal components of standard models.\n\n\n## Register New Components\n\nFor common concepts that users often want to customize, such as \"backbone feature extractor\", \"box head\",\nwe provide a registration mechanism for users to inject custom implementation that\nwill be immediately available to use in config files.\n\nFor example, to add a new backbone, import this code in your code:\n```python\nfrom detectron2.modeling import BACKBONE_REGISTRY, Backbone, ShapeSpec\n\n@BACKBONE_REGISTRY.register()\nclass ToyBackbone(Backbone):\n  def __init__(self, cfg, input_shape):\n    super().__init__()\n    # create your own backbone\n    self.conv1 = nn.Conv2d(3, 64, kernel_size=7, stride=16, padding=3)\n\n  def forward(self, image):\n    return {\"conv1\": self.conv1(image)}\n\n  def output_shape(self):\n    return {\"conv1\": ShapeSpec(channels=64, stride=16)}\n```\n\nIn this code, we implement a new backbone following the interface of the\n[Backbone](../modules/modeling.html#detectron2.modeling.Backbone) class,\nand register it into the [BACKBONE_REGISTRY](../modules/modeling.html#detectron2.modeling.BACKBONE_REGISTRY)\nwhich requires subclasses of `Backbone`.\nAfter importing this code, detectron2 can link the name of the class to its implementation. Therefore you can write the following code:\n\n```python\ncfg = ...   # read a config\ncfg.MODEL.BACKBONE.NAME = 'ToyBackbone'   # or set it in the config file\nmodel = build_model(cfg)  # it will find `ToyBackbone` defined above\n```\n\nAs another example, to add new abilities to the ROI heads in the Generalized R-CNN meta-architecture,\nyou can implement a new\n[ROIHeads](../modules/modeling.html#detectron2.modeling.ROIHeads) subclass and put it in the `ROI_HEADS_REGISTRY`.\n[DensePose](../../projects/DensePose)\nand [MeshRCNN](https://github.com/facebookresearch/meshrcnn)\nare two examples that implement new ROIHeads to perform new tasks.\nAnd [projects/](../../projects/)\ncontains more examples that implement different architectures.\n\nA complete list of registries can be found in [API documentation](../modules/modeling.html#model-registries).\nYou can register components in these registries to customize different parts of a model, or the\nentire model.\n\n## Construct Models with Explicit Arguments\n\nRegistry is a bridge to connect names in config files to the actual code.\nThey are meant to cover a few main components that users frequently need to replace.\nHowever, the capability of a text-based config file is sometimes limited and\nsome deeper customization may be available only through writing code.\n\nMost model components in detectron2 have a clear `__init__` interface that documents\nwhat input arguments it needs. Calling them with custom arguments will give you a custom variant\nof the model.\n\nAs an example, to use __custom loss function__ in the box head of a Faster R-CNN, we can do the following:\n\n1. Losses are currently computed in [FastRCNNOutputLayers](../modules/modeling.html#detectron2.modeling.FastRCNNOutputLayers).\n   We need to implement a variant or a subclass of it, with custom loss functions, named  `MyRCNNOutput`.\n2. Call `StandardROIHeads` with `box_predictor=MyRCNNOutput()` argument instead of the builtin `FastRCNNOutputLayers`.\n   If all other arguments should stay unchanged, this can be easily achieved by using the [configurable `__init__`](../modules/config.html#detectron2.config.configurable) mechanism:\n\n   ```python\n   roi_heads = StandardROIHeads(\n     cfg, backbone.output_shape(),\n     box_predictor=MyRCNNOutput(...)\n   )\n   ```\n3. (optional) If we want to enable this new model from a config file, registration is needed:\n   ```python\n   @ROI_HEADS_REGISTRY.register()\n   class MyStandardROIHeads(StandardROIHeads):\n     def __init__(self, cfg, input_shape):\n       super().__init__(cfg, input_shape,\n                        box_predictor=MyRCNNOutput(...))\n   ```\n"
  },
  {
    "path": "VPS_Module/projects/DeepLab/README.md",
    "content": "# DeepLab in Detectron2\n\nIn this repository, we implement DeepLabV3 and DeepLabV3+ in Detectron2.\n\n## Installation\nInstall Detectron2 following [the instructions](https://detectron2.readthedocs.io/tutorials/install.html).\n\n## Training\n\nTo train a model with 8 GPUs run:\n```bash\ncd /path/to/detectron2/projects/DeepLab\npython train_net.py --config-file configs/Cityscapes-SemanticSegmentation/deeplab_v3_plus_R_103_os16_mg124_poly_90k_bs16.yaml --num-gpus 8\n```\n\n## Evaluation\n\nModel evaluation can be done similarly:\n```bash\ncd /path/to/detectron2/projects/DeepLab\npython train_net.py --config-file configs/Cityscapes-SemanticSegmentation/deeplab_v3_plus_R_103_os16_mg124_poly_90k_bs16.yaml --eval-only MODEL.WEIGHTS /path/to/model_checkpoint\n```\n\n## Cityscapes Semantic Segmentation\nCityscapes models are trained with ImageNet pretraining.\n\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Method</th>\n<th valign=\"bottom\">Backbone</th>\n<th valign=\"bottom\">Output<br/>resolution</th>\n<th valign=\"bottom\">mIoU</th>\n<th valign=\"bottom\">model id</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n <tr><td align=\"left\">DeepLabV3</td>\n<td align=\"center\">R101-DC5</td>\n<td align=\"center\">1024&times;2048</td>\n<td align=\"center\"> 76.7 </td>\n<td align=\"center\"> - </td>\n<td align=\"center\"> - &nbsp;|&nbsp; - </td>\n</tr>\n <tr><td align=\"left\"><a href=\"configs/Cityscapes-SemanticSegmentation/deeplab_v3_R_103_os16_mg124_poly_90k_bs16.yaml\">DeepLabV3</a></td>\n<td align=\"center\">R103-DC5</td>\n<td align=\"center\">1024&times;2048</td>\n<td align=\"center\"> 78.5 </td>\n<td align=\"center\"> 28041665 </td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/detectron2/DeepLab/Cityscapes-SemanticSegmentation/deeplab_v3_R_103_os16_mg124_poly_90k_bs16/28041665/model_final_0dff1b.pkl\n\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/DeepLab/Cityscapes-SemanticSegmentation/deeplab_v3_R_103_os16_mg124_poly_90k_bs16/28041665/metrics.json\n\">metrics</a></td>\n</tr>\n <tr><td align=\"left\">DeepLabV3+</td>\n<td align=\"center\">R101-DC5</td>\n<td align=\"center\">1024&times;2048</td>\n<td align=\"center\"> 78.1 </td>\n<td align=\"center\"> - </td>\n<td align=\"center\"> - &nbsp;|&nbsp; - </td>\n</tr>\n <tr><td align=\"left\"><a href=\"configs/Cityscapes-SemanticSegmentation/deeplab_v3_plus_R_103_os16_mg124_poly_90k_bs16.yaml\">DeepLabV3+</a></td>\n<td align=\"center\">R103-DC5</td>\n<td align=\"center\">1024&times;2048</td>\n<td align=\"center\"> 80.0 </td>\n<td align=\"center\">28054032</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/detectron2/DeepLab/Cityscapes-SemanticSegmentation/deeplab_v3_plus_R_103_os16_mg124_poly_90k_bs16/28054032/model_final_a8a355.pkl\n\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/DeepLab/Cityscapes-SemanticSegmentation/deeplab_v3_plus_R_103_os16_mg124_poly_90k_bs16/28054032/metrics.json\n\">metrics</a></td>\n</tr>\n</tbody></table>\n\nNote:\n- [R103](https://dl.fbaipublicfiles.com/detectron2/DeepLab/R-103.pkl): a ResNet-101 with its first 7x7 convolution replaced by 3 3x3 convolutions. \nThis modification has been used in most semantic segmentation papers. We pre-train this backbone on ImageNet using the default recipe of [pytorch examples](https://github.com/pytorch/examples/tree/master/imagenet).\n- DC5 means using dilated convolution in `res5`.\n\n## <a name=\"CitingDeepLab\"></a>Citing DeepLab\n\nIf you use DeepLab, please use the following BibTeX entry.\n\n*   DeepLabv3+:\n\n```\n@inproceedings{deeplabv3plus2018,\n  title={Encoder-Decoder with Atrous Separable Convolution for Semantic Image Segmentation},\n  author={Liang-Chieh Chen and Yukun Zhu and George Papandreou and Florian Schroff and Hartwig Adam},\n  booktitle={ECCV},\n  year={2018}\n}\n```\n\n*   DeepLabv3:\n\n```\n@article{deeplabv32018,\n  title={Rethinking atrous convolution for semantic image segmentation},\n  author={Chen, Liang-Chieh and Papandreou, George and Schroff, Florian and Adam, Hartwig},\n  journal={arXiv:1706.05587},\n  year={2017}\n}\n```\n"
  },
  {
    "path": "VPS_Module/projects/DeepLab/configs/Cityscapes-SemanticSegmentation/Base-DeepLabV3-OS16-Semantic.yaml",
    "content": "_BASE_: \"../../../../configs/Base-RCNN-DilatedC5.yaml\"\nMODEL:\n  META_ARCHITECTURE: \"SemanticSegmentor\"\n  BACKBONE:\n    FREEZE_AT: 0\n  SEM_SEG_HEAD:\n    NAME: \"DeepLabV3Head\"\n    IN_FEATURES: [\"res5\"]\n    ASPP_CHANNELS: 256\n    ASPP_DILATIONS: [6, 12, 18]\n    ASPP_DROPOUT: 0.1\n    CONVS_DIM: 256\n    COMMON_STRIDE: 16\n    NUM_CLASSES: 19\n    LOSS_TYPE: \"hard_pixel_mining\"\nDATASETS:\n  TRAIN: (\"cityscapes_fine_sem_seg_train\",)\n  TEST: (\"cityscapes_fine_sem_seg_val\",)\nSOLVER:\n  BASE_LR: 0.01\n  MAX_ITER: 90000\n  LR_SCHEDULER_NAME: \"WarmupPolyLR\"\n  IMS_PER_BATCH: 16\nINPUT:\n  MIN_SIZE_TRAIN: (512, 768, 1024, 1280, 1536, 1792, 2048)\n  MIN_SIZE_TRAIN_SAMPLING: \"choice\"\n  MIN_SIZE_TEST: 1024\n  MAX_SIZE_TRAIN: 4096\n  MAX_SIZE_TEST: 2048\n  CROP:\n    ENABLED: True\n    TYPE: \"absolute\"\n    SIZE: (512, 1024)\n    SINGLE_CATEGORY_MAX_AREA: 1.0\nDATALOADER:\n  NUM_WORKERS: 10\n"
  },
  {
    "path": "VPS_Module/projects/DeepLab/configs/Cityscapes-SemanticSegmentation/deeplab_v3_R_103_os16_mg124_poly_90k_bs16.yaml",
    "content": "_BASE_: Base-DeepLabV3-OS16-Semantic.yaml\nMODEL:\n  WEIGHTS: \"detectron2://DeepLab/R-103.pkl\"\n  PIXEL_MEAN: [123.675, 116.280, 103.530]\n  PIXEL_STD: [58.395, 57.120, 57.375]\n  BACKBONE:\n    NAME: \"build_resnet_deeplab_backbone\"\n  RESNETS:\n    DEPTH: 101\n    NORM: \"SyncBN\"\n    RES5_MULTI_GRID: [1, 2, 4]\n    STEM_TYPE: \"deeplab\"\n    STEM_OUT_CHANNELS: 128\n    STRIDE_IN_1X1: False\n  SEM_SEG_HEAD:\n    NAME: \"DeepLabV3Head\"\n    NORM: \"SyncBN\"\nINPUT:\n  FORMAT: \"RGB\"\n"
  },
  {
    "path": "VPS_Module/projects/DeepLab/configs/Cityscapes-SemanticSegmentation/deeplab_v3_plus_R_103_os16_mg124_poly_90k_bs16.yaml",
    "content": "_BASE_: Base-DeepLabV3-OS16-Semantic.yaml\nMODEL:\n  WEIGHTS: \"detectron2://DeepLab/R-103.pkl\"\n  PIXEL_MEAN: [123.675, 116.280, 103.530]\n  PIXEL_STD: [58.395, 57.120, 57.375]\n  BACKBONE:\n    NAME: \"build_resnet_deeplab_backbone\"\n  RESNETS:\n    DEPTH: 101\n    NORM: \"SyncBN\"\n    OUT_FEATURES: [\"res2\", \"res5\"]\n    RES5_MULTI_GRID: [1, 2, 4]\n    STEM_TYPE: \"deeplab\"\n    STEM_OUT_CHANNELS: 128\n    STRIDE_IN_1X1: False\n  SEM_SEG_HEAD:\n    NAME: \"DeepLabV3PlusHead\"\n    IN_FEATURES: [\"res2\", \"res5\"]\n    PROJECT_FEATURES: [\"res2\"]\n    PROJECT_CHANNELS: [48]\n    NORM: \"SyncBN\"\n    COMMON_STRIDE: 4\nINPUT:\n  FORMAT: \"RGB\"\n"
  },
  {
    "path": "VPS_Module/projects/DeepLab/deeplab/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom .build_solver import build_lr_scheduler\nfrom .config import add_deeplab_config\nfrom .resnet import build_resnet_deeplab_backbone\nfrom .semantic_seg import DeepLabV3Head, DeepLabV3PlusHead\n"
  },
  {
    "path": "VPS_Module/projects/DeepLab/deeplab/build_solver.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport torch\n\nfrom detectron2.config import CfgNode\nfrom detectron2.solver import build_lr_scheduler as build_d2_lr_scheduler\n\nfrom .lr_scheduler import WarmupPolyLR\n\n\ndef build_lr_scheduler(\n    cfg: CfgNode, optimizer: torch.optim.Optimizer\n) -> torch.optim.lr_scheduler._LRScheduler:\n    \"\"\"\n    Build a LR scheduler from config.\n    \"\"\"\n    name = cfg.SOLVER.LR_SCHEDULER_NAME\n    if name == \"WarmupPolyLR\":\n        return WarmupPolyLR(\n            optimizer,\n            cfg.SOLVER.MAX_ITER,\n            warmup_factor=cfg.SOLVER.WARMUP_FACTOR,\n            warmup_iters=cfg.SOLVER.WARMUP_ITERS,\n            warmup_method=cfg.SOLVER.WARMUP_METHOD,\n            power=cfg.SOLVER.POLY_LR_POWER,\n            constant_ending=cfg.SOLVER.POLY_LR_CONSTANT_ENDING,\n        )\n    else:\n        return build_d2_lr_scheduler(cfg, optimizer)\n"
  },
  {
    "path": "VPS_Module/projects/DeepLab/deeplab/config.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n\n\ndef add_deeplab_config(cfg):\n    \"\"\"\n    Add config for DeepLab.\n    \"\"\"\n    # We retry random cropping until no single category in semantic segmentation GT occupies more\n    # than `SINGLE_CATEGORY_MAX_AREA` part of the crop.\n    cfg.INPUT.CROP.SINGLE_CATEGORY_MAX_AREA = 1.0\n    # Used for `poly` learning rate schedule.\n    cfg.SOLVER.POLY_LR_POWER = 0.9\n    cfg.SOLVER.POLY_LR_CONSTANT_ENDING = 0.0\n    # Loss type, choose from `cross_entropy`, `hard_pixel_mining`.\n    cfg.MODEL.SEM_SEG_HEAD.LOSS_TYPE = \"hard_pixel_mining\"\n    # DeepLab settings\n    cfg.MODEL.SEM_SEG_HEAD.PROJECT_FEATURES = [\"res2\"]\n    cfg.MODEL.SEM_SEG_HEAD.PROJECT_CHANNELS = [48]\n    cfg.MODEL.SEM_SEG_HEAD.ASPP_CHANNELS = 256\n    cfg.MODEL.SEM_SEG_HEAD.ASPP_DILATIONS = [6, 12, 18]\n    cfg.MODEL.SEM_SEG_HEAD.ASPP_DROPOUT = 0.1\n    cfg.MODEL.SEM_SEG_HEAD.USE_DEPTHWISE_SEPARABLE_CONV = False\n    # Backbone new configs\n    cfg.MODEL.RESNETS.RES4_DILATION = 1\n    cfg.MODEL.RESNETS.RES5_MULTI_GRID = [1, 2, 4]\n    # ResNet stem type from: `basic`, `deeplab`\n    cfg.MODEL.RESNETS.STEM_TYPE = \"deeplab\"\n"
  },
  {
    "path": "VPS_Module/projects/DeepLab/deeplab/loss.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport torch\nimport torch.nn as nn\n\n\nclass DeepLabCE(nn.Module):\n    \"\"\"\n    Hard pixel mining with cross entropy loss, for semantic segmentation.\n    This is used in TensorFlow DeepLab frameworks.\n    Paper: DeeperLab: Single-Shot Image Parser\n    Reference: https://github.com/tensorflow/models/blob/bd488858d610e44df69da6f89277e9de8a03722c/research/deeplab/utils/train_utils.py#L33  # noqa\n    Arguments:\n        ignore_label: Integer, label to ignore.\n        top_k_percent_pixels: Float, the value lies in [0.0, 1.0]. When its\n            value < 1.0, only compute the loss for the top k percent pixels\n            (e.g., the top 20% pixels). This is useful for hard pixel mining.\n        weight: Tensor, a manual rescaling weight given to each class.\n    \"\"\"\n\n    def __init__(self, ignore_label=-1, top_k_percent_pixels=1.0, weight=None):\n        super(DeepLabCE, self).__init__()\n        self.top_k_percent_pixels = top_k_percent_pixels\n        self.ignore_label = ignore_label\n        self.criterion = nn.CrossEntropyLoss(\n            weight=weight, ignore_index=ignore_label, reduction=\"none\"\n        )\n\n    def forward(self, logits, labels, weights=None):\n        if weights is None:\n            pixel_losses = self.criterion(logits, labels).contiguous().view(-1)\n        else:\n            # Apply per-pixel loss weights.\n            pixel_losses = self.criterion(logits, labels) * weights\n            pixel_losses = pixel_losses.contiguous().view(-1)\n        if self.top_k_percent_pixels == 1.0:\n            return pixel_losses.mean()\n\n        top_k_pixels = int(self.top_k_percent_pixels * pixel_losses.numel())\n        pixel_losses, _ = torch.topk(pixel_losses, top_k_pixels)\n        return pixel_losses.mean()\n"
  },
  {
    "path": "VPS_Module/projects/DeepLab/deeplab/lr_scheduler.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport math\nfrom typing import List\nimport torch\n\nfrom detectron2.solver.lr_scheduler import _get_warmup_factor_at_iter\n\n# NOTE: PyTorch's LR scheduler interface uses names that assume the LR changes\n# only on epoch boundaries. We typically use iteration based schedules instead.\n# As a result, \"epoch\" (e.g., as in self.last_epoch) should be understood to mean\n# \"iteration\" instead.\n\n# FIXME: ideally this would be achieved with a CombinedLRScheduler, separating\n# MultiStepLR with WarmupLR but the current LRScheduler design doesn't allow it.\n\n\nclass WarmupPolyLR(torch.optim.lr_scheduler._LRScheduler):\n    \"\"\"\n    Poly learning rate schedule used to train DeepLab.\n    Paper: DeepLab: Semantic Image Segmentation with Deep Convolutional Nets,\n        Atrous Convolution, and Fully Connected CRFs.\n    Reference: https://github.com/tensorflow/models/blob/21b73d22f3ed05b650e85ac50849408dd36de32e/research/deeplab/utils/train_utils.py#L337  # noqa\n    \"\"\"\n\n    def __init__(\n        self,\n        optimizer: torch.optim.Optimizer,\n        max_iters: int,\n        warmup_factor: float = 0.001,\n        warmup_iters: int = 1000,\n        warmup_method: str = \"linear\",\n        last_epoch: int = -1,\n        power: float = 0.9,\n        constant_ending: float = 0.0,\n    ):\n        self.max_iters = max_iters\n        self.warmup_factor = warmup_factor\n        self.warmup_iters = warmup_iters\n        self.warmup_method = warmup_method\n        self.power = power\n        self.constant_ending = constant_ending\n        super().__init__(optimizer, last_epoch)\n\n    def get_lr(self) -> List[float]:\n        warmup_factor = _get_warmup_factor_at_iter(\n            self.warmup_method, self.last_epoch, self.warmup_iters, self.warmup_factor\n        )\n        if self.constant_ending > 0 and warmup_factor == 1.0:\n            # Constant ending lr.\n            if (\n                math.pow((1.0 - self.last_epoch / self.max_iters), self.power)\n                < self.constant_ending\n            ):\n                return [base_lr * self.constant_ending for base_lr in self.base_lrs]\n        return [\n            base_lr * warmup_factor * math.pow((1.0 - self.last_epoch / self.max_iters), self.power)\n            for base_lr in self.base_lrs\n        ]\n\n    def _compute_values(self) -> List[float]:\n        # The new interface\n        return self.get_lr()\n"
  },
  {
    "path": "VPS_Module/projects/DeepLab/deeplab/resnet.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport fvcore.nn.weight_init as weight_init\nimport torch.nn.functional as F\n\nfrom detectron2.layers import CNNBlockBase, Conv2d, get_norm\nfrom detectron2.modeling import BACKBONE_REGISTRY\nfrom detectron2.modeling.backbone.resnet import (\n    BasicStem,\n    BottleneckBlock,\n    DeformBottleneckBlock,\n    ResNet,\n)\n\n\nclass DeepLabStem(CNNBlockBase):\n    \"\"\"\n    The DeepLab ResNet stem (layers before the first residual block).\n    \"\"\"\n\n    def __init__(self, in_channels=3, out_channels=128, norm=\"BN\"):\n        \"\"\"\n        Args:\n            norm (str or callable): norm after the first conv layer.\n                See :func:`layers.get_norm` for supported format.\n        \"\"\"\n        super().__init__(in_channels, out_channels, 4)\n        self.in_channels = in_channels\n        self.conv1 = Conv2d(\n            in_channels,\n            out_channels // 2,\n            kernel_size=3,\n            stride=2,\n            padding=1,\n            bias=False,\n            norm=get_norm(norm, out_channels // 2),\n        )\n        self.conv2 = Conv2d(\n            out_channels // 2,\n            out_channels // 2,\n            kernel_size=3,\n            stride=1,\n            padding=1,\n            bias=False,\n            norm=get_norm(norm, out_channels // 2),\n        )\n        self.conv3 = Conv2d(\n            out_channels // 2,\n            out_channels,\n            kernel_size=3,\n            stride=1,\n            padding=1,\n            bias=False,\n            norm=get_norm(norm, out_channels),\n        )\n        weight_init.c2_msra_fill(self.conv1)\n        weight_init.c2_msra_fill(self.conv2)\n        weight_init.c2_msra_fill(self.conv3)\n\n    def forward(self, x):\n        x = self.conv1(x)\n        x = F.relu_(x)\n        x = self.conv2(x)\n        x = F.relu_(x)\n        x = self.conv3(x)\n        x = F.relu_(x)\n        x = F.max_pool2d(x, kernel_size=3, stride=2, padding=1)\n        return x\n\n\n@BACKBONE_REGISTRY.register()\ndef build_resnet_deeplab_backbone(cfg, input_shape):\n    \"\"\"\n    Create a ResNet instance from config.\n    Returns:\n        ResNet: a :class:`ResNet` instance.\n    \"\"\"\n    # need registration of new blocks/stems?\n    norm = cfg.MODEL.RESNETS.NORM\n    if cfg.MODEL.RESNETS.STEM_TYPE == \"basic\":\n        stem = BasicStem(\n            in_channels=input_shape.channels,\n            out_channels=cfg.MODEL.RESNETS.STEM_OUT_CHANNELS,\n            norm=norm,\n        )\n    elif cfg.MODEL.RESNETS.STEM_TYPE == \"deeplab\":\n        stem = DeepLabStem(\n            in_channels=input_shape.channels,\n            out_channels=cfg.MODEL.RESNETS.STEM_OUT_CHANNELS,\n            norm=norm,\n        )\n    else:\n        raise ValueError(\"Unknown stem type: {}\".format(cfg.MODEL.RESNETS.STEM_TYPE))\n\n    # fmt: off\n    freeze_at           = cfg.MODEL.BACKBONE.FREEZE_AT\n    out_features        = cfg.MODEL.RESNETS.OUT_FEATURES\n    depth               = cfg.MODEL.RESNETS.DEPTH\n    num_groups          = cfg.MODEL.RESNETS.NUM_GROUPS\n    width_per_group     = cfg.MODEL.RESNETS.WIDTH_PER_GROUP\n    bottleneck_channels = num_groups * width_per_group\n    in_channels         = cfg.MODEL.RESNETS.STEM_OUT_CHANNELS\n    out_channels        = cfg.MODEL.RESNETS.RES2_OUT_CHANNELS\n    stride_in_1x1       = cfg.MODEL.RESNETS.STRIDE_IN_1X1\n    res4_dilation       = cfg.MODEL.RESNETS.RES4_DILATION\n    res5_dilation       = cfg.MODEL.RESNETS.RES5_DILATION\n    deform_on_per_stage = cfg.MODEL.RESNETS.DEFORM_ON_PER_STAGE\n    deform_modulated    = cfg.MODEL.RESNETS.DEFORM_MODULATED\n    deform_num_groups   = cfg.MODEL.RESNETS.DEFORM_NUM_GROUPS\n    res5_multi_grid     = cfg.MODEL.RESNETS.RES5_MULTI_GRID\n    # fmt: on\n    assert res4_dilation in {1, 2}, \"res4_dilation cannot be {}.\".format(res4_dilation)\n    assert res5_dilation in {1, 2, 4}, \"res5_dilation cannot be {}.\".format(res5_dilation)\n    if res4_dilation == 2:\n        # Always dilate res5 if res4 is dilated.\n        assert res5_dilation == 4\n\n    num_blocks_per_stage = {50: [3, 4, 6, 3], 101: [3, 4, 23, 3], 152: [3, 8, 36, 3]}[depth]\n\n    stages = []\n\n    # Avoid creating variables without gradients\n    # It consumes extra memory and may cause allreduce to fail\n    out_stage_idx = [{\"res2\": 2, \"res3\": 3, \"res4\": 4, \"res5\": 5}[f] for f in out_features]\n    max_stage_idx = max(out_stage_idx)\n    for idx, stage_idx in enumerate(range(2, max_stage_idx + 1)):\n        if stage_idx == 4:\n            dilation = res4_dilation\n        elif stage_idx == 5:\n            dilation = res5_dilation\n        else:\n            dilation = 1\n        first_stride = 1 if idx == 0 or dilation > 1 else 2\n        stage_kargs = {\n            \"num_blocks\": num_blocks_per_stage[idx],\n            \"stride_per_block\": [first_stride] + [1] * (num_blocks_per_stage[idx] - 1),\n            \"in_channels\": in_channels,\n            \"out_channels\": out_channels,\n            \"norm\": norm,\n        }\n        stage_kargs[\"bottleneck_channels\"] = bottleneck_channels\n        stage_kargs[\"stride_in_1x1\"] = stride_in_1x1\n        stage_kargs[\"dilation\"] = dilation\n        stage_kargs[\"num_groups\"] = num_groups\n        if deform_on_per_stage[idx]:\n            stage_kargs[\"block_class\"] = DeformBottleneckBlock\n            stage_kargs[\"deform_modulated\"] = deform_modulated\n            stage_kargs[\"deform_num_groups\"] = deform_num_groups\n        else:\n            stage_kargs[\"block_class\"] = BottleneckBlock\n        if stage_idx == 5:\n            stage_kargs.pop(\"dilation\")\n            stage_kargs[\"dilation_per_block\"] = [dilation * mg for mg in res5_multi_grid]\n        blocks = ResNet.make_stage(**stage_kargs)\n        in_channels = out_channels\n        out_channels *= 2\n        bottleneck_channels *= 2\n        stages.append(blocks)\n    return ResNet(stem, stages, out_features=out_features).freeze(freeze_at)\n"
  },
  {
    "path": "VPS_Module/projects/DeepLab/deeplab/semantic_seg.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom typing import Callable, Dict, List, Optional, Tuple, Union\nimport fvcore.nn.weight_init as weight_init\nimport torch\nfrom torch import nn\nfrom torch.nn import functional as F\n\nfrom detectron2.config import configurable\nfrom detectron2.layers import ASPP, Conv2d, DepthwiseSeparableConv2d, ShapeSpec, get_norm\nfrom detectron2.modeling import SEM_SEG_HEADS_REGISTRY\n\nfrom .loss import DeepLabCE\n\n\n@SEM_SEG_HEADS_REGISTRY.register()\nclass DeepLabV3PlusHead(nn.Module):\n    \"\"\"\n    A semantic segmentation head described in :paper:`DeepLabV3+`.\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self,\n        input_shape: Dict[str, ShapeSpec],\n        *,\n        project_channels: List[int],\n        aspp_dilations: List[int],\n        aspp_dropout: float,\n        decoder_channels: List[int],\n        common_stride: int,\n        norm: Union[str, Callable],\n        train_size: Optional[Tuple],\n        loss_weight: float = 1.0,\n        loss_type: str = \"cross_entropy\",\n        ignore_value: int = -1,\n        num_classes: Optional[int] = None,\n        use_depthwise_separable_conv: bool = False,\n    ):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            input_shape: shape of the input features. They will be ordered by stride\n                and the last one (with largest stride) is used as the input to the\n                decoder (i.e.  the ASPP module); the rest are low-level feature for\n                the intermediate levels of decoder.\n            project_channels (list[int]): a list of low-level feature channels.\n                The length should be len(in_features) - 1.\n            aspp_dilations (list(int)): a list of 3 dilations in ASPP.\n            aspp_dropout (float): apply dropout on the output of ASPP.\n            decoder_channels (list[int]): a list of output channels of each\n                decoder stage. It should have the same length as \"in_features\"\n                (each element in \"in_features\" corresponds to one decoder stage).\n            common_stride (int): output stride of decoder.\n            norm (str or callable): normalization for all conv layers.\n            train_size (tuple): (height, width) of training images.\n            loss_weight (float): loss weight.\n            loss_type (str): type of loss function, 2 opptions:\n                (1) \"cross_entropy\" is the standard cross entropy loss.\n                (2) \"hard_pixel_mining\" is the loss in DeepLab that samples\n                    top k% hardest pixels.\n            ignore_value (int): category to be ignored during training.\n            num_classes (int): number of classes, if set to None, the decoder\n                will not construct a predictor.\n            use_depthwise_separable_conv (bool): use DepthwiseSeparableConv2d\n                in ASPP and decoder.\n        \"\"\"\n        super().__init__()\n        input_shape = sorted(input_shape.items(), key=lambda x: x[1].stride)\n\n        # fmt: off\n        self.in_features      = [k for k, v in input_shape]  # starting from \"res2\" to \"res5\"\n        in_channels           = [x[1].channels for x in input_shape]\n        in_strides            = [x[1].stride for x in input_shape]\n        aspp_channels         = decoder_channels[-1]\n        self.ignore_value     = ignore_value\n        self.common_stride    = common_stride  # output stride\n        self.loss_weight      = loss_weight\n        self.loss_type        = loss_type\n        self.decoder_only     = num_classes is None\n        self.use_depthwise_separable_conv = use_depthwise_separable_conv\n        # fmt: on\n\n        assert (\n            len(project_channels) == len(self.in_features) - 1\n        ), \"Expected {} project_channels, got {}\".format(\n            len(self.in_features) - 1, len(project_channels)\n        )\n        assert len(decoder_channels) == len(\n            self.in_features\n        ), \"Expected {} decoder_channels, got {}\".format(\n            len(self.in_features), len(decoder_channels)\n        )\n        self.decoder = nn.ModuleDict()\n\n        use_bias = norm == \"\"\n        for idx, in_channel in enumerate(in_channels):\n            decoder_stage = nn.ModuleDict()\n\n            if idx == len(self.in_features) - 1:\n                # ASPP module\n                if train_size is not None:\n                    train_h, train_w = train_size\n                    encoder_stride = in_strides[-1]\n                    if train_h % encoder_stride or train_w % encoder_stride:\n                        raise ValueError(\"Crop size need to be divisible by encoder stride.\")\n                    pool_h = train_h // encoder_stride\n                    pool_w = train_w // encoder_stride\n                    pool_kernel_size = (pool_h, pool_w)\n                else:\n                    pool_kernel_size = None\n                project_conv = ASPP(\n                    in_channel,\n                    aspp_channels,\n                    aspp_dilations,\n                    norm=norm,\n                    activation=F.relu,\n                    pool_kernel_size=pool_kernel_size,\n                    dropout=aspp_dropout,\n                    use_depthwise_separable_conv=use_depthwise_separable_conv,\n                )\n                fuse_conv = None\n            else:\n                project_conv = Conv2d(\n                    in_channel,\n                    project_channels[idx],\n                    kernel_size=1,\n                    bias=use_bias,\n                    norm=get_norm(norm, project_channels[idx]),\n                    activation=F.relu,\n                )\n                weight_init.c2_xavier_fill(project_conv)\n                if use_depthwise_separable_conv:\n                    # We use a single 5x5 DepthwiseSeparableConv2d to replace\n                    # 2 3x3 Conv2d since they have the same receptive field,\n                    # proposed in :paper:`Panoptic-DeepLab`.\n                    fuse_conv = DepthwiseSeparableConv2d(\n                        project_channels[idx] + decoder_channels[idx + 1],\n                        decoder_channels[idx],\n                        kernel_size=5,\n                        padding=2,\n                        norm1=norm,\n                        activation1=F.relu,\n                        norm2=norm,\n                        activation2=F.relu,\n                    )\n                else:\n                    fuse_conv = nn.Sequential(\n                        Conv2d(\n                            project_channels[idx] + decoder_channels[idx + 1],\n                            decoder_channels[idx],\n                            kernel_size=3,\n                            padding=1,\n                            bias=use_bias,\n                            norm=get_norm(norm, decoder_channels[idx]),\n                            activation=F.relu,\n                        ),\n                        Conv2d(\n                            decoder_channels[idx],\n                            decoder_channels[idx],\n                            kernel_size=3,\n                            padding=1,\n                            bias=use_bias,\n                            norm=get_norm(norm, decoder_channels[idx]),\n                            activation=F.relu,\n                        ),\n                    )\n                    weight_init.c2_xavier_fill(fuse_conv[0])\n                    weight_init.c2_xavier_fill(fuse_conv[1])\n\n            decoder_stage[\"project_conv\"] = project_conv\n            decoder_stage[\"fuse_conv\"] = fuse_conv\n\n            self.decoder[self.in_features[idx]] = decoder_stage\n\n        if not self.decoder_only:\n            self.predictor = Conv2d(\n                decoder_channels[0], num_classes, kernel_size=1, stride=1, padding=0\n            )\n            nn.init.normal_(self.predictor.weight, 0, 0.001)\n            nn.init.constant_(self.predictor.bias, 0)\n\n            if self.loss_type == \"cross_entropy\":\n                self.loss = nn.CrossEntropyLoss(reduction=\"mean\", ignore_index=self.ignore_value)\n            elif self.loss_type == \"hard_pixel_mining\":\n                self.loss = DeepLabCE(ignore_label=self.ignore_value, top_k_percent_pixels=0.2)\n            else:\n                raise ValueError(\"Unexpected loss type: %s\" % self.loss_type)\n\n    @classmethod\n    def from_config(cls, cfg, input_shape):\n        if cfg.INPUT.CROP.ENABLED:\n            assert cfg.INPUT.CROP.TYPE == \"absolute\"\n            train_size = cfg.INPUT.CROP.SIZE\n        else:\n            train_size = None\n        decoder_channels = [cfg.MODEL.SEM_SEG_HEAD.CONVS_DIM] * (\n            len(cfg.MODEL.SEM_SEG_HEAD.IN_FEATURES) - 1\n        ) + [cfg.MODEL.SEM_SEG_HEAD.ASPP_CHANNELS]\n        ret = dict(\n            input_shape={\n                k: v for k, v in input_shape.items() if k in cfg.MODEL.SEM_SEG_HEAD.IN_FEATURES\n            },\n            project_channels=cfg.MODEL.SEM_SEG_HEAD.PROJECT_CHANNELS,\n            aspp_dilations=cfg.MODEL.SEM_SEG_HEAD.ASPP_DILATIONS,\n            aspp_dropout=cfg.MODEL.SEM_SEG_HEAD.ASPP_DROPOUT,\n            decoder_channels=decoder_channels,\n            common_stride=cfg.MODEL.SEM_SEG_HEAD.COMMON_STRIDE,\n            norm=cfg.MODEL.SEM_SEG_HEAD.NORM,\n            train_size=train_size,\n            loss_weight=cfg.MODEL.SEM_SEG_HEAD.LOSS_WEIGHT,\n            loss_type=cfg.MODEL.SEM_SEG_HEAD.LOSS_TYPE,\n            ignore_value=cfg.MODEL.SEM_SEG_HEAD.IGNORE_VALUE,\n            num_classes=cfg.MODEL.SEM_SEG_HEAD.NUM_CLASSES,\n            use_depthwise_separable_conv=cfg.MODEL.SEM_SEG_HEAD.USE_DEPTHWISE_SEPARABLE_CONV,\n        )\n        return ret\n\n    def forward(self, features, targets=None):\n        \"\"\"\n        Returns:\n            In training, returns (None, dict of losses)\n            In inference, returns (CxHxW logits, {})\n        \"\"\"\n        y = self.layers(features)\n        if self.decoder_only:\n            # Output from self.layers() only contains decoder feature.\n            return y\n        if self.training:\n            return None, self.losses(y, targets)\n        else:\n            y = F.interpolate(\n                y, scale_factor=self.common_stride, mode=\"bilinear\", align_corners=False\n            )\n            return y, {}\n\n    def layers(self, features):\n        # Reverse feature maps into top-down order (from low to high resolution)\n        for f in self.in_features[::-1]:\n            x = features[f]\n            proj_x = self.decoder[f][\"project_conv\"](x)\n            if self.decoder[f][\"fuse_conv\"] is None:\n                # This is aspp module\n                y = proj_x\n            else:\n                # Upsample y\n                y = F.interpolate(y, size=proj_x.size()[2:], mode=\"bilinear\", align_corners=False)\n                y = torch.cat([proj_x, y], dim=1)\n                y = self.decoder[f][\"fuse_conv\"](y)\n        if not self.decoder_only:\n            y = self.predictor(y)\n        return y\n\n    def losses(self, predictions, targets):\n        predictions = F.interpolate(\n            predictions, scale_factor=self.common_stride, mode=\"bilinear\", align_corners=False\n        )\n        loss = self.loss(predictions, targets)\n        losses = {\"loss_sem_seg\": loss * self.loss_weight}\n        return losses\n\n\n@SEM_SEG_HEADS_REGISTRY.register()\nclass DeepLabV3Head(nn.Module):\n    \"\"\"\n    A semantic segmentation head described in :paper:`DeepLabV3`.\n    \"\"\"\n\n    def __init__(self, cfg, input_shape: Dict[str, ShapeSpec]):\n        super().__init__()\n\n        # fmt: off\n        self.in_features      = cfg.MODEL.SEM_SEG_HEAD.IN_FEATURES\n        in_channels           = [input_shape[f].channels for f in self.in_features]\n        aspp_channels         = cfg.MODEL.SEM_SEG_HEAD.ASPP_CHANNELS\n        aspp_dilations        = cfg.MODEL.SEM_SEG_HEAD.ASPP_DILATIONS\n        self.ignore_value     = cfg.MODEL.SEM_SEG_HEAD.IGNORE_VALUE\n        num_classes           = cfg.MODEL.SEM_SEG_HEAD.NUM_CLASSES\n        conv_dims             = cfg.MODEL.SEM_SEG_HEAD.CONVS_DIM\n        self.common_stride    = cfg.MODEL.SEM_SEG_HEAD.COMMON_STRIDE  # output stride\n        norm                  = cfg.MODEL.SEM_SEG_HEAD.NORM\n        self.loss_weight      = cfg.MODEL.SEM_SEG_HEAD.LOSS_WEIGHT\n        self.loss_type        = cfg.MODEL.SEM_SEG_HEAD.LOSS_TYPE\n        train_crop_size       = cfg.INPUT.CROP.SIZE\n        aspp_dropout          = cfg.MODEL.SEM_SEG_HEAD.ASPP_DROPOUT\n        use_depthwise_separable_conv = cfg.MODEL.SEM_SEG_HEAD.USE_DEPTHWISE_SEPARABLE_CONV\n        # fmt: on\n\n        assert len(self.in_features) == 1\n        assert len(in_channels) == 1\n\n        # ASPP module\n        if cfg.INPUT.CROP.ENABLED:\n            assert cfg.INPUT.CROP.TYPE == \"absolute\"\n            train_crop_h, train_crop_w = train_crop_size\n            if train_crop_h % self.common_stride or train_crop_w % self.common_stride:\n                raise ValueError(\"Crop size need to be divisible by output stride.\")\n            pool_h = train_crop_h // self.common_stride\n            pool_w = train_crop_w // self.common_stride\n            pool_kernel_size = (pool_h, pool_w)\n        else:\n            pool_kernel_size = None\n        self.aspp = ASPP(\n            in_channels[0],\n            aspp_channels,\n            aspp_dilations,\n            norm=norm,\n            activation=F.relu,\n            pool_kernel_size=pool_kernel_size,\n            dropout=aspp_dropout,\n            use_depthwise_separable_conv=use_depthwise_separable_conv,\n        )\n\n        self.predictor = Conv2d(conv_dims, num_classes, kernel_size=1, stride=1, padding=0)\n        nn.init.normal_(self.predictor.weight, 0, 0.001)\n        nn.init.constant_(self.predictor.bias, 0)\n\n        if self.loss_type == \"cross_entropy\":\n            self.loss = nn.CrossEntropyLoss(reduction=\"mean\", ignore_index=self.ignore_value)\n        elif self.loss_type == \"hard_pixel_mining\":\n            self.loss = DeepLabCE(ignore_label=self.ignore_value, top_k_percent_pixels=0.2)\n        else:\n            raise ValueError(\"Unexpected loss type: %s\" % self.loss_type)\n\n    def forward(self, features, targets=None):\n        \"\"\"\n        Returns:\n            In training, returns (None, dict of losses)\n            In inference, returns (CxHxW logits, {})\n        \"\"\"\n        x = features[self.in_features[0]]\n        x = self.aspp(x)\n        x = self.predictor(x)\n        if self.training:\n            return None, self.losses(x, targets)\n        else:\n            x = F.interpolate(\n                x, scale_factor=self.common_stride, mode=\"bilinear\", align_corners=False\n            )\n            return x, {}\n\n    def losses(self, predictions, targets):\n        predictions = F.interpolate(\n            predictions, scale_factor=self.common_stride, mode=\"bilinear\", align_corners=False\n        )\n        loss = self.loss(predictions, targets)\n        losses = {\"loss_sem_seg\": loss * self.loss_weight}\n        return losses\n"
  },
  {
    "path": "VPS_Module/projects/DeepLab/train_net.py",
    "content": "#!/usr/bin/env python3\n# Copyright (c) Facebook, Inc. and its affiliates.\n\n\"\"\"\nDeepLab Training Script.\n\nThis script is a simplified version of the training script in detectron2/tools.\n\"\"\"\n\nimport os\nimport torch\n\nimport detectron2.data.transforms as T\nimport detectron2.utils.comm as comm\nfrom detectron2.checkpoint import DetectionCheckpointer\nfrom detectron2.config import get_cfg\nfrom detectron2.data import DatasetMapper, MetadataCatalog, build_detection_train_loader\nfrom detectron2.engine import DefaultTrainer, default_argument_parser, default_setup, launch\nfrom detectron2.evaluation import CityscapesSemSegEvaluator, DatasetEvaluators, SemSegEvaluator\nfrom detectron2.projects.deeplab import add_deeplab_config, build_lr_scheduler\n\n\ndef build_sem_seg_train_aug(cfg):\n    augs = [\n        T.ResizeShortestEdge(\n            cfg.INPUT.MIN_SIZE_TRAIN, cfg.INPUT.MAX_SIZE_TRAIN, cfg.INPUT.MIN_SIZE_TRAIN_SAMPLING\n        )\n    ]\n    if cfg.INPUT.CROP.ENABLED:\n        augs.append(\n            T.RandomCrop_CategoryAreaConstraint(\n                cfg.INPUT.CROP.TYPE,\n                cfg.INPUT.CROP.SIZE,\n                cfg.INPUT.CROP.SINGLE_CATEGORY_MAX_AREA,\n                cfg.MODEL.SEM_SEG_HEAD.IGNORE_VALUE,\n            )\n        )\n    augs.append(T.RandomFlip())\n    return augs\n\n\nclass Trainer(DefaultTrainer):\n    \"\"\"\n    We use the \"DefaultTrainer\" which contains a number pre-defined logic for\n    standard training workflow. They may not work for you, especially if you\n    are working on a new research project. In that case you can use the cleaner\n    \"SimpleTrainer\", or write your own training loop.\n    \"\"\"\n\n    @classmethod\n    def build_evaluator(cls, cfg, dataset_name, output_folder=None):\n        \"\"\"\n        Create evaluator(s) for a given dataset.\n        This uses the special metadata \"evaluator_type\" associated with each builtin dataset.\n        For your own dataset, you can simply create an evaluator manually in your\n        script and do not have to worry about the hacky if-else logic here.\n        \"\"\"\n        if output_folder is None:\n            output_folder = os.path.join(cfg.OUTPUT_DIR, \"inference\")\n        evaluator_list = []\n        evaluator_type = MetadataCatalog.get(dataset_name).evaluator_type\n        if evaluator_type == \"sem_seg\":\n            return SemSegEvaluator(\n                dataset_name,\n                distributed=True,\n                output_dir=output_folder,\n            )\n        if evaluator_type == \"cityscapes_sem_seg\":\n            assert (\n                torch.cuda.device_count() > comm.get_rank()\n            ), \"CityscapesEvaluator currently do not work with multiple machines.\"\n            return CityscapesSemSegEvaluator(dataset_name)\n        if len(evaluator_list) == 0:\n            raise NotImplementedError(\n                \"no Evaluator for the dataset {} with the type {}\".format(\n                    dataset_name, evaluator_type\n                )\n            )\n        if len(evaluator_list) == 1:\n            return evaluator_list[0]\n        return DatasetEvaluators(evaluator_list)\n\n    @classmethod\n    def build_train_loader(cls, cfg):\n        if \"SemanticSegmentor\" in cfg.MODEL.META_ARCHITECTURE:\n            mapper = DatasetMapper(cfg, is_train=True, augmentations=build_sem_seg_train_aug(cfg))\n        else:\n            mapper = None\n        return build_detection_train_loader(cfg, mapper=mapper)\n\n    @classmethod\n    def build_lr_scheduler(cls, cfg, optimizer):\n        \"\"\"\n        It now calls :func:`detectron2.solver.build_lr_scheduler`.\n        Overwrite it if you'd like a different scheduler.\n        \"\"\"\n        return build_lr_scheduler(cfg, optimizer)\n\n\ndef setup(args):\n    \"\"\"\n    Create configs and perform basic setups.\n    \"\"\"\n    cfg = get_cfg()\n    add_deeplab_config(cfg)\n    cfg.merge_from_file(args.config_file)\n    cfg.merge_from_list(args.opts)\n    cfg.freeze()\n    default_setup(cfg, args)\n    return cfg\n\n\ndef main(args):\n    cfg = setup(args)\n\n    if args.eval_only:\n        model = Trainer.build_model(cfg)\n        DetectionCheckpointer(model, save_dir=cfg.OUTPUT_DIR).resume_or_load(\n            cfg.MODEL.WEIGHTS, resume=args.resume\n        )\n        res = Trainer.test(cfg, model)\n        return res\n\n    trainer = Trainer(cfg)\n    trainer.resume_or_load(resume=args.resume)\n    return trainer.train()\n\n\nif __name__ == \"__main__\":\n    args = default_argument_parser().parse_args()\n    print(\"Command Line Args:\", args)\n    launch(\n        main,\n        args.num_gpus,\n        num_machines=args.num_machines,\n        machine_rank=args.machine_rank,\n        dist_url=args.dist_url,\n        args=(args,),\n    )\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/README.md",
    "content": "# DensePose in Detectron2\n\nDensePose aims at learning and establishing dense correspondences between image pixels\nand 3D object geometry for deformable objects, such as humans or animals.\nIn this repository, we provide the code to train and evaluate DensePose R-CNN and\nvarious tools to visualize DensePose annotations and results.\n\nThere are two main paradigms that are used within DensePose project.\n\n## [Chart-based Dense Pose Estimation for Humans and Animals](doc/DENSEPOSE_IUV.md)\n\n<div align=\"center\">\n  <img src=\"https://dl.fbaipublicfiles.com/densepose/web/densepose_teaser_compressed_25.gif\" width=\"700px\" />\n</div>\n\nFor chart-based estimation, 3D object mesh is split into charts and\nfor each pixel the model estimates chart index `I` and local chart coordinates `(U, V)`.\nPlease follow the link above to find a [detailed overview](doc/DENSEPOSE_IUV.md#Overview)\nof the method, links to trained models along with their performance evaluation in the\n[Model Zoo](doc/DENSEPOSE_IUV.md#ModelZoo) and\n[references](doc/DENSEPOSE_IUV.md#References) to the corresponding papers.\n\n## [Continuous Surface Embeddings for Dense Pose Estimation for Humans and Animals](doc/DENSEPOSE_CSE.md)\n\n<div align=\"center\">\n  <img src=\"https://dl.fbaipublicfiles.com/densepose/web/densepose_cse_teaser.png\" width=\"700px\" />\n</div>\n\nTo establish continuous surface embeddings, the model simultaneously learns\ndescriptors for mesh vertices and for image pixels.\nThe embeddings are put into correspondence, thus the location\nof each pixel on the 3D model is derived.\nPlease follow the link above to find a [detailed overview](doc/DENSEPOSE_CSE.md#Overview)\nof the method, links to trained models along with their performance evaluation in the\n[Model Zoo](doc/DENSEPOSE_CSE.md#ModelZoo) and\n[references](doc/DENSEPOSE_CSE.md#References) to the corresponding papers.\n\n# Quick Start\n\nSee [ Getting Started ](doc/GETTING_STARTED.md)\n\n# Model Zoo\n\nPlease check the dedicated pages\nfor [chart-based model zoo](doc/DENSEPOSE_IUV.md#ModelZoo)\nand for [continuous surface embeddings model zoo](doc/DENSEPOSE_CSE.md#ModelZoo).\n\n# What's New\n\n* June 2021: [DensePose CSE with Cycle Losses](doc/RELEASE_2021_06.md)\n* March 2021: [DensePose CSE (a framework to extend DensePose to various categories using 3D models)\n  and DensePose Evolution (a framework to bootstrap DensePose on unlabeled data) released](doc/RELEASE_2021_03.md)\n* April 2020: [DensePose Confidence Estimation and Model Zoo Improvements](doc/RELEASE_2020_04.md)\n\n# License\n\nDetectron2 is released under the [Apache 2.0 license](../../LICENSE)\n\n## <a name=\"CitingDensePose\"></a>Citing DensePose\n\nIf you use DensePose, please refer to the BibTeX entries\nfor [chart-based models](doc/DENSEPOSE_IUV.md#References)\nand for [continuous surface embeddings](doc/DENSEPOSE_CSE.md#References).\n\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/apply_net.py",
    "content": "#!/usr/bin/env python3\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport argparse\nimport glob\nimport logging\nimport os\nimport pickle\nimport sys\nfrom typing import Any, ClassVar, Dict, List\nimport torch\n\nfrom detectron2.config import CfgNode, get_cfg\nfrom detectron2.data.detection_utils import read_image\nfrom detectron2.engine.defaults import DefaultPredictor\nfrom detectron2.structures.instances import Instances\nfrom detectron2.utils.logger import setup_logger\n\nfrom densepose import add_densepose_config\nfrom densepose.structures import DensePoseChartPredictorOutput, DensePoseEmbeddingPredictorOutput\nfrom densepose.utils.logger import verbosity_to_level\nfrom densepose.vis.base import CompoundVisualizer\nfrom densepose.vis.bounding_box import ScoredBoundingBoxVisualizer\nfrom densepose.vis.densepose_outputs_vertex import (\n    DensePoseOutputsTextureVisualizer,\n    DensePoseOutputsVertexVisualizer,\n    get_texture_atlases,\n)\nfrom densepose.vis.densepose_results import (\n    DensePoseResultsContourVisualizer,\n    DensePoseResultsFineSegmentationVisualizer,\n    DensePoseResultsUVisualizer,\n    DensePoseResultsVVisualizer,\n)\nfrom densepose.vis.densepose_results_textures import (\n    DensePoseResultsVisualizerWithTexture,\n    get_texture_atlas,\n)\nfrom densepose.vis.extractor import (\n    CompoundExtractor,\n    DensePoseOutputsExtractor,\n    DensePoseResultExtractor,\n    create_extractor,\n)\n\nDOC = \"\"\"Apply Net - a tool to print / visualize DensePose results\n\"\"\"\n\nLOGGER_NAME = \"apply_net\"\nlogger = logging.getLogger(LOGGER_NAME)\n\n_ACTION_REGISTRY: Dict[str, \"Action\"] = {}\n\n\nclass Action(object):\n    @classmethod\n    def add_arguments(cls: type, parser: argparse.ArgumentParser):\n        parser.add_argument(\n            \"-v\",\n            \"--verbosity\",\n            action=\"count\",\n            help=\"Verbose mode. Multiple -v options increase the verbosity.\",\n        )\n\n\ndef register_action(cls: type):\n    \"\"\"\n    Decorator for action classes to automate action registration\n    \"\"\"\n    global _ACTION_REGISTRY\n    _ACTION_REGISTRY[cls.COMMAND] = cls\n    return cls\n\n\nclass InferenceAction(Action):\n    @classmethod\n    def add_arguments(cls: type, parser: argparse.ArgumentParser):\n        super(InferenceAction, cls).add_arguments(parser)\n        parser.add_argument(\"cfg\", metavar=\"<config>\", help=\"Config file\")\n        parser.add_argument(\"model\", metavar=\"<model>\", help=\"Model file\")\n        parser.add_argument(\"input\", metavar=\"<input>\", help=\"Input data\")\n        parser.add_argument(\n            \"--opts\",\n            help=\"Modify config options using the command-line 'KEY VALUE' pairs\",\n            default=[],\n            nargs=argparse.REMAINDER,\n        )\n\n    @classmethod\n    def execute(cls: type, args: argparse.Namespace):\n        logger.info(f\"Loading config from {args.cfg}\")\n        opts = []\n        cfg = cls.setup_config(args.cfg, args.model, args, opts)\n        logger.info(f\"Loading model from {args.model}\")\n        predictor = DefaultPredictor(cfg)\n        logger.info(f\"Loading data from {args.input}\")\n        file_list = cls._get_input_file_list(args.input)\n        if len(file_list) == 0:\n            logger.warning(f\"No input images for {args.input}\")\n            return\n        context = cls.create_context(args, cfg)\n        for file_name in file_list:\n            img = read_image(file_name, format=\"BGR\")  # predictor expects BGR image.\n            with torch.no_grad():\n                outputs = predictor(img)[\"instances\"]\n                cls.execute_on_outputs(context, {\"file_name\": file_name, \"image\": img}, outputs)\n        cls.postexecute(context)\n\n    @classmethod\n    def setup_config(\n        cls: type, config_fpath: str, model_fpath: str, args: argparse.Namespace, opts: List[str]\n    ):\n        cfg = get_cfg()\n        add_densepose_config(cfg)\n        cfg.merge_from_file(config_fpath)\n        cfg.merge_from_list(args.opts)\n        if opts:\n            cfg.merge_from_list(opts)\n        cfg.MODEL.WEIGHTS = model_fpath\n        cfg.freeze()\n        return cfg\n\n    @classmethod\n    def _get_input_file_list(cls: type, input_spec: str):\n        if os.path.isdir(input_spec):\n            file_list = [\n                os.path.join(input_spec, fname)\n                for fname in os.listdir(input_spec)\n                if os.path.isfile(os.path.join(input_spec, fname))\n            ]\n        elif os.path.isfile(input_spec):\n            file_list = [input_spec]\n        else:\n            file_list = glob.glob(input_spec)\n        return file_list\n\n\n@register_action\nclass DumpAction(InferenceAction):\n    \"\"\"\n    Dump action that outputs results to a pickle file\n    \"\"\"\n\n    COMMAND: ClassVar[str] = \"dump\"\n\n    @classmethod\n    def add_parser(cls: type, subparsers: argparse._SubParsersAction):\n        parser = subparsers.add_parser(cls.COMMAND, help=\"Dump model outputs to a file.\")\n        cls.add_arguments(parser)\n        parser.set_defaults(func=cls.execute)\n\n    @classmethod\n    def add_arguments(cls: type, parser: argparse.ArgumentParser):\n        super(DumpAction, cls).add_arguments(parser)\n        parser.add_argument(\n            \"--output\",\n            metavar=\"<dump_file>\",\n            default=\"results.pkl\",\n            help=\"File name to save dump to\",\n        )\n\n    @classmethod\n    def execute_on_outputs(\n        cls: type, context: Dict[str, Any], entry: Dict[str, Any], outputs: Instances\n    ):\n        image_fpath = entry[\"file_name\"]\n        logger.info(f\"Processing {image_fpath}\")\n        result = {\"file_name\": image_fpath}\n        if outputs.has(\"scores\"):\n            result[\"scores\"] = outputs.get(\"scores\").cpu()\n        if outputs.has(\"pred_boxes\"):\n            result[\"pred_boxes_XYXY\"] = outputs.get(\"pred_boxes\").tensor.cpu()\n            if outputs.has(\"pred_densepose\"):\n                if isinstance(outputs.pred_densepose, DensePoseChartPredictorOutput):\n                    extractor = DensePoseResultExtractor()\n                elif isinstance(outputs.pred_densepose, DensePoseEmbeddingPredictorOutput):\n                    extractor = DensePoseOutputsExtractor()\n                result[\"pred_densepose\"] = extractor(outputs)[0]\n        context[\"results\"].append(result)\n\n    @classmethod\n    def create_context(cls: type, args: argparse.Namespace, cfg: CfgNode):\n        context = {\"results\": [], \"out_fname\": args.output}\n        return context\n\n    @classmethod\n    def postexecute(cls: type, context: Dict[str, Any]):\n        out_fname = context[\"out_fname\"]\n        out_dir = os.path.dirname(out_fname)\n        if len(out_dir) > 0 and not os.path.exists(out_dir):\n            os.makedirs(out_dir)\n        with open(out_fname, \"wb\") as hFile:\n            pickle.dump(context[\"results\"], hFile)\n            logger.info(f\"Output saved to {out_fname}\")\n\n\n@register_action\nclass ShowAction(InferenceAction):\n    \"\"\"\n    Show action that visualizes selected entries on an image\n    \"\"\"\n\n    COMMAND: ClassVar[str] = \"show\"\n    VISUALIZERS: ClassVar[Dict[str, object]] = {\n        \"dp_contour\": DensePoseResultsContourVisualizer,\n        \"dp_segm\": DensePoseResultsFineSegmentationVisualizer,\n        \"dp_u\": DensePoseResultsUVisualizer,\n        \"dp_v\": DensePoseResultsVVisualizer,\n        \"dp_iuv_texture\": DensePoseResultsVisualizerWithTexture,\n        \"dp_cse_texture\": DensePoseOutputsTextureVisualizer,\n        \"dp_vertex\": DensePoseOutputsVertexVisualizer,\n        \"bbox\": ScoredBoundingBoxVisualizer,\n    }\n\n    @classmethod\n    def add_parser(cls: type, subparsers: argparse._SubParsersAction):\n        parser = subparsers.add_parser(cls.COMMAND, help=\"Visualize selected entries\")\n        cls.add_arguments(parser)\n        parser.set_defaults(func=cls.execute)\n\n    @classmethod\n    def add_arguments(cls: type, parser: argparse.ArgumentParser):\n        super(ShowAction, cls).add_arguments(parser)\n        parser.add_argument(\n            \"visualizations\",\n            metavar=\"<visualizations>\",\n            help=\"Comma separated list of visualizations, possible values: \"\n            \"[{}]\".format(\",\".join(sorted(cls.VISUALIZERS.keys()))),\n        )\n        parser.add_argument(\n            \"--min_score\",\n            metavar=\"<score>\",\n            default=0.8,\n            type=float,\n            help=\"Minimum detection score to visualize\",\n        )\n        parser.add_argument(\n            \"--nms_thresh\", metavar=\"<threshold>\", default=None, type=float, help=\"NMS threshold\"\n        )\n        parser.add_argument(\n            \"--texture_atlas\",\n            metavar=\"<texture_atlas>\",\n            default=None,\n            help=\"Texture atlas file (for IUV texture transfer)\",\n        )\n        parser.add_argument(\n            \"--texture_atlases_map\",\n            metavar=\"<texture_atlases_map>\",\n            default=None,\n            help=\"JSON string of a dict containing texture atlas files for each mesh\",\n        )\n        parser.add_argument(\n            \"--output\",\n            metavar=\"<image_file>\",\n            default=\"outputres.png\",\n            help=\"File name to save output to\",\n        )\n\n    @classmethod\n    def setup_config(\n        cls: type, config_fpath: str, model_fpath: str, args: argparse.Namespace, opts: List[str]\n    ):\n        opts.append(\"MODEL.ROI_HEADS.SCORE_THRESH_TEST\")\n        opts.append(str(args.min_score))\n        if args.nms_thresh is not None:\n            opts.append(\"MODEL.ROI_HEADS.NMS_THRESH_TEST\")\n            opts.append(str(args.nms_thresh))\n        cfg = super(ShowAction, cls).setup_config(config_fpath, model_fpath, args, opts)\n        return cfg\n\n    @classmethod\n    def execute_on_outputs(\n        cls: type, context: Dict[str, Any], entry: Dict[str, Any], outputs: Instances\n    ):\n        import cv2\n        import numpy as np\n\n        visualizer = context[\"visualizer\"]\n        extractor = context[\"extractor\"]\n        image_fpath = entry[\"file_name\"]\n        logger.info(f\"Processing {image_fpath}\")\n        image = cv2.cvtColor(entry[\"image\"], cv2.COLOR_BGR2GRAY)\n        image = np.tile(image[:, :, np.newaxis], [1, 1, 3])\n        data = extractor(outputs)\n        image_vis = visualizer.visualize(image, data)\n        entry_idx = context[\"entry_idx\"] + 1\n        out_fname = cls._get_out_fname(entry_idx, context[\"out_fname\"])\n        out_dir = os.path.dirname(out_fname)\n        if len(out_dir) > 0 and not os.path.exists(out_dir):\n            os.makedirs(out_dir)\n        cv2.imwrite(out_fname, image_vis)\n        logger.info(f\"Output saved to {out_fname}\")\n        context[\"entry_idx\"] += 1\n\n    @classmethod\n    def postexecute(cls: type, context: Dict[str, Any]):\n        pass\n\n    @classmethod\n    def _get_out_fname(cls: type, entry_idx: int, fname_base: str):\n        base, ext = os.path.splitext(fname_base)\n        return base + \".{0:04d}\".format(entry_idx) + ext\n\n    @classmethod\n    def create_context(cls: type, args: argparse.Namespace, cfg: CfgNode) -> Dict[str, Any]:\n        vis_specs = args.visualizations.split(\",\")\n        visualizers = []\n        extractors = []\n        for vis_spec in vis_specs:\n            texture_atlas = get_texture_atlas(args.texture_atlas)\n            texture_atlases_dict = get_texture_atlases(args.texture_atlases_map)\n            vis = cls.VISUALIZERS[vis_spec](\n                cfg=cfg,\n                texture_atlas=texture_atlas,\n                texture_atlases_dict=texture_atlases_dict,\n            )\n            visualizers.append(vis)\n            extractor = create_extractor(vis)\n            extractors.append(extractor)\n        visualizer = CompoundVisualizer(visualizers)\n        extractor = CompoundExtractor(extractors)\n        context = {\n            \"extractor\": extractor,\n            \"visualizer\": visualizer,\n            \"out_fname\": args.output,\n            \"entry_idx\": 0,\n        }\n        return context\n\n\ndef create_argument_parser() -> argparse.ArgumentParser:\n    parser = argparse.ArgumentParser(\n        description=DOC,\n        formatter_class=lambda prog: argparse.HelpFormatter(prog, max_help_position=120),\n    )\n    parser.set_defaults(func=lambda _: parser.print_help(sys.stdout))\n    subparsers = parser.add_subparsers(title=\"Actions\")\n    for _, action in _ACTION_REGISTRY.items():\n        action.add_parser(subparsers)\n    return parser\n\n\ndef main():\n    parser = create_argument_parser()\n    args = parser.parse_args()\n    verbosity = args.verbosity if hasattr(args, \"verbosity\") else None\n    global logger\n    logger = setup_logger(name=LOGGER_NAME)\n    logger.setLevel(verbosity_to_level(verbosity))\n    args.func(args)\n\n\nif __name__ == \"__main__\":\n    main()\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/Base-DensePose-RCNN-FPN.yaml",
    "content": "VERSION: 2\nMODEL:\n  META_ARCHITECTURE: \"GeneralizedRCNN\"\n  BACKBONE:\n    NAME: \"build_resnet_fpn_backbone\"\n  RESNETS:\n    OUT_FEATURES: [\"res2\", \"res3\", \"res4\", \"res5\"]\n  FPN:\n    IN_FEATURES: [\"res2\", \"res3\", \"res4\", \"res5\"]\n  ANCHOR_GENERATOR:\n    SIZES: [[32], [64], [128], [256], [512]]  # One size for each in feature map\n    ASPECT_RATIOS: [[0.5, 1.0, 2.0]]  # Three aspect ratios (same for all in feature maps)\n  RPN:\n    IN_FEATURES: [\"p2\", \"p3\", \"p4\", \"p5\", \"p6\"]\n    PRE_NMS_TOPK_TRAIN: 2000  # Per FPN level\n    PRE_NMS_TOPK_TEST: 1000  # Per FPN level\n    # Detectron1 uses 2000 proposals per-batch,\n    # (See \"modeling/rpn/rpn_outputs.py\" for details of this legacy issue)\n    # which is approximately 1000 proposals per-image since the default batch size for FPN is 2.\n    POST_NMS_TOPK_TRAIN: 1000\n    POST_NMS_TOPK_TEST: 1000\n\n  DENSEPOSE_ON: True\n  ROI_HEADS:\n    NAME: \"DensePoseROIHeads\"\n    IN_FEATURES: [\"p2\", \"p3\", \"p4\", \"p5\"]\n    NUM_CLASSES: 1\n  ROI_BOX_HEAD:\n    NAME: \"FastRCNNConvFCHead\"\n    NUM_FC: 2\n    POOLER_RESOLUTION: 7\n    POOLER_SAMPLING_RATIO: 2\n    POOLER_TYPE: \"ROIAlign\"\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseV1ConvXHead\"\n    POOLER_TYPE: \"ROIAlign\"\n    NUM_COARSE_SEGM_CHANNELS: 2\nDATASETS:\n  TRAIN: (\"densepose_coco_2014_train\", \"densepose_coco_2014_valminusminival\")\n  TEST: (\"densepose_coco_2014_minival\",)\nSOLVER:\n  IMS_PER_BATCH: 16\n  BASE_LR: 0.01\n  STEPS: (60000, 80000)\n  MAX_ITER: 90000\n  WARMUP_FACTOR: 0.1\nINPUT:\n  MIN_SIZE_TRAIN: (640, 672, 704, 736, 768, 800)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/HRNet/densepose_rcnn_HRFPN_HRNet_w32_s1x.yaml",
    "content": "_BASE_: \"../Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"https://1drv.ms/u/s!Aus8VCZ_C_33dYBMemi9xOUFR0w\"\n  BACKBONE:\n    NAME: \"build_hrfpn_backbone\"\n  RPN:\n    IN_FEATURES: ['p1', 'p2', 'p3', 'p4', 'p5']\n  ROI_HEADS:\n    IN_FEATURES: ['p1', 'p2', 'p3', 'p4', 'p5']\nSOLVER:\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n  CLIP_GRADIENTS:\n    ENABLED: True\n    CLIP_TYPE: \"norm\"\n  BASE_LR: 0.03\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/HRNet/densepose_rcnn_HRFPN_HRNet_w40_s1x.yaml",
    "content": "_BASE_: \"../Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"https://1drv.ms/u/s!Aus8VCZ_C_33ck0gvo5jfoWBOPo\"\n  BACKBONE:\n    NAME: \"build_hrfpn_backbone\"\n  RPN:\n    IN_FEATURES: ['p1', 'p2', 'p3', 'p4', 'p5']\n  ROI_HEADS:\n    IN_FEATURES: ['p1', 'p2', 'p3', 'p4', 'p5']\n  HRNET:\n    STAGE2:\n      NUM_CHANNELS: [40, 80]\n    STAGE3:\n      NUM_CHANNELS: [40, 80, 160]\n    STAGE4:\n      NUM_CHANNELS: [40, 80, 160, 320]\nSOLVER:\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n  CLIP_GRADIENTS:\n    ENABLED: True\n    CLIP_TYPE: \"norm\"\n  BASE_LR: 0.03\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/HRNet/densepose_rcnn_HRFPN_HRNet_w48_s1x.yaml",
    "content": "_BASE_: \"../Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"https://1drv.ms/u/s!Aus8VCZ_C_33dKvqI6pBZlifgJk\"\n  BACKBONE:\n    NAME: \"build_hrfpn_backbone\"\n  RPN:\n    IN_FEATURES: ['p1', 'p2', 'p3', 'p4', 'p5']\n  ROI_HEADS:\n    IN_FEATURES: ['p1', 'p2', 'p3', 'p4', 'p5']\n  HRNET:\n    STAGE2:\n      NUM_CHANNELS: [48, 96]\n    STAGE3:\n      NUM_CHANNELS: [48, 96, 192]\n    STAGE4:\n      NUM_CHANNELS: [48, 96, 192, 384]\nSOLVER:\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n  CLIP_GRADIENTS:\n    ENABLED: True\n    CLIP_TYPE: \"norm\"\n  BASE_LR: 0.03\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/cse/Base-DensePose-RCNN-FPN-Human.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  ROI_DENSEPOSE_HEAD:\n    CSE:\n      EMBEDDERS:\n        \"smpl_27554\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 27554\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_smpl_27554_256.pkl\"\nDATASETS:\n  TRAIN:\n    - \"densepose_coco_2014_train_cse\"\n    - \"densepose_coco_2014_valminusminival_cse\"\n  TEST:\n    - \"densepose_coco_2014_minival_cse\"\n  CLASS_TO_MESH_NAME_MAPPING:\n    \"0\": \"smpl_27554\"\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/cse/Base-DensePose-RCNN-FPN.yaml",
    "content": "VERSION: 2\nMODEL:\n  META_ARCHITECTURE: \"GeneralizedRCNN\"\n  BACKBONE:\n    NAME: \"build_resnet_fpn_backbone\"\n  RESNETS:\n    OUT_FEATURES: [\"res2\", \"res3\", \"res4\", \"res5\"]\n  FPN:\n    IN_FEATURES: [\"res2\", \"res3\", \"res4\", \"res5\"]\n  ANCHOR_GENERATOR:\n    SIZES: [[32], [64], [128], [256], [512]]  # One size for each in feature map\n    ASPECT_RATIOS: [[0.5, 1.0, 2.0]]  # Three aspect ratios (same for all in feature maps)\n  RPN:\n    IN_FEATURES: [\"p2\", \"p3\", \"p4\", \"p5\", \"p6\"]\n    PRE_NMS_TOPK_TRAIN: 2000  # Per FPN level\n    PRE_NMS_TOPK_TEST: 1000  # Per FPN level\n    # Detectron1 uses 2000 proposals per-batch,\n    # (See \"modeling/rpn/rpn_outputs.py\" for details of this legacy issue)\n    # which is approximately 1000 proposals per-image since the default batch size for FPN is 2.\n    POST_NMS_TOPK_TRAIN: 1000\n    POST_NMS_TOPK_TEST: 1000\n\n  DENSEPOSE_ON: True\n  ROI_HEADS:\n    NAME: \"DensePoseROIHeads\"\n    IN_FEATURES: [\"p2\", \"p3\", \"p4\", \"p5\"]\n    NUM_CLASSES: 1\n  ROI_BOX_HEAD:\n    NAME: \"FastRCNNConvFCHead\"\n    NUM_FC: 2\n    POOLER_RESOLUTION: 7\n    POOLER_SAMPLING_RATIO: 2\n    POOLER_TYPE: \"ROIAlign\"\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseV1ConvXHead\"\n    POOLER_TYPE: \"ROIAlign\"\n    NUM_COARSE_SEGM_CHANNELS: 2\n    PREDICTOR_NAME: \"DensePoseEmbeddingPredictor\"\n    LOSS_NAME: \"DensePoseCseLoss\"\n    CSE:\n      # embedding loss, possible values:\n      # - \"EmbeddingLoss\"\n      # - \"SoftEmbeddingLoss\"\n      EMBED_LOSS_NAME: \"EmbeddingLoss\"\nSOLVER:\n  IMS_PER_BATCH: 16\n  BASE_LR: 0.01\n  STEPS: (60000, 80000)\n  MAX_ITER: 90000\n  WARMUP_FACTOR: 0.1\n  CLIP_GRADIENTS:\n    CLIP_TYPE: norm\n    CLIP_VALUE: 1.0\n    ENABLED: true\n    NORM_TYPE: 2.0\nINPUT:\n  MIN_SIZE_TRAIN: (640, 672, 704, 736, 768, 800)\nDENSEPOSE_EVALUATION:\n  TYPE: cse\n  STORAGE: file\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/cse/densepose_rcnn_R_101_FPN_DL_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN-Human.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  RESNETS:\n    DEPTH: 101\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\n    CSE:\n      EMBED_LOSS_NAME: \"EmbeddingLoss\"\nSOLVER:\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/cse/densepose_rcnn_R_101_FPN_DL_soft_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN-Human.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  RESNETS:\n    DEPTH: 101\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\n    CSE:\n      EMBED_LOSS_NAME: \"SoftEmbeddingLoss\"\nSOLVER:\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/cse/densepose_rcnn_R_101_FPN_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN-Human.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  RESNETS:\n    DEPTH: 101\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseV1ConvXHead\"\n    CSE:\n      EMBED_LOSS_NAME: \"EmbeddingLoss\"\nSOLVER:\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/cse/densepose_rcnn_R_101_FPN_soft_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN-Human.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  RESNETS:\n    DEPTH: 101\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseV1ConvXHead\"\n    CSE:\n      EMBED_LOSS_NAME: \"SoftEmbeddingLoss\"\nSOLVER:\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/cse/densepose_rcnn_R_50_FPN_DL_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN-Human.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\n    CSE:\n      EMBED_LOSS_NAME: \"EmbeddingLoss\"\nSOLVER:\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/cse/densepose_rcnn_R_50_FPN_DL_soft_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN-Human.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\n    CSE:\n      EMBED_LOSS_NAME: \"SoftEmbeddingLoss\"\nSOLVER:\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/cse/densepose_rcnn_R_50_FPN_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN-Human.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseV1ConvXHead\"\n    CSE:\n      EMBED_LOSS_NAME: \"EmbeddingLoss\"\nSOLVER:\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/cse/densepose_rcnn_R_50_FPN_soft_animals_CA_finetune_16k.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_s1x/250533982/model_final_2c4512.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    NUM_CLASSES: 1\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseV1ConvXHead\"\n    COARSE_SEGM_TRAINED_BY_MASKS: True\n    CSE:\n      EMBED_LOSS_NAME: \"SoftEmbeddingLoss\"\n      EMBEDDING_DIST_GAUSS_SIGMA: 0.1\n      GEODESIC_DIST_GAUSS_SIGMA: 0.1\n      EMBEDDERS:\n        \"cat_7466\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 7466\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_cat_7466_256.pkl\"\n        \"dog_7466\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 7466\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_dog_7466_256.pkl\"\n        \"sheep_5004\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5004\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_sheep_5004_256.pkl\"\n        \"horse_5004\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5004\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_horse_5004_256.pkl\"\n        \"zebra_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_zebra_5002_256.pkl\"\n        \"giraffe_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_giraffe_5002_256.pkl\"\n        \"elephant_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_elephant_5002_256.pkl\"\n        \"cow_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_cow_5002_256.pkl\"\n        \"bear_4936\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 4936\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_bear_4936_256.pkl\"\nDATASETS:\n  TRAIN:\n    - \"densepose_lvis_v1_ds2_train_v1\"\n  TEST:\n    - \"densepose_lvis_v1_ds2_val_v1\"\n  WHITELISTED_CATEGORIES:\n    \"densepose_lvis_v1_ds2_train_v1\":\n      - 943  # sheep\n      - 1202 # zebra\n      - 569  # horse\n      - 496  # giraffe\n      - 422  # elephant\n      - 80   # cow\n      - 76   # bear\n      - 225  # cat\n      - 378  # dog\n    \"densepose_lvis_v1_ds2_val_v1\":\n      - 943  # sheep\n      - 1202 # zebra\n      - 569  # horse\n      - 496  # giraffe\n      - 422  # elephant\n      - 80   # cow\n      - 76   # bear\n      - 225  # cat\n      - 378  # dog\n  CATEGORY_MAPS:\n    \"densepose_lvis_v1_ds2_train_v1\":\n      \"1202\": 943 # zebra -> sheep\n      \"569\": 943  # horse -> sheep\n      \"496\": 943  # giraffe -> sheep\n      \"422\": 943  # elephant -> sheep\n      \"80\": 943   # cow -> sheep\n      \"76\": 943   # bear -> sheep\n      \"225\": 943  # cat -> sheep\n      \"378\": 943  # dog -> sheep\n    \"densepose_lvis_v1_ds2_val_v1\":\n      \"1202\": 943 # zebra -> sheep\n      \"569\": 943  # horse -> sheep\n      \"496\": 943  # giraffe -> sheep\n      \"422\": 943  # elephant -> sheep\n      \"80\": 943   # cow -> sheep\n      \"76\": 943   # bear -> sheep\n      \"225\": 943  # cat -> sheep\n      \"378\": 943  # dog -> sheep\n  CLASS_TO_MESH_NAME_MAPPING:\n    # Note: different classes are mapped to a single class\n    # mesh is chosen based on GT data, so this is just some\n    # value which has no particular meaning\n    \"0\": \"sheep_5004\"\nSOLVER:\n  MAX_ITER: 16000\n  STEPS: (12000, 14000)\nDENSEPOSE_EVALUATION:\n  EVALUATE_MESH_ALIGNMENT: True\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/cse/densepose_rcnn_R_50_FPN_soft_animals_CA_finetune_4k.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_s1x/250533982/model_final_2c4512.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    NUM_CLASSES: 1\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseV1ConvXHead\"\n    COARSE_SEGM_TRAINED_BY_MASKS: True\n    CSE:\n      EMBED_LOSS_NAME: \"SoftEmbeddingLoss\"\n      EMBEDDING_DIST_GAUSS_SIGMA: 0.1\n      GEODESIC_DIST_GAUSS_SIGMA: 0.1\n      EMBEDDERS:\n        \"cat_5001\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5001\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_cat_5001_256.pkl\"\n        \"dog_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_dog_5002_256.pkl\"\n        \"sheep_5004\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5004\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_sheep_5004_256.pkl\"\n        \"horse_5004\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5004\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_horse_5004_256.pkl\"\n        \"zebra_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_zebra_5002_256.pkl\"\n        \"giraffe_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_giraffe_5002_256.pkl\"\n        \"elephant_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_elephant_5002_256.pkl\"\n        \"cow_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_cow_5002_256.pkl\"\n        \"bear_4936\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 4936\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_bear_4936_256.pkl\"\nDATASETS:\n  TRAIN:\n    - \"densepose_lvis_v1_ds1_train_v1\"\n  TEST:\n    - \"densepose_lvis_v1_ds1_val_v1\"\n  WHITELISTED_CATEGORIES:\n    \"densepose_lvis_v1_ds1_train_v1\":\n      - 943  # sheep\n      - 1202 # zebra\n      - 569  # horse\n      - 496  # giraffe\n      - 422  # elephant\n      - 80   # cow\n      - 76   # bear\n      - 225  # cat\n      - 378  # dog\n    \"densepose_lvis_v1_ds1_val_v1\":\n      - 943  # sheep\n      - 1202 # zebra\n      - 569  # horse\n      - 496  # giraffe\n      - 422  # elephant\n      - 80   # cow\n      - 76   # bear\n      - 225  # cat\n      - 378  # dog\n  CATEGORY_MAPS:\n    \"densepose_lvis_v1_ds1_train_v1\":\n      \"1202\": 943 # zebra -> sheep\n      \"569\": 943  # horse -> sheep\n      \"496\": 943  # giraffe -> sheep\n      \"422\": 943  # elephant -> sheep\n      \"80\": 943   # cow -> sheep\n      \"76\": 943   # bear -> sheep\n      \"225\": 943  # cat -> sheep\n      \"378\": 943  # dog -> sheep\n    \"densepose_lvis_v1_ds1_val_v1\":\n      \"1202\": 943 # zebra -> sheep\n      \"569\": 943  # horse -> sheep\n      \"496\": 943  # giraffe -> sheep\n      \"422\": 943  # elephant -> sheep\n      \"80\": 943   # cow -> sheep\n      \"76\": 943   # bear -> sheep\n      \"225\": 943  # cat -> sheep\n      \"378\": 943  # dog -> sheep\n  CLASS_TO_MESH_NAME_MAPPING:\n    # Note: different classes are mapped to a single class\n    # mesh is chosen based on GT data, so this is just some\n    # value which has no particular meaning\n    \"0\": \"sheep_5004\"\nSOLVER:\n  MAX_ITER: 4000\n  STEPS: (3000, 3500)\nDENSEPOSE_EVALUATION:\n  EVALUATE_MESH_ALIGNMENT: True\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/cse/densepose_rcnn_R_50_FPN_soft_animals_I0_finetune_16k.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_animals_finetune_maskonly_24k/270668502/model_final_21b1d2.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    NUM_CLASSES: 9\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseV1ConvXHead\"\n    COARSE_SEGM_TRAINED_BY_MASKS: True\n    CSE:\n      EMBED_LOSS_NAME: \"SoftEmbeddingLoss\"\n      EMBEDDING_DIST_GAUSS_SIGMA: 0.1\n      GEODESIC_DIST_GAUSS_SIGMA: 0.1\n      EMBEDDERS:\n        \"cat_7466\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 7466\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_cat_7466_256.pkl\"\n        \"dog_7466\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 7466\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_dog_7466_256.pkl\"\n        \"sheep_5004\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5004\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_sheep_5004_256.pkl\"\n        \"horse_5004\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5004\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_horse_5004_256.pkl\"\n        \"zebra_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_zebra_5002_256.pkl\"\n        \"giraffe_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_giraffe_5002_256.pkl\"\n        \"elephant_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_elephant_5002_256.pkl\"\n        \"cow_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_cow_5002_256.pkl\"\n        \"bear_4936\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 4936\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_bear_4936_256.pkl\"\nDATASETS:\n  TRAIN:\n    - \"densepose_lvis_v1_ds2_train_v1\"\n  TEST:\n    - \"densepose_lvis_v1_ds2_val_v1\"\n  WHITELISTED_CATEGORIES:\n    \"densepose_lvis_v1_ds2_train_v1\":\n      - 943  # sheep\n      - 1202 # zebra\n      - 569  # horse\n      - 496  # giraffe\n      - 422  # elephant\n      - 80   # cow\n      - 76   # bear\n      - 225  # cat\n      - 378  # dog\n    \"densepose_lvis_v1_ds2_val_v1\":\n      - 943  # sheep\n      - 1202 # zebra\n      - 569  # horse\n      - 496  # giraffe\n      - 422  # elephant\n      - 80   # cow\n      - 76   # bear\n      - 225  # cat\n      - 378  # dog\n  CLASS_TO_MESH_NAME_MAPPING:\n    \"0\": \"bear_4936\"\n    \"1\": \"cow_5002\"\n    \"2\": \"cat_7466\"\n    \"3\": \"dog_7466\"\n    \"4\": \"elephant_5002\"\n    \"5\": \"giraffe_5002\"\n    \"6\": \"horse_5004\"\n    \"7\": \"sheep_5004\"\n    \"8\": \"zebra_5002\"\nSOLVER:\n  MAX_ITER: 16000\n  STEPS: (12000, 14000)\nDENSEPOSE_EVALUATION:\n  EVALUATE_MESH_ALIGNMENT: True\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/cse/densepose_rcnn_R_50_FPN_soft_animals_I0_finetune_i2m_16k.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_animals_finetune_maskonly_24k/270668502/model_final_21b1d2.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    NUM_CLASSES: 9\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseV1ConvXHead\"\n    COARSE_SEGM_TRAINED_BY_MASKS: True\n    CSE:\n      EMBED_LOSS_NAME: \"SoftEmbeddingLoss\"\n      EMBEDDING_DIST_GAUSS_SIGMA: 0.1\n      GEODESIC_DIST_GAUSS_SIGMA: 0.1\n      PIX_TO_SHAPE_CYCLE_LOSS:\n        ENABLED: True\n      EMBEDDERS:\n        \"cat_7466\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 7466\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_cat_7466_256.pkl\"\n        \"dog_7466\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 7466\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_dog_7466_256.pkl\"\n        \"sheep_5004\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5004\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_sheep_5004_256.pkl\"\n        \"horse_5004\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5004\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_horse_5004_256.pkl\"\n        \"zebra_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_zebra_5002_256.pkl\"\n        \"giraffe_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_giraffe_5002_256.pkl\"\n        \"elephant_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_elephant_5002_256.pkl\"\n        \"cow_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_cow_5002_256.pkl\"\n        \"bear_4936\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 4936\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_bear_4936_256.pkl\"\nDATASETS:\n  TRAIN:\n    - \"densepose_lvis_v1_ds2_train_v1\"\n  TEST:\n    - \"densepose_lvis_v1_ds2_val_v1\"\n  WHITELISTED_CATEGORIES:\n    \"densepose_lvis_v1_ds2_train_v1\":\n      - 943  # sheep\n      - 1202 # zebra\n      - 569  # horse\n      - 496  # giraffe\n      - 422  # elephant\n      - 80   # cow\n      - 76   # bear\n      - 225  # cat\n      - 378  # dog\n    \"densepose_lvis_v1_ds2_val_v1\":\n      - 943  # sheep\n      - 1202 # zebra\n      - 569  # horse\n      - 496  # giraffe\n      - 422  # elephant\n      - 80   # cow\n      - 76   # bear\n      - 225  # cat\n      - 378  # dog\n  CLASS_TO_MESH_NAME_MAPPING:\n    \"0\": \"bear_4936\"\n    \"1\": \"cow_5002\"\n    \"2\": \"cat_7466\"\n    \"3\": \"dog_7466\"\n    \"4\": \"elephant_5002\"\n    \"5\": \"giraffe_5002\"\n    \"6\": \"horse_5004\"\n    \"7\": \"sheep_5004\"\n    \"8\": \"zebra_5002\"\nSOLVER:\n  MAX_ITER: 16000\n  STEPS: (12000, 14000)\nDENSEPOSE_EVALUATION:\n  EVALUATE_MESH_ALIGNMENT: True\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/cse/densepose_rcnn_R_50_FPN_soft_animals_I0_finetune_m2m_16k.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_animals_finetune_maskonly_24k/267687159/model_final_354e61.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    NUM_CLASSES: 9\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseV1ConvXHead\"\n    COARSE_SEGM_TRAINED_BY_MASKS: True\n    CSE:\n      EMBED_LOSS_NAME: \"SoftEmbeddingLoss\"\n      EMBEDDING_DIST_GAUSS_SIGMA: 0.1\n      GEODESIC_DIST_GAUSS_SIGMA: 0.1\n      SHAPE_TO_SHAPE_CYCLE_LOSS:\n        ENABLED: True\n      EMBEDDERS:\n        \"cat_7466\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 7466\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_cat_7466_256.pkl\"\n        \"dog_7466\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 7466\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_dog_7466_256.pkl\"\n        \"sheep_5004\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5004\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_sheep_5004_256.pkl\"\n        \"horse_5004\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5004\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_horse_5004_256.pkl\"\n        \"zebra_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_zebra_5002_256.pkl\"\n        \"giraffe_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_giraffe_5002_256.pkl\"\n        \"elephant_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_elephant_5002_256.pkl\"\n        \"cow_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_cow_5002_256.pkl\"\n        \"bear_4936\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 4936\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_bear_4936_256.pkl\"\n        \"smpl_27554\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 27554\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_smpl_27554_256.pkl\"\nDATASETS:\n  TRAIN:\n    - \"densepose_lvis_v1_ds2_train_v1\"\n  TEST:\n    - \"densepose_lvis_v1_ds2_val_v1\"\n  WHITELISTED_CATEGORIES:\n    \"densepose_lvis_v1_ds2_train_v1\":\n      - 943  # sheep\n      - 1202 # zebra\n      - 569  # horse\n      - 496  # giraffe\n      - 422  # elephant\n      - 80   # cow\n      - 76   # bear\n      - 225  # cat\n      - 378  # dog\n    \"densepose_lvis_v1_ds2_val_v1\":\n      - 943  # sheep\n      - 1202 # zebra\n      - 569  # horse\n      - 496  # giraffe\n      - 422  # elephant\n      - 80   # cow\n      - 76   # bear\n      - 225  # cat\n      - 378  # dog\n  CLASS_TO_MESH_NAME_MAPPING:\n    \"0\": \"bear_4936\"\n    \"1\": \"cow_5002\"\n    \"2\": \"cat_7466\"\n    \"3\": \"dog_7466\"\n    \"4\": \"elephant_5002\"\n    \"5\": \"giraffe_5002\"\n    \"6\": \"horse_5004\"\n    \"7\": \"sheep_5004\"\n    \"8\": \"zebra_5002\"\nSOLVER:\n  MAX_ITER: 16000\n  STEPS: (12000, 14000)\nDENSEPOSE_EVALUATION:\n  EVALUATE_MESH_ALIGNMENT: True\n  MESH_ALIGNMENT_MESH_NAMES:\n    - bear_4936\n    - cow_5002\n    - cat_7466\n    - dog_7466\n    - elephant_5002\n    - giraffe_5002\n    - horse_5004\n    - sheep_5004\n    - zebra_5002\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/cse/densepose_rcnn_R_50_FPN_soft_animals_finetune_16k.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_s1x/250533982/model_final_2c4512.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    NUM_CLASSES: 9\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseV1ConvXHead\"\n    COARSE_SEGM_TRAINED_BY_MASKS: True\n    CSE:\n      EMBED_LOSS_NAME: \"SoftEmbeddingLoss\"\n      EMBEDDING_DIST_GAUSS_SIGMA: 0.1\n      GEODESIC_DIST_GAUSS_SIGMA: 0.1\n      EMBEDDERS:\n        \"cat_7466\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 7466\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_cat_7466_256.pkl\"\n        \"dog_7466\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 7466\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_dog_7466_256.pkl\"\n        \"sheep_5004\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5004\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_sheep_5004_256.pkl\"\n        \"horse_5004\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5004\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_horse_5004_256.pkl\"\n        \"zebra_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_zebra_5002_256.pkl\"\n        \"giraffe_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_giraffe_5002_256.pkl\"\n        \"elephant_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_elephant_5002_256.pkl\"\n        \"cow_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_cow_5002_256.pkl\"\n        \"bear_4936\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 4936\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_bear_4936_256.pkl\"\nDATASETS:\n  TRAIN:\n    - \"densepose_lvis_v1_ds2_train_v1\"\n  TEST:\n    - \"densepose_lvis_v1_ds2_val_v1\"\n  WHITELISTED_CATEGORIES:\n    \"densepose_lvis_v1_ds2_train_v1\":\n      - 943  # sheep\n      - 1202 # zebra\n      - 569  # horse\n      - 496  # giraffe\n      - 422  # elephant\n      - 80   # cow\n      - 76   # bear\n      - 225  # cat\n      - 378  # dog\n    \"densepose_lvis_v1_ds2_val_v1\":\n      - 943  # sheep\n      - 1202 # zebra\n      - 569  # horse\n      - 496  # giraffe\n      - 422  # elephant\n      - 80   # cow\n      - 76   # bear\n      - 225  # cat\n      - 378  # dog\n  CLASS_TO_MESH_NAME_MAPPING:\n    \"0\": \"bear_4936\"\n    \"1\": \"cow_5002\"\n    \"2\": \"cat_7466\"\n    \"3\": \"dog_7466\"\n    \"4\": \"elephant_5002\"\n    \"5\": \"giraffe_5002\"\n    \"6\": \"horse_5004\"\n    \"7\": \"sheep_5004\"\n    \"8\": \"zebra_5002\"\nSOLVER:\n  MAX_ITER: 16000\n  STEPS: (12000, 14000)\nDENSEPOSE_EVALUATION:\n  EVALUATE_MESH_ALIGNMENT: True\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/cse/densepose_rcnn_R_50_FPN_soft_animals_finetune_4k.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_s1x/250533982/model_final_2c4512.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    NUM_CLASSES: 9\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseV1ConvXHead\"\n    COARSE_SEGM_TRAINED_BY_MASKS: True\n    CSE:\n      EMBED_LOSS_NAME: \"SoftEmbeddingLoss\"\n      EMBEDDING_DIST_GAUSS_SIGMA: 0.1\n      GEODESIC_DIST_GAUSS_SIGMA: 0.1\n      EMBEDDERS:\n        \"cat_5001\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5001\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_cat_5001_256.pkl\"\n        \"dog_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_dog_5002_256.pkl\"\n        \"sheep_5004\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5004\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_sheep_5004_256.pkl\"\n        \"horse_5004\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5004\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_horse_5004_256.pkl\"\n        \"zebra_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_zebra_5002_256.pkl\"\n        \"giraffe_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_giraffe_5002_256.pkl\"\n        \"elephant_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_elephant_5002_256.pkl\"\n        \"cow_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_cow_5002_256.pkl\"\n        \"bear_4936\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 4936\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_bear_4936_256.pkl\"\nDATASETS:\n  TRAIN:\n    - \"densepose_lvis_v1_ds1_train_v1\"\n  TEST:\n    - \"densepose_lvis_v1_ds1_val_v1\"\n  WHITELISTED_CATEGORIES:\n    \"densepose_lvis_v1_ds1_train_v1\":\n      - 943  # sheep\n      - 1202 # zebra\n      - 569  # horse\n      - 496  # giraffe\n      - 422  # elephant\n      - 80   # cow\n      - 76   # bear\n      - 225  # cat\n      - 378  # dog\n    \"densepose_lvis_v1_ds1_val_v1\":\n      - 943  # sheep\n      - 1202 # zebra\n      - 569  # horse\n      - 496  # giraffe\n      - 422  # elephant\n      - 80   # cow\n      - 76   # bear\n      - 225  # cat\n      - 378  # dog\n  CLASS_TO_MESH_NAME_MAPPING:\n    \"0\": \"bear_4936\"\n    \"1\": \"cow_5002\"\n    \"2\": \"cat_5001\"\n    \"3\": \"dog_5002\"\n    \"4\": \"elephant_5002\"\n    \"5\": \"giraffe_5002\"\n    \"6\": \"horse_5004\"\n    \"7\": \"sheep_5004\"\n    \"8\": \"zebra_5002\"\nSOLVER:\n  MAX_ITER: 4000\n  STEPS: (3000, 3500)\nDENSEPOSE_EVALUATION:\n  EVALUATE_MESH_ALIGNMENT: True\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/cse/densepose_rcnn_R_50_FPN_soft_animals_finetune_maskonly_24k.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_s1x/250533982/model_final_2c4512.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    NUM_CLASSES: 9\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseV1ConvXHead\"\n    COARSE_SEGM_TRAINED_BY_MASKS: True\n    CSE:\n      EMBED_LOSS_NAME: \"SoftEmbeddingLoss\"\n      EMBED_LOSS_WEIGHT: 0.0\n      EMBEDDING_DIST_GAUSS_SIGMA: 0.1\n      GEODESIC_DIST_GAUSS_SIGMA: 0.1\n      EMBEDDERS:\n        \"cat_7466\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 7466\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_cat_7466_256.pkl\"\n        \"dog_7466\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 7466\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_dog_7466_256.pkl\"\n        \"sheep_5004\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5004\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_sheep_5004_256.pkl\"\n        \"horse_5004\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5004\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_horse_5004_256.pkl\"\n        \"zebra_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_zebra_5002_256.pkl\"\n        \"giraffe_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_giraffe_5002_256.pkl\"\n        \"elephant_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_elephant_5002_256.pkl\"\n        \"cow_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_cow_5002_256.pkl\"\n        \"bear_4936\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 4936\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_bear_4936_256.pkl\"\nDATASETS:\n  TRAIN:\n    - \"densepose_lvis_v1_ds2_train_v1\"\n  TEST:\n    - \"densepose_lvis_v1_ds2_val_v1\"\n  WHITELISTED_CATEGORIES:\n    \"densepose_lvis_v1_ds2_train_v1\":\n      - 943  # sheep\n      - 1202 # zebra\n      - 569  # horse\n      - 496  # giraffe\n      - 422  # elephant\n      - 80   # cow\n      - 76   # bear\n      - 225  # cat\n      - 378  # dog\n    \"densepose_lvis_v1_ds2_val_v1\":\n      - 943  # sheep\n      - 1202 # zebra\n      - 569  # horse\n      - 496  # giraffe\n      - 422  # elephant\n      - 80   # cow\n      - 76   # bear\n      - 225  # cat\n      - 378  # dog\n  CLASS_TO_MESH_NAME_MAPPING:\n    \"0\": \"bear_4936\"\n    \"1\": \"cow_5002\"\n    \"2\": \"cat_7466\"\n    \"3\": \"dog_7466\"\n    \"4\": \"elephant_5002\"\n    \"5\": \"giraffe_5002\"\n    \"6\": \"horse_5004\"\n    \"7\": \"sheep_5004\"\n    \"8\": \"zebra_5002\"\nSOLVER:\n  MAX_ITER: 24000\n  STEPS: (20000, 22000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/cse/densepose_rcnn_R_50_FPN_soft_chimps_finetune_4k.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_s1x/250533982/model_final_2c4512.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseV1ConvXHead\"\n    CSE:\n      EMBED_LOSS_NAME: \"SoftEmbeddingLoss\"\n      EMBEDDING_DIST_GAUSS_SIGMA: 0.1\n      GEODESIC_DIST_GAUSS_SIGMA: 0.1\n      EMBEDDERS:\n        \"chimp_5029\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5029\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_chimp_5029_256.pkl\"\nDATASETS:\n  TRAIN:\n    - \"densepose_chimps_cse_train\"\n  TEST:\n    - \"densepose_chimps_cse_val\"\n  CLASS_TO_MESH_NAME_MAPPING:\n    \"0\": \"chimp_5029\"\nSOLVER:\n  MAX_ITER: 4000\n  STEPS: (3000, 3500)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/cse/densepose_rcnn_R_50_FPN_soft_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN-Human.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseV1ConvXHead\"\n    CSE:\n      EMBED_LOSS_NAME: \"SoftEmbeddingLoss\"\nSOLVER:\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_101_FPN_DL_WC1M_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  RESNETS:\n    DEPTH: 101\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"iid_iso\"\n    SEGM_CONFIDENCE:\n      ENABLED: True\n    POINT_REGRESSION_WEIGHTS: 0.0005\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_101_FPN_DL_WC1_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  RESNETS:\n    DEPTH: 101\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"iid_iso\"\n    POINT_REGRESSION_WEIGHTS: 0.0005\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_101_FPN_DL_WC2M_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  RESNETS:\n    DEPTH: 101\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"indep_aniso\"\n    SEGM_CONFIDENCE:\n      ENABLED: True\n    POINT_REGRESSION_WEIGHTS: 0.0005\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_101_FPN_DL_WC2_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  RESNETS:\n    DEPTH: 101\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"indep_aniso\"\n    POINT_REGRESSION_WEIGHTS: 0.0005\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_101_FPN_DL_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  RESNETS:\n    DEPTH: 101\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\nSOLVER:\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_101_FPN_WC1M_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  RESNETS:\n    DEPTH: 101\n  ROI_DENSEPOSE_HEAD:\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"iid_iso\"\n    SEGM_CONFIDENCE:\n      ENABLED: True\n    POINT_REGRESSION_WEIGHTS: 0.0005\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n  WARMUP_FACTOR: 0.025\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_101_FPN_WC1_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  RESNETS:\n    DEPTH: 101\n  ROI_DENSEPOSE_HEAD:\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"iid_iso\"\n    POINT_REGRESSION_WEIGHTS: 0.0005\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n  WARMUP_FACTOR: 0.025\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_101_FPN_WC2M_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  RESNETS:\n    DEPTH: 101\n  ROI_DENSEPOSE_HEAD:\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"indep_aniso\"\n    SEGM_CONFIDENCE:\n      ENABLED: True\n    POINT_REGRESSION_WEIGHTS: 0.0005\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n  WARMUP_FACTOR: 0.025\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_101_FPN_WC2_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  RESNETS:\n    DEPTH: 101\n  ROI_DENSEPOSE_HEAD:\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"indep_aniso\"\n    POINT_REGRESSION_WEIGHTS: 0.0005\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n  WARMUP_FACTOR: 0.025\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_101_FPN_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  RESNETS:\n    DEPTH: 101\nSOLVER:\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_101_FPN_s1x_legacy.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  RESNETS:\n    DEPTH: 101\n  ROI_DENSEPOSE_HEAD:\n    NUM_COARSE_SEGM_CHANNELS: 15\n    POOLER_RESOLUTION: 14\n    HEATMAP_SIZE: 56\n    INDEX_WEIGHTS: 2.0\n    PART_WEIGHTS: 0.3\n    POINT_REGRESSION_WEIGHTS: 0.1\n    DECODER_ON: False\nSOLVER:\n  BASE_LR: 0.002\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_50_FPN_DL_WC1M_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"iid_iso\"\n    SEGM_CONFIDENCE:\n      ENABLED: True\n    POINT_REGRESSION_WEIGHTS: 0.0005\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_50_FPN_DL_WC1_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"iid_iso\"\n    POINT_REGRESSION_WEIGHTS: 0.0005\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_50_FPN_DL_WC2M_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"indep_aniso\"\n    SEGM_CONFIDENCE:\n      ENABLED: True\n    POINT_REGRESSION_WEIGHTS: 0.0005\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_50_FPN_DL_WC2_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"indep_aniso\"\n    POINT_REGRESSION_WEIGHTS: 0.0005\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_50_FPN_DL_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\nSOLVER:\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_50_FPN_WC1M_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_DENSEPOSE_HEAD:\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"iid_iso\"\n    SEGM_CONFIDENCE:\n      ENABLED: True\n    POINT_REGRESSION_WEIGHTS: 0.0005\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n    CLIP_TYPE: norm\n    CLIP_VALUE: 100.0\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n  WARMUP_FACTOR: 0.025\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_50_FPN_WC1_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_DENSEPOSE_HEAD:\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"iid_iso\"\n    POINT_REGRESSION_WEIGHTS: 0.0005\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n  WARMUP_FACTOR: 0.025\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_50_FPN_WC2M_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_DENSEPOSE_HEAD:\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"indep_aniso\"\n    SEGM_CONFIDENCE:\n      ENABLED: True\n    POINT_REGRESSION_WEIGHTS: 0.0005\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n  WARMUP_FACTOR: 0.025\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_50_FPN_WC2_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_DENSEPOSE_HEAD:\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"indep_aniso\"\n    POINT_REGRESSION_WEIGHTS: 0.0005\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n  WARMUP_FACTOR: 0.025\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_50_FPN_s1x.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\nSOLVER:\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/densepose_rcnn_R_50_FPN_s1x_legacy.yaml",
    "content": "_BASE_: \"Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_DENSEPOSE_HEAD:\n    NUM_COARSE_SEGM_CHANNELS: 15\n    POOLER_RESOLUTION: 14\n    HEATMAP_SIZE: 56\n    INDEX_WEIGHTS: 2.0\n    PART_WEIGHTS: 0.3\n    POINT_REGRESSION_WEIGHTS: 0.1\n    DECODER_ON: False\nSOLVER:\n  BASE_LR: 0.002\n  MAX_ITER: 130000\n  STEPS: (100000, 120000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/evolution/Base-RCNN-FPN-Atop10P_CA.yaml",
    "content": "MODEL:\n  META_ARCHITECTURE: \"GeneralizedRCNN\"\n  BACKBONE:\n    NAME: \"build_resnet_fpn_backbone\"\n  RESNETS:\n    OUT_FEATURES: [\"res2\", \"res3\", \"res4\", \"res5\"]\n  FPN:\n    IN_FEATURES: [\"res2\", \"res3\", \"res4\", \"res5\"]\n  ANCHOR_GENERATOR:\n    SIZES: [[32], [64], [128], [256], [512]]  # One size for each in feature map\n    ASPECT_RATIOS: [[0.5, 1.0, 2.0]]  # Three aspect ratios (same for all in feature maps)\n  RPN:\n    IN_FEATURES: [\"p2\", \"p3\", \"p4\", \"p5\", \"p6\"]\n    PRE_NMS_TOPK_TRAIN: 2000  # Per FPN level\n    PRE_NMS_TOPK_TEST: 1000  # Per FPN level\n    # Detectron1 uses 2000 proposals per-batch,\n    # (See \"modeling/rpn/rpn_outputs.py\" for details of this legacy issue)\n    # which is approximately 1000 proposals per-image since the default batch size for FPN is 2.\n    POST_NMS_TOPK_TRAIN: 1000\n    POST_NMS_TOPK_TEST: 1000\n  ROI_HEADS:\n    NAME: \"StandardROIHeads\"\n    IN_FEATURES: [\"p2\", \"p3\", \"p4\", \"p5\"]\n    NUM_CLASSES: 1\n  ROI_BOX_HEAD:\n    NAME: \"FastRCNNConvFCHead\"\n    NUM_FC: 2\n    POOLER_RESOLUTION: 7\n  ROI_MASK_HEAD:\n    NAME: \"MaskRCNNConvUpsampleHead\"\n    NUM_CONV: 4\n    POOLER_RESOLUTION: 14\nDATASETS:\n  TRAIN: (\"base_coco_2017_train\", \"densepose_coco_2014_train\")\n  TEST: (\"densepose_chimps\",)\n  CATEGORY_MAPS:\n    \"base_coco_2017_train\":\n      \"16\": 1 # bird -> person\n      \"17\": 1 # cat -> person\n      \"18\": 1 # dog -> person\n      \"19\": 1 # horse -> person\n      \"20\": 1 # sheep -> person\n      \"21\": 1 # cow -> person\n      \"22\": 1 # elephant -> person\n      \"23\": 1 # bear -> person\n      \"24\": 1 # zebra -> person\n      \"25\": 1 # girafe -> person\n    \"base_coco_2017_val\":\n      \"16\": 1 # bird -> person\n      \"17\": 1 # cat -> person\n      \"18\": 1 # dog -> person\n      \"19\": 1 # horse -> person\n      \"20\": 1 # sheep -> person\n      \"21\": 1 # cow -> person\n      \"22\": 1 # elephant -> person\n      \"23\": 1 # bear -> person\n      \"24\": 1 # zebra -> person\n      \"25\": 1 # girafe -> person\n  WHITELISTED_CATEGORIES:\n    \"base_coco_2017_train\":\n      - 1  # person\n      - 16 # bird\n      - 17 # cat\n      - 18 # dog\n      - 19 # horse\n      - 20 # sheep\n      - 21 # cow\n      - 22 # elephant\n      - 23 # bear\n      - 24 # zebra\n      - 25 # girafe\n    \"base_coco_2017_val\":\n      - 1  # person\n      - 16 # bird\n      - 17 # cat\n      - 18 # dog\n      - 19 # horse\n      - 20 # sheep\n      - 21 # cow\n      - 22 # elephant\n      - 23 # bear\n      - 24 # zebra\n      - 25 # girafe\nSOLVER:\n  IMS_PER_BATCH: 16\n  BASE_LR: 0.02\n  STEPS: (60000, 80000)\n  MAX_ITER: 90000\nINPUT:\n  MIN_SIZE_TRAIN: (640, 672, 704, 736, 768, 800)\nVERSION: 2\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA.yaml",
    "content": "_BASE_: \"Base-RCNN-FPN-Atop10P_CA.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  DENSEPOSE_ON: True\n  ROI_HEADS:\n    NAME: \"DensePoseROIHeads\"\n    IN_FEATURES: [\"p2\", \"p3\", \"p4\", \"p5\"]\n    NUM_CLASSES: 1\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"iid_iso\"\n    SEGM_CONFIDENCE:\n      ENABLED: True\n    POINT_REGRESSION_WEIGHTS: 0.0005\n    POOLER_TYPE: \"ROIAlign\"\n    NUM_COARSE_SEGM_CHANNELS: 2\n    COARSE_SEGM_TRAINED_BY_MASKS: True\n    INDEX_WEIGHTS: 1.0\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  WARMUP_FACTOR: 0.025\n  MAX_ITER: 270000\n  STEPS: (210000, 250000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_coarsesegm.yaml",
    "content": "_BASE_: \"Base-RCNN-FPN-Atop10P_CA.yaml\"\nMODEL:\n  WEIGHTS: https://dl.fbaipublicfiles.com/densepose/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA/217578784/model_final_9fe1cc.pkl\n  RESNETS:\n    DEPTH: 50\n  DENSEPOSE_ON: True\n  ROI_HEADS:\n    NAME: \"DensePoseROIHeads\"\n    IN_FEATURES: [\"p2\", \"p3\", \"p4\", \"p5\"]\n    NUM_CLASSES: 1\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"iid_iso\"\n    SEGM_CONFIDENCE:\n      ENABLED: True\n    POINT_REGRESSION_WEIGHTS: 0.0005\n    POOLER_TYPE: \"ROIAlign\"\n    NUM_COARSE_SEGM_CHANNELS: 2\n    COARSE_SEGM_TRAINED_BY_MASKS: True\nBOOTSTRAP_DATASETS:\n  - DATASET: \"chimpnsee\"\n    RATIO: 1.0\n    IMAGE_LOADER:\n      TYPE: \"video_keyframe\"\n      SELECT:\n        STRATEGY: \"random_k\"\n        NUM_IMAGES: 4\n      TRANSFORM:\n        TYPE: \"resize\"\n        MIN_SIZE: 800\n        MAX_SIZE: 1333\n      BATCH_SIZE: 8\n      NUM_WORKERS: 1\n    INFERENCE:\n      INPUT_BATCH_SIZE: 1\n      OUTPUT_BATCH_SIZE: 1\n    DATA_SAMPLER:\n      # supported types:\n      #   densepose_uniform\n      #   densepose_UV_confidence\n      #   densepose_fine_segm_confidence\n      #   densepose_coarse_segm_confidence\n      TYPE: \"densepose_coarse_segm_confidence\"\n      COUNT_PER_CLASS: 8\n    FILTER:\n      TYPE: \"detection_score\"\n      MIN_VALUE: 0.8\nBOOTSTRAP_MODEL:\n  WEIGHTS: https://dl.fbaipublicfiles.com/densepose/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA/217578784/model_final_9fe1cc.pkl\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 270000\n  STEPS: (210000, 250000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_finesegm.yaml",
    "content": "_BASE_: \"Base-RCNN-FPN-Atop10P_CA.yaml\"\nMODEL:\n  WEIGHTS: https://dl.fbaipublicfiles.com/densepose/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA/217578784/model_final_9fe1cc.pkl\n  RESNETS:\n    DEPTH: 50\n  DENSEPOSE_ON: True\n  ROI_HEADS:\n    NAME: \"DensePoseROIHeads\"\n    IN_FEATURES: [\"p2\", \"p3\", \"p4\", \"p5\"]\n    NUM_CLASSES: 1\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"iid_iso\"\n    SEGM_CONFIDENCE:\n      ENABLED: True\n    POINT_REGRESSION_WEIGHTS: 0.0005\n    POOLER_TYPE: \"ROIAlign\"\n    NUM_COARSE_SEGM_CHANNELS: 2\n    COARSE_SEGM_TRAINED_BY_MASKS: True\nBOOTSTRAP_DATASETS:\n  - DATASET: \"chimpnsee\"\n    RATIO: 1.0\n    IMAGE_LOADER:\n      TYPE: \"video_keyframe\"\n      SELECT:\n        STRATEGY: \"random_k\"\n        NUM_IMAGES: 4\n      TRANSFORM:\n        TYPE: \"resize\"\n        MIN_SIZE: 800\n        MAX_SIZE: 1333\n      BATCH_SIZE: 8\n      NUM_WORKERS: 1\n    INFERENCE:\n      INPUT_BATCH_SIZE: 1\n      OUTPUT_BATCH_SIZE: 1\n    DATA_SAMPLER:\n      # supported types:\n      #   densepose_uniform\n      #   densepose_UV_confidence\n      #   densepose_fine_segm_confidence\n      #   densepose_coarse_segm_confidence\n      TYPE: \"densepose_fine_segm_confidence\"\n      COUNT_PER_CLASS: 8\n    FILTER:\n      TYPE: \"detection_score\"\n      MIN_VALUE: 0.8\nBOOTSTRAP_MODEL:\n  WEIGHTS: https://dl.fbaipublicfiles.com/densepose/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA/217578784/model_final_9fe1cc.pkl\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 270000\n  STEPS: (210000, 250000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_uniform.yaml",
    "content": "_BASE_: \"Base-RCNN-FPN-Atop10P_CA.yaml\"\nMODEL:\n  WEIGHTS: https://dl.fbaipublicfiles.com/densepose/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA/217578784/model_final_9fe1cc.pkl\n  RESNETS:\n    DEPTH: 50\n  DENSEPOSE_ON: True\n  ROI_HEADS:\n    NAME: \"DensePoseROIHeads\"\n    IN_FEATURES: [\"p2\", \"p3\", \"p4\", \"p5\"]\n    NUM_CLASSES: 1\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"iid_iso\"\n    SEGM_CONFIDENCE:\n      ENABLED: True\n    POINT_REGRESSION_WEIGHTS: 0.0005\n    POOLER_TYPE: \"ROIAlign\"\n    NUM_COARSE_SEGM_CHANNELS: 2\n    COARSE_SEGM_TRAINED_BY_MASKS: True\nBOOTSTRAP_DATASETS:\n  - DATASET: \"chimpnsee\"\n    RATIO: 1.0\n    IMAGE_LOADER:\n      TYPE: \"video_keyframe\"\n      SELECT:\n        STRATEGY: \"random_k\"\n        NUM_IMAGES: 4\n      TRANSFORM:\n        TYPE: \"resize\"\n        MIN_SIZE: 800\n        MAX_SIZE: 1333\n      BATCH_SIZE: 8\n      NUM_WORKERS: 1\n    INFERENCE:\n      INPUT_BATCH_SIZE: 1\n      OUTPUT_BATCH_SIZE: 1\n    DATA_SAMPLER:\n      # supported types:\n      #   densepose_uniform\n      #   densepose_UV_confidence\n      #   densepose_fine_segm_confidence\n      #   densepose_coarse_segm_confidence\n      TYPE: \"densepose_uniform\"\n      COUNT_PER_CLASS: 8\n    FILTER:\n      TYPE: \"detection_score\"\n      MIN_VALUE: 0.8\nBOOTSTRAP_MODEL:\n  WEIGHTS: https://dl.fbaipublicfiles.com/densepose/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA/217578784/model_final_9fe1cc.pkl\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 270000\n  STEPS: (210000, 250000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_uv.yaml",
    "content": "_BASE_: \"Base-RCNN-FPN-Atop10P_CA.yaml\"\nMODEL:\n  WEIGHTS: https://dl.fbaipublicfiles.com/densepose/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA/217578784/model_final_9fe1cc.pkl\n  RESNETS:\n    DEPTH: 50\n  DENSEPOSE_ON: True\n  ROI_HEADS:\n    NAME: \"DensePoseROIHeads\"\n    IN_FEATURES: [\"p2\", \"p3\", \"p4\", \"p5\"]\n    NUM_CLASSES: 1\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"iid_iso\"\n    SEGM_CONFIDENCE:\n      ENABLED: True\n    POINT_REGRESSION_WEIGHTS: 0.0005\n    POOLER_TYPE: \"ROIAlign\"\n    NUM_COARSE_SEGM_CHANNELS: 2\n    COARSE_SEGM_TRAINED_BY_MASKS: True\nBOOTSTRAP_DATASETS:\n  - DATASET: \"chimpnsee\"\n    RATIO: 1.0\n    IMAGE_LOADER:\n      TYPE: \"video_keyframe\"\n      SELECT:\n        STRATEGY: \"random_k\"\n        NUM_IMAGES: 4\n      TRANSFORM:\n        TYPE: \"resize\"\n        MIN_SIZE: 800\n        MAX_SIZE: 1333\n      BATCH_SIZE: 8\n      NUM_WORKERS: 1\n    INFERENCE:\n      INPUT_BATCH_SIZE: 1\n      OUTPUT_BATCH_SIZE: 1\n    DATA_SAMPLER:\n      # supported types:\n      #   densepose_uniform\n      #   densepose_UV_confidence\n      #   densepose_fine_segm_confidence\n      #   densepose_coarse_segm_confidence\n      TYPE: \"densepose_UV_confidence\"\n      COUNT_PER_CLASS: 8\n    FILTER:\n      TYPE: \"detection_score\"\n      MIN_VALUE: 0.8\nBOOTSTRAP_MODEL:\n  WEIGHTS: https://dl.fbaipublicfiles.com/densepose/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA/217578784/model_final_9fe1cc.pkl\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 270000\n  STEPS: (210000, 250000)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/quick_schedules/cse/densepose_rcnn_R_50_FPN_DL_instant_test.yaml",
    "content": "_BASE_: \"../../cse/Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\nDATASETS:\n  TRAIN: (\"densepose_coco_2014_minival_100_cse\",)\n  TEST: (\"densepose_coco_2014_minival_100_cse\",)\nSOLVER:\n  MAX_ITER: 40\n  STEPS: (30,)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/quick_schedules/cse/densepose_rcnn_R_50_FPN_soft_animals_finetune_instant_test.yaml",
    "content": "_BASE_: \"../../cse/Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    NUM_CLASSES: 9\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseV1ConvXHead\"\n    CSE:\n      EMBED_LOSS_NAME: \"SoftEmbeddingLoss\"\n      EMBEDDING_DIST_GAUSS_SIGMA: 0.1\n      EMBEDDERS:\n        \"cat_5001\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5001\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_cat_5001_256.pkl\"\n        \"dog_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_dog_5002_256.pkl\"\n        \"sheep_5004\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5004\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_sheep_5004_256.pkl\"\n        \"horse_5004\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5004\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_horse_5004_256.pkl\"\n        \"zebra_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_zebra_5002_256.pkl\"\n        \"giraffe_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_giraffe_5002_256.pkl\"\n        \"elephant_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_elephant_5002_256.pkl\"\n        \"cow_5002\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 5002\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_cow_5002_256.pkl\"\n        \"bear_4936\":\n          TYPE: vertex_feature\n          NUM_VERTICES: 4936\n          FEATURE_DIM: 256\n          FEATURES_TRAINABLE: False\n          IS_TRAINABLE: True\n          INIT_FILE: \"https://dl.fbaipublicfiles.com/densepose/data/cse/lbo/phi_bear_4936_256.pkl\"\nDATASETS:\n  TRAIN:\n    - \"densepose_lvis_v1_train1\"\n    - \"densepose_lvis_v1_train2\"\n  TEST:\n    - \"densepose_lvis_v1_val_animals_100\"\n  WHITELISTED_CATEGORIES:\n    \"densepose_lvis_v1_train1\":\n      - 943  # sheep\n      - 1202 # zebra\n      - 569  # horse\n      - 496  # giraffe\n      - 422  # elephant\n      - 80   # cow\n      - 76   # bear\n      - 225  # cat\n      - 378  # dog\n    \"densepose_lvis_v1_train2\":\n      - 943  # sheep\n      - 1202 # zebra\n      - 569  # horse\n      - 496  # giraffe\n      - 422  # elephant\n      - 80   # cow\n      - 76   # bear\n      - 225  # cat\n      - 378  # dog\n    \"densepose_lvis_v1_val_animals_100\":\n      - 943  # sheep\n      - 1202 # zebra\n      - 569  # horse\n      - 496  # giraffe\n      - 422  # elephant\n      - 80   # cow\n      - 76   # bear\n      - 225  # cat\n      - 378  # dog\n  CLASS_TO_MESH_NAME_MAPPING:\n    \"0\": \"bear_4936\"\n    \"1\": \"cow_5002\"\n    \"2\": \"cat_5001\"\n    \"3\": \"dog_5002\"\n    \"4\": \"elephant_5002\"\n    \"5\": \"giraffe_5002\"\n    \"6\": \"horse_5004\"\n    \"7\": \"sheep_5004\"\n    \"8\": \"zebra_5002\"\nSOLVER:\n  MAX_ITER: 40\n  STEPS: (30,)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/quick_schedules/densepose_rcnn_HRFPN_HRNet_w32_instant_test.yaml",
    "content": "_BASE_: \"../HRNet/densepose_rcnn_HRFPN_HRNet_w32_s1x.yaml\"\nDATASETS:\n  TRAIN: (\"densepose_coco_2014_minival_100\",)\n  TEST: (\"densepose_coco_2014_minival_100\",)\nSOLVER:\n  MAX_ITER: 40\n  STEPS: (30,)\n  IMS_PER_BATCH: 2\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/quick_schedules/densepose_rcnn_R_50_FPN_DL_instant_test.yaml",
    "content": "_BASE_: \"../Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  ROI_DENSEPOSE_HEAD:\n    NAME: \"DensePoseDeepLabHead\"\nDATASETS:\n  TRAIN: (\"densepose_coco_2014_minival_100\",)\n  TEST: (\"densepose_coco_2014_minival_100\",)\nSOLVER:\n  MAX_ITER: 40\n  STEPS: (30,)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/quick_schedules/densepose_rcnn_R_50_FPN_TTA_inference_acc_test.yaml",
    "content": "_BASE_: \"../densepose_rcnn_R_50_FPN_s1x.yaml\"\nMODEL:\n  WEIGHTS: \"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_s1x/165712039/model_final_162be9.pkl\"\nDATASETS:\n  TRAIN: ()\n  TEST: (\"densepose_coco_2014_minival_100\",)\nTEST:\n  AUG:\n    ENABLED: True\n    MIN_SIZES: (400, 500, 600, 700, 800, 900, 1000, 1100, 1200)\n    MAX_SIZE: 4000\n    FLIP: True\n  EXPECTED_RESULTS: [[\"bbox_TTA\", \"AP\", 61.74, 0.03], [\"densepose_gps_TTA\", \"AP\",  60.22, 0.03], [\"densepose_gpsm_TTA\", \"AP\", 63.59, 0.03]]\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/quick_schedules/densepose_rcnn_R_50_FPN_WC1_instant_test.yaml",
    "content": "_BASE_: \"../Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_DENSEPOSE_HEAD:\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"iid_iso\"\n    POINT_REGRESSION_WEIGHTS: 0.0005\nDATASETS:\n  TRAIN: (\"densepose_coco_2014_minival_100\",)\n  TEST: (\"densepose_coco_2014_minival_100\",)\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 40\n  STEPS: (30,)\n  WARMUP_FACTOR: 0.025\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/quick_schedules/densepose_rcnn_R_50_FPN_WC2_instant_test.yaml",
    "content": "_BASE_: \"../Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n  ROI_DENSEPOSE_HEAD:\n    UV_CONFIDENCE:\n      ENABLED: True\n      TYPE: \"indep_aniso\"\n    POINT_REGRESSION_WEIGHTS: 0.0005\nDATASETS:\n  TRAIN: (\"densepose_coco_2014_minival_100\",)\n  TEST: (\"densepose_coco_2014_minival_100\",)\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n  MAX_ITER: 40 \n  STEPS: (30,)\n  WARMUP_FACTOR: 0.025\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/quick_schedules/densepose_rcnn_R_50_FPN_inference_acc_test.yaml",
    "content": "_BASE_: \"../densepose_rcnn_R_50_FPN_s1x.yaml\"\nMODEL:\n  WEIGHTS: \"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_s1x/165712039/model_final_162be9.pkl\"\nDATASETS:\n  TRAIN: ()\n  TEST: (\"densepose_coco_2014_minival_100\",)\nTEST:\n  EXPECTED_RESULTS: [[\"bbox\", \"AP\", 59.27, 0.025], [\"densepose_gps\", \"AP\",  60.11, 0.02], [\"densepose_gpsm\", \"AP\", 64.09, 0.02]]\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/quick_schedules/densepose_rcnn_R_50_FPN_instant_test.yaml",
    "content": "_BASE_: \"../Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\nDATASETS:\n  TRAIN: (\"densepose_coco_2014_minival_100\",)\n  TEST: (\"densepose_coco_2014_minival_100\",)\nSOLVER:\n  MAX_ITER: 40\n  STEPS: (30,)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/configs/quick_schedules/densepose_rcnn_R_50_FPN_training_acc_test.yaml",
    "content": "_BASE_: \"../Base-DensePose-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  ROI_HEADS:\n    NUM_CLASSES: 1\nDATASETS:\n  TRAIN: (\"densepose_coco_2014_minival\",)\n  TEST: (\"densepose_coco_2014_minival\",)\nSOLVER:\n  CLIP_GRADIENTS:\n    ENABLED: True\n    CLIP_TYPE: norm\n    CLIP_VALUE: 1.0\n  MAX_ITER: 6000\n  STEPS: (5500, 5800)\nTEST:\n  EXPECTED_RESULTS: [[\"bbox\", \"AP\", 76.2477, 1.0], [\"densepose_gps\", \"AP\", 79.6090, 1.5], [\"densepose_gpsm\", \"AP\", 80.0061, 1.5]]\n\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom .data.datasets import builtin  # just to register data\nfrom .converters import builtin as builtin_converters  # register converters\nfrom .config import (\n    add_densepose_config,\n    add_densepose_head_config,\n    add_hrnet_config,\n    add_dataset_category_config,\n    add_bootstrap_config,\n    load_bootstrap_config,\n)\nfrom .structures import DensePoseDataRelative, DensePoseList, DensePoseTransformData\nfrom .evaluation import DensePoseCOCOEvaluator\nfrom .modeling.roi_heads import DensePoseROIHeads\nfrom .modeling.test_time_augmentation import (\n    DensePoseGeneralizedRCNNWithTTA,\n    DensePoseDatasetMapperTTA,\n)\nfrom .utils.transform import load_from_cfg\nfrom .modeling.hrfpn import build_hrfpn_backbone\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/config.py",
    "content": "# -*- coding = utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n# pyre-ignore-all-errors\n\nfrom detectron2.config import CfgNode as CN\n\n\ndef add_dataset_category_config(cfg: CN):\n    \"\"\"\n    Add config for additional category-related dataset options\n     - category whitelisting\n     - category mapping\n    \"\"\"\n    _C = cfg\n    _C.DATASETS.CATEGORY_MAPS = CN(new_allowed=True)\n    _C.DATASETS.WHITELISTED_CATEGORIES = CN(new_allowed=True)\n    # class to mesh mapping\n    _C.DATASETS.CLASS_TO_MESH_NAME_MAPPING = CN(new_allowed=True)\n\n\ndef add_evaluation_config(cfg: CN):\n    _C = cfg\n    _C.DENSEPOSE_EVALUATION = CN()\n    # evaluator type, possible values:\n    #  - \"iou\": evaluator for models that produce iou data\n    #  - \"cse\": evaluator for models that produce cse data\n    _C.DENSEPOSE_EVALUATION.TYPE = \"iou\"\n    # storage for DensePose results, possible values:\n    #  - \"none\": no explicit storage, all the results are stored in the\n    #            dictionary with predictions, memory intensive;\n    #            historically the default storage type\n    #  - \"ram\": RAM storage, uses per-process RAM storage, which is\n    #           reduced to a single process storage on later stages,\n    #           less memory intensive\n    #  - \"file\": file storage, uses per-process file-based storage,\n    #            the least memory intensive, but may create bottlenecks\n    #            on file system accesses\n    _C.DENSEPOSE_EVALUATION.STORAGE = \"none\"\n    # minimum threshold for IOU values: the lower its values is,\n    # the more matches are produced (and the higher the AP score)\n    _C.DENSEPOSE_EVALUATION.MIN_IOU_THRESHOLD = 0.5\n    # Non-distributed inference is slower (at inference time) but can avoid RAM OOM\n    _C.DENSEPOSE_EVALUATION.DISTRIBUTED_INFERENCE = True\n    # evaluate mesh alignment based on vertex embeddings, only makes sense in CSE context\n    _C.DENSEPOSE_EVALUATION.EVALUATE_MESH_ALIGNMENT = False\n    # meshes to compute mesh alignment for\n    _C.DENSEPOSE_EVALUATION.MESH_ALIGNMENT_MESH_NAMES = []\n\n\ndef add_bootstrap_config(cfg: CN):\n    \"\"\" \"\"\"\n    _C = cfg\n    _C.BOOTSTRAP_DATASETS = []\n    _C.BOOTSTRAP_MODEL = CN()\n    _C.BOOTSTRAP_MODEL.WEIGHTS = \"\"\n    _C.BOOTSTRAP_MODEL.DEVICE = \"cuda\"\n\n\ndef get_bootstrap_dataset_config() -> CN:\n    _C = CN()\n    _C.DATASET = \"\"\n    # ratio used to mix data loaders\n    _C.RATIO = 0.1\n    # image loader\n    _C.IMAGE_LOADER = CN(new_allowed=True)\n    _C.IMAGE_LOADER.TYPE = \"\"\n    _C.IMAGE_LOADER.BATCH_SIZE = 4\n    _C.IMAGE_LOADER.NUM_WORKERS = 4\n    _C.IMAGE_LOADER.CATEGORIES = []\n    _C.IMAGE_LOADER.MAX_COUNT_PER_CATEGORY = 1_000_000\n    _C.IMAGE_LOADER.CATEGORY_TO_CLASS_MAPPING = CN(new_allowed=True)\n    # inference\n    _C.INFERENCE = CN()\n    # batch size for model inputs\n    _C.INFERENCE.INPUT_BATCH_SIZE = 4\n    # batch size to group model outputs\n    _C.INFERENCE.OUTPUT_BATCH_SIZE = 2\n    # sampled data\n    _C.DATA_SAMPLER = CN(new_allowed=True)\n    _C.DATA_SAMPLER.TYPE = \"\"\n    _C.DATA_SAMPLER.USE_GROUND_TRUTH_CATEGORIES = False\n    # filter\n    _C.FILTER = CN(new_allowed=True)\n    _C.FILTER.TYPE = \"\"\n    return _C\n\n\ndef load_bootstrap_config(cfg: CN):\n    \"\"\"\n    Bootstrap datasets are given as a list of `dict` that are not automatically\n    converted into CfgNode. This method processes all bootstrap dataset entries\n    and ensures that they are in CfgNode format and comply with the specification\n    \"\"\"\n    if not cfg.BOOTSTRAP_DATASETS:\n        return\n\n    bootstrap_datasets_cfgnodes = []\n    for dataset_cfg in cfg.BOOTSTRAP_DATASETS:\n        _C = get_bootstrap_dataset_config().clone()\n        _C.merge_from_other_cfg(CN(dataset_cfg))\n        bootstrap_datasets_cfgnodes.append(_C)\n    cfg.BOOTSTRAP_DATASETS = bootstrap_datasets_cfgnodes\n\n\ndef add_densepose_head_cse_config(cfg: CN):\n    \"\"\"\n    Add configuration options for Continuous Surface Embeddings (CSE)\n    \"\"\"\n    _C = cfg\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE = CN()\n    # Dimensionality D of the embedding space\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBED_SIZE = 16\n    # Embedder specifications for various mesh IDs\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBEDDERS = CN(new_allowed=True)\n    # normalization coefficient for embedding distances\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBEDDING_DIST_GAUSS_SIGMA = 0.01\n    # normalization coefficient for geodesic distances\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.GEODESIC_DIST_GAUSS_SIGMA = 0.01\n    # embedding loss weight\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBED_LOSS_WEIGHT = 0.6\n    # embedding loss name, currently the following options are supported:\n    # - EmbeddingLoss: cross-entropy on vertex labels\n    # - SoftEmbeddingLoss: cross-entropy on vertex label combined with\n    #    Gaussian penalty on distance between vertices\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBED_LOSS_NAME = \"EmbeddingLoss\"\n    # optimizer hyperparameters\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.FEATURES_LR_FACTOR = 1.0\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBEDDING_LR_FACTOR = 1.0\n    # Shape to shape cycle consistency loss parameters:\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.SHAPE_TO_SHAPE_CYCLE_LOSS = CN({\"ENABLED\": False})\n    # shape to shape cycle consistency loss weight\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.SHAPE_TO_SHAPE_CYCLE_LOSS.WEIGHT = 0.025\n    # norm type used for loss computation\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.SHAPE_TO_SHAPE_CYCLE_LOSS.NORM_P = 2\n    # normalization term for embedding similarity matrices\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.SHAPE_TO_SHAPE_CYCLE_LOSS.TEMPERATURE = 0.05\n    # maximum number of vertices to include into shape to shape cycle loss\n    # if negative or zero, all vertices are considered\n    # if positive, random subset of vertices of given size is considered\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.SHAPE_TO_SHAPE_CYCLE_LOSS.MAX_NUM_VERTICES = 4936\n    # Pixel to shape cycle consistency loss parameters:\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.PIX_TO_SHAPE_CYCLE_LOSS = CN({\"ENABLED\": False})\n    # pixel to shape cycle consistency loss weight\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.PIX_TO_SHAPE_CYCLE_LOSS.WEIGHT = 0.0001\n    # norm type used for loss computation\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.PIX_TO_SHAPE_CYCLE_LOSS.NORM_P = 2\n    # map images to all meshes and back (if false, use only gt meshes from the batch)\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.PIX_TO_SHAPE_CYCLE_LOSS.USE_ALL_MESHES_NOT_GT_ONLY = False\n    # Randomly select at most this number of pixels from every instance\n    # if negative or zero, all vertices are considered\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.PIX_TO_SHAPE_CYCLE_LOSS.NUM_PIXELS_TO_SAMPLE = 100\n    # normalization factor for pixel to pixel distances (higher value = smoother distribution)\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.PIX_TO_SHAPE_CYCLE_LOSS.PIXEL_SIGMA = 5.0\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.PIX_TO_SHAPE_CYCLE_LOSS.TEMPERATURE_PIXEL_TO_VERTEX = 0.05\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CSE.PIX_TO_SHAPE_CYCLE_LOSS.TEMPERATURE_VERTEX_TO_PIXEL = 0.05\n\n\ndef add_densepose_head_config(cfg: CN):\n    \"\"\"\n    Add config for densepose head.\n    \"\"\"\n    _C = cfg\n\n    _C.MODEL.DENSEPOSE_ON = True\n\n    _C.MODEL.ROI_DENSEPOSE_HEAD = CN()\n    _C.MODEL.ROI_DENSEPOSE_HEAD.NAME = \"\"\n    _C.MODEL.ROI_DENSEPOSE_HEAD.NUM_STACKED_CONVS = 8\n    # Number of parts used for point labels\n    _C.MODEL.ROI_DENSEPOSE_HEAD.NUM_PATCHES = 24\n    _C.MODEL.ROI_DENSEPOSE_HEAD.DECONV_KERNEL = 4\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CONV_HEAD_DIM = 512\n    _C.MODEL.ROI_DENSEPOSE_HEAD.CONV_HEAD_KERNEL = 3\n    _C.MODEL.ROI_DENSEPOSE_HEAD.UP_SCALE = 2\n    _C.MODEL.ROI_DENSEPOSE_HEAD.HEATMAP_SIZE = 112\n    _C.MODEL.ROI_DENSEPOSE_HEAD.POOLER_TYPE = \"ROIAlignV2\"\n    _C.MODEL.ROI_DENSEPOSE_HEAD.POOLER_RESOLUTION = 28\n    _C.MODEL.ROI_DENSEPOSE_HEAD.POOLER_SAMPLING_RATIO = 2\n    _C.MODEL.ROI_DENSEPOSE_HEAD.NUM_COARSE_SEGM_CHANNELS = 2  # 15 or 2\n    # Overlap threshold for an RoI to be considered foreground (if >= FG_IOU_THRESHOLD)\n    _C.MODEL.ROI_DENSEPOSE_HEAD.FG_IOU_THRESHOLD = 0.7\n    # Loss weights for annotation masks.(14 Parts)\n    _C.MODEL.ROI_DENSEPOSE_HEAD.INDEX_WEIGHTS = 5.0\n    # Loss weights for surface parts. (24 Parts)\n    _C.MODEL.ROI_DENSEPOSE_HEAD.PART_WEIGHTS = 1.0\n    # Loss weights for UV regression.\n    _C.MODEL.ROI_DENSEPOSE_HEAD.POINT_REGRESSION_WEIGHTS = 0.01\n    # Coarse segmentation is trained using instance segmentation task data\n    _C.MODEL.ROI_DENSEPOSE_HEAD.COARSE_SEGM_TRAINED_BY_MASKS = False\n    # For Decoder\n    _C.MODEL.ROI_DENSEPOSE_HEAD.DECODER_ON = True\n    _C.MODEL.ROI_DENSEPOSE_HEAD.DECODER_NUM_CLASSES = 256\n    _C.MODEL.ROI_DENSEPOSE_HEAD.DECODER_CONV_DIMS = 256\n    _C.MODEL.ROI_DENSEPOSE_HEAD.DECODER_NORM = \"\"\n    _C.MODEL.ROI_DENSEPOSE_HEAD.DECODER_COMMON_STRIDE = 4\n    # For DeepLab head\n    _C.MODEL.ROI_DENSEPOSE_HEAD.DEEPLAB = CN()\n    _C.MODEL.ROI_DENSEPOSE_HEAD.DEEPLAB.NORM = \"GN\"\n    _C.MODEL.ROI_DENSEPOSE_HEAD.DEEPLAB.NONLOCAL_ON = 0\n    # Predictor class name, must be registered in DENSEPOSE_PREDICTOR_REGISTRY\n    # Some registered predictors:\n    #   \"DensePoseChartPredictor\": predicts segmentation and UV coordinates for predefined charts\n    #   \"DensePoseChartWithConfidencePredictor\": predicts segmentation, UV coordinates\n    #       and associated confidences for predefined charts (default)\n    #   \"DensePoseEmbeddingWithConfidencePredictor\": predicts segmentation, embeddings\n    #       and associated confidences for CSE\n    _C.MODEL.ROI_DENSEPOSE_HEAD.PREDICTOR_NAME = \"DensePoseChartWithConfidencePredictor\"\n    # Loss class name, must be registered in DENSEPOSE_LOSS_REGISTRY\n    # Some registered losses:\n    #   \"DensePoseChartLoss\": loss for chart-based models that estimate\n    #      segmentation and UV coordinates\n    #   \"DensePoseChartWithConfidenceLoss\": loss for chart-based models that estimate\n    #      segmentation, UV coordinates and the corresponding confidences (default)\n    _C.MODEL.ROI_DENSEPOSE_HEAD.LOSS_NAME = \"DensePoseChartWithConfidenceLoss\"\n    # Confidences\n    # Enable learning UV confidences (variances) along with the actual values\n    _C.MODEL.ROI_DENSEPOSE_HEAD.UV_CONFIDENCE = CN({\"ENABLED\": False})\n    # UV confidence lower bound\n    _C.MODEL.ROI_DENSEPOSE_HEAD.UV_CONFIDENCE.EPSILON = 0.01\n    # Enable learning segmentation confidences (variances) along with the actual values\n    _C.MODEL.ROI_DENSEPOSE_HEAD.SEGM_CONFIDENCE = CN({\"ENABLED\": False})\n    # Segmentation confidence lower bound\n    _C.MODEL.ROI_DENSEPOSE_HEAD.SEGM_CONFIDENCE.EPSILON = 0.01\n    # Statistical model type for confidence learning, possible values:\n    # - \"iid_iso\": statistically independent identically distributed residuals\n    #    with isotropic covariance\n    # - \"indep_aniso\": statistically independent residuals with anisotropic\n    #    covariances\n    _C.MODEL.ROI_DENSEPOSE_HEAD.UV_CONFIDENCE.TYPE = \"iid_iso\"\n    # List of angles for rotation in data augmentation during training\n    _C.INPUT.ROTATION_ANGLES = [0]\n    _C.TEST.AUG.ROTATION_ANGLES = ()  # Rotation TTA\n\n    add_densepose_head_cse_config(cfg)\n\n\ndef add_hrnet_config(cfg: CN):\n    \"\"\"\n    Add config for HRNet backbone.\n    \"\"\"\n    _C = cfg\n\n    # For HigherHRNet w32\n    _C.MODEL.HRNET = CN()\n    _C.MODEL.HRNET.STEM_INPLANES = 64\n    _C.MODEL.HRNET.STAGE2 = CN()\n    _C.MODEL.HRNET.STAGE2.NUM_MODULES = 1\n    _C.MODEL.HRNET.STAGE2.NUM_BRANCHES = 2\n    _C.MODEL.HRNET.STAGE2.BLOCK = \"BASIC\"\n    _C.MODEL.HRNET.STAGE2.NUM_BLOCKS = [4, 4]\n    _C.MODEL.HRNET.STAGE2.NUM_CHANNELS = [32, 64]\n    _C.MODEL.HRNET.STAGE2.FUSE_METHOD = \"SUM\"\n    _C.MODEL.HRNET.STAGE3 = CN()\n    _C.MODEL.HRNET.STAGE3.NUM_MODULES = 4\n    _C.MODEL.HRNET.STAGE3.NUM_BRANCHES = 3\n    _C.MODEL.HRNET.STAGE3.BLOCK = \"BASIC\"\n    _C.MODEL.HRNET.STAGE3.NUM_BLOCKS = [4, 4, 4]\n    _C.MODEL.HRNET.STAGE3.NUM_CHANNELS = [32, 64, 128]\n    _C.MODEL.HRNET.STAGE3.FUSE_METHOD = \"SUM\"\n    _C.MODEL.HRNET.STAGE4 = CN()\n    _C.MODEL.HRNET.STAGE4.NUM_MODULES = 3\n    _C.MODEL.HRNET.STAGE4.NUM_BRANCHES = 4\n    _C.MODEL.HRNET.STAGE4.BLOCK = \"BASIC\"\n    _C.MODEL.HRNET.STAGE4.NUM_BLOCKS = [4, 4, 4, 4]\n    _C.MODEL.HRNET.STAGE4.NUM_CHANNELS = [32, 64, 128, 256]\n    _C.MODEL.HRNET.STAGE4.FUSE_METHOD = \"SUM\"\n\n    _C.MODEL.HRNET.HRFPN = CN()\n    _C.MODEL.HRNET.HRFPN.OUT_CHANNELS = 256\n\n\ndef add_densepose_config(cfg: CN):\n    add_densepose_head_config(cfg)\n    add_hrnet_config(cfg)\n    add_bootstrap_config(cfg)\n    add_dataset_category_config(cfg)\n    add_evaluation_config(cfg)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/converters/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom .hflip import HFlipConverter\nfrom .to_mask import ToMaskConverter\nfrom .to_chart_result import ToChartResultConverter, ToChartResultConverterWithConfidences\nfrom .segm_to_mask import (\n    predictor_output_with_fine_and_coarse_segm_to_mask,\n    predictor_output_with_coarse_segm_to_mask,\n    resample_fine_and_coarse_segm_to_bbox,\n)\nfrom .chart_output_to_chart_result import (\n    densepose_chart_predictor_output_to_result,\n    densepose_chart_predictor_output_to_result_with_confidences,\n)\nfrom .chart_output_hflip import densepose_chart_predictor_output_hflip\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/converters/base.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom typing import Any, Tuple, Type\nimport torch\n\n\nclass BaseConverter:\n    \"\"\"\n    Converter base class to be reused by various converters.\n    Converter allows one to convert data from various source types to a particular\n    destination type. Each source type needs to register its converter. The\n    registration for each source type is valid for all descendants of that type.\n    \"\"\"\n\n    @classmethod\n    def register(cls, from_type: Type, converter: Any = None):\n        \"\"\"\n        Registers a converter for the specified type.\n        Can be used as a decorator (if converter is None), or called as a method.\n\n        Args:\n            from_type (type): type to register the converter for;\n                all instances of this type will use the same converter\n            converter (callable): converter to be registered for the given\n                type; if None, this method is assumed to be a decorator for the converter\n        \"\"\"\n\n        if converter is not None:\n            cls._do_register(from_type, converter)\n\n        def wrapper(converter: Any) -> Any:\n            cls._do_register(from_type, converter)\n            return converter\n\n        return wrapper\n\n    @classmethod\n    def _do_register(cls, from_type: Type, converter: Any):\n        cls.registry[from_type] = converter  # pyre-ignore[16]\n\n    @classmethod\n    def _lookup_converter(cls, from_type: Type) -> Any:\n        \"\"\"\n        Perform recursive lookup for the given type\n        to find registered converter. If a converter was found for some base\n        class, it gets registered for this class to save on further lookups.\n\n        Args:\n            from_type: type for which to find a converter\n        Return:\n            callable or None - registered converter or None\n                if no suitable entry was found in the registry\n        \"\"\"\n        if from_type in cls.registry:  # pyre-ignore[16]\n            return cls.registry[from_type]\n        for base in from_type.__bases__:\n            converter = cls._lookup_converter(base)\n            if converter is not None:\n                cls._do_register(from_type, converter)\n                return converter\n        return None\n\n    @classmethod\n    def convert(cls, instance: Any, *args, **kwargs):\n        \"\"\"\n        Convert an instance to the destination type using some registered\n        converter. Does recursive lookup for base classes, so there's no need\n        for explicit registration for derived classes.\n\n        Args:\n            instance: source instance to convert to the destination type\n        Return:\n            An instance of the destination type obtained from the source instance\n            Raises KeyError, if no suitable converter found\n        \"\"\"\n        instance_type = type(instance)\n        converter = cls._lookup_converter(instance_type)\n        if converter is None:\n            if cls.dst_type is None:  # pyre-ignore[16]\n                output_type_str = \"itself\"\n            else:\n                output_type_str = cls.dst_type\n            raise KeyError(f\"Could not find converter from {instance_type} to {output_type_str}\")\n        return converter(instance, *args, **kwargs)\n\n\nIntTupleBox = Tuple[int, int, int, int]\n\n\ndef make_int_box(box: torch.Tensor) -> IntTupleBox:\n    int_box = [0, 0, 0, 0]\n    int_box[0], int_box[1], int_box[2], int_box[3] = tuple(box.long().tolist())\n    return int_box[0], int_box[1], int_box[2], int_box[3]\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/converters/builtin.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom ..structures import DensePoseChartPredictorOutput, DensePoseEmbeddingPredictorOutput\nfrom . import (\n    HFlipConverter,\n    ToChartResultConverter,\n    ToChartResultConverterWithConfidences,\n    ToMaskConverter,\n    densepose_chart_predictor_output_hflip,\n    densepose_chart_predictor_output_to_result,\n    densepose_chart_predictor_output_to_result_with_confidences,\n    predictor_output_with_coarse_segm_to_mask,\n    predictor_output_with_fine_and_coarse_segm_to_mask,\n)\n\nToMaskConverter.register(\n    DensePoseChartPredictorOutput, predictor_output_with_fine_and_coarse_segm_to_mask\n)\nToMaskConverter.register(\n    DensePoseEmbeddingPredictorOutput, predictor_output_with_coarse_segm_to_mask\n)\n\nToChartResultConverter.register(\n    DensePoseChartPredictorOutput, densepose_chart_predictor_output_to_result\n)\n\nToChartResultConverterWithConfidences.register(\n    DensePoseChartPredictorOutput, densepose_chart_predictor_output_to_result_with_confidences\n)\n\nHFlipConverter.register(DensePoseChartPredictorOutput, densepose_chart_predictor_output_hflip)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/converters/chart_output_hflip.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom dataclasses import fields\nimport torch\n\nfrom densepose.structures import DensePoseChartPredictorOutput, DensePoseTransformData\n\n\ndef densepose_chart_predictor_output_hflip(\n    densepose_predictor_output: DensePoseChartPredictorOutput,\n    transform_data: DensePoseTransformData,\n) -> DensePoseChartPredictorOutput:\n    \"\"\"\n    Change  to take into account a Horizontal flip.\n    \"\"\"\n    if len(densepose_predictor_output) > 0:\n\n        PredictorOutput = type(densepose_predictor_output)\n        output_dict = {}\n\n        for field in fields(densepose_predictor_output):\n            field_value = getattr(densepose_predictor_output, field.name)\n            # flip tensors\n            if isinstance(field_value, torch.Tensor):\n                setattr(densepose_predictor_output, field.name, torch.flip(field_value, [3]))\n\n        densepose_predictor_output = _flip_iuv_semantics_tensor(\n            densepose_predictor_output, transform_data\n        )\n        densepose_predictor_output = _flip_segm_semantics_tensor(\n            densepose_predictor_output, transform_data\n        )\n\n        for field in fields(densepose_predictor_output):\n            output_dict[field.name] = getattr(densepose_predictor_output, field.name)\n\n        return PredictorOutput(**output_dict)\n    else:\n        return densepose_predictor_output\n\n\ndef _flip_iuv_semantics_tensor(\n    densepose_predictor_output: DensePoseChartPredictorOutput,\n    dp_transform_data: DensePoseTransformData,\n) -> DensePoseChartPredictorOutput:\n    point_label_symmetries = dp_transform_data.point_label_symmetries\n    uv_symmetries = dp_transform_data.uv_symmetries\n\n    N, C, H, W = densepose_predictor_output.u.shape\n    u_loc = (densepose_predictor_output.u[:, 1:, :, :].clamp(0, 1) * 255).long()\n    v_loc = (densepose_predictor_output.v[:, 1:, :, :].clamp(0, 1) * 255).long()\n    Iindex = torch.arange(C - 1, device=densepose_predictor_output.u.device)[\n        None, :, None, None\n    ].expand(N, C - 1, H, W)\n    densepose_predictor_output.u[:, 1:, :, :] = uv_symmetries[\"U_transforms\"][Iindex, v_loc, u_loc]\n    densepose_predictor_output.v[:, 1:, :, :] = uv_symmetries[\"V_transforms\"][Iindex, v_loc, u_loc]\n\n    for el in [\"fine_segm\", \"u\", \"v\"]:\n        densepose_predictor_output.__dict__[el] = densepose_predictor_output.__dict__[el][\n            :, point_label_symmetries, :, :\n        ]\n    return densepose_predictor_output\n\n\ndef _flip_segm_semantics_tensor(\n    densepose_predictor_output: DensePoseChartPredictorOutput, dp_transform_data\n):\n    if densepose_predictor_output.coarse_segm.shape[1] > 2:\n        densepose_predictor_output.coarse_segm = densepose_predictor_output.coarse_segm[\n            :, dp_transform_data.mask_label_symmetries, :, :\n        ]\n    return densepose_predictor_output\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/converters/chart_output_to_chart_result.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom typing import Dict\nimport torch\nfrom torch.nn import functional as F\n\nfrom detectron2.structures.boxes import Boxes, BoxMode\n\nfrom ..structures import (\n    DensePoseChartPredictorOutput,\n    DensePoseChartResult,\n    DensePoseChartResultWithConfidences,\n)\nfrom . import resample_fine_and_coarse_segm_to_bbox\nfrom .base import IntTupleBox, make_int_box\n\n\ndef resample_uv_tensors_to_bbox(\n    u: torch.Tensor,\n    v: torch.Tensor,\n    labels: torch.Tensor,\n    box_xywh_abs: IntTupleBox,\n) -> torch.Tensor:\n    \"\"\"\n    Resamples U and V coordinate estimates for the given bounding box\n\n    Args:\n        u (tensor [1, C, H, W] of float): U coordinates\n        v (tensor [1, C, H, W] of float): V coordinates\n        labels (tensor [H, W] of long): labels obtained by resampling segmentation\n            outputs for the given bounding box\n        box_xywh_abs (tuple of 4 int): bounding box that corresponds to predictor outputs\n    Return:\n       Resampled U and V coordinates - a tensor [2, H, W] of float\n    \"\"\"\n    x, y, w, h = box_xywh_abs\n    w = max(int(w), 1)\n    h = max(int(h), 1)\n    u_bbox = F.interpolate(u, (h, w), mode=\"bilinear\", align_corners=False)\n    v_bbox = F.interpolate(v, (h, w), mode=\"bilinear\", align_corners=False)\n    uv = torch.zeros([2, h, w], dtype=torch.float32, device=u.device)\n    for part_id in range(1, u_bbox.size(1)):\n        uv[0][labels == part_id] = u_bbox[0, part_id][labels == part_id]\n        uv[1][labels == part_id] = v_bbox[0, part_id][labels == part_id]\n    return uv\n\n\ndef resample_uv_to_bbox(\n    predictor_output: DensePoseChartPredictorOutput,\n    labels: torch.Tensor,\n    box_xywh_abs: IntTupleBox,\n) -> torch.Tensor:\n    \"\"\"\n    Resamples U and V coordinate estimates for the given bounding box\n\n    Args:\n        predictor_output (DensePoseChartPredictorOutput): DensePose predictor\n            output to be resampled\n        labels (tensor [H, W] of long): labels obtained by resampling segmentation\n            outputs for the given bounding box\n        box_xywh_abs (tuple of 4 int): bounding box that corresponds to predictor outputs\n    Return:\n       Resampled U and V coordinates - a tensor [2, H, W] of float\n    \"\"\"\n    return resample_uv_tensors_to_bbox(\n        predictor_output.u,\n        predictor_output.v,\n        labels,\n        box_xywh_abs,\n    )\n\n\ndef densepose_chart_predictor_output_to_result(\n    predictor_output: DensePoseChartPredictorOutput, boxes: Boxes\n) -> DensePoseChartResult:\n    \"\"\"\n    Convert densepose chart predictor outputs to results\n\n    Args:\n        predictor_output (DensePoseChartPredictorOutput): DensePose predictor\n            output to be converted to results, must contain only 1 output\n        boxes (Boxes): bounding box that corresponds to the predictor output,\n            must contain only 1 bounding box\n    Return:\n       DensePose chart-based result (DensePoseChartResult)\n    \"\"\"\n    assert len(predictor_output) == 1 and len(boxes) == 1, (\n        f\"Predictor output to result conversion can operate only single outputs\"\n        f\", got {len(predictor_output)} predictor outputs and {len(boxes)} boxes\"\n    )\n\n    boxes_xyxy_abs = boxes.tensor.clone()\n    boxes_xywh_abs = BoxMode.convert(boxes_xyxy_abs, BoxMode.XYXY_ABS, BoxMode.XYWH_ABS)\n    box_xywh = make_int_box(boxes_xywh_abs[0])\n\n    labels = resample_fine_and_coarse_segm_to_bbox(predictor_output, box_xywh).squeeze(0)\n    uv = resample_uv_to_bbox(predictor_output, labels, box_xywh)\n    return DensePoseChartResult(labels=labels, uv=uv)\n\n\ndef resample_confidences_to_bbox(\n    predictor_output: DensePoseChartPredictorOutput,\n    labels: torch.Tensor,\n    box_xywh_abs: IntTupleBox,\n) -> Dict[str, torch.Tensor]:\n    \"\"\"\n    Resamples confidences for the given bounding box\n\n    Args:\n        predictor_output (DensePoseChartPredictorOutput): DensePose predictor\n            output to be resampled\n        labels (tensor [H, W] of long): labels obtained by resampling segmentation\n            outputs for the given bounding box\n        box_xywh_abs (tuple of 4 int): bounding box that corresponds to predictor outputs\n    Return:\n       Resampled confidences - a dict of [H, W] tensors of float\n    \"\"\"\n\n    x, y, w, h = box_xywh_abs\n    w = max(int(w), 1)\n    h = max(int(h), 1)\n\n    confidence_names = [\n        \"sigma_1\",\n        \"sigma_2\",\n        \"kappa_u\",\n        \"kappa_v\",\n        \"fine_segm_confidence\",\n        \"coarse_segm_confidence\",\n    ]\n    confidence_results = {key: None for key in confidence_names}\n    confidence_names = [\n        key for key in confidence_names if getattr(predictor_output, key) is not None\n    ]\n    confidence_base = torch.zeros([h, w], dtype=torch.float32, device=predictor_output.u.device)\n\n    # assign data from channels that correspond to the labels\n    for key in confidence_names:\n        resampled_confidence = F.interpolate(\n            getattr(predictor_output, key), (h, w), mode=\"bilinear\", align_corners=False\n        )\n        result = confidence_base.clone()\n        for part_id in range(1, predictor_output.u.size(1)):\n            if resampled_confidence.size(1) != predictor_output.u.size(1):\n                # confidence is not part-based, don't try to fill it part by part\n                continue\n            result[labels == part_id] = resampled_confidence[0, part_id][labels == part_id]\n\n        if resampled_confidence.size(1) != predictor_output.u.size(1):\n            # confidence is not part-based, fill the data with the first channel\n            # (targeted for segmentation confidences that have only 1 channel)\n            result = resampled_confidence[0, 0]\n\n        confidence_results[key] = result\n\n    return confidence_results  # pyre-ignore[7]\n\n\ndef densepose_chart_predictor_output_to_result_with_confidences(\n    predictor_output: DensePoseChartPredictorOutput, boxes: Boxes\n) -> DensePoseChartResultWithConfidences:\n    \"\"\"\n    Convert densepose chart predictor outputs to results\n\n    Args:\n        predictor_output (DensePoseChartPredictorOutput): DensePose predictor\n            output with confidences to be converted to results, must contain only 1 output\n        boxes (Boxes): bounding box that corresponds to the predictor output,\n            must contain only 1 bounding box\n    Return:\n       DensePose chart-based result with confidences (DensePoseChartResultWithConfidences)\n    \"\"\"\n    assert len(predictor_output) == 1 and len(boxes) == 1, (\n        f\"Predictor output to result conversion can operate only single outputs\"\n        f\", got {len(predictor_output)} predictor outputs and {len(boxes)} boxes\"\n    )\n\n    boxes_xyxy_abs = boxes.tensor.clone()\n    boxes_xywh_abs = BoxMode.convert(boxes_xyxy_abs, BoxMode.XYXY_ABS, BoxMode.XYWH_ABS)\n    box_xywh = make_int_box(boxes_xywh_abs[0])\n\n    labels = resample_fine_and_coarse_segm_to_bbox(predictor_output, box_xywh).squeeze(0)\n    uv = resample_uv_to_bbox(predictor_output, labels, box_xywh)\n    confidences = resample_confidences_to_bbox(predictor_output, labels, box_xywh)\n    return DensePoseChartResultWithConfidences(labels=labels, uv=uv, **confidences)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/converters/hflip.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom typing import Any\n\nfrom .base import BaseConverter\n\n\nclass HFlipConverter(BaseConverter):\n    \"\"\"\n    Converts various DensePose predictor outputs to DensePose results.\n    Each DensePose predictor output type has to register its convertion strategy.\n    \"\"\"\n\n    registry = {}\n    dst_type = None\n\n    @classmethod\n    def convert(cls, predictor_outputs: Any, transform_data: Any, *args, **kwargs):\n        \"\"\"\n        Performs an horizontal flip on DensePose predictor outputs.\n        Does recursive lookup for base classes, so there's no need\n        for explicit registration for derived classes.\n\n        Args:\n            predictor_outputs: DensePose predictor output to be converted to BitMasks\n            transform_data: Anything useful for the flip\n        Return:\n            An instance of the same type as predictor_outputs\n        \"\"\"\n        return super(HFlipConverter, cls).convert(\n            predictor_outputs, transform_data, *args, **kwargs\n        )\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/converters/segm_to_mask.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom typing import Any\nimport torch\nfrom torch.nn import functional as F\n\nfrom detectron2.structures import BitMasks, Boxes, BoxMode\n\nfrom .base import IntTupleBox, make_int_box\nfrom .to_mask import ImageSizeType\n\n\ndef resample_coarse_segm_tensor_to_bbox(coarse_segm: torch.Tensor, box_xywh_abs: IntTupleBox):\n    \"\"\"\n    Resample coarse segmentation tensor to the given\n    bounding box and derive labels for each pixel of the bounding box\n\n    Args:\n        coarse_segm: float tensor of shape [1, K, Hout, Wout]\n        box_xywh_abs (tuple of 4 int): bounding box given by its upper-left\n            corner coordinates, width (W) and height (H)\n    Return:\n        Labels for each pixel of the bounding box, a long tensor of size [1, H, W]\n    \"\"\"\n    x, y, w, h = box_xywh_abs\n    w = max(int(w), 1)\n    h = max(int(h), 1)\n    labels = F.interpolate(coarse_segm, (h, w), mode=\"bilinear\", align_corners=False).argmax(dim=1)\n    return labels\n\n\ndef resample_fine_and_coarse_segm_tensors_to_bbox(\n    fine_segm: torch.Tensor, coarse_segm: torch.Tensor, box_xywh_abs: IntTupleBox\n):\n    \"\"\"\n    Resample fine and coarse segmentation tensors to the given\n    bounding box and derive labels for each pixel of the bounding box\n\n    Args:\n        fine_segm: float tensor of shape [1, C, Hout, Wout]\n        coarse_segm: float tensor of shape [1, K, Hout, Wout]\n        box_xywh_abs (tuple of 4 int): bounding box given by its upper-left\n            corner coordinates, width (W) and height (H)\n    Return:\n        Labels for each pixel of the bounding box, a long tensor of size [1, H, W]\n    \"\"\"\n    x, y, w, h = box_xywh_abs\n    w = max(int(w), 1)\n    h = max(int(h), 1)\n    # coarse segmentation\n    coarse_segm_bbox = F.interpolate(\n        coarse_segm, (h, w), mode=\"bilinear\", align_corners=False\n    ).argmax(dim=1)\n    # combined coarse and fine segmentation\n    labels = (\n        F.interpolate(fine_segm, (h, w), mode=\"bilinear\", align_corners=False).argmax(dim=1)\n        * (coarse_segm_bbox > 0).long()\n    )\n    return labels\n\n\ndef resample_fine_and_coarse_segm_to_bbox(predictor_output: Any, box_xywh_abs: IntTupleBox):\n    \"\"\"\n    Resample fine and coarse segmentation outputs from a predictor to the given\n    bounding box and derive labels for each pixel of the bounding box\n\n    Args:\n        predictor_output: DensePose predictor output that contains segmentation\n            results to be resampled\n        box_xywh_abs (tuple of 4 int): bounding box given by its upper-left\n            corner coordinates, width (W) and height (H)\n    Return:\n        Labels for each pixel of the bounding box, a long tensor of size [1, H, W]\n    \"\"\"\n    return resample_fine_and_coarse_segm_tensors_to_bbox(\n        predictor_output.fine_segm,\n        predictor_output.coarse_segm,\n        box_xywh_abs,\n    )\n\n\ndef predictor_output_with_coarse_segm_to_mask(\n    predictor_output: Any, boxes: Boxes, image_size_hw: ImageSizeType\n) -> BitMasks:\n    \"\"\"\n    Convert predictor output with coarse and fine segmentation to a mask.\n    Assumes that predictor output has the following attributes:\n     - coarse_segm (tensor of size [N, D, H, W]): coarse segmentation\n         unnormalized scores for N instances; D is the number of coarse\n         segmentation labels, H and W is the resolution of the estimate\n\n    Args:\n        predictor_output: DensePose predictor output to be converted to mask\n        boxes (Boxes): bounding boxes that correspond to the DensePose\n            predictor outputs\n        image_size_hw (tuple [int, int]): image height Himg and width Wimg\n    Return:\n        BitMasks that contain a bool tensor of size [N, Himg, Wimg] with\n        a mask of the size of the image for each instance\n    \"\"\"\n    H, W = image_size_hw\n    boxes_xyxy_abs = boxes.tensor.clone()\n    boxes_xywh_abs = BoxMode.convert(boxes_xyxy_abs, BoxMode.XYXY_ABS, BoxMode.XYWH_ABS)\n    N = len(boxes_xywh_abs)\n    masks = torch.zeros((N, H, W), dtype=torch.bool, device=boxes.tensor.device)\n    for i in range(len(boxes_xywh_abs)):\n        box_xywh = make_int_box(boxes_xywh_abs[i])\n        box_mask = resample_coarse_segm_tensor_to_bbox(predictor_output[i].coarse_segm, box_xywh)\n        x, y, w, h = box_xywh\n        masks[i, y : y + h, x : x + w] = box_mask\n\n    return BitMasks(masks)\n\n\ndef predictor_output_with_fine_and_coarse_segm_to_mask(\n    predictor_output: Any, boxes: Boxes, image_size_hw: ImageSizeType\n) -> BitMasks:\n    \"\"\"\n    Convert predictor output with coarse and fine segmentation to a mask.\n    Assumes that predictor output has the following attributes:\n     - coarse_segm (tensor of size [N, D, H, W]): coarse segmentation\n         unnormalized scores for N instances; D is the number of coarse\n         segmentation labels, H and W is the resolution of the estimate\n     - fine_segm (tensor of size [N, C, H, W]): fine segmentation\n         unnormalized scores for N instances; C is the number of fine\n         segmentation labels, H and W is the resolution of the estimate\n\n    Args:\n        predictor_output: DensePose predictor output to be converted to mask\n        boxes (Boxes): bounding boxes that correspond to the DensePose\n            predictor outputs\n        image_size_hw (tuple [int, int]): image height Himg and width Wimg\n    Return:\n        BitMasks that contain a bool tensor of size [N, Himg, Wimg] with\n        a mask of the size of the image for each instance\n    \"\"\"\n    H, W = image_size_hw\n    boxes_xyxy_abs = boxes.tensor.clone()\n    boxes_xywh_abs = BoxMode.convert(boxes_xyxy_abs, BoxMode.XYXY_ABS, BoxMode.XYWH_ABS)\n    N = len(boxes_xywh_abs)\n    masks = torch.zeros((N, H, W), dtype=torch.bool, device=boxes.tensor.device)\n    for i in range(len(boxes_xywh_abs)):\n        box_xywh = make_int_box(boxes_xywh_abs[i])\n        labels_i = resample_fine_and_coarse_segm_to_bbox(predictor_output[i], box_xywh)\n        x, y, w, h = box_xywh\n        masks[i, y : y + h, x : x + w] = labels_i > 0\n    return BitMasks(masks)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/converters/to_chart_result.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom typing import Any\n\nfrom detectron2.structures import Boxes\n\nfrom ..structures import DensePoseChartResult, DensePoseChartResultWithConfidences\nfrom .base import BaseConverter\n\n\nclass ToChartResultConverter(BaseConverter):\n    \"\"\"\n    Converts various DensePose predictor outputs to DensePose results.\n    Each DensePose predictor output type has to register its convertion strategy.\n    \"\"\"\n\n    registry = {}\n    dst_type = DensePoseChartResult\n\n    @classmethod\n    def convert(cls, predictor_outputs: Any, boxes: Boxes, *args, **kwargs) -> DensePoseChartResult:\n        \"\"\"\n        Convert DensePose predictor outputs to DensePoseResult using some registered\n        converter. Does recursive lookup for base classes, so there's no need\n        for explicit registration for derived classes.\n\n        Args:\n            densepose_predictor_outputs: DensePose predictor output to be\n                converted to BitMasks\n            boxes (Boxes): bounding boxes that correspond to the DensePose\n                predictor outputs\n        Return:\n            An instance of DensePoseResult. If no suitable converter was found, raises KeyError\n        \"\"\"\n        return super(ToChartResultConverter, cls).convert(predictor_outputs, boxes, *args, **kwargs)\n\n\nclass ToChartResultConverterWithConfidences(BaseConverter):\n    \"\"\"\n    Converts various DensePose predictor outputs to DensePose results.\n    Each DensePose predictor output type has to register its convertion strategy.\n    \"\"\"\n\n    registry = {}\n    dst_type = DensePoseChartResultWithConfidences\n\n    @classmethod\n    def convert(\n        cls, predictor_outputs: Any, boxes: Boxes, *args, **kwargs\n    ) -> DensePoseChartResultWithConfidences:\n        \"\"\"\n        Convert DensePose predictor outputs to DensePoseResult with confidences\n        using some registered converter. Does recursive lookup for base classes,\n        so there's no need for explicit registration for derived classes.\n\n        Args:\n            densepose_predictor_outputs: DensePose predictor output with confidences\n                to be converted to BitMasks\n            boxes (Boxes): bounding boxes that correspond to the DensePose\n                predictor outputs\n        Return:\n            An instance of DensePoseResult. If no suitable converter was found, raises KeyError\n        \"\"\"\n        return super(ToChartResultConverterWithConfidences, cls).convert(\n            predictor_outputs, boxes, *args, **kwargs\n        )\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/converters/to_mask.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom typing import Any, Tuple\n\nfrom detectron2.structures import BitMasks, Boxes\n\nfrom .base import BaseConverter\n\nImageSizeType = Tuple[int, int]\n\n\nclass ToMaskConverter(BaseConverter):\n    \"\"\"\n    Converts various DensePose predictor outputs to masks\n    in bit mask format (see `BitMasks`). Each DensePose predictor output type\n    has to register its convertion strategy.\n    \"\"\"\n\n    registry = {}\n    dst_type = BitMasks\n\n    @classmethod\n    def convert(\n        cls,\n        densepose_predictor_outputs: Any,\n        boxes: Boxes,\n        image_size_hw: ImageSizeType,\n        *args,\n        **kwargs\n    ) -> BitMasks:\n        \"\"\"\n        Convert DensePose predictor outputs to BitMasks using some registered\n        converter. Does recursive lookup for base classes, so there's no need\n        for explicit registration for derived classes.\n\n        Args:\n            densepose_predictor_outputs: DensePose predictor output to be\n                converted to BitMasks\n            boxes (Boxes): bounding boxes that correspond to the DensePose\n                predictor outputs\n            image_size_hw (tuple [int, int]): image height and width\n        Return:\n            An instance of `BitMasks`. If no suitable converter was found, raises KeyError\n        \"\"\"\n        return super(ToMaskConverter, cls).convert(\n            densepose_predictor_outputs, boxes, image_size_hw, *args, **kwargs\n        )\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/engine/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom .trainer import Trainer\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/engine/trainer.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nimport logging\nimport os\nfrom collections import OrderedDict\nfrom typing import List, Optional, Union\nimport torch\nfrom torch import nn\n\nfrom detectron2.checkpoint import DetectionCheckpointer\nfrom detectron2.config import CfgNode\nfrom detectron2.engine import DefaultTrainer\nfrom detectron2.evaluation import (\n    DatasetEvaluator,\n    DatasetEvaluators,\n    inference_on_dataset,\n    print_csv_format,\n)\nfrom detectron2.solver.build import get_default_optimizer_params, maybe_add_gradient_clipping\nfrom detectron2.utils import comm\nfrom detectron2.utils.events import EventWriter, get_event_storage\n\nfrom densepose import DensePoseDatasetMapperTTA, DensePoseGeneralizedRCNNWithTTA, load_from_cfg\nfrom densepose.data import (\n    DatasetMapper,\n    build_combined_loader,\n    build_detection_test_loader,\n    build_detection_train_loader,\n    build_inference_based_loaders,\n    has_inference_based_loaders,\n)\nfrom densepose.evaluation.d2_evaluator_adapter import Detectron2COCOEvaluatorAdapter\nfrom densepose.evaluation.evaluator import DensePoseCOCOEvaluator, build_densepose_evaluator_storage\nfrom densepose.modeling.cse import Embedder\n\n\nclass SampleCountingLoader:\n    def __init__(self, loader):\n        self.loader = loader\n\n    def __iter__(self):\n        it = iter(self.loader)\n        storage = get_event_storage()\n        while True:\n            try:\n                batch = next(it)\n                num_inst_per_dataset = {}\n                for data in batch:\n                    dataset_name = data[\"dataset\"]\n                    if dataset_name not in num_inst_per_dataset:\n                        num_inst_per_dataset[dataset_name] = 0\n                    num_inst = len(data[\"instances\"])\n                    num_inst_per_dataset[dataset_name] += num_inst\n                for dataset_name in num_inst_per_dataset:\n                    storage.put_scalar(f\"batch/{dataset_name}\", num_inst_per_dataset[dataset_name])\n                yield batch\n            except StopIteration:\n                break\n\n\nclass SampleCountMetricPrinter(EventWriter):\n    def __init__(self):\n        self.logger = logging.getLogger(__name__)\n\n    def write(self):\n        storage = get_event_storage()\n        batch_stats_strs = []\n        for key, buf in storage.histories().items():\n            if key.startswith(\"batch/\"):\n                batch_stats_strs.append(f\"{key} {buf.avg(20)}\")\n        self.logger.info(\", \".join(batch_stats_strs))\n\n\nclass Trainer(DefaultTrainer):\n    @classmethod\n    def extract_embedder_from_model(cls, model: nn.Module) -> Optional[Embedder]:\n        if isinstance(model, nn.parallel.DistributedDataParallel):\n            model = model.module\n        if hasattr(model, \"roi_heads\") and hasattr(model.roi_heads, \"embedder\"):\n            # pyre-fixme[16]: `Tensor` has no attribute `embedder`.\n            return model.roi_heads.embedder\n        return None\n\n    # TODO: the only reason to copy the base class code here is to pass the embedder from\n    # the model to the evaluator; that should be refactored to avoid unnecessary copy-pasting\n    @classmethod\n    def test(\n        cls,\n        cfg: CfgNode,\n        model: nn.Module,\n        evaluators: Optional[Union[DatasetEvaluator, List[DatasetEvaluator]]] = None,\n    ):\n        \"\"\"\n        Args:\n            cfg (CfgNode):\n            model (nn.Module):\n            evaluators (DatasetEvaluator, list[DatasetEvaluator] or None): if None, will call\n                :meth:`build_evaluator`. Otherwise, must have the same length as\n                ``cfg.DATASETS.TEST``.\n\n        Returns:\n            dict: a dict of result metrics\n        \"\"\"\n        logger = logging.getLogger(__name__)\n        if isinstance(evaluators, DatasetEvaluator):\n            evaluators = [evaluators]\n        if evaluators is not None:\n            assert len(cfg.DATASETS.TEST) == len(evaluators), \"{} != {}\".format(\n                len(cfg.DATASETS.TEST), len(evaluators)\n            )\n\n        results = OrderedDict()\n        for idx, dataset_name in enumerate(cfg.DATASETS.TEST):\n            data_loader = cls.build_test_loader(cfg, dataset_name)\n            # When evaluators are passed in as arguments,\n            # implicitly assume that evaluators can be created before data_loader.\n            if evaluators is not None:\n                evaluator = evaluators[idx]\n            else:\n                try:\n                    embedder = cls.extract_embedder_from_model(model)\n                    evaluator = cls.build_evaluator(cfg, dataset_name, embedder=embedder)\n                except NotImplementedError:\n                    logger.warn(\n                        \"No evaluator found. Use `DefaultTrainer.test(evaluators=)`, \"\n                        \"or implement its `build_evaluator` method.\"\n                    )\n                    results[dataset_name] = {}\n                    continue\n            if cfg.DENSEPOSE_EVALUATION.DISTRIBUTED_INFERENCE or comm.is_main_process():\n                results_i = inference_on_dataset(model, data_loader, evaluator)\n            else:\n                results_i = {}\n            results[dataset_name] = results_i\n            if comm.is_main_process():\n                assert isinstance(\n                    results_i, dict\n                ), \"Evaluator must return a dict on the main process. Got {} instead.\".format(\n                    results_i\n                )\n                logger.info(\"Evaluation results for {} in csv format:\".format(dataset_name))\n                print_csv_format(results_i)\n\n        if len(results) == 1:\n            results = list(results.values())[0]\n        return results\n\n    @classmethod\n    def build_evaluator(\n        cls,\n        cfg: CfgNode,\n        dataset_name: str,\n        output_folder: Optional[str] = None,\n        embedder: Optional[Embedder] = None,\n    ) -> DatasetEvaluators:\n        if output_folder is None:\n            output_folder = os.path.join(cfg.OUTPUT_DIR, \"inference\")\n        evaluators = []\n        distributed = cfg.DENSEPOSE_EVALUATION.DISTRIBUTED_INFERENCE\n        # Note: we currently use COCO evaluator for both COCO and LVIS datasets\n        # to have compatible metrics. LVIS bbox evaluator could also be used\n        # with an adapter to properly handle filtered / mapped categories\n        # evaluator_type = MetadataCatalog.get(dataset_name).evaluator_type\n        # if evaluator_type == \"coco\":\n        #     evaluators.append(COCOEvaluator(dataset_name, output_dir=output_folder))\n        # elif evaluator_type == \"lvis\":\n        #     evaluators.append(LVISEvaluator(dataset_name, output_dir=output_folder))\n        evaluators.append(\n            Detectron2COCOEvaluatorAdapter(\n                dataset_name, output_dir=output_folder, distributed=distributed\n            )\n        )\n        if cfg.MODEL.DENSEPOSE_ON:\n            storage = build_densepose_evaluator_storage(cfg, output_folder)\n            evaluators.append(\n                DensePoseCOCOEvaluator(\n                    dataset_name,\n                    distributed,\n                    output_folder,\n                    evaluator_type=cfg.DENSEPOSE_EVALUATION.TYPE,\n                    min_iou_threshold=cfg.DENSEPOSE_EVALUATION.MIN_IOU_THRESHOLD,\n                    storage=storage,\n                    embedder=embedder,\n                    should_evaluate_mesh_alignment=cfg.DENSEPOSE_EVALUATION.EVALUATE_MESH_ALIGNMENT,\n                    mesh_alignment_mesh_names=cfg.DENSEPOSE_EVALUATION.MESH_ALIGNMENT_MESH_NAMES,\n                )\n            )\n        return DatasetEvaluators(evaluators)\n\n    @classmethod\n    def build_optimizer(cls, cfg: CfgNode, model: nn.Module):\n        params = get_default_optimizer_params(\n            model,\n            base_lr=cfg.SOLVER.BASE_LR,\n            weight_decay_norm=cfg.SOLVER.WEIGHT_DECAY_NORM,\n            bias_lr_factor=cfg.SOLVER.BIAS_LR_FACTOR,\n            weight_decay_bias=cfg.SOLVER.WEIGHT_DECAY_BIAS,\n            overrides={\n                \"features\": {\n                    \"lr\": cfg.SOLVER.BASE_LR * cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.FEATURES_LR_FACTOR,\n                },\n                \"embeddings\": {\n                    \"lr\": cfg.SOLVER.BASE_LR * cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBEDDING_LR_FACTOR,\n                },\n            },\n        )\n        optimizer = torch.optim.SGD(\n            params,\n            cfg.SOLVER.BASE_LR,\n            momentum=cfg.SOLVER.MOMENTUM,\n            nesterov=cfg.SOLVER.NESTEROV,\n            weight_decay=cfg.SOLVER.WEIGHT_DECAY,\n        )\n        return maybe_add_gradient_clipping(cfg, optimizer)\n\n    @classmethod\n    def build_test_loader(cls, cfg: CfgNode, dataset_name):\n        return build_detection_test_loader(cfg, dataset_name, mapper=DatasetMapper(cfg, False))\n\n    @classmethod\n    def build_train_loader(cls, cfg: CfgNode):\n        data_loader = build_detection_train_loader(cfg, mapper=DatasetMapper(cfg, True))\n        if not has_inference_based_loaders(cfg):\n            return data_loader\n        model = cls.build_model(cfg)\n        model.to(cfg.BOOTSTRAP_MODEL.DEVICE)\n        DetectionCheckpointer(model).resume_or_load(cfg.BOOTSTRAP_MODEL.WEIGHTS, resume=False)\n        inference_based_loaders, ratios = build_inference_based_loaders(cfg, model)\n        loaders = [data_loader] + inference_based_loaders\n        ratios = [1.0] + ratios\n        combined_data_loader = build_combined_loader(cfg, loaders, ratios)\n        sample_counting_loader = SampleCountingLoader(combined_data_loader)\n        return sample_counting_loader\n\n    def build_writers(self):\n        writers = super().build_writers()\n        writers.append(SampleCountMetricPrinter())\n        return writers\n\n    @classmethod\n    def test_with_TTA(cls, cfg: CfgNode, model):\n        logger = logging.getLogger(\"detectron2.trainer\")\n        # In the end of training, run an evaluation with TTA\n        # Only support some R-CNN models.\n        logger.info(\"Running inference with test-time augmentation ...\")\n        transform_data = load_from_cfg(cfg)\n        model = DensePoseGeneralizedRCNNWithTTA(\n            cfg, model, transform_data, DensePoseDatasetMapperTTA(cfg)\n        )\n        evaluators = [\n            cls.build_evaluator(\n                cfg, name, output_folder=os.path.join(cfg.OUTPUT_DIR, \"inference_TTA\")\n            )\n            for name in cfg.DATASETS.TEST\n        ]\n        res = cls.test(cfg, model, evaluators)  # pyre-ignore[6]\n        res = OrderedDict({k + \"_TTA\": v for k, v in res.items()})\n        return res\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/evaluation/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom .evaluator import DensePoseCOCOEvaluator\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/evaluation/d2_evaluator_adapter.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom detectron2.data.catalog import Metadata\nfrom detectron2.evaluation import COCOEvaluator\n\nfrom densepose.data.datasets.coco import (\n    get_contiguous_id_to_category_id_map,\n    maybe_filter_categories_cocoapi,\n)\n\n\ndef _maybe_add_iscrowd_annotations(cocoapi):\n    for ann in cocoapi.dataset[\"annotations\"]:\n        if \"iscrowd\" not in ann:\n            ann[\"iscrowd\"] = 0\n\n\nclass Detectron2COCOEvaluatorAdapter(COCOEvaluator):\n    def __init__(\n        self,\n        dataset_name,\n        output_dir=None,\n        distributed=True,\n    ):\n        super().__init__(dataset_name, output_dir=output_dir, distributed=distributed)\n        maybe_filter_categories_cocoapi(dataset_name, self._coco_api)\n        _maybe_add_iscrowd_annotations(self._coco_api)\n        # substitute category metadata to account for categories\n        # that are mapped to the same contiguous id\n        if hasattr(self._metadata, \"thing_dataset_id_to_contiguous_id\"):\n            self._maybe_substitute_metadata()\n\n    def _maybe_substitute_metadata(self):\n        cont_id_2_cat_id = get_contiguous_id_to_category_id_map(self._metadata)\n        cat_id_2_cont_id = self._metadata.thing_dataset_id_to_contiguous_id\n        if len(cont_id_2_cat_id) == len(cat_id_2_cont_id):\n            return\n\n        cat_id_2_cont_id_injective = {}\n        for cat_id, cont_id in cat_id_2_cont_id.items():\n            if (cont_id in cont_id_2_cat_id) and (cont_id_2_cat_id[cont_id] == cat_id):\n                cat_id_2_cont_id_injective[cat_id] = cont_id\n\n        metadata_new = Metadata(name=self._metadata.name)\n        for key, value in self._metadata.__dict__.items():\n            if key == \"thing_dataset_id_to_contiguous_id\":\n                setattr(metadata_new, key, cat_id_2_cont_id_injective)\n            else:\n                setattr(metadata_new, key, value)\n        self._metadata = metadata_new\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/evaluation/densepose_coco_evaluation.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n# All rights reserved.\n#\n# This source code is licensed under the license found in the\n# LICENSE file in the root directory of this source tree.\n# This is a modified version of cocoeval.py where we also have the densepose evaluation.\n\n__author__ = \"tsungyi\"\n\nimport copy\nimport datetime\nimport logging\nimport numpy as np\nimport pickle\nimport time\nfrom collections import defaultdict\nfrom enum import Enum\nfrom typing import Any, Dict, Tuple\nimport scipy.spatial.distance as ssd\nimport torch\nimport torch.nn.functional as F\nfrom pycocotools import mask as maskUtils\nfrom scipy.io import loadmat\nfrom scipy.ndimage import zoom as spzoom\n\nfrom detectron2.utils.file_io import PathManager\n\nfrom densepose.converters.chart_output_to_chart_result import resample_uv_tensors_to_bbox\nfrom densepose.converters.segm_to_mask import (\n    resample_coarse_segm_tensor_to_bbox,\n    resample_fine_and_coarse_segm_tensors_to_bbox,\n)\nfrom densepose.modeling.cse.utils import squared_euclidean_distance_matrix\nfrom densepose.structures import DensePoseDataRelative\nfrom densepose.structures.mesh import create_mesh\n\nlogger = logging.getLogger(__name__)\n\n\nclass DensePoseEvalMode(str, Enum):\n    # use both masks and geodesic distances (GPS * IOU) to compute scores\n    GPSM = \"gpsm\"\n    # use only geodesic distances (GPS)  to compute scores\n    GPS = \"gps\"\n    # use only masks (IOU) to compute scores\n    IOU = \"iou\"\n\n\nclass DensePoseDataMode(str, Enum):\n    # use estimated IUV data (default mode)\n    IUV_DT = \"iuvdt\"\n    # use ground truth IUV data\n    IUV_GT = \"iuvgt\"\n    # use ground truth labels I and set UV to 0\n    I_GT_UV_0 = \"igtuv0\"\n    # use ground truth labels I and estimated UV coordinates\n    I_GT_UV_DT = \"igtuvdt\"\n    # use estimated labels I and set UV to 0\n    I_DT_UV_0 = \"idtuv0\"\n\n\nclass DensePoseCocoEval(object):\n    # Interface for evaluating detection on the Microsoft COCO dataset.\n    #\n    # The usage for CocoEval is as follows:\n    #  cocoGt=..., cocoDt=...       # load dataset and results\n    #  E = CocoEval(cocoGt,cocoDt); # initialize CocoEval object\n    #  E.params.recThrs = ...;      # set parameters as desired\n    #  E.evaluate();                # run per image evaluation\n    #  E.accumulate();              # accumulate per image results\n    #  E.summarize();               # display summary metrics of results\n    # For example usage see evalDemo.m and http://mscoco.org/.\n    #\n    # The evaluation parameters are as follows (defaults in brackets):\n    #  imgIds     - [all] N img ids to use for evaluation\n    #  catIds     - [all] K cat ids to use for evaluation\n    #  iouThrs    - [.5:.05:.95] T=10 IoU thresholds for evaluation\n    #  recThrs    - [0:.01:1] R=101 recall thresholds for evaluation\n    #  areaRng    - [...] A=4 object area ranges for evaluation\n    #  maxDets    - [1 10 100] M=3 thresholds on max detections per image\n    #  iouType    - ['segm'] set iouType to 'segm', 'bbox', 'keypoints' or 'densepose'\n    #  iouType replaced the now DEPRECATED useSegm parameter.\n    #  useCats    - [1] if true use category labels for evaluation\n    # Note: if useCats=0 category labels are ignored as in proposal scoring.\n    # Note: multiple areaRngs [Ax2] and maxDets [Mx1] can be specified.\n    #\n    # evaluate(): evaluates detections on every image and every category and\n    # concats the results into the \"evalImgs\" with fields:\n    #  dtIds      - [1xD] id for each of the D detections (dt)\n    #  gtIds      - [1xG] id for each of the G ground truths (gt)\n    #  dtMatches  - [TxD] matching gt id at each IoU or 0\n    #  gtMatches  - [TxG] matching dt id at each IoU or 0\n    #  dtScores   - [1xD] confidence of each dt\n    #  gtIgnore   - [1xG] ignore flag for each gt\n    #  dtIgnore   - [TxD] ignore flag for each dt at each IoU\n    #\n    # accumulate(): accumulates the per-image, per-category evaluation\n    # results in \"evalImgs\" into the dictionary \"eval\" with fields:\n    #  params     - parameters used for evaluation\n    #  date       - date evaluation was performed\n    #  counts     - [T,R,K,A,M] parameter dimensions (see above)\n    #  precision  - [TxRxKxAxM] precision for every evaluation setting\n    #  recall     - [TxKxAxM] max recall for every evaluation setting\n    # Note: precision and recall==-1 for settings with no gt objects.\n    #\n    # See also coco, mask, pycocoDemo, pycocoEvalDemo\n    #\n    # Microsoft COCO Toolbox.      version 2.0\n    # Data, paper, and tutorials available at:  http://mscoco.org/\n    # Code written by Piotr Dollar and Tsung-Yi Lin, 2015.\n    # Licensed under the Simplified BSD License [see coco/license.txt]\n    def __init__(\n        self,\n        cocoGt=None,\n        cocoDt=None,\n        iouType: str = \"densepose\",\n        multi_storage=None,\n        embedder=None,\n        dpEvalMode: DensePoseEvalMode = DensePoseEvalMode.GPS,\n        dpDataMode: DensePoseDataMode = DensePoseDataMode.IUV_DT,\n    ):\n        \"\"\"\n        Initialize CocoEval using coco APIs for gt and dt\n        :param cocoGt: coco object with ground truth annotations\n        :param cocoDt: coco object with detection results\n        :return: None\n        \"\"\"\n        self.cocoGt = cocoGt  # ground truth COCO API\n        self.cocoDt = cocoDt  # detections COCO API\n        self.multi_storage = multi_storage\n        self.embedder = embedder\n        self._dpEvalMode = dpEvalMode\n        self._dpDataMode = dpDataMode\n        self.evalImgs = defaultdict(list)  # per-image per-category eval results [KxAxI]\n        self.eval = {}  # accumulated evaluation results\n        self._gts = defaultdict(list)  # gt for evaluation\n        self._dts = defaultdict(list)  # dt for evaluation\n        self.params = Params(iouType=iouType)  # parameters\n        self._paramsEval = {}  # parameters for evaluation\n        self.stats = []  # result summarization\n        self.ious = {}  # ious between all gts and dts\n        if cocoGt is not None:\n            self.params.imgIds = sorted(cocoGt.getImgIds())\n            self.params.catIds = sorted(cocoGt.getCatIds())\n        self.ignoreThrBB = 0.7\n        self.ignoreThrUV = 0.9\n\n    def _loadGEval(self):\n        smpl_subdiv_fpath = PathManager.get_local_path(\n            \"https://dl.fbaipublicfiles.com/densepose/data/SMPL_subdiv.mat\"\n        )\n        pdist_transform_fpath = PathManager.get_local_path(\n            \"https://dl.fbaipublicfiles.com/densepose/data/SMPL_SUBDIV_TRANSFORM.mat\"\n        )\n        pdist_matrix_fpath = PathManager.get_local_path(\n            \"https://dl.fbaipublicfiles.com/densepose/data/Pdist_matrix.pkl\", timeout_sec=120\n        )\n        SMPL_subdiv = loadmat(smpl_subdiv_fpath)\n        self.PDIST_transform = loadmat(pdist_transform_fpath)\n        self.PDIST_transform = self.PDIST_transform[\"index\"].squeeze()\n        UV = np.array([SMPL_subdiv[\"U_subdiv\"], SMPL_subdiv[\"V_subdiv\"]]).squeeze()\n        ClosestVertInds = np.arange(UV.shape[1]) + 1\n        self.Part_UVs = []\n        self.Part_ClosestVertInds = []\n        for i in np.arange(24):\n            self.Part_UVs.append(UV[:, SMPL_subdiv[\"Part_ID_subdiv\"].squeeze() == (i + 1)])\n            self.Part_ClosestVertInds.append(\n                ClosestVertInds[SMPL_subdiv[\"Part_ID_subdiv\"].squeeze() == (i + 1)]\n            )\n\n        with open(pdist_matrix_fpath, \"rb\") as hFile:\n            arrays = pickle.load(hFile, encoding=\"latin1\")\n        self.Pdist_matrix = arrays[\"Pdist_matrix\"]\n        self.Part_ids = np.array(SMPL_subdiv[\"Part_ID_subdiv\"].squeeze())\n        # Mean geodesic distances for parts.\n        self.Mean_Distances = np.array([0, 0.351, 0.107, 0.126, 0.237, 0.173, 0.142, 0.128, 0.150])\n        # Coarse Part labels.\n        self.CoarseParts = np.array(\n            [0, 1, 1, 2, 2, 3, 3, 4, 4, 4, 4, 5, 5, 5, 5, 6, 6, 6, 6, 7, 7, 7, 7, 8, 8]\n        )\n\n    def _prepare(self):\n        \"\"\"\n        Prepare ._gts and ._dts for evaluation based on params\n        :return: None\n        \"\"\"\n\n        def _toMask(anns, coco):\n            # modify ann['segmentation'] by reference\n            for ann in anns:\n                # safeguard for invalid segmentation annotation;\n                # annotations containing empty lists exist in the posetrack\n                # dataset. This is not a correct segmentation annotation\n                # in terms of COCO format; we need to deal with it somehow\n                segm = ann[\"segmentation\"]\n                if type(segm) == list and len(segm) == 0:\n                    ann[\"segmentation\"] = None\n                    continue\n                rle = coco.annToRLE(ann)\n                ann[\"segmentation\"] = rle\n\n        def _getIgnoreRegion(iid, coco):\n            img = coco.imgs[iid]\n\n            if \"ignore_regions_x\" not in img.keys():\n                return None\n\n            if len(img[\"ignore_regions_x\"]) == 0:\n                return None\n\n            rgns_merged = [\n                [v for xy in zip(region_x, region_y) for v in xy]\n                for region_x, region_y in zip(img[\"ignore_regions_x\"], img[\"ignore_regions_y\"])\n            ]\n            rles = maskUtils.frPyObjects(rgns_merged, img[\"height\"], img[\"width\"])\n            rle = maskUtils.merge(rles)\n            return maskUtils.decode(rle)\n\n        def _checkIgnore(dt, iregion):\n            if iregion is None:\n                return True\n\n            bb = np.array(dt[\"bbox\"]).astype(np.int)\n            x1, y1, x2, y2 = bb[0], bb[1], bb[0] + bb[2], bb[1] + bb[3]\n            x2 = min([x2, iregion.shape[1]])\n            y2 = min([y2, iregion.shape[0]])\n\n            if bb[2] * bb[3] == 0:\n                return False\n\n            crop_iregion = iregion[y1:y2, x1:x2]\n\n            if crop_iregion.sum() == 0:\n                return True\n\n            if \"densepose\" not in dt.keys():  # filtering boxes\n                return crop_iregion.sum() / bb[2] / bb[3] < self.ignoreThrBB\n\n            # filtering UVs\n            ignoremask = np.require(crop_iregion, requirements=[\"F\"])\n            mask = self._extract_mask(dt)\n            uvmask = np.require(np.asarray(mask > 0), dtype=np.uint8, requirements=[\"F\"])\n            uvmask_ = maskUtils.encode(uvmask)\n            ignoremask_ = maskUtils.encode(ignoremask)\n            uviou = maskUtils.iou([uvmask_], [ignoremask_], [1])[0]\n            return uviou < self.ignoreThrUV\n\n        p = self.params\n\n        if p.useCats:\n            gts = self.cocoGt.loadAnns(self.cocoGt.getAnnIds(imgIds=p.imgIds, catIds=p.catIds))\n            dts = self.cocoDt.loadAnns(self.cocoDt.getAnnIds(imgIds=p.imgIds, catIds=p.catIds))\n        else:\n            gts = self.cocoGt.loadAnns(self.cocoGt.getAnnIds(imgIds=p.imgIds))\n            dts = self.cocoDt.loadAnns(self.cocoDt.getAnnIds(imgIds=p.imgIds))\n\n        imns = self.cocoGt.loadImgs(p.imgIds)\n        self.size_mapping = {}\n        for im in imns:\n            self.size_mapping[im[\"id\"]] = [im[\"height\"], im[\"width\"]]\n\n        # if iouType == 'uv', add point gt annotations\n        if p.iouType == \"densepose\":\n            self._loadGEval()\n\n        # convert ground truth to mask if iouType == 'segm'\n        if p.iouType == \"segm\":\n            _toMask(gts, self.cocoGt)\n            _toMask(dts, self.cocoDt)\n\n        # set ignore flag\n        for gt in gts:\n            gt[\"ignore\"] = gt[\"ignore\"] if \"ignore\" in gt else 0\n            gt[\"ignore\"] = \"iscrowd\" in gt and gt[\"iscrowd\"]\n            if p.iouType == \"keypoints\":\n                gt[\"ignore\"] = (gt[\"num_keypoints\"] == 0) or gt[\"ignore\"]\n            if p.iouType == \"densepose\":\n                gt[\"ignore\"] = (\"dp_x\" in gt) == 0\n            if p.iouType == \"segm\":\n                gt[\"ignore\"] = gt[\"segmentation\"] is None\n\n        self._gts = defaultdict(list)  # gt for evaluation\n        self._dts = defaultdict(list)  # dt for evaluation\n        self._igrgns = defaultdict(list)\n\n        for gt in gts:\n            iid = gt[\"image_id\"]\n            if iid not in self._igrgns.keys():\n                self._igrgns[iid] = _getIgnoreRegion(iid, self.cocoGt)\n            if _checkIgnore(gt, self._igrgns[iid]):\n                self._gts[iid, gt[\"category_id\"]].append(gt)\n        for dt in dts:\n            iid = dt[\"image_id\"]\n            if (iid not in self._igrgns) or _checkIgnore(dt, self._igrgns[iid]):\n                self._dts[iid, dt[\"category_id\"]].append(dt)\n\n        self.evalImgs = defaultdict(list)  # per-image per-category evaluation results\n        self.eval = {}  # accumulated evaluation results\n\n    def evaluate(self):\n        \"\"\"\n        Run per image evaluation on given images and store results (a list of dict) in self.evalImgs\n        :return: None\n        \"\"\"\n        tic = time.time()\n        logger.info(\"Running per image DensePose evaluation... {}\".format(self.params.iouType))\n        p = self.params\n        # add backward compatibility if useSegm is specified in params\n        if p.useSegm is not None:\n            p.iouType = \"segm\" if p.useSegm == 1 else \"bbox\"\n            logger.info(\"useSegm (deprecated) is not None. Running DensePose evaluation\")\n        p.imgIds = list(np.unique(p.imgIds))\n        if p.useCats:\n            p.catIds = list(np.unique(p.catIds))\n        p.maxDets = sorted(p.maxDets)\n        self.params = p\n\n        self._prepare()\n        # loop through images, area range, max detection number\n        catIds = p.catIds if p.useCats else [-1]\n\n        if p.iouType in [\"segm\", \"bbox\"]:\n            computeIoU = self.computeIoU\n        elif p.iouType == \"keypoints\":\n            computeIoU = self.computeOks\n        elif p.iouType == \"densepose\":\n            computeIoU = self.computeOgps\n            if self._dpEvalMode in {DensePoseEvalMode.GPSM, DensePoseEvalMode.IOU}:\n                self.real_ious = {\n                    (imgId, catId): self.computeDPIoU(imgId, catId)\n                    for imgId in p.imgIds\n                    for catId in catIds\n                }\n\n        self.ious = {\n            (imgId, catId): computeIoU(imgId, catId) for imgId in p.imgIds for catId in catIds\n        }\n\n        evaluateImg = self.evaluateImg\n        maxDet = p.maxDets[-1]\n        self.evalImgs = [\n            evaluateImg(imgId, catId, areaRng, maxDet)\n            for catId in catIds\n            for areaRng in p.areaRng\n            for imgId in p.imgIds\n        ]\n        self._paramsEval = copy.deepcopy(self.params)\n        toc = time.time()\n        logger.info(\"DensePose evaluation DONE (t={:0.2f}s).\".format(toc - tic))\n\n    def getDensePoseMask(self, polys):\n        maskGen = np.zeros([256, 256])\n        stop = min(len(polys) + 1, 15)\n        for i in range(1, stop):\n            if polys[i - 1]:\n                currentMask = maskUtils.decode(polys[i - 1])\n                maskGen[currentMask > 0] = i\n        return maskGen\n\n    def _generate_rlemask_on_image(self, mask, imgId, data):\n        bbox_xywh = np.array(data[\"bbox\"])\n        x, y, w, h = bbox_xywh\n        im_h, im_w = self.size_mapping[imgId]\n        im_mask = np.zeros((im_h, im_w), dtype=np.uint8)\n        if mask is not None:\n            x0 = max(int(x), 0)\n            x1 = min(int(x + w), im_w, int(x) + mask.shape[1])\n            y0 = max(int(y), 0)\n            y1 = min(int(y + h), im_h, int(y) + mask.shape[0])\n            y = int(y)\n            x = int(x)\n            im_mask[y0:y1, x0:x1] = mask[y0 - y : y1 - y, x0 - x : x1 - x]\n        im_mask = np.require(np.asarray(im_mask > 0), dtype=np.uint8, requirements=[\"F\"])\n        rle_mask = maskUtils.encode(np.array(im_mask[:, :, np.newaxis], order=\"F\"))[0]\n        return rle_mask\n\n    def computeDPIoU(self, imgId, catId):\n        p = self.params\n        if p.useCats:\n            gt = self._gts[imgId, catId]\n            dt = self._dts[imgId, catId]\n        else:\n            gt = [_ for cId in p.catIds for _ in self._gts[imgId, cId]]\n            dt = [_ for cId in p.catIds for _ in self._dts[imgId, cId]]\n        if len(gt) == 0 and len(dt) == 0:\n            return []\n        inds = np.argsort([-d[\"score\"] for d in dt], kind=\"mergesort\")\n        dt = [dt[i] for i in inds]\n        if len(dt) > p.maxDets[-1]:\n            dt = dt[0 : p.maxDets[-1]]\n\n        gtmasks = []\n        for g in gt:\n            if DensePoseDataRelative.S_KEY in g:\n                # convert DensePose mask to a binary mask\n                mask = np.minimum(self.getDensePoseMask(g[DensePoseDataRelative.S_KEY]), 1.0)\n                _, _, w, h = g[\"bbox\"]\n                scale_x = float(max(w, 1)) / mask.shape[1]\n                scale_y = float(max(h, 1)) / mask.shape[0]\n                mask = spzoom(mask, (scale_y, scale_x), order=1, prefilter=False)\n                mask = np.array(mask > 0.5, dtype=np.uint8)\n                rle_mask = self._generate_rlemask_on_image(mask, imgId, g)\n            elif \"segmentation\" in g:\n                segmentation = g[\"segmentation\"]\n                if isinstance(segmentation, list) and segmentation:\n                    # polygons\n                    im_h, im_w = self.size_mapping[imgId]\n                    rles = maskUtils.frPyObjects(segmentation, im_h, im_w)\n                    rle_mask = maskUtils.merge(rles)\n                elif isinstance(segmentation, dict):\n                    if isinstance(segmentation[\"counts\"], list):\n                        # uncompressed RLE\n                        im_h, im_w = self.size_mapping[imgId]\n                        rle_mask = maskUtils.frPyObjects(segmentation, im_h, im_w)\n                    else:\n                        # compressed RLE\n                        rle_mask = segmentation\n                else:\n                    rle_mask = self._generate_rlemask_on_image(None, imgId, g)\n            else:\n                rle_mask = self._generate_rlemask_on_image(None, imgId, g)\n            gtmasks.append(rle_mask)\n\n        dtmasks = []\n        for d in dt:\n            mask = self._extract_mask(d)\n            mask = np.require(np.asarray(mask > 0), dtype=np.uint8, requirements=[\"F\"])\n            rle_mask = self._generate_rlemask_on_image(mask, imgId, d)\n            dtmasks.append(rle_mask)\n\n        # compute iou between each dt and gt region\n        iscrowd = [int(o.get(\"iscrowd\", 0)) for o in gt]\n        iousDP = maskUtils.iou(dtmasks, gtmasks, iscrowd)\n        return iousDP\n\n    def computeIoU(self, imgId, catId):\n        p = self.params\n        if p.useCats:\n            gt = self._gts[imgId, catId]\n            dt = self._dts[imgId, catId]\n        else:\n            gt = [_ for cId in p.catIds for _ in self._gts[imgId, cId]]\n            dt = [_ for cId in p.catIds for _ in self._dts[imgId, cId]]\n        if len(gt) == 0 and len(dt) == 0:\n            return []\n        inds = np.argsort([-d[\"score\"] for d in dt], kind=\"mergesort\")\n        dt = [dt[i] for i in inds]\n        if len(dt) > p.maxDets[-1]:\n            dt = dt[0 : p.maxDets[-1]]\n\n        if p.iouType == \"segm\":\n            g = [g[\"segmentation\"] for g in gt if g[\"segmentation\"] is not None]\n            d = [d[\"segmentation\"] for d in dt if d[\"segmentation\"] is not None]\n        elif p.iouType == \"bbox\":\n            g = [g[\"bbox\"] for g in gt]\n            d = [d[\"bbox\"] for d in dt]\n        else:\n            raise Exception(\"unknown iouType for iou computation\")\n\n        # compute iou between each dt and gt region\n        iscrowd = [int(o.get(\"iscrowd\", 0)) for o in gt]\n        ious = maskUtils.iou(d, g, iscrowd)\n        return ious\n\n    def computeOks(self, imgId, catId):\n        p = self.params\n        # dimension here should be Nxm\n        gts = self._gts[imgId, catId]\n        dts = self._dts[imgId, catId]\n        inds = np.argsort([-d[\"score\"] for d in dts], kind=\"mergesort\")\n        dts = [dts[i] for i in inds]\n        if len(dts) > p.maxDets[-1]:\n            dts = dts[0 : p.maxDets[-1]]\n        # if len(gts) == 0 and len(dts) == 0:\n        if len(gts) == 0 or len(dts) == 0:\n            return []\n        ious = np.zeros((len(dts), len(gts)))\n        sigmas = (\n            np.array(\n                [\n                    0.26,\n                    0.25,\n                    0.25,\n                    0.35,\n                    0.35,\n                    0.79,\n                    0.79,\n                    0.72,\n                    0.72,\n                    0.62,\n                    0.62,\n                    1.07,\n                    1.07,\n                    0.87,\n                    0.87,\n                    0.89,\n                    0.89,\n                ]\n            )\n            / 10.0\n        )\n        vars = (sigmas * 2) ** 2\n        k = len(sigmas)\n        # compute oks between each detection and ground truth object\n        for j, gt in enumerate(gts):\n            # create bounds for ignore regions(double the gt bbox)\n            g = np.array(gt[\"keypoints\"])\n            xg = g[0::3]\n            yg = g[1::3]\n            vg = g[2::3]\n            k1 = np.count_nonzero(vg > 0)\n            bb = gt[\"bbox\"]\n            x0 = bb[0] - bb[2]\n            x1 = bb[0] + bb[2] * 2\n            y0 = bb[1] - bb[3]\n            y1 = bb[1] + bb[3] * 2\n            for i, dt in enumerate(dts):\n                d = np.array(dt[\"keypoints\"])\n                xd = d[0::3]\n                yd = d[1::3]\n                if k1 > 0:\n                    # measure the per-keypoint distance if keypoints visible\n                    dx = xd - xg\n                    dy = yd - yg\n                else:\n                    # measure minimum distance to keypoints in (x0,y0) & (x1,y1)\n                    z = np.zeros(k)\n                    dx = np.max((z, x0 - xd), axis=0) + np.max((z, xd - x1), axis=0)\n                    dy = np.max((z, y0 - yd), axis=0) + np.max((z, yd - y1), axis=0)\n                e = (dx ** 2 + dy ** 2) / vars / (gt[\"area\"] + np.spacing(1)) / 2\n                if k1 > 0:\n                    e = e[vg > 0]\n                ious[i, j] = np.sum(np.exp(-e)) / e.shape[0]\n        return ious\n\n    def _extract_mask(self, dt: Dict[str, Any]) -> np.ndarray:\n        if \"densepose\" in dt:\n            densepose_results_quantized = dt[\"densepose\"]\n            return densepose_results_quantized.labels_uv_uint8[0].numpy()\n        elif \"cse_mask\" in dt:\n            return dt[\"cse_mask\"]\n        elif \"coarse_segm\" in dt:\n            dy = max(int(dt[\"bbox\"][3]), 1)\n            dx = max(int(dt[\"bbox\"][2]), 1)\n            return (\n                F.interpolate(\n                    dt[\"coarse_segm\"].unsqueeze(0), (dy, dx), mode=\"bilinear\", align_corners=False\n                )\n                .squeeze(0)\n                .argmax(0)\n                .numpy()\n                .astype(np.uint8)\n            )\n        elif \"record_id\" in dt:\n            assert (\n                self.multi_storage is not None\n            ), f\"Storage record id encountered in a detection {dt}, but no storage provided!\"\n            record = self.multi_storage.get(dt[\"rank\"], dt[\"record_id\"])\n            coarse_segm = record[\"coarse_segm\"]\n            dy = max(int(dt[\"bbox\"][3]), 1)\n            dx = max(int(dt[\"bbox\"][2]), 1)\n            return (\n                F.interpolate(\n                    coarse_segm.unsqueeze(0), (dy, dx), mode=\"bilinear\", align_corners=False\n                )\n                .squeeze(0)\n                .argmax(0)\n                .numpy()\n                .astype(np.uint8)\n            )\n        else:\n            raise Exception(f\"No mask data in the detection: {dt}\")\n        raise ValueError('The prediction dict needs to contain either \"densepose\" or \"cse_mask\"')\n\n    def _extract_iuv(\n        self, densepose_data: np.ndarray, py: np.ndarray, px: np.ndarray, gt: Dict[str, Any]\n    ) -> Tuple[np.ndarray, np.ndarray, np.ndarray]:\n        \"\"\"\n        Extract arrays of I, U and V values at given points as numpy arrays\n        given the data mode stored in self._dpDataMode\n        \"\"\"\n        if self._dpDataMode == DensePoseDataMode.IUV_DT:\n            # estimated labels and UV (default)\n            ipoints = densepose_data[0, py, px]\n            upoints = densepose_data[1, py, px] / 255.0  # convert from uint8 by /255.\n            vpoints = densepose_data[2, py, px] / 255.0\n        elif self._dpDataMode == DensePoseDataMode.IUV_GT:\n            # ground truth\n            ipoints = np.array(gt[\"dp_I\"])\n            upoints = np.array(gt[\"dp_U\"])\n            vpoints = np.array(gt[\"dp_V\"])\n        elif self._dpDataMode == DensePoseDataMode.I_GT_UV_0:\n            # ground truth labels, UV = 0\n            ipoints = np.array(gt[\"dp_I\"])\n            upoints = upoints * 0.0\n            vpoints = vpoints * 0.0\n        elif self._dpDataMode == DensePoseDataMode.I_GT_UV_DT:\n            # ground truth labels, estimated UV\n            ipoints = np.array(gt[\"dp_I\"])\n            upoints = densepose_data[1, py, px] / 255.0  # convert from uint8 by /255.\n            vpoints = densepose_data[2, py, px] / 255.0\n        elif self._dpDataMode == DensePoseDataMode.I_DT_UV_0:\n            # estimated labels, UV = 0\n            ipoints = densepose_data[0, py, px]\n            upoints = upoints * 0.0\n            vpoints = vpoints * 0.0\n        else:\n            raise ValueError(f\"Unknown data mode: {self._dpDataMode}\")\n        return ipoints, upoints, vpoints\n\n    def computeOgps_single_pair(self, dt, gt, py, px, pt_mask):\n        if \"densepose\" in dt:\n            ipoints, upoints, vpoints = self.extract_iuv_from_quantized(dt, gt, py, px, pt_mask)\n            return self.computeOgps_single_pair_iuv(dt, gt, ipoints, upoints, vpoints)\n        elif \"u\" in dt:\n            ipoints, upoints, vpoints = self.extract_iuv_from_raw(dt, gt, py, px, pt_mask)\n            return self.computeOgps_single_pair_iuv(dt, gt, ipoints, upoints, vpoints)\n        elif \"record_id\" in dt:\n            assert (\n                self.multi_storage is not None\n            ), f\"Storage record id encountered in detection {dt}, but no storage provided!\"\n            record = self.multi_storage.get(dt[\"rank\"], dt[\"record_id\"])\n            record[\"bbox\"] = dt[\"bbox\"]\n            if \"u\" in record:\n                ipoints, upoints, vpoints = self.extract_iuv_from_raw(record, gt, py, px, pt_mask)\n                return self.computeOgps_single_pair_iuv(dt, gt, ipoints, upoints, vpoints)\n            elif \"embedding\" in record:\n                return self.computeOgps_single_pair_cse(\n                    dt,\n                    gt,\n                    py,\n                    px,\n                    pt_mask,\n                    record[\"coarse_segm\"],\n                    record[\"embedding\"],\n                    record[\"bbox\"],\n                )\n            else:\n                raise Exception(f\"Unknown record format: {record}\")\n        elif \"embedding\" in dt:\n            return self.computeOgps_single_pair_cse(\n                dt, gt, py, px, pt_mask, dt[\"coarse_segm\"], dt[\"embedding\"], dt[\"bbox\"]\n            )\n        raise Exception(f\"Unknown detection format: {dt}\")\n\n    def extract_iuv_from_quantized(self, dt, gt, py, px, pt_mask):\n        densepose_results_quantized = dt[\"densepose\"]\n        ipoints, upoints, vpoints = self._extract_iuv(\n            densepose_results_quantized.labels_uv_uint8.numpy(), py, px, gt\n        )\n        ipoints[pt_mask == -1] = 0\n        return ipoints, upoints, vpoints\n\n    def extract_iuv_from_raw(self, dt, gt, py, px, pt_mask):\n        labels_dt = resample_fine_and_coarse_segm_tensors_to_bbox(\n            dt[\"fine_segm\"].unsqueeze(0),\n            dt[\"coarse_segm\"].unsqueeze(0),\n            dt[\"bbox\"],\n        )\n        uv = resample_uv_tensors_to_bbox(\n            dt[\"u\"].unsqueeze(0), dt[\"v\"].unsqueeze(0), labels_dt.squeeze(0), dt[\"bbox\"]\n        )\n        labels_uv_uint8 = torch.cat((labels_dt.byte(), (uv * 255).clamp(0, 255).byte()))\n        ipoints, upoints, vpoints = self._extract_iuv(labels_uv_uint8.numpy(), py, px, gt)\n        ipoints[pt_mask == -1] = 0\n        return ipoints, upoints, vpoints\n\n    def computeOgps_single_pair_iuv(self, dt, gt, ipoints, upoints, vpoints):\n        cVertsGT, ClosestVertsGTTransformed = self.findAllClosestVertsGT(gt)\n        cVerts = self.findAllClosestVertsUV(upoints, vpoints, ipoints)\n        # Get pairwise geodesic distances between gt and estimated mesh points.\n        dist = self.getDistancesUV(ClosestVertsGTTransformed, cVerts)\n        # Compute the Ogps measure.\n        # Find the mean geodesic normalization distance for\n        # each GT point, based on which part it is on.\n        Current_Mean_Distances = self.Mean_Distances[\n            self.CoarseParts[self.Part_ids[cVertsGT[cVertsGT > 0].astype(int) - 1]]\n        ]\n        return dist, Current_Mean_Distances\n\n    def computeOgps_single_pair_cse(\n        self, dt, gt, py, px, pt_mask, coarse_segm, embedding, bbox_xywh_abs\n    ):\n        # 0-based mesh vertex indices\n        cVertsGT = torch.as_tensor(gt[\"dp_vertex\"], dtype=torch.int64)\n        # label for each pixel of the bbox, [H, W] tensor of long\n        labels_dt = resample_coarse_segm_tensor_to_bbox(\n            coarse_segm.unsqueeze(0), bbox_xywh_abs\n        ).squeeze(0)\n        x, y, w, h = bbox_xywh_abs\n        # embedding for each pixel of the bbox, [D, H, W] tensor of float32\n        embedding = F.interpolate(\n            embedding.unsqueeze(0), (int(h), int(w)), mode=\"bilinear\", align_corners=False\n        ).squeeze(0)\n        # valid locations py, px\n        py_pt = torch.from_numpy(py[pt_mask > -1])\n        px_pt = torch.from_numpy(px[pt_mask > -1])\n        cVerts = torch.ones_like(cVertsGT) * -1\n        cVerts[pt_mask > -1] = self.findClosestVertsCse(\n            embedding, py_pt, px_pt, labels_dt, gt[\"ref_model\"]\n        )\n        # Get pairwise geodesic distances between gt and estimated mesh points.\n        dist = self.getDistancesCse(cVertsGT, cVerts, gt[\"ref_model\"])\n        # normalize distances\n        if (gt[\"ref_model\"] == \"smpl_27554\") and (\"dp_I\" in gt):\n            Current_Mean_Distances = self.Mean_Distances[\n                self.CoarseParts[np.array(gt[\"dp_I\"], dtype=int)]\n            ]\n        else:\n            Current_Mean_Distances = 0.255\n        return dist, Current_Mean_Distances\n\n    def computeOgps(self, imgId, catId):\n        p = self.params\n        # dimension here should be Nxm\n        g = self._gts[imgId, catId]\n        d = self._dts[imgId, catId]\n        inds = np.argsort([-d_[\"score\"] for d_ in d], kind=\"mergesort\")\n        d = [d[i] for i in inds]\n        if len(d) > p.maxDets[-1]:\n            d = d[0 : p.maxDets[-1]]\n        # if len(gts) == 0 and len(dts) == 0:\n        if len(g) == 0 or len(d) == 0:\n            return []\n        ious = np.zeros((len(d), len(g)))\n        # compute opgs between each detection and ground truth object\n        # sigma = self.sigma #0.255 # dist = 0.3m corresponds to ogps = 0.5\n        # 1 # dist = 0.3m corresponds to ogps = 0.96\n        # 1.45 # dist = 1.7m (person height) corresponds to ogps = 0.5)\n        for j, gt in enumerate(g):\n            if not gt[\"ignore\"]:\n                g_ = gt[\"bbox\"]\n                for i, dt in enumerate(d):\n                    #\n                    dy = int(dt[\"bbox\"][3])\n                    dx = int(dt[\"bbox\"][2])\n                    dp_x = np.array(gt[\"dp_x\"]) * g_[2] / 255.0\n                    dp_y = np.array(gt[\"dp_y\"]) * g_[3] / 255.0\n                    py = (dp_y + g_[1] - dt[\"bbox\"][1]).astype(np.int)\n                    px = (dp_x + g_[0] - dt[\"bbox\"][0]).astype(np.int)\n                    #\n                    pts = np.zeros(len(px))\n                    pts[px >= dx] = -1\n                    pts[py >= dy] = -1\n                    pts[px < 0] = -1\n                    pts[py < 0] = -1\n                    if len(pts) < 1:\n                        ogps = 0.0\n                    elif np.max(pts) == -1:\n                        ogps = 0.0\n                    else:\n                        px[pts == -1] = 0\n                        py[pts == -1] = 0\n                        dists_between_matches, dist_norm_coeffs = self.computeOgps_single_pair(\n                            dt, gt, py, px, pts\n                        )\n                        # Compute gps\n                        ogps_values = np.exp(\n                            -(dists_between_matches ** 2) / (2 * (dist_norm_coeffs ** 2))\n                        )\n                        #\n                        ogps = np.mean(ogps_values) if len(ogps_values) > 0 else 0.0\n                    ious[i, j] = ogps\n\n        gbb = [gt[\"bbox\"] for gt in g]\n        dbb = [dt[\"bbox\"] for dt in d]\n\n        # compute iou between each dt and gt region\n        iscrowd = [int(o.get(\"iscrowd\", 0)) for o in g]\n        ious_bb = maskUtils.iou(dbb, gbb, iscrowd)\n        return ious, ious_bb\n\n    def evaluateImg(self, imgId, catId, aRng, maxDet):\n        \"\"\"\n        perform evaluation for single category and image\n        :return: dict (single image results)\n        \"\"\"\n\n        p = self.params\n        if p.useCats:\n            gt = self._gts[imgId, catId]\n            dt = self._dts[imgId, catId]\n        else:\n            gt = [_ for cId in p.catIds for _ in self._gts[imgId, cId]]\n            dt = [_ for cId in p.catIds for _ in self._dts[imgId, cId]]\n        if len(gt) == 0 and len(dt) == 0:\n            return None\n\n        for g in gt:\n            # g['_ignore'] = g['ignore']\n            if g[\"ignore\"] or (g[\"area\"] < aRng[0] or g[\"area\"] > aRng[1]):\n                g[\"_ignore\"] = True\n            else:\n                g[\"_ignore\"] = False\n\n        # sort dt highest score first, sort gt ignore last\n        gtind = np.argsort([g[\"_ignore\"] for g in gt], kind=\"mergesort\")\n        gt = [gt[i] for i in gtind]\n        dtind = np.argsort([-d[\"score\"] for d in dt], kind=\"mergesort\")\n        dt = [dt[i] for i in dtind[0:maxDet]]\n        iscrowd = [int(o.get(\"iscrowd\", 0)) for o in gt]\n        # load computed ious\n        if p.iouType == \"densepose\":\n            # print('Checking the length', len(self.ious[imgId, catId]))\n            # if len(self.ious[imgId, catId]) == 0:\n            #    print(self.ious[imgId, catId])\n            ious = (\n                self.ious[imgId, catId][0][:, gtind]\n                if len(self.ious[imgId, catId]) > 0\n                else self.ious[imgId, catId]\n            )\n            ioubs = (\n                self.ious[imgId, catId][1][:, gtind]\n                if len(self.ious[imgId, catId]) > 0\n                else self.ious[imgId, catId]\n            )\n            if self._dpEvalMode in {DensePoseEvalMode.GPSM, DensePoseEvalMode.IOU}:\n                iousM = (\n                    self.real_ious[imgId, catId][:, gtind]\n                    if len(self.real_ious[imgId, catId]) > 0\n                    else self.real_ious[imgId, catId]\n                )\n        else:\n            ious = (\n                self.ious[imgId, catId][:, gtind]\n                if len(self.ious[imgId, catId]) > 0\n                else self.ious[imgId, catId]\n            )\n\n        T = len(p.iouThrs)\n        G = len(gt)\n        D = len(dt)\n        gtm = np.zeros((T, G))\n        dtm = np.zeros((T, D))\n        gtIg = np.array([g[\"_ignore\"] for g in gt])\n        dtIg = np.zeros((T, D))\n        if np.all(gtIg) and p.iouType == \"densepose\":\n            dtIg = np.logical_or(dtIg, True)\n\n        if len(ious) > 0:  # and not p.iouType == 'densepose':\n            for tind, t in enumerate(p.iouThrs):\n                for dind, d in enumerate(dt):\n                    # information about best match so far (m=-1 -> unmatched)\n                    iou = min([t, 1 - 1e-10])\n                    m = -1\n                    for gind, _g in enumerate(gt):\n                        # if this gt already matched, and not a crowd, continue\n                        if gtm[tind, gind] > 0 and not iscrowd[gind]:\n                            continue\n                        # if dt matched to reg gt, and on ignore gt, stop\n                        if m > -1 and gtIg[m] == 0 and gtIg[gind] == 1:\n                            break\n                        if p.iouType == \"densepose\":\n                            if self._dpEvalMode == DensePoseEvalMode.GPSM:\n                                new_iou = np.sqrt(iousM[dind, gind] * ious[dind, gind])\n                            elif self._dpEvalMode == DensePoseEvalMode.IOU:\n                                new_iou = iousM[dind, gind]\n                            elif self._dpEvalMode == DensePoseEvalMode.GPS:\n                                new_iou = ious[dind, gind]\n                        else:\n                            new_iou = ious[dind, gind]\n                        if new_iou < iou:\n                            continue\n                        if new_iou == 0.0:\n                            continue\n                        # if match successful and best so far, store appropriately\n                        iou = new_iou\n                        m = gind\n                    # if match made store id of match for both dt and gt\n                    if m == -1:\n                        continue\n                    dtIg[tind, dind] = gtIg[m]\n                    dtm[tind, dind] = gt[m][\"id\"]\n                    gtm[tind, m] = d[\"id\"]\n\n        if p.iouType == \"densepose\":\n            if not len(ioubs) == 0:\n                for dind, d in enumerate(dt):\n                    # information about best match so far (m=-1 -> unmatched)\n                    if dtm[tind, dind] == 0:\n                        ioub = 0.8\n                        m = -1\n                        for gind, _g in enumerate(gt):\n                            # if this gt already matched, and not a crowd, continue\n                            if gtm[tind, gind] > 0 and not iscrowd[gind]:\n                                continue\n                            # continue to next gt unless better match made\n                            if ioubs[dind, gind] < ioub:\n                                continue\n                            # if match successful and best so far, store appropriately\n                            ioub = ioubs[dind, gind]\n                            m = gind\n                            # if match made store id of match for both dt and gt\n                        if m > -1:\n                            dtIg[:, dind] = gtIg[m]\n                            if gtIg[m]:\n                                dtm[tind, dind] = gt[m][\"id\"]\n                                gtm[tind, m] = d[\"id\"]\n        # set unmatched detections outside of area range to ignore\n        a = np.array([d[\"area\"] < aRng[0] or d[\"area\"] > aRng[1] for d in dt]).reshape((1, len(dt)))\n        dtIg = np.logical_or(dtIg, np.logical_and(dtm == 0, np.repeat(a, T, 0)))\n        # store results for given image and category\n        # print('Done with the function', len(self.ious[imgId, catId]))\n        return {\n            \"image_id\": imgId,\n            \"category_id\": catId,\n            \"aRng\": aRng,\n            \"maxDet\": maxDet,\n            \"dtIds\": [d[\"id\"] for d in dt],\n            \"gtIds\": [g[\"id\"] for g in gt],\n            \"dtMatches\": dtm,\n            \"gtMatches\": gtm,\n            \"dtScores\": [d[\"score\"] for d in dt],\n            \"gtIgnore\": gtIg,\n            \"dtIgnore\": dtIg,\n        }\n\n    def accumulate(self, p=None):\n        \"\"\"\n        Accumulate per image evaluation results and store the result in self.eval\n        :param p: input params for evaluation\n        :return: None\n        \"\"\"\n        logger.info(\"Accumulating evaluation results...\")\n        tic = time.time()\n        if not self.evalImgs:\n            logger.info(\"Please run evaluate() first\")\n        # allows input customized parameters\n        if p is None:\n            p = self.params\n        p.catIds = p.catIds if p.useCats == 1 else [-1]\n        T = len(p.iouThrs)\n        R = len(p.recThrs)\n        K = len(p.catIds) if p.useCats else 1\n        A = len(p.areaRng)\n        M = len(p.maxDets)\n        precision = -(np.ones((T, R, K, A, M)))  # -1 for the precision of absent categories\n        recall = -(np.ones((T, K, A, M)))\n\n        # create dictionary for future indexing\n        logger.info(\"Categories: {}\".format(p.catIds))\n        _pe = self._paramsEval\n        catIds = _pe.catIds if _pe.useCats else [-1]\n        setK = set(catIds)\n        setA = set(map(tuple, _pe.areaRng))\n        setM = set(_pe.maxDets)\n        setI = set(_pe.imgIds)\n        # get inds to evaluate\n        k_list = [n for n, k in enumerate(p.catIds) if k in setK]\n        m_list = [m for n, m in enumerate(p.maxDets) if m in setM]\n        a_list = [n for n, a in enumerate(map(lambda x: tuple(x), p.areaRng)) if a in setA]\n        i_list = [n for n, i in enumerate(p.imgIds) if i in setI]\n        I0 = len(_pe.imgIds)\n        A0 = len(_pe.areaRng)\n        # retrieve E at each category, area range, and max number of detections\n        for k, k0 in enumerate(k_list):\n            Nk = k0 * A0 * I0\n            for a, a0 in enumerate(a_list):\n                Na = a0 * I0\n                for m, maxDet in enumerate(m_list):\n                    E = [self.evalImgs[Nk + Na + i] for i in i_list]\n                    E = [e for e in E if e is not None]\n                    if len(E) == 0:\n                        continue\n                    dtScores = np.concatenate([e[\"dtScores\"][0:maxDet] for e in E])\n\n                    # different sorting method generates slightly different results.\n                    # mergesort is used to be consistent as Matlab implementation.\n                    inds = np.argsort(-dtScores, kind=\"mergesort\")\n\n                    dtm = np.concatenate([e[\"dtMatches\"][:, 0:maxDet] for e in E], axis=1)[:, inds]\n                    dtIg = np.concatenate([e[\"dtIgnore\"][:, 0:maxDet] for e in E], axis=1)[:, inds]\n                    gtIg = np.concatenate([e[\"gtIgnore\"] for e in E])\n                    npig = np.count_nonzero(gtIg == 0)\n                    if npig == 0:\n                        continue\n                    tps = np.logical_and(dtm, np.logical_not(dtIg))\n                    fps = np.logical_and(np.logical_not(dtm), np.logical_not(dtIg))\n                    tp_sum = np.cumsum(tps, axis=1).astype(dtype=np.float)\n                    fp_sum = np.cumsum(fps, axis=1).astype(dtype=np.float)\n                    for t, (tp, fp) in enumerate(zip(tp_sum, fp_sum)):\n                        tp = np.array(tp)\n                        fp = np.array(fp)\n                        nd = len(tp)\n                        rc = tp / npig\n                        pr = tp / (fp + tp + np.spacing(1))\n                        q = np.zeros((R,))\n\n                        if nd:\n                            recall[t, k, a, m] = rc[-1]\n                        else:\n                            recall[t, k, a, m] = 0\n\n                        # numpy is slow without cython optimization for accessing elements\n                        # use python array gets significant speed improvement\n                        pr = pr.tolist()\n                        q = q.tolist()\n\n                        for i in range(nd - 1, 0, -1):\n                            if pr[i] > pr[i - 1]:\n                                pr[i - 1] = pr[i]\n\n                        inds = np.searchsorted(rc, p.recThrs, side=\"left\")\n                        try:\n                            for ri, pi in enumerate(inds):\n                                q[ri] = pr[pi]\n                        except Exception:\n                            pass\n                        precision[t, :, k, a, m] = np.array(q)\n        logger.info(\n            \"Final: max precision {}, min precision {}\".format(np.max(precision), np.min(precision))\n        )\n        self.eval = {\n            \"params\": p,\n            \"counts\": [T, R, K, A, M],\n            \"date\": datetime.datetime.now().strftime(\"%Y-%m-%d %H:%M:%S\"),\n            \"precision\": precision,\n            \"recall\": recall,\n        }\n        toc = time.time()\n        logger.info(\"DONE (t={:0.2f}s).\".format(toc - tic))\n\n    def summarize(self):\n        \"\"\"\n        Compute and display summary metrics for evaluation results.\n        Note this function can *only* be applied on the default parameter setting\n        \"\"\"\n\n        def _summarize(ap=1, iouThr=None, areaRng=\"all\", maxDets=100):\n            p = self.params\n            iStr = \" {:<18} {} @[ {}={:<9} | area={:>6s} | maxDets={:>3d} ] = {:0.3f}\"\n            titleStr = \"Average Precision\" if ap == 1 else \"Average Recall\"\n            typeStr = \"(AP)\" if ap == 1 else \"(AR)\"\n            measure = \"IoU\"\n            if self.params.iouType == \"keypoints\":\n                measure = \"OKS\"\n            elif self.params.iouType == \"densepose\":\n                measure = \"OGPS\"\n            iouStr = (\n                \"{:0.2f}:{:0.2f}\".format(p.iouThrs[0], p.iouThrs[-1])\n                if iouThr is None\n                else \"{:0.2f}\".format(iouThr)\n            )\n\n            aind = [i for i, aRng in enumerate(p.areaRngLbl) if aRng == areaRng]\n            mind = [i for i, mDet in enumerate(p.maxDets) if mDet == maxDets]\n            if ap == 1:\n                # dimension of precision: [TxRxKxAxM]\n                s = self.eval[\"precision\"]\n                # IoU\n                if iouThr is not None:\n                    t = np.where(np.abs(iouThr - p.iouThrs) < 0.001)[0]\n                    s = s[t]\n                s = s[:, :, :, aind, mind]\n            else:\n                # dimension of recall: [TxKxAxM]\n                s = self.eval[\"recall\"]\n                if iouThr is not None:\n                    t = np.where(np.abs(iouThr - p.iouThrs) < 0.001)[0]\n                    s = s[t]\n                s = s[:, :, aind, mind]\n            if len(s[s > -1]) == 0:\n                mean_s = -1\n            else:\n                mean_s = np.mean(s[s > -1])\n            logger.info(iStr.format(titleStr, typeStr, measure, iouStr, areaRng, maxDets, mean_s))\n            return mean_s\n\n        def _summarizeDets():\n            stats = np.zeros((12,))\n            stats[0] = _summarize(1)\n            stats[1] = _summarize(1, iouThr=0.5, maxDets=self.params.maxDets[2])\n            stats[2] = _summarize(1, iouThr=0.75, maxDets=self.params.maxDets[2])\n            stats[3] = _summarize(1, areaRng=\"small\", maxDets=self.params.maxDets[2])\n            stats[4] = _summarize(1, areaRng=\"medium\", maxDets=self.params.maxDets[2])\n            stats[5] = _summarize(1, areaRng=\"large\", maxDets=self.params.maxDets[2])\n            stats[6] = _summarize(0, maxDets=self.params.maxDets[0])\n            stats[7] = _summarize(0, maxDets=self.params.maxDets[1])\n            stats[8] = _summarize(0, maxDets=self.params.maxDets[2])\n            stats[9] = _summarize(0, areaRng=\"small\", maxDets=self.params.maxDets[2])\n            stats[10] = _summarize(0, areaRng=\"medium\", maxDets=self.params.maxDets[2])\n            stats[11] = _summarize(0, areaRng=\"large\", maxDets=self.params.maxDets[2])\n            return stats\n\n        def _summarizeKps():\n            stats = np.zeros((10,))\n            stats[0] = _summarize(1, maxDets=20)\n            stats[1] = _summarize(1, maxDets=20, iouThr=0.5)\n            stats[2] = _summarize(1, maxDets=20, iouThr=0.75)\n            stats[3] = _summarize(1, maxDets=20, areaRng=\"medium\")\n            stats[4] = _summarize(1, maxDets=20, areaRng=\"large\")\n            stats[5] = _summarize(0, maxDets=20)\n            stats[6] = _summarize(0, maxDets=20, iouThr=0.5)\n            stats[7] = _summarize(0, maxDets=20, iouThr=0.75)\n            stats[8] = _summarize(0, maxDets=20, areaRng=\"medium\")\n            stats[9] = _summarize(0, maxDets=20, areaRng=\"large\")\n            return stats\n\n        def _summarizeUvs():\n            stats = [_summarize(1, maxDets=self.params.maxDets[0])]\n            min_threshold = self.params.iouThrs.min()\n            if min_threshold <= 0.201:\n                stats += [_summarize(1, maxDets=self.params.maxDets[0], iouThr=0.2)]\n            if min_threshold <= 0.301:\n                stats += [_summarize(1, maxDets=self.params.maxDets[0], iouThr=0.3)]\n            if min_threshold <= 0.401:\n                stats += [_summarize(1, maxDets=self.params.maxDets[0], iouThr=0.4)]\n            stats += [\n                _summarize(1, maxDets=self.params.maxDets[0], iouThr=0.5),\n                _summarize(1, maxDets=self.params.maxDets[0], iouThr=0.75),\n                _summarize(1, maxDets=self.params.maxDets[0], areaRng=\"medium\"),\n                _summarize(1, maxDets=self.params.maxDets[0], areaRng=\"large\"),\n                _summarize(0, maxDets=self.params.maxDets[0]),\n                _summarize(0, maxDets=self.params.maxDets[0], iouThr=0.5),\n                _summarize(0, maxDets=self.params.maxDets[0], iouThr=0.75),\n                _summarize(0, maxDets=self.params.maxDets[0], areaRng=\"medium\"),\n                _summarize(0, maxDets=self.params.maxDets[0], areaRng=\"large\"),\n            ]\n            return np.array(stats)\n\n        def _summarizeUvsOld():\n            stats = np.zeros((18,))\n            stats[0] = _summarize(1, maxDets=self.params.maxDets[0])\n            stats[1] = _summarize(1, maxDets=self.params.maxDets[0], iouThr=0.5)\n            stats[2] = _summarize(1, maxDets=self.params.maxDets[0], iouThr=0.55)\n            stats[3] = _summarize(1, maxDets=self.params.maxDets[0], iouThr=0.60)\n            stats[4] = _summarize(1, maxDets=self.params.maxDets[0], iouThr=0.65)\n            stats[5] = _summarize(1, maxDets=self.params.maxDets[0], iouThr=0.70)\n            stats[6] = _summarize(1, maxDets=self.params.maxDets[0], iouThr=0.75)\n            stats[7] = _summarize(1, maxDets=self.params.maxDets[0], iouThr=0.80)\n            stats[8] = _summarize(1, maxDets=self.params.maxDets[0], iouThr=0.85)\n            stats[9] = _summarize(1, maxDets=self.params.maxDets[0], iouThr=0.90)\n            stats[10] = _summarize(1, maxDets=self.params.maxDets[0], iouThr=0.95)\n            stats[11] = _summarize(1, maxDets=self.params.maxDets[0], areaRng=\"medium\")\n            stats[12] = _summarize(1, maxDets=self.params.maxDets[0], areaRng=\"large\")\n            stats[13] = _summarize(0, maxDets=self.params.maxDets[0])\n            stats[14] = _summarize(0, maxDets=self.params.maxDets[0], iouThr=0.5)\n            stats[15] = _summarize(0, maxDets=self.params.maxDets[0], iouThr=0.75)\n            stats[16] = _summarize(0, maxDets=self.params.maxDets[0], areaRng=\"medium\")\n            stats[17] = _summarize(0, maxDets=self.params.maxDets[0], areaRng=\"large\")\n            return stats\n\n        if not self.eval:\n            raise Exception(\"Please run accumulate() first\")\n        iouType = self.params.iouType\n        if iouType in [\"segm\", \"bbox\"]:\n            summarize = _summarizeDets\n        elif iouType in [\"keypoints\"]:\n            summarize = _summarizeKps\n        elif iouType in [\"densepose\"]:\n            summarize = _summarizeUvs\n        self.stats = summarize()\n\n    def __str__(self):\n        self.summarize()\n\n    # ================ functions for dense pose ==============================\n    def findAllClosestVertsUV(self, U_points, V_points, Index_points):\n        ClosestVerts = np.ones(Index_points.shape) * -1\n        for i in np.arange(24):\n            #\n            if (i + 1) in Index_points:\n                UVs = np.array(\n                    [U_points[Index_points == (i + 1)], V_points[Index_points == (i + 1)]]\n                )\n                Current_Part_UVs = self.Part_UVs[i]\n                Current_Part_ClosestVertInds = self.Part_ClosestVertInds[i]\n                D = ssd.cdist(Current_Part_UVs.transpose(), UVs.transpose()).squeeze()\n                ClosestVerts[Index_points == (i + 1)] = Current_Part_ClosestVertInds[\n                    np.argmin(D, axis=0)\n                ]\n        ClosestVertsTransformed = self.PDIST_transform[ClosestVerts.astype(int) - 1]\n        ClosestVertsTransformed[ClosestVerts < 0] = 0\n        return ClosestVertsTransformed\n\n    def findClosestVertsCse(self, embedding, py, px, mask, mesh_name):\n        mesh_vertex_embeddings = self.embedder(mesh_name)\n        pixel_embeddings = embedding[:, py, px].t().to(device=\"cuda\")\n        mask_vals = mask[py, px]\n        edm = squared_euclidean_distance_matrix(pixel_embeddings, mesh_vertex_embeddings)\n        vertex_indices = edm.argmin(dim=1).cpu()\n        vertex_indices[mask_vals <= 0] = -1\n        return vertex_indices\n\n    def findAllClosestVertsGT(self, gt):\n        #\n        I_gt = np.array(gt[\"dp_I\"])\n        U_gt = np.array(gt[\"dp_U\"])\n        V_gt = np.array(gt[\"dp_V\"])\n        #\n        # print(I_gt)\n        #\n        ClosestVertsGT = np.ones(I_gt.shape) * -1\n        for i in np.arange(24):\n            if (i + 1) in I_gt:\n                UVs = np.array([U_gt[I_gt == (i + 1)], V_gt[I_gt == (i + 1)]])\n                Current_Part_UVs = self.Part_UVs[i]\n                Current_Part_ClosestVertInds = self.Part_ClosestVertInds[i]\n                D = ssd.cdist(Current_Part_UVs.transpose(), UVs.transpose()).squeeze()\n                ClosestVertsGT[I_gt == (i + 1)] = Current_Part_ClosestVertInds[np.argmin(D, axis=0)]\n        #\n        ClosestVertsGTTransformed = self.PDIST_transform[ClosestVertsGT.astype(int) - 1]\n        ClosestVertsGTTransformed[ClosestVertsGT < 0] = 0\n        return ClosestVertsGT, ClosestVertsGTTransformed\n\n    def getDistancesCse(self, cVertsGT, cVerts, mesh_name):\n        geodists_vertices = torch.ones_like(cVertsGT) * float(\"inf\")\n        selected = (cVertsGT >= 0) * (cVerts >= 0)\n        mesh = create_mesh(mesh_name, \"cpu\")\n        geodists_vertices[selected] = mesh.geodists[cVertsGT[selected], cVerts[selected]]\n        return geodists_vertices.numpy()\n\n    def getDistancesUV(self, cVertsGT, cVerts):\n        #\n        n = 27554\n        dists = []\n        for d in range(len(cVertsGT)):\n            if cVertsGT[d] > 0:\n                if cVerts[d] > 0:\n                    i = cVertsGT[d] - 1\n                    j = cVerts[d] - 1\n                    if j == i:\n                        dists.append(0)\n                    elif j > i:\n                        ccc = i\n                        i = j\n                        j = ccc\n                        i = n - i - 1\n                        j = n - j - 1\n                        k = (n * (n - 1) / 2) - (n - i) * ((n - i) - 1) / 2 + j - i - 1\n                        k = (n * n - n) / 2 - k - 1\n                        dists.append(self.Pdist_matrix[int(k)][0])\n                    else:\n                        i = n - i - 1\n                        j = n - j - 1\n                        k = (n * (n - 1) / 2) - (n - i) * ((n - i) - 1) / 2 + j - i - 1\n                        k = (n * n - n) / 2 - k - 1\n                        dists.append(self.Pdist_matrix[int(k)][0])\n                else:\n                    dists.append(np.inf)\n        return np.atleast_1d(np.array(dists).squeeze())\n\n\nclass Params:\n    \"\"\"\n    Params for coco evaluation api\n    \"\"\"\n\n    def setDetParams(self):\n        self.imgIds = []\n        self.catIds = []\n        # np.arange causes trouble.  the data point on arange is slightly larger than the true value\n        self.iouThrs = np.linspace(0.5, 0.95, int(np.round((0.95 - 0.5) / 0.05)) + 1, endpoint=True)\n        self.recThrs = np.linspace(0.0, 1.00, int(np.round((1.00 - 0.0) / 0.01)) + 1, endpoint=True)\n        self.maxDets = [1, 10, 100]\n        self.areaRng = [\n            [0 ** 2, 1e5 ** 2],\n            [0 ** 2, 32 ** 2],\n            [32 ** 2, 96 ** 2],\n            [96 ** 2, 1e5 ** 2],\n        ]\n        self.areaRngLbl = [\"all\", \"small\", \"medium\", \"large\"]\n        self.useCats = 1\n\n    def setKpParams(self):\n        self.imgIds = []\n        self.catIds = []\n        # np.arange causes trouble.  the data point on arange is slightly larger than the true value\n        self.iouThrs = np.linspace(0.5, 0.95, np.round((0.95 - 0.5) / 0.05) + 1, endpoint=True)\n        self.recThrs = np.linspace(0.0, 1.00, np.round((1.00 - 0.0) / 0.01) + 1, endpoint=True)\n        self.maxDets = [20]\n        self.areaRng = [[0 ** 2, 1e5 ** 2], [32 ** 2, 96 ** 2], [96 ** 2, 1e5 ** 2]]\n        self.areaRngLbl = [\"all\", \"medium\", \"large\"]\n        self.useCats = 1\n\n    def setUvParams(self):\n        self.imgIds = []\n        self.catIds = []\n        self.iouThrs = np.linspace(0.5, 0.95, int(np.round((0.95 - 0.5) / 0.05)) + 1, endpoint=True)\n        self.recThrs = np.linspace(0.0, 1.00, int(np.round((1.00 - 0.0) / 0.01)) + 1, endpoint=True)\n        self.maxDets = [20]\n        self.areaRng = [[0 ** 2, 1e5 ** 2], [32 ** 2, 96 ** 2], [96 ** 2, 1e5 ** 2]]\n        self.areaRngLbl = [\"all\", \"medium\", \"large\"]\n        self.useCats = 1\n\n    def __init__(self, iouType=\"segm\"):\n        if iouType == \"segm\" or iouType == \"bbox\":\n            self.setDetParams()\n        elif iouType == \"keypoints\":\n            self.setKpParams()\n        elif iouType == \"densepose\":\n            self.setUvParams()\n        else:\n            raise Exception(\"iouType not supported\")\n        self.iouType = iouType\n        # useSegm is deprecated\n        self.useSegm = None\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/evaluation/evaluator.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport contextlib\nimport copy\nimport io\nimport itertools\nimport logging\nimport numpy as np\nimport os\nfrom collections import OrderedDict\nfrom typing import Dict, Iterable, List, Optional\nimport pycocotools.mask as mask_utils\nimport torch\nfrom pycocotools.coco import COCO\nfrom tabulate import tabulate\n\nfrom detectron2.config import CfgNode\nfrom detectron2.data import MetadataCatalog\nfrom detectron2.evaluation import DatasetEvaluator\nfrom detectron2.structures import BoxMode\nfrom detectron2.utils.comm import gather, get_rank, is_main_process, synchronize\nfrom detectron2.utils.file_io import PathManager\nfrom detectron2.utils.logger import create_small_table\n\nfrom densepose.converters import ToChartResultConverter, ToMaskConverter\nfrom densepose.data.datasets.coco import maybe_filter_and_map_categories_cocoapi\nfrom densepose.structures import (\n    DensePoseChartPredictorOutput,\n    DensePoseEmbeddingPredictorOutput,\n    quantize_densepose_chart_result,\n)\n\nfrom .densepose_coco_evaluation import DensePoseCocoEval, DensePoseEvalMode\nfrom .mesh_alignment_evaluator import MeshAlignmentEvaluator\nfrom .tensor_storage import (\n    SingleProcessFileTensorStorage,\n    SingleProcessRamTensorStorage,\n    SingleProcessTensorStorage,\n    SizeData,\n    storage_gather,\n)\n\n\nclass DensePoseCOCOEvaluator(DatasetEvaluator):\n    def __init__(\n        self,\n        dataset_name,\n        distributed,\n        output_dir=None,\n        evaluator_type: str = \"iuv\",\n        min_iou_threshold: float = 0.5,\n        storage: Optional[SingleProcessTensorStorage] = None,\n        embedder=None,\n        should_evaluate_mesh_alignment: bool = False,\n        mesh_alignment_mesh_names: Optional[List[str]] = None,\n    ):\n        self._embedder = embedder\n        self._distributed = distributed\n        self._output_dir = output_dir\n        self._evaluator_type = evaluator_type\n        self._storage = storage\n        self._should_evaluate_mesh_alignment = should_evaluate_mesh_alignment\n\n        assert not (\n            should_evaluate_mesh_alignment and embedder is None\n        ), \"Mesh alignment evaluation is activated, but no vertex embedder provided!\"\n        if should_evaluate_mesh_alignment:\n            self._mesh_alignment_evaluator = MeshAlignmentEvaluator(\n                embedder,\n                mesh_alignment_mesh_names,\n            )\n\n        self._cpu_device = torch.device(\"cpu\")\n        self._logger = logging.getLogger(__name__)\n\n        self._metadata = MetadataCatalog.get(dataset_name)\n        self._min_threshold = min_iou_threshold\n        json_file = PathManager.get_local_path(self._metadata.json_file)\n        with contextlib.redirect_stdout(io.StringIO()):\n            self._coco_api = COCO(json_file)\n        maybe_filter_and_map_categories_cocoapi(dataset_name, self._coco_api)\n\n    def reset(self):\n        self._predictions = []\n\n    def process(self, inputs, outputs):\n        \"\"\"\n        Args:\n            inputs: the inputs to a COCO model (e.g., GeneralizedRCNN).\n                It is a list of dict. Each dict corresponds to an image and\n                contains keys like \"height\", \"width\", \"file_name\", \"image_id\".\n            outputs: the outputs of a COCO model. It is a list of dicts with key\n                \"instances\" that contains :class:`Instances`.\n                The :class:`Instances` object needs to have `densepose` field.\n        \"\"\"\n        for input, output in zip(inputs, outputs):\n            instances = output[\"instances\"].to(self._cpu_device)\n            if not instances.has(\"pred_densepose\"):\n                continue\n            prediction_list = prediction_to_dict(\n                instances,\n                input[\"image_id\"],\n                self._embedder,\n                self._metadata.class_to_mesh_name,\n                self._storage is not None,\n            )\n            if self._storage is not None:\n                for prediction_dict in prediction_list:\n                    dict_to_store = {}\n                    for field_name in self._storage.data_schema:\n                        dict_to_store[field_name] = prediction_dict[field_name]\n                    record_id = self._storage.put(dict_to_store)\n                    prediction_dict[\"record_id\"] = record_id\n                    prediction_dict[\"rank\"] = get_rank()\n                    for field_name in self._storage.data_schema:\n                        del prediction_dict[field_name]\n            self._predictions.extend(prediction_list)\n\n    def evaluate(self, img_ids=None):\n        if self._distributed:\n            synchronize()\n            predictions = gather(self._predictions)\n            predictions = list(itertools.chain(*predictions))\n        else:\n            predictions = self._predictions\n\n        multi_storage = storage_gather(self._storage) if self._storage is not None else None\n\n        if not is_main_process():\n            return\n        return copy.deepcopy(self._eval_predictions(predictions, multi_storage, img_ids))\n\n    def _eval_predictions(self, predictions, multi_storage=None, img_ids=None):\n        \"\"\"\n        Evaluate predictions on densepose.\n        Return results with the metrics of the tasks.\n        \"\"\"\n        self._logger.info(\"Preparing results for COCO format ...\")\n\n        if self._output_dir:\n            PathManager.mkdirs(self._output_dir)\n            file_path = os.path.join(self._output_dir, \"coco_densepose_predictions.pth\")\n            with PathManager.open(file_path, \"wb\") as f:\n                torch.save(predictions, f)\n\n        self._logger.info(\"Evaluating predictions ...\")\n        res = OrderedDict()\n        results_gps, results_gpsm, results_segm = _evaluate_predictions_on_coco(\n            self._coco_api,\n            predictions,\n            multi_storage,\n            self._embedder,\n            class_names=self._metadata.get(\"thing_classes\"),\n            min_threshold=self._min_threshold,\n            img_ids=img_ids,\n        )\n        res[\"densepose_gps\"] = results_gps\n        res[\"densepose_gpsm\"] = results_gpsm\n        res[\"densepose_segm\"] = results_segm\n        if self._should_evaluate_mesh_alignment:\n            res[\"densepose_mesh_alignment\"] = self._evaluate_mesh_alignment()\n        return res\n\n    def _evaluate_mesh_alignment(self):\n        self._logger.info(\"Mesh alignment evaluation ...\")\n        mean_ge, mean_gps, per_mesh_metrics = self._mesh_alignment_evaluator.evaluate()\n        results = {\n            \"GE\": mean_ge * 100,\n            \"GPS\": mean_gps * 100,\n        }\n        mesh_names = set()\n        for metric_name in per_mesh_metrics:\n            for mesh_name, value in per_mesh_metrics[metric_name].items():\n                results[f\"{metric_name}-{mesh_name}\"] = value * 100\n                mesh_names.add(mesh_name)\n        self._print_mesh_alignment_results(results, mesh_names)\n        return results\n\n    def _print_mesh_alignment_results(self, results: Dict[str, float], mesh_names: Iterable[str]):\n        self._logger.info(\"Evaluation results for densepose, mesh alignment:\")\n        self._logger.info(f'| {\"Mesh\":13s} | {\"GErr\":7s} | {\"GPS\":7s} |')\n        self._logger.info(\"| :-----------: | :-----: | :-----: |\")\n        for mesh_name in mesh_names:\n            ge_key = f\"GE-{mesh_name}\"\n            ge_str = f\"{results[ge_key]:.4f}\" if ge_key in results else \" \"\n            gps_key = f\"GPS-{mesh_name}\"\n            gps_str = f\"{results[gps_key]:.4f}\" if gps_key in results else \" \"\n            self._logger.info(f\"| {mesh_name:13s} | {ge_str:7s} | {gps_str:7s} |\")\n        self._logger.info(\"| :-------------------------------: |\")\n        ge_key = \"GE\"\n        ge_str = f\"{results[ge_key]:.4f}\" if ge_key in results else \" \"\n        gps_key = \"GPS\"\n        gps_str = f\"{results[gps_key]:.4f}\" if gps_key in results else \" \"\n        self._logger.info(f'| {\"MEAN\":13s} | {ge_str:7s} | {gps_str:7s} |')\n\n\ndef prediction_to_dict(instances, img_id, embedder, class_to_mesh_name, use_storage):\n    \"\"\"\n    Args:\n        instances (Instances): the output of the model\n        img_id (str): the image id in COCO\n\n    Returns:\n        list[dict]: the results in densepose evaluation format\n    \"\"\"\n    scores = instances.scores.tolist()\n    classes = instances.pred_classes.tolist()\n    raw_boxes_xywh = BoxMode.convert(\n        instances.pred_boxes.tensor.clone(), BoxMode.XYXY_ABS, BoxMode.XYWH_ABS\n    )\n\n    if isinstance(instances.pred_densepose, DensePoseEmbeddingPredictorOutput):\n        results_densepose = densepose_cse_predictions_to_dict(\n            instances, embedder, class_to_mesh_name, use_storage\n        )\n    elif isinstance(instances.pred_densepose, DensePoseChartPredictorOutput):\n        if not use_storage:\n            results_densepose = densepose_chart_predictions_to_dict(instances)\n        else:\n            results_densepose = densepose_chart_predictions_to_storage_dict(instances)\n\n    results = []\n    for k in range(len(instances)):\n        result = {\n            \"image_id\": img_id,\n            \"category_id\": classes[k],\n            \"bbox\": raw_boxes_xywh[k].tolist(),\n            \"score\": scores[k],\n        }\n        results.append({**result, **results_densepose[k]})\n    return results\n\n\ndef densepose_chart_predictions_to_dict(instances):\n    segmentations = ToMaskConverter.convert(\n        instances.pred_densepose, instances.pred_boxes, instances.image_size\n    )\n\n    results = []\n    for k in range(len(instances)):\n        densepose_results_quantized = quantize_densepose_chart_result(\n            ToChartResultConverter.convert(instances.pred_densepose[k], instances.pred_boxes[k])\n        )\n        densepose_results_quantized.labels_uv_uint8 = (\n            densepose_results_quantized.labels_uv_uint8.cpu()\n        )\n        segmentation = segmentations.tensor[k]\n        segmentation_encoded = mask_utils.encode(\n            np.require(segmentation.numpy(), dtype=np.uint8, requirements=[\"F\"])\n        )\n        segmentation_encoded[\"counts\"] = segmentation_encoded[\"counts\"].decode(\"utf-8\")\n        result = {\n            \"densepose\": densepose_results_quantized,\n            \"segmentation\": segmentation_encoded,\n        }\n        results.append(result)\n    return results\n\n\ndef densepose_chart_predictions_to_storage_dict(instances):\n    results = []\n    for k in range(len(instances)):\n        densepose_predictor_output = instances.pred_densepose[k]\n        result = {\n            \"coarse_segm\": densepose_predictor_output.coarse_segm.squeeze(0).cpu(),\n            \"fine_segm\": densepose_predictor_output.fine_segm.squeeze(0).cpu(),\n            \"u\": densepose_predictor_output.u.squeeze(0).cpu(),\n            \"v\": densepose_predictor_output.v.squeeze(0).cpu(),\n        }\n        results.append(result)\n    return results\n\n\ndef densepose_cse_predictions_to_dict(instances, embedder, class_to_mesh_name, use_storage):\n    results = []\n    for k in range(len(instances)):\n        cse = instances.pred_densepose[k]\n        results.append(\n            {\n                \"coarse_segm\": cse.coarse_segm[0].cpu(),\n                \"embedding\": cse.embedding[0].cpu(),\n            }\n        )\n    return results\n\n\ndef _evaluate_predictions_on_coco(\n    coco_gt,\n    coco_results,\n    multi_storage=None,\n    embedder=None,\n    class_names=None,\n    min_threshold=0.5,\n    img_ids=None,\n):\n    logger = logging.getLogger(__name__)\n\n    densepose_metrics = _get_densepose_metrics(min_threshold)\n    if len(coco_results) == 0:  # cocoapi does not handle empty results very well\n        logger.warn(\"No predictions from the model! Set scores to -1\")\n        results_gps = {metric: -1 for metric in densepose_metrics}\n        results_gpsm = {metric: -1 for metric in densepose_metrics}\n        results_segm = {metric: -1 for metric in densepose_metrics}\n        return results_gps, results_gpsm, results_segm\n\n    coco_dt = coco_gt.loadRes(coco_results)\n\n    results = []\n    for eval_mode_name in [\"GPS\", \"GPSM\", \"IOU\"]:\n        eval_mode = getattr(DensePoseEvalMode, eval_mode_name)\n        coco_eval = DensePoseCocoEval(\n            coco_gt, coco_dt, \"densepose\", multi_storage, embedder, dpEvalMode=eval_mode\n        )\n        result = _derive_results_from_coco_eval(\n            coco_eval, eval_mode_name, densepose_metrics, class_names, min_threshold, img_ids\n        )\n        results.append(result)\n    return results\n\n\ndef _get_densepose_metrics(min_threshold=0.5):\n    metrics = [\"AP\"]\n    if min_threshold <= 0.201:\n        metrics += [\"AP20\"]\n    if min_threshold <= 0.301:\n        metrics += [\"AP30\"]\n    if min_threshold <= 0.401:\n        metrics += [\"AP40\"]\n    metrics.extend([\"AP50\", \"AP75\", \"APm\", \"APl\", \"AR\", \"AR50\", \"AR75\", \"ARm\", \"ARl\"])\n    return metrics\n\n\ndef _derive_results_from_coco_eval(\n    coco_eval, eval_mode_name, metrics, class_names, min_threshold, img_ids\n):\n    if img_ids is not None:\n        coco_eval.params.imgIds = img_ids\n    coco_eval.params.iouThrs = np.linspace(\n        min_threshold, 0.95, int(np.round((0.95 - min_threshold) / 0.05)) + 1, endpoint=True\n    )\n    coco_eval.evaluate()\n    coco_eval.accumulate()\n    coco_eval.summarize()\n    results = {metric: float(coco_eval.stats[idx] * 100) for idx, metric in enumerate(metrics)}\n    logger = logging.getLogger(__name__)\n    logger.info(\n        f\"Evaluation results for densepose, {eval_mode_name} metric: \\n\"\n        + create_small_table(results)\n    )\n    if class_names is None or len(class_names) <= 1:\n        return results\n\n    # Compute per-category AP, the same way as it is done in D2\n    # (see detectron2/evaluation/coco_evaluation.py):\n    precisions = coco_eval.eval[\"precision\"]\n    # precision has dims (iou, recall, cls, area range, max dets)\n    assert len(class_names) == precisions.shape[2]\n\n    results_per_category = []\n    for idx, name in enumerate(class_names):\n        # area range index 0: all area ranges\n        # max dets index -1: typically 100 per image\n        precision = precisions[:, :, idx, 0, -1]\n        precision = precision[precision > -1]\n        ap = np.mean(precision) if precision.size else float(\"nan\")\n        results_per_category.append((f\"{name}\", float(ap * 100)))\n\n    # tabulate it\n    n_cols = min(6, len(results_per_category) * 2)\n    results_flatten = list(itertools.chain(*results_per_category))\n    results_2d = itertools.zip_longest(*[results_flatten[i::n_cols] for i in range(n_cols)])\n    table = tabulate(\n        results_2d,\n        tablefmt=\"pipe\",\n        floatfmt=\".3f\",\n        headers=[\"category\", \"AP\"] * (n_cols // 2),\n        numalign=\"left\",\n    )\n    logger.info(f\"Per-category {eval_mode_name} AP: \\n\" + table)\n\n    results.update({\"AP-\" + name: ap for name, ap in results_per_category})\n    return results\n\n\ndef build_densepose_evaluator_storage(cfg: CfgNode, output_folder: str):\n    storage_spec = cfg.DENSEPOSE_EVALUATION.STORAGE\n    if storage_spec == \"none\":\n        return None\n    evaluator_type = cfg.DENSEPOSE_EVALUATION.TYPE\n    # common output tensor sizes\n    hout = cfg.MODEL.ROI_DENSEPOSE_HEAD.HEATMAP_SIZE\n    wout = cfg.MODEL.ROI_DENSEPOSE_HEAD.HEATMAP_SIZE\n    n_csc = cfg.MODEL.ROI_DENSEPOSE_HEAD.NUM_COARSE_SEGM_CHANNELS\n    # specific output tensors\n    if evaluator_type == \"iuv\":\n        n_fsc = cfg.MODEL.ROI_DENSEPOSE_HEAD.NUM_PATCHES + 1\n        schema = {\n            \"coarse_segm\": SizeData(dtype=\"float32\", shape=(n_csc, hout, wout)),\n            \"fine_segm\": SizeData(dtype=\"float32\", shape=(n_fsc, hout, wout)),\n            \"u\": SizeData(dtype=\"float32\", shape=(n_fsc, hout, wout)),\n            \"v\": SizeData(dtype=\"float32\", shape=(n_fsc, hout, wout)),\n        }\n    elif evaluator_type == \"cse\":\n        embed_size = cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBED_SIZE\n        schema = {\n            \"coarse_segm\": SizeData(dtype=\"float32\", shape=(n_csc, hout, wout)),\n            \"embedding\": SizeData(dtype=\"float32\", shape=(embed_size, hout, wout)),\n        }\n    else:\n        raise ValueError(f\"Unknown evaluator type: {evaluator_type}\")\n    # storage types\n    if storage_spec == \"ram\":\n        storage = SingleProcessRamTensorStorage(schema, io.BytesIO())\n    elif storage_spec == \"file\":\n        fpath = os.path.join(output_folder, f\"DensePoseEvaluatorStorage.{get_rank()}.bin\")\n        PathManager.mkdirs(output_folder)\n        storage = SingleProcessFileTensorStorage(schema, fpath, \"wb\")\n    else:\n        raise ValueError(f\"Unknown storage specification: {storage_spec}\")\n    return storage\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/evaluation/mesh_alignment_evaluator.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nimport json\nimport logging\nfrom typing import List, Optional\nimport torch\nfrom torch import nn\n\nfrom detectron2.utils.file_io import PathManager\n\nfrom densepose.structures.mesh import create_mesh\n\n\nclass MeshAlignmentEvaluator:\n    \"\"\"\n    Class for evaluation of 3D mesh alignment based on the learned vertex embeddings\n    \"\"\"\n\n    def __init__(self, embedder: nn.Module, mesh_names: Optional[List[str]]):\n        self.embedder = embedder\n        # use the provided mesh names if not None and not an empty list\n        self.mesh_names = mesh_names if mesh_names else embedder.mesh_names\n        self.logger = logging.getLogger(__name__)\n        with PathManager.open(\n            \"https://dl.fbaipublicfiles.com/densepose/data/cse/mesh_keyvertices_v0.json\", \"r\"\n        ) as f:\n            self.mesh_keyvertices = json.load(f)\n\n    def evaluate(self):\n        ge_per_mesh = {}\n        gps_per_mesh = {}\n        for mesh_name_1 in self.mesh_names:\n            avg_errors = []\n            avg_gps = []\n            embeddings_1 = self.embedder(mesh_name_1)\n            keyvertices_1 = self.mesh_keyvertices[mesh_name_1]\n            keyvertex_names_1 = list(keyvertices_1.keys())\n            keyvertex_indices_1 = [keyvertices_1[name] for name in keyvertex_names_1]\n            for mesh_name_2 in self.mesh_names:\n                if mesh_name_1 == mesh_name_2:\n                    continue\n                embeddings_2 = self.embedder(mesh_name_2)\n                keyvertices_2 = self.mesh_keyvertices[mesh_name_2]\n                sim_matrix_12 = embeddings_1[keyvertex_indices_1].mm(embeddings_2.T)\n                vertices_2_matching_keyvertices_1 = sim_matrix_12.argmax(axis=1)\n                mesh_2 = create_mesh(mesh_name_2, embeddings_2.device)\n                geodists = mesh_2.geodists[\n                    vertices_2_matching_keyvertices_1,\n                    [keyvertices_2[name] for name in keyvertex_names_1],\n                ]\n                Current_Mean_Distances = 0.255\n                gps = (-(geodists ** 2) / (2 * (Current_Mean_Distances ** 2))).exp()\n                avg_errors.append(geodists.mean().item())\n                avg_gps.append(gps.mean().item())\n\n            ge_mean = torch.as_tensor(avg_errors).mean().item()\n            gps_mean = torch.as_tensor(avg_gps).mean().item()\n            ge_per_mesh[mesh_name_1] = ge_mean\n            gps_per_mesh[mesh_name_1] = gps_mean\n        ge_mean_global = torch.as_tensor(list(ge_per_mesh.values())).mean().item()\n        gps_mean_global = torch.as_tensor(list(gps_per_mesh.values())).mean().item()\n        per_mesh_metrics = {\n            \"GE\": ge_per_mesh,\n            \"GPS\": gps_per_mesh,\n        }\n        return ge_mean_global, gps_mean_global, per_mesh_metrics\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/evaluation/tensor_storage.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport io\nimport numpy as np\nimport os\nfrom dataclasses import dataclass\nfrom functools import reduce\nfrom operator import mul\nfrom typing import BinaryIO, Dict, Optional, Tuple\nimport torch\n\nfrom detectron2.utils.comm import gather, get_rank\nfrom detectron2.utils.file_io import PathManager\n\n\n@dataclass\nclass SizeData:\n    dtype: str\n    shape: Tuple[int]\n\n\ndef _calculate_record_field_size_b(data_schema: Dict[str, SizeData], field_name: str) -> int:\n    schema = data_schema[field_name]\n    element_size_b = np.dtype(schema.dtype).itemsize\n    record_field_size_b = reduce(mul, schema.shape) * element_size_b\n    return record_field_size_b\n\n\ndef _calculate_record_size_b(data_schema: Dict[str, SizeData]) -> int:\n    record_size_b = 0\n    for field_name in data_schema:\n        record_field_size_b = _calculate_record_field_size_b(data_schema, field_name)\n        record_size_b += record_field_size_b\n    return record_size_b\n\n\ndef _calculate_record_field_sizes_b(data_schema: Dict[str, SizeData]) -> Dict[str, int]:\n    field_sizes_b = {}\n    for field_name in data_schema:\n        field_sizes_b[field_name] = _calculate_record_field_size_b(data_schema, field_name)\n    return field_sizes_b\n\n\nclass SingleProcessTensorStorage:\n    \"\"\"\n    Compact tensor storage to keep tensor data of predefined size and type.\n    \"\"\"\n\n    def __init__(self, data_schema: Dict[str, SizeData], storage_impl: BinaryIO):\n        \"\"\"\n        Construct tensor storage based on information on data shape and size.\n        Internally uses numpy to interpret the type specification.\n        The storage must support operations `seek(offset, whence=os.SEEK_SET)` and\n        `read(size)` to be able to perform the `get` operation.\n        The storage must support operation `write(bytes)` to be able to perform\n        the `put` operation.\n\n        Args:\n            data_schema (dict: str -> SizeData): dictionary which maps tensor name\n                to its size data (shape and data type), e.g.\n                ```\n                {\n                  \"coarse_segm\": SizeData(dtype=\"float32\", shape=(112, 112)),\n                  \"embedding\": SizeData(dtype=\"float32\", shape=(16, 112, 112)),\n                }\n                ```\n            storage_impl (BinaryIO): io instance that handles file-like seek, read\n                and write operations, e.g. a file handle or a memory buffer like io.BytesIO\n        \"\"\"\n        self.data_schema = data_schema\n        self.record_size_b = _calculate_record_size_b(data_schema)\n        self.record_field_sizes_b = _calculate_record_field_sizes_b(data_schema)\n        self.storage_impl = storage_impl\n        self.next_record_id = 0\n\n    def get(self, record_id: int) -> Dict[str, torch.Tensor]:\n        \"\"\"\n        Load tensors from the storage by record ID\n\n        Args:\n            record_id (int): Record ID, for which to load the data\n\n        Return:\n            dict: str -> tensor: tensor name mapped to tensor data, recorded under the provided ID\n        \"\"\"\n        self.storage_impl.seek(record_id * self.record_size_b, os.SEEK_SET)\n        data_bytes = self.storage_impl.read(self.record_size_b)\n        assert len(data_bytes) == self.record_size_b, (\n            f\"Expected data size {self.record_size_b} B could not be read: \"\n            f\"got {len(data_bytes)} B\"\n        )\n        record = {}\n        cur_idx = 0\n        # it's important to read and write in the same order\n        for field_name in sorted(self.data_schema):\n            schema = self.data_schema[field_name]\n            field_size_b = self.record_field_sizes_b[field_name]\n            chunk = data_bytes[cur_idx : cur_idx + field_size_b]\n            data_np = np.frombuffer(\n                chunk, dtype=schema.dtype, count=reduce(mul, schema.shape)\n            ).reshape(schema.shape)\n            record[field_name] = torch.from_numpy(data_np)\n            cur_idx += field_size_b\n        return record\n\n    def put(self, data: Dict[str, torch.Tensor]) -> int:\n        \"\"\"\n        Store tensors in the storage\n\n        Args:\n            data (dict: str -> tensor): data to store, a dictionary which maps\n                tensor names into tensors; tensor shapes must match those specified\n                in data schema.\n        Return:\n            int: record ID, under which the data is stored\n        \"\"\"\n        # it's important to read and write in the same order\n        for field_name in sorted(self.data_schema):\n            assert (\n                field_name in data\n            ), f\"Field '{field_name}' not present in data: data keys are {data.keys()}\"\n            value = data[field_name]\n            assert value.shape == self.data_schema[field_name].shape, (\n                f\"Mismatched tensor shapes for field '{field_name}': \"\n                f\"expected {self.data_schema[field_name].shape}, got {value.shape}\"\n            )\n            data_bytes = value.cpu().numpy().tobytes()\n            assert len(data_bytes) == self.record_field_sizes_b[field_name], (\n                f\"Expected field {field_name} to be of size \"\n                f\"{self.record_field_sizes_b[field_name]} B, got {len(data_bytes)} B\"\n            )\n            self.storage_impl.write(data_bytes)\n        record_id = self.next_record_id\n        self.next_record_id += 1\n        return record_id\n\n\nclass SingleProcessFileTensorStorage(SingleProcessTensorStorage):\n    \"\"\"\n    Implementation of a single process tensor storage which stores data in a file\n    \"\"\"\n\n    def __init__(self, data_schema: Dict[str, SizeData], fpath: str, mode: str):\n        self.fpath = fpath\n        assert \"b\" in mode, f\"Tensor storage should be opened in binary mode, got '{mode}'\"\n        if \"w\" in mode:\n            file_h = PathManager.open(fpath, mode)\n        elif \"r\" in mode:\n            local_fpath = PathManager.get_local_path(fpath)\n            file_h = open(local_fpath, mode)\n        else:\n            raise ValueError(f\"Unsupported file mode {mode}, supported modes: rb, wb\")\n        super().__init__(data_schema, file_h)  # pyre-ignore[6]\n\n\nclass SingleProcessRamTensorStorage(SingleProcessTensorStorage):\n    \"\"\"\n    Implementation of a single process tensor storage which stores data in RAM\n    \"\"\"\n\n    def __init__(self, data_schema: Dict[str, SizeData], buf: io.BytesIO):\n        super().__init__(data_schema, buf)\n\n\nclass MultiProcessTensorStorage:\n    \"\"\"\n    Representation of a set of tensor storages created by individual processes,\n    allows to access those storages from a single owner process. The storages\n    should either be shared or broadcasted to the owner process.\n    The processes are identified by their rank, data is uniquely defined by\n    the rank of the process and the record ID.\n    \"\"\"\n\n    def __init__(self, rank_to_storage: Dict[int, SingleProcessTensorStorage]):\n        self.rank_to_storage = rank_to_storage\n\n    def get(self, rank: int, record_id: int) -> Dict[str, torch.Tensor]:\n        storage = self.rank_to_storage[rank]\n        return storage.get(record_id)\n\n    def put(self, rank: int, data: Dict[str, torch.Tensor]) -> int:\n        storage = self.rank_to_storage[rank]\n        return storage.put(data)\n\n\nclass MultiProcessFileTensorStorage(MultiProcessTensorStorage):\n    def __init__(self, data_schema: Dict[str, SizeData], rank_to_fpath: Dict[int, str], mode: str):\n        rank_to_storage = {\n            rank: SingleProcessFileTensorStorage(data_schema, fpath, mode)\n            for rank, fpath in rank_to_fpath.items()\n        }\n        super().__init__(rank_to_storage)  # pyre-ignore[6]\n\n\nclass MultiProcessRamTensorStorage(MultiProcessTensorStorage):\n    def __init__(self, data_schema: Dict[str, SizeData], rank_to_buffer: Dict[int, io.BytesIO]):\n        rank_to_storage = {\n            rank: SingleProcessRamTensorStorage(data_schema, buf)\n            for rank, buf in rank_to_buffer.items()\n        }\n        super().__init__(rank_to_storage)  # pyre-ignore[6]\n\n\ndef _ram_storage_gather(\n    storage: SingleProcessRamTensorStorage, dst_rank: int = 0\n) -> Optional[MultiProcessRamTensorStorage]:\n    storage.storage_impl.seek(0, os.SEEK_SET)\n    # TODO: overhead, pickling a bytes object, can just pass bytes in a tensor directly\n    # see detectron2/utils.comm.py\n    data_list = gather(storage.storage_impl.read(), dst=dst_rank)\n    if get_rank() != dst_rank:\n        return None\n    rank_to_buffer = {i: io.BytesIO(data_list[i]) for i in range(len(data_list))}\n    multiprocess_storage = MultiProcessRamTensorStorage(storage.data_schema, rank_to_buffer)\n    return multiprocess_storage\n\n\ndef _file_storage_gather(\n    storage: SingleProcessFileTensorStorage,\n    dst_rank: int = 0,\n    mode: str = \"rb\",\n) -> Optional[MultiProcessFileTensorStorage]:\n    storage.storage_impl.close()\n    fpath_list = gather(storage.fpath, dst=dst_rank)\n    if get_rank() != dst_rank:\n        return None\n    rank_to_fpath = {i: fpath_list[i] for i in range(len(fpath_list))}\n    return MultiProcessFileTensorStorage(storage.data_schema, rank_to_fpath, mode)\n\n\ndef storage_gather(\n    storage: SingleProcessTensorStorage, dst_rank: int = 0\n) -> Optional[MultiProcessTensorStorage]:\n    if isinstance(storage, SingleProcessRamTensorStorage):\n        return _ram_storage_gather(storage, dst_rank)\n    elif isinstance(storage, SingleProcessFileTensorStorage):\n        return _file_storage_gather(storage, dst_rank)\n    raise Exception(f\"Unsupported storage for gather operation: {storage}\")\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom .confidence import DensePoseConfidenceModelConfig, DensePoseUVConfidenceType\nfrom .filter import DensePoseDataFilter\nfrom .inference import densepose_inference\nfrom .utils import initialize_module_params\nfrom .build import (\n    build_densepose_data_filter,\n    build_densepose_embedder,\n    build_densepose_head,\n    build_densepose_losses,\n    build_densepose_predictor,\n)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/build.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom typing import Optional\nfrom torch import nn\n\nfrom detectron2.config import CfgNode\n\nfrom .cse.embedder import Embedder\nfrom .filter import DensePoseDataFilter\n\n\ndef build_densepose_predictor(cfg: CfgNode, input_channels: int):\n    \"\"\"\n    Create an instance of DensePose predictor based on configuration options.\n\n    Args:\n        cfg (CfgNode): configuration options\n        input_channels (int): input tensor size along the channel dimension\n    Return:\n        An instance of DensePose predictor\n    \"\"\"\n    from .predictors import DENSEPOSE_PREDICTOR_REGISTRY\n\n    predictor_name = cfg.MODEL.ROI_DENSEPOSE_HEAD.PREDICTOR_NAME\n    return DENSEPOSE_PREDICTOR_REGISTRY.get(predictor_name)(cfg, input_channels)\n\n\ndef build_densepose_data_filter(cfg: CfgNode):\n    \"\"\"\n    Build DensePose data filter which selects data for training\n\n    Args:\n        cfg (CfgNode): configuration options\n\n    Return:\n        Callable: list(Tensor), list(Instances) -> list(Tensor), list(Instances)\n        An instance of DensePose filter, which takes feature tensors and proposals\n        as an input and returns filtered features and proposals\n    \"\"\"\n    dp_filter = DensePoseDataFilter(cfg)\n    return dp_filter\n\n\ndef build_densepose_head(cfg: CfgNode, input_channels: int):\n    \"\"\"\n    Build DensePose head based on configurations options\n\n    Args:\n        cfg (CfgNode): configuration options\n        input_channels (int): input tensor size along the channel dimension\n    Return:\n        An instance of DensePose head\n    \"\"\"\n    from .roi_heads.registry import ROI_DENSEPOSE_HEAD_REGISTRY\n\n    head_name = cfg.MODEL.ROI_DENSEPOSE_HEAD.NAME\n    return ROI_DENSEPOSE_HEAD_REGISTRY.get(head_name)(cfg, input_channels)\n\n\ndef build_densepose_losses(cfg: CfgNode):\n    \"\"\"\n    Build DensePose loss based on configurations options\n\n    Args:\n        cfg (CfgNode): configuration options\n    Return:\n        An instance of DensePose loss\n    \"\"\"\n    from .losses import DENSEPOSE_LOSS_REGISTRY\n\n    loss_name = cfg.MODEL.ROI_DENSEPOSE_HEAD.LOSS_NAME\n    return DENSEPOSE_LOSS_REGISTRY.get(loss_name)(cfg)\n\n\ndef build_densepose_embedder(cfg: CfgNode) -> Optional[nn.Module]:\n    \"\"\"\n    Build embedder used to embed mesh vertices into an embedding space.\n    Embedder contains sub-embedders, one for each mesh ID.\n\n    Args:\n        cfg (cfgNode): configuration options\n    Return:\n        Embedding module\n    \"\"\"\n    if cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBEDDERS:\n        return Embedder(cfg)\n    return None\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/confidence.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom dataclasses import dataclass\nfrom enum import Enum\n\nfrom detectron2.config import CfgNode\n\n\nclass DensePoseUVConfidenceType(Enum):\n    \"\"\"\n    Statistical model type for confidence learning, possible values:\n     - \"iid_iso\": statistically independent identically distributed residuals\n         with anisotropic covariance\n     - \"indep_aniso\": statistically independent residuals with anisotropic\n         covariances\n    For details, see:\n    N. Neverova, D. Novotny, A. Vedaldi \"Correlated Uncertainty for Learning\n    Dense Correspondences from Noisy Labels\", p. 918--926, in Proc. NIPS 2019\n    \"\"\"\n\n    # fmt: off\n    IID_ISO     = \"iid_iso\"\n    INDEP_ANISO = \"indep_aniso\"\n    # fmt: on\n\n\n@dataclass\nclass DensePoseUVConfidenceConfig:\n    \"\"\"\n    Configuration options for confidence on UV data\n    \"\"\"\n\n    enabled: bool = False\n    # lower bound on UV confidences\n    epsilon: float = 0.01\n    type: DensePoseUVConfidenceType = DensePoseUVConfidenceType.IID_ISO\n\n\n@dataclass\nclass DensePoseSegmConfidenceConfig:\n    \"\"\"\n    Configuration options for confidence on segmentation\n    \"\"\"\n\n    enabled: bool = False\n    # lower bound on confidence values\n    epsilon: float = 0.01\n\n\n@dataclass\nclass DensePoseConfidenceModelConfig:\n    \"\"\"\n    Configuration options for confidence models\n    \"\"\"\n\n    # confidence for U and V values\n    uv_confidence: DensePoseUVConfidenceConfig\n    # segmentation confidence\n    segm_confidence: DensePoseSegmConfidenceConfig\n\n    @staticmethod\n    def from_cfg(cfg: CfgNode) -> \"DensePoseConfidenceModelConfig\":\n        return DensePoseConfidenceModelConfig(\n            uv_confidence=DensePoseUVConfidenceConfig(\n                enabled=cfg.MODEL.ROI_DENSEPOSE_HEAD.UV_CONFIDENCE.ENABLED,\n                epsilon=cfg.MODEL.ROI_DENSEPOSE_HEAD.UV_CONFIDENCE.EPSILON,\n                type=DensePoseUVConfidenceType(cfg.MODEL.ROI_DENSEPOSE_HEAD.UV_CONFIDENCE.TYPE),\n            ),\n            segm_confidence=DensePoseSegmConfidenceConfig(\n                enabled=cfg.MODEL.ROI_DENSEPOSE_HEAD.SEGM_CONFIDENCE.ENABLED,\n                epsilon=cfg.MODEL.ROI_DENSEPOSE_HEAD.SEGM_CONFIDENCE.EPSILON,\n            ),\n        )\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/cse/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nfrom .vertex_direct_embedder import VertexDirectEmbedder\nfrom .vertex_feature_embedder import VertexFeatureEmbedder\nfrom .embedder import Embedder\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/cse/embedder.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nimport logging\nimport numpy as np\nimport pickle\nfrom enum import Enum\nfrom typing import Optional\nimport torch\nfrom torch import nn\n\nfrom detectron2.config import CfgNode\nfrom detectron2.utils.file_io import PathManager\n\nfrom .vertex_direct_embedder import VertexDirectEmbedder\nfrom .vertex_feature_embedder import VertexFeatureEmbedder\n\n\nclass EmbedderType(Enum):\n    \"\"\"\n    Embedder type which defines how vertices are mapped into the embedding space:\n     - \"vertex_direct\": direct vertex embedding\n     - \"vertex_feature\": embedding vertex features\n    \"\"\"\n\n    VERTEX_DIRECT = \"vertex_direct\"\n    VERTEX_FEATURE = \"vertex_feature\"\n\n\ndef create_embedder(embedder_spec: CfgNode, embedder_dim: int) -> nn.Module:\n    \"\"\"\n    Create an embedder based on the provided configuration\n\n    Args:\n        embedder_spec (CfgNode): embedder configuration\n        embedder_dim (int): embedding space dimensionality\n    Return:\n        An embedder instance for the specified configuration\n        Raises ValueError, in case of unexpected  embedder type\n    \"\"\"\n    embedder_type = EmbedderType(embedder_spec.TYPE)\n    if embedder_type == EmbedderType.VERTEX_DIRECT:\n        embedder = VertexDirectEmbedder(\n            num_vertices=embedder_spec.NUM_VERTICES,\n            embed_dim=embedder_dim,\n        )\n        if embedder_spec.INIT_FILE != \"\":\n            embedder.load(embedder_spec.INIT_FILE)\n    elif embedder_type == EmbedderType.VERTEX_FEATURE:\n        embedder = VertexFeatureEmbedder(\n            num_vertices=embedder_spec.NUM_VERTICES,\n            feature_dim=embedder_spec.FEATURE_DIM,\n            embed_dim=embedder_dim,\n            train_features=embedder_spec.FEATURES_TRAINABLE,\n        )\n        if embedder_spec.INIT_FILE != \"\":\n            embedder.load(embedder_spec.INIT_FILE)\n    else:\n        raise ValueError(f\"Unexpected embedder type {embedder_type}\")\n\n    if not embedder_spec.IS_TRAINABLE:\n        # pyre-fixme[29]: `Union[nn.Module, torch.Tensor]` is not a function.\n        embedder.requires_grad_(False)\n\n    return embedder\n\n\nclass Embedder(nn.Module):\n    \"\"\"\n    Embedder module that serves as a container for embedders to use with different\n    meshes. Extends Module to automatically save / load state dict.\n    \"\"\"\n\n    DEFAULT_MODEL_CHECKPOINT_PREFIX = \"roi_heads.embedder.\"\n\n    def __init__(self, cfg: CfgNode):\n        \"\"\"\n        Initialize mesh embedders. An embedder for mesh `i` is stored in a submodule\n        \"embedder_{i}\".\n\n        Args:\n            cfg (CfgNode): configuration options\n        \"\"\"\n        super(Embedder, self).__init__()\n        self.mesh_names = set()\n        embedder_dim = cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBED_SIZE\n        logger = logging.getLogger(__name__)\n        for mesh_name, embedder_spec in cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBEDDERS.items():\n            logger.info(f\"Adding embedder embedder_{mesh_name} with spec {embedder_spec}\")\n            # pyre-fixme[29]: `Union[nn.Module, torch.Tensor]` is not a function.\n            self.add_module(f\"embedder_{mesh_name}\", create_embedder(embedder_spec, embedder_dim))\n            self.mesh_names.add(mesh_name)\n        if cfg.MODEL.WEIGHTS != \"\":\n            self.load_from_model_checkpoint(cfg.MODEL.WEIGHTS)\n\n    def load_from_model_checkpoint(self, fpath: str, prefix: Optional[str] = None):\n        if prefix is None:\n            prefix = Embedder.DEFAULT_MODEL_CHECKPOINT_PREFIX\n        state_dict = None\n        if fpath.endswith(\".pkl\"):\n            with PathManager.open(fpath, \"rb\") as hFile:\n                state_dict = pickle.load(hFile, encoding=\"latin1\")  # pyre-ignore[6]\n        else:\n            with PathManager.open(fpath, \"rb\") as hFile:\n                state_dict = torch.load(hFile, map_location=torch.device(\"cpu\"))\n        if state_dict is not None and \"model\" in state_dict:\n            state_dict_local = {}\n            for key in state_dict[\"model\"]:\n                if key.startswith(prefix):\n                    v_key = state_dict[\"model\"][key]\n                    if isinstance(v_key, np.ndarray):\n                        v_key = torch.from_numpy(v_key)\n                    state_dict_local[key[len(prefix) :]] = v_key\n            # non-strict loading to finetune on different meshes\n            # pyre-fixme[6]: Expected `OrderedDict[typing.Any, typing.Any]` for 1st\n            #  param but got `Dict[typing.Any, typing.Any]`.\n            self.load_state_dict(state_dict_local, strict=False)\n\n    def forward(self, mesh_name: str) -> torch.Tensor:\n        \"\"\"\n        Produce vertex embeddings for the specific mesh; vertex embeddings are\n        a tensor of shape [N, D] where:\n            N = number of vertices\n            D = number of dimensions in the embedding space\n        Args:\n            mesh_name (str): name of a mesh for which to obtain vertex embeddings\n        Return:\n            Vertex embeddings, a tensor of shape [N, D]\n        \"\"\"\n        return getattr(self, f\"embedder_{mesh_name}\")()\n\n    def has_embeddings(self, mesh_name: str) -> bool:\n        return hasattr(self, f\"embedder_{mesh_name}\")\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/cse/utils.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nimport torch\nfrom torch.nn import functional as F\n\n\ndef squared_euclidean_distance_matrix(pts1: torch.Tensor, pts2: torch.Tensor) -> torch.Tensor:\n    \"\"\"\n    Get squared Euclidean Distance Matrix\n    Computes pairwise squared Euclidean distances between points\n\n    Args:\n        pts1: Tensor [M x D], M is the number of points, D is feature dimensionality\n        pts2: Tensor [N x D], N is the number of points, D is feature dimensionality\n\n    Return:\n        Tensor [M, N]: matrix of squared Euclidean distances; at index (m, n)\n            it contains || pts1[m] - pts2[n] ||^2\n    \"\"\"\n    edm = torch.mm(-2 * pts1, pts2.t())\n    edm += (pts1 * pts1).sum(1, keepdim=True) + (pts2 * pts2).sum(1, keepdim=True).t()\n    return edm.contiguous()\n\n\ndef normalize_embeddings(embeddings: torch.Tensor, epsilon: float = 1e-6) -> torch.Tensor:\n    \"\"\"\n    Normalize N D-dimensional embedding vectors arranged in a tensor [N, D]\n\n    Args:\n        embeddings (tensor [N, D]): N D-dimensional embedding vectors\n        epsilon (float): minimum value for a vector norm\n    Return:\n        Normalized embeddings (tensor [N, D]), such that L2 vector norms are all equal to 1.\n    \"\"\"\n    return embeddings / torch.clamp(\n        embeddings.norm(p=None, dim=1, keepdim=True), min=epsilon  # pyre-ignore[6]\n    )\n\n\ndef get_closest_vertices_mask_from_ES(\n    E: torch.Tensor,\n    S: torch.Tensor,\n    h: int,\n    w: int,\n    mesh_vertex_embeddings: torch.Tensor,\n    device: torch.device,\n):\n    \"\"\"\n    Interpolate Embeddings and Segmentations to the size of a given bounding box,\n    and compute closest vertices and the segmentation mask\n\n    Args:\n        E (tensor [1, D, H, W]): D-dimensional embedding vectors for every point of the\n            default-sized box\n        S (tensor [1, 2, H, W]): 2-dimensional segmentation mask for every point of the\n            default-sized box\n        h (int): height of the target bounding box\n        w (int): width of the target bounding box\n        mesh_vertex_embeddings (tensor [N, D]): vertex embeddings for a chosen mesh\n            N is the number of vertices in the mesh, D is feature dimensionality\n        device (torch.device): device to move the tensors to\n    Return:\n        Closest Vertices (tensor [h, w]), int, for every point of the resulting box\n        Segmentation mask (tensor [h, w]), boolean, for every point of the resulting box\n    \"\"\"\n    embedding_resized = F.interpolate(E, size=(h, w), mode=\"bilinear\")[0].to(device)\n    coarse_segm_resized = F.interpolate(S, size=(h, w), mode=\"bilinear\")[0].to(device)\n    mask = coarse_segm_resized.argmax(0) > 0\n    closest_vertices = torch.zeros(mask.shape, dtype=torch.long, device=device)\n    all_embeddings = embedding_resized[:, mask].t()\n    size_chunk = 10_000  # Chunking to avoid possible OOM\n    edm = []\n    if len(all_embeddings) == 0:\n        return closest_vertices, mask\n    for chunk in range((len(all_embeddings) - 1) // size_chunk + 1):\n        chunk_embeddings = all_embeddings[size_chunk * chunk : size_chunk * (chunk + 1)]\n        edm.append(\n            torch.argmin(\n                squared_euclidean_distance_matrix(chunk_embeddings, mesh_vertex_embeddings), dim=1\n            )\n        )\n    closest_vertices[mask] = torch.cat(edm)\n    return closest_vertices, mask\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/cse/vertex_direct_embedder.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nimport pickle\nimport torch\nfrom torch import nn\n\nfrom detectron2.utils.file_io import PathManager\n\nfrom .utils import normalize_embeddings\n\n\nclass VertexDirectEmbedder(nn.Module):\n    \"\"\"\n    Class responsible for embedding vertices. Vertex embeddings take\n    the form of a tensor of size [N, D], where\n        N = number of vertices\n        D = number of dimensions in the embedding space\n    \"\"\"\n\n    def __init__(self, num_vertices: int, embed_dim: int):\n        \"\"\"\n        Initialize embedder, set random embeddings\n\n        Args:\n            num_vertices (int): number of vertices to embed\n            embed_dim (int): number of dimensions in the embedding space\n        \"\"\"\n        super(VertexDirectEmbedder, self).__init__()\n        self.embeddings = nn.Parameter(torch.Tensor(num_vertices, embed_dim))\n        self.reset_parameters()\n\n    @torch.no_grad()\n    def reset_parameters(self):\n        \"\"\"\n        Reset embeddings to random values\n        \"\"\"\n        self.embeddings.zero_()\n\n    def forward(self) -> torch.Tensor:\n        \"\"\"\n        Produce vertex embeddings, a tensor of shape [N, D] where:\n            N = number of vertices\n            D = number of dimensions in the embedding space\n\n        Return:\n           Full vertex embeddings, a tensor of shape [N, D]\n        \"\"\"\n        return normalize_embeddings(self.embeddings)\n\n    @torch.no_grad()\n    def load(self, fpath: str):\n        \"\"\"\n        Load data from a file\n\n        Args:\n            fpath (str): file path to load data from\n        \"\"\"\n        with PathManager.open(fpath, \"rb\") as hFile:\n            data = pickle.load(hFile)  # pyre-ignore[6]\n            for name in [\"embeddings\"]:\n                if name in data:\n                    getattr(self, name).copy_(\n                        torch.tensor(data[name]).float().to(device=getattr(self, name).device)\n                    )\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/cse/vertex_feature_embedder.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nimport pickle\nimport torch\nfrom torch import nn\n\nfrom detectron2.utils.file_io import PathManager\n\nfrom .utils import normalize_embeddings\n\n\nclass VertexFeatureEmbedder(nn.Module):\n    \"\"\"\n    Class responsible for embedding vertex features. Mapping from\n    feature space to the embedding space is a tensor of size [K, D], where\n        K = number of dimensions in the feature space\n        D = number of dimensions in the embedding space\n    Vertex features is a tensor of size [N, K], where\n        N = number of vertices\n        K = number of dimensions in the feature space\n    Vertex embeddings are computed as F * E = tensor of size [N, D]\n    \"\"\"\n\n    def __init__(\n        self, num_vertices: int, feature_dim: int, embed_dim: int, train_features: bool = False\n    ):\n        \"\"\"\n        Initialize embedder, set random embeddings\n\n        Args:\n            num_vertices (int): number of vertices to embed\n            feature_dim (int): number of dimensions in the feature space\n            embed_dim (int): number of dimensions in the embedding space\n            train_features (bool): determines whether vertex features should\n                be trained (default: False)\n        \"\"\"\n        super(VertexFeatureEmbedder, self).__init__()\n        if train_features:\n            self.features = nn.Parameter(torch.Tensor(num_vertices, feature_dim))\n        else:\n            self.register_buffer(\"features\", torch.Tensor(num_vertices, feature_dim))\n        self.embeddings = nn.Parameter(torch.Tensor(feature_dim, embed_dim))\n        self.reset_parameters()\n\n    @torch.no_grad()\n    def reset_parameters(self):\n        self.features.zero_()\n        self.embeddings.zero_()\n\n    def forward(self) -> torch.Tensor:\n        \"\"\"\n        Produce vertex embeddings, a tensor of shape [N, D] where:\n            N = number of vertices\n            D = number of dimensions in the embedding space\n\n        Return:\n           Full vertex embeddings, a tensor of shape [N, D]\n        \"\"\"\n        return normalize_embeddings(torch.mm(self.features, self.embeddings))\n\n    @torch.no_grad()\n    def load(self, fpath: str):\n        \"\"\"\n        Load data from a file\n\n        Args:\n            fpath (str): file path to load data from\n        \"\"\"\n        with PathManager.open(fpath, \"rb\") as hFile:\n            data = pickle.load(hFile)  # pyre-ignore[6]\n            for name in [\"features\", \"embeddings\"]:\n                if name in data:\n                    getattr(self, name).copy_(\n                        torch.tensor(data[name]).float().to(device=getattr(self, name).device)\n                    )\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/densepose_checkpoint.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom collections import OrderedDict\n\nfrom detectron2.checkpoint import DetectionCheckpointer\n\n\ndef _rename_HRNet_weights(weights):\n    # We detect and  rename HRNet weights for DensePose. 1956 and 1716 are values that are\n    # common to all HRNet pretrained weights, and should be enough to accurately identify them\n    if (\n        len(weights[\"model\"].keys()) == 1956\n        and len([k for k in weights[\"model\"].keys() if k.startswith(\"stage\")]) == 1716\n    ):\n        hrnet_weights = OrderedDict()\n        for k in weights[\"model\"].keys():\n            hrnet_weights[\"backbone.bottom_up.\" + str(k)] = weights[\"model\"][k]\n        return {\"model\": hrnet_weights}\n    else:\n        return weights\n\n\nclass DensePoseCheckpointer(DetectionCheckpointer):\n    \"\"\"\n    Same as :class:`DetectionCheckpointer`, but is able to handle HRNet weights\n    \"\"\"\n\n    def __init__(self, model, save_dir=\"\", *, save_to_disk=None, **checkpointables):\n        super().__init__(model, save_dir, save_to_disk=save_to_disk, **checkpointables)\n\n    def _load_file(self, filename: str) -> object:\n        \"\"\"\n        Adding hrnet support\n        \"\"\"\n        weights = super()._load_file(filename)\n        return _rename_HRNet_weights(weights)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/filter.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom typing import List\nimport torch\n\nfrom detectron2.config import CfgNode\nfrom detectron2.structures import Instances\nfrom detectron2.structures.boxes import matched_pairwise_iou\n\n\nclass DensePoseDataFilter(object):\n    def __init__(self, cfg: CfgNode):\n        self.iou_threshold = cfg.MODEL.ROI_DENSEPOSE_HEAD.FG_IOU_THRESHOLD\n        self.keep_masks = cfg.MODEL.ROI_DENSEPOSE_HEAD.COARSE_SEGM_TRAINED_BY_MASKS\n\n    @torch.no_grad()\n    def __call__(self, features: List[torch.Tensor], proposals_with_targets: List[Instances]):\n        \"\"\"\n        Filters proposals with targets to keep only the ones relevant for\n        DensePose training\n\n        Args:\n            features (list[Tensor]): input data as a list of features,\n                each feature is a tensor. Axis 0 represents the number of\n                images `N` in the input data; axes 1-3 are channels,\n                height, and width, which may vary between features\n                (e.g., if a feature pyramid is used).\n            proposals_with_targets (list[Instances]): length `N` list of\n                `Instances`. The i-th `Instances` contains instances\n                (proposals, GT) for the i-th input image,\n        Returns:\n            list[Tensor]: filtered features\n            list[Instances]: filtered proposals\n        \"\"\"\n        proposals_filtered = []\n        # TODO: the commented out code was supposed to correctly deal with situations\n        # where no valid DensePose GT is available for certain images. The corresponding\n        # image features were sliced and proposals were filtered. This led to performance\n        # deterioration, both in terms of runtime and in terms of evaluation results.\n        #\n        # feature_mask = torch.ones(\n        #    len(proposals_with_targets),\n        #    dtype=torch.bool,\n        #    device=features[0].device if len(features) > 0 else torch.device(\"cpu\"),\n        # )\n        for i, proposals_per_image in enumerate(proposals_with_targets):\n            if not proposals_per_image.has(\"gt_densepose\") and (\n                not proposals_per_image.has(\"gt_masks\") or not self.keep_masks\n            ):\n                # feature_mask[i] = 0\n                continue\n            gt_boxes = proposals_per_image.gt_boxes\n            est_boxes = proposals_per_image.proposal_boxes\n            # apply match threshold for densepose head\n            iou = matched_pairwise_iou(gt_boxes, est_boxes)\n            iou_select = iou > self.iou_threshold\n            proposals_per_image = proposals_per_image[iou_select]  # pyre-ignore[6]\n\n            N_gt_boxes = len(proposals_per_image.gt_boxes)\n            assert N_gt_boxes == len(proposals_per_image.proposal_boxes), (\n                f\"The number of GT boxes {N_gt_boxes} is different from the \"\n                f\"number of proposal boxes {len(proposals_per_image.proposal_boxes)}\"\n            )\n            # filter out any target without suitable annotation\n            if self.keep_masks:\n                gt_masks = (\n                    proposals_per_image.gt_masks\n                    if hasattr(proposals_per_image, \"gt_masks\")\n                    else [None] * N_gt_boxes\n                )\n            else:\n                gt_masks = [None] * N_gt_boxes\n            gt_densepose = (\n                proposals_per_image.gt_densepose\n                if hasattr(proposals_per_image, \"gt_densepose\")\n                else [None] * N_gt_boxes\n            )\n            assert len(gt_masks) == N_gt_boxes\n            assert len(gt_densepose) == N_gt_boxes\n            selected_indices = [\n                i\n                for i, (dp_target, mask_target) in enumerate(zip(gt_densepose, gt_masks))\n                if (dp_target is not None) or (mask_target is not None)\n            ]\n            # if not len(selected_indices):\n            #     feature_mask[i] = 0\n            #     continue\n            if len(selected_indices) != N_gt_boxes:\n                proposals_per_image = proposals_per_image[selected_indices]  # pyre-ignore[6]\n            assert len(proposals_per_image.gt_boxes) == len(proposals_per_image.proposal_boxes)\n            proposals_filtered.append(proposals_per_image)\n        # features_filtered = [feature[feature_mask] for feature in features]\n        # return features_filtered, proposals_filtered\n        return features, proposals_filtered\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/hrfpn.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\"\"\"\nMIT License\nCopyright (c) 2019 Microsoft\nPermission is hereby granted, free of charge, to any person obtaining a copy\nof this software and associated documentation files (the \"Software\"), to deal\nin the Software without restriction, including without limitation the rights\nto use, copy, modify, merge, publish, distribute, sublicense, and/or sell\ncopies of the Software, and to permit persons to whom the Software is\nfurnished to do so, subject to the following conditions:\nThe above copyright notice and this permission notice shall be included in all\ncopies or substantial portions of the Software.\nTHE SOFTWARE IS PROVIDED \"AS IS\", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR\nIMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,\nFITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE\nAUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER\nLIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,\nOUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE\nSOFTWARE.\n\"\"\"\n\nimport torch\nimport torch.nn as nn\nimport torch.nn.functional as F\n\nfrom detectron2.layers import ShapeSpec\nfrom detectron2.modeling.backbone import BACKBONE_REGISTRY\nfrom detectron2.modeling.backbone.backbone import Backbone\n\nfrom .hrnet import build_pose_hrnet_backbone\n\n\nclass HRFPN(Backbone):\n    \"\"\"HRFPN (High Resolution Feature Pyramids)\n    Transforms outputs of HRNet backbone so they are suitable for the ROI_heads\n    arXiv: https://arxiv.org/abs/1904.04514\n    Adapted from https://github.com/open-mmlab/mmdetection/blob/master/mmdet/models/necks/hrfpn.py\n    Args:\n        bottom_up: (list) output of HRNet\n        in_features (list): names of the input features (output of HRNet)\n        in_channels (list): number of channels for each branch\n        out_channels (int): output channels of feature pyramids\n        n_out_features (int): number of output stages\n        pooling (str): pooling for generating feature pyramids (from {MAX, AVG})\n        share_conv (bool): Have one conv per output, or share one with all the outputs\n    \"\"\"\n\n    def __init__(\n        self,\n        bottom_up,\n        in_features,\n        n_out_features,\n        in_channels,\n        out_channels,\n        pooling=\"AVG\",\n        share_conv=False,\n    ):\n        super(HRFPN, self).__init__()\n        assert isinstance(in_channels, list)\n        self.bottom_up = bottom_up\n        self.in_features = in_features\n        self.n_out_features = n_out_features\n        self.in_channels = in_channels\n        self.out_channels = out_channels\n        self.num_ins = len(in_channels)\n        self.share_conv = share_conv\n\n        if self.share_conv:\n            self.fpn_conv = nn.Conv2d(\n                in_channels=out_channels, out_channels=out_channels, kernel_size=3, padding=1\n            )\n        else:\n            self.fpn_conv = nn.ModuleList()\n            for _ in range(self.n_out_features):\n                self.fpn_conv.append(\n                    nn.Conv2d(\n                        in_channels=out_channels,\n                        out_channels=out_channels,\n                        kernel_size=3,\n                        padding=1,\n                    )\n                )\n\n        # Custom change: Replaces a simple bilinear interpolation\n        self.interp_conv = nn.ModuleList()\n        for i in range(len(self.in_features)):\n            self.interp_conv.append(\n                nn.Sequential(\n                    nn.ConvTranspose2d(\n                        in_channels=in_channels[i],\n                        out_channels=in_channels[i],\n                        kernel_size=4,\n                        stride=2 ** i,\n                        padding=0,\n                        output_padding=0,\n                        bias=False,\n                    ),\n                    nn.BatchNorm2d(in_channels[i], momentum=0.1),\n                    nn.ReLU(inplace=True),\n                )\n            )\n\n        # Custom change: Replaces a couple (reduction conv + pooling) by one conv\n        self.reduction_pooling_conv = nn.ModuleList()\n        for i in range(self.n_out_features):\n            self.reduction_pooling_conv.append(\n                nn.Sequential(\n                    nn.Conv2d(sum(in_channels), out_channels, kernel_size=2 ** i, stride=2 ** i),\n                    nn.BatchNorm2d(out_channels, momentum=0.1),\n                    nn.ReLU(inplace=True),\n                )\n            )\n\n        if pooling == \"MAX\":\n            self.pooling = F.max_pool2d\n        else:\n            self.pooling = F.avg_pool2d\n\n        self._out_features = []\n        self._out_feature_channels = {}\n        self._out_feature_strides = {}\n\n        for i in range(self.n_out_features):\n            self._out_features.append(\"p%d\" % (i + 1))\n            self._out_feature_channels.update({self._out_features[-1]: self.out_channels})\n            self._out_feature_strides.update({self._out_features[-1]: 2 ** (i + 2)})\n\n    # default init_weights for conv(msra) and norm in ConvModule\n    def init_weights(self):\n        for m in self.modules():\n            if isinstance(m, nn.Conv2d):\n                nn.init.kaiming_normal_(m.weight, a=1)\n                nn.init.constant_(m.bias, 0)\n\n    def forward(self, inputs):\n        bottom_up_features = self.bottom_up(inputs)\n        assert len(bottom_up_features) == len(self.in_features)\n        inputs = [bottom_up_features[f] for f in self.in_features]\n\n        outs = []\n        for i in range(len(inputs)):\n            outs.append(self.interp_conv[i](inputs[i]))\n        shape_2 = min(o.shape[2] for o in outs)\n        shape_3 = min(o.shape[3] for o in outs)\n        out = torch.cat([o[:, :, :shape_2, :shape_3] for o in outs], dim=1)\n        outs = []\n        for i in range(self.n_out_features):\n            outs.append(self.reduction_pooling_conv[i](out))\n        for i in range(len(outs)):  # Make shapes consistent\n            outs[-1 - i] = outs[-1 - i][\n                :, :, : outs[-1].shape[2] * 2 ** i, : outs[-1].shape[3] * 2 ** i\n            ]\n        outputs = []\n        for i in range(len(outs)):\n            if self.share_conv:\n                outputs.append(self.fpn_conv(outs[i]))\n            else:\n                outputs.append(self.fpn_conv[i](outs[i]))\n\n        assert len(self._out_features) == len(outputs)\n        return dict(zip(self._out_features, outputs))\n\n\n@BACKBONE_REGISTRY.register()\ndef build_hrfpn_backbone(cfg, input_shape: ShapeSpec):\n\n    in_channels = cfg.MODEL.HRNET.STAGE4.NUM_CHANNELS\n    in_features = [\"p%d\" % (i + 1) for i in range(cfg.MODEL.HRNET.STAGE4.NUM_BRANCHES)]\n    n_out_features = len(cfg.MODEL.ROI_HEADS.IN_FEATURES)\n    out_channels = cfg.MODEL.HRNET.HRFPN.OUT_CHANNELS\n    hrnet = build_pose_hrnet_backbone(cfg, input_shape)\n    hrfpn = HRFPN(\n        hrnet,\n        in_features,\n        n_out_features,\n        in_channels,\n        out_channels,\n        pooling=\"AVG\",\n        share_conv=False,\n    )\n\n    return hrfpn\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/hrnet.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n# ------------------------------------------------------------------------------\n# Copyright (c) Microsoft\n# Licensed under the MIT License.\n# Written by Bin Xiao (leoxiaobin@gmail.com)\n# Modified by Bowen Cheng (bcheng9@illinois.edu)\n# Adapted from https://github.com/HRNet/Higher-HRNet-Human-Pose-Estimation/blob/master/lib/models/pose_higher_hrnet.py  # noqa\n# ------------------------------------------------------------------------------\n\nfrom __future__ import absolute_import, division, print_function\nimport logging\nimport torch.nn as nn\n\nfrom detectron2.layers import ShapeSpec\nfrom detectron2.modeling.backbone import BACKBONE_REGISTRY\nfrom detectron2.modeling.backbone.backbone import Backbone\n\nBN_MOMENTUM = 0.1\nlogger = logging.getLogger(__name__)\n\n__all__ = [\"build_pose_hrnet_backbone\", \"PoseHigherResolutionNet\"]\n\n\ndef conv3x3(in_planes, out_planes, stride=1):\n    \"\"\"3x3 convolution with padding\"\"\"\n    return nn.Conv2d(in_planes, out_planes, kernel_size=3, stride=stride, padding=1, bias=False)\n\n\nclass BasicBlock(nn.Module):\n    expansion = 1\n\n    def __init__(self, inplanes, planes, stride=1, downsample=None):\n        super(BasicBlock, self).__init__()\n        self.conv1 = conv3x3(inplanes, planes, stride)\n        self.bn1 = nn.BatchNorm2d(planes, momentum=BN_MOMENTUM)\n        self.relu = nn.ReLU(inplace=True)\n        self.conv2 = conv3x3(planes, planes)\n        self.bn2 = nn.BatchNorm2d(planes, momentum=BN_MOMENTUM)\n        self.downsample = downsample\n        self.stride = stride\n\n    def forward(self, x):\n        residual = x\n\n        out = self.conv1(x)\n        out = self.bn1(out)\n        out = self.relu(out)\n\n        out = self.conv2(out)\n        out = self.bn2(out)\n\n        if self.downsample is not None:\n            residual = self.downsample(x)\n\n        out += residual\n        out = self.relu(out)\n\n        return out\n\n\nclass Bottleneck(nn.Module):\n    expansion = 4\n\n    def __init__(self, inplanes, planes, stride=1, downsample=None):\n        super(Bottleneck, self).__init__()\n        self.conv1 = nn.Conv2d(inplanes, planes, kernel_size=1, bias=False)\n        self.bn1 = nn.BatchNorm2d(planes, momentum=BN_MOMENTUM)\n        self.conv2 = nn.Conv2d(planes, planes, kernel_size=3, stride=stride, padding=1, bias=False)\n        self.bn2 = nn.BatchNorm2d(planes, momentum=BN_MOMENTUM)\n        self.conv3 = nn.Conv2d(planes, planes * self.expansion, kernel_size=1, bias=False)\n        self.bn3 = nn.BatchNorm2d(planes * self.expansion, momentum=BN_MOMENTUM)\n        self.relu = nn.ReLU(inplace=True)\n        self.downsample = downsample\n        self.stride = stride\n\n    def forward(self, x):\n        residual = x\n\n        out = self.conv1(x)\n        out = self.bn1(out)\n        out = self.relu(out)\n\n        out = self.conv2(out)\n        out = self.bn2(out)\n        out = self.relu(out)\n\n        out = self.conv3(out)\n        out = self.bn3(out)\n\n        if self.downsample is not None:\n            residual = self.downsample(x)\n\n        out += residual\n        out = self.relu(out)\n\n        return out\n\n\nclass HighResolutionModule(nn.Module):\n    \"\"\"HighResolutionModule\n    Building block of the PoseHigherResolutionNet (see lower)\n    arXiv: https://arxiv.org/abs/1908.10357\n    Args:\n        num_branches (int): number of branches of the modyle\n        blocks (str): type of block of the module\n        num_blocks (int): number of blocks of the module\n        num_inchannels (int): number of input channels of the module\n        num_channels (list): number of channels of each branch\n        multi_scale_output (bool): only used by the last module of PoseHigherResolutionNet\n    \"\"\"\n\n    def __init__(\n        self,\n        num_branches,\n        blocks,\n        num_blocks,\n        num_inchannels,\n        num_channels,\n        multi_scale_output=True,\n    ):\n        super(HighResolutionModule, self).__init__()\n        self._check_branches(num_branches, blocks, num_blocks, num_inchannels, num_channels)\n\n        self.num_inchannels = num_inchannels\n        self.num_branches = num_branches\n\n        self.multi_scale_output = multi_scale_output\n\n        self.branches = self._make_branches(num_branches, blocks, num_blocks, num_channels)\n        self.fuse_layers = self._make_fuse_layers()\n        self.relu = nn.ReLU(True)\n\n    def _check_branches(self, num_branches, blocks, num_blocks, num_inchannels, num_channels):\n        if num_branches != len(num_blocks):\n            error_msg = \"NUM_BRANCHES({}) <> NUM_BLOCKS({})\".format(num_branches, len(num_blocks))\n            logger.error(error_msg)\n            raise ValueError(error_msg)\n\n        if num_branches != len(num_channels):\n            error_msg = \"NUM_BRANCHES({}) <> NUM_CHANNELS({})\".format(\n                num_branches, len(num_channels)\n            )\n            logger.error(error_msg)\n            raise ValueError(error_msg)\n\n        if num_branches != len(num_inchannels):\n            error_msg = \"NUM_BRANCHES({}) <> NUM_INCHANNELS({})\".format(\n                num_branches, len(num_inchannels)\n            )\n            logger.error(error_msg)\n            raise ValueError(error_msg)\n\n    def _make_one_branch(self, branch_index, block, num_blocks, num_channels, stride=1):\n        downsample = None\n        if (\n            stride != 1\n            or self.num_inchannels[branch_index] != num_channels[branch_index] * block.expansion\n        ):\n            downsample = nn.Sequential(\n                nn.Conv2d(\n                    self.num_inchannels[branch_index],\n                    num_channels[branch_index] * block.expansion,\n                    kernel_size=1,\n                    stride=stride,\n                    bias=False,\n                ),\n                nn.BatchNorm2d(num_channels[branch_index] * block.expansion, momentum=BN_MOMENTUM),\n            )\n\n        layers = []\n        layers.append(\n            block(self.num_inchannels[branch_index], num_channels[branch_index], stride, downsample)\n        )\n        self.num_inchannels[branch_index] = num_channels[branch_index] * block.expansion\n        for _ in range(1, num_blocks[branch_index]):\n            layers.append(block(self.num_inchannels[branch_index], num_channels[branch_index]))\n\n        return nn.Sequential(*layers)\n\n    def _make_branches(self, num_branches, block, num_blocks, num_channels):\n        branches = []\n\n        for i in range(num_branches):\n            branches.append(self._make_one_branch(i, block, num_blocks, num_channels))\n\n        return nn.ModuleList(branches)\n\n    def _make_fuse_layers(self):\n        if self.num_branches == 1:\n            return None\n\n        num_branches = self.num_branches\n        num_inchannels = self.num_inchannels\n        fuse_layers = []\n        for i in range(num_branches if self.multi_scale_output else 1):\n            fuse_layer = []\n            for j in range(num_branches):\n                if j > i:\n                    fuse_layer.append(\n                        nn.Sequential(\n                            nn.Conv2d(num_inchannels[j], num_inchannels[i], 1, 1, 0, bias=False),\n                            nn.BatchNorm2d(num_inchannels[i]),\n                            nn.Upsample(scale_factor=2 ** (j - i), mode=\"nearest\"),\n                        )\n                    )\n                elif j == i:\n                    fuse_layer.append(None)\n                else:\n                    conv3x3s = []\n                    for k in range(i - j):\n                        if k == i - j - 1:\n                            num_outchannels_conv3x3 = num_inchannels[i]\n                            conv3x3s.append(\n                                nn.Sequential(\n                                    nn.Conv2d(\n                                        num_inchannels[j],\n                                        num_outchannels_conv3x3,\n                                        3,\n                                        2,\n                                        1,\n                                        bias=False,\n                                    ),\n                                    nn.BatchNorm2d(num_outchannels_conv3x3),\n                                )\n                            )\n                        else:\n                            num_outchannels_conv3x3 = num_inchannels[j]\n                            conv3x3s.append(\n                                nn.Sequential(\n                                    nn.Conv2d(\n                                        num_inchannels[j],\n                                        num_outchannels_conv3x3,\n                                        3,\n                                        2,\n                                        1,\n                                        bias=False,\n                                    ),\n                                    nn.BatchNorm2d(num_outchannels_conv3x3),\n                                    nn.ReLU(True),\n                                )\n                            )\n                    fuse_layer.append(nn.Sequential(*conv3x3s))\n            fuse_layers.append(nn.ModuleList(fuse_layer))\n\n        return nn.ModuleList(fuse_layers)\n\n    def get_num_inchannels(self):\n        return self.num_inchannels\n\n    def forward(self, x):\n        if self.num_branches == 1:\n            return [self.branches[0](x[0])]\n\n        for i in range(self.num_branches):\n            x[i] = self.branches[i](x[i])\n\n        x_fuse = []\n\n        for i in range(len(self.fuse_layers)):\n            y = x[0] if i == 0 else self.fuse_layers[i][0](x[0])\n            for j in range(1, self.num_branches):\n                if i == j:\n                    y = y + x[j]\n                else:\n                    z = self.fuse_layers[i][j](x[j])[:, :, : y.shape[2], : y.shape[3]]\n                    y = y + z\n            x_fuse.append(self.relu(y))\n\n        return x_fuse\n\n\nblocks_dict = {\"BASIC\": BasicBlock, \"BOTTLENECK\": Bottleneck}\n\n\nclass PoseHigherResolutionNet(Backbone):\n    \"\"\"PoseHigherResolutionNet\n    Composed of several HighResolutionModule tied together with ConvNets\n    Adapted from the GitHub version to fit with HRFPN and the Detectron2 infrastructure\n    arXiv: https://arxiv.org/abs/1908.10357\n    \"\"\"\n\n    def __init__(self, cfg, **kwargs):\n        self.inplanes = cfg.MODEL.HRNET.STEM_INPLANES\n        super(PoseHigherResolutionNet, self).__init__()\n\n        # stem net\n        self.conv1 = nn.Conv2d(3, 64, kernel_size=3, stride=2, padding=1, bias=False)\n        self.bn1 = nn.BatchNorm2d(64, momentum=BN_MOMENTUM)\n        self.conv2 = nn.Conv2d(64, 64, kernel_size=3, stride=2, padding=1, bias=False)\n        self.bn2 = nn.BatchNorm2d(64, momentum=BN_MOMENTUM)\n        self.relu = nn.ReLU(inplace=True)\n        self.layer1 = self._make_layer(Bottleneck, 64, 4)\n\n        self.stage2_cfg = cfg.MODEL.HRNET.STAGE2\n        num_channels = self.stage2_cfg.NUM_CHANNELS\n        block = blocks_dict[self.stage2_cfg.BLOCK]\n        num_channels = [num_channels[i] * block.expansion for i in range(len(num_channels))]\n        self.transition1 = self._make_transition_layer([256], num_channels)\n        self.stage2, pre_stage_channels = self._make_stage(self.stage2_cfg, num_channels)\n\n        self.stage3_cfg = cfg.MODEL.HRNET.STAGE3\n        num_channels = self.stage3_cfg.NUM_CHANNELS\n        block = blocks_dict[self.stage3_cfg.BLOCK]\n        num_channels = [num_channels[i] * block.expansion for i in range(len(num_channels))]\n        self.transition2 = self._make_transition_layer(pre_stage_channels, num_channels)\n        self.stage3, pre_stage_channels = self._make_stage(self.stage3_cfg, num_channels)\n\n        self.stage4_cfg = cfg.MODEL.HRNET.STAGE4\n        num_channels = self.stage4_cfg.NUM_CHANNELS\n        block = blocks_dict[self.stage4_cfg.BLOCK]\n        num_channels = [num_channels[i] * block.expansion for i in range(len(num_channels))]\n        self.transition3 = self._make_transition_layer(pre_stage_channels, num_channels)\n        self.stage4, pre_stage_channels = self._make_stage(\n            self.stage4_cfg, num_channels, multi_scale_output=True\n        )\n\n        self._out_features = []\n        self._out_feature_channels = {}\n        self._out_feature_strides = {}\n\n        for i in range(cfg.MODEL.HRNET.STAGE4.NUM_BRANCHES):\n            self._out_features.append(\"p%d\" % (i + 1))\n            self._out_feature_channels.update(\n                {self._out_features[-1]: cfg.MODEL.HRNET.STAGE4.NUM_CHANNELS[i]}\n            )\n            self._out_feature_strides.update({self._out_features[-1]: 1})\n\n    def _get_deconv_cfg(self, deconv_kernel):\n        if deconv_kernel == 4:\n            padding = 1\n            output_padding = 0\n        elif deconv_kernel == 3:\n            padding = 1\n            output_padding = 1\n        elif deconv_kernel == 2:\n            padding = 0\n            output_padding = 0\n\n        return deconv_kernel, padding, output_padding\n\n    def _make_transition_layer(self, num_channels_pre_layer, num_channels_cur_layer):\n        num_branches_cur = len(num_channels_cur_layer)\n        num_branches_pre = len(num_channels_pre_layer)\n\n        transition_layers = []\n        for i in range(num_branches_cur):\n            if i < num_branches_pre:\n                if num_channels_cur_layer[i] != num_channels_pre_layer[i]:\n                    transition_layers.append(\n                        nn.Sequential(\n                            nn.Conv2d(\n                                num_channels_pre_layer[i],\n                                num_channels_cur_layer[i],\n                                3,\n                                1,\n                                1,\n                                bias=False,\n                            ),\n                            nn.BatchNorm2d(num_channels_cur_layer[i]),\n                            nn.ReLU(inplace=True),\n                        )\n                    )\n                else:\n                    transition_layers.append(None)\n            else:\n                conv3x3s = []\n                for j in range(i + 1 - num_branches_pre):\n                    inchannels = num_channels_pre_layer[-1]\n                    outchannels = (\n                        num_channels_cur_layer[i] if j == i - num_branches_pre else inchannels\n                    )\n                    conv3x3s.append(\n                        nn.Sequential(\n                            nn.Conv2d(inchannels, outchannels, 3, 2, 1, bias=False),\n                            nn.BatchNorm2d(outchannels),\n                            nn.ReLU(inplace=True),\n                        )\n                    )\n                transition_layers.append(nn.Sequential(*conv3x3s))\n\n        return nn.ModuleList(transition_layers)\n\n    def _make_layer(self, block, planes, blocks, stride=1):\n        downsample = None\n        if stride != 1 or self.inplanes != planes * block.expansion:\n            downsample = nn.Sequential(\n                nn.Conv2d(\n                    self.inplanes,\n                    planes * block.expansion,\n                    kernel_size=1,\n                    stride=stride,\n                    bias=False,\n                ),\n                nn.BatchNorm2d(planes * block.expansion, momentum=BN_MOMENTUM),\n            )\n\n        layers = []\n        layers.append(block(self.inplanes, planes, stride, downsample))\n        self.inplanes = planes * block.expansion\n        for _ in range(1, blocks):\n            layers.append(block(self.inplanes, planes))\n\n        return nn.Sequential(*layers)\n\n    def _make_stage(self, layer_config, num_inchannels, multi_scale_output=True):\n        num_modules = layer_config[\"NUM_MODULES\"]\n        num_branches = layer_config[\"NUM_BRANCHES\"]\n        num_blocks = layer_config[\"NUM_BLOCKS\"]\n        num_channels = layer_config[\"NUM_CHANNELS\"]\n        block = blocks_dict[layer_config[\"BLOCK\"]]\n\n        modules = []\n        for i in range(num_modules):\n            # multi_scale_output is only used last module\n            if not multi_scale_output and i == num_modules - 1:\n                reset_multi_scale_output = False\n            else:\n                reset_multi_scale_output = True\n\n            modules.append(\n                HighResolutionModule(\n                    num_branches,\n                    block,\n                    num_blocks,\n                    num_inchannels,\n                    num_channels,\n                    reset_multi_scale_output,\n                )\n            )\n            num_inchannels = modules[-1].get_num_inchannels()\n\n        return nn.Sequential(*modules), num_inchannels\n\n    def forward(self, x):\n        x = self.conv1(x)\n        x = self.bn1(x)\n        x = self.relu(x)\n        x = self.conv2(x)\n        x = self.bn2(x)\n        x = self.relu(x)\n        x = self.layer1(x)\n\n        x_list = []\n        for i in range(self.stage2_cfg.NUM_BRANCHES):\n            if self.transition1[i] is not None:\n                x_list.append(self.transition1[i](x))\n            else:\n                x_list.append(x)\n        y_list = self.stage2(x_list)\n\n        x_list = []\n        for i in range(self.stage3_cfg.NUM_BRANCHES):\n            if self.transition2[i] is not None:\n                x_list.append(self.transition2[i](y_list[-1]))\n            else:\n                x_list.append(y_list[i])\n        y_list = self.stage3(x_list)\n\n        x_list = []\n        for i in range(self.stage4_cfg.NUM_BRANCHES):\n            if self.transition3[i] is not None:\n                x_list.append(self.transition3[i](y_list[-1]))\n            else:\n                x_list.append(y_list[i])\n        y_list = self.stage4(x_list)\n\n        assert len(self._out_features) == len(y_list)\n        return dict(zip(self._out_features, y_list))  # final_outputs\n\n\n@BACKBONE_REGISTRY.register()\ndef build_pose_hrnet_backbone(cfg, input_shape: ShapeSpec):\n    model = PoseHigherResolutionNet(cfg)\n    return model\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/inference.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom dataclasses import fields\nfrom typing import Any, List\nimport torch\n\nfrom detectron2.structures import Instances\n\n\ndef densepose_inference(densepose_predictor_output: Any, detections: List[Instances]):\n    \"\"\"\n    Splits DensePose predictor outputs into chunks, each chunk corresponds to\n    detections on one image. Predictor output chunks are stored in `pred_densepose`\n    attribute of the corresponding `Instances` object.\n\n    Args:\n        densepose_predictor_output: a dataclass instance (can be of different types,\n            depending on predictor used for inference). Each field can be `None`\n            (if the corresponding output was not inferred) or a tensor of size\n            [N, ...], where N = N_1 + N_2 + .. + N_k is a total number of\n            detections on all images, N_1 is the number of detections on image 1,\n            N_2 is the number of detections on image 2, etc.\n        detections: a list of objects of type `Instance`, k-th object corresponds\n            to detections on k-th image.\n    \"\"\"\n    k = 0\n    for detection_i in detections:\n        if densepose_predictor_output is None:\n            # don't add `pred_densepose` attribute\n            continue\n        n_i = len(detection_i)\n        PredictorOutput = type(densepose_predictor_output)\n        output_i_dict = {}\n        # we assume here that `densepose_predictor_output` is a dataclass object\n        for field in fields(densepose_predictor_output):\n            field_value = getattr(densepose_predictor_output, field.name)\n            # slice tensors\n            if isinstance(field_value, torch.Tensor):\n                output_i_dict[field.name] = field_value[k : k + n_i]\n            # leave others as is\n            else:\n                output_i_dict[field.name] = field_value\n        detection_i.pred_densepose = PredictorOutput(**output_i_dict)\n        k += n_i\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/losses/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom .chart import DensePoseChartLoss\nfrom .chart_with_confidences import DensePoseChartWithConfidenceLoss\nfrom .cse import DensePoseCseLoss\nfrom .registry import DENSEPOSE_LOSS_REGISTRY\n\n\n__all__ = [\n    \"DensePoseChartLoss\",\n    \"DensePoseChartWithConfidenceLoss\",\n    \"DensePoseCseLoss\",\n    \"DENSEPOSE_LOSS_REGISTRY\",\n]\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/losses/chart.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom typing import Any, List\nimport torch\nfrom torch.nn import functional as F\n\nfrom detectron2.config import CfgNode\nfrom detectron2.structures import Instances\n\nfrom .mask_or_segm import MaskOrSegmentationLoss\nfrom .registry import DENSEPOSE_LOSS_REGISTRY\nfrom .utils import (\n    BilinearInterpolationHelper,\n    ChartBasedAnnotationsAccumulator,\n    LossDict,\n    extract_packed_annotations_from_matches,\n)\n\n\n@DENSEPOSE_LOSS_REGISTRY.register()\nclass DensePoseChartLoss:\n    \"\"\"\n    DensePose loss for chart-based training. A mesh is split into charts,\n    each chart is given a label (I) and parametrized by 2 coordinates referred to\n    as U and V. Ground truth consists of a number of points annotated with\n    I, U and V values and coarse segmentation S defined for all pixels of the\n    object bounding box. In some cases (see `COARSE_SEGM_TRAINED_BY_MASKS`),\n    semantic segmentation annotations can be used as ground truth inputs as well.\n\n    Estimated values are tensors:\n     * U coordinates, tensor of shape [N, C, S, S]\n     * V coordinates, tensor of shape [N, C, S, S]\n     * fine segmentation estimates, tensor of shape [N, C, S, S] with raw unnormalized\n       scores for each fine segmentation label at each location\n     * coarse segmentation estimates, tensor of shape [N, D, S, S] with raw unnormalized\n       scores for each coarse segmentation label at each location\n    where N is the number of detections, C is the number of fine segmentation\n    labels, S is the estimate size ( = width = height) and D is the number of\n    coarse segmentation channels.\n\n    The losses are:\n    * regression (smooth L1) loss for U and V coordinates\n    * cross entropy loss for fine (I) and coarse (S) segmentations\n    Each loss has an associated weight\n    \"\"\"\n\n    def __init__(self, cfg: CfgNode):\n        \"\"\"\n        Initialize chart-based loss from configuration options\n\n        Args:\n            cfg (CfgNode): configuration options\n        \"\"\"\n        # fmt: off\n        self.heatmap_size = cfg.MODEL.ROI_DENSEPOSE_HEAD.HEATMAP_SIZE\n        self.w_points     = cfg.MODEL.ROI_DENSEPOSE_HEAD.POINT_REGRESSION_WEIGHTS\n        self.w_part       = cfg.MODEL.ROI_DENSEPOSE_HEAD.PART_WEIGHTS\n        self.w_segm       = cfg.MODEL.ROI_DENSEPOSE_HEAD.INDEX_WEIGHTS\n        self.n_segm_chan  = cfg.MODEL.ROI_DENSEPOSE_HEAD.NUM_COARSE_SEGM_CHANNELS\n        # fmt: on\n        self.segm_trained_by_masks = cfg.MODEL.ROI_DENSEPOSE_HEAD.COARSE_SEGM_TRAINED_BY_MASKS\n        self.segm_loss = MaskOrSegmentationLoss(cfg)\n\n    def __call__(\n        self, proposals_with_gt: List[Instances], densepose_predictor_outputs: Any, **kwargs\n    ) -> LossDict:\n        \"\"\"\n        Produce chart-based DensePose losses\n\n        Args:\n            proposals_with_gt (list of Instances): detections with associated ground truth data\n            densepose_predictor_outputs: an object of a dataclass that contains predictor outputs\n                with estimated values; assumed to have the following attributes:\n                * coarse_segm - coarse segmentation estimates, tensor of shape [N, D, S, S]\n                * fine_segm - fine segmentation estimates, tensor of shape [N, C, S, S]\n                * u - U coordinate estimates per fine labels, tensor of shape [N, C, S, S]\n                * v - V coordinate estimates per fine labels, tensor of shape [N, C, S, S]\n            where N is the number of detections, C is the number of fine segmentation\n            labels, S is the estimate size ( = width = height) and D is the number of\n            coarse segmentation channels.\n\n        Return:\n            dict: str -> tensor: dict of losses with the following entries:\n             * `loss_densepose_U`: smooth L1 loss for U coordinate estimates\n             * `loss_densepose_V`: smooth L1 loss for V coordinate estimates\n             * `loss_densepose_I`: cross entropy for raw unnormalized scores for fine\n                 segmentation estimates given ground truth labels;\n             * `loss_densepose_S`: cross entropy for raw unnormalized scores for coarse\n                 segmentation estimates given ground truth labels;\n        \"\"\"\n        # densepose outputs are computed for all images and all bounding boxes;\n        # i.e. if a batch has 4 images with (3, 1, 2, 1) proposals respectively,\n        # the outputs will have size(0) == 3+1+2+1 == 7\n\n        if not len(proposals_with_gt):\n            return self.produce_fake_densepose_losses(densepose_predictor_outputs)\n\n        accumulator = ChartBasedAnnotationsAccumulator()\n        packed_annotations = extract_packed_annotations_from_matches(proposals_with_gt, accumulator)\n\n        # NOTE: we need to keep the same computation graph on all the GPUs to\n        # perform reduction properly. Hence even if we have no data on one\n        # of the GPUs, we still need to generate the computation graph.\n        # Add fake (zero) loss in the form Tensor.sum() * 0\n        if packed_annotations is None:\n            return self.produce_fake_densepose_losses(densepose_predictor_outputs)\n\n        h, w = densepose_predictor_outputs.u.shape[2:]\n        interpolator = BilinearInterpolationHelper.from_matches(\n            packed_annotations,\n            (h, w),\n        )\n\n        j_valid_fg = interpolator.j_valid * (  # pyre-ignore[16]\n            packed_annotations.fine_segm_labels_gt > 0\n        )\n        if not torch.any(j_valid_fg):\n            return self.produce_fake_densepose_losses(densepose_predictor_outputs)\n\n        losses_uv = self.produce_densepose_losses_uv(\n            proposals_with_gt,\n            densepose_predictor_outputs,\n            packed_annotations,\n            interpolator,\n            j_valid_fg,  # pyre-ignore[6]\n        )\n\n        losses_segm = self.produce_densepose_losses_segm(\n            proposals_with_gt,\n            densepose_predictor_outputs,\n            packed_annotations,\n            interpolator,\n            j_valid_fg,  # pyre-ignore[6]\n        )\n\n        return {**losses_uv, **losses_segm}\n\n    def produce_fake_densepose_losses(self, densepose_predictor_outputs: Any) -> LossDict:\n        \"\"\"\n        Fake losses for fine segmentation and U/V coordinates. These are used when\n        no suitable ground truth data was found in a batch. The loss has a value 0\n        and is primarily used to construct the computation graph, so that\n        `DistributedDataParallel` has similar graphs on all GPUs and can perform\n        reduction properly.\n\n        Args:\n            densepose_predictor_outputs: DensePose predictor outputs, an object\n                of a dataclass that is assumed to have the following attributes:\n             * fine_segm - fine segmentation estimates, tensor of shape [N, C, S, S]\n             * u - U coordinate estimates per fine labels, tensor of shape [N, C, S, S]\n             * v - V coordinate estimates per fine labels, tensor of shape [N, C, S, S]\n        Return:\n            dict: str -> tensor: dict of losses with the following entries:\n             * `loss_densepose_U`: has value 0\n             * `loss_densepose_V`: has value 0\n             * `loss_densepose_I`: has value 0\n             * `loss_densepose_S`: has value 0\n        \"\"\"\n        losses_uv = self.produce_fake_densepose_losses_uv(densepose_predictor_outputs)\n        losses_segm = self.produce_fake_densepose_losses_segm(densepose_predictor_outputs)\n        return {**losses_uv, **losses_segm}\n\n    def produce_fake_densepose_losses_uv(self, densepose_predictor_outputs: Any) -> LossDict:\n        \"\"\"\n        Fake losses for U/V coordinates. These are used when no suitable ground\n        truth data was found in a batch. The loss has a value 0\n        and is primarily used to construct the computation graph, so that\n        `DistributedDataParallel` has similar graphs on all GPUs and can perform\n        reduction properly.\n\n        Args:\n            densepose_predictor_outputs: DensePose predictor outputs, an object\n                of a dataclass that is assumed to have the following attributes:\n             * u - U coordinate estimates per fine labels, tensor of shape [N, C, S, S]\n             * v - V coordinate estimates per fine labels, tensor of shape [N, C, S, S]\n        Return:\n            dict: str -> tensor: dict of losses with the following entries:\n             * `loss_densepose_U`: has value 0\n             * `loss_densepose_V`: has value 0\n        \"\"\"\n        return {\n            \"loss_densepose_U\": densepose_predictor_outputs.u.sum() * 0,\n            \"loss_densepose_V\": densepose_predictor_outputs.v.sum() * 0,\n        }\n\n    def produce_fake_densepose_losses_segm(self, densepose_predictor_outputs: Any) -> LossDict:\n        \"\"\"\n        Fake losses for fine / coarse segmentation. These are used when\n        no suitable ground truth data was found in a batch. The loss has a value 0\n        and is primarily used to construct the computation graph, so that\n        `DistributedDataParallel` has similar graphs on all GPUs and can perform\n        reduction properly.\n\n        Args:\n            densepose_predictor_outputs: DensePose predictor outputs, an object\n                of a dataclass that is assumed to have the following attributes:\n             * fine_segm - fine segmentation estimates, tensor of shape [N, C, S, S]\n             * coarse_segm - coarse segmentation estimates, tensor of shape [N, D, S, S]\n        Return:\n            dict: str -> tensor: dict of losses with the following entries:\n             * `loss_densepose_I`: has value 0\n             * `loss_densepose_S`: has value 0, added only if `segm_trained_by_masks` is False\n        \"\"\"\n        losses = {\n            \"loss_densepose_I\": densepose_predictor_outputs.fine_segm.sum() * 0,\n            \"loss_densepose_S\": self.segm_loss.fake_value(densepose_predictor_outputs),\n        }\n        return losses\n\n    def produce_densepose_losses_uv(\n        self,\n        proposals_with_gt: List[Instances],\n        densepose_predictor_outputs: Any,\n        packed_annotations: Any,\n        interpolator: BilinearInterpolationHelper,\n        j_valid_fg: torch.Tensor,\n    ) -> LossDict:\n        \"\"\"\n        Compute losses for U/V coordinates: smooth L1 loss between\n        estimated coordinates and the ground truth.\n\n        Args:\n            proposals_with_gt (list of Instances): detections with associated ground truth data\n            densepose_predictor_outputs: DensePose predictor outputs, an object\n                of a dataclass that is assumed to have the following attributes:\n             * u - U coordinate estimates per fine labels, tensor of shape [N, C, S, S]\n             * v - V coordinate estimates per fine labels, tensor of shape [N, C, S, S]\n        Return:\n            dict: str -> tensor: dict of losses with the following entries:\n             * `loss_densepose_U`: smooth L1 loss for U coordinate estimates\n             * `loss_densepose_V`: smooth L1 loss for V coordinate estimates\n        \"\"\"\n        u_gt = packed_annotations.u_gt[j_valid_fg]\n        u_est = interpolator.extract_at_points(densepose_predictor_outputs.u)[j_valid_fg]\n        v_gt = packed_annotations.v_gt[j_valid_fg]\n        v_est = interpolator.extract_at_points(densepose_predictor_outputs.v)[j_valid_fg]\n        return {\n            \"loss_densepose_U\": F.smooth_l1_loss(u_est, u_gt, reduction=\"sum\") * self.w_points,\n            \"loss_densepose_V\": F.smooth_l1_loss(v_est, v_gt, reduction=\"sum\") * self.w_points,\n        }\n\n    def produce_densepose_losses_segm(\n        self,\n        proposals_with_gt: List[Instances],\n        densepose_predictor_outputs: Any,\n        packed_annotations: Any,\n        interpolator: BilinearInterpolationHelper,\n        j_valid_fg: torch.Tensor,\n    ) -> LossDict:\n        \"\"\"\n        Losses for fine / coarse segmentation: cross-entropy\n        for segmentation unnormalized scores given ground truth labels at\n        annotated points for fine segmentation and dense mask annotations\n        for coarse segmentation.\n\n        Args:\n            proposals_with_gt (list of Instances): detections with associated ground truth data\n            densepose_predictor_outputs: DensePose predictor outputs, an object\n                of a dataclass that is assumed to have the following attributes:\n             * fine_segm - fine segmentation estimates, tensor of shape [N, C, S, S]\n             * coarse_segm - coarse segmentation estimates, tensor of shape [N, D, S, S]\n        Return:\n            dict: str -> tensor: dict of losses with the following entries:\n             * `loss_densepose_I`: cross entropy for raw unnormalized scores for fine\n                 segmentation estimates given ground truth labels\n             * `loss_densepose_S`: cross entropy for raw unnormalized scores for coarse\n                 segmentation estimates given ground truth labels;\n                 may be included if coarse segmentation is only trained\n                 using DensePose ground truth; if additional supervision through\n                 instance segmentation data is performed (`segm_trained_by_masks` is True),\n                 this loss is handled by `produce_mask_losses` instead\n        \"\"\"\n        fine_segm_gt = packed_annotations.fine_segm_labels_gt[\n            interpolator.j_valid  # pyre-ignore[16]\n        ]\n        fine_segm_est = interpolator.extract_at_points(\n            densepose_predictor_outputs.fine_segm,\n            slice_fine_segm=slice(None),\n            w_ylo_xlo=interpolator.w_ylo_xlo[:, None],  # pyre-ignore[16]\n            w_ylo_xhi=interpolator.w_ylo_xhi[:, None],  # pyre-ignore[16]\n            w_yhi_xlo=interpolator.w_yhi_xlo[:, None],  # pyre-ignore[16]\n            w_yhi_xhi=interpolator.w_yhi_xhi[:, None],  # pyre-ignore[16]\n        )[interpolator.j_valid, :]\n        return {\n            \"loss_densepose_I\": F.cross_entropy(fine_segm_est, fine_segm_gt.long()) * self.w_part,\n            \"loss_densepose_S\": self.segm_loss(\n                proposals_with_gt, densepose_predictor_outputs, packed_annotations\n            )\n            * self.w_segm,\n        }\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/losses/chart_with_confidences.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport math\nfrom typing import Any, List\nimport torch\nfrom torch import nn\nfrom torch.nn import functional as F\n\nfrom detectron2.config import CfgNode\nfrom detectron2.structures import Instances\n\nfrom .. import DensePoseConfidenceModelConfig, DensePoseUVConfidenceType\nfrom .chart import DensePoseChartLoss\nfrom .registry import DENSEPOSE_LOSS_REGISTRY\nfrom .utils import BilinearInterpolationHelper, LossDict\n\n\n@DENSEPOSE_LOSS_REGISTRY.register()\nclass DensePoseChartWithConfidenceLoss(DensePoseChartLoss):\n    \"\"\" \"\"\"\n\n    def __init__(self, cfg: CfgNode):\n        super().__init__(cfg)\n        self.confidence_model_cfg = DensePoseConfidenceModelConfig.from_cfg(cfg)\n        if self.confidence_model_cfg.uv_confidence.type == DensePoseUVConfidenceType.IID_ISO:\n            self.uv_loss_with_confidences = IIDIsotropicGaussianUVLoss(\n                self.confidence_model_cfg.uv_confidence.epsilon\n            )\n        elif self.confidence_model_cfg.uv_confidence.type == DensePoseUVConfidenceType.INDEP_ANISO:\n            self.uv_loss_with_confidences = IndepAnisotropicGaussianUVLoss(\n                self.confidence_model_cfg.uv_confidence.epsilon\n            )\n\n    def produce_fake_densepose_losses_uv(self, densepose_predictor_outputs: Any) -> LossDict:\n        \"\"\"\n        Overrides fake losses for fine segmentation and U/V coordinates to\n        include computation graphs for additional confidence parameters.\n        These are used when no suitable ground truth data was found in a batch.\n        The loss has a value 0 and is primarily used to construct the computation graph,\n        so that `DistributedDataParallel` has similar graphs on all GPUs and can\n        perform reduction properly.\n\n        Args:\n            densepose_predictor_outputs: DensePose predictor outputs, an object\n                of a dataclass that is assumed to have the following attributes:\n             * fine_segm - fine segmentation estimates, tensor of shape [N, C, S, S]\n             * u - U coordinate estimates per fine labels, tensor of shape [N, C, S, S]\n             * v - V coordinate estimates per fine labels, tensor of shape [N, C, S, S]\n        Return:\n            dict: str -> tensor: dict of losses with the following entries:\n             * `loss_densepose_U`: has value 0\n             * `loss_densepose_V`: has value 0\n             * `loss_densepose_I`: has value 0\n        \"\"\"\n        conf_type = self.confidence_model_cfg.uv_confidence.type\n        if self.confidence_model_cfg.uv_confidence.enabled:\n            loss_uv = (\n                densepose_predictor_outputs.u.sum() + densepose_predictor_outputs.v.sum()\n            ) * 0\n            if conf_type == DensePoseUVConfidenceType.IID_ISO:\n                loss_uv += densepose_predictor_outputs.sigma_2.sum() * 0\n            elif conf_type == DensePoseUVConfidenceType.INDEP_ANISO:\n                loss_uv += (\n                    densepose_predictor_outputs.sigma_2.sum()\n                    + densepose_predictor_outputs.kappa_u.sum()\n                    + densepose_predictor_outputs.kappa_v.sum()\n                ) * 0\n            return {\"loss_densepose_UV\": loss_uv}\n        else:\n            return super().produce_fake_densepose_losses_uv(densepose_predictor_outputs)\n\n    def produce_densepose_losses_uv(\n        self,\n        proposals_with_gt: List[Instances],\n        densepose_predictor_outputs: Any,\n        packed_annotations: Any,\n        interpolator: BilinearInterpolationHelper,\n        j_valid_fg: torch.Tensor,\n    ) -> LossDict:\n        conf_type = self.confidence_model_cfg.uv_confidence.type\n        if self.confidence_model_cfg.uv_confidence.enabled:\n            u_gt = packed_annotations.u_gt[j_valid_fg]\n            u_est = interpolator.extract_at_points(densepose_predictor_outputs.u)[j_valid_fg]\n            v_gt = packed_annotations.v_gt[j_valid_fg]\n            v_est = interpolator.extract_at_points(densepose_predictor_outputs.v)[j_valid_fg]\n            sigma_2_est = interpolator.extract_at_points(densepose_predictor_outputs.sigma_2)[\n                j_valid_fg\n            ]\n            if conf_type == DensePoseUVConfidenceType.IID_ISO:\n                return {\n                    \"loss_densepose_UV\": (\n                        self.uv_loss_with_confidences(u_est, v_est, sigma_2_est, u_gt, v_gt)\n                        * self.w_points\n                    )\n                }\n            elif conf_type in [DensePoseUVConfidenceType.INDEP_ANISO]:\n                kappa_u_est = interpolator.extract_at_points(densepose_predictor_outputs.kappa_u)[\n                    j_valid_fg\n                ]\n                kappa_v_est = interpolator.extract_at_points(densepose_predictor_outputs.kappa_v)[\n                    j_valid_fg\n                ]\n                return {\n                    \"loss_densepose_UV\": (\n                        self.uv_loss_with_confidences(\n                            u_est, v_est, sigma_2_est, kappa_u_est, kappa_v_est, u_gt, v_gt\n                        )\n                        * self.w_points\n                    )\n                }\n        return super().produce_densepose_losses_uv(\n            proposals_with_gt,\n            densepose_predictor_outputs,\n            packed_annotations,\n            interpolator,\n            j_valid_fg,\n        )\n\n\nclass IIDIsotropicGaussianUVLoss(nn.Module):\n    \"\"\"\n    Loss for the case of iid residuals with isotropic covariance:\n    $Sigma_i = sigma_i^2 I$\n    The loss (negative log likelihood) is then:\n    $1/2 sum_{i=1}^n (log(2 pi) + 2 log sigma_i^2 + ||delta_i||^2 / sigma_i^2)$,\n    where $delta_i=(u - u', v - v')$ is a 2D vector containing UV coordinates\n    difference between estimated and ground truth UV values\n    For details, see:\n    N. Neverova, D. Novotny, A. Vedaldi \"Correlated Uncertainty for Learning\n    Dense Correspondences from Noisy Labels\", p. 918--926, in Proc. NIPS 2019\n    \"\"\"\n\n    def __init__(self, sigma_lower_bound: float):\n        super(IIDIsotropicGaussianUVLoss, self).__init__()\n        self.sigma_lower_bound = sigma_lower_bound\n        self.log2pi = math.log(2 * math.pi)\n\n    def forward(\n        self,\n        u: torch.Tensor,\n        v: torch.Tensor,\n        sigma_u: torch.Tensor,\n        target_u: torch.Tensor,\n        target_v: torch.Tensor,\n    ):\n        # compute $\\sigma_i^2$\n        # use sigma_lower_bound to avoid degenerate solution for variance\n        # (sigma -> 0)\n        sigma2 = F.softplus(sigma_u) + self.sigma_lower_bound\n        # compute \\|delta_i\\|^2\n        delta_t_delta = (u - target_u) ** 2 + (v - target_v) ** 2\n        # the total loss from the formula above:\n        loss = 0.5 * (self.log2pi + 2 * torch.log(sigma2) + delta_t_delta / sigma2)\n        # pyre-fixme[16]: `float` has no attribute `sum`.\n        return loss.sum()\n\n\nclass IndepAnisotropicGaussianUVLoss(nn.Module):\n    \"\"\"\n    Loss for the case of independent residuals with anisotropic covariances:\n    $Sigma_i = sigma_i^2 I + r_i r_i^T$\n    The loss (negative log likelihood) is then:\n    $1/2 sum_{i=1}^n (log(2 pi)\n      + log sigma_i^2 (sigma_i^2 + ||r_i||^2)\n      + ||delta_i||^2 / sigma_i^2\n      - <delta_i, r_i>^2 / (sigma_i^2 * (sigma_i^2 + ||r_i||^2)))$,\n    where $delta_i=(u - u', v - v')$ is a 2D vector containing UV coordinates\n    difference between estimated and ground truth UV values\n    For details, see:\n    N. Neverova, D. Novotny, A. Vedaldi \"Correlated Uncertainty for Learning\n    Dense Correspondences from Noisy Labels\", p. 918--926, in Proc. NIPS 2019\n    \"\"\"\n\n    def __init__(self, sigma_lower_bound: float):\n        super(IndepAnisotropicGaussianUVLoss, self).__init__()\n        self.sigma_lower_bound = sigma_lower_bound\n        self.log2pi = math.log(2 * math.pi)\n\n    def forward(\n        self,\n        u: torch.Tensor,\n        v: torch.Tensor,\n        sigma_u: torch.Tensor,\n        kappa_u_est: torch.Tensor,\n        kappa_v_est: torch.Tensor,\n        target_u: torch.Tensor,\n        target_v: torch.Tensor,\n    ):\n        # compute $\\sigma_i^2$\n        sigma2 = F.softplus(sigma_u) + self.sigma_lower_bound\n        # compute \\|r_i\\|^2\n        r_sqnorm2 = kappa_u_est ** 2 + kappa_v_est ** 2\n        delta_u = u - target_u\n        delta_v = v - target_v\n        # compute \\|delta_i\\|^2\n        delta_sqnorm = delta_u ** 2 + delta_v ** 2\n        delta_u_r_u = delta_u * kappa_u_est\n        delta_v_r_v = delta_v * kappa_v_est\n        # compute the scalar product <delta_i, r_i>\n        delta_r = delta_u_r_u + delta_v_r_v\n        # compute squared scalar product <delta_i, r_i>^2\n        delta_r_sqnorm = delta_r ** 2\n        denom2 = sigma2 * (sigma2 + r_sqnorm2)\n        loss = 0.5 * (\n            self.log2pi + torch.log(denom2) + delta_sqnorm / sigma2 - delta_r_sqnorm / denom2\n        )\n        return loss.sum()  # pyre-ignore[16]\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/losses/cse.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nfrom typing import Any, List\nfrom torch import nn\n\nfrom detectron2.config import CfgNode\nfrom detectron2.structures import Instances\n\nfrom .cycle_pix2shape import PixToShapeCycleLoss\nfrom .cycle_shape2shape import ShapeToShapeCycleLoss\nfrom .embed import EmbeddingLoss\nfrom .embed_utils import CseAnnotationsAccumulator\nfrom .mask_or_segm import MaskOrSegmentationLoss\nfrom .registry import DENSEPOSE_LOSS_REGISTRY\nfrom .soft_embed import SoftEmbeddingLoss\nfrom .utils import BilinearInterpolationHelper, LossDict, extract_packed_annotations_from_matches\n\n\n@DENSEPOSE_LOSS_REGISTRY.register()\nclass DensePoseCseLoss:\n    \"\"\" \"\"\"\n\n    _EMBED_LOSS_REGISTRY = {\n        EmbeddingLoss.__name__: EmbeddingLoss,\n        SoftEmbeddingLoss.__name__: SoftEmbeddingLoss,\n    }\n\n    def __init__(self, cfg: CfgNode):\n        \"\"\"\n        Initialize CSE loss from configuration options\n\n        Args:\n            cfg (CfgNode): configuration options\n        \"\"\"\n        self.w_segm = cfg.MODEL.ROI_DENSEPOSE_HEAD.INDEX_WEIGHTS\n        self.w_embed = cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBED_LOSS_WEIGHT\n        self.segm_loss = MaskOrSegmentationLoss(cfg)\n        self.embed_loss = DensePoseCseLoss.create_embed_loss(cfg)\n        self.do_shape2shape = cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.SHAPE_TO_SHAPE_CYCLE_LOSS.ENABLED\n        if self.do_shape2shape:\n            self.w_shape2shape = cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.SHAPE_TO_SHAPE_CYCLE_LOSS.WEIGHT\n            self.shape2shape_loss = ShapeToShapeCycleLoss(cfg)\n        self.do_pix2shape = cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.PIX_TO_SHAPE_CYCLE_LOSS.ENABLED\n        if self.do_pix2shape:\n            self.w_pix2shape = cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.PIX_TO_SHAPE_CYCLE_LOSS.WEIGHT\n            self.pix2shape_loss = PixToShapeCycleLoss(cfg)\n\n    @classmethod\n    def create_embed_loss(cls, cfg: CfgNode):\n        # registry not used here, since embedding losses are currently local\n        # and are not used anywhere else\n        return cls._EMBED_LOSS_REGISTRY[cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBED_LOSS_NAME](cfg)\n\n    def __call__(\n        self,\n        proposals_with_gt: List[Instances],\n        densepose_predictor_outputs: Any,\n        embedder: nn.Module,\n    ) -> LossDict:\n        if not len(proposals_with_gt):\n            return self.produce_fake_losses(densepose_predictor_outputs, embedder)\n        accumulator = CseAnnotationsAccumulator()\n        packed_annotations = extract_packed_annotations_from_matches(proposals_with_gt, accumulator)\n        if packed_annotations is None:\n            return self.produce_fake_losses(densepose_predictor_outputs, embedder)\n        h, w = densepose_predictor_outputs.embedding.shape[2:]\n        interpolator = BilinearInterpolationHelper.from_matches(\n            packed_annotations,\n            (h, w),\n        )\n        meshid_to_embed_losses = self.embed_loss(\n            proposals_with_gt,\n            densepose_predictor_outputs,\n            packed_annotations,\n            interpolator,\n            embedder,\n        )\n        embed_loss_dict = {\n            f\"loss_densepose_E{meshid}\": self.w_embed * meshid_to_embed_losses[meshid]\n            for meshid in meshid_to_embed_losses\n        }\n        all_loss_dict = {\n            \"loss_densepose_S\": self.w_segm\n            * self.segm_loss(proposals_with_gt, densepose_predictor_outputs, packed_annotations),\n            **embed_loss_dict,\n        }\n        if self.do_shape2shape:\n            all_loss_dict[\"loss_shape2shape\"] = self.w_shape2shape * self.shape2shape_loss(embedder)\n        if self.do_pix2shape:\n            all_loss_dict[\"loss_pix2shape\"] = self.w_pix2shape * self.pix2shape_loss(\n                proposals_with_gt, densepose_predictor_outputs, packed_annotations, embedder\n            )\n        return all_loss_dict\n\n    def produce_fake_losses(\n        self, densepose_predictor_outputs: Any, embedder: nn.Module\n    ) -> LossDict:\n        meshname_to_embed_losses = self.embed_loss.fake_values(\n            densepose_predictor_outputs, embedder=embedder\n        )\n        embed_loss_dict = {\n            f\"loss_densepose_E{mesh_name}\": meshname_to_embed_losses[mesh_name]\n            for mesh_name in meshname_to_embed_losses\n        }\n        all_loss_dict = {\n            \"loss_densepose_S\": self.segm_loss.fake_value(densepose_predictor_outputs),\n            **embed_loss_dict,\n        }\n        if self.do_shape2shape:\n            all_loss_dict[\"loss_shape2shape\"] = self.shape2shape_loss.fake_value(embedder)\n        if self.do_pix2shape:\n            all_loss_dict[\"loss_pix2shape\"] = self.pix2shape_loss.fake_value(\n                densepose_predictor_outputs, embedder\n            )\n        return all_loss_dict\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/losses/cycle_pix2shape.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nfrom typing import Any, List\nimport torch\nfrom torch import nn\nfrom torch.nn import functional as F\n\nfrom detectron2.config import CfgNode\nfrom detectron2.structures import Instances\n\nfrom densepose.data.meshes.catalog import MeshCatalog\nfrom densepose.modeling.cse.utils import normalize_embeddings, squared_euclidean_distance_matrix\n\nfrom .embed_utils import PackedCseAnnotations\nfrom .mask import extract_data_for_mask_loss_from_matches\n\n\ndef _create_pixel_dist_matrix(grid_size: int) -> torch.Tensor:\n    rows = torch.arange(grid_size)\n    cols = torch.arange(grid_size)\n    # at index `i` contains [row, col], where\n    # row = i // grid_size\n    # col = i % grid_size\n    pix_coords = (\n        torch.stack(torch.meshgrid(rows, cols), -1).reshape((grid_size * grid_size, 2)).float()\n    )\n    return squared_euclidean_distance_matrix(pix_coords, pix_coords)\n\n\ndef _sample_fg_pixels_randperm(fg_mask: torch.Tensor, sample_size: int) -> torch.Tensor:\n    fg_mask_flattened = fg_mask.reshape((-1,))\n    num_pixels = int(fg_mask_flattened.sum().item())\n    fg_pixel_indices = fg_mask_flattened.nonzero(as_tuple=True)[0]\n    if (sample_size <= 0) or (num_pixels <= sample_size):\n        return fg_pixel_indices\n    sample_indices = torch.randperm(num_pixels, device=fg_mask.device)[:sample_size]\n    return fg_pixel_indices[sample_indices]\n\n\ndef _sample_fg_pixels_multinomial(fg_mask: torch.Tensor, sample_size: int) -> torch.Tensor:\n    fg_mask_flattened = fg_mask.reshape((-1,))\n    num_pixels = int(fg_mask_flattened.sum().item())\n    if (sample_size <= 0) or (num_pixels <= sample_size):\n        return fg_mask_flattened.nonzero(as_tuple=True)[0]\n    return fg_mask_flattened.float().multinomial(sample_size, replacement=False)  # pyre-ignore[16]\n\n\nclass PixToShapeCycleLoss(nn.Module):\n    \"\"\"\n    Cycle loss for pixel-vertex correspondence\n    \"\"\"\n\n    def __init__(self, cfg: CfgNode):\n        super().__init__()\n        self.shape_names = list(cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBEDDERS.keys())\n        self.embed_size = cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBED_SIZE\n        self.norm_p = cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.PIX_TO_SHAPE_CYCLE_LOSS.NORM_P\n        self.use_all_meshes_not_gt_only = (\n            cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.PIX_TO_SHAPE_CYCLE_LOSS.USE_ALL_MESHES_NOT_GT_ONLY\n        )\n        self.num_pixels_to_sample = (\n            cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.PIX_TO_SHAPE_CYCLE_LOSS.NUM_PIXELS_TO_SAMPLE\n        )\n        self.pix_sigma = cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.PIX_TO_SHAPE_CYCLE_LOSS.PIXEL_SIGMA\n        self.temperature_pix_to_vertex = (\n            cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.PIX_TO_SHAPE_CYCLE_LOSS.TEMPERATURE_PIXEL_TO_VERTEX\n        )\n        self.temperature_vertex_to_pix = (\n            cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.PIX_TO_SHAPE_CYCLE_LOSS.TEMPERATURE_VERTEX_TO_PIXEL\n        )\n        self.pixel_dists = _create_pixel_dist_matrix(cfg.MODEL.ROI_DENSEPOSE_HEAD.HEATMAP_SIZE)\n\n    def forward(\n        self,\n        proposals_with_gt: List[Instances],\n        densepose_predictor_outputs: Any,\n        packed_annotations: PackedCseAnnotations,\n        embedder: nn.Module,\n    ):\n        \"\"\"\n        Args:\n            proposals_with_gt (list of Instances): detections with associated\n                ground truth data; each item corresponds to instances detected\n                on 1 image; the number of items corresponds to the number of\n                images in a batch\n            densepose_predictor_outputs: an object of a dataclass that contains predictor\n                outputs with estimated values; assumed to have the following attributes:\n                * embedding - embedding estimates, tensor of shape [N, D, S, S], where\n                  N = number of instances (= sum N_i, where N_i is the number of\n                      instances on image i)\n                  D = embedding space dimensionality (MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBED_SIZE)\n                  S = output size (width and height)\n            packed_annotations (PackedCseAnnotations): contains various data useful\n                for loss computation, each data is packed into a single tensor\n            embedder (nn.Module): module that computes vertex embeddings for different meshes\n        \"\"\"\n        pix_embeds = densepose_predictor_outputs.embedding\n        if self.pixel_dists.device != pix_embeds.device:\n            # should normally be done only once\n            self.pixel_dists = self.pixel_dists.to(device=pix_embeds.device)\n        with torch.no_grad():\n            mask_loss_data = extract_data_for_mask_loss_from_matches(\n                proposals_with_gt, densepose_predictor_outputs.coarse_segm\n            )\n        # GT masks - tensor of shape [N, S, S] of int64\n        masks_gt = mask_loss_data.masks_gt.long()  # pyre-ignore[16]\n        assert len(pix_embeds) == len(masks_gt), (\n            f\"Number of instances with embeddings {len(pix_embeds)} != \"\n            f\"number of instances with GT masks {len(masks_gt)}\"\n        )\n        losses = []\n        mesh_names = (\n            self.shape_names\n            if self.use_all_meshes_not_gt_only\n            else [\n                MeshCatalog.get_mesh_name(mesh_id.item())\n                for mesh_id in packed_annotations.vertex_mesh_ids_gt.unique()  # pyre-ignore[16]\n            ]\n        )\n        for pixel_embeddings, mask_gt in zip(pix_embeds, masks_gt):\n            # pixel_embeddings [D, S, S]\n            # mask_gt [S, S]\n            for mesh_name in mesh_names:\n                mesh_vertex_embeddings = embedder(mesh_name)\n                # pixel indices [M]\n                pixel_indices_flattened = _sample_fg_pixels_randperm(\n                    mask_gt, self.num_pixels_to_sample\n                )\n                # pixel distances [M, M]\n                pixel_dists = self.pixel_dists.to(pixel_embeddings.device)[\n                    torch.meshgrid(pixel_indices_flattened, pixel_indices_flattened)\n                ]\n                # pixel embeddings [M, D]\n                pixel_embeddings_sampled = normalize_embeddings(\n                    pixel_embeddings.reshape((self.embed_size, -1))[:, pixel_indices_flattened].T\n                )\n                # pixel-vertex similarity [M, K]\n                sim_matrix = pixel_embeddings_sampled.mm(  # pyre-ignore[16]\n                    mesh_vertex_embeddings.T\n                )\n                c_pix_vertex = F.softmax(sim_matrix / self.temperature_pix_to_vertex, dim=1)\n                c_vertex_pix = F.softmax(sim_matrix.T / self.temperature_vertex_to_pix, dim=1)\n                c_cycle = c_pix_vertex.mm(c_vertex_pix)\n                loss_cycle = torch.norm(pixel_dists * c_cycle, p=self.norm_p)\n                losses.append(loss_cycle)\n\n        if len(losses) == 0:\n            return pix_embeds.sum() * 0\n        return torch.stack(losses, dim=0).mean()\n\n    def fake_value(self, densepose_predictor_outputs: Any, embedder: nn.Module):\n        losses = [\n            embedder(mesh_name).sum() * 0 for mesh_name in embedder.mesh_names  # pyre-ignore[29]\n        ]\n        losses.append(densepose_predictor_outputs.embedding.sum() * 0)\n        return torch.mean(torch.stack(losses))\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/losses/cycle_shape2shape.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nimport random\nfrom typing import Tuple\nimport torch\nfrom torch import nn\nfrom torch.nn import functional as F\n\nfrom detectron2.config import CfgNode\n\nfrom densepose.structures.mesh import create_mesh\n\nfrom .utils import sample_random_indices\n\n\nclass ShapeToShapeCycleLoss(nn.Module):\n    \"\"\"\n    Cycle Loss for Shapes.\n    Inspired by:\n    \"Mapping in a Cycle: Sinkhorn Regularized Unsupervised Learning for Point Cloud Shapes\".\n    \"\"\"\n\n    def __init__(self, cfg: CfgNode):\n        super().__init__()\n        self.shape_names = list(cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBEDDERS.keys())\n        self.all_shape_pairs = [\n            (x, y) for i, x in enumerate(self.shape_names) for y in self.shape_names[i + 1 :]\n        ]\n        random.shuffle(self.all_shape_pairs)\n        self.cur_pos = 0\n        self.norm_p = cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.SHAPE_TO_SHAPE_CYCLE_LOSS.NORM_P\n        self.temperature = cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.SHAPE_TO_SHAPE_CYCLE_LOSS.TEMPERATURE\n        self.max_num_vertices = (\n            cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.SHAPE_TO_SHAPE_CYCLE_LOSS.MAX_NUM_VERTICES\n        )\n\n    def _sample_random_pair(self) -> Tuple[str, str]:\n        \"\"\"\n        Produce a random pair of different mesh names\n\n        Return:\n            tuple(str, str): a pair of different mesh names\n        \"\"\"\n        if self.cur_pos >= len(self.all_shape_pairs):\n            random.shuffle(self.all_shape_pairs)\n            self.cur_pos = 0\n        shape_pair = self.all_shape_pairs[self.cur_pos]\n        self.cur_pos += 1\n        return shape_pair\n\n    def forward(self, embedder: nn.Module):\n        \"\"\"\n        Do a forward pass with a random pair (src, dst) pair of shapes\n        Args:\n            embedder (nn.Module): module that computes vertex embeddings for different meshes\n        \"\"\"\n        src_mesh_name, dst_mesh_name = self._sample_random_pair()\n        return self._forward_one_pair(embedder, src_mesh_name, dst_mesh_name)\n\n    def fake_value(self, embedder: nn.Module):\n        losses = []\n        for mesh_name in embedder.mesh_names:  # pyre-ignore[29]\n            losses.append(embedder(mesh_name).sum() * 0)\n        return torch.mean(torch.stack(losses))\n\n    def _get_embeddings_and_geodists_for_mesh(\n        self, embedder: nn.Module, mesh_name: str\n    ) -> Tuple[torch.Tensor, torch.Tensor]:\n        \"\"\"\n        Produces embeddings and geodesic distance tensors for a given mesh. May subsample\n        the mesh, if it contains too many vertices (controlled by\n        SHAPE_CYCLE_LOSS_MAX_NUM_VERTICES parameter).\n        Args:\n            embedder (nn.Module): module that computes embeddings for mesh vertices\n            mesh_name (str): mesh name\n        Return:\n            embeddings (torch.Tensor of size [N, D]): embeddings for selected mesh\n                vertices (N = number of selected vertices, D = embedding space dim)\n            geodists (torch.Tensor of size [N, N]): geodesic distances for the selected\n                mesh vertices (N = number of selected vertices)\n        \"\"\"\n        embeddings = embedder(mesh_name)\n        indices = sample_random_indices(\n            embeddings.shape[0], self.max_num_vertices, embeddings.device\n        )\n        mesh = create_mesh(mesh_name, embeddings.device)\n        geodists = mesh.geodists\n        if indices is not None:\n            embeddings = embeddings[indices]\n            geodists = geodists[torch.meshgrid(indices, indices)]\n        return embeddings, geodists\n\n    def _forward_one_pair(\n        self, embedder: nn.Module, mesh_name_1: str, mesh_name_2: str\n    ) -> torch.Tensor:\n        \"\"\"\n        Do a forward pass with a selected pair of meshes\n        Args:\n            embedder (nn.Module): module that computes vertex embeddings for different meshes\n            mesh_name_1 (str): first mesh name\n            mesh_name_2 (str): second mesh name\n        Return:\n            Tensor containing the loss value\n        \"\"\"\n        embeddings_1, geodists_1 = self._get_embeddings_and_geodists_for_mesh(embedder, mesh_name_1)\n        embeddings_2, geodists_2 = self._get_embeddings_and_geodists_for_mesh(embedder, mesh_name_2)\n        sim_matrix_12 = embeddings_1.mm(embeddings_2.T)  # pyre-ignore[16]\n\n        c_12 = F.softmax(sim_matrix_12 / self.temperature, dim=1)\n        c_21 = F.softmax(sim_matrix_12.T / self.temperature, dim=1)\n        c_11 = c_12.mm(c_21)\n        c_22 = c_21.mm(c_12)\n\n        loss_cycle_11 = torch.norm(geodists_1 * c_11, p=self.norm_p)\n        loss_cycle_22 = torch.norm(geodists_2 * c_22, p=self.norm_p)\n\n        return loss_cycle_11 + loss_cycle_22\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/losses/embed.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nfrom typing import Any, Dict, List\nimport torch\nfrom torch import nn\nfrom torch.nn import functional as F\n\nfrom detectron2.config import CfgNode\nfrom detectron2.structures import Instances\n\nfrom densepose.data.meshes.catalog import MeshCatalog\nfrom densepose.modeling.cse.utils import normalize_embeddings, squared_euclidean_distance_matrix\n\nfrom .embed_utils import PackedCseAnnotations\nfrom .utils import BilinearInterpolationHelper\n\n\nclass EmbeddingLoss:\n    \"\"\"\n    Computes losses for estimated embeddings given annotated vertices.\n    Instances in a minibatch that correspond to the same mesh are grouped\n    together. For each group, loss is computed as cross-entropy for\n    unnormalized scores given ground truth mesh vertex ids.\n    Scores are based on squared distances between estimated vertex embeddings\n    and mesh vertex embeddings.\n    \"\"\"\n\n    def __init__(self, cfg: CfgNode):\n        \"\"\"\n        Initialize embedding loss from config\n        \"\"\"\n        self.embdist_gauss_sigma = cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBEDDING_DIST_GAUSS_SIGMA\n\n    def __call__(\n        self,\n        proposals_with_gt: List[Instances],\n        densepose_predictor_outputs: Any,\n        packed_annotations: PackedCseAnnotations,\n        interpolator: BilinearInterpolationHelper,\n        embedder: nn.Module,\n    ) -> Dict[int, torch.Tensor]:\n        \"\"\"\n        Produces losses for estimated embeddings given annotated vertices.\n        Embeddings for all the vertices of a mesh are computed by the embedder.\n        Embeddings for observed pixels are estimated by a predictor.\n        Losses are computed as cross-entropy for squared distances between\n        observed vertex embeddings and all mesh vertex embeddings given\n        ground truth vertex IDs.\n\n        Args:\n            proposals_with_gt (list of Instances): detections with associated\n                ground truth data; each item corresponds to instances detected\n                on 1 image; the number of items corresponds to the number of\n                images in a batch\n            densepose_predictor_outputs: an object of a dataclass that contains predictor\n                outputs with estimated values; assumed to have the following attributes:\n                * embedding - embedding estimates, tensor of shape [N, D, S, S], where\n                  N = number of instances (= sum N_i, where N_i is the number of\n                      instances on image i)\n                  D = embedding space dimensionality (MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBED_SIZE)\n                  S = output size (width and height)\n            packed_annotations (PackedCseAnnotations): contains various data useful\n                for loss computation, each data is packed into a single tensor\n            interpolator (BilinearInterpolationHelper): bilinear interpolation helper\n            embedder (nn.Module): module that computes vertex embeddings for different meshes\n        Return:\n            dict(int -> tensor): losses for different mesh IDs\n        \"\"\"\n        losses = {}\n        for mesh_id_tensor in packed_annotations.vertex_mesh_ids_gt.unique():  # pyre-ignore[16]\n            mesh_id = mesh_id_tensor.item()\n            mesh_name = MeshCatalog.get_mesh_name(mesh_id)\n            # valid points are those that fall into estimated bbox\n            # and correspond to the current mesh\n            j_valid = interpolator.j_valid * (  # pyre-ignore[16]\n                packed_annotations.vertex_mesh_ids_gt == mesh_id\n            )\n            if not torch.any(j_valid):\n                continue\n            # extract estimated embeddings for valid points\n            # -> tensor [J, D]\n            vertex_embeddings_i = normalize_embeddings(\n                interpolator.extract_at_points(\n                    densepose_predictor_outputs.embedding,\n                    slice_fine_segm=slice(None),\n                    w_ylo_xlo=interpolator.w_ylo_xlo[:, None],  # pyre-ignore[16]\n                    w_ylo_xhi=interpolator.w_ylo_xhi[:, None],  # pyre-ignore[16]\n                    w_yhi_xlo=interpolator.w_yhi_xlo[:, None],  # pyre-ignore[16]\n                    w_yhi_xhi=interpolator.w_yhi_xhi[:, None],  # pyre-ignore[16]\n                )[j_valid, :]\n            )\n            # extract vertex ids for valid points\n            # -> tensor [J]\n            vertex_indices_i = packed_annotations.vertex_ids_gt[j_valid]\n            # embeddings for all mesh vertices\n            # -> tensor [K, D]\n            mesh_vertex_embeddings = embedder(mesh_name)\n            # unnormalized scores for valid points\n            # -> tensor [J, K]\n            scores = squared_euclidean_distance_matrix(\n                vertex_embeddings_i, mesh_vertex_embeddings\n            ) / (-self.embdist_gauss_sigma)\n            losses[mesh_name] = F.cross_entropy(scores, vertex_indices_i, ignore_index=-1)\n\n        # pyre-fixme[29]:\n        #  `Union[BoundMethod[typing.Callable(torch.Tensor.__iter__)[[Named(self,\n        #  torch.Tensor)], typing.Iterator[typing.Any]], torch.Tensor], nn.Module,\n        #  torch.Tensor]` is not a function.\n        for mesh_name in embedder.mesh_names:\n            if mesh_name not in losses:\n                losses[mesh_name] = self.fake_value(\n                    densepose_predictor_outputs, embedder, mesh_name\n                )\n        return losses\n\n    def fake_values(self, densepose_predictor_outputs: Any, embedder: nn.Module):\n        losses = {}\n        # pyre-fixme[29]:\n        #  `Union[BoundMethod[typing.Callable(torch.Tensor.__iter__)[[Named(self,\n        #  torch.Tensor)], typing.Iterator[typing.Any]], torch.Tensor], nn.Module,\n        #  torch.Tensor]` is not a function.\n        for mesh_name in embedder.mesh_names:\n            losses[mesh_name] = self.fake_value(densepose_predictor_outputs, embedder, mesh_name)\n        return losses\n\n    def fake_value(self, densepose_predictor_outputs: Any, embedder: nn.Module, mesh_name: str):\n        return densepose_predictor_outputs.embedding.sum() * 0 + embedder(mesh_name).sum() * 0\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/losses/embed_utils.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nfrom dataclasses import dataclass\nfrom typing import Any, Optional\nimport torch\n\nfrom detectron2.structures import BoxMode, Instances\n\nfrom .utils import AnnotationsAccumulator\n\n\n@dataclass\nclass PackedCseAnnotations:\n    x_gt: torch.Tensor\n    y_gt: torch.Tensor\n    coarse_segm_gt: Optional[torch.Tensor]\n    vertex_mesh_ids_gt: torch.Tensor\n    vertex_ids_gt: torch.Tensor\n    bbox_xywh_gt: torch.Tensor\n    bbox_xywh_est: torch.Tensor\n    point_bbox_with_dp_indices: torch.Tensor\n    point_bbox_indices: torch.Tensor\n    bbox_indices: torch.Tensor\n\n\nclass CseAnnotationsAccumulator(AnnotationsAccumulator):\n    \"\"\"\n    Accumulates annotations by batches that correspond to objects detected on\n    individual images. Can pack them together into single tensors.\n    \"\"\"\n\n    def __init__(self):\n        self.x_gt = []\n        self.y_gt = []\n        self.s_gt = []\n        self.vertex_mesh_ids_gt = []\n        self.vertex_ids_gt = []\n        self.bbox_xywh_gt = []\n        self.bbox_xywh_est = []\n        self.point_bbox_with_dp_indices = []\n        self.point_bbox_indices = []\n        self.bbox_indices = []\n        self.nxt_bbox_with_dp_index = 0\n        self.nxt_bbox_index = 0\n\n    def accumulate(self, instances_one_image: Instances):\n        \"\"\"\n        Accumulate instances data for one image\n\n        Args:\n            instances_one_image (Instances): instances data to accumulate\n        \"\"\"\n        boxes_xywh_est = BoxMode.convert(\n            instances_one_image.proposal_boxes.tensor.clone(), BoxMode.XYXY_ABS, BoxMode.XYWH_ABS\n        )\n        boxes_xywh_gt = BoxMode.convert(\n            instances_one_image.gt_boxes.tensor.clone(), BoxMode.XYXY_ABS, BoxMode.XYWH_ABS\n        )\n        n_matches = len(boxes_xywh_gt)\n        assert n_matches == len(\n            boxes_xywh_est\n        ), f\"Got {len(boxes_xywh_est)} proposal boxes and {len(boxes_xywh_gt)} GT boxes\"\n        if not n_matches:\n            # no detection - GT matches\n            return\n        if (\n            not hasattr(instances_one_image, \"gt_densepose\")\n            or instances_one_image.gt_densepose is None\n        ):\n            # no densepose GT for the detections, just increase the bbox index\n            self.nxt_bbox_index += n_matches\n            return\n        for box_xywh_est, box_xywh_gt, dp_gt in zip(\n            boxes_xywh_est, boxes_xywh_gt, instances_one_image.gt_densepose\n        ):\n            if (dp_gt is not None) and (len(dp_gt.x) > 0):\n                self._do_accumulate(box_xywh_gt, box_xywh_est, dp_gt)\n            self.nxt_bbox_index += 1\n\n    def _do_accumulate(self, box_xywh_gt: torch.Tensor, box_xywh_est: torch.Tensor, dp_gt: Any):\n        \"\"\"\n        Accumulate instances data for one image, given that the data is not empty\n\n        Args:\n            box_xywh_gt (tensor): GT bounding box\n            box_xywh_est (tensor): estimated bounding box\n            dp_gt: GT densepose data with the following attributes:\n             - x: normalized X coordinates\n             - y: normalized Y coordinates\n             - segm: tensor of size [S, S] with coarse segmentation\n             -\n        \"\"\"\n        self.x_gt.append(dp_gt.x)\n        self.y_gt.append(dp_gt.y)\n        if hasattr(dp_gt, \"segm\"):\n            self.s_gt.append(dp_gt.segm.unsqueeze(0))\n        self.vertex_ids_gt.append(dp_gt.vertex_ids)\n        self.vertex_mesh_ids_gt.append(torch.full_like(dp_gt.vertex_ids, dp_gt.mesh_id))\n        self.bbox_xywh_gt.append(box_xywh_gt.view(-1, 4))\n        self.bbox_xywh_est.append(box_xywh_est.view(-1, 4))\n        self.point_bbox_with_dp_indices.append(\n            torch.full_like(dp_gt.vertex_ids, self.nxt_bbox_with_dp_index)\n        )\n        self.point_bbox_indices.append(torch.full_like(dp_gt.vertex_ids, self.nxt_bbox_index))\n        self.bbox_indices.append(self.nxt_bbox_index)\n        self.nxt_bbox_with_dp_index += 1\n\n    def pack(self) -> Optional[PackedCseAnnotations]:\n        \"\"\"\n        Pack data into tensors\n        \"\"\"\n        if not len(self.x_gt):\n            # TODO:\n            # returning proper empty annotations would require\n            # creating empty tensors of appropriate shape and\n            # type on an appropriate device;\n            # we return None so far to indicate empty annotations\n            return None\n        return PackedCseAnnotations(\n            x_gt=torch.cat(self.x_gt, 0),\n            y_gt=torch.cat(self.y_gt, 0),\n            vertex_mesh_ids_gt=torch.cat(self.vertex_mesh_ids_gt, 0),\n            vertex_ids_gt=torch.cat(self.vertex_ids_gt, 0),\n            # ignore segmentation annotations, if not all the instances contain those\n            coarse_segm_gt=torch.cat(self.s_gt, 0)\n            if len(self.s_gt) == len(self.bbox_xywh_gt)\n            else None,\n            bbox_xywh_gt=torch.cat(self.bbox_xywh_gt, 0),\n            bbox_xywh_est=torch.cat(self.bbox_xywh_est, 0),\n            point_bbox_with_dp_indices=torch.cat(self.point_bbox_with_dp_indices, 0),\n            point_bbox_indices=torch.cat(self.point_bbox_indices, 0),\n            bbox_indices=torch.as_tensor(\n                self.bbox_indices, dtype=torch.long, device=self.x_gt[0].device\n            ),\n        )\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/losses/mask.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nfrom dataclasses import dataclass\nfrom typing import Any, Iterable, List, Optional\nimport torch\nfrom torch.nn import functional as F\n\nfrom detectron2.structures import Instances\n\n\n@dataclass\nclass DataForMaskLoss:\n    \"\"\"\n    Contains mask GT and estimated data for proposals from multiple images:\n    \"\"\"\n\n    # tensor of size (K, H, W) containing GT labels\n    masks_gt: Optional[torch.Tensor] = None\n    # tensor of size (K, C, H, W) containing estimated scores\n    masks_est: Optional[torch.Tensor] = None\n\n\ndef extract_data_for_mask_loss_from_matches(\n    proposals_targets: Iterable[Instances], estimated_segm: torch.Tensor\n) -> DataForMaskLoss:\n    \"\"\"\n    Extract data for mask loss from instances that contain matched GT and\n    estimated bounding boxes.\n    Args:\n        proposals_targets: Iterable[Instances]\n            matched GT and estimated results, each item in the iterable\n            corresponds to data in 1 image\n        estimated_segm: tensor(K, C, S, S) of float - raw unnormalized\n            segmentation scores, here S is the size to which GT masks are\n            to be resized\n    Return:\n        masks_est: tensor(K, C, S, S) of float - class scores\n        masks_gt: tensor(K, S, S) of int64 - labels\n    \"\"\"\n    data = DataForMaskLoss()\n    masks_gt = []\n    offset = 0\n    assert estimated_segm.shape[2] == estimated_segm.shape[3], (\n        f\"Expected estimated segmentation to have a square shape, \"\n        f\"but the actual shape is {estimated_segm.shape[2:]}\"\n    )\n    mask_size = estimated_segm.shape[2]\n    num_proposals = sum(inst.proposal_boxes.tensor.size(0) for inst in proposals_targets)\n    num_estimated = estimated_segm.shape[0]\n    assert (\n        num_proposals == num_estimated\n    ), \"The number of proposals {} must be equal to the number of estimates {}\".format(\n        num_proposals, num_estimated\n    )\n\n    for proposals_targets_per_image in proposals_targets:\n        n_i = proposals_targets_per_image.proposal_boxes.tensor.size(0)\n        if not n_i:\n            continue\n        gt_masks_per_image = proposals_targets_per_image.gt_masks.crop_and_resize(\n            proposals_targets_per_image.proposal_boxes.tensor, mask_size\n        ).to(device=estimated_segm.device)\n        masks_gt.append(gt_masks_per_image)\n        offset += n_i\n    if masks_gt:\n        data.masks_est = estimated_segm\n        data.masks_gt = torch.cat(masks_gt, dim=0)\n    return data\n\n\nclass MaskLoss:\n    \"\"\"\n    Mask loss as cross-entropy for raw unnormalized scores given ground truth labels.\n    Mask ground truth labels are defined for the whole image and not only the\n    bounding box of interest. They are stored as objects that are assumed to implement\n    the `crop_and_resize` interface (e.g. BitMasks, PolygonMasks).\n    \"\"\"\n\n    def __call__(\n        self, proposals_with_gt: List[Instances], densepose_predictor_outputs: Any\n    ) -> torch.Tensor:\n        \"\"\"\n        Computes segmentation loss as cross-entropy for raw unnormalized\n        scores given ground truth labels.\n\n        Args:\n            proposals_with_gt (list of Instances): detections with associated ground truth data\n            densepose_predictor_outputs: an object of a dataclass that contains predictor outputs\n                with estimated values; assumed to have the following attribute:\n                * coarse_segm (tensor of shape [N, D, S, S]): coarse segmentation estimates\n                    as raw unnormalized scores\n                where N is the number of detections, S is the estimate size ( = width = height)\n                and D is the number of coarse segmentation channels.\n        Return:\n            Cross entropy for raw unnormalized scores for coarse segmentation given\n            ground truth labels from masks\n        \"\"\"\n        if not len(proposals_with_gt):\n            return self.fake_value(densepose_predictor_outputs)\n        # densepose outputs are computed for all images and all bounding boxes;\n        # i.e. if a batch has 4 images with (3, 1, 2, 1) proposals respectively,\n        # the outputs will have size(0) == 3+1+2+1 == 7\n        with torch.no_grad():\n            mask_loss_data = extract_data_for_mask_loss_from_matches(\n                proposals_with_gt, densepose_predictor_outputs.coarse_segm\n            )\n        if (mask_loss_data.masks_gt is None) or (mask_loss_data.masks_est is None):\n            return self.fake_value(densepose_predictor_outputs)\n        return F.cross_entropy(mask_loss_data.masks_est, mask_loss_data.masks_gt.long())\n\n    def fake_value(self, densepose_predictor_outputs: Any) -> torch.Tensor:\n        \"\"\"\n        Fake segmentation loss used when no suitable ground truth data\n        was found in a batch. The loss has a value 0 and is primarily used to\n        construct the computation graph, so that `DistributedDataParallel`\n        has similar graphs on all GPUs and can perform reduction properly.\n\n        Args:\n            densepose_predictor_outputs: DensePose predictor outputs, an object\n                of a dataclass that is assumed to have `coarse_segm`\n                attribute\n        Return:\n            Zero value loss with proper computation graph\n        \"\"\"\n        return densepose_predictor_outputs.coarse_segm.sum() * 0\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/losses/mask_or_segm.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nfrom typing import Any, List\nimport torch\n\nfrom detectron2.config import CfgNode\nfrom detectron2.structures import Instances\n\nfrom .mask import MaskLoss\nfrom .segm import SegmentationLoss\n\n\nclass MaskOrSegmentationLoss:\n    \"\"\"\n    Mask or segmentation loss as cross-entropy for raw unnormalized scores\n    given ground truth labels. Ground truth labels are either defined by coarse\n    segmentation annotation, or by mask annotation, depending on the config\n    value MODEL.ROI_DENSEPOSE_HEAD.COARSE_SEGM_TRAINED_BY_MASKS\n    \"\"\"\n\n    def __init__(self, cfg: CfgNode):\n        \"\"\"\n        Initialize segmentation loss from configuration options\n\n        Args:\n            cfg (CfgNode): configuration options\n        \"\"\"\n        self.segm_trained_by_masks = cfg.MODEL.ROI_DENSEPOSE_HEAD.COARSE_SEGM_TRAINED_BY_MASKS\n        if self.segm_trained_by_masks:\n            self.mask_loss = MaskLoss()\n        self.segm_loss = SegmentationLoss(cfg)\n\n    def __call__(\n        self,\n        proposals_with_gt: List[Instances],\n        densepose_predictor_outputs: Any,\n        packed_annotations: Any,\n    ) -> torch.Tensor:\n        \"\"\"\n        Compute segmentation loss as cross-entropy between aligned unnormalized\n        score estimates and ground truth; with ground truth given\n        either by masks, or by coarse segmentation annotations.\n\n        Args:\n            proposals_with_gt (list of Instances): detections with associated ground truth data\n            densepose_predictor_outputs: an object of a dataclass that contains predictor outputs\n                with estimated values; assumed to have the following attributes:\n                * coarse_segm - coarse segmentation estimates, tensor of shape [N, D, S, S]\n            packed_annotations: packed annotations for efficient loss computation\n        Return:\n            tensor: loss value as cross-entropy for raw unnormalized scores\n                given ground truth labels\n        \"\"\"\n        if self.segm_trained_by_masks:\n            return self.mask_loss(proposals_with_gt, densepose_predictor_outputs)\n        return self.segm_loss(proposals_with_gt, densepose_predictor_outputs, packed_annotations)\n\n    def fake_value(self, densepose_predictor_outputs: Any) -> torch.Tensor:\n        \"\"\"\n        Fake segmentation loss used when no suitable ground truth data\n        was found in a batch. The loss has a value 0 and is primarily used to\n        construct the computation graph, so that `DistributedDataParallel`\n        has similar graphs on all GPUs and can perform reduction properly.\n\n        Args:\n            densepose_predictor_outputs: DensePose predictor outputs, an object\n                of a dataclass that is assumed to have `coarse_segm`\n                attribute\n        Return:\n            Zero value loss with proper computation graph\n        \"\"\"\n        return densepose_predictor_outputs.coarse_segm.sum() * 0\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/losses/registry.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom detectron2.utils.registry import Registry\n\nDENSEPOSE_LOSS_REGISTRY = Registry(\"DENSEPOSE_LOSS\")\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/losses/segm.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nfrom typing import Any, List\nimport torch\nfrom torch.nn import functional as F\n\nfrom detectron2.config import CfgNode\nfrom detectron2.structures import Instances\n\nfrom .utils import resample_data\n\n\nclass SegmentationLoss:\n    \"\"\"\n    Segmentation loss as cross-entropy for raw unnormalized scores given ground truth\n    labels. Segmentation ground truth labels are defined for the bounding box of\n    interest at some fixed resolution [S, S], where\n        S = MODEL.ROI_DENSEPOSE_HEAD.HEATMAP_SIZE.\n    \"\"\"\n\n    def __init__(self, cfg: CfgNode):\n        \"\"\"\n        Initialize segmentation loss from configuration options\n\n        Args:\n            cfg (CfgNode): configuration options\n        \"\"\"\n        self.heatmap_size = cfg.MODEL.ROI_DENSEPOSE_HEAD.HEATMAP_SIZE\n        self.n_segm_chan = cfg.MODEL.ROI_DENSEPOSE_HEAD.NUM_COARSE_SEGM_CHANNELS\n\n    def __call__(\n        self,\n        proposals_with_gt: List[Instances],\n        densepose_predictor_outputs: Any,\n        packed_annotations: Any,\n    ) -> torch.Tensor:\n        \"\"\"\n        Compute segmentation loss as cross-entropy on aligned segmentation\n        ground truth and estimated scores.\n\n        Args:\n            proposals_with_gt (list of Instances): detections with associated ground truth data\n            densepose_predictor_outputs: an object of a dataclass that contains predictor outputs\n                with estimated values; assumed to have the following attributes:\n                * coarse_segm - coarse segmentation estimates, tensor of shape [N, D, S, S]\n            packed_annotations: packed annotations for efficient loss computation;\n                the following attributes are used:\n                 - coarse_segm_gt\n                 - bbox_xywh_gt\n                 - bbox_xywh_est\n        \"\"\"\n        if packed_annotations.coarse_segm_gt is None:\n            return self.fake_value(densepose_predictor_outputs)\n        coarse_segm_est = densepose_predictor_outputs.coarse_segm[packed_annotations.bbox_indices]\n        with torch.no_grad():\n            coarse_segm_gt = resample_data(\n                packed_annotations.coarse_segm_gt.unsqueeze(1),\n                packed_annotations.bbox_xywh_gt,\n                packed_annotations.bbox_xywh_est,\n                self.heatmap_size,\n                self.heatmap_size,\n                mode=\"nearest\",\n                padding_mode=\"zeros\",\n            ).squeeze(1)\n        if self.n_segm_chan == 2:\n            coarse_segm_gt = coarse_segm_gt > 0\n        return F.cross_entropy(coarse_segm_est, coarse_segm_gt.long())\n\n    def fake_value(self, densepose_predictor_outputs: Any) -> torch.Tensor:\n        \"\"\"\n        Fake segmentation loss used when no suitable ground truth data\n        was found in a batch. The loss has a value 0 and is primarily used to\n        construct the computation graph, so that `DistributedDataParallel`\n        has similar graphs on all GPUs and can perform reduction properly.\n\n        Args:\n            densepose_predictor_outputs: DensePose predictor outputs, an object\n                of a dataclass that is assumed to have `coarse_segm`\n                attribute\n        Return:\n            Zero value loss with proper computation graph\n        \"\"\"\n        return densepose_predictor_outputs.coarse_segm.sum() * 0\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/losses/soft_embed.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nfrom typing import Any, Dict, List\nimport torch\nfrom torch import nn\nfrom torch.nn import functional as F\n\nfrom detectron2.config import CfgNode\nfrom detectron2.structures import Instances\n\nfrom densepose.data.meshes.catalog import MeshCatalog\nfrom densepose.modeling.cse.utils import normalize_embeddings, squared_euclidean_distance_matrix\nfrom densepose.structures.mesh import create_mesh\n\nfrom .embed_utils import PackedCseAnnotations\nfrom .utils import BilinearInterpolationHelper\n\n\nclass SoftEmbeddingLoss:\n    \"\"\"\n    Computes losses for estimated embeddings given annotated vertices.\n    Instances in a minibatch that correspond to the same mesh are grouped\n    together. For each group, loss is computed as cross-entropy for\n    unnormalized scores given ground truth mesh vertex ids.\n    Scores are based on:\n     1) squared distances between estimated vertex embeddings\n        and mesh vertex embeddings;\n     2) geodesic distances between vertices of a mesh\n    \"\"\"\n\n    def __init__(self, cfg: CfgNode):\n        \"\"\"\n        Initialize embedding loss from config\n        \"\"\"\n        self.embdist_gauss_sigma = cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBEDDING_DIST_GAUSS_SIGMA\n        self.geodist_gauss_sigma = cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.GEODESIC_DIST_GAUSS_SIGMA\n\n    def __call__(\n        self,\n        proposals_with_gt: List[Instances],\n        densepose_predictor_outputs: Any,\n        packed_annotations: PackedCseAnnotations,\n        interpolator: BilinearInterpolationHelper,\n        embedder: nn.Module,\n    ) -> Dict[int, torch.Tensor]:\n        \"\"\"\n        Produces losses for estimated embeddings given annotated vertices.\n        Embeddings for all the vertices of a mesh are computed by the embedder.\n        Embeddings for observed pixels are estimated by a predictor.\n        Losses are computed as cross-entropy for unnormalized scores given\n        ground truth vertex IDs.\n         1) squared distances between estimated vertex embeddings\n            and mesh vertex embeddings;\n         2) geodesic distances between vertices of a mesh\n\n        Args:\n            proposals_with_gt (list of Instances): detections with associated\n                ground truth data; each item corresponds to instances detected\n                on 1 image; the number of items corresponds to the number of\n                images in a batch\n            densepose_predictor_outputs: an object of a dataclass that contains predictor\n                outputs with estimated values; assumed to have the following attributes:\n                * embedding - embedding estimates, tensor of shape [N, D, S, S], where\n                  N = number of instances (= sum N_i, where N_i is the number of\n                      instances on image i)\n                  D = embedding space dimensionality (MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBED_SIZE)\n                  S = output size (width and height)\n            packed_annotations (PackedCseAnnotations): contains various data useful\n                for loss computation, each data is packed into a single tensor\n            interpolator (BilinearInterpolationHelper): bilinear interpolation helper\n            embedder (nn.Module): module that computes vertex embeddings for different meshes\n        Return:\n            dict(int -> tensor): losses for different mesh IDs\n        \"\"\"\n        losses = {}\n        for mesh_id_tensor in packed_annotations.vertex_mesh_ids_gt.unique():  # pyre-ignore[16]\n            mesh_id = mesh_id_tensor.item()\n            mesh_name = MeshCatalog.get_mesh_name(mesh_id)\n            # valid points are those that fall into estimated bbox\n            # and correspond to the current mesh\n            j_valid = interpolator.j_valid * (  # pyre-ignore[16]\n                packed_annotations.vertex_mesh_ids_gt == mesh_id\n            )\n            if not torch.any(j_valid):\n                continue\n            # extract estimated embeddings for valid points\n            # -> tensor [J, D]\n            vertex_embeddings_i = normalize_embeddings(\n                interpolator.extract_at_points(\n                    densepose_predictor_outputs.embedding,\n                    slice_fine_segm=slice(None),\n                    w_ylo_xlo=interpolator.w_ylo_xlo[:, None],  # pyre-ignore[16]\n                    w_ylo_xhi=interpolator.w_ylo_xhi[:, None],  # pyre-ignore[16]\n                    w_yhi_xlo=interpolator.w_yhi_xlo[:, None],  # pyre-ignore[16]\n                    w_yhi_xhi=interpolator.w_yhi_xhi[:, None],  # pyre-ignore[16]\n                )[j_valid, :]\n            )\n            # extract vertex ids for valid points\n            # -> tensor [J]\n            vertex_indices_i = packed_annotations.vertex_ids_gt[j_valid]\n            # embeddings for all mesh vertices\n            # -> tensor [K, D]\n            mesh_vertex_embeddings = embedder(mesh_name)\n            # softmax values of geodesic distances for GT mesh vertices\n            # -> tensor [J, K]\n            mesh = create_mesh(mesh_name, mesh_vertex_embeddings.device)\n            geodist_softmax_values = F.softmax(\n                mesh.geodists[vertex_indices_i] / (-self.geodist_gauss_sigma), dim=1\n            )\n            # logsoftmax values for valid points\n            # -> tensor [J, K]\n            embdist_logsoftmax_values = F.log_softmax(\n                squared_euclidean_distance_matrix(vertex_embeddings_i, mesh_vertex_embeddings)\n                / (-self.embdist_gauss_sigma),\n                dim=1,\n            )\n            losses[mesh_name] = (-geodist_softmax_values * embdist_logsoftmax_values).sum(1).mean()\n\n        # pyre-fixme[29]:\n        #  `Union[BoundMethod[typing.Callable(torch.Tensor.__iter__)[[Named(self,\n        #  torch.Tensor)], typing.Iterator[typing.Any]], torch.Tensor], nn.Module,\n        #  torch.Tensor]` is not a function.\n        for mesh_name in embedder.mesh_names:\n            if mesh_name not in losses:\n                losses[mesh_name] = self.fake_value(\n                    densepose_predictor_outputs, embedder, mesh_name\n                )\n        return losses\n\n    def fake_values(self, densepose_predictor_outputs: Any, embedder: nn.Module):\n        losses = {}\n        # pyre-fixme[29]:\n        #  `Union[BoundMethod[typing.Callable(torch.Tensor.__iter__)[[Named(self,\n        #  torch.Tensor)], typing.Iterator[typing.Any]], torch.Tensor], nn.Module,\n        #  torch.Tensor]` is not a function.\n        for mesh_name in embedder.mesh_names:\n            losses[mesh_name] = self.fake_value(densepose_predictor_outputs, embedder, mesh_name)\n        return losses\n\n    def fake_value(self, densepose_predictor_outputs: Any, embedder: nn.Module, mesh_name: str):\n        return densepose_predictor_outputs.embedding.sum() * 0 + embedder(mesh_name).sum() * 0\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/losses/utils.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom abc import ABC, abstractmethod\nfrom dataclasses import dataclass\nfrom typing import Any, Dict, List, Optional, Tuple\nimport torch\nfrom torch.nn import functional as F\n\nfrom detectron2.structures import BoxMode, Instances\n\nfrom densepose import DensePoseDataRelative\n\nLossDict = Dict[str, torch.Tensor]\n\n\ndef _linear_interpolation_utilities(v_norm, v0_src, size_src, v0_dst, size_dst, size_z):\n    \"\"\"\n    Computes utility values for linear interpolation at points v.\n    The points are given as normalized offsets in the source interval\n    (v0_src, v0_src + size_src), more precisely:\n        v = v0_src + v_norm * size_src / 256.0\n    The computed utilities include lower points v_lo, upper points v_hi,\n    interpolation weights v_w and flags j_valid indicating whether the\n    points falls into the destination interval (v0_dst, v0_dst + size_dst).\n\n    Args:\n        v_norm (:obj: `torch.Tensor`): tensor of size N containing\n            normalized point offsets\n        v0_src (:obj: `torch.Tensor`): tensor of size N containing\n            left bounds of source intervals for normalized points\n        size_src (:obj: `torch.Tensor`): tensor of size N containing\n            source interval sizes for normalized points\n        v0_dst (:obj: `torch.Tensor`): tensor of size N containing\n            left bounds of destination intervals\n        size_dst (:obj: `torch.Tensor`): tensor of size N containing\n            destination interval sizes\n        size_z (int): interval size for data to be interpolated\n\n    Returns:\n        v_lo (:obj: `torch.Tensor`): int tensor of size N containing\n            indices of lower values used for interpolation, all values are\n            integers from [0, size_z - 1]\n        v_hi (:obj: `torch.Tensor`): int tensor of size N containing\n            indices of upper values used for interpolation, all values are\n            integers from [0, size_z - 1]\n        v_w (:obj: `torch.Tensor`): float tensor of size N containing\n            interpolation weights\n        j_valid (:obj: `torch.Tensor`): uint8 tensor of size N containing\n            0 for points outside the estimation interval\n            (v0_est, v0_est + size_est) and 1 otherwise\n    \"\"\"\n    v = v0_src + v_norm * size_src / 256.0\n    j_valid = (v - v0_dst >= 0) * (v - v0_dst < size_dst)\n    v_grid = (v - v0_dst) * size_z / size_dst\n    v_lo = v_grid.floor().long().clamp(min=0, max=size_z - 1)\n    v_hi = (v_lo + 1).clamp(max=size_z - 1)\n    v_grid = torch.min(v_hi.float(), v_grid)\n    v_w = v_grid - v_lo.float()\n    return v_lo, v_hi, v_w, j_valid\n\n\nclass BilinearInterpolationHelper:\n    \"\"\"\n    Args:\n        packed_annotations: object that contains packed annotations\n        j_valid (:obj: `torch.Tensor`): uint8 tensor of size M containing\n            0 for points to be discarded and 1 for points to be selected\n        y_lo (:obj: `torch.Tensor`): int tensor of indices of upper values\n            in z_est for each point\n        y_hi (:obj: `torch.Tensor`): int tensor of indices of lower values\n            in z_est for each point\n        x_lo (:obj: `torch.Tensor`): int tensor of indices of left values\n            in z_est for each point\n        x_hi (:obj: `torch.Tensor`): int tensor of indices of right values\n            in z_est for each point\n        w_ylo_xlo (:obj: `torch.Tensor`): float tensor of size M;\n            contains upper-left value weight for each point\n        w_ylo_xhi (:obj: `torch.Tensor`): float tensor of size M;\n            contains upper-right value weight for each point\n        w_yhi_xlo (:obj: `torch.Tensor`): float tensor of size M;\n            contains lower-left value weight for each point\n        w_yhi_xhi (:obj: `torch.Tensor`): float tensor of size M;\n            contains lower-right value weight for each point\n    \"\"\"\n\n    def __init__(\n        self,\n        packed_annotations: Any,\n        j_valid: torch.Tensor,\n        y_lo: torch.Tensor,\n        y_hi: torch.Tensor,\n        x_lo: torch.Tensor,\n        x_hi: torch.Tensor,\n        w_ylo_xlo: torch.Tensor,\n        w_ylo_xhi: torch.Tensor,\n        w_yhi_xlo: torch.Tensor,\n        w_yhi_xhi: torch.Tensor,\n    ):\n        for k, v in locals().items():\n            if k != \"self\":\n                setattr(self, k, v)\n\n    @staticmethod\n    def from_matches(\n        packed_annotations: Any, densepose_outputs_size_hw: Tuple[int, int]\n    ) -> \"BilinearInterpolationHelper\":\n        \"\"\"\n        Args:\n            packed_annotations: annotations packed into tensors, the following\n                attributes are required:\n                 - bbox_xywh_gt\n                 - bbox_xywh_est\n                 - x_gt\n                 - y_gt\n                 - point_bbox_with_dp_indices\n                 - point_bbox_indices\n            densepose_outputs_size_hw (tuple [int, int]): resolution of\n                DensePose predictor outputs (H, W)\n        Return:\n            An instance of `BilinearInterpolationHelper` used to perform\n            interpolation for the given annotation points and output resolution\n        \"\"\"\n\n        zh, zw = densepose_outputs_size_hw\n        x0_gt, y0_gt, w_gt, h_gt = packed_annotations.bbox_xywh_gt[\n            packed_annotations.point_bbox_with_dp_indices\n        ].unbind(dim=1)\n        x0_est, y0_est, w_est, h_est = packed_annotations.bbox_xywh_est[\n            packed_annotations.point_bbox_with_dp_indices\n        ].unbind(dim=1)\n        x_lo, x_hi, x_w, jx_valid = _linear_interpolation_utilities(\n            packed_annotations.x_gt, x0_gt, w_gt, x0_est, w_est, zw\n        )\n        y_lo, y_hi, y_w, jy_valid = _linear_interpolation_utilities(\n            packed_annotations.y_gt, y0_gt, h_gt, y0_est, h_est, zh\n        )\n        j_valid = jx_valid * jy_valid\n\n        w_ylo_xlo = (1.0 - x_w) * (1.0 - y_w)\n        w_ylo_xhi = x_w * (1.0 - y_w)\n        w_yhi_xlo = (1.0 - x_w) * y_w\n        w_yhi_xhi = x_w * y_w\n\n        return BilinearInterpolationHelper(\n            packed_annotations,\n            j_valid,\n            y_lo,\n            y_hi,\n            x_lo,\n            x_hi,\n            w_ylo_xlo,  # pyre-ignore[6]\n            w_ylo_xhi,\n            # pyre-fixme[6]: Expected `Tensor` for 9th param but got `float`.\n            w_yhi_xlo,\n            w_yhi_xhi,\n        )\n\n    def extract_at_points(\n        self,\n        z_est,\n        slice_fine_segm=None,\n        w_ylo_xlo=None,\n        w_ylo_xhi=None,\n        w_yhi_xlo=None,\n        w_yhi_xhi=None,\n    ):\n        \"\"\"\n        Extract ground truth values z_gt for valid point indices and estimated\n        values z_est using bilinear interpolation over top-left (y_lo, x_lo),\n        top-right (y_lo, x_hi), bottom-left (y_hi, x_lo) and bottom-right\n        (y_hi, x_hi) values in z_est with corresponding weights:\n        w_ylo_xlo, w_ylo_xhi, w_yhi_xlo and w_yhi_xhi.\n        Use slice_fine_segm to slice dim=1 in z_est\n        \"\"\"\n        slice_fine_segm = (\n            self.packed_annotations.fine_segm_labels_gt\n            if slice_fine_segm is None\n            else slice_fine_segm\n        )\n        w_ylo_xlo = self.w_ylo_xlo if w_ylo_xlo is None else w_ylo_xlo\n        w_ylo_xhi = self.w_ylo_xhi if w_ylo_xhi is None else w_ylo_xhi\n        w_yhi_xlo = self.w_yhi_xlo if w_yhi_xlo is None else w_yhi_xlo\n        w_yhi_xhi = self.w_yhi_xhi if w_yhi_xhi is None else w_yhi_xhi\n\n        index_bbox = self.packed_annotations.point_bbox_indices\n        z_est_sampled = (\n            z_est[index_bbox, slice_fine_segm, self.y_lo, self.x_lo] * w_ylo_xlo\n            + z_est[index_bbox, slice_fine_segm, self.y_lo, self.x_hi] * w_ylo_xhi\n            + z_est[index_bbox, slice_fine_segm, self.y_hi, self.x_lo] * w_yhi_xlo\n            + z_est[index_bbox, slice_fine_segm, self.y_hi, self.x_hi] * w_yhi_xhi\n        )\n        return z_est_sampled\n\n\ndef resample_data(\n    z, bbox_xywh_src, bbox_xywh_dst, wout, hout, mode=\"nearest\", padding_mode=\"zeros\"\n):\n    \"\"\"\n    Args:\n        z (:obj: `torch.Tensor`): tensor of size (N,C,H,W) with data to be\n            resampled\n        bbox_xywh_src (:obj: `torch.Tensor`): tensor of size (N,4) containing\n            source bounding boxes in format XYWH\n        bbox_xywh_dst (:obj: `torch.Tensor`): tensor of size (N,4) containing\n            destination bounding boxes in format XYWH\n    Return:\n        zresampled (:obj: `torch.Tensor`): tensor of size (N, C, Hout, Wout)\n            with resampled values of z, where D is the discretization size\n    \"\"\"\n    n = bbox_xywh_src.size(0)\n    assert n == bbox_xywh_dst.size(0), (\n        \"The number of \"\n        \"source ROIs for resampling ({}) should be equal to the number \"\n        \"of destination ROIs ({})\".format(bbox_xywh_src.size(0), bbox_xywh_dst.size(0))\n    )\n    x0src, y0src, wsrc, hsrc = bbox_xywh_src.unbind(dim=1)\n    x0dst, y0dst, wdst, hdst = bbox_xywh_dst.unbind(dim=1)\n    x0dst_norm = 2 * (x0dst - x0src) / wsrc - 1\n    y0dst_norm = 2 * (y0dst - y0src) / hsrc - 1\n    x1dst_norm = 2 * (x0dst + wdst - x0src) / wsrc - 1\n    y1dst_norm = 2 * (y0dst + hdst - y0src) / hsrc - 1\n    grid_w = torch.arange(wout, device=z.device, dtype=torch.float) / wout\n    grid_h = torch.arange(hout, device=z.device, dtype=torch.float) / hout\n    grid_w_expanded = grid_w[None, None, :].expand(n, hout, wout)\n    grid_h_expanded = grid_h[None, :, None].expand(n, hout, wout)\n    dx_expanded = (x1dst_norm - x0dst_norm)[:, None, None].expand(n, hout, wout)\n    dy_expanded = (y1dst_norm - y0dst_norm)[:, None, None].expand(n, hout, wout)\n    x0_expanded = x0dst_norm[:, None, None].expand(n, hout, wout)\n    y0_expanded = y0dst_norm[:, None, None].expand(n, hout, wout)\n    grid_x = grid_w_expanded * dx_expanded + x0_expanded\n    grid_y = grid_h_expanded * dy_expanded + y0_expanded\n    grid = torch.stack((grid_x, grid_y), dim=3)\n    # resample Z from (N, C, H, W) into (N, C, Hout, Wout)\n    zresampled = F.grid_sample(z, grid, mode=mode, padding_mode=padding_mode, align_corners=True)\n    return zresampled\n\n\nclass AnnotationsAccumulator(ABC):\n    \"\"\"\n    Abstract class for an accumulator for annotations that can produce\n    dense annotations packed into tensors.\n    \"\"\"\n\n    @abstractmethod\n    def accumulate(self, instances_one_image: Instances):\n        \"\"\"\n        Accumulate instances data for one image\n\n        Args:\n            instances_one_image (Instances): instances data to accumulate\n        \"\"\"\n        pass\n\n    @abstractmethod\n    def pack(self) -> Any:\n        \"\"\"\n        Pack data into tensors\n        \"\"\"\n        pass\n\n\n@dataclass\nclass PackedChartBasedAnnotations:\n    \"\"\"\n    Packed annotations for chart-based model training. The following attributes\n    are defined:\n     - fine_segm_labels_gt (tensor [K] of `int64`): GT fine segmentation point labels\n     - x_gt (tensor [K] of `float32`): GT normalized X point coordinates\n     - y_gt (tensor [K] of `float32`): GT normalized Y point coordinates\n     - u_gt (tensor [K] of `float32`): GT point U values\n     - v_gt (tensor [K] of `float32`): GT point V values\n     - coarse_segm_gt (tensor [N, S, S] of `float32`): GT segmentation for bounding boxes\n     - bbox_xywh_gt (tensor [N, 4] of `float32`): selected GT bounding boxes in\n         XYWH format\n     - bbox_xywh_est (tensor [N, 4] of `float32`): selected matching estimated\n         bounding boxes in XYWH format\n     - point_bbox_with_dp_indices (tensor [K] of `int64`): indices of bounding boxes\n         with DensePose annotations that correspond to the point data\n     - point_bbox_indices (tensor [K] of `int64`): indices of bounding boxes\n         (not necessarily the selected ones with DensePose data) that correspond\n         to the point data\n     - bbox_indices (tensor [N] of `int64`): global indices of selected bounding\n         boxes with DensePose annotations; these indices could be used to access\n         features that are computed for all bounding boxes, not only the ones with\n         DensePose annotations.\n    Here K is the total number of points and N is the total number of instances\n    with DensePose annotations.\n    \"\"\"\n\n    fine_segm_labels_gt: torch.Tensor\n    x_gt: torch.Tensor\n    y_gt: torch.Tensor\n    u_gt: torch.Tensor\n    v_gt: torch.Tensor\n    coarse_segm_gt: Optional[torch.Tensor]\n    bbox_xywh_gt: torch.Tensor\n    bbox_xywh_est: torch.Tensor\n    point_bbox_with_dp_indices: torch.Tensor\n    point_bbox_indices: torch.Tensor\n    bbox_indices: torch.Tensor\n\n\nclass ChartBasedAnnotationsAccumulator(AnnotationsAccumulator):\n    \"\"\"\n    Accumulates annotations by batches that correspond to objects detected on\n    individual images. Can pack them together into single tensors.\n    \"\"\"\n\n    def __init__(self):\n        self.i_gt = []\n        self.x_gt = []\n        self.y_gt = []\n        self.u_gt = []\n        self.v_gt = []\n        self.s_gt = []\n        self.bbox_xywh_gt = []\n        self.bbox_xywh_est = []\n        self.point_bbox_with_dp_indices = []\n        self.point_bbox_indices = []\n        self.bbox_indices = []\n        self.nxt_bbox_with_dp_index = 0\n        self.nxt_bbox_index = 0\n\n    def accumulate(self, instances_one_image: Instances):\n        \"\"\"\n        Accumulate instances data for one image\n\n        Args:\n            instances_one_image (Instances): instances data to accumulate\n        \"\"\"\n        boxes_xywh_est = BoxMode.convert(\n            instances_one_image.proposal_boxes.tensor.clone(), BoxMode.XYXY_ABS, BoxMode.XYWH_ABS\n        )\n        boxes_xywh_gt = BoxMode.convert(\n            instances_one_image.gt_boxes.tensor.clone(), BoxMode.XYXY_ABS, BoxMode.XYWH_ABS\n        )\n        n_matches = len(boxes_xywh_gt)\n        assert n_matches == len(\n            boxes_xywh_est\n        ), f\"Got {len(boxes_xywh_est)} proposal boxes and {len(boxes_xywh_gt)} GT boxes\"\n        if not n_matches:\n            # no detection - GT matches\n            return\n        if (\n            not hasattr(instances_one_image, \"gt_densepose\")\n            or instances_one_image.gt_densepose is None\n        ):\n            # no densepose GT for the detections, just increase the bbox index\n            self.nxt_bbox_index += n_matches\n            return\n        for box_xywh_est, box_xywh_gt, dp_gt in zip(\n            boxes_xywh_est, boxes_xywh_gt, instances_one_image.gt_densepose\n        ):\n            if (dp_gt is not None) and (len(dp_gt.x) > 0):\n                self._do_accumulate(box_xywh_gt, box_xywh_est, dp_gt)\n            self.nxt_bbox_index += 1\n\n    def _do_accumulate(\n        self, box_xywh_gt: torch.Tensor, box_xywh_est: torch.Tensor, dp_gt: DensePoseDataRelative\n    ):\n        \"\"\"\n        Accumulate instances data for one image, given that the data is not empty\n\n        Args:\n            box_xywh_gt (tensor): GT bounding box\n            box_xywh_est (tensor): estimated bounding box\n            dp_gt (DensePoseDataRelative): GT densepose data\n        \"\"\"\n        self.i_gt.append(dp_gt.i)\n        self.x_gt.append(dp_gt.x)\n        self.y_gt.append(dp_gt.y)\n        self.u_gt.append(dp_gt.u)\n        self.v_gt.append(dp_gt.v)\n        if hasattr(dp_gt, \"segm\"):\n            self.s_gt.append(dp_gt.segm.unsqueeze(0))\n        self.bbox_xywh_gt.append(box_xywh_gt.view(-1, 4))\n        self.bbox_xywh_est.append(box_xywh_est.view(-1, 4))\n        self.point_bbox_with_dp_indices.append(\n            torch.full_like(dp_gt.i, self.nxt_bbox_with_dp_index)\n        )\n        self.point_bbox_indices.append(torch.full_like(dp_gt.i, self.nxt_bbox_index))\n        self.bbox_indices.append(self.nxt_bbox_index)\n        self.nxt_bbox_with_dp_index += 1\n\n    def pack(self) -> Optional[PackedChartBasedAnnotations]:\n        \"\"\"\n        Pack data into tensors\n        \"\"\"\n        if not len(self.i_gt):\n            # TODO:\n            # returning proper empty annotations would require\n            # creating empty tensors of appropriate shape and\n            # type on an appropriate device;\n            # we return None so far to indicate empty annotations\n            return None\n        return PackedChartBasedAnnotations(\n            fine_segm_labels_gt=torch.cat(self.i_gt, 0).long(),\n            x_gt=torch.cat(self.x_gt, 0),\n            y_gt=torch.cat(self.y_gt, 0),\n            u_gt=torch.cat(self.u_gt, 0),\n            v_gt=torch.cat(self.v_gt, 0),\n            # ignore segmentation annotations, if not all the instances contain those\n            coarse_segm_gt=torch.cat(self.s_gt, 0)\n            if len(self.s_gt) == len(self.bbox_xywh_gt)\n            else None,\n            bbox_xywh_gt=torch.cat(self.bbox_xywh_gt, 0),\n            bbox_xywh_est=torch.cat(self.bbox_xywh_est, 0),\n            point_bbox_with_dp_indices=torch.cat(self.point_bbox_with_dp_indices, 0).long(),\n            point_bbox_indices=torch.cat(self.point_bbox_indices, 0).long(),\n            bbox_indices=torch.as_tensor(\n                self.bbox_indices, dtype=torch.long, device=self.x_gt[0].device\n            ).long(),\n        )\n\n\ndef extract_packed_annotations_from_matches(\n    proposals_with_targets: List[Instances], accumulator: AnnotationsAccumulator\n) -> Any:\n    for proposals_targets_per_image in proposals_with_targets:\n        accumulator.accumulate(proposals_targets_per_image)\n    return accumulator.pack()\n\n\ndef sample_random_indices(\n    n_indices: int, n_samples: int, device: Optional[torch.device] = None\n) -> Optional[torch.Tensor]:\n    \"\"\"\n    Samples `n_samples` random indices from range `[0..n_indices - 1]`.\n    If `n_indices` is smaller than `n_samples`, returns `None` meaning that all indices\n    are selected.\n    Args:\n        n_indices (int): total number of indices\n        n_samples (int): number of indices to sample\n        device (torch.device): the desired device of returned tensor\n    Return:\n        Tensor of selected vertex indices, or `None`, if all vertices are selected\n    \"\"\"\n    if (n_samples <= 0) or (n_indices <= n_samples):\n        return None\n    indices = torch.randperm(n_indices, device=device)[:n_samples]\n    return indices\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/predictors/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom .chart import DensePoseChartPredictor\nfrom .chart_confidence import DensePoseChartConfidencePredictorMixin\nfrom .chart_with_confidence import DensePoseChartWithConfidencePredictor\nfrom .cse import DensePoseEmbeddingPredictor\nfrom .cse_confidence import DensePoseEmbeddingConfidencePredictorMixin\nfrom .cse_with_confidence import DensePoseEmbeddingWithConfidencePredictor\nfrom .registry import DENSEPOSE_PREDICTOR_REGISTRY\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/predictors/chart.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport torch\nfrom torch import nn\n\nfrom detectron2.config import CfgNode\nfrom detectron2.layers import ConvTranspose2d, interpolate\n\nfrom ...structures import DensePoseChartPredictorOutput\nfrom ..utils import initialize_module_params\nfrom .registry import DENSEPOSE_PREDICTOR_REGISTRY\n\n\n@DENSEPOSE_PREDICTOR_REGISTRY.register()\nclass DensePoseChartPredictor(nn.Module):\n    \"\"\"\n    Predictor (last layers of a DensePose model) that takes DensePose head outputs as an input\n    and produces 4 tensors which represent DensePose results for predefined body parts\n    (patches / charts):\n     * coarse segmentation, a tensor of shape [N, K, Hout, Wout]\n     * fine segmentation, a tensor of shape [N, C, Hout, Wout]\n     * U coordinates, a tensor of shape [N, C, Hout, Wout]\n     * V coordinates, a tensor of shape [N, C, Hout, Wout]\n    where\n     - N is the number of instances\n     - K is the number of coarse segmentation channels (\n         2 = foreground / background,\n         15 = one of 14 body parts / background)\n     - C is the number of fine segmentation channels (\n         24 fine body parts / background)\n     - Hout and Wout are height and width of predictions\n    \"\"\"\n\n    def __init__(self, cfg: CfgNode, input_channels: int):\n        \"\"\"\n        Initialize predictor using configuration options\n\n        Args:\n            cfg (CfgNode): configuration options\n            input_channels (int): input tensor size along the channel dimension\n        \"\"\"\n        super().__init__()\n        dim_in = input_channels\n        n_segm_chan = cfg.MODEL.ROI_DENSEPOSE_HEAD.NUM_COARSE_SEGM_CHANNELS\n        dim_out_patches = cfg.MODEL.ROI_DENSEPOSE_HEAD.NUM_PATCHES + 1\n        kernel_size = cfg.MODEL.ROI_DENSEPOSE_HEAD.DECONV_KERNEL\n        # coarse segmentation\n        self.ann_index_lowres = ConvTranspose2d(\n            dim_in, n_segm_chan, kernel_size, stride=2, padding=int(kernel_size / 2 - 1)\n        )\n        # fine segmentation\n        self.index_uv_lowres = ConvTranspose2d(\n            dim_in, dim_out_patches, kernel_size, stride=2, padding=int(kernel_size / 2 - 1)\n        )\n        # U\n        self.u_lowres = ConvTranspose2d(\n            dim_in, dim_out_patches, kernel_size, stride=2, padding=int(kernel_size / 2 - 1)\n        )\n        # V\n        self.v_lowres = ConvTranspose2d(\n            dim_in, dim_out_patches, kernel_size, stride=2, padding=int(kernel_size / 2 - 1)\n        )\n        self.scale_factor = cfg.MODEL.ROI_DENSEPOSE_HEAD.UP_SCALE\n        initialize_module_params(self)\n\n    def interp2d(self, tensor_nchw: torch.Tensor):\n        \"\"\"\n        Bilinear interpolation method to be used for upscaling\n\n        Args:\n            tensor_nchw (tensor): tensor of shape (N, C, H, W)\n        Return:\n            tensor of shape (N, C, Hout, Wout), where Hout and Wout are computed\n                by applying the scale factor to H and W\n        \"\"\"\n        return interpolate(\n            tensor_nchw, scale_factor=self.scale_factor, mode=\"bilinear\", align_corners=False\n        )\n\n    def forward(self, head_outputs: torch.Tensor):\n        \"\"\"\n        Perform forward step on DensePose head outputs\n\n        Args:\n            head_outputs (tensor): DensePose head outputs, tensor of shape [N, D, H, W]\n        Return:\n           An instance of DensePoseChartPredictorOutput\n        \"\"\"\n        return DensePoseChartPredictorOutput(\n            coarse_segm=self.interp2d(self.ann_index_lowres(head_outputs)),\n            fine_segm=self.interp2d(self.index_uv_lowres(head_outputs)),\n            u=self.interp2d(self.u_lowres(head_outputs)),\n            v=self.interp2d(self.v_lowres(head_outputs)),\n        )\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/predictors/chart_confidence.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom typing import Any\nimport torch\nfrom torch.nn import functional as F\n\nfrom detectron2.config import CfgNode\nfrom detectron2.layers import ConvTranspose2d\n\nfrom ...structures import decorate_predictor_output_class_with_confidences\nfrom ..confidence import DensePoseConfidenceModelConfig, DensePoseUVConfidenceType\nfrom ..utils import initialize_module_params\n\n\nclass DensePoseChartConfidencePredictorMixin:\n    \"\"\"\n    Predictor contains the last layers of a DensePose model that take DensePose head\n    outputs as an input and produce model outputs. Confidence predictor mixin is used\n    to generate confidences for segmentation and UV tensors estimated by some\n    base predictor. Several assumptions need to hold for the base predictor:\n    1) the `forward` method must return SIUV tuple as the first result (\n        S = coarse segmentation, I = fine segmentation, U and V are intrinsic\n        chart coordinates)\n    2) `interp2d` method must be defined to perform bilinear interpolation;\n        the same method is typically used for SIUV and confidences\n    Confidence predictor mixin provides confidence estimates, as described in:\n        N. Neverova et al., Correlated Uncertainty for Learning Dense Correspondences\n            from Noisy Labels, NeurIPS 2019\n        A. Sanakoyeu et al., Transferring Dense Pose to Proximal Animal Classes, CVPR 2020\n    \"\"\"\n\n    def __init__(self, cfg: CfgNode, input_channels: int):\n        \"\"\"\n        Initialize confidence predictor using configuration options.\n\n        Args:\n            cfg (CfgNode): configuration options\n            input_channels (int): number of input channels\n        \"\"\"\n        # we rely on base predictor to call nn.Module.__init__\n        super().__init__(cfg, input_channels)  # pyre-ignore[19]\n        self.confidence_model_cfg = DensePoseConfidenceModelConfig.from_cfg(cfg)\n        self._initialize_confidence_estimation_layers(cfg, input_channels)\n        self._registry = {}\n        initialize_module_params(self)  # pyre-ignore[6]\n\n    def _initialize_confidence_estimation_layers(self, cfg: CfgNode, dim_in: int):\n        \"\"\"\n        Initialize confidence estimation layers based on configuration options\n\n        Args:\n            cfg (CfgNode): configuration options\n            dim_in (int): number of input channels\n        \"\"\"\n        dim_out_patches = cfg.MODEL.ROI_DENSEPOSE_HEAD.NUM_PATCHES + 1\n        kernel_size = cfg.MODEL.ROI_DENSEPOSE_HEAD.DECONV_KERNEL\n        if self.confidence_model_cfg.uv_confidence.enabled:\n            if self.confidence_model_cfg.uv_confidence.type == DensePoseUVConfidenceType.IID_ISO:\n                self.sigma_2_lowres = ConvTranspose2d(  # pyre-ignore[16]\n                    dim_in, dim_out_patches, kernel_size, stride=2, padding=int(kernel_size / 2 - 1)\n                )\n            elif (\n                self.confidence_model_cfg.uv_confidence.type\n                == DensePoseUVConfidenceType.INDEP_ANISO\n            ):\n                self.sigma_2_lowres = ConvTranspose2d(\n                    dim_in, dim_out_patches, kernel_size, stride=2, padding=int(kernel_size / 2 - 1)\n                )\n                self.kappa_u_lowres = ConvTranspose2d(  # pyre-ignore[16]\n                    dim_in, dim_out_patches, kernel_size, stride=2, padding=int(kernel_size / 2 - 1)\n                )\n                self.kappa_v_lowres = ConvTranspose2d(  # pyre-ignore[16]\n                    dim_in, dim_out_patches, kernel_size, stride=2, padding=int(kernel_size / 2 - 1)\n                )\n            else:\n                raise ValueError(\n                    f\"Unknown confidence model type: \"\n                    f\"{self.confidence_model_cfg.confidence_model_type}\"\n                )\n        if self.confidence_model_cfg.segm_confidence.enabled:\n            self.fine_segm_confidence_lowres = ConvTranspose2d(  # pyre-ignore[16]\n                dim_in, 1, kernel_size, stride=2, padding=int(kernel_size / 2 - 1)\n            )\n            self.coarse_segm_confidence_lowres = ConvTranspose2d(  # pyre-ignore[16]\n                dim_in, 1, kernel_size, stride=2, padding=int(kernel_size / 2 - 1)\n            )\n\n    def forward(self, head_outputs: torch.Tensor):\n        \"\"\"\n        Perform forward operation on head outputs used as inputs for the predictor.\n        Calls forward method from the base predictor and uses its outputs to compute\n        confidences.\n\n        Args:\n            head_outputs (Tensor): head outputs used as predictor inputs\n        Return:\n            An instance of outputs with confidences,\n            see `decorate_predictor_output_class_with_confidences`\n        \"\"\"\n        # assuming base class returns SIUV estimates in its first result\n        base_predictor_outputs = super().forward(head_outputs)  # pyre-ignore[16]\n\n        # create output instance by extending base predictor outputs:\n        output = self._create_output_instance(base_predictor_outputs)\n\n        if self.confidence_model_cfg.uv_confidence.enabled:\n            if self.confidence_model_cfg.uv_confidence.type == DensePoseUVConfidenceType.IID_ISO:\n                # assuming base class defines interp2d method for bilinear interpolation\n                output.sigma_2 = self.interp2d(self.sigma_2_lowres(head_outputs))  # pyre-ignore[16]\n            elif (\n                self.confidence_model_cfg.uv_confidence.type\n                == DensePoseUVConfidenceType.INDEP_ANISO\n            ):\n                # assuming base class defines interp2d method for bilinear interpolation\n                output.sigma_2 = self.interp2d(self.sigma_2_lowres(head_outputs))\n                output.kappa_u = self.interp2d(self.kappa_u_lowres(head_outputs))  # pyre-ignore[16]\n                output.kappa_v = self.interp2d(self.kappa_v_lowres(head_outputs))  # pyre-ignore[16]\n            else:\n                raise ValueError(\n                    f\"Unknown confidence model type: \"\n                    f\"{self.confidence_model_cfg.confidence_model_type}\"\n                )\n        if self.confidence_model_cfg.segm_confidence.enabled:\n            # base predictor outputs are assumed to have `fine_segm` and `coarse_segm` attributes\n            # base predictor is assumed to define `interp2d` method for bilinear interpolation\n            output.fine_segm_confidence = (\n                F.softplus(\n                    self.interp2d(self.fine_segm_confidence_lowres(head_outputs))  # pyre-ignore[16]\n                )\n                + self.confidence_model_cfg.segm_confidence.epsilon\n            )\n            output.fine_segm = base_predictor_outputs.fine_segm * torch.repeat_interleave(\n                output.fine_segm_confidence, base_predictor_outputs.fine_segm.shape[1], dim=1\n            )\n            output.coarse_segm_confidence = (\n                F.softplus(\n                    self.interp2d(\n                        self.coarse_segm_confidence_lowres(head_outputs)  # pyre-ignore[16]\n                    )\n                )\n                + self.confidence_model_cfg.segm_confidence.epsilon\n            )\n            output.coarse_segm = base_predictor_outputs.coarse_segm * torch.repeat_interleave(\n                output.coarse_segm_confidence, base_predictor_outputs.coarse_segm.shape[1], dim=1\n            )\n\n        return output\n\n    def _create_output_instance(self, base_predictor_outputs: Any):\n        \"\"\"\n        Create an instance of predictor outputs by copying the outputs from the\n        base predictor and initializing confidence\n\n        Args:\n            base_predictor_outputs: an instance of base predictor outputs\n                (the outputs type is assumed to be a dataclass)\n        Return:\n           An instance of outputs with confidences\n        \"\"\"\n        PredictorOutput = decorate_predictor_output_class_with_confidences(\n            type(base_predictor_outputs)  # pyre-ignore[6]\n        )\n        # base_predictor_outputs is assumed to be a dataclass\n        # reassign all the fields from base_predictor_outputs (no deep copy!), add new fields\n        output = PredictorOutput(\n            **base_predictor_outputs.__dict__,\n            coarse_segm_confidence=None,\n            fine_segm_confidence=None,\n            sigma_1=None,\n            sigma_2=None,\n            kappa_u=None,\n            kappa_v=None,\n        )\n        return output\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/predictors/chart_with_confidence.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom . import DensePoseChartConfidencePredictorMixin, DensePoseChartPredictor\nfrom .registry import DENSEPOSE_PREDICTOR_REGISTRY\n\n\n@DENSEPOSE_PREDICTOR_REGISTRY.register()\nclass DensePoseChartWithConfidencePredictor(\n    DensePoseChartConfidencePredictorMixin, DensePoseChartPredictor\n):\n    \"\"\"\n    Predictor that combines chart and chart confidence estimation\n    \"\"\"\n\n    pass\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/predictors/cse.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nimport torch\nfrom torch import nn\n\nfrom detectron2.config import CfgNode\nfrom detectron2.layers import ConvTranspose2d, interpolate\n\nfrom ...structures import DensePoseEmbeddingPredictorOutput\nfrom ..utils import initialize_module_params\nfrom .registry import DENSEPOSE_PREDICTOR_REGISTRY\n\n\n@DENSEPOSE_PREDICTOR_REGISTRY.register()\nclass DensePoseEmbeddingPredictor(nn.Module):\n    \"\"\"\n    Last layers of a DensePose model that take DensePose head outputs as an input\n    and produce model outputs for continuous surface embeddings (CSE).\n    \"\"\"\n\n    def __init__(self, cfg: CfgNode, input_channels: int):\n        \"\"\"\n        Initialize predictor using configuration options\n\n        Args:\n            cfg (CfgNode): configuration options\n            input_channels (int): input tensor size along the channel dimension\n        \"\"\"\n        super().__init__()\n        dim_in = input_channels\n        n_segm_chan = cfg.MODEL.ROI_DENSEPOSE_HEAD.NUM_COARSE_SEGM_CHANNELS\n        embed_size = cfg.MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBED_SIZE\n        kernel_size = cfg.MODEL.ROI_DENSEPOSE_HEAD.DECONV_KERNEL\n        # coarse segmentation\n        self.coarse_segm_lowres = ConvTranspose2d(\n            dim_in, n_segm_chan, kernel_size, stride=2, padding=int(kernel_size / 2 - 1)\n        )\n        # embedding\n        self.embed_lowres = ConvTranspose2d(\n            dim_in, embed_size, kernel_size, stride=2, padding=int(kernel_size / 2 - 1)\n        )\n        self.scale_factor = cfg.MODEL.ROI_DENSEPOSE_HEAD.UP_SCALE\n        initialize_module_params(self)\n\n    def interp2d(self, tensor_nchw: torch.Tensor):\n        \"\"\"\n        Bilinear interpolation method to be used for upscaling\n\n        Args:\n            tensor_nchw (tensor): tensor of shape (N, C, H, W)\n        Return:\n            tensor of shape (N, C, Hout, Wout), where Hout and Wout are computed\n                by applying the scale factor to H and W\n        \"\"\"\n        return interpolate(\n            tensor_nchw, scale_factor=self.scale_factor, mode=\"bilinear\", align_corners=False\n        )\n\n    def forward(self, head_outputs):\n        \"\"\"\n        Perform forward step on DensePose head outputs\n\n        Args:\n            head_outputs (tensor): DensePose head outputs, tensor of shape [N, D, H, W]\n        \"\"\"\n        embed_lowres = self.embed_lowres(head_outputs)\n        coarse_segm_lowres = self.coarse_segm_lowres(head_outputs)\n        embed = self.interp2d(embed_lowres)\n        coarse_segm = self.interp2d(coarse_segm_lowres)\n        return DensePoseEmbeddingPredictorOutput(embedding=embed, coarse_segm=coarse_segm)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/predictors/cse_confidence.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom typing import Any\nimport torch\nfrom torch.nn import functional as F\n\nfrom detectron2.config import CfgNode\nfrom detectron2.layers import ConvTranspose2d\n\nfrom densepose.modeling.confidence import DensePoseConfidenceModelConfig\nfrom densepose.modeling.utils import initialize_module_params\nfrom densepose.structures import decorate_cse_predictor_output_class_with_confidences\n\n\nclass DensePoseEmbeddingConfidencePredictorMixin:\n    \"\"\"\n    Predictor contains the last layers of a DensePose model that take DensePose head\n    outputs as an input and produce model outputs. Confidence predictor mixin is used\n    to generate confidences for coarse segmentation estimated by some\n    base predictor. Several assumptions need to hold for the base predictor:\n    1) the `forward` method must return CSE DensePose head outputs,\n        tensor of shape [N, D, H, W]\n    2) `interp2d` method must be defined to perform bilinear interpolation;\n        the same method is typically used for masks and confidences\n    Confidence predictor mixin provides confidence estimates, as described in:\n        N. Neverova et al., Correlated Uncertainty for Learning Dense Correspondences\n            from Noisy Labels, NeurIPS 2019\n        A. Sanakoyeu et al., Transferring Dense Pose to Proximal Animal Classes, CVPR 2020\n    \"\"\"\n\n    def __init__(self, cfg: CfgNode, input_channels: int):\n        \"\"\"\n        Initialize confidence predictor using configuration options.\n\n        Args:\n            cfg (CfgNode): configuration options\n            input_channels (int): number of input channels\n        \"\"\"\n        # we rely on base predictor to call nn.Module.__init__\n        super().__init__(cfg, input_channels)  # pyre-ignore[19]\n        self.confidence_model_cfg = DensePoseConfidenceModelConfig.from_cfg(cfg)\n        self._initialize_confidence_estimation_layers(cfg, input_channels)\n        self._registry = {}\n        initialize_module_params(self)  # pyre-ignore[6]\n\n    def _initialize_confidence_estimation_layers(self, cfg: CfgNode, dim_in: int):\n        \"\"\"\n        Initialize confidence estimation layers based on configuration options\n\n        Args:\n            cfg (CfgNode): configuration options\n            dim_in (int): number of input channels\n        \"\"\"\n        kernel_size = cfg.MODEL.ROI_DENSEPOSE_HEAD.DECONV_KERNEL\n        if self.confidence_model_cfg.segm_confidence.enabled:\n            self.coarse_segm_confidence_lowres = ConvTranspose2d(  # pyre-ignore[16]\n                dim_in, 1, kernel_size, stride=2, padding=int(kernel_size / 2 - 1)\n            )\n\n    def forward(self, head_outputs: torch.Tensor):\n        \"\"\"\n        Perform forward operation on head outputs used as inputs for the predictor.\n        Calls forward method from the base predictor and uses its outputs to compute\n        confidences.\n\n        Args:\n            head_outputs (Tensor): head outputs used as predictor inputs\n        Return:\n            An instance of outputs with confidences,\n            see `decorate_cse_predictor_output_class_with_confidences`\n        \"\"\"\n        # assuming base class returns SIUV estimates in its first result\n        base_predictor_outputs = super().forward(head_outputs)  # pyre-ignore[16]\n\n        # create output instance by extending base predictor outputs:\n        output = self._create_output_instance(base_predictor_outputs)\n\n        if self.confidence_model_cfg.segm_confidence.enabled:\n            # base predictor outputs are assumed to have `coarse_segm` attribute\n            # base predictor is assumed to define `interp2d` method for bilinear interpolation\n            output.coarse_segm_confidence = (\n                F.softplus(\n                    self.interp2d(  # pyre-ignore[16]\n                        self.coarse_segm_confidence_lowres(head_outputs)  # pyre-ignore[16]\n                    )\n                )\n                + self.confidence_model_cfg.segm_confidence.epsilon\n            )\n            output.coarse_segm = base_predictor_outputs.coarse_segm * torch.repeat_interleave(\n                output.coarse_segm_confidence, base_predictor_outputs.coarse_segm.shape[1], dim=1\n            )\n\n        return output\n\n    def _create_output_instance(self, base_predictor_outputs: Any):\n        \"\"\"\n        Create an instance of predictor outputs by copying the outputs from the\n        base predictor and initializing confidence\n\n        Args:\n            base_predictor_outputs: an instance of base predictor outputs\n                (the outputs type is assumed to be a dataclass)\n        Return:\n           An instance of outputs with confidences\n        \"\"\"\n        PredictorOutput = decorate_cse_predictor_output_class_with_confidences(\n            type(base_predictor_outputs)  # pyre-ignore[6]\n        )\n        # base_predictor_outputs is assumed to be a dataclass\n        # reassign all the fields from base_predictor_outputs (no deep copy!), add new fields\n        output = PredictorOutput(\n            **base_predictor_outputs.__dict__,\n            coarse_segm_confidence=None,\n        )\n        return output\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/predictors/cse_with_confidence.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom . import DensePoseEmbeddingConfidencePredictorMixin, DensePoseEmbeddingPredictor\nfrom .registry import DENSEPOSE_PREDICTOR_REGISTRY\n\n\n@DENSEPOSE_PREDICTOR_REGISTRY.register()\nclass DensePoseEmbeddingWithConfidencePredictor(\n    DensePoseEmbeddingConfidencePredictorMixin, DensePoseEmbeddingPredictor\n):\n    \"\"\"\n    Predictor that combines CSE and CSE confidence estimation\n    \"\"\"\n\n    pass\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/predictors/registry.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom detectron2.utils.registry import Registry\n\nDENSEPOSE_PREDICTOR_REGISTRY = Registry(\"DENSEPOSE_PREDICTOR\")\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/roi_heads/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom .v1convx import DensePoseV1ConvXHead\nfrom .deeplab import DensePoseDeepLabHead\nfrom .registry import ROI_DENSEPOSE_HEAD_REGISTRY\nfrom .roi_head import Decoder, DensePoseROIHeads\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/roi_heads/deeplab.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport fvcore.nn.weight_init as weight_init\nimport torch\nfrom torch import nn\nfrom torch.nn import functional as F\n\nfrom detectron2.config import CfgNode\nfrom detectron2.layers import Conv2d\n\nfrom .registry import ROI_DENSEPOSE_HEAD_REGISTRY\n\n\n@ROI_DENSEPOSE_HEAD_REGISTRY.register()\nclass DensePoseDeepLabHead(nn.Module):\n    \"\"\"\n    DensePose head using DeepLabV3 model from\n    \"Rethinking Atrous Convolution for Semantic Image Segmentation\"\n    <https://arxiv.org/abs/1706.05587>.\n    \"\"\"\n\n    def __init__(self, cfg: CfgNode, input_channels: int):\n        super(DensePoseDeepLabHead, self).__init__()\n        # fmt: off\n        hidden_dim           = cfg.MODEL.ROI_DENSEPOSE_HEAD.CONV_HEAD_DIM\n        kernel_size          = cfg.MODEL.ROI_DENSEPOSE_HEAD.CONV_HEAD_KERNEL\n        norm                 = cfg.MODEL.ROI_DENSEPOSE_HEAD.DEEPLAB.NORM\n        self.n_stacked_convs = cfg.MODEL.ROI_DENSEPOSE_HEAD.NUM_STACKED_CONVS\n        self.use_nonlocal    = cfg.MODEL.ROI_DENSEPOSE_HEAD.DEEPLAB.NONLOCAL_ON\n        # fmt: on\n        pad_size = kernel_size // 2\n        n_channels = input_channels\n\n        self.ASPP = ASPP(input_channels, [6, 12, 56], n_channels)  # 6, 12, 56\n        # pyre-fixme[29]: `Union[nn.Module, torch.Tensor]` is not a function.\n        self.add_module(\"ASPP\", self.ASPP)\n\n        if self.use_nonlocal:\n            self.NLBlock = NONLocalBlock2D(input_channels, bn_layer=True)\n            # pyre-fixme[29]: `Union[nn.Module, torch.Tensor]` is not a function.\n            self.add_module(\"NLBlock\", self.NLBlock)\n        # weight_init.c2_msra_fill(self.ASPP)\n\n        for i in range(self.n_stacked_convs):\n            norm_module = nn.GroupNorm(32, hidden_dim) if norm == \"GN\" else None\n            layer = Conv2d(\n                n_channels,\n                hidden_dim,\n                kernel_size,\n                stride=1,\n                padding=pad_size,\n                bias=not norm,\n                norm=norm_module,\n            )\n            weight_init.c2_msra_fill(layer)\n            n_channels = hidden_dim\n            layer_name = self._get_layer_name(i)\n            # pyre-fixme[29]: `Union[nn.Module, torch.Tensor]` is not a function.\n            self.add_module(layer_name, layer)\n        self.n_out_channels = hidden_dim\n        # initialize_module_params(self)\n\n    def forward(self, features):\n        x0 = features\n        x = self.ASPP(x0)\n        if self.use_nonlocal:\n            x = self.NLBlock(x)\n        output = x\n        for i in range(self.n_stacked_convs):\n            layer_name = self._get_layer_name(i)\n            x = getattr(self, layer_name)(x)\n            x = F.relu(x)\n            output = x\n        return output\n\n    def _get_layer_name(self, i: int):\n        layer_name = \"body_conv_fcn{}\".format(i + 1)\n        return layer_name\n\n\n# Copied from\n# https://github.com/pytorch/vision/blob/master/torchvision/models/segmentation/deeplabv3.py\n# See https://arxiv.org/pdf/1706.05587.pdf for details\nclass ASPPConv(nn.Sequential):  # pyre-ignore[11]\n    def __init__(self, in_channels, out_channels, dilation):\n        modules = [\n            nn.Conv2d(\n                in_channels, out_channels, 3, padding=dilation, dilation=dilation, bias=False\n            ),\n            nn.GroupNorm(32, out_channels),\n            nn.ReLU(),\n        ]\n        super(ASPPConv, self).__init__(*modules)\n\n\nclass ASPPPooling(nn.Sequential):\n    def __init__(self, in_channels, out_channels):\n        super(ASPPPooling, self).__init__(\n            nn.AdaptiveAvgPool2d(1),\n            nn.Conv2d(in_channels, out_channels, 1, bias=False),\n            nn.GroupNorm(32, out_channels),\n            nn.ReLU(),\n        )\n\n    def forward(self, x):\n        size = x.shape[-2:]\n        x = super(ASPPPooling, self).forward(x)\n        return F.interpolate(x, size=size, mode=\"bilinear\", align_corners=False)\n\n\nclass ASPP(nn.Module):\n    def __init__(self, in_channels, atrous_rates, out_channels):\n        super(ASPP, self).__init__()\n        modules = []\n        modules.append(\n            nn.Sequential(\n                nn.Conv2d(in_channels, out_channels, 1, bias=False),\n                nn.GroupNorm(32, out_channels),\n                nn.ReLU(),\n            )\n        )\n\n        rate1, rate2, rate3 = tuple(atrous_rates)\n        modules.append(ASPPConv(in_channels, out_channels, rate1))\n        modules.append(ASPPConv(in_channels, out_channels, rate2))\n        modules.append(ASPPConv(in_channels, out_channels, rate3))\n        modules.append(ASPPPooling(in_channels, out_channels))\n\n        self.convs = nn.ModuleList(modules)\n\n        self.project = nn.Sequential(\n            nn.Conv2d(5 * out_channels, out_channels, 1, bias=False),\n            # nn.BatchNorm2d(out_channels),\n            nn.ReLU()\n            # nn.Dropout(0.5)\n        )\n\n    def forward(self, x):\n        res = []\n        for conv in self.convs:\n            res.append(conv(x))\n        res = torch.cat(res, dim=1)\n        return self.project(res)\n\n\n# copied from\n# https://github.com/AlexHex7/Non-local_pytorch/blob/master/lib/non_local_embedded_gaussian.py\n# See https://arxiv.org/abs/1711.07971 for details\nclass _NonLocalBlockND(nn.Module):\n    def __init__(\n        self, in_channels, inter_channels=None, dimension=3, sub_sample=True, bn_layer=True\n    ):\n        super(_NonLocalBlockND, self).__init__()\n\n        assert dimension in [1, 2, 3]\n\n        self.dimension = dimension\n        self.sub_sample = sub_sample\n\n        self.in_channels = in_channels\n        self.inter_channels = inter_channels\n\n        if self.inter_channels is None:\n            self.inter_channels = in_channels // 2\n            if self.inter_channels == 0:\n                self.inter_channels = 1\n\n        if dimension == 3:\n            conv_nd = nn.Conv3d\n            max_pool_layer = nn.MaxPool3d(kernel_size=(1, 2, 2))\n            bn = nn.GroupNorm  # (32, hidden_dim) #nn.BatchNorm3d\n        elif dimension == 2:\n            conv_nd = nn.Conv2d\n            max_pool_layer = nn.MaxPool2d(kernel_size=(2, 2))\n            bn = nn.GroupNorm  # (32, hidden_dim)nn.BatchNorm2d\n        else:\n            conv_nd = nn.Conv1d\n            max_pool_layer = nn.MaxPool1d(kernel_size=2)\n            bn = nn.GroupNorm  # (32, hidden_dim)nn.BatchNorm1d\n\n        self.g = conv_nd(\n            in_channels=self.in_channels,\n            out_channels=self.inter_channels,\n            kernel_size=1,\n            stride=1,\n            padding=0,\n        )\n\n        if bn_layer:\n            self.W = nn.Sequential(\n                conv_nd(\n                    in_channels=self.inter_channels,\n                    out_channels=self.in_channels,\n                    kernel_size=1,\n                    stride=1,\n                    padding=0,\n                ),\n                bn(32, self.in_channels),\n            )\n            nn.init.constant_(self.W[1].weight, 0)\n            nn.init.constant_(self.W[1].bias, 0)\n        else:\n            self.W = conv_nd(\n                in_channels=self.inter_channels,\n                out_channels=self.in_channels,\n                kernel_size=1,\n                stride=1,\n                padding=0,\n            )\n            nn.init.constant_(self.W.weight, 0)\n            nn.init.constant_(self.W.bias, 0)\n\n        self.theta = conv_nd(\n            in_channels=self.in_channels,\n            out_channels=self.inter_channels,\n            kernel_size=1,\n            stride=1,\n            padding=0,\n        )\n        self.phi = conv_nd(\n            in_channels=self.in_channels,\n            out_channels=self.inter_channels,\n            kernel_size=1,\n            stride=1,\n            padding=0,\n        )\n\n        if sub_sample:\n            self.g = nn.Sequential(self.g, max_pool_layer)\n            self.phi = nn.Sequential(self.phi, max_pool_layer)\n\n    def forward(self, x):\n        \"\"\"\n        :param x: (b, c, t, h, w)\n        :return:\n        \"\"\"\n\n        batch_size = x.size(0)\n\n        g_x = self.g(x).view(batch_size, self.inter_channels, -1)\n        g_x = g_x.permute(0, 2, 1)\n\n        theta_x = self.theta(x).view(batch_size, self.inter_channels, -1)\n        theta_x = theta_x.permute(0, 2, 1)\n        phi_x = self.phi(x).view(batch_size, self.inter_channels, -1)\n        f = torch.matmul(theta_x, phi_x)\n        f_div_C = F.softmax(f, dim=-1)\n\n        y = torch.matmul(f_div_C, g_x)\n        y = y.permute(0, 2, 1).contiguous()\n        y = y.view(batch_size, self.inter_channels, *x.size()[2:])\n        W_y = self.W(y)\n        z = W_y + x\n\n        return z\n\n\nclass NONLocalBlock2D(_NonLocalBlockND):\n    def __init__(self, in_channels, inter_channels=None, sub_sample=True, bn_layer=True):\n        super(NONLocalBlock2D, self).__init__(\n            in_channels,\n            inter_channels=inter_channels,\n            dimension=2,\n            sub_sample=sub_sample,\n            bn_layer=bn_layer,\n        )\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/roi_heads/registry.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom detectron2.utils.registry import Registry\n\nROI_DENSEPOSE_HEAD_REGISTRY = Registry(\"ROI_DENSEPOSE_HEAD\")\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/roi_heads/roi_head.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport numpy as np\nfrom typing import Dict, List, Optional\nimport fvcore.nn.weight_init as weight_init\nimport torch\nimport torch.nn as nn\nfrom torch.nn import functional as F\n\nfrom detectron2.layers import Conv2d, ShapeSpec, get_norm\nfrom detectron2.modeling import ROI_HEADS_REGISTRY, StandardROIHeads\nfrom detectron2.modeling.poolers import ROIPooler\nfrom detectron2.modeling.roi_heads import select_foreground_proposals\nfrom detectron2.structures import ImageList, Instances\n\nfrom .. import (\n    build_densepose_data_filter,\n    build_densepose_embedder,\n    build_densepose_head,\n    build_densepose_losses,\n    build_densepose_predictor,\n    densepose_inference,\n)\n\n\nclass Decoder(nn.Module):\n    \"\"\"\n    A semantic segmentation head described in detail in the Panoptic Feature Pyramid Networks paper\n    (https://arxiv.org/abs/1901.02446). It takes FPN features as input and merges information from\n    all levels of the FPN into single output.\n    \"\"\"\n\n    def __init__(self, cfg, input_shape: Dict[str, ShapeSpec], in_features):\n        super(Decoder, self).__init__()\n\n        # fmt: off\n        self.in_features      = in_features\n        feature_strides       = {k: v.stride for k, v in input_shape.items()}\n        feature_channels      = {k: v.channels for k, v in input_shape.items()}\n        num_classes           = cfg.MODEL.ROI_DENSEPOSE_HEAD.DECODER_NUM_CLASSES\n        conv_dims             = cfg.MODEL.ROI_DENSEPOSE_HEAD.DECODER_CONV_DIMS\n        self.common_stride    = cfg.MODEL.ROI_DENSEPOSE_HEAD.DECODER_COMMON_STRIDE\n        norm                  = cfg.MODEL.ROI_DENSEPOSE_HEAD.DECODER_NORM\n        # fmt: on\n\n        self.scale_heads = []\n        for in_feature in self.in_features:\n            head_ops = []\n            head_length = max(\n                1, int(np.log2(feature_strides[in_feature]) - np.log2(self.common_stride))\n            )\n            for k in range(head_length):\n                conv = Conv2d(\n                    feature_channels[in_feature] if k == 0 else conv_dims,\n                    conv_dims,\n                    kernel_size=3,\n                    stride=1,\n                    padding=1,\n                    bias=not norm,\n                    norm=get_norm(norm, conv_dims),\n                    activation=F.relu,\n                )\n                weight_init.c2_msra_fill(conv)\n                head_ops.append(conv)\n                if feature_strides[in_feature] != self.common_stride:\n                    head_ops.append(\n                        nn.Upsample(scale_factor=2, mode=\"bilinear\", align_corners=False)\n                    )\n            self.scale_heads.append(nn.Sequential(*head_ops))\n            # pyre-fixme[29]: `Union[nn.Module, torch.Tensor]` is not a function.\n            self.add_module(in_feature, self.scale_heads[-1])\n        self.predictor = Conv2d(conv_dims, num_classes, kernel_size=1, stride=1, padding=0)\n        weight_init.c2_msra_fill(self.predictor)\n\n    def forward(self, features: List[torch.Tensor]):\n        for i, _ in enumerate(self.in_features):\n            if i == 0:\n                x = self.scale_heads[i](features[i])\n            else:\n                x = x + self.scale_heads[i](features[i])\n        x = self.predictor(x)\n        return x\n\n\n@ROI_HEADS_REGISTRY.register()\nclass DensePoseROIHeads(StandardROIHeads):\n    \"\"\"\n    A Standard ROIHeads which contains an addition of DensePose head.\n    \"\"\"\n\n    def __init__(self, cfg, input_shape):\n        super().__init__(cfg, input_shape)\n        self._init_densepose_head(cfg, input_shape)\n\n    def _init_densepose_head(self, cfg, input_shape):\n        # fmt: off\n        self.densepose_on          = cfg.MODEL.DENSEPOSE_ON\n        if not self.densepose_on:\n            return\n        self.densepose_data_filter = build_densepose_data_filter(cfg)\n        dp_pooler_resolution       = cfg.MODEL.ROI_DENSEPOSE_HEAD.POOLER_RESOLUTION\n        dp_pooler_sampling_ratio   = cfg.MODEL.ROI_DENSEPOSE_HEAD.POOLER_SAMPLING_RATIO\n        dp_pooler_type             = cfg.MODEL.ROI_DENSEPOSE_HEAD.POOLER_TYPE\n        self.use_decoder           = cfg.MODEL.ROI_DENSEPOSE_HEAD.DECODER_ON\n        # fmt: on\n        if self.use_decoder:\n            dp_pooler_scales = (1.0 / input_shape[self.in_features[0]].stride,)\n        else:\n            dp_pooler_scales = tuple(1.0 / input_shape[k].stride for k in self.in_features)\n        in_channels = [input_shape[f].channels for f in self.in_features][0]\n\n        if self.use_decoder:\n            self.decoder = Decoder(cfg, input_shape, self.in_features)\n\n        self.densepose_pooler = ROIPooler(\n            output_size=dp_pooler_resolution,\n            scales=dp_pooler_scales,\n            sampling_ratio=dp_pooler_sampling_ratio,\n            pooler_type=dp_pooler_type,\n        )\n        self.densepose_head = build_densepose_head(cfg, in_channels)\n        self.densepose_predictor = build_densepose_predictor(\n            cfg, self.densepose_head.n_out_channels\n        )\n        self.densepose_losses = build_densepose_losses(cfg)\n        self.embedder = build_densepose_embedder(cfg)\n\n    def _forward_densepose(self, features: Dict[str, torch.Tensor], instances: List[Instances]):\n        \"\"\"\n        Forward logic of the densepose prediction branch.\n\n        Args:\n            features (dict[str, Tensor]): input data as a mapping from feature\n                map name to tensor. Axis 0 represents the number of images `N` in\n                the input data; axes 1-3 are channels, height, and width, which may\n                vary between feature maps (e.g., if a feature pyramid is used).\n            instances (list[Instances]): length `N` list of `Instances`. The i-th\n                `Instances` contains instances for the i-th input image,\n                In training, they can be the proposals.\n                In inference, they can be the predicted boxes.\n\n        Returns:\n            In training, a dict of losses.\n            In inference, update `instances` with new fields \"densepose\" and return it.\n        \"\"\"\n        if not self.densepose_on:\n            return {} if self.training else instances\n\n        features_list = [features[f] for f in self.in_features]\n        if self.training:\n            proposals, _ = select_foreground_proposals(instances, self.num_classes)\n            features_list, proposals = self.densepose_data_filter(features_list, proposals)\n            if len(proposals) > 0:\n                proposal_boxes = [x.proposal_boxes for x in proposals]\n\n                if self.use_decoder:\n                    # pyre-fixme[29]: `Union[nn.Module, torch.Tensor]` is not a\n                    #  function.\n                    features_list = [self.decoder(features_list)]\n\n                features_dp = self.densepose_pooler(features_list, proposal_boxes)\n                densepose_head_outputs = self.densepose_head(features_dp)\n                densepose_predictor_outputs = self.densepose_predictor(densepose_head_outputs)\n                densepose_loss_dict = self.densepose_losses(\n                    proposals, densepose_predictor_outputs, embedder=self.embedder\n                )\n                return densepose_loss_dict\n        else:\n            pred_boxes = [x.pred_boxes for x in instances]\n\n            if self.use_decoder:\n                # pyre-fixme[29]: `Union[nn.Module, torch.Tensor]` is not a function.\n                features_list = [self.decoder(features_list)]\n\n            features_dp = self.densepose_pooler(features_list, pred_boxes)\n            if len(features_dp) > 0:\n                densepose_head_outputs = self.densepose_head(features_dp)\n                densepose_predictor_outputs = self.densepose_predictor(densepose_head_outputs)\n            else:\n                densepose_predictor_outputs = None\n\n            densepose_inference(densepose_predictor_outputs, instances)\n            return instances\n\n    def forward(\n        self,\n        images: ImageList,\n        features: Dict[str, torch.Tensor],\n        proposals: List[Instances],\n        targets: Optional[List[Instances]] = None,\n    ):\n        instances, losses = super().forward(images, features, proposals, targets)\n        del targets, images\n\n        if self.training:\n            losses.update(self._forward_densepose(features, instances))\n        return instances, losses\n\n    def forward_with_given_boxes(\n        self, features: Dict[str, torch.Tensor], instances: List[Instances]\n    ):\n        \"\"\"\n        Use the given boxes in `instances` to produce other (non-box) per-ROI outputs.\n\n        This is useful for downstream tasks where a box is known, but need to obtain\n        other attributes (outputs of other heads).\n        Test-time augmentation also uses this.\n\n        Args:\n            features: same as in `forward()`\n            instances (list[Instances]): instances to predict other outputs. Expect the keys\n                \"pred_boxes\" and \"pred_classes\" to exist.\n\n        Returns:\n            instances (list[Instances]):\n                the same `Instances` objects, with extra\n                fields such as `pred_masks` or `pred_keypoints`.\n        \"\"\"\n\n        instances = super().forward_with_given_boxes(features, instances)\n        instances = self._forward_densepose(features, instances)\n        return instances\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/roi_heads/v1convx.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport torch\nfrom torch import nn\nfrom torch.nn import functional as F\n\nfrom detectron2.config import CfgNode\nfrom detectron2.layers import Conv2d\n\nfrom ..utils import initialize_module_params\nfrom .registry import ROI_DENSEPOSE_HEAD_REGISTRY\n\n\n@ROI_DENSEPOSE_HEAD_REGISTRY.register()\nclass DensePoseV1ConvXHead(nn.Module):\n    \"\"\"\n    Fully convolutional DensePose head.\n    \"\"\"\n\n    def __init__(self, cfg: CfgNode, input_channels: int):\n        \"\"\"\n        Initialize DensePose fully convolutional head\n\n        Args:\n            cfg (CfgNode): configuration options\n            input_channels (int): number of input channels\n        \"\"\"\n        super(DensePoseV1ConvXHead, self).__init__()\n        # fmt: off\n        hidden_dim           = cfg.MODEL.ROI_DENSEPOSE_HEAD.CONV_HEAD_DIM\n        kernel_size          = cfg.MODEL.ROI_DENSEPOSE_HEAD.CONV_HEAD_KERNEL\n        self.n_stacked_convs = cfg.MODEL.ROI_DENSEPOSE_HEAD.NUM_STACKED_CONVS\n        # fmt: on\n        pad_size = kernel_size // 2\n        n_channels = input_channels\n        for i in range(self.n_stacked_convs):\n            layer = Conv2d(n_channels, hidden_dim, kernel_size, stride=1, padding=pad_size)\n            layer_name = self._get_layer_name(i)\n            # pyre-fixme[29]: `Union[nn.Module, torch.Tensor]` is not a function.\n            self.add_module(layer_name, layer)\n            n_channels = hidden_dim\n        self.n_out_channels = n_channels\n        initialize_module_params(self)\n\n    def forward(self, features: torch.Tensor):\n        \"\"\"\n        Apply DensePose fully convolutional head to the input features\n\n        Args:\n            features (tensor): input features\n        Result:\n            A tensor of DensePose head outputs\n        \"\"\"\n        x = features\n        output = x\n        for i in range(self.n_stacked_convs):\n            layer_name = self._get_layer_name(i)\n            x = getattr(self, layer_name)(x)\n            x = F.relu(x)\n            output = x\n        return output\n\n    def _get_layer_name(self, i: int):\n        layer_name = \"body_conv_fcn{}\".format(i + 1)\n        return layer_name\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/test_time_augmentation.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport copy\nimport numpy as np\nimport torch\nfrom fvcore.transforms import HFlipTransform, TransformList\nfrom torch.nn import functional as F\n\nfrom detectron2.data.transforms import RandomRotation, RotationTransform, apply_transform_gens\nfrom detectron2.modeling.postprocessing import detector_postprocess\nfrom detectron2.modeling.test_time_augmentation import DatasetMapperTTA, GeneralizedRCNNWithTTA\n\nfrom ..converters import HFlipConverter\n\n\nclass DensePoseDatasetMapperTTA(DatasetMapperTTA):\n    def __init__(self, cfg):\n        super().__init__(cfg=cfg)\n        self.angles = cfg.TEST.AUG.ROTATION_ANGLES\n\n    def __call__(self, dataset_dict):\n        ret = super().__call__(dataset_dict=dataset_dict)\n        numpy_image = dataset_dict[\"image\"].permute(1, 2, 0).numpy()\n        for angle in self.angles:\n            rotate = RandomRotation(angle=angle, expand=True)\n            new_numpy_image, tfms = apply_transform_gens([rotate], np.copy(numpy_image))\n            torch_image = torch.from_numpy(np.ascontiguousarray(new_numpy_image.transpose(2, 0, 1)))\n            dic = copy.deepcopy(dataset_dict)\n            # In DatasetMapperTTA, there is a pre_tfm transform (resize or no-op) that is\n            # added at the beginning of each TransformList. That's '.transforms[0]'.\n            dic[\"transforms\"] = TransformList(\n                [ret[-1][\"transforms\"].transforms[0]] + tfms.transforms\n            )\n            dic[\"image\"] = torch_image\n            ret.append(dic)\n        return ret\n\n\nclass DensePoseGeneralizedRCNNWithTTA(GeneralizedRCNNWithTTA):\n    def __init__(self, cfg, model, transform_data, tta_mapper=None, batch_size=1):\n        \"\"\"\n        Args:\n            cfg (CfgNode):\n            model (GeneralizedRCNN): a GeneralizedRCNN to apply TTA on.\n            transform_data (DensePoseTransformData): contains symmetry label\n                transforms used for horizontal flip\n            tta_mapper (callable): takes a dataset dict and returns a list of\n                augmented versions of the dataset dict. Defaults to\n                `DatasetMapperTTA(cfg)`.\n            batch_size (int): batch the augmented images into this batch size for inference.\n        \"\"\"\n        self._transform_data = transform_data.to(model.device)\n        super().__init__(cfg=cfg, model=model, tta_mapper=tta_mapper, batch_size=batch_size)\n\n    # the implementation follows closely the one from detectron2/modeling\n    def _inference_one_image(self, input):\n        \"\"\"\n        Args:\n            input (dict): one dataset dict with \"image\" field being a CHW tensor\n\n        Returns:\n            dict: one output dict\n        \"\"\"\n        orig_shape = (input[\"height\"], input[\"width\"])\n        # For some reason, resize with uint8 slightly increases box AP but decreases densepose AP\n        input[\"image\"] = input[\"image\"].to(torch.uint8)\n        augmented_inputs, tfms = self._get_augmented_inputs(input)\n        # Detect boxes from all augmented versions\n        with self._turn_off_roi_heads([\"mask_on\", \"keypoint_on\", \"densepose_on\"]):\n            # temporarily disable roi heads\n            all_boxes, all_scores, all_classes = self._get_augmented_boxes(augmented_inputs, tfms)\n        merged_instances = self._merge_detections(all_boxes, all_scores, all_classes, orig_shape)\n\n        if self.cfg.MODEL.MASK_ON or self.cfg.MODEL.DENSEPOSE_ON:\n            # Use the detected boxes to obtain new fields\n            augmented_instances = self._rescale_detected_boxes(\n                augmented_inputs, merged_instances, tfms\n            )\n            # run forward on the detected boxes\n            outputs = self._batch_inference(augmented_inputs, augmented_instances)\n            # Delete now useless variables to avoid being out of memory\n            del augmented_inputs, augmented_instances\n            # average the predictions\n            if self.cfg.MODEL.MASK_ON:\n                merged_instances.pred_masks = self._reduce_pred_masks(outputs, tfms)\n            if self.cfg.MODEL.DENSEPOSE_ON:\n                merged_instances.pred_densepose = self._reduce_pred_densepose(outputs, tfms)\n            # postprocess\n            merged_instances = detector_postprocess(merged_instances, *orig_shape)\n            return {\"instances\": merged_instances}\n        else:\n            return {\"instances\": merged_instances}\n\n    def _get_augmented_boxes(self, augmented_inputs, tfms):\n        # Heavily based on detectron2/modeling/test_time_augmentation.py\n        # Only difference is that RotationTransform is excluded from bbox computation\n        # 1: forward with all augmented images\n        outputs = self._batch_inference(augmented_inputs)\n        # 2: union the results\n        all_boxes = []\n        all_scores = []\n        all_classes = []\n        for output, tfm in zip(outputs, tfms):\n            # Need to inverse the transforms on boxes, to obtain results on original image\n            if not any(isinstance(t, RotationTransform) for t in tfm.transforms):\n                # Some transforms can't compute bbox correctly\n                pred_boxes = output.pred_boxes.tensor\n                original_pred_boxes = tfm.inverse().apply_box(pred_boxes.cpu().numpy())\n                all_boxes.append(torch.from_numpy(original_pred_boxes).to(pred_boxes.device))\n                all_scores.extend(output.scores)\n                all_classes.extend(output.pred_classes)\n        all_boxes = torch.cat(all_boxes, dim=0)\n        return all_boxes, all_scores, all_classes\n\n    def _reduce_pred_densepose(self, outputs, tfms):\n        # Should apply inverse transforms on densepose preds.\n        # We assume only rotation, resize & flip are used. pred_masks is a scale-invariant\n        # representation, so we handle the other ones specially\n        for idx, (output, tfm) in enumerate(zip(outputs, tfms)):\n            for t in tfm.transforms:\n                for attr in [\"coarse_segm\", \"fine_segm\", \"u\", \"v\"]:\n                    setattr(\n                        output.pred_densepose,\n                        attr,\n                        _inverse_rotation(\n                            getattr(output.pred_densepose, attr), output.pred_boxes.tensor, t\n                        ),\n                    )\n            if any(isinstance(t, HFlipTransform) for t in tfm.transforms):\n                output.pred_densepose = HFlipConverter.convert(\n                    output.pred_densepose, self._transform_data\n                )\n            self._incremental_avg_dp(outputs[0].pred_densepose, output.pred_densepose, idx)\n        return outputs[0].pred_densepose\n\n    # incrementally computed average: u_(n + 1) = u_n + (x_(n+1) - u_n) / (n + 1).\n    def _incremental_avg_dp(self, avg, new_el, idx):\n        for attr in [\"coarse_segm\", \"fine_segm\", \"u\", \"v\"]:\n            setattr(avg, attr, (getattr(avg, attr) * idx + getattr(new_el, attr)) / (idx + 1))\n            if idx:\n                # Deletion of the > 0 index intermediary values to prevent GPU OOM\n                setattr(new_el, attr, None)\n        return avg\n\n\ndef _inverse_rotation(densepose_attrs, boxes, transform):\n    # resample outputs to image size and rotate back the densepose preds\n    # on the rotated images to the space of the original image\n    if len(boxes) == 0 or not isinstance(transform, RotationTransform):\n        return densepose_attrs\n    boxes = boxes.int().cpu().numpy()\n    wh_boxes = boxes[:, 2:] - boxes[:, :2]  # bboxes in the rotated space\n    inv_boxes = rotate_box_inverse(transform, boxes).astype(int)  # bboxes in original image\n    wh_diff = (inv_boxes[:, 2:] - inv_boxes[:, :2] - wh_boxes) // 2  # diff between new/old bboxes\n    rotation_matrix = torch.tensor([transform.rm_image]).to(device=densepose_attrs.device).float()\n    rotation_matrix[:, :, -1] = 0\n    # To apply grid_sample for rotation, we need to have enough space to fit the original and\n    # rotated bboxes. l_bds and r_bds are the left/right bounds that will be used to\n    # crop the difference once the rotation is done\n    l_bds = np.maximum(0, -wh_diff)\n    for i in range(len(densepose_attrs)):\n        if min(wh_boxes[i]) <= 0:\n            continue\n        densepose_attr = densepose_attrs[[i]].clone()\n        # 1. Interpolate densepose attribute to size of the rotated bbox\n        densepose_attr = F.interpolate(densepose_attr, wh_boxes[i].tolist()[::-1], mode=\"bilinear\")\n        # 2. Pad the interpolated attribute so it has room for the original + rotated bbox\n        densepose_attr = F.pad(densepose_attr, tuple(np.repeat(np.maximum(0, wh_diff[i]), 2)))\n        # 3. Compute rotation grid and transform\n        grid = F.affine_grid(rotation_matrix, size=densepose_attr.shape)\n        densepose_attr = F.grid_sample(densepose_attr, grid)\n        # 4. Compute right bounds and crop the densepose_attr to the size of the original bbox\n        r_bds = densepose_attr.shape[2:][::-1] - l_bds[i]\n        densepose_attr = densepose_attr[:, :, l_bds[i][1] : r_bds[1], l_bds[i][0] : r_bds[0]]\n        if min(densepose_attr.shape) > 0:\n            # Interpolate back to the original size of the densepose attribute\n            densepose_attr = F.interpolate(\n                densepose_attr, densepose_attrs.shape[-2:], mode=\"bilinear\"\n            )\n            # Adding a very small probability to the background class to fill padded zones\n            densepose_attr[:, 0] += 1e-10\n            densepose_attrs[i] = densepose_attr\n    return densepose_attrs\n\n\ndef rotate_box_inverse(rot_tfm, rotated_box):\n    \"\"\"\n    rotated_box is a N * 4 array of [x0, y0, x1, y1] boxes\n    When a bbox is rotated, it gets bigger, because we need to surround the tilted bbox\n    So when a bbox is rotated then inverse-rotated, it is much bigger than the original\n    This function aims to invert the rotation on the box, but also resize it to its original size\n    \"\"\"\n    # 1. Compute the inverse rotation of the rotated bboxes (bigger than it )\n    invrot_box = rot_tfm.inverse().apply_box(rotated_box)\n    h, w = rotated_box[:, 3] - rotated_box[:, 1], rotated_box[:, 2] - rotated_box[:, 0]\n    ih, iw = invrot_box[:, 3] - invrot_box[:, 1], invrot_box[:, 2] - invrot_box[:, 0]\n    assert 2 * rot_tfm.abs_sin ** 2 != 1, \"45 degrees angle can't be inverted\"\n    # 2. Inverse the corresponding computation in the rotation transform\n    # to get the original height/width of the rotated boxes\n    orig_h = (h * rot_tfm.abs_cos - w * rot_tfm.abs_sin) / (1 - 2 * rot_tfm.abs_sin ** 2)\n    orig_w = (w * rot_tfm.abs_cos - h * rot_tfm.abs_sin) / (1 - 2 * rot_tfm.abs_sin ** 2)\n    # 3. Resize the inverse-rotated bboxes to their original size\n    invrot_box[:, 0] += (iw - orig_w) / 2\n    invrot_box[:, 1] += (ih - orig_h) / 2\n    invrot_box[:, 2] -= (iw - orig_w) / 2\n    invrot_box[:, 3] -= (ih - orig_h) / 2\n\n    return invrot_box\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/modeling/utils.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom torch import nn\n\n\ndef initialize_module_params(module: nn.Module):\n    for name, param in module.named_parameters():\n        if \"bias\" in name:\n            nn.init.constant_(param, 0)\n        elif \"weight\" in name:\n            nn.init.kaiming_normal_(param, mode=\"fan_out\", nonlinearity=\"relu\")\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/structures/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom .chart import DensePoseChartPredictorOutput\nfrom .chart_confidence import decorate_predictor_output_class_with_confidences\nfrom .cse_confidence import decorate_cse_predictor_output_class_with_confidences\nfrom .chart_result import (\n    DensePoseChartResult,\n    DensePoseChartResultWithConfidences,\n    quantize_densepose_chart_result,\n    compress_quantized_densepose_chart_result,\n    decompress_compressed_densepose_chart_result,\n)\nfrom .cse import DensePoseEmbeddingPredictorOutput\nfrom .data_relative import DensePoseDataRelative\nfrom .list import DensePoseList\nfrom .mesh import Mesh, create_mesh\nfrom .transform_data import DensePoseTransformData, normalized_coords_transform\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/structures/chart.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom dataclasses import dataclass\nfrom typing import Union\nimport torch\n\n\n@dataclass\nclass DensePoseChartPredictorOutput:\n    \"\"\"\n    Predictor output that contains segmentation and inner coordinates predictions for predefined\n    body parts:\n     * coarse segmentation, a tensor of shape [N, K, Hout, Wout]\n     * fine segmentation, a tensor of shape [N, C, Hout, Wout]\n     * U coordinates, a tensor of shape [N, C, Hout, Wout]\n     * V coordinates, a tensor of shape [N, C, Hout, Wout]\n    where\n     - N is the number of instances\n     - K is the number of coarse segmentation channels (\n         2 = foreground / background,\n         15 = one of 14 body parts / background)\n     - C is the number of fine segmentation channels (\n         24 fine body parts / background)\n     - Hout and Wout are height and width of predictions\n    \"\"\"\n\n    coarse_segm: torch.Tensor\n    fine_segm: torch.Tensor\n    u: torch.Tensor\n    v: torch.Tensor\n\n    def __len__(self):\n        \"\"\"\n        Number of instances (N) in the output\n        \"\"\"\n        return self.coarse_segm.size(0)\n\n    def __getitem__(\n        self, item: Union[int, slice, torch.BoolTensor]\n    ) -> \"DensePoseChartPredictorOutput\":\n        \"\"\"\n        Get outputs for the selected instance(s)\n\n        Args:\n            item (int or slice or tensor): selected items\n        \"\"\"\n        if isinstance(item, int):\n            return DensePoseChartPredictorOutput(\n                coarse_segm=self.coarse_segm[item].unsqueeze(0),\n                fine_segm=self.fine_segm[item].unsqueeze(0),\n                u=self.u[item].unsqueeze(0),\n                v=self.v[item].unsqueeze(0),\n            )\n        else:\n            return DensePoseChartPredictorOutput(\n                coarse_segm=self.coarse_segm[item],\n                fine_segm=self.fine_segm[item],\n                u=self.u[item],\n                v=self.v[item],\n            )\n\n    def to(self, device: torch.device):\n        \"\"\"\n        Transfers all tensors to the given device\n        \"\"\"\n        coarse_segm = self.coarse_segm.to(device)\n        fine_segm = self.fine_segm.to(device)\n        u = self.u.to(device)\n        v = self.v.to(device)\n        return DensePoseChartPredictorOutput(coarse_segm=coarse_segm, fine_segm=fine_segm, u=u, v=v)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/structures/chart_confidence.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom dataclasses import make_dataclass\nfrom functools import lru_cache\nfrom typing import Any, Optional\nimport torch\n\n\n@lru_cache(maxsize=None)\ndef decorate_predictor_output_class_with_confidences(BasePredictorOutput: type) -> type:\n    \"\"\"\n    Create a new output class from an existing one by adding new attributes\n    related to confidence estimation:\n    - sigma_1 (tensor)\n    - sigma_2 (tensor)\n    - kappa_u (tensor)\n    - kappa_v (tensor)\n    - fine_segm_confidence (tensor)\n    - coarse_segm_confidence (tensor)\n\n    Details on confidence estimation parameters can be found in:\n    N. Neverova, D. Novotny, A. Vedaldi \"Correlated Uncertainty for Learning\n        Dense Correspondences from Noisy Labels\", p. 918--926, in Proc. NIPS 2019\n    A. Sanakoyeu et al., Transferring Dense Pose to Proximal Animal Classes, CVPR 2020\n\n    The new class inherits the provided `BasePredictorOutput` class,\n    it's name is composed of the name of the provided class and\n    \"WithConfidences\" suffix.\n\n    Args:\n        BasePredictorOutput (type): output type to which confidence data\n            is to be added, assumed to be a dataclass\n    Return:\n        New dataclass derived from the provided one that has attributes\n        for confidence estimation\n    \"\"\"\n\n    PredictorOutput = make_dataclass(\n        BasePredictorOutput.__name__ + \"WithConfidences\",\n        fields=[  # pyre-ignore[6]\n            (\"sigma_1\", Optional[torch.Tensor], None),\n            (\"sigma_2\", Optional[torch.Tensor], None),\n            (\"kappa_u\", Optional[torch.Tensor], None),\n            (\"kappa_v\", Optional[torch.Tensor], None),\n            (\"fine_segm_confidence\", Optional[torch.Tensor], None),\n            (\"coarse_segm_confidence\", Optional[torch.Tensor], None),\n        ],\n        bases=(BasePredictorOutput,),\n    )\n\n    # add possibility to index PredictorOutput\n\n    def slice_if_not_none(data, item):\n        if data is None:\n            return None\n        if isinstance(item, int):\n            return data[item].unsqueeze(0)\n        return data[item]\n\n    def PredictorOutput_getitem(self, item):\n        PredictorOutput = type(self)\n        base_predictor_output_sliced = super(PredictorOutput, self).__getitem__(item)\n        return PredictorOutput(\n            **base_predictor_output_sliced.__dict__,\n            coarse_segm_confidence=slice_if_not_none(self.coarse_segm_confidence, item),\n            fine_segm_confidence=slice_if_not_none(self.fine_segm_confidence, item),\n            sigma_1=slice_if_not_none(self.sigma_1, item),\n            sigma_2=slice_if_not_none(self.sigma_2, item),\n            kappa_u=slice_if_not_none(self.kappa_u, item),\n            kappa_v=slice_if_not_none(self.kappa_v, item),\n        )\n\n    PredictorOutput.__getitem__ = PredictorOutput_getitem\n\n    def PredictorOutput_to(self, device: torch.device):\n        \"\"\"\n        Transfers all tensors to the given device\n        \"\"\"\n        PredictorOutput = type(self)\n        base_predictor_output_to = super(PredictorOutput, self).to(device)  # pyre-ignore[16]\n\n        def to_device_if_tensor(var: Any):\n            if isinstance(var, torch.Tensor):\n                return var.to(device)\n            return var\n\n        return PredictorOutput(\n            **base_predictor_output_to.__dict__,\n            sigma_1=to_device_if_tensor(self.sigma_1),\n            sigma_2=to_device_if_tensor(self.sigma_2),\n            kappa_u=to_device_if_tensor(self.kappa_u),\n            kappa_v=to_device_if_tensor(self.kappa_v),\n            fine_segm_confidence=to_device_if_tensor(self.fine_segm_confidence),\n            coarse_segm_confidence=to_device_if_tensor(self.coarse_segm_confidence),\n        )\n\n    PredictorOutput.to = PredictorOutput_to\n    return PredictorOutput\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/structures/chart_result.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom dataclasses import dataclass\nfrom typing import Any, Optional, Tuple\nimport torch\n\n\n@dataclass\nclass DensePoseChartResult:\n    \"\"\"\n    DensePose results for chart-based methods represented by labels and inner\n    coordinates (U, V) of individual charts. Each chart is a 2D manifold\n    that has an associated label and is parameterized by two coordinates U and V.\n    Both U and V take values in [0, 1].\n    Thus the results are represented by two tensors:\n    - labels (tensor [H, W] of long): contains estimated label for each pixel of\n        the detection bounding box of size (H, W)\n    - uv (tensor [2, H, W] of float): contains estimated U and V coordinates\n        for each pixel of the detection bounding box of size (H, W)\n    \"\"\"\n\n    labels: torch.Tensor\n    uv: torch.Tensor\n\n    def to(self, device: torch.device):\n        \"\"\"\n        Transfers all tensors to the given device\n        \"\"\"\n        labels = self.labels.to(device)\n        uv = self.uv.to(device)\n        return DensePoseChartResult(labels=labels, uv=uv)\n\n\n@dataclass\nclass DensePoseChartResultWithConfidences:\n    \"\"\"\n    We add confidence values to DensePoseChartResult\n    Thus the results are represented by two tensors:\n    - labels (tensor [H, W] of long): contains estimated label for each pixel of\n        the detection bounding box of size (H, W)\n    - uv (tensor [2, H, W] of float): contains estimated U and V coordinates\n        for each pixel of the detection bounding box of size (H, W)\n    Plus one [H, W] tensor of float for each confidence type\n    \"\"\"\n\n    labels: torch.Tensor\n    uv: torch.Tensor\n    sigma_1: Optional[torch.Tensor] = None\n    sigma_2: Optional[torch.Tensor] = None\n    kappa_u: Optional[torch.Tensor] = None\n    kappa_v: Optional[torch.Tensor] = None\n    fine_segm_confidence: Optional[torch.Tensor] = None\n    coarse_segm_confidence: Optional[torch.Tensor] = None\n\n    def to(self, device: torch.device):\n        \"\"\"\n        Transfers all tensors to the given device, except if their value is None\n        \"\"\"\n\n        def to_device_if_tensor(var: Any):\n            if isinstance(var, torch.Tensor):\n                return var.to(device)\n            return var\n\n        return DensePoseChartResultWithConfidences(\n            labels=self.labels.to(device),\n            uv=self.uv.to(device),\n            sigma_1=to_device_if_tensor(self.sigma_1),\n            sigma_2=to_device_if_tensor(self.sigma_2),\n            kappa_u=to_device_if_tensor(self.kappa_u),\n            kappa_v=to_device_if_tensor(self.kappa_v),\n            fine_segm_confidence=to_device_if_tensor(self.fine_segm_confidence),\n            coarse_segm_confidence=to_device_if_tensor(self.coarse_segm_confidence),\n        )\n\n\n@dataclass\nclass DensePoseChartResultQuantized:\n    \"\"\"\n    DensePose results for chart-based methods represented by labels and quantized\n    inner coordinates (U, V) of individual charts. Each chart is a 2D manifold\n    that has an associated label and is parameterized by two coordinates U and V.\n    Both U and V take values in [0, 1].\n    Quantized coordinates Uq and Vq have uint8 values which are obtained as:\n      Uq = U * 255 (hence 0 <= Uq <= 255)\n      Vq = V * 255 (hence 0 <= Vq <= 255)\n    Thus the results are represented by one tensor:\n    - labels_uv_uint8 (tensor [3, H, W] of uint8): contains estimated label\n        and quantized coordinates Uq and Vq for each pixel of the detection\n        bounding box of size (H, W)\n    \"\"\"\n\n    labels_uv_uint8: torch.Tensor\n\n    def to(self, device: torch.device):\n        \"\"\"\n        Transfers all tensors to the given device\n        \"\"\"\n        labels_uv_uint8 = self.labels_uv_uint8.to(device)\n        return DensePoseChartResultQuantized(labels_uv_uint8=labels_uv_uint8)\n\n\n@dataclass\nclass DensePoseChartResultCompressed:\n    \"\"\"\n    DensePose results for chart-based methods represented by a PNG-encoded string.\n    The tensor of quantized DensePose results of size [3, H, W] is considered\n    as an image with 3 color channels. PNG compression is applied and the result\n    is stored as a Base64-encoded string. The following attributes are defined:\n    - shape_chw (tuple of 3 int): contains shape of the result tensor\n        (number of channels, height, width)\n    - labels_uv_str (str): contains Base64-encoded results tensor of size\n        [3, H, W] compressed with PNG compression methods\n    \"\"\"\n\n    shape_chw: Tuple[int, int, int]\n    labels_uv_str: str\n\n\ndef quantize_densepose_chart_result(result: DensePoseChartResult) -> DensePoseChartResultQuantized:\n    \"\"\"\n    Applies quantization to DensePose chart-based result.\n\n    Args:\n        result (DensePoseChartResult): DensePose chart-based result\n    Return:\n        Quantized DensePose chart-based result (DensePoseChartResultQuantized)\n    \"\"\"\n    h, w = result.labels.shape\n    labels_uv_uint8 = torch.zeros([3, h, w], dtype=torch.uint8, device=result.labels.device)\n    labels_uv_uint8[0] = result.labels\n    labels_uv_uint8[1:] = (result.uv * 255).clamp(0, 255).byte()\n    return DensePoseChartResultQuantized(labels_uv_uint8=labels_uv_uint8)\n\n\ndef compress_quantized_densepose_chart_result(\n    result: DensePoseChartResultQuantized,\n) -> DensePoseChartResultCompressed:\n    \"\"\"\n    Compresses quantized DensePose chart-based result\n\n    Args:\n        result (DensePoseChartResultQuantized): quantized DensePose chart-based result\n    Return:\n        Compressed DensePose chart-based result (DensePoseChartResultCompressed)\n    \"\"\"\n    import base64\n    import numpy as np\n    from io import BytesIO\n    from PIL import Image\n\n    labels_uv_uint8_np_chw = result.labels_uv_uint8.cpu().numpy()\n    labels_uv_uint8_np_hwc = np.moveaxis(labels_uv_uint8_np_chw, 0, -1)\n    im = Image.fromarray(labels_uv_uint8_np_hwc)\n    fstream = BytesIO()\n    im.save(fstream, format=\"png\", optimize=True)\n    labels_uv_str = base64.encodebytes(fstream.getvalue()).decode()\n    shape_chw = labels_uv_uint8_np_chw.shape\n    return DensePoseChartResultCompressed(labels_uv_str=labels_uv_str, shape_chw=shape_chw)\n\n\ndef decompress_compressed_densepose_chart_result(\n    result: DensePoseChartResultCompressed,\n) -> DensePoseChartResultQuantized:\n    \"\"\"\n    Decompresses DensePose chart-based result encoded into a base64 string\n\n    Args:\n        result (DensePoseChartResultCompressed): compressed DensePose chart result\n    Return:\n        Quantized DensePose chart-based result (DensePoseChartResultQuantized)\n    \"\"\"\n    import base64\n    import numpy as np\n    from io import BytesIO\n    from PIL import Image\n\n    fstream = BytesIO(base64.decodebytes(result.labels_uv_str.encode()))\n    im = Image.open(fstream)\n    labels_uv_uint8_np_chw = np.moveaxis(np.array(im, dtype=np.uint8), -1, 0)\n    return DensePoseChartResultQuantized(\n        labels_uv_uint8=torch.from_numpy(labels_uv_uint8_np_chw.reshape(result.shape_chw))\n    )\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/structures/cse.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nfrom dataclasses import dataclass\nfrom typing import Union\nimport torch\n\n\n@dataclass\nclass DensePoseEmbeddingPredictorOutput:\n    \"\"\"\n    Predictor output that contains embedding and coarse segmentation data:\n     * embedding: float tensor of size [N, D, H, W], contains estimated embeddings\n     * coarse_segm: float tensor of size [N, K, H, W]\n    Here D = MODEL.ROI_DENSEPOSE_HEAD.CSE.EMBED_SIZE\n         K = MODEL.ROI_DENSEPOSE_HEAD.NUM_COARSE_SEGM_CHANNELS\n    \"\"\"\n\n    embedding: torch.Tensor\n    coarse_segm: torch.Tensor\n\n    def __len__(self):\n        \"\"\"\n        Number of instances (N) in the output\n        \"\"\"\n        return self.coarse_segm.size(0)\n\n    def __getitem__(\n        self, item: Union[int, slice, torch.BoolTensor]\n    ) -> \"DensePoseEmbeddingPredictorOutput\":\n        \"\"\"\n        Get outputs for the selected instance(s)\n\n        Args:\n            item (int or slice or tensor): selected items\n        \"\"\"\n        if isinstance(item, int):\n            return DensePoseEmbeddingPredictorOutput(\n                coarse_segm=self.coarse_segm[item].unsqueeze(0),\n                embedding=self.embedding[item].unsqueeze(0),\n            )\n        else:\n            return DensePoseEmbeddingPredictorOutput(\n                coarse_segm=self.coarse_segm[item], embedding=self.embedding[item]\n            )\n\n    def to(self, device: torch.device):\n        \"\"\"\n        Transfers all tensors to the given device\n        \"\"\"\n        coarse_segm = self.coarse_segm.to(device)\n        embedding = self.embedding.to(device)\n        return DensePoseEmbeddingPredictorOutput(coarse_segm=coarse_segm, embedding=embedding)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/structures/cse_confidence.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom dataclasses import make_dataclass\nfrom functools import lru_cache\nfrom typing import Any, Optional\nimport torch\n\n\n@lru_cache(maxsize=None)\ndef decorate_cse_predictor_output_class_with_confidences(BasePredictorOutput: type) -> type:\n    \"\"\"\n    Create a new output class from an existing one by adding new attributes\n    related to confidence estimation:\n    - coarse_segm_confidence (tensor)\n\n    Details on confidence estimation parameters can be found in:\n    N. Neverova, D. Novotny, A. Vedaldi \"Correlated Uncertainty for Learning\n        Dense Correspondences from Noisy Labels\", p. 918--926, in Proc. NIPS 2019\n    A. Sanakoyeu et al., Transferring Dense Pose to Proximal Animal Classes, CVPR 2020\n\n    The new class inherits the provided `BasePredictorOutput` class,\n    it's name is composed of the name of the provided class and\n    \"WithConfidences\" suffix.\n\n    Args:\n        BasePredictorOutput (type): output type to which confidence data\n            is to be added, assumed to be a dataclass\n    Return:\n        New dataclass derived from the provided one that has attributes\n        for confidence estimation\n    \"\"\"\n\n    PredictorOutput = make_dataclass(\n        BasePredictorOutput.__name__ + \"WithConfidences\",\n        fields=[  # pyre-ignore[6]\n            (\"coarse_segm_confidence\", Optional[torch.Tensor], None),\n        ],\n        bases=(BasePredictorOutput,),\n    )\n\n    # add possibility to index PredictorOutput\n\n    def slice_if_not_none(data, item):\n        if data is None:\n            return None\n        if isinstance(item, int):\n            return data[item].unsqueeze(0)\n        return data[item]\n\n    def PredictorOutput_getitem(self, item):\n        PredictorOutput = type(self)\n        base_predictor_output_sliced = super(PredictorOutput, self).__getitem__(item)\n        return PredictorOutput(\n            **base_predictor_output_sliced.__dict__,\n            coarse_segm_confidence=slice_if_not_none(self.coarse_segm_confidence, item),\n        )\n\n    PredictorOutput.__getitem__ = PredictorOutput_getitem\n\n    def PredictorOutput_to(self, device: torch.device):\n        \"\"\"\n        Transfers all tensors to the given device\n        \"\"\"\n        PredictorOutput = type(self)\n        base_predictor_output_to = super(PredictorOutput, self).to(device)  # pyre-ignore[16]\n\n        def to_device_if_tensor(var: Any):\n            if isinstance(var, torch.Tensor):\n                return var.to(device)\n            return var\n\n        return PredictorOutput(\n            **base_predictor_output_to.__dict__,\n            coarse_segm_confidence=to_device_if_tensor(self.coarse_segm_confidence),\n        )\n\n    PredictorOutput.to = PredictorOutput_to\n    return PredictorOutput\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/structures/data_relative.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport numpy as np\nimport torch\nfrom torch.nn import functional as F\n\nfrom densepose.data.meshes.catalog import MeshCatalog\nfrom densepose.structures.mesh import load_mesh_symmetry\nfrom densepose.structures.transform_data import DensePoseTransformData\n\n\nclass DensePoseDataRelative(object):\n    \"\"\"\n    Dense pose relative annotations that can be applied to any bounding box:\n        x - normalized X coordinates [0, 255] of annotated points\n        y - normalized Y coordinates [0, 255] of annotated points\n        i - body part labels 0,...,24 for annotated points\n        u - body part U coordinates [0, 1] for annotated points\n        v - body part V coordinates [0, 1] for annotated points\n        segm - 256x256 segmentation mask with values 0,...,14\n    To obtain absolute x and y data wrt some bounding box one needs to first\n    divide the data by 256, multiply by the respective bounding box size\n    and add bounding box offset:\n        x_img = x0 + x_norm * w / 256.0\n        y_img = y0 + y_norm * h / 256.0\n    Segmentation masks are typically sampled to get image-based masks.\n    \"\"\"\n\n    # Key for normalized X coordinates in annotation dict\n    X_KEY = \"dp_x\"\n    # Key for normalized Y coordinates in annotation dict\n    Y_KEY = \"dp_y\"\n    # Key for U part coordinates in annotation dict (used in chart-based annotations)\n    U_KEY = \"dp_U\"\n    # Key for V part coordinates in annotation dict (used in chart-based annotations)\n    V_KEY = \"dp_V\"\n    # Key for I point labels in annotation dict (used in chart-based annotations)\n    I_KEY = \"dp_I\"\n    # Key for segmentation mask in annotation dict\n    S_KEY = \"dp_masks\"\n    # Key for vertex ids (used in continuous surface embeddings annotations)\n    VERTEX_IDS_KEY = \"dp_vertex\"\n    # Key for mesh id (used in continuous surface embeddings annotations)\n    MESH_NAME_KEY = \"ref_model\"\n    # Number of body parts in segmentation masks\n    N_BODY_PARTS = 14\n    # Number of parts in point labels\n    N_PART_LABELS = 24\n    MASK_SIZE = 256\n\n    def __init__(self, annotation, cleanup=False):\n        self.x = torch.as_tensor(annotation[DensePoseDataRelative.X_KEY])\n        self.y = torch.as_tensor(annotation[DensePoseDataRelative.Y_KEY])\n        if (\n            DensePoseDataRelative.I_KEY in annotation\n            and DensePoseDataRelative.U_KEY in annotation\n            and DensePoseDataRelative.V_KEY in annotation\n        ):\n            self.i = torch.as_tensor(annotation[DensePoseDataRelative.I_KEY])\n            self.u = torch.as_tensor(annotation[DensePoseDataRelative.U_KEY])\n            self.v = torch.as_tensor(annotation[DensePoseDataRelative.V_KEY])\n        if (\n            DensePoseDataRelative.VERTEX_IDS_KEY in annotation\n            and DensePoseDataRelative.MESH_NAME_KEY in annotation\n        ):\n            self.vertex_ids = torch.as_tensor(\n                annotation[DensePoseDataRelative.VERTEX_IDS_KEY], dtype=torch.long\n            )\n            self.mesh_id = MeshCatalog.get_mesh_id(annotation[DensePoseDataRelative.MESH_NAME_KEY])\n        if DensePoseDataRelative.S_KEY in annotation:\n            self.segm = DensePoseDataRelative.extract_segmentation_mask(annotation)\n        self.device = torch.device(\"cpu\")\n        if cleanup:\n            DensePoseDataRelative.cleanup_annotation(annotation)\n\n    def to(self, device):\n        if self.device == device:\n            return self\n        new_data = DensePoseDataRelative.__new__(DensePoseDataRelative)\n        new_data.x = self.x.to(device)\n        new_data.y = self.y.to(device)\n        for attr in [\"i\", \"u\", \"v\", \"vertex_ids\", \"segm\"]:\n            if hasattr(self, attr):\n                setattr(new_data, attr, getattr(self, attr).to(device))\n        if hasattr(self, \"mesh_id\"):\n            new_data.mesh_id = self.mesh_id\n        new_data.device = device\n        return new_data\n\n    @staticmethod\n    def extract_segmentation_mask(annotation):\n        import pycocotools.mask as mask_utils\n\n        # TODO: annotation instance is accepted if it contains either\n        # DensePose segmentation or instance segmentation. However, here we\n        # only rely on DensePose segmentation\n        poly_specs = annotation[DensePoseDataRelative.S_KEY]\n        if isinstance(poly_specs, torch.Tensor):\n            # data is already given as mask tensors, no need to decode\n            return poly_specs\n        segm = torch.zeros((DensePoseDataRelative.MASK_SIZE,) * 2, dtype=torch.float32)\n        if isinstance(poly_specs, dict):\n            if poly_specs:\n                mask = mask_utils.decode(poly_specs)\n                segm[mask > 0] = 1\n        else:\n            for i in range(len(poly_specs)):\n                poly_i = poly_specs[i]\n                if poly_i:\n                    mask_i = mask_utils.decode(poly_i)\n                    segm[mask_i > 0] = i + 1\n        return segm\n\n    @staticmethod\n    def validate_annotation(annotation):\n        for key in [\n            DensePoseDataRelative.X_KEY,\n            DensePoseDataRelative.Y_KEY,\n        ]:\n            if key not in annotation:\n                return False, \"no {key} data in the annotation\".format(key=key)\n        valid_for_iuv_setting = all(\n            key in annotation\n            for key in [\n                DensePoseDataRelative.I_KEY,\n                DensePoseDataRelative.U_KEY,\n                DensePoseDataRelative.V_KEY,\n            ]\n        )\n        valid_for_cse_setting = all(\n            key in annotation\n            for key in [\n                DensePoseDataRelative.VERTEX_IDS_KEY,\n                DensePoseDataRelative.MESH_NAME_KEY,\n            ]\n        )\n        if not valid_for_iuv_setting and not valid_for_cse_setting:\n            return (\n                False,\n                \"expected either {} (IUV setting) or {} (CSE setting) annotations\".format(\n                    \", \".join(\n                        [\n                            DensePoseDataRelative.I_KEY,\n                            DensePoseDataRelative.U_KEY,\n                            DensePoseDataRelative.V_KEY,\n                        ]\n                    ),\n                    \", \".join(\n                        [\n                            DensePoseDataRelative.VERTEX_IDS_KEY,\n                            DensePoseDataRelative.MESH_NAME_KEY,\n                        ]\n                    ),\n                ),\n            )\n        return True, None\n\n    @staticmethod\n    def cleanup_annotation(annotation):\n        for key in [\n            DensePoseDataRelative.X_KEY,\n            DensePoseDataRelative.Y_KEY,\n            DensePoseDataRelative.I_KEY,\n            DensePoseDataRelative.U_KEY,\n            DensePoseDataRelative.V_KEY,\n            DensePoseDataRelative.S_KEY,\n            DensePoseDataRelative.VERTEX_IDS_KEY,\n            DensePoseDataRelative.MESH_NAME_KEY,\n        ]:\n            if key in annotation:\n                del annotation[key]\n\n    def apply_transform(self, transforms, densepose_transform_data):\n        self._transform_pts(transforms, densepose_transform_data)\n        if hasattr(self, \"segm\"):\n            self._transform_segm(transforms, densepose_transform_data)\n\n    def _transform_pts(self, transforms, dp_transform_data):\n        import detectron2.data.transforms as T\n\n        # NOTE: This assumes that HorizFlipTransform is the only one that does flip\n        do_hflip = sum(isinstance(t, T.HFlipTransform) for t in transforms.transforms) % 2 == 1\n        if do_hflip:\n            self.x = self.MASK_SIZE - self.x\n            if hasattr(self, \"i\"):\n                self._flip_iuv_semantics(dp_transform_data)\n            if hasattr(self, \"vertex_ids\"):\n                self._flip_vertices()\n\n        for t in transforms.transforms:\n            if isinstance(t, T.RotationTransform):\n                xy_scale = np.array((t.w, t.h)) / DensePoseDataRelative.MASK_SIZE\n                xy = t.apply_coords(np.stack((self.x, self.y), axis=1) * xy_scale)\n                self.x, self.y = torch.tensor(xy / xy_scale, dtype=self.x.dtype).T\n\n    def _flip_iuv_semantics(self, dp_transform_data: DensePoseTransformData) -> None:\n        i_old = self.i.clone()\n        uv_symmetries = dp_transform_data.uv_symmetries\n        pt_label_symmetries = dp_transform_data.point_label_symmetries\n        for i in range(self.N_PART_LABELS):\n            if i + 1 in i_old:\n                annot_indices_i = i_old == i + 1\n                if pt_label_symmetries[i + 1] != i + 1:\n                    self.i[annot_indices_i] = pt_label_symmetries[i + 1]\n                u_loc = (self.u[annot_indices_i] * 255).long()\n                v_loc = (self.v[annot_indices_i] * 255).long()\n                self.u[annot_indices_i] = uv_symmetries[\"U_transforms\"][i][v_loc, u_loc].to(\n                    device=self.u.device\n                )\n                self.v[annot_indices_i] = uv_symmetries[\"V_transforms\"][i][v_loc, u_loc].to(\n                    device=self.v.device\n                )\n\n    def _flip_vertices(self):\n        mesh_info = MeshCatalog[MeshCatalog.get_mesh_name(self.mesh_id)]\n        mesh_symmetry = (\n            load_mesh_symmetry(mesh_info.symmetry) if mesh_info.symmetry is not None else None\n        )\n        self.vertex_ids = mesh_symmetry[\"vertex_transforms\"][self.vertex_ids]\n\n    def _transform_segm(self, transforms, dp_transform_data):\n        import detectron2.data.transforms as T\n\n        # NOTE: This assumes that HorizFlipTransform is the only one that does flip\n        do_hflip = sum(isinstance(t, T.HFlipTransform) for t in transforms.transforms) % 2 == 1\n        if do_hflip:\n            self.segm = torch.flip(self.segm, [1])\n            self._flip_segm_semantics(dp_transform_data)\n\n        for t in transforms.transforms:\n            if isinstance(t, T.RotationTransform):\n                self._transform_segm_rotation(t)\n\n    def _flip_segm_semantics(self, dp_transform_data):\n        old_segm = self.segm.clone()\n        mask_label_symmetries = dp_transform_data.mask_label_symmetries\n        for i in range(self.N_BODY_PARTS):\n            if mask_label_symmetries[i + 1] != i + 1:\n                self.segm[old_segm == i + 1] = mask_label_symmetries[i + 1]\n\n    def _transform_segm_rotation(self, rotation):\n        self.segm = F.interpolate(self.segm[None, None, :], (rotation.h, rotation.w)).numpy()\n        self.segm = torch.tensor(rotation.apply_segmentation(self.segm[0, 0]))[None, None, :]\n        self.segm = F.interpolate(self.segm, [DensePoseDataRelative.MASK_SIZE] * 2)[0, 0]\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/structures/list.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport torch\n\nfrom densepose.structures.data_relative import DensePoseDataRelative\n\n\nclass DensePoseList(object):\n\n    _TORCH_DEVICE_CPU = torch.device(\"cpu\")\n\n    def __init__(self, densepose_datas, boxes_xyxy_abs, image_size_hw, device=_TORCH_DEVICE_CPU):\n        assert len(densepose_datas) == len(\n            boxes_xyxy_abs\n        ), \"Attempt to initialize DensePoseList with {} DensePose datas \" \"and {} boxes\".format(\n            len(densepose_datas), len(boxes_xyxy_abs)\n        )\n        self.densepose_datas = []\n        for densepose_data in densepose_datas:\n            assert isinstance(densepose_data, DensePoseDataRelative) or densepose_data is None, (\n                \"Attempt to initialize DensePoseList with DensePose datas \"\n                \"of type {}, expected DensePoseDataRelative\".format(type(densepose_data))\n            )\n            densepose_data_ondevice = (\n                densepose_data.to(device) if densepose_data is not None else None\n            )\n            self.densepose_datas.append(densepose_data_ondevice)\n        self.boxes_xyxy_abs = boxes_xyxy_abs.to(device)\n        self.image_size_hw = image_size_hw\n        self.device = device\n\n    def to(self, device):\n        if self.device == device:\n            return self\n        return DensePoseList(self.densepose_datas, self.boxes_xyxy_abs, self.image_size_hw, device)\n\n    def __iter__(self):\n        return iter(self.densepose_datas)\n\n    def __len__(self):\n        return len(self.densepose_datas)\n\n    def __repr__(self):\n        s = self.__class__.__name__ + \"(\"\n        s += \"num_instances={}, \".format(len(self.densepose_datas))\n        s += \"image_width={}, \".format(self.image_size_hw[1])\n        s += \"image_height={})\".format(self.image_size_hw[0])\n        return s\n\n    def __getitem__(self, item):\n        if isinstance(item, int):\n            densepose_data_rel = self.densepose_datas[item]\n            return densepose_data_rel\n        elif isinstance(item, slice):\n            densepose_datas_rel = self.densepose_datas[item]\n            boxes_xyxy_abs = self.boxes_xyxy_abs[item]\n            return DensePoseList(\n                densepose_datas_rel, boxes_xyxy_abs, self.image_size_hw, self.device\n            )\n        elif isinstance(item, torch.Tensor) and (item.dtype == torch.bool):\n            densepose_datas_rel = [self.densepose_datas[i] for i, x in enumerate(item) if x > 0]\n            boxes_xyxy_abs = self.boxes_xyxy_abs[item]\n            return DensePoseList(\n                densepose_datas_rel, boxes_xyxy_abs, self.image_size_hw, self.device\n            )\n        else:\n            densepose_datas_rel = [self.densepose_datas[i] for i in item]\n            boxes_xyxy_abs = self.boxes_xyxy_abs[item]\n            return DensePoseList(\n                densepose_datas_rel, boxes_xyxy_abs, self.image_size_hw, self.device\n            )\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/structures/mesh.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nimport pickle\nfrom functools import lru_cache\nfrom typing import Dict, Optional, Tuple\nimport torch\n\nfrom detectron2.utils.file_io import PathManager\n\nfrom densepose.data.meshes.catalog import MeshCatalog, MeshInfo\n\n\ndef _maybe_copy_to_device(\n    attribute: Optional[torch.Tensor], device: torch.device\n) -> Optional[torch.Tensor]:\n    if attribute is None:\n        return None\n    return attribute.to(device)\n\n\nclass Mesh:\n    def __init__(\n        self,\n        vertices: Optional[torch.Tensor] = None,\n        faces: Optional[torch.Tensor] = None,\n        geodists: Optional[torch.Tensor] = None,\n        symmetry: Optional[Dict[str, torch.Tensor]] = None,\n        texcoords: Optional[torch.Tensor] = None,\n        mesh_info: Optional[MeshInfo] = None,\n        device: Optional[torch.device] = None,\n    ):\n        \"\"\"\n        Args:\n            vertices (tensor [N, 3] of float32): vertex coordinates in 3D\n            faces (tensor [M, 3] of long): triangular face represented as 3\n                vertex indices\n            geodists (tensor [N, N] of float32): geodesic distances from\n                vertex `i` to vertex `j` (optional, default: None)\n            symmetry (dict: str -> tensor): various mesh symmetry data:\n                - \"vertex_transforms\": vertex mapping under horizontal flip,\n                  tensor of size [N] of type long; vertex `i` is mapped to\n                  vertex `tensor[i]` (optional, default: None)\n            texcoords (tensor [N, 2] of float32): texture coordinates, i.e. global\n                and normalized mesh UVs (optional, default: None)\n            mesh_info (MeshInfo type): necessary to load the attributes on-the-go,\n                can be used instead of passing all the variables one by one\n            device (torch.device): device of the Mesh. If not provided, will use\n                the device of the vertices\n        \"\"\"\n        self._vertices = vertices\n        self._faces = faces\n        self._geodists = geodists\n        self._symmetry = symmetry\n        self._texcoords = texcoords\n        self.mesh_info = mesh_info\n        self.device = device\n\n        assert self._vertices is not None or self.mesh_info is not None\n\n        all_fields = [self._vertices, self._faces, self._geodists, self._texcoords]\n\n        if self.device is None:\n            for field in all_fields:\n                if field is not None:\n                    self.device = field.device\n                    break\n            if self.device is None and symmetry is not None:\n                for key in symmetry:\n                    self.device = symmetry[key].device\n                    break\n            self.device = torch.device(\"cpu\") if self.device is None else self.device\n\n        assert all([var.device == self.device for var in all_fields if var is not None])\n        if symmetry:\n            assert all(symmetry[key].device == self.device for key in symmetry)\n        if texcoords and vertices:\n            assert len(vertices) == len(texcoords)\n\n    def to(self, device: torch.device):\n        device_symmetry = self._symmetry\n        if device_symmetry:\n            device_symmetry = {key: value.to(device) for key, value in device_symmetry.items()}\n        return Mesh(\n            _maybe_copy_to_device(self._vertices, device),\n            _maybe_copy_to_device(self._faces, device),\n            _maybe_copy_to_device(self._geodists, device),\n            device_symmetry,\n            _maybe_copy_to_device(self._texcoords, device),\n            self.mesh_info,\n            device,\n        )\n\n    @property\n    def vertices(self):\n        if self._vertices is None and self.mesh_info is not None:\n            self._vertices = load_mesh_data(self.mesh_info.data, \"vertices\", self.device)\n        return self._vertices\n\n    @property\n    def faces(self):\n        if self._faces is None and self.mesh_info is not None:\n            self._faces = load_mesh_data(self.mesh_info.data, \"faces\", self.device)\n        return self._faces\n\n    @property\n    def geodists(self):\n        if self._geodists is None and self.mesh_info is not None:\n            self._geodists = load_mesh_auxiliary_data(self.mesh_info.geodists, self.device)\n        return self._geodists\n\n    @property\n    def symmetry(self):\n        if self._symmetry is None and self.mesh_info is not None:\n            self._symmetry = load_mesh_symmetry(self.mesh_info.symmetry, self.device)\n        return self._symmetry\n\n    @property\n    def texcoords(self):\n        if self._texcoords is None and self.mesh_info is not None:\n            self._texcoords = load_mesh_auxiliary_data(self.mesh_info.texcoords, self.device)\n        return self._texcoords\n\n    def get_geodists(self):\n        if self.geodists is None:\n            self.geodists = self._compute_geodists()\n        return self.geodists\n\n    def _compute_geodists(self):\n        # TODO: compute using Laplace-Beltrami\n        geodists = None\n        return geodists\n\n\ndef load_mesh_data(\n    mesh_fpath: str, field: str, device: Optional[torch.device] = None\n) -> Tuple[Optional[torch.Tensor], Optional[torch.Tensor]]:\n    with PathManager.open(mesh_fpath, \"rb\") as hFile:\n        return torch.as_tensor(pickle.load(hFile)[field], dtype=torch.float).to(  # pyre-ignore[6]\n            device\n        )\n    return None\n\n\ndef load_mesh_auxiliary_data(\n    fpath: str, device: Optional[torch.device] = None\n) -> Optional[torch.Tensor]:\n    fpath_local = PathManager.get_local_path(fpath)\n    with PathManager.open(fpath_local, \"rb\") as hFile:\n        return torch.as_tensor(pickle.load(hFile), dtype=torch.float).to(device)  # pyre-ignore[6]\n    return None\n\n\n@lru_cache()\ndef load_mesh_symmetry(\n    symmetry_fpath: str, device: Optional[torch.device] = None\n) -> Optional[Dict[str, torch.Tensor]]:\n    with PathManager.open(symmetry_fpath, \"rb\") as hFile:\n        symmetry_loaded = pickle.load(hFile)  # pyre-ignore[6]\n        symmetry = {\n            \"vertex_transforms\": torch.as_tensor(\n                symmetry_loaded[\"vertex_transforms\"], dtype=torch.long\n            ).to(device),\n        }\n        return symmetry\n    return None\n\n\n@lru_cache()\ndef create_mesh(mesh_name: str, device: Optional[torch.device] = None):\n    return Mesh(mesh_info=MeshCatalog[mesh_name], device=device)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/structures/transform_data.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom typing import BinaryIO, Dict, Union\nimport torch\n\n\ndef normalized_coords_transform(x0, y0, w, h):\n    \"\"\"\n    Coordinates transform that maps top left corner to (-1, -1) and bottom\n    right corner to (1, 1). Used for torch.grid_sample to initialize the\n    grid\n    \"\"\"\n\n    def f(p):\n        return (2 * (p[0] - x0) / w - 1, 2 * (p[1] - y0) / h - 1)\n\n    return f\n\n\nclass DensePoseTransformData(object):\n\n    # Horizontal symmetry label transforms used for horizontal flip\n    MASK_LABEL_SYMMETRIES = [0, 1, 3, 2, 5, 4, 7, 6, 9, 8, 11, 10, 13, 12, 14]\n    # fmt: off\n    POINT_LABEL_SYMMETRIES = [ 0, 1, 2, 4, 3, 6, 5, 8, 7, 10, 9, 12, 11, 14, 13, 16, 15, 18, 17, 20, 19, 22, 21, 24, 23]  # noqa\n    # fmt: on\n\n    def __init__(self, uv_symmetries: Dict[str, torch.Tensor], device: torch.device):\n        self.mask_label_symmetries = DensePoseTransformData.MASK_LABEL_SYMMETRIES\n        self.point_label_symmetries = DensePoseTransformData.POINT_LABEL_SYMMETRIES\n        self.uv_symmetries = uv_symmetries\n        self.device = torch.device(\"cpu\")\n\n    def to(self, device: torch.device, copy: bool = False) -> \"DensePoseTransformData\":\n        \"\"\"\n        Convert transform data to the specified device\n\n        Args:\n            device (torch.device): device to convert the data to\n            copy (bool): flag that specifies whether to copy or to reference the data\n                in case the device is the same\n        Return:\n            An instance of `DensePoseTransformData` with data stored on the specified device\n        \"\"\"\n        if self.device == device and not copy:\n            return self\n        uv_symmetry_map = {}\n        for key in self.uv_symmetries:\n            uv_symmetry_map[key] = self.uv_symmetries[key].to(device=device, copy=copy)\n        return DensePoseTransformData(uv_symmetry_map, device)\n\n    @staticmethod\n    def load(io: Union[str, BinaryIO]):\n        \"\"\"\n        Args:\n            io: (str or binary file-like object): input file to load data from\n        Returns:\n            An instance of `DensePoseTransformData` with transforms loaded from the file\n        \"\"\"\n        import scipy.io\n\n        uv_symmetry_map = scipy.io.loadmat(io)\n        uv_symmetry_map_torch = {}\n        for key in [\"U_transforms\", \"V_transforms\"]:\n            uv_symmetry_map_torch[key] = []\n            map_src = uv_symmetry_map[key]\n            map_dst = uv_symmetry_map_torch[key]\n            for i in range(map_src.shape[1]):\n                map_dst.append(torch.from_numpy(map_src[0, i]).to(dtype=torch.float))\n            uv_symmetry_map_torch[key] = torch.stack(map_dst, dim=0)\n        transform_data = DensePoseTransformData(uv_symmetry_map_torch, device=torch.device(\"cpu\"))\n        return transform_data\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/utils/__init__.py",
    "content": ""
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/utils/dbhelper.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom typing import Any, Dict, Optional, Tuple\n\n\nclass EntrySelector(object):\n    \"\"\"\n    Base class for entry selectors\n    \"\"\"\n\n    @staticmethod\n    def from_string(spec: str) -> \"EntrySelector\":\n        if spec == \"*\":\n            return AllEntrySelector()\n        return FieldEntrySelector(spec)\n\n\nclass AllEntrySelector(EntrySelector):\n    \"\"\"\n    Selector that accepts all entries\n    \"\"\"\n\n    SPECIFIER = \"*\"\n\n    def __call__(self, entry):\n        return True\n\n\nclass FieldEntrySelector(EntrySelector):\n    \"\"\"\n    Selector that accepts only entries that match provided field\n    specifier(s). Only a limited set of specifiers is supported for now:\n      <specifiers>::=<specifier>[<comma><specifiers>]\n      <specifier>::=<field_name>[<type_delim><type>]<equal><value_or_range>\n      <field_name> is a valid identifier\n      <type> ::= \"int\" | \"str\"\n      <equal> ::= \"=\"\n      <comma> ::= \",\"\n      <type_delim> ::= \":\"\n      <value_or_range> ::= <value> | <range>\n      <range> ::= <value><range_delim><value>\n      <range_delim> ::= \"-\"\n      <value> is a string without spaces and special symbols\n        (e.g. <comma>, <equal>, <type_delim>, <range_delim>)\n    \"\"\"\n\n    _SPEC_DELIM = \",\"\n    _TYPE_DELIM = \":\"\n    _RANGE_DELIM = \"-\"\n    _EQUAL = \"=\"\n    _ERROR_PREFIX = \"Invalid field selector specifier\"\n\n    class _FieldEntryValuePredicate(object):\n        \"\"\"\n        Predicate that checks strict equality for the specified entry field\n        \"\"\"\n\n        def __init__(self, name: str, typespec: Optional[str], value: str):\n            import builtins\n\n            self.name = name\n            self.type = getattr(builtins, typespec) if typespec is not None else str\n            self.value = value\n\n        def __call__(self, entry):\n            return entry[self.name] == self.type(self.value)\n\n    class _FieldEntryRangePredicate(object):\n        \"\"\"\n        Predicate that checks whether an entry field falls into the specified range\n        \"\"\"\n\n        def __init__(self, name: str, typespec: Optional[str], vmin: str, vmax: str):\n            import builtins\n\n            self.name = name\n            self.type = getattr(builtins, typespec) if typespec is not None else str\n            self.vmin = vmin\n            self.vmax = vmax\n\n        def __call__(self, entry):\n            return (entry[self.name] >= self.type(self.vmin)) and (\n                entry[self.name] <= self.type(self.vmax)\n            )\n\n    def __init__(self, spec: str):\n        self._predicates = self._parse_specifier_into_predicates(spec)\n\n    def __call__(self, entry: Dict[str, Any]):\n        for predicate in self._predicates:\n            if not predicate(entry):\n                return False\n        return True\n\n    def _parse_specifier_into_predicates(self, spec: str):\n        predicates = []\n        specs = spec.split(self._SPEC_DELIM)\n        for subspec in specs:\n            eq_idx = subspec.find(self._EQUAL)\n            if eq_idx > 0:\n                field_name_with_type = subspec[:eq_idx]\n                field_name, field_type = self._parse_field_name_type(field_name_with_type)\n                field_value_or_range = subspec[eq_idx + 1 :]\n                if self._is_range_spec(field_value_or_range):\n                    vmin, vmax = self._get_range_spec(field_value_or_range)\n                    predicate = FieldEntrySelector._FieldEntryRangePredicate(\n                        field_name, field_type, vmin, vmax\n                    )\n                else:\n                    predicate = FieldEntrySelector._FieldEntryValuePredicate(\n                        field_name, field_type, field_value_or_range\n                    )\n                predicates.append(predicate)\n            elif eq_idx == 0:\n                self._parse_error(f'\"{subspec}\", field name is empty!')\n            else:\n                self._parse_error(f'\"{subspec}\", should have format ' \"<field>=<value_or_range>!\")\n        return predicates\n\n    def _parse_field_name_type(self, field_name_with_type: str) -> Tuple[str, Optional[str]]:\n        type_delim_idx = field_name_with_type.find(self._TYPE_DELIM)\n        if type_delim_idx > 0:\n            field_name = field_name_with_type[:type_delim_idx]\n            field_type = field_name_with_type[type_delim_idx + 1 :]\n        elif type_delim_idx == 0:\n            self._parse_error(f'\"{field_name_with_type}\", field name is empty!')\n        else:\n            field_name = field_name_with_type\n            field_type = None\n        # pyre-fixme[61]: `field_name` may not be initialized here.\n        # pyre-fixme[61]: `field_type` may not be initialized here.\n        return field_name, field_type\n\n    def _is_range_spec(self, field_value_or_range):\n        delim_idx = field_value_or_range.find(self._RANGE_DELIM)\n        return delim_idx > 0\n\n    def _get_range_spec(self, field_value_or_range):\n        if self._is_range_spec(field_value_or_range):\n            delim_idx = field_value_or_range.find(self._RANGE_DELIM)\n            vmin = field_value_or_range[:delim_idx]\n            vmax = field_value_or_range[delim_idx + 1 :]\n            return vmin, vmax\n        else:\n            self._parse_error('\"field_value_or_range\", range of values expected!')\n\n    def _parse_error(self, msg):\n        raise ValueError(f\"{self._ERROR_PREFIX}: {msg}\")\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/utils/logger.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport logging\n\n\ndef verbosity_to_level(verbosity):\n    if verbosity is not None:\n        if verbosity == 0:\n            return logging.WARNING\n        elif verbosity == 1:\n            return logging.INFO\n        elif verbosity >= 2:\n            return logging.DEBUG\n    return logging.WARNING\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/utils/transform.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom detectron2.data import MetadataCatalog\nfrom detectron2.utils.file_io import PathManager\n\nfrom densepose import DensePoseTransformData\n\n\ndef load_for_dataset(dataset_name):\n    path = MetadataCatalog.get(dataset_name).densepose_transform_src\n    densepose_transform_data_fpath = PathManager.get_local_path(path)\n    return DensePoseTransformData.load(densepose_transform_data_fpath)\n\n\ndef load_from_cfg(cfg):\n    return load_for_dataset(cfg.DATASETS.TEST[0])\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/vis/__init__.py",
    "content": ""
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/vis/base.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport logging\nimport numpy as np\nimport cv2\nimport torch\n\nImage = np.ndarray\nBoxes = torch.Tensor\n\n\nclass MatrixVisualizer(object):\n    \"\"\"\n    Base visualizer for matrix data\n    \"\"\"\n\n    def __init__(\n        self,\n        inplace=True,\n        cmap=cv2.COLORMAP_PARULA,\n        val_scale=1.0,\n        alpha=0.7,\n        interp_method_matrix=cv2.INTER_LINEAR,\n        interp_method_mask=cv2.INTER_NEAREST,\n    ):\n        self.inplace = inplace\n        self.cmap = cmap\n        self.val_scale = val_scale\n        self.alpha = alpha\n        self.interp_method_matrix = interp_method_matrix\n        self.interp_method_mask = interp_method_mask\n\n    def visualize(self, image_bgr, mask, matrix, bbox_xywh):\n        self._check_image(image_bgr)\n        self._check_mask_matrix(mask, matrix)\n        if self.inplace:\n            image_target_bgr = image_bgr\n        else:\n            image_target_bgr = image_bgr * 0\n        x, y, w, h = [int(v) for v in bbox_xywh]\n        if w <= 0 or h <= 0:\n            return image_bgr\n        mask, matrix = self._resize(mask, matrix, w, h)\n        mask_bg = np.tile((mask == 0)[:, :, np.newaxis], [1, 1, 3])\n        matrix_scaled = matrix.astype(np.float32) * self.val_scale\n        _EPSILON = 1e-6\n        if np.any(matrix_scaled > 255 + _EPSILON):\n            logger = logging.getLogger(__name__)\n            logger.warning(\n                f\"Matrix has values > {255 + _EPSILON} after \" f\"scaling, clipping to [0..255]\"\n            )\n        matrix_scaled_8u = matrix_scaled.clip(0, 255).astype(np.uint8)\n        matrix_vis = cv2.applyColorMap(matrix_scaled_8u, self.cmap)\n        matrix_vis[mask_bg] = image_target_bgr[y : y + h, x : x + w, :][mask_bg]\n        image_target_bgr[y : y + h, x : x + w, :] = (\n            image_target_bgr[y : y + h, x : x + w, :] * (1.0 - self.alpha) + matrix_vis * self.alpha\n        )\n        return image_target_bgr.astype(np.uint8)\n\n    def _resize(self, mask, matrix, w, h):\n        if (w != mask.shape[1]) or (h != mask.shape[0]):\n            mask = cv2.resize(mask, (w, h), self.interp_method_mask)\n        if (w != matrix.shape[1]) or (h != matrix.shape[0]):\n            matrix = cv2.resize(matrix, (w, h), self.interp_method_matrix)\n        return mask, matrix\n\n    def _check_image(self, image_rgb):\n        assert len(image_rgb.shape) == 3\n        assert image_rgb.shape[2] == 3\n        assert image_rgb.dtype == np.uint8\n\n    def _check_mask_matrix(self, mask, matrix):\n        assert len(matrix.shape) == 2\n        assert len(mask.shape) == 2\n        assert mask.dtype == np.uint8\n\n\nclass RectangleVisualizer(object):\n\n    _COLOR_GREEN = (18, 127, 15)\n\n    def __init__(self, color=_COLOR_GREEN, thickness=1):\n        self.color = color\n        self.thickness = thickness\n\n    def visualize(self, image_bgr, bbox_xywh, color=None, thickness=None):\n        x, y, w, h = bbox_xywh\n        color = color or self.color\n        thickness = thickness or self.thickness\n        cv2.rectangle(image_bgr, (int(x), int(y)), (int(x + w), int(y + h)), color, thickness)\n        return image_bgr\n\n\nclass PointsVisualizer(object):\n\n    _COLOR_GREEN = (18, 127, 15)\n\n    def __init__(self, color_bgr=_COLOR_GREEN, r=5):\n        self.color_bgr = color_bgr\n        self.r = r\n\n    def visualize(self, image_bgr, pts_xy, colors_bgr=None, rs=None):\n        for j, pt_xy in enumerate(pts_xy):\n            x, y = pt_xy\n            color_bgr = colors_bgr[j] if colors_bgr is not None else self.color_bgr\n            r = rs[j] if rs is not None else self.r\n            cv2.circle(image_bgr, (x, y), r, color_bgr, -1)\n        return image_bgr\n\n\nclass TextVisualizer(object):\n\n    _COLOR_GRAY = (218, 227, 218)\n    _COLOR_WHITE = (255, 255, 255)\n\n    def __init__(\n        self,\n        font_face=cv2.FONT_HERSHEY_SIMPLEX,\n        font_color_bgr=_COLOR_GRAY,\n        font_scale=0.35,\n        font_line_type=cv2.LINE_AA,\n        font_line_thickness=1,\n        fill_color_bgr=_COLOR_WHITE,\n        fill_color_transparency=1.0,\n        frame_color_bgr=_COLOR_WHITE,\n        frame_color_transparency=1.0,\n        frame_thickness=1,\n    ):\n        self.font_face = font_face\n        self.font_color_bgr = font_color_bgr\n        self.font_scale = font_scale\n        self.font_line_type = font_line_type\n        self.font_line_thickness = font_line_thickness\n        self.fill_color_bgr = fill_color_bgr\n        self.fill_color_transparency = fill_color_transparency\n        self.frame_color_bgr = frame_color_bgr\n        self.frame_color_transparency = frame_color_transparency\n        self.frame_thickness = frame_thickness\n\n    def visualize(self, image_bgr, txt, topleft_xy):\n        txt_w, txt_h = self.get_text_size_wh(txt)\n        topleft_xy = tuple(map(int, topleft_xy))\n        x, y = topleft_xy\n        if self.frame_color_transparency < 1.0:\n            t = self.frame_thickness\n            image_bgr[y - t : y + txt_h + t, x - t : x + txt_w + t, :] = (\n                image_bgr[y - t : y + txt_h + t, x - t : x + txt_w + t, :]\n                * self.frame_color_transparency\n                + np.array(self.frame_color_bgr) * (1.0 - self.frame_color_transparency)\n            ).astype(np.float)\n        if self.fill_color_transparency < 1.0:\n            image_bgr[y : y + txt_h, x : x + txt_w, :] = (\n                image_bgr[y : y + txt_h, x : x + txt_w, :] * self.fill_color_transparency\n                + np.array(self.fill_color_bgr) * (1.0 - self.fill_color_transparency)\n            ).astype(np.float)\n        cv2.putText(\n            image_bgr,\n            txt,\n            topleft_xy,\n            self.font_face,\n            self.font_scale,\n            self.font_color_bgr,\n            self.font_line_thickness,\n            self.font_line_type,\n        )\n        return image_bgr\n\n    def get_text_size_wh(self, txt):\n        ((txt_w, txt_h), _) = cv2.getTextSize(\n            txt, self.font_face, self.font_scale, self.font_line_thickness\n        )\n        return txt_w, txt_h\n\n\nclass CompoundVisualizer(object):\n    def __init__(self, visualizers):\n        self.visualizers = visualizers\n\n    def visualize(self, image_bgr, data):\n        assert len(data) == len(\n            self.visualizers\n        ), \"The number of datas {} should match the number of visualizers\" \" {}\".format(\n            len(data), len(self.visualizers)\n        )\n        image = image_bgr\n        for i, visualizer in enumerate(self.visualizers):\n            image = visualizer.visualize(image, data[i])\n        return image\n\n    def __str__(self):\n        visualizer_str = \", \".join([str(v) for v in self.visualizers])\n        return \"Compound Visualizer [{}]\".format(visualizer_str)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/vis/bounding_box.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom .base import RectangleVisualizer, TextVisualizer\n\n\nclass BoundingBoxVisualizer(object):\n    def __init__(self):\n        self.rectangle_visualizer = RectangleVisualizer()\n\n    def visualize(self, image_bgr, boxes_xywh):\n        for bbox_xywh in boxes_xywh:\n            image_bgr = self.rectangle_visualizer.visualize(image_bgr, bbox_xywh)\n        return image_bgr\n\n\nclass ScoredBoundingBoxVisualizer(object):\n    def __init__(self, bbox_visualizer_params=None, score_visualizer_params=None, **kwargs):\n        if bbox_visualizer_params is None:\n            bbox_visualizer_params = {}\n        if score_visualizer_params is None:\n            score_visualizer_params = {}\n        self.visualizer_bbox = RectangleVisualizer(**bbox_visualizer_params)\n        self.visualizer_score = TextVisualizer(**score_visualizer_params)\n\n    def visualize(self, image_bgr, scored_bboxes):\n        boxes_xywh, box_scores = scored_bboxes\n        assert len(boxes_xywh) == len(\n            box_scores\n        ), \"Number of bounding boxes {} should be equal to the number of scores {}\".format(\n            len(boxes_xywh), len(box_scores)\n        )\n        for i, box_xywh in enumerate(boxes_xywh):\n            score_i = box_scores[i]\n            image_bgr = self.visualizer_bbox.visualize(image_bgr, box_xywh)\n            score_txt = \"{0:6.4f}\".format(score_i)\n            topleft_xy = box_xywh[0], box_xywh[1]\n            image_bgr = self.visualizer_score.visualize(image_bgr, score_txt, topleft_xy)\n        return image_bgr\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/vis/densepose_data_points.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport numpy as np\nfrom typing import Iterable, Optional, Tuple\nimport cv2\n\nfrom densepose.structures import DensePoseDataRelative\n\nfrom .base import Boxes, Image, MatrixVisualizer, PointsVisualizer\n\n\nclass DensePoseDataCoarseSegmentationVisualizer(object):\n    \"\"\"\n    Visualizer for ground truth segmentation\n    \"\"\"\n\n    def __init__(self, inplace=True, cmap=cv2.COLORMAP_PARULA, alpha=0.7, **kwargs):\n        self.mask_visualizer = MatrixVisualizer(\n            inplace=inplace,\n            cmap=cmap,\n            val_scale=255.0 / DensePoseDataRelative.N_BODY_PARTS,\n            alpha=alpha,\n        )\n\n    def visualize(\n        self,\n        image_bgr: Image,\n        bbox_densepose_datas: Optional[Tuple[Iterable[Boxes], Iterable[DensePoseDataRelative]]],\n    ) -> Image:\n        if bbox_densepose_datas is None:\n            return image_bgr\n        for bbox_xywh, densepose_data in zip(*bbox_densepose_datas):\n            matrix = densepose_data.segm.numpy()\n            mask = np.zeros(matrix.shape, dtype=np.uint8)\n            mask[matrix > 0] = 1\n            image_bgr = self.mask_visualizer.visualize(image_bgr, mask, matrix, bbox_xywh.numpy())\n        return image_bgr\n\n\nclass DensePoseDataPointsVisualizer(object):\n    def __init__(self, densepose_data_to_value_fn=None, cmap=cv2.COLORMAP_PARULA, **kwargs):\n        self.points_visualizer = PointsVisualizer()\n        self.densepose_data_to_value_fn = densepose_data_to_value_fn\n        self.cmap = cmap\n\n    def visualize(\n        self,\n        image_bgr: Image,\n        bbox_densepose_datas: Optional[Tuple[Iterable[Boxes], Iterable[DensePoseDataRelative]]],\n    ) -> Image:\n        if bbox_densepose_datas is None:\n            return image_bgr\n        for bbox_xywh, densepose_data in zip(*bbox_densepose_datas):\n            x0, y0, w, h = bbox_xywh.numpy()\n            x = densepose_data.x.numpy() * w / 255.0 + x0\n            y = densepose_data.y.numpy() * h / 255.0 + y0\n            pts_xy = zip(x, y)\n            if self.densepose_data_to_value_fn is None:\n                image_bgr = self.points_visualizer.visualize(image_bgr, pts_xy)\n            else:\n                v = self.densepose_data_to_value_fn(densepose_data)\n                img_colors_bgr = cv2.applyColorMap(v, self.cmap)\n                colors_bgr = [\n                    [int(v) for v in img_color_bgr.ravel()] for img_color_bgr in img_colors_bgr\n                ]\n                image_bgr = self.points_visualizer.visualize(image_bgr, pts_xy, colors_bgr)\n        return image_bgr\n\n\ndef _densepose_data_u_for_cmap(densepose_data):\n    u = np.clip(densepose_data.u.numpy(), 0, 1) * 255.0\n    return u.astype(np.uint8)\n\n\ndef _densepose_data_v_for_cmap(densepose_data):\n    v = np.clip(densepose_data.v.numpy(), 0, 1) * 255.0\n    return v.astype(np.uint8)\n\n\ndef _densepose_data_i_for_cmap(densepose_data):\n    i = (\n        np.clip(densepose_data.i.numpy(), 0.0, DensePoseDataRelative.N_PART_LABELS)\n        * 255.0\n        / DensePoseDataRelative.N_PART_LABELS\n    )\n    return i.astype(np.uint8)\n\n\nclass DensePoseDataPointsUVisualizer(DensePoseDataPointsVisualizer):\n    def __init__(self, **kwargs):\n        super(DensePoseDataPointsUVisualizer, self).__init__(\n            densepose_data_to_value_fn=_densepose_data_u_for_cmap, **kwargs\n        )\n\n\nclass DensePoseDataPointsVVisualizer(DensePoseDataPointsVisualizer):\n    def __init__(self, **kwargs):\n        super(DensePoseDataPointsVVisualizer, self).__init__(\n            densepose_data_to_value_fn=_densepose_data_v_for_cmap, **kwargs\n        )\n\n\nclass DensePoseDataPointsIVisualizer(DensePoseDataPointsVisualizer):\n    def __init__(self, **kwargs):\n        super(DensePoseDataPointsIVisualizer, self).__init__(\n            densepose_data_to_value_fn=_densepose_data_i_for_cmap, **kwargs\n        )\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/vis/densepose_outputs_iuv.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport numpy as np\nfrom typing import Optional, Tuple\nimport cv2\n\nfrom densepose.structures import DensePoseDataRelative\n\nfrom ..structures import DensePoseChartPredictorOutput\nfrom .base import Boxes, Image, MatrixVisualizer\n\n\nclass DensePoseOutputsVisualizer(object):\n    def __init__(\n        self, inplace=True, cmap=cv2.COLORMAP_PARULA, alpha=0.7, to_visualize=None, **kwargs\n    ):\n        assert to_visualize in \"IUV\", \"can only visualize IUV\"\n        self.to_visualize = to_visualize\n\n        if self.to_visualize == \"I\":\n            val_scale = 255.0 / DensePoseDataRelative.N_PART_LABELS\n        else:\n            val_scale = 1.0\n        self.mask_visualizer = MatrixVisualizer(\n            inplace=inplace, cmap=cmap, val_scale=val_scale, alpha=alpha\n        )\n\n    def visualize(\n        self,\n        image_bgr: Image,\n        dp_output_with_bboxes: Tuple[Optional[DensePoseChartPredictorOutput], Optional[Boxes]],\n    ) -> Image:\n        densepose_output, bboxes_xywh = dp_output_with_bboxes\n        if densepose_output is None or bboxes_xywh is None:\n            return image_bgr\n\n        assert isinstance(\n            densepose_output, DensePoseChartPredictorOutput\n        ), \"DensePoseChartPredictorOutput expected, {} encountered\".format(type(densepose_output))\n\n        S = densepose_output.coarse_segm\n        I = densepose_output.fine_segm  # noqa\n        U = densepose_output.u\n        V = densepose_output.v\n        N = S.size(0)\n        assert N == I.size(\n            0\n        ), \"densepose outputs S {} and I {}\" \" should have equal first dim size\".format(\n            S.size(), I.size()\n        )\n        assert N == U.size(\n            0\n        ), \"densepose outputs S {} and U {}\" \" should have equal first dim size\".format(\n            S.size(), U.size()\n        )\n        assert N == V.size(\n            0\n        ), \"densepose outputs S {} and V {}\" \" should have equal first dim size\".format(\n            S.size(), V.size()\n        )\n        assert N == len(\n            bboxes_xywh\n        ), \"number of bounding boxes {}\" \" should be equal to first dim size of outputs {}\".format(\n            len(bboxes_xywh), N\n        )\n        for n in range(N):\n            Sn = S[n].argmax(dim=0)\n            In = I[n].argmax(dim=0) * (Sn > 0).long()\n            segmentation = In.cpu().numpy().astype(np.uint8)\n            mask = np.zeros(segmentation.shape, dtype=np.uint8)\n            mask[segmentation > 0] = 1\n            bbox_xywh = bboxes_xywh[n]\n\n            if self.to_visualize == \"I\":\n                vis = segmentation\n            elif self.to_visualize in \"UV\":\n                U_or_Vn = {\"U\": U, \"V\": V}[self.to_visualize][n].cpu().numpy().astype(np.float32)\n                vis = np.zeros(segmentation.shape, dtype=np.float32)\n                for partId in range(U_or_Vn.shape[0]):\n                    vis[segmentation == partId] = (\n                        U_or_Vn[partId][segmentation == partId].clip(0, 1) * 255\n                    )\n\n            # pyre-fixme[61]: `vis` may not be initialized here.\n            image_bgr = self.mask_visualizer.visualize(image_bgr, mask, vis, bbox_xywh)\n\n        return image_bgr\n\n\nclass DensePoseOutputsUVisualizer(DensePoseOutputsVisualizer):\n    def __init__(self, inplace=True, cmap=cv2.COLORMAP_PARULA, alpha=0.7, **kwargs):\n        super().__init__(inplace=inplace, cmap=cmap, alpha=alpha, to_visualize=\"U\", **kwargs)\n\n\nclass DensePoseOutputsVVisualizer(DensePoseOutputsVisualizer):\n    def __init__(self, inplace=True, cmap=cv2.COLORMAP_PARULA, alpha=0.7, **kwargs):\n        super().__init__(inplace=inplace, cmap=cmap, alpha=alpha, to_visualize=\"V\", **kwargs)\n\n\nclass DensePoseOutputsFineSegmentationVisualizer(DensePoseOutputsVisualizer):\n    def __init__(self, inplace=True, cmap=cv2.COLORMAP_PARULA, alpha=0.7, **kwargs):\n        super().__init__(inplace=inplace, cmap=cmap, alpha=alpha, to_visualize=\"I\", **kwargs)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/vis/densepose_outputs_vertex.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\nimport json\nimport numpy as np\nfrom functools import lru_cache\nfrom typing import Dict, List, Optional, Tuple\nimport cv2\nimport torch\n\nfrom detectron2.utils.file_io import PathManager\n\nfrom densepose.modeling import build_densepose_embedder\nfrom densepose.modeling.cse.utils import get_closest_vertices_mask_from_ES\n\nfrom ..data.utils import get_class_to_mesh_name_mapping\nfrom ..structures import DensePoseEmbeddingPredictorOutput\nfrom ..structures.mesh import create_mesh\nfrom .base import Boxes, Image, MatrixVisualizer\nfrom .densepose_results_textures import get_texture_atlas\n\n\n@lru_cache()\ndef get_xyz_vertex_embedding(mesh_name: str, device: torch.device):\n    if mesh_name == \"smpl_27554\":\n        embed_path = PathManager.get_local_path(\n            \"https://dl.fbaipublicfiles.com/densepose/data/cse/mds_d=256.npy\"\n        )\n        embed_map, _ = np.load(embed_path, allow_pickle=True)\n        embed_map = torch.tensor(embed_map).float()[:, 0]\n        embed_map -= embed_map.min()\n        embed_map /= embed_map.max()\n    else:\n        mesh = create_mesh(mesh_name, device)\n        embed_map = mesh.vertices.sum(dim=1)\n        embed_map -= embed_map.min()\n        embed_map /= embed_map.max()\n        embed_map = embed_map ** 2\n    return embed_map\n\n\nclass DensePoseOutputsVertexVisualizer(object):\n    def __init__(\n        self,\n        cfg,\n        inplace=True,\n        cmap=cv2.COLORMAP_JET,\n        alpha=0.7,\n        device=\"cuda\",\n        default_class=0,\n        **kwargs,\n    ):\n        self.mask_visualizer = MatrixVisualizer(\n            inplace=inplace, cmap=cmap, val_scale=1.0, alpha=alpha\n        )\n        self.class_to_mesh_name = get_class_to_mesh_name_mapping(cfg)\n        self.embedder = build_densepose_embedder(cfg)\n        self.device = torch.device(device)\n        self.default_class = default_class\n\n        self.mesh_vertex_embeddings = {\n            mesh_name: self.embedder(mesh_name).to(self.device)\n            for mesh_name in self.class_to_mesh_name.values()\n            if self.embedder.has_embeddings(mesh_name)\n        }\n\n    def visualize(\n        self,\n        image_bgr: Image,\n        outputs_boxes_xywh_classes: Tuple[\n            Optional[DensePoseEmbeddingPredictorOutput], Optional[Boxes], Optional[List[int]]\n        ],\n    ) -> Image:\n        if outputs_boxes_xywh_classes[0] is None:\n            return image_bgr\n\n        S, E, N, bboxes_xywh, pred_classes = self.extract_and_check_outputs_and_boxes(\n            outputs_boxes_xywh_classes\n        )\n\n        for n in range(N):\n            x, y, w, h = bboxes_xywh[n].int().tolist()\n            mesh_name = self.class_to_mesh_name[pred_classes[n]]\n            closest_vertices, mask = get_closest_vertices_mask_from_ES(\n                E[[n]],\n                S[[n]],\n                h,\n                w,\n                self.mesh_vertex_embeddings[mesh_name],\n                self.device,\n            )\n            embed_map = get_xyz_vertex_embedding(mesh_name, self.device)\n            vis = (embed_map[closest_vertices].clip(0, 1) * 255.0).cpu().numpy()\n            mask_numpy = mask.cpu().numpy().astype(dtype=np.uint8)\n            image_bgr = self.mask_visualizer.visualize(image_bgr, mask_numpy, vis, [x, y, w, h])\n\n        return image_bgr\n\n    def extract_and_check_outputs_and_boxes(self, outputs_boxes_xywh_classes):\n\n        densepose_output, bboxes_xywh, pred_classes = outputs_boxes_xywh_classes\n\n        if pred_classes is None:\n            pred_classes = [self.default_class] * len(bboxes_xywh)\n\n        assert isinstance(\n            densepose_output, DensePoseEmbeddingPredictorOutput\n        ), \"DensePoseEmbeddingPredictorOutput expected, {} encountered\".format(\n            type(densepose_output)\n        )\n\n        S = densepose_output.coarse_segm\n        E = densepose_output.embedding\n        N = S.size(0)\n        assert N == E.size(\n            0\n        ), \"CSE coarse_segm {} and embeddings {}\" \" should have equal first dim size\".format(\n            S.size(), E.size()\n        )\n        assert N == len(\n            bboxes_xywh\n        ), \"number of bounding boxes {}\" \" should be equal to first dim size of outputs {}\".format(\n            len(bboxes_xywh), N\n        )\n        assert N == len(pred_classes), (\n            \"number of predicted classes {}\"\n            \" should be equal to first dim size of outputs {}\".format(len(bboxes_xywh), N)\n        )\n\n        return S, E, N, bboxes_xywh, pred_classes\n\n\ndef get_texture_atlases(json_str: Optional[str]) -> Optional[Dict[str, Optional[np.ndarray]]]:\n    \"\"\"\n    json_str is a JSON string representing a mesh_name -> texture_atlas_path dictionary\n    \"\"\"\n    if json_str is None:\n        return None\n\n    paths = json.loads(json_str)\n    return {mesh_name: get_texture_atlas(path) for mesh_name, path in paths.items()}\n\n\nclass DensePoseOutputsTextureVisualizer(DensePoseOutputsVertexVisualizer):\n    def __init__(\n        self,\n        cfg,\n        texture_atlases_dict,\n        device=\"cuda\",\n        default_class=0,\n        **kwargs,\n    ):\n        self.embedder = build_densepose_embedder(cfg)\n\n        self.texture_image_dict = {}\n        self.alpha_dict = {}\n\n        for mesh_name in texture_atlases_dict.keys():\n            if texture_atlases_dict[mesh_name].shape[-1] == 4:  # Image with alpha channel\n                self.alpha_dict[mesh_name] = texture_atlases_dict[mesh_name][:, :, -1] / 255.0\n                self.texture_image_dict[mesh_name] = texture_atlases_dict[mesh_name][:, :, :3]\n            else:\n                self.alpha_dict[mesh_name] = texture_atlases_dict[mesh_name].sum(axis=-1) > 0\n                self.texture_image_dict[mesh_name] = texture_atlases_dict[mesh_name]\n\n        self.device = torch.device(device)\n        self.class_to_mesh_name = get_class_to_mesh_name_mapping(cfg)\n        self.default_class = default_class\n\n        self.mesh_vertex_embeddings = {\n            mesh_name: self.embedder(mesh_name).to(self.device)\n            for mesh_name in self.class_to_mesh_name.values()\n        }\n\n    def visualize(\n        self,\n        image_bgr: Image,\n        outputs_boxes_xywh_classes: Tuple[\n            Optional[DensePoseEmbeddingPredictorOutput], Optional[Boxes], Optional[List[int]]\n        ],\n    ) -> Image:\n        image_target_bgr = image_bgr.copy()\n        if outputs_boxes_xywh_classes[0] is None:\n            return image_target_bgr\n\n        S, E, N, bboxes_xywh, pred_classes = self.extract_and_check_outputs_and_boxes(\n            outputs_boxes_xywh_classes\n        )\n\n        meshes = {\n            p: create_mesh(self.class_to_mesh_name[p], self.device) for p in np.unique(pred_classes)\n        }\n\n        for n in range(N):\n            x, y, w, h = bboxes_xywh[n].int().cpu().numpy()\n            mesh_name = self.class_to_mesh_name[pred_classes[n]]\n            closest_vertices, mask = get_closest_vertices_mask_from_ES(\n                E[[n]],\n                S[[n]],\n                h,\n                w,\n                self.mesh_vertex_embeddings[mesh_name],\n                self.device,\n            )\n            uv_array = meshes[pred_classes[n]].texcoords[closest_vertices].permute((2, 0, 1))\n            uv_array = uv_array.cpu().numpy().clip(0, 1)\n            textured_image = self.generate_image_with_texture(\n                image_target_bgr[y : y + h, x : x + w],\n                uv_array,\n                mask.cpu().numpy(),\n                self.class_to_mesh_name[pred_classes[n]],\n            )\n            if textured_image is None:\n                continue\n            image_target_bgr[y : y + h, x : x + w] = textured_image\n\n        return image_target_bgr\n\n    def generate_image_with_texture(self, bbox_image_bgr, uv_array, mask, mesh_name):\n        alpha = self.alpha_dict.get(mesh_name)\n        texture_image = self.texture_image_dict.get(mesh_name)\n        if alpha is None or texture_image is None:\n            return None\n        U, V = uv_array\n        x_index = (U * texture_image.shape[1]).astype(int)\n        y_index = (V * texture_image.shape[0]).astype(int)\n        local_texture = texture_image[y_index, x_index][mask]\n        local_alpha = np.expand_dims(alpha[y_index, x_index][mask], -1)\n        output_image = bbox_image_bgr.copy()\n        output_image[mask] = output_image[mask] * (1 - local_alpha) + local_texture * local_alpha\n        return output_image.astype(np.uint8)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/vis/densepose_results.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport logging\nimport numpy as np\nfrom typing import List, Optional, Tuple\nimport cv2\nimport torch\n\nfrom densepose.structures import DensePoseDataRelative\n\nfrom ..structures import DensePoseChartResult\nfrom .base import Boxes, Image, MatrixVisualizer\n\n\nclass DensePoseResultsVisualizer(object):\n    def visualize(\n        self,\n        image_bgr: Image,\n        results_and_boxes_xywh: Tuple[Optional[List[DensePoseChartResult]], Optional[Boxes]],\n    ) -> Image:\n        densepose_result, boxes_xywh = results_and_boxes_xywh\n        if densepose_result is None or boxes_xywh is None:\n            return image_bgr\n\n        boxes_xywh = boxes_xywh.cpu().numpy()\n        context = self.create_visualization_context(image_bgr)\n        for i, result in enumerate(densepose_result):\n            iuv_array = torch.cat(\n                (result.labels[None].type(torch.float32), result.uv * 255.0)\n            ).type(torch.uint8)\n            self.visualize_iuv_arr(context, iuv_array.cpu().numpy(), boxes_xywh[i])\n        image_bgr = self.context_to_image_bgr(context)\n        return image_bgr\n\n    def create_visualization_context(self, image_bgr: Image):\n        return image_bgr\n\n    def visualize_iuv_arr(self, context, iuv_arr: np.ndarray, bbox_xywh) -> None:\n        pass\n\n    def context_to_image_bgr(self, context):\n        return context\n\n    def get_image_bgr_from_context(self, context):\n        return context\n\n\nclass DensePoseMaskedColormapResultsVisualizer(DensePoseResultsVisualizer):\n    def __init__(\n        self,\n        data_extractor,\n        segm_extractor,\n        inplace=True,\n        cmap=cv2.COLORMAP_PARULA,\n        alpha=0.7,\n        val_scale=1.0,\n        **kwargs,\n    ):\n        self.mask_visualizer = MatrixVisualizer(\n            inplace=inplace, cmap=cmap, val_scale=val_scale, alpha=alpha\n        )\n        self.data_extractor = data_extractor\n        self.segm_extractor = segm_extractor\n\n    def context_to_image_bgr(self, context):\n        return context\n\n    def visualize_iuv_arr(self, context, iuv_arr: np.ndarray, bbox_xywh) -> None:\n        image_bgr = self.get_image_bgr_from_context(context)\n        matrix = self.data_extractor(iuv_arr)\n        segm = self.segm_extractor(iuv_arr)\n        mask = np.zeros(matrix.shape, dtype=np.uint8)\n        mask[segm > 0] = 1\n        image_bgr = self.mask_visualizer.visualize(image_bgr, mask, matrix, bbox_xywh)\n\n\ndef _extract_i_from_iuvarr(iuv_arr):\n    return iuv_arr[0, :, :]\n\n\ndef _extract_u_from_iuvarr(iuv_arr):\n    return iuv_arr[1, :, :]\n\n\ndef _extract_v_from_iuvarr(iuv_arr):\n    return iuv_arr[2, :, :]\n\n\nclass DensePoseResultsMplContourVisualizer(DensePoseResultsVisualizer):\n    def __init__(self, levels=10, **kwargs):\n        self.levels = levels\n        self.plot_args = kwargs\n\n    def create_visualization_context(self, image_bgr: Image):\n        import matplotlib.pyplot as plt\n        from matplotlib.backends.backend_agg import FigureCanvasAgg as FigureCanvas\n\n        context = {}\n        context[\"image_bgr\"] = image_bgr\n        dpi = 100\n        height_inches = float(image_bgr.shape[0]) / dpi\n        width_inches = float(image_bgr.shape[1]) / dpi\n        fig = plt.figure(figsize=(width_inches, height_inches), dpi=dpi)\n        plt.axes([0, 0, 1, 1])\n        plt.axis(\"off\")\n        context[\"fig\"] = fig\n        canvas = FigureCanvas(fig)\n        context[\"canvas\"] = canvas\n        extent = (0, image_bgr.shape[1], image_bgr.shape[0], 0)\n        plt.imshow(image_bgr[:, :, ::-1], extent=extent)\n        return context\n\n    def context_to_image_bgr(self, context):\n        fig = context[\"fig\"]\n        w, h = map(int, fig.get_size_inches() * fig.get_dpi())\n        canvas = context[\"canvas\"]\n        canvas.draw()\n        image_1d = np.fromstring(canvas.tostring_rgb(), dtype=\"uint8\")\n        image_rgb = image_1d.reshape(h, w, 3)\n        image_bgr = image_rgb[:, :, ::-1].copy()\n        return image_bgr\n\n    def visualize_iuv_arr(self, context, iuv_arr: np.ndarray, bbox_xywh: Boxes) -> None:\n        import matplotlib.pyplot as plt\n\n        u = _extract_u_from_iuvarr(iuv_arr).astype(float) / 255.0\n        v = _extract_v_from_iuvarr(iuv_arr).astype(float) / 255.0\n        extent = (\n            bbox_xywh[0],\n            bbox_xywh[0] + bbox_xywh[2],\n            bbox_xywh[1],\n            bbox_xywh[1] + bbox_xywh[3],\n        )\n        plt.contour(u, self.levels, extent=extent, **self.plot_args)\n        plt.contour(v, self.levels, extent=extent, **self.plot_args)\n\n\nclass DensePoseResultsCustomContourVisualizer(DensePoseResultsVisualizer):\n    \"\"\"\n    Contour visualization using marching squares\n    \"\"\"\n\n    def __init__(self, levels=10, **kwargs):\n        # TODO: colormap is hardcoded\n        cmap = cv2.COLORMAP_PARULA\n        if isinstance(levels, int):\n            self.levels = np.linspace(0, 1, levels)\n        else:\n            self.levels = levels\n        if \"linewidths\" in kwargs:\n            self.linewidths = kwargs[\"linewidths\"]\n        else:\n            self.linewidths = [1] * len(self.levels)\n        self.plot_args = kwargs\n        img_colors_bgr = cv2.applyColorMap((self.levels * 255).astype(np.uint8), cmap)\n        self.level_colors_bgr = [\n            [int(v) for v in img_color_bgr.ravel()] for img_color_bgr in img_colors_bgr\n        ]\n\n    def visualize_iuv_arr(self, context, iuv_arr: np.ndarray, bbox_xywh: Boxes) -> None:\n        image_bgr = self.get_image_bgr_from_context(context)\n        segm = _extract_i_from_iuvarr(iuv_arr)\n        u = _extract_u_from_iuvarr(iuv_arr).astype(float) / 255.0\n        v = _extract_v_from_iuvarr(iuv_arr).astype(float) / 255.0\n        self._contours(image_bgr, u, segm, bbox_xywh)\n        self._contours(image_bgr, v, segm, bbox_xywh)\n\n    def _contours(self, image_bgr, arr, segm, bbox_xywh):\n        for part_idx in range(1, DensePoseDataRelative.N_PART_LABELS + 1):\n            mask = segm == part_idx\n            if not np.any(mask):\n                continue\n            arr_min = np.amin(arr[mask])\n            arr_max = np.amax(arr[mask])\n            I, J = np.nonzero(mask)\n            i0 = np.amin(I)\n            i1 = np.amax(I) + 1\n            j0 = np.amin(J)\n            j1 = np.amax(J) + 1\n            if (j1 == j0 + 1) or (i1 == i0 + 1):\n                continue\n            Nw = arr.shape[1] - 1\n            Nh = arr.shape[0] - 1\n            for level_idx, level in enumerate(self.levels):\n                if (level < arr_min) or (level > arr_max):\n                    continue\n                vp = arr[i0:i1, j0:j1] >= level\n                bin_codes = vp[:-1, :-1] + vp[1:, :-1] * 2 + vp[1:, 1:] * 4 + vp[:-1, 1:] * 8\n                mp = mask[i0:i1, j0:j1]\n                bin_mask_codes = mp[:-1, :-1] + mp[1:, :-1] * 2 + mp[1:, 1:] * 4 + mp[:-1, 1:] * 8\n                it = np.nditer(bin_codes, flags=[\"multi_index\"])\n                color_bgr = self.level_colors_bgr[level_idx]\n                linewidth = self.linewidths[level_idx]\n                while not it.finished:\n                    if (it[0] != 0) and (it[0] != 15):\n                        i, j = it.multi_index\n                        if bin_mask_codes[i, j] != 0:\n                            self._draw_line(\n                                image_bgr,\n                                arr,\n                                mask,\n                                level,\n                                color_bgr,\n                                linewidth,\n                                it[0],\n                                it.multi_index,\n                                bbox_xywh,\n                                Nw,\n                                Nh,\n                                (i0, j0),\n                            )\n                    it.iternext()\n\n    def _draw_line(\n        self,\n        image_bgr,\n        arr,\n        mask,\n        v,\n        color_bgr,\n        linewidth,\n        bin_code,\n        multi_idx,\n        bbox_xywh,\n        Nw,\n        Nh,\n        offset,\n    ):\n        lines = self._bin_code_2_lines(arr, v, bin_code, multi_idx, Nw, Nh, offset)\n        x0, y0, w, h = bbox_xywh\n        x1 = x0 + w\n        y1 = y0 + h\n        for line in lines:\n            x0r, y0r = line[0]\n            x1r, y1r = line[1]\n            pt0 = (int(x0 + x0r * (x1 - x0)), int(y0 + y0r * (y1 - y0)))\n            pt1 = (int(x0 + x1r * (x1 - x0)), int(y0 + y1r * (y1 - y0)))\n            cv2.line(image_bgr, pt0, pt1, color_bgr, linewidth)\n\n    def _bin_code_2_lines(self, arr, v, bin_code, multi_idx, Nw, Nh, offset):\n        i0, j0 = offset\n        i, j = multi_idx\n        i += i0\n        j += j0\n        v0, v1, v2, v3 = arr[i, j], arr[i + 1, j], arr[i + 1, j + 1], arr[i, j + 1]\n        x0i = float(j) / Nw\n        y0j = float(i) / Nh\n        He = 1.0 / Nh\n        We = 1.0 / Nw\n        if (bin_code == 1) or (bin_code == 14):\n            a = (v - v0) / (v1 - v0)\n            b = (v - v0) / (v3 - v0)\n            pt1 = (x0i, y0j + a * He)\n            pt2 = (x0i + b * We, y0j)\n            return [(pt1, pt2)]\n        elif (bin_code == 2) or (bin_code == 13):\n            a = (v - v0) / (v1 - v0)\n            b = (v - v1) / (v2 - v1)\n            pt1 = (x0i, y0j + a * He)\n            pt2 = (x0i + b * We, y0j + He)\n            return [(pt1, pt2)]\n        elif (bin_code == 3) or (bin_code == 12):\n            a = (v - v0) / (v3 - v0)\n            b = (v - v1) / (v2 - v1)\n            pt1 = (x0i + a * We, y0j)\n            pt2 = (x0i + b * We, y0j + He)\n            return [(pt1, pt2)]\n        elif (bin_code == 4) or (bin_code == 11):\n            a = (v - v1) / (v2 - v1)\n            b = (v - v3) / (v2 - v3)\n            pt1 = (x0i + a * We, y0j + He)\n            pt2 = (x0i + We, y0j + b * He)\n            return [(pt1, pt2)]\n        elif (bin_code == 6) or (bin_code == 9):\n            a = (v - v0) / (v1 - v0)\n            b = (v - v3) / (v2 - v3)\n            pt1 = (x0i, y0j + a * He)\n            pt2 = (x0i + We, y0j + b * He)\n            return [(pt1, pt2)]\n        elif (bin_code == 7) or (bin_code == 8):\n            a = (v - v0) / (v3 - v0)\n            b = (v - v3) / (v2 - v3)\n            pt1 = (x0i + a * We, y0j)\n            pt2 = (x0i + We, y0j + b * He)\n            return [(pt1, pt2)]\n        elif bin_code == 5:\n            a1 = (v - v0) / (v1 - v0)\n            b1 = (v - v1) / (v2 - v1)\n            pt11 = (x0i, y0j + a1 * He)\n            pt12 = (x0i + b1 * We, y0j + He)\n            a2 = (v - v0) / (v3 - v0)\n            b2 = (v - v3) / (v2 - v3)\n            pt21 = (x0i + a2 * We, y0j)\n            pt22 = (x0i + We, y0j + b2 * He)\n            return [(pt11, pt12), (pt21, pt22)]\n        elif bin_code == 10:\n            a1 = (v - v0) / (v3 - v0)\n            b1 = (v - v0) / (v1 - v0)\n            pt11 = (x0i + a1 * We, y0j)\n            pt12 = (x0i, y0j + b1 * He)\n            a2 = (v - v1) / (v2 - v1)\n            b2 = (v - v3) / (v2 - v3)\n            pt21 = (x0i + a2 * We, y0j + He)\n            pt22 = (x0i + We, y0j + b2 * He)\n            return [(pt11, pt12), (pt21, pt22)]\n        return []\n\n\ntry:\n    import matplotlib\n\n    matplotlib.use(\"Agg\")\n    DensePoseResultsContourVisualizer = DensePoseResultsMplContourVisualizer\nexcept ModuleNotFoundError:\n    logger = logging.getLogger(__name__)\n    logger.warning(\"Could not import matplotlib, using custom contour visualizer\")\n    DensePoseResultsContourVisualizer = DensePoseResultsCustomContourVisualizer\n\n\nclass DensePoseResultsFineSegmentationVisualizer(DensePoseMaskedColormapResultsVisualizer):\n    def __init__(self, inplace=True, cmap=cv2.COLORMAP_PARULA, alpha=0.7, **kwargs):\n        super(DensePoseResultsFineSegmentationVisualizer, self).__init__(\n            _extract_i_from_iuvarr,\n            _extract_i_from_iuvarr,\n            inplace,\n            cmap,\n            alpha,\n            val_scale=255.0 / DensePoseDataRelative.N_PART_LABELS,\n            **kwargs,\n        )\n\n\nclass DensePoseResultsUVisualizer(DensePoseMaskedColormapResultsVisualizer):\n    def __init__(self, inplace=True, cmap=cv2.COLORMAP_PARULA, alpha=0.7, **kwargs):\n        super(DensePoseResultsUVisualizer, self).__init__(\n            _extract_u_from_iuvarr,\n            _extract_i_from_iuvarr,\n            inplace,\n            cmap,\n            alpha,\n            val_scale=1.0,\n            **kwargs,\n        )\n\n\nclass DensePoseResultsVVisualizer(DensePoseMaskedColormapResultsVisualizer):\n    def __init__(self, inplace=True, cmap=cv2.COLORMAP_PARULA, alpha=0.7, **kwargs):\n        super(DensePoseResultsVVisualizer, self).__init__(\n            _extract_v_from_iuvarr,\n            _extract_i_from_iuvarr,\n            inplace,\n            cmap,\n            alpha,\n            val_scale=1.0,\n            **kwargs,\n        )\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/vis/densepose_results_textures.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport numpy as np\nfrom typing import List, Optional, Tuple\nimport torch\n\nfrom detectron2.data.detection_utils import read_image\n\nfrom ..structures import DensePoseChartResult\nfrom .base import Boxes, Image\nfrom .densepose_results import DensePoseResultsVisualizer\n\n\ndef get_texture_atlas(path: Optional[str]) -> Optional[np.ndarray]:\n    if path is None:\n        return None\n\n    # Reading images like that downsamples 16-bit images to 8-bit\n    # If 16-bit images are needed, we can replace that by cv2.imread with the\n    # cv2.IMREAD_UNCHANGED flag (with cv2 we also need it to keep alpha channels)\n    # The rest of the pipeline would need to be adapted to 16-bit images too\n    bgr_image = read_image(path)\n    rgb_image = np.copy(bgr_image)  # Convert BGR -> RGB\n    rgb_image[:, :, :3] = rgb_image[:, :, 2::-1]  # Works with alpha channel\n    return rgb_image\n\n\nclass DensePoseResultsVisualizerWithTexture(DensePoseResultsVisualizer):\n    \"\"\"\n    texture_atlas: An image, size 6N * 4N, with N * N squares for each of the 24 body parts.\n            It must follow the grid found at https://github.com/facebookresearch/DensePose/blob/master/DensePoseData/demo_data/texture_atlas_200.png  # noqa\n            For each body part, U is proportional to the x coordinate, and (1 - V) to y\n    \"\"\"\n\n    def __init__(self, texture_atlas, **kwargs):\n        self.texture_atlas = texture_atlas\n        self.body_part_size = texture_atlas.shape[0] // 6\n        assert self.body_part_size == texture_atlas.shape[1] // 4\n\n    def visualize(\n        self,\n        image_bgr: Image,\n        results_and_boxes_xywh: Tuple[Optional[List[DensePoseChartResult]], Optional[Boxes]],\n    ) -> Image:\n        densepose_result, boxes_xywh = results_and_boxes_xywh\n        if densepose_result is None or boxes_xywh is None:\n            return image_bgr\n\n        boxes_xywh = boxes_xywh.int().cpu().numpy()\n        texture_image, alpha = self.get_texture()\n        for i, result in enumerate(densepose_result):\n            iuv_array = torch.cat((result.labels[None], result.uv.clamp(0, 1)))\n            x, y, w, h = boxes_xywh[i]\n            bbox_image = image_bgr[y : y + h, x : x + w]\n            image_bgr[y : y + h, x : x + w] = self.generate_image_with_texture(\n                texture_image, alpha, bbox_image, iuv_array.cpu().numpy()\n            )\n        return image_bgr\n\n    def get_texture(self):\n        N = self.body_part_size\n        texture_image = np.zeros([24, N, N, self.texture_atlas.shape[-1]])\n        for i in range(4):\n            for j in range(6):\n                texture_image[(6 * i + j), :, :, :] = self.texture_atlas[\n                    N * j : N * (j + 1), N * i : N * (i + 1), :\n                ]\n\n        if texture_image.shape[-1] == 4:  # Image with alpha channel\n            alpha = texture_image[:, :, :, -1] / 255.0\n            texture_image = texture_image[:, :, :, :3]\n        else:\n            alpha = texture_image.sum(axis=-1) > 0\n\n        return texture_image, alpha\n\n    def generate_image_with_texture(self, texture_image, alpha, bbox_image_bgr, iuv_array):\n\n        I, U, V = iuv_array\n        generated_image_bgr = bbox_image_bgr.copy()\n\n        for PartInd in range(1, 25):\n            x, y = np.where(I == PartInd)\n            x_index = (U[x, y] * (self.body_part_size - 1)).astype(int)\n            y_index = ((1 - V[x, y]) * (self.body_part_size - 1)).astype(int)\n            part_alpha = np.expand_dims(alpha[PartInd - 1, y_index, x_index], -1)\n            generated_image_bgr[I == PartInd] = (\n                generated_image_bgr[I == PartInd] * (1 - part_alpha)\n                + texture_image[PartInd - 1, y_index, x_index] * part_alpha\n            )\n\n        return generated_image_bgr.astype(np.uint8)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/densepose/vis/extractor.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport logging\nfrom typing import List, Optional, Sequence, Tuple\nimport torch\n\nfrom detectron2.layers.nms import batched_nms\nfrom detectron2.structures.instances import Instances\n\nfrom densepose.converters import ToChartResultConverterWithConfidences\nfrom densepose.structures import (\n    DensePoseChartResultWithConfidences,\n    DensePoseEmbeddingPredictorOutput,\n)\nfrom densepose.vis.bounding_box import BoundingBoxVisualizer, ScoredBoundingBoxVisualizer\nfrom densepose.vis.densepose_outputs_vertex import DensePoseOutputsVertexVisualizer\nfrom densepose.vis.densepose_results import DensePoseResultsVisualizer\n\nfrom .base import CompoundVisualizer\n\nScores = Sequence[float]\nDensePoseChartResultsWithConfidences = List[DensePoseChartResultWithConfidences]\n\n\ndef extract_scores_from_instances(instances: Instances, select=None):\n    if instances.has(\"scores\"):\n        return instances.scores if select is None else instances.scores[select]\n    return None\n\n\ndef extract_boxes_xywh_from_instances(instances: Instances, select=None):\n    if instances.has(\"pred_boxes\"):\n        boxes_xywh = instances.pred_boxes.tensor.clone()\n        boxes_xywh[:, 2] -= boxes_xywh[:, 0]\n        boxes_xywh[:, 3] -= boxes_xywh[:, 1]\n        return boxes_xywh if select is None else boxes_xywh[select]\n    return None\n\n\ndef create_extractor(visualizer: object):\n    \"\"\"\n    Create an extractor for the provided visualizer\n    \"\"\"\n    if isinstance(visualizer, CompoundVisualizer):\n        extractors = [create_extractor(v) for v in visualizer.visualizers]\n        return CompoundExtractor(extractors)\n    elif isinstance(visualizer, DensePoseResultsVisualizer):\n        return DensePoseResultExtractor()\n    elif isinstance(visualizer, ScoredBoundingBoxVisualizer):\n        return CompoundExtractor([extract_boxes_xywh_from_instances, extract_scores_from_instances])\n    elif isinstance(visualizer, BoundingBoxVisualizer):\n        return extract_boxes_xywh_from_instances\n    elif isinstance(visualizer, DensePoseOutputsVertexVisualizer):\n        return DensePoseOutputsExtractor()\n    else:\n        logger = logging.getLogger(__name__)\n        logger.error(f\"Could not create extractor for {visualizer}\")\n        return None\n\n\nclass BoundingBoxExtractor(object):\n    \"\"\"\n    Extracts bounding boxes from instances\n    \"\"\"\n\n    def __call__(self, instances: Instances):\n        boxes_xywh = extract_boxes_xywh_from_instances(instances)\n        return boxes_xywh\n\n\nclass ScoredBoundingBoxExtractor(object):\n    \"\"\"\n    Extracts bounding boxes from instances\n    \"\"\"\n\n    def __call__(self, instances: Instances, select=None):\n        scores = extract_scores_from_instances(instances)\n        boxes_xywh = extract_boxes_xywh_from_instances(instances)\n        if (scores is None) or (boxes_xywh is None):\n            return (boxes_xywh, scores)\n        if select is not None:\n            scores = scores[select]\n            boxes_xywh = boxes_xywh[select]\n        return (boxes_xywh, scores)\n\n\nclass DensePoseResultExtractor(object):\n    \"\"\"\n    Extracts DensePose chart result with confidences from instances\n    \"\"\"\n\n    def __call__(\n        self, instances: Instances, select=None\n    ) -> Tuple[Optional[DensePoseChartResultsWithConfidences], Optional[torch.Tensor]]:\n        if instances.has(\"pred_densepose\") and instances.has(\"pred_boxes\"):\n            dpout = instances.pred_densepose\n            boxes_xyxy = instances.pred_boxes\n            boxes_xywh = extract_boxes_xywh_from_instances(instances)\n            if select is not None:\n                dpout = dpout[select]\n                boxes_xyxy = boxes_xyxy[select]\n            converter = ToChartResultConverterWithConfidences()\n            results = [converter.convert(dpout[i], boxes_xyxy[[i]]) for i in range(len(dpout))]\n            return results, boxes_xywh\n        else:\n            return None, None\n\n\nclass DensePoseOutputsExtractor(object):\n    \"\"\"\n    Extracts DensePose result from instances\n    \"\"\"\n\n    def __call__(\n        self,\n        instances: Instances,\n        select=None,\n    ) -> Tuple[\n        Optional[DensePoseEmbeddingPredictorOutput], Optional[torch.Tensor], Optional[List[int]]\n    ]:\n        if not (instances.has(\"pred_densepose\") and instances.has(\"pred_boxes\")):\n            return None, None, None\n\n        dpout = instances.pred_densepose\n        boxes_xyxy = instances.pred_boxes\n        boxes_xywh = extract_boxes_xywh_from_instances(instances)\n\n        if instances.has(\"pred_classes\"):\n            classes = instances.pred_classes.tolist()\n        else:\n            classes = None\n\n        if select is not None:\n            dpout = dpout[select]\n            boxes_xyxy = boxes_xyxy[select]\n            if classes is not None:\n                classes = classes[select]\n\n        return dpout, boxes_xywh, classes\n\n\nclass CompoundExtractor(object):\n    \"\"\"\n    Extracts data for CompoundVisualizer\n    \"\"\"\n\n    def __init__(self, extractors):\n        self.extractors = extractors\n\n    def __call__(self, instances: Instances, select=None):\n        datas = []\n        for extractor in self.extractors:\n            data = extractor(instances, select)\n            datas.append(data)\n        return datas\n\n\nclass NmsFilteredExtractor(object):\n    \"\"\"\n    Extracts data in the format accepted by NmsFilteredVisualizer\n    \"\"\"\n\n    def __init__(self, extractor, iou_threshold):\n        self.extractor = extractor\n        self.iou_threshold = iou_threshold\n\n    def __call__(self, instances: Instances, select=None):\n        scores = extract_scores_from_instances(instances)\n        boxes_xywh = extract_boxes_xywh_from_instances(instances)\n        if boxes_xywh is None:\n            return None\n        select_local_idx = batched_nms(\n            boxes_xywh,\n            scores,\n            torch.zeros(len(scores), dtype=torch.int32),\n            iou_threshold=self.iou_threshold,\n        ).squeeze()\n        select_local = torch.zeros(len(boxes_xywh), dtype=torch.bool, device=boxes_xywh.device)\n        select_local[select_local_idx] = True\n        select = select_local if select is None else (select & select_local)\n        return self.extractor(instances, select=select)\n\n\nclass ScoreThresholdedExtractor(object):\n    \"\"\"\n    Extracts data in the format accepted by ScoreThresholdedVisualizer\n    \"\"\"\n\n    def __init__(self, extractor, min_score):\n        self.extractor = extractor\n        self.min_score = min_score\n\n    def __call__(self, instances: Instances, select=None):\n        scores = extract_scores_from_instances(instances)\n        if scores is None:\n            return None\n        select_local = scores > self.min_score\n        select = select_local if select is None else (select & select_local)\n        data = self.extractor(instances, select=select)\n        return data\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/dev/README.md",
    "content": "\n## Some scripts for developers to use, include:\n\n- `run_instant_tests.sh`: run training for a few iterations.\n- `run_inference_tests.sh`: run inference on a small dataset.\n- `../../dev/linter.sh`: lint the codebase before commit\n- `../../dev/parse_results.sh`: parse results from log file.\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/dev/run_inference_tests.sh",
    "content": "#!/bin/bash -e\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nBIN=\"python train_net.py\"\nOUTPUT=\"inference_test_output\"\nNUM_GPUS=2\nIMS_PER_GPU=2\nIMS_PER_BATCH=$(( NUM_GPUS * IMS_PER_GPU ))\n\nCFG_LIST=( \"${@:1}\" )\n\nif [ ${#CFG_LIST[@]} -eq 0 ]; then\n  CFG_LIST=( ./configs/quick_schedules/*inference_acc_test.yaml )\nfi\n\necho \"========================================================================\"\necho \"Configs to run:\"\necho \"${CFG_LIST[@]}\"\necho \"========================================================================\"\n\nfor cfg in \"${CFG_LIST[@]}\"; do\n    echo \"========================================================================\"\n    echo \"Running $cfg ...\"\n    echo \"========================================================================\"\n    $BIN \\\n      --eval-only \\\n      --num-gpus $NUM_GPUS \\\n      --config-file \"$cfg\" \\\n      OUTPUT_DIR \"$OUTPUT\" \\\n      SOLVER.IMS_PER_BATCH $IMS_PER_BATCH\n    rm -rf $OUTPUT\ndone\n\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/dev/run_instant_tests.sh",
    "content": "#!/bin/bash -e\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nBIN=\"python train_net.py\"\nOUTPUT=\"instant_test_output\"\nNUM_GPUS=2\nSOLVER_IMS_PER_BATCH=$((NUM_GPUS * 2))\n\nCFG_LIST=( \"${@:1}\" )\nif [ ${#CFG_LIST[@]} -eq 0 ]; then\n  CFG_LIST=( ./configs/quick_schedules/*instant_test.yaml )\nfi\n\necho \"========================================================================\"\necho \"Configs to run:\"\necho \"${CFG_LIST[@]}\"\necho \"========================================================================\"\n\nfor cfg in \"${CFG_LIST[@]}\"; do\n    echo \"========================================================================\"\n    echo \"Running $cfg ...\"\n    echo \"========================================================================\"\n    $BIN --num-gpus $NUM_GPUS --config-file \"$cfg\" \\\n      SOLVER.IMS_PER_BATCH $SOLVER_IMS_PER_BATCH \\\n      OUTPUT_DIR \"$OUTPUT\"\n    rm -rf \"$OUTPUT\"\ndone\n\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/doc/BOOTSTRAPPING_PIPELINE.md",
    "content": "# Bootstrapping Pipeline\n\nBootstrapping pipeline for DensePose was proposed in\n[Sanakoyeu et al., 2020](https://arxiv.org/pdf/2003.00080.pdf)\nto extend DensePose from humans to proximal animal classes\n(chimpanzees). Currently, the pipeline is only implemented for\n[chart-based models](DENSEPOSE_IUV.md).\nBootstrapping proceeds in two steps.\n\n## Master Model Training\n\nMaster model is trained on data from source domain (humans)\nand supporting domain (animals). Instances from the source domain\ncontain full DensePose annotations (`S`, `I`, `U` and `V`) and\ninstances from the supporting domain have segmentation annotations only.\nTo ensure segmentation quality in the target domain, only a subset of\nsupporting domain classes is included into the training. This is achieved\nthrough category filters, e.g.\n(see [configs/evolution/Base-RCNN-FPN-Atop10P_CA.yaml](../configs/evolution/Base-RCNN-FPN-Atop10P_CA.yaml)):\n\n```\n  WHITELISTED_CATEGORIES:\n    \"base_coco_2017_train\":\n      - 1  # person\n      - 16 # bird\n      - 17 # cat\n      - 18 # dog\n      - 19 # horse\n      - 20 # sheep\n      - 21 # cow\n      - 22 # elephant\n      - 23 # bear\n      - 24 # zebra\n      - 25 # girafe\n```\nThe acronym `Atop10P` in config file names indicates that categories are filtered to\nonly contain top 10 animals and person.\n\nThe training is performed in a *class-agnostic* manner: all instances\nare mapped into the same class (person), e.g.\n(see [configs/evolution/Base-RCNN-FPN-Atop10P_CA.yaml](../configs/evolution/Base-RCNN-FPN-Atop10P_CA.yaml)):\n\n```\n  CATEGORY_MAPS:\n    \"base_coco_2017_train\":\n      \"16\": 1 # bird -> person\n      \"17\": 1 # cat -> person\n      \"18\": 1 # dog -> person\n      \"19\": 1 # horse -> person\n      \"20\": 1 # sheep -> person\n      \"21\": 1 # cow -> person\n      \"22\": 1 # elephant -> person\n      \"23\": 1 # bear -> person\n      \"24\": 1 # zebra -> person\n      \"25\": 1 # girafe -> person\n```\nThe acronym `CA` in config file names indicates that the training is class-agnostic.\n\n## Student Model Training\n\nStudent model is trained on data from source domain (humans),\nsupporting domain (animals) and target domain (chimpanzees).\nAnnotations in source and supporting domains are similar to the ones\nused for the master model training.\nAnnotations in target domain are obtained by applying the master model\nto images that contain instances from the target category and sampling\nsparse annotations from dense results. This process is called *bootstrapping*.\nBelow we give details on how the bootstrapping pipeline is implemented.\n\n### Data Loaders\n\nThe central components that enable bootstrapping are\n[`InferenceBasedLoader`](../densepose/data/inference_based_loader.py) and\n[`CombinedDataLoader`](../densepose/data/combined_loader.py).\n\n`InferenceBasedLoader` takes images from a data loader, applies a model\nto the images, filters the model outputs based on the selected criteria and\nsamples the filtered outputs to produce annotations.\n\n`CombinedDataLoader` combines data obtained from the loaders based on specified\nratios. The standard data loader has the default ratio of 1.0,\nratios for bootstrap datasets are specified in the configuration file.\nThe higher the ratio the higher the probability to include samples from the\nparticular data loader into a batch.\n\nHere is an example of the bootstrapping configuration taken from\n[`configs/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_uniform.yaml`](../configs/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_uniform.yaml):\n```\nBOOTSTRAP_DATASETS:\n  - DATASET: \"chimpnsee\"\n    RATIO: 1.0\n    IMAGE_LOADER:\n      TYPE: \"video_keyframe\"\n      SELECT:\n        STRATEGY: \"random_k\"\n        NUM_IMAGES: 4\n      TRANSFORM:\n        TYPE: \"resize\"\n        MIN_SIZE: 800\n        MAX_SIZE: 1333\n      BATCH_SIZE: 8\n      NUM_WORKERS: 1\n    INFERENCE:\n      INPUT_BATCH_SIZE: 1\n      OUTPUT_BATCH_SIZE: 1\n    DATA_SAMPLER:\n      # supported types:\n      #   densepose_uniform\n      #   densepose_UV_confidence\n      #   densepose_fine_segm_confidence\n      #   densepose_coarse_segm_confidence\n      TYPE: \"densepose_uniform\"\n      COUNT_PER_CLASS: 8\n    FILTER:\n      TYPE: \"detection_score\"\n      MIN_VALUE: 0.8\nBOOTSTRAP_MODEL:\n  WEIGHTS: https://dl.fbaipublicfiles.com/densepose/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA/217578784/model_final_9fe1cc.pkl\n```\n\nThe above example has one bootstrap dataset (`chimpnsee`). This dataset is registered as\na [VIDEO_LIST](../densepose/data/datasets/chimpnsee.py) dataset, which means that\nit consists of a number of videos specified in a text file. For videos there can be\ndifferent strategies to sample individual images. Here we use `video_keyframe` strategy\nwhich considers only keyframes; this ensures temporal offset between sampled images and\nfaster seek operations. We select at most 4 random keyframes in each video:\n\n```\nSELECT:\n  STRATEGY: \"random_k\"\n  NUM_IMAGES: 4\n```\n\nThe frames are then resized\n\n```\nTRANSFORM:\n  TYPE: \"resize\"\n  MIN_SIZE: 800\n  MAX_SIZE: 1333\n```\n\nand batched using the standard\n[PyTorch DataLoader](https://pytorch.org/docs/stable/data.html#torch.utils.data.DataLoader):\n\n```\nBATCH_SIZE: 8\nNUM_WORKERS: 1\n```\n\n`InferenceBasedLoader` decomposes those batches into batches of size `INPUT_BATCH_SIZE`\nand applies the master model specified by `BOOTSTRAP_MODEL`. Models outputs are filtered\nby detection score:\n\n```\nFILTER:\n  TYPE: \"detection_score\"\n  MIN_VALUE: 0.8\n```\n\nand sampled using the specified sampling strategy:\n\n```\nDATA_SAMPLER:\n  # supported types:\n  #   densepose_uniform\n  #   densepose_UV_confidence\n  #   densepose_fine_segm_confidence\n  #   densepose_coarse_segm_confidence\n  TYPE: \"densepose_uniform\"\n  COUNT_PER_CLASS: 8\n```\n\nThe current implementation supports\n[uniform sampling](../densepose/data/samplers/densepose_uniform.py) and\n[confidence-based sampling](../densepose/data/samplers/densepose_confidence_based.py)\nto obtain sparse annotations from dense results. For confidence-based\nsampling one needs to use the master model which produces confidence estimates.\nThe `WC1M` master model used in the example above produces all three types of confidence\nestimates.\n\nFinally, sampled data is grouped into batches of size `OUTPUT_BATCH_SIZE`:\n\n```\nINFERENCE:\n  INPUT_BATCH_SIZE: 1\n  OUTPUT_BATCH_SIZE: 1\n```\n\nThe proportion of data from annotated datasets and bootstrapped dataset can be tracked\nin the logs, e.g.:\n\n```\n[... densepose.engine.trainer]: batch/ 1.8, batch/base_coco_2017_train 6.4, batch/densepose_coco_2014_train 3.85\n```\n\nwhich means that over the last 20 iterations, on average for 1.8 bootstrapped data samples there were 6.4 samples from `base_coco_2017_train` and 3.85 samples from `densepose_coco_2014_train`.\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/doc/DENSEPOSE_CSE.md",
    "content": "# Continuous Surface Embeddings for Dense Pose Estimation for Humans and Animals\n\n## <a name=\"Overview\"></a> Overview\n\n<div align=\"center\">\n  <img src=\"https://dl.fbaipublicfiles.com/densepose/web/densepose_cse_teaser.png\" width=\"700px\" />\n</div>\n\nThe pipeline uses [Faster R-CNN](https://arxiv.org/abs/1506.01497)\nwith [Feature Pyramid Network](https://arxiv.org/abs/1612.03144) meta architecture\noutlined in Figure 1. For each detected object, the model predicts\nits coarse segmentation `S` (2 channels: foreground / background)\nand the embedding `E` (16 channels). At the same time, the embedder produces vertex\nembeddings `Ê` for the corresponding mesh. Universal positional embeddings `E`\nand vertex embeddings `Ê` are matched to derive for each pixel its continuous\nsurface embedding.\n\n<div align=\"center\">\n  <img src=\"https://dl.fbaipublicfiles.com/densepose/web/densepose_pipeline_cse.png\" width=\"700px\" />\n</div>\n<p class=\"image-caption\"><b>Figure 1.</b> DensePose continuous surface embeddings architecture based on Faster R-CNN with Feature Pyramid Network (FPN).</p>\n\n### Datasets\n\nFor more details on datasets used for training and validation of\ncontinuous surface embeddings models,\nplease refer to the [DensePose Datasets](DENSEPOSE_DATASETS.md) page.\n\n## <a name=\"ModelZoo\"></a> Model Zoo and Baselines\n\n### Human CSE Models\n\nContinuous surface embeddings models for humans trained using the protocols from [Neverova et al, 2020](https://arxiv.org/abs/2011.12438).\n\nModels trained with hard assignment loss &#x2112;:\n\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Name</th>\n<th valign=\"bottom\">lr<br/>sched</th>\n<th valign=\"bottom\">train<br/>time<br/>(s/iter)</th>\n<th valign=\"bottom\">inference<br/>time<br/>(s/im)</th>\n<th valign=\"bottom\">train<br/>mem<br/>(GB)</th>\n<th valign=\"bottom\">box<br/>AP</th>\n<th valign=\"bottom\">segm<br/>AP</th>\n<th valign=\"bottom\">dp. AP<br/>GPS</th>\n<th valign=\"bottom\">dp. AP<br/>GPSm</th>\n<th valign=\"bottom\">model id</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n<!-- ROW: densepose_rcnn_R_50_FPN_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/cse/densepose_rcnn_R_50_FPN_s1x.yaml\">R_50_FPN_s1x</a></td>\n <td align=\"center\">s1x</td>\n <td align=\"center\">0.349</td>\n <td align=\"center\">0.060</td>\n <td align=\"center\">6.3</td>\n <td align=\"center\">61.1</td>\n <td align=\"center\">67.1</td>\n <td align=\"center\">64.4</td>\n <td align=\"center\">65.7</td>\n <td align=\"center\">251155172</td>\n <td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_s1x/251155172/model_final_c4ea5f.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_s1x/251155172/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_101_FPN_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/cse/densepose_rcnn_R_101_FPN_s1x.yaml\">R_101_FPN_s1x</a></td>\n  <td align=\"center\">s1x</td>\n  <td align=\"center\">0.461</td>\n  <td align=\"center\">0.071</td>\n  <td align=\"center\">7.4</td>\n  <td align=\"center\">62.3</td>\n  <td align=\"center\">67.2</td>\n  <td align=\"center\">64.7</td>\n  <td align=\"center\">65.8</td>\n  <td align=\"center\">251155500</td>\n  <td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_101_FPN_s1x/251155500/model_final_5c995f.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_101_FPN_s1x/251155500/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_50_FPN_DL_s1x -->\n <tr><td align=\"left\"><a href=\"../configs/cse/densepose_rcnn_R_50_FPN_DL_s1x.yaml\">R_50_FPN_DL_s1x</a></td>\n <td align=\"center\">s1x</td>\n <td align=\"center\">0.399</td>\n <td align=\"center\">0.061</td>\n <td align=\"center\">7.0</td>\n <td align=\"center\">60.8</td>\n <td align=\"center\">67.8</td>\n <td align=\"center\">65.5</td>\n <td align=\"center\">66.4</td>\n <td align=\"center\">251156349</td>\n <td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_DL_s1x/251156349/model_final_e96218.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_DL_s1x/251156349/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_101_FPN_DL_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/cse/densepose_rcnn_R_101_FPN_DL_s1x.yaml\">R_101_FPN_DL_s1x</a></td>\n  <td align=\"center\">s1x</td>\n  <td align=\"center\">0.504</td>\n  <td align=\"center\">0.074</td>\n  <td align=\"center\">8.3</td>\n  <td align=\"center\">61.5</td>\n  <td align=\"center\">68.0</td>\n  <td align=\"center\">65.6</td>\n  <td align=\"center\">66.6</td>\n  <td align=\"center\">251156606</td>\n  <td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_101_FPN_DL_s1x/251156606/model_final_b236ce.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_101_FPN_DL_s1x/251156606/metrics.json\">metrics</a></td>\n</tr>\n</tbody></table>\n\nModels trained with soft assignment loss &#x2112;<sub>&sigma;</sub>:\n\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Name</th>\n<th valign=\"bottom\">lr<br/>sched</th>\n<th valign=\"bottom\">train<br/>time<br/>(s/iter)</th>\n<th valign=\"bottom\">inference<br/>time<br/>(s/im)</th>\n<th valign=\"bottom\">train<br/>mem<br/>(GB)</th>\n<th valign=\"bottom\">box<br/>AP</th>\n<th valign=\"bottom\">segm<br/>AP</th>\n<th valign=\"bottom\">dp. AP<br/>GPS</th>\n<th valign=\"bottom\">dp. AP<br/>GPSm</th>\n<th valign=\"bottom\">model id</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n<!-- ROW: densepose_rcnn_R_50_FPN_soft_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/cse/densepose_rcnn_R_50_FPN_soft_s1x.yaml\">R_50_FPN_soft_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.357</td>\n<td align=\"center\">0.057</td>\n<td align=\"center\">9.7</td>\n<td align=\"center\">61.3</td>\n<td align=\"center\">66.9</td>\n<td align=\"center\">64.3</td>\n<td align=\"center\">65.4</td>\n<td align=\"center\">250533982</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_s1x/250533982/model_final_2c4512.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_s1x/250533982/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_101_FPN_soft_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/cse/densepose_rcnn_R_101_FPN_soft_s1x.yaml\">R_101_FPN_soft_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.464</td>\n<td align=\"center\">0.071</td>\n<td align=\"center\">10.5</td>\n<td align=\"center\">62.1</td>\n<td align=\"center\">67.3</td>\n<td align=\"center\">64.5</td>\n<td align=\"center\">66.0</td>\n<td align=\"center\">250712522</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_101_FPN_soft_s1x/250712522/model_final_4637da.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_101_FPN_soft_s1x/250712522/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_50_FPN_DL_soft_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/cse/densepose_rcnn_R_50_FPN_DL_soft_s1x.yaml\">R_50_FPN_DL_soft_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.427</td>\n<td align=\"center\">0.062</td>\n<td align=\"center\">11.3</td>\n<td align=\"center\">60.8</td>\n<td align=\"center\">68.0</td>\n<td align=\"center\">66.1</td>\n<td align=\"center\">66.7</td>\n<td align=\"center\">250713703</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_DL_soft_s1x/250713703/model_final_9199f5.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_DL_soft_s1x/250713703/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_101_FPN_DL_soft_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/cse/densepose_rcnn_R_101_FPN_DL_soft_s1x.yaml\">R_101_FPN_DL_soft_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.483</td>\n<td align=\"center\">0.071</td>\n<td align=\"center\">12.2</td>\n<td align=\"center\">61.5</td>\n<td align=\"center\">68.2</td>\n<td align=\"center\">66.2</td>\n<td align=\"center\">67.1</td>\n<td align=\"center\">250713061</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_101_FPN_DL_soft_s1x/250713061/model_final_1d3314.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_101_FPN_DL_soft_s1x/250713061/metrics.json\">metrics</a></td>\n</tr>\n</tbody></table>\n\n### Animal CSE Models\n\nModels obtained by finetuning human CSE models on animals data from `ds1_train`\n(see the [DensePose LVIS](DENSEPOSE_DATASETS.md#continuous-surface-embeddings-annotations-3)\nsection for more details on the datasets) with soft assignment loss &#x2112;<sub>&sigma;</sub>:\n\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Name</th>\n<th valign=\"bottom\">lr<br/>sched</th>\n<th valign=\"bottom\">train<br/>time<br/>(s/iter)</th>\n<th valign=\"bottom\">inference<br/>time<br/>(s/im)</th>\n<th valign=\"bottom\">train<br/>mem<br/>(GB)</th>\n<th valign=\"bottom\">box<br/>AP</th>\n<th valign=\"bottom\">segm<br/>AP</th>\n<th valign=\"bottom\">dp. AP<br/>GPS</th>\n<th valign=\"bottom\">dp. AP<br/>GPSm</th>\n<th valign=\"bottom\">model id</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n<!-- ROW: densepose_rcnn_R_50_FPN_soft_chimps_finetune_4k -->\n <tr><td align=\"left\"><a href=\"../configs/cse/densepose_rcnn_R_50_FPN_soft_chimps_finetune_4k.yaml\">R_50_FPN_soft_chimps_finetune_4k</a></td>\n<td align=\"center\">4K</td>\n<td align=\"center\">0.569</td>\n<td align=\"center\">0.051</td>\n<td align=\"center\">4.7</td>\n<td align=\"center\">62.0</td>\n<td align=\"center\">59.0</td>\n<td align=\"center\">32.2</td>\n<td align=\"center\">39.6</td>\n<td align=\"center\">253146869</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_chimps_finetune_4k/253146869/model_final_52f649.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_chimps_finetune_4k/253146869/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_50_FPN_soft_animals_finetune_4k -->\n<tr><td align=\"left\"><a href=\"../configs/cse/densepose_rcnn_R_50_FPN_soft_animals_finetune_4k.yaml\">R_50_FPN_soft_animals_finetune_4k</a></td>\n<td align=\"center\">4K</td>\n<td align=\"center\">0.381</td>\n<td align=\"center\">0.061</td>\n<td align=\"center\">7.3</td>\n<td align=\"center\">44.9</td>\n<td align=\"center\">55.5</td>\n<td align=\"center\">21.3</td>\n<td align=\"center\">28.8</td>\n<td align=\"center\">253145793</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_animals_finetune_4k/253145793/model_final_8f8ba2.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_animals_finetune_4k/253145793/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_50_FPN_soft_animals_CA_finetune_4k -->\n <tr><td align=\"left\"><a href=\"../configs/cse/densepose_rcnn_R_50_FPN_soft_animals_CA_finetune_4k.yaml\">R_50_FPN_soft_animals_CA_finetune_4k</a></td>\n<td align=\"center\">4K</td>\n<td align=\"center\">0.412</td>\n<td align=\"center\">0.059</td>\n<td align=\"center\">7.1</td>\n<td align=\"center\">53.4</td>\n<td align=\"center\">59.5</td>\n<td align=\"center\">25.4</td>\n<td align=\"center\">33.4</td>\n<td align=\"center\">253498611</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_animals_CA_finetune_4k/253498611/model_final_6d69b7.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_animals_CA_finetune_4k/253498611/metrics.json\">metrics</a></td>\n</tr>\n</tbody></table>\n\nAcronyms:\n\n`CA`: class agnostic training, where all annotated instances are mapped into a single category\n\n\nModels obtained by finetuning human CSE models on animals data from `ds2_train` dataset\nwith soft assignment loss &#x2112;<sub>&sigma;</sub> and, for some schedules, cycle losses.\nPlease refer to [DensePose LVIS](DENSEPOSE_DATASETS.md#continuous-surface-embeddings-annotations-3)\nsection for details on the dataset and to [Neverova et al, 2021]() for details on cycle losses.\n\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Name</th>\n<th valign=\"bottom\">lr<br/>sched</th>\n<th valign=\"bottom\">train<br/>time<br/>(s/iter)</th>\n<th valign=\"bottom\">inference<br/>time<br/>(s/im)</th>\n<th valign=\"bottom\">train<br/>mem<br/>(GB)</th>\n<th valign=\"bottom\">box<br/>AP</th>\n<th valign=\"bottom\">segm<br/>AP</th>\n<th valign=\"bottom\">dp. AP<br/>GPS</th>\n<th valign=\"bottom\">dp. AP<br/>GPSm</th>\n<th valign=\"bottom\">GErr</th>\n<th valign=\"bottom\">GPS</th>\n<th valign=\"bottom\">model id</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n<!-- ROW: densepose_rcnn_R_50_FPN_soft_animals_I0_finetune_16k -->\n<tr><td align=\"left\"><a href=\"../configs/cse/densepose_rcnn_R_50_FPN_soft_animals_I0_finetune_16k.yaml\">R_50_FPN_soft_animals_I0_finetune_16k</a></td>\n <td align=\"center\">16k</td>\n <td align=\"center\">0.386</td>\n <td align=\"center\">0.058</td>\n <td align=\"center\">8.4</td>\n <td align=\"center\">54.2</td>\n <td align=\"center\">67.0</td>\n <td align=\"center\">29.0</td>\n <td align=\"center\">38.6</td>\n <td align=\"center\">13.2</td>\n <td align=\"center\">85.4</td>\n <td align=\"center\">270727112</td>\n <td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_animals_I0_finetune_16k/270727112/model_final_421d28.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_animals_I0_finetune_16k/270727112/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_50_FPN_soft_animals_I0_finetune_m2m_16k -->\n<tr><td align=\"left\"><a href=\"../configs/cse/densepose_rcnn_R_50_FPN_soft_animals_I0_finetune_m2m_16k.yaml\">R_50_FPN_soft_animals_I0_finetune_m2m_16k</a></td>\n <td align=\"center\">16k</td>\n <td align=\"center\">0.508</td>\n <td align=\"center\">0.056</td>\n <td align=\"center\">12.2</td>\n <td align=\"center\">54.1</td>\n <td align=\"center\">67.3</td>\n <td align=\"center\">28.6</td>\n <td align=\"center\">38.4</td>\n <td align=\"center\">12.5</td>\n <td align=\"center\">87.6</td>\n <td align=\"center\">270982215</td>\n <td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_animals_I0_finetune_m2m_16k/270982215/model_final_6fe5f4.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_animals_I0_finetune_m2m_16k/270982215/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_50_FPN_soft_animals_I0_finetune_i2m_16k -->\n<tr><td align=\"left\"><a href=\"../configs/cse/densepose_rcnn_R_50_FPN_soft_animals_I0_finetune_i2m_16k.yaml\">R_50_FPN_soft_animals_I0_finetune_i2m_16k</a></td>\n <td align=\"center\">16k</td>\n <td align=\"center\">0.483</td>\n <td align=\"center\">0.056</td>\n <td align=\"center\">9.7</td>\n <td align=\"center\">54.0</td>\n <td align=\"center\">66.6</td>\n <td align=\"center\">28.9</td>\n <td align=\"center\">38.3</td>\n <td align=\"center\">11.0</td>\n <td align=\"center\">88.9</td>\n <td align=\"center\">270727461</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_animals_I0_finetune_i2m_16k/270727461/model_final_8c9d99.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_soft_animals_I0_finetune_i2m_16k/270727461/metrics.json\">metrics</a></td>\n</tr>\n</tbody></table>\n\n## <a name=\"References\"></a> References\n\nIf you use DensePose methods based on continuous surface embeddings, please take the\nreferences from the following BibTeX entries:\n\nContinuous surface embeddings:\n```\n@InProceedings{Neverova2020ContinuousSurfaceEmbeddings,\n    title = {Continuous Surface Embeddings},\n    author = {Neverova, Natalia and Novotny, David and Khalidov, Vasil and Szafraniec, Marc and Labatut, Patrick and Vedaldi, Andrea},\n    journal = {Advances in Neural Information Processing Systems},\n    year = {2020},\n}\n```\n\nCycle Losses:\n```\n@InProceedings{Neverova2021UniversalCanonicalMaps,\n    title = {Discovering Relationships between Object Categories via Universal Canonical Maps},\n    author = {Neverova, Natalia and Sanakoyeu, Artsiom and Novotny, David and Labatut, Patrick and Vedaldi, Andrea},\n    journal = {The IEEE Conference on Computer Vision and Pattern Recognition (CVPR)},\n    year = {2021},\n}\n```\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/doc/DENSEPOSE_DATASETS.md",
    "content": "# DensePose Datasets\n\nWe summarize the datasets used in various DensePose training\nschedules and describe different available annotation types.\n\n## Table of Contents\n\n[General Information](#general-information)\n\n[DensePose COCO](#densepose-coco)\n\n[DensePose PoseTrack](#densepose-posetrack)\n\n[DensePose Chimps](#densepose-chimps)\n\n[DensePose LVIS](#densepose-lvis)\n\n## General Information\n\nDensePose annotations are typically stored in JSON files. Their\nstructure follows the [COCO Data Format](https://cocodataset.org/#format-data),\nthe basic data structure is outlined below:\n\n```\n{\n    \"info\": info,\n    \"images\": [image],\n    \"annotations\": [annotation],\n    \"licenses\": [license],\n}\n\ninfo{\n    \"year\": int,\n    \"version\": str,\n    \"description\": str,\n    \"contributor\": str,\n    \"url\": str,\n    \"date_created\": datetime,\n}\n\nimage{\n    \"id\": int,\n    \"width\": int,\n    \"height\": int,\n    \"file_name\": str,\n    \"license\": int,\n    \"flickr_url\": str,\n    \"coco_url\": str,\n    \"date_captured\": datetime,\n}\n\nlicense{\n    \"id\": int, \"name\": str, \"url\": str,\n}\n```\n\nDensePose annotations can be of two types:\n*chart-based annotations* or *continuous surface embeddings annotations*.\nWe give more details on each of the two annotation types below.\n\n### Chart-based Annotations\n\nThese annotations assume a single 3D model which corresponds to\nall the instances in a given dataset.\n3D model is assumed to be split into *charts*. Each chart has its own\n2D parametrization through inner coordinates `U` and `V`, typically\ntaking values in `[0, 1]`.\n\nChart-based annotations consist of *point-based annotations* and\n*segmentation annotations*. Point-based annotations specify, for a given\nimage point, which model part it belongs to and what are its coordinates\nin the corresponding chart. Segmentation annotations specify regions\nin an image that are occupied by a given part. In some cases, charts\nassociated with point annotations are more detailed than the ones\nassociated with segmentation annotations. In this case we distinguish\n*fine segmentation* (associated with points) and *coarse segmentation*\n(associated with masks).\n\n**Point-based annotations**:\n\n`dp_x` and `dp_y`:  image coordinates of the annotated points along\nthe horizontal and vertical axes respectively. The coordinates are defined\nwith respect to the top-left corner of the annotated bounding box and are\nnormalized assuming the bounding box size to be `256x256`;\n\n`dp_I`: for each point specifies the index of the fine segmentation chart\nit belongs to;\n\n`dp_U` and `dp_V`: point coordinates on the corresponding chart.\nEach fine segmentation part has its own parametrization in terms of chart\ncoordinates.\n\n**Segmentation annotations**:\n\n`dp_masks`: RLE encoded dense masks (`dict` containing keys `counts` and `size`).\nThe masks are typically of size `256x256`, they define segmentation within the\nbounding box.\n\n### Continuous Surface Embeddings Annotations\n\nContinuous surface embeddings annotations also consist of *point-based annotations*\nand *segmentation annotations*. Point-based annotations establish correspondence\nbetween image points and 3D model vertices. Segmentation annotations specify\nforeground regions for a given instane.\n\n**Point-based annotations**:\n\n`dp_x` and `dp_y` specify image point coordinates the same way as for chart-based\nannotations;\n\n`dp_vertex` gives indices of 3D model vertices, which the annotated image points\ncorrespond to;\n\n`ref_model` specifies 3D model name.\n\n**Segmentation annotations**:\n\nSegmentations can either be given by `dp_masks` field or by `segmentation` field.\n\n`dp_masks`: RLE encoded dense masks (`dict` containing keys `counts` and `size`).\nThe masks are typically of size `256x256`, they define segmentation within the\nbounding box.\n\n`segmentation`: polygon-based masks stored as a 2D list\n`[[x1 y1 x2 y2...],[x1 y1 ...],...]` of polygon vertex coordinates in a given\nimage.\n\n## DensePose COCO\n\n<div align=\"center\">\n  <img src=\"http://cocodataset.org/images/densepose-splash.png\" width=\"700px\" />\n</div>\n<p class=\"image-caption\">\n  <b>Figure 1.</b> Annotation examples from the DensePose COCO dataset.\n</p>\n\nDensePose COCO dataset contains about 50K annotated persons on images from the\n[COCO dataset](https://cocodataset.org/#home)\nThe images are available for download from the\n[COCO Dataset download page](https://cocodataset.org/#download):\n[train2014](http://images.cocodataset.org/zips/train2014.zip),\n[val2014](http://images.cocodataset.org/zips/val2014.zip).\nThe details on available annotations and their download links are given below.\n\n### Chart-based Annotations\n\nChart-based DensePose COCO annotations are available for the instances of category\n`person` and correspond to the model shown in Figure 2.\nThey include `dp_x`, `dp_y`, `dp_I`, `dp_U` and `dp_V` fields for annotated points\n(~100 points per annotated instance) and `dp_masks` field, which encodes\ncoarse segmentation into 14 parts in the following order:\n`Torso`, `Right Hand`, `Left Hand`, `Left Foot`, `Right Foot`,\n`Upper Leg Right`, `Upper Leg Left`, `Lower Leg Right`, `Lower Leg Left`,\n`Upper Arm Left`, `Upper Arm Right`, `Lower Arm Left`, `Lower Arm Right`,\n`Head`.\n\n<div align=\"center\">\n  <img src=\"https://dl.fbaipublicfiles.com/densepose/web/densepose_human_charts_wcoarse.png\" width=\"500px\" />\n</div>\n<p class=\"image-caption\">\n  <b>Figure 2.</b> Human body charts (<i>fine segmentation</i>)\n  and the associated 14 body parts depicted with rounded rectangles\n  (<i>coarse segmentation</i>).\n</p>\n\nThe dataset splits used in the training schedules are\n`train2014`, `valminusminival2014` and `minival2014`.\n`train2014` and `valminusminival2014` are used for training,\nand `minival2014` is used for validation.\nThe table with annotation download links, which summarizes the number of annotated\ninstances and images for each of the dataset splits is given below:\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Name</th>\n<th valign=\"bottom\"># inst</th>\n<th valign=\"bottom\"># images</th>\n<th valign=\"bottom\">file size</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n<!-- ROW: densepose_train2014 -->\n<tr><td align=\"left\">densepose_train2014</td>\n<td align=\"center\">39210</td>\n<td align=\"center\">26437</td>\n<td valign=\"center\">526M</td>\n<td align=\"left\"><a href=\"https://dl.fbaipublicfiles.com/densepose/annotations/coco/densepose_train2014.json\">densepose_train2014.json</a></td>\n</tr>\n<!-- ROW: densepose_valminusminival2014 -->\n<tr><td align=\"left\">densepose_valminusminival2014</td>\n<td align=\"center\">7297</td>\n<td align=\"center\">5984</td>\n<td valign=\"center\">105M</td>\n<td align=\"left\"><a href=\"https://dl.fbaipublicfiles.com/densepose/annotations/coco/densepose_valminusminival2014.json\">densepose_valminusminival2014.json</a></td>\n</tr>\n<!-- ROW: densepose_minival2014 -->\n<tr><td align=\"left\">densepose_minival2014</td>\n<td align=\"center\">2243</td>\n<td align=\"center\">1508</td>\n<td valign=\"center\">31M</td>\n<td align=\"left\"><a href=\"https://dl.fbaipublicfiles.com/densepose/annotations/coco/densepose_minival2014.json\">densepose_minival2014.json</a></td>\n</tr>\n</tbody></table>\n\n### Continuous Surface Embeddings Annotations\n\nDensePose COCO continuous surface embeddings annotations are available for the instances\nof category `person`. The annotations correspond to the 3D model shown in Figure 2,\nand include `dp_x`, `dp_y` and `dp_vertex` and `ref_model` fields.\nAll chart-based annotations were also kept for convenience.\n\nAs with chart-based annotations, the dataset splits used in the training schedules are\n`train2014`, `valminusminival2014` and `minival2014`.\n`train2014` and `valminusminival2014` are used for training,\nand `minival2014` is used for validation.\nThe table with annotation download links, which summarizes the number of annotated\ninstances and images for each of the dataset splits is given below:\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Name</th>\n<th valign=\"bottom\"># inst</th>\n<th valign=\"bottom\"># images</th>\n<th valign=\"bottom\">file size</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n<!-- ROW: densepose_train2014_cse -->\n<tr><td align=\"left\">densepose_train2014_cse</td>\n<td align=\"center\">39210</td>\n<td align=\"center\">26437</td>\n<td valign=\"center\">554M</td>\n<td align=\"left\"><a href=\"https://dl.fbaipublicfiles.com/densepose/annotations/coco_cse/densepose_train2014_cse.json\">densepose_train2014_cse.json</a></td>\n</tr>\n<!-- ROW: densepose_valminusminival2014_cse -->\n<tr><td align=\"left\">densepose_valminusminival2014_cse</td>\n<td align=\"center\">7297</td>\n<td align=\"center\">5984</td>\n<td valign=\"center\">110M</td>\n<td align=\"left\"><a href=\"https://dl.fbaipublicfiles.com/densepose/annotations/coco_cse/densepose_valminusminival2014_cse.json\">densepose_valminusminival2014_cse.json</a></td>\n</tr>\n<!-- ROW: densepose_minival2014_cse -->\n<tr><td align=\"left\">densepose_minival2014_cse</td>\n<td align=\"center\">2243</td>\n<td align=\"center\">1508</td>\n<td valign=\"center\">32M</td>\n<td align=\"left\"><a href=\"https://dl.fbaipublicfiles.com/densepose/annotations/coco_cse/densepose_minival2014_cse.json\">densepose_minival2014_cse.json</a></td>\n</tr>\n</tbody></table>\n\n## DensePose PoseTrack\n\n<div align=\"center\">\n  <img src=\"https://posetrack.net/workshops/eccv2018/assets/images/densepose-posetrack_examples.jpg\" width=\"700px\" />\n</div>\n<p class=\"image-caption\">\n  <b>Figure 3.</b> Annotation examples from the PoseTrack dataset.\n</p>\n\nDensePose PoseTrack dataset contains annotated image sequences.\nTo download the images for this dataset, please follow the instructions\nfrom the [PoseTrack Download Page](https://posetrack.net/users/download.php).\n\n### Chart-based Annotations\n\nChart-based DensePose PoseTrack annotations are available for the instances with category\n`person` and correspond to the model shown in Figure 2.\nThey include `dp_x`, `dp_y`, `dp_I`, `dp_U` and `dp_V` fields for annotated points\n(~100 points per annotated instance) and `dp_masks` field, which encodes\ncoarse segmentation into the same 14 parts as in DensePose COCO.\n\nThe dataset splits used in the training schedules are\n`posetrack_train2017` (train set) and `posetrack_val2017` (validation set).\nThe table with annotation download links, which summarizes the number of annotated\ninstances, instance tracks and images for the dataset splits is given below:\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Name</th>\n<th valign=\"bottom\"># inst</th>\n<th valign=\"bottom\"># images</th>\n<th valign=\"bottom\"># tracks</th>\n<th valign=\"bottom\">file size</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n<!-- ROW: densepose_posetrack_train2017 -->\n<tr><td align=\"left\">densepose_posetrack_train2017</td>\n<td align=\"center\">8274</td>\n<td align=\"center\">1680</td>\n<td align=\"center\">36</td>\n<td valign=\"center\">118M</td>\n<td align=\"left\"><a href=\"https://dl.fbaipublicfiles.com/densepose/annotations/coco/densepose_posetrack_train2017.json\">densepose_posetrack_train2017.json</a></td>\n</tr>\n<!-- ROW: densepose_posetrack_val2017 -->\n<tr><td align=\"left\">densepose_posetrack_val2017</td>\n<td align=\"center\">4753</td>\n<td align=\"center\">782</td>\n<td align=\"center\">46</td>\n<td valign=\"center\">59M</td>\n<td align=\"left\"><a href=\"https://dl.fbaipublicfiles.com/densepose/annotations/coco/densepose_posetrack_val2017.json\">densepose_posetrack_val2017.json</a></td>\n</tr>\n</tbody></table>\n\n## DensePose Chimps\n\n<div align=\"center\">\n  <img src=\"https://dl.fbaipublicfiles.com/densepose/web/densepose_chimps_preview.jpg\" width=\"700px\" />\n</div>\n<p class=\"image-caption\">\n  <b>Figure 4.</b> Example images from the DensePose Chimps dataset.\n</p>\n\nDensePose Chimps dataset contains annotated images of chimpanzees.\nTo download the images for this dataset, please use the URL specified in\n`image_url` field in the annotations.\n\n### Chart-based Annotations\n\nChart-based DensePose Chimps annotations correspond to the human model shown in Figure 2,\nthe instances are thus annotated to belong to the `person` category.\nThey include `dp_x`, `dp_y`, `dp_I`, `dp_U` and `dp_V` fields for annotated points\n(~3 points per annotated instance) and `dp_masks` field, which encodes\nforeground mask in RLE format.\n\nChart-base DensePose Chimps annotations are used for validation only.\nThe table with annotation download link, which summarizes the number of annotated\ninstances and images is given below:\n\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Name</th>\n<th valign=\"bottom\"># inst</th>\n<th valign=\"bottom\"># images</th>\n<th valign=\"bottom\">file size</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n<!-- ROW: densepose_chimps -->\n<tr><td align=\"left\">densepose_chimps</td>\n<td align=\"center\">930</td>\n<td align=\"center\">654</td>\n<td valign=\"center\">6M</td>\n<td align=\"left\"><a href=\"https://dl.fbaipublicfiles.com/densepose/annotations/densepose_chimps/densepose_chimps_full_v2.json\">densepose_chimps_full_v2.json</a></td>\n</tr>\n</tbody></table>\n\n### Continuous Surface Embeddings Annotations\n\nContinuous surface embeddings annotations for DensePose Chimps\ninclude `dp_x`, `dp_y` and `dp_vertex` point-based annotations\n(~3 points per annotated instance), `dp_masks` field with the same\ncontents as for chart-based annotations and `ref_model` field\nwhich refers to a chimpanzee 3D model `chimp_5029`.\n\nThe dataset is split into training and validation subsets.\nThe table with annotation download links, which summarizes the number of annotated\ninstances and images for each of the dataset splits is given below:\n\nThe table below outlines the dataset splits:\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Name</th>\n<th valign=\"bottom\"># inst</th>\n<th valign=\"bottom\"># images</th>\n<th valign=\"bottom\">file size</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n<!-- ROW: densepose_chimps_cse_train -->\n<tr><td align=\"left\">densepose_chimps_cse_train</td>\n<td align=\"center\">500</td>\n<td align=\"center\">350</td>\n<td valign=\"center\">3M</td>\n<td align=\"left\"><a href=\"https://dl.fbaipublicfiles.com/densepose/annotations/densepose_chimps/densepose_chimps_cse_train.json\">densepose_chimps_cse_train.json</a></td>\n</tr>\n<!-- ROW: densepose_chimps_cse_val -->\n<tr><td align=\"left\">densepose_chimps_cse_val</td>\n<td align=\"center\">430</td>\n<td align=\"center\">304</td>\n<td valign=\"center\">3M</td>\n<td align=\"left\"><a href=\"https://dl.fbaipublicfiles.com/densepose/annotations/densepose_chimps/densepose_chimps_cse_val.json\">densepose_chimps_cse_val.json</a></td>\n</tr>\n</tbody></table>\n\n## DensePose LVIS\n\n<div align=\"center\">\n  <img src=\"https://dl.fbaipublicfiles.com/densepose/web/lvis_selected_animals_preview.jpg\" width=\"700px\" />\n</div>\n<p class=\"image-caption\">\n  <b>Figure 5.</b> Example images from the DensePose LVIS dataset.\n</p>\n\nDensePose LVIS dataset contains segmentation and DensePose annotations for animals\non images from the [LVIS dataset](https://www.lvisdataset.org/dataset).\nThe images are available for download through the links:\n[train2017](http://images.cocodataset.org/zips/train2017.zip),\n[val2017](http://images.cocodataset.org/zips/val2017.zip).\n\n### Continuous Surface Embeddings Annotations\n\nContinuous surface embeddings (CSE) annotations for DensePose LVIS\ninclude `dp_x`, `dp_y` and `dp_vertex` point-based annotations\n(~3 points per annotated instance) and a `ref_model` field\nwhich refers to a 3D model that corresponds to the instance.\nInstances from 9 animal categories were annotated with CSE DensePose data:\nbear, cow, cat, dog, elephant, giraffe, horse, sheep and zebra.\n\nForeground masks are available from instance segmentation annotations\n(`segmentation` field) in polygon format, they are stored as a 2D list\n`[[x1 y1 x2 y2...],[x1 y1 ...],...]`.\n\nWe used two datasets, each constising of one training (`train`)\nand validation (`val`) subsets: the first one (`ds1`)\nwas used in [Neverova et al, 2020](https://arxiv.org/abs/2011.12438).\nThe second one (`ds2`), was used in [Neverova et al, 2021]().\n\nThe summary of the available datasets is given below:\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<tr>\n<th valign=\"bottom\"></th>\n<th valign=\"bottom\" colspan=\"3\">All Data</th>\n<th valign=\"bottom\" colspan=\"3\">Selected Animals<br>(9 categories)</th>\n<th valign=\"bottom\" colspan=\"2\">File</th>\n</tr>\n<tr>\n<th valign=\"bottom\">Name</th>\n<th valign=\"bottom\"># cat</th>\n<th valign=\"bottom\"># img</th>\n<th valign=\"bottom\"># segm</th>\n<th valign=\"bottom\"># img</th>\n<th valign=\"bottom\"># segm</th>\n<th valign=\"bottom\"># dp</th>\n<th valign=\"bottom\">size</th>\n<th valign=\"bottom\">download</th>\n</tr>\n<!-- TABLE BODY -->\n<!-- ROW: densepose_lvis_v1_ds1_train_v1 -->\n<tr><td align=\"left\">ds1_train</td>\n<td align=\"center\">556</td>\n<td align=\"center\">4141</td>\n<td align=\"center\">23985</td>\n<td align=\"center\">4141</td>\n<td align=\"center\">9472</td>\n<td align=\"center\">5184</td>\n<td valign=\"center\">46M</td>\n<td align=\"left\"><a href=\"https://dl.fbaipublicfiles.com/densepose/annotations/lvis/densepose_lvis_v1_ds1_train_v1.json\">densepose_lvis_v1_ds1_train_v1.json</a></td>\n</tr>\n<!-- ROW: densepose_lvis_v1_ds1_val_v1 -->\n<tr><td align=\"left\">ds1_val</td>\n<td align=\"center\">251</td>\n<td align=\"center\">571</td>\n<td align=\"center\">3281</td>\n<td align=\"center\">571</td>\n<td align=\"center\">1537</td>\n<td align=\"center\">1036</td>\n<td valign=\"center\">5M</td>\n<td align=\"left\"><a href=\"https://dl.fbaipublicfiles.com/densepose/annotations/lvis/densepose_lvis_v1_ds1_val_v1.json\">densepose_lvis_v1_ds1_val_v1.json</a></td>\n</tr>\n<!-- ROW: densepose_lvis_v1_ds2_train_v1 -->\n<tr><td align=\"left\">ds2_train</td>\n<td align=\"center\">1203</td>\n<td align=\"center\">99388</td>\n<td align=\"center\">1270141</td>\n<td align=\"center\">13746</td>\n<td align=\"center\">46964</td>\n<td align=\"center\">18932</td>\n<td valign=\"center\">1051M</td>\n<td align=\"left\"><a href=\"https://dl.fbaipublicfiles.com/densepose/annotations/lvis/densepose_lvis_v1_ds2_train_v1.json\">densepose_lvis_v1_ds2_train_v1.json</a></td>\n</tr>\n<!-- ROW: densepose_lvis_v1_ds2_val_v1 -->\n<tr><td align=\"left\">ds2_val</td>\n<td align=\"center\">9</td>\n<td align=\"center\">2690</td>\n<td align=\"center\">9155</td>\n<td align=\"center\">2690</td>\n<td align=\"center\">9155</td>\n<td align=\"center\">3604</td>\n<td valign=\"center\">24M</td>\n<td align=\"left\"><a href=\"https://dl.fbaipublicfiles.com/densepose/annotations/lvis/densepose_lvis_v1_ds2_val_v1.json\">densepose_lvis_v1_ds2_val_v1.json</a></td>\n</tr>\n</tbody></table>\n\nLegend:\n\n`#cat` - number of categories in the dataset for which annotations are available;\n\n`#img` - number of images with annotations in the dataset;\n\n`#segm` - number of segmentation annotations;\n\n`#dp` - number of DensePose annotations.\n\n\nImportant Notes:\n\n1. The reference models used for `ds1_train` and `ds1_val` are\n`bear_4936`, `cow_5002`, `cat_5001`, `dog_5002`, `elephant_5002`, `giraffe_5002`,\n`horse_5004`, `sheep_5004` and `zebra_5002`. The reference models used for\n`ds2_train` and `ds2_val` are `bear_4936`, `cow_5002`, `cat_7466`,\n`dog_7466`, `elephant_5002`, `giraffe_5002`, `horse_5004`, `sheep_5004` and `zebra_5002`.\nSo reference models for categories `cat` aind `dog` are different for `ds1` and `ds2`.\n\n2. Some annotations from `ds1_train` are reused in `ds2_train` (4538 DensePose annotations\nand 21275 segmentation annotations). The ones for cat and dog categories were remapped\nfrom `cat_5001` and `dog_5002` reference models used in `ds1` to `cat_7466` and `dog_7466`\nused in `ds2`.\n\n3. All annotations from `ds1_val` are included into `ds2_val` after the remapping\nprocedure mentioned in note 2.\n\n4. Some annotations from `ds1_train` are part of `ds2_val` (646 DensePose annotations and\n1225 segmentation annotations). Thus one should not train on `ds1_train` if evaluating on `ds2_val`.\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/doc/DENSEPOSE_IUV.md",
    "content": "# Chart-based Dense Pose Estimation for Humans and Animals\n\n## <a name=\"Overview\"></a> Overview\n\nThe goal of chart-based DensePose methods is to establish dense correspondences\nbetween image pixels and 3D object mesh by splitting the latter into charts and estimating\nfor each pixel the corresponding chart index `I` and local chart coordinates `(U, V)`.\n\n<div align=\"center\">\n  <img src=\"https://dl.fbaipublicfiles.com/densepose/web/densepose_teaser_compressed_25.gif\" width=\"700px\" />\n</div>\n\nThe charts used for human DensePose estimation are shown in Figure 1.\nThe human body is split into 24 parts, each part is parametrized by `U` and `V`\ncoordinates, each taking values in `[0, 1]`.\n\n<div align=\"center\">\n  <img src=\"https://dl.fbaipublicfiles.com/densepose/web/coords.png\" width=\"400px\" />\n</div>\n<p class=\"image-caption\"><b>Figure 1.</b> Partitioning and parametrization of human body surface.</p>\n\nThe pipeline uses [Faster R-CNN](https://arxiv.org/abs/1506.01497)\nwith [Feature Pyramid Network](https://arxiv.org/abs/1612.03144) meta architecture\noutlined in Figure 2. For each detected object, the model predicts\nits coarse segmentation `S` (2 or 15 channels: foreground / background or\nbackground + 14 predefined body parts), fine segmentation `I` (25 channels:\nbackground + 24 predefined body parts) and local chart coordinates `U` and `V`.\n\n<div align=\"center\">\n  <img src=\"https://dl.fbaipublicfiles.com/densepose/web/densepose_pipeline_iuv.png\" width=\"500px\" />\n</div>\n<p class=\"image-caption\"><b>Figure 2.</b> DensePose chart-based architecture based on Faster R-CNN with Feature Pyramid Network (FPN).</p>\n\n### <a name=\"Bootstrap\"></a> Bootstrapping Chart-Based Models\n\n[Sanakoyeu et al., 2020](https://arxiv.org/pdf/2003.00080.pdf) introduced a pipeline\nto transfer DensePose models trained on humans to proximal animal classes (chimpanzees),\nwhich is summarized in Figure 3. The training proceeds in two stages:\n\nFirst, a *master* model is trained on data from source domain (humans with full\nDensePose annotation `S`, `I`, `U` and `V`)\nand supporting domain (animals with segmentation annotation only).\nOnly selected animal classes are chosen from the supporting\ndomain through *category filters* to guarantee the quality of target domain results.\nThe training is done in *class-agnostic manner*: all selected categories are mapped\nto a single category (human).\n\nSecond, a *student* model is trained on data from source and supporting domains,\nas well as data from target domain obtained by applying the master model, selecting\nhigh-confidence detections and sampling the results.\n\n<div align=\"center\">\n  <img src=\"https://dl.fbaipublicfiles.com/densepose/web/densepose_pipeline_bootstrap_iuv.png\" width=\"1000px\" />\n</div>\n<p class=\"image-caption\"><b>Figure 3.</b> Domain adaptation: <i>master</i> model is trained on data from source and\nsupporting domains to produce predictions in target domain; <i>student</i> model combines data from source and\nsupporting domains, as well as sampled predictions from the master model on target domain to improve\ntarget domain predictions quality.</p>\n\nExamples of pretrained master and student models are available in the [Model Zoo](#ModelZooBootstrap).\nFor more details on the bootstrapping pipeline, please see [Bootstrapping Pipeline](BOOTSTRAPPING_PIPELINE.md).\n\n### Datasets\n\nFor more details on datasets used for chart-based model training and validation,\nplease refer to the [DensePose Datasets](DENSEPOSE_DATASETS.md) page.\n\n## <a name=\"ModelZoo\"></a> Model Zoo and Baselines\n\n### Legacy Models\n\nBaselines trained using schedules from [Güler et al, 2018](https://arxiv.org/pdf/1802.00434.pdf)\n\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Name</th>\n<th valign=\"bottom\">lr<br/>sched</th>\n<th valign=\"bottom\">train<br/>time<br/>(s/iter)</th>\n<th valign=\"bottom\">inference<br/>time<br/>(s/im)</th>\n<th valign=\"bottom\">train<br/>mem<br/>(GB)</th>\n<th valign=\"bottom\">box<br/>AP</th>\n<th valign=\"bottom\">segm<br/>AP</th>\n<th valign=\"bottom\">dp. AP<br/>GPS</th>\n<th valign=\"bottom\">dp. AP<br/>GPSm</th>\n<th valign=\"bottom\">model id</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n<!-- ROW: densepose_rcnn_R_50_FPN_s1x_legacy -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_50_FPN_s1x_legacy.yaml\">R_50_FPN_s1x_legacy</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.307</td>\n<td align=\"center\">0.051</td>\n<td align=\"center\">3.2</td>\n<td align=\"center\">58.1</td>\n<td align=\"center\">58.2</td>\n<td align=\"center\">52.1</td>\n<td align=\"center\">54.9</td>\n<td align=\"center\">164832157</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_s1x_legacy/164832157/model_final_d366fa.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_s1x_legacy/164832157/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_101_FPN_s1x_legacy -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_101_FPN_s1x_legacy.yaml\">R_101_FPN_s1x_legacy</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.390</td>\n<td align=\"center\">0.063</td>\n<td align=\"center\">4.3</td>\n<td align=\"center\">59.5</td>\n<td align=\"center\">59.3</td>\n<td align=\"center\">53.2</td>\n<td align=\"center\">56.0</td>\n<td align=\"center\">164832182</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_s1x_legacy/164832182/model_final_10af0e.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_s1x_legacy/164832182/metrics.json\">metrics</a></td>\n</tr>\n</tbody></table>\n\n### Improved Baselines, Original Fully Convolutional Head\n\nThese models use an improved training schedule and Panoptic FPN head from [Kirillov et al, 2019](https://arxiv.org/abs/1901.02446).\n\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Name</th>\n<th valign=\"bottom\">lr<br/>sched</th>\n<th valign=\"bottom\">train<br/>time<br/>(s/iter)</th>\n<th valign=\"bottom\">inference<br/>time<br/>(s/im)</th>\n<th valign=\"bottom\">train<br/>mem<br/>(GB)</th>\n<th valign=\"bottom\">box<br/>AP</th>\n<th valign=\"bottom\">segm<br/>AP</th>\n<th valign=\"bottom\">dp. AP<br/>GPS</th>\n<th valign=\"bottom\">dp. AP<br/>GPSm</th>\n<th valign=\"bottom\">model id</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n<!-- ROW: densepose_rcnn_R_50_FPN_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_50_FPN_s1x.yaml\">R_50_FPN_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.359</td>\n<td align=\"center\">0.066</td>\n<td align=\"center\">4.5</td>\n<td align=\"center\">61.2</td>\n<td align=\"center\">67.2</td>\n<td align=\"center\">63.7</td>\n<td align=\"center\">65.3</td>\n<td align=\"center\">165712039</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_s1x/165712039/model_final_162be9.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_s1x/165712039/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_101_FPN_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_101_FPN_s1x.yaml\">R_101_FPN_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.428</td>\n<td align=\"center\">0.079</td>\n<td align=\"center\">5.8</td>\n<td align=\"center\">62.3</td>\n<td align=\"center\">67.8</td>\n<td align=\"center\">64.5</td>\n<td align=\"center\">66.2</td>\n<td align=\"center\">165712084</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_s1x/165712084/model_final_c6ab63.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_s1x/165712084/metrics.json\">metrics</a></td>\n</tr>\n</tbody></table>\n\n### <a name=\"ModelZooDeepLabV3\"> Improved Baselines, DeepLabV3 Head\n\nThese models use an improved training schedule, Panoptic FPN head from [Kirillov et al, 2019](https://arxiv.org/abs/1901.02446) and DeepLabV3 head from [Chen et al, 2017](https://arxiv.org/abs/1706.05587).\n\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Name</th>\n<th valign=\"bottom\">lr<br/>sched</th>\n<th valign=\"bottom\">train<br/>time<br/>(s/iter)</th>\n<th valign=\"bottom\">inference<br/>time<br/>(s/im)</th>\n<th valign=\"bottom\">train<br/>mem<br/>(GB)</th>\n<th valign=\"bottom\">box<br/>AP</th>\n<th valign=\"bottom\">segm<br/>AP</th>\n<th valign=\"bottom\">dp. AP<br/>GPS</th>\n<th valign=\"bottom\">dp. AP<br/>GPSm</th>\n<th valign=\"bottom\">model id</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n<!-- ROW: densepose_rcnn_R_50_FPN_DL_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_50_FPN_DL_s1x.yaml\">R_50_FPN_DL_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.392</td>\n<td align=\"center\">0.070</td>\n<td align=\"center\">6.7</td>\n<td align=\"center\">61.1</td>\n<td align=\"center\">68.3</td>\n<td align=\"center\">65.6</td>\n<td align=\"center\">66.7</td>\n<td align=\"center\">165712097</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_DL_s1x/165712097/model_final_0ed407.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_DL_s1x/165712097/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_101_FPN_DL_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_101_FPN_DL_s1x.yaml\">R_101_FPN_DL_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.478</td>\n<td align=\"center\">0.083</td>\n<td align=\"center\">7.0</td>\n<td align=\"center\">62.3</td>\n<td align=\"center\">68.7</td>\n<td align=\"center\">66.3</td>\n<td align=\"center\">67.6</td>\n<td align=\"center\">165712116</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_DL_s1x/165712116/model_final_844d15.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_DL_s1x/165712116/metrics.json\">metrics</a></td>\n</tr>\n</tbody></table>\n\n### <a name=\"ModelZooConfidence\"> Baselines with Confidence Estimation\n\nThese models perform additional estimation of confidence in regressed UV coodrinates, along the lines of [Neverova et al., 2019](https://papers.nips.cc/paper/8378-correlated-uncertainty-for-learning-dense-correspondences-from-noisy-labels).\n\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Name</th>\n<th valign=\"bottom\">lr<br/>sched</th>\n<th valign=\"bottom\">train<br/>time<br/>(s/iter)</th>\n<th valign=\"bottom\">inference<br/>time<br/>(s/im)</th>\n<th valign=\"bottom\">train<br/>mem<br/>(GB)</th>\n<th valign=\"bottom\">box<br/>AP</th>\n<th valign=\"bottom\">segm<br/>AP</th>\n<th valign=\"bottom\">dp. AP<br/>GPS</th>\n<th valign=\"bottom\">dp. AP<br/>GPSm</th>\n<th valign=\"bottom\">model id</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n<!-- ROW: densepose_rcnn_R_50_FPN_WC1_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_50_FPN_WC1_s1x.yaml\">R_50_FPN_WC1_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.353</td>\n<td align=\"center\">0.064</td>\n<td align=\"center\">4.6</td>\n<td align=\"center\">60.5</td>\n<td align=\"center\">67.0</td>\n<td align=\"center\">64.2</td>\n<td align=\"center\">65.4</td>\n<td align=\"center\">173862049</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_WC1_s1x/173862049/model_final_289019.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_WC1_s1x/173862049/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_50_FPN_WC2_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_50_FPN_WC2_s1x.yaml\">R_50_FPN_WC2_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.364</td>\n<td align=\"center\">0.066</td>\n<td align=\"center\">4.8</td>\n<td align=\"center\">60.7</td>\n<td align=\"center\">66.9</td>\n<td align=\"center\">64.2</td>\n<td align=\"center\">65.7</td>\n<td align=\"center\">173861455</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_WC2_s1x/173861455/model_final_3abe14.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_WC2_s1x/173861455/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_50_FPN_DL_WC1_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_50_FPN_DL_WC1_s1x.yaml\">R_50_FPN_DL_WC1_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.397</td>\n<td align=\"center\">0.068</td>\n<td align=\"center\">6.7</td>\n<td align=\"center\">61.1</td>\n<td align=\"center\">68.1</td>\n<td align=\"center\">65.8</td>\n<td align=\"center\">67.0</td>\n<td align=\"center\">173067973</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_DL_WC1_s1x/173067973/model_final_b1e525.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_DL_WC1_s1x/173067973/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_50_FPN_DL_WC2_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_50_FPN_DL_WC2_s1x.yaml\">R_50_FPN_DL_WC2_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.410</td>\n<td align=\"center\">0.070</td>\n<td align=\"center\">6.8</td>\n<td align=\"center\">60.8</td>\n<td align=\"center\">67.9</td>\n<td align=\"center\">65.6</td>\n<td align=\"center\">66.7</td>\n<td align=\"center\">173859335</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_DL_WC2_s1x/173859335/model_final_60fed4.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_DL_WC2_s1x/173859335/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_101_FPN_WC1_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_101_FPN_WC1_s1x.yaml\">R_101_FPN_WC1_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.435</td>\n<td align=\"center\">0.076</td>\n<td align=\"center\">5.7</td>\n<td align=\"center\">62.5</td>\n<td align=\"center\">67.6</td>\n<td align=\"center\">64.9</td>\n<td align=\"center\">66.3</td>\n<td align=\"center\">171402969</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_WC1_s1x/171402969/model_final_9e47f0.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_WC1_s1x/171402969/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_101_FPN_WC2_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_101_FPN_WC2_s1x.yaml\">R_101_FPN_WC2_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.450</td>\n<td align=\"center\">0.078</td>\n<td align=\"center\">5.7</td>\n<td align=\"center\">62.3</td>\n<td align=\"center\">67.6</td>\n<td align=\"center\">64.8</td>\n<td align=\"center\">66.4</td>\n<td align=\"center\">173860702</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_WC2_s1x/173860702/model_final_5ea023.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_WC2_s1x/173860702/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_101_FPN_DL_WC1_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_101_FPN_DL_WC1_s1x.yaml\">R_101_FPN_DL_WC1_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.479</td>\n<td align=\"center\">0.081</td>\n<td align=\"center\">7.9</td>\n<td align=\"center\">62.0</td>\n<td align=\"center\">68.4</td>\n<td align=\"center\">66.2</td>\n<td align=\"center\">67.2</td>\n<td align=\"center\">173858525</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_DL_WC1_s1x/173858525/model_final_f359f3.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_DL_WC1_s1x/173858525/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_101_FPN_DL_WC2_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_101_FPN_DL_WC2_s1x.yaml\">R_101_FPN_DL_WC2_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.491</td>\n<td align=\"center\">0.082</td>\n<td align=\"center\">7.6</td>\n<td align=\"center\">61.7</td>\n<td align=\"center\">68.3</td>\n<td align=\"center\">65.9</td>\n<td align=\"center\">67.2</td>\n<td align=\"center\">173294801</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_DL_WC2_s1x/173294801/model_final_6e1ed1.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_DL_WC2_s1x/173294801/metrics.json\">metrics</a></td>\n</tr>\n</tbody></table>\n\nAcronyms:\n\n`WC1`: with confidence estimation model type 1 for `U` and `V`\n\n`WC2`: with confidence estimation model type 2 for `U` and `V`\n\n### <a name=\"ModelZooMaskConfidence\"> Baselines with Mask Confidence Estimation\n\nModels that perform estimation of confidence in regressed UV coodrinates\nas well as confidences associated with coarse and fine segmentation,\nsee [Sanakoyeu et al., 2020](https://arxiv.org/pdf/2003.00080.pdf) for details.\n\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Name</th>\n<th valign=\"bottom\">lr<br/>sched</th>\n<th valign=\"bottom\">train<br/>time<br/>(s/iter)</th>\n<th valign=\"bottom\">inference<br/>time<br/>(s/im)</th>\n<th valign=\"bottom\">train<br/>mem<br/>(GB)</th>\n<th valign=\"bottom\">box<br/>AP</th>\n<th valign=\"bottom\">segm<br/>AP</th>\n<th valign=\"bottom\">dp. AP<br/>GPS</th>\n<th valign=\"bottom\">dp. AP<br/>GPSm</th>\n<th valign=\"bottom\">model id</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n<!-- ROW: densepose_rcnn_R_50_FPN_WC1M_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_50_FPN_WC1M_s1x.yaml\">R_50_FPN_WC1M_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.381</td>\n<td align=\"center\">0.066</td>\n<td align=\"center\">4.8</td>\n<td align=\"center\">60.6</td>\n<td align=\"center\">66.7</td>\n<td align=\"center\">64.0</td>\n<td align=\"center\">65.4</td>\n<td align=\"center\">217144516</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_WC1M_s1x/217144516/model_final_48a9d9.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_WC1M_s1x/217144516/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_50_FPN_WC2M_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_50_FPN_WC2M_s1x.yaml\">R_50_FPN_WC2M_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.342</td>\n<td align=\"center\">0.068</td>\n<td align=\"center\">5.0</td>\n<td align=\"center\">60.7</td>\n<td align=\"center\">66.9</td>\n<td align=\"center\">64.2</td>\n<td align=\"center\">65.5</td>\n<td align=\"center\">216245640</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_WC2M_s1x/216245640/model_final_d79ada.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_WC2M_s1x/216245640/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_50_FPN_DL_WC1M_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_50_FPN_DL_WC1M_s1x.yaml\">R_50_FPN_DL_WC1M_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.371</td>\n<td align=\"center\">0.068</td>\n<td align=\"center\">6.0</td>\n<td align=\"center\">60.7</td>\n<td align=\"center\">68.0</td>\n<td align=\"center\">65.2</td>\n<td align=\"center\">66.7</td>\n<td align=\"center\">216245703</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_DL_WC1M_s1x/216245703/model_final_61971e.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_DL_WC1M_s1x/216245703/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_50_FPN_DL_WC2M_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_50_FPN_DL_WC2M_s1x.yaml\">R_50_FPN_DL_WC2M_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.385</td>\n<td align=\"center\">0.071</td>\n<td align=\"center\">6.1</td>\n<td align=\"center\">60.8</td>\n<td align=\"center\">68.1</td>\n<td align=\"center\">65.0</td>\n<td align=\"center\">66.4</td>\n<td align=\"center\">216245758</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_DL_WC2M_s1x/216245758/model_final_7bfb43.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_DL_WC2M_s1x/216245758/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_101_FPN_WC1M_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_101_FPN_WC1M_s1x.yaml\">R_101_FPN_WC1M_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.423</td>\n<td align=\"center\">0.079</td>\n<td align=\"center\">5.9</td>\n<td align=\"center\">62.0</td>\n<td align=\"center\">67.3</td>\n<td align=\"center\">64.8</td>\n<td align=\"center\">66.0</td>\n<td align=\"center\">216453687</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_WC1M_s1x/216453687/model_final_0a7287.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_WC1M_s1x/216453687/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_101_FPN_WC2M_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_101_FPN_WC2M_s1x.yaml\">R_101_FPN_WC2M_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.436</td>\n<td align=\"center\">0.080</td>\n<td align=\"center\">5.9</td>\n<td align=\"center\">62.5</td>\n<td align=\"center\">67.4</td>\n<td align=\"center\">64.5</td>\n<td align=\"center\">66.0</td>\n<td align=\"center\">216245682</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_WC2M_s1x/216245682/model_final_e354d9.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_WC2M_s1x/216245682/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_101_FPN_DL_WC1M_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_101_FPN_DL_WC1M_s1x.yaml\">R_101_FPN_DL_WC1M_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.453</td>\n<td align=\"center\">0.079</td>\n<td align=\"center\">6.8</td>\n<td align=\"center\">62.0</td>\n<td align=\"center\">68.1</td>\n<td align=\"center\">66.4</td>\n<td align=\"center\">67.1</td>\n<td align=\"center\">216245771</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_DL_WC1M_s1x/216245771/model_final_0ebeb3.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_DL_WC1M_s1x/216245771/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_rcnn_R_101_FPN_DL_WC2M_s1x -->\n<tr><td align=\"left\"><a href=\"../configs/densepose_rcnn_R_101_FPN_DL_WC2M_s1x.yaml\">R_101_FPN_DL_WC2M_s1x</a></td>\n<td align=\"center\">s1x</td>\n<td align=\"center\">0.464</td>\n<td align=\"center\">0.080</td>\n<td align=\"center\">6.9</td>\n<td align=\"center\">61.9</td>\n<td align=\"center\">68.2</td>\n<td align=\"center\">66.1</td>\n<td align=\"center\">67.1</td>\n<td align=\"center\">216245790</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_DL_WC2M_s1x/216245790/model_final_de6e7a.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_101_FPN_DL_WC2M_s1x/216245790/metrics.json\">metrics</a></td>\n</tr>\n</tbody></table>\n\nAcronyms:\n\n`WC1M`: with confidence estimation model type 1 for `U` and `V` and mask confidence estimation\n\n`WC2M`: with confidence estimation model type 2 for `U` and `V` and mask confidence estimation\n\n### <a name=\"ModelZooBootstrap\"></a> Bootstrapping Baselines\n\nMaster and student models trained using the bootstrapping pipeline with chimpanzee as the target category,\nsee [Sanakoyeu et al., 2020](https://arxiv.org/pdf/2003.00080.pdf)\nand [Bootstrapping Pipeline](BOOTSTRAPPING_PIPELINE.md) for details.\nEvaluation is performed on [DensePose Chimps](DENSEPOSE_DATASETS.md#densepose-chimps) dataset.\n\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Name</th>\n<th valign=\"bottom\">lr<br/>sched</th>\n<th valign=\"bottom\">train<br/>time<br/>(s/iter)</th>\n<th valign=\"bottom\">inference<br/>time<br/>(s/im)</th>\n<th valign=\"bottom\">train<br/>mem<br/>(GB)</th>\n<th valign=\"bottom\">box<br/>AP</th>\n<th valign=\"bottom\">segm<br/>AP</th>\n<th valign=\"bottom\">dp. APex<br/>GPS</th>\n<th valign=\"bottom\">dp. AP<br/>GPS</th>\n<th valign=\"bottom\">dp. AP<br/>GPSm</th>\n<th valign=\"bottom\">model id</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n<!-- ROW: densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA -->\n<tr><td align=\"left\"><a href=\"../configs/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA.yaml\">R_50_FPN_DL_WC1M_3x_Atop10P_CA</a></td>\n<td align=\"center\">3x</td>\n<td align=\"center\">0.522</td>\n<td align=\"center\">0.073</td>\n<td align=\"center\">9.7</td>\n<td align=\"center\">61.3</td>\n<td align=\"center\">59.1</td>\n<td align=\"center\">36.2</td>\n<td align=\"center\">20.0</td>\n<td align=\"center\">30.2</td>\n<td align=\"center\">217578784</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA/217578784/model_final_9fe1cc.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10\nP_CA/217578784/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_uniform -->\n<tr><td align=\"left\"><a href=\"../configs/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_uniform.yaml\">R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_uniform</a></td>\n<td align=\"center\">3x</td>\n<td align=\"center\">1.939</td>\n<td align=\"center\">0.072</td>\n<td align=\"center\">10.1</td>\n<td align=\"center\">60.9</td>\n<td align=\"center\">58.5</td>\n<td align=\"center\">37.2</td>\n<td align=\"center\">21.5</td>\n<td align=\"center\">31.0</td>\n<td align=\"center\">256453729</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_uniform/256453729/model_final_241ff5.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_uniform/256453729/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_uv -->\n<tr><td align=\"left\"><a href=\"../configs/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_uv.yaml\">R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_uv</a></td>\n<td align=\"center\">3x</td>\n<td align=\"center\">1.985</td>\n<td align=\"center\">0.072</td>\n<td align=\"center\">9.6</td>\n<td align=\"center\">61.4</td>\n<td align=\"center\">58.9</td>\n<td align=\"center\">38.3</td>\n<td align=\"center\">22.2</td>\n<td align=\"center\">32.1</td>\n<td align=\"center\">256452095</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_uv/256452095/model_final_d689e2.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_uv/256452095/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_finesegm -->\n<tr><td align=\"left\"><a href=\"../configs/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_finesegm.yaml\">R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_finesegm</a></td>\n<td align=\"center\">3x</td>\n<td align=\"center\">2.047</td>\n<td align=\"center\">0.072</td>\n<td align=\"center\">10.3</td>\n<td align=\"center\">60.9</td>\n<td align=\"center\">58.5</td>\n<td align=\"center\">36.7</td>\n<td align=\"center\">20.7</td>\n<td align=\"center\">30.7</td>\n<td align=\"center\">256452819</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_finesegm/256452819/model_final_cb4ac6.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_finesegm/256452819/metrics.json\">metrics</a></td>\n</tr>\n<!-- ROW: densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_coarsesegm -->\n<tr><td align=\"left\"><a href=\"../configs/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_coarsesegm.yaml\">R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_coarsesegm</a></td>\n<td align=\"center\">3x</td>\n<td align=\"center\">1.830</td>\n<td align=\"center\">0.070</td>\n<td align=\"center\">9.6</td>\n<td align=\"center\">61.3</td>\n<td align=\"center\">59.2</td>\n<td align=\"center\">37.9</td>\n<td align=\"center\">21.5</td>\n<td align=\"center\">31.6</td>\n<td align=\"center\">256455697</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/densepose/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_coarsesegm/256455697/model_final_a6a4bf.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/densepose/evolution/densepose_R_50_FPN_DL_WC1M_3x_Atop10P_CA_B_coarsesegm/256455697/metrics.json\">metrics</a></td>\n</tr>\n</tbody></table>\n\nAcronyms:\n\n`WC1M`: with confidence estimation model type 1 for `U` and `V` and mask confidence estimation\n\n`Atop10P`: humans and animals from the 10 best suitable categories are used for training\n\n`CA`: class agnostic training, where all annotated instances are mapped into a single category\n\n`B_<...>`: schedule with bootstrapping with the specified results sampling strategy\n\nNote:\n\nThe relaxed `dp. APex GPS` metric was used in\n[Sanakoyeu et al., 2020](https://arxiv.org/pdf/2003.00080.pdf) to evaluate DensePose\nresults. This metric considers matches at thresholds 0.2, 0.3 and 0.4 additionally\nto the standard ones used in the evaluation protocol. The minimum threshold is\ncontrolled by `DENSEPOSE_EVALUATION.MIN_IOU_THRESHOLD` config option.\n\n### License\n\nAll models available for download are licensed under the\n[Creative Commons Attribution-ShareAlike 3.0 license](https://creativecommons.org/licenses/by-sa/3.0/)\n\n## <a name=\"References\"></a> References\n\nIf you use chart-based DensePose methods, please take the references from the following\nBibTeX entries:\n\nDensePose bootstrapping pipeline:\n```\n@InProceedings{Sanakoyeu2020TransferringDensePose,\n    title = {Transferring Dense Pose to Proximal Animal Classes},\n    author = {Artsiom Sanakoyeu and Vasil Khalidov and Maureen S. McCarthy and Andrea Vedaldi and Natalia Neverova},\n    journal = {The IEEE Conference on Computer Vision and Pattern Recognition (CVPR)},\n    year = {2020},\n}\n```\n\nDensePose with confidence estimation:\n```\n@InProceedings{Neverova2019DensePoseConfidences,\n    title = {Correlated Uncertainty for Learning Dense Correspondences from Noisy Labels},\n    author = {Neverova, Natalia and Novotny, David and Vedaldi, Andrea},\n    journal = {Advances in Neural Information Processing Systems},\n    year = {2019},\n}\n```\n\nOriginal DensePose:\n```\n@InProceedings{Guler2018DensePose,\n  title={DensePose: Dense Human Pose Estimation In The Wild},\n  author={R\\{i}za Alp G\\\"uler, Natalia Neverova, Iasonas Kokkinos},\n  journal={The IEEE Conference on Computer Vision and Pattern Recognition (CVPR)},\n  year={2018}\n}\n```\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/doc/GETTING_STARTED.md",
    "content": "# Getting Started with DensePose\n\n## Inference with Pre-trained Models\n\n1. Pick a model and its config file from [Model Zoo](MODEL_ZOO.md), for example [densepose_rcnn_R_50_FPN_s1x.yaml](../configs/densepose_rcnn_R_50_FPN_s1x.yaml)\n2. Run the [Apply Net](TOOL_APPLY_NET.md) tool to visualize the results or save the to disk. For example, to use contour visualization for DensePose, one can run:\n```bash\npython apply_net.py show configs/densepose_rcnn_R_50_FPN_s1x.yaml densepose_rcnn_R_50_FPN_s1x.pkl image.jpg dp_contour,bbox --output image_densepose_contour.png\n```\nPlease see [Apply Net](TOOL_APPLY_NET.md) for more details on the tool.\n\n## Training\n\nFirst, prepare the [dataset](http://densepose.org/#dataset) into the following structure under the directory you'll run training scripts:\n<pre>\ndatasets/coco/\n  annotations/\n    densepose_{train,minival,valminusminival}2014.json\n    <a href=\"https://dl.fbaipublicfiles.com/detectron2/densepose/densepose_minival2014_100.json\">densepose_minival2014_100.json </a>  (optional, for testing only)\n  {train,val}2014/\n    # image files that are mentioned in the corresponding json\n</pre>\n\nTo train a model one can use the [train_net.py](../train_net.py) script.\nThis script was used to train all DensePose models in [Model Zoo](MODEL_ZOO.md).\nFor example, to launch end-to-end DensePose-RCNN training with ResNet-50 FPN backbone\non 8 GPUs following the s1x schedule, one can run\n```bash\npython train_net.py --config-file configs/densepose_rcnn_R_50_FPN_s1x.yaml --num-gpus 8\n```\nThe configs are made for 8-GPU training. To train on 1 GPU, one can apply the\n[linear learning rate scaling rule](https://arxiv.org/abs/1706.02677):\n```bash\npython train_net.py --config-file configs/densepose_rcnn_R_50_FPN_s1x.yaml \\\n    SOLVER.IMS_PER_BATCH 2 SOLVER.BASE_LR 0.0025\n```\n\n## Evaluation\n\nModel testing can be done in the same way as training, except for an additional flag `--eval-only` and\nmodel location specification through `MODEL.WEIGHTS model.pth` in the command line\n```bash\npython train_net.py --config-file configs/densepose_rcnn_R_50_FPN_s1x.yaml \\\n    --eval-only MODEL.WEIGHTS model.pth\n```\n\n## Tools\n\nWe provide tools which allow one to:\n - easily view DensePose annotated data in a dataset;\n - perform DensePose inference on a set of images;\n - visualize DensePose model results;\n\n`query_db` is a tool to print or visualize DensePose data in a dataset.\nPlease refer to [Query DB](TOOL_QUERY_DB.md) for more details on this tool\n\n`apply_net` is a tool to print or visualize DensePose results.\nPlease refer to [Apply Net](TOOL_APPLY_NET.md) for more details on this tool\n\n\n## Installation as a package\n\nDensePose can also be installed as a Python package for integration with other software.\n\nThe following dependencies are needed:\n- Python >= 3.6\n- [PyTorch](https://pytorch.org/get-started/locally/#start-locally) >= 1.7 (to match [detectron2 requirements](https://detectron2.readthedocs.io/en/latest/tutorials/install.html#requirements))\n- [torchvision](https://pytorch.org/vision/stable/) version [compatible with your version of PyTorch](https://github.com/pytorch/vision#installation)\n\nDensePose can then be installed from this repository with:\n\n```\npip install git+https://github.com/facebookresearch/detectron2@main#subdirectory=projects/DensePose\n```\n\nAfter installation, the package will be importable as `densepose`.\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/doc/RELEASE_2020_04.md",
    "content": "# DensePose Confidence Estimation and Model Zoo Improvements\n\n* [DensePose models with confidence estimation](doc/DENSEPOSE_IUV.md#ModelZooConfidence)\n* [Panoptic FPN and DeepLabV3 head implementation](doc/DENSEPOSE_IUV.md#ModelZooDeepLabV3)\n* Test time augmentations for DensePose\n* New evaluation metric (GPSm) that yields more reliable scores\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/doc/RELEASE_2021_03.md",
    "content": "# DensePose CSE and DensePose Evolution\n\n* [DensePose Evolution pipeline](DENSEPOSE_IUV.md#ModelZooBootstrap), a framework to bootstrap\n  DensePose on unlabeled data\n  * [`InferenceBasedLoader`](../densepose/data/inference_based_loader.py)\n    with data samplers to use inference results from one model\n    to train another model (bootstrap);\n  * [`VideoKeyframeDataset`](../densepose/data/video/video_keyframe_dataset.py)\n    to efficiently load images from video keyframes;\n  * Category maps and filters to combine annotations from different categories\n    and train in a class-agnostic manner;\n  * [Pretrained models](DENSEPOSE_IUV.md#ModelZooBootstrap) for DensePose estimation on chimpanzees;\n  * DensePose head training from partial data (segmentation only);\n  * [DensePose models with mask confidence estimation](DENSEPOSE_IUV.md#ModelZooMaskConfidence);\n  * [DensePose Chimps]() dataset for IUV evaluation\n* [DensePose Continuous Surface Embeddings](DENSEPOSE_CSE.md), a framework to extend DensePose\n  to various categories using 3D models\n  * [Hard embedding](../densepose/modeling/losses/embed.py) and\n    [soft embedding](../densepose/modeling/losses/soft_embed.py)\n    losses to train universal positional embeddings;\n  * [Embedder](../(densepose/modeling/cse/embedder.py) to handle\n    mesh vertex embeddings;\n  * [Storage](../densepose/evaluation/tensor_storage.py) for evaluation with high volumes of data;\n  * [Pretrained models](DENSEPOSE_CSE.md#ModelZoo) for DensePose CSE estimation on humans and animals;\n  * [DensePose Chimps](DENSEPOSE_DATASETS.md#densepose-chimps) and\n    [DensePose LVIS](DENSEPOSE_DATASETS.md#densepose-lvis) datasets for CSE finetuning and evaluation;\n  * [Vertex and texture mapping visualizers](../densepose/vis/densepose_outputs_vertex.py);\n* Refactoring of all major components: losses, predictors, model outputs, model results, visualizers;\n  * Dedicated structures for [chart outputs](../densepose/structures/chart.py),\n    [chart outputs with confidences](../densepose/structures/chart_confidence.py),\n    [chart results](../densepose/structures/chart_result.py),\n    [CSE outputs](../densepose/structures/cse.py);\n  * Dedicated predictors for\n    [chart-based estimation](../densepose/modeling/predictors/chart.py),\n    [confidence estimation](../densepose/modeling/predictors/chart_confidence.py)\n    and [CSE estimation](../densepose/modeling/predictors/cse.py);\n  * Generic handling of various [conversions](../densepose/converters) (e.g. from outputs to results);\n  * Better organization of various [losses](../densepose/modeling/losses);\n  * Segregation of loss data accumulators for\n    [IUV setting](../densepose/modeling/losses/utils.py)\n    and [CSE setting](../densepose/modeling/losses/embed_utils.py);\n  * Splitting visualizers into separate modules;\n* [HRNet](../densepose/modeling/hrnet.py) and [HRFPN](../densepose/modeling/hrfpn.py) backbones;\n* [PoseTrack](DENSEPOSE_DATASETS.md#densepose-posetrack) dataset;\n* [IUV texture visualizer](../densepose/vis/densepose_results_textures.py)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/doc/RELEASE_2021_06.md",
    "content": "# DensePose CSE with Cycle Losses\n\nThis release follows the paper [Neverova et al, 2021]() and\nadds CSE datasets with more annotations, better CSE animal models\nto the model zoo, losses to ensure cycle consistency for models and mesh\nalignment evaluator. In particular:\n\n* [Pixel to shape](../densepose/modeling/losses/cycle_pix2shape.py) and [shape to shape](../densepose/modeling/losses/cycle_shape2shape.py) cycle consistency losses;\n* Mesh alignment [evaluator](../densepose/evaluation/mesh_alignment_evaluator.py);\n* Existing CSE datasets renamed to [ds1_train](https://dl.fbaipublicfiles.com/densepose/annotations/lvis/densepose_lvis_v1_ds1_train_v1.json) and [ds1_val](https://dl.fbaipublicfiles.com/densepose/annotations/lvis/densepose_lvis_v1_ds1_val_v1.json);\n* New CSE datasets [ds2_train](https://dl.fbaipublicfiles.com/densepose/annotations/lvis/densepose_lvis_v1_ds2_train_v1.json) and [ds2_val](https://dl.fbaipublicfiles.com/densepose/annotations/lvis/densepose_lvis_v1_ds2_val_v1.json) added;\n* Better CSE animal models trained with the 16k schedule added to the [model zoo](DENSEPOSE_CSE.md#animal-cse-models).\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/doc/TOOL_APPLY_NET.md",
    "content": "# Apply Net\n\n`apply_net` is a tool to print or visualize DensePose results on a set of images.\nIt has two modes: `dump` to save DensePose model results to a pickle file\nand `show` to visualize them on images.\n\nThe `image.jpg` file that is used as an example in this doc can be found [here](http://images.cocodataset.org/train2017/000000117508.jpg)\n\n## Dump Mode\n\nThe general command form is:\n```bash\npython apply_net.py dump [-h] [-v] [--output <dump_file>] <config> <model> <input>\n```\n\nThere are three mandatory arguments:\n - `<config>`, configuration file for a given model;\n - `<model>`, model file with trained parameters\n - `<input>`, input image file name, pattern or folder\n\nOne can additionally provide `--output` argument to define the output file name,\nwhich defaults to `output.pkl`.\n\n\nExamples:\n\n1. Dump results of the [R_50_FPN_s1x](https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_s1x/165712039/model_final_162be9.pkl) DensePose model for images in a folder `images` to file `dump.pkl`:\n```bash\npython apply_net.py dump configs/densepose_rcnn_R_50_FPN_s1x.yaml \\\nhttps://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_s1x/165712039/model_final_162be9.pkl \\\nimages --output dump.pkl -v\n```\n\n2. Dump results of the [R_50_FPN_s1x](https://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_s1x/165712039/model_final_162be9.pkl) DensePose model for images with file name matching a pattern `image*.jpg` to file `results.pkl`:\n```bash\npython apply_net.py dump configs/densepose_rcnn_R_50_FPN_s1x.yaml \\\nhttps://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_s1x/165712039/model_final_162be9.pkl \\\n\"image*.jpg\" --output results.pkl -v\n```\n\nIf you want to load the pickle file generated by the above command:\n```\n# make sure DensePose is in your PYTHONPATH, or use the following line to add it:\nsys.path.append(\"/your_detectron2_path/detectron2_repo/projects/DensePose/\")\n\nf = open('/your_result_path/results.pkl', 'rb')\ndata = pickle.load(f)\n```\n\nThe file `results.pkl` contains the list of results per image, for each image the result is a dictionary.\n\n**If you use a [IUV model](DENSEPOSE_IUV.md#-model-zoo-and-baselines)**, the dumped data will have the following format:\n\n```\ndata: [{'file_name': '/your_path/image1.jpg',\n        'scores': tensor([0.9884]),\n        'pred_boxes_XYXY': tensor([[ 69.6114,   0.0000, 706.9797, 706.0000]]),\n        'pred_densepose': [DensePoseChartResultWithConfidences(labels=tensor(...), uv=tensor(...), sigma_1=None,\n            sigma_2=None, kappa_u=None, kappa_v=None, fine_segm_confidence=None, coarse_segm_confidence=None),\n            DensePoseChartResultWithConfidences, ...]\n        }\n       {'file_name': '/your_path/image2.jpg',\n        'scores': tensor([0.9999, 0.5373, 0.3991]),\n        'pred_boxes_XYXY': tensor([[ 59.5734,   7.7535, 579.9311, 932.3619],\n                                   [612.9418, 686.1254, 612.9999, 704.6053],\n                                   [164.5081, 407.4034, 598.3944, 920.4266]]),\n        'pred_densepose': [DensePoseChartResultWithConfidences(labels=tensor(...), uv=tensor(...), sigma_1=None,\n            sigma_2=None, kappa_u=None, kappa_v=None, fine_segm_confidence=None, coarse_segm_confidence=None),\n            DensePoseChartResultWithConfidences, ...]\n        }]\n```\n\n`DensePoseChartResultWithConfidences` contains the following fields:\n- `labels` - a tensor of size `[H, W]` of type `torch.long` which contains fine segmentation labels (previously called `I`)\n- `uv` - a tensor of size `[2, H, W]` of type `torch.float` which contains `U` and `V` coordinates\n- various optional confidence-related fields (`sigma_1`, `sigma_2`, `kappa_u`, `kappa_v`, `fine_segm_confidence`, `coarse_segm_confidence`)\n\n\n**If you use a [CSE model](DENSEPOSE_CSE.md#-model-zoo-and-baselines)**, the dumped data will have the following format:\n```\ndata: [{'file_name': '/your_path/image1.jpg',\n        'scores': tensor([0.9984, 0.9961]),\n        'pred_boxes_XYXY': tensor([[480.0093, 461.0796, 698.3614, 696.1011],\n                                   [78.1589, 168.6614, 307.1287, 653.8522]]),\n        'pred_densepose': DensePoseEmbeddingPredictorOutput(embedding=tensor(...), coarse_segm=tensor(...))}\n        {'file_name': '/your_path/image2.jpg',\n        'scores': tensor([0.9189, 0.9491]),\n        'pred_boxes_XYXY': tensor([[734.9685, 534.2003, 287.3923, 254.8859],\n                                   [434.2853, 765.1219, 132.1029, 867.9283]]),\n        'pred_densepose': DensePoseEmbeddingPredictorOutput(embedding=tensor(...), coarse_segm=tensor(...))}]\n```\n\n`DensePoseEmbeddingPredictorOutput` contains the following fields:\n- `embedding` - a tensor of size `[N, D, sz, sz]` of type `torch.float`, which contains embeddings of size `D` of the `N` detections in the image\n- `coarse_segm` - a tensor of size `[N, 2, sz, sz]` of type `torch.float` which contains segmentation scores of the `N` detections in the image; e.g. a mask can be obtained by `coarse_segm.argmax(dim=1)`\n\n`sz` is a fixed size for the tensors; you can resize them to the size of the bounding box, if needed\n\nWe can use the following code, to parse the outputs of the first\ndetected instance on the first image (IUV model).\n```\nimg_id, instance_id = 0, 0  # Look at the first image and the first detected instance\nbbox_xyxy = data[img_id]['pred_boxes_XYXY'][instance_id]\nresult = data[img_id]['pred_densepose'][instance_id]\nuv = result.uv\n```\nThe array `bbox_xyxy` contains (x0, y0, x1, y1) of the bounding box.\n\n\n## Visualization Mode\n\nThe general command form is:\n```bash\npython apply_net.py show [-h] [-v] [--min_score <score>] [--nms_thresh <threshold>] [--output <image_file>] <config> <model> <input> <visualizations>\n```\n\nThere are four mandatory arguments:\n - `<config>`, configuration file for a given model;\n - `<model>`, model file with trained parameters\n - `<input>`, input image file name, pattern or folder\n - `<visualizations>`, visualizations specifier; currently available visualizations are:\n   * `bbox` - bounding boxes of detected persons;\n   * `dp_segm` - segmentation masks for detected persons;\n   * `dp_u` - each body part is colored according to the estimated values of the\n     U coordinate in part parameterization;\n   * `dp_v` - each body part is colored according to the estimated values of the\n     V coordinate in part parameterization;\n   * `dp_contour` - plots contours with color-coded U and V coordinates;\n   * `dp_iuv_texture` - transfers the texture from a given texture image file to detected instances, in IUV mode;\n   * `dp_vertex` - plots the rainbow visualization of the closest vertices prediction for a given mesh, in CSE mode;\n   * `dp_cse_texture` - transfers the texture from a given list of texture image files (one from each human or animal mesh) to detected instances, in CSE mode\n\n\nOne can additionally provide the following optional arguments:\n - `--min_score` to only show detections with sufficient scores that are not lower than provided value\n - `--nms_thresh` to additionally apply non-maximum suppression to detections at a given threshold\n - `--output` to define visualization file name template, which defaults to `output.png`.\n   To distinguish output file names for different images, the tool appends 1-based entry index,\n   e.g. output.0001.png, output.0002.png, etc...\n- `--texture_atlas` to define the texture atlas image for IUV texture transfer\n- `--texture_atlases_map` to define the texture atlas images map (a dictionary `{mesh name: texture atlas image}`) for CSE texture transfer\n\n\nThe following examples show how to output results of a DensePose model\nwith ResNet-50 FPN backbone using different visualizations for image `image.jpg`:\n\n1. Show bounding box and segmentation:\n```bash\npython apply_net.py show configs/densepose_rcnn_R_50_FPN_s1x.yaml \\\nhttps://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_s1x/165712039/model_final_162be9.pkl \\\nimage.jpg bbox,dp_segm -v\n```\n![Bounding Box + Segmentation Visualization](https://dl.fbaipublicfiles.com/densepose/web/apply_net/res_bbox_dp_segm.jpg)\n\n2. Show bounding box and estimated U coordinates for body parts:\n```bash\npython apply_net.py show configs/densepose_rcnn_R_50_FPN_s1x.yaml  \\\nhttps://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_s1x/165712039/model_final_162be9.pkl \\\nimage.jpg bbox,dp_u -v\n```\n![Bounding Box + U Coordinate Visualization](https://dl.fbaipublicfiles.com/densepose/web/apply_net/res_bbox_dp_u.jpg)\n\n3. Show bounding box and estimated V coordinates for body parts:\n```bash\npython apply_net.py show configs/densepose_rcnn_R_50_FPN_s1x.yaml  \\\nhttps://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_s1x/165712039/model_final_162be9.pkl \\\nimage.jpg bbox,dp_v -v\n```\n![Bounding Box + V Coordinate Visualization](https://dl.fbaipublicfiles.com/densepose/web/apply_net/res_bbox_dp_v.jpg)\n\n4. Show bounding box and estimated U and V coordinates via contour plots:\n```bash\npython apply_net.py show configs/densepose_rcnn_R_50_FPN_s1x.yaml  \\\nhttps://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_s1x/165712039/model_final_162be9.pkl \\\nimage.jpg dp_contour,bbox -v\n```\n![Bounding Box + Contour Visualization](https://dl.fbaipublicfiles.com/densepose/web/apply_net/res_bbox_dp_contour.jpg)\n\n5. Show bounding box and texture transfer:\n```bash\npython apply_net.py show configs/densepose_rcnn_R_50_FPN_s1x.yaml  \\\nhttps://dl.fbaipublicfiles.com/densepose/densepose_rcnn_R_50_FPN_s1x/165712039/model_final_162be9.pkl \\\nimage.jpg dp_iuv_texture,bbox --texture_atlas texture_from_SURREAL.jpg -v\n```\n![Bounding Box + IUV Texture Transfer Visualization](https://dl.fbaipublicfiles.com/densepose/web/apply_net/res_bbox_dp_iuv_texture.jpg)\n\n6. Show bounding box and CSE rainbow visualization:\n```bash\npython apply_net.py show configs/cse/densepose_rcnn_R_50_FPN_s1x.yaml  \\\nhttps://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_s1x/251155172/model_final_c4ea5f.pkl \\\nimage.jpg dp_vertex,bbox -v\n```\n![Bounding Box + CSE Rainbow Visualization](https://dl.fbaipublicfiles.com/densepose/web/apply_net/res_bbox_dp_vertex.jpg)\n\n7. Show bounding box and CSE texture transfer:\n```bash\npython apply_net.py show configs/cse/densepose_rcnn_R_50_FPN_s1x.yaml  \\\nhttps://dl.fbaipublicfiles.com/densepose/cse/densepose_rcnn_R_50_FPN_s1x/251155172/model_final_c4ea5f.pkl \\\nimage.jpg dp_cse_texture,bbox  --texture_atlases_map '{\"smpl_27554\": \"smpl_uvSnapshot_colors.jpg\"}' -v\n```\n![Bounding Box + CSE Texture Transfer Visualization](https://dl.fbaipublicfiles.com/densepose/web/apply_net/res_bbox_dp_cse_texture.jpg)\n\nThe texture files can be found in the `doc/images` folder\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/doc/TOOL_QUERY_DB.md",
    "content": "\n# Query Dataset\n\n`query_db` is a tool to print or visualize DensePose data from a dataset.\nIt has two modes: `print` and `show` to output dataset entries to standard\noutput or to visualize them on images.\n\n## Print Mode\n\nThe general command form is:\n```bash\npython query_db.py print [-h] [-v] [--max-entries N] <dataset> <selector>\n```\n\nThere are two mandatory arguments:\n - `<dataset>`, DensePose dataset specification, from which to select\n   the entries (e.g. `densepose_coco_2014_train`).\n - `<selector>`, dataset entry selector which can be a single specification,\n   or a comma-separated list of specifications of the form\n   `field[:type]=value` for exact match with the value\n   or `field[:type]=min-max` for a range of values\n\nOne can additionally limit the maximum number of entries to output\nby providing `--max-entries` argument.\n\nExamples:\n\n1. Output at most 10 first entries from the `densepose_coco_2014_train` dataset:\n```bash\npython query_db.py print densepose_coco_2014_train \\* --max-entries 10 -v\n```\n\n2. Output all entries with `file_name` equal to `COCO_train2014_000000000036.jpg`: \n```bash\npython query_db.py print densepose_coco_2014_train file_name=COCO_train2014_000000000036.jpg -v\n```\n\n3. Output all entries with `image_id` between 36 and 156:\n```bash\npython query_db.py print densepose_coco_2014_train image_id:int=36-156 -v\n```\n\n## Visualization Mode\n\nThe general command form is:\n```bash\npython query_db.py show [-h] [-v] [--max-entries N] [--output <image_file>] <dataset> <selector> <visualizations>\n```\n\nThere are three mandatory arguments:\n - `<dataset>`, DensePose dataset specification, from which to select\n   the entries (e.g. `densepose_coco_2014_train`).\n - `<selector>`, dataset entry selector which can be a single specification,\n   or a comma-separated list of specifications of the form\n   `field[:type]=value` for exact match with the value\n   or `field[:type]=min-max` for a range of values\n - `<visualizations>`, visualizations specifier; currently available visualizations are:\n   * `bbox` - bounding boxes of annotated persons;\n   * `dp_i` - annotated points colored according to the containing part;\n   * `dp_pts` - annotated points in green color;\n   * `dp_segm` - segmentation masks for annotated persons;\n   * `dp_u` - annotated points colored according to their U coordinate in part parameterization;\n   * `dp_v` - annotated points colored according to their V coordinate in part parameterization;\n\nOne can additionally provide one of the two optional arguments:\n - `--max_entries` to limit the maximum number of entries to visualize\n - `--output` to provide visualization file name template, which defaults\n   to `output.png`. To distinguish file names for different dataset\n   entries, the tool appends 1-based entry index to the output file name,\n   e.g. output.0001.png, output.0002.png, etc.\n\nThe following examples show how to output different visualizations for image with `id = 322`\nfrom `densepose_coco_2014_train` dataset:\n\n1. Show bounding box and segmentation:\n```bash\npython query_db.py show densepose_coco_2014_train image_id:int=322 bbox,dp_segm -v\n```\n![Bounding Box + Segmentation Visualization](images/vis_bbox_dp_segm.jpg)\n\n2. Show bounding box and points colored according to the containing part:\n```bash\npython query_db.py show densepose_coco_2014_train image_id:int=322 bbox,dp_i -v\n```\n![Bounding Box + Point Label Visualization](images/vis_bbox_dp_i.jpg)\n\n3. Show bounding box and annotated points in green color:\n```bash\npython query_db.py show densepose_coco_2014_train image_id:int=322 bbox,dp_segm -v\n```\n![Bounding Box + Point Visualization](images/vis_bbox_dp_pts.jpg)\n\n4. Show bounding box and annotated points colored according to their U coordinate in part parameterization:\n```bash\npython query_db.py show densepose_coco_2014_train image_id:int=322 bbox,dp_u -v\n```\n![Bounding Box + Point U Visualization](images/vis_bbox_dp_u.jpg)\n\n5. Show bounding box and annotated points colored according to their V coordinate in part parameterization:\n```bash\npython query_db.py show densepose_coco_2014_train image_id:int=322 bbox,dp_v -v\n```\n![Bounding Box + Point V Visualization](images/vis_bbox_dp_v.jpg)\n\n\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/query_db.py",
    "content": "#!/usr/bin/env python3\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport argparse\nimport logging\nimport os\nimport sys\nfrom timeit import default_timer as timer\nfrom typing import Any, ClassVar, Dict, List\nimport torch\n\nfrom detectron2.data.catalog import DatasetCatalog\nfrom detectron2.utils.file_io import PathManager\nfrom detectron2.utils.logger import setup_logger\n\nfrom densepose.structures import DensePoseDataRelative\nfrom densepose.utils.dbhelper import EntrySelector\nfrom densepose.utils.logger import verbosity_to_level\nfrom densepose.vis.base import CompoundVisualizer\nfrom densepose.vis.bounding_box import BoundingBoxVisualizer\nfrom densepose.vis.densepose_data_points import (\n    DensePoseDataCoarseSegmentationVisualizer,\n    DensePoseDataPointsIVisualizer,\n    DensePoseDataPointsUVisualizer,\n    DensePoseDataPointsVisualizer,\n    DensePoseDataPointsVVisualizer,\n)\n\nDOC = \"\"\"Query DB - a tool to print / visualize data from a database\n\"\"\"\n\nLOGGER_NAME = \"query_db\"\n\nlogger = logging.getLogger(LOGGER_NAME)\n\n_ACTION_REGISTRY: Dict[str, \"Action\"] = {}\n\n\nclass Action(object):\n    @classmethod\n    def add_arguments(cls: type, parser: argparse.ArgumentParser):\n        parser.add_argument(\n            \"-v\",\n            \"--verbosity\",\n            action=\"count\",\n            help=\"Verbose mode. Multiple -v options increase the verbosity.\",\n        )\n\n\ndef register_action(cls: type):\n    \"\"\"\n    Decorator for action classes to automate action registration\n    \"\"\"\n    global _ACTION_REGISTRY\n    _ACTION_REGISTRY[cls.COMMAND] = cls\n    return cls\n\n\nclass EntrywiseAction(Action):\n    @classmethod\n    def add_arguments(cls: type, parser: argparse.ArgumentParser):\n        super(EntrywiseAction, cls).add_arguments(parser)\n        parser.add_argument(\n            \"dataset\", metavar=\"<dataset>\", help=\"Dataset name (e.g. densepose_coco_2014_train)\"\n        )\n        parser.add_argument(\n            \"selector\",\n            metavar=\"<selector>\",\n            help=\"Dataset entry selector in the form field1[:type]=value1[,\"\n            \"field2[:type]=value_min-value_max...] which selects all \"\n            \"entries from the dataset that satisfy the constraints\",\n        )\n        parser.add_argument(\n            \"--max-entries\", metavar=\"N\", help=\"Maximum number of entries to process\", type=int\n        )\n\n    @classmethod\n    def execute(cls: type, args: argparse.Namespace):\n        dataset = setup_dataset(args.dataset)\n        entry_selector = EntrySelector.from_string(args.selector)\n        context = cls.create_context(args)\n        if args.max_entries is not None:\n            for _, entry in zip(range(args.max_entries), dataset):\n                if entry_selector(entry):\n                    cls.execute_on_entry(entry, context)\n        else:\n            for entry in dataset:\n                if entry_selector(entry):\n                    cls.execute_on_entry(entry, context)\n\n    @classmethod\n    def create_context(cls: type, args: argparse.Namespace) -> Dict[str, Any]:\n        context = {}\n        return context\n\n\n@register_action\nclass PrintAction(EntrywiseAction):\n    \"\"\"\n    Print action that outputs selected entries to stdout\n    \"\"\"\n\n    COMMAND: ClassVar[str] = \"print\"\n\n    @classmethod\n    def add_parser(cls: type, subparsers: argparse._SubParsersAction):\n        parser = subparsers.add_parser(cls.COMMAND, help=\"Output selected entries to stdout. \")\n        cls.add_arguments(parser)\n        parser.set_defaults(func=cls.execute)\n\n    @classmethod\n    def add_arguments(cls: type, parser: argparse.ArgumentParser):\n        super(PrintAction, cls).add_arguments(parser)\n\n    @classmethod\n    def execute_on_entry(cls: type, entry: Dict[str, Any], context: Dict[str, Any]):\n        import pprint\n\n        printer = pprint.PrettyPrinter(indent=2, width=200, compact=True)\n        printer.pprint(entry)\n\n\n@register_action\nclass ShowAction(EntrywiseAction):\n    \"\"\"\n    Show action that visualizes selected entries on an image\n    \"\"\"\n\n    COMMAND: ClassVar[str] = \"show\"\n    VISUALIZERS: ClassVar[Dict[str, object]] = {\n        \"dp_segm\": DensePoseDataCoarseSegmentationVisualizer(),\n        \"dp_i\": DensePoseDataPointsIVisualizer(),\n        \"dp_u\": DensePoseDataPointsUVisualizer(),\n        \"dp_v\": DensePoseDataPointsVVisualizer(),\n        \"dp_pts\": DensePoseDataPointsVisualizer(),\n        \"bbox\": BoundingBoxVisualizer(),\n    }\n\n    @classmethod\n    def add_parser(cls: type, subparsers: argparse._SubParsersAction):\n        parser = subparsers.add_parser(cls.COMMAND, help=\"Visualize selected entries\")\n        cls.add_arguments(parser)\n        parser.set_defaults(func=cls.execute)\n\n    @classmethod\n    def add_arguments(cls: type, parser: argparse.ArgumentParser):\n        super(ShowAction, cls).add_arguments(parser)\n        parser.add_argument(\n            \"visualizations\",\n            metavar=\"<visualizations>\",\n            help=\"Comma separated list of visualizations, possible values: \"\n            \"[{}]\".format(\",\".join(sorted(cls.VISUALIZERS.keys()))),\n        )\n        parser.add_argument(\n            \"--output\",\n            metavar=\"<image_file>\",\n            default=\"output.png\",\n            help=\"File name to save output to\",\n        )\n\n    @classmethod\n    def execute_on_entry(cls: type, entry: Dict[str, Any], context: Dict[str, Any]):\n        import cv2\n        import numpy as np\n\n        image_fpath = PathManager.get_local_path(entry[\"file_name\"])\n        image = cv2.imread(image_fpath, cv2.IMREAD_GRAYSCALE)\n        image = np.tile(image[:, :, np.newaxis], [1, 1, 3])\n        datas = cls._extract_data_for_visualizers_from_entry(context[\"vis_specs\"], entry)\n        visualizer = context[\"visualizer\"]\n        image_vis = visualizer.visualize(image, datas)\n        entry_idx = context[\"entry_idx\"] + 1\n        out_fname = cls._get_out_fname(entry_idx, context[\"out_fname\"])\n        cv2.imwrite(out_fname, image_vis)\n        logger.info(f\"Output saved to {out_fname}\")\n        context[\"entry_idx\"] += 1\n\n    @classmethod\n    def _get_out_fname(cls: type, entry_idx: int, fname_base: str):\n        base, ext = os.path.splitext(fname_base)\n        return base + \".{0:04d}\".format(entry_idx) + ext\n\n    @classmethod\n    def create_context(cls: type, args: argparse.Namespace) -> Dict[str, Any]:\n        vis_specs = args.visualizations.split(\",\")\n        visualizers = []\n        for vis_spec in vis_specs:\n            vis = cls.VISUALIZERS[vis_spec]\n            visualizers.append(vis)\n        context = {\n            \"vis_specs\": vis_specs,\n            \"visualizer\": CompoundVisualizer(visualizers),\n            \"out_fname\": args.output,\n            \"entry_idx\": 0,\n        }\n        return context\n\n    @classmethod\n    def _extract_data_for_visualizers_from_entry(\n        cls: type, vis_specs: List[str], entry: Dict[str, Any]\n    ):\n        dp_list = []\n        bbox_list = []\n        for annotation in entry[\"annotations\"]:\n            is_valid, _ = DensePoseDataRelative.validate_annotation(annotation)\n            if not is_valid:\n                continue\n            bbox = torch.as_tensor(annotation[\"bbox\"])\n            bbox_list.append(bbox)\n            dp_data = DensePoseDataRelative(annotation)\n            dp_list.append(dp_data)\n        datas = []\n        for vis_spec in vis_specs:\n            datas.append(bbox_list if \"bbox\" == vis_spec else (bbox_list, dp_list))\n        return datas\n\n\ndef setup_dataset(dataset_name):\n    logger.info(\"Loading dataset {}\".format(dataset_name))\n    start = timer()\n    dataset = DatasetCatalog.get(dataset_name)\n    stop = timer()\n    logger.info(\"Loaded dataset {} in {:.3f}s\".format(dataset_name, stop - start))\n    return dataset\n\n\ndef create_argument_parser() -> argparse.ArgumentParser:\n    parser = argparse.ArgumentParser(\n        description=DOC,\n        formatter_class=lambda prog: argparse.HelpFormatter(prog, max_help_position=120),\n    )\n    parser.set_defaults(func=lambda _: parser.print_help(sys.stdout))\n    subparsers = parser.add_subparsers(title=\"Actions\")\n    for _, action in _ACTION_REGISTRY.items():\n        action.add_parser(subparsers)\n    return parser\n\n\ndef main():\n    parser = create_argument_parser()\n    args = parser.parse_args()\n    verbosity = args.verbosity if hasattr(args, \"verbosity\") else None\n    global logger\n    logger = setup_logger(name=LOGGER_NAME)\n    logger.setLevel(verbosity_to_level(verbosity))\n    args.func(args)\n\n\nif __name__ == \"__main__\":\n    main()\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/setup.py",
    "content": "import re\nfrom pathlib import Path\nfrom setuptools import find_packages, setup\n\ntry:\n    import torch  # noqa: F401\nexcept ImportError as e:\n    raise Exception(\n        \"\"\"\nYou must install PyTorch prior to installing DensePose:\npip install torch\n\nFor more information:\n    https://pytorch.org/get-started/locally/\n    \"\"\"\n    ) from e\n\n\ndef get_detectron2_current_version():\n    \"\"\"Version is not available for import through Python since it is\n    above the top level of the package. Instead, we parse it from the\n    file with a regex.\"\"\"\n    # Get version info from detectron2 __init__.py\n    version_source = (Path(__file__).parents[2] / \"detectron2\" / \"__init__.py\").read_text()\n    version_number = re.findall(r'__version__ = \"([0-9\\.]+)\"', version_source)[0]\n    return version_number\n\n\nsetup(\n    name=\"detectron2-densepose\",\n    author=\"FAIR\",\n    version=get_detectron2_current_version(),\n    url=\"https://github.com/facebookresearch/detectron2/tree/main/projects/DensePose\",\n    packages=find_packages(),\n    python_requires=\">=3.6\",\n    install_requires=[\n        \"av>=8.0.3\",\n        \"detectron2@git+https://github.com/facebookresearch/detectron2.git\",\n        \"opencv-python-headless>=4.5.3.56\",\n        \"scipy>=1.5.4\",\n    ],\n)\n"
  },
  {
    "path": "VPS_Module/projects/DensePose/train_net.py",
    "content": "#!/usr/bin/env python3\n# Copyright (c) Facebook, Inc. and its affiliates.\n\n\"\"\"\nDensePose Training Script.\n\nThis script is similar to the training script in detectron2/tools.\n\nIt is an example of how a user might use detectron2 for a new project.\n\"\"\"\n\nfrom datetime import timedelta\n\nimport detectron2.utils.comm as comm\nfrom detectron2.config import get_cfg\nfrom detectron2.engine import DEFAULT_TIMEOUT, default_argument_parser, default_setup, hooks, launch\nfrom detectron2.evaluation import verify_results\nfrom detectron2.utils.file_io import PathManager\nfrom detectron2.utils.logger import setup_logger\n\nfrom densepose import add_densepose_config\nfrom densepose.engine import Trainer\nfrom densepose.modeling.densepose_checkpoint import DensePoseCheckpointer\n\n\ndef setup(args):\n    cfg = get_cfg()\n    add_densepose_config(cfg)\n    cfg.merge_from_file(args.config_file)\n    cfg.merge_from_list(args.opts)\n    cfg.freeze()\n    default_setup(cfg, args)\n    # Setup logger for \"densepose\" module\n    setup_logger(output=cfg.OUTPUT_DIR, distributed_rank=comm.get_rank(), name=\"densepose\")\n    return cfg\n\n\ndef main(args):\n    cfg = setup(args)\n    # disable strict kwargs checking: allow one to specify path handle\n    # hints through kwargs, like timeout in DP evaluation\n    PathManager.set_strict_kwargs_checking(False)\n\n    if args.eval_only:\n        model = Trainer.build_model(cfg)\n        DensePoseCheckpointer(model, save_dir=cfg.OUTPUT_DIR).resume_or_load(\n            cfg.MODEL.WEIGHTS, resume=args.resume\n        )\n        res = Trainer.test(cfg, model)\n        if cfg.TEST.AUG.ENABLED:\n            res.update(Trainer.test_with_TTA(cfg, model))\n        if comm.is_main_process():\n            verify_results(cfg, res)\n        return res\n\n    trainer = Trainer(cfg)\n    trainer.resume_or_load(resume=args.resume)\n    if cfg.TEST.AUG.ENABLED:\n        trainer.register_hooks(\n            [hooks.EvalHook(0, lambda: trainer.test_with_TTA(cfg, trainer.model))]\n        )\n    return trainer.train()\n\n\nif __name__ == \"__main__\":\n    args = default_argument_parser().parse_args()\n    cfg = setup(args)\n    timeout = (\n        DEFAULT_TIMEOUT if cfg.DENSEPOSE_EVALUATION.DISTRIBUTED_INFERENCE else timedelta(hours=4)\n    )\n    print(\"Command Line Args:\", args)\n    launch(\n        main,\n        args.num_gpus,\n        num_machines=args.num_machines,\n        machine_rank=args.machine_rank,\n        dist_url=args.dist_url,\n        args=(args,),\n        timeout=timeout,\n    )\n"
  },
  {
    "path": "VPS_Module/projects/Panoptic-DeepLab/README.md",
    "content": "# Panoptic-DeepLab: A Simple, Strong, and Fast Baseline for Bottom-Up Panoptic Segmentation\n\nBowen Cheng, Maxwell D. Collins, Yukun Zhu, Ting Liu, Thomas S. Huang, Hartwig Adam, Liang-Chieh Chen\n\n[[`arXiv`](https://arxiv.org/abs/1911.10194)] [[`BibTeX`](#CitingPanopticDeepLab)] [[`Reference implementation`](https://github.com/bowenc0221/panoptic-deeplab)]\n\n<div align=\"center\">\n  <img src=\"https://github.com/bowenc0221/panoptic-deeplab/blob/master/docs/panoptic_deeplab.png\"/>\n</div><br/>\n\n## Installation\nInstall Detectron2 following [the instructions](https://detectron2.readthedocs.io/tutorials/install.html).\nTo use cityscapes, prepare data follow the [tutorial](https://detectron2.readthedocs.io/tutorials/builtin_datasets.html#expected-dataset-structure-for-cityscapes).\n\n## Training\n\nTo train a model with 8 GPUs run:\n```bash\ncd /path/to/detectron2/projects/Panoptic-DeepLab\npython train_net.py --config-file configs/Cityscapes-PanopticSegmentation/panoptic_deeplab_R_52_os16_mg124_poly_90k_bs32_crop_512_1024_dsconv.yaml --num-gpus 8\n```\n\n## Evaluation\n\nModel evaluation can be done similarly:\n```bash\ncd /path/to/detectron2/projects/Panoptic-DeepLab\npython train_net.py --config-file configs/Cityscapes-PanopticSegmentation/panoptic_deeplab_R_52_os16_mg124_poly_90k_bs32_crop_512_1024_dsconv.yaml --eval-only MODEL.WEIGHTS /path/to/model_checkpoint\n```\n\n## Benchmark network speed\n\nIf you want to benchmark the network speed without post-processing, you can run the evaluation script with `MODEL.PANOPTIC_DEEPLAB.BENCHMARK_NETWORK_SPEED True`:\n```bash\ncd /path/to/detectron2/projects/Panoptic-DeepLab\npython train_net.py --config-file configs/Cityscapes-PanopticSegmentation/panoptic_deeplab_R_52_os16_mg124_poly_90k_bs32_crop_512_1024_dsconv.yaml --eval-only MODEL.WEIGHTS /path/to/model_checkpoint MODEL.PANOPTIC_DEEPLAB.BENCHMARK_NETWORK_SPEED True\n```\n\n## Cityscapes Panoptic Segmentation\nCityscapes models are trained with ImageNet pretraining.\n\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Method</th>\n<th valign=\"bottom\">Backbone</th>\n<th valign=\"bottom\">Output<br/>resolution</th>\n<th valign=\"bottom\">PQ</th>\n<th valign=\"bottom\">SQ</th>\n<th valign=\"bottom\">RQ</th>\n<th valign=\"bottom\">mIoU</th>\n<th valign=\"bottom\">AP</th>\n<th valign=\"bottom\">Memory (M)</th>\n<th valign=\"bottom\">model id</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n <tr><td align=\"left\">Panoptic-DeepLab</td>\n<td align=\"center\">R50-DC5</td>\n<td align=\"center\">1024&times;2048</td>\n<td align=\"center\"> 58.6 </td>\n<td align=\"center\"> 80.9 </td>\n<td align=\"center\"> 71.2 </td>\n<td align=\"center\"> 75.9 </td>\n<td align=\"center\"> 29.8 </td>\n<td align=\"center\"> 8668 </td>\n<td align=\"center\"> - </td>\n<td align=\"center\">model&nbsp;|&nbsp;metrics</td>\n</tr>\n <tr><td align=\"left\"><a href=\"configs/Cityscapes-PanopticSegmentation/panoptic_deeplab_R_52_os16_mg124_poly_90k_bs32_crop_512_1024.yaml\">Panoptic-DeepLab</a></td>\n<td align=\"center\">R52-DC5</td>\n<td align=\"center\">1024&times;2048</td>\n<td align=\"center\"> 60.3 </td>\n<td align=\"center\"> 81.5 </td>\n<td align=\"center\"> 72.9 </td>\n<td align=\"center\"> 78.2 </td>\n<td align=\"center\"> 33.2 </td>\n<td align=\"center\"> 9682 </td>\n<td align=\"center\"> 30841561 </td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/detectron2/PanopticDeepLab/Cityscapes-PanopticSegmentation/panoptic_deeplab_R_52_os16_mg124_poly_90k_bs32/model_final_bd324a.pkl\n\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/PanopticDeepLab/Cityscapes-PanopticSegmentation/panoptic_deeplab_R_52_os16_mg124_poly_90k_bs32/metrics.json\n\">metrics</a></td>\n</tr>\n <tr><td align=\"left\"><a href=\"configs/Cityscapes-PanopticSegmentation/panoptic_deeplab_R_52_os16_mg124_poly_90k_bs32_crop_512_1024_dsconv.yaml\">Panoptic-DeepLab (DSConv)</a></td>\n<td align=\"center\">R52-DC5</td>\n<td align=\"center\">1024&times;2048</td>\n<td align=\"center\"> 60.3 </td>\n<td align=\"center\"> 81.0 </td>\n<td align=\"center\"> 73.2 </td>\n<td align=\"center\"> 78.7 </td>\n<td align=\"center\"> 32.1 </td>\n<td align=\"center\"> 10466 </td>\n<td align=\"center\"> 33148034 </td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/detectron2/PanopticDeepLab/Cityscapes-PanopticSegmentation/panoptic_deeplab_R_52_os16_mg124_poly_90k_bs32_crop_512_1024_dsconv/model_final_23d03a.pkl\n\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/PanopticDeepLab/Cityscapes-PanopticSegmentation/panoptic_deeplab_R_52_os16_mg124_poly_90k_bs32_crop_512_1024_dsconv/metrics.json\n\">metrics</a></td>\n</tr>\n</tbody></table>\n\nNote:\n- [R52](https://dl.fbaipublicfiles.com/detectron2/DeepLab/R-52.pkl): a ResNet-50 with its first 7x7 convolution replaced by 3 3x3 convolutions. This modification has been used in most semantic segmentation papers. We pre-train this backbone on ImageNet using the default recipe of [pytorch examples](https://github.com/pytorch/examples/tree/master/imagenet).\n- DC5 means using dilated convolution in `res5`.\n- We use a smaller training crop size (512x1024) than the original paper (1025x2049), we find using larger crop size (1024x2048) could further improve PQ by 1.5% but also degrades AP by 3%.\n- The implementation with regular Conv2d in ASPP and head is much heavier head than the original paper.\n- This implementation does not include optimized post-processing code needed for deployment. Post-processing the network\n  outputs now takes similar amount of time to the network itself. Please refer to speed in the\n  original paper for comparison.\n- DSConv refers to using DepthwiseSeparableConv2d in ASPP and decoder. The implementation with DSConv is identical to the original paper.\n\n## COCO Panoptic Segmentation\nCOCO models are trained with ImageNet pretraining on 16 V100s.\n\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Method</th>\n<th valign=\"bottom\">Backbone</th>\n<th valign=\"bottom\">Output<br/>resolution</th>\n<th valign=\"bottom\">PQ</th>\n<th valign=\"bottom\">SQ</th>\n<th valign=\"bottom\">RQ</th>\n<th valign=\"bottom\">Box AP</th>\n<th valign=\"bottom\">Mask AP</th>\n<th valign=\"bottom\">Memory (M)</th>\n<th valign=\"bottom\">model id</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n <tr><td align=\"left\"><a href=\"configs/COCO-PanopticSegmentation/panoptic_deeplab_R_52_os16_mg124_poly_200k_bs64_crop_640_640_coco_dsconv.yaml\">Panoptic-DeepLab (DSConv)</a></td>\n<td align=\"center\">R52-DC5</td>\n<td align=\"center\">640&times;640</td>\n<td align=\"center\"> 35.5 </td>\n<td align=\"center\"> 77.3 </td>\n<td align=\"center\"> 44.7 </td>\n<td align=\"center\"> 18.6 </td>\n<td align=\"center\"> 19.7 </td>\n<td align=\"center\">  </td>\n<td align=\"center\"> 246448865 </td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/detectron2/PanopticDeepLab/COCO-PanopticSegmentation/panoptic_deeplab_R_52_os16_mg124_poly_200k_bs64_crop_640_640_coco_dsconv/model_final_5e6da2.pkl\n\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/PanopticDeepLab/COCO-PanopticSegmentation/panoptic_deeplab_R_52_os16_mg124_poly_200k_bs64_crop_640_640_coco_dsconv/metrics.json\n\">metrics</a></td>\n</tr>\n</tbody></table>\n\nNote:\n- [R52](https://dl.fbaipublicfiles.com/detectron2/DeepLab/R-52.pkl): a ResNet-50 with its first 7x7 convolution replaced by 3 3x3 convolutions. This modification has been used in most semantic segmentation papers. We pre-train this backbone on ImageNet using the default recipe of [pytorch examples](https://github.com/pytorch/examples/tree/master/imagenet).\n- DC5 means using dilated convolution in `res5`.\n- This reproduced number matches the original paper (35.5 vs. 35.1 PQ).\n- This implementation does not include optimized post-processing code needed for deployment. Post-processing the network\n  outputs now takes more time than the network itself. Please refer to speed in the original paper for comparison.\n- DSConv refers to using DepthwiseSeparableConv2d in ASPP and decoder.\n\n## <a name=\"CitingPanopticDeepLab\"></a>Citing Panoptic-DeepLab\n\nIf you use Panoptic-DeepLab, please use the following BibTeX entry.\n\n*   CVPR 2020 paper:\n\n```\n@inproceedings{cheng2020panoptic,\n  title={Panoptic-DeepLab: A Simple, Strong, and Fast Baseline for Bottom-Up Panoptic Segmentation},\n  author={Cheng, Bowen and Collins, Maxwell D and Zhu, Yukun and Liu, Ting and Huang, Thomas S and Adam, Hartwig and Chen, Liang-Chieh},\n  booktitle={CVPR},\n  year={2020}\n}\n```\n\n*   ICCV 2019 COCO-Mapillary workshp challenge report:\n\n```\n@inproceedings{cheng2019panoptic,\n  title={Panoptic-DeepLab},\n  author={Cheng, Bowen and Collins, Maxwell D and Zhu, Yukun and Liu, Ting and Huang, Thomas S and Adam, Hartwig and Chen, Liang-Chieh},\n  booktitle={ICCV COCO + Mapillary Joint Recognition Challenge Workshop},\n  year={2019}\n}\n```\n"
  },
  {
    "path": "VPS_Module/projects/Panoptic-DeepLab/configs/COCO-PanopticSegmentation/panoptic_deeplab_R_52_os16_mg124_poly_200k_bs64_crop_640_640_coco_dsconv.yaml",
    "content": "_BASE_: ../Cityscapes-PanopticSegmentation/Base-PanopticDeepLab-OS16.yaml\nMODEL:\n  WEIGHTS: \"detectron2://DeepLab/R-52.pkl\"\n  PIXEL_MEAN: [123.675, 116.280, 103.530]\n  PIXEL_STD: [58.395, 57.120, 57.375]\n  BACKBONE:\n    NAME: \"build_resnet_deeplab_backbone\"\n  RESNETS:\n    DEPTH: 50\n    NORM: \"SyncBN\"\n    RES5_MULTI_GRID: [1, 2, 4]\n    STEM_TYPE: \"deeplab\"\n    STEM_OUT_CHANNELS: 128\n    STRIDE_IN_1X1: False\n  SEM_SEG_HEAD:\n    NUM_CLASSES: 133\n    LOSS_TOP_K: 1.0\n    USE_DEPTHWISE_SEPARABLE_CONV: True\n  PANOPTIC_DEEPLAB:\n    STUFF_AREA: 4096\n    NMS_KERNEL: 41\n    SIZE_DIVISIBILITY: 640\n    USE_DEPTHWISE_SEPARABLE_CONV: True\nDATASETS:\n  TRAIN: (\"coco_2017_train_panoptic\",)\n  TEST: (\"coco_2017_val_panoptic\",)\nSOLVER:\n  BASE_LR: 0.0005\n  MAX_ITER: 200000\n  IMS_PER_BATCH: 64\nINPUT:\n  FORMAT: \"RGB\"\n  GAUSSIAN_SIGMA: 8\n  MIN_SIZE_TRAIN: !!python/object/apply:eval [\"[int(x * 0.1 * 640) for x in range(5, 16)]\"]\n  MIN_SIZE_TRAIN_SAMPLING: \"choice\"\n  MIN_SIZE_TEST: 640\n  MAX_SIZE_TRAIN: 960\n  MAX_SIZE_TEST: 640\n  CROP:\n    ENABLED: True\n    TYPE: \"absolute\"\n    SIZE: (640, 640)\n"
  },
  {
    "path": "VPS_Module/projects/Panoptic-DeepLab/configs/Cityscapes-PanopticSegmentation/Base-PanopticDeepLab-OS16.yaml",
    "content": "MODEL:\n  META_ARCHITECTURE: \"PanopticDeepLab\"\n  BACKBONE:\n    FREEZE_AT: 0\n  RESNETS:\n    OUT_FEATURES: [\"res2\", \"res3\", \"res5\"]\n    RES5_DILATION: 2\n  SEM_SEG_HEAD:\n    NAME: \"PanopticDeepLabSemSegHead\"\n    IN_FEATURES: [\"res2\", \"res3\", \"res5\"]\n    PROJECT_FEATURES: [\"res2\", \"res3\"]\n    PROJECT_CHANNELS: [32, 64]\n    ASPP_CHANNELS: 256\n    ASPP_DILATIONS: [6, 12, 18]\n    ASPP_DROPOUT: 0.1\n    HEAD_CHANNELS: 256\n    CONVS_DIM: 256\n    COMMON_STRIDE: 4\n    NUM_CLASSES: 19\n    LOSS_TYPE: \"hard_pixel_mining\"\n    NORM: \"SyncBN\"\n  INS_EMBED_HEAD:\n    NAME: \"PanopticDeepLabInsEmbedHead\"\n    IN_FEATURES: [\"res2\", \"res3\", \"res5\"]\n    PROJECT_FEATURES: [\"res2\", \"res3\"]\n    PROJECT_CHANNELS: [32, 64]\n    ASPP_CHANNELS: 256\n    ASPP_DILATIONS: [6, 12, 18]\n    ASPP_DROPOUT: 0.1\n    HEAD_CHANNELS: 32\n    CONVS_DIM: 128\n    COMMON_STRIDE: 4\n    NORM: \"SyncBN\"\n    CENTER_LOSS_WEIGHT: 200.0\n    OFFSET_LOSS_WEIGHT: 0.01\n  PANOPTIC_DEEPLAB:\n    STUFF_AREA: 2048\n    CENTER_THRESHOLD: 0.1\n    NMS_KERNEL: 7\n    TOP_K_INSTANCE: 200\nDATASETS:\n  TRAIN: (\"cityscapes_fine_panoptic_train\",)\n  TEST: (\"cityscapes_fine_panoptic_val\",)\nSOLVER:\n  OPTIMIZER: \"ADAM\"\n  BASE_LR: 0.001\n  WEIGHT_DECAY: 0.0\n  WEIGHT_DECAY_NORM: 0.0\n  WEIGHT_DECAY_BIAS: 0.0\n  MAX_ITER: 60000\n  LR_SCHEDULER_NAME: \"WarmupPolyLR\"\n  IMS_PER_BATCH: 32\nINPUT:\n  MIN_SIZE_TRAIN: (512, 640, 704, 832, 896, 1024, 1152, 1216, 1344, 1408, 1536, 1664, 1728, 1856, 1920, 2048)\n  MIN_SIZE_TRAIN_SAMPLING: \"choice\"\n  MIN_SIZE_TEST: 1024\n  MAX_SIZE_TRAIN: 4096\n  MAX_SIZE_TEST: 2048\n  CROP:\n    ENABLED: True\n    TYPE: \"absolute\"\n    SIZE: (1024, 2048)\nDATALOADER:\n  NUM_WORKERS: 10\nVERSION: 2\n"
  },
  {
    "path": "VPS_Module/projects/Panoptic-DeepLab/configs/Cityscapes-PanopticSegmentation/panoptic_deeplab_R_52_os16_mg124_poly_90k_bs32_crop_512_1024.yaml",
    "content": "_BASE_: Base-PanopticDeepLab-OS16.yaml\nMODEL:\n  WEIGHTS: \"detectron2://DeepLab/R-52.pkl\"\n  PIXEL_MEAN: [123.675, 116.280, 103.530]\n  PIXEL_STD: [58.395, 57.120, 57.375]\n  BACKBONE:\n    NAME: \"build_resnet_deeplab_backbone\"\n  RESNETS:\n    DEPTH: 50\n    NORM: \"SyncBN\"\n    RES5_MULTI_GRID: [1, 2, 4]\n    STEM_TYPE: \"deeplab\"\n    STEM_OUT_CHANNELS: 128\n    STRIDE_IN_1X1: False\nSOLVER:\n  MAX_ITER: 90000\nINPUT:\n  FORMAT: \"RGB\"\n  CROP:\n    SIZE: (512, 1024)\n"
  },
  {
    "path": "VPS_Module/projects/Panoptic-DeepLab/configs/Cityscapes-PanopticSegmentation/panoptic_deeplab_R_52_os16_mg124_poly_90k_bs32_crop_512_1024_dsconv.yaml",
    "content": "_BASE_: Base-PanopticDeepLab-OS16.yaml\nMODEL:\n  WEIGHTS: \"detectron2://DeepLab/R-52.pkl\"\n  PIXEL_MEAN: [123.675, 116.280, 103.530]\n  PIXEL_STD: [58.395, 57.120, 57.375]\n  BACKBONE:\n    NAME: \"build_resnet_deeplab_backbone\"\n  RESNETS:\n    DEPTH: 50\n    NORM: \"SyncBN\"\n    RES5_MULTI_GRID: [1, 2, 4]\n    STEM_TYPE: \"deeplab\"\n    STEM_OUT_CHANNELS: 128\n    STRIDE_IN_1X1: False\n  PANOPTIC_DEEPLAB:\n    USE_DEPTHWISE_SEPARABLE_CONV: True\n  SEM_SEG_HEAD:\n    USE_DEPTHWISE_SEPARABLE_CONV: True\nSOLVER:\n  MAX_ITER: 90000\nINPUT:\n  FORMAT: \"RGB\"\n  CROP:\n    SIZE: (512, 1024)\n"
  },
  {
    "path": "VPS_Module/projects/Panoptic-DeepLab/panoptic_deeplab/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom .config import add_panoptic_deeplab_config\nfrom .dataset_mapper import PanopticDeeplabDatasetMapper\nfrom .panoptic_seg import (\n    PanopticDeepLab,\n    INS_EMBED_BRANCHES_REGISTRY,\n    build_ins_embed_branch,\n    PanopticDeepLabSemSegHead,\n    PanopticDeepLabInsEmbedHead,\n)\n"
  },
  {
    "path": "VPS_Module/projects/Panoptic-DeepLab/panoptic_deeplab/config.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom detectron2.config import CfgNode as CN\nfrom detectron2.projects.deeplab import add_deeplab_config\n\n\ndef add_panoptic_deeplab_config(cfg):\n    \"\"\"\n    Add config for Panoptic-DeepLab.\n    \"\"\"\n    # Reuse DeepLab config.\n    add_deeplab_config(cfg)\n    # Target generation parameters.\n    cfg.INPUT.GAUSSIAN_SIGMA = 10\n    cfg.INPUT.IGNORE_STUFF_IN_OFFSET = True\n    cfg.INPUT.SMALL_INSTANCE_AREA = 4096\n    cfg.INPUT.SMALL_INSTANCE_WEIGHT = 3\n    cfg.INPUT.IGNORE_CROWD_IN_SEMANTIC = False\n    # Optimizer type.\n    cfg.SOLVER.OPTIMIZER = \"ADAM\"\n    # Panoptic-DeepLab semantic segmentation head.\n    # We add an extra convolution before predictor.\n    cfg.MODEL.SEM_SEG_HEAD.HEAD_CHANNELS = 256\n    cfg.MODEL.SEM_SEG_HEAD.LOSS_TOP_K = 0.2\n    # Panoptic-DeepLab instance segmentation head.\n    cfg.MODEL.INS_EMBED_HEAD = CN()\n    cfg.MODEL.INS_EMBED_HEAD.NAME = \"PanopticDeepLabInsEmbedHead\"\n    cfg.MODEL.INS_EMBED_HEAD.IN_FEATURES = [\"res2\", \"res3\", \"res5\"]\n    cfg.MODEL.INS_EMBED_HEAD.PROJECT_FEATURES = [\"res2\", \"res3\"]\n    cfg.MODEL.INS_EMBED_HEAD.PROJECT_CHANNELS = [32, 64]\n    cfg.MODEL.INS_EMBED_HEAD.ASPP_CHANNELS = 256\n    cfg.MODEL.INS_EMBED_HEAD.ASPP_DILATIONS = [6, 12, 18]\n    cfg.MODEL.INS_EMBED_HEAD.ASPP_DROPOUT = 0.1\n    # We add an extra convolution before predictor.\n    cfg.MODEL.INS_EMBED_HEAD.HEAD_CHANNELS = 32\n    cfg.MODEL.INS_EMBED_HEAD.CONVS_DIM = 128\n    cfg.MODEL.INS_EMBED_HEAD.COMMON_STRIDE = 4\n    cfg.MODEL.INS_EMBED_HEAD.NORM = \"SyncBN\"\n    cfg.MODEL.INS_EMBED_HEAD.CENTER_LOSS_WEIGHT = 200.0\n    cfg.MODEL.INS_EMBED_HEAD.OFFSET_LOSS_WEIGHT = 0.01\n    # Panoptic-DeepLab post-processing setting.\n    cfg.MODEL.PANOPTIC_DEEPLAB = CN()\n    # Stuff area limit, ignore stuff region below this number.\n    cfg.MODEL.PANOPTIC_DEEPLAB.STUFF_AREA = 2048\n    cfg.MODEL.PANOPTIC_DEEPLAB.CENTER_THRESHOLD = 0.1\n    cfg.MODEL.PANOPTIC_DEEPLAB.NMS_KERNEL = 7\n    cfg.MODEL.PANOPTIC_DEEPLAB.TOP_K_INSTANCE = 200\n    # If set to False, Panoptic-DeepLab will not evaluate instance segmentation.\n    cfg.MODEL.PANOPTIC_DEEPLAB.PREDICT_INSTANCES = True\n    cfg.MODEL.PANOPTIC_DEEPLAB.USE_DEPTHWISE_SEPARABLE_CONV = False\n    # This is the padding parameter for images with various sizes. ASPP layers\n    # requires input images to be divisible by the average pooling size and we\n    # can use `MODEL.PANOPTIC_DEEPLAB.SIZE_DIVISIBILITY` to pad all images to\n    # a fixed resolution (e.g. 640x640 for COCO) to avoid having a image size\n    # that is not divisible by ASPP average pooling size.\n    cfg.MODEL.PANOPTIC_DEEPLAB.SIZE_DIVISIBILITY = -1\n    # Only evaluates network speed (ignores post-processing).\n    cfg.MODEL.PANOPTIC_DEEPLAB.BENCHMARK_NETWORK_SPEED = False\n"
  },
  {
    "path": "VPS_Module/projects/Panoptic-DeepLab/panoptic_deeplab/dataset_mapper.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport copy\nimport logging\nimport numpy as np\nfrom typing import Callable, List, Union\nimport torch\nfrom panopticapi.utils import rgb2id\n\nfrom detectron2.config import configurable\nfrom detectron2.data import MetadataCatalog\nfrom detectron2.data import detection_utils as utils\nfrom detectron2.data import transforms as T\n\nfrom .target_generator import PanopticDeepLabTargetGenerator\n\n__all__ = [\"PanopticDeeplabDatasetMapper\"]\n\n\nclass PanopticDeeplabDatasetMapper:\n    \"\"\"\n    The callable currently does the following:\n\n    1. Read the image from \"file_name\" and label from \"pan_seg_file_name\"\n    2. Applies random scale, crop and flip transforms to image and label\n    3. Prepare data to Tensor and generate training targets from label\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self,\n        *,\n        augmentations: List[Union[T.Augmentation, T.Transform]],\n        image_format: str,\n        panoptic_target_generator: Callable,\n    ):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            augmentations: a list of augmentations or deterministic transforms to apply\n            image_format: an image format supported by :func:`detection_utils.read_image`.\n            panoptic_target_generator: a callable that takes \"panoptic_seg\" and\n                \"segments_info\" to generate training targets for the model.\n        \"\"\"\n        # fmt: off\n        self.augmentations          = T.AugmentationList(augmentations)\n        self.image_format           = image_format\n        # fmt: on\n        logger = logging.getLogger(__name__)\n        logger.info(\"Augmentations used in training: \" + str(augmentations))\n\n        self.panoptic_target_generator = panoptic_target_generator\n\n    @classmethod\n    def from_config(cls, cfg):\n        augs = [\n            T.ResizeShortestEdge(\n                cfg.INPUT.MIN_SIZE_TRAIN,\n                cfg.INPUT.MAX_SIZE_TRAIN,\n                cfg.INPUT.MIN_SIZE_TRAIN_SAMPLING,\n            )\n        ]\n        if cfg.INPUT.CROP.ENABLED:\n            augs.append(T.RandomCrop(cfg.INPUT.CROP.TYPE, cfg.INPUT.CROP.SIZE))\n        augs.append(T.RandomFlip())\n\n        # Assume always applies to the training set.\n        dataset_names = cfg.DATASETS.TRAIN\n        meta = MetadataCatalog.get(dataset_names[0])\n        panoptic_target_generator = PanopticDeepLabTargetGenerator(\n            ignore_label=meta.ignore_label,\n            thing_ids=list(meta.thing_dataset_id_to_contiguous_id.values()),\n            sigma=cfg.INPUT.GAUSSIAN_SIGMA,\n            ignore_stuff_in_offset=cfg.INPUT.IGNORE_STUFF_IN_OFFSET,\n            small_instance_area=cfg.INPUT.SMALL_INSTANCE_AREA,\n            small_instance_weight=cfg.INPUT.SMALL_INSTANCE_WEIGHT,\n            ignore_crowd_in_semantic=cfg.INPUT.IGNORE_CROWD_IN_SEMANTIC,\n        )\n\n        ret = {\n            \"augmentations\": augs,\n            \"image_format\": cfg.INPUT.FORMAT,\n            \"panoptic_target_generator\": panoptic_target_generator,\n        }\n        return ret\n\n    def __call__(self, dataset_dict):\n        \"\"\"\n        Args:\n            dataset_dict (dict): Metadata of one image, in Detectron2 Dataset format.\n\n        Returns:\n            dict: a format that builtin models in detectron2 accept\n        \"\"\"\n        dataset_dict = copy.deepcopy(dataset_dict)  # it will be modified by code below\n        # Load image.\n        image = utils.read_image(dataset_dict[\"file_name\"], format=self.image_format)\n        utils.check_image_size(dataset_dict, image)\n        # Panoptic label is encoded in RGB image.\n        pan_seg_gt = utils.read_image(dataset_dict.pop(\"pan_seg_file_name\"), \"RGB\")\n\n        # Reuses semantic transform for panoptic labels.\n        aug_input = T.AugInput(image, sem_seg=pan_seg_gt)\n        _ = self.augmentations(aug_input)\n        image, pan_seg_gt = aug_input.image, aug_input.sem_seg\n\n        # Pytorch's dataloader is efficient on torch.Tensor due to shared-memory,\n        # but not efficient on large generic data structures due to the use of pickle & mp.Queue.\n        # Therefore it's important to use torch.Tensor.\n        dataset_dict[\"image\"] = torch.as_tensor(np.ascontiguousarray(image.transpose(2, 0, 1)))\n\n        # Generates training targets for Panoptic-DeepLab.\n        targets = self.panoptic_target_generator(rgb2id(pan_seg_gt), dataset_dict[\"segments_info\"])\n        dataset_dict.update(targets)\n\n        return dataset_dict\n"
  },
  {
    "path": "VPS_Module/projects/Panoptic-DeepLab/panoptic_deeplab/panoptic_seg.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport numpy as np\nfrom typing import Callable, Dict, List, Union\nimport fvcore.nn.weight_init as weight_init\nimport torch\nfrom torch import nn\nfrom torch.nn import functional as F\n\nfrom detectron2.config import configurable\nfrom detectron2.data import MetadataCatalog\nfrom detectron2.layers import Conv2d, DepthwiseSeparableConv2d, ShapeSpec, get_norm\nfrom detectron2.modeling import (\n    META_ARCH_REGISTRY,\n    SEM_SEG_HEADS_REGISTRY,\n    build_backbone,\n    build_sem_seg_head,\n)\nfrom detectron2.modeling.postprocessing import sem_seg_postprocess\nfrom detectron2.projects.deeplab import DeepLabV3PlusHead\nfrom detectron2.projects.deeplab.loss import DeepLabCE\nfrom detectron2.structures import BitMasks, ImageList, Instances\nfrom detectron2.utils.registry import Registry\n\nfrom .post_processing import get_panoptic_segmentation\n\n__all__ = [\"PanopticDeepLab\", \"INS_EMBED_BRANCHES_REGISTRY\", \"build_ins_embed_branch\"]\n\n\nINS_EMBED_BRANCHES_REGISTRY = Registry(\"INS_EMBED_BRANCHES\")\nINS_EMBED_BRANCHES_REGISTRY.__doc__ = \"\"\"\nRegistry for instance embedding branches, which make instance embedding\npredictions from feature maps.\n\"\"\"\n\n\n@META_ARCH_REGISTRY.register()\nclass PanopticDeepLab(nn.Module):\n    \"\"\"\n    Main class for panoptic segmentation architectures.\n    \"\"\"\n\n    def __init__(self, cfg):\n        super().__init__()\n        self.backbone = build_backbone(cfg)\n        self.sem_seg_head = build_sem_seg_head(cfg, self.backbone.output_shape())\n        self.ins_embed_head = build_ins_embed_branch(cfg, self.backbone.output_shape())\n        self.register_buffer(\"pixel_mean\", torch.tensor(cfg.MODEL.PIXEL_MEAN).view(-1, 1, 1), False)\n        self.register_buffer(\"pixel_std\", torch.tensor(cfg.MODEL.PIXEL_STD).view(-1, 1, 1), False)\n        self.meta = MetadataCatalog.get(cfg.DATASETS.TRAIN[0])\n        self.stuff_area = cfg.MODEL.PANOPTIC_DEEPLAB.STUFF_AREA\n        self.threshold = cfg.MODEL.PANOPTIC_DEEPLAB.CENTER_THRESHOLD\n        self.nms_kernel = cfg.MODEL.PANOPTIC_DEEPLAB.NMS_KERNEL\n        self.top_k = cfg.MODEL.PANOPTIC_DEEPLAB.TOP_K_INSTANCE\n        self.predict_instances = cfg.MODEL.PANOPTIC_DEEPLAB.PREDICT_INSTANCES\n        self.use_depthwise_separable_conv = cfg.MODEL.PANOPTIC_DEEPLAB.USE_DEPTHWISE_SEPARABLE_CONV\n        assert (\n            cfg.MODEL.SEM_SEG_HEAD.USE_DEPTHWISE_SEPARABLE_CONV\n            == cfg.MODEL.PANOPTIC_DEEPLAB.USE_DEPTHWISE_SEPARABLE_CONV\n        )\n        self.size_divisibility = cfg.MODEL.PANOPTIC_DEEPLAB.SIZE_DIVISIBILITY\n        self.benchmark_network_speed = cfg.MODEL.PANOPTIC_DEEPLAB.BENCHMARK_NETWORK_SPEED\n\n    @property\n    def device(self):\n        return self.pixel_mean.device\n\n    def forward(self, batched_inputs):\n        \"\"\"\n        Args:\n            batched_inputs: a list, batched outputs of :class:`DatasetMapper`.\n                Each item in the list contains the inputs for one image.\n                For now, each item in the list is a dict that contains:\n                   * \"image\": Tensor, image in (C, H, W) format.\n                   * \"sem_seg\": semantic segmentation ground truth\n                   * \"center\": center points heatmap ground truth\n                   * \"offset\": pixel offsets to center points ground truth\n                   * Other information that's included in the original dicts, such as:\n                     \"height\", \"width\" (int): the output resolution of the model (may be different\n                     from input resolution), used in inference.\n        Returns:\n            list[dict]:\n                each dict is the results for one image. The dict contains the following keys:\n\n                * \"panoptic_seg\", \"sem_seg\": see documentation\n                    :doc:`/tutorials/models` for the standard output format\n                * \"instances\": available if ``predict_instances is True``. see documentation\n                    :doc:`/tutorials/models` for the standard output format\n        \"\"\"\n        images = [x[\"image\"].to(self.device) for x in batched_inputs]\n        images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n        # To avoid error in ASPP layer when input has different size.\n        size_divisibility = (\n            self.size_divisibility\n            if self.size_divisibility > 0\n            else self.backbone.size_divisibility\n        )\n        images = ImageList.from_tensors(images, size_divisibility)\n\n        features = self.backbone(images.tensor)\n\n        losses = {}\n        if \"sem_seg\" in batched_inputs[0]:\n            targets = [x[\"sem_seg\"].to(self.device) for x in batched_inputs]\n            targets = ImageList.from_tensors(\n                targets, size_divisibility, self.sem_seg_head.ignore_value\n            ).tensor\n            if \"sem_seg_weights\" in batched_inputs[0]:\n                # The default D2 DatasetMapper may not contain \"sem_seg_weights\"\n                # Avoid error in testing when default DatasetMapper is used.\n                weights = [x[\"sem_seg_weights\"].to(self.device) for x in batched_inputs]\n                weights = ImageList.from_tensors(weights, size_divisibility).tensor\n            else:\n                weights = None\n        else:\n            targets = None\n            weights = None\n        sem_seg_results, sem_seg_losses = self.sem_seg_head(features, targets, weights)\n        losses.update(sem_seg_losses)\n\n        if \"center\" in batched_inputs[0] and \"offset\" in batched_inputs[0]:\n            center_targets = [x[\"center\"].to(self.device) for x in batched_inputs]\n            center_targets = ImageList.from_tensors(\n                center_targets, size_divisibility\n            ).tensor.unsqueeze(1)\n            center_weights = [x[\"center_weights\"].to(self.device) for x in batched_inputs]\n            center_weights = ImageList.from_tensors(center_weights, size_divisibility).tensor\n\n            offset_targets = [x[\"offset\"].to(self.device) for x in batched_inputs]\n            offset_targets = ImageList.from_tensors(offset_targets, size_divisibility).tensor\n            offset_weights = [x[\"offset_weights\"].to(self.device) for x in batched_inputs]\n            offset_weights = ImageList.from_tensors(offset_weights, size_divisibility).tensor\n        else:\n            center_targets = None\n            center_weights = None\n\n            offset_targets = None\n            offset_weights = None\n\n        center_results, offset_results, center_losses, offset_losses = self.ins_embed_head(\n            features, center_targets, center_weights, offset_targets, offset_weights\n        )\n        losses.update(center_losses)\n        losses.update(offset_losses)\n\n        if self.training:\n            return losses\n\n        if self.benchmark_network_speed:\n            return []\n\n        processed_results = []\n        for sem_seg_result, center_result, offset_result, input_per_image, image_size in zip(\n            sem_seg_results, center_results, offset_results, batched_inputs, images.image_sizes\n        ):\n            height = input_per_image.get(\"height\")\n            width = input_per_image.get(\"width\")\n            r = sem_seg_postprocess(sem_seg_result, image_size, height, width)\n            c = sem_seg_postprocess(center_result, image_size, height, width)\n            o = sem_seg_postprocess(offset_result, image_size, height, width)\n            # Post-processing to get panoptic segmentation.\n            panoptic_image, _ = get_panoptic_segmentation(\n                r.argmax(dim=0, keepdim=True),\n                c,\n                o,\n                thing_ids=self.meta.thing_dataset_id_to_contiguous_id.values(),\n                label_divisor=self.meta.label_divisor,\n                stuff_area=self.stuff_area,\n                void_label=-1,\n                threshold=self.threshold,\n                nms_kernel=self.nms_kernel,\n                top_k=self.top_k,\n            )\n            # For semantic segmentation evaluation.\n            processed_results.append({\"sem_seg\": r})\n            panoptic_image = panoptic_image.squeeze(0)\n            semantic_prob = F.softmax(r, dim=0)\n            # For panoptic segmentation evaluation.\n            processed_results[-1][\"panoptic_seg\"] = (panoptic_image, None)\n            # For instance segmentation evaluation.\n            if self.predict_instances:\n                instances = []\n                panoptic_image_cpu = panoptic_image.cpu().numpy()\n                for panoptic_label in np.unique(panoptic_image_cpu):\n                    if panoptic_label == -1:\n                        continue\n                    pred_class = panoptic_label // self.meta.label_divisor\n                    isthing = pred_class in list(\n                        self.meta.thing_dataset_id_to_contiguous_id.values()\n                    )\n                    # Get instance segmentation results.\n                    if isthing:\n                        instance = Instances((height, width))\n                        # Evaluation code takes continuous id starting from 0\n                        instance.pred_classes = torch.tensor(\n                            [pred_class], device=panoptic_image.device\n                        )\n                        mask = panoptic_image == panoptic_label\n                        instance.pred_masks = mask.unsqueeze(0)\n                        # Average semantic probability\n                        sem_scores = semantic_prob[pred_class, ...]\n                        sem_scores = torch.mean(sem_scores[mask])\n                        # Center point probability\n                        mask_indices = torch.nonzero(mask).float()\n                        center_y, center_x = (\n                            torch.mean(mask_indices[:, 0]),\n                            torch.mean(mask_indices[:, 1]),\n                        )\n                        center_scores = c[0, int(center_y.item()), int(center_x.item())]\n                        # Confidence score is semantic prob * center prob.\n                        instance.scores = torch.tensor(\n                            [sem_scores * center_scores], device=panoptic_image.device\n                        )\n                        # Get bounding boxes\n                        instance.pred_boxes = BitMasks(instance.pred_masks).get_bounding_boxes()\n                        instances.append(instance)\n                if len(instances) > 0:\n                    processed_results[-1][\"instances\"] = Instances.cat(instances)\n\n        return processed_results\n\n\n@SEM_SEG_HEADS_REGISTRY.register()\nclass PanopticDeepLabSemSegHead(DeepLabV3PlusHead):\n    \"\"\"\n    A semantic segmentation head described in :paper:`Panoptic-DeepLab`.\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self,\n        input_shape: Dict[str, ShapeSpec],\n        *,\n        decoder_channels: List[int],\n        norm: Union[str, Callable],\n        head_channels: int,\n        loss_weight: float,\n        loss_type: str,\n        loss_top_k: float,\n        ignore_value: int,\n        num_classes: int,\n        **kwargs,\n    ):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            input_shape (ShapeSpec): shape of the input feature\n            decoder_channels (list[int]): a list of output channels of each\n                decoder stage. It should have the same length as \"input_shape\"\n                (each element in \"input_shape\" corresponds to one decoder stage).\n            norm (str or callable): normalization for all conv layers.\n            head_channels (int): the output channels of extra convolutions\n                between decoder and predictor.\n            loss_weight (float): loss weight.\n            loss_top_k: (float): setting the top k% hardest pixels for\n                \"hard_pixel_mining\" loss.\n            loss_type, ignore_value, num_classes: the same as the base class.\n        \"\"\"\n        super().__init__(\n            input_shape,\n            decoder_channels=decoder_channels,\n            norm=norm,\n            ignore_value=ignore_value,\n            **kwargs,\n        )\n        assert self.decoder_only\n\n        self.loss_weight = loss_weight\n        use_bias = norm == \"\"\n        # `head` is additional transform before predictor\n        if self.use_depthwise_separable_conv:\n            # We use a single 5x5 DepthwiseSeparableConv2d to replace\n            # 2 3x3 Conv2d since they have the same receptive field.\n            self.head = DepthwiseSeparableConv2d(\n                decoder_channels[0],\n                head_channels,\n                kernel_size=5,\n                padding=2,\n                norm1=norm,\n                activation1=F.relu,\n                norm2=norm,\n                activation2=F.relu,\n            )\n        else:\n            self.head = nn.Sequential(\n                Conv2d(\n                    decoder_channels[0],\n                    decoder_channels[0],\n                    kernel_size=3,\n                    padding=1,\n                    bias=use_bias,\n                    norm=get_norm(norm, decoder_channels[0]),\n                    activation=F.relu,\n                ),\n                Conv2d(\n                    decoder_channels[0],\n                    head_channels,\n                    kernel_size=3,\n                    padding=1,\n                    bias=use_bias,\n                    norm=get_norm(norm, head_channels),\n                    activation=F.relu,\n                ),\n            )\n            weight_init.c2_xavier_fill(self.head[0])\n            weight_init.c2_xavier_fill(self.head[1])\n        self.predictor = Conv2d(head_channels, num_classes, kernel_size=1)\n        nn.init.normal_(self.predictor.weight, 0, 0.001)\n        nn.init.constant_(self.predictor.bias, 0)\n\n        if loss_type == \"cross_entropy\":\n            self.loss = nn.CrossEntropyLoss(reduction=\"mean\", ignore_index=ignore_value)\n        elif loss_type == \"hard_pixel_mining\":\n            self.loss = DeepLabCE(ignore_label=ignore_value, top_k_percent_pixels=loss_top_k)\n        else:\n            raise ValueError(\"Unexpected loss type: %s\" % loss_type)\n\n    @classmethod\n    def from_config(cls, cfg, input_shape):\n        ret = super().from_config(cfg, input_shape)\n        ret[\"head_channels\"] = cfg.MODEL.SEM_SEG_HEAD.HEAD_CHANNELS\n        ret[\"loss_top_k\"] = cfg.MODEL.SEM_SEG_HEAD.LOSS_TOP_K\n        return ret\n\n    def forward(self, features, targets=None, weights=None):\n        \"\"\"\n        Returns:\n            In training, returns (None, dict of losses)\n            In inference, returns (CxHxW logits, {})\n        \"\"\"\n        y = self.layers(features)\n        if self.training:\n            return None, self.losses(y, targets, weights)\n        else:\n            y = F.interpolate(\n                y, scale_factor=self.common_stride, mode=\"bilinear\", align_corners=False\n            )\n            return y, {}\n\n    def layers(self, features):\n        assert self.decoder_only\n        y = super().layers(features)\n        y = self.head(y)\n        y = self.predictor(y)\n        return y\n\n    def losses(self, predictions, targets, weights=None):\n        predictions = F.interpolate(\n            predictions, scale_factor=self.common_stride, mode=\"bilinear\", align_corners=False\n        )\n        loss = self.loss(predictions, targets, weights)\n        losses = {\"loss_sem_seg\": loss * self.loss_weight}\n        return losses\n\n\ndef build_ins_embed_branch(cfg, input_shape):\n    \"\"\"\n    Build a instance embedding branch from `cfg.MODEL.INS_EMBED_HEAD.NAME`.\n    \"\"\"\n    name = cfg.MODEL.INS_EMBED_HEAD.NAME\n    return INS_EMBED_BRANCHES_REGISTRY.get(name)(cfg, input_shape)\n\n\n@INS_EMBED_BRANCHES_REGISTRY.register()\nclass PanopticDeepLabInsEmbedHead(DeepLabV3PlusHead):\n    \"\"\"\n    A instance embedding head described in :paper:`Panoptic-DeepLab`.\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self,\n        input_shape: Dict[str, ShapeSpec],\n        *,\n        decoder_channels: List[int],\n        norm: Union[str, Callable],\n        head_channels: int,\n        center_loss_weight: float,\n        offset_loss_weight: float,\n        **kwargs,\n    ):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            input_shape (ShapeSpec): shape of the input feature\n            decoder_channels (list[int]): a list of output channels of each\n                decoder stage. It should have the same length as \"input_shape\"\n                (each element in \"input_shape\" corresponds to one decoder stage).\n            norm (str or callable): normalization for all conv layers.\n            head_channels (int): the output channels of extra convolutions\n                between decoder and predictor.\n            center_loss_weight (float): loss weight for center point prediction.\n            offset_loss_weight (float): loss weight for center offset prediction.\n        \"\"\"\n        super().__init__(input_shape, decoder_channels=decoder_channels, norm=norm, **kwargs)\n        assert self.decoder_only\n\n        self.center_loss_weight = center_loss_weight\n        self.offset_loss_weight = offset_loss_weight\n        use_bias = norm == \"\"\n        # center prediction\n        # `head` is additional transform before predictor\n        self.center_head = nn.Sequential(\n            Conv2d(\n                decoder_channels[0],\n                decoder_channels[0],\n                kernel_size=3,\n                padding=1,\n                bias=use_bias,\n                norm=get_norm(norm, decoder_channels[0]),\n                activation=F.relu,\n            ),\n            Conv2d(\n                decoder_channels[0],\n                head_channels,\n                kernel_size=3,\n                padding=1,\n                bias=use_bias,\n                norm=get_norm(norm, head_channels),\n                activation=F.relu,\n            ),\n        )\n        weight_init.c2_xavier_fill(self.center_head[0])\n        weight_init.c2_xavier_fill(self.center_head[1])\n        self.center_predictor = Conv2d(head_channels, 1, kernel_size=1)\n        nn.init.normal_(self.center_predictor.weight, 0, 0.001)\n        nn.init.constant_(self.center_predictor.bias, 0)\n\n        # offset prediction\n        # `head` is additional transform before predictor\n        if self.use_depthwise_separable_conv:\n            # We use a single 5x5 DepthwiseSeparableConv2d to replace\n            # 2 3x3 Conv2d since they have the same receptive field.\n            self.offset_head = DepthwiseSeparableConv2d(\n                decoder_channels[0],\n                head_channels,\n                kernel_size=5,\n                padding=2,\n                norm1=norm,\n                activation1=F.relu,\n                norm2=norm,\n                activation2=F.relu,\n            )\n        else:\n            self.offset_head = nn.Sequential(\n                Conv2d(\n                    decoder_channels[0],\n                    decoder_channels[0],\n                    kernel_size=3,\n                    padding=1,\n                    bias=use_bias,\n                    norm=get_norm(norm, decoder_channels[0]),\n                    activation=F.relu,\n                ),\n                Conv2d(\n                    decoder_channels[0],\n                    head_channels,\n                    kernel_size=3,\n                    padding=1,\n                    bias=use_bias,\n                    norm=get_norm(norm, head_channels),\n                    activation=F.relu,\n                ),\n            )\n            weight_init.c2_xavier_fill(self.offset_head[0])\n            weight_init.c2_xavier_fill(self.offset_head[1])\n        self.offset_predictor = Conv2d(head_channels, 2, kernel_size=1)\n        nn.init.normal_(self.offset_predictor.weight, 0, 0.001)\n        nn.init.constant_(self.offset_predictor.bias, 0)\n\n        self.center_loss = nn.MSELoss(reduction=\"none\")\n        self.offset_loss = nn.L1Loss(reduction=\"none\")\n\n    @classmethod\n    def from_config(cls, cfg, input_shape):\n        if cfg.INPUT.CROP.ENABLED:\n            assert cfg.INPUT.CROP.TYPE == \"absolute\"\n            train_size = cfg.INPUT.CROP.SIZE\n        else:\n            train_size = None\n        decoder_channels = [cfg.MODEL.INS_EMBED_HEAD.CONVS_DIM] * (\n            len(cfg.MODEL.INS_EMBED_HEAD.IN_FEATURES) - 1\n        ) + [cfg.MODEL.INS_EMBED_HEAD.ASPP_CHANNELS]\n        ret = dict(\n            input_shape={\n                k: v for k, v in input_shape.items() if k in cfg.MODEL.INS_EMBED_HEAD.IN_FEATURES\n            },\n            project_channels=cfg.MODEL.INS_EMBED_HEAD.PROJECT_CHANNELS,\n            aspp_dilations=cfg.MODEL.INS_EMBED_HEAD.ASPP_DILATIONS,\n            aspp_dropout=cfg.MODEL.INS_EMBED_HEAD.ASPP_DROPOUT,\n            decoder_channels=decoder_channels,\n            common_stride=cfg.MODEL.INS_EMBED_HEAD.COMMON_STRIDE,\n            norm=cfg.MODEL.INS_EMBED_HEAD.NORM,\n            train_size=train_size,\n            head_channels=cfg.MODEL.INS_EMBED_HEAD.HEAD_CHANNELS,\n            center_loss_weight=cfg.MODEL.INS_EMBED_HEAD.CENTER_LOSS_WEIGHT,\n            offset_loss_weight=cfg.MODEL.INS_EMBED_HEAD.OFFSET_LOSS_WEIGHT,\n            use_depthwise_separable_conv=cfg.MODEL.SEM_SEG_HEAD.USE_DEPTHWISE_SEPARABLE_CONV,\n        )\n        return ret\n\n    def forward(\n        self,\n        features,\n        center_targets=None,\n        center_weights=None,\n        offset_targets=None,\n        offset_weights=None,\n    ):\n        \"\"\"\n        Returns:\n            In training, returns (None, dict of losses)\n            In inference, returns (CxHxW logits, {})\n        \"\"\"\n        center, offset = self.layers(features)\n        if self.training:\n            return (\n                None,\n                None,\n                self.center_losses(center, center_targets, center_weights),\n                self.offset_losses(offset, offset_targets, offset_weights),\n            )\n        else:\n            center = F.interpolate(\n                center, scale_factor=self.common_stride, mode=\"bilinear\", align_corners=False\n            )\n            offset = (\n                F.interpolate(\n                    offset, scale_factor=self.common_stride, mode=\"bilinear\", align_corners=False\n                )\n                * self.common_stride\n            )\n            return center, offset, {}, {}\n\n    def layers(self, features):\n        assert self.decoder_only\n        y = super().layers(features)\n        # center\n        center = self.center_head(y)\n        center = self.center_predictor(center)\n        # offset\n        offset = self.offset_head(y)\n        offset = self.offset_predictor(offset)\n        return center, offset\n\n    def center_losses(self, predictions, targets, weights):\n        predictions = F.interpolate(\n            predictions, scale_factor=self.common_stride, mode=\"bilinear\", align_corners=False\n        )\n        loss = self.center_loss(predictions, targets) * weights\n        if weights.sum() > 0:\n            loss = loss.sum() / weights.sum()\n        else:\n            loss = loss.sum() * 0\n        losses = {\"loss_center\": loss * self.center_loss_weight}\n        return losses\n\n    def offset_losses(self, predictions, targets, weights):\n        predictions = (\n            F.interpolate(\n                predictions, scale_factor=self.common_stride, mode=\"bilinear\", align_corners=False\n            )\n            * self.common_stride\n        )\n        loss = self.offset_loss(predictions, targets) * weights\n        if weights.sum() > 0:\n            loss = loss.sum() / weights.sum()\n        else:\n            loss = loss.sum() * 0\n        losses = {\"loss_offset\": loss * self.offset_loss_weight}\n        return losses\n"
  },
  {
    "path": "VPS_Module/projects/Panoptic-DeepLab/panoptic_deeplab/post_processing.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n# Reference: https://github.com/bowenc0221/panoptic-deeplab/blob/master/segmentation/model/post_processing/instance_post_processing.py  # noqa\n\nfrom collections import Counter\nimport torch\nimport torch.nn.functional as F\n\n\ndef find_instance_center(center_heatmap, threshold=0.1, nms_kernel=3, top_k=None):\n    \"\"\"\n    Find the center points from the center heatmap.\n    Args:\n        center_heatmap: A Tensor of shape [1, H, W] of raw center heatmap output.\n        threshold: A float, threshold applied to center heatmap score.\n        nms_kernel: An integer, NMS max pooling kernel size.\n        top_k: An integer, top k centers to keep.\n    Returns:\n        A Tensor of shape [K, 2] where K is the number of center points. The\n            order of second dim is (y, x).\n    \"\"\"\n    # Thresholding, setting values below threshold to -1.\n    center_heatmap = F.threshold(center_heatmap, threshold, -1)\n\n    # NMS\n    nms_padding = (nms_kernel - 1) // 2\n    center_heatmap_max_pooled = F.max_pool2d(\n        center_heatmap, kernel_size=nms_kernel, stride=1, padding=nms_padding\n    )\n    center_heatmap[center_heatmap != center_heatmap_max_pooled] = -1\n\n    # Squeeze first two dimensions.\n    center_heatmap = center_heatmap.squeeze()\n    assert len(center_heatmap.size()) == 2, \"Something is wrong with center heatmap dimension.\"\n\n    # Find non-zero elements.\n    if top_k is None:\n        return torch.nonzero(center_heatmap > 0)\n    else:\n        # find top k centers.\n        top_k_scores, _ = torch.topk(torch.flatten(center_heatmap), top_k)\n        return torch.nonzero(center_heatmap > top_k_scores[-1].clamp_(min=0))\n\n\ndef group_pixels(center_points, offsets):\n    \"\"\"\n    Gives each pixel in the image an instance id.\n    Args:\n        center_points: A Tensor of shape [K, 2] where K is the number of center points.\n            The order of second dim is (y, x).\n        offsets: A Tensor of shape [2, H, W] of raw offset output. The order of\n            second dim is (offset_y, offset_x).\n    Returns:\n        A Tensor of shape [1, H, W] with values in range [1, K], which represents\n            the center this pixel belongs to.\n    \"\"\"\n    height, width = offsets.size()[1:]\n\n    # Generates a coordinate map, where each location is the coordinate of\n    # that location.\n    y_coord, x_coord = torch.meshgrid(\n        torch.arange(height, dtype=offsets.dtype, device=offsets.device),\n        torch.arange(width, dtype=offsets.dtype, device=offsets.device),\n    )\n    coord = torch.cat((y_coord.unsqueeze(0), x_coord.unsqueeze(0)), dim=0)\n\n    center_loc = coord + offsets\n    center_loc = center_loc.flatten(1).T.unsqueeze_(0)  # [1, H*W, 2]\n    center_points = center_points.unsqueeze(1)  # [K, 1, 2]\n\n    # Distance: [K, H*W].\n    distance = torch.norm(center_points - center_loc, dim=-1)\n\n    # Finds center with minimum distance at each location, offset by 1, to\n    # reserve id=0 for stuff.\n    instance_id = torch.argmin(distance, dim=0).reshape((1, height, width)) + 1\n    return instance_id\n\n\ndef get_instance_segmentation(\n    sem_seg, center_heatmap, offsets, thing_seg, thing_ids, threshold=0.1, nms_kernel=3, top_k=None\n):\n    \"\"\"\n    Post-processing for instance segmentation, gets class agnostic instance id.\n    Args:\n        sem_seg: A Tensor of shape [1, H, W], predicted semantic label.\n        center_heatmap: A Tensor of shape [1, H, W] of raw center heatmap output.\n        offsets: A Tensor of shape [2, H, W] of raw offset output. The order of\n            second dim is (offset_y, offset_x).\n        thing_seg: A Tensor of shape [1, H, W], predicted foreground mask,\n            if not provided, inference from semantic prediction.\n        thing_ids: A set of ids from contiguous category ids belonging\n            to thing categories.\n        threshold: A float, threshold applied to center heatmap score.\n        nms_kernel: An integer, NMS max pooling kernel size.\n        top_k: An integer, top k centers to keep.\n    Returns:\n        A Tensor of shape [1, H, W] with value 0 represent stuff (not instance)\n            and other positive values represent different instances.\n        A Tensor of shape [1, K, 2] where K is the number of center points.\n            The order of second dim is (y, x).\n    \"\"\"\n    center_points = find_instance_center(\n        center_heatmap, threshold=threshold, nms_kernel=nms_kernel, top_k=top_k\n    )\n    if center_points.size(0) == 0:\n        return torch.zeros_like(sem_seg), center_points.unsqueeze(0)\n    ins_seg = group_pixels(center_points, offsets)\n    return thing_seg * ins_seg, center_points.unsqueeze(0)\n\n\ndef merge_semantic_and_instance(\n    sem_seg, ins_seg, semantic_thing_seg, label_divisor, thing_ids, stuff_area, void_label\n):\n    \"\"\"\n    Post-processing for panoptic segmentation, by merging semantic segmentation\n        label and class agnostic instance segmentation label.\n    Args:\n        sem_seg: A Tensor of shape [1, H, W], predicted category id for each pixel.\n        ins_seg: A Tensor of shape [1, H, W], predicted instance id for each pixel.\n        semantic_thing_seg: A Tensor of shape [1, H, W], predicted foreground mask.\n        label_divisor: An integer, used to convert panoptic id =\n            semantic id * label_divisor + instance_id.\n        thing_ids: Set, a set of ids from contiguous category ids belonging\n            to thing categories.\n        stuff_area: An integer, remove stuff whose area is less tan stuff_area.\n        void_label: An integer, indicates the region has no confident prediction.\n    Returns:\n        A Tensor of shape [1, H, W].\n    \"\"\"\n    # In case thing mask does not align with semantic prediction.\n    pan_seg = torch.zeros_like(sem_seg) + void_label\n    is_thing = (ins_seg > 0) & (semantic_thing_seg > 0)\n\n    # Keep track of instance id for each class.\n    class_id_tracker = Counter()\n\n    # Paste thing by majority voting.\n    instance_ids = torch.unique(ins_seg)\n    for ins_id in instance_ids:\n        if ins_id == 0:\n            continue\n        # Make sure only do majority voting within `semantic_thing_seg`.\n        thing_mask = (ins_seg == ins_id) & is_thing\n        if torch.nonzero(thing_mask).size(0) == 0:\n            continue\n        class_id, _ = torch.mode(sem_seg[thing_mask].view(-1))\n        class_id_tracker[class_id.item()] += 1\n        new_ins_id = class_id_tracker[class_id.item()]\n        pan_seg[thing_mask] = class_id * label_divisor + new_ins_id\n\n    # Paste stuff to unoccupied area.\n    class_ids = torch.unique(sem_seg)\n    for class_id in class_ids:\n        if class_id.item() in thing_ids:\n            # thing class\n            continue\n        # Calculate stuff area.\n        stuff_mask = (sem_seg == class_id) & (ins_seg == 0)\n        if stuff_mask.sum().item() >= stuff_area:\n            pan_seg[stuff_mask] = class_id * label_divisor\n\n    return pan_seg\n\n\ndef get_panoptic_segmentation(\n    sem_seg,\n    center_heatmap,\n    offsets,\n    thing_ids,\n    label_divisor,\n    stuff_area,\n    void_label,\n    threshold=0.1,\n    nms_kernel=7,\n    top_k=200,\n    foreground_mask=None,\n):\n    \"\"\"\n    Post-processing for panoptic segmentation.\n    Args:\n        sem_seg: A Tensor of shape [1, H, W] of predicted semantic label.\n        center_heatmap: A Tensor of shape [1, H, W] of raw center heatmap output.\n        offsets: A Tensor of shape [2, H, W] of raw offset output. The order of\n            second dim is (offset_y, offset_x).\n        thing_ids: A set of ids from contiguous category ids belonging\n            to thing categories.\n        label_divisor: An integer, used to convert panoptic id =\n            semantic id * label_divisor + instance_id.\n        stuff_area: An integer, remove stuff whose area is less tan stuff_area.\n        void_label: An integer, indicates the region has no confident prediction.\n        threshold: A float, threshold applied to center heatmap score.\n        nms_kernel: An integer, NMS max pooling kernel size.\n        top_k: An integer, top k centers to keep.\n        foreground_mask: Optional, A Tensor of shape [1, H, W] of predicted\n            binary foreground mask. If not provided, it will be generated from\n            sem_seg.\n    Returns:\n        A Tensor of shape [1, H, W], int64.\n    \"\"\"\n    if sem_seg.dim() != 3 and sem_seg.size(0) != 1:\n        raise ValueError(\"Semantic prediction with un-supported shape: {}.\".format(sem_seg.size()))\n    if center_heatmap.dim() != 3:\n        raise ValueError(\n            \"Center prediction with un-supported dimension: {}.\".format(center_heatmap.dim())\n        )\n    if offsets.dim() != 3:\n        raise ValueError(\"Offset prediction with un-supported dimension: {}.\".format(offsets.dim()))\n    if foreground_mask is not None:\n        if foreground_mask.dim() != 3 and foreground_mask.size(0) != 1:\n            raise ValueError(\n                \"Foreground prediction with un-supported shape: {}.\".format(sem_seg.size())\n            )\n        thing_seg = foreground_mask\n    else:\n        # inference from semantic segmentation\n        thing_seg = torch.zeros_like(sem_seg)\n        for thing_class in list(thing_ids):\n            thing_seg[sem_seg == thing_class] = 1\n\n    instance, center = get_instance_segmentation(\n        sem_seg,\n        center_heatmap,\n        offsets,\n        thing_seg,\n        thing_ids,\n        threshold=threshold,\n        nms_kernel=nms_kernel,\n        top_k=top_k,\n    )\n    panoptic = merge_semantic_and_instance(\n        sem_seg, instance, thing_seg, label_divisor, thing_ids, stuff_area, void_label\n    )\n\n    return panoptic, center\n"
  },
  {
    "path": "VPS_Module/projects/Panoptic-DeepLab/panoptic_deeplab/target_generator.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n# Reference: https://github.com/bowenc0221/panoptic-deeplab/blob/aa934324b55a34ce95fea143aea1cb7a6dbe04bd/segmentation/data/transforms/target_transforms.py#L11  # noqa\nimport numpy as np\nimport torch\n\n\nclass PanopticDeepLabTargetGenerator(object):\n    \"\"\"\n    Generates training targets for Panoptic-DeepLab.\n    \"\"\"\n\n    def __init__(\n        self,\n        ignore_label,\n        thing_ids,\n        sigma=8,\n        ignore_stuff_in_offset=False,\n        small_instance_area=0,\n        small_instance_weight=1,\n        ignore_crowd_in_semantic=False,\n    ):\n        \"\"\"\n        Args:\n            ignore_label: Integer, the ignore label for semantic segmentation.\n            thing_ids: Set, a set of ids from contiguous category ids belonging\n                to thing categories.\n            sigma: the sigma for Gaussian kernel.\n            ignore_stuff_in_offset: Boolean, whether to ignore stuff region when\n                training the offset branch.\n            small_instance_area: Integer, indicates largest area for small instances.\n            small_instance_weight: Integer, indicates semantic loss weights for\n                small instances.\n            ignore_crowd_in_semantic: Boolean, whether to ignore crowd region in\n                semantic segmentation branch, crowd region is ignored in the original\n                TensorFlow implementation.\n        \"\"\"\n        self.ignore_label = ignore_label\n        self.thing_ids = set(thing_ids)\n        self.ignore_stuff_in_offset = ignore_stuff_in_offset\n        self.small_instance_area = small_instance_area\n        self.small_instance_weight = small_instance_weight\n        self.ignore_crowd_in_semantic = ignore_crowd_in_semantic\n\n        # Generate the default Gaussian image for each center\n        self.sigma = sigma\n        size = 6 * sigma + 3\n        x = np.arange(0, size, 1, float)\n        y = x[:, np.newaxis]\n        x0, y0 = 3 * sigma + 1, 3 * sigma + 1\n        self.g = np.exp(-((x - x0) ** 2 + (y - y0) ** 2) / (2 * sigma ** 2))\n\n    def __call__(self, panoptic, segments_info):\n        \"\"\"Generates the training target.\n        reference: https://github.com/mcordts/cityscapesScripts/blob/master/cityscapesscripts/preparation/createPanopticImgs.py  # noqa\n        reference: https://github.com/facebookresearch/detectron2/blob/main/datasets/prepare_panoptic_fpn.py#L18  # noqa\n\n        Args:\n            panoptic: numpy.array, panoptic label, we assume it is already\n                converted from rgb image by panopticapi.utils.rgb2id.\n            segments_info (list[dict]): see detectron2 documentation of \"Use Custom Datasets\".\n\n        Returns:\n            A dictionary with fields:\n                - sem_seg: Tensor, semantic label, shape=(H, W).\n                - center: Tensor, center heatmap, shape=(H, W).\n                - center_points: List, center coordinates, with tuple\n                    (y-coord, x-coord).\n                - offset: Tensor, offset, shape=(2, H, W), first dim is\n                    (offset_y, offset_x).\n                - sem_seg_weights: Tensor, loss weight for semantic prediction,\n                    shape=(H, W).\n                - center_weights: Tensor, ignore region of center prediction,\n                    shape=(H, W), used as weights for center regression 0 is\n                    ignore, 1 is has instance. Multiply this mask to loss.\n                - offset_weights: Tensor, ignore region of offset prediction,\n                    shape=(H, W), used as weights for offset regression 0 is\n                    ignore, 1 is has instance. Multiply this mask to loss.\n        \"\"\"\n        height, width = panoptic.shape[0], panoptic.shape[1]\n        semantic = np.zeros_like(panoptic, dtype=np.uint8) + self.ignore_label\n        center = np.zeros((height, width), dtype=np.float32)\n        center_pts = []\n        offset = np.zeros((2, height, width), dtype=np.float32)\n        y_coord, x_coord = np.meshgrid(\n            np.arange(height, dtype=np.float32), np.arange(width, dtype=np.float32), indexing=\"ij\"\n        )\n        # Generate pixel-wise loss weights\n        semantic_weights = np.ones_like(panoptic, dtype=np.uint8)\n        # 0: ignore, 1: has instance\n        # three conditions for a region to be ignored for instance branches:\n        # (1) It is labeled as `ignore_label`\n        # (2) It is crowd region (iscrowd=1)\n        # (3) (Optional) It is stuff region (for offset branch)\n        center_weights = np.zeros_like(panoptic, dtype=np.uint8)\n        offset_weights = np.zeros_like(panoptic, dtype=np.uint8)\n        for seg in segments_info:\n            cat_id = seg[\"category_id\"]\n            if not (self.ignore_crowd_in_semantic and seg[\"iscrowd\"]):\n                semantic[panoptic == seg[\"id\"]] = cat_id\n            if not seg[\"iscrowd\"]:\n                # Ignored regions are not in `segments_info`.\n                # Handle crowd region.\n                center_weights[panoptic == seg[\"id\"]] = 1\n                if not self.ignore_stuff_in_offset or cat_id in self.thing_ids:\n                    offset_weights[panoptic == seg[\"id\"]] = 1\n            if cat_id in self.thing_ids:\n                # find instance center\n                mask_index = np.where(panoptic == seg[\"id\"])\n                if len(mask_index[0]) == 0:\n                    # the instance is completely cropped\n                    continue\n\n                # Find instance area\n                ins_area = len(mask_index[0])\n                if ins_area < self.small_instance_area:\n                    semantic_weights[panoptic == seg[\"id\"]] = self.small_instance_weight\n\n                center_y, center_x = np.mean(mask_index[0]), np.mean(mask_index[1])\n                center_pts.append([center_y, center_x])\n\n                # generate center heatmap\n                y, x = int(round(center_y)), int(round(center_x))\n                sigma = self.sigma\n                # upper left\n                ul = int(np.round(x - 3 * sigma - 1)), int(np.round(y - 3 * sigma - 1))\n                # bottom right\n                br = int(np.round(x + 3 * sigma + 2)), int(np.round(y + 3 * sigma + 2))\n\n                # start and end indices in default Gaussian image\n                gaussian_x0, gaussian_x1 = max(0, -ul[0]), min(br[0], width) - ul[0]\n                gaussian_y0, gaussian_y1 = max(0, -ul[1]), min(br[1], height) - ul[1]\n\n                # start and end indices in center heatmap image\n                center_x0, center_x1 = max(0, ul[0]), min(br[0], width)\n                center_y0, center_y1 = max(0, ul[1]), min(br[1], height)\n                center[center_y0:center_y1, center_x0:center_x1] = np.maximum(\n                    center[center_y0:center_y1, center_x0:center_x1],\n                    self.g[gaussian_y0:gaussian_y1, gaussian_x0:gaussian_x1],\n                )\n\n                # generate offset (2, h, w) -> (y-dir, x-dir)\n                offset[0][mask_index] = center_y - y_coord[mask_index]\n                offset[1][mask_index] = center_x - x_coord[mask_index]\n\n        center_weights = center_weights[None]\n        offset_weights = offset_weights[None]\n        return dict(\n            sem_seg=torch.as_tensor(semantic.astype(\"long\")),\n            center=torch.as_tensor(center.astype(np.float32)),\n            center_points=center_pts,\n            offset=torch.as_tensor(offset.astype(np.float32)),\n            sem_seg_weights=torch.as_tensor(semantic_weights.astype(np.float32)),\n            center_weights=torch.as_tensor(center_weights.astype(np.float32)),\n            offset_weights=torch.as_tensor(offset_weights.astype(np.float32)),\n        )\n"
  },
  {
    "path": "VPS_Module/projects/Panoptic-DeepLab/train_net.py",
    "content": "#!/usr/bin/env python3\n# Copyright (c) Facebook, Inc. and its affiliates.\n\n\"\"\"\nPanoptic-DeepLab Training Script.\nThis script is a simplified version of the training script in detectron2/tools.\n\"\"\"\n\nimport os\nimport torch\n\nimport detectron2.data.transforms as T\nimport detectron2.utils.comm as comm\nfrom detectron2.checkpoint import DetectionCheckpointer\nfrom detectron2.config import get_cfg\nfrom detectron2.data import MetadataCatalog, build_detection_train_loader\nfrom detectron2.engine import DefaultTrainer, default_argument_parser, default_setup, launch\nfrom detectron2.evaluation import (\n    CityscapesInstanceEvaluator,\n    CityscapesSemSegEvaluator,\n    COCOEvaluator,\n    COCOPanopticEvaluator,\n    DatasetEvaluators,\n)\nfrom detectron2.projects.deeplab import build_lr_scheduler\nfrom detectron2.projects.panoptic_deeplab import (\n    PanopticDeeplabDatasetMapper,\n    add_panoptic_deeplab_config,\n)\nfrom detectron2.solver import get_default_optimizer_params\nfrom detectron2.solver.build import maybe_add_gradient_clipping\n\n\ndef build_sem_seg_train_aug(cfg):\n    augs = [\n        T.ResizeShortestEdge(\n            cfg.INPUT.MIN_SIZE_TRAIN, cfg.INPUT.MAX_SIZE_TRAIN, cfg.INPUT.MIN_SIZE_TRAIN_SAMPLING\n        )\n    ]\n    if cfg.INPUT.CROP.ENABLED:\n        augs.append(T.RandomCrop(cfg.INPUT.CROP.TYPE, cfg.INPUT.CROP.SIZE))\n    augs.append(T.RandomFlip())\n    return augs\n\n\nclass Trainer(DefaultTrainer):\n    \"\"\"\n    We use the \"DefaultTrainer\" which contains a number pre-defined logic for\n    standard training workflow. They may not work for you, especially if you\n    are working on a new research project. In that case you can use the cleaner\n    \"SimpleTrainer\", or write your own training loop.\n    \"\"\"\n\n    @classmethod\n    def build_evaluator(cls, cfg, dataset_name, output_folder=None):\n        \"\"\"\n        Create evaluator(s) for a given dataset.\n        This uses the special metadata \"evaluator_type\" associated with each builtin dataset.\n        For your own dataset, you can simply create an evaluator manually in your\n        script and do not have to worry about the hacky if-else logic here.\n        \"\"\"\n        if cfg.MODEL.PANOPTIC_DEEPLAB.BENCHMARK_NETWORK_SPEED:\n            return None\n        if output_folder is None:\n            output_folder = os.path.join(cfg.OUTPUT_DIR, \"inference\")\n        evaluator_list = []\n        evaluator_type = MetadataCatalog.get(dataset_name).evaluator_type\n        if evaluator_type in [\"cityscapes_panoptic_seg\", \"coco_panoptic_seg\"]:\n            evaluator_list.append(COCOPanopticEvaluator(dataset_name, output_folder))\n        if evaluator_type == \"cityscapes_panoptic_seg\":\n            assert (\n                torch.cuda.device_count() > comm.get_rank()\n            ), \"CityscapesEvaluator currently do not work with multiple machines.\"\n            evaluator_list.append(CityscapesSemSegEvaluator(dataset_name))\n            evaluator_list.append(CityscapesInstanceEvaluator(dataset_name))\n        if evaluator_type == \"coco_panoptic_seg\":\n            # `thing_classes` in COCO panoptic metadata includes both thing and\n            # stuff classes for visualization. COCOEvaluator requires metadata\n            # which only contains thing classes, thus we map the name of\n            # panoptic datasets to their corresponding instance datasets.\n            dataset_name_mapper = {\n                \"coco_2017_val_panoptic\": \"coco_2017_val\",\n                \"coco_2017_val_100_panoptic\": \"coco_2017_val_100\",\n            }\n            evaluator_list.append(\n                COCOEvaluator(dataset_name_mapper[dataset_name], output_dir=output_folder)\n            )\n        if len(evaluator_list) == 0:\n            raise NotImplementedError(\n                \"no Evaluator for the dataset {} with the type {}\".format(\n                    dataset_name, evaluator_type\n                )\n            )\n        elif len(evaluator_list) == 1:\n            return evaluator_list[0]\n        return DatasetEvaluators(evaluator_list)\n\n    @classmethod\n    def build_train_loader(cls, cfg):\n        mapper = PanopticDeeplabDatasetMapper(cfg, augmentations=build_sem_seg_train_aug(cfg))\n        return build_detection_train_loader(cfg, mapper=mapper)\n\n    @classmethod\n    def build_lr_scheduler(cls, cfg, optimizer):\n        \"\"\"\n        It now calls :func:`detectron2.solver.build_lr_scheduler`.\n        Overwrite it if you'd like a different scheduler.\n        \"\"\"\n        return build_lr_scheduler(cfg, optimizer)\n\n    @classmethod\n    def build_optimizer(cls, cfg, model):\n        \"\"\"\n        Build an optimizer from config.\n        \"\"\"\n        params = get_default_optimizer_params(\n            model,\n            weight_decay=cfg.SOLVER.WEIGHT_DECAY,\n            weight_decay_norm=cfg.SOLVER.WEIGHT_DECAY_NORM,\n        )\n\n        optimizer_type = cfg.SOLVER.OPTIMIZER\n        if optimizer_type == \"SGD\":\n            return maybe_add_gradient_clipping(cfg, torch.optim.SGD)(\n                params,\n                cfg.SOLVER.BASE_LR,\n                momentum=cfg.SOLVER.MOMENTUM,\n                nesterov=cfg.SOLVER.NESTEROV,\n            )\n        elif optimizer_type == \"ADAM\":\n            return maybe_add_gradient_clipping(cfg, torch.optim.Adam)(params, cfg.SOLVER.BASE_LR)\n        else:\n            raise NotImplementedError(f\"no optimizer type {optimizer_type}\")\n\n\ndef setup(args):\n    \"\"\"\n    Create configs and perform basic setups.\n    \"\"\"\n    cfg = get_cfg()\n    add_panoptic_deeplab_config(cfg)\n    cfg.merge_from_file(args.config_file)\n    cfg.merge_from_list(args.opts)\n    cfg.freeze()\n    default_setup(cfg, args)\n    return cfg\n\n\ndef main(args):\n    cfg = setup(args)\n\n    if args.eval_only:\n        model = Trainer.build_model(cfg)\n        DetectionCheckpointer(model, save_dir=cfg.OUTPUT_DIR).resume_or_load(\n            cfg.MODEL.WEIGHTS, resume=args.resume\n        )\n        res = Trainer.test(cfg, model)\n        return res\n\n    trainer = Trainer(cfg)\n    trainer.resume_or_load(resume=args.resume)\n    return trainer.train()\n\n\nif __name__ == \"__main__\":\n    args = default_argument_parser().parse_args()\n    print(\"Command Line Args:\", args)\n    launch(\n        main,\n        args.num_gpus,\n        num_machines=args.num_machines,\n        machine_rank=args.machine_rank,\n        dist_url=args.dist_url,\n        args=(args,),\n    )\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/README.md",
    "content": "# PointRend: Image Segmentation as Rendering\n\nAlexander Kirillov, Yuxin Wu, Kaiming He, Ross Girshick\n\n[[`arXiv`](https://arxiv.org/abs/1912.08193)] [[`BibTeX`](#CitingPointRend)]\n\n<div align=\"center\">\n  <img src=\"https://alexander-kirillov.github.io/images/kirillov2019pointrend.jpg\"/>\n</div><br/>\n\nIn this repository, we release code for PointRend in Detectron2. PointRend can be flexibly applied to both instance and semantic segmentation tasks by building on top of existing state-of-the-art models.\n\n## Quick start and visualization\n\nThis [Colab Notebook](https://colab.research.google.com/drive/1isGPL5h5_cKoPPhVL9XhMokRtHDvmMVL) tutorial contains examples of PointRend usage and visualizations of its point sampling stages.\n\n## Training\n\nTo train a model with 8 GPUs run:\n```bash\ncd /path/to/detectron2/projects/PointRend\npython train_net.py --config-file configs/InstanceSegmentation/pointrend_rcnn_R_50_FPN_1x_coco.yaml --num-gpus 8\n```\n\n## Evaluation\n\nModel evaluation can be done similarly:\n```bash\ncd /path/to/detectron2/projects/PointRend\npython train_net.py --config-file configs/InstanceSegmentation/pointrend_rcnn_R_50_FPN_1x_coco.yaml --eval-only MODEL.WEIGHTS /path/to/model_checkpoint\n```\n\n# Pretrained Models\n\n## Instance Segmentation\n#### COCO\n\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Mask<br/>head</th>\n<th valign=\"bottom\">Backbone</th>\n<th valign=\"bottom\">lr<br/>sched</th>\n<th valign=\"bottom\">Output<br/>resolution</th>\n<th valign=\"bottom\">mask<br/>AP</th>\n<th valign=\"bottom\">mask<br/>AP&ast;</th>\n<th valign=\"bottom\">model id</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n <tr><td align=\"left\"><a href=\"configs/InstanceSegmentation/pointrend_rcnn_R_50_FPN_1x_coco.yaml\">PointRend</a></td>\n<td align=\"center\">R50-FPN</td>\n<td align=\"center\">1&times;</td>\n<td align=\"center\">224&times;224</td>\n<td align=\"center\">36.2</td>\n<td align=\"center\">39.7</td>\n<td align=\"center\">164254221</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/detectron2/PointRend/InstanceSegmentation/pointrend_rcnn_R_50_FPN_1x_coco/164254221/model_final_736f5a.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/PointRend/InstanceSegmentation/pointrend_rcnn_R_50_FPN_1x_coco/164254221/metrics.json\">metrics</a></td>\n</tr>\n <tr><td align=\"left\"><a href=\"configs/InstanceSegmentation/pointrend_rcnn_R_50_FPN_3x_coco.yaml\">PointRend</a></td>\n<td align=\"center\">R50-FPN</td>\n<td align=\"center\">3&times;</td>\n<td align=\"center\">224&times;224</td>\n<td align=\"center\">38.3</td>\n<td align=\"center\">41.6</td>\n<td align=\"center\">164955410</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/detectron2/PointRend/InstanceSegmentation/pointrend_rcnn_R_50_FPN_3x_coco/164955410/model_final_edd263.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/PointRend/InstanceSegmentation/pointrend_rcnn_R_50_FPN_3x_coco/164955410/metrics.json\">metrics</a></td>\n</tr>\n</tr>\n <tr><td align=\"left\"><a href=\"configs/InstanceSegmentation/pointrend_rcnn_R_101_FPN_3x_coco.yaml\">PointRend</a></td>\n<td align=\"center\">R101-FPN</td>\n<td align=\"center\">3&times;</td>\n<td align=\"center\">224&times;224</td>\n<td align=\"center\">40.1</td>\n<td align=\"center\">43.8</td>\n<td align=\"center\"></td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/detectron2/PointRend/InstanceSegmentation/pointrend_rcnn_R_101_FPN_3x_coco/28119983/model_final_3f4d2a.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/PointRend/InstanceSegmentation/pointrend_rcnn_R_101_FPN_3x_coco/28119983/metrics.json\">metrics</a></td>\n</tr>\n</tr>\n <tr><td align=\"left\"><a href=\"configs/InstanceSegmentation/pointrend_rcnn_X_101_32x8d_FPN_3x_coco.yaml\">PointRend</a></td>\n<td align=\"center\">X101-FPN</td>\n<td align=\"center\">3&times;</td>\n<td align=\"center\">224&times;224</td>\n<td align=\"center\">41.1</td>\n<td align=\"center\">44.7</td>\n<td align=\"center\"></td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/detectron2/PointRend/InstanceSegmentation/pointrend_rcnn_X_101_32x8d_FPN_3x_coco/28119989/model_final_ba17b9.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/PointRend/InstanceSegmentation/pointrend_rcnn_X_101_32x8d_FPN_3x_coco/28119989/metrics.json\">metrics</a></td>\n</tr>\n</tbody></table>\n\nAP&ast; is COCO mask AP evaluated against the higher-quality LVIS annotations; see the paper for details.\nRun `python detectron2/datasets/prepare_cocofied_lvis.py` to prepare GT files for AP&ast; evaluation.\nSince LVIS annotations are not exhaustive, `lvis-api` and not `cocoapi` should be used to evaluate AP&ast;.\n\n#### Cityscapes\nCityscapes model is trained with ImageNet pretraining.\n\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Mask<br/>head</th>\n<th valign=\"bottom\">Backbone</th>\n<th valign=\"bottom\">lr<br/>sched</th>\n<th valign=\"bottom\">Output<br/>resolution</th>\n<th valign=\"bottom\">mask<br/>AP</th>\n<th valign=\"bottom\">model id</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n <tr><td align=\"left\"><a href=\"configs/InstanceSegmentation/pointrend_rcnn_R_50_FPN_1x_cityscapes.yaml\">PointRend</a></td>\n<td align=\"center\">R50-FPN</td>\n<td align=\"center\">1&times;</td>\n<td align=\"center\">224&times;224</td>\n<td align=\"center\">35.9</td>\n<td align=\"center\">164255101</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/detectron2/PointRend/InstanceSegmentation/pointrend_rcnn_R_50_FPN_1x_cityscapes/164255101/model_final_115bfb.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/PointRend/InstanceSegmentation/pointrend_rcnn_R_50_FPN_1x_cityscapes/164255101/metrics.json\">metrics</a></td>\n</tr>\n</tbody></table>\n\n\n## Semantic Segmentation\n\n#### Cityscapes\nCityscapes model is trained with ImageNet pretraining.\n\n<table><tbody>\n<!-- START TABLE -->\n<!-- TABLE HEADER -->\n<th valign=\"bottom\">Method</th>\n<th valign=\"bottom\">Backbone</th>\n<th valign=\"bottom\">Output<br/>resolution</th>\n<th valign=\"bottom\">mIoU</th>\n<th valign=\"bottom\">model id</th>\n<th valign=\"bottom\">download</th>\n<!-- TABLE BODY -->\n <tr><td align=\"left\"><a href=\"configs/SemanticSegmentation/pointrend_semantic_R_101_FPN_1x_cityscapes.yaml\">SemanticFPN + PointRend</a></td>\n<td align=\"center\">R101-FPN</td>\n<td align=\"center\">1024&times;2048</td>\n<td align=\"center\">78.9</td>\n<td align=\"center\">202576688</td>\n<td align=\"center\"><a href=\"https://dl.fbaipublicfiles.com/detectron2/PointRend/SemanticSegmentation/pointrend_semantic_R_101_FPN_1x_cityscapes/202576688/model_final_cf6ac1.pkl\">model</a>&nbsp;|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/PointRend/SemanticSegmentation/pointrend_semantic_R_101_FPN_1x_cityscapes/202576688/metrics.json\">metrics</a></td>\n</tr>\n</tbody></table>\n\n## <a name=\"CitingPointRend\"></a>Citing PointRend\n\nIf you use PointRend, please use the following BibTeX entry.\n\n```BibTeX\n@InProceedings{kirillov2019pointrend,\n  title={{PointRend}: Image Segmentation as Rendering},\n  author={Alexander Kirillov and Yuxin Wu and Kaiming He and Ross Girshick},\n  journal={ArXiv:1912.08193},\n  year={2019}\n}\n```\n\n## <a name=\"CitingImplicitPointRend\"></a>Citing Implicit PointRend\n\nIf you use Implicit PointRend, please use the following BibTeX entry.\n\n```BibTeX\n@InProceedings{cheng2021pointly,\n  title={Pointly-Supervised Instance Segmentation,\n  author={Bowen Cheng and Omkar Parkhi and Alexander Kirillov},\n  journal={ArXiv},\n  year={2021}\n}\n```\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/configs/InstanceSegmentation/Base-Implicit-PointRend.yaml",
    "content": "_BASE_: \"../../../../configs/Base-RCNN-FPN.yaml\"\nMODEL:\n  MASK_ON: true\n  ROI_MASK_HEAD:\n    NAME: \"ImplicitPointRendMaskHead\"\n    POOLER_TYPE: \"\"  # No RoI pooling, let the head process image features directly\n    FC_DIM: 1024\n    NUM_FC: 2\n  POINT_HEAD:\n    NAME: \"ImplicitPointHead\"\n    FC_DIM: 256\n    NUM_FC: 3\n    IN_FEATURES: [\"p2\"]\n    NUM_CLASSES: 80\n    CLS_AGNOSTIC_MASK: False\n    TRAIN_NUM_POINTS: 196\n    SUBDIVISION_STEPS: 3\n    SUBDIVISION_NUM_POINTS: 784\n  IMPLICIT_POINTREND:\n    IMAGE_FEATURE_ENABLED: True\n    POS_ENC_ENABLED: True\n    PARAMS_L2_REGULARIZER: 0.00001\nINPUT:\n  # PointRend for instance segmentation does not work with \"polygon\" mask_format.\n  MASK_FORMAT: \"bitmask\"\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/configs/InstanceSegmentation/Base-PointRend-RCNN-FPN.yaml",
    "content": "_BASE_: \"../../../../configs/Base-RCNN-FPN.yaml\"\nMODEL:\n  MASK_ON: true\n  ROI_BOX_HEAD:\n    TRAIN_ON_PRED_BOXES: True\n  ROI_MASK_HEAD:\n    POOLER_TYPE: \"\"  # No RoI pooling, let the head process image features directly\n    NAME: \"PointRendMaskHead\"\n    FC_DIM: 1024\n    NUM_FC: 2\n    OUTPUT_SIDE_RESOLUTION: 7\n    IN_FEATURES: [\"p2\"]  # for the coarse mask head\n    POINT_HEAD_ON: True\n  POINT_HEAD:\n    FC_DIM: 256\n    NUM_FC: 3\n    IN_FEATURES: [\"p2\"]\nINPUT:\n  # PointRend for instance segmentation does not work with \"polygon\" mask_format.\n  MASK_FORMAT: \"bitmask\"\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/configs/InstanceSegmentation/implicit_pointrend_R_50_FPN_1x_coco.yaml",
    "content": "_BASE_: \"Base-Implicit-PointRend.yaml\"\nMODEL:\n  WEIGHTS: detectron2://ImageNetPretrained/MSRA/R-50.pkl\n  RESNETS:\n    DEPTH: 50\n# To add COCO AP evaluation against the higher-quality LVIS annotations.\n# DATASETS:\n#   TEST: (\"coco_2017_val\", \"lvis_v0.5_val_cocofied\")\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/configs/InstanceSegmentation/implicit_pointrend_R_50_FPN_3x_coco.yaml",
    "content": "_BASE_: \"Base-Implicit-PointRend.yaml\"\nMODEL:\n  WEIGHTS: detectron2://ImageNetPretrained/MSRA/R-50.pkl\n  RESNETS:\n    DEPTH: 50\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n# To add COCO AP evaluation against the higher-quality LVIS annotations.\n# DATASETS:\n#   TEST: (\"coco_2017_val\", \"lvis_v0.5_val_cocofied\")\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/configs/InstanceSegmentation/pointrend_rcnn_R_101_FPN_3x_coco.yaml",
    "content": "_BASE_: Base-PointRend-RCNN-FPN.yaml\nMODEL:\n  WEIGHTS: detectron2://ImageNetPretrained/MSRA/R-101.pkl\n  MASK_ON: true\n  RESNETS:\n    DEPTH: 101\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n# To add COCO AP evaluation against the higher-quality LVIS annotations.\n# DATASETS:\n#   TEST: (\"coco_2017_val\", \"lvis_v0.5_val_cocofied\")\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/configs/InstanceSegmentation/pointrend_rcnn_R_50_FPN_1x_cityscapes.yaml",
    "content": "_BASE_: Base-PointRend-RCNN-FPN.yaml\nMODEL:\n  WEIGHTS: detectron2://ImageNetPretrained/MSRA/R-50.pkl\n  RESNETS:\n    DEPTH: 50\n  ROI_HEADS:\n    NUM_CLASSES: 8\n  POINT_HEAD:\n    NUM_CLASSES: 8\nDATASETS:\n  TEST: (\"cityscapes_fine_instance_seg_val\",)\n  TRAIN: (\"cityscapes_fine_instance_seg_train\",)\nSOLVER:\n  BASE_LR: 0.01\n  IMS_PER_BATCH: 8\n  MAX_ITER: 24000\n  STEPS: (18000,)\nINPUT:\n  MAX_SIZE_TEST: 2048\n  MAX_SIZE_TRAIN: 2048\n  MIN_SIZE_TEST: 1024\n  MIN_SIZE_TRAIN: (800, 832, 864, 896, 928, 960, 992, 1024)\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/configs/InstanceSegmentation/pointrend_rcnn_R_50_FPN_1x_coco.yaml",
    "content": "_BASE_: Base-PointRend-RCNN-FPN.yaml\nMODEL:\n  WEIGHTS: detectron2://ImageNetPretrained/MSRA/R-50.pkl\n  RESNETS:\n    DEPTH: 50\n# To add COCO AP evaluation against the higher-quality LVIS annotations.\n# DATASETS:\n#   TEST: (\"coco_2017_val\", \"lvis_v0.5_val_cocofied\")\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/configs/InstanceSegmentation/pointrend_rcnn_R_50_FPN_3x_coco.yaml",
    "content": "_BASE_: Base-PointRend-RCNN-FPN.yaml\nMODEL:\n  WEIGHTS: detectron2://ImageNetPretrained/MSRA/R-50.pkl\n  RESNETS:\n    DEPTH: 50\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n# To add COCO AP evaluation against the higher-quality LVIS annotations.\n# DATASETS:\n#   TEST: (\"coco_2017_val\", \"lvis_v0.5_val_cocofied\")\n\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/configs/InstanceSegmentation/pointrend_rcnn_X_101_32x8d_FPN_3x_coco.yaml",
    "content": "_BASE_: Base-PointRend-RCNN-FPN.yaml\nMODEL:\n  MASK_ON: True\n  WEIGHTS: \"detectron2://ImageNetPretrained/FAIR/X-101-32x8d.pkl\"\n  PIXEL_STD: [57.375, 57.120, 58.395]\n  RESNETS:\n    STRIDE_IN_1X1: False  # this is a C2 model\n    NUM_GROUPS: 32\n    WIDTH_PER_GROUP: 8\n    DEPTH: 101\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n# To add COCO AP evaluation against the higher-quality LVIS annotations.\n# DATASETS:\n#   TEST: (\"coco_2017_val\", \"lvis_v0.5_val_cocofied\")\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/configs/SemanticSegmentation/Base-PointRend-Semantic-FPN.yaml",
    "content": "_BASE_: \"../../../../configs/Base-RCNN-FPN.yaml\"\nMODEL:\n  META_ARCHITECTURE: \"SemanticSegmentor\"\n  BACKBONE:\n    FREEZE_AT: 0\n  SEM_SEG_HEAD:\n    NAME: \"PointRendSemSegHead\"\n  POINT_HEAD:\n    NUM_CLASSES: 54\n    FC_DIM: 256\n    NUM_FC: 3\n    IN_FEATURES: [\"p2\"]\n    TRAIN_NUM_POINTS: 1024\n    SUBDIVISION_STEPS: 2\n    SUBDIVISION_NUM_POINTS: 8192\n    COARSE_SEM_SEG_HEAD_NAME: \"SemSegFPNHead\"\n    COARSE_PRED_EACH_LAYER: False\nDATASETS:\n  TRAIN: (\"coco_2017_train_panoptic_stuffonly\",)\n  TEST: (\"coco_2017_val_panoptic_stuffonly\",)\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/configs/SemanticSegmentation/pointrend_semantic_R_101_FPN_1x_cityscapes.yaml",
    "content": "_BASE_: Base-PointRend-Semantic-FPN.yaml\nMODEL:\n  WEIGHTS: detectron2://ImageNetPretrained/MSRA/R-101.pkl\n  RESNETS:\n    DEPTH: 101\n  SEM_SEG_HEAD:\n    NUM_CLASSES: 19\n  POINT_HEAD:\n    NUM_CLASSES: 19\n    TRAIN_NUM_POINTS: 2048\n    SUBDIVISION_NUM_POINTS: 8192\nDATASETS:\n  TRAIN: (\"cityscapes_fine_sem_seg_train\",)\n  TEST: (\"cityscapes_fine_sem_seg_val\",)\nSOLVER:\n  BASE_LR: 0.01\n  STEPS: (40000, 55000)\n  MAX_ITER: 65000\n  IMS_PER_BATCH: 32\nINPUT:\n  MIN_SIZE_TRAIN: (512, 768, 1024, 1280, 1536, 1792, 2048)\n  MIN_SIZE_TRAIN_SAMPLING: \"choice\"\n  MIN_SIZE_TEST: 1024\n  MAX_SIZE_TRAIN: 4096\n  MAX_SIZE_TEST: 2048\n  CROP:\n    ENABLED: True\n    TYPE: \"absolute\"\n    SIZE: (512, 1024)\n    SINGLE_CATEGORY_MAX_AREA: 0.75\n  COLOR_AUG_SSD: True\nDATALOADER:\n  NUM_WORKERS: 10\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/point_rend/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom .config import add_pointrend_config\nfrom .mask_head import PointRendMaskHead, ImplicitPointRendMaskHead\nfrom .semantic_seg import PointRendSemSegHead\nfrom .color_augmentation import ColorAugSSDTransform\n\nfrom . import roi_heads as _  # only registration\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/point_rend/color_augmentation.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport numpy as np\nimport random\nimport cv2\nfrom fvcore.transforms.transform import Transform\n\n\nclass ColorAugSSDTransform(Transform):\n    \"\"\"\n    A color related data augmentation used in Single Shot Multibox Detector (SSD).\n\n    Wei Liu, Dragomir Anguelov, Dumitru Erhan, Christian Szegedy,\n       Scott Reed, Cheng-Yang Fu, Alexander C. Berg.\n       SSD: Single Shot MultiBox Detector. ECCV 2016.\n\n    Implementation based on:\n\n     https://github.com/weiliu89/caffe/blob\n       /4817bf8b4200b35ada8ed0dc378dceaf38c539e4\n       /src/caffe/util/im_transforms.cpp\n\n     https://github.com/chainer/chainercv/blob\n       /7159616642e0be7c5b3ef380b848e16b7e99355b/chainercv\n       /links/model/ssd/transforms.py\n    \"\"\"\n\n    def __init__(\n        self,\n        img_format,\n        brightness_delta=32,\n        contrast_low=0.5,\n        contrast_high=1.5,\n        saturation_low=0.5,\n        saturation_high=1.5,\n        hue_delta=18,\n    ):\n        super().__init__()\n        assert img_format in [\"BGR\", \"RGB\"]\n        self.is_rgb = img_format == \"RGB\"\n        del img_format\n        self._set_attributes(locals())\n\n    def apply_coords(self, coords):\n        return coords\n\n    def apply_segmentation(self, segmentation):\n        return segmentation\n\n    def apply_image(self, img, interp=None):\n        if self.is_rgb:\n            img = img[:, :, [2, 1, 0]]\n        img = self.brightness(img)\n        if random.randrange(2):\n            img = self.contrast(img)\n            img = self.saturation(img)\n            img = self.hue(img)\n        else:\n            img = self.saturation(img)\n            img = self.hue(img)\n            img = self.contrast(img)\n        if self.is_rgb:\n            img = img[:, :, [2, 1, 0]]\n        return img\n\n    def convert(self, img, alpha=1, beta=0):\n        img = img.astype(np.float32) * alpha + beta\n        img = np.clip(img, 0, 255)\n        return img.astype(np.uint8)\n\n    def brightness(self, img):\n        if random.randrange(2):\n            return self.convert(\n                img, beta=random.uniform(-self.brightness_delta, self.brightness_delta)\n            )\n        return img\n\n    def contrast(self, img):\n        if random.randrange(2):\n            return self.convert(img, alpha=random.uniform(self.contrast_low, self.contrast_high))\n        return img\n\n    def saturation(self, img):\n        if random.randrange(2):\n            img = cv2.cvtColor(img, cv2.COLOR_BGR2HSV)\n            img[:, :, 1] = self.convert(\n                img[:, :, 1], alpha=random.uniform(self.saturation_low, self.saturation_high)\n            )\n            return cv2.cvtColor(img, cv2.COLOR_HSV2BGR)\n        return img\n\n    def hue(self, img):\n        if random.randrange(2):\n            img = cv2.cvtColor(img, cv2.COLOR_BGR2HSV)\n            img[:, :, 0] = (\n                img[:, :, 0].astype(int) + random.randint(-self.hue_delta, self.hue_delta)\n            ) % 180\n            return cv2.cvtColor(img, cv2.COLOR_HSV2BGR)\n        return img\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/point_rend/config.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom detectron2.config import CfgNode as CN\n\n\ndef add_pointrend_config(cfg):\n    \"\"\"\n    Add config for PointRend.\n    \"\"\"\n    # We retry random cropping until no single category in semantic segmentation GT occupies more\n    # than `SINGLE_CATEGORY_MAX_AREA` part of the crop.\n    cfg.INPUT.CROP.SINGLE_CATEGORY_MAX_AREA = 1.0\n    # Color augmentatition from SSD paper for semantic segmentation model during training.\n    cfg.INPUT.COLOR_AUG_SSD = False\n\n    # Names of the input feature maps to be used by a coarse mask head.\n    cfg.MODEL.ROI_MASK_HEAD.IN_FEATURES = (\"p2\",)\n    cfg.MODEL.ROI_MASK_HEAD.FC_DIM = 1024\n    cfg.MODEL.ROI_MASK_HEAD.NUM_FC = 2\n    # The side size of a coarse mask head prediction.\n    cfg.MODEL.ROI_MASK_HEAD.OUTPUT_SIDE_RESOLUTION = 7\n    # True if point head is used.\n    cfg.MODEL.ROI_MASK_HEAD.POINT_HEAD_ON = False\n\n    cfg.MODEL.POINT_HEAD = CN()\n    cfg.MODEL.POINT_HEAD.NAME = \"StandardPointHead\"\n    cfg.MODEL.POINT_HEAD.NUM_CLASSES = 80\n    # Names of the input feature maps to be used by a mask point head.\n    cfg.MODEL.POINT_HEAD.IN_FEATURES = (\"p2\",)\n    # Number of points sampled during training for a mask point head.\n    cfg.MODEL.POINT_HEAD.TRAIN_NUM_POINTS = 14 * 14\n    # Oversampling parameter for PointRend point sampling during training. Parameter `k` in the\n    # original paper.\n    cfg.MODEL.POINT_HEAD.OVERSAMPLE_RATIO = 3\n    # Importance sampling parameter for PointRend point sampling during training. Parametr `beta` in\n    # the original paper.\n    cfg.MODEL.POINT_HEAD.IMPORTANCE_SAMPLE_RATIO = 0.75\n    # Number of subdivision steps during inference.\n    cfg.MODEL.POINT_HEAD.SUBDIVISION_STEPS = 5\n    # Maximum number of points selected at each subdivision step (N).\n    cfg.MODEL.POINT_HEAD.SUBDIVISION_NUM_POINTS = 28 * 28\n    cfg.MODEL.POINT_HEAD.FC_DIM = 256\n    cfg.MODEL.POINT_HEAD.NUM_FC = 3\n    cfg.MODEL.POINT_HEAD.CLS_AGNOSTIC_MASK = False\n    # If True, then coarse prediction features are used as inout for each layer in PointRend's MLP.\n    cfg.MODEL.POINT_HEAD.COARSE_PRED_EACH_LAYER = True\n    cfg.MODEL.POINT_HEAD.COARSE_SEM_SEG_HEAD_NAME = \"SemSegFPNHead\"\n\n    \"\"\"\n    Add config for Implicit PointRend.\n    \"\"\"\n    cfg.MODEL.IMPLICIT_POINTREND = CN()\n\n    cfg.MODEL.IMPLICIT_POINTREND.IMAGE_FEATURE_ENABLED = True\n    cfg.MODEL.IMPLICIT_POINTREND.POS_ENC_ENABLED = True\n\n    cfg.MODEL.IMPLICIT_POINTREND.PARAMS_L2_REGULARIZER = 0.00001\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/point_rend/mask_head.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport logging\nimport math\nimport numpy as np\nfrom typing import Dict, List, Tuple\nimport fvcore.nn.weight_init as weight_init\nimport torch\nfrom torch import Tensor, nn\nfrom torch.nn import functional as F\n\nfrom detectron2.config import configurable\nfrom detectron2.layers import Conv2d, ShapeSpec, cat, interpolate\nfrom detectron2.modeling import ROI_MASK_HEAD_REGISTRY\nfrom detectron2.modeling.roi_heads.mask_head import mask_rcnn_inference, mask_rcnn_loss\nfrom detectron2.structures import Boxes\n\nfrom .point_features import (\n    generate_regular_grid_point_coords,\n    get_point_coords_wrt_image,\n    get_uncertain_point_coords_on_grid,\n    get_uncertain_point_coords_with_randomness,\n    point_sample,\n    point_sample_fine_grained_features,\n    sample_point_labels,\n)\nfrom .point_head import build_point_head, roi_mask_point_loss\n\n\ndef calculate_uncertainty(logits, classes):\n    \"\"\"\n    We estimate uncerainty as L1 distance between 0.0 and the logit prediction in 'logits' for the\n        foreground class in `classes`.\n    Args:\n        logits (Tensor): A tensor of shape (R, C, ...) or (R, 1, ...) for class-specific or\n            class-agnostic, where R is the total number of predicted masks in all images and C is\n            the number of foreground classes. The values are logits.\n        classes (list): A list of length R that contains either predicted of ground truth class\n            for eash predicted mask.\n    Returns:\n        scores (Tensor): A tensor of shape (R, 1, ...) that contains uncertainty scores with\n            the most uncertain locations having the highest uncertainty score.\n    \"\"\"\n    if logits.shape[1] == 1:\n        gt_class_logits = logits.clone()\n    else:\n        gt_class_logits = logits[\n            torch.arange(logits.shape[0], device=logits.device), classes\n        ].unsqueeze(1)\n    return -(torch.abs(gt_class_logits))\n\n\nclass ConvFCHead(nn.Module):\n    \"\"\"\n    A mask head with fully connected layers. Given pooled features it first reduces channels and\n    spatial dimensions with conv layers and then uses FC layers to predict coarse masks analogously\n    to the standard box head.\n    \"\"\"\n\n    _version = 2\n\n    @configurable\n    def __init__(\n        self, input_shape: ShapeSpec, *, conv_dim: int, fc_dims: List[int], output_shape: Tuple[int]\n    ):\n        \"\"\"\n        Args:\n            conv_dim: the output dimension of the conv layers\n            fc_dims: a list of N>0 integers representing the output dimensions of N FC layers\n            output_shape: shape of the output mask prediction\n        \"\"\"\n        super().__init__()\n\n        # fmt: off\n        input_channels    = input_shape.channels\n        input_h           = input_shape.height\n        input_w           = input_shape.width\n        self.output_shape = output_shape\n        # fmt: on\n\n        self.conv_layers = []\n        if input_channels > conv_dim:\n            self.reduce_channel_dim_conv = Conv2d(\n                input_channels,\n                conv_dim,\n                kernel_size=1,\n                stride=1,\n                padding=0,\n                bias=True,\n                activation=F.relu,\n            )\n            self.conv_layers.append(self.reduce_channel_dim_conv)\n\n        self.reduce_spatial_dim_conv = Conv2d(\n            conv_dim, conv_dim, kernel_size=2, stride=2, padding=0, bias=True, activation=F.relu\n        )\n        self.conv_layers.append(self.reduce_spatial_dim_conv)\n\n        input_dim = conv_dim * input_h * input_w\n        input_dim //= 4\n\n        self.fcs = []\n        for k, fc_dim in enumerate(fc_dims):\n            fc = nn.Linear(input_dim, fc_dim)\n            self.add_module(\"fc{}\".format(k + 1), fc)\n            self.fcs.append(fc)\n            input_dim = fc_dim\n\n        output_dim = int(np.prod(self.output_shape))\n\n        self.prediction = nn.Linear(fc_dims[-1], output_dim)\n        # use normal distribution initialization for mask prediction layer\n        nn.init.normal_(self.prediction.weight, std=0.001)\n        nn.init.constant_(self.prediction.bias, 0)\n\n        for layer in self.conv_layers:\n            weight_init.c2_msra_fill(layer)\n        for layer in self.fcs:\n            weight_init.c2_xavier_fill(layer)\n\n    @classmethod\n    def from_config(cls, cfg, input_shape):\n        output_shape = (\n            cfg.MODEL.ROI_HEADS.NUM_CLASSES,\n            cfg.MODEL.ROI_MASK_HEAD.OUTPUT_SIDE_RESOLUTION,\n            cfg.MODEL.ROI_MASK_HEAD.OUTPUT_SIDE_RESOLUTION,\n        )\n        fc_dim = cfg.MODEL.ROI_MASK_HEAD.FC_DIM\n        num_fc = cfg.MODEL.ROI_MASK_HEAD.NUM_FC\n        ret = dict(\n            input_shape=input_shape,\n            conv_dim=cfg.MODEL.ROI_MASK_HEAD.CONV_DIM,\n            fc_dims=[fc_dim] * num_fc,\n            output_shape=output_shape,\n        )\n        return ret\n\n    def forward(self, x):\n        N = x.shape[0]\n        for layer in self.conv_layers:\n            x = layer(x)\n        x = torch.flatten(x, start_dim=1)\n        for layer in self.fcs:\n            x = F.relu(layer(x))\n        output_shape = [N] + list(self.output_shape)\n        return self.prediction(x).view(*output_shape)\n\n    def _load_from_state_dict(\n        self, state_dict, prefix, local_metadata, strict, missing_keys, unexpected_keys, error_msgs\n    ):\n        version = local_metadata.get(\"version\", None)\n\n        if version is None or version < 2:\n            logger = logging.getLogger(__name__)\n            logger.warning(\n                \"Weight format of PointRend models have changed! \"\n                \"Applying automatic conversion now ...\"\n            )\n            for k in list(state_dict.keys()):\n                newk = k\n                if k.startswith(prefix + \"coarse_mask_fc\"):\n                    newk = k.replace(prefix + \"coarse_mask_fc\", prefix + \"fc\")\n                if newk != k:\n                    state_dict[newk] = state_dict[k]\n                    del state_dict[k]\n\n\n@ROI_MASK_HEAD_REGISTRY.register()\nclass PointRendMaskHead(nn.Module):\n    def __init__(self, cfg, input_shape: Dict[str, ShapeSpec]):\n        super().__init__()\n        self._feature_scales = {k: 1.0 / v.stride for k, v in input_shape.items()}\n        # point head\n        self._init_point_head(cfg, input_shape)\n        # coarse mask head\n        self.roi_pooler_in_features = cfg.MODEL.ROI_MASK_HEAD.IN_FEATURES\n        self.roi_pooler_size = cfg.MODEL.ROI_MASK_HEAD.POOLER_RESOLUTION\n        self._feature_scales = {k: 1.0 / v.stride for k, v in input_shape.items()}\n        in_channels = np.sum([input_shape[f].channels for f in self.roi_pooler_in_features])\n        self._init_roi_head(\n            cfg,\n            ShapeSpec(\n                channels=in_channels,\n                width=self.roi_pooler_size,\n                height=self.roi_pooler_size,\n            ),\n        )\n\n    def _init_roi_head(self, cfg, input_shape):\n        self.coarse_head = ConvFCHead(cfg, input_shape)\n\n    def _init_point_head(self, cfg, input_shape):\n        # fmt: off\n        self.mask_point_on                      = cfg.MODEL.ROI_MASK_HEAD.POINT_HEAD_ON\n        if not self.mask_point_on:\n            return\n        assert cfg.MODEL.ROI_HEADS.NUM_CLASSES == cfg.MODEL.POINT_HEAD.NUM_CLASSES\n        self.mask_point_in_features             = cfg.MODEL.POINT_HEAD.IN_FEATURES\n        self.mask_point_train_num_points        = cfg.MODEL.POINT_HEAD.TRAIN_NUM_POINTS\n        self.mask_point_oversample_ratio        = cfg.MODEL.POINT_HEAD.OVERSAMPLE_RATIO\n        self.mask_point_importance_sample_ratio = cfg.MODEL.POINT_HEAD.IMPORTANCE_SAMPLE_RATIO\n        # next three parameters are use in the adaptive subdivions inference procedure\n        self.mask_point_subdivision_init_resolution = cfg.MODEL.ROI_MASK_HEAD.OUTPUT_SIDE_RESOLUTION\n        self.mask_point_subdivision_steps       = cfg.MODEL.POINT_HEAD.SUBDIVISION_STEPS\n        self.mask_point_subdivision_num_points  = cfg.MODEL.POINT_HEAD.SUBDIVISION_NUM_POINTS\n        # fmt: on\n\n        in_channels = int(np.sum([input_shape[f].channels for f in self.mask_point_in_features]))\n        self.point_head = build_point_head(cfg, ShapeSpec(channels=in_channels, width=1, height=1))\n\n        # An optimization to skip unused subdivision steps: if after subdivision, all pixels on\n        # the mask will be selected and recomputed anyway, we should just double our init_resolution\n        while (\n            4 * self.mask_point_subdivision_init_resolution ** 2\n            <= self.mask_point_subdivision_num_points\n        ):\n            self.mask_point_subdivision_init_resolution *= 2\n            self.mask_point_subdivision_steps -= 1\n\n    def forward(self, features, instances):\n        \"\"\"\n        Args:\n            features (dict[str, Tensor]): a dict of image-level features\n            instances (list[Instances]): proposals in training; detected\n                instances in inference\n        \"\"\"\n        if self.training:\n            proposal_boxes = [x.proposal_boxes for x in instances]\n            coarse_mask = self.coarse_head(self._roi_pooler(features, proposal_boxes))\n            losses = {\"loss_mask\": mask_rcnn_loss(coarse_mask, instances)}\n            if not self.mask_point_on:\n                return losses\n\n            point_coords, point_labels = self._sample_train_points(coarse_mask, instances)\n            point_fine_grained_features = self._point_pooler(features, proposal_boxes, point_coords)\n            point_logits = self._get_point_logits(\n                point_fine_grained_features, point_coords, coarse_mask\n            )\n            losses[\"loss_mask_point\"] = roi_mask_point_loss(point_logits, instances, point_labels)\n            return losses\n        else:\n            pred_boxes = [x.pred_boxes for x in instances]\n            coarse_mask = self.coarse_head(self._roi_pooler(features, pred_boxes))\n            return self._subdivision_inference(features, coarse_mask, instances)\n\n    def _roi_pooler(self, features: List[Tensor], boxes: List[Boxes]):\n        \"\"\"\n        Extract per-box feature. This is similar to RoIAlign(sampling_ratio=1) except:\n        1. It's implemented by point_sample\n        2. It pools features across all levels and concat them, while typically\n           RoIAlign select one level for every box. However in the config we only use\n           one level (p2) so there is no difference.\n\n        Returns:\n            Tensor of shape (R, C, pooler_size, pooler_size) where R is the total number of boxes\n        \"\"\"\n        features_list = [features[k] for k in self.roi_pooler_in_features]\n        features_scales = [self._feature_scales[k] for k in self.roi_pooler_in_features]\n\n        num_boxes = sum(x.tensor.size(0) for x in boxes)\n        output_size = self.roi_pooler_size\n        point_coords = generate_regular_grid_point_coords(num_boxes, output_size, boxes[0].device)\n        # For regular grids of points, this function is equivalent to `len(features_list)' calls\n        # of `ROIAlign` (with `SAMPLING_RATIO=1`), and concat the results.\n        roi_features, _ = point_sample_fine_grained_features(\n            features_list, features_scales, boxes, point_coords\n        )\n        return roi_features.view(num_boxes, roi_features.shape[1], output_size, output_size)\n\n    def _sample_train_points(self, coarse_mask, instances):\n        assert self.training\n        gt_classes = cat([x.gt_classes for x in instances])\n        with torch.no_grad():\n            # sample point_coords\n            point_coords = get_uncertain_point_coords_with_randomness(\n                coarse_mask,\n                lambda logits: calculate_uncertainty(logits, gt_classes),\n                self.mask_point_train_num_points,\n                self.mask_point_oversample_ratio,\n                self.mask_point_importance_sample_ratio,\n            )\n            # sample point_labels\n            proposal_boxes = [x.proposal_boxes for x in instances]\n            cat_boxes = Boxes.cat(proposal_boxes)\n            point_coords_wrt_image = get_point_coords_wrt_image(cat_boxes.tensor, point_coords)\n            point_labels = sample_point_labels(instances, point_coords_wrt_image)\n        return point_coords, point_labels\n\n    def _point_pooler(self, features, proposal_boxes, point_coords):\n        point_features_list = [features[k] for k in self.mask_point_in_features]\n        point_features_scales = [self._feature_scales[k] for k in self.mask_point_in_features]\n        # sample image-level features\n        point_fine_grained_features, _ = point_sample_fine_grained_features(\n            point_features_list, point_features_scales, proposal_boxes, point_coords\n        )\n        return point_fine_grained_features\n\n    def _get_point_logits(self, point_fine_grained_features, point_coords, coarse_mask):\n        coarse_features = point_sample(coarse_mask, point_coords, align_corners=False)\n        point_logits = self.point_head(point_fine_grained_features, coarse_features)\n        return point_logits\n\n    def _subdivision_inference(self, features, mask_representations, instances):\n        assert not self.training\n\n        pred_boxes = [x.pred_boxes for x in instances]\n        pred_classes = cat([x.pred_classes for x in instances])\n\n        mask_logits = None\n        # +1 here to include an initial step to generate the coarsest mask\n        # prediction with init_resolution, when mask_logits is None.\n        # We compute initial mask by sampling on a regular grid. coarse_mask\n        # can be used as initial mask as well, but it's typically very low-res\n        # so it will be completely overwritten during subdivision anyway.\n        for _ in range(self.mask_point_subdivision_steps + 1):\n            if mask_logits is None:\n                point_coords = generate_regular_grid_point_coords(\n                    pred_classes.size(0),\n                    self.mask_point_subdivision_init_resolution,\n                    pred_boxes[0].device,\n                )\n            else:\n                mask_logits = interpolate(\n                    mask_logits, scale_factor=2, mode=\"bilinear\", align_corners=False\n                )\n                uncertainty_map = calculate_uncertainty(mask_logits, pred_classes)\n                point_indices, point_coords = get_uncertain_point_coords_on_grid(\n                    uncertainty_map, self.mask_point_subdivision_num_points\n                )\n\n            # Run the point head for every point in point_coords\n            fine_grained_features = self._point_pooler(features, pred_boxes, point_coords)\n            point_logits = self._get_point_logits(\n                fine_grained_features, point_coords, mask_representations\n            )\n\n            if mask_logits is None:\n                # Create initial mask_logits using point_logits on this regular grid\n                R, C, _ = point_logits.shape\n                mask_logits = point_logits.reshape(\n                    R,\n                    C,\n                    self.mask_point_subdivision_init_resolution,\n                    self.mask_point_subdivision_init_resolution,\n                )\n                # The subdivision code will fail with the empty list of boxes\n                if len(pred_classes) == 0:\n                    mask_rcnn_inference(mask_logits, instances)\n                    return instances\n            else:\n                # Put point predictions to the right places on the upsampled grid.\n                R, C, H, W = mask_logits.shape\n                point_indices = point_indices.unsqueeze(1).expand(-1, C, -1)\n                mask_logits = (\n                    mask_logits.reshape(R, C, H * W)\n                    .scatter_(2, point_indices, point_logits)\n                    .view(R, C, H, W)\n                )\n        mask_rcnn_inference(mask_logits, instances)\n        return instances\n\n\n@ROI_MASK_HEAD_REGISTRY.register()\nclass ImplicitPointRendMaskHead(PointRendMaskHead):\n    def __init__(self, cfg, input_shape: Dict[str, ShapeSpec]):\n        super().__init__(cfg, input_shape)\n\n    def _init_roi_head(self, cfg, input_shape):\n        assert hasattr(self, \"num_params\"), \"Please initialize point_head first!\"\n        self.parameter_head = ConvFCHead(cfg, input_shape, output_shape=(self.num_params,))\n        self.regularizer = cfg.MODEL.IMPLICIT_POINTREND.PARAMS_L2_REGULARIZER\n\n    def _init_point_head(self, cfg, input_shape):\n        # fmt: off\n        self.mask_point_on = True  # always on\n        assert cfg.MODEL.ROI_HEADS.NUM_CLASSES == cfg.MODEL.POINT_HEAD.NUM_CLASSES\n        self.mask_point_in_features             = cfg.MODEL.POINT_HEAD.IN_FEATURES\n        self.mask_point_train_num_points        = cfg.MODEL.POINT_HEAD.TRAIN_NUM_POINTS\n        # next two parameters are use in the adaptive subdivions inference procedure\n        self.mask_point_subdivision_steps       = cfg.MODEL.POINT_HEAD.SUBDIVISION_STEPS\n        self.mask_point_subdivision_num_points  = cfg.MODEL.POINT_HEAD.SUBDIVISION_NUM_POINTS\n        # fmt: on\n\n        in_channels = int(np.sum([input_shape[f].channels for f in self.mask_point_in_features]))\n        self.point_head = build_point_head(cfg, ShapeSpec(channels=in_channels, width=1, height=1))\n        self.num_params = self.point_head.num_params\n\n        # inference parameters\n        self.mask_point_subdivision_init_resolution = int(\n            math.sqrt(self.mask_point_subdivision_num_points)\n        )\n        assert (\n            self.mask_point_subdivision_init_resolution\n            * self.mask_point_subdivision_init_resolution\n            == self.mask_point_subdivision_num_points\n        )\n\n    def forward(self, features, instances):\n        \"\"\"\n        Args:\n            features (dict[str, Tensor]): a dict of image-level features\n            instances (list[Instances]): proposals in training; detected\n                instances in inference\n        \"\"\"\n        if self.training:\n            proposal_boxes = [x.proposal_boxes for x in instances]\n            parameters = self.parameter_head(self._roi_pooler(features, proposal_boxes))\n            losses = {\"loss_l2\": self.regularizer * (parameters ** 2).mean()}\n\n            point_coords, point_labels = self._uniform_sample_train_points(instances)\n            point_fine_grained_features = self._point_pooler(features, proposal_boxes, point_coords)\n            point_logits = self._get_point_logits(\n                point_fine_grained_features, point_coords, parameters\n            )\n            losses[\"loss_mask_point\"] = roi_mask_point_loss(point_logits, instances, point_labels)\n            return losses\n        else:\n            pred_boxes = [x.pred_boxes for x in instances]\n            parameters = self.parameter_head(self._roi_pooler(features, pred_boxes))\n            return self._subdivision_inference(features, parameters, instances)\n\n    def _uniform_sample_train_points(self, instances):\n        assert self.training\n        proposal_boxes = [x.proposal_boxes for x in instances]\n        cat_boxes = Boxes.cat(proposal_boxes)\n        # uniform sample\n        point_coords = torch.rand(\n            len(cat_boxes), self.mask_point_train_num_points, 2, device=cat_boxes.tensor.device\n        )\n        # sample point_labels\n        point_coords_wrt_image = get_point_coords_wrt_image(cat_boxes.tensor, point_coords)\n        point_labels = sample_point_labels(instances, point_coords_wrt_image)\n        return point_coords, point_labels\n\n    def _get_point_logits(self, fine_grained_features, point_coords, parameters):\n        return self.point_head(fine_grained_features, point_coords, parameters)\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/point_rend/point_features.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport torch\nfrom torch.nn import functional as F\n\nfrom detectron2.layers import cat, shapes_to_tensor\nfrom detectron2.structures import BitMasks, Boxes\n\n\n\"\"\"\nShape shorthand in this module:\n\n    N: minibatch dimension size, i.e. the number of RoIs for instance segmenation or the\n        number of images for semantic segmenation.\n    R: number of ROIs, combined over all images, in the minibatch\n    P: number of points\n\"\"\"\n\n\ndef point_sample(input, point_coords, **kwargs):\n    \"\"\"\n    A wrapper around :function:`torch.nn.functional.grid_sample` to support 3D point_coords tensors.\n    Unlike :function:`torch.nn.functional.grid_sample` it assumes `point_coords` to lie inside\n    [0, 1] x [0, 1] square.\n\n    Args:\n        input (Tensor): A tensor of shape (N, C, H, W) that contains features map on a H x W grid.\n        point_coords (Tensor): A tensor of shape (N, P, 2) or (N, Hgrid, Wgrid, 2) that contains\n        [0, 1] x [0, 1] normalized point coordinates.\n\n    Returns:\n        output (Tensor): A tensor of shape (N, C, P) or (N, C, Hgrid, Wgrid) that contains\n            features for points in `point_coords`. The features are obtained via bilinear\n            interplation from `input` the same way as :function:`torch.nn.functional.grid_sample`.\n    \"\"\"\n    add_dim = False\n    if point_coords.dim() == 3:\n        add_dim = True\n        point_coords = point_coords.unsqueeze(2)\n    output = F.grid_sample(input, 2.0 * point_coords - 1.0, **kwargs)\n    if add_dim:\n        output = output.squeeze(3)\n    return output\n\n\ndef generate_regular_grid_point_coords(R, side_size, device):\n    \"\"\"\n    Generate regular square grid of points in [0, 1] x [0, 1] coordinate space.\n\n    Args:\n        R (int): The number of grids to sample, one for each region.\n        side_size (int): The side size of the regular grid.\n        device (torch.device): Desired device of returned tensor.\n\n    Returns:\n        (Tensor): A tensor of shape (R, side_size^2, 2) that contains coordinates\n            for the regular grids.\n    \"\"\"\n    aff = torch.tensor([[[0.5, 0, 0.5], [0, 0.5, 0.5]]], device=device)\n    r = F.affine_grid(aff, torch.Size((1, 1, side_size, side_size)), align_corners=False)\n    return r.view(1, -1, 2).expand(R, -1, -1)\n\n\ndef get_uncertain_point_coords_with_randomness(\n    coarse_logits, uncertainty_func, num_points, oversample_ratio, importance_sample_ratio\n):\n    \"\"\"\n    Sample points in [0, 1] x [0, 1] coordinate space based on their uncertainty. The unceratinties\n        are calculated for each point using 'uncertainty_func' function that takes point's logit\n        prediction as input.\n    See PointRend paper for details.\n\n    Args:\n        coarse_logits (Tensor): A tensor of shape (N, C, Hmask, Wmask) or (N, 1, Hmask, Wmask) for\n            class-specific or class-agnostic prediction.\n        uncertainty_func: A function that takes a Tensor of shape (N, C, P) or (N, 1, P) that\n            contains logit predictions for P points and returns their uncertainties as a Tensor of\n            shape (N, 1, P).\n        num_points (int): The number of points P to sample.\n        oversample_ratio (int): Oversampling parameter.\n        importance_sample_ratio (float): Ratio of points that are sampled via importnace sampling.\n\n    Returns:\n        point_coords (Tensor): A tensor of shape (N, P, 2) that contains the coordinates of P\n            sampled points.\n    \"\"\"\n    assert oversample_ratio >= 1\n    assert importance_sample_ratio <= 1 and importance_sample_ratio >= 0\n    num_boxes = coarse_logits.shape[0]\n    num_sampled = int(num_points * oversample_ratio)\n    point_coords = torch.rand(num_boxes, num_sampled, 2, device=coarse_logits.device)\n    point_logits = point_sample(coarse_logits, point_coords, align_corners=False)\n    # It is crucial to calculate uncertainty based on the sampled prediction value for the points.\n    # Calculating uncertainties of the coarse predictions first and sampling them for points leads\n    # to incorrect results.\n    # To illustrate this: assume uncertainty_func(logits)=-abs(logits), a sampled point between\n    # two coarse predictions with -1 and 1 logits has 0 logits, and therefore 0 uncertainty value.\n    # However, if we calculate uncertainties for the coarse predictions first,\n    # both will have -1 uncertainty, and the sampled point will get -1 uncertainty.\n    point_uncertainties = uncertainty_func(point_logits)\n    num_uncertain_points = int(importance_sample_ratio * num_points)\n    num_random_points = num_points - num_uncertain_points\n    idx = torch.topk(point_uncertainties[:, 0, :], k=num_uncertain_points, dim=1)[1]\n    shift = num_sampled * torch.arange(num_boxes, dtype=torch.long, device=coarse_logits.device)\n    idx += shift[:, None]\n    point_coords = point_coords.view(-1, 2)[idx.view(-1), :].view(\n        num_boxes, num_uncertain_points, 2\n    )\n    if num_random_points > 0:\n        point_coords = cat(\n            [\n                point_coords,\n                torch.rand(num_boxes, num_random_points, 2, device=coarse_logits.device),\n            ],\n            dim=1,\n        )\n    return point_coords\n\n\ndef get_uncertain_point_coords_on_grid(uncertainty_map, num_points):\n    \"\"\"\n    Find `num_points` most uncertain points from `uncertainty_map` grid.\n\n    Args:\n        uncertainty_map (Tensor): A tensor of shape (N, 1, H, W) that contains uncertainty\n            values for a set of points on a regular H x W grid.\n        num_points (int): The number of points P to select.\n\n    Returns:\n        point_indices (Tensor): A tensor of shape (N, P) that contains indices from\n            [0, H x W) of the most uncertain points.\n        point_coords (Tensor): A tensor of shape (N, P, 2) that contains [0, 1] x [0, 1] normalized\n            coordinates of the most uncertain points from the H x W grid.\n    \"\"\"\n    R, _, H, W = uncertainty_map.shape\n    h_step = 1.0 / float(H)\n    w_step = 1.0 / float(W)\n\n    num_points = min(H * W, num_points)\n    point_indices = torch.topk(uncertainty_map.view(R, H * W), k=num_points, dim=1)[1]\n    point_coords = torch.zeros(R, num_points, 2, dtype=torch.float, device=uncertainty_map.device)\n    point_coords[:, :, 0] = w_step / 2.0 + (point_indices % W).to(torch.float) * w_step\n    point_coords[:, :, 1] = h_step / 2.0 + (point_indices // W).to(torch.float) * h_step\n    return point_indices, point_coords\n\n\ndef point_sample_fine_grained_features(features_list, feature_scales, boxes, point_coords):\n    \"\"\"\n    Get features from feature maps in `features_list` that correspond to specific point coordinates\n        inside each bounding box from `boxes`.\n\n    Args:\n        features_list (list[Tensor]): A list of feature map tensors to get features from.\n        feature_scales (list[float]): A list of scales for tensors in `features_list`.\n        boxes (list[Boxes]): A list of I Boxes  objects that contain R_1 + ... + R_I = R boxes all\n            together.\n        point_coords (Tensor): A tensor of shape (R, P, 2) that contains\n            [0, 1] x [0, 1] box-normalized coordinates of the P sampled points.\n\n    Returns:\n        point_features (Tensor): A tensor of shape (R, C, P) that contains features sampled\n            from all features maps in feature_list for P sampled points for all R boxes in `boxes`.\n        point_coords_wrt_image (Tensor): A tensor of shape (R, P, 2) that contains image-level\n            coordinates of P points.\n    \"\"\"\n    cat_boxes = Boxes.cat(boxes)\n    num_boxes = [b.tensor.size(0) for b in boxes]\n\n    point_coords_wrt_image = get_point_coords_wrt_image(cat_boxes.tensor, point_coords)\n    split_point_coords_wrt_image = torch.split(point_coords_wrt_image, num_boxes)\n\n    point_features = []\n    for idx_img, point_coords_wrt_image_per_image in enumerate(split_point_coords_wrt_image):\n        point_features_per_image = []\n        for idx_feature, feature_map in enumerate(features_list):\n            h, w = feature_map.shape[-2:]\n            scale = shapes_to_tensor([w, h]) / feature_scales[idx_feature]\n            point_coords_scaled = point_coords_wrt_image_per_image / scale.to(feature_map.device)\n            point_features_per_image.append(\n                point_sample(\n                    feature_map[idx_img].unsqueeze(0),\n                    point_coords_scaled.unsqueeze(0),\n                    align_corners=False,\n                )\n                .squeeze(0)\n                .transpose(1, 0)\n            )\n        point_features.append(cat(point_features_per_image, dim=1))\n\n    return cat(point_features, dim=0), point_coords_wrt_image\n\n\ndef get_point_coords_wrt_image(boxes_coords, point_coords):\n    \"\"\"\n    Convert box-normalized [0, 1] x [0, 1] point cooordinates to image-level coordinates.\n\n    Args:\n        boxes_coords (Tensor): A tensor of shape (R, 4) that contains bounding boxes.\n            coordinates.\n        point_coords (Tensor): A tensor of shape (R, P, 2) that contains\n            [0, 1] x [0, 1] box-normalized coordinates of the P sampled points.\n\n    Returns:\n        point_coords_wrt_image (Tensor): A tensor of shape (R, P, 2) that contains\n            image-normalized coordinates of P sampled points.\n    \"\"\"\n    with torch.no_grad():\n        point_coords_wrt_image = point_coords.clone()\n        point_coords_wrt_image[:, :, 0] = point_coords_wrt_image[:, :, 0] * (\n            boxes_coords[:, None, 2] - boxes_coords[:, None, 0]\n        )\n        point_coords_wrt_image[:, :, 1] = point_coords_wrt_image[:, :, 1] * (\n            boxes_coords[:, None, 3] - boxes_coords[:, None, 1]\n        )\n        point_coords_wrt_image[:, :, 0] += boxes_coords[:, None, 0]\n        point_coords_wrt_image[:, :, 1] += boxes_coords[:, None, 1]\n    return point_coords_wrt_image\n\n\ndef sample_point_labels(instances, point_coords):\n    \"\"\"\n    Sample point labels from ground truth mask given point_coords.\n\n    Args:\n        instances (list[Instances]): A list of N Instances, where N is the number of images\n            in the batch. So, i_th elememt of the list contains R_i objects and R_1 + ... + R_N is\n            equal to R. The ground-truth gt_masks in each instance will be used to compute labels.\n        points_coords (Tensor): A tensor of shape (R, P, 2), where R is the total number of\n            instances and P is the number of points for each instance. The coordinates are in\n            the absolute image pixel coordinate space, i.e. [0, H] x [0, W].\n\n    Returns:\n        Tensor: A tensor of shape (R, P) that contains the labels of P sampled points.\n    \"\"\"\n    with torch.no_grad():\n        gt_mask_logits = []\n        point_coords_splits = torch.split(\n            point_coords, [len(instances_per_image) for instances_per_image in instances]\n        )\n        for i, instances_per_image in enumerate(instances):\n            if len(instances_per_image) == 0:\n                continue\n            assert isinstance(\n                instances_per_image.gt_masks, BitMasks\n            ), \"Point head works with GT in 'bitmask' format. Set INPUT.MASK_FORMAT to 'bitmask'.\"\n\n            gt_bit_masks = instances_per_image.gt_masks.tensor\n            h, w = instances_per_image.gt_masks.image_size\n            scale = torch.tensor([w, h], dtype=torch.float, device=gt_bit_masks.device)\n            points_coord_grid_sample_format = point_coords_splits[i] / scale\n            gt_mask_logits.append(\n                point_sample(\n                    gt_bit_masks.to(torch.float32).unsqueeze(1),\n                    points_coord_grid_sample_format,\n                    align_corners=False,\n                ).squeeze(1)\n            )\n\n    point_labels = cat(gt_mask_logits)\n    return point_labels\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/point_rend/point_head.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport numpy as np\nimport fvcore.nn.weight_init as weight_init\nimport torch\nfrom torch import nn\nfrom torch.nn import functional as F\n\nfrom detectron2.layers import ShapeSpec, cat\nfrom detectron2.utils.events import get_event_storage\nfrom detectron2.utils.registry import Registry\n\nPOINT_HEAD_REGISTRY = Registry(\"POINT_HEAD\")\nPOINT_HEAD_REGISTRY.__doc__ = \"\"\"\nRegistry for point heads, which makes prediction for a given set of per-point features.\n\nThe registered object will be called with `obj(cfg, input_shape)`.\n\"\"\"\n\n\ndef roi_mask_point_loss(mask_logits, instances, point_labels):\n    \"\"\"\n    Compute the point-based loss for instance segmentation mask predictions\n    given point-wise mask prediction and its corresponding point-wise labels.\n    Args:\n        mask_logits (Tensor): A tensor of shape (R, C, P) or (R, 1, P) for class-specific or\n            class-agnostic, where R is the total number of predicted masks in all images, C is the\n            number of foreground classes, and P is the number of points sampled for each mask.\n            The values are logits.\n        instances (list[Instances]): A list of N Instances, where N is the number of images\n            in the batch. These instances are in 1:1 correspondence with the `mask_logits`. So, i_th\n            elememt of the list contains R_i objects and R_1 + ... + R_N is equal to R.\n            The ground-truth labels (class, box, mask, ...) associated with each instance are stored\n            in fields.\n        point_labels (Tensor): A tensor of shape (R, P), where R is the total number of\n            predicted masks and P is the number of points for each mask.\n            Labels with value of -1 will be ignored.\n    Returns:\n        point_loss (Tensor): A scalar tensor containing the loss.\n    \"\"\"\n    with torch.no_grad():\n        cls_agnostic_mask = mask_logits.size(1) == 1\n        total_num_masks = mask_logits.size(0)\n\n        gt_classes = []\n        for instances_per_image in instances:\n            if len(instances_per_image) == 0:\n                continue\n\n            if not cls_agnostic_mask:\n                gt_classes_per_image = instances_per_image.gt_classes.to(dtype=torch.int64)\n                gt_classes.append(gt_classes_per_image)\n\n    gt_mask_logits = point_labels\n    point_ignores = point_labels == -1\n    if gt_mask_logits.shape[0] == 0:\n        return mask_logits.sum() * 0\n\n    assert gt_mask_logits.numel() > 0, gt_mask_logits.shape\n\n    if cls_agnostic_mask:\n        mask_logits = mask_logits[:, 0]\n    else:\n        indices = torch.arange(total_num_masks)\n        gt_classes = cat(gt_classes, dim=0)\n        mask_logits = mask_logits[indices, gt_classes]\n\n    # Log the training accuracy (using gt classes and 0.0 threshold for the logits)\n    mask_accurate = (mask_logits > 0.0) == gt_mask_logits.to(dtype=torch.uint8)\n    mask_accurate = mask_accurate[~point_ignores]\n    mask_accuracy = mask_accurate.nonzero().size(0) / max(mask_accurate.numel(), 1.0)\n    get_event_storage().put_scalar(\"point/accuracy\", mask_accuracy)\n\n    point_loss = F.binary_cross_entropy_with_logits(\n        mask_logits, gt_mask_logits.to(dtype=torch.float32), weight=~point_ignores, reduction=\"mean\"\n    )\n    return point_loss\n\n\n@POINT_HEAD_REGISTRY.register()\nclass StandardPointHead(nn.Module):\n    \"\"\"\n    A point head multi-layer perceptron which we model with conv1d layers with kernel 1. The head\n    takes both fine-grained and coarse prediction features as its input.\n    \"\"\"\n\n    def __init__(self, cfg, input_shape: ShapeSpec):\n        \"\"\"\n        The following attributes are parsed from config:\n            fc_dim: the output dimension of each FC layers\n            num_fc: the number of FC layers\n            coarse_pred_each_layer: if True, coarse prediction features are concatenated to each\n                layer's input\n        \"\"\"\n        super(StandardPointHead, self).__init__()\n        # fmt: off\n        num_classes                 = cfg.MODEL.POINT_HEAD.NUM_CLASSES\n        fc_dim                      = cfg.MODEL.POINT_HEAD.FC_DIM\n        num_fc                      = cfg.MODEL.POINT_HEAD.NUM_FC\n        cls_agnostic_mask           = cfg.MODEL.POINT_HEAD.CLS_AGNOSTIC_MASK\n        self.coarse_pred_each_layer = cfg.MODEL.POINT_HEAD.COARSE_PRED_EACH_LAYER\n        input_channels              = input_shape.channels\n        # fmt: on\n\n        fc_dim_in = input_channels + num_classes\n        self.fc_layers = []\n        for k in range(num_fc):\n            fc = nn.Conv1d(fc_dim_in, fc_dim, kernel_size=1, stride=1, padding=0, bias=True)\n            self.add_module(\"fc{}\".format(k + 1), fc)\n            self.fc_layers.append(fc)\n            fc_dim_in = fc_dim\n            fc_dim_in += num_classes if self.coarse_pred_each_layer else 0\n\n        num_mask_classes = 1 if cls_agnostic_mask else num_classes\n        self.predictor = nn.Conv1d(fc_dim_in, num_mask_classes, kernel_size=1, stride=1, padding=0)\n\n        for layer in self.fc_layers:\n            weight_init.c2_msra_fill(layer)\n        # use normal distribution initialization for mask prediction layer\n        nn.init.normal_(self.predictor.weight, std=0.001)\n        if self.predictor.bias is not None:\n            nn.init.constant_(self.predictor.bias, 0)\n\n    def forward(self, fine_grained_features, coarse_features):\n        x = torch.cat((fine_grained_features, coarse_features), dim=1)\n        for layer in self.fc_layers:\n            x = F.relu(layer(x))\n            if self.coarse_pred_each_layer:\n                x = cat((x, coarse_features), dim=1)\n        return self.predictor(x)\n\n\n@POINT_HEAD_REGISTRY.register()\nclass ImplicitPointHead(nn.Module):\n    \"\"\"\n    A point head multi-layer perceptron which we model with conv1d layers with kernel 1. The head\n    takes both fine-grained features and instance-wise MLP parameters as its input.\n    \"\"\"\n\n    def __init__(self, cfg, input_shape: ShapeSpec):\n        \"\"\"\n        The following attributes are parsed from config:\n            channels: the output dimension of each FC layers\n            num_layers: the number of FC layers (including the final prediction layer)\n            image_feature_enabled: if True, fine-grained image-level features are used\n            positional_encoding_enabled: if True, positional encoding is used\n        \"\"\"\n        super(ImplicitPointHead, self).__init__()\n        # fmt: off\n        self.num_layers                         = cfg.MODEL.POINT_HEAD.NUM_FC + 1\n        self.channels                           = cfg.MODEL.POINT_HEAD.FC_DIM\n        self.image_feature_enabled              = cfg.MODEL.IMPLICIT_POINTREND.IMAGE_FEATURE_ENABLED\n        self.positional_encoding_enabled        = cfg.MODEL.IMPLICIT_POINTREND.POS_ENC_ENABLED\n        self.num_classes                        = (\n            cfg.MODEL.POINT_HEAD.NUM_CLASSES if not cfg.MODEL.POINT_HEAD.CLS_AGNOSTIC_MASK else 1\n        )\n        self.in_channels                        = input_shape.channels\n        # fmt: on\n\n        if not self.image_feature_enabled:\n            self.in_channels = 0\n        if self.positional_encoding_enabled:\n            self.in_channels += 256\n            self.register_buffer(\"positional_encoding_gaussian_matrix\", torch.randn((2, 128)))\n\n        assert self.in_channels > 0\n\n        num_weight_params, num_bias_params = [], []\n        assert self.num_layers >= 2\n        for l in range(self.num_layers):\n            if l == 0:\n                # input layer\n                num_weight_params.append(self.in_channels * self.channels)\n                num_bias_params.append(self.channels)\n            elif l == self.num_layers - 1:\n                # output layer\n                num_weight_params.append(self.channels * self.num_classes)\n                num_bias_params.append(self.num_classes)\n            else:\n                # intermediate layer\n                num_weight_params.append(self.channels * self.channels)\n                num_bias_params.append(self.channels)\n\n        self.num_weight_params = num_weight_params\n        self.num_bias_params = num_bias_params\n        self.num_params = sum(num_weight_params) + sum(num_bias_params)\n\n    def forward(self, fine_grained_features, point_coords, parameters):\n        # features: [R, channels, K]\n        # point_coords: [R, K, 2]\n        num_instances = fine_grained_features.size(0)\n        num_points = fine_grained_features.size(2)\n\n        if num_instances == 0:\n            return torch.zeros((0, 1, num_points), device=fine_grained_features.device)\n\n        if self.positional_encoding_enabled:\n            # locations: [R*K, 2]\n            locations = 2 * point_coords.reshape(num_instances * num_points, 2) - 1\n            locations = locations @ self.positional_encoding_gaussian_matrix.to(locations.device)\n            locations = 2 * np.pi * locations\n            locations = torch.cat([torch.sin(locations), torch.cos(locations)], dim=1)\n            # locations: [R, C, K]\n            locations = locations.reshape(num_instances, num_points, 256).permute(0, 2, 1)\n            if not self.image_feature_enabled:\n                fine_grained_features = locations\n            else:\n                fine_grained_features = torch.cat([locations, fine_grained_features], dim=1)\n\n        # features [R, C, K]\n        mask_feat = fine_grained_features.reshape(num_instances, self.in_channels, num_points)\n\n        weights, biases = self._parse_params(\n            parameters,\n            self.in_channels,\n            self.channels,\n            self.num_classes,\n            self.num_weight_params,\n            self.num_bias_params,\n        )\n\n        point_logits = self._dynamic_mlp(mask_feat, weights, biases, num_instances)\n        point_logits = point_logits.reshape(-1, self.num_classes, num_points)\n\n        return point_logits\n\n    @staticmethod\n    def _dynamic_mlp(features, weights, biases, num_instances):\n        assert features.dim() == 3, features.dim()\n        n_layers = len(weights)\n        x = features\n        for i, (w, b) in enumerate(zip(weights, biases)):\n            x = torch.einsum(\"nck,ndc->ndk\", x, w) + b\n            if i < n_layers - 1:\n                x = F.relu(x)\n        return x\n\n    @staticmethod\n    def _parse_params(\n        pred_params,\n        in_channels,\n        channels,\n        num_classes,\n        num_weight_params,\n        num_bias_params,\n    ):\n        assert pred_params.dim() == 2\n        assert len(num_weight_params) == len(num_bias_params)\n        assert pred_params.size(1) == sum(num_weight_params) + sum(num_bias_params)\n\n        num_instances = pred_params.size(0)\n        num_layers = len(num_weight_params)\n\n        params_splits = list(\n            torch.split_with_sizes(pred_params, num_weight_params + num_bias_params, dim=1)\n        )\n\n        weight_splits = params_splits[:num_layers]\n        bias_splits = params_splits[num_layers:]\n\n        for l in range(num_layers):\n            if l == 0:\n                # input layer\n                weight_splits[l] = weight_splits[l].reshape(num_instances, channels, in_channels)\n                bias_splits[l] = bias_splits[l].reshape(num_instances, channels, 1)\n            elif l < num_layers - 1:\n                # intermediate layer\n                weight_splits[l] = weight_splits[l].reshape(num_instances, channels, channels)\n                bias_splits[l] = bias_splits[l].reshape(num_instances, channels, 1)\n            else:\n                # output layer\n                weight_splits[l] = weight_splits[l].reshape(num_instances, num_classes, channels)\n                bias_splits[l] = bias_splits[l].reshape(num_instances, num_classes, 1)\n\n        return weight_splits, bias_splits\n\n\ndef build_point_head(cfg, input_channels):\n    \"\"\"\n    Build a point head defined by `cfg.MODEL.POINT_HEAD.NAME`.\n    \"\"\"\n    head_name = cfg.MODEL.POINT_HEAD.NAME\n    return POINT_HEAD_REGISTRY.get(head_name)(cfg, input_channels)\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/point_rend/roi_heads.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport logging\n\nfrom detectron2.modeling import ROI_HEADS_REGISTRY, StandardROIHeads\n\n\n@ROI_HEADS_REGISTRY.register()\nclass PointRendROIHeads(StandardROIHeads):\n    \"\"\"\n    Identical to StandardROIHeads, except for some weights conversion code to\n    handle old models.\n    \"\"\"\n\n    _version = 2\n\n    def _load_from_state_dict(\n        self, state_dict, prefix, local_metadata, strict, missing_keys, unexpected_keys, error_msgs\n    ):\n        version = local_metadata.get(\"version\", None)\n        if version is None or version < 2:\n            logger = logging.getLogger(__name__)\n            logger.warning(\n                \"Weight format of PointRend models have changed! \"\n                \"Please upgrade your models. Applying automatic conversion now ...\"\n            )\n            for k in list(state_dict.keys()):\n                newk = k\n                if k.startswith(prefix + \"mask_point_head\"):\n                    newk = k.replace(prefix + \"mask_point_head\", prefix + \"mask_head.point_head\")\n                if k.startswith(prefix + \"mask_coarse_head\"):\n                    newk = k.replace(prefix + \"mask_coarse_head\", prefix + \"mask_head.coarse_head\")\n                if newk != k:\n                    state_dict[newk] = state_dict[k]\n                    del state_dict[k]\n\n    @classmethod\n    def _init_mask_head(cls, cfg, input_shape):\n        if cfg.MODEL.MASK_ON and cfg.MODEL.ROI_MASK_HEAD.NAME != \"PointRendMaskHead\":\n            logger = logging.getLogger(__name__)\n            logger.warning(\n                \"Config of PointRend models have changed! \"\n                \"Please upgrade your models. Applying automatic conversion now ...\"\n            )\n            assert cfg.MODEL.ROI_MASK_HEAD.NAME == \"CoarseMaskHead\"\n            cfg.defrost()\n            cfg.MODEL.ROI_MASK_HEAD.NAME = \"PointRendMaskHead\"\n            cfg.MODEL.ROI_MASK_HEAD.POOLER_TYPE = \"\"\n            cfg.freeze()\n        return super()._init_mask_head(cfg, input_shape)\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/point_rend/semantic_seg.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport numpy as np\nfrom typing import Dict\nimport torch\nfrom torch import nn\nfrom torch.nn import functional as F\n\nfrom detectron2.layers import ShapeSpec, cat\nfrom detectron2.modeling import SEM_SEG_HEADS_REGISTRY\n\nfrom .point_features import (\n    get_uncertain_point_coords_on_grid,\n    get_uncertain_point_coords_with_randomness,\n    point_sample,\n)\nfrom .point_head import build_point_head\n\n\ndef calculate_uncertainty(sem_seg_logits):\n    \"\"\"\n    For each location of the prediction `sem_seg_logits` we estimate uncerainty as the\n        difference between top first and top second predicted logits.\n\n    Args:\n        mask_logits (Tensor): A tensor of shape (N, C, ...), where N is the minibatch size and\n            C is the number of foreground classes. The values are logits.\n\n    Returns:\n        scores (Tensor): A tensor of shape (N, 1, ...) that contains uncertainty scores with\n            the most uncertain locations having the highest uncertainty score.\n    \"\"\"\n    top2_scores = torch.topk(sem_seg_logits, k=2, dim=1)[0]\n    return (top2_scores[:, 1] - top2_scores[:, 0]).unsqueeze(1)\n\n\n@SEM_SEG_HEADS_REGISTRY.register()\nclass PointRendSemSegHead(nn.Module):\n    \"\"\"\n    A semantic segmentation head that combines a head set in `POINT_HEAD.COARSE_SEM_SEG_HEAD_NAME`\n    and a point head set in `MODEL.POINT_HEAD.NAME`.\n    \"\"\"\n\n    def __init__(self, cfg, input_shape: Dict[str, ShapeSpec]):\n        super().__init__()\n\n        self.ignore_value = cfg.MODEL.SEM_SEG_HEAD.IGNORE_VALUE\n\n        self.coarse_sem_seg_head = SEM_SEG_HEADS_REGISTRY.get(\n            cfg.MODEL.POINT_HEAD.COARSE_SEM_SEG_HEAD_NAME\n        )(cfg, input_shape)\n        self._init_point_head(cfg, input_shape)\n\n    def _init_point_head(self, cfg, input_shape: Dict[str, ShapeSpec]):\n        # fmt: off\n        assert cfg.MODEL.SEM_SEG_HEAD.NUM_CLASSES == cfg.MODEL.POINT_HEAD.NUM_CLASSES\n        feature_channels             = {k: v.channels for k, v in input_shape.items()}\n        self.in_features             = cfg.MODEL.POINT_HEAD.IN_FEATURES\n        self.train_num_points        = cfg.MODEL.POINT_HEAD.TRAIN_NUM_POINTS\n        self.oversample_ratio        = cfg.MODEL.POINT_HEAD.OVERSAMPLE_RATIO\n        self.importance_sample_ratio = cfg.MODEL.POINT_HEAD.IMPORTANCE_SAMPLE_RATIO\n        self.subdivision_steps       = cfg.MODEL.POINT_HEAD.SUBDIVISION_STEPS\n        self.subdivision_num_points  = cfg.MODEL.POINT_HEAD.SUBDIVISION_NUM_POINTS\n        # fmt: on\n\n        in_channels = int(np.sum([feature_channels[f] for f in self.in_features]))\n        self.point_head = build_point_head(cfg, ShapeSpec(channels=in_channels, width=1, height=1))\n\n    def forward(self, features, targets=None):\n        coarse_sem_seg_logits = self.coarse_sem_seg_head.layers(features)\n\n        if self.training:\n            losses = self.coarse_sem_seg_head.losses(coarse_sem_seg_logits, targets)\n\n            with torch.no_grad():\n                point_coords = get_uncertain_point_coords_with_randomness(\n                    coarse_sem_seg_logits,\n                    calculate_uncertainty,\n                    self.train_num_points,\n                    self.oversample_ratio,\n                    self.importance_sample_ratio,\n                )\n            coarse_features = point_sample(coarse_sem_seg_logits, point_coords, align_corners=False)\n\n            fine_grained_features = cat(\n                [\n                    point_sample(features[in_feature], point_coords, align_corners=False)\n                    for in_feature in self.in_features\n                ],\n                dim=1,\n            )\n            point_logits = self.point_head(fine_grained_features, coarse_features)\n            point_targets = (\n                point_sample(\n                    targets.unsqueeze(1).to(torch.float),\n                    point_coords,\n                    mode=\"nearest\",\n                    align_corners=False,\n                )\n                .squeeze(1)\n                .to(torch.long)\n            )\n            losses[\"loss_sem_seg_point\"] = F.cross_entropy(\n                point_logits, point_targets, reduction=\"mean\", ignore_index=self.ignore_value\n            )\n            return None, losses\n        else:\n            sem_seg_logits = coarse_sem_seg_logits.clone()\n            for _ in range(self.subdivision_steps):\n                sem_seg_logits = F.interpolate(\n                    sem_seg_logits, scale_factor=2, mode=\"bilinear\", align_corners=False\n                )\n                uncertainty_map = calculate_uncertainty(sem_seg_logits)\n                point_indices, point_coords = get_uncertain_point_coords_on_grid(\n                    uncertainty_map, self.subdivision_num_points\n                )\n                fine_grained_features = cat(\n                    [\n                        point_sample(features[in_feature], point_coords, align_corners=False)\n                        for in_feature in self.in_features\n                    ]\n                )\n                coarse_features = point_sample(\n                    coarse_sem_seg_logits, point_coords, align_corners=False\n                )\n                point_logits = self.point_head(fine_grained_features, coarse_features)\n\n                # put sem seg point predictions to the right places on the upsampled grid.\n                N, C, H, W = sem_seg_logits.shape\n                point_indices = point_indices.unsqueeze(1).expand(-1, C, -1)\n                sem_seg_logits = (\n                    sem_seg_logits.reshape(N, C, H * W)\n                    .scatter_(2, point_indices, point_logits)\n                    .view(N, C, H, W)\n                )\n            return sem_seg_logits, {}\n"
  },
  {
    "path": "VPS_Module/projects/PointRend/train_net.py",
    "content": "#!/usr/bin/env python3\n# Copyright (c) Facebook, Inc. and its affiliates.\n\n\"\"\"\nPointRend Training Script.\n\nThis script is a simplified version of the training script in detectron2/tools.\n\"\"\"\n\nimport os\nimport torch\n\nimport detectron2.data.transforms as T\nimport detectron2.utils.comm as comm\nfrom detectron2.checkpoint import DetectionCheckpointer\nfrom detectron2.config import get_cfg\nfrom detectron2.data import DatasetMapper, MetadataCatalog, build_detection_train_loader\nfrom detectron2.engine import DefaultTrainer, default_argument_parser, default_setup, launch\nfrom detectron2.evaluation import (\n    CityscapesInstanceEvaluator,\n    CityscapesSemSegEvaluator,\n    COCOEvaluator,\n    DatasetEvaluators,\n    LVISEvaluator,\n    SemSegEvaluator,\n    verify_results,\n)\nfrom detectron2.projects.point_rend import ColorAugSSDTransform, add_pointrend_config\n\n\ndef build_sem_seg_train_aug(cfg):\n    augs = [\n        T.ResizeShortestEdge(\n            cfg.INPUT.MIN_SIZE_TRAIN, cfg.INPUT.MAX_SIZE_TRAIN, cfg.INPUT.MIN_SIZE_TRAIN_SAMPLING\n        )\n    ]\n    if cfg.INPUT.CROP.ENABLED:\n        augs.append(\n            T.RandomCrop_CategoryAreaConstraint(\n                cfg.INPUT.CROP.TYPE,\n                cfg.INPUT.CROP.SIZE,\n                cfg.INPUT.CROP.SINGLE_CATEGORY_MAX_AREA,\n                cfg.MODEL.SEM_SEG_HEAD.IGNORE_VALUE,\n            )\n        )\n    if cfg.INPUT.COLOR_AUG_SSD:\n        augs.append(ColorAugSSDTransform(img_format=cfg.INPUT.FORMAT))\n    augs.append(T.RandomFlip())\n    return augs\n\n\nclass Trainer(DefaultTrainer):\n    \"\"\"\n    We use the \"DefaultTrainer\" which contains a number pre-defined logic for\n    standard training workflow. They may not work for you, especially if you\n    are working on a new research project. In that case you can use the cleaner\n    \"SimpleTrainer\", or write your own training loop.\n    \"\"\"\n\n    @classmethod\n    def build_evaluator(cls, cfg, dataset_name, output_folder=None):\n        \"\"\"\n        Create evaluator(s) for a given dataset.\n        This uses the special metadata \"evaluator_type\" associated with each builtin dataset.\n        For your own dataset, you can simply create an evaluator manually in your\n        script and do not have to worry about the hacky if-else logic here.\n        \"\"\"\n        if output_folder is None:\n            output_folder = os.path.join(cfg.OUTPUT_DIR, \"inference\")\n        evaluator_list = []\n        evaluator_type = MetadataCatalog.get(dataset_name).evaluator_type\n        if evaluator_type == \"lvis\":\n            return LVISEvaluator(dataset_name, output_dir=output_folder)\n        if evaluator_type == \"coco\":\n            return COCOEvaluator(dataset_name, output_dir=output_folder)\n        if evaluator_type == \"sem_seg\":\n            return SemSegEvaluator(\n                dataset_name,\n                distributed=True,\n                output_dir=output_folder,\n            )\n        if evaluator_type == \"cityscapes_instance\":\n            assert (\n                torch.cuda.device_count() > comm.get_rank()\n            ), \"CityscapesEvaluator currently do not work with multiple machines.\"\n            return CityscapesInstanceEvaluator(dataset_name)\n        if evaluator_type == \"cityscapes_sem_seg\":\n            assert (\n                torch.cuda.device_count() > comm.get_rank()\n            ), \"CityscapesEvaluator currently do not work with multiple machines.\"\n            return CityscapesSemSegEvaluator(dataset_name)\n        if len(evaluator_list) == 0:\n            raise NotImplementedError(\n                \"no Evaluator for the dataset {} with the type {}\".format(\n                    dataset_name, evaluator_type\n                )\n            )\n        if len(evaluator_list) == 1:\n            return evaluator_list[0]\n        return DatasetEvaluators(evaluator_list)\n\n    @classmethod\n    def build_train_loader(cls, cfg):\n        if \"SemanticSegmentor\" in cfg.MODEL.META_ARCHITECTURE:\n            mapper = DatasetMapper(cfg, is_train=True, augmentations=build_sem_seg_train_aug(cfg))\n        else:\n            mapper = None\n        return build_detection_train_loader(cfg, mapper=mapper)\n\n\ndef setup(args):\n    \"\"\"\n    Create configs and perform basic setups.\n    \"\"\"\n    cfg = get_cfg()\n    add_pointrend_config(cfg)\n    cfg.merge_from_file(args.config_file)\n    cfg.merge_from_list(args.opts)\n    cfg.freeze()\n    default_setup(cfg, args)\n    return cfg\n\n\ndef main(args):\n    cfg = setup(args)\n\n    if args.eval_only:\n        model = Trainer.build_model(cfg)\n        DetectionCheckpointer(model, save_dir=cfg.OUTPUT_DIR).resume_or_load(\n            cfg.MODEL.WEIGHTS, resume=args.resume\n        )\n        res = Trainer.test(cfg, model)\n        if comm.is_main_process():\n            verify_results(cfg, res)\n        return res\n\n    trainer = Trainer(cfg)\n    trainer.resume_or_load(resume=args.resume)\n    return trainer.train()\n\n\nif __name__ == \"__main__\":\n    args = default_argument_parser().parse_args()\n    print(\"Command Line Args:\", args)\n    launch(\n        main,\n        args.num_gpus,\n        num_machines=args.num_machines,\n        machine_rank=args.machine_rank,\n        dist_url=args.dist_url,\n        args=(args,),\n    )\n"
  },
  {
    "path": "VPS_Module/projects/PointSup/README.md",
    "content": "# Pointly-Supervised Instance Segmentation\n\nBowen Cheng, Omkar Parkhi, Alexander Kirillov\n\n[[`arXiv`](https://arxiv.org/abs/2104.06404)] [[`Project`](https://bowenc0221.github.io/point-sup)] [[`BibTeX`](#CitingPointSup)]\n\n<div align=\"center\">\n  <img src=\"https://bowenc0221.github.io/images/cheng2021pointly.png\" width=\"50%\" height=\"50%\"/>\n</div><br/>\n\n## Data preparation\nPlease follow these steps to prepare your datasets:\n1. Follow official Detectron2 instruction to prepare COCO dataset. Set up `DETECTRON2_DATASETS` environment variable to the location of your Detectron2 dataset.\n2. Generate 10-points annotations for COCO by running: `python tools/prepare_coco_point_annotations_without_masks.py 10`\n\n## Training\n\nTo train a model with 8 GPUs run:\n```bash\npython train_net.py --config-file configs/mask_rcnn_R_50_FPN_3x_point_sup_point_aug_coco.yaml --num-gpus 8\n```\n\n## Evaluation\n\nModel evaluation can be done similarly:\n```bash\npython train_net.py --config-file configs/mask_rcnn_R_50_FPN_3x_point_sup_point_aug_coco.yaml --eval-only MODEL.WEIGHTS /path/to/model_checkpoint\n```\n\n## <a name=\"CitingPointSup\"></a>Citing Pointly-Supervised Instance Segmentation\n\nIf you use PointSup, please use the following BibTeX entry.\n\n```BibTeX\n@article{cheng2021pointly,\n  title={Pointly-Supervised Instance Segmentation},\n  author={Bowen Cheng and Omkar Parkhi and Alexander Kirillov},\n  journal={arXiv},\n  year={2021}\n}\n```\n"
  },
  {
    "path": "VPS_Module/projects/PointSup/configs/implicit_pointrend_R_50_FPN_3x_point_sup_point_aug_coco.yaml",
    "content": "_BASE_: \"../../PointRend/configs/InstanceSegmentation/implicit_pointrend_R_50_FPN_3x_coco.yaml\"\nMODEL:\n  ROI_MASK_HEAD:\n    NAME: \"ImplicitPointRendPointSupHead\"\nINPUT:\n  POINT_SUP: True\n  SAMPLE_POINTS: 5\nDATASETS:\n  TRAIN: (\"coco_2017_train_points_n10_v1_without_masks\",)\n"
  },
  {
    "path": "VPS_Module/projects/PointSup/configs/mask_rcnn_R_50_FPN_3x_point_sup_coco.yaml",
    "content": "_BASE_: \"../../../configs/Base-RCNN-FPN.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: True\n  RESNETS:\n    DEPTH: 50\n  ROI_MASK_HEAD:\n    NAME: \"MaskRCNNConvUpsamplePointSupHead\"\nINPUT:\n  POINT_SUP: True\nDATASETS:\n  TRAIN: (\"coco_2017_train_points_n10_v1_without_masks\",)\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/projects/PointSup/configs/mask_rcnn_R_50_FPN_3x_point_sup_point_aug_coco.yaml",
    "content": "_BASE_: \"mask_rcnn_R_50_FPN_3x_point_sup_coco.yaml\"\nINPUT:\n  SAMPLE_POINTS: 5\n"
  },
  {
    "path": "VPS_Module/projects/PointSup/point_sup/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\nfrom . import register_point_annotations\nfrom .config import add_point_sup_config\nfrom .dataset_mapper import PointSupDatasetMapper\nfrom .mask_head import MaskRCNNConvUpsamplePointSupHead\nfrom .point_utils import get_point_coords_from_point_annotation\n"
  },
  {
    "path": "VPS_Module/projects/PointSup/point_sup/config.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\n\ndef add_point_sup_config(cfg):\n    \"\"\"\n    Add config for point supervision.\n    \"\"\"\n    # Use point annotation\n    cfg.INPUT.POINT_SUP = False\n    # Sample only part of points in each iteration.\n    # Default: 0, use all available points.\n    cfg.INPUT.SAMPLE_POINTS = 0\n"
  },
  {
    "path": "VPS_Module/projects/PointSup/point_sup/dataset_mapper.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\nimport copy\nimport logging\nimport numpy as np\nfrom typing import List, Union\nimport torch\n\nimport detectron2.data.detection_utils as utils\nimport detectron2.data.transforms as T\nfrom detectron2.config import configurable\n\nfrom .detection_utils import annotations_to_instances, transform_instance_annotations\n\n__all__ = [\n    \"PointSupDatasetMapper\",\n]\n\n\nclass PointSupDatasetMapper:\n    \"\"\"\n    The callable currently does the following:\n    1. Read the image from \"file_name\"\n    2. Applies transforms to the image and annotations\n    3. Prepare data and annotations to Tensor and :class:`Instances`\n    \"\"\"\n\n    @configurable\n    def __init__(\n        self,\n        is_train: bool,\n        *,\n        augmentations: List[Union[T.Augmentation, T.Transform]],\n        image_format: str,\n        # Extra data augmentation for point supervision\n        sample_points: int = 0,\n    ):\n        \"\"\"\n        NOTE: this interface is experimental.\n\n        Args:\n            is_train: whether it's used in training or inference\n            augmentations: a list of augmentations or deterministic transforms to apply\n            image_format: an image format supported by :func:`detection_utils.read_image`.\n            sample_points: subsample points at each iteration\n        \"\"\"\n        # fmt: off\n        self.is_train               = is_train\n        self.augmentations          = T.AugmentationList(augmentations)\n        self.image_format           = image_format\n        self.sample_points          = sample_points\n        # fmt: on\n        logger = logging.getLogger(__name__)\n        mode = \"training\" if is_train else \"inference\"\n        logger.info(f\"[DatasetMapper] Augmentations used in {mode}: {augmentations}\")\n        logger.info(f\"Point Augmentations used in {mode}: sample {sample_points} points\")\n\n    @classmethod\n    def from_config(cls, cfg, is_train: bool = True):\n        augs = utils.build_augmentation(cfg, is_train)\n        if cfg.INPUT.CROP.ENABLED and is_train:\n            raise ValueError(\"Crop augmentation not supported to point supervision.\")\n\n        ret = {\n            \"is_train\": is_train,\n            \"augmentations\": augs,\n            \"image_format\": cfg.INPUT.FORMAT,\n            \"sample_points\": cfg.INPUT.SAMPLE_POINTS,\n        }\n\n        return ret\n\n    def __call__(self, dataset_dict):\n        \"\"\"\n        Args:\n            dataset_dict (dict): Metadata of one image, in Detectron2 Dataset format.\n        Returns:\n            dict: a format that builtin models in detectron2 accept\n        \"\"\"\n        dataset_dict = copy.deepcopy(dataset_dict)  # it will be modified by code below\n        image = utils.read_image(dataset_dict[\"file_name\"], format=self.image_format)\n        utils.check_image_size(dataset_dict, image)\n\n        aug_input = T.AugInput(image)\n        transforms = self.augmentations(aug_input)\n        image = aug_input.image\n\n        image_shape = image.shape[:2]  # h, w\n        # Pytorch's dataloader is efficient on torch.Tensor due to shared-memory,\n        # but not efficient on large generic data structures due to the use of pickle & mp.Queue.\n        # Therefore it's important to use torch.Tensor.\n        dataset_dict[\"image\"] = torch.as_tensor(np.ascontiguousarray(image.transpose(2, 0, 1)))\n\n        if not self.is_train:\n            dataset_dict.pop(\"annotations\", None)\n            return dataset_dict\n\n        if \"annotations\" in dataset_dict:\n            # Maps points from the closed interval [0, image_size - 1] on discrete\n            # image coordinates to the half-open interval [x1, x2) on continuous image\n            # coordinates. We use the continuous-discrete conversion from Heckbert\n            # 1990 (\"What is the coordinate of a pixel?\"): d = floor(c) and c = d + 0.5,\n            # where d is a discrete coordinate and c is a continuous coordinate.\n            for ann in dataset_dict[\"annotations\"]:\n                point_coords_wrt_image = np.array(ann[\"point_coords\"]).astype(np.float)\n                point_coords_wrt_image = point_coords_wrt_image + 0.5\n                ann[\"point_coords\"] = point_coords_wrt_image\n\n            annos = [\n                # also need to transform point coordinates\n                transform_instance_annotations(\n                    obj,\n                    transforms,\n                    image_shape,\n                )\n                for obj in dataset_dict.pop(\"annotations\")\n                if obj.get(\"iscrowd\", 0) == 0\n            ]\n            instances = annotations_to_instances(\n                annos,\n                image_shape,\n                sample_points=self.sample_points,\n            )\n\n            dataset_dict[\"instances\"] = utils.filter_empty_instances(instances)\n        return dataset_dict\n"
  },
  {
    "path": "VPS_Module/projects/PointSup/point_sup/detection_utils.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nimport numpy as np\nimport torch\n\n# fmt: off\nfrom detectron2.data.detection_utils import \\\n    annotations_to_instances as base_annotations_to_instances\nfrom detectron2.data.detection_utils import \\\n    transform_instance_annotations as base_transform_instance_annotations\n\n# fmt: on\n\n\ndef annotations_to_instances(annos, image_size, sample_points=0):\n    \"\"\"\n    Create an :class:`Instances` object used by the models,\n    from instance annotations in the dataset dict.\n\n    Args:\n        annos (list[dict]): a list of instance annotations in one image, each\n            element for one instance.\n        image_size (tuple): height, width\n        sample_points (int): subsample points at each iteration\n\n    Returns:\n        Instances:\n            It will contain fields \"gt_boxes\", \"gt_classes\",\n            \"gt_point_coords\", \"gt_point_labels\", if they can be obtained from `annos`.\n            This is the format that builtin models with point supervision expect.\n    \"\"\"\n    target = base_annotations_to_instances(annos, image_size)\n\n    assert (\"point_coords\" in annos[0]) == (\"point_labels\" in annos[0])\n\n    if len(annos) and \"point_labels\" in annos[0]:\n        point_coords = []\n        point_labels = []\n        for i, _ in enumerate(annos):\n            # Already in the image coordinate system\n            point_coords_wrt_image = np.array(annos[i][\"point_coords\"])\n            point_labels_wrt_image = np.array(annos[i][\"point_labels\"])\n\n            if sample_points > 0:\n                random_indices = np.random.choice(\n                    point_coords_wrt_image.shape[0],\n                    sample_points,\n                    replace=point_coords_wrt_image.shape[0] < sample_points,\n                ).astype(int)\n                point_coords_wrt_image = point_coords_wrt_image[random_indices]\n                point_labels_wrt_image = point_labels_wrt_image[random_indices]\n                assert point_coords_wrt_image.shape[0] == point_labels_wrt_image.size\n\n            point_coords.append(point_coords_wrt_image)\n            point_labels.append(point_labels_wrt_image)\n\n        point_coords = torch.stack([torch.from_numpy(x) for x in point_coords])\n        point_labels = torch.stack([torch.from_numpy(x) for x in point_labels])\n        target.gt_point_coords = point_coords\n        target.gt_point_labels = point_labels\n\n    return target\n\n\ndef transform_instance_annotations(\n    annotation, transforms, image_size, *, keypoint_hflip_indices=None\n):\n    \"\"\"\n    Apply transforms to box, and point annotations of a single instance.\n    It will use `transforms.apply_box` for the box, and\n    `transforms.apply_coords` for points.\n    Args:\n        annotation (dict): dict of instance annotations for a single instance.\n            It will be modified in-place.\n        transforms (TransformList or list[Transform]):\n        image_size (tuple): the height, width of the transformed image\n        keypoint_hflip_indices (ndarray[int]): see `create_keypoint_hflip_indices`.\n    Returns:\n        dict:\n            the same input dict with fields \"bbox\", \"point_coords\", \"point_labels\"\n            transformed according to `transforms`.\n            The \"bbox_mode\" field will be set to XYXY_ABS.\n    \"\"\"\n    annotation = base_transform_instance_annotations(\n        annotation, transforms, image_size, keypoint_hflip_indices\n    )\n\n    assert (\"point_coords\" in annotation) == (\"point_labels\" in annotation)\n    if \"point_coords\" in annotation and \"point_labels\" in annotation:\n        point_coords = annotation[\"point_coords\"]\n        point_labels = np.array(annotation[\"point_labels\"]).astype(np.float)\n        point_coords = transforms.apply_coords(point_coords)\n\n        # Set all out-of-boundary points to \"unlabeled\"\n        inside = (point_coords >= np.array([0, 0])) & (point_coords <= np.array(image_size[::-1]))\n        inside = inside.all(axis=1)\n        point_labels[~inside] = -1\n\n        annotation[\"point_coords\"] = point_coords\n        annotation[\"point_labels\"] = point_labels\n\n    return annotation\n"
  },
  {
    "path": "VPS_Module/projects/PointSup/point_sup/mask_head.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\nimport numpy as np\nfrom typing import Any, List\n\nfrom detectron2.modeling import ROI_MASK_HEAD_REGISTRY\nfrom detectron2.modeling.roi_heads.mask_head import MaskRCNNConvUpsampleHead, mask_rcnn_inference\nfrom detectron2.projects.point_rend import ImplicitPointRendMaskHead\nfrom detectron2.projects.point_rend.point_features import point_sample\nfrom detectron2.projects.point_rend.point_head import roi_mask_point_loss\nfrom detectron2.structures import Instances\n\nfrom .point_utils import get_point_coords_from_point_annotation\n\n__all__ = [\n    \"ImplicitPointRendPointSupHead\",\n    \"MaskRCNNConvUpsamplePointSupHead\",\n]\n\n\n@ROI_MASK_HEAD_REGISTRY.register()\nclass MaskRCNNConvUpsamplePointSupHead(MaskRCNNConvUpsampleHead):\n    \"\"\"\n    A mask head with several conv layers, plus an upsample layer (with `ConvTranspose2d`).\n    Predictions are made with a final 1x1 conv layer.\n\n    The difference with `MaskRCNNConvUpsampleHead` is that this head is trained\n    with point supervision. Please use the `MaskRCNNConvUpsampleHead` if you want\n    to train the model with mask supervision.\n    \"\"\"\n\n    def forward(self, x, instances: List[Instances]) -> Any:\n        \"\"\"\n        Args:\n            x: input region feature(s) provided by :class:`ROIHeads`.\n            instances (list[Instances]): contains the boxes & labels corresponding\n                to the input features.\n                Exact format is up to its caller to decide.\n                Typically, this is the foreground instances in training, with\n                \"proposal_boxes\" field and other gt annotations.\n                In inference, it contains boxes that are already predicted.\n        Returns:\n            A dict of losses in training. The predicted \"instances\" in inference.\n        \"\"\"\n        x = self.layers(x)\n        if self.training:\n            N, C, H, W = x.shape\n            assert H == W\n\n            proposal_boxes = [x.proposal_boxes for x in instances]\n            assert N == np.sum(len(x) for x in proposal_boxes)\n\n            if N == 0:\n                return {\"loss_mask\": x.sum() * 0}\n\n            # Training with point supervision\n            point_coords, point_labels = get_point_coords_from_point_annotation(instances)\n\n            mask_logits = point_sample(\n                x,\n                point_coords,\n                align_corners=False,\n            )\n\n            return {\"loss_mask\": roi_mask_point_loss(mask_logits, instances, point_labels)}\n        else:\n            mask_rcnn_inference(x, instances)\n            return instances\n\n\n@ROI_MASK_HEAD_REGISTRY.register()\nclass ImplicitPointRendPointSupHead(ImplicitPointRendMaskHead):\n    def _uniform_sample_train_points(self, instances):\n        assert self.training\n        # Please keep in mind that \"gt_masks\" is not used in this mask head.\n        point_coords, point_labels = get_point_coords_from_point_annotation(instances)\n\n        return point_coords, point_labels\n"
  },
  {
    "path": "VPS_Module/projects/PointSup/point_sup/point_utils.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\nimport torch\n\nfrom detectron2.layers import cat\n\n\ndef get_point_coords_from_point_annotation(instances):\n    \"\"\"\n    Load point coords and their corresponding labels from point annotation.\n\n    Args:\n        instances (list[Instances]): A list of N Instances, where N is the number of images\n            in the batch. These instances are in 1:1\n            correspondence with the pred_mask_logits. The ground-truth labels (class, box, mask,\n            ...) associated with each instance are stored in fields.\n    Returns:\n        point_coords (Tensor): A tensor of shape (N, P, 2) that contains the coordinates of P\n            sampled points.\n        point_labels (Tensor): A tensor of shape (N, P) that contains the labels of P\n            sampled points. `point_labels` takes 3 possible values:\n            - 0: the point belongs to background\n            - 1: the point belongs to the object\n            - -1: the point is ignored during training\n    \"\"\"\n    point_coords_list = []\n    point_labels_list = []\n    for instances_per_image in instances:\n        if len(instances_per_image) == 0:\n            continue\n        point_coords = instances_per_image.gt_point_coords.to(torch.float32)\n        point_labels = instances_per_image.gt_point_labels.to(torch.float32).clone()\n        proposal_boxes_per_image = instances_per_image.proposal_boxes.tensor\n\n        # Convert point coordinate system, ground truth points are in image coord.\n        point_coords_wrt_box = get_point_coords_wrt_box(proposal_boxes_per_image, point_coords)\n\n        # Ignore points that are outside predicted boxes.\n        point_ignores = (\n            (point_coords_wrt_box[:, :, 0] < 0)\n            | (point_coords_wrt_box[:, :, 0] > 1)\n            | (point_coords_wrt_box[:, :, 1] < 0)\n            | (point_coords_wrt_box[:, :, 1] > 1)\n        )\n        point_labels[point_ignores] = -1\n\n        point_coords_list.append(point_coords_wrt_box)\n        point_labels_list.append(point_labels)\n\n    return (\n        cat(point_coords_list, dim=0),\n        cat(point_labels_list, dim=0),\n    )\n\n\ndef get_point_coords_wrt_box(boxes_coords, point_coords):\n    \"\"\"\n    Convert image-level absolute coordinates to box-normalized [0, 1] x [0, 1] point cooordinates.\n    Args:\n        boxes_coords (Tensor): A tensor of shape (R, 4) that contains bounding boxes.\n            coordinates.\n        point_coords (Tensor): A tensor of shape (R, P, 2) that contains\n            image-normalized coordinates of P sampled points.\n    Returns:\n        point_coords_wrt_box (Tensor): A tensor of shape (R, P, 2) that contains\n            [0, 1] x [0, 1] box-normalized coordinates of the P sampled points.\n    \"\"\"\n    with torch.no_grad():\n        point_coords_wrt_box = point_coords.clone()\n        point_coords_wrt_box[:, :, 0] -= boxes_coords[:, None, 0]\n        point_coords_wrt_box[:, :, 1] -= boxes_coords[:, None, 1]\n        point_coords_wrt_box[:, :, 0] = point_coords_wrt_box[:, :, 0] / (\n            boxes_coords[:, None, 2] - boxes_coords[:, None, 0]\n        )\n        point_coords_wrt_box[:, :, 1] = point_coords_wrt_box[:, :, 1] / (\n            boxes_coords[:, None, 3] - boxes_coords[:, None, 1]\n        )\n    return point_coords_wrt_box\n"
  },
  {
    "path": "VPS_Module/projects/PointSup/point_sup/register_point_annotations.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\nimport logging\nimport os\n\nfrom detectron2.data import DatasetCatalog, MetadataCatalog\nfrom detectron2.data.datasets.builtin import _get_builtin_metadata\nfrom detectron2.data.datasets.coco import load_coco_json\n\nlogger = logging.getLogger(__name__)\n\n\n# COCO dataset\ndef register_coco_instances_with_points(name, metadata, json_file, image_root):\n    \"\"\"\n    Register a dataset in COCO's json annotation format for\n    instance segmentation with point annotation.\n\n    The point annotation json does not have \"segmentation\" field, instead,\n    it has \"point_coords\" and \"point_labels\" fields.\n\n    Args:\n        name (str): the name that identifies a dataset, e.g. \"coco_2014_train\".\n        metadata (dict): extra metadata associated with this dataset.  You can\n            leave it as an empty dict.\n        json_file (str): path to the json instance annotation file.\n        image_root (str or path-like): directory which contains all the images.\n    \"\"\"\n    assert isinstance(name, str), name\n    assert isinstance(json_file, (str, os.PathLike)), json_file\n    assert isinstance(image_root, (str, os.PathLike)), image_root\n    # 1. register a function which returns dicts\n    DatasetCatalog.register(\n        name, lambda: load_coco_json(json_file, image_root, name, [\"point_coords\", \"point_labels\"])\n    )\n\n    # 2. Optionally, add metadata about this dataset,\n    # since they might be useful in evaluation, visualization or logging\n    MetadataCatalog.get(name).set(\n        json_file=json_file, image_root=image_root, evaluator_type=\"coco\", **metadata\n    )\n\n\n_PREDEFINED_SPLITS_COCO = {}\n_PREDEFINED_SPLITS_COCO[\"coco\"] = {\n    # point annotations without masks\n    \"coco_2017_train_points_n10_v1_without_masks\": (\n        \"coco/train2017\",\n        \"coco/annotations/instances_train2017_n10_v1_without_masks.json\",\n    ),\n}\n\n\ndef register_all_coco_train_points(root):\n    for dataset_name, splits_per_dataset in _PREDEFINED_SPLITS_COCO.items():\n        for key, (image_root, json_file) in splits_per_dataset.items():\n            # Assume pre-defined datasets live in `./datasets`.\n            register_coco_instances_with_points(\n                key,\n                _get_builtin_metadata(dataset_name),\n                os.path.join(root, json_file) if \"://\" not in json_file else json_file,\n                os.path.join(root, image_root),\n            )\n\n\n# True for open source;\n# Internally at fb, we register them elsewhere\nif __name__.endswith(\".register_point_annotations\"):\n    _root = os.getenv(\"DETECTRON2_DATASETS\", \"datasets\")\n    register_all_coco_train_points(_root)\n"
  },
  {
    "path": "VPS_Module/projects/PointSup/tools/prepare_coco_point_annotations_without_masks.py",
    "content": "#!/usr/bin/env python3\n# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates. All Rights Reserved\n\nimport copy\nimport json\nimport numpy as np\nimport os\nimport sys\nimport pycocotools.mask as mask_utils\n\nfrom detectron2.utils.env import seed_all_rng\nfrom detectron2.utils.file_io import PathManager\n\n\ndef get_point_annotations(input_filename, output_filename, num_points_per_instance):\n    with PathManager.open(input_filename, \"r\") as f:\n        coco_json = json.load(f)\n\n    coco_annos = coco_json.pop(\"annotations\")\n    coco_points_json = copy.deepcopy(coco_json)\n\n    imgs = {}\n    for img in coco_json[\"images\"]:\n        imgs[img[\"id\"]] = img\n\n    new_annos = []\n    for ann in coco_annos:\n        # convert mask\n        t = imgs[ann[\"image_id\"]]\n        h, w = t[\"height\"], t[\"width\"]\n        segm = ann.pop(\"segmentation\")\n        if type(segm) == list:\n            # polygon -- a single object might consist of multiple parts\n            # we merge all parts into one mask rle code\n            rles = mask_utils.frPyObjects(segm, h, w)\n            rle = mask_utils.merge(rles)\n        elif type(segm[\"counts\"]) == list:\n            # uncompressed RLE\n            rle = mask_utils.frPyObjects(segm, h, w)\n        else:\n            # rle\n            rle = segm\n        mask = mask_utils.decode(rle)\n        new_ann = copy.deepcopy(ann)\n        # sample points in image coordinates\n        box = ann[\"bbox\"]\n        point_coords_wrt_image = np.random.rand(num_points_per_instance, 2)\n        point_coords_wrt_image[:, 0] = point_coords_wrt_image[:, 0] * box[2]\n        point_coords_wrt_image[:, 1] = point_coords_wrt_image[:, 1] * box[3]\n        point_coords_wrt_image[:, 0] += box[0]\n        point_coords_wrt_image[:, 1] += box[1]\n        # round to integer coordinates\n        point_coords_wrt_image = np.floor(point_coords_wrt_image).astype(int)\n        # get labels\n        assert (point_coords_wrt_image >= 0).all(), (point_coords_wrt_image, mask.shape)\n        assert (point_coords_wrt_image[:, 0] < w).all(), (point_coords_wrt_image, mask.shape)\n        assert (point_coords_wrt_image[:, 1] < h).all(), (point_coords_wrt_image, mask.shape)\n        point_labels = mask[point_coords_wrt_image[:, 1], point_coords_wrt_image[:, 0]]\n        # store new annotations\n        new_ann[\"point_coords\"] = point_coords_wrt_image.tolist()\n        new_ann[\"point_labels\"] = point_labels.tolist()\n        new_annos.append(new_ann)\n    coco_points_json[\"annotations\"] = new_annos\n\n    with PathManager.open(output_filename, \"w\") as f:\n        json.dump(coco_points_json, f)\n\n    print(\"{} is modified and stored in {}.\".format(input_filename, output_filename))\n\n\nif __name__ == \"__main__\":\n    \"\"\"\n    Generate point-based supervision for COCO dataset.\n\n    Usage:\n        python tools/prepare_coco_point_annotations_without_masks.py \\\n            NUM_POINTS_PER_INSTANCE NUM_VERSIONS_WITH_DIFFERENT_SEED\n\n    Example to generate point-based COCO dataset with 10 points per instance:\n        python tools/prepare_coco_point_annotations_without_masks.py 10\n    \"\"\"\n\n    # Fix random seed\n    seed_all_rng(12345)\n\n    assert len(sys.argv) >= 2, \"Please provide number of points to sample per instance\"\n    dataset_dir = os.path.join(os.getenv(\"DETECTRON2_DATASETS\", \"datasets\"), \"coco/annotations\")\n    num_points_per_instance = int(sys.argv[1])\n    if len(sys.argv) == 3:\n        repeat = int(sys.argv[2])\n    else:\n        repeat = 1\n    s = \"instances_train2017\"\n    for version in range(repeat):\n        print(\n            \"Start sampling {} points per instance for annotations {}.\".format(\n                num_points_per_instance, s\n            )\n        )\n        get_point_annotations(\n            os.path.join(dataset_dir, \"{}.json\".format(s)),\n            os.path.join(\n                dataset_dir,\n                \"{}_n{}_v{}_without_masks.json\".format(s, num_points_per_instance, version + 1),\n            ),\n            num_points_per_instance,\n        )\n"
  },
  {
    "path": "VPS_Module/projects/PointSup/train_net.py",
    "content": "#!/usr/bin/env python\n# Copyright (c) Facebook, Inc. and its affiliates.\n\"\"\"\nPoint supervision Training Script.\n\nThis script is a simplified version of the training script in detectron2/tools.\n\"\"\"\n\nimport os\n\nimport detectron2.utils.comm as comm\nfrom detectron2.checkpoint import DetectionCheckpointer\nfrom detectron2.config import get_cfg\nfrom detectron2.data import MetadataCatalog, build_detection_train_loader\nfrom detectron2.engine import DefaultTrainer, default_argument_parser, default_setup, launch\nfrom detectron2.evaluation import COCOEvaluator, DatasetEvaluators, verify_results\nfrom detectron2.projects.point_rend import add_pointrend_config\nfrom detectron2.utils.logger import setup_logger\n\nfrom point_sup import PointSupDatasetMapper, add_point_sup_config\n\n\nclass Trainer(DefaultTrainer):\n    \"\"\"\n    We use the \"DefaultTrainer\" which contains pre-defined default logic for\n    standard training workflow. They may not work for you, especially if you\n    are working on a new research project. In that case you can write your\n    own training loop. You can use \"tools/plain_train_net.py\" as an example.\n    \"\"\"\n\n    @classmethod\n    def build_evaluator(cls, cfg, dataset_name, output_folder=None):\n        \"\"\"\n        Create evaluator(s) for a given dataset.\n        This uses the special metadata \"evaluator_type\" associated with each builtin dataset.\n        For your own dataset, you can simply create an evaluator manually in your\n        script and do not have to worry about the hacky if-else logic here.\n        \"\"\"\n        if output_folder is None:\n            output_folder = os.path.join(cfg.OUTPUT_DIR, \"inference\")\n        evaluator_list = []\n        evaluator_type = MetadataCatalog.get(dataset_name).evaluator_type\n        if evaluator_type == \"coco\":\n            evaluator_list.append(COCOEvaluator(dataset_name, output_dir=output_folder))\n        if len(evaluator_list) == 0:\n            raise NotImplementedError(\n                \"no Evaluator for the dataset {} with the type {}\".format(\n                    dataset_name, evaluator_type\n                )\n            )\n        elif len(evaluator_list) == 1:\n            return evaluator_list[0]\n        return DatasetEvaluators(evaluator_list)\n\n    @classmethod\n    def build_train_loader(cls, cfg):\n        if cfg.INPUT.POINT_SUP:\n            mapper = PointSupDatasetMapper(cfg, is_train=True)\n        else:\n            mapper = None\n        return build_detection_train_loader(cfg, mapper=mapper)\n\n\ndef setup(args):\n    \"\"\"\n    Create configs and perform basic setups.\n    \"\"\"\n    cfg = get_cfg()\n    add_pointrend_config(cfg)\n    add_point_sup_config(cfg)\n    cfg.merge_from_file(args.config_file)\n    cfg.merge_from_list(args.opts)\n    cfg.freeze()\n    default_setup(cfg, args)\n    # Setup logger for \"point_sup\" module\n    setup_logger(output=cfg.OUTPUT_DIR, distributed_rank=comm.get_rank(), name=\"point_sup\")\n    return cfg\n\n\ndef main(args):\n    cfg = setup(args)\n\n    if args.eval_only:\n        model = Trainer.build_model(cfg)\n        DetectionCheckpointer(model, save_dir=cfg.OUTPUT_DIR).resume_or_load(\n            cfg.MODEL.WEIGHTS, resume=args.resume\n        )\n        res = Trainer.test(cfg, model)\n        if cfg.TEST.AUG.ENABLED:\n            res.update(Trainer.test_with_TTA(cfg, model))\n        if comm.is_main_process():\n            verify_results(cfg, res)\n        return res\n\n    \"\"\"\n    If you'd like to do anything fancier than the standard training logic,\n    consider writing your own training loop (see plain_train_net.py) or\n    subclassing the trainer.\n    \"\"\"\n    trainer = Trainer(cfg)\n    trainer.resume_or_load(resume=args.resume)\n    return trainer.train()\n\n\nif __name__ == \"__main__\":\n    args = default_argument_parser().parse_args()\n    print(\"Command Line Args:\", args)\n    launch(\n        main,\n        args.num_gpus,\n        num_machines=args.num_machines,\n        machine_rank=args.machine_rank,\n        dist_url=args.dist_url,\n        args=(args,),\n    )\n"
  },
  {
    "path": "VPS_Module/projects/README.md",
    "content": "\nHere are a few projects that are built on detectron2.\nThey are examples of how to use detectron2 as a library, to make your projects more\nmaintainable.\n\n## Projects by Facebook\n\nNote that these are research projects, and therefore may not have the same level\nof support or stability as detectron2.\n\n+ [DensePose: Dense Human Pose Estimation In The Wild](DensePose)\n+ [Scale-Aware Trident Networks for Object Detection](TridentNet)\n+ [TensorMask: A Foundation for Dense Object Segmentation](TensorMask)\n+ [Mesh R-CNN](https://github.com/facebookresearch/meshrcnn)\n+ [PointRend: Image Segmentation as Rendering](PointRend)\n+ [Momentum Contrast for Unsupervised Visual Representation Learning](https://github.com/facebookresearch/moco/tree/master/detection)\n+ [DETR: End-to-End Object Detection with Transformers](https://github.com/facebookresearch/detr/tree/master/d2)\n+ [Panoptic-DeepLab: A Simple, Strong, and Fast Baseline for Bottom-Up Panoptic Segmentation](Panoptic-DeepLab)\n+ [D2Go (Detectron2Go)](https://github.com/facebookresearch/d2go), an end-to-end production system for training and deployment for mobile platforms.\n+ [Pointly-Supervised Instance Segmentation](PointSup)\n+ [Unbiased Teacher for Semi-Supervised Object Detection](https://github.com/facebookresearch/unbiased-teacher)\n+ [Rethinking \"Batch\" in BatchNorm](Rethinking-BatchNorm/)\n+ [Per-Pixel Classification is Not All You Need for Semantic Segmentation](https://github.com/facebookresearch/MaskFormer)\n\n\n## External Projects\n\nExternal projects in the community that use detectron2:\n\n<!--\n - If you want to contribute, note that:\n -  1. please add your project to the list and try to use only one line\n -  2. the project must provide models trained on standard datasets\n\n Projects are *roughly sorted* by: \"score = PaperCitation * 5 + Stars\",\n where PaperCitation equals the citation count of the paper, if the project is an *official* implementation of the paper.\n PaperCitation equals 0 otherwise.\n -->\n\n+ [AdelaiDet](https://github.com/aim-uofa/adet), a detection toolbox including FCOS, BlendMask, etc.\n+ [CenterMask](https://github.com/youngwanLEE/centermask2)\n+ [Res2Net backbones](https://github.com/Res2Net/Res2Net-detectron2)\n+ [VoVNet backbones](https://github.com/youngwanLEE/vovnet-detectron2)\n+ [FsDet](https://github.com/ucbdrive/few-shot-object-detection), Few-Shot Object Detection.\n+ [Sparse R-CNN](https://github.com/PeizeSun/SparseR-CNN)\n+ [BCNet](https://github.com/lkeab/BCNet), a bilayer decoupling instance segmentation method.\n+ [DD3D](https://github.com/TRI-ML/dd3d), A fully convolutional 3D detector.\n\n"
  },
  {
    "path": "VPS_Module/projects/Rethinking-BatchNorm/README.md",
    "content": "# Rethinking \"Batch\" in BatchNorm\n\nWe provide configs that reproduce detection experiments in the paper [Rethinking \"Batch\" in BatchNorm](https://arxiv.org/abs/2105.07576).\n\nAll configs can be trained with:\n\n```\n../../tools/lazyconfig_train_net.py --config-file configs/X.py --num-gpus 8\n```\n\n## Mask R-CNN\n\n* `mask_rcnn_BNhead.py`, `mask_rcnn_BNhead_batch_stats.py`:\n  Mask R-CNN with BatchNorm in the head. See Table 3 in the paper.\n\n* `mask_rcnn_BNhead_shuffle.py`: Mask R-CNN with cross-GPU shuffling of head inputs.\n  See Figure 9 and Table 6 in the paper.\n\n* `mask_rcnn_SyncBNhead.py`: Mask R-CNN with cross-GPU SyncBatchNorm in the head.\n  It matches Table 6 in the paper.\n\n## RetinaNet\n\n* `retinanet_SyncBNhead.py`: RetinaNet with SyncBN in head, a straightforward implementation\n  which matches row 3 of Table 5.\n\n* `retinanet_SyncBNhead_SharedTraining.py`: RetinaNet with SyncBN in head, normalizing\n  all 5 feature levels together. Match row 1 of Table 5.\n\nThe script `retinanet-eval-domain-specific.py` evaluates a checkpoint after recomputing\ndomain-specific statistics. Running it with\n```\n./retinanet-eval-domain-specific.py checkpoint.pth\n```\non a model produced by the above two configs, can produce results that match row 4 and\nrow 2 of Table 5.\n"
  },
  {
    "path": "VPS_Module/projects/Rethinking-BatchNorm/configs/mask_rcnn_BNhead.py",
    "content": "from detectron2.model_zoo import get_config\n\nmodel = get_config(\"common/models/mask_rcnn_fpn.py\").model\n\nmodel.backbone.bottom_up.freeze_at = 2\n\nmodel.roi_heads.box_head.conv_norm = model.roi_heads.mask_head.conv_norm = \"BN\"\n# 4conv1fc head\nmodel.roi_heads.box_head.conv_dims = [256, 256, 256, 256]\nmodel.roi_heads.box_head.fc_dims = [1024]\n\ndataloader = get_config(\"common/data/coco.py\").dataloader\nlr_multiplier = get_config(\"common/coco_schedule.py\").lr_multiplier_3x\noptimizer = get_config(\"common/optim.py\").SGD\ntrain = get_config(\"common/train.py\").train\n\ntrain.init_checkpoint = \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\ntrain.max_iter = 270000  # 3x for batchsize = 16\n"
  },
  {
    "path": "VPS_Module/projects/Rethinking-BatchNorm/configs/mask_rcnn_BNhead_batch_stats.py",
    "content": "from torch.nn import BatchNorm2d\nfrom torch.nn import functional as F\n\n\nclass BatchNormBatchStat(BatchNorm2d):\n    \"\"\"\n    BN that uses batch stat in inference\n    \"\"\"\n\n    def forward(self, input):\n        if self.training:\n            return super().forward(input)\n        return F.batch_norm(input, None, None, self.weight, self.bias, True, 1.0, self.eps)\n\n\n# After training with the base config, it's sufficient to load its model with\n# this config only for inference -- because the training-time behavior is identical.\nfrom .mask_rcnn_BNhead import model, dataloader, lr_multiplier, optimizer, train\n\nmodel.roi_heads.box_head.conv_norm = model.roi_heads.mask_head.conv_norm = BatchNormBatchStat\n"
  },
  {
    "path": "VPS_Module/projects/Rethinking-BatchNorm/configs/mask_rcnn_BNhead_shuffle.py",
    "content": "import math\nimport torch\nimport torch.distributed as dist\n\nfrom detectron2.modeling.roi_heads import FastRCNNConvFCHead, MaskRCNNConvUpsampleHead\nfrom detectron2.utils import comm\nfrom fvcore.nn.distributed import differentiable_all_gather\n\n\ndef concat_all_gather(input):\n    bs_int = input.shape[0]\n    size_list = comm.all_gather(bs_int)\n    max_size = max(size_list)\n    max_shape = (max_size,) + input.shape[1:]\n\n    padded_input = input.new_zeros(max_shape)\n    padded_input[:bs_int] = input\n    all_inputs = differentiable_all_gather(padded_input)\n    inputs = [x[:sz] for sz, x in zip(size_list, all_inputs)]\n    return inputs, size_list\n\n\ndef batch_shuffle(x):\n    # gather from all gpus\n    batch_size_this = x.shape[0]\n    all_xs, batch_size_all = concat_all_gather(x)\n    all_xs_concat = torch.cat(all_xs, dim=0)\n    total_bs = sum(batch_size_all)\n\n    rank = dist.get_rank()\n    assert batch_size_all[rank] == batch_size_this\n\n    idx_range = (sum(batch_size_all[:rank]), sum(batch_size_all[: rank + 1]))\n\n    # random shuffle index\n    idx_shuffle = torch.randperm(total_bs, device=x.device)\n    # broadcast to all gpus\n    dist.broadcast(idx_shuffle, src=0)\n\n    # index for restoring\n    idx_unshuffle = torch.argsort(idx_shuffle)\n\n    # shuffled index for this gpu\n    splits = torch.split(idx_shuffle, math.ceil(total_bs / dist.get_world_size()))\n    if len(splits) > rank:\n        idx_this = splits[rank]\n    else:\n        idx_this = idx_shuffle.new_zeros([0])\n    return all_xs_concat[idx_this], idx_unshuffle[idx_range[0] : idx_range[1]]\n\n\ndef batch_unshuffle(x, idx_unshuffle):\n    all_x, _ = concat_all_gather(x)\n    x_gather = torch.cat(all_x, dim=0)\n    return x_gather[idx_unshuffle]\n\n\ndef wrap_shuffle(module_type, method):\n    def new_method(self, x):\n        if self.training:\n            x, idx = batch_shuffle(x)\n        x = getattr(module_type, method)(self, x)\n        if self.training:\n            x = batch_unshuffle(x, idx)\n        return x\n\n    return type(module_type.__name__ + \"WithShuffle\", (module_type,), {method: new_method})\n\n\nfrom .mask_rcnn_BNhead import model, dataloader, lr_multiplier, optimizer, train\n\n\nmodel.roi_heads.box_head._target_ = wrap_shuffle(FastRCNNConvFCHead, \"forward\")\nmodel.roi_heads.mask_head._target_ = wrap_shuffle(MaskRCNNConvUpsampleHead, \"layers\")\n"
  },
  {
    "path": "VPS_Module/projects/Rethinking-BatchNorm/configs/mask_rcnn_SyncBNhead.py",
    "content": "from .mask_rcnn_BNhead import model, dataloader, lr_multiplier, optimizer, train\n\nmodel.roi_heads.box_head.conv_norm = model.roi_heads.mask_head.conv_norm = \"SyncBN\"\n"
  },
  {
    "path": "VPS_Module/projects/Rethinking-BatchNorm/configs/retinanet_SyncBNhead.py",
    "content": "from detectron2.model_zoo import get_config\nfrom torch import nn\n\nmodel = get_config(\"common/models/retinanet.py\").model\nmodel.backbone.bottom_up.freeze_at = 2\n\n# The head will overwrite string \"SyncBN\" to use domain-specific BN, so we\n# provide a class here to use shared BN in training.\nmodel.head.norm = nn.SyncBatchNorm2d\n\ndataloader = get_config(\"common/data/coco.py\").dataloader\nlr_multiplier = get_config(\"common/coco_schedule.py\").lr_multiplier_3x\noptimizer = get_config(\"common/optim.py\").SGD\ntrain = get_config(\"common/train.py\").train\n\noptimizer.lr = 0.01\n\ntrain.init_checkpoint = \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\ntrain.max_iter = 270000  # 3x for batchsize = 16\n"
  },
  {
    "path": "VPS_Module/projects/Rethinking-BatchNorm/configs/retinanet_SyncBNhead_SharedTraining.py",
    "content": "from typing import List\nimport torch\nfrom torch import Tensor, nn\n\nfrom detectron2.modeling.meta_arch.retinanet import RetinaNetHead\n\n\ndef apply_sequential(inputs, modules):\n    for mod in modules:\n        if isinstance(mod, (nn.BatchNorm2d, nn.SyncBatchNorm)):\n            # for BN layer, normalize all inputs together\n            shapes = [i.shape for i in inputs]\n            spatial_sizes = [s[2] * s[3] for s in shapes]\n            x = [i.flatten(2) for i in inputs]\n            x = torch.cat(x, dim=2).unsqueeze(3)\n            x = mod(x).split(spatial_sizes, dim=2)\n            inputs = [i.view(s) for s, i in zip(shapes, x)]\n        else:\n            inputs = [mod(i) for i in inputs]\n    return inputs\n\n\nclass RetinaNetHead_SharedTrainingBN(RetinaNetHead):\n    def forward(self, features: List[Tensor]):\n        logits = apply_sequential(features, list(self.cls_subnet) + [self.cls_score])\n        bbox_reg = apply_sequential(features, list(self.bbox_subnet) + [self.bbox_pred])\n        return logits, bbox_reg\n\n\nfrom .retinanet_SyncBNhead import model, dataloader, lr_multiplier, optimizer, train\n\nmodel.head._target_ = RetinaNetHead_SharedTrainingBN\n"
  },
  {
    "path": "VPS_Module/projects/Rethinking-BatchNorm/retinanet-eval-domain-specific.py",
    "content": "#!/usr/bin/env python\n# Copyright (c) Facebook, Inc. and its affiliates.\nimport sys\nimport torch\nfrom fvcore.nn.precise_bn import update_bn_stats\n\nfrom detectron2.checkpoint import DetectionCheckpointer\nfrom detectron2.config import LazyConfig, instantiate\nfrom detectron2.evaluation import inference_on_dataset\nfrom detectron2.layers import CycleBatchNormList\nfrom detectron2.utils.events import EventStorage\nfrom detectron2.utils.logger import setup_logger\n\nlogger = setup_logger()\nsetup_logger(name=\"fvcore\")\n\n\nif __name__ == \"__main__\":\n    checkpoint = sys.argv[1]\n    cfg = LazyConfig.load_rel(\"./configs/retinanet_SyncBNhead.py\")\n    model = cfg.model\n    model.head.norm = lambda c: CycleBatchNormList(len(model.head_in_features), num_features=c)\n    model = instantiate(model)\n    model.cuda()\n    DetectionCheckpointer(model).load(checkpoint)\n\n    cfg.dataloader.train.total_batch_size = 8\n    logger.info(\"Running PreciseBN ...\")\n    with EventStorage(), torch.no_grad():\n        update_bn_stats(model, instantiate(cfg.dataloader.train), 500)\n\n    logger.info(\"Running evaluation ...\")\n    inference_on_dataset(\n        model, instantiate(cfg.dataloader.test), instantiate(cfg.dataloader.evaluator)\n    )\n"
  },
  {
    "path": "VPS_Module/projects/TensorMask/README.md",
    "content": "\n# TensorMask in Detectron2\n**A Foundation for Dense Object Segmentation**\n\nXinlei Chen, Ross Girshick, Kaiming He, Piotr Dollár\n\n[[`arXiv`](https://arxiv.org/abs/1903.12174)] [[`BibTeX`](#CitingTensorMask)]\n\n<div align=\"center\">\n  <img src=\"http://xinleic.xyz/images/tmask.png\" width=\"700px\" />\n</div>\n\nIn this repository, we release code for TensorMask in Detectron2.\nTensorMask is a dense sliding-window instance segmentation framework that, for the first time, achieves results close to the well-developed Mask R-CNN framework -- both qualitatively and quantitatively. It establishes a conceptually complementary direction for object instance segmentation research.\n\n## Installation\nFirst install Detectron2 following the [documentation](https://detectron2.readthedocs.io/tutorials/install.html) and\n[setup the dataset](../../datasets). Then compile the TensorMask-specific op (`swap_align2nat`):\n```bash\npip install -e /path/to/detectron2/projects/TensorMask\n```\n\n## Training\n\nTo train a model, run:\n```bash\npython /path/to/detectron2/projects/TensorMask/train_net.py --config-file <config.yaml>\n```\n\nFor example, to launch TensorMask BiPyramid training (1x schedule) with ResNet-50 backbone on 8 GPUs,\none should execute:\n```bash\npython /path/to/detectron2/projects/TensorMask/train_net.py --config-file configs/tensormask_R_50_FPN_1x.yaml --num-gpus 8\n```\n\n## Evaluation\n\nModel evaluation can be done similarly (6x schedule with scale augmentation):\n```bash\npython /path/to/detectron2/projects/TensorMask/train_net.py --config-file configs/tensormask_R_50_FPN_6x.yaml --eval-only MODEL.WEIGHTS /path/to/model_checkpoint\n```\n\n# Pretrained Models\n\n| Backbone | lr sched | AP box | AP mask | download                                                                                                                                    |\n| -------- | -------- | --     | ---  | --------                                                                                                                                    |\n| R50      | 1x       | 37.6   | 32.4 | <a href=\"https://dl.fbaipublicfiles.com/detectron2/TensorMask/tensormask_R_50_FPN_1x/152549419/model_final_8f325c.pkl\">model</a>&nbsp;\\| &nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/TensorMask/tensormask_R_50_FPN_1x/152549419/metrics.json\">metrics</a> |\n| R50      | 6x       | 41.4   | 35.8 | <a href=\"https://dl.fbaipublicfiles.com/detectron2/TensorMask/tensormask_R_50_FPN_6x/153538791/model_final_e8df31.pkl\">model</a>&nbsp;\\| &nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/TensorMask/tensormask_R_50_FPN_6x/153538791/metrics.json\">metrics</a> |\n\n\n## <a name=\"CitingTensorMask\"></a>Citing TensorMask\n\nIf you use TensorMask, please use the following BibTeX entry.\n\n```\n@InProceedings{chen2019tensormask,\n  title={Tensormask: A Foundation for Dense Object Segmentation},\n  author={Chen, Xinlei and Girshick, Ross and He, Kaiming and Doll{\\'a}r, Piotr},\n  journal={The International Conference on Computer Vision (ICCV)},\n  year={2019}\n}\n```\n\n"
  },
  {
    "path": "VPS_Module/projects/TensorMask/configs/Base-TensorMask.yaml",
    "content": "MODEL:\n  META_ARCHITECTURE: \"TensorMask\"\n  MASK_ON: True\n  BACKBONE:\n    NAME: \"build_retinanet_resnet_fpn_backbone\"\n  RESNETS:\n    OUT_FEATURES: [\"res2\", \"res3\", \"res4\", \"res5\"]\n  ANCHOR_GENERATOR:\n    SIZES: [[44, 60], [88, 120], [176, 240], [352, 480], [704, 960], [1408, 1920]]\n    ASPECT_RATIOS: [[1.0]]\n  FPN:\n    IN_FEATURES: [\"res2\", \"res3\", \"res4\", \"res5\"]\n    FUSE_TYPE: \"avg\"\n  TENSOR_MASK:\n    ALIGNED_ON: True\n    BIPYRAMID_ON: True\nDATASETS:\n  TRAIN: (\"coco_2017_train\",)\n  TEST: (\"coco_2017_val\",)\nSOLVER:\n  IMS_PER_BATCH: 16\n  BASE_LR: 0.02\n  STEPS: (60000, 80000)\n  MAX_ITER: 90000\nVERSION: 2\n"
  },
  {
    "path": "VPS_Module/projects/TensorMask/configs/tensormask_R_50_FPN_1x.yaml",
    "content": "_BASE_: \"Base-TensorMask.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\n"
  },
  {
    "path": "VPS_Module/projects/TensorMask/configs/tensormask_R_50_FPN_6x.yaml",
    "content": "_BASE_: \"Base-TensorMask.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  RESNETS:\n    DEPTH: 50\nSOLVER:\n  STEPS: (480000, 520000)\n  MAX_ITER: 540000\nINPUT:\n  MIN_SIZE_TRAIN_SAMPLING: \"range\"\n  MIN_SIZE_TRAIN: (640, 800)\n"
  },
  {
    "path": "VPS_Module/projects/TensorMask/setup.py",
    "content": "#!/usr/bin/env python\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport glob\nimport os\nfrom setuptools import find_packages, setup\nimport torch\nfrom torch.utils.cpp_extension import CUDA_HOME, CppExtension, CUDAExtension\n\n\ndef get_extensions():\n    this_dir = os.path.dirname(os.path.abspath(__file__))\n    extensions_dir = os.path.join(this_dir, \"tensormask\", \"layers\", \"csrc\")\n\n    main_source = os.path.join(extensions_dir, \"vision.cpp\")\n    sources = glob.glob(os.path.join(extensions_dir, \"**\", \"*.cpp\"))\n    source_cuda = glob.glob(os.path.join(extensions_dir, \"**\", \"*.cu\")) + glob.glob(\n        os.path.join(extensions_dir, \"*.cu\")\n    )\n\n    sources = [main_source] + sources\n\n    extension = CppExtension\n\n    extra_compile_args = {\"cxx\": []}\n    define_macros = []\n\n    if (torch.cuda.is_available() and CUDA_HOME is not None) or os.getenv(\"FORCE_CUDA\", \"0\") == \"1\":\n        extension = CUDAExtension\n        sources += source_cuda\n        define_macros += [(\"WITH_CUDA\", None)]\n        extra_compile_args[\"nvcc\"] = [\n            \"-DCUDA_HAS_FP16=1\",\n            \"-D__CUDA_NO_HALF_OPERATORS__\",\n            \"-D__CUDA_NO_HALF_CONVERSIONS__\",\n            \"-D__CUDA_NO_HALF2_OPERATORS__\",\n        ]\n\n        # It's better if pytorch can do this by default ..\n        CC = os.environ.get(\"CC\", None)\n        if CC is not None:\n            extra_compile_args[\"nvcc\"].append(\"-ccbin={}\".format(CC))\n\n    sources = [os.path.join(extensions_dir, s) for s in sources]\n\n    include_dirs = [extensions_dir]\n\n    ext_modules = [\n        extension(\n            \"tensormask._C\",\n            sources,\n            include_dirs=include_dirs,\n            define_macros=define_macros,\n            extra_compile_args=extra_compile_args,\n        )\n    ]\n\n    return ext_modules\n\n\nsetup(\n    name=\"tensormask\",\n    version=\"0.1\",\n    author=\"FAIR\",\n    packages=find_packages(exclude=(\"configs\", \"tests\")),\n    python_requires=\">=3.6\",\n    ext_modules=get_extensions(),\n    cmdclass={\"build_ext\": torch.utils.cpp_extension.BuildExtension},\n)\n"
  },
  {
    "path": "VPS_Module/projects/TensorMask/tensormask/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom .config import add_tensormask_config\nfrom .arch import TensorMask\n"
  },
  {
    "path": "VPS_Module/projects/TensorMask/tensormask/arch.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport copy\nimport math\nfrom typing import List\nimport torch\nimport torch.nn.functional as F\nfrom fvcore.nn import sigmoid_focal_loss_star_jit, smooth_l1_loss\nfrom torch import nn\n\nfrom detectron2.layers import ShapeSpec, batched_nms, cat, paste_masks_in_image\nfrom detectron2.modeling.anchor_generator import DefaultAnchorGenerator\nfrom detectron2.modeling.backbone import build_backbone\nfrom detectron2.modeling.box_regression import Box2BoxTransform\nfrom detectron2.modeling.meta_arch.build import META_ARCH_REGISTRY\nfrom detectron2.modeling.meta_arch.retinanet import permute_to_N_HWA_K\nfrom detectron2.structures import Boxes, ImageList, Instances\n\nfrom tensormask.layers import SwapAlign2Nat\n\n__all__ = [\"TensorMask\"]\n\n\ndef permute_all_cls_and_box_to_N_HWA_K_and_concat(pred_logits, pred_anchor_deltas, num_classes=80):\n    \"\"\"\n    Rearrange the tensor layout from the network output, i.e.:\n    list[Tensor]: #lvl tensors of shape (N, A x K, Hi, Wi)\n    to per-image predictions, i.e.:\n    Tensor: of shape (N x sum(Hi x Wi x A), K)\n    \"\"\"\n    # for each feature level, permute the outputs to make them be in the\n    # same format as the labels.\n    pred_logits_flattened = [permute_to_N_HWA_K(x, num_classes) for x in pred_logits]\n    pred_anchor_deltas_flattened = [permute_to_N_HWA_K(x, 4) for x in pred_anchor_deltas]\n    # concatenate on the first dimension (representing the feature levels), to\n    # take into account the way the labels were generated (with all feature maps\n    # being concatenated as well)\n    pred_logits = cat(pred_logits_flattened, dim=1).view(-1, num_classes)\n    pred_anchor_deltas = cat(pred_anchor_deltas_flattened, dim=1).view(-1, 4)\n    return pred_logits, pred_anchor_deltas\n\n\ndef _assignment_rule(\n    gt_boxes,\n    anchor_boxes,\n    unit_lengths,\n    min_anchor_size,\n    scale_thresh=2.0,\n    spatial_thresh=1.0,\n    uniqueness_on=True,\n):\n    \"\"\"\n    Given two lists of boxes of N ground truth boxes and M anchor boxes,\n    compute the assignment between the two, following the assignment rules in\n    https://arxiv.org/abs/1903.12174.\n    The box order must be (xmin, ymin, xmax, ymax), so please make sure to convert\n    to BoxMode.XYXY_ABS before calling this function.\n\n    Args:\n        gt_boxes, anchor_boxes (Boxes): two Boxes. Contains N & M boxes/anchors, respectively.\n        unit_lengths (Tensor): Contains the unit lengths of M anchor boxes.\n        min_anchor_size (float): Minimum size of the anchor, in pixels\n        scale_thresh (float): The `scale` threshold: the maximum size of the anchor\n                              should not be greater than scale_thresh x max(h, w) of\n                              the ground truth box.\n        spatial_thresh (float): The `spatial` threshold: the l2 distance between the\n                              center of the anchor and the ground truth box should not\n                              be greater than spatial_thresh x u where u is the unit length.\n\n    Returns:\n        matches (Tensor[int64]): a vector of length M, where matches[i] is a matched\n                ground-truth index in [0, N)\n        match_labels (Tensor[int8]): a vector of length M, where pred_labels[i] indicates\n            whether a prediction is a true or false positive or ignored\n    \"\"\"\n    gt_boxes, anchor_boxes = gt_boxes.tensor, anchor_boxes.tensor\n    N = gt_boxes.shape[0]\n    M = anchor_boxes.shape[0]\n    if N == 0 or M == 0:\n        return (\n            gt_boxes.new_full((N,), 0, dtype=torch.int64),\n            gt_boxes.new_full((N,), -1, dtype=torch.int8),\n        )\n\n    # Containment rule\n    lt = torch.min(gt_boxes[:, None, :2], anchor_boxes[:, :2])  # [N,M,2]\n    rb = torch.max(gt_boxes[:, None, 2:], anchor_boxes[:, 2:])  # [N,M,2]\n    union = cat([lt, rb], dim=2)  # [N,M,4]\n\n    dummy_gt_boxes = torch.zeros_like(gt_boxes)\n    anchor = dummy_gt_boxes[:, None, :] + anchor_boxes[:, :]  # [N,M,4]\n\n    contain_matrix = torch.all(union == anchor, dim=2)  # [N,M]\n\n    # Centrality rule, scale\n    gt_size_lower = torch.max(gt_boxes[:, 2:] - gt_boxes[:, :2], dim=1)[0]  # [N]\n    gt_size_upper = gt_size_lower * scale_thresh  # [N]\n    # Fall back for small objects\n    gt_size_upper[gt_size_upper < min_anchor_size] = min_anchor_size\n    # Due to sampling of locations, the anchor sizes are deducted with sampling strides\n    anchor_size = (\n        torch.max(anchor_boxes[:, 2:] - anchor_boxes[:, :2], dim=1)[0] - unit_lengths\n    )  # [M]\n\n    size_diff_upper = gt_size_upper[:, None] - anchor_size  # [N,M]\n    scale_matrix = size_diff_upper >= 0  # [N,M]\n\n    # Centrality rule, spatial\n    gt_center = (gt_boxes[:, 2:] + gt_boxes[:, :2]) / 2  # [N,2]\n    anchor_center = (anchor_boxes[:, 2:] + anchor_boxes[:, :2]) / 2  # [M,2]\n    offset_center = gt_center[:, None, :] - anchor_center[:, :]  # [N,M,2]\n    offset_center /= unit_lengths[:, None]  # [N,M,2]\n    spatial_square = spatial_thresh * spatial_thresh\n    spatial_matrix = torch.sum(offset_center * offset_center, dim=2) <= spatial_square\n\n    assign_matrix = (contain_matrix & scale_matrix & spatial_matrix).int()\n\n    # assign_matrix is N (gt) x M (predicted)\n    # Max over gt elements (dim 0) to find best gt candidate for each prediction\n    matched_vals, matches = assign_matrix.max(dim=0)\n    match_labels = matches.new_full(matches.size(), 1, dtype=torch.int8)\n\n    match_labels[matched_vals == 0] = 0\n    match_labels[matched_vals == 1] = 1\n\n    # find all the elements that match to ground truths multiple times\n    not_unique_idxs = assign_matrix.sum(dim=0) > 1\n    if uniqueness_on:\n        match_labels[not_unique_idxs] = 0\n    else:\n        match_labels[not_unique_idxs] = -1\n\n    return matches, match_labels\n\n\n# TODO make the paste_mask function in d2 core support mask list\ndef _paste_mask_lists_in_image(masks, boxes, image_shape, threshold=0.5):\n    \"\"\"\n    Paste a list of masks that are of various resolutions (e.g., 28 x 28) into an image.\n    The location, height, and width for pasting each mask is determined by their\n    corresponding bounding boxes in boxes.\n\n    Args:\n        masks (list(Tensor)): A list of Tensor of shape (1, Hmask_i, Wmask_i).\n                            Values are in [0, 1]. The list length, Bimg, is the\n                            number of detected object instances in the image.\n        boxes (Boxes): A Boxes of length Bimg. boxes.tensor[i] and masks[i] correspond\n                            to the same object instance.\n        image_shape (tuple): height, width\n        threshold (float): A threshold in [0, 1] for converting the (soft) masks to\n            binary masks.\n\n    Returns:\n        img_masks (Tensor): A tensor of shape (Bimg, Himage, Wimage), where Bimg is the\n        number of detected object instances and Himage, Wimage are the image width\n        and height. img_masks[i] is a binary mask for object instance i.\n    \"\"\"\n    if len(masks) == 0:\n        return torch.empty((0, 1) + image_shape, dtype=torch.uint8)\n\n    # Loop over masks groups. Each group has the same mask prediction size.\n    img_masks = []\n    ind_masks = []\n    mask_sizes = torch.tensor([m.shape[-1] for m in masks])\n    unique_sizes = torch.unique(mask_sizes)\n    for msize in unique_sizes.tolist():\n        cur_ind = torch.where(mask_sizes == msize)[0]\n        ind_masks.append(cur_ind)\n\n        cur_masks = cat([masks[i] for i in cur_ind])\n        cur_boxes = boxes[cur_ind]\n        img_masks.append(paste_masks_in_image(cur_masks, cur_boxes, image_shape, threshold))\n\n    img_masks = cat(img_masks)\n    ind_masks = cat(ind_masks)\n\n    img_masks_out = torch.empty_like(img_masks)\n    img_masks_out[ind_masks, :, :] = img_masks\n\n    return img_masks_out\n\n\ndef _postprocess(results, result_mask_info, output_height, output_width, mask_threshold=0.5):\n    \"\"\"\n    Post-process the output boxes for TensorMask.\n    The input images are often resized when entering an object detector.\n    As a result, we often need the outputs of the detector in a different\n    resolution from its inputs.\n\n    This function will postprocess the raw outputs of TensorMask\n    to produce outputs according to the desired output resolution.\n\n    Args:\n        results (Instances): the raw outputs from the detector.\n            `results.image_size` contains the input image resolution the detector sees.\n            This object might be modified in-place. Note that it does not contain the field\n            `pred_masks`, which is provided by another input `result_masks`.\n        result_mask_info (list[Tensor], Boxes): a pair of two items for mask related results.\n                The first item is a list of #detection tensors, each is the predicted masks.\n                The second item is the anchors corresponding to the predicted masks.\n        output_height, output_width: the desired output resolution.\n\n    Returns:\n        Instances: the postprocessed output from the model, based on the output resolution\n    \"\"\"\n    scale_x, scale_y = (output_width / results.image_size[1], output_height / results.image_size[0])\n    results = Instances((output_height, output_width), **results.get_fields())\n\n    output_boxes = results.pred_boxes\n    output_boxes.tensor[:, 0::2] *= scale_x\n    output_boxes.tensor[:, 1::2] *= scale_y\n    output_boxes.clip(results.image_size)\n\n    inds_nonempty = output_boxes.nonempty()\n    results = results[inds_nonempty]\n    result_masks, result_anchors = result_mask_info\n    if result_masks:\n        result_anchors.tensor[:, 0::2] *= scale_x\n        result_anchors.tensor[:, 1::2] *= scale_y\n        result_masks = [x for (i, x) in zip(inds_nonempty.tolist(), result_masks) if i]\n        results.pred_masks = _paste_mask_lists_in_image(\n            result_masks,\n            result_anchors[inds_nonempty],\n            results.image_size,\n            threshold=mask_threshold,\n        )\n    return results\n\n\nclass TensorMaskAnchorGenerator(DefaultAnchorGenerator):\n    \"\"\"\n    For a set of image sizes and feature maps, computes a set of anchors for TensorMask.\n    It also computes the unit lengths and indexes for each anchor box.\n    \"\"\"\n\n    def grid_anchors_with_unit_lengths_and_indexes(self, grid_sizes):\n        anchors = []\n        unit_lengths = []\n        indexes = []\n        for lvl, (size, stride, base_anchors) in enumerate(\n            zip(grid_sizes, self.strides, self.cell_anchors)\n        ):\n            grid_height, grid_width = size\n            device = base_anchors.device\n            shifts_x = torch.arange(\n                0, grid_width * stride, step=stride, dtype=torch.float32, device=device\n            )\n            shifts_y = torch.arange(\n                0, grid_height * stride, step=stride, dtype=torch.float32, device=device\n            )\n            shift_y, shift_x = torch.meshgrid(shifts_y, shifts_x)\n            shifts = torch.stack((shift_x, shift_y, shift_x, shift_y), dim=2)\n            # Stack anchors in shapes of (HWA, 4)\n            cur_anchor = (shifts[:, :, None, :] + base_anchors.view(1, 1, -1, 4)).view(-1, 4)\n            anchors.append(cur_anchor)\n            unit_lengths.append(\n                torch.full((cur_anchor.shape[0],), stride, dtype=torch.float32, device=device)\n            )\n            # create mask indexes using mesh grid\n            shifts_l = torch.full((1,), lvl, dtype=torch.int64, device=device)\n            shifts_i = torch.zeros((1,), dtype=torch.int64, device=device)\n            shifts_h = torch.arange(0, grid_height, dtype=torch.int64, device=device)\n            shifts_w = torch.arange(0, grid_width, dtype=torch.int64, device=device)\n            shifts_a = torch.arange(0, base_anchors.shape[0], dtype=torch.int64, device=device)\n            grids = torch.meshgrid(shifts_l, shifts_i, shifts_h, shifts_w, shifts_a)\n\n            indexes.append(torch.stack(grids, dim=5).view(-1, 5))\n\n        return anchors, unit_lengths, indexes\n\n    def forward(self, features):\n        \"\"\"\n        Returns:\n            list[list[Boxes]]: a list of #image elements. Each is a list of #feature level Boxes.\n                The Boxes contains anchors of this image on the specific feature level.\n            list[list[Tensor]]: a list of #image elements. Each is a list of #feature level tensors.\n                The tensor contains strides, or unit lengths for the anchors.\n            list[list[Tensor]]: a list of #image elements. Each is a list of #feature level tensors.\n                The Tensor contains indexes for the anchors, with the last dimension meaning\n                (L, N, H, W, A), where L is level, I is image (not set yet), H is height,\n                W is width, and A is anchor.\n        \"\"\"\n        num_images = len(features[0])\n        grid_sizes = [feature_map.shape[-2:] for feature_map in features]\n        anchors_list, lengths_list, indexes_list = self.grid_anchors_with_unit_lengths_and_indexes(\n            grid_sizes\n        )\n\n        # Convert anchors from Tensor to Boxes\n        anchors_per_im = [Boxes(x) for x in anchors_list]\n\n        # TODO it can be simplified to not return duplicated information for\n        # each image, just like detectron2's own AnchorGenerator\n        anchors = [copy.deepcopy(anchors_per_im) for _ in range(num_images)]\n        unit_lengths = [copy.deepcopy(lengths_list) for _ in range(num_images)]\n        indexes = [copy.deepcopy(indexes_list) for _ in range(num_images)]\n\n        return anchors, unit_lengths, indexes\n\n\n@META_ARCH_REGISTRY.register()\nclass TensorMask(nn.Module):\n    \"\"\"\n    TensorMask model. Creates FPN backbone, anchors and a head for classification\n    and box regression. Calculates and applies proper losses to class, box, and\n    masks.\n    \"\"\"\n\n    def __init__(self, cfg):\n        super().__init__()\n\n        # fmt: off\n        self.num_classes              = cfg.MODEL.TENSOR_MASK.NUM_CLASSES\n        self.in_features              = cfg.MODEL.TENSOR_MASK.IN_FEATURES\n        self.anchor_sizes             = cfg.MODEL.ANCHOR_GENERATOR.SIZES\n        self.num_levels               = len(cfg.MODEL.ANCHOR_GENERATOR.SIZES)\n        # Loss parameters:\n        self.focal_loss_alpha         = cfg.MODEL.TENSOR_MASK.FOCAL_LOSS_ALPHA\n        self.focal_loss_gamma         = cfg.MODEL.TENSOR_MASK.FOCAL_LOSS_GAMMA\n        # Inference parameters:\n        self.score_threshold          = cfg.MODEL.TENSOR_MASK.SCORE_THRESH_TEST\n        self.topk_candidates          = cfg.MODEL.TENSOR_MASK.TOPK_CANDIDATES_TEST\n        self.nms_threshold            = cfg.MODEL.TENSOR_MASK.NMS_THRESH_TEST\n        self.detections_im            = cfg.TEST.DETECTIONS_PER_IMAGE\n        # Mask parameters:\n        self.mask_on                  = cfg.MODEL.MASK_ON\n        self.mask_loss_weight         = cfg.MODEL.TENSOR_MASK.MASK_LOSS_WEIGHT\n        self.mask_pos_weight          = torch.tensor(cfg.MODEL.TENSOR_MASK.POSITIVE_WEIGHT,\n                                                     dtype=torch.float32)\n        self.bipyramid_on             = cfg.MODEL.TENSOR_MASK.BIPYRAMID_ON\n        # fmt: on\n\n        # build the backbone\n        self.backbone = build_backbone(cfg)\n\n        backbone_shape = self.backbone.output_shape()\n        feature_shapes = [backbone_shape[f] for f in self.in_features]\n        feature_strides = [x.stride for x in feature_shapes]\n        # build anchors\n        self.anchor_generator = TensorMaskAnchorGenerator(cfg, feature_shapes)\n        self.num_anchors = self.anchor_generator.num_cell_anchors[0]\n        anchors_min_level = cfg.MODEL.ANCHOR_GENERATOR.SIZES[0]\n        self.mask_sizes = [size // feature_strides[0] for size in anchors_min_level]\n        self.min_anchor_size = min(anchors_min_level) - feature_strides[0]\n\n        # head of the TensorMask\n        self.head = TensorMaskHead(\n            cfg, self.num_levels, self.num_anchors, self.mask_sizes, feature_shapes\n        )\n        # box transform\n        self.box2box_transform = Box2BoxTransform(weights=cfg.MODEL.TENSOR_MASK.BBOX_REG_WEIGHTS)\n        self.register_buffer(\"pixel_mean\", torch.tensor(cfg.MODEL.PIXEL_MEAN).view(-1, 1, 1), False)\n        self.register_buffer(\"pixel_std\", torch.tensor(cfg.MODEL.PIXEL_STD).view(-1, 1, 1), False)\n\n    @property\n    def device(self):\n        return self.pixel_mean.device\n\n    def forward(self, batched_inputs):\n        \"\"\"\n        Args:\n            batched_inputs: a list, batched outputs of :class:`DetectionTransform` .\n                Each item in the list contains the inputs for one image.\n            For now, each item in the list is a dict that contains:\n                image: Tensor, image in (C, H, W) format.\n                instances: Instances\n                Other information that's included in the original dicts, such as:\n                    \"height\", \"width\" (int): the output resolution of the model, used in inference.\n                        See :meth:`postprocess` for details.\n         Returns:\n            losses (dict[str: Tensor]): mapping from a named loss to a tensor\n                storing the loss. Used during training only.\n        \"\"\"\n        images = self.preprocess_image(batched_inputs)\n        if \"instances\" in batched_inputs[0]:\n            gt_instances = [x[\"instances\"].to(self.device) for x in batched_inputs]\n        else:\n            gt_instances = None\n\n        features = self.backbone(images.tensor)\n        features = [features[f] for f in self.in_features]\n        # apply the TensorMask head\n        pred_logits, pred_deltas, pred_masks = self.head(features)\n        # generate anchors based on features, is it image specific?\n        anchors, unit_lengths, indexes = self.anchor_generator(features)\n\n        if self.training:\n            # get ground truths for class labels and box targets, it will label each anchor\n            gt_class_info, gt_delta_info, gt_mask_info, num_fg = self.get_ground_truth(\n                anchors, unit_lengths, indexes, gt_instances\n            )\n            # compute the loss\n            return self.losses(\n                gt_class_info,\n                gt_delta_info,\n                gt_mask_info,\n                num_fg,\n                pred_logits,\n                pred_deltas,\n                pred_masks,\n            )\n        else:\n            # do inference to get the output\n            results = self.inference(pred_logits, pred_deltas, pred_masks, anchors, indexes, images)\n            processed_results = []\n            for results_im, input_im, image_size in zip(\n                results, batched_inputs, images.image_sizes\n            ):\n                height = input_im.get(\"height\", image_size[0])\n                width = input_im.get(\"width\", image_size[1])\n                # this is to do post-processing with the image size\n                result_box, result_mask = results_im\n                r = _postprocess(result_box, result_mask, height, width)\n                processed_results.append({\"instances\": r})\n            return processed_results\n\n    def losses(\n        self,\n        gt_class_info,\n        gt_delta_info,\n        gt_mask_info,\n        num_fg,\n        pred_logits,\n        pred_deltas,\n        pred_masks,\n    ):\n        \"\"\"\n        Args:\n            For `gt_class_info`, `gt_delta_info`, `gt_mask_info` and `num_fg` parameters, see\n                :meth:`TensorMask.get_ground_truth`.\n            For `pred_logits`, `pred_deltas` and `pred_masks`, see\n                :meth:`TensorMaskHead.forward`.\n\n        Returns:\n            losses (dict[str: Tensor]): mapping from a named loss to a scalar tensor\n                storing the loss. Used during training only. The potential dict keys are:\n                \"loss_cls\", \"loss_box_reg\" and \"loss_mask\".\n        \"\"\"\n        gt_classes_target, gt_valid_inds = gt_class_info\n        gt_deltas, gt_fg_inds = gt_delta_info\n        gt_masks, gt_mask_inds = gt_mask_info\n        loss_normalizer = torch.tensor(max(1, num_fg), dtype=torch.float32, device=self.device)\n\n        # classification and regression\n        pred_logits, pred_deltas = permute_all_cls_and_box_to_N_HWA_K_and_concat(\n            pred_logits, pred_deltas, self.num_classes\n        )\n        loss_cls = (\n            sigmoid_focal_loss_star_jit(\n                pred_logits[gt_valid_inds],\n                gt_classes_target[gt_valid_inds],\n                alpha=self.focal_loss_alpha,\n                gamma=self.focal_loss_gamma,\n                reduction=\"sum\",\n            )\n            / loss_normalizer\n        )\n\n        if num_fg == 0:\n            loss_box_reg = pred_deltas.sum() * 0\n        else:\n            loss_box_reg = (\n                smooth_l1_loss(pred_deltas[gt_fg_inds], gt_deltas, beta=0.0, reduction=\"sum\")\n                / loss_normalizer\n            )\n        losses = {\"loss_cls\": loss_cls, \"loss_box_reg\": loss_box_reg}\n\n        # mask prediction\n        if self.mask_on:\n            loss_mask = 0\n            for lvl in range(self.num_levels):\n                cur_level_factor = 2 ** lvl if self.bipyramid_on else 1\n                for anc in range(self.num_anchors):\n                    cur_gt_mask_inds = gt_mask_inds[lvl][anc]\n                    if cur_gt_mask_inds is None:\n                        loss_mask += pred_masks[lvl][anc][0, 0, 0, 0] * 0\n                    else:\n                        cur_mask_size = self.mask_sizes[anc] * cur_level_factor\n                        # TODO maybe there are numerical issues when mask sizes are large\n                        cur_size_divider = torch.tensor(\n                            self.mask_loss_weight / (cur_mask_size ** 2),\n                            dtype=torch.float32,\n                            device=self.device,\n                        )\n\n                        cur_pred_masks = pred_masks[lvl][anc][\n                            cur_gt_mask_inds[:, 0],  # N\n                            :,  # V x U\n                            cur_gt_mask_inds[:, 1],  # H\n                            cur_gt_mask_inds[:, 2],  # W\n                        ]\n\n                        loss_mask += F.binary_cross_entropy_with_logits(\n                            cur_pred_masks.view(-1, cur_mask_size, cur_mask_size),  # V, U\n                            gt_masks[lvl][anc].to(dtype=torch.float32),\n                            reduction=\"sum\",\n                            weight=cur_size_divider,\n                            pos_weight=self.mask_pos_weight,\n                        )\n            losses[\"loss_mask\"] = loss_mask / loss_normalizer\n        return losses\n\n    @torch.no_grad()\n    def get_ground_truth(self, anchors, unit_lengths, indexes, targets):\n        \"\"\"\n        Args:\n            anchors (list[list[Boxes]]): a list of N=#image elements. Each is a\n                list of #feature level Boxes. The Boxes contains anchors of\n                this image on the specific feature level.\n            unit_lengths (list[list[Tensor]]): a list of N=#image elements. Each is a\n                list of #feature level Tensor. The tensor contains unit lengths for anchors of\n                this image on the specific feature level.\n            indexes (list[list[Tensor]]): a list of N=#image elements. Each is a\n                list of #feature level Tensor. The tensor contains the 5D index of\n                each anchor, the second dimension means (L, N, H, W, A), where L\n                is level, I is image, H is height, W is width, and A is anchor.\n            targets (list[Instances]): a list of N `Instances`s. The i-th\n                `Instances` contains the ground-truth per-instance annotations\n                for the i-th input image.  Specify `targets` during training only.\n\n        Returns:\n            gt_class_info (Tensor, Tensor): A pair of two tensors for classification.\n                The first one is an integer tensor of shape (R, #classes) storing ground-truth\n                labels for each anchor. R is the total number of anchors in the batch.\n                The second one is an integer tensor of shape (R,), to indicate which\n                anchors are valid for loss computation, which anchors are not.\n            gt_delta_info (Tensor, Tensor): A pair of two tensors for boxes.\n                The first one, of shape (F, 4). F=#foreground anchors.\n                The last dimension represents ground-truth box2box transform\n                targets (dx, dy, dw, dh) that map each anchor to its matched ground-truth box.\n                Only foreground anchors have values in this tensor. Could be `None` if F=0.\n                The second one, of shape (R,), is an integer tensor indicating which anchors\n                are foreground ones used for box regression. Could be `None` if F=0.\n            gt_mask_info (list[list[Tensor]], list[list[Tensor]]): A pair of two lists for masks.\n                The first one is a list of P=#feature level elements. Each is a\n                list of A=#anchor tensors. Each tensor contains the ground truth\n                masks of the same size and for the same feature level. Could be `None`.\n                The second one is a list of P=#feature level elements. Each is a\n                list of A=#anchor tensors. Each tensor contains the location of the ground truth\n                masks of the same size and for the same feature level. The second dimension means\n                (N, H, W), where N is image, H is height, and W is width. Could be `None`.\n            num_fg (int): F=#foreground anchors, used later for loss normalization.\n        \"\"\"\n        gt_classes = []\n        gt_deltas = []\n        gt_masks = [[[] for _ in range(self.num_anchors)] for _ in range(self.num_levels)]\n        gt_mask_inds = [[[] for _ in range(self.num_anchors)] for _ in range(self.num_levels)]\n\n        anchors = [Boxes.cat(anchors_i) for anchors_i in anchors]\n        unit_lengths = [cat(unit_lengths_i) for unit_lengths_i in unit_lengths]\n        indexes = [cat(indexes_i) for indexes_i in indexes]\n\n        num_fg = 0\n        for i, (anchors_im, unit_lengths_im, indexes_im, targets_im) in enumerate(\n            zip(anchors, unit_lengths, indexes, targets)\n        ):\n            # Initialize all\n            gt_classes_i = torch.full_like(\n                unit_lengths_im, self.num_classes, dtype=torch.int64, device=self.device\n            )\n            # Ground truth classes\n            has_gt = len(targets_im) > 0\n            if has_gt:\n                # Compute the pairwise matrix\n                gt_matched_inds, anchor_labels = _assignment_rule(\n                    targets_im.gt_boxes, anchors_im, unit_lengths_im, self.min_anchor_size\n                )\n                # Find the foreground instances\n                fg_inds = anchor_labels == 1\n                fg_anchors = anchors_im[fg_inds]\n                num_fg += len(fg_anchors)\n                # Find the ground truths for foreground instances\n                gt_fg_matched_inds = gt_matched_inds[fg_inds]\n                # Assign labels for foreground instances\n                gt_classes_i[fg_inds] = targets_im.gt_classes[gt_fg_matched_inds]\n                # Anchors with label -1 are ignored, others are left as negative\n                gt_classes_i[anchor_labels == -1] = -1\n\n                # Boxes\n                # Ground truth box regression, only for foregrounds\n                matched_gt_boxes = targets_im[gt_fg_matched_inds].gt_boxes\n                # Compute box regression offsets for foregrounds only\n                gt_deltas_i = self.box2box_transform.get_deltas(\n                    fg_anchors.tensor, matched_gt_boxes.tensor\n                )\n                gt_deltas.append(gt_deltas_i)\n\n                # Masks\n                if self.mask_on:\n                    # Compute masks for each level and each anchor\n                    matched_indexes = indexes_im[fg_inds, :]\n                    for lvl in range(self.num_levels):\n                        ids_lvl = matched_indexes[:, 0] == lvl\n                        if torch.any(ids_lvl):\n                            cur_level_factor = 2 ** lvl if self.bipyramid_on else 1\n                            for anc in range(self.num_anchors):\n                                ids_lvl_anchor = ids_lvl & (matched_indexes[:, 4] == anc)\n                                if torch.any(ids_lvl_anchor):\n                                    gt_masks[lvl][anc].append(\n                                        targets_im[\n                                            gt_fg_matched_inds[ids_lvl_anchor]\n                                        ].gt_masks.crop_and_resize(\n                                            fg_anchors[ids_lvl_anchor].tensor,\n                                            self.mask_sizes[anc] * cur_level_factor,\n                                        )\n                                    )\n                                    # Select (N, H, W) dimensions\n                                    gt_mask_inds_lvl_anc = matched_indexes[ids_lvl_anchor, 1:4]\n                                    # Set the image index to the current image\n                                    gt_mask_inds_lvl_anc[:, 0] = i\n                                    gt_mask_inds[lvl][anc].append(gt_mask_inds_lvl_anc)\n            gt_classes.append(gt_classes_i)\n\n        # Classes and boxes\n        gt_classes = cat(gt_classes)\n        gt_valid_inds = gt_classes >= 0\n        gt_fg_inds = gt_valid_inds & (gt_classes < self.num_classes)\n        gt_classes_target = torch.zeros(\n            (gt_classes.shape[0], self.num_classes), dtype=torch.float32, device=self.device\n        )\n        gt_classes_target[gt_fg_inds, gt_classes[gt_fg_inds]] = 1\n        gt_deltas = cat(gt_deltas) if gt_deltas else None\n\n        # Masks\n        gt_masks = [[cat(mla) if mla else None for mla in ml] for ml in gt_masks]\n        gt_mask_inds = [[cat(ila) if ila else None for ila in il] for il in gt_mask_inds]\n        return (\n            (gt_classes_target, gt_valid_inds),\n            (gt_deltas, gt_fg_inds),\n            (gt_masks, gt_mask_inds),\n            num_fg,\n        )\n\n    def inference(self, pred_logits, pred_deltas, pred_masks, anchors, indexes, images):\n        \"\"\"\n        Arguments:\n            pred_logits, pred_deltas, pred_masks: Same as the output of:\n                meth:`TensorMaskHead.forward`\n            anchors, indexes: Same as the input of meth:`TensorMask.get_ground_truth`\n            images (ImageList): the input images\n\n        Returns:\n            results (List[Instances]): a list of #images elements.\n        \"\"\"\n        assert len(anchors) == len(images)\n        results = []\n\n        pred_logits = [permute_to_N_HWA_K(x, self.num_classes) for x in pred_logits]\n        pred_deltas = [permute_to_N_HWA_K(x, 4) for x in pred_deltas]\n\n        pred_logits = cat(pred_logits, dim=1)\n        pred_deltas = cat(pred_deltas, dim=1)\n\n        for img_idx, (anchors_im, indexes_im) in enumerate(zip(anchors, indexes)):\n            # Get the size of the current image\n            image_size = images.image_sizes[img_idx]\n\n            logits_im = pred_logits[img_idx]\n            deltas_im = pred_deltas[img_idx]\n\n            if self.mask_on:\n                masks_im = [[mla[img_idx] for mla in ml] for ml in pred_masks]\n            else:\n                masks_im = [None] * self.num_levels\n            results_im = self.inference_single_image(\n                logits_im,\n                deltas_im,\n                masks_im,\n                Boxes.cat(anchors_im),\n                cat(indexes_im),\n                tuple(image_size),\n            )\n            results.append(results_im)\n        return results\n\n    def inference_single_image(\n        self, pred_logits, pred_deltas, pred_masks, anchors, indexes, image_size\n    ):\n        \"\"\"\n        Single-image inference. Return bounding-box detection results by thresholding\n        on scores and applying non-maximum suppression (NMS).\n\n        Arguments:\n            pred_logits (list[Tensor]): list of #feature levels. Each entry contains\n                tensor of size (AxHxW, K)\n            pred_deltas (list[Tensor]): Same shape as 'pred_logits' except that K becomes 4.\n            pred_masks (list[list[Tensor]]): List of #feature levels, each is a list of #anchors.\n                Each entry contains tensor of size (M_i*M_i, H, W). `None` if mask_on=False.\n            anchors (list[Boxes]): list of #feature levels. Each entry contains\n                a Boxes object, which contains all the anchors for that\n                image in that feature level.\n            image_size (tuple(H, W)): a tuple of the image height and width.\n\n        Returns:\n            Same as `inference`, but for only one image.\n        \"\"\"\n        pred_logits = pred_logits.flatten().sigmoid_()\n        # We get top locations across all levels to accelerate the inference speed,\n        # which does not seem to affect the accuracy.\n        # First select values above the threshold\n        logits_top_idxs = torch.where(pred_logits > self.score_threshold)[0]\n        # Then get the top values\n        num_topk = min(self.topk_candidates, logits_top_idxs.shape[0])\n        pred_prob, topk_idxs = pred_logits[logits_top_idxs].sort(descending=True)\n        # Keep top k scoring values\n        pred_prob = pred_prob[:num_topk]\n        # Keep top k values\n        top_idxs = logits_top_idxs[topk_idxs[:num_topk]]\n\n        # class index\n        cls_idxs = top_idxs % self.num_classes\n        # HWA index\n        top_idxs //= self.num_classes\n        # predict boxes\n        pred_boxes = self.box2box_transform.apply_deltas(\n            pred_deltas[top_idxs], anchors[top_idxs].tensor\n        )\n        # apply nms\n        keep = batched_nms(pred_boxes, pred_prob, cls_idxs, self.nms_threshold)\n        # pick the top ones\n        keep = keep[: self.detections_im]\n\n        results = Instances(image_size)\n        results.pred_boxes = Boxes(pred_boxes[keep])\n        results.scores = pred_prob[keep]\n        results.pred_classes = cls_idxs[keep]\n\n        # deal with masks\n        result_masks, result_anchors = [], None\n        if self.mask_on:\n            # index and anchors, useful for masks\n            top_indexes = indexes[top_idxs]\n            top_anchors = anchors[top_idxs]\n            result_indexes = top_indexes[keep]\n            result_anchors = top_anchors[keep]\n            # Get masks and do sigmoid\n            for lvl, _, h, w, anc in result_indexes.tolist():\n                cur_size = self.mask_sizes[anc] * (2 ** lvl if self.bipyramid_on else 1)\n                result_masks.append(\n                    torch.sigmoid(pred_masks[lvl][anc][:, h, w].view(1, cur_size, cur_size))\n                )\n\n        return results, (result_masks, result_anchors)\n\n    def preprocess_image(self, batched_inputs):\n        \"\"\"\n        Normalize, pad and batch the input images.\n        \"\"\"\n        images = [x[\"image\"].to(self.device) for x in batched_inputs]\n        images = [(x - self.pixel_mean) / self.pixel_std for x in images]\n        images = ImageList.from_tensors(images, self.backbone.size_divisibility)\n        return images\n\n\nclass TensorMaskHead(nn.Module):\n    def __init__(self, cfg, num_levels, num_anchors, mask_sizes, input_shape: List[ShapeSpec]):\n        \"\"\"\n        TensorMask head.\n        \"\"\"\n        super().__init__()\n        # fmt: off\n        self.in_features        = cfg.MODEL.TENSOR_MASK.IN_FEATURES\n        in_channels             = input_shape[0].channels\n        num_classes             = cfg.MODEL.TENSOR_MASK.NUM_CLASSES\n        cls_channels            = cfg.MODEL.TENSOR_MASK.CLS_CHANNELS\n        num_convs               = cfg.MODEL.TENSOR_MASK.NUM_CONVS\n        # box parameters\n        bbox_channels           = cfg.MODEL.TENSOR_MASK.BBOX_CHANNELS\n        # mask parameters\n        self.mask_on            = cfg.MODEL.MASK_ON\n        self.mask_sizes         = mask_sizes\n        mask_channels           = cfg.MODEL.TENSOR_MASK.MASK_CHANNELS\n        self.align_on           = cfg.MODEL.TENSOR_MASK.ALIGNED_ON\n        self.bipyramid_on       = cfg.MODEL.TENSOR_MASK.BIPYRAMID_ON\n        # fmt: on\n\n        # class subnet\n        cls_subnet = []\n        cur_channels = in_channels\n        for _ in range(num_convs):\n            cls_subnet.append(\n                nn.Conv2d(cur_channels, cls_channels, kernel_size=3, stride=1, padding=1)\n            )\n            cur_channels = cls_channels\n            cls_subnet.append(nn.ReLU())\n\n        self.cls_subnet = nn.Sequential(*cls_subnet)\n        self.cls_score = nn.Conv2d(\n            cur_channels, num_anchors * num_classes, kernel_size=3, stride=1, padding=1\n        )\n        modules_list = [self.cls_subnet, self.cls_score]\n\n        # box subnet\n        bbox_subnet = []\n        cur_channels = in_channels\n        for _ in range(num_convs):\n            bbox_subnet.append(\n                nn.Conv2d(cur_channels, bbox_channels, kernel_size=3, stride=1, padding=1)\n            )\n            cur_channels = bbox_channels\n            bbox_subnet.append(nn.ReLU())\n\n        self.bbox_subnet = nn.Sequential(*bbox_subnet)\n        self.bbox_pred = nn.Conv2d(\n            cur_channels, num_anchors * 4, kernel_size=3, stride=1, padding=1\n        )\n        modules_list.extend([self.bbox_subnet, self.bbox_pred])\n\n        # mask subnet\n        if self.mask_on:\n            mask_subnet = []\n            cur_channels = in_channels\n            for _ in range(num_convs):\n                mask_subnet.append(\n                    nn.Conv2d(cur_channels, mask_channels, kernel_size=3, stride=1, padding=1)\n                )\n                cur_channels = mask_channels\n                mask_subnet.append(nn.ReLU())\n\n            self.mask_subnet = nn.Sequential(*mask_subnet)\n            modules_list.append(self.mask_subnet)\n            for mask_size in self.mask_sizes:\n                cur_mask_module = \"mask_pred_%02d\" % mask_size\n                self.add_module(\n                    cur_mask_module,\n                    nn.Conv2d(\n                        cur_channels, mask_size * mask_size, kernel_size=1, stride=1, padding=0\n                    ),\n                )\n                modules_list.append(getattr(self, cur_mask_module))\n            if self.align_on:\n                if self.bipyramid_on:\n                    for lvl in range(num_levels):\n                        cur_mask_module = \"align2nat_%02d\" % lvl\n                        lambda_val = 2 ** lvl\n                        setattr(self, cur_mask_module, SwapAlign2Nat(lambda_val))\n                    # Also the fusing layer, stay at the same channel size\n                    mask_fuse = [\n                        nn.Conv2d(cur_channels, cur_channels, kernel_size=3, stride=1, padding=1),\n                        nn.ReLU(),\n                    ]\n                    self.mask_fuse = nn.Sequential(*mask_fuse)\n                    modules_list.append(self.mask_fuse)\n                else:\n                    self.align2nat = SwapAlign2Nat(1)\n\n        # Initialization\n        for modules in modules_list:\n            for layer in modules.modules():\n                if isinstance(layer, nn.Conv2d):\n                    torch.nn.init.normal_(layer.weight, mean=0, std=0.01)\n                    torch.nn.init.constant_(layer.bias, 0)\n\n        # Use prior in model initialization to improve stability\n        bias_value = -(math.log((1 - 0.01) / 0.01))\n        torch.nn.init.constant_(self.cls_score.bias, bias_value)\n\n    def forward(self, features):\n        \"\"\"\n        Arguments:\n            features (list[Tensor]): FPN feature map tensors in high to low resolution.\n                Each tensor in the list correspond to different feature levels.\n\n        Returns:\n            pred_logits (list[Tensor]): #lvl tensors, each has shape (N, AxK, Hi, Wi).\n                The tensor predicts the classification probability\n                at each spatial position for each of the A anchors and K object\n                classes.\n            pred_deltas (list[Tensor]): #lvl tensors, each has shape (N, Ax4, Hi, Wi).\n                The tensor predicts 4-vector (dx,dy,dw,dh) box\n                regression values for every anchor. These values are the\n                relative offset between the anchor and the ground truth box.\n            pred_masks (list(list[Tensor])): #lvl list of tensors, each is a list of\n                A tensors of shape (N, M_{i,a}, Hi, Wi).\n                The tensor predicts a dense set of M_ixM_i masks at every location.\n        \"\"\"\n        pred_logits = [self.cls_score(self.cls_subnet(x)) for x in features]\n        pred_deltas = [self.bbox_pred(self.bbox_subnet(x)) for x in features]\n\n        pred_masks = None\n        if self.mask_on:\n            mask_feats = [self.mask_subnet(x) for x in features]\n\n            if self.bipyramid_on:\n                mask_feat_high_res = mask_feats[0]\n                H, W = mask_feat_high_res.shape[-2:]\n                mask_feats_up = []\n                for lvl, mask_feat in enumerate(mask_feats):\n                    lambda_val = 2.0 ** lvl\n                    mask_feat_up = mask_feat\n                    if lvl > 0:\n                        mask_feat_up = F.interpolate(\n                            mask_feat, scale_factor=lambda_val, mode=\"bilinear\", align_corners=False\n                        )\n                    mask_feats_up.append(\n                        self.mask_fuse(mask_feat_up[:, :, :H, :W] + mask_feat_high_res)\n                    )\n                mask_feats = mask_feats_up\n\n            pred_masks = []\n            for lvl, mask_feat in enumerate(mask_feats):\n                cur_masks = []\n                for mask_size in self.mask_sizes:\n                    cur_mask_module = getattr(self, \"mask_pred_%02d\" % mask_size)\n                    cur_mask = cur_mask_module(mask_feat)\n                    if self.align_on:\n                        if self.bipyramid_on:\n                            cur_mask_module = getattr(self, \"align2nat_%02d\" % lvl)\n                            cur_mask = cur_mask_module(cur_mask)\n                        else:\n                            cur_mask = self.align2nat(cur_mask)\n                    cur_masks.append(cur_mask)\n                pred_masks.append(cur_masks)\n        return pred_logits, pred_deltas, pred_masks\n"
  },
  {
    "path": "VPS_Module/projects/TensorMask/tensormask/config.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom detectron2.config import CfgNode as CN\n\n\ndef add_tensormask_config(cfg):\n    \"\"\"\n    Add config for TensorMask.\n    \"\"\"\n    cfg.MODEL.TENSOR_MASK = CN()\n\n    # Anchor parameters\n    cfg.MODEL.TENSOR_MASK.IN_FEATURES = [\"p2\", \"p3\", \"p4\", \"p5\", \"p6\", \"p7\"]\n\n    # Convolutions to use in the towers\n    cfg.MODEL.TENSOR_MASK.NUM_CONVS = 4\n\n    # Number of foreground classes.\n    cfg.MODEL.TENSOR_MASK.NUM_CLASSES = 80\n    # Channel size for the classification tower\n    cfg.MODEL.TENSOR_MASK.CLS_CHANNELS = 256\n\n    cfg.MODEL.TENSOR_MASK.SCORE_THRESH_TEST = 0.05\n    # Only the top (1000 * #levels) candidate boxes across all levels are\n    # considered jointly during test (to improve speed)\n    cfg.MODEL.TENSOR_MASK.TOPK_CANDIDATES_TEST = 6000\n    cfg.MODEL.TENSOR_MASK.NMS_THRESH_TEST = 0.5\n\n    # Box parameters\n    # Channel size for the box tower\n    cfg.MODEL.TENSOR_MASK.BBOX_CHANNELS = 128\n    # Weights on (dx, dy, dw, dh)\n    cfg.MODEL.TENSOR_MASK.BBOX_REG_WEIGHTS = (1.5, 1.5, 0.75, 0.75)\n\n    # Loss parameters\n    cfg.MODEL.TENSOR_MASK.FOCAL_LOSS_GAMMA = 3.0\n    cfg.MODEL.TENSOR_MASK.FOCAL_LOSS_ALPHA = 0.3\n\n    # Mask parameters\n    # Channel size for the mask tower\n    cfg.MODEL.TENSOR_MASK.MASK_CHANNELS = 128\n    # Mask loss weight\n    cfg.MODEL.TENSOR_MASK.MASK_LOSS_WEIGHT = 2.0\n    # weight on positive pixels within the mask\n    cfg.MODEL.TENSOR_MASK.POSITIVE_WEIGHT = 1.5\n    # Whether to predict in the aligned representation\n    cfg.MODEL.TENSOR_MASK.ALIGNED_ON = False\n    # Whether to use the bipyramid architecture\n    cfg.MODEL.TENSOR_MASK.BIPYRAMID_ON = False\n"
  },
  {
    "path": "VPS_Module/projects/TensorMask/tensormask/layers/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom .swap_align2nat import SwapAlign2Nat, swap_align2nat\n\n__all__ = [k for k in globals().keys() if not k.startswith(\"_\")]\n"
  },
  {
    "path": "VPS_Module/projects/TensorMask/tensormask/layers/csrc/SwapAlign2Nat/SwapAlign2Nat.h",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#pragma once\n#include <torch/types.h>\n\nnamespace tensormask {\n\n#if defined(WITH_CUDA) || defined(WITH_HIP)\nat::Tensor SwapAlign2Nat_forward_cuda(\n    const at::Tensor& X,\n    const int lambda_val,\n    const float pad_val);\n\nat::Tensor SwapAlign2Nat_backward_cuda(\n    const at::Tensor& gY,\n    const int lambda_val,\n    const int batch_size,\n    const int channel,\n    const int height,\n    const int width);\n#endif\n\ninline at::Tensor SwapAlign2Nat_forward(\n    const at::Tensor& X,\n    const int lambda_val,\n    const float pad_val) {\n  if (X.type().is_cuda()) {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n    return SwapAlign2Nat_forward_cuda(X, lambda_val, pad_val);\n#else\n    AT_ERROR(\"Not compiled with GPU support\");\n#endif\n  }\n  AT_ERROR(\"Not implemented on the CPU\");\n}\n\ninline at::Tensor SwapAlign2Nat_backward(\n    const at::Tensor& gY,\n    const int lambda_val,\n    const int batch_size,\n    const int channel,\n    const int height,\n    const int width) {\n  if (gY.type().is_cuda()) {\n#if defined(WITH_CUDA) || defined(WITH_HIP)\n    return SwapAlign2Nat_backward_cuda(\n        gY, lambda_val, batch_size, channel, height, width);\n#else\n    AT_ERROR(\"Not compiled with GPU support\");\n#endif\n  }\n  AT_ERROR(\"Not implemented on the CPU\");\n}\n\n} // namespace tensormask\n"
  },
  {
    "path": "VPS_Module/projects/TensorMask/tensormask/layers/csrc/SwapAlign2Nat/SwapAlign2Nat_cuda.cu",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n#include <ATen/ATen.h>\n#include <ATen/cuda/CUDAContext.h>\n#include <c10/cuda/CUDAGuard.h>\n#include <ATen/cuda/CUDAApplyUtils.cuh>\n\n// TODO make it in a common file\n#define CUDA_1D_KERNEL_LOOP(i, n)                            \\\n  for (int i = blockIdx.x * blockDim.x + threadIdx.x; i < n; \\\n       i += blockDim.x * gridDim.x)\n\ntemplate <typename T>\n__device__ inline T get_pixel_val(\n    const T* tensor,\n    const int idx,\n    const int H,\n    const int W,\n    const int y,\n    const int x,\n    const int V,\n    const int U,\n    const int v,\n    const int u,\n    const T pad_val) {\n  if ((y < 0) || (y >= H) || (x < 0) || (x >= W) || (v < 0) || (v >= V) ||\n      (u < 0) || (u >= U)) {\n    return pad_val;\n  } else {\n    return tensor[(((idx * V + v) * U + u) * H + y) * W + x];\n  }\n}\n\ntemplate <typename T>\n__device__ inline void add_pixel_val(\n    T* tensor,\n    const T val,\n    const int idx,\n    const int H,\n    const int W,\n    const int y,\n    const int x,\n    const int V,\n    const int U,\n    const int v,\n    const int u) {\n  if ((val == 0.) || (y < 0) || (y >= H) || (x < 0) || (x >= W) || (v < 0) ||\n      (v >= V) || (u < 0) || (u >= U)) {\n    return;\n  } else {\n    atomicAdd(tensor + ((((idx * V + v) * U + u) * H + y) * W + x), val);\n  }\n}\n\ntemplate <typename T>\n__global__ void SwapAlign2NatForwardFeat(\n    const int nthreads,\n    const T* bottom_data,\n    const int Vout,\n    const int Uout,\n    const float hVout,\n    const float hUout,\n    const int Vin,\n    const int Uin,\n    const float lambda,\n    const int Hin,\n    const int Win,\n    const int Hout,\n    const int Wout,\n    const T pad_val,\n    T* top_data) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    int idx = index;\n    const int x = idx % Wout;\n    idx /= Wout;\n    const int y = idx % Hout;\n    idx /= Hout;\n    const int u = idx % Uout;\n    idx /= Uout;\n    const int v = idx % Vout;\n    idx /= Vout;\n\n    const float ox = x * lambda + u - hUout + 0.5;\n    const int xf = static_cast<int>(floor(ox));\n    const int xc = static_cast<int>(ceil(ox));\n    const float xwc = ox - xf;\n    const float xwf = 1. - xwc;\n\n    const float oy = y * lambda + v - hVout + 0.5;\n    const int yf = static_cast<int>(floor(oy));\n    const int yc = static_cast<int>(ceil(oy));\n    const float ywc = oy - yf;\n    const float ywf = 1. - ywc;\n\n    const float ou = (u + 0.5) / lambda - 0.5;\n    const int uf = static_cast<int>(floor(ou));\n    const int uc = static_cast<int>(ceil(ou));\n    const float uwc = ou - uf;\n    const float uwf = 1. - uwc;\n\n    const float ov = (v + 0.5) / lambda - 0.5;\n    const int vf = static_cast<int>(floor(ov));\n    const int vc = static_cast<int>(ceil(ov));\n    const float vwc = ov - vf;\n    const float vwf = 1. - vwc;\n\n    T val = ywf * xwf * vwf * uwf *\n            get_pixel_val(\n                bottom_data, idx, Hin, Win, yf, xf, Vin, Uin, vf, uf, pad_val) +\n        ywf * xwf * vwf * uwc *\n            get_pixel_val(\n                bottom_data, idx, Hin, Win, yf, xf, Vin, Uin, vf, uc, pad_val) +\n        ywf * xwf * vwc * uwf *\n            get_pixel_val(\n                bottom_data, idx, Hin, Win, yf, xf, Vin, Uin, vc, uf, pad_val) +\n        ywf * xwf * vwc * uwc *\n            get_pixel_val(\n                bottom_data, idx, Hin, Win, yf, xf, Vin, Uin, vc, uc, pad_val) +\n        ywf * xwc * vwf * uwf *\n            get_pixel_val(\n                bottom_data, idx, Hin, Win, yf, xc, Vin, Uin, vf, uf, pad_val) +\n        ywf * xwc * vwf * uwc *\n            get_pixel_val(\n                bottom_data, idx, Hin, Win, yf, xc, Vin, Uin, vf, uc, pad_val) +\n        ywf * xwc * vwc * uwf *\n            get_pixel_val(\n                bottom_data, idx, Hin, Win, yf, xc, Vin, Uin, vc, uf, pad_val) +\n        ywf * xwc * vwc * uwc *\n            get_pixel_val(\n                bottom_data, idx, Hin, Win, yf, xc, Vin, Uin, vc, uc, pad_val) +\n        ywc * xwf * vwf * uwf *\n            get_pixel_val(\n                bottom_data, idx, Hin, Win, yc, xf, Vin, Uin, vf, uf, pad_val) +\n        ywc * xwf * vwf * uwc *\n            get_pixel_val(\n                bottom_data, idx, Hin, Win, yc, xf, Vin, Uin, vf, uc, pad_val) +\n        ywc * xwf * vwc * uwf *\n            get_pixel_val(\n                bottom_data, idx, Hin, Win, yc, xf, Vin, Uin, vc, uf, pad_val) +\n        ywc * xwf * vwc * uwc *\n            get_pixel_val(\n                bottom_data, idx, Hin, Win, yc, xf, Vin, Uin, vc, uc, pad_val) +\n        ywc * xwc * vwf * uwf *\n            get_pixel_val(\n                bottom_data, idx, Hin, Win, yc, xc, Vin, Uin, vf, uf, pad_val) +\n        ywc * xwc * vwf * uwc *\n            get_pixel_val(\n                bottom_data, idx, Hin, Win, yc, xc, Vin, Uin, vf, uc, pad_val) +\n        ywc * xwc * vwc * uwf *\n            get_pixel_val(\n                bottom_data, idx, Hin, Win, yc, xc, Vin, Uin, vc, uf, pad_val) +\n        ywc * xwc * vwc * uwc *\n            get_pixel_val(\n                bottom_data, idx, Hin, Win, yc, xc, Vin, Uin, vc, uc, pad_val);\n\n    top_data[index] = val;\n  }\n}\n\ntemplate <typename T>\n__global__ void SwapAlign2NatBackwardFeat(\n    const int nthreads,\n    const T* top_diff,\n    const int Vout,\n    const int Uout,\n    const float hVout,\n    const float hUout,\n    const int Vin,\n    const int Uin,\n    const float lambda,\n    const int Hin,\n    const int Win,\n    const int Hout,\n    const int Wout,\n    T* bottom_diff) {\n  CUDA_1D_KERNEL_LOOP(index, nthreads) {\n    int idx = index;\n    const int x = idx % Wout;\n    idx /= Wout;\n    const int y = idx % Hout;\n    idx /= Hout;\n    const int u = idx % Uout;\n    idx /= Uout;\n    const int v = idx % Vout;\n    idx /= Vout;\n\n    const float ox = x * lambda + u - hUout + 0.5;\n    const int xf = static_cast<int>(floor(ox));\n    const int xc = static_cast<int>(ceil(ox));\n    const float xwc = ox - xf;\n    const float xwf = 1. - xwc;\n\n    const float oy = y * lambda + v - hVout + 0.5;\n    const int yf = static_cast<int>(floor(oy));\n    const int yc = static_cast<int>(ceil(oy));\n    const float ywc = oy - yf;\n    const float ywf = 1. - ywc;\n\n    const float ou = (u + 0.5) / lambda - 0.5;\n    const int uf = static_cast<int>(floor(ou));\n    const int uc = static_cast<int>(ceil(ou));\n    const float uwc = ou - uf;\n    const float uwf = 1. - uwc;\n\n    const float ov = (v + 0.5) / lambda - 0.5;\n    const int vf = static_cast<int>(floor(ov));\n    const int vc = static_cast<int>(ceil(ov));\n    const float vwc = ov - vf;\n    const float vwf = 1. - vwc;\n\n    const T grad = top_diff[index];\n\n    add_pixel_val(\n        bottom_diff,\n        ywf * xwf * vwf * uwf * grad,\n        idx,\n        Hin,\n        Win,\n        yf,\n        xf,\n        Vin,\n        Uin,\n        vf,\n        uf);\n    add_pixel_val(\n        bottom_diff,\n        ywf * xwf * vwf * uwc * grad,\n        idx,\n        Hin,\n        Win,\n        yf,\n        xf,\n        Vin,\n        Uin,\n        vf,\n        uc);\n    add_pixel_val(\n        bottom_diff,\n        ywf * xwf * vwc * uwf * grad,\n        idx,\n        Hin,\n        Win,\n        yf,\n        xf,\n        Vin,\n        Uin,\n        vc,\n        uf);\n    add_pixel_val(\n        bottom_diff,\n        ywf * xwf * vwc * uwc * grad,\n        idx,\n        Hin,\n        Win,\n        yf,\n        xf,\n        Vin,\n        Uin,\n        vc,\n        uc);\n    add_pixel_val(\n        bottom_diff,\n        ywf * xwc * vwf * uwf * grad,\n        idx,\n        Hin,\n        Win,\n        yf,\n        xc,\n        Vin,\n        Uin,\n        vf,\n        uf);\n    add_pixel_val(\n        bottom_diff,\n        ywf * xwc * vwf * uwc * grad,\n        idx,\n        Hin,\n        Win,\n        yf,\n        xc,\n        Vin,\n        Uin,\n        vf,\n        uc);\n    add_pixel_val(\n        bottom_diff,\n        ywf * xwc * vwc * uwf * grad,\n        idx,\n        Hin,\n        Win,\n        yf,\n        xc,\n        Vin,\n        Uin,\n        vc,\n        uf);\n    add_pixel_val(\n        bottom_diff,\n        ywf * xwc * vwc * uwc * grad,\n        idx,\n        Hin,\n        Win,\n        yf,\n        xc,\n        Vin,\n        Uin,\n        vc,\n        uc);\n    add_pixel_val(\n        bottom_diff,\n        ywc * xwf * vwf * uwf * grad,\n        idx,\n        Hin,\n        Win,\n        yc,\n        xf,\n        Vin,\n        Uin,\n        vf,\n        uf);\n    add_pixel_val(\n        bottom_diff,\n        ywc * xwf * vwf * uwc * grad,\n        idx,\n        Hin,\n        Win,\n        yc,\n        xf,\n        Vin,\n        Uin,\n        vf,\n        uc);\n    add_pixel_val(\n        bottom_diff,\n        ywc * xwf * vwc * uwf * grad,\n        idx,\n        Hin,\n        Win,\n        yc,\n        xf,\n        Vin,\n        Uin,\n        vc,\n        uf);\n    add_pixel_val(\n        bottom_diff,\n        ywc * xwf * vwc * uwc * grad,\n        idx,\n        Hin,\n        Win,\n        yc,\n        xf,\n        Vin,\n        Uin,\n        vc,\n        uc);\n    add_pixel_val(\n        bottom_diff,\n        ywc * xwc * vwf * uwf * grad,\n        idx,\n        Hin,\n        Win,\n        yc,\n        xc,\n        Vin,\n        Uin,\n        vf,\n        uf);\n    add_pixel_val(\n        bottom_diff,\n        ywc * xwc * vwf * uwc * grad,\n        idx,\n        Hin,\n        Win,\n        yc,\n        xc,\n        Vin,\n        Uin,\n        vf,\n        uc);\n    add_pixel_val(\n        bottom_diff,\n        ywc * xwc * vwc * uwf * grad,\n        idx,\n        Hin,\n        Win,\n        yc,\n        xc,\n        Vin,\n        Uin,\n        vc,\n        uf);\n    add_pixel_val(\n        bottom_diff,\n        ywc * xwc * vwc * uwc * grad,\n        idx,\n        Hin,\n        Win,\n        yc,\n        xc,\n        Vin,\n        Uin,\n        vc,\n        uc);\n  }\n}\n\nnamespace tensormask {\n\nat::Tensor SwapAlign2Nat_forward_cuda(\n    const at::Tensor& X,\n    const int lambda_val,\n    const float pad_val) {\n  AT_ASSERTM(X.device().is_cuda(), \"input must be a CUDA tensor\");\n  AT_ASSERTM(X.ndimension() == 4, \"input must be a 4D tensor\");\n  AT_ASSERTM(lambda_val >= 1, \"lambda should be greater or equal to 1\");\n  const int N = X.size(0);\n  const int C = X.size(1);\n  const int Vin = static_cast<int>(sqrt(static_cast<float>(C)));\n  const int Uin = C / Vin;\n  AT_ASSERTM(\n      C == Vin * Uin && Vin == Uin, \"#channels should be a square number\");\n  const int Vout = lambda_val * Vin;\n  const int Uout = lambda_val * Uin;\n  const int Hin = X.size(2);\n  const int Win = X.size(3);\n  const float lambda = static_cast<float>(lambda_val);\n  const int Hout = static_cast<int>(ceil(Hin / lambda));\n  const int Wout = static_cast<int>(ceil(Win / lambda));\n  const float hVout = Vout / 2.;\n  const float hUout = Uout / 2.;\n\n  at::cuda::CUDAGuard device_guard(X.device());\n\n  at::Tensor Y = at::empty({N, Vout * Uout, Hout, Wout}, X.options());\n\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  dim3 grid(std::min(at::cuda::ATenCeilDiv(Y.numel(), 512L), 4096L));\n  dim3 block(512);\n\n  if (Y.numel() == 0) {\n    AT_CUDA_CHECK(cudaGetLastError());\n    return Y;\n  }\n\n  auto X_ = X.contiguous();\n  AT_DISPATCH_FLOATING_TYPES(X.scalar_type(), \"SwapAlign2Nat_forward\", [&] {\n    SwapAlign2NatForwardFeat<scalar_t><<<grid, block, 0, stream>>>(\n        Y.numel(),\n        X_.data_ptr<scalar_t>(),\n        Vout,\n        Uout,\n        hVout,\n        hUout,\n        Vin,\n        Uin,\n        lambda,\n        Hin,\n        Win,\n        Hout,\n        Wout,\n        pad_val,\n        Y.data_ptr<scalar_t>());\n  });\n  cudaDeviceSynchronize();\n  AT_CUDA_CHECK(cudaGetLastError());\n  return Y;\n}\n\nat::Tensor SwapAlign2Nat_backward_cuda(\n    const at::Tensor& gY,\n    const int lambda_val,\n    const int batch_size,\n    const int channel,\n    const int height,\n    const int width) {\n  AT_ASSERTM(gY.device().is_cuda(), \"input gradient must be a CUDA tensor\");\n  AT_ASSERTM(gY.ndimension() == 4, \"input gradient must be a 4D tensor\");\n  AT_ASSERTM(lambda_val >= 1, \"lambda should be greater or equal to 1\");\n  const int Vin = static_cast<int>(sqrt(static_cast<float>(channel)));\n  const int Uin = channel / Vin;\n  const int Vout = lambda_val * Vin;\n  const int Uout = lambda_val * Uin;\n  const float hVout = Vout / 2.;\n  const float hUout = Uout / 2.;\n  const int Hout = gY.size(2);\n  const int Wout = gY.size(3);\n\n  at::cuda::CUDAGuard device_guard(gY.device());\n\n  at::Tensor gX = at::zeros({batch_size, channel, height, width}, gY.options());\n\n  cudaStream_t stream = at::cuda::getCurrentCUDAStream();\n\n  dim3 grid(std::min(at::cuda::ATenCeilDiv(gY.numel(), 512L), 4096L));\n  dim3 block(512);\n\n  // handle possibly empty gradients\n  if (gY.numel() == 0) {\n    AT_CUDA_CHECK(cudaGetLastError());\n    return gX;\n  }\n\n  auto gY_ = gY.contiguous();\n  AT_DISPATCH_FLOATING_TYPES(gY.scalar_type(), \"SwapAlign2Nat_backward\", [&] {\n    SwapAlign2NatBackwardFeat<scalar_t><<<grid, block, 0, stream>>>(\n        gY.numel(),\n        gY_.data_ptr<scalar_t>(),\n        Vout,\n        Uout,\n        hVout,\n        hUout,\n        Vin,\n        Uin,\n        static_cast<float>(lambda_val),\n        height,\n        width,\n        Hout,\n        Wout,\n        gX.data_ptr<scalar_t>());\n  });\n  AT_CUDA_CHECK(cudaGetLastError());\n  return gX;\n}\n\n} // namespace tensormask\n"
  },
  {
    "path": "VPS_Module/projects/TensorMask/tensormask/layers/csrc/vision.cpp",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n\n#include <torch/extension.h>\n#include \"SwapAlign2Nat/SwapAlign2Nat.h\"\n\nnamespace tensormask {\n\nPYBIND11_MODULE(TORCH_EXTENSION_NAME, m) {\n  m.def(\n      \"swap_align2nat_forward\",\n      &SwapAlign2Nat_forward,\n      \"SwapAlign2Nat_forward\");\n  m.def(\n      \"swap_align2nat_backward\",\n      &SwapAlign2Nat_backward,\n      \"SwapAlign2Nat_backward\");\n}\n\n} // namespace tensormask\n"
  },
  {
    "path": "VPS_Module/projects/TensorMask/tensormask/layers/swap_align2nat.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom torch import nn\nfrom torch.autograd import Function\nfrom torch.autograd.function import once_differentiable\n\nfrom tensormask import _C\n\n\nclass _SwapAlign2Nat(Function):\n    @staticmethod\n    def forward(ctx, X, lambda_val, pad_val):\n        ctx.lambda_val = lambda_val\n        ctx.input_shape = X.size()\n\n        Y = _C.swap_align2nat_forward(X, lambda_val, pad_val)\n        return Y\n\n    @staticmethod\n    @once_differentiable\n    def backward(ctx, gY):\n        lambda_val = ctx.lambda_val\n        bs, ch, h, w = ctx.input_shape\n\n        gX = _C.swap_align2nat_backward(gY, lambda_val, bs, ch, h, w)\n\n        return gX, None, None\n\n\nswap_align2nat = _SwapAlign2Nat.apply\n\n\nclass SwapAlign2Nat(nn.Module):\n    \"\"\"\n    The op `SwapAlign2Nat` described in https://arxiv.org/abs/1903.12174.\n    Given an input tensor that predicts masks of shape (N, C=VxU, H, W),\n    apply the op, it will return masks of shape (N, V'xU', H', W') where\n    the unit lengths of (V, U) and (H, W) are swapped, and the mask representation\n    is transformed from aligned to natural.\n    Args:\n        lambda_val (int): the relative unit length ratio between (V, U) and (H, W),\n                            as we always have larger unit lengths for (V, U) than (H, W),\n                            lambda_val is always >= 1.\n        pad_val (float):    padding value for the values falling outside of the input\n                            tensor, default set to -6 as sigmoid(-6) is ~0, indicating\n                            that is no masks outside of the tensor.\n    \"\"\"\n\n    def __init__(self, lambda_val, pad_val=-6.0):\n        super(SwapAlign2Nat, self).__init__()\n        self.lambda_val = lambda_val\n        self.pad_val = pad_val\n\n    def forward(self, X):\n        return swap_align2nat(X, self.lambda_val, self.pad_val)\n\n    def __repr__(self):\n        tmpstr = self.__class__.__name__ + \"(\"\n        tmpstr += \"lambda_val=\" + str(self.lambda_val)\n        tmpstr += \", pad_val=\" + str(self.pad_val)\n        tmpstr += \")\"\n        return tmpstr\n"
  },
  {
    "path": "VPS_Module/projects/TensorMask/train_net.py",
    "content": "#!/usr/bin/env python3\n# Copyright (c) Facebook, Inc. and its affiliates.\n\n\"\"\"\nTensorMask Training Script.\n\nThis script is a simplified version of the training script in detectron2/tools.\n\"\"\"\n\nimport os\n\nimport detectron2.utils.comm as comm\nfrom detectron2.checkpoint import DetectionCheckpointer\nfrom detectron2.config import get_cfg\nfrom detectron2.engine import DefaultTrainer, default_argument_parser, default_setup, launch\nfrom detectron2.evaluation import COCOEvaluator, verify_results\n\nfrom tensormask import add_tensormask_config\n\n\nclass Trainer(DefaultTrainer):\n    @classmethod\n    def build_evaluator(cls, cfg, dataset_name, output_folder=None):\n        if output_folder is None:\n            output_folder = os.path.join(cfg.OUTPUT_DIR, \"inference\")\n        return COCOEvaluator(dataset_name, output_dir=output_folder)\n\n\ndef setup(args):\n    \"\"\"\n    Create configs and perform basic setups.\n    \"\"\"\n    cfg = get_cfg()\n    add_tensormask_config(cfg)\n    cfg.merge_from_file(args.config_file)\n    cfg.merge_from_list(args.opts)\n    cfg.freeze()\n    default_setup(cfg, args)\n    return cfg\n\n\ndef main(args):\n    cfg = setup(args)\n\n    if args.eval_only:\n        model = Trainer.build_model(cfg)\n        DetectionCheckpointer(model, save_dir=cfg.OUTPUT_DIR).resume_or_load(\n            cfg.MODEL.WEIGHTS, resume=args.resume\n        )\n        res = Trainer.test(cfg, model)\n        if comm.is_main_process():\n            verify_results(cfg, res)\n        return res\n\n    trainer = Trainer(cfg)\n    trainer.resume_or_load(resume=args.resume)\n    return trainer.train()\n\n\nif __name__ == \"__main__\":\n    args = default_argument_parser().parse_args()\n    print(\"Command Line Args:\", args)\n    launch(\n        main,\n        args.num_gpus,\n        num_machines=args.num_machines,\n        machine_rank=args.machine_rank,\n        dist_url=args.dist_url,\n        args=(args,),\n    )\n"
  },
  {
    "path": "VPS_Module/projects/TridentNet/README.md",
    "content": "\n# TridentNet in Detectron2\n**Scale-Aware Trident Networks for Object Detection**\n\nYanghao Li\\*, Yuntao Chen\\*, Naiyan Wang, Zhaoxiang Zhang\n\n[[`TridentNet`](https://github.com/TuSimple/simpledet/tree/master/models/tridentnet)] [[`arXiv`](https://arxiv.org/abs/1901.01892)] [[`BibTeX`](#CitingTridentNet)]\n\n<div align=\"center\">\n  <img src=\"https://drive.google.com/uc?export=view&id=10THEPdIPmf3ooMyNzrfZbpWihEBvixwt\" width=\"700px\" />\n</div>\n\nIn this repository, we implement TridentNet-Fast in Detectron2.\nTrident Network (TridentNet) aims to generate scale-specific feature maps with a uniform representational power. We construct a parallel multi-branch architecture in which each branch shares the same transformation parameters but with different receptive fields. TridentNet-Fast is a fast approximation version of TridentNet that could achieve significant improvements without any additional parameters and computational cost.\n\n## Training\n\nTo train a model, run\n```bash\npython /path/to/detectron2/projects/TridentNet/train_net.py --config-file <config.yaml>\n```\n\nFor example, to launch end-to-end TridentNet training with ResNet-50 backbone on 8 GPUs,\none should execute:\n```bash\npython /path/to/detectron2/projects/TridentNet/train_net.py --config-file configs/tridentnet_fast_R_50_C4_1x.yaml --num-gpus 8\n```\n\n## Evaluation\n\nModel evaluation can be done similarly:\n```bash\npython /path/to/detectron2/projects/TridentNet/train_net.py --config-file configs/tridentnet_fast_R_50_C4_1x.yaml --eval-only MODEL.WEIGHTS model.pth\n```\n\n## Results on MS-COCO in Detectron2\n\n|Model|Backbone|Head|lr sched|AP|AP50|AP75|APs|APm|APl|download|\n|-----|--------|----|--------|--|----|----|---|---|---|--------|\n|Faster|R50-C4|C5-512ROI|1X|35.7|56.1|38.0|19.2|40.9|48.7|<a href=\"https://dl.fbaipublicfiles.com/detectron2/COCO-Detection/faster_rcnn_R_50_C4_1x/137257644/model_final_721ade.pkl\">model</a>&nbsp;\\|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/COCO-Detection/faster_rcnn_R_50_C4_1x/137257644/metrics.json\">metrics</a>|\n|TridentFast|R50-C4|C5-128ROI|1X|38.0|58.1|40.8|19.5|42.2|54.6|<a href=\"https://dl.fbaipublicfiles.com/detectron2/TridentNet/tridentnet_fast_R_50_C4_1x/148572687/model_final_756cda.pkl\">model</a>&nbsp;\\|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/TridentNet/tridentnet_fast_R_50_C4_1x/148572687/metrics.json\">metrics</a>|\n|Faster|R50-C4|C5-512ROI|3X|38.4|58.7|41.3|20.7|42.7|53.1|<a href=\"https://dl.fbaipublicfiles.com/detectron2/COCO-Detection/faster_rcnn_R_50_C4_3x/137849393/model_final_f97cb7.pkl\">model</a>&nbsp;\\|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/COCO-Detection/faster_rcnn_R_50_C4_3x/137849393/metrics.json\">metrics</a>|\n|TridentFast|R50-C4|C5-128ROI|3X|40.6|60.8|43.6|23.4|44.7|57.1|<a href=\"https://dl.fbaipublicfiles.com/detectron2/TridentNet/tridentnet_fast_R_50_C4_3x/148572287/model_final_e1027c.pkl\">model</a>&nbsp;\\|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/TridentNet/tridentnet_fast_R_50_C4_3x/148572287/metrics.json\">metrics</a>|\n|Faster|R101-C4|C5-512ROI|3X|41.1|61.4|44.0|22.2|45.5|55.9|<a href=\"https://dl.fbaipublicfiles.com/detectron2/COCO-Detection/faster_rcnn_R_101_C4_3x/138204752/model_final_298dad.pkl\">model</a>&nbsp;\\|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/COCO-Detection/faster_rcnn_R_101_C4_3x/138204752/metrics.json\">metrics</a>|\n|TridentFast|R101-C4|C5-128ROI|3X|43.6|63.4|47.0|24.3|47.8|60.0|<a href=\"https://dl.fbaipublicfiles.com/detectron2/TridentNet/tridentnet_fast_R_101_C4_3x/148572198/model_final_164568.pkl\">model</a>&nbsp;\\|&nbsp;<a href=\"https://dl.fbaipublicfiles.com/detectron2/TridentNet/tridentnet_fast_R_101_C4_3x/148572198/metrics.json\">metrics</a>|\n\n\n## <a name=\"CitingTridentNet\"></a>Citing TridentNet\n\nIf you use TridentNet, please use the following BibTeX entry.\n\n```\n@InProceedings{li2019scale,\n  title={Scale-Aware Trident Networks for Object Detection},\n  author={Li, Yanghao and Chen, Yuntao and Wang, Naiyan and Zhang, Zhaoxiang},\n  journal={The International Conference on Computer Vision (ICCV)},\n  year={2019}\n}\n```\n\n"
  },
  {
    "path": "VPS_Module/projects/TridentNet/configs/Base-TridentNet-Fast-C4.yaml",
    "content": "MODEL:\n  META_ARCHITECTURE: \"GeneralizedRCNN\"\n  BACKBONE:\n    NAME: \"build_trident_resnet_backbone\"\n  ROI_HEADS:\n    NAME: \"TridentRes5ROIHeads\"\n    POSITIVE_FRACTION: 0.5\n    BATCH_SIZE_PER_IMAGE: 128\n    PROPOSAL_APPEND_GT: False\n  PROPOSAL_GENERATOR:\n    NAME: \"TridentRPN\"\n  RPN:\n    POST_NMS_TOPK_TRAIN: 500\n  TRIDENT:\n    NUM_BRANCH: 3\n    BRANCH_DILATIONS: [1, 2, 3]\n    TEST_BRANCH_IDX: 1\n    TRIDENT_STAGE: \"res4\"\nDATASETS:\n  TRAIN: (\"coco_2017_train\",)\n  TEST: (\"coco_2017_val\",)\nSOLVER:\n  IMS_PER_BATCH: 16\n  BASE_LR: 0.02\n  STEPS: (60000, 80000)\n  MAX_ITER: 90000\nINPUT:\n  MIN_SIZE_TRAIN: (640, 672, 704, 736, 768, 800)\nVERSION: 2\n"
  },
  {
    "path": "VPS_Module/projects/TridentNet/configs/tridentnet_fast_R_101_C4_3x.yaml",
    "content": "_BASE_: \"Base-TridentNet-Fast-C4.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-101.pkl\"\n  MASK_ON: False\n  RESNETS:\n    DEPTH: 101\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/projects/TridentNet/configs/tridentnet_fast_R_50_C4_1x.yaml",
    "content": "_BASE_: \"Base-TridentNet-Fast-C4.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: False\n  RESNETS:\n    DEPTH: 50\n"
  },
  {
    "path": "VPS_Module/projects/TridentNet/configs/tridentnet_fast_R_50_C4_3x.yaml",
    "content": "_BASE_: \"Base-TridentNet-Fast-C4.yaml\"\nMODEL:\n  WEIGHTS: \"detectron2://ImageNetPretrained/MSRA/R-50.pkl\"\n  MASK_ON: False\n  RESNETS:\n    DEPTH: 50\nSOLVER:\n  STEPS: (210000, 250000)\n  MAX_ITER: 270000\n"
  },
  {
    "path": "VPS_Module/projects/TridentNet/train_net.py",
    "content": "#!/usr/bin/env python3\n# Copyright (c) Facebook, Inc. and its affiliates.\n\n\"\"\"\nTridentNet Training Script.\n\nThis script is a simplified version of the training script in detectron2/tools.\n\"\"\"\n\nimport os\n\nfrom detectron2.checkpoint import DetectionCheckpointer\nfrom detectron2.config import get_cfg\nfrom detectron2.engine import DefaultTrainer, default_argument_parser, default_setup, launch\nfrom detectron2.evaluation import COCOEvaluator\n\nfrom tridentnet import add_tridentnet_config\n\n\nclass Trainer(DefaultTrainer):\n    @classmethod\n    def build_evaluator(cls, cfg, dataset_name, output_folder=None):\n        if output_folder is None:\n            output_folder = os.path.join(cfg.OUTPUT_DIR, \"inference\")\n        return COCOEvaluator(dataset_name, output_dir=output_folder)\n\n\ndef setup(args):\n    \"\"\"\n    Create configs and perform basic setups.\n    \"\"\"\n    cfg = get_cfg()\n    add_tridentnet_config(cfg)\n    cfg.merge_from_file(args.config_file)\n    cfg.merge_from_list(args.opts)\n    cfg.freeze()\n    default_setup(cfg, args)\n    return cfg\n\n\ndef main(args):\n    cfg = setup(args)\n\n    if args.eval_only:\n        model = Trainer.build_model(cfg)\n        DetectionCheckpointer(model, save_dir=cfg.OUTPUT_DIR).resume_or_load(\n            cfg.MODEL.WEIGHTS, resume=args.resume\n        )\n        res = Trainer.test(cfg, model)\n        return res\n\n    trainer = Trainer(cfg)\n    trainer.resume_or_load(resume=args.resume)\n    return trainer.train()\n\n\nif __name__ == \"__main__\":\n    args = default_argument_parser().parse_args()\n    print(\"Command Line Args:\", args)\n    launch(\n        main,\n        args.num_gpus,\n        num_machines=args.num_machines,\n        machine_rank=args.machine_rank,\n        dist_url=args.dist_url,\n        args=(args,),\n    )\n"
  },
  {
    "path": "VPS_Module/projects/TridentNet/tridentnet/__init__.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom .config import add_tridentnet_config\nfrom .trident_backbone import (\n    TridentBottleneckBlock,\n    build_trident_resnet_backbone,\n    make_trident_stage,\n)\nfrom .trident_rpn import TridentRPN\nfrom .trident_rcnn import TridentRes5ROIHeads, TridentStandardROIHeads\n"
  },
  {
    "path": "VPS_Module/projects/TridentNet/tridentnet/config.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nfrom detectron2.config import CfgNode as CN\n\n\ndef add_tridentnet_config(cfg):\n    \"\"\"\n    Add config for tridentnet.\n    \"\"\"\n    _C = cfg\n\n    _C.MODEL.TRIDENT = CN()\n\n    # Number of branches for TridentNet.\n    _C.MODEL.TRIDENT.NUM_BRANCH = 3\n    # Specify the dilations for each branch.\n    _C.MODEL.TRIDENT.BRANCH_DILATIONS = [1, 2, 3]\n    # Specify the stage for applying trident blocks. Default stage is Res4 according to the\n    # TridentNet paper.\n    _C.MODEL.TRIDENT.TRIDENT_STAGE = \"res4\"\n    # Specify the test branch index TridentNet Fast inference:\n    #   - use -1 to aggregate results of all branches during inference.\n    #   - otherwise, only using specified branch for fast inference. Recommended setting is\n    #     to use the middle branch.\n    _C.MODEL.TRIDENT.TEST_BRANCH_IDX = 1\n"
  },
  {
    "path": "VPS_Module/projects/TridentNet/tridentnet/trident_backbone.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport fvcore.nn.weight_init as weight_init\nimport torch\nimport torch.nn.functional as F\n\nfrom detectron2.layers import Conv2d, FrozenBatchNorm2d, get_norm\nfrom detectron2.modeling import BACKBONE_REGISTRY, ResNet, ResNetBlockBase\nfrom detectron2.modeling.backbone.resnet import BasicStem, BottleneckBlock, DeformBottleneckBlock\n\nfrom .trident_conv import TridentConv\n\n__all__ = [\"TridentBottleneckBlock\", \"make_trident_stage\", \"build_trident_resnet_backbone\"]\n\n\nclass TridentBottleneckBlock(ResNetBlockBase):\n    def __init__(\n        self,\n        in_channels,\n        out_channels,\n        *,\n        bottleneck_channels,\n        stride=1,\n        num_groups=1,\n        norm=\"BN\",\n        stride_in_1x1=False,\n        num_branch=3,\n        dilations=(1, 2, 3),\n        concat_output=False,\n        test_branch_idx=-1,\n    ):\n        \"\"\"\n        Args:\n            num_branch (int): the number of branches in TridentNet.\n            dilations (tuple): the dilations of multiple branches in TridentNet.\n            concat_output (bool): if concatenate outputs of multiple branches in TridentNet.\n                Use 'True' for the last trident block.\n        \"\"\"\n        super().__init__(in_channels, out_channels, stride)\n\n        assert num_branch == len(dilations)\n\n        self.num_branch = num_branch\n        self.concat_output = concat_output\n        self.test_branch_idx = test_branch_idx\n\n        if in_channels != out_channels:\n            self.shortcut = Conv2d(\n                in_channels,\n                out_channels,\n                kernel_size=1,\n                stride=stride,\n                bias=False,\n                norm=get_norm(norm, out_channels),\n            )\n        else:\n            self.shortcut = None\n\n        stride_1x1, stride_3x3 = (stride, 1) if stride_in_1x1 else (1, stride)\n\n        self.conv1 = Conv2d(\n            in_channels,\n            bottleneck_channels,\n            kernel_size=1,\n            stride=stride_1x1,\n            bias=False,\n            norm=get_norm(norm, bottleneck_channels),\n        )\n\n        self.conv2 = TridentConv(\n            bottleneck_channels,\n            bottleneck_channels,\n            kernel_size=3,\n            stride=stride_3x3,\n            paddings=dilations,\n            bias=False,\n            groups=num_groups,\n            dilations=dilations,\n            num_branch=num_branch,\n            test_branch_idx=test_branch_idx,\n            norm=get_norm(norm, bottleneck_channels),\n        )\n\n        self.conv3 = Conv2d(\n            bottleneck_channels,\n            out_channels,\n            kernel_size=1,\n            bias=False,\n            norm=get_norm(norm, out_channels),\n        )\n\n        for layer in [self.conv1, self.conv2, self.conv3, self.shortcut]:\n            if layer is not None:  # shortcut can be None\n                weight_init.c2_msra_fill(layer)\n\n    def forward(self, x):\n        num_branch = self.num_branch if self.training or self.test_branch_idx == -1 else 1\n        if not isinstance(x, list):\n            x = [x] * num_branch\n        out = [self.conv1(b) for b in x]\n        out = [F.relu_(b) for b in out]\n\n        out = self.conv2(out)\n        out = [F.relu_(b) for b in out]\n\n        out = [self.conv3(b) for b in out]\n\n        if self.shortcut is not None:\n            shortcut = [self.shortcut(b) for b in x]\n        else:\n            shortcut = x\n\n        out = [out_b + shortcut_b for out_b, shortcut_b in zip(out, shortcut)]\n        out = [F.relu_(b) for b in out]\n        if self.concat_output:\n            out = torch.cat(out)\n        return out\n\n\ndef make_trident_stage(block_class, num_blocks, **kwargs):\n    \"\"\"\n    Create a resnet stage by creating many blocks for TridentNet.\n    \"\"\"\n    concat_output = [False] * (num_blocks - 1) + [True]\n    kwargs[\"concat_output_per_block\"] = concat_output\n    return ResNet.make_stage(block_class, num_blocks, **kwargs)\n\n\n@BACKBONE_REGISTRY.register()\ndef build_trident_resnet_backbone(cfg, input_shape):\n    \"\"\"\n    Create a ResNet instance from config for TridentNet.\n\n    Returns:\n        ResNet: a :class:`ResNet` instance.\n    \"\"\"\n    # need registration of new blocks/stems?\n    norm = cfg.MODEL.RESNETS.NORM\n    stem = BasicStem(\n        in_channels=input_shape.channels,\n        out_channels=cfg.MODEL.RESNETS.STEM_OUT_CHANNELS,\n        norm=norm,\n    )\n    freeze_at = cfg.MODEL.BACKBONE.FREEZE_AT\n\n    if freeze_at >= 1:\n        for p in stem.parameters():\n            p.requires_grad = False\n        stem = FrozenBatchNorm2d.convert_frozen_batchnorm(stem)\n\n    # fmt: off\n    out_features         = cfg.MODEL.RESNETS.OUT_FEATURES\n    depth                = cfg.MODEL.RESNETS.DEPTH\n    num_groups           = cfg.MODEL.RESNETS.NUM_GROUPS\n    width_per_group      = cfg.MODEL.RESNETS.WIDTH_PER_GROUP\n    bottleneck_channels  = num_groups * width_per_group\n    in_channels          = cfg.MODEL.RESNETS.STEM_OUT_CHANNELS\n    out_channels         = cfg.MODEL.RESNETS.RES2_OUT_CHANNELS\n    stride_in_1x1        = cfg.MODEL.RESNETS.STRIDE_IN_1X1\n    res5_dilation        = cfg.MODEL.RESNETS.RES5_DILATION\n    deform_on_per_stage  = cfg.MODEL.RESNETS.DEFORM_ON_PER_STAGE\n    deform_modulated     = cfg.MODEL.RESNETS.DEFORM_MODULATED\n    deform_num_groups    = cfg.MODEL.RESNETS.DEFORM_NUM_GROUPS\n    num_branch           = cfg.MODEL.TRIDENT.NUM_BRANCH\n    branch_dilations     = cfg.MODEL.TRIDENT.BRANCH_DILATIONS\n    trident_stage        = cfg.MODEL.TRIDENT.TRIDENT_STAGE\n    test_branch_idx      = cfg.MODEL.TRIDENT.TEST_BRANCH_IDX\n    # fmt: on\n    assert res5_dilation in {1, 2}, \"res5_dilation cannot be {}.\".format(res5_dilation)\n\n    num_blocks_per_stage = {50: [3, 4, 6, 3], 101: [3, 4, 23, 3], 152: [3, 8, 36, 3]}[depth]\n\n    stages = []\n\n    res_stage_idx = {\"res2\": 2, \"res3\": 3, \"res4\": 4, \"res5\": 5}\n    out_stage_idx = [res_stage_idx[f] for f in out_features]\n    trident_stage_idx = res_stage_idx[trident_stage]\n    max_stage_idx = max(out_stage_idx)\n    for idx, stage_idx in enumerate(range(2, max_stage_idx + 1)):\n        dilation = res5_dilation if stage_idx == 5 else 1\n        first_stride = 1 if idx == 0 or (stage_idx == 5 and dilation == 2) else 2\n        stage_kargs = {\n            \"num_blocks\": num_blocks_per_stage[idx],\n            \"stride_per_block\": [first_stride] + [1] * (num_blocks_per_stage[idx] - 1),\n            \"in_channels\": in_channels,\n            \"bottleneck_channels\": bottleneck_channels,\n            \"out_channels\": out_channels,\n            \"num_groups\": num_groups,\n            \"norm\": norm,\n            \"stride_in_1x1\": stride_in_1x1,\n            \"dilation\": dilation,\n        }\n        if stage_idx == trident_stage_idx:\n            assert not deform_on_per_stage[\n                idx\n            ], \"Not support deformable conv in Trident blocks yet.\"\n            stage_kargs[\"block_class\"] = TridentBottleneckBlock\n            stage_kargs[\"num_branch\"] = num_branch\n            stage_kargs[\"dilations\"] = branch_dilations\n            stage_kargs[\"test_branch_idx\"] = test_branch_idx\n            stage_kargs.pop(\"dilation\")\n        elif deform_on_per_stage[idx]:\n            stage_kargs[\"block_class\"] = DeformBottleneckBlock\n            stage_kargs[\"deform_modulated\"] = deform_modulated\n            stage_kargs[\"deform_num_groups\"] = deform_num_groups\n        else:\n            stage_kargs[\"block_class\"] = BottleneckBlock\n        blocks = (\n            make_trident_stage(**stage_kargs)\n            if stage_idx == trident_stage_idx\n            else ResNet.make_stage(**stage_kargs)\n        )\n        in_channels = out_channels\n        out_channels *= 2\n        bottleneck_channels *= 2\n\n        if freeze_at >= stage_idx:\n            for block in blocks:\n                block.freeze()\n        stages.append(blocks)\n    return ResNet(stem, stages, out_features=out_features)\n"
  },
  {
    "path": "VPS_Module/projects/TridentNet/tridentnet/trident_conv.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport torch\nfrom torch import nn\nfrom torch.nn import functional as F\nfrom torch.nn.modules.utils import _pair\n\nfrom detectron2.layers.wrappers import _NewEmptyTensorOp\n\n\nclass TridentConv(nn.Module):\n    def __init__(\n        self,\n        in_channels,\n        out_channels,\n        kernel_size,\n        stride=1,\n        paddings=0,\n        dilations=1,\n        groups=1,\n        num_branch=1,\n        test_branch_idx=-1,\n        bias=False,\n        norm=None,\n        activation=None,\n    ):\n        super(TridentConv, self).__init__()\n        self.in_channels = in_channels\n        self.out_channels = out_channels\n        self.kernel_size = _pair(kernel_size)\n        self.num_branch = num_branch\n        self.stride = _pair(stride)\n        self.groups = groups\n        self.with_bias = bias\n        if isinstance(paddings, int):\n            paddings = [paddings] * self.num_branch\n        if isinstance(dilations, int):\n            dilations = [dilations] * self.num_branch\n        self.paddings = [_pair(padding) for padding in paddings]\n        self.dilations = [_pair(dilation) for dilation in dilations]\n        self.test_branch_idx = test_branch_idx\n        self.norm = norm\n        self.activation = activation\n\n        assert len({self.num_branch, len(self.paddings), len(self.dilations)}) == 1\n\n        self.weight = nn.Parameter(\n            torch.Tensor(out_channels, in_channels // groups, *self.kernel_size)\n        )\n        if bias:\n            self.bias = nn.Parameter(torch.Tensor(out_channels))\n        else:\n            self.bias = None\n\n        nn.init.kaiming_uniform_(self.weight, nonlinearity=\"relu\")\n        if self.bias is not None:\n            nn.init.constant_(self.bias, 0)\n\n    def forward(self, inputs):\n        num_branch = self.num_branch if self.training or self.test_branch_idx == -1 else 1\n        assert len(inputs) == num_branch\n\n        if inputs[0].numel() == 0:\n            output_shape = [\n                (i + 2 * p - (di * (k - 1) + 1)) // s + 1\n                for i, p, di, k, s in zip(\n                    inputs[0].shape[-2:], self.padding, self.dilation, self.kernel_size, self.stride\n                )\n            ]\n            output_shape = [input[0].shape[0], self.weight.shape[0]] + output_shape\n            return [_NewEmptyTensorOp.apply(input, output_shape) for input in inputs]\n\n        if self.training or self.test_branch_idx == -1:\n            outputs = [\n                F.conv2d(input, self.weight, self.bias, self.stride, padding, dilation, self.groups)\n                for input, dilation, padding in zip(inputs, self.dilations, self.paddings)\n            ]\n        else:\n            outputs = [\n                F.conv2d(\n                    inputs[0],\n                    self.weight,\n                    self.bias,\n                    self.stride,\n                    self.paddings[self.test_branch_idx],\n                    self.dilations[self.test_branch_idx],\n                    self.groups,\n                )\n            ]\n\n        if self.norm is not None:\n            outputs = [self.norm(x) for x in outputs]\n        if self.activation is not None:\n            outputs = [self.activation(x) for x in outputs]\n        return outputs\n\n    def extra_repr(self):\n        tmpstr = \"in_channels=\" + str(self.in_channels)\n        tmpstr += \", out_channels=\" + str(self.out_channels)\n        tmpstr += \", kernel_size=\" + str(self.kernel_size)\n        tmpstr += \", num_branch=\" + str(self.num_branch)\n        tmpstr += \", test_branch_idx=\" + str(self.test_branch_idx)\n        tmpstr += \", stride=\" + str(self.stride)\n        tmpstr += \", paddings=\" + str(self.paddings)\n        tmpstr += \", dilations=\" + str(self.dilations)\n        tmpstr += \", groups=\" + str(self.groups)\n        tmpstr += \", bias=\" + str(self.with_bias)\n        return tmpstr\n"
  },
  {
    "path": "VPS_Module/projects/TridentNet/tridentnet/trident_rcnn.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nfrom detectron2.layers import batched_nms\nfrom detectron2.modeling import ROI_HEADS_REGISTRY, StandardROIHeads\nfrom detectron2.modeling.roi_heads.roi_heads import Res5ROIHeads\nfrom detectron2.structures import Instances\n\n\ndef merge_branch_instances(instances, num_branch, nms_thresh, topk_per_image):\n    \"\"\"\n    Merge detection results from different branches of TridentNet.\n    Return detection results by applying non-maximum suppression (NMS) on bounding boxes\n    and keep the unsuppressed boxes and other instances (e.g mask) if any.\n\n    Args:\n        instances (list[Instances]): A list of N * num_branch instances that store detection\n            results. Contain N images and each image has num_branch instances.\n        num_branch (int): Number of branches used for merging detection results for each image.\n        nms_thresh (float):  The threshold to use for box non-maximum suppression. Value in [0, 1].\n        topk_per_image (int): The number of top scoring detections to return. Set < 0 to return\n            all detections.\n\n    Returns:\n        results: (list[Instances]): A list of N instances, one for each image in the batch,\n            that stores the topk most confidence detections after merging results from multiple\n            branches.\n    \"\"\"\n    if num_branch == 1:\n        return instances\n\n    batch_size = len(instances) // num_branch\n    results = []\n    for i in range(batch_size):\n        instance = Instances.cat([instances[i + batch_size * j] for j in range(num_branch)])\n\n        # Apply per-class NMS\n        keep = batched_nms(\n            instance.pred_boxes.tensor, instance.scores, instance.pred_classes, nms_thresh\n        )\n        keep = keep[:topk_per_image]\n        result = instance[keep]\n\n        results.append(result)\n\n    return results\n\n\n@ROI_HEADS_REGISTRY.register()\nclass TridentRes5ROIHeads(Res5ROIHeads):\n    \"\"\"\n    The TridentNet ROIHeads in a typical \"C4\" R-CNN model.\n    See :class:`Res5ROIHeads`.\n    \"\"\"\n\n    def __init__(self, cfg, input_shape):\n        super().__init__(cfg, input_shape)\n\n        self.num_branch = cfg.MODEL.TRIDENT.NUM_BRANCH\n        self.trident_fast = cfg.MODEL.TRIDENT.TEST_BRANCH_IDX != -1\n\n    def forward(self, images, features, proposals, targets=None):\n        \"\"\"\n        See :class:`Res5ROIHeads.forward`.\n        \"\"\"\n        num_branch = self.num_branch if self.training or not self.trident_fast else 1\n        all_targets = targets * num_branch if targets is not None else None\n        pred_instances, losses = super().forward(images, features, proposals, all_targets)\n        del images, all_targets, targets\n\n        if self.training:\n            return pred_instances, losses\n        else:\n            pred_instances = merge_branch_instances(\n                pred_instances,\n                num_branch,\n                self.box_predictor.test_nms_thresh,\n                self.box_predictor.test_topk_per_image,\n            )\n\n            return pred_instances, {}\n\n\n@ROI_HEADS_REGISTRY.register()\nclass TridentStandardROIHeads(StandardROIHeads):\n    \"\"\"\n    The `StandardROIHeads` for TridentNet.\n    See :class:`StandardROIHeads`.\n    \"\"\"\n\n    def __init__(self, cfg, input_shape):\n        super(TridentStandardROIHeads, self).__init__(cfg, input_shape)\n\n        self.num_branch = cfg.MODEL.TRIDENT.NUM_BRANCH\n        self.trident_fast = cfg.MODEL.TRIDENT.TEST_BRANCH_IDX != -1\n\n    def forward(self, images, features, proposals, targets=None):\n        \"\"\"\n        See :class:`Res5ROIHeads.forward`.\n        \"\"\"\n        # Use 1 branch if using trident_fast during inference.\n        num_branch = self.num_branch if self.training or not self.trident_fast else 1\n        # Duplicate targets for all branches in TridentNet.\n        all_targets = targets * num_branch if targets is not None else None\n        pred_instances, losses = super().forward(images, features, proposals, all_targets)\n        del images, all_targets, targets\n\n        if self.training:\n            return pred_instances, losses\n        else:\n            pred_instances = merge_branch_instances(\n                pred_instances,\n                num_branch,\n                self.box_predictor.test_nms_thresh,\n                self.box_predictor.test_topk_per_image,\n            )\n\n            return pred_instances, {}\n"
  },
  {
    "path": "VPS_Module/projects/TridentNet/tridentnet/trident_rpn.py",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\nimport torch\n\nfrom detectron2.modeling import PROPOSAL_GENERATOR_REGISTRY\nfrom detectron2.modeling.proposal_generator.rpn import RPN\nfrom detectron2.structures import ImageList\n\n\n@PROPOSAL_GENERATOR_REGISTRY.register()\nclass TridentRPN(RPN):\n    \"\"\"\n    Trident RPN subnetwork.\n    \"\"\"\n\n    def __init__(self, cfg, input_shape):\n        super(TridentRPN, self).__init__(cfg, input_shape)\n\n        self.num_branch = cfg.MODEL.TRIDENT.NUM_BRANCH\n        self.trident_fast = cfg.MODEL.TRIDENT.TEST_BRANCH_IDX != -1\n\n    def forward(self, images, features, gt_instances=None):\n        \"\"\"\n        See :class:`RPN.forward`.\n        \"\"\"\n        num_branch = self.num_branch if self.training or not self.trident_fast else 1\n        # Duplicate images and gt_instances for all branches in TridentNet.\n        all_images = ImageList(\n            torch.cat([images.tensor] * num_branch), images.image_sizes * num_branch\n        )\n        all_gt_instances = gt_instances * num_branch if gt_instances is not None else None\n\n        return super(TridentRPN, self).forward(all_images, features, all_gt_instances)\n"
  },
  {
    "path": "VPS_Module/setup.cfg",
    "content": "[isort]\nline_length=100\nmulti_line_output=3\ninclude_trailing_comma=True\nknown_standard_library=numpy,setuptools,mock\nskip=./datasets,docs\nskip_glob=*/__init__.py,**/configs/**,tests/config/**\nknown_myself=detectron2\nknown_third_party=fvcore,matplotlib,cv2,torch,torchvision,PIL,pycocotools,yacs,termcolor,cityscapesscripts,tabulate,tqdm,scipy,lvis,psutil,pkg_resources,caffe2,onnx,panopticapi,black,isort,av,iopath,omegaconf,hydra,yaml,pydoc,submitit,cloudpickle\nno_lines_before=STDLIB,THIRDPARTY\nsections=FUTURE,STDLIB,THIRDPARTY,myself,FIRSTPARTY,LOCALFOLDER\ndefault_section=FIRSTPARTY\n\n[mypy]\npython_version=3.6\nignore_missing_imports = True\nwarn_unused_configs = True\ndisallow_untyped_defs = True\ncheck_untyped_defs = True\nwarn_unused_ignores = True\nwarn_redundant_casts = True\nshow_column_numbers = True\nfollow_imports = silent\nallow_redefinition = True\n; Require all functions to be annotated\ndisallow_incomplete_defs = True\n"
  },
  {
    "path": "VPS_Module/setup.py",
    "content": "#!/usr/bin/env python\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport glob\nimport os\nimport shutil\nfrom os import path\nfrom setuptools import find_packages, setup\nfrom typing import List\nimport torch\nfrom torch.utils.cpp_extension import CUDA_HOME, CppExtension, CUDAExtension\n\ntorch_ver = [int(x) for x in torch.__version__.split(\".\")[:2]]\nassert torch_ver >= [1, 6], \"Requires PyTorch >= 1.6\"\n\n\ndef get_version():\n    init_py_path = path.join(path.abspath(path.dirname(__file__)), \"detectron2\", \"__init__.py\")\n    init_py = open(init_py_path, \"r\").readlines()\n    version_line = [l.strip() for l in init_py if l.startswith(\"__version__\")][0]\n    version = version_line.split(\"=\")[-1].strip().strip(\"'\\\"\")\n\n    # The following is used to build release packages.\n    # Users should never use it.\n    suffix = os.getenv(\"D2_VERSION_SUFFIX\", \"\")\n    version = version + suffix\n    if os.getenv(\"BUILD_NIGHTLY\", \"0\") == \"1\":\n        from datetime import datetime\n\n        date_str = datetime.today().strftime(\"%y%m%d\")\n        version = version + \".dev\" + date_str\n\n        new_init_py = [l for l in init_py if not l.startswith(\"__version__\")]\n        new_init_py.append('__version__ = \"{}\"\\n'.format(version))\n        with open(init_py_path, \"w\") as f:\n            f.write(\"\".join(new_init_py))\n    return version\n\n\ndef get_extensions():\n    this_dir = path.dirname(path.abspath(__file__))\n    extensions_dir = path.join(this_dir, \"detectron2\", \"layers\", \"csrc\")\n\n    main_source = path.join(extensions_dir, \"vision.cpp\")\n    sources = glob.glob(path.join(extensions_dir, \"**\", \"*.cpp\"))\n\n    from torch.utils.cpp_extension import ROCM_HOME\n\n    is_rocm_pytorch = (\n        True if ((torch.version.hip is not None) and (ROCM_HOME is not None)) else False\n    )\n    if is_rocm_pytorch:\n        assert torch_ver >= [1, 8], \"ROCM support requires PyTorch >= 1.8!\"\n\n    # common code between cuda and rocm platforms, for hipify version [1,0,0] and later.\n    source_cuda = glob.glob(path.join(extensions_dir, \"**\", \"*.cu\")) + glob.glob(\n        path.join(extensions_dir, \"*.cu\")\n    )\n    sources = [main_source] + sources\n\n    extension = CppExtension\n\n    extra_compile_args = {\"cxx\": []}\n    define_macros = []\n\n    if (torch.cuda.is_available() and ((CUDA_HOME is not None) or is_rocm_pytorch)) or os.getenv(\n        \"FORCE_CUDA\", \"0\"\n    ) == \"1\":\n        extension = CUDAExtension\n        sources += source_cuda\n\n        if not is_rocm_pytorch:\n            define_macros += [(\"WITH_CUDA\", None)]\n            extra_compile_args[\"nvcc\"] = [\n                \"-O3\",\n                \"-DCUDA_HAS_FP16=1\",\n                \"-D__CUDA_NO_HALF_OPERATORS__\",\n                \"-D__CUDA_NO_HALF_CONVERSIONS__\",\n                \"-D__CUDA_NO_HALF2_OPERATORS__\",\n            ]\n        else:\n            define_macros += [(\"WITH_HIP\", None)]\n            extra_compile_args[\"nvcc\"] = []\n\n        if torch_ver < [1, 7]:\n            # supported by https://github.com/pytorch/pytorch/pull/43931\n            CC = os.environ.get(\"CC\", None)\n            if CC is not None:\n                extra_compile_args[\"nvcc\"].append(\"-ccbin={}\".format(CC))\n\n    include_dirs = [extensions_dir]\n\n    ext_modules = [\n        extension(\n            \"detectron2._C\",\n            sources,\n            include_dirs=include_dirs,\n            define_macros=define_macros,\n            extra_compile_args=extra_compile_args,\n        )\n    ]\n\n    return ext_modules\n\n\ndef get_model_zoo_configs() -> List[str]:\n    \"\"\"\n    Return a list of configs to include in package for model zoo. Copy over these configs inside\n    detectron2/model_zoo.\n    \"\"\"\n\n    # Use absolute paths while symlinking.\n    source_configs_dir = path.join(path.dirname(path.realpath(__file__)), \"configs\")\n    destination = path.join(\n        path.dirname(path.realpath(__file__)), \"detectron2\", \"model_zoo\", \"configs\"\n    )\n    # Symlink the config directory inside package to have a cleaner pip install.\n\n    # Remove stale symlink/directory from a previous build.\n    if path.exists(source_configs_dir):\n        if path.islink(destination):\n            os.unlink(destination)\n        elif path.isdir(destination):\n            shutil.rmtree(destination)\n\n    if not path.exists(destination):\n        try:\n            os.symlink(source_configs_dir, destination)\n        except OSError:\n            # Fall back to copying if symlink fails: ex. on Windows.\n            shutil.copytree(source_configs_dir, destination)\n\n    config_paths = glob.glob(\"configs/**/*.yaml\", recursive=True) + glob.glob(\n        \"configs/**/*.py\", recursive=True\n    )\n    return config_paths\n\n\n# For projects that are relative small and provide features that are very close\n# to detectron2's core functionalities, we install them under detectron2.projects\nPROJECTS = {\n    \"detectron2.projects.point_rend\": \"projects/PointRend/point_rend\",\n    \"detectron2.projects.deeplab\": \"projects/DeepLab/deeplab\",\n    \"detectron2.projects.panoptic_deeplab\": \"projects/Panoptic-DeepLab/panoptic_deeplab\",\n}\n\nsetup(\n    name=\"detectron2\",\n    version=get_version(),\n    author=\"FAIR\",\n    url=\"https://github.com/facebookresearch/detectron2\",\n    description=\"Detectron2 is FAIR's next-generation research \"\n    \"platform for object detection and segmentation.\",\n    packages=find_packages(exclude=(\"configs\", \"tests*\")) + list(PROJECTS.keys()),\n    package_dir=PROJECTS,\n    package_data={\"detectron2.model_zoo\": get_model_zoo_configs()},\n    python_requires=\">=3.6\",\n    install_requires=[\n        # These dependencies are not pure-python.\n        # In general, avoid adding more dependencies like them because they are not\n        # guaranteed to be installable by `pip install` on all platforms.\n        # To tell if a package is pure-python, go to https://pypi.org/project/{name}/#files\n        \"Pillow>=7.1\",  # or use pillow-simd for better performance\n        \"matplotlib\",  # TODO move it to optional after we add opencv visualization\n        \"pycocotools>=2.0.2\",  # corresponds to https://github.com/ppwwyyxx/cocoapi\n        # Do not add opencv here. Just like pytorch, user should install\n        # opencv themselves, preferrably by OS's package manager, or by\n        # choosing the proper pypi package name at https://github.com/skvark/opencv-python\n        # The following are pure-python dependencies that should be easily installable\n        \"termcolor>=1.1\",\n        \"yacs>=0.1.8\",\n        \"tabulate\",\n        \"cloudpickle\",\n        \"tqdm>4.29.0\",\n        \"tensorboard\",\n        # Lock version of fvcore/iopath because they may have breaking changes\n        # NOTE: when updating fvcore/iopath version, make sure fvcore depends\n        # on compatible version of iopath.\n        \"fvcore>=0.1.5,<0.1.6\",  # required like this to make it pip installable\n        \"iopath>=0.1.7,<0.1.10\",\n        \"future\",  # used by caffe2\n        \"pydot\",  # used to save caffe2 SVGs\n        \"dataclasses; python_version<'3.7'\",\n        \"omegaconf>=2.1\",\n        \"hydra-core>=1.1\",\n        \"black==21.4b2\",\n        # If a new dependency is required at import time (in addition to runtime), it\n        # probably needs to exist in docs/requirements.txt, or as a mock in docs/conf.py\n    ],\n    extras_require={\n        # optional dependencies, required by some features\n        \"all\": [\n            \"shapely\",\n            \"pygments>=2.2\",\n            \"psutil\",\n            \"panopticapi @ https://github.com/cocodataset/panopticapi/archive/master.zip\",\n        ],\n        # dev dependencies. Install them by `pip install 'detectron2[dev]'`\n        \"dev\": [\n            \"flake8==3.8.1\",\n            \"isort==4.3.21\",\n            \"flake8-bugbear\",\n            \"flake8-comprehensions\",\n        ],\n    },\n    ext_modules=get_extensions(),\n    cmdclass={\"build_ext\": torch.utils.cpp_extension.BuildExtension},\n)\n"
  },
  {
    "path": "VPS_Module/tools/1_tracking.py",
    "content": "import numpy as np\nimport cv2\nimport os\nimport PIL.Image as Image\nfrom panopticapi.utils import id2rgb, rgb2id\n\nflow_path = \"/mnt/nas_8/group/lanxinyue/droid_slam_output/full_flow\" # \"shared_data/full_flow\"\nflow_names = os.listdir(flow_path)\nflow_names.sort()\ndepth_path = 'shared_data/depth'\ndepth_names = os.listdir(depth_path)\ndepth_names.sort()\nsegment_dir = \"shared_data/panoptic_segm_fusion/inference/pan_seg\"\nseg_list = os.listdir(segment_dir)\nseg_list.sort()\ndata_root =  \"shared_data/tmp\"\noutput_dir = os.path.join(data_root, \"vo_fusion_vo_track\") \nif not os.path.isdir(output_dir):\n    os.makedirs(output_dir)\n\nhas_depth = False\ncnt = 0\nref_segm = None\nseq_id = None\nflow_idx = 0\nfor idx in range(len(seg_list)): \n    cnt = cnt + 1\n    if has_depth:\n        cur_depth_f = depth_names[idx]\n    cur_mask_f = seg_list[idx]\n    cur_seq_id = seg_list[idx][:4]\n\n    print(cur_mask_f)\n    segmentation = np.array(Image.open(os.path.join(segment_dir, cur_mask_f)))\n    segmentation = rgb2id(segmentation)\n    # depth = np.array(Image.open(os.path.join(depth_path, cur_depth_f))) / 100\n    if has_depth:\n        depth = np.array(Image.open(os.path.join(depth_path, cur_depth_f))) / 100\n\n    if cur_seq_id != seq_id:\n        seq_id = cur_seq_id\n        ref_segm = segmentation\n        if has_depth:\n            ref_depth = depth\n        ref_flow = np.load(os.path.join(flow_path, flow_names[flow_idx]))\n        ref_flow = cv2.resize(ref_flow, (375, 1242))\n        ref_flow = np.transpose(ref_flow, (1,0,2))\n        flow_idx = flow_idx + 1\n        Image.fromarray(id2rgb(segmentation)).save(os.path.join(output_dir, cur_mask_f))\n        continue\n\n    rows, cols = ref_flow.shape[:2]\n    mask = np.zeros_like(segmentation)\n    dep = np.zeros_like(segmentation)\n\n    v = np.arange(rows)\n    v = v.reshape(rows, 1)\n    v = np.repeat(v, cols, axis=1)\n    u = np.arange(cols)\n    u = np.tile(u, (rows, 1))\n\n    u1 = (u + ref_flow[:,:,0]).astype(np.int32) # 1247\n    v1 = (v + ref_flow[:,:,1]).astype(np.int32) # 374\n\n    u = u.flatten()\n    v = v.flatten()\n    u1 = u1.flatten()\n    v1 = v1.flatten()\n\n    mm = (0 <= u1).__and__(u1 < cols).__and__(0 <= v1).__and__(v1 < rows)\n    u1 = u1[mm]\n    v1 = v1[mm]\n    u = u[mm]\n    v = v[mm]\n\n    if has_depth:\n        dep_uv = ref_depth.flatten()\n        dep_uv = dep_uv[mm]\n        encode_uvu1v1 = u * 1e14 + v * 1e10 + u1 * 1e6 + v1 * 1e2\n        dic = dict(zip(encode_uvu1v1, dep_uv))\n        ndic = np.array(sorted(dic.items(), key=lambda item:item[1], reverse=True))\n        new_encode_uvu1v1 = ndic[:,0]\n    \n        u = (new_encode_uvu1v1 // 1e14).astype(np.int32)\n        v = (new_encode_uvu1v1 % 1e14 // 1e10).astype(np.int32)\n        u1 = (new_encode_uvu1v1 % 1e10 // 1e6).astype(np.int32)\n        v1 = (new_encode_uvu1v1 % 1e6 // 1e2).astype(np.int32)\n\n        ref_depth = depth\n\n    mask[v1, u1] = ref_segm[v,u]\n\n    ref_segm = segmentation\n    Image.fromarray(id2rgb(mask)).save(os.path.join(output_dir, cur_mask_f))\n    if idx < len(flow_names) and cur_seq_id == seg_list[idx + 1][:4]:\n        ref_flow = np.load(os.path.join(flow_path, flow_names[flow_idx]))\n        ref_flow = cv2.resize(ref_flow, (375, 1242))\n        ref_flow = np.transpose(ref_flow, (1,0,2))\n        flow_idx = flow_idx + 1\nprint(cnt)\n\n"
  },
  {
    "path": "VPS_Module/tools/2_matching.py",
    "content": "import numpy as np\nimport cv2\nimport os\nimport PIL.Image as Image\nfrom panopticapi.utils import rgb2id, id2rgb\nimport six\nimport torch \n\noffset = 2 ** 30\nmax_ins = 10000 # cat * 10000 + inst_id\n\ndef _filter_thing(ps_map):\n    cat_mask = ps_map // max_ins\n    mask = cat_mask > 14 # 把 stuff 去掉 (id_generator)\n    ps_map[mask] = 0\n    mask = cat_mask == 0\n    ps_map[mask] = 0\n    return ps_map\n\ndef _ids_to_counts(id_array):\n    ids, counts = np.unique(id_array, return_counts=True)\n    return dict(six.moves.zip(ids, counts))\n\nsegment_dir = \"shared_data/panoptic_segm_fusion/inference/pan_seg\"\nseg_list = os.listdir(segment_dir)\nseg_list.sort()\n\ndata_root =  \"shared_data/tmp\"\npred_dir = os.path.join(data_root, \"vo_fusion_vo_track\")\npred_list = os.listdir(pred_dir)\npred_list.sort()\n\noutput_dir =  os.path.join(data_root, \"vo_fusion_vo_match\")\nif not os.path.isdir(output_dir):\n    os.makedirs(output_dir)\n\nref_match = None\nempty_id = 1\ncolor_map = None\nseq_id = None\nfor (seg_f, pred_f) in zip(seg_list, pred_list):\n    print(seg_f, pred_f)\n    cur_seq_id = seg_f[:4]\n    next_mask = rgb2id(np.array(Image.open(os.path.join(segment_dir, seg_f))))\n    pred_mask = rgb2id(np.array(Image.open(os.path.join(pred_dir, pred_f))))\n    pan_res = np.array(next_mask, copy=True)\n\n    next_map = _filter_thing(next_mask)\n    pred_map = _filter_thing(pred_mask) \n    \n    rows_list = np.unique(next_map)\n    cols_list = np.unique(pred_map)\n    rows_id = {v:k for k,v in enumerate(rows_list)}\n    cols_id = {v:k for k,v in enumerate(cols_list)}\n    rows = len(rows_list) \n    cols = len(cols_list)\n\n    if cur_seq_id != seq_id:\n        ref_match = None\n        seq_id = cur_seq_id\n\n    if ref_match == None: \n        ref_match = {}\n        for item in np.unique(next_map):\n            if item == 0:\n                continue\n            cat = item // max_ins\n            mask = next_map == item\n            new_id = cat * max_ins + empty_id\n            pan_res[mask] = new_id\n            empty_id = empty_id + 1\n            ref_match[item] = new_id\n        print(np.unique(ref_match))\n        Image.fromarray(id2rgb(pan_res)).save(os.path.join(output_dir, pred_f))\n        continue\n\n    # ==========================================\n    # 参考 dvpq 的match\n    # ==========================================\n    gt_areas = _ids_to_counts(next_map) \n    pred_areas = _ids_to_counts(pred_map)\n\n    int_ids = next_map.astype(np.int64) * offset + pred_map.astype(np.int64)\n    int_areas = _ids_to_counts(int_ids)\n\n    gt_match_pred = {}\n    \n    match_score = np.zeros((rows, cols))\n\n    for int_id, int_area in six.iteritems(int_areas):\n        gt_id = int(int_id // offset)\n        gt_cat = int(gt_id // max_ins)\n        pred_id = int(int_id % offset)\n        pred_cat = int(pred_id // max_ins)\n        if gt_cat != pred_cat or gt_id == 0: #  \n            continue\n        iou  = int_area / pred_areas[pred_id]\n        match_score[rows_id[gt_id]][cols_id[pred_id]] = iou\n\n    match_score = torch.tensor(match_score)\n    match_likelihood_embed, match_ids = torch.max(match_score, dim=1)\n    match_ids = match_ids.cpu().numpy().astype(np.int32).tolist()\n    match_likelihood = match_likelihood_embed.cpu().numpy()\n    ref_max_prob_idx = {}\n\n    for idx, match_id in enumerate(match_ids):\n        if match_id in ref_max_prob_idx:\n            if match_likelihood[idx] > match_likelihood[ref_max_prob_idx[match_id]]:\n                ref_max_prob_idx[match_id] = idx\n        else:\n            ref_max_prob_idx[match_id] = idx\n   \n    cur_match = {}\n    for idx, match_id in enumerate(match_ids): \n        ori_id = rows_list[idx]\n        mask = next_mask == ori_id\n        if ori_id == 0 or match_ids == 0:\n            continue\n        if match_id not in ref_max_prob_idx or ref_max_prob_idx[match_id] != idx:\n            cat = ori_id // max_ins\n            new_id = cat * max_ins + empty_id\n            empty_id = empty_id + 1\n        else:\n            new_id = ref_match[cols_list[match_id]]        \n        pan_res[mask] = new_id       \n        cur_match[ori_id] = new_id\n    ref_match = cur_match\n   \n    Image.fromarray(id2rgb(pan_res)).save(os.path.join(output_dir, pred_f))"
  },
  {
    "path": "VPS_Module/tools/3_preparing.py",
    "content": "import os\nimport json\nfrom PIL import Image\nimport numpy as np\nfrom panopticapi.utils import rgb2id, id2rgb, save_json, IdGenerator\nimport argparse\nfrom default import VKITTI_CATEGORIES\nimport pycocotools.mask as mask_util\nimport shutil\n\nmax_ins = 10000\n\ndef generate_json(filelist, scene_id, path, target_dir, json_file):   \n    images = []\n    anns = []\n    for f in filelist:\n        cur_seq_id = f[:4]\n        if cur_seq_id != scene_id:\n            continue\n        img_id = f[:-4]\n        print(img_id)\n        img = np.array(Image.open(os.path.join(path, f)))\n        images.append(\n            {\n                \"id\": img_id, \n                \"width\":img.shape[1], \n                \"height\": img.shape[0],\n                \"file_name\": f,\n            }\n        )\n        pan_res = rgb2id(img)\n        item = np.unique(pan_res)\n\n        segments_info = []\n        for i in item:\n            if i == 0:\n                continue\n            mask = pan_res == i     \n            segments_info.append(\n                {\n                    \"id\": int(i),\n                    \"category_id\": int(i // max_ins),\n                    \"iscrowd\": 0,\n                }\n            )\n        anns.append(\n            {\n                \"image_id\": img_id,\n                \"file_name\": f,\n                \"segments_info\": segments_info,\n            }\n        )\n        dst = os.path.join(target_dir, f)\n        src = os.path.join(path, f)\n        shutil.copyfile(src, dst)\n\n    annotations = {\n                \"images\": images,\n                \"annotations\": anns,\n                \"categories\": VKITTI_CATEGORIES,\n              }\n    save_json(annotations, json_file)\n    print(\"done====\" + json_file)\n\ncategories_dict = {el['trainId']: el for el in VKITTI_CATEGORIES}\nid_generator = IdGenerator(categories_dict)\nstuff_cat_map = {}\nfor i in range(1,12):\n    new_id, color = id_generator.get_id_and_color(i)\n    stuff_cat_map[new_id] = i\n\npath = \"shared_data/tmp/vo_fusion_vo_match\" \nfilelist = os.listdir(path)\nfilelist.sort()\n\njson_root = \"shared_data/json\" \nif not os.path.isdir(json_root):\n    os.makedirs(json_root)\ntarget_root = \"shared_data/final_vps_res\"\ndic = {\n    '0001': 'vo_fusion_vo_track_s1.json',\n    '0002': 'vo_fusion_vo_track_s2.json',\n    '0006': 'vo_fusion_vo_track_s6.json',\n    '0018': 'vo_fusion_vo_track_s18.json',\n    '0020': 'vo_fusion_vo_track_s20.json',\n}\nsce_dic = {\n    '0001': 's1',\n    '0002': 's2',\n    '0006': 's6',\n    '0018': 's18',\n    '0020': 's20',\n}\nfor scene_id, json_name in dic.items():\n    json_file = os.path.join(json_root, json_name)\n    target_dir = os.path.join(target_root, sce_dic[scene_id])\n    if not os.path.isdir(target_dir):\n        os.makedirs(target_dir)\n    generate_json(filelist, scene_id, path, target_dir, json_file)\n"
  },
  {
    "path": "VPS_Module/tools/4_eval_vpq.py",
    "content": "# -------------------------------------------------------------------\n# Video Panoptic Segmentation\n#\n# VPQ evaluation code by tube (video segment) matching\n# Inference on every frames and evaluation on every 5 frames.\n# ------------------------------------------------------------------\n\nimport argparse\nimport sys\nimport os\nimport os.path\nimport numpy as np\nfrom PIL import Image\nimport multiprocessing\nimport time\nimport json\nfrom collections import defaultdict\nimport copy\nimport pdb\nfrom panopticapi.utils import id2rgb, rgb2id\n\nclass PQStatCat():\n    def __init__(self):\n        self.iou = 0.0\n        self.tp = 0\n        self.fp = 0\n        self.fn = 0\n\n    def __iadd__(self, pq_stat_cat):\n        self.iou += pq_stat_cat.iou\n        self.tp += pq_stat_cat.tp\n        self.fp += pq_stat_cat.fp\n        self.fn += pq_stat_cat.fn\n        return self\n\nclass PQStat():\n    def __init__(self):\n        self.pq_per_cat = defaultdict(PQStatCat)\n\n    def __getitem__(self, i):\n        return self.pq_per_cat[i]\n\n    def __iadd__(self, pq_stat):\n        for label, pq_stat_cat in pq_stat.pq_per_cat.items():\n            self.pq_per_cat[label] += pq_stat_cat\n        return self\n\n    def pq_average(self, categories, isthing):\n        pq, sq, rq, n = 0, 0, 0, 0\n        per_class_results = {}\n        for label, label_info in categories.items():\n            if isthing is not None:\n                cat_isthing = label_info['isthing'] == 1\n                if isthing != cat_isthing:\n                    continue\n            iou = self.pq_per_cat[label].iou\n            tp = self.pq_per_cat[label].tp\n            fp = self.pq_per_cat[label].fp\n            fn = self.pq_per_cat[label].fn\n            if tp + fp + fn == 0:\n                per_class_results[label] = {'pq': 0.0, 'sq': 0.0, 'rq': 0.0, 'iou': 0.0, 'tp':0, 'fp':0, 'fn':0}\n                continue\n            n += 1\n            pq_class = iou / (tp + 0.5 * fp + 0.5 * fn)\n            sq_class = iou / tp if tp != 0 else 0\n            rq_class = tp / (tp + 0.5 * fp + 0.5 * fn)\n            per_class_results[label] = {'pq': pq_class, 'sq': sq_class, 'rq': rq_class, 'iou': iou, 'tp':tp, 'fp':fp, 'fn':fn}\n            pq += pq_class\n            sq += sq_class\n            rq += rq_class\n        if n == 0:\n            return {'pq': pq , 'sq': sq , 'rq': rq , 'n': n}, per_class_results\n    \n        return {'pq': pq / n, 'sq': sq / n, 'rq': rq / n, 'n': n}, per_class_results\n\ndef vpq_compute_single_core(gt_pred_set, categories, nframes=2):\n    OFFSET = 256 * 256 * 256\n    VOID = 0\n    vpq_stat = PQStat()\n\n    # Iterate over the video frames 0::T-λ\n    for idx in range(0, len(gt_pred_set)-nframes+1): \n        vid_pan_gt, vid_pan_pred = [], []\n        gt_segms_list, pred_segms_list = [], []\n\n        # Matching nframes-long tubes.\n        # Collect tube IoU, TP, FP, FN\n        for i, (gt_json, pred_json, gt_pan, pred_pan, gt_image_json) in enumerate(gt_pred_set[idx:idx+nframes]):\n            #### Step1. Collect frame-level pan_gt, pan_pred, etc.\n            gt_pan, pred_pan = np.uint32(gt_pan), np.uint32(pred_pan)\n\n            pan_gt = rgb2id(gt_pan) \n            pan_pred = rgb2id(pred_pan) \n\n            gt_segms = {}\n            for el in gt_json['segments_info']: \n                if el['id'] in gt_segms:\n                    gt_segms[el['id']]['area'] += el['area']\n                else:\n                    gt_segms[el['id']] = copy.deepcopy(el)\n            pred_segms = {}\n            for el in pred_json['segments_info']:\n                if el['id'] in pred_segms:\n                    pred_segms[el['id']]['area'] += el['area']\n                else:\n                    pred_segms[el['id']] = copy.deepcopy(el)\n\n            # predicted segments area calculation + prediction sanity checks\n            pred_labels_set = set(el['id'] for el in pred_json['segments_info'])\n            labels, labels_cnt = np.unique(pan_pred, return_counts=True) \n            for label, label_cnt in zip(labels, labels_cnt):\n                if label not in pred_segms:\n                    if label == VOID:\n                        continue\n                    raise KeyError('Segment with ID {} is presented in PNG and not presented in JSON.'.format(label))\n                pred_segms[label]['area'] = label_cnt\n                pred_labels_set.remove(label)\n                if pred_segms[label]['category_id'] not in categories:\n                    raise KeyError('Segment with ID {} has unknown category_id {}.'.format(label, pred_segms[label]['category_id']))\n            if len(pred_labels_set) != 0:\n                raise KeyError(\n                    'The following segment IDs {} are presented in JSON and not presented in PNG.'.format(list(pred_labels_set)))\n\n            vid_pan_gt.append(pan_gt)\n            vid_pan_pred.append(pan_pred)\n            gt_segms_list.append(gt_segms)\n            pred_segms_list.append(pred_segms)\n\n        #### Step 2. Concatenate the collected items -> tube-level. \n        vid_pan_gt = np.stack(vid_pan_gt) \n        vid_pan_pred = np.stack(vid_pan_pred) \n        vid_gt_segms, vid_pred_segms = {}, {} \n        for gt_segms, pred_segms in zip(gt_segms_list, pred_segms_list): \n            # aggregate into tube 'area'\n            for k in gt_segms.keys():\n                if not k in vid_gt_segms:\n                    vid_gt_segms[k] = gt_segms[k]\n                else:\n                    # print(\"add gt area: \",k)\n                    vid_gt_segms[k]['area'] += gt_segms[k]['area']\n            for k in pred_segms.keys():\n                if not k in vid_pred_segms:\n                    vid_pred_segms[k] = pred_segms[k]\n                else:\n                    # print(\"add pred area: \",k)\n                    vid_pred_segms[k]['area'] += pred_segms[k]['area']\n\n        #### Step3. Confusion matrix calculation\n        vid_pan_gt_pred = vid_pan_gt.astype(np.uint64) * OFFSET + vid_pan_pred.astype(np.uint64)\n        gt_pred_map = {}\n        labels, labels_cnt = np.unique(vid_pan_gt_pred, return_counts=True)\n        for label, intersection in zip(labels, labels_cnt):\n            gt_id = label // OFFSET\n            pred_id = label % OFFSET\n            gt_pred_map[(gt_id, pred_id)] = intersection\n\n        # count all matched pairs\n        gt_matched = set()\n        pred_matched = set()\n        tp = 0\n        fp = 0\n        fn = 0\n\n        #### Step4. Tube matching\n        for label_tuple, intersection in gt_pred_map.items():\n            gt_label, pred_label = label_tuple\n\n            if gt_label not in vid_gt_segms:\n                continue\n            if pred_label not in vid_pred_segms:\n                continue\n            if vid_gt_segms[gt_label]['iscrowd'] == 1:\n                continue\n            if vid_gt_segms[gt_label]['category_id'] != \\\n                    vid_pred_segms[pred_label]['category_id']:\n                continue\n\n            union = vid_pred_segms[pred_label]['area'] + vid_gt_segms[gt_label]['area'] - intersection - gt_pred_map.get(\n                (VOID, pred_label), 0)\n            iou = intersection / union\n            assert iou <= 1.0, 'INVALID IOU VALUE : %d'%(gt_label)\n            # count true positives\n            if iou > 0.5:\n                vpq_stat[vid_gt_segms[gt_label]['category_id']].tp += 1\n                vpq_stat[vid_gt_segms[gt_label]['category_id']].iou += iou\n                gt_matched.add(gt_label)\n                pred_matched.add(pred_label)\n                tp += 1\n\n        # count false negatives\n        crowd_labels_dict = {}\n        for gt_label, gt_info in vid_gt_segms.items():\n            if gt_label in gt_matched:\n                continue\n            # crowd segments are ignored\n            if gt_info['iscrowd'] == 1:\n                crowd_labels_dict[gt_info['category_id']] = gt_label\n                continue\n            vpq_stat[gt_info['category_id']].fn += 1\n            fn += 1\n\n        # count false positives\n        for pred_label, pred_info in vid_pred_segms.items():\n            if pred_label in pred_matched:\n                continue\n            # intersection of the segment with VOID\n            intersection = gt_pred_map.get((VOID, pred_label), 0)\n            # plus intersection with corresponding CROWD region if it exists\n            if pred_info['category_id'] in crowd_labels_dict:\n                intersection += gt_pred_map.get((crowd_labels_dict[pred_info['category_id']], pred_label), 0)\n            # predicted segment is ignored if more than half of the segment correspond to VOID and CROWD regions\n            if intersection / pred_info['area'] > 0.5:\n                continue\n            vpq_stat[pred_info['category_id']].fp += 1\n            fp += 1\n\n    return vpq_stat\n\n\ndef vpq_compute(gt_pred_split, categories, nframes, output_dir):\n    start_time = time.time()\n    vpq_stat = PQStat()\n    for idx, gt_pred_set in enumerate(gt_pred_split):\n        tmp = vpq_compute_single_core(gt_pred_set, categories, nframes=nframes)\n        vpq_stat += tmp\n\n    # hyperparameter: window size k\n    k = nframes\n    print('==> %d-frame vpq_stat:'%(k), time.time()-start_time, 'sec')\n    metrics = [(\"All\", None), (\"Things\", True), (\"Stuff\", False)]\n    results = {}\n    for name, isthing in metrics:\n        results[name], per_class_results = vpq_stat.pq_average(categories, isthing=isthing)\n        if name == 'All':\n            results['per_class'] = per_class_results\n\n    vpq_all = 100 * results['All']['pq']\n    vpq_thing = 100 * results['Things']['pq']\n    vpq_stuff = 100 * results['Stuff']['pq']\n\n    save_name = os.path.join(output_dir, 'vpq-%d.txt'%(k))\n    f = open(save_name, 'a') if save_name else None\n    f.write(\"================================================\\n\")\n    f.write(\"{:10s}| {:>5s}  {:>5s}  {:>5s} {:>5s}\".format(\"\", \"PQ\", \"SQ\", \"RQ\", \"N\\n\"))\n    f.write(\"-\" * (10 + 7 * 4)+'\\n')\n    for name, _isthing in metrics:\n        f.write(\"{:10s}| {:5.1f}  {:5.1f}  {:5.1f} {:5d}\\n\".format(name, 100 * results[name]['pq'], 100 * results[name]['sq'], 100 * results[name]['rq'], results[name]['n']))\n    f.write(\"{:4s}| {:>5s} {:>5s} {:>5s} {:>6s} {:>7s} {:>7s} {:>7s}\\n\".format(\"IDX\", \"PQ\", \"SQ\", \"RQ\", \"IoU\", \"TP\", \"FP\", \"FN\"))\n    for idx, result in results['per_class'].items():\n        f.write(\"{:4d} | {:5.1f} {:5.1f} {:5.1f} {:6.1f} {:7d} {:7d} {:7d}\\n\".format(idx, 100 * result['pq'], 100 * result['sq'], 100 * result['rq'], result['iou'], result['tp'], result['fp'], result['fn']))\n    if save_name:\n        f.close()\n\n    return vpq_all, vpq_thing, vpq_stuff\n\ndef cal_vpq_compute(gt_json, pred_json, gt_folder, pred_folder, output_dir):\n    print(\"begin vpq computation.....\")\n    with open(pred_json, 'r') as f:\n        pred_jsons = json.load(f)\n    with open(gt_json, 'r') as f:\n        gt_jsons = json.load(f)\n    categories = gt_jsons['categories']\n    categories = {el['trainId']: el for el in categories} # 0,7,8...\n\n    start_time = time.time()\n    files = [item['file_name'] for item in gt_jsons['images']]\n    files.sort()\n    gt_pans = []\n    for idx, file in enumerate(files):\n        image = np.array(Image.open(os.path.join(gt_folder, file)))\n        gt_pans.append(image)\n    print('==> gt_pans:', len(gt_pans), '//', time.time() - start_time,'sec')\n\n    files = [item['file_name'] for item in pred_jsons['images']]\n    pred_pans = []\n    for idx, file in enumerate(files):\n        image = np.array(Image.open(os.path.join(pred_folder, file)))\n        pred_pans.append(image)\n    print('==> pred_pans:', len(pred_pans), '//', time.time() - start_time,'sec')\n    assert len(gt_pans) == len(pred_pans), \"number of prediction does not match with the groud truth.\"\n\n    gt_image_jsons = gt_jsons['images']\n    gt_jsons, pred_jsons = gt_jsons['annotations'], pred_jsons['annotations']\n    vid_num = 1 \n\n    gt_pred_all = list(zip(gt_jsons, pred_jsons, gt_pans, pred_pans, gt_image_jsons))\n    gt_pred_split = np.array_split(gt_pred_all, vid_num)\n\n    start_time = time.time()\n    vpq_all, vpq_thing, vpq_stuff = [], [], []\n\n    output_filename = os.path.join(output_dir, 'vpq-final.txt')\n    output_file = open(output_filename, 'a')\n\n    # for k in [0,5,10,15] --> num_frames_w_gt [1,2,3,4]\n    for nframes in [1,5,10,15,20]:\n        gt_pred_split_ = copy.deepcopy(gt_pred_split)\n        vpq_all_, vpq_thing_, vpq_stuff_ = vpq_compute(\n                    gt_pred_split_, categories, nframes, output_dir)\n        del gt_pred_split_\n        print(vpq_all_, vpq_thing_, vpq_stuff_)\n        vpq_all.append(vpq_all_)\n        vpq_thing.append(vpq_thing_)\n        vpq_stuff.append(vpq_stuff_)\n        output_file.write('==> %d-frame vpq_stat: '%(nframes))\n        output_file.write('%.4f, %.4f, %.4f\\n'%(vpq_all_, vpq_thing_, vpq_stuff_))\n    \n    output_file.write(\"vpq_all:%.4f\\n\"%(sum(vpq_all)/len(vpq_all)))\n    output_file.write(\"vpq_thing:%.4f\\n\"%(sum(vpq_thing)/len(vpq_thing)))\n    output_file.write(\"vpq_stuff:%.4f\\n\"%(sum(vpq_stuff)/len(vpq_stuff)))\n    output_file.close()\n    print(\"--vpq_all:\",sum(vpq_all)/len(vpq_all))\n    print(\"--vpq_thing:\",sum(vpq_thing)/len(vpq_thing))\n    print(\"--vpq_stuff:\",sum(vpq_stuff)/len(vpq_stuff))\n    print('==> DONE')\n\n\n\nif __name__ == \"__main__\":\n\n    import argparse\n\n    parser = argparse.ArgumentParser()\n    parser.add_argument(\"--gt-json\")\n    parser.add_argument(\"--gt-dir\")\n    parser.add_argument(\"--pred-json\")\n    parser.add_argument(\"--pred-dir\")\n    parser.add_argument(\"--output\")\n    args = parser.parse_args()\n    if not os.path.isdir(args.output):\n        os.makedirs(args.output)\n\n    cal_vpq_compute(\n        gt_json = args.gt_json,\n        pred_json = args.pred_json,\n        gt_folder = args.gt_dir,\n        pred_folder = args.pred_dir,\n        output_dir = args.output,\n        )"
  },
  {
    "path": "VPS_Module/tools/README.md",
    "content": "\nThis directory contains a few example scripts that demonstrate features of detectron2.\n\n\n* `train_net.py`\n\nAn example training script that's made to train builtin models of detectron2.\n\nFor usage, see [GETTING_STARTED.md](../GETTING_STARTED.md).\n\n* `plain_train_net.py`\n\nSimilar to `train_net.py`, but implements a training loop instead of using `Trainer`.\nThis script includes fewer features but it may be more friendly to hackers.\n\n* `benchmark.py`\n\nBenchmark the training speed, inference speed or data loading speed of a given config.\n\nUsage:\n```\npython benchmark.py --config-file config.yaml --task train/eval/data [optional DDP flags]\n```\n\n* `analyze_model.py`\n\nAnalyze FLOPs, parameters, activations of a detectron2 model.  See its `--help` for usage.\n\n* `visualize_json_results.py`\n\nVisualize the json instance detection/segmentation results dumped by `COCOEvalutor` or `LVISEvaluator`\n\nUsage:\n```\npython visualize_json_results.py --input x.json --output dir/ --dataset coco_2017_val\n```\nIf not using a builtin dataset, you'll need your own script or modify this script.\n\n* `visualize_data.py`\n\nVisualize ground truth raw annotations or training data (after preprocessing/augmentations).\n\nUsage:\n```\npython visualize_data.py --config-file config.yaml --source annotation/dataloader --output-dir dir/ [--show]\n```\n\nNOTE: the script does not stop by itself when using `--source dataloader` because a training\ndataloader is usually infinite.\n"
  },
  {
    "path": "VPS_Module/tools/__init__.py",
    "content": ""
  },
  {
    "path": "VPS_Module/tools/analyze_model.py",
    "content": "# -*- coding: utf-8 -*-\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport logging\nimport numpy as np\nfrom collections import Counter\nimport tqdm\nfrom fvcore.nn import flop_count_table  # can also try flop_count_str\n\nfrom detectron2.checkpoint import DetectionCheckpointer\nfrom detectron2.config import CfgNode, LazyConfig, get_cfg, instantiate\nfrom detectron2.data import build_detection_test_loader\nfrom detectron2.engine import default_argument_parser\nfrom detectron2.modeling import build_model\nfrom detectron2.utils.analysis import (\n    FlopCountAnalysis,\n    activation_count_operators,\n    parameter_count_table,\n)\nfrom detectron2.utils.logger import setup_logger\n\nlogger = logging.getLogger(\"detectron2\")\n\n\ndef setup(args):\n    if args.config_file.endswith(\".yaml\"):\n        cfg = get_cfg()\n        cfg.merge_from_file(args.config_file)\n        cfg.DATALOADER.NUM_WORKERS = 0\n        cfg.merge_from_list(args.opts)\n        cfg.freeze()\n    else:\n        cfg = LazyConfig.load(args.config_file)\n        cfg = LazyConfig.apply_overrides(cfg, args.opts)\n    setup_logger(name=\"fvcore\")\n    setup_logger()\n    return cfg\n\n\ndef do_flop(cfg):\n    if isinstance(cfg, CfgNode):\n        data_loader = build_detection_test_loader(cfg, cfg.DATASETS.TEST[0])\n        model = build_model(cfg)\n        DetectionCheckpointer(model).load(cfg.MODEL.WEIGHTS)\n    else:\n        data_loader = instantiate(cfg.dataloader.test)\n        model = instantiate(cfg.model)\n        model.to(cfg.train.device)\n        DetectionCheckpointer(model).load(cfg.train.init_checkpoint)\n    model.eval()\n\n    counts = Counter()\n    total_flops = []\n    for idx, data in zip(tqdm.trange(args.num_inputs), data_loader):  # noqa\n        flops = FlopCountAnalysis(model, data)\n        if idx > 0:\n            flops.unsupported_ops_warnings(False).uncalled_modules_warnings(False)\n        counts += flops.by_operator()\n        total_flops.append(flops.total())\n\n    logger.info(\"Flops table computed from only one input sample:\\n\" + flop_count_table(flops))\n    logger.info(\n        \"Average GFlops for each type of operators:\\n\"\n        + str([(k, v / (idx + 1) / 1e9) for k, v in counts.items()])\n    )\n    logger.info(\n        \"Total GFlops: {:.1f}±{:.1f}\".format(np.mean(total_flops) / 1e9, np.std(total_flops) / 1e9)\n    )\n\n\ndef do_activation(cfg):\n    if isinstance(cfg, CfgNode):\n        data_loader = build_detection_test_loader(cfg, cfg.DATASETS.TEST[0])\n        model = build_model(cfg)\n        DetectionCheckpointer(model).load(cfg.MODEL.WEIGHTS)\n    else:\n        data_loader = instantiate(cfg.dataloader.test)\n        model = instantiate(cfg.model)\n        model.to(cfg.train.device)\n        DetectionCheckpointer(model).load(cfg.train.init_checkpoint)\n    model.eval()\n\n    counts = Counter()\n    total_activations = []\n    for idx, data in zip(tqdm.trange(args.num_inputs), data_loader):  # noqa\n        count = activation_count_operators(model, data)\n        counts += count\n        total_activations.append(sum(count.values()))\n    logger.info(\n        \"(Million) Activations for Each Type of Operators:\\n\"\n        + str([(k, v / idx) for k, v in counts.items()])\n    )\n    logger.info(\n        \"Total (Million) Activations: {}±{}\".format(\n            np.mean(total_activations), np.std(total_activations)\n        )\n    )\n\n\ndef do_parameter(cfg):\n    if isinstance(cfg, CfgNode):\n        model = build_model(cfg)\n    else:\n        model = instantiate(cfg.model)\n    logger.info(\"Parameter Count:\\n\" + parameter_count_table(model, max_depth=5))\n\n\ndef do_structure(cfg):\n    if isinstance(cfg, CfgNode):\n        model = build_model(cfg)\n    else:\n        model = instantiate(cfg.model)\n    logger.info(\"Model Structure:\\n\" + str(model))\n\n\nif __name__ == \"__main__\":\n    parser = default_argument_parser(\n        epilog=\"\"\"\nExamples:\n\nTo show parameters of a model:\n$ ./analyze_model.py --tasks parameter \\\\\n    --config-file ../configs/COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_1x.yaml\n\nFlops and activations are data-dependent, therefore inputs and model weights\nare needed to count them:\n\n$ ./analyze_model.py --num-inputs 100 --tasks flop \\\\\n    --config-file ../configs/COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_1x.yaml \\\\\n    MODEL.WEIGHTS /path/to/model.pkl\n\"\"\"\n    )\n    parser.add_argument(\n        \"--tasks\",\n        choices=[\"flop\", \"activation\", \"parameter\", \"structure\"],\n        required=True,\n        nargs=\"+\",\n    )\n    parser.add_argument(\n        \"-n\",\n        \"--num-inputs\",\n        default=100,\n        type=int,\n        help=\"number of inputs used to compute statistics for flops/activations, \"\n        \"both are data dependent.\",\n    )\n    args = parser.parse_args()\n    assert not args.eval_only\n    assert args.num_gpus == 1\n\n    cfg = setup(args)\n\n    for task in args.tasks:\n        {\n            \"flop\": do_flop,\n            \"activation\": do_activation,\n            \"parameter\": do_parameter,\n            \"structure\": do_structure,\n        }[task](cfg)\n"
  },
  {
    "path": "VPS_Module/tools/benchmark.py",
    "content": "#!/usr/bin/env python\n# Copyright (c) Facebook, Inc. and its affiliates.\n\"\"\"\nA script to benchmark builtin models.\n\nNote: this script has an extra dependency of psutil.\n\"\"\"\n\nimport itertools\nimport logging\nimport psutil\nimport torch\nimport tqdm\nfrom fvcore.common.timer import Timer\nfrom torch.nn.parallel import DistributedDataParallel\n\nfrom detectron2.checkpoint import DetectionCheckpointer\nfrom detectron2.config import LazyConfig, get_cfg, instantiate\nfrom detectron2.data import (\n    DatasetFromList,\n    build_detection_test_loader,\n    build_detection_train_loader,\n)\nfrom detectron2.data.benchmark import DataLoaderBenchmark\nfrom detectron2.engine import AMPTrainer, SimpleTrainer, default_argument_parser, hooks, launch\nfrom detectron2.modeling import build_model\nfrom detectron2.solver import build_optimizer\nfrom detectron2.utils import comm\nfrom detectron2.utils.collect_env import collect_env_info\nfrom detectron2.utils.events import CommonMetricPrinter\nfrom detectron2.utils.logger import setup_logger\n\nlogger = logging.getLogger(\"detectron2\")\n\n\ndef setup(args):\n    if args.config_file.endswith(\".yaml\"):\n        cfg = get_cfg()\n        cfg.merge_from_file(args.config_file)\n        cfg.SOLVER.BASE_LR = 0.001  # Avoid NaNs. Not useful in this script anyway.\n        cfg.merge_from_list(args.opts)\n        cfg.freeze()\n    else:\n        cfg = LazyConfig.load(args.config_file)\n        cfg = LazyConfig.apply_overrides(cfg, args.opts)\n    setup_logger(distributed_rank=comm.get_rank())\n    return cfg\n\n\ndef create_data_benchmark(cfg, args):\n    if args.config_file.endswith(\".py\"):\n        dl_cfg = cfg.dataloader.train\n        dl_cfg._target_ = DataLoaderBenchmark\n        return instantiate(dl_cfg)\n    else:\n        kwargs = build_detection_train_loader.from_config(cfg)\n        kwargs.pop(\"aspect_ratio_grouping\", None)\n        kwargs[\"_target_\"] = DataLoaderBenchmark\n        return instantiate(kwargs)\n\n\ndef RAM_msg():\n    vram = psutil.virtual_memory()\n    return \"RAM Usage: {:.2f}/{:.2f} GB\".format(\n        (vram.total - vram.available) / 1024 ** 3, vram.total / 1024 ** 3\n    )\n\n\ndef benchmark_data(args):\n    cfg = setup(args)\n    logger.info(\"After spawning \" + RAM_msg())\n\n    benchmark = create_data_benchmark(cfg, args)\n    benchmark.benchmark_distributed(250, 10)\n    # test for a few more rounds\n    for k in range(10):\n        logger.info(f\"Iteration {k} \" + RAM_msg())\n        benchmark.benchmark_distributed(250, 1)\n\n\ndef benchmark_data_advanced(args):\n    # benchmark dataloader with more details to help analyze performance bottleneck\n    cfg = setup(args)\n    benchmark = create_data_benchmark(cfg, args)\n\n    if comm.get_rank() == 0:\n        benchmark.benchmark_dataset(100)\n        benchmark.benchmark_mapper(100)\n        benchmark.benchmark_workers(100, warmup=10)\n        benchmark.benchmark_IPC(100, warmup=10)\n    if comm.get_world_size() > 1:\n        benchmark.benchmark_distributed(100)\n        logger.info(\"Rerun ...\")\n        benchmark.benchmark_distributed(100)\n\n\ndef benchmark_train(args):\n    cfg = setup(args)\n    model = build_model(cfg)\n    logger.info(\"Model:\\n{}\".format(model))\n    if comm.get_world_size() > 1:\n        model = DistributedDataParallel(\n            model, device_ids=[comm.get_local_rank()], broadcast_buffers=False\n        )\n    optimizer = build_optimizer(cfg, model)\n    checkpointer = DetectionCheckpointer(model, optimizer=optimizer)\n    checkpointer.load(cfg.MODEL.WEIGHTS)\n\n    cfg.defrost()\n    cfg.DATALOADER.NUM_WORKERS = 2\n    data_loader = build_detection_train_loader(cfg)\n    dummy_data = list(itertools.islice(data_loader, 100))\n\n    def f():\n        data = DatasetFromList(dummy_data, copy=False, serialize=False)\n        while True:\n            yield from data\n\n    max_iter = 400\n    trainer = (AMPTrainer if cfg.SOLVER.AMP.ENABLED else SimpleTrainer)(model, f(), optimizer)\n    trainer.register_hooks(\n        [\n            hooks.IterationTimer(),\n            hooks.PeriodicWriter([CommonMetricPrinter(max_iter)]),\n            hooks.TorchProfiler(\n                lambda trainer: trainer.iter == max_iter - 1, cfg.OUTPUT_DIR, save_tensorboard=True\n            ),\n        ]\n    )\n    trainer.train(1, max_iter)\n\n\n@torch.no_grad()\ndef benchmark_eval(args):\n    cfg = setup(args)\n    if args.config_file.endswith(\".yaml\"):\n        model = build_model(cfg)\n        DetectionCheckpointer(model).load(cfg.MODEL.WEIGHTS)\n\n        cfg.defrost()\n        cfg.DATALOADER.NUM_WORKERS = 0\n        data_loader = build_detection_test_loader(cfg, cfg.DATASETS.TEST[0])\n    else:\n        model = instantiate(cfg.model)\n        model.to(cfg.train.device)\n        DetectionCheckpointer(model).load(cfg.train.init_checkpoint)\n\n        cfg.dataloader.num_workers = 0\n        data_loader = instantiate(cfg.dataloader.test)\n\n    model.eval()\n    logger.info(\"Model:\\n{}\".format(model))\n    dummy_data = DatasetFromList(list(itertools.islice(data_loader, 100)), copy=False)\n\n    def f():\n        while True:\n            yield from dummy_data\n\n    for k in range(5):  # warmup\n        model(dummy_data[k])\n\n    max_iter = 300\n    timer = Timer()\n    with tqdm.tqdm(total=max_iter) as pbar:\n        for idx, d in enumerate(f()):\n            if idx == max_iter:\n                break\n            model(d)\n            pbar.update()\n    logger.info(\"{} iters in {} seconds.\".format(max_iter, timer.seconds()))\n\n\nif __name__ == \"__main__\":\n    parser = default_argument_parser()\n    parser.add_argument(\"--task\", choices=[\"train\", \"eval\", \"data\", \"data_advanced\"], required=True)\n    args = parser.parse_args()\n    assert not args.eval_only\n\n    logger.info(\"Environment info:\\n\" + collect_env_info())\n    if \"data\" in args.task:\n        print(\"Initial \" + RAM_msg())\n    if args.task == \"data\":\n        f = benchmark_data\n    if args.task == \"data_advanced\":\n        f = benchmark_data_advanced\n    elif args.task == \"train\":\n        \"\"\"\n        Note: training speed may not be representative.\n        The training cost of a R-CNN model varies with the content of the data\n        and the quality of the model.\n        \"\"\"\n        f = benchmark_train\n    elif args.task == \"eval\":\n        f = benchmark_eval\n        # only benchmark single-GPU inference.\n        assert args.num_gpus == 1 and args.num_machines == 1\n    launch(f, args.num_gpus, args.num_machines, args.machine_rank, args.dist_url, args=(args,))\n"
  },
  {
    "path": "VPS_Module/tools/convert-torchvision-to-d2.py",
    "content": "#!/usr/bin/env python\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport pickle as pkl\nimport sys\nimport torch\n\n\"\"\"\nUsage:\n  # download one of the ResNet{18,34,50,101,152} models from torchvision:\n  wget https://download.pytorch.org/models/resnet50-19c8e357.pth -O r50.pth\n  # run the conversion\n  ./convert-torchvision-to-d2.py r50.pth r50.pkl\n\n  # Then, use r50.pkl with the following changes in config:\n\nMODEL:\n  WEIGHTS: \"/path/to/r50.pkl\"\n  PIXEL_MEAN: [123.675, 116.280, 103.530]\n  PIXEL_STD: [58.395, 57.120, 57.375]\n  RESNETS:\n    DEPTH: 50\n    STRIDE_IN_1X1: False\nINPUT:\n  FORMAT: \"RGB\"\n\n  These models typically produce slightly worse results than the\n  pre-trained ResNets we use in official configs, which are the\n  original ResNet models released by MSRA.\n\"\"\"\n\nif __name__ == \"__main__\":\n    input = sys.argv[1]\n\n    obj = torch.load(input, map_location=\"cpu\")\n\n    newmodel = {}\n    for k in list(obj.keys()):\n        old_k = k\n        if \"layer\" not in k:\n            k = \"stem.\" + k\n        for t in [1, 2, 3, 4]:\n            k = k.replace(\"layer{}\".format(t), \"res{}\".format(t + 1))\n        for t in [1, 2, 3]:\n            k = k.replace(\"bn{}\".format(t), \"conv{}.norm\".format(t))\n        k = k.replace(\"downsample.0\", \"shortcut\")\n        k = k.replace(\"downsample.1\", \"shortcut.norm\")\n        print(old_k, \"->\", k)\n        newmodel[k] = obj.pop(old_k).detach().numpy()\n\n    res = {\"model\": newmodel, \"__author__\": \"torchvision\", \"matching_heuristics\": True}\n\n    with open(sys.argv[2], \"wb\") as f:\n        pkl.dump(res, f)\n    if obj:\n        print(\"Unconverted keys:\", obj.keys())\n"
  },
  {
    "path": "VPS_Module/tools/default.py",
    "content": "VKITTI_CATEGORIES = [\n    {\"id\": 0, \"trainId\": 1, \"isthing\": 0, \"name\": \"Terrain\", \"color\": [210, 0, 200]}, \n    {\"id\": 1, \"trainId\": 2, \"isthing\": 0, \"name\": \"sky\", \"color\": [90, 200, 255]}, \n    {\"id\": 2, \"trainId\": 3, \"isthing\": 0, \"name\": \"Tree\", \"color\": [0, 199, 0]},\n    {\"id\": 3, \"trainId\": 4, \"isthing\": 0, \"name\": \"Vegetation\", 'color': [90, 240, 0]},  \n    {\"id\": 4, \"trainId\": 5, \"isthing\": 0, \"name\": \"Building\", \"color\": [140, 140, 140]}, \n    {\"id\": 5, \"trainId\": 6, \"isthing\": 0, \"name\": \"Road\",  'color': [100, 60, 100]}, \n    {\"id\": 6, \"trainId\": 7, \"isthing\": 0, \"name\": \"GuardRail\", \"color\": [250, 100, 255]}, \n    {\"id\": 7, \"trainId\": 8, \"isthing\": 0, \"name\": \"TrafficSign\", \"color\": [255, 255, 0]},\n    {\"id\": 8, \"trainId\": 9, \"isthing\": 0, \"name\": \"TrafficLight\", \"color\": [200, 200, 0]},  \n    {\"id\": 9, \"trainId\": 10, \"isthing\": 0, \"name\": \"Pole\", \"color\": [255, 130, 0]},\n    {\"id\": 10, \"trainId\": 11, \"isthing\": 0, \"name\": \"Misc\", \"color\": [80, 80, 80]},\n    {\"id\": 11, \"trainId\": 12, \"isthing\": 1, \"name\": \"Truck\", \"color\": [160, 60, 60]},\n    {\"id\": 12, \"trainId\": 13, \"isthing\": 1, \"name\": \"Car\", 'color': [255, 127, 80]},\n    {\"id\": 13, \"trainId\": 14, \"isthing\": 1, \"name\": \"Van\", \"color\": [0, 139, 139]},          \n]"
  },
  {
    "path": "VPS_Module/tools/deploy/CMakeLists.txt",
    "content": "# Copyright (c) Facebook, Inc. and its affiliates.\n# See https://pytorch.org/tutorials/advanced/cpp_frontend.html\ncmake_minimum_required(VERSION 3.12 FATAL_ERROR)\nproject(torchscript_mask_rcnn)\n\nfind_package(Torch REQUIRED)\nfind_package(OpenCV REQUIRED)\nfind_package(TorchVision REQUIRED)   # needed by export-method=tracing/scripting\n\nadd_executable(torchscript_mask_rcnn torchscript_mask_rcnn.cpp)\ntarget_link_libraries(\n  torchscript_mask_rcnn\n  -Wl,--no-as-needed TorchVision::TorchVision -Wl,--as-needed\n  \"${TORCH_LIBRARIES}\" ${OpenCV_LIBS})\nset_property(TARGET torchscript_mask_rcnn PROPERTY CXX_STANDARD 14)\n"
  },
  {
    "path": "VPS_Module/tools/deploy/README.md",
    "content": "See [deployment tutorial](https://detectron2.readthedocs.io/tutorials/deployment.html)\nfor some high-level background about deployment.\n\nThis directory contains the following examples:\n\n1. An example script `export_model.py`\n   that exports a detectron2 model for deployment using different methods and formats.\n\n2. A C++ example that runs inference with Mask R-CNN model in TorchScript format.\n\n## Build\nDeployment depends on libtorch and OpenCV. Some require more dependencies:\n\n* Running TorchScript-format models produced by `--export-method=caffe2_tracing` requires libtorch\n  to be built with caffe2 enabled.\n* Running TorchScript-format models produced by `--export-method=tracing/scripting` requires libtorchvision (C++ library of torchvision).\n\nAll methods are supported in one C++ file that requires all the above dependencies.\nAdjust it and remove code you don't need.\nAs a reference, we provide a [Dockerfile](../../docker/deploy.Dockerfile) that installs all the above dependencies and builds the C++ example.\n\n## Use\n\nWe show a few example commands to export and execute a Mask R-CNN model in C++.\n\n* `export-method=tracing, format=torchscript`:\n```\n./export_model.py --config-file ../../configs/COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_3x.yaml \\\n    --output ./output --export-method tracing --format torchscript \\\n    MODEL.WEIGHTS detectron2://COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_3x/137849600/model_final_f10217.pkl \\\n    MODEL.DEVICE cuda\n\n./build/torchscript_mask_rcnn output/model.ts input.jpg tracing\n```\n\n* `export-method=scripting, format=torchscript`:\n```\n./export_model.py --config-file ../../configs/COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_3x.yaml \\\n    --output ./output --export-method scripting --format torchscript \\\n    MODEL.WEIGHTS detectron2://COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_3x/137849600/model_final_f10217.pkl \\\n\n./build/torchscript_mask_rcnn output/model.ts input.jpg scripting\n```\n\n* `export-method=caffe2_tracing, format=torchscript`:\n\n```\n./export_model.py --config-file ../../configs/COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_3x.yaml \\\n    --output ./output --export-method caffe2_tracing --format torchscript \\\n    MODEL.WEIGHTS detectron2://COCO-InstanceSegmentation/mask_rcnn_R_50_FPN_3x/137849600/model_final_f10217.pkl \\\n\n./build/torchscript_mask_rcnn output/model.ts input.jpg caffe2_tracing\n```\n\n\n## Notes:\n\n1. Tracing/Caffe2-tracing requires valid weights & sample inputs.\n   Therefore the above commands require pre-trained models and [COCO dataset](https://detectron2.readthedocs.io/tutorials/builtin_datasets.html).\n   You can modify the script to obtain sample inputs in other ways instead of from COCO.\n\n2. `--run-eval` is implemented only for tracing mode\n   to evaluate the exported model using the dataset in the config.\n   It's recommended to always verify the accuracy in case the conversion is not successful.\n   Evaluation can be slow if model is exported to CPU or dataset is too large (\"coco_2017_val_100\" is a small subset of COCO useful for evaluation).\n   `caffe2_tracing` accuracy may be slightly different (within 0.1 AP) from original model due to numerical precisions between different runtime.\n"
  },
  {
    "path": "VPS_Module/tools/deploy/export_model.py",
    "content": "#!/usr/bin/env python\n# Copyright (c) Facebook, Inc. and its affiliates.\nimport argparse\nimport os\nfrom typing import Dict, List, Tuple\nimport torch\nfrom torch import Tensor, nn\n\nimport detectron2.data.transforms as T\nfrom detectron2.checkpoint import DetectionCheckpointer\nfrom detectron2.config import get_cfg\nfrom detectron2.data import build_detection_test_loader, detection_utils\nfrom detectron2.evaluation import COCOEvaluator, inference_on_dataset, print_csv_format\nfrom detectron2.export import TracingAdapter, dump_torchscript_IR, scripting_with_instances\nfrom detectron2.modeling import GeneralizedRCNN, RetinaNet, build_model\nfrom detectron2.modeling.postprocessing import detector_postprocess\nfrom detectron2.projects.point_rend import add_pointrend_config\nfrom detectron2.structures import Boxes\nfrom detectron2.utils.env import TORCH_VERSION\nfrom detectron2.utils.file_io import PathManager\nfrom detectron2.utils.logger import setup_logger\n\n\ndef setup_cfg(args):\n    cfg = get_cfg()\n    # cuda context is initialized before creating dataloader, so we don't fork anymore\n    cfg.DATALOADER.NUM_WORKERS = 0\n    add_pointrend_config(cfg)\n    cfg.merge_from_file(args.config_file)\n    cfg.merge_from_list(args.opts)\n    cfg.freeze()\n    return cfg\n\n\ndef export_caffe2_tracing(cfg, torch_model, inputs):\n    from detectron2.export import Caffe2Tracer\n\n    tracer = Caffe2Tracer(cfg, torch_model, inputs)\n    if args.format == \"caffe2\":\n        caffe2_model = tracer.export_caffe2()\n        caffe2_model.save_protobuf(args.output)\n        # draw the caffe2 graph\n        caffe2_model.save_graph(os.path.join(args.output, \"model.svg\"), inputs=inputs)\n        return caffe2_model\n    elif args.format == \"onnx\":\n        import onnx\n\n        onnx_model = tracer.export_onnx()\n        onnx.save(onnx_model, os.path.join(args.output, \"model.onnx\"))\n    elif args.format == \"torchscript\":\n        ts_model = tracer.export_torchscript()\n        with PathManager.open(os.path.join(args.output, \"model.ts\"), \"wb\") as f:\n            torch.jit.save(ts_model, f)\n        dump_torchscript_IR(ts_model, args.output)\n\n\n# experimental. API not yet final\ndef export_scripting(torch_model):\n    assert TORCH_VERSION >= (1, 8)\n    fields = {\n        \"proposal_boxes\": Boxes,\n        \"objectness_logits\": Tensor,\n        \"pred_boxes\": Boxes,\n        \"scores\": Tensor,\n        \"pred_classes\": Tensor,\n        \"pred_masks\": Tensor,\n        \"pred_keypoints\": torch.Tensor,\n        \"pred_keypoint_heatmaps\": torch.Tensor,\n    }\n    assert args.format == \"torchscript\", \"Scripting only supports torchscript format.\"\n\n    class ScriptableAdapterBase(nn.Module):\n        # Use this adapter to workaround https://github.com/pytorch/pytorch/issues/46944\n        # by not retuning instances but dicts. Otherwise the exported model is not deployable\n        def __init__(self):\n            super().__init__()\n            self.model = torch_model\n            self.eval()\n\n    if isinstance(torch_model, GeneralizedRCNN):\n\n        class ScriptableAdapter(ScriptableAdapterBase):\n            def forward(self, inputs: Tuple[Dict[str, torch.Tensor]]) -> List[Dict[str, Tensor]]:\n                instances = self.model.inference(inputs, do_postprocess=False)\n                return [i.get_fields() for i in instances]\n\n    else:\n\n        class ScriptableAdapter(ScriptableAdapterBase):\n            def forward(self, inputs: Tuple[Dict[str, torch.Tensor]]) -> List[Dict[str, Tensor]]:\n                instances = self.model(inputs)\n                return [i.get_fields() for i in instances]\n\n    ts_model = scripting_with_instances(ScriptableAdapter(), fields)\n    with PathManager.open(os.path.join(args.output, \"model.ts\"), \"wb\") as f:\n        torch.jit.save(ts_model, f)\n    dump_torchscript_IR(ts_model, args.output)\n    # TODO inference in Python now missing postprocessing glue code\n    return None\n\n\n# experimental. API not yet final\ndef export_tracing(torch_model, inputs):\n    assert TORCH_VERSION >= (1, 8)\n    image = inputs[0][\"image\"]\n    inputs = [{\"image\": image}]  # remove other unused keys\n\n    if isinstance(torch_model, GeneralizedRCNN):\n\n        def inference(model, inputs):\n            # use do_postprocess=False so it returns ROI mask\n            inst = model.inference(inputs, do_postprocess=False)[0]\n            return [{\"instances\": inst}]\n\n    else:\n        inference = None  # assume that we just call the model directly\n\n    traceable_model = TracingAdapter(torch_model, inputs, inference)\n\n    if args.format == \"torchscript\":\n        ts_model = torch.jit.trace(traceable_model, (image,))\n        with PathManager.open(os.path.join(args.output, \"model.ts\"), \"wb\") as f:\n            torch.jit.save(ts_model, f)\n        dump_torchscript_IR(ts_model, args.output)\n    elif args.format == \"onnx\":\n        with PathManager.open(os.path.join(args.output, \"model.onnx\"), \"wb\") as f:\n            torch.onnx.export(traceable_model, (image,), f, opset_version=11)\n    logger.info(\"Inputs schema: \" + str(traceable_model.inputs_schema))\n    logger.info(\"Outputs schema: \" + str(traceable_model.outputs_schema))\n\n    if args.format != \"torchscript\":\n        return None\n    if not isinstance(torch_model, (GeneralizedRCNN, RetinaNet)):\n        return None\n\n    def eval_wrapper(inputs):\n        \"\"\"\n        The exported model does not contain the final resize step, which is typically\n        unused in deployment but needed for evaluation. We add it manually here.\n        \"\"\"\n        input = inputs[0]\n        instances = traceable_model.outputs_schema(ts_model(input[\"image\"]))[0][\"instances\"]\n        postprocessed = detector_postprocess(instances, input[\"height\"], input[\"width\"])\n        return [{\"instances\": postprocessed}]\n\n    return eval_wrapper\n\n\ndef get_sample_inputs(args):\n\n    if args.sample_image is None:\n        # get a first batch from dataset\n        data_loader = build_detection_test_loader(cfg, cfg.DATASETS.TEST[0])\n        first_batch = next(iter(data_loader))\n        return first_batch\n    else:\n        # get a sample data\n        original_image = detection_utils.read_image(args.sample_image, format=cfg.INPUT.FORMAT)\n        # Do same preprocessing as DefaultPredictor\n        aug = T.ResizeShortestEdge(\n            [cfg.INPUT.MIN_SIZE_TEST, cfg.INPUT.MIN_SIZE_TEST], cfg.INPUT.MAX_SIZE_TEST\n        )\n        height, width = original_image.shape[:2]\n        image = aug.get_transform(original_image).apply_image(original_image)\n        image = torch.as_tensor(image.astype(\"float32\").transpose(2, 0, 1))\n\n        inputs = {\"image\": image, \"height\": height, \"width\": width}\n\n        # Sample ready\n        sample_inputs = [inputs]\n        return sample_inputs\n\n\nif __name__ == \"__main__\":\n    parser = argparse.ArgumentParser(description=\"Export a model for deployment.\")\n    parser.add_argument(\n        \"--format\",\n        choices=[\"caffe2\", \"onnx\", \"torchscript\"],\n        help=\"output format\",\n        default=\"torchscript\",\n    )\n    parser.add_argument(\n        \"--export-method\",\n        choices=[\"caffe2_tracing\", \"tracing\", \"scripting\"],\n        help=\"Method to export models\",\n        default=\"tracing\",\n    )\n    parser.add_argument(\"--config-file\", default=\"\", metavar=\"FILE\", help=\"path to config file\")\n    parser.add_argument(\"--sample-image\", default=None, type=str, help=\"sample image for input\")\n    parser.add_argument(\"--run-eval\", action=\"store_true\")\n    parser.add_argument(\"--output\", help=\"output directory for the converted model\")\n    parser.add_argument(\n        \"opts\",\n        help=\"Modify config options using the command-line\",\n        default=None,\n        nargs=argparse.REMAINDER,\n    )\n    args = parser.parse_args()\n    logger = setup_logger()\n    logger.info(\"Command line arguments: \" + str(args))\n    PathManager.mkdirs(args.output)\n    # Disable respecialization on new shapes. Otherwise --run-eval will be slow\n    torch._C._jit_set_bailout_depth(1)\n\n    cfg = setup_cfg(args)\n\n    # create a torch model\n    torch_model = build_model(cfg)\n    DetectionCheckpointer(torch_model).resume_or_load(cfg.MODEL.WEIGHTS)\n    torch_model.eval()\n\n    # get sample data\n    sample_inputs = get_sample_inputs(args)\n\n    # convert and save model\n    if args.export_method == \"caffe2_tracing\":\n        exported_model = export_caffe2_tracing(cfg, torch_model, sample_inputs)\n    elif args.export_method == \"scripting\":\n        exported_model = export_scripting(torch_model)\n    elif args.export_method == \"tracing\":\n        exported_model = export_tracing(torch_model, sample_inputs)\n\n    # run evaluation with the converted model\n    if args.run_eval:\n        assert exported_model is not None, (\n            \"Python inference is not yet implemented for \"\n            f\"export_method={args.export_method}, format={args.format}.\"\n        )\n        logger.info(\"Running evaluation ... this takes a long time if you export to CPU.\")\n        dataset = cfg.DATASETS.TEST[0]\n        data_loader = build_detection_test_loader(cfg, dataset)\n        # NOTE: hard-coded evaluator. change to the evaluator for your dataset\n        evaluator = COCOEvaluator(dataset, output_dir=args.output)\n        metrics = inference_on_dataset(exported_model, data_loader, evaluator)\n        print_csv_format(metrics)\n"
  },
  {
    "path": "VPS_Module/tools/deploy/torchscript_mask_rcnn.cpp",
    "content": "// Copyright (c) Facebook, Inc. and its affiliates.\n// @lint-ignore-every CLANGTIDY\n// This is an example code that demonstrates how to run inference\n// with a torchscript format Mask R-CNN model exported by ./export_model.py\n// using export method=tracing, caffe2_tracing & scripting.\n\n#include <opencv2/opencv.hpp>\n#include <iostream>\n#include <string>\n\n#include <c10/cuda/CUDAStream.h>\n#include <torch/csrc/autograd/grad_mode.h>\n#include <torch/csrc/jit/runtime/graph_executor.h>\n#include <torch/script.h>\n\n// only needed for export_method=tracing\n#include <torchvision/vision.h> // @oss-only\n// @fb-only: #include <torchvision/csrc/vision.h>\n\nusing namespace std;\n\nc10::IValue get_caffe2_tracing_inputs(cv::Mat& img, c10::Device device) {\n  const int height = img.rows;\n  const int width = img.cols;\n  // FPN models require divisibility of 32.\n  // Tracing mode does padding inside the graph, but caffe2_tracing does not.\n  assert(height % 32 == 0 && width % 32 == 0);\n  const int channels = 3;\n\n  auto input =\n      torch::from_blob(img.data, {1, height, width, channels}, torch::kUInt8);\n  // NHWC to NCHW\n  input = input.to(device, torch::kFloat).permute({0, 3, 1, 2}).contiguous();\n\n  std::array<float, 3> im_info_data{height * 1.0f, width * 1.0f, 1.0f};\n  auto im_info =\n      torch::from_blob(im_info_data.data(), {1, 3}).clone().to(device);\n  return std::make_tuple(input, im_info);\n}\n\nc10::IValue get_tracing_inputs(cv::Mat& img, c10::Device device) {\n  const int height = img.rows;\n  const int width = img.cols;\n  const int channels = 3;\n\n  auto input =\n      torch::from_blob(img.data, {height, width, channels}, torch::kUInt8);\n  // HWC to CHW\n  input = input.to(device, torch::kFloat).permute({2, 0, 1}).contiguous();\n  return input;\n}\n\n// create a Tuple[Dict[str, Tensor]] which is the input type of scripted model\nc10::IValue get_scripting_inputs(cv::Mat& img, c10::Device device) {\n  const int height = img.rows;\n  const int width = img.cols;\n  const int channels = 3;\n\n  auto img_tensor =\n      torch::from_blob(img.data, {height, width, channels}, torch::kUInt8);\n  // HWC to CHW\n  img_tensor =\n      img_tensor.to(device, torch::kFloat).permute({2, 0, 1}).contiguous();\n  auto dic = c10::Dict<std::string, torch::Tensor>();\n  dic.insert(\"image\", img_tensor);\n  return std::make_tuple(dic);\n}\n\nc10::IValue\nget_inputs(std::string export_method, cv::Mat& img, c10::Device device) {\n  // Given an image, create inputs in the format required by the model.\n  if (export_method == \"tracing\")\n    return get_tracing_inputs(img, device);\n  if (export_method == \"caffe2_tracing\")\n    return get_caffe2_tracing_inputs(img, device);\n  if (export_method == \"scripting\")\n    return get_scripting_inputs(img, device);\n  abort();\n}\n\nstruct MaskRCNNOutputs {\n  at::Tensor pred_boxes, pred_classes, pred_masks, scores;\n  int num_instances() const {\n    return pred_boxes.sizes()[0];\n  }\n};\n\nMaskRCNNOutputs get_outputs(std::string export_method, c10::IValue outputs) {\n  // Given outputs of the model, extract tensors from it to turn into a\n  // common MaskRCNNOutputs format.\n  if (export_method == \"tracing\") {\n    auto out_tuple = outputs.toTuple()->elements();\n    // They are ordered alphabetically by their field name in Instances\n    return MaskRCNNOutputs{\n        out_tuple[0].toTensor(),\n        out_tuple[1].toTensor(),\n        out_tuple[2].toTensor(),\n        out_tuple[3].toTensor()};\n  }\n  if (export_method == \"caffe2_tracing\") {\n    auto out_tuple = outputs.toTuple()->elements();\n    // A legacy order used by caffe2 models\n    return MaskRCNNOutputs{\n        out_tuple[0].toTensor(),\n        out_tuple[2].toTensor(),\n        out_tuple[3].toTensor(),\n        out_tuple[1].toTensor()};\n  }\n  if (export_method == \"scripting\") {\n    // With the ScriptableAdapter defined in export_model.py, the output is\n    // List[Dict[str, Any]].\n    auto out_dict = outputs.toList().get(0).toGenericDict();\n    return MaskRCNNOutputs{\n        out_dict.at(\"pred_boxes\").toTensor(),\n        out_dict.at(\"pred_classes\").toTensor(),\n        out_dict.at(\"pred_masks\").toTensor(),\n        out_dict.at(\"scores\").toTensor()};\n  }\n  abort();\n}\n\nint main(int argc, const char* argv[]) {\n  if (argc != 4) {\n    cerr << R\"xx(\nUsage:\n   ./torchscript_mask_rcnn model.ts input.jpg EXPORT_METHOD\n\n   EXPORT_METHOD can be \"tracing\", \"caffe2_tracing\" or \"scripting\".\n)xx\";\n    return 1;\n  }\n  std::string image_file = argv[2];\n  std::string export_method = argv[3];\n  assert(\n      export_method == \"caffe2_tracing\" || export_method == \"tracing\" ||\n      export_method == \"scripting\");\n\n  torch::jit::getBailoutDepth() = 1;\n  torch::autograd::AutoGradMode guard(false);\n  auto module = torch::jit::load(argv[1]);\n\n  assert(module.buffers().size() > 0);\n  // Assume that the entire model is on the same device.\n  // We just put input to this device.\n  auto device = (*begin(module.buffers())).device();\n\n  cv::Mat input_img = cv::imread(image_file, cv::IMREAD_COLOR);\n  auto inputs = get_inputs(export_method, input_img, device);\n\n  // Run the network\n  auto output = module.forward({inputs});\n  if (device.is_cuda())\n    c10::cuda::getCurrentCUDAStream().synchronize();\n\n  // run 3 more times to benchmark\n  int N_benchmark = 3, N_warmup = 1;\n  auto start_time = chrono::high_resolution_clock::now();\n  for (int i = 0; i < N_benchmark + N_warmup; ++i) {\n    if (i == N_warmup)\n      start_time = chrono::high_resolution_clock::now();\n    output = module.forward({inputs});\n    if (device.is_cuda())\n      c10::cuda::getCurrentCUDAStream().synchronize();\n  }\n  auto end_time = chrono::high_resolution_clock::now();\n  auto ms = chrono::duration_cast<chrono::microseconds>(end_time - start_time)\n                .count();\n  cout << \"Latency (should vary with different inputs): \"\n       << ms * 1.0 / 1e6 / N_benchmark << \" seconds\" << endl;\n\n  // Parse Mask R-CNN outputs\n  auto rcnn_outputs = get_outputs(export_method, output);\n  cout << \"Number of detected objects: \" << rcnn_outputs.num_instances()\n       << endl;\n\n  cout << \"pred_boxes: \" << rcnn_outputs.pred_boxes.toString() << \" \"\n       << rcnn_outputs.pred_boxes.sizes() << endl;\n  cout << \"scores: \" << rcnn_outputs.scores.toString() << \" \"\n       << rcnn_outputs.scores.sizes() << endl;\n  cout << \"pred_classes: \" << rcnn_outputs.pred_classes.toString() << \" \"\n       << rcnn_outputs.pred_classes.sizes() << endl;\n  cout << \"pred_masks: \" << rcnn_outputs.pred_masks.toString() << \" \"\n       << rcnn_outputs.pred_masks.sizes() << endl;\n\n  cout << rcnn_outputs.pred_boxes << endl;\n  return 0;\n}\n"
  },
  {
    "path": "VPS_Module/tools/lazyconfig_train_net.py",
    "content": "#!/usr/bin/env python\n# Copyright (c) Facebook, Inc. and its affiliates.\n\"\"\"\nTraining script using the new \"LazyConfig\" python config files.\n\nThis scripts reads a given python config file and runs the training or evaluation.\nIt can be used to train any models or dataset as long as they can be\ninstantiated by the recursive construction defined in the given config file.\n\nBesides lazy construction of models, dataloader, etc., this scripts expects a\nfew common configuration parameters currently defined in \"configs/common/train.py\".\nTo add more complicated training logic, you can easily add other configs\nin the config file and implement a new train_net.py to handle them.\n\"\"\"\nimport logging\n\nfrom detectron2.checkpoint import DetectionCheckpointer\nfrom detectron2.config import LazyConfig, instantiate\nfrom detectron2.engine import (\n    AMPTrainer,\n    SimpleTrainer,\n    default_argument_parser,\n    default_setup,\n    default_writers,\n    hooks,\n    launch,\n)\nfrom detectron2.engine.defaults import create_ddp_model\nfrom detectron2.evaluation import inference_on_dataset, print_csv_format\nfrom detectron2.utils import comm\n\nlogger = logging.getLogger(\"detectron2\")\n\n\ndef do_test(cfg, model):\n    if \"evaluator\" in cfg.dataloader:\n        ret = inference_on_dataset(\n            model, instantiate(cfg.dataloader.test), instantiate(cfg.dataloader.evaluator)\n        )\n        print_csv_format(ret)\n        return ret\n\n\ndef do_train(args, cfg):\n    \"\"\"\n    Args:\n        cfg: an object with the following attributes:\n            model: instantiate to a module\n            dataloader.{train,test}: instantiate to dataloaders\n            dataloader.evaluator: instantiate to evaluator for test set\n            optimizer: instantaite to an optimizer\n            lr_multiplier: instantiate to a fvcore scheduler\n            train: other misc config defined in `configs/common/train.py`, including:\n                output_dir (str)\n                init_checkpoint (str)\n                amp.enabled (bool)\n                max_iter (int)\n                eval_period, log_period (int)\n                device (str)\n                checkpointer (dict)\n                ddp (dict)\n    \"\"\"\n    model = instantiate(cfg.model)\n    logger = logging.getLogger(\"detectron2\")\n    logger.info(\"Model:\\n{}\".format(model))\n    model.to(cfg.train.device)\n\n    cfg.optimizer.params.model = model\n    optim = instantiate(cfg.optimizer)\n\n    train_loader = instantiate(cfg.dataloader.train)\n\n    model = create_ddp_model(model, **cfg.train.ddp)\n    trainer = (AMPTrainer if cfg.train.amp.enabled else SimpleTrainer)(model, train_loader, optim)\n    checkpointer = DetectionCheckpointer(\n        model,\n        cfg.train.output_dir,\n        trainer=trainer,\n    )\n    trainer.register_hooks(\n        [\n            hooks.IterationTimer(),\n            hooks.LRScheduler(scheduler=instantiate(cfg.lr_multiplier)),\n            hooks.PeriodicCheckpointer(checkpointer, **cfg.train.checkpointer)\n            if comm.is_main_process()\n            else None,\n            hooks.EvalHook(cfg.train.eval_period, lambda: do_test(cfg, model)),\n            hooks.PeriodicWriter(\n                default_writers(cfg.train.output_dir, cfg.train.max_iter),\n                period=cfg.train.log_period,\n            )\n            if comm.is_main_process()\n            else None,\n        ]\n    )\n\n    checkpointer.resume_or_load(cfg.train.init_checkpoint, resume=args.resume)\n    if args.resume and checkpointer.has_checkpoint():\n        # The checkpoint stores the training iteration that just finished, thus we start\n        # at the next iteration\n        start_iter = trainer.iter + 1\n    else:\n        start_iter = 0\n    trainer.train(start_iter, cfg.train.max_iter)\n\n\ndef main(args):\n    cfg = LazyConfig.load(args.config_file)\n    cfg = LazyConfig.apply_overrides(cfg, args.opts)\n    default_setup(cfg, args)\n\n    if args.eval_only:\n        model = instantiate(cfg.model)\n        model.to(cfg.train.device)\n        model = create_ddp_model(model)\n        DetectionCheckpointer(model).load(cfg.train.init_checkpoint)\n        print(do_test(cfg, model))\n    else:\n        do_train(args, cfg)\n\n\nif __name__ == \"__main__\":\n    args = default_argument_parser().parse_args()\n    launch(\n        main,\n        args.num_gpus,\n        num_machines=args.num_machines,\n        machine_rank=args.machine_rank,\n        dist_url=args.dist_url,\n        args=(args,),\n    )\n"
  },
  {
    "path": "VPS_Module/tools/lightning_train_net.py",
    "content": "#!/usr/bin/env python3\n# Copyright (c) Facebook, Inc. and its affiliates.\n# Lightning Trainer should be considered beta at this point\n# We have confirmed that training and validation run correctly and produce correct results\n# Depending on how you launch the trainer, there are issues with processes terminating correctly\n# This module is still dependent on D2 logging, but could be transferred to use Lightning logging\n\nimport logging\nimport os\nimport time\nimport weakref\nfrom collections import OrderedDict\nfrom typing import Any, Dict, List\n\nimport detectron2.utils.comm as comm\nfrom detectron2.checkpoint import DetectionCheckpointer\nfrom detectron2.config import get_cfg\nfrom detectron2.data import build_detection_test_loader, build_detection_train_loader\nfrom detectron2.engine import (\n    DefaultTrainer,\n    SimpleTrainer,\n    default_argument_parser,\n    default_setup,\n    default_writers,\n    hooks,\n)\nfrom detectron2.evaluation import print_csv_format\nfrom detectron2.evaluation.testing import flatten_results_dict\nfrom detectron2.modeling import build_model\nfrom detectron2.solver import build_lr_scheduler, build_optimizer\nfrom detectron2.utils.events import EventStorage\nfrom detectron2.utils.logger import setup_logger\n\nimport pytorch_lightning as pl  # type: ignore\nfrom pytorch_lightning import LightningDataModule, LightningModule\nfrom train_net import build_evaluator\n\nlogging.basicConfig(level=logging.INFO)\nlogger = logging.getLogger(\"detectron2\")\n\n\nclass TrainingModule(LightningModule):\n    def __init__(self, cfg):\n        super().__init__()\n        if not logger.isEnabledFor(logging.INFO):  # setup_logger is not called for d2\n            setup_logger()\n        self.cfg = DefaultTrainer.auto_scale_workers(cfg, comm.get_world_size())\n        self.storage: EventStorage = None\n        self.model = build_model(self.cfg)\n\n        self.start_iter = 0\n        self.max_iter = cfg.SOLVER.MAX_ITER\n\n    def on_save_checkpoint(self, checkpoint: Dict[str, Any]) -> None:\n        checkpoint[\"iteration\"] = self.storage.iter\n\n    def on_load_checkpoint(self, checkpointed_state: Dict[str, Any]) -> None:\n        self.start_iter = checkpointed_state[\"iteration\"]\n        self.storage.iter = self.start_iter\n\n    def setup(self, stage: str):\n        if self.cfg.MODEL.WEIGHTS:\n            self.checkpointer = DetectionCheckpointer(\n                # Assume you want to save checkpoints together with logs/statistics\n                self.model,\n                self.cfg.OUTPUT_DIR,\n            )\n            logger.info(f\"Load model weights from checkpoint: {self.cfg.MODEL.WEIGHTS}.\")\n            # Only load weights, use lightning checkpointing if you want to resume\n            self.checkpointer.load(self.cfg.MODEL.WEIGHTS)\n\n        self.iteration_timer = hooks.IterationTimer()\n        self.iteration_timer.before_train()\n        self.data_start = time.perf_counter()\n        self.writers = None\n\n    def training_step(self, batch, batch_idx):\n        data_time = time.perf_counter() - self.data_start\n        # Need to manually enter/exit since trainer may launch processes\n        # This ideally belongs in setup, but setup seems to run before processes are spawned\n        if self.storage is None:\n            self.storage = EventStorage(0)\n            self.storage.__enter__()\n            self.iteration_timer.trainer = weakref.proxy(self)\n            self.iteration_timer.before_step()\n            self.writers = (\n                default_writers(self.cfg.OUTPUT_DIR, self.max_iter)\n                if comm.is_main_process()\n                else {}\n            )\n\n        loss_dict = self.model(batch)\n        SimpleTrainer.write_metrics(loss_dict, data_time)\n\n        opt = self.optimizers()\n        self.storage.put_scalar(\n            \"lr\", opt.param_groups[self._best_param_group_id][\"lr\"], smoothing_hint=False\n        )\n        self.iteration_timer.after_step()\n        self.storage.step()\n        # A little odd to put before step here, but it's the best way to get a proper timing\n        self.iteration_timer.before_step()\n\n        if self.storage.iter % 20 == 0:\n            for writer in self.writers:\n                writer.write()\n        return sum(loss_dict.values())\n\n    def training_step_end(self, training_step_outpus):\n        self.data_start = time.perf_counter()\n        return training_step_outpus\n\n    def training_epoch_end(self, training_step_outputs):\n        self.iteration_timer.after_train()\n        if comm.is_main_process():\n            self.checkpointer.save(\"model_final\")\n        for writer in self.writers:\n            writer.write()\n            writer.close()\n        self.storage.__exit__(None, None, None)\n\n    def _process_dataset_evaluation_results(self) -> OrderedDict:\n        results = OrderedDict()\n        for idx, dataset_name in enumerate(self.cfg.DATASETS.TEST):\n            results[dataset_name] = self._evaluators[idx].evaluate()\n            if comm.is_main_process():\n                print_csv_format(results[dataset_name])\n\n        if len(results) == 1:\n            results = list(results.values())[0]\n        return results\n\n    def _reset_dataset_evaluators(self):\n        self._evaluators = []\n        for dataset_name in self.cfg.DATASETS.TEST:\n            evaluator = build_evaluator(self.cfg, dataset_name)\n            evaluator.reset()\n            self._evaluators.append(evaluator)\n\n    def on_validation_epoch_start(self, _outputs):\n        self._reset_dataset_evaluators()\n\n    def validation_epoch_end(self, _outputs):\n        results = self._process_dataset_evaluation_results(_outputs)\n\n        flattened_results = flatten_results_dict(results)\n        for k, v in flattened_results.items():\n            try:\n                v = float(v)\n            except Exception as e:\n                raise ValueError(\n                    \"[EvalHook] eval_function should return a nested dict of float. \"\n                    \"Got '{}: {}' instead.\".format(k, v)\n                ) from e\n        self.storage.put_scalars(**flattened_results, smoothing_hint=False)\n\n    def validation_step(self, batch, batch_idx: int, dataloader_idx: int = 0) -> None:\n        if not isinstance(batch, List):\n            batch = [batch]\n        outputs = self.model(batch)\n        self._evaluators[dataloader_idx].process(batch, outputs)\n\n    def configure_optimizers(self):\n        optimizer = build_optimizer(self.cfg, self.model)\n        self._best_param_group_id = hooks.LRScheduler.get_best_param_group_id(optimizer)\n        scheduler = build_lr_scheduler(self.cfg, optimizer)\n        return [optimizer], [{\"scheduler\": scheduler, \"interval\": \"step\"}]\n\n\nclass DataModule(LightningDataModule):\n    def __init__(self, cfg):\n        super().__init__()\n        self.cfg = DefaultTrainer.auto_scale_workers(cfg, comm.get_world_size())\n\n    def train_dataloader(self):\n        return build_detection_train_loader(self.cfg)\n\n    def val_dataloader(self):\n        dataloaders = []\n        for dataset_name in self.cfg.DATASETS.TEST:\n            dataloaders.append(build_detection_test_loader(self.cfg, dataset_name))\n        return dataloaders\n\n\ndef main(args):\n    cfg = setup(args)\n    train(cfg, args)\n\n\ndef train(cfg, args):\n    trainer_params = {\n        # training loop is bounded by max steps, use a large max_epochs to make\n        # sure max_steps is met first\n        \"max_epochs\": 10 ** 8,\n        \"max_steps\": cfg.SOLVER.MAX_ITER,\n        \"val_check_interval\": cfg.TEST.EVAL_PERIOD if cfg.TEST.EVAL_PERIOD > 0 else 10 ** 8,\n        \"num_nodes\": args.num_machines,\n        \"gpus\": args.num_gpus,\n        \"num_sanity_val_steps\": 0,\n    }\n    if cfg.SOLVER.AMP.ENABLED:\n        trainer_params[\"precision\"] = 16\n\n    last_checkpoint = os.path.join(cfg.OUTPUT_DIR, \"last.ckpt\")\n    if args.resume:\n        # resume training from checkpoint\n        trainer_params[\"resume_from_checkpoint\"] = last_checkpoint\n        logger.info(f\"Resuming training from checkpoint: {last_checkpoint}.\")\n\n    trainer = pl.Trainer(**trainer_params)\n    logger.info(f\"start to train with {args.num_machines} nodes and {args.num_gpus} GPUs\")\n\n    module = TrainingModule(cfg)\n    data_module = DataModule(cfg)\n    if args.eval_only:\n        logger.info(\"Running inference\")\n        trainer.validate(module, data_module)\n    else:\n        logger.info(\"Running training\")\n        trainer.fit(module, data_module)\n\n\ndef setup(args):\n    \"\"\"\n    Create configs and perform basic setups.\n    \"\"\"\n    cfg = get_cfg()\n    cfg.merge_from_file(args.config_file)\n    cfg.merge_from_list(args.opts)\n    cfg.freeze()\n    default_setup(cfg, args)\n    return cfg\n\n\nif __name__ == \"__main__\":\n    parser = default_argument_parser()\n    args = parser.parse_args()\n    logger.info(\"Command Line Args:\", args)\n    main(args)\n"
  },
  {
    "path": "VPS_Module/tools/plain_train_net.py",
    "content": "#!/usr/bin/env python\n# Copyright (c) Facebook, Inc. and its affiliates.\n\"\"\"\nDetectron2 training script with a plain training loop.\n\nThis script reads a given config file and runs the training or evaluation.\nIt is an entry point that is able to train standard models in detectron2.\n\nIn order to let one script support training of many models,\nthis script contains logic that are specific to these built-in models and therefore\nmay not be suitable for your own project.\nFor example, your research project perhaps only needs a single \"evaluator\".\n\nTherefore, we recommend you to use detectron2 as a library and take\nthis file as an example of how to use the library.\nYou may want to write your own script with your datasets and other customizations.\n\nCompared to \"train_net.py\", this script supports fewer default features.\nIt also includes fewer abstraction, therefore is easier to add custom logic.\n\"\"\"\n\nimport logging\nimport os\nfrom collections import OrderedDict\nimport torch\nfrom torch.nn.parallel import DistributedDataParallel\n\nimport detectron2.utils.comm as comm\nfrom detectron2.checkpoint import DetectionCheckpointer, PeriodicCheckpointer\nfrom detectron2.config import get_cfg\nfrom detectron2.data import (\n    MetadataCatalog,\n    build_detection_test_loader,\n    build_detection_train_loader,\n)\nfrom detectron2.engine import default_argument_parser, default_setup, default_writers, launch\nfrom detectron2.evaluation import (\n    CityscapesInstanceEvaluator,\n    CityscapesSemSegEvaluator,\n    COCOEvaluator,\n    COCOPanopticEvaluator,\n    DatasetEvaluators,\n    LVISEvaluator,\n    PascalVOCDetectionEvaluator,\n    SemSegEvaluator,\n    inference_on_dataset,\n    print_csv_format,\n)\nfrom detectron2.modeling import build_model\nfrom detectron2.solver import build_lr_scheduler, build_optimizer\nfrom detectron2.utils.events import EventStorage\n\nlogger = logging.getLogger(\"detectron2\")\n\n\ndef get_evaluator(cfg, dataset_name, output_folder=None):\n    \"\"\"\n    Create evaluator(s) for a given dataset.\n    This uses the special metadata \"evaluator_type\" associated with each builtin dataset.\n    For your own dataset, you can simply create an evaluator manually in your\n    script and do not have to worry about the hacky if-else logic here.\n    \"\"\"\n    if output_folder is None:\n        output_folder = os.path.join(cfg.OUTPUT_DIR, \"inference\")\n    evaluator_list = []\n    evaluator_type = MetadataCatalog.get(dataset_name).evaluator_type\n    if evaluator_type in [\"sem_seg\", \"coco_panoptic_seg\"]:\n        evaluator_list.append(\n            SemSegEvaluator(\n                dataset_name,\n                distributed=True,\n                output_dir=output_folder,\n            )\n        )\n    if evaluator_type in [\"coco\", \"coco_panoptic_seg\"]:\n        evaluator_list.append(COCOEvaluator(dataset_name, output_dir=output_folder))\n    if evaluator_type == \"coco_panoptic_seg\":\n        evaluator_list.append(COCOPanopticEvaluator(dataset_name, output_folder))\n    if evaluator_type == \"cityscapes_instance\":\n        assert (\n            torch.cuda.device_count() > comm.get_rank()\n        ), \"CityscapesEvaluator currently do not work with multiple machines.\"\n        return CityscapesInstanceEvaluator(dataset_name)\n    if evaluator_type == \"cityscapes_sem_seg\":\n        assert (\n            torch.cuda.device_count() > comm.get_rank()\n        ), \"CityscapesEvaluator currently do not work with multiple machines.\"\n        return CityscapesSemSegEvaluator(dataset_name)\n    if evaluator_type == \"pascal_voc\":\n        return PascalVOCDetectionEvaluator(dataset_name)\n    if evaluator_type == \"lvis\":\n        return LVISEvaluator(dataset_name, cfg, True, output_folder)\n    if len(evaluator_list) == 0:\n        raise NotImplementedError(\n            \"no Evaluator for the dataset {} with the type {}\".format(dataset_name, evaluator_type)\n        )\n    if len(evaluator_list) == 1:\n        return evaluator_list[0]\n    return DatasetEvaluators(evaluator_list)\n\n\ndef do_test(cfg, model):\n    results = OrderedDict()\n    for dataset_name in cfg.DATASETS.TEST:\n        data_loader = build_detection_test_loader(cfg, dataset_name)\n        evaluator = get_evaluator(\n            cfg, dataset_name, os.path.join(cfg.OUTPUT_DIR, \"inference\", dataset_name)\n        )\n        results_i = inference_on_dataset(model, data_loader, evaluator)\n        results[dataset_name] = results_i\n        if comm.is_main_process():\n            logger.info(\"Evaluation results for {} in csv format:\".format(dataset_name))\n            print_csv_format(results_i)\n    if len(results) == 1:\n        results = list(results.values())[0]\n    return results\n\n\ndef do_train(cfg, model, resume=False):\n    model.train()\n    optimizer = build_optimizer(cfg, model)\n    scheduler = build_lr_scheduler(cfg, optimizer)\n\n    checkpointer = DetectionCheckpointer(\n        model, cfg.OUTPUT_DIR, optimizer=optimizer, scheduler=scheduler\n    )\n    start_iter = (\n        checkpointer.resume_or_load(cfg.MODEL.WEIGHTS, resume=resume).get(\"iteration\", -1) + 1\n    )\n    max_iter = cfg.SOLVER.MAX_ITER\n\n    periodic_checkpointer = PeriodicCheckpointer(\n        checkpointer, cfg.SOLVER.CHECKPOINT_PERIOD, max_iter=max_iter\n    )\n\n    writers = default_writers(cfg.OUTPUT_DIR, max_iter) if comm.is_main_process() else []\n\n    # compared to \"train_net.py\", we do not support accurate timing and\n    # precise BN here, because they are not trivial to implement in a small training loop\n    data_loader = build_detection_train_loader(cfg)\n    logger.info(\"Starting training from iteration {}\".format(start_iter))\n    with EventStorage(start_iter) as storage:\n        for data, iteration in zip(data_loader, range(start_iter, max_iter)):\n            storage.iter = iteration\n\n            loss_dict = model(data)\n            losses = sum(loss_dict.values())\n            assert torch.isfinite(losses).all(), loss_dict\n\n            loss_dict_reduced = {k: v.item() for k, v in comm.reduce_dict(loss_dict).items()}\n            losses_reduced = sum(loss for loss in loss_dict_reduced.values())\n            if comm.is_main_process():\n                storage.put_scalars(total_loss=losses_reduced, **loss_dict_reduced)\n\n            optimizer.zero_grad()\n            losses.backward()\n            optimizer.step()\n            storage.put_scalar(\"lr\", optimizer.param_groups[0][\"lr\"], smoothing_hint=False)\n            scheduler.step()\n\n            if (\n                cfg.TEST.EVAL_PERIOD > 0\n                and (iteration + 1) % cfg.TEST.EVAL_PERIOD == 0\n                and iteration != max_iter - 1\n            ):\n                do_test(cfg, model)\n                # Compared to \"train_net.py\", the test results are not dumped to EventStorage\n                comm.synchronize()\n\n            if iteration - start_iter > 5 and (\n                (iteration + 1) % 20 == 0 or iteration == max_iter - 1\n            ):\n                for writer in writers:\n                    writer.write()\n            periodic_checkpointer.step(iteration)\n\n\ndef setup(args):\n    \"\"\"\n    Create configs and perform basic setups.\n    \"\"\"\n    cfg = get_cfg()\n    cfg.merge_from_file(args.config_file)\n    cfg.merge_from_list(args.opts)\n    cfg.freeze()\n    default_setup(\n        cfg, args\n    )  # if you don't like any of the default setup, write your own setup code\n    return cfg\n\n\ndef main(args):\n    cfg = setup(args)\n\n    model = build_model(cfg)\n    logger.info(\"Model:\\n{}\".format(model))\n    if args.eval_only:\n        DetectionCheckpointer(model, save_dir=cfg.OUTPUT_DIR).resume_or_load(\n            cfg.MODEL.WEIGHTS, resume=args.resume\n        )\n        return do_test(cfg, model)\n\n    distributed = comm.get_world_size() > 1\n    if distributed:\n        model = DistributedDataParallel(\n            model, device_ids=[comm.get_local_rank()], broadcast_buffers=False\n        )\n\n    do_train(cfg, model, resume=args.resume)\n    return do_test(cfg, model)\n\n\nif __name__ == \"__main__\":\n    args = default_argument_parser().parse_args()\n    print(\"Command Line Args:\", args)\n    launch(\n        main,\n        args.num_gpus,\n        num_machines=args.num_machines,\n        machine_rank=args.machine_rank,\n        dist_url=args.dist_url,\n        args=(args,),\n    )\n"
  },
  {
    "path": "VPS_Module/tools/train_net.py",
    "content": "#!/usr/bin/env python\n# Copyright (c) Facebook, Inc. and its affiliates.\n\"\"\"\nA main training script.\n\nThis scripts reads a given config file and runs the training or evaluation.\nIt is an entry point that is made to train standard models in detectron2.\n\nIn order to let one script support training of many models,\nthis script contains logic that are specific to these built-in models and therefore\nmay not be suitable for your own project.\nFor example, your research project perhaps only needs a single \"evaluator\".\n\nTherefore, we recommend you to use detectron2 as an library and take\nthis file as an example of how to use the library.\nYou may want to write your own script with your datasets and other customizations.\n\"\"\"\n\nimport logging\nimport os\nos.environ[\"OMP_NUM_THREADS\"]=\"4\"\nos.environ[\"MKL_NUM_THREADS\"]=\"4\"\n\nfrom collections import OrderedDict\nimport torch\n\nimport detectron2.utils.comm as comm\nfrom detectron2.checkpoint import DetectionCheckpointer\nfrom detectron2.config import get_cfg\nfrom detectron2.data import MetadataCatalog, build_detection_test_loader, build_detection_train_loader\nfrom detectron2.engine import DefaultTrainer, default_argument_parser, default_setup, hooks, launch\nfrom detectron2.evaluation import (\n    CityscapesInstanceEvaluator,\n    CityscapesSemSegEvaluator,\n    COCOEvaluator,\n    COCOPanopticEvaluator,\n    DatasetEvaluators,\n    LVISEvaluator,\n    PascalVOCDetectionEvaluator,\n    SemSegEvaluator,\n    verify_results,\n)\nfrom detectron2.modeling import GeneralizedRCNNWithTTA\n\nfrom detectron2.data.PanopticFPN_video_DatasetMapper import PanopticFPN_video_DatasetMapper\n\n\ndef build_evaluator(cfg, dataset_name, output_folder=None):\n    \"\"\"\n    Create evaluator(s) for a given dataset.\n    This uses the special metadata \"evaluator_type\" associated with each builtin dataset.\n    For your own dataset, you can simply create an evaluator manually in your\n    script and do not have to worry about the hacky if-else logic here.\n    \"\"\"\n    if output_folder is None:\n        output_folder = os.path.join(cfg.OUTPUT_DIR, \"inference\")\n    evaluator_list = []\n    evaluator_type = MetadataCatalog.get(dataset_name).evaluator_type\n    # if evaluator_type in [\"sem_seg\", \"coco_panoptic_seg\"]:\n    #     evaluator_list.append(\n    #         SemSegEvaluator(\n    #             dataset_name,\n    #             distributed=True,\n    #             output_dir=output_folder,\n    #         )\n    #     )\n    # if evaluator_type in [\"coco\", \"coco_panoptic_seg\"]:\n    #     evaluator_list.append(COCOEvaluator(dataset_name, output_dir=output_folder))\n    if evaluator_type == \"coco_panoptic_seg\":\n        evaluator_list.append(COCOPanopticEvaluator(dataset_name, output_folder))\n    if evaluator_type == \"cityscapes_instance\":\n        assert (\n            torch.cuda.device_count() > comm.get_rank()\n        ), \"CityscapesEvaluator currently do not work with multiple machines.\"\n        return CityscapesInstanceEvaluator(dataset_name)\n    if evaluator_type == \"cityscapes_sem_seg\":\n        assert (\n            torch.cuda.device_count() > comm.get_rank()\n        ), \"CityscapesEvaluator currently do not work with multiple machines.\"\n        return CityscapesSemSegEvaluator(dataset_name)\n    elif evaluator_type == \"pascal_voc\":\n        return PascalVOCDetectionEvaluator(dataset_name)\n    elif evaluator_type == \"lvis\":\n        return LVISEvaluator(dataset_name, output_dir=output_folder)\n    if len(evaluator_list) == 0:\n        raise NotImplementedError(\n            \"no Evaluator for the dataset {} with the type {}\".format(dataset_name, evaluator_type)\n        )\n    elif len(evaluator_list) == 1:\n        return evaluator_list[0]\n    return DatasetEvaluators(evaluator_list)\n\n\nclass Trainer(DefaultTrainer):\n    \"\"\"\n    We use the \"DefaultTrainer\" which contains pre-defined default logic for\n    standard training workflow. They may not work for you, especially if you\n    are working on a new research project. In that case you can write your\n    own training loop. You can use \"tools/plain_train_net.py\" as an example.\n    \"\"\"\n\n    @classmethod\n    def build_evaluator(cls, cfg, dataset_name, output_folder=None):\n        return build_evaluator(cfg, dataset_name, output_folder)\n\n    @classmethod\n    def build_train_loader(cls, cfg):\n        mapper = PanopticFPN_video_DatasetMapper(cfg)\n        return build_detection_train_loader(cfg, mapper=mapper)\n    \n    # @classmethod\n    # def build_test_loader(cls, cfg, dataset_name):\n    #     mapper = PanopticFPN_video_DatasetMapper(cfg)\n    #     return build_detection_test_loader(cfg, dataset_name, mapper=mapper)\n\n    @classmethod\n    def test_with_TTA(cls, cfg, model):\n        logger = logging.getLogger(\"detectron2.trainer\")\n        # In the end of training, run an evaluation with TTA\n        # Only support some R-CNN models.\n        logger.info(\"Running inference with test-time augmentation ...\")\n        model = GeneralizedRCNNWithTTA(cfg, model)\n        evaluators = [\n            cls.build_evaluator(\n                cfg, name, output_folder=os.path.join(cfg.OUTPUT_DIR, \"inference_TTA\")\n            )\n            for name in cfg.DATASETS.TEST\n        ]\n        res = cls.test(cfg, model, evaluators)\n        res = OrderedDict({k + \"_TTA\": v for k, v in res.items()})\n        return res\n\n\ndef setup(args):\n    \"\"\"\n    Create configs and perform basic setups.\n    \"\"\"\n    cfg = get_cfg()\n    cfg.merge_from_file(args.config_file)\n    cfg.merge_from_list(args.opts)\n    cfg.freeze()\n    default_setup(cfg, args)\n    return cfg\n\n\ndef main(args):\n    cfg = setup(args)\n\n    if args.eval_only:\n        model = Trainer.build_model(cfg)\n        DetectionCheckpointer(model, save_dir=cfg.OUTPUT_DIR).resume_or_load(\n            cfg.MODEL.WEIGHTS, resume=args.resume\n        )\n        res = Trainer.test(cfg, model)\n        if cfg.TEST.AUG.ENABLED:\n            res.update(Trainer.test_with_TTA(cfg, model))\n        if comm.is_main_process():\n            verify_results(cfg, res)\n        \n            output_filename = os.path.join(cfg.OUTPUT_DIR,'inference/pq.txt')\n            if not os.path.isdir(os.path.join(cfg.OUTPUT_DIR,'inference')):\n                os.makedirs(os.path.join(cfg.OUTPUT_DIR,'inference'))\n            f = open(output_filename,'a')\n            f.write( '\\n'+ cfg.MODEL.WEIGHTS + '----')\n            for k,v in res['panoptic_seg'].items():\n                f.write(k + ' : ' + str(v) + '\\n')  \n            f.close()\n        return res\n\n    \"\"\"\n    If you'd like to do anything fancier than the standard training logic,\n    consider writing your own training loop (see plain_train_net.py) or\n    subclassing the trainer.\n    \"\"\"\n    trainer = Trainer(cfg)\n    trainer.resume_or_load(resume=args.resume)\n    if cfg.TEST.AUG.ENABLED:\n        trainer.register_hooks(\n            [hooks.EvalHook(0, lambda: trainer.test_with_TTA(cfg, trainer.model))]\n        )\n    return trainer.train()\n\n\nif __name__ == \"__main__\":\n    args = default_argument_parser().parse_args()\n    print(\"Command Line Args:\", args)\n    launch(\n        main,\n        args.num_gpus,\n        num_machines=args.num_machines,\n        machine_rank=args.machine_rank,\n        dist_url=args.dist_url,\n        args=(args,),\n    )\n"
  },
  {
    "path": "VPS_Module/tools/visualize_data.py",
    "content": "#!/usr/bin/env python\n# Copyright (c) Facebook, Inc. and its affiliates.\nimport argparse\nimport os\nfrom itertools import chain\nimport cv2\nimport tqdm\n\nfrom detectron2.config import get_cfg\nfrom detectron2.data import DatasetCatalog, MetadataCatalog, build_detection_train_loader\nfrom detectron2.data import detection_utils as utils\nfrom detectron2.data.build import filter_images_with_few_keypoints\nfrom detectron2.utils.logger import setup_logger\nfrom detectron2.utils.visualizer import Visualizer\n\n\ndef setup(args):\n    cfg = get_cfg()\n    if args.config_file:\n        cfg.merge_from_file(args.config_file)\n    cfg.merge_from_list(args.opts)\n    cfg.DATALOADER.NUM_WORKERS = 0\n    cfg.freeze()\n    return cfg\n\n\ndef parse_args(in_args=None):\n    parser = argparse.ArgumentParser(description=\"Visualize ground-truth data\")\n    parser.add_argument(\n        \"--source\",\n        choices=[\"annotation\", \"dataloader\"],\n        required=True,\n        help=\"visualize the annotations or the data loader (with pre-processing)\",\n    )\n    parser.add_argument(\"--config-file\", metavar=\"FILE\", help=\"path to config file\")\n    parser.add_argument(\"--output-dir\", default=\"./\", help=\"path to output directory\")\n    parser.add_argument(\"--show\", action=\"store_true\", help=\"show output in a window\")\n    parser.add_argument(\n        \"opts\",\n        help=\"Modify config options using the command-line\",\n        default=None,\n        nargs=argparse.REMAINDER,\n    )\n    return parser.parse_args(in_args)\n\n\nif __name__ == \"__main__\":\n    args = parse_args()\n    logger = setup_logger()\n    logger.info(\"Arguments: \" + str(args))\n    cfg = setup(args)\n\n    dirname = args.output_dir\n    os.makedirs(dirname, exist_ok=True)\n    metadata = MetadataCatalog.get(cfg.DATASETS.TRAIN[0])\n\n    def output(vis, fname):\n        if args.show:\n            print(fname)\n            cv2.imshow(\"window\", vis.get_image()[:, :, ::-1])\n            cv2.waitKey()\n        else:\n            filepath = os.path.join(dirname, fname)\n            print(\"Saving to {} ...\".format(filepath))\n            vis.save(filepath)\n\n    scale = 1.0\n    if args.source == \"dataloader\":\n        train_data_loader = build_detection_train_loader(cfg)\n        for batch in train_data_loader:\n            for per_image in batch:\n                # Pytorch tensor is in (C, H, W) format\n                img = per_image[\"image\"].permute(1, 2, 0).cpu().detach().numpy()\n                img = utils.convert_image_to_rgb(img, cfg.INPUT.FORMAT)\n\n                visualizer = Visualizer(img, metadata=metadata, scale=scale)\n                target_fields = per_image[\"instances\"].get_fields()\n                labels = [metadata.thing_classes[i] for i in target_fields[\"gt_classes\"]]\n                vis = visualizer.overlay_instances(\n                    labels=labels,\n                    boxes=target_fields.get(\"gt_boxes\", None),\n                    masks=target_fields.get(\"gt_masks\", None),\n                    keypoints=target_fields.get(\"gt_keypoints\", None),\n                )\n                output(vis, str(per_image[\"image_id\"]) + \".jpg\")\n    else:\n        dicts = list(chain.from_iterable([DatasetCatalog.get(k) for k in cfg.DATASETS.TRAIN]))\n        if cfg.MODEL.KEYPOINT_ON:\n            dicts = filter_images_with_few_keypoints(dicts, 1)\n        for dic in tqdm.tqdm(dicts):\n            img = utils.read_image(dic[\"file_name\"], \"RGB\")\n            visualizer = Visualizer(img, metadata=metadata, scale=scale)\n            vis = visualizer.draw_dataset_dict(dic)\n            output(vis, os.path.basename(dic[\"file_name\"]))\n"
  },
  {
    "path": "VPS_Module/tools/visualize_json_results.py",
    "content": "#!/usr/bin/env python\n# Copyright (c) Facebook, Inc. and its affiliates.\n\nimport argparse\nimport json\nimport numpy as np\nimport os\nfrom collections import defaultdict\nimport cv2\nimport tqdm\n\nfrom detectron2.data import DatasetCatalog, MetadataCatalog\nfrom detectron2.structures import Boxes, BoxMode, Instances\nfrom detectron2.utils.file_io import PathManager\nfrom detectron2.utils.logger import setup_logger\nfrom detectron2.utils.visualizer import Visualizer\n\n\ndef create_instances(predictions, image_size):\n    ret = Instances(image_size)\n\n    score = np.asarray([x[\"score\"] for x in predictions])\n    chosen = (score > args.conf_threshold).nonzero()[0]\n    score = score[chosen]\n    bbox = np.asarray([predictions[i][\"bbox\"] for i in chosen]).reshape(-1, 4)\n    bbox = BoxMode.convert(bbox, BoxMode.XYWH_ABS, BoxMode.XYXY_ABS)\n\n    labels = np.asarray([dataset_id_map(predictions[i][\"category_id\"]) for i in chosen])\n\n    ret.scores = score\n    ret.pred_boxes = Boxes(bbox)\n    ret.pred_classes = labels\n\n    try:\n        ret.pred_masks = [predictions[i][\"segmentation\"] for i in chosen]\n    except KeyError:\n        pass\n    return ret\n\n\nif __name__ == \"__main__\":\n    parser = argparse.ArgumentParser(\n        description=\"A script that visualizes the json predictions from COCO or LVIS dataset.\"\n    )\n    parser.add_argument(\"--input\", required=True, help=\"JSON file produced by the model\")\n    parser.add_argument(\"--output\", required=True, help=\"output directory\")\n    parser.add_argument(\"--dataset\", help=\"name of the dataset\", default=\"coco_2017_val\")\n    parser.add_argument(\"--conf-threshold\", default=0.5, type=float, help=\"confidence threshold\")\n    args = parser.parse_args()\n\n    logger = setup_logger()\n\n    with PathManager.open(args.input, \"r\") as f:\n        predictions = json.load(f)\n\n    pred_by_image = defaultdict(list)\n    for p in predictions:\n        pred_by_image[p[\"image_id\"]].append(p)\n\n    dicts = list(DatasetCatalog.get(args.dataset))\n    metadata = MetadataCatalog.get(args.dataset)\n    if hasattr(metadata, \"thing_dataset_id_to_contiguous_id\"):\n\n        def dataset_id_map(ds_id):\n            return metadata.thing_dataset_id_to_contiguous_id[ds_id]\n\n    elif \"lvis\" in args.dataset:\n        # LVIS results are in the same format as COCO results, but have a different\n        # mapping from dataset category id to contiguous category id in [0, #categories - 1]\n        def dataset_id_map(ds_id):\n            return ds_id - 1\n\n    else:\n        raise ValueError(\"Unsupported dataset: {}\".format(args.dataset))\n\n    os.makedirs(args.output, exist_ok=True)\n\n    for dic in tqdm.tqdm(dicts):\n        img = cv2.imread(dic[\"file_name\"], cv2.IMREAD_COLOR)[:, :, ::-1]\n        basename = os.path.basename(dic[\"file_name\"])\n\n        predictions = create_instances(pred_by_image[dic[\"image_id\"]], img.shape[:2])\n        vis = Visualizer(img, metadata)\n        vis_pred = vis.draw_instance_predictions(predictions).get_image()\n\n        vis = Visualizer(img, metadata)\n        vis_gt = vis.draw_dataset_dict(dic).get_image()\n\n        concat = np.concatenate((vis_pred, vis_gt), axis=1)\n        cv2.imwrite(os.path.join(args.output, basename), concat[:, :, ::-1])\n"
  },
  {
    "path": "prepare.md",
    "content": "\n# checkpoint\n-  Download the panFPN model from google drive: [panFPN_checkpoint](https://pan.baidu.com/s/1ncSi_EihY479SkCEFLHYzw?pwd=zsjq) and save to checkpoints/panFPN.pth\n- Download the vo model from google drive:[vo_checkpoint](https://pan.baidu.com/s/10_tIdaDPf5DjgmU9O6iVYg?pwd=nei5) and save to checkpoints/vkitti2_dy_train_semiv4_080000.pth \n\n# droidenv env\n1. Creating a new anaconda environment using the provided .yaml file. Use `VO_Module/environment_novis.yaml` to if you do not want to use the visualization\n```Bash\nconda env create -f VO_Module/environment.yml\npip install evo --upgrade --no-binary evo\npip install gdown\n```\n2. Compile the extensions (takes about 10 minutes)\n```Bash\npython setup.py install\n```\n3. video panoptic segmentation requirements. The Video panoptic segmentation module is based on [Detectron2](https://github.com/facebookresearch/detectron2), you can install Detectron2 following [the instructions](https://detectron2.readthedocs.io/en/latest/tutorials/install.html).\n```Bash\nconda activate droidenv\nconda install pytorch==1.9.0 torchvision cudatoolkit=11.1 -c pytorch -c nvidia\n\npython -m pip install -e VPS_Module\npip install git+https://github.com/cocodataset/panopticapi.git\n```\n\n# vkitti 15-deg-left dataset\n- download [Virtual_KITTI2](https://europe.naverlabs.com/research/computer-vision/proxy-virtual-worlds-vkitti-2/) into datasets/Virtual_KITTI2\n## Expected dataset structure for Virtual_KITTI2\n```\nVirtual_KITTI2/\n  Scene01/\n    15-deg-left/\n    15-deg-right/\n    ...\n    clone/\n  Scene02/\n  Scene06/\n  Scene18/\n  Scene20/\n```\n- generate annotation for training and evaluating\n```Bash\nconda activate droidenv\nsh tools/datasets/generate_vkitti_datasets.sh\npython tools/datasets/generate_dynamic_masks.py\n```\n\n"
  },
  {
    "path": "tools/initial_segmentation.sh",
    "content": "\n# generate initial segmentation\nCUDA_VISIBLE_DEVICES=0 python3 -W ignore VPS_Module/tools/train_net.py \\\n--config-file VPS_Module/configs/COCO-PanopticSegmentation/panoptic_fpn_R_50_3x_vkitti_init_clone.yaml --num-gpu 1 \\\n--eval-only MODEL.WEIGHTS checkpoints/panFPN.pth \\\nOUTPUT_DIR shared_data/panoptic_segm_init_clone/\n\nCUDA_VISIBLE_DEVICES=0 python3 -W ignore VPS_Module/tools/train_net.py \\\n--config-file VPS_Module/configs/COCO-PanopticSegmentation/panoptic_fpn_R_50_3x_vkitti_init_test.yaml --num-gpu 1 \\\n--eval-only MODEL.WEIGHTS checkpoints/panFPN.pth \\\nOUTPUT_DIR shared_data/panoptic_segm_init_15-deg-left/\n\n# split initial segmentation into datasets/\npython tools/split_init_segm.py\n"
  },
  {
    "path": "tools/split_init_segm.py",
    "content": "import os\nimport shutil\n\nprint(\"copy segmentation into datasets\")\ntarget_root = \"datasets/Virtual_KITTI2/\"\ndic = { \"0001\": \"Scene01\",\n        \"0002\": \"Scene02\",\n        \"0006\": \"Scene06\",\n        \"0018\": \"Scene18\",\n        \"0020\": \"Scene20\"}\n\nclone_path = \"shared_data/panoptic_segm_init_clone/inference/pan_seg\"\nfilelist = os.listdir(clone_path)\nfilelist.sort()\nfor filename in filelist:\n    seg_id = filename[:4]\n    sce = dic[seg_id]\n    target_dir = os.path.join(os.path.join(target_root, sce), \"clone/panFPN_segm\")\n    if not os.path.isdir(target_dir):\n        os.makedirs(target_dir)\n    dst = os.path.join(target_dir, filename)\n    src = os.path.join(clone_path, filename)\n    shutil.copyfile(src, dst)\n\nleft_path = \"shared_data/panoptic_segm_init_15-deg-left/inference/pan_seg\"\nfilelist = os.listdir(left_path)\nfilelist.sort()\nfor filename in filelist:\n    seg_id = filename[:4]\n    sce = dic[seg_id]\n    target_dir = os.path.join(os.path.join(target_root, sce), \"15-deg-left/panFPN_segm\")\n    if not os.path.isdir(target_dir):\n        os.makedirs(target_dir)\n    dst = os.path.join(target_dir, filename)\n    src = os.path.join(clone_path, filename)\n    shutil.copyfile(src, dst)\n"
  },
  {
    "path": "tools/test_vo_scene.sh",
    "content": "\nfor scene in 'Scene01' 'Scene02' 'Scene06' 'Scene18' 'Scene20'\ndo \n    # 生成 pose 得到 rmse 结果\n    python VO_Module/evaluation_scripts/test_vo.py \\\n    --datapath=datasets/Virtual_KITTI2/$scene \\\n    --disable_vis --segm_filter True\n\n    # # 逐帧生成 flow 和 depth\n    python VO_Module/evaluation_scripts/test_vo2.py --scene $scene\ndone\n"
  },
  {
    "path": "tools/test_vps.sh",
    "content": "\n# test ps fusion \nCUDA_VISIBLE_DEVICES=0 python3 -W ignore VPS_Module/tools/train_net.py \\\n--config-file VPS_Module/configs/COCO-PanopticSegmentation/panoptic_fpn_R_50_3x_vkitti_511.yaml --num-gpu 1 \\\n--eval-only MODEL.WEIGHTS checkpoints/panFPN.pth \\\nOUTPUT_DIR shared_data/panoptic_segm_fusion/\n\n# track match and prepare json and segm per scene\npython VPS_Module/tools/1_tracking.py\npython VPS_Module/tools/2_matching.py\npython VPS_Module/tools/3_preparing.py\n\n# calculate vpq per scene on clone 5:1:1\nfor sce in 's1' 's2' 's6' 's18' 's20'\ndo\n    python VPS_Module/tools/4_eval_vpq.py \\\n    --gt-json datasets/Virtual_KITTI2/ALL_clone/vkitti_511_val_$sce.json \\\n    --gt-dir datasets/Virtual_KITTI2/ALL_clone/pan_gt_511_val_$sce \\\n    --pred-json shared_data/json/vo_fusion_vo_track_$sce.json \\\n    --pred-dir shared_data/final_vps_res/$sce \\\n    --output shared_data/vpq/$sce\ndone\n\n\n\n\n"
  }
]